[
  {
    "path": ".gitignore",
    "content": "*.pyc\n*.npy\n*.pth\n*.whl\n*.swp\n\ndata/\nckpt/\nwork_dirs*/\ndist_test/\nvis/\nval/\nlib/\n\n*.egg-info\nbuild/\n__pycache__/\n*.so\n\njob_scripts/\ntemp_ops/"
  },
  {
    "path": "LICENSE",
    "content": "MIT License\n\nCopyright (c) 2024 swc-17\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "README.md",
    "content": "# [CVPR2025] Don't Shake the Wheel: Momentum-Aware Planning in End-to-End Autonomous Driving\n\n<div align=\"justify\">  \n\nThis is the official repository of [**MomAD**](https://arxiv.org/abs/2503.03125). \n\n:fire: Our work has been accepted by CVPR 2025!\n\n</div>\n\n<div align=\"center\">\n  <img src=\"open_loop/vis_5(3).png\" />\n</div>\n\n## Abstract\n<div align=\"justify\">  \nEnd-to-end autonomous driving frameworks facilitate seamless integration of perception and planning but often rely on one-shot trajectory prediction, lacking temporal consistency and long-horizon awareness. This limitation can lead to unstable control, undesirable shifts, and vulnerability to occlusions in single-frame perception. In this work, we propose the Momentum-Aware Driving (MomAD) framework to address these issues by introducing trajectory momentum and perception momentum to stabilize and refine trajectory prediction. MomAD consists of two key components: (1) Topological Trajectory Matching (TTM), which uses Hausdorff Distance to align predictions with prior paths and ensure temporal coherence, and (2) Momentum Planning Interactor (MPI), which cross-attends the planning query with historical spatial-temporal context. Additionally, an encoder-decoder module introduces feature perturbations to increase robustness against perception noise. To quantify planning stability, we propose the Trajectory Prediction Consistency (TPC) metric, showing that MomAD achieves long-term consistency (>3s) on the nuScenes dataset. We further curate the challenging Turning-nuScenes validation set, focused on turning scenarios, where MomAD surpasses state-of-the-art methods, highlighting its enhanced stability and responsiveness in dynamic driving conditions.\n</div>\n<div align=\"justify\">\n\n\n\n:fire: Contributions:\n* **Momentum Planning Concept.** We propose the concept of momentum planning in multi-modal trajectory planning, drawing an analogy to human driving behavior. We provide theoretical evidence to demonstrate the effectiveness of our momentum planning in addressing temporal consistency in end-to-end autonomous driving\n\n* **MomAD Framework.** We propose MomAD, an end-to-end autonomous driving framework that employs momentum planning. It optimizes current trajectory planning by integrating historical planning guidance, significantly improving trajectory consistency and stability in autonomous driving.\n\n* **Turning NuScenes Validation Dataset.** We create the Turning-nuScenes val dataset, derived from the nuScenes full validation dataset. This new dataset focuses on turning scenarios, providing a specialized benchmark for evaluating the performance of autonomous driving systems in complex driving situations.\n\n* **Trajectory Prediction Consistency (TPC) Metric.** We introduce the TPC metric to quantitatively assess the consistency of trajectory predictions in existing end-to-end autonomous driving methods, addressing a critical gap in the evaluation of trajectory planning.\n\n* **Performance Evaluation.** Through extensive experiments on the nuScenes dataset, we demonstrate that MomAD significantly outperforms SOTA methods in terms of trajectory consistency and stability, highlighting its effectiveness in tackling challenges within autonomous driving planning. We evaluated the results of long trajectory predictions, specifically at 4, 5, and 6 seconds, which are critical for ensuring the stability of autonomous driving systems.\n</div>\n\n\n\n\n## Method\n<center>\n    <img style=\"border-radius: 0.3125em;\n    box-shadow: 0 2px 4px 0 rgba(34,36,38,.12),0 2px 10px 0 rgba(34,36,38,.08);\" \n    src=\"main.png\" width=\"1000\">\n    <br>\n    <div style=\"color:orange; border-bottom: 1px solid #d9d9d9;\n    display: inline-block;\n    color: #999;\n    padding: 2px;\">The overall architecture of MomAD. MomAD, as a multi-model trajectory end-to-end autonomous driving method, first encodes multi-view images into feature maps, then learns a sparse scene representation through sparse perception, and finally performs a momentum-guided motion planner to accomplish the planning task. The momentum planning module integrates historical planning to inform current planning, effectively addressing the issue of maximum score deviation in multi-modal trajectories.</div>\n</center>\n\n\n## Results in paper\n\n### Open-loop mertics\n\n- Planning results on [nuScenes](https://github.com/nutonomy/nuscenes-devkit).\n- MomAD 3s stage2: [ckpt](https://huggingface.co/ZI-YING/MomAD_nuScenes_stage2_planing_3s)\n\n| Method | Backbone | L2 (m) 1s  | L2 (m) 2s | L2 (m) 3s | L2 (m) Avg | Col. (%) 1s | Col. (%) 2s | Col. (%) 3s | Col. (%) Avg | TPC (m) 1s | TPC (m) 2s | TPC (m) 3s | TPC (m) Avg | FPS |\n| :---: | :---:| :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: |:---: |\n| UniAD | ResNet101 | 0.45 | 0.70 | 1.04 |0.73 | 0.62 | 0.58 | 0.63 | 0.61 |0.41 | 0.68 | 0.97 | 0.68 |1.8 (A100)|\nSparseDrive |ResNet50| **0.29**  | 0.58  | 0.96 |  0.61 |  **0.01** |  **0.05** |  0.18 |  **0.08** |  **0.30** |  0.57 |  0.85 |  0.57 |  **9.0 (4090)**|\n**MomAD (Ours)** |  ResNet50    |  0.31 |  **0.57** |  **0.91**  | **0.60** |  **0.01** |  **0.05**  | **0.22**  | 0.09  | **0.30** |  **0.53** |  **0.78** |  **0.54** |  7.8 (4090) | \n\n- Planning results for long trajectory prediction on [nuScenes](https://github.com/nutonomy/nuscenes-devkit).  We train 10 epochs on 6s trajectories and test on 6s trajectories.\n\n| Method | L2 (m) 4s  | L2 (m) 5s | L2 (m) 6s | Col. (%) 4s | Col. (%) 5s | Col. (%) 6s | TPC (m) 4s | TPC (m) 5s | TPC (m) 6s |\n| :---: | :---:| :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: |\nSparseDrive   | 1.75|2.32|2.95| 0.87| 1.54| 2.33| 1.33| 1.66| 1.99|\n**MomAD (Ours)** |  **1.67**| **1.98**| **2.45**| **0.83**| **1.43**| **2.13**| **1.19**| **1.45**| **1.61**|\n\n- Planning results on the Turning-nuScenes validation dataset [Turning-nuScenes ](/open_loop/nuscenes_infos_val_hrad_planing_scene.pkl).  We train 10 epochs on 6s trajectories and test on 6s trajectories.\n\n| Method |L2 (m) 1s  | L2 (m) 2s | L2 (m) 3s  | Col. (%) 1s | Col. (%) 2s | Col. (%) 3s | TPC (m) 1s | TPC (m) 2s | TPC (m) 3s |\n| :---: | :---:| :---: | :---: | :---: | :---: | :---: | :---: | :---: | :---: |\nSparseDrive   |0.35 | 0.77 | 1.46 | 0.86 | 0.04 | 0.17 | 0.98 | 0.40 | 0.34 | 0.70 | 1.33 | 0.79|\n**MomAD (Ours)** | 0.33| 0.70| 1.24| 0.76| 0.03| 0.13| 0.79| 0.32| 0.32| 0.54| 1.05| 0.63|\n\n\n### Close-loop mertics (**weight** and **pkl**)\n\n- Open-loop and Closed-loop Results of E2E-AD Methods in Bench2Drive (V0.0.3)} under base training set. `mmt' denotes the extension of VAD on Multi-modal Trajectory. * denotes our re-implementation. The metircs momad used follows [Bench2Drive](https://github.com/Thinklab-SJTU/Bench2Drive)\n- The **weight(stage-1)**, **data pkl** and**kmenas**  of MomAD in Bench2Drive:[**MomAD**](https://pan.baidu.com/s/1qBVdpXUohfveU8au9ShAyg?pwd=u36f)\n<table border=\"1\">\n  <thead>\n    <tr>\n      <th rowspan=\"2\">Method</th>\n      <th colspan=\"1\">Open-loop Metric</th>\n      <th colspan=\"4\">Closed-loop Metric</th>\n    </tr>\n    <tr>\n      <th>Avg. L2 ↓</th>\n      <th>DS ↑</th>\n      <th>SR(%) ↑</th>\n      <th>Effi ↑</th>\n      <th>Comf ↑</th>\n    </tr>\n  </thead>\n  <tbody>\n    <tr>\n      <td>VAD</td>\n      <td>0.91</td>\n      <td>42.35</td>\n      <td>15.00</td>\n      <td>157.94</td>\n      <td>46.01</td>\n    </tr>\n    <tr>\n      <td>VAD mmt*</td>\n      <td>0.89</td>\n      <td>42.87</td>\n      <td>15.91</td>\n      <td>158.12</td>\n      <td>47.22</td>\n    </tr>\n    <tr>\n      <td>Our MomAD (Euclidean)</td>\n      <td>0.84</td>\n      <td>46.12</td>\n      <td>17.45</td>\n      <td>173.35</td>\n      <td>50.98</td>\n    </tr>\n    <tr>\n      <td>Our MomAD</td>\n      <td>0.85</td>\n      <td>45.35</td>\n      <td>17.44</td>\n      <td>162.09</td>\n      <td>49.34</td>\n    </tr>\n    <tr>\n      <td>SparcDrive*</td>\n      <td>0.87</td>\n      <td>44.54</td>\n      <td>16.71</td>\n      <td>170.21</td>\n      <td>48.63</td>\n    </tr>\n    <tr>\n      <td>Our MomAD (Euclidean)</td>\n      <td>0.84</td>\n      <td>46.12</td>\n      <td>17.45</td>\n      <td>173.35</td>\n      <td>50.98</td>\n    </tr>\n    <tr>\n      <td>Our MomAD</td>\n      <td>0.82</td>\n      <td>47.91</td>\n      <td>18.11</td>\n      <td>174.91</td>\n      <td>51.20</td>\n    </tr>\n  </tbody>\n</table>\n\n### Close_loop Vis\n\n<p align=\"left\">\n  <img src = \"./close_loop/video_show.gif\" width=\"60%\">\n</p>\n\n### Robustness evaluation\n\n- Robustness analysis on [nuScenes-C](https://github.com/thu-ml/3D_Corruptions_AD)\n\n<table border=\"1\">\n  <thead>\n    <tr>\n      <th rowspan=\"2\">Setting</th>\n      <th rowspan=\"2\">Method</th>\n      <th colspan=\"2\">Detection</th>\n      <th colspan=\"1\">Tracking</th>\n      <th colspan=\"1\">Mapping</th>\n      <th colspan=\"1\">Motion</th>\n      <th colspan=\"3\">Planning</th>\n    </tr>\n    <tr>\n      <th>mAP ↑</th>\n      <th>NDS ↑</th>\n      <th>AMOTA ↑</th>\n      <th>mAP ↑</th>\n      <th>mADE ↓</th>\n      <th>L2 ↓</th>\n      <th>Col. ↓</th>\n      <th>TPC ↓</th>\n    </tr>\n  </thead>\n  <tbody>\n    <tr>\n      <td>Clean</td>\n      <td>SparseDrive</td>\n      <td>0.418</td>\n      <td>0.525</td>\n      <td>0.386</td>\n      <td>55.1</td>\n      <td>0.62</td>\n      <td>0.61</td>\n      <td>0.08</td>\n      <td>0.57</td>\n    </tr>\n    <tr>\n      <td>Clean</td>\n      <td>Our MomAD</td>\n      <td>0.423</td>\n      <td>0.531</td>\n      <td>0.391</td>\n      <td>55.9</td>\n      <td>0.61</td>\n      <td>0.60</td>\n      <td>0.09</td>\n      <td>0.54</td>\n    </tr>\n    <tr>\n      <td>Snow</td>\n      <td>SparseDrive</td>\n      <td>0.091</td>\n      <td>0.111</td>\n      <td>0.102</td>\n      <td>16.0</td>\n      <td>0.98</td>\n      <td>0.88</td>\n      <td>0.32</td>\n      <td>0.82</td>\n    </tr>\n    <tr>\n      <td>Snow</td>\n      <td>Our MomAD</td>\n      <td>0.154</td>\n      <td>0.173</td>\n      <td>0.166</td>\n      <td>20.9</td>\n      <td>0.76</td>\n      <td>0.73</td>\n      <td>0.16</td>\n      <td>0.68</td>\n    </tr>\n    <tr>\n      <td>Fog</td>\n      <td>SparseDrive</td>\n      <td>0.141</td>\n      <td>0.159</td>\n      <td>0.154</td>\n      <td>18.8</td>\n      <td>0.91</td>\n      <td>0.86</td>\n      <td>0.41</td>\n      <td>0.80</td>\n    </tr>\n    <tr>\n      <td>Fog</td>\n      <td>Our MomAD</td>\n      <td>0.197</td>\n      <td>0.197</td>\n      <td>0.206</td>\n      <td>24.9</td>\n      <td>0.73</td>\n      <td>0.71</td>\n      <td>0.18</td>\n      <td>0.67</td>\n    </tr>\n    <tr>\n      <td>Rain</td>\n      <td>SparseDrive</td>\n      <td>0.128</td>\n      <td>0.140</td>\n      <td>0.193</td>\n      <td>19.4</td>\n      <td>0.97</td>\n      <td>0.93</td>\n      <td>0.46</td>\n      <td>0.92</td>\n    </tr>\n    <tr>\n      <td>Rain</td>\n      <td>Our MomAD</td>\n      <td>0.207</td>\n      <td>0.213</td>\n      <td>0.266</td>\n      <td>25.2</td>\n      <td>0.76</td>\n      <td>0.71</td>\n      <td>0.21</td>\n      <td>0.71</td>\n    </tr>\n  </tbody>\n</table>\n\n\n## Trajectory Prediction Consistency (TPC) metric\nTo evaluate the planning stability of MomAD, we propose a new [Trajectory Prediction Consistency (TPC) metric](/open_loop/projects/mmdet3d_plugin/datasets/evaluation/planning/planning_eval_roboAD_6s.py) to measure consistency between predicted and historical trajectories.\n\n## How to generate a 6s nuScenes trajectory dataset？\n```\npython tools/data_converter/nuscenes_converter_6s.py nuscenes \\\n    --root-path ./data/nuscenes \\\n    --canbus ./data/nuscenes \\\n    --out-dir ./data/infos/ \\\n    --extra-tag nuscenes \\\n    --version v1.0\n```\n## Quick Start\n[Quick Start for Open_loop](open_loop/docs/quick_start.md)\n\n[Quick start for Close_loop](close_loop/quick_start.md)\n\n## Citation\nIf you find MomAD is useful in your research or applications, please consider giving us a star 🌟 and citing it by the following BibTeX entry.\n```\n@article{song2025momad,\n      title={Don't Shake the Wheel: Momentum-Aware Planning in End-to-End Autonomous Driving}, \n      author={Ziying Song and Caiyan Jia and Lin Liu and Hongyu Pan and Yongchang Zhang and Junming Wang and Xingyu Zhang and Shaoqing Xu and Lei Yang and Yadan Luo},\n      year={2025},\n      eprint={2503.03125},\n      archivePrefix={arXiv},\n      primaryClass={cs.RO},\n      url={https://arxiv.org/abs/2503.03125}, \n}\n```\n## Acknowledgement\n- [SparseDrive](https://github.com/swc-17/SparseDrive)\n- [UniAD](https://github.com/OpenDriveLab/UniAD) \n- [VAD](https://github.com/hustvl/VAD)\n- [mmdet3d](https://github.com/open-mmlab/mmdetection3d)\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/configs/momad_small_b2d_stage1.py",
    "content": "# ================ base config ===================\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(234769 // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"MomAD\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MomADMotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"DenseDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            'ego_his_trajs',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n            'ego_his_trajs',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=6,\n    future_frames=6,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/configs/momad_small_b2d_stage2_multiplan.py",
    "content": "# ================ base config ===================\nversion = \"mini\"\nversion = \"base\"\nlength = {'base': 234769, 'mini': 1933}\n\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 6\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 1\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"MomAD\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    # depth_branch=dict(  # for auxiliary supervision only\n    #     type=\"DenseDepthNet\",\n    #     embed_dims=embed_dims,\n    #     num_depth_layers=num_depth_layers,\n    #     loss_weight=0.2,\n    # ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MomADMotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=None,\n            # plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}_b2d.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                frame_rate=1,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n                use_ego_status=False,\n                use_tp=['near',],\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_gru=False,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\" if version == 'base' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    # dict(\n    #     type=\"DenseDepthMapGenerator\",\n    #     downsample=strides[:num_depth_layers],\n    # ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            # \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            #'ego_his_trajs',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            #\n            # 'ego_status',\n            #'ego_his_trajs',\n            'gt_ego_fut_cmd',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=6,\n    future_frames=6,\n    use_cmd=num_cmd>1,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\n# load_from = 'http://svcspawner.bcloud-beijing.hobot.cc/user/homespace/wenchao.sun/plat_gpu/sparsedrive_small_b2d_stage1_20e-20240903-225131.954333/output/work_dirs/latest.pth'\nload_from = \"ckpt/sparsedrive_small_b2d_stage1.pth\""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/configs/momad_small_b2d_stage2_singleplan.py",
    "content": "# ================ base config ===================\nversion = \"mini\"\nversion = \"base\"\nlength = {'base': 234769, 'mini': 1933}\n\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 6\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 1\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"MomAD\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    # depth_branch=dict(  # for auxiliary supervision only\n    #     type=\"DenseDepthNet\",\n    #     embed_dims=embed_dims,\n    #     num_depth_layers=num_depth_layers,\n    #     loss_weight=0.2,\n    # ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MomADMotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=None,\n            # plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}_b2d.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                frame_rate=1,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n                use_ego_status=False,\n                use_tp=['near',],\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_gru=False,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\" if version == 'base' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    # dict(\n    #     type=\"DenseDepthMapGenerator\",\n    #     downsample=strides[:num_depth_layers],\n    # ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            # \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            'ego_his_trajs',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'ego_his_trajs',\n            'gt_ego_fut_cmd',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=6,\n    future_frames=6,\n    use_cmd=num_cmd>1,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\n# load_from = 'http://svcspawner.bcloud-beijing.hobot.cc/user/homespace/wenchao.sun/plat_gpu/sparsedrive_small_b2d_stage1_20e-20240903-225131.954333/output/work_dirs/latest.pth'\nload_from = \"ckpt/sparsedrive_small_b2d_stage1.pth\""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/configs/sparsedrive_small_b2d_stage1.py",
    "content": "# ================ base config ===================\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(234769 // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"DenseDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=2,\n    future_frames=6,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/configs/sparsedrive_small_b2d_stage2_cmd_singleplan.py",
    "content": "# ================ base config ===================\nversion = \"mini\"\nversion = \"base\"\nlength = {'base': 234769, 'mini': 1933}\n\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 16\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 1\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    # depth_branch=dict(  # for auxiliary supervision only\n    #     type=\"DenseDepthNet\",\n    #     embed_dims=embed_dims,\n    #     num_depth_layers=num_depth_layers,\n    #     loss_weight=0.2,\n    # ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=None,\n            #plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                frame_rate=1,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n                use_ego_status=False,\n                use_tp=['near',],\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_gru=False,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\" if version == 'base' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    # dict(\n    #     type=\"DenseDepthMapGenerator\",\n    #     downsample=strides[:num_depth_layers],\n    # ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            # \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=2,\n    future_frames=6,\n    use_cmd=num_cmd>1,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\n# load_from = 'http://svcspawner.bcloud-beijing.hobot.cc/user/homespace/wenchao.sun/plat_gpu/sparsedrive_small_b2d_stage1_20e-20240903-225131.954333/output/work_dirs/latest.pth'\nload_from = \"ckpt/sparsedrive_small_b2d_stage1.pth\""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/configs/sparsedrive_small_b2d_stage2_targetpoint_multiplan.py",
    "content": "# ================ base config ===================\nversion = \"mini\"\nversion = \"base\"\nlength = {'base': 234769, 'mini': 1933}\n\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 16\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 1\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    # depth_branch=dict(  # for auxiliary supervision only\n    #     type=\"DenseDepthNet\",\n    #     embed_dims=embed_dims,\n    #     num_depth_layers=num_depth_layers,\n    #     loss_weight=0.2,\n    # ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=None,\n            # plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}_b2d.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                frame_rate=1,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n                use_ego_status=False,\n                use_tp=['near',],\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_gru=False,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,#6\n                ego_fut_mode=ego_fut_mode,#6\n                num_cmd=num_cmd,#1\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\" if version == 'base' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    # dict(\n    #     type=\"DenseDepthMapGenerator\",\n    #     downsample=strides[:num_depth_layers],\n    # ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            # \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=2,\n    future_frames=6,\n    use_cmd=num_cmd>1,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\n# load_from = 'http://svcspawner.bcloud-beijing.hobot.cc/user/homespace/wenchao.sun/plat_gpu/sparsedrive_small_b2d_stage1_20e-20240903-225131.954333/output/work_dirs/latest.pth'\nload_from = \"ckpt/sparsedrive_small_b2d_stage1.pth\""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28512}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\nCUDA_VISIBLE_DEVICES=0,1,2,3,4,5,6,7 python -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3} --deterministic \n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/create_data.sh",
    "content": "export PYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH\n\n#python tools/data_converter/B2D_converter.py nuscenes \\\n##    --root-path ./data/nuscenes \\\n#    --canbus ./data/nuscenes \\\n#    --out-dir ./data/infos/ \\\n#    --extra-tag nuscenes \\\n#    --version v1.0\npython adzoo/sparsedrive/tools/data_converter/B2D_converter.py"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/kmeans.sh",
    "content": "python tools/kmeans/kmeans_det.py\npython tools/kmeans/kmeans_map.py\npython tools/kmeans/kmeans_motion.py\npython tools/kmeans/kmeans_plan.py"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/test.sh",
    "content": "CUDA_VISIBLE_DEVICES=0,1,2,3,4,5,6,7\\ \n   bash ./tools/dist_test.sh \\\n    projects/configs/sparsedrive_small_stage2.py \\\n    work_dirs/sparsedrive_small_stage2/iter_5860.pth \\\n    8 \\\n    --deterministic \\\n    --eval bbox\n    # --result_file ./work_dirs/sparsedrive_small_stage2/results.pkl"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/test_roboAD.sh",
    "content": "# bash ./tools/dist_test.sh \\\n#     projects/configs/sparsedrive_small_stage2.py \\\n#     ckpt/sparsedrive_stage2.pth \\\n#     8 \\\n#     --deterministic \\\n#     --ev/data/songziying/workspace/SparseDrive/scriptsal bbox\n#     # --result_file ./work_dirs/sparsedrive_small_stage2/results.pkl\nbash ./tools/dist_test.sh \\\n    projects/configs/sparsedrive_small_stage2_roboAD_6s.py \\\n    work_dirs/sparsedrive_small_stage2_roboAD_6s/iter_5860.pth\\\n    1 \\\n    --deterministic \\\n    --eval bbox\n    # --result_file ./work_dirs/sparsedrive_small_stage2_roboAD/results.pkl"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/train.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py \\\n#    1 \\\n#    --deterministic\n\n# stage2\nbash ./adzoo/sparsedrive/tools/dist_train.sh \\\n   ./adzoo/sparsedrive/configs/sparsedrive_small_stage2.py \\\n   8 \\\n   --deterministic\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/train_6s.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py \\\n#    1 \\\n#    --deterministic\n\n# stage2\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2_6s.py \\\n   8 \\\n   --deterministic\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/train_roboAD.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_stage1_roboAD.py \\\n#    1 \\\n#    --deterministic\n\n## stage2\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_stage2_roboAD.py \\\n#    8 \\\n#    --deterministic\n\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2_roboAD_6s.py \\\n   8 \\\n   --deterministic"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/scripts/visualize.sh",
    "content": "export PYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH\npython tools/visualization/visualize.py \\\n\tprojects/configs/sparsedrive_small_stage2.py \\\n\t--result-path work_dirs/sparsedrive_small_stage2/results.pkl"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/benchmark.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport time\nimport torch\nfrom mmcv import Config\nfrom mmcv.parallel import MMDataParallel\nfrom mmcv.runner import load_checkpoint, wrap_fp16_model\nimport sys\nsys.path.append('.')\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.datasets import custom_build_dataset\nfrom mmdet.models import build_detector\nfrom mmcv.cnn.utils.flops_counter import add_flops_counting_methods\nfrom mmcv.parallel import scatter\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='MMDet benchmark a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--checkpoint', default=None, help='checkpoint file')\n    parser.add_argument('--samples', default=1000, help='samples to benchmark')\n    parser.add_argument(\n        '--log-interval', default=50, help='interval of logging')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    args = parser.parse_args()\n    return args\n\n\ndef get_max_memory(model):\n    device = getattr(model, 'output_device', None)\n    mem = torch.cuda.max_memory_allocated(device=device)\n    mem_mb = torch.tensor([mem / (1024 * 1024)],\n        dtype=torch.int,\n        device=device)\n    return mem_mb.item()\n\n\ndef main():\n    args = parse_args()\n    get_flops_params(args)\n    get_mem_fps(args)\n\ndef get_mem_fps(args):\n    cfg = Config.fromfile(args.config)\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n\n    # build the dataloader\n    # TODO: support multiple images per gpu (only minor changes are needed)\n    print(cfg.data.test)\n    dataset = custom_build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=False,\n        shuffle=False)\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    # if args.fuse_conv_bn:\n    #     model = fuse_module(model)\n\n    model = MMDataParallel(model, device_ids=[0])\n\n    model.eval()\n\n    # the first several iterations may be very slow so skip them\n    num_warmup = 5\n    pure_inf_time = 0\n\n    # benchmark with several samples and take the average\n    max_memory = 0\n    for i, data in enumerate(data_loader):\n        # torch.cuda.synchronize()\n        with torch.no_grad():\n            start_time = time.perf_counter()\n            model(return_loss=False, rescale=True, **data)\n\n            torch.cuda.synchronize()\n            elapsed = time.perf_counter() - start_time\n            max_memory = max(max_memory, get_max_memory(model))\n\n        if i >= num_warmup:\n            pure_inf_time += elapsed\n            if (i + 1) % args.log_interval == 0:\n                fps = (i + 1 - num_warmup) / pure_inf_time\n                print(f'Done image [{i + 1:<3}/ {args.samples}], '\n                      f'fps: {fps:.1f} img / s, '\n                      f\"gpu mem: {max_memory} M\")\n\n        if (i + 1) == args.samples:\n            pure_inf_time += elapsed\n            fps = (i + 1 - num_warmup) / pure_inf_time\n            print(f'Overall fps: {fps:.1f} img / s')\n            break\n\n\ndef get_flops_params(args):\n    gpu_id = 0\n    cfg = Config.fromfile(args.config)\n    dataset = custom_build_dataset(cfg.data.val)\n    dataloader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=0,\n        dist=False,\n        shuffle=False,\n    )\n    data_iter = dataloader.__iter__()\n    data = next(data_iter)\n    data = scatter(data, [gpu_id])[0]\n\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    model = model.cuda(gpu_id)\n    model.eval()\n\n    bilinear_flops = 11\n    num_key_pts_det = (\n        cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"kps_generator\"][\"num_learnable_pts\"]\n        + len(cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"kps_generator\"][\"fix_scale\"])\n    )\n    deformable_agg_flops_det = (\n        cfg.num_decoder\n        * cfg.embed_dims\n        * cfg.num_levels\n        * cfg.model[\"head\"]['det_head'][\"instance_bank\"][\"num_anchor\"]\n        * cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"num_cams\"]\n        * num_key_pts_det\n        * bilinear_flops\n    )\n    num_key_pts_map = (\n        cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"num_learnable_pts\"]\n        + len(cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"fix_height\"])\n    ) * cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"num_sample\"]\n    deformable_agg_flops_map = (\n        cfg.num_decoder\n        * cfg.embed_dims\n        * cfg.num_levels\n        * cfg.model[\"head\"]['map_head'][\"instance_bank\"][\"num_anchor\"]\n        * cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"num_cams\"]\n        * num_key_pts_map\n        * bilinear_flops\n    )\n    deformable_agg_flops = deformable_agg_flops_det + deformable_agg_flops_map\n\n    for module in [\"total\", \"img_backbone\", \"img_neck\", \"head\"]:\n        if module != \"total\":\n            flops_model = add_flops_counting_methods(getattr(model, module))\n        else:\n            flops_model = add_flops_counting_methods(model)\n        flops_model.eval()\n        flops_model.start_flops_count()\n        \n        if module == \"img_backbone\":\n            flops_model(data[\"img\"].flatten(0, 1))\n        elif module == \"img_neck\":\n            flops_model(model.img_backbone(data[\"img\"].flatten(0, 1)))\n        elif module == \"head\":\n            flops_model(model.extract_feat(data[\"img\"], metas=data), data)\n        else:\n            flops_model(**data)\n        flops_count, params_count = flops_model.compute_average_flops_cost()\n        flops_count *= flops_model.__batch_counter__\n        flops_model.stop_flops_count()\n        if module == \"head\" or module == \"total\":\n            flops_count += deformable_agg_flops\n        if module == \"total\":\n            total_flops = flops_count\n            total_params = params_count\n        print(\n            f\"{module:<13} complexity: \"\n            f\"FLOPs={flops_count/ 10.**9:>8.4f} G / {flops_count/total_flops*100:>6.2f}%, \"\n            f\"Params={params_count/10**6:>8.4f} M / {params_count/total_params*100:>6.2f}%.\"\n        )\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/data_converter/B2D_converter.py",
    "content": "import os\nfrom os.path import join\nimport gzip, json, pickle\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom tqdm import tqdm\nimport copy\n# from vis_utils import calculate_cube_vertices,calculate_occlusion_stats,edges,DIS_CAR_SAVE\nimport cv2\nimport multiprocessing\nimport argparse\nfrom shapely.geometry import LineString\n# All data in the Bench2Drive dataset are in the left-handed coordinate system.\n# This code converts all coordinate systems (world coordinate system, vehicle coordinate system,\n# camera coordinate system, and lidar coordinate system) to the right-handed coordinate system\n# consistent with the nuscenes dataset.\n\nDATAROOT = 'data/bench2drive'\nMAP_ROOT = 'data/bench2drive/maps'\nOUT_DIR = 'data/infos'\n# split_file = 'data/bench2drive/bench2drive_mini_train_val_split.json'\nsplit_file = 'data/splits/bench2drive_base_train_val_split.json'\n\nMAP_CLASSES = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    'Center',\n    'TrafficLight',\n    'StopSign',\n]\npoint_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\n\nMAX_DISTANCE = 75              # Filter bounding boxes that are too far from the vehicle\nFILTER_Z_SHRESHOLD = 10        # Filter bounding boxes that are too high/low from the vehicle\nFILTER_INVISINLE = True        # Filter bounding boxes based on visibility\nNUM_VISIBLE_SHRESHOLD = 1      # Filter bounding boxes with fewer visible vertices than this value\nNUM_OUTPOINT_SHRESHOLD = 7     # Filter bounding boxes where the number of vertices outside the frame is greater than this value in all cameras\nCAMERAS = ['CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_FRONT_LEFT', 'CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']\nCAMERA_TO_FOLDER_MAP = {'CAM_FRONT':'rgb_front', 'CAM_FRONT_LEFT':'rgb_front_left', 'CAM_FRONT_RIGHT':'rgb_front_right', 'CAM_BACK':'rgb_back', 'CAM_BACK_LEFT':'rgb_back_left', 'CAM_BACK_RIGHT':'rgb_back_right'}\n\nstand_to_ue4_rotate = np.array([[ 0, 0, 1, 0],\n                                [ 1, 0, 0, 0],\n                                [ 0,-1, 0, 0],\n                                [ 0, 0, 0, 1]])\n\nlidar_to_righthand_ego = np.array([[  0, 1, 0, 0],\n                                   [ -1, 0, 0, 0],\n                                   [  0, 0, 1, 0],\n                                   [  0, 0, 0, 1]])\n\nlefthand_ego_to_lidar = np.array([[ 0, 1, 0, 0],\n                                  [ 1, 0, 0, 0],\n                                  [ 0, 0, 1, 0],\n                                  [ 0, 0, 0, 1]])\n\nleft2right = np.eye(4)\nleft2right[1,1] = -1\n\nWINDOW_HEIGHT = 900\nWINDOW_WIDTH = 1600\n\ndef point_in_canvas_hw(pos):\n    \"\"\"Return true if point is in canvas\"\"\"\n    if (pos[0] >= 0) and (pos[0] < WINDOW_HEIGHT) and (pos[1] >= 0) and (pos[1] < WINDOW_WIDTH):\n        return True\n    return False\n\ndef calculate_cube_vertices(center, extent):\n    cx, cy, cz = center\n    x, y, z = extent\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\ndef calculate_occlusion_stats(bbox_points, depth, depth_map, max_render_depth):\n    \"\"\" Draws each vertex in vertices_pos2d if it is in front of the camera\n        The color is based on whether the object is occluded or not.\n        Returns the number of visible vertices and the number of vertices outside the camera.\n    \"\"\"\n    num_visible_vertices = 0\n    num_invisible_vertices = 0\n    num_vertices_outside_camera = 0\n    points = []\n\n    for i in range(len(bbox_points)):\n        x_2d = bbox_points[i][0]\n        y_2d = bbox_points[i][1]\n        point_depth = depth[i]\n\n        # if the point is in front of the camera but not too far away\n        if max_render_depth > point_depth > 0 and point_in_canvas_hw((y_2d, x_2d)):\n            #is_occluded_v = point_is_occluded_vectorized([[y_2d, x_2d]], point_depth, depth_map)\n            is_occluded = point_is_occluded(\n                (y_2d, x_2d), point_depth, depth_map)\n                \n            if is_occluded:\n                vertex_color = (0,0,255) # bgr, red\n                num_invisible_vertices += 1\n            else:\n                num_visible_vertices += 1\n                vertex_color = (0,255,0) # bgr, green\n            points.append((x_2d, y_2d, vertex_color))\n        else:\n            num_vertices_outside_camera += 1\n    return num_visible_vertices, num_invisible_vertices, num_vertices_outside_camera, points\n\ndef point_is_occluded(point, vertex_depth, depth_map):\n    \"\"\" Checks whether or not the four pixels directly around the given point has less depth than the given vertex depth\n        If True, this means that the point is occluded.\n    \"\"\"\n    y, x = map(int, point)\n    from itertools import product\n    neigbours = product((1, -1), repeat=2)\n    is_occluded = []\n    for dy, dx in neigbours:\n        if point_in_canvas_hw((dy+y, dx+x)):\n            # If the depth map says the pixel is closer to the camera than the actual vertex\n            if depth_map[y+dy, x+dx] < vertex_depth:\n                is_occluded.append(True)\n            else:\n                is_occluded.append(False)\n    # Only say point is occluded if all four neighbours are closer to camera than vertex\n    return all(is_occluded)\n\ndef apply_trans(vec,world2ego):\n    vec = np.concatenate((vec,np.array([1])))\n    t = world2ego @ vec\n    return t[0:3]\n\ndef get_pose_matrix(dic):\n    new_matrix = np.zeros((4,4))\n    new_matrix[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=dic['theta']-np.pi/2).rotation_matrix\n    new_matrix[0,3] = dic['x']\n    new_matrix[1,3] = dic['y']\n    new_matrix[3,3] = 1\n    return new_matrix\n\ndef get_npc2world(npc):\n    for key in ['world2vehicle','world2ego','world2sign','world2ped']:\n        if key in npc.keys():\n            npc2world = np.linalg.inv(np.array(npc[key]))\n            yaw_from_matrix = np.arctan2(npc2world[1,0], npc2world[0,0])\n            yaw = npc['rotation'][-1] / 180 * np.pi\n            if abs(yaw-yaw_from_matrix)> 0.01:\n                npc2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=yaw).rotation_matrix\n            npc2world = left2right @ npc2world @ left2right\n            return npc2world\n    npc2world = np.eye(4)\n    npc2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=npc['rotation'][-1]/180*np.pi).rotation_matrix\n    npc2world[0:3,3] = np.array(npc['location'])\n    return left2right @ npc2world @ left2right\n\n\ndef get_global_trigger_vertex(center,extent,yaw_in_degree):\n    x,y = center[0],-center[1]\n    dx,dy = extent[0],extent[1]\n    yaw_in_radians = -yaw_in_degree/180*np.pi\n    vertex_in_self = np.array([[ dx, dy],\n                               [-dx, dy],\n                               [-dx,-dy],\n                               [ dx,-dy]])\n    rotate_matrix = np.array([[np.cos(yaw_in_radians),-np.sin(yaw_in_radians)],\n                              [np.sin(yaw_in_radians), np.cos(yaw_in_radians)]])\n    rotated_vertex = (rotate_matrix @ vertex_in_self.T).T\n    vertex_in_global = np.array([[x,y]]).repeat(4,axis=0) + rotated_vertex\n    return vertex_in_global\n\n\n\ndef get_image_point(loc, K, w2c):\n    point = np.array([loc[0], loc[1], loc[2], 1])\n    point_camera = np.dot(w2c, point)\n    point_camera = point_camera[0:3]\n    depth = point_camera[2]\n    point_img = np.dot(K, point_camera)\n    point_img[0] /= point_img[2]\n    point_img[1] /= point_img[2]\n    return point_img[0:2], depth\n\ndef get_action(index):\n\tDiscrete_Actions_DICT = {\n\t\t0:  (0, 0, 1, False),\n\t\t1:  (0.7, -0.5, 0, False),\n\t\t2:  (0.7, -0.3, 0, False),\n\t\t3:  (0.7, -0.2, 0, False),\n\t\t4:  (0.7, -0.1, 0, False),\n\t\t5:  (0.7, 0, 0, False),\n\t\t6:  (0.7, 0.1, 0, False),\n\t\t7:  (0.7, 0.2, 0, False),\n\t\t8:  (0.7, 0.3, 0, False),\n\t\t9:  (0.7, 0.5, 0, False),\n\t\t10: (0.3, -0.7, 0, False),\n\t\t11: (0.3, -0.5, 0, False),\n\t\t12: (0.3, -0.3, 0, False),\n\t\t13: (0.3, -0.2, 0, False),\n\t\t14: (0.3, -0.1, 0, False),\n\t\t15: (0.3, 0, 0, False),\n\t\t16: (0.3, 0.1, 0, False),\n\t\t17: (0.3, 0.2, 0, False),\n\t\t18: (0.3, 0.3, 0, False),\n\t\t19: (0.3, 0.5, 0, False),\n\t\t20: (0.3, 0.7, 0, False),\n\t\t21: (0, -1, 0, False),\n\t\t22: (0, -0.6, 0, False),\n\t\t23: (0, -0.3, 0, False),\n\t\t24: (0, -0.1, 0, False),\n\t\t25: (1, 0, 0, False),\n\t\t26: (0, 0.1, 0, False),\n\t\t27: (0, 0.3, 0, False),\n\t\t28: (0, 0.6, 0, False),\n\t\t29: (0, 1.0, 0, False),\n\t\t30: (0.5, -0.5, 0, True),\n\t\t31: (0.5, -0.3, 0, True),\n\t\t32: (0.5, -0.2, 0, True),\n\t\t33: (0.5, -0.1, 0, True),\n\t\t34: (0.5, 0, 0, True),\n\t\t35: (0.5, 0.1, 0, True),\n\t\t36: (0.5, 0.2, 0, True),\n\t\t37: (0.5, 0.3, 0, True),\n\t\t38: (0.5, 0.5, 0, True),\n\t\t}\n\tthrottle, steer, brake, reverse = Discrete_Actions_DICT[index]\n\treturn throttle, steer, brake\n\n\ndef gengrate_map(map_root):\n    map_infos = {}\n    for file_name in os.listdir(map_root):\n        if '.npz' in file_name:\n            map_info = dict(np.load(join(map_root,file_name), allow_pickle=True)['arr'])\n            town_name = file_name.split('_')[0]\n            map_infos[town_name] = {} \n            lane_points = []\n            lane_types = []\n            lane_sample_points = []\n            trigger_volumes_points = []\n            trigger_volumes_types = []\n            trigger_volumes_sample_points = []\n            for road_id, road in map_info.items():\n                for lane_id, lane in road.items():\n                    if lane_id == 'Trigger_Volumes':\n                        for single_trigger_volume in lane:\n                            points = np.array(single_trigger_volume['Points'])\n                            points[:,1] *= -1 #left2right\n                            trigger_volumes_points.append(points)\n                            trigger_volumes_sample_points.append(points.mean(axis=0))\n                            trigger_volumes_types.append(single_trigger_volume['Type'])\n                    else:\n                        for single_lane in lane:\n                            points = np.array([raw_point[0] for raw_point in single_lane['Points']])\n                            points[:,1] *= -1\n                            lane_points.append(points)\n                            lane_types.append(single_lane['Type'])\n                            lane_lenth = points.shape[0]\n                            if lane_lenth % 50 != 0:\n                                devide_points = [50*i for i in range(lane_lenth//50+1)]\n                            else:\n                                devide_points = [50*i for i in range(lane_lenth//50)]\n                            devide_points.append(lane_lenth-1)\n                            lane_sample_points_tmp = points[devide_points]\n                            lane_sample_points.append(lane_sample_points_tmp)\n            map_infos[town_name]['lane_points'] = lane_points\n            map_infos[town_name]['lane_sample_points'] = lane_sample_points\n            map_infos[town_name]['lane_types'] = lane_types\n            map_infos[town_name]['trigger_volumes_points'] = trigger_volumes_points\n            map_infos[town_name]['trigger_volumes_sample_points'] = trigger_volumes_sample_points\n            map_infos[town_name]['trigger_volumes_types'] = trigger_volumes_types\n    with open(join(OUT_DIR,'b2d_map_infos.pkl'),'wb') as f:\n        pickle.dump(map_infos,f)\n    return map_infos\n\ndef preprocess(folder_list,idx,tmp_dir,train_or_val,map_infos):\n\n    data_root = DATAROOT\n    cameras = CAMERAS\n    final_data = []\n    if idx == 0:\n        folders = tqdm(folder_list)\n    else:\n        folders = folder_list\n\n    for folder_name in folders:\n        print(folder_name)\n        folder_path = join(data_root, folder_name)\n        last_position_dict = {}\n        for ann_name in sorted(os.listdir(join(folder_path,'anno')),key= lambda x: int(x.split('.')[0])):\n            if idx == 0:\n                print(ann_name)\n            position_dict = {}\n            frame_data = {}\n            cam_gray_depth = {}\n            with gzip.open(join(folder_path,'anno',ann_name), 'rt', encoding='utf-8') as gz_file:\n                anno = json.load(gz_file) \n            frame_data['folder'] = folder_name\n            frame_data['town_name'] =  folder_name.split('/')[1].split('_')[1]\n            frame_data['command_far_xy'] = np.array([anno['x_command_far'],-anno['y_command_far']])\n            frame_data['command_far'] = anno['command_far']\n            frame_data['command_near_xy'] = np.array([anno['x_command_near'],-anno['y_command_near']])\n            frame_data['command_near'] = anno['command_near']\n            frame_data['frame_idx'] = int(ann_name.split('.')[0])\n            frame_data['timestamp'] = int(ann_name.split('.')[0]) / 10 * 1e6 # consistent with nusc\n            frame_data['token'] = folder_name + '_' + str(int(ann_name.split('.')[0])).zfill(4)\n            frame_data['ego_yaw'] = -np.nan_to_num(anno['theta'],nan=np.pi)+np.pi/2  \n            frame_data['ego_translation'] = np.array([anno['x'],-anno['y'],0])\n            frame_data['ego_vel'] = np.array([anno['speed'],0,0])\n            frame_data['ego_accel'] = np.array([anno['acceleration'][0],-anno['acceleration'][1],anno['acceleration'][2]])\n            frame_data['ego_rotation_rate'] = -np.array(anno['angular_velocity'])\n            frame_data['ego_size'] = np.array([anno['bounding_boxes'][0]['extent'][1],anno['bounding_boxes'][0]['extent'][0],anno['bounding_boxes'][0]['extent'][2]])*2\n            world2ego = left2right @ anno['bounding_boxes'][0]['world2ego'] @ left2right\n            frame_data['world2ego'] = world2ego\n            if frame_data['frame_idx'] == 0:\n                expert_file_path = join(folder_path,'expert_assessment','-0001.npz')\n            else:\n                expert_file_path = join(folder_path,'expert_assessment',str(frame_data['frame_idx']-1).zfill(5)+'.npz')\n            expert_data = np.load(expert_file_path,allow_pickle=True)['arr_0']\n            action_id = expert_data[-1]\n            # value = expert_data[-2]\n            # expert_feature = expert_data[:-2]\n            throttle, steer, brake = get_action(action_id)\n            frame_data['brake'] = brake\n            frame_data['throttle'] = throttle\n            frame_data['steer'] = steer\n            #frame_data['action_id'] = action_id\n            #frame_data['value'] = value\n            #frame_data['expert_feature'] = expert_feature\n            ###get sensor infos###\n            sensor_infos = {}\n            for cam in CAMERAS:\n                sensor_infos[cam] = {}\n                sensor_infos[cam]['cam2ego'] = left2right @ np.array(anno['sensors'][cam]['cam2ego']) @ stand_to_ue4_rotate \n                sensor_infos[cam]['intrinsic'] = np.array(anno['sensors'][cam]['intrinsic'])\n                sensor_infos[cam]['world2cam'] = np.linalg.inv(stand_to_ue4_rotate) @ np.array(anno['sensors'][cam]['world2cam']) @left2right\n                sensor_infos[cam]['data_path'] = join(folder_name,'camera',CAMERA_TO_FOLDER_MAP[cam],ann_name.split('.')[0]+'.jpg')\n                cam_gray_depth[cam] = cv2.imread(join(data_root,sensor_infos[cam]['data_path']).replace('rgb_','depth_').replace('.jpg','.png'))[:,:,0]\n            sensor_infos['LIDAR_TOP'] = {}\n            sensor_infos['LIDAR_TOP']['lidar2ego'] = left2right @ np.array(anno['sensors']['LIDAR_TOP']['lidar2ego']) @ left2right @ lidar_to_righthand_ego\n            world2lidar = lefthand_ego_to_lidar @ np.array(anno['sensors']['LIDAR_TOP']['world2lidar']) @ left2right\n            sensor_infos['LIDAR_TOP']['world2lidar'] = world2lidar\n            frame_data['sensors'] = sensor_infos\n            map_annos = get_map_anno(frame_data, map_infos)\n            frame_data[\"map_annos\"] = map_annos\n            ###get bounding_boxes infos###\n            gt_boxes = []\n            gt_names = []\n            gt_ids = []\n            num_points_list = []\n            npc2world_list = []\n            for npc in anno['bounding_boxes']:\n                if npc['class'] == 'ego_vehicle': continue\n                if npc['distance'] > MAX_DISTANCE: continue\n                if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > FILTER_Z_SHRESHOLD: continue\n                center = np.array([npc['center'][0],-npc['center'][1],npc['center'][2]]) # left hand -> right hand\n                # extent = np.array([npc['extent'][1],npc['extent'][0],npc['extent'][2]])  # lwh -> wlh\n                extent = np.array([npc['extent'][0],npc['extent'][1],npc['extent'][2]])  # lwh\n                position_dict[npc['id']] = center\n                local_center = apply_trans(center, world2lidar)\n                size = extent * 2 \n                if 'world2vehicle' in npc.keys():\n                    world2vehicle = left2right @ np.array(npc['world2vehicle'])@left2right\n                    vehicle2lidar = world2lidar @ np.linalg.inv(world2vehicle) \n                    yaw_local = np.arctan2(vehicle2lidar[1,0], vehicle2lidar[0,0])\n\n                else:\n                    yaw_local = -npc['rotation'][-1]/180*np.pi - frame_data['ego_yaw'] +np.pi / 2  \n                # yaw_local_in_lidar_box = -yaw_local - np.pi / 2  \n                yaw_local_in_lidar_box = yaw_local  \n                while yaw_local < -np.pi:\n                    yaw_local += 2*np.pi\n                while yaw_local > np.pi:\n                    yaw_local -= 2*np.pi  \n                if 'speed' in npc.keys():\n                    if 'vehicle' in npc['class']:  # only vehicles have correct speed\n                        speed = npc['speed']\n                    else:\n                        if npc['id'] in last_position_dict.keys():  #calculate speed for other object\n                            speed = np.linalg.norm((center-last_position_dict[npc['id']])[0:2]) * 10\n                        else:\n                            speed = 0\n                else:\n                    speed = 0\n                if 'num_points' in npc.keys():\n                    num_points = npc['num_points']\n                else:\n                    num_points = -1\n                npc2world = get_npc2world(npc)\n                speed_x = speed * np.cos(yaw_local)\n                speed_y = speed * np.sin(yaw_local)\n\n                ###fliter_bounding_boxes###\n                if FILTER_INVISINLE:\n                    valid = False\n                    box2lidar = np.eye(4)\n                    box2lidar[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=yaw_local).rotation_matrix\n                    box2lidar[0:3,3] = local_center\n                    lidar2box = np.linalg.inv(box2lidar)\n                    raw_verts = calculate_cube_vertices(local_center,extent)\n                    verts = []\n                    for raw_vert in raw_verts:\n                        tmp = np.dot(lidar2box, [raw_vert[0], raw_vert[1], raw_vert[2],1])\n                        tmp[0:3] += local_center\n                        verts.append(tmp.tolist()[:-1])\n                    for cam in cameras:\n                        lidar2cam = np.linalg.inv(frame_data['sensors'][cam]['cam2ego']) @ sensor_infos['LIDAR_TOP']['lidar2ego']\n                        test_points = [] \n                        test_depth = []\n                        for vert in verts:\n                            point, depth = get_image_point(vert, frame_data['sensors'][cam]['intrinsic'], lidar2cam)\n                            if depth > 0:\n                                test_points.append(point)\n                                test_depth.append(depth)\n\n                        num_visible_vertices, num_invisible_vertices, num_vertices_outside_camera, colored_points = calculate_occlusion_stats(np.array(test_points), np.array(test_depth),  cam_gray_depth[cam], max_render_depth=MAX_DISTANCE)\n                        if num_visible_vertices>NUM_VISIBLE_SHRESHOLD and num_vertices_outside_camera<NUM_OUTPOINT_SHRESHOLD:\n                            valid = True\n                            break\n                else:\n                    valid = True\n                if valid:\n                    npc2world_list.append(npc2world)\n                    num_points_list.append(num_points)            \n                    gt_boxes.append(np.concatenate([local_center,size,np.array([yaw_local_in_lidar_box,speed_x,speed_y])]))\n                    gt_names.append(npc['type_id'])\n                    gt_ids.append(int(npc['id']))\n\n            if len(gt_boxes) == 0:\n                continue\n\n            last_position_dict = position_dict.copy()    \n            gt_ids = np.array(gt_ids)\n            gt_names = np.array(gt_names)\n            num_points_list = np.array(num_points_list)\n            gt_boxes = np.stack(gt_boxes)\n            npc2world = np.stack(npc2world_list)\n            frame_data['gt_ids'] = gt_ids\n            frame_data['gt_boxes'] = gt_boxes\n            frame_data['gt_names'] = gt_names\n            frame_data['num_points'] = num_points_list\n            frame_data['npc2world'] = npc2world\n            final_data.append(frame_data)\n    \n    os.makedirs(join(OUT_DIR,tmp_dir),exist_ok=True)\n    with open(join(OUT_DIR,tmp_dir,'b2d_infos_'+train_or_val+'_'+str(idx)+'.pkl'),'wb') as f:\n        pickle.dump(final_data,f)\n\n\ndef get_map_anno(ann_info, map_infos):\n    town_name = ann_info['town_name']\n    map_info = map_infos[town_name]\n    lane_points = map_info['lane_points']\n    lane_sample_points = map_info['lane_sample_points']\n    lane_types = map_info['lane_types']\n    trigger_volumes_points = map_info['trigger_volumes_points']\n    trigger_volumes_sample_points = map_info['trigger_volumes_sample_points']\n    trigger_volumes_types = map_info['trigger_volumes_types']\n    world2lidar = np.array(ann_info['sensors']['LIDAR_TOP']['world2lidar'])\n    ego_xy = np.linalg.inv(world2lidar)[0:2,3]\n    max_distance = 50\n    chosed_idx = []\n\n    for idx in range(len(lane_sample_points)):\n        single_sample_points = lane_sample_points[idx]\n        distance = np.linalg.norm((single_sample_points[:,0:2]-ego_xy),axis=-1)\n        if np.min(distance) < max_distance:\n            chosed_idx.append(idx)\n\n    map_anno = {}\n    for i in range(len(MAP_CLASSES)):\n        map_anno[i] = []\n\n    for idx in chosed_idx:\n        if not lane_types[idx] in MAP_CLASSES:\n            continue\n        points = lane_points[idx]\n        points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n        points_in_lidar = (world2lidar @ points.T).T\n        mask = (points_in_lidar[:,0]>point_cloud_range[0]) & (points_in_lidar[:,0]<point_cloud_range[3]) & (points_in_lidar[:,1]>point_cloud_range[1]) & (points_in_lidar[:,1]<point_cloud_range[4])\n        points_in_lidar_range = points_in_lidar[mask,0:2]\n        if len(points_in_lidar_range) > 1:\n            label = MAP_CLASSES.index(lane_types[idx])\n            line = LineString(points_in_lidar_range).simplify(0.2, preserve_topology=True)\n            line = np.array(line.coords)\n            map_anno[label].append(line)\n\n    for idx in range(len(trigger_volumes_points)):\n        if not trigger_volumes_types[idx] in MAP_CLASSES:\n            continue\n        points = trigger_volumes_points[idx]\n        points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n        points_in_lidar = (world2lidar @ points.T).T\n        mask = (points_in_lidar[:,0]>point_cloud_range[0]) & (points_in_lidar[:,0]<point_cloud_range[3]) & (points_in_lidar[:,1]>point_cloud_range[1]) & (points_in_lidar[:,1]<point_cloud_range[4])\n        points_in_lidar_range = points_in_lidar[mask,0:2]\n        if mask.all():\n            label = MAP_CLASSES.index(trigger_volumes_types[idx])\n            line = LineString(points_in_lidar_range).simplify(0.2, preserve_topology=True)\n            line = np.array(line.coords)\n            map_anno[label].append(line)\n\n    return map_anno\n\ndef generate_infos(folder_list,workers,train_or_val,tmp_dir, map_infos):\n\n    folder_num = len(folder_list)\n    devide_list = [(folder_num//workers)*i for i in range(workers)]\n    devide_list.append(folder_num)\n    for i in range(workers):\n        sub_folder_list = folder_list[devide_list[i]:devide_list[i+1]]\n        process = multiprocessing.Process(target=preprocess, args=(sub_folder_list,i,tmp_dir,train_or_val, map_infos))\n        process.start()\n        process_list.append(process)\n    for i in range(workers):\n        process_list[i].join()\n    union_data = []\n    for i in range(workers):\n        with open(join(OUT_DIR,tmp_dir,'b2d_infos_'+train_or_val+'_'+str(i)+'.pkl'),'rb') as f:\n            data = pickle.load(f)\n        union_data.extend(data)\n    with open(join(OUT_DIR,'b2d_infos_'+train_or_val+'.pkl'),'wb') as f:\n        pickle.dump(union_data,f)\n        print(\"data write!\")\n    print(train_or_val, len(union_data))\n\nif __name__ == \"__main__\":\n\n    os.makedirs(OUT_DIR,exist_ok=True)\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--tmp_dir', default=\"tmp_data\", )\n    args = argparser.parse_args()    \n    process_list = []\n    with open(split_file,'r') as f:\n        train_val_split = json.load(f)\n        \n    all_folder = os.listdir(join(DATAROOT,'v1'))\n    train_list = []\n    for foldername in all_folder:\n        if 'Town' in foldername and 'Route' in foldername and 'Weather' in foldername and not join('v1',foldername) in train_val_split['val']:\n            train_list.append(join('v1',foldername))   \n    print('processing map data...')\n    #map_infos = gengrate_map(MAP_ROOT)\n    with open(join(OUT_DIR,'b2d_map_infos.pkl'),'rb') as f:\n        map_infos = pickle.load(f)\n\n    #preprocess(train_list[1:2], 0, args.tmp_dir, \"train\", map_infos)\n    # print('processing train data...')\n    #generate_infos(train_list, 16,'train',args.tmp_dir, map_infos)\n    print('processing val data...')\n    generate_infos(train_val_split['val'], 16,'val',args.tmp_dir, map_infos)\n\n    print('finish!')"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/data_converter/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/data_converter/nuscenes_converter.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_test.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/data_converter/nuscenes_converter_1_10.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n       \n        import random\n        random.shuffle(train_scenes)\n        train_scenes = train_scenes[:int(len(train_scenes)*0.1)] # 0.2 为 1/5；0.5为 1/2 以此类推\n    \n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n    # import pdb; pdb.set_trace()\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        pass\n        # print('test sample: {}'.format(len(train_nusc_infos)))\n        # data = dict(infos=train_nusc_infos, metadata=metadata)\n        # info_path = osp.join(out_path,\n        #                      '{}_infos_test.pkl'.format(info_prefix))\n        # mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_1_10_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        # data['infos'] = val_nusc_infos\n        # info_val_path = osp.join(out_path,\n        #                          '{}_infos_val.pkl'.format(info_prefix))\n        # mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n    # import pdb; pdb.set_trace()\n    predict_helper = PredictHelper(nusc)\n    trainval_samples=[]\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        if sample['scene_token'] in train_scenes:\n            trainval_samples.append(sample)\n    # import pdb; pdb.set_trace()\n    for sample in mmcv.track_iter_progress(trainval_samples):\n        \n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/data_converter/nuscenes_converter_6s.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_test_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_train_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=12):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/data_converter/nuscenes_converter_hrad_planing_scene.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\n\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        import random\n        random.shuffle(train_scenes)\n        train_scenes = train_scenes[:int(len(train_scenes)*0.1)] # 0.2 为 1/5；0.5为 1/2 以此类推\n        # import pdb; pdb.set_trace()\n        val_scenes = splits.val\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    \n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    # import pdb; pdb.set_trace()\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n    val_scenes = set(['a178a1b5415f45c08d179bd2cacdf284', 'e005041f659c47e194cd5b18ea6fc346', 'e8099a6136804f3bb9b38ff94d98eb64', 'b789de07180846cc972118ee6d1fb027', '080a52cb8f59489b9cddc7b721808088', 'ed242d80ccb34b139aaf9ab89859332e', '325cef682f064c55a255f2625c533b75', '2f56eb47c64f43df8902d9f88aa8a019', '7210f928860043b5a7e0d3dd4b3e80ff', 'f97bf749746c4c3a8ad9f1c11eab6444', 'cba3ddd5c3664a43b6a08e586e094900', 'd29527ec841045d18d04a933e7a0afd2', 'c4df079d260241ff8015218e29b42ea7', '7052d21b95fc4bae8761b8d9524f3e42', '01e4fcbe6e49483293ce45727152b36e', '19d97841d6f64eba9f6eb9b6e8c257dc', 'fcc020250f884397965ba00c1d9ad9e6'])\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        pass\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val_hrad_planing_scene.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    trainval_samples=[]\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        if sample['scene_token'] in val_scenes :\n            trainval_samples.append(sample)\n    # import pdb; pdb.set_trace()\n    for sample in mmcv.track_iter_progress(trainval_samples):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/dist_test.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nPORT=${PORT:-29611}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython3 -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/test.py $CONFIG $CHECKPOINT --launcher pytorch ${@:4}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28651}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython3 -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/fuse_conv_bn.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\n\nimport torch\nfrom mmcv.runner import save_checkpoint\nfrom torch import nn as nn\n\nfrom mmdet3d.apis import init_model\n\n\ndef fuse_conv_bn(conv, bn):\n    \"\"\"During inference, the functionary of batch norm layers is turned off but\n    only the mean and var alone channels are used, which exposes the chance to\n    fuse it with the preceding conv layers to save computations and simplify\n    network structures.\"\"\"\n    conv_w = conv.weight\n    conv_b = conv.bias if conv.bias is not None else torch.zeros_like(\n        bn.running_mean)\n\n    factor = bn.weight / torch.sqrt(bn.running_var + bn.eps)\n    conv.weight = nn.Parameter(conv_w *\n                               factor.reshape([conv.out_channels, 1, 1, 1]))\n    conv.bias = nn.Parameter((conv_b - bn.running_mean) * factor + bn.bias)\n    return conv\n\n\ndef fuse_module(m):\n    last_conv = None\n    last_conv_name = None\n\n    for name, child in m.named_children():\n        if isinstance(child, (nn.BatchNorm2d, nn.SyncBatchNorm)):\n            if last_conv is None:  # only fuse BN that is after Conv\n                continue\n            fused_conv = fuse_conv_bn(last_conv, child)\n            m._modules[last_conv_name] = fused_conv\n            # To reduce changes, set BN as Identity instead of deleting it.\n            m._modules[name] = nn.Identity()\n            last_conv = None\n        elif isinstance(child, nn.Conv2d):\n            last_conv = child\n            last_conv_name = name\n        else:\n            fuse_module(child)\n    return m\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='fuse Conv and BN layers in a model')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument('checkpoint', help='checkpoint file path')\n    parser.add_argument('out', help='output path of the converted model')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n    # build the model from a config file and a checkpoint file\n    model = init_model(args.config, args.checkpoint)\n    # fuse conv and bn layers of the model\n    fused_model = fuse_module(model)\n    save_checkpoint(fused_model, args.out)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/kmeans/kmeans_det.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nos.makedirs('data/kmeans', exist_ok=True)\nos.makedirs('vis/kmeans', exist_ok=True)\n\nK = 900\nDIS_THRESH = 55\n\nfp = 'data/infos_sparsedrive/b2d_infos_train.pkl'\ndata = mmcv.load(fp)\n#import pdb;pdb.set_trace()\n#data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\ndata_infos = sorted(data ,key=lambda e: e[\"timestamp\"])\ncenter = []\nfor idx in tqdm(range(len(data_infos))):\n    boxes = data_infos[idx]['gt_boxes'][:,:3]\n    if len(boxes) == 0:\n        continue\n    distance = np.linalg.norm(boxes[:, :2], axis=1)\n    center.append(boxes[distance < DIS_THRESH])\ncenter = np.concatenate(center, axis=0)\nprint(\"start clustering, may take a few minutes.\")\ncluster = KMeans(n_clusters=K).fit(center).cluster_centers_\nplt.scatter(cluster[:,0], cluster[:,1])\nplt.savefig(f'vis/kmeans/det_anchor_{K}', bbox_inches='tight')\nothers = np.array([1,1,1,1,0,0,0,0])[np.newaxis].repeat(K, axis=0)\ncluster = np.concatenate([cluster, others], axis=1)\nnp.save(f'data/kmeans/kmeans_det_{K}.npy', cluster)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/kmeans/kmeans_map.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nK = 100\nnum_sample = 20\n\nfp = 'data/infos_sparsedrive/b2d_infos_train.pkl'\ndata = mmcv.load(fp)\n#data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\nimport pdb;pdb.set_trace()\ndata_infos = sorted(data ,key=lambda e: e[\"timestamp\"])\ncenter = []\nfor idx in tqdm(range(len(data_infos))):\n    for cls, geoms in data_infos[idx][\"map_annos\"].items():\n        for geom in geoms:  \n            center.append(geom.mean(axis=0))\ncenter = np.stack(center, axis=0)\ncenter = KMeans(n_clusters=K).fit(center).cluster_centers_\ndelta_y = np.linspace(-4, 4, num_sample)\ndelta_x = np.zeros([num_sample])\ndelta = np.stack([delta_x, delta_y], axis=-1)\nvecs = center[:, np.newaxis] + delta[np.newaxis]\n\nfor i in range(K):\n    x = vecs[i, :, 0]\n    y = vecs[i, :, 1]\n    plt.plot(x, y, linewidth=1, marker='o', linestyle='-', markersize=2)\nplt.savefig(f'vis/kmeans/map_anchor_{K}', bbox_inches='tight')\nnp.save(f'data/kmeans/kmeans_map_{K}.npy', vecs)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/kmeans/kmeans_motion.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nCLASSES = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\n\ndef get_fut_agent(idx, sample_rate, frames, data_infos):\n        adj_idx_list = range(idx,idx+(frames+1)*sample_rate,sample_rate)\n        cur_frame = data_infos[idx]\n        cur_boxes = cur_frame['gt_boxes'].copy()\n        box_ids = cur_frame['gt_ids']\n\n        future_track = np.zeros((len(box_ids),frames+1,2))\n        future_mask = np.zeros((len(box_ids),frames+1))\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for i in range(len(box_ids)):\n            box_id = box_ids[i]\n            cur_box2lidar = world2lidar_lidar_cur @ cur_frame['npc2world'][i]\n            cur_xy = cur_box2lidar[0:2,3]\n            for j in range(len(adj_idx_list)):\n                adj_idx = adj_idx_list[j]\n                if adj_idx < 0 or adj_idx >= len(data_infos):\n                    break\n                adj_frame = data_infos[adj_idx]\n                if adj_frame['folder'] != cur_frame ['folder']:\n                    break\n                if len(np.where(adj_frame['gt_ids']==box_id)[0])==0:\n                    break\n                assert len(np.where(adj_frame['gt_ids']==box_id)[0]) == 1 , np.where(adj_frame['gt_ids']==box_id)[0]\n                adj_idx = np.where(adj_frame['gt_ids']==box_id)[0][0]\n                adj_box2lidar = world2lidar_lidar_cur @ adj_frame['npc2world'][adj_idx]\n                adj_xy = adj_box2lidar[0:2,3]\n                if j > 0:\n                    last_xy = future_track[i,j-1,:]\n                    distance = np.linalg.norm(last_xy - adj_xy)\n                    if distance > 10:\n                        break\n                future_track[i,j,:] = adj_xy\n                future_mask[i,j] = 1\n\n        future_track_offset = future_track[:,1:,:] - future_track[:,:-1,:]\n        future_mask_offset = future_mask[:,1:]\n        future_track_offset[future_mask_offset==0] = 0\n\n        return future_track_offset.astype(np.float32), future_mask_offset.astype(np.float32)\n\n\ndef lidar2agent(trajs_offset, boxes):\n    origin = np.zeros((trajs_offset.shape[0], 1, 2), dtype=np.float32)\n    trajs_offset = np.concatenate([origin, trajs_offset], axis=1)\n    trajs = trajs_offset.cumsum(axis=1)\n    yaws = - boxes[:, 6]\n    rot_sin = np.sin(yaws)\n    rot_cos = np.cos(yaws)\n    rot_mat_T = np.stack(\n        [\n            np.stack([rot_cos, rot_sin]),\n            np.stack([-rot_sin, rot_cos]),\n        ]\n    )\n    trajs_new = np.einsum('aij,jka->aik', trajs, rot_mat_T)\n    trajs_new = trajs_new[:, 1:]\n    return trajs_new\n\nK = 6\nDIS_THRESH = 65\n\nfp = 'data/infos_sparsedrive/b2d_infos_train.pkl'\ndata = mmcv.load(fp)\n#import pdb;pdb.set_trace()\ndata_infos = data #sorted(data, key=lambda e: e[\"timestamp\"])\n\nintention = dict()\n\nfor i in range(len(CLASSES)):\n    intention[i] = []\nfor idx in tqdm(range(len(data_infos))):\n    info = data_infos[idx]\n    boxes = info['gt_boxes']\n    names = info['gt_names']\n    for name_i in range(len(names)):\n        names[name_i] = NameMapping[names[name_i]]\n    #import pdb;pdb.set_trace()\n    gt_agent_fut_trajs, gt_agent_fut_masks = get_fut_agent(idx, 5, 6, data_infos)\n    fut_masks = gt_agent_fut_masks\n    trajs = gt_agent_fut_trajs\n    x = gt_agent_fut_trajs[:,0,0]\n    y = gt_agent_fut_trajs[:,0,1]\n    result = np.sqrt(x**2 + y**2)\n    #import pdb;pdb.set_trace()\n    velos = result\n    labels = []\n    for cat in names:\n        if cat in CLASSES:\n            labels.append(CLASSES.index(cat))\n        else:\n            labels.append(-1)\n    labels = np.array(labels)\n    if len(boxes) == 0:\n        continue\n    #import pdb;pdb.set_trace()    \n    for i in range(len(CLASSES)):\n        #import pdb;pdb.set_trace()\n        cls_mask = (labels == i)\n        box_cls = boxes[cls_mask]\n        fut_masks_cls = fut_masks[cls_mask]\n        trajs_cls = trajs[cls_mask]\n        velos_cls = velos[cls_mask]\n\n        distance = np.linalg.norm(box_cls[:, :2], axis=1)\n        mask = np.logical_and(\n            fut_masks_cls.sum(axis=1) == 6,\n            distance < DIS_THRESH,\n        )\n        trajs_cls = trajs_cls[mask]\n        box_cls = box_cls[mask]\n        velos_cls = velos_cls[mask]\n\n        trajs_agent = lidar2agent(trajs_cls, box_cls)\n        if trajs_agent.shape[0] == 0:\n            continue\n        intention[i].append(trajs_agent)\n#import pdb;pdb.set_trace()\nclusters = []\nfor i in range(len(CLASSES)):\n    intention_cls = np.concatenate(intention[i], axis=0).reshape(-1, 12)\n    if intention_cls.shape[0] < K:\n        continue\n    cluster = KMeans(n_clusters=K).fit(intention_cls).cluster_centers_\n    cluster = cluster.reshape(-1, 6, 2)\n    clusters.append(cluster)\n    for j in range(K):\n        plt.scatter(cluster[j, :, 0], cluster[j, :,1])\n    plt.savefig(f'vis/kmeans/motion_intention_{CLASSES[i]}_{K}', bbox_inches='tight')\n    plt.close()\n\nclusters = np.stack(clusters, axis=0)\nnp.save(f'data/kmeans/kmeans_motion_{K}.npy', clusters)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/kmeans/kmeans_plan.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nK = 6\n\nfp = './data/infos/b2d_infos_val.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data, key=lambda e: e[\"timestamp\"]))\nnavi_trajs = [[], [], [], [], [], []]\n\n\ndef get_ego_trajs(idx,sample_rate,past_frames,future_frames,data_infos):\n        #import pdb;pdb.set_trace()\n        # idx = 128386\n        adj_idx_list = range(idx-past_frames*sample_rate,idx+(future_frames+1)*sample_rate,sample_rate)\n        cur_frame = data_infos[idx]\n        full_adj_track = np.zeros((past_frames+future_frames+1,2))\n        full_adj_adj_mask = np.zeros(past_frames+future_frames+1)\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for j in range(len(adj_idx_list)):\n            adj_idx = adj_idx_list[j]\n            if adj_idx <0 or adj_idx>=len(data_infos):\n                break\n            adj_frame = data_infos[adj_idx]\n            if adj_frame['folder'] != cur_frame ['folder']:\n                break\n            world2lidar_ego_adj = adj_frame['sensors']['LIDAR_TOP']['world2lidar']\n            adj2cur_lidar = world2lidar_lidar_cur @ np.linalg.inv(world2lidar_ego_adj)\n            xy = adj2cur_lidar[0:2,3]\n            full_adj_track[j,0:2] = xy\n            full_adj_adj_mask[j] = 1\n        offset_track = full_adj_track[1:] - full_adj_track[:-1]\n        for j in range(past_frames-1,-1,-1):\n            if full_adj_adj_mask[j] == 0:\n                offset_track[j] = offset_track[j+1]\n        for j in range(past_frames,past_frames+future_frames,1):\n\n            if full_adj_adj_mask[j+1] == 0 :\n                offset_track[j] = 0\n        #command = self.command2hot(cur_frame['command_near'])\n        return offset_track[past_frames:].copy()\n\n\ndef lidar2agent(trajs_offset, boxes):\n    origin = np.zeros((trajs_offset.shape[0], 1, 2), dtype=np.float32)\n    trajs_offset = np.concatenate([origin, trajs_offset], axis=1)\n    trajs = trajs_offset.cumsum(axis=1)\n    yaws = - boxes[:, 6]\n    rot_sin = np.sin(yaws)\n    rot_cos = np.cos(yaws)\n    rot_mat_T = np.stack(\n        [\n            np.stack([rot_cos, rot_sin]),\n            np.stack([-rot_sin, rot_cos]),\n        ]\n    )\n    trajs_new = np.einsum('aij,jka->aik', trajs, rot_mat_T)\n    trajs_new = trajs_new[:, 1:]\n    return trajs_new\n\nsum_turn = 0\nfor idx in tqdm(range(len(data_infos))):\n    info = data_infos[idx]\n    plan_traj = get_ego_trajs(idx, 5, 6, 6, data_infos)\n    #plan_traj = info['gt_ego_fut_trajs'].cumsum(axis=-2)\n    #plan_mask = info['gt_ego_fut_masks']\n    #import pdb;pdb.set_trace()\n    cmd = info['command_near']#.astype(np.int32)\n    if cmd == 1 or cmd == 2 or cmd == 5 or cmd == 6:\n        print(cmd)\n        sum_turn = sum_turn + 1\n    #cmd = cmd.argmax(axis=-1)\n    #if not plan_mask.sum() == 6:\n    #    continue\n    navi_trajs[cmd-1].append(plan_traj)\nimport pdb;pdb.set_trace()\nclusters = []\nimport pdb;pdb.set_trace()\nfor trajs in navi_trajs:\n    trajs = np.concatenate(trajs, axis=0).reshape(-1, 12)\n    cluster = KMeans(n_clusters=K).fit(trajs).cluster_centers_\n    cluster = cluster.reshape(-1, 6, 2)\n    clusters.append(cluster)\n    for j in range(K):\n        plt.scatter(cluster[j, :, 0], cluster[j, :,1])\nplt.savefig(f'vis/kmeans/plan_{K}', bbox_inches='tight')\nplt.close()\n\nclusters = np.stack(clusters, axis=0)\nnp.save(f'data/kmeans/kmeans_plan_{K}.npy', clusters)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/test.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport mmcv\nimport os\nfrom os import path as osp\n\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.cnn import fuse_conv_bn\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.runner import (\n    get_dist_info,\n    init_dist,\n    load_checkpoint,\n    wrap_fp16_model,\n)\n\nfrom mmdet.apis import single_gpu_test, multi_gpu_test, set_random_seed\nfrom mmdet.datasets import replace_ImageToTensor, build_dataset\nfrom mmdet.datasets import build_dataloader as build_dataloader_origin\nfrom mmdet.models import build_detector\n\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.apis.test import custom_multi_gpu_test\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description=\"MMDet test (and eval) a model\"\n    )\n    parser.add_argument(\"config\", help=\"test config file path\")\n    parser.add_argument(\"checkpoint\", help=\"checkpoint file\")\n    parser.add_argument(\"--out\", help=\"output result file in pickle format\")\n    parser.add_argument(\n        \"--fuse-conv-bn\",\n        action=\"store_true\",\n        help=\"Whether to fuse conv and bn, this will slightly increase\"\n        \"the inference speed\",\n    )\n    parser.add_argument(\n        \"--format-only\",\n        action=\"store_true\",\n        help=\"Format the output results without perform evaluation. It is\"\n        \"useful when you want to format the result to a specific format and \"\n        \"submit it to the test server\",\n    )\n    parser.add_argument(\n        \"--eval\",\n        type=str,\n        nargs=\"+\",\n        help='evaluation metrics, which depends on the dataset, e.g., \"bbox\",'\n        ' \"segm\", \"proposal\" for COCO, and \"mAP\", \"recall\" for PASCAL VOC',\n    )\n    parser.add_argument(\"--show\", action=\"store_true\", help=\"show results\")\n    parser.add_argument(\n        \"--show-dir\", help=\"directory where results will be saved\"\n    )\n    parser.add_argument(\n        \"--gpu-collect\",\n        action=\"store_true\",\n        help=\"whether to use gpu to collect results.\",\n    )\n    parser.add_argument(\n        \"--tmpdir\",\n        help=\"tmp directory used for collecting results from multiple \"\n        \"workers, available when gpu-collect is not specified\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"custom options for evaluation, the key-value pair in xxx=yyy \"\n        \"format will be kwargs for dataset.evaluate() function (deprecate), \"\n        \"change to --eval-options instead.\",\n    )\n    parser.add_argument(\n        \"--eval-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"custom options for evaluation, the key-value pair in xxx=yyy \"\n        \"format will be kwargs for dataset.evaluate() function\",\n    )\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\"--result_file\", type=str, default=None)\n    parser.add_argument(\"--show_only\", action=\"store_true\")\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.eval_options:\n        raise ValueError(\n            \"--options and --eval-options cannot be both specified, \"\n            \"--options is deprecated in favor of --eval-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --eval-options\")\n        args.eval_options = args.options\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    assert (\n        args.out or args.eval or args.format_only or args.show or args.show_dir\n    ), (\n        \"Please specify at least one operation (save/eval/format/show the \"\n        'results / save the results) with the argument \"--out\", \"--eval\"'\n        ', \"--format-only\", \"--show\" or \"--show-dir\"'\n    )\n\n    if args.eval and args.format_only:\n        raise ValueError(\"--eval and --format_only cannot be both specified\")\n\n    if args.out is not None and not args.out.endswith((\".pkl\", \".pickle\")):\n        raise ValueError(\"The output file must be a pkl file.\")\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    cfg.model.pretrained = None\n    # in case the test dataset is concatenated\n    samples_per_gpu = 1\n    if isinstance(cfg.data.test, dict):\n        cfg.data.test.test_mode = True\n        samples_per_gpu = cfg.data.test.pop(\"samples_per_gpu\", 1)\n        if samples_per_gpu > 1:\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.test.pipeline = replace_ImageToTensor(\n                cfg.data.test.pipeline\n            )\n    elif isinstance(cfg.data.test, list):\n        for ds_cfg in cfg.data.test:\n            ds_cfg.test_mode = True\n        samples_per_gpu = max(\n            [ds_cfg.pop(\"samples_per_gpu\", 1) for ds_cfg in cfg.data.test]\n        )\n        if samples_per_gpu > 1:\n            for ds_cfg in cfg.data.test:\n                ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n\n    # set random seeds\n    if args.seed is not None:\n        set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # set work dir\n    if cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0]) \n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    cfg.data.test.work_dir = cfg.work_dir\n    print('work_dir: ',cfg.work_dir)\n\n\n    # build the dataloader\n    dataset = build_dataset(cfg.data.test)\n    import pdb;\n    if distributed:\n        data_loader = build_dataloader(\n            dataset,\n            samples_per_gpu=samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n        )\n    else:\n        data_loader = build_dataloader_origin(\n            dataset,\n            samples_per_gpu=samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n        )\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get(\"test_cfg\"))\n    # model = build_model(cfg.model, test_cfg=cfg.get(\"test_cfg\"))\n    fp16_cfg = cfg.get(\"fp16\", None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    checkpoint = load_checkpoint(model, args.checkpoint, map_location=\"cpu\")\n    if args.fuse_conv_bn:\n        model = fuse_conv_bn(model)\n    # old versions did not save class info in checkpoints, this walkaround is\n    # for backward compatibility\n    if \"CLASSES\" in checkpoint.get(\"meta\", {}):\n        model.CLASSES = checkpoint[\"meta\"][\"CLASSES\"]\n    else:\n        model.CLASSES = dataset.CLASSES\n    # palette for visualization in segmentation tasks\n    if \"PALETTE\" in checkpoint.get(\"meta\", {}):\n        model.PALETTE = checkpoint[\"meta\"][\"PALETTE\"]\n    elif hasattr(dataset, \"PALETTE\"):\n        # segmentation dataset has `PALETTE` attribute\n        model.PALETTE = dataset.PALETTE\n\n    if args.result_file is not None:\n        # outputs = torch.load(args.result_file)\n        outputs = mmcv.load(args.result_file)\n    elif not distributed:\n        model = MMDataParallel(model, device_ids=[0])\n        outputs = single_gpu_test(model, data_loader, args.show, args.show_dir)\n    else:\n        model = MMDistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n        )\n        outputs = custom_multi_gpu_test(\n            model, data_loader, args.tmpdir, args.gpu_collect\n        )\n\n    rank, _ = get_dist_info()\n    if rank == 0:\n        if args.out:\n            print(f\"\\nwriting results to {args.out}\")\n            mmcv.dump(outputs, args.out)\n        kwargs = {} if args.eval_options is None else args.eval_options\n        if args.show_only:\n            eval_kwargs = cfg.get(\"evaluation\", {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                \"interval\",\n                \"tmpdir\",\n                \"start\",\n                \"gpu_collect\",\n                \"save_best\",\n                \"rule\",\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(kwargs)\n            dataset.show(outputs, show=True, **eval_kwargs)\n        elif args.format_only:\n            dataset.format_results(outputs, **kwargs)\n        elif args.eval:\n            eval_kwargs = cfg.get(\"evaluation\", {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                \"interval\",\n                \"tmpdir\",\n                \"start\",\n                \"gpu_collect\",\n                \"save_best\",\n                \"rule\",\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(dict(metric=args.eval, **kwargs))\n            print(eval_kwargs)\n            results_dict = dataset.evaluate(outputs, **eval_kwargs)\n            print(results_dict)\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/train.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from projects.mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    # print(\"hhhhhhhhhhhhhhh\")\n    print(cfg.data.train)\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/train_single.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\n# for single gpu debug\nBASE_DIR = os.path.dirname(os.path.abspath(__file__))\nROOT_DIR = os.path.dirname(BASE_DIR)\nsys.path.append(ROOT_DIR)\n###############\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from projects.mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/visualization/bev_render.py",
    "content": "import os\nimport numpy as np\nimport cv2\n\nimport matplotlib\nimport matplotlib.pyplot as plt\n\n#from .projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\n\ndef box3d_to_corners(box3d):\n    if isinstance(box3d, torch.Tensor):\n        box3d = box3d.detach().cpu().numpy()\n    corners_norm = np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)\n    corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n    # use relative origin [0.5, 0.5, 0]\n    corners_norm = corners_norm - np.array([0.5, 0.5, 0.5])\n    corners = box3d[:, None, [W, L, H]] * corners_norm.reshape([1, 8, 3])\n\n    # rotate around z axis\n    rot_cos = np.cos(box3d[:, YAW])\n    rot_sin = np.sin(box3d[:, YAW])\n    rot_mat = np.tile(np.eye(3)[None], (box3d.shape[0], 1, 1))\n    rot_mat[:, 0, 0] = rot_cos\n    rot_mat[:, 0, 1] = -rot_sin\n    rot_mat[:, 1, 0] = rot_sin\n    rot_mat[:, 1, 1] = rot_cos\n    corners = (rot_mat[:, None] @ corners[..., None]).squeeze(axis=-1)\n    corners += box3d[:, None, :3]\n    return corners\n \nCMD_LIST = ['Turn Right', 'Turn Left', 'Go Straight']\nCOLOR_VECTORS = ['cornflowerblue', 'royalblue', 'slategrey']\nSCORE_THRESH = 0.3\nMAP_SCORE_THRESH = 0.3\ncolor_mapping = np.asarray([\n    [0, 0, 0],\n    [255, 179, 0],\n    [128, 62, 117],\n    [255, 104, 0],\n    [166, 189, 215],\n    [193, 0, 32],\n    [206, 162, 98],\n    [129, 112, 102],\n    [0, 125, 52],\n    [246, 118, 142],\n    [0, 83, 138],\n    [255, 122, 92],\n    [83, 55, 122],\n    [255, 142, 0],\n    [179, 40, 81],\n    [244, 200, 0],\n    [127, 24, 13],\n    [147, 170, 0],\n    [89, 51, 21],\n    [241, 58, 19],\n    [35, 44, 22],\n    [112, 224, 255],\n    [70, 184, 160],\n    [153, 0, 255],\n    [71, 255, 0],\n    [255, 0, 163],\n    [255, 204, 0],\n    [0, 255, 235],\n    [255, 0, 235],\n    [255, 0, 122],\n    [255, 245, 0],\n    [10, 190, 212],\n    [214, 255, 0],\n    [0, 204, 255],\n    [20, 0, 255],\n    [255, 255, 0],\n    [0, 153, 255],\n    [0, 255, 204],\n    [41, 255, 0],\n    [173, 0, 255],\n    [0, 245, 255],\n    [71, 0, 255],\n    [0, 255, 184],\n    [0, 92, 255],\n    [184, 255, 0],\n    [255, 214, 0],\n    [25, 194, 194],\n    [92, 0, 255],\n    [220, 220, 220],\n    [255, 9, 92],\n    [112, 9, 255],\n    [8, 255, 214],\n    [255, 184, 6],\n    [10, 255, 71],\n    [255, 41, 10],\n    [7, 255, 255],\n    [224, 255, 8],\n    [102, 8, 255],\n    [255, 61, 6],\n    [255, 194, 7],\n    [0, 255, 20],\n    [255, 8, 41],\n    [255, 5, 153],\n    [6, 51, 255],\n    [235, 12, 255],\n    [160, 150, 20],\n    [0, 163, 255],\n    [140, 140, 140],\n    [250, 10, 15],\n    [20, 255, 0],\n]) / 255\n\n\nclass BEVRender:\n    def __init__(\n        self, \n        plot_choices,\n        out_dir,\n        xlim = 40,\n        ylim = 40,\n    ):\n        self.plot_choices = plot_choices\n        self.xlim = xlim\n        self.ylim = ylim\n        self.gt_dir = os.path.join(out_dir, \"bev_gt\")\n        self.pred_dir = os.path.join(out_dir, \"bev_pred\")\n        os.makedirs(self.gt_dir, exist_ok=True)\n        os.makedirs(self.pred_dir, exist_ok=True)\n\n    def reset_canvas(self):\n        plt.close()\n        self.fig, self.axes = plt.subplots(1, 1, figsize=(20, 20))\n        self.axes.set_xlim(- self.xlim, self.xlim)\n        self.axes.set_ylim(- self.ylim, self.ylim)\n        self.axes.axis('off')\n\n    def render(\n        self,\n        data, \n        result,\n        index,\n    ):\n        self.reset_canvas()\n        self.draw_detection_gt(data)\n        self.draw_motion_gt(data)\n        self.draw_map_gt(data)\n        self.draw_planning_gt(data)\n        self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_gt = os.path.join(self.gt_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_gt)\n\n        self.reset_canvas()\n        self.draw_detection_pred(result)\n        self.draw_track_pred(result)\n        self.draw_motion_pred(result)\n        self.draw_map_pred(result)\n        self.draw_planning_pred(data, result)\n        self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_pred = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_pred)\n\n        return save_path_gt, save_path_pred\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        plt.savefig(filename)\n\n    def draw_detection_gt(self, data):\n        if not self.plot_choices['det']:\n            return\n\n        for i in range(data['gt_labels_3d'].shape[0]):\n            label = data['gt_labels_3d'][i]\n            if label == -1: \n                continue\n            color = color_mapping[i % len(color_mapping)]\n\n            # draw corners\n            corners = box3d_to_corners(data['gt_bboxes_3d'])[i, [0, 3, 7, 4, 0]]\n            x = corners[:, 0]\n            y = corners[:, 1]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n            # draw line to indicate forward direction\n            forward_center = np.mean(corners[2:4], axis=0)\n            center = np.mean(corners[0:4], axis=0)\n            x = [forward_center[0], center[0]]\n            y = [forward_center[1], center[1]]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n    def draw_detection_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['det'] and \"boxes_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n\n            # draw corners\n            corners = box3d_to_corners(bboxes)[i, [0, 3, 7, 4, 0]]\n            x = corners[:, 0]\n            y = corners[:, 1]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n            # draw line to indicate forward direction\n            forward_center = np.mean(corners[2:4], axis=0)\n            center = np.mean(corners[0:4], axis=0)\n            x = [forward_center[0], center[0]]\n            y = [forward_center[1], center[1]]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n    def draw_track_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['track'] and \"anchor_queue\" in result):\n            return\n        \n        temp_bboxes = result[\"anchor_queue\"]\n        period = result[\"period\"]\n        bboxes = result['boxes_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n            center = bboxes[i, :3]\n            centers = [center]\n            for j in range(period[i]):\n                # draw corners\n                corners = box3d_to_corners(temp_bboxes[:, -1-j])[i, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color=color, linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color=color, linewidth=2, linestyle='-')\n                centers.append(center)\n\n            centers = np.stack(centers)\n            xs = centers[:, 0]\n            ys = centers[:, 1]\n            self.axes.plot(xs, ys, color=color, linewidth=2, linestyle='-')\n\n    def draw_motion_gt(self, data):\n        if not self.plot_choices['motion']:\n            return\n\n        for i in range(data['gt_labels_3d'].shape[0]):\n            label = data['gt_labels_3d'][i]\n            if label == -1: \n                continue\n            color = color_mapping[i % len(color_mapping)]\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n\n            center = data['gt_bboxes_3d'][i, :2]\n            masks = data['gt_agent_fut_masks'][i].astype(bool)\n            if masks[0] == 0:\n                continue\n            trajs = data['gt_agent_fut_trajs'][i][masks]\n            trajs = trajs.cumsum(axis=0) + center\n            trajs = np.concatenate([center.reshape(1, 2), trajs], axis=0)\n            \n            self._render_traj(trajs, traj_score=1.0,\n                            colormap='winter', dot_size=dot_size)\n\n    def draw_motion_pred(self, result, top_k=3):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['motion'] and \"trajs_3d\" in result):\n            return\n        \n        bboxes = result['boxes_3d']\n        labels = result['labels_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            label = labels[i]\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n\n            traj_score = result['trajs_score'][i].numpy()\n            traj = result['trajs_3d'][i].numpy()\n            num_modes = len(traj_score)\n            center = bboxes[i, :2][None, None].repeat(num_modes, 1, 1).numpy()\n            traj = np.concatenate([center, traj], axis=1)\n\n            sorted_ind = np.argsort(traj_score)[::-1]\n            sorted_traj = traj[sorted_ind, :, :2]\n            sorted_score = traj_score[sorted_ind]\n            norm_score = np.exp(sorted_score[0])\n\n            for j in range(top_k - 1, -1, -1):\n                viz_traj = sorted_traj[j]\n                traj_score = np.exp(sorted_score[j])/norm_score\n                self._render_traj(viz_traj, traj_score=traj_score,\n                                colormap='winter', dot_size=dot_size)\n    \n    def draw_map_gt(self, data):\n        if not self.plot_choices['map']:\n            return\n        vectors = data['map_infos']\n        for label, vector_list in vectors.items():\n            color = COLOR_VECTORS[label]\n            for vector in vector_list:\n                pts = vector[:, :2]\n                x = np.array([pt[0] for pt in pts])\n                y = np.array([pt[1] for pt in pts])\n                self.axes.plot(x, y, color=color, linewidth=3, marker='o', linestyle='-', markersize=7)\n\n    def draw_map_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['map'] and \"vectors\" in result):\n            return\n\n        for i in range(result['scores'].shape[0]):\n            score = result['scores'][i]\n            if  score < MAP_SCORE_THRESH:\n                continue\n            color = COLOR_VECTORS[result['labels'][i]]\n            pts = result['vectors'][i]\n            x = pts[:, 0]\n            y = pts[:, 1]\n            plt.plot(x, y, color=color, linewidth=3, marker='o', linestyle='-', markersize=7)\n\n    def draw_planning_gt(self, data):\n        if not self.plot_choices['planning']:\n            return\n\n        # draw planning gt\n        masks = data['gt_ego_fut_masks'].astype(bool)\n        if masks[0] != 0:\n            plan_traj = data['gt_ego_fut_trajs'][masks]\n            cmd = data['gt_ego_fut_cmd']\n            plan_traj[abs(plan_traj) < 0.01] = 0.0\n            plan_traj = plan_traj.cumsum(axis=0)\n            plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n            self._render_traj(plan_traj, traj_score=1.0,\n                colormap='autumn', dot_size=50)\n\n    def draw_planning_pred(self, data, result, top_k=3):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n\n        if self.plot_choices['track'] and \"ego_anchor_queue\" in result:\n            ego_temp_bboxes = result[\"ego_anchor_queue\"]\n            ego_period = result[\"ego_period\"]\n            for j in range(ego_period[0]):\n                # draw corners\n                corners = box3d_to_corners(ego_temp_bboxes[:, -1-j])[0, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n        # import ipdb; ipdb.set_trace()\n        plan_trajs = result['planning'].cpu().numpy()\n        num_cmd = len(CMD_LIST)\n        num_mode = plan_trajs.shape[1]\n        plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        plan_score = result['planning_score'].cpu().numpy()\n\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        plan_trajs = plan_trajs[cmd]\n        plan_score = plan_score[cmd]\n\n        sorted_ind = np.argsort(plan_score)[::-1]\n        sorted_traj = plan_trajs[sorted_ind, :, :2]\n        sorted_score = plan_score[sorted_ind]\n        norm_score = np.exp(sorted_score[0])\n\n        for j in range(top_k - 1, -1, -1):\n            viz_traj = sorted_traj[j]\n            traj_score = np.exp(sorted_score[j]) / norm_score\n            self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='autumn', dot_size=50)\n\n    def _render_traj(\n        self, \n        future_traj, \n        traj_score=1, \n        colormap='winter', \n        points_per_step=20, \n        dot_size=25\n    ):\n        total_steps = (len(future_traj) - 1) * points_per_step + 1\n        dot_colors = matplotlib.colormaps[colormap](\n            np.linspace(0, 1, total_steps))[:, :3]\n        dot_colors = dot_colors * traj_score + \\\n            (1 - traj_score) * np.ones_like(dot_colors)\n        total_xy = np.zeros((total_steps, 2))\n        for i in range(total_steps - 1):\n            unit_vec = future_traj[i // points_per_step +\n                                   1] - future_traj[i // points_per_step]\n            total_xy[i] = (i / points_per_step - i // points_per_step) * \\\n                unit_vec + future_traj[i // points_per_step]\n        total_xy[-1] = future_traj[-1]\n        self.axes.scatter(\n            total_xy[:, 0], total_xy[:, 1], c=dot_colors, s=dot_size)\n\n    def _render_sdc_car(self):\n        sdc_car_png = cv2.imread('resources/sdc_car.png')\n        sdc_car_png = cv2.cvtColor(sdc_car_png, cv2.COLOR_BGR2RGB)\n        im = self.axes.imshow(sdc_car_png, extent=(-1, 1, -2, 2))\n        im.set_zorder(2)\n\n    def _render_legend(self):\n        legend = cv2.imread('resources/legend.png')\n        legend = cv2.cvtColor(legend, cv2.COLOR_BGR2RGB)\n        self.axes.imshow(legend, extent=(15, 40, -40, -30))\n\n    def _render_command(self, data):\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        self.axes.text(-38, -38, CMD_LIST[cmd], fontsize=60)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/tools/visualization/cam_render.py",
    "content": "import os\nimport numpy as np\nimport cv2\nfrom PIL import Image\n\nimport matplotlib\nimport matplotlib.pyplot as plt\nfrom pyquaternion import Quaternion\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\n\nfrom tools.visualization.bev_render import (\n    color_mapping, \n    SCORE_THRESH, \n    MAP_SCORE_THRESH,\n    CMD_LIST\n)\n\n\nCAM_NAMES_NUSC = [\n    'CAM_FRONT_LEFT',\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_BACK_RIGHT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n]\nCAM_NAMES_NUSC_converter = [\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_FRONT_LEFT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n    'CAM_BACK_RIGHT',\n]\n\nclass CamRender:\n    def __init__(\n        self, \n        plot_choices,\n        out_dir,\n    ):\n        self.plot_choices = plot_choices\n        self.pred_dir = os.path.join(out_dir, \"cam_pred\")\n        os.makedirs(self.pred_dir, exist_ok=True)\n\n    def reset_canvas(self):\n        plt.close()\n        plt.gca().set_axis_off()\n        plt.axis('off')\n        self.fig, self.axes = plt.subplots(2, 3, figsize=(160 /3 , 20))\n        plt.tight_layout()\n\n    def render(\n        self,\n        data, \n        result,\n        index,\n    ):\n        self.reset_canvas()\n        self.render_image_data(data, index)\n        self.draw_detection_pred(data, result)\n        self.draw_motion_pred(data, result)\n        self.draw_planning_pred(data, result)\n        save_path = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path)\n        return save_path\n\n    def load_image(self, data_path, cam):\n        \"\"\"Update the axis of the plot with the provided image.\"\"\"\n        image = np.array(Image.open(data_path))\n        font = cv2.FONT_HERSHEY_SIMPLEX\n        org = (50, 60)\n        fontScale = 2\n        color = (0, 0, 0)\n        thickness = 4\n        return cv2.putText(image, cam, org, font, fontScale, color, thickness, cv2.LINE_AA)\n\n    def update_image(self, image, index, cam):\n        \"\"\"Render image data for each camera.\"\"\"\n        ax = self.get_axis(index)\n        ax.imshow(image)\n        plt.axis('off')\n        ax.axis('off')\n        ax.grid(False)\n\n    def get_axis(self, index):\n        \"\"\"Retrieve the corresponding axis based on the index.\"\"\"\n        return self.axes[index//3, index % 3]\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        plt.savefig(filename)\n\n    def render_image_data(self, data, index):\n        \"\"\"Load and annotate image based on the provided path.\"\"\"\n        for i, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            img_path = data['img_filename'][idx]\n            image = self.load_image(img_path, cam)\n            self.update_image(image, i, cam)\n    \n    def draw_detection_pred(self, data, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['det'] and \"boxes_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d'].numpy()\n        for j, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            cam_intrinsic = data['cam_intrinsic'][idx]\n            lidar2cam = data['lidar2cam']\n            extrinsic = lidar2cam[idx]\n            trans = extrinsic[3, :3]\n            rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n            imsize = (1600, 900)\n\n            for i in range(result['labels_3d'].shape[0]):\n                score = result['scores_3d'][i]\n                if score < SCORE_THRESH: \n                    continue\n                color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n                \n                center = bboxes[i, 0 : 3]\n                box_dims = bboxes[i, 3 : 6]\n                nusc_dims = box_dims[..., [1, 0, 2]]\n                quat = Quaternion(axis=[0, 0, 1], radians=bboxes[i, 6])\n                box = NuScenesBox(\n                    center,\n                    nusc_dims,\n                    quat\n                )\n                box.rotate(rot)\n                box.translate(trans)\n                if box_in_image(box, cam_intrinsic, imsize):\n                    box.render(\n                        self.axes[j // 3, j % 3], \n                        view=cam_intrinsic, \n                        normalize=True, \n                        colors=(color, color, color),\n                        linewidth=4,\n                    )\n            \n            self.axes[j//3, j % 3].set_xlim(0, imsize[0])\n            self.axes[j//3, j % 3].set_ylim(imsize[1], 0)\n\n    def draw_motion_pred(self, data, result, points_per_step=10):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['motion'] and \"trajs_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d'].numpy()\n        for j, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            cam_intrinsic = data['cam_intrinsic'][idx]\n            lidar2cam = data['lidar2cam']\n            extrinsic = lidar2cam[idx]\n            trans = extrinsic[3, :3]\n            rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n            imsize = (1600, 900)\n\n            for i in range(result['labels_3d'].shape[0]):\n                score = result['scores_3d'][i]\n                if score < SCORE_THRESH: \n                    continue\n                color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n                \n                traj_score = result['trajs_score'][i].numpy()\n                traj = result['trajs_3d'][i].numpy()\n                \n                mode_idx = traj_score.argmax()\n                traj = traj[mode_idx]\n                origin = bboxes[i, :2][None]\n                traj = np.concatenate([origin, traj], axis=0)\n                traj_expand = np.ones((traj.shape[0], 1)) \n                traj_expand[:] = bboxes[i, 2] - bboxes[i, 5] / 2\n                traj = np.concatenate([traj, traj_expand], axis=1)\n\n                center = bboxes[i, 0 : 3]\n                box_dims = bboxes[i, 3 : 6]\n                nusc_dims = box_dims[..., [1, 0, 2]]\n                quat = Quaternion(axis=[0, 0, 1], radians=bboxes[i, 6])\n                box = NuScenesBox(\n                    center,\n                    nusc_dims,\n                    quat\n                )\n                box.rotate(rot)\n                box.translate(trans)\n                if not box_in_image(box, cam_intrinsic, imsize):\n                    continue\n                traj_points = traj @ extrinsic[:3, :3] + trans\n                self._render_traj(traj_points, cam_intrinsic, j, color=color, s=15)\n\n        \n    def draw_planning_pred(self, data, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n        # for j, cam in enumerate(CAM_NAMES_NUSC[1]):\n        #     idx = CAM_NAMES_NUSC_converter.index(cam)\n        #     cam_intrinsic = data['cam_intrinsic'][idx]\n        #     lidar2cam = data['lidar2cam']\n        #     extrinsic = lidar2cam[idx]\n        #     trans = extrinsic[3, :3]\n        #     rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n        #     imsize = (1600, 900)\n\n        #     plan_trajs = result['planning'][0].cpu().numpy()\n        #     plan_trajs = plan_trajs.reshape(3, -1, 6, 2)\n        #     num_cmd = len(CMD_LIST)\n        #     num_mode = plan_trajs.shape[1]\n        #     plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        #     plan_trajs = plan_trajs.cumsum(axis=-2)\n        #     plan_score = result['planning_score'][0].cpu().numpy()\n        #     plan_score = plan_score.reshape(3, -1)\n\n        #     cmd = data['gt_ego_fut_cmd'].argmax()\n        #     plan_trajs = plan_trajs[cmd]\n        #     plan_score = plan_score[cmd]\n\n        #     mode_idx = plan_score.argmax()\n        #     plan_traj = plan_trajs[mode_idx]\n        #     traj_expand = np.ones((plan_traj.shape[0], 1)) * -2\n        #     # traj_expand[:] = bboxes[i, 2] - bboxes[i, 5] / 2\n        #     plan_traj = np.concatenate([plan_traj, traj_expand], axis=1)\n\n        #     traj_points = plan_traj @ extrinsic[:3, :3] + trans\n        #     self._render_traj(traj_points, cam_intrinsic, j)\n\n        idx = 0 ## front camera\n        cam_intrinsic = data['cam_intrinsic'][idx]\n        lidar2cam = data['lidar2cam']\n        extrinsic = lidar2cam[idx]\n        trans = extrinsic[3, :3]\n        rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n        # plan_trajs = result['planning'][0].cpu().numpy()\n        # plan_trajs = plan_trajs.reshape(3, -1, 6, 2)\n        # num_cmd = len(CMD_LIST)\n        # num_mode = plan_trajs.shape[1]\n        # plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        # plan_trajs = plan_trajs.cumsum(axis=-2)\n        # plan_score = result['planning_score'][0].cpu().numpy()\n        # plan_score = plan_score.reshape(3, -1)\n\n        # cmd = data['gt_ego_fut_cmd'].argmax()\n        # plan_trajs = plan_trajs[cmd]\n        # plan_score = plan_score[cmd]\n\n        # mode_idx = plan_score.argmax()\n        # plan_traj = plan_trajs[mode_idx]\n        plan_traj = result[\"final_planning\"]\n        plan_traj = np.concatenate((np.zeros((1, 2)), plan_traj), axis=0)\n        traj_expand = np.ones((plan_traj.shape[0], 1)) * -1.8\n        plan_traj = np.concatenate([plan_traj, traj_expand], axis=1)\n\n        traj_points = plan_traj @ extrinsic[:3, :3] + trans\n        self._render_traj(traj_points, cam_intrinsic, j=1)\n\n    def _render_traj(self, traj_points, cam_intrinsic, j, color=(1, 0.5, 0), s=150, points_per_step=10):\n        total_steps = (len(traj_points)-1) * points_per_step + 1\n        total_xy = np.zeros((total_steps, 3))\n        for k in range(total_steps-1):\n            unit_vec = traj_points[k//points_per_step +\n                                    1] - traj_points[k//points_per_step]\n            total_xy[k] = (k/points_per_step - k//points_per_step) * \\\n                unit_vec + traj_points[k//points_per_step]\n        in_range_mask = total_xy[:, 2] > 0.1\n        traj_points = view_points(\n            total_xy.T, cam_intrinsic, normalize=True)[:2, :]\n        traj_points = traj_points[:2, in_range_mask]\n        self.axes[j // 3, j % 3].scatter(traj_points[0], traj_points[1], color=color, s=s)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/adzoo/sparsedrive/train.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    # print(\"hhhhhhhhhhhhhhh\")\n    print(cfg.data.train)\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\", force=True\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/.pylintrc",
    "content": "[MESSAGES CONTROL]\nmax-line-length=120\ndisable=no-self-use,anomalous-backslash-in-string,too-many-arguments,too-few-public-methods,too-many-instance-attributes,redefined-variable-type,unused-argument,wildcard-import,unused-wildcard-import,bare-except,broad-except,bad-continuation,too-many-lines,too-many-branches,locally-disabled,too-many-locals,too-many-statements,duplicate-code,too-many-nested-blocks,fixme\nignored-modules=carla,carla.command\nvariable-rgx=[a-z0-9_]{1,40}$\nfunction-rgx=[a-z0-9_]{1,40}$\nextension-pkg-whitelist=cv2,pygame,numpy"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/CHANGELOG.md",
    "content": "## Latest changes\n\n* Added support to ROS agents, which are meant to inherit from the new `ROS1Agent` and `ROS2Agent` agents. The old `RosAgent` has been deleted.\n* Improved the format of the printed runtime information\n* Added optional side mirrors to the hyman agent\n* Improved the performance of the routes by initializing the scenarios during runtime\n* Improved result writer output, in the same wasy as ScenarioRunner's one.\n* Improved the initialization and cleanup of the Leaderboard.\n* Improved the robustness of the resuming functionality\n* Improved the example Dockerfile and added new example for ROS based agents\n* Added new utility scripts:\n    - merge_statistics.py: join two or more json results into one\n    - route_creator.py: simplifies the creation of new routes\n    - route_displayer.py: parse and debug route xml files from inside the simulator\n    - route_summarizer.py: parses the route xml file into a table.\n    - scenario_creator.py: uses the spectator and terminal inputs to automatically add scenarios to a route\n    - scenario_orderer.py: modifies the scenarios part of the route file to be ordered according to their route's position\n    - weather_creator.py: gets the current simulation's weather in the route format for easy copy.\n* The `StatisticsManager` class has been remade to add robustness, remove unneeded complexity and hardcoded values. Its interaction with other classes has remained unchanged\n* Routes have had the same changed as the ones in ScenarioRunner\n* Added parked vehicles to the routes. These are parsed from a file with all their possible positions.\n* Added new arguments to the leaderboard:\n    - `routes-subset` allows to run part of the routes. Use `-` to run groups of routes (i.e `0-4`), `,` to run specific routes (i.e `1,6,8,14`), or a combination of the two (i.e `0-2,5,8-10`).\n    - `debug-checkpoint` defines the endpoint of the live results, created when the `debug` argument is 2 or higher.\n* Added support for traffic manager hybrid mode.\n* Added a new attribute to the global statistics, *scores_std_dev*, which calculates the standard deviation of the scores done throughout the simulation.\n* Fixed bug causing the global infractions to not be correctly calculated\n\n* Creating stable version for the CARLA online leaderboard\n* Initial creation of the repository\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/LICENSE",
    "content": "MIT License\n\nCopyright (c) 2019 CARLA\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/README.md",
    "content": "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.\n\nAutonomous 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.\n\nAgents will face multiple traffic situations based in the NHTSA typology, such as:\n\n* Lane merging\n* Lane changing\n* Negotiations at traffic intersections\n* Negotiations at roundabouts\n* Handling traffic lights and traffic signs\n* Coping with pedestrians, cyclists and other elements\n\nThe 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.\n\nMore information can be found [here](https://leaderboard.carla.org/)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/Gemfile",
    "content": "source \"https://rubygems.org\"\n\ngem \"jekyll\", \"~> 3.8.5\"\n\ngroup :jekyll_plugins do\n  gem \"jekyll-feed\", \"~> 0.6\"\n  gem \"jekyll-paginate\", \"~> 1.1.0\"\n  gem \"jekyll-sitemap\"\nend\n\n# Windows does not include zoneinfo files, so bundle the tzinfo-data gem\ngem \"tzinfo-data\", platforms: [:mingw, :mswin, :x64_mingw, :jruby]\n\n# Performance-booster for watching directories on Windows\ngem \"wdm\", \"~> 0.1.0\" if Gem.win_platform?\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/LICENSE",
    "content": "The MIT License (MIT)\n\nCopyright (c) 2013-2019 Blackrock Digital LLC\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in\nall copies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN\nTHE SOFTWARE.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/README.md",
    "content": "## Welcome to GitHub Pages\n\nYou can use the [editor on GitHub](https://github.com/carla-simulator/leaderboard/edit/master/README.md) to maintain and preview the content for your website in Markdown files.\n\nWhenever you commit to this repository, GitHub Pages will run [Jekyll](https://jekyllrb.com/) to rebuild the pages in your site, from the content in your Markdown files.\n\n### Markdown\n\nMarkdown is a lightweight and easy-to-use syntax for styling your writing. It includes conventions for\n\n```markdown\nSyntax highlighted code block\n\n# Header 1\n## Header 2\n### Header 3\n\n- Bulleted\n- List\n\n1. Numbered\n2. List\n\n**Bold** and _Italic_ and `Code` text\n\n[Link](url) and ![Image](src)\n```\n\nFor more details see [GitHub Flavored Markdown](https://guides.github.com/features/mastering-markdown/).\n\n### Jekyll Themes\n\nYour Pages site will use the layout and styles from the Jekyll theme you have selected in your [repository settings](https://github.com/carla-simulator/leaderboard/settings). The name of this theme is saved in the Jekyll `_config.yml` configuration file.\n\n### Support or Contact\n\nHaving trouble with Pages? Check out our [documentation](https://help.github.com/categories/github-pages-basics/) or [contact support](https://github.com/contact) and we’ll help you sort it out.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_config.yml",
    "content": "title:              CARLA Leaderboard\nemail:              carla.simulator@gmail.com\ndescription:        CARLA Autonomous Driving competition\nauthor:             CARLA Team\nbaseurl:            \"\"\nurl:                https://leaderboard.carla.org/\n\n# Social Profiles\ngithub_username:   carla-simulator\ntwitter_username:  carlasimulator\ndiscord_invite:    8kqACuC\nyoutube_channel:   UC1llP9ekCwt8nEJzMJBQekg\n\ntwitter:\n  username: carlasimulator\n\nsocial:\n  name: CARLA Simulator\n  links:\n    - https://github.com/carla-simulator/carla\n    - https://twitter.com/carlasimulator\n    - https://discord.gg/8kqACuC\n    - https://www.youtube.com/channel/UC1llP9ekCwt8nEJzMJBQekg\n\n# Build settings\nmarkdown:           kramdown\npaginate:           5\npaginate_path:      \"/posts/page:num/\"\nplugins:\n  - jekyll-feed\n  - jekyll-paginate\n  - jekyll-sitemap ## Uncomment this line to silently generate a sitemaps.org compliant sitemap for your Jekyll site\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_includes/footer.html",
    "content": "<!-- Footer -->\n\n<hr>\n\n<footer>\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n        <ul class=\"list-inline text-center\">\n          {% if site.email %}\n          <li class=\"list-inline-item\">\n            <a href=\"mailto:{{ site.email | encode_email }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"far fa-envelope fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.twitter_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://twitter.com/{{ site.twitter_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-twitter fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.facebook_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://www.facebook.com/{{ site.facebook_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-facebook-f fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.linkedin_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://www.linkedin.com/in/{{ site.linkedin_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-linkedin fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.github_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://github.com/{{ site.github_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-github fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n        </ul>\n        <p class=\"copyright text-muted\">Copyright &copy; {{ site.author }} {{ 'now' | date: \"%Y\" }}</p>\n      </div>\n    </div>\n  </div>\n</footer>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_includes/google-analytics.html",
    "content": "<!-- Global site tag (gtag.js) - Google Analytics -->\n<script async src=\"https://www.googletagmanager.com/gtag/js?id={{ site.google_analytics }}\"></script>\n<script>\n  window.dataLayer = window.dataLayer || [];\n  function gtag(){dataLayer.push(arguments);}\n  gtag('js', new Date());\n\n  gtag('config', '{{ site.google_analytics }}');\n</script>\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_includes/head.html",
    "content": "<head>\n\n  <meta charset=\"utf-8\">\n  <meta name=\"viewport\" content=\"width=device-width, initial-scale=1, shrink-to-fit=no\">\n\n  <title>\n    {% if page.title %}{{ page.title | escape }} - {{ site.title | escape }}\n    {% else %}{{ site.title | escape }}{% endif %}\n  </title>\n\n  <meta name=\"description\" content=\"{{ page.excerpt | default: site.description | strip_html | normalize_whitespace | truncate: 160 | escape }}\">\n\n  <link href='https://fonts.googleapis.com/css?family=Lora:400,700,400italic,700italic' rel='stylesheet' type='text/css'>\n  <link href='https://fonts.googleapis.com/css?family=Open+Sans:300italic,400italic,600italic,700italic,800italic,400,300,600,700,800' rel='stylesheet' type='text/css'>\n\n  <link rel=\"stylesheet\" href=\"{{\"/assets/vendor/bootstrap/css/bootstrap.min.css\" | relative_url }}\">\n\n  <link rel=\"stylesheet\" href=\"{{\"/assets/vendor/fontawesome-free/css/all.min.css\" | relative_url }}\">\n\n  <link rel=\"stylesheet\" href=\"{{\"/assets/main.css\" | relative_url }}\">\n  <link rel=\"canonical\" href=\"{{ page.url | replace:'index.html','' | absolute_url }}\">\n  <link rel=\"alternate\" type=\"application/rss+xml\" title=\"{{ site.title | escape }}\" href=\"{{ \"/feed.xml\" | relative_url }}\">\n\n</head>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_includes/navbar.html",
    "content": "<!-- Navigation -->\n<nav class=\"navbar navbar-expand-lg navbar-light fixed-top\" id=\"mainNav\">\n  <div class=\"container\">\n    <a class=\"navbar-brand\" href=\"{{\"/\" | relative_url }}\">{{ site.title | escape }}</a>\n    <button class=\"navbar-toggler navbar-toggler-right\" type=\"button\" data-toggle=\"collapse\" data-target=\"#navbarResponsive\" aria-controls=\"navbarResponsive\" aria-expanded=\"false\" aria-label=\"Toggle navigation\">\n      Menu\n      <i class=\"fa fa-bars\"></i>\n    </button>\n    <div class=\"collapse navbar-collapse\" id=\"navbarResponsive\">\n      <ul class=\"navbar-nav ml-auto\">\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{\"/\" | relative_url }}\">Home</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{\"/get_started\" | relative_url }}\">Getting started</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{ \"/submit\" | relative_url }}\">Submit</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{ \"/leaderboard\" | relative_url }}\">Leaderboard</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" target=\"_blank\" href=\"https://github.com/carla-simulator/leaderboard\">GitHub</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{\"/contact\" | relative_url }}\">About</a>\n        </li>\n      </ul>\n    </div>\n  </div>\n</nav>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_includes/read_time.html",
    "content": "<span class=\"reading-time\" title=\"Estimated read time\">\n  {% assign words = include.content | number_of_words %}\n  {% if words < 270 %} 1 min {% else %} {{ words | divided_by:135 }} mins {% endif %} read </span>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_includes/scripts.html",
    "content": "<script src=\"{{\"/assets/vendor/jquery/jquery.min.js\" | relative_url }}\"></script>\n<script src=\"{{\"/assets/vendor/bootstrap/js/bootstrap.bundle.min.js\" | relative_url }}\"></script>\n<script src=\"{{\"/assets/vendor/startbootstrap-clean-blog/js/clean-blog.min.js\" | relative_url }}\"></script>\n\n<script src=\"{{\"/assets/scripts.js\" | relative_url }}\"></script>\n\n{% if page.url contains 'contact' %}\n  <!-- Form Validation -->\n  <script src=\"{{\"/assets/vendor/startbootstrap-clean-blog/js/jqBootstrapValidation.js\" | relative_url }}\"></script>\n  <!-- Send Form -->\n  <script>\n    $(function () {\n\n      $(\"#contactForm input,#contactForm textarea\").jqBootstrapValidation({\n        preventSubmit: true,\n        submitError: function ($form, event, errors) {\n          // additional error messages or events\n        },\n        submitSuccess: function ($form, event) {\n          event.preventDefault(); // prevent default submit behaviour\n          // get values from FORM\n          var name = $(\"input#name\").val();\n          var email = $(\"input#email\").val();\n          var phone = $(\"input#phone\").val();\n          var message = $(\"textarea#message\").val();\n          var firstName = name; // For Success/Failure Message\n          // Check for white space in name for Success/Fail message\n          if (firstName.indexOf(' ') >= 0) {\n            firstName = name.split(' ').slice(0, -1).join(' ');\n          }\n          $this = $(\"#sendMessageButton\");\n          $this.prop(\"disabled\", true); // Disable submit button until AJAX call is complete to prevent duplicate messages\n          $.ajax({\n            url: \"//formspree.io/{{ site.email }}\",\n            type: \"POST\",\n            data: {\n              name: name,\n              phone: phone,\n              email: email,\n              message: message\n            },\n            cache: false,\n            success: function () {\n              // Success message\n              $('#success').html(\"<div class='alert alert-success'>\");\n              $('#success > .alert-success').html(\"<button type='button' class='close' data-dismiss='alert' aria-hidden='true'>&times;\").append(\"</button>\");\n              $('#success > .alert-success').append(\"<strong>Your message has been sent. </strong>\");\n              $('#success > .alert-success').append('</div>');\n              //clear all fields\n              $('#contactForm').trigger(\"reset\");\n            },\n            error: function () {\n              // Fail message\n              $('#success').html(\"<div class='alert alert-danger'>\");\n              $('#success > .alert-danger').html(\"<button type='button' class='close' data-dismiss='alert' aria-hidden='true'>&times;\").append(\"</button>\");\n              $('#success > .alert-danger').append($(\"<strong>\").text(\"Sorry \" + firstName + \", it seems that my mail server is not responding. Please try again later!\"));\n              $('#success > .alert-danger').append('</div>');\n              //clear all fields\n              $('#contactForm').trigger(\"reset\");\n            },\n            complete: function () {\n              setTimeout(function () {\n                $this.prop(\"disabled\", false); // Re-enable submit button when AJAX call is complete\n              }, 1000);\n            }\n          });\n        },\n        filter: function () {\n          return $(this).is(\":visible\");\n        }\n      });\n\n      $(\"a[data-toggle=\\\"tab\\\"]\").click(function (e) {\n        e.preventDefault();\n        $(this).tab(\"show\");\n      });\n    });\n\n    /*When clicking on Full hide fail/success boxes */\n    $('#name').focus(function () {\n      $('#success').html('');\n    });\n  </script>\n{% endif %}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_layouts/default.html",
    "content": "<!DOCTYPE html>\n\n<html>\n\n{% include head.html %}\n\n<body>\n\n  {% include navbar.html %}\n\n  {{ content }}\n\n  {% include footer.html %}\n\n  {% include scripts.html %}\n\n  {% include google-analytics.html %}\n\n</body>\n\n</html>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_layouts/home.html",
    "content": "---\nlayout: default\n---\n\n<!-- Page Header -->\n{% if page.background %}\n<header class=\"masthead\" style=\"background-image: url('{{ page.background | prepend: site.baseurl | replace: '//', '/' }}')\">\n  {% else %}\n  <header class=\"masthead\">\n    {% endif %}\n    <div class=\"overlay\"></div>\n    <div class=\"container\">\n      <div class=\"row\">\n        <div class=\"col-lg-8 col-md-10 mx-auto\">\n          <div class=\"page-heading\">\n            \n          </div>\n        </div>\n      </div>\n    </div>\n  </header>\n\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n\n        {{ content }}\n\n      </div>\n    </div>\n  </div>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_layouts/page.html",
    "content": "---\nlayout: default\n---\n\n<!-- Page Header -->\n{% if page.background %}\n<header class=\"masthead\" style=\"background-image: url('{{ page.background | prepend: site.baseurl | replace: '//', '/' }}')\">\n  {% else %}\n  <header class=\"masthead\">\n    {% endif %}\n    <div class=\"overlay\"></div>\n    <div class=\"container\">\n      <div class=\"row\">\n        <div class=\"col-lg-8 col-md-10 mx-auto\">\n          <div class=\"page-heading\">\n            <h1>{{ page.title }}</h1>\n            {% if page.description %}\n            <span class=\"subheading\">{{ page.description }}</span>\n            {% endif %}\n          </div>\n        </div>\n      </div>\n    </div>\n  </header>\n\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n\n        {{ content }}\n\n      </div>\n    </div>\n  </div>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_layouts/post.html",
    "content": "---\nlayout: default\n---\n\n<!-- Page Header -->\n{% if page.background %}\n<header class=\"masthead\" style=\"background-image: url('{{ page.background | prepend: site.baseurl | replace: '//', '/' }}')\">\n  {% else %}\n  <header class=\"masthead\">\n    {% endif %}\n    <div class=\"overlay\"></div>\n    <div class=\"container\">\n      <div class=\"row\">\n        <div class=\"col-lg-8 col-md-10 mx-auto\">\n          <div class=\"post-heading\">\n            <h1>{{ page.title }}</h1>\n            {% if page.subtitle %}\n            <h2 class=\"subheading\">{{ page.subtitle }}</h2>\n            {% endif %}\n            <span class=\"meta\">Posted by\n              <a href=\"#\">{% if page.author %}{{ page.author }}{% else %}{{ site.author }}{% endif %}</a>\n              on {{ page.date | date: '%B %d, %Y' }} &middot; {% include read_time.html\n              content=page.content %}\n            </span>\n          </div>\n        </div>\n      </div>\n    </div>\n  </header>\n\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n\n        {{ content }}\n\n        <hr>\n\n        <div class=\"clearfix\">\n\n          {% if page.previous.url %}\n          <a class=\"btn btn-primary float-left\" href=\"{{ page.previous.url | prepend: site.baseurl | replace: '//', '/' }}\" data-toggle=\"tooltip\" data-placement=\"top\" title=\"{{ page.previous.title }}\">&larr; Previous<span class=\"d-none d-md-inline\">\n              Post</span></a>\n          {% endif %}\n          {% if page.next.url %}\n          <a class=\"btn btn-primary float-right\" href=\"{{ page.next.url | prepend: site.baseurl | replace: '//', '/' }}\" data-toggle=\"tooltip\" data-placement=\"top\" title=\"{{ page.next.title }}\">Next<span class=\"d-none d-md-inline\">\n              Post</span> &rarr;</a>\n          {% endif %}\n\n        </div>\n\n      </div>\n    </div>\n  </div>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/_sass/styles.scss",
    "content": "// Import Core Clean Blog SCSS\n@import \"../assets/vendor/startbootstrap-clean-blog/scss/clean-blog.scss\";\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/about.html",
    "content": "---\nlayout: page\ntitle: About us\ndescription: This is what I do.\nbackground: '/img/bg-about.jpg'\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/main.scss",
    "content": "---\n# Only the main Sass file needs front matter (the dashes are enough)\n---\n\n@import \"styles\";\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/scripts.js",
    "content": "$(function () {\n  $('[data-toggle=\"tooltip\"]').tooltip()\n})\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/bootstrap/css/bootstrap.css",
    "content": "/*!\n * Bootstrap v4.3.1 (https://getbootstrap.com/)\n * Copyright 2011-2019 The Bootstrap Authors\n * Copyright 2011-2019 Twitter, Inc.\n * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n */\n:root {\n  --blue: #007bff;\n  --indigo: #6610f2;\n  --purple: #6f42c1;\n  --pink: #e83e8c;\n  --red: #dc3545;\n  --orange: #fd7e14;\n  --yellow: #ffc107;\n  --green: #28a745;\n  --teal: #20c997;\n  --cyan: #17a2b8;\n  --white: #fff;\n  --gray: #6c757d;\n  --gray-dark: #343a40;\n  --primary: #007bff;\n  --secondary: #6c757d;\n  --success: #28a745;\n  --info: #17a2b8;\n  --warning: #ffc107;\n  --danger: #dc3545;\n  --light: #f8f9fa;\n  --dark: #343a40;\n  --breakpoint-xs: 0;\n  --breakpoint-sm: 576px;\n  --breakpoint-md: 768px;\n  --breakpoint-lg: 992px;\n  --breakpoint-xl: 1200px;\n  --font-family-sans-serif: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  --font-family-monospace: SFMono-Regular, Menlo, Monaco, Consolas, \"Liberation Mono\", \"Courier New\", monospace;\n}\n\n*,\n*::before,\n*::after {\n  box-sizing: border-box;\n}\n\nhtml {\n  font-family: sans-serif;\n  line-height: 1.15;\n  -webkit-text-size-adjust: 100%;\n  -webkit-tap-highlight-color: rgba(0, 0, 0, 0);\n}\n\narticle, aside, figcaption, figure, footer, header, hgroup, main, nav, section {\n  display: block;\n}\n\nbody {\n  margin: 0;\n  font-family: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #212529;\n  text-align: left;\n  background-color: #fff;\n}\n\n[tabindex=\"-1\"]:focus {\n  outline: 0 !important;\n}\n\nhr {\n  box-sizing: content-box;\n  height: 0;\n  overflow: visible;\n}\n\nh1, h2, h3, h4, h5, h6 {\n  margin-top: 0;\n  margin-bottom: 0.5rem;\n}\n\np {\n  margin-top: 0;\n  margin-bottom: 1rem;\n}\n\nabbr[title],\nabbr[data-original-title] {\n  text-decoration: underline;\n  -webkit-text-decoration: underline dotted;\n  text-decoration: underline dotted;\n  cursor: help;\n  border-bottom: 0;\n  -webkit-text-decoration-skip-ink: none;\n  text-decoration-skip-ink: none;\n}\n\naddress {\n  margin-bottom: 1rem;\n  font-style: normal;\n  line-height: inherit;\n}\n\nol,\nul,\ndl {\n  margin-top: 0;\n  margin-bottom: 1rem;\n}\n\nol ol,\nul ul,\nol ul,\nul ol {\n  margin-bottom: 0;\n}\n\ndt {\n  font-weight: 700;\n}\n\ndd {\n  margin-bottom: .5rem;\n  margin-left: 0;\n}\n\nblockquote {\n  margin: 0 0 1rem;\n}\n\nb,\nstrong {\n  font-weight: bolder;\n}\n\nsmall {\n  font-size: 80%;\n}\n\nsub,\nsup {\n  position: relative;\n  font-size: 75%;\n  line-height: 0;\n  vertical-align: baseline;\n}\n\nsub {\n  bottom: -.25em;\n}\n\nsup {\n  top: -.5em;\n}\n\na {\n  color: #007bff;\n  text-decoration: none;\n  background-color: transparent;\n}\n\na:hover {\n  color: #0056b3;\n  text-decoration: underline;\n}\n\na:not([href]):not([tabindex]) {\n  color: inherit;\n  text-decoration: none;\n}\n\na:not([href]):not([tabindex]):hover, a:not([href]):not([tabindex]):focus {\n  color: inherit;\n  text-decoration: none;\n}\n\na:not([href]):not([tabindex]):focus {\n  outline: 0;\n}\n\npre,\ncode,\nkbd,\nsamp {\n  font-family: SFMono-Regular, Menlo, Monaco, Consolas, \"Liberation Mono\", \"Courier New\", monospace;\n  font-size: 1em;\n}\n\npre {\n  margin-top: 0;\n  margin-bottom: 1rem;\n  overflow: auto;\n}\n\nfigure {\n  margin: 0 0 1rem;\n}\n\nimg {\n  vertical-align: middle;\n  border-style: none;\n}\n\nsvg {\n  overflow: hidden;\n  vertical-align: middle;\n}\n\ntable {\n  border-collapse: collapse;\n}\n\ncaption {\n  padding-top: 0.75rem;\n  padding-bottom: 0.75rem;\n  color: #6c757d;\n  text-align: left;\n  caption-side: bottom;\n}\n\nth {\n  text-align: inherit;\n}\n\nlabel {\n  display: inline-block;\n  margin-bottom: 0.5rem;\n}\n\nbutton {\n  border-radius: 0;\n}\n\nbutton:focus {\n  outline: 1px dotted;\n  outline: 5px auto -webkit-focus-ring-color;\n}\n\ninput,\nbutton,\nselect,\noptgroup,\ntextarea {\n  margin: 0;\n  font-family: inherit;\n  font-size: inherit;\n  line-height: inherit;\n}\n\nbutton,\ninput {\n  overflow: visible;\n}\n\nbutton,\nselect {\n  text-transform: none;\n}\n\nselect {\n  word-wrap: normal;\n}\n\nbutton,\n[type=\"button\"],\n[type=\"reset\"],\n[type=\"submit\"] {\n  -webkit-appearance: button;\n}\n\nbutton:not(:disabled),\n[type=\"button\"]:not(:disabled),\n[type=\"reset\"]:not(:disabled),\n[type=\"submit\"]:not(:disabled) {\n  cursor: pointer;\n}\n\nbutton::-moz-focus-inner,\n[type=\"button\"]::-moz-focus-inner,\n[type=\"reset\"]::-moz-focus-inner,\n[type=\"submit\"]::-moz-focus-inner {\n  padding: 0;\n  border-style: none;\n}\n\ninput[type=\"radio\"],\ninput[type=\"checkbox\"] {\n  box-sizing: border-box;\n  padding: 0;\n}\n\ninput[type=\"date\"],\ninput[type=\"time\"],\ninput[type=\"datetime-local\"],\ninput[type=\"month\"] {\n  -webkit-appearance: listbox;\n}\n\ntextarea {\n  overflow: auto;\n  resize: vertical;\n}\n\nfieldset {\n  min-width: 0;\n  padding: 0;\n  margin: 0;\n  border: 0;\n}\n\nlegend {\n  display: block;\n  width: 100%;\n  max-width: 100%;\n  padding: 0;\n  margin-bottom: .5rem;\n  font-size: 1.5rem;\n  line-height: inherit;\n  color: inherit;\n  white-space: normal;\n}\n\nprogress {\n  vertical-align: baseline;\n}\n\n[type=\"number\"]::-webkit-inner-spin-button,\n[type=\"number\"]::-webkit-outer-spin-button {\n  height: auto;\n}\n\n[type=\"search\"] {\n  outline-offset: -2px;\n  -webkit-appearance: none;\n}\n\n[type=\"search\"]::-webkit-search-decoration {\n  -webkit-appearance: none;\n}\n\n::-webkit-file-upload-button {\n  font: inherit;\n  -webkit-appearance: button;\n}\n\noutput {\n  display: inline-block;\n}\n\nsummary {\n  display: list-item;\n  cursor: pointer;\n}\n\ntemplate {\n  display: none;\n}\n\n[hidden] {\n  display: none !important;\n}\n\nh1, h2, h3, h4, h5, h6,\n.h1, .h2, .h3, .h4, .h5, .h6 {\n  margin-bottom: 0.5rem;\n  font-weight: 500;\n  line-height: 1.2;\n}\n\nh1, .h1 {\n  font-size: 2.5rem;\n}\n\nh2, .h2 {\n  font-size: 2rem;\n}\n\nh3, .h3 {\n  font-size: 1.75rem;\n}\n\nh4, .h4 {\n  font-size: 1.5rem;\n}\n\nh5, .h5 {\n  font-size: 1.25rem;\n}\n\nh6, .h6 {\n  font-size: 1rem;\n}\n\n.lead {\n  font-size: 1.25rem;\n  font-weight: 300;\n}\n\n.display-1 {\n  font-size: 6rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\n.display-2 {\n  font-size: 5.5rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\n.display-3 {\n  font-size: 4.5rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\n.display-4 {\n  font-size: 3.5rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\nhr {\n  margin-top: 1rem;\n  margin-bottom: 1rem;\n  border: 0;\n  border-top: 1px solid rgba(0, 0, 0, 0.1);\n}\n\nsmall,\n.small {\n  font-size: 80%;\n  font-weight: 400;\n}\n\nmark,\n.mark {\n  padding: 0.2em;\n  background-color: #fcf8e3;\n}\n\n.list-unstyled {\n  padding-left: 0;\n  list-style: none;\n}\n\n.list-inline {\n  padding-left: 0;\n  list-style: none;\n}\n\n.list-inline-item {\n  display: inline-block;\n}\n\n.list-inline-item:not(:last-child) {\n  margin-right: 0.5rem;\n}\n\n.initialism {\n  font-size: 90%;\n  text-transform: uppercase;\n}\n\n.blockquote {\n  margin-bottom: 1rem;\n  font-size: 1.25rem;\n}\n\n.blockquote-footer {\n  display: block;\n  font-size: 80%;\n  color: #6c757d;\n}\n\n.blockquote-footer::before {\n  content: \"\\2014\\00A0\";\n}\n\n.img-fluid {\n  max-width: 100%;\n  height: auto;\n}\n\n.img-thumbnail {\n  padding: 0.25rem;\n  background-color: #fff;\n  border: 1px solid #dee2e6;\n  border-radius: 0.25rem;\n  max-width: 100%;\n  height: auto;\n}\n\n.figure {\n  display: inline-block;\n}\n\n.figure-img {\n  margin-bottom: 0.5rem;\n  line-height: 1;\n}\n\n.figure-caption {\n  font-size: 90%;\n  color: #6c757d;\n}\n\ncode {\n  font-size: 87.5%;\n  color: #e83e8c;\n  word-break: break-word;\n}\n\na > code {\n  color: inherit;\n}\n\nkbd {\n  padding: 0.2rem 0.4rem;\n  font-size: 87.5%;\n  color: #fff;\n  background-color: #212529;\n  border-radius: 0.2rem;\n}\n\nkbd kbd {\n  padding: 0;\n  font-size: 100%;\n  font-weight: 700;\n}\n\npre {\n  display: block;\n  font-size: 87.5%;\n  color: #212529;\n}\n\npre code {\n  font-size: inherit;\n  color: inherit;\n  word-break: normal;\n}\n\n.pre-scrollable {\n  max-height: 340px;\n  overflow-y: scroll;\n}\n\n.container {\n  width: 100%;\n  padding-right: 15px;\n  padding-left: 15px;\n  margin-right: auto;\n  margin-left: auto;\n}\n\n@media (min-width: 576px) {\n  .container {\n    max-width: 540px;\n  }\n}\n\n@media (min-width: 768px) {\n  .container {\n    max-width: 720px;\n  }\n}\n\n@media (min-width: 992px) {\n  .container {\n    max-width: 960px;\n  }\n}\n\n@media (min-width: 1200px) {\n  .container {\n    max-width: 1140px;\n  }\n}\n\n.container-fluid {\n  width: 100%;\n  padding-right: 15px;\n  padding-left: 15px;\n  margin-right: auto;\n  margin-left: auto;\n}\n\n.row {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  margin-right: -15px;\n  margin-left: -15px;\n}\n\n.no-gutters {\n  margin-right: 0;\n  margin-left: 0;\n}\n\n.no-gutters > .col,\n.no-gutters > [class*=\"col-\"] {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.col-1, .col-2, .col-3, .col-4, .col-5, .col-6, .col-7, .col-8, .col-9, .col-10, .col-11, .col-12, .col,\n.col-auto, .col-sm-1, .col-sm-2, .col-sm-3, .col-sm-4, .col-sm-5, .col-sm-6, .col-sm-7, .col-sm-8, .col-sm-9, .col-sm-10, .col-sm-11, .col-sm-12, .col-sm,\n.col-sm-auto, .col-md-1, .col-md-2, .col-md-3, .col-md-4, .col-md-5, .col-md-6, .col-md-7, .col-md-8, .col-md-9, .col-md-10, .col-md-11, .col-md-12, .col-md,\n.col-md-auto, .col-lg-1, .col-lg-2, .col-lg-3, .col-lg-4, .col-lg-5, .col-lg-6, .col-lg-7, .col-lg-8, .col-lg-9, .col-lg-10, .col-lg-11, .col-lg-12, .col-lg,\n.col-lg-auto, .col-xl-1, .col-xl-2, .col-xl-3, .col-xl-4, .col-xl-5, .col-xl-6, .col-xl-7, .col-xl-8, .col-xl-9, .col-xl-10, .col-xl-11, .col-xl-12, .col-xl,\n.col-xl-auto {\n  position: relative;\n  width: 100%;\n  padding-right: 15px;\n  padding-left: 15px;\n}\n\n.col {\n  -ms-flex-preferred-size: 0;\n  flex-basis: 0;\n  -ms-flex-positive: 1;\n  flex-grow: 1;\n  max-width: 100%;\n}\n\n.col-auto {\n  -ms-flex: 0 0 auto;\n  flex: 0 0 auto;\n  width: auto;\n  max-width: 100%;\n}\n\n.col-1 {\n  -ms-flex: 0 0 8.333333%;\n  flex: 0 0 8.333333%;\n  max-width: 8.333333%;\n}\n\n.col-2 {\n  -ms-flex: 0 0 16.666667%;\n  flex: 0 0 16.666667%;\n  max-width: 16.666667%;\n}\n\n.col-3 {\n  -ms-flex: 0 0 25%;\n  flex: 0 0 25%;\n  max-width: 25%;\n}\n\n.col-4 {\n  -ms-flex: 0 0 33.333333%;\n  flex: 0 0 33.333333%;\n  max-width: 33.333333%;\n}\n\n.col-5 {\n  -ms-flex: 0 0 41.666667%;\n  flex: 0 0 41.666667%;\n  max-width: 41.666667%;\n}\n\n.col-6 {\n  -ms-flex: 0 0 50%;\n  flex: 0 0 50%;\n  max-width: 50%;\n}\n\n.col-7 {\n  -ms-flex: 0 0 58.333333%;\n  flex: 0 0 58.333333%;\n  max-width: 58.333333%;\n}\n\n.col-8 {\n  -ms-flex: 0 0 66.666667%;\n  flex: 0 0 66.666667%;\n  max-width: 66.666667%;\n}\n\n.col-9 {\n  -ms-flex: 0 0 75%;\n  flex: 0 0 75%;\n  max-width: 75%;\n}\n\n.col-10 {\n  -ms-flex: 0 0 83.333333%;\n  flex: 0 0 83.333333%;\n  max-width: 83.333333%;\n}\n\n.col-11 {\n  -ms-flex: 0 0 91.666667%;\n  flex: 0 0 91.666667%;\n  max-width: 91.666667%;\n}\n\n.col-12 {\n  -ms-flex: 0 0 100%;\n  flex: 0 0 100%;\n  max-width: 100%;\n}\n\n.order-first {\n  -ms-flex-order: -1;\n  order: -1;\n}\n\n.order-last {\n  -ms-flex-order: 13;\n  order: 13;\n}\n\n.order-0 {\n  -ms-flex-order: 0;\n  order: 0;\n}\n\n.order-1 {\n  -ms-flex-order: 1;\n  order: 1;\n}\n\n.order-2 {\n  -ms-flex-order: 2;\n  order: 2;\n}\n\n.order-3 {\n  -ms-flex-order: 3;\n  order: 3;\n}\n\n.order-4 {\n  -ms-flex-order: 4;\n  order: 4;\n}\n\n.order-5 {\n  -ms-flex-order: 5;\n  order: 5;\n}\n\n.order-6 {\n  -ms-flex-order: 6;\n  order: 6;\n}\n\n.order-7 {\n  -ms-flex-order: 7;\n  order: 7;\n}\n\n.order-8 {\n  -ms-flex-order: 8;\n  order: 8;\n}\n\n.order-9 {\n  -ms-flex-order: 9;\n  order: 9;\n}\n\n.order-10 {\n  -ms-flex-order: 10;\n  order: 10;\n}\n\n.order-11 {\n  -ms-flex-order: 11;\n  order: 11;\n}\n\n.order-12 {\n  -ms-flex-order: 12;\n  order: 12;\n}\n\n.offset-1 {\n  margin-left: 8.333333%;\n}\n\n.offset-2 {\n  margin-left: 16.666667%;\n}\n\n.offset-3 {\n  margin-left: 25%;\n}\n\n.offset-4 {\n  margin-left: 33.333333%;\n}\n\n.offset-5 {\n  margin-left: 41.666667%;\n}\n\n.offset-6 {\n  margin-left: 50%;\n}\n\n.offset-7 {\n  margin-left: 58.333333%;\n}\n\n.offset-8 {\n  margin-left: 66.666667%;\n}\n\n.offset-9 {\n  margin-left: 75%;\n}\n\n.offset-10 {\n  margin-left: 83.333333%;\n}\n\n.offset-11 {\n  margin-left: 91.666667%;\n}\n\n@media (min-width: 576px) {\n  .col-sm {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-sm-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-sm-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-sm-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-sm-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-sm-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-sm-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-sm-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-sm-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-sm-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-sm-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-sm-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-sm-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-sm-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-sm-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-sm-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-sm-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-sm-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-sm-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-sm-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-sm-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-sm-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-sm-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-sm-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-sm-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-sm-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-sm-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-sm-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-sm-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-sm-0 {\n    margin-left: 0;\n  }\n  .offset-sm-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-sm-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-sm-3 {\n    margin-left: 25%;\n  }\n  .offset-sm-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-sm-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-sm-6 {\n    margin-left: 50%;\n  }\n  .offset-sm-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-sm-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-sm-9 {\n    margin-left: 75%;\n  }\n  .offset-sm-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-sm-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n@media (min-width: 768px) {\n  .col-md {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-md-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-md-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-md-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-md-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-md-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-md-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-md-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-md-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-md-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-md-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-md-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-md-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-md-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-md-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-md-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-md-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-md-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-md-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-md-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-md-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-md-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-md-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-md-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-md-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-md-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-md-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-md-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-md-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-md-0 {\n    margin-left: 0;\n  }\n  .offset-md-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-md-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-md-3 {\n    margin-left: 25%;\n  }\n  .offset-md-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-md-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-md-6 {\n    margin-left: 50%;\n  }\n  .offset-md-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-md-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-md-9 {\n    margin-left: 75%;\n  }\n  .offset-md-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-md-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n@media (min-width: 992px) {\n  .col-lg {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-lg-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-lg-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-lg-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-lg-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-lg-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-lg-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-lg-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-lg-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-lg-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-lg-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-lg-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-lg-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-lg-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-lg-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-lg-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-lg-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-lg-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-lg-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-lg-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-lg-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-lg-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-lg-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-lg-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-lg-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-lg-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-lg-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-lg-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-lg-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-lg-0 {\n    margin-left: 0;\n  }\n  .offset-lg-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-lg-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-lg-3 {\n    margin-left: 25%;\n  }\n  .offset-lg-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-lg-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-lg-6 {\n    margin-left: 50%;\n  }\n  .offset-lg-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-lg-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-lg-9 {\n    margin-left: 75%;\n  }\n  .offset-lg-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-lg-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n@media (min-width: 1200px) {\n  .col-xl {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-xl-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-xl-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-xl-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-xl-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-xl-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-xl-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-xl-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-xl-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-xl-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-xl-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-xl-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-xl-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-xl-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-xl-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-xl-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-xl-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-xl-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-xl-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-xl-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-xl-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-xl-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-xl-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-xl-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-xl-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-xl-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-xl-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-xl-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-xl-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-xl-0 {\n    margin-left: 0;\n  }\n  .offset-xl-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-xl-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-xl-3 {\n    margin-left: 25%;\n  }\n  .offset-xl-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-xl-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-xl-6 {\n    margin-left: 50%;\n  }\n  .offset-xl-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-xl-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-xl-9 {\n    margin-left: 75%;\n  }\n  .offset-xl-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-xl-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n.table {\n  width: 100%;\n  margin-bottom: 1rem;\n  color: #212529;\n}\n\n.table th,\n.table td {\n  padding: 0.75rem;\n  vertical-align: top;\n  border-top: 1px solid #dee2e6;\n}\n\n.table thead th {\n  vertical-align: bottom;\n  border-bottom: 2px solid #dee2e6;\n}\n\n.table tbody + tbody {\n  border-top: 2px solid #dee2e6;\n}\n\n.table-sm th,\n.table-sm td {\n  padding: 0.3rem;\n}\n\n.table-bordered {\n  border: 1px solid #dee2e6;\n}\n\n.table-bordered th,\n.table-bordered td {\n  border: 1px solid #dee2e6;\n}\n\n.table-bordered thead th,\n.table-bordered thead td {\n  border-bottom-width: 2px;\n}\n\n.table-borderless th,\n.table-borderless td,\n.table-borderless thead th,\n.table-borderless tbody + tbody {\n  border: 0;\n}\n\n.table-striped tbody tr:nth-of-type(odd) {\n  background-color: rgba(0, 0, 0, 0.05);\n}\n\n.table-hover tbody tr:hover {\n  color: #212529;\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table-primary,\n.table-primary > th,\n.table-primary > td {\n  background-color: #b8daff;\n}\n\n.table-primary th,\n.table-primary td,\n.table-primary thead th,\n.table-primary tbody + tbody {\n  border-color: #7abaff;\n}\n\n.table-hover .table-primary:hover {\n  background-color: #9fcdff;\n}\n\n.table-hover .table-primary:hover > td,\n.table-hover .table-primary:hover > th {\n  background-color: #9fcdff;\n}\n\n.table-secondary,\n.table-secondary > th,\n.table-secondary > td {\n  background-color: #d6d8db;\n}\n\n.table-secondary th,\n.table-secondary td,\n.table-secondary thead th,\n.table-secondary tbody + tbody {\n  border-color: #b3b7bb;\n}\n\n.table-hover .table-secondary:hover {\n  background-color: #c8cbcf;\n}\n\n.table-hover .table-secondary:hover > td,\n.table-hover .table-secondary:hover > th {\n  background-color: #c8cbcf;\n}\n\n.table-success,\n.table-success > th,\n.table-success > td {\n  background-color: #c3e6cb;\n}\n\n.table-success th,\n.table-success td,\n.table-success thead th,\n.table-success tbody + tbody {\n  border-color: #8fd19e;\n}\n\n.table-hover .table-success:hover {\n  background-color: #b1dfbb;\n}\n\n.table-hover .table-success:hover > td,\n.table-hover .table-success:hover > th {\n  background-color: #b1dfbb;\n}\n\n.table-info,\n.table-info > th,\n.table-info > td {\n  background-color: #bee5eb;\n}\n\n.table-info th,\n.table-info td,\n.table-info thead th,\n.table-info tbody + tbody {\n  border-color: #86cfda;\n}\n\n.table-hover .table-info:hover {\n  background-color: #abdde5;\n}\n\n.table-hover .table-info:hover > td,\n.table-hover .table-info:hover > th {\n  background-color: #abdde5;\n}\n\n.table-warning,\n.table-warning > th,\n.table-warning > td {\n  background-color: #ffeeba;\n}\n\n.table-warning th,\n.table-warning td,\n.table-warning thead th,\n.table-warning tbody + tbody {\n  border-color: #ffdf7e;\n}\n\n.table-hover .table-warning:hover {\n  background-color: #ffe8a1;\n}\n\n.table-hover .table-warning:hover > td,\n.table-hover .table-warning:hover > th {\n  background-color: #ffe8a1;\n}\n\n.table-danger,\n.table-danger > th,\n.table-danger > td {\n  background-color: #f5c6cb;\n}\n\n.table-danger th,\n.table-danger td,\n.table-danger thead th,\n.table-danger tbody + tbody {\n  border-color: #ed969e;\n}\n\n.table-hover .table-danger:hover {\n  background-color: #f1b0b7;\n}\n\n.table-hover .table-danger:hover > td,\n.table-hover .table-danger:hover > th {\n  background-color: #f1b0b7;\n}\n\n.table-light,\n.table-light > th,\n.table-light > td {\n  background-color: #fdfdfe;\n}\n\n.table-light th,\n.table-light td,\n.table-light thead th,\n.table-light tbody + tbody {\n  border-color: #fbfcfc;\n}\n\n.table-hover .table-light:hover {\n  background-color: #ececf6;\n}\n\n.table-hover .table-light:hover > td,\n.table-hover .table-light:hover > th {\n  background-color: #ececf6;\n}\n\n.table-dark,\n.table-dark > th,\n.table-dark > td {\n  background-color: #c6c8ca;\n}\n\n.table-dark th,\n.table-dark td,\n.table-dark thead th,\n.table-dark tbody + tbody {\n  border-color: #95999c;\n}\n\n.table-hover .table-dark:hover {\n  background-color: #b9bbbe;\n}\n\n.table-hover .table-dark:hover > td,\n.table-hover .table-dark:hover > th {\n  background-color: #b9bbbe;\n}\n\n.table-active,\n.table-active > th,\n.table-active > td {\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table-hover .table-active:hover {\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table-hover .table-active:hover > td,\n.table-hover .table-active:hover > th {\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table .thead-dark th {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #454d55;\n}\n\n.table .thead-light th {\n  color: #495057;\n  background-color: #e9ecef;\n  border-color: #dee2e6;\n}\n\n.table-dark {\n  color: #fff;\n  background-color: #343a40;\n}\n\n.table-dark th,\n.table-dark td,\n.table-dark thead th {\n  border-color: #454d55;\n}\n\n.table-dark.table-bordered {\n  border: 0;\n}\n\n.table-dark.table-striped tbody tr:nth-of-type(odd) {\n  background-color: rgba(255, 255, 255, 0.05);\n}\n\n.table-dark.table-hover tbody tr:hover {\n  color: #fff;\n  background-color: rgba(255, 255, 255, 0.075);\n}\n\n@media (max-width: 575.98px) {\n  .table-responsive-sm {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-sm > .table-bordered {\n    border: 0;\n  }\n}\n\n@media (max-width: 767.98px) {\n  .table-responsive-md {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-md > .table-bordered {\n    border: 0;\n  }\n}\n\n@media (max-width: 991.98px) {\n  .table-responsive-lg {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-lg > .table-bordered {\n    border: 0;\n  }\n}\n\n@media (max-width: 1199.98px) {\n  .table-responsive-xl {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-xl > .table-bordered {\n    border: 0;\n  }\n}\n\n.table-responsive {\n  display: block;\n  width: 100%;\n  overflow-x: auto;\n  -webkit-overflow-scrolling: touch;\n}\n\n.table-responsive > .table-bordered {\n  border: 0;\n}\n\n.form-control {\n  display: block;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  padding: 0.375rem 0.75rem;\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n  transition: border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .form-control {\n    transition: none;\n  }\n}\n\n.form-control::-ms-expand {\n  background-color: transparent;\n  border: 0;\n}\n\n.form-control:focus {\n  color: #495057;\n  background-color: #fff;\n  border-color: #80bdff;\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.form-control::-webkit-input-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control::-moz-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control:-ms-input-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control::-ms-input-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control::placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control:disabled, .form-control[readonly] {\n  background-color: #e9ecef;\n  opacity: 1;\n}\n\nselect.form-control:focus::-ms-value {\n  color: #495057;\n  background-color: #fff;\n}\n\n.form-control-file,\n.form-control-range {\n  display: block;\n  width: 100%;\n}\n\n.col-form-label {\n  padding-top: calc(0.375rem + 1px);\n  padding-bottom: calc(0.375rem + 1px);\n  margin-bottom: 0;\n  font-size: inherit;\n  line-height: 1.5;\n}\n\n.col-form-label-lg {\n  padding-top: calc(0.5rem + 1px);\n  padding-bottom: calc(0.5rem + 1px);\n  font-size: 1.25rem;\n  line-height: 1.5;\n}\n\n.col-form-label-sm {\n  padding-top: calc(0.25rem + 1px);\n  padding-bottom: calc(0.25rem + 1px);\n  font-size: 0.875rem;\n  line-height: 1.5;\n}\n\n.form-control-plaintext {\n  display: block;\n  width: 100%;\n  padding-top: 0.375rem;\n  padding-bottom: 0.375rem;\n  margin-bottom: 0;\n  line-height: 1.5;\n  color: #212529;\n  background-color: transparent;\n  border: solid transparent;\n  border-width: 1px 0;\n}\n\n.form-control-plaintext.form-control-sm, .form-control-plaintext.form-control-lg {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.form-control-sm {\n  height: calc(1.5em + 0.5rem + 2px);\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  border-radius: 0.2rem;\n}\n\n.form-control-lg {\n  height: calc(1.5em + 1rem + 2px);\n  padding: 0.5rem 1rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n  border-radius: 0.3rem;\n}\n\nselect.form-control[size], select.form-control[multiple] {\n  height: auto;\n}\n\ntextarea.form-control {\n  height: auto;\n}\n\n.form-group {\n  margin-bottom: 1rem;\n}\n\n.form-text {\n  display: block;\n  margin-top: 0.25rem;\n}\n\n.form-row {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  margin-right: -5px;\n  margin-left: -5px;\n}\n\n.form-row > .col,\n.form-row > [class*=\"col-\"] {\n  padding-right: 5px;\n  padding-left: 5px;\n}\n\n.form-check {\n  position: relative;\n  display: block;\n  padding-left: 1.25rem;\n}\n\n.form-check-input {\n  position: absolute;\n  margin-top: 0.3rem;\n  margin-left: -1.25rem;\n}\n\n.form-check-input:disabled ~ .form-check-label {\n  color: #6c757d;\n}\n\n.form-check-label {\n  margin-bottom: 0;\n}\n\n.form-check-inline {\n  display: -ms-inline-flexbox;\n  display: inline-flex;\n  -ms-flex-align: center;\n  align-items: center;\n  padding-left: 0;\n  margin-right: 0.75rem;\n}\n\n.form-check-inline .form-check-input {\n  position: static;\n  margin-top: 0;\n  margin-right: 0.3125rem;\n  margin-left: 0;\n}\n\n.valid-feedback {\n  display: none;\n  width: 100%;\n  margin-top: 0.25rem;\n  font-size: 80%;\n  color: #28a745;\n}\n\n.valid-tooltip {\n  position: absolute;\n  top: 100%;\n  z-index: 5;\n  display: none;\n  max-width: 100%;\n  padding: 0.25rem 0.5rem;\n  margin-top: .1rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  color: #fff;\n  background-color: rgba(40, 167, 69, 0.9);\n  border-radius: 0.25rem;\n}\n\n.was-validated .form-control:valid, .form-control.is-valid {\n  border-color: #28a745;\n  padding-right: calc(1.5em + 0.75rem);\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 8 8'%3e%3cpath fill='%2328a745' d='M2.3 6.73L.6 4.53c-.4-1.04.46-1.4 1.1-.8l1.1 1.4 3.4-3.8c.6-.63 1.6-.27 1.2.7l-4 4.6c-.43.5-.8.4-1.1.1z'/%3e%3c/svg%3e\");\n  background-repeat: no-repeat;\n  background-position: center right calc(0.375em + 0.1875rem);\n  background-size: calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .form-control:valid:focus, .form-control.is-valid:focus {\n  border-color: #28a745;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.was-validated .form-control:valid ~ .valid-feedback,\n.was-validated .form-control:valid ~ .valid-tooltip, .form-control.is-valid ~ .valid-feedback,\n.form-control.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated textarea.form-control:valid, textarea.form-control.is-valid {\n  padding-right: calc(1.5em + 0.75rem);\n  background-position: top calc(0.375em + 0.1875rem) right calc(0.375em + 0.1875rem);\n}\n\n.was-validated .custom-select:valid, .custom-select.is-valid {\n  border-color: #28a745;\n  padding-right: calc((1em + 0.75rem) * 3 / 4 + 1.75rem);\n  background: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e\") no-repeat right 0.75rem center/8px 10px, url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 8 8'%3e%3cpath fill='%2328a745' d='M2.3 6.73L.6 4.53c-.4-1.04.46-1.4 1.1-.8l1.1 1.4 3.4-3.8c.6-.63 1.6-.27 1.2.7l-4 4.6c-.43.5-.8.4-1.1.1z'/%3e%3c/svg%3e\") #fff no-repeat center right 1.75rem/calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .custom-select:valid:focus, .custom-select.is-valid:focus {\n  border-color: #28a745;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.was-validated .custom-select:valid ~ .valid-feedback,\n.was-validated .custom-select:valid ~ .valid-tooltip, .custom-select.is-valid ~ .valid-feedback,\n.custom-select.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .form-control-file:valid ~ .valid-feedback,\n.was-validated .form-control-file:valid ~ .valid-tooltip, .form-control-file.is-valid ~ .valid-feedback,\n.form-control-file.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .form-check-input:valid ~ .form-check-label, .form-check-input.is-valid ~ .form-check-label {\n  color: #28a745;\n}\n\n.was-validated .form-check-input:valid ~ .valid-feedback,\n.was-validated .form-check-input:valid ~ .valid-tooltip, .form-check-input.is-valid ~ .valid-feedback,\n.form-check-input.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:valid ~ .custom-control-label, .custom-control-input.is-valid ~ .custom-control-label {\n  color: #28a745;\n}\n\n.was-validated .custom-control-input:valid ~ .custom-control-label::before, .custom-control-input.is-valid ~ .custom-control-label::before {\n  border-color: #28a745;\n}\n\n.was-validated .custom-control-input:valid ~ .valid-feedback,\n.was-validated .custom-control-input:valid ~ .valid-tooltip, .custom-control-input.is-valid ~ .valid-feedback,\n.custom-control-input.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:valid:checked ~ .custom-control-label::before, .custom-control-input.is-valid:checked ~ .custom-control-label::before {\n  border-color: #34ce57;\n  background-color: #34ce57;\n}\n\n.was-validated .custom-control-input:valid:focus ~ .custom-control-label::before, .custom-control-input.is-valid:focus ~ .custom-control-label::before {\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.was-validated .custom-control-input:valid:focus:not(:checked) ~ .custom-control-label::before, .custom-control-input.is-valid:focus:not(:checked) ~ .custom-control-label::before {\n  border-color: #28a745;\n}\n\n.was-validated .custom-file-input:valid ~ .custom-file-label, .custom-file-input.is-valid ~ .custom-file-label {\n  border-color: #28a745;\n}\n\n.was-validated .custom-file-input:valid ~ .valid-feedback,\n.was-validated .custom-file-input:valid ~ .valid-tooltip, .custom-file-input.is-valid ~ .valid-feedback,\n.custom-file-input.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-file-input:valid:focus ~ .custom-file-label, .custom-file-input.is-valid:focus ~ .custom-file-label {\n  border-color: #28a745;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.invalid-feedback {\n  display: none;\n  width: 100%;\n  margin-top: 0.25rem;\n  font-size: 80%;\n  color: #dc3545;\n}\n\n.invalid-tooltip {\n  position: absolute;\n  top: 100%;\n  z-index: 5;\n  display: none;\n  max-width: 100%;\n  padding: 0.25rem 0.5rem;\n  margin-top: .1rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  color: #fff;\n  background-color: rgba(220, 53, 69, 0.9);\n  border-radius: 0.25rem;\n}\n\n.was-validated .form-control:invalid, .form-control.is-invalid {\n  border-color: #dc3545;\n  padding-right: calc(1.5em + 0.75rem);\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23dc3545' viewBox='-2 -2 7 7'%3e%3cpath stroke='%23dc3545' d='M0 0l3 3m0-3L0 3'/%3e%3ccircle r='.5'/%3e%3ccircle cx='3' r='.5'/%3e%3ccircle cy='3' r='.5'/%3e%3ccircle cx='3' cy='3' r='.5'/%3e%3c/svg%3E\");\n  background-repeat: no-repeat;\n  background-position: center right calc(0.375em + 0.1875rem);\n  background-size: calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .form-control:invalid:focus, .form-control.is-invalid:focus {\n  border-color: #dc3545;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.was-validated .form-control:invalid ~ .invalid-feedback,\n.was-validated .form-control:invalid ~ .invalid-tooltip, .form-control.is-invalid ~ .invalid-feedback,\n.form-control.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated textarea.form-control:invalid, textarea.form-control.is-invalid {\n  padding-right: calc(1.5em + 0.75rem);\n  background-position: top calc(0.375em + 0.1875rem) right calc(0.375em + 0.1875rem);\n}\n\n.was-validated .custom-select:invalid, .custom-select.is-invalid {\n  border-color: #dc3545;\n  padding-right: calc((1em + 0.75rem) * 3 / 4 + 1.75rem);\n  background: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e\") no-repeat right 0.75rem center/8px 10px, url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23dc3545' viewBox='-2 -2 7 7'%3e%3cpath stroke='%23dc3545' d='M0 0l3 3m0-3L0 3'/%3e%3ccircle r='.5'/%3e%3ccircle cx='3' r='.5'/%3e%3ccircle cy='3' r='.5'/%3e%3ccircle cx='3' cy='3' r='.5'/%3e%3c/svg%3E\") #fff no-repeat center right 1.75rem/calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .custom-select:invalid:focus, .custom-select.is-invalid:focus {\n  border-color: #dc3545;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.was-validated .custom-select:invalid ~ .invalid-feedback,\n.was-validated .custom-select:invalid ~ .invalid-tooltip, .custom-select.is-invalid ~ .invalid-feedback,\n.custom-select.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .form-control-file:invalid ~ .invalid-feedback,\n.was-validated .form-control-file:invalid ~ .invalid-tooltip, .form-control-file.is-invalid ~ .invalid-feedback,\n.form-control-file.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .form-check-input:invalid ~ .form-check-label, .form-check-input.is-invalid ~ .form-check-label {\n  color: #dc3545;\n}\n\n.was-validated .form-check-input:invalid ~ .invalid-feedback,\n.was-validated .form-check-input:invalid ~ .invalid-tooltip, .form-check-input.is-invalid ~ .invalid-feedback,\n.form-check-input.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:invalid ~ .custom-control-label, .custom-control-input.is-invalid ~ .custom-control-label {\n  color: #dc3545;\n}\n\n.was-validated .custom-control-input:invalid ~ .custom-control-label::before, .custom-control-input.is-invalid ~ .custom-control-label::before {\n  border-color: #dc3545;\n}\n\n.was-validated .custom-control-input:invalid ~ .invalid-feedback,\n.was-validated .custom-control-input:invalid ~ .invalid-tooltip, .custom-control-input.is-invalid ~ .invalid-feedback,\n.custom-control-input.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:invalid:checked ~ .custom-control-label::before, .custom-control-input.is-invalid:checked ~ .custom-control-label::before {\n  border-color: #e4606d;\n  background-color: #e4606d;\n}\n\n.was-validated .custom-control-input:invalid:focus ~ .custom-control-label::before, .custom-control-input.is-invalid:focus ~ .custom-control-label::before {\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.was-validated .custom-control-input:invalid:focus:not(:checked) ~ .custom-control-label::before, .custom-control-input.is-invalid:focus:not(:checked) ~ .custom-control-label::before {\n  border-color: #dc3545;\n}\n\n.was-validated .custom-file-input:invalid ~ .custom-file-label, .custom-file-input.is-invalid ~ .custom-file-label {\n  border-color: #dc3545;\n}\n\n.was-validated .custom-file-input:invalid ~ .invalid-feedback,\n.was-validated .custom-file-input:invalid ~ .invalid-tooltip, .custom-file-input.is-invalid ~ .invalid-feedback,\n.custom-file-input.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-file-input:invalid:focus ~ .custom-file-label, .custom-file-input.is-invalid:focus ~ .custom-file-label {\n  border-color: #dc3545;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.form-inline {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-flow: row wrap;\n  flex-flow: row wrap;\n  -ms-flex-align: center;\n  align-items: center;\n}\n\n.form-inline .form-check {\n  width: 100%;\n}\n\n@media (min-width: 576px) {\n  .form-inline label {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex-align: center;\n    align-items: center;\n    -ms-flex-pack: center;\n    justify-content: center;\n    margin-bottom: 0;\n  }\n  .form-inline .form-group {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    -ms-flex-flow: row wrap;\n    flex-flow: row wrap;\n    -ms-flex-align: center;\n    align-items: center;\n    margin-bottom: 0;\n  }\n  .form-inline .form-control {\n    display: inline-block;\n    width: auto;\n    vertical-align: middle;\n  }\n  .form-inline .form-control-plaintext {\n    display: inline-block;\n  }\n  .form-inline .input-group,\n  .form-inline .custom-select {\n    width: auto;\n  }\n  .form-inline .form-check {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex-align: center;\n    align-items: center;\n    -ms-flex-pack: center;\n    justify-content: center;\n    width: auto;\n    padding-left: 0;\n  }\n  .form-inline .form-check-input {\n    position: relative;\n    -ms-flex-negative: 0;\n    flex-shrink: 0;\n    margin-top: 0;\n    margin-right: 0.25rem;\n    margin-left: 0;\n  }\n  .form-inline .custom-control {\n    -ms-flex-align: center;\n    align-items: center;\n    -ms-flex-pack: center;\n    justify-content: center;\n  }\n  .form-inline .custom-control-label {\n    margin-bottom: 0;\n  }\n}\n\n.btn {\n  display: inline-block;\n  font-weight: 400;\n  color: #212529;\n  text-align: center;\n  vertical-align: middle;\n  -webkit-user-select: none;\n  -moz-user-select: none;\n  -ms-user-select: none;\n  user-select: none;\n  background-color: transparent;\n  border: 1px solid transparent;\n  padding: 0.375rem 0.75rem;\n  font-size: 1rem;\n  line-height: 1.5;\n  border-radius: 0.25rem;\n  transition: color 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .btn {\n    transition: none;\n  }\n}\n\n.btn:hover {\n  color: #212529;\n  text-decoration: none;\n}\n\n.btn:focus, .btn.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.btn.disabled, .btn:disabled {\n  opacity: 0.65;\n}\n\na.btn.disabled,\nfieldset:disabled a.btn {\n  pointer-events: none;\n}\n\n.btn-primary {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-primary:hover {\n  color: #fff;\n  background-color: #0069d9;\n  border-color: #0062cc;\n}\n\n.btn-primary:focus, .btn-primary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(38, 143, 255, 0.5);\n}\n\n.btn-primary.disabled, .btn-primary:disabled {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-primary:not(:disabled):not(.disabled):active, .btn-primary:not(:disabled):not(.disabled).active,\n.show > .btn-primary.dropdown-toggle {\n  color: #fff;\n  background-color: #0062cc;\n  border-color: #005cbf;\n}\n\n.btn-primary:not(:disabled):not(.disabled):active:focus, .btn-primary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-primary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(38, 143, 255, 0.5);\n}\n\n.btn-secondary {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-secondary:hover {\n  color: #fff;\n  background-color: #5a6268;\n  border-color: #545b62;\n}\n\n.btn-secondary:focus, .btn-secondary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(130, 138, 145, 0.5);\n}\n\n.btn-secondary.disabled, .btn-secondary:disabled {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-secondary:not(:disabled):not(.disabled):active, .btn-secondary:not(:disabled):not(.disabled).active,\n.show > .btn-secondary.dropdown-toggle {\n  color: #fff;\n  background-color: #545b62;\n  border-color: #4e555b;\n}\n\n.btn-secondary:not(:disabled):not(.disabled):active:focus, .btn-secondary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-secondary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(130, 138, 145, 0.5);\n}\n\n.btn-success {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-success:hover {\n  color: #fff;\n  background-color: #218838;\n  border-color: #1e7e34;\n}\n\n.btn-success:focus, .btn-success.focus {\n  box-shadow: 0 0 0 0.2rem rgba(72, 180, 97, 0.5);\n}\n\n.btn-success.disabled, .btn-success:disabled {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-success:not(:disabled):not(.disabled):active, .btn-success:not(:disabled):not(.disabled).active,\n.show > .btn-success.dropdown-toggle {\n  color: #fff;\n  background-color: #1e7e34;\n  border-color: #1c7430;\n}\n\n.btn-success:not(:disabled):not(.disabled):active:focus, .btn-success:not(:disabled):not(.disabled).active:focus,\n.show > .btn-success.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(72, 180, 97, 0.5);\n}\n\n.btn-info {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-info:hover {\n  color: #fff;\n  background-color: #138496;\n  border-color: #117a8b;\n}\n\n.btn-info:focus, .btn-info.focus {\n  box-shadow: 0 0 0 0.2rem rgba(58, 176, 195, 0.5);\n}\n\n.btn-info.disabled, .btn-info:disabled {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-info:not(:disabled):not(.disabled):active, .btn-info:not(:disabled):not(.disabled).active,\n.show > .btn-info.dropdown-toggle {\n  color: #fff;\n  background-color: #117a8b;\n  border-color: #10707f;\n}\n\n.btn-info:not(:disabled):not(.disabled):active:focus, .btn-info:not(:disabled):not(.disabled).active:focus,\n.show > .btn-info.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(58, 176, 195, 0.5);\n}\n\n.btn-warning {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-warning:hover {\n  color: #212529;\n  background-color: #e0a800;\n  border-color: #d39e00;\n}\n\n.btn-warning:focus, .btn-warning.focus {\n  box-shadow: 0 0 0 0.2rem rgba(222, 170, 12, 0.5);\n}\n\n.btn-warning.disabled, .btn-warning:disabled {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-warning:not(:disabled):not(.disabled):active, .btn-warning:not(:disabled):not(.disabled).active,\n.show > .btn-warning.dropdown-toggle {\n  color: #212529;\n  background-color: #d39e00;\n  border-color: #c69500;\n}\n\n.btn-warning:not(:disabled):not(.disabled):active:focus, .btn-warning:not(:disabled):not(.disabled).active:focus,\n.show > .btn-warning.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(222, 170, 12, 0.5);\n}\n\n.btn-danger {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-danger:hover {\n  color: #fff;\n  background-color: #c82333;\n  border-color: #bd2130;\n}\n\n.btn-danger:focus, .btn-danger.focus {\n  box-shadow: 0 0 0 0.2rem rgba(225, 83, 97, 0.5);\n}\n\n.btn-danger.disabled, .btn-danger:disabled {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-danger:not(:disabled):not(.disabled):active, .btn-danger:not(:disabled):not(.disabled).active,\n.show > .btn-danger.dropdown-toggle {\n  color: #fff;\n  background-color: #bd2130;\n  border-color: #b21f2d;\n}\n\n.btn-danger:not(:disabled):not(.disabled):active:focus, .btn-danger:not(:disabled):not(.disabled).active:focus,\n.show > .btn-danger.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(225, 83, 97, 0.5);\n}\n\n.btn-light {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-light:hover {\n  color: #212529;\n  background-color: #e2e6ea;\n  border-color: #dae0e5;\n}\n\n.btn-light:focus, .btn-light.focus {\n  box-shadow: 0 0 0 0.2rem rgba(216, 217, 219, 0.5);\n}\n\n.btn-light.disabled, .btn-light:disabled {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-light:not(:disabled):not(.disabled):active, .btn-light:not(:disabled):not(.disabled).active,\n.show > .btn-light.dropdown-toggle {\n  color: #212529;\n  background-color: #dae0e5;\n  border-color: #d3d9df;\n}\n\n.btn-light:not(:disabled):not(.disabled):active:focus, .btn-light:not(:disabled):not(.disabled).active:focus,\n.show > .btn-light.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(216, 217, 219, 0.5);\n}\n\n.btn-dark {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-dark:hover {\n  color: #fff;\n  background-color: #23272b;\n  border-color: #1d2124;\n}\n\n.btn-dark:focus, .btn-dark.focus {\n  box-shadow: 0 0 0 0.2rem rgba(82, 88, 93, 0.5);\n}\n\n.btn-dark.disabled, .btn-dark:disabled {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-dark:not(:disabled):not(.disabled):active, .btn-dark:not(:disabled):not(.disabled).active,\n.show > .btn-dark.dropdown-toggle {\n  color: #fff;\n  background-color: #1d2124;\n  border-color: #171a1d;\n}\n\n.btn-dark:not(:disabled):not(.disabled):active:focus, .btn-dark:not(:disabled):not(.disabled).active:focus,\n.show > .btn-dark.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(82, 88, 93, 0.5);\n}\n\n.btn-outline-primary {\n  color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-outline-primary:hover {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-outline-primary:focus, .btn-outline-primary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.5);\n}\n\n.btn-outline-primary.disabled, .btn-outline-primary:disabled {\n  color: #007bff;\n  background-color: transparent;\n}\n\n.btn-outline-primary:not(:disabled):not(.disabled):active, .btn-outline-primary:not(:disabled):not(.disabled).active,\n.show > .btn-outline-primary.dropdown-toggle {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-outline-primary:not(:disabled):not(.disabled):active:focus, .btn-outline-primary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-primary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.5);\n}\n\n.btn-outline-secondary {\n  color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-outline-secondary:hover {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-outline-secondary:focus, .btn-outline-secondary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(108, 117, 125, 0.5);\n}\n\n.btn-outline-secondary.disabled, .btn-outline-secondary:disabled {\n  color: #6c757d;\n  background-color: transparent;\n}\n\n.btn-outline-secondary:not(:disabled):not(.disabled):active, .btn-outline-secondary:not(:disabled):not(.disabled).active,\n.show > .btn-outline-secondary.dropdown-toggle {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-outline-secondary:not(:disabled):not(.disabled):active:focus, .btn-outline-secondary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-secondary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(108, 117, 125, 0.5);\n}\n\n.btn-outline-success {\n  color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-outline-success:hover {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-outline-success:focus, .btn-outline-success.focus {\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.5);\n}\n\n.btn-outline-success.disabled, .btn-outline-success:disabled {\n  color: #28a745;\n  background-color: transparent;\n}\n\n.btn-outline-success:not(:disabled):not(.disabled):active, .btn-outline-success:not(:disabled):not(.disabled).active,\n.show > .btn-outline-success.dropdown-toggle {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-outline-success:not(:disabled):not(.disabled):active:focus, .btn-outline-success:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-success.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.5);\n}\n\n.btn-outline-info {\n  color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-outline-info:hover {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-outline-info:focus, .btn-outline-info.focus {\n  box-shadow: 0 0 0 0.2rem rgba(23, 162, 184, 0.5);\n}\n\n.btn-outline-info.disabled, .btn-outline-info:disabled {\n  color: #17a2b8;\n  background-color: transparent;\n}\n\n.btn-outline-info:not(:disabled):not(.disabled):active, .btn-outline-info:not(:disabled):not(.disabled).active,\n.show > .btn-outline-info.dropdown-toggle {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-outline-info:not(:disabled):not(.disabled):active:focus, .btn-outline-info:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-info.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(23, 162, 184, 0.5);\n}\n\n.btn-outline-warning {\n  color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-outline-warning:hover {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-outline-warning:focus, .btn-outline-warning.focus {\n  box-shadow: 0 0 0 0.2rem rgba(255, 193, 7, 0.5);\n}\n\n.btn-outline-warning.disabled, .btn-outline-warning:disabled {\n  color: #ffc107;\n  background-color: transparent;\n}\n\n.btn-outline-warning:not(:disabled):not(.disabled):active, .btn-outline-warning:not(:disabled):not(.disabled).active,\n.show > .btn-outline-warning.dropdown-toggle {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-outline-warning:not(:disabled):not(.disabled):active:focus, .btn-outline-warning:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-warning.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(255, 193, 7, 0.5);\n}\n\n.btn-outline-danger {\n  color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-outline-danger:hover {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-outline-danger:focus, .btn-outline-danger.focus {\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.5);\n}\n\n.btn-outline-danger.disabled, .btn-outline-danger:disabled {\n  color: #dc3545;\n  background-color: transparent;\n}\n\n.btn-outline-danger:not(:disabled):not(.disabled):active, .btn-outline-danger:not(:disabled):not(.disabled).active,\n.show > .btn-outline-danger.dropdown-toggle {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-outline-danger:not(:disabled):not(.disabled):active:focus, .btn-outline-danger:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-danger.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.5);\n}\n\n.btn-outline-light {\n  color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-outline-light:hover {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-outline-light:focus, .btn-outline-light.focus {\n  box-shadow: 0 0 0 0.2rem rgba(248, 249, 250, 0.5);\n}\n\n.btn-outline-light.disabled, .btn-outline-light:disabled {\n  color: #f8f9fa;\n  background-color: transparent;\n}\n\n.btn-outline-light:not(:disabled):not(.disabled):active, .btn-outline-light:not(:disabled):not(.disabled).active,\n.show > .btn-outline-light.dropdown-toggle {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-outline-light:not(:disabled):not(.disabled):active:focus, .btn-outline-light:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-light.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(248, 249, 250, 0.5);\n}\n\n.btn-outline-dark {\n  color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-outline-dark:hover {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-outline-dark:focus, .btn-outline-dark.focus {\n  box-shadow: 0 0 0 0.2rem rgba(52, 58, 64, 0.5);\n}\n\n.btn-outline-dark.disabled, .btn-outline-dark:disabled {\n  color: #343a40;\n  background-color: transparent;\n}\n\n.btn-outline-dark:not(:disabled):not(.disabled):active, .btn-outline-dark:not(:disabled):not(.disabled).active,\n.show > .btn-outline-dark.dropdown-toggle {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-outline-dark:not(:disabled):not(.disabled):active:focus, .btn-outline-dark:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-dark.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(52, 58, 64, 0.5);\n}\n\n.btn-link {\n  font-weight: 400;\n  color: #007bff;\n  text-decoration: none;\n}\n\n.btn-link:hover {\n  color: #0056b3;\n  text-decoration: underline;\n}\n\n.btn-link:focus, .btn-link.focus {\n  text-decoration: underline;\n  box-shadow: none;\n}\n\n.btn-link:disabled, .btn-link.disabled {\n  color: #6c757d;\n  pointer-events: none;\n}\n\n.btn-lg, .btn-group-lg > .btn {\n  padding: 0.5rem 1rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n  border-radius: 0.3rem;\n}\n\n.btn-sm, .btn-group-sm > .btn {\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  border-radius: 0.2rem;\n}\n\n.btn-block {\n  display: block;\n  width: 100%;\n}\n\n.btn-block + .btn-block {\n  margin-top: 0.5rem;\n}\n\ninput[type=\"submit\"].btn-block,\ninput[type=\"reset\"].btn-block,\ninput[type=\"button\"].btn-block {\n  width: 100%;\n}\n\n.fade {\n  transition: opacity 0.15s linear;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .fade {\n    transition: none;\n  }\n}\n\n.fade:not(.show) {\n  opacity: 0;\n}\n\n.collapse:not(.show) {\n  display: none;\n}\n\n.collapsing {\n  position: relative;\n  height: 0;\n  overflow: hidden;\n  transition: height 0.35s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .collapsing {\n    transition: none;\n  }\n}\n\n.dropup,\n.dropright,\n.dropdown,\n.dropleft {\n  position: relative;\n}\n\n.dropdown-toggle {\n  white-space: nowrap;\n}\n\n.dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0.3em solid;\n  border-right: 0.3em solid transparent;\n  border-bottom: 0;\n  border-left: 0.3em solid transparent;\n}\n\n.dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropdown-menu {\n  position: absolute;\n  top: 100%;\n  left: 0;\n  z-index: 1000;\n  display: none;\n  float: left;\n  min-width: 10rem;\n  padding: 0.5rem 0;\n  margin: 0.125rem 0 0;\n  font-size: 1rem;\n  color: #212529;\n  text-align: left;\n  list-style: none;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.15);\n  border-radius: 0.25rem;\n}\n\n.dropdown-menu-left {\n  right: auto;\n  left: 0;\n}\n\n.dropdown-menu-right {\n  right: 0;\n  left: auto;\n}\n\n@media (min-width: 576px) {\n  .dropdown-menu-sm-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-sm-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n@media (min-width: 768px) {\n  .dropdown-menu-md-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-md-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n@media (min-width: 992px) {\n  .dropdown-menu-lg-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-lg-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n@media (min-width: 1200px) {\n  .dropdown-menu-xl-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-xl-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n.dropup .dropdown-menu {\n  top: auto;\n  bottom: 100%;\n  margin-top: 0;\n  margin-bottom: 0.125rem;\n}\n\n.dropup .dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0;\n  border-right: 0.3em solid transparent;\n  border-bottom: 0.3em solid;\n  border-left: 0.3em solid transparent;\n}\n\n.dropup .dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropright .dropdown-menu {\n  top: 0;\n  right: auto;\n  left: 100%;\n  margin-top: 0;\n  margin-left: 0.125rem;\n}\n\n.dropright .dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0.3em solid transparent;\n  border-right: 0;\n  border-bottom: 0.3em solid transparent;\n  border-left: 0.3em solid;\n}\n\n.dropright .dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropright .dropdown-toggle::after {\n  vertical-align: 0;\n}\n\n.dropleft .dropdown-menu {\n  top: 0;\n  right: 100%;\n  left: auto;\n  margin-top: 0;\n  margin-right: 0.125rem;\n}\n\n.dropleft .dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n}\n\n.dropleft .dropdown-toggle::after {\n  display: none;\n}\n\n.dropleft .dropdown-toggle::before {\n  display: inline-block;\n  margin-right: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0.3em solid transparent;\n  border-right: 0.3em solid;\n  border-bottom: 0.3em solid transparent;\n}\n\n.dropleft .dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropleft .dropdown-toggle::before {\n  vertical-align: 0;\n}\n\n.dropdown-menu[x-placement^=\"top\"], .dropdown-menu[x-placement^=\"right\"], .dropdown-menu[x-placement^=\"bottom\"], .dropdown-menu[x-placement^=\"left\"] {\n  right: auto;\n  bottom: auto;\n}\n\n.dropdown-divider {\n  height: 0;\n  margin: 0.5rem 0;\n  overflow: hidden;\n  border-top: 1px solid #e9ecef;\n}\n\n.dropdown-item {\n  display: block;\n  width: 100%;\n  padding: 0.25rem 1.5rem;\n  clear: both;\n  font-weight: 400;\n  color: #212529;\n  text-align: inherit;\n  white-space: nowrap;\n  background-color: transparent;\n  border: 0;\n}\n\n.dropdown-item:hover, .dropdown-item:focus {\n  color: #16181b;\n  text-decoration: none;\n  background-color: #f8f9fa;\n}\n\n.dropdown-item.active, .dropdown-item:active {\n  color: #fff;\n  text-decoration: none;\n  background-color: #007bff;\n}\n\n.dropdown-item.disabled, .dropdown-item:disabled {\n  color: #6c757d;\n  pointer-events: none;\n  background-color: transparent;\n}\n\n.dropdown-menu.show {\n  display: block;\n}\n\n.dropdown-header {\n  display: block;\n  padding: 0.5rem 1.5rem;\n  margin-bottom: 0;\n  font-size: 0.875rem;\n  color: #6c757d;\n  white-space: nowrap;\n}\n\n.dropdown-item-text {\n  display: block;\n  padding: 0.25rem 1.5rem;\n  color: #212529;\n}\n\n.btn-group,\n.btn-group-vertical {\n  position: relative;\n  display: -ms-inline-flexbox;\n  display: inline-flex;\n  vertical-align: middle;\n}\n\n.btn-group > .btn,\n.btn-group-vertical > .btn {\n  position: relative;\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n}\n\n.btn-group > .btn:hover,\n.btn-group-vertical > .btn:hover {\n  z-index: 1;\n}\n\n.btn-group > .btn:focus, .btn-group > .btn:active, .btn-group > .btn.active,\n.btn-group-vertical > .btn:focus,\n.btn-group-vertical > .btn:active,\n.btn-group-vertical > .btn.active {\n  z-index: 1;\n}\n\n.btn-toolbar {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-pack: start;\n  justify-content: flex-start;\n}\n\n.btn-toolbar .input-group {\n  width: auto;\n}\n\n.btn-group > .btn:not(:first-child),\n.btn-group > .btn-group:not(:first-child) {\n  margin-left: -1px;\n}\n\n.btn-group > .btn:not(:last-child):not(.dropdown-toggle),\n.btn-group > .btn-group:not(:last-child) > .btn {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.btn-group > .btn:not(:first-child),\n.btn-group > .btn-group:not(:first-child) > .btn {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.dropdown-toggle-split {\n  padding-right: 0.5625rem;\n  padding-left: 0.5625rem;\n}\n\n.dropdown-toggle-split::after,\n.dropup .dropdown-toggle-split::after,\n.dropright .dropdown-toggle-split::after {\n  margin-left: 0;\n}\n\n.dropleft .dropdown-toggle-split::before {\n  margin-right: 0;\n}\n\n.btn-sm + .dropdown-toggle-split, .btn-group-sm > .btn + .dropdown-toggle-split {\n  padding-right: 0.375rem;\n  padding-left: 0.375rem;\n}\n\n.btn-lg + .dropdown-toggle-split, .btn-group-lg > .btn + .dropdown-toggle-split {\n  padding-right: 0.75rem;\n  padding-left: 0.75rem;\n}\n\n.btn-group-vertical {\n  -ms-flex-direction: column;\n  flex-direction: column;\n  -ms-flex-align: start;\n  align-items: flex-start;\n  -ms-flex-pack: center;\n  justify-content: center;\n}\n\n.btn-group-vertical > .btn,\n.btn-group-vertical > .btn-group {\n  width: 100%;\n}\n\n.btn-group-vertical > .btn:not(:first-child),\n.btn-group-vertical > .btn-group:not(:first-child) {\n  margin-top: -1px;\n}\n\n.btn-group-vertical > .btn:not(:last-child):not(.dropdown-toggle),\n.btn-group-vertical > .btn-group:not(:last-child) > .btn {\n  border-bottom-right-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.btn-group-vertical > .btn:not(:first-child),\n.btn-group-vertical > .btn-group:not(:first-child) > .btn {\n  border-top-left-radius: 0;\n  border-top-right-radius: 0;\n}\n\n.btn-group-toggle > .btn,\n.btn-group-toggle > .btn-group > .btn {\n  margin-bottom: 0;\n}\n\n.btn-group-toggle > .btn input[type=\"radio\"],\n.btn-group-toggle > .btn input[type=\"checkbox\"],\n.btn-group-toggle > .btn-group > .btn input[type=\"radio\"],\n.btn-group-toggle > .btn-group > .btn input[type=\"checkbox\"] {\n  position: absolute;\n  clip: rect(0, 0, 0, 0);\n  pointer-events: none;\n}\n\n.input-group {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-align: stretch;\n  align-items: stretch;\n  width: 100%;\n}\n\n.input-group > .form-control,\n.input-group > .form-control-plaintext,\n.input-group > .custom-select,\n.input-group > .custom-file {\n  position: relative;\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  width: 1%;\n  margin-bottom: 0;\n}\n\n.input-group > .form-control + .form-control,\n.input-group > .form-control + .custom-select,\n.input-group > .form-control + .custom-file,\n.input-group > .form-control-plaintext + .form-control,\n.input-group > .form-control-plaintext + .custom-select,\n.input-group > .form-control-plaintext + .custom-file,\n.input-group > .custom-select + .form-control,\n.input-group > .custom-select + .custom-select,\n.input-group > .custom-select + .custom-file,\n.input-group > .custom-file + .form-control,\n.input-group > .custom-file + .custom-select,\n.input-group > .custom-file + .custom-file {\n  margin-left: -1px;\n}\n\n.input-group > .form-control:focus,\n.input-group > .custom-select:focus,\n.input-group > .custom-file .custom-file-input:focus ~ .custom-file-label {\n  z-index: 3;\n}\n\n.input-group > .custom-file .custom-file-input:focus {\n  z-index: 4;\n}\n\n.input-group > .form-control:not(:last-child),\n.input-group > .custom-select:not(:last-child) {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.input-group > .form-control:not(:first-child),\n.input-group > .custom-select:not(:first-child) {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.input-group > .custom-file {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n}\n\n.input-group > .custom-file:not(:last-child) .custom-file-label,\n.input-group > .custom-file:not(:last-child) .custom-file-label::after {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.input-group > .custom-file:not(:first-child) .custom-file-label {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.input-group-prepend,\n.input-group-append {\n  display: -ms-flexbox;\n  display: flex;\n}\n\n.input-group-prepend .btn,\n.input-group-append .btn {\n  position: relative;\n  z-index: 2;\n}\n\n.input-group-prepend .btn:focus,\n.input-group-append .btn:focus {\n  z-index: 3;\n}\n\n.input-group-prepend .btn + .btn,\n.input-group-prepend .btn + .input-group-text,\n.input-group-prepend .input-group-text + .input-group-text,\n.input-group-prepend .input-group-text + .btn,\n.input-group-append .btn + .btn,\n.input-group-append .btn + .input-group-text,\n.input-group-append .input-group-text + .input-group-text,\n.input-group-append .input-group-text + .btn {\n  margin-left: -1px;\n}\n\n.input-group-prepend {\n  margin-right: -1px;\n}\n\n.input-group-append {\n  margin-left: -1px;\n}\n\n.input-group-text {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  padding: 0.375rem 0.75rem;\n  margin-bottom: 0;\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  text-align: center;\n  white-space: nowrap;\n  background-color: #e9ecef;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n}\n\n.input-group-text input[type=\"radio\"],\n.input-group-text input[type=\"checkbox\"] {\n  margin-top: 0;\n}\n\n.input-group-lg > .form-control:not(textarea),\n.input-group-lg > .custom-select {\n  height: calc(1.5em + 1rem + 2px);\n}\n\n.input-group-lg > .form-control,\n.input-group-lg > .custom-select,\n.input-group-lg > .input-group-prepend > .input-group-text,\n.input-group-lg > .input-group-append > .input-group-text,\n.input-group-lg > .input-group-prepend > .btn,\n.input-group-lg > .input-group-append > .btn {\n  padding: 0.5rem 1rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n  border-radius: 0.3rem;\n}\n\n.input-group-sm > .form-control:not(textarea),\n.input-group-sm > .custom-select {\n  height: calc(1.5em + 0.5rem + 2px);\n}\n\n.input-group-sm > .form-control,\n.input-group-sm > .custom-select,\n.input-group-sm > .input-group-prepend > .input-group-text,\n.input-group-sm > .input-group-append > .input-group-text,\n.input-group-sm > .input-group-prepend > .btn,\n.input-group-sm > .input-group-append > .btn {\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  border-radius: 0.2rem;\n}\n\n.input-group-lg > .custom-select,\n.input-group-sm > .custom-select {\n  padding-right: 1.75rem;\n}\n\n.input-group > .input-group-prepend > .btn,\n.input-group > .input-group-prepend > .input-group-text,\n.input-group > .input-group-append:not(:last-child) > .btn,\n.input-group > .input-group-append:not(:last-child) > .input-group-text,\n.input-group > .input-group-append:last-child > .btn:not(:last-child):not(.dropdown-toggle),\n.input-group > .input-group-append:last-child > .input-group-text:not(:last-child) {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.input-group > .input-group-append > .btn,\n.input-group > .input-group-append > .input-group-text,\n.input-group > .input-group-prepend:not(:first-child) > .btn,\n.input-group > .input-group-prepend:not(:first-child) > .input-group-text,\n.input-group > .input-group-prepend:first-child > .btn:not(:first-child),\n.input-group > .input-group-prepend:first-child > .input-group-text:not(:first-child) {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.custom-control {\n  position: relative;\n  display: block;\n  min-height: 1.5rem;\n  padding-left: 1.5rem;\n}\n\n.custom-control-inline {\n  display: -ms-inline-flexbox;\n  display: inline-flex;\n  margin-right: 1rem;\n}\n\n.custom-control-input {\n  position: absolute;\n  z-index: -1;\n  opacity: 0;\n}\n\n.custom-control-input:checked ~ .custom-control-label::before {\n  color: #fff;\n  border-color: #007bff;\n  background-color: #007bff;\n}\n\n.custom-control-input:focus ~ .custom-control-label::before {\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-control-input:focus:not(:checked) ~ .custom-control-label::before {\n  border-color: #80bdff;\n}\n\n.custom-control-input:not(:disabled):active ~ .custom-control-label::before {\n  color: #fff;\n  background-color: #b3d7ff;\n  border-color: #b3d7ff;\n}\n\n.custom-control-input:disabled ~ .custom-control-label {\n  color: #6c757d;\n}\n\n.custom-control-input:disabled ~ .custom-control-label::before {\n  background-color: #e9ecef;\n}\n\n.custom-control-label {\n  position: relative;\n  margin-bottom: 0;\n  vertical-align: top;\n}\n\n.custom-control-label::before {\n  position: absolute;\n  top: 0.25rem;\n  left: -1.5rem;\n  display: block;\n  width: 1rem;\n  height: 1rem;\n  pointer-events: none;\n  content: \"\";\n  background-color: #fff;\n  border: #adb5bd solid 1px;\n}\n\n.custom-control-label::after {\n  position: absolute;\n  top: 0.25rem;\n  left: -1.5rem;\n  display: block;\n  width: 1rem;\n  height: 1rem;\n  content: \"\";\n  background: no-repeat 50% / 50% 50%;\n}\n\n.custom-checkbox .custom-control-label::before {\n  border-radius: 0.25rem;\n}\n\n.custom-checkbox .custom-control-input:checked ~ .custom-control-label::after {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 8 8'%3e%3cpath fill='%23fff' d='M6.564.75l-3.59 3.612-1.538-1.55L0 4.26 2.974 7.25 8 2.193z'/%3e%3c/svg%3e\");\n}\n\n.custom-checkbox .custom-control-input:indeterminate ~ .custom-control-label::before {\n  border-color: #007bff;\n  background-color: #007bff;\n}\n\n.custom-checkbox .custom-control-input:indeterminate ~ .custom-control-label::after {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 4'%3e%3cpath stroke='%23fff' d='M0 2h4'/%3e%3c/svg%3e\");\n}\n\n.custom-checkbox .custom-control-input:disabled:checked ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-checkbox .custom-control-input:disabled:indeterminate ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-radio .custom-control-label::before {\n  border-radius: 50%;\n}\n\n.custom-radio .custom-control-input:checked ~ .custom-control-label::after {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='-4 -4 8 8'%3e%3ccircle r='3' fill='%23fff'/%3e%3c/svg%3e\");\n}\n\n.custom-radio .custom-control-input:disabled:checked ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-switch {\n  padding-left: 2.25rem;\n}\n\n.custom-switch .custom-control-label::before {\n  left: -2.25rem;\n  width: 1.75rem;\n  pointer-events: all;\n  border-radius: 0.5rem;\n}\n\n.custom-switch .custom-control-label::after {\n  top: calc(0.25rem + 2px);\n  left: calc(-2.25rem + 2px);\n  width: calc(1rem - 4px);\n  height: calc(1rem - 4px);\n  background-color: #adb5bd;\n  border-radius: 0.5rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out, -webkit-transform 0.15s ease-in-out;\n  transition: transform 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  transition: transform 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out, -webkit-transform 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-switch .custom-control-label::after {\n    transition: none;\n  }\n}\n\n.custom-switch .custom-control-input:checked ~ .custom-control-label::after {\n  background-color: #fff;\n  -webkit-transform: translateX(0.75rem);\n  transform: translateX(0.75rem);\n}\n\n.custom-switch .custom-control-input:disabled:checked ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-select {\n  display: inline-block;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  padding: 0.375rem 1.75rem 0.375rem 0.75rem;\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  vertical-align: middle;\n  background: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e\") no-repeat right 0.75rem center/8px 10px;\n  background-color: #fff;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n  -webkit-appearance: none;\n  -moz-appearance: none;\n  appearance: none;\n}\n\n.custom-select:focus {\n  border-color: #80bdff;\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-select:focus::-ms-value {\n  color: #495057;\n  background-color: #fff;\n}\n\n.custom-select[multiple], .custom-select[size]:not([size=\"1\"]) {\n  height: auto;\n  padding-right: 0.75rem;\n  background-image: none;\n}\n\n.custom-select:disabled {\n  color: #6c757d;\n  background-color: #e9ecef;\n}\n\n.custom-select::-ms-expand {\n  display: none;\n}\n\n.custom-select-sm {\n  height: calc(1.5em + 0.5rem + 2px);\n  padding-top: 0.25rem;\n  padding-bottom: 0.25rem;\n  padding-left: 0.5rem;\n  font-size: 0.875rem;\n}\n\n.custom-select-lg {\n  height: calc(1.5em + 1rem + 2px);\n  padding-top: 0.5rem;\n  padding-bottom: 0.5rem;\n  padding-left: 1rem;\n  font-size: 1.25rem;\n}\n\n.custom-file {\n  position: relative;\n  display: inline-block;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  margin-bottom: 0;\n}\n\n.custom-file-input {\n  position: relative;\n  z-index: 2;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  margin: 0;\n  opacity: 0;\n}\n\n.custom-file-input:focus ~ .custom-file-label {\n  border-color: #80bdff;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-file-input:disabled ~ .custom-file-label {\n  background-color: #e9ecef;\n}\n\n.custom-file-input:lang(en) ~ .custom-file-label::after {\n  content: \"Browse\";\n}\n\n.custom-file-input ~ .custom-file-label[data-browse]::after {\n  content: attr(data-browse);\n}\n\n.custom-file-label {\n  position: absolute;\n  top: 0;\n  right: 0;\n  left: 0;\n  z-index: 1;\n  height: calc(1.5em + 0.75rem + 2px);\n  padding: 0.375rem 0.75rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  background-color: #fff;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n}\n\n.custom-file-label::after {\n  position: absolute;\n  top: 0;\n  right: 0;\n  bottom: 0;\n  z-index: 3;\n  display: block;\n  height: calc(1.5em + 0.75rem);\n  padding: 0.375rem 0.75rem;\n  line-height: 1.5;\n  color: #495057;\n  content: \"Browse\";\n  background-color: #e9ecef;\n  border-left: inherit;\n  border-radius: 0 0.25rem 0.25rem 0;\n}\n\n.custom-range {\n  width: 100%;\n  height: calc(1rem + 0.4rem);\n  padding: 0;\n  background-color: transparent;\n  -webkit-appearance: none;\n  -moz-appearance: none;\n  appearance: none;\n}\n\n.custom-range:focus {\n  outline: none;\n}\n\n.custom-range:focus::-webkit-slider-thumb {\n  box-shadow: 0 0 0 1px #fff, 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-range:focus::-moz-range-thumb {\n  box-shadow: 0 0 0 1px #fff, 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-range:focus::-ms-thumb {\n  box-shadow: 0 0 0 1px #fff, 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-range::-moz-focus-outer {\n  border: 0;\n}\n\n.custom-range::-webkit-slider-thumb {\n  width: 1rem;\n  height: 1rem;\n  margin-top: -0.25rem;\n  background-color: #007bff;\n  border: 0;\n  border-radius: 1rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  -webkit-appearance: none;\n  appearance: none;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-range::-webkit-slider-thumb {\n    transition: none;\n  }\n}\n\n.custom-range::-webkit-slider-thumb:active {\n  background-color: #b3d7ff;\n}\n\n.custom-range::-webkit-slider-runnable-track {\n  width: 100%;\n  height: 0.5rem;\n  color: transparent;\n  cursor: pointer;\n  background-color: #dee2e6;\n  border-color: transparent;\n  border-radius: 1rem;\n}\n\n.custom-range::-moz-range-thumb {\n  width: 1rem;\n  height: 1rem;\n  background-color: #007bff;\n  border: 0;\n  border-radius: 1rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  -moz-appearance: none;\n  appearance: none;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-range::-moz-range-thumb {\n    transition: none;\n  }\n}\n\n.custom-range::-moz-range-thumb:active {\n  background-color: #b3d7ff;\n}\n\n.custom-range::-moz-range-track {\n  width: 100%;\n  height: 0.5rem;\n  color: transparent;\n  cursor: pointer;\n  background-color: #dee2e6;\n  border-color: transparent;\n  border-radius: 1rem;\n}\n\n.custom-range::-ms-thumb {\n  width: 1rem;\n  height: 1rem;\n  margin-top: 0;\n  margin-right: 0.2rem;\n  margin-left: 0.2rem;\n  background-color: #007bff;\n  border: 0;\n  border-radius: 1rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  appearance: none;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-range::-ms-thumb {\n    transition: none;\n  }\n}\n\n.custom-range::-ms-thumb:active {\n  background-color: #b3d7ff;\n}\n\n.custom-range::-ms-track {\n  width: 100%;\n  height: 0.5rem;\n  color: transparent;\n  cursor: pointer;\n  background-color: transparent;\n  border-color: transparent;\n  border-width: 0.5rem;\n}\n\n.custom-range::-ms-fill-lower {\n  background-color: #dee2e6;\n  border-radius: 1rem;\n}\n\n.custom-range::-ms-fill-upper {\n  margin-right: 15px;\n  background-color: #dee2e6;\n  border-radius: 1rem;\n}\n\n.custom-range:disabled::-webkit-slider-thumb {\n  background-color: #adb5bd;\n}\n\n.custom-range:disabled::-webkit-slider-runnable-track {\n  cursor: default;\n}\n\n.custom-range:disabled::-moz-range-thumb {\n  background-color: #adb5bd;\n}\n\n.custom-range:disabled::-moz-range-track {\n  cursor: default;\n}\n\n.custom-range:disabled::-ms-thumb {\n  background-color: #adb5bd;\n}\n\n.custom-control-label::before,\n.custom-file-label,\n.custom-select {\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-control-label::before,\n  .custom-file-label,\n  .custom-select {\n    transition: none;\n  }\n}\n\n.nav {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  padding-left: 0;\n  margin-bottom: 0;\n  list-style: none;\n}\n\n.nav-link {\n  display: block;\n  padding: 0.5rem 1rem;\n}\n\n.nav-link:hover, .nav-link:focus {\n  text-decoration: none;\n}\n\n.nav-link.disabled {\n  color: #6c757d;\n  pointer-events: none;\n  cursor: default;\n}\n\n.nav-tabs {\n  border-bottom: 1px solid #dee2e6;\n}\n\n.nav-tabs .nav-item {\n  margin-bottom: -1px;\n}\n\n.nav-tabs .nav-link {\n  border: 1px solid transparent;\n  border-top-left-radius: 0.25rem;\n  border-top-right-radius: 0.25rem;\n}\n\n.nav-tabs .nav-link:hover, .nav-tabs .nav-link:focus {\n  border-color: #e9ecef #e9ecef #dee2e6;\n}\n\n.nav-tabs .nav-link.disabled {\n  color: #6c757d;\n  background-color: transparent;\n  border-color: transparent;\n}\n\n.nav-tabs .nav-link.active,\n.nav-tabs .nav-item.show .nav-link {\n  color: #495057;\n  background-color: #fff;\n  border-color: #dee2e6 #dee2e6 #fff;\n}\n\n.nav-tabs .dropdown-menu {\n  margin-top: -1px;\n  border-top-left-radius: 0;\n  border-top-right-radius: 0;\n}\n\n.nav-pills .nav-link {\n  border-radius: 0.25rem;\n}\n\n.nav-pills .nav-link.active,\n.nav-pills .show > .nav-link {\n  color: #fff;\n  background-color: #007bff;\n}\n\n.nav-fill .nav-item {\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  text-align: center;\n}\n\n.nav-justified .nav-item {\n  -ms-flex-preferred-size: 0;\n  flex-basis: 0;\n  -ms-flex-positive: 1;\n  flex-grow: 1;\n  text-align: center;\n}\n\n.tab-content > .tab-pane {\n  display: none;\n}\n\n.tab-content > .active {\n  display: block;\n}\n\n.navbar {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: justify;\n  justify-content: space-between;\n  padding: 0.5rem 1rem;\n}\n\n.navbar > .container,\n.navbar > .container-fluid {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: justify;\n  justify-content: space-between;\n}\n\n.navbar-brand {\n  display: inline-block;\n  padding-top: 0.3125rem;\n  padding-bottom: 0.3125rem;\n  margin-right: 1rem;\n  font-size: 1.25rem;\n  line-height: inherit;\n  white-space: nowrap;\n}\n\n.navbar-brand:hover, .navbar-brand:focus {\n  text-decoration: none;\n}\n\n.navbar-nav {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  padding-left: 0;\n  margin-bottom: 0;\n  list-style: none;\n}\n\n.navbar-nav .nav-link {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.navbar-nav .dropdown-menu {\n  position: static;\n  float: none;\n}\n\n.navbar-text {\n  display: inline-block;\n  padding-top: 0.5rem;\n  padding-bottom: 0.5rem;\n}\n\n.navbar-collapse {\n  -ms-flex-preferred-size: 100%;\n  flex-basis: 100%;\n  -ms-flex-positive: 1;\n  flex-grow: 1;\n  -ms-flex-align: center;\n  align-items: center;\n}\n\n.navbar-toggler {\n  padding: 0.25rem 0.75rem;\n  font-size: 1.25rem;\n  line-height: 1;\n  background-color: transparent;\n  border: 1px solid transparent;\n  border-radius: 0.25rem;\n}\n\n.navbar-toggler:hover, .navbar-toggler:focus {\n  text-decoration: none;\n}\n\n.navbar-toggler-icon {\n  display: inline-block;\n  width: 1.5em;\n  height: 1.5em;\n  vertical-align: middle;\n  content: \"\";\n  background: no-repeat center center;\n  background-size: 100% 100%;\n}\n\n@media (max-width: 575.98px) {\n  .navbar-expand-sm > .container,\n  .navbar-expand-sm > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 576px) {\n  .navbar-expand-sm {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-sm .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-sm .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-sm .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-sm > .container,\n  .navbar-expand-sm > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-sm .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-sm .navbar-toggler {\n    display: none;\n  }\n}\n\n@media (max-width: 767.98px) {\n  .navbar-expand-md > .container,\n  .navbar-expand-md > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 768px) {\n  .navbar-expand-md {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-md .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-md .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-md .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-md > .container,\n  .navbar-expand-md > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-md .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-md .navbar-toggler {\n    display: none;\n  }\n}\n\n@media (max-width: 991.98px) {\n  .navbar-expand-lg > .container,\n  .navbar-expand-lg > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 992px) {\n  .navbar-expand-lg {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-lg .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-lg .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-lg .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-lg > .container,\n  .navbar-expand-lg > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-lg .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-lg .navbar-toggler {\n    display: none;\n  }\n}\n\n@media (max-width: 1199.98px) {\n  .navbar-expand-xl > .container,\n  .navbar-expand-xl > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 1200px) {\n  .navbar-expand-xl {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-xl .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-xl .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-xl .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-xl > .container,\n  .navbar-expand-xl > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-xl .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-xl .navbar-toggler {\n    display: none;\n  }\n}\n\n.navbar-expand {\n  -ms-flex-flow: row nowrap;\n  flex-flow: row nowrap;\n  -ms-flex-pack: start;\n  justify-content: flex-start;\n}\n\n.navbar-expand > .container,\n.navbar-expand > .container-fluid {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.navbar-expand .navbar-nav {\n  -ms-flex-direction: row;\n  flex-direction: row;\n}\n\n.navbar-expand .navbar-nav .dropdown-menu {\n  position: absolute;\n}\n\n.navbar-expand .navbar-nav .nav-link {\n  padding-right: 0.5rem;\n  padding-left: 0.5rem;\n}\n\n.navbar-expand > .container,\n.navbar-expand > .container-fluid {\n  -ms-flex-wrap: nowrap;\n  flex-wrap: nowrap;\n}\n\n.navbar-expand .navbar-collapse {\n  display: -ms-flexbox !important;\n  display: flex !important;\n  -ms-flex-preferred-size: auto;\n  flex-basis: auto;\n}\n\n.navbar-expand .navbar-toggler {\n  display: none;\n}\n\n.navbar-light .navbar-brand {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-brand:hover, .navbar-light .navbar-brand:focus {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-nav .nav-link {\n  color: rgba(0, 0, 0, 0.5);\n}\n\n.navbar-light .navbar-nav .nav-link:hover, .navbar-light .navbar-nav .nav-link:focus {\n  color: rgba(0, 0, 0, 0.7);\n}\n\n.navbar-light .navbar-nav .nav-link.disabled {\n  color: rgba(0, 0, 0, 0.3);\n}\n\n.navbar-light .navbar-nav .show > .nav-link,\n.navbar-light .navbar-nav .active > .nav-link,\n.navbar-light .navbar-nav .nav-link.show,\n.navbar-light .navbar-nav .nav-link.active {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-toggler {\n  color: rgba(0, 0, 0, 0.5);\n  border-color: rgba(0, 0, 0, 0.1);\n}\n\n.navbar-light .navbar-toggler-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg viewBox='0 0 30 30' xmlns='http://www.w3.org/2000/svg'%3e%3cpath stroke='rgba(0, 0, 0, 0.5)' stroke-width='2' stroke-linecap='round' stroke-miterlimit='10' d='M4 7h22M4 15h22M4 23h22'/%3e%3c/svg%3e\");\n}\n\n.navbar-light .navbar-text {\n  color: rgba(0, 0, 0, 0.5);\n}\n\n.navbar-light .navbar-text a {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-text a:hover, .navbar-light .navbar-text a:focus {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-dark .navbar-brand {\n  color: #fff;\n}\n\n.navbar-dark .navbar-brand:hover, .navbar-dark .navbar-brand:focus {\n  color: #fff;\n}\n\n.navbar-dark .navbar-nav .nav-link {\n  color: rgba(255, 255, 255, 0.5);\n}\n\n.navbar-dark .navbar-nav .nav-link:hover, .navbar-dark .navbar-nav .nav-link:focus {\n  color: rgba(255, 255, 255, 0.75);\n}\n\n.navbar-dark .navbar-nav .nav-link.disabled {\n  color: rgba(255, 255, 255, 0.25);\n}\n\n.navbar-dark .navbar-nav .show > .nav-link,\n.navbar-dark .navbar-nav .active > .nav-link,\n.navbar-dark .navbar-nav .nav-link.show,\n.navbar-dark .navbar-nav .nav-link.active {\n  color: #fff;\n}\n\n.navbar-dark .navbar-toggler {\n  color: rgba(255, 255, 255, 0.5);\n  border-color: rgba(255, 255, 255, 0.1);\n}\n\n.navbar-dark .navbar-toggler-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg viewBox='0 0 30 30' xmlns='http://www.w3.org/2000/svg'%3e%3cpath stroke='rgba(255, 255, 255, 0.5)' stroke-width='2' stroke-linecap='round' stroke-miterlimit='10' d='M4 7h22M4 15h22M4 23h22'/%3e%3c/svg%3e\");\n}\n\n.navbar-dark .navbar-text {\n  color: rgba(255, 255, 255, 0.5);\n}\n\n.navbar-dark .navbar-text a {\n  color: #fff;\n}\n\n.navbar-dark .navbar-text a:hover, .navbar-dark .navbar-text a:focus {\n  color: #fff;\n}\n\n.card {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  min-width: 0;\n  word-wrap: break-word;\n  background-color: #fff;\n  background-clip: border-box;\n  border: 1px solid rgba(0, 0, 0, 0.125);\n  border-radius: 0.25rem;\n}\n\n.card > hr {\n  margin-right: 0;\n  margin-left: 0;\n}\n\n.card > .list-group:first-child .list-group-item:first-child {\n  border-top-left-radius: 0.25rem;\n  border-top-right-radius: 0.25rem;\n}\n\n.card > .list-group:last-child .list-group-item:last-child {\n  border-bottom-right-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n}\n\n.card-body {\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  padding: 1.25rem;\n}\n\n.card-title {\n  margin-bottom: 0.75rem;\n}\n\n.card-subtitle {\n  margin-top: -0.375rem;\n  margin-bottom: 0;\n}\n\n.card-text:last-child {\n  margin-bottom: 0;\n}\n\n.card-link:hover {\n  text-decoration: none;\n}\n\n.card-link + .card-link {\n  margin-left: 1.25rem;\n}\n\n.card-header {\n  padding: 0.75rem 1.25rem;\n  margin-bottom: 0;\n  background-color: rgba(0, 0, 0, 0.03);\n  border-bottom: 1px solid rgba(0, 0, 0, 0.125);\n}\n\n.card-header:first-child {\n  border-radius: calc(0.25rem - 1px) calc(0.25rem - 1px) 0 0;\n}\n\n.card-header + .list-group .list-group-item:first-child {\n  border-top: 0;\n}\n\n.card-footer {\n  padding: 0.75rem 1.25rem;\n  background-color: rgba(0, 0, 0, 0.03);\n  border-top: 1px solid rgba(0, 0, 0, 0.125);\n}\n\n.card-footer:last-child {\n  border-radius: 0 0 calc(0.25rem - 1px) calc(0.25rem - 1px);\n}\n\n.card-header-tabs {\n  margin-right: -0.625rem;\n  margin-bottom: -0.75rem;\n  margin-left: -0.625rem;\n  border-bottom: 0;\n}\n\n.card-header-pills {\n  margin-right: -0.625rem;\n  margin-left: -0.625rem;\n}\n\n.card-img-overlay {\n  position: absolute;\n  top: 0;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  padding: 1.25rem;\n}\n\n.card-img {\n  width: 100%;\n  border-radius: calc(0.25rem - 1px);\n}\n\n.card-img-top {\n  width: 100%;\n  border-top-left-radius: calc(0.25rem - 1px);\n  border-top-right-radius: calc(0.25rem - 1px);\n}\n\n.card-img-bottom {\n  width: 100%;\n  border-bottom-right-radius: calc(0.25rem - 1px);\n  border-bottom-left-radius: calc(0.25rem - 1px);\n}\n\n.card-deck {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n}\n\n.card-deck .card {\n  margin-bottom: 15px;\n}\n\n@media (min-width: 576px) {\n  .card-deck {\n    -ms-flex-flow: row wrap;\n    flex-flow: row wrap;\n    margin-right: -15px;\n    margin-left: -15px;\n  }\n  .card-deck .card {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex: 1 0 0%;\n    flex: 1 0 0%;\n    -ms-flex-direction: column;\n    flex-direction: column;\n    margin-right: 15px;\n    margin-bottom: 0;\n    margin-left: 15px;\n  }\n}\n\n.card-group {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n}\n\n.card-group > .card {\n  margin-bottom: 15px;\n}\n\n@media (min-width: 576px) {\n  .card-group {\n    -ms-flex-flow: row wrap;\n    flex-flow: row wrap;\n  }\n  .card-group > .card {\n    -ms-flex: 1 0 0%;\n    flex: 1 0 0%;\n    margin-bottom: 0;\n  }\n  .card-group > .card + .card {\n    margin-left: 0;\n    border-left: 0;\n  }\n  .card-group > .card:not(:last-child) {\n    border-top-right-radius: 0;\n    border-bottom-right-radius: 0;\n  }\n  .card-group > .card:not(:last-child) .card-img-top,\n  .card-group > .card:not(:last-child) .card-header {\n    border-top-right-radius: 0;\n  }\n  .card-group > .card:not(:last-child) .card-img-bottom,\n  .card-group > .card:not(:last-child) .card-footer {\n    border-bottom-right-radius: 0;\n  }\n  .card-group > .card:not(:first-child) {\n    border-top-left-radius: 0;\n    border-bottom-left-radius: 0;\n  }\n  .card-group > .card:not(:first-child) .card-img-top,\n  .card-group > .card:not(:first-child) .card-header {\n    border-top-left-radius: 0;\n  }\n  .card-group > .card:not(:first-child) .card-img-bottom,\n  .card-group > .card:not(:first-child) .card-footer {\n    border-bottom-left-radius: 0;\n  }\n}\n\n.card-columns .card {\n  margin-bottom: 0.75rem;\n}\n\n@media (min-width: 576px) {\n  .card-columns {\n    -webkit-column-count: 3;\n    -moz-column-count: 3;\n    column-count: 3;\n    -webkit-column-gap: 1.25rem;\n    -moz-column-gap: 1.25rem;\n    column-gap: 1.25rem;\n    orphans: 1;\n    widows: 1;\n  }\n  .card-columns .card {\n    display: inline-block;\n    width: 100%;\n  }\n}\n\n.accordion > .card {\n  overflow: hidden;\n}\n\n.accordion > .card:not(:first-of-type) .card-header:first-child {\n  border-radius: 0;\n}\n\n.accordion > .card:not(:first-of-type):not(:last-of-type) {\n  border-bottom: 0;\n  border-radius: 0;\n}\n\n.accordion > .card:first-of-type {\n  border-bottom: 0;\n  border-bottom-right-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.accordion > .card:last-of-type {\n  border-top-left-radius: 0;\n  border-top-right-radius: 0;\n}\n\n.accordion > .card .card-header {\n  margin-bottom: -1px;\n}\n\n.breadcrumb {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  padding: 0.75rem 1rem;\n  margin-bottom: 1rem;\n  list-style: none;\n  background-color: #e9ecef;\n  border-radius: 0.25rem;\n}\n\n.breadcrumb-item + .breadcrumb-item {\n  padding-left: 0.5rem;\n}\n\n.breadcrumb-item + .breadcrumb-item::before {\n  display: inline-block;\n  padding-right: 0.5rem;\n  color: #6c757d;\n  content: \"/\";\n}\n\n.breadcrumb-item + .breadcrumb-item:hover::before {\n  text-decoration: underline;\n}\n\n.breadcrumb-item + .breadcrumb-item:hover::before {\n  text-decoration: none;\n}\n\n.breadcrumb-item.active {\n  color: #6c757d;\n}\n\n.pagination {\n  display: -ms-flexbox;\n  display: flex;\n  padding-left: 0;\n  list-style: none;\n  border-radius: 0.25rem;\n}\n\n.page-link {\n  position: relative;\n  display: block;\n  padding: 0.5rem 0.75rem;\n  margin-left: -1px;\n  line-height: 1.25;\n  color: #007bff;\n  background-color: #fff;\n  border: 1px solid #dee2e6;\n}\n\n.page-link:hover {\n  z-index: 2;\n  color: #0056b3;\n  text-decoration: none;\n  background-color: #e9ecef;\n  border-color: #dee2e6;\n}\n\n.page-link:focus {\n  z-index: 2;\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.page-item:first-child .page-link {\n  margin-left: 0;\n  border-top-left-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n}\n\n.page-item:last-child .page-link {\n  border-top-right-radius: 0.25rem;\n  border-bottom-right-radius: 0.25rem;\n}\n\n.page-item.active .page-link {\n  z-index: 1;\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.page-item.disabled .page-link {\n  color: #6c757d;\n  pointer-events: none;\n  cursor: auto;\n  background-color: #fff;\n  border-color: #dee2e6;\n}\n\n.pagination-lg .page-link {\n  padding: 0.75rem 1.5rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n}\n\n.pagination-lg .page-item:first-child .page-link {\n  border-top-left-radius: 0.3rem;\n  border-bottom-left-radius: 0.3rem;\n}\n\n.pagination-lg .page-item:last-child .page-link {\n  border-top-right-radius: 0.3rem;\n  border-bottom-right-radius: 0.3rem;\n}\n\n.pagination-sm .page-link {\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n}\n\n.pagination-sm .page-item:first-child .page-link {\n  border-top-left-radius: 0.2rem;\n  border-bottom-left-radius: 0.2rem;\n}\n\n.pagination-sm .page-item:last-child .page-link {\n  border-top-right-radius: 0.2rem;\n  border-bottom-right-radius: 0.2rem;\n}\n\n.badge {\n  display: inline-block;\n  padding: 0.25em 0.4em;\n  font-size: 75%;\n  font-weight: 700;\n  line-height: 1;\n  text-align: center;\n  white-space: nowrap;\n  vertical-align: baseline;\n  border-radius: 0.25rem;\n  transition: color 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .badge {\n    transition: none;\n  }\n}\n\na.badge:hover, a.badge:focus {\n  text-decoration: none;\n}\n\n.badge:empty {\n  display: none;\n}\n\n.btn .badge {\n  position: relative;\n  top: -1px;\n}\n\n.badge-pill {\n  padding-right: 0.6em;\n  padding-left: 0.6em;\n  border-radius: 10rem;\n}\n\n.badge-primary {\n  color: #fff;\n  background-color: #007bff;\n}\n\na.badge-primary:hover, a.badge-primary:focus {\n  color: #fff;\n  background-color: #0062cc;\n}\n\na.badge-primary:focus, a.badge-primary.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.5);\n}\n\n.badge-secondary {\n  color: #fff;\n  background-color: #6c757d;\n}\n\na.badge-secondary:hover, a.badge-secondary:focus {\n  color: #fff;\n  background-color: #545b62;\n}\n\na.badge-secondary:focus, a.badge-secondary.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(108, 117, 125, 0.5);\n}\n\n.badge-success {\n  color: #fff;\n  background-color: #28a745;\n}\n\na.badge-success:hover, a.badge-success:focus {\n  color: #fff;\n  background-color: #1e7e34;\n}\n\na.badge-success:focus, a.badge-success.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.5);\n}\n\n.badge-info {\n  color: #fff;\n  background-color: #17a2b8;\n}\n\na.badge-info:hover, a.badge-info:focus {\n  color: #fff;\n  background-color: #117a8b;\n}\n\na.badge-info:focus, a.badge-info.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(23, 162, 184, 0.5);\n}\n\n.badge-warning {\n  color: #212529;\n  background-color: #ffc107;\n}\n\na.badge-warning:hover, a.badge-warning:focus {\n  color: #212529;\n  background-color: #d39e00;\n}\n\na.badge-warning:focus, a.badge-warning.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(255, 193, 7, 0.5);\n}\n\n.badge-danger {\n  color: #fff;\n  background-color: #dc3545;\n}\n\na.badge-danger:hover, a.badge-danger:focus {\n  color: #fff;\n  background-color: #bd2130;\n}\n\na.badge-danger:focus, a.badge-danger.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.5);\n}\n\n.badge-light {\n  color: #212529;\n  background-color: #f8f9fa;\n}\n\na.badge-light:hover, a.badge-light:focus {\n  color: #212529;\n  background-color: #dae0e5;\n}\n\na.badge-light:focus, a.badge-light.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(248, 249, 250, 0.5);\n}\n\n.badge-dark {\n  color: #fff;\n  background-color: #343a40;\n}\n\na.badge-dark:hover, a.badge-dark:focus {\n  color: #fff;\n  background-color: #1d2124;\n}\n\na.badge-dark:focus, a.badge-dark.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(52, 58, 64, 0.5);\n}\n\n.jumbotron {\n  padding: 2rem 1rem;\n  margin-bottom: 2rem;\n  background-color: #e9ecef;\n  border-radius: 0.3rem;\n}\n\n@media (min-width: 576px) {\n  .jumbotron {\n    padding: 4rem 2rem;\n  }\n}\n\n.jumbotron-fluid {\n  padding-right: 0;\n  padding-left: 0;\n  border-radius: 0;\n}\n\n.alert {\n  position: relative;\n  padding: 0.75rem 1.25rem;\n  margin-bottom: 1rem;\n  border: 1px solid transparent;\n  border-radius: 0.25rem;\n}\n\n.alert-heading {\n  color: inherit;\n}\n\n.alert-link {\n  font-weight: 700;\n}\n\n.alert-dismissible {\n  padding-right: 4rem;\n}\n\n.alert-dismissible .close {\n  position: absolute;\n  top: 0;\n  right: 0;\n  padding: 0.75rem 1.25rem;\n  color: inherit;\n}\n\n.alert-primary {\n  color: #004085;\n  background-color: #cce5ff;\n  border-color: #b8daff;\n}\n\n.alert-primary hr {\n  border-top-color: #9fcdff;\n}\n\n.alert-primary .alert-link {\n  color: #002752;\n}\n\n.alert-secondary {\n  color: #383d41;\n  background-color: #e2e3e5;\n  border-color: #d6d8db;\n}\n\n.alert-secondary hr {\n  border-top-color: #c8cbcf;\n}\n\n.alert-secondary .alert-link {\n  color: #202326;\n}\n\n.alert-success {\n  color: #155724;\n  background-color: #d4edda;\n  border-color: #c3e6cb;\n}\n\n.alert-success hr {\n  border-top-color: #b1dfbb;\n}\n\n.alert-success .alert-link {\n  color: #0b2e13;\n}\n\n.alert-info {\n  color: #0c5460;\n  background-color: #d1ecf1;\n  border-color: #bee5eb;\n}\n\n.alert-info hr {\n  border-top-color: #abdde5;\n}\n\n.alert-info .alert-link {\n  color: #062c33;\n}\n\n.alert-warning {\n  color: #856404;\n  background-color: #fff3cd;\n  border-color: #ffeeba;\n}\n\n.alert-warning hr {\n  border-top-color: #ffe8a1;\n}\n\n.alert-warning .alert-link {\n  color: #533f03;\n}\n\n.alert-danger {\n  color: #721c24;\n  background-color: #f8d7da;\n  border-color: #f5c6cb;\n}\n\n.alert-danger hr {\n  border-top-color: #f1b0b7;\n}\n\n.alert-danger .alert-link {\n  color: #491217;\n}\n\n.alert-light {\n  color: #818182;\n  background-color: #fefefe;\n  border-color: #fdfdfe;\n}\n\n.alert-light hr {\n  border-top-color: #ececf6;\n}\n\n.alert-light .alert-link {\n  color: #686868;\n}\n\n.alert-dark {\n  color: #1b1e21;\n  background-color: #d6d8d9;\n  border-color: #c6c8ca;\n}\n\n.alert-dark hr {\n  border-top-color: #b9bbbe;\n}\n\n.alert-dark .alert-link {\n  color: #040505;\n}\n\n@-webkit-keyframes progress-bar-stripes {\n  from {\n    background-position: 1rem 0;\n  }\n  to {\n    background-position: 0 0;\n  }\n}\n\n@keyframes progress-bar-stripes {\n  from {\n    background-position: 1rem 0;\n  }\n  to {\n    background-position: 0 0;\n  }\n}\n\n.progress {\n  display: -ms-flexbox;\n  display: flex;\n  height: 1rem;\n  overflow: hidden;\n  font-size: 0.75rem;\n  background-color: #e9ecef;\n  border-radius: 0.25rem;\n}\n\n.progress-bar {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  -ms-flex-pack: center;\n  justify-content: center;\n  color: #fff;\n  text-align: center;\n  white-space: nowrap;\n  background-color: #007bff;\n  transition: width 0.6s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .progress-bar {\n    transition: none;\n  }\n}\n\n.progress-bar-striped {\n  background-image: linear-gradient(45deg, rgba(255, 255, 255, 0.15) 25%, transparent 25%, transparent 50%, rgba(255, 255, 255, 0.15) 50%, rgba(255, 255, 255, 0.15) 75%, transparent 75%, transparent);\n  background-size: 1rem 1rem;\n}\n\n.progress-bar-animated {\n  -webkit-animation: progress-bar-stripes 1s linear infinite;\n  animation: progress-bar-stripes 1s linear infinite;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .progress-bar-animated {\n    -webkit-animation: none;\n    animation: none;\n  }\n}\n\n.media {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: start;\n  align-items: flex-start;\n}\n\n.media-body {\n  -ms-flex: 1;\n  flex: 1;\n}\n\n.list-group {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  padding-left: 0;\n  margin-bottom: 0;\n}\n\n.list-group-item-action {\n  width: 100%;\n  color: #495057;\n  text-align: inherit;\n}\n\n.list-group-item-action:hover, .list-group-item-action:focus {\n  z-index: 1;\n  color: #495057;\n  text-decoration: none;\n  background-color: #f8f9fa;\n}\n\n.list-group-item-action:active {\n  color: #212529;\n  background-color: #e9ecef;\n}\n\n.list-group-item {\n  position: relative;\n  display: block;\n  padding: 0.75rem 1.25rem;\n  margin-bottom: -1px;\n  background-color: #fff;\n  border: 1px solid rgba(0, 0, 0, 0.125);\n}\n\n.list-group-item:first-child {\n  border-top-left-radius: 0.25rem;\n  border-top-right-radius: 0.25rem;\n}\n\n.list-group-item:last-child {\n  margin-bottom: 0;\n  border-bottom-right-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n}\n\n.list-group-item.disabled, .list-group-item:disabled {\n  color: #6c757d;\n  pointer-events: none;\n  background-color: #fff;\n}\n\n.list-group-item.active {\n  z-index: 2;\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.list-group-horizontal {\n  -ms-flex-direction: row;\n  flex-direction: row;\n}\n\n.list-group-horizontal .list-group-item {\n  margin-right: -1px;\n  margin-bottom: 0;\n}\n\n.list-group-horizontal .list-group-item:first-child {\n  border-top-left-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n  border-top-right-radius: 0;\n}\n\n.list-group-horizontal .list-group-item:last-child {\n  margin-right: 0;\n  border-top-right-radius: 0.25rem;\n  border-bottom-right-radius: 0.25rem;\n  border-bottom-left-radius: 0;\n}\n\n@media (min-width: 576px) {\n  .list-group-horizontal-sm {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-sm .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-sm .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-sm .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n@media (min-width: 768px) {\n  .list-group-horizontal-md {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-md .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-md .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-md .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n@media (min-width: 992px) {\n  .list-group-horizontal-lg {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-lg .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-lg .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-lg .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n@media (min-width: 1200px) {\n  .list-group-horizontal-xl {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-xl .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-xl .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-xl .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n.list-group-flush .list-group-item {\n  border-right: 0;\n  border-left: 0;\n  border-radius: 0;\n}\n\n.list-group-flush .list-group-item:last-child {\n  margin-bottom: -1px;\n}\n\n.list-group-flush:first-child .list-group-item:first-child {\n  border-top: 0;\n}\n\n.list-group-flush:last-child .list-group-item:last-child {\n  margin-bottom: 0;\n  border-bottom: 0;\n}\n\n.list-group-item-primary {\n  color: #004085;\n  background-color: #b8daff;\n}\n\n.list-group-item-primary.list-group-item-action:hover, .list-group-item-primary.list-group-item-action:focus {\n  color: #004085;\n  background-color: #9fcdff;\n}\n\n.list-group-item-primary.list-group-item-action.active {\n  color: #fff;\n  background-color: #004085;\n  border-color: #004085;\n}\n\n.list-group-item-secondary {\n  color: #383d41;\n  background-color: #d6d8db;\n}\n\n.list-group-item-secondary.list-group-item-action:hover, .list-group-item-secondary.list-group-item-action:focus {\n  color: #383d41;\n  background-color: #c8cbcf;\n}\n\n.list-group-item-secondary.list-group-item-action.active {\n  color: #fff;\n  background-color: #383d41;\n  border-color: #383d41;\n}\n\n.list-group-item-success {\n  color: #155724;\n  background-color: #c3e6cb;\n}\n\n.list-group-item-success.list-group-item-action:hover, .list-group-item-success.list-group-item-action:focus {\n  color: #155724;\n  background-color: #b1dfbb;\n}\n\n.list-group-item-success.list-group-item-action.active {\n  color: #fff;\n  background-color: #155724;\n  border-color: #155724;\n}\n\n.list-group-item-info {\n  color: #0c5460;\n  background-color: #bee5eb;\n}\n\n.list-group-item-info.list-group-item-action:hover, .list-group-item-info.list-group-item-action:focus {\n  color: #0c5460;\n  background-color: #abdde5;\n}\n\n.list-group-item-info.list-group-item-action.active {\n  color: #fff;\n  background-color: #0c5460;\n  border-color: #0c5460;\n}\n\n.list-group-item-warning {\n  color: #856404;\n  background-color: #ffeeba;\n}\n\n.list-group-item-warning.list-group-item-action:hover, .list-group-item-warning.list-group-item-action:focus {\n  color: #856404;\n  background-color: #ffe8a1;\n}\n\n.list-group-item-warning.list-group-item-action.active {\n  color: #fff;\n  background-color: #856404;\n  border-color: #856404;\n}\n\n.list-group-item-danger {\n  color: #721c24;\n  background-color: #f5c6cb;\n}\n\n.list-group-item-danger.list-group-item-action:hover, .list-group-item-danger.list-group-item-action:focus {\n  color: #721c24;\n  background-color: #f1b0b7;\n}\n\n.list-group-item-danger.list-group-item-action.active {\n  color: #fff;\n  background-color: #721c24;\n  border-color: #721c24;\n}\n\n.list-group-item-light {\n  color: #818182;\n  background-color: #fdfdfe;\n}\n\n.list-group-item-light.list-group-item-action:hover, .list-group-item-light.list-group-item-action:focus {\n  color: #818182;\n  background-color: #ececf6;\n}\n\n.list-group-item-light.list-group-item-action.active {\n  color: #fff;\n  background-color: #818182;\n  border-color: #818182;\n}\n\n.list-group-item-dark {\n  color: #1b1e21;\n  background-color: #c6c8ca;\n}\n\n.list-group-item-dark.list-group-item-action:hover, .list-group-item-dark.list-group-item-action:focus {\n  color: #1b1e21;\n  background-color: #b9bbbe;\n}\n\n.list-group-item-dark.list-group-item-action.active {\n  color: #fff;\n  background-color: #1b1e21;\n  border-color: #1b1e21;\n}\n\n.close {\n  float: right;\n  font-size: 1.5rem;\n  font-weight: 700;\n  line-height: 1;\n  color: #000;\n  text-shadow: 0 1px 0 #fff;\n  opacity: .5;\n}\n\n.close:hover {\n  color: #000;\n  text-decoration: none;\n}\n\n.close:not(:disabled):not(.disabled):hover, .close:not(:disabled):not(.disabled):focus {\n  opacity: .75;\n}\n\nbutton.close {\n  padding: 0;\n  background-color: transparent;\n  border: 0;\n  -webkit-appearance: none;\n  -moz-appearance: none;\n  appearance: none;\n}\n\na.close.disabled {\n  pointer-events: none;\n}\n\n.toast {\n  max-width: 350px;\n  overflow: hidden;\n  font-size: 0.875rem;\n  background-color: rgba(255, 255, 255, 0.85);\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.1);\n  box-shadow: 0 0.25rem 0.75rem rgba(0, 0, 0, 0.1);\n  -webkit-backdrop-filter: blur(10px);\n  backdrop-filter: blur(10px);\n  opacity: 0;\n  border-radius: 0.25rem;\n}\n\n.toast:not(:last-child) {\n  margin-bottom: 0.75rem;\n}\n\n.toast.showing {\n  opacity: 1;\n}\n\n.toast.show {\n  display: block;\n  opacity: 1;\n}\n\n.toast.hide {\n  display: none;\n}\n\n.toast-header {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  padding: 0.25rem 0.75rem;\n  color: #6c757d;\n  background-color: rgba(255, 255, 255, 0.85);\n  background-clip: padding-box;\n  border-bottom: 1px solid rgba(0, 0, 0, 0.05);\n}\n\n.toast-body {\n  padding: 0.75rem;\n}\n\n.modal-open {\n  overflow: hidden;\n}\n\n.modal-open .modal {\n  overflow-x: hidden;\n  overflow-y: auto;\n}\n\n.modal {\n  position: fixed;\n  top: 0;\n  left: 0;\n  z-index: 1050;\n  display: none;\n  width: 100%;\n  height: 100%;\n  overflow: hidden;\n  outline: 0;\n}\n\n.modal-dialog {\n  position: relative;\n  width: auto;\n  margin: 0.5rem;\n  pointer-events: none;\n}\n\n.modal.fade .modal-dialog {\n  transition: -webkit-transform 0.3s ease-out;\n  transition: transform 0.3s ease-out;\n  transition: transform 0.3s ease-out, -webkit-transform 0.3s ease-out;\n  -webkit-transform: translate(0, -50px);\n  transform: translate(0, -50px);\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .modal.fade .modal-dialog {\n    transition: none;\n  }\n}\n\n.modal.show .modal-dialog {\n  -webkit-transform: none;\n  transform: none;\n}\n\n.modal-dialog-scrollable {\n  display: -ms-flexbox;\n  display: flex;\n  max-height: calc(100% - 1rem);\n}\n\n.modal-dialog-scrollable .modal-content {\n  max-height: calc(100vh - 1rem);\n  overflow: hidden;\n}\n\n.modal-dialog-scrollable .modal-header,\n.modal-dialog-scrollable .modal-footer {\n  -ms-flex-negative: 0;\n  flex-shrink: 0;\n}\n\n.modal-dialog-scrollable .modal-body {\n  overflow-y: auto;\n}\n\n.modal-dialog-centered {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  min-height: calc(100% - 1rem);\n}\n\n.modal-dialog-centered::before {\n  display: block;\n  height: calc(100vh - 1rem);\n  content: \"\";\n}\n\n.modal-dialog-centered.modal-dialog-scrollable {\n  -ms-flex-direction: column;\n  flex-direction: column;\n  -ms-flex-pack: center;\n  justify-content: center;\n  height: 100%;\n}\n\n.modal-dialog-centered.modal-dialog-scrollable .modal-content {\n  max-height: none;\n}\n\n.modal-dialog-centered.modal-dialog-scrollable::before {\n  content: none;\n}\n\n.modal-content {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  width: 100%;\n  pointer-events: auto;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.2);\n  border-radius: 0.3rem;\n  outline: 0;\n}\n\n.modal-backdrop {\n  position: fixed;\n  top: 0;\n  left: 0;\n  z-index: 1040;\n  width: 100vw;\n  height: 100vh;\n  background-color: #000;\n}\n\n.modal-backdrop.fade {\n  opacity: 0;\n}\n\n.modal-backdrop.show {\n  opacity: 0.5;\n}\n\n.modal-header {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: start;\n  align-items: flex-start;\n  -ms-flex-pack: justify;\n  justify-content: space-between;\n  padding: 1rem 1rem;\n  border-bottom: 1px solid #dee2e6;\n  border-top-left-radius: 0.3rem;\n  border-top-right-radius: 0.3rem;\n}\n\n.modal-header .close {\n  padding: 1rem 1rem;\n  margin: -1rem -1rem -1rem auto;\n}\n\n.modal-title {\n  margin-bottom: 0;\n  line-height: 1.5;\n}\n\n.modal-body {\n  position: relative;\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  padding: 1rem;\n}\n\n.modal-footer {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: end;\n  justify-content: flex-end;\n  padding: 1rem;\n  border-top: 1px solid #dee2e6;\n  border-bottom-right-radius: 0.3rem;\n  border-bottom-left-radius: 0.3rem;\n}\n\n.modal-footer > :not(:first-child) {\n  margin-left: .25rem;\n}\n\n.modal-footer > :not(:last-child) {\n  margin-right: .25rem;\n}\n\n.modal-scrollbar-measure {\n  position: absolute;\n  top: -9999px;\n  width: 50px;\n  height: 50px;\n  overflow: scroll;\n}\n\n@media (min-width: 576px) {\n  .modal-dialog {\n    max-width: 500px;\n    margin: 1.75rem auto;\n  }\n  .modal-dialog-scrollable {\n    max-height: calc(100% - 3.5rem);\n  }\n  .modal-dialog-scrollable .modal-content {\n    max-height: calc(100vh - 3.5rem);\n  }\n  .modal-dialog-centered {\n    min-height: calc(100% - 3.5rem);\n  }\n  .modal-dialog-centered::before {\n    height: calc(100vh - 3.5rem);\n  }\n  .modal-sm {\n    max-width: 300px;\n  }\n}\n\n@media (min-width: 992px) {\n  .modal-lg,\n  .modal-xl {\n    max-width: 800px;\n  }\n}\n\n@media (min-width: 1200px) {\n  .modal-xl {\n    max-width: 1140px;\n  }\n}\n\n.tooltip {\n  position: absolute;\n  z-index: 1070;\n  display: block;\n  margin: 0;\n  font-family: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  font-style: normal;\n  font-weight: 400;\n  line-height: 1.5;\n  text-align: left;\n  text-align: start;\n  text-decoration: none;\n  text-shadow: none;\n  text-transform: none;\n  letter-spacing: normal;\n  word-break: normal;\n  word-spacing: normal;\n  white-space: normal;\n  line-break: auto;\n  font-size: 0.875rem;\n  word-wrap: break-word;\n  opacity: 0;\n}\n\n.tooltip.show {\n  opacity: 0.9;\n}\n\n.tooltip .arrow {\n  position: absolute;\n  display: block;\n  width: 0.8rem;\n  height: 0.4rem;\n}\n\n.tooltip .arrow::before {\n  position: absolute;\n  content: \"\";\n  border-color: transparent;\n  border-style: solid;\n}\n\n.bs-tooltip-top, .bs-tooltip-auto[x-placement^=\"top\"] {\n  padding: 0.4rem 0;\n}\n\n.bs-tooltip-top .arrow, .bs-tooltip-auto[x-placement^=\"top\"] .arrow {\n  bottom: 0;\n}\n\n.bs-tooltip-top .arrow::before, .bs-tooltip-auto[x-placement^=\"top\"] .arrow::before {\n  top: 0;\n  border-width: 0.4rem 0.4rem 0;\n  border-top-color: #000;\n}\n\n.bs-tooltip-right, .bs-tooltip-auto[x-placement^=\"right\"] {\n  padding: 0 0.4rem;\n}\n\n.bs-tooltip-right .arrow, .bs-tooltip-auto[x-placement^=\"right\"] .arrow {\n  left: 0;\n  width: 0.4rem;\n  height: 0.8rem;\n}\n\n.bs-tooltip-right .arrow::before, .bs-tooltip-auto[x-placement^=\"right\"] .arrow::before {\n  right: 0;\n  border-width: 0.4rem 0.4rem 0.4rem 0;\n  border-right-color: #000;\n}\n\n.bs-tooltip-bottom, .bs-tooltip-auto[x-placement^=\"bottom\"] {\n  padding: 0.4rem 0;\n}\n\n.bs-tooltip-bottom .arrow, .bs-tooltip-auto[x-placement^=\"bottom\"] .arrow {\n  top: 0;\n}\n\n.bs-tooltip-bottom .arrow::before, .bs-tooltip-auto[x-placement^=\"bottom\"] .arrow::before {\n  bottom: 0;\n  border-width: 0 0.4rem 0.4rem;\n  border-bottom-color: #000;\n}\n\n.bs-tooltip-left, .bs-tooltip-auto[x-placement^=\"left\"] {\n  padding: 0 0.4rem;\n}\n\n.bs-tooltip-left .arrow, .bs-tooltip-auto[x-placement^=\"left\"] .arrow {\n  right: 0;\n  width: 0.4rem;\n  height: 0.8rem;\n}\n\n.bs-tooltip-left .arrow::before, .bs-tooltip-auto[x-placement^=\"left\"] .arrow::before {\n  left: 0;\n  border-width: 0.4rem 0 0.4rem 0.4rem;\n  border-left-color: #000;\n}\n\n.tooltip-inner {\n  max-width: 200px;\n  padding: 0.25rem 0.5rem;\n  color: #fff;\n  text-align: center;\n  background-color: #000;\n  border-radius: 0.25rem;\n}\n\n.popover {\n  position: absolute;\n  top: 0;\n  left: 0;\n  z-index: 1060;\n  display: block;\n  max-width: 276px;\n  font-family: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  font-style: normal;\n  font-weight: 400;\n  line-height: 1.5;\n  text-align: left;\n  text-align: start;\n  text-decoration: none;\n  text-shadow: none;\n  text-transform: none;\n  letter-spacing: normal;\n  word-break: normal;\n  word-spacing: normal;\n  white-space: normal;\n  line-break: auto;\n  font-size: 0.875rem;\n  word-wrap: break-word;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.2);\n  border-radius: 0.3rem;\n}\n\n.popover .arrow {\n  position: absolute;\n  display: block;\n  width: 1rem;\n  height: 0.5rem;\n  margin: 0 0.3rem;\n}\n\n.popover .arrow::before, .popover .arrow::after {\n  position: absolute;\n  display: block;\n  content: \"\";\n  border-color: transparent;\n  border-style: solid;\n}\n\n.bs-popover-top, .bs-popover-auto[x-placement^=\"top\"] {\n  margin-bottom: 0.5rem;\n}\n\n.bs-popover-top > .arrow, .bs-popover-auto[x-placement^=\"top\"] > .arrow {\n  bottom: calc((0.5rem + 1px) * -1);\n}\n\n.bs-popover-top > .arrow::before, .bs-popover-auto[x-placement^=\"top\"] > .arrow::before {\n  bottom: 0;\n  border-width: 0.5rem 0.5rem 0;\n  border-top-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-top > .arrow::after, .bs-popover-auto[x-placement^=\"top\"] > .arrow::after {\n  bottom: 1px;\n  border-width: 0.5rem 0.5rem 0;\n  border-top-color: #fff;\n}\n\n.bs-popover-right, .bs-popover-auto[x-placement^=\"right\"] {\n  margin-left: 0.5rem;\n}\n\n.bs-popover-right > .arrow, .bs-popover-auto[x-placement^=\"right\"] > .arrow {\n  left: calc((0.5rem + 1px) * -1);\n  width: 0.5rem;\n  height: 1rem;\n  margin: 0.3rem 0;\n}\n\n.bs-popover-right > .arrow::before, .bs-popover-auto[x-placement^=\"right\"] > .arrow::before {\n  left: 0;\n  border-width: 0.5rem 0.5rem 0.5rem 0;\n  border-right-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-right > .arrow::after, .bs-popover-auto[x-placement^=\"right\"] > .arrow::after {\n  left: 1px;\n  border-width: 0.5rem 0.5rem 0.5rem 0;\n  border-right-color: #fff;\n}\n\n.bs-popover-bottom, .bs-popover-auto[x-placement^=\"bottom\"] {\n  margin-top: 0.5rem;\n}\n\n.bs-popover-bottom > .arrow, .bs-popover-auto[x-placement^=\"bottom\"] > .arrow {\n  top: calc((0.5rem + 1px) * -1);\n}\n\n.bs-popover-bottom > .arrow::before, .bs-popover-auto[x-placement^=\"bottom\"] > .arrow::before {\n  top: 0;\n  border-width: 0 0.5rem 0.5rem 0.5rem;\n  border-bottom-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-bottom > .arrow::after, .bs-popover-auto[x-placement^=\"bottom\"] > .arrow::after {\n  top: 1px;\n  border-width: 0 0.5rem 0.5rem 0.5rem;\n  border-bottom-color: #fff;\n}\n\n.bs-popover-bottom .popover-header::before, .bs-popover-auto[x-placement^=\"bottom\"] .popover-header::before {\n  position: absolute;\n  top: 0;\n  left: 50%;\n  display: block;\n  width: 1rem;\n  margin-left: -0.5rem;\n  content: \"\";\n  border-bottom: 1px solid #f7f7f7;\n}\n\n.bs-popover-left, .bs-popover-auto[x-placement^=\"left\"] {\n  margin-right: 0.5rem;\n}\n\n.bs-popover-left > .arrow, .bs-popover-auto[x-placement^=\"left\"] > .arrow {\n  right: calc((0.5rem + 1px) * -1);\n  width: 0.5rem;\n  height: 1rem;\n  margin: 0.3rem 0;\n}\n\n.bs-popover-left > .arrow::before, .bs-popover-auto[x-placement^=\"left\"] > .arrow::before {\n  right: 0;\n  border-width: 0.5rem 0 0.5rem 0.5rem;\n  border-left-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-left > .arrow::after, .bs-popover-auto[x-placement^=\"left\"] > .arrow::after {\n  right: 1px;\n  border-width: 0.5rem 0 0.5rem 0.5rem;\n  border-left-color: #fff;\n}\n\n.popover-header {\n  padding: 0.5rem 0.75rem;\n  margin-bottom: 0;\n  font-size: 1rem;\n  background-color: #f7f7f7;\n  border-bottom: 1px solid #ebebeb;\n  border-top-left-radius: calc(0.3rem - 1px);\n  border-top-right-radius: calc(0.3rem - 1px);\n}\n\n.popover-header:empty {\n  display: none;\n}\n\n.popover-body {\n  padding: 0.5rem 0.75rem;\n  color: #212529;\n}\n\n.carousel {\n  position: relative;\n}\n\n.carousel.pointer-event {\n  -ms-touch-action: pan-y;\n  touch-action: pan-y;\n}\n\n.carousel-inner {\n  position: relative;\n  width: 100%;\n  overflow: hidden;\n}\n\n.carousel-inner::after {\n  display: block;\n  clear: both;\n  content: \"\";\n}\n\n.carousel-item {\n  position: relative;\n  display: none;\n  float: left;\n  width: 100%;\n  margin-right: -100%;\n  -webkit-backface-visibility: hidden;\n  backface-visibility: hidden;\n  transition: -webkit-transform 0.6s ease-in-out;\n  transition: transform 0.6s ease-in-out;\n  transition: transform 0.6s ease-in-out, -webkit-transform 0.6s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-item {\n    transition: none;\n  }\n}\n\n.carousel-item.active,\n.carousel-item-next,\n.carousel-item-prev {\n  display: block;\n}\n\n.carousel-item-next:not(.carousel-item-left),\n.active.carousel-item-right {\n  -webkit-transform: translateX(100%);\n  transform: translateX(100%);\n}\n\n.carousel-item-prev:not(.carousel-item-right),\n.active.carousel-item-left {\n  -webkit-transform: translateX(-100%);\n  transform: translateX(-100%);\n}\n\n.carousel-fade .carousel-item {\n  opacity: 0;\n  transition-property: opacity;\n  -webkit-transform: none;\n  transform: none;\n}\n\n.carousel-fade .carousel-item.active,\n.carousel-fade .carousel-item-next.carousel-item-left,\n.carousel-fade .carousel-item-prev.carousel-item-right {\n  z-index: 1;\n  opacity: 1;\n}\n\n.carousel-fade .active.carousel-item-left,\n.carousel-fade .active.carousel-item-right {\n  z-index: 0;\n  opacity: 0;\n  transition: 0s 0.6s opacity;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-fade .active.carousel-item-left,\n  .carousel-fade .active.carousel-item-right {\n    transition: none;\n  }\n}\n\n.carousel-control-prev,\n.carousel-control-next {\n  position: absolute;\n  top: 0;\n  bottom: 0;\n  z-index: 1;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: center;\n  justify-content: center;\n  width: 15%;\n  color: #fff;\n  text-align: center;\n  opacity: 0.5;\n  transition: opacity 0.15s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-control-prev,\n  .carousel-control-next {\n    transition: none;\n  }\n}\n\n.carousel-control-prev:hover, .carousel-control-prev:focus,\n.carousel-control-next:hover,\n.carousel-control-next:focus {\n  color: #fff;\n  text-decoration: none;\n  outline: 0;\n  opacity: 0.9;\n}\n\n.carousel-control-prev {\n  left: 0;\n}\n\n.carousel-control-next {\n  right: 0;\n}\n\n.carousel-control-prev-icon,\n.carousel-control-next-icon {\n  display: inline-block;\n  width: 20px;\n  height: 20px;\n  background: no-repeat 50% / 100% 100%;\n}\n\n.carousel-control-prev-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23fff' viewBox='0 0 8 8'%3e%3cpath d='M5.25 0l-4 4 4 4 1.5-1.5-2.5-2.5 2.5-2.5-1.5-1.5z'/%3e%3c/svg%3e\");\n}\n\n.carousel-control-next-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23fff' viewBox='0 0 8 8'%3e%3cpath d='M2.75 0l-1.5 1.5 2.5 2.5-2.5 2.5 1.5 1.5 4-4-4-4z'/%3e%3c/svg%3e\");\n}\n\n.carousel-indicators {\n  position: absolute;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  z-index: 15;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-pack: center;\n  justify-content: center;\n  padding-left: 0;\n  margin-right: 15%;\n  margin-left: 15%;\n  list-style: none;\n}\n\n.carousel-indicators li {\n  box-sizing: content-box;\n  -ms-flex: 0 1 auto;\n  flex: 0 1 auto;\n  width: 30px;\n  height: 3px;\n  margin-right: 3px;\n  margin-left: 3px;\n  text-indent: -999px;\n  cursor: pointer;\n  background-color: #fff;\n  background-clip: padding-box;\n  border-top: 10px solid transparent;\n  border-bottom: 10px solid transparent;\n  opacity: .5;\n  transition: opacity 0.6s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-indicators li {\n    transition: none;\n  }\n}\n\n.carousel-indicators .active {\n  opacity: 1;\n}\n\n.carousel-caption {\n  position: absolute;\n  right: 15%;\n  bottom: 20px;\n  left: 15%;\n  z-index: 10;\n  padding-top: 20px;\n  padding-bottom: 20px;\n  color: #fff;\n  text-align: center;\n}\n\n@-webkit-keyframes spinner-border {\n  to {\n    -webkit-transform: rotate(360deg);\n    transform: rotate(360deg);\n  }\n}\n\n@keyframes spinner-border {\n  to {\n    -webkit-transform: rotate(360deg);\n    transform: rotate(360deg);\n  }\n}\n\n.spinner-border {\n  display: inline-block;\n  width: 2rem;\n  height: 2rem;\n  vertical-align: text-bottom;\n  border: 0.25em solid currentColor;\n  border-right-color: transparent;\n  border-radius: 50%;\n  -webkit-animation: spinner-border .75s linear infinite;\n  animation: spinner-border .75s linear infinite;\n}\n\n.spinner-border-sm {\n  width: 1rem;\n  height: 1rem;\n  border-width: 0.2em;\n}\n\n@-webkit-keyframes spinner-grow {\n  0% {\n    -webkit-transform: scale(0);\n    transform: scale(0);\n  }\n  50% {\n    opacity: 1;\n  }\n}\n\n@keyframes spinner-grow {\n  0% {\n    -webkit-transform: scale(0);\n    transform: scale(0);\n  }\n  50% {\n    opacity: 1;\n  }\n}\n\n.spinner-grow {\n  display: inline-block;\n  width: 2rem;\n  height: 2rem;\n  vertical-align: text-bottom;\n  background-color: currentColor;\n  border-radius: 50%;\n  opacity: 0;\n  -webkit-animation: spinner-grow .75s linear infinite;\n  animation: spinner-grow .75s linear infinite;\n}\n\n.spinner-grow-sm {\n  width: 1rem;\n  height: 1rem;\n}\n\n.align-baseline {\n  vertical-align: baseline !important;\n}\n\n.align-top {\n  vertical-align: top !important;\n}\n\n.align-middle {\n  vertical-align: middle !important;\n}\n\n.align-bottom {\n  vertical-align: bottom !important;\n}\n\n.align-text-bottom {\n  vertical-align: text-bottom !important;\n}\n\n.align-text-top {\n  vertical-align: text-top !important;\n}\n\n.bg-primary {\n  background-color: #007bff !important;\n}\n\na.bg-primary:hover, a.bg-primary:focus,\nbutton.bg-primary:hover,\nbutton.bg-primary:focus {\n  background-color: #0062cc !important;\n}\n\n.bg-secondary {\n  background-color: #6c757d !important;\n}\n\na.bg-secondary:hover, a.bg-secondary:focus,\nbutton.bg-secondary:hover,\nbutton.bg-secondary:focus {\n  background-color: #545b62 !important;\n}\n\n.bg-success {\n  background-color: #28a745 !important;\n}\n\na.bg-success:hover, a.bg-success:focus,\nbutton.bg-success:hover,\nbutton.bg-success:focus {\n  background-color: #1e7e34 !important;\n}\n\n.bg-info {\n  background-color: #17a2b8 !important;\n}\n\na.bg-info:hover, a.bg-info:focus,\nbutton.bg-info:hover,\nbutton.bg-info:focus {\n  background-color: #117a8b !important;\n}\n\n.bg-warning {\n  background-color: #ffc107 !important;\n}\n\na.bg-warning:hover, a.bg-warning:focus,\nbutton.bg-warning:hover,\nbutton.bg-warning:focus {\n  background-color: #d39e00 !important;\n}\n\n.bg-danger {\n  background-color: #dc3545 !important;\n}\n\na.bg-danger:hover, a.bg-danger:focus,\nbutton.bg-danger:hover,\nbutton.bg-danger:focus {\n  background-color: #bd2130 !important;\n}\n\n.bg-light {\n  background-color: #f8f9fa !important;\n}\n\na.bg-light:hover, a.bg-light:focus,\nbutton.bg-light:hover,\nbutton.bg-light:focus {\n  background-color: #dae0e5 !important;\n}\n\n.bg-dark {\n  background-color: #343a40 !important;\n}\n\na.bg-dark:hover, a.bg-dark:focus,\nbutton.bg-dark:hover,\nbutton.bg-dark:focus {\n  background-color: #1d2124 !important;\n}\n\n.bg-white {\n  background-color: #fff !important;\n}\n\n.bg-transparent {\n  background-color: transparent !important;\n}\n\n.border {\n  border: 1px solid #dee2e6 !important;\n}\n\n.border-top {\n  border-top: 1px solid #dee2e6 !important;\n}\n\n.border-right {\n  border-right: 1px solid #dee2e6 !important;\n}\n\n.border-bottom {\n  border-bottom: 1px solid #dee2e6 !important;\n}\n\n.border-left {\n  border-left: 1px solid #dee2e6 !important;\n}\n\n.border-0 {\n  border: 0 !important;\n}\n\n.border-top-0 {\n  border-top: 0 !important;\n}\n\n.border-right-0 {\n  border-right: 0 !important;\n}\n\n.border-bottom-0 {\n  border-bottom: 0 !important;\n}\n\n.border-left-0 {\n  border-left: 0 !important;\n}\n\n.border-primary {\n  border-color: #007bff !important;\n}\n\n.border-secondary {\n  border-color: #6c757d !important;\n}\n\n.border-success {\n  border-color: #28a745 !important;\n}\n\n.border-info {\n  border-color: #17a2b8 !important;\n}\n\n.border-warning {\n  border-color: #ffc107 !important;\n}\n\n.border-danger {\n  border-color: #dc3545 !important;\n}\n\n.border-light {\n  border-color: #f8f9fa !important;\n}\n\n.border-dark {\n  border-color: #343a40 !important;\n}\n\n.border-white {\n  border-color: #fff !important;\n}\n\n.rounded-sm {\n  border-radius: 0.2rem !important;\n}\n\n.rounded {\n  border-radius: 0.25rem !important;\n}\n\n.rounded-top {\n  border-top-left-radius: 0.25rem !important;\n  border-top-right-radius: 0.25rem !important;\n}\n\n.rounded-right {\n  border-top-right-radius: 0.25rem !important;\n  border-bottom-right-radius: 0.25rem !important;\n}\n\n.rounded-bottom {\n  border-bottom-right-radius: 0.25rem !important;\n  border-bottom-left-radius: 0.25rem !important;\n}\n\n.rounded-left {\n  border-top-left-radius: 0.25rem !important;\n  border-bottom-left-radius: 0.25rem !important;\n}\n\n.rounded-lg {\n  border-radius: 0.3rem !important;\n}\n\n.rounded-circle {\n  border-radius: 50% !important;\n}\n\n.rounded-pill {\n  border-radius: 50rem !important;\n}\n\n.rounded-0 {\n  border-radius: 0 !important;\n}\n\n.clearfix::after {\n  display: block;\n  clear: both;\n  content: \"\";\n}\n\n.d-none {\n  display: none !important;\n}\n\n.d-inline {\n  display: inline !important;\n}\n\n.d-inline-block {\n  display: inline-block !important;\n}\n\n.d-block {\n  display: block !important;\n}\n\n.d-table {\n  display: table !important;\n}\n\n.d-table-row {\n  display: table-row !important;\n}\n\n.d-table-cell {\n  display: table-cell !important;\n}\n\n.d-flex {\n  display: -ms-flexbox !important;\n  display: flex !important;\n}\n\n.d-inline-flex {\n  display: -ms-inline-flexbox !important;\n  display: inline-flex !important;\n}\n\n@media (min-width: 576px) {\n  .d-sm-none {\n    display: none !important;\n  }\n  .d-sm-inline {\n    display: inline !important;\n  }\n  .d-sm-inline-block {\n    display: inline-block !important;\n  }\n  .d-sm-block {\n    display: block !important;\n  }\n  .d-sm-table {\n    display: table !important;\n  }\n  .d-sm-table-row {\n    display: table-row !important;\n  }\n  .d-sm-table-cell {\n    display: table-cell !important;\n  }\n  .d-sm-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-sm-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .d-md-none {\n    display: none !important;\n  }\n  .d-md-inline {\n    display: inline !important;\n  }\n  .d-md-inline-block {\n    display: inline-block !important;\n  }\n  .d-md-block {\n    display: block !important;\n  }\n  .d-md-table {\n    display: table !important;\n  }\n  .d-md-table-row {\n    display: table-row !important;\n  }\n  .d-md-table-cell {\n    display: table-cell !important;\n  }\n  .d-md-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-md-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .d-lg-none {\n    display: none !important;\n  }\n  .d-lg-inline {\n    display: inline !important;\n  }\n  .d-lg-inline-block {\n    display: inline-block !important;\n  }\n  .d-lg-block {\n    display: block !important;\n  }\n  .d-lg-table {\n    display: table !important;\n  }\n  .d-lg-table-row {\n    display: table-row !important;\n  }\n  .d-lg-table-cell {\n    display: table-cell !important;\n  }\n  .d-lg-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-lg-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .d-xl-none {\n    display: none !important;\n  }\n  .d-xl-inline {\n    display: inline !important;\n  }\n  .d-xl-inline-block {\n    display: inline-block !important;\n  }\n  .d-xl-block {\n    display: block !important;\n  }\n  .d-xl-table {\n    display: table !important;\n  }\n  .d-xl-table-row {\n    display: table-row !important;\n  }\n  .d-xl-table-cell {\n    display: table-cell !important;\n  }\n  .d-xl-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-xl-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media print {\n  .d-print-none {\n    display: none !important;\n  }\n  .d-print-inline {\n    display: inline !important;\n  }\n  .d-print-inline-block {\n    display: inline-block !important;\n  }\n  .d-print-block {\n    display: block !important;\n  }\n  .d-print-table {\n    display: table !important;\n  }\n  .d-print-table-row {\n    display: table-row !important;\n  }\n  .d-print-table-cell {\n    display: table-cell !important;\n  }\n  .d-print-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-print-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n.embed-responsive {\n  position: relative;\n  display: block;\n  width: 100%;\n  padding: 0;\n  overflow: hidden;\n}\n\n.embed-responsive::before {\n  display: block;\n  content: \"\";\n}\n\n.embed-responsive .embed-responsive-item,\n.embed-responsive iframe,\n.embed-responsive embed,\n.embed-responsive object,\n.embed-responsive video {\n  position: absolute;\n  top: 0;\n  bottom: 0;\n  left: 0;\n  width: 100%;\n  height: 100%;\n  border: 0;\n}\n\n.embed-responsive-21by9::before {\n  padding-top: 42.857143%;\n}\n\n.embed-responsive-16by9::before {\n  padding-top: 56.25%;\n}\n\n.embed-responsive-4by3::before {\n  padding-top: 75%;\n}\n\n.embed-responsive-1by1::before {\n  padding-top: 100%;\n}\n\n.flex-row {\n  -ms-flex-direction: row !important;\n  flex-direction: row !important;\n}\n\n.flex-column {\n  -ms-flex-direction: column !important;\n  flex-direction: column !important;\n}\n\n.flex-row-reverse {\n  -ms-flex-direction: row-reverse !important;\n  flex-direction: row-reverse !important;\n}\n\n.flex-column-reverse {\n  -ms-flex-direction: column-reverse !important;\n  flex-direction: column-reverse !important;\n}\n\n.flex-wrap {\n  -ms-flex-wrap: wrap !important;\n  flex-wrap: wrap !important;\n}\n\n.flex-nowrap {\n  -ms-flex-wrap: nowrap !important;\n  flex-wrap: nowrap !important;\n}\n\n.flex-wrap-reverse {\n  -ms-flex-wrap: wrap-reverse !important;\n  flex-wrap: wrap-reverse !important;\n}\n\n.flex-fill {\n  -ms-flex: 1 1 auto !important;\n  flex: 1 1 auto !important;\n}\n\n.flex-grow-0 {\n  -ms-flex-positive: 0 !important;\n  flex-grow: 0 !important;\n}\n\n.flex-grow-1 {\n  -ms-flex-positive: 1 !important;\n  flex-grow: 1 !important;\n}\n\n.flex-shrink-0 {\n  -ms-flex-negative: 0 !important;\n  flex-shrink: 0 !important;\n}\n\n.flex-shrink-1 {\n  -ms-flex-negative: 1 !important;\n  flex-shrink: 1 !important;\n}\n\n.justify-content-start {\n  -ms-flex-pack: start !important;\n  justify-content: flex-start !important;\n}\n\n.justify-content-end {\n  -ms-flex-pack: end !important;\n  justify-content: flex-end !important;\n}\n\n.justify-content-center {\n  -ms-flex-pack: center !important;\n  justify-content: center !important;\n}\n\n.justify-content-between {\n  -ms-flex-pack: justify !important;\n  justify-content: space-between !important;\n}\n\n.justify-content-around {\n  -ms-flex-pack: distribute !important;\n  justify-content: space-around !important;\n}\n\n.align-items-start {\n  -ms-flex-align: start !important;\n  align-items: flex-start !important;\n}\n\n.align-items-end {\n  -ms-flex-align: end !important;\n  align-items: flex-end !important;\n}\n\n.align-items-center {\n  -ms-flex-align: center !important;\n  align-items: center !important;\n}\n\n.align-items-baseline {\n  -ms-flex-align: baseline !important;\n  align-items: baseline !important;\n}\n\n.align-items-stretch {\n  -ms-flex-align: stretch !important;\n  align-items: stretch !important;\n}\n\n.align-content-start {\n  -ms-flex-line-pack: start !important;\n  align-content: flex-start !important;\n}\n\n.align-content-end {\n  -ms-flex-line-pack: end !important;\n  align-content: flex-end !important;\n}\n\n.align-content-center {\n  -ms-flex-line-pack: center !important;\n  align-content: center !important;\n}\n\n.align-content-between {\n  -ms-flex-line-pack: justify !important;\n  align-content: space-between !important;\n}\n\n.align-content-around {\n  -ms-flex-line-pack: distribute !important;\n  align-content: space-around !important;\n}\n\n.align-content-stretch {\n  -ms-flex-line-pack: stretch !important;\n  align-content: stretch !important;\n}\n\n.align-self-auto {\n  -ms-flex-item-align: auto !important;\n  align-self: auto !important;\n}\n\n.align-self-start {\n  -ms-flex-item-align: start !important;\n  align-self: flex-start !important;\n}\n\n.align-self-end {\n  -ms-flex-item-align: end !important;\n  align-self: flex-end !important;\n}\n\n.align-self-center {\n  -ms-flex-item-align: center !important;\n  align-self: center !important;\n}\n\n.align-self-baseline {\n  -ms-flex-item-align: baseline !important;\n  align-self: baseline !important;\n}\n\n.align-self-stretch {\n  -ms-flex-item-align: stretch !important;\n  align-self: stretch !important;\n}\n\n@media (min-width: 576px) {\n  .flex-sm-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-sm-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-sm-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-sm-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-sm-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-sm-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-sm-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-sm-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-sm-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-sm-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-sm-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-sm-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-sm-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-sm-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-sm-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-sm-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-sm-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-sm-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-sm-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-sm-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-sm-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-sm-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-sm-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-sm-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-sm-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-sm-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-sm-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-sm-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-sm-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-sm-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-sm-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-sm-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-sm-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-sm-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .flex-md-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-md-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-md-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-md-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-md-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-md-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-md-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-md-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-md-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-md-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-md-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-md-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-md-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-md-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-md-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-md-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-md-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-md-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-md-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-md-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-md-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-md-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-md-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-md-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-md-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-md-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-md-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-md-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-md-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-md-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-md-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-md-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-md-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-md-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .flex-lg-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-lg-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-lg-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-lg-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-lg-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-lg-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-lg-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-lg-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-lg-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-lg-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-lg-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-lg-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-lg-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-lg-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-lg-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-lg-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-lg-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-lg-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-lg-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-lg-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-lg-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-lg-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-lg-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-lg-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-lg-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-lg-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-lg-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-lg-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-lg-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-lg-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-lg-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-lg-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-lg-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-lg-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .flex-xl-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-xl-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-xl-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-xl-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-xl-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-xl-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-xl-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-xl-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-xl-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-xl-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-xl-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-xl-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-xl-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-xl-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-xl-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-xl-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-xl-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-xl-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-xl-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-xl-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-xl-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-xl-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-xl-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-xl-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-xl-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-xl-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-xl-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-xl-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-xl-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-xl-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-xl-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-xl-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-xl-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-xl-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n.float-left {\n  float: left !important;\n}\n\n.float-right {\n  float: right !important;\n}\n\n.float-none {\n  float: none !important;\n}\n\n@media (min-width: 576px) {\n  .float-sm-left {\n    float: left !important;\n  }\n  .float-sm-right {\n    float: right !important;\n  }\n  .float-sm-none {\n    float: none !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .float-md-left {\n    float: left !important;\n  }\n  .float-md-right {\n    float: right !important;\n  }\n  .float-md-none {\n    float: none !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .float-lg-left {\n    float: left !important;\n  }\n  .float-lg-right {\n    float: right !important;\n  }\n  .float-lg-none {\n    float: none !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .float-xl-left {\n    float: left !important;\n  }\n  .float-xl-right {\n    float: right !important;\n  }\n  .float-xl-none {\n    float: none !important;\n  }\n}\n\n.overflow-auto {\n  overflow: auto !important;\n}\n\n.overflow-hidden {\n  overflow: hidden !important;\n}\n\n.position-static {\n  position: static !important;\n}\n\n.position-relative {\n  position: relative !important;\n}\n\n.position-absolute {\n  position: absolute !important;\n}\n\n.position-fixed {\n  position: fixed !important;\n}\n\n.position-sticky {\n  position: -webkit-sticky !important;\n  position: sticky !important;\n}\n\n.fixed-top {\n  position: fixed;\n  top: 0;\n  right: 0;\n  left: 0;\n  z-index: 1030;\n}\n\n.fixed-bottom {\n  position: fixed;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  z-index: 1030;\n}\n\n@supports ((position: -webkit-sticky) or (position: sticky)) {\n  .sticky-top {\n    position: -webkit-sticky;\n    position: sticky;\n    top: 0;\n    z-index: 1020;\n  }\n}\n\n.sr-only {\n  position: absolute;\n  width: 1px;\n  height: 1px;\n  padding: 0;\n  overflow: hidden;\n  clip: rect(0, 0, 0, 0);\n  white-space: nowrap;\n  border: 0;\n}\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  position: static;\n  width: auto;\n  height: auto;\n  overflow: visible;\n  clip: auto;\n  white-space: normal;\n}\n\n.shadow-sm {\n  box-shadow: 0 0.125rem 0.25rem rgba(0, 0, 0, 0.075) !important;\n}\n\n.shadow {\n  box-shadow: 0 0.5rem 1rem rgba(0, 0, 0, 0.15) !important;\n}\n\n.shadow-lg {\n  box-shadow: 0 1rem 3rem rgba(0, 0, 0, 0.175) !important;\n}\n\n.shadow-none {\n  box-shadow: none !important;\n}\n\n.w-25 {\n  width: 25% !important;\n}\n\n.w-50 {\n  width: 50% !important;\n}\n\n.w-75 {\n  width: 75% !important;\n}\n\n.w-100 {\n  width: 100% !important;\n}\n\n.w-auto {\n  width: auto !important;\n}\n\n.h-25 {\n  height: 25% !important;\n}\n\n.h-50 {\n  height: 50% !important;\n}\n\n.h-75 {\n  height: 75% !important;\n}\n\n.h-100 {\n  height: 100% !important;\n}\n\n.h-auto {\n  height: auto !important;\n}\n\n.mw-100 {\n  max-width: 100% !important;\n}\n\n.mh-100 {\n  max-height: 100% !important;\n}\n\n.min-vw-100 {\n  min-width: 100vw !important;\n}\n\n.min-vh-100 {\n  min-height: 100vh !important;\n}\n\n.vw-100 {\n  width: 100vw !important;\n}\n\n.vh-100 {\n  height: 100vh !important;\n}\n\n.stretched-link::after {\n  position: absolute;\n  top: 0;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  z-index: 1;\n  pointer-events: auto;\n  content: \"\";\n  background-color: rgba(0, 0, 0, 0);\n}\n\n.m-0 {\n  margin: 0 !important;\n}\n\n.mt-0,\n.my-0 {\n  margin-top: 0 !important;\n}\n\n.mr-0,\n.mx-0 {\n  margin-right: 0 !important;\n}\n\n.mb-0,\n.my-0 {\n  margin-bottom: 0 !important;\n}\n\n.ml-0,\n.mx-0 {\n  margin-left: 0 !important;\n}\n\n.m-1 {\n  margin: 0.25rem !important;\n}\n\n.mt-1,\n.my-1 {\n  margin-top: 0.25rem !important;\n}\n\n.mr-1,\n.mx-1 {\n  margin-right: 0.25rem !important;\n}\n\n.mb-1,\n.my-1 {\n  margin-bottom: 0.25rem !important;\n}\n\n.ml-1,\n.mx-1 {\n  margin-left: 0.25rem !important;\n}\n\n.m-2 {\n  margin: 0.5rem !important;\n}\n\n.mt-2,\n.my-2 {\n  margin-top: 0.5rem !important;\n}\n\n.mr-2,\n.mx-2 {\n  margin-right: 0.5rem !important;\n}\n\n.mb-2,\n.my-2 {\n  margin-bottom: 0.5rem !important;\n}\n\n.ml-2,\n.mx-2 {\n  margin-left: 0.5rem !important;\n}\n\n.m-3 {\n  margin: 1rem !important;\n}\n\n.mt-3,\n.my-3 {\n  margin-top: 1rem !important;\n}\n\n.mr-3,\n.mx-3 {\n  margin-right: 1rem !important;\n}\n\n.mb-3,\n.my-3 {\n  margin-bottom: 1rem !important;\n}\n\n.ml-3,\n.mx-3 {\n  margin-left: 1rem !important;\n}\n\n.m-4 {\n  margin: 1.5rem !important;\n}\n\n.mt-4,\n.my-4 {\n  margin-top: 1.5rem !important;\n}\n\n.mr-4,\n.mx-4 {\n  margin-right: 1.5rem !important;\n}\n\n.mb-4,\n.my-4 {\n  margin-bottom: 1.5rem !important;\n}\n\n.ml-4,\n.mx-4 {\n  margin-left: 1.5rem !important;\n}\n\n.m-5 {\n  margin: 3rem !important;\n}\n\n.mt-5,\n.my-5 {\n  margin-top: 3rem !important;\n}\n\n.mr-5,\n.mx-5 {\n  margin-right: 3rem !important;\n}\n\n.mb-5,\n.my-5 {\n  margin-bottom: 3rem !important;\n}\n\n.ml-5,\n.mx-5 {\n  margin-left: 3rem !important;\n}\n\n.p-0 {\n  padding: 0 !important;\n}\n\n.pt-0,\n.py-0 {\n  padding-top: 0 !important;\n}\n\n.pr-0,\n.px-0 {\n  padding-right: 0 !important;\n}\n\n.pb-0,\n.py-0 {\n  padding-bottom: 0 !important;\n}\n\n.pl-0,\n.px-0 {\n  padding-left: 0 !important;\n}\n\n.p-1 {\n  padding: 0.25rem !important;\n}\n\n.pt-1,\n.py-1 {\n  padding-top: 0.25rem !important;\n}\n\n.pr-1,\n.px-1 {\n  padding-right: 0.25rem !important;\n}\n\n.pb-1,\n.py-1 {\n  padding-bottom: 0.25rem !important;\n}\n\n.pl-1,\n.px-1 {\n  padding-left: 0.25rem !important;\n}\n\n.p-2 {\n  padding: 0.5rem !important;\n}\n\n.pt-2,\n.py-2 {\n  padding-top: 0.5rem !important;\n}\n\n.pr-2,\n.px-2 {\n  padding-right: 0.5rem !important;\n}\n\n.pb-2,\n.py-2 {\n  padding-bottom: 0.5rem !important;\n}\n\n.pl-2,\n.px-2 {\n  padding-left: 0.5rem !important;\n}\n\n.p-3 {\n  padding: 1rem !important;\n}\n\n.pt-3,\n.py-3 {\n  padding-top: 1rem !important;\n}\n\n.pr-3,\n.px-3 {\n  padding-right: 1rem !important;\n}\n\n.pb-3,\n.py-3 {\n  padding-bottom: 1rem !important;\n}\n\n.pl-3,\n.px-3 {\n  padding-left: 1rem !important;\n}\n\n.p-4 {\n  padding: 1.5rem !important;\n}\n\n.pt-4,\n.py-4 {\n  padding-top: 1.5rem !important;\n}\n\n.pr-4,\n.px-4 {\n  padding-right: 1.5rem !important;\n}\n\n.pb-4,\n.py-4 {\n  padding-bottom: 1.5rem !important;\n}\n\n.pl-4,\n.px-4 {\n  padding-left: 1.5rem !important;\n}\n\n.p-5 {\n  padding: 3rem !important;\n}\n\n.pt-5,\n.py-5 {\n  padding-top: 3rem !important;\n}\n\n.pr-5,\n.px-5 {\n  padding-right: 3rem !important;\n}\n\n.pb-5,\n.py-5 {\n  padding-bottom: 3rem !important;\n}\n\n.pl-5,\n.px-5 {\n  padding-left: 3rem !important;\n}\n\n.m-n1 {\n  margin: -0.25rem !important;\n}\n\n.mt-n1,\n.my-n1 {\n  margin-top: -0.25rem !important;\n}\n\n.mr-n1,\n.mx-n1 {\n  margin-right: -0.25rem !important;\n}\n\n.mb-n1,\n.my-n1 {\n  margin-bottom: -0.25rem !important;\n}\n\n.ml-n1,\n.mx-n1 {\n  margin-left: -0.25rem !important;\n}\n\n.m-n2 {\n  margin: -0.5rem !important;\n}\n\n.mt-n2,\n.my-n2 {\n  margin-top: -0.5rem !important;\n}\n\n.mr-n2,\n.mx-n2 {\n  margin-right: -0.5rem !important;\n}\n\n.mb-n2,\n.my-n2 {\n  margin-bottom: -0.5rem !important;\n}\n\n.ml-n2,\n.mx-n2 {\n  margin-left: -0.5rem !important;\n}\n\n.m-n3 {\n  margin: -1rem !important;\n}\n\n.mt-n3,\n.my-n3 {\n  margin-top: -1rem !important;\n}\n\n.mr-n3,\n.mx-n3 {\n  margin-right: -1rem !important;\n}\n\n.mb-n3,\n.my-n3 {\n  margin-bottom: -1rem !important;\n}\n\n.ml-n3,\n.mx-n3 {\n  margin-left: -1rem !important;\n}\n\n.m-n4 {\n  margin: -1.5rem !important;\n}\n\n.mt-n4,\n.my-n4 {\n  margin-top: -1.5rem !important;\n}\n\n.mr-n4,\n.mx-n4 {\n  margin-right: -1.5rem !important;\n}\n\n.mb-n4,\n.my-n4 {\n  margin-bottom: -1.5rem !important;\n}\n\n.ml-n4,\n.mx-n4 {\n  margin-left: -1.5rem !important;\n}\n\n.m-n5 {\n  margin: -3rem !important;\n}\n\n.mt-n5,\n.my-n5 {\n  margin-top: -3rem !important;\n}\n\n.mr-n5,\n.mx-n5 {\n  margin-right: -3rem !important;\n}\n\n.mb-n5,\n.my-n5 {\n  margin-bottom: -3rem !important;\n}\n\n.ml-n5,\n.mx-n5 {\n  margin-left: -3rem !important;\n}\n\n.m-auto {\n  margin: auto !important;\n}\n\n.mt-auto,\n.my-auto {\n  margin-top: auto !important;\n}\n\n.mr-auto,\n.mx-auto {\n  margin-right: auto !important;\n}\n\n.mb-auto,\n.my-auto {\n  margin-bottom: auto !important;\n}\n\n.ml-auto,\n.mx-auto {\n  margin-left: auto !important;\n}\n\n@media (min-width: 576px) {\n  .m-sm-0 {\n    margin: 0 !important;\n  }\n  .mt-sm-0,\n  .my-sm-0 {\n    margin-top: 0 !important;\n  }\n  .mr-sm-0,\n  .mx-sm-0 {\n    margin-right: 0 !important;\n  }\n  .mb-sm-0,\n  .my-sm-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-sm-0,\n  .mx-sm-0 {\n    margin-left: 0 !important;\n  }\n  .m-sm-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-sm-1,\n  .my-sm-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-sm-1,\n  .mx-sm-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-sm-1,\n  .my-sm-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-sm-1,\n  .mx-sm-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-sm-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-sm-2,\n  .my-sm-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-sm-2,\n  .mx-sm-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-sm-2,\n  .my-sm-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-sm-2,\n  .mx-sm-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-sm-3 {\n    margin: 1rem !important;\n  }\n  .mt-sm-3,\n  .my-sm-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-sm-3,\n  .mx-sm-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-sm-3,\n  .my-sm-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-sm-3,\n  .mx-sm-3 {\n    margin-left: 1rem !important;\n  }\n  .m-sm-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-sm-4,\n  .my-sm-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-sm-4,\n  .mx-sm-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-sm-4,\n  .my-sm-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-sm-4,\n  .mx-sm-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-sm-5 {\n    margin: 3rem !important;\n  }\n  .mt-sm-5,\n  .my-sm-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-sm-5,\n  .mx-sm-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-sm-5,\n  .my-sm-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-sm-5,\n  .mx-sm-5 {\n    margin-left: 3rem !important;\n  }\n  .p-sm-0 {\n    padding: 0 !important;\n  }\n  .pt-sm-0,\n  .py-sm-0 {\n    padding-top: 0 !important;\n  }\n  .pr-sm-0,\n  .px-sm-0 {\n    padding-right: 0 !important;\n  }\n  .pb-sm-0,\n  .py-sm-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-sm-0,\n  .px-sm-0 {\n    padding-left: 0 !important;\n  }\n  .p-sm-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-sm-1,\n  .py-sm-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-sm-1,\n  .px-sm-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-sm-1,\n  .py-sm-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-sm-1,\n  .px-sm-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-sm-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-sm-2,\n  .py-sm-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-sm-2,\n  .px-sm-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-sm-2,\n  .py-sm-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-sm-2,\n  .px-sm-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-sm-3 {\n    padding: 1rem !important;\n  }\n  .pt-sm-3,\n  .py-sm-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-sm-3,\n  .px-sm-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-sm-3,\n  .py-sm-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-sm-3,\n  .px-sm-3 {\n    padding-left: 1rem !important;\n  }\n  .p-sm-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-sm-4,\n  .py-sm-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-sm-4,\n  .px-sm-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-sm-4,\n  .py-sm-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-sm-4,\n  .px-sm-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-sm-5 {\n    padding: 3rem !important;\n  }\n  .pt-sm-5,\n  .py-sm-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-sm-5,\n  .px-sm-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-sm-5,\n  .py-sm-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-sm-5,\n  .px-sm-5 {\n    padding-left: 3rem !important;\n  }\n  .m-sm-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-sm-n1,\n  .my-sm-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-sm-n1,\n  .mx-sm-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-sm-n1,\n  .my-sm-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-sm-n1,\n  .mx-sm-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-sm-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-sm-n2,\n  .my-sm-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-sm-n2,\n  .mx-sm-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-sm-n2,\n  .my-sm-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-sm-n2,\n  .mx-sm-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-sm-n3 {\n    margin: -1rem !important;\n  }\n  .mt-sm-n3,\n  .my-sm-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-sm-n3,\n  .mx-sm-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-sm-n3,\n  .my-sm-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-sm-n3,\n  .mx-sm-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-sm-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-sm-n4,\n  .my-sm-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-sm-n4,\n  .mx-sm-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-sm-n4,\n  .my-sm-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-sm-n4,\n  .mx-sm-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-sm-n5 {\n    margin: -3rem !important;\n  }\n  .mt-sm-n5,\n  .my-sm-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-sm-n5,\n  .mx-sm-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-sm-n5,\n  .my-sm-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-sm-n5,\n  .mx-sm-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-sm-auto {\n    margin: auto !important;\n  }\n  .mt-sm-auto,\n  .my-sm-auto {\n    margin-top: auto !important;\n  }\n  .mr-sm-auto,\n  .mx-sm-auto {\n    margin-right: auto !important;\n  }\n  .mb-sm-auto,\n  .my-sm-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-sm-auto,\n  .mx-sm-auto {\n    margin-left: auto !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .m-md-0 {\n    margin: 0 !important;\n  }\n  .mt-md-0,\n  .my-md-0 {\n    margin-top: 0 !important;\n  }\n  .mr-md-0,\n  .mx-md-0 {\n    margin-right: 0 !important;\n  }\n  .mb-md-0,\n  .my-md-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-md-0,\n  .mx-md-0 {\n    margin-left: 0 !important;\n  }\n  .m-md-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-md-1,\n  .my-md-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-md-1,\n  .mx-md-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-md-1,\n  .my-md-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-md-1,\n  .mx-md-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-md-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-md-2,\n  .my-md-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-md-2,\n  .mx-md-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-md-2,\n  .my-md-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-md-2,\n  .mx-md-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-md-3 {\n    margin: 1rem !important;\n  }\n  .mt-md-3,\n  .my-md-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-md-3,\n  .mx-md-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-md-3,\n  .my-md-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-md-3,\n  .mx-md-3 {\n    margin-left: 1rem !important;\n  }\n  .m-md-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-md-4,\n  .my-md-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-md-4,\n  .mx-md-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-md-4,\n  .my-md-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-md-4,\n  .mx-md-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-md-5 {\n    margin: 3rem !important;\n  }\n  .mt-md-5,\n  .my-md-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-md-5,\n  .mx-md-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-md-5,\n  .my-md-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-md-5,\n  .mx-md-5 {\n    margin-left: 3rem !important;\n  }\n  .p-md-0 {\n    padding: 0 !important;\n  }\n  .pt-md-0,\n  .py-md-0 {\n    padding-top: 0 !important;\n  }\n  .pr-md-0,\n  .px-md-0 {\n    padding-right: 0 !important;\n  }\n  .pb-md-0,\n  .py-md-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-md-0,\n  .px-md-0 {\n    padding-left: 0 !important;\n  }\n  .p-md-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-md-1,\n  .py-md-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-md-1,\n  .px-md-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-md-1,\n  .py-md-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-md-1,\n  .px-md-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-md-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-md-2,\n  .py-md-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-md-2,\n  .px-md-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-md-2,\n  .py-md-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-md-2,\n  .px-md-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-md-3 {\n    padding: 1rem !important;\n  }\n  .pt-md-3,\n  .py-md-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-md-3,\n  .px-md-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-md-3,\n  .py-md-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-md-3,\n  .px-md-3 {\n    padding-left: 1rem !important;\n  }\n  .p-md-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-md-4,\n  .py-md-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-md-4,\n  .px-md-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-md-4,\n  .py-md-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-md-4,\n  .px-md-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-md-5 {\n    padding: 3rem !important;\n  }\n  .pt-md-5,\n  .py-md-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-md-5,\n  .px-md-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-md-5,\n  .py-md-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-md-5,\n  .px-md-5 {\n    padding-left: 3rem !important;\n  }\n  .m-md-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-md-n1,\n  .my-md-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-md-n1,\n  .mx-md-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-md-n1,\n  .my-md-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-md-n1,\n  .mx-md-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-md-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-md-n2,\n  .my-md-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-md-n2,\n  .mx-md-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-md-n2,\n  .my-md-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-md-n2,\n  .mx-md-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-md-n3 {\n    margin: -1rem !important;\n  }\n  .mt-md-n3,\n  .my-md-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-md-n3,\n  .mx-md-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-md-n3,\n  .my-md-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-md-n3,\n  .mx-md-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-md-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-md-n4,\n  .my-md-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-md-n4,\n  .mx-md-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-md-n4,\n  .my-md-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-md-n4,\n  .mx-md-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-md-n5 {\n    margin: -3rem !important;\n  }\n  .mt-md-n5,\n  .my-md-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-md-n5,\n  .mx-md-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-md-n5,\n  .my-md-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-md-n5,\n  .mx-md-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-md-auto {\n    margin: auto !important;\n  }\n  .mt-md-auto,\n  .my-md-auto {\n    margin-top: auto !important;\n  }\n  .mr-md-auto,\n  .mx-md-auto {\n    margin-right: auto !important;\n  }\n  .mb-md-auto,\n  .my-md-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-md-auto,\n  .mx-md-auto {\n    margin-left: auto !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .m-lg-0 {\n    margin: 0 !important;\n  }\n  .mt-lg-0,\n  .my-lg-0 {\n    margin-top: 0 !important;\n  }\n  .mr-lg-0,\n  .mx-lg-0 {\n    margin-right: 0 !important;\n  }\n  .mb-lg-0,\n  .my-lg-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-lg-0,\n  .mx-lg-0 {\n    margin-left: 0 !important;\n  }\n  .m-lg-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-lg-1,\n  .my-lg-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-lg-1,\n  .mx-lg-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-lg-1,\n  .my-lg-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-lg-1,\n  .mx-lg-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-lg-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-lg-2,\n  .my-lg-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-lg-2,\n  .mx-lg-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-lg-2,\n  .my-lg-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-lg-2,\n  .mx-lg-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-lg-3 {\n    margin: 1rem !important;\n  }\n  .mt-lg-3,\n  .my-lg-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-lg-3,\n  .mx-lg-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-lg-3,\n  .my-lg-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-lg-3,\n  .mx-lg-3 {\n    margin-left: 1rem !important;\n  }\n  .m-lg-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-lg-4,\n  .my-lg-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-lg-4,\n  .mx-lg-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-lg-4,\n  .my-lg-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-lg-4,\n  .mx-lg-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-lg-5 {\n    margin: 3rem !important;\n  }\n  .mt-lg-5,\n  .my-lg-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-lg-5,\n  .mx-lg-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-lg-5,\n  .my-lg-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-lg-5,\n  .mx-lg-5 {\n    margin-left: 3rem !important;\n  }\n  .p-lg-0 {\n    padding: 0 !important;\n  }\n  .pt-lg-0,\n  .py-lg-0 {\n    padding-top: 0 !important;\n  }\n  .pr-lg-0,\n  .px-lg-0 {\n    padding-right: 0 !important;\n  }\n  .pb-lg-0,\n  .py-lg-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-lg-0,\n  .px-lg-0 {\n    padding-left: 0 !important;\n  }\n  .p-lg-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-lg-1,\n  .py-lg-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-lg-1,\n  .px-lg-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-lg-1,\n  .py-lg-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-lg-1,\n  .px-lg-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-lg-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-lg-2,\n  .py-lg-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-lg-2,\n  .px-lg-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-lg-2,\n  .py-lg-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-lg-2,\n  .px-lg-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-lg-3 {\n    padding: 1rem !important;\n  }\n  .pt-lg-3,\n  .py-lg-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-lg-3,\n  .px-lg-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-lg-3,\n  .py-lg-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-lg-3,\n  .px-lg-3 {\n    padding-left: 1rem !important;\n  }\n  .p-lg-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-lg-4,\n  .py-lg-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-lg-4,\n  .px-lg-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-lg-4,\n  .py-lg-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-lg-4,\n  .px-lg-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-lg-5 {\n    padding: 3rem !important;\n  }\n  .pt-lg-5,\n  .py-lg-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-lg-5,\n  .px-lg-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-lg-5,\n  .py-lg-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-lg-5,\n  .px-lg-5 {\n    padding-left: 3rem !important;\n  }\n  .m-lg-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-lg-n1,\n  .my-lg-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-lg-n1,\n  .mx-lg-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-lg-n1,\n  .my-lg-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-lg-n1,\n  .mx-lg-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-lg-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-lg-n2,\n  .my-lg-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-lg-n2,\n  .mx-lg-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-lg-n2,\n  .my-lg-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-lg-n2,\n  .mx-lg-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-lg-n3 {\n    margin: -1rem !important;\n  }\n  .mt-lg-n3,\n  .my-lg-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-lg-n3,\n  .mx-lg-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-lg-n3,\n  .my-lg-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-lg-n3,\n  .mx-lg-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-lg-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-lg-n4,\n  .my-lg-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-lg-n4,\n  .mx-lg-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-lg-n4,\n  .my-lg-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-lg-n4,\n  .mx-lg-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-lg-n5 {\n    margin: -3rem !important;\n  }\n  .mt-lg-n5,\n  .my-lg-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-lg-n5,\n  .mx-lg-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-lg-n5,\n  .my-lg-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-lg-n5,\n  .mx-lg-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-lg-auto {\n    margin: auto !important;\n  }\n  .mt-lg-auto,\n  .my-lg-auto {\n    margin-top: auto !important;\n  }\n  .mr-lg-auto,\n  .mx-lg-auto {\n    margin-right: auto !important;\n  }\n  .mb-lg-auto,\n  .my-lg-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-lg-auto,\n  .mx-lg-auto {\n    margin-left: auto !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .m-xl-0 {\n    margin: 0 !important;\n  }\n  .mt-xl-0,\n  .my-xl-0 {\n    margin-top: 0 !important;\n  }\n  .mr-xl-0,\n  .mx-xl-0 {\n    margin-right: 0 !important;\n  }\n  .mb-xl-0,\n  .my-xl-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-xl-0,\n  .mx-xl-0 {\n    margin-left: 0 !important;\n  }\n  .m-xl-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-xl-1,\n  .my-xl-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-xl-1,\n  .mx-xl-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-xl-1,\n  .my-xl-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-xl-1,\n  .mx-xl-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-xl-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-xl-2,\n  .my-xl-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-xl-2,\n  .mx-xl-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-xl-2,\n  .my-xl-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-xl-2,\n  .mx-xl-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-xl-3 {\n    margin: 1rem !important;\n  }\n  .mt-xl-3,\n  .my-xl-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-xl-3,\n  .mx-xl-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-xl-3,\n  .my-xl-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-xl-3,\n  .mx-xl-3 {\n    margin-left: 1rem !important;\n  }\n  .m-xl-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-xl-4,\n  .my-xl-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-xl-4,\n  .mx-xl-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-xl-4,\n  .my-xl-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-xl-4,\n  .mx-xl-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-xl-5 {\n    margin: 3rem !important;\n  }\n  .mt-xl-5,\n  .my-xl-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-xl-5,\n  .mx-xl-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-xl-5,\n  .my-xl-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-xl-5,\n  .mx-xl-5 {\n    margin-left: 3rem !important;\n  }\n  .p-xl-0 {\n    padding: 0 !important;\n  }\n  .pt-xl-0,\n  .py-xl-0 {\n    padding-top: 0 !important;\n  }\n  .pr-xl-0,\n  .px-xl-0 {\n    padding-right: 0 !important;\n  }\n  .pb-xl-0,\n  .py-xl-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-xl-0,\n  .px-xl-0 {\n    padding-left: 0 !important;\n  }\n  .p-xl-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-xl-1,\n  .py-xl-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-xl-1,\n  .px-xl-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-xl-1,\n  .py-xl-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-xl-1,\n  .px-xl-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-xl-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-xl-2,\n  .py-xl-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-xl-2,\n  .px-xl-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-xl-2,\n  .py-xl-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-xl-2,\n  .px-xl-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-xl-3 {\n    padding: 1rem !important;\n  }\n  .pt-xl-3,\n  .py-xl-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-xl-3,\n  .px-xl-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-xl-3,\n  .py-xl-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-xl-3,\n  .px-xl-3 {\n    padding-left: 1rem !important;\n  }\n  .p-xl-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-xl-4,\n  .py-xl-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-xl-4,\n  .px-xl-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-xl-4,\n  .py-xl-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-xl-4,\n  .px-xl-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-xl-5 {\n    padding: 3rem !important;\n  }\n  .pt-xl-5,\n  .py-xl-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-xl-5,\n  .px-xl-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-xl-5,\n  .py-xl-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-xl-5,\n  .px-xl-5 {\n    padding-left: 3rem !important;\n  }\n  .m-xl-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-xl-n1,\n  .my-xl-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-xl-n1,\n  .mx-xl-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-xl-n1,\n  .my-xl-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-xl-n1,\n  .mx-xl-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-xl-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-xl-n2,\n  .my-xl-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-xl-n2,\n  .mx-xl-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-xl-n2,\n  .my-xl-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-xl-n2,\n  .mx-xl-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-xl-n3 {\n    margin: -1rem !important;\n  }\n  .mt-xl-n3,\n  .my-xl-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-xl-n3,\n  .mx-xl-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-xl-n3,\n  .my-xl-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-xl-n3,\n  .mx-xl-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-xl-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-xl-n4,\n  .my-xl-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-xl-n4,\n  .mx-xl-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-xl-n4,\n  .my-xl-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-xl-n4,\n  .mx-xl-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-xl-n5 {\n    margin: -3rem !important;\n  }\n  .mt-xl-n5,\n  .my-xl-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-xl-n5,\n  .mx-xl-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-xl-n5,\n  .my-xl-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-xl-n5,\n  .mx-xl-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-xl-auto {\n    margin: auto !important;\n  }\n  .mt-xl-auto,\n  .my-xl-auto {\n    margin-top: auto !important;\n  }\n  .mr-xl-auto,\n  .mx-xl-auto {\n    margin-right: auto !important;\n  }\n  .mb-xl-auto,\n  .my-xl-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-xl-auto,\n  .mx-xl-auto {\n    margin-left: auto !important;\n  }\n}\n\n.text-monospace {\n  font-family: SFMono-Regular, Menlo, Monaco, Consolas, \"Liberation Mono\", \"Courier New\", monospace !important;\n}\n\n.text-justify {\n  text-align: justify !important;\n}\n\n.text-wrap {\n  white-space: normal !important;\n}\n\n.text-nowrap {\n  white-space: nowrap !important;\n}\n\n.text-truncate {\n  overflow: hidden;\n  text-overflow: ellipsis;\n  white-space: nowrap;\n}\n\n.text-left {\n  text-align: left !important;\n}\n\n.text-right {\n  text-align: right !important;\n}\n\n.text-center {\n  text-align: center !important;\n}\n\n@media (min-width: 576px) {\n  .text-sm-left {\n    text-align: left !important;\n  }\n  .text-sm-right {\n    text-align: right !important;\n  }\n  .text-sm-center {\n    text-align: center !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .text-md-left {\n    text-align: left !important;\n  }\n  .text-md-right {\n    text-align: right !important;\n  }\n  .text-md-center {\n    text-align: center !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .text-lg-left {\n    text-align: left !important;\n  }\n  .text-lg-right {\n    text-align: right !important;\n  }\n  .text-lg-center {\n    text-align: center !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .text-xl-left {\n    text-align: left !important;\n  }\n  .text-xl-right {\n    text-align: right !important;\n  }\n  .text-xl-center {\n    text-align: center !important;\n  }\n}\n\n.text-lowercase {\n  text-transform: lowercase !important;\n}\n\n.text-uppercase {\n  text-transform: uppercase !important;\n}\n\n.text-capitalize {\n  text-transform: capitalize !important;\n}\n\n.font-weight-light {\n  font-weight: 300 !important;\n}\n\n.font-weight-lighter {\n  font-weight: lighter !important;\n}\n\n.font-weight-normal {\n  font-weight: 400 !important;\n}\n\n.font-weight-bold {\n  font-weight: 700 !important;\n}\n\n.font-weight-bolder {\n  font-weight: bolder !important;\n}\n\n.font-italic {\n  font-style: italic !important;\n}\n\n.text-white {\n  color: #fff !important;\n}\n\n.text-primary {\n  color: #007bff !important;\n}\n\na.text-primary:hover, a.text-primary:focus {\n  color: #0056b3 !important;\n}\n\n.text-secondary {\n  color: #6c757d !important;\n}\n\na.text-secondary:hover, a.text-secondary:focus {\n  color: #494f54 !important;\n}\n\n.text-success {\n  color: #28a745 !important;\n}\n\na.text-success:hover, a.text-success:focus {\n  color: #19692c !important;\n}\n\n.text-info {\n  color: #17a2b8 !important;\n}\n\na.text-info:hover, a.text-info:focus {\n  color: #0f6674 !important;\n}\n\n.text-warning {\n  color: #ffc107 !important;\n}\n\na.text-warning:hover, a.text-warning:focus {\n  color: #ba8b00 !important;\n}\n\n.text-danger {\n  color: #dc3545 !important;\n}\n\na.text-danger:hover, a.text-danger:focus {\n  color: #a71d2a !important;\n}\n\n.text-light {\n  color: #f8f9fa !important;\n}\n\na.text-light:hover, a.text-light:focus {\n  color: #cbd3da !important;\n}\n\n.text-dark {\n  color: #343a40 !important;\n}\n\na.text-dark:hover, a.text-dark:focus {\n  color: #121416 !important;\n}\n\n.text-body {\n  color: #212529 !important;\n}\n\n.text-muted {\n  color: #6c757d !important;\n}\n\n.text-black-50 {\n  color: rgba(0, 0, 0, 0.5) !important;\n}\n\n.text-white-50 {\n  color: rgba(255, 255, 255, 0.5) !important;\n}\n\n.text-hide {\n  font: 0/0 a;\n  color: transparent;\n  text-shadow: none;\n  background-color: transparent;\n  border: 0;\n}\n\n.text-decoration-none {\n  text-decoration: none !important;\n}\n\n.text-break {\n  word-break: break-word !important;\n  overflow-wrap: break-word !important;\n}\n\n.text-reset {\n  color: inherit !important;\n}\n\n.visible {\n  visibility: visible !important;\n}\n\n.invisible {\n  visibility: hidden !important;\n}\n\n@media print {\n  *,\n  *::before,\n  *::after {\n    text-shadow: none !important;\n    box-shadow: none !important;\n  }\n  a:not(.btn) {\n    text-decoration: underline;\n  }\n  abbr[title]::after {\n    content: \" (\" attr(title) \")\";\n  }\n  pre {\n    white-space: pre-wrap !important;\n  }\n  pre,\n  blockquote {\n    border: 1px solid #adb5bd;\n    page-break-inside: avoid;\n  }\n  thead {\n    display: table-header-group;\n  }\n  tr,\n  img {\n    page-break-inside: avoid;\n  }\n  p,\n  h2,\n  h3 {\n    orphans: 3;\n    widows: 3;\n  }\n  h2,\n  h3 {\n    page-break-after: avoid;\n  }\n  @page {\n    size: a3;\n  }\n  body {\n    min-width: 992px !important;\n  }\n  .container {\n    min-width: 992px !important;\n  }\n  .navbar {\n    display: none;\n  }\n  .badge {\n    border: 1px solid #000;\n  }\n  .table {\n    border-collapse: collapse !important;\n  }\n  .table td,\n  .table th {\n    background-color: #fff !important;\n  }\n  .table-bordered th,\n  .table-bordered td {\n    border: 1px solid #dee2e6 !important;\n  }\n  .table-dark {\n    color: inherit;\n  }\n  .table-dark th,\n  .table-dark td,\n  .table-dark thead th,\n  .table-dark tbody + tbody {\n    border-color: #dee2e6;\n  }\n  .table .thead-dark th {\n    color: inherit;\n    border-color: #dee2e6;\n  }\n}\n/*# sourceMappingURL=bootstrap.css.map */"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/bootstrap/js/bootstrap.bundle.js",
    "content": "/*!\n  * Bootstrap v4.3.1 (https://getbootstrap.com/)\n  * Copyright 2011-2019 The Bootstrap Authors (https://github.com/twbs/bootstrap/graphs/contributors)\n  * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n  */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? factory(exports, require('jquery')) :\n  typeof define === 'function' && define.amd ? define(['exports', 'jquery'], factory) :\n  (global = global || self, factory(global.bootstrap = {}, global.jQuery));\n}(this, function (exports, $) { 'use strict';\n\n  $ = $ && $.hasOwnProperty('default') ? $['default'] : $;\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _inheritsLoose(subClass, superClass) {\n    subClass.prototype = Object.create(superClass.prototype);\n    subClass.prototype.constructor = subClass;\n    subClass.__proto__ = superClass;\n  }\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): util.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  /**\n   * ------------------------------------------------------------------------\n   * Private TransitionEnd Helpers\n   * ------------------------------------------------------------------------\n   */\n\n  var TRANSITION_END = 'transitionend';\n  var MAX_UID = 1000000;\n  var MILLISECONDS_MULTIPLIER = 1000; // Shoutout AngusCroll (https://goo.gl/pxwQGp)\n\n  function toType(obj) {\n    return {}.toString.call(obj).match(/\\s([a-z]+)/i)[1].toLowerCase();\n  }\n\n  function getSpecialTransitionEndEvent() {\n    return {\n      bindType: TRANSITION_END,\n      delegateType: TRANSITION_END,\n      handle: function handle(event) {\n        if ($(event.target).is(this)) {\n          return event.handleObj.handler.apply(this, arguments); // eslint-disable-line prefer-rest-params\n        }\n\n        return undefined; // eslint-disable-line no-undefined\n      }\n    };\n  }\n\n  function transitionEndEmulator(duration) {\n    var _this = this;\n\n    var called = false;\n    $(this).one(Util.TRANSITION_END, function () {\n      called = true;\n    });\n    setTimeout(function () {\n      if (!called) {\n        Util.triggerTransitionEnd(_this);\n      }\n    }, duration);\n    return this;\n  }\n\n  function setTransitionEndSupport() {\n    $.fn.emulateTransitionEnd = transitionEndEmulator;\n    $.event.special[Util.TRANSITION_END] = getSpecialTransitionEndEvent();\n  }\n  /**\n   * --------------------------------------------------------------------------\n   * Public Util Api\n   * --------------------------------------------------------------------------\n   */\n\n\n  var Util = {\n    TRANSITION_END: 'bsTransitionEnd',\n    getUID: function getUID(prefix) {\n      do {\n        // eslint-disable-next-line no-bitwise\n        prefix += ~~(Math.random() * MAX_UID); // \"~~\" acts like a faster Math.floor() here\n      } while (document.getElementById(prefix));\n\n      return prefix;\n    },\n    getSelectorFromElement: function getSelectorFromElement(element) {\n      var selector = element.getAttribute('data-target');\n\n      if (!selector || selector === '#') {\n        var hrefAttr = element.getAttribute('href');\n        selector = hrefAttr && hrefAttr !== '#' ? hrefAttr.trim() : '';\n      }\n\n      try {\n        return document.querySelector(selector) ? selector : null;\n      } catch (err) {\n        return null;\n      }\n    },\n    getTransitionDurationFromElement: function getTransitionDurationFromElement(element) {\n      if (!element) {\n        return 0;\n      } // Get transition-duration of the element\n\n\n      var transitionDuration = $(element).css('transition-duration');\n      var transitionDelay = $(element).css('transition-delay');\n      var floatTransitionDuration = parseFloat(transitionDuration);\n      var floatTransitionDelay = parseFloat(transitionDelay); // Return 0 if element or transition duration is not found\n\n      if (!floatTransitionDuration && !floatTransitionDelay) {\n        return 0;\n      } // If multiple durations are defined, take the first\n\n\n      transitionDuration = transitionDuration.split(',')[0];\n      transitionDelay = transitionDelay.split(',')[0];\n      return (parseFloat(transitionDuration) + parseFloat(transitionDelay)) * MILLISECONDS_MULTIPLIER;\n    },\n    reflow: function reflow(element) {\n      return element.offsetHeight;\n    },\n    triggerTransitionEnd: function triggerTransitionEnd(element) {\n      $(element).trigger(TRANSITION_END);\n    },\n    // TODO: Remove in v5\n    supportsTransitionEnd: function supportsTransitionEnd() {\n      return Boolean(TRANSITION_END);\n    },\n    isElement: function isElement(obj) {\n      return (obj[0] || obj).nodeType;\n    },\n    typeCheckConfig: function typeCheckConfig(componentName, config, configTypes) {\n      for (var property in configTypes) {\n        if (Object.prototype.hasOwnProperty.call(configTypes, property)) {\n          var expectedTypes = configTypes[property];\n          var value = config[property];\n          var valueType = value && Util.isElement(value) ? 'element' : toType(value);\n\n          if (!new RegExp(expectedTypes).test(valueType)) {\n            throw new Error(componentName.toUpperCase() + \": \" + (\"Option \\\"\" + property + \"\\\" provided type \\\"\" + valueType + \"\\\" \") + (\"but expected type \\\"\" + expectedTypes + \"\\\".\"));\n          }\n        }\n      }\n    },\n    findShadowRoot: function findShadowRoot(element) {\n      if (!document.documentElement.attachShadow) {\n        return null;\n      } // Can find the shadow root otherwise it'll return the document\n\n\n      if (typeof element.getRootNode === 'function') {\n        var root = element.getRootNode();\n        return root instanceof ShadowRoot ? root : null;\n      }\n\n      if (element instanceof ShadowRoot) {\n        return element;\n      } // when we don't find a shadow root\n\n\n      if (!element.parentNode) {\n        return null;\n      }\n\n      return Util.findShadowRoot(element.parentNode);\n    }\n  };\n  setTransitionEndSupport();\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME = 'alert';\n  var VERSION = '4.3.1';\n  var DATA_KEY = 'bs.alert';\n  var EVENT_KEY = \".\" + DATA_KEY;\n  var DATA_API_KEY = '.data-api';\n  var JQUERY_NO_CONFLICT = $.fn[NAME];\n  var Selector = {\n    DISMISS: '[data-dismiss=\"alert\"]'\n  };\n  var Event = {\n    CLOSE: \"close\" + EVENT_KEY,\n    CLOSED: \"closed\" + EVENT_KEY,\n    CLICK_DATA_API: \"click\" + EVENT_KEY + DATA_API_KEY\n  };\n  var ClassName = {\n    ALERT: 'alert',\n    FADE: 'fade',\n    SHOW: 'show'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Alert =\n  /*#__PURE__*/\n  function () {\n    function Alert(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Alert.prototype;\n\n    // Public\n    _proto.close = function close(element) {\n      var rootElement = this._element;\n\n      if (element) {\n        rootElement = this._getRootElement(element);\n      }\n\n      var customEvent = this._triggerCloseEvent(rootElement);\n\n      if (customEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._removeElement(rootElement);\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._getRootElement = function _getRootElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      var parent = false;\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      if (!parent) {\n        parent = $(element).closest(\".\" + ClassName.ALERT)[0];\n      }\n\n      return parent;\n    };\n\n    _proto._triggerCloseEvent = function _triggerCloseEvent(element) {\n      var closeEvent = $.Event(Event.CLOSE);\n      $(element).trigger(closeEvent);\n      return closeEvent;\n    };\n\n    _proto._removeElement = function _removeElement(element) {\n      var _this = this;\n\n      $(element).removeClass(ClassName.SHOW);\n\n      if (!$(element).hasClass(ClassName.FADE)) {\n        this._destroyElement(element);\n\n        return;\n      }\n\n      var transitionDuration = Util.getTransitionDurationFromElement(element);\n      $(element).one(Util.TRANSITION_END, function (event) {\n        return _this._destroyElement(element, event);\n      }).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto._destroyElement = function _destroyElement(element) {\n      $(element).detach().trigger(Event.CLOSED).remove();\n    } // Static\n    ;\n\n    Alert._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY);\n\n        if (!data) {\n          data = new Alert(this);\n          $element.data(DATA_KEY, data);\n        }\n\n        if (config === 'close') {\n          data[config](this);\n        }\n      });\n    };\n\n    Alert._handleDismiss = function _handleDismiss(alertInstance) {\n      return function (event) {\n        if (event) {\n          event.preventDefault();\n        }\n\n        alertInstance.close(this);\n      };\n    };\n\n    _createClass(Alert, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION;\n      }\n    }]);\n\n    return Alert;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event.CLICK_DATA_API, Selector.DISMISS, Alert._handleDismiss(new Alert()));\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME] = Alert._jQueryInterface;\n  $.fn[NAME].Constructor = Alert;\n\n  $.fn[NAME].noConflict = function () {\n    $.fn[NAME] = JQUERY_NO_CONFLICT;\n    return Alert._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$1 = 'button';\n  var VERSION$1 = '4.3.1';\n  var DATA_KEY$1 = 'bs.button';\n  var EVENT_KEY$1 = \".\" + DATA_KEY$1;\n  var DATA_API_KEY$1 = '.data-api';\n  var JQUERY_NO_CONFLICT$1 = $.fn[NAME$1];\n  var ClassName$1 = {\n    ACTIVE: 'active',\n    BUTTON: 'btn',\n    FOCUS: 'focus'\n  };\n  var Selector$1 = {\n    DATA_TOGGLE_CARROT: '[data-toggle^=\"button\"]',\n    DATA_TOGGLE: '[data-toggle=\"buttons\"]',\n    INPUT: 'input:not([type=\"hidden\"])',\n    ACTIVE: '.active',\n    BUTTON: '.btn'\n  };\n  var Event$1 = {\n    CLICK_DATA_API: \"click\" + EVENT_KEY$1 + DATA_API_KEY$1,\n    FOCUS_BLUR_DATA_API: \"focus\" + EVENT_KEY$1 + DATA_API_KEY$1 + \" \" + (\"blur\" + EVENT_KEY$1 + DATA_API_KEY$1)\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Button =\n  /*#__PURE__*/\n  function () {\n    function Button(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Button.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      var triggerChangeEvent = true;\n      var addAriaPressed = true;\n      var rootElement = $(this._element).closest(Selector$1.DATA_TOGGLE)[0];\n\n      if (rootElement) {\n        var input = this._element.querySelector(Selector$1.INPUT);\n\n        if (input) {\n          if (input.type === 'radio') {\n            if (input.checked && this._element.classList.contains(ClassName$1.ACTIVE)) {\n              triggerChangeEvent = false;\n            } else {\n              var activeElement = rootElement.querySelector(Selector$1.ACTIVE);\n\n              if (activeElement) {\n                $(activeElement).removeClass(ClassName$1.ACTIVE);\n              }\n            }\n          }\n\n          if (triggerChangeEvent) {\n            if (input.hasAttribute('disabled') || rootElement.hasAttribute('disabled') || input.classList.contains('disabled') || rootElement.classList.contains('disabled')) {\n              return;\n            }\n\n            input.checked = !this._element.classList.contains(ClassName$1.ACTIVE);\n            $(input).trigger('change');\n          }\n\n          input.focus();\n          addAriaPressed = false;\n        }\n      }\n\n      if (addAriaPressed) {\n        this._element.setAttribute('aria-pressed', !this._element.classList.contains(ClassName$1.ACTIVE));\n      }\n\n      if (triggerChangeEvent) {\n        $(this._element).toggleClass(ClassName$1.ACTIVE);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$1);\n      this._element = null;\n    } // Static\n    ;\n\n    Button._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$1);\n\n        if (!data) {\n          data = new Button(this);\n          $(this).data(DATA_KEY$1, data);\n        }\n\n        if (config === 'toggle') {\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Button, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$1;\n      }\n    }]);\n\n    return Button;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$1.CLICK_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    event.preventDefault();\n    var button = event.target;\n\n    if (!$(button).hasClass(ClassName$1.BUTTON)) {\n      button = $(button).closest(Selector$1.BUTTON);\n    }\n\n    Button._jQueryInterface.call($(button), 'toggle');\n  }).on(Event$1.FOCUS_BLUR_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    var button = $(event.target).closest(Selector$1.BUTTON)[0];\n    $(button).toggleClass(ClassName$1.FOCUS, /^focus(in)?$/.test(event.type));\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$1] = Button._jQueryInterface;\n  $.fn[NAME$1].Constructor = Button;\n\n  $.fn[NAME$1].noConflict = function () {\n    $.fn[NAME$1] = JQUERY_NO_CONFLICT$1;\n    return Button._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$2 = 'carousel';\n  var VERSION$2 = '4.3.1';\n  var DATA_KEY$2 = 'bs.carousel';\n  var EVENT_KEY$2 = \".\" + DATA_KEY$2;\n  var DATA_API_KEY$2 = '.data-api';\n  var JQUERY_NO_CONFLICT$2 = $.fn[NAME$2];\n  var ARROW_LEFT_KEYCODE = 37; // KeyboardEvent.which value for left arrow key\n\n  var ARROW_RIGHT_KEYCODE = 39; // KeyboardEvent.which value for right arrow key\n\n  var TOUCHEVENT_COMPAT_WAIT = 500; // Time for mouse compat events to fire after touch\n\n  var SWIPE_THRESHOLD = 40;\n  var Default = {\n    interval: 5000,\n    keyboard: true,\n    slide: false,\n    pause: 'hover',\n    wrap: true,\n    touch: true\n  };\n  var DefaultType = {\n    interval: '(number|boolean)',\n    keyboard: 'boolean',\n    slide: '(boolean|string)',\n    pause: '(string|boolean)',\n    wrap: 'boolean',\n    touch: 'boolean'\n  };\n  var Direction = {\n    NEXT: 'next',\n    PREV: 'prev',\n    LEFT: 'left',\n    RIGHT: 'right'\n  };\n  var Event$2 = {\n    SLIDE: \"slide\" + EVENT_KEY$2,\n    SLID: \"slid\" + EVENT_KEY$2,\n    KEYDOWN: \"keydown\" + EVENT_KEY$2,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$2,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$2,\n    TOUCHSTART: \"touchstart\" + EVENT_KEY$2,\n    TOUCHMOVE: \"touchmove\" + EVENT_KEY$2,\n    TOUCHEND: \"touchend\" + EVENT_KEY$2,\n    POINTERDOWN: \"pointerdown\" + EVENT_KEY$2,\n    POINTERUP: \"pointerup\" + EVENT_KEY$2,\n    DRAG_START: \"dragstart\" + EVENT_KEY$2,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$2 + DATA_API_KEY$2,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$2 + DATA_API_KEY$2\n  };\n  var ClassName$2 = {\n    CAROUSEL: 'carousel',\n    ACTIVE: 'active',\n    SLIDE: 'slide',\n    RIGHT: 'carousel-item-right',\n    LEFT: 'carousel-item-left',\n    NEXT: 'carousel-item-next',\n    PREV: 'carousel-item-prev',\n    ITEM: 'carousel-item',\n    POINTER_EVENT: 'pointer-event'\n  };\n  var Selector$2 = {\n    ACTIVE: '.active',\n    ACTIVE_ITEM: '.active.carousel-item',\n    ITEM: '.carousel-item',\n    ITEM_IMG: '.carousel-item img',\n    NEXT_PREV: '.carousel-item-next, .carousel-item-prev',\n    INDICATORS: '.carousel-indicators',\n    DATA_SLIDE: '[data-slide], [data-slide-to]',\n    DATA_RIDE: '[data-ride=\"carousel\"]'\n  };\n  var PointerType = {\n    TOUCH: 'touch',\n    PEN: 'pen'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Carousel =\n  /*#__PURE__*/\n  function () {\n    function Carousel(element, config) {\n      this._items = null;\n      this._interval = null;\n      this._activeElement = null;\n      this._isPaused = false;\n      this._isSliding = false;\n      this.touchTimeout = null;\n      this.touchStartX = 0;\n      this.touchDeltaX = 0;\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._indicatorsElement = this._element.querySelector(Selector$2.INDICATORS);\n      this._touchSupported = 'ontouchstart' in document.documentElement || navigator.maxTouchPoints > 0;\n      this._pointerEvent = Boolean(window.PointerEvent || window.MSPointerEvent);\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Carousel.prototype;\n\n    // Public\n    _proto.next = function next() {\n      if (!this._isSliding) {\n        this._slide(Direction.NEXT);\n      }\n    };\n\n    _proto.nextWhenVisible = function nextWhenVisible() {\n      // Don't call next when the page isn't visible\n      // or the carousel or its parent isn't visible\n      if (!document.hidden && $(this._element).is(':visible') && $(this._element).css('visibility') !== 'hidden') {\n        this.next();\n      }\n    };\n\n    _proto.prev = function prev() {\n      if (!this._isSliding) {\n        this._slide(Direction.PREV);\n      }\n    };\n\n    _proto.pause = function pause(event) {\n      if (!event) {\n        this._isPaused = true;\n      }\n\n      if (this._element.querySelector(Selector$2.NEXT_PREV)) {\n        Util.triggerTransitionEnd(this._element);\n        this.cycle(true);\n      }\n\n      clearInterval(this._interval);\n      this._interval = null;\n    };\n\n    _proto.cycle = function cycle(event) {\n      if (!event) {\n        this._isPaused = false;\n      }\n\n      if (this._interval) {\n        clearInterval(this._interval);\n        this._interval = null;\n      }\n\n      if (this._config.interval && !this._isPaused) {\n        this._interval = setInterval((document.visibilityState ? this.nextWhenVisible : this.next).bind(this), this._config.interval);\n      }\n    };\n\n    _proto.to = function to(index) {\n      var _this = this;\n\n      this._activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeIndex = this._getItemIndex(this._activeElement);\n\n      if (index > this._items.length - 1 || index < 0) {\n        return;\n      }\n\n      if (this._isSliding) {\n        $(this._element).one(Event$2.SLID, function () {\n          return _this.to(index);\n        });\n        return;\n      }\n\n      if (activeIndex === index) {\n        this.pause();\n        this.cycle();\n        return;\n      }\n\n      var direction = index > activeIndex ? Direction.NEXT : Direction.PREV;\n\n      this._slide(direction, this._items[index]);\n    };\n\n    _proto.dispose = function dispose() {\n      $(this._element).off(EVENT_KEY$2);\n      $.removeData(this._element, DATA_KEY$2);\n      this._items = null;\n      this._config = null;\n      this._element = null;\n      this._interval = null;\n      this._isPaused = null;\n      this._isSliding = null;\n      this._activeElement = null;\n      this._indicatorsElement = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default, config);\n      Util.typeCheckConfig(NAME$2, config, DefaultType);\n      return config;\n    };\n\n    _proto._handleSwipe = function _handleSwipe() {\n      var absDeltax = Math.abs(this.touchDeltaX);\n\n      if (absDeltax <= SWIPE_THRESHOLD) {\n        return;\n      }\n\n      var direction = absDeltax / this.touchDeltaX; // swipe left\n\n      if (direction > 0) {\n        this.prev();\n      } // swipe right\n\n\n      if (direction < 0) {\n        this.next();\n      }\n    };\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this2 = this;\n\n      if (this._config.keyboard) {\n        $(this._element).on(Event$2.KEYDOWN, function (event) {\n          return _this2._keydown(event);\n        });\n      }\n\n      if (this._config.pause === 'hover') {\n        $(this._element).on(Event$2.MOUSEENTER, function (event) {\n          return _this2.pause(event);\n        }).on(Event$2.MOUSELEAVE, function (event) {\n          return _this2.cycle(event);\n        });\n      }\n\n      if (this._config.touch) {\n        this._addTouchEventListeners();\n      }\n    };\n\n    _proto._addTouchEventListeners = function _addTouchEventListeners() {\n      var _this3 = this;\n\n      if (!this._touchSupported) {\n        return;\n      }\n\n      var start = function start(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchStartX = event.originalEvent.clientX;\n        } else if (!_this3._pointerEvent) {\n          _this3.touchStartX = event.originalEvent.touches[0].clientX;\n        }\n      };\n\n      var move = function move(event) {\n        // ensure swiping with one touch and not pinching\n        if (event.originalEvent.touches && event.originalEvent.touches.length > 1) {\n          _this3.touchDeltaX = 0;\n        } else {\n          _this3.touchDeltaX = event.originalEvent.touches[0].clientX - _this3.touchStartX;\n        }\n      };\n\n      var end = function end(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchDeltaX = event.originalEvent.clientX - _this3.touchStartX;\n        }\n\n        _this3._handleSwipe();\n\n        if (_this3._config.pause === 'hover') {\n          // If it's a touch-enabled device, mouseenter/leave are fired as\n          // part of the mouse compatibility events on first tap - the carousel\n          // would stop cycling until user tapped out of it;\n          // here, we listen for touchend, explicitly pause the carousel\n          // (as if it's the second time we tap on it, mouseenter compat event\n          // is NOT fired) and after a timeout (to allow for mouse compatibility\n          // events to fire) we explicitly restart cycling\n          _this3.pause();\n\n          if (_this3.touchTimeout) {\n            clearTimeout(_this3.touchTimeout);\n          }\n\n          _this3.touchTimeout = setTimeout(function (event) {\n            return _this3.cycle(event);\n          }, TOUCHEVENT_COMPAT_WAIT + _this3._config.interval);\n        }\n      };\n\n      $(this._element.querySelectorAll(Selector$2.ITEM_IMG)).on(Event$2.DRAG_START, function (e) {\n        return e.preventDefault();\n      });\n\n      if (this._pointerEvent) {\n        $(this._element).on(Event$2.POINTERDOWN, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.POINTERUP, function (event) {\n          return end(event);\n        });\n\n        this._element.classList.add(ClassName$2.POINTER_EVENT);\n      } else {\n        $(this._element).on(Event$2.TOUCHSTART, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.TOUCHMOVE, function (event) {\n          return move(event);\n        });\n        $(this._element).on(Event$2.TOUCHEND, function (event) {\n          return end(event);\n        });\n      }\n    };\n\n    _proto._keydown = function _keydown(event) {\n      if (/input|textarea/i.test(event.target.tagName)) {\n        return;\n      }\n\n      switch (event.which) {\n        case ARROW_LEFT_KEYCODE:\n          event.preventDefault();\n          this.prev();\n          break;\n\n        case ARROW_RIGHT_KEYCODE:\n          event.preventDefault();\n          this.next();\n          break;\n\n        default:\n      }\n    };\n\n    _proto._getItemIndex = function _getItemIndex(element) {\n      this._items = element && element.parentNode ? [].slice.call(element.parentNode.querySelectorAll(Selector$2.ITEM)) : [];\n      return this._items.indexOf(element);\n    };\n\n    _proto._getItemByDirection = function _getItemByDirection(direction, activeElement) {\n      var isNextDirection = direction === Direction.NEXT;\n      var isPrevDirection = direction === Direction.PREV;\n\n      var activeIndex = this._getItemIndex(activeElement);\n\n      var lastItemIndex = this._items.length - 1;\n      var isGoingToWrap = isPrevDirection && activeIndex === 0 || isNextDirection && activeIndex === lastItemIndex;\n\n      if (isGoingToWrap && !this._config.wrap) {\n        return activeElement;\n      }\n\n      var delta = direction === Direction.PREV ? -1 : 1;\n      var itemIndex = (activeIndex + delta) % this._items.length;\n      return itemIndex === -1 ? this._items[this._items.length - 1] : this._items[itemIndex];\n    };\n\n    _proto._triggerSlideEvent = function _triggerSlideEvent(relatedTarget, eventDirectionName) {\n      var targetIndex = this._getItemIndex(relatedTarget);\n\n      var fromIndex = this._getItemIndex(this._element.querySelector(Selector$2.ACTIVE_ITEM));\n\n      var slideEvent = $.Event(Event$2.SLIDE, {\n        relatedTarget: relatedTarget,\n        direction: eventDirectionName,\n        from: fromIndex,\n        to: targetIndex\n      });\n      $(this._element).trigger(slideEvent);\n      return slideEvent;\n    };\n\n    _proto._setActiveIndicatorElement = function _setActiveIndicatorElement(element) {\n      if (this._indicatorsElement) {\n        var indicators = [].slice.call(this._indicatorsElement.querySelectorAll(Selector$2.ACTIVE));\n        $(indicators).removeClass(ClassName$2.ACTIVE);\n\n        var nextIndicator = this._indicatorsElement.children[this._getItemIndex(element)];\n\n        if (nextIndicator) {\n          $(nextIndicator).addClass(ClassName$2.ACTIVE);\n        }\n      }\n    };\n\n    _proto._slide = function _slide(direction, element) {\n      var _this4 = this;\n\n      var activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeElementIndex = this._getItemIndex(activeElement);\n\n      var nextElement = element || activeElement && this._getItemByDirection(direction, activeElement);\n\n      var nextElementIndex = this._getItemIndex(nextElement);\n\n      var isCycling = Boolean(this._interval);\n      var directionalClassName;\n      var orderClassName;\n      var eventDirectionName;\n\n      if (direction === Direction.NEXT) {\n        directionalClassName = ClassName$2.LEFT;\n        orderClassName = ClassName$2.NEXT;\n        eventDirectionName = Direction.LEFT;\n      } else {\n        directionalClassName = ClassName$2.RIGHT;\n        orderClassName = ClassName$2.PREV;\n        eventDirectionName = Direction.RIGHT;\n      }\n\n      if (nextElement && $(nextElement).hasClass(ClassName$2.ACTIVE)) {\n        this._isSliding = false;\n        return;\n      }\n\n      var slideEvent = this._triggerSlideEvent(nextElement, eventDirectionName);\n\n      if (slideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (!activeElement || !nextElement) {\n        // Some weirdness is happening, so we bail\n        return;\n      }\n\n      this._isSliding = true;\n\n      if (isCycling) {\n        this.pause();\n      }\n\n      this._setActiveIndicatorElement(nextElement);\n\n      var slidEvent = $.Event(Event$2.SLID, {\n        relatedTarget: nextElement,\n        direction: eventDirectionName,\n        from: activeElementIndex,\n        to: nextElementIndex\n      });\n\n      if ($(this._element).hasClass(ClassName$2.SLIDE)) {\n        $(nextElement).addClass(orderClassName);\n        Util.reflow(nextElement);\n        $(activeElement).addClass(directionalClassName);\n        $(nextElement).addClass(directionalClassName);\n        var nextElementInterval = parseInt(nextElement.getAttribute('data-interval'), 10);\n\n        if (nextElementInterval) {\n          this._config.defaultInterval = this._config.defaultInterval || this._config.interval;\n          this._config.interval = nextElementInterval;\n        } else {\n          this._config.interval = this._config.defaultInterval || this._config.interval;\n        }\n\n        var transitionDuration = Util.getTransitionDurationFromElement(activeElement);\n        $(activeElement).one(Util.TRANSITION_END, function () {\n          $(nextElement).removeClass(directionalClassName + \" \" + orderClassName).addClass(ClassName$2.ACTIVE);\n          $(activeElement).removeClass(ClassName$2.ACTIVE + \" \" + orderClassName + \" \" + directionalClassName);\n          _this4._isSliding = false;\n          setTimeout(function () {\n            return $(_this4._element).trigger(slidEvent);\n          }, 0);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        $(activeElement).removeClass(ClassName$2.ACTIVE);\n        $(nextElement).addClass(ClassName$2.ACTIVE);\n        this._isSliding = false;\n        $(this._element).trigger(slidEvent);\n      }\n\n      if (isCycling) {\n        this.cycle();\n      }\n    } // Static\n    ;\n\n    Carousel._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$2);\n\n        var _config = _objectSpread({}, Default, $(this).data());\n\n        if (typeof config === 'object') {\n          _config = _objectSpread({}, _config, config);\n        }\n\n        var action = typeof config === 'string' ? config : _config.slide;\n\n        if (!data) {\n          data = new Carousel(this, _config);\n          $(this).data(DATA_KEY$2, data);\n        }\n\n        if (typeof config === 'number') {\n          data.to(config);\n        } else if (typeof action === 'string') {\n          if (typeof data[action] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + action + \"\\\"\");\n          }\n\n          data[action]();\n        } else if (_config.interval && _config.ride) {\n          data.pause();\n          data.cycle();\n        }\n      });\n    };\n\n    Carousel._dataApiClickHandler = function _dataApiClickHandler(event) {\n      var selector = Util.getSelectorFromElement(this);\n\n      if (!selector) {\n        return;\n      }\n\n      var target = $(selector)[0];\n\n      if (!target || !$(target).hasClass(ClassName$2.CAROUSEL)) {\n        return;\n      }\n\n      var config = _objectSpread({}, $(target).data(), $(this).data());\n\n      var slideIndex = this.getAttribute('data-slide-to');\n\n      if (slideIndex) {\n        config.interval = false;\n      }\n\n      Carousel._jQueryInterface.call($(target), config);\n\n      if (slideIndex) {\n        $(target).data(DATA_KEY$2).to(slideIndex);\n      }\n\n      event.preventDefault();\n    };\n\n    _createClass(Carousel, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$2;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default;\n      }\n    }]);\n\n    return Carousel;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$2.CLICK_DATA_API, Selector$2.DATA_SLIDE, Carousel._dataApiClickHandler);\n  $(window).on(Event$2.LOAD_DATA_API, function () {\n    var carousels = [].slice.call(document.querySelectorAll(Selector$2.DATA_RIDE));\n\n    for (var i = 0, len = carousels.length; i < len; i++) {\n      var $carousel = $(carousels[i]);\n\n      Carousel._jQueryInterface.call($carousel, $carousel.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$2] = Carousel._jQueryInterface;\n  $.fn[NAME$2].Constructor = Carousel;\n\n  $.fn[NAME$2].noConflict = function () {\n    $.fn[NAME$2] = JQUERY_NO_CONFLICT$2;\n    return Carousel._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$3 = 'collapse';\n  var VERSION$3 = '4.3.1';\n  var DATA_KEY$3 = 'bs.collapse';\n  var EVENT_KEY$3 = \".\" + DATA_KEY$3;\n  var DATA_API_KEY$3 = '.data-api';\n  var JQUERY_NO_CONFLICT$3 = $.fn[NAME$3];\n  var Default$1 = {\n    toggle: true,\n    parent: ''\n  };\n  var DefaultType$1 = {\n    toggle: 'boolean',\n    parent: '(string|element)'\n  };\n  var Event$3 = {\n    SHOW: \"show\" + EVENT_KEY$3,\n    SHOWN: \"shown\" + EVENT_KEY$3,\n    HIDE: \"hide\" + EVENT_KEY$3,\n    HIDDEN: \"hidden\" + EVENT_KEY$3,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$3 + DATA_API_KEY$3\n  };\n  var ClassName$3 = {\n    SHOW: 'show',\n    COLLAPSE: 'collapse',\n    COLLAPSING: 'collapsing',\n    COLLAPSED: 'collapsed'\n  };\n  var Dimension = {\n    WIDTH: 'width',\n    HEIGHT: 'height'\n  };\n  var Selector$3 = {\n    ACTIVES: '.show, .collapsing',\n    DATA_TOGGLE: '[data-toggle=\"collapse\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Collapse =\n  /*#__PURE__*/\n  function () {\n    function Collapse(element, config) {\n      this._isTransitioning = false;\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._triggerArray = [].slice.call(document.querySelectorAll(\"[data-toggle=\\\"collapse\\\"][href=\\\"#\" + element.id + \"\\\"],\" + (\"[data-toggle=\\\"collapse\\\"][data-target=\\\"#\" + element.id + \"\\\"]\")));\n      var toggleList = [].slice.call(document.querySelectorAll(Selector$3.DATA_TOGGLE));\n\n      for (var i = 0, len = toggleList.length; i < len; i++) {\n        var elem = toggleList[i];\n        var selector = Util.getSelectorFromElement(elem);\n        var filterElement = [].slice.call(document.querySelectorAll(selector)).filter(function (foundElem) {\n          return foundElem === element;\n        });\n\n        if (selector !== null && filterElement.length > 0) {\n          this._selector = selector;\n\n          this._triggerArray.push(elem);\n        }\n      }\n\n      this._parent = this._config.parent ? this._getParent() : null;\n\n      if (!this._config.parent) {\n        this._addAriaAndCollapsedClass(this._element, this._triggerArray);\n      }\n\n      if (this._config.toggle) {\n        this.toggle();\n      }\n    } // Getters\n\n\n    var _proto = Collapse.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if ($(this._element).hasClass(ClassName$3.SHOW)) {\n        this.hide();\n      } else {\n        this.show();\n      }\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._isTransitioning || $(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var actives;\n      var activesData;\n\n      if (this._parent) {\n        actives = [].slice.call(this._parent.querySelectorAll(Selector$3.ACTIVES)).filter(function (elem) {\n          if (typeof _this._config.parent === 'string') {\n            return elem.getAttribute('data-parent') === _this._config.parent;\n          }\n\n          return elem.classList.contains(ClassName$3.COLLAPSE);\n        });\n\n        if (actives.length === 0) {\n          actives = null;\n        }\n      }\n\n      if (actives) {\n        activesData = $(actives).not(this._selector).data(DATA_KEY$3);\n\n        if (activesData && activesData._isTransitioning) {\n          return;\n        }\n      }\n\n      var startEvent = $.Event(Event$3.SHOW);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (actives) {\n        Collapse._jQueryInterface.call($(actives).not(this._selector), 'hide');\n\n        if (!activesData) {\n          $(actives).data(DATA_KEY$3, null);\n        }\n      }\n\n      var dimension = this._getDimension();\n\n      $(this._element).removeClass(ClassName$3.COLLAPSE).addClass(ClassName$3.COLLAPSING);\n      this._element.style[dimension] = 0;\n\n      if (this._triggerArray.length) {\n        $(this._triggerArray).removeClass(ClassName$3.COLLAPSED).attr('aria-expanded', true);\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        $(_this._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).addClass(ClassName$3.SHOW);\n        _this._element.style[dimension] = '';\n\n        _this.setTransitioning(false);\n\n        $(_this._element).trigger(Event$3.SHOWN);\n      };\n\n      var capitalizedDimension = dimension[0].toUpperCase() + dimension.slice(1);\n      var scrollSize = \"scroll\" + capitalizedDimension;\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      this._element.style[dimension] = this._element[scrollSize] + \"px\";\n    };\n\n    _proto.hide = function hide() {\n      var _this2 = this;\n\n      if (this._isTransitioning || !$(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var startEvent = $.Event(Event$3.HIDE);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      var dimension = this._getDimension();\n\n      this._element.style[dimension] = this._element.getBoundingClientRect()[dimension] + \"px\";\n      Util.reflow(this._element);\n      $(this._element).addClass(ClassName$3.COLLAPSING).removeClass(ClassName$3.COLLAPSE).removeClass(ClassName$3.SHOW);\n      var triggerArrayLength = this._triggerArray.length;\n\n      if (triggerArrayLength > 0) {\n        for (var i = 0; i < triggerArrayLength; i++) {\n          var trigger = this._triggerArray[i];\n          var selector = Util.getSelectorFromElement(trigger);\n\n          if (selector !== null) {\n            var $elem = $([].slice.call(document.querySelectorAll(selector)));\n\n            if (!$elem.hasClass(ClassName$3.SHOW)) {\n              $(trigger).addClass(ClassName$3.COLLAPSED).attr('aria-expanded', false);\n            }\n          }\n        }\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        _this2.setTransitioning(false);\n\n        $(_this2._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).trigger(Event$3.HIDDEN);\n      };\n\n      this._element.style[dimension] = '';\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto.setTransitioning = function setTransitioning(isTransitioning) {\n      this._isTransitioning = isTransitioning;\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$3);\n      this._config = null;\n      this._parent = null;\n      this._element = null;\n      this._triggerArray = null;\n      this._isTransitioning = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$1, config);\n      config.toggle = Boolean(config.toggle); // Coerce string values\n\n      Util.typeCheckConfig(NAME$3, config, DefaultType$1);\n      return config;\n    };\n\n    _proto._getDimension = function _getDimension() {\n      var hasWidth = $(this._element).hasClass(Dimension.WIDTH);\n      return hasWidth ? Dimension.WIDTH : Dimension.HEIGHT;\n    };\n\n    _proto._getParent = function _getParent() {\n      var _this3 = this;\n\n      var parent;\n\n      if (Util.isElement(this._config.parent)) {\n        parent = this._config.parent; // It's a jQuery object\n\n        if (typeof this._config.parent.jquery !== 'undefined') {\n          parent = this._config.parent[0];\n        }\n      } else {\n        parent = document.querySelector(this._config.parent);\n      }\n\n      var selector = \"[data-toggle=\\\"collapse\\\"][data-parent=\\\"\" + this._config.parent + \"\\\"]\";\n      var children = [].slice.call(parent.querySelectorAll(selector));\n      $(children).each(function (i, element) {\n        _this3._addAriaAndCollapsedClass(Collapse._getTargetFromElement(element), [element]);\n      });\n      return parent;\n    };\n\n    _proto._addAriaAndCollapsedClass = function _addAriaAndCollapsedClass(element, triggerArray) {\n      var isOpen = $(element).hasClass(ClassName$3.SHOW);\n\n      if (triggerArray.length) {\n        $(triggerArray).toggleClass(ClassName$3.COLLAPSED, !isOpen).attr('aria-expanded', isOpen);\n      }\n    } // Static\n    ;\n\n    Collapse._getTargetFromElement = function _getTargetFromElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      return selector ? document.querySelector(selector) : null;\n    };\n\n    Collapse._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$3);\n\n        var _config = _objectSpread({}, Default$1, $this.data(), typeof config === 'object' && config ? config : {});\n\n        if (!data && _config.toggle && /show|hide/.test(config)) {\n          _config.toggle = false;\n        }\n\n        if (!data) {\n          data = new Collapse(this, _config);\n          $this.data(DATA_KEY$3, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Collapse, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$3;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$1;\n      }\n    }]);\n\n    return Collapse;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$3.CLICK_DATA_API, Selector$3.DATA_TOGGLE, function (event) {\n    // preventDefault only for <a> elements (which change the URL) not inside the collapsible element\n    if (event.currentTarget.tagName === 'A') {\n      event.preventDefault();\n    }\n\n    var $trigger = $(this);\n    var selector = Util.getSelectorFromElement(this);\n    var selectors = [].slice.call(document.querySelectorAll(selector));\n    $(selectors).each(function () {\n      var $target = $(this);\n      var data = $target.data(DATA_KEY$3);\n      var config = data ? 'toggle' : $trigger.data();\n\n      Collapse._jQueryInterface.call($target, config);\n    });\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$3] = Collapse._jQueryInterface;\n  $.fn[NAME$3].Constructor = Collapse;\n\n  $.fn[NAME$3].noConflict = function () {\n    $.fn[NAME$3] = JQUERY_NO_CONFLICT$3;\n    return Collapse._jQueryInterface;\n  };\n\n  /**!\n   * @fileOverview Kickass library to create and place poppers near their reference elements.\n   * @version 1.14.7\n   * @license\n   * Copyright (c) 2016 Federico Zivolo and contributors\n   *\n   * Permission is hereby granted, free of charge, to any person obtaining a copy\n   * of this software and associated documentation files (the \"Software\"), to deal\n   * in the Software without restriction, including without limitation the rights\n   * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell\n   * copies of the Software, and to permit persons to whom the Software is\n   * furnished to do so, subject to the following conditions:\n   *\n   * The above copyright notice and this permission notice shall be included in all\n   * copies or substantial portions of the Software.\n   *\n   * THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n   * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n   * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\n   * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\n   * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\n   * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\n   * SOFTWARE.\n   */\n  var isBrowser = typeof window !== 'undefined' && typeof document !== 'undefined';\n\n  var longerTimeoutBrowsers = ['Edge', 'Trident', 'Firefox'];\n  var timeoutDuration = 0;\n  for (var i = 0; i < longerTimeoutBrowsers.length; i += 1) {\n    if (isBrowser && navigator.userAgent.indexOf(longerTimeoutBrowsers[i]) >= 0) {\n      timeoutDuration = 1;\n      break;\n    }\n  }\n\n  function microtaskDebounce(fn) {\n    var called = false;\n    return function () {\n      if (called) {\n        return;\n      }\n      called = true;\n      window.Promise.resolve().then(function () {\n        called = false;\n        fn();\n      });\n    };\n  }\n\n  function taskDebounce(fn) {\n    var scheduled = false;\n    return function () {\n      if (!scheduled) {\n        scheduled = true;\n        setTimeout(function () {\n          scheduled = false;\n          fn();\n        }, timeoutDuration);\n      }\n    };\n  }\n\n  var supportsMicroTasks = isBrowser && window.Promise;\n\n  /**\n  * Create a debounced version of a method, that's asynchronously deferred\n  * but called in the minimum time possible.\n  *\n  * @method\n  * @memberof Popper.Utils\n  * @argument {Function} fn\n  * @returns {Function}\n  */\n  var debounce = supportsMicroTasks ? microtaskDebounce : taskDebounce;\n\n  /**\n   * Check if the given variable is a function\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Any} functionToCheck - variable to check\n   * @returns {Boolean} answer to: is a function?\n   */\n  function isFunction(functionToCheck) {\n    var getType = {};\n    return functionToCheck && getType.toString.call(functionToCheck) === '[object Function]';\n  }\n\n  /**\n   * Get CSS computed property of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Eement} element\n   * @argument {String} property\n   */\n  function getStyleComputedProperty(element, property) {\n    if (element.nodeType !== 1) {\n      return [];\n    }\n    // NOTE: 1 DOM access here\n    var window = element.ownerDocument.defaultView;\n    var css = window.getComputedStyle(element, null);\n    return property ? css[property] : css;\n  }\n\n  /**\n   * Returns the parentNode or the host of the element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} parent\n   */\n  function getParentNode(element) {\n    if (element.nodeName === 'HTML') {\n      return element;\n    }\n    return element.parentNode || element.host;\n  }\n\n  /**\n   * Returns the scrolling parent of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} scroll parent\n   */\n  function getScrollParent(element) {\n    // Return body, `getScroll` will take care to get the correct `scrollTop` from it\n    if (!element) {\n      return document.body;\n    }\n\n    switch (element.nodeName) {\n      case 'HTML':\n      case 'BODY':\n        return element.ownerDocument.body;\n      case '#document':\n        return element.body;\n    }\n\n    // Firefox want us to check `-x` and `-y` variations as well\n\n    var _getStyleComputedProp = getStyleComputedProperty(element),\n        overflow = _getStyleComputedProp.overflow,\n        overflowX = _getStyleComputedProp.overflowX,\n        overflowY = _getStyleComputedProp.overflowY;\n\n    if (/(auto|scroll|overlay)/.test(overflow + overflowY + overflowX)) {\n      return element;\n    }\n\n    return getScrollParent(getParentNode(element));\n  }\n\n  var isIE11 = isBrowser && !!(window.MSInputMethodContext && document.documentMode);\n  var isIE10 = isBrowser && /MSIE 10/.test(navigator.userAgent);\n\n  /**\n   * Determines if the browser is Internet Explorer\n   * @method\n   * @memberof Popper.Utils\n   * @param {Number} version to check\n   * @returns {Boolean} isIE\n   */\n  function isIE(version) {\n    if (version === 11) {\n      return isIE11;\n    }\n    if (version === 10) {\n      return isIE10;\n    }\n    return isIE11 || isIE10;\n  }\n\n  /**\n   * Returns the offset parent of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} offset parent\n   */\n  function getOffsetParent(element) {\n    if (!element) {\n      return document.documentElement;\n    }\n\n    var noOffsetParent = isIE(10) ? document.body : null;\n\n    // NOTE: 1 DOM access here\n    var offsetParent = element.offsetParent || null;\n    // Skip hidden elements which don't have an offsetParent\n    while (offsetParent === noOffsetParent && element.nextElementSibling) {\n      offsetParent = (element = element.nextElementSibling).offsetParent;\n    }\n\n    var nodeName = offsetParent && offsetParent.nodeName;\n\n    if (!nodeName || nodeName === 'BODY' || nodeName === 'HTML') {\n      return element ? element.ownerDocument.documentElement : document.documentElement;\n    }\n\n    // .offsetParent will return the closest TH, TD or TABLE in case\n    // no offsetParent is present, I hate this job...\n    if (['TH', 'TD', 'TABLE'].indexOf(offsetParent.nodeName) !== -1 && getStyleComputedProperty(offsetParent, 'position') === 'static') {\n      return getOffsetParent(offsetParent);\n    }\n\n    return offsetParent;\n  }\n\n  function isOffsetContainer(element) {\n    var nodeName = element.nodeName;\n\n    if (nodeName === 'BODY') {\n      return false;\n    }\n    return nodeName === 'HTML' || getOffsetParent(element.firstElementChild) === element;\n  }\n\n  /**\n   * Finds the root node (document, shadowDOM root) of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} node\n   * @returns {Element} root node\n   */\n  function getRoot(node) {\n    if (node.parentNode !== null) {\n      return getRoot(node.parentNode);\n    }\n\n    return node;\n  }\n\n  /**\n   * Finds the offset parent common to the two provided nodes\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element1\n   * @argument {Element} element2\n   * @returns {Element} common offset parent\n   */\n  function findCommonOffsetParent(element1, element2) {\n    // This check is needed to avoid errors in case one of the elements isn't defined for any reason\n    if (!element1 || !element1.nodeType || !element2 || !element2.nodeType) {\n      return document.documentElement;\n    }\n\n    // Here we make sure to give as \"start\" the element that comes first in the DOM\n    var order = element1.compareDocumentPosition(element2) & Node.DOCUMENT_POSITION_FOLLOWING;\n    var start = order ? element1 : element2;\n    var end = order ? element2 : element1;\n\n    // Get common ancestor container\n    var range = document.createRange();\n    range.setStart(start, 0);\n    range.setEnd(end, 0);\n    var commonAncestorContainer = range.commonAncestorContainer;\n\n    // Both nodes are inside #document\n\n    if (element1 !== commonAncestorContainer && element2 !== commonAncestorContainer || start.contains(end)) {\n      if (isOffsetContainer(commonAncestorContainer)) {\n        return commonAncestorContainer;\n      }\n\n      return getOffsetParent(commonAncestorContainer);\n    }\n\n    // one of the nodes is inside shadowDOM, find which one\n    var element1root = getRoot(element1);\n    if (element1root.host) {\n      return findCommonOffsetParent(element1root.host, element2);\n    } else {\n      return findCommonOffsetParent(element1, getRoot(element2).host);\n    }\n  }\n\n  /**\n   * Gets the scroll value of the given element in the given side (top and left)\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @argument {String} side `top` or `left`\n   * @returns {number} amount of scrolled pixels\n   */\n  function getScroll(element) {\n    var side = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : 'top';\n\n    var upperSide = side === 'top' ? 'scrollTop' : 'scrollLeft';\n    var nodeName = element.nodeName;\n\n    if (nodeName === 'BODY' || nodeName === 'HTML') {\n      var html = element.ownerDocument.documentElement;\n      var scrollingElement = element.ownerDocument.scrollingElement || html;\n      return scrollingElement[upperSide];\n    }\n\n    return element[upperSide];\n  }\n\n  /*\n   * Sum or subtract the element scroll values (left and top) from a given rect object\n   * @method\n   * @memberof Popper.Utils\n   * @param {Object} rect - Rect object you want to change\n   * @param {HTMLElement} element - The element from the function reads the scroll values\n   * @param {Boolean} subtract - set to true if you want to subtract the scroll values\n   * @return {Object} rect - The modifier rect object\n   */\n  function includeScroll(rect, element) {\n    var subtract = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false;\n\n    var scrollTop = getScroll(element, 'top');\n    var scrollLeft = getScroll(element, 'left');\n    var modifier = subtract ? -1 : 1;\n    rect.top += scrollTop * modifier;\n    rect.bottom += scrollTop * modifier;\n    rect.left += scrollLeft * modifier;\n    rect.right += scrollLeft * modifier;\n    return rect;\n  }\n\n  /*\n   * Helper to detect borders of a given element\n   * @method\n   * @memberof Popper.Utils\n   * @param {CSSStyleDeclaration} styles\n   * Result of `getStyleComputedProperty` on the given element\n   * @param {String} axis - `x` or `y`\n   * @return {number} borders - The borders size of the given axis\n   */\n\n  function getBordersSize(styles, axis) {\n    var sideA = axis === 'x' ? 'Left' : 'Top';\n    var sideB = sideA === 'Left' ? 'Right' : 'Bottom';\n\n    return parseFloat(styles['border' + sideA + 'Width'], 10) + parseFloat(styles['border' + sideB + 'Width'], 10);\n  }\n\n  function getSize(axis, body, html, computedStyle) {\n    return Math.max(body['offset' + axis], body['scroll' + axis], html['client' + axis], html['offset' + axis], html['scroll' + axis], isIE(10) ? parseInt(html['offset' + axis]) + parseInt(computedStyle['margin' + (axis === 'Height' ? 'Top' : 'Left')]) + parseInt(computedStyle['margin' + (axis === 'Height' ? 'Bottom' : 'Right')]) : 0);\n  }\n\n  function getWindowSizes(document) {\n    var body = document.body;\n    var html = document.documentElement;\n    var computedStyle = isIE(10) && getComputedStyle(html);\n\n    return {\n      height: getSize('Height', body, html, computedStyle),\n      width: getSize('Width', body, html, computedStyle)\n    };\n  }\n\n  var classCallCheck = function (instance, Constructor) {\n    if (!(instance instanceof Constructor)) {\n      throw new TypeError(\"Cannot call a class as a function\");\n    }\n  };\n\n  var createClass = function () {\n    function defineProperties(target, props) {\n      for (var i = 0; i < props.length; i++) {\n        var descriptor = props[i];\n        descriptor.enumerable = descriptor.enumerable || false;\n        descriptor.configurable = true;\n        if (\"value\" in descriptor) descriptor.writable = true;\n        Object.defineProperty(target, descriptor.key, descriptor);\n      }\n    }\n\n    return function (Constructor, protoProps, staticProps) {\n      if (protoProps) defineProperties(Constructor.prototype, protoProps);\n      if (staticProps) defineProperties(Constructor, staticProps);\n      return Constructor;\n    };\n  }();\n\n\n\n\n\n  var defineProperty = function (obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  };\n\n  var _extends = Object.assign || function (target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i];\n\n      for (var key in source) {\n        if (Object.prototype.hasOwnProperty.call(source, key)) {\n          target[key] = source[key];\n        }\n      }\n    }\n\n    return target;\n  };\n\n  /**\n   * Given element offsets, generate an output similar to getBoundingClientRect\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Object} offsets\n   * @returns {Object} ClientRect like output\n   */\n  function getClientRect(offsets) {\n    return _extends({}, offsets, {\n      right: offsets.left + offsets.width,\n      bottom: offsets.top + offsets.height\n    });\n  }\n\n  /**\n   * Get bounding client rect of given element\n   * @method\n   * @memberof Popper.Utils\n   * @param {HTMLElement} element\n   * @return {Object} client rect\n   */\n  function getBoundingClientRect(element) {\n    var rect = {};\n\n    // IE10 10 FIX: Please, don't ask, the element isn't\n    // considered in DOM in some circumstances...\n    // This isn't reproducible in IE10 compatibility mode of IE11\n    try {\n      if (isIE(10)) {\n        rect = element.getBoundingClientRect();\n        var scrollTop = getScroll(element, 'top');\n        var scrollLeft = getScroll(element, 'left');\n        rect.top += scrollTop;\n        rect.left += scrollLeft;\n        rect.bottom += scrollTop;\n        rect.right += scrollLeft;\n      } else {\n        rect = element.getBoundingClientRect();\n      }\n    } catch (e) {}\n\n    var result = {\n      left: rect.left,\n      top: rect.top,\n      width: rect.right - rect.left,\n      height: rect.bottom - rect.top\n    };\n\n    // subtract scrollbar size from sizes\n    var sizes = element.nodeName === 'HTML' ? getWindowSizes(element.ownerDocument) : {};\n    var width = sizes.width || element.clientWidth || result.right - result.left;\n    var height = sizes.height || element.clientHeight || result.bottom - result.top;\n\n    var horizScrollbar = element.offsetWidth - width;\n    var vertScrollbar = element.offsetHeight - height;\n\n    // if an hypothetical scrollbar is detected, we must be sure it's not a `border`\n    // we make this check conditional for performance reasons\n    if (horizScrollbar || vertScrollbar) {\n      var styles = getStyleComputedProperty(element);\n      horizScrollbar -= getBordersSize(styles, 'x');\n      vertScrollbar -= getBordersSize(styles, 'y');\n\n      result.width -= horizScrollbar;\n      result.height -= vertScrollbar;\n    }\n\n    return getClientRect(result);\n  }\n\n  function getOffsetRectRelativeToArbitraryNode(children, parent) {\n    var fixedPosition = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false;\n\n    var isIE10 = isIE(10);\n    var isHTML = parent.nodeName === 'HTML';\n    var childrenRect = getBoundingClientRect(children);\n    var parentRect = getBoundingClientRect(parent);\n    var scrollParent = getScrollParent(children);\n\n    var styles = getStyleComputedProperty(parent);\n    var borderTopWidth = parseFloat(styles.borderTopWidth, 10);\n    var borderLeftWidth = parseFloat(styles.borderLeftWidth, 10);\n\n    // In cases where the parent is fixed, we must ignore negative scroll in offset calc\n    if (fixedPosition && isHTML) {\n      parentRect.top = Math.max(parentRect.top, 0);\n      parentRect.left = Math.max(parentRect.left, 0);\n    }\n    var offsets = getClientRect({\n      top: childrenRect.top - parentRect.top - borderTopWidth,\n      left: childrenRect.left - parentRect.left - borderLeftWidth,\n      width: childrenRect.width,\n      height: childrenRect.height\n    });\n    offsets.marginTop = 0;\n    offsets.marginLeft = 0;\n\n    // Subtract margins of documentElement in case it's being used as parent\n    // we do this only on HTML because it's the only element that behaves\n    // differently when margins are applied to it. The margins are included in\n    // the box of the documentElement, in the other cases not.\n    if (!isIE10 && isHTML) {\n      var marginTop = parseFloat(styles.marginTop, 10);\n      var marginLeft = parseFloat(styles.marginLeft, 10);\n\n      offsets.top -= borderTopWidth - marginTop;\n      offsets.bottom -= borderTopWidth - marginTop;\n      offsets.left -= borderLeftWidth - marginLeft;\n      offsets.right -= borderLeftWidth - marginLeft;\n\n      // Attach marginTop and marginLeft because in some circumstances we may need them\n      offsets.marginTop = marginTop;\n      offsets.marginLeft = marginLeft;\n    }\n\n    if (isIE10 && !fixedPosition ? parent.contains(scrollParent) : parent === scrollParent && scrollParent.nodeName !== 'BODY') {\n      offsets = includeScroll(offsets, parent);\n    }\n\n    return offsets;\n  }\n\n  function getViewportOffsetRectRelativeToArtbitraryNode(element) {\n    var excludeScroll = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;\n\n    var html = element.ownerDocument.documentElement;\n    var relativeOffset = getOffsetRectRelativeToArbitraryNode(element, html);\n    var width = Math.max(html.clientWidth, window.innerWidth || 0);\n    var height = Math.max(html.clientHeight, window.innerHeight || 0);\n\n    var scrollTop = !excludeScroll ? getScroll(html) : 0;\n    var scrollLeft = !excludeScroll ? getScroll(html, 'left') : 0;\n\n    var offset = {\n      top: scrollTop - relativeOffset.top + relativeOffset.marginTop,\n      left: scrollLeft - relativeOffset.left + relativeOffset.marginLeft,\n      width: width,\n      height: height\n    };\n\n    return getClientRect(offset);\n  }\n\n  /**\n   * Check if the given element is fixed or is inside a fixed parent\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @argument {Element} customContainer\n   * @returns {Boolean} answer to \"isFixed?\"\n   */\n  function isFixed(element) {\n    var nodeName = element.nodeName;\n    if (nodeName === 'BODY' || nodeName === 'HTML') {\n      return false;\n    }\n    if (getStyleComputedProperty(element, 'position') === 'fixed') {\n      return true;\n    }\n    var parentNode = getParentNode(element);\n    if (!parentNode) {\n      return false;\n    }\n    return isFixed(parentNode);\n  }\n\n  /**\n   * Finds the first parent of an element that has a transformed property defined\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} first transformed parent or documentElement\n   */\n\n  function getFixedPositionOffsetParent(element) {\n    // This check is needed to avoid errors in case one of the elements isn't defined for any reason\n    if (!element || !element.parentElement || isIE()) {\n      return document.documentElement;\n    }\n    var el = element.parentElement;\n    while (el && getStyleComputedProperty(el, 'transform') === 'none') {\n      el = el.parentElement;\n    }\n    return el || document.documentElement;\n  }\n\n  /**\n   * Computed the boundaries limits and return them\n   * @method\n   * @memberof Popper.Utils\n   * @param {HTMLElement} popper\n   * @param {HTMLElement} reference\n   * @param {number} padding\n   * @param {HTMLElement} boundariesElement - Element used to define the boundaries\n   * @param {Boolean} fixedPosition - Is in fixed position mode\n   * @returns {Object} Coordinates of the boundaries\n   */\n  function getBoundaries(popper, reference, padding, boundariesElement) {\n    var fixedPosition = arguments.length > 4 && arguments[4] !== undefined ? arguments[4] : false;\n\n    // NOTE: 1 DOM access here\n\n    var boundaries = { top: 0, left: 0 };\n    var offsetParent = fixedPosition ? getFixedPositionOffsetParent(popper) : findCommonOffsetParent(popper, reference);\n\n    // Handle viewport case\n    if (boundariesElement === 'viewport') {\n      boundaries = getViewportOffsetRectRelativeToArtbitraryNode(offsetParent, fixedPosition);\n    } else {\n      // Handle other cases based on DOM element used as boundaries\n      var boundariesNode = void 0;\n      if (boundariesElement === 'scrollParent') {\n        boundariesNode = getScrollParent(getParentNode(reference));\n        if (boundariesNode.nodeName === 'BODY') {\n          boundariesNode = popper.ownerDocument.documentElement;\n        }\n      } else if (boundariesElement === 'window') {\n        boundariesNode = popper.ownerDocument.documentElement;\n      } else {\n        boundariesNode = boundariesElement;\n      }\n\n      var offsets = getOffsetRectRelativeToArbitraryNode(boundariesNode, offsetParent, fixedPosition);\n\n      // In case of HTML, we need a different computation\n      if (boundariesNode.nodeName === 'HTML' && !isFixed(offsetParent)) {\n        var _getWindowSizes = getWindowSizes(popper.ownerDocument),\n            height = _getWindowSizes.height,\n            width = _getWindowSizes.width;\n\n        boundaries.top += offsets.top - offsets.marginTop;\n        boundaries.bottom = height + offsets.top;\n        boundaries.left += offsets.left - offsets.marginLeft;\n        boundaries.right = width + offsets.left;\n      } else {\n        // for all the other DOM elements, this one is good\n        boundaries = offsets;\n      }\n    }\n\n    // Add paddings\n    padding = padding || 0;\n    var isPaddingNumber = typeof padding === 'number';\n    boundaries.left += isPaddingNumber ? padding : padding.left || 0;\n    boundaries.top += isPaddingNumber ? padding : padding.top || 0;\n    boundaries.right -= isPaddingNumber ? padding : padding.right || 0;\n    boundaries.bottom -= isPaddingNumber ? padding : padding.bottom || 0;\n\n    return boundaries;\n  }\n\n  function getArea(_ref) {\n    var width = _ref.width,\n        height = _ref.height;\n\n    return width * height;\n  }\n\n  /**\n   * Utility used to transform the `auto` placement to the placement with more\n   * available space.\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function computeAutoPlacement(placement, refRect, popper, reference, boundariesElement) {\n    var padding = arguments.length > 5 && arguments[5] !== undefined ? arguments[5] : 0;\n\n    if (placement.indexOf('auto') === -1) {\n      return placement;\n    }\n\n    var boundaries = getBoundaries(popper, reference, padding, boundariesElement);\n\n    var rects = {\n      top: {\n        width: boundaries.width,\n        height: refRect.top - boundaries.top\n      },\n      right: {\n        width: boundaries.right - refRect.right,\n        height: boundaries.height\n      },\n      bottom: {\n        width: boundaries.width,\n        height: boundaries.bottom - refRect.bottom\n      },\n      left: {\n        width: refRect.left - boundaries.left,\n        height: boundaries.height\n      }\n    };\n\n    var sortedAreas = Object.keys(rects).map(function (key) {\n      return _extends({\n        key: key\n      }, rects[key], {\n        area: getArea(rects[key])\n      });\n    }).sort(function (a, b) {\n      return b.area - a.area;\n    });\n\n    var filteredAreas = sortedAreas.filter(function (_ref2) {\n      var width = _ref2.width,\n          height = _ref2.height;\n      return width >= popper.clientWidth && height >= popper.clientHeight;\n    });\n\n    var computedPlacement = filteredAreas.length > 0 ? filteredAreas[0].key : sortedAreas[0].key;\n\n    var variation = placement.split('-')[1];\n\n    return computedPlacement + (variation ? '-' + variation : '');\n  }\n\n  /**\n   * Get offsets to the reference element\n   * @method\n   * @memberof Popper.Utils\n   * @param {Object} state\n   * @param {Element} popper - the popper element\n   * @param {Element} reference - the reference element (the popper will be relative to this)\n   * @param {Element} fixedPosition - is in fixed position mode\n   * @returns {Object} An object containing the offsets which will be applied to the popper\n   */\n  function getReferenceOffsets(state, popper, reference) {\n    var fixedPosition = arguments.length > 3 && arguments[3] !== undefined ? arguments[3] : null;\n\n    var commonOffsetParent = fixedPosition ? getFixedPositionOffsetParent(popper) : findCommonOffsetParent(popper, reference);\n    return getOffsetRectRelativeToArbitraryNode(reference, commonOffsetParent, fixedPosition);\n  }\n\n  /**\n   * Get the outer sizes of the given element (offset size + margins)\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Object} object containing width and height properties\n   */\n  function getOuterSizes(element) {\n    var window = element.ownerDocument.defaultView;\n    var styles = window.getComputedStyle(element);\n    var x = parseFloat(styles.marginTop || 0) + parseFloat(styles.marginBottom || 0);\n    var y = parseFloat(styles.marginLeft || 0) + parseFloat(styles.marginRight || 0);\n    var result = {\n      width: element.offsetWidth + y,\n      height: element.offsetHeight + x\n    };\n    return result;\n  }\n\n  /**\n   * Get the opposite placement of the given one\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} placement\n   * @returns {String} flipped placement\n   */\n  function getOppositePlacement(placement) {\n    var hash = { left: 'right', right: 'left', bottom: 'top', top: 'bottom' };\n    return placement.replace(/left|right|bottom|top/g, function (matched) {\n      return hash[matched];\n    });\n  }\n\n  /**\n   * Get offsets to the popper\n   * @method\n   * @memberof Popper.Utils\n   * @param {Object} position - CSS position the Popper will get applied\n   * @param {HTMLElement} popper - the popper element\n   * @param {Object} referenceOffsets - the reference offsets (the popper will be relative to this)\n   * @param {String} placement - one of the valid placement options\n   * @returns {Object} popperOffsets - An object containing the offsets which will be applied to the popper\n   */\n  function getPopperOffsets(popper, referenceOffsets, placement) {\n    placement = placement.split('-')[0];\n\n    // Get popper node sizes\n    var popperRect = getOuterSizes(popper);\n\n    // Add position, width and height to our offsets object\n    var popperOffsets = {\n      width: popperRect.width,\n      height: popperRect.height\n    };\n\n    // depending by the popper placement we have to compute its offsets slightly differently\n    var isHoriz = ['right', 'left'].indexOf(placement) !== -1;\n    var mainSide = isHoriz ? 'top' : 'left';\n    var secondarySide = isHoriz ? 'left' : 'top';\n    var measurement = isHoriz ? 'height' : 'width';\n    var secondaryMeasurement = !isHoriz ? 'height' : 'width';\n\n    popperOffsets[mainSide] = referenceOffsets[mainSide] + referenceOffsets[measurement] / 2 - popperRect[measurement] / 2;\n    if (placement === secondarySide) {\n      popperOffsets[secondarySide] = referenceOffsets[secondarySide] - popperRect[secondaryMeasurement];\n    } else {\n      popperOffsets[secondarySide] = referenceOffsets[getOppositePlacement(secondarySide)];\n    }\n\n    return popperOffsets;\n  }\n\n  /**\n   * Mimics the `find` method of Array\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Array} arr\n   * @argument prop\n   * @argument value\n   * @returns index or -1\n   */\n  function find(arr, check) {\n    // use native find if supported\n    if (Array.prototype.find) {\n      return arr.find(check);\n    }\n\n    // use `filter` to obtain the same behavior of `find`\n    return arr.filter(check)[0];\n  }\n\n  /**\n   * Return the index of the matching object\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Array} arr\n   * @argument prop\n   * @argument value\n   * @returns index or -1\n   */\n  function findIndex(arr, prop, value) {\n    // use native findIndex if supported\n    if (Array.prototype.findIndex) {\n      return arr.findIndex(function (cur) {\n        return cur[prop] === value;\n      });\n    }\n\n    // use `find` + `indexOf` if `findIndex` isn't supported\n    var match = find(arr, function (obj) {\n      return obj[prop] === value;\n    });\n    return arr.indexOf(match);\n  }\n\n  /**\n   * Loop trough the list of modifiers and run them in order,\n   * each of them will then edit the data object.\n   * @method\n   * @memberof Popper.Utils\n   * @param {dataObject} data\n   * @param {Array} modifiers\n   * @param {String} ends - Optional modifier name used as stopper\n   * @returns {dataObject}\n   */\n  function runModifiers(modifiers, data, ends) {\n    var modifiersToRun = ends === undefined ? modifiers : modifiers.slice(0, findIndex(modifiers, 'name', ends));\n\n    modifiersToRun.forEach(function (modifier) {\n      if (modifier['function']) {\n        // eslint-disable-line dot-notation\n        console.warn('`modifier.function` is deprecated, use `modifier.fn`!');\n      }\n      var fn = modifier['function'] || modifier.fn; // eslint-disable-line dot-notation\n      if (modifier.enabled && isFunction(fn)) {\n        // Add properties to offsets to make them a complete clientRect object\n        // we do this before each modifier to make sure the previous one doesn't\n        // mess with these values\n        data.offsets.popper = getClientRect(data.offsets.popper);\n        data.offsets.reference = getClientRect(data.offsets.reference);\n\n        data = fn(data, modifier);\n      }\n    });\n\n    return data;\n  }\n\n  /**\n   * Updates the position of the popper, computing the new offsets and applying\n   * the new style.<br />\n   * Prefer `scheduleUpdate` over `update` because of performance reasons.\n   * @method\n   * @memberof Popper\n   */\n  function update() {\n    // if popper is destroyed, don't perform any further update\n    if (this.state.isDestroyed) {\n      return;\n    }\n\n    var data = {\n      instance: this,\n      styles: {},\n      arrowStyles: {},\n      attributes: {},\n      flipped: false,\n      offsets: {}\n    };\n\n    // compute reference element offsets\n    data.offsets.reference = getReferenceOffsets(this.state, this.popper, this.reference, this.options.positionFixed);\n\n    // compute auto placement, store placement inside the data object,\n    // modifiers will be able to edit `placement` if needed\n    // and refer to originalPlacement to know the original value\n    data.placement = computeAutoPlacement(this.options.placement, data.offsets.reference, this.popper, this.reference, this.options.modifiers.flip.boundariesElement, this.options.modifiers.flip.padding);\n\n    // store the computed placement inside `originalPlacement`\n    data.originalPlacement = data.placement;\n\n    data.positionFixed = this.options.positionFixed;\n\n    // compute the popper offsets\n    data.offsets.popper = getPopperOffsets(this.popper, data.offsets.reference, data.placement);\n\n    data.offsets.popper.position = this.options.positionFixed ? 'fixed' : 'absolute';\n\n    // run the modifiers\n    data = runModifiers(this.modifiers, data);\n\n    // the first `update` will call `onCreate` callback\n    // the other ones will call `onUpdate` callback\n    if (!this.state.isCreated) {\n      this.state.isCreated = true;\n      this.options.onCreate(data);\n    } else {\n      this.options.onUpdate(data);\n    }\n  }\n\n  /**\n   * Helper used to know if the given modifier is enabled.\n   * @method\n   * @memberof Popper.Utils\n   * @returns {Boolean}\n   */\n  function isModifierEnabled(modifiers, modifierName) {\n    return modifiers.some(function (_ref) {\n      var name = _ref.name,\n          enabled = _ref.enabled;\n      return enabled && name === modifierName;\n    });\n  }\n\n  /**\n   * Get the prefixed supported property name\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} property (camelCase)\n   * @returns {String} prefixed property (camelCase or PascalCase, depending on the vendor prefix)\n   */\n  function getSupportedPropertyName(property) {\n    var prefixes = [false, 'ms', 'Webkit', 'Moz', 'O'];\n    var upperProp = property.charAt(0).toUpperCase() + property.slice(1);\n\n    for (var i = 0; i < prefixes.length; i++) {\n      var prefix = prefixes[i];\n      var toCheck = prefix ? '' + prefix + upperProp : property;\n      if (typeof document.body.style[toCheck] !== 'undefined') {\n        return toCheck;\n      }\n    }\n    return null;\n  }\n\n  /**\n   * Destroys the popper.\n   * @method\n   * @memberof Popper\n   */\n  function destroy() {\n    this.state.isDestroyed = true;\n\n    // touch DOM only if `applyStyle` modifier is enabled\n    if (isModifierEnabled(this.modifiers, 'applyStyle')) {\n      this.popper.removeAttribute('x-placement');\n      this.popper.style.position = '';\n      this.popper.style.top = '';\n      this.popper.style.left = '';\n      this.popper.style.right = '';\n      this.popper.style.bottom = '';\n      this.popper.style.willChange = '';\n      this.popper.style[getSupportedPropertyName('transform')] = '';\n    }\n\n    this.disableEventListeners();\n\n    // remove the popper if user explicity asked for the deletion on destroy\n    // do not use `remove` because IE11 doesn't support it\n    if (this.options.removeOnDestroy) {\n      this.popper.parentNode.removeChild(this.popper);\n    }\n    return this;\n  }\n\n  /**\n   * Get the window associated with the element\n   * @argument {Element} element\n   * @returns {Window}\n   */\n  function getWindow(element) {\n    var ownerDocument = element.ownerDocument;\n    return ownerDocument ? ownerDocument.defaultView : window;\n  }\n\n  function attachToScrollParents(scrollParent, event, callback, scrollParents) {\n    var isBody = scrollParent.nodeName === 'BODY';\n    var target = isBody ? scrollParent.ownerDocument.defaultView : scrollParent;\n    target.addEventListener(event, callback, { passive: true });\n\n    if (!isBody) {\n      attachToScrollParents(getScrollParent(target.parentNode), event, callback, scrollParents);\n    }\n    scrollParents.push(target);\n  }\n\n  /**\n   * Setup needed event listeners used to update the popper position\n   * @method\n   * @memberof Popper.Utils\n   * @private\n   */\n  function setupEventListeners(reference, options, state, updateBound) {\n    // Resize event listener on window\n    state.updateBound = updateBound;\n    getWindow(reference).addEventListener('resize', state.updateBound, { passive: true });\n\n    // Scroll event listener on scroll parents\n    var scrollElement = getScrollParent(reference);\n    attachToScrollParents(scrollElement, 'scroll', state.updateBound, state.scrollParents);\n    state.scrollElement = scrollElement;\n    state.eventsEnabled = true;\n\n    return state;\n  }\n\n  /**\n   * It will add resize/scroll events and start recalculating\n   * position of the popper element when they are triggered.\n   * @method\n   * @memberof Popper\n   */\n  function enableEventListeners() {\n    if (!this.state.eventsEnabled) {\n      this.state = setupEventListeners(this.reference, this.options, this.state, this.scheduleUpdate);\n    }\n  }\n\n  /**\n   * Remove event listeners used to update the popper position\n   * @method\n   * @memberof Popper.Utils\n   * @private\n   */\n  function removeEventListeners(reference, state) {\n    // Remove resize event listener on window\n    getWindow(reference).removeEventListener('resize', state.updateBound);\n\n    // Remove scroll event listener on scroll parents\n    state.scrollParents.forEach(function (target) {\n      target.removeEventListener('scroll', state.updateBound);\n    });\n\n    // Reset state\n    state.updateBound = null;\n    state.scrollParents = [];\n    state.scrollElement = null;\n    state.eventsEnabled = false;\n    return state;\n  }\n\n  /**\n   * It will remove resize/scroll events and won't recalculate popper position\n   * when they are triggered. It also won't trigger `onUpdate` callback anymore,\n   * unless you call `update` method manually.\n   * @method\n   * @memberof Popper\n   */\n  function disableEventListeners() {\n    if (this.state.eventsEnabled) {\n      cancelAnimationFrame(this.scheduleUpdate);\n      this.state = removeEventListeners(this.reference, this.state);\n    }\n  }\n\n  /**\n   * Tells if a given input is a number\n   * @method\n   * @memberof Popper.Utils\n   * @param {*} input to check\n   * @return {Boolean}\n   */\n  function isNumeric(n) {\n    return n !== '' && !isNaN(parseFloat(n)) && isFinite(n);\n  }\n\n  /**\n   * Set the style to the given popper\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element - Element to apply the style to\n   * @argument {Object} styles\n   * Object with a list of properties and values which will be applied to the element\n   */\n  function setStyles(element, styles) {\n    Object.keys(styles).forEach(function (prop) {\n      var unit = '';\n      // add unit if the value is numeric and is one of the following\n      if (['width', 'height', 'top', 'right', 'bottom', 'left'].indexOf(prop) !== -1 && isNumeric(styles[prop])) {\n        unit = 'px';\n      }\n      element.style[prop] = styles[prop] + unit;\n    });\n  }\n\n  /**\n   * Set the attributes to the given popper\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element - Element to apply the attributes to\n   * @argument {Object} styles\n   * Object with a list of properties and values which will be applied to the element\n   */\n  function setAttributes(element, attributes) {\n    Object.keys(attributes).forEach(function (prop) {\n      var value = attributes[prop];\n      if (value !== false) {\n        element.setAttribute(prop, attributes[prop]);\n      } else {\n        element.removeAttribute(prop);\n      }\n    });\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} data.styles - List of style properties - values to apply to popper element\n   * @argument {Object} data.attributes - List of attribute properties - values to apply to popper element\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The same data object\n   */\n  function applyStyle(data) {\n    // any property present in `data.styles` will be applied to the popper,\n    // in this way we can make the 3rd party modifiers add custom styles to it\n    // Be aware, modifiers could override the properties defined in the previous\n    // lines of this modifier!\n    setStyles(data.instance.popper, data.styles);\n\n    // any property present in `data.attributes` will be applied to the popper,\n    // they will be set as HTML attributes of the element\n    setAttributes(data.instance.popper, data.attributes);\n\n    // if arrowElement is defined and arrowStyles has some properties\n    if (data.arrowElement && Object.keys(data.arrowStyles).length) {\n      setStyles(data.arrowElement, data.arrowStyles);\n    }\n\n    return data;\n  }\n\n  /**\n   * Set the x-placement attribute before everything else because it could be used\n   * to add margins to the popper margins needs to be calculated to get the\n   * correct popper offsets.\n   * @method\n   * @memberof Popper.modifiers\n   * @param {HTMLElement} reference - The reference element used to position the popper\n   * @param {HTMLElement} popper - The HTML element used as popper\n   * @param {Object} options - Popper.js options\n   */\n  function applyStyleOnLoad(reference, popper, options, modifierOptions, state) {\n    // compute reference element offsets\n    var referenceOffsets = getReferenceOffsets(state, popper, reference, options.positionFixed);\n\n    // compute auto placement, store placement inside the data object,\n    // modifiers will be able to edit `placement` if needed\n    // and refer to originalPlacement to know the original value\n    var placement = computeAutoPlacement(options.placement, referenceOffsets, popper, reference, options.modifiers.flip.boundariesElement, options.modifiers.flip.padding);\n\n    popper.setAttribute('x-placement', placement);\n\n    // Apply `position` to popper before anything else because\n    // without the position applied we can't guarantee correct computations\n    setStyles(popper, { position: options.positionFixed ? 'fixed' : 'absolute' });\n\n    return options;\n  }\n\n  /**\n   * @function\n   * @memberof Popper.Utils\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Boolean} shouldRound - If the offsets should be rounded at all\n   * @returns {Object} The popper's position offsets rounded\n   *\n   * The tale of pixel-perfect positioning. It's still not 100% perfect, but as\n   * good as it can be within reason.\n   * Discussion here: https://github.com/FezVrasta/popper.js/pull/715\n   *\n   * Low DPI screens cause a popper to be blurry if not using full pixels (Safari\n   * as well on High DPI screens).\n   *\n   * Firefox prefers no rounding for positioning and does not have blurriness on\n   * high DPI screens.\n   *\n   * Only horizontal placement and left/right values need to be considered.\n   */\n  function getRoundedOffsets(data, shouldRound) {\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n    var round = Math.round,\n        floor = Math.floor;\n\n    var noRound = function noRound(v) {\n      return v;\n    };\n\n    var referenceWidth = round(reference.width);\n    var popperWidth = round(popper.width);\n\n    var isVertical = ['left', 'right'].indexOf(data.placement) !== -1;\n    var isVariation = data.placement.indexOf('-') !== -1;\n    var sameWidthParity = referenceWidth % 2 === popperWidth % 2;\n    var bothOddWidth = referenceWidth % 2 === 1 && popperWidth % 2 === 1;\n\n    var horizontalToInteger = !shouldRound ? noRound : isVertical || isVariation || sameWidthParity ? round : floor;\n    var verticalToInteger = !shouldRound ? noRound : round;\n\n    return {\n      left: horizontalToInteger(bothOddWidth && !isVariation && shouldRound ? popper.left - 1 : popper.left),\n      top: verticalToInteger(popper.top),\n      bottom: verticalToInteger(popper.bottom),\n      right: horizontalToInteger(popper.right)\n    };\n  }\n\n  var isFirefox = isBrowser && /Firefox/i.test(navigator.userAgent);\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function computeStyle(data, options) {\n    var x = options.x,\n        y = options.y;\n    var popper = data.offsets.popper;\n\n    // Remove this legacy support in Popper.js v2\n\n    var legacyGpuAccelerationOption = find(data.instance.modifiers, function (modifier) {\n      return modifier.name === 'applyStyle';\n    }).gpuAcceleration;\n    if (legacyGpuAccelerationOption !== undefined) {\n      console.warn('WARNING: `gpuAcceleration` option moved to `computeStyle` modifier and will not be supported in future versions of Popper.js!');\n    }\n    var gpuAcceleration = legacyGpuAccelerationOption !== undefined ? legacyGpuAccelerationOption : options.gpuAcceleration;\n\n    var offsetParent = getOffsetParent(data.instance.popper);\n    var offsetParentRect = getBoundingClientRect(offsetParent);\n\n    // Styles\n    var styles = {\n      position: popper.position\n    };\n\n    var offsets = getRoundedOffsets(data, window.devicePixelRatio < 2 || !isFirefox);\n\n    var sideA = x === 'bottom' ? 'top' : 'bottom';\n    var sideB = y === 'right' ? 'left' : 'right';\n\n    // if gpuAcceleration is set to `true` and transform is supported,\n    //  we use `translate3d` to apply the position to the popper we\n    // automatically use the supported prefixed version if needed\n    var prefixedProperty = getSupportedPropertyName('transform');\n\n    // now, let's make a step back and look at this code closely (wtf?)\n    // If the content of the popper grows once it's been positioned, it\n    // may happen that the popper gets misplaced because of the new content\n    // overflowing its reference element\n    // To avoid this problem, we provide two options (x and y), which allow\n    // the consumer to define the offset origin.\n    // If we position a popper on top of a reference element, we can set\n    // `x` to `top` to make the popper grow towards its top instead of\n    // its bottom.\n    var left = void 0,\n        top = void 0;\n    if (sideA === 'bottom') {\n      // when offsetParent is <html> the positioning is relative to the bottom of the screen (excluding the scrollbar)\n      // and not the bottom of the html element\n      if (offsetParent.nodeName === 'HTML') {\n        top = -offsetParent.clientHeight + offsets.bottom;\n      } else {\n        top = -offsetParentRect.height + offsets.bottom;\n      }\n    } else {\n      top = offsets.top;\n    }\n    if (sideB === 'right') {\n      if (offsetParent.nodeName === 'HTML') {\n        left = -offsetParent.clientWidth + offsets.right;\n      } else {\n        left = -offsetParentRect.width + offsets.right;\n      }\n    } else {\n      left = offsets.left;\n    }\n    if (gpuAcceleration && prefixedProperty) {\n      styles[prefixedProperty] = 'translate3d(' + left + 'px, ' + top + 'px, 0)';\n      styles[sideA] = 0;\n      styles[sideB] = 0;\n      styles.willChange = 'transform';\n    } else {\n      // othwerise, we use the standard `top`, `left`, `bottom` and `right` properties\n      var invertTop = sideA === 'bottom' ? -1 : 1;\n      var invertLeft = sideB === 'right' ? -1 : 1;\n      styles[sideA] = top * invertTop;\n      styles[sideB] = left * invertLeft;\n      styles.willChange = sideA + ', ' + sideB;\n    }\n\n    // Attributes\n    var attributes = {\n      'x-placement': data.placement\n    };\n\n    // Update `data` attributes, styles and arrowStyles\n    data.attributes = _extends({}, attributes, data.attributes);\n    data.styles = _extends({}, styles, data.styles);\n    data.arrowStyles = _extends({}, data.offsets.arrow, data.arrowStyles);\n\n    return data;\n  }\n\n  /**\n   * Helper used to know if the given modifier depends from another one.<br />\n   * It checks if the needed modifier is listed and enabled.\n   * @method\n   * @memberof Popper.Utils\n   * @param {Array} modifiers - list of modifiers\n   * @param {String} requestingName - name of requesting modifier\n   * @param {String} requestedName - name of requested modifier\n   * @returns {Boolean}\n   */\n  function isModifierRequired(modifiers, requestingName, requestedName) {\n    var requesting = find(modifiers, function (_ref) {\n      var name = _ref.name;\n      return name === requestingName;\n    });\n\n    var isRequired = !!requesting && modifiers.some(function (modifier) {\n      return modifier.name === requestedName && modifier.enabled && modifier.order < requesting.order;\n    });\n\n    if (!isRequired) {\n      var _requesting = '`' + requestingName + '`';\n      var requested = '`' + requestedName + '`';\n      console.warn(requested + ' modifier is required by ' + _requesting + ' modifier in order to work, be sure to include it before ' + _requesting + '!');\n    }\n    return isRequired;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function arrow(data, options) {\n    var _data$offsets$arrow;\n\n    // arrow depends on keepTogether in order to work\n    if (!isModifierRequired(data.instance.modifiers, 'arrow', 'keepTogether')) {\n      return data;\n    }\n\n    var arrowElement = options.element;\n\n    // if arrowElement is a string, suppose it's a CSS selector\n    if (typeof arrowElement === 'string') {\n      arrowElement = data.instance.popper.querySelector(arrowElement);\n\n      // if arrowElement is not found, don't run the modifier\n      if (!arrowElement) {\n        return data;\n      }\n    } else {\n      // if the arrowElement isn't a query selector we must check that the\n      // provided DOM node is child of its popper node\n      if (!data.instance.popper.contains(arrowElement)) {\n        console.warn('WARNING: `arrow.element` must be child of its popper element!');\n        return data;\n      }\n    }\n\n    var placement = data.placement.split('-')[0];\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var isVertical = ['left', 'right'].indexOf(placement) !== -1;\n\n    var len = isVertical ? 'height' : 'width';\n    var sideCapitalized = isVertical ? 'Top' : 'Left';\n    var side = sideCapitalized.toLowerCase();\n    var altSide = isVertical ? 'left' : 'top';\n    var opSide = isVertical ? 'bottom' : 'right';\n    var arrowElementSize = getOuterSizes(arrowElement)[len];\n\n    //\n    // extends keepTogether behavior making sure the popper and its\n    // reference have enough pixels in conjunction\n    //\n\n    // top/left side\n    if (reference[opSide] - arrowElementSize < popper[side]) {\n      data.offsets.popper[side] -= popper[side] - (reference[opSide] - arrowElementSize);\n    }\n    // bottom/right side\n    if (reference[side] + arrowElementSize > popper[opSide]) {\n      data.offsets.popper[side] += reference[side] + arrowElementSize - popper[opSide];\n    }\n    data.offsets.popper = getClientRect(data.offsets.popper);\n\n    // compute center of the popper\n    var center = reference[side] + reference[len] / 2 - arrowElementSize / 2;\n\n    // Compute the sideValue using the updated popper offsets\n    // take popper margin in account because we don't have this info available\n    var css = getStyleComputedProperty(data.instance.popper);\n    var popperMarginSide = parseFloat(css['margin' + sideCapitalized], 10);\n    var popperBorderSide = parseFloat(css['border' + sideCapitalized + 'Width'], 10);\n    var sideValue = center - data.offsets.popper[side] - popperMarginSide - popperBorderSide;\n\n    // prevent arrowElement from being placed not contiguously to its popper\n    sideValue = Math.max(Math.min(popper[len] - arrowElementSize, sideValue), 0);\n\n    data.arrowElement = arrowElement;\n    data.offsets.arrow = (_data$offsets$arrow = {}, defineProperty(_data$offsets$arrow, side, Math.round(sideValue)), defineProperty(_data$offsets$arrow, altSide, ''), _data$offsets$arrow);\n\n    return data;\n  }\n\n  /**\n   * Get the opposite placement variation of the given one\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} placement variation\n   * @returns {String} flipped placement variation\n   */\n  function getOppositeVariation(variation) {\n    if (variation === 'end') {\n      return 'start';\n    } else if (variation === 'start') {\n      return 'end';\n    }\n    return variation;\n  }\n\n  /**\n   * List of accepted placements to use as values of the `placement` option.<br />\n   * Valid placements are:\n   * - `auto`\n   * - `top`\n   * - `right`\n   * - `bottom`\n   * - `left`\n   *\n   * Each placement can have a variation from this list:\n   * - `-start`\n   * - `-end`\n   *\n   * Variations are interpreted easily if you think of them as the left to right\n   * written languages. Horizontally (`top` and `bottom`), `start` is left and `end`\n   * is right.<br />\n   * Vertically (`left` and `right`), `start` is top and `end` is bottom.\n   *\n   * Some valid examples are:\n   * - `top-end` (on top of reference, right aligned)\n   * - `right-start` (on right of reference, top aligned)\n   * - `bottom` (on bottom, centered)\n   * - `auto-end` (on the side with more space available, alignment depends by placement)\n   *\n   * @static\n   * @type {Array}\n   * @enum {String}\n   * @readonly\n   * @method placements\n   * @memberof Popper\n   */\n  var placements = ['auto-start', 'auto', 'auto-end', 'top-start', 'top', 'top-end', 'right-start', 'right', 'right-end', 'bottom-end', 'bottom', 'bottom-start', 'left-end', 'left', 'left-start'];\n\n  // Get rid of `auto` `auto-start` and `auto-end`\n  var validPlacements = placements.slice(3);\n\n  /**\n   * Given an initial placement, returns all the subsequent placements\n   * clockwise (or counter-clockwise).\n   *\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} placement - A valid placement (it accepts variations)\n   * @argument {Boolean} counter - Set to true to walk the placements counterclockwise\n   * @returns {Array} placements including their variations\n   */\n  function clockwise(placement) {\n    var counter = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;\n\n    var index = validPlacements.indexOf(placement);\n    var arr = validPlacements.slice(index + 1).concat(validPlacements.slice(0, index));\n    return counter ? arr.reverse() : arr;\n  }\n\n  var BEHAVIORS = {\n    FLIP: 'flip',\n    CLOCKWISE: 'clockwise',\n    COUNTERCLOCKWISE: 'counterclockwise'\n  };\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function flip(data, options) {\n    // if `inner` modifier is enabled, we can't use the `flip` modifier\n    if (isModifierEnabled(data.instance.modifiers, 'inner')) {\n      return data;\n    }\n\n    if (data.flipped && data.placement === data.originalPlacement) {\n      // seems like flip is trying to loop, probably there's not enough space on any of the flippable sides\n      return data;\n    }\n\n    var boundaries = getBoundaries(data.instance.popper, data.instance.reference, options.padding, options.boundariesElement, data.positionFixed);\n\n    var placement = data.placement.split('-')[0];\n    var placementOpposite = getOppositePlacement(placement);\n    var variation = data.placement.split('-')[1] || '';\n\n    var flipOrder = [];\n\n    switch (options.behavior) {\n      case BEHAVIORS.FLIP:\n        flipOrder = [placement, placementOpposite];\n        break;\n      case BEHAVIORS.CLOCKWISE:\n        flipOrder = clockwise(placement);\n        break;\n      case BEHAVIORS.COUNTERCLOCKWISE:\n        flipOrder = clockwise(placement, true);\n        break;\n      default:\n        flipOrder = options.behavior;\n    }\n\n    flipOrder.forEach(function (step, index) {\n      if (placement !== step || flipOrder.length === index + 1) {\n        return data;\n      }\n\n      placement = data.placement.split('-')[0];\n      placementOpposite = getOppositePlacement(placement);\n\n      var popperOffsets = data.offsets.popper;\n      var refOffsets = data.offsets.reference;\n\n      // using floor because the reference offsets may contain decimals we are not going to consider here\n      var floor = Math.floor;\n      var overlapsRef = placement === 'left' && floor(popperOffsets.right) > floor(refOffsets.left) || placement === 'right' && floor(popperOffsets.left) < floor(refOffsets.right) || placement === 'top' && floor(popperOffsets.bottom) > floor(refOffsets.top) || placement === 'bottom' && floor(popperOffsets.top) < floor(refOffsets.bottom);\n\n      var overflowsLeft = floor(popperOffsets.left) < floor(boundaries.left);\n      var overflowsRight = floor(popperOffsets.right) > floor(boundaries.right);\n      var overflowsTop = floor(popperOffsets.top) < floor(boundaries.top);\n      var overflowsBottom = floor(popperOffsets.bottom) > floor(boundaries.bottom);\n\n      var overflowsBoundaries = placement === 'left' && overflowsLeft || placement === 'right' && overflowsRight || placement === 'top' && overflowsTop || placement === 'bottom' && overflowsBottom;\n\n      // flip the variation if required\n      var isVertical = ['top', 'bottom'].indexOf(placement) !== -1;\n      var flippedVariation = !!options.flipVariations && (isVertical && variation === 'start' && overflowsLeft || isVertical && variation === 'end' && overflowsRight || !isVertical && variation === 'start' && overflowsTop || !isVertical && variation === 'end' && overflowsBottom);\n\n      if (overlapsRef || overflowsBoundaries || flippedVariation) {\n        // this boolean to detect any flip loop\n        data.flipped = true;\n\n        if (overlapsRef || overflowsBoundaries) {\n          placement = flipOrder[index + 1];\n        }\n\n        if (flippedVariation) {\n          variation = getOppositeVariation(variation);\n        }\n\n        data.placement = placement + (variation ? '-' + variation : '');\n\n        // this object contains `position`, we want to preserve it along with\n        // any additional property we may add in the future\n        data.offsets.popper = _extends({}, data.offsets.popper, getPopperOffsets(data.instance.popper, data.offsets.reference, data.placement));\n\n        data = runModifiers(data.instance.modifiers, data, 'flip');\n      }\n    });\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function keepTogether(data) {\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var placement = data.placement.split('-')[0];\n    var floor = Math.floor;\n    var isVertical = ['top', 'bottom'].indexOf(placement) !== -1;\n    var side = isVertical ? 'right' : 'bottom';\n    var opSide = isVertical ? 'left' : 'top';\n    var measurement = isVertical ? 'width' : 'height';\n\n    if (popper[side] < floor(reference[opSide])) {\n      data.offsets.popper[opSide] = floor(reference[opSide]) - popper[measurement];\n    }\n    if (popper[opSide] > floor(reference[side])) {\n      data.offsets.popper[opSide] = floor(reference[side]);\n    }\n\n    return data;\n  }\n\n  /**\n   * Converts a string containing value + unit into a px value number\n   * @function\n   * @memberof {modifiers~offset}\n   * @private\n   * @argument {String} str - Value + unit string\n   * @argument {String} measurement - `height` or `width`\n   * @argument {Object} popperOffsets\n   * @argument {Object} referenceOffsets\n   * @returns {Number|String}\n   * Value in pixels, or original string if no values were extracted\n   */\n  function toValue(str, measurement, popperOffsets, referenceOffsets) {\n    // separate value from unit\n    var split = str.match(/((?:\\-|\\+)?\\d*\\.?\\d*)(.*)/);\n    var value = +split[1];\n    var unit = split[2];\n\n    // If it's not a number it's an operator, I guess\n    if (!value) {\n      return str;\n    }\n\n    if (unit.indexOf('%') === 0) {\n      var element = void 0;\n      switch (unit) {\n        case '%p':\n          element = popperOffsets;\n          break;\n        case '%':\n        case '%r':\n        default:\n          element = referenceOffsets;\n      }\n\n      var rect = getClientRect(element);\n      return rect[measurement] / 100 * value;\n    } else if (unit === 'vh' || unit === 'vw') {\n      // if is a vh or vw, we calculate the size based on the viewport\n      var size = void 0;\n      if (unit === 'vh') {\n        size = Math.max(document.documentElement.clientHeight, window.innerHeight || 0);\n      } else {\n        size = Math.max(document.documentElement.clientWidth, window.innerWidth || 0);\n      }\n      return size / 100 * value;\n    } else {\n      // if is an explicit pixel unit, we get rid of the unit and keep the value\n      // if is an implicit unit, it's px, and we return just the value\n      return value;\n    }\n  }\n\n  /**\n   * Parse an `offset` string to extrapolate `x` and `y` numeric offsets.\n   * @function\n   * @memberof {modifiers~offset}\n   * @private\n   * @argument {String} offset\n   * @argument {Object} popperOffsets\n   * @argument {Object} referenceOffsets\n   * @argument {String} basePlacement\n   * @returns {Array} a two cells array with x and y offsets in numbers\n   */\n  function parseOffset(offset, popperOffsets, referenceOffsets, basePlacement) {\n    var offsets = [0, 0];\n\n    // Use height if placement is left or right and index is 0 otherwise use width\n    // in this way the first offset will use an axis and the second one\n    // will use the other one\n    var useHeight = ['right', 'left'].indexOf(basePlacement) !== -1;\n\n    // Split the offset string to obtain a list of values and operands\n    // The regex addresses values with the plus or minus sign in front (+10, -20, etc)\n    var fragments = offset.split(/(\\+|\\-)/).map(function (frag) {\n      return frag.trim();\n    });\n\n    // Detect if the offset string contains a pair of values or a single one\n    // they could be separated by comma or space\n    var divider = fragments.indexOf(find(fragments, function (frag) {\n      return frag.search(/,|\\s/) !== -1;\n    }));\n\n    if (fragments[divider] && fragments[divider].indexOf(',') === -1) {\n      console.warn('Offsets separated by white space(s) are deprecated, use a comma (,) instead.');\n    }\n\n    // If divider is found, we divide the list of values and operands to divide\n    // them by ofset X and Y.\n    var splitRegex = /\\s*,\\s*|\\s+/;\n    var ops = divider !== -1 ? [fragments.slice(0, divider).concat([fragments[divider].split(splitRegex)[0]]), [fragments[divider].split(splitRegex)[1]].concat(fragments.slice(divider + 1))] : [fragments];\n\n    // Convert the values with units to absolute pixels to allow our computations\n    ops = ops.map(function (op, index) {\n      // Most of the units rely on the orientation of the popper\n      var measurement = (index === 1 ? !useHeight : useHeight) ? 'height' : 'width';\n      var mergeWithPrevious = false;\n      return op\n      // This aggregates any `+` or `-` sign that aren't considered operators\n      // e.g.: 10 + +5 => [10, +, +5]\n      .reduce(function (a, b) {\n        if (a[a.length - 1] === '' && ['+', '-'].indexOf(b) !== -1) {\n          a[a.length - 1] = b;\n          mergeWithPrevious = true;\n          return a;\n        } else if (mergeWithPrevious) {\n          a[a.length - 1] += b;\n          mergeWithPrevious = false;\n          return a;\n        } else {\n          return a.concat(b);\n        }\n      }, [])\n      // Here we convert the string values into number values (in px)\n      .map(function (str) {\n        return toValue(str, measurement, popperOffsets, referenceOffsets);\n      });\n    });\n\n    // Loop trough the offsets arrays and execute the operations\n    ops.forEach(function (op, index) {\n      op.forEach(function (frag, index2) {\n        if (isNumeric(frag)) {\n          offsets[index] += frag * (op[index2 - 1] === '-' ? -1 : 1);\n        }\n      });\n    });\n    return offsets;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @argument {Number|String} options.offset=0\n   * The offset value as described in the modifier description\n   * @returns {Object} The data object, properly modified\n   */\n  function offset(data, _ref) {\n    var offset = _ref.offset;\n    var placement = data.placement,\n        _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var basePlacement = placement.split('-')[0];\n\n    var offsets = void 0;\n    if (isNumeric(+offset)) {\n      offsets = [+offset, 0];\n    } else {\n      offsets = parseOffset(offset, popper, reference, basePlacement);\n    }\n\n    if (basePlacement === 'left') {\n      popper.top += offsets[0];\n      popper.left -= offsets[1];\n    } else if (basePlacement === 'right') {\n      popper.top += offsets[0];\n      popper.left += offsets[1];\n    } else if (basePlacement === 'top') {\n      popper.left += offsets[0];\n      popper.top -= offsets[1];\n    } else if (basePlacement === 'bottom') {\n      popper.left += offsets[0];\n      popper.top += offsets[1];\n    }\n\n    data.popper = popper;\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function preventOverflow(data, options) {\n    var boundariesElement = options.boundariesElement || getOffsetParent(data.instance.popper);\n\n    // If offsetParent is the reference element, we really want to\n    // go one step up and use the next offsetParent as reference to\n    // avoid to make this modifier completely useless and look like broken\n    if (data.instance.reference === boundariesElement) {\n      boundariesElement = getOffsetParent(boundariesElement);\n    }\n\n    // NOTE: DOM access here\n    // resets the popper's position so that the document size can be calculated excluding\n    // the size of the popper element itself\n    var transformProp = getSupportedPropertyName('transform');\n    var popperStyles = data.instance.popper.style; // assignment to help minification\n    var top = popperStyles.top,\n        left = popperStyles.left,\n        transform = popperStyles[transformProp];\n\n    popperStyles.top = '';\n    popperStyles.left = '';\n    popperStyles[transformProp] = '';\n\n    var boundaries = getBoundaries(data.instance.popper, data.instance.reference, options.padding, boundariesElement, data.positionFixed);\n\n    // NOTE: DOM access here\n    // restores the original style properties after the offsets have been computed\n    popperStyles.top = top;\n    popperStyles.left = left;\n    popperStyles[transformProp] = transform;\n\n    options.boundaries = boundaries;\n\n    var order = options.priority;\n    var popper = data.offsets.popper;\n\n    var check = {\n      primary: function primary(placement) {\n        var value = popper[placement];\n        if (popper[placement] < boundaries[placement] && !options.escapeWithReference) {\n          value = Math.max(popper[placement], boundaries[placement]);\n        }\n        return defineProperty({}, placement, value);\n      },\n      secondary: function secondary(placement) {\n        var mainSide = placement === 'right' ? 'left' : 'top';\n        var value = popper[mainSide];\n        if (popper[placement] > boundaries[placement] && !options.escapeWithReference) {\n          value = Math.min(popper[mainSide], boundaries[placement] - (placement === 'right' ? popper.width : popper.height));\n        }\n        return defineProperty({}, mainSide, value);\n      }\n    };\n\n    order.forEach(function (placement) {\n      var side = ['left', 'top'].indexOf(placement) !== -1 ? 'primary' : 'secondary';\n      popper = _extends({}, popper, check[side](placement));\n    });\n\n    data.offsets.popper = popper;\n\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function shift(data) {\n    var placement = data.placement;\n    var basePlacement = placement.split('-')[0];\n    var shiftvariation = placement.split('-')[1];\n\n    // if shift shiftvariation is specified, run the modifier\n    if (shiftvariation) {\n      var _data$offsets = data.offsets,\n          reference = _data$offsets.reference,\n          popper = _data$offsets.popper;\n\n      var isVertical = ['bottom', 'top'].indexOf(basePlacement) !== -1;\n      var side = isVertical ? 'left' : 'top';\n      var measurement = isVertical ? 'width' : 'height';\n\n      var shiftOffsets = {\n        start: defineProperty({}, side, reference[side]),\n        end: defineProperty({}, side, reference[side] + reference[measurement] - popper[measurement])\n      };\n\n      data.offsets.popper = _extends({}, popper, shiftOffsets[shiftvariation]);\n    }\n\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function hide(data) {\n    if (!isModifierRequired(data.instance.modifiers, 'hide', 'preventOverflow')) {\n      return data;\n    }\n\n    var refRect = data.offsets.reference;\n    var bound = find(data.instance.modifiers, function (modifier) {\n      return modifier.name === 'preventOverflow';\n    }).boundaries;\n\n    if (refRect.bottom < bound.top || refRect.left > bound.right || refRect.top > bound.bottom || refRect.right < bound.left) {\n      // Avoid unnecessary DOM access if visibility hasn't changed\n      if (data.hide === true) {\n        return data;\n      }\n\n      data.hide = true;\n      data.attributes['x-out-of-boundaries'] = '';\n    } else {\n      // Avoid unnecessary DOM access if visibility hasn't changed\n      if (data.hide === false) {\n        return data;\n      }\n\n      data.hide = false;\n      data.attributes['x-out-of-boundaries'] = false;\n    }\n\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function inner(data) {\n    var placement = data.placement;\n    var basePlacement = placement.split('-')[0];\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var isHoriz = ['left', 'right'].indexOf(basePlacement) !== -1;\n\n    var subtractLength = ['top', 'left'].indexOf(basePlacement) === -1;\n\n    popper[isHoriz ? 'left' : 'top'] = reference[basePlacement] - (subtractLength ? popper[isHoriz ? 'width' : 'height'] : 0);\n\n    data.placement = getOppositePlacement(placement);\n    data.offsets.popper = getClientRect(popper);\n\n    return data;\n  }\n\n  /**\n   * Modifier function, each modifier can have a function of this type assigned\n   * to its `fn` property.<br />\n   * These functions will be called on each update, this means that you must\n   * make sure they are performant enough to avoid performance bottlenecks.\n   *\n   * @function ModifierFn\n   * @argument {dataObject} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {dataObject} The data object, properly modified\n   */\n\n  /**\n   * Modifiers are plugins used to alter the behavior of your poppers.<br />\n   * Popper.js uses a set of 9 modifiers to provide all the basic functionalities\n   * needed by the library.\n   *\n   * Usually you don't want to override the `order`, `fn` and `onLoad` props.\n   * All the other properties are configurations that could be tweaked.\n   * @namespace modifiers\n   */\n  var modifiers = {\n    /**\n     * Modifier used to shift the popper on the start or end of its reference\n     * element.<br />\n     * It will read the variation of the `placement` property.<br />\n     * It can be one either `-end` or `-start`.\n     * @memberof modifiers\n     * @inner\n     */\n    shift: {\n      /** @prop {number} order=100 - Index used to define the order of execution */\n      order: 100,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: shift\n    },\n\n    /**\n     * The `offset` modifier can shift your popper on both its axis.\n     *\n     * It accepts the following units:\n     * - `px` or unit-less, interpreted as pixels\n     * - `%` or `%r`, percentage relative to the length of the reference element\n     * - `%p`, percentage relative to the length of the popper element\n     * - `vw`, CSS viewport width unit\n     * - `vh`, CSS viewport height unit\n     *\n     * For length is intended the main axis relative to the placement of the popper.<br />\n     * This means that if the placement is `top` or `bottom`, the length will be the\n     * `width`. In case of `left` or `right`, it will be the `height`.\n     *\n     * You can provide a single value (as `Number` or `String`), or a pair of values\n     * as `String` divided by a comma or one (or more) white spaces.<br />\n     * The latter is a deprecated method because it leads to confusion and will be\n     * removed in v2.<br />\n     * Additionally, it accepts additions and subtractions between different units.\n     * Note that multiplications and divisions aren't supported.\n     *\n     * Valid examples are:\n     * ```\n     * 10\n     * '10%'\n     * '10, 10'\n     * '10%, 10'\n     * '10 + 10%'\n     * '10 - 5vh + 3%'\n     * '-10px + 5vh, 5px - 6%'\n     * ```\n     * > **NB**: If you desire to apply offsets to your poppers in a way that may make them overlap\n     * > with their reference element, unfortunately, you will have to disable the `flip` modifier.\n     * > You can read more on this at this [issue](https://github.com/FezVrasta/popper.js/issues/373).\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    offset: {\n      /** @prop {number} order=200 - Index used to define the order of execution */\n      order: 200,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: offset,\n      /** @prop {Number|String} offset=0\n       * The offset value as described in the modifier description\n       */\n      offset: 0\n    },\n\n    /**\n     * Modifier used to prevent the popper from being positioned outside the boundary.\n     *\n     * A scenario exists where the reference itself is not within the boundaries.<br />\n     * We can say it has \"escaped the boundaries\" — or just \"escaped\".<br />\n     * In this case we need to decide whether the popper should either:\n     *\n     * - detach from the reference and remain \"trapped\" in the boundaries, or\n     * - if it should ignore the boundary and \"escape with its reference\"\n     *\n     * When `escapeWithReference` is set to`true` and reference is completely\n     * outside its boundaries, the popper will overflow (or completely leave)\n     * the boundaries in order to remain attached to the edge of the reference.\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    preventOverflow: {\n      /** @prop {number} order=300 - Index used to define the order of execution */\n      order: 300,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: preventOverflow,\n      /**\n       * @prop {Array} [priority=['left','right','top','bottom']]\n       * Popper will try to prevent overflow following these priorities by default,\n       * then, it could overflow on the left and on top of the `boundariesElement`\n       */\n      priority: ['left', 'right', 'top', 'bottom'],\n      /**\n       * @prop {number} padding=5\n       * Amount of pixel used to define a minimum distance between the boundaries\n       * and the popper. This makes sure the popper always has a little padding\n       * between the edges of its container\n       */\n      padding: 5,\n      /**\n       * @prop {String|HTMLElement} boundariesElement='scrollParent'\n       * Boundaries used by the modifier. Can be `scrollParent`, `window`,\n       * `viewport` or any DOM element.\n       */\n      boundariesElement: 'scrollParent'\n    },\n\n    /**\n     * Modifier used to make sure the reference and its popper stay near each other\n     * without leaving any gap between the two. Especially useful when the arrow is\n     * enabled and you want to ensure that it points to its reference element.\n     * It cares only about the first axis. You can still have poppers with margin\n     * between the popper and its reference element.\n     * @memberof modifiers\n     * @inner\n     */\n    keepTogether: {\n      /** @prop {number} order=400 - Index used to define the order of execution */\n      order: 400,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: keepTogether\n    },\n\n    /**\n     * This modifier is used to move the `arrowElement` of the popper to make\n     * sure it is positioned between the reference element and its popper element.\n     * It will read the outer size of the `arrowElement` node to detect how many\n     * pixels of conjunction are needed.\n     *\n     * It has no effect if no `arrowElement` is provided.\n     * @memberof modifiers\n     * @inner\n     */\n    arrow: {\n      /** @prop {number} order=500 - Index used to define the order of execution */\n      order: 500,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: arrow,\n      /** @prop {String|HTMLElement} element='[x-arrow]' - Selector or node used as arrow */\n      element: '[x-arrow]'\n    },\n\n    /**\n     * Modifier used to flip the popper's placement when it starts to overlap its\n     * reference element.\n     *\n     * Requires the `preventOverflow` modifier before it in order to work.\n     *\n     * **NOTE:** this modifier will interrupt the current update cycle and will\n     * restart it if it detects the need to flip the placement.\n     * @memberof modifiers\n     * @inner\n     */\n    flip: {\n      /** @prop {number} order=600 - Index used to define the order of execution */\n      order: 600,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: flip,\n      /**\n       * @prop {String|Array} behavior='flip'\n       * The behavior used to change the popper's placement. It can be one of\n       * `flip`, `clockwise`, `counterclockwise` or an array with a list of valid\n       * placements (with optional variations)\n       */\n      behavior: 'flip',\n      /**\n       * @prop {number} padding=5\n       * The popper will flip if it hits the edges of the `boundariesElement`\n       */\n      padding: 5,\n      /**\n       * @prop {String|HTMLElement} boundariesElement='viewport'\n       * The element which will define the boundaries of the popper position.\n       * The popper will never be placed outside of the defined boundaries\n       * (except if `keepTogether` is enabled)\n       */\n      boundariesElement: 'viewport'\n    },\n\n    /**\n     * Modifier used to make the popper flow toward the inner of the reference element.\n     * By default, when this modifier is disabled, the popper will be placed outside\n     * the reference element.\n     * @memberof modifiers\n     * @inner\n     */\n    inner: {\n      /** @prop {number} order=700 - Index used to define the order of execution */\n      order: 700,\n      /** @prop {Boolean} enabled=false - Whether the modifier is enabled or not */\n      enabled: false,\n      /** @prop {ModifierFn} */\n      fn: inner\n    },\n\n    /**\n     * Modifier used to hide the popper when its reference element is outside of the\n     * popper boundaries. It will set a `x-out-of-boundaries` attribute which can\n     * be used to hide with a CSS selector the popper when its reference is\n     * out of boundaries.\n     *\n     * Requires the `preventOverflow` modifier before it in order to work.\n     * @memberof modifiers\n     * @inner\n     */\n    hide: {\n      /** @prop {number} order=800 - Index used to define the order of execution */\n      order: 800,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: hide\n    },\n\n    /**\n     * Computes the style that will be applied to the popper element to gets\n     * properly positioned.\n     *\n     * Note that this modifier will not touch the DOM, it just prepares the styles\n     * so that `applyStyle` modifier can apply it. This separation is useful\n     * in case you need to replace `applyStyle` with a custom implementation.\n     *\n     * This modifier has `850` as `order` value to maintain backward compatibility\n     * with previous versions of Popper.js. Expect the modifiers ordering method\n     * to change in future major versions of the library.\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    computeStyle: {\n      /** @prop {number} order=850 - Index used to define the order of execution */\n      order: 850,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: computeStyle,\n      /**\n       * @prop {Boolean} gpuAcceleration=true\n       * If true, it uses the CSS 3D transformation to position the popper.\n       * Otherwise, it will use the `top` and `left` properties\n       */\n      gpuAcceleration: true,\n      /**\n       * @prop {string} [x='bottom']\n       * Where to anchor the X axis (`bottom` or `top`). AKA X offset origin.\n       * Change this if your popper should grow in a direction different from `bottom`\n       */\n      x: 'bottom',\n      /**\n       * @prop {string} [x='left']\n       * Where to anchor the Y axis (`left` or `right`). AKA Y offset origin.\n       * Change this if your popper should grow in a direction different from `right`\n       */\n      y: 'right'\n    },\n\n    /**\n     * Applies the computed styles to the popper element.\n     *\n     * All the DOM manipulations are limited to this modifier. This is useful in case\n     * you want to integrate Popper.js inside a framework or view library and you\n     * want to delegate all the DOM manipulations to it.\n     *\n     * Note that if you disable this modifier, you must make sure the popper element\n     * has its position set to `absolute` before Popper.js can do its work!\n     *\n     * Just disable this modifier and define your own to achieve the desired effect.\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    applyStyle: {\n      /** @prop {number} order=900 - Index used to define the order of execution */\n      order: 900,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: applyStyle,\n      /** @prop {Function} */\n      onLoad: applyStyleOnLoad,\n      /**\n       * @deprecated since version 1.10.0, the property moved to `computeStyle` modifier\n       * @prop {Boolean} gpuAcceleration=true\n       * If true, it uses the CSS 3D transformation to position the popper.\n       * Otherwise, it will use the `top` and `left` properties\n       */\n      gpuAcceleration: undefined\n    }\n  };\n\n  /**\n   * The `dataObject` is an object containing all the information used by Popper.js.\n   * This object is passed to modifiers and to the `onCreate` and `onUpdate` callbacks.\n   * @name dataObject\n   * @property {Object} data.instance The Popper.js instance\n   * @property {String} data.placement Placement applied to popper\n   * @property {String} data.originalPlacement Placement originally defined on init\n   * @property {Boolean} data.flipped True if popper has been flipped by flip modifier\n   * @property {Boolean} data.hide True if the reference element is out of boundaries, useful to know when to hide the popper\n   * @property {HTMLElement} data.arrowElement Node used as arrow by arrow modifier\n   * @property {Object} data.styles Any CSS property defined here will be applied to the popper. It expects the JavaScript nomenclature (eg. `marginBottom`)\n   * @property {Object} data.arrowStyles Any CSS property defined here will be applied to the popper arrow. It expects the JavaScript nomenclature (eg. `marginBottom`)\n   * @property {Object} data.boundaries Offsets of the popper boundaries\n   * @property {Object} data.offsets The measurements of popper, reference and arrow elements\n   * @property {Object} data.offsets.popper `top`, `left`, `width`, `height` values\n   * @property {Object} data.offsets.reference `top`, `left`, `width`, `height` values\n   * @property {Object} data.offsets.arrow] `top` and `left` offsets, only one of them will be different from 0\n   */\n\n  /**\n   * Default options provided to Popper.js constructor.<br />\n   * These can be overridden using the `options` argument of Popper.js.<br />\n   * To override an option, simply pass an object with the same\n   * structure of the `options` object, as the 3rd argument. For example:\n   * ```\n   * new Popper(ref, pop, {\n   *   modifiers: {\n   *     preventOverflow: { enabled: false }\n   *   }\n   * })\n   * ```\n   * @type {Object}\n   * @static\n   * @memberof Popper\n   */\n  var Defaults = {\n    /**\n     * Popper's placement.\n     * @prop {Popper.placements} placement='bottom'\n     */\n    placement: 'bottom',\n\n    /**\n     * Set this to true if you want popper to position it self in 'fixed' mode\n     * @prop {Boolean} positionFixed=false\n     */\n    positionFixed: false,\n\n    /**\n     * Whether events (resize, scroll) are initially enabled.\n     * @prop {Boolean} eventsEnabled=true\n     */\n    eventsEnabled: true,\n\n    /**\n     * Set to true if you want to automatically remove the popper when\n     * you call the `destroy` method.\n     * @prop {Boolean} removeOnDestroy=false\n     */\n    removeOnDestroy: false,\n\n    /**\n     * Callback called when the popper is created.<br />\n     * By default, it is set to no-op.<br />\n     * Access Popper.js instance with `data.instance`.\n     * @prop {onCreate}\n     */\n    onCreate: function onCreate() {},\n\n    /**\n     * Callback called when the popper is updated. This callback is not called\n     * on the initialization/creation of the popper, but only on subsequent\n     * updates.<br />\n     * By default, it is set to no-op.<br />\n     * Access Popper.js instance with `data.instance`.\n     * @prop {onUpdate}\n     */\n    onUpdate: function onUpdate() {},\n\n    /**\n     * List of modifiers used to modify the offsets before they are applied to the popper.\n     * They provide most of the functionalities of Popper.js.\n     * @prop {modifiers}\n     */\n    modifiers: modifiers\n  };\n\n  /**\n   * @callback onCreate\n   * @param {dataObject} data\n   */\n\n  /**\n   * @callback onUpdate\n   * @param {dataObject} data\n   */\n\n  // Utils\n  // Methods\n  var Popper = function () {\n    /**\n     * Creates a new Popper.js instance.\n     * @class Popper\n     * @param {HTMLElement|referenceObject} reference - The reference element used to position the popper\n     * @param {HTMLElement} popper - The HTML element used as the popper\n     * @param {Object} options - Your custom options to override the ones defined in [Defaults](#defaults)\n     * @return {Object} instance - The generated Popper.js instance\n     */\n    function Popper(reference, popper) {\n      var _this = this;\n\n      var options = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n      classCallCheck(this, Popper);\n\n      this.scheduleUpdate = function () {\n        return requestAnimationFrame(_this.update);\n      };\n\n      // make update() debounced, so that it only runs at most once-per-tick\n      this.update = debounce(this.update.bind(this));\n\n      // with {} we create a new object with the options inside it\n      this.options = _extends({}, Popper.Defaults, options);\n\n      // init state\n      this.state = {\n        isDestroyed: false,\n        isCreated: false,\n        scrollParents: []\n      };\n\n      // get reference and popper elements (allow jQuery wrappers)\n      this.reference = reference && reference.jquery ? reference[0] : reference;\n      this.popper = popper && popper.jquery ? popper[0] : popper;\n\n      // Deep merge modifiers options\n      this.options.modifiers = {};\n      Object.keys(_extends({}, Popper.Defaults.modifiers, options.modifiers)).forEach(function (name) {\n        _this.options.modifiers[name] = _extends({}, Popper.Defaults.modifiers[name] || {}, options.modifiers ? options.modifiers[name] : {});\n      });\n\n      // Refactoring modifiers' list (Object => Array)\n      this.modifiers = Object.keys(this.options.modifiers).map(function (name) {\n        return _extends({\n          name: name\n        }, _this.options.modifiers[name]);\n      })\n      // sort the modifiers by order\n      .sort(function (a, b) {\n        return a.order - b.order;\n      });\n\n      // modifiers have the ability to execute arbitrary code when Popper.js get inited\n      // such code is executed in the same order of its modifier\n      // they could add new properties to their options configuration\n      // BE AWARE: don't add options to `options.modifiers.name` but to `modifierOptions`!\n      this.modifiers.forEach(function (modifierOptions) {\n        if (modifierOptions.enabled && isFunction(modifierOptions.onLoad)) {\n          modifierOptions.onLoad(_this.reference, _this.popper, _this.options, modifierOptions, _this.state);\n        }\n      });\n\n      // fire the first update to position the popper in the right place\n      this.update();\n\n      var eventsEnabled = this.options.eventsEnabled;\n      if (eventsEnabled) {\n        // setup event listeners, they will take care of update the position in specific situations\n        this.enableEventListeners();\n      }\n\n      this.state.eventsEnabled = eventsEnabled;\n    }\n\n    // We can't use class properties because they don't get listed in the\n    // class prototype and break stuff like Sinon stubs\n\n\n    createClass(Popper, [{\n      key: 'update',\n      value: function update$$1() {\n        return update.call(this);\n      }\n    }, {\n      key: 'destroy',\n      value: function destroy$$1() {\n        return destroy.call(this);\n      }\n    }, {\n      key: 'enableEventListeners',\n      value: function enableEventListeners$$1() {\n        return enableEventListeners.call(this);\n      }\n    }, {\n      key: 'disableEventListeners',\n      value: function disableEventListeners$$1() {\n        return disableEventListeners.call(this);\n      }\n\n      /**\n       * Schedules an update. It will run on the next UI update available.\n       * @method scheduleUpdate\n       * @memberof Popper\n       */\n\n\n      /**\n       * Collection of utilities useful when writing custom modifiers.\n       * Starting from version 1.7, this method is available only if you\n       * include `popper-utils.js` before `popper.js`.\n       *\n       * **DEPRECATION**: This way to access PopperUtils is deprecated\n       * and will be removed in v2! Use the PopperUtils module directly instead.\n       * Due to the high instability of the methods contained in Utils, we can't\n       * guarantee them to follow semver. Use them at your own risk!\n       * @static\n       * @private\n       * @type {Object}\n       * @deprecated since version 1.8\n       * @member Utils\n       * @memberof Popper\n       */\n\n    }]);\n    return Popper;\n  }();\n\n  /**\n   * The `referenceObject` is an object that provides an interface compatible with Popper.js\n   * and lets you use it as replacement of a real DOM node.<br />\n   * You can use this method to position a popper relatively to a set of coordinates\n   * in case you don't have a DOM node to use as reference.\n   *\n   * ```\n   * new Popper(referenceObject, popperNode);\n   * ```\n   *\n   * NB: This feature isn't supported in Internet Explorer 10.\n   * @name referenceObject\n   * @property {Function} data.getBoundingClientRect\n   * A function that returns a set of coordinates compatible with the native `getBoundingClientRect` method.\n   * @property {number} data.clientWidth\n   * An ES6 getter that will return the width of the virtual reference element.\n   * @property {number} data.clientHeight\n   * An ES6 getter that will return the height of the virtual reference element.\n   */\n\n\n  Popper.Utils = (typeof window !== 'undefined' ? window : global).PopperUtils;\n  Popper.placements = placements;\n  Popper.Defaults = Defaults;\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$4 = 'dropdown';\n  var VERSION$4 = '4.3.1';\n  var DATA_KEY$4 = 'bs.dropdown';\n  var EVENT_KEY$4 = \".\" + DATA_KEY$4;\n  var DATA_API_KEY$4 = '.data-api';\n  var JQUERY_NO_CONFLICT$4 = $.fn[NAME$4];\n  var ESCAPE_KEYCODE = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var SPACE_KEYCODE = 32; // KeyboardEvent.which value for space key\n\n  var TAB_KEYCODE = 9; // KeyboardEvent.which value for tab key\n\n  var ARROW_UP_KEYCODE = 38; // KeyboardEvent.which value for up arrow key\n\n  var ARROW_DOWN_KEYCODE = 40; // KeyboardEvent.which value for down arrow key\n\n  var RIGHT_MOUSE_BUTTON_WHICH = 3; // MouseEvent.which value for the right button (assuming a right-handed mouse)\n\n  var REGEXP_KEYDOWN = new RegExp(ARROW_UP_KEYCODE + \"|\" + ARROW_DOWN_KEYCODE + \"|\" + ESCAPE_KEYCODE);\n  var Event$4 = {\n    HIDE: \"hide\" + EVENT_KEY$4,\n    HIDDEN: \"hidden\" + EVENT_KEY$4,\n    SHOW: \"show\" + EVENT_KEY$4,\n    SHOWN: \"shown\" + EVENT_KEY$4,\n    CLICK: \"click\" + EVENT_KEY$4,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYDOWN_DATA_API: \"keydown\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYUP_DATA_API: \"keyup\" + EVENT_KEY$4 + DATA_API_KEY$4\n  };\n  var ClassName$4 = {\n    DISABLED: 'disabled',\n    SHOW: 'show',\n    DROPUP: 'dropup',\n    DROPRIGHT: 'dropright',\n    DROPLEFT: 'dropleft',\n    MENURIGHT: 'dropdown-menu-right',\n    MENULEFT: 'dropdown-menu-left',\n    POSITION_STATIC: 'position-static'\n  };\n  var Selector$4 = {\n    DATA_TOGGLE: '[data-toggle=\"dropdown\"]',\n    FORM_CHILD: '.dropdown form',\n    MENU: '.dropdown-menu',\n    NAVBAR_NAV: '.navbar-nav',\n    VISIBLE_ITEMS: '.dropdown-menu .dropdown-item:not(.disabled):not(:disabled)'\n  };\n  var AttachmentMap = {\n    TOP: 'top-start',\n    TOPEND: 'top-end',\n    BOTTOM: 'bottom-start',\n    BOTTOMEND: 'bottom-end',\n    RIGHT: 'right-start',\n    RIGHTEND: 'right-end',\n    LEFT: 'left-start',\n    LEFTEND: 'left-end'\n  };\n  var Default$2 = {\n    offset: 0,\n    flip: true,\n    boundary: 'scrollParent',\n    reference: 'toggle',\n    display: 'dynamic'\n  };\n  var DefaultType$2 = {\n    offset: '(number|string|function)',\n    flip: 'boolean',\n    boundary: '(string|element)',\n    reference: '(string|element)',\n    display: 'string'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Dropdown =\n  /*#__PURE__*/\n  function () {\n    function Dropdown(element, config) {\n      this._element = element;\n      this._popper = null;\n      this._config = this._getConfig(config);\n      this._menu = this._getMenuElement();\n      this._inNavbar = this._detectNavbar();\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Dropdown.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      var isActive = $(this._menu).hasClass(ClassName$4.SHOW);\n\n      Dropdown._clearMenus();\n\n      if (isActive) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      } // Disable totally Popper.js for Dropdown in Navbar\n\n\n      if (!this._inNavbar) {\n        /**\n         * Check for Popper dependency\n         * Popper - https://popper.js.org\n         */\n        if (typeof Popper === 'undefined') {\n          throw new TypeError('Bootstrap\\'s dropdowns require Popper.js (https://popper.js.org/)');\n        }\n\n        var referenceElement = this._element;\n\n        if (this._config.reference === 'parent') {\n          referenceElement = parent;\n        } else if (Util.isElement(this._config.reference)) {\n          referenceElement = this._config.reference; // Check if it's jQuery element\n\n          if (typeof this._config.reference.jquery !== 'undefined') {\n            referenceElement = this._config.reference[0];\n          }\n        } // If boundary is not `scrollParent`, then set position to `static`\n        // to allow the menu to \"escape\" the scroll parent's boundaries\n        // https://github.com/twbs/bootstrap/issues/24251\n\n\n        if (this._config.boundary !== 'scrollParent') {\n          $(parent).addClass(ClassName$4.POSITION_STATIC);\n        }\n\n        this._popper = new Popper(referenceElement, this._menu, this._getPopperConfig());\n      } // If this is a touch-enabled device we add extra\n      // empty mouseover listeners to the body's immediate children;\n      // only needed because of broken event delegation on iOS\n      // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n\n      if ('ontouchstart' in document.documentElement && $(parent).closest(Selector$4.NAVBAR_NAV).length === 0) {\n        $(document.body).children().on('mouseover', null, $.noop);\n      }\n\n      this._element.focus();\n\n      this._element.setAttribute('aria-expanded', true);\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.show = function show() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || $(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.hide = function hide() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || !$(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$4);\n      $(this._element).off(EVENT_KEY$4);\n      this._element = null;\n      this._menu = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n\n        this._popper = null;\n      }\n    };\n\n    _proto.update = function update() {\n      this._inNavbar = this._detectNavbar();\n\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Private\n    ;\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this = this;\n\n      $(this._element).on(Event$4.CLICK, function (event) {\n        event.preventDefault();\n        event.stopPropagation();\n\n        _this.toggle();\n      });\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, this.constructor.Default, $(this._element).data(), config);\n      Util.typeCheckConfig(NAME$4, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._getMenuElement = function _getMenuElement() {\n      if (!this._menu) {\n        var parent = Dropdown._getParentFromElement(this._element);\n\n        if (parent) {\n          this._menu = parent.querySelector(Selector$4.MENU);\n        }\n      }\n\n      return this._menu;\n    };\n\n    _proto._getPlacement = function _getPlacement() {\n      var $parentDropdown = $(this._element.parentNode);\n      var placement = AttachmentMap.BOTTOM; // Handle dropup\n\n      if ($parentDropdown.hasClass(ClassName$4.DROPUP)) {\n        placement = AttachmentMap.TOP;\n\n        if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n          placement = AttachmentMap.TOPEND;\n        }\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPRIGHT)) {\n        placement = AttachmentMap.RIGHT;\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPLEFT)) {\n        placement = AttachmentMap.LEFT;\n      } else if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n        placement = AttachmentMap.BOTTOMEND;\n      }\n\n      return placement;\n    };\n\n    _proto._detectNavbar = function _detectNavbar() {\n      return $(this._element).closest('.navbar').length > 0;\n    };\n\n    _proto._getOffset = function _getOffset() {\n      var _this2 = this;\n\n      var offset = {};\n\n      if (typeof this._config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this2._config.offset(data.offsets, _this2._element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this._config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getPopperConfig = function _getPopperConfig() {\n      var popperConfig = {\n        placement: this._getPlacement(),\n        modifiers: {\n          offset: this._getOffset(),\n          flip: {\n            enabled: this._config.flip\n          },\n          preventOverflow: {\n            boundariesElement: this._config.boundary\n          }\n        } // Disable Popper.js if we have a static display\n\n      };\n\n      if (this._config.display === 'static') {\n        popperConfig.modifiers.applyStyle = {\n          enabled: false\n        };\n      }\n\n      return popperConfig;\n    } // Static\n    ;\n\n    Dropdown._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$4);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data) {\n          data = new Dropdown(this, _config);\n          $(this).data(DATA_KEY$4, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    Dropdown._clearMenus = function _clearMenus(event) {\n      if (event && (event.which === RIGHT_MOUSE_BUTTON_WHICH || event.type === 'keyup' && event.which !== TAB_KEYCODE)) {\n        return;\n      }\n\n      var toggles = [].slice.call(document.querySelectorAll(Selector$4.DATA_TOGGLE));\n\n      for (var i = 0, len = toggles.length; i < len; i++) {\n        var parent = Dropdown._getParentFromElement(toggles[i]);\n\n        var context = $(toggles[i]).data(DATA_KEY$4);\n        var relatedTarget = {\n          relatedTarget: toggles[i]\n        };\n\n        if (event && event.type === 'click') {\n          relatedTarget.clickEvent = event;\n        }\n\n        if (!context) {\n          continue;\n        }\n\n        var dropdownMenu = context._menu;\n\n        if (!$(parent).hasClass(ClassName$4.SHOW)) {\n          continue;\n        }\n\n        if (event && (event.type === 'click' && /input|textarea/i.test(event.target.tagName) || event.type === 'keyup' && event.which === TAB_KEYCODE) && $.contains(parent, event.target)) {\n          continue;\n        }\n\n        var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n        $(parent).trigger(hideEvent);\n\n        if (hideEvent.isDefaultPrevented()) {\n          continue;\n        } // If this is a touch-enabled device we remove the extra\n        // empty mouseover listeners we added for iOS support\n\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().off('mouseover', null, $.noop);\n        }\n\n        toggles[i].setAttribute('aria-expanded', 'false');\n        $(dropdownMenu).removeClass(ClassName$4.SHOW);\n        $(parent).removeClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n      }\n    };\n\n    Dropdown._getParentFromElement = function _getParentFromElement(element) {\n      var parent;\n      var selector = Util.getSelectorFromElement(element);\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      return parent || element.parentNode;\n    } // eslint-disable-next-line complexity\n    ;\n\n    Dropdown._dataApiKeydownHandler = function _dataApiKeydownHandler(event) {\n      // If not input/textarea:\n      //  - And not a key in REGEXP_KEYDOWN => not a dropdown command\n      // If input/textarea:\n      //  - If space key => not a dropdown command\n      //  - If key is other than escape\n      //    - If key is not up or down => not a dropdown command\n      //    - If trigger inside the menu => not a dropdown command\n      if (/input|textarea/i.test(event.target.tagName) ? event.which === SPACE_KEYCODE || event.which !== ESCAPE_KEYCODE && (event.which !== ARROW_DOWN_KEYCODE && event.which !== ARROW_UP_KEYCODE || $(event.target).closest(Selector$4.MENU).length) : !REGEXP_KEYDOWN.test(event.which)) {\n        return;\n      }\n\n      event.preventDefault();\n      event.stopPropagation();\n\n      if (this.disabled || $(this).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this);\n\n      var isActive = $(parent).hasClass(ClassName$4.SHOW);\n\n      if (!isActive || isActive && (event.which === ESCAPE_KEYCODE || event.which === SPACE_KEYCODE)) {\n        if (event.which === ESCAPE_KEYCODE) {\n          var toggle = parent.querySelector(Selector$4.DATA_TOGGLE);\n          $(toggle).trigger('focus');\n        }\n\n        $(this).trigger('click');\n        return;\n      }\n\n      var items = [].slice.call(parent.querySelectorAll(Selector$4.VISIBLE_ITEMS));\n\n      if (items.length === 0) {\n        return;\n      }\n\n      var index = items.indexOf(event.target);\n\n      if (event.which === ARROW_UP_KEYCODE && index > 0) {\n        // Up\n        index--;\n      }\n\n      if (event.which === ARROW_DOWN_KEYCODE && index < items.length - 1) {\n        // Down\n        index++;\n      }\n\n      if (index < 0) {\n        index = 0;\n      }\n\n      items[index].focus();\n    };\n\n    _createClass(Dropdown, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$4;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$2;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$2;\n      }\n    }]);\n\n    return Dropdown;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$4.KEYDOWN_DATA_API, Selector$4.DATA_TOGGLE, Dropdown._dataApiKeydownHandler).on(Event$4.KEYDOWN_DATA_API, Selector$4.MENU, Dropdown._dataApiKeydownHandler).on(Event$4.CLICK_DATA_API + \" \" + Event$4.KEYUP_DATA_API, Dropdown._clearMenus).on(Event$4.CLICK_DATA_API, Selector$4.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n    event.stopPropagation();\n\n    Dropdown._jQueryInterface.call($(this), 'toggle');\n  }).on(Event$4.CLICK_DATA_API, Selector$4.FORM_CHILD, function (e) {\n    e.stopPropagation();\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$4] = Dropdown._jQueryInterface;\n  $.fn[NAME$4].Constructor = Dropdown;\n\n  $.fn[NAME$4].noConflict = function () {\n    $.fn[NAME$4] = JQUERY_NO_CONFLICT$4;\n    return Dropdown._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$5 = 'modal';\n  var VERSION$5 = '4.3.1';\n  var DATA_KEY$5 = 'bs.modal';\n  var EVENT_KEY$5 = \".\" + DATA_KEY$5;\n  var DATA_API_KEY$5 = '.data-api';\n  var JQUERY_NO_CONFLICT$5 = $.fn[NAME$5];\n  var ESCAPE_KEYCODE$1 = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var Default$3 = {\n    backdrop: true,\n    keyboard: true,\n    focus: true,\n    show: true\n  };\n  var DefaultType$3 = {\n    backdrop: '(boolean|string)',\n    keyboard: 'boolean',\n    focus: 'boolean',\n    show: 'boolean'\n  };\n  var Event$5 = {\n    HIDE: \"hide\" + EVENT_KEY$5,\n    HIDDEN: \"hidden\" + EVENT_KEY$5,\n    SHOW: \"show\" + EVENT_KEY$5,\n    SHOWN: \"shown\" + EVENT_KEY$5,\n    FOCUSIN: \"focusin\" + EVENT_KEY$5,\n    RESIZE: \"resize\" + EVENT_KEY$5,\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$5,\n    KEYDOWN_DISMISS: \"keydown.dismiss\" + EVENT_KEY$5,\n    MOUSEUP_DISMISS: \"mouseup.dismiss\" + EVENT_KEY$5,\n    MOUSEDOWN_DISMISS: \"mousedown.dismiss\" + EVENT_KEY$5,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$5 + DATA_API_KEY$5\n  };\n  var ClassName$5 = {\n    SCROLLABLE: 'modal-dialog-scrollable',\n    SCROLLBAR_MEASURER: 'modal-scrollbar-measure',\n    BACKDROP: 'modal-backdrop',\n    OPEN: 'modal-open',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$5 = {\n    DIALOG: '.modal-dialog',\n    MODAL_BODY: '.modal-body',\n    DATA_TOGGLE: '[data-toggle=\"modal\"]',\n    DATA_DISMISS: '[data-dismiss=\"modal\"]',\n    FIXED_CONTENT: '.fixed-top, .fixed-bottom, .is-fixed, .sticky-top',\n    STICKY_CONTENT: '.sticky-top'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Modal =\n  /*#__PURE__*/\n  function () {\n    function Modal(element, config) {\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._dialog = element.querySelector(Selector$5.DIALOG);\n      this._backdrop = null;\n      this._isShown = false;\n      this._isBodyOverflowing = false;\n      this._ignoreBackdropClick = false;\n      this._isTransitioning = false;\n      this._scrollbarWidth = 0;\n    } // Getters\n\n\n    var _proto = Modal.prototype;\n\n    // Public\n    _proto.toggle = function toggle(relatedTarget) {\n      return this._isShown ? this.hide() : this.show(relatedTarget);\n    };\n\n    _proto.show = function show(relatedTarget) {\n      var _this = this;\n\n      if (this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      if ($(this._element).hasClass(ClassName$5.FADE)) {\n        this._isTransitioning = true;\n      }\n\n      var showEvent = $.Event(Event$5.SHOW, {\n        relatedTarget: relatedTarget\n      });\n      $(this._element).trigger(showEvent);\n\n      if (this._isShown || showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = true;\n\n      this._checkScrollbar();\n\n      this._setScrollbar();\n\n      this._adjustDialog();\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(this._element).on(Event$5.CLICK_DISMISS, Selector$5.DATA_DISMISS, function (event) {\n        return _this.hide(event);\n      });\n      $(this._dialog).on(Event$5.MOUSEDOWN_DISMISS, function () {\n        $(_this._element).one(Event$5.MOUSEUP_DISMISS, function (event) {\n          if ($(event.target).is(_this._element)) {\n            _this._ignoreBackdropClick = true;\n          }\n        });\n      });\n\n      this._showBackdrop(function () {\n        return _this._showElement(relatedTarget);\n      });\n    };\n\n    _proto.hide = function hide(event) {\n      var _this2 = this;\n\n      if (event) {\n        event.preventDefault();\n      }\n\n      if (!this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      var hideEvent = $.Event(Event$5.HIDE);\n      $(this._element).trigger(hideEvent);\n\n      if (!this._isShown || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = false;\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (transition) {\n        this._isTransitioning = true;\n      }\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(document).off(Event$5.FOCUSIN);\n      $(this._element).removeClass(ClassName$5.SHOW);\n      $(this._element).off(Event$5.CLICK_DISMISS);\n      $(this._dialog).off(Event$5.MOUSEDOWN_DISMISS);\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, function (event) {\n          return _this2._hideModal(event);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        this._hideModal();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      [window, this._element, this._dialog].forEach(function (htmlElement) {\n        return $(htmlElement).off(EVENT_KEY$5);\n      });\n      /**\n       * `document` has 2 events `Event.FOCUSIN` and `Event.CLICK_DATA_API`\n       * Do not move `document` in `htmlElements` array\n       * It will remove `Event.CLICK_DATA_API` event that should remain\n       */\n\n      $(document).off(Event$5.FOCUSIN);\n      $.removeData(this._element, DATA_KEY$5);\n      this._config = null;\n      this._element = null;\n      this._dialog = null;\n      this._backdrop = null;\n      this._isShown = null;\n      this._isBodyOverflowing = null;\n      this._ignoreBackdropClick = null;\n      this._isTransitioning = null;\n      this._scrollbarWidth = null;\n    };\n\n    _proto.handleUpdate = function handleUpdate() {\n      this._adjustDialog();\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$3, config);\n      Util.typeCheckConfig(NAME$5, config, DefaultType$3);\n      return config;\n    };\n\n    _proto._showElement = function _showElement(relatedTarget) {\n      var _this3 = this;\n\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (!this._element.parentNode || this._element.parentNode.nodeType !== Node.ELEMENT_NODE) {\n        // Don't move modal's DOM position\n        document.body.appendChild(this._element);\n      }\n\n      this._element.style.display = 'block';\n\n      this._element.removeAttribute('aria-hidden');\n\n      this._element.setAttribute('aria-modal', true);\n\n      if ($(this._dialog).hasClass(ClassName$5.SCROLLABLE)) {\n        this._dialog.querySelector(Selector$5.MODAL_BODY).scrollTop = 0;\n      } else {\n        this._element.scrollTop = 0;\n      }\n\n      if (transition) {\n        Util.reflow(this._element);\n      }\n\n      $(this._element).addClass(ClassName$5.SHOW);\n\n      if (this._config.focus) {\n        this._enforceFocus();\n      }\n\n      var shownEvent = $.Event(Event$5.SHOWN, {\n        relatedTarget: relatedTarget\n      });\n\n      var transitionComplete = function transitionComplete() {\n        if (_this3._config.focus) {\n          _this3._element.focus();\n        }\n\n        _this3._isTransitioning = false;\n        $(_this3._element).trigger(shownEvent);\n      };\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._dialog);\n        $(this._dialog).one(Util.TRANSITION_END, transitionComplete).emulateTransitionEnd(transitionDuration);\n      } else {\n        transitionComplete();\n      }\n    };\n\n    _proto._enforceFocus = function _enforceFocus() {\n      var _this4 = this;\n\n      $(document).off(Event$5.FOCUSIN) // Guard against infinite focus loop\n      .on(Event$5.FOCUSIN, function (event) {\n        if (document !== event.target && _this4._element !== event.target && $(_this4._element).has(event.target).length === 0) {\n          _this4._element.focus();\n        }\n      });\n    };\n\n    _proto._setEscapeEvent = function _setEscapeEvent() {\n      var _this5 = this;\n\n      if (this._isShown && this._config.keyboard) {\n        $(this._element).on(Event$5.KEYDOWN_DISMISS, function (event) {\n          if (event.which === ESCAPE_KEYCODE$1) {\n            event.preventDefault();\n\n            _this5.hide();\n          }\n        });\n      } else if (!this._isShown) {\n        $(this._element).off(Event$5.KEYDOWN_DISMISS);\n      }\n    };\n\n    _proto._setResizeEvent = function _setResizeEvent() {\n      var _this6 = this;\n\n      if (this._isShown) {\n        $(window).on(Event$5.RESIZE, function (event) {\n          return _this6.handleUpdate(event);\n        });\n      } else {\n        $(window).off(Event$5.RESIZE);\n      }\n    };\n\n    _proto._hideModal = function _hideModal() {\n      var _this7 = this;\n\n      this._element.style.display = 'none';\n\n      this._element.setAttribute('aria-hidden', true);\n\n      this._element.removeAttribute('aria-modal');\n\n      this._isTransitioning = false;\n\n      this._showBackdrop(function () {\n        $(document.body).removeClass(ClassName$5.OPEN);\n\n        _this7._resetAdjustments();\n\n        _this7._resetScrollbar();\n\n        $(_this7._element).trigger(Event$5.HIDDEN);\n      });\n    };\n\n    _proto._removeBackdrop = function _removeBackdrop() {\n      if (this._backdrop) {\n        $(this._backdrop).remove();\n        this._backdrop = null;\n      }\n    };\n\n    _proto._showBackdrop = function _showBackdrop(callback) {\n      var _this8 = this;\n\n      var animate = $(this._element).hasClass(ClassName$5.FADE) ? ClassName$5.FADE : '';\n\n      if (this._isShown && this._config.backdrop) {\n        this._backdrop = document.createElement('div');\n        this._backdrop.className = ClassName$5.BACKDROP;\n\n        if (animate) {\n          this._backdrop.classList.add(animate);\n        }\n\n        $(this._backdrop).appendTo(document.body);\n        $(this._element).on(Event$5.CLICK_DISMISS, function (event) {\n          if (_this8._ignoreBackdropClick) {\n            _this8._ignoreBackdropClick = false;\n            return;\n          }\n\n          if (event.target !== event.currentTarget) {\n            return;\n          }\n\n          if (_this8._config.backdrop === 'static') {\n            _this8._element.focus();\n          } else {\n            _this8.hide();\n          }\n        });\n\n        if (animate) {\n          Util.reflow(this._backdrop);\n        }\n\n        $(this._backdrop).addClass(ClassName$5.SHOW);\n\n        if (!callback) {\n          return;\n        }\n\n        if (!animate) {\n          callback();\n          return;\n        }\n\n        var backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n        $(this._backdrop).one(Util.TRANSITION_END, callback).emulateTransitionEnd(backdropTransitionDuration);\n      } else if (!this._isShown && this._backdrop) {\n        $(this._backdrop).removeClass(ClassName$5.SHOW);\n\n        var callbackRemove = function callbackRemove() {\n          _this8._removeBackdrop();\n\n          if (callback) {\n            callback();\n          }\n        };\n\n        if ($(this._element).hasClass(ClassName$5.FADE)) {\n          var _backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n\n          $(this._backdrop).one(Util.TRANSITION_END, callbackRemove).emulateTransitionEnd(_backdropTransitionDuration);\n        } else {\n          callbackRemove();\n        }\n      } else if (callback) {\n        callback();\n      }\n    } // ----------------------------------------------------------------------\n    // the following methods are used to handle overflowing modals\n    // todo (fat): these should probably be refactored out of modal.js\n    // ----------------------------------------------------------------------\n    ;\n\n    _proto._adjustDialog = function _adjustDialog() {\n      var isModalOverflowing = this._element.scrollHeight > document.documentElement.clientHeight;\n\n      if (!this._isBodyOverflowing && isModalOverflowing) {\n        this._element.style.paddingLeft = this._scrollbarWidth + \"px\";\n      }\n\n      if (this._isBodyOverflowing && !isModalOverflowing) {\n        this._element.style.paddingRight = this._scrollbarWidth + \"px\";\n      }\n    };\n\n    _proto._resetAdjustments = function _resetAdjustments() {\n      this._element.style.paddingLeft = '';\n      this._element.style.paddingRight = '';\n    };\n\n    _proto._checkScrollbar = function _checkScrollbar() {\n      var rect = document.body.getBoundingClientRect();\n      this._isBodyOverflowing = rect.left + rect.right < window.innerWidth;\n      this._scrollbarWidth = this._getScrollbarWidth();\n    };\n\n    _proto._setScrollbar = function _setScrollbar() {\n      var _this9 = this;\n\n      if (this._isBodyOverflowing) {\n        // Note: DOMNode.style.paddingRight returns the actual value or '' if not set\n        //   while $(DOMNode).css('padding-right') returns the calculated value or 0 if not set\n        var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n        var stickyContent = [].slice.call(document.querySelectorAll(Selector$5.STICKY_CONTENT)); // Adjust fixed content padding\n\n        $(fixedContent).each(function (index, element) {\n          var actualPadding = element.style.paddingRight;\n          var calculatedPadding = $(element).css('padding-right');\n          $(element).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + _this9._scrollbarWidth + \"px\");\n        }); // Adjust sticky content margin\n\n        $(stickyContent).each(function (index, element) {\n          var actualMargin = element.style.marginRight;\n          var calculatedMargin = $(element).css('margin-right');\n          $(element).data('margin-right', actualMargin).css('margin-right', parseFloat(calculatedMargin) - _this9._scrollbarWidth + \"px\");\n        }); // Adjust body padding\n\n        var actualPadding = document.body.style.paddingRight;\n        var calculatedPadding = $(document.body).css('padding-right');\n        $(document.body).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + this._scrollbarWidth + \"px\");\n      }\n\n      $(document.body).addClass(ClassName$5.OPEN);\n    };\n\n    _proto._resetScrollbar = function _resetScrollbar() {\n      // Restore fixed content padding\n      var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n      $(fixedContent).each(function (index, element) {\n        var padding = $(element).data('padding-right');\n        $(element).removeData('padding-right');\n        element.style.paddingRight = padding ? padding : '';\n      }); // Restore sticky content\n\n      var elements = [].slice.call(document.querySelectorAll(\"\" + Selector$5.STICKY_CONTENT));\n      $(elements).each(function (index, element) {\n        var margin = $(element).data('margin-right');\n\n        if (typeof margin !== 'undefined') {\n          $(element).css('margin-right', margin).removeData('margin-right');\n        }\n      }); // Restore body padding\n\n      var padding = $(document.body).data('padding-right');\n      $(document.body).removeData('padding-right');\n      document.body.style.paddingRight = padding ? padding : '';\n    };\n\n    _proto._getScrollbarWidth = function _getScrollbarWidth() {\n      // thx d.walsh\n      var scrollDiv = document.createElement('div');\n      scrollDiv.className = ClassName$5.SCROLLBAR_MEASURER;\n      document.body.appendChild(scrollDiv);\n      var scrollbarWidth = scrollDiv.getBoundingClientRect().width - scrollDiv.clientWidth;\n      document.body.removeChild(scrollDiv);\n      return scrollbarWidth;\n    } // Static\n    ;\n\n    Modal._jQueryInterface = function _jQueryInterface(config, relatedTarget) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$5);\n\n        var _config = _objectSpread({}, Default$3, $(this).data(), typeof config === 'object' && config ? config : {});\n\n        if (!data) {\n          data = new Modal(this, _config);\n          $(this).data(DATA_KEY$5, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](relatedTarget);\n        } else if (_config.show) {\n          data.show(relatedTarget);\n        }\n      });\n    };\n\n    _createClass(Modal, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$5;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$3;\n      }\n    }]);\n\n    return Modal;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$5.CLICK_DATA_API, Selector$5.DATA_TOGGLE, function (event) {\n    var _this10 = this;\n\n    var target;\n    var selector = Util.getSelectorFromElement(this);\n\n    if (selector) {\n      target = document.querySelector(selector);\n    }\n\n    var config = $(target).data(DATA_KEY$5) ? 'toggle' : _objectSpread({}, $(target).data(), $(this).data());\n\n    if (this.tagName === 'A' || this.tagName === 'AREA') {\n      event.preventDefault();\n    }\n\n    var $target = $(target).one(Event$5.SHOW, function (showEvent) {\n      if (showEvent.isDefaultPrevented()) {\n        // Only register focus restorer if modal will actually get shown\n        return;\n      }\n\n      $target.one(Event$5.HIDDEN, function () {\n        if ($(_this10).is(':visible')) {\n          _this10.focus();\n        }\n      });\n    });\n\n    Modal._jQueryInterface.call($(target), config, this);\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$5] = Modal._jQueryInterface;\n  $.fn[NAME$5].Constructor = Modal;\n\n  $.fn[NAME$5].noConflict = function () {\n    $.fn[NAME$5] = JQUERY_NO_CONFLICT$5;\n    return Modal._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): tools/sanitizer.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  var uriAttrs = ['background', 'cite', 'href', 'itemtype', 'longdesc', 'poster', 'src', 'xlink:href'];\n  var ARIA_ATTRIBUTE_PATTERN = /^aria-[\\w-]*$/i;\n  var DefaultWhitelist = {\n    // Global attributes allowed on any supplied element below.\n    '*': ['class', 'dir', 'id', 'lang', 'role', ARIA_ATTRIBUTE_PATTERN],\n    a: ['target', 'href', 'title', 'rel'],\n    area: [],\n    b: [],\n    br: [],\n    col: [],\n    code: [],\n    div: [],\n    em: [],\n    hr: [],\n    h1: [],\n    h2: [],\n    h3: [],\n    h4: [],\n    h5: [],\n    h6: [],\n    i: [],\n    img: ['src', 'alt', 'title', 'width', 'height'],\n    li: [],\n    ol: [],\n    p: [],\n    pre: [],\n    s: [],\n    small: [],\n    span: [],\n    sub: [],\n    sup: [],\n    strong: [],\n    u: [],\n    ul: []\n    /**\n     * A pattern that recognizes a commonly useful subset of URLs that are safe.\n     *\n     * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n     */\n\n  };\n  var SAFE_URL_PATTERN = /^(?:(?:https?|mailto|ftp|tel|file):|[^&:/?#]*(?:[/?#]|$))/gi;\n  /**\n   * A pattern that matches safe data URLs. Only matches image, video and audio types.\n   *\n   * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n   */\n\n  var DATA_URL_PATTERN = /^data:(?:image\\/(?:bmp|gif|jpeg|jpg|png|tiff|webp)|video\\/(?:mpeg|mp4|ogg|webm)|audio\\/(?:mp3|oga|ogg|opus));base64,[a-z0-9+/]+=*$/i;\n\n  function allowedAttribute(attr, allowedAttributeList) {\n    var attrName = attr.nodeName.toLowerCase();\n\n    if (allowedAttributeList.indexOf(attrName) !== -1) {\n      if (uriAttrs.indexOf(attrName) !== -1) {\n        return Boolean(attr.nodeValue.match(SAFE_URL_PATTERN) || attr.nodeValue.match(DATA_URL_PATTERN));\n      }\n\n      return true;\n    }\n\n    var regExp = allowedAttributeList.filter(function (attrRegex) {\n      return attrRegex instanceof RegExp;\n    }); // Check if a regular expression validates the attribute.\n\n    for (var i = 0, l = regExp.length; i < l; i++) {\n      if (attrName.match(regExp[i])) {\n        return true;\n      }\n    }\n\n    return false;\n  }\n\n  function sanitizeHtml(unsafeHtml, whiteList, sanitizeFn) {\n    if (unsafeHtml.length === 0) {\n      return unsafeHtml;\n    }\n\n    if (sanitizeFn && typeof sanitizeFn === 'function') {\n      return sanitizeFn(unsafeHtml);\n    }\n\n    var domParser = new window.DOMParser();\n    var createdDocument = domParser.parseFromString(unsafeHtml, 'text/html');\n    var whitelistKeys = Object.keys(whiteList);\n    var elements = [].slice.call(createdDocument.body.querySelectorAll('*'));\n\n    var _loop = function _loop(i, len) {\n      var el = elements[i];\n      var elName = el.nodeName.toLowerCase();\n\n      if (whitelistKeys.indexOf(el.nodeName.toLowerCase()) === -1) {\n        el.parentNode.removeChild(el);\n        return \"continue\";\n      }\n\n      var attributeList = [].slice.call(el.attributes);\n      var whitelistedAttributes = [].concat(whiteList['*'] || [], whiteList[elName] || []);\n      attributeList.forEach(function (attr) {\n        if (!allowedAttribute(attr, whitelistedAttributes)) {\n          el.removeAttribute(attr.nodeName);\n        }\n      });\n    };\n\n    for (var i = 0, len = elements.length; i < len; i++) {\n      var _ret = _loop(i, len);\n\n      if (_ret === \"continue\") continue;\n    }\n\n    return createdDocument.body.innerHTML;\n  }\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$6 = 'tooltip';\n  var VERSION$6 = '4.3.1';\n  var DATA_KEY$6 = 'bs.tooltip';\n  var EVENT_KEY$6 = \".\" + DATA_KEY$6;\n  var JQUERY_NO_CONFLICT$6 = $.fn[NAME$6];\n  var CLASS_PREFIX = 'bs-tooltip';\n  var BSCLS_PREFIX_REGEX = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX + \"\\\\S+\", 'g');\n  var DISALLOWED_ATTRIBUTES = ['sanitize', 'whiteList', 'sanitizeFn'];\n  var DefaultType$4 = {\n    animation: 'boolean',\n    template: 'string',\n    title: '(string|element|function)',\n    trigger: 'string',\n    delay: '(number|object)',\n    html: 'boolean',\n    selector: '(string|boolean)',\n    placement: '(string|function)',\n    offset: '(number|string|function)',\n    container: '(string|element|boolean)',\n    fallbackPlacement: '(string|array)',\n    boundary: '(string|element)',\n    sanitize: 'boolean',\n    sanitizeFn: '(null|function)',\n    whiteList: 'object'\n  };\n  var AttachmentMap$1 = {\n    AUTO: 'auto',\n    TOP: 'top',\n    RIGHT: 'right',\n    BOTTOM: 'bottom',\n    LEFT: 'left'\n  };\n  var Default$4 = {\n    animation: true,\n    template: '<div class=\"tooltip\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<div class=\"tooltip-inner\"></div></div>',\n    trigger: 'hover focus',\n    title: '',\n    delay: 0,\n    html: false,\n    selector: false,\n    placement: 'top',\n    offset: 0,\n    container: false,\n    fallbackPlacement: 'flip',\n    boundary: 'scrollParent',\n    sanitize: true,\n    sanitizeFn: null,\n    whiteList: DefaultWhitelist\n  };\n  var HoverState = {\n    SHOW: 'show',\n    OUT: 'out'\n  };\n  var Event$6 = {\n    HIDE: \"hide\" + EVENT_KEY$6,\n    HIDDEN: \"hidden\" + EVENT_KEY$6,\n    SHOW: \"show\" + EVENT_KEY$6,\n    SHOWN: \"shown\" + EVENT_KEY$6,\n    INSERTED: \"inserted\" + EVENT_KEY$6,\n    CLICK: \"click\" + EVENT_KEY$6,\n    FOCUSIN: \"focusin\" + EVENT_KEY$6,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$6,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$6,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$6\n  };\n  var ClassName$6 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$6 = {\n    TOOLTIP: '.tooltip',\n    TOOLTIP_INNER: '.tooltip-inner',\n    ARROW: '.arrow'\n  };\n  var Trigger = {\n    HOVER: 'hover',\n    FOCUS: 'focus',\n    CLICK: 'click',\n    MANUAL: 'manual'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tooltip =\n  /*#__PURE__*/\n  function () {\n    function Tooltip(element, config) {\n      /**\n       * Check for Popper dependency\n       * Popper - https://popper.js.org\n       */\n      if (typeof Popper === 'undefined') {\n        throw new TypeError('Bootstrap\\'s tooltips require Popper.js (https://popper.js.org/)');\n      } // private\n\n\n      this._isEnabled = true;\n      this._timeout = 0;\n      this._hoverState = '';\n      this._activeTrigger = {};\n      this._popper = null; // Protected\n\n      this.element = element;\n      this.config = this._getConfig(config);\n      this.tip = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Tooltip.prototype;\n\n    // Public\n    _proto.enable = function enable() {\n      this._isEnabled = true;\n    };\n\n    _proto.disable = function disable() {\n      this._isEnabled = false;\n    };\n\n    _proto.toggleEnabled = function toggleEnabled() {\n      this._isEnabled = !this._isEnabled;\n    };\n\n    _proto.toggle = function toggle(event) {\n      if (!this._isEnabled) {\n        return;\n      }\n\n      if (event) {\n        var dataKey = this.constructor.DATA_KEY;\n        var context = $(event.currentTarget).data(dataKey);\n\n        if (!context) {\n          context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n          $(event.currentTarget).data(dataKey, context);\n        }\n\n        context._activeTrigger.click = !context._activeTrigger.click;\n\n        if (context._isWithActiveTrigger()) {\n          context._enter(null, context);\n        } else {\n          context._leave(null, context);\n        }\n      } else {\n        if ($(this.getTipElement()).hasClass(ClassName$6.SHOW)) {\n          this._leave(null, this);\n\n          return;\n        }\n\n        this._enter(null, this);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      $.removeData(this.element, this.constructor.DATA_KEY);\n      $(this.element).off(this.constructor.EVENT_KEY);\n      $(this.element).closest('.modal').off('hide.bs.modal');\n\n      if (this.tip) {\n        $(this.tip).remove();\n      }\n\n      this._isEnabled = null;\n      this._timeout = null;\n      this._hoverState = null;\n      this._activeTrigger = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n      }\n\n      this._popper = null;\n      this.element = null;\n      this.config = null;\n      this.tip = null;\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if ($(this.element).css('display') === 'none') {\n        throw new Error('Please use show on visible elements');\n      }\n\n      var showEvent = $.Event(this.constructor.Event.SHOW);\n\n      if (this.isWithContent() && this._isEnabled) {\n        $(this.element).trigger(showEvent);\n        var shadowRoot = Util.findShadowRoot(this.element);\n        var isInTheDom = $.contains(shadowRoot !== null ? shadowRoot : this.element.ownerDocument.documentElement, this.element);\n\n        if (showEvent.isDefaultPrevented() || !isInTheDom) {\n          return;\n        }\n\n        var tip = this.getTipElement();\n        var tipId = Util.getUID(this.constructor.NAME);\n        tip.setAttribute('id', tipId);\n        this.element.setAttribute('aria-describedby', tipId);\n        this.setContent();\n\n        if (this.config.animation) {\n          $(tip).addClass(ClassName$6.FADE);\n        }\n\n        var placement = typeof this.config.placement === 'function' ? this.config.placement.call(this, tip, this.element) : this.config.placement;\n\n        var attachment = this._getAttachment(placement);\n\n        this.addAttachmentClass(attachment);\n\n        var container = this._getContainer();\n\n        $(tip).data(this.constructor.DATA_KEY, this);\n\n        if (!$.contains(this.element.ownerDocument.documentElement, this.tip)) {\n          $(tip).appendTo(container);\n        }\n\n        $(this.element).trigger(this.constructor.Event.INSERTED);\n        this._popper = new Popper(this.element, tip, {\n          placement: attachment,\n          modifiers: {\n            offset: this._getOffset(),\n            flip: {\n              behavior: this.config.fallbackPlacement\n            },\n            arrow: {\n              element: Selector$6.ARROW\n            },\n            preventOverflow: {\n              boundariesElement: this.config.boundary\n            }\n          },\n          onCreate: function onCreate(data) {\n            if (data.originalPlacement !== data.placement) {\n              _this._handlePopperPlacementChange(data);\n            }\n          },\n          onUpdate: function onUpdate(data) {\n            return _this._handlePopperPlacementChange(data);\n          }\n        });\n        $(tip).addClass(ClassName$6.SHOW); // If this is a touch-enabled device we add extra\n        // empty mouseover listeners to the body's immediate children;\n        // only needed because of broken event delegation on iOS\n        // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().on('mouseover', null, $.noop);\n        }\n\n        var complete = function complete() {\n          if (_this.config.animation) {\n            _this._fixTransition();\n          }\n\n          var prevHoverState = _this._hoverState;\n          _this._hoverState = null;\n          $(_this.element).trigger(_this.constructor.Event.SHOWN);\n\n          if (prevHoverState === HoverState.OUT) {\n            _this._leave(null, _this);\n          }\n        };\n\n        if ($(this.tip).hasClass(ClassName$6.FADE)) {\n          var transitionDuration = Util.getTransitionDurationFromElement(this.tip);\n          $(this.tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n        } else {\n          complete();\n        }\n      }\n    };\n\n    _proto.hide = function hide(callback) {\n      var _this2 = this;\n\n      var tip = this.getTipElement();\n      var hideEvent = $.Event(this.constructor.Event.HIDE);\n\n      var complete = function complete() {\n        if (_this2._hoverState !== HoverState.SHOW && tip.parentNode) {\n          tip.parentNode.removeChild(tip);\n        }\n\n        _this2._cleanTipClass();\n\n        _this2.element.removeAttribute('aria-describedby');\n\n        $(_this2.element).trigger(_this2.constructor.Event.HIDDEN);\n\n        if (_this2._popper !== null) {\n          _this2._popper.destroy();\n        }\n\n        if (callback) {\n          callback();\n        }\n      };\n\n      $(this.element).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.SHOW); // If this is a touch-enabled device we remove the extra\n      // empty mouseover listeners we added for iOS support\n\n      if ('ontouchstart' in document.documentElement) {\n        $(document.body).children().off('mouseover', null, $.noop);\n      }\n\n      this._activeTrigger[Trigger.CLICK] = false;\n      this._activeTrigger[Trigger.FOCUS] = false;\n      this._activeTrigger[Trigger.HOVER] = false;\n\n      if ($(this.tip).hasClass(ClassName$6.FADE)) {\n        var transitionDuration = Util.getTransitionDurationFromElement(tip);\n        $(tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n\n      this._hoverState = '';\n    };\n\n    _proto.update = function update() {\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Protected\n    ;\n\n    _proto.isWithContent = function isWithContent() {\n      return Boolean(this.getTitle());\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var tip = this.getTipElement();\n      this.setElementContent($(tip.querySelectorAll(Selector$6.TOOLTIP_INNER)), this.getTitle());\n      $(tip).removeClass(ClassName$6.FADE + \" \" + ClassName$6.SHOW);\n    };\n\n    _proto.setElementContent = function setElementContent($element, content) {\n      if (typeof content === 'object' && (content.nodeType || content.jquery)) {\n        // Content is a DOM node or a jQuery\n        if (this.config.html) {\n          if (!$(content).parent().is($element)) {\n            $element.empty().append(content);\n          }\n        } else {\n          $element.text($(content).text());\n        }\n\n        return;\n      }\n\n      if (this.config.html) {\n        if (this.config.sanitize) {\n          content = sanitizeHtml(content, this.config.whiteList, this.config.sanitizeFn);\n        }\n\n        $element.html(content);\n      } else {\n        $element.text(content);\n      }\n    };\n\n    _proto.getTitle = function getTitle() {\n      var title = this.element.getAttribute('data-original-title');\n\n      if (!title) {\n        title = typeof this.config.title === 'function' ? this.config.title.call(this.element) : this.config.title;\n      }\n\n      return title;\n    } // Private\n    ;\n\n    _proto._getOffset = function _getOffset() {\n      var _this3 = this;\n\n      var offset = {};\n\n      if (typeof this.config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this3.config.offset(data.offsets, _this3.element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this.config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getContainer = function _getContainer() {\n      if (this.config.container === false) {\n        return document.body;\n      }\n\n      if (Util.isElement(this.config.container)) {\n        return $(this.config.container);\n      }\n\n      return $(document).find(this.config.container);\n    };\n\n    _proto._getAttachment = function _getAttachment(placement) {\n      return AttachmentMap$1[placement.toUpperCase()];\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this4 = this;\n\n      var triggers = this.config.trigger.split(' ');\n      triggers.forEach(function (trigger) {\n        if (trigger === 'click') {\n          $(_this4.element).on(_this4.constructor.Event.CLICK, _this4.config.selector, function (event) {\n            return _this4.toggle(event);\n          });\n        } else if (trigger !== Trigger.MANUAL) {\n          var eventIn = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSEENTER : _this4.constructor.Event.FOCUSIN;\n          var eventOut = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSELEAVE : _this4.constructor.Event.FOCUSOUT;\n          $(_this4.element).on(eventIn, _this4.config.selector, function (event) {\n            return _this4._enter(event);\n          }).on(eventOut, _this4.config.selector, function (event) {\n            return _this4._leave(event);\n          });\n        }\n      });\n      $(this.element).closest('.modal').on('hide.bs.modal', function () {\n        if (_this4.element) {\n          _this4.hide();\n        }\n      });\n\n      if (this.config.selector) {\n        this.config = _objectSpread({}, this.config, {\n          trigger: 'manual',\n          selector: ''\n        });\n      } else {\n        this._fixTitle();\n      }\n    };\n\n    _proto._fixTitle = function _fixTitle() {\n      var titleType = typeof this.element.getAttribute('data-original-title');\n\n      if (this.element.getAttribute('title') || titleType !== 'string') {\n        this.element.setAttribute('data-original-title', this.element.getAttribute('title') || '');\n        this.element.setAttribute('title', '');\n      }\n    };\n\n    _proto._enter = function _enter(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusin' ? Trigger.FOCUS : Trigger.HOVER] = true;\n      }\n\n      if ($(context.getTipElement()).hasClass(ClassName$6.SHOW) || context._hoverState === HoverState.SHOW) {\n        context._hoverState = HoverState.SHOW;\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.SHOW;\n\n      if (!context.config.delay || !context.config.delay.show) {\n        context.show();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.SHOW) {\n          context.show();\n        }\n      }, context.config.delay.show);\n    };\n\n    _proto._leave = function _leave(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusout' ? Trigger.FOCUS : Trigger.HOVER] = false;\n      }\n\n      if (context._isWithActiveTrigger()) {\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.OUT;\n\n      if (!context.config.delay || !context.config.delay.hide) {\n        context.hide();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.OUT) {\n          context.hide();\n        }\n      }, context.config.delay.hide);\n    };\n\n    _proto._isWithActiveTrigger = function _isWithActiveTrigger() {\n      for (var trigger in this._activeTrigger) {\n        if (this._activeTrigger[trigger]) {\n          return true;\n        }\n      }\n\n      return false;\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      var dataAttributes = $(this.element).data();\n      Object.keys(dataAttributes).forEach(function (dataAttr) {\n        if (DISALLOWED_ATTRIBUTES.indexOf(dataAttr) !== -1) {\n          delete dataAttributes[dataAttr];\n        }\n      });\n      config = _objectSpread({}, this.constructor.Default, dataAttributes, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.delay === 'number') {\n        config.delay = {\n          show: config.delay,\n          hide: config.delay\n        };\n      }\n\n      if (typeof config.title === 'number') {\n        config.title = config.title.toString();\n      }\n\n      if (typeof config.content === 'number') {\n        config.content = config.content.toString();\n      }\n\n      Util.typeCheckConfig(NAME$6, config, this.constructor.DefaultType);\n\n      if (config.sanitize) {\n        config.template = sanitizeHtml(config.template, config.whiteList, config.sanitizeFn);\n      }\n\n      return config;\n    };\n\n    _proto._getDelegateConfig = function _getDelegateConfig() {\n      var config = {};\n\n      if (this.config) {\n        for (var key in this.config) {\n          if (this.constructor.Default[key] !== this.config[key]) {\n            config[key] = this.config[key];\n          }\n        }\n      }\n\n      return config;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX);\n\n      if (tabClass !== null && tabClass.length) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    };\n\n    _proto._handlePopperPlacementChange = function _handlePopperPlacementChange(popperData) {\n      var popperInstance = popperData.instance;\n      this.tip = popperInstance.popper;\n\n      this._cleanTipClass();\n\n      this.addAttachmentClass(this._getAttachment(popperData.placement));\n    };\n\n    _proto._fixTransition = function _fixTransition() {\n      var tip = this.getTipElement();\n      var initConfigAnimation = this.config.animation;\n\n      if (tip.getAttribute('x-placement') !== null) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.FADE);\n      this.config.animation = false;\n      this.hide();\n      this.show();\n      this.config.animation = initConfigAnimation;\n    } // Static\n    ;\n\n    Tooltip._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$6);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Tooltip(this, _config);\n          $(this).data(DATA_KEY$6, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tooltip, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$6;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$4;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$6;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$6;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$6;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$6;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$4;\n      }\n    }]);\n\n    return Tooltip;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$6] = Tooltip._jQueryInterface;\n  $.fn[NAME$6].Constructor = Tooltip;\n\n  $.fn[NAME$6].noConflict = function () {\n    $.fn[NAME$6] = JQUERY_NO_CONFLICT$6;\n    return Tooltip._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$7 = 'popover';\n  var VERSION$7 = '4.3.1';\n  var DATA_KEY$7 = 'bs.popover';\n  var EVENT_KEY$7 = \".\" + DATA_KEY$7;\n  var JQUERY_NO_CONFLICT$7 = $.fn[NAME$7];\n  var CLASS_PREFIX$1 = 'bs-popover';\n  var BSCLS_PREFIX_REGEX$1 = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX$1 + \"\\\\S+\", 'g');\n\n  var Default$5 = _objectSpread({}, Tooltip.Default, {\n    placement: 'right',\n    trigger: 'click',\n    content: '',\n    template: '<div class=\"popover\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<h3 class=\"popover-header\"></h3>' + '<div class=\"popover-body\"></div></div>'\n  });\n\n  var DefaultType$5 = _objectSpread({}, Tooltip.DefaultType, {\n    content: '(string|element|function)'\n  });\n\n  var ClassName$7 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$7 = {\n    TITLE: '.popover-header',\n    CONTENT: '.popover-body'\n  };\n  var Event$7 = {\n    HIDE: \"hide\" + EVENT_KEY$7,\n    HIDDEN: \"hidden\" + EVENT_KEY$7,\n    SHOW: \"show\" + EVENT_KEY$7,\n    SHOWN: \"shown\" + EVENT_KEY$7,\n    INSERTED: \"inserted\" + EVENT_KEY$7,\n    CLICK: \"click\" + EVENT_KEY$7,\n    FOCUSIN: \"focusin\" + EVENT_KEY$7,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$7,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$7,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$7\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Popover =\n  /*#__PURE__*/\n  function (_Tooltip) {\n    _inheritsLoose(Popover, _Tooltip);\n\n    function Popover() {\n      return _Tooltip.apply(this, arguments) || this;\n    }\n\n    var _proto = Popover.prototype;\n\n    // Overrides\n    _proto.isWithContent = function isWithContent() {\n      return this.getTitle() || this._getContent();\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX$1 + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var $tip = $(this.getTipElement()); // We use append for html objects to maintain js events\n\n      this.setElementContent($tip.find(Selector$7.TITLE), this.getTitle());\n\n      var content = this._getContent();\n\n      if (typeof content === 'function') {\n        content = content.call(this.element);\n      }\n\n      this.setElementContent($tip.find(Selector$7.CONTENT), content);\n      $tip.removeClass(ClassName$7.FADE + \" \" + ClassName$7.SHOW);\n    } // Private\n    ;\n\n    _proto._getContent = function _getContent() {\n      return this.element.getAttribute('data-content') || this.config.content;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX$1);\n\n      if (tabClass !== null && tabClass.length > 0) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    } // Static\n    ;\n\n    Popover._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$7);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Popover(this, _config);\n          $(this).data(DATA_KEY$7, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Popover, null, [{\n      key: \"VERSION\",\n      // Getters\n      get: function get() {\n        return VERSION$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$5;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$7;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$7;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$7;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$7;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$5;\n      }\n    }]);\n\n    return Popover;\n  }(Tooltip);\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$7] = Popover._jQueryInterface;\n  $.fn[NAME$7].Constructor = Popover;\n\n  $.fn[NAME$7].noConflict = function () {\n    $.fn[NAME$7] = JQUERY_NO_CONFLICT$7;\n    return Popover._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$8 = 'scrollspy';\n  var VERSION$8 = '4.3.1';\n  var DATA_KEY$8 = 'bs.scrollspy';\n  var EVENT_KEY$8 = \".\" + DATA_KEY$8;\n  var DATA_API_KEY$6 = '.data-api';\n  var JQUERY_NO_CONFLICT$8 = $.fn[NAME$8];\n  var Default$6 = {\n    offset: 10,\n    method: 'auto',\n    target: ''\n  };\n  var DefaultType$6 = {\n    offset: 'number',\n    method: 'string',\n    target: '(string|element)'\n  };\n  var Event$8 = {\n    ACTIVATE: \"activate\" + EVENT_KEY$8,\n    SCROLL: \"scroll\" + EVENT_KEY$8,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$8 + DATA_API_KEY$6\n  };\n  var ClassName$8 = {\n    DROPDOWN_ITEM: 'dropdown-item',\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active'\n  };\n  var Selector$8 = {\n    DATA_SPY: '[data-spy=\"scroll\"]',\n    ACTIVE: '.active',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    NAV_LINKS: '.nav-link',\n    NAV_ITEMS: '.nav-item',\n    LIST_ITEMS: '.list-group-item',\n    DROPDOWN: '.dropdown',\n    DROPDOWN_ITEMS: '.dropdown-item',\n    DROPDOWN_TOGGLE: '.dropdown-toggle'\n  };\n  var OffsetMethod = {\n    OFFSET: 'offset',\n    POSITION: 'position'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var ScrollSpy =\n  /*#__PURE__*/\n  function () {\n    function ScrollSpy(element, config) {\n      var _this = this;\n\n      this._element = element;\n      this._scrollElement = element.tagName === 'BODY' ? window : element;\n      this._config = this._getConfig(config);\n      this._selector = this._config.target + \" \" + Selector$8.NAV_LINKS + \",\" + (this._config.target + \" \" + Selector$8.LIST_ITEMS + \",\") + (this._config.target + \" \" + Selector$8.DROPDOWN_ITEMS);\n      this._offsets = [];\n      this._targets = [];\n      this._activeTarget = null;\n      this._scrollHeight = 0;\n      $(this._scrollElement).on(Event$8.SCROLL, function (event) {\n        return _this._process(event);\n      });\n      this.refresh();\n\n      this._process();\n    } // Getters\n\n\n    var _proto = ScrollSpy.prototype;\n\n    // Public\n    _proto.refresh = function refresh() {\n      var _this2 = this;\n\n      var autoMethod = this._scrollElement === this._scrollElement.window ? OffsetMethod.OFFSET : OffsetMethod.POSITION;\n      var offsetMethod = this._config.method === 'auto' ? autoMethod : this._config.method;\n      var offsetBase = offsetMethod === OffsetMethod.POSITION ? this._getScrollTop() : 0;\n      this._offsets = [];\n      this._targets = [];\n      this._scrollHeight = this._getScrollHeight();\n      var targets = [].slice.call(document.querySelectorAll(this._selector));\n      targets.map(function (element) {\n        var target;\n        var targetSelector = Util.getSelectorFromElement(element);\n\n        if (targetSelector) {\n          target = document.querySelector(targetSelector);\n        }\n\n        if (target) {\n          var targetBCR = target.getBoundingClientRect();\n\n          if (targetBCR.width || targetBCR.height) {\n            // TODO (fat): remove sketch reliance on jQuery position/offset\n            return [$(target)[offsetMethod]().top + offsetBase, targetSelector];\n          }\n        }\n\n        return null;\n      }).filter(function (item) {\n        return item;\n      }).sort(function (a, b) {\n        return a[0] - b[0];\n      }).forEach(function (item) {\n        _this2._offsets.push(item[0]);\n\n        _this2._targets.push(item[1]);\n      });\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$8);\n      $(this._scrollElement).off(EVENT_KEY$8);\n      this._element = null;\n      this._scrollElement = null;\n      this._config = null;\n      this._selector = null;\n      this._offsets = null;\n      this._targets = null;\n      this._activeTarget = null;\n      this._scrollHeight = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$6, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.target !== 'string') {\n        var id = $(config.target).attr('id');\n\n        if (!id) {\n          id = Util.getUID(NAME$8);\n          $(config.target).attr('id', id);\n        }\n\n        config.target = \"#\" + id;\n      }\n\n      Util.typeCheckConfig(NAME$8, config, DefaultType$6);\n      return config;\n    };\n\n    _proto._getScrollTop = function _getScrollTop() {\n      return this._scrollElement === window ? this._scrollElement.pageYOffset : this._scrollElement.scrollTop;\n    };\n\n    _proto._getScrollHeight = function _getScrollHeight() {\n      return this._scrollElement.scrollHeight || Math.max(document.body.scrollHeight, document.documentElement.scrollHeight);\n    };\n\n    _proto._getOffsetHeight = function _getOffsetHeight() {\n      return this._scrollElement === window ? window.innerHeight : this._scrollElement.getBoundingClientRect().height;\n    };\n\n    _proto._process = function _process() {\n      var scrollTop = this._getScrollTop() + this._config.offset;\n\n      var scrollHeight = this._getScrollHeight();\n\n      var maxScroll = this._config.offset + scrollHeight - this._getOffsetHeight();\n\n      if (this._scrollHeight !== scrollHeight) {\n        this.refresh();\n      }\n\n      if (scrollTop >= maxScroll) {\n        var target = this._targets[this._targets.length - 1];\n\n        if (this._activeTarget !== target) {\n          this._activate(target);\n        }\n\n        return;\n      }\n\n      if (this._activeTarget && scrollTop < this._offsets[0] && this._offsets[0] > 0) {\n        this._activeTarget = null;\n\n        this._clear();\n\n        return;\n      }\n\n      var offsetLength = this._offsets.length;\n\n      for (var i = offsetLength; i--;) {\n        var isActiveTarget = this._activeTarget !== this._targets[i] && scrollTop >= this._offsets[i] && (typeof this._offsets[i + 1] === 'undefined' || scrollTop < this._offsets[i + 1]);\n\n        if (isActiveTarget) {\n          this._activate(this._targets[i]);\n        }\n      }\n    };\n\n    _proto._activate = function _activate(target) {\n      this._activeTarget = target;\n\n      this._clear();\n\n      var queries = this._selector.split(',').map(function (selector) {\n        return selector + \"[data-target=\\\"\" + target + \"\\\"],\" + selector + \"[href=\\\"\" + target + \"\\\"]\";\n      });\n\n      var $link = $([].slice.call(document.querySelectorAll(queries.join(','))));\n\n      if ($link.hasClass(ClassName$8.DROPDOWN_ITEM)) {\n        $link.closest(Selector$8.DROPDOWN).find(Selector$8.DROPDOWN_TOGGLE).addClass(ClassName$8.ACTIVE);\n        $link.addClass(ClassName$8.ACTIVE);\n      } else {\n        // Set triggered link as active\n        $link.addClass(ClassName$8.ACTIVE); // Set triggered links parents as active\n        // With both <ul> and <nav> markup a parent is the previous sibling of any nav ancestor\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_LINKS + \", \" + Selector$8.LIST_ITEMS).addClass(ClassName$8.ACTIVE); // Handle special case when .nav-link is inside .nav-item\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_ITEMS).children(Selector$8.NAV_LINKS).addClass(ClassName$8.ACTIVE);\n      }\n\n      $(this._scrollElement).trigger(Event$8.ACTIVATE, {\n        relatedTarget: target\n      });\n    };\n\n    _proto._clear = function _clear() {\n      [].slice.call(document.querySelectorAll(this._selector)).filter(function (node) {\n        return node.classList.contains(ClassName$8.ACTIVE);\n      }).forEach(function (node) {\n        return node.classList.remove(ClassName$8.ACTIVE);\n      });\n    } // Static\n    ;\n\n    ScrollSpy._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$8);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new ScrollSpy(this, _config);\n          $(this).data(DATA_KEY$8, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(ScrollSpy, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$8;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$6;\n      }\n    }]);\n\n    return ScrollSpy;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(window).on(Event$8.LOAD_DATA_API, function () {\n    var scrollSpys = [].slice.call(document.querySelectorAll(Selector$8.DATA_SPY));\n    var scrollSpysLength = scrollSpys.length;\n\n    for (var i = scrollSpysLength; i--;) {\n      var $spy = $(scrollSpys[i]);\n\n      ScrollSpy._jQueryInterface.call($spy, $spy.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$8] = ScrollSpy._jQueryInterface;\n  $.fn[NAME$8].Constructor = ScrollSpy;\n\n  $.fn[NAME$8].noConflict = function () {\n    $.fn[NAME$8] = JQUERY_NO_CONFLICT$8;\n    return ScrollSpy._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$9 = 'tab';\n  var VERSION$9 = '4.3.1';\n  var DATA_KEY$9 = 'bs.tab';\n  var EVENT_KEY$9 = \".\" + DATA_KEY$9;\n  var DATA_API_KEY$7 = '.data-api';\n  var JQUERY_NO_CONFLICT$9 = $.fn[NAME$9];\n  var Event$9 = {\n    HIDE: \"hide\" + EVENT_KEY$9,\n    HIDDEN: \"hidden\" + EVENT_KEY$9,\n    SHOW: \"show\" + EVENT_KEY$9,\n    SHOWN: \"shown\" + EVENT_KEY$9,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$9 + DATA_API_KEY$7\n  };\n  var ClassName$9 = {\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active',\n    DISABLED: 'disabled',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$9 = {\n    DROPDOWN: '.dropdown',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    ACTIVE: '.active',\n    ACTIVE_UL: '> li > .active',\n    DATA_TOGGLE: '[data-toggle=\"tab\"], [data-toggle=\"pill\"], [data-toggle=\"list\"]',\n    DROPDOWN_TOGGLE: '.dropdown-toggle',\n    DROPDOWN_ACTIVE_CHILD: '> .dropdown-menu .active'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tab =\n  /*#__PURE__*/\n  function () {\n    function Tab(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Tab.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._element.parentNode && this._element.parentNode.nodeType === Node.ELEMENT_NODE && $(this._element).hasClass(ClassName$9.ACTIVE) || $(this._element).hasClass(ClassName$9.DISABLED)) {\n        return;\n      }\n\n      var target;\n      var previous;\n      var listElement = $(this._element).closest(Selector$9.NAV_LIST_GROUP)[0];\n      var selector = Util.getSelectorFromElement(this._element);\n\n      if (listElement) {\n        var itemSelector = listElement.nodeName === 'UL' || listElement.nodeName === 'OL' ? Selector$9.ACTIVE_UL : Selector$9.ACTIVE;\n        previous = $.makeArray($(listElement).find(itemSelector));\n        previous = previous[previous.length - 1];\n      }\n\n      var hideEvent = $.Event(Event$9.HIDE, {\n        relatedTarget: this._element\n      });\n      var showEvent = $.Event(Event$9.SHOW, {\n        relatedTarget: previous\n      });\n\n      if (previous) {\n        $(previous).trigger(hideEvent);\n      }\n\n      $(this._element).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented() || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (selector) {\n        target = document.querySelector(selector);\n      }\n\n      this._activate(this._element, listElement);\n\n      var complete = function complete() {\n        var hiddenEvent = $.Event(Event$9.HIDDEN, {\n          relatedTarget: _this._element\n        });\n        var shownEvent = $.Event(Event$9.SHOWN, {\n          relatedTarget: previous\n        });\n        $(previous).trigger(hiddenEvent);\n        $(_this._element).trigger(shownEvent);\n      };\n\n      if (target) {\n        this._activate(target, target.parentNode, complete);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$9);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._activate = function _activate(element, container, callback) {\n      var _this2 = this;\n\n      var activeElements = container && (container.nodeName === 'UL' || container.nodeName === 'OL') ? $(container).find(Selector$9.ACTIVE_UL) : $(container).children(Selector$9.ACTIVE);\n      var active = activeElements[0];\n      var isTransitioning = callback && active && $(active).hasClass(ClassName$9.FADE);\n\n      var complete = function complete() {\n        return _this2._transitionComplete(element, active, callback);\n      };\n\n      if (active && isTransitioning) {\n        var transitionDuration = Util.getTransitionDurationFromElement(active);\n        $(active).removeClass(ClassName$9.SHOW).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto._transitionComplete = function _transitionComplete(element, active, callback) {\n      if (active) {\n        $(active).removeClass(ClassName$9.ACTIVE);\n        var dropdownChild = $(active.parentNode).find(Selector$9.DROPDOWN_ACTIVE_CHILD)[0];\n\n        if (dropdownChild) {\n          $(dropdownChild).removeClass(ClassName$9.ACTIVE);\n        }\n\n        if (active.getAttribute('role') === 'tab') {\n          active.setAttribute('aria-selected', false);\n        }\n      }\n\n      $(element).addClass(ClassName$9.ACTIVE);\n\n      if (element.getAttribute('role') === 'tab') {\n        element.setAttribute('aria-selected', true);\n      }\n\n      Util.reflow(element);\n\n      if (element.classList.contains(ClassName$9.FADE)) {\n        element.classList.add(ClassName$9.SHOW);\n      }\n\n      if (element.parentNode && $(element.parentNode).hasClass(ClassName$9.DROPDOWN_MENU)) {\n        var dropdownElement = $(element).closest(Selector$9.DROPDOWN)[0];\n\n        if (dropdownElement) {\n          var dropdownToggleList = [].slice.call(dropdownElement.querySelectorAll(Selector$9.DROPDOWN_TOGGLE));\n          $(dropdownToggleList).addClass(ClassName$9.ACTIVE);\n        }\n\n        element.setAttribute('aria-expanded', true);\n      }\n\n      if (callback) {\n        callback();\n      }\n    } // Static\n    ;\n\n    Tab._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$9);\n\n        if (!data) {\n          data = new Tab(this);\n          $this.data(DATA_KEY$9, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tab, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$9;\n      }\n    }]);\n\n    return Tab;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$9.CLICK_DATA_API, Selector$9.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n\n    Tab._jQueryInterface.call($(this), 'show');\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$9] = Tab._jQueryInterface;\n  $.fn[NAME$9].Constructor = Tab;\n\n  $.fn[NAME$9].noConflict = function () {\n    $.fn[NAME$9] = JQUERY_NO_CONFLICT$9;\n    return Tab._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$a = 'toast';\n  var VERSION$a = '4.3.1';\n  var DATA_KEY$a = 'bs.toast';\n  var EVENT_KEY$a = \".\" + DATA_KEY$a;\n  var JQUERY_NO_CONFLICT$a = $.fn[NAME$a];\n  var Event$a = {\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$a,\n    HIDE: \"hide\" + EVENT_KEY$a,\n    HIDDEN: \"hidden\" + EVENT_KEY$a,\n    SHOW: \"show\" + EVENT_KEY$a,\n    SHOWN: \"shown\" + EVENT_KEY$a\n  };\n  var ClassName$a = {\n    FADE: 'fade',\n    HIDE: 'hide',\n    SHOW: 'show',\n    SHOWING: 'showing'\n  };\n  var DefaultType$7 = {\n    animation: 'boolean',\n    autohide: 'boolean',\n    delay: 'number'\n  };\n  var Default$7 = {\n    animation: true,\n    autohide: true,\n    delay: 500\n  };\n  var Selector$a = {\n    DATA_DISMISS: '[data-dismiss=\"toast\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Toast =\n  /*#__PURE__*/\n  function () {\n    function Toast(element, config) {\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._timeout = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Toast.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      $(this._element).trigger(Event$a.SHOW);\n\n      if (this._config.animation) {\n        this._element.classList.add(ClassName$a.FADE);\n      }\n\n      var complete = function complete() {\n        _this._element.classList.remove(ClassName$a.SHOWING);\n\n        _this._element.classList.add(ClassName$a.SHOW);\n\n        $(_this._element).trigger(Event$a.SHOWN);\n\n        if (_this._config.autohide) {\n          _this.hide();\n        }\n      };\n\n      this._element.classList.remove(ClassName$a.HIDE);\n\n      this._element.classList.add(ClassName$a.SHOWING);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.hide = function hide(withoutTimeout) {\n      var _this2 = this;\n\n      if (!this._element.classList.contains(ClassName$a.SHOW)) {\n        return;\n      }\n\n      $(this._element).trigger(Event$a.HIDE);\n\n      if (withoutTimeout) {\n        this._close();\n      } else {\n        this._timeout = setTimeout(function () {\n          _this2._close();\n        }, this._config.delay);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      this._timeout = null;\n\n      if (this._element.classList.contains(ClassName$a.SHOW)) {\n        this._element.classList.remove(ClassName$a.SHOW);\n      }\n\n      $(this._element).off(Event$a.CLICK_DISMISS);\n      $.removeData(this._element, DATA_KEY$a);\n      this._element = null;\n      this._config = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$7, $(this._element).data(), typeof config === 'object' && config ? config : {});\n      Util.typeCheckConfig(NAME$a, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this3 = this;\n\n      $(this._element).on(Event$a.CLICK_DISMISS, Selector$a.DATA_DISMISS, function () {\n        return _this3.hide(true);\n      });\n    };\n\n    _proto._close = function _close() {\n      var _this4 = this;\n\n      var complete = function complete() {\n        _this4._element.classList.add(ClassName$a.HIDE);\n\n        $(_this4._element).trigger(Event$a.HIDDEN);\n      };\n\n      this._element.classList.remove(ClassName$a.SHOW);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    } // Static\n    ;\n\n    Toast._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY$a);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new Toast(this, _config);\n          $element.data(DATA_KEY$a, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](this);\n        }\n      });\n    };\n\n    _createClass(Toast, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$a;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$7;\n      }\n    }]);\n\n    return Toast;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$a] = Toast._jQueryInterface;\n  $.fn[NAME$a].Constructor = Toast;\n\n  $.fn[NAME$a].noConflict = function () {\n    $.fn[NAME$a] = JQUERY_NO_CONFLICT$a;\n    return Toast._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): index.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n\n  (function () {\n    if (typeof $ === 'undefined') {\n      throw new TypeError('Bootstrap\\'s JavaScript requires jQuery. jQuery must be included before Bootstrap\\'s JavaScript.');\n    }\n\n    var version = $.fn.jquery.split(' ')[0].split('.');\n    var minMajor = 1;\n    var ltMajor = 2;\n    var minMinor = 9;\n    var minPatch = 1;\n    var maxMajor = 4;\n\n    if (version[0] < ltMajor && version[1] < minMinor || version[0] === minMajor && version[1] === minMinor && version[2] < minPatch || version[0] >= maxMajor) {\n      throw new Error('Bootstrap\\'s JavaScript requires at least jQuery v1.9.1 but less than v4.0.0');\n    }\n  })();\n\n  exports.Util = Util;\n  exports.Alert = Alert;\n  exports.Button = Button;\n  exports.Carousel = Carousel;\n  exports.Collapse = Collapse;\n  exports.Dropdown = Dropdown;\n  exports.Modal = Modal;\n  exports.Popover = Popover;\n  exports.Scrollspy = ScrollSpy;\n  exports.Tab = Tab;\n  exports.Toast = Toast;\n  exports.Tooltip = Tooltip;\n\n  Object.defineProperty(exports, '__esModule', { value: true });\n\n}));\n//# sourceMappingURL=bootstrap.bundle.js.map\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/bootstrap/js/bootstrap.js",
    "content": "/*!\n  * Bootstrap v4.3.1 (https://getbootstrap.com/)\n  * Copyright 2011-2019 The Bootstrap Authors (https://github.com/twbs/bootstrap/graphs/contributors)\n  * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n  */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? factory(exports, require('jquery'), require('popper.js')) :\n  typeof define === 'function' && define.amd ? define(['exports', 'jquery', 'popper.js'], factory) :\n  (global = global || self, factory(global.bootstrap = {}, global.jQuery, global.Popper));\n}(this, function (exports, $, Popper) { 'use strict';\n\n  $ = $ && $.hasOwnProperty('default') ? $['default'] : $;\n  Popper = Popper && Popper.hasOwnProperty('default') ? Popper['default'] : Popper;\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _inheritsLoose(subClass, superClass) {\n    subClass.prototype = Object.create(superClass.prototype);\n    subClass.prototype.constructor = subClass;\n    subClass.__proto__ = superClass;\n  }\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): util.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  /**\n   * ------------------------------------------------------------------------\n   * Private TransitionEnd Helpers\n   * ------------------------------------------------------------------------\n   */\n\n  var TRANSITION_END = 'transitionend';\n  var MAX_UID = 1000000;\n  var MILLISECONDS_MULTIPLIER = 1000; // Shoutout AngusCroll (https://goo.gl/pxwQGp)\n\n  function toType(obj) {\n    return {}.toString.call(obj).match(/\\s([a-z]+)/i)[1].toLowerCase();\n  }\n\n  function getSpecialTransitionEndEvent() {\n    return {\n      bindType: TRANSITION_END,\n      delegateType: TRANSITION_END,\n      handle: function handle(event) {\n        if ($(event.target).is(this)) {\n          return event.handleObj.handler.apply(this, arguments); // eslint-disable-line prefer-rest-params\n        }\n\n        return undefined; // eslint-disable-line no-undefined\n      }\n    };\n  }\n\n  function transitionEndEmulator(duration) {\n    var _this = this;\n\n    var called = false;\n    $(this).one(Util.TRANSITION_END, function () {\n      called = true;\n    });\n    setTimeout(function () {\n      if (!called) {\n        Util.triggerTransitionEnd(_this);\n      }\n    }, duration);\n    return this;\n  }\n\n  function setTransitionEndSupport() {\n    $.fn.emulateTransitionEnd = transitionEndEmulator;\n    $.event.special[Util.TRANSITION_END] = getSpecialTransitionEndEvent();\n  }\n  /**\n   * --------------------------------------------------------------------------\n   * Public Util Api\n   * --------------------------------------------------------------------------\n   */\n\n\n  var Util = {\n    TRANSITION_END: 'bsTransitionEnd',\n    getUID: function getUID(prefix) {\n      do {\n        // eslint-disable-next-line no-bitwise\n        prefix += ~~(Math.random() * MAX_UID); // \"~~\" acts like a faster Math.floor() here\n      } while (document.getElementById(prefix));\n\n      return prefix;\n    },\n    getSelectorFromElement: function getSelectorFromElement(element) {\n      var selector = element.getAttribute('data-target');\n\n      if (!selector || selector === '#') {\n        var hrefAttr = element.getAttribute('href');\n        selector = hrefAttr && hrefAttr !== '#' ? hrefAttr.trim() : '';\n      }\n\n      try {\n        return document.querySelector(selector) ? selector : null;\n      } catch (err) {\n        return null;\n      }\n    },\n    getTransitionDurationFromElement: function getTransitionDurationFromElement(element) {\n      if (!element) {\n        return 0;\n      } // Get transition-duration of the element\n\n\n      var transitionDuration = $(element).css('transition-duration');\n      var transitionDelay = $(element).css('transition-delay');\n      var floatTransitionDuration = parseFloat(transitionDuration);\n      var floatTransitionDelay = parseFloat(transitionDelay); // Return 0 if element or transition duration is not found\n\n      if (!floatTransitionDuration && !floatTransitionDelay) {\n        return 0;\n      } // If multiple durations are defined, take the first\n\n\n      transitionDuration = transitionDuration.split(',')[0];\n      transitionDelay = transitionDelay.split(',')[0];\n      return (parseFloat(transitionDuration) + parseFloat(transitionDelay)) * MILLISECONDS_MULTIPLIER;\n    },\n    reflow: function reflow(element) {\n      return element.offsetHeight;\n    },\n    triggerTransitionEnd: function triggerTransitionEnd(element) {\n      $(element).trigger(TRANSITION_END);\n    },\n    // TODO: Remove in v5\n    supportsTransitionEnd: function supportsTransitionEnd() {\n      return Boolean(TRANSITION_END);\n    },\n    isElement: function isElement(obj) {\n      return (obj[0] || obj).nodeType;\n    },\n    typeCheckConfig: function typeCheckConfig(componentName, config, configTypes) {\n      for (var property in configTypes) {\n        if (Object.prototype.hasOwnProperty.call(configTypes, property)) {\n          var expectedTypes = configTypes[property];\n          var value = config[property];\n          var valueType = value && Util.isElement(value) ? 'element' : toType(value);\n\n          if (!new RegExp(expectedTypes).test(valueType)) {\n            throw new Error(componentName.toUpperCase() + \": \" + (\"Option \\\"\" + property + \"\\\" provided type \\\"\" + valueType + \"\\\" \") + (\"but expected type \\\"\" + expectedTypes + \"\\\".\"));\n          }\n        }\n      }\n    },\n    findShadowRoot: function findShadowRoot(element) {\n      if (!document.documentElement.attachShadow) {\n        return null;\n      } // Can find the shadow root otherwise it'll return the document\n\n\n      if (typeof element.getRootNode === 'function') {\n        var root = element.getRootNode();\n        return root instanceof ShadowRoot ? root : null;\n      }\n\n      if (element instanceof ShadowRoot) {\n        return element;\n      } // when we don't find a shadow root\n\n\n      if (!element.parentNode) {\n        return null;\n      }\n\n      return Util.findShadowRoot(element.parentNode);\n    }\n  };\n  setTransitionEndSupport();\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME = 'alert';\n  var VERSION = '4.3.1';\n  var DATA_KEY = 'bs.alert';\n  var EVENT_KEY = \".\" + DATA_KEY;\n  var DATA_API_KEY = '.data-api';\n  var JQUERY_NO_CONFLICT = $.fn[NAME];\n  var Selector = {\n    DISMISS: '[data-dismiss=\"alert\"]'\n  };\n  var Event = {\n    CLOSE: \"close\" + EVENT_KEY,\n    CLOSED: \"closed\" + EVENT_KEY,\n    CLICK_DATA_API: \"click\" + EVENT_KEY + DATA_API_KEY\n  };\n  var ClassName = {\n    ALERT: 'alert',\n    FADE: 'fade',\n    SHOW: 'show'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Alert =\n  /*#__PURE__*/\n  function () {\n    function Alert(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Alert.prototype;\n\n    // Public\n    _proto.close = function close(element) {\n      var rootElement = this._element;\n\n      if (element) {\n        rootElement = this._getRootElement(element);\n      }\n\n      var customEvent = this._triggerCloseEvent(rootElement);\n\n      if (customEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._removeElement(rootElement);\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._getRootElement = function _getRootElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      var parent = false;\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      if (!parent) {\n        parent = $(element).closest(\".\" + ClassName.ALERT)[0];\n      }\n\n      return parent;\n    };\n\n    _proto._triggerCloseEvent = function _triggerCloseEvent(element) {\n      var closeEvent = $.Event(Event.CLOSE);\n      $(element).trigger(closeEvent);\n      return closeEvent;\n    };\n\n    _proto._removeElement = function _removeElement(element) {\n      var _this = this;\n\n      $(element).removeClass(ClassName.SHOW);\n\n      if (!$(element).hasClass(ClassName.FADE)) {\n        this._destroyElement(element);\n\n        return;\n      }\n\n      var transitionDuration = Util.getTransitionDurationFromElement(element);\n      $(element).one(Util.TRANSITION_END, function (event) {\n        return _this._destroyElement(element, event);\n      }).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto._destroyElement = function _destroyElement(element) {\n      $(element).detach().trigger(Event.CLOSED).remove();\n    } // Static\n    ;\n\n    Alert._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY);\n\n        if (!data) {\n          data = new Alert(this);\n          $element.data(DATA_KEY, data);\n        }\n\n        if (config === 'close') {\n          data[config](this);\n        }\n      });\n    };\n\n    Alert._handleDismiss = function _handleDismiss(alertInstance) {\n      return function (event) {\n        if (event) {\n          event.preventDefault();\n        }\n\n        alertInstance.close(this);\n      };\n    };\n\n    _createClass(Alert, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION;\n      }\n    }]);\n\n    return Alert;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event.CLICK_DATA_API, Selector.DISMISS, Alert._handleDismiss(new Alert()));\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME] = Alert._jQueryInterface;\n  $.fn[NAME].Constructor = Alert;\n\n  $.fn[NAME].noConflict = function () {\n    $.fn[NAME] = JQUERY_NO_CONFLICT;\n    return Alert._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$1 = 'button';\n  var VERSION$1 = '4.3.1';\n  var DATA_KEY$1 = 'bs.button';\n  var EVENT_KEY$1 = \".\" + DATA_KEY$1;\n  var DATA_API_KEY$1 = '.data-api';\n  var JQUERY_NO_CONFLICT$1 = $.fn[NAME$1];\n  var ClassName$1 = {\n    ACTIVE: 'active',\n    BUTTON: 'btn',\n    FOCUS: 'focus'\n  };\n  var Selector$1 = {\n    DATA_TOGGLE_CARROT: '[data-toggle^=\"button\"]',\n    DATA_TOGGLE: '[data-toggle=\"buttons\"]',\n    INPUT: 'input:not([type=\"hidden\"])',\n    ACTIVE: '.active',\n    BUTTON: '.btn'\n  };\n  var Event$1 = {\n    CLICK_DATA_API: \"click\" + EVENT_KEY$1 + DATA_API_KEY$1,\n    FOCUS_BLUR_DATA_API: \"focus\" + EVENT_KEY$1 + DATA_API_KEY$1 + \" \" + (\"blur\" + EVENT_KEY$1 + DATA_API_KEY$1)\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Button =\n  /*#__PURE__*/\n  function () {\n    function Button(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Button.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      var triggerChangeEvent = true;\n      var addAriaPressed = true;\n      var rootElement = $(this._element).closest(Selector$1.DATA_TOGGLE)[0];\n\n      if (rootElement) {\n        var input = this._element.querySelector(Selector$1.INPUT);\n\n        if (input) {\n          if (input.type === 'radio') {\n            if (input.checked && this._element.classList.contains(ClassName$1.ACTIVE)) {\n              triggerChangeEvent = false;\n            } else {\n              var activeElement = rootElement.querySelector(Selector$1.ACTIVE);\n\n              if (activeElement) {\n                $(activeElement).removeClass(ClassName$1.ACTIVE);\n              }\n            }\n          }\n\n          if (triggerChangeEvent) {\n            if (input.hasAttribute('disabled') || rootElement.hasAttribute('disabled') || input.classList.contains('disabled') || rootElement.classList.contains('disabled')) {\n              return;\n            }\n\n            input.checked = !this._element.classList.contains(ClassName$1.ACTIVE);\n            $(input).trigger('change');\n          }\n\n          input.focus();\n          addAriaPressed = false;\n        }\n      }\n\n      if (addAriaPressed) {\n        this._element.setAttribute('aria-pressed', !this._element.classList.contains(ClassName$1.ACTIVE));\n      }\n\n      if (triggerChangeEvent) {\n        $(this._element).toggleClass(ClassName$1.ACTIVE);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$1);\n      this._element = null;\n    } // Static\n    ;\n\n    Button._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$1);\n\n        if (!data) {\n          data = new Button(this);\n          $(this).data(DATA_KEY$1, data);\n        }\n\n        if (config === 'toggle') {\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Button, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$1;\n      }\n    }]);\n\n    return Button;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$1.CLICK_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    event.preventDefault();\n    var button = event.target;\n\n    if (!$(button).hasClass(ClassName$1.BUTTON)) {\n      button = $(button).closest(Selector$1.BUTTON);\n    }\n\n    Button._jQueryInterface.call($(button), 'toggle');\n  }).on(Event$1.FOCUS_BLUR_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    var button = $(event.target).closest(Selector$1.BUTTON)[0];\n    $(button).toggleClass(ClassName$1.FOCUS, /^focus(in)?$/.test(event.type));\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$1] = Button._jQueryInterface;\n  $.fn[NAME$1].Constructor = Button;\n\n  $.fn[NAME$1].noConflict = function () {\n    $.fn[NAME$1] = JQUERY_NO_CONFLICT$1;\n    return Button._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$2 = 'carousel';\n  var VERSION$2 = '4.3.1';\n  var DATA_KEY$2 = 'bs.carousel';\n  var EVENT_KEY$2 = \".\" + DATA_KEY$2;\n  var DATA_API_KEY$2 = '.data-api';\n  var JQUERY_NO_CONFLICT$2 = $.fn[NAME$2];\n  var ARROW_LEFT_KEYCODE = 37; // KeyboardEvent.which value for left arrow key\n\n  var ARROW_RIGHT_KEYCODE = 39; // KeyboardEvent.which value for right arrow key\n\n  var TOUCHEVENT_COMPAT_WAIT = 500; // Time for mouse compat events to fire after touch\n\n  var SWIPE_THRESHOLD = 40;\n  var Default = {\n    interval: 5000,\n    keyboard: true,\n    slide: false,\n    pause: 'hover',\n    wrap: true,\n    touch: true\n  };\n  var DefaultType = {\n    interval: '(number|boolean)',\n    keyboard: 'boolean',\n    slide: '(boolean|string)',\n    pause: '(string|boolean)',\n    wrap: 'boolean',\n    touch: 'boolean'\n  };\n  var Direction = {\n    NEXT: 'next',\n    PREV: 'prev',\n    LEFT: 'left',\n    RIGHT: 'right'\n  };\n  var Event$2 = {\n    SLIDE: \"slide\" + EVENT_KEY$2,\n    SLID: \"slid\" + EVENT_KEY$2,\n    KEYDOWN: \"keydown\" + EVENT_KEY$2,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$2,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$2,\n    TOUCHSTART: \"touchstart\" + EVENT_KEY$2,\n    TOUCHMOVE: \"touchmove\" + EVENT_KEY$2,\n    TOUCHEND: \"touchend\" + EVENT_KEY$2,\n    POINTERDOWN: \"pointerdown\" + EVENT_KEY$2,\n    POINTERUP: \"pointerup\" + EVENT_KEY$2,\n    DRAG_START: \"dragstart\" + EVENT_KEY$2,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$2 + DATA_API_KEY$2,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$2 + DATA_API_KEY$2\n  };\n  var ClassName$2 = {\n    CAROUSEL: 'carousel',\n    ACTIVE: 'active',\n    SLIDE: 'slide',\n    RIGHT: 'carousel-item-right',\n    LEFT: 'carousel-item-left',\n    NEXT: 'carousel-item-next',\n    PREV: 'carousel-item-prev',\n    ITEM: 'carousel-item',\n    POINTER_EVENT: 'pointer-event'\n  };\n  var Selector$2 = {\n    ACTIVE: '.active',\n    ACTIVE_ITEM: '.active.carousel-item',\n    ITEM: '.carousel-item',\n    ITEM_IMG: '.carousel-item img',\n    NEXT_PREV: '.carousel-item-next, .carousel-item-prev',\n    INDICATORS: '.carousel-indicators',\n    DATA_SLIDE: '[data-slide], [data-slide-to]',\n    DATA_RIDE: '[data-ride=\"carousel\"]'\n  };\n  var PointerType = {\n    TOUCH: 'touch',\n    PEN: 'pen'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Carousel =\n  /*#__PURE__*/\n  function () {\n    function Carousel(element, config) {\n      this._items = null;\n      this._interval = null;\n      this._activeElement = null;\n      this._isPaused = false;\n      this._isSliding = false;\n      this.touchTimeout = null;\n      this.touchStartX = 0;\n      this.touchDeltaX = 0;\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._indicatorsElement = this._element.querySelector(Selector$2.INDICATORS);\n      this._touchSupported = 'ontouchstart' in document.documentElement || navigator.maxTouchPoints > 0;\n      this._pointerEvent = Boolean(window.PointerEvent || window.MSPointerEvent);\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Carousel.prototype;\n\n    // Public\n    _proto.next = function next() {\n      if (!this._isSliding) {\n        this._slide(Direction.NEXT);\n      }\n    };\n\n    _proto.nextWhenVisible = function nextWhenVisible() {\n      // Don't call next when the page isn't visible\n      // or the carousel or its parent isn't visible\n      if (!document.hidden && $(this._element).is(':visible') && $(this._element).css('visibility') !== 'hidden') {\n        this.next();\n      }\n    };\n\n    _proto.prev = function prev() {\n      if (!this._isSliding) {\n        this._slide(Direction.PREV);\n      }\n    };\n\n    _proto.pause = function pause(event) {\n      if (!event) {\n        this._isPaused = true;\n      }\n\n      if (this._element.querySelector(Selector$2.NEXT_PREV)) {\n        Util.triggerTransitionEnd(this._element);\n        this.cycle(true);\n      }\n\n      clearInterval(this._interval);\n      this._interval = null;\n    };\n\n    _proto.cycle = function cycle(event) {\n      if (!event) {\n        this._isPaused = false;\n      }\n\n      if (this._interval) {\n        clearInterval(this._interval);\n        this._interval = null;\n      }\n\n      if (this._config.interval && !this._isPaused) {\n        this._interval = setInterval((document.visibilityState ? this.nextWhenVisible : this.next).bind(this), this._config.interval);\n      }\n    };\n\n    _proto.to = function to(index) {\n      var _this = this;\n\n      this._activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeIndex = this._getItemIndex(this._activeElement);\n\n      if (index > this._items.length - 1 || index < 0) {\n        return;\n      }\n\n      if (this._isSliding) {\n        $(this._element).one(Event$2.SLID, function () {\n          return _this.to(index);\n        });\n        return;\n      }\n\n      if (activeIndex === index) {\n        this.pause();\n        this.cycle();\n        return;\n      }\n\n      var direction = index > activeIndex ? Direction.NEXT : Direction.PREV;\n\n      this._slide(direction, this._items[index]);\n    };\n\n    _proto.dispose = function dispose() {\n      $(this._element).off(EVENT_KEY$2);\n      $.removeData(this._element, DATA_KEY$2);\n      this._items = null;\n      this._config = null;\n      this._element = null;\n      this._interval = null;\n      this._isPaused = null;\n      this._isSliding = null;\n      this._activeElement = null;\n      this._indicatorsElement = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default, config);\n      Util.typeCheckConfig(NAME$2, config, DefaultType);\n      return config;\n    };\n\n    _proto._handleSwipe = function _handleSwipe() {\n      var absDeltax = Math.abs(this.touchDeltaX);\n\n      if (absDeltax <= SWIPE_THRESHOLD) {\n        return;\n      }\n\n      var direction = absDeltax / this.touchDeltaX; // swipe left\n\n      if (direction > 0) {\n        this.prev();\n      } // swipe right\n\n\n      if (direction < 0) {\n        this.next();\n      }\n    };\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this2 = this;\n\n      if (this._config.keyboard) {\n        $(this._element).on(Event$2.KEYDOWN, function (event) {\n          return _this2._keydown(event);\n        });\n      }\n\n      if (this._config.pause === 'hover') {\n        $(this._element).on(Event$2.MOUSEENTER, function (event) {\n          return _this2.pause(event);\n        }).on(Event$2.MOUSELEAVE, function (event) {\n          return _this2.cycle(event);\n        });\n      }\n\n      if (this._config.touch) {\n        this._addTouchEventListeners();\n      }\n    };\n\n    _proto._addTouchEventListeners = function _addTouchEventListeners() {\n      var _this3 = this;\n\n      if (!this._touchSupported) {\n        return;\n      }\n\n      var start = function start(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchStartX = event.originalEvent.clientX;\n        } else if (!_this3._pointerEvent) {\n          _this3.touchStartX = event.originalEvent.touches[0].clientX;\n        }\n      };\n\n      var move = function move(event) {\n        // ensure swiping with one touch and not pinching\n        if (event.originalEvent.touches && event.originalEvent.touches.length > 1) {\n          _this3.touchDeltaX = 0;\n        } else {\n          _this3.touchDeltaX = event.originalEvent.touches[0].clientX - _this3.touchStartX;\n        }\n      };\n\n      var end = function end(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchDeltaX = event.originalEvent.clientX - _this3.touchStartX;\n        }\n\n        _this3._handleSwipe();\n\n        if (_this3._config.pause === 'hover') {\n          // If it's a touch-enabled device, mouseenter/leave are fired as\n          // part of the mouse compatibility events on first tap - the carousel\n          // would stop cycling until user tapped out of it;\n          // here, we listen for touchend, explicitly pause the carousel\n          // (as if it's the second time we tap on it, mouseenter compat event\n          // is NOT fired) and after a timeout (to allow for mouse compatibility\n          // events to fire) we explicitly restart cycling\n          _this3.pause();\n\n          if (_this3.touchTimeout) {\n            clearTimeout(_this3.touchTimeout);\n          }\n\n          _this3.touchTimeout = setTimeout(function (event) {\n            return _this3.cycle(event);\n          }, TOUCHEVENT_COMPAT_WAIT + _this3._config.interval);\n        }\n      };\n\n      $(this._element.querySelectorAll(Selector$2.ITEM_IMG)).on(Event$2.DRAG_START, function (e) {\n        return e.preventDefault();\n      });\n\n      if (this._pointerEvent) {\n        $(this._element).on(Event$2.POINTERDOWN, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.POINTERUP, function (event) {\n          return end(event);\n        });\n\n        this._element.classList.add(ClassName$2.POINTER_EVENT);\n      } else {\n        $(this._element).on(Event$2.TOUCHSTART, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.TOUCHMOVE, function (event) {\n          return move(event);\n        });\n        $(this._element).on(Event$2.TOUCHEND, function (event) {\n          return end(event);\n        });\n      }\n    };\n\n    _proto._keydown = function _keydown(event) {\n      if (/input|textarea/i.test(event.target.tagName)) {\n        return;\n      }\n\n      switch (event.which) {\n        case ARROW_LEFT_KEYCODE:\n          event.preventDefault();\n          this.prev();\n          break;\n\n        case ARROW_RIGHT_KEYCODE:\n          event.preventDefault();\n          this.next();\n          break;\n\n        default:\n      }\n    };\n\n    _proto._getItemIndex = function _getItemIndex(element) {\n      this._items = element && element.parentNode ? [].slice.call(element.parentNode.querySelectorAll(Selector$2.ITEM)) : [];\n      return this._items.indexOf(element);\n    };\n\n    _proto._getItemByDirection = function _getItemByDirection(direction, activeElement) {\n      var isNextDirection = direction === Direction.NEXT;\n      var isPrevDirection = direction === Direction.PREV;\n\n      var activeIndex = this._getItemIndex(activeElement);\n\n      var lastItemIndex = this._items.length - 1;\n      var isGoingToWrap = isPrevDirection && activeIndex === 0 || isNextDirection && activeIndex === lastItemIndex;\n\n      if (isGoingToWrap && !this._config.wrap) {\n        return activeElement;\n      }\n\n      var delta = direction === Direction.PREV ? -1 : 1;\n      var itemIndex = (activeIndex + delta) % this._items.length;\n      return itemIndex === -1 ? this._items[this._items.length - 1] : this._items[itemIndex];\n    };\n\n    _proto._triggerSlideEvent = function _triggerSlideEvent(relatedTarget, eventDirectionName) {\n      var targetIndex = this._getItemIndex(relatedTarget);\n\n      var fromIndex = this._getItemIndex(this._element.querySelector(Selector$2.ACTIVE_ITEM));\n\n      var slideEvent = $.Event(Event$2.SLIDE, {\n        relatedTarget: relatedTarget,\n        direction: eventDirectionName,\n        from: fromIndex,\n        to: targetIndex\n      });\n      $(this._element).trigger(slideEvent);\n      return slideEvent;\n    };\n\n    _proto._setActiveIndicatorElement = function _setActiveIndicatorElement(element) {\n      if (this._indicatorsElement) {\n        var indicators = [].slice.call(this._indicatorsElement.querySelectorAll(Selector$2.ACTIVE));\n        $(indicators).removeClass(ClassName$2.ACTIVE);\n\n        var nextIndicator = this._indicatorsElement.children[this._getItemIndex(element)];\n\n        if (nextIndicator) {\n          $(nextIndicator).addClass(ClassName$2.ACTIVE);\n        }\n      }\n    };\n\n    _proto._slide = function _slide(direction, element) {\n      var _this4 = this;\n\n      var activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeElementIndex = this._getItemIndex(activeElement);\n\n      var nextElement = element || activeElement && this._getItemByDirection(direction, activeElement);\n\n      var nextElementIndex = this._getItemIndex(nextElement);\n\n      var isCycling = Boolean(this._interval);\n      var directionalClassName;\n      var orderClassName;\n      var eventDirectionName;\n\n      if (direction === Direction.NEXT) {\n        directionalClassName = ClassName$2.LEFT;\n        orderClassName = ClassName$2.NEXT;\n        eventDirectionName = Direction.LEFT;\n      } else {\n        directionalClassName = ClassName$2.RIGHT;\n        orderClassName = ClassName$2.PREV;\n        eventDirectionName = Direction.RIGHT;\n      }\n\n      if (nextElement && $(nextElement).hasClass(ClassName$2.ACTIVE)) {\n        this._isSliding = false;\n        return;\n      }\n\n      var slideEvent = this._triggerSlideEvent(nextElement, eventDirectionName);\n\n      if (slideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (!activeElement || !nextElement) {\n        // Some weirdness is happening, so we bail\n        return;\n      }\n\n      this._isSliding = true;\n\n      if (isCycling) {\n        this.pause();\n      }\n\n      this._setActiveIndicatorElement(nextElement);\n\n      var slidEvent = $.Event(Event$2.SLID, {\n        relatedTarget: nextElement,\n        direction: eventDirectionName,\n        from: activeElementIndex,\n        to: nextElementIndex\n      });\n\n      if ($(this._element).hasClass(ClassName$2.SLIDE)) {\n        $(nextElement).addClass(orderClassName);\n        Util.reflow(nextElement);\n        $(activeElement).addClass(directionalClassName);\n        $(nextElement).addClass(directionalClassName);\n        var nextElementInterval = parseInt(nextElement.getAttribute('data-interval'), 10);\n\n        if (nextElementInterval) {\n          this._config.defaultInterval = this._config.defaultInterval || this._config.interval;\n          this._config.interval = nextElementInterval;\n        } else {\n          this._config.interval = this._config.defaultInterval || this._config.interval;\n        }\n\n        var transitionDuration = Util.getTransitionDurationFromElement(activeElement);\n        $(activeElement).one(Util.TRANSITION_END, function () {\n          $(nextElement).removeClass(directionalClassName + \" \" + orderClassName).addClass(ClassName$2.ACTIVE);\n          $(activeElement).removeClass(ClassName$2.ACTIVE + \" \" + orderClassName + \" \" + directionalClassName);\n          _this4._isSliding = false;\n          setTimeout(function () {\n            return $(_this4._element).trigger(slidEvent);\n          }, 0);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        $(activeElement).removeClass(ClassName$2.ACTIVE);\n        $(nextElement).addClass(ClassName$2.ACTIVE);\n        this._isSliding = false;\n        $(this._element).trigger(slidEvent);\n      }\n\n      if (isCycling) {\n        this.cycle();\n      }\n    } // Static\n    ;\n\n    Carousel._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$2);\n\n        var _config = _objectSpread({}, Default, $(this).data());\n\n        if (typeof config === 'object') {\n          _config = _objectSpread({}, _config, config);\n        }\n\n        var action = typeof config === 'string' ? config : _config.slide;\n\n        if (!data) {\n          data = new Carousel(this, _config);\n          $(this).data(DATA_KEY$2, data);\n        }\n\n        if (typeof config === 'number') {\n          data.to(config);\n        } else if (typeof action === 'string') {\n          if (typeof data[action] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + action + \"\\\"\");\n          }\n\n          data[action]();\n        } else if (_config.interval && _config.ride) {\n          data.pause();\n          data.cycle();\n        }\n      });\n    };\n\n    Carousel._dataApiClickHandler = function _dataApiClickHandler(event) {\n      var selector = Util.getSelectorFromElement(this);\n\n      if (!selector) {\n        return;\n      }\n\n      var target = $(selector)[0];\n\n      if (!target || !$(target).hasClass(ClassName$2.CAROUSEL)) {\n        return;\n      }\n\n      var config = _objectSpread({}, $(target).data(), $(this).data());\n\n      var slideIndex = this.getAttribute('data-slide-to');\n\n      if (slideIndex) {\n        config.interval = false;\n      }\n\n      Carousel._jQueryInterface.call($(target), config);\n\n      if (slideIndex) {\n        $(target).data(DATA_KEY$2).to(slideIndex);\n      }\n\n      event.preventDefault();\n    };\n\n    _createClass(Carousel, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$2;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default;\n      }\n    }]);\n\n    return Carousel;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$2.CLICK_DATA_API, Selector$2.DATA_SLIDE, Carousel._dataApiClickHandler);\n  $(window).on(Event$2.LOAD_DATA_API, function () {\n    var carousels = [].slice.call(document.querySelectorAll(Selector$2.DATA_RIDE));\n\n    for (var i = 0, len = carousels.length; i < len; i++) {\n      var $carousel = $(carousels[i]);\n\n      Carousel._jQueryInterface.call($carousel, $carousel.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$2] = Carousel._jQueryInterface;\n  $.fn[NAME$2].Constructor = Carousel;\n\n  $.fn[NAME$2].noConflict = function () {\n    $.fn[NAME$2] = JQUERY_NO_CONFLICT$2;\n    return Carousel._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$3 = 'collapse';\n  var VERSION$3 = '4.3.1';\n  var DATA_KEY$3 = 'bs.collapse';\n  var EVENT_KEY$3 = \".\" + DATA_KEY$3;\n  var DATA_API_KEY$3 = '.data-api';\n  var JQUERY_NO_CONFLICT$3 = $.fn[NAME$3];\n  var Default$1 = {\n    toggle: true,\n    parent: ''\n  };\n  var DefaultType$1 = {\n    toggle: 'boolean',\n    parent: '(string|element)'\n  };\n  var Event$3 = {\n    SHOW: \"show\" + EVENT_KEY$3,\n    SHOWN: \"shown\" + EVENT_KEY$3,\n    HIDE: \"hide\" + EVENT_KEY$3,\n    HIDDEN: \"hidden\" + EVENT_KEY$3,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$3 + DATA_API_KEY$3\n  };\n  var ClassName$3 = {\n    SHOW: 'show',\n    COLLAPSE: 'collapse',\n    COLLAPSING: 'collapsing',\n    COLLAPSED: 'collapsed'\n  };\n  var Dimension = {\n    WIDTH: 'width',\n    HEIGHT: 'height'\n  };\n  var Selector$3 = {\n    ACTIVES: '.show, .collapsing',\n    DATA_TOGGLE: '[data-toggle=\"collapse\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Collapse =\n  /*#__PURE__*/\n  function () {\n    function Collapse(element, config) {\n      this._isTransitioning = false;\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._triggerArray = [].slice.call(document.querySelectorAll(\"[data-toggle=\\\"collapse\\\"][href=\\\"#\" + element.id + \"\\\"],\" + (\"[data-toggle=\\\"collapse\\\"][data-target=\\\"#\" + element.id + \"\\\"]\")));\n      var toggleList = [].slice.call(document.querySelectorAll(Selector$3.DATA_TOGGLE));\n\n      for (var i = 0, len = toggleList.length; i < len; i++) {\n        var elem = toggleList[i];\n        var selector = Util.getSelectorFromElement(elem);\n        var filterElement = [].slice.call(document.querySelectorAll(selector)).filter(function (foundElem) {\n          return foundElem === element;\n        });\n\n        if (selector !== null && filterElement.length > 0) {\n          this._selector = selector;\n\n          this._triggerArray.push(elem);\n        }\n      }\n\n      this._parent = this._config.parent ? this._getParent() : null;\n\n      if (!this._config.parent) {\n        this._addAriaAndCollapsedClass(this._element, this._triggerArray);\n      }\n\n      if (this._config.toggle) {\n        this.toggle();\n      }\n    } // Getters\n\n\n    var _proto = Collapse.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if ($(this._element).hasClass(ClassName$3.SHOW)) {\n        this.hide();\n      } else {\n        this.show();\n      }\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._isTransitioning || $(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var actives;\n      var activesData;\n\n      if (this._parent) {\n        actives = [].slice.call(this._parent.querySelectorAll(Selector$3.ACTIVES)).filter(function (elem) {\n          if (typeof _this._config.parent === 'string') {\n            return elem.getAttribute('data-parent') === _this._config.parent;\n          }\n\n          return elem.classList.contains(ClassName$3.COLLAPSE);\n        });\n\n        if (actives.length === 0) {\n          actives = null;\n        }\n      }\n\n      if (actives) {\n        activesData = $(actives).not(this._selector).data(DATA_KEY$3);\n\n        if (activesData && activesData._isTransitioning) {\n          return;\n        }\n      }\n\n      var startEvent = $.Event(Event$3.SHOW);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (actives) {\n        Collapse._jQueryInterface.call($(actives).not(this._selector), 'hide');\n\n        if (!activesData) {\n          $(actives).data(DATA_KEY$3, null);\n        }\n      }\n\n      var dimension = this._getDimension();\n\n      $(this._element).removeClass(ClassName$3.COLLAPSE).addClass(ClassName$3.COLLAPSING);\n      this._element.style[dimension] = 0;\n\n      if (this._triggerArray.length) {\n        $(this._triggerArray).removeClass(ClassName$3.COLLAPSED).attr('aria-expanded', true);\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        $(_this._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).addClass(ClassName$3.SHOW);\n        _this._element.style[dimension] = '';\n\n        _this.setTransitioning(false);\n\n        $(_this._element).trigger(Event$3.SHOWN);\n      };\n\n      var capitalizedDimension = dimension[0].toUpperCase() + dimension.slice(1);\n      var scrollSize = \"scroll\" + capitalizedDimension;\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      this._element.style[dimension] = this._element[scrollSize] + \"px\";\n    };\n\n    _proto.hide = function hide() {\n      var _this2 = this;\n\n      if (this._isTransitioning || !$(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var startEvent = $.Event(Event$3.HIDE);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      var dimension = this._getDimension();\n\n      this._element.style[dimension] = this._element.getBoundingClientRect()[dimension] + \"px\";\n      Util.reflow(this._element);\n      $(this._element).addClass(ClassName$3.COLLAPSING).removeClass(ClassName$3.COLLAPSE).removeClass(ClassName$3.SHOW);\n      var triggerArrayLength = this._triggerArray.length;\n\n      if (triggerArrayLength > 0) {\n        for (var i = 0; i < triggerArrayLength; i++) {\n          var trigger = this._triggerArray[i];\n          var selector = Util.getSelectorFromElement(trigger);\n\n          if (selector !== null) {\n            var $elem = $([].slice.call(document.querySelectorAll(selector)));\n\n            if (!$elem.hasClass(ClassName$3.SHOW)) {\n              $(trigger).addClass(ClassName$3.COLLAPSED).attr('aria-expanded', false);\n            }\n          }\n        }\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        _this2.setTransitioning(false);\n\n        $(_this2._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).trigger(Event$3.HIDDEN);\n      };\n\n      this._element.style[dimension] = '';\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto.setTransitioning = function setTransitioning(isTransitioning) {\n      this._isTransitioning = isTransitioning;\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$3);\n      this._config = null;\n      this._parent = null;\n      this._element = null;\n      this._triggerArray = null;\n      this._isTransitioning = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$1, config);\n      config.toggle = Boolean(config.toggle); // Coerce string values\n\n      Util.typeCheckConfig(NAME$3, config, DefaultType$1);\n      return config;\n    };\n\n    _proto._getDimension = function _getDimension() {\n      var hasWidth = $(this._element).hasClass(Dimension.WIDTH);\n      return hasWidth ? Dimension.WIDTH : Dimension.HEIGHT;\n    };\n\n    _proto._getParent = function _getParent() {\n      var _this3 = this;\n\n      var parent;\n\n      if (Util.isElement(this._config.parent)) {\n        parent = this._config.parent; // It's a jQuery object\n\n        if (typeof this._config.parent.jquery !== 'undefined') {\n          parent = this._config.parent[0];\n        }\n      } else {\n        parent = document.querySelector(this._config.parent);\n      }\n\n      var selector = \"[data-toggle=\\\"collapse\\\"][data-parent=\\\"\" + this._config.parent + \"\\\"]\";\n      var children = [].slice.call(parent.querySelectorAll(selector));\n      $(children).each(function (i, element) {\n        _this3._addAriaAndCollapsedClass(Collapse._getTargetFromElement(element), [element]);\n      });\n      return parent;\n    };\n\n    _proto._addAriaAndCollapsedClass = function _addAriaAndCollapsedClass(element, triggerArray) {\n      var isOpen = $(element).hasClass(ClassName$3.SHOW);\n\n      if (triggerArray.length) {\n        $(triggerArray).toggleClass(ClassName$3.COLLAPSED, !isOpen).attr('aria-expanded', isOpen);\n      }\n    } // Static\n    ;\n\n    Collapse._getTargetFromElement = function _getTargetFromElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      return selector ? document.querySelector(selector) : null;\n    };\n\n    Collapse._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$3);\n\n        var _config = _objectSpread({}, Default$1, $this.data(), typeof config === 'object' && config ? config : {});\n\n        if (!data && _config.toggle && /show|hide/.test(config)) {\n          _config.toggle = false;\n        }\n\n        if (!data) {\n          data = new Collapse(this, _config);\n          $this.data(DATA_KEY$3, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Collapse, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$3;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$1;\n      }\n    }]);\n\n    return Collapse;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$3.CLICK_DATA_API, Selector$3.DATA_TOGGLE, function (event) {\n    // preventDefault only for <a> elements (which change the URL) not inside the collapsible element\n    if (event.currentTarget.tagName === 'A') {\n      event.preventDefault();\n    }\n\n    var $trigger = $(this);\n    var selector = Util.getSelectorFromElement(this);\n    var selectors = [].slice.call(document.querySelectorAll(selector));\n    $(selectors).each(function () {\n      var $target = $(this);\n      var data = $target.data(DATA_KEY$3);\n      var config = data ? 'toggle' : $trigger.data();\n\n      Collapse._jQueryInterface.call($target, config);\n    });\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$3] = Collapse._jQueryInterface;\n  $.fn[NAME$3].Constructor = Collapse;\n\n  $.fn[NAME$3].noConflict = function () {\n    $.fn[NAME$3] = JQUERY_NO_CONFLICT$3;\n    return Collapse._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$4 = 'dropdown';\n  var VERSION$4 = '4.3.1';\n  var DATA_KEY$4 = 'bs.dropdown';\n  var EVENT_KEY$4 = \".\" + DATA_KEY$4;\n  var DATA_API_KEY$4 = '.data-api';\n  var JQUERY_NO_CONFLICT$4 = $.fn[NAME$4];\n  var ESCAPE_KEYCODE = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var SPACE_KEYCODE = 32; // KeyboardEvent.which value for space key\n\n  var TAB_KEYCODE = 9; // KeyboardEvent.which value for tab key\n\n  var ARROW_UP_KEYCODE = 38; // KeyboardEvent.which value for up arrow key\n\n  var ARROW_DOWN_KEYCODE = 40; // KeyboardEvent.which value for down arrow key\n\n  var RIGHT_MOUSE_BUTTON_WHICH = 3; // MouseEvent.which value for the right button (assuming a right-handed mouse)\n\n  var REGEXP_KEYDOWN = new RegExp(ARROW_UP_KEYCODE + \"|\" + ARROW_DOWN_KEYCODE + \"|\" + ESCAPE_KEYCODE);\n  var Event$4 = {\n    HIDE: \"hide\" + EVENT_KEY$4,\n    HIDDEN: \"hidden\" + EVENT_KEY$4,\n    SHOW: \"show\" + EVENT_KEY$4,\n    SHOWN: \"shown\" + EVENT_KEY$4,\n    CLICK: \"click\" + EVENT_KEY$4,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYDOWN_DATA_API: \"keydown\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYUP_DATA_API: \"keyup\" + EVENT_KEY$4 + DATA_API_KEY$4\n  };\n  var ClassName$4 = {\n    DISABLED: 'disabled',\n    SHOW: 'show',\n    DROPUP: 'dropup',\n    DROPRIGHT: 'dropright',\n    DROPLEFT: 'dropleft',\n    MENURIGHT: 'dropdown-menu-right',\n    MENULEFT: 'dropdown-menu-left',\n    POSITION_STATIC: 'position-static'\n  };\n  var Selector$4 = {\n    DATA_TOGGLE: '[data-toggle=\"dropdown\"]',\n    FORM_CHILD: '.dropdown form',\n    MENU: '.dropdown-menu',\n    NAVBAR_NAV: '.navbar-nav',\n    VISIBLE_ITEMS: '.dropdown-menu .dropdown-item:not(.disabled):not(:disabled)'\n  };\n  var AttachmentMap = {\n    TOP: 'top-start',\n    TOPEND: 'top-end',\n    BOTTOM: 'bottom-start',\n    BOTTOMEND: 'bottom-end',\n    RIGHT: 'right-start',\n    RIGHTEND: 'right-end',\n    LEFT: 'left-start',\n    LEFTEND: 'left-end'\n  };\n  var Default$2 = {\n    offset: 0,\n    flip: true,\n    boundary: 'scrollParent',\n    reference: 'toggle',\n    display: 'dynamic'\n  };\n  var DefaultType$2 = {\n    offset: '(number|string|function)',\n    flip: 'boolean',\n    boundary: '(string|element)',\n    reference: '(string|element)',\n    display: 'string'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Dropdown =\n  /*#__PURE__*/\n  function () {\n    function Dropdown(element, config) {\n      this._element = element;\n      this._popper = null;\n      this._config = this._getConfig(config);\n      this._menu = this._getMenuElement();\n      this._inNavbar = this._detectNavbar();\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Dropdown.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      var isActive = $(this._menu).hasClass(ClassName$4.SHOW);\n\n      Dropdown._clearMenus();\n\n      if (isActive) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      } // Disable totally Popper.js for Dropdown in Navbar\n\n\n      if (!this._inNavbar) {\n        /**\n         * Check for Popper dependency\n         * Popper - https://popper.js.org\n         */\n        if (typeof Popper === 'undefined') {\n          throw new TypeError('Bootstrap\\'s dropdowns require Popper.js (https://popper.js.org/)');\n        }\n\n        var referenceElement = this._element;\n\n        if (this._config.reference === 'parent') {\n          referenceElement = parent;\n        } else if (Util.isElement(this._config.reference)) {\n          referenceElement = this._config.reference; // Check if it's jQuery element\n\n          if (typeof this._config.reference.jquery !== 'undefined') {\n            referenceElement = this._config.reference[0];\n          }\n        } // If boundary is not `scrollParent`, then set position to `static`\n        // to allow the menu to \"escape\" the scroll parent's boundaries\n        // https://github.com/twbs/bootstrap/issues/24251\n\n\n        if (this._config.boundary !== 'scrollParent') {\n          $(parent).addClass(ClassName$4.POSITION_STATIC);\n        }\n\n        this._popper = new Popper(referenceElement, this._menu, this._getPopperConfig());\n      } // If this is a touch-enabled device we add extra\n      // empty mouseover listeners to the body's immediate children;\n      // only needed because of broken event delegation on iOS\n      // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n\n      if ('ontouchstart' in document.documentElement && $(parent).closest(Selector$4.NAVBAR_NAV).length === 0) {\n        $(document.body).children().on('mouseover', null, $.noop);\n      }\n\n      this._element.focus();\n\n      this._element.setAttribute('aria-expanded', true);\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.show = function show() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || $(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.hide = function hide() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || !$(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$4);\n      $(this._element).off(EVENT_KEY$4);\n      this._element = null;\n      this._menu = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n\n        this._popper = null;\n      }\n    };\n\n    _proto.update = function update() {\n      this._inNavbar = this._detectNavbar();\n\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Private\n    ;\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this = this;\n\n      $(this._element).on(Event$4.CLICK, function (event) {\n        event.preventDefault();\n        event.stopPropagation();\n\n        _this.toggle();\n      });\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, this.constructor.Default, $(this._element).data(), config);\n      Util.typeCheckConfig(NAME$4, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._getMenuElement = function _getMenuElement() {\n      if (!this._menu) {\n        var parent = Dropdown._getParentFromElement(this._element);\n\n        if (parent) {\n          this._menu = parent.querySelector(Selector$4.MENU);\n        }\n      }\n\n      return this._menu;\n    };\n\n    _proto._getPlacement = function _getPlacement() {\n      var $parentDropdown = $(this._element.parentNode);\n      var placement = AttachmentMap.BOTTOM; // Handle dropup\n\n      if ($parentDropdown.hasClass(ClassName$4.DROPUP)) {\n        placement = AttachmentMap.TOP;\n\n        if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n          placement = AttachmentMap.TOPEND;\n        }\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPRIGHT)) {\n        placement = AttachmentMap.RIGHT;\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPLEFT)) {\n        placement = AttachmentMap.LEFT;\n      } else if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n        placement = AttachmentMap.BOTTOMEND;\n      }\n\n      return placement;\n    };\n\n    _proto._detectNavbar = function _detectNavbar() {\n      return $(this._element).closest('.navbar').length > 0;\n    };\n\n    _proto._getOffset = function _getOffset() {\n      var _this2 = this;\n\n      var offset = {};\n\n      if (typeof this._config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this2._config.offset(data.offsets, _this2._element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this._config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getPopperConfig = function _getPopperConfig() {\n      var popperConfig = {\n        placement: this._getPlacement(),\n        modifiers: {\n          offset: this._getOffset(),\n          flip: {\n            enabled: this._config.flip\n          },\n          preventOverflow: {\n            boundariesElement: this._config.boundary\n          }\n        } // Disable Popper.js if we have a static display\n\n      };\n\n      if (this._config.display === 'static') {\n        popperConfig.modifiers.applyStyle = {\n          enabled: false\n        };\n      }\n\n      return popperConfig;\n    } // Static\n    ;\n\n    Dropdown._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$4);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data) {\n          data = new Dropdown(this, _config);\n          $(this).data(DATA_KEY$4, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    Dropdown._clearMenus = function _clearMenus(event) {\n      if (event && (event.which === RIGHT_MOUSE_BUTTON_WHICH || event.type === 'keyup' && event.which !== TAB_KEYCODE)) {\n        return;\n      }\n\n      var toggles = [].slice.call(document.querySelectorAll(Selector$4.DATA_TOGGLE));\n\n      for (var i = 0, len = toggles.length; i < len; i++) {\n        var parent = Dropdown._getParentFromElement(toggles[i]);\n\n        var context = $(toggles[i]).data(DATA_KEY$4);\n        var relatedTarget = {\n          relatedTarget: toggles[i]\n        };\n\n        if (event && event.type === 'click') {\n          relatedTarget.clickEvent = event;\n        }\n\n        if (!context) {\n          continue;\n        }\n\n        var dropdownMenu = context._menu;\n\n        if (!$(parent).hasClass(ClassName$4.SHOW)) {\n          continue;\n        }\n\n        if (event && (event.type === 'click' && /input|textarea/i.test(event.target.tagName) || event.type === 'keyup' && event.which === TAB_KEYCODE) && $.contains(parent, event.target)) {\n          continue;\n        }\n\n        var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n        $(parent).trigger(hideEvent);\n\n        if (hideEvent.isDefaultPrevented()) {\n          continue;\n        } // If this is a touch-enabled device we remove the extra\n        // empty mouseover listeners we added for iOS support\n\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().off('mouseover', null, $.noop);\n        }\n\n        toggles[i].setAttribute('aria-expanded', 'false');\n        $(dropdownMenu).removeClass(ClassName$4.SHOW);\n        $(parent).removeClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n      }\n    };\n\n    Dropdown._getParentFromElement = function _getParentFromElement(element) {\n      var parent;\n      var selector = Util.getSelectorFromElement(element);\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      return parent || element.parentNode;\n    } // eslint-disable-next-line complexity\n    ;\n\n    Dropdown._dataApiKeydownHandler = function _dataApiKeydownHandler(event) {\n      // If not input/textarea:\n      //  - And not a key in REGEXP_KEYDOWN => not a dropdown command\n      // If input/textarea:\n      //  - If space key => not a dropdown command\n      //  - If key is other than escape\n      //    - If key is not up or down => not a dropdown command\n      //    - If trigger inside the menu => not a dropdown command\n      if (/input|textarea/i.test(event.target.tagName) ? event.which === SPACE_KEYCODE || event.which !== ESCAPE_KEYCODE && (event.which !== ARROW_DOWN_KEYCODE && event.which !== ARROW_UP_KEYCODE || $(event.target).closest(Selector$4.MENU).length) : !REGEXP_KEYDOWN.test(event.which)) {\n        return;\n      }\n\n      event.preventDefault();\n      event.stopPropagation();\n\n      if (this.disabled || $(this).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this);\n\n      var isActive = $(parent).hasClass(ClassName$4.SHOW);\n\n      if (!isActive || isActive && (event.which === ESCAPE_KEYCODE || event.which === SPACE_KEYCODE)) {\n        if (event.which === ESCAPE_KEYCODE) {\n          var toggle = parent.querySelector(Selector$4.DATA_TOGGLE);\n          $(toggle).trigger('focus');\n        }\n\n        $(this).trigger('click');\n        return;\n      }\n\n      var items = [].slice.call(parent.querySelectorAll(Selector$4.VISIBLE_ITEMS));\n\n      if (items.length === 0) {\n        return;\n      }\n\n      var index = items.indexOf(event.target);\n\n      if (event.which === ARROW_UP_KEYCODE && index > 0) {\n        // Up\n        index--;\n      }\n\n      if (event.which === ARROW_DOWN_KEYCODE && index < items.length - 1) {\n        // Down\n        index++;\n      }\n\n      if (index < 0) {\n        index = 0;\n      }\n\n      items[index].focus();\n    };\n\n    _createClass(Dropdown, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$4;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$2;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$2;\n      }\n    }]);\n\n    return Dropdown;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$4.KEYDOWN_DATA_API, Selector$4.DATA_TOGGLE, Dropdown._dataApiKeydownHandler).on(Event$4.KEYDOWN_DATA_API, Selector$4.MENU, Dropdown._dataApiKeydownHandler).on(Event$4.CLICK_DATA_API + \" \" + Event$4.KEYUP_DATA_API, Dropdown._clearMenus).on(Event$4.CLICK_DATA_API, Selector$4.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n    event.stopPropagation();\n\n    Dropdown._jQueryInterface.call($(this), 'toggle');\n  }).on(Event$4.CLICK_DATA_API, Selector$4.FORM_CHILD, function (e) {\n    e.stopPropagation();\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$4] = Dropdown._jQueryInterface;\n  $.fn[NAME$4].Constructor = Dropdown;\n\n  $.fn[NAME$4].noConflict = function () {\n    $.fn[NAME$4] = JQUERY_NO_CONFLICT$4;\n    return Dropdown._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$5 = 'modal';\n  var VERSION$5 = '4.3.1';\n  var DATA_KEY$5 = 'bs.modal';\n  var EVENT_KEY$5 = \".\" + DATA_KEY$5;\n  var DATA_API_KEY$5 = '.data-api';\n  var JQUERY_NO_CONFLICT$5 = $.fn[NAME$5];\n  var ESCAPE_KEYCODE$1 = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var Default$3 = {\n    backdrop: true,\n    keyboard: true,\n    focus: true,\n    show: true\n  };\n  var DefaultType$3 = {\n    backdrop: '(boolean|string)',\n    keyboard: 'boolean',\n    focus: 'boolean',\n    show: 'boolean'\n  };\n  var Event$5 = {\n    HIDE: \"hide\" + EVENT_KEY$5,\n    HIDDEN: \"hidden\" + EVENT_KEY$5,\n    SHOW: \"show\" + EVENT_KEY$5,\n    SHOWN: \"shown\" + EVENT_KEY$5,\n    FOCUSIN: \"focusin\" + EVENT_KEY$5,\n    RESIZE: \"resize\" + EVENT_KEY$5,\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$5,\n    KEYDOWN_DISMISS: \"keydown.dismiss\" + EVENT_KEY$5,\n    MOUSEUP_DISMISS: \"mouseup.dismiss\" + EVENT_KEY$5,\n    MOUSEDOWN_DISMISS: \"mousedown.dismiss\" + EVENT_KEY$5,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$5 + DATA_API_KEY$5\n  };\n  var ClassName$5 = {\n    SCROLLABLE: 'modal-dialog-scrollable',\n    SCROLLBAR_MEASURER: 'modal-scrollbar-measure',\n    BACKDROP: 'modal-backdrop',\n    OPEN: 'modal-open',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$5 = {\n    DIALOG: '.modal-dialog',\n    MODAL_BODY: '.modal-body',\n    DATA_TOGGLE: '[data-toggle=\"modal\"]',\n    DATA_DISMISS: '[data-dismiss=\"modal\"]',\n    FIXED_CONTENT: '.fixed-top, .fixed-bottom, .is-fixed, .sticky-top',\n    STICKY_CONTENT: '.sticky-top'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Modal =\n  /*#__PURE__*/\n  function () {\n    function Modal(element, config) {\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._dialog = element.querySelector(Selector$5.DIALOG);\n      this._backdrop = null;\n      this._isShown = false;\n      this._isBodyOverflowing = false;\n      this._ignoreBackdropClick = false;\n      this._isTransitioning = false;\n      this._scrollbarWidth = 0;\n    } // Getters\n\n\n    var _proto = Modal.prototype;\n\n    // Public\n    _proto.toggle = function toggle(relatedTarget) {\n      return this._isShown ? this.hide() : this.show(relatedTarget);\n    };\n\n    _proto.show = function show(relatedTarget) {\n      var _this = this;\n\n      if (this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      if ($(this._element).hasClass(ClassName$5.FADE)) {\n        this._isTransitioning = true;\n      }\n\n      var showEvent = $.Event(Event$5.SHOW, {\n        relatedTarget: relatedTarget\n      });\n      $(this._element).trigger(showEvent);\n\n      if (this._isShown || showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = true;\n\n      this._checkScrollbar();\n\n      this._setScrollbar();\n\n      this._adjustDialog();\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(this._element).on(Event$5.CLICK_DISMISS, Selector$5.DATA_DISMISS, function (event) {\n        return _this.hide(event);\n      });\n      $(this._dialog).on(Event$5.MOUSEDOWN_DISMISS, function () {\n        $(_this._element).one(Event$5.MOUSEUP_DISMISS, function (event) {\n          if ($(event.target).is(_this._element)) {\n            _this._ignoreBackdropClick = true;\n          }\n        });\n      });\n\n      this._showBackdrop(function () {\n        return _this._showElement(relatedTarget);\n      });\n    };\n\n    _proto.hide = function hide(event) {\n      var _this2 = this;\n\n      if (event) {\n        event.preventDefault();\n      }\n\n      if (!this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      var hideEvent = $.Event(Event$5.HIDE);\n      $(this._element).trigger(hideEvent);\n\n      if (!this._isShown || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = false;\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (transition) {\n        this._isTransitioning = true;\n      }\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(document).off(Event$5.FOCUSIN);\n      $(this._element).removeClass(ClassName$5.SHOW);\n      $(this._element).off(Event$5.CLICK_DISMISS);\n      $(this._dialog).off(Event$5.MOUSEDOWN_DISMISS);\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, function (event) {\n          return _this2._hideModal(event);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        this._hideModal();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      [window, this._element, this._dialog].forEach(function (htmlElement) {\n        return $(htmlElement).off(EVENT_KEY$5);\n      });\n      /**\n       * `document` has 2 events `Event.FOCUSIN` and `Event.CLICK_DATA_API`\n       * Do not move `document` in `htmlElements` array\n       * It will remove `Event.CLICK_DATA_API` event that should remain\n       */\n\n      $(document).off(Event$5.FOCUSIN);\n      $.removeData(this._element, DATA_KEY$5);\n      this._config = null;\n      this._element = null;\n      this._dialog = null;\n      this._backdrop = null;\n      this._isShown = null;\n      this._isBodyOverflowing = null;\n      this._ignoreBackdropClick = null;\n      this._isTransitioning = null;\n      this._scrollbarWidth = null;\n    };\n\n    _proto.handleUpdate = function handleUpdate() {\n      this._adjustDialog();\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$3, config);\n      Util.typeCheckConfig(NAME$5, config, DefaultType$3);\n      return config;\n    };\n\n    _proto._showElement = function _showElement(relatedTarget) {\n      var _this3 = this;\n\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (!this._element.parentNode || this._element.parentNode.nodeType !== Node.ELEMENT_NODE) {\n        // Don't move modal's DOM position\n        document.body.appendChild(this._element);\n      }\n\n      this._element.style.display = 'block';\n\n      this._element.removeAttribute('aria-hidden');\n\n      this._element.setAttribute('aria-modal', true);\n\n      if ($(this._dialog).hasClass(ClassName$5.SCROLLABLE)) {\n        this._dialog.querySelector(Selector$5.MODAL_BODY).scrollTop = 0;\n      } else {\n        this._element.scrollTop = 0;\n      }\n\n      if (transition) {\n        Util.reflow(this._element);\n      }\n\n      $(this._element).addClass(ClassName$5.SHOW);\n\n      if (this._config.focus) {\n        this._enforceFocus();\n      }\n\n      var shownEvent = $.Event(Event$5.SHOWN, {\n        relatedTarget: relatedTarget\n      });\n\n      var transitionComplete = function transitionComplete() {\n        if (_this3._config.focus) {\n          _this3._element.focus();\n        }\n\n        _this3._isTransitioning = false;\n        $(_this3._element).trigger(shownEvent);\n      };\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._dialog);\n        $(this._dialog).one(Util.TRANSITION_END, transitionComplete).emulateTransitionEnd(transitionDuration);\n      } else {\n        transitionComplete();\n      }\n    };\n\n    _proto._enforceFocus = function _enforceFocus() {\n      var _this4 = this;\n\n      $(document).off(Event$5.FOCUSIN) // Guard against infinite focus loop\n      .on(Event$5.FOCUSIN, function (event) {\n        if (document !== event.target && _this4._element !== event.target && $(_this4._element).has(event.target).length === 0) {\n          _this4._element.focus();\n        }\n      });\n    };\n\n    _proto._setEscapeEvent = function _setEscapeEvent() {\n      var _this5 = this;\n\n      if (this._isShown && this._config.keyboard) {\n        $(this._element).on(Event$5.KEYDOWN_DISMISS, function (event) {\n          if (event.which === ESCAPE_KEYCODE$1) {\n            event.preventDefault();\n\n            _this5.hide();\n          }\n        });\n      } else if (!this._isShown) {\n        $(this._element).off(Event$5.KEYDOWN_DISMISS);\n      }\n    };\n\n    _proto._setResizeEvent = function _setResizeEvent() {\n      var _this6 = this;\n\n      if (this._isShown) {\n        $(window).on(Event$5.RESIZE, function (event) {\n          return _this6.handleUpdate(event);\n        });\n      } else {\n        $(window).off(Event$5.RESIZE);\n      }\n    };\n\n    _proto._hideModal = function _hideModal() {\n      var _this7 = this;\n\n      this._element.style.display = 'none';\n\n      this._element.setAttribute('aria-hidden', true);\n\n      this._element.removeAttribute('aria-modal');\n\n      this._isTransitioning = false;\n\n      this._showBackdrop(function () {\n        $(document.body).removeClass(ClassName$5.OPEN);\n\n        _this7._resetAdjustments();\n\n        _this7._resetScrollbar();\n\n        $(_this7._element).trigger(Event$5.HIDDEN);\n      });\n    };\n\n    _proto._removeBackdrop = function _removeBackdrop() {\n      if (this._backdrop) {\n        $(this._backdrop).remove();\n        this._backdrop = null;\n      }\n    };\n\n    _proto._showBackdrop = function _showBackdrop(callback) {\n      var _this8 = this;\n\n      var animate = $(this._element).hasClass(ClassName$5.FADE) ? ClassName$5.FADE : '';\n\n      if (this._isShown && this._config.backdrop) {\n        this._backdrop = document.createElement('div');\n        this._backdrop.className = ClassName$5.BACKDROP;\n\n        if (animate) {\n          this._backdrop.classList.add(animate);\n        }\n\n        $(this._backdrop).appendTo(document.body);\n        $(this._element).on(Event$5.CLICK_DISMISS, function (event) {\n          if (_this8._ignoreBackdropClick) {\n            _this8._ignoreBackdropClick = false;\n            return;\n          }\n\n          if (event.target !== event.currentTarget) {\n            return;\n          }\n\n          if (_this8._config.backdrop === 'static') {\n            _this8._element.focus();\n          } else {\n            _this8.hide();\n          }\n        });\n\n        if (animate) {\n          Util.reflow(this._backdrop);\n        }\n\n        $(this._backdrop).addClass(ClassName$5.SHOW);\n\n        if (!callback) {\n          return;\n        }\n\n        if (!animate) {\n          callback();\n          return;\n        }\n\n        var backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n        $(this._backdrop).one(Util.TRANSITION_END, callback).emulateTransitionEnd(backdropTransitionDuration);\n      } else if (!this._isShown && this._backdrop) {\n        $(this._backdrop).removeClass(ClassName$5.SHOW);\n\n        var callbackRemove = function callbackRemove() {\n          _this8._removeBackdrop();\n\n          if (callback) {\n            callback();\n          }\n        };\n\n        if ($(this._element).hasClass(ClassName$5.FADE)) {\n          var _backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n\n          $(this._backdrop).one(Util.TRANSITION_END, callbackRemove).emulateTransitionEnd(_backdropTransitionDuration);\n        } else {\n          callbackRemove();\n        }\n      } else if (callback) {\n        callback();\n      }\n    } // ----------------------------------------------------------------------\n    // the following methods are used to handle overflowing modals\n    // todo (fat): these should probably be refactored out of modal.js\n    // ----------------------------------------------------------------------\n    ;\n\n    _proto._adjustDialog = function _adjustDialog() {\n      var isModalOverflowing = this._element.scrollHeight > document.documentElement.clientHeight;\n\n      if (!this._isBodyOverflowing && isModalOverflowing) {\n        this._element.style.paddingLeft = this._scrollbarWidth + \"px\";\n      }\n\n      if (this._isBodyOverflowing && !isModalOverflowing) {\n        this._element.style.paddingRight = this._scrollbarWidth + \"px\";\n      }\n    };\n\n    _proto._resetAdjustments = function _resetAdjustments() {\n      this._element.style.paddingLeft = '';\n      this._element.style.paddingRight = '';\n    };\n\n    _proto._checkScrollbar = function _checkScrollbar() {\n      var rect = document.body.getBoundingClientRect();\n      this._isBodyOverflowing = rect.left + rect.right < window.innerWidth;\n      this._scrollbarWidth = this._getScrollbarWidth();\n    };\n\n    _proto._setScrollbar = function _setScrollbar() {\n      var _this9 = this;\n\n      if (this._isBodyOverflowing) {\n        // Note: DOMNode.style.paddingRight returns the actual value or '' if not set\n        //   while $(DOMNode).css('padding-right') returns the calculated value or 0 if not set\n        var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n        var stickyContent = [].slice.call(document.querySelectorAll(Selector$5.STICKY_CONTENT)); // Adjust fixed content padding\n\n        $(fixedContent).each(function (index, element) {\n          var actualPadding = element.style.paddingRight;\n          var calculatedPadding = $(element).css('padding-right');\n          $(element).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + _this9._scrollbarWidth + \"px\");\n        }); // Adjust sticky content margin\n\n        $(stickyContent).each(function (index, element) {\n          var actualMargin = element.style.marginRight;\n          var calculatedMargin = $(element).css('margin-right');\n          $(element).data('margin-right', actualMargin).css('margin-right', parseFloat(calculatedMargin) - _this9._scrollbarWidth + \"px\");\n        }); // Adjust body padding\n\n        var actualPadding = document.body.style.paddingRight;\n        var calculatedPadding = $(document.body).css('padding-right');\n        $(document.body).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + this._scrollbarWidth + \"px\");\n      }\n\n      $(document.body).addClass(ClassName$5.OPEN);\n    };\n\n    _proto._resetScrollbar = function _resetScrollbar() {\n      // Restore fixed content padding\n      var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n      $(fixedContent).each(function (index, element) {\n        var padding = $(element).data('padding-right');\n        $(element).removeData('padding-right');\n        element.style.paddingRight = padding ? padding : '';\n      }); // Restore sticky content\n\n      var elements = [].slice.call(document.querySelectorAll(\"\" + Selector$5.STICKY_CONTENT));\n      $(elements).each(function (index, element) {\n        var margin = $(element).data('margin-right');\n\n        if (typeof margin !== 'undefined') {\n          $(element).css('margin-right', margin).removeData('margin-right');\n        }\n      }); // Restore body padding\n\n      var padding = $(document.body).data('padding-right');\n      $(document.body).removeData('padding-right');\n      document.body.style.paddingRight = padding ? padding : '';\n    };\n\n    _proto._getScrollbarWidth = function _getScrollbarWidth() {\n      // thx d.walsh\n      var scrollDiv = document.createElement('div');\n      scrollDiv.className = ClassName$5.SCROLLBAR_MEASURER;\n      document.body.appendChild(scrollDiv);\n      var scrollbarWidth = scrollDiv.getBoundingClientRect().width - scrollDiv.clientWidth;\n      document.body.removeChild(scrollDiv);\n      return scrollbarWidth;\n    } // Static\n    ;\n\n    Modal._jQueryInterface = function _jQueryInterface(config, relatedTarget) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$5);\n\n        var _config = _objectSpread({}, Default$3, $(this).data(), typeof config === 'object' && config ? config : {});\n\n        if (!data) {\n          data = new Modal(this, _config);\n          $(this).data(DATA_KEY$5, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](relatedTarget);\n        } else if (_config.show) {\n          data.show(relatedTarget);\n        }\n      });\n    };\n\n    _createClass(Modal, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$5;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$3;\n      }\n    }]);\n\n    return Modal;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$5.CLICK_DATA_API, Selector$5.DATA_TOGGLE, function (event) {\n    var _this10 = this;\n\n    var target;\n    var selector = Util.getSelectorFromElement(this);\n\n    if (selector) {\n      target = document.querySelector(selector);\n    }\n\n    var config = $(target).data(DATA_KEY$5) ? 'toggle' : _objectSpread({}, $(target).data(), $(this).data());\n\n    if (this.tagName === 'A' || this.tagName === 'AREA') {\n      event.preventDefault();\n    }\n\n    var $target = $(target).one(Event$5.SHOW, function (showEvent) {\n      if (showEvent.isDefaultPrevented()) {\n        // Only register focus restorer if modal will actually get shown\n        return;\n      }\n\n      $target.one(Event$5.HIDDEN, function () {\n        if ($(_this10).is(':visible')) {\n          _this10.focus();\n        }\n      });\n    });\n\n    Modal._jQueryInterface.call($(target), config, this);\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$5] = Modal._jQueryInterface;\n  $.fn[NAME$5].Constructor = Modal;\n\n  $.fn[NAME$5].noConflict = function () {\n    $.fn[NAME$5] = JQUERY_NO_CONFLICT$5;\n    return Modal._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): tools/sanitizer.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  var uriAttrs = ['background', 'cite', 'href', 'itemtype', 'longdesc', 'poster', 'src', 'xlink:href'];\n  var ARIA_ATTRIBUTE_PATTERN = /^aria-[\\w-]*$/i;\n  var DefaultWhitelist = {\n    // Global attributes allowed on any supplied element below.\n    '*': ['class', 'dir', 'id', 'lang', 'role', ARIA_ATTRIBUTE_PATTERN],\n    a: ['target', 'href', 'title', 'rel'],\n    area: [],\n    b: [],\n    br: [],\n    col: [],\n    code: [],\n    div: [],\n    em: [],\n    hr: [],\n    h1: [],\n    h2: [],\n    h3: [],\n    h4: [],\n    h5: [],\n    h6: [],\n    i: [],\n    img: ['src', 'alt', 'title', 'width', 'height'],\n    li: [],\n    ol: [],\n    p: [],\n    pre: [],\n    s: [],\n    small: [],\n    span: [],\n    sub: [],\n    sup: [],\n    strong: [],\n    u: [],\n    ul: []\n    /**\n     * A pattern that recognizes a commonly useful subset of URLs that are safe.\n     *\n     * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n     */\n\n  };\n  var SAFE_URL_PATTERN = /^(?:(?:https?|mailto|ftp|tel|file):|[^&:/?#]*(?:[/?#]|$))/gi;\n  /**\n   * A pattern that matches safe data URLs. Only matches image, video and audio types.\n   *\n   * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n   */\n\n  var DATA_URL_PATTERN = /^data:(?:image\\/(?:bmp|gif|jpeg|jpg|png|tiff|webp)|video\\/(?:mpeg|mp4|ogg|webm)|audio\\/(?:mp3|oga|ogg|opus));base64,[a-z0-9+/]+=*$/i;\n\n  function allowedAttribute(attr, allowedAttributeList) {\n    var attrName = attr.nodeName.toLowerCase();\n\n    if (allowedAttributeList.indexOf(attrName) !== -1) {\n      if (uriAttrs.indexOf(attrName) !== -1) {\n        return Boolean(attr.nodeValue.match(SAFE_URL_PATTERN) || attr.nodeValue.match(DATA_URL_PATTERN));\n      }\n\n      return true;\n    }\n\n    var regExp = allowedAttributeList.filter(function (attrRegex) {\n      return attrRegex instanceof RegExp;\n    }); // Check if a regular expression validates the attribute.\n\n    for (var i = 0, l = regExp.length; i < l; i++) {\n      if (attrName.match(regExp[i])) {\n        return true;\n      }\n    }\n\n    return false;\n  }\n\n  function sanitizeHtml(unsafeHtml, whiteList, sanitizeFn) {\n    if (unsafeHtml.length === 0) {\n      return unsafeHtml;\n    }\n\n    if (sanitizeFn && typeof sanitizeFn === 'function') {\n      return sanitizeFn(unsafeHtml);\n    }\n\n    var domParser = new window.DOMParser();\n    var createdDocument = domParser.parseFromString(unsafeHtml, 'text/html');\n    var whitelistKeys = Object.keys(whiteList);\n    var elements = [].slice.call(createdDocument.body.querySelectorAll('*'));\n\n    var _loop = function _loop(i, len) {\n      var el = elements[i];\n      var elName = el.nodeName.toLowerCase();\n\n      if (whitelistKeys.indexOf(el.nodeName.toLowerCase()) === -1) {\n        el.parentNode.removeChild(el);\n        return \"continue\";\n      }\n\n      var attributeList = [].slice.call(el.attributes);\n      var whitelistedAttributes = [].concat(whiteList['*'] || [], whiteList[elName] || []);\n      attributeList.forEach(function (attr) {\n        if (!allowedAttribute(attr, whitelistedAttributes)) {\n          el.removeAttribute(attr.nodeName);\n        }\n      });\n    };\n\n    for (var i = 0, len = elements.length; i < len; i++) {\n      var _ret = _loop(i, len);\n\n      if (_ret === \"continue\") continue;\n    }\n\n    return createdDocument.body.innerHTML;\n  }\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$6 = 'tooltip';\n  var VERSION$6 = '4.3.1';\n  var DATA_KEY$6 = 'bs.tooltip';\n  var EVENT_KEY$6 = \".\" + DATA_KEY$6;\n  var JQUERY_NO_CONFLICT$6 = $.fn[NAME$6];\n  var CLASS_PREFIX = 'bs-tooltip';\n  var BSCLS_PREFIX_REGEX = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX + \"\\\\S+\", 'g');\n  var DISALLOWED_ATTRIBUTES = ['sanitize', 'whiteList', 'sanitizeFn'];\n  var DefaultType$4 = {\n    animation: 'boolean',\n    template: 'string',\n    title: '(string|element|function)',\n    trigger: 'string',\n    delay: '(number|object)',\n    html: 'boolean',\n    selector: '(string|boolean)',\n    placement: '(string|function)',\n    offset: '(number|string|function)',\n    container: '(string|element|boolean)',\n    fallbackPlacement: '(string|array)',\n    boundary: '(string|element)',\n    sanitize: 'boolean',\n    sanitizeFn: '(null|function)',\n    whiteList: 'object'\n  };\n  var AttachmentMap$1 = {\n    AUTO: 'auto',\n    TOP: 'top',\n    RIGHT: 'right',\n    BOTTOM: 'bottom',\n    LEFT: 'left'\n  };\n  var Default$4 = {\n    animation: true,\n    template: '<div class=\"tooltip\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<div class=\"tooltip-inner\"></div></div>',\n    trigger: 'hover focus',\n    title: '',\n    delay: 0,\n    html: false,\n    selector: false,\n    placement: 'top',\n    offset: 0,\n    container: false,\n    fallbackPlacement: 'flip',\n    boundary: 'scrollParent',\n    sanitize: true,\n    sanitizeFn: null,\n    whiteList: DefaultWhitelist\n  };\n  var HoverState = {\n    SHOW: 'show',\n    OUT: 'out'\n  };\n  var Event$6 = {\n    HIDE: \"hide\" + EVENT_KEY$6,\n    HIDDEN: \"hidden\" + EVENT_KEY$6,\n    SHOW: \"show\" + EVENT_KEY$6,\n    SHOWN: \"shown\" + EVENT_KEY$6,\n    INSERTED: \"inserted\" + EVENT_KEY$6,\n    CLICK: \"click\" + EVENT_KEY$6,\n    FOCUSIN: \"focusin\" + EVENT_KEY$6,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$6,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$6,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$6\n  };\n  var ClassName$6 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$6 = {\n    TOOLTIP: '.tooltip',\n    TOOLTIP_INNER: '.tooltip-inner',\n    ARROW: '.arrow'\n  };\n  var Trigger = {\n    HOVER: 'hover',\n    FOCUS: 'focus',\n    CLICK: 'click',\n    MANUAL: 'manual'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tooltip =\n  /*#__PURE__*/\n  function () {\n    function Tooltip(element, config) {\n      /**\n       * Check for Popper dependency\n       * Popper - https://popper.js.org\n       */\n      if (typeof Popper === 'undefined') {\n        throw new TypeError('Bootstrap\\'s tooltips require Popper.js (https://popper.js.org/)');\n      } // private\n\n\n      this._isEnabled = true;\n      this._timeout = 0;\n      this._hoverState = '';\n      this._activeTrigger = {};\n      this._popper = null; // Protected\n\n      this.element = element;\n      this.config = this._getConfig(config);\n      this.tip = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Tooltip.prototype;\n\n    // Public\n    _proto.enable = function enable() {\n      this._isEnabled = true;\n    };\n\n    _proto.disable = function disable() {\n      this._isEnabled = false;\n    };\n\n    _proto.toggleEnabled = function toggleEnabled() {\n      this._isEnabled = !this._isEnabled;\n    };\n\n    _proto.toggle = function toggle(event) {\n      if (!this._isEnabled) {\n        return;\n      }\n\n      if (event) {\n        var dataKey = this.constructor.DATA_KEY;\n        var context = $(event.currentTarget).data(dataKey);\n\n        if (!context) {\n          context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n          $(event.currentTarget).data(dataKey, context);\n        }\n\n        context._activeTrigger.click = !context._activeTrigger.click;\n\n        if (context._isWithActiveTrigger()) {\n          context._enter(null, context);\n        } else {\n          context._leave(null, context);\n        }\n      } else {\n        if ($(this.getTipElement()).hasClass(ClassName$6.SHOW)) {\n          this._leave(null, this);\n\n          return;\n        }\n\n        this._enter(null, this);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      $.removeData(this.element, this.constructor.DATA_KEY);\n      $(this.element).off(this.constructor.EVENT_KEY);\n      $(this.element).closest('.modal').off('hide.bs.modal');\n\n      if (this.tip) {\n        $(this.tip).remove();\n      }\n\n      this._isEnabled = null;\n      this._timeout = null;\n      this._hoverState = null;\n      this._activeTrigger = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n      }\n\n      this._popper = null;\n      this.element = null;\n      this.config = null;\n      this.tip = null;\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if ($(this.element).css('display') === 'none') {\n        throw new Error('Please use show on visible elements');\n      }\n\n      var showEvent = $.Event(this.constructor.Event.SHOW);\n\n      if (this.isWithContent() && this._isEnabled) {\n        $(this.element).trigger(showEvent);\n        var shadowRoot = Util.findShadowRoot(this.element);\n        var isInTheDom = $.contains(shadowRoot !== null ? shadowRoot : this.element.ownerDocument.documentElement, this.element);\n\n        if (showEvent.isDefaultPrevented() || !isInTheDom) {\n          return;\n        }\n\n        var tip = this.getTipElement();\n        var tipId = Util.getUID(this.constructor.NAME);\n        tip.setAttribute('id', tipId);\n        this.element.setAttribute('aria-describedby', tipId);\n        this.setContent();\n\n        if (this.config.animation) {\n          $(tip).addClass(ClassName$6.FADE);\n        }\n\n        var placement = typeof this.config.placement === 'function' ? this.config.placement.call(this, tip, this.element) : this.config.placement;\n\n        var attachment = this._getAttachment(placement);\n\n        this.addAttachmentClass(attachment);\n\n        var container = this._getContainer();\n\n        $(tip).data(this.constructor.DATA_KEY, this);\n\n        if (!$.contains(this.element.ownerDocument.documentElement, this.tip)) {\n          $(tip).appendTo(container);\n        }\n\n        $(this.element).trigger(this.constructor.Event.INSERTED);\n        this._popper = new Popper(this.element, tip, {\n          placement: attachment,\n          modifiers: {\n            offset: this._getOffset(),\n            flip: {\n              behavior: this.config.fallbackPlacement\n            },\n            arrow: {\n              element: Selector$6.ARROW\n            },\n            preventOverflow: {\n              boundariesElement: this.config.boundary\n            }\n          },\n          onCreate: function onCreate(data) {\n            if (data.originalPlacement !== data.placement) {\n              _this._handlePopperPlacementChange(data);\n            }\n          },\n          onUpdate: function onUpdate(data) {\n            return _this._handlePopperPlacementChange(data);\n          }\n        });\n        $(tip).addClass(ClassName$6.SHOW); // If this is a touch-enabled device we add extra\n        // empty mouseover listeners to the body's immediate children;\n        // only needed because of broken event delegation on iOS\n        // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().on('mouseover', null, $.noop);\n        }\n\n        var complete = function complete() {\n          if (_this.config.animation) {\n            _this._fixTransition();\n          }\n\n          var prevHoverState = _this._hoverState;\n          _this._hoverState = null;\n          $(_this.element).trigger(_this.constructor.Event.SHOWN);\n\n          if (prevHoverState === HoverState.OUT) {\n            _this._leave(null, _this);\n          }\n        };\n\n        if ($(this.tip).hasClass(ClassName$6.FADE)) {\n          var transitionDuration = Util.getTransitionDurationFromElement(this.tip);\n          $(this.tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n        } else {\n          complete();\n        }\n      }\n    };\n\n    _proto.hide = function hide(callback) {\n      var _this2 = this;\n\n      var tip = this.getTipElement();\n      var hideEvent = $.Event(this.constructor.Event.HIDE);\n\n      var complete = function complete() {\n        if (_this2._hoverState !== HoverState.SHOW && tip.parentNode) {\n          tip.parentNode.removeChild(tip);\n        }\n\n        _this2._cleanTipClass();\n\n        _this2.element.removeAttribute('aria-describedby');\n\n        $(_this2.element).trigger(_this2.constructor.Event.HIDDEN);\n\n        if (_this2._popper !== null) {\n          _this2._popper.destroy();\n        }\n\n        if (callback) {\n          callback();\n        }\n      };\n\n      $(this.element).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.SHOW); // If this is a touch-enabled device we remove the extra\n      // empty mouseover listeners we added for iOS support\n\n      if ('ontouchstart' in document.documentElement) {\n        $(document.body).children().off('mouseover', null, $.noop);\n      }\n\n      this._activeTrigger[Trigger.CLICK] = false;\n      this._activeTrigger[Trigger.FOCUS] = false;\n      this._activeTrigger[Trigger.HOVER] = false;\n\n      if ($(this.tip).hasClass(ClassName$6.FADE)) {\n        var transitionDuration = Util.getTransitionDurationFromElement(tip);\n        $(tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n\n      this._hoverState = '';\n    };\n\n    _proto.update = function update() {\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Protected\n    ;\n\n    _proto.isWithContent = function isWithContent() {\n      return Boolean(this.getTitle());\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var tip = this.getTipElement();\n      this.setElementContent($(tip.querySelectorAll(Selector$6.TOOLTIP_INNER)), this.getTitle());\n      $(tip).removeClass(ClassName$6.FADE + \" \" + ClassName$6.SHOW);\n    };\n\n    _proto.setElementContent = function setElementContent($element, content) {\n      if (typeof content === 'object' && (content.nodeType || content.jquery)) {\n        // Content is a DOM node or a jQuery\n        if (this.config.html) {\n          if (!$(content).parent().is($element)) {\n            $element.empty().append(content);\n          }\n        } else {\n          $element.text($(content).text());\n        }\n\n        return;\n      }\n\n      if (this.config.html) {\n        if (this.config.sanitize) {\n          content = sanitizeHtml(content, this.config.whiteList, this.config.sanitizeFn);\n        }\n\n        $element.html(content);\n      } else {\n        $element.text(content);\n      }\n    };\n\n    _proto.getTitle = function getTitle() {\n      var title = this.element.getAttribute('data-original-title');\n\n      if (!title) {\n        title = typeof this.config.title === 'function' ? this.config.title.call(this.element) : this.config.title;\n      }\n\n      return title;\n    } // Private\n    ;\n\n    _proto._getOffset = function _getOffset() {\n      var _this3 = this;\n\n      var offset = {};\n\n      if (typeof this.config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this3.config.offset(data.offsets, _this3.element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this.config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getContainer = function _getContainer() {\n      if (this.config.container === false) {\n        return document.body;\n      }\n\n      if (Util.isElement(this.config.container)) {\n        return $(this.config.container);\n      }\n\n      return $(document).find(this.config.container);\n    };\n\n    _proto._getAttachment = function _getAttachment(placement) {\n      return AttachmentMap$1[placement.toUpperCase()];\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this4 = this;\n\n      var triggers = this.config.trigger.split(' ');\n      triggers.forEach(function (trigger) {\n        if (trigger === 'click') {\n          $(_this4.element).on(_this4.constructor.Event.CLICK, _this4.config.selector, function (event) {\n            return _this4.toggle(event);\n          });\n        } else if (trigger !== Trigger.MANUAL) {\n          var eventIn = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSEENTER : _this4.constructor.Event.FOCUSIN;\n          var eventOut = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSELEAVE : _this4.constructor.Event.FOCUSOUT;\n          $(_this4.element).on(eventIn, _this4.config.selector, function (event) {\n            return _this4._enter(event);\n          }).on(eventOut, _this4.config.selector, function (event) {\n            return _this4._leave(event);\n          });\n        }\n      });\n      $(this.element).closest('.modal').on('hide.bs.modal', function () {\n        if (_this4.element) {\n          _this4.hide();\n        }\n      });\n\n      if (this.config.selector) {\n        this.config = _objectSpread({}, this.config, {\n          trigger: 'manual',\n          selector: ''\n        });\n      } else {\n        this._fixTitle();\n      }\n    };\n\n    _proto._fixTitle = function _fixTitle() {\n      var titleType = typeof this.element.getAttribute('data-original-title');\n\n      if (this.element.getAttribute('title') || titleType !== 'string') {\n        this.element.setAttribute('data-original-title', this.element.getAttribute('title') || '');\n        this.element.setAttribute('title', '');\n      }\n    };\n\n    _proto._enter = function _enter(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusin' ? Trigger.FOCUS : Trigger.HOVER] = true;\n      }\n\n      if ($(context.getTipElement()).hasClass(ClassName$6.SHOW) || context._hoverState === HoverState.SHOW) {\n        context._hoverState = HoverState.SHOW;\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.SHOW;\n\n      if (!context.config.delay || !context.config.delay.show) {\n        context.show();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.SHOW) {\n          context.show();\n        }\n      }, context.config.delay.show);\n    };\n\n    _proto._leave = function _leave(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusout' ? Trigger.FOCUS : Trigger.HOVER] = false;\n      }\n\n      if (context._isWithActiveTrigger()) {\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.OUT;\n\n      if (!context.config.delay || !context.config.delay.hide) {\n        context.hide();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.OUT) {\n          context.hide();\n        }\n      }, context.config.delay.hide);\n    };\n\n    _proto._isWithActiveTrigger = function _isWithActiveTrigger() {\n      for (var trigger in this._activeTrigger) {\n        if (this._activeTrigger[trigger]) {\n          return true;\n        }\n      }\n\n      return false;\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      var dataAttributes = $(this.element).data();\n      Object.keys(dataAttributes).forEach(function (dataAttr) {\n        if (DISALLOWED_ATTRIBUTES.indexOf(dataAttr) !== -1) {\n          delete dataAttributes[dataAttr];\n        }\n      });\n      config = _objectSpread({}, this.constructor.Default, dataAttributes, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.delay === 'number') {\n        config.delay = {\n          show: config.delay,\n          hide: config.delay\n        };\n      }\n\n      if (typeof config.title === 'number') {\n        config.title = config.title.toString();\n      }\n\n      if (typeof config.content === 'number') {\n        config.content = config.content.toString();\n      }\n\n      Util.typeCheckConfig(NAME$6, config, this.constructor.DefaultType);\n\n      if (config.sanitize) {\n        config.template = sanitizeHtml(config.template, config.whiteList, config.sanitizeFn);\n      }\n\n      return config;\n    };\n\n    _proto._getDelegateConfig = function _getDelegateConfig() {\n      var config = {};\n\n      if (this.config) {\n        for (var key in this.config) {\n          if (this.constructor.Default[key] !== this.config[key]) {\n            config[key] = this.config[key];\n          }\n        }\n      }\n\n      return config;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX);\n\n      if (tabClass !== null && tabClass.length) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    };\n\n    _proto._handlePopperPlacementChange = function _handlePopperPlacementChange(popperData) {\n      var popperInstance = popperData.instance;\n      this.tip = popperInstance.popper;\n\n      this._cleanTipClass();\n\n      this.addAttachmentClass(this._getAttachment(popperData.placement));\n    };\n\n    _proto._fixTransition = function _fixTransition() {\n      var tip = this.getTipElement();\n      var initConfigAnimation = this.config.animation;\n\n      if (tip.getAttribute('x-placement') !== null) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.FADE);\n      this.config.animation = false;\n      this.hide();\n      this.show();\n      this.config.animation = initConfigAnimation;\n    } // Static\n    ;\n\n    Tooltip._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$6);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Tooltip(this, _config);\n          $(this).data(DATA_KEY$6, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tooltip, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$6;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$4;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$6;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$6;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$6;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$6;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$4;\n      }\n    }]);\n\n    return Tooltip;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$6] = Tooltip._jQueryInterface;\n  $.fn[NAME$6].Constructor = Tooltip;\n\n  $.fn[NAME$6].noConflict = function () {\n    $.fn[NAME$6] = JQUERY_NO_CONFLICT$6;\n    return Tooltip._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$7 = 'popover';\n  var VERSION$7 = '4.3.1';\n  var DATA_KEY$7 = 'bs.popover';\n  var EVENT_KEY$7 = \".\" + DATA_KEY$7;\n  var JQUERY_NO_CONFLICT$7 = $.fn[NAME$7];\n  var CLASS_PREFIX$1 = 'bs-popover';\n  var BSCLS_PREFIX_REGEX$1 = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX$1 + \"\\\\S+\", 'g');\n\n  var Default$5 = _objectSpread({}, Tooltip.Default, {\n    placement: 'right',\n    trigger: 'click',\n    content: '',\n    template: '<div class=\"popover\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<h3 class=\"popover-header\"></h3>' + '<div class=\"popover-body\"></div></div>'\n  });\n\n  var DefaultType$5 = _objectSpread({}, Tooltip.DefaultType, {\n    content: '(string|element|function)'\n  });\n\n  var ClassName$7 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$7 = {\n    TITLE: '.popover-header',\n    CONTENT: '.popover-body'\n  };\n  var Event$7 = {\n    HIDE: \"hide\" + EVENT_KEY$7,\n    HIDDEN: \"hidden\" + EVENT_KEY$7,\n    SHOW: \"show\" + EVENT_KEY$7,\n    SHOWN: \"shown\" + EVENT_KEY$7,\n    INSERTED: \"inserted\" + EVENT_KEY$7,\n    CLICK: \"click\" + EVENT_KEY$7,\n    FOCUSIN: \"focusin\" + EVENT_KEY$7,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$7,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$7,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$7\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Popover =\n  /*#__PURE__*/\n  function (_Tooltip) {\n    _inheritsLoose(Popover, _Tooltip);\n\n    function Popover() {\n      return _Tooltip.apply(this, arguments) || this;\n    }\n\n    var _proto = Popover.prototype;\n\n    // Overrides\n    _proto.isWithContent = function isWithContent() {\n      return this.getTitle() || this._getContent();\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX$1 + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var $tip = $(this.getTipElement()); // We use append for html objects to maintain js events\n\n      this.setElementContent($tip.find(Selector$7.TITLE), this.getTitle());\n\n      var content = this._getContent();\n\n      if (typeof content === 'function') {\n        content = content.call(this.element);\n      }\n\n      this.setElementContent($tip.find(Selector$7.CONTENT), content);\n      $tip.removeClass(ClassName$7.FADE + \" \" + ClassName$7.SHOW);\n    } // Private\n    ;\n\n    _proto._getContent = function _getContent() {\n      return this.element.getAttribute('data-content') || this.config.content;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX$1);\n\n      if (tabClass !== null && tabClass.length > 0) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    } // Static\n    ;\n\n    Popover._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$7);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Popover(this, _config);\n          $(this).data(DATA_KEY$7, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Popover, null, [{\n      key: \"VERSION\",\n      // Getters\n      get: function get() {\n        return VERSION$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$5;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$7;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$7;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$7;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$7;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$5;\n      }\n    }]);\n\n    return Popover;\n  }(Tooltip);\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$7] = Popover._jQueryInterface;\n  $.fn[NAME$7].Constructor = Popover;\n\n  $.fn[NAME$7].noConflict = function () {\n    $.fn[NAME$7] = JQUERY_NO_CONFLICT$7;\n    return Popover._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$8 = 'scrollspy';\n  var VERSION$8 = '4.3.1';\n  var DATA_KEY$8 = 'bs.scrollspy';\n  var EVENT_KEY$8 = \".\" + DATA_KEY$8;\n  var DATA_API_KEY$6 = '.data-api';\n  var JQUERY_NO_CONFLICT$8 = $.fn[NAME$8];\n  var Default$6 = {\n    offset: 10,\n    method: 'auto',\n    target: ''\n  };\n  var DefaultType$6 = {\n    offset: 'number',\n    method: 'string',\n    target: '(string|element)'\n  };\n  var Event$8 = {\n    ACTIVATE: \"activate\" + EVENT_KEY$8,\n    SCROLL: \"scroll\" + EVENT_KEY$8,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$8 + DATA_API_KEY$6\n  };\n  var ClassName$8 = {\n    DROPDOWN_ITEM: 'dropdown-item',\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active'\n  };\n  var Selector$8 = {\n    DATA_SPY: '[data-spy=\"scroll\"]',\n    ACTIVE: '.active',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    NAV_LINKS: '.nav-link',\n    NAV_ITEMS: '.nav-item',\n    LIST_ITEMS: '.list-group-item',\n    DROPDOWN: '.dropdown',\n    DROPDOWN_ITEMS: '.dropdown-item',\n    DROPDOWN_TOGGLE: '.dropdown-toggle'\n  };\n  var OffsetMethod = {\n    OFFSET: 'offset',\n    POSITION: 'position'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var ScrollSpy =\n  /*#__PURE__*/\n  function () {\n    function ScrollSpy(element, config) {\n      var _this = this;\n\n      this._element = element;\n      this._scrollElement = element.tagName === 'BODY' ? window : element;\n      this._config = this._getConfig(config);\n      this._selector = this._config.target + \" \" + Selector$8.NAV_LINKS + \",\" + (this._config.target + \" \" + Selector$8.LIST_ITEMS + \",\") + (this._config.target + \" \" + Selector$8.DROPDOWN_ITEMS);\n      this._offsets = [];\n      this._targets = [];\n      this._activeTarget = null;\n      this._scrollHeight = 0;\n      $(this._scrollElement).on(Event$8.SCROLL, function (event) {\n        return _this._process(event);\n      });\n      this.refresh();\n\n      this._process();\n    } // Getters\n\n\n    var _proto = ScrollSpy.prototype;\n\n    // Public\n    _proto.refresh = function refresh() {\n      var _this2 = this;\n\n      var autoMethod = this._scrollElement === this._scrollElement.window ? OffsetMethod.OFFSET : OffsetMethod.POSITION;\n      var offsetMethod = this._config.method === 'auto' ? autoMethod : this._config.method;\n      var offsetBase = offsetMethod === OffsetMethod.POSITION ? this._getScrollTop() : 0;\n      this._offsets = [];\n      this._targets = [];\n      this._scrollHeight = this._getScrollHeight();\n      var targets = [].slice.call(document.querySelectorAll(this._selector));\n      targets.map(function (element) {\n        var target;\n        var targetSelector = Util.getSelectorFromElement(element);\n\n        if (targetSelector) {\n          target = document.querySelector(targetSelector);\n        }\n\n        if (target) {\n          var targetBCR = target.getBoundingClientRect();\n\n          if (targetBCR.width || targetBCR.height) {\n            // TODO (fat): remove sketch reliance on jQuery position/offset\n            return [$(target)[offsetMethod]().top + offsetBase, targetSelector];\n          }\n        }\n\n        return null;\n      }).filter(function (item) {\n        return item;\n      }).sort(function (a, b) {\n        return a[0] - b[0];\n      }).forEach(function (item) {\n        _this2._offsets.push(item[0]);\n\n        _this2._targets.push(item[1]);\n      });\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$8);\n      $(this._scrollElement).off(EVENT_KEY$8);\n      this._element = null;\n      this._scrollElement = null;\n      this._config = null;\n      this._selector = null;\n      this._offsets = null;\n      this._targets = null;\n      this._activeTarget = null;\n      this._scrollHeight = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$6, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.target !== 'string') {\n        var id = $(config.target).attr('id');\n\n        if (!id) {\n          id = Util.getUID(NAME$8);\n          $(config.target).attr('id', id);\n        }\n\n        config.target = \"#\" + id;\n      }\n\n      Util.typeCheckConfig(NAME$8, config, DefaultType$6);\n      return config;\n    };\n\n    _proto._getScrollTop = function _getScrollTop() {\n      return this._scrollElement === window ? this._scrollElement.pageYOffset : this._scrollElement.scrollTop;\n    };\n\n    _proto._getScrollHeight = function _getScrollHeight() {\n      return this._scrollElement.scrollHeight || Math.max(document.body.scrollHeight, document.documentElement.scrollHeight);\n    };\n\n    _proto._getOffsetHeight = function _getOffsetHeight() {\n      return this._scrollElement === window ? window.innerHeight : this._scrollElement.getBoundingClientRect().height;\n    };\n\n    _proto._process = function _process() {\n      var scrollTop = this._getScrollTop() + this._config.offset;\n\n      var scrollHeight = this._getScrollHeight();\n\n      var maxScroll = this._config.offset + scrollHeight - this._getOffsetHeight();\n\n      if (this._scrollHeight !== scrollHeight) {\n        this.refresh();\n      }\n\n      if (scrollTop >= maxScroll) {\n        var target = this._targets[this._targets.length - 1];\n\n        if (this._activeTarget !== target) {\n          this._activate(target);\n        }\n\n        return;\n      }\n\n      if (this._activeTarget && scrollTop < this._offsets[0] && this._offsets[0] > 0) {\n        this._activeTarget = null;\n\n        this._clear();\n\n        return;\n      }\n\n      var offsetLength = this._offsets.length;\n\n      for (var i = offsetLength; i--;) {\n        var isActiveTarget = this._activeTarget !== this._targets[i] && scrollTop >= this._offsets[i] && (typeof this._offsets[i + 1] === 'undefined' || scrollTop < this._offsets[i + 1]);\n\n        if (isActiveTarget) {\n          this._activate(this._targets[i]);\n        }\n      }\n    };\n\n    _proto._activate = function _activate(target) {\n      this._activeTarget = target;\n\n      this._clear();\n\n      var queries = this._selector.split(',').map(function (selector) {\n        return selector + \"[data-target=\\\"\" + target + \"\\\"],\" + selector + \"[href=\\\"\" + target + \"\\\"]\";\n      });\n\n      var $link = $([].slice.call(document.querySelectorAll(queries.join(','))));\n\n      if ($link.hasClass(ClassName$8.DROPDOWN_ITEM)) {\n        $link.closest(Selector$8.DROPDOWN).find(Selector$8.DROPDOWN_TOGGLE).addClass(ClassName$8.ACTIVE);\n        $link.addClass(ClassName$8.ACTIVE);\n      } else {\n        // Set triggered link as active\n        $link.addClass(ClassName$8.ACTIVE); // Set triggered links parents as active\n        // With both <ul> and <nav> markup a parent is the previous sibling of any nav ancestor\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_LINKS + \", \" + Selector$8.LIST_ITEMS).addClass(ClassName$8.ACTIVE); // Handle special case when .nav-link is inside .nav-item\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_ITEMS).children(Selector$8.NAV_LINKS).addClass(ClassName$8.ACTIVE);\n      }\n\n      $(this._scrollElement).trigger(Event$8.ACTIVATE, {\n        relatedTarget: target\n      });\n    };\n\n    _proto._clear = function _clear() {\n      [].slice.call(document.querySelectorAll(this._selector)).filter(function (node) {\n        return node.classList.contains(ClassName$8.ACTIVE);\n      }).forEach(function (node) {\n        return node.classList.remove(ClassName$8.ACTIVE);\n      });\n    } // Static\n    ;\n\n    ScrollSpy._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$8);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new ScrollSpy(this, _config);\n          $(this).data(DATA_KEY$8, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(ScrollSpy, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$8;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$6;\n      }\n    }]);\n\n    return ScrollSpy;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(window).on(Event$8.LOAD_DATA_API, function () {\n    var scrollSpys = [].slice.call(document.querySelectorAll(Selector$8.DATA_SPY));\n    var scrollSpysLength = scrollSpys.length;\n\n    for (var i = scrollSpysLength; i--;) {\n      var $spy = $(scrollSpys[i]);\n\n      ScrollSpy._jQueryInterface.call($spy, $spy.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$8] = ScrollSpy._jQueryInterface;\n  $.fn[NAME$8].Constructor = ScrollSpy;\n\n  $.fn[NAME$8].noConflict = function () {\n    $.fn[NAME$8] = JQUERY_NO_CONFLICT$8;\n    return ScrollSpy._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$9 = 'tab';\n  var VERSION$9 = '4.3.1';\n  var DATA_KEY$9 = 'bs.tab';\n  var EVENT_KEY$9 = \".\" + DATA_KEY$9;\n  var DATA_API_KEY$7 = '.data-api';\n  var JQUERY_NO_CONFLICT$9 = $.fn[NAME$9];\n  var Event$9 = {\n    HIDE: \"hide\" + EVENT_KEY$9,\n    HIDDEN: \"hidden\" + EVENT_KEY$9,\n    SHOW: \"show\" + EVENT_KEY$9,\n    SHOWN: \"shown\" + EVENT_KEY$9,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$9 + DATA_API_KEY$7\n  };\n  var ClassName$9 = {\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active',\n    DISABLED: 'disabled',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$9 = {\n    DROPDOWN: '.dropdown',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    ACTIVE: '.active',\n    ACTIVE_UL: '> li > .active',\n    DATA_TOGGLE: '[data-toggle=\"tab\"], [data-toggle=\"pill\"], [data-toggle=\"list\"]',\n    DROPDOWN_TOGGLE: '.dropdown-toggle',\n    DROPDOWN_ACTIVE_CHILD: '> .dropdown-menu .active'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tab =\n  /*#__PURE__*/\n  function () {\n    function Tab(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Tab.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._element.parentNode && this._element.parentNode.nodeType === Node.ELEMENT_NODE && $(this._element).hasClass(ClassName$9.ACTIVE) || $(this._element).hasClass(ClassName$9.DISABLED)) {\n        return;\n      }\n\n      var target;\n      var previous;\n      var listElement = $(this._element).closest(Selector$9.NAV_LIST_GROUP)[0];\n      var selector = Util.getSelectorFromElement(this._element);\n\n      if (listElement) {\n        var itemSelector = listElement.nodeName === 'UL' || listElement.nodeName === 'OL' ? Selector$9.ACTIVE_UL : Selector$9.ACTIVE;\n        previous = $.makeArray($(listElement).find(itemSelector));\n        previous = previous[previous.length - 1];\n      }\n\n      var hideEvent = $.Event(Event$9.HIDE, {\n        relatedTarget: this._element\n      });\n      var showEvent = $.Event(Event$9.SHOW, {\n        relatedTarget: previous\n      });\n\n      if (previous) {\n        $(previous).trigger(hideEvent);\n      }\n\n      $(this._element).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented() || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (selector) {\n        target = document.querySelector(selector);\n      }\n\n      this._activate(this._element, listElement);\n\n      var complete = function complete() {\n        var hiddenEvent = $.Event(Event$9.HIDDEN, {\n          relatedTarget: _this._element\n        });\n        var shownEvent = $.Event(Event$9.SHOWN, {\n          relatedTarget: previous\n        });\n        $(previous).trigger(hiddenEvent);\n        $(_this._element).trigger(shownEvent);\n      };\n\n      if (target) {\n        this._activate(target, target.parentNode, complete);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$9);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._activate = function _activate(element, container, callback) {\n      var _this2 = this;\n\n      var activeElements = container && (container.nodeName === 'UL' || container.nodeName === 'OL') ? $(container).find(Selector$9.ACTIVE_UL) : $(container).children(Selector$9.ACTIVE);\n      var active = activeElements[0];\n      var isTransitioning = callback && active && $(active).hasClass(ClassName$9.FADE);\n\n      var complete = function complete() {\n        return _this2._transitionComplete(element, active, callback);\n      };\n\n      if (active && isTransitioning) {\n        var transitionDuration = Util.getTransitionDurationFromElement(active);\n        $(active).removeClass(ClassName$9.SHOW).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto._transitionComplete = function _transitionComplete(element, active, callback) {\n      if (active) {\n        $(active).removeClass(ClassName$9.ACTIVE);\n        var dropdownChild = $(active.parentNode).find(Selector$9.DROPDOWN_ACTIVE_CHILD)[0];\n\n        if (dropdownChild) {\n          $(dropdownChild).removeClass(ClassName$9.ACTIVE);\n        }\n\n        if (active.getAttribute('role') === 'tab') {\n          active.setAttribute('aria-selected', false);\n        }\n      }\n\n      $(element).addClass(ClassName$9.ACTIVE);\n\n      if (element.getAttribute('role') === 'tab') {\n        element.setAttribute('aria-selected', true);\n      }\n\n      Util.reflow(element);\n\n      if (element.classList.contains(ClassName$9.FADE)) {\n        element.classList.add(ClassName$9.SHOW);\n      }\n\n      if (element.parentNode && $(element.parentNode).hasClass(ClassName$9.DROPDOWN_MENU)) {\n        var dropdownElement = $(element).closest(Selector$9.DROPDOWN)[0];\n\n        if (dropdownElement) {\n          var dropdownToggleList = [].slice.call(dropdownElement.querySelectorAll(Selector$9.DROPDOWN_TOGGLE));\n          $(dropdownToggleList).addClass(ClassName$9.ACTIVE);\n        }\n\n        element.setAttribute('aria-expanded', true);\n      }\n\n      if (callback) {\n        callback();\n      }\n    } // Static\n    ;\n\n    Tab._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$9);\n\n        if (!data) {\n          data = new Tab(this);\n          $this.data(DATA_KEY$9, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tab, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$9;\n      }\n    }]);\n\n    return Tab;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$9.CLICK_DATA_API, Selector$9.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n\n    Tab._jQueryInterface.call($(this), 'show');\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$9] = Tab._jQueryInterface;\n  $.fn[NAME$9].Constructor = Tab;\n\n  $.fn[NAME$9].noConflict = function () {\n    $.fn[NAME$9] = JQUERY_NO_CONFLICT$9;\n    return Tab._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$a = 'toast';\n  var VERSION$a = '4.3.1';\n  var DATA_KEY$a = 'bs.toast';\n  var EVENT_KEY$a = \".\" + DATA_KEY$a;\n  var JQUERY_NO_CONFLICT$a = $.fn[NAME$a];\n  var Event$a = {\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$a,\n    HIDE: \"hide\" + EVENT_KEY$a,\n    HIDDEN: \"hidden\" + EVENT_KEY$a,\n    SHOW: \"show\" + EVENT_KEY$a,\n    SHOWN: \"shown\" + EVENT_KEY$a\n  };\n  var ClassName$a = {\n    FADE: 'fade',\n    HIDE: 'hide',\n    SHOW: 'show',\n    SHOWING: 'showing'\n  };\n  var DefaultType$7 = {\n    animation: 'boolean',\n    autohide: 'boolean',\n    delay: 'number'\n  };\n  var Default$7 = {\n    animation: true,\n    autohide: true,\n    delay: 500\n  };\n  var Selector$a = {\n    DATA_DISMISS: '[data-dismiss=\"toast\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Toast =\n  /*#__PURE__*/\n  function () {\n    function Toast(element, config) {\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._timeout = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Toast.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      $(this._element).trigger(Event$a.SHOW);\n\n      if (this._config.animation) {\n        this._element.classList.add(ClassName$a.FADE);\n      }\n\n      var complete = function complete() {\n        _this._element.classList.remove(ClassName$a.SHOWING);\n\n        _this._element.classList.add(ClassName$a.SHOW);\n\n        $(_this._element).trigger(Event$a.SHOWN);\n\n        if (_this._config.autohide) {\n          _this.hide();\n        }\n      };\n\n      this._element.classList.remove(ClassName$a.HIDE);\n\n      this._element.classList.add(ClassName$a.SHOWING);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.hide = function hide(withoutTimeout) {\n      var _this2 = this;\n\n      if (!this._element.classList.contains(ClassName$a.SHOW)) {\n        return;\n      }\n\n      $(this._element).trigger(Event$a.HIDE);\n\n      if (withoutTimeout) {\n        this._close();\n      } else {\n        this._timeout = setTimeout(function () {\n          _this2._close();\n        }, this._config.delay);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      this._timeout = null;\n\n      if (this._element.classList.contains(ClassName$a.SHOW)) {\n        this._element.classList.remove(ClassName$a.SHOW);\n      }\n\n      $(this._element).off(Event$a.CLICK_DISMISS);\n      $.removeData(this._element, DATA_KEY$a);\n      this._element = null;\n      this._config = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$7, $(this._element).data(), typeof config === 'object' && config ? config : {});\n      Util.typeCheckConfig(NAME$a, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this3 = this;\n\n      $(this._element).on(Event$a.CLICK_DISMISS, Selector$a.DATA_DISMISS, function () {\n        return _this3.hide(true);\n      });\n    };\n\n    _proto._close = function _close() {\n      var _this4 = this;\n\n      var complete = function complete() {\n        _this4._element.classList.add(ClassName$a.HIDE);\n\n        $(_this4._element).trigger(Event$a.HIDDEN);\n      };\n\n      this._element.classList.remove(ClassName$a.SHOW);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    } // Static\n    ;\n\n    Toast._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY$a);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new Toast(this, _config);\n          $element.data(DATA_KEY$a, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](this);\n        }\n      });\n    };\n\n    _createClass(Toast, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$a;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$7;\n      }\n    }]);\n\n    return Toast;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$a] = Toast._jQueryInterface;\n  $.fn[NAME$a].Constructor = Toast;\n\n  $.fn[NAME$a].noConflict = function () {\n    $.fn[NAME$a] = JQUERY_NO_CONFLICT$a;\n    return Toast._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): index.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n\n  (function () {\n    if (typeof $ === 'undefined') {\n      throw new TypeError('Bootstrap\\'s JavaScript requires jQuery. jQuery must be included before Bootstrap\\'s JavaScript.');\n    }\n\n    var version = $.fn.jquery.split(' ')[0].split('.');\n    var minMajor = 1;\n    var ltMajor = 2;\n    var minMinor = 9;\n    var minPatch = 1;\n    var maxMajor = 4;\n\n    if (version[0] < ltMajor && version[1] < minMinor || version[0] === minMajor && version[1] === minMinor && version[2] < minPatch || version[0] >= maxMajor) {\n      throw new Error('Bootstrap\\'s JavaScript requires at least jQuery v1.9.1 but less than v4.0.0');\n    }\n  })();\n\n  exports.Util = Util;\n  exports.Alert = Alert;\n  exports.Button = Button;\n  exports.Carousel = Carousel;\n  exports.Collapse = Collapse;\n  exports.Dropdown = Dropdown;\n  exports.Modal = Modal;\n  exports.Popover = Popover;\n  exports.Scrollspy = ScrollSpy;\n  exports.Tab = Tab;\n  exports.Toast = Toast;\n  exports.Tooltip = Tooltip;\n\n  Object.defineProperty(exports, '__esModule', { value: true });\n\n}));\n//# sourceMappingURL=bootstrap.js.map\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/LICENSE.txt",
    "content": "Font Awesome Free License\n-------------------------\n\nFont Awesome Free is free, open source, and GPL friendly. You can use it for\ncommercial projects, open source projects, or really almost whatever you want.\nFull Font Awesome Free license: https://fontawesome.com/license/free.\n\n# Icons: CC BY 4.0 License (https://creativecommons.org/licenses/by/4.0/)\nIn the Font Awesome Free download, the CC BY 4.0 license applies to all icons\npackaged as SVG and JS file types.\n\n# Fonts: SIL OFL 1.1 License (https://scripts.sil.org/OFL)\nIn the Font Awesome Free download, the SIL OFL license applies to all icons\npackaged as web and desktop font files.\n\n# Code: MIT License (https://opensource.org/licenses/MIT)\nIn the Font Awesome Free download, the MIT license applies to all non-font and\nnon-icon files.\n\n# Attribution\nAttribution is required by MIT, SIL OFL, and CC BY licenses. Downloaded Font\nAwesome Free files already contain embedded comments with sufficient\nattribution, so you shouldn't need to do anything additional when using these\nfiles normally.\n\nWe've kept attribution comments terse, so we ask that you do not actively work\nto remove them from files, especially code. They're a great way for folks to\nlearn about Font Awesome.\n\n# Brand Icons\nAll brand icons are trademarks of their respective owners. The use of these\ntrademarks does not indicate endorsement of the trademark holder by Font\nAwesome, nor vice versa. **Please do not use brand logos for any purpose except\nto represent the company, product, or service to which they refer.**\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/all.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n.fa,\n.fas,\n.far,\n.fal,\n.fad,\n.fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1; }\n\n.fa-lg {\n  font-size: 1.33333em;\n  line-height: 0.75em;\n  vertical-align: -.0667em; }\n\n.fa-xs {\n  font-size: .75em; }\n\n.fa-sm {\n  font-size: .875em; }\n\n.fa-1x {\n  font-size: 1em; }\n\n.fa-2x {\n  font-size: 2em; }\n\n.fa-3x {\n  font-size: 3em; }\n\n.fa-4x {\n  font-size: 4em; }\n\n.fa-5x {\n  font-size: 5em; }\n\n.fa-6x {\n  font-size: 6em; }\n\n.fa-7x {\n  font-size: 7em; }\n\n.fa-8x {\n  font-size: 8em; }\n\n.fa-9x {\n  font-size: 9em; }\n\n.fa-10x {\n  font-size: 10em; }\n\n.fa-fw {\n  text-align: center;\n  width: 1.25em; }\n\n.fa-ul {\n  list-style-type: none;\n  margin-left: 2.5em;\n  padding-left: 0; }\n  .fa-ul > li {\n    position: relative; }\n\n.fa-li {\n  left: -2em;\n  position: absolute;\n  text-align: center;\n  width: 2em;\n  line-height: inherit; }\n\n.fa-border {\n  border: solid 0.08em #eee;\n  border-radius: .1em;\n  padding: .2em .25em .15em; }\n\n.fa-pull-left {\n  float: left; }\n\n.fa-pull-right {\n  float: right; }\n\n.fa.fa-pull-left,\n.fas.fa-pull-left,\n.far.fa-pull-left,\n.fal.fa-pull-left,\n.fab.fa-pull-left {\n  margin-right: .3em; }\n\n.fa.fa-pull-right,\n.fas.fa-pull-right,\n.far.fa-pull-right,\n.fal.fa-pull-right,\n.fab.fa-pull-right {\n  margin-left: .3em; }\n\n.fa-spin {\n  -webkit-animation: fa-spin 2s infinite linear;\n          animation: fa-spin 2s infinite linear; }\n\n.fa-pulse {\n  -webkit-animation: fa-spin 1s infinite steps(8);\n          animation: fa-spin 1s infinite steps(8); }\n\n@-webkit-keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n@keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n.fa-rotate-90 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)\";\n  -webkit-transform: rotate(90deg);\n          transform: rotate(90deg); }\n\n.fa-rotate-180 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)\";\n  -webkit-transform: rotate(180deg);\n          transform: rotate(180deg); }\n\n.fa-rotate-270 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)\";\n  -webkit-transform: rotate(270deg);\n          transform: rotate(270deg); }\n\n.fa-flip-horizontal {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)\";\n  -webkit-transform: scale(-1, 1);\n          transform: scale(-1, 1); }\n\n.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(1, -1);\n          transform: scale(1, -1); }\n\n.fa-flip-both, .fa-flip-horizontal.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(-1, -1);\n          transform: scale(-1, -1); }\n\n:root .fa-rotate-90,\n:root .fa-rotate-180,\n:root .fa-rotate-270,\n:root .fa-flip-horizontal,\n:root .fa-flip-vertical,\n:root .fa-flip-both {\n  -webkit-filter: none;\n          filter: none; }\n\n.fa-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: 2.5em; }\n\n.fa-stack-1x,\n.fa-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%; }\n\n.fa-stack-1x {\n  line-height: inherit; }\n\n.fa-stack-2x {\n  font-size: 2em; }\n\n.fa-inverse {\n  color: #fff; }\n\n/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\nreaders do not read off random characters that represent icons */\n.fa-500px:before {\n  content: \"\\f26e\"; }\n\n.fa-accessible-icon:before {\n  content: \"\\f368\"; }\n\n.fa-accusoft:before {\n  content: \"\\f369\"; }\n\n.fa-acquisitions-incorporated:before {\n  content: \"\\f6af\"; }\n\n.fa-ad:before {\n  content: \"\\f641\"; }\n\n.fa-address-book:before {\n  content: \"\\f2b9\"; }\n\n.fa-address-card:before {\n  content: \"\\f2bb\"; }\n\n.fa-adjust:before {\n  content: \"\\f042\"; }\n\n.fa-adn:before {\n  content: \"\\f170\"; }\n\n.fa-adobe:before {\n  content: \"\\f778\"; }\n\n.fa-adversal:before {\n  content: \"\\f36a\"; }\n\n.fa-affiliatetheme:before {\n  content: \"\\f36b\"; }\n\n.fa-air-freshener:before {\n  content: \"\\f5d0\"; }\n\n.fa-airbnb:before {\n  content: \"\\f834\"; }\n\n.fa-algolia:before {\n  content: \"\\f36c\"; }\n\n.fa-align-center:before {\n  content: \"\\f037\"; }\n\n.fa-align-justify:before {\n  content: \"\\f039\"; }\n\n.fa-align-left:before {\n  content: \"\\f036\"; }\n\n.fa-align-right:before {\n  content: \"\\f038\"; }\n\n.fa-alipay:before {\n  content: \"\\f642\"; }\n\n.fa-allergies:before {\n  content: \"\\f461\"; }\n\n.fa-amazon:before {\n  content: \"\\f270\"; }\n\n.fa-amazon-pay:before {\n  content: \"\\f42c\"; }\n\n.fa-ambulance:before {\n  content: \"\\f0f9\"; }\n\n.fa-american-sign-language-interpreting:before {\n  content: \"\\f2a3\"; }\n\n.fa-amilia:before {\n  content: \"\\f36d\"; }\n\n.fa-anchor:before {\n  content: \"\\f13d\"; }\n\n.fa-android:before {\n  content: \"\\f17b\"; }\n\n.fa-angellist:before {\n  content: \"\\f209\"; }\n\n.fa-angle-double-down:before {\n  content: \"\\f103\"; }\n\n.fa-angle-double-left:before {\n  content: \"\\f100\"; }\n\n.fa-angle-double-right:before {\n  content: \"\\f101\"; }\n\n.fa-angle-double-up:before {\n  content: \"\\f102\"; }\n\n.fa-angle-down:before {\n  content: \"\\f107\"; }\n\n.fa-angle-left:before {\n  content: \"\\f104\"; }\n\n.fa-angle-right:before {\n  content: \"\\f105\"; }\n\n.fa-angle-up:before {\n  content: \"\\f106\"; }\n\n.fa-angry:before {\n  content: \"\\f556\"; }\n\n.fa-angrycreative:before {\n  content: \"\\f36e\"; }\n\n.fa-angular:before {\n  content: \"\\f420\"; }\n\n.fa-ankh:before {\n  content: \"\\f644\"; }\n\n.fa-app-store:before {\n  content: \"\\f36f\"; }\n\n.fa-app-store-ios:before {\n  content: \"\\f370\"; }\n\n.fa-apper:before {\n  content: \"\\f371\"; }\n\n.fa-apple:before {\n  content: \"\\f179\"; }\n\n.fa-apple-alt:before {\n  content: \"\\f5d1\"; }\n\n.fa-apple-pay:before {\n  content: \"\\f415\"; }\n\n.fa-archive:before {\n  content: \"\\f187\"; }\n\n.fa-archway:before {\n  content: \"\\f557\"; }\n\n.fa-arrow-alt-circle-down:before {\n  content: \"\\f358\"; }\n\n.fa-arrow-alt-circle-left:before {\n  content: \"\\f359\"; }\n\n.fa-arrow-alt-circle-right:before {\n  content: \"\\f35a\"; }\n\n.fa-arrow-alt-circle-up:before {\n  content: \"\\f35b\"; }\n\n.fa-arrow-circle-down:before {\n  content: \"\\f0ab\"; }\n\n.fa-arrow-circle-left:before {\n  content: \"\\f0a8\"; }\n\n.fa-arrow-circle-right:before {\n  content: \"\\f0a9\"; }\n\n.fa-arrow-circle-up:before {\n  content: \"\\f0aa\"; }\n\n.fa-arrow-down:before {\n  content: \"\\f063\"; }\n\n.fa-arrow-left:before {\n  content: \"\\f060\"; }\n\n.fa-arrow-right:before {\n  content: \"\\f061\"; }\n\n.fa-arrow-up:before {\n  content: \"\\f062\"; }\n\n.fa-arrows-alt:before {\n  content: \"\\f0b2\"; }\n\n.fa-arrows-alt-h:before {\n  content: \"\\f337\"; }\n\n.fa-arrows-alt-v:before {\n  content: \"\\f338\"; }\n\n.fa-artstation:before {\n  content: \"\\f77a\"; }\n\n.fa-assistive-listening-systems:before {\n  content: \"\\f2a2\"; }\n\n.fa-asterisk:before {\n  content: \"\\f069\"; }\n\n.fa-asymmetrik:before {\n  content: \"\\f372\"; }\n\n.fa-at:before {\n  content: \"\\f1fa\"; }\n\n.fa-atlas:before {\n  content: \"\\f558\"; }\n\n.fa-atlassian:before {\n  content: \"\\f77b\"; }\n\n.fa-atom:before {\n  content: \"\\f5d2\"; }\n\n.fa-audible:before {\n  content: \"\\f373\"; }\n\n.fa-audio-description:before {\n  content: \"\\f29e\"; }\n\n.fa-autoprefixer:before {\n  content: \"\\f41c\"; }\n\n.fa-avianex:before {\n  content: \"\\f374\"; }\n\n.fa-aviato:before {\n  content: \"\\f421\"; }\n\n.fa-award:before {\n  content: \"\\f559\"; }\n\n.fa-aws:before {\n  content: \"\\f375\"; }\n\n.fa-baby:before {\n  content: \"\\f77c\"; }\n\n.fa-baby-carriage:before {\n  content: \"\\f77d\"; }\n\n.fa-backspace:before {\n  content: \"\\f55a\"; }\n\n.fa-backward:before {\n  content: \"\\f04a\"; }\n\n.fa-bacon:before {\n  content: \"\\f7e5\"; }\n\n.fa-balance-scale:before {\n  content: \"\\f24e\"; }\n\n.fa-balance-scale-left:before {\n  content: \"\\f515\"; }\n\n.fa-balance-scale-right:before {\n  content: \"\\f516\"; }\n\n.fa-ban:before {\n  content: \"\\f05e\"; }\n\n.fa-band-aid:before {\n  content: \"\\f462\"; }\n\n.fa-bandcamp:before {\n  content: \"\\f2d5\"; }\n\n.fa-barcode:before {\n  content: \"\\f02a\"; }\n\n.fa-bars:before {\n  content: \"\\f0c9\"; }\n\n.fa-baseball-ball:before {\n  content: \"\\f433\"; }\n\n.fa-basketball-ball:before {\n  content: \"\\f434\"; }\n\n.fa-bath:before {\n  content: \"\\f2cd\"; }\n\n.fa-battery-empty:before {\n  content: \"\\f244\"; }\n\n.fa-battery-full:before {\n  content: \"\\f240\"; }\n\n.fa-battery-half:before {\n  content: \"\\f242\"; }\n\n.fa-battery-quarter:before {\n  content: \"\\f243\"; }\n\n.fa-battery-three-quarters:before {\n  content: \"\\f241\"; }\n\n.fa-battle-net:before {\n  content: \"\\f835\"; }\n\n.fa-bed:before {\n  content: \"\\f236\"; }\n\n.fa-beer:before {\n  content: \"\\f0fc\"; }\n\n.fa-behance:before {\n  content: \"\\f1b4\"; }\n\n.fa-behance-square:before {\n  content: \"\\f1b5\"; }\n\n.fa-bell:before {\n  content: \"\\f0f3\"; }\n\n.fa-bell-slash:before {\n  content: \"\\f1f6\"; }\n\n.fa-bezier-curve:before {\n  content: \"\\f55b\"; }\n\n.fa-bible:before {\n  content: \"\\f647\"; }\n\n.fa-bicycle:before {\n  content: \"\\f206\"; }\n\n.fa-biking:before {\n  content: \"\\f84a\"; }\n\n.fa-bimobject:before {\n  content: \"\\f378\"; }\n\n.fa-binoculars:before {\n  content: \"\\f1e5\"; }\n\n.fa-biohazard:before {\n  content: \"\\f780\"; }\n\n.fa-birthday-cake:before {\n  content: \"\\f1fd\"; }\n\n.fa-bitbucket:before {\n  content: \"\\f171\"; }\n\n.fa-bitcoin:before {\n  content: \"\\f379\"; }\n\n.fa-bity:before {\n  content: \"\\f37a\"; }\n\n.fa-black-tie:before {\n  content: \"\\f27e\"; }\n\n.fa-blackberry:before {\n  content: \"\\f37b\"; }\n\n.fa-blender:before {\n  content: \"\\f517\"; }\n\n.fa-blender-phone:before {\n  content: \"\\f6b6\"; }\n\n.fa-blind:before {\n  content: \"\\f29d\"; }\n\n.fa-blog:before {\n  content: \"\\f781\"; }\n\n.fa-blogger:before {\n  content: \"\\f37c\"; }\n\n.fa-blogger-b:before {\n  content: \"\\f37d\"; }\n\n.fa-bluetooth:before {\n  content: \"\\f293\"; }\n\n.fa-bluetooth-b:before {\n  content: \"\\f294\"; }\n\n.fa-bold:before {\n  content: \"\\f032\"; }\n\n.fa-bolt:before {\n  content: \"\\f0e7\"; }\n\n.fa-bomb:before {\n  content: \"\\f1e2\"; }\n\n.fa-bone:before {\n  content: \"\\f5d7\"; }\n\n.fa-bong:before {\n  content: \"\\f55c\"; }\n\n.fa-book:before {\n  content: \"\\f02d\"; }\n\n.fa-book-dead:before {\n  content: \"\\f6b7\"; }\n\n.fa-book-medical:before {\n  content: \"\\f7e6\"; }\n\n.fa-book-open:before {\n  content: \"\\f518\"; }\n\n.fa-book-reader:before {\n  content: \"\\f5da\"; }\n\n.fa-bookmark:before {\n  content: \"\\f02e\"; }\n\n.fa-bootstrap:before {\n  content: \"\\f836\"; }\n\n.fa-border-all:before {\n  content: \"\\f84c\"; }\n\n.fa-border-none:before {\n  content: \"\\f850\"; }\n\n.fa-border-style:before {\n  content: \"\\f853\"; }\n\n.fa-bowling-ball:before {\n  content: \"\\f436\"; }\n\n.fa-box:before {\n  content: \"\\f466\"; }\n\n.fa-box-open:before {\n  content: \"\\f49e\"; }\n\n.fa-boxes:before {\n  content: \"\\f468\"; }\n\n.fa-braille:before {\n  content: \"\\f2a1\"; }\n\n.fa-brain:before {\n  content: \"\\f5dc\"; }\n\n.fa-bread-slice:before {\n  content: \"\\f7ec\"; }\n\n.fa-briefcase:before {\n  content: \"\\f0b1\"; }\n\n.fa-briefcase-medical:before {\n  content: \"\\f469\"; }\n\n.fa-broadcast-tower:before {\n  content: \"\\f519\"; }\n\n.fa-broom:before {\n  content: \"\\f51a\"; }\n\n.fa-brush:before {\n  content: \"\\f55d\"; }\n\n.fa-btc:before {\n  content: \"\\f15a\"; }\n\n.fa-buffer:before {\n  content: \"\\f837\"; }\n\n.fa-bug:before {\n  content: \"\\f188\"; }\n\n.fa-building:before {\n  content: \"\\f1ad\"; }\n\n.fa-bullhorn:before {\n  content: \"\\f0a1\"; }\n\n.fa-bullseye:before {\n  content: \"\\f140\"; }\n\n.fa-burn:before {\n  content: \"\\f46a\"; }\n\n.fa-buromobelexperte:before {\n  content: \"\\f37f\"; }\n\n.fa-bus:before {\n  content: \"\\f207\"; }\n\n.fa-bus-alt:before {\n  content: \"\\f55e\"; }\n\n.fa-business-time:before {\n  content: \"\\f64a\"; }\n\n.fa-buysellads:before {\n  content: \"\\f20d\"; }\n\n.fa-calculator:before {\n  content: \"\\f1ec\"; }\n\n.fa-calendar:before {\n  content: \"\\f133\"; }\n\n.fa-calendar-alt:before {\n  content: \"\\f073\"; }\n\n.fa-calendar-check:before {\n  content: \"\\f274\"; }\n\n.fa-calendar-day:before {\n  content: \"\\f783\"; }\n\n.fa-calendar-minus:before {\n  content: \"\\f272\"; }\n\n.fa-calendar-plus:before {\n  content: \"\\f271\"; }\n\n.fa-calendar-times:before {\n  content: \"\\f273\"; }\n\n.fa-calendar-week:before {\n  content: \"\\f784\"; }\n\n.fa-camera:before {\n  content: \"\\f030\"; }\n\n.fa-camera-retro:before {\n  content: \"\\f083\"; }\n\n.fa-campground:before {\n  content: \"\\f6bb\"; }\n\n.fa-canadian-maple-leaf:before {\n  content: \"\\f785\"; }\n\n.fa-candy-cane:before {\n  content: \"\\f786\"; }\n\n.fa-cannabis:before {\n  content: \"\\f55f\"; }\n\n.fa-capsules:before {\n  content: \"\\f46b\"; }\n\n.fa-car:before {\n  content: \"\\f1b9\"; }\n\n.fa-car-alt:before {\n  content: \"\\f5de\"; }\n\n.fa-car-battery:before {\n  content: \"\\f5df\"; }\n\n.fa-car-crash:before {\n  content: \"\\f5e1\"; }\n\n.fa-car-side:before {\n  content: \"\\f5e4\"; }\n\n.fa-caret-down:before {\n  content: \"\\f0d7\"; }\n\n.fa-caret-left:before {\n  content: \"\\f0d9\"; }\n\n.fa-caret-right:before {\n  content: \"\\f0da\"; }\n\n.fa-caret-square-down:before {\n  content: \"\\f150\"; }\n\n.fa-caret-square-left:before {\n  content: \"\\f191\"; }\n\n.fa-caret-square-right:before {\n  content: \"\\f152\"; }\n\n.fa-caret-square-up:before {\n  content: \"\\f151\"; }\n\n.fa-caret-up:before {\n  content: \"\\f0d8\"; }\n\n.fa-carrot:before {\n  content: \"\\f787\"; }\n\n.fa-cart-arrow-down:before {\n  content: \"\\f218\"; }\n\n.fa-cart-plus:before {\n  content: \"\\f217\"; }\n\n.fa-cash-register:before {\n  content: \"\\f788\"; }\n\n.fa-cat:before {\n  content: \"\\f6be\"; }\n\n.fa-cc-amazon-pay:before {\n  content: \"\\f42d\"; }\n\n.fa-cc-amex:before {\n  content: \"\\f1f3\"; }\n\n.fa-cc-apple-pay:before {\n  content: \"\\f416\"; }\n\n.fa-cc-diners-club:before {\n  content: \"\\f24c\"; }\n\n.fa-cc-discover:before {\n  content: \"\\f1f2\"; }\n\n.fa-cc-jcb:before {\n  content: \"\\f24b\"; }\n\n.fa-cc-mastercard:before {\n  content: \"\\f1f1\"; }\n\n.fa-cc-paypal:before {\n  content: \"\\f1f4\"; }\n\n.fa-cc-stripe:before {\n  content: \"\\f1f5\"; }\n\n.fa-cc-visa:before {\n  content: \"\\f1f0\"; }\n\n.fa-centercode:before {\n  content: \"\\f380\"; }\n\n.fa-centos:before {\n  content: \"\\f789\"; }\n\n.fa-certificate:before {\n  content: \"\\f0a3\"; }\n\n.fa-chair:before {\n  content: \"\\f6c0\"; }\n\n.fa-chalkboard:before {\n  content: \"\\f51b\"; }\n\n.fa-chalkboard-teacher:before {\n  content: \"\\f51c\"; }\n\n.fa-charging-station:before {\n  content: \"\\f5e7\"; }\n\n.fa-chart-area:before {\n  content: \"\\f1fe\"; }\n\n.fa-chart-bar:before {\n  content: \"\\f080\"; }\n\n.fa-chart-line:before {\n  content: \"\\f201\"; }\n\n.fa-chart-pie:before {\n  content: \"\\f200\"; }\n\n.fa-check:before {\n  content: \"\\f00c\"; }\n\n.fa-check-circle:before {\n  content: \"\\f058\"; }\n\n.fa-check-double:before {\n  content: \"\\f560\"; }\n\n.fa-check-square:before {\n  content: \"\\f14a\"; }\n\n.fa-cheese:before {\n  content: \"\\f7ef\"; }\n\n.fa-chess:before {\n  content: \"\\f439\"; }\n\n.fa-chess-bishop:before {\n  content: \"\\f43a\"; }\n\n.fa-chess-board:before {\n  content: \"\\f43c\"; }\n\n.fa-chess-king:before {\n  content: \"\\f43f\"; }\n\n.fa-chess-knight:before {\n  content: \"\\f441\"; }\n\n.fa-chess-pawn:before {\n  content: \"\\f443\"; }\n\n.fa-chess-queen:before {\n  content: \"\\f445\"; }\n\n.fa-chess-rook:before {\n  content: \"\\f447\"; }\n\n.fa-chevron-circle-down:before {\n  content: \"\\f13a\"; }\n\n.fa-chevron-circle-left:before {\n  content: \"\\f137\"; }\n\n.fa-chevron-circle-right:before {\n  content: \"\\f138\"; }\n\n.fa-chevron-circle-up:before {\n  content: \"\\f139\"; }\n\n.fa-chevron-down:before {\n  content: \"\\f078\"; }\n\n.fa-chevron-left:before {\n  content: \"\\f053\"; }\n\n.fa-chevron-right:before {\n  content: \"\\f054\"; }\n\n.fa-chevron-up:before {\n  content: \"\\f077\"; }\n\n.fa-child:before {\n  content: \"\\f1ae\"; }\n\n.fa-chrome:before {\n  content: \"\\f268\"; }\n\n.fa-chromecast:before {\n  content: \"\\f838\"; }\n\n.fa-church:before {\n  content: \"\\f51d\"; }\n\n.fa-circle:before {\n  content: \"\\f111\"; }\n\n.fa-circle-notch:before {\n  content: \"\\f1ce\"; }\n\n.fa-city:before {\n  content: \"\\f64f\"; }\n\n.fa-clinic-medical:before {\n  content: \"\\f7f2\"; }\n\n.fa-clipboard:before {\n  content: \"\\f328\"; }\n\n.fa-clipboard-check:before {\n  content: \"\\f46c\"; }\n\n.fa-clipboard-list:before {\n  content: \"\\f46d\"; }\n\n.fa-clock:before {\n  content: \"\\f017\"; }\n\n.fa-clone:before {\n  content: \"\\f24d\"; }\n\n.fa-closed-captioning:before {\n  content: \"\\f20a\"; }\n\n.fa-cloud:before {\n  content: \"\\f0c2\"; }\n\n.fa-cloud-download-alt:before {\n  content: \"\\f381\"; }\n\n.fa-cloud-meatball:before {\n  content: \"\\f73b\"; }\n\n.fa-cloud-moon:before {\n  content: \"\\f6c3\"; }\n\n.fa-cloud-moon-rain:before {\n  content: \"\\f73c\"; }\n\n.fa-cloud-rain:before {\n  content: \"\\f73d\"; }\n\n.fa-cloud-showers-heavy:before {\n  content: \"\\f740\"; }\n\n.fa-cloud-sun:before {\n  content: \"\\f6c4\"; }\n\n.fa-cloud-sun-rain:before {\n  content: \"\\f743\"; }\n\n.fa-cloud-upload-alt:before {\n  content: \"\\f382\"; }\n\n.fa-cloudscale:before {\n  content: \"\\f383\"; }\n\n.fa-cloudsmith:before {\n  content: \"\\f384\"; }\n\n.fa-cloudversify:before {\n  content: \"\\f385\"; }\n\n.fa-cocktail:before {\n  content: \"\\f561\"; }\n\n.fa-code:before {\n  content: \"\\f121\"; }\n\n.fa-code-branch:before {\n  content: \"\\f126\"; }\n\n.fa-codepen:before {\n  content: \"\\f1cb\"; }\n\n.fa-codiepie:before {\n  content: \"\\f284\"; }\n\n.fa-coffee:before {\n  content: \"\\f0f4\"; }\n\n.fa-cog:before {\n  content: \"\\f013\"; }\n\n.fa-cogs:before {\n  content: \"\\f085\"; }\n\n.fa-coins:before {\n  content: \"\\f51e\"; }\n\n.fa-columns:before {\n  content: \"\\f0db\"; }\n\n.fa-comment:before {\n  content: \"\\f075\"; }\n\n.fa-comment-alt:before {\n  content: \"\\f27a\"; }\n\n.fa-comment-dollar:before {\n  content: \"\\f651\"; }\n\n.fa-comment-dots:before {\n  content: \"\\f4ad\"; }\n\n.fa-comment-medical:before {\n  content: \"\\f7f5\"; }\n\n.fa-comment-slash:before {\n  content: \"\\f4b3\"; }\n\n.fa-comments:before {\n  content: \"\\f086\"; }\n\n.fa-comments-dollar:before {\n  content: \"\\f653\"; }\n\n.fa-compact-disc:before {\n  content: \"\\f51f\"; }\n\n.fa-compass:before {\n  content: \"\\f14e\"; }\n\n.fa-compress:before {\n  content: \"\\f066\"; }\n\n.fa-compress-arrows-alt:before {\n  content: \"\\f78c\"; }\n\n.fa-concierge-bell:before {\n  content: \"\\f562\"; }\n\n.fa-confluence:before {\n  content: \"\\f78d\"; }\n\n.fa-connectdevelop:before {\n  content: \"\\f20e\"; }\n\n.fa-contao:before {\n  content: \"\\f26d\"; }\n\n.fa-cookie:before {\n  content: \"\\f563\"; }\n\n.fa-cookie-bite:before {\n  content: \"\\f564\"; }\n\n.fa-copy:before {\n  content: \"\\f0c5\"; }\n\n.fa-copyright:before {\n  content: \"\\f1f9\"; }\n\n.fa-cotton-bureau:before {\n  content: \"\\f89e\"; }\n\n.fa-couch:before {\n  content: \"\\f4b8\"; }\n\n.fa-cpanel:before {\n  content: \"\\f388\"; }\n\n.fa-creative-commons:before {\n  content: \"\\f25e\"; }\n\n.fa-creative-commons-by:before {\n  content: \"\\f4e7\"; }\n\n.fa-creative-commons-nc:before {\n  content: \"\\f4e8\"; }\n\n.fa-creative-commons-nc-eu:before {\n  content: \"\\f4e9\"; }\n\n.fa-creative-commons-nc-jp:before {\n  content: \"\\f4ea\"; }\n\n.fa-creative-commons-nd:before {\n  content: \"\\f4eb\"; }\n\n.fa-creative-commons-pd:before {\n  content: \"\\f4ec\"; }\n\n.fa-creative-commons-pd-alt:before {\n  content: \"\\f4ed\"; }\n\n.fa-creative-commons-remix:before {\n  content: \"\\f4ee\"; }\n\n.fa-creative-commons-sa:before {\n  content: \"\\f4ef\"; }\n\n.fa-creative-commons-sampling:before {\n  content: \"\\f4f0\"; }\n\n.fa-creative-commons-sampling-plus:before {\n  content: \"\\f4f1\"; }\n\n.fa-creative-commons-share:before {\n  content: \"\\f4f2\"; }\n\n.fa-creative-commons-zero:before {\n  content: \"\\f4f3\"; }\n\n.fa-credit-card:before {\n  content: \"\\f09d\"; }\n\n.fa-critical-role:before {\n  content: \"\\f6c9\"; }\n\n.fa-crop:before {\n  content: \"\\f125\"; }\n\n.fa-crop-alt:before {\n  content: \"\\f565\"; }\n\n.fa-cross:before {\n  content: \"\\f654\"; }\n\n.fa-crosshairs:before {\n  content: \"\\f05b\"; }\n\n.fa-crow:before {\n  content: \"\\f520\"; }\n\n.fa-crown:before {\n  content: \"\\f521\"; }\n\n.fa-crutch:before {\n  content: \"\\f7f7\"; }\n\n.fa-css3:before {\n  content: \"\\f13c\"; }\n\n.fa-css3-alt:before {\n  content: \"\\f38b\"; }\n\n.fa-cube:before {\n  content: \"\\f1b2\"; }\n\n.fa-cubes:before {\n  content: \"\\f1b3\"; }\n\n.fa-cut:before {\n  content: \"\\f0c4\"; }\n\n.fa-cuttlefish:before {\n  content: \"\\f38c\"; }\n\n.fa-d-and-d:before {\n  content: \"\\f38d\"; }\n\n.fa-d-and-d-beyond:before {\n  content: \"\\f6ca\"; }\n\n.fa-dashcube:before {\n  content: \"\\f210\"; }\n\n.fa-database:before {\n  content: \"\\f1c0\"; }\n\n.fa-deaf:before {\n  content: \"\\f2a4\"; }\n\n.fa-delicious:before {\n  content: \"\\f1a5\"; }\n\n.fa-democrat:before {\n  content: \"\\f747\"; }\n\n.fa-deploydog:before {\n  content: \"\\f38e\"; }\n\n.fa-deskpro:before {\n  content: \"\\f38f\"; }\n\n.fa-desktop:before {\n  content: \"\\f108\"; }\n\n.fa-dev:before {\n  content: \"\\f6cc\"; }\n\n.fa-deviantart:before {\n  content: \"\\f1bd\"; }\n\n.fa-dharmachakra:before {\n  content: \"\\f655\"; }\n\n.fa-dhl:before {\n  content: \"\\f790\"; }\n\n.fa-diagnoses:before {\n  content: \"\\f470\"; }\n\n.fa-diaspora:before {\n  content: \"\\f791\"; }\n\n.fa-dice:before {\n  content: \"\\f522\"; }\n\n.fa-dice-d20:before {\n  content: \"\\f6cf\"; }\n\n.fa-dice-d6:before {\n  content: \"\\f6d1\"; }\n\n.fa-dice-five:before {\n  content: \"\\f523\"; }\n\n.fa-dice-four:before {\n  content: \"\\f524\"; }\n\n.fa-dice-one:before {\n  content: \"\\f525\"; }\n\n.fa-dice-six:before {\n  content: \"\\f526\"; }\n\n.fa-dice-three:before {\n  content: \"\\f527\"; }\n\n.fa-dice-two:before {\n  content: \"\\f528\"; }\n\n.fa-digg:before {\n  content: \"\\f1a6\"; }\n\n.fa-digital-ocean:before {\n  content: \"\\f391\"; }\n\n.fa-digital-tachograph:before {\n  content: \"\\f566\"; }\n\n.fa-directions:before {\n  content: \"\\f5eb\"; }\n\n.fa-discord:before {\n  content: \"\\f392\"; }\n\n.fa-discourse:before {\n  content: \"\\f393\"; }\n\n.fa-divide:before {\n  content: \"\\f529\"; }\n\n.fa-dizzy:before {\n  content: \"\\f567\"; }\n\n.fa-dna:before {\n  content: \"\\f471\"; }\n\n.fa-dochub:before {\n  content: \"\\f394\"; }\n\n.fa-docker:before {\n  content: \"\\f395\"; }\n\n.fa-dog:before {\n  content: \"\\f6d3\"; }\n\n.fa-dollar-sign:before {\n  content: \"\\f155\"; }\n\n.fa-dolly:before {\n  content: \"\\f472\"; }\n\n.fa-dolly-flatbed:before {\n  content: \"\\f474\"; }\n\n.fa-donate:before {\n  content: \"\\f4b9\"; }\n\n.fa-door-closed:before {\n  content: \"\\f52a\"; }\n\n.fa-door-open:before {\n  content: \"\\f52b\"; }\n\n.fa-dot-circle:before {\n  content: \"\\f192\"; }\n\n.fa-dove:before {\n  content: \"\\f4ba\"; }\n\n.fa-download:before {\n  content: \"\\f019\"; }\n\n.fa-draft2digital:before {\n  content: \"\\f396\"; }\n\n.fa-drafting-compass:before {\n  content: \"\\f568\"; }\n\n.fa-dragon:before {\n  content: \"\\f6d5\"; }\n\n.fa-draw-polygon:before {\n  content: \"\\f5ee\"; }\n\n.fa-dribbble:before {\n  content: \"\\f17d\"; }\n\n.fa-dribbble-square:before {\n  content: \"\\f397\"; }\n\n.fa-dropbox:before {\n  content: \"\\f16b\"; }\n\n.fa-drum:before {\n  content: \"\\f569\"; }\n\n.fa-drum-steelpan:before {\n  content: \"\\f56a\"; }\n\n.fa-drumstick-bite:before {\n  content: \"\\f6d7\"; }\n\n.fa-drupal:before {\n  content: \"\\f1a9\"; }\n\n.fa-dumbbell:before {\n  content: \"\\f44b\"; }\n\n.fa-dumpster:before {\n  content: \"\\f793\"; }\n\n.fa-dumpster-fire:before {\n  content: \"\\f794\"; }\n\n.fa-dungeon:before {\n  content: \"\\f6d9\"; }\n\n.fa-dyalog:before {\n  content: \"\\f399\"; }\n\n.fa-earlybirds:before {\n  content: \"\\f39a\"; }\n\n.fa-ebay:before {\n  content: \"\\f4f4\"; }\n\n.fa-edge:before {\n  content: \"\\f282\"; }\n\n.fa-edit:before {\n  content: \"\\f044\"; }\n\n.fa-egg:before {\n  content: \"\\f7fb\"; }\n\n.fa-eject:before {\n  content: \"\\f052\"; }\n\n.fa-elementor:before {\n  content: \"\\f430\"; }\n\n.fa-ellipsis-h:before {\n  content: \"\\f141\"; }\n\n.fa-ellipsis-v:before {\n  content: \"\\f142\"; }\n\n.fa-ello:before {\n  content: \"\\f5f1\"; }\n\n.fa-ember:before {\n  content: \"\\f423\"; }\n\n.fa-empire:before {\n  content: \"\\f1d1\"; }\n\n.fa-envelope:before {\n  content: \"\\f0e0\"; }\n\n.fa-envelope-open:before {\n  content: \"\\f2b6\"; }\n\n.fa-envelope-open-text:before {\n  content: \"\\f658\"; }\n\n.fa-envelope-square:before {\n  content: \"\\f199\"; }\n\n.fa-envira:before {\n  content: \"\\f299\"; }\n\n.fa-equals:before {\n  content: \"\\f52c\"; }\n\n.fa-eraser:before {\n  content: \"\\f12d\"; }\n\n.fa-erlang:before {\n  content: \"\\f39d\"; }\n\n.fa-ethereum:before {\n  content: \"\\f42e\"; }\n\n.fa-ethernet:before {\n  content: \"\\f796\"; }\n\n.fa-etsy:before {\n  content: \"\\f2d7\"; }\n\n.fa-euro-sign:before {\n  content: \"\\f153\"; }\n\n.fa-evernote:before {\n  content: \"\\f839\"; }\n\n.fa-exchange-alt:before {\n  content: \"\\f362\"; }\n\n.fa-exclamation:before {\n  content: \"\\f12a\"; }\n\n.fa-exclamation-circle:before {\n  content: \"\\f06a\"; }\n\n.fa-exclamation-triangle:before {\n  content: \"\\f071\"; }\n\n.fa-expand:before {\n  content: \"\\f065\"; }\n\n.fa-expand-arrows-alt:before {\n  content: \"\\f31e\"; }\n\n.fa-expeditedssl:before {\n  content: \"\\f23e\"; }\n\n.fa-external-link-alt:before {\n  content: \"\\f35d\"; }\n\n.fa-external-link-square-alt:before {\n  content: \"\\f360\"; }\n\n.fa-eye:before {\n  content: \"\\f06e\"; }\n\n.fa-eye-dropper:before {\n  content: \"\\f1fb\"; }\n\n.fa-eye-slash:before {\n  content: \"\\f070\"; }\n\n.fa-facebook:before {\n  content: \"\\f09a\"; }\n\n.fa-facebook-f:before {\n  content: \"\\f39e\"; }\n\n.fa-facebook-messenger:before {\n  content: \"\\f39f\"; }\n\n.fa-facebook-square:before {\n  content: \"\\f082\"; }\n\n.fa-fan:before {\n  content: \"\\f863\"; }\n\n.fa-fantasy-flight-games:before {\n  content: \"\\f6dc\"; }\n\n.fa-fast-backward:before {\n  content: \"\\f049\"; }\n\n.fa-fast-forward:before {\n  content: \"\\f050\"; }\n\n.fa-fax:before {\n  content: \"\\f1ac\"; }\n\n.fa-feather:before {\n  content: \"\\f52d\"; }\n\n.fa-feather-alt:before {\n  content: \"\\f56b\"; }\n\n.fa-fedex:before {\n  content: \"\\f797\"; }\n\n.fa-fedora:before {\n  content: \"\\f798\"; }\n\n.fa-female:before {\n  content: \"\\f182\"; }\n\n.fa-fighter-jet:before {\n  content: \"\\f0fb\"; }\n\n.fa-figma:before {\n  content: \"\\f799\"; }\n\n.fa-file:before {\n  content: \"\\f15b\"; }\n\n.fa-file-alt:before {\n  content: \"\\f15c\"; }\n\n.fa-file-archive:before {\n  content: \"\\f1c6\"; }\n\n.fa-file-audio:before {\n  content: \"\\f1c7\"; }\n\n.fa-file-code:before {\n  content: \"\\f1c9\"; }\n\n.fa-file-contract:before {\n  content: \"\\f56c\"; }\n\n.fa-file-csv:before {\n  content: \"\\f6dd\"; }\n\n.fa-file-download:before {\n  content: \"\\f56d\"; }\n\n.fa-file-excel:before {\n  content: \"\\f1c3\"; }\n\n.fa-file-export:before {\n  content: \"\\f56e\"; }\n\n.fa-file-image:before {\n  content: \"\\f1c5\"; }\n\n.fa-file-import:before {\n  content: \"\\f56f\"; }\n\n.fa-file-invoice:before {\n  content: \"\\f570\"; }\n\n.fa-file-invoice-dollar:before {\n  content: \"\\f571\"; }\n\n.fa-file-medical:before {\n  content: \"\\f477\"; }\n\n.fa-file-medical-alt:before {\n  content: \"\\f478\"; }\n\n.fa-file-pdf:before {\n  content: \"\\f1c1\"; }\n\n.fa-file-powerpoint:before {\n  content: \"\\f1c4\"; }\n\n.fa-file-prescription:before {\n  content: \"\\f572\"; }\n\n.fa-file-signature:before {\n  content: \"\\f573\"; }\n\n.fa-file-upload:before {\n  content: \"\\f574\"; }\n\n.fa-file-video:before {\n  content: \"\\f1c8\"; }\n\n.fa-file-word:before {\n  content: \"\\f1c2\"; }\n\n.fa-fill:before {\n  content: \"\\f575\"; }\n\n.fa-fill-drip:before {\n  content: \"\\f576\"; }\n\n.fa-film:before {\n  content: \"\\f008\"; }\n\n.fa-filter:before {\n  content: \"\\f0b0\"; }\n\n.fa-fingerprint:before {\n  content: \"\\f577\"; }\n\n.fa-fire:before {\n  content: \"\\f06d\"; }\n\n.fa-fire-alt:before {\n  content: \"\\f7e4\"; }\n\n.fa-fire-extinguisher:before {\n  content: \"\\f134\"; }\n\n.fa-firefox:before {\n  content: \"\\f269\"; }\n\n.fa-first-aid:before {\n  content: \"\\f479\"; }\n\n.fa-first-order:before {\n  content: \"\\f2b0\"; }\n\n.fa-first-order-alt:before {\n  content: \"\\f50a\"; }\n\n.fa-firstdraft:before {\n  content: \"\\f3a1\"; }\n\n.fa-fish:before {\n  content: \"\\f578\"; }\n\n.fa-fist-raised:before {\n  content: \"\\f6de\"; }\n\n.fa-flag:before {\n  content: \"\\f024\"; }\n\n.fa-flag-checkered:before {\n  content: \"\\f11e\"; }\n\n.fa-flag-usa:before {\n  content: \"\\f74d\"; }\n\n.fa-flask:before {\n  content: \"\\f0c3\"; }\n\n.fa-flickr:before {\n  content: \"\\f16e\"; }\n\n.fa-flipboard:before {\n  content: \"\\f44d\"; }\n\n.fa-flushed:before {\n  content: \"\\f579\"; }\n\n.fa-fly:before {\n  content: \"\\f417\"; }\n\n.fa-folder:before {\n  content: \"\\f07b\"; }\n\n.fa-folder-minus:before {\n  content: \"\\f65d\"; }\n\n.fa-folder-open:before {\n  content: \"\\f07c\"; }\n\n.fa-folder-plus:before {\n  content: \"\\f65e\"; }\n\n.fa-font:before {\n  content: \"\\f031\"; }\n\n.fa-font-awesome:before {\n  content: \"\\f2b4\"; }\n\n.fa-font-awesome-alt:before {\n  content: \"\\f35c\"; }\n\n.fa-font-awesome-flag:before {\n  content: \"\\f425\"; }\n\n.fa-font-awesome-logo-full:before {\n  content: \"\\f4e6\"; }\n\n.fa-fonticons:before {\n  content: \"\\f280\"; }\n\n.fa-fonticons-fi:before {\n  content: \"\\f3a2\"; }\n\n.fa-football-ball:before {\n  content: \"\\f44e\"; }\n\n.fa-fort-awesome:before {\n  content: \"\\f286\"; }\n\n.fa-fort-awesome-alt:before {\n  content: \"\\f3a3\"; }\n\n.fa-forumbee:before {\n  content: \"\\f211\"; }\n\n.fa-forward:before {\n  content: \"\\f04e\"; }\n\n.fa-foursquare:before {\n  content: \"\\f180\"; }\n\n.fa-free-code-camp:before {\n  content: \"\\f2c5\"; }\n\n.fa-freebsd:before {\n  content: \"\\f3a4\"; }\n\n.fa-frog:before {\n  content: \"\\f52e\"; }\n\n.fa-frown:before {\n  content: \"\\f119\"; }\n\n.fa-frown-open:before {\n  content: \"\\f57a\"; }\n\n.fa-fulcrum:before {\n  content: \"\\f50b\"; }\n\n.fa-funnel-dollar:before {\n  content: \"\\f662\"; }\n\n.fa-futbol:before {\n  content: \"\\f1e3\"; }\n\n.fa-galactic-republic:before {\n  content: \"\\f50c\"; }\n\n.fa-galactic-senate:before {\n  content: \"\\f50d\"; }\n\n.fa-gamepad:before {\n  content: \"\\f11b\"; }\n\n.fa-gas-pump:before {\n  content: \"\\f52f\"; }\n\n.fa-gavel:before {\n  content: \"\\f0e3\"; }\n\n.fa-gem:before {\n  content: \"\\f3a5\"; }\n\n.fa-genderless:before {\n  content: \"\\f22d\"; }\n\n.fa-get-pocket:before {\n  content: \"\\f265\"; }\n\n.fa-gg:before {\n  content: \"\\f260\"; }\n\n.fa-gg-circle:before {\n  content: \"\\f261\"; }\n\n.fa-ghost:before {\n  content: \"\\f6e2\"; }\n\n.fa-gift:before {\n  content: \"\\f06b\"; }\n\n.fa-gifts:before {\n  content: \"\\f79c\"; }\n\n.fa-git:before {\n  content: \"\\f1d3\"; }\n\n.fa-git-alt:before {\n  content: \"\\f841\"; }\n\n.fa-git-square:before {\n  content: \"\\f1d2\"; }\n\n.fa-github:before {\n  content: \"\\f09b\"; }\n\n.fa-github-alt:before {\n  content: \"\\f113\"; }\n\n.fa-github-square:before {\n  content: \"\\f092\"; }\n\n.fa-gitkraken:before {\n  content: \"\\f3a6\"; }\n\n.fa-gitlab:before {\n  content: \"\\f296\"; }\n\n.fa-gitter:before {\n  content: \"\\f426\"; }\n\n.fa-glass-cheers:before {\n  content: \"\\f79f\"; }\n\n.fa-glass-martini:before {\n  content: \"\\f000\"; }\n\n.fa-glass-martini-alt:before {\n  content: \"\\f57b\"; }\n\n.fa-glass-whiskey:before {\n  content: \"\\f7a0\"; }\n\n.fa-glasses:before {\n  content: \"\\f530\"; }\n\n.fa-glide:before {\n  content: \"\\f2a5\"; }\n\n.fa-glide-g:before {\n  content: \"\\f2a6\"; }\n\n.fa-globe:before {\n  content: \"\\f0ac\"; }\n\n.fa-globe-africa:before {\n  content: \"\\f57c\"; }\n\n.fa-globe-americas:before {\n  content: \"\\f57d\"; }\n\n.fa-globe-asia:before {\n  content: \"\\f57e\"; }\n\n.fa-globe-europe:before {\n  content: \"\\f7a2\"; }\n\n.fa-gofore:before {\n  content: \"\\f3a7\"; }\n\n.fa-golf-ball:before {\n  content: \"\\f450\"; }\n\n.fa-goodreads:before {\n  content: \"\\f3a8\"; }\n\n.fa-goodreads-g:before {\n  content: \"\\f3a9\"; }\n\n.fa-google:before {\n  content: \"\\f1a0\"; }\n\n.fa-google-drive:before {\n  content: \"\\f3aa\"; }\n\n.fa-google-play:before {\n  content: \"\\f3ab\"; }\n\n.fa-google-plus:before {\n  content: \"\\f2b3\"; }\n\n.fa-google-plus-g:before {\n  content: \"\\f0d5\"; }\n\n.fa-google-plus-square:before {\n  content: \"\\f0d4\"; }\n\n.fa-google-wallet:before {\n  content: \"\\f1ee\"; }\n\n.fa-gopuram:before {\n  content: \"\\f664\"; }\n\n.fa-graduation-cap:before {\n  content: \"\\f19d\"; }\n\n.fa-gratipay:before {\n  content: \"\\f184\"; }\n\n.fa-grav:before {\n  content: \"\\f2d6\"; }\n\n.fa-greater-than:before {\n  content: \"\\f531\"; }\n\n.fa-greater-than-equal:before {\n  content: \"\\f532\"; }\n\n.fa-grimace:before {\n  content: \"\\f57f\"; }\n\n.fa-grin:before {\n  content: \"\\f580\"; }\n\n.fa-grin-alt:before {\n  content: \"\\f581\"; }\n\n.fa-grin-beam:before {\n  content: \"\\f582\"; }\n\n.fa-grin-beam-sweat:before {\n  content: \"\\f583\"; }\n\n.fa-grin-hearts:before {\n  content: \"\\f584\"; }\n\n.fa-grin-squint:before {\n  content: \"\\f585\"; }\n\n.fa-grin-squint-tears:before {\n  content: \"\\f586\"; }\n\n.fa-grin-stars:before {\n  content: \"\\f587\"; }\n\n.fa-grin-tears:before {\n  content: \"\\f588\"; }\n\n.fa-grin-tongue:before {\n  content: \"\\f589\"; }\n\n.fa-grin-tongue-squint:before {\n  content: \"\\f58a\"; }\n\n.fa-grin-tongue-wink:before {\n  content: \"\\f58b\"; }\n\n.fa-grin-wink:before {\n  content: \"\\f58c\"; }\n\n.fa-grip-horizontal:before {\n  content: \"\\f58d\"; }\n\n.fa-grip-lines:before {\n  content: \"\\f7a4\"; }\n\n.fa-grip-lines-vertical:before {\n  content: \"\\f7a5\"; }\n\n.fa-grip-vertical:before {\n  content: \"\\f58e\"; }\n\n.fa-gripfire:before {\n  content: \"\\f3ac\"; }\n\n.fa-grunt:before {\n  content: \"\\f3ad\"; }\n\n.fa-guitar:before {\n  content: \"\\f7a6\"; }\n\n.fa-gulp:before {\n  content: \"\\f3ae\"; }\n\n.fa-h-square:before {\n  content: \"\\f0fd\"; }\n\n.fa-hacker-news:before {\n  content: \"\\f1d4\"; }\n\n.fa-hacker-news-square:before {\n  content: \"\\f3af\"; }\n\n.fa-hackerrank:before {\n  content: \"\\f5f7\"; }\n\n.fa-hamburger:before {\n  content: \"\\f805\"; }\n\n.fa-hammer:before {\n  content: \"\\f6e3\"; }\n\n.fa-hamsa:before {\n  content: \"\\f665\"; }\n\n.fa-hand-holding:before {\n  content: \"\\f4bd\"; }\n\n.fa-hand-holding-heart:before {\n  content: \"\\f4be\"; }\n\n.fa-hand-holding-usd:before {\n  content: \"\\f4c0\"; }\n\n.fa-hand-lizard:before {\n  content: \"\\f258\"; }\n\n.fa-hand-middle-finger:before {\n  content: \"\\f806\"; }\n\n.fa-hand-paper:before {\n  content: \"\\f256\"; }\n\n.fa-hand-peace:before {\n  content: \"\\f25b\"; }\n\n.fa-hand-point-down:before {\n  content: \"\\f0a7\"; }\n\n.fa-hand-point-left:before {\n  content: \"\\f0a5\"; }\n\n.fa-hand-point-right:before {\n  content: \"\\f0a4\"; }\n\n.fa-hand-point-up:before {\n  content: \"\\f0a6\"; }\n\n.fa-hand-pointer:before {\n  content: \"\\f25a\"; }\n\n.fa-hand-rock:before {\n  content: \"\\f255\"; }\n\n.fa-hand-scissors:before {\n  content: \"\\f257\"; }\n\n.fa-hand-spock:before {\n  content: \"\\f259\"; }\n\n.fa-hands:before {\n  content: \"\\f4c2\"; }\n\n.fa-hands-helping:before {\n  content: \"\\f4c4\"; }\n\n.fa-handshake:before {\n  content: \"\\f2b5\"; }\n\n.fa-hanukiah:before {\n  content: \"\\f6e6\"; }\n\n.fa-hard-hat:before {\n  content: \"\\f807\"; }\n\n.fa-hashtag:before {\n  content: \"\\f292\"; }\n\n.fa-hat-wizard:before {\n  content: \"\\f6e8\"; }\n\n.fa-haykal:before {\n  content: \"\\f666\"; }\n\n.fa-hdd:before {\n  content: \"\\f0a0\"; }\n\n.fa-heading:before {\n  content: \"\\f1dc\"; }\n\n.fa-headphones:before {\n  content: \"\\f025\"; }\n\n.fa-headphones-alt:before {\n  content: \"\\f58f\"; }\n\n.fa-headset:before {\n  content: \"\\f590\"; }\n\n.fa-heart:before {\n  content: \"\\f004\"; }\n\n.fa-heart-broken:before {\n  content: \"\\f7a9\"; }\n\n.fa-heartbeat:before {\n  content: \"\\f21e\"; }\n\n.fa-helicopter:before {\n  content: \"\\f533\"; }\n\n.fa-highlighter:before {\n  content: \"\\f591\"; }\n\n.fa-hiking:before {\n  content: \"\\f6ec\"; }\n\n.fa-hippo:before {\n  content: \"\\f6ed\"; }\n\n.fa-hips:before {\n  content: \"\\f452\"; }\n\n.fa-hire-a-helper:before {\n  content: \"\\f3b0\"; }\n\n.fa-history:before {\n  content: \"\\f1da\"; }\n\n.fa-hockey-puck:before {\n  content: \"\\f453\"; }\n\n.fa-holly-berry:before {\n  content: \"\\f7aa\"; }\n\n.fa-home:before {\n  content: \"\\f015\"; }\n\n.fa-hooli:before {\n  content: \"\\f427\"; }\n\n.fa-hornbill:before {\n  content: \"\\f592\"; }\n\n.fa-horse:before {\n  content: \"\\f6f0\"; }\n\n.fa-horse-head:before {\n  content: \"\\f7ab\"; }\n\n.fa-hospital:before {\n  content: \"\\f0f8\"; }\n\n.fa-hospital-alt:before {\n  content: \"\\f47d\"; }\n\n.fa-hospital-symbol:before {\n  content: \"\\f47e\"; }\n\n.fa-hot-tub:before {\n  content: \"\\f593\"; }\n\n.fa-hotdog:before {\n  content: \"\\f80f\"; }\n\n.fa-hotel:before {\n  content: \"\\f594\"; }\n\n.fa-hotjar:before {\n  content: \"\\f3b1\"; }\n\n.fa-hourglass:before {\n  content: \"\\f254\"; }\n\n.fa-hourglass-end:before {\n  content: \"\\f253\"; }\n\n.fa-hourglass-half:before {\n  content: \"\\f252\"; }\n\n.fa-hourglass-start:before {\n  content: \"\\f251\"; }\n\n.fa-house-damage:before {\n  content: \"\\f6f1\"; }\n\n.fa-houzz:before {\n  content: \"\\f27c\"; }\n\n.fa-hryvnia:before {\n  content: \"\\f6f2\"; }\n\n.fa-html5:before {\n  content: \"\\f13b\"; }\n\n.fa-hubspot:before {\n  content: \"\\f3b2\"; }\n\n.fa-i-cursor:before {\n  content: \"\\f246\"; }\n\n.fa-ice-cream:before {\n  content: \"\\f810\"; }\n\n.fa-icicles:before {\n  content: \"\\f7ad\"; }\n\n.fa-icons:before {\n  content: \"\\f86d\"; }\n\n.fa-id-badge:before {\n  content: \"\\f2c1\"; }\n\n.fa-id-card:before {\n  content: \"\\f2c2\"; }\n\n.fa-id-card-alt:before {\n  content: \"\\f47f\"; }\n\n.fa-igloo:before {\n  content: \"\\f7ae\"; }\n\n.fa-image:before {\n  content: \"\\f03e\"; }\n\n.fa-images:before {\n  content: \"\\f302\"; }\n\n.fa-imdb:before {\n  content: \"\\f2d8\"; }\n\n.fa-inbox:before {\n  content: \"\\f01c\"; }\n\n.fa-indent:before {\n  content: \"\\f03c\"; }\n\n.fa-industry:before {\n  content: \"\\f275\"; }\n\n.fa-infinity:before {\n  content: \"\\f534\"; }\n\n.fa-info:before {\n  content: \"\\f129\"; }\n\n.fa-info-circle:before {\n  content: \"\\f05a\"; }\n\n.fa-instagram:before {\n  content: \"\\f16d\"; }\n\n.fa-intercom:before {\n  content: \"\\f7af\"; }\n\n.fa-internet-explorer:before {\n  content: \"\\f26b\"; }\n\n.fa-invision:before {\n  content: \"\\f7b0\"; }\n\n.fa-ioxhost:before {\n  content: \"\\f208\"; }\n\n.fa-italic:before {\n  content: \"\\f033\"; }\n\n.fa-itch-io:before {\n  content: \"\\f83a\"; }\n\n.fa-itunes:before {\n  content: \"\\f3b4\"; }\n\n.fa-itunes-note:before {\n  content: \"\\f3b5\"; }\n\n.fa-java:before {\n  content: \"\\f4e4\"; }\n\n.fa-jedi:before {\n  content: \"\\f669\"; }\n\n.fa-jedi-order:before {\n  content: \"\\f50e\"; }\n\n.fa-jenkins:before {\n  content: \"\\f3b6\"; }\n\n.fa-jira:before {\n  content: \"\\f7b1\"; }\n\n.fa-joget:before {\n  content: \"\\f3b7\"; }\n\n.fa-joint:before {\n  content: \"\\f595\"; }\n\n.fa-joomla:before {\n  content: \"\\f1aa\"; }\n\n.fa-journal-whills:before {\n  content: \"\\f66a\"; }\n\n.fa-js:before {\n  content: \"\\f3b8\"; }\n\n.fa-js-square:before {\n  content: \"\\f3b9\"; }\n\n.fa-jsfiddle:before {\n  content: \"\\f1cc\"; }\n\n.fa-kaaba:before {\n  content: \"\\f66b\"; }\n\n.fa-kaggle:before {\n  content: \"\\f5fa\"; }\n\n.fa-key:before {\n  content: \"\\f084\"; }\n\n.fa-keybase:before {\n  content: \"\\f4f5\"; }\n\n.fa-keyboard:before {\n  content: \"\\f11c\"; }\n\n.fa-keycdn:before {\n  content: \"\\f3ba\"; }\n\n.fa-khanda:before {\n  content: \"\\f66d\"; }\n\n.fa-kickstarter:before {\n  content: \"\\f3bb\"; }\n\n.fa-kickstarter-k:before {\n  content: \"\\f3bc\"; }\n\n.fa-kiss:before {\n  content: \"\\f596\"; }\n\n.fa-kiss-beam:before {\n  content: \"\\f597\"; }\n\n.fa-kiss-wink-heart:before {\n  content: \"\\f598\"; }\n\n.fa-kiwi-bird:before {\n  content: \"\\f535\"; }\n\n.fa-korvue:before {\n  content: \"\\f42f\"; }\n\n.fa-landmark:before {\n  content: \"\\f66f\"; }\n\n.fa-language:before {\n  content: \"\\f1ab\"; }\n\n.fa-laptop:before {\n  content: \"\\f109\"; }\n\n.fa-laptop-code:before {\n  content: \"\\f5fc\"; }\n\n.fa-laptop-medical:before {\n  content: \"\\f812\"; }\n\n.fa-laravel:before {\n  content: \"\\f3bd\"; }\n\n.fa-lastfm:before {\n  content: \"\\f202\"; }\n\n.fa-lastfm-square:before {\n  content: \"\\f203\"; }\n\n.fa-laugh:before {\n  content: \"\\f599\"; }\n\n.fa-laugh-beam:before {\n  content: \"\\f59a\"; }\n\n.fa-laugh-squint:before {\n  content: \"\\f59b\"; }\n\n.fa-laugh-wink:before {\n  content: \"\\f59c\"; }\n\n.fa-layer-group:before {\n  content: \"\\f5fd\"; }\n\n.fa-leaf:before {\n  content: \"\\f06c\"; }\n\n.fa-leanpub:before {\n  content: \"\\f212\"; }\n\n.fa-lemon:before {\n  content: \"\\f094\"; }\n\n.fa-less:before {\n  content: \"\\f41d\"; }\n\n.fa-less-than:before {\n  content: \"\\f536\"; }\n\n.fa-less-than-equal:before {\n  content: \"\\f537\"; }\n\n.fa-level-down-alt:before {\n  content: \"\\f3be\"; }\n\n.fa-level-up-alt:before {\n  content: \"\\f3bf\"; }\n\n.fa-life-ring:before {\n  content: \"\\f1cd\"; }\n\n.fa-lightbulb:before {\n  content: \"\\f0eb\"; }\n\n.fa-line:before {\n  content: \"\\f3c0\"; }\n\n.fa-link:before {\n  content: \"\\f0c1\"; }\n\n.fa-linkedin:before {\n  content: \"\\f08c\"; }\n\n.fa-linkedin-in:before {\n  content: \"\\f0e1\"; }\n\n.fa-linode:before {\n  content: \"\\f2b8\"; }\n\n.fa-linux:before {\n  content: \"\\f17c\"; }\n\n.fa-lira-sign:before {\n  content: \"\\f195\"; }\n\n.fa-list:before {\n  content: \"\\f03a\"; }\n\n.fa-list-alt:before {\n  content: \"\\f022\"; }\n\n.fa-list-ol:before {\n  content: \"\\f0cb\"; }\n\n.fa-list-ul:before {\n  content: \"\\f0ca\"; }\n\n.fa-location-arrow:before {\n  content: \"\\f124\"; }\n\n.fa-lock:before {\n  content: \"\\f023\"; }\n\n.fa-lock-open:before {\n  content: \"\\f3c1\"; }\n\n.fa-long-arrow-alt-down:before {\n  content: \"\\f309\"; }\n\n.fa-long-arrow-alt-left:before {\n  content: \"\\f30a\"; }\n\n.fa-long-arrow-alt-right:before {\n  content: \"\\f30b\"; }\n\n.fa-long-arrow-alt-up:before {\n  content: \"\\f30c\"; }\n\n.fa-low-vision:before {\n  content: \"\\f2a8\"; }\n\n.fa-luggage-cart:before {\n  content: \"\\f59d\"; }\n\n.fa-lyft:before {\n  content: \"\\f3c3\"; }\n\n.fa-magento:before {\n  content: \"\\f3c4\"; }\n\n.fa-magic:before {\n  content: \"\\f0d0\"; }\n\n.fa-magnet:before {\n  content: \"\\f076\"; }\n\n.fa-mail-bulk:before {\n  content: \"\\f674\"; }\n\n.fa-mailchimp:before {\n  content: \"\\f59e\"; }\n\n.fa-male:before {\n  content: \"\\f183\"; }\n\n.fa-mandalorian:before {\n  content: \"\\f50f\"; }\n\n.fa-map:before {\n  content: \"\\f279\"; }\n\n.fa-map-marked:before {\n  content: \"\\f59f\"; }\n\n.fa-map-marked-alt:before {\n  content: \"\\f5a0\"; }\n\n.fa-map-marker:before {\n  content: \"\\f041\"; }\n\n.fa-map-marker-alt:before {\n  content: \"\\f3c5\"; }\n\n.fa-map-pin:before {\n  content: \"\\f276\"; }\n\n.fa-map-signs:before {\n  content: \"\\f277\"; }\n\n.fa-markdown:before {\n  content: \"\\f60f\"; }\n\n.fa-marker:before {\n  content: \"\\f5a1\"; }\n\n.fa-mars:before {\n  content: \"\\f222\"; }\n\n.fa-mars-double:before {\n  content: \"\\f227\"; }\n\n.fa-mars-stroke:before {\n  content: \"\\f229\"; }\n\n.fa-mars-stroke-h:before {\n  content: \"\\f22b\"; }\n\n.fa-mars-stroke-v:before {\n  content: \"\\f22a\"; }\n\n.fa-mask:before {\n  content: \"\\f6fa\"; }\n\n.fa-mastodon:before {\n  content: \"\\f4f6\"; }\n\n.fa-maxcdn:before {\n  content: \"\\f136\"; }\n\n.fa-medal:before {\n  content: \"\\f5a2\"; }\n\n.fa-medapps:before {\n  content: \"\\f3c6\"; }\n\n.fa-medium:before {\n  content: \"\\f23a\"; }\n\n.fa-medium-m:before {\n  content: \"\\f3c7\"; }\n\n.fa-medkit:before {\n  content: \"\\f0fa\"; }\n\n.fa-medrt:before {\n  content: \"\\f3c8\"; }\n\n.fa-meetup:before {\n  content: \"\\f2e0\"; }\n\n.fa-megaport:before {\n  content: \"\\f5a3\"; }\n\n.fa-meh:before {\n  content: \"\\f11a\"; }\n\n.fa-meh-blank:before {\n  content: \"\\f5a4\"; }\n\n.fa-meh-rolling-eyes:before {\n  content: \"\\f5a5\"; }\n\n.fa-memory:before {\n  content: \"\\f538\"; }\n\n.fa-mendeley:before {\n  content: \"\\f7b3\"; }\n\n.fa-menorah:before {\n  content: \"\\f676\"; }\n\n.fa-mercury:before {\n  content: \"\\f223\"; }\n\n.fa-meteor:before {\n  content: \"\\f753\"; }\n\n.fa-microchip:before {\n  content: \"\\f2db\"; }\n\n.fa-microphone:before {\n  content: \"\\f130\"; }\n\n.fa-microphone-alt:before {\n  content: \"\\f3c9\"; }\n\n.fa-microphone-alt-slash:before {\n  content: \"\\f539\"; }\n\n.fa-microphone-slash:before {\n  content: \"\\f131\"; }\n\n.fa-microscope:before {\n  content: \"\\f610\"; }\n\n.fa-microsoft:before {\n  content: \"\\f3ca\"; }\n\n.fa-minus:before {\n  content: \"\\f068\"; }\n\n.fa-minus-circle:before {\n  content: \"\\f056\"; }\n\n.fa-minus-square:before {\n  content: \"\\f146\"; }\n\n.fa-mitten:before {\n  content: \"\\f7b5\"; }\n\n.fa-mix:before {\n  content: \"\\f3cb\"; }\n\n.fa-mixcloud:before {\n  content: \"\\f289\"; }\n\n.fa-mizuni:before {\n  content: \"\\f3cc\"; }\n\n.fa-mobile:before {\n  content: \"\\f10b\"; }\n\n.fa-mobile-alt:before {\n  content: \"\\f3cd\"; }\n\n.fa-modx:before {\n  content: \"\\f285\"; }\n\n.fa-monero:before {\n  content: \"\\f3d0\"; }\n\n.fa-money-bill:before {\n  content: \"\\f0d6\"; }\n\n.fa-money-bill-alt:before {\n  content: \"\\f3d1\"; }\n\n.fa-money-bill-wave:before {\n  content: \"\\f53a\"; }\n\n.fa-money-bill-wave-alt:before {\n  content: \"\\f53b\"; }\n\n.fa-money-check:before {\n  content: \"\\f53c\"; }\n\n.fa-money-check-alt:before {\n  content: \"\\f53d\"; }\n\n.fa-monument:before {\n  content: \"\\f5a6\"; }\n\n.fa-moon:before {\n  content: \"\\f186\"; }\n\n.fa-mortar-pestle:before {\n  content: \"\\f5a7\"; }\n\n.fa-mosque:before {\n  content: \"\\f678\"; }\n\n.fa-motorcycle:before {\n  content: \"\\f21c\"; }\n\n.fa-mountain:before {\n  content: \"\\f6fc\"; }\n\n.fa-mouse-pointer:before {\n  content: \"\\f245\"; }\n\n.fa-mug-hot:before {\n  content: \"\\f7b6\"; }\n\n.fa-music:before {\n  content: \"\\f001\"; }\n\n.fa-napster:before {\n  content: \"\\f3d2\"; }\n\n.fa-neos:before {\n  content: \"\\f612\"; }\n\n.fa-network-wired:before {\n  content: \"\\f6ff\"; }\n\n.fa-neuter:before {\n  content: \"\\f22c\"; }\n\n.fa-newspaper:before {\n  content: \"\\f1ea\"; }\n\n.fa-nimblr:before {\n  content: \"\\f5a8\"; }\n\n.fa-node:before {\n  content: \"\\f419\"; }\n\n.fa-node-js:before {\n  content: \"\\f3d3\"; }\n\n.fa-not-equal:before {\n  content: \"\\f53e\"; }\n\n.fa-notes-medical:before {\n  content: \"\\f481\"; }\n\n.fa-npm:before {\n  content: \"\\f3d4\"; }\n\n.fa-ns8:before {\n  content: \"\\f3d5\"; }\n\n.fa-nutritionix:before {\n  content: \"\\f3d6\"; }\n\n.fa-object-group:before {\n  content: \"\\f247\"; }\n\n.fa-object-ungroup:before {\n  content: \"\\f248\"; }\n\n.fa-odnoklassniki:before {\n  content: \"\\f263\"; }\n\n.fa-odnoklassniki-square:before {\n  content: \"\\f264\"; }\n\n.fa-oil-can:before {\n  content: \"\\f613\"; }\n\n.fa-old-republic:before {\n  content: \"\\f510\"; }\n\n.fa-om:before {\n  content: \"\\f679\"; }\n\n.fa-opencart:before {\n  content: \"\\f23d\"; }\n\n.fa-openid:before {\n  content: \"\\f19b\"; }\n\n.fa-opera:before {\n  content: \"\\f26a\"; }\n\n.fa-optin-monster:before {\n  content: \"\\f23c\"; }\n\n.fa-osi:before {\n  content: \"\\f41a\"; }\n\n.fa-otter:before {\n  content: \"\\f700\"; }\n\n.fa-outdent:before {\n  content: \"\\f03b\"; }\n\n.fa-page4:before {\n  content: \"\\f3d7\"; }\n\n.fa-pagelines:before {\n  content: \"\\f18c\"; }\n\n.fa-pager:before {\n  content: \"\\f815\"; }\n\n.fa-paint-brush:before {\n  content: \"\\f1fc\"; }\n\n.fa-paint-roller:before {\n  content: \"\\f5aa\"; }\n\n.fa-palette:before {\n  content: \"\\f53f\"; }\n\n.fa-palfed:before {\n  content: \"\\f3d8\"; }\n\n.fa-pallet:before {\n  content: \"\\f482\"; }\n\n.fa-paper-plane:before {\n  content: \"\\f1d8\"; }\n\n.fa-paperclip:before {\n  content: \"\\f0c6\"; }\n\n.fa-parachute-box:before {\n  content: \"\\f4cd\"; }\n\n.fa-paragraph:before {\n  content: \"\\f1dd\"; }\n\n.fa-parking:before {\n  content: \"\\f540\"; }\n\n.fa-passport:before {\n  content: \"\\f5ab\"; }\n\n.fa-pastafarianism:before {\n  content: \"\\f67b\"; }\n\n.fa-paste:before {\n  content: \"\\f0ea\"; }\n\n.fa-patreon:before {\n  content: \"\\f3d9\"; }\n\n.fa-pause:before {\n  content: \"\\f04c\"; }\n\n.fa-pause-circle:before {\n  content: \"\\f28b\"; }\n\n.fa-paw:before {\n  content: \"\\f1b0\"; }\n\n.fa-paypal:before {\n  content: \"\\f1ed\"; }\n\n.fa-peace:before {\n  content: \"\\f67c\"; }\n\n.fa-pen:before {\n  content: \"\\f304\"; }\n\n.fa-pen-alt:before {\n  content: \"\\f305\"; }\n\n.fa-pen-fancy:before {\n  content: \"\\f5ac\"; }\n\n.fa-pen-nib:before {\n  content: \"\\f5ad\"; }\n\n.fa-pen-square:before {\n  content: \"\\f14b\"; }\n\n.fa-pencil-alt:before {\n  content: \"\\f303\"; }\n\n.fa-pencil-ruler:before {\n  content: \"\\f5ae\"; }\n\n.fa-penny-arcade:before {\n  content: \"\\f704\"; }\n\n.fa-people-carry:before {\n  content: \"\\f4ce\"; }\n\n.fa-pepper-hot:before {\n  content: \"\\f816\"; }\n\n.fa-percent:before {\n  content: \"\\f295\"; }\n\n.fa-percentage:before {\n  content: \"\\f541\"; }\n\n.fa-periscope:before {\n  content: \"\\f3da\"; }\n\n.fa-person-booth:before {\n  content: \"\\f756\"; }\n\n.fa-phabricator:before {\n  content: \"\\f3db\"; }\n\n.fa-phoenix-framework:before {\n  content: \"\\f3dc\"; }\n\n.fa-phoenix-squadron:before {\n  content: \"\\f511\"; }\n\n.fa-phone:before {\n  content: \"\\f095\"; }\n\n.fa-phone-alt:before {\n  content: \"\\f879\"; }\n\n.fa-phone-slash:before {\n  content: \"\\f3dd\"; }\n\n.fa-phone-square:before {\n  content: \"\\f098\"; }\n\n.fa-phone-square-alt:before {\n  content: \"\\f87b\"; }\n\n.fa-phone-volume:before {\n  content: \"\\f2a0\"; }\n\n.fa-photo-video:before {\n  content: \"\\f87c\"; }\n\n.fa-php:before {\n  content: \"\\f457\"; }\n\n.fa-pied-piper:before {\n  content: \"\\f2ae\"; }\n\n.fa-pied-piper-alt:before {\n  content: \"\\f1a8\"; }\n\n.fa-pied-piper-hat:before {\n  content: \"\\f4e5\"; }\n\n.fa-pied-piper-pp:before {\n  content: \"\\f1a7\"; }\n\n.fa-piggy-bank:before {\n  content: \"\\f4d3\"; }\n\n.fa-pills:before {\n  content: \"\\f484\"; }\n\n.fa-pinterest:before {\n  content: \"\\f0d2\"; }\n\n.fa-pinterest-p:before {\n  content: \"\\f231\"; }\n\n.fa-pinterest-square:before {\n  content: \"\\f0d3\"; }\n\n.fa-pizza-slice:before {\n  content: \"\\f818\"; }\n\n.fa-place-of-worship:before {\n  content: \"\\f67f\"; }\n\n.fa-plane:before {\n  content: \"\\f072\"; }\n\n.fa-plane-arrival:before {\n  content: \"\\f5af\"; }\n\n.fa-plane-departure:before {\n  content: \"\\f5b0\"; }\n\n.fa-play:before {\n  content: \"\\f04b\"; }\n\n.fa-play-circle:before {\n  content: \"\\f144\"; }\n\n.fa-playstation:before {\n  content: \"\\f3df\"; }\n\n.fa-plug:before {\n  content: \"\\f1e6\"; }\n\n.fa-plus:before {\n  content: \"\\f067\"; }\n\n.fa-plus-circle:before {\n  content: \"\\f055\"; }\n\n.fa-plus-square:before {\n  content: \"\\f0fe\"; }\n\n.fa-podcast:before {\n  content: \"\\f2ce\"; }\n\n.fa-poll:before {\n  content: \"\\f681\"; }\n\n.fa-poll-h:before {\n  content: \"\\f682\"; }\n\n.fa-poo:before {\n  content: \"\\f2fe\"; }\n\n.fa-poo-storm:before {\n  content: \"\\f75a\"; }\n\n.fa-poop:before {\n  content: \"\\f619\"; }\n\n.fa-portrait:before {\n  content: \"\\f3e0\"; }\n\n.fa-pound-sign:before {\n  content: \"\\f154\"; }\n\n.fa-power-off:before {\n  content: \"\\f011\"; }\n\n.fa-pray:before {\n  content: \"\\f683\"; }\n\n.fa-praying-hands:before {\n  content: \"\\f684\"; }\n\n.fa-prescription:before {\n  content: \"\\f5b1\"; }\n\n.fa-prescription-bottle:before {\n  content: \"\\f485\"; }\n\n.fa-prescription-bottle-alt:before {\n  content: \"\\f486\"; }\n\n.fa-print:before {\n  content: \"\\f02f\"; }\n\n.fa-procedures:before {\n  content: \"\\f487\"; }\n\n.fa-product-hunt:before {\n  content: \"\\f288\"; }\n\n.fa-project-diagram:before {\n  content: \"\\f542\"; }\n\n.fa-pushed:before {\n  content: \"\\f3e1\"; }\n\n.fa-puzzle-piece:before {\n  content: \"\\f12e\"; }\n\n.fa-python:before {\n  content: \"\\f3e2\"; }\n\n.fa-qq:before {\n  content: \"\\f1d6\"; }\n\n.fa-qrcode:before {\n  content: \"\\f029\"; }\n\n.fa-question:before {\n  content: \"\\f128\"; }\n\n.fa-question-circle:before {\n  content: \"\\f059\"; }\n\n.fa-quidditch:before {\n  content: \"\\f458\"; }\n\n.fa-quinscape:before {\n  content: \"\\f459\"; }\n\n.fa-quora:before {\n  content: \"\\f2c4\"; }\n\n.fa-quote-left:before {\n  content: \"\\f10d\"; }\n\n.fa-quote-right:before {\n  content: \"\\f10e\"; }\n\n.fa-quran:before {\n  content: \"\\f687\"; }\n\n.fa-r-project:before {\n  content: \"\\f4f7\"; }\n\n.fa-radiation:before {\n  content: \"\\f7b9\"; }\n\n.fa-radiation-alt:before {\n  content: \"\\f7ba\"; }\n\n.fa-rainbow:before {\n  content: \"\\f75b\"; }\n\n.fa-random:before {\n  content: \"\\f074\"; }\n\n.fa-raspberry-pi:before {\n  content: \"\\f7bb\"; }\n\n.fa-ravelry:before {\n  content: \"\\f2d9\"; }\n\n.fa-react:before {\n  content: \"\\f41b\"; }\n\n.fa-reacteurope:before {\n  content: \"\\f75d\"; }\n\n.fa-readme:before {\n  content: \"\\f4d5\"; }\n\n.fa-rebel:before {\n  content: \"\\f1d0\"; }\n\n.fa-receipt:before {\n  content: \"\\f543\"; }\n\n.fa-recycle:before {\n  content: \"\\f1b8\"; }\n\n.fa-red-river:before {\n  content: \"\\f3e3\"; }\n\n.fa-reddit:before {\n  content: \"\\f1a1\"; }\n\n.fa-reddit-alien:before {\n  content: \"\\f281\"; }\n\n.fa-reddit-square:before {\n  content: \"\\f1a2\"; }\n\n.fa-redhat:before {\n  content: \"\\f7bc\"; }\n\n.fa-redo:before {\n  content: \"\\f01e\"; }\n\n.fa-redo-alt:before {\n  content: \"\\f2f9\"; }\n\n.fa-registered:before {\n  content: \"\\f25d\"; }\n\n.fa-remove-format:before {\n  content: \"\\f87d\"; }\n\n.fa-renren:before {\n  content: \"\\f18b\"; }\n\n.fa-reply:before {\n  content: \"\\f3e5\"; }\n\n.fa-reply-all:before {\n  content: \"\\f122\"; }\n\n.fa-replyd:before {\n  content: \"\\f3e6\"; }\n\n.fa-republican:before {\n  content: \"\\f75e\"; }\n\n.fa-researchgate:before {\n  content: \"\\f4f8\"; }\n\n.fa-resolving:before {\n  content: \"\\f3e7\"; }\n\n.fa-restroom:before {\n  content: \"\\f7bd\"; }\n\n.fa-retweet:before {\n  content: \"\\f079\"; }\n\n.fa-rev:before {\n  content: \"\\f5b2\"; }\n\n.fa-ribbon:before {\n  content: \"\\f4d6\"; }\n\n.fa-ring:before {\n  content: \"\\f70b\"; }\n\n.fa-road:before {\n  content: \"\\f018\"; }\n\n.fa-robot:before {\n  content: \"\\f544\"; }\n\n.fa-rocket:before {\n  content: \"\\f135\"; }\n\n.fa-rocketchat:before {\n  content: \"\\f3e8\"; }\n\n.fa-rockrms:before {\n  content: \"\\f3e9\"; }\n\n.fa-route:before {\n  content: \"\\f4d7\"; }\n\n.fa-rss:before {\n  content: \"\\f09e\"; }\n\n.fa-rss-square:before {\n  content: \"\\f143\"; }\n\n.fa-ruble-sign:before {\n  content: \"\\f158\"; }\n\n.fa-ruler:before {\n  content: \"\\f545\"; }\n\n.fa-ruler-combined:before {\n  content: \"\\f546\"; }\n\n.fa-ruler-horizontal:before {\n  content: \"\\f547\"; }\n\n.fa-ruler-vertical:before {\n  content: \"\\f548\"; }\n\n.fa-running:before {\n  content: \"\\f70c\"; }\n\n.fa-rupee-sign:before {\n  content: \"\\f156\"; }\n\n.fa-sad-cry:before {\n  content: \"\\f5b3\"; }\n\n.fa-sad-tear:before {\n  content: \"\\f5b4\"; }\n\n.fa-safari:before {\n  content: \"\\f267\"; }\n\n.fa-salesforce:before {\n  content: \"\\f83b\"; }\n\n.fa-sass:before {\n  content: \"\\f41e\"; }\n\n.fa-satellite:before {\n  content: \"\\f7bf\"; }\n\n.fa-satellite-dish:before {\n  content: \"\\f7c0\"; }\n\n.fa-save:before {\n  content: \"\\f0c7\"; }\n\n.fa-schlix:before {\n  content: \"\\f3ea\"; }\n\n.fa-school:before {\n  content: \"\\f549\"; }\n\n.fa-screwdriver:before {\n  content: \"\\f54a\"; }\n\n.fa-scribd:before {\n  content: \"\\f28a\"; }\n\n.fa-scroll:before {\n  content: \"\\f70e\"; }\n\n.fa-sd-card:before {\n  content: \"\\f7c2\"; }\n\n.fa-search:before {\n  content: \"\\f002\"; }\n\n.fa-search-dollar:before {\n  content: \"\\f688\"; }\n\n.fa-search-location:before {\n  content: \"\\f689\"; }\n\n.fa-search-minus:before {\n  content: \"\\f010\"; }\n\n.fa-search-plus:before {\n  content: \"\\f00e\"; }\n\n.fa-searchengin:before {\n  content: \"\\f3eb\"; }\n\n.fa-seedling:before {\n  content: \"\\f4d8\"; }\n\n.fa-sellcast:before {\n  content: \"\\f2da\"; }\n\n.fa-sellsy:before {\n  content: \"\\f213\"; }\n\n.fa-server:before {\n  content: \"\\f233\"; }\n\n.fa-servicestack:before {\n  content: \"\\f3ec\"; }\n\n.fa-shapes:before {\n  content: \"\\f61f\"; }\n\n.fa-share:before {\n  content: \"\\f064\"; }\n\n.fa-share-alt:before {\n  content: \"\\f1e0\"; }\n\n.fa-share-alt-square:before {\n  content: \"\\f1e1\"; }\n\n.fa-share-square:before {\n  content: \"\\f14d\"; }\n\n.fa-shekel-sign:before {\n  content: \"\\f20b\"; }\n\n.fa-shield-alt:before {\n  content: \"\\f3ed\"; }\n\n.fa-ship:before {\n  content: \"\\f21a\"; }\n\n.fa-shipping-fast:before {\n  content: \"\\f48b\"; }\n\n.fa-shirtsinbulk:before {\n  content: \"\\f214\"; }\n\n.fa-shoe-prints:before {\n  content: \"\\f54b\"; }\n\n.fa-shopping-bag:before {\n  content: \"\\f290\"; }\n\n.fa-shopping-basket:before {\n  content: \"\\f291\"; }\n\n.fa-shopping-cart:before {\n  content: \"\\f07a\"; }\n\n.fa-shopware:before {\n  content: \"\\f5b5\"; }\n\n.fa-shower:before {\n  content: \"\\f2cc\"; }\n\n.fa-shuttle-van:before {\n  content: \"\\f5b6\"; }\n\n.fa-sign:before {\n  content: \"\\f4d9\"; }\n\n.fa-sign-in-alt:before {\n  content: \"\\f2f6\"; }\n\n.fa-sign-language:before {\n  content: \"\\f2a7\"; }\n\n.fa-sign-out-alt:before {\n  content: \"\\f2f5\"; }\n\n.fa-signal:before {\n  content: \"\\f012\"; }\n\n.fa-signature:before {\n  content: \"\\f5b7\"; }\n\n.fa-sim-card:before {\n  content: \"\\f7c4\"; }\n\n.fa-simplybuilt:before {\n  content: \"\\f215\"; }\n\n.fa-sistrix:before {\n  content: \"\\f3ee\"; }\n\n.fa-sitemap:before {\n  content: \"\\f0e8\"; }\n\n.fa-sith:before {\n  content: \"\\f512\"; }\n\n.fa-skating:before {\n  content: \"\\f7c5\"; }\n\n.fa-sketch:before {\n  content: \"\\f7c6\"; }\n\n.fa-skiing:before {\n  content: \"\\f7c9\"; }\n\n.fa-skiing-nordic:before {\n  content: \"\\f7ca\"; }\n\n.fa-skull:before {\n  content: \"\\f54c\"; }\n\n.fa-skull-crossbones:before {\n  content: \"\\f714\"; }\n\n.fa-skyatlas:before {\n  content: \"\\f216\"; }\n\n.fa-skype:before {\n  content: \"\\f17e\"; }\n\n.fa-slack:before {\n  content: \"\\f198\"; }\n\n.fa-slack-hash:before {\n  content: \"\\f3ef\"; }\n\n.fa-slash:before {\n  content: \"\\f715\"; }\n\n.fa-sleigh:before {\n  content: \"\\f7cc\"; }\n\n.fa-sliders-h:before {\n  content: \"\\f1de\"; }\n\n.fa-slideshare:before {\n  content: \"\\f1e7\"; }\n\n.fa-smile:before {\n  content: \"\\f118\"; }\n\n.fa-smile-beam:before {\n  content: \"\\f5b8\"; }\n\n.fa-smile-wink:before {\n  content: \"\\f4da\"; }\n\n.fa-smog:before {\n  content: \"\\f75f\"; }\n\n.fa-smoking:before {\n  content: \"\\f48d\"; }\n\n.fa-smoking-ban:before {\n  content: \"\\f54d\"; }\n\n.fa-sms:before {\n  content: \"\\f7cd\"; }\n\n.fa-snapchat:before {\n  content: \"\\f2ab\"; }\n\n.fa-snapchat-ghost:before {\n  content: \"\\f2ac\"; }\n\n.fa-snapchat-square:before {\n  content: \"\\f2ad\"; }\n\n.fa-snowboarding:before {\n  content: \"\\f7ce\"; }\n\n.fa-snowflake:before {\n  content: \"\\f2dc\"; }\n\n.fa-snowman:before {\n  content: \"\\f7d0\"; }\n\n.fa-snowplow:before {\n  content: \"\\f7d2\"; }\n\n.fa-socks:before {\n  content: \"\\f696\"; }\n\n.fa-solar-panel:before {\n  content: \"\\f5ba\"; }\n\n.fa-sort:before {\n  content: \"\\f0dc\"; }\n\n.fa-sort-alpha-down:before {\n  content: \"\\f15d\"; }\n\n.fa-sort-alpha-down-alt:before {\n  content: \"\\f881\"; }\n\n.fa-sort-alpha-up:before {\n  content: \"\\f15e\"; }\n\n.fa-sort-alpha-up-alt:before {\n  content: \"\\f882\"; }\n\n.fa-sort-amount-down:before {\n  content: \"\\f160\"; }\n\n.fa-sort-amount-down-alt:before {\n  content: \"\\f884\"; }\n\n.fa-sort-amount-up:before {\n  content: \"\\f161\"; }\n\n.fa-sort-amount-up-alt:before {\n  content: \"\\f885\"; }\n\n.fa-sort-down:before {\n  content: \"\\f0dd\"; }\n\n.fa-sort-numeric-down:before {\n  content: \"\\f162\"; }\n\n.fa-sort-numeric-down-alt:before {\n  content: \"\\f886\"; }\n\n.fa-sort-numeric-up:before {\n  content: \"\\f163\"; }\n\n.fa-sort-numeric-up-alt:before {\n  content: \"\\f887\"; }\n\n.fa-sort-up:before {\n  content: \"\\f0de\"; }\n\n.fa-soundcloud:before {\n  content: \"\\f1be\"; }\n\n.fa-sourcetree:before {\n  content: \"\\f7d3\"; }\n\n.fa-spa:before {\n  content: \"\\f5bb\"; }\n\n.fa-space-shuttle:before {\n  content: \"\\f197\"; }\n\n.fa-speakap:before {\n  content: \"\\f3f3\"; }\n\n.fa-speaker-deck:before {\n  content: \"\\f83c\"; }\n\n.fa-spell-check:before {\n  content: \"\\f891\"; }\n\n.fa-spider:before {\n  content: \"\\f717\"; }\n\n.fa-spinner:before {\n  content: \"\\f110\"; }\n\n.fa-splotch:before {\n  content: \"\\f5bc\"; }\n\n.fa-spotify:before {\n  content: \"\\f1bc\"; }\n\n.fa-spray-can:before {\n  content: \"\\f5bd\"; }\n\n.fa-square:before {\n  content: \"\\f0c8\"; }\n\n.fa-square-full:before {\n  content: \"\\f45c\"; }\n\n.fa-square-root-alt:before {\n  content: \"\\f698\"; }\n\n.fa-squarespace:before {\n  content: \"\\f5be\"; }\n\n.fa-stack-exchange:before {\n  content: \"\\f18d\"; }\n\n.fa-stack-overflow:before {\n  content: \"\\f16c\"; }\n\n.fa-stackpath:before {\n  content: \"\\f842\"; }\n\n.fa-stamp:before {\n  content: \"\\f5bf\"; }\n\n.fa-star:before {\n  content: \"\\f005\"; }\n\n.fa-star-and-crescent:before {\n  content: \"\\f699\"; }\n\n.fa-star-half:before {\n  content: \"\\f089\"; }\n\n.fa-star-half-alt:before {\n  content: \"\\f5c0\"; }\n\n.fa-star-of-david:before {\n  content: \"\\f69a\"; }\n\n.fa-star-of-life:before {\n  content: \"\\f621\"; }\n\n.fa-staylinked:before {\n  content: \"\\f3f5\"; }\n\n.fa-steam:before {\n  content: \"\\f1b6\"; }\n\n.fa-steam-square:before {\n  content: \"\\f1b7\"; }\n\n.fa-steam-symbol:before {\n  content: \"\\f3f6\"; }\n\n.fa-step-backward:before {\n  content: \"\\f048\"; }\n\n.fa-step-forward:before {\n  content: \"\\f051\"; }\n\n.fa-stethoscope:before {\n  content: \"\\f0f1\"; }\n\n.fa-sticker-mule:before {\n  content: \"\\f3f7\"; }\n\n.fa-sticky-note:before {\n  content: \"\\f249\"; }\n\n.fa-stop:before {\n  content: \"\\f04d\"; }\n\n.fa-stop-circle:before {\n  content: \"\\f28d\"; }\n\n.fa-stopwatch:before {\n  content: \"\\f2f2\"; }\n\n.fa-store:before {\n  content: \"\\f54e\"; }\n\n.fa-store-alt:before {\n  content: \"\\f54f\"; }\n\n.fa-strava:before {\n  content: \"\\f428\"; }\n\n.fa-stream:before {\n  content: \"\\f550\"; }\n\n.fa-street-view:before {\n  content: \"\\f21d\"; }\n\n.fa-strikethrough:before {\n  content: \"\\f0cc\"; }\n\n.fa-stripe:before {\n  content: \"\\f429\"; }\n\n.fa-stripe-s:before {\n  content: \"\\f42a\"; }\n\n.fa-stroopwafel:before {\n  content: \"\\f551\"; }\n\n.fa-studiovinari:before {\n  content: \"\\f3f8\"; }\n\n.fa-stumbleupon:before {\n  content: \"\\f1a4\"; }\n\n.fa-stumbleupon-circle:before {\n  content: \"\\f1a3\"; }\n\n.fa-subscript:before {\n  content: \"\\f12c\"; }\n\n.fa-subway:before {\n  content: \"\\f239\"; }\n\n.fa-suitcase:before {\n  content: \"\\f0f2\"; }\n\n.fa-suitcase-rolling:before {\n  content: \"\\f5c1\"; }\n\n.fa-sun:before {\n  content: \"\\f185\"; }\n\n.fa-superpowers:before {\n  content: \"\\f2dd\"; }\n\n.fa-superscript:before {\n  content: \"\\f12b\"; }\n\n.fa-supple:before {\n  content: \"\\f3f9\"; }\n\n.fa-surprise:before {\n  content: \"\\f5c2\"; }\n\n.fa-suse:before {\n  content: \"\\f7d6\"; }\n\n.fa-swatchbook:before {\n  content: \"\\f5c3\"; }\n\n.fa-swimmer:before {\n  content: \"\\f5c4\"; }\n\n.fa-swimming-pool:before {\n  content: \"\\f5c5\"; }\n\n.fa-symfony:before {\n  content: \"\\f83d\"; }\n\n.fa-synagogue:before {\n  content: \"\\f69b\"; }\n\n.fa-sync:before {\n  content: \"\\f021\"; }\n\n.fa-sync-alt:before {\n  content: \"\\f2f1\"; }\n\n.fa-syringe:before {\n  content: \"\\f48e\"; }\n\n.fa-table:before {\n  content: \"\\f0ce\"; }\n\n.fa-table-tennis:before {\n  content: \"\\f45d\"; }\n\n.fa-tablet:before {\n  content: \"\\f10a\"; }\n\n.fa-tablet-alt:before {\n  content: \"\\f3fa\"; }\n\n.fa-tablets:before {\n  content: \"\\f490\"; }\n\n.fa-tachometer-alt:before {\n  content: \"\\f3fd\"; }\n\n.fa-tag:before {\n  content: \"\\f02b\"; }\n\n.fa-tags:before {\n  content: \"\\f02c\"; }\n\n.fa-tape:before {\n  content: \"\\f4db\"; }\n\n.fa-tasks:before {\n  content: \"\\f0ae\"; }\n\n.fa-taxi:before {\n  content: \"\\f1ba\"; }\n\n.fa-teamspeak:before {\n  content: \"\\f4f9\"; }\n\n.fa-teeth:before {\n  content: \"\\f62e\"; }\n\n.fa-teeth-open:before {\n  content: \"\\f62f\"; }\n\n.fa-telegram:before {\n  content: \"\\f2c6\"; }\n\n.fa-telegram-plane:before {\n  content: \"\\f3fe\"; }\n\n.fa-temperature-high:before {\n  content: \"\\f769\"; }\n\n.fa-temperature-low:before {\n  content: \"\\f76b\"; }\n\n.fa-tencent-weibo:before {\n  content: \"\\f1d5\"; }\n\n.fa-tenge:before {\n  content: \"\\f7d7\"; }\n\n.fa-terminal:before {\n  content: \"\\f120\"; }\n\n.fa-text-height:before {\n  content: \"\\f034\"; }\n\n.fa-text-width:before {\n  content: \"\\f035\"; }\n\n.fa-th:before {\n  content: \"\\f00a\"; }\n\n.fa-th-large:before {\n  content: \"\\f009\"; }\n\n.fa-th-list:before {\n  content: \"\\f00b\"; }\n\n.fa-the-red-yeti:before {\n  content: \"\\f69d\"; }\n\n.fa-theater-masks:before {\n  content: \"\\f630\"; }\n\n.fa-themeco:before {\n  content: \"\\f5c6\"; }\n\n.fa-themeisle:before {\n  content: \"\\f2b2\"; }\n\n.fa-thermometer:before {\n  content: \"\\f491\"; }\n\n.fa-thermometer-empty:before {\n  content: \"\\f2cb\"; }\n\n.fa-thermometer-full:before {\n  content: \"\\f2c7\"; }\n\n.fa-thermometer-half:before {\n  content: \"\\f2c9\"; }\n\n.fa-thermometer-quarter:before {\n  content: \"\\f2ca\"; }\n\n.fa-thermometer-three-quarters:before {\n  content: \"\\f2c8\"; }\n\n.fa-think-peaks:before {\n  content: \"\\f731\"; }\n\n.fa-thumbs-down:before {\n  content: \"\\f165\"; }\n\n.fa-thumbs-up:before {\n  content: \"\\f164\"; }\n\n.fa-thumbtack:before {\n  content: \"\\f08d\"; }\n\n.fa-ticket-alt:before {\n  content: \"\\f3ff\"; }\n\n.fa-times:before {\n  content: \"\\f00d\"; }\n\n.fa-times-circle:before {\n  content: \"\\f057\"; }\n\n.fa-tint:before {\n  content: \"\\f043\"; }\n\n.fa-tint-slash:before {\n  content: \"\\f5c7\"; }\n\n.fa-tired:before {\n  content: \"\\f5c8\"; }\n\n.fa-toggle-off:before {\n  content: \"\\f204\"; }\n\n.fa-toggle-on:before {\n  content: \"\\f205\"; }\n\n.fa-toilet:before {\n  content: \"\\f7d8\"; }\n\n.fa-toilet-paper:before {\n  content: \"\\f71e\"; }\n\n.fa-toolbox:before {\n  content: \"\\f552\"; }\n\n.fa-tools:before {\n  content: \"\\f7d9\"; }\n\n.fa-tooth:before {\n  content: \"\\f5c9\"; }\n\n.fa-torah:before {\n  content: \"\\f6a0\"; }\n\n.fa-torii-gate:before {\n  content: \"\\f6a1\"; }\n\n.fa-tractor:before {\n  content: \"\\f722\"; }\n\n.fa-trade-federation:before {\n  content: \"\\f513\"; }\n\n.fa-trademark:before {\n  content: \"\\f25c\"; }\n\n.fa-traffic-light:before {\n  content: \"\\f637\"; }\n\n.fa-train:before {\n  content: \"\\f238\"; }\n\n.fa-tram:before {\n  content: \"\\f7da\"; }\n\n.fa-transgender:before {\n  content: \"\\f224\"; }\n\n.fa-transgender-alt:before {\n  content: \"\\f225\"; }\n\n.fa-trash:before {\n  content: \"\\f1f8\"; }\n\n.fa-trash-alt:before {\n  content: \"\\f2ed\"; }\n\n.fa-trash-restore:before {\n  content: \"\\f829\"; }\n\n.fa-trash-restore-alt:before {\n  content: \"\\f82a\"; }\n\n.fa-tree:before {\n  content: \"\\f1bb\"; }\n\n.fa-trello:before {\n  content: \"\\f181\"; }\n\n.fa-tripadvisor:before {\n  content: \"\\f262\"; }\n\n.fa-trophy:before {\n  content: \"\\f091\"; }\n\n.fa-truck:before {\n  content: \"\\f0d1\"; }\n\n.fa-truck-loading:before {\n  content: \"\\f4de\"; }\n\n.fa-truck-monster:before {\n  content: \"\\f63b\"; }\n\n.fa-truck-moving:before {\n  content: \"\\f4df\"; }\n\n.fa-truck-pickup:before {\n  content: \"\\f63c\"; }\n\n.fa-tshirt:before {\n  content: \"\\f553\"; }\n\n.fa-tty:before {\n  content: \"\\f1e4\"; }\n\n.fa-tumblr:before {\n  content: \"\\f173\"; }\n\n.fa-tumblr-square:before {\n  content: \"\\f174\"; }\n\n.fa-tv:before {\n  content: \"\\f26c\"; }\n\n.fa-twitch:before {\n  content: \"\\f1e8\"; }\n\n.fa-twitter:before {\n  content: \"\\f099\"; }\n\n.fa-twitter-square:before {\n  content: \"\\f081\"; }\n\n.fa-typo3:before {\n  content: \"\\f42b\"; }\n\n.fa-uber:before {\n  content: \"\\f402\"; }\n\n.fa-ubuntu:before {\n  content: \"\\f7df\"; }\n\n.fa-uikit:before {\n  content: \"\\f403\"; }\n\n.fa-umbrella:before {\n  content: \"\\f0e9\"; }\n\n.fa-umbrella-beach:before {\n  content: \"\\f5ca\"; }\n\n.fa-underline:before {\n  content: \"\\f0cd\"; }\n\n.fa-undo:before {\n  content: \"\\f0e2\"; }\n\n.fa-undo-alt:before {\n  content: \"\\f2ea\"; }\n\n.fa-uniregistry:before {\n  content: \"\\f404\"; }\n\n.fa-universal-access:before {\n  content: \"\\f29a\"; }\n\n.fa-university:before {\n  content: \"\\f19c\"; }\n\n.fa-unlink:before {\n  content: \"\\f127\"; }\n\n.fa-unlock:before {\n  content: \"\\f09c\"; }\n\n.fa-unlock-alt:before {\n  content: \"\\f13e\"; }\n\n.fa-untappd:before {\n  content: \"\\f405\"; }\n\n.fa-upload:before {\n  content: \"\\f093\"; }\n\n.fa-ups:before {\n  content: \"\\f7e0\"; }\n\n.fa-usb:before {\n  content: \"\\f287\"; }\n\n.fa-user:before {\n  content: \"\\f007\"; }\n\n.fa-user-alt:before {\n  content: \"\\f406\"; }\n\n.fa-user-alt-slash:before {\n  content: \"\\f4fa\"; }\n\n.fa-user-astronaut:before {\n  content: \"\\f4fb\"; }\n\n.fa-user-check:before {\n  content: \"\\f4fc\"; }\n\n.fa-user-circle:before {\n  content: \"\\f2bd\"; }\n\n.fa-user-clock:before {\n  content: \"\\f4fd\"; }\n\n.fa-user-cog:before {\n  content: \"\\f4fe\"; }\n\n.fa-user-edit:before {\n  content: \"\\f4ff\"; }\n\n.fa-user-friends:before {\n  content: \"\\f500\"; }\n\n.fa-user-graduate:before {\n  content: \"\\f501\"; }\n\n.fa-user-injured:before {\n  content: \"\\f728\"; }\n\n.fa-user-lock:before {\n  content: \"\\f502\"; }\n\n.fa-user-md:before {\n  content: \"\\f0f0\"; }\n\n.fa-user-minus:before {\n  content: \"\\f503\"; }\n\n.fa-user-ninja:before {\n  content: \"\\f504\"; }\n\n.fa-user-nurse:before {\n  content: \"\\f82f\"; }\n\n.fa-user-plus:before {\n  content: \"\\f234\"; }\n\n.fa-user-secret:before {\n  content: \"\\f21b\"; }\n\n.fa-user-shield:before {\n  content: \"\\f505\"; }\n\n.fa-user-slash:before {\n  content: \"\\f506\"; }\n\n.fa-user-tag:before {\n  content: \"\\f507\"; }\n\n.fa-user-tie:before {\n  content: \"\\f508\"; }\n\n.fa-user-times:before {\n  content: \"\\f235\"; }\n\n.fa-users:before {\n  content: \"\\f0c0\"; }\n\n.fa-users-cog:before {\n  content: \"\\f509\"; }\n\n.fa-usps:before {\n  content: \"\\f7e1\"; }\n\n.fa-ussunnah:before {\n  content: \"\\f407\"; }\n\n.fa-utensil-spoon:before {\n  content: \"\\f2e5\"; }\n\n.fa-utensils:before {\n  content: \"\\f2e7\"; }\n\n.fa-vaadin:before {\n  content: \"\\f408\"; }\n\n.fa-vector-square:before {\n  content: \"\\f5cb\"; }\n\n.fa-venus:before {\n  content: \"\\f221\"; }\n\n.fa-venus-double:before {\n  content: \"\\f226\"; }\n\n.fa-venus-mars:before {\n  content: \"\\f228\"; }\n\n.fa-viacoin:before {\n  content: \"\\f237\"; }\n\n.fa-viadeo:before {\n  content: \"\\f2a9\"; }\n\n.fa-viadeo-square:before {\n  content: \"\\f2aa\"; }\n\n.fa-vial:before {\n  content: \"\\f492\"; }\n\n.fa-vials:before {\n  content: \"\\f493\"; }\n\n.fa-viber:before {\n  content: \"\\f409\"; }\n\n.fa-video:before {\n  content: \"\\f03d\"; }\n\n.fa-video-slash:before {\n  content: \"\\f4e2\"; }\n\n.fa-vihara:before {\n  content: \"\\f6a7\"; }\n\n.fa-vimeo:before {\n  content: \"\\f40a\"; }\n\n.fa-vimeo-square:before {\n  content: \"\\f194\"; }\n\n.fa-vimeo-v:before {\n  content: \"\\f27d\"; }\n\n.fa-vine:before {\n  content: \"\\f1ca\"; }\n\n.fa-vk:before {\n  content: \"\\f189\"; }\n\n.fa-vnv:before {\n  content: \"\\f40b\"; }\n\n.fa-voicemail:before {\n  content: \"\\f897\"; }\n\n.fa-volleyball-ball:before {\n  content: \"\\f45f\"; }\n\n.fa-volume-down:before {\n  content: \"\\f027\"; }\n\n.fa-volume-mute:before {\n  content: \"\\f6a9\"; }\n\n.fa-volume-off:before {\n  content: \"\\f026\"; }\n\n.fa-volume-up:before {\n  content: \"\\f028\"; }\n\n.fa-vote-yea:before {\n  content: \"\\f772\"; }\n\n.fa-vr-cardboard:before {\n  content: \"\\f729\"; }\n\n.fa-vuejs:before {\n  content: \"\\f41f\"; }\n\n.fa-walking:before {\n  content: \"\\f554\"; }\n\n.fa-wallet:before {\n  content: \"\\f555\"; }\n\n.fa-warehouse:before {\n  content: \"\\f494\"; }\n\n.fa-water:before {\n  content: \"\\f773\"; }\n\n.fa-wave-square:before {\n  content: \"\\f83e\"; }\n\n.fa-waze:before {\n  content: \"\\f83f\"; }\n\n.fa-weebly:before {\n  content: \"\\f5cc\"; }\n\n.fa-weibo:before {\n  content: \"\\f18a\"; }\n\n.fa-weight:before {\n  content: \"\\f496\"; }\n\n.fa-weight-hanging:before {\n  content: \"\\f5cd\"; }\n\n.fa-weixin:before {\n  content: \"\\f1d7\"; }\n\n.fa-whatsapp:before {\n  content: \"\\f232\"; }\n\n.fa-whatsapp-square:before {\n  content: \"\\f40c\"; }\n\n.fa-wheelchair:before {\n  content: \"\\f193\"; }\n\n.fa-whmcs:before {\n  content: \"\\f40d\"; }\n\n.fa-wifi:before {\n  content: \"\\f1eb\"; }\n\n.fa-wikipedia-w:before {\n  content: \"\\f266\"; }\n\n.fa-wind:before {\n  content: \"\\f72e\"; }\n\n.fa-window-close:before {\n  content: \"\\f410\"; }\n\n.fa-window-maximize:before {\n  content: \"\\f2d0\"; }\n\n.fa-window-minimize:before {\n  content: \"\\f2d1\"; }\n\n.fa-window-restore:before {\n  content: \"\\f2d2\"; }\n\n.fa-windows:before {\n  content: \"\\f17a\"; }\n\n.fa-wine-bottle:before {\n  content: \"\\f72f\"; }\n\n.fa-wine-glass:before {\n  content: \"\\f4e3\"; }\n\n.fa-wine-glass-alt:before {\n  content: \"\\f5ce\"; }\n\n.fa-wix:before {\n  content: \"\\f5cf\"; }\n\n.fa-wizards-of-the-coast:before {\n  content: \"\\f730\"; }\n\n.fa-wolf-pack-battalion:before {\n  content: \"\\f514\"; }\n\n.fa-won-sign:before {\n  content: \"\\f159\"; }\n\n.fa-wordpress:before {\n  content: \"\\f19a\"; }\n\n.fa-wordpress-simple:before {\n  content: \"\\f411\"; }\n\n.fa-wpbeginner:before {\n  content: \"\\f297\"; }\n\n.fa-wpexplorer:before {\n  content: \"\\f2de\"; }\n\n.fa-wpforms:before {\n  content: \"\\f298\"; }\n\n.fa-wpressr:before {\n  content: \"\\f3e4\"; }\n\n.fa-wrench:before {\n  content: \"\\f0ad\"; }\n\n.fa-x-ray:before {\n  content: \"\\f497\"; }\n\n.fa-xbox:before {\n  content: \"\\f412\"; }\n\n.fa-xing:before {\n  content: \"\\f168\"; }\n\n.fa-xing-square:before {\n  content: \"\\f169\"; }\n\n.fa-y-combinator:before {\n  content: \"\\f23b\"; }\n\n.fa-yahoo:before {\n  content: \"\\f19e\"; }\n\n.fa-yammer:before {\n  content: \"\\f840\"; }\n\n.fa-yandex:before {\n  content: \"\\f413\"; }\n\n.fa-yandex-international:before {\n  content: \"\\f414\"; }\n\n.fa-yarn:before {\n  content: \"\\f7e3\"; }\n\n.fa-yelp:before {\n  content: \"\\f1e9\"; }\n\n.fa-yen-sign:before {\n  content: \"\\f157\"; }\n\n.fa-yin-yang:before {\n  content: \"\\f6ad\"; }\n\n.fa-yoast:before {\n  content: \"\\f2b1\"; }\n\n.fa-youtube:before {\n  content: \"\\f167\"; }\n\n.fa-youtube-square:before {\n  content: \"\\f431\"; }\n\n.fa-zhihu:before {\n  content: \"\\f63f\"; }\n\n.sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px; }\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  clip: auto;\n  height: auto;\n  margin: 0;\n  overflow: visible;\n  position: static;\n  width: auto; }\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: auto;\n  src: url(\"../webfonts/fa-brands-400.eot\");\n  src: url(\"../webfonts/fa-brands-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-brands-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-brands-400.woff\") format(\"woff\"), url(\"../webfonts/fa-brands-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-brands-400.svg#fontawesome\") format(\"svg\"); }\n\n.fab {\n  font-family: 'Font Awesome 5 Brands'; }\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: auto;\n  src: url(\"../webfonts/fa-regular-400.eot\");\n  src: url(\"../webfonts/fa-regular-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-regular-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-regular-400.woff\") format(\"woff\"), url(\"../webfonts/fa-regular-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-regular-400.svg#fontawesome\") format(\"svg\"); }\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: auto;\n  src: url(\"../webfonts/fa-solid-900.eot\");\n  src: url(\"../webfonts/fa-solid-900.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-solid-900.woff2\") format(\"woff2\"), url(\"../webfonts/fa-solid-900.woff\") format(\"woff\"), url(\"../webfonts/fa-solid-900.ttf\") format(\"truetype\"), url(\"../webfonts/fa-solid-900.svg#fontawesome\") format(\"svg\"); }\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/brands.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: auto;\n  src: url(\"../webfonts/fa-brands-400.eot\");\n  src: url(\"../webfonts/fa-brands-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-brands-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-brands-400.woff\") format(\"woff\"), url(\"../webfonts/fa-brands-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-brands-400.svg#fontawesome\") format(\"svg\"); }\n\n.fab {\n  font-family: 'Font Awesome 5 Brands'; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/fontawesome.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n.fa,\n.fas,\n.far,\n.fal,\n.fad,\n.fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1; }\n\n.fa-lg {\n  font-size: 1.33333em;\n  line-height: 0.75em;\n  vertical-align: -.0667em; }\n\n.fa-xs {\n  font-size: .75em; }\n\n.fa-sm {\n  font-size: .875em; }\n\n.fa-1x {\n  font-size: 1em; }\n\n.fa-2x {\n  font-size: 2em; }\n\n.fa-3x {\n  font-size: 3em; }\n\n.fa-4x {\n  font-size: 4em; }\n\n.fa-5x {\n  font-size: 5em; }\n\n.fa-6x {\n  font-size: 6em; }\n\n.fa-7x {\n  font-size: 7em; }\n\n.fa-8x {\n  font-size: 8em; }\n\n.fa-9x {\n  font-size: 9em; }\n\n.fa-10x {\n  font-size: 10em; }\n\n.fa-fw {\n  text-align: center;\n  width: 1.25em; }\n\n.fa-ul {\n  list-style-type: none;\n  margin-left: 2.5em;\n  padding-left: 0; }\n  .fa-ul > li {\n    position: relative; }\n\n.fa-li {\n  left: -2em;\n  position: absolute;\n  text-align: center;\n  width: 2em;\n  line-height: inherit; }\n\n.fa-border {\n  border: solid 0.08em #eee;\n  border-radius: .1em;\n  padding: .2em .25em .15em; }\n\n.fa-pull-left {\n  float: left; }\n\n.fa-pull-right {\n  float: right; }\n\n.fa.fa-pull-left,\n.fas.fa-pull-left,\n.far.fa-pull-left,\n.fal.fa-pull-left,\n.fab.fa-pull-left {\n  margin-right: .3em; }\n\n.fa.fa-pull-right,\n.fas.fa-pull-right,\n.far.fa-pull-right,\n.fal.fa-pull-right,\n.fab.fa-pull-right {\n  margin-left: .3em; }\n\n.fa-spin {\n  -webkit-animation: fa-spin 2s infinite linear;\n          animation: fa-spin 2s infinite linear; }\n\n.fa-pulse {\n  -webkit-animation: fa-spin 1s infinite steps(8);\n          animation: fa-spin 1s infinite steps(8); }\n\n@-webkit-keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n@keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n.fa-rotate-90 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)\";\n  -webkit-transform: rotate(90deg);\n          transform: rotate(90deg); }\n\n.fa-rotate-180 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)\";\n  -webkit-transform: rotate(180deg);\n          transform: rotate(180deg); }\n\n.fa-rotate-270 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)\";\n  -webkit-transform: rotate(270deg);\n          transform: rotate(270deg); }\n\n.fa-flip-horizontal {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)\";\n  -webkit-transform: scale(-1, 1);\n          transform: scale(-1, 1); }\n\n.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(1, -1);\n          transform: scale(1, -1); }\n\n.fa-flip-both, .fa-flip-horizontal.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(-1, -1);\n          transform: scale(-1, -1); }\n\n:root .fa-rotate-90,\n:root .fa-rotate-180,\n:root .fa-rotate-270,\n:root .fa-flip-horizontal,\n:root .fa-flip-vertical,\n:root .fa-flip-both {\n  -webkit-filter: none;\n          filter: none; }\n\n.fa-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: 2.5em; }\n\n.fa-stack-1x,\n.fa-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%; }\n\n.fa-stack-1x {\n  line-height: inherit; }\n\n.fa-stack-2x {\n  font-size: 2em; }\n\n.fa-inverse {\n  color: #fff; }\n\n/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\nreaders do not read off random characters that represent icons */\n.fa-500px:before {\n  content: \"\\f26e\"; }\n\n.fa-accessible-icon:before {\n  content: \"\\f368\"; }\n\n.fa-accusoft:before {\n  content: \"\\f369\"; }\n\n.fa-acquisitions-incorporated:before {\n  content: \"\\f6af\"; }\n\n.fa-ad:before {\n  content: \"\\f641\"; }\n\n.fa-address-book:before {\n  content: \"\\f2b9\"; }\n\n.fa-address-card:before {\n  content: \"\\f2bb\"; }\n\n.fa-adjust:before {\n  content: \"\\f042\"; }\n\n.fa-adn:before {\n  content: \"\\f170\"; }\n\n.fa-adobe:before {\n  content: \"\\f778\"; }\n\n.fa-adversal:before {\n  content: \"\\f36a\"; }\n\n.fa-affiliatetheme:before {\n  content: \"\\f36b\"; }\n\n.fa-air-freshener:before {\n  content: \"\\f5d0\"; }\n\n.fa-airbnb:before {\n  content: \"\\f834\"; }\n\n.fa-algolia:before {\n  content: \"\\f36c\"; }\n\n.fa-align-center:before {\n  content: \"\\f037\"; }\n\n.fa-align-justify:before {\n  content: \"\\f039\"; }\n\n.fa-align-left:before {\n  content: \"\\f036\"; }\n\n.fa-align-right:before {\n  content: \"\\f038\"; }\n\n.fa-alipay:before {\n  content: \"\\f642\"; }\n\n.fa-allergies:before {\n  content: \"\\f461\"; }\n\n.fa-amazon:before {\n  content: \"\\f270\"; }\n\n.fa-amazon-pay:before {\n  content: \"\\f42c\"; }\n\n.fa-ambulance:before {\n  content: \"\\f0f9\"; }\n\n.fa-american-sign-language-interpreting:before {\n  content: \"\\f2a3\"; }\n\n.fa-amilia:before {\n  content: \"\\f36d\"; }\n\n.fa-anchor:before {\n  content: \"\\f13d\"; }\n\n.fa-android:before {\n  content: \"\\f17b\"; }\n\n.fa-angellist:before {\n  content: \"\\f209\"; }\n\n.fa-angle-double-down:before {\n  content: \"\\f103\"; }\n\n.fa-angle-double-left:before {\n  content: \"\\f100\"; }\n\n.fa-angle-double-right:before {\n  content: \"\\f101\"; }\n\n.fa-angle-double-up:before {\n  content: \"\\f102\"; }\n\n.fa-angle-down:before {\n  content: \"\\f107\"; }\n\n.fa-angle-left:before {\n  content: \"\\f104\"; }\n\n.fa-angle-right:before {\n  content: \"\\f105\"; }\n\n.fa-angle-up:before {\n  content: \"\\f106\"; }\n\n.fa-angry:before {\n  content: \"\\f556\"; }\n\n.fa-angrycreative:before {\n  content: \"\\f36e\"; }\n\n.fa-angular:before {\n  content: \"\\f420\"; }\n\n.fa-ankh:before {\n  content: \"\\f644\"; }\n\n.fa-app-store:before {\n  content: \"\\f36f\"; }\n\n.fa-app-store-ios:before {\n  content: \"\\f370\"; }\n\n.fa-apper:before {\n  content: \"\\f371\"; }\n\n.fa-apple:before {\n  content: \"\\f179\"; }\n\n.fa-apple-alt:before {\n  content: \"\\f5d1\"; }\n\n.fa-apple-pay:before {\n  content: \"\\f415\"; }\n\n.fa-archive:before {\n  content: \"\\f187\"; }\n\n.fa-archway:before {\n  content: \"\\f557\"; }\n\n.fa-arrow-alt-circle-down:before {\n  content: \"\\f358\"; }\n\n.fa-arrow-alt-circle-left:before {\n  content: \"\\f359\"; }\n\n.fa-arrow-alt-circle-right:before {\n  content: \"\\f35a\"; }\n\n.fa-arrow-alt-circle-up:before {\n  content: \"\\f35b\"; }\n\n.fa-arrow-circle-down:before {\n  content: \"\\f0ab\"; }\n\n.fa-arrow-circle-left:before {\n  content: \"\\f0a8\"; }\n\n.fa-arrow-circle-right:before {\n  content: \"\\f0a9\"; }\n\n.fa-arrow-circle-up:before {\n  content: \"\\f0aa\"; }\n\n.fa-arrow-down:before {\n  content: \"\\f063\"; }\n\n.fa-arrow-left:before {\n  content: \"\\f060\"; }\n\n.fa-arrow-right:before {\n  content: \"\\f061\"; }\n\n.fa-arrow-up:before {\n  content: \"\\f062\"; }\n\n.fa-arrows-alt:before {\n  content: \"\\f0b2\"; }\n\n.fa-arrows-alt-h:before {\n  content: \"\\f337\"; }\n\n.fa-arrows-alt-v:before {\n  content: \"\\f338\"; }\n\n.fa-artstation:before {\n  content: \"\\f77a\"; }\n\n.fa-assistive-listening-systems:before {\n  content: \"\\f2a2\"; }\n\n.fa-asterisk:before {\n  content: \"\\f069\"; }\n\n.fa-asymmetrik:before {\n  content: \"\\f372\"; }\n\n.fa-at:before {\n  content: \"\\f1fa\"; }\n\n.fa-atlas:before {\n  content: \"\\f558\"; }\n\n.fa-atlassian:before {\n  content: \"\\f77b\"; }\n\n.fa-atom:before {\n  content: \"\\f5d2\"; }\n\n.fa-audible:before {\n  content: \"\\f373\"; }\n\n.fa-audio-description:before {\n  content: \"\\f29e\"; }\n\n.fa-autoprefixer:before {\n  content: \"\\f41c\"; }\n\n.fa-avianex:before {\n  content: \"\\f374\"; }\n\n.fa-aviato:before {\n  content: \"\\f421\"; }\n\n.fa-award:before {\n  content: \"\\f559\"; }\n\n.fa-aws:before {\n  content: \"\\f375\"; }\n\n.fa-baby:before {\n  content: \"\\f77c\"; }\n\n.fa-baby-carriage:before {\n  content: \"\\f77d\"; }\n\n.fa-backspace:before {\n  content: \"\\f55a\"; }\n\n.fa-backward:before {\n  content: \"\\f04a\"; }\n\n.fa-bacon:before {\n  content: \"\\f7e5\"; }\n\n.fa-balance-scale:before {\n  content: \"\\f24e\"; }\n\n.fa-balance-scale-left:before {\n  content: \"\\f515\"; }\n\n.fa-balance-scale-right:before {\n  content: \"\\f516\"; }\n\n.fa-ban:before {\n  content: \"\\f05e\"; }\n\n.fa-band-aid:before {\n  content: \"\\f462\"; }\n\n.fa-bandcamp:before {\n  content: \"\\f2d5\"; }\n\n.fa-barcode:before {\n  content: \"\\f02a\"; }\n\n.fa-bars:before {\n  content: \"\\f0c9\"; }\n\n.fa-baseball-ball:before {\n  content: \"\\f433\"; }\n\n.fa-basketball-ball:before {\n  content: \"\\f434\"; }\n\n.fa-bath:before {\n  content: \"\\f2cd\"; }\n\n.fa-battery-empty:before {\n  content: \"\\f244\"; }\n\n.fa-battery-full:before {\n  content: \"\\f240\"; }\n\n.fa-battery-half:before {\n  content: \"\\f242\"; }\n\n.fa-battery-quarter:before {\n  content: \"\\f243\"; }\n\n.fa-battery-three-quarters:before {\n  content: \"\\f241\"; }\n\n.fa-battle-net:before {\n  content: \"\\f835\"; }\n\n.fa-bed:before {\n  content: \"\\f236\"; }\n\n.fa-beer:before {\n  content: \"\\f0fc\"; }\n\n.fa-behance:before {\n  content: \"\\f1b4\"; }\n\n.fa-behance-square:before {\n  content: \"\\f1b5\"; }\n\n.fa-bell:before {\n  content: \"\\f0f3\"; }\n\n.fa-bell-slash:before {\n  content: \"\\f1f6\"; }\n\n.fa-bezier-curve:before {\n  content: \"\\f55b\"; }\n\n.fa-bible:before {\n  content: \"\\f647\"; }\n\n.fa-bicycle:before {\n  content: \"\\f206\"; }\n\n.fa-biking:before {\n  content: \"\\f84a\"; }\n\n.fa-bimobject:before {\n  content: \"\\f378\"; }\n\n.fa-binoculars:before {\n  content: \"\\f1e5\"; }\n\n.fa-biohazard:before {\n  content: \"\\f780\"; }\n\n.fa-birthday-cake:before {\n  content: \"\\f1fd\"; }\n\n.fa-bitbucket:before {\n  content: \"\\f171\"; }\n\n.fa-bitcoin:before {\n  content: \"\\f379\"; }\n\n.fa-bity:before {\n  content: \"\\f37a\"; }\n\n.fa-black-tie:before {\n  content: \"\\f27e\"; }\n\n.fa-blackberry:before {\n  content: \"\\f37b\"; }\n\n.fa-blender:before {\n  content: \"\\f517\"; }\n\n.fa-blender-phone:before {\n  content: \"\\f6b6\"; }\n\n.fa-blind:before {\n  content: \"\\f29d\"; }\n\n.fa-blog:before {\n  content: \"\\f781\"; }\n\n.fa-blogger:before {\n  content: \"\\f37c\"; }\n\n.fa-blogger-b:before {\n  content: \"\\f37d\"; }\n\n.fa-bluetooth:before {\n  content: \"\\f293\"; }\n\n.fa-bluetooth-b:before {\n  content: \"\\f294\"; }\n\n.fa-bold:before {\n  content: \"\\f032\"; }\n\n.fa-bolt:before {\n  content: \"\\f0e7\"; }\n\n.fa-bomb:before {\n  content: \"\\f1e2\"; }\n\n.fa-bone:before {\n  content: \"\\f5d7\"; }\n\n.fa-bong:before {\n  content: \"\\f55c\"; }\n\n.fa-book:before {\n  content: \"\\f02d\"; }\n\n.fa-book-dead:before {\n  content: \"\\f6b7\"; }\n\n.fa-book-medical:before {\n  content: \"\\f7e6\"; }\n\n.fa-book-open:before {\n  content: \"\\f518\"; }\n\n.fa-book-reader:before {\n  content: \"\\f5da\"; }\n\n.fa-bookmark:before {\n  content: \"\\f02e\"; }\n\n.fa-bootstrap:before {\n  content: \"\\f836\"; }\n\n.fa-border-all:before {\n  content: \"\\f84c\"; }\n\n.fa-border-none:before {\n  content: \"\\f850\"; }\n\n.fa-border-style:before {\n  content: \"\\f853\"; }\n\n.fa-bowling-ball:before {\n  content: \"\\f436\"; }\n\n.fa-box:before {\n  content: \"\\f466\"; }\n\n.fa-box-open:before {\n  content: \"\\f49e\"; }\n\n.fa-boxes:before {\n  content: \"\\f468\"; }\n\n.fa-braille:before {\n  content: \"\\f2a1\"; }\n\n.fa-brain:before {\n  content: \"\\f5dc\"; }\n\n.fa-bread-slice:before {\n  content: \"\\f7ec\"; }\n\n.fa-briefcase:before {\n  content: \"\\f0b1\"; }\n\n.fa-briefcase-medical:before {\n  content: \"\\f469\"; }\n\n.fa-broadcast-tower:before {\n  content: \"\\f519\"; }\n\n.fa-broom:before {\n  content: \"\\f51a\"; }\n\n.fa-brush:before {\n  content: \"\\f55d\"; }\n\n.fa-btc:before {\n  content: \"\\f15a\"; }\n\n.fa-buffer:before {\n  content: \"\\f837\"; }\n\n.fa-bug:before {\n  content: \"\\f188\"; }\n\n.fa-building:before {\n  content: \"\\f1ad\"; }\n\n.fa-bullhorn:before {\n  content: \"\\f0a1\"; }\n\n.fa-bullseye:before {\n  content: \"\\f140\"; }\n\n.fa-burn:before {\n  content: \"\\f46a\"; }\n\n.fa-buromobelexperte:before {\n  content: \"\\f37f\"; }\n\n.fa-bus:before {\n  content: \"\\f207\"; }\n\n.fa-bus-alt:before {\n  content: \"\\f55e\"; }\n\n.fa-business-time:before {\n  content: \"\\f64a\"; }\n\n.fa-buysellads:before {\n  content: \"\\f20d\"; }\n\n.fa-calculator:before {\n  content: \"\\f1ec\"; }\n\n.fa-calendar:before {\n  content: \"\\f133\"; }\n\n.fa-calendar-alt:before {\n  content: \"\\f073\"; }\n\n.fa-calendar-check:before {\n  content: \"\\f274\"; }\n\n.fa-calendar-day:before {\n  content: \"\\f783\"; }\n\n.fa-calendar-minus:before {\n  content: \"\\f272\"; }\n\n.fa-calendar-plus:before {\n  content: \"\\f271\"; }\n\n.fa-calendar-times:before {\n  content: \"\\f273\"; }\n\n.fa-calendar-week:before {\n  content: \"\\f784\"; }\n\n.fa-camera:before {\n  content: \"\\f030\"; }\n\n.fa-camera-retro:before {\n  content: \"\\f083\"; }\n\n.fa-campground:before {\n  content: \"\\f6bb\"; }\n\n.fa-canadian-maple-leaf:before {\n  content: \"\\f785\"; }\n\n.fa-candy-cane:before {\n  content: \"\\f786\"; }\n\n.fa-cannabis:before {\n  content: \"\\f55f\"; }\n\n.fa-capsules:before {\n  content: \"\\f46b\"; }\n\n.fa-car:before {\n  content: \"\\f1b9\"; }\n\n.fa-car-alt:before {\n  content: \"\\f5de\"; }\n\n.fa-car-battery:before {\n  content: \"\\f5df\"; }\n\n.fa-car-crash:before {\n  content: \"\\f5e1\"; }\n\n.fa-car-side:before {\n  content: \"\\f5e4\"; }\n\n.fa-caret-down:before {\n  content: \"\\f0d7\"; }\n\n.fa-caret-left:before {\n  content: \"\\f0d9\"; }\n\n.fa-caret-right:before {\n  content: \"\\f0da\"; }\n\n.fa-caret-square-down:before {\n  content: \"\\f150\"; }\n\n.fa-caret-square-left:before {\n  content: \"\\f191\"; }\n\n.fa-caret-square-right:before {\n  content: \"\\f152\"; }\n\n.fa-caret-square-up:before {\n  content: \"\\f151\"; }\n\n.fa-caret-up:before {\n  content: \"\\f0d8\"; }\n\n.fa-carrot:before {\n  content: \"\\f787\"; }\n\n.fa-cart-arrow-down:before {\n  content: \"\\f218\"; }\n\n.fa-cart-plus:before {\n  content: \"\\f217\"; }\n\n.fa-cash-register:before {\n  content: \"\\f788\"; }\n\n.fa-cat:before {\n  content: \"\\f6be\"; }\n\n.fa-cc-amazon-pay:before {\n  content: \"\\f42d\"; }\n\n.fa-cc-amex:before {\n  content: \"\\f1f3\"; }\n\n.fa-cc-apple-pay:before {\n  content: \"\\f416\"; }\n\n.fa-cc-diners-club:before {\n  content: \"\\f24c\"; }\n\n.fa-cc-discover:before {\n  content: \"\\f1f2\"; }\n\n.fa-cc-jcb:before {\n  content: \"\\f24b\"; }\n\n.fa-cc-mastercard:before {\n  content: \"\\f1f1\"; }\n\n.fa-cc-paypal:before {\n  content: \"\\f1f4\"; }\n\n.fa-cc-stripe:before {\n  content: \"\\f1f5\"; }\n\n.fa-cc-visa:before {\n  content: \"\\f1f0\"; }\n\n.fa-centercode:before {\n  content: \"\\f380\"; }\n\n.fa-centos:before {\n  content: \"\\f789\"; }\n\n.fa-certificate:before {\n  content: \"\\f0a3\"; }\n\n.fa-chair:before {\n  content: \"\\f6c0\"; }\n\n.fa-chalkboard:before {\n  content: \"\\f51b\"; }\n\n.fa-chalkboard-teacher:before {\n  content: \"\\f51c\"; }\n\n.fa-charging-station:before {\n  content: \"\\f5e7\"; }\n\n.fa-chart-area:before {\n  content: \"\\f1fe\"; }\n\n.fa-chart-bar:before {\n  content: \"\\f080\"; }\n\n.fa-chart-line:before {\n  content: \"\\f201\"; }\n\n.fa-chart-pie:before {\n  content: \"\\f200\"; }\n\n.fa-check:before {\n  content: \"\\f00c\"; }\n\n.fa-check-circle:before {\n  content: \"\\f058\"; }\n\n.fa-check-double:before {\n  content: \"\\f560\"; }\n\n.fa-check-square:before {\n  content: \"\\f14a\"; }\n\n.fa-cheese:before {\n  content: \"\\f7ef\"; }\n\n.fa-chess:before {\n  content: \"\\f439\"; }\n\n.fa-chess-bishop:before {\n  content: \"\\f43a\"; }\n\n.fa-chess-board:before {\n  content: \"\\f43c\"; }\n\n.fa-chess-king:before {\n  content: \"\\f43f\"; }\n\n.fa-chess-knight:before {\n  content: \"\\f441\"; }\n\n.fa-chess-pawn:before {\n  content: \"\\f443\"; }\n\n.fa-chess-queen:before {\n  content: \"\\f445\"; }\n\n.fa-chess-rook:before {\n  content: \"\\f447\"; }\n\n.fa-chevron-circle-down:before {\n  content: \"\\f13a\"; }\n\n.fa-chevron-circle-left:before {\n  content: \"\\f137\"; }\n\n.fa-chevron-circle-right:before {\n  content: \"\\f138\"; }\n\n.fa-chevron-circle-up:before {\n  content: \"\\f139\"; }\n\n.fa-chevron-down:before {\n  content: \"\\f078\"; }\n\n.fa-chevron-left:before {\n  content: \"\\f053\"; }\n\n.fa-chevron-right:before {\n  content: \"\\f054\"; }\n\n.fa-chevron-up:before {\n  content: \"\\f077\"; }\n\n.fa-child:before {\n  content: \"\\f1ae\"; }\n\n.fa-chrome:before {\n  content: \"\\f268\"; }\n\n.fa-chromecast:before {\n  content: \"\\f838\"; }\n\n.fa-church:before {\n  content: \"\\f51d\"; }\n\n.fa-circle:before {\n  content: \"\\f111\"; }\n\n.fa-circle-notch:before {\n  content: \"\\f1ce\"; }\n\n.fa-city:before {\n  content: \"\\f64f\"; }\n\n.fa-clinic-medical:before {\n  content: \"\\f7f2\"; }\n\n.fa-clipboard:before {\n  content: \"\\f328\"; }\n\n.fa-clipboard-check:before {\n  content: \"\\f46c\"; }\n\n.fa-clipboard-list:before {\n  content: \"\\f46d\"; }\n\n.fa-clock:before {\n  content: \"\\f017\"; }\n\n.fa-clone:before {\n  content: \"\\f24d\"; }\n\n.fa-closed-captioning:before {\n  content: \"\\f20a\"; }\n\n.fa-cloud:before {\n  content: \"\\f0c2\"; }\n\n.fa-cloud-download-alt:before {\n  content: \"\\f381\"; }\n\n.fa-cloud-meatball:before {\n  content: \"\\f73b\"; }\n\n.fa-cloud-moon:before {\n  content: \"\\f6c3\"; }\n\n.fa-cloud-moon-rain:before {\n  content: \"\\f73c\"; }\n\n.fa-cloud-rain:before {\n  content: \"\\f73d\"; }\n\n.fa-cloud-showers-heavy:before {\n  content: \"\\f740\"; }\n\n.fa-cloud-sun:before {\n  content: \"\\f6c4\"; }\n\n.fa-cloud-sun-rain:before {\n  content: \"\\f743\"; }\n\n.fa-cloud-upload-alt:before {\n  content: \"\\f382\"; }\n\n.fa-cloudscale:before {\n  content: \"\\f383\"; }\n\n.fa-cloudsmith:before {\n  content: \"\\f384\"; }\n\n.fa-cloudversify:before {\n  content: \"\\f385\"; }\n\n.fa-cocktail:before {\n  content: \"\\f561\"; }\n\n.fa-code:before {\n  content: \"\\f121\"; }\n\n.fa-code-branch:before {\n  content: \"\\f126\"; }\n\n.fa-codepen:before {\n  content: \"\\f1cb\"; }\n\n.fa-codiepie:before {\n  content: \"\\f284\"; }\n\n.fa-coffee:before {\n  content: \"\\f0f4\"; }\n\n.fa-cog:before {\n  content: \"\\f013\"; }\n\n.fa-cogs:before {\n  content: \"\\f085\"; }\n\n.fa-coins:before {\n  content: \"\\f51e\"; }\n\n.fa-columns:before {\n  content: \"\\f0db\"; }\n\n.fa-comment:before {\n  content: \"\\f075\"; }\n\n.fa-comment-alt:before {\n  content: \"\\f27a\"; }\n\n.fa-comment-dollar:before {\n  content: \"\\f651\"; }\n\n.fa-comment-dots:before {\n  content: \"\\f4ad\"; }\n\n.fa-comment-medical:before {\n  content: \"\\f7f5\"; }\n\n.fa-comment-slash:before {\n  content: \"\\f4b3\"; }\n\n.fa-comments:before {\n  content: \"\\f086\"; }\n\n.fa-comments-dollar:before {\n  content: \"\\f653\"; }\n\n.fa-compact-disc:before {\n  content: \"\\f51f\"; }\n\n.fa-compass:before {\n  content: \"\\f14e\"; }\n\n.fa-compress:before {\n  content: \"\\f066\"; }\n\n.fa-compress-arrows-alt:before {\n  content: \"\\f78c\"; }\n\n.fa-concierge-bell:before {\n  content: \"\\f562\"; }\n\n.fa-confluence:before {\n  content: \"\\f78d\"; }\n\n.fa-connectdevelop:before {\n  content: \"\\f20e\"; }\n\n.fa-contao:before {\n  content: \"\\f26d\"; }\n\n.fa-cookie:before {\n  content: \"\\f563\"; }\n\n.fa-cookie-bite:before {\n  content: \"\\f564\"; }\n\n.fa-copy:before {\n  content: \"\\f0c5\"; }\n\n.fa-copyright:before {\n  content: \"\\f1f9\"; }\n\n.fa-cotton-bureau:before {\n  content: \"\\f89e\"; }\n\n.fa-couch:before {\n  content: \"\\f4b8\"; }\n\n.fa-cpanel:before {\n  content: \"\\f388\"; }\n\n.fa-creative-commons:before {\n  content: \"\\f25e\"; }\n\n.fa-creative-commons-by:before {\n  content: \"\\f4e7\"; }\n\n.fa-creative-commons-nc:before {\n  content: \"\\f4e8\"; }\n\n.fa-creative-commons-nc-eu:before {\n  content: \"\\f4e9\"; }\n\n.fa-creative-commons-nc-jp:before {\n  content: \"\\f4ea\"; }\n\n.fa-creative-commons-nd:before {\n  content: \"\\f4eb\"; }\n\n.fa-creative-commons-pd:before {\n  content: \"\\f4ec\"; }\n\n.fa-creative-commons-pd-alt:before {\n  content: \"\\f4ed\"; }\n\n.fa-creative-commons-remix:before {\n  content: \"\\f4ee\"; }\n\n.fa-creative-commons-sa:before {\n  content: \"\\f4ef\"; }\n\n.fa-creative-commons-sampling:before {\n  content: \"\\f4f0\"; }\n\n.fa-creative-commons-sampling-plus:before {\n  content: \"\\f4f1\"; }\n\n.fa-creative-commons-share:before {\n  content: \"\\f4f2\"; }\n\n.fa-creative-commons-zero:before {\n  content: \"\\f4f3\"; }\n\n.fa-credit-card:before {\n  content: \"\\f09d\"; }\n\n.fa-critical-role:before {\n  content: \"\\f6c9\"; }\n\n.fa-crop:before {\n  content: \"\\f125\"; }\n\n.fa-crop-alt:before {\n  content: \"\\f565\"; }\n\n.fa-cross:before {\n  content: \"\\f654\"; }\n\n.fa-crosshairs:before {\n  content: \"\\f05b\"; }\n\n.fa-crow:before {\n  content: \"\\f520\"; }\n\n.fa-crown:before {\n  content: \"\\f521\"; }\n\n.fa-crutch:before {\n  content: \"\\f7f7\"; }\n\n.fa-css3:before {\n  content: \"\\f13c\"; }\n\n.fa-css3-alt:before {\n  content: \"\\f38b\"; }\n\n.fa-cube:before {\n  content: \"\\f1b2\"; }\n\n.fa-cubes:before {\n  content: \"\\f1b3\"; }\n\n.fa-cut:before {\n  content: \"\\f0c4\"; }\n\n.fa-cuttlefish:before {\n  content: \"\\f38c\"; }\n\n.fa-d-and-d:before {\n  content: \"\\f38d\"; }\n\n.fa-d-and-d-beyond:before {\n  content: \"\\f6ca\"; }\n\n.fa-dashcube:before {\n  content: \"\\f210\"; }\n\n.fa-database:before {\n  content: \"\\f1c0\"; }\n\n.fa-deaf:before {\n  content: \"\\f2a4\"; }\n\n.fa-delicious:before {\n  content: \"\\f1a5\"; }\n\n.fa-democrat:before {\n  content: \"\\f747\"; }\n\n.fa-deploydog:before {\n  content: \"\\f38e\"; }\n\n.fa-deskpro:before {\n  content: \"\\f38f\"; }\n\n.fa-desktop:before {\n  content: \"\\f108\"; }\n\n.fa-dev:before {\n  content: \"\\f6cc\"; }\n\n.fa-deviantart:before {\n  content: \"\\f1bd\"; }\n\n.fa-dharmachakra:before {\n  content: \"\\f655\"; }\n\n.fa-dhl:before {\n  content: \"\\f790\"; }\n\n.fa-diagnoses:before {\n  content: \"\\f470\"; }\n\n.fa-diaspora:before {\n  content: \"\\f791\"; }\n\n.fa-dice:before {\n  content: \"\\f522\"; }\n\n.fa-dice-d20:before {\n  content: \"\\f6cf\"; }\n\n.fa-dice-d6:before {\n  content: \"\\f6d1\"; }\n\n.fa-dice-five:before {\n  content: \"\\f523\"; }\n\n.fa-dice-four:before {\n  content: \"\\f524\"; }\n\n.fa-dice-one:before {\n  content: \"\\f525\"; }\n\n.fa-dice-six:before {\n  content: \"\\f526\"; }\n\n.fa-dice-three:before {\n  content: \"\\f527\"; }\n\n.fa-dice-two:before {\n  content: \"\\f528\"; }\n\n.fa-digg:before {\n  content: \"\\f1a6\"; }\n\n.fa-digital-ocean:before {\n  content: \"\\f391\"; }\n\n.fa-digital-tachograph:before {\n  content: \"\\f566\"; }\n\n.fa-directions:before {\n  content: \"\\f5eb\"; }\n\n.fa-discord:before {\n  content: \"\\f392\"; }\n\n.fa-discourse:before {\n  content: \"\\f393\"; }\n\n.fa-divide:before {\n  content: \"\\f529\"; }\n\n.fa-dizzy:before {\n  content: \"\\f567\"; }\n\n.fa-dna:before {\n  content: \"\\f471\"; }\n\n.fa-dochub:before {\n  content: \"\\f394\"; }\n\n.fa-docker:before {\n  content: \"\\f395\"; }\n\n.fa-dog:before {\n  content: \"\\f6d3\"; }\n\n.fa-dollar-sign:before {\n  content: \"\\f155\"; }\n\n.fa-dolly:before {\n  content: \"\\f472\"; }\n\n.fa-dolly-flatbed:before {\n  content: \"\\f474\"; }\n\n.fa-donate:before {\n  content: \"\\f4b9\"; }\n\n.fa-door-closed:before {\n  content: \"\\f52a\"; }\n\n.fa-door-open:before {\n  content: \"\\f52b\"; }\n\n.fa-dot-circle:before {\n  content: \"\\f192\"; }\n\n.fa-dove:before {\n  content: \"\\f4ba\"; }\n\n.fa-download:before {\n  content: \"\\f019\"; }\n\n.fa-draft2digital:before {\n  content: \"\\f396\"; }\n\n.fa-drafting-compass:before {\n  content: \"\\f568\"; }\n\n.fa-dragon:before {\n  content: \"\\f6d5\"; }\n\n.fa-draw-polygon:before {\n  content: \"\\f5ee\"; }\n\n.fa-dribbble:before {\n  content: \"\\f17d\"; }\n\n.fa-dribbble-square:before {\n  content: \"\\f397\"; }\n\n.fa-dropbox:before {\n  content: \"\\f16b\"; }\n\n.fa-drum:before {\n  content: \"\\f569\"; }\n\n.fa-drum-steelpan:before {\n  content: \"\\f56a\"; }\n\n.fa-drumstick-bite:before {\n  content: \"\\f6d7\"; }\n\n.fa-drupal:before {\n  content: \"\\f1a9\"; }\n\n.fa-dumbbell:before {\n  content: \"\\f44b\"; }\n\n.fa-dumpster:before {\n  content: \"\\f793\"; }\n\n.fa-dumpster-fire:before {\n  content: \"\\f794\"; }\n\n.fa-dungeon:before {\n  content: \"\\f6d9\"; }\n\n.fa-dyalog:before {\n  content: \"\\f399\"; }\n\n.fa-earlybirds:before {\n  content: \"\\f39a\"; }\n\n.fa-ebay:before {\n  content: \"\\f4f4\"; }\n\n.fa-edge:before {\n  content: \"\\f282\"; }\n\n.fa-edit:before {\n  content: \"\\f044\"; }\n\n.fa-egg:before {\n  content: \"\\f7fb\"; }\n\n.fa-eject:before {\n  content: \"\\f052\"; }\n\n.fa-elementor:before {\n  content: \"\\f430\"; }\n\n.fa-ellipsis-h:before {\n  content: \"\\f141\"; }\n\n.fa-ellipsis-v:before {\n  content: \"\\f142\"; }\n\n.fa-ello:before {\n  content: \"\\f5f1\"; }\n\n.fa-ember:before {\n  content: \"\\f423\"; }\n\n.fa-empire:before {\n  content: \"\\f1d1\"; }\n\n.fa-envelope:before {\n  content: \"\\f0e0\"; }\n\n.fa-envelope-open:before {\n  content: \"\\f2b6\"; }\n\n.fa-envelope-open-text:before {\n  content: \"\\f658\"; }\n\n.fa-envelope-square:before {\n  content: \"\\f199\"; }\n\n.fa-envira:before {\n  content: \"\\f299\"; }\n\n.fa-equals:before {\n  content: \"\\f52c\"; }\n\n.fa-eraser:before {\n  content: \"\\f12d\"; }\n\n.fa-erlang:before {\n  content: \"\\f39d\"; }\n\n.fa-ethereum:before {\n  content: \"\\f42e\"; }\n\n.fa-ethernet:before {\n  content: \"\\f796\"; }\n\n.fa-etsy:before {\n  content: \"\\f2d7\"; }\n\n.fa-euro-sign:before {\n  content: \"\\f153\"; }\n\n.fa-evernote:before {\n  content: \"\\f839\"; }\n\n.fa-exchange-alt:before {\n  content: \"\\f362\"; }\n\n.fa-exclamation:before {\n  content: \"\\f12a\"; }\n\n.fa-exclamation-circle:before {\n  content: \"\\f06a\"; }\n\n.fa-exclamation-triangle:before {\n  content: \"\\f071\"; }\n\n.fa-expand:before {\n  content: \"\\f065\"; }\n\n.fa-expand-arrows-alt:before {\n  content: \"\\f31e\"; }\n\n.fa-expeditedssl:before {\n  content: \"\\f23e\"; }\n\n.fa-external-link-alt:before {\n  content: \"\\f35d\"; }\n\n.fa-external-link-square-alt:before {\n  content: \"\\f360\"; }\n\n.fa-eye:before {\n  content: \"\\f06e\"; }\n\n.fa-eye-dropper:before {\n  content: \"\\f1fb\"; }\n\n.fa-eye-slash:before {\n  content: \"\\f070\"; }\n\n.fa-facebook:before {\n  content: \"\\f09a\"; }\n\n.fa-facebook-f:before {\n  content: \"\\f39e\"; }\n\n.fa-facebook-messenger:before {\n  content: \"\\f39f\"; }\n\n.fa-facebook-square:before {\n  content: \"\\f082\"; }\n\n.fa-fan:before {\n  content: \"\\f863\"; }\n\n.fa-fantasy-flight-games:before {\n  content: \"\\f6dc\"; }\n\n.fa-fast-backward:before {\n  content: \"\\f049\"; }\n\n.fa-fast-forward:before {\n  content: \"\\f050\"; }\n\n.fa-fax:before {\n  content: \"\\f1ac\"; }\n\n.fa-feather:before {\n  content: \"\\f52d\"; }\n\n.fa-feather-alt:before {\n  content: \"\\f56b\"; }\n\n.fa-fedex:before {\n  content: \"\\f797\"; }\n\n.fa-fedora:before {\n  content: \"\\f798\"; }\n\n.fa-female:before {\n  content: \"\\f182\"; }\n\n.fa-fighter-jet:before {\n  content: \"\\f0fb\"; }\n\n.fa-figma:before {\n  content: \"\\f799\"; }\n\n.fa-file:before {\n  content: \"\\f15b\"; }\n\n.fa-file-alt:before {\n  content: \"\\f15c\"; }\n\n.fa-file-archive:before {\n  content: \"\\f1c6\"; }\n\n.fa-file-audio:before {\n  content: \"\\f1c7\"; }\n\n.fa-file-code:before {\n  content: \"\\f1c9\"; }\n\n.fa-file-contract:before {\n  content: \"\\f56c\"; }\n\n.fa-file-csv:before {\n  content: \"\\f6dd\"; }\n\n.fa-file-download:before {\n  content: \"\\f56d\"; }\n\n.fa-file-excel:before {\n  content: \"\\f1c3\"; }\n\n.fa-file-export:before {\n  content: \"\\f56e\"; }\n\n.fa-file-image:before {\n  content: \"\\f1c5\"; }\n\n.fa-file-import:before {\n  content: \"\\f56f\"; }\n\n.fa-file-invoice:before {\n  content: \"\\f570\"; }\n\n.fa-file-invoice-dollar:before {\n  content: \"\\f571\"; }\n\n.fa-file-medical:before {\n  content: \"\\f477\"; }\n\n.fa-file-medical-alt:before {\n  content: \"\\f478\"; }\n\n.fa-file-pdf:before {\n  content: \"\\f1c1\"; }\n\n.fa-file-powerpoint:before {\n  content: \"\\f1c4\"; }\n\n.fa-file-prescription:before {\n  content: \"\\f572\"; }\n\n.fa-file-signature:before {\n  content: \"\\f573\"; }\n\n.fa-file-upload:before {\n  content: \"\\f574\"; }\n\n.fa-file-video:before {\n  content: \"\\f1c8\"; }\n\n.fa-file-word:before {\n  content: \"\\f1c2\"; }\n\n.fa-fill:before {\n  content: \"\\f575\"; }\n\n.fa-fill-drip:before {\n  content: \"\\f576\"; }\n\n.fa-film:before {\n  content: \"\\f008\"; }\n\n.fa-filter:before {\n  content: \"\\f0b0\"; }\n\n.fa-fingerprint:before {\n  content: \"\\f577\"; }\n\n.fa-fire:before {\n  content: \"\\f06d\"; }\n\n.fa-fire-alt:before {\n  content: \"\\f7e4\"; }\n\n.fa-fire-extinguisher:before {\n  content: \"\\f134\"; }\n\n.fa-firefox:before {\n  content: \"\\f269\"; }\n\n.fa-first-aid:before {\n  content: \"\\f479\"; }\n\n.fa-first-order:before {\n  content: \"\\f2b0\"; }\n\n.fa-first-order-alt:before {\n  content: \"\\f50a\"; }\n\n.fa-firstdraft:before {\n  content: \"\\f3a1\"; }\n\n.fa-fish:before {\n  content: \"\\f578\"; }\n\n.fa-fist-raised:before {\n  content: \"\\f6de\"; }\n\n.fa-flag:before {\n  content: \"\\f024\"; }\n\n.fa-flag-checkered:before {\n  content: \"\\f11e\"; }\n\n.fa-flag-usa:before {\n  content: \"\\f74d\"; }\n\n.fa-flask:before {\n  content: \"\\f0c3\"; }\n\n.fa-flickr:before {\n  content: \"\\f16e\"; }\n\n.fa-flipboard:before {\n  content: \"\\f44d\"; }\n\n.fa-flushed:before {\n  content: \"\\f579\"; }\n\n.fa-fly:before {\n  content: \"\\f417\"; }\n\n.fa-folder:before {\n  content: \"\\f07b\"; }\n\n.fa-folder-minus:before {\n  content: \"\\f65d\"; }\n\n.fa-folder-open:before {\n  content: \"\\f07c\"; }\n\n.fa-folder-plus:before {\n  content: \"\\f65e\"; }\n\n.fa-font:before {\n  content: \"\\f031\"; }\n\n.fa-font-awesome:before {\n  content: \"\\f2b4\"; }\n\n.fa-font-awesome-alt:before {\n  content: \"\\f35c\"; }\n\n.fa-font-awesome-flag:before {\n  content: \"\\f425\"; }\n\n.fa-font-awesome-logo-full:before {\n  content: \"\\f4e6\"; }\n\n.fa-fonticons:before {\n  content: \"\\f280\"; }\n\n.fa-fonticons-fi:before {\n  content: \"\\f3a2\"; }\n\n.fa-football-ball:before {\n  content: \"\\f44e\"; }\n\n.fa-fort-awesome:before {\n  content: \"\\f286\"; }\n\n.fa-fort-awesome-alt:before {\n  content: \"\\f3a3\"; }\n\n.fa-forumbee:before {\n  content: \"\\f211\"; }\n\n.fa-forward:before {\n  content: \"\\f04e\"; }\n\n.fa-foursquare:before {\n  content: \"\\f180\"; }\n\n.fa-free-code-camp:before {\n  content: \"\\f2c5\"; }\n\n.fa-freebsd:before {\n  content: \"\\f3a4\"; }\n\n.fa-frog:before {\n  content: \"\\f52e\"; }\n\n.fa-frown:before {\n  content: \"\\f119\"; }\n\n.fa-frown-open:before {\n  content: \"\\f57a\"; }\n\n.fa-fulcrum:before {\n  content: \"\\f50b\"; }\n\n.fa-funnel-dollar:before {\n  content: \"\\f662\"; }\n\n.fa-futbol:before {\n  content: \"\\f1e3\"; }\n\n.fa-galactic-republic:before {\n  content: \"\\f50c\"; }\n\n.fa-galactic-senate:before {\n  content: \"\\f50d\"; }\n\n.fa-gamepad:before {\n  content: \"\\f11b\"; }\n\n.fa-gas-pump:before {\n  content: \"\\f52f\"; }\n\n.fa-gavel:before {\n  content: \"\\f0e3\"; }\n\n.fa-gem:before {\n  content: \"\\f3a5\"; }\n\n.fa-genderless:before {\n  content: \"\\f22d\"; }\n\n.fa-get-pocket:before {\n  content: \"\\f265\"; }\n\n.fa-gg:before {\n  content: \"\\f260\"; }\n\n.fa-gg-circle:before {\n  content: \"\\f261\"; }\n\n.fa-ghost:before {\n  content: \"\\f6e2\"; }\n\n.fa-gift:before {\n  content: \"\\f06b\"; }\n\n.fa-gifts:before {\n  content: \"\\f79c\"; }\n\n.fa-git:before {\n  content: \"\\f1d3\"; }\n\n.fa-git-alt:before {\n  content: \"\\f841\"; }\n\n.fa-git-square:before {\n  content: \"\\f1d2\"; }\n\n.fa-github:before {\n  content: \"\\f09b\"; }\n\n.fa-github-alt:before {\n  content: \"\\f113\"; }\n\n.fa-github-square:before {\n  content: \"\\f092\"; }\n\n.fa-gitkraken:before {\n  content: \"\\f3a6\"; }\n\n.fa-gitlab:before {\n  content: \"\\f296\"; }\n\n.fa-gitter:before {\n  content: \"\\f426\"; }\n\n.fa-glass-cheers:before {\n  content: \"\\f79f\"; }\n\n.fa-glass-martini:before {\n  content: \"\\f000\"; }\n\n.fa-glass-martini-alt:before {\n  content: \"\\f57b\"; }\n\n.fa-glass-whiskey:before {\n  content: \"\\f7a0\"; }\n\n.fa-glasses:before {\n  content: \"\\f530\"; }\n\n.fa-glide:before {\n  content: \"\\f2a5\"; }\n\n.fa-glide-g:before {\n  content: \"\\f2a6\"; }\n\n.fa-globe:before {\n  content: \"\\f0ac\"; }\n\n.fa-globe-africa:before {\n  content: \"\\f57c\"; }\n\n.fa-globe-americas:before {\n  content: \"\\f57d\"; }\n\n.fa-globe-asia:before {\n  content: \"\\f57e\"; }\n\n.fa-globe-europe:before {\n  content: \"\\f7a2\"; }\n\n.fa-gofore:before {\n  content: \"\\f3a7\"; }\n\n.fa-golf-ball:before {\n  content: \"\\f450\"; }\n\n.fa-goodreads:before {\n  content: \"\\f3a8\"; }\n\n.fa-goodreads-g:before {\n  content: \"\\f3a9\"; }\n\n.fa-google:before {\n  content: \"\\f1a0\"; }\n\n.fa-google-drive:before {\n  content: \"\\f3aa\"; }\n\n.fa-google-play:before {\n  content: \"\\f3ab\"; }\n\n.fa-google-plus:before {\n  content: \"\\f2b3\"; }\n\n.fa-google-plus-g:before {\n  content: \"\\f0d5\"; }\n\n.fa-google-plus-square:before {\n  content: \"\\f0d4\"; }\n\n.fa-google-wallet:before {\n  content: \"\\f1ee\"; }\n\n.fa-gopuram:before {\n  content: \"\\f664\"; }\n\n.fa-graduation-cap:before {\n  content: \"\\f19d\"; }\n\n.fa-gratipay:before {\n  content: \"\\f184\"; }\n\n.fa-grav:before {\n  content: \"\\f2d6\"; }\n\n.fa-greater-than:before {\n  content: \"\\f531\"; }\n\n.fa-greater-than-equal:before {\n  content: \"\\f532\"; }\n\n.fa-grimace:before {\n  content: \"\\f57f\"; }\n\n.fa-grin:before {\n  content: \"\\f580\"; }\n\n.fa-grin-alt:before {\n  content: \"\\f581\"; }\n\n.fa-grin-beam:before {\n  content: \"\\f582\"; }\n\n.fa-grin-beam-sweat:before {\n  content: \"\\f583\"; }\n\n.fa-grin-hearts:before {\n  content: \"\\f584\"; }\n\n.fa-grin-squint:before {\n  content: \"\\f585\"; }\n\n.fa-grin-squint-tears:before {\n  content: \"\\f586\"; }\n\n.fa-grin-stars:before {\n  content: \"\\f587\"; }\n\n.fa-grin-tears:before {\n  content: \"\\f588\"; }\n\n.fa-grin-tongue:before {\n  content: \"\\f589\"; }\n\n.fa-grin-tongue-squint:before {\n  content: \"\\f58a\"; }\n\n.fa-grin-tongue-wink:before {\n  content: \"\\f58b\"; }\n\n.fa-grin-wink:before {\n  content: \"\\f58c\"; }\n\n.fa-grip-horizontal:before {\n  content: \"\\f58d\"; }\n\n.fa-grip-lines:before {\n  content: \"\\f7a4\"; }\n\n.fa-grip-lines-vertical:before {\n  content: \"\\f7a5\"; }\n\n.fa-grip-vertical:before {\n  content: \"\\f58e\"; }\n\n.fa-gripfire:before {\n  content: \"\\f3ac\"; }\n\n.fa-grunt:before {\n  content: \"\\f3ad\"; }\n\n.fa-guitar:before {\n  content: \"\\f7a6\"; }\n\n.fa-gulp:before {\n  content: \"\\f3ae\"; }\n\n.fa-h-square:before {\n  content: \"\\f0fd\"; }\n\n.fa-hacker-news:before {\n  content: \"\\f1d4\"; }\n\n.fa-hacker-news-square:before {\n  content: \"\\f3af\"; }\n\n.fa-hackerrank:before {\n  content: \"\\f5f7\"; }\n\n.fa-hamburger:before {\n  content: \"\\f805\"; }\n\n.fa-hammer:before {\n  content: \"\\f6e3\"; }\n\n.fa-hamsa:before {\n  content: \"\\f665\"; }\n\n.fa-hand-holding:before {\n  content: \"\\f4bd\"; }\n\n.fa-hand-holding-heart:before {\n  content: \"\\f4be\"; }\n\n.fa-hand-holding-usd:before {\n  content: \"\\f4c0\"; }\n\n.fa-hand-lizard:before {\n  content: \"\\f258\"; }\n\n.fa-hand-middle-finger:before {\n  content: \"\\f806\"; }\n\n.fa-hand-paper:before {\n  content: \"\\f256\"; }\n\n.fa-hand-peace:before {\n  content: \"\\f25b\"; }\n\n.fa-hand-point-down:before {\n  content: \"\\f0a7\"; }\n\n.fa-hand-point-left:before {\n  content: \"\\f0a5\"; }\n\n.fa-hand-point-right:before {\n  content: \"\\f0a4\"; }\n\n.fa-hand-point-up:before {\n  content: \"\\f0a6\"; }\n\n.fa-hand-pointer:before {\n  content: \"\\f25a\"; }\n\n.fa-hand-rock:before {\n  content: \"\\f255\"; }\n\n.fa-hand-scissors:before {\n  content: \"\\f257\"; }\n\n.fa-hand-spock:before {\n  content: \"\\f259\"; }\n\n.fa-hands:before {\n  content: \"\\f4c2\"; }\n\n.fa-hands-helping:before {\n  content: \"\\f4c4\"; }\n\n.fa-handshake:before {\n  content: \"\\f2b5\"; }\n\n.fa-hanukiah:before {\n  content: \"\\f6e6\"; }\n\n.fa-hard-hat:before {\n  content: \"\\f807\"; }\n\n.fa-hashtag:before {\n  content: \"\\f292\"; }\n\n.fa-hat-wizard:before {\n  content: \"\\f6e8\"; }\n\n.fa-haykal:before {\n  content: \"\\f666\"; }\n\n.fa-hdd:before {\n  content: \"\\f0a0\"; }\n\n.fa-heading:before {\n  content: \"\\f1dc\"; }\n\n.fa-headphones:before {\n  content: \"\\f025\"; }\n\n.fa-headphones-alt:before {\n  content: \"\\f58f\"; }\n\n.fa-headset:before {\n  content: \"\\f590\"; }\n\n.fa-heart:before {\n  content: \"\\f004\"; }\n\n.fa-heart-broken:before {\n  content: \"\\f7a9\"; }\n\n.fa-heartbeat:before {\n  content: \"\\f21e\"; }\n\n.fa-helicopter:before {\n  content: \"\\f533\"; }\n\n.fa-highlighter:before {\n  content: \"\\f591\"; }\n\n.fa-hiking:before {\n  content: \"\\f6ec\"; }\n\n.fa-hippo:before {\n  content: \"\\f6ed\"; }\n\n.fa-hips:before {\n  content: \"\\f452\"; }\n\n.fa-hire-a-helper:before {\n  content: \"\\f3b0\"; }\n\n.fa-history:before {\n  content: \"\\f1da\"; }\n\n.fa-hockey-puck:before {\n  content: \"\\f453\"; }\n\n.fa-holly-berry:before {\n  content: \"\\f7aa\"; }\n\n.fa-home:before {\n  content: \"\\f015\"; }\n\n.fa-hooli:before {\n  content: \"\\f427\"; }\n\n.fa-hornbill:before {\n  content: \"\\f592\"; }\n\n.fa-horse:before {\n  content: \"\\f6f0\"; }\n\n.fa-horse-head:before {\n  content: \"\\f7ab\"; }\n\n.fa-hospital:before {\n  content: \"\\f0f8\"; }\n\n.fa-hospital-alt:before {\n  content: \"\\f47d\"; }\n\n.fa-hospital-symbol:before {\n  content: \"\\f47e\"; }\n\n.fa-hot-tub:before {\n  content: \"\\f593\"; }\n\n.fa-hotdog:before {\n  content: \"\\f80f\"; }\n\n.fa-hotel:before {\n  content: \"\\f594\"; }\n\n.fa-hotjar:before {\n  content: \"\\f3b1\"; }\n\n.fa-hourglass:before {\n  content: \"\\f254\"; }\n\n.fa-hourglass-end:before {\n  content: \"\\f253\"; }\n\n.fa-hourglass-half:before {\n  content: \"\\f252\"; }\n\n.fa-hourglass-start:before {\n  content: \"\\f251\"; }\n\n.fa-house-damage:before {\n  content: \"\\f6f1\"; }\n\n.fa-houzz:before {\n  content: \"\\f27c\"; }\n\n.fa-hryvnia:before {\n  content: \"\\f6f2\"; }\n\n.fa-html5:before {\n  content: \"\\f13b\"; }\n\n.fa-hubspot:before {\n  content: \"\\f3b2\"; }\n\n.fa-i-cursor:before {\n  content: \"\\f246\"; }\n\n.fa-ice-cream:before {\n  content: \"\\f810\"; }\n\n.fa-icicles:before {\n  content: \"\\f7ad\"; }\n\n.fa-icons:before {\n  content: \"\\f86d\"; }\n\n.fa-id-badge:before {\n  content: \"\\f2c1\"; }\n\n.fa-id-card:before {\n  content: \"\\f2c2\"; }\n\n.fa-id-card-alt:before {\n  content: \"\\f47f\"; }\n\n.fa-igloo:before {\n  content: \"\\f7ae\"; }\n\n.fa-image:before {\n  content: \"\\f03e\"; }\n\n.fa-images:before {\n  content: \"\\f302\"; }\n\n.fa-imdb:before {\n  content: \"\\f2d8\"; }\n\n.fa-inbox:before {\n  content: \"\\f01c\"; }\n\n.fa-indent:before {\n  content: \"\\f03c\"; }\n\n.fa-industry:before {\n  content: \"\\f275\"; }\n\n.fa-infinity:before {\n  content: \"\\f534\"; }\n\n.fa-info:before {\n  content: \"\\f129\"; }\n\n.fa-info-circle:before {\n  content: \"\\f05a\"; }\n\n.fa-instagram:before {\n  content: \"\\f16d\"; }\n\n.fa-intercom:before {\n  content: \"\\f7af\"; }\n\n.fa-internet-explorer:before {\n  content: \"\\f26b\"; }\n\n.fa-invision:before {\n  content: \"\\f7b0\"; }\n\n.fa-ioxhost:before {\n  content: \"\\f208\"; }\n\n.fa-italic:before {\n  content: \"\\f033\"; }\n\n.fa-itch-io:before {\n  content: \"\\f83a\"; }\n\n.fa-itunes:before {\n  content: \"\\f3b4\"; }\n\n.fa-itunes-note:before {\n  content: \"\\f3b5\"; }\n\n.fa-java:before {\n  content: \"\\f4e4\"; }\n\n.fa-jedi:before {\n  content: \"\\f669\"; }\n\n.fa-jedi-order:before {\n  content: \"\\f50e\"; }\n\n.fa-jenkins:before {\n  content: \"\\f3b6\"; }\n\n.fa-jira:before {\n  content: \"\\f7b1\"; }\n\n.fa-joget:before {\n  content: \"\\f3b7\"; }\n\n.fa-joint:before {\n  content: \"\\f595\"; }\n\n.fa-joomla:before {\n  content: \"\\f1aa\"; }\n\n.fa-journal-whills:before {\n  content: \"\\f66a\"; }\n\n.fa-js:before {\n  content: \"\\f3b8\"; }\n\n.fa-js-square:before {\n  content: \"\\f3b9\"; }\n\n.fa-jsfiddle:before {\n  content: \"\\f1cc\"; }\n\n.fa-kaaba:before {\n  content: \"\\f66b\"; }\n\n.fa-kaggle:before {\n  content: \"\\f5fa\"; }\n\n.fa-key:before {\n  content: \"\\f084\"; }\n\n.fa-keybase:before {\n  content: \"\\f4f5\"; }\n\n.fa-keyboard:before {\n  content: \"\\f11c\"; }\n\n.fa-keycdn:before {\n  content: \"\\f3ba\"; }\n\n.fa-khanda:before {\n  content: \"\\f66d\"; }\n\n.fa-kickstarter:before {\n  content: \"\\f3bb\"; }\n\n.fa-kickstarter-k:before {\n  content: \"\\f3bc\"; }\n\n.fa-kiss:before {\n  content: \"\\f596\"; }\n\n.fa-kiss-beam:before {\n  content: \"\\f597\"; }\n\n.fa-kiss-wink-heart:before {\n  content: \"\\f598\"; }\n\n.fa-kiwi-bird:before {\n  content: \"\\f535\"; }\n\n.fa-korvue:before {\n  content: \"\\f42f\"; }\n\n.fa-landmark:before {\n  content: \"\\f66f\"; }\n\n.fa-language:before {\n  content: \"\\f1ab\"; }\n\n.fa-laptop:before {\n  content: \"\\f109\"; }\n\n.fa-laptop-code:before {\n  content: \"\\f5fc\"; }\n\n.fa-laptop-medical:before {\n  content: \"\\f812\"; }\n\n.fa-laravel:before {\n  content: \"\\f3bd\"; }\n\n.fa-lastfm:before {\n  content: \"\\f202\"; }\n\n.fa-lastfm-square:before {\n  content: \"\\f203\"; }\n\n.fa-laugh:before {\n  content: \"\\f599\"; }\n\n.fa-laugh-beam:before {\n  content: \"\\f59a\"; }\n\n.fa-laugh-squint:before {\n  content: \"\\f59b\"; }\n\n.fa-laugh-wink:before {\n  content: \"\\f59c\"; }\n\n.fa-layer-group:before {\n  content: \"\\f5fd\"; }\n\n.fa-leaf:before {\n  content: \"\\f06c\"; }\n\n.fa-leanpub:before {\n  content: \"\\f212\"; }\n\n.fa-lemon:before {\n  content: \"\\f094\"; }\n\n.fa-less:before {\n  content: \"\\f41d\"; }\n\n.fa-less-than:before {\n  content: \"\\f536\"; }\n\n.fa-less-than-equal:before {\n  content: \"\\f537\"; }\n\n.fa-level-down-alt:before {\n  content: \"\\f3be\"; }\n\n.fa-level-up-alt:before {\n  content: \"\\f3bf\"; }\n\n.fa-life-ring:before {\n  content: \"\\f1cd\"; }\n\n.fa-lightbulb:before {\n  content: \"\\f0eb\"; }\n\n.fa-line:before {\n  content: \"\\f3c0\"; }\n\n.fa-link:before {\n  content: \"\\f0c1\"; }\n\n.fa-linkedin:before {\n  content: \"\\f08c\"; }\n\n.fa-linkedin-in:before {\n  content: \"\\f0e1\"; }\n\n.fa-linode:before {\n  content: \"\\f2b8\"; }\n\n.fa-linux:before {\n  content: \"\\f17c\"; }\n\n.fa-lira-sign:before {\n  content: \"\\f195\"; }\n\n.fa-list:before {\n  content: \"\\f03a\"; }\n\n.fa-list-alt:before {\n  content: \"\\f022\"; }\n\n.fa-list-ol:before {\n  content: \"\\f0cb\"; }\n\n.fa-list-ul:before {\n  content: \"\\f0ca\"; }\n\n.fa-location-arrow:before {\n  content: \"\\f124\"; }\n\n.fa-lock:before {\n  content: \"\\f023\"; }\n\n.fa-lock-open:before {\n  content: \"\\f3c1\"; }\n\n.fa-long-arrow-alt-down:before {\n  content: \"\\f309\"; }\n\n.fa-long-arrow-alt-left:before {\n  content: \"\\f30a\"; }\n\n.fa-long-arrow-alt-right:before {\n  content: \"\\f30b\"; }\n\n.fa-long-arrow-alt-up:before {\n  content: \"\\f30c\"; }\n\n.fa-low-vision:before {\n  content: \"\\f2a8\"; }\n\n.fa-luggage-cart:before {\n  content: \"\\f59d\"; }\n\n.fa-lyft:before {\n  content: \"\\f3c3\"; }\n\n.fa-magento:before {\n  content: \"\\f3c4\"; }\n\n.fa-magic:before {\n  content: \"\\f0d0\"; }\n\n.fa-magnet:before {\n  content: \"\\f076\"; }\n\n.fa-mail-bulk:before {\n  content: \"\\f674\"; }\n\n.fa-mailchimp:before {\n  content: \"\\f59e\"; }\n\n.fa-male:before {\n  content: \"\\f183\"; }\n\n.fa-mandalorian:before {\n  content: \"\\f50f\"; }\n\n.fa-map:before {\n  content: \"\\f279\"; }\n\n.fa-map-marked:before {\n  content: \"\\f59f\"; }\n\n.fa-map-marked-alt:before {\n  content: \"\\f5a0\"; }\n\n.fa-map-marker:before {\n  content: \"\\f041\"; }\n\n.fa-map-marker-alt:before {\n  content: \"\\f3c5\"; }\n\n.fa-map-pin:before {\n  content: \"\\f276\"; }\n\n.fa-map-signs:before {\n  content: \"\\f277\"; }\n\n.fa-markdown:before {\n  content: \"\\f60f\"; }\n\n.fa-marker:before {\n  content: \"\\f5a1\"; }\n\n.fa-mars:before {\n  content: \"\\f222\"; }\n\n.fa-mars-double:before {\n  content: \"\\f227\"; }\n\n.fa-mars-stroke:before {\n  content: \"\\f229\"; }\n\n.fa-mars-stroke-h:before {\n  content: \"\\f22b\"; }\n\n.fa-mars-stroke-v:before {\n  content: \"\\f22a\"; }\n\n.fa-mask:before {\n  content: \"\\f6fa\"; }\n\n.fa-mastodon:before {\n  content: \"\\f4f6\"; }\n\n.fa-maxcdn:before {\n  content: \"\\f136\"; }\n\n.fa-medal:before {\n  content: \"\\f5a2\"; }\n\n.fa-medapps:before {\n  content: \"\\f3c6\"; }\n\n.fa-medium:before {\n  content: \"\\f23a\"; }\n\n.fa-medium-m:before {\n  content: \"\\f3c7\"; }\n\n.fa-medkit:before {\n  content: \"\\f0fa\"; }\n\n.fa-medrt:before {\n  content: \"\\f3c8\"; }\n\n.fa-meetup:before {\n  content: \"\\f2e0\"; }\n\n.fa-megaport:before {\n  content: \"\\f5a3\"; }\n\n.fa-meh:before {\n  content: \"\\f11a\"; }\n\n.fa-meh-blank:before {\n  content: \"\\f5a4\"; }\n\n.fa-meh-rolling-eyes:before {\n  content: \"\\f5a5\"; }\n\n.fa-memory:before {\n  content: \"\\f538\"; }\n\n.fa-mendeley:before {\n  content: \"\\f7b3\"; }\n\n.fa-menorah:before {\n  content: \"\\f676\"; }\n\n.fa-mercury:before {\n  content: \"\\f223\"; }\n\n.fa-meteor:before {\n  content: \"\\f753\"; }\n\n.fa-microchip:before {\n  content: \"\\f2db\"; }\n\n.fa-microphone:before {\n  content: \"\\f130\"; }\n\n.fa-microphone-alt:before {\n  content: \"\\f3c9\"; }\n\n.fa-microphone-alt-slash:before {\n  content: \"\\f539\"; }\n\n.fa-microphone-slash:before {\n  content: \"\\f131\"; }\n\n.fa-microscope:before {\n  content: \"\\f610\"; }\n\n.fa-microsoft:before {\n  content: \"\\f3ca\"; }\n\n.fa-minus:before {\n  content: \"\\f068\"; }\n\n.fa-minus-circle:before {\n  content: \"\\f056\"; }\n\n.fa-minus-square:before {\n  content: \"\\f146\"; }\n\n.fa-mitten:before {\n  content: \"\\f7b5\"; }\n\n.fa-mix:before {\n  content: \"\\f3cb\"; }\n\n.fa-mixcloud:before {\n  content: \"\\f289\"; }\n\n.fa-mizuni:before {\n  content: \"\\f3cc\"; }\n\n.fa-mobile:before {\n  content: \"\\f10b\"; }\n\n.fa-mobile-alt:before {\n  content: \"\\f3cd\"; }\n\n.fa-modx:before {\n  content: \"\\f285\"; }\n\n.fa-monero:before {\n  content: \"\\f3d0\"; }\n\n.fa-money-bill:before {\n  content: \"\\f0d6\"; }\n\n.fa-money-bill-alt:before {\n  content: \"\\f3d1\"; }\n\n.fa-money-bill-wave:before {\n  content: \"\\f53a\"; }\n\n.fa-money-bill-wave-alt:before {\n  content: \"\\f53b\"; }\n\n.fa-money-check:before {\n  content: \"\\f53c\"; }\n\n.fa-money-check-alt:before {\n  content: \"\\f53d\"; }\n\n.fa-monument:before {\n  content: \"\\f5a6\"; }\n\n.fa-moon:before {\n  content: \"\\f186\"; }\n\n.fa-mortar-pestle:before {\n  content: \"\\f5a7\"; }\n\n.fa-mosque:before {\n  content: \"\\f678\"; }\n\n.fa-motorcycle:before {\n  content: \"\\f21c\"; }\n\n.fa-mountain:before {\n  content: \"\\f6fc\"; }\n\n.fa-mouse-pointer:before {\n  content: \"\\f245\"; }\n\n.fa-mug-hot:before {\n  content: \"\\f7b6\"; }\n\n.fa-music:before {\n  content: \"\\f001\"; }\n\n.fa-napster:before {\n  content: \"\\f3d2\"; }\n\n.fa-neos:before {\n  content: \"\\f612\"; }\n\n.fa-network-wired:before {\n  content: \"\\f6ff\"; }\n\n.fa-neuter:before {\n  content: \"\\f22c\"; }\n\n.fa-newspaper:before {\n  content: \"\\f1ea\"; }\n\n.fa-nimblr:before {\n  content: \"\\f5a8\"; }\n\n.fa-node:before {\n  content: \"\\f419\"; }\n\n.fa-node-js:before {\n  content: \"\\f3d3\"; }\n\n.fa-not-equal:before {\n  content: \"\\f53e\"; }\n\n.fa-notes-medical:before {\n  content: \"\\f481\"; }\n\n.fa-npm:before {\n  content: \"\\f3d4\"; }\n\n.fa-ns8:before {\n  content: \"\\f3d5\"; }\n\n.fa-nutritionix:before {\n  content: \"\\f3d6\"; }\n\n.fa-object-group:before {\n  content: \"\\f247\"; }\n\n.fa-object-ungroup:before {\n  content: \"\\f248\"; }\n\n.fa-odnoklassniki:before {\n  content: \"\\f263\"; }\n\n.fa-odnoklassniki-square:before {\n  content: \"\\f264\"; }\n\n.fa-oil-can:before {\n  content: \"\\f613\"; }\n\n.fa-old-republic:before {\n  content: \"\\f510\"; }\n\n.fa-om:before {\n  content: \"\\f679\"; }\n\n.fa-opencart:before {\n  content: \"\\f23d\"; }\n\n.fa-openid:before {\n  content: \"\\f19b\"; }\n\n.fa-opera:before {\n  content: \"\\f26a\"; }\n\n.fa-optin-monster:before {\n  content: \"\\f23c\"; }\n\n.fa-osi:before {\n  content: \"\\f41a\"; }\n\n.fa-otter:before {\n  content: \"\\f700\"; }\n\n.fa-outdent:before {\n  content: \"\\f03b\"; }\n\n.fa-page4:before {\n  content: \"\\f3d7\"; }\n\n.fa-pagelines:before {\n  content: \"\\f18c\"; }\n\n.fa-pager:before {\n  content: \"\\f815\"; }\n\n.fa-paint-brush:before {\n  content: \"\\f1fc\"; }\n\n.fa-paint-roller:before {\n  content: \"\\f5aa\"; }\n\n.fa-palette:before {\n  content: \"\\f53f\"; }\n\n.fa-palfed:before {\n  content: \"\\f3d8\"; }\n\n.fa-pallet:before {\n  content: \"\\f482\"; }\n\n.fa-paper-plane:before {\n  content: \"\\f1d8\"; }\n\n.fa-paperclip:before {\n  content: \"\\f0c6\"; }\n\n.fa-parachute-box:before {\n  content: \"\\f4cd\"; }\n\n.fa-paragraph:before {\n  content: \"\\f1dd\"; }\n\n.fa-parking:before {\n  content: \"\\f540\"; }\n\n.fa-passport:before {\n  content: \"\\f5ab\"; }\n\n.fa-pastafarianism:before {\n  content: \"\\f67b\"; }\n\n.fa-paste:before {\n  content: \"\\f0ea\"; }\n\n.fa-patreon:before {\n  content: \"\\f3d9\"; }\n\n.fa-pause:before {\n  content: \"\\f04c\"; }\n\n.fa-pause-circle:before {\n  content: \"\\f28b\"; }\n\n.fa-paw:before {\n  content: \"\\f1b0\"; }\n\n.fa-paypal:before {\n  content: \"\\f1ed\"; }\n\n.fa-peace:before {\n  content: \"\\f67c\"; }\n\n.fa-pen:before {\n  content: \"\\f304\"; }\n\n.fa-pen-alt:before {\n  content: \"\\f305\"; }\n\n.fa-pen-fancy:before {\n  content: \"\\f5ac\"; }\n\n.fa-pen-nib:before {\n  content: \"\\f5ad\"; }\n\n.fa-pen-square:before {\n  content: \"\\f14b\"; }\n\n.fa-pencil-alt:before {\n  content: \"\\f303\"; }\n\n.fa-pencil-ruler:before {\n  content: \"\\f5ae\"; }\n\n.fa-penny-arcade:before {\n  content: \"\\f704\"; }\n\n.fa-people-carry:before {\n  content: \"\\f4ce\"; }\n\n.fa-pepper-hot:before {\n  content: \"\\f816\"; }\n\n.fa-percent:before {\n  content: \"\\f295\"; }\n\n.fa-percentage:before {\n  content: \"\\f541\"; }\n\n.fa-periscope:before {\n  content: \"\\f3da\"; }\n\n.fa-person-booth:before {\n  content: \"\\f756\"; }\n\n.fa-phabricator:before {\n  content: \"\\f3db\"; }\n\n.fa-phoenix-framework:before {\n  content: \"\\f3dc\"; }\n\n.fa-phoenix-squadron:before {\n  content: \"\\f511\"; }\n\n.fa-phone:before {\n  content: \"\\f095\"; }\n\n.fa-phone-alt:before {\n  content: \"\\f879\"; }\n\n.fa-phone-slash:before {\n  content: \"\\f3dd\"; }\n\n.fa-phone-square:before {\n  content: \"\\f098\"; }\n\n.fa-phone-square-alt:before {\n  content: \"\\f87b\"; }\n\n.fa-phone-volume:before {\n  content: \"\\f2a0\"; }\n\n.fa-photo-video:before {\n  content: \"\\f87c\"; }\n\n.fa-php:before {\n  content: \"\\f457\"; }\n\n.fa-pied-piper:before {\n  content: \"\\f2ae\"; }\n\n.fa-pied-piper-alt:before {\n  content: \"\\f1a8\"; }\n\n.fa-pied-piper-hat:before {\n  content: \"\\f4e5\"; }\n\n.fa-pied-piper-pp:before {\n  content: \"\\f1a7\"; }\n\n.fa-piggy-bank:before {\n  content: \"\\f4d3\"; }\n\n.fa-pills:before {\n  content: \"\\f484\"; }\n\n.fa-pinterest:before {\n  content: \"\\f0d2\"; }\n\n.fa-pinterest-p:before {\n  content: \"\\f231\"; }\n\n.fa-pinterest-square:before {\n  content: \"\\f0d3\"; }\n\n.fa-pizza-slice:before {\n  content: \"\\f818\"; }\n\n.fa-place-of-worship:before {\n  content: \"\\f67f\"; }\n\n.fa-plane:before {\n  content: \"\\f072\"; }\n\n.fa-plane-arrival:before {\n  content: \"\\f5af\"; }\n\n.fa-plane-departure:before {\n  content: \"\\f5b0\"; }\n\n.fa-play:before {\n  content: \"\\f04b\"; }\n\n.fa-play-circle:before {\n  content: \"\\f144\"; }\n\n.fa-playstation:before {\n  content: \"\\f3df\"; }\n\n.fa-plug:before {\n  content: \"\\f1e6\"; }\n\n.fa-plus:before {\n  content: \"\\f067\"; }\n\n.fa-plus-circle:before {\n  content: \"\\f055\"; }\n\n.fa-plus-square:before {\n  content: \"\\f0fe\"; }\n\n.fa-podcast:before {\n  content: \"\\f2ce\"; }\n\n.fa-poll:before {\n  content: \"\\f681\"; }\n\n.fa-poll-h:before {\n  content: \"\\f682\"; }\n\n.fa-poo:before {\n  content: \"\\f2fe\"; }\n\n.fa-poo-storm:before {\n  content: \"\\f75a\"; }\n\n.fa-poop:before {\n  content: \"\\f619\"; }\n\n.fa-portrait:before {\n  content: \"\\f3e0\"; }\n\n.fa-pound-sign:before {\n  content: \"\\f154\"; }\n\n.fa-power-off:before {\n  content: \"\\f011\"; }\n\n.fa-pray:before {\n  content: \"\\f683\"; }\n\n.fa-praying-hands:before {\n  content: \"\\f684\"; }\n\n.fa-prescription:before {\n  content: \"\\f5b1\"; }\n\n.fa-prescription-bottle:before {\n  content: \"\\f485\"; }\n\n.fa-prescription-bottle-alt:before {\n  content: \"\\f486\"; }\n\n.fa-print:before {\n  content: \"\\f02f\"; }\n\n.fa-procedures:before {\n  content: \"\\f487\"; }\n\n.fa-product-hunt:before {\n  content: \"\\f288\"; }\n\n.fa-project-diagram:before {\n  content: \"\\f542\"; }\n\n.fa-pushed:before {\n  content: \"\\f3e1\"; }\n\n.fa-puzzle-piece:before {\n  content: \"\\f12e\"; }\n\n.fa-python:before {\n  content: \"\\f3e2\"; }\n\n.fa-qq:before {\n  content: \"\\f1d6\"; }\n\n.fa-qrcode:before {\n  content: \"\\f029\"; }\n\n.fa-question:before {\n  content: \"\\f128\"; }\n\n.fa-question-circle:before {\n  content: \"\\f059\"; }\n\n.fa-quidditch:before {\n  content: \"\\f458\"; }\n\n.fa-quinscape:before {\n  content: \"\\f459\"; }\n\n.fa-quora:before {\n  content: \"\\f2c4\"; }\n\n.fa-quote-left:before {\n  content: \"\\f10d\"; }\n\n.fa-quote-right:before {\n  content: \"\\f10e\"; }\n\n.fa-quran:before {\n  content: \"\\f687\"; }\n\n.fa-r-project:before {\n  content: \"\\f4f7\"; }\n\n.fa-radiation:before {\n  content: \"\\f7b9\"; }\n\n.fa-radiation-alt:before {\n  content: \"\\f7ba\"; }\n\n.fa-rainbow:before {\n  content: \"\\f75b\"; }\n\n.fa-random:before {\n  content: \"\\f074\"; }\n\n.fa-raspberry-pi:before {\n  content: \"\\f7bb\"; }\n\n.fa-ravelry:before {\n  content: \"\\f2d9\"; }\n\n.fa-react:before {\n  content: \"\\f41b\"; }\n\n.fa-reacteurope:before {\n  content: \"\\f75d\"; }\n\n.fa-readme:before {\n  content: \"\\f4d5\"; }\n\n.fa-rebel:before {\n  content: \"\\f1d0\"; }\n\n.fa-receipt:before {\n  content: \"\\f543\"; }\n\n.fa-recycle:before {\n  content: \"\\f1b8\"; }\n\n.fa-red-river:before {\n  content: \"\\f3e3\"; }\n\n.fa-reddit:before {\n  content: \"\\f1a1\"; }\n\n.fa-reddit-alien:before {\n  content: \"\\f281\"; }\n\n.fa-reddit-square:before {\n  content: \"\\f1a2\"; }\n\n.fa-redhat:before {\n  content: \"\\f7bc\"; }\n\n.fa-redo:before {\n  content: \"\\f01e\"; }\n\n.fa-redo-alt:before {\n  content: \"\\f2f9\"; }\n\n.fa-registered:before {\n  content: \"\\f25d\"; }\n\n.fa-remove-format:before {\n  content: \"\\f87d\"; }\n\n.fa-renren:before {\n  content: \"\\f18b\"; }\n\n.fa-reply:before {\n  content: \"\\f3e5\"; }\n\n.fa-reply-all:before {\n  content: \"\\f122\"; }\n\n.fa-replyd:before {\n  content: \"\\f3e6\"; }\n\n.fa-republican:before {\n  content: \"\\f75e\"; }\n\n.fa-researchgate:before {\n  content: \"\\f4f8\"; }\n\n.fa-resolving:before {\n  content: \"\\f3e7\"; }\n\n.fa-restroom:before {\n  content: \"\\f7bd\"; }\n\n.fa-retweet:before {\n  content: \"\\f079\"; }\n\n.fa-rev:before {\n  content: \"\\f5b2\"; }\n\n.fa-ribbon:before {\n  content: \"\\f4d6\"; }\n\n.fa-ring:before {\n  content: \"\\f70b\"; }\n\n.fa-road:before {\n  content: \"\\f018\"; }\n\n.fa-robot:before {\n  content: \"\\f544\"; }\n\n.fa-rocket:before {\n  content: \"\\f135\"; }\n\n.fa-rocketchat:before {\n  content: \"\\f3e8\"; }\n\n.fa-rockrms:before {\n  content: \"\\f3e9\"; }\n\n.fa-route:before {\n  content: \"\\f4d7\"; }\n\n.fa-rss:before {\n  content: \"\\f09e\"; }\n\n.fa-rss-square:before {\n  content: \"\\f143\"; }\n\n.fa-ruble-sign:before {\n  content: \"\\f158\"; }\n\n.fa-ruler:before {\n  content: \"\\f545\"; }\n\n.fa-ruler-combined:before {\n  content: \"\\f546\"; }\n\n.fa-ruler-horizontal:before {\n  content: \"\\f547\"; }\n\n.fa-ruler-vertical:before {\n  content: \"\\f548\"; }\n\n.fa-running:before {\n  content: \"\\f70c\"; }\n\n.fa-rupee-sign:before {\n  content: \"\\f156\"; }\n\n.fa-sad-cry:before {\n  content: \"\\f5b3\"; }\n\n.fa-sad-tear:before {\n  content: \"\\f5b4\"; }\n\n.fa-safari:before {\n  content: \"\\f267\"; }\n\n.fa-salesforce:before {\n  content: \"\\f83b\"; }\n\n.fa-sass:before {\n  content: \"\\f41e\"; }\n\n.fa-satellite:before {\n  content: \"\\f7bf\"; }\n\n.fa-satellite-dish:before {\n  content: \"\\f7c0\"; }\n\n.fa-save:before {\n  content: \"\\f0c7\"; }\n\n.fa-schlix:before {\n  content: \"\\f3ea\"; }\n\n.fa-school:before {\n  content: \"\\f549\"; }\n\n.fa-screwdriver:before {\n  content: \"\\f54a\"; }\n\n.fa-scribd:before {\n  content: \"\\f28a\"; }\n\n.fa-scroll:before {\n  content: \"\\f70e\"; }\n\n.fa-sd-card:before {\n  content: \"\\f7c2\"; }\n\n.fa-search:before {\n  content: \"\\f002\"; }\n\n.fa-search-dollar:before {\n  content: \"\\f688\"; }\n\n.fa-search-location:before {\n  content: \"\\f689\"; }\n\n.fa-search-minus:before {\n  content: \"\\f010\"; }\n\n.fa-search-plus:before {\n  content: \"\\f00e\"; }\n\n.fa-searchengin:before {\n  content: \"\\f3eb\"; }\n\n.fa-seedling:before {\n  content: \"\\f4d8\"; }\n\n.fa-sellcast:before {\n  content: \"\\f2da\"; }\n\n.fa-sellsy:before {\n  content: \"\\f213\"; }\n\n.fa-server:before {\n  content: \"\\f233\"; }\n\n.fa-servicestack:before {\n  content: \"\\f3ec\"; }\n\n.fa-shapes:before {\n  content: \"\\f61f\"; }\n\n.fa-share:before {\n  content: \"\\f064\"; }\n\n.fa-share-alt:before {\n  content: \"\\f1e0\"; }\n\n.fa-share-alt-square:before {\n  content: \"\\f1e1\"; }\n\n.fa-share-square:before {\n  content: \"\\f14d\"; }\n\n.fa-shekel-sign:before {\n  content: \"\\f20b\"; }\n\n.fa-shield-alt:before {\n  content: \"\\f3ed\"; }\n\n.fa-ship:before {\n  content: \"\\f21a\"; }\n\n.fa-shipping-fast:before {\n  content: \"\\f48b\"; }\n\n.fa-shirtsinbulk:before {\n  content: \"\\f214\"; }\n\n.fa-shoe-prints:before {\n  content: \"\\f54b\"; }\n\n.fa-shopping-bag:before {\n  content: \"\\f290\"; }\n\n.fa-shopping-basket:before {\n  content: \"\\f291\"; }\n\n.fa-shopping-cart:before {\n  content: \"\\f07a\"; }\n\n.fa-shopware:before {\n  content: \"\\f5b5\"; }\n\n.fa-shower:before {\n  content: \"\\f2cc\"; }\n\n.fa-shuttle-van:before {\n  content: \"\\f5b6\"; }\n\n.fa-sign:before {\n  content: \"\\f4d9\"; }\n\n.fa-sign-in-alt:before {\n  content: \"\\f2f6\"; }\n\n.fa-sign-language:before {\n  content: \"\\f2a7\"; }\n\n.fa-sign-out-alt:before {\n  content: \"\\f2f5\"; }\n\n.fa-signal:before {\n  content: \"\\f012\"; }\n\n.fa-signature:before {\n  content: \"\\f5b7\"; }\n\n.fa-sim-card:before {\n  content: \"\\f7c4\"; }\n\n.fa-simplybuilt:before {\n  content: \"\\f215\"; }\n\n.fa-sistrix:before {\n  content: \"\\f3ee\"; }\n\n.fa-sitemap:before {\n  content: \"\\f0e8\"; }\n\n.fa-sith:before {\n  content: \"\\f512\"; }\n\n.fa-skating:before {\n  content: \"\\f7c5\"; }\n\n.fa-sketch:before {\n  content: \"\\f7c6\"; }\n\n.fa-skiing:before {\n  content: \"\\f7c9\"; }\n\n.fa-skiing-nordic:before {\n  content: \"\\f7ca\"; }\n\n.fa-skull:before {\n  content: \"\\f54c\"; }\n\n.fa-skull-crossbones:before {\n  content: \"\\f714\"; }\n\n.fa-skyatlas:before {\n  content: \"\\f216\"; }\n\n.fa-skype:before {\n  content: \"\\f17e\"; }\n\n.fa-slack:before {\n  content: \"\\f198\"; }\n\n.fa-slack-hash:before {\n  content: \"\\f3ef\"; }\n\n.fa-slash:before {\n  content: \"\\f715\"; }\n\n.fa-sleigh:before {\n  content: \"\\f7cc\"; }\n\n.fa-sliders-h:before {\n  content: \"\\f1de\"; }\n\n.fa-slideshare:before {\n  content: \"\\f1e7\"; }\n\n.fa-smile:before {\n  content: \"\\f118\"; }\n\n.fa-smile-beam:before {\n  content: \"\\f5b8\"; }\n\n.fa-smile-wink:before {\n  content: \"\\f4da\"; }\n\n.fa-smog:before {\n  content: \"\\f75f\"; }\n\n.fa-smoking:before {\n  content: \"\\f48d\"; }\n\n.fa-smoking-ban:before {\n  content: \"\\f54d\"; }\n\n.fa-sms:before {\n  content: \"\\f7cd\"; }\n\n.fa-snapchat:before {\n  content: \"\\f2ab\"; }\n\n.fa-snapchat-ghost:before {\n  content: \"\\f2ac\"; }\n\n.fa-snapchat-square:before {\n  content: \"\\f2ad\"; }\n\n.fa-snowboarding:before {\n  content: \"\\f7ce\"; }\n\n.fa-snowflake:before {\n  content: \"\\f2dc\"; }\n\n.fa-snowman:before {\n  content: \"\\f7d0\"; }\n\n.fa-snowplow:before {\n  content: \"\\f7d2\"; }\n\n.fa-socks:before {\n  content: \"\\f696\"; }\n\n.fa-solar-panel:before {\n  content: \"\\f5ba\"; }\n\n.fa-sort:before {\n  content: \"\\f0dc\"; }\n\n.fa-sort-alpha-down:before {\n  content: \"\\f15d\"; }\n\n.fa-sort-alpha-down-alt:before {\n  content: \"\\f881\"; }\n\n.fa-sort-alpha-up:before {\n  content: \"\\f15e\"; }\n\n.fa-sort-alpha-up-alt:before {\n  content: \"\\f882\"; }\n\n.fa-sort-amount-down:before {\n  content: \"\\f160\"; }\n\n.fa-sort-amount-down-alt:before {\n  content: \"\\f884\"; }\n\n.fa-sort-amount-up:before {\n  content: \"\\f161\"; }\n\n.fa-sort-amount-up-alt:before {\n  content: \"\\f885\"; }\n\n.fa-sort-down:before {\n  content: \"\\f0dd\"; }\n\n.fa-sort-numeric-down:before {\n  content: \"\\f162\"; }\n\n.fa-sort-numeric-down-alt:before {\n  content: \"\\f886\"; }\n\n.fa-sort-numeric-up:before {\n  content: \"\\f163\"; }\n\n.fa-sort-numeric-up-alt:before {\n  content: \"\\f887\"; }\n\n.fa-sort-up:before {\n  content: \"\\f0de\"; }\n\n.fa-soundcloud:before {\n  content: \"\\f1be\"; }\n\n.fa-sourcetree:before {\n  content: \"\\f7d3\"; }\n\n.fa-spa:before {\n  content: \"\\f5bb\"; }\n\n.fa-space-shuttle:before {\n  content: \"\\f197\"; }\n\n.fa-speakap:before {\n  content: \"\\f3f3\"; }\n\n.fa-speaker-deck:before {\n  content: \"\\f83c\"; }\n\n.fa-spell-check:before {\n  content: \"\\f891\"; }\n\n.fa-spider:before {\n  content: \"\\f717\"; }\n\n.fa-spinner:before {\n  content: \"\\f110\"; }\n\n.fa-splotch:before {\n  content: \"\\f5bc\"; }\n\n.fa-spotify:before {\n  content: \"\\f1bc\"; }\n\n.fa-spray-can:before {\n  content: \"\\f5bd\"; }\n\n.fa-square:before {\n  content: \"\\f0c8\"; }\n\n.fa-square-full:before {\n  content: \"\\f45c\"; }\n\n.fa-square-root-alt:before {\n  content: \"\\f698\"; }\n\n.fa-squarespace:before {\n  content: \"\\f5be\"; }\n\n.fa-stack-exchange:before {\n  content: \"\\f18d\"; }\n\n.fa-stack-overflow:before {\n  content: \"\\f16c\"; }\n\n.fa-stackpath:before {\n  content: \"\\f842\"; }\n\n.fa-stamp:before {\n  content: \"\\f5bf\"; }\n\n.fa-star:before {\n  content: \"\\f005\"; }\n\n.fa-star-and-crescent:before {\n  content: \"\\f699\"; }\n\n.fa-star-half:before {\n  content: \"\\f089\"; }\n\n.fa-star-half-alt:before {\n  content: \"\\f5c0\"; }\n\n.fa-star-of-david:before {\n  content: \"\\f69a\"; }\n\n.fa-star-of-life:before {\n  content: \"\\f621\"; }\n\n.fa-staylinked:before {\n  content: \"\\f3f5\"; }\n\n.fa-steam:before {\n  content: \"\\f1b6\"; }\n\n.fa-steam-square:before {\n  content: \"\\f1b7\"; }\n\n.fa-steam-symbol:before {\n  content: \"\\f3f6\"; }\n\n.fa-step-backward:before {\n  content: \"\\f048\"; }\n\n.fa-step-forward:before {\n  content: \"\\f051\"; }\n\n.fa-stethoscope:before {\n  content: \"\\f0f1\"; }\n\n.fa-sticker-mule:before {\n  content: \"\\f3f7\"; }\n\n.fa-sticky-note:before {\n  content: \"\\f249\"; }\n\n.fa-stop:before {\n  content: \"\\f04d\"; }\n\n.fa-stop-circle:before {\n  content: \"\\f28d\"; }\n\n.fa-stopwatch:before {\n  content: \"\\f2f2\"; }\n\n.fa-store:before {\n  content: \"\\f54e\"; }\n\n.fa-store-alt:before {\n  content: \"\\f54f\"; }\n\n.fa-strava:before {\n  content: \"\\f428\"; }\n\n.fa-stream:before {\n  content: \"\\f550\"; }\n\n.fa-street-view:before {\n  content: \"\\f21d\"; }\n\n.fa-strikethrough:before {\n  content: \"\\f0cc\"; }\n\n.fa-stripe:before {\n  content: \"\\f429\"; }\n\n.fa-stripe-s:before {\n  content: \"\\f42a\"; }\n\n.fa-stroopwafel:before {\n  content: \"\\f551\"; }\n\n.fa-studiovinari:before {\n  content: \"\\f3f8\"; }\n\n.fa-stumbleupon:before {\n  content: \"\\f1a4\"; }\n\n.fa-stumbleupon-circle:before {\n  content: \"\\f1a3\"; }\n\n.fa-subscript:before {\n  content: \"\\f12c\"; }\n\n.fa-subway:before {\n  content: \"\\f239\"; }\n\n.fa-suitcase:before {\n  content: \"\\f0f2\"; }\n\n.fa-suitcase-rolling:before {\n  content: \"\\f5c1\"; }\n\n.fa-sun:before {\n  content: \"\\f185\"; }\n\n.fa-superpowers:before {\n  content: \"\\f2dd\"; }\n\n.fa-superscript:before {\n  content: \"\\f12b\"; }\n\n.fa-supple:before {\n  content: \"\\f3f9\"; }\n\n.fa-surprise:before {\n  content: \"\\f5c2\"; }\n\n.fa-suse:before {\n  content: \"\\f7d6\"; }\n\n.fa-swatchbook:before {\n  content: \"\\f5c3\"; }\n\n.fa-swimmer:before {\n  content: \"\\f5c4\"; }\n\n.fa-swimming-pool:before {\n  content: \"\\f5c5\"; }\n\n.fa-symfony:before {\n  content: \"\\f83d\"; }\n\n.fa-synagogue:before {\n  content: \"\\f69b\"; }\n\n.fa-sync:before {\n  content: \"\\f021\"; }\n\n.fa-sync-alt:before {\n  content: \"\\f2f1\"; }\n\n.fa-syringe:before {\n  content: \"\\f48e\"; }\n\n.fa-table:before {\n  content: \"\\f0ce\"; }\n\n.fa-table-tennis:before {\n  content: \"\\f45d\"; }\n\n.fa-tablet:before {\n  content: \"\\f10a\"; }\n\n.fa-tablet-alt:before {\n  content: \"\\f3fa\"; }\n\n.fa-tablets:before {\n  content: \"\\f490\"; }\n\n.fa-tachometer-alt:before {\n  content: \"\\f3fd\"; }\n\n.fa-tag:before {\n  content: \"\\f02b\"; }\n\n.fa-tags:before {\n  content: \"\\f02c\"; }\n\n.fa-tape:before {\n  content: \"\\f4db\"; }\n\n.fa-tasks:before {\n  content: \"\\f0ae\"; }\n\n.fa-taxi:before {\n  content: \"\\f1ba\"; }\n\n.fa-teamspeak:before {\n  content: \"\\f4f9\"; }\n\n.fa-teeth:before {\n  content: \"\\f62e\"; }\n\n.fa-teeth-open:before {\n  content: \"\\f62f\"; }\n\n.fa-telegram:before {\n  content: \"\\f2c6\"; }\n\n.fa-telegram-plane:before {\n  content: \"\\f3fe\"; }\n\n.fa-temperature-high:before {\n  content: \"\\f769\"; }\n\n.fa-temperature-low:before {\n  content: \"\\f76b\"; }\n\n.fa-tencent-weibo:before {\n  content: \"\\f1d5\"; }\n\n.fa-tenge:before {\n  content: \"\\f7d7\"; }\n\n.fa-terminal:before {\n  content: \"\\f120\"; }\n\n.fa-text-height:before {\n  content: \"\\f034\"; }\n\n.fa-text-width:before {\n  content: \"\\f035\"; }\n\n.fa-th:before {\n  content: \"\\f00a\"; }\n\n.fa-th-large:before {\n  content: \"\\f009\"; }\n\n.fa-th-list:before {\n  content: \"\\f00b\"; }\n\n.fa-the-red-yeti:before {\n  content: \"\\f69d\"; }\n\n.fa-theater-masks:before {\n  content: \"\\f630\"; }\n\n.fa-themeco:before {\n  content: \"\\f5c6\"; }\n\n.fa-themeisle:before {\n  content: \"\\f2b2\"; }\n\n.fa-thermometer:before {\n  content: \"\\f491\"; }\n\n.fa-thermometer-empty:before {\n  content: \"\\f2cb\"; }\n\n.fa-thermometer-full:before {\n  content: \"\\f2c7\"; }\n\n.fa-thermometer-half:before {\n  content: \"\\f2c9\"; }\n\n.fa-thermometer-quarter:before {\n  content: \"\\f2ca\"; }\n\n.fa-thermometer-three-quarters:before {\n  content: \"\\f2c8\"; }\n\n.fa-think-peaks:before {\n  content: \"\\f731\"; }\n\n.fa-thumbs-down:before {\n  content: \"\\f165\"; }\n\n.fa-thumbs-up:before {\n  content: \"\\f164\"; }\n\n.fa-thumbtack:before {\n  content: \"\\f08d\"; }\n\n.fa-ticket-alt:before {\n  content: \"\\f3ff\"; }\n\n.fa-times:before {\n  content: \"\\f00d\"; }\n\n.fa-times-circle:before {\n  content: \"\\f057\"; }\n\n.fa-tint:before {\n  content: \"\\f043\"; }\n\n.fa-tint-slash:before {\n  content: \"\\f5c7\"; }\n\n.fa-tired:before {\n  content: \"\\f5c8\"; }\n\n.fa-toggle-off:before {\n  content: \"\\f204\"; }\n\n.fa-toggle-on:before {\n  content: \"\\f205\"; }\n\n.fa-toilet:before {\n  content: \"\\f7d8\"; }\n\n.fa-toilet-paper:before {\n  content: \"\\f71e\"; }\n\n.fa-toolbox:before {\n  content: \"\\f552\"; }\n\n.fa-tools:before {\n  content: \"\\f7d9\"; }\n\n.fa-tooth:before {\n  content: \"\\f5c9\"; }\n\n.fa-torah:before {\n  content: \"\\f6a0\"; }\n\n.fa-torii-gate:before {\n  content: \"\\f6a1\"; }\n\n.fa-tractor:before {\n  content: \"\\f722\"; }\n\n.fa-trade-federation:before {\n  content: \"\\f513\"; }\n\n.fa-trademark:before {\n  content: \"\\f25c\"; }\n\n.fa-traffic-light:before {\n  content: \"\\f637\"; }\n\n.fa-train:before {\n  content: \"\\f238\"; }\n\n.fa-tram:before {\n  content: \"\\f7da\"; }\n\n.fa-transgender:before {\n  content: \"\\f224\"; }\n\n.fa-transgender-alt:before {\n  content: \"\\f225\"; }\n\n.fa-trash:before {\n  content: \"\\f1f8\"; }\n\n.fa-trash-alt:before {\n  content: \"\\f2ed\"; }\n\n.fa-trash-restore:before {\n  content: \"\\f829\"; }\n\n.fa-trash-restore-alt:before {\n  content: \"\\f82a\"; }\n\n.fa-tree:before {\n  content: \"\\f1bb\"; }\n\n.fa-trello:before {\n  content: \"\\f181\"; }\n\n.fa-tripadvisor:before {\n  content: \"\\f262\"; }\n\n.fa-trophy:before {\n  content: \"\\f091\"; }\n\n.fa-truck:before {\n  content: \"\\f0d1\"; }\n\n.fa-truck-loading:before {\n  content: \"\\f4de\"; }\n\n.fa-truck-monster:before {\n  content: \"\\f63b\"; }\n\n.fa-truck-moving:before {\n  content: \"\\f4df\"; }\n\n.fa-truck-pickup:before {\n  content: \"\\f63c\"; }\n\n.fa-tshirt:before {\n  content: \"\\f553\"; }\n\n.fa-tty:before {\n  content: \"\\f1e4\"; }\n\n.fa-tumblr:before {\n  content: \"\\f173\"; }\n\n.fa-tumblr-square:before {\n  content: \"\\f174\"; }\n\n.fa-tv:before {\n  content: \"\\f26c\"; }\n\n.fa-twitch:before {\n  content: \"\\f1e8\"; }\n\n.fa-twitter:before {\n  content: \"\\f099\"; }\n\n.fa-twitter-square:before {\n  content: \"\\f081\"; }\n\n.fa-typo3:before {\n  content: \"\\f42b\"; }\n\n.fa-uber:before {\n  content: \"\\f402\"; }\n\n.fa-ubuntu:before {\n  content: \"\\f7df\"; }\n\n.fa-uikit:before {\n  content: \"\\f403\"; }\n\n.fa-umbrella:before {\n  content: \"\\f0e9\"; }\n\n.fa-umbrella-beach:before {\n  content: \"\\f5ca\"; }\n\n.fa-underline:before {\n  content: \"\\f0cd\"; }\n\n.fa-undo:before {\n  content: \"\\f0e2\"; }\n\n.fa-undo-alt:before {\n  content: \"\\f2ea\"; }\n\n.fa-uniregistry:before {\n  content: \"\\f404\"; }\n\n.fa-universal-access:before {\n  content: \"\\f29a\"; }\n\n.fa-university:before {\n  content: \"\\f19c\"; }\n\n.fa-unlink:before {\n  content: \"\\f127\"; }\n\n.fa-unlock:before {\n  content: \"\\f09c\"; }\n\n.fa-unlock-alt:before {\n  content: \"\\f13e\"; }\n\n.fa-untappd:before {\n  content: \"\\f405\"; }\n\n.fa-upload:before {\n  content: \"\\f093\"; }\n\n.fa-ups:before {\n  content: \"\\f7e0\"; }\n\n.fa-usb:before {\n  content: \"\\f287\"; }\n\n.fa-user:before {\n  content: \"\\f007\"; }\n\n.fa-user-alt:before {\n  content: \"\\f406\"; }\n\n.fa-user-alt-slash:before {\n  content: \"\\f4fa\"; }\n\n.fa-user-astronaut:before {\n  content: \"\\f4fb\"; }\n\n.fa-user-check:before {\n  content: \"\\f4fc\"; }\n\n.fa-user-circle:before {\n  content: \"\\f2bd\"; }\n\n.fa-user-clock:before {\n  content: \"\\f4fd\"; }\n\n.fa-user-cog:before {\n  content: \"\\f4fe\"; }\n\n.fa-user-edit:before {\n  content: \"\\f4ff\"; }\n\n.fa-user-friends:before {\n  content: \"\\f500\"; }\n\n.fa-user-graduate:before {\n  content: \"\\f501\"; }\n\n.fa-user-injured:before {\n  content: \"\\f728\"; }\n\n.fa-user-lock:before {\n  content: \"\\f502\"; }\n\n.fa-user-md:before {\n  content: \"\\f0f0\"; }\n\n.fa-user-minus:before {\n  content: \"\\f503\"; }\n\n.fa-user-ninja:before {\n  content: \"\\f504\"; }\n\n.fa-user-nurse:before {\n  content: \"\\f82f\"; }\n\n.fa-user-plus:before {\n  content: \"\\f234\"; }\n\n.fa-user-secret:before {\n  content: \"\\f21b\"; }\n\n.fa-user-shield:before {\n  content: \"\\f505\"; }\n\n.fa-user-slash:before {\n  content: \"\\f506\"; }\n\n.fa-user-tag:before {\n  content: \"\\f507\"; }\n\n.fa-user-tie:before {\n  content: \"\\f508\"; }\n\n.fa-user-times:before {\n  content: \"\\f235\"; }\n\n.fa-users:before {\n  content: \"\\f0c0\"; }\n\n.fa-users-cog:before {\n  content: \"\\f509\"; }\n\n.fa-usps:before {\n  content: \"\\f7e1\"; }\n\n.fa-ussunnah:before {\n  content: \"\\f407\"; }\n\n.fa-utensil-spoon:before {\n  content: \"\\f2e5\"; }\n\n.fa-utensils:before {\n  content: \"\\f2e7\"; }\n\n.fa-vaadin:before {\n  content: \"\\f408\"; }\n\n.fa-vector-square:before {\n  content: \"\\f5cb\"; }\n\n.fa-venus:before {\n  content: \"\\f221\"; }\n\n.fa-venus-double:before {\n  content: \"\\f226\"; }\n\n.fa-venus-mars:before {\n  content: \"\\f228\"; }\n\n.fa-viacoin:before {\n  content: \"\\f237\"; }\n\n.fa-viadeo:before {\n  content: \"\\f2a9\"; }\n\n.fa-viadeo-square:before {\n  content: \"\\f2aa\"; }\n\n.fa-vial:before {\n  content: \"\\f492\"; }\n\n.fa-vials:before {\n  content: \"\\f493\"; }\n\n.fa-viber:before {\n  content: \"\\f409\"; }\n\n.fa-video:before {\n  content: \"\\f03d\"; }\n\n.fa-video-slash:before {\n  content: \"\\f4e2\"; }\n\n.fa-vihara:before {\n  content: \"\\f6a7\"; }\n\n.fa-vimeo:before {\n  content: \"\\f40a\"; }\n\n.fa-vimeo-square:before {\n  content: \"\\f194\"; }\n\n.fa-vimeo-v:before {\n  content: \"\\f27d\"; }\n\n.fa-vine:before {\n  content: \"\\f1ca\"; }\n\n.fa-vk:before {\n  content: \"\\f189\"; }\n\n.fa-vnv:before {\n  content: \"\\f40b\"; }\n\n.fa-voicemail:before {\n  content: \"\\f897\"; }\n\n.fa-volleyball-ball:before {\n  content: \"\\f45f\"; }\n\n.fa-volume-down:before {\n  content: \"\\f027\"; }\n\n.fa-volume-mute:before {\n  content: \"\\f6a9\"; }\n\n.fa-volume-off:before {\n  content: \"\\f026\"; }\n\n.fa-volume-up:before {\n  content: \"\\f028\"; }\n\n.fa-vote-yea:before {\n  content: \"\\f772\"; }\n\n.fa-vr-cardboard:before {\n  content: \"\\f729\"; }\n\n.fa-vuejs:before {\n  content: \"\\f41f\"; }\n\n.fa-walking:before {\n  content: \"\\f554\"; }\n\n.fa-wallet:before {\n  content: \"\\f555\"; }\n\n.fa-warehouse:before {\n  content: \"\\f494\"; }\n\n.fa-water:before {\n  content: \"\\f773\"; }\n\n.fa-wave-square:before {\n  content: \"\\f83e\"; }\n\n.fa-waze:before {\n  content: \"\\f83f\"; }\n\n.fa-weebly:before {\n  content: \"\\f5cc\"; }\n\n.fa-weibo:before {\n  content: \"\\f18a\"; }\n\n.fa-weight:before {\n  content: \"\\f496\"; }\n\n.fa-weight-hanging:before {\n  content: \"\\f5cd\"; }\n\n.fa-weixin:before {\n  content: \"\\f1d7\"; }\n\n.fa-whatsapp:before {\n  content: \"\\f232\"; }\n\n.fa-whatsapp-square:before {\n  content: \"\\f40c\"; }\n\n.fa-wheelchair:before {\n  content: \"\\f193\"; }\n\n.fa-whmcs:before {\n  content: \"\\f40d\"; }\n\n.fa-wifi:before {\n  content: \"\\f1eb\"; }\n\n.fa-wikipedia-w:before {\n  content: \"\\f266\"; }\n\n.fa-wind:before {\n  content: \"\\f72e\"; }\n\n.fa-window-close:before {\n  content: \"\\f410\"; }\n\n.fa-window-maximize:before {\n  content: \"\\f2d0\"; }\n\n.fa-window-minimize:before {\n  content: \"\\f2d1\"; }\n\n.fa-window-restore:before {\n  content: \"\\f2d2\"; }\n\n.fa-windows:before {\n  content: \"\\f17a\"; }\n\n.fa-wine-bottle:before {\n  content: \"\\f72f\"; }\n\n.fa-wine-glass:before {\n  content: \"\\f4e3\"; }\n\n.fa-wine-glass-alt:before {\n  content: \"\\f5ce\"; }\n\n.fa-wix:before {\n  content: \"\\f5cf\"; }\n\n.fa-wizards-of-the-coast:before {\n  content: \"\\f730\"; }\n\n.fa-wolf-pack-battalion:before {\n  content: \"\\f514\"; }\n\n.fa-won-sign:before {\n  content: \"\\f159\"; }\n\n.fa-wordpress:before {\n  content: \"\\f19a\"; }\n\n.fa-wordpress-simple:before {\n  content: \"\\f411\"; }\n\n.fa-wpbeginner:before {\n  content: \"\\f297\"; }\n\n.fa-wpexplorer:before {\n  content: \"\\f2de\"; }\n\n.fa-wpforms:before {\n  content: \"\\f298\"; }\n\n.fa-wpressr:before {\n  content: \"\\f3e4\"; }\n\n.fa-wrench:before {\n  content: \"\\f0ad\"; }\n\n.fa-x-ray:before {\n  content: \"\\f497\"; }\n\n.fa-xbox:before {\n  content: \"\\f412\"; }\n\n.fa-xing:before {\n  content: \"\\f168\"; }\n\n.fa-xing-square:before {\n  content: \"\\f169\"; }\n\n.fa-y-combinator:before {\n  content: \"\\f23b\"; }\n\n.fa-yahoo:before {\n  content: \"\\f19e\"; }\n\n.fa-yammer:before {\n  content: \"\\f840\"; }\n\n.fa-yandex:before {\n  content: \"\\f413\"; }\n\n.fa-yandex-international:before {\n  content: \"\\f414\"; }\n\n.fa-yarn:before {\n  content: \"\\f7e3\"; }\n\n.fa-yelp:before {\n  content: \"\\f1e9\"; }\n\n.fa-yen-sign:before {\n  content: \"\\f157\"; }\n\n.fa-yin-yang:before {\n  content: \"\\f6ad\"; }\n\n.fa-yoast:before {\n  content: \"\\f2b1\"; }\n\n.fa-youtube:before {\n  content: \"\\f167\"; }\n\n.fa-youtube-square:before {\n  content: \"\\f431\"; }\n\n.fa-zhihu:before {\n  content: \"\\f63f\"; }\n\n.sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px; }\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  clip: auto;\n  height: auto;\n  margin: 0;\n  overflow: visible;\n  position: static;\n  width: auto; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/regular.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: auto;\n  src: url(\"../webfonts/fa-regular-400.eot\");\n  src: url(\"../webfonts/fa-regular-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-regular-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-regular-400.woff\") format(\"woff\"), url(\"../webfonts/fa-regular-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-regular-400.svg#fontawesome\") format(\"svg\"); }\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/solid.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: auto;\n  src: url(\"../webfonts/fa-solid-900.eot\");\n  src: url(\"../webfonts/fa-solid-900.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-solid-900.woff2\") format(\"woff2\"), url(\"../webfonts/fa-solid-900.woff\") format(\"woff\"), url(\"../webfonts/fa-solid-900.ttf\") format(\"truetype\"), url(\"../webfonts/fa-solid-900.svg#fontawesome\") format(\"svg\"); }\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/svg-with-js.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\nsvg:not(:root).svg-inline--fa {\n  overflow: visible; }\n\n.svg-inline--fa {\n  display: inline-block;\n  font-size: inherit;\n  height: 1em;\n  overflow: visible;\n  vertical-align: -.125em; }\n  .svg-inline--fa.fa-lg {\n    vertical-align: -.225em; }\n  .svg-inline--fa.fa-w-1 {\n    width: 0.0625em; }\n  .svg-inline--fa.fa-w-2 {\n    width: 0.125em; }\n  .svg-inline--fa.fa-w-3 {\n    width: 0.1875em; }\n  .svg-inline--fa.fa-w-4 {\n    width: 0.25em; }\n  .svg-inline--fa.fa-w-5 {\n    width: 0.3125em; }\n  .svg-inline--fa.fa-w-6 {\n    width: 0.375em; }\n  .svg-inline--fa.fa-w-7 {\n    width: 0.4375em; }\n  .svg-inline--fa.fa-w-8 {\n    width: 0.5em; }\n  .svg-inline--fa.fa-w-9 {\n    width: 0.5625em; }\n  .svg-inline--fa.fa-w-10 {\n    width: 0.625em; }\n  .svg-inline--fa.fa-w-11 {\n    width: 0.6875em; }\n  .svg-inline--fa.fa-w-12 {\n    width: 0.75em; }\n  .svg-inline--fa.fa-w-13 {\n    width: 0.8125em; }\n  .svg-inline--fa.fa-w-14 {\n    width: 0.875em; }\n  .svg-inline--fa.fa-w-15 {\n    width: 0.9375em; }\n  .svg-inline--fa.fa-w-16 {\n    width: 1em; }\n  .svg-inline--fa.fa-w-17 {\n    width: 1.0625em; }\n  .svg-inline--fa.fa-w-18 {\n    width: 1.125em; }\n  .svg-inline--fa.fa-w-19 {\n    width: 1.1875em; }\n  .svg-inline--fa.fa-w-20 {\n    width: 1.25em; }\n  .svg-inline--fa.fa-pull-left {\n    margin-right: .3em;\n    width: auto; }\n  .svg-inline--fa.fa-pull-right {\n    margin-left: .3em;\n    width: auto; }\n  .svg-inline--fa.fa-border {\n    height: 1.5em; }\n  .svg-inline--fa.fa-li {\n    width: 2em; }\n  .svg-inline--fa.fa-fw {\n    width: 1.25em; }\n\n.fa-layers svg.svg-inline--fa {\n  bottom: 0;\n  left: 0;\n  margin: auto;\n  position: absolute;\n  right: 0;\n  top: 0; }\n\n.fa-layers {\n  display: inline-block;\n  height: 1em;\n  position: relative;\n  text-align: center;\n  vertical-align: -.125em;\n  width: 1em; }\n  .fa-layers svg.svg-inline--fa {\n    -webkit-transform-origin: center center;\n            transform-origin: center center; }\n\n.fa-layers-text, .fa-layers-counter {\n  display: inline-block;\n  position: absolute;\n  text-align: center; }\n\n.fa-layers-text {\n  left: 50%;\n  top: 50%;\n  -webkit-transform: translate(-50%, -50%);\n          transform: translate(-50%, -50%);\n  -webkit-transform-origin: center center;\n          transform-origin: center center; }\n\n.fa-layers-counter {\n  background-color: #ff253a;\n  border-radius: 1em;\n  -webkit-box-sizing: border-box;\n          box-sizing: border-box;\n  color: #fff;\n  height: 1.5em;\n  line-height: 1;\n  max-width: 5em;\n  min-width: 1.5em;\n  overflow: hidden;\n  padding: .25em;\n  right: 0;\n  text-overflow: ellipsis;\n  top: 0;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: top right;\n          transform-origin: top right; }\n\n.fa-layers-bottom-right {\n  bottom: 0;\n  right: 0;\n  top: auto;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: bottom right;\n          transform-origin: bottom right; }\n\n.fa-layers-bottom-left {\n  bottom: 0;\n  left: 0;\n  right: auto;\n  top: auto;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: bottom left;\n          transform-origin: bottom left; }\n\n.fa-layers-top-right {\n  right: 0;\n  top: 0;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: top right;\n          transform-origin: top right; }\n\n.fa-layers-top-left {\n  left: 0;\n  right: auto;\n  top: 0;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: top left;\n          transform-origin: top left; }\n\n.fa-lg {\n  font-size: 1.33333em;\n  line-height: 0.75em;\n  vertical-align: -.0667em; }\n\n.fa-xs {\n  font-size: .75em; }\n\n.fa-sm {\n  font-size: .875em; }\n\n.fa-1x {\n  font-size: 1em; }\n\n.fa-2x {\n  font-size: 2em; }\n\n.fa-3x {\n  font-size: 3em; }\n\n.fa-4x {\n  font-size: 4em; }\n\n.fa-5x {\n  font-size: 5em; }\n\n.fa-6x {\n  font-size: 6em; }\n\n.fa-7x {\n  font-size: 7em; }\n\n.fa-8x {\n  font-size: 8em; }\n\n.fa-9x {\n  font-size: 9em; }\n\n.fa-10x {\n  font-size: 10em; }\n\n.fa-fw {\n  text-align: center;\n  width: 1.25em; }\n\n.fa-ul {\n  list-style-type: none;\n  margin-left: 2.5em;\n  padding-left: 0; }\n  .fa-ul > li {\n    position: relative; }\n\n.fa-li {\n  left: -2em;\n  position: absolute;\n  text-align: center;\n  width: 2em;\n  line-height: inherit; }\n\n.fa-border {\n  border: solid 0.08em #eee;\n  border-radius: .1em;\n  padding: .2em .25em .15em; }\n\n.fa-pull-left {\n  float: left; }\n\n.fa-pull-right {\n  float: right; }\n\n.fa.fa-pull-left,\n.fas.fa-pull-left,\n.far.fa-pull-left,\n.fal.fa-pull-left,\n.fab.fa-pull-left {\n  margin-right: .3em; }\n\n.fa.fa-pull-right,\n.fas.fa-pull-right,\n.far.fa-pull-right,\n.fal.fa-pull-right,\n.fab.fa-pull-right {\n  margin-left: .3em; }\n\n.fa-spin {\n  -webkit-animation: fa-spin 2s infinite linear;\n          animation: fa-spin 2s infinite linear; }\n\n.fa-pulse {\n  -webkit-animation: fa-spin 1s infinite steps(8);\n          animation: fa-spin 1s infinite steps(8); }\n\n@-webkit-keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n@keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n.fa-rotate-90 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)\";\n  -webkit-transform: rotate(90deg);\n          transform: rotate(90deg); }\n\n.fa-rotate-180 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)\";\n  -webkit-transform: rotate(180deg);\n          transform: rotate(180deg); }\n\n.fa-rotate-270 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)\";\n  -webkit-transform: rotate(270deg);\n          transform: rotate(270deg); }\n\n.fa-flip-horizontal {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)\";\n  -webkit-transform: scale(-1, 1);\n          transform: scale(-1, 1); }\n\n.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(1, -1);\n          transform: scale(1, -1); }\n\n.fa-flip-both, .fa-flip-horizontal.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(-1, -1);\n          transform: scale(-1, -1); }\n\n:root .fa-rotate-90,\n:root .fa-rotate-180,\n:root .fa-rotate-270,\n:root .fa-flip-horizontal,\n:root .fa-flip-vertical,\n:root .fa-flip-both {\n  -webkit-filter: none;\n          filter: none; }\n\n.fa-stack {\n  display: inline-block;\n  height: 2em;\n  position: relative;\n  width: 2.5em; }\n\n.fa-stack-1x,\n.fa-stack-2x {\n  bottom: 0;\n  left: 0;\n  margin: auto;\n  position: absolute;\n  right: 0;\n  top: 0; }\n\n.svg-inline--fa.fa-stack-1x {\n  height: 1em;\n  width: 1.25em; }\n\n.svg-inline--fa.fa-stack-2x {\n  height: 2em;\n  width: 2.5em; }\n\n.fa-inverse {\n  color: #fff; }\n\n.sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px; }\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  clip: auto;\n  height: auto;\n  margin: 0;\n  overflow: visible;\n  position: static;\n  width: auto; }\n\n.svg-inline--fa .fa-primary {\n  fill: var(--fa-primary-color, currentColor);\n  opacity: 1;\n  opacity: var(--fa-primary-opacity, 1); }\n\n.svg-inline--fa .fa-secondary {\n  fill: var(--fa-secondary-color, currentColor);\n  opacity: 0.4;\n  opacity: var(--fa-secondary-opacity, 0.4); }\n\n.svg-inline--fa.fa-swap-opacity .fa-primary {\n  opacity: 0.4;\n  opacity: var(--fa-secondary-opacity, 0.4); }\n\n.svg-inline--fa.fa-swap-opacity .fa-secondary {\n  opacity: 1;\n  opacity: var(--fa-primary-opacity, 1); }\n\n.svg-inline--fa mask .fa-primary,\n.svg-inline--fa mask .fa-secondary {\n  fill: black; }\n\n.fad.fa-inverse {\n  color: #fff; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/v4-shims.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n.fa.fa-glass:before {\n  content: \"\\f000\"; }\n\n.fa.fa-meetup {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-star-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-o:before {\n  content: \"\\f005\"; }\n\n.fa.fa-remove:before {\n  content: \"\\f00d\"; }\n\n.fa.fa-close:before {\n  content: \"\\f00d\"; }\n\n.fa.fa-gear:before {\n  content: \"\\f013\"; }\n\n.fa.fa-trash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-trash-o:before {\n  content: \"\\f2ed\"; }\n\n.fa.fa-file-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-o:before {\n  content: \"\\f15b\"; }\n\n.fa.fa-clock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-clock-o:before {\n  content: \"\\f017\"; }\n\n.fa.fa-arrow-circle-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-down:before {\n  content: \"\\f358\"; }\n\n.fa.fa-arrow-circle-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-up:before {\n  content: \"\\f35b\"; }\n\n.fa.fa-play-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-play-circle-o:before {\n  content: \"\\f144\"; }\n\n.fa.fa-repeat:before {\n  content: \"\\f01e\"; }\n\n.fa.fa-rotate-right:before {\n  content: \"\\f01e\"; }\n\n.fa.fa-refresh:before {\n  content: \"\\f021\"; }\n\n.fa.fa-list-alt {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-dedent:before {\n  content: \"\\f03b\"; }\n\n.fa.fa-video-camera:before {\n  content: \"\\f03d\"; }\n\n.fa.fa-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-picture-o:before {\n  content: \"\\f03e\"; }\n\n.fa.fa-photo {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-photo:before {\n  content: \"\\f03e\"; }\n\n.fa.fa-image {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-image:before {\n  content: \"\\f03e\"; }\n\n.fa.fa-pencil:before {\n  content: \"\\f303\"; }\n\n.fa.fa-map-marker:before {\n  content: \"\\f3c5\"; }\n\n.fa.fa-pencil-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-pencil-square-o:before {\n  content: \"\\f044\"; }\n\n.fa.fa-share-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-share-square-o:before {\n  content: \"\\f14d\"; }\n\n.fa.fa-check-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-check-square-o:before {\n  content: \"\\f14a\"; }\n\n.fa.fa-arrows:before {\n  content: \"\\f0b2\"; }\n\n.fa.fa-times-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-times-circle-o:before {\n  content: \"\\f057\"; }\n\n.fa.fa-check-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-check-circle-o:before {\n  content: \"\\f058\"; }\n\n.fa.fa-mail-forward:before {\n  content: \"\\f064\"; }\n\n.fa.fa-eye {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-eye-slash {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-warning:before {\n  content: \"\\f071\"; }\n\n.fa.fa-calendar:before {\n  content: \"\\f073\"; }\n\n.fa.fa-arrows-v:before {\n  content: \"\\f338\"; }\n\n.fa.fa-arrows-h:before {\n  content: \"\\f337\"; }\n\n.fa.fa-bar-chart {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bar-chart:before {\n  content: \"\\f080\"; }\n\n.fa.fa-bar-chart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bar-chart-o:before {\n  content: \"\\f080\"; }\n\n.fa.fa-twitter-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gears:before {\n  content: \"\\f085\"; }\n\n.fa.fa-thumbs-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-thumbs-o-up:before {\n  content: \"\\f164\"; }\n\n.fa.fa-thumbs-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-thumbs-o-down:before {\n  content: \"\\f165\"; }\n\n.fa.fa-heart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-heart-o:before {\n  content: \"\\f004\"; }\n\n.fa.fa-sign-out:before {\n  content: \"\\f2f5\"; }\n\n.fa.fa-linkedin-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-linkedin-square:before {\n  content: \"\\f08c\"; }\n\n.fa.fa-thumb-tack:before {\n  content: \"\\f08d\"; }\n\n.fa.fa-external-link:before {\n  content: \"\\f35d\"; }\n\n.fa.fa-sign-in:before {\n  content: \"\\f2f6\"; }\n\n.fa.fa-github-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-lemon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-lemon-o:before {\n  content: \"\\f094\"; }\n\n.fa.fa-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-square-o:before {\n  content: \"\\f0c8\"; }\n\n.fa.fa-bookmark-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bookmark-o:before {\n  content: \"\\f02e\"; }\n\n.fa.fa-twitter {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook:before {\n  content: \"\\f39e\"; }\n\n.fa.fa-facebook-f {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook-f:before {\n  content: \"\\f39e\"; }\n\n.fa.fa-github {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-credit-card {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-feed:before {\n  content: \"\\f09e\"; }\n\n.fa.fa-hdd-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hdd-o:before {\n  content: \"\\f0a0\"; }\n\n.fa.fa-hand-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-right:before {\n  content: \"\\f0a4\"; }\n\n.fa.fa-hand-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-left:before {\n  content: \"\\f0a5\"; }\n\n.fa.fa-hand-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-up:before {\n  content: \"\\f0a6\"; }\n\n.fa.fa-hand-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-down:before {\n  content: \"\\f0a7\"; }\n\n.fa.fa-arrows-alt:before {\n  content: \"\\f31e\"; }\n\n.fa.fa-group:before {\n  content: \"\\f0c0\"; }\n\n.fa.fa-chain:before {\n  content: \"\\f0c1\"; }\n\n.fa.fa-scissors:before {\n  content: \"\\f0c4\"; }\n\n.fa.fa-files-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-files-o:before {\n  content: \"\\f0c5\"; }\n\n.fa.fa-floppy-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-floppy-o:before {\n  content: \"\\f0c7\"; }\n\n.fa.fa-navicon:before {\n  content: \"\\f0c9\"; }\n\n.fa.fa-reorder:before {\n  content: \"\\f0c9\"; }\n\n.fa.fa-pinterest {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pinterest-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus:before {\n  content: \"\\f0d5\"; }\n\n.fa.fa-money {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-money:before {\n  content: \"\\f3d1\"; }\n\n.fa.fa-unsorted:before {\n  content: \"\\f0dc\"; }\n\n.fa.fa-sort-desc:before {\n  content: \"\\f0dd\"; }\n\n.fa.fa-sort-asc:before {\n  content: \"\\f0de\"; }\n\n.fa.fa-linkedin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-linkedin:before {\n  content: \"\\f0e1\"; }\n\n.fa.fa-rotate-left:before {\n  content: \"\\f0e2\"; }\n\n.fa.fa-legal:before {\n  content: \"\\f0e3\"; }\n\n.fa.fa-tachometer:before {\n  content: \"\\f3fd\"; }\n\n.fa.fa-dashboard:before {\n  content: \"\\f3fd\"; }\n\n.fa.fa-comment-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-comment-o:before {\n  content: \"\\f075\"; }\n\n.fa.fa-comments-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-comments-o:before {\n  content: \"\\f086\"; }\n\n.fa.fa-flash:before {\n  content: \"\\f0e7\"; }\n\n.fa.fa-clipboard {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-paste {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-paste:before {\n  content: \"\\f328\"; }\n\n.fa.fa-lightbulb-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-lightbulb-o:before {\n  content: \"\\f0eb\"; }\n\n.fa.fa-exchange:before {\n  content: \"\\f362\"; }\n\n.fa.fa-cloud-download:before {\n  content: \"\\f381\"; }\n\n.fa.fa-cloud-upload:before {\n  content: \"\\f382\"; }\n\n.fa.fa-bell-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bell-o:before {\n  content: \"\\f0f3\"; }\n\n.fa.fa-cutlery:before {\n  content: \"\\f2e7\"; }\n\n.fa.fa-file-text-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-text-o:before {\n  content: \"\\f15c\"; }\n\n.fa.fa-building-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-building-o:before {\n  content: \"\\f1ad\"; }\n\n.fa.fa-hospital-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hospital-o:before {\n  content: \"\\f0f8\"; }\n\n.fa.fa-tablet:before {\n  content: \"\\f3fa\"; }\n\n.fa.fa-mobile:before {\n  content: \"\\f3cd\"; }\n\n.fa.fa-mobile-phone:before {\n  content: \"\\f3cd\"; }\n\n.fa.fa-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-circle-o:before {\n  content: \"\\f111\"; }\n\n.fa.fa-mail-reply:before {\n  content: \"\\f3e5\"; }\n\n.fa.fa-github-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-folder-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-folder-o:before {\n  content: \"\\f07b\"; }\n\n.fa.fa-folder-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-folder-open-o:before {\n  content: \"\\f07c\"; }\n\n.fa.fa-smile-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-smile-o:before {\n  content: \"\\f118\"; }\n\n.fa.fa-frown-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-frown-o:before {\n  content: \"\\f119\"; }\n\n.fa.fa-meh-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-meh-o:before {\n  content: \"\\f11a\"; }\n\n.fa.fa-keyboard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-keyboard-o:before {\n  content: \"\\f11c\"; }\n\n.fa.fa-flag-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-flag-o:before {\n  content: \"\\f024\"; }\n\n.fa.fa-mail-reply-all:before {\n  content: \"\\f122\"; }\n\n.fa.fa-star-half-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-half-o:before {\n  content: \"\\f089\"; }\n\n.fa.fa-star-half-empty {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-half-empty:before {\n  content: \"\\f089\"; }\n\n.fa.fa-star-half-full {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-half-full:before {\n  content: \"\\f089\"; }\n\n.fa.fa-code-fork:before {\n  content: \"\\f126\"; }\n\n.fa.fa-chain-broken:before {\n  content: \"\\f127\"; }\n\n.fa.fa-shield:before {\n  content: \"\\f3ed\"; }\n\n.fa.fa-calendar-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-o:before {\n  content: \"\\f133\"; }\n\n.fa.fa-maxcdn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-html5 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-css3 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ticket:before {\n  content: \"\\f3ff\"; }\n\n.fa.fa-minus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-minus-square-o:before {\n  content: \"\\f146\"; }\n\n.fa.fa-level-up:before {\n  content: \"\\f3bf\"; }\n\n.fa.fa-level-down:before {\n  content: \"\\f3be\"; }\n\n.fa.fa-pencil-square:before {\n  content: \"\\f14b\"; }\n\n.fa.fa-external-link-square:before {\n  content: \"\\f360\"; }\n\n.fa.fa-compass {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-down:before {\n  content: \"\\f150\"; }\n\n.fa.fa-toggle-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-down:before {\n  content: \"\\f150\"; }\n\n.fa.fa-caret-square-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-up:before {\n  content: \"\\f151\"; }\n\n.fa.fa-toggle-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-up:before {\n  content: \"\\f151\"; }\n\n.fa.fa-caret-square-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-right:before {\n  content: \"\\f152\"; }\n\n.fa.fa-toggle-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-right:before {\n  content: \"\\f152\"; }\n\n.fa.fa-eur:before {\n  content: \"\\f153\"; }\n\n.fa.fa-euro:before {\n  content: \"\\f153\"; }\n\n.fa.fa-gbp:before {\n  content: \"\\f154\"; }\n\n.fa.fa-usd:before {\n  content: \"\\f155\"; }\n\n.fa.fa-dollar:before {\n  content: \"\\f155\"; }\n\n.fa.fa-inr:before {\n  content: \"\\f156\"; }\n\n.fa.fa-rupee:before {\n  content: \"\\f156\"; }\n\n.fa.fa-jpy:before {\n  content: \"\\f157\"; }\n\n.fa.fa-cny:before {\n  content: \"\\f157\"; }\n\n.fa.fa-rmb:before {\n  content: \"\\f157\"; }\n\n.fa.fa-yen:before {\n  content: \"\\f157\"; }\n\n.fa.fa-rub:before {\n  content: \"\\f158\"; }\n\n.fa.fa-ruble:before {\n  content: \"\\f158\"; }\n\n.fa.fa-rouble:before {\n  content: \"\\f158\"; }\n\n.fa.fa-krw:before {\n  content: \"\\f159\"; }\n\n.fa.fa-won:before {\n  content: \"\\f159\"; }\n\n.fa.fa-btc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitcoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitcoin:before {\n  content: \"\\f15a\"; }\n\n.fa.fa-file-text:before {\n  content: \"\\f15c\"; }\n\n.fa.fa-sort-alpha-asc:before {\n  content: \"\\f15d\"; }\n\n.fa.fa-sort-alpha-desc:before {\n  content: \"\\f881\"; }\n\n.fa.fa-sort-amount-asc:before {\n  content: \"\\f160\"; }\n\n.fa.fa-sort-amount-desc:before {\n  content: \"\\f884\"; }\n\n.fa.fa-sort-numeric-asc:before {\n  content: \"\\f162\"; }\n\n.fa.fa-sort-numeric-desc:before {\n  content: \"\\f886\"; }\n\n.fa.fa-youtube-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-youtube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-xing {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-xing-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-youtube-play {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-youtube-play:before {\n  content: \"\\f167\"; }\n\n.fa.fa-dropbox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stack-overflow {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-instagram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-flickr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-adn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitbucket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitbucket-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitbucket-square:before {\n  content: \"\\f171\"; }\n\n.fa.fa-tumblr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-tumblr-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-long-arrow-down:before {\n  content: \"\\f309\"; }\n\n.fa.fa-long-arrow-up:before {\n  content: \"\\f30c\"; }\n\n.fa.fa-long-arrow-left:before {\n  content: \"\\f30a\"; }\n\n.fa.fa-long-arrow-right:before {\n  content: \"\\f30b\"; }\n\n.fa.fa-apple {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-windows {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-android {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-linux {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-dribbble {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-skype {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-foursquare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-trello {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gratipay {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gittip {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gittip:before {\n  content: \"\\f184\"; }\n\n.fa.fa-sun-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-sun-o:before {\n  content: \"\\f185\"; }\n\n.fa.fa-moon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-moon-o:before {\n  content: \"\\f186\"; }\n\n.fa.fa-vk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-renren {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pagelines {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stack-exchange {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-right:before {\n  content: \"\\f35a\"; }\n\n.fa.fa-arrow-circle-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-left:before {\n  content: \"\\f359\"; }\n\n.fa.fa-caret-square-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-left:before {\n  content: \"\\f191\"; }\n\n.fa.fa-toggle-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-left:before {\n  content: \"\\f191\"; }\n\n.fa.fa-dot-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-dot-circle-o:before {\n  content: \"\\f192\"; }\n\n.fa.fa-vimeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-try:before {\n  content: \"\\f195\"; }\n\n.fa.fa-turkish-lira:before {\n  content: \"\\f195\"; }\n\n.fa.fa-plus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-plus-square-o:before {\n  content: \"\\f0fe\"; }\n\n.fa.fa-slack {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wordpress {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-openid {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-institution:before {\n  content: \"\\f19c\"; }\n\n.fa.fa-bank:before {\n  content: \"\\f19c\"; }\n\n.fa.fa-mortar-board:before {\n  content: \"\\f19d\"; }\n\n.fa.fa-yahoo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-reddit {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-reddit-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stumbleupon-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stumbleupon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-delicious {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-digg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pied-piper-pp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pied-piper-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-drupal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-joomla {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-spoon:before {\n  content: \"\\f2e5\"; }\n\n.fa.fa-behance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-behance-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-steam {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-steam-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-automobile:before {\n  content: \"\\f1b9\"; }\n\n.fa.fa-cab:before {\n  content: \"\\f1ba\"; }\n\n.fa.fa-envelope-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-envelope-o:before {\n  content: \"\\f0e0\"; }\n\n.fa.fa-deviantart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-soundcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-file-pdf-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-pdf-o:before {\n  content: \"\\f1c1\"; }\n\n.fa.fa-file-word-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-word-o:before {\n  content: \"\\f1c2\"; }\n\n.fa.fa-file-excel-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-excel-o:before {\n  content: \"\\f1c3\"; }\n\n.fa.fa-file-powerpoint-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-powerpoint-o:before {\n  content: \"\\f1c4\"; }\n\n.fa.fa-file-image-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-image-o:before {\n  content: \"\\f1c5\"; }\n\n.fa.fa-file-photo-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-photo-o:before {\n  content: \"\\f1c5\"; }\n\n.fa.fa-file-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-picture-o:before {\n  content: \"\\f1c5\"; }\n\n.fa.fa-file-archive-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-archive-o:before {\n  content: \"\\f1c6\"; }\n\n.fa.fa-file-zip-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-zip-o:before {\n  content: \"\\f1c6\"; }\n\n.fa.fa-file-audio-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-audio-o:before {\n  content: \"\\f1c7\"; }\n\n.fa.fa-file-sound-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-sound-o:before {\n  content: \"\\f1c7\"; }\n\n.fa.fa-file-video-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-video-o:before {\n  content: \"\\f1c8\"; }\n\n.fa.fa-file-movie-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-movie-o:before {\n  content: \"\\f1c8\"; }\n\n.fa.fa-file-code-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-code-o:before {\n  content: \"\\f1c9\"; }\n\n.fa.fa-vine {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-codepen {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-jsfiddle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-life-ring {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-bouy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-bouy:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-life-buoy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-buoy:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-life-saver {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-saver:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-support {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-support:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-circle-o-notch:before {\n  content: \"\\f1ce\"; }\n\n.fa.fa-rebel {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ra {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ra:before {\n  content: \"\\f1d0\"; }\n\n.fa.fa-resistance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-resistance:before {\n  content: \"\\f1d0\"; }\n\n.fa.fa-empire {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ge:before {\n  content: \"\\f1d1\"; }\n\n.fa.fa-git-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-git {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-hacker-news {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-y-combinator-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-y-combinator-square:before {\n  content: \"\\f1d4\"; }\n\n.fa.fa-yc-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yc-square:before {\n  content: \"\\f1d4\"; }\n\n.fa.fa-tencent-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-qq {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-weixin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wechat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wechat:before {\n  content: \"\\f1d7\"; }\n\n.fa.fa-send:before {\n  content: \"\\f1d8\"; }\n\n.fa.fa-paper-plane-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-paper-plane-o:before {\n  content: \"\\f1d8\"; }\n\n.fa.fa-send-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-send-o:before {\n  content: \"\\f1d8\"; }\n\n.fa.fa-circle-thin {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-circle-thin:before {\n  content: \"\\f111\"; }\n\n.fa.fa-header:before {\n  content: \"\\f1dc\"; }\n\n.fa.fa-sliders:before {\n  content: \"\\f1de\"; }\n\n.fa.fa-futbol-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-futbol-o:before {\n  content: \"\\f1e3\"; }\n\n.fa.fa-soccer-ball-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-soccer-ball-o:before {\n  content: \"\\f1e3\"; }\n\n.fa.fa-slideshare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-twitch {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yelp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-newspaper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-newspaper-o:before {\n  content: \"\\f1ea\"; }\n\n.fa.fa-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-wallet {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-visa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-mastercard {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-discover {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-amex {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-stripe {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bell-slash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bell-slash-o:before {\n  content: \"\\f1f6\"; }\n\n.fa.fa-trash:before {\n  content: \"\\f2ed\"; }\n\n.fa.fa-copyright {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-eyedropper:before {\n  content: \"\\f1fb\"; }\n\n.fa.fa-area-chart:before {\n  content: \"\\f1fe\"; }\n\n.fa.fa-pie-chart:before {\n  content: \"\\f200\"; }\n\n.fa.fa-line-chart:before {\n  content: \"\\f201\"; }\n\n.fa.fa-lastfm {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-lastfm-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ioxhost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-angellist {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-cc:before {\n  content: \"\\f20a\"; }\n\n.fa.fa-ils:before {\n  content: \"\\f20b\"; }\n\n.fa.fa-shekel:before {\n  content: \"\\f20b\"; }\n\n.fa.fa-sheqel:before {\n  content: \"\\f20b\"; }\n\n.fa.fa-meanpath {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-meanpath:before {\n  content: \"\\f2b4\"; }\n\n.fa.fa-buysellads {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-connectdevelop {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-dashcube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-forumbee {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-leanpub {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-sellsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-shirtsinbulk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-simplybuilt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-skyatlas {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-diamond {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-diamond:before {\n  content: \"\\f3a5\"; }\n\n.fa.fa-intersex:before {\n  content: \"\\f224\"; }\n\n.fa.fa-facebook-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook-official:before {\n  content: \"\\f09a\"; }\n\n.fa.fa-pinterest-p {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-whatsapp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-hotel:before {\n  content: \"\\f236\"; }\n\n.fa.fa-viacoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-medium {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-y-combinator {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yc:before {\n  content: \"\\f23b\"; }\n\n.fa.fa-optin-monster {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-opencart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-expeditedssl {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-battery-4:before {\n  content: \"\\f240\"; }\n\n.fa.fa-battery:before {\n  content: \"\\f240\"; }\n\n.fa.fa-battery-3:before {\n  content: \"\\f241\"; }\n\n.fa.fa-battery-2:before {\n  content: \"\\f242\"; }\n\n.fa.fa-battery-1:before {\n  content: \"\\f243\"; }\n\n.fa.fa-battery-0:before {\n  content: \"\\f244\"; }\n\n.fa.fa-object-group {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-object-ungroup {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-sticky-note-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-sticky-note-o:before {\n  content: \"\\f249\"; }\n\n.fa.fa-cc-jcb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-diners-club {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-clone {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hourglass-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hourglass-o:before {\n  content: \"\\f254\"; }\n\n.fa.fa-hourglass-1:before {\n  content: \"\\f251\"; }\n\n.fa.fa-hourglass-2:before {\n  content: \"\\f252\"; }\n\n.fa.fa-hourglass-3:before {\n  content: \"\\f253\"; }\n\n.fa.fa-hand-rock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-rock-o:before {\n  content: \"\\f255\"; }\n\n.fa.fa-hand-grab-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-grab-o:before {\n  content: \"\\f255\"; }\n\n.fa.fa-hand-paper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-paper-o:before {\n  content: \"\\f256\"; }\n\n.fa.fa-hand-stop-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-stop-o:before {\n  content: \"\\f256\"; }\n\n.fa.fa-hand-scissors-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-scissors-o:before {\n  content: \"\\f257\"; }\n\n.fa.fa-hand-lizard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-lizard-o:before {\n  content: \"\\f258\"; }\n\n.fa.fa-hand-spock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-spock-o:before {\n  content: \"\\f259\"; }\n\n.fa.fa-hand-pointer-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-pointer-o:before {\n  content: \"\\f25a\"; }\n\n.fa.fa-hand-peace-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-peace-o:before {\n  content: \"\\f25b\"; }\n\n.fa.fa-registered {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-creative-commons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gg-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-tripadvisor {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-odnoklassniki {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-odnoklassniki-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-get-pocket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wikipedia-w {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-safari {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-chrome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-firefox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-opera {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-internet-explorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-television:before {\n  content: \"\\f26c\"; }\n\n.fa.fa-contao {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-500px {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-amazon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-calendar-plus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-plus-o:before {\n  content: \"\\f271\"; }\n\n.fa.fa-calendar-minus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-minus-o:before {\n  content: \"\\f272\"; }\n\n.fa.fa-calendar-times-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-times-o:before {\n  content: \"\\f273\"; }\n\n.fa.fa-calendar-check-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-check-o:before {\n  content: \"\\f274\"; }\n\n.fa.fa-map-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-map-o:before {\n  content: \"\\f279\"; }\n\n.fa.fa-commenting:before {\n  content: \"\\f4ad\"; }\n\n.fa.fa-commenting-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-commenting-o:before {\n  content: \"\\f4ad\"; }\n\n.fa.fa-houzz {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-vimeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-vimeo:before {\n  content: \"\\f27d\"; }\n\n.fa.fa-black-tie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fonticons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-reddit-alien {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-edge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-credit-card-alt:before {\n  content: \"\\f09d\"; }\n\n.fa.fa-codiepie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-modx {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fort-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-usb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-product-hunt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-mixcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-scribd {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pause-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-pause-circle-o:before {\n  content: \"\\f28b\"; }\n\n.fa.fa-stop-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-stop-circle-o:before {\n  content: \"\\f28d\"; }\n\n.fa.fa-bluetooth {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bluetooth-b {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gitlab {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wpbeginner {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wpforms {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-envira {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wheelchair-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wheelchair-alt:before {\n  content: \"\\f368\"; }\n\n.fa.fa-question-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-question-circle-o:before {\n  content: \"\\f059\"; }\n\n.fa.fa-volume-control-phone:before {\n  content: \"\\f2a0\"; }\n\n.fa.fa-asl-interpreting:before {\n  content: \"\\f2a3\"; }\n\n.fa.fa-deafness:before {\n  content: \"\\f2a4\"; }\n\n.fa.fa-hard-of-hearing:before {\n  content: \"\\f2a4\"; }\n\n.fa.fa-glide {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-glide-g {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-signing:before {\n  content: \"\\f2a7\"; }\n\n.fa.fa-viadeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-viadeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-snapchat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-snapchat-ghost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-snapchat-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pied-piper {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-first-order {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yoast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-themeisle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-official:before {\n  content: \"\\f2b3\"; }\n\n.fa.fa-google-plus-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-circle:before {\n  content: \"\\f2b3\"; }\n\n.fa.fa-font-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fa:before {\n  content: \"\\f2b4\"; }\n\n.fa.fa-handshake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-handshake-o:before {\n  content: \"\\f2b5\"; }\n\n.fa.fa-envelope-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-envelope-open-o:before {\n  content: \"\\f2b6\"; }\n\n.fa.fa-linode {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-address-book-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-address-book-o:before {\n  content: \"\\f2b9\"; }\n\n.fa.fa-vcard:before {\n  content: \"\\f2bb\"; }\n\n.fa.fa-address-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-address-card-o:before {\n  content: \"\\f2bb\"; }\n\n.fa.fa-vcard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-vcard-o:before {\n  content: \"\\f2bb\"; }\n\n.fa.fa-user-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-user-circle-o:before {\n  content: \"\\f2bd\"; }\n\n.fa.fa-user-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-user-o:before {\n  content: \"\\f007\"; }\n\n.fa.fa-id-badge {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-drivers-license:before {\n  content: \"\\f2c2\"; }\n\n.fa.fa-id-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-id-card-o:before {\n  content: \"\\f2c2\"; }\n\n.fa.fa-drivers-license-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-drivers-license-o:before {\n  content: \"\\f2c2\"; }\n\n.fa.fa-quora {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-free-code-camp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-telegram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-thermometer-4:before {\n  content: \"\\f2c7\"; }\n\n.fa.fa-thermometer:before {\n  content: \"\\f2c7\"; }\n\n.fa.fa-thermometer-3:before {\n  content: \"\\f2c8\"; }\n\n.fa.fa-thermometer-2:before {\n  content: \"\\f2c9\"; }\n\n.fa.fa-thermometer-1:before {\n  content: \"\\f2ca\"; }\n\n.fa.fa-thermometer-0:before {\n  content: \"\\f2cb\"; }\n\n.fa.fa-bathtub:before {\n  content: \"\\f2cd\"; }\n\n.fa.fa-s15:before {\n  content: \"\\f2cd\"; }\n\n.fa.fa-window-maximize {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-window-restore {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-times-rectangle:before {\n  content: \"\\f410\"; }\n\n.fa.fa-window-close-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-window-close-o:before {\n  content: \"\\f410\"; }\n\n.fa.fa-times-rectangle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-times-rectangle-o:before {\n  content: \"\\f410\"; }\n\n.fa.fa-bandcamp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-grav {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-etsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-imdb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ravelry {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-eercast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-eercast:before {\n  content: \"\\f2da\"; }\n\n.fa.fa-snowflake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-snowflake-o:before {\n  content: \"\\f2dc\"; }\n\n.fa.fa-superpowers {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wpexplorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-spotify {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/all.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"500px\": [448, 512, [], \"f26e\", \"M103.3 344.3c-6.5-14.2-6.9-18.3 7.4-23.1 25.6-8 8 9.2 43.2 49.2h.3v-93.9c1.2-50.2 44-92.2 97.7-92.2 53.9 0 97.7 43.5 97.7 96.8 0 63.4-60.8 113.2-128.5 93.3-10.5-4.2-2.1-31.7 8.5-28.6 53 0 89.4-10.1 89.4-64.4 0-61-77.1-89.6-116.9-44.6-23.5 26.4-17.6 42.1-17.6 157.6 50.7 31 118.3 22 160.4-20.1 24.8-24.8 38.5-58 38.5-93 0-35.2-13.8-68.2-38.8-93.3-24.8-24.8-57.8-38.5-93.3-38.5s-68.8 13.8-93.5 38.5c-.3.3-16 16.5-21.2 23.9l-.5.6c-3.3 4.7-6.3 9.1-20.1 6.1-6.9-1.7-14.3-5.8-14.3-11.8V20c0-5 3.9-10.5 10.5-10.5h241.3c8.3 0 8.3 11.6 8.3 15.1 0 3.9 0 15.1-8.3 15.1H130.3v132.9h.3c104.2-109.8 282.8-36 282.8 108.9 0 178.1-244.8 220.3-310.1 62.8zm63.3-260.8c-.5 4.2 4.6 24.5 14.6 20.6C306 56.6 384 144.5 390.6 144.5c4.8 0 22.8-15.3 14.3-22.8-93.2-89-234.5-57-238.3-38.2zM393 414.7C283 524.6 94 475.5 61 310.5c0-12.2-30.4-7.4-28.9 3.3 24 173.4 246 256.9 381.6 121.3 6.9-7.8-12.6-28.4-20.7-20.4zM213.6 306.6c0 4 4.3 7.3 5.5 8.5 3 3 6.1 4.4 8.5 4.4 3.8 0 2.6.2 22.3-19.5 19.6 19.3 19.1 19.5 22.3 19.5 5.4 0 18.5-10.4 10.7-18.2L265.6 284l18.2-18.2c6.3-6.8-10.1-21.8-16.2-15.7L249.7 268c-18.6-18.8-18.4-19.5-21.5-19.5-5 0-18 11.7-12.4 17.3L234 284c-18.1 17.9-20.4 19.2-20.4 22.6z\"],\n    \"accessible-icon\": [448, 512, [], \"f368\", \"M423.9 255.8L411 413.1c-3.3 40.7-63.9 35.1-60.6-4.9l10-122.5-41.1 2.3c10.1 20.7 15.8 43.9 15.8 68.5 0 41.2-16.1 78.7-42.3 106.5l-39.3-39.3c57.9-63.7 13.1-167.2-74-167.2-25.9 0-49.5 9.9-67.2 26L73 243.2c22-20.7 50.1-35.1 81.4-40.2l75.3-85.7-42.6-24.8-51.6 46c-30 26.8-70.6-18.5-40.5-45.4l68-60.7c9.8-8.8 24.1-10.2 35.5-3.6 0 0 139.3 80.9 139.5 81.1 16.2 10.1 20.7 36 6.1 52.6L285.7 229l106.1-5.9c18.5-1.1 33.6 14.4 32.1 32.7zm-64.9-154c28.1 0 50.9-22.8 50.9-50.9C409.9 22.8 387.1 0 359 0c-28.1 0-50.9 22.8-50.9 50.9 0 28.1 22.8 50.9 50.9 50.9zM179.6 456.5c-80.6 0-127.4-90.6-82.7-156.1l-39.7-39.7C36.4 287 24 320.3 24 356.4c0 130.7 150.7 201.4 251.4 122.5l-39.7-39.7c-16 10.9-35.3 17.3-56.1 17.3z\"],\n    \"accusoft\": [640, 512, [], \"f369\", \"M322.1 252v-1l-51.2-65.8s-12 1.6-25 15.1c-9 9.3-242.1 239.1-243.4 240.9-7 10 1.6 6.8 15.7 1.7.8 0 114.5-36.6 114.5-36.6.5-.6-.1-.1.6-.6-.4-5.1-.8-26.2-1-27.7-.6-5.2 2.2-6.9 7-8.9l92.6-33.8c.6-.8 88.5-81.7 90.2-83.3zm160.1 120.1c13.3 16.1 20.7 13.3 30.8 9.3 3.2-1.2 115.4-47.6 117.8-48.9 8-4.3-1.7-16.7-7.2-23.4-2.1-2.5-205.1-245.6-207.2-248.3-9.7-12.2-14.3-12.9-38.4-12.8-10.2 0-106.8.5-116.5.6-19.2.1-32.9-.3-19.2 16.9C250 75 476.5 365.2 482.2 372.1zm152.7 1.6c-2.3-.3-24.6-4.7-38-7.2 0 0-115 50.4-117.5 51.6-16 7.3-26.9-3.2-36.7-14.6l-57.1-74c-5.4-.9-60.4-9.6-65.3-9.3-3.1.2-9.6.8-14.4 2.9-4.9 2.1-145.2 52.8-150.2 54.7-5.1 2-11.4 3.6-11.1 7.6.2 2.5 2 2.6 4.6 3.5 2.7.8 300.9 67.6 308 69.1 15.6 3.3 38.5 10.5 53.6 1.7 2.1-1.2 123.8-76.4 125.8-77.8 5.4-4 4.3-6.8-1.7-8.2z\"],\n    \"acquisitions-incorporated\": [384, 512, [], \"f6af\", \"M357.45 468.2c-1.2-7.7-1.3-7.6-9.6-7.6-99.8.2-111.8-2.4-112.7-2.6-12.3-1.7-20.6-10.5-21-23.1-.1-1.6-.2-71.6-1-129.1-.1-4.7 1.6-6.4 5.9-7.5 12.5-3 24.9-6.1 37.3-9.7 4.3-1.3 6.8-.2 8.4 3.5 4.5 10.3 8.8 20.6 13.2 30.9 1.6 3.7.1 4.4-3.4 4.4-10-.2-20-.1-30.4-.1v27h116c-1.4-9.5-2.7-18.1-4-27.5-7 0-13.8.4-20.4-.1-22.6-1.6-18.3-4.4-84-158.6-8.8-20.1-27.9-62.1-36.5-89.2-4.4-14 5.5-25.4 18.9-26.6 18.6-1.7 37.5-1.6 56.2-2 20.6-.4 41.2-.4 61.8-.5 3.1 0 4-1.4 4.3-4.3 1.2-9.8 2.7-19.5 4-29.2.8-5.3 1.6-10.7 2.4-16.1L23.75 0c-3.6 0-5.3 1.1-4.6 5.3 2.2 13.2-.8.8 6.4 45.3 63.4 0 71.8.9 101.8.5 12.3-.2 37 3.5 37.7 22.1.4 11.4-1.1 11.3-32.6 87.4-53.8 129.8-50.7 120.3-67.3 161-1.7 4.1-3.6 5.2-7.6 5.2-8.5-.2-17-.3-25.4.1-1.9.1-5.2 1.8-5.5 3.2-1.5 8.1-2.2 16.3-3.2 24.9h114.3v-27.6c-6.9 0-33.5.4-35.3-2.9 5.3-12.3 10.4-24.4 15.7-36.7 16.3 4 31.9 7.8 47.6 11.7 3.4.9 4.6 3 4.6 6.8-.1 42.9.1 85.9.2 128.8 0 10.2-5.5 19.1-14.9 23.1-6.5 2.7-3.3 3.4-121.4 2.4-5.3 0-7.1 2-7.6 6.8-1.5 12.9-2.9 25.9-5 38.8-.8 5 1.3 5.7 5.3 5.7 183.2.6-30.7 0 337.1 0-2.5-15-4.4-29.4-6.6-43.7zm-174.9-205.7c-13.3-4.2-26.6-8.2-39.9-12.5a44.53 44.53 0 0 1-5.8-2.9c17.2-44.3 34.2-88.1 51.3-132.1 7.5 2.4 7.9-.8 9.4 0 9.3 22.5 18.1 60.1 27 82.8 6.6 16.7 13 33.5 19.7 50.9a35.78 35.78 0 0 1-3.9 2.1c-13.1 3.9-26.4 7.5-39.4 11.7a27.66 27.66 0 0 1-18.4 0z\"],\n    \"adn\": [496, 512, [], \"f170\", \"M248 167.5l64.9 98.8H183.1l64.9-98.8zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-99.8 82.7L248 115.5 99.8 338.7h30.4l33.6-51.7h168.6l33.6 51.7h30.2z\"],\n    \"adobe\": [512, 512, [], \"f778\", \"M315.5 64h170.9v384L315.5 64zm-119 0H25.6v384L196.5 64zM256 206.1L363.5 448h-73l-30.7-76.8h-78.7L256 206.1z\"],\n    \"adversal\": [512, 512, [], \"f36a\", \"M482.1 32H28.7C5.8 32 0 37.9 0 60.9v390.2C0 474.4 5.8 480 28.7 480h453.4c24.4 0 29.9-5.2 29.9-29.7V62.2c0-24.6-5.4-30.2-29.9-30.2zM178.4 220.3c-27.5-20.2-72.1-8.7-84.2 23.4-4.3 11.1-9.3 9.5-17.5 8.3-9.7-1.5-17.2-3.2-22.5-5.5-28.8-11.4 8.6-55.3 24.9-64.3 41.1-21.4 83.4-22.2 125.3-4.8 40.9 16.8 34.5 59.2 34.5 128.5 2.7 25.8-4.3 58.3 9.3 88.8 1.9 4.4.4 7.9-2.7 10.7-8.4 6.7-39.3 2.2-46.6-7.4-1.9-2.2-1.8-3.6-3.9-6.2-3.6-3.9-7.3-2.2-11.9 1-57.4 36.4-140.3 21.4-147-43.3-3.1-29.3 12.4-57.1 39.6-71 38.2-19.5 112.2-11.8 114-30.9 1.1-10.2-1.9-20.1-11.3-27.3zm286.7 222c0 15.1-11.1 9.9-17.8 9.9H52.4c-7.4 0-18.2 4.8-17.8-10.7.4-13.9 10.5-9.1 17.1-9.1 132.3-.4 264.5-.4 396.8 0 6.8 0 16.6-4.4 16.6 9.9zm3.8-340.5v291c0 5.7-.7 13.9-8.1 13.9-12.4-.4-27.5 7.1-36.1-5.6-5.8-8.7-7.8-4-12.4-1.2-53.4 29.7-128.1 7.1-144.4-85.2-6.1-33.4-.7-67.1 15.7-100 11.8-23.9 56.9-76.1 136.1-30.5v-71c0-26.2-.1-26.2 26-26.2 3.1 0 6.6.4 9.7 0 10.1-.8 13.6 4.4 13.6 14.3-.1.2-.1.3-.1.5zm-51.5 232.3c-19.5 47.6-72.9 43.3-90 5.2-15.1-33.3-15.5-68.2.4-101.5 16.3-34.1 59.7-35.7 81.5-4.8 20.6 28.8 14.9 84.6 8.1 101.1zm-294.8 35.3c-7.5-1.3-33-3.3-33.7-27.8-.4-13.9 7.8-23 19.8-25.8 24.4-5.9 49.3-9.9 73.7-14.7 8.9-2 7.4 4.4 7.8 9.5 1.4 33-26.1 59.2-67.6 58.8z\"],\n    \"affiliatetheme\": [512, 512, [], \"f36b\", \"M159.7 237.4C108.4 308.3 43.1 348.2 14 326.6-15.2 304.9 2.8 230 54.2 159.1c51.3-70.9 116.6-110.8 145.7-89.2 29.1 21.6 11.1 96.6-40.2 167.5zm351.2-57.3C437.1 303.5 319 367.8 246.4 323.7c-25-15.2-41.3-41.2-49-73.8-33.6 64.8-92.8 113.8-164.1 133.2 49.8 59.3 124.1 96.9 207 96.9 150 0 271.6-123.1 271.6-274.9.1-8.5-.3-16.8-1-25z\"],\n    \"airbnb\": [448, 512, [], \"f834\", \"M224 373.12c-25.24-31.67-40.08-59.43-45-83.18-22.55-88 112.61-88 90.06 0-5.45 24.25-20.29 52-45 83.18zm138.15 73.23c-42.06 18.31-83.67-10.88-119.3-50.47 103.9-130.07 46.11-200-18.85-200-54.92 0-85.16 46.51-73.28 100.5 6.93 29.19 25.23 62.39 54.43 99.5-32.53 36.05-60.55 52.69-85.15 54.92-50 7.43-89.11-41.06-71.3-91.09 15.1-39.16 111.72-231.18 115.87-241.56 15.75-30.07 25.56-57.4 59.38-57.4 32.34 0 43.4 25.94 60.37 59.87 36 70.62 89.35 177.48 114.84 239.09 13.17 33.07-1.37 71.29-37.01 86.64zm47-136.12C280.27 35.93 273.13 32 224 32c-45.52 0-64.87 31.67-84.66 72.79C33.18 317.1 22.89 347.19 22 349.81-3.22 419.14 48.74 480 111.63 480c21.71 0 60.61-6.06 112.37-62.4 58.68 63.78 101.26 62.4 112.37 62.4 62.89.05 114.85-60.86 89.61-130.19.02-3.89-16.82-38.9-16.82-39.58z\"],\n    \"algolia\": [448, 512, [], \"f36c\", \"M229.3 182.6c-49.3 0-89.2 39.9-89.2 89.2 0 49.3 39.9 89.2 89.2 89.2s89.2-39.9 89.2-89.2c0-49.3-40-89.2-89.2-89.2zm62.7 56.6l-58.9 30.6c-1.8.9-3.8-.4-3.8-2.3V201c0-1.5 1.3-2.7 2.7-2.6 26.2 1 48.9 15.7 61.1 37.1.7 1.3.2 3-1.1 3.7zM389.1 32H58.9C26.4 32 0 58.4 0 90.9V421c0 32.6 26.4 59 58.9 59H389c32.6 0 58.9-26.4 58.9-58.9V90.9C448 58.4 421.6 32 389.1 32zm-202.6 84.7c0-10.8 8.7-19.5 19.5-19.5h45.3c10.8 0 19.5 8.7 19.5 19.5v15.4c0 1.8-1.7 3-3.3 2.5-12.3-3.4-25.1-5.1-38.1-5.1-13.5 0-26.7 1.8-39.4 5.5-1.7.5-3.4-.8-3.4-2.5v-15.8zm-84.4 37l9.2-9.2c7.6-7.6 19.9-7.6 27.5 0l7.7 7.7c1.1 1.1 1 3-.3 4-6.2 4.5-12.1 9.4-17.6 14.9-5.4 5.4-10.4 11.3-14.8 17.4-1 1.3-2.9 1.5-4 .3l-7.7-7.7c-7.6-7.5-7.6-19.8 0-27.4zm127.2 244.8c-70 0-126.6-56.7-126.6-126.6s56.7-126.6 126.6-126.6c70 0 126.6 56.6 126.6 126.6 0 69.8-56.7 126.6-126.6 126.6z\"],\n    \"alipay\": [448, 512, [], \"f642\", \"M377.74 32H70.26C31.41 32 0 63.41 0 102.26v307.48C0 448.59 31.41 480 70.26 480h307.48c38.52 0 69.76-31.08 70.26-69.6-45.96-25.62-110.59-60.34-171.6-88.44-32.07 43.97-84.14 81-148.62 81-70.59 0-93.73-45.3-97.04-76.37-3.97-39.01 14.88-81.5 99.52-81.5 35.38 0 79.35 10.25 127.13 24.96 16.53-30.09 26.45-60.34 26.45-60.34h-178.2v-16.7h92.08v-31.24H88.28v-19.01h109.44V92.34h50.92v50.42h109.44v19.01H248.63v31.24h88.77s-15.21 46.62-38.35 90.92c48.93 16.7 100.01 36.04 148.62 52.74V102.26C447.83 63.57 416.43 32 377.74 32zM47.28 322.95c.99 20.17 10.25 53.73 69.93 53.73 52.07 0 92.58-39.68 117.87-72.9-44.63-18.68-84.48-31.41-109.44-31.41-67.45 0-79.35 33.06-78.36 50.58z\"],\n    \"amazon\": [448, 512, [], \"f270\", \"M257.2 162.7c-48.7 1.8-169.5 15.5-169.5 117.5 0 109.5 138.3 114 183.5 43.2 6.5 10.2 35.4 37.5 45.3 46.8l56.8-56S341 288.9 341 261.4V114.3C341 89 316.5 32 228.7 32 140.7 32 94 87 94 136.3l73.5 6.8c16.3-49.5 54.2-49.5 54.2-49.5 40.7-.1 35.5 29.8 35.5 69.1zm0 86.8c0 80-84.2 68-84.2 17.2 0-47.2 50.5-56.7 84.2-57.8v40.6zm136 163.5c-7.7 10-70 67-174.5 67S34.2 408.5 9.7 379c-6.8-7.7 1-11.3 5.5-8.3C88.5 415.2 203 488.5 387.7 401c7.5-3.7 13.3 2 5.5 12zm39.8 2.2c-6.5 15.8-16 26.8-21.2 31-5.5 4.5-9.5 2.7-6.5-3.8s19.3-46.5 12.7-55c-6.5-8.3-37-4.3-48-3.2-10.8 1-13 2-14-.3-2.3-5.7 21.7-15.5 37.5-17.5 15.7-1.8 41-.8 46 5.7 3.7 5.1 0 27.1-6.5 43.1z\"],\n    \"amazon-pay\": [640, 512, [], \"f42c\", \"M14 325.3c2.3-4.2 5.2-4.9 9.7-2.5 10.4 5.6 20.6 11.4 31.2 16.7a595.88 595.88 0 0 0 127.4 46.3 616.61 616.61 0 0 0 63.2 11.8 603.33 603.33 0 0 0 95 5.2c17.4-.4 34.8-1.8 52.1-3.8a603.66 603.66 0 0 0 163.3-42.8c2.9-1.2 5.9-2 9.1-1.2 6.7 1.8 9 9 4.1 13.9a70 70 0 0 1-9.6 7.4c-30.7 21.1-64.2 36.4-99.6 47.9a473.31 473.31 0 0 1-75.1 17.6 431 431 0 0 1-53.2 4.8 21.3 21.3 0 0 0-2.5.3H308a21.3 21.3 0 0 0-2.5-.3c-3.6-.2-7.2-.3-10.7-.4a426.3 426.3 0 0 1-50.4-5.3A448.4 448.4 0 0 1 164 420a443.33 443.33 0 0 1-145.6-87c-1.8-1.6-3-3.8-4.4-5.7zM172 65.1l-4.3.6a80.92 80.92 0 0 0-38 15.1c-2.4 1.7-4.6 3.5-7.1 5.4a4.29 4.29 0 0 1-.4-1.4c-.4-2.7-.8-5.5-1.3-8.2-.7-4.6-3-6.6-7.6-6.6h-11.5c-6.9 0-8.2 1.3-8.2 8.2v209.3c0 1 0 2 .1 3 .2 3 2 4.9 4.9 5 7 .1 14.1.1 21.1 0 2.9 0 4.7-2 5-5 .1-1 .1-2 .1-3v-72.4c1.1.9 1.7 1.4 2.2 1.9 17.9 14.9 38.5 19.8 61 15.4 20.4-4 34.6-16.5 43.8-34.9 7-13.9 9.9-28.7 10.3-44.1.5-17.1-1.2-33.9-8.1-49.8-8.5-19.6-22.6-32.5-43.9-36.9-3.2-.7-6.5-1-9.8-1.5-2.8-.1-5.5-.1-8.3-.1zM124.6 107a3.48 3.48 0 0 1 1.7-3.3c13.7-9.5 28.8-14.5 45.6-13.2 14.9 1.1 27.1 8.4 33.5 25.9 3.9 10.7 4.9 21.8 4.9 33 0 10.4-.8 20.6-4 30.6-6.8 21.3-22.4 29.4-42.6 28.5-14-.6-26.2-6-37.4-13.9a3.57 3.57 0 0 1-1.7-3.3c.1-14.1 0-28.1 0-42.2s.1-28 0-42.1zm205.7-41.9c-1 .1-2 .3-2.9.4a148 148 0 0 0-28.9 4.1c-6.1 1.6-12 3.8-17.9 5.8-3.6 1.2-5.4 3.8-5.3 7.7.1 3.3-.1 6.6 0 9.9.1 4.8 2.1 6.1 6.8 4.9 7.8-2 15.6-4.2 23.5-5.7 12.3-2.3 24.7-3.3 37.2-1.4 6.5 1 12.6 2.9 16.8 8.4 3.7 4.8 5.1 10.5 5.3 16.4.3 8.3.2 16.6.3 24.9a7.84 7.84 0 0 1-.2 1.4c-.5-.1-.9 0-1.3-.1a180.56 180.56 0 0 0-32-4.9c-11.3-.6-22.5.1-33.3 3.9-12.9 4.5-23.3 12.3-29.4 24.9-4.7 9.8-5.4 20.2-3.9 30.7 2 14 9 24.8 21.4 31.7 11.9 6.6 24.8 7.4 37.9 5.4 15.1-2.3 28.5-8.7 40.3-18.4a7.36 7.36 0 0 1 1.6-1.1c.6 3.8 1.1 7.4 1.8 11 .6 3.1 2.5 5.1 5.4 5.2 5.4.1 10.9.1 16.3 0a4.84 4.84 0 0 0 4.8-4.7 26.2 26.2 0 0 0 .1-2.8v-106a80 80 0 0 0-.9-12.9c-1.9-12.9-7.4-23.5-19-30.4-6.7-4-14.1-6-21.8-7.1-3.6-.5-7.2-.8-10.8-1.3-3.9.1-7.9.1-11.9.1zm35 127.7a3.33 3.33 0 0 1-1.5 3c-11.2 8.1-23.5 13.5-37.4 14.9-5.7.6-11.4.4-16.8-1.8a20.08 20.08 0 0 1-12.4-13.3 32.9 32.9 0 0 1-.1-19.4c2.5-8.3 8.4-13 16.4-15.6a61.33 61.33 0 0 1 24.8-2.2c8.4.7 16.6 2.3 25 3.4 1.6.2 2.1 1 2.1 2.6-.1 4.8 0 9.5 0 14.3s-.2 9.4-.1 14.1zm259.9 129.4c-1-5-4.8-6.9-9.1-8.3a88.42 88.42 0 0 0-21-3.9 147.32 147.32 0 0 0-39.2 1.9c-14.3 2.7-27.9 7.3-40 15.6a13.75 13.75 0 0 0-3.7 3.5 5.11 5.11 0 0 0-.5 4c.4 1.5 2.1 1.9 3.6 1.8a16.2 16.2 0 0 0 2.2-.1c7.8-.8 15.5-1.7 23.3-2.5 11.4-1.1 22.9-1.8 34.3-.9a71.64 71.64 0 0 1 14.4 2.7c5.1 1.4 7.4 5.2 7.6 10.4.4 8-1.4 15.7-3.5 23.3-4.1 15.4-10 30.3-15.8 45.1a17.6 17.6 0 0 0-1 3c-.5 2.9 1.2 4.8 4.1 4.1a10.56 10.56 0 0 0 4.8-2.5 145.91 145.91 0 0 0 12.7-13.4c12.8-16.4 20.3-35.3 24.7-55.6.8-3.6 1.4-7.3 2.1-10.9v-17.3zM493.1 199q-19.35-53.55-38.7-107.2c-2-5.7-4.2-11.3-6.3-16.9-1.1-2.9-3.2-4.8-6.4-4.8-7.6-.1-15.2-.2-22.9-.1-2.5 0-3.7 2-3.2 4.5a43.1 43.1 0 0 0 1.9 6.1q29.4 72.75 59.1 145.5c1.7 4.1 2.1 7.6.2 11.8-3.3 7.3-5.9 15-9.3 22.3-3 6.5-8 11.4-15.2 13.3a42.13 42.13 0 0 1-15.4 1.1c-2.5-.2-5-.8-7.5-1-3.4-.2-5.1 1.3-5.2 4.8q-.15 5 0 9.9c.1 5.5 2 8 7.4 8.9a108.18 108.18 0 0 0 16.9 2c17.1.4 30.7-6.5 39.5-21.4a131.63 131.63 0 0 0 9.2-18.4q35.55-89.7 70.6-179.6a26.62 26.62 0 0 0 1.6-5.5c.4-2.8-.9-4.4-3.7-4.4-6.6-.1-13.3 0-19.9 0a7.54 7.54 0 0 0-7.7 5.2c-.5 1.4-1.1 2.7-1.6 4.1l-34.8 100c-2.5 7.2-5.1 14.5-7.7 22.2-.4-1.1-.6-1.7-.9-2.4z\"],\n    \"amilia\": [448, 512, [], \"f36d\", \"M240.1 32c-61.9 0-131.5 16.9-184.2 55.4-5.1 3.1-9.1 9.2-7.2 19.4 1.1 5.1 5.1 27.4 10.2 39.6 4.1 10.2 14.2 10.2 20.3 6.1 32.5-22.3 96.5-47.7 152.3-47.7 57.9 0 58.9 28.4 58.9 73.1v38.5C203 227.7 78.2 251 46.7 264.2 11.2 280.5 16.3 357.7 16.3 376s15.2 104 124.9 104c47.8 0 113.7-20.7 153.3-42.1v25.4c0 3 2.1 8.2 6.1 9.1 3.1 1 50.7 2 59.9 2s62.5.3 66.5-.7c4.1-1 5.1-6.1 5.1-9.1V168c-.1-80.3-57.9-136-192-136zm50.2 348c-21.4 13.2-48.7 24.4-79.1 24.4-52.8 0-58.9-33.5-59-44.7 0-12.2-3-42.7 18.3-52.9 24.3-13.2 75.1-29.4 119.8-33.5z\"],\n    \"android\": [448, 512, [], \"f17b\", \"M89.6 204.5v115.8c0 15.4-12.1 27.7-27.5 27.7-15.3 0-30.1-12.4-30.1-27.7V204.5c0-15.1 14.8-27.5 30.1-27.5 15.1 0 27.5 12.4 27.5 27.5zm10.8 157c0 16.4 13.2 29.6 29.6 29.6h19.9l.3 61.1c0 36.9 55.2 36.6 55.2 0v-61.1h37.2v61.1c0 36.7 55.5 36.8 55.5 0v-61.1h20.2c16.2 0 29.4-13.2 29.4-29.6V182.1H100.4v179.4zm248-189.1H99.3c0-42.8 25.6-80 63.6-99.4l-19.1-35.3c-2.8-4.9 4.3-8 6.7-3.8l19.4 35.6c34.9-15.5 75-14.7 108.3 0L297.5 34c2.5-4.3 9.5-1.1 6.7 3.8L285.1 73c37.7 19.4 63.3 56.6 63.3 99.4zm-170.7-55.5c0-5.7-4.6-10.5-10.5-10.5-5.7 0-10.2 4.8-10.2 10.5s4.6 10.5 10.2 10.5c5.9 0 10.5-4.8 10.5-10.5zm113.4 0c0-5.7-4.6-10.5-10.2-10.5-5.9 0-10.5 4.8-10.5 10.5s4.6 10.5 10.5 10.5c5.6 0 10.2-4.8 10.2-10.5zm94.8 60.1c-15.1 0-27.5 12.1-27.5 27.5v115.8c0 15.4 12.4 27.7 27.5 27.7 15.4 0 30.1-12.4 30.1-27.7V204.5c0-15.4-14.8-27.5-30.1-27.5z\"],\n    \"angellist\": [448, 512, [], \"f209\", \"M347.1 215.4c11.7-32.6 45.4-126.9 45.4-157.1 0-26.6-15.7-48.9-43.7-48.9-44.6 0-84.6 131.7-97.1 163.1C242 144 196.6 0 156.6 0c-31.1 0-45.7 22.9-45.7 51.7 0 35.3 34.2 126.8 46.6 162-6.3-2.3-13.1-4.3-20-4.3-23.4 0-48.3 29.1-48.3 52.6 0 8.9 4.9 21.4 8 29.7-36.9 10-51.1 34.6-51.1 71.7C46 435.6 114.4 512 210.6 512c118 0 191.4-88.6 191.4-202.9 0-43.1-6.9-82-54.9-93.7zM311.7 108c4-12.3 21.1-64.3 37.1-64.3 8.6 0 10.9 8.9 10.9 16 0 19.1-38.6 124.6-47.1 148l-34-6 33.1-93.7zM142.3 48.3c0-11.9 14.5-45.7 46.3 47.1l34.6 100.3c-15.6-1.3-27.7-3-35.4 1.4-10.9-28.8-45.5-119.7-45.5-148.8zM140 244c29.3 0 67.1 94.6 67.1 107.4 0 5.1-4.9 11.4-10.6 11.4-20.9 0-76.9-76.9-76.9-97.7.1-7.7 12.7-21.1 20.4-21.1zm184.3 186.3c-29.1 32-66.3 48.6-109.7 48.6-59.4 0-106.3-32.6-128.9-88.3-17.1-43.4 3.8-68.3 20.6-68.3 11.4 0 54.3 60.3 54.3 73.1 0 4.9-7.7 8.3-11.7 8.3-16.1 0-22.4-15.5-51.1-51.4-29.7 29.7 20.5 86.9 58.3 86.9 26.1 0 43.1-24.2 38-42 3.7 0 8.3.3 11.7-.6 1.1 27.1 9.1 59.4 41.7 61.7 0-.9 2-7.1 2-7.4 0-17.4-10.6-32.6-10.6-50.3 0-28.3 21.7-55.7 43.7-71.7 8-6 17.7-9.7 27.1-13.1 9.7-3.7 20-8 27.4-15.4-1.1-11.2-5.7-21.1-16.9-21.1-27.7 0-120.6 4-120.6-39.7 0-6.7.1-13.1 17.4-13.1 32.3 0 114.3 8 138.3 29.1 18.1 16.1 24.3 113.2-31 174.7zm-98.6-126c9.7 3.1 19.7 4 29.7 6-7.4 5.4-14 12-20.3 19.1-2.8-8.5-6.2-16.8-9.4-25.1z\"],\n    \"angrycreative\": [640, 512, [], \"f36e\", \"M640 238.2l-3.2 28.2-34.5 2.3-2 18.1 34.5-2.3-3.2 28.2-34.4 2.2-2.3 20.1 34.4-2.2-3 26.1-64.7 4.1 12.7-113.2L527 365.2l-31.9 2-23.8-117.8 30.3-2 13.6 79.4 31.7-82.4 93.1-6.2zM426.8 371.5l28.3-1.8L468 249.6l-28.4 1.9-12.8 120zM162 388.1l-19.4-36-3.5 37.4-28.2 1.7 2.7-29.1c-11 18-32 34.3-56.9 35.8C23.9 399.9-3 377 .3 339.7c2.6-29.3 26.7-62.8 67.5-65.4 37.7-2.4 47.6 23.2 51.3 28.8l2.8-30.8 38.9-2.5c20.1-1.3 38.7 3.7 42.5 23.7l2.6-26.6 64.8-4.2-2.7 27.9-36.4 2.4-1.7 17.9 36.4-2.3-2.7 27.9-36.4 2.3-1.9 19.9 36.3-2.3-2.1 20.8 55-117.2 23.8-1.6L370.4 369l8.9-85.6-22.3 1.4 2.9-27.9 75-4.9-3 28-24.3 1.6-9.7 91.9-58 3.7-4.3-15.6-39.4 2.5-8 16.3-126.2 7.7zm-44.3-70.2l-26.4 1.7C84.6 307.2 76.9 303 65 303.8c-19 1.2-33.3 17.5-34.6 33.3-1.4 16 7.3 32.5 28.7 31.2 12.8-.8 21.3-8.6 28.9-18.9l27-1.7 2.7-29.8zm56.1-7.7c1.2-12.9-7.6-13.6-26.1-12.4l-2.7 28.5c14.2-.9 27.5-2.1 28.8-16.1zm21.1 70.8l5.8-60c-5 13.5-14.7 21.1-27.9 26.6l22.1 33.4zm135.4-45l-7.9-37.8-15.8 39.3 23.7-1.5zm-170.1-74.6l-4.3-17.5-39.6 2.6-8.1 18.2-31.9 2.1 57-121.9 23.9-1.6 30.7 102 9.9-104.7 27-1.8 37.8 63.6 6.5-66.6 28.5-1.9-4 41.2c7.4-13.5 22.9-44.7 63.6-47.5 40.5-2.8 52.4 29.3 53.4 30.3l3.3-32 39.3-2.7c12.7-.9 27.8.3 36.3 9.7l-4.4-11.9 32.2-2.2 12.9 43.2 23-45.7 31-2.2-43.6 78.4-4.8 44.3-28.4 1.9 4.8-44.3-15.8-43c1 22.3-9.2 40.1-32 49.6l25.2 38.8-36.4 2.4-19.2-36.8-4 38.3-28.4 1.9 3.3-31.5c-6.7 9.3-19.7 35.4-59.6 38-26.2 1.7-45.6-10.3-55.4-39.2l-4 40.3-25 1.6-37.6-63.3-6.3 66.2-56.8 3.7zm276.6-82.1c10.2-.7 17.5-2.1 21.6-4.3 4.5-2.4 7-6.4 7.6-12.1.6-5.3-.6-8.8-3.4-10.4-3.6-2.1-10.6-2.8-22.9-2l-2.9 28.8zM327.7 214c5.6 5.9 12.7 8.5 21.3 7.9 4.7-.3 9.1-1.8 13.3-4.1 5.5-3 10.6-8 15.1-14.3l-34.2 2.3 2.4-23.9 63.1-4.3 1.2-12-31.2 2.1c-4.1-3.7-7.8-6.6-11.1-8.1-4-1.7-8.1-2.8-12.2-2.5-8 .5-15.3 3.6-22 9.2-7.7 6.4-12 14.5-12.9 24.4-1.1 9.6 1.4 17.3 7.2 23.3zm-201.3 8.2l23.8-1.6-8.3-37.6-15.5 39.2z\"],\n    \"angular\": [448, 512, [], \"f420\", \"M185.7 268.1h76.2l-38.1-91.6-38.1 91.6zM223.8 32L16 106.4l31.8 275.7 176 97.9 176-97.9 31.8-275.7zM354 373.8h-48.6l-26.2-65.4H168.6l-26.2 65.4H93.7L223.8 81.5z\"],\n    \"app-store\": [512, 512, [], \"f36f\", \"M255.9 120.9l9.1-15.7c5.6-9.8 18.1-13.1 27.9-7.5 9.8 5.6 13.1 18.1 7.5 27.9l-87.5 151.5h63.3c20.5 0 32 24.1 23.1 40.8H113.8c-11.3 0-20.4-9.1-20.4-20.4 0-11.3 9.1-20.4 20.4-20.4h52l66.6-115.4-20.8-36.1c-5.6-9.8-2.3-22.2 7.5-27.9 9.8-5.6 22.2-2.3 27.9 7.5l8.9 15.7zm-78.7 218l-19.6 34c-5.6 9.8-18.1 13.1-27.9 7.5-9.8-5.6-13.1-18.1-7.5-27.9l14.6-25.2c16.4-5.1 29.8-1.2 40.4 11.6zm168.9-61.7h53.1c11.3 0 20.4 9.1 20.4 20.4 0 11.3-9.1 20.4-20.4 20.4h-29.5l19.9 34.5c5.6 9.8 2.3 22.2-7.5 27.9-9.8 5.6-22.2 2.3-27.9-7.5-33.5-58.1-58.7-101.6-75.4-130.6-17.1-29.5-4.9-59.1 7.2-69.1 13.4 23 33.4 57.7 60.1 104zM256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm216 248c0 118.7-96.1 216-216 216-118.7 0-216-96.1-216-216 0-118.7 96.1-216 216-216 118.7 0 216 96.1 216 216z\"],\n    \"app-store-ios\": [448, 512, [], \"f370\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM127 384.5c-5.5 9.6-17.8 12.8-27.3 7.3-9.6-5.5-12.8-17.8-7.3-27.3l14.3-24.7c16.1-4.9 29.3-1.1 39.6 11.4L127 384.5zm138.9-53.9H84c-11 0-20-9-20-20s9-20 20-20h51l65.4-113.2-20.5-35.4c-5.5-9.6-2.2-21.8 7.3-27.3 9.6-5.5 21.8-2.2 27.3 7.3l8.9 15.4 8.9-15.4c5.5-9.6 17.8-12.8 27.3-7.3 9.6 5.5 12.8 17.8 7.3 27.3l-85.8 148.6h62.1c20.2 0 31.5 23.7 22.7 40zm98.1 0h-29l19.6 33.9c5.5 9.6 2.2 21.8-7.3 27.3-9.6 5.5-21.8 2.2-27.3-7.3-32.9-56.9-57.5-99.7-74-128.1-16.7-29-4.8-58 7.1-67.8 13.1 22.7 32.7 56.7 58.9 102h52c11 0 20 9 20 20 0 11.1-9 20-20 20z\"],\n    \"apper\": [640, 512, [], \"f371\", \"M42.1 239.1c22.2 0 29 2.8 33.5 14.6h.8v-22.9c0-11.3-4.8-15.4-17.9-15.4-11.3 0-14.4 2.5-15.1 12.8H4.8c.3-13.9 1.5-19.1 5.8-24.4C17.9 195 29.5 192 56.7 192c33 0 47.1 5 53.9 18.9 2 4.3 4 15.6 4 23.7v76.3H76.3l1.3-19.1h-1c-5.3 15.6-13.6 20.4-35.5 20.4-30.3 0-41.1-10.1-41.1-37.3 0-25.2 12.3-35.8 42.1-35.8zm17.1 48.1c13.1 0 16.9-3 16.9-13.4 0-9.1-4.3-11.6-19.6-11.6-13.1 0-17.9 3-17.9 12.1-.1 10.4 3.7 12.9 20.6 12.9zm77.8-94.9h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.2 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3H137v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm57.9-60.7h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.3 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3h-39.5v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm53.8-3.8c0-25.4 3.3-37.8 12.3-45.8 8.8-8.1 22.2-11.3 45.1-11.3 42.8 0 55.7 12.8 55.7 55.7v11.1h-75.3c-.3 2-.3 4-.3 4.8 0 16.9 4.5 21.9 20.1 21.9 13.9 0 17.9-3 17.9-13.9h37.5v2.3c0 9.8-2.5 18.9-6.8 24.7-7.3 9.8-19.6 13.6-44.3 13.6-27.5 0-41.6-3.3-50.6-12.3-8.5-8.5-11.3-21.3-11.3-50.8zm76.4-11.6c-.3-1.8-.3-3.3-.3-3.8 0-12.3-3.3-14.6-19.6-14.6-14.4 0-17.1 3-18.1 15.1l-.3 3.3h38.3zm55.6-45.3h38.3l-1.8 19.9h.7c6.8-14.9 14.4-20.2 29.7-20.2 10.8 0 19.1 3.3 23.4 9.3 5.3 7.3 6.8 14.4 6.8 34 0 1.5 0 5 .2 9.3h-35c.3-1.8.3-3.3.3-4 0-15.4-2-19.4-10.3-19.4-6.3 0-10.8 3.3-13.1 9.3-1 3-1 4.3-1 12.3v68h-38.3V192.3z\"],\n    \"apple\": [384, 512, [], \"f179\", \"M318.7 268.7c-.2-36.7 16.4-64.4 50-84.8-18.8-26.9-47.2-41.7-84.7-44.6-35.5-2.8-74.3 20.7-88.5 20.7-15 0-49.4-19.7-76.4-19.7C63.3 141.2 4 184.8 4 273.5q0 39.3 14.4 81.2c12.8 36.7 59 126.7 107.2 125.2 25.2-.6 43-17.9 75.8-17.9 31.8 0 48.3 17.9 76.4 17.9 48.6-.7 90.4-82.5 102.6-119.3-65.2-30.7-61.7-90-61.7-91.9zm-56.6-164.2c27.3-32.4 24.8-61.9 24-72.5-24.1 1.4-52 16.4-67.9 34.9-17.5 19.8-27.8 44.3-25.6 71.9 26.1 2 49.9-11.4 69.5-34.3z\"],\n    \"apple-pay\": [640, 512, [], \"f415\", \"M116.9 158.5c-7.5 8.9-19.5 15.9-31.5 14.9-1.5-12 4.4-24.8 11.3-32.6 7.5-9.1 20.6-15.6 31.3-16.1 1.2 12.4-3.7 24.7-11.1 33.8m10.9 17.2c-17.4-1-32.3 9.9-40.5 9.9-8.4 0-21-9.4-34.8-9.1-17.9.3-34.5 10.4-43.6 26.5-18.8 32.3-4.9 80 13.3 106.3 8.9 13 19.5 27.3 33.5 26.8 13.3-.5 18.5-8.6 34.5-8.6 16.1 0 20.8 8.6 34.8 8.4 14.5-.3 23.6-13 32.5-26 10.1-14.8 14.3-29.1 14.5-29.9-.3-.3-28-10.9-28.3-42.9-.3-26.8 21.9-39.5 22.9-40.3-12.5-18.6-32-20.6-38.8-21.1m100.4-36.2v194.9h30.3v-66.6h41.9c38.3 0 65.1-26.3 65.1-64.3s-26.4-64-64.1-64h-73.2zm30.3 25.5h34.9c26.3 0 41.3 14 41.3 38.6s-15 38.8-41.4 38.8h-34.8V165zm162.2 170.9c19 0 36.6-9.6 44.6-24.9h.6v23.4h28v-97c0-28.1-22.5-46.3-57.1-46.3-32.1 0-55.9 18.4-56.8 43.6h27.3c2.3-12 13.4-19.9 28.6-19.9 18.5 0 28.9 8.6 28.9 24.5v10.8l-37.8 2.3c-35.1 2.1-54.1 16.5-54.1 41.5.1 25.2 19.7 42 47.8 42zm8.2-23.1c-16.1 0-26.4-7.8-26.4-19.6 0-12.3 9.9-19.4 28.8-20.5l33.6-2.1v11c0 18.2-15.5 31.2-36 31.2zm102.5 74.6c29.5 0 43.4-11.3 55.5-45.4L640 193h-30.8l-35.6 115.1h-.6L537.4 193h-31.6L557 334.9l-2.8 8.6c-4.6 14.6-12.1 20.3-25.5 20.3-2.4 0-7-.3-8.9-.5v23.4c1.8.4 9.3.7 11.6.7z\"],\n    \"artstation\": [512, 512, [], \"f77a\", \"M2 377.4l43 74.3A51.35 51.35 0 0 0 90.9 480h285.4l-59.2-102.6zM501.8 350L335.6 59.3A51.38 51.38 0 0 0 290.2 32h-88.4l257.3 447.6 40.7-70.5c1.9-3.2 21-29.7 2-59.1zM275 304.5l-115.5-200L44 304.5z\"],\n    \"asymmetrik\": [576, 512, [], \"f372\", \"M517.5 309.2c38.8-40 58.1-80 58.5-116.1.8-65.5-59.4-118.2-169.4-135C277.9 38.4 118.1 73.6 0 140.5 52 114 110.6 92.3 170.7 82.3c74.5-20.5 153-25.4 221.3-14.8C544.5 91.3 588.8 195 490.8 299.2c-10.2 10.8-22 21.1-35 30.6L304.9 103.4 114.7 388.9c-65.6-29.4-76.5-90.2-19.1-151.2 20.8-22.2 48.3-41.9 79.5-58.1 20-12.2 39.7-22.6 62-30.7-65.1 20.3-122.7 52.9-161.6 92.9-27.7 28.6-41.4 57.1-41.7 82.9-.5 35.1 23.4 65.1 68.4 83l-34.5 51.7h101.6l22-34.4c22.2 1 45.3 0 68.6-2.7l-22.8 37.1h135.5L340 406.3c18.6-5.3 36.9-11.5 54.5-18.7l45.9 71.8H542L468.6 349c18.5-12.1 35-25.5 48.9-39.8zm-187.6 80.5l-25-40.6-32.7 53.3c-23.4 3.5-46.7 5.1-69.2 4.4l101.9-159.3 78.7 123c-17.2 7.4-35.3 13.9-53.7 19.2z\"],\n    \"atlassian\": [512, 512, [], \"f77b\", \"M152.2 236.4c-7.7-8.2-19.7-7.7-24.8 2.8L1.6 490.2c-5 10 2.4 21.7 13.4 21.7h175c5.8.1 11-3.2 13.4-8.4 37.9-77.8 15.1-196.3-51.2-267.1zM244.4 8.1c-122.3 193.4-8.5 348.6 65 495.5 2.5 5.1 7.7 8.4 13.4 8.4H497c11.2 0 18.4-11.8 13.4-21.7 0 0-234.5-470.6-240.4-482.3-5.3-10.6-18.8-10.8-25.6.1z\"],\n    \"audible\": [640, 512, [], \"f373\", \"M640 199.9v54l-320 200L0 254v-54l320 200 320-200.1zm-194.5 72l47.1-29.4c-37.2-55.8-100.7-92.6-172.7-92.6-72 0-135.5 36.7-172.6 92.4h.3c2.5-2.3 5.1-4.5 7.7-6.7 89.7-74.4 219.4-58.1 290.2 36.3zm-220.1 18.8c16.9-11.9 36.5-18.7 57.4-18.7 34.4 0 65.2 18.4 86.4 47.6l45.4-28.4c-20.9-29.9-55.6-49.5-94.8-49.5-38.9 0-73.4 19.4-94.4 49zM103.6 161.1c131.8-104.3 318.2-76.4 417.5 62.1l.7 1 48.8-30.4C517.1 112.1 424.8 58.1 319.9 58.1c-103.5 0-196.6 53.5-250.5 135.6 9.9-10.5 22.7-23.5 34.2-32.6zm467 32.7z\"],\n    \"autoprefixer\": [640, 512, [], \"f41c\", \"M318.4 16l-161 480h77.5l25.4-81.4h119.5L405 496h77.5L318.4 16zm-40.3 341.9l41.2-130.4h1.5l40.9 130.4h-83.6zM640 405l-10-31.4L462.1 358l19.4 56.5L640 405zm-462.1-47L10 373.7 0 405l158.5 9.4 19.4-56.4z\"],\n    \"avianex\": [512, 512, [], \"f374\", \"M453.1 32h-312c-38.9 0-76.2 31.2-83.3 69.7L1.2 410.3C-5.9 448.8 19.9 480 58.9 480h312c38.9 0 76.2-31.2 83.3-69.7l56.7-308.5c7-38.6-18.8-69.8-57.8-69.8zm-58.2 347.3l-32 13.5-115.4-110c-14.7 10-29.2 19.5-41.7 27.1l22.1 64.2-17.9 12.7-40.6-61-52.4-48.1 15.7-15.4 58 31.1c9.3-10.5 20.8-22.6 32.8-34.9L203 228.9l-68.8-99.8 18.8-28.9 8.9-4.8L265 207.8l4.9 4.5c19.4-18.8 33.8-32.4 33.8-32.4 7.7-6.5 21.5-2.9 30.7 7.9 9 10.5 10.6 24.7 2.7 31.3-1.8 1.3-15.5 11.4-35.3 25.6l4.5 7.3 94.9 119.4-6.3 7.9z\"],\n    \"aviato\": [640, 512, [], \"f421\", \"M107.2 283.5l-19-41.8H36.1l-19 41.8H0l62.2-131.4 62.2 131.4h-17.2zm-45-98.1l-19.6 42.5h39.2l-19.6-42.5zm112.7 102.4l-62.2-131.4h17.1l45.1 96 45.1-96h17l-62.1 131.4zm80.6-4.3V156.4H271v127.1h-15.5zm209.1-115.6v115.6h-17.3V167.9h-41.2v-11.5h99.6v11.5h-41.1zM640 218.8c0 9.2-1.7 17.8-5.1 25.8-3.4 8-8.2 15.1-14.2 21.1-6 6-13.1 10.8-21.1 14.2-8 3.4-16.6 5.1-25.8 5.1s-17.8-1.7-25.8-5.1c-8-3.4-15.1-8.2-21.1-14.2-6-6-10.8-13-14.2-21.1-3.4-8-5.1-16.6-5.1-25.8s1.7-17.8 5.1-25.8c3.4-8 8.2-15.1 14.2-21.1 6-6 13-8.4 21.1-11.9 8-3.4 16.6-5.1 25.8-5.1s17.8 1.7 25.8 5.1c8 3.4 15.1 5.8 21.1 11.9 6 6 10.7 13.1 14.2 21.1 3.4 8 5.1 16.6 5.1 25.8zm-15.5 0c0-7.3-1.3-14-3.9-20.3-2.6-6.3-6.2-11.7-10.8-16.3-4.6-4.6-10-8.2-16.2-10.9-6.2-2.7-12.8-4-19.8-4s-13.6 1.3-19.8 4c-6.2 2.7-11.6 6.3-16.2 10.9-4.6 4.6-8.2 10-10.8 16.3-2.6 6.3-3.9 13.1-3.9 20.3 0 7.3 1.3 14 3.9 20.3 2.6 6.3 6.2 11.7 10.8 16.3 4.6 4.6 10 8.2 16.2 10.9 6.2 2.7 12.8 4 19.8 4s13.6-1.3 19.8-4c6.2-2.7 11.6-6.3 16.2-10.9 4.6-4.6 8.2-10 10.8-16.3 2.6-6.3 3.9-13.1 3.9-20.3zm-94.8 96.7v-6.3l88.9-10-242.9 13.4c.6-2.2 1.1-4.6 1.4-7.2.3-2 .5-4.2.6-6.5l64.8-8.1-64.9 1.9c0-.4-.1-.7-.1-1.1-2.8-17.2-25.5-23.7-25.5-23.7l-1.1-26.3h23.8l19 41.8h17.1L348.6 152l-62.2 131.4h17.1l19-41.8h23.6L345 268s-22.7 6.5-25.5 23.7c-.1.3-.1.7-.1 1.1l-64.9-1.9 64.8 8.1c.1 2.3.3 4.4.6 6.5.3 2.6.8 5 1.4 7.2L78.4 299.2l88.9 10v6.3c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4 0-6.2-4.6-11.3-10.5-12.2v-5.8l80.3 9v5.4c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-4.9l28.4 3.2v23.7h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9V323l38.3 4.3c8.1 11.4 19 13.6 19 13.6l-.1 6.7-5.1.2-.1 12.1h4.1l.1-5h5.2l.1 5h4.1l-.1-12.1-5.1-.2-.1-6.7s10.9-2.1 19-13.6l38.3-4.3v23.2h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9v-23.7l28.4-3.2v4.9c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-5.4l80.3-9v5.8c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4-.2-6.3-4.7-11.4-10.7-12.3zm-200.8-87.6l19.6-42.5 19.6 42.5h-17.9l-1.7-40.3-1.7 40.3h-17.9z\"],\n    \"aws\": [640, 512, [], \"f375\", \"M180.41 203.01c-.72 22.65 10.6 32.68 10.88 39.05a8.164 8.164 0 0 1-4.1 6.27l-12.8 8.96a10.66 10.66 0 0 1-5.63 1.92c-.43-.02-8.19 1.83-20.48-25.61a78.608 78.608 0 0 1-62.61 29.45c-16.28.89-60.4-9.24-58.13-56.21-1.59-38.28 34.06-62.06 70.93-60.05 7.1.02 21.6.37 46.99 6.27v-15.62c2.69-26.46-14.7-46.99-44.81-43.91-2.4.01-19.4-.5-45.84 10.11-7.36 3.38-8.3 2.82-10.75 2.82-7.41 0-4.36-21.48-2.94-24.2 5.21-6.4 35.86-18.35 65.94-18.18a76.857 76.857 0 0 1 55.69 17.28 70.285 70.285 0 0 1 17.67 52.36l-.01 69.29zM93.99 235.4c32.43-.47 46.16-19.97 49.29-30.47 2.46-10.05 2.05-16.41 2.05-27.4-9.67-2.32-23.59-4.85-39.56-4.87-15.15-1.14-42.82 5.63-41.74 32.26-1.24 16.79 11.12 31.4 29.96 30.48zm170.92 23.05c-7.86.72-11.52-4.86-12.68-10.37l-49.8-164.65c-.97-2.78-1.61-5.65-1.92-8.58a4.61 4.61 0 0 1 3.86-5.25c.24-.04-2.13 0 22.25 0 8.78-.88 11.64 6.03 12.55 10.37l35.72 140.83 33.16-140.83c.53-3.22 2.94-11.07 12.8-10.24h17.16c2.17-.18 11.11-.5 12.68 10.37l33.42 142.63L420.98 80.1c.48-2.18 2.72-11.37 12.68-10.37h19.72c.85-.13 6.15-.81 5.25 8.58-.43 1.85 3.41-10.66-52.75 169.9-1.15 5.51-4.82 11.09-12.68 10.37h-18.69c-10.94 1.15-12.51-9.66-12.68-10.75L328.67 110.7l-32.78 136.99c-.16 1.09-1.73 11.9-12.68 10.75h-18.3zm273.48 5.63c-5.88.01-33.92-.3-57.36-12.29a12.802 12.802 0 0 1-7.81-11.91v-10.75c0-8.45 6.2-6.9 8.83-5.89 10.04 4.06 16.48 7.14 28.81 9.6 36.65 7.53 52.77-2.3 56.72-4.48 13.15-7.81 14.19-25.68 5.25-34.95-10.48-8.79-15.48-9.12-53.13-21-4.64-1.29-43.7-13.61-43.79-52.36-.61-28.24 25.05-56.18 69.52-55.95 12.67-.01 46.43 4.13 55.57 15.62 1.35 2.09 2.02 4.55 1.92 7.04v10.11c0 4.44-1.62 6.66-4.87 6.66-7.71-.86-21.39-11.17-49.16-10.75-6.89-.36-39.89.91-38.41 24.97-.43 18.96 26.61 26.07 29.7 26.89 36.46 10.97 48.65 12.79 63.12 29.58 17.14 22.25 7.9 48.3 4.35 55.44-19.08 37.49-68.42 34.44-69.26 34.42zm40.2 104.86c-70.03 51.72-171.69 79.25-258.49 79.25A469.127 469.127 0 0 1 2.83 327.46c-6.53-5.89-.77-13.96 7.17-9.47a637.37 637.37 0 0 0 316.88 84.12 630.22 630.22 0 0 0 241.59-49.55c11.78-5 21.77 7.8 10.12 16.38zm29.19-33.29c-8.96-11.52-59.28-5.38-81.81-2.69-6.79.77-7.94-5.12-1.79-9.47 40.07-28.17 105.88-20.1 113.44-10.63 7.55 9.47-2.05 75.41-39.56 106.91-5.76 4.87-11.27 2.3-8.71-4.1 8.44-21.25 27.39-68.49 18.43-80.02z\"],\n    \"bandcamp\": [496, 512, [], \"f2d5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm48.2 326.1h-181L199.9 178h181l-84.7 156.1z\"],\n    \"battle-net\": [512, 512, [], \"f835\", \"M448.61 225.62c26.87.18 35.57-7.43 38.92-12.37 12.47-16.32-7.06-47.6-52.85-71.33 17.76-33.58 30.11-63.68 36.34-85.3 3.38-11.83 1.09-19 .45-20.25-1.72 10.52-15.85 48.46-48.2 100.05-25-11.22-56.52-20.1-93.77-23.8-8.94-16.94-34.88-63.86-60.48-88.93C252.18 7.14 238.7 1.07 228.18.22h-.05c-13.83-1.55-22.67 5.85-27.4 11-17.2 18.53-24.33 48.87-25 84.07-7.24-12.35-17.17-24.63-28.5-25.93h-.18c-20.66-3.48-38.39 29.22-36 81.29-38.36 1.38-71 5.75-93 11.23-9.9 2.45-16.22 7.27-17.76 9.72 1-.38 22.4-9.22 111.56-9.22 5.22 53 29.75 101.82 26 93.19-9.73 15.4-38.24 62.36-47.31 97.7-5.87 22.88-4.37 37.61.15 47.14 5.57 12.75 16.41 16.72 23.2 18.26 25 5.71 55.38-3.63 86.7-21.14-7.53 12.84-13.9 28.51-9.06 39.34 7.31 19.65 44.49 18.66 88.44-9.45 20.18 32.18 40.07 57.94 55.7 74.12a39.79 39.79 0 0 0 8.75 7.09c5.14 3.21 8.58 3.37 8.58 3.37-8.24-6.75-34-38-62.54-91.78 22.22-16 45.65-38.87 67.47-69.27 122.82 4.6 143.29-24.76 148-31.64 14.67-19.88 3.43-57.44-57.32-93.69zm-77.85 106.22c23.81-37.71 30.34-67.77 29.45-92.33 27.86 17.57 47.18 37.58 49.06 58.83 1.14 12.93-8.1 29.12-78.51 33.5zM216.9 387.69c9.76-6.23 19.53-13.12 29.2-20.49 6.68 13.33 13.6 26.1 20.6 38.19-40.6 21.86-68.84 12.76-49.8-17.7zm215-171.35c-10.29-5.34-21.16-10.34-32.38-15.05a722.459 722.459 0 0 0 22.74-36.9c39.06 24.1 45.9 53.18 9.64 51.95zM279.18 398c-5.51-11.35-11-23.5-16.5-36.44 43.25 1.27 62.42-18.73 63.28-20.41 0 .07-25 15.64-62.53 12.25a718.78 718.78 0 0 0 85.06-84q13.06-15.31 24.93-31.11c-.36-.29-1.54-3-16.51-12-51.7 60.27-102.34 98-132.75 115.92-20.59-11.18-40.84-31.78-55.71-61.49-20-39.92-30-82.39-31.57-116.07 12.3.91 25.27 2.17 38.85 3.88-22.29 36.8-14.39 63-13.47 64.23 0-.07-.95-29.17 20.14-59.57a695.23 695.23 0 0 0 44.67 152.84c.93-.38 1.84.88 18.67-8.25-26.33-74.47-33.76-138.17-34-173.43 20-12.42 48.18-19.8 81.63-17.81 44.57 2.67 86.36 15.25 116.32 30.71q-10.69 15.66-23.33 32.47C365.63 152 339.1 145.84 337.5 146c.11 0 25.9 14.07 41.52 47.22a717.63 717.63 0 0 0-115.34-31.71 646.608 646.608 0 0 0-39.39-6.05c-.07.45-1.81 1.85-2.16 20.33C300 190.28 358.78 215.68 389.36 233c.74 23.55-6.95 51.61-25.41 79.57-24.6 37.31-56.39 67.23-84.77 85.43zm27.4-287c-44.56-1.66-73.58 7.43-94.69 20.67 2-52.3 21.31-76.38 38.21-75.28C267 52.15 305 108.55 306.58 111zm-130.65 3.1c.48 12.11 1.59 24.62 3.21 37.28-14.55-.85-28.74-1.25-42.4-1.26-.08 3.24-.12-51 24.67-49.59h.09c5.76 1.09 10.63 6.88 14.43 13.57zm-28.06 162c20.76 39.7 43.3 60.57 65.25 72.31-46.79 24.76-77.53 20-84.92 4.51-.2-.21-11.13-15.3 19.67-76.81zm210.06 74.8\"],\n    \"behance\": [576, 512, [], \"f1b4\", \"M232 237.2c31.8-15.2 48.4-38.2 48.4-74 0-70.6-52.6-87.8-113.3-87.8H0v354.4h171.8c64.4 0 124.9-30.9 124.9-102.9 0-44.5-21.1-77.4-64.7-89.7zM77.9 135.9H151c28.1 0 53.4 7.9 53.4 40.5 0 30.1-19.7 42.2-47.5 42.2h-79v-82.7zm83.3 233.7H77.9V272h84.9c34.3 0 56 14.3 56 50.6 0 35.8-25.9 47-57.6 47zm358.5-240.7H376V94h143.7v34.9zM576 305.2c0-75.9-44.4-139.2-124.9-139.2-78.2 0-131.3 58.8-131.3 135.8 0 79.9 50.3 134.7 131.3 134.7 61.3 0 101-27.6 120.1-86.3H509c-6.7 21.9-34.3 33.5-55.7 33.5-41.3 0-63-24.2-63-65.3h185.1c.3-4.2.6-8.7.6-13.2zM390.4 274c2.3-33.7 24.7-54.8 58.5-54.8 35.4 0 53.2 20.8 56.2 54.8H390.4z\"],\n    \"behance-square\": [448, 512, [], \"f1b5\", \"M186.5 293c0 19.3-14 25.4-31.2 25.4h-45.1v-52.9h46c18.6.1 30.3 7.8 30.3 27.5zm-7.7-82.3c0-17.7-13.7-21.9-28.9-21.9h-39.6v44.8H153c15.1 0 25.8-6.6 25.8-22.9zm132.3 23.2c-18.3 0-30.5 11.4-31.7 29.7h62.2c-1.7-18.5-11.3-29.7-30.5-29.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM271.7 185h77.8v-18.9h-77.8V185zm-43 110.3c0-24.1-11.4-44.9-35-51.6 17.2-8.2 26.2-17.7 26.2-37 0-38.2-28.5-47.5-61.4-47.5H68v192h93.1c34.9-.2 67.6-16.9 67.6-55.9zM380 280.5c0-41.1-24.1-75.4-67.6-75.4-42.4 0-71.1 31.8-71.1 73.6 0 43.3 27.3 73 71.1 73 33.2 0 54.7-14.9 65.1-46.8h-33.7c-3.7 11.9-18.6 18.1-30.2 18.1-22.4 0-34.1-13.1-34.1-35.3h100.2c.1-2.3.3-4.8.3-7.2z\"],\n    \"bimobject\": [448, 512, [], \"f378\", \"M416 32H32C14.4 32 0 46.4 0 64v384c0 17.6 14.4 32 32 32h384c17.6 0 32-14.4 32-32V64c0-17.6-14.4-32-32-32zm-64 257.4c0 49.4-11.4 82.6-103.8 82.6h-16.9c-44.1 0-62.4-14.9-70.4-38.8h-.9V368H96V136h64v74.7h1.1c4.6-30.5 39.7-38.8 69.7-38.8h17.3c92.4 0 103.8 33.1 103.8 82.5v35zm-64-28.9v22.9c0 21.7-3.4 33.8-38.4 33.8h-45.3c-28.9 0-44.1-6.5-44.1-35.7v-19c0-29.3 15.2-35.7 44.1-35.7h45.3c35-.2 38.4 12 38.4 33.7z\"],\n    \"bitbucket\": [512, 512, [], \"f171\", \"M22.2 32A16 16 0 0 0 6 47.8a26.35 26.35 0 0 0 .2 2.8l67.9 412.1a21.77 21.77 0 0 0 21.3 18.2h325.7a16 16 0 0 0 16-13.4L505 50.7a16 16 0 0 0-13.2-18.3 24.58 24.58 0 0 0-2.8-.2L22.2 32zm285.9 297.8h-104l-28.1-147h157.3l-25.2 147z\"],\n    \"bitcoin\": [512, 512, [], \"f379\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-141.651-35.33c4.937-32.999-20.191-50.739-54.55-62.573l11.146-44.702-27.213-6.781-10.851 43.524c-7.154-1.783-14.502-3.464-21.803-5.13l10.929-43.81-27.198-6.781-11.153 44.686c-5.922-1.349-11.735-2.682-17.377-4.084l.031-.14-37.53-9.37-7.239 29.062s20.191 4.627 19.765 4.913c11.022 2.751 13.014 10.044 12.68 15.825l-12.696 50.925c.76.194 1.744.473 2.829.907-.907-.225-1.876-.473-2.876-.713l-17.796 71.338c-1.349 3.348-4.767 8.37-12.471 6.464.271.395-19.78-4.937-19.78-4.937l-13.51 31.147 35.414 8.827c6.588 1.651 13.045 3.379 19.4 5.006l-11.262 45.213 27.182 6.781 11.153-44.733a1038.209 1038.209 0 0 0 21.687 5.627l-11.115 44.523 27.213 6.781 11.262-45.128c46.404 8.781 81.299 5.239 95.986-36.727 11.836-33.79-.589-53.281-25.004-65.991 17.78-4.098 31.174-15.792 34.747-39.949zm-62.177 87.179c-8.41 33.79-65.308 15.523-83.755 10.943l14.944-59.899c18.446 4.603 77.6 13.717 68.811 48.956zm8.417-87.667c-7.673 30.736-55.031 15.12-70.393 11.292l13.548-54.327c15.363 3.828 64.836 10.973 56.845 43.035z\"],\n    \"bity\": [496, 512, [], \"f37a\", \"M78.4 67.2C173.8-22 324.5-24 421.5 71c14.3 14.1-6.4 37.1-22.4 21.5-84.8-82.4-215.8-80.3-298.9-3.2-16.3 15.1-36.5-8.3-21.8-22.1zm98.9 418.6c19.3 5.7 29.3-23.6 7.9-30C73 421.9 9.4 306.1 37.7 194.8c5-19.6-24.9-28.1-30.2-7.1-32.1 127.4 41.1 259.8 169.8 298.1zm148.1-2c121.9-40.2 192.9-166.9 164.4-291-4.5-19.7-34.9-13.8-30 7.9 24.2 107.7-37.1 217.9-143.2 253.4-21.2 7-10.4 36 8.8 29.7zm-62.9-79l.2-71.8c0-8.2-6.6-14.8-14.8-14.8-8.2 0-14.8 6.7-14.8 14.8l-.2 71.8c0 8.2 6.6 14.8 14.8 14.8s14.8-6.6 14.8-14.8zm71-269c2.1 90.9 4.7 131.9-85.5 132.5-92.5-.7-86.9-44.3-85.5-132.5 0-21.8-32.5-19.6-32.5 0v71.6c0 69.3 60.7 90.9 118 90.1 57.3.8 118-20.8 118-90.1v-71.6c0-19.6-32.5-21.8-32.5 0z\"],\n    \"black-tie\": [448, 512, [], \"f27e\", \"M0 32v448h448V32H0zm316.5 325.2L224 445.9l-92.5-88.7 64.5-184-64.5-86.6h184.9L252 173.2l64.5 184z\"],\n    \"blackberry\": [512, 512, [], \"f37b\", \"M166 116.9c0 23.4-16.4 49.1-72.5 49.1H23.4l21-88.8h67.8c42.1 0 53.8 23.3 53.8 39.7zm126.2-39.7h-67.8L205.7 166h70.1c53.8 0 70.1-25.7 70.1-49.1.1-16.4-11.6-39.7-53.7-39.7zM88.8 208.1H21L0 296.9h70.1c56.1 0 72.5-23.4 72.5-49.1 0-16.3-11.7-39.7-53.8-39.7zm180.1 0h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1 0-16.3-11.7-39.7-53.7-39.7zm189.3-53.8h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7zm-28 137.9h-67.8L343.7 381h70.1c56.1 0 70.1-23.4 70.1-49.1 0-16.3-11.6-39.7-53.7-39.7zM240.8 346H173l-18.7 88.8h70.1c56.1 0 70.1-25.7 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7z\"],\n    \"blogger\": [448, 512, [], \"f37c\", \"M162.4 196c4.8-4.9 6.2-5.1 36.4-5.1 27.2 0 28.1.1 32.1 2.1 5.8 2.9 8.3 7 8.3 13.6 0 5.9-2.4 10-7.6 13.4-2.8 1.8-4.5 1.9-31.1 2.1-16.4.1-29.5-.2-31.5-.8-10.3-2.9-14.1-17.7-6.6-25.3zm61.4 94.5c-53.9 0-55.8.2-60.2 4.1-3.5 3.1-5.7 9.4-5.1 13.9.7 4.7 4.8 10.1 9.2 12 2.2 1 14.1 1.7 56.3 1.2l47.9-.6 9.2-1.5c9-5.1 10.5-17.4 3.1-24.4-5.3-4.7-5-4.7-60.4-4.7zm223.4 130.1c-3.5 28.4-23 50.4-51.1 57.5-7.2 1.8-9.7 1.9-172.9 1.8-157.8 0-165.9-.1-172-1.8-8.4-2.2-15.6-5.5-22.3-10-5.6-3.8-13.9-11.8-17-16.4-3.8-5.6-8.2-15.3-10-22C.1 423 0 420.3 0 256.3 0 93.2 0 89.7 1.8 82.6 8.1 57.9 27.7 39 53 33.4c7.3-1.6 332.1-1.9 340-.3 21.2 4.3 37.9 17.1 47.6 36.4 7.7 15.3 7-1.5 7.3 180.6.2 115.8 0 164.5-.7 170.5zm-85.4-185.2c-1.1-5-4.2-9.6-7.7-11.5-1.1-.6-8-1.3-15.5-1.7-12.4-.6-13.8-.8-17.8-3.1-6.2-3.6-7.9-7.6-8-18.3 0-20.4-8.5-39.4-25.3-56.5-12-12.2-25.3-20.5-40.6-25.1-3.6-1.1-11.8-1.5-39.2-1.8-42.9-.5-52.5.4-67.1 6.2-27 10.7-46.3 33.4-53.4 62.4-1.3 5.4-1.6 14.2-1.9 64.3-.4 62.8 0 72.1 4 84.5 9.7 30.7 37.1 53.4 64.6 58.4 9.2 1.7 122.2 2.1 133.7.5 20.1-2.7 35.9-10.8 50.7-25.9 10.7-10.9 17.4-22.8 21.8-38.5 3.2-10.9 2.9-88.4 1.7-93.9z\"],\n    \"blogger-b\": [448, 512, [], \"f37d\", \"M446.6 222.7c-1.8-8-6.8-15.4-12.5-18.5-1.8-1-13-2.2-25-2.7-20.1-.9-22.3-1.3-28.7-5-10.1-5.9-12.8-12.3-12.9-29.5-.1-33-13.8-63.7-40.9-91.3-19.3-19.7-40.9-33-65.5-40.5-5.9-1.8-19.1-2.4-63.3-2.9-69.4-.8-84.8.6-108.4 10C45.9 59.5 14.7 96.1 3.3 142.9 1.2 151.7.7 165.8.2 246.8c-.6 101.5.1 116.4 6.4 136.5 15.6 49.6 59.9 86.3 104.4 94.3 14.8 2.7 197.3 3.3 216 .8 32.5-4.4 58-17.5 81.9-41.9 17.3-17.7 28.1-36.8 35.2-62.1 4.9-17.6 4.5-142.8 2.5-151.7zm-322.1-63.6c7.8-7.9 10-8.2 58.8-8.2 43.9 0 45.4.1 51.8 3.4 9.3 4.7 13.4 11.3 13.4 21.9 0 9.5-3.8 16.2-12.3 21.6-4.6 2.9-7.3 3.1-50.3 3.3-26.5.2-47.7-.4-50.8-1.2-16.6-4.7-22.8-28.5-10.6-40.8zm191.8 199.8l-14.9 2.4-77.5.9c-68.1.8-87.3-.4-90.9-2-7.1-3.1-13.8-11.7-14.9-19.4-1.1-7.3 2.6-17.3 8.2-22.4 7.1-6.4 10.2-6.6 97.3-6.7 89.6-.1 89.1-.1 97.6 7.8 12.1 11.3 9.5 31.2-4.9 39.4z\"],\n    \"bluetooth\": [448, 512, [], \"f293\", \"M292.6 171.1L249.7 214l-.3-86 43.2 43.1m-43.2 219.8l43.1-43.1-42.9-42.9-.2 86zM416 259.4C416 465 344.1 512 230.9 512S32 465 32 259.4 115.4 0 228.6 0 416 53.9 416 259.4zm-158.5 0l79.4-88.6L211.8 36.5v176.9L138 139.6l-27 26.9 92.7 93-92.7 93 26.9 26.9 73.8-73.8 2.3 170 127.4-127.5-83.9-88.7z\"],\n    \"bluetooth-b\": [320, 512, [], \"f294\", \"M196.48 260.023l92.626-103.333L143.125 0v206.33l-86.111-86.111-31.406 31.405 108.061 108.399L25.608 368.422l31.406 31.405 86.111-86.111L145.84 512l148.552-148.644-97.912-103.333zm40.86-102.996l-49.977 49.978-.338-100.295 50.315 50.317zM187.363 313.04l49.977 49.978-50.315 50.316.338-100.294z\"],\n    \"bootstrap\": [448, 512, [], \"f836\", \"M292.3 311.93c0 42.41-39.72 41.43-43.92 41.43h-80.89v-81.69h80.89c42.56 0 43.92 31.9 43.92 40.26zm-50.15-73.13c.67 0 38.44 1 38.44-36.31 0-15.52-3.51-35.87-38.44-35.87h-74.66v72.18h74.66zM448 106.67v298.66A74.89 74.89 0 0 1 373.33 480H74.67A74.89 74.89 0 0 1 0 405.33V106.67A74.89 74.89 0 0 1 74.67 32h298.66A74.89 74.89 0 0 1 448 106.67zM338.05 317.86c0-21.57-6.65-58.29-49.05-67.35v-.73c22.91-9.78 37.34-28.25 37.34-55.64 0-7 2-64.78-77.6-64.78h-127v261.33c128.23 0 139.87 1.68 163.6-5.71 14.21-4.42 52.71-17.98 52.71-67.12z\"],\n    \"btc\": [384, 512, [], \"f15a\", \"M310.204 242.638c27.73-14.18 45.377-39.39 41.28-81.3-5.358-57.351-52.458-76.573-114.85-81.929V0h-48.528v77.203c-12.605 0-25.525.315-38.444.63V0h-48.528v79.409c-17.842.539-38.622.276-97.37 0v51.678c38.314-.678 58.417-3.14 63.023 21.427v217.429c-2.925 19.492-18.524 16.685-53.255 16.071L3.765 443.68c88.481 0 97.37.315 97.37.315V512h48.528v-67.06c13.234.315 26.154.315 38.444.315V512h48.528v-68.005c81.299-4.412 135.647-24.894 142.895-101.467 5.671-61.446-23.32-88.862-69.326-99.89zM150.608 134.553c27.415 0 113.126-8.507 113.126 48.528 0 54.515-85.71 48.212-113.126 48.212v-96.74zm0 251.776V279.821c32.772 0 133.127-9.138 133.127 53.255-.001 60.186-100.355 53.253-133.127 53.253z\"],\n    \"buffer\": [448, 512, [], \"f837\", \"M427.84 380.67l-196.5 97.82a18.6 18.6 0 0 1-14.67 0L20.16 380.67c-4-2-4-5.28 0-7.29L67.22 350a18.65 18.65 0 0 1 14.69 0l134.76 67a18.51 18.51 0 0 0 14.67 0l134.76-67a18.62 18.62 0 0 1 14.68 0l47.06 23.43c4.05 1.96 4.05 5.24 0 7.24zm0-136.53l-47.06-23.43a18.62 18.62 0 0 0-14.68 0l-134.76 67.08a18.68 18.68 0 0 1-14.67 0L81.91 220.71a18.65 18.65 0 0 0-14.69 0l-47.06 23.43c-4 2-4 5.29 0 7.31l196.51 97.8a18.6 18.6 0 0 0 14.67 0l196.5-97.8c4.05-2.02 4.05-5.3 0-7.31zM20.16 130.42l196.5 90.29a20.08 20.08 0 0 0 14.67 0l196.51-90.29c4-1.86 4-4.89 0-6.74L231.33 33.4a19.88 19.88 0 0 0-14.67 0l-196.5 90.28c-4.05 1.85-4.05 4.88 0 6.74z\"],\n    \"buromobelexperte\": [448, 512, [], \"f37f\", \"M0 32v128h128V32H0zm120 120H8V40h112v112zm40-120v128h128V32H160zm120 120H168V40h112v112zm40-120v128h128V32H320zm120 120H328V40h112v112zM0 192v128h128V192H0zm120 120H8V200h112v112zm40-120v128h128V192H160zm120 120H168V200h112v112zm40-120v128h128V192H320zm120 120H328V200h112v112zM0 352v128h128V352H0zm120 120H8V360h112v112zm40-120v128h128V352H160zm120 120H168V360h112v112zm40-120v128h128V352H320z\"],\n    \"buysellads\": [448, 512, [], \"f20d\", \"M224 150.7l42.9 160.7h-85.8L224 150.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-65.3 325.3l-94.5-298.7H159.8L65.3 405.3H156l111.7-91.6 24.2 91.6h90.8z\"],\n    \"canadian-maple-leaf\": [512, 512, [], \"f785\", \"M383.8 351.7c2.5-2.5 105.2-92.4 105.2-92.4l-17.5-7.5c-10-4.9-7.4-11.5-5-17.4 2.4-7.6 20.1-67.3 20.1-67.3s-47.7 10-57.7 12.5c-7.5 2.4-10-2.5-12.5-7.5s-15-32.4-15-32.4-52.6 59.9-55.1 62.3c-10 7.5-20.1 0-17.6-10 0-10 27.6-129.6 27.6-129.6s-30.1 17.4-40.1 22.4c-7.5 5-12.6 5-17.6-5C293.5 72.3 255.9 0 255.9 0s-37.5 72.3-42.5 79.8c-5 10-10 10-17.6 5-10-5-40.1-22.4-40.1-22.4S183.3 182 183.3 192c2.5 10-7.5 17.5-17.6 10-2.5-2.5-55.1-62.3-55.1-62.3S98.1 167 95.6 172s-5 9.9-12.5 7.5C73 177 25.4 167 25.4 167s17.6 59.7 20.1 67.3c2.4 6 5 12.5-5 17.4L23 259.3s102.6 89.9 105.2 92.4c5.1 5 10 7.5 5.1 22.5-5.1 15-10.1 35.1-10.1 35.1s95.2-20.1 105.3-22.6c8.7-.9 18.3 2.5 18.3 12.5S241 512 241 512h30s-5.8-102.7-5.8-112.8 9.5-13.4 18.4-12.5c10 2.5 105.2 22.6 105.2 22.6s-5-20.1-10-35.1 0-17.5 5-22.5z\"],\n    \"cc-amazon-pay\": [576, 512, [], \"f42d\", \"M124.7 201.8c.1-11.8 0-23.5 0-35.3v-35.3c0-1.3.4-2 1.4-2.7 11.5-8 24.1-12.1 38.2-11.1 12.5.9 22.7 7 28.1 21.7 3.3 8.9 4.1 18.2 4.1 27.7 0 8.7-.7 17.3-3.4 25.6-5.7 17.8-18.7 24.7-35.7 23.9-11.7-.5-21.9-5-31.4-11.7-.9-.8-1.4-1.6-1.3-2.8zm154.9 14.6c4.6 1.8 9.3 2 14.1 1.5 11.6-1.2 21.9-5.7 31.3-12.5.9-.6 1.3-1.3 1.3-2.5-.1-3.9 0-7.9 0-11.8 0-4-.1-8 0-12 0-1.4-.4-2-1.8-2.2-7-.9-13.9-2.2-20.9-2.9-7-.6-14-.3-20.8 1.9-6.7 2.2-11.7 6.2-13.7 13.1-1.6 5.4-1.6 10.8.1 16.2 1.6 5.5 5.2 9.2 10.4 11.2zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zm-207.5 23.9c.4 1.7.9 3.4 1.6 5.1 16.5 40.6 32.9 81.3 49.5 121.9 1.4 3.5 1.7 6.4.2 9.9-2.8 6.2-4.9 12.6-7.8 18.7-2.6 5.5-6.7 9.5-12.7 11.2-4.2 1.1-8.5 1.3-12.9.9-2.1-.2-4.2-.7-6.3-.8-2.8-.2-4.2 1.1-4.3 4-.1 2.8-.1 5.6 0 8.3.1 4.6 1.6 6.7 6.2 7.5 4.7.8 9.4 1.6 14.2 1.7 14.3.3 25.7-5.4 33.1-17.9 2.9-4.9 5.6-10.1 7.7-15.4 19.8-50.1 39.5-100.3 59.2-150.5.6-1.5 1.1-3 1.3-4.6.4-2.4-.7-3.6-3.1-3.7-5.6-.1-11.1 0-16.7 0-3.1 0-5.3 1.4-6.4 4.3-.4 1.1-.9 2.3-1.3 3.4l-29.1 83.7c-2.1 6.1-4.2 12.1-6.5 18.6-.4-.9-.6-1.4-.8-1.9-10.8-29.9-21.6-59.9-32.4-89.8-1.7-4.7-3.5-9.5-5.3-14.2-.9-2.5-2.7-4-5.4-4-6.4-.1-12.8-.2-19.2-.1-2.2 0-3.3 1.6-2.8 3.7zM242.4 206c1.7 11.7 7.6 20.8 18 26.6 9.9 5.5 20.7 6.2 31.7 4.6 12.7-1.9 23.9-7.3 33.8-15.5.4-.3.8-.6 1.4-1 .5 3.2.9 6.2 1.5 9.2.5 2.6 2.1 4.3 4.5 4.4 4.6.1 9.1.1 13.7 0 2.3-.1 3.8-1.6 4-3.9.1-.8.1-1.6.1-2.3v-88.8c0-3.6-.2-7.2-.7-10.8-1.6-10.8-6.2-19.7-15.9-25.4-5.6-3.3-11.8-5-18.2-5.9-3-.4-6-.7-9.1-1.1h-10c-.8.1-1.6.3-2.5.3-8.2.4-16.3 1.4-24.2 3.5-5.1 1.3-10 3.2-15 4.9-3 1-4.5 3.2-4.4 6.5.1 2.8-.1 5.6 0 8.3.1 4.1 1.8 5.2 5.7 4.1 6.5-1.7 13.1-3.5 19.7-4.8 10.3-1.9 20.7-2.7 31.1-1.2 5.4.8 10.5 2.4 14.1 7 3.1 4 4.2 8.8 4.4 13.7.3 6.9.2 13.9.3 20.8 0 .4-.1.7-.2 1.2-.4 0-.8 0-1.1-.1-8.8-2.1-17.7-3.6-26.8-4.1-9.5-.5-18.9.1-27.9 3.2-10.8 3.8-19.5 10.3-24.6 20.8-4.1 8.3-4.6 17-3.4 25.8zM98.7 106.9v175.3c0 .8 0 1.7.1 2.5.2 2.5 1.7 4.1 4.1 4.2 5.9.1 11.8.1 17.7 0 2.5 0 4-1.7 4.1-4.1.1-.8.1-1.7.1-2.5v-60.7c.9.7 1.4 1.2 1.9 1.6 15 12.5 32.2 16.6 51.1 12.9 17.1-3.4 28.9-13.9 36.7-29.2 5.8-11.6 8.3-24.1 8.7-37 .5-14.3-1-28.4-6.8-41.7-7.1-16.4-18.9-27.3-36.7-30.9-2.7-.6-5.5-.8-8.2-1.2h-7c-1.2.2-2.4.3-3.6.5-11.7 1.4-22.3 5.8-31.8 12.7-2 1.4-3.9 3-5.9 4.5-.1-.5-.3-.8-.4-1.2-.4-2.3-.7-4.6-1.1-6.9-.6-3.9-2.5-5.5-6.4-5.6h-9.7c-5.9-.1-6.9 1-6.9 6.8zM493.6 339c-2.7-.7-5.1 0-7.6 1-43.9 18.4-89.5 30.2-136.8 35.8-14.5 1.7-29.1 2.8-43.7 3.2-26.6.7-53.2-.8-79.6-4.3-17.8-2.4-35.5-5.7-53-9.9-37-8.9-72.7-21.7-106.7-38.8-8.8-4.4-17.4-9.3-26.1-14-3.8-2.1-6.2-1.5-8.2 2.1v1.7c1.2 1.6 2.2 3.4 3.7 4.8 36 32.2 76.6 56.5 122 72.9 21.9 7.9 44.4 13.7 67.3 17.5 14 2.3 28 3.8 42.2 4.5 3 .1 6 .2 9 .4.7 0 1.4.2 2.1.3h17.7c.7-.1 1.4-.3 2.1-.3 14.9-.4 29.8-1.8 44.6-4 21.4-3.2 42.4-8.1 62.9-14.7 29.6-9.6 57.7-22.4 83.4-40.1 2.8-1.9 5.7-3.8 8-6.2 4.3-4.4 2.3-10.4-3.3-11.9zm50.4-27.7c-.8-4.2-4-5.8-7.6-7-5.7-1.9-11.6-2.8-17.6-3.3-11-.9-22-.4-32.8 1.6-12 2.2-23.4 6.1-33.5 13.1-1.2.8-2.4 1.8-3.1 3-.6.9-.7 2.3-.5 3.4.3 1.3 1.7 1.6 3 1.5.6 0 1.2 0 1.8-.1l19.5-2.1c9.6-.9 19.2-1.5 28.8-.8 4.1.3 8.1 1.2 12 2.2 4.3 1.1 6.2 4.4 6.4 8.7.3 6.7-1.2 13.1-2.9 19.5-3.5 12.9-8.3 25.4-13.3 37.8-.3.8-.7 1.7-.8 2.5-.4 2.5 1 4 3.4 3.5 1.4-.3 3-1.1 4-2.1 3.7-3.6 7.5-7.2 10.6-11.2 10.7-13.8 17-29.6 20.7-46.6.7-3 1.2-6.1 1.7-9.1.2-4.7.2-9.6.2-14.5z\"],\n    \"cc-amex\": [576, 512, [], \"f1f3\", \"M325.1 167.8c0-16.4-14.1-18.4-27.4-18.4l-39.1-.3v69.3H275v-25.1h18c18.4 0 14.5 10.3 14.8 25.1h16.6v-13.5c0-9.2-1.5-15.1-11-18.4 7.4-3 11.8-10.7 11.7-18.7zm-29.4 11.3H275v-15.3h21c5.1 0 10.7 1 10.7 7.4 0 6.6-5.3 7.9-11 7.9zM279 268.6h-52.7l-21 22.8-20.5-22.8h-66.5l-.1 69.3h65.4l21.3-23 20.4 23h32.2l.1-23.3c18.9 0 49.3 4.6 49.3-23.3 0-17.3-12.3-22.7-27.9-22.7zm-103.8 54.7h-40.6v-13.8h36.3v-14.1h-36.3v-12.5h41.7l17.9 20.2zm65.8 8.2l-25.3-28.1L241 276zm37.8-31h-21.2v-17.6h21.5c5.6 0 10.2 2.3 10.2 8.4 0 6.4-4.6 9.2-10.5 9.2zm-31.6-136.7v-14.6h-55.5v69.3h55.5v-14.3h-38.9v-13.8h37.8v-14.1h-37.8v-12.5zM576 255.4h-.2zm-194.6 31.9c0-16.4-14.1-18.7-27.1-18.7h-39.4l-.1 69.3h16.6l.1-25.3h17.6c11 0 14.8 2 14.8 13.8l-.1 11.5h16.6l.1-13.8c0-8.9-1.8-15.1-11-18.4 7.7-3.1 11.8-10.8 11.9-18.4zm-29.2 11.2h-20.7v-15.6h21c5.1 0 10.7 1 10.7 7.4 0 6.9-5.4 8.2-11 8.2zm-172.8-80v-69.3h-27.6l-19.7 47-21.7-47H83.3v65.7l-28.1-65.7H30.7L1 218.5h17.9l6.4-15.3h34.5l6.4 15.3H100v-54.2l24 54.2h14.6l24-54.2v54.2zM31.2 188.8l11.2-27.6 11.5 27.6zm477.4 158.9v-4.5c-10.8 5.6-3.9 4.5-156.7 4.5 0-25.2.1-23.9 0-25.2-1.7-.1-3.2-.1-9.4-.1 0 17.9-.1 6.8-.1 25.3h-39.6c0-12.1.1-15.3.1-29.2-10 6-22.8 6.4-34.3 6.2 0 14.7-.1 8.3-.1 23h-48.9c-5.1-5.7-2.7-3.1-15.4-17.4-3.2 3.5-12.8 13.9-16.1 17.4h-82v-92.3h83.1c5 5.6 2.8 3.1 15.5 17.2 3.2-3.5 12.2-13.4 15.7-17.2h58c9.8 0 18 1.9 24.3 5.6v-5.6c54.3 0 64.3-1.4 75.7 5.1v-5.1h78.2v5.2c11.4-6.9 19.6-5.2 64.9-5.2v5c10.3-5.9 16.6-5.2 54.3-5V80c0-26.5-21.5-48-48-48h-480c-26.5 0-48 21.5-48 48v109.8c9.4-21.9 19.7-46 23.1-53.9h39.7c4.3 10.1 1.6 3.7 9 21.1v-21.1h46c2.9 6.2 11.1 24 13.9 30 5.8-13.6 10.1-23.9 12.6-30h103c0-.1 11.5 0 11.6 0 43.7.2 53.6-.8 64.4 5.3v-5.3H363v9.3c7.6-6.1 17.9-9.3 30.7-9.3h27.6c0 .5 1.9.3 2.3.3H456c4.2 9.8 2.6 6 8.8 20.6v-20.6h43.3c4.9 8-1-1.8 11.2 18.4v-18.4h39.9v92h-41.6c-5.4-9-1.4-2.2-13.2-21.9v21.9h-52.8c-6.4-14.8-.1-.3-6.6-15.3h-19c-4.2 10-2.2 5.2-6.4 15.3h-26.8c-12.3 0-22.3-3-29.7-8.9v8.9h-66.5c-.3-13.9-.1-24.8-.1-24.8-1.8-.3-3.4-.2-9.8-.2v25.1H151.2v-11.4c-2.5 5.6-2.7 5.9-5.1 11.4h-29.5c-4-8.9-2.9-6.4-5.1-11.4v11.4H58.6c-4.2-10.1-2.2-5.3-6.4-15.3H33c-4.2 10-2.2 5.2-6.4 15.3H0V432c0 26.5 21.5 48 48 48h480.1c26.5 0 48-21.5 48-48v-90.4c-12.7 8.3-32.7 6.1-67.5 6.1zm36.3-64.5H575v-14.6h-32.9c-12.8 0-23.8 6.6-23.8 20.7 0 33 42.7 12.8 42.7 27.4 0 5.1-4.3 6.4-8.4 6.4h-32l-.1 14.8h32c8.4 0 17.6-1.8 22.5-8.9v-25.8c-10.5-13.8-39.3-1.3-39.3-13.5 0-5.8 4.6-6.5 9.2-6.5zm-57 39.8h-32.2l-.1 14.8h32.2c14.8 0 26.2-5.6 26.2-22 0-33.2-42.9-11.2-42.9-26.3 0-5.6 4.9-6.4 9.2-6.4h30.4v-14.6h-33.2c-12.8 0-23.5 6.6-23.5 20.7 0 33 42.7 12.5 42.7 27.4-.1 5.4-4.7 6.4-8.8 6.4zm-42.2-40.1v-14.3h-55.2l-.1 69.3h55.2l.1-14.3-38.6-.3v-13.8H445v-14.1h-37.8v-12.5zm-56.3-108.1c-.3.2-1.4 2.2-1.4 7.6 0 6 .9 7.7 1.1 7.9.2.1 1.1.5 3.4.5l7.3-16.9c-1.1 0-2.1-.1-3.1-.1-5.6 0-7 .7-7.3 1zm20.4-10.5h-.1zm-16.2-15.2c-23.5 0-34 12-34 35.3 0 22.2 10.2 34 33 34h19.2l6.4-15.3h34.3l6.6 15.3h33.7v-51.9l31.2 51.9h23.6v-69h-16.9v48.1l-29.1-48.1h-25.3v65.4l-27.9-65.4h-24.8l-23.5 54.5h-7.4c-13.3 0-16.1-8.1-16.1-19.9 0-23.8 15.7-20 33.1-19.7v-15.2zm42.1 12.1l11.2 27.6h-22.8zm-101.1-12v69.3h16.9v-69.3z\"],\n    \"cc-apple-pay\": [576, 512, [], \"f416\", \"M302.2 218.4c0 17.2-10.5 27.1-29 27.1h-24.3v-54.2h24.4c18.4 0 28.9 9.8 28.9 27.1zm47.5 62.6c0 8.3 7.2 13.7 18.5 13.7 14.4 0 25.2-9.1 25.2-21.9v-7.7l-23.5 1.5c-13.3.9-20.2 5.8-20.2 14.4zM576 79v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM127.8 197.2c8.4.7 16.8-4.2 22.1-10.4 5.2-6.4 8.6-15 7.7-23.7-7.4.3-16.6 4.9-21.9 11.3-4.8 5.5-8.9 14.4-7.9 22.8zm60.6 74.5c-.2-.2-19.6-7.6-19.8-30-.2-18.7 15.3-27.7 16-28.2-8.8-13-22.4-14.4-27.1-14.7-12.2-.7-22.6 6.9-28.4 6.9-5.9 0-14.7-6.6-24.3-6.4-12.5.2-24.2 7.3-30.5 18.6-13.1 22.6-3.4 56 9.3 74.4 6.2 9.1 13.7 19.1 23.5 18.7 9.3-.4 13-6 24.2-6 11.3 0 14.5 6 24.3 5.9 10.2-.2 16.5-9.1 22.8-18.2 6.9-10.4 9.8-20.4 10-21zm135.4-53.4c0-26.6-18.5-44.8-44.9-44.8h-51.2v136.4h21.2v-46.6h29.3c26.8 0 45.6-18.4 45.6-45zm90 23.7c0-19.7-15.8-32.4-40-32.4-22.5 0-39.1 12.9-39.7 30.5h19.1c1.6-8.4 9.4-13.9 20-13.9 13 0 20.2 6 20.2 17.2v7.5l-26.4 1.6c-24.6 1.5-37.9 11.6-37.9 29.1 0 17.7 13.7 29.4 33.4 29.4 13.3 0 25.6-6.7 31.2-17.4h.4V310h19.6v-68zM516 210.9h-21.5l-24.9 80.6h-.4l-24.9-80.6H422l35.9 99.3-1.9 6c-3.2 10.2-8.5 14.2-17.9 14.2-1.7 0-4.9-.2-6.2-.3v16.4c1.2.4 6.5.5 8.1.5 20.7 0 30.4-7.9 38.9-31.8L516 210.9z\"],\n    \"cc-diners-club\": [576, 512, [], \"f24c\", \"M239.7 79.9c-96.9 0-175.8 78.6-175.8 175.8 0 96.9 78.9 175.8 175.8 175.8 97.2 0 175.8-78.9 175.8-175.8 0-97.2-78.6-175.8-175.8-175.8zm-39.9 279.6c-41.7-15.9-71.4-56.4-71.4-103.8s29.7-87.9 71.4-104.1v207.9zm79.8.3V151.6c41.7 16.2 71.4 56.7 71.4 104.1s-29.7 87.9-71.4 104.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM329.7 448h-90.3c-106.2 0-193.8-85.5-193.8-190.2C45.6 143.2 133.2 64 239.4 64h90.3c105 0 200.7 79.2 200.7 193.8 0 104.7-95.7 190.2-200.7 190.2z\"],\n    \"cc-discover\": [576, 512, [], \"f1f2\", \"M520.4 196.1c0-7.9-5.5-12.1-15.6-12.1h-4.9v24.9h4.7c10.3 0 15.8-4.4 15.8-12.8zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-44.1 138.9c22.6 0 52.9-4.1 52.9 24.4 0 12.6-6.6 20.7-18.7 23.2l25.8 34.4h-19.6l-22.2-32.8h-2.2v32.8h-16zm-55.9.1h45.3v14H444v18.2h28.3V217H444v22.2h29.3V253H428zm-68.7 0l21.9 55.2 22.2-55.2h17.5l-35.5 84.2h-8.6l-35-84.2zm-55.9-3c24.7 0 44.6 20 44.6 44.6 0 24.7-20 44.6-44.6 44.6-24.7 0-44.6-20-44.6-44.6 0-24.7 20-44.6 44.6-44.6zm-49.3 6.1v19c-20.1-20.1-46.8-4.7-46.8 19 0 25 27.5 38.5 46.8 19.2v19c-29.7 14.3-63.3-5.7-63.3-38.2 0-31.2 33.1-53 63.3-38zm-97.2 66.3c11.4 0 22.4-15.3-3.3-24.4-15-5.5-20.2-11.4-20.2-22.7 0-23.2 30.6-31.4 49.7-14.3l-8.4 10.8c-10.4-11.6-24.9-6.2-24.9 2.5 0 4.4 2.7 6.9 12.3 10.3 18.2 6.6 23.6 12.5 23.6 25.6 0 29.5-38.8 37.4-56.6 11.3l10.3-9.9c3.7 7.1 9.9 10.8 17.5 10.8zM55.4 253H32v-82h23.4c26.1 0 44.1 17 44.1 41.1 0 18.5-13.2 40.9-44.1 40.9zm67.5 0h-16v-82h16zM544 433c0 8.2-6.8 15-15 15H128c189.6-35.6 382.7-139.2 416-160zM74.1 191.6c-5.2-4.9-11.6-6.6-21.9-6.6H48v54.2h4.2c10.3 0 17-2 21.9-6.4 5.7-5.2 8.9-12.8 8.9-20.7s-3.2-15.5-8.9-20.5z\"],\n    \"cc-jcb\": [576, 512, [], \"f24b\", \"M431.5 244.3V212c41.2 0 38.5.2 38.5.2 7.3 1.3 13.3 7.3 13.3 16 0 8.8-6 14.5-13.3 15.8-1.2.4-3.3.3-38.5.3zm42.8 20.2c-2.8-.7-3.3-.5-42.8-.5v35c39.6 0 40 .2 42.8-.5 7.5-1.5 13.5-8 13.5-17 0-8.7-6-15.5-13.5-17zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM182 192.3h-57c0 67.1 10.7 109.7-35.8 109.7-19.5 0-38.8-5.7-57.2-14.8v28c30 8.3 68 8.3 68 8.3 97.9 0 82-47.7 82-131.2zm178.5 4.5c-63.4-16-165-14.9-165 59.3 0 77.1 108.2 73.6 165 59.2V287C312.9 311.7 253 309 253 256s59.8-55.6 107.5-31.2v-28zM544 286.5c0-18.5-16.5-30.5-38-32v-.8c19.5-2.7 30.3-15.5 30.3-30.2 0-19-15.7-30-37-31 0 0 6.3-.3-120.3-.3v127.5h122.7c24.3.1 42.3-12.9 42.3-33.2z\"],\n    \"cc-mastercard\": [576, 512, [], \"f1f1\", \"M482.9 410.3c0 6.8-4.6 11.7-11.2 11.7-6.8 0-11.2-5.2-11.2-11.7 0-6.5 4.4-11.7 11.2-11.7 6.6 0 11.2 5.2 11.2 11.7zm-310.8-11.7c-7.1 0-11.2 5.2-11.2 11.7 0 6.5 4.1 11.7 11.2 11.7 6.5 0 10.9-4.9 10.9-11.7-.1-6.5-4.4-11.7-10.9-11.7zm117.5-.3c-5.4 0-8.7 3.5-9.5 8.7h19.1c-.9-5.7-4.4-8.7-9.6-8.7zm107.8.3c-6.8 0-10.9 5.2-10.9 11.7 0 6.5 4.1 11.7 10.9 11.7 6.8 0 11.2-4.9 11.2-11.7 0-6.5-4.4-11.7-11.2-11.7zm105.9 26.1c0 .3.3.5.3 1.1 0 .3-.3.5-.3 1.1-.3.3-.3.5-.5.8-.3.3-.5.5-1.1.5-.3.3-.5.3-1.1.3-.3 0-.5 0-1.1-.3-.3 0-.5-.3-.8-.5-.3-.3-.5-.5-.5-.8-.3-.5-.3-.8-.3-1.1 0-.5 0-.8.3-1.1 0-.5.3-.8.5-1.1.3-.3.5-.3.8-.5.5-.3.8-.3 1.1-.3.5 0 .8 0 1.1.3.5.3.8.3 1.1.5s.2.6.5 1.1zm-2.2 1.4c.5 0 .5-.3.8-.3.3-.3.3-.5.3-.8 0-.3 0-.5-.3-.8-.3 0-.5-.3-1.1-.3h-1.6v3.5h.8V426h.3l1.1 1.4h.8l-1.1-1.3zM576 81v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V81c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM64 220.6c0 76.5 62.1 138.5 138.5 138.5 27.2 0 53.9-8.2 76.5-23.1-72.9-59.3-72.4-171.2 0-230.5-22.6-15-49.3-23.1-76.5-23.1-76.4-.1-138.5 62-138.5 138.2zm224 108.8c70.5-55 70.2-162.2 0-217.5-70.2 55.3-70.5 162.6 0 217.5zm-142.3 76.3c0-8.7-5.7-14.4-14.7-14.7-4.6 0-9.5 1.4-12.8 6.5-2.4-4.1-6.5-6.5-12.2-6.5-3.8 0-7.6 1.4-10.6 5.4V392h-8.2v36.7h8.2c0-18.9-2.5-30.2 9-30.2 10.2 0 8.2 10.2 8.2 30.2h7.9c0-18.3-2.5-30.2 9-30.2 10.2 0 8.2 10 8.2 30.2h8.2v-23zm44.9-13.7h-7.9v4.4c-2.7-3.3-6.5-5.4-11.7-5.4-10.3 0-18.2 8.2-18.2 19.3 0 11.2 7.9 19.3 18.2 19.3 5.2 0 9-1.9 11.7-5.4v4.6h7.9V392zm40.5 25.6c0-15-22.9-8.2-22.9-15.2 0-5.7 11.9-4.8 18.5-1.1l3.3-6.5c-9.4-6.1-30.2-6-30.2 8.2 0 14.3 22.9 8.3 22.9 15 0 6.3-13.5 5.8-20.7.8l-3.5 6.3c11.2 7.6 32.6 6 32.6-7.5zm35.4 9.3l-2.2-6.8c-3.8 2.1-12.2 4.4-12.2-4.1v-16.6h13.1V392h-13.1v-11.2h-8.2V392h-7.6v7.3h7.6V416c0 17.6 17.3 14.4 22.6 10.9zm13.3-13.4h27.5c0-16.2-7.4-22.6-17.4-22.6-10.6 0-18.2 7.9-18.2 19.3 0 20.5 22.6 23.9 33.8 14.2l-3.8-6c-7.8 6.4-19.6 5.8-21.9-4.9zm59.1-21.5c-4.6-2-11.6-1.8-15.2 4.4V392h-8.2v36.7h8.2V408c0-11.6 9.5-10.1 12.8-8.4l2.4-7.6zm10.6 18.3c0-11.4 11.6-15.1 20.7-8.4l3.8-6.5c-11.6-9.1-32.7-4.1-32.7 15 0 19.8 22.4 23.8 32.7 15l-3.8-6.5c-9.2 6.5-20.7 2.6-20.7-8.6zm66.7-18.3H408v4.4c-8.3-11-29.9-4.8-29.9 13.9 0 19.2 22.4 24.7 29.9 13.9v4.6h8.2V392zm33.7 0c-2.4-1.2-11-2.9-15.2 4.4V392h-7.9v36.7h7.9V408c0-11 9-10.3 12.8-8.4l2.4-7.6zm40.3-14.9h-7.9v19.3c-8.2-10.9-29.9-5.1-29.9 13.9 0 19.4 22.5 24.6 29.9 13.9v4.6h7.9v-51.7zm7.6-75.1v4.6h.8V302h1.9v-.8h-4.6v.8h1.9zm6.6 123.8c0-.5 0-1.1-.3-1.6-.3-.3-.5-.8-.8-1.1-.3-.3-.8-.5-1.1-.8-.5 0-1.1-.3-1.6-.3-.3 0-.8.3-1.4.3-.5.3-.8.5-1.1.8-.5.3-.8.8-.8 1.1-.3.5-.3 1.1-.3 1.6 0 .3 0 .8.3 1.4 0 .3.3.8.8 1.1.3.3.5.5 1.1.8.5.3 1.1.3 1.4.3.5 0 1.1 0 1.6-.3.3-.3.8-.5 1.1-.8.3-.3.5-.8.8-1.1.3-.6.3-1.1.3-1.4zm3.2-124.7h-1.4l-1.6 3.5-1.6-3.5h-1.4v5.4h.8v-4.1l1.6 3.5h1.1l1.4-3.5v4.1h1.1v-5.4zm4.4-80.5c0-76.2-62.1-138.3-138.5-138.3-27.2 0-53.9 8.2-76.5 23.1 72.1 59.3 73.2 171.5 0 230.5 22.6 15 49.5 23.1 76.5 23.1 76.4.1 138.5-61.9 138.5-138.4z\"],\n    \"cc-paypal\": [576, 512, [], \"f1f4\", \"M186.3 258.2c0 12.2-9.7 21.5-22 21.5-9.2 0-16-5.2-16-15 0-12.2 9.5-22 21.7-22 9.3 0 16.3 5.7 16.3 15.5zM80.5 209.7h-4.7c-1.5 0-3 1-3.2 2.7l-4.3 26.7 8.2-.3c11 0 19.5-1.5 21.5-14.2 2.3-13.4-6.2-14.9-17.5-14.9zm284 0H360c-1.8 0-3 1-3.2 2.7l-4.2 26.7 8-.3c13 0 22-3 22-18-.1-10.6-9.6-11.1-18.1-11.1zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM128.3 215.4c0-21-16.2-28-34.7-28h-40c-2.5 0-5 2-5.2 4.7L32 294.2c-.3 2 1.2 4 3.2 4h19c2.7 0 5.2-2.9 5.5-5.7l4.5-26.6c1-7.2 13.2-4.7 18-4.7 28.6 0 46.1-17 46.1-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.2 8.2-5.8-8.5-14.2-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9 0 20.2-4.9 26.5-11.9-.5 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H200c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm40.5 97.9l63.7-92.6c.5-.5.5-1 .5-1.7 0-1.7-1.5-3.5-3.2-3.5h-19.2c-1.7 0-3.5 1-4.5 2.5l-26.5 39-11-37.5c-.8-2.2-3-4-5.5-4h-18.7c-1.7 0-3.2 1.8-3.2 3.5 0 1.2 19.5 56.8 21.2 62.1-2.7 3.8-20.5 28.6-20.5 31.6 0 1.8 1.5 3.2 3.2 3.2h19.2c1.8-.1 3.5-1.1 4.5-2.6zm159.3-106.7c0-21-16.2-28-34.7-28h-39.7c-2.7 0-5.2 2-5.5 4.7l-16.2 102c-.2 2 1.3 4 3.2 4h20.5c2 0 3.5-1.5 4-3.2l4.5-29c1-7.2 13.2-4.7 18-4.7 28.4 0 45.9-17 45.9-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.3 8.2-5.5-8.5-14-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9.3 0 20.5-4.9 26.5-11.9-.3 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H484c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm47.5-33.3c0-2-1.5-3.5-3.2-3.5h-18.5c-1.5 0-3 1.2-3.2 2.7l-16.2 104-.3.5c0 1.8 1.5 3.5 3.5 3.5h16.5c2.5 0 5-2.9 5.2-5.7L544 191.2v-.3zm-90 51.8c-12.2 0-21.7 9.7-21.7 22 0 9.7 7 15 16.2 15 12 0 21.7-9.2 21.7-21.5.1-9.8-6.9-15.5-16.2-15.5z\"],\n    \"cc-stripe\": [576, 512, [], \"f1f5\", \"M492.4 220.8c-8.9 0-18.7 6.7-18.7 22.7h36.7c0-16-9.3-22.7-18-22.7zM375 223.4c-8.2 0-13.3 2.9-17 7l.2 52.8c3.5 3.7 8.5 6.7 16.8 6.7 13.1 0 21.9-14.3 21.9-33.4 0-18.6-9-33.2-21.9-33.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM122.2 281.1c0 25.6-20.3 40.1-49.9 40.3-12.2 0-25.6-2.4-38.8-8.1v-33.9c12 6.4 27.1 11.3 38.9 11.3 7.9 0 13.6-2.1 13.6-8.7 0-17-54-10.6-54-49.9 0-25.2 19.2-40.2 48-40.2 11.8 0 23.5 1.8 35.3 6.5v33.4c-10.8-5.8-24.5-9.1-35.3-9.1-7.5 0-12.1 2.2-12.1 7.7 0 16 54.3 8.4 54.3 50.7zm68.8-56.6h-27V275c0 20.9 22.5 14.4 27 12.6v28.9c-4.7 2.6-13.3 4.7-24.9 4.7-21.1 0-36.9-15.5-36.9-36.5l.2-113.9 34.7-7.4v30.8H191zm74 2.4c-4.5-1.5-18.7-3.6-27.1 7.4v84.4h-35.5V194.2h30.7l2.2 10.5c8.3-15.3 24.9-12.2 29.6-10.5h.1zm44.1 91.8h-35.7V194.2h35.7zm0-142.9l-35.7 7.6v-28.9l35.7-7.6zm74.1 145.5c-12.4 0-20-5.3-25.1-9l-.1 40.2-35.5 7.5V194.2h31.3l1.8 8.8c4.9-4.5 13.9-11.1 27.8-11.1 24.9 0 48.4 22.5 48.4 63.8 0 45.1-23.2 65.5-48.6 65.6zm160.4-51.5h-69.5c1.6 16.6 13.8 21.5 27.6 21.5 14.1 0 25.2-3 34.9-7.9V312c-9.7 5.3-22.4 9.2-39.4 9.2-34.6 0-58.8-21.7-58.8-64.5 0-36.2 20.5-64.9 54.3-64.9 33.7 0 51.3 28.7 51.3 65.1 0 3.5-.3 10.9-.4 12.9z\"],\n    \"cc-visa\": [576, 512, [], \"f1f0\", \"M470.1 231.3s7.6 37.2 9.3 45H446c3.3-8.9 16-43.5 16-43.5-.2.3 3.3-9.1 5.3-14.9l2.8 13.4zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM152.5 331.2L215.7 176h-42.5l-39.3 106-4.3-21.5-14-71.4c-2.3-9.9-9.4-12.7-18.2-13.1H32.7l-.7 3.1c15.8 4 29.9 9.8 42.2 17.1l35.8 135h42.5zm94.4.2L272.1 176h-40.2l-25.1 155.4h40.1zm139.9-50.8c.2-17.7-10.6-31.2-33.7-42.3-14.1-7.1-22.7-11.9-22.7-19.2.2-6.6 7.3-13.4 23.1-13.4 13.1-.3 22.7 2.8 29.9 5.9l3.6 1.7 5.5-33.6c-7.9-3.1-20.5-6.6-36-6.6-39.7 0-67.6 21.2-67.8 51.4-.3 22.3 20 34.7 35.2 42.2 15.5 7.6 20.8 12.6 20.8 19.3-.2 10.4-12.6 15.2-24.1 15.2-16 0-24.6-2.5-37.7-8.3l-5.3-2.5-5.6 34.9c9.4 4.3 26.8 8.1 44.8 8.3 42.2.1 69.7-20.8 70-53zM528 331.4L495.6 176h-31.1c-9.6 0-16.9 2.8-21 12.9l-59.7 142.5H426s6.9-19.2 8.4-23.3H486c1.2 5.5 4.8 23.3 4.8 23.3H528z\"],\n    \"centercode\": [512, 512, [], \"f380\", \"M329.2 268.6c-3.8 35.2-35.4 60.6-70.6 56.8-35.2-3.8-60.6-35.4-56.8-70.6 3.8-35.2 35.4-60.6 70.6-56.8 35.1 3.8 60.6 35.4 56.8 70.6zm-85.8 235.1C96.7 496-8.2 365.5 10.1 224.3c11.2-86.6 65.8-156.9 139.1-192 161-77.1 349.7 37.4 354.7 216.6 4.1 147-118.4 262.2-260.5 254.8zm179.9-180c27.9-118-160.5-205.9-237.2-234.2-57.5 56.3-69.1 188.6-33.8 344.4 68.8 15.8 169.1-26.4 271-110.2z\"],\n    \"centos\": [448, 512, [], \"f789\", \"M289.6 97.5l31.6 31.7-76.3 76.5V97.5zm-162.4 31.7l76.3 76.5V97.5h-44.7zm41.5-41.6h44.7v127.9l10.8 10.8 10.8-10.8V87.6h44.7L224.2 32zm26.2 168.1l-10.8-10.8H55.5v-44.8L0 255.7l55.5 55.6v-44.8h128.6l10.8-10.8zm79.3-20.7h107.9v-44.8l-31.6-31.7zm173.3 20.7L392 200.1v44.8H264.3l-10.8 10.8 10.8 10.8H392v44.8l55.5-55.6zM65.4 176.2l32.5-31.7 90.3 90.5h15.3v-15.3l-90.3-90.5 31.6-31.7H65.4zm316.7-78.7h-78.5l31.6 31.7-90.3 90.5V235h15.3l90.3-90.5 31.6 31.7zM203.5 413.9V305.8l-76.3 76.5 31.6 31.7h44.7zM65.4 235h108.8l-76.3-76.5-32.5 31.7zm316.7 100.2l-31.6 31.7-90.3-90.5h-15.3v15.3l90.3 90.5-31.6 31.7h78.5zm0-58.8H274.2l76.3 76.5 31.6-31.7zm-60.9 105.8l-76.3-76.5v108.1h44.7zM97.9 352.9l76.3-76.5H65.4v44.8zm181.8 70.9H235V295.9l-10.8-10.8-10.8 10.8v127.9h-44.7l55.5 55.6zm-166.5-41.6l90.3-90.5v-15.3h-15.3l-90.3 90.5-32.5-31.7v78.7h79.4z\"],\n    \"chrome\": [496, 512, [], \"f268\", \"M131.5 217.5L55.1 100.1c47.6-59.2 119-91.8 192-92.1 42.3-.3 85.5 10.5 124.8 33.2 43.4 25.2 76.4 61.4 97.4 103L264 133.4c-58.1-3.4-113.4 29.3-132.5 84.1zm32.9 38.5c0 46.2 37.4 83.6 83.6 83.6s83.6-37.4 83.6-83.6-37.4-83.6-83.6-83.6-83.6 37.3-83.6 83.6zm314.9-89.2L339.6 174c37.9 44.3 38.5 108.2 6.6 157.2L234.1 503.6c46.5 2.5 94.4-7.7 137.8-32.9 107.4-62 150.9-192 107.4-303.9zM133.7 303.6L40.4 120.1C14.9 159.1 0 205.9 0 256c0 124 90.8 226.7 209.5 244.9l63.7-124.8c-57.6 10.8-113.2-20.8-139.5-72.5z\"],\n    \"chromecast\": [512, 512, [], \"f838\", \"M447.83 64H64a42.72 42.72 0 0 0-42.72 42.72v63.92H64v-63.92h383.83v298.56H298.64V448H448a42.72 42.72 0 0 0 42.72-42.72V106.72A42.72 42.72 0 0 0 448 64zM21.28 383.58v63.92h63.91a63.91 63.91 0 0 0-63.91-63.92zm0-85.28V341a106.63 106.63 0 0 1 106.64 106.66v.34h42.72a149.19 149.19 0 0 0-149-149.36h-.33zm0-85.27v42.72c106-.1 192 85.75 192.08 191.75v.5h42.72c-.46-129.46-105.34-234.27-234.8-234.64z\"],\n    \"cloudscale\": [448, 512, [], \"f383\", \"M318.1 154l-9.4 7.6c-22.5-19.3-51.5-33.6-83.3-33.6C153.8 128 96 188.8 96 260.3c0 6.6.4 13.1 1.4 19.4-2-56 41.8-97.4 92.6-97.4 24.2 0 46.2 9.4 62.6 24.7l-25.2 20.4c-8.3-.9-16.8 1.8-23.1 8.1-11.1 11-11.1 28.9 0 40 11.1 11 28.9 11 40 0 6.3-6.3 9-14.9 8.1-23.1l75.2-88.8c6.3-6.5-3.3-15.9-9.5-9.6zm-83.8 111.5c-5.6 5.5-14.6 5.5-20.2 0-5.6-5.6-5.6-14.6 0-20.2s14.6-5.6 20.2 0 5.6 14.7 0 20.2zM224 32C100.5 32 0 132.5 0 256s100.5 224 224 224 224-100.5 224-224S347.5 32 224 32zm0 384c-88.2 0-160-71.8-160-160S135.8 96 224 96s160 71.8 160 160-71.8 160-160 160z\"],\n    \"cloudsmith\": [332, 512, [], \"f384\", \"M332.5 419.9c0 46.4-37.6 84.1-84 84.1s-84-37.7-84-84.1 37.6-84 84-84 84 37.6 84 84zm-84-243.9c46.4 0 80-37.6 80-84s-33.6-84-80-84-88 37.6-88 84-29.6 76-76 76-84 41.6-84 88 37.6 80 84 80 84-33.6 84-80 33.6-80 80-80z\"],\n    \"cloudversify\": [616, 512, [], \"f385\", \"M148.6 304c8.2 68.5 67.4 115.5 146 111.3 51.2 43.3 136.8 45.8 186.4-5.6 69.2 1.1 118.5-44.6 131.5-99.5 14.8-62.5-18.2-132.5-92.1-155.1-33-88.1-131.4-101.5-186.5-85-57.3 17.3-84.3 53.2-99.3 109.7-7.8 2.7-26.5 8.9-45 24.1 11.7 0 15.2 8.9 15.2 19.5v20.4c0 10.7-8.7 19.5-19.5 19.5h-20.2c-10.7 0-19.5-6-19.5-16.7V240H98.8C95 240 88 244.3 88 251.9v40.4c0 6.4 5.3 11.8 11.7 11.8h48.9zm227.4 8c-10.7 46.3 21.7 72.4 55.3 86.8C324.1 432.6 259.7 348 296 288c-33.2 21.6-33.7 71.2-29.2 92.9-17.9-12.4-53.8-32.4-57.4-79.8-3-39.9 21.5-75.7 57-93.9C297 191.4 369.9 198.7 400 248c-14.1-48-53.8-70.1-101.8-74.8 30.9-30.7 64.4-50.3 114.2-43.7 69.8 9.3 133.2 82.8 67.7 150.5 35-16.3 48.7-54.4 47.5-76.9l10.5 19.6c11.8 22 15.2 47.6 9.4 72-9.2 39-40.6 68.8-79.7 76.5-32.1 6.3-83.1-5.1-91.8-59.2zM128 208H88.2c-8.9 0-16.2-7.3-16.2-16.2v-39.6c0-8.9 7.3-16.2 16.2-16.2H128c8.9 0 16.2 7.3 16.2 16.2v39.6c0 8.9-7.3 16.2-16.2 16.2zM10.1 168C4.5 168 0 163.5 0 157.9v-27.8c0-5.6 4.5-10.1 10.1-10.1h27.7c5.5 0 10.1 4.5 10.1 10.1v27.8c0 5.6-4.5 10.1-10.1 10.1H10.1zM168 142.7v-21.4c0-5.1 4.2-9.3 9.3-9.3h21.4c5.1 0 9.3 4.2 9.3 9.3v21.4c0 5.1-4.2 9.3-9.3 9.3h-21.4c-5.1 0-9.3-4.2-9.3-9.3zM56 235.5v25c0 6.3-5.1 11.5-11.4 11.5H19.4C13.1 272 8 266.8 8 260.5v-25c0-6.3 5.1-11.5 11.4-11.5h25.1c6.4 0 11.5 5.2 11.5 11.5z\"],\n    \"codepen\": [512, 512, [], \"f1cb\", \"M502.285 159.704l-234-156c-7.987-4.915-16.511-4.96-24.571 0l-234 156C3.714 163.703 0 170.847 0 177.989v155.999c0 7.143 3.714 14.286 9.715 18.286l234 156.022c7.987 4.915 16.511 4.96 24.571 0l234-156.022c6-3.999 9.715-11.143 9.715-18.286V177.989c-.001-7.142-3.715-14.286-9.716-18.285zM278 63.131l172.286 114.858-76.857 51.429L278 165.703V63.131zm-44 0v102.572l-95.429 63.715-76.857-51.429L234 63.131zM44 219.132l55.143 36.857L44 292.846v-73.714zm190 229.715L61.714 333.989l76.857-51.429L234 346.275v102.572zm22-140.858l-77.715-52 77.715-52 77.715 52-77.715 52zm22 140.858V346.275l95.429-63.715 76.857 51.429L278 448.847zm190-156.001l-55.143-36.857L468 219.132v73.714z\"],\n    \"codiepie\": [472, 512, [], \"f284\", \"M422.5 202.9c30.7 0 33.5 53.1-.3 53.1h-10.8v44.3h-26.6v-97.4h37.7zM472 352.6C429.9 444.5 350.4 504 248 504 111 504 0 393 0 256S111 8 248 8c97.4 0 172.8 53.7 218.2 138.4l-186 108.8L472 352.6zm-38.5 12.5l-60.3-30.7c-27.1 44.3-70.4 71.4-122.4 71.4-82.5 0-149.2-66.7-149.2-148.9 0-82.5 66.7-149.2 149.2-149.2 48.4 0 88.9 23.5 116.9 63.4l59.5-34.6c-40.7-62.6-104.7-100-179.2-100-121.2 0-219.5 98.3-219.5 219.5S126.8 475.5 248 475.5c78.6 0 146.5-42.1 185.5-110.4z\"],\n    \"confluence\": [512, 512, [], \"f78d\", \"M2.3 412.2c-4.5 7.6-2.1 17.5 5.5 22.2l105.9 65.2c7.7 4.7 17.7 2.4 22.4-5.3 0-.1.1-.2.1-.2 67.1-112.2 80.5-95.9 280.9-.7 8.1 3.9 17.8.4 21.7-7.7.1-.1.1-.3.2-.4l50.4-114.1c3.6-8.1-.1-17.6-8.1-21.3-22.2-10.4-66.2-31.2-105.9-50.3C127.5 179 44.6 345.3 2.3 412.2zm507.4-312.1c4.5-7.6 2.1-17.5-5.5-22.2L398.4 12.8c-7.5-5-17.6-3.1-22.6 4.4-.2.3-.4.6-.6 1-67.3 112.6-81.1 95.6-280.6.9-8.1-3.9-17.8-.4-21.7 7.7-.1.1-.1.3-.2.4L22.2 141.3c-3.6 8.1.1 17.6 8.1 21.3 22.2 10.4 66.3 31.2 106 50.4 248 120 330.8-45.4 373.4-112.9z\"],\n    \"connectdevelop\": [576, 512, [], \"f20e\", \"M550.5 241l-50.089-86.786c1.071-2.142 1.875-4.553 1.875-7.232 0-8.036-6.696-14.733-14.732-15.001l-55.447-95.893c.536-1.607 1.071-3.214 1.071-4.821 0-8.571-6.964-15.268-15.268-15.268-4.821 0-8.839 2.143-11.786 5.625H299.518C296.839 18.143 292.821 16 288 16s-8.839 2.143-11.518 5.625H170.411C167.464 18.143 163.447 16 158.625 16c-8.303 0-15.268 6.696-15.268 15.268 0 1.607.536 3.482 1.072 4.821l-55.983 97.233c-5.356 2.41-9.107 7.5-9.107 13.661 0 .535.268 1.071.268 1.607l-53.304 92.143c-7.232 1.339-12.59 7.5-12.59 15 0 7.232 5.089 13.393 12.054 15l55.179 95.358c-.536 1.607-.804 2.946-.804 4.821 0 7.232 5.089 13.393 12.054 14.732l51.697 89.732c-.536 1.607-1.071 3.482-1.071 5.357 0 8.571 6.964 15.268 15.268 15.268 4.821 0 8.839-2.143 11.518-5.357h106.875C279.161 493.857 283.447 496 288 496s8.839-2.143 11.518-5.357h107.143c2.678 2.946 6.696 4.821 10.982 4.821 8.571 0 15.268-6.964 15.268-15.268 0-1.607-.267-2.946-.803-4.285l51.697-90.268c6.964-1.339 12.054-7.5 12.054-14.732 0-1.607-.268-3.214-.804-4.821l54.911-95.358c6.964-1.339 12.322-7.5 12.322-15-.002-7.232-5.092-13.393-11.788-14.732zM153.535 450.732l-43.66-75.803h43.66v75.803zm0-83.839h-43.66c-.268-1.071-.804-2.142-1.339-3.214l44.999-47.41v50.624zm0-62.411l-50.357 53.304c-1.339-.536-2.679-1.34-4.018-1.607L43.447 259.75c.535-1.339.535-2.679.535-4.018s0-2.41-.268-3.482l51.965-90c2.679-.268 5.357-1.072 7.768-2.679l50.089 51.965v92.946zm0-102.322l-45.803-47.41c1.339-2.143 2.143-4.821 2.143-7.767 0-.268-.268-.804-.268-1.072l43.928-15.804v72.053zm0-80.625l-43.66 15.804 43.66-75.536v59.732zm326.519 39.108l.804 1.339L445.5 329.125l-63.75-67.232 98.036-101.518.268.268zM291.75 355.107l11.518 11.786H280.5l11.25-11.786zm-.268-11.25l-83.303-85.446 79.553-84.375 83.036 87.589-79.286 82.232zm5.357 5.893l79.286-82.232 67.5 71.25-5.892 28.125H313.714l-16.875-17.143zM410.411 44.393c1.071.536 2.142 1.072 3.482 1.34l57.857 100.714v.536c0 2.946.803 5.624 2.143 7.767L376.393 256l-83.035-87.589L410.411 44.393zm-9.107-2.143L287.732 162.518l-57.054-60.268 166.339-60h4.287zm-123.483 0c2.678 2.678 6.16 4.285 10.179 4.285s7.5-1.607 10.179-4.285h75L224.786 95.821 173.893 42.25h103.928zm-116.249 5.625l1.071-2.142a33.834 33.834 0 0 0 2.679-.804l51.161 53.84-54.911 19.821V47.875zm0 79.286l60.803-21.964 59.732 63.214-79.553 84.107-40.982-42.053v-83.304zm0 92.678L198 257.607l-36.428 38.304v-76.072zm0 87.858l42.053-44.464 82.768 85.982-17.143 17.678H161.572v-59.196zm6.964 162.053c-1.607-1.607-3.482-2.678-5.893-3.482l-1.071-1.607v-89.732h99.91l-91.607 94.821h-1.339zm129.911 0c-2.679-2.41-6.428-4.285-10.447-4.285s-7.767 1.875-10.447 4.285h-96.429l91.607-94.821h38.304l91.607 94.821H298.447zm120-11.786l-4.286 7.5c-1.339.268-2.41.803-3.482 1.339l-89.196-91.875h114.376l-17.412 83.036zm12.856-22.232l12.858-60.803h21.964l-34.822 60.803zm34.822-68.839h-20.357l4.553-21.16 17.143 18.214c-.535.803-1.071 1.874-1.339 2.946zm66.161-107.411l-55.447 96.697c-1.339.535-2.679 1.071-4.018 1.874l-20.625-21.964 34.554-163.928 45.803 79.286c-.267 1.339-.803 2.678-.803 4.285 0 1.339.268 2.411.536 3.75z\"],\n    \"contao\": [512, 512, [], \"f26d\", \"M45.4 305c14.4 67.1 26.4 129 68.2 175H34c-18.7 0-34-15.2-34-34V66c0-18.7 15.2-34 34-34h57.7C77.9 44.6 65.6 59.2 54.8 75.6c-45.4 70-27 146.8-9.4 229.4zM478 32h-90.2c21.4 21.4 39.2 49.5 52.7 84.1l-137.1 29.3c-14.9-29-37.8-53.3-82.6-43.9-24.6 5.3-41 19.3-48.3 34.6-8.8 18.7-13.2 39.8 8.2 140.3 21.1 100.2 33.7 117.7 49.5 131.2 12.9 11.1 33.4 17 58.3 11.7 44.5-9.4 55.7-40.7 57.4-73.2l137.4-29.6c3.2 71.5-18.7 125.2-57.4 163.6H478c18.7 0 34-15.2 34-34V66c0-18.8-15.2-34-34-34z\"],\n    \"cotton-bureau\": [512, 512, [], \"f89e\", \"M474.31 330.41c-23.66 91.85-94.23 144.59-201.9 148.35V429.6c0-48 26.41-74.39 74.39-74.39 62 0 99.2-37.2 99.2-99.21 0-61.37-36.53-98.28-97.38-99.06-33-69.32-146.5-64.65-177.24 0C110.52 157.72 74 194.63 74 256c0 62.13 37.27 99.41 99.4 99.41 48 0 74.55 26.23 74.55 74.39V479c-134.43-5-211.1-85.07-211.1-223 0-141.82 81.35-223.2 223.2-223.2 114.77 0 189.84 53.2 214.69 148.81H500C473.88 71.51 388.22 8 259.82 8 105 8 12 101.19 12 255.82 12 411.14 105.19 504.34 259.82 504c128.27 0 213.87-63.81 239.67-173.59zM357 182.33c41.37 3.45 64.2 29 64.2 73.67 0 48-26.43 74.41-74.4 74.41-28.61 0-49.33-9.59-61.59-27.33 83.06-16.55 75.59-99.67 71.79-120.75zm-81.68 97.36c-2.46-10.34-16.33-87 56.23-97 2.27 10.09 16.52 87.11-56.26 97zM260 132c28.61 0 49 9.67 61.44 27.61-28.36 5.48-49.36 20.59-61.59 43.45-12.23-22.86-33.23-38-61.6-43.45 12.41-17.69 33.27-27.35 61.57-27.35zm-71.52 50.72c73.17 10.57 58.91 86.81 56.49 97-72.41-9.84-59-86.95-56.25-97zM173.2 330.41c-48 0-74.4-26.4-74.4-74.41 0-44.36 22.86-70 64.22-73.67-6.75 37.2-1.38 106.53 71.65 120.75-12.14 17.63-32.84 27.3-61.14 27.3zm53.21 12.39A80.8 80.8 0 0 0 260 309.25c7.77 14.49 19.33 25.54 33.82 33.55a80.28 80.28 0 0 0-33.58 33.83c-8-14.5-19.07-26.23-33.56-33.83z\"],\n    \"cpanel\": [640, 512, [], \"f388\", \"M210.3 220.2c-5.6-24.8-26.9-41.2-51-41.2h-37c-7.1 0-12.5 4.5-14.3 10.9L73.1 320l24.7-.1c6.8 0 12.3-4.5 14.2-10.7l25.8-95.7h19.8c8.4 0 16.2 5.6 18.3 14.8 2.5 10.9-5.9 22.6-18.3 22.6h-10.3c-7 0-12.5 4.6-14.3 10.8l-6.4 23.8h32c37.2 0 58.3-36.2 51.7-65.3zm-156.5 28h18.6c6.9 0 12.4-4.4 14.3-10.9l6.2-23.6h-40C30 213.7 9 227.8 1.7 254.8-7 288.6 18.5 320 52 320h12.4l7.1-26.1c1.2-4.4-2.2-8.3-6.4-8.3H53.8c-24.7 0-24.9-37.4 0-37.4zm247.5-34.8h-77.9l-3.5 13.4c-2.4 9.6 4.5 18.5 14.2 18.5h57.5c4 0 2.4 4.3 2.1 5.3l-8.6 31.8c-.4 1.4-.9 5.3-5.5 5.3h-34.9c-5.3 0-5.3-7.9 0-7.9h21.6c6.8 0 12.3-4.6 14.2-10.8l3.5-13.2h-48.4c-39.2 0-43.6 63.8-.7 63.8l57.5.2c11.2 0 20.6-7.2 23.4-17.8l14-51.8c4.8-19.2-9.7-36.8-28.5-36.8zM633.1 179h-18.9c-4.9 0-9.2 3.2-10.4 7.9L568.2 320c20.7 0 39.8-13.8 44.9-34.5l26.5-98.2c1.2-4.3-2-8.3-6.5-8.3zm-236.3 34.7v.1h-48.3l-26.2 98c-1.2 4.4 2.2 8.3 6.4 8.3h18.9c4.8 0 9.2-3 10.4-7.8l17.2-64H395c12.5 0 21.4 11.8 18.1 23.4l-10.6 40c-1.2 4.3 1.9 8.3 6.4 8.3H428c4.6 0 9.1-2.9 10.3-7.8l8.8-33.1c9-33.1-15.9-65.4-50.3-65.4zm98.3 74.6c-3.6 0-6-3.4-5.1-6.7l8-30c.9-3.9 3.7-6 7.8-6h32.9c2.6 0 4.6 2.4 3.9 5.1l-.7 2.6c-.6 2-1.9 3-3.9 3h-21.6c-7 0-12.6 4.6-14.2 10.8l-3.5 13h53.4c10.5 0 20.3-6.6 23.2-17.6l3.2-12c4.9-19.1-9.3-36.8-28.3-36.8h-47.3c-17.9 0-33.8 12-38.6 29.6l-10.8 40c-5 17.7 8.3 36.7 28.3 36.7h66.7c6.8 0 12.3-4.5 14.2-10.7l5.7-21z\"],\n    \"creative-commons\": [496, 512, [], \"f25e\", \"M245.83 214.87l-33.22 17.28c-9.43-19.58-25.24-19.93-27.46-19.93-22.13 0-33.22 14.61-33.22 43.84 0 23.57 9.21 43.84 33.22 43.84 14.47 0 24.65-7.09 30.57-21.26l30.55 15.5c-6.17 11.51-25.69 38.98-65.1 38.98-22.6 0-73.96-10.32-73.96-77.05 0-58.69 43-77.06 72.63-77.06 30.72-.01 52.7 11.95 65.99 35.86zm143.05 0l-32.78 17.28c-9.5-19.77-25.72-19.93-27.9-19.93-22.14 0-33.22 14.61-33.22 43.84 0 23.55 9.23 43.84 33.22 43.84 14.45 0 24.65-7.09 30.54-21.26l31 15.5c-2.1 3.75-21.39 38.98-65.09 38.98-22.69 0-73.96-9.87-73.96-77.05 0-58.67 42.97-77.06 72.63-77.06 30.71-.01 52.58 11.95 65.56 35.86zM247.56 8.05C104.74 8.05 0 123.11 0 256.05c0 138.49 113.6 248 247.56 248 129.93 0 248.44-100.87 248.44-248 0-137.87-106.62-248-248.44-248zm.87 450.81c-112.54 0-203.7-93.04-203.7-202.81 0-105.42 85.43-203.27 203.72-203.27 112.53 0 202.82 89.46 202.82 203.26-.01 121.69-99.68 202.82-202.84 202.82z\"],\n    \"creative-commons-by\": [496, 512, [], \"f4e7\", \"M314.9 194.4v101.4h-28.3v120.5h-77.1V295.9h-28.3V194.4c0-4.4 1.6-8.2 4.6-11.3 3.1-3.1 6.9-4.7 11.3-4.7H299c4.1 0 7.8 1.6 11.1 4.7 3.1 3.2 4.8 6.9 4.8 11.3zm-101.5-63.7c0-23.3 11.5-35 34.5-35s34.5 11.7 34.5 35c0 23-11.5 34.5-34.5 34.5s-34.5-11.5-34.5-34.5zM247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3z\"],\n    \"creative-commons-nc\": [496, 512, [], \"f4e8\", \"M247.6 8C387.4 8 496 115.9 496 256c0 147.2-118.5 248-248.4 248C113.1 504 0 393.2 0 256 0 123.1 104.7 8 247.6 8zM55.8 189.1c-7.4 20.4-11.1 42.7-11.1 66.9 0 110.9 92.1 202.4 203.7 202.4 122.4 0 177.2-101.8 178.5-104.1l-93.4-41.6c-7.7 37.1-41.2 53-68.2 55.4v38.1h-28.8V368c-27.5-.3-52.6-10.2-75.3-29.7l34.1-34.5c31.7 29.4 86.4 31.8 86.4-2.2 0-6.2-2.2-11.2-6.6-15.1-14.2-6-1.8-.1-219.3-97.4zM248.4 52.3c-38.4 0-112.4 8.7-170.5 93l94.8 42.5c10-31.3 40.4-42.9 63.8-44.3v-38.1h28.8v38.1c22.7 1.2 43.4 8.9 62 23L295 199.7c-42.7-29.9-83.5-8-70 11.1 53.4 24.1 43.8 19.8 93 41.6l127.1 56.7c4.1-17.4 6.2-35.1 6.2-53.1 0-57-19.8-105-59.3-143.9-39.3-39.9-87.2-59.8-143.6-59.8z\"],\n    \"creative-commons-nc-eu\": [496, 512, [], \"f4e9\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.3 111.7 248 247.7 248C377.9 504 496 403.1 496 256 496 117 388.4 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-23.2 3.7-45.2 10.9-66l65.7 29.1h-4.7v29.5h23.3c0 6.2-.4 3.2-.4 19.5h-22.8v29.5h27c11.4 67 67.2 101.3 124.6 101.3 26.6 0 50.6-7.9 64.8-15.8l-10-46.1c-8.7 4.6-28.2 10.8-47.3 10.8-28.2 0-58.1-10.9-67.3-50.2h90.3l128.3 56.8c-1.5 2.1-56.2 104.3-178.8 104.3zm-16.7-190.6l-.5-.4.9.4h-.4zm77.2-19.5h3.7v-29.5h-70.3l-28.6-12.6c2.5-5.5 5.4-10.5 8.8-14.3 12.9-15.8 31.1-22.4 51.1-22.4 18.3 0 35.3 5.4 46.1 10l11.6-47.3c-15-6.6-37-12.4-62.3-12.4-39 0-72.2 15.8-95.9 42.3-5.3 6.1-9.8 12.9-13.9 20.1l-81.6-36.1c64.6-96.8 157.7-93.6 170.7-93.6 113 0 203 90.2 203 203.4 0 18.7-2.1 36.3-6.3 52.9l-136.1-60.5z\"],\n    \"creative-commons-nc-jp\": [496, 512, [], \"f4ea\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.4 111.8 248 247.7 248C377.9 504 496 403.2 496 256 496 117.2 388.5 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-21.1 3-41.2 9-60.3l127 56.5h-27.9v38.6h58.1l5.7 11.8v18.7h-63.8V360h63.8v56h61.7v-56h64.2v-35.7l81 36.1c-1.5 2.2-57.1 98.3-175.2 98.3zm87.6-137.3h-57.6v-18.7l2.9-5.6 54.7 24.3zm6.5-51.4v-17.8h-38.6l63-116H301l-43.4 96-23-10.2-39.6-85.7h-65.8l27.3 51-81.9-36.5c27.8-44.1 82.6-98.1 173.7-98.1 112.8 0 203 90 203 203.4 0 21-2.7 40.6-7.9 59l-101-45.1z\"],\n    \"creative-commons-nd\": [496, 512, [], \"f4eb\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm94 144.3v42.5H162.1V197h180.3zm0 79.8v42.5H162.1v-42.5h180.3z\"],\n    \"creative-commons-pd\": [496, 512, [], \"f4ec\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm0 449.5c-139.2 0-235.8-138-190.2-267.9l78.8 35.1c-2.1 10.5-3.3 21.5-3.3 32.9 0 99 73.9 126.9 120.4 126.9 22.9 0 53.5-6.7 79.4-29.5L297 311.1c-5.5 6.3-17.6 16.7-36.3 16.7-37.8 0-53.7-39.9-53.9-71.9 230.4 102.6 216.5 96.5 217.9 96.8-34.3 62.4-100.6 104.8-176.7 104.8zm194.2-150l-224-100c18.8-34 54.9-30.7 74.7-11l40.4-41.6c-27.1-23.3-58-27.5-78.1-27.5-47.4 0-80.9 20.5-100.7 51.6l-74.9-33.4c36.1-54.9 98.1-91.2 168.5-91.2 111.1 0 201.5 90.4 201.5 201.5 0 18-2.4 35.4-6.8 52-.3-.1-.4-.2-.6-.4z\"],\n    \"creative-commons-pd-alt\": [496, 512, [], \"f4ed\", \"M247.6 8C104.7 8 0 123.1 0 256c0 138.5 113.6 248 247.6 248C377.5 504 496 403.1 496 256 496 118.1 389.4 8 247.6 8zm.8 450.8c-112.5 0-203.7-93-203.7-202.8 0-105.4 85.5-203.3 203.7-203.3 112.6 0 202.9 89.5 202.8 203.3 0 121.7-99.6 202.8-202.8 202.8zM316.7 186h-53.2v137.2h53.2c21.4 0 70-5.1 70-68.6 0-63.4-48.6-68.6-70-68.6zm.8 108.5h-19.9v-79.7l19.4-.1c3.8 0 35-2.1 35 39.9 0 24.6-10.5 39.9-34.5 39.9zM203.7 186h-68.2v137.3h34.6V279h27c54.1 0 57.1-37.5 57.1-46.5 0-31-16.8-46.5-50.5-46.5zm-4.9 67.3h-29.2v-41.6h28.3c30.9 0 28.8 41.6.9 41.6z\"],\n    \"creative-commons-remix\": [496, 512, [], \"f4ee\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm161.7 207.7l4.9 2.2v70c-7.2 3.6-63.4 27.5-67.3 28.8-6.5-1.8-113.7-46.8-137.3-56.2l-64.2 26.6-63.3-27.5v-63.8l59.3-24.8c-.7-.7-.4 5-.4-70.4l67.3-29.7L361 178.5v61.6l49.1 20.3zm-70.4 81.5v-43.8h-.4v-1.8l-113.8-46.5V295l113.8 46.9v-.4l.4.4zm7.5-57.6l39.9-16.4-36.8-15.5-39 16.4 35.9 15.5zm52.3 38.1v-43L355.2 298v43.4l44.3-19z\"],\n    \"creative-commons-sa\": [496, 512, [], \"f4ef\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zM137.7 221c13-83.9 80.5-95.7 108.9-95.7 99.8 0 127.5 82.5 127.5 134.2 0 63.6-41 132.9-128.9 132.9-38.9 0-99.1-20-109.4-97h62.5c1.5 30.1 19.6 45.2 54.5 45.2 23.3 0 58-18.2 58-82.8 0-82.5-49.1-80.6-56.7-80.6-33.1 0-51.7 14.6-55.8 43.8h18.2l-49.2 49.2-49-49.2h19.4z\"],\n    \"creative-commons-sampling\": [496, 512, [], \"f4f0\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm3.6 53.2c2.8-.3 11.5 1 11.5 11.5l6.6 107.2 4.9-59.3c0-6 4.7-10.6 10.6-10.6 5.9 0 10.6 4.7 10.6 10.6 0 2.5-.5-5.7 5.7 81.5l5.8-64.2c.3-2.9 2.9-9.3 10.2-9.3 3.8 0 9.9 2.3 10.6 8.9l11.5 96.5 5.3-12.8c1.8-4.4 5.2-6.6 10.2-6.6h58v21.3h-50.9l-18.2 44.3c-3.9 9.9-19.5 9.1-20.8-3.1l-4-31.9-7.5 92.6c-.3 3-3 9.3-10.2 9.3-3 0-9.8-2.1-10.6-9.3 0-1.9.6 5.8-6.2-77.9l-5.3 72.2c-1.1 4.8-4.8 9.3-10.6 9.3-2.9 0-9.8-2-10.6-9.3 0-1.9.5 6.7-5.8-87.7l-5.8 94.8c0 6.3-3.6 12.4-10.6 12.4-5.2 0-10.6-4.1-10.6-12l-5.8-87.7c-5.8 92.5-5.3 84-5.3 85.9-1.1 4.8-4.8 9.3-10.6 9.3-3 0-9.8-2.1-10.6-9.3 0-.7-.4-1.1-.4-2.6l-6.2-88.6L182 348c-.7 6.5-6.7 9.3-10.6 9.3-5.8 0-9.6-4.1-10.6-8.9L149.7 272c-2 4-3.5 8.4-11.1 8.4H87.2v-21.3H132l13.7-27.9c4.4-9.9 18.2-7.2 19.9 2.7l3.1 20.4 8.4-97.9c0-6 4.8-10.6 10.6-10.6.5 0 10.6-.2 10.6 12.4l4.9 69.1 6.6-92.6c0-10.1 9.5-10.6 10.2-10.6.6 0 10.6.7 10.6 10.6l5.3 80.6 6.2-97.9c.1-1.1-.6-10.3 9.9-11.5z\"],\n    \"creative-commons-sampling-plus\": [496, 512, [], \"f4f1\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm107 205.6c-4.7 0-9 2.8-10.7 7.2l-4 9.5-11-92.8c-1.7-13.9-22-13.4-23.1.4l-4.3 51.4-5.2-68.8c-1.1-14.3-22.1-14.2-23.2 0l-3.5 44.9-5.9-94.3c-.9-14.5-22.3-14.4-23.2 0l-5.1 83.7-4.3-66.3c-.9-14.4-22.2-14.4-23.2 0l-5.3 80.2-4.1-57c-1.1-14.3-22-14.3-23.2-.2l-7.7 89.8-1.8-12.2c-1.7-11.4-17.1-13.6-22-3.3l-13.2 27.7H87.5v23.2h51.3c4.4 0 8.4-2.5 10.4-6.4l10.7 73.1c2 13.5 21.9 13 23.1-.7l3.8-43.6 5.7 78.3c1.1 14.4 22.3 14.2 23.2-.1l4.6-70.4 4.8 73.3c.9 14.4 22.3 14.4 23.2-.1l4.9-80.5 4.5 71.8c.9 14.3 22.1 14.5 23.2.2l4.6-58.6 4.9 64.4c1.1 14.3 22 14.2 23.1.1l6.8-83 2.7 22.3c1.4 11.8 17.7 14.1 22.3 3.1l18-43.4h50.5V258l-58.4.3zm-78 5.2h-21.9v21.9c0 4.1-3.3 7.5-7.5 7.5-4.1 0-7.5-3.3-7.5-7.5v-21.9h-21.9c-4.1 0-7.5-3.3-7.5-7.5 0-4.1 3.4-7.5 7.5-7.5h21.9v-21.9c0-4.1 3.4-7.5 7.5-7.5s7.5 3.3 7.5 7.5v21.9h21.9c4.1 0 7.5 3.3 7.5 7.5 0 4.1-3.4 7.5-7.5 7.5z\"],\n    \"creative-commons-share\": [496, 512, [], \"f4f2\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm101 132.4c7.8 0 13.7 6.1 13.7 13.7v182.5c0 7.7-6.1 13.7-13.7 13.7H214.3c-7.7 0-13.7-6-13.7-13.7v-54h-54c-7.8 0-13.7-6-13.7-13.7V131.1c0-8.2 6.6-12.7 12.4-13.7h136.4c7.7 0 13.7 6 13.7 13.7v54h54zM159.9 300.3h40.7V198.9c0-7.4 5.8-12.6 12-13.7h55.8v-40.3H159.9v155.4zm176.2-88.1H227.6v155.4h108.5V212.2z\"],\n    \"creative-commons-zero\": [496, 512, [], \"f4f3\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm-.4 60.5c-81.9 0-102.5 77.3-102.5 142.8 0 65.5 20.6 142.8 102.5 142.8S350.5 321.5 350.5 256c0-65.5-20.6-142.8-102.5-142.8zm0 53.9c3.3 0 6.4.5 9.2 1.2 5.9 5.1 8.8 12.1 3.1 21.9l-54.5 100.2c-1.7-12.7-1.9-25.1-1.9-34.4 0-28.8 2-88.9 44.1-88.9zm40.8 46.2c2.9 15.4 3.3 31.4 3.3 42.7 0 28.9-2 88.9-44.1 88.9-13.5 0-32.6-7.7-20.1-26.4l60.9-105.2z\"],\n    \"critical-role\": [448, 512, [], \"f6c9\", \"M225.82 0c.26.15 216.57 124.51 217.12 124.72 3 1.18 3.7 3.46 3.7 6.56q-.11 125.17 0 250.36a5.88 5.88 0 0 1-3.38 5.78c-21.37 12-207.86 118.29-218.93 124.58h-3C142 466.34 3.08 386.56 2.93 386.48a3.29 3.29 0 0 1-1.88-3.24c0-.87 0-225.94-.05-253.1a5 5 0 0 1 2.93-4.93C27.19 112.11 213.2 6 224.07 0zM215.4 20.42l-.22-.16Q118.06 75.55 21 130.87c0 .12.08.23.13.35l30.86 11.64c-7.71 6-8.32 6-10.65 5.13-.1 0-24.17-9.28-26.8-10v230.43c.88-1.41 64.07-110.91 64.13-111 1.62-2.82 3-1.92 9.12-1.52 1.4.09 1.48.22.78 1.42-41.19 71.33-36.4 63-67.48 116.94-.81 1.4-.61 1.13 1.25 1.13h186.5c1.44 0 1.69-.23 1.7-1.64v-8.88c0-1.34 2.36-.81-18.37-1-7.46-.07-14.14-3.22-21.38-12.7-7.38-9.66-14.62-19.43-21.85-29.21-2.28-3.08-3.45-2.38-16.76-2.38-1.75 0-1.78 0-1.76 1.82.29 26.21.15 25.27 1 32.66.52 4.37 2.16 4.2 9.69 4.81 3.14.26 3.88 4.08.52 4.92-1.57.39-31.6.51-33.67-.1a2.42 2.42 0 0 1 .3-4.73c3.29-.76 6.16.81 6.66-4.44 1.3-13.66 1.17-9 1.1-79.42 0-10.82-.35-12.58-5.36-13.55-1.22-.24-3.54-.16-4.69-.55-2.88-1-2-4.84 1.77-4.85 33.67 0 46.08-1.07 56.06 4.86 7.74 4.61 12 11.48 12.51 20.4.88 14.59-6.51 22.35-15 32.59a1.46 1.46 0 0 0 0 2.22c2.6 3.25 5 6.63 7.71 9.83 27.56 33.23 24.11 30.54 41.28 33.06.89.13 1-.42 1-1.15v-11c0-1 .32-1.43 1.41-1.26a72.37 72.37 0 0 0 23.58-.3c1.08-.15 1.5.2 1.48 1.33 0 .11.88 26.69.87 26.8-.05 1.52.67 1.62 1.89 1.62h186.71Q386.51 304.6 346 234.33c2.26-.66-.4 0 6.69-1.39 2-.39 2.05-.41 3.11 1.44 7.31 12.64 77.31 134 77.37 134.06V138c-1.72.5-103.3 38.72-105.76 39.68-1.08.42-1.55.2-1.91-.88-.63-1.9-1.34-3.76-2.09-5.62-.32-.79-.09-1.13.65-1.39.1 0 95.53-35.85 103-38.77-65.42-37.57-130.56-75-196-112.6l86.82 150.39-.28.33c-9.57-.9-10.46-1.6-11.8-3.94-1-1.69-73.5-127.71-82-142.16-9.1 14.67-83.56 146.21-85.37 146.32-2.93.17-5.88.08-9.25.08q43.25-74.74 86.18-149zm51.93 129.92a37.68 37.68 0 0 0 5.54-.85c1.69-.3 2.53.2 2.6 1.92 0 .11.07 19.06-.86 20.45s-1.88 1.22-2.6-.19c-5-9.69 6.22-9.66-39.12-12-.7 0-1 .23-1 .93 0 .13 3.72 122 3.73 122.11 0 .89.52 1.2 1.21 1.51a83.92 83.92 0 0 1 8.7 4.05c7.31 4.33 11.38 10.84 12.41 19.31 1.44 11.8-2.77 35.77-32.21 37.14-2.75.13-28.26 1.08-34.14-23.25-4.66-19.26 8.26-32.7 19.89-36.4a2.45 2.45 0 0 0 2-2.66c.1-5.63 3-107.1 3.71-121.35.05-1.08-.62-1.16-1.35-1.15-32.35.52-36.75-.34-40.22 8.52-2.42 6.18-4.14 1.32-3.95.23q1.59-9 3.31-18c.4-2.11 1.43-2.61 3.43-1.86 5.59 2.11 6.72 1.7 37.25 1.92 1.73 0 1.78-.08 1.82-1.85.68-27.49.58-22.59 1-29.55a2.69 2.69 0 0 0-1.63-2.8c-5.6-2.91-8.75-7.55-8.9-13.87-.35-14.81 17.72-21.67 27.38-11.51 6.84 7.19 5.8 18.91-2.45 24.15a4.35 4.35 0 0 0-2.22 4.34c0 .59-.11-4.31 1 30.05 0 .9.43 1.12 1.24 1.11.1 0 23-.09 34.47-.37zM68.27 141.7c19.84-4.51 32.68-.56 52.49 1.69 2.76.31 3.74 1.22 3.62 4-.21 5-1.16 22.33-1.24 23.15a2.65 2.65 0 0 1-1.63 2.34c-4.06 1.7-3.61-4.45-4-7.29-3.13-22.43-73.87-32.7-74.63 25.4-.31 23.92 17 53.63 54.08 50.88 27.24-2 19-20.19 24.84-20.47a2.72 2.72 0 0 1 3 3.36c-1.83 10.85-3.42 18.95-3.45 19.15-1.54 9.17-86.7 22.09-93.35-42.06-2.71-25.85 10.44-53.37 40.27-60.15zm80 87.67h-19.49a2.57 2.57 0 0 1-2.66-1.79c2.38-3.75 5.89.92 5.86-6.14-.08-25.75.21-38 .23-40.1 0-3.42-.53-4.65-3.32-4.94-7-.72-3.11-3.37-1.11-3.38 11.84-.1 22.62-.18 30.05.72 8.77 1.07 16.71 12.63 7.93 22.62-2 2.25-4 4.42-6.14 6.73.95 1.15 6.9 8.82 17.28 19.68 2.66 2.78 6.15 3.51 9.88 3.13a2.21 2.21 0 0 0 2.23-2.12c.3-3.42.26 4.73.45-40.58 0-5.65-.34-6.58-3.23-6.83-3.95-.35-4-2.26-.69-3.37l19.09-.09c.32 0 4.49.53 1 3.38 0 .05-.16 0-.24 0-3.61.26-3.94 1-4 4.62-.27 43.93.07 40.23.41 42.82.11.84.27 2.23 5.1 2.14 2.49 0 3.86 3.37 0 3.4-10.37.08-20.74 0-31.11.07-10.67 0-13.47-6.2-24.21-20.82-1.6-2.18-8.31-2.36-8.2-.37.88 16.47 0 17.78 4 17.67 4.75-.1 4.73 3.57.83 3.55zm275-10.15c-1.21 7.13.17 10.38-5.3 10.34-61.55-.42-47.82-.22-50.72-.31a18.4 18.4 0 0 1-3.63-.73c-2.53-.6 1.48-1.23-.38-5.6-1.43-3.37-2.78-6.78-4.11-10.19a1.94 1.94 0 0 0-2-1.44 138 138 0 0 0-14.58.07 2.23 2.23 0 0 0-1.62 1.06c-1.58 3.62-3.07 7.29-4.51 11-1.27 3.23 7.86 1.32 12.19 2.16 3 .57 4.53 3.72.66 3.73H322.9c-2.92 0-3.09-3.15-.74-3.21a6.3 6.3 0 0 0 5.92-3.47c1.5-3 2.8-6 4.11-9.09 18.18-42.14 17.06-40.17 18.42-41.61a1.83 1.83 0 0 1 3 0c2.93 3.34 18.4 44.71 23.62 51.92 2 2.7 5.74 2 6.36 2 3.61.13 4-1.11 4.13-4.29.09-1.87.08 1.17.07-41.24 0-4.46-2.36-3.74-5.55-4.27-.26 0-2.56-.63-.08-3.06.21-.2-.89-.24 21.7-.15 2.32 0 5.32 2.75-1.21 3.45a2.56 2.56 0 0 0-2.66 2.83c-.07 1.63-.19 38.89.29 41.21a3.06 3.06 0 0 0 3.23 2.43c13.25.43 14.92.44 16-3.41 1.67-5.78 4.13-2.52 3.73-.19zm-104.72 64.37c-4.24 0-4.42-3.39-.61-3.41 35.91-.16 28.11.38 37.19-.65 1.68-.19 2.38.24 2.25 1.89-.26 3.39-.64 6.78-1 10.16-.25 2.16-3.2 2.61-3.4-.15-.38-5.31-2.15-4.45-15.63-5.08-1.58-.07-1.64 0-1.64 1.52V304c0 1.65 0 1.6 1.62 1.47 3.12-.25 10.31.34 15.69-1.52.47-.16 3.3-1.79 3.07 1.76 0 .21-.76 10.35-1.18 11.39-.53 1.29-1.88 1.51-2.58.32-1.17-2 0-5.08-3.71-5.3-15.42-.9-12.91-2.55-12.91 6 0 12.25-.76 16.11 3.89 16.24 16.64.48 14.4 0 16.43-5.71.84-2.37 3.5-1.77 3.18.58-.44 3.21-.85 6.43-1.23 9.64 0 .36-.16 2.4-4.66 2.39-37.16-.08-34.54-.19-35.21-.31-2.72-.51-2.2-3 .22-3.45 1.1-.19 4 .54 4.16-2.56 2.44-56.22-.07-51.34-3.91-51.33zm-.41-109.52c2.46.61 3.13 1.76 2.95 4.65-.33 5.3-.34 9-.55 9.69-.66 2.23-3.15 2.12-3.34-.27-.38-4.81-3.05-7.82-7.57-9.15-26.28-7.73-32.81 15.46-27.17 30.22 5.88 15.41 22 15.92 28.86 13.78 5.92-1.85 5.88-6.5 6.91-7.58 1.23-1.3 2.25-1.84 3.12 1.1 0 .1.57 11.89-6 12.75-1.6.21-19.38 3.69-32.68-3.39-21-11.19-16.74-35.47-6.88-45.33 14-14.06 39.91-7.06 42.32-6.47zM289.8 280.14c3.28 0 3.66 3 .16 3.43-2.61.32-5-.42-5 5.46 0 2-.19 29.05.4 41.45.11 2.29 1.15 3.52 3.44 3.65 22 1.21 14.95-1.65 18.79-6.34 1.83-2.24 2.76.84 2.76 1.08.35 13.62-4 12.39-5.19 12.4l-38.16-.19c-1.93-.23-2.06-3-.42-3.38 2-.48 4.94.4 5.13-2.8 1-15.87.57-44.65.34-47.81-.27-3.77-2.8-3.27-5.68-3.71-2.47-.38-2-3.22.34-3.22 1.45-.02 17.97-.03 23.09-.02zm-31.63-57.79c.07 4.08 2.86 3.46 6 3.58 2.61.1 2.53 3.41-.07 3.43-6.48 0-13.7 0-21.61-.06-3.84 0-3.38-3.35 0-3.37 4.49 0 3.24 1.61 3.41-45.54 0-5.08-3.27-3.54-4.72-4.23-2.58-1.23-1.36-3.09.41-3.15 1.29 0 20.19-.41 21.17.21s1.87 1.65-.42 2.86c-1 .52-3.86-.28-4.15 2.47 0 .21-.82 1.63-.07 43.8zm-36.91 274.27a2.93 2.93 0 0 0 3.26 0c17-9.79 182-103.57 197.42-112.51-.14-.43 11.26-.18-181.52-.27-1.22 0-1.57.37-1.53 1.56 0 .1 1.25 44.51 1.22 50.38a28.33 28.33 0 0 1-1.36 7.71c-.55 1.83.38-.5-13.5 32.23-.73 1.72-1 2.21-2-.08-4.19-10.34-8.28-20.72-12.57-31a23.6 23.6 0 0 1-2-10.79c.16-2.46.8-16.12 1.51-48 0-1.95 0-2-2-2h-183c2.58 1.63 178.32 102.57 196 112.76zm-90.9-188.75c0 2.4.36 2.79 2.76 3 11.54 1.17 21 3.74 25.64-7.32 6-14.46 2.66-34.41-12.48-38.84-2-.59-16-2.76-15.94 1.51.05 8.04.01 11.61.02 41.65zm105.75-15.05c0 2.13 1.07 38.68 1.09 39.13.34 9.94-25.58 5.77-25.23-2.59.08-2 1.37-37.42 1.1-39.43-14.1 7.44-14.42 40.21 6.44 48.8a17.9 17.9 0 0 0 22.39-7.07c4.91-7.76 6.84-29.47-5.43-39a2.53 2.53 0 0 1-.36.12zm-12.28-198c-9.83 0-9.73 14.75-.07 14.87s10.1-14.88.07-14.91zm-80.15 103.83c0 1.8.41 2.4 2.17 2.58 13.62 1.39 12.51-11 12.16-13.36-1.69-11.22-14.38-10.2-14.35-7.81.05 4.5-.03 13.68.02 18.59zm212.32 6.4l-6.1-15.84c-2.16 5.48-4.16 10.57-6.23 15.84z\"],\n    \"css3\": [512, 512, [], \"f13c\", \"M480 32l-64 368-223.3 80L0 400l19.6-94.8h82l-8 40.6L210 390.2l134.1-44.4 18.8-97.1H29.5l16-82h333.7l10.5-52.7H56.3l16.3-82H480z\"],\n    \"css3-alt\": [384, 512, [], \"f38b\", \"M0 32l34.9 395.8L192 480l157.1-52.2L384 32H0zm313.1 80l-4.8 47.3L193 208.6l-.3.1h111.5l-12.8 146.6-98.2 28.7-98.8-29.2-6.4-73.9h48.9l3.2 38.3 52.6 13.3 54.7-15.4 3.7-61.6-166.3-.5v-.1l-.2.1-3.6-46.3L193.1 162l6.5-2.7H76.7L70.9 112h242.2z\"],\n    \"cuttlefish\": [440, 512, [], \"f38c\", \"M344 305.5c-17.5 31.6-57.4 54.5-96 54.5-56.6 0-104-47.4-104-104s47.4-104 104-104c38.6 0 78.5 22.9 96 54.5 13.7-50.9 41.7-93.3 87-117.8C385.7 39.1 320.5 8 248 8 111 8 0 119 0 256s111 248 248 248c72.5 0 137.7-31.1 183-80.7-45.3-24.5-73.3-66.9-87-117.8z\"],\n    \"d-and-d\": [576, 512, [], \"f38d\", \"M82.5 98.9c-.6-17.2 2-33.8 12.7-48.2.3 7.4 1.2 14.5 4.2 21.6 5.9-27.5 19.7-49.3 42.3-65.5-1.9 5.9-3.5 11.8-3 17.7 8.7-7.4 18.8-17.8 44.4-22.7 14.7-2.8 29.7-2 42.1 1 38.5 9.3 61 34.3 69.7 72.3 5.3 23.1.7 45-8.3 66.4-5.2 12.4-12 24.4-20.7 35.1-2-1.9-3.9-3.8-5.8-5.6-42.8-40.8-26.8-25.2-37.4-37.4-1.1-1.2-1-2.2-.1-3.6 8.3-13.5 11.8-28.2 10-44-1.1-9.8-4.3-18.9-11.3-26.2-14.5-15.3-39.2-15-53.5.6-11.4 12.5-14.1 27.4-10.9 43.6.2 1.3.4 2.7 0 3.9-3.4 13.7-4.6 27.6-2.5 41.6.1.5.1 1.1.1 1.6 0 .3-.1.5-.2 1.1-21.8-11-36-28.3-43.2-52.2-8.3 17.8-11.1 35.5-6.6 54.1-15.6-15.2-21.3-34.3-22-55.2zm469.6 123.2c-11.6-11.6-25-20.4-40.1-26.6-12.8-5.2-26-7.9-39.9-7.1-10 .6-19.6 3.1-29 6.4-2.5.9-5.1 1.6-7.7 2.2-4.9 1.2-7.3-3.1-4.7-6.8 3.2-4.6 3.4-4.2 15-12 .6-.4 1.2-.8 2.2-1.5h-2.5c-.6 0-1.2.2-1.9.3-19.3 3.3-30.7 15.5-48.9 29.6-10.4 8.1-13.8 3.8-12-.5 1.4-3.5 3.3-6.7 5.1-10 1-1.8 2.3-3.4 3.5-5.1-.2-.2-.5-.3-.7-.5-27 18.3-46.7 42.4-57.7 73.3.3.3.7.6 1 .9.3-.6.5-1.2.9-1.7 10.4-12.1 22.8-21.8 36.6-29.8 18.2-10.6 37.5-18.3 58.7-20.2 4.3-.4 8.7-.1 13.1-.1-1.8.7-3.5.9-5.3 1.1-18.5 2.4-35.5 9-51.5 18.5-30.2 17.9-54.5 42.2-75.1 70.4-.3.4-.4.9-.7 1.3 14.5 5.3 24 17.3 36.1 25.6.2-.1.3-.2.4-.4l1.2-2.7c12.2-26.9 27-52.3 46.7-74.5 16.7-18.8 38-25.3 62.5-20 5.9 1.3 11.4 4.4 17.2 6.8 2.3-1.4 5.1-3.2 8-4.7 8.4-4.3 17.4-7 26.7-9 14.7-3.1 29.5-4.9 44.5-1.3v-.5c-.5-.4-1.2-.8-1.7-1.4zM316.7 397.6c-39.4-33-22.8-19.5-42.7-35.6-.8.9 0-.2-1.9 3-11.2 19.1-25.5 35.3-44 47.6-10.3 6.8-21.5 11.8-34.1 11.8-21.6 0-38.2-9.5-49.4-27.8-12-19.5-13.3-40.7-8.2-62.6 7.8-33.8 30.1-55.2 38.6-64.3-18.7-6.2-33 1.7-46.4 13.9.8-13.9 4.3-26.2 11.8-37.3-24.3 10.6-45.9 25-64.8 43.9-.3-5.8 5.4-43.7 5.6-44.7.3-2.7-.6-5.3-3-7.4-24.2 24.7-44.5 51.8-56.1 84.6 7.4-5.9 14.9-11.4 23.6-16.2-8.3 22.3-19.6 52.8-7.8 101.1 4.6 19 11.9 36.8 24.1 52.3 2.9 3.7 6.3 6.9 9.5 10.3.2-.2.4-.3.6-.5-1.4-7-2.2-14.1-1.5-21.9 2.2 3.2 3.9 6 5.9 8.6 12.6 16 28.7 27.4 47.2 35.6 25 11.3 51.1 13.3 77.9 8.6 54.9-9.7 90.7-48.6 116-98.8 1-1.8.6-2.9-.9-4.2zm172-46.4c-9.5-3.1-22.2-4.2-28.7-2.9 9.9 4 14.1 6.6 18.8 12 12.6 14.4 10.4 34.7-5.4 45.6-11.7 8.1-24.9 10.5-38.9 9.1-1.2-.1-2.3-.4-3-.6 2.8-3.7 6-7 8.1-10.8 9.4-16.8 5.4-42.1-8.7-56.1-2.1-2.1-4.6-3.9-7-5.9-.3 1.3-.1 2.1.1 2.8 4.2 16.6-8.1 32.4-24.8 31.8-7.6-.3-13.9-3.8-19.6-8.5-19.5-16.1-39.1-32.1-58.5-48.3-5.9-4.9-12.5-8.1-20.1-8.7-4.6-.4-9.3-.6-13.9-.9-5.9-.4-8.8-2.8-10.4-8.4-.9-3.4-1.5-6.8-2.2-10.2-1.5-8.1-6.2-13-14.3-14.2-4.4-.7-8.9-1-13.3-1.5-13-1.4-19.8-7.4-22.6-20.3-5 11-1.6 22.4 7.3 29.9 4.5 3.8 9.3 7.3 13.8 11.2 4.6 3.8 7.4 8.7 7.9 14.8.4 4.7.8 9.5 1.8 14.1 2.2 10.6 8.9 18.4 17 25.1 16.5 13.7 33 27.3 49.5 41.1 17.9 15 13.9 32.8 13 56-.9 22.9 12.2 42.9 33.5 51.2 1 .4 2 .6 3.6 1.1-15.7-18.2-10.1-44.1.7-52.3.3 2.2.4 4.3.9 6.4 9.4 44.1 45.4 64.2 85 56.9 16-2.9 30.6-8.9 42.9-19.8 2-1.8 3.7-4.1 5.9-6.5-19.3 4.6-35.8.1-50.9-10.6.7-.3 1.3-.3 1.9-.3 21.3 1.8 40.6-3.4 57-17.4 19.5-16.6 26.6-42.9 17.4-66-8.3-20.1-23.6-32.3-43.8-38.9zM99.4 179.3c-5.3-9.2-13.2-15.6-22.1-21.3 13.7-.5 26.6.2 39.6 3.7-7-12.2-8.5-24.7-5-38.7 5.3 11.9 13.7 20.1 23.6 26.8 19.7 13.2 35.7 19.6 46.7 30.2 3.4 3.3 6.3 7.1 9.6 10.9-.8-2.1-1.4-4.1-2.2-6-5-10.6-13-18.6-22.6-25-1.8-1.2-2.8-2.5-3.4-4.5-3.3-12.5-3-25.1-.7-37.6 1-5.5 2.8-10.9 4.5-16.3.8-2.4 2.3-4.6 4-6.6.6 6.9 0 25.5 19.6 46 10.8 11.3 22.4 21.9 33.9 32.7 9 8.5 18.3 16.7 25.5 26.8 1.1 1.6 2.2 3.3 3.8 4.7-5-13-14.2-24.1-24.2-33.8-9.6-9.3-19.4-18.4-29.2-27.4-3.3-3-4.6-6.7-5.1-10.9-1.2-10.4 0-20.6 4.3-30.2.5-1 1.1-2 1.9-3.3.5 4.2.6 7.9 1.4 11.6 4.8 23.1 20.4 36.3 49.3 63.5 10 9.4 19.3 19.2 25.6 31.6 4.8 9.3 7.3 19 5.7 29.6-.1.6.5 1.7 1.1 2 6.2 2.6 10 6.9 9.7 14.3 7.7-2.6 12.5-8 16.4-14.5 4.2 20.2-9.1 50.3-27.2 58.7.4-4.5 5-23.4-16.5-27.7-6.8-1.3-12.8-1.3-22.9-2.1 4.7-9 10.4-20.6.5-22.4-24.9-4.6-52.8 1.9-57.8 4.6 8.2.4 16.3 1 23.5 3.3-2 6.5-4 12.7-5.8 18.9-1.9 6.5 2.1 14.6 9.3 9.6 1.2-.9 2.3-1.9 3.3-2.7-3.1 17.9-2.9 15.9-2.8 18.3.3 10.2 9.5 7.8 15.7 7.3-2.5 11.8-29.5 27.3-45.4 25.8 7-4.7 12.7-10.3 15.9-17.9-6.5.8-12.9 1.6-19.2 2.4l-.3-.9c4.7-3.4 8-7.8 10.2-13.1 8.7-21.1-3.6-38-25-39.9-9.1-.8-17.8.8-25.9 5.5 6.2-15.6 17.2-26.6 32.6-34.5-15.2-4.3-8.9-2.7-24.6-6.3 14.6-9.3 30.2-13.2 46.5-14.6-5.2-3.2-48.1-3.6-70.2 20.9 7.9 1.4 15.5 2.8 23.2 4.2-23.8 7-44 19.7-62.4 35.6 1.1-4.8 2.7-9.5 3.3-14.3.6-4.5.8-9.2.1-13.6-1.5-9.4-8.9-15.1-19.7-16.3-7.9-.9-15.6.1-23.3 1.3-.9.1-1.7.3-2.9 0 15.8-14.8 36-21.7 53.1-33.5 6-4.5 6.8-8.2 3-14.9zm128.4 26.8c3.3 16 12.6 25.5 23.8 24.3-4.6-11.3-12.1-19.5-23.8-24.3z\"],\n    \"d-and-d-beyond\": [640, 512, [], \"f6ca\", \"M313.8 241.5c13.8 0 21-10.1 24.8-17.9-1-1.1-5-4.2-7.4-6.6-2.4 4.3-8.2 10.7-13.9 10.7-10.2 0-15.4-14.7-3.2-26.6-.5-.2-4.3-1.8-8 2.4 0-3 1-5.1 2.1-6.6-3.5 1.3-9.8 5.6-11.4 7.9.2-5.8 1.6-7.5.6-9l-.2-.2s-8.5 5.6-9.3 14.7c0 0 1.1-1.6 2.1-1.9.6-.3 1.3 0 .6 1.9-.2.6-5.8 15.7 5.1 26-.6-1.6-1.9-7.6 2.4-1.9-.3.1 5.8 7.1 15.7 7.1zm52.4-21.1c0-4-4.9-4.4-5.6-4.5 2 3.9.9 7.5.2 9 2.5-.4 5.4-1.6 5.4-4.5zm10.3 5.2c0-6.4-6.2-11.4-13.5-10.7 8 1.3 5.6 13.8-5 11.4 3.7-2.6 3.2-9.9-1.3-12.5 1.4 4.2-3 8.2-7.4 4.6-2.4-1.9-8-6.6-10.6-8.6-2.4-2.1-5.5-1-6.6-1.8-1.3-1.1-.5-3.8-2.2-5-1.6-.8-3-.3-4.8-1-1.6-.6-2.7-1.9-2.6-3.5-2.5 4.4 3.4 6.3 4.5 8.5 1 1.9-.8 4.8 4 8.5 14.8 11.6 9.1 8 10.4 18.1.6 4.3 4.2 6.7 6.4 7.4-2.1-1.9-2.9-6.4 0-9.3 0 13.9 19.2 13.3 23.1 6.4-2.4 1.1-7-.2-9-1.9 7.7 1 14.2-4.1 14.6-10.6zm-39.4-18.4c2 .8 1.6.7 6.4 4.5 10.2-24.5 21.7-15.7 22-15.5 2.2-1.9 9.8-3.8 13.8-2.7-2.4-2.7-7.5-6.2-13.3-6.2-4.7 0-7.4 2.2-8 1.3-.8-1.4 3.2-3.4 3.2-3.4-5.4.2-9.6 6.7-11.2 5.9-1.1-.5 1.4-3.7 1.4-3.7-5.1 2.9-9.3 9.1-10.2 13 4.6-5.8 13.8-9.8 19.7-9-10.5.5-19.5 9.7-23.8 15.8zm242.5 51.9c-20.7 0-40 1.3-50.3 2.1l7.4 8.2v77.2l-7.4 8.2c10.4.8 30.9 2.1 51.6 2.1 42.1 0 59.1-20.7 59.1-48.9 0-29.3-23.2-48.9-60.4-48.9zm-15.1 75.6v-53.3c30.1-3.3 46.8 3.8 46.8 26.3 0 25.6-21.4 30.2-46.8 27zM301.6 181c-1-3.4-.2-6.9 1.1-9.4 1 3 2.6 6.4 7.5 9-.5-2.4-.2-5.6.5-8-1.4-5.4 2.1-9.9 6.4-9.9 6.9 0 8.5 8.8 4.7 14.4 2.1 3.2 5.5 5.6 7.7 7.8 3.2-3.7 5.5-9.5 5.5-13.8 0-8.2-5.5-15.9-16.7-16.5-20-.9-20.2 16.6-20 18.9.5 5.2 3.4 7.8 3.3 7.5zm-.4 6c-.5 1.8-7 3.7-10.2 6.9 4.8-1 7-.2 7.8 1.8.5 1.4-.2 3.4-.5 5.6 1.6-1.8 7-5.5 11-6.2-1-.3-3.4-.8-4.3-.8 2.9-3.4 9.3-4.5 12.8-3.7-2.2-.2-6.7 1.1-8.5 2.6 1.6.3 3 .6 4.3 1.1-2.1.8-4.8 3.4-5.8 6.1 7-5 13.1 5.2 7 8.2.8.2 2.7 0 3.5-.5-.3 1.1-1.9 3-3 3.4 2.9 0 7-1.9 8.2-4.6 0 0-1.8.6-2.6-.2s.3-4.3.3-4.3c-2.3 2.9-3.4-1.3-1.3-4.2-1-.3-3.5-.6-4.6-.5 3.2-1.1 10.4-1.8 11.2-.3.6 1.1-1 3.4-1 3.4 4-.5 8.3 1.1 6.7 5.1 2.9-1.4 5.5-5.9 4.8-10.4-.3 1-1.6 2.4-2.9 2.7.2-1.4-1-2.2-1.9-2.6 1.7-9.6-14.6-14.2-14.1-23.9-1 1.3-1.8 5-.8 7.1 2.7 3.2 8.7 6.7 10.1 12.2-2.6-6.4-15.1-11.4-14.6-20.2-1.6 1.6-2.6 7.8-1.3 11 2.4 1.4 4.5 3.8 4.8 6.1-2.2-5.1-11.4-6.1-13.9-12.2-.6 2.2-.3 5 1 6.7 0 0-2.2-.8-7-.6 1.7.6 5.1 3.5 4.8 5.2zm25.9 7.4c-2.7 0-3.5-2.1-4.2-4.3 3.3 1.3 4.2 4.3 4.2 4.3zm38.9 3.7l-1-.6c-1.1-1-2.9-1.4-4.7-1.4-2.9 0-5.8 1.3-7.5 3.4-.8.8-1.4 1.8-2.1 2.6v15.7c3.5 2.6 7.1-2.9 3-7.2 1.5.3 4.6 2.7 5.1 3.2 0 0 2.6-.5 5-.5 2.1 0 3.9.3 5.6 1.1V196c-1.1.5-2.2 1-2.7 1.4zM79.9 305.9c17.2-4.6 16.2-18 16.2-19.9 0-20.6-24.1-25-37-25H3l8.3 8.6v29.5H0l11.4 14.6V346L3 354.6c61.7 0 73.8 1.5 86.4-5.9 6.7-4 9.9-9.8 9.9-17.6 0-5.1 2.6-18.8-19.4-25.2zm-41.3-27.5c20 0 29.6-.8 29.6 9.1v3c0 12.1-19 8.8-29.6 8.8zm0 59.2V315c12.2 0 32.7-2.3 32.7 8.8v4.5h.2c0 11.2-12.5 9.3-32.9 9.3zm101.2-19.3l23.1.2v-.2l14.1-21.2h-37.2v-14.9h52.4l-14.1-21v-.2l-73.5.2 7.4 8.2v77.1l-7.4 8.2h81.2l14.1-21.2-60.1.2zm214.7-60.1c-73.9 0-77.5 99.3-.3 99.3 77.9 0 74.1-99.3.3-99.3zm-.3 77.5c-37.4 0-36.9-55.3.2-55.3 36.8.1 38.8 55.3-.2 55.3zm-91.3-8.3l44.1-66.2h-41.7l6.1 7.2-20.5 37.2h-.3l-21-37.2 6.4-7.2h-44.9l44.1 65.8.2 19.4-7.7 8.2h42.6l-7.2-8.2zm-28.4-151.3c1.6 1.3 2.9 2.4 2.9 6.6v38.8c0 4.2-.8 5.3-2.7 6.4-.1.1-7.5 4.5-7.9 4.6h35.1c10 0 17.4-1.5 26-8.6-.6-5 .2-9.5.8-12 0-.2-1.8 1.4-2.7 3.5 0-5.7 1.6-15.4 9.6-20.5-.1 0-3.7-.8-9 1.1 2-3.1 10-7.9 10.4-7.9-8.2-26-38-22.9-32.2-22.9-30.9 0-32.6.3-39.9-4 .1.8.5 8.2 9.6 14.9zm21.5 5.5c4.6 0 23.1-3.3 23.1 17.3 0 20.7-18.4 17.3-23.1 17.3zm228.9 79.6l7 8.3V312h-.3c-5.4-14.4-42.3-41.5-45.2-50.9h-31.6l7.4 8.5v76.9l-7.2 8.3h39l-7.4-8.2v-47.4h.3c3.7 10.6 44.5 42.9 48.5 55.6h21.3v-85.2l7.4-8.3zm-106.7-96.1c-32.2 0-32.8.2-39.9-4 .1.7.5 8.3 9.6 14.9 3.1 2 2.9 4.3 2.9 9.5 1.8-1.1 3.8-2.2 6.1-3-1.1 1.1-2.7 2.7-3.5 4.5 1-1.1 7.5-5.1 14.6-3.5-1.6.3-4 1.1-6.1 2.9.1 0 2.1-1.1 7.5-.3v-4.3c4.7 0 23.1-3.4 23.1 17.3 0 20.5-18.5 17.3-19.7 17.3 5.7 4.4 5.8 12 2.2 16.3h.3c33.4 0 36.7-27.3 36.7-34 0-3.8-1.1-32-33.8-33.6z\"],\n    \"dashcube\": [448, 512, [], \"f210\", \"M326.6 104H110.4c-51.1 0-91.2 43.3-91.2 93.5V427c0 50.5 40.1 85 91.2 85h227.2c51.1 0 91.2-34.5 91.2-85V0L326.6 104zM153.9 416.5c-17.7 0-32.4-15.1-32.4-32.8V240.8c0-17.7 14.7-32.5 32.4-32.5h140.7c17.7 0 32 14.8 32 32.5v123.5l51.1 52.3H153.9z\"],\n    \"delicious\": [448, 512, [], \"f1a5\", \"M446.5 68c-.4-1.5-.9-3-1.4-4.5-.9-2.5-2-4.8-3.3-7.1-1.4-2.4-3-4.8-4.7-6.9-2.1-2.5-4.4-4.8-6.9-6.8-1.1-.9-2.2-1.7-3.3-2.5-1.3-.9-2.6-1.7-4-2.4-1.8-1-3.6-1.8-5.5-2.5-1.7-.7-3.5-1.3-5.4-1.7-3.8-1-7.9-1.5-12-1.5H48C21.5 32 0 53.5 0 80v352c0 4.1.5 8.2 1.5 12 2 7.7 5.8 14.6 11 20.3 1 1.1 2.1 2.2 3.3 3.3 5.7 5.2 12.6 9 20.3 11 3.8 1 7.9 1.5 12 1.5h352c26.5 0 48-21.5 48-48V80c-.1-4.1-.6-8.2-1.6-12zM416 432c0 8.8-7.2 16-16 16H224V256H32V80c0-8.8 7.2-16 16-16h176v192h192z\"],\n    \"deploydog\": [512, 512, [], \"f38e\", \"M382.2 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.6 0-33.2 16.4-33.2 32.6zM188.5 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.7 0-33.2 16.4-33.2 32.6zM448 96c17.5 0 32 14.4 32 32v256c0 17.5-14.4 32-32 32H64c-17.5 0-32-14.4-32-32V128c0-17.5 14.4-32 32-32h384m0-32H64C28.8 64 0 92.8 0 128v256c0 35.2 28.8 64 64 64h384c35.2 0 64-28.8 64-64V128c0-35.2-28.8-64-64-64z\"],\n    \"deskpro\": [480, 512, [], \"f38f\", \"M205.9 512l31.1-38.4c12.3-.2 25.6-1.4 36.5-6.6 38.9-18.6 38.4-61.9 38.3-63.8-.1-5-.8-4.4-28.9-37.4H362c-.2 50.1-7.3 68.5-10.2 75.7-9.4 23.7-43.9 62.8-95.2 69.4-8.7 1.1-32.8 1.2-50.7 1.1zm200.4-167.7c38.6 0 58.5-13.6 73.7-30.9l-175.5-.3-17.4 31.3 119.2-.1zm-43.6-223.9v168.3h-73.5l-32.7 55.5H250c-52.3 0-58.1-56.5-58.3-58.9-1.2-13.2-21.3-11.6-20.1 1.8 1.4 15.8 8.8 40 26.4 57.1h-91c-25.5 0-110.8-26.8-107-114V16.9C0 .9 9.7.3 15 .1h82c.2 0 .3.1.5.1 4.3-.4 50.1-2.1 50.1 43.7 0 13.3 20.2 13.4 20.2 0 0-18.2-5.5-32.8-15.8-43.7h84.2c108.7-.4 126.5 79.4 126.5 120.2zm-132.5 56l64 29.3c13.3-45.5-42.2-71.7-64-29.3z\"],\n    \"dev\": [448, 512, [], \"f6cc\", \"M120.12 208.29c-3.88-2.9-7.77-4.35-11.65-4.35H91.03v104.47h17.45c3.88 0 7.77-1.45 11.65-4.35 3.88-2.9 5.82-7.25 5.82-13.06v-69.65c-.01-5.8-1.96-10.16-5.83-13.06zM404.1 32H43.9C19.7 32 .06 51.59 0 75.8v360.4C.06 460.41 19.7 480 43.9 480h360.2c24.21 0 43.84-19.59 43.9-43.8V75.8c-.06-24.21-19.7-43.8-43.9-43.8zM154.2 291.19c0 18.81-11.61 47.31-48.36 47.25h-46.4V172.98h47.38c35.44 0 47.36 28.46 47.37 47.28l.01 70.93zm100.68-88.66H201.6v38.42h32.57v29.57H201.6v38.41h53.29v29.57h-62.18c-11.16.29-20.44-8.53-20.72-19.69V193.7c-.27-11.15 8.56-20.41 19.71-20.69h63.19l-.01 29.52zm103.64 115.29c-13.2 30.75-36.85 24.63-47.44 0l-38.53-144.8h32.57l29.71 113.72 29.57-113.72h32.58l-38.46 144.8z\"],\n    \"deviantart\": [320, 512, [], \"f1bd\", \"M320 93.2l-98.2 179.1 7.4 9.5H320v127.7H159.1l-13.5 9.2-43.7 84c-.3 0-8.6 8.6-9.2 9.2H0v-93.2l93.2-179.4-7.4-9.2H0V102.5h156l13.5-9.2 43.7-84c.3 0 8.6-8.6 9.2-9.2H320v93.1z\"],\n    \"dhl\": [640, 512, [], \"f790\", \"M238 301.2h58.7L319 271h-58.7L238 301.2zM0 282.9v6.4h81.8l4.7-6.4H0zM172.9 271c-8.7 0-6-3.6-4.6-5.5 2.8-3.8 7.6-10.4 10.4-14.1 2.8-3.7 2.8-5.9-2.8-5.9h-51l-41.1 55.8h100.1c33.1 0 51.5-22.5 57.2-30.3h-68.2zm317.5-6.9l39.3-53.4h-62.2l-39.3 53.4h62.2zM95.3 271H0v6.4h90.6l4.7-6.4zm111-26.6c-2.8 3.8-7.5 10.4-10.3 14.2-1.4 2-4.1 5.5 4.6 5.5h45.6s7.3-10 13.5-18.4c8.4-11.4.7-35-29.2-35H112.6l-20.4 27.8h111.4c5.6 0 5.5 2.2 2.7 5.9zM0 301.2h73.1l4.7-6.4H0v6.4zm323 0h58.7L404 271h-58.7c-.1 0-22.3 30.2-22.3 30.2zm222 .1h95v-6.4h-90.3l-4.7 6.4zm22.3-30.3l-4.7 6.4H640V271h-72.7zm-13.5 18.3H640v-6.4h-81.5l-4.7 6.4zm-164.2-78.6l-22.5 30.6h-26.2l22.5-30.6h-58.7l-39.3 53.4H409l39.3-53.4h-58.7zm33.5 60.3s-4.3 5.9-6.4 8.7c-7.4 10-.9 21.6 23.2 21.6h94.3l22.3-30.3H423.1z\"],\n    \"diaspora\": [512, 512, [], \"f791\", \"M251.64 354.55c-1.4 0-88 119.9-88.7 119.9S76.34 414 76 413.25s86.6-125.7 86.6-127.4c0-2.2-129.6-44-137.6-47.1-1.3-.5 31.4-101.8 31.7-102.1.6-.7 144.4 47 145.5 47 .4 0 .9-.6 1-1.3.4-2 1-148.6 1.7-149.6.8-1.2 104.5-.7 105.1-.3 1.5 1 3.5 156.1 6.1 156.1 1.4 0 138.7-47 139.3-46.3.8.9 31.9 102.2 31.5 102.6-.9.9-140.2 47.1-140.6 48.8-.3 1.4 82.8 122.1 82.5 122.9s-85.5 63.5-86.3 63.5c-1-.2-89-125.5-90.9-125.5z\"],\n    \"digg\": [512, 512, [], \"f1a6\", \"M81.7 172.3H0v174.4h132.7V96h-51v76.3zm0 133.4H50.9v-92.3h30.8v92.3zm297.2-133.4v174.4h81.8v28.5h-81.8V416H512V172.3H378.9zm81.8 133.4h-30.8v-92.3h30.8v92.3zm-235.6 41h82.1v28.5h-82.1V416h133.3V172.3H225.1v174.4zm51.2-133.3h30.8v92.3h-30.8v-92.3zM153.3 96h51.3v51h-51.3V96zm0 76.3h51.3v174.4h-51.3V172.3z\"],\n    \"digital-ocean\": [512, 512, [], \"f391\", \"M87 481.8h73.7v-73.6H87zM25.4 346.6v61.6H87v-61.6zm466.2-169.7c-23-74.2-82.4-133.3-156.6-156.6C164.9-32.8 8 93.7 8 255.9h95.8c0-101.8 101-180.5 208.1-141.7 39.7 14.3 71.5 46.1 85.8 85.7 39.1 107-39.7 207.8-141.4 208v.3h-.3V504c162.6 0 288.8-156.8 235.6-327.1zm-235.3 231v-95.3h-95.6v95.6H256v-.3z\"],\n    \"discord\": [448, 512, [], \"f392\", \"M297.216 243.2c0 15.616-11.52 28.416-26.112 28.416-14.336 0-26.112-12.8-26.112-28.416s11.52-28.416 26.112-28.416c14.592 0 26.112 12.8 26.112 28.416zm-119.552-28.416c-14.592 0-26.112 12.8-26.112 28.416s11.776 28.416 26.112 28.416c14.592 0 26.112-12.8 26.112-28.416.256-15.616-11.52-28.416-26.112-28.416zM448 52.736V512c-64.494-56.994-43.868-38.128-118.784-107.776l13.568 47.36H52.48C23.552 451.584 0 428.032 0 398.848V52.736C0 23.552 23.552 0 52.48 0h343.04C424.448 0 448 23.552 448 52.736zm-72.96 242.688c0-82.432-36.864-149.248-36.864-149.248-36.864-27.648-71.936-26.88-71.936-26.88l-3.584 4.096c43.52 13.312 63.744 32.512 63.744 32.512-60.811-33.329-132.244-33.335-191.232-7.424-9.472 4.352-15.104 7.424-15.104 7.424s21.248-20.224 67.328-33.536l-2.56-3.072s-35.072-.768-71.936 26.88c0 0-36.864 66.816-36.864 149.248 0 0 21.504 37.12 78.08 38.912 0 0 9.472-11.52 17.152-21.248-32.512-9.728-44.8-30.208-44.8-30.208 3.766 2.636 9.976 6.053 10.496 6.4 43.21 24.198 104.588 32.126 159.744 8.96 8.96-3.328 18.944-8.192 29.44-15.104 0 0-12.8 20.992-46.336 30.464 7.68 9.728 16.896 20.736 16.896 20.736 56.576-1.792 78.336-38.912 78.336-38.912z\"],\n    \"discourse\": [448, 512, [], \"f393\", \"M225.9 32C103.3 32 0 130.5 0 252.1 0 256 .1 480 .1 480l225.8-.2c122.7 0 222.1-102.3 222.1-223.9C448 134.3 348.6 32 225.9 32zM224 384c-19.4 0-37.9-4.3-54.4-12.1L88.5 392l22.9-75c-9.8-18.1-15.4-38.9-15.4-61 0-70.7 57.3-128 128-128s128 57.3 128 128-57.3 128-128 128z\"],\n    \"dochub\": [416, 512, [], \"f394\", \"M397.9 160H256V19.6L397.9 160zM304 192v130c0 66.8-36.5 100.1-113.3 100.1H96V84.8h94.7c12 0 23.1.8 33.1 2.5v-84C212.9 1.1 201.4 0 189.2 0H0v512h189.2C329.7 512 400 447.4 400 318.1V192h-96z\"],\n    \"docker\": [640, 512, [], \"f395\", \"M349.9 236.3h-66.1v-59.4h66.1v59.4zm0-204.3h-66.1v60.7h66.1V32zm78.2 144.8H362v59.4h66.1v-59.4zm-156.3-72.1h-66.1v60.1h66.1v-60.1zm78.1 0h-66.1v60.1h66.1v-60.1zm276.8 100c-14.4-9.7-47.6-13.2-73.1-8.4-3.3-24-16.7-44.9-41.1-63.7l-14-9.3-9.3 14c-18.4 27.8-23.4 73.6-3.7 103.8-8.7 4.7-25.8 11.1-48.4 10.7H2.4c-8.7 50.8 5.8 116.8 44 162.1 37.1 43.9 92.7 66.2 165.4 66.2 157.4 0 273.9-72.5 328.4-204.2 21.4.4 67.6.1 91.3-45.2 1.5-2.5 6.6-13.2 8.5-17.1l-13.3-8.9zm-511.1-27.9h-66v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm-78.1-72.1h-66.1v60.1h66.1v-60.1z\"],\n    \"draft2digital\": [480, 512, [], \"f396\", \"M480 398.1l-144-82.2v64.7h-91.3c30.8-35 81.8-95.9 111.8-149.3 35.2-62.6 16.1-123.4-12.8-153.3-4.4-4.6-62.2-62.9-166-41.2-59.1 12.4-89.4 43.4-104.3 67.3-13.1 20.9-17 39.8-18.2 47.7-5.5 33 19.4 67.1 56.7 67.1 31.7 0 57.3-25.7 57.3-57.4 0-27.1-19.7-52.1-48-56.8 1.8-7.3 17.7-21.1 26.3-24.7 41.1-17.3 78 5.2 83.3 33.5 8.3 44.3-37.1 90.4-69.7 127.6C84.5 328.1 18.3 396.8 0 415.9l336-.1V480zM369.9 371l47.1 27.2-47.1 27.2zM134.2 161.4c0 12.4-10 22.4-22.4 22.4s-22.4-10-22.4-22.4 10-22.4 22.4-22.4 22.4 10.1 22.4 22.4zM82.5 380.5c25.6-27.4 97.7-104.7 150.8-169.9 35.1-43.1 40.3-82.4 28.4-112.7-7.4-18.8-17.5-30.2-24.3-35.7 45.3 2.1 68 23.4 82.2 38.3 0 0 42.4 48.2 5.8 113.3-37 65.9-110.9 147.5-128.5 166.7z\"],\n    \"dribbble\": [512, 512, [], \"f17d\", \"M256 8C119.252 8 8 119.252 8 256s111.252 248 248 248 248-111.252 248-248S392.748 8 256 8zm163.97 114.366c29.503 36.046 47.369 81.957 47.835 131.955-6.984-1.477-77.018-15.682-147.502-6.818-5.752-14.041-11.181-26.393-18.617-41.614 78.321-31.977 113.818-77.482 118.284-83.523zM396.421 97.87c-3.81 5.427-35.697 48.286-111.021 76.519-34.712-63.776-73.185-116.168-79.04-124.008 67.176-16.193 137.966 1.27 190.061 47.489zm-230.48-33.25c5.585 7.659 43.438 60.116 78.537 122.509-99.087 26.313-186.36 25.934-195.834 25.809C62.38 147.205 106.678 92.573 165.941 64.62zM44.17 256.323c0-2.166.043-4.322.108-6.473 9.268.19 111.92 1.513 217.706-30.146 6.064 11.868 11.857 23.915 17.174 35.949-76.599 21.575-146.194 83.527-180.531 142.306C64.794 360.405 44.17 310.73 44.17 256.323zm81.807 167.113c22.127-45.233 82.178-103.622 167.579-132.756 29.74 77.283 42.039 142.053 45.189 160.638-68.112 29.013-150.015 21.053-212.768-27.882zm248.38 8.489c-2.171-12.886-13.446-74.897-41.152-151.033 66.38-10.626 124.7 6.768 131.947 9.055-9.442 58.941-43.273 109.844-90.795 141.978z\"],\n    \"dribbble-square\": [448, 512, [], \"f397\", \"M90.2 228.2c8.9-42.4 37.4-77.7 75.7-95.7 3.6 4.9 28 38.8 50.7 79-64 17-120.3 16.8-126.4 16.7zM314.6 154c-33.6-29.8-79.3-41.1-122.6-30.6 3.8 5.1 28.6 38.9 51 80 48.6-18.3 69.1-45.9 71.6-49.4zM140.1 364c40.5 31.6 93.3 36.7 137.3 18-2-12-10-53.8-29.2-103.6-55.1 18.8-93.8 56.4-108.1 85.6zm98.8-108.2c-3.4-7.8-7.2-15.5-11.1-23.2C159.6 253 93.4 252.2 87.4 252c0 1.4-.1 2.8-.1 4.2 0 35.1 13.3 67.1 35.1 91.4 22.2-37.9 67.1-77.9 116.5-91.8zm34.9 16.3c17.9 49.1 25.1 89.1 26.5 97.4 30.7-20.7 52.5-53.6 58.6-91.6-4.6-1.5-42.3-12.7-85.1-5.8zm-20.3-48.4c4.8 9.8 8.3 17.8 12 26.8 45.5-5.7 90.7 3.4 95.2 4.4-.3-32.3-11.8-61.9-30.9-85.1-2.9 3.9-25.8 33.2-76.3 53.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 176c0-88.2-71.8-160-160-160S64 167.8 64 256s71.8 160 160 160 160-71.8 160-160z\"],\n    \"dropbox\": [528, 512, [], \"f16b\", \"M264.4 116.3l-132 84.3 132 84.3-132 84.3L0 284.1l132.3-84.3L0 116.3 132.3 32l132.1 84.3zM131.6 395.7l132-84.3 132 84.3-132 84.3-132-84.3zm132.8-111.6l132-84.3-132-83.6L395.7 32 528 116.3l-132.3 84.3L528 284.8l-132.3 84.3-131.3-85z\"],\n    \"drupal\": [448, 512, [], \"f1a9\", \"M319.5 114.7c-22.2-14-43.5-19.5-64.7-33.5-13-8.8-31.3-30-46.5-48.3-2.7 29.3-11.5 41.2-22 49.5-21.3 17-34.8 22.2-53.5 32.3C117 123 32 181.5 32 290.5 32 399.7 123.8 480 225.8 480 327.5 480 416 406 416 294c0-112.3-83-171-96.5-179.3zm2.5 325.6c-20.1 20.1-90.1 28.7-116.7 4.2-4.8-4.8.3-12 6.5-12 0 0 17 13.3 51.5 13.3 27 0 46-7.7 54.5-14 6.1-4.6 8.4 4.3 4.2 8.5zm-54.5-52.6c8.7-3.6 29-3.8 36.8 1.3 4.1 2.8 16.1 18.8 6.2 23.7-8.4 4.2-1.2-15.7-26.5-15.7-14.7 0-19.5 5.2-26.7 11-7 6-9.8 8-12.2 4.7-6-8.2 15.9-22.3 22.4-25zM360 405c-15.2-1-45.5-48.8-65-49.5-30.9-.9-104.1 80.7-161.3 42-38.8-26.6-14.6-104.8 51.8-105.2 49.5-.5 83.8 49 108.5 48.5 21.3-.3 61.8-41.8 81.8-41.8 48.7 0 23.3 109.3-15.8 106z\"],\n    \"dyalog\": [416, 512, [], \"f399\", \"M0 32v119.2h64V96h107.2C284.6 96 352 176.2 352 255.9 352 332 293.4 416 171.2 416H0v64h171.2C331.9 480 416 367.3 416 255.9c0-58.7-22.1-113.4-62.3-154.3C308.9 56 245.7 32 171.2 32H0z\"],\n    \"earlybirds\": [480, 512, [], \"f39a\", \"M313.2 47.5c1.2-13 21.3-14 36.6-8.7.9.3 26.2 9.7 19 15.2-27.9-7.4-56.4 18.2-55.6-6.5zm-201 6.9c30.7-8.1 62 20 61.1-7.1-1.3-14.2-23.4-15.3-40.2-9.6-1 .3-28.7 10.5-20.9 16.7zM319.4 160c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-159.7 0c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm318.5 163.2c-9.9 24-40.7 11-63.9-1.2-13.5 69.1-58.1 111.4-126.3 124.2.3.9-2-.1 24 1 33.6 1.4 63.8-3.1 97.4-8-19.8-13.8-11.4-37.1-9.8-38.1 1.4-.9 14.7 1.7 21.6 11.5 8.6-12.5 28.4-14.8 30.2-13.6 1.6 1.1 6.6 20.9-6.9 34.6 4.7-.9 8.2-1.6 9.8-2.1 2.6-.8 17.7 11.3 3.1 13.3-14.3 2.3-22.6 5.1-47.1 10.8-45.9 10.7-85.9 11.8-117.7 12.8l1 11.6c3.8 18.1-23.4 24.3-27.6 6.2.8 17.9-27.1 21.8-28.4-1l-.5 5.3c-.7 18.4-28.4 17.9-28.3-.6-7.5 13.5-28.1 6.8-26.4-8.5l1.2-12.4c-36.7.9-59.7 3.1-61.8 3.1-20.9 0-20.9-31.6 0-31.6 2.4 0 27.7 1.3 63.2 2.8-61.1-15.5-103.7-55-114.9-118.2-25 12.8-57.5 26.8-68.2.8-10.5-25.4 21.5-42.6 66.8-73.4.7-6.6 1.6-13.3 2.7-19.8-14.4-19.6-11.6-36.3-16.1-60.4-16.8 2.4-23.2-9.1-23.6-23.1.3-7.3 2.1-14.9 2.4-15.4 1.1-1.8 10.1-2 12.7-2.6 6-31.7 50.6-33.2 90.9-34.5 19.7-21.8 45.2-41.5 80.9-48.3C203.3 29 215.2 8.5 216.2 8c1.7-.8 21.2 4.3 26.3 23.2 5.2-8.8 18.3-11.4 19.6-10.7 1.1.6 6.4 15-4.9 25.9 40.3 3.5 72.2 24.7 96 50.7 36.1 1.5 71.8 5.9 77.1 34 2.7.6 11.6.8 12.7 2.6.3.5 2.1 8.1 2.4 15.4-.5 13.9-6.8 25.4-23.6 23.1-3.2 17.3-2.7 32.9-8.7 47.7 2.4 11.7 4 23.8 4.8 36.4 37 25.4 70.3 42.5 60.3 66.9zM207.4 159.9c.9-44-37.9-42.2-78.6-40.3-21.7 1-38.9 1.9-45.5 13.9-11.4 20.9 5.9 92.9 23.2 101.2 9.8 4.7 73.4 7.9 86.3-7.1 8.2-9.4 15-49.4 14.6-67.7zm52 58.3c-4.3-12.4-6-30.1-15.3-32.7-2-.5-9-.5-11 0-10 2.8-10.8 22.1-17 37.2 15.4 0 19.3 9.7 23.7 9.7 4.3 0 6.3-11.3 19.6-14.2zm135.7-84.7c-6.6-12.1-24.8-12.9-46.5-13.9-40.2-1.9-78.2-3.8-77.3 40.3-.5 18.3 5 58.3 13.2 67.8 13 14.9 76.6 11.8 86.3 7.1 15.8-7.6 36.5-78.9 24.3-101.3z\"],\n    \"ebay\": [640, 512, [], \"f4f4\", \"M606 189.5l-54.8 109.9-54.9-109.9h-37.5l10.9 20.6c-11.5-19-35.9-26-63.3-26-31.8 0-67.9 8.7-71.5 43.1h33.7c1.4-13.8 15.7-21.8 35-21.8 26 0 41 9.6 41 33v3.4c-12.7 0-28 .1-41.7.4-42.4.9-69.6 10-76.7 34.4 1-5.2 1.5-10.6 1.5-16.2 0-52.1-39.7-76.2-75.4-76.2-21.3 0-43 5.5-58.7 24.2v-80.6h-32.1v169.5c0 10.3-.6 22.9-1.1 33.1h31.5c.7-6.3 1.1-12.9 1.1-19.5 13.6 16.6 35.4 24.9 58.7 24.9 36.9 0 64.9-21.9 73.3-54.2-.5 2.8-.7 5.8-.7 9 0 24.1 21.1 45 60.6 45 26.6 0 45.8-5.7 61.9-25.5 0 6.6.3 13.3 1.1 20.2h29.8c-.7-8.2-1-17.5-1-26.8v-65.6c0-9.3-1.7-17.2-4.8-23.8l61.5 116.1-28.5 54.1h35.9L640 189.5zM243.7 313.8c-29.6 0-50.2-21.5-50.2-53.8 0-32.4 20.6-53.8 50.2-53.8 29.8 0 50.2 21.4 50.2 53.8 0 32.3-20.4 53.8-50.2 53.8zm200.9-47.3c0 30-17.9 48.4-51.6 48.4-25.1 0-35-13.4-35-25.8 0-19.1 18.1-24.4 47.2-25.3 13.1-.5 27.6-.6 39.4-.6zm-411.9 1.6h128.8v-8.5c0-51.7-33.1-75.4-78.4-75.4-56.8 0-83 30.8-83 77.6 0 42.5 25.3 74 82.5 74 31.4 0 68-11.7 74.4-46.1h-33.1c-12 35.8-87.7 36.7-91.2-21.6zm95-21.4H33.3c6.9-56.6 92.1-54.7 94.4 0z\"],\n    \"edge\": [512, 512, [], \"f282\", \"M25.714 228.163c.111-.162.23-.323.342-.485-.021.162-.045.323-.065.485h-.277zm460.572 15.508c0-44.032-7.754-84.465-28.801-122.405C416.498 47.879 343.912 8.001 258.893 8.001 118.962 7.724 40.617 113.214 26.056 227.679c42.429-61.312 117.073-121.376 220.375-124.966 0 0 109.666 0 99.419 104.957H169.997c6.369-37.386 18.554-58.986 34.339-78.926-75.048 34.893-121.85 96.096-120.742 188.315.83 71.448 50.124 144.836 120.743 171.976 83.357 31.847 192.776 7.2 240.132-21.324V363.307c-80.864 56.494-270.871 60.925-272.255-67.572h314.073v-52.064z\"],\n    \"elementor\": [448, 512, [], \"f430\", \"M425.6 32H22.4C10 32 0 42 0 54.4v403.2C0 470 10 480 22.4 480h403.2c12.4 0 22.4-10 22.4-22.4V54.4C448 42 438 32 425.6 32M164.3 355.5h-39.8v-199h39.8v199zm159.3 0H204.1v-39.8h119.5v39.8zm0-79.6H204.1v-39.8h119.5v39.8zm0-79.7H204.1v-39.8h119.5v39.8z\"],\n    \"ello\": [496, 512, [], \"f5f1\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm143.84 285.2C375.31 358.51 315.79 404.8 248 404.8s-127.31-46.29-143.84-111.6c-1.65-7.44 2.48-15.71 9.92-17.36 7.44-1.65 15.71 2.48 17.36 9.92 14.05 52.91 62 90.11 116.56 90.11s102.51-37.2 116.56-90.11c1.65-7.44 9.92-12.4 17.36-9.92 7.44 1.65 12.4 9.92 9.92 17.36z\"],\n    \"ember\": [640, 512, [], \"f423\", \"M639.9 254.6c-1.1-10.7-10.7-6.8-10.7-6.8s-15.6 12.1-29.3 10.7c-13.7-1.3-9.4-32-9.4-32s3-28.1-5.1-30.4c-8.1-2.4-18 7.3-18 7.3s-12.4 13.7-18.3 31.2l-1.6.5s1.9-30.6-.3-37.6c-1.6-3.5-16.4-3.2-18.8 3s-14.2 49.2-15 67.2c0 0-23.1 19.6-43.3 22.8s-25-9.4-25-9.4 54.8-15.3 52.9-59.1-44.2-27.6-49-24c-4.6 3.5-29.4 18.4-36.6 59.7-.2 1.4-.7 7.5-.7 7.5s-21.2 14.2-33 18c0 0 33-55.6-7.3-80.9-11.4-6.8-21.3-.5-27.2 5.3 13.6-17.3 46.4-64.2 36.9-105.2-5.8-24.4-18-27.1-29.2-23.1-17 6.7-23.5 16.7-23.5 16.7s-22 32-27.1 79.5-12.6 105.1-12.6 105.1-10.5 10.2-20.2 10.7-5.4-28.7-5.4-28.7 7.5-44.6 7-52.1-1.1-11.6-9.9-14.2c-8.9-2.7-18.5 8.6-18.5 8.6s-25.5 38.7-27.7 44.6l-1.3 2.4-1.3-1.6s18-52.7.8-53.5-28.5 18.8-28.5 18.8-19.6 32.8-20.4 36.5l-1.3-1.6s8.1-38.2 6.4-47.6c-1.6-9.4-10.5-7.5-10.5-7.5s-11.3-1.3-14.2 5.9-13.7 55.3-15 70.7c0 0-28.2 20.2-46.8 20.4-18.5.3-16.7-11.8-16.7-11.8s68-23.3 49.4-69.2c-8.3-11.8-18-15.5-31.7-15.3-13.7.3-30.3 8.6-41.3 33.3-5.3 11.8-6.8 23-7.8 31.5 0 0-12.3 2.4-18.8-2.9s-10 0-10 0-11.2 14-.1 18.3 28.1 6.1 28.1 6.1c1.6 7.5 6.2 19.5 19.6 29.7 20.2 15.3 58.8-1.3 58.8-1.3l15.9-8.8s.5 14.6 12.1 16.7 16.4 1 36.5-47.9c11.8-25 12.6-23.6 12.6-23.6l1.3-.3s-9.1 46.8-5.6 59.7C187.7 319.4 203 318 203 318s8.3 2.4 15-21.2 19.6-49.9 19.6-49.9h1.6s-5.6 48.1 3 63.7 30.9 5.3 30.9 5.3 15.6-7.8 18-10.2c0 0 18.5 15.8 44.6 12.9 58.3-11.5 79.1-25.9 79.1-25.9s10 24.4 41.1 26.7c35.5 2.7 54.8-18.6 54.8-18.6s-.3 13.5 12.1 18.6 20.7-22.8 20.7-22.8l20.7-57.2h1.9s1.1 37.3 21.5 43.2 47-13.7 47-13.7 6.4-3.5 5.3-14.3zm-578 5.3c.8-32 21.8-45.9 29-39 7.3 7 4.6 22-9.1 31.4-13.7 9.5-19.9 7.6-19.9 7.6zm272.8-123.8s19.1-49.7 23.6-25.5-40 96.2-40 96.2c.5-16.2 16.4-70.7 16.4-70.7zm22.8 138.4c-12.6 33-43.3 19.6-43.3 19.6s-3.5-11.8 6.4-44.9 33.3-20.2 33.3-20.2 16.2 12.4 3.6 45.5zm84.6-14.6s-3-10.5 8.1-30.6c11-20.2 19.6-9.1 19.6-9.1s9.4 10.2-1.3 25.5-26.4 14.2-26.4 14.2z\"],\n    \"empire\": [496, 512, [], \"f1d1\", \"M287.6 54.2c-10.8-2.2-22.1-3.3-33.5-3.6V32.4c78.1 2.2 146.1 44 184.6 106.6l-15.8 9.1c-6.1-9.7-12.7-18.8-20.2-27.1l-18 15.5c-26-29.6-61.4-50.7-101.9-58.4l4.8-23.9zM53.4 322.4l23-7.7c-6.4-18.3-10-38.2-10-58.7s3.3-40.4 9.7-58.7l-22.7-7.7c3.6-10.8 8.3-21.3 13.6-31l-15.8-9.1C34 181 24.1 217.5 24.1 256s10 75 27.1 106.6l15.8-9.1c-5.3-10-9.7-20.3-13.6-31.1zM213.1 434c-40.4-8-75.8-29.1-101.9-58.7l-18 15.8c-7.5-8.6-14.4-17.7-20.2-27.4l-16 9.4c38.5 62.3 106.8 104.3 184.9 106.6v-18.3c-11.3-.3-22.7-1.7-33.5-3.6l4.7-23.8zM93.3 120.9l18 15.5c26-29.6 61.4-50.7 101.9-58.4l-4.7-23.8c10.8-2.2 22.1-3.3 33.5-3.6V32.4C163.9 34.6 95.9 76.4 57.4 139l15.8 9.1c6-9.7 12.6-18.9 20.1-27.2zm309.4 270.2l-18-15.8c-26 29.6-61.4 50.7-101.9 58.7l4.7 23.8c-10.8 1.9-22.1 3.3-33.5 3.6v18.3c78.1-2.2 146.4-44.3 184.9-106.6l-16.1-9.4c-5.7 9.7-12.6 18.8-20.1 27.4zM496 256c0 137-111 248-248 248S0 393 0 256 111 8 248 8s248 111 248 248zm-12.2 0c0-130.1-105.7-235.8-235.8-235.8S12.2 125.9 12.2 256 117.9 491.8 248 491.8 483.8 386.1 483.8 256zm-39-106.6l-15.8 9.1c5.3 9.7 10 20.2 13.6 31l-22.7 7.7c6.4 18.3 9.7 38.2 9.7 58.7s-3.6 40.4-10 58.7l23 7.7c-3.9 10.8-8.3 21-13.6 31l15.8 9.1C462 331 471.9 294.5 471.9 256s-9.9-75-27.1-106.6zm-183 177.7c16.3-3.3 30.4-11.6 40.7-23.5l51.2 44.8c11.9-13.6 21.3-29.3 27.1-46.8l-64.2-22.1c2.5-7.5 3.9-15.2 3.9-23.5s-1.4-16.1-3.9-23.5l64.5-22.1c-6.1-17.4-15.5-33.2-27.4-46.8l-51.2 44.8c-10.2-11.9-24.4-20.5-40.7-23.8l13.3-66.4c-8.6-1.9-17.7-2.8-27.1-2.8-9.4 0-18.5.8-27.1 2.8l13.3 66.4c-16.3 3.3-30.4 11.9-40.7 23.8l-51.2-44.8c-11.9 13.6-21.3 29.3-27.4 46.8l64.5 22.1c-2.5 7.5-3.9 15.2-3.9 23.5s1.4 16.1 3.9 23.5l-64.2 22.1c5.8 17.4 15.2 33.2 27.1 46.8l51.2-44.8c10.2 11.9 24.4 20.2 40.7 23.5l-13.3 66.7c8.6 1.7 17.7 2.8 27.1 2.8 9.4 0 18.5-1.1 27.1-2.8l-13.3-66.7z\"],\n    \"envira\": [448, 512, [], \"f299\", \"M0 32c477.6 0 366.6 317.3 367.1 366.3L448 480h-26l-70.4-71.2c-39 4.2-124.4 34.5-214.4-37C47 300.3 52 214.7 0 32zm79.7 46c-49.7-23.5-5.2 9.2-5.2 9.2 45.2 31.2 66 73.7 90.2 119.9 31.5 60.2 79 139.7 144.2 167.7 65 28 34.2 12.5 6-8.5-28.2-21.2-68.2-87-91-130.2-31.7-60-61-118.6-144.2-158.1z\"],\n    \"erlang\": [640, 512, [], \"f39d\", \"M87.2 53.5H0v405h100.4c-49.7-52.6-78.8-125.3-78.7-212.1-.1-76.7 24-142.7 65.5-192.9zm238.2 9.7c-45.9.1-85.1 33.5-89.2 83.2h169.9c-1.1-49.7-34.5-83.1-80.7-83.2zm230.7-9.6h.3l-.1-.1zm.3 0c31.4 42.7 48.7 97.5 46.2 162.7.5 6 .5 11.7 0 24.1H230.2c-.2 109.7 38.9 194.9 138.6 195.3 68.5-.3 118-51 151.9-106.1l96.4 48.2c-17.4 30.9-36.5 57.8-57.9 80.8H640v-405z\"],\n    \"ethereum\": [320, 512, [], \"f42e\", \"M311.9 260.8L160 353.6 8 260.8 160 0l151.9 260.8zM160 383.4L8 290.6 160 512l152-221.4-152 92.8z\"],\n    \"etsy\": [384, 512, [], \"f2d7\", \"M384 348c-1.75 10.75-13.75 110-15.5 132-117.879-4.299-219.895-4.743-368.5 0v-25.5c45.457-8.948 60.627-8.019 61-35.25 1.793-72.322 3.524-244.143 0-322-1.029-28.46-12.13-26.765-61-36v-25.5c73.886 2.358 255.933 8.551 362.999-3.75-3.5 38.25-7.75 126.5-7.75 126.5H332C320.947 115.665 313.241 68 277.25 68h-137c-10.25 0-10.75 3.5-10.75 9.75V241.5c58 .5 88.5-2.5 88.5-2.5 29.77-.951 27.56-8.502 40.75-65.251h25.75c-4.407 101.351-3.91 61.829-1.75 160.25H257c-9.155-40.086-9.065-61.045-39.501-61.5 0 0-21.5-2-88-2v139c0 26 14.25 38.25 44.25 38.25H263c63.636 0 66.564-24.996 98.751-99.75H384z\"],\n    \"evernote\": [384, 512, [], \"f839\", \"M120.82 132.21c1.6 22.31-17.55 21.59-21.61 21.59-68.93 0-73.64-1-83.58 3.34-.56.22-.74 0-.37-.37L123.79 46.45c.38-.37.6-.22.38.37-4.35 9.99-3.35 15.09-3.35 85.39zm79 308c-14.68-37.08 13-76.93 52.52-76.62 17.49 0 22.6 23.21 7.95 31.42-6.19 3.3-24.95 1.74-25.14 19.2-.05 17.09 19.67 25 31.2 24.89A45.64 45.64 0 0 0 312 393.45v-.08c0-11.63-7.79-47.22-47.54-55.34-7.72-1.54-65-6.35-68.35-50.52-3.74 16.93-17.4 63.49-43.11 69.09-8.74 1.94-69.68 7.64-112.92-36.77 0 0-18.57-15.23-28.23-57.95-3.38-15.75-9.28-39.7-11.14-62 0-18 11.14-30.45 25.07-32.2 81 0 90 2.32 101-7.8 9.82-9.24 7.8-15.5 7.8-102.78 1-8.3 7.79-30.81 53.41-24.14 6 .86 31.91 4.18 37.48 30.64l64.26 11.15c20.43 3.71 70.94 7 80.6 57.94 22.66 121.09 8.91 238.46 7.8 238.46C362.15 485.53 267.06 480 267.06 480c-18.95-.23-54.25-9.4-67.27-39.83zm80.94-204.84c-1 1.92-2.2 6 .85 7 14.09 4.93 39.75 6.84 45.88 5.53 3.11-.25 3.05-4.43 2.48-6.65-3.53-21.85-40.83-26.5-49.24-5.92z\"],\n    \"expeditedssl\": [496, 512, [], \"f23e\", \"M248 43.4C130.6 43.4 35.4 138.6 35.4 256S130.6 468.6 248 468.6 460.6 373.4 460.6 256 365.4 43.4 248 43.4zm-97.4 132.9c0-53.7 43.7-97.4 97.4-97.4s97.4 43.7 97.4 97.4v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6c0-82.1-124-82.1-124 0v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6zM389.7 380c0 9.7-8 17.7-17.7 17.7H124c-9.7 0-17.7-8-17.7-17.7V238.3c0-9.7 8-17.7 17.7-17.7h248c9.7 0 17.7 8 17.7 17.7V380zm-248-137.3v132.9c0 2.5-1.9 4.4-4.4 4.4h-8.9c-2.5 0-4.4-1.9-4.4-4.4V242.7c0-2.5 1.9-4.4 4.4-4.4h8.9c2.5 0 4.4 1.9 4.4 4.4zm141.7 48.7c0 13-7.2 24.4-17.7 30.4v31.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-31.6c-10.5-6.1-17.7-17.4-17.7-30.4 0-19.7 15.8-35.4 35.4-35.4s35.5 15.8 35.5 35.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 478.3C121 486.3 17.7 383 17.7 256S121 25.7 248 25.7 478.3 129 478.3 256 375 486.3 248 486.3z\"],\n    \"facebook\": [512, 512, [], \"f09a\", \"M504 256C504 119 393 8 256 8S8 119 8 256c0 123.78 90.69 226.38 209.25 245V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.28c-30.8 0-40.41 19.12-40.41 38.73V256h68.78l-11 71.69h-57.78V501C413.31 482.38 504 379.78 504 256z\"],\n    \"facebook-f\": [320, 512, [], \"f39e\", \"M279.14 288l14.22-92.66h-88.91v-60.13c0-25.35 12.42-50.06 52.24-50.06h40.42V6.26S260.43 0 225.36 0c-73.22 0-121.08 44.38-121.08 124.72v70.62H22.89V288h81.39v224h100.17V288z\"],\n    \"facebook-messenger\": [512, 512, [], \"f39f\", \"M256.55 8C116.52 8 8 110.34 8 248.57c0 72.3 29.71 134.78 78.07 177.94 8.35 7.51 6.63 11.86 8.05 58.23A19.92 19.92 0 0 0 122 502.31c52.91-23.3 53.59-25.14 62.56-22.7C337.85 521.8 504 423.7 504 248.57 504 110.34 396.59 8 256.55 8zm149.24 185.13l-73 115.57a37.37 37.37 0 0 1-53.91 9.93l-58.08-43.47a15 15 0 0 0-18 0l-78.37 59.44c-10.46 7.93-24.16-4.6-17.11-15.67l73-115.57a37.36 37.36 0 0 1 53.91-9.93l58.06 43.46a15 15 0 0 0 18 0l78.41-59.38c10.44-7.98 24.14 4.54 17.09 15.62z\"],\n    \"facebook-square\": [448, 512, [], \"f082\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h137.25V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.27c-30.81 0-40.42 19.12-40.42 38.73V256h68.78l-11 71.69h-57.78V480H400a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48z\"],\n    \"fantasy-flight-games\": [512, 512, [], \"f6dc\", \"M256 32.86L32.86 256 256 479.14 479.14 256 256 32.86zM88.34 255.83c1.96-2 11.92-12.3 96.49-97.48 41.45-41.75 86.19-43.77 119.77-18.69 24.63 18.4 62.06 58.9 62.15 59 .68.74 1.07 2.86.58 3.38-11.27 11.84-22.68 23.54-33.5 34.69-34.21-32.31-40.52-38.24-48.51-43.95-17.77-12.69-41.4-10.13-56.98 5.1-2.17 2.13-1.79 3.43.12 5.35 2.94 2.95 28.1 28.33 35.09 35.78-11.95 11.6-23.66 22.97-35.69 34.66-12.02-12.54-24.48-25.53-36.54-38.11-21.39 21.09-41.69 41.11-61.85 60.99a42569.01 42569.01 0 0 1-41.13-40.72zm234.82 101.6c-35.49 35.43-78.09 38.14-106.99 20.47-22.08-13.5-39.38-32.08-72.93-66.84 12.05-12.37 23.79-24.42 35.37-36.31 33.02 31.91 37.06 36.01 44.68 42.09 18.48 14.74 42.52 13.67 59.32-1.8 3.68-3.39 3.69-3.64.14-7.24-10.59-10.73-21.19-21.44-31.77-32.18-1.32-1.34-3.03-2.48-.8-4.69 10.79-10.71 21.48-21.52 32.21-32.29.26-.26.65-.38 1.91-1.07 12.37 12.87 24.92 25.92 37.25 38.75 21.01-20.73 41.24-40.68 61.25-60.42 13.68 13.4 27.13 26.58 40.86 40.03-20.17 20.86-81.68 82.71-100.5 101.5zM256 0L0 256l256 256 256-256L256 0zM16 256L256 16l240 240-240 240L16 256z\"],\n    \"fedex\": [640, 512, [], \"f797\", \"M586 284.5l53.3-59.9h-62.4l-21.7 24.8-22.5-24.8H414v-16h56.1v-48.1H318.9V236h-.5c-9.6-11-21.5-14.8-35.4-14.8-28.4 0-49.8 19.4-57.3 44.9-18-59.4-97.4-57.6-121.9-14v-24.2H49v-26.2h60v-41.1H0V345h49v-77.5h48.9c-1.5 5.7-2.3 11.8-2.3 18.2 0 73.1 102.6 91.4 130.2 23.7h-42c-14.7 20.9-45.8 8.9-45.8-14.6h85.5c3.7 30.5 27.4 56.9 60.1 56.9 14.1 0 27-6.9 34.9-18.6h.5V345h212.2l22.1-25 22.3 25H640l-54-60.5zm-446.7-16.6c6.1-26.3 41.7-25.6 46.5 0h-46.5zm153.4 48.9c-34.6 0-34-62.8 0-62.8 32.6 0 34.5 62.8 0 62.8zm167.8 19.1h-94.4V169.4h95v30.2H405v33.9h55.5v28.1h-56.1v44.7h56.1v29.6zm-45.9-39.8v-24.4h56.1v-44l50.7 57-50.7 57v-45.6h-56.1zm138.6 10.3l-26.1 29.5H489l45.6-51.2-45.6-51.2h39.7l26.6 29.3 25.6-29.3h38.5l-45.4 51 46 51.4h-40.5l-26.3-29.5z\"],\n    \"fedora\": [448, 512, [], \"f798\", \"M225 32C101.3 31.7.8 131.7.4 255.4L0 425.7a53.6 53.6 0 0 0 53.6 53.9l170.2.4c123.7.3 224.3-99.7 224.6-223.4S348.7 32.3 225 32zm169.8 157.2L333 126.6c2.3-4.7 3.8-9.2 3.8-14.3v-1.6l55.2 56.1a101 101 0 0 1 2.8 22.4zM331 94.3a106.06 106.06 0 0 1 58.5 63.8l-54.3-54.6a26.48 26.48 0 0 0-4.2-9.2zM118.1 247.2a49.66 49.66 0 0 0-7.7 11.4l-8.5-8.5a85.78 85.78 0 0 1 16.2-2.9zM97 251.4l11.8 11.9-.9 8a34.74 34.74 0 0 0 2.4 12.5l-27-27.2a80.6 80.6 0 0 1 13.7-5.2zm-18.2 7.4l38.2 38.4a53.17 53.17 0 0 0-14.1 4.7L67.6 266a107 107 0 0 1 11.2-7.2zm-15.2 9.8l35.3 35.5a67.25 67.25 0 0 0-10.5 8.5L53.5 278a64.33 64.33 0 0 1 10.1-9.4zm-13.3 12.3l34.9 35a56.84 56.84 0 0 0-7.7 11.4l-35.8-35.9c2.8-3.8 5.7-7.2 8.6-10.5zm-11 14.3l36.4 36.6a48.29 48.29 0 0 0-3.6 15.2l-39.5-39.8a99.81 99.81 0 0 1 6.7-12zm-8.8 16.3l41.3 41.8a63.47 63.47 0 0 0 6.7 26.2L25.8 326c1.4-4.9 2.9-9.6 4.7-14.5zm-7.9 43l61.9 62.2a31.24 31.24 0 0 0-3.6 14.3v1.1l-55.4-55.7a88.27 88.27 0 0 1-2.9-21.9zm5.3 30.7l54.3 54.6a28.44 28.44 0 0 0 4.2 9.2 106.32 106.32 0 0 1-58.5-63.8zm-5.3-37a80.69 80.69 0 0 1 2.1-17l72.2 72.5a37.59 37.59 0 0 0-9.9 8.7zm253.3-51.8l-42.6-.1-.1 56c-.2 69.3-64.4 115.8-125.7 102.9-5.7 0-19.9-8.7-19.9-24.2a24.89 24.89 0 0 1 24.5-24.6c6.3 0 6.3 1.6 15.7 1.6a55.91 55.91 0 0 0 56.1-55.9l.1-47c0-4.5-4.5-9-8.9-9l-33.6-.1c-32.6-.1-32.5-49.4.1-49.3l42.6.1.1-56a105.18 105.18 0 0 1 105.6-105 86.35 86.35 0 0 1 20.2 2.3c11.2 1.8 19.9 11.9 19.9 24 0 15.5-14.9 27.8-30.3 23.9-27.4-5.9-65.9 14.4-66 54.9l-.1 47a8.94 8.94 0 0 0 8.9 9l33.6.1c32.5.2 32.4 49.5-.2 49.4zm23.5-.3a35.58 35.58 0 0 0 7.6-11.4l8.5 8.5a102 102 0 0 1-16.1 2.9zm21-4.2L308.6 280l.9-8.1a34.74 34.74 0 0 0-2.4-12.5l27 27.2a74.89 74.89 0 0 1-13.7 5.3zm18-7.4l-38-38.4c4.9-1.1 9.6-2.4 13.7-4.7l36.2 35.9c-3.8 2.5-7.9 5-11.9 7.2zm15.5-9.8l-35.3-35.5a61.06 61.06 0 0 0 10.5-8.5l34.9 35a124.56 124.56 0 0 1-10.1 9zm13.2-12.3l-34.9-35a63.18 63.18 0 0 0 7.7-11.4l35.8 35.9a130.28 130.28 0 0 1-8.6 10.5zm11-14.3l-36.4-36.6a48.29 48.29 0 0 0 3.6-15.2l39.5 39.8a87.72 87.72 0 0 1-6.7 12zm13.5-30.9a140.63 140.63 0 0 1-4.7 14.3L345.6 190a58.19 58.19 0 0 0-7.1-26.2zm1-5.6l-71.9-72.1a32 32 0 0 0 9.9-9.2l64.3 64.7a90.93 90.93 0 0 1-2.3 16.6z\"],\n    \"figma\": [384, 512, [], \"f799\", \"M277 170.7A85.35 85.35 0 0 0 277 0H106.3a85.3 85.3 0 0 0 0 170.6 85.35 85.35 0 0 0 0 170.7 85.35 85.35 0 1 0 85.3 85.4v-256zm0 0a85.3 85.3 0 1 0 85.3 85.3 85.31 85.31 0 0 0-85.3-85.3z\"],\n    \"firefox\": [480, 512, [], \"f269\", \"M478.1 235.3c-.7-4.5-1.4-7.1-1.4-7.1s-1.8 2-4.7 5.9c-.9-10.7-2.8-21.2-5.8-31.6-3.7-12.9-8.5-25.4-14.5-37.4-3.8-8-8.2-15.6-13.3-22.8-1.8-2.7-3.7-5.4-5.6-7.9-8.8-14.4-19-23.3-30.7-40-7.6-12.8-12.9-26.9-15.4-41.6-3.2 8.9-5.7 18-7.4 27.3-12.1-12.2-22.5-20.8-28.9-26.7C319.4 24.2 323 9.1 323 9.1S264.7 74.2 289.9 142c8.7 23 23.8 43.1 43.4 57.9 24.4 20.2 50.8 36 64.7 76.6-11.2-21.3-28.1-39.2-48.8-51.5 6.2 14.7 9.4 30.6 9.3 46.5 0 61-49.6 110.5-110.6 110.4-8.3 0-16.5-.9-24.5-2.8-9.5-1.8-18.7-4.9-27.4-9.3-12.9-7.8-24-18.1-32.8-30.3l-.2-.3 2 .7c4.6 1.6 9.2 2.8 14 3.7 18.7 4 38.3 1.7 55.6-6.6 17.5-9.7 28-16.9 36.6-14h.2c8.4 2.7 15-5.5 9-14-10.4-13.4-27.4-20-44.2-17-17.5 2.5-33.5 15-56.4 2.9-1.5-.8-2.9-1.6-4.3-2.5-1.6-.9 4.9 1.3 3.4.3-5-2.5-9.8-5.4-14.4-8.6-.3-.3 3.5 1.1 3.1.8-5.9-4-11-9.2-15-15.2-4.1-7.4-4.5-16.4-1-24.1 2.1-3.8 5.4-6.9 9.3-8.7 3 1.5 4.8 2.6 4.8 2.6s-1.3-2.5-2.1-3.8c.3-.1.5 0 .8-.2 2.6 1.1 8.3 4 11.4 5.8 2.1 1.1 3.8 2.7 5.2 4.7 0 0 1-.5.3-2.7-1.1-2.7-2.9-5-5.4-6.6h.2c2.3 1.2 4.5 2.6 6.6 4.1 1.9-4.4 2.8-9.2 2.6-14 .2-2.6-.2-5.3-1.1-7.8-.8-1.6.5-2.2 1.9-.5-.2-1.3-.7-2.5-1.2-3.7v-.1s.8-1.1 1.2-1.5c1-1 2.1-1.9 3.4-2.7 7.2-4.5 14.8-8.4 22.7-11.6 6.4-2.8 11.7-4.9 12.8-5.6 1.6-1 3.1-2.2 4.5-3.5 5.3-4.5 9-10.8 10.2-17.7.1-.9.2-1.8.3-2.8v-1.5c-.9-3.5-6.9-6.1-38.4-9.1-11.1-1.8-20-10.1-22.5-21.1v-.1c6-15.7 16.8-29.1 30.8-38.3.8-.7-3.2.2-2.4-.5 2.7-1.3 5.4-2.5 8.2-3.5 1.4-.6-6-3.4-12.6-2.7-4 .2-8 1.2-11.7 2.8 1.6-1.3 6.2-3.1 5.1-3.1-8.4 1.6-16.5 4.7-23.9 9 0-.8.1-1.5.5-2.2-5.9 2.5-11 6.5-15 11.5.1-.9.2-1.8.2-2.7-2.7 2-5.2 4.3-7.3 6.9l-.1.1c-17.4-6.7-36.3-8.3-54.6-4.7l-.2-.1h.2c-3.8-3.1-7.1-6.7-9.7-10.9l-.2.1-.4-.2c-1.2-1.8-2.4-3.8-3.7-6-.9-1.6-1.8-3.4-2.7-5.2 0-.1-.1-.2-.2-.2-.4 0-.6 1.7-.9 1.3v-.1c-3.2-8.3-4.7-17.2-4.4-26.2l-.2.1c-5.1 3.5-9 8.6-11.1 14.5-.9 2.1-1.6 3.3-2.2 4.5v-.5c.1-1.1.6-3.3.5-3.1s-.2.3-.3.4c-1.5 1.7-2.9 3.7-3.9 5.8-.9 1.9-1.7 3.9-2.3 5.9-.1.3 0-.3 0-1s.1-2 0-1.7l-.3.7c-6.7 14.9-10.9 30.8-12.4 47.1-.4 2.8-.6 5.6-.5 8.3v.2c-4.8 5.2-9 11-12.7 17.1-12.1 20.4-21.1 42.5-26.8 65.6 4-8.8 8.8-17.2 14.3-25.1C5.5 228.5 0 257.4 0 286.6c1.8-8.6 4.2-17 7-25.3-1.7 34.5 4.9 68.9 19.4 100.3 19.4 43.5 51.6 80 92.3 104.7 16.6 11.2 34.7 19.9 53.8 25.8 2.5.9 5.1 1.8 7.7 2.7-.8-.3-1.6-.7-2.4-1 22.6 6.8 46.2 10.3 69.8 10.3 83.7 0 111.3-31.9 113.8-35 4.1-3.7 7.5-8.2 9.9-13.3 1.6-.7 3.2-1.4 4.9-2.1l1-.5 1.9-.9c12.6-5.9 24.5-13.4 35.3-22.1 16.3-11.7 27.9-28.7 32.9-48.1 3-7.1 3.1-15 .4-22.2.9-1.4 1.7-2.8 2.7-4.3 18-28.9 28.2-61.9 29.6-95.9v-2.8c0-7.3-.6-14.5-1.9-21.6zm-299-97.6c-.4 1.1-.9 2.3-1.3 3.5.4-1.2.8-2.3 1.3-3.5z\"],\n    \"first-order\": [448, 512, [], \"f2b0\", \"M12.9 229.2c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4h-.2zM224 96.6c-7.1 0-14.6.6-21.4 1.7l3.7 67.4-22-64c-14.3 3.7-27.7 9.4-40 16.6l29.4 61.4-45.1-50.9c-11.4 8.9-21.7 19.1-30.6 30.9l50.6 45.4-61.1-29.7c-7.1 12.3-12.9 25.7-16.6 40l64.3 22.6-68-4c-.9 7.1-1.4 14.6-1.4 22s.6 14.6 1.4 21.7l67.7-4-64 22.6c3.7 14.3 9.4 27.7 16.6 40.3l61.1-29.7L97.7 352c8.9 11.7 19.1 22.3 30.9 30.9l44.9-50.9-29.5 61.4c12.3 7.4 25.7 13.1 40 16.9l22.3-64.6-4 68c7.1 1.1 14.6 1.7 21.7 1.7 7.4 0 14.6-.6 21.7-1.7l-4-68.6 22.6 65.1c14.3-4 27.7-9.4 40-16.9L274.9 332l44.9 50.9c11.7-8.9 22-19.1 30.6-30.9l-50.6-45.1 61.1 29.4c7.1-12.3 12.9-25.7 16.6-40.3l-64-22.3 67.4 4c1.1-7.1 1.4-14.3 1.4-21.7s-.3-14.9-1.4-22l-67.7 4 64-22.3c-3.7-14.3-9.1-28-16.6-40.3l-60.9 29.7 50.6-45.4c-8.9-11.7-19.1-22-30.6-30.9l-45.1 50.9 29.4-61.1c-12.3-7.4-25.7-13.1-40-16.9L241.7 166l4-67.7c-7.1-1.2-14.3-1.7-21.7-1.7zM443.4 128v256L224 512 4.6 384V128L224 0l219.4 128zm-17.1 10.3L224 20.9 21.7 138.3v235.1L224 491.1l202.3-117.7V138.3zM224 37.1l187.7 109.4v218.9L224 474.9 36.3 365.4V146.6L224 37.1zm0 50.9c-92.3 0-166.9 75.1-166.9 168 0 92.6 74.6 167.7 166.9 167.7 92 0 166.9-75.1 166.9-167.7 0-92.9-74.9-168-166.9-168z\"],\n    \"first-order-alt\": [496, 512, [], \"f50a\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 488.21C115.34 496.21 7.79 388.66 7.79 256S115.34 15.79 248 15.79 488.21 123.34 488.21 256 380.66 496.21 248 496.21zm0-459.92C126.66 36.29 28.29 134.66 28.29 256S126.66 475.71 248 475.71 467.71 377.34 467.71 256 369.34 36.29 248 36.29zm0 431.22c-116.81 0-211.51-94.69-211.51-211.51S131.19 44.49 248 44.49 459.51 139.19 459.51 256 364.81 467.51 248 467.51zm186.23-162.98a191.613 191.613 0 0 1-20.13 48.69l-74.13-35.88 61.48 54.82a193.515 193.515 0 0 1-37.2 37.29l-54.8-61.57 35.88 74.27a190.944 190.944 0 0 1-48.63 20.23l-27.29-78.47 4.79 82.93c-8.61 1.18-17.4 1.8-26.33 1.8s-17.72-.62-26.33-1.8l4.76-82.46-27.15 78.03a191.365 191.365 0 0 1-48.65-20.2l35.93-74.34-54.87 61.64a193.85 193.85 0 0 1-37.22-37.28l61.59-54.9-74.26 35.93a191.638 191.638 0 0 1-20.14-48.69l77.84-27.11-82.23 4.76c-1.16-8.57-1.78-17.32-1.78-26.21 0-9 .63-17.84 1.82-26.51l82.38 4.77-77.94-27.16a191.726 191.726 0 0 1 20.23-48.67l74.22 35.92-61.52-54.86a193.85 193.85 0 0 1 37.28-37.22l54.76 61.53-35.83-74.17a191.49 191.49 0 0 1 48.65-20.13l26.87 77.25-4.71-81.61c8.61-1.18 17.39-1.8 26.32-1.8s17.71.62 26.32 1.8l-4.74 82.16 27.05-77.76c17.27 4.5 33.6 11.35 48.63 20.17l-35.82 74.12 54.72-61.47a193.13 193.13 0 0 1 37.24 37.23l-61.45 54.77 74.12-35.86a191.515 191.515 0 0 1 20.2 48.65l-77.81 27.1 82.24-4.75c1.19 8.66 1.82 17.5 1.82 26.49 0 8.88-.61 17.63-1.78 26.19l-82.12-4.75 77.72 27.09z\"],\n    \"firstdraft\": [384, 512, [], \"f3a1\", \"M384 192h-64v128H192v128H0v-25.6h166.4v-128h128v-128H384V192zm-25.6 38.4v128h-128v128H64V512h192V384h128V230.4h-25.6zm25.6 192h-89.6V512H320v-64h64v-25.6zM0 0v384h128V256h128V128h128V0H0z\"],\n    \"flickr\": [448, 512, [], \"f16e\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM144.5 319c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5zm159 0c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5z\"],\n    \"flipboard\": [448, 512, [], \"f44d\", \"M0 32v448h448V32H0zm358.4 179.2h-89.6v89.6h-89.6v89.6H89.6V121.6h268.8v89.6z\"],\n    \"fly\": [384, 512, [], \"f417\", \"M197.8 427.8c12.9 11.7 33.7 33.3 33.2 50.7 0 .8-.1 1.6-.1 2.5-1.8 19.8-18.8 31.1-39.1 31-25-.1-39.9-16.8-38.7-35.8 1-16.2 20.5-36.7 32.4-47.6 2.3-2.1 2.7-2.7 5.6-3.6 3.4 0 3.9.3 6.7 2.8zM331.9 67.3c-16.3-25.7-38.6-40.6-63.3-52.1C243.1 4.5 214-.2 192 0c-44.1 0-71.2 13.2-81.1 17.3C57.3 45.2 26.5 87.2 28 158.6c7.1 82.2 97 176 155.8 233.8 1.7 1.6 4.5 4.5 6.2 5.1l3.3.1c2.1-.7 1.8-.5 3.5-2.1 52.3-49.2 140.7-145.8 155.9-215.7 7-39.2 3.1-72.5-20.8-112.5zM186.8 351.9c-28-51.1-65.2-130.7-69.3-189-3.4-47.5 11.4-131.2 69.3-136.7v325.7zM328.7 180c-16.4 56.8-77.3 128-118.9 170.3C237.6 298.4 275 217 277 158.4c1.6-45.9-9.8-105.8-48-131.4 88.8 18.3 115.5 98.1 99.7 153z\"],\n    \"font-awesome\": [448, 512, [], \"f2b4\", \"M397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm-45.4 284.3c0 4.2-3.6 6-7.8 7.8-16.7 7.2-34.6 13.7-53.8 13.7-26.9 0-39.4-16.7-71.7-16.7-23.3 0-47.8 8.4-67.5 17.3-1.2.6-2.4.6-3.6 1.2V385c0 1.8 0 3.6-.6 4.8v1.2c-2.4 8.4-10.2 14.3-19.1 14.3-11.3 0-20.3-9-20.3-20.3V166.4c-7.8-6-13.1-15.5-13.1-26.3 0-18.5 14.9-33.5 33.5-33.5 18.5 0 33.5 14.9 33.5 33.5 0 10.8-4.8 20.3-13.1 26.3v18.5c1.8-.6 3.6-1.2 5.4-2.4 18.5-7.8 40.6-14.3 61.5-14.3 22.7 0 40.6 6 60.9 13.7 4.2 1.8 8.4 2.4 13.1 2.4 22.7 0 47.8-16.1 53.8-16.1 4.8 0 9 3.6 9 7.8v140.3z\"],\n    \"font-awesome-alt\": [448, 512, [], \"f35c\", \"M339.3 171.2c-6 0-29.9 15.5-52.6 15.5-4.2 0-8.4-.6-12.5-2.4-19.7-7.8-37-13.7-59.1-13.7-20.3 0-41.8 6.6-59.7 13.7-1.8.6-3.6 1.2-4.8 1.8v-17.9c7.8-6 12.5-14.9 12.5-25.7 0-17.9-14.3-32.3-32.3-32.3s-32.3 14.3-32.3 32.3c0 10.2 4.8 19.7 12.5 25.7v212.1c0 10.8 9 19.7 19.7 19.7 9 0 16.1-6 18.5-13.7V385c.6-1.8.6-3 .6-4.8V336c1.2 0 2.4-.6 3-1.2 19.7-8.4 43-16.7 65.7-16.7 31.1 0 43 16.1 69.3 16.1 18.5 0 36.4-6.6 52-13.7 4.2-1.8 7.2-3.6 7.2-7.8V178.3c1.8-4.1-2.3-7.1-7.7-7.1zM397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm14.3 397.7c0 7.8-6.6 14.3-14.3 14.3H50.2c-7.8 0-14.3-6.6-14.3-14.3V82.2c0-7.8 6.6-14.3 14.3-14.3h347.6v-.1c7.8 0 14.3 6.6 14.3 14.3z\"],\n    \"font-awesome-flag\": [448, 512, [], \"f425\", \"M444.373 359.424c0 7.168-6.144 10.24-13.312 13.312-28.672 12.288-59.392 23.552-92.16 23.552-46.08 0-67.584-28.672-122.88-28.672-39.936 0-81.92 14.336-115.712 29.696-2.048 1.024-4.096 1.024-6.144 2.048v77.824c0 21.405-16.122 34.816-33.792 34.816-19.456 0-34.816-15.36-34.816-34.816V102.4C12.245 92.16 3.029 75.776 3.029 57.344 3.029 25.6 28.629 0 60.373 0s57.344 25.6 57.344 57.344c0 18.432-8.192 34.816-22.528 45.056v31.744c4.124-1.374 58.768-28.672 114.688-28.672 65.27 0 97.676 27.648 126.976 27.648 38.912 0 81.92-27.648 92.16-27.648 8.192 0 15.36 6.144 15.36 13.312v240.64z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"fonticons\": [448, 512, [], \"f280\", \"M0 32v448h448V32zm187 140.9c-18.4 0-19 9.9-19 27.4v23.3c0 2.4-3.5 4.4-.6 4.4h67.4l-11.1 37.3H168v112.9c0 5.8-2 6.7 3.2 7.3l43.5 4.1v25.1H84V389l21.3-2c5.2-.6 6.7-2.3 6.7-7.9V267.7c0-2.3-2.9-2.3-5.8-2.3H84V228h28v-21c0-49.6 26.5-70 77.3-70 34.1 0 64.7 8.2 64.7 52.8l-50.7 6.1c.3-18.7-4.4-23-16.3-23zm74.3 241.8v-25.1l20.4-2.6c5.2-.6 7.6-1.7 7.6-7.3V271.8c0-4.1-2.9-6.7-6.7-7.9l-24.2-6.4 6.7-29.5h80.2v151.7c0 5.8-2.6 6.4 2.9 7.3l15.7 2.6v25.1zm80.8-255.5l9 33.2-7.3 7.3-31.2-16.6-31.2 16.6-7.3-7.3 9-33.2-21.8-24.2 3.5-9.6h27.7l15.5-28h9.3l15.5 28h27.7l3.5 9.6z\"],\n    \"fonticons-fi\": [384, 512, [], \"f3a2\", \"M114.4 224h92.4l-15.2 51.2h-76.4V433c0 8-2.8 9.2 4.4 10l59.6 5.6V483H0v-35.2l29.2-2.8c7.2-.8 9.2-3.2 9.2-10.8V278.4c0-3.2-4-3.2-8-3.2H0V224h38.4v-28.8c0-68 36.4-96 106-96 46.8 0 88.8 11.2 88.8 72.4l-69.6 8.4c.4-25.6-6-31.6-22.4-31.6-25.2 0-26 13.6-26 37.6v32c0 3.2-4.8 6-.8 6zM384 483H243.2v-34.4l28-3.6c7.2-.8 10.4-2.4 10.4-10V287c0-5.6-4-9.2-9.2-10.8l-33.2-8.8 9.2-40.4h110v208c0 8-3.6 8.8 4 10l21.6 3.6V483zm-30-347.2l12.4 45.6-10 10-42.8-22.8-42.8 22.8-10-10 12.4-45.6-30-36.4 4.8-10h38L307.2 51H320l21.2 38.4h38l4.8 13.2-30 33.2z\"],\n    \"fort-awesome\": [512, 512, [], \"f286\", \"M489.2 287.9h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6V146.2c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-6-8-4.6-11.7-4.6v-38c8.3-2 17.1-3.4 25.7-3.4 10.9 0 20.9 4.3 31.4 4.3 4.6 0 27.7-1.1 27.7-8v-60c0-2.6-2-4.6-4.6-4.6-5.1 0-15.1 4.3-24 4.3-9.7 0-20.9-4.3-32.6-4.3-8 0-16 1.1-23.7 2.9v-4.9c5.4-2.6 9.1-8.3 9.1-14.3 0-20.7-31.4-20.8-31.4 0 0 6 3.7 11.7 9.1 14.3v111.7c-3.7 0-11.7-1.4-11.7 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32H128v-32c0-2.6-2-4.6-4.6-4.6H96c-2.6 0-4.6 2-4.6 4.6v178.3H54.8v-32c0-2.6-2-4.6-4.6-4.6H22.8c-2.6 0-4.6 2-4.6 4.6V512h182.9v-96c0-72.6 109.7-72.6 109.7 0v96h182.9V292.5c.1-2.6-1.9-4.6-4.5-4.6zm-288.1-4.5c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64zm146.4 0c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64z\"],\n    \"fort-awesome-alt\": [512, 512, [], \"f3a3\", \"M208 237.4h-22.2c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7H208c2.1 0 3.7-1.6 3.7-3.7v-51.7c0-2.1-1.6-3.7-3.7-3.7zm118.2 0H304c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7h22.2c2.1 0 3.7-1.6 3.7-3.7v-51.7c-.1-2.1-1.7-3.7-3.7-3.7zm132-125.1c-2.3-3.2-4.6-6.4-7.1-9.5-9.8-12.5-20.8-24-32.8-34.4-4.5-3.9-9.1-7.6-13.9-11.2-1.6-1.2-3.2-2.3-4.8-3.5C372 34.1 340.3 20 306 13c-16.2-3.3-32.9-5-50-5s-33.9 1.7-50 5c-34.3 7.1-66 21.2-93.3 40.8-1.6 1.1-3.2 2.3-4.8 3.5-4.8 3.6-9.4 7.3-13.9 11.2-3 2.6-5.9 5.3-8.8 8s-5.7 5.5-8.4 8.4c-5.5 5.7-10.7 11.8-15.6 18-2.4 3.1-4.8 6.3-7.1 9.5C25.2 153 8.3 202.5 8.3 256c0 2 .1 4 .1 6 .1.7.1 1.3.1 2 .1 1.3.1 2.7.2 4 0 .8.1 1.5.1 2.3 0 1.3.1 2.5.2 3.7.1.8.1 1.6.2 2.4.1 1.1.2 2.3.3 3.5 0 .8.1 1.6.2 2.4.1 1.2.3 2.4.4 3.6.1.8.2 1.5.3 2.3.1 1.3.3 2.6.5 3.9.1.6.2 1.3.3 1.9l.9 5.7c.1.6.2 1.1.3 1.7.3 1.3.5 2.7.8 4 .2.8.3 1.6.5 2.4.2 1 .5 2.1.7 3.2.2.9.4 1.7.6 2.6.2 1 .4 2 .7 3 .2.9.5 1.8.7 2.7.3 1 .5 1.9.8 2.9.3.9.5 1.8.8 2.7.2.9.5 1.9.8 2.8s.5 1.8.8 2.7c.3 1 .6 1.9.9 2.8.6 1.6 1.1 3.3 1.7 4.9.4 1 .7 1.9 1 2.8.3 1 .7 2 1.1 3 .3.8.6 1.5.9 2.3l1.2 3c.3.7.6 1.5.9 2.2.4 1 .9 2 1.3 3l.9 2.1c.5 1 .9 2 1.4 3 .3.7.6 1.3.9 2 .5 1 1 2.1 1.5 3.1.2.6.5 1.1.8 1.7.6 1.1 1.1 2.2 1.7 3.3.1.2.2.3.3.5 2.2 4.1 4.4 8.2 6.8 12.2.2.4.5.8.7 1.2.7 1.1 1.3 2.2 2 3.3.3.5.6.9.9 1.4.6 1.1 1.3 2.1 2 3.2.3.5.6.9.9 1.4.7 1.1 1.4 2.1 2.1 3.2.2.4.5.8.8 1.2.7 1.1 1.5 2.2 2.3 3.3.2.2.3.5.5.7 37.5 51.7 94.4 88.5 160 99.4.9.1 1.7.3 2.6.4 1 .2 2.1.4 3.1.5s1.9.3 2.8.4c1 .2 2 .3 3 .4.9.1 1.9.2 2.9.3s1.9.2 2.9.3 2.1.2 3.1.3c.9.1 1.8.1 2.7.2 1.1.1 2.3.1 3.4.2.8 0 1.7.1 2.5.1 1.3 0 2.6.1 3.9.1.7.1 1.4.1 2.1.1 2 .1 4 .1 6 .1s4-.1 6-.1c.7 0 1.4-.1 2.1-.1 1.3 0 2.6 0 3.9-.1.8 0 1.7-.1 2.5-.1 1.1-.1 2.3-.1 3.4-.2.9 0 1.8-.1 2.7-.2 1-.1 2.1-.2 3.1-.3s1.9-.2 2.9-.3c.9-.1 1.9-.2 2.9-.3s2-.3 3-.4 1.9-.3 2.8-.4c1-.2 2.1-.3 3.1-.5.9-.1 1.7-.3 2.6-.4 65.6-11 122.5-47.7 160.1-102.4.2-.2.3-.5.5-.7.8-1.1 1.5-2.2 2.3-3.3.2-.4.5-.8.8-1.2.7-1.1 1.4-2.1 2.1-3.2.3-.5.6-.9.9-1.4.6-1.1 1.3-2.1 2-3.2.3-.5.6-.9.9-1.4.7-1.1 1.3-2.2 2-3.3.2-.4.5-.8.7-1.2 2.4-4 4.6-8.1 6.8-12.2.1-.2.2-.3.3-.5.6-1.1 1.1-2.2 1.7-3.3.2-.6.5-1.1.8-1.7.5-1 1-2.1 1.5-3.1.3-.7.6-1.3.9-2 .5-1 1-2 1.4-3l.9-2.1c.5-1 .9-2 1.3-3 .3-.7.6-1.5.9-2.2l1.2-3c.3-.8.6-1.5.9-2.3.4-1 .7-2 1.1-3s.7-1.9 1-2.8c.6-1.6 1.2-3.3 1.7-4.9.3-1 .6-1.9.9-2.8s.5-1.8.8-2.7c.2-.9.5-1.9.8-2.8s.6-1.8.8-2.7c.3-1 .5-1.9.8-2.9.2-.9.5-1.8.7-2.7.2-1 .5-2 .7-3 .2-.9.4-1.7.6-2.6.2-1 .5-2.1.7-3.2.2-.8.3-1.6.5-2.4.3-1.3.6-2.7.8-4 .1-.6.2-1.1.3-1.7l.9-5.7c.1-.6.2-1.3.3-1.9.1-1.3.3-2.6.5-3.9.1-.8.2-1.5.3-2.3.1-1.2.3-2.4.4-3.6 0-.8.1-1.6.2-2.4.1-1.1.2-2.3.3-3.5.1-.8.1-1.6.2-2.4.1 1.7.1.5.2-.7 0-.8.1-1.5.1-2.3.1-1.3.2-2.7.2-4 .1-.7.1-1.3.1-2 .1-2 .1-4 .1-6 0-53.5-16.9-103-45.8-143.7zM448 371.5c-9.4 15.5-20.6 29.9-33.6 42.9-20.6 20.6-44.5 36.7-71.2 48-13.9 5.8-28.2 10.3-42.9 13.2v-75.8c0-58.6-88.6-58.6-88.6 0v75.8c-14.7-2.9-29-7.3-42.9-13.2-26.7-11.3-50.6-27.4-71.2-48-13-13-24.2-27.4-33.6-42.9v-71.3c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7V326h29.6V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7H208c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-4.8 6.5-3.7 9.5-3.7V88.1c-4.4-2-7.4-6.7-7.4-11.5 0-16.8 25.4-16.8 25.4 0 0 4.8-3 9.4-7.4 11.5V92c6.3-1.4 12.7-2.3 19.2-2.3 9.4 0 18.4 3.5 26.3 3.5 7.2 0 15.2-3.5 19.4-3.5 2.1 0 3.7 1.6 3.7 3.7v48.4c0 5.6-18.7 6.5-22.4 6.5-8.6 0-16.6-3.5-25.4-3.5-7 0-14.1 1.2-20.8 2.8v30.7c3 0 9.5-1.1 9.5 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v144h29.5v-25.8c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7z\"],\n    \"forumbee\": [448, 512, [], \"f211\", \"M5.8 309.7C2 292.7 0 275.5 0 258.3 0 135 99.8 35 223.1 35c16.6 0 33.3 2 49.3 5.5C149 87.5 51.9 186 5.8 309.7zm392.9-189.2C385 103 369 87.8 350.9 75.2c-149.6 44.3-266.3 162.1-309.7 312 12.5 18.1 28 35.6 45.2 49 43.1-151.3 161.2-271.7 312.3-315.7zm15.8 252.7c15.2-25.1 25.4-53.7 29.5-82.8-79.4 42.9-145 110.6-187.6 190.3 30-4.4 58.9-15.3 84.6-31.3 35 13.1 70.9 24.3 107 33.6-9.3-36.5-20.4-74.5-33.5-109.8zm29.7-145.5c-2.6-19.5-7.9-38.7-15.8-56.8C290.5 216.7 182 327.5 137.1 466c18.1 7.6 37 12.5 56.6 15.2C240 367.1 330.5 274.4 444.2 227.7z\"],\n    \"foursquare\": [368, 512, [], \"f180\", \"M323.1 3H49.9C12.4 3 0 31.3 0 49.1v433.8c0 20.3 12.1 27.7 18.2 30.1 6.2 2.5 22.8 4.6 32.9-7.1C180 356.5 182.2 354 182.2 354c3.1-3.4 3.4-3.1 6.8-3.1h83.4c35.1 0 40.6-25.2 44.3-39.7l48.6-243C373.8 25.8 363.1 3 323.1 3zm-16.3 73.8l-11.4 59.7c-1.2 6.5-9.5 13.2-16.9 13.2H172.1c-12 0-20.6 8.3-20.6 20.3v13c0 12 8.6 20.6 20.6 20.6h90.4c8.3 0 16.6 9.2 14.8 18.2-1.8 8.9-10.5 53.8-11.4 58.8-.9 4.9-6.8 13.5-16.9 13.5h-73.5c-13.5 0-17.2 1.8-26.5 12.6 0 0-8.9 11.4-89.5 108.3-.9.9-1.8.6-1.8-.3V75.9c0-7.7 6.8-16.6 16.6-16.6h219c8.2 0 15.6 7.7 13.5 17.5z\"],\n    \"free-code-camp\": [576, 512, [], \"f2c5\", \"M69.3 144.5c-41 68.5-36.4 163 1 227C92.5 409.7 120 423.9 120 438c0 6.8-6 13-12.8 13C87.7 451 8 375.5 8 253.2c0-111.5 78-186 97.1-186 6 0 14.9 4.8 14.9 11.1 0 12.7-28.3 28.6-50.7 66.2zm195.8 213.8c4.5 1.8 12.3 5.2 12.3-1.2 0-2.7-2.2-2.9-4.3-3.6-8.5-3.4-14-7.7-19.1-15.2-8.2-12.1-10.1-24.2-10.1-38.6 0-32.1 44.2-37.9 44.2-70 0-12.3-7.7-15.9-7.7-19.3 0-2.2.7-2.2 2.9-2.2 8 0 19.1 13.3 22.5 19.8 2.2 4.6 2.4 6 2.4 11.1 0 7-.7 14.2-.7 21.3 0 27 31.9 19.8 31.9 6.8 0-6-3.6-11.6-3.6-17.4 0-.7 0-1.2.7-1.2 3.4 0 9.4 7.7 11.1 10.1 5.8 8.9 8.5 20.8 8.5 31.4 0 32.4-29.5 49-29.5 56 0 1 2.9 7.7 12.1 1.9 29.7-15.1 53.1-47.6 53.1-89.8 0-33.6-8.7-57.7-32.1-82.6-3.9-4.1-16.4-16.9-22.5-16.9-8.2 0 7.2 18.6 7.2 31.2 0 7.2-4.8 12.3-12.3 12.3-11.6 0-14.5-25.4-15.9-33.3-5.8-33.8-12.8-58.2-46.4-74.1-10.4-5-36.5-11.8-36.5-2.2 0 2.4 2.7 4.1 4.6 5.1 9.2 5.6 19.6 21.4 19.6 38.2 0 46.1-57.7 88.2-57.7 136.2-.2 40.3 28.1 72.6 65.3 86.2zM470.4 67c-6 0-14.4 6.5-14.4 12.6 0 8.7 12.1 19.6 17.6 25.4 81.6 85.1 78.6 214.3 17.6 291-7 8.9-35.3 35.3-35.3 43.5 0 5.1 8.2 11.4 13.2 11.4 25.4 0 98.8-80.8 98.8-185.7C568 145.9 491.8 67 470.4 67zm-42.3 323.1H167c-9.4 0-15.5 7.5-15.5 16.4 0 8.5 7 15.5 15.5 15.5h261.1c9.4 0 11.9-7.5 11.9-16.4 0-8.5-3.5-15.5-11.9-15.5z\"],\n    \"freebsd\": [448, 512, [], \"f3a4\", \"M303.7 96.2c11.1-11.1 115.5-77 139.2-53.2 23.7 23.7-42.1 128.1-53.2 139.2-11.1 11.1-39.4.9-63.1-22.9-23.8-23.7-34.1-52-22.9-63.1zM109.9 68.1C73.6 47.5 22 24.6 5.6 41.1c-16.6 16.6 7.1 69.4 27.9 105.7 18.5-32.2 44.8-59.3 76.4-78.7zM406.7 174c3.3 11.3 2.7 20.7-2.7 26.1-20.3 20.3-87.5-27-109.3-70.1-18-32.3-11.1-53.4 14.9-48.7 5.7-3.6 12.3-7.6 19.6-11.6-29.8-15.5-63.6-24.3-99.5-24.3-119.1 0-215.6 96.5-215.6 215.6 0 119 96.5 215.6 215.6 215.6S445.3 380.1 445.3 261c0-38.4-10.1-74.5-27.7-105.8-3.9 7-7.6 13.3-10.9 18.8z\"],\n    \"fulcrum\": [320, 512, [], \"f50b\", \"M95.75 164.14l-35.38 43.55L25 164.14l35.38-43.55zM144.23 0l-20.54 198.18L72.72 256l51 57.82L144.23 512V300.89L103.15 256l41.08-44.89zm79.67 164.14l35.38 43.55 35.38-43.55-35.38-43.55zm-48.48 47L216.5 256l-41.08 44.89V512L196 313.82 247 256l-51-57.82L175.42 0z\"],\n    \"galactic-republic\": [496, 512, [], \"f50c\", \"M248 504C111.25 504 0 392.75 0 256S111.25 8 248 8s248 111.25 248 248-111.25 248-248 248zm0-479.47C120.37 24.53 16.53 128.37 16.53 256S120.37 487.47 248 487.47 479.47 383.63 479.47 256 375.63 24.53 248 24.53zm27.62 21.81v24.62a185.933 185.933 0 0 1 83.57 34.54l17.39-17.36c-28.75-22.06-63.3-36.89-100.96-41.8zm-55.37.07c-37.64 4.94-72.16 19.8-100.88 41.85l17.28 17.36h.08c24.07-17.84 52.55-30.06 83.52-34.67V46.41zm12.25 50.17v82.87c-10.04 2.03-19.42 5.94-27.67 11.42l-58.62-58.59-21.93 21.93 58.67 58.67c-5.47 8.23-9.45 17.59-11.47 27.62h-82.9v31h82.9c2.02 10.02 6.01 19.31 11.47 27.54l-58.67 58.69 21.93 21.93 58.62-58.62a77.873 77.873 0 0 0 27.67 11.47v82.9h31v-82.9c10.05-2.03 19.37-6.06 27.62-11.55l58.67 58.69 21.93-21.93-58.67-58.69c5.46-8.23 9.47-17.52 11.5-27.54h82.87v-31h-82.87c-2.02-10.02-6.03-19.38-11.5-27.62l58.67-58.67-21.93-21.93-58.67 58.67c-8.25-5.49-17.57-9.47-27.62-11.5V96.58h-31zm183.24 30.72l-17.36 17.36a186.337 186.337 0 0 1 34.67 83.67h24.62c-4.95-37.69-19.83-72.29-41.93-101.03zm-335.55.13c-22.06 28.72-36.91 63.26-41.85 100.91h24.65c4.6-30.96 16.76-59.45 34.59-83.52l-17.39-17.39zM38.34 283.67c4.92 37.64 19.75 72.18 41.8 100.9l17.36-17.39c-17.81-24.07-29.92-52.57-34.51-83.52H38.34zm394.7 0c-4.61 30.99-16.8 59.5-34.67 83.6l17.36 17.36c22.08-28.74 36.98-63.29 41.93-100.96h-24.62zM136.66 406.38l-17.36 17.36c28.73 22.09 63.3 36.98 100.96 41.93v-24.64c-30.99-4.63-59.53-16.79-83.6-34.65zm222.53.05c-24.09 17.84-52.58 30.08-83.57 34.67v24.57c37.67-4.92 72.21-19.79 100.96-41.85l-17.31-17.39h-.08z\"],\n    \"galactic-senate\": [512, 512, [], \"f50d\", \"M249.86 33.48v26.07C236.28 80.17 226 168.14 225.39 274.9c11.74-15.62 19.13-33.33 19.13-48.24v-16.88c-.03-5.32.75-10.53 2.19-15.65.65-2.14 1.39-4.08 2.62-5.82 1.23-1.75 3.43-3.79 6.68-3.79 3.24 0 5.45 2.05 6.68 3.79 1.23 1.75 1.97 3.68 2.62 5.82 1.44 5.12 2.22 10.33 2.19 15.65v16.88c0 14.91 7.39 32.62 19.13 48.24-.63-106.76-10.91-194.73-24.49-215.35V33.48h-12.28zm-26.34 147.77c-9.52 2.15-18.7 5.19-27.46 9.08 8.9 16.12 9.76 32.64 1.71 37.29-8 4.62-21.85-4.23-31.36-19.82-11.58 8.79-21.88 19.32-30.56 31.09 14.73 9.62 22.89 22.92 18.32 30.66-4.54 7.7-20.03 7.14-35.47-.96-5.78 13.25-9.75 27.51-11.65 42.42 9.68.18 18.67 2.38 26.18 6.04 17.78-.3 32.77-1.96 40.49-4.22 5.55-26.35 23.02-48.23 46.32-59.51.73-25.55 1.88-49.67 3.48-72.07zm64.96 0c1.59 22.4 2.75 46.52 3.47 72.07 23.29 11.28 40.77 33.16 46.32 59.51 7.72 2.26 22.71 3.92 40.49 4.22 7.51-3.66 16.5-5.85 26.18-6.04-1.9-14.91-5.86-29.17-11.65-42.42-15.44 8.1-30.93 8.66-35.47.96-4.57-7.74 3.6-21.05 18.32-30.66-8.68-11.77-18.98-22.3-30.56-31.09-9.51 15.59-23.36 24.44-31.36 19.82-8.05-4.65-7.19-21.16 1.71-37.29a147.49 147.49 0 0 0-27.45-9.08zm-32.48 8.6c-3.23 0-5.86 8.81-6.09 19.93h-.05v16.88c0 41.42-49.01 95.04-93.49 95.04-52 0-122.75-1.45-156.37 29.17v2.51c9.42 17.12 20.58 33.17 33.18 47.97C45.7 380.26 84.77 360.4 141.2 360c45.68 1.02 79.03 20.33 90.76 40.87.01.01-.01.04 0 .05 7.67 2.14 15.85 3.23 24.04 3.21 8.19.02 16.37-1.07 24.04-3.21.01-.01-.01-.04 0-.05 11.74-20.54 45.08-39.85 90.76-40.87 56.43.39 95.49 20.26 108.02 41.35 12.6-14.8 23.76-30.86 33.18-47.97v-2.51c-33.61-30.62-104.37-29.17-156.37-29.17-44.48 0-93.49-53.62-93.49-95.04v-16.88h-.05c-.23-11.12-2.86-19.93-6.09-19.93zm0 96.59c22.42 0 40.6 18.18 40.6 40.6s-18.18 40.65-40.6 40.65-40.6-18.23-40.6-40.65c0-22.42 18.18-40.6 40.6-40.6zm0 7.64c-18.19 0-32.96 14.77-32.96 32.96S237.81 360 256 360s32.96-14.77 32.96-32.96-14.77-32.96-32.96-32.96zm0 6.14c14.81 0 26.82 12.01 26.82 26.82s-12.01 26.82-26.82 26.82-26.82-12.01-26.82-26.82 12.01-26.82 26.82-26.82zm-114.8 66.67c-10.19.07-21.6.36-30.5 1.66.43 4.42 1.51 18.63 7.11 29.76 9.11-2.56 18.36-3.9 27.62-3.9 41.28.94 71.48 34.35 78.26 74.47l.11 4.7c10.4 1.91 21.19 2.94 32.21 2.94 11.03 0 21.81-1.02 32.21-2.94l.11-4.7c6.78-40.12 36.98-73.53 78.26-74.47 9.26 0 18.51 1.34 27.62 3.9 5.6-11.13 6.68-25.34 7.11-29.76-8.9-1.3-20.32-1.58-30.5-1.66-18.76.42-35.19 4.17-48.61 9.67-12.54 16.03-29.16 30.03-49.58 33.07-.09.02-.17.04-.27.05-.05.01-.11.04-.16.05-5.24 1.07-10.63 1.6-16.19 1.6-5.55 0-10.95-.53-16.19-1.6-.05-.01-.11-.04-.16-.05-.1-.02-.17-.04-.27-.05-20.42-3.03-37.03-17.04-49.58-33.07-13.42-5.49-29.86-9.25-48.61-9.67z\"],\n    \"get-pocket\": [448, 512, [], \"f265\", \"M407.6 64h-367C18.5 64 0 82.5 0 104.6v135.2C0 364.5 99.7 464 224.2 464c124 0 223.8-99.5 223.8-224.2V104.6c0-22.4-17.7-40.6-40.4-40.6zm-162 268.5c-12.4 11.8-31.4 11.1-42.4 0C89.5 223.6 88.3 227.4 88.3 209.3c0-16.9 13.8-30.7 30.7-30.7 17 0 16.1 3.8 105.2 89.3 90.6-86.9 88.6-89.3 105.5-89.3 16.9 0 30.7 13.8 30.7 30.7 0 17.8-2.9 15.7-114.8 123.2z\"],\n    \"gg\": [512, 512, [], \"f260\", \"M179.2 230.4l102.4 102.4-102.4 102.4L0 256 179.2 76.8l44.8 44.8-25.6 25.6-19.2-19.2-128 128 128 128 51.5-51.5-77.1-76.5 25.6-25.6zM332.8 76.8L230.4 179.2l102.4 102.4 25.6-25.6-77.1-76.5 51.5-51.5 128 128-128 128-19.2-19.2-25.6 25.6 44.8 44.8L512 256 332.8 76.8z\"],\n    \"gg-circle\": [512, 512, [], \"f261\", \"M257 8C120 8 9 119 9 256s111 248 248 248 248-111 248-248S394 8 257 8zm-49.5 374.8L81.8 257.1l125.7-125.7 35.2 35.4-24.2 24.2-11.1-11.1-77.2 77.2 77.2 77.2 26.6-26.6-53.1-52.9 24.4-24.4 77.2 77.2-75 75.2zm99-2.2l-35.2-35.2 24.1-24.4 11.1 11.1 77.2-77.2-77.2-77.2-26.5 26.5 53.1 52.9-24.4 24.4-77.2-77.2 75-75L432.2 255 306.5 380.6z\"],\n    \"git\": [512, 512, [], \"f1d3\", \"M216.29 158.39H137C97 147.9 6.51 150.63 6.51 233.18c0 30.09 15 51.23 35 61-25.1 23-37 33.85-37 49.21 0 11 4.47 21.14 17.89 26.81C8.13 383.61 0 393.35 0 411.65c0 32.11 28.05 50.82 101.63 50.82 70.75 0 111.79-26.42 111.79-73.18 0-58.66-45.16-56.5-151.63-63l13.43-21.55c27.27 7.58 118.7 10 118.7-67.89 0-18.7-7.73-31.71-15-41.07l37.41-2.84zm-63.42 241.9c0 32.06-104.89 32.1-104.89 2.43 0-8.14 5.27-15 10.57-21.54 77.71 5.3 94.32 3.37 94.32 19.11zm-50.81-134.58c-52.8 0-50.46-71.16 1.2-71.16 49.54 0 50.82 71.16-1.2 71.16zm133.3 100.51v-32.1c26.75-3.66 27.24-2 27.24-11V203.61c0-8.5-2.05-7.38-27.24-16.26l4.47-32.92H324v168.71c0 6.51.4 7.32 6.51 8.14l20.73 2.84v32.1zm52.45-244.31c-23.17 0-36.59-13.43-36.59-36.61s13.42-35.77 36.59-35.77c23.58 0 37 12.62 37 35.77s-13.42 36.61-37 36.61zM512 350.46c-17.49 8.53-43.1 16.26-66.28 16.26-48.38 0-66.67-19.5-66.67-65.46V194.75c0-5.42 1.05-4.06-31.71-4.06V154.5c35.78-4.07 50-22 54.47-66.27h38.63c0 65.83-1.34 61.81 3.26 61.81H501v40.65h-60.56v97.15c0 6.92-4.92 51.41 60.57 26.84z\"],\n    \"git-alt\": [448, 512, [], \"f841\", \"M439.55 236.05L244 40.45a28.87 28.87 0 0 0-40.81 0l-40.66 40.63 51.52 51.52c27.06-9.14 52.68 16.77 43.39 43.68l49.66 49.66c34.23-11.8 61.18 31 35.47 56.69-26.49 26.49-70.21-2.87-56-37.34L240.22 199v121.85c25.3 12.54 22.26 41.85 9.08 55a34.34 34.34 0 0 1-48.55 0c-17.57-17.6-11.07-46.91 11.25-56v-123c-20.8-8.51-24.6-30.74-18.64-45L142.57 101 8.45 235.14a28.86 28.86 0 0 0 0 40.81l195.61 195.6a28.86 28.86 0 0 0 40.8 0l194.69-194.69a28.86 28.86 0 0 0 0-40.81z\"],\n    \"git-square\": [448, 512, [], \"f1d2\", \"M100.59 334.24c48.57 3.31 58.95 2.11 58.95 11.94 0 20-65.55 20.06-65.55 1.52.01-5.09 3.29-9.4 6.6-13.46zm27.95-116.64c-32.29 0-33.75 44.47-.75 44.47 32.51 0 31.71-44.47.75-44.47zM448 80v352a48 48 0 0 1-48 48H48a48 48 0 0 1-48-48V80a48 48 0 0 1 48-48h352a48 48 0 0 1 48 48zm-227 69.31c0 14.49 8.38 22.88 22.86 22.88 14.74 0 23.13-8.39 23.13-22.88S258.62 127 243.88 127c-14.48 0-22.88 7.84-22.88 22.31zM199.18 195h-49.55c-25-6.55-81.56-4.85-81.56 46.75 0 18.8 9.4 32 21.85 38.11C74.23 294.23 66.8 301 66.8 310.6c0 6.87 2.79 13.22 11.18 16.76-8.9 8.4-14 14.48-14 25.92C64 373.35 81.53 385 127.52 385c44.22 0 69.87-16.51 69.87-45.73 0-36.67-28.23-35.32-94.77-39.38l8.38-13.43c17 4.74 74.19 6.23 74.19-42.43 0-11.69-4.83-19.82-9.4-25.67l23.38-1.78zm84.34 109.84l-13-1.78c-3.82-.51-4.07-1-4.07-5.09V192.52h-52.6l-2.79 20.57c15.75 5.55 17 4.86 17 10.17V298c0 5.62-.31 4.58-17 6.87v20.06h72.42zM384 315l-6.87-22.37c-40.93 15.37-37.85-12.41-37.85-16.73v-60.72h37.85v-25.41h-35.82c-2.87 0-2 2.52-2-38.63h-24.18c-2.79 27.7-11.68 38.88-34 41.42v22.62c20.47 0 19.82-.85 19.82 2.54v66.57c0 28.72 11.43 40.91 41.67 40.91 14.45 0 30.45-4.83 41.38-10.2z\"],\n    \"github\": [496, 512, [], \"f09b\", \"M165.9 397.4c0 2-2.3 3.6-5.2 3.6-3.3.3-5.6-1.3-5.6-3.6 0-2 2.3-3.6 5.2-3.6 3-.3 5.6 1.3 5.6 3.6zm-31.1-4.5c-.7 2 1.3 4.3 4.3 4.9 2.6 1 5.6 0 6.2-2s-1.3-4.3-4.3-5.2c-2.6-.7-5.5.3-6.2 2.3zm44.2-1.7c-2.9.7-4.9 2.6-4.6 4.9.3 2 2.9 3.3 5.9 2.6 2.9-.7 4.9-2.6 4.6-4.6-.3-1.9-3-3.2-5.9-2.9zM244.8 8C106.1 8 0 113.3 0 252c0 110.9 69.8 205.8 169.5 239.2 12.8 2.3 17.3-5.6 17.3-12.1 0-6.2-.3-40.4-.3-61.4 0 0-70 15-84.7-29.8 0 0-11.4-29.1-27.8-36.6 0 0-22.9-15.7 1.6-15.4 0 0 24.9 2 38.6 25.8 21.9 38.6 58.6 27.5 72.9 20.9 2.3-16 8.8-27.1 16-33.7-55.9-6.2-112.3-14.3-112.3-110.5 0-27.5 7.6-41.3 23.6-58.9-2.6-6.5-11.1-33.3 2.6-67.9 20.9-6.5 69 27 69 27 20-5.6 41.5-8.5 62.8-8.5s42.8 2.9 62.8 8.5c0 0 48.1-33.6 69-27 13.7 34.7 5.2 61.4 2.6 67.9 16 17.7 25.8 31.5 25.8 58.9 0 96.5-58.9 104.2-114.8 110.5 9.2 7.9 17 22.9 17 46.4 0 33.7-.3 75.4-.3 83.6 0 6.5 4.6 14.4 17.3 12.1C428.2 457.8 496 362.9 496 252 496 113.3 383.5 8 244.8 8zM97.2 352.9c-1.3 1-1 3.3.7 5.2 1.6 1.6 3.9 2.3 5.2 1 1.3-1 1-3.3-.7-5.2-1.6-1.6-3.9-2.3-5.2-1zm-10.8-8.1c-.7 1.3.3 2.9 2.3 3.9 1.6 1 3.6.7 4.3-.7.7-1.3-.3-2.9-2.3-3.9-2-.6-3.6-.3-4.3.7zm32.4 35.6c-1.6 1.3-1 4.3 1.3 6.2 2.3 2.3 5.2 2.6 6.5 1 1.3-1.3.7-4.3-1.3-6.2-2.2-2.3-5.2-2.6-6.5-1zm-11.4-14.7c-1.6 1-1.6 3.6 0 5.9 1.6 2.3 4.3 3.3 5.6 2.3 1.6-1.3 1.6-3.9 0-6.2-1.4-2.3-4-3.3-5.6-2z\"],\n    \"github-alt\": [480, 512, [], \"f113\", \"M186.1 328.7c0 20.9-10.9 55.1-36.7 55.1s-36.7-34.2-36.7-55.1 10.9-55.1 36.7-55.1 36.7 34.2 36.7 55.1zM480 278.2c0 31.9-3.2 65.7-17.5 95-37.9 76.6-142.1 74.8-216.7 74.8-75.8 0-186.2 2.7-225.6-74.8-14.6-29-20.2-63.1-20.2-95 0-41.9 13.9-81.5 41.5-113.6-5.2-15.8-7.7-32.4-7.7-48.8 0-21.5 4.9-32.3 14.6-51.8 45.3 0 74.3 9 108.8 36 29-6.9 58.8-10 88.7-10 27 0 54.2 2.9 80.4 9.2 34-26.7 63-35.2 107.8-35.2 9.8 19.5 14.6 30.3 14.6 51.8 0 16.4-2.6 32.7-7.7 48.2 27.5 32.4 39 72.3 39 114.2zm-64.3 50.5c0-43.9-26.7-82.6-73.5-82.6-18.9 0-37 3.4-56 6-14.9 2.3-29.8 3.2-45.1 3.2-15.2 0-30.1-.9-45.1-3.2-18.7-2.6-37-6-56-6-46.8 0-73.5 38.7-73.5 82.6 0 87.8 80.4 101.3 150.4 101.3h48.2c70.3 0 150.6-13.4 150.6-101.3zm-82.6-55.1c-25.8 0-36.7 34.2-36.7 55.1s10.9 55.1 36.7 55.1 36.7-34.2 36.7-55.1-10.9-55.1-36.7-55.1z\"],\n    \"github-square\": [448, 512, [], \"f092\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM277.3 415.7c-8.4 1.5-11.5-3.7-11.5-8 0-5.4.2-33 .2-55.3 0-15.6-5.2-25.5-11.3-30.7 37-4.1 76-9.2 76-73.1 0-18.2-6.5-27.3-17.1-39 1.7-4.3 7.4-22-1.7-45-13.9-4.3-45.7 17.9-45.7 17.9-13.2-3.7-27.5-5.6-41.6-5.6-14.1 0-28.4 1.9-41.6 5.6 0 0-31.8-22.2-45.7-17.9-9.1 22.9-3.5 40.6-1.7 45-10.6 11.7-15.6 20.8-15.6 39 0 63.6 37.3 69 74.3 73.1-4.8 4.3-9.1 11.7-10.6 22.3-9.5 4.3-33.8 11.7-48.3-13.9-9.1-15.8-25.5-17.1-25.5-17.1-16.2-.2-1.1 10.2-1.1 10.2 10.8 5 18.4 24.2 18.4 24.2 9.7 29.7 56.1 19.7 56.1 19.7 0 13.9.2 36.5.2 40.6 0 4.3-3 9.5-11.5 8-66-22.1-112.2-84.9-112.2-158.3 0-91.8 70.2-161.5 162-161.5S388 165.6 388 257.4c.1 73.4-44.7 136.3-110.7 158.3zm-98.1-61.1c-1.9.4-3.7-.4-3.9-1.7-.2-1.5 1.1-2.8 3-3.2 1.9-.2 3.7.6 3.9 1.9.3 1.3-1 2.6-3 3zm-9.5-.9c0 1.3-1.5 2.4-3.5 2.4-2.2.2-3.7-.9-3.7-2.4 0-1.3 1.5-2.4 3.5-2.4 1.9-.2 3.7.9 3.7 2.4zm-13.7-1.1c-.4 1.3-2.4 1.9-4.1 1.3-1.9-.4-3.2-1.9-2.8-3.2.4-1.3 2.4-1.9 4.1-1.5 2 .6 3.3 2.1 2.8 3.4zm-12.3-5.4c-.9 1.1-2.8.9-4.3-.6-1.5-1.3-1.9-3.2-.9-4.1.9-1.1 2.8-.9 4.3.6 1.3 1.3 1.8 3.3.9 4.1zm-9.1-9.1c-.9.6-2.6 0-3.7-1.5s-1.1-3.2 0-3.9c1.1-.9 2.8-.2 3.7 1.3 1.1 1.5 1.1 3.3 0 4.1zm-6.5-9.7c-.9.9-2.4.4-3.5-.6-1.1-1.3-1.3-2.8-.4-3.5.9-.9 2.4-.4 3.5.6 1.1 1.3 1.3 2.8.4 3.5zm-6.7-7.4c-.4.9-1.7 1.1-2.8.4-1.3-.6-1.9-1.7-1.5-2.6.4-.6 1.5-.9 2.8-.4 1.3.7 1.9 1.8 1.5 2.6z\"],\n    \"gitkraken\": [592, 512, [], \"f3a6\", \"M565.7 118.1c-2.3-6.1-9.3-9.2-15.3-6.6-5.7 2.4-8.5 8.9-6.3 14.6 10.9 29 16.9 60.5 16.9 93.3 0 134.6-100.3 245.7-230.2 262.7V358.4c7.9-1.5 15.5-3.6 23-6.2v104c106.7-25.9 185.9-122.1 185.9-236.8 0-91.8-50.8-171.8-125.8-213.3-5.7-3.2-13-.9-15.9 5-2.7 5.5-.6 12.2 4.7 15.1 67.9 37.6 113.9 110 113.9 193.2 0 93.3-57.9 173.1-139.8 205.4v-92.2c14.2-4.5 24.9-17.7 24.9-33.5 0-13.1-6.8-24.4-17.3-30.5 8.3-79.5 44.5-58.6 44.5-83.9V170c0-38-87.9-161.8-129-164.7-2.5-.2-5-.2-7.6 0C251.1 8.3 163.2 132 163.2 170v14.8c0 25.3 36.3 4.3 44.5 83.9-10.6 6.1-17.3 17.4-17.3 30.5 0 15.8 10.6 29 24.8 33.5v92.2c-81.9-32.2-139.8-112-139.8-205.4 0-83.1 46-155.5 113.9-193.2 5.4-3 7.4-9.6 4.7-15.1-2.9-5.9-10.1-8.2-15.9-5-75 41.5-125.8 121.5-125.8 213.3 0 114.7 79.2 210.8 185.9 236.8v-104c7.6 2.5 15.1 4.6 23 6.2v123.7C131.4 465.2 31 354.1 31 219.5c0-32.8 6-64.3 16.9-93.3 2.2-5.8-.6-12.2-6.3-14.6-6-2.6-13 .4-15.3 6.6C14.5 149.7 8 183.8 8 219.5c0 155.1 122.6 281.6 276.3 287.8V361.4c6.8.4 15 .5 23.4 0v145.8C461.4 501.1 584 374.6 584 219.5c0-35.7-6.5-69.8-18.3-101.4zM365.9 275.5c13 0 23.7 10.5 23.7 23.7 0 13.1-10.6 23.7-23.7 23.7-13 0-23.7-10.5-23.7-23.7 0-13.1 10.6-23.7 23.7-23.7zm-139.8 47.3c-13.2 0-23.7-10.7-23.7-23.7s10.5-23.7 23.7-23.7c13.1 0 23.7 10.6 23.7 23.7 0 13-10.5 23.7-23.7 23.7z\"],\n    \"gitlab\": [512, 512, [], \"f296\", \"M105.2 24.9c-3.1-8.9-15.7-8.9-18.9 0L29.8 199.7h132c-.1 0-56.6-174.8-56.6-174.8zM.9 287.7c-2.6 8 .3 16.9 7.1 22l247.9 184-226.2-294zm160.8-88l94.3 294 94.3-294zm349.4 88l-28.8-88-226.3 294 247.9-184c6.9-5.1 9.7-14 7.2-22zM425.7 24.9c-3.1-8.9-15.7-8.9-18.9 0l-56.6 174.8h132z\"],\n    \"gitter\": [384, 512, [], \"f426\", \"M66.4 322.5H16V0h50.4v322.5zM166.9 76.1h-50.4V512h50.4V76.1zm100.6 0h-50.4V512h50.4V76.1zM368 76h-50.4v247H368V76z\"],\n    \"glide\": [448, 512, [], \"f2a5\", \"M252.8 148.6c0 8.8-1.6 17.7-3.4 26.4-5.8 27.8-11.6 55.8-17.3 83.6-1.4 6.3-8.3 4.9-13.7 4.9-23.8 0-30.5-26-30.5-45.5 0-29.3 11.2-68.1 38.5-83.1 4.3-2.5 9.2-4.2 14.1-4.2 11.4 0 12.3 8.3 12.3 17.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 187c0-5.1-20.8-37.7-25.5-39.5-2.2-.9-7.2-2.3-9.6-2.3-23.1 0-38.7 10.5-58.2 21.5l-.5-.5c4.3-29.4 14.6-57.2 14.6-87.4 0-44.6-23.8-62.7-67.5-62.7-71.7 0-108 70.8-108 123.5 0 54.7 32 85 86.3 85 7.5 0 6.9-.6 6.9 2.3-10.5 80.3-56.5 82.9-56.5 58.9 0-24.4 28-36.5 28.3-38-.2-7.6-29.3-17.2-36.7-17.2-21.1 0-32.7 33-32.7 50.6 0 32.3 20.4 54.7 53.3 54.7 48.2 0 83.4-49.7 94.3-91.7 9.4-37.7 7-39.4 12.3-42.1 20-10.1 35.8-16.8 58.4-16.8 11.1 0 19 2.3 36.7 5.2 1.8.1 4.1-1.7 4.1-3.5z\"],\n    \"glide-g\": [448, 512, [], \"f2a6\", \"M407.1 211.2c-3.5-1.4-11.6-3.8-15.4-3.8-37.1 0-62.2 16.8-93.5 34.5l-.9-.9c7-47.3 23.5-91.9 23.5-140.4C320.8 29.1 282.6 0 212.4 0 97.3 0 39 113.7 39 198.4 39 286.3 90.3 335 177.6 335c12 0 11-1 11 3.8-16.9 128.9-90.8 133.1-90.8 94.6 0-39.2 45-58.6 45.5-61-.3-12.2-47-27.6-58.9-27.6-33.9.1-52.4 51.2-52.4 79.3C32 476 64.8 512 117.5 512c77.4 0 134-77.8 151.4-145.4 15.1-60.5 11.2-63.3 19.7-67.6 32.2-16.2 57.5-27 93.8-27 17.8 0 30.5 3.7 58.9 8.4 2.9 0 6.7-2.9 6.7-5.8 0-8-33.4-60.5-40.9-63.4zm-175.3-84.4c-9.3 44.7-18.6 89.6-27.8 134.3-2.3 10.2-13.3 7.8-22 7.8-38.3 0-49-41.8-49-73.1 0-47 18-109.3 61.8-133.4 7-4.1 14.8-6.7 22.6-6.7 18.6 0 20 13.3 20 28.7-.1 14.3-2.7 28.5-5.6 42.4z\"],\n    \"gofore\": [400, 512, [], \"f3a7\", \"M324 319.8h-13.2v34.7c-24.5 23.1-56.3 35.8-89.9 35.8-73.2 0-132.4-60.2-132.4-134.4 0-74.1 59.2-134.4 132.4-134.4 35.3 0 68.6 14 93.6 39.4l62.3-63.3C335 55.3 279.7 32 220.7 32 98 32 0 132.6 0 256c0 122.5 97 224 220.7 224 63.2 0 124.5-26.2 171-82.5-2-27.6-13.4-77.7-67.7-77.7zm-12.1-112.5H205.6v89H324c33.5 0 60.5 15.1 76 41.8v-30.6c0-65.2-40.4-100.2-88.1-100.2z\"],\n    \"goodreads\": [448, 512, [], \"f3a8\", \"M299.9 191.2c5.1 37.3-4.7 79-35.9 100.7-22.3 15.5-52.8 14.1-70.8 5.7-37.1-17.3-49.5-58.6-46.8-97.2 4.3-60.9 40.9-87.9 75.3-87.5 46.9-.2 71.8 31.8 78.2 78.3zM448 88v336c0 30.9-25.1 56-56 56H56c-30.9 0-56-25.1-56-56V88c0-30.9 25.1-56 56-56h336c30.9 0 56 25.1 56 56zM330 313.2s-.1-34-.1-217.3h-29v40.3c-.8.3-1.2-.5-1.6-1.2-9.6-20.7-35.9-46.3-76-46-51.9.4-87.2 31.2-100.6 77.8-4.3 14.9-5.8 30.1-5.5 45.6 1.7 77.9 45.1 117.8 112.4 115.2 28.9-1.1 54.5-17 69-45.2.5-1 1.1-1.9 1.7-2.9.2.1.4.1.6.2.3 3.8.2 30.7.1 34.5-.2 14.8-2 29.5-7.2 43.5-7.8 21-22.3 34.7-44.5 39.5-17.8 3.9-35.6 3.8-53.2-1.2-21.5-6.1-36.5-19-41.1-41.8-.3-1.6-1.3-1.3-2.3-1.3h-26.8c.8 10.6 3.2 20.3 8.5 29.2 24.2 40.5 82.7 48.5 128.2 37.4 49.9-12.3 67.3-54.9 67.4-106.3z\"],\n    \"goodreads-g\": [384, 512, [], \"f3a9\", \"M42.6 403.3h2.8c12.7 0 25.5 0 38.2.1 1.6 0 3.1-.4 3.6 2.1 7.1 34.9 30 54.6 62.9 63.9 26.9 7.6 54.1 7.8 81.3 1.8 33.8-7.4 56-28.3 68-60.4 8-21.5 10.7-43.8 11-66.5.1-5.8.3-47-.2-52.8l-.9-.3c-.8 1.5-1.7 2.9-2.5 4.4-22.1 43.1-61.3 67.4-105.4 69.1-103 4-169.4-57-172-176.2-.5-23.7 1.8-46.9 8.3-69.7C58.3 47.7 112.3.6 191.6 0c61.3-.4 101.5 38.7 116.2 70.3.5 1.1 1.3 2.3 2.4 1.9V10.6h44.3c0 280.3.1 332.2.1 332.2-.1 78.5-26.7 143.7-103 162.2-69.5 16.9-159 4.8-196-57.2-8-13.5-11.8-28.3-13-44.5zM188.9 36.5c-52.5-.5-108.5 40.7-115 133.8-4.1 59 14.8 122.2 71.5 148.6 27.6 12.9 74.3 15 108.3-8.7 47.6-33.2 62.7-97 54.8-154-9.7-71.1-47.8-120-119.6-119.7z\"],\n    \"google\": [488, 512, [], \"f1a0\", \"M488 261.8C488 403.3 391.1 504 248 504 110.8 504 0 393.2 0 256S110.8 8 248 8c66.8 0 123 24.5 166.3 64.9l-67.5 64.9C258.5 52.6 94.3 116.6 94.3 256c0 86.5 69.1 156.6 153.7 156.6 98.2 0 135-70.4 140.8-106.9H248v-85.3h236.1c2.3 12.7 3.9 24.9 3.9 41.4z\"],\n    \"google-drive\": [512, 512, [], \"f3aa\", \"M339 314.9L175.4 32h161.2l163.6 282.9H339zm-137.5 23.6L120.9 480h310.5L512 338.5H201.5zM154.1 67.4L0 338.5 80.6 480 237 208.8 154.1 67.4z\"],\n    \"google-play\": [512, 512, [], \"f3ab\", \"M325.3 234.3L104.6 13l280.8 161.2-60.1 60.1zM47 0C34 6.8 25.3 19.2 25.3 35.3v441.3c0 16.1 8.7 28.5 21.7 35.3l256.6-256L47 0zm425.2 225.6l-58.9-34.1-65.7 64.5 65.7 64.5 60.1-34.1c18-14.3 18-46.5-1.2-60.8zM104.6 499l280.8-161.2-60.1-60.1L104.6 499z\"],\n    \"google-plus\": [496, 512, [], \"f2b3\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm-70.7 372c-68.8 0-124-55.5-124-124s55.2-124 124-124c31.3 0 60.1 11 83 32.3l-33.6 32.6c-13.2-12.9-31.3-19.1-49.4-19.1-42.9 0-77.2 35.5-77.2 78.1s34.2 78.1 77.2 78.1c32.6 0 64.9-19.1 70.1-53.3h-70.1v-42.6h116.9c1.3 6.8 1.9 13.6 1.9 20.7 0 70.8-47.5 121.2-118.8 121.2zm230.2-106.2v35.5H372v-35.5h-35.5v-35.5H372v-35.5h35.5v35.5h35.2v35.5h-35.2z\"],\n    \"google-plus-g\": [640, 512, [], \"f0d5\", \"M386.061 228.496c1.834 9.692 3.143 19.384 3.143 31.956C389.204 370.205 315.599 448 204.8 448c-106.084 0-192-85.915-192-192s85.916-192 192-192c51.864 0 95.083 18.859 128.611 50.292l-52.126 50.03c-14.145-13.621-39.028-29.599-76.485-29.599-65.484 0-118.92 54.221-118.92 121.277 0 67.056 53.436 121.277 118.92 121.277 75.961 0 104.513-54.745 108.965-82.773H204.8v-66.009h181.261zm185.406 6.437V179.2h-56.001v55.733h-55.733v56.001h55.733v55.733h56.001v-55.733H627.2v-56.001h-55.733z\"],\n    \"google-plus-square\": [448, 512, [], \"f0d4\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM164 356c-55.3 0-100-44.7-100-100s44.7-100 100-100c27 0 49.5 9.8 67 26.2l-27.1 26.1c-7.4-7.1-20.3-15.4-39.8-15.4-34.1 0-61.9 28.2-61.9 63.2 0 34.9 27.8 63.2 61.9 63.2 39.6 0 54.4-28.5 56.8-43.1H164v-34.4h94.4c1 5 1.6 10.1 1.6 16.6 0 57.1-38.3 97.6-96 97.6zm220-81.8h-29v29h-29.2v-29h-29V245h29v-29H355v29h29v29.2z\"],\n    \"google-wallet\": [448, 512, [], \"f1ee\", \"M156.8 126.8c37.6 60.6 64.2 113.1 84.3 162.5-8.3 33.8-18.8 66.5-31.3 98.3-13.2-52.3-26.5-101.3-56-148.5 6.5-36.4 2.3-73.6 3-112.3zM109.3 200H16.1c-6.5 0-10.5 7.5-6.5 12.7C51.8 267 81.3 330.5 101.3 400h103.5c-16.2-69.7-38.7-133.7-82.5-193.5-3-4-8-6.5-13-6.5zm47.8-88c68.5 108 130 234.5 138.2 368H409c-12-138-68.4-265-143.2-368H157.1zm251.8-68.5c-1.8-6.8-8.2-11.5-15.2-11.5h-88.3c-5.3 0-9 5-7.8 10.3 13.2 46.5 22.3 95.5 26.5 146 48.2 86.2 79.7 178.3 90.6 270.8 15.8-60.5 25.3-133.5 25.3-203 0-73.6-12.1-145.1-31.1-212.6z\"],\n    \"gratipay\": [496, 512, [], \"f184\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm114.6 226.4l-113 152.7-112.7-152.7c-8.7-11.9-19.1-50.4 13.6-72 28.1-18.1 54.6-4.2 68.5 11.9 15.9 17.9 46.6 16.9 61.7 0 13.9-16.1 40.4-30 68.1-11.9 32.9 21.6 22.6 60 13.8 72z\"],\n    \"grav\": [512, 512, [], \"f2d6\", \"M301.1 212c4.4 4.4 4.4 11.9 0 16.3l-9.7 9.7c-4.4 4.7-11.9 4.7-16.6 0l-10.5-10.5c-4.4-4.7-4.4-11.9 0-16.6l9.7-9.7c4.4-4.4 11.9-4.4 16.6 0l10.5 10.8zm-30.2-19.7c3-3 3-7.8 0-10.5-2.8-3-7.5-3-10.5 0-2.8 2.8-2.8 7.5 0 10.5 3.1 2.8 7.8 2.8 10.5 0zm-26 5.3c-3 2.8-3 7.5 0 10.2 2.8 3 7.5 3 10.5 0 2.8-2.8 2.8-7.5 0-10.2-3-3-7.7-3-10.5 0zm72.5-13.3c-19.9-14.4-33.8-43.2-11.9-68.1 21.6-24.9 40.7-17.2 59.8.8 11.9 11.3 29.3 24.9 17.2 48.2-12.5 23.5-45.1 33.2-65.1 19.1zm47.7-44.5c-8.9-10-23.3 6.9-15.5 16.1 7.4 9 32.1 2.4 15.5-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-66.2 42.6c2.5-16.1-20.2-16.6-25.2-25.7-13.6-24.1-27.7-36.8-54.5-30.4 11.6-8 23.5-6.1 23.5-6.1.3-6.4 0-13-9.4-24.9 3.9-12.5.3-22.4.3-22.4 15.5-8.6 26.8-24.4 29.1-43.2 3.6-31-18.8-59.2-49.8-62.8-22.1-2.5-43.7 7.7-54.3 25.7-23.2 40.1 1.4 70.9 22.4 81.4-14.4-1.4-34.3-11.9-40.1-34.3-6.6-25.7 2.8-49.8 8.9-61.4 0 0-4.4-5.8-8-8.9 0 0-13.8 0-24.6 5.3 11.9-15.2 25.2-14.4 25.2-14.4 0-6.4-.6-14.9-3.6-21.6-5.4-11-23.8-12.9-31.7 2.8.1-.2.3-.4.4-.5-5 11.9-1.1 55.9 16.9 87.2-2.5 1.4-9.1 6.1-13 10-21.6 9.7-56.2 60.3-56.2 60.3-28.2 10.8-77.2 50.9-70.6 79.7.3 3 1.4 5.5 3 7.5-2.8 2.2-5.5 5-8.3 8.3-11.9 13.8-5.3 35.2 17.7 24.4 15.8-7.2 29.6-20.2 36.3-30.4 0 0-5.5-5-16.3-4.4 27.7-6.6 34.3-9.4 46.2-9.1 8 3.9 8-34.3 8-34.3 0-14.7-2.2-31-11.1-41.5 12.5 12.2 29.1 32.7 28 60.6-.8 18.3-15.2 23-15.2 23-9.1 16.6-43.2 65.9-30.4 106 0 0-9.7-14.9-10.2-22.1-17.4 19.4-46.5 52.3-24.6 64.5 26.6 14.7 108.8-88.6 126.2-142.3 34.6-20.8 55.4-47.3 63.9-65 22 43.5 95.3 94.5 101.1 59z\"],\n    \"gripfire\": [384, 512, [], \"f3ac\", \"M112.5 301.4c0-73.8 105.1-122.5 105.1-203 0-47.1-34-88-39.1-90.4.4 3.3.6 6.7.6 10C179.1 110.1 32 171.9 32 286.6c0 49.8 32.2 79.2 66.5 108.3 65.1 46.7 78.1 71.4 78.1 86.6 0 10.1-4.8 17-4.8 22.3 13.1-16.7 17.4-31.9 17.5-46.4 0-29.6-21.7-56.3-44.2-86.5-16-22.3-32.6-42.6-32.6-69.5zm205.3-39c-12.1-66.8-78-124.4-94.7-130.9l4 7.2c2.4 5.1 3.4 10.9 3.4 17.1 0 44.7-54.2 111.2-56.6 116.7-2.2 5.1-3.2 10.5-3.2 15.8 0 20.1 15.2 42.1 17.9 42.1 2.4 0 56.6-55.4 58.1-87.7 6.4 11.7 9.1 22.6 9.1 33.4 0 41.2-41.8 96.9-41.8 96.9 0 11.6 31.9 53.2 35.5 53.2 1 0 2.2-1.4 3.2-2.4 37.9-39.3 67.3-85 67.3-136.8 0-8-.7-16.2-2.2-24.6z\"],\n    \"grunt\": [384, 512, [], \"f3ad\", \"M61.3 189.3c-1.1 10 5.2 19.1 5.2 19.1.7-7.5 2.2-12.8 4-16.6.4 10.3 3.2 23.5 12.8 34.1 6.9 7.6 35.6 23.3 54.9 6.1 1 2.4 2.1 5.3 3 8.5 2.9 10.3-2.7 25.3-2.7 25.3s15.1-17.1 13.9-32.5c10.8-.5 21.4-8.4 21.1-19.5 0 0-18.9 10.4-35.5-8.8-9.7-11.2-40.9-42-83.1-31.8 4.3 1 8.9 2.4 13.5 4.1h-.1c-4.2 2-6.5 7.1-7 12zm28.3-1.8c19.5 11 37.4 25.7 44.9 37-5.7 3.3-21.7 10.4-38-1.7-10.3-7.6-9.8-26.2-6.9-35.3zm142.1 45.8c-1.2 15.5 13.9 32.5 13.9 32.5s-5.6-15-2.7-25.3c.9-3.2 2-6 3-8.5 19.3 17.3 48 1.5 54.8-6.1 9.6-10.6 12.3-23.8 12.8-34.1 1.8 3.8 3.4 9.1 4 16.6 0 0 6.4-9.1 5.2-19.1-.6-5-2.9-10-7-11.8h-.1c4.6-1.8 9.2-3.2 13.5-4.1-42.3-10.2-73.4 20.6-83.1 31.8-16.7 19.2-35.5 8.8-35.5 8.8-.2 10.9 10.4 18.9 21.2 19.3zm62.7-45.8c3 9.1 3.4 27.7-7 35.4-16.3 12.1-32.2 5-37.9 1.6 7.5-11.4 25.4-26 44.9-37zM160 418.5h-29.4c-5.5 0-8.2 1.6-9.5 2.9-1.9 2-2.2 4.7-.9 8.1 3.5 9.1 11.4 16.5 13.7 18.6 3.1 2.7 7.5 4.3 11.8 4.3 4.4 0 8.3-1.7 11-4.6 7.5-8.2 11.9-17.1 13-19.8.6-1.5 1.3-4.5-.9-6.8-1.8-1.8-4.7-2.7-8.8-2.7zm189.2-101.2c-2.4 17.9-13 33.8-24.6 43.7-3.1-22.7-3.7-55.5-3.7-62.4 0-14.7 9.5-24.5 12.2-26.1 2.5-1.5 5.4-3 8.3-4.6 18-9.6 40.4-21.6 40.4-43.7 0-16.2-9.3-23.2-15.4-27.8-.8-.6-1.5-1.1-2.2-1.7-2.1-1.7-3.7-3-4.3-4.4-4.4-9.8-3.6-34.2-1.7-37.6.6-.6 16.7-20.9 11.8-39.2-2-7.4-6.9-13.3-14.1-17-5.3-2.7-11.9-4.2-19.5-4.5-.1-2-.5-3.9-.9-5.9-.6-2.6-1.1-5.3-.9-8.1.4-4.7.8-9 2.2-11.3 8.4-13.3 28.8-17.6 29-17.6l12.3-2.4-8.1-9.5c-.1-.2-17.3-17.5-46.3-17.5-7.9 0-16 1.3-24.1 3.9-24.2 7.8-42.9 30.5-49.4 39.3-3.1-1-6.3-1.9-9.6-2.7-4.2-15.8 9-38.5 9-38.5s-13.6-3-33.7 15.2c-2.6-6.5-8.1-20.5-1.8-37.2C184.6 10.1 177.2 26 175 40.4c-7.6-5.4-6.7-23.1-7.2-27.6-7.5.9-29.2 21.9-28.2 48.3-2 .5-3.9 1.1-5.9 1.7-6.5-8.8-25.1-31.5-49.4-39.3-7.9-2.2-16-3.5-23.9-3.5-29 0-46.1 17.3-46.3 17.5L6 46.9l12.3 2.4c.2 0 20.6 4.3 29 17.6 1.4 2.2 1.8 6.6 2.2 11.3.2 2.8-.4 5.5-.9 8.1-.4 1.9-.8 3.9-.9 5.9-7.7.3-14.2 1.8-19.5 4.5-7.2 3.7-12.1 9.6-14.1 17-5 18.2 11.2 38.5 11.8 39.2 1.9 3.4 2.7 27.8-1.7 37.6-.6 1.4-2.2 2.7-4.3 4.4-.7.5-1.4 1.1-2.2 1.7-6.1 4.6-15.4 11.7-15.4 27.8 0 22.1 22.4 34.1 40.4 43.7 3 1.6 5.8 3.1 8.3 4.6 2.7 1.6 12.2 11.4 12.2 26.1 0 6.9-.6 39.7-3.7 62.4-11.6-9.9-22.2-25.9-24.6-43.8 0 0-29.2 22.6-20.6 70.8 5.2 29.5 23.2 46.1 47 54.7 8.8 19.1 29.4 45.7 67.3 49.6C143 504.3 163 512 192.2 512h.2c29.1 0 49.1-7.7 63.6-19.5 37.9-3.9 58.5-30.5 67.3-49.6 23.8-8.7 41.7-25.2 47-54.7 8.2-48.4-21.1-70.9-21.1-70.9zM305.7 37.7c5.6-1.8 11.6-2.7 17.7-2.7 11 0 19.9 3 24.7 5-3.1 1.4-6.4 3.2-9.7 5.3-2.4-.4-5.6-.8-9.2-.8-10.5 0-20.5 3.1-28.7 8.9-12.3 8.7-18 16.9-20.7 22.4-2.2-1.3-4.5-2.5-7.1-3.7-1.6-.8-3.1-1.5-4.7-2.2 6.1-9.1 19.9-26.5 37.7-32.2zm21 18.2c-.8 1-1.6 2.1-2.3 3.2-3.3 5.2-3.9 11.6-4.4 17.8-.5 6.4-1.1 12.5-4.4 17-4.2.8-8.1 1.7-11.5 2.7-2.3-3.1-5.6-7-10.5-11.2 1.4-4.8 5.5-16.1 13.5-22.5 5.6-4.3 12.2-6.7 19.6-7zM45.6 45.3c-3.3-2.2-6.6-4-9.7-5.3 4.8-2 13.7-5 24.7-5 6.1 0 12 .9 17.7 2.7 17.8 5.8 31.6 23.2 37.7 32.1-1.6.7-3.2 1.4-4.8 2.2-2.5 1.2-4.9 2.5-7.1 3.7-2.6-5.4-8.3-13.7-20.7-22.4-8.3-5.8-18.2-8.9-28.8-8.9-3.4.1-6.6.5-9 .9zm44.7 40.1c-4.9 4.2-8.3 8-10.5 11.2-3.4-.9-7.3-1.9-11.5-2.7C65 89.5 64.5 83.4 64 77c-.5-6.2-1.1-12.6-4.4-17.8-.7-1.1-1.5-2.2-2.3-3.2 7.4.3 14 2.6 19.5 7 8 6.3 12.1 17.6 13.5 22.4zM58.1 259.9c-2.7-1.6-5.6-3.1-8.4-4.6-14.9-8-30.2-16.3-30.2-30.5 0-11.1 4.3-14.6 8.9-18.2l.5-.4c.7-.6 1.4-1.2 2.2-1.8-.9 7.2-1.9 13.3-2.7 14.9 0 0 12.1-15 15.7-44.3 1.4-11.5-1.1-34.3-5.1-43 .2 4.9 0 9.8-.3 14.4-.4-.8-.8-1.6-1.3-2.2-3.2-4-11.8-17.5-9.4-26.6.9-3.5 3.1-6 6.7-7.8 3.8-1.9 8.8-2.9 15.1-2.9 12.3 0 25.9 3.7 32.9 6 25.1 8 55.4 30.9 64.1 37.7.2.2.4.3.4.3l5.6 3.9-3.5-5.8c-.2-.3-19.1-31.4-53.2-46.5 2-2.9 7.4-8.1 21.6-15.1 21.4-10.5 46.5-15.8 74.3-15.8 27.9 0 52.9 5.3 74.3 15.8 14.2 6.9 19.6 12.2 21.6 15.1-34 15.1-52.9 46.2-53.1 46.5l-3.5 5.8 5.6-3.9s.2-.1.4-.3c8.7-6.8 39-29.8 64.1-37.7 7-2.2 20.6-6 32.9-6 6.3 0 11.3 1 15.1 2.9 3.5 1.8 5.7 4.4 6.7 7.8 2.5 9.1-6.1 22.6-9.4 26.6-.5.6-.9 1.3-1.3 2.2-.3-4.6-.5-9.5-.3-14.4-4 8.8-6.5 31.5-5.1 43 3.6 29.3 15.7 44.3 15.7 44.3-.8-1.6-1.8-7.7-2.7-14.9.7.6 1.5 1.2 2.2 1.8l.5.4c4.6 3.7 8.9 7.1 8.9 18.2 0 14.2-15.4 22.5-30.2 30.5-2.9 1.5-5.7 3.1-8.4 4.6-8.7 5-18 16.7-19.1 34.2-.9 14.6.9 49.9 3.4 75.9-12.4 4.8-26.7 6.4-39.7 6.8-2-4.1-3.9-8.5-5.5-13.1-.7-2-19.6-51.1-26.4-62.2 5.5 39 17.5 73.7 23.5 89.6-3.5-.5-7.3-.7-11.7-.7h-117c-4.4 0-8.3.3-11.7.7 6-15.9 18.1-50.6 23.5-89.6-6.8 11.2-25.7 60.3-26.4 62.2-1.6 4.6-3.5 9-5.5 13.1-13-.4-27.2-2-39.7-6.8 2.5-26 4.3-61.2 3.4-75.9-.9-17.4-10.3-29.2-19-34.2zM34.8 404.6c-12.1-20-8.7-54.1-3.7-59.1 10.9 34.4 47.2 44.3 74.4 45.4-2.7 4.2-5.2 7.6-7 10l-1.4 1.4c-7.2 7.8-8.6 18.5-4.1 31.8-22.7-.1-46.3-9.8-58.2-29.5zm45.7 43.5c6 1.1 12.2 1.9 18.6 2.4 3.5 8 7.4 15.9 12.3 23.1-14.4-5.9-24.4-16-30.9-25.5zM192 498.2c-60.6-.1-78.3-45.8-84.9-64.7-3.7-10.5-3.4-18.2.9-23.1 2.9-3.3 9.5-7.2 24.6-7.2h118.8c15.1 0 21.8 3.9 24.6 7.2 4.2 4.8 4.5 12.6.9 23.1-6.6 18.8-24.3 64.6-84.9 64.7zm80.6-24.6c4.9-7.2 8.8-15.1 12.3-23.1 6.4-.5 12.6-1.3 18.6-2.4-6.5 9.5-16.5 19.6-30.9 25.5zm76.6-69c-12 19.7-35.6 29.3-58.1 29.7 4.5-13.3 3.1-24.1-4.1-31.8-.4-.5-.9-1-1.4-1.5-1.8-2.4-4.3-5.8-7-10 27.2-1.2 63.5-11 74.4-45.4 5 5 8.4 39.1-3.8 59zM191.9 187.7h.2c12.7-.1 27.2-17.8 27.2-17.8-9.9 6-18.8 8.1-27.3 8.3-8.5-.2-17.4-2.3-27.3-8.3 0 0 14.5 17.6 27.2 17.8zm61.7 230.7h-29.4c-4.2 0-7.2.9-8.9 2.7-2.2 2.3-1.5 5.2-.9 6.7 1 2.6 5.5 11.3 13 19.3 2.7 2.9 6.6 4.5 11 4.5s8.7-1.6 11.8-4.2c2.3-2 10.2-9.2 13.7-18.1 1.3-3.3 1-6-.9-7.9-1.3-1.3-4-2.9-9.4-3z\"],\n    \"gulp\": [256, 512, [], \"f3ae\", \"M209.8 391.1l-14.1 24.6-4.6 80.2c0 8.9-28.3 16.1-63.1 16.1s-63.1-7.2-63.1-16.1l-5.8-79.4-14.9-25.4c41.2 17.3 126 16.7 165.6 0zm-196-253.3l13.6 125.5c5.9-20 20.8-47 40-55.2 6.3-2.7 12.7-2.7 18.7.9 5.2 3 9.6 9.3 10.1 11.8 1.2 6.5-2 9.1-4.5 9.1-3 0-5.3-4.6-6.8-7.3-4.1-7.3-10.3-7.6-16.9-2.8-6.9 5-12.9 13.4-17.1 20.7-5.1 8.8-9.4 18.5-12 28.2-1.5 5.6-2.9 14.6-.6 19.9 1 2.2 2.5 3.6 4.9 3.6 5 0 12.3-6.6 15.8-10.1 4.5-4.5 10.3-11.5 12.5-16l5.2-15.5c2.6-6.8 9.9-5.6 9.9 0 0 10.2-3.7 13.6-10 34.7-5.8 19.5-7.6 25.8-7.6 25.8-.7 2.8-3.4 7.5-6.3 7.5-1.2 0-2.1-.4-2.6-1.2-1-1.4-.9-5.3-.8-6.3.2-3.2 6.3-22.2 7.3-25.2-2 2.2-4.1 4.4-6.4 6.6-5.4 5.1-14.1 11.8-21.5 11.8-3.4 0-5.6-.9-7.7-2.4l7.6 79.6c2 5 39.2 17.1 88.2 17.1 49.1 0 86.3-12.2 88.2-17.1l10.9-94.6c-5.7 5.2-12.3 11.6-19.6 14.8-5.4 2.3-17.4 3.8-17.4-5.7 0-5.2 9.1-14.8 14.4-21.5 1.4-1.7 4.7-5.9 4.7-8.1 0-2.9-6-2.2-11.7 2.5-3.2 2.7-6.2 6.3-8.7 9.7-4.3 6-6.6 11.2-8.5 15.5-6.2 14.2-4.1 8.6-9.1 22-5 13.3-4.2 11.8-5.2 14-.9 1.9-2.2 3.5-4 4.5-1.9 1-4.5.9-6.1-.3-.9-.6-1.3-1.9-1.3-3.7 0-.9.1-1.8.3-2.7 1.5-6.1 7.8-18.1 15-34.3 1.6-3.7 1-2.6.8-2.3-6.2 6-10.9 8.9-14.4 10.5-5.8 2.6-13 2.6-14.5-4.1-.1-.4-.1-.8-.2-1.2-11.8 9.2-24.3 11.7-20-8.1-4.6 8.2-12.6 14.9-22.4 14.9-4.1 0-7.1-1.4-8.6-5.1-2.3-5.5 1.3-14.9 4.6-23.8 1.7-4.5 4-9.9 7.1-16.2 1.6-3.4 4.2-5.4 7.6-4.5.6.2 1.1.4 1.6.7 2.6 1.8 1.6 4.5.3 7.2-3.8 7.5-7.1 13-9.3 20.8-.9 3.3-2 9 1.5 9 2.4 0 4.7-.8 6.9-2.4 4.6-3.4 8.3-8.5 11.1-13.5 2-3.6 4.4-8.3 5.6-12.3.5-1.7 1.1-3.3 1.8-4.8 1.1-2.5 2.6-5.1 5.2-5.1 1.3 0 2.4.5 3.2 1.5 1.7 2.2 1.3 4.5.4 6.9-2 5.6-4.7 10.6-6.9 16.7-1.3 3.5-2.7 8-2.7 11.7 0 3.4 3.7 2.6 6.8 1.2 2.4-1.1 4.8-2.8 6.8-4.5 1.2-4.9.9-3.8 26.4-68.2 1.3-3.3 3.7-4.7 6.1-4.7 1.2 0 2.2.4 3.2 1.1 1.7 1.3 1.7 4.1 1 6.2-.7 1.9-.6 1.3-4.5 10.5-5.2 12.1-8.6 20.8-13.2 31.9-1.9 4.6-7.7 18.9-8.7 22.3-.6 2.2-1.3 5.8 1 5.8 5.4 0 19.3-13.1 23.1-17 .2-.3.5-.4.9-.6.6-1.9 1.2-3.7 1.7-5.5 1.4-3.8 2.7-8.2 5.3-11.3.8-1 1.7-1.6 2.7-1.6 2.8 0 4.2 1.2 4.2 4 0 1.1-.7 5.1-1.1 6.2 1.4-1.5 2.9-3 4.5-4.5 15-13.9 25.7-6.8 25.7.2 0 7.4-8.9 17.7-13.8 23.4-1.6 1.9-4.9 5.4-5 6.4 0 1.3.9 1.8 2.2 1.8 2 0 6.4-3.5 8-4.7 5-3.9 11.8-9.9 16.6-14.1l14.8-136.8c-30.5 17.1-197.6 17.2-228.3.2zm229.7-8.5c0 21-231.2 21-231.2 0 0-8.8 51.8-15.9 115.6-15.9 9 0 17.8.1 26.3.4l12.6-48.7L228.1.6c1.4-1.4 5.8-.2 9.9 3.5s6.6 7.9 5.3 9.3l-.1.1L185.9 74l-10 40.7c39.9 2.6 67.6 8.1 67.6 14.6zm-69.4 4.6c0-.8-.9-1.5-2.5-2.1l-.2.8c0 1.3-5 2.4-11.1 2.4s-11.1-1.1-11.1-2.4c0-.1 0-.2.1-.3l.2-.7c-1.8.6-3 1.4-3 2.3 0 2.1 6.2 3.7 13.7 3.7 7.7.1 13.9-1.6 13.9-3.7z\"],\n    \"hacker-news\": [448, 512, [], \"f1d4\", \"M0 32v448h448V32H0zm21.2 197.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hacker-news-square\": [448, 512, [], \"f3af\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.2 229.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hackerrank\": [512, 512, [], \"f5f7\", \"M477.5 128C463 103.05 285.13 0 256.16 0S49.25 102.79 34.84 128s-14.49 230.8 0 256 192.38 128 221.32 128S463 409.08 477.49 384s14.51-231 .01-256zM316.13 414.22c-4 0-40.91-35.77-38-38.69.87-.87 6.26-1.48 17.55-1.83 0-26.23.59-68.59.94-86.32 0-2-.44-3.43-.44-5.85h-79.93c0 7.1-.46 36.2 1.37 72.88.23 4.54-1.58 6-5.74 5.94-10.13 0-20.27-.11-30.41-.08-4.1 0-5.87-1.53-5.74-6.11.92-33.44 3-84-.15-212.67v-3.17c-9.67-.35-16.38-1-17.26-1.84-2.92-2.92 34.54-38.69 38.49-38.69s41.17 35.78 38.27 38.69c-.87.87-7.9 1.49-16.77 1.84v3.16c-2.42 25.75-2 79.59-2.63 105.39h80.26c0-4.55.39-34.74-1.2-83.64-.1-3.39.95-5.17 4.21-5.2 11.07-.08 22.15-.13 33.23-.06 3.46 0 4.57 1.72 4.5 5.38C333 354.64 336 341.29 336 373.69c8.87.35 16.82 1 17.69 1.84 2.88 2.91-33.62 38.69-37.58 38.69z\"],\n    \"hips\": [640, 512, [], \"f452\", \"M251.6 157.6c0-1.9-.9-2.8-2.8-2.8h-40.9c-1.6 0-2.7 1.4-2.7 2.8v201.8c0 1.4 1.1 2.8 2.7 2.8h40.9c1.9 0 2.8-.9 2.8-2.8zM156.5 168c-16.1-11.8-36.3-17.9-60.3-18-18.1-.1-34.6 3.7-49.8 11.4V80.2c0-1.8-.9-2.7-2.8-2.7H2.7c-1.8 0-2.7.9-2.7 2.7v279.2c0 1.9.9 2.8 2.7 2.8h41c1.9 0 2.8-.9 2.8-2.8V223.3c0-.8-2.8-27 45.8-27 48.5 0 45.8 26.1 45.8 27v122.6c0 9 7.3 16.3 16.4 16.3h27.3c1.8 0 2.7-.9 2.7-2.8V223.3c0-23.4-9.3-41.8-28-55.3zm478.4 110.1c-6.8-15.7-18.4-27-34.9-34.1l-57.6-25.3c-8.6-3.6-9.2-11.2-2.6-16.1 7.4-5.5 44.3-13.9 84 6.8 1.7 1 4-.3 4-2.4v-44.7c0-1.3-.6-2.1-1.9-2.6-17.7-6.6-36.1-9.9-55.1-9.9-26.5 0-45.3 5.8-58.5 15.4-.5.4-28.4 20-22.7 53.7 3.4 19.6 15.8 34.2 37.2 43.6l53.6 23.5c11.6 5.1 15.2 13.3 12.2 21.2-3.7 9.1-13.2 13.6-36.5 13.6-24.3 0-44.7-8.9-58.4-19.1-2.1-1.4-4.4.2-4.4 2.3v34.4c0 10.4 4.9 17.3 14.6 20.7 15.6 5.5 31.6 8.2 48.2 8.2 12.7 0 25.8-1.2 36.3-4.3.7-.3 36-8.9 45.6-45.8 3.5-13.5 2.4-26.5-3.1-39.1zM376.2 149.8c-31.7 0-104.2 20.1-104.2 103.5v183.5c0 .8.6 2.7 2.7 2.7h40.9c1.9 0 2.8-.9 2.8-2.7V348c16.5 12.7 35.8 19.1 57.7 19.1 60.5 0 108.7-48.5 108.7-108.7.1-60.3-48.2-108.6-108.6-108.6zm0 170.9c-17.2 0-31.9-6.1-44-18.2-12.2-12.2-18.2-26.8-18.2-44 0-34.5 27.6-62.2 62.2-62.2 34.5 0 62.2 27.6 62.2 62.2.1 34.3-27.3 62.2-62.2 62.2zM228.3 72.5c-15.9 0-28.8 12.9-28.9 28.9 0 15.6 12.7 28.9 28.9 28.9s28.9-13.1 28.9-28.9c0-16.2-13-28.9-28.9-28.9z\"],\n    \"hire-a-helper\": [512, 512, [], \"f3b0\", \"M443.1 0H71.9C67.9 37.3 37.4 67.8 0 71.7v371.5c37.4 4.9 66 32.4 71.9 68.8h372.2c3-36.4 32.5-65.8 67.9-69.8V71.7c-36.4-5.9-65-35.3-68.9-71.7zm-37 404.9c-36.3 0-18.8-2-55.1-2-35.8 0-21 2-56.1 2-5.9 0-4.9-8.2 0-9.8 22.8-7.6 22.9-10.2 24.6-12.8 10.4-15.6 5.9-83 5.9-113 0-5.3-6.4-12.8-13.8-12.8H200.4c-7.4 0-13.8 7.5-13.8 12.8 0 30-4.5 97.4 5.9 113 1.7 2.5 1.8 5.2 24.6 12.8 4.9 1.6 6 9.8 0 9.8-35.1 0-20.3-2-56.1-2-36.3 0-18.8 2-55.1 2-7.9 0-5.8-10.8 0-10.8 10.2-3.4 13.5-3.5 21.7-13.8 7.7-12.9 7.9-44.4 7.9-127.8V151.3c0-22.2-12.2-28.3-28.6-32.4-8.8-2.2-4-11.8 1-11.8 36.5 0 20.6 2 57.1 2 32.7 0 16.5-2 49.2-2 3.3 0 8.5 8.3 1 10.8-4.9 1.6-27.6 3.7-27.6 39.3 0 45.6-.2 55.8 1 68.8 0 1.3 2.3 12.8 12.8 12.8h109.2c10.5 0 12.8-11.5 12.8-12.8 1.2-13 1-23.2 1-68.8 0-35.6-22.7-37.7-27.6-39.3-7.5-2.5-2.3-10.8 1-10.8 32.7 0 16.5 2 49.2 2 36.5 0 20.6-2 57.1-2 4.9 0 9.9 9.6 1 11.8-16.4 4.1-28.6 10.3-28.6 32.4v101.2c0 83.4.1 114.9 7.9 127.8 8.2 10.2 11.4 10.4 21.7 13.8 5.8 0 7.8 10.8 0 10.8z\"],\n    \"hooli\": [640, 512, [], \"f427\", \"M144.5 352l38.3.8c-13.2-4.6-26-10.2-38.3-16.8zm57.7-5.3v5.3l-19.4.8c36.5 12.5 69.9 14.2 94.7 7.2-19.9.2-45.8-2.6-75.3-13.3zm408.9-115.2c15.9 0 28.9-12.9 28.9-28.9s-12.9-24.5-28.9-24.5c-15.9 0-28.9 8.6-28.9 24.5s12.9 28.9 28.9 28.9zm-29 120.5H640V241.5h-57.9zm-73.7 0h57.9V156.7L508.4 184zm-31-119.4c-18.2-18.2-50.4-17.1-50.4-17.1s-32.3-1.1-50.4 17.1c-18.2 18.2-16.8 33.9-16.8 52.6s-1.4 34.3 16.8 52.5 50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.8-33.8 16.8-52.5-.1-18.8 1.3-34.5-16.8-52.6zm-39.8 71.9c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9zm-106.2-71.9c-18.2-18.2-50.4-17.1-50.4-17.1s-32.2-1.1-50.4 17.1c-1.9 1.9-3.7 3.9-5.3 6-38.2-29.6-72.5-46.5-102.1-61.1v-20.7l-22.5 10.6c-54.4-22.1-89-18.2-97.3.1 0 0-24.9 32.8 61.8 110.8V352h57.9v-28.6c-6.5-4.2-13-8.7-19.4-13.6-14.8-11.2-27.4-21.6-38.4-31.4v-31c13.1 14.7 30.5 31.4 53.4 50.3l4.5 3.6v-29.8c0-6.9 1.7-18.2 10.8-18.2s10.6 6.9 10.6 15V317c18 12.2 37.3 22.1 57.7 29.6v-93.9c0-18.7-13.4-37.4-40.6-37.4-15.8-.1-30.5 8.2-38.5 21.9v-54.3c41.9 20.9 83.9 46.5 99.9 58.3-10.2 14.6-9.3 28.1-9.3 43.7 0 18.7-1.4 34.3 16.8 52.5s50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.7-33.8 16.7-52.5 0-18.5 1.5-34.2-16.7-52.3zM65.2 184v63.3c-48.7-54.5-38.9-76-35.2-79.1 13.5-11.4 37.5-8 64.4 2.1zm226.5 120.5c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9z\"],\n    \"hornbill\": [512, 512, [], \"f592\", \"M76.38 370.3a37.8 37.8 0 1 1-32.07-32.42c-78.28-111.35 52-190.53 52-190.53-5.86 43-8.24 91.16-8.24 91.16-67.31 41.49.93 64.06 39.81 72.87a140.38 140.38 0 0 0 131.66 91.94c1.92 0 3.77-.21 5.67-.28l.11 18.86c-99.22 1.39-158.7-29.14-188.94-51.6zm108-327.7A37.57 37.57 0 0 0 181 21.45a37.95 37.95 0 1 0-31.17 54.22c-22.55 29.91-53.83 89.57-52.42 190l21.84-.15c0-.9-.14-1.77-.14-2.68A140.42 140.42 0 0 1 207 132.71c8-37.71 30.7-114.3 73.8-44.29 0 0 48.14 2.38 91.18 8.24 0 0-77.84-128-187.59-54.06zm304.19 134.17a37.94 37.94 0 1 0-53.84-28.7C403 126.13 344.89 99 251.28 100.33l.14 22.5c2.7-.15 5.39-.41 8.14-.41a140.37 140.37 0 0 1 130.49 88.76c39.1 9 105.06 31.58 38.46 72.54 0 0-2.34 48.13-8.21 91.16 0 0 133.45-81.16 49-194.61a37.45 37.45 0 0 0 19.31-3.5zM374.06 436.24c21.43-32.46 46.42-89.69 45.14-179.66l-19.52.14c.08 2.06.3 4.07.3 6.15a140.34 140.34 0 0 1-91.39 131.45c-8.85 38.95-31.44 106.66-72.77 39.49 0 0-48.12-2.34-91.19-8.22 0 0 79.92 131.34 191.9 51a37.5 37.5 0 0 0 3.64 14 37.93 37.93 0 1 0 33.89-54.29z\"],\n    \"hotjar\": [448, 512, [], \"f3b1\", \"M414.9 161.5C340.2 29 121.1 0 121.1 0S222.2 110.4 93 197.7C11.3 252.8-21 324.4 14 402.6c26.8 59.9 83.5 84.3 144.6 93.4-29.2-55.1-6.6-122.4-4.1-129.6 57.1 86.4 165 0 110.8-93.9 71 15.4 81.6 138.6 27.1 215.5 80.5-25.3 134.1-88.9 148.8-145.6 15.5-59.3 3.7-127.9-26.3-180.9z\"],\n    \"houzz\": [448, 512, [], \"f27c\", \"M275.9 330.7H171.3V480H17V32h109.5v104.5l305.1 85.6V480H275.9z\"],\n    \"html5\": [384, 512, [], \"f13b\", \"M0 32l34.9 395.8L191.5 480l157.6-52.2L384 32H0zm308.2 127.9H124.4l4.1 49.4h175.6l-13.6 148.4-97.9 27v.3h-1.1l-98.7-27.3-6-75.8h47.7L138 320l53.5 14.5 53.7-14.5 6-62.2H84.3L71.5 112.2h241.1l-4.4 47.7z\"],\n    \"hubspot\": [512, 512, [], \"f3b2\", \"M267.4 211.6c-25.1 23.7-40.8 57.3-40.8 94.6 0 29.3 9.7 56.3 26 78L203.1 434c-4.4-1.6-9.1-2.5-14-2.5-10.8 0-20.9 4.2-28.5 11.8-7.6 7.6-11.8 17.8-11.8 28.6s4.2 20.9 11.8 28.5c7.6 7.6 17.8 11.6 28.5 11.6 10.8 0 20.9-3.9 28.6-11.6 7.6-7.6 11.8-17.8 11.8-28.5 0-4.2-.6-8.2-1.9-12.1l50-50.2c22 16.9 49.4 26.9 79.3 26.9 71.9 0 130-58.3 130-130.2 0-65.2-47.7-119.2-110.2-128.7V116c17.5-7.4 28.2-23.8 28.2-42.9 0-26.1-20.9-47.9-47-47.9S311.2 47 311.2 73.1c0 19.1 10.7 35.5 28.2 42.9v61.2c-15.2 2.1-29.6 6.7-42.7 13.6-27.6-20.9-117.5-85.7-168.9-124.8 1.2-4.4 2-9 2-13.8C129.8 23.4 106.3 0 77.4 0 48.6 0 25.2 23.4 25.2 52.2c0 28.9 23.4 52.3 52.2 52.3 9.8 0 18.9-2.9 26.8-7.6l163.2 114.7zm89.5 163.6c-38.1 0-69-30.9-69-69s30.9-69 69-69 69 30.9 69 69-30.9 69-69 69z\"],\n    \"imdb\": [448, 512, [], \"f2d8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.3 229.2H21c.1-.1.2-.3.3-.4zM97 319.8H64V192h33zm113.2 0h-28.7v-86.4l-11.6 86.4h-20.6l-12.2-84.5v84.5h-29V192h42.8c3.3 19.8 6 39.9 8.7 59.9l7.6-59.9h43zm11.4 0V192h24.6c17.6 0 44.7-1.6 49 20.9 1.7 7.6 1.4 16.3 1.4 24.4 0 88.5 11.1 82.6-75 82.5zm160.9-29.2c0 15.7-2.4 30.9-22.2 30.9-9 0-15.2-3-20.9-9.8l-1.9 8.1h-29.8V192h31.7v41.7c6-6.5 12-9.2 20.9-9.2 21.4 0 22.2 12.8 22.2 30.1zM265 229.9c0-9.7 1.6-16-10.3-16v83.7c12.2.3 10.3-8.7 10.3-18.4zm85.5 26.1c0-5.4 1.1-12.7-6.2-12.7-6 0-4.9 8.9-4.9 12.7 0 .6-1.1 39.6 1.1 44.7.8 1.6 2.2 2.4 3.8 2.4 7.8 0 6.2-9 6.2-14.4z\"],\n    \"instagram\": [448, 512, [], \"f16d\", \"M224.1 141c-63.6 0-114.9 51.3-114.9 114.9s51.3 114.9 114.9 114.9S339 319.5 339 255.9 287.7 141 224.1 141zm0 189.6c-41.1 0-74.7-33.5-74.7-74.7s33.5-74.7 74.7-74.7 74.7 33.5 74.7 74.7-33.6 74.7-74.7 74.7zm146.4-194.3c0 14.9-12 26.8-26.8 26.8-14.9 0-26.8-12-26.8-26.8s12-26.8 26.8-26.8 26.8 12 26.8 26.8zm76.1 27.2c-1.7-35.9-9.9-67.7-36.2-93.9-26.2-26.2-58-34.4-93.9-36.2-37-2.1-147.9-2.1-184.9 0-35.8 1.7-67.6 9.9-93.9 36.1s-34.4 58-36.2 93.9c-2.1 37-2.1 147.9 0 184.9 1.7 35.9 9.9 67.7 36.2 93.9s58 34.4 93.9 36.2c37 2.1 147.9 2.1 184.9 0 35.9-1.7 67.7-9.9 93.9-36.2 26.2-26.2 34.4-58 36.2-93.9 2.1-37 2.1-147.8 0-184.8zM398.8 388c-7.8 19.6-22.9 34.7-42.6 42.6-29.5 11.7-99.5 9-132.1 9s-102.7 2.6-132.1-9c-19.6-7.8-34.7-22.9-42.6-42.6-11.7-29.5-9-99.5-9-132.1s-2.6-102.7 9-132.1c7.8-19.6 22.9-34.7 42.6-42.6 29.5-11.7 99.5-9 132.1-9s102.7-2.6 132.1 9c19.6 7.8 34.7 22.9 42.6 42.6 11.7 29.5 9 99.5 9 132.1s2.7 102.7-9 132.1z\"],\n    \"intercom\": [448, 512, [], \"f7af\", \"M392 32H56C25.1 32 0 57.1 0 88v336c0 30.9 25.1 56 56 56h336c30.9 0 56-25.1 56-56V88c0-30.9-25.1-56-56-56zm-108.3 82.1c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zm-74.6-7.5c0-19.8 29.9-19.8 29.9 0v216.5c0 19.8-29.9 19.8-29.9 0V106.6zm-74.7 7.5c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zM59.7 144c0-19.8 29.9-19.8 29.9 0v134.3c0 19.8-29.9 19.8-29.9 0V144zm323.4 227.8c-72.8 63-241.7 65.4-318.1 0-15-12.8 4.4-35.5 19.4-22.7 65.9 55.3 216.1 53.9 279.3 0 14.9-12.9 34.3 9.8 19.4 22.7zm5.2-93.5c0 19.8-29.9 19.8-29.9 0V144c0-19.8 29.9-19.8 29.9 0v134.3z\"],\n    \"internet-explorer\": [512, 512, [], \"f26b\", \"M483.049 159.706c10.855-24.575 21.424-60.438 21.424-87.871 0-72.722-79.641-98.371-209.673-38.577-107.632-7.181-211.221 73.67-237.098 186.457 30.852-34.862 78.271-82.298 121.977-101.158C125.404 166.85 79.128 228.002 43.992 291.725 23.246 329.651 0 390.94 0 436.747c0 98.575 92.854 86.5 180.251 42.006 31.423 15.43 66.559 15.573 101.695 15.573 97.124 0 184.249-54.294 216.814-146.022H377.927c-52.509 88.593-196.819 52.996-196.819-47.436H509.9c6.407-43.581-1.655-95.715-26.851-141.162zM64.559 346.877c17.711 51.15 53.703 95.871 100.266 123.304-88.741 48.94-173.267 29.096-100.266-123.304zm115.977-108.873c2-55.151 50.276-94.871 103.98-94.871 53.418 0 101.981 39.72 103.981 94.871H180.536zm184.536-187.6c21.425-10.287 48.563-22.003 72.558-22.003 31.422 0 54.274 21.717 54.274 53.722 0 20.003-7.427 49.007-14.569 67.867-26.28-42.292-65.986-81.584-112.263-99.586z\"],\n    \"invision\": [448, 512, [], \"f7b0\", \"M407.4 32H40.6C18.2 32 0 50.2 0 72.6v366.8C0 461.8 18.2 480 40.6 480h366.8c22.4 0 40.6-18.2 40.6-40.6V72.6c0-22.4-18.2-40.6-40.6-40.6zM176.1 145.6c.4 23.4-22.4 27.3-26.6 27.4-14.9 0-27.1-12-27.1-27 .1-35.2 53.1-35.5 53.7-.4zM332.8 377c-65.6 0-34.1-74-25-106.6 14.1-46.4-45.2-59-59.9.7l-25.8 103.3H177l8.1-32.5c-31.5 51.8-94.6 44.4-94.6-4.3.1-14.3.9-14 23-104.1H81.7l9.7-35.6h76.4c-33.6 133.7-32.6 126.9-32.9 138.2 0 20.9 40.9 13.5 57.4-23.2l19.8-79.4h-32.3l9.7-35.6h68.8l-8.9 40.5c40.5-75.5 127.9-47.8 101.8 38-14.2 51.1-14.6 50.7-14.9 58.8 0 15.5 17.5 22.6 31.8-16.9L386 325c-10.5 36.7-29.4 52-53.2 52z\"],\n    \"ioxhost\": [640, 512, [], \"f208\", \"M616 160h-67.3C511.2 70.7 422.9 8 320 8 183 8 72 119 72 256c0 16.4 1.6 32.5 4.7 48H24c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h67.3c37.5 89.3 125.8 152 228.7 152 137 0 248-111 248-248 0-16.4-1.6-32.5-4.7-48H616c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24zm-96 96c0 110.5-89.5 200-200 200-75.7 0-141.6-42-175.5-104H424c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24H125.8c-3.8-15.4-5.8-31.4-5.8-48 0-110.5 89.5-200 200-200 75.7 0 141.6 42 175.5 104H216c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h298.2c3.8 15.4 5.8 31.4 5.8 48zm-304-24h208c13.3 0 24 10.7 24 24 0 13.2-10.7 24-24 24H216c-13.3 0-24-10.7-24-24 0-13.2 10.7-24 24-24z\"],\n    \"itch-io\": [512, 512, [], \"f83a\", \"M71.92 34.77C50.2 47.67 7.4 96.84 7 109.73v21.34c0 27.06 25.29 50.84 48.25 50.84 27.57 0 50.54-22.85 50.54-50 0 27.12 22.18 50 49.76 50s49-22.85 49-50c0 27.12 23.59 50 51.16 50h.5c27.57 0 51.16-22.85 51.16-50 0 27.12 21.47 50 49 50s49.76-22.85 49.76-50c0 27.12 23 50 50.54 50 23 0 48.25-23.78 48.25-50.84v-21.34c-.4-12.9-43.2-62.07-64.92-75C372.56 32.4 325.76 32 256 32S91.14 33.1 71.92 34.77zm132.32 134.39c-22 38.4-77.9 38.71-99.85.25-13.17 23.14-43.17 32.07-56 27.66-3.87 40.15-13.67 237.13 17.73 269.15 80 18.67 302.08 18.12 379.76 0 31.65-32.27 21.32-232 17.75-269.15-12.92 4.44-42.88-4.6-56-27.66-22 38.52-77.85 38.1-99.85-.24-7.1 12.49-23.05 28.94-51.76 28.94a57.54 57.54 0 0 1-51.75-28.94zm-41.58 53.77c16.47 0 31.09 0 49.22 19.78a436.91 436.91 0 0 1 88.18 0C318.22 223 332.85 223 349.31 223c52.33 0 65.22 77.53 83.87 144.45 17.26 62.15-5.52 63.67-33.95 63.73-42.15-1.57-65.49-32.18-65.49-62.79-39.25 6.43-101.93 8.79-155.55 0 0 30.61-23.34 61.22-65.49 62.79-28.42-.06-51.2-1.58-33.94-63.73 18.67-67 31.56-144.45 83.88-144.45zM256 270.79s-44.38 40.77-52.35 55.21l29-1.17v25.32c0 1.55 21.34.16 23.33.16 11.65.54 23.31 1 23.31-.16v-25.28l29 1.17c-8-14.48-52.35-55.24-52.35-55.24z\"],\n    \"itunes\": [448, 512, [], \"f3b4\", \"M223.6 80.3C129 80.3 52.5 157 52.5 251.5S129 422.8 223.6 422.8s171.2-76.7 171.2-171.2c0-94.6-76.7-171.3-171.2-171.3zm79.4 240c-3.2 13.6-13.5 21.2-27.3 23.8-12.1 2.2-22.2 2.8-31.9-5-11.8-10-12-26.4-1.4-36.8 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 3.2-3.6 2.2-2 2.2-80.8 0-5.6-2.7-7.1-8.4-6.1-4 .7-91.9 17.1-91.9 17.1-5 1.1-6.7 2.6-6.7 8.3 0 116.1.5 110.8-1.2 118.5-2.1 9-7.6 15.8-14.9 19.6-8.3 4.6-23.4 6.6-31.4 5.2-21.4-4-28.9-28.7-14.4-42.9 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 5-5.7.9-127 2.6-133.7.4-2.6 1.5-4.8 3.5-6.4 2.1-1.7 5.8-2.7 6.7-2.7 101-19 113.3-21.4 115.1-21.4 5.7-.4 9 3 9 8.7-.1 170.6.4 161.4-1 167.6zM345.2 32H102.8C45.9 32 0 77.9 0 134.8v242.4C0 434.1 45.9 480 102.8 480h242.4c57 0 102.8-45.9 102.8-102.8V134.8C448 77.9 402.1 32 345.2 32zM223.6 444c-106.3 0-192.5-86.2-192.5-192.5S117.3 59 223.6 59s192.5 86.2 192.5 192.5S329.9 444 223.6 444z\"],\n    \"itunes-note\": [384, 512, [], \"f3b5\", \"M381.9 388.2c-6.4 27.4-27.2 42.8-55.1 48-24.5 4.5-44.9 5.6-64.5-10.2-23.9-20.1-24.2-53.4-2.7-74.4 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 6.4-7.2 4.4-4.1 4.4-163.2 0-11.2-5.5-14.3-17-12.3-8.2 1.4-185.7 34.6-185.7 34.6-10.2 2.2-13.4 5.2-13.4 16.7 0 234.7 1.1 223.9-2.5 239.5-4.2 18.2-15.4 31.9-30.2 39.5-16.8 9.3-47.2 13.4-63.4 10.4-43.2-8.1-58.4-58-29.1-86.6 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 10.1-11.5 1.8-256.6 5.2-270.2.8-5.2 3-9.6 7.1-12.9 4.2-3.5 11.8-5.5 13.4-5.5 204-38.2 228.9-43.1 232.4-43.1 11.5-.8 18.1 6 18.1 17.6.2 344.5 1.1 326-1.8 338.5z\"],\n    \"java\": [384, 512, [], \"f4e4\", \"M277.74 312.9c9.8-6.7 23.4-12.5 23.4-12.5s-38.7 7-77.2 10.2c-47.1 3.9-97.7 4.7-123.1 1.3-60.1-8 33-30.1 33-30.1s-36.1-2.4-80.6 19c-52.5 25.4 130 37 224.5 12.1zm-85.4-32.1c-19-42.7-83.1-80.2 0-145.8C296 53.2 242.84 0 242.84 0c21.5 84.5-75.6 110.1-110.7 162.6-23.9 35.9 11.7 74.4 60.2 118.2zm114.6-176.2c.1 0-175.2 43.8-91.5 140.2 24.7 28.4-6.5 54-6.5 54s62.7-32.4 33.9-72.9c-26.9-37.8-47.5-56.6 64.1-121.3zm-6.1 270.5a12.19 12.19 0 0 1-2 2.6c128.3-33.7 81.1-118.9 19.8-97.3a17.33 17.33 0 0 0-8.2 6.3 70.45 70.45 0 0 1 11-3c31-6.5 75.5 41.5-20.6 91.4zM348 437.4s14.5 11.9-15.9 21.2c-57.9 17.5-240.8 22.8-291.6.7-18.3-7.9 16-19 26.8-21.3 11.2-2.4 17.7-2 17.7-2-20.3-14.3-131.3 28.1-56.4 40.2C232.84 509.4 401 461.3 348 437.4zM124.44 396c-78.7 22 47.9 67.4 148.1 24.5a185.89 185.89 0 0 1-28.2-13.8c-44.7 8.5-65.4 9.1-106 4.5-33.5-3.8-13.9-15.2-13.9-15.2zm179.8 97.2c-78.7 14.8-175.8 13.1-233.3 3.6 0-.1 11.8 9.7 72.4 13.6 92.2 5.9 233.8-3.3 237.1-46.9 0 0-6.4 16.5-76.2 29.7zM260.64 353c-59.2 11.4-93.5 11.1-136.8 6.6-33.5-3.5-11.6-19.7-11.6-19.7-86.8 28.8 48.2 61.4 169.5 25.9a60.37 60.37 0 0 1-21.1-12.8z\"],\n    \"jedi-order\": [448, 512, [], \"f50e\", \"M398.5 373.6c95.9-122.1 17.2-233.1 17.2-233.1 45.4 85.8-41.4 170.5-41.4 170.5 105-171.5-60.5-271.5-60.5-271.5 96.9 72.7-10.1 190.7-10.1 190.7 85.8 158.4-68.6 230.1-68.6 230.1s-.4-16.9-2.2-85.7c4.3 4.5 34.5 36.2 34.5 36.2l-24.2-47.4 62.6-9.1-62.6-9.1 20.2-55.5-31.4 45.9c-2.2-87.7-7.8-305.1-7.9-306.9v-2.4 1-1 2.4c0 1-5.6 219-7.9 306.9l-31.4-45.9 20.2 55.5-62.6 9.1 62.6 9.1-24.2 47.4 34.5-36.2c-1.8 68.8-2.2 85.7-2.2 85.7s-154.4-71.7-68.6-230.1c0 0-107-118.1-10.1-190.7 0 0-165.5 99.9-60.5 271.5 0 0-86.8-84.8-41.4-170.5 0 0-78.7 111 17.2 233.1 0 0-26.2-16.1-49.4-77.7 0 0 16.9 183.3 222 185.7h4.1c205-2.4 222-185.7 222-185.7-23.6 61.5-49.9 77.7-49.9 77.7z\"],\n    \"jenkins\": [512, 512, [], \"f3b6\", \"M487.1 425c-1.4-11.2-19-23.1-28.2-31.9-5.1-5-29-23.1-30.4-29.9-1.4-6.6 9.7-21.5 13.3-28.9 5.1-10.7 8.8-23.7 11.3-32.6 18.8-66.1 20.7-156.9-6.2-211.2-10.2-20.6-38.6-49-56.4-62.5-42-31.7-119.6-35.3-170.1-16.6-14.1 5.2-27.8 9.8-40.1 17.1-33.1 19.4-68.3 32.5-78.1 71.6-24.2 10.8-31.5 41.8-30.3 77.8.2 7 4.1 15.8 2.7 22.4-.7 3.3-5.2 7.6-6.1 9.8-11.6 27.7-2.3 64 11.1 83.7 8.1 11.9 21.5 22.4 39.2 25.2.7 10.6 3.3 19.7 8.2 30.4 3.1 6.8 14.7 19 10.4 27.7-2.2 4.4-21 13.8-27.3 17.6C89 407.2 73.7 415 54.2 429c-12.6 9-32.3 10.2-29.2 31.1 2.1 14.1 10.1 31.6 14.7 45.8.7 2 1.4 4.1 2.1 6h422c4.9-15.3 9.7-30.9 14.6-47.2 3.4-11.4 10.2-27.8 8.7-39.7zM205.9 33.7c1.8-.5 3.4.7 4.9 2.4-.2 5.2-5.4 5.1-8.9 6.8-5.4 6.7-13.4 9.8-20 17.2-6.8 7.5-14.4 27.7-23.4 30-4.5 1.1-9.7-.8-13.6-.5-10.4.7-17.7 6-28.3 7.5 13.6-29.9 56.1-54 89.3-63.4zm-104.8 93.6c13.5-14.9 32.1-24.1 54.8-25.9 11.7 29.7-8.4 65-.9 97.6 2.3 9.9 10.2 25.4-2.4 25.7.3-28.3-34.8-46.3-61.3-29.6-1.8-21.5-4.9-51.7 9.8-67.8zm36.7 200.2c-1-4.1-2.7-12.9-2.3-15.1 1.6-8.7 17.1-12.5 11-24.7-11.3-.1-13.8 10.2-24.1 11.3-26.7 2.6-45.6-35.4-44.4-58.4 1-19.5 17.6-38.2 40.1-35.8 16 1.8 21.4 19.2 24.5 34.7 9.2.5 22.5-.4 26.9-7.6-.6-17.5-8.8-31.6-8.2-47.7 1-30.3 17.5-57.6 4.8-87.4 13.6-30.9 53.5-55.3 83.1-70 36.6-18.3 94.9-3.7 129.3 15.8 19.7 11.1 34.4 32.7 48.3 50.7-19.5-5.8-36.1 4.2-33.1 20.3 16.3-14.9 44.2-.2 52.5 16.4 7.9 15.8 7.8 39.3 9 62.8 2.9 57-10.4 115.9-39.1 157.1-7.7 11-14.1 23-24.9 30.6-26 18.2-65.4 34.7-99.2 23.4-44.7-15-65-44.8-89.5-78.8.7 18.7 13.8 34.1 26.8 48.4 11.3 12.5 25 26.6 39.7 32.4-12.3-2.9-31.1-3.8-36.2 7.2-28.6-1.9-55.1-4.8-68.7-24.2-10.6-15.4-21.4-41.4-26.3-61.4zm222 124.1c4.1-3 11.1-2.9 17.4-3.6-5.4-2.7-13-3.7-19.3-2.2-.1-4.2-2-6.8-3.2-10.2 10.6-3.8 35.5-28.5 49.6-20.3 6.7 3.9 9.5 26.2 10.1 37 .4 9-.8 18-4.5 22.8-18.8-.6-35.8-2.8-50.7-7 .9-6.1-1-12.1.6-16.5zm-17.2-20c-16.8.8-26-1.2-38.3-10.8.2-.8 1.4-.5 1.5-1.4 18 8 40.8-3.3 59-4.9-7.9 5.1-14.6 11.6-22.2 17.1zm-12.1 33.2c-1.6-9.4-3.5-12-2.8-20.2 25-16.6 29.7 28.6 2.8 20.2zM226 438.6c-11.6-.7-48.1-14-38.5-23.7 9.4 6.5 27.5 4.9 41.3 7.3.8 4.4-2.8 10.2-2.8 16.4zM57.7 497.1c-4.3-12.7-9.2-25.1-14.8-36.9 30.8-23.8 65.3-48.9 102.2-63.5 2.8-1.1 23.2 25.4 26.2 27.6 16.5 11.7 37 21 56.2 30.2 1.2 8.8 3.9 20.2 8.7 35.5.7 2.3 1.4 4.7 2.2 7.2H57.7zm240.6 5.7h-.8c.3-.2.5-.4.8-.5v.5zm7.5-5.7c2.1-1.4 4.3-2.8 6.4-4.3 1.1 1.4 2.2 2.8 3.2 4.3h-9.6zm15.1-24.7c-10.8 7.3-20.6 18.3-33.3 25.2-6 3.3-27 11.7-33.4 10.2-3.6-.8-3.9-5.3-5.4-9.5-3.1-9-10.1-23.4-10.8-37-.8-17.2-2.5-46 16-42.4 14.9 2.9 32.3 9.7 43.9 16.1 7.1 3.9 11.1 8.6 21.9 9.5-.1 1.4-.1 2.8-.2 4.3-5.9 3.9-15.3 3.8-21.8 7.1 9.5.4 17 2.7 23.5 5.9-.1 3.4-.3 7-.4 10.6zm53.4 24.7h-14c-.1-3.2-2.8-5.8-6.1-5.8s-5.9 2.6-6.1 5.8h-17.4c-2.8-4.4-5.7-8.6-8.9-12.5 2.1-2.2 4-4.7 6-6.9 9 3.7 14.8-4.9 21.7-4.2 7.9.8 14.2 11.7 25.4 11l-.6 12.6zm8.7 0c.2-4 .4-7.8.6-11.5 15.6-7.3 29 1.3 35.7 11.5H383zm83.4-37c-2.3 11.2-5.8 24-9.9 37.1-.2-.1-.4-.1-.6-.1H428c.6-1.1 1.2-2.2 1.9-3.3-2.6-6.1-9-8.7-10.9-15.5 12.1-22.7 6.5-93.4-24.2-78.5 4.3-6.3 15.6-11.5 20.8-19.3 13 10.4 20.8 20.3 33.2 31.4 6.8 6 20 13.3 21.4 23.1.8 5.5-2.6 18.9-3.8 25.1zM222.2 130.5c5.4-14.9 27.2-34.7 45-32 7.7 1.2 18 8.2 12.2 17.7-30.2-7-45.2 12.6-54.4 33.1-8.1-2-4.9-13.1-2.8-18.8zm184.1 63.1c8.2-3.6 22.4-.7 29.6-5.3-4.2-11.5-10.3-21.4-9.3-37.7.5 0 1 0 1.4.1 6.8 14.2 12.7 29.2 21.4 41.7-5.7 13.5-43.6 25.4-43.1 1.2zm20.4-43zm-117.2 45.7c-6.8-10.9-19-32.5-14.5-45.3 6.5 11.9 8.6 24.4 17.8 33.3 4.1 4 12.2 9 8.2 20.2-.9 2.7-7.8 8.6-11.7 9.7-14.4 4.3-47.9.9-36.6-17.1 11.9.7 27.9 7.8 36.8-.8zm27.3 70c3.8 6.6 1.4 18.7 12.1 20.6 20.2 3.4 43.6-12.3 58.1-17.8 9-15.2-.8-20.7-8.9-30.5-16.6-20-38.8-44.8-38-74.7 6.7-4.9 7.3 7.4 8.2 9.7 8.7 20.3 30.4 46.2 46.3 63.5 3.9 4.3 10.3 8.4 11 11.2 2.1 8.2-5.4 18-4.5 23.5-21.7 13.9-45.8 29.1-81.4 25.6-7.4-6.7-10.3-21.4-2.9-31.1zm-201.3-9.2c-6.8-3.9-8.4-21-16.4-21.4-11.4-.7-9.3 22.2-9.3 35.5-7.8-7.1-9.2-29.1-3.5-40.3-6.6-3.2-9.5 3.6-13.1 5.9 4.7-34.1 49.8-15.8 42.3 20.3zm299.6 28.8c-10.1 19.2-24.4 40.4-54 41-.6-6.2-1.1-15.6 0-19.4 22.7-2.2 36.6-13.7 54-21.6zm-141.9 12.4c18.9 9.9 53.6 11 79.3 10.2 1.4 5.6 1.3 12.6 1.4 19.4-33 1.8-72-6.4-80.7-29.6zm92.2 46.7c-1.7 4.3-5.3 9.3-9.8 11.1-12.1 4.9-45.6 8.7-62.4-.3-10.7-5.7-17.5-18.5-23.4-26-2.8-3.6-16.9-12.9-.2-12.9 13.1 32.7 58 29 95.8 28.1z\"],\n    \"jira\": [496, 512, [], \"f7b1\", \"M490 241.7C417.1 169 320.6 71.8 248.5 0 83 164.9 6 241.7 6 241.7c-7.9 7.9-7.9 20.7 0 28.7C138.8 402.7 67.8 331.9 248.5 512c379.4-378 15.7-16.7 241.5-241.7 8-7.9 8-20.7 0-28.6zm-241.5 90l-76-75.7 76-75.7 76 75.7-76 75.7z\"],\n    \"joget\": [496, 512, [], \"f3b7\", \"M378.1 45C337.6 19.9 292.6 8 248.2 8 165 8 83.8 49.9 36.9 125.9c-71.9 116.6-35.6 269.3 81 341.2s269.3 35.6 341.2-80.9c71.9-116.6 35.6-269.4-81-341.2zm51.8 323.2c-40.4 65.5-110.4 101.5-182 101.5-6.8 0-13.6-.4-20.4-1-9-13.6-19.9-33.3-23.7-42.4-5.7-13.7-27.2-45.6 31.2-67.1 51.7-19.1 176.7-16.5 208.8-17.6-4 9-8.6 17.9-13.9 26.6zm-200.8-86.3c-55.5-1.4-81.7-20.8-58.5-48.2s51.1-40.7 68.9-51.2c17.9-10.5 27.3-33.7-23.6-29.7C87.3 161.5 48.6 252.1 37.6 293c-8.8-49.7-.1-102.7 28.5-149.1C128 43.4 259.6 12.2 360.1 74.1c74.8 46.1 111.2 130.9 99.3 212.7-24.9-.5-179.3-3.6-230.3-4.9zm183.8-54.8c-22.7-6-57 11.3-86.7 27.2-29.7 15.8-31.1 8.2-31.1 8.2s40.2-28.1 50.7-34.5 31.9-14 13.4-24.6c-3.2-1.8-6.7-2.7-10.4-2.7-17.8 0-41.5 18.7-67.5 35.6-31.5 20.5-65.3 31.3-65.3 31.3l169.5-1.6 46.5-23.4s3.6-9.5-19.1-15.5z\"],\n    \"joomla\": [448, 512, [], \"f1aa\", \"M.6 92.1C.6 58.8 27.4 32 60.4 32c30 0 54.5 21.9 59.2 50.2 32.6-7.6 67.1.6 96.5 30l-44.3 44.3c-20.5-20.5-42.6-16.3-55.4-3.5-14.3 14.3-14.3 37.9 0 52.2l99.5 99.5-44 44.3c-87.7-87.2-49.7-49.7-99.8-99.7-26.8-26.5-35-64.8-24.8-98.9C20.4 144.6.6 120.7.6 92.1zm129.5 116.4l44.3 44.3c10-10 89.7-89.7 99.7-99.8 14.3-14.3 37.6-14.3 51.9 0 12.8 12.8 17 35-3.5 55.4l44 44.3c31.2-31.2 38.5-67.6 28.9-101.2 29.2-4.1 51.9-29.2 51.9-59.5 0-33.2-26.8-60.1-59.8-60.1-30.3 0-55.4 22.5-59.5 51.6-33.8-9.9-71.7-1.5-98.3 25.1-18.3 19.1-71.1 71.5-99.6 99.9zm266.3 152.2c8.2-32.7-.9-68.5-26.3-93.9-11.8-12.2 5 4.7-99.5-99.7l-44.3 44.3 99.7 99.7c14.3 14.3 14.3 37.6 0 51.9-12.8 12.8-35 17-55.4-3.5l-44 44.3c27.6 30.2 68 38.8 102.7 28 5.5 27.4 29.7 48.1 58.9 48.1 33 0 59.8-26.8 59.8-60.1 0-30.2-22.5-55-51.6-59.1zm-84.3-53.1l-44-44.3c-87 86.4-50.4 50.4-99.7 99.8-14.3 14.3-37.6 14.3-51.9 0-13.1-13.4-16.9-35.3 3.2-55.4l-44-44.3c-30.2 30.2-38 65.2-29.5 98.3-26.7 6-46.2 29.9-46.2 58.2C0 453.2 26.8 480 59.8 480c28.6 0 52.5-19.8 58.6-46.7 32.7 8.2 68.5-.6 94.2-26 32.1-32 12.2-12.4 99.5-99.7z\"],\n    \"js\": [448, 512, [], \"f3b8\", \"M0 32v448h448V32H0zm243.8 349.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"js-square\": [448, 512, [], \"f3b9\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM243.8 381.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"jsfiddle\": [576, 512, [], \"f1cc\", \"M510.634 237.462c-4.727-2.621-5.664-5.748-6.381-10.776-2.352-16.488-3.539-33.619-9.097-49.095-35.895-99.957-153.99-143.386-246.849-91.646-27.37 15.25-48.971 36.369-65.493 63.903-3.184-1.508-5.458-2.71-7.824-3.686-30.102-12.421-59.049-10.121-85.331 9.167-25.531 18.737-36.422 44.548-32.676 76.408.355 3.025-1.967 7.621-4.514 9.545-39.712 29.992-56.031 78.065-41.902 124.615 13.831 45.569 57.514 79.796 105.608 81.433 30.291 1.031 60.637.546 90.959.539 84.041-.021 168.09.531 252.12-.48 52.664-.634 96.108-36.873 108.212-87.293 11.54-48.074-11.144-97.3-56.832-122.634zm21.107 156.88c-18.23 22.432-42.343 35.253-71.28 35.65-56.874.781-113.767.23-170.652.23 0 .7-163.028.159-163.728.154-43.861-.332-76.739-19.766-95.175-59.995-18.902-41.245-4.004-90.848 34.186-116.106 9.182-6.073 12.505-11.566 10.096-23.136-5.49-26.361 4.453-47.956 26.42-62.981 22.987-15.723 47.422-16.146 72.034-3.083 10.269 5.45 14.607 11.564 22.198-2.527 14.222-26.399 34.557-46.727 60.671-61.294 97.46-54.366 228.37 7.568 230.24 132.697.122 8.15 2.412 12.428 9.848 15.894 57.56 26.829 74.456 96.122 35.142 144.497zm-87.789-80.499c-5.848 31.157-34.622 55.096-66.666 55.095-16.953-.001-32.058-6.545-44.079-17.705-27.697-25.713-71.141-74.98-95.937-93.387-20.056-14.888-41.99-12.333-60.272 3.782-49.996 44.071 15.859 121.775 67.063 77.188 4.548-3.96 7.84-9.543 12.744-12.844 8.184-5.509 20.766-.884 13.168 10.622-17.358 26.284-49.33 38.197-78.863 29.301-28.897-8.704-48.84-35.968-48.626-70.179 1.225-22.485 12.364-43.06 35.414-55.965 22.575-12.638 46.369-13.146 66.991 2.474C295.68 280.7 320.467 323.97 352.185 343.47c24.558 15.099 54.254 7.363 68.823-17.506 28.83-49.209-34.592-105.016-78.868-63.46-3.989 3.744-6.917 8.932-11.41 11.72-10.975 6.811-17.333-4.113-12.809-10.353 20.703-28.554 50.464-40.44 83.271-28.214 31.429 11.714 49.108 44.366 42.76 78.186z\"],\n    \"kaggle\": [320, 512, [], \"f5fa\", \"M304.2 501.5L158.4 320.3 298.2 185c2.6-2.7 1.7-10.5-5.3-10.5h-69.2c-3.5 0-7 1.8-10.5 5.3L80.9 313.5V7.5q0-7.5-7.5-7.5H21.5Q14 0 14 7.5v497q0 7.5 7.5 7.5h51.9q7.5 0 7.5-7.5v-109l30.8-29.3 110.5 140.6c3 3.5 6.5 5.3 10.5 5.3h66.9q5.25 0 6-3z\"],\n    \"keybase\": [448, 512, [], \"f4f5\", \"M286.17,419a18,18,0,1,0,18,18A18,18,0,0,0,286.17,419ZM398.09,271.4c-9.5-14.62-39.37-52.45-87.26-73.71q-9.1-4.06-18.38-7.27A78.43,78.43,0,0,0,244.57,86.29c-12.41-4.1-23.33-6-32.41-5.77-.6-2-1.89-11,9.4-35L198.66,32l-5.48,7.56c-8.69,12.06-16.92,23.55-24.34,34.89a51,51,0,0,0-8.29-1.25c-41.53-2.45-39-2.33-41.06-2.33-50.61,0-50.75,52.12-50.75,45.88l-2.36,36.68c-1.61,27,19.75,50.21,47.63,51.85l8.93.54a214,214,0,0,0-46.29,35.54C14,304.66,14,374,14,429.77v33.64l23.32-29.8a148.6,148.6,0,0,0,14.56,37.56c5.78,10.13,14.87,9.45,19.64,7.33,4.21-1.87,10-6.92,3.75-20.11a178.29,178.29,0,0,1-15.76-53.13l46.82-59.83L81.67,419.54c58.23-42.4,157.38-61.76,236.25-38.59,34.2,10.05,67.45.69,84.74-23.84.72-1,1.2-2.16,1.85-3.22a156.09,156.09,0,0,1,2.8,28.43c0,23.3-3.69,52.93-14.88,81.64-2.52,6.46,1.76,14.5,8.6,15.74,7.42,1.57,15.33-3.1,18.37-11.15C429,443,434,414,434,382.32,434,343.74,421,304.86,398.09,271.4ZM142.37,128.58l-15.7-.93-1.39,21.79,13.13.78a93,93,0,0,0,.32,19.57l-22.38-1.34a12.28,12.28,0,0,1-11.76-12.79L107,119c1-12.17,13.87-11.27,13.26-11.32l29.11,1.73A144.35,144.35,0,0,0,142.37,128.58ZM290.79,300.76a10.51,10.51,0,0,1-14.35-1.39l-9.68-11.49-34.42,27a8.09,8.09,0,0,1-11.13-1.08l-15.78-18.64a7.38,7.38,0,0,1,1.34-10.34l34.57-27.18L227.2,240.9l-17.09,13.45a7.75,7.75,0,0,1-10.59-1s-3.72-4.42-3.8-4.53a7.38,7.38,0,0,1,1.37-10.34L214,225.19s-18.51-22-18.6-22.14a9.56,9.56,0,0,1,1.74-13.42A10.38,10.38,0,0,1,211.44,191l81.09,96.32A9.58,9.58,0,0,1,290.79,300.76ZM187.44,419a18,18,0,1,0,18,18A18,18,0,0,0,187.44,419Z\"],\n    \"keycdn\": [512, 512, [], \"f3ba\", \"M63.8 409.3l60.5-59c32.1 42.8 71.1 66 126.6 67.4 30.5.7 60.3-7 86.4-22.4 5.1 5.3 18.5 19.5 20.9 22-32.2 20.7-69.6 31.1-108.1 30.2-43.3-1.1-84.6-16.7-117.7-44.4.3-.6-38.2 37.5-38.6 37.9 9.5 29.8-13.1 62.4-46.3 62.4C20.7 503.3 0 481.7 0 454.9c0-34.3 33.1-56.6 63.8-45.6zm354.9-252.4c19.1 31.3 29.6 67.4 28.7 104-1.1 44.8-19 87.5-48.6 121 .3.3 23.8 25.2 24.1 25.5 9.6-1.3 19.2 2 25.9 9.1 11.3 12 10.9 30.9-1.1 42.4-12 11.3-30.9 10.9-42.4-1.1-6.7-7-9.4-16.8-7.6-26.3-24.9-26.6-44.4-47.2-44.4-47.2 42.7-34.1 63.3-79.6 64.4-124.2.7-28.9-7.2-57.2-21.1-82.2l22.1-21zM104 53.1c6.7 7 9.4 16.8 7.6 26.3l45.9 48.1c-4.7 3.8-13.3 10.4-22.8 21.3-25.4 28.5-39.6 64.8-40.7 102.9-.7 28.9 6.1 57.2 20 82.4l-22 21.5C72.7 324 63.1 287.9 64.2 250.9c1-44.6 18.3-87.6 47.5-121.1l-25.3-26.4c-9.6 1.3-19.2-2-25.9-9.1-11.3-12-10.9-30.9 1.1-42.4C73.5 40.7 92.2 41 104 53.1zM464.9 8c26 0 47.1 22.4 47.1 48.3S490.9 104 464.9 104c-6.3.1-14-1.1-15.9-1.8l-62.9 59.7c-32.7-43.6-76.7-65.9-126.9-67.2-30.5-.7-60.3 6.8-86.2 22.4l-21.1-22C184.1 74.3 221.5 64 260 64.9c43.3 1.1 84.6 16.7 117.7 44.6l41.1-38.6c-1.5-4.7-2.2-9.6-2.2-14.5C416.5 29.7 438.9 8 464.9 8zM256.7 113.4c5.5 0 10.9.4 16.4 1.1 78.1 9.8 133.4 81.1 123.8 159.1-9.8 78.1-81.1 133.4-159.1 123.8-78.1-9.8-133.4-81.1-123.8-159.2 9.3-72.4 70.1-124.6 142.7-124.8zm-59 119.4c.6 22.7 12.2 41.8 32.4 52.2l-11 51.7h73.7l-11-51.7c20.1-10.9 32.1-29 32.4-52.2-.4-32.8-25.8-57.5-58.3-58.3-32.1.8-57.3 24.8-58.2 58.3zM256 160\"],\n    \"kickstarter\": [448, 512, [], \"f3bb\", \"M400 480H48c-26.4 0-48-21.6-48-48V80c0-26.4 21.6-48 48-48h352c26.4 0 48 21.6 48 48v352c0 26.4-21.6 48-48 48zM199.6 178.5c0-30.7-17.6-45.1-39.7-45.1-25.8 0-40 19.8-40 44.5v154.8c0 25.8 13.7 45.6 40.5 45.6 21.5 0 39.2-14 39.2-45.6v-41.8l60.6 75.7c12.3 14.9 39 16.8 55.8 0 14.6-15.1 14.8-36.8 4-50.4l-49.1-62.8 40.5-58.7c9.4-13.5 9.5-34.5-5.6-49.1-16.4-15.9-44.6-17.3-61.4 7l-44.8 64.7v-38.8z\"],\n    \"kickstarter-k\": [384, 512, [], \"f3bc\", \"M147.3 114.4c0-56.2-32.5-82.4-73.4-82.4C26.2 32 0 68.2 0 113.4v283c0 47.3 25.3 83.4 74.9 83.4 39.8 0 72.4-25.6 72.4-83.4v-76.5l112.1 138.3c22.7 27.2 72.1 30.7 103.2 0 27-27.6 27.3-67.4 7.4-92.2l-90.8-114.8 74.9-107.4c17.4-24.7 17.5-63.1-10.4-89.8-30.3-29-82.4-31.6-113.6 12.8L147.3 185v-70.6z\"],\n    \"korvue\": [446, 512, [], \"f42f\", \"M386.5 34h-327C26.8 34 0 60.8 0 93.5v327.1C0 453.2 26.8 480 59.5 480h327.1c33 0 59.5-26.8 59.5-59.5v-327C446 60.8 419.2 34 386.5 34zM87.1 120.8h96v116l61.8-116h110.9l-81.2 132H87.1v-132zm161.8 272.1l-65.7-113.6v113.6h-96V262.1h191.5l88.6 130.8H248.9z\"],\n    \"laravel\": [640, 512, [], \"f3bd\", \"M637.5 241.6c-4.2-4.8-62.8-78.1-73.1-90.5-10.3-12.4-15.4-10.2-21.7-9.3-6.4.9-80.5 13.4-89.1 14.8-8.6 1.5-14 4.9-8.7 12.3 4.7 6.6 53.4 75.7 64.2 90.9l-193.7 46.4L161.2 48.7c-6.1-9.1-7.4-12.3-21.4-11.6-14 .6-120.9 9.5-128.5 10.2-7.6.6-16 4-8.4 22s129 279.6 132.4 287.2c3.4 7.6 12.2 20 32.8 15 21.1-5.1 94.3-24.2 134.3-34.7 21.1 38.3 64.2 115.9 72.2 127 10.6 14.9 18 12.4 34.3 7.4 12.8-3.9 199.6-71.1 208-74.5 8.4-3.5 13.6-5.9 7.9-14.4-4.2-6.2-53.5-72.2-79.3-106.8 17.7-4.7 80.6-21.4 87.3-23.3 7.9-2 9-5.8 4.7-10.6zm-352.2 72c-2.3.5-110.8 26.5-116.6 27.8-5.8 1.3-5.8.7-6.5-1.3-.7-2-129-266.7-130.8-270-1.8-3.3-1.7-5.9 0-5.9s102.5-9 106-9.2c3.6-.2 3.2.6 4.5 2.8 0 0 142.2 245.4 144.6 249.7 2.6 4.3 1.1 5.6-1.2 6.1zm306 57.4c1.7 2.7 3.5 4.5-2 6.4-5.4 2-183.7 62.1-187.1 63.6-3.5 1.5-6.2 2-10.6-4.5s-62.4-106.8-62.4-106.8L518 280.6c4.7-1.5 6.2-2.5 9.2 2.2 2.9 4.8 62.4 85.5 64.1 88.2zm12.1-134.1c-4.2.9-73.6 18.1-73.6 18.1l-56.7-77.8c-1.6-2.3-2.9-4.5 1.1-5s68.4-12.2 71.3-12.8c2.9-.7 5.4-1.5 9 3.4 3.6 4.9 52.6 67 54.5 69.4 1.8 2.3-1.4 3.7-5.6 4.7z\"],\n    \"lastfm\": [512, 512, [], \"f202\", \"M225.8 367.1l-18.8-51s-30.5 34-76.2 34c-40.5 0-69.2-35.2-69.2-91.5 0-72.1 36.4-97.9 72.1-97.9 66.5 0 74.8 53.3 100.9 134.9 18.8 56.9 54 102.6 155.4 102.6 72.7 0 122-22.3 122-80.9 0-72.9-62.7-80.6-115-92.1-25.8-5.9-33.4-16.4-33.4-34 0-19.9 15.8-31.7 41.6-31.7 28.2 0 43.4 10.6 45.7 35.8l58.6-7c-4.7-52.8-41.1-74.5-100.9-74.5-52.8 0-104.4 19.9-104.4 83.9 0 39.9 19.4 65.1 68 76.8 44.9 10.6 79.8 13.8 79.8 45.7 0 21.7-21.1 30.5-61 30.5-59.2 0-83.9-31.1-97.9-73.9-32-96.8-43.6-163-161.3-163C45.7 113.8 0 168.3 0 261c0 89.1 45.7 137.2 127.9 137.2 66.2 0 97.9-31.1 97.9-31.1z\"],\n    \"lastfm-square\": [448, 512, [], \"f203\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-92.2 312.9c-63.4 0-85.4-28.6-97.1-64.1-16.3-51-21.5-84.3-63-84.3-22.4 0-45.1 16.1-45.1 61.2 0 35.2 18 57.2 43.3 57.2 28.6 0 47.6-21.3 47.6-21.3l11.7 31.9s-19.8 19.4-61.2 19.4c-51.3 0-79.9-30.1-79.9-85.8 0-57.9 28.6-92 82.5-92 73.5 0 80.8 41.4 100.8 101.9 8.8 26.8 24.2 46.2 61.2 46.2 24.9 0 38.1-5.5 38.1-19.1 0-19.9-21.8-22-49.9-28.6-30.4-7.3-42.5-23.1-42.5-48 0-40 32.3-52.4 65.2-52.4 37.4 0 60.1 13.6 63 46.6l-36.7 4.4c-1.5-15.8-11-22.4-28.6-22.4-16.1 0-26 7.3-26 19.8 0 11 4.8 17.6 20.9 21.3 32.7 7.1 71.8 12 71.8 57.5.1 36.7-30.7 50.6-76.1 50.6z\"],\n    \"leanpub\": [576, 512, [], \"f212\", \"M386.539 111.485l15.096 248.955-10.979-.275c-36.232-.824-71.64 8.783-102.657 27.997-31.016-19.214-66.424-27.997-102.657-27.997-45.564 0-82.07 10.705-123.516 27.723L93.117 129.6c28.546-11.803 61.484-18.115 92.226-18.115 41.173 0 73.836 13.175 102.657 42.544 27.723-28.271 59.013-41.721 98.539-42.544zM569.07 448c-25.526 0-47.485-5.215-70.542-15.645-34.31-15.645-69.993-24.978-107.871-24.978-38.977 0-74.934 12.901-102.657 40.623-27.723-27.723-63.68-40.623-102.657-40.623-37.878 0-73.561 9.333-107.871 24.978C55.239 442.236 32.731 448 8.303 448H6.93L49.475 98.859C88.726 76.626 136.486 64 181.775 64 218.83 64 256.984 71.685 288 93.095 319.016 71.685 357.17 64 394.225 64c45.289 0 93.049 12.626 132.3 34.859L569.07 448zm-43.368-44.741l-34.036-280.246c-30.742-13.999-67.248-21.41-101.009-21.41-38.428 0-74.385 12.077-102.657 38.702-28.272-26.625-64.228-38.702-102.657-38.702-33.761 0-70.267 7.411-101.009 21.41L50.298 403.259c47.211-19.487 82.894-33.486 135.045-33.486 37.604 0 70.817 9.606 102.657 29.644 31.84-20.038 65.052-29.644 102.657-29.644 52.151 0 87.834 13.999 135.045 33.486z\"],\n    \"less\": [640, 512, [], \"f41d\", \"M612.7 219c0-20.5 3.2-32.6 3.2-54.6 0-34.2-12.6-45.2-40.5-45.2h-20.5v24.2h6.3c14.2 0 17.3 4.7 17.3 22.1 0 16.3-1.6 32.6-1.6 51.5 0 24.2 7.9 33.6 23.6 37.3v1.6c-15.8 3.7-23.6 13.1-23.6 37.3 0 18.9 1.6 34.2 1.6 51.5 0 17.9-3.7 22.6-17.3 22.6v.5h-6.3V393h20.5c27.8 0 40.5-11 40.5-45.2 0-22.6-3.2-34.2-3.2-54.6 0-11 6.8-22.6 27.3-23.6v-27.3c-20.5-.7-27.3-12.3-27.3-23.3zm-105.6 32c-15.8-6.3-30.5-10-30.5-20.5 0-7.9 6.3-12.6 17.9-12.6s22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-21 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51s-22.5-41-43-47.8zm-358.9 59.4c-3.7 0-8.4-3.2-8.4-13.1V119.1H65.2c-28.4 0-41 11-41 45.2 0 22.6 3.2 35.2 3.2 54.6 0 11-6.8 22.6-27.3 23.6v27.3c20.5.5 27.3 12.1 27.3 23.1 0 19.4-3.2 31-3.2 53.6 0 34.2 12.6 45.2 40.5 45.2h20.5v-24.2h-6.3c-13.1 0-17.3-5.3-17.3-22.6s1.6-32.1 1.6-51.5c0-24.2-7.9-33.6-23.6-37.3v-1.6c15.8-3.7 23.6-13.1 23.6-37.3 0-18.9-1.6-34.2-1.6-51.5s3.7-22.1 17.3-22.1H93v150.8c0 32.1 11 53.1 43.1 53.1 10 0 17.9-1.6 23.6-3.7l-5.3-34.2c-3.1.8-4.6.8-6.2.8zM379.9 251c-16.3-6.3-31-10-31-20.5 0-7.9 6.3-12.6 17.9-12.6 11.6 0 22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-20.5 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51 .1-28.9-22.5-41-43-47.8zm-155-68.8c-38.4 0-75.1 32.1-74.1 82.5 0 52 34.2 82.5 79.3 82.5 18.9 0 39.9-6.8 56.2-17.9l-15.8-27.8c-11.6 6.8-22.6 10-34.2 10-21 0-37.3-10-41.5-34.2H290c.5-3.7 1.6-11 1.6-19.4.6-42.6-22.6-75.7-66.7-75.7zm-30 66.2c3.2-21 15.8-31 30.5-31 18.9 0 26.3 13.1 26.3 31h-56.8z\"],\n    \"line\": [448, 512, [], \"f3c0\", \"M272.1 204.2v71.1c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.1 0-2.1-.6-2.6-1.3l-32.6-44v42.2c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.8 0-3.2-1.4-3.2-3.2v-71.1c0-1.8 1.4-3.2 3.2-3.2H219c1 0 2.1.5 2.6 1.4l32.6 44v-42.2c0-1.8 1.4-3.2 3.2-3.2h11.4c1.8-.1 3.3 1.4 3.3 3.1zm-82-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 1.8 1.4 3.2 3.2 3.2h11.4c1.8 0 3.2-1.4 3.2-3.2v-71.1c0-1.7-1.4-3.2-3.2-3.2zm-27.5 59.6h-31.1v-56.4c0-1.8-1.4-3.2-3.2-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 .9.3 1.6.9 2.2.6.5 1.3.9 2.2.9h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.7-1.4-3.2-3.1-3.2zM332.1 201h-45.7c-1.7 0-3.2 1.4-3.2 3.2v71.1c0 1.7 1.4 3.2 3.2 3.2h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2V234c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2v-11.4c-.1-1.7-1.5-3.2-3.2-3.2zM448 113.7V399c-.1 44.8-36.8 81.1-81.7 81H81c-44.8-.1-81.1-36.9-81-81.7V113c.1-44.8 36.9-81.1 81.7-81H367c44.8.1 81.1 36.8 81 81.7zm-61.6 122.6c0-73-73.2-132.4-163.1-132.4-89.9 0-163.1 59.4-163.1 132.4 0 65.4 58 120.2 136.4 130.6 19.1 4.1 16.9 11.1 12.6 36.8-.7 4.1-3.3 16.1 14.1 8.8 17.4-7.3 93.9-55.3 128.2-94.7 23.6-26 34.9-52.3 34.9-81.5z\"],\n    \"linkedin\": [448, 512, [], \"f08c\", \"M416 32H31.9C14.3 32 0 46.5 0 64.3v383.4C0 465.5 14.3 480 31.9 480H416c17.6 0 32-14.5 32-32.3V64.3c0-17.8-14.4-32.3-32-32.3zM135.4 416H69V202.2h66.5V416zm-33.2-243c-21.3 0-38.5-17.3-38.5-38.5S80.9 96 102.2 96c21.2 0 38.5 17.3 38.5 38.5 0 21.3-17.2 38.5-38.5 38.5zm282.1 243h-66.4V312c0-24.8-.5-56.7-34.5-56.7-34.6 0-39.9 27-39.9 54.9V416h-66.4V202.2h63.7v29.2h.9c8.9-16.8 30.6-34.5 62.9-34.5 67.2 0 79.7 44.3 79.7 101.9V416z\"],\n    \"linkedin-in\": [448, 512, [], \"f0e1\", \"M100.28 448H7.4V148.9h92.88zM53.79 108.1C24.09 108.1 0 83.5 0 53.8a53.79 53.79 0 0 1 107.58 0c0 29.7-24.1 54.3-53.79 54.3zM447.9 448h-92.68V302.4c0-34.7-.7-79.2-48.29-79.2-48.29 0-55.69 37.7-55.69 76.7V448h-92.78V148.9h89.08v40.8h1.3c12.4-23.5 42.69-48.3 87.88-48.3 94 0 111.28 61.9 111.28 142.3V448z\"],\n    \"linode\": [448, 512, [], \"f2b8\", \"M437.4 226.3c-.3-.9-.9-1.4-1.4-2l-70-38.6c-.9-.6-2-.6-3.1 0l-58.9 36c-.9.6-1.4 1.7-1.4 2.6l-.9 31.4-24-16c-.9-.6-2.3-.6-3.1 0L240 260.9l-1.4-35.1c0-.9-.6-2-1.4-2.3l-36-24.3 33.7-17.4c1.1-.6 1.7-1.7 1.7-2.9l-5.7-132.3c0-.9-.9-2-1.7-2.6L138.6.3c-.9-.3-1.7-.3-2.3-.3L12.6 38.6c-1.4.6-2.3 2-2 3.7L38 175.4c.9 3.4 34 27.4 38.6 30.9l-26.9 12.9c-1.4.9-2 2.3-1.7 3.4l20.6 100.3c.6 2.9 23.7 23.1 27.1 26.3l-17.4 10.6c-.9.6-1.7 2-1.4 3.1 1.4 7.1 15.4 77.7 16.9 79.1l65.1 69.1c.6.6 1.4.6 2.3.9.6 0 1.1-.3 1.7-.6l83.7-66.9c.9-.6 1.1-1.4 1.1-2.3l-2-46 28 23.7c1.1.9 2.9.9 4 0l66.9-53.4c.9-.6 1.1-1.4 1.1-2.3l2.3-33.4 20.3 14c1.1.9 2.6.9 3.7 0l54.6-43.7c.6-.3 1.1-1.1 1.1-2 .9-6.5 10.3-70.8 9.7-72.8zm-204.8 4.8l4 92.6-90.6 61.2-14-96.6 100.6-57.2zm-7.7-180l5.4 126-106.6 55.4L104 97.7l120.9-46.6zM44 173.1L18 48l79.7 49.4 19.4 132.9L44 173.1zm30.6 147.8L55.7 230l70 58.3 13.7 93.4-64.8-60.8zm24.3 117.7l-13.7-67.1 61.7 60.9 9.7 67.4-57.7-61.2zm64.5 64.5l-10.6-70.9 85.7-61.4 3.1 70-78.2 62.3zm82-115.1c0-3.4.9-22.9-2-25.1l-24.3-20 22.3-14.9c2.3-1.7 1.1-5.7 1.1-8l29.4 22.6.6 68.3-27.1-22.9zm94.3-25.4l-60.9 48.6-.6-68.6 65.7-46.9-4.2 66.9zm27.7-25.7l-19.1-13.4 2-34c.3-.9-.3-2-1.1-2.6L308 259.7l.6-30 64.6 40.6-5.8 66.6zm54.6-39.8l-48.3 38.3 5.7-65.1 51.1-36.6-8.5 63.4z\"],\n    \"linux\": [448, 512, [], \"f17c\", \"M220.8 123.3c1 .5 1.8 1.7 3 1.7 1.1 0 2.8-.4 2.9-1.5.2-1.4-1.9-2.3-3.2-2.9-1.7-.7-3.9-1-5.5-.1-.4.2-.8.7-.6 1.1.3 1.3 2.3 1.1 3.4 1.7zm-21.9 1.7c1.2 0 2-1.2 3-1.7 1.1-.6 3.1-.4 3.5-1.6.2-.4-.2-.9-.6-1.1-1.6-.9-3.8-.6-5.5.1-1.3.6-3.4 1.5-3.2 2.9.1 1 1.8 1.5 2.8 1.4zM420 403.8c-3.6-4-5.3-11.6-7.2-19.7-1.8-8.1-3.9-16.8-10.5-22.4-1.3-1.1-2.6-2.1-4-2.9-1.3-.8-2.7-1.5-4.1-2 9.2-27.3 5.6-54.5-3.7-79.1-11.4-30.1-31.3-56.4-46.5-74.4-17.1-21.5-33.7-41.9-33.4-72C311.1 85.4 315.7.1 234.8 0 132.4-.2 158 103.4 156.9 135.2c-1.7 23.4-6.4 41.8-22.5 64.7-18.9 22.5-45.5 58.8-58.1 96.7-6 17.9-8.8 36.1-6.2 53.3-6.5 5.8-11.4 14.7-16.6 20.2-4.2 4.3-10.3 5.9-17 8.3s-14 6-18.5 14.5c-2.1 3.9-2.8 8.1-2.8 12.4 0 3.9.6 7.9 1.2 11.8 1.2 8.1 2.5 15.7.8 20.8-5.2 14.4-5.9 24.4-2.2 31.7 3.8 7.3 11.4 10.5 20.1 12.3 17.3 3.6 40.8 2.7 59.3 12.5 19.8 10.4 39.9 14.1 55.9 10.4 11.6-2.6 21.1-9.6 25.9-20.2 12.5-.1 26.3-5.4 48.3-6.6 14.9-1.2 33.6 5.3 55.1 4.1.6 2.3 1.4 4.6 2.5 6.7v.1c8.3 16.7 23.8 24.3 40.3 23 16.6-1.3 34.1-11 48.3-27.9 13.6-16.4 36-23.2 50.9-32.2 7.4-4.5 13.4-10.1 13.9-18.3.4-8.2-4.4-17.3-15.5-29.7zM223.7 87.3c9.8-22.2 34.2-21.8 44-.4 6.5 14.2 3.6 30.9-4.3 40.4-1.6-.8-5.9-2.6-12.6-4.9 1.1-1.2 3.1-2.7 3.9-4.6 4.8-11.8-.2-27-9.1-27.3-7.3-.5-13.9 10.8-11.8 23-4.1-2-9.4-3.5-13-4.4-1-6.9-.3-14.6 2.9-21.8zM183 75.8c10.1 0 20.8 14.2 19.1 33.5-3.5 1-7.1 2.5-10.2 4.6 1.2-8.9-3.3-20.1-9.6-19.6-8.4.7-9.8 21.2-1.8 28.1 1 .8 1.9-.2-5.9 5.5-15.6-14.6-10.5-52.1 8.4-52.1zm-13.6 60.7c6.2-4.6 13.6-10 14.1-10.5 4.7-4.4 13.5-14.2 27.9-14.2 7.1 0 15.6 2.3 25.9 8.9 6.3 4.1 11.3 4.4 22.6 9.3 8.4 3.5 13.7 9.7 10.5 18.2-2.6 7.1-11 14.4-22.7 18.1-11.1 3.6-19.8 16-38.2 14.9-3.9-.2-7-1-9.6-2.1-8-3.5-12.2-10.4-20-15-8.6-4.8-13.2-10.4-14.7-15.3-1.4-4.9 0-9 4.2-12.3zm3.3 334c-2.7 35.1-43.9 34.4-75.3 18-29.9-15.8-68.6-6.5-76.5-21.9-2.4-4.7-2.4-12.7 2.6-26.4v-.2c2.4-7.6.6-16-.6-23.9-1.2-7.8-1.8-15 .9-20 3.5-6.7 8.5-9.1 14.8-11.3 10.3-3.7 11.8-3.4 19.6-9.9 5.5-5.7 9.5-12.9 14.3-18 5.1-5.5 10-8.1 17.7-6.9 8.1 1.2 15.1 6.8 21.9 16l19.6 35.6c9.5 19.9 43.1 48.4 41 68.9zm-1.4-25.9c-4.1-6.6-9.6-13.6-14.4-19.6 7.1 0 14.2-2.2 16.7-8.9 2.3-6.2 0-14.9-7.4-24.9-13.5-18.2-38.3-32.5-38.3-32.5-13.5-8.4-21.1-18.7-24.6-29.9s-3-23.3-.3-35.2c5.2-22.9 18.6-45.2 27.2-59.2 2.3-1.7.8 3.2-8.7 20.8-8.5 16.1-24.4 53.3-2.6 82.4.6-20.7 5.5-41.8 13.8-61.5 12-27.4 37.3-74.9 39.3-112.7 1.1.8 4.6 3.2 6.2 4.1 4.6 2.7 8.1 6.7 12.6 10.3 12.4 10 28.5 9.2 42.4 1.2 6.2-3.5 11.2-7.5 15.9-9 9.9-3.1 17.8-8.6 22.3-15 7.7 30.4 25.7 74.3 37.2 95.7 6.1 11.4 18.3 35.5 23.6 64.6 3.3-.1 7 .4 10.9 1.4 13.8-35.7-11.7-74.2-23.3-84.9-4.7-4.6-4.9-6.6-2.6-6.5 12.6 11.2 29.2 33.7 35.2 59 2.8 11.6 3.3 23.7.4 35.7 16.4 6.8 35.9 17.9 30.7 34.8-2.2-.1-3.2 0-4.2 0 3.2-10.1-3.9-17.6-22.8-26.1-19.6-8.6-36-8.6-38.3 12.5-12.1 4.2-18.3 14.7-21.4 27.3-2.8 11.2-3.6 24.7-4.4 39.9-.5 7.7-3.6 18-6.8 29-32.1 22.9-76.7 32.9-114.3 7.2zm257.4-11.5c-.9 16.8-41.2 19.9-63.2 46.5-13.2 15.7-29.4 24.4-43.6 25.5s-26.5-4.8-33.7-19.3c-4.7-11.1-2.4-23.1 1.1-36.3 3.7-14.2 9.2-28.8 9.9-40.6.8-15.2 1.7-28.5 4.2-38.7 2.6-10.3 6.6-17.2 13.7-21.1.3-.2.7-.3 1-.5.8 13.2 7.3 26.6 18.8 29.5 12.6 3.3 30.7-7.5 38.4-16.3 9-.3 15.7-.9 22.6 5.1 9.9 8.5 7.1 30.3 17.1 41.6 10.6 11.6 14 19.5 13.7 24.6zM173.3 148.7c2 1.9 4.7 4.5 8 7.1 6.6 5.2 15.8 10.6 27.3 10.6 11.6 0 22.5-5.9 31.8-10.8 4.9-2.6 10.9-7 14.8-10.4s5.9-6.3 3.1-6.6-2.6 2.6-6 5.1c-4.4 3.2-9.7 7.4-13.9 9.8-7.4 4.2-19.5 10.2-29.9 10.2s-18.7-4.8-24.9-9.7c-3.1-2.5-5.7-5-7.7-6.9-1.5-1.4-1.9-4.6-4.3-4.9-1.4-.1-1.8 3.7 1.7 6.5z\"],\n    \"lyft\": [512, 512, [], \"f3c3\", \"M0 81.1h77.8v208.7c0 33.1 15 52.8 27.2 61-12.7 11.1-51.2 20.9-80.2-2.8C7.8 334 0 310.7 0 289V81.1zm485.9 173.5v-22h23.8v-76.8h-26.1c-10.1-46.3-51.2-80.7-100.3-80.7-56.6 0-102.7 46-102.7 102.7V357c16 2.3 35.4-.3 51.7-14 17.1-14 24.8-37.2 24.8-59v-6.7h38.8v-76.8h-38.8v-23.3c0-34.6 52.2-34.6 52.2 0v77.1c0 56.6 46 102.7 102.7 102.7v-76.5c-14.5 0-26.1-11.7-26.1-25.9zm-294.3-99v113c0 15.4-23.8 15.4-23.8 0v-113H91v132.7c0 23.8 8 54 45 63.9 37 9.8 58.2-10.6 58.2-10.6-2.1 13.4-14.5 23.3-34.9 25.3-15.5 1.6-35.2-3.6-45-7.8v70.3c25.1 7.5 51.5 9.8 77.6 4.7 47.1-9.1 76.8-48.4 76.8-100.8V155.1h-77.1v.5z\"],\n    \"magento\": [448, 512, [], \"f3c4\", \"M445.7 127.9V384l-63.4 36.5V164.7L223.8 73.1 65.2 164.7l.4 255.9L2.3 384V128.1L224.2 0l221.5 127.9zM255.6 420.5L224 438.9l-31.8-18.2v-256l-63.3 36.6.1 255.9 94.9 54.9 95.1-54.9v-256l-63.4-36.6v255.9z\"],\n    \"mailchimp\": [448, 512, [], \"f59e\", \"M330.61 243.52a36.15 36.15 0 0 1 9.3 0c1.66-3.83 1.95-10.43.45-17.61-2.23-10.67-5.25-17.14-11.48-16.13s-6.47 8.74-4.24 19.42c1.26 6 3.49 11.14 6 14.32zM277.05 252c4.47 2 7.2 3.26 8.28 2.13 1.89-1.94-3.48-9.39-12.12-13.09a31.44 31.44 0 0 0-30.61 3.68c-3 2.18-5.81 5.22-5.41 7.06.85 3.74 10-2.71 22.6-3.48 7-.44 12.8 1.75 17.26 3.71zm-9 5.13c-9.07 1.42-15 6.53-13.47 10.1.9.34 1.17.81 5.21-.81a37 37 0 0 1 18.72-1.95c2.92.34 4.31.52 4.94-.49 1.46-2.22-5.71-8-15.39-6.85zm54.17 17.1c3.38-6.87-10.9-13.93-14.3-7s10.92 13.88 14.32 6.97zm15.66-20.47c-7.66-.13-7.95 15.8-.26 15.93s7.98-15.81.28-15.96zm-218.79 78.9c-1.32.31-6 1.45-8.47-2.35-5.2-8 11.11-20.38 3-35.77-9.1-17.47-27.82-13.54-35.05-5.54-8.71 9.6-8.72 23.54-5 24.08 4.27.57 4.08-6.47 7.38-11.63a12.83 12.83 0 0 1 17.85-3.72c11.59 7.59 1.37 17.76 2.28 28.62 1.39 16.68 18.42 16.37 21.58 9a2.08 2.08 0 0 0-.2-2.33c.03.89.68-1.3-3.35-.39zm299.72-17.07c-3.35-11.73-2.57-9.22-6.78-20.52 2.45-3.67 15.29-24-3.07-43.25-10.4-10.92-33.9-16.54-41.1-18.54-1.5-11.39 4.65-58.7-21.52-83 20.79-21.55 33.76-45.29 33.73-65.65-.06-39.16-48.15-51-107.42-26.47l-12.55 5.33c-.06-.05-22.71-22.27-23.05-22.57C169.5-18-41.77 216.81 25.78 273.85l14.76 12.51a72.49 72.49 0 0 0-4.1 33.5c3.36 33.4 36 60.42 67.53 60.38 57.73 133.06 267.9 133.28 322.29 3 1.74-4.47 9.11-24.61 9.11-42.38s-10.09-25.27-16.53-25.27zm-316 48.16c-22.82-.61-47.46-21.15-49.91-45.51-6.17-61.31 74.26-75.27 84-12.33 4.54 29.64-4.67 58.49-34.12 57.81zM84.3 249.55C69.14 252.5 55.78 261.09 47.6 273c-4.88-4.07-14-12-15.59-15-13.01-24.85 14.24-73 33.3-100.21C112.42 90.56 186.19 39.68 220.36 48.91c5.55 1.57 23.94 22.89 23.94 22.89s-34.15 18.94-65.8 45.35c-42.66 32.85-74.89 80.59-94.2 132.4zM323.18 350.7s-35.74 5.3-69.51-7.07c6.21-20.16 27 6.1 96.4-13.81 15.29-4.38 35.37-13 51-25.35a102.85 102.85 0 0 1 7.12 24.28c3.66-.66 14.25-.52 11.44 18.1-3.29 19.87-11.73 36-25.93 50.84A106.86 106.86 0 0 1 362.55 421a132.45 132.45 0 0 1-20.34 8.58c-53.51 17.48-108.3-1.74-126-43a66.33 66.33 0 0 1-3.55-9.74c-7.53-27.2-1.14-59.83 18.84-80.37 1.23-1.31 2.48-2.85 2.48-4.79a8.45 8.45 0 0 0-1.92-4.54c-7-10.13-31.19-27.4-26.33-60.83 3.5-24 24.49-40.91 44.07-39.91l5 .29c8.48.5 15.89 1.59 22.88 1.88 11.69.5 22.2-1.19 34.64-11.56 4.2-3.5 7.57-6.54 13.26-7.51a17.45 17.45 0 0 1 13.6 2.24c10 6.64 11.4 22.73 11.92 34.49.29 6.72 1.1 23 1.38 27.63.63 10.67 3.43 12.17 9.11 14 3.19 1.05 6.15 1.83 10.51 3.06 13.21 3.71 21 7.48 26 12.31a16.38 16.38 0 0 1 4.74 9.29c1.56 11.37-8.82 25.4-36.31 38.16-46.71 21.68-93.68 14.45-100.48 13.68-20.15-2.71-31.63 23.32-19.55 41.15 22.64 33.41 122.4 20 151.37-21.35.69-1 .12-1.59-.73-1-41.77 28.58-97.06 38.21-128.46 26-4.77-1.85-14.73-6.44-15.94-16.67 43.6 13.49 71 .74 71 .74s2.03-2.79-.56-2.53zm-68.47-5.7zm-83.4-187.5c16.74-19.35 37.36-36.18 55.83-45.63a.73.73 0 0 1 1 1c-1.46 2.66-4.29 8.34-5.19 12.65a.75.75 0 0 0 1.16.79c11.49-7.83 31.48-16.22 49-17.3a.77.77 0 0 1 .52 1.38 41.86 41.86 0 0 0-7.71 7.74.75.75 0 0 0 .59 1.19c12.31.09 29.66 4.4 41 10.74.76.43.22 1.91-.64 1.72-69.55-15.94-123.08 18.53-134.5 26.83a.76.76 0 0 1-1-1.12z\"],\n    \"mandalorian\": [448, 512, [], \"f50f\", \"M232.27 511.89c-1-3.26-1.69-15.83-1.39-24.58.55-15.89 1-24.72 1.4-28.76.64-6.2 2.87-20.72 3.28-21.38.6-1 .4-27.87-.24-33.13-.31-2.58-.63-11.9-.69-20.73-.13-16.47-.53-20.12-2.73-24.76-1.1-2.32-1.23-3.84-1-11.43a92.38 92.38 0 0 0-.34-12.71c-2-13-3.46-27.7-3.25-33.9s.43-7.15 2.06-9.67c3.05-4.71 6.51-14 8.62-23.27 2.26-9.86 3.88-17.18 4.59-20.74a109.54 109.54 0 0 1 4.42-15.05c2.27-6.25 2.49-15.39.37-15.39-.3 0-1.38 1.22-2.41 2.71s-4.76 4.8-8.29 7.36c-8.37 6.08-11.7 9.39-12.66 12.58s-1 7.23-.16 7.76c.34.21 1.29 2.4 2.11 4.88a28.83 28.83 0 0 1 .72 15.36c-.39 1.77-1 5.47-1.46 8.23s-1 6.46-1.25 8.22a9.85 9.85 0 0 1-1.55 4.26c-1 1-1.14.91-2.05-.53a14.87 14.87 0 0 1-1.44-4.75c-.25-1.74-1.63-7.11-3.08-11.93-3.28-10.9-3.52-16.15-1-21a14.24 14.24 0 0 0 1.67-4.61c0-2.39-2.2-5.32-7.41-9.89-7-6.18-8.63-7.92-10.23-11.3-1.71-3.6-3.06-4.06-4.54-1.54-1.78 3-2.6 9.11-3 22l-.34 12.19 2 2.25c3.21 3.7 12.07 16.45 13.78 19.83 3.41 6.74 4.34 11.69 4.41 23.56s.95 22.75 2 24.71c.36.66.51 1.35.34 1.52s.41 2.09 1.29 4.27a38.14 38.14 0 0 1 2.06 9 91 91 0 0 0 1.71 10.37c2.23 9.56 2.77 14.08 2.39 20.14-.2 3.27-.53 11.07-.73 17.32-1.31 41.76-1.85 58-2 61.21-.12 2-.39 11.51-.6 21.07-.36 16.3-1.3 27.37-2.42 28.65-.64.73-8.07-4.91-12.52-9.49-3.75-3.87-4-4.79-2.83-9.95.7-3 2.26-18.29 3.33-32.62.36-4.78.81-10.5 1-12.71.83-9.37 1.66-20.35 2.61-34.78.56-8.46 1.33-16.44 1.72-17.73s.89-9.89 1.13-19.11l.43-16.77-2.26-4.3c-1.72-3.28-4.87-6.94-13.22-15.34-6-6.07-11.84-12.3-12.91-13.85l-1.95-2.81.75-10.9c1.09-15.71 1.1-48.57 0-59.06l-.89-8.7-3.28-4.52c-5.86-8.08-5.8-7.75-6.22-33.27-.1-6.07-.38-11.5-.63-12.06-.83-1.87-3.05-2.66-8.54-3.05-8.86-.62-11-1.9-23.85-14.55-6.15-6-12.34-12-13.75-13.19-2.81-2.42-2.79-2-.56-9.63l1.35-4.65-1.69-3a32.22 32.22 0 0 0-2.59-4.07c-1.33-1.51-5.5-10.89-6-13.49a4.24 4.24 0 0 1 .87-3.9c2.23-2.86 3.4-5.68 4.45-10.73 2.33-11.19 7.74-26.09 10.6-29.22 3.18-3.47 7.7-1 9.41 5 1.34 4.79 1.37 9.79.1 18.55a101.2 101.2 0 0 0-1 11.11c0 4 .19 4.69 2.25 7.39 3.33 4.37 7.73 7.41 15.2 10.52a18.67 18.67 0 0 1 4.72 2.85c11.17 10.72 18.62 16.18 22.95 16.85 5.18.8 8 4.54 10 13.39 1.31 5.65 4 11.14 5.46 11.14a9.38 9.38 0 0 0 3.33-1.39c2-1.22 2.25-1.73 2.25-4.18a132.88 132.88 0 0 0-2-17.84c-.37-1.66-.78-4.06-.93-5.35s-.61-3.85-1-5.69c-2.55-11.16-3.65-15.46-4.1-16-1.55-2-4.08-10.2-4.93-15.92-1.64-11.11-4-14.23-12.91-17.39A43.15 43.15 0 0 1 165.24 78c-1.15-1-4-3.22-6.35-5.06s-4.41-3.53-4.6-3.76a22.7 22.7 0 0 0-2.69-2c-6.24-4.22-8.84-7-11.26-12l-2.44-5-.22-13-.22-13 6.91-6.55c3.95-3.75 8.48-7.35 10.59-8.43 3.31-1.69 4.45-1.89 11.37-2 8.53-.19 10.12 0 11.66 1.56s1.36 6.4-.29 8.5a6.66 6.66 0 0 0-1.34 2.32c0 .58-2.61 4.91-5.42 9a30.39 30.39 0 0 0-2.37 6.82c20.44 13.39 21.55 3.77 14.07 29L194 66.92c3.11-8.66 6.47-17.26 8.61-26.22.29-7.63-12-4.19-15.4-8.68-2.33-5.93 3.13-14.18 6.06-19.2 1.6-2.34 6.62-4.7 8.82-4.15.88.22 4.16-.35 7.37-1.28a45.3 45.3 0 0 1 7.55-1.68 29.57 29.57 0 0 0 6-1.29c3.65-1.11 4.5-1.17 6.35-.4a29.54 29.54 0 0 0 5.82 1.36 18.18 18.18 0 0 1 6 1.91 22.67 22.67 0 0 0 5 2.17c2.51.68 3 .57 7.05-1.67l4.35-2.4L268.32 5c10.44-.4 10.81-.47 15.26-2.68L288.16 0l2.46 1.43c1.76 1 3.14 2.73 4.85 6 2.36 4.51 2.38 4.58 1.37 7.37-.88 2.44-.89 3.3-.1 6.39a35.76 35.76 0 0 0 2.1 5.91 13.55 13.55 0 0 1 1.31 4c.31 4.33 0 5.3-2.41 6.92-2.17 1.47-7 7.91-7 9.34a14.77 14.77 0 0 1-1.07 3c-5 11.51-6.76 13.56-14.26 17-9.2 4.2-12.3 5.19-16.21 5.19-3.1 0-4 .25-4.54 1.26a18.33 18.33 0 0 1-4.09 3.71 13.62 13.62 0 0 0-4.38 4.78 5.89 5.89 0 0 1-2.49 2.91 6.88 6.88 0 0 0-2.45 1.71 67.62 67.62 0 0 1-7 5.38c-3.33 2.34-6.87 5-7.87 6A7.27 7.27 0 0 1 224 100a5.76 5.76 0 0 0-2.13 1.65c-1.31 1.39-1.49 2.11-1.14 4.6a36.45 36.45 0 0 0 1.42 5.88c1.32 3.8 1.31 7.86 0 10.57s-.89 6.65 1.35 9.59c2 2.63 2.16 4.56.71 8.84a33.45 33.45 0 0 0-1.06 8.91c0 4.88.22 6.28 1.46 8.38s1.82 2.48 3.24 2.32c2-.23 2.3-1.05 4.71-12.12 2.18-10 3.71-11.92 13.76-17.08 2.94-1.51 7.46-4 10-5.44s6.79-3.69 9.37-4.91a40.09 40.09 0 0 0 15.22-11.67c7.11-8.79 10-16.22 12.85-33.3a18.37 18.37 0 0 1 2.86-7.73 20.39 20.39 0 0 0 2.89-7.31c1-5.3 2.85-9.08 5.58-11.51 4.7-4.18 6-1.09 4.59 10.87-.46 3.86-1.1 10.33-1.44 14.38l-.61 7.36 4.45 4.09 4.45 4.09.11 8.42c.06 4.63.47 9.53.92 10.89l.82 2.47-6.43 6.28c-8.54 8.33-12.88 13.93-16.76 21.61-1.77 3.49-3.74 7.11-4.38 8-2.18 3.11-6.46 13-8.76 20.26l-2.29 7.22-7 6.49c-3.83 3.57-8 7.25-9.17 8.17-3.05 2.32-4.26 5.15-4.26 10a14.62 14.62 0 0 0 1.59 7.26 42 42 0 0 1 2.09 4.83 9.28 9.28 0 0 0 1.57 2.89c1.4 1.59 1.92 16.12.83 23.22-.68 4.48-3.63 12-4.7 12-1.79 0-4.06 9.27-5.07 20.74-.18 2-.62 5.94-1 8.7s-1 10-1.35 16.05c-.77 12.22-.19 18.77 2 23.15 3.41 6.69.52 12.69-11 22.84l-4 3.49.07 5.19a40.81 40.81 0 0 0 1.14 8.87c4.61 16 4.73 16.92 4.38 37.13-.46 26.4-.26 40.27.63 44.15a61.31 61.31 0 0 1 1.08 7c.17 2 .66 5.33 1.08 7.36.47 2.26.78 11 .79 22.74v19.06l-1.81 2.63c-2.71 3.91-15.11 13.54-15.49 12.29zm29.53-45.11c-.18-.3-.33-6.87-.33-14.59 0-14.06-.89-27.54-2.26-34.45-.4-2-.81-9.7-.9-17.06-.15-11.93-1.4-24.37-2.64-26.38-.66-1.07-3-17.66-3-21.3 0-4.23 1-6 5.28-9.13s4.86-3.14 5.48-.72c.28 1.1 1.45 5.62 2.6 10 3.93 15.12 4.14 16.27 4.05 21.74-.1 5.78-.13 6.13-1.74 17.73-1 7.07-1.17 12.39-1 28.43.17 19.4-.64 35.73-2 41.27-.71 2.78-2.8 5.48-3.43 4.43zm-71-37.58a101 101 0 0 1-1.73-10.79 100.5 100.5 0 0 0-1.73-10.79 37.53 37.53 0 0 1-1-6.49c-.31-3.19-.91-7.46-1.33-9.48-1-4.79-3.35-19.35-3.42-21.07 0-.74-.34-4.05-.7-7.36-.67-6.21-.84-27.67-.22-28.29 1-1 6.63 2.76 11.33 7.43l5.28 5.25-.45 6.47c-.25 3.56-.6 10.23-.78 14.83s-.49 9.87-.67 11.71-.61 9.36-.94 16.72c-.79 17.41-1.94 31.29-2.65 32a.62.62 0 0 1-1-.14zm-87.18-266.59c21.07 12.79 17.84 14.15 28.49 17.66 13 4.29 18.87 7.13 23.15 16.87C111.6 233.28 86.25 255 78.55 268c-31 52-6 101.59 62.75 87.21-14.18 29.23-78 28.63-98.68-4.9-24.68-39.95-22.09-118.3 61-187.66zm210.79 179c56.66 6.88 82.32-37.74 46.54-89.23 0 0-26.87-29.34-64.28-68 3-15.45 9.49-32.12 30.57-53.82 89.2 63.51 92 141.61 92.46 149.36 4.3 70.64-78.7 91.18-105.29 61.71z\"],\n    \"markdown\": [640, 512, [], \"f60f\", \"M593.8 59.1H46.2C20.7 59.1 0 79.8 0 105.2v301.5c0 25.5 20.7 46.2 46.2 46.2h547.7c25.5 0 46.2-20.7 46.1-46.1V105.2c0-25.4-20.7-46.1-46.2-46.1zM338.5 360.6H277v-120l-61.5 76.9-61.5-76.9v120H92.3V151.4h61.5l61.5 76.9 61.5-76.9h61.5v209.2zm135.3 3.1L381.5 256H443V151.4h61.5V256H566z\"],\n    \"mastodon\": [448, 512, [], \"f4f6\", \"M433 179.11c0-97.2-63.71-125.7-63.71-125.7-62.52-28.7-228.56-28.4-290.48 0 0 0-63.72 28.5-63.72 125.7 0 115.7-6.6 259.4 105.63 289.1 40.51 10.7 75.32 13 103.33 11.4 50.81-2.8 79.32-18.1 79.32-18.1l-1.7-36.9s-36.31 11.4-77.12 10.1c-40.41-1.4-83-4.4-89.63-54a102.54 102.54 0 0 1-.9-13.9c85.63 20.9 158.65 9.1 178.75 6.7 56.12-6.7 105-41.3 111.23-72.9 9.8-49.8 9-121.5 9-121.5zm-75.12 125.2h-46.63v-114.2c0-49.7-64-51.6-64 6.9v62.5h-46.33V197c0-58.5-64-56.6-64-6.9v114.2H90.19c0-122.1-5.2-147.9 18.41-175 25.9-28.9 79.82-30.8 103.83 6.1l11.6 19.5 11.6-19.5c24.11-37.1 78.12-34.8 103.83-6.1 23.71 27.3 18.4 53 18.4 175z\"],\n    \"maxcdn\": [512, 512, [], \"f136\", \"M461.1 442.7h-97.4L415.6 200c2.3-10.2.9-19.5-4.4-25.7-5-6.1-13.7-9.6-24.2-9.6h-49.3l-59.5 278h-97.4l59.5-278h-83.4l-59.5 278H0l59.5-278-44.6-95.4H387c39.4 0 75.3 16.3 98.3 44.9 23.3 28.6 31.8 67.4 23.6 105.9l-47.8 222.6z\"],\n    \"medapps\": [320, 512, [], \"f3c6\", \"M118.3 238.4c3.5-12.5 6.9-33.6 13.2-33.6 8.3 1.8 9.6 23.4 18.6 36.6 4.6-23.5 5.3-85.1 14.1-86.7 9-.7 19.7 66.5 22 77.5 9.9 4.1 48.9 6.6 48.9 6.6 1.9 7.3-24 7.6-40 7.8-4.6 14.8-5.4 27.7-11.4 28-4.7.2-8.2-28.8-17.5-49.6l-9.4 65.5c-4.4 13-15.5-22.5-21.9-39.3-3.3-.1-62.4-1.6-47.6-7.8l31-5zM228 448c21.2 0 21.2-32 0-32H92c-21.2 0-21.2 32 0 32h136zm-24 64c21.2 0 21.2-32 0-32h-88c-21.2 0-21.2 32 0 32h88zm34.2-141.5c3.2-18.9 5.2-36.4 11.9-48.8 7.9-14.7 16.1-28.1 24-41 24.6-40.4 45.9-75.2 45.9-125.5C320 69.6 248.2 0 160 0S0 69.6 0 155.2c0 50.2 21.3 85.1 45.9 125.5 7.9 12.9 16 26.3 24 41 6.7 12.5 8.7 29.8 11.9 48.9 3.5 21 36.1 15.7 32.6-5.1-3.6-21.7-5.6-40.7-15.3-58.6C66.5 246.5 33 211.3 33 155.2 33 87.3 90 32 160 32s127 55.3 127 123.2c0 56.1-33.5 91.3-66.1 151.6-9.7 18-11.7 37.4-15.3 58.6-3.4 20.6 29 26.4 32.6 5.1z\"],\n    \"medium\": [448, 512, [], \"f23a\", \"M0 32v448h448V32H0zm372.2 106.1l-24 23c-2.1 1.6-3.1 4.2-2.7 6.7v169.3c-.4 2.6.6 5.2 2.7 6.7l23.5 23v5.1h-118V367l24.3-23.6c2.4-2.4 2.4-3.1 2.4-6.7V199.8l-67.6 171.6h-9.1L125 199.8v115c-.7 4.8 1 9.7 4.4 13.2l31.6 38.3v5.1H71.2v-5.1l31.6-38.3c3.4-3.5 4.9-8.4 4.1-13.2v-133c.4-3.7-1-7.3-3.8-9.8L75 138.1V133h87.3l67.4 148L289 133.1h83.2v5z\"],\n    \"medium-m\": [512, 512, [], \"f3c7\", \"M71.5 142.3c.6-5.9-1.7-11.8-6.1-15.8L20.3 72.1V64h140.2l108.4 237.7L364.2 64h133.7v8.1l-38.6 37c-3.3 2.5-5 6.7-4.3 10.8v272c-.7 4.1 1 8.3 4.3 10.8l37.7 37v8.1H307.3v-8.1l39.1-37.9c3.8-3.8 3.8-5 3.8-10.8V171.2L241.5 447.1h-14.7L100.4 171.2v184.9c-1.1 7.8 1.5 15.6 7 21.2l50.8 61.6v8.1h-144v-8L65 377.3c5.4-5.6 7.9-13.5 6.5-21.2V142.3z\"],\n    \"medrt\": [544, 512, [], \"f3c8\", \"M113.7 256c0 121.8 83.9 222.8 193.5 241.1-18.7 4.5-38.2 6.9-58.2 6.9C111.4 504 0 393 0 256S111.4 8 248.9 8c20.1 0 39.6 2.4 58.2 6.9C197.5 33.2 113.7 134.2 113.7 256m297.4 100.3c-77.7 55.4-179.6 47.5-240.4-14.6 5.5 14.1 12.7 27.7 21.7 40.5 61.6 88.2 182.4 109.3 269.7 47 87.3-62.3 108.1-184.3 46.5-272.6-9-12.9-19.3-24.3-30.5-34.2 37.4 78.8 10.7 178.5-67 233.9m-218.8-244c-1.4 1-2.7 2.1-4 3.1 64.3-17.8 135.9 4 178.9 60.5 35.7 47 42.9 106.6 24.4 158 56.7-56.2 67.6-142.1 22.3-201.8-50-65.5-149.1-74.4-221.6-19.8M296 224c-4.4 0-8-3.6-8-8v-40c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v40c0 4.4-3.6 8-8 8h-40c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h40c4.4 0 8 3.6 8 8v40c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-40c0-4.4 3.6-8 8-8h40c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8h-40z\"],\n    \"meetup\": [512, 512, [], \"f2e0\", \"M99 414.3c1.1 5.7-2.3 11.1-8 12.3-5.4 1.1-10.9-2.3-12-8-1.1-5.4 2.3-11.1 7.7-12.3 5.4-1.2 11.1 2.3 12.3 8zm143.1 71.4c-6.3 4.6-8 13.4-3.7 20 4.6 6.6 13.4 8.3 20 3.7 6.3-4.6 8-13.4 3.4-20-4.2-6.5-13.1-8.3-19.7-3.7zm-86-462.3c6.3-1.4 10.3-7.7 8.9-14-1.1-6.6-7.4-10.6-13.7-9.1-6.3 1.4-10.3 7.7-9.1 14 1.4 6.6 7.6 10.6 13.9 9.1zM34.4 226.3c-10-6.9-23.7-4.3-30.6 6-6.9 10-4.3 24 5.7 30.9 10 7.1 23.7 4.6 30.6-5.7 6.9-10.4 4.3-24.1-5.7-31.2zm272-170.9c10.6-6.3 13.7-20 7.7-30.3-6.3-10.6-19.7-14-30-7.7s-13.7 20-7.4 30.6c6 10.3 19.4 13.7 29.7 7.4zm-191.1 58c7.7-5.4 9.4-16 4.3-23.7s-15.7-9.4-23.1-4.3c-7.7 5.4-9.4 16-4.3 23.7 5.1 7.8 15.6 9.5 23.1 4.3zm372.3 156c-7.4 1.7-12.3 9.1-10.6 16.9 1.4 7.4 8.9 12.3 16.3 10.6 7.4-1.4 12.3-8.9 10.6-16.6-1.5-7.4-8.9-12.3-16.3-10.9zm39.7-56.8c-1.1-5.7-6.6-9.1-12-8-5.7 1.1-9.1 6.9-8 12.6 1.1 5.4 6.6 9.1 12.3 8 5.4-1.5 9.1-6.9 7.7-12.6zM447 138.9c-8.6 6-10.6 17.7-4.9 26.3 5.7 8.6 17.4 10.6 26 4.9 8.3-6 10.3-17.7 4.6-26.3-5.7-8.7-17.4-10.9-25.7-4.9zm-6.3 139.4c26.3 43.1 15.1 100-26.3 129.1-17.4 12.3-37.1 17.7-56.9 17.1-12 47.1-69.4 64.6-105.1 32.6-1.1.9-2.6 1.7-3.7 2.9-39.1 27.1-92.3 17.4-119.4-22.3-9.7-14.3-14.6-30.6-15.1-46.9-65.4-10.9-90-94-41.1-139.7-28.3-46.9.6-107.4 53.4-114.9C151.6 70 234.1 38.6 290.1 82c67.4-22.3 136.3 29.4 130.9 101.1 41.1 12.6 52.8 66.9 19.7 95.2zm-70 74.3c-3.1-20.6-40.9-4.6-43.1-27.1-3.1-32 43.7-101.1 40-128-3.4-24-19.4-29.1-33.4-29.4-13.4-.3-16.9 2-21.4 4.6-2.9 1.7-6.6 4.9-11.7-.3-6.3-6-11.1-11.7-19.4-12.9-12.3-2-17.7 2-26.6 9.7-3.4 2.9-12 12.9-20 9.1-3.4-1.7-15.4-7.7-24-11.4-16.3-7.1-40 4.6-48.6 20-12.9 22.9-38 113.1-41.7 125.1-8.6 26.6 10.9 48.6 36.9 47.1 11.1-.6 18.3-4.6 25.4-17.4 4-7.4 41.7-107.7 44.6-112.6 2-3.4 8.9-8 14.6-5.1 5.7 3.1 6.9 9.4 6 15.1-1.1 9.7-28 70.9-28.9 77.7-3.4 22.9 26.9 26.6 38.6 4 3.7-7.1 45.7-92.6 49.4-98.3 4.3-6.3 7.4-8.3 11.7-8 3.1 0 8.3.9 7.1 10.9-1.4 9.4-35.1 72.3-38.9 87.7-4.6 20.6 6.6 41.4 24.9 50.6 11.4 5.7 62.5 15.7 58.5-11.1zm5.7 92.3c-10.3 7.4-12.9 22-5.7 32.6 7.1 10.6 21.4 13.1 32 6 10.6-7.4 13.1-22 6-32.6-7.4-10.6-21.7-13.5-32.3-6z\"],\n    \"megaport\": [496, 512, [], \"f5a3\", \"M214.5 209.6v66.2l33.5 33.5 33.3-33.3v-66.4l-33.4-33.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm145.1 414.4L367 441.6l-26-19.2v-65.5l-33.4-33.4-33.4 33.4v65.5L248 441.6l-26.1-19.2v-65.5l-33.4-33.4-33.5 33.4v65.5l-26.1 19.2-26.1-19.2v-87l59.5-59.5V188l59.5-59.5V52.9l26.1-19.2L274 52.9v75.6l59.5 59.5v87.6l59.7 59.7v87.1z\"],\n    \"mendeley\": [640, 512, [], \"f7b3\", \"M624.6 325.2c-12.3-12.4-29.7-19.2-48.4-17.2-43.3-1-49.7-34.9-37.5-98.8 22.8-57.5-14.9-131.5-87.4-130.8-77.4.7-81.7 82-130.9 82-48.1 0-54-81.3-130.9-82-72.9-.8-110.1 73.3-87.4 130.8 12.2 63.9 5.8 97.8-37.5 98.8-21.2-2.3-37 6.5-53 22.5-19.9 19.7-19.3 94.8 42.6 102.6 47.1 5.9 81.6-42.9 61.2-87.8-47.3-103.7 185.9-106.1 146.5-8.2-.1.1-.2.2-.3.4-26.8 42.8 6.8 97.4 58.8 95.2 52.1 2.1 85.4-52.6 58.8-95.2-.1-.2-.2-.3-.3-.4-39.4-97.9 193.8-95.5 146.5 8.2-4.6 10-6.7 21.3-5.7 33 4.9 53.4 68.7 74.1 104.9 35.2 17.8-14.8 23.1-65.6 0-88.3zm-303.9-19.1h-.6c-43.4 0-62.8-37.5-62.8-62.8 0-34.7 28.2-62.8 62.8-62.8h.6c34.7 0 62.8 28.1 62.8 62.8 0 25-19.2 62.8-62.8 62.8z\"],\n    \"microsoft\": [448, 512, [], \"f3ca\", \"M0 32h214.6v214.6H0V32zm233.4 0H448v214.6H233.4V32zM0 265.4h214.6V480H0V265.4zm233.4 0H448V480H233.4V265.4z\"],\n    \"mix\": [448, 512, [], \"f3cb\", \"M0 64v348.9c0 56.2 88 58.1 88 0V174.3c7.9-52.9 88-50.4 88 6.5v175.3c0 57.9 96 58 96 0V240c5.3-54.7 88-52.5 88 4.3v23.8c0 59.9 88 56.6 88 0V64H0z\"],\n    \"mixcloud\": [640, 512, [], \"f289\", \"M424.43 219.729C416.124 134.727 344.135 68 256.919 68c-72.266 0-136.224 46.516-159.205 114.074-54.545 8.029-96.63 54.822-96.63 111.582 0 62.298 50.668 112.966 113.243 112.966h289.614c52.329 0 94.969-42.362 94.969-94.693 0-45.131-32.118-83.063-74.48-92.2zm-20.489 144.53H114.327c-39.04 0-70.881-31.564-70.881-70.604s31.841-70.604 70.881-70.604c18.827 0 36.548 7.475 49.838 20.766 19.963 19.963 50.133-10.227 30.18-30.18-14.675-14.398-32.672-24.365-52.053-29.349 19.935-44.3 64.79-73.926 114.628-73.926 69.496 0 125.979 56.483 125.979 125.702 0 13.568-2.215 26.857-6.369 39.594-8.943 27.517 32.133 38.939 40.147 13.29 2.769-8.306 4.984-16.889 6.369-25.472 19.381 7.476 33.502 26.303 33.502 48.453 0 28.795-23.535 52.33-52.607 52.33zm235.069-52.33c0 44.024-12.737 86.386-37.102 122.657-4.153 6.092-10.798 9.414-17.72 9.414-16.317 0-27.127-18.826-17.443-32.949 19.381-29.349 29.903-63.682 29.903-99.122s-10.521-69.773-29.903-98.845c-15.655-22.831 19.361-47.24 35.163-23.534 24.366 35.993 37.102 78.356 37.102 122.379zm-70.88 0c0 31.565-9.137 62.021-26.857 88.325-4.153 6.091-10.798 9.136-17.72 9.136-17.201 0-27.022-18.979-17.443-32.948 13.013-19.104 19.658-41.255 19.658-64.513 0-22.981-6.645-45.408-19.658-64.512-15.761-22.986 19.008-47.095 35.163-23.535 17.719 26.026 26.857 56.483 26.857 88.047z\"],\n    \"mizuni\": [496, 512, [], \"f3cc\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm-80 351.9c-31.4 10.6-58.8 27.3-80 48.2V136c0-22.1 17.9-40 40-40s40 17.9 40 40v223.9zm120-9.9c-12.9-2-26.2-3.1-39.8-3.1-13.8 0-27.2 1.1-40.2 3.1V136c0-22.1 17.9-40 40-40s40 17.9 40 40v214zm120 57.7c-21.2-20.8-48.6-37.4-80-48V136c0-22.1 17.9-40 40-40s40 17.9 40 40v271.7z\"],\n    \"modx\": [448, 512, [], \"f285\", \"M356 241.8l36.7 23.7V480l-133-83.8L356 241.8zM440 75H226.3l-23 37.8 153.5 96.5L440 75zm-89 142.8L55.2 32v214.5l46 29L351 217.8zM97 294.2L8 437h213.7l125-200.5L97 294.2z\"],\n    \"monero\": [496, 512, [], \"f3d0\", \"M352 384h108.4C417 455.9 338.1 504 248 504S79 455.9 35.6 384H144V256.2L248 361l104-105v128zM88 336V128l159.4 159.4L408 128v208h74.8c8.5-25.1 13.2-52 13.2-80C496 119 385 8 248 8S0 119 0 256c0 28 4.6 54.9 13.2 80H88z\"],\n    \"napster\": [496, 512, [], \"f3d2\", \"M298.3 373.6c-14.2 13.6-31.3 24.1-50.4 30.5-19-6.4-36.2-16.9-50.3-30.5h100.7zm44-199.6c20-16.9 43.6-29.2 69.6-36.2V299c0 219.4-328 217.6-328 .3V137.7c25.9 6.9 49.6 19.6 69.5 36.4 56.8-40 132.5-39.9 188.9-.1zm-208.8-58.5c64.4-60 164.3-60.1 228.9-.2-7.1 3.5-13.9 7.3-20.6 11.5-58.7-30.5-129.2-30.4-187.9.1-6.3-4-13.9-8.2-20.4-11.4zM43.8 93.2v69.3c-58.4 36.5-58.4 121.1.1 158.3 26.4 245.1 381.7 240.3 407.6 1.5l.3-1.7c58.7-36.3 58.9-121.7.2-158.2V93.2c-17.3.5-34 3-50.1 7.4-82-91.5-225.5-91.5-307.5.1-16.3-4.4-33.1-7-50.6-7.5zM259.2 352s36-.3 61.3-1.5c10.2-.5 21.1-4 25.5-6.5 26.3-15.1 25.4-39.2 26.2-47.4-79.5-.6-99.9-3.9-113 55.4zm-135.5-55.3c.8 8.2-.1 32.3 26.2 47.4 4.4 2.5 15.2 6 25.5 6.5 25.3 1.1 61.3 1.5 61.3 1.5-13.2-59.4-33.7-56.1-113-55.4zm169.1 123.4c-3.2-5.3-6.9-7.3-6.9-7.3-24.8 7.3-52.2 6.9-75.9 0 0 0-2.9 1.5-6.4 6.6-2.8 4.1-3.7 9.6-3.7 9.6 29.1 17.6 67.1 17.6 96.2 0-.1-.1-.3-4-3.3-8.9z\"],\n    \"neos\": [512, 512, [], \"f612\", \"M415.44 512h-95.11L212.12 357.46v91.1L125.69 512H28V29.82L68.47 0h108.05l123.74 176.13V63.45L386.69 0h97.69v461.5zM38.77 35.27V496l72-52.88V194l215.5 307.64h84.79l52.35-38.17h-78.27L69 13zm82.54 466.61l80-58.78v-101l-79.76-114.4v220.94L49 501.89h72.34zM80.63 10.77l310.6 442.57h82.37V10.77h-79.75v317.56L170.91 10.77zM311 191.65l72 102.81V15.93l-72 53v122.72z\"],\n    \"nimblr\": [384, 512, [], \"f5a8\", \"M246.6 299.29c15.57 0 27.15 11.46 27.15 27s-11.62 27-27.15 27c-15.7 0-27.15-11.57-27.15-27s11.55-27 27.15-27zM113 326.25c0-15.61 11.68-27 27.15-27s27.15 11.46 27.15 27-11.47 27-27.15 27c-15.44 0-27.15-11.31-27.15-27M191.76 159C157 159 89.45 178.77 59.25 227L14 0v335.48C14 433.13 93.61 512 191.76 512s177.76-78.95 177.76-176.52S290.13 159 191.76 159zm0 308.12c-73.27 0-132.51-58.9-132.51-131.59s59.24-131.59 132.51-131.59 132.51 58.86 132.51 131.54S265 467.07 191.76 467.07z\"],\n    \"node\": [640, 512, [], \"f419\", \"M316.3 452c-2.1 0-4.2-.6-6.1-1.6L291 439c-2.9-1.6-1.5-2.2-.5-2.5 3.8-1.3 4.6-1.6 8.7-4 .4-.2 1-.1 1.4.1l14.8 8.8c.5.3 1.3.3 1.8 0L375 408c.5-.3.9-.9.9-1.6v-66.7c0-.7-.3-1.3-.9-1.6l-57.8-33.3c-.5-.3-1.2-.3-1.8 0l-57.8 33.3c-.6.3-.9 1-.9 1.6v66.7c0 .6.4 1.2.9 1.5l15.8 9.1c8.6 4.3 13.9-.8 13.9-5.8v-65.9c0-.9.7-1.7 1.7-1.7h7.3c.9 0 1.7.7 1.7 1.7v65.9c0 11.5-6.2 18-17.1 18-3.3 0-6 0-13.3-3.6l-15.2-8.7c-3.7-2.2-6.1-6.2-6.1-10.5v-66.7c0-4.3 2.3-8.4 6.1-10.5l57.8-33.4c3.7-2.1 8.5-2.1 12.1 0l57.8 33.4c3.7 2.2 6.1 6.2 6.1 10.5v66.7c0 4.3-2.3 8.4-6.1 10.5l-57.8 33.4c-1.7 1.1-3.8 1.7-6 1.7zm46.7-65.8c0-12.5-8.4-15.8-26.2-18.2-18-2.4-19.8-3.6-19.8-7.8 0-3.5 1.5-8.1 14.8-8.1 11.9 0 16.3 2.6 18.1 10.6.2.8.8 1.3 1.6 1.3h7.5c.5 0 .9-.2 1.2-.5.3-.4.5-.8.4-1.3-1.2-13.8-10.3-20.2-28.8-20.2-16.5 0-26.3 7-26.3 18.6 0 12.7 9.8 16.1 25.6 17.7 18.9 1.9 20.4 4.6 20.4 8.3 0 6.5-5.2 9.2-17.4 9.2-15.3 0-18.7-3.8-19.8-11.4-.1-.8-.8-1.4-1.7-1.4h-7.5c-.9 0-1.7.7-1.7 1.7 0 9.7 5.3 21.3 30.6 21.3 18.5 0 29-7.2 29-19.8zm54.5-50.1c0 6.1-5 11.1-11.1 11.1s-11.1-5-11.1-11.1c0-6.3 5.2-11.1 11.1-11.1 6-.1 11.1 4.8 11.1 11.1zm-1.8 0c0-5.2-4.2-9.3-9.4-9.3-5.1 0-9.3 4.1-9.3 9.3 0 5.2 4.2 9.4 9.3 9.4 5.2-.1 9.4-4.3 9.4-9.4zm-4.5 6.2h-2.6c-.1-.6-.5-3.8-.5-3.9-.2-.7-.4-1.1-1.3-1.1h-2.2v5h-2.4v-12.5h4.3c1.5 0 4.4 0 4.4 3.3 0 2.3-1.5 2.8-2.4 3.1 1.7.1 1.8 1.2 2.1 2.8.1 1 .3 2.7.6 3.3zm-2.8-8.8c0-1.7-1.2-1.7-1.8-1.7h-2v3.5h1.9c1.6 0 1.9-1.1 1.9-1.8zM137.3 191c0-2.7-1.4-5.1-3.7-6.4l-61.3-35.3c-1-.6-2.2-.9-3.4-1h-.6c-1.2 0-2.3.4-3.4 1L3.7 184.6C1.4 185.9 0 188.4 0 191l.1 95c0 1.3.7 2.5 1.8 3.2 1.1.7 2.5.7 3.7 0L42 268.3c2.3-1.4 3.7-3.8 3.7-6.4v-44.4c0-2.6 1.4-5.1 3.7-6.4l15.5-8.9c1.2-.7 2.4-1 3.7-1 1.3 0 2.6.3 3.7 1l15.5 8.9c2.3 1.3 3.7 3.8 3.7 6.4v44.4c0 2.6 1.4 5.1 3.7 6.4l36.4 20.9c1.1.7 2.6.7 3.7 0 1.1-.6 1.8-1.9 1.8-3.2l.2-95zM472.5 87.3v176.4c0 2.6-1.4 5.1-3.7 6.4l-61.3 35.4c-2.3 1.3-5.1 1.3-7.4 0l-61.3-35.4c-2.3-1.3-3.7-3.8-3.7-6.4v-70.8c0-2.6 1.4-5.1 3.7-6.4l61.3-35.4c2.3-1.3 5.1-1.3 7.4 0l15.3 8.8c1.7 1 3.9-.3 3.9-2.2v-94c0-2.8 3-4.6 5.5-3.2l36.5 20.4c2.3 1.2 3.8 3.7 3.8 6.4zm-46 128.9c0-.7-.4-1.3-.9-1.6l-21-12.2c-.6-.3-1.3-.3-1.9 0l-21 12.2c-.6.3-.9.9-.9 1.6v24.3c0 .7.4 1.3.9 1.6l21 12.1c.6.3 1.3.3 1.8 0l21-12.1c.6-.3.9-.9.9-1.6v-24.3zm209.8-.7c2.3-1.3 3.7-3.8 3.7-6.4V192c0-2.6-1.4-5.1-3.7-6.4l-60.9-35.4c-2.3-1.3-5.1-1.3-7.4 0l-61.3 35.4c-2.3 1.3-3.7 3.8-3.7 6.4v70.8c0 2.7 1.4 5.1 3.7 6.4l60.9 34.7c2.2 1.3 5 1.3 7.3 0l36.8-20.5c2.5-1.4 2.5-5 0-6.4L550 241.6c-1.2-.7-1.9-1.9-1.9-3.2v-22.2c0-1.3.7-2.5 1.9-3.2l19.2-11.1c1.1-.7 2.6-.7 3.7 0l19.2 11.1c1.1.7 1.9 1.9 1.9 3.2v17.4c0 2.8 3.1 4.6 5.6 3.2l36.7-21.3zM559 219c-.4.3-.7.7-.7 1.2v13.6c0 .5.3 1 .7 1.2l11.8 6.8c.4.3 1 .3 1.4 0L584 235c.4-.3.7-.7.7-1.2v-13.6c0-.5-.3-1-.7-1.2l-11.8-6.8c-.4-.3-1-.3-1.4 0L559 219zm-254.2 43.5v-70.4c0-2.6-1.6-5.1-3.9-6.4l-61.1-35.2c-2.1-1.2-5-1.4-7.4 0l-61.1 35.2c-2.3 1.3-3.9 3.7-3.9 6.4v70.4c0 2.8 1.9 5.2 4 6.4l61.2 35.2c2.4 1.4 5.2 1.3 7.4 0l61-35.2c1.8-1 3.1-2.7 3.6-4.7.1-.5.2-1.1.2-1.7zm-74.3-124.9l-.8.5h1.1l-.3-.5zm76.2 130.2l-.4-.7v.9l.4-.2z\"],\n    \"node-js\": [448, 512, [], \"f3d3\", \"M224 508c-6.7 0-13.5-1.8-19.4-5.2l-61.7-36.5c-9.2-5.2-4.7-7-1.7-8 12.3-4.3 14.8-5.2 27.9-12.7 1.4-.8 3.2-.5 4.6.4l47.4 28.1c1.7 1 4.1 1 5.7 0l184.7-106.6c1.7-1 2.8-3 2.8-5V149.3c0-2.1-1.1-4-2.9-5.1L226.8 37.7c-1.7-1-4-1-5.7 0L36.6 144.3c-1.8 1-2.9 3-2.9 5.1v213.1c0 2 1.1 4 2.9 4.9l50.6 29.2c27.5 13.7 44.3-2.4 44.3-18.7V167.5c0-3 2.4-5.3 5.4-5.3h23.4c2.9 0 5.4 2.3 5.4 5.3V378c0 36.6-20 57.6-54.7 57.6-10.7 0-19.1 0-42.5-11.6l-48.4-27.9C8.1 389.2.7 376.3.7 362.4V149.3c0-13.8 7.4-26.8 19.4-33.7L204.6 9c11.7-6.6 27.2-6.6 38.8 0l184.7 106.7c12 6.9 19.4 19.8 19.4 33.7v213.1c0 13.8-7.4 26.7-19.4 33.7L243.4 502.8c-5.9 3.4-12.6 5.2-19.4 5.2zm149.1-210.1c0-39.9-27-50.5-83.7-58-57.4-7.6-63.2-11.5-63.2-24.9 0-11.1 4.9-25.9 47.4-25.9 37.9 0 51.9 8.2 57.7 33.8.5 2.4 2.7 4.2 5.2 4.2h24c1.5 0 2.9-.6 3.9-1.7s1.5-2.6 1.4-4.1c-3.7-44.1-33-64.6-92.2-64.6-52.7 0-84.1 22.2-84.1 59.5 0 40.4 31.3 51.6 81.8 56.6 60.5 5.9 65.2 14.8 65.2 26.7 0 20.6-16.6 29.4-55.5 29.4-48.9 0-59.6-12.3-63.2-36.6-.4-2.6-2.6-4.5-5.3-4.5h-23.9c-3 0-5.3 2.4-5.3 5.3 0 31.1 16.9 68.2 97.8 68.2 58.4-.1 92-23.2 92-63.4z\"],\n    \"npm\": [576, 512, [], \"f3d4\", \"M288 288h-32v-64h32v64zm288-128v192H288v32H160v-32H0V160h576zm-416 32H32v128h64v-96h32v96h32V192zm160 0H192v160h64v-32h64V192zm224 0H352v128h64v-96h32v96h32v-96h32v96h32V192z\"],\n    \"ns8\": [640, 512, [], \"f3d5\", \"M187.1 159.9l-34.2 113.7-54.5-113.7H49L0 320h44.9L76 213.5 126.6 320h56.9L232 159.9h-44.9zm452.5-.9c-2.9-18-23.9-28.1-42.1-31.3-44.6-7.8-101.9 16.3-88.5 58.8v.1c-43.8 8.7-74.3 26.8-94.2 48.2-3-9.8-13.6-16.6-34-16.6h-87.6c-9.3 0-12.9-2.3-11.5-7.4 1.6-5.5 1.9-6.8 3.7-12.2 2.1-6.4 7.8-7.1 13.3-7.1h133.5l9.7-31.5c-139.7 0-144.5-.5-160.1 1.2-12.3 1.3-23.5 4.8-30.6 15-6.8 9.9-14.4 35.6-17.6 47.1-5.4 19.4-.6 28.6 32.8 28.6h87.3c7.8 0 8.8 2.7 7.7 6.6-1.1 4.4-2.8 10-4.5 14.6-1.6 4.2-4.7 7.4-13.8 7.4H216.3L204.7 320c139.9 0 145.3-.6 160.9-2.3 6.6-.7 13-2.1 18.5-4.9.2 3.7.5 7.3 1.2 10.8 5.4 30.5 27.4 52.3 56.8 59.5 48.6 11.9 108.7-16.8 135.1-68 18.7-36.2 14.1-76.2-3.4-105.5h.1c29.6-5.9 70.3-22 65.7-50.6zM530.7 263.7c-5.9 29.5-36.6 47.8-61.6 43.9-30.9-4.8-38.5-39.5-14.1-64.8 16.2-16.8 45.2-24 68.5-26.9 6.7 14.1 10.3 32 7.2 47.8zm21.8-83.1c-4.2-6-9.8-18.5-2.5-26.3 6.7-7.2 20.9-10.1 31.8-7.7 15.3 3.4 19.7 15.9 4.9 24.4-10.7 6.1-23.6 8.1-34.2 9.6z\"],\n    \"nutritionix\": [400, 512, [], \"f3d6\", \"M88 8.1S221.4-.1 209 112.5c0 0 19.1-74.9 103-40.6 0 0-17.7 74-88 56 0 0 14.6-54.6 66.1-56.6 0 0-39.9-10.3-82.1 48.8 0 0-19.8-94.5-93.6-99.7 0 0 75.2 19.4 77.6 107.5 0 .1-106.4 7-104-119.8zm312 315.6c0 48.5-9.7 95.3-32 132.3-42.2 30.9-105 48-168 48-62.9 0-125.8-17.1-168-48C9.7 419 0 372.2 0 323.7 0 275.3 17.7 229 40 192c42.2-30.9 97.1-48.6 160-48.6 63 0 117.8 17.6 160 48.6 22.3 37 40 83.3 40 131.7zM120 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM192 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM264 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM336 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm24-39.6c-4.8-22.3-7.4-36.9-16-56-38.8-19.9-90.5-32-144-32S94.8 180.1 56 200c-8.8 19.5-11.2 33.9-16 56 42.2-7.9 98.7-14.8 160-14.8s117.8 6.9 160 14.8z\"],\n    \"odnoklassniki\": [320, 512, [], \"f263\", \"M275.1 334c-27.4 17.4-65.1 24.3-90 26.9l20.9 20.6 76.3 76.3c27.9 28.6-17.5 73.3-45.7 45.7-19.1-19.4-47.1-47.4-76.3-76.6L84 503.4c-28.2 27.5-73.6-17.6-45.4-45.7 19.4-19.4 47.1-47.4 76.3-76.3l20.6-20.6c-24.6-2.6-62.9-9.1-90.6-26.9-32.6-21-46.9-33.3-34.3-59 7.4-14.6 27.7-26.9 54.6-5.7 0 0 36.3 28.9 94.9 28.9s94.9-28.9 94.9-28.9c26.9-21.1 47.1-8.9 54.6 5.7 12.4 25.7-1.9 38-34.5 59.1zM30.3 129.7C30.3 58 88.6 0 160 0s129.7 58 129.7 129.7c0 71.4-58.3 129.4-129.7 129.4s-129.7-58-129.7-129.4zm66 0c0 35.1 28.6 63.7 63.7 63.7s63.7-28.6 63.7-63.7c0-35.4-28.6-64-63.7-64s-63.7 28.6-63.7 64z\"],\n    \"odnoklassniki-square\": [448, 512, [], \"f264\", \"M184.2 177.1c0-22.1 17.9-40 39.8-40s39.8 17.9 39.8 40c0 22-17.9 39.8-39.8 39.8s-39.8-17.9-39.8-39.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-305.1 97.1c0 44.6 36.4 80.9 81.1 80.9s81.1-36.2 81.1-80.9c0-44.8-36.4-81.1-81.1-81.1s-81.1 36.2-81.1 81.1zm174.5 90.7c-4.6-9.1-17.3-16.8-34.1-3.6 0 0-22.7 18-59.3 18s-59.3-18-59.3-18c-16.8-13.2-29.5-5.5-34.1 3.6-7.9 16.1 1.1 23.7 21.4 37 17.3 11.1 41.2 15.2 56.6 16.8l-12.9 12.9c-18.2 18-35.5 35.5-47.7 47.7-17.6 17.6 10.7 45.8 28.4 28.6l47.7-47.9c18.2 18.2 35.7 35.7 47.7 47.9 17.6 17.2 46-10.7 28.6-28.6l-47.7-47.7-13-12.9c15.5-1.6 39.1-5.9 56.2-16.8 20.4-13.3 29.3-21 21.5-37z\"],\n    \"old-republic\": [496, 512, [], \"f510\", \"M235.76 10.23c7.5-.31 15-.28 22.5-.09 3.61.14 7.2.4 10.79.73 4.92.27 9.79 1.03 14.67 1.62 2.93.43 5.83.98 8.75 1.46 7.9 1.33 15.67 3.28 23.39 5.4 12.24 3.47 24.19 7.92 35.76 13.21 26.56 12.24 50.94 29.21 71.63 49.88 20.03 20.09 36.72 43.55 48.89 69.19 1.13 2.59 2.44 5.1 3.47 7.74 2.81 6.43 5.39 12.97 7.58 19.63 4.14 12.33 7.34 24.99 9.42 37.83.57 3.14 1.04 6.3 1.4 9.47.55 3.83.94 7.69 1.18 11.56.83 8.34.84 16.73.77 25.1-.07 4.97-.26 9.94-.75 14.89-.24 3.38-.51 6.76-.98 10.12-.39 2.72-.63 5.46-1.11 8.17-.9 5.15-1.7 10.31-2.87 15.41-4.1 18.5-10.3 36.55-18.51 53.63-15.77 32.83-38.83 62.17-67.12 85.12a246.503 246.503 0 0 1-56.91 34.86c-6.21 2.68-12.46 5.25-18.87 7.41-3.51 1.16-7.01 2.38-10.57 3.39-6.62 1.88-13.29 3.64-20.04 5-4.66.91-9.34 1.73-14.03 2.48-5.25.66-10.5 1.44-15.79 1.74-6.69.66-13.41.84-20.12.81-6.82.03-13.65-.12-20.45-.79-3.29-.23-6.57-.5-9.83-.95-2.72-.39-5.46-.63-8.17-1.11-4.12-.72-8.25-1.37-12.35-2.22-4.25-.94-8.49-1.89-12.69-3.02-8.63-2.17-17.08-5.01-25.41-8.13-10.49-4.12-20.79-8.75-30.64-14.25-2.14-1.15-4.28-2.29-6.35-3.57-11.22-6.58-21.86-14.1-31.92-22.34-34.68-28.41-61.41-66.43-76.35-108.7-3.09-8.74-5.71-17.65-7.8-26.68-1.48-6.16-2.52-12.42-3.58-18.66-.4-2.35-.61-4.73-.95-7.09-.6-3.96-.75-7.96-1.17-11.94-.8-9.47-.71-18.99-.51-28.49.14-3.51.34-7.01.7-10.51.31-3.17.46-6.37.92-9.52.41-2.81.65-5.65 1.16-8.44.7-3.94 1.3-7.9 2.12-11.82 3.43-16.52 8.47-32.73 15.26-48.18 1.15-2.92 2.59-5.72 3.86-8.59 8.05-16.71 17.9-32.56 29.49-47.06 20-25.38 45.1-46.68 73.27-62.47 7.5-4.15 15.16-8.05 23.07-11.37 15.82-6.88 32.41-11.95 49.31-15.38 3.51-.67 7.04-1.24 10.56-1.85 2.62-.47 5.28-.7 7.91-1.08 3.53-.53 7.1-.68 10.65-1.04 2.46-.24 4.91-.36 7.36-.51m8.64 24.41c-9.23.1-18.43.99-27.57 2.23-7.3 1.08-14.53 2.6-21.71 4.3-13.91 3.5-27.48 8.34-40.46 14.42-10.46 4.99-20.59 10.7-30.18 17.22-4.18 2.92-8.4 5.8-12.34 9.03-5.08 3.97-9.98 8.17-14.68 12.59-2.51 2.24-4.81 4.7-7.22 7.06-28.22 28.79-48.44 65.39-57.5 104.69-2.04 8.44-3.54 17.02-4.44 25.65-1.1 8.89-1.44 17.85-1.41 26.8.11 7.14.38 14.28 1.22 21.37.62 7.12 1.87 14.16 3.2 21.18 1.07 4.65 2.03 9.32 3.33 13.91 6.29 23.38 16.5 45.7 30.07 65.75 8.64 12.98 18.78 24.93 29.98 35.77 16.28 15.82 35.05 29.04 55.34 39.22 7.28 3.52 14.66 6.87 22.27 9.63 5.04 1.76 10.06 3.57 15.22 4.98 11.26 3.23 22.77 5.6 34.39 7.06 2.91.29 5.81.61 8.72.9 13.82 1.08 27.74 1 41.54-.43 4.45-.6 8.92-.99 13.35-1.78 3.63-.67 7.28-1.25 10.87-2.1 4.13-.98 8.28-1.91 12.36-3.07 26.5-7.34 51.58-19.71 73.58-36.2 15.78-11.82 29.96-25.76 42.12-41.28 3.26-4.02 6.17-8.31 9.13-12.55 3.39-5.06 6.58-10.25 9.6-15.54 2.4-4.44 4.74-8.91 6.95-13.45 5.69-12.05 10.28-24.62 13.75-37.49 2.59-10.01 4.75-20.16 5.9-30.45 1.77-13.47 1.94-27.1 1.29-40.65-.29-3.89-.67-7.77-1-11.66-2.23-19.08-6.79-37.91-13.82-55.8-5.95-15.13-13.53-29.63-22.61-43.13-12.69-18.8-28.24-35.68-45.97-49.83-25.05-20-54.47-34.55-85.65-42.08-7.78-1.93-15.69-3.34-23.63-4.45-3.91-.59-7.85-.82-11.77-1.24-7.39-.57-14.81-.72-22.22-.58zM139.26 83.53c13.3-8.89 28.08-15.38 43.3-20.18-3.17 1.77-6.44 3.38-9.53 5.29-11.21 6.68-21.52 14.9-30.38 24.49-6.8 7.43-12.76 15.73-17.01 24.89-3.29 6.86-5.64 14.19-6.86 21.71-.93 4.85-1.3 9.81-1.17 14.75.13 13.66 4.44 27.08 11.29 38.82 5.92 10.22 13.63 19.33 22.36 27.26 4.85 4.36 10.24 8.09 14.95 12.6 2.26 2.19 4.49 4.42 6.43 6.91 2.62 3.31 4.89 6.99 5.99 11.1.9 3.02.66 6.2.69 9.31.02 4.1-.04 8.2.03 12.3.14 3.54-.02 7.09.11 10.63.08 2.38.02 4.76.05 7.14.16 5.77.06 11.53.15 17.3.11 2.91.02 5.82.13 8.74.03 1.63.13 3.28-.03 4.91-.91.12-1.82.18-2.73.16-10.99 0-21.88-2.63-31.95-6.93-6-2.7-11.81-5.89-17.09-9.83-5.75-4.19-11.09-8.96-15.79-14.31-6.53-7.24-11.98-15.39-16.62-23.95-1.07-2.03-2.24-4.02-3.18-6.12-1.16-2.64-2.62-5.14-3.67-7.82-4.05-9.68-6.57-19.94-8.08-30.31-.49-4.44-1.09-8.88-1.2-13.35-.7-15.73.84-31.55 4.67-46.82 2.12-8.15 4.77-16.18 8.31-23.83 6.32-14.2 15.34-27.18 26.3-38.19 6.28-6.2 13.13-11.84 20.53-16.67zm175.37-20.12c2.74.74 5.41 1.74 8.09 2.68 6.36 2.33 12.68 4.84 18.71 7.96 13.11 6.44 25.31 14.81 35.82 24.97 10.2 9.95 18.74 21.6 25.14 34.34 1.28 2.75 2.64 5.46 3.81 8.26 6.31 15.1 10 31.26 11.23 47.57.41 4.54.44 9.09.45 13.64.07 11.64-1.49 23.25-4.3 34.53-1.97 7.27-4.35 14.49-7.86 21.18-3.18 6.64-6.68 13.16-10.84 19.24-6.94 10.47-15.6 19.87-25.82 27.22-10.48 7.64-22.64 13.02-35.4 15.38-3.51.69-7.08 1.08-10.66 1.21-1.85.06-3.72.16-5.56-.1-.28-2.15 0-4.31-.01-6.46-.03-3.73.14-7.45.1-11.17.19-7.02.02-14.05.21-21.07.03-2.38-.03-4.76.03-7.14.17-5.07-.04-10.14.14-15.21.1-2.99-.24-6.04.51-8.96.66-2.5 1.78-4.86 3.09-7.08 4.46-7.31 11.06-12.96 17.68-18.26 5.38-4.18 10.47-8.77 15.02-13.84 7.68-8.37 14.17-17.88 18.78-28.27 2.5-5.93 4.52-12.1 5.55-18.46.86-4.37 1.06-8.83 1.01-13.27-.02-7.85-1.4-15.65-3.64-23.17-1.75-5.73-4.27-11.18-7.09-16.45-3.87-6.93-8.65-13.31-13.96-19.2-9.94-10.85-21.75-19.94-34.6-27.1-1.85-1.02-3.84-1.82-5.63-2.97zm-100.8 58.45c.98-1.18 1.99-2.33 3.12-3.38-.61.93-1.27 1.81-1.95 2.68-3.1 3.88-5.54 8.31-7.03 13.06-.87 3.27-1.68 6.6-1.73 10-.07 2.52-.08 5.07.32 7.57 1.13 7.63 4.33 14.85 8.77 21.12 2 2.7 4.25 5.27 6.92 7.33 1.62 1.27 3.53 2.09 5.34 3.05 3.11 1.68 6.32 3.23 9.07 5.48 2.67 2.09 4.55 5.33 4.4 8.79-.01 73.67 0 147.34-.01 221.02 0 1.35-.08 2.7.04 4.04.13 1.48.82 2.83 1.47 4.15.86 1.66 1.78 3.34 3.18 4.62.85.77 1.97 1.4 3.15 1.24 1.5-.2 2.66-1.35 3.45-2.57.96-1.51 1.68-3.16 2.28-4.85.76-2.13.44-4.42.54-6.63.14-4.03-.02-8.06.14-12.09.03-5.89.03-11.77.06-17.66.14-3.62.03-7.24.11-10.86.15-4.03-.02-8.06.14-12.09.03-5.99.03-11.98.07-17.97.14-3.62.02-7.24.11-10.86.14-3.93-.02-7.86.14-11.78.03-5.99.03-11.98.06-17.97.16-3.94-.01-7.88.19-11.82.29 1.44.13 2.92.22 4.38.19 3.61.42 7.23.76 10.84.32 3.44.44 6.89.86 10.32.37 3.1.51 6.22.95 9.31.57 4.09.87 8.21 1.54 12.29 1.46 9.04 2.83 18.11 5.09 26.99 1.13 4.82 2.4 9.61 4 14.3 2.54 7.9 5.72 15.67 10.31 22.62 1.73 2.64 3.87 4.98 6.1 7.21.27.25.55.51.88.71.6.25 1.31-.07 1.7-.57.71-.88 1.17-1.94 1.7-2.93 4.05-7.8 8.18-15.56 12.34-23.31.7-1.31 1.44-2.62 2.56-3.61 1.75-1.57 3.84-2.69 5.98-3.63 2.88-1.22 5.9-2.19 9.03-2.42 6.58-.62 13.11.75 19.56 1.85 3.69.58 7.4 1.17 11.13 1.41 3.74.1 7.48.05 11.21-.28 8.55-.92 16.99-2.96 24.94-6.25 5.3-2.24 10.46-4.83 15.31-7.93 11.46-7.21 21.46-16.57 30.04-27.01 1.17-1.42 2.25-2.9 3.46-4.28-1.2 3.24-2.67 6.37-4.16 9.48-1.25 2.9-2.84 5.61-4.27 8.42-5.16 9.63-11.02 18.91-17.75 27.52-4.03 5.21-8.53 10.05-13.33 14.57-6.64 6.05-14.07 11.37-22.43 14.76-8.21 3.37-17.31 4.63-26.09 3.29-3.56-.58-7.01-1.69-10.41-2.88-2.79-.97-5.39-2.38-8.03-3.69-3.43-1.71-6.64-3.81-9.71-6.08 2.71 3.06 5.69 5.86 8.7 8.61 4.27 3.76 8.74 7.31 13.63 10.23 3.98 2.45 8.29 4.4 12.84 5.51 1.46.37 2.96.46 4.45.6-1.25 1.1-2.63 2.04-3.99 2.98-9.61 6.54-20.01 11.86-30.69 16.43-20.86 8.7-43.17 13.97-65.74 15.34-4.66.24-9.32.36-13.98.36-4.98-.11-9.97-.13-14.92-.65-11.2-.76-22.29-2.73-33.17-5.43-10.35-2.71-20.55-6.12-30.3-10.55-8.71-3.86-17.12-8.42-24.99-13.79-1.83-1.31-3.74-2.53-5.37-4.08 6.6-1.19 13.03-3.39 18.99-6.48 5.74-2.86 10.99-6.66 15.63-11.07 2.24-2.19 4.29-4.59 6.19-7.09-3.43 2.13-6.93 4.15-10.62 5.78-4.41 2.16-9.07 3.77-13.81 5.02-5.73 1.52-11.74 1.73-17.61 1.14-8.13-.95-15.86-4.27-22.51-8.98-4.32-2.94-8.22-6.43-11.96-10.06-9.93-10.16-18.2-21.81-25.66-33.86-3.94-6.27-7.53-12.75-11.12-19.22-1.05-2.04-2.15-4.05-3.18-6.1 2.85 2.92 5.57 5.97 8.43 8.88 8.99 8.97 18.56 17.44 29.16 24.48 7.55 4.9 15.67 9.23 24.56 11.03 3.11.73 6.32.47 9.47.81 2.77.28 5.56.2 8.34.3 5.05.06 10.11.04 15.16-.16 3.65-.16 7.27-.66 10.89-1.09 2.07-.25 4.11-.71 6.14-1.2 3.88-.95 8.11-.96 11.83.61 4.76 1.85 8.44 5.64 11.38 9.71 2.16 3.02 4.06 6.22 5.66 9.58 1.16 2.43 2.46 4.79 3.55 7.26 1 2.24 2.15 4.42 3.42 6.52.67 1.02 1.4 2.15 2.62 2.55 1.06-.75 1.71-1.91 2.28-3.03 2.1-4.16 3.42-8.65 4.89-13.05 2.02-6.59 3.78-13.27 5.19-20.02 2.21-9.25 3.25-18.72 4.54-28.13.56-3.98.83-7.99 1.31-11.97.87-10.64 1.9-21.27 2.24-31.94.08-1.86.24-3.71.25-5.57.01-4.35.25-8.69.22-13.03-.01-2.38-.01-4.76 0-7.13.05-5.07-.2-10.14-.22-15.21-.2-6.61-.71-13.2-1.29-19.78-.73-5.88-1.55-11.78-3.12-17.51-2.05-7.75-5.59-15.03-9.8-21.82-3.16-5.07-6.79-9.88-11.09-14.03-3.88-3.86-8.58-7.08-13.94-8.45-1.5-.41-3.06-.45-4.59-.64.07-2.99.7-5.93 1.26-8.85 1.59-7.71 3.8-15.3 6.76-22.6 1.52-4.03 3.41-7.9 5.39-11.72 3.45-6.56 7.62-12.79 12.46-18.46zm31.27 1.7c.35-.06.71-.12 1.07-.19.19 1.79.09 3.58.1 5.37v38.13c-.01 1.74.13 3.49-.15 5.22-.36-.03-.71-.05-1.06-.05-.95-3.75-1.72-7.55-2.62-11.31-.38-1.53-.58-3.09-1.07-4.59-1.7-.24-3.43-.17-5.15-.2-5.06-.01-10.13 0-15.19-.01-1.66-.01-3.32.09-4.98-.03-.03-.39-.26-.91.16-1.18 1.28-.65 2.72-.88 4.06-1.35 3.43-1.14 6.88-2.16 10.31-3.31 1.39-.48 2.9-.72 4.16-1.54.04-.56.02-1.13-.05-1.68-1.23-.55-2.53-.87-3.81-1.28-3.13-1.03-6.29-1.96-9.41-3.02-1.79-.62-3.67-1-5.41-1.79-.03-.37-.07-.73-.11-1.09 5.09-.19 10.2.06 15.3-.12 3.36-.13 6.73.08 10.09-.07.12-.39.26-.77.37-1.16 1.08-4.94 2.33-9.83 3.39-14.75zm5.97-.2c.36.05.72.12 1.08.2.98 3.85 1.73 7.76 2.71 11.61.36 1.42.56 2.88 1.03 4.27 2.53.18 5.07-.01 7.61.05 5.16.12 10.33.12 15.49.07.76-.01 1.52.03 2.28.08-.04.36-.07.72-.1 1.08-1.82.83-3.78 1.25-5.67 1.89-3.73 1.23-7.48 2.39-11.22 3.57-.57.17-1.12.42-1.67.64-.15.55-.18 1.12-.12 1.69.87.48 1.82.81 2.77 1.09 4.88 1.52 9.73 3.14 14.63 4.6.38.13.78.27 1.13.49.4.27.23.79.15 1.18-1.66.13-3.31.03-4.97.04-5.17.01-10.33-.01-15.5.01-1.61.03-3.22-.02-4.82.21-.52 1.67-.72 3.42-1.17 5.11-.94 3.57-1.52 7.24-2.54 10.78-.36.01-.71.02-1.06.06-.29-1.73-.15-3.48-.15-5.22v-38.13c.02-1.78-.08-3.58.11-5.37zM65.05 168.33c1.12-2.15 2.08-4.4 3.37-6.46-1.82 7.56-2.91 15.27-3.62 23-.8 7.71-.85 15.49-.54 23.23 1.05 19.94 5.54 39.83 14.23 57.88 2.99 5.99 6.35 11.83 10.5 17.11 6.12 7.47 12.53 14.76 19.84 21.09 4.8 4.1 9.99 7.78 15.54 10.8 3.27 1.65 6.51 3.39 9.94 4.68 5.01 2.03 10.19 3.61 15.42 4.94 3.83.96 7.78 1.41 11.52 2.71 5 1.57 9.47 4.61 13.03 8.43 4.93 5.23 8.09 11.87 10.2 18.67.99 2.9 1.59 5.91 2.17 8.92.15.75.22 1.52.16 2.29-6.5 2.78-13.26 5.06-20.26 6.18-4.11.78-8.29.99-12.46 1.08-10.25.24-20.47-1.76-30.12-5.12-3.74-1.42-7.49-2.85-11.03-4.72-8.06-3.84-15.64-8.7-22.46-14.46-2.92-2.55-5.83-5.13-8.4-8.03-9.16-9.83-16.3-21.41-21.79-33.65-2.39-5.55-4.61-11.18-6.37-16.96-1.17-3.94-2.36-7.89-3.26-11.91-.75-2.94-1.22-5.95-1.87-8.92-.46-2.14-.69-4.32-1.03-6.48-.85-5.43-1.28-10.93-1.33-16.43.11-6.18.25-12.37 1.07-18.5.4-2.86.67-5.74 1.15-8.6.98-5.7 2.14-11.37 3.71-16.93 3.09-11.65 7.48-22.95 12.69-33.84zm363.73-6.44c1.1 1.66 1.91 3.48 2.78 5.26 2.1 4.45 4.24 8.9 6.02 13.49 7.61 18.76 12.3 38.79 13.04 59.05.02 1.76.07 3.52.11 5.29.13 9.57-1.27 19.09-3.18 28.45-.73 3.59-1.54 7.17-2.58 10.69-4.04 14.72-10 29-18.41 41.78-8.21 12.57-19.01 23.55-31.84 31.41-5.73 3.59-11.79 6.64-18.05 9.19-5.78 2.19-11.71 4.03-17.8 5.11-6.4 1.05-12.91 1.52-19.4 1.23-7.92-.48-15.78-2.07-23.21-4.85-1.94-.8-3.94-1.46-5.84-2.33-.21-1.51.25-2.99.53-4.46 1.16-5.74 3.03-11.36 5.7-16.58 2.37-4.51 5.52-8.65 9.46-11.9 2.43-2.05 5.24-3.61 8.16-4.83 3.58-1.5 7.47-1.97 11.24-2.83 7.23-1.71 14.37-3.93 21.15-7 10.35-4.65 19.71-11.38 27.65-19.46 1.59-1.61 3.23-3.18 4.74-4.87 3.37-3.76 6.71-7.57 9.85-11.53 7.48-10.07 12.82-21.59 16.71-33.48 1.58-5.3 3.21-10.6 4.21-16.05.63-2.87 1.04-5.78 1.52-8.68.87-6.09 1.59-12.22 1.68-18.38.12-6.65.14-13.32-.53-19.94-.73-7.99-1.87-15.96-3.71-23.78z\"],\n    \"opencart\": [640, 512, [], \"f23d\", \"M423.3 440.7c0 25.3-20.3 45.6-45.6 45.6s-45.8-20.3-45.8-45.6 20.6-45.8 45.8-45.8c25.4 0 45.6 20.5 45.6 45.8zm-253.9-45.8c-25.3 0-45.6 20.6-45.6 45.8s20.3 45.6 45.6 45.6 45.8-20.3 45.8-45.6-20.5-45.8-45.8-45.8zm291.7-270C158.9 124.9 81.9 112.1 0 25.7c34.4 51.7 53.3 148.9 373.1 144.2 333.3-5 130 86.1 70.8 188.9 186.7-166.7 319.4-233.9 17.2-233.9z\"],\n    \"openid\": [448, 512, [], \"f19b\", \"M271.5 432l-68 32C88.5 453.7 0 392.5 0 318.2c0-71.5 82.5-131 191.7-144.3v43c-71.5 12.5-124 53-124 101.3 0 51 58.5 93.3 135.7 103v-340l68-33.2v384zM448 291l-131.3-28.5 36.8-20.7c-19.5-11.5-43.5-20-70-24.8v-43c46.2 5.5 87.7 19.5 120.3 39.3l35-19.8L448 291z\"],\n    \"opera\": [496, 512, [], \"f26a\", \"M313.9 32.7c-170.2 0-252.6 223.8-147.5 355.1 36.5 45.4 88.6 75.6 147.5 75.6 36.3 0 70.3-11.1 99.4-30.4-43.8 39.2-101.9 63-165.3 63-3.9 0-8 0-11.9-.3C104.6 489.6 0 381.1 0 248 0 111 111 0 248 0h.8c63.1.3 120.7 24.1 164.4 63.1-29-19.4-63.1-30.4-99.3-30.4zm101.8 397.7c-40.9 24.7-90.7 23.6-132-5.8 56.2-20.5 97.7-91.6 97.7-176.6 0-84.7-41.2-155.8-97.4-176.6 41.8-29.2 91.2-30.3 132.9-5 105.9 98.7 105.5 265.7-1.2 364z\"],\n    \"optin-monster\": [576, 512, [], \"f23c\", \"M572.6 421.4c5.6-9.5 4.7-15.2-5.4-11.6-3-4.9-7-9.5-11.1-13.8 2.9-9.7-.7-14.2-10.8-9.2-4.6-3.2-10.3-6.5-15.9-9.2 0-15.1-11.6-11.6-17.6-5.7-10.4-1.5-18.7-.3-26.8 5.7.3-6.5.3-13 .3-19.7 12.6 0 40.2-11 45.9-36.2 1.4-6.8 1.6-13.8-.3-21.9-3-13.5-14.3-21.3-25.1-25.7-.8-5.9-7.6-14.3-14.9-15.9s-12.4 4.9-14.1 10.3c-8.5 0-19.2 2.8-21.1 8.4-5.4-.5-11.1-1.4-16.8-1.9 2.7-1.9 5.4-3.5 8.4-4.6 5.4-9.2 14.6-11.4 25.7-11.6V256c19.5-.5 43-5.9 53.8-18.1 12.7-13.8 14.6-37.3 12.4-55.1-2.4-17.3-9.7-37.6-24.6-48.1-8.4-5.9-21.6-.8-22.7 9.5-2.2 19.6 1.2 30-38.6 25.1-10.3-23.8-24.6-44.6-42.7-60C341 49.6 242.9 55.5 166.4 71.7c19.7 4.6 41.1 8.6 59.7 16.5-26.2 2.4-52.7 11.3-76.2 23.2-32.8 17-44 29.9-56.7 42.4 14.9-2.2 28.9-5.1 43.8-3.8-9.7 5.4-18.4 12.2-26.5 20-25.8.9-23.8-5.3-26.2-25.9-1.1-10.5-14.3-15.4-22.7-9.7-28.1 19.9-33.5 79.9-12.2 103.5 10.8 12.2 35.1 17.3 54.9 17.8-.3 1.1-.3 1.9-.3 2.7 10.8.5 19.5 2.7 24.6 11.6 3 1.1 5.7 2.7 8.1 4.6-5.4.5-11.1 1.4-16.5 1.9-3.3-6.6-13.7-8.1-21.1-8.1-1.6-5.7-6.5-12.2-14.1-10.3-6.8 1.9-14.1 10-14.9 15.9-22.5 9.5-30.1 26.8-25.1 47.6 5.3 24.8 33 36.2 45.9 36.2v19.7c-6.6-5-14.3-7.5-26.8-5.7-5.5-5.5-17.3-10.1-17.3 5.7-5.9 2.7-11.4 5.9-15.9 9.2-9.8-4.9-13.6-1.7-11.1 9.2-4.1 4.3-7.8 8.6-11.1 13.8-10.2-3.7-11 2.2-5.4 11.6-1.1 3.5-1.6 7-1.9 10.8-.5 31.6 44.6 64 73.5 65.1 17.3.5 34.6-8.4 43-23.5 113.2 4.9 226.7 4.1 340.2 0 8.1 15.1 25.4 24.3 42.7 23.5 29.2-1.1 74.3-33.5 73.5-65.1.2-3.7-.7-7.2-1.7-10.7zm-73.8-254c1.1-3 2.4-8.4 2.4-14.6 0-5.9 6.8-8.1 14.1-.8 11.1 11.6 14.9 40.5 13.8 51.1-4.1-13.6-13-29-30.3-35.7zm-4.6 6.7c19.5 6.2 28.6 27.6 29.7 48.9-1.1 2.7-3 5.4-4.9 7.6-5.7 5.9-15.4 10-26.2 12.2 4.3-21.3.3-47.3-12.7-63 4.9-.8 10.9-2.4 14.1-5.7zm-24.1 6.8c13.8 11.9 20 39.2 14.1 63.5-4.1.5-8.1.8-11.6.8-1.9-21.9-6.8-44-14.3-64.6 3.7.3 8.1.3 11.8.3zM47.5 203c-1.1-10.5 2.4-39.5 13.8-51.1 7-7.3 14.1-5.1 14.1.8 0 6.2 1.4 11.6 2.4 14.6-17.3 6.8-26.2 22.2-30.3 35.7zm9.7 27.6c-1.9-2.2-3.5-4.9-4.9-7.6 1.4-21.3 10.3-42.7 29.7-48.9 3.2 3.2 9.2 4.9 14.1 5.7-13 15.7-17 41.6-12.7 63-10.8-2.2-20.5-6-26.2-12.2zm47.9 14.6c-4.1 0-8.1-.3-12.7-.8-4.6-18.6-1.9-38.9 5.4-53v.3l12.2-5.1c4.9-1.9 9.7-3.8 14.9-4.9-10.7 19.7-17.4 41.3-19.8 63.5zm184-162.7c41.9 0 76.2 34 76.2 75.9 0 42.2-34.3 76.2-76.2 76.2s-76.2-34-76.2-76.2c0-41.8 34.3-75.9 76.2-75.9zm115.6 174.3c-.3 17.8-7 48.9-23 57-13.2 6.6-6.5-7.5-16.5-58.1 13.3.3 26.6.3 39.5 1.1zm-54-1.6c.8 4.9 3.8 40.3-1.6 41.9-11.6 3.5-40 4.3-51.1-1.1-4.1-3-4.6-35.9-4.3-41.1v.3c18.9-.3 38.1-.3 57 0zM278.3 309c-13 3.5-41.6 4.1-54.6-1.6-6.5-2.7-3.8-42.4-1.9-51.6 19.2-.5 38.4-.5 57.8-.8v.3c1.1 8.3 3.3 51.2-1.3 53.7zm-106.5-51.1c12.2-.8 24.6-1.4 36.8-1.6-2.4 15.4-3 43.5-4.9 52.2-1.1 6.8-4.3 6.8-9.7 4.3-21.9-9.8-27.6-35.2-22.2-54.9zm-35.4 31.3c7.8-1.1 15.7-1.9 23.5-2.7 1.6 6.2 3.8 11.9 7 17.6 10 17 44 35.7 45.1 7 6.2 14.9 40.8 12.2 54.9 10.8 15.7-1.4 23.8-1.4 26.8-14.3 12.4 4.3 30.8 4.1 44 3 11.3-.8 20.8-.5 24.6-8.9 1.1 5.1 1.9 11.6 4.6 16.8 10.8 21.3 37.3 1.4 46.8-31.6 8.6.8 17.6 1.9 26.5 2.7-.4 1.3-3.8 7.3 7.3 11.6-47.6 47-95.7 87.8-163.2 107-63.2-20.8-112.1-59.5-155.9-106.5 9.6-3.4 10.4-8.8 8-12.5zm-21.6 172.5c-3.8 17.8-21.9 29.7-39.7 28.9-19.2-.8-46.5-17-59.2-36.5-2.7-31.1 43.8-61.3 66.2-54.6 14.9 4.3 27.8 30.8 33.5 54 0 3-.3 5.7-.8 8.2zm-8.7-66c-.5-13.5-.5-27-.3-40.5h.3c2.7-1.6 5.7-3.8 7.8-6.5 6.5-1.6 13-5.1 15.1-9.2 3.3-7.1-7-7.5-5.4-12.4 2.7-1.1 5.7-2.2 7.8-3.5 29.2 29.2 58.6 56.5 97.3 77-36.8 11.3-72.4 27.6-105.9 47-1.2-18.6-7.7-35.9-16.7-51.9zm337.6 64.6c-103 3.5-206.2 4.1-309.4 0 0 .3 0 .3-.3.3v-.3h.3c35.1-21.6 72.2-39.2 112.4-50.8 11.6 5.1 23 9.5 34.9 13.2 2.2.8 2.2.8 4.3 0 14.3-4.1 28.4-9.2 42.2-15.4 41.5 11.7 78.8 31.7 115.6 53zm10.5-12.4c-35.9-19.5-73-35.9-111.9-47.6 38.1-20 71.9-47.3 103.5-76.7 2.2 1.4 4.6 2.4 7.6 3.2 0 .8.3 1.9.5 2.4-4.6 2.7-7.8 6.2-5.9 10.3 2.2 3.8 8.6 7.6 15.1 8.9 2.4 2.7 5.1 5.1 8.1 6.8 0 13.8-.3 27.6-.8 41.3l.3-.3c-9.3 15.9-15.5 37-16.5 51.7zm105.9 6.2c-12.7 19.5-40 35.7-59.2 36.5-19.3.9-40.5-13.2-40.5-37 5.7-23.2 18.9-49.7 33.5-54 22.7-6.9 69.2 23.4 66.2 54.5zM372.9 75.2c-3.8-72.1-100.8-79.7-126-23.5 44.6-24.3 90.3-15.7 126 23.5zM74.8 407.1c-15.7 1.6-49.5 25.4-49.5 43.2 0 11.6 15.7 19.5 32.2 14.9 12.2-3.2 31.1-17.6 35.9-27.3 6-11.6-3.7-32.7-18.6-30.8zm215.9-176.2c28.6 0 51.9-21.6 51.9-48.4 0-36.1-40.5-58.1-72.2-44.3 9.5 3 16.5 11.6 16.5 21.6 0 23.3-33.3 32-46.5 11.3-7.3 34.1 19.4 59.8 50.3 59.8zM68 474.1c.5 6.5 12.2 12.7 21.6 9.5 6.8-2.7 14.6-10.5 17.3-16.2 3-7-1.1-20-9.7-18.4-8.9 1.6-29.7 16.7-29.2 25.1zm433.2-67c-14.9-1.9-24.6 19.2-18.9 30.8 4.9 9.7 24.1 24.1 36.2 27.3 16.5 4.6 32.2-3.2 32.2-14.9 0-17.8-33.8-41.6-49.5-43.2zM478.8 449c-8.4-1.6-12.4 11.3-9.5 18.4 2.4 5.7 10.3 13.5 17.3 16.2 9.2 3.2 21.1-3 21.3-9.5.9-8.4-20.2-23.5-29.1-25.1z\"],\n    \"osi\": [512, 512, [], \"f41a\", \"M8 266.44C10.3 130.64 105.4 34 221.8 18.34c138.8-18.6 255.6 75.8 278 201.1 21.3 118.8-44 230-151.6 274-9.3 3.8-14.4 1.7-18-7.7q-26.7-69.45-53.4-139c-3.1-8.1-1-13.2 7-16.8 24.2-11 39.3-29.4 43.3-55.8a71.47 71.47 0 0 0-64.5-82.2c-39-3.4-71.8 23.7-77.5 59.7-5.2 33 11.1 63.7 41.9 77.7 9.6 4.4 11.5 8.6 7.8 18.4q-26.85 69.9-53.7 139.9c-2.6 6.9-8.3 9.3-15.5 6.5-52.6-20.3-101.4-61-130.8-119-24.9-49.2-25.2-87.7-26.8-108.7zm20.9-1.9c.4 6.6.6 14.3 1.3 22.1 6.3 71.9 49.6 143.5 131 183.1 3.2 1.5 4.4.8 5.6-2.3q22.35-58.65 45-117.3c1.3-3.3.6-4.8-2.4-6.7-31.6-19.9-47.3-48.5-45.6-86 1-21.6 9.3-40.5 23.8-56.3 30-32.7 77-39.8 115.5-17.6a91.64 91.64 0 0 1 45.2 90.4c-3.6 30.6-19.3 53.9-45.7 69.8-2.7 1.6-3.5 2.9-2.3 6q22.8 58.8 45.2 117.7c1.2 3.1 2.4 3.8 5.6 2.3 35.5-16.6 65.2-40.3 88.1-72 34.8-48.2 49.1-101.9 42.3-161-13.7-117.5-119.4-214.8-255.5-198-106.1 13-195.3 102.5-197.1 225.8z\"],\n    \"page4\": [496, 512, [], \"f3d7\", \"M248 504C111 504 0 393 0 256S111 8 248 8c20.9 0 41.3 2.6 60.7 7.5L42.3 392H248v112zm0-143.6V146.8L98.6 360.4H248zm96 31.6v92.7c45.7-19.2 84.5-51.7 111.4-92.7H344zm57.4-138.2l-21.2 8.4 21.2 8.3v-16.7zm-20.3 54.5c-6.7 0-8 6.3-8 12.9v7.7h16.2v-10c0-5.9-2.3-10.6-8.2-10.6zM496 256c0 37.3-8.2 72.7-23 104.4H344V27.3C433.3 64.8 496 153.1 496 256zM360.4 143.6h68.2V96h-13.9v32.6h-13.9V99h-13.9v29.6h-12.7V96h-13.9v47.6zm68.1 185.3H402v-11c0-15.4-5.6-25.2-20.9-25.2-15.4 0-20.7 10.6-20.7 25.9v25.3h68.2v-15zm0-103l-68.2 29.7V268l68.2 29.5v-16.6l-14.4-5.7v-26.5l14.4-5.9v-16.9zm-4.8-68.5h-35.6V184H402v-12.2h11c8.6 15.8 1.3 35.3-18.6 35.3-22.5 0-28.3-25.3-15.5-37.7l-11.6-10.6c-16.2 17.5-12.2 63.9 27.1 63.9 34 0 44.7-35.9 29.3-65.3z\"],\n    \"pagelines\": [384, 512, [], \"f18c\", \"M384 312.7c-55.1 136.7-187.1 54-187.1 54-40.5 81.8-107.4 134.4-184.6 134.7-16.1 0-16.6-24.4 0-24.4 64.4-.3 120.5-42.7 157.2-110.1-41.1 15.9-118.6 27.9-161.6-82.2 109-44.9 159.1 11.2 178.3 45.5 9.9-24.4 17-50.9 21.6-79.7 0 0-139.7 21.9-149.5-98.1 119.1-47.9 152.6 76.7 152.6 76.7 1.6-16.7 3.3-52.6 3.3-53.4 0 0-106.3-73.7-38.1-165.2 124.6 43 61.4 162.4 61.4 162.4.5 1.6.5 23.8 0 33.4 0 0 45.2-89 136.4-57.5-4.2 134-141.9 106.4-141.9 106.4-4.4 27.4-11.2 53.4-20 77.5 0 0 83-91.8 172-20z\"],\n    \"palfed\": [576, 512, [], \"f3d8\", \"M384.9 193.9c0-47.4-55.2-44.2-95.4-29.8-1.3 39.4-2.5 80.7-3 119.8.7 2.8 2.6 6.2 15.1 6.2 36.8 0 83.4-42.8 83.3-96.2zm-194.5 72.2c.2 0 6.5-2.7 11.2-2.7 26.6 0 20.7 44.1-14.4 44.1-21.5 0-37.1-18.1-37.1-43 0-42 42.9-95.6 100.7-126.5 1-12.4 3-22 10.5-28.2 11.2-9 26.6-3.5 29.5 11.1 72.2-22.2 135.2 1 135.2 72 0 77.9-79.3 152.6-140.1 138.2-.1 39.4.9 74.4 2.7 100v.2c.2 3.4.6 12.5-5.3 19.1-9.6 10.6-33.4 10-36.4-22.3-4.1-44.4.2-206.1 1.4-242.5-21.5 15-58.5 50.3-58.5 75.9.2 2.5.4 4 .6 4.6zM8 181.1s-.1 37.4 38.4 37.4h30l22.4 217.2s0 44.3 44.7 44.3h288.9s44.7-.4 44.7-44.3l22.4-217.2h30s38.4 1.2 38.4-37.4c0 0 .1-37.4-38.4-37.4h-30.1c-7.3-25.6-30.2-74.3-119.4-74.3h-28V50.3s-2.7-18.4-21.1-18.4h-85.8s-21.1 0-21.1 18.4v19.1h-28.1s-105 4.2-120.5 74.3h-29S8 142.5 8 181.1z\"],\n    \"patreon\": [512, 512, [], \"f3d9\", \"M512 194.8c0 101.3-82.4 183.8-183.8 183.8-101.7 0-184.4-82.4-184.4-183.8 0-101.6 82.7-184.3 184.4-184.3C429.6 10.5 512 93.2 512 194.8zM0 501.5h90v-491H0v491z\"],\n    \"paypal\": [384, 512, [], \"f1ed\", \"M111.4 295.9c-3.5 19.2-17.4 108.7-21.5 134-.3 1.8-1 2.5-3 2.5H12.3c-7.6 0-13.1-6.6-12.1-13.9L58.8 46.6c1.5-9.6 10.1-16.9 20-16.9 152.3 0 165.1-3.7 204 11.4 60.1 23.3 65.6 79.5 44 140.3-21.5 62.6-72.5 89.5-140.1 90.3-43.4.7-69.5-7-75.3 24.2zM357.1 152c-1.8-1.3-2.5-1.8-3 1.3-2 11.4-5.1 22.5-8.8 33.6-39.9 113.8-150.5 103.9-204.5 103.9-6.1 0-10.1 3.3-10.9 9.4-22.6 140.4-27.1 169.7-27.1 169.7-1 7.1 3.5 12.9 10.6 12.9h63.5c8.6 0 15.7-6.3 17.4-14.9.7-5.4-1.1 6.1 14.4-91.3 4.6-22 14.3-19.7 29.3-19.7 71 0 126.4-28.8 142.9-112.3 6.5-34.8 4.6-71.4-23.8-92.6z\"],\n    \"penny-arcade\": [640, 512, [], \"f704\", \"M421.91 164.27c-4.49 19.45-1.4 6.06-15.1 65.29l39.73-10.61c-22.34-49.61-17.29-38.41-24.63-54.68zm-206.09 51.11c-20.19 5.4-11.31 3.03-39.63 10.58l4.46 46.19c28.17-7.59 20.62-5.57 34.82-9.34 42.3-9.79 32.85-56.42.35-47.43zm326.16-26.19l-45.47-99.2c-5.69-12.37-19.46-18.84-32.62-15.33-70.27 18.75-38.72 10.32-135.59 36.23a27.618 27.618 0 0 0-18.89 17.41C144.26 113.27 0 153.75 0 226.67c0 33.5 30.67 67.11 80.9 95.37l1.74 17.88a27.891 27.891 0 0 0-17.77 28.67l4.3 44.48c1.39 14.31 13.43 25.21 27.8 25.2 5.18-.01-3.01 1.78 122.53-31.76 12.57-3.37 21.12-15.02 20.58-28.02 216.59 45.5 401.99-5.98 399.89-84.83.01-28.15-22.19-66.56-97.99-104.47zM255.14 298.3l-21.91 5.88-48.44 12.91 2.46 23.55 20.53-5.51 4.51 44.51-115.31 30.78-4.3-44.52 20.02-5.35-11.11-114.64-20.12 5.39-4.35-44.5c178.15-47.54 170.18-46.42 186.22-46.65 56.66-1.13 64.15 71.84 42.55 104.43a86.7 86.7 0 0 1-50.75 33.72zm199.18 16.62l-3.89-39.49 14.9-3.98-6.61-14.68-57.76 15.42-4.1 17.54 19.2-5.12 4.05 39.54-112.85 30.07-4.46-44.43 20.99-5.59 33.08-126.47-17.15 4.56-4.2-44.48c93.36-24.99 65.01-17.41 135.59-36.24l66.67 145.47 20.79-5.56 4.3 44.48-108.55 28.96z\"],\n    \"periscope\": [448, 512, [], \"f3da\", \"M370 63.6C331.4 22.6 280.5 0 226.6 0 111.9 0 18.5 96.2 18.5 214.4c0 75.1 57.8 159.8 82.7 192.7C137.8 455.5 192.6 512 226.6 512c41.6 0 112.9-94.2 120.9-105 24.6-33.1 82-118.3 82-192.6 0-56.5-21.1-110.1-59.5-150.8zM226.6 493.9c-42.5 0-190-167.3-190-279.4 0-107.4 83.9-196.3 190-196.3 100.8 0 184.7 89 184.7 196.3.1 112.1-147.4 279.4-184.7 279.4zM338 206.8c0 59.1-51.1 109.7-110.8 109.7-100.6 0-150.7-108.2-92.9-181.8v.4c0 24.5 20.1 44.4 44.8 44.4 24.7 0 44.8-19.9 44.8-44.4 0-18.2-11.1-33.8-26.9-40.7 76.6-19.2 141 39.3 141 112.4z\"],\n    \"phabricator\": [496, 512, [], \"f3db\", \"M323 262.1l-.1-13s21.7-19.8 21.1-21.2l-9.5-20c-.6-1.4-29.5-.5-29.5-.5l-9.4-9.3s.2-28.5-1.2-29.1l-20.1-9.2c-1.4-.6-20.7 21-20.7 21l-13.1-.2s-20.5-21.4-21.9-20.8l-20 8.3c-1.4.5.2 28.9.2 28.9l-9.1 9.1s-29.2-.9-29.7.4l-8.1 19.8c-.6 1.4 21 21 21 21l.1 12.9s-21.7 19.8-21.1 21.2l9.5 20c.6 1.4 29.5.5 29.5.5l9.4 9.3s-.2 31.8 1.2 32.3l20.1 8.3c1.4.6 20.7-23.5 20.7-23.5l13.1.2s20.5 23.8 21.8 23.3l20-7.5c1.4-.6-.2-32.1-.2-32.1l9.1-9.1s29.2.9 29.7-.5l8.1-19.8c.7-1.1-20.9-20.7-20.9-20.7zm-44.9-8.7c.7 17.1-12.8 31.6-30.1 32.4-17.3.8-32.1-12.5-32.8-29.6-.7-17.1 12.8-31.6 30.1-32.3 17.3-.8 32.1 12.5 32.8 29.5zm201.2-37.9l-97-97-.1.1c-75.1-73.3-195.4-72.8-269.8 1.6-50.9 51-27.8 27.9-95.7 95.3-22.3 22.3-22.3 58.7 0 81 69.9 69.4 46.4 46 97.4 97l.1-.1c75.1 73.3 195.4 72.9 269.8-1.6 51-50.9 27.9-27.9 95.3-95.3 22.3-22.3 22.3-58.7 0-81zM140.4 363.8c-59.6-59.5-59.6-156 0-215.5 59.5-59.6 156-59.5 215.6 0 59.5 59.5 59.6 156 0 215.6-59.6 59.5-156 59.4-215.6-.1z\"],\n    \"phoenix-framework\": [640, 512, [], \"f3dc\", \"M212.9 344.3c3.8-.1 22.8-1.4 25.6-2.2-2.4-2.6-43.6-1-68-49.6-4.3-8.6-7.5-17.6-6.4-27.6 2.9-25.5 32.9-30 52-18.5 36 21.6 63.3 91.3 113.7 97.5 37 4.5 84.6-17 108.2-45.4-.6-.1-.8-.2-1-.1-.4.1-.8.2-1.1.3-33.3 12.1-94.3 9.7-134.7-14.8-37.6-22.8-53.1-58.7-51.8-74.6 1.8-21.3 22.9-23.2 35.9-19.6 14.4 3.9 24.4 17.6 38.9 27.4 15.6 10.4 32.9 13.7 51.3 10.3 14.9-2.7 34.4-12.3 36.5-14.5-1.1-.1-1.8-.1-2.5-.2-6.2-.6-12.4-.8-18.5-1.7C279.8 194.5 262.1 47.4 138.5 37.9 94.2 34.5 39.1 46 2.2 72.9c-.8.6-1.5 1.2-2.2 1.8.1.2.1.3.2.5.8 0 1.6-.1 2.4-.2 6.3-1 12.5-.8 18.7.3 23.8 4.3 47.7 23.1 55.9 76.5 5.3 34.3-.7 50.8 8 86.1 19 77.1 91 107.6 127.7 106.4zM75.3 64.9c-.9-1-.9-1.2-1.3-2 12.1-2.6 24.2-4.1 36.6-4.8-1.1 14.7-22.2 21.3-35.3 6.8zm196.9 350.5c-42.8 1.2-92-26.7-123.5-61.4-4.6-5-16.8-20.2-18.6-23.4l.4-.4c6.6 4.1 25.7 18.6 54.8 27 24.2 7 48.1 6.3 71.6-3.3 22.7-9.3 41-.5 43.1 2.9-18.5 3.8-20.1 4.4-24 7.9-5.1 4.4-4.6 11.7 7 17.2 26.2 12.4 63-2.8 97.2 25.4 2.4 2 8.1 7.8 10.1 10.7-.1.2-.3.3-.4.5-4.8-1.5-16.4-7.5-40.2-9.3-24.7-2-46.3 5.3-77.5 6.2zm174.8-252c16.4-5.2 41.3-13.4 66.5-3.3 16.1 6.5 26.2 18.7 32.1 34.6 3.5 9.4 5.1 19.7 5.1 28.7-.2 0-.4 0-.6.1-.2-.4-.4-.9-.5-1.3-5-22-29.9-43.8-67.6-29.9-50.2 18.6-130.4 9.7-176.9-48-.7-.9-2.4-1.7-1.3-3.2.1-.2 2.1.6 3 1.3 18.1 13.4 38.3 21.9 60.3 26.2 30.5 6.1 54.6 2.9 79.9-5.2zm102.7 117.5c-32.4.2-33.8 50.1-103.6 64.4-18.2 3.7-38.7 4.6-44.9 4.2v-.4c2.8-1.5 14.7-2.6 29.7-16.6 7.9-7.3 15.3-15.1 22.8-22.9 19.5-20.2 41.4-42.2 81.9-39 23.1 1.8 29.3 8.2 36.1 12.7.3.2.4.5.7.9-.5 0-.7.1-.9 0-7-2.7-14.3-3.3-21.8-3.3zm-12.3-24.1c-.1.2-.1.4-.2.6-28.9-4.4-48-7.9-68.5 4-17 9.9-31.4 20.5-62 24.4-27.1 3.4-45.1 2.4-66.1-8-.3-.2-.6-.4-1-.6 0-.2.1-.3.1-.5 24.9 3.8 36.4 5.1 55.5-5.8 22.3-12.9 40.1-26.6 71.3-31 29.6-4.1 51.3 2.5 70.9 16.9zM268.6 97.3c-.6-.6-1.1-1.2-2.1-2.3 7.6 0 29.7-1.2 53.4 8.4 19.7 8 32.2 21 50.2 32.9 11.1 7.3 23.4 9.3 36.4 8.1 4.3-.4 8.5-1.2 12.8-1.7.4-.1.9 0 1.5.3-.6.4-1.2.9-1.8 1.2-8.1 4-16.7 6.3-25.6 7.1-26.1 2.6-50.3-3.7-73.4-15.4-19.3-9.9-36.4-22.9-51.4-38.6zM640 335.7c-3.5 3.1-22.7 11.6-42.7 5.3-12.3-3.9-19.5-14.9-31.6-24.1-10-7.6-20.9-7.9-28.1-8.4.6-.8.9-1.2 1.2-1.4 14.8-9.2 30.5-12.2 47.3-6.5 12.5 4.2 19.2 13.5 30.4 24.2 10.8 10.4 21 9.9 23.1 10.5.1-.1.2 0 .4.4zm-212.5 137c2.2 1.2 1.6 1.5 1.5 2-18.5-1.4-33.9-7.6-46.8-22.2-21.8-24.7-41.7-27.9-48.6-29.7.5-.2.8-.4 1.1-.4 13.1.1 26.1.7 38.9 3.9 25.3 6.4 35 25.4 41.6 35.3 3.2 4.8 7.3 8.3 12.3 11.1z\"],\n    \"phoenix-squadron\": [512, 512, [], \"f511\", \"M96 63.38C142.49 27.25 201.55 7.31 260.51 8.81c29.58-.38 59.11 5.37 86.91 15.33-24.13-4.63-49-6.34-73.38-2.45C231.17 27 191 48.84 162.21 80.87c5.67-1 10.78-3.67 16-5.86 18.14-7.87 37.49-13.26 57.23-14.83 19.74-2.13 39.64-.43 59.28 1.92-14.42 2.79-29.12 4.57-43 9.59-34.43 11.07-65.27 33.16-86.3 62.63-13.8 19.71-23.63 42.86-24.67 67.13-.35 16.49 5.22 34.81 19.83 44a53.27 53.27 0 0 0 37.52 6.74c15.45-2.46 30.07-8.64 43.6-16.33 11.52-6.82 22.67-14.55 32-24.25 3.79-3.22 2.53-8.45 2.62-12.79-2.12-.34-4.38-1.11-6.3.3a203 203 0 0 1-35.82 15.37c-20 6.17-42.16 8.46-62.1.78 12.79 1.73 26.06.31 37.74-5.44 20.23-9.72 36.81-25.2 54.44-38.77a526.57 526.57 0 0 1 88.9-55.31c25.71-12 52.94-22.78 81.57-24.12-15.63 13.72-32.15 26.52-46.78 41.38-14.51 14-27.46 29.5-40.11 45.18-3.52 4.6-8.95 6.94-13.58 10.16a150.7 150.7 0 0 0-51.89 60.1c-9.33 19.68-14.5 41.85-11.77 63.65 1.94 13.69 8.71 27.59 20.9 34.91 12.9 8 29.05 8.07 43.48 5.1 32.8-7.45 61.43-28.89 81-55.84 20.44-27.52 30.52-62.2 29.16-96.35-.52-7.5-1.57-15-1.66-22.49 8 19.48 14.82 39.71 16.65 60.83 2 14.28.75 28.76-1.62 42.9-1.91 11-5.67 21.51-7.78 32.43a165 165 0 0 0 39.34-81.07 183.64 183.64 0 0 0-14.21-104.64c20.78 32 32.34 69.58 35.71 107.48.49 12.73.49 25.51 0 38.23A243.21 243.21 0 0 1 482 371.34c-26.12 47.34-68 85.63-117.19 108-78.29 36.23-174.68 31.32-248-14.68A248.34 248.34 0 0 1 25.36 366 238.34 238.34 0 0 1 0 273.08v-31.34C3.93 172 40.87 105.82 96 63.38m222 80.33a79.13 79.13 0 0 0 16-4.48c5-1.77 9.24-5.94 10.32-11.22-8.96 4.99-17.98 9.92-26.32 15.7z\"],\n    \"php\": [640, 512, [], \"f457\", \"M320 104.5c171.4 0 303.2 72.2 303.2 151.5S491.3 407.5 320 407.5c-171.4 0-303.2-72.2-303.2-151.5S148.7 104.5 320 104.5m0-16.8C143.3 87.7 0 163 0 256s143.3 168.3 320 168.3S640 349 640 256 496.7 87.7 320 87.7zM218.2 242.5c-7.9 40.5-35.8 36.3-70.1 36.3l13.7-70.6c38 0 63.8-4.1 56.4 34.3zM97.4 350.3h36.7l8.7-44.8c41.1 0 66.6 3 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7h-70.7L97.4 350.3zm185.7-213.6h36.5l-8.7 44.8c31.5 0 60.7-2.3 74.8 10.7 14.8 13.6 7.7 31-8.3 113.1h-37c15.4-79.4 18.3-86 12.7-92-5.4-5.8-17.7-4.6-47.4-4.6l-18.8 96.6h-36.5l32.7-168.6zM505 242.5c-8 41.1-36.7 36.3-70.1 36.3l13.7-70.6c38.2 0 63.8-4.1 56.4 34.3zM384.2 350.3H421l8.7-44.8c43.2 0 67.1 2.5 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7H417l-32.8 168.7z\"],\n    \"pied-piper\": [448, 512, [], \"f2ae\", \"M32 419L0 479.2l.8-328C.8 85.3 54 32 120 32h327.2c-93 28.9-189.9 94.2-253.9 168.6C122.7 282 82.6 338 32 419M448 32S305.2 98.8 261.6 199.1c-23.2 53.6-28.9 118.1-71 158.6-28.9 27.8-69.8 38.2-105.3 56.3-23.2 12-66.4 40.5-84.9 66h328.4c66 0 119.3-53.3 119.3-119.2-.1 0-.1-328.8-.1-328.8z\"],\n    \"pied-piper-alt\": [576, 512, [], \"f1a8\", \"M244 246c-3.2-2-6.3-2.9-10.1-2.9-6.6 0-12.6 3.2-19.3 3.7l1.7 4.9zm135.9 197.9c-19 0-64.1 9.5-79.9 19.8l6.9 45.1c35.7 6.1 70.1 3.6 106-9.8-4.8-10-23.5-55.1-33-55.1zM340.8 177c6.6 2.8 11.5 9.2 22.7 22.1 2-1.4 7.5-5.2 7.5-8.6 0-4.9-11.8-13.2-13.2-23 11.2-5.7 25.2-6 37.6-8.9 68.1-16.4 116.3-52.9 146.8-116.7C548.3 29.3 554 16.1 554.6 2l-2 2.6c-28.4 50-33 63.2-81.3 100-31.9 24.4-69.2 40.2-106.6 54.6l-6.3-.3v-21.8c-19.6 1.6-19.7-14.6-31.6-23-18.7 20.6-31.6 40.8-58.9 51.1-12.7 4.8-19.6 10-25.9 21.8 34.9-16.4 91.2-13.5 98.8-10zM555.5 0l-.6 1.1-.3.9.6-.6zm-59.2 382.1c-33.9-56.9-75.3-118.4-150-115.5l-.3-6c-1.1-13.5 32.8 3.2 35.1-31l-14.4 7.2c-19.8-45.7-8.6-54.3-65.5-54.3-14.7 0-26.7 1.7-41.4 4.6 2.9 18.6 2.2 36.7-10.9 50.3l19.5 5.5c-1.7 3.2-2.9 6.3-2.9 9.8 0 21 42.8 2.9 42.8 33.6 0 18.4-36.8 60.1-54.9 60.1-8 0-53.7-50-53.4-60.1l.3-4.6 52.3-11.5c13-2.6 12.3-22.7-2.9-22.7-3.7 0-43.1 9.2-49.4 10.6-2-5.2-7.5-14.1-13.8-14.1-3.2 0-6.3 3.2-9.5 4-9.2 2.6-31 2.9-21.5 20.1L15.9 298.5c-5.5 1.1-8.9 6.3-8.9 11.8 0 6 5.5 10.9 11.5 10.9 8 0 131.3-28.4 147.4-32.2 2.6 3.2 4.6 6.3 7.8 8.6 20.1 14.4 59.8 85.9 76.4 85.9 24.1 0 58-22.4 71.3-41.9 3.2-4.3 6.9-7.5 12.4-6.9.6 13.8-31.6 34.2-33 43.7-1.4 10.2-1 35.2-.3 41.1 26.7 8.1 52-3.6 77.9-2.9 4.3-21 10.6-41.9 9.8-63.5l-.3-9.5c-1.4-34.2-10.9-38.5-34.8-58.6-1.1-1.1-2.6-2.6-3.7-4 2.2-1.4 1.1-1 4.6-1.7 88.5 0 56.3 183.6 111.5 229.9 33.1-15 72.5-27.9 103.5-47.2-29-25.6-52.6-45.7-72.7-79.9zm-196.2 46.1v27.2l11.8-3.4-2.9-23.8zm-68.7-150.4l24.1 61.2 21-13.8-31.3-50.9zm84.4 154.9l2 12.4c9-1.5 58.4-6.6 58.4-14.1 0-1.4-.6-3.2-.9-4.6-26.8 0-36.9 3.8-59.5 6.3z\"],\n    \"pied-piper-hat\": [640, 512, [], \"f4e5\", \"M640 24.9c-80.8 53.6-89.4 92.5-96.4 104.4-6.7 12.2-11.7 60.3-23.3 83.6-11.7 23.6-54.2 42.2-66.1 50-11.7 7.8-28.3 38.1-41.9 64.2-108.1-4.4-167.4 38.8-259.2 93.6 29.4-9.7 43.3-16.7 43.3-16.7 94.2-36 139.3-68.3 281.1-49.2 1.1 0 1.9.6 2.8.8 3.9 2.2 5.3 6.9 3.1 10.8l-53.9 95.8c-2.5 4.7-7.8 7.2-13.1 6.1-126.8-23.8-226.9 17.3-318.9 18.6C24.1 488 0 453.4 0 451.8c0-1.1.6-1.7 1.7-1.7 0 0 38.3 0 103.1-15.3C178.4 294.5 244 245.4 315.4 245.4c0 0 71.7 0 90.6 61.9 22.8-39.7 28.3-49.2 28.3-49.2 5.3-9.4 35-77.2 86.4-141.4 51.5-64 90.4-79.9 119.3-91.8z\"],\n    \"pied-piper-pp\": [448, 512, [], \"f1a7\", \"M205.3 174.6c0 21.1-14.2 38.1-31.7 38.1-7.1 0-12.8-1.2-17.2-3.7v-68c4.4-2.7 10.1-4.2 17.2-4.2 17.5 0 31.7 16.9 31.7 37.8zm52.6 67c-7.1 0-12.8 1.5-17.2 4.2v68c4.4 2.5 10.1 3.7 17.2 3.7 17.4 0 31.7-16.9 31.7-37.8 0-21.1-14.3-38.1-31.7-38.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM185 255.1c41 0 74.2-35.6 74.2-79.6 0-44-33.2-79.6-74.2-79.6-12 0-24.1 3.2-34.6 8.8h-45.7V311l51.8-10.1v-50.6c8.6 3.1 18.1 4.8 28.5 4.8zm158.4 25.3c0-44-33.2-79.6-73.9-79.6-3.2 0-6.4.2-9.6.7-3.7 12.5-10.1 23.8-19.2 33.4-13.8 15-32.2 23.8-51.8 24.8V416l51.8-10.1v-50.6c8.6 3.2 18.2 4.7 28.7 4.7 40.8 0 74-35.6 74-79.6z\"],\n    \"pinterest\": [496, 512, [], \"f0d2\", \"M496 256c0 137-111 248-248 248-25.6 0-50.2-3.9-73.4-11.1 10.1-16.5 25.2-43.5 30.8-65 3-11.6 15.4-59 15.4-59 8.1 15.4 31.7 28.5 56.8 28.5 74.8 0 128.7-68.8 128.7-154.3 0-81.9-66.9-143.2-152.9-143.2-107 0-163.9 71.8-163.9 150.1 0 36.4 19.4 81.7 50.3 96.1 4.7 2.2 7.2 1.2 8.3-3.3.8-3.4 5-20.3 6.9-28.1.6-2.5.3-4.7-1.7-7.1-10.1-12.5-18.3-35.3-18.3-56.6 0-54.7 41.4-107.6 112-107.6 60.9 0 103.6 41.5 103.6 100.9 0 67.1-33.9 113.6-78 113.6-24.3 0-42.6-20.1-36.7-44.8 7-29.5 20.5-61.3 20.5-82.6 0-19-10.2-34.9-31.4-34.9-24.9 0-44.9 25.7-44.9 60.2 0 22 7.4 36.8 7.4 36.8s-24.5 103.8-29 123.2c-5 21.4-3 51.6-.9 71.2C65.4 450.9 0 361.1 0 256 0 119 111 8 248 8s248 111 248 248z\"],\n    \"pinterest-p\": [384, 512, [], \"f231\", \"M204 6.5C101.4 6.5 0 74.9 0 185.6 0 256 39.6 296 63.6 296c9.9 0 15.6-27.6 15.6-35.4 0-9.3-23.7-29.1-23.7-67.8 0-80.4 61.2-137.4 140.4-137.4 68.1 0 118.5 38.7 118.5 109.8 0 53.1-21.3 152.7-90.3 152.7-24.9 0-46.2-18-46.2-43.8 0-37.8 26.4-74.4 26.4-113.4 0-66.2-93.9-54.2-93.9 25.8 0 16.8 2.1 35.4 9.6 50.7-13.8 59.4-42 147.9-42 209.1 0 18.9 2.7 37.5 4.5 56.4 3.4 3.8 1.7 3.4 6.9 1.5 50.4-69 48.6-82.5 71.4-172.8 12.3 23.4 44.1 36 69.3 36 106.2 0 153.9-103.5 153.9-196.8C384 71.3 298.2 6.5 204 6.5z\"],\n    \"pinterest-square\": [448, 512, [], \"f0d3\", \"M448 80v352c0 26.5-21.5 48-48 48H154.4c9.8-16.4 22.4-40 27.4-59.3 3-11.5 15.3-58.4 15.3-58.4 8 15.3 31.4 28.2 56.3 28.2 74.1 0 127.4-68.1 127.4-152.7 0-81.1-66.2-141.8-151.4-141.8-106 0-162.2 71.1-162.2 148.6 0 36 19.2 80.8 49.8 95.1 4.7 2.2 7.1 1.2 8.2-3.3.8-3.4 5-20.1 6.8-27.8.6-2.5.3-4.6-1.7-7-10.1-12.3-18.3-34.9-18.3-56 0-54.2 41-106.6 110.9-106.6 60.3 0 102.6 41.1 102.6 99.9 0 66.4-33.5 112.4-77.2 112.4-24.1 0-42.1-19.9-36.4-44.4 6.9-29.2 20.3-60.7 20.3-81.8 0-53-75.5-45.7-75.5 25 0 21.7 7.3 36.5 7.3 36.5-31.4 132.8-36.1 134.5-29.6 192.6l2.2.8H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48z\"],\n    \"playstation\": [576, 512, [], \"f3df\", \"M570.9 372.3c-11.3 14.2-38.8 24.3-38.8 24.3L327 470.2v-54.3l150.9-53.8c17.1-6.1 19.8-14.8 5.8-19.4-13.9-4.6-39.1-3.3-56.2 2.9L327 381.1v-56.4c23.2-7.8 47.1-13.6 75.7-16.8 40.9-4.5 90.9.6 130.2 15.5 44.2 14 49.2 34.7 38 48.9zm-224.4-92.5v-139c0-16.3-3-31.3-18.3-35.6-11.7-3.8-19 7.1-19 23.4v347.9l-93.8-29.8V32c39.9 7.4 98 24.9 129.2 35.4C424.1 94.7 451 128.7 451 205.2c0 74.5-46 102.8-104.5 74.6zM43.2 410.2c-45.4-12.8-53-39.5-32.3-54.8 19.1-14.2 51.7-24.9 51.7-24.9l134.5-47.8v54.5l-96.8 34.6c-17.1 6.1-19.7 14.8-5.8 19.4 13.9 4.6 39.1 3.3 56.2-2.9l46.4-16.9v48.8c-51.6 9.3-101.4 7.3-153.9-10z\"],\n    \"product-hunt\": [512, 512, [], \"f288\", \"M326.3 218.8c0 20.5-16.7 37.2-37.2 37.2h-70.3v-74.4h70.3c20.5 0 37.2 16.7 37.2 37.2zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-128.1-37.2c0-47.9-38.9-86.8-86.8-86.8H169.2v248h49.6v-74.4h70.3c47.9 0 86.8-38.9 86.8-86.8z\"],\n    \"pushed\": [432, 512, [], \"f3e1\", \"M407 111.9l-98.5-9 14-33.4c10.4-23.5-10.8-40.4-28.7-37L22.5 76.9c-15.1 2.7-26 18.3-21.4 36.6l105.1 348.3c6.5 21.3 36.7 24.2 47.7 7l35.3-80.8 235.2-231.3c16.4-16.8 4.3-42.9-17.4-44.8zM297.6 53.6c5.1-.7 7.5 2.5 5.2 7.4L286 100.9 108.6 84.6l189-31zM22.7 107.9c-3.1-5.1 1-10 6.1-9.1l248.7 22.7-96.9 230.7L22.7 107.9zM136 456.4c-2.6 4-7.9 3.1-9.4-1.2L43.5 179.7l127.7 197.6c-7 15-35.2 79.1-35.2 79.1zm272.8-314.5L210.1 337.3l89.7-213.7 106.4 9.7c4 1.1 5.7 5.3 2.6 8.6z\"],\n    \"python\": [448, 512, [], \"f3e2\", \"M439.8 200.5c-7.7-30.9-22.3-54.2-53.4-54.2h-40.1v47.4c0 36.8-31.2 67.8-66.8 67.8H172.7c-29.2 0-53.4 25-53.4 54.3v101.8c0 29 25.2 46 53.4 54.3 33.8 9.9 66.3 11.7 106.8 0 26.9-7.8 53.4-23.5 53.4-54.3v-40.7H226.2v-13.6h160.2c31.1 0 42.6-21.7 53.4-54.2 11.2-33.5 10.7-65.7 0-108.6zM286.2 404c11.1 0 20.1 9.1 20.1 20.3 0 11.3-9 20.4-20.1 20.4-11 0-20.1-9.2-20.1-20.4.1-11.3 9.1-20.3 20.1-20.3zM167.8 248.1h106.8c29.7 0 53.4-24.5 53.4-54.3V91.9c0-29-24.4-50.7-53.4-55.6-35.8-5.9-74.7-5.6-106.8.1-45.2 8-53.4 24.7-53.4 55.6v40.7h106.9v13.6h-147c-31.1 0-58.3 18.7-66.8 54.2-9.8 40.7-10.2 66.1 0 108.6 7.6 31.6 25.7 54.2 56.8 54.2H101v-48.8c0-35.3 30.5-66.4 66.8-66.4zm-6.7-142.6c-11.1 0-20.1-9.1-20.1-20.3.1-11.3 9-20.4 20.1-20.4 11 0 20.1 9.2 20.1 20.4s-9 20.3-20.1 20.3z\"],\n    \"qq\": [448, 512, [], \"f1d6\", \"M433.754 420.445c-11.526 1.393-44.86-52.741-44.86-52.741 0 31.345-16.136 72.247-51.051 101.786 16.842 5.192 54.843 19.167 45.803 34.421-7.316 12.343-125.51 7.881-159.632 4.037-34.122 3.844-152.316 8.306-159.632-4.037-9.045-15.25 28.918-29.214 45.783-34.415-34.92-29.539-51.059-70.445-51.059-101.792 0 0-33.334 54.134-44.859 52.741-5.37-.65-12.424-29.644 9.347-99.704 10.261-33.024 21.995-60.478 40.144-105.779C60.683 98.063 108.982.006 224 0c113.737.006 163.156 96.133 160.264 214.963 18.118 45.223 29.912 72.85 40.144 105.778 21.768 70.06 14.716 99.053 9.346 99.704z\"],\n    \"quinscape\": [512, 512, [], \"f459\", \"M313.6 474.6h-1a158.1 158.1 0 0 1 0-316.2c94.9 0 168.2 83.1 157 176.6 4 5.1 8.2 9.6 11.2 15.3 13.4-30.3 20.3-62.4 20.3-97.7C501.1 117.5 391.6 8 256.5 8S12 117.5 12 252.6s109.5 244.6 244.5 244.6a237.36 237.36 0 0 0 70.4-10.1c-5.2-3.5-8.9-8.1-13.3-12.5zm-.1-.1l.4.1zm78.4-168.9a99.2 99.2 0 1 0 99.2 99.2 99.18 99.18 0 0 0-99.2-99.2z\"],\n    \"quora\": [448, 512, [], \"f2c4\", \"M440.5 386.7h-29.3c-1.5 13.5-10.5 30.8-33 30.8-20.5 0-35.3-14.2-49.5-35.8 44.2-34.2 74.7-87.5 74.7-153C403.5 111.2 306.8 32 205 32 105.3 32 7.3 111.7 7.3 228.7c0 134.1 131.3 221.6 249 189C276 451.3 302 480 351.5 480c81.8 0 90.8-75.3 89-93.3zM297 329.2C277.5 300 253.3 277 205.5 277c-30.5 0-54.3 10-69 22.8l12.2 24.3c6.2-3 13-4 19.8-4 35.5 0 53.7 30.8 69.2 61.3-10 3-20.7 4.2-32.7 4.2-75 0-107.5-53-107.5-156.7C97.5 124.5 130 71 205 71c76.2 0 108.7 53.5 108.7 157.7.1 41.8-5.4 75.6-16.7 100.5z\"],\n    \"r-project\": [581, 512, [], \"f4f7\", \"M581 226.6C581 119.1 450.9 32 290.5 32S0 119.1 0 226.6C0 322.4 103.3 402 239.4 418.1V480h99.1v-61.5c24.3-2.7 47.6-7.4 69.4-13.9L448 480h112l-67.4-113.7c54.5-35.4 88.4-84.9 88.4-139.7zm-466.8 14.5c0-73.5 98.9-133 220.8-133s211.9 40.7 211.9 133c0 50.1-26.5 85-70.3 106.4-2.4-1.6-4.7-2.9-6.4-3.7-10.2-5.2-27.8-10.5-27.8-10.5s86.6-6.4 86.6-92.7-90.6-87.9-90.6-87.9h-199V361c-74.1-21.5-125.2-67.1-125.2-119.9zm225.1 38.3v-55.6c57.8 0 87.8-6.8 87.8 27.3 0 36.5-38.2 28.3-87.8 28.3zm-.9 72.5H365c10.8 0 18.9 11.7 24 19.2-16.1 1.9-33 2.8-50.6 2.9v-22.1z\"],\n    \"raspberry-pi\": [407, 512, [], \"f7bb\", \"M372 232.5l-3.7-6.5c.1-46.4-21.4-65.3-46.5-79.7 7.6-2 15.4-3.6 17.6-13.2 13.1-3.3 15.8-9.4 17.1-15.8 3.4-2.3 14.8-8.7 13.6-19.7 6.4-4.4 10-10.1 8.1-18.1 6.9-7.5 8.7-13.7 5.8-19.4 8.3-10.3 4.6-15.6 1.1-20.9 6.2-11.2.7-23.2-16.6-21.2-6.9-10.1-21.9-7.8-24.2-7.8-2.6-3.2-6-6-16.5-4.7-6.8-6.1-14.4-5-22.3-2.1-9.3-7.3-15.5-1.4-22.6.8C271.6.6 269 5.5 263.5 7.6c-12.3-2.6-16.1 3-22 8.9l-6.9-.1c-18.6 10.8-27.8 32.8-31.1 44.1-3.3-11.3-12.5-33.3-31.1-44.1l-6.9.1c-5.9-5.9-9.7-11.5-22-8.9-5.6-2-8.1-7-19.4-3.4-4.6-1.4-8.9-4.4-13.9-4.3-2.6.1-5.5 1-8.7 3.5-7.9-3-15.5-4-22.3 2.1-10.5-1.3-14 1.4-16.5 4.7-2.3 0-17.3-2.3-24.2 7.8C21.2 16 15.8 28 22 39.2c-3.5 5.4-7.2 10.7 1.1 20.9-2.9 5.7-1.1 11.9 5.8 19.4-1.8 8 1.8 13.7 8.1 18.1-1.2 11 10.2 17.4 13.6 19.7 1.3 6.4 4 12.4 17.1 15.8 2.2 9.5 10 11.2 17.6 13.2-25.1 14.4-46.6 33.3-46.5 79.7l-3.7 6.5c-28.8 17.2-54.7 72.7-14.2 117.7 2.6 14.1 7.1 24.2 11 35.4 5.9 45.2 44.5 66.3 54.6 68.8 14.9 11.2 30.8 21.8 52.2 29.2C159 504.2 181 512 203 512h1c22.1 0 44-7.8 64.2-28.4 21.5-7.4 37.3-18 52.2-29.2 10.2-2.5 48.7-23.6 54.6-68.8 3.9-11.2 8.4-21.3 11-35.4 40.6-45.1 14.7-100.5-14-117.7zm-22.2-8c-1.5 18.7-98.9-65.1-82.1-67.9 45.7-7.5 83.6 19.2 82.1 67.9zm-43 93.1c-24.5 15.8-59.8 5.6-78.8-22.8s-14.6-64.2 9.9-80c24.5-15.8 59.8-5.6 78.8 22.8s14.6 64.2-9.9 80zM238.9 29.3c.8 4.2 1.8 6.8 2.9 7.6 5.4-5.8 9.8-11.7 16.8-17.3 0 3.3-1.7 6.8 2.5 9.4 3.7-5 8.8-9.5 15.5-13.3-3.2 5.6-.6 7.3 1.2 9.6 5.1-4.4 10-8.8 19.4-12.3-2.6 3.1-6.2 6.2-2.4 9.8 5.3-3.3 10.6-6.6 23.1-8.9-2.8 3.1-8.7 6.3-5.1 9.4 6.6-2.5 14-4.4 22.1-5.4-3.9 3.2-7.1 6.3-3.9 8.8 7.1-2.2 16.9-5.1 26.4-2.6l-6 6.1c-.7.8 14.1.6 23.9.8-3.6 5-7.2 9.7-9.3 18.2 1 1 5.8.4 10.4 0-4.7 9.9-12.8 12.3-14.7 16.6 2.9 2.2 6.8 1.6 11.2.1-3.4 6.9-10.4 11.7-16 17.3 1.4 1 3.9 1.6 9.7.9-5.2 5.5-11.4 10.5-18.8 15 1.3 1.5 5.8 1.5 10 1.6-6.7 6.5-15.3 9.9-23.4 14.2 4 2.7 6.9 2.1 10 2.1-5.7 4.7-15.4 7.1-24.4 10 1.7 2.7 3.4 3.4 7.1 4.1-9.5 5.3-23.2 2.9-27 5.6.9 2.7 3.6 4.4 6.7 5.8-15.4.9-57.3-.6-65.4-32.3 15.7-17.3 44.4-37.5 93.7-62.6-38.4 12.8-73 30-102 53.5-34.3-15.9-10.8-55.9 5.8-71.8zm-34.4 114.6c24.2-.3 54.1 17.8 54 34.7-.1 15-21 27.1-53.8 26.9-32.1-.4-53.7-15.2-53.6-29.8 0-11.9 26.2-32.5 53.4-31.8zm-123-12.8c3.7-.7 5.4-1.5 7.1-4.1-9-2.8-18.7-5.3-24.4-10 3.1 0 6 .7 10-2.1-8.1-4.3-16.7-7.7-23.4-14.2 4.2-.1 8.7 0 10-1.6-7.4-4.5-13.6-9.5-18.8-15 5.8.7 8.3.1 9.7-.9-5.6-5.6-12.7-10.4-16-17.3 4.3 1.5 8.3 2 11.2-.1-1.9-4.2-10-6.7-14.7-16.6 4.6.4 9.4 1 10.4 0-2.1-8.5-5.8-13.3-9.3-18.2 9.8-.1 24.6 0 23.9-.8l-6-6.1c9.5-2.5 19.3.4 26.4 2.6 3.2-2.5-.1-5.6-3.9-8.8 8.1 1.1 15.4 2.9 22.1 5.4 3.5-3.1-2.3-6.3-5.1-9.4 12.5 2.3 17.8 5.6 23.1 8.9 3.8-3.6.2-6.7-2.4-9.8 9.4 3.4 14.3 7.9 19.4 12.3 1.7-2.3 4.4-4 1.2-9.6 6.7 3.8 11.8 8.3 15.5 13.3 4.1-2.6 2.5-6.2 2.5-9.4 7 5.6 11.4 11.5 16.8 17.3 1.1-.8 2-3.4 2.9-7.6 16.6 15.9 40.1 55.9 6 71.8-29-23.5-63.6-40.7-102-53.5 49.3 25 78 45.3 93.7 62.6-8 31.8-50 33.2-65.4 32.3 3.1-1.4 5.8-3.2 6.7-5.8-4-2.8-17.6-.4-27.2-5.6zm60.1 24.1c16.8 2.8-80.6 86.5-82.1 67.9-1.5-48.7 36.5-75.5 82.1-67.9zM38.2 342c-23.7-18.8-31.3-73.7 12.6-98.3 26.5-7 9 107.8-12.6 98.3zm91 98.2c-13.3 7.9-45.8 4.7-68.8-27.9-15.5-27.4-13.5-55.2-2.6-63.4 16.3-9.8 41.5 3.4 60.9 25.6 16.9 20 24.6 55.3 10.5 65.7zm-26.4-119.7c-24.5-15.8-28.9-51.6-9.9-80s54.3-38.6 78.8-22.8 28.9 51.6 9.9 80c-19.1 28.4-54.4 38.6-78.8 22.8zM205 496c-29.4 1.2-58.2-23.7-57.8-32.3-.4-12.7 35.8-22.6 59.3-22 23.7-1 55.6 7.5 55.7 18.9.5 11-28.8 35.9-57.2 35.4zm58.9-124.9c.2 29.7-26.2 53.8-58.8 54-32.6.2-59.2-23.8-59.4-53.4v-.6c-.2-29.7 26.2-53.8 58.8-54 32.6-.2 59.2 23.8 59.4 53.4v.6zm82.2 42.7c-25.3 34.6-59.6 35.9-72.3 26.3-13.3-12.4-3.2-50.9 15.1-72 20.9-23.3 43.3-38.5 58.9-26.6 10.5 10.3 16.7 49.1-1.7 72.3zm22.9-73.2c-21.5 9.4-39-105.3-12.6-98.3 43.9 24.7 36.3 79.6 12.6 98.3z\"],\n    \"ravelry\": [512, 512, [], \"f2d9\", \"M407.4 61.5C331.6 22.1 257.8 31 182.9 66c-11.3 5.2-15.5 10.6-19.9 19-10.3 19.2-16.2 37.4-19.9 52.7-21.2 25.6-36.4 56.1-43.3 89.9-10.6 18-20.9 41.4-23.1 71.4 0 0-.7 7.6-.5 7.9-35.3-4.6-76.2-27-76.2-27 9.1 14.5 61.3 32.3 76.3 37.9 0 0 1.7 98 64.5 131.2-11.3-17.2-13.3-20.2-13.3-20.2S94.8 369 100.4 324.7c.7 0 1.5.2 2.2.2 23.9 87.4 103.2 151.4 196.9 151.4 6.2 0 12.1-.2 18-.7 14 1.5 27.6.5 40.1-3.9 6.9-2.2 13.8-6.4 20.2-10.8 70.2-39.1 100.9-82 123.1-147.7 5.4-16 8.1-35.5 9.8-52.2 8.7-82.3-30.6-161.6-103.3-199.5zM138.8 163.2s-1.2 12.3-.7 19.7c-3.4 2.5-10.1 8.1-18.2 16.7 5.2-12.8 11.3-25.1 18.9-36.4zm-31.2 121.9c4.4-17.2 13.3-39.1 29.8-55.1 0 0 1.7 48 15.8 90.1l-41.4-6.9c-2.2-9.2-3.5-18.5-4.2-28.1zm7.9 42.8c14.8 3.2 34 7.6 43.1 9.1 27.3 76.8 108.3 124.3 108.3 124.3 1 .5 1.7.7 2.7 1-73.1-11.6-132.7-64.7-154.1-134.4zM386 444.1c-14.5 4.7-36.2 8.4-64.7 3.7 0 0-91.1-23.1-127.5-107.8 38.2.7 52.4-.2 78-3.9 39.4-5.7 79-16.2 115-33 11.8-5.4 11.1-19.4 9.6-29.8-2-12.8-11.1-12.1-21.4-4.7 0 0-82 58.6-189.8 53.7-18.7-32-26.8-110.8-26.8-110.8 41.4-35.2 83.2-59.6 168.4-52.4.2-6.4 3-27.1-20.4-28.1 0 0-93.5-11.1-146 33.5 2.5-16.5 5.9-29.3 11.1-39.4 34.2-30.8 79-49.5 128.3-49.5 106.4 0 193 87.1 193 194.5-.2 76-43.8 142-106.8 174z\"],\n    \"react\": [512, 512, [], \"f41b\", \"M418.2 177.2c-5.4-1.8-10.8-3.5-16.2-5.1.9-3.7 1.7-7.4 2.5-11.1 12.3-59.6 4.2-107.5-23.1-123.3-26.3-15.1-69.2.6-112.6 38.4-4.3 3.7-8.5 7.6-12.5 11.5-2.7-2.6-5.5-5.2-8.3-7.7-45.5-40.4-91.1-57.4-118.4-41.5-26.2 15.2-34 60.3-23 116.7 1.1 5.6 2.3 11.1 3.7 16.7-6.4 1.8-12.7 3.8-18.6 5.9C38.3 196.2 0 225.4 0 255.6c0 31.2 40.8 62.5 96.3 81.5 4.5 1.5 9 3 13.6 4.3-1.5 6-2.8 11.9-4 18-10.5 55.5-2.3 99.5 23.9 114.6 27 15.6 72.4-.4 116.6-39.1 3.5-3.1 7-6.3 10.5-9.7 4.4 4.3 9 8.4 13.6 12.4 42.8 36.8 85.1 51.7 111.2 36.6 27-15.6 35.8-62.9 24.4-120.5-.9-4.4-1.9-8.9-3-13.5 3.2-.9 6.3-1.9 9.4-2.9 57.7-19.1 99.5-50 99.5-81.7 0-30.3-39.4-59.7-93.8-78.4zM282.9 92.3c37.2-32.4 71.9-45.1 87.7-36 16.9 9.7 23.4 48.9 12.8 100.4-.7 3.4-1.4 6.7-2.3 10-22.2-5-44.7-8.6-67.3-10.6-13-18.6-27.2-36.4-42.6-53.1 3.9-3.7 7.7-7.2 11.7-10.7zM167.2 307.5c5.1 8.7 10.3 17.4 15.8 25.9-15.6-1.7-31.1-4.2-46.4-7.5 4.4-14.4 9.9-29.3 16.3-44.5 4.6 8.8 9.3 17.5 14.3 26.1zm-30.3-120.3c14.4-3.2 29.7-5.8 45.6-7.8-5.3 8.3-10.5 16.8-15.4 25.4-4.9 8.5-9.7 17.2-14.2 26-6.3-14.9-11.6-29.5-16-43.6zm27.4 68.9c6.6-13.8 13.8-27.3 21.4-40.6s15.8-26.2 24.4-38.9c15-1.1 30.3-1.7 45.9-1.7s31 .6 45.9 1.7c8.5 12.6 16.6 25.5 24.3 38.7s14.9 26.7 21.7 40.4c-6.7 13.8-13.9 27.4-21.6 40.8-7.6 13.3-15.7 26.2-24.2 39-14.9 1.1-30.4 1.6-46.1 1.6s-30.9-.5-45.6-1.4c-8.7-12.7-16.9-25.7-24.6-39s-14.8-26.8-21.5-40.6zm180.6 51.2c5.1-8.8 9.9-17.7 14.6-26.7 6.4 14.5 12 29.2 16.9 44.3-15.5 3.5-31.2 6.2-47 8 5.4-8.4 10.5-17 15.5-25.6zm14.4-76.5c-4.7-8.8-9.5-17.6-14.5-26.2-4.9-8.5-10-16.9-15.3-25.2 16.1 2 31.5 4.7 45.9 8-4.6 14.8-10 29.2-16.1 43.4zM256.2 118.3c10.5 11.4 20.4 23.4 29.6 35.8-19.8-.9-39.7-.9-59.5 0 9.8-12.9 19.9-24.9 29.9-35.8zM140.2 57c16.8-9.8 54.1 4.2 93.4 39 2.5 2.2 5 4.6 7.6 7-15.5 16.7-29.8 34.5-42.9 53.1-22.6 2-45 5.5-67.2 10.4-1.3-5.1-2.4-10.3-3.5-15.5-9.4-48.4-3.2-84.9 12.6-94zm-24.5 263.6c-4.2-1.2-8.3-2.5-12.4-3.9-21.3-6.7-45.5-17.3-63-31.2-10.1-7-16.9-17.8-18.8-29.9 0-18.3 31.6-41.7 77.2-57.6 5.7-2 11.5-3.8 17.3-5.5 6.8 21.7 15 43 24.5 63.6-9.6 20.9-17.9 42.5-24.8 64.5zm116.6 98c-16.5 15.1-35.6 27.1-56.4 35.3-11.1 5.3-23.9 5.8-35.3 1.3-15.9-9.2-22.5-44.5-13.5-92 1.1-5.6 2.3-11.2 3.7-16.7 22.4 4.8 45 8.1 67.9 9.8 13.2 18.7 27.7 36.6 43.2 53.4-3.2 3.1-6.4 6.1-9.6 8.9zm24.5-24.3c-10.2-11-20.4-23.2-30.3-36.3 9.6.4 19.5.6 29.5.6 10.3 0 20.4-.2 30.4-.7-9.2 12.7-19.1 24.8-29.6 36.4zm130.7 30c-.9 12.2-6.9 23.6-16.5 31.3-15.9 9.2-49.8-2.8-86.4-34.2-4.2-3.6-8.4-7.5-12.7-11.5 15.3-16.9 29.4-34.8 42.2-53.6 22.9-1.9 45.7-5.4 68.2-10.5 1 4.1 1.9 8.2 2.7 12.2 4.9 21.6 5.7 44.1 2.5 66.3zm18.2-107.5c-2.8.9-5.6 1.8-8.5 2.6-7-21.8-15.6-43.1-25.5-63.8 9.6-20.4 17.7-41.4 24.5-62.9 5.2 1.5 10.2 3.1 15 4.7 46.6 16 79.3 39.8 79.3 58 0 19.6-34.9 44.9-84.8 61.4zm-149.7-15c25.3 0 45.8-20.5 45.8-45.8s-20.5-45.8-45.8-45.8c-25.3 0-45.8 20.5-45.8 45.8s20.5 45.8 45.8 45.8z\"],\n    \"reacteurope\": [576, 512, [], \"f75d\", \"M250.6 211.74l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm63.7 0l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.2-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm-91.3 50.5h-3.4c-4.8 0-3.8 4-3.8 12.1 0 4.7-2.3 6.1-5.8 6.1s-5.8-1.4-5.8-6.1v-36.6c0-4.7 2.3-6.1 5.8-6.1s5.8 1.4 5.8 6.1c0 7.2-.7 10.5 3.8 10.5h3.4c4.7-.1 3.8-3.9 3.8-12.3 0-9.9-6.7-14.1-16.8-14.1h-.2c-10.1 0-16.8 4.2-16.8 14.1V276c0 10.4 6.7 14.1 16.8 14.1h.2c10.1 0 16.8-3.8 16.8-14.1 0-9.86 1.1-13.76-3.8-13.76zm-80.7 17.4h-14.7v-19.3H139c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-11.4v-18.3H142c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-21.7c-2.4-.1-3.7 1.3-3.7 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h21.9c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8zm-42-18.5c4.6-2 7.3-6 7.3-12.4v-11.9c0-10.1-6.7-14.1-16.8-14.1H77.4c-2.5 0-3.8 1.3-3.8 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5 0 3.8-1.3 3.8-3.8v-22.9h5.6l7.4 23.5a4.1 4.1 0 0 0 4.3 3.2h3.3c2.8 0 4-1.8 3.2-4.4zm-3.8-14c0 4.8-2.5 6.1-6.1 6.1h-5.8v-20.9h5.8c3.6 0 6.1 1.3 6.1 6.1zM176 226a3.82 3.82 0 0 0-4.2-3.4h-6.9a3.68 3.68 0 0 0-4 3.4l-11 59.2c-.5 2.7.9 4.1 3.4 4.1h3a3.74 3.74 0 0 0 4.1-3.5l1.8-11.3h12.2l1.8 11.3a3.74 3.74 0 0 0 4.1 3.5h3.5c2.6 0 3.9-1.4 3.4-4.1zm-12.3 39.3l4.7-29.7 4.7 29.7zm89.3 20.2v-53.2h7.5c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-25.8c-2.5 0-3.8 1.3-3.8 3.8v2.1c0 2.5 1.3 3.8 3.8 3.8h7.3v53.2c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5.04 3.8-1.3 3.8-3.76zm248-.8h-19.4V258h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9H501a1.81 1.81 0 0 0 2-1.9v-.8a1.84 1.84 0 0 0-2-1.96zm-93.1-62.9h-.8c-10.1 0-15.3 4.7-15.3 14.1V276c0 9.3 5.2 14.1 15.3 14.1h.8c10.1 0 15.3-4.8 15.3-14.1v-40.1c0-9.36-5.2-14.06-15.3-14.06zm10.2 52.4c-.1 8-3 11.1-10.5 11.1s-10.5-3.1-10.5-11.1v-36.6c0-7.9 3-11.1 10.5-11.1s10.5 3.2 10.5 11.1zm-46.5-14.5c6.1-1.6 9.2-6.1 9.2-13.3v-9.7c0-9.4-5.2-14.1-15.3-14.1h-13.7a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.9h11.6l10.4 27.2a2.32 2.32 0 0 0 2.3 1.5h1.5c1.4 0 2-1 1.5-2.3zm-6.4-3.9H355v-28.5h10.2c7.5 0 10.5 3.1 10.5 11.1v6.4c0 7.84-3 11.04-10.5 11.04zm85.9-33.1h-13.7a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.1h10.6c10.1 0 15.3-4.8 15.3-14.1v-10.5c0-9.4-5.2-14.1-15.3-14.1zm10.2 22.8c0 7.9-3 11.1-10.5 11.1h-10.2v-29.2h10.2c7.5-.1 10.5 3.1 10.5 11zM259.5 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm227.6-136.1a364.42 364.42 0 0 0-35.6-11.3c19.6-78 11.6-134.7-22.3-153.9C394.7-12.66 343.3 11 291 61.94q5.1 4.95 10.2 10.2c82.5-80 119.6-53.5 120.9-52.8 22.4 12.7 36 55.8 15.5 137.8a587.83 587.83 0 0 0-84.6-13C281.1 43.64 212.4 2 170.8 2 140 2 127 23 123.2 29.74c-18.1 32-13.3 84.2.1 133.8-70.5 20.3-120.7 54.1-120.3 95 .5 59.6 103.2 87.8 122.1 92.8-20.5 81.9-10.1 135.6 22.3 153.9 28 15.8 75.1 6 138.2-55.2q-5.1-4.95-10.2-10.2c-82.5 80-119.7 53.5-120.9 52.8-22.3-12.6-36-55.6-15.5-137.9 12.4 2.9 41.8 9.5 84.6 13 71.9 100.4 140.6 142 182.1 142 30.8 0 43.8-21 47.6-27.7 18-31.9 13.3-84.1-.1-133.8 152.3-43.8 156.2-130.2 33.9-176.3zM135.9 36.84c2.9-5.1 11.9-20.3 34.9-20.3 36.8 0 98.8 39.6 163.3 126.2a714 714 0 0 0-93.9.9 547.76 547.76 0 0 1 42.2-52.4Q277.3 86 272.2 81a598.25 598.25 0 0 0-50.7 64.2 569.69 569.69 0 0 0-84.4 14.6c-.2-1.4-24.3-82.2-1.2-123zm304.8 438.3c-2.9 5.1-11.8 20.3-34.9 20.3-36.7 0-98.7-39.4-163.3-126.2a695.38 695.38 0 0 0 93.9-.9 547.76 547.76 0 0 1-42.2 52.4q5.1 5.25 10.2 10.2a588.47 588.47 0 0 0 50.7-64.2c47.3-4.7 80.3-13.5 84.4-14.6 22.7 84.4 4.5 117 1.2 123zm9.1-138.6c-3.6-11.9-7.7-24.1-12.4-36.4a12.67 12.67 0 0 1-10.7-5.7l-.1.1a19.61 19.61 0 0 1-5.4 3.6c5.7 14.3 10.6 28.4 14.7 42.2a535.3 535.3 0 0 1-72 13c3.5-5.3 17.2-26.2 32.2-54.2a24.6 24.6 0 0 1-6-3.2c-1.1 1.2-3.6 4.2-10.9 4.2-6.2 11.2-17.4 30.9-33.9 55.2a711.91 711.91 0 0 1-112.4 1c-7.9-11.2-21.5-31.1-36.8-57.8a21 21 0 0 1-3-1.5c-1.9 1.6-3.9 3.2-12.6 3.2 6.3 11.2 17.5 30.7 33.8 54.6a548.81 548.81 0 0 1-72.2-11.7q5.85-21 14.1-42.9c-3.2 0-5.4.2-8.4-1a17.58 17.58 0 0 1-6.9 1c-4.9 13.4-9.1 26.5-12.7 39.4C-31.7 297-12.1 216 126.7 175.64c3.6 11.9 7.7 24.1 12.4 36.4 10.4 0 12.9 3.4 14.4 5.3a12 12 0 0 1 2.3-2.2c-5.8-14.7-10.9-29.2-15.2-43.3 7-1.8 32.4-8.4 72-13-15.9 24.3-26.7 43.9-32.8 55.3a14.22 14.22 0 0 1 6.4 8 23.42 23.42 0 0 1 10.2-8.4c6.5-11.7 17.9-31.9 34.8-56.9a711.72 711.72 0 0 1 112.4-1c31.5 44.6 28.9 48.1 42.5 64.5a21.42 21.42 0 0 1 10.4-7.4c-6.4-11.4-17.6-31-34.3-55.5 40.4 4.1 65 10 72.2 11.7-4 14.4-8.9 29.2-14.6 44.2a20.74 20.74 0 0 1 6.8 4.3l.1.1a12.72 12.72 0 0 1 8.9-5.6c4.9-13.4 9.2-26.6 12.8-39.5a359.71 359.71 0 0 1 34.5 11c106.1 39.9 74 87.9 72.6 90.4-19.8 35.1-80.1 55.2-105.7 62.5zm-114.4-114h-1.2a1.74 1.74 0 0 0-1.9 1.9v49.8c0 7.9-2.6 11.1-10.1 11.1s-10.1-3.1-10.1-11.1v-49.8a1.69 1.69 0 0 0-1.9-1.9H309a1.81 1.81 0 0 0-2 1.9v51.5c0 9.6 5 14.1 15.1 14.1h.4c10.1 0 15.1-4.6 15.1-14.1v-51.5a2 2 0 0 0-2.2-1.9zM321.7 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm-31.1 7.4l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm5.1-30.8h-19.4v-26.7h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h22.5a1.77 1.77 0 0 0 2-1.9v-.8a1.83 1.83 0 0 0-2-2.06zm-7.4-99.4L286 192l-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1z\"],\n    \"readme\": [576, 512, [], \"f4d5\", \"M528.3 46.5H388.5c-48.1 0-89.9 33.3-100.4 80.3-10.6-47-52.3-80.3-100.4-80.3H48c-26.5 0-48 21.5-48 48v245.8c0 26.5 21.5 48 48 48h89.7c102.2 0 132.7 24.4 147.3 75 .7 2.8 5.2 2.8 6 0 14.7-50.6 45.2-75 147.3-75H528c26.5 0 48-21.5 48-48V94.6c0-26.4-21.3-47.9-47.7-48.1zM242 311.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5V289c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V251zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm259.3 121.7c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5V228c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.8c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V190z\"],\n    \"rebel\": [512, 512, [], \"f1d0\", \"M256.5 504C117.2 504 9 387.8 13.2 249.9 16 170.7 56.4 97.7 129.7 49.5c.3 0 1.9-.6 1.1.8-5.8 5.5-111.3 129.8-14.1 226.4 49.8 49.5 90 2.5 90 2.5 38.5-50.1-.6-125.9-.6-125.9-10-24.9-45.7-40.1-45.7-40.1l28.8-31.8c24.4 10.5 43.2 38.7 43.2 38.7.8-29.6-21.9-61.4-21.9-61.4L255.1 8l44.3 50.1c-20.5 28.8-21.9 62.6-21.9 62.6 13.8-23 43.5-39.3 43.5-39.3l28.5 31.8c-27.4 8.9-45.4 39.9-45.4 39.9-15.8 28.5-27.1 89.4.6 127.3 32.4 44.6 87.7-2.8 87.7-2.8 102.7-91.9-10.5-225-10.5-225-6.1-5.5.8-2.8.8-2.8 50.1 36.5 114.6 84.4 116.2 204.8C500.9 400.2 399 504 256.5 504z\"],\n    \"red-river\": [448, 512, [], \"f3e3\", \"M353.2 32H94.8C42.4 32 0 74.4 0 126.8v258.4C0 437.6 42.4 480 94.8 480h258.4c52.4 0 94.8-42.4 94.8-94.8V126.8c0-52.4-42.4-94.8-94.8-94.8zM144.9 200.9v56.3c0 27-21.9 48.9-48.9 48.9V151.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9h-56.3c-12.3-.6-24.6 11.6-24 24zm176.3 72h-56.3c-12.3-.6-24.6 11.6-24 24v56.3c0 27-21.9 48.9-48.9 48.9V247.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9z\"],\n    \"reddit\": [512, 512, [], \"f1a1\", \"M201.5 305.5c-13.8 0-24.9-11.1-24.9-24.6 0-13.8 11.1-24.9 24.9-24.9 13.6 0 24.6 11.1 24.6 24.9 0 13.6-11.1 24.6-24.6 24.6zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-132.3-41.2c-9.4 0-17.7 3.9-23.8 10-22.4-15.5-52.6-25.5-86.1-26.6l17.4-78.3 55.4 12.5c0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.3 24.9-24.9s-11.1-24.9-24.9-24.9c-9.7 0-18 5.8-22.1 13.8l-61.2-13.6c-3-.8-6.1 1.4-6.9 4.4l-19.1 86.4c-33.2 1.4-63.1 11.3-85.5 26.8-6.1-6.4-14.7-10.2-24.1-10.2-34.9 0-46.3 46.9-14.4 62.8-1.1 5-1.7 10.2-1.7 15.5 0 52.6 59.2 95.2 132 95.2 73.1 0 132.3-42.6 132.3-95.2 0-5.3-.6-10.8-1.9-15.8 31.3-16 19.8-62.5-14.9-62.5zM302.8 331c-18.2 18.2-76.1 17.9-93.6 0-2.2-2.2-6.1-2.2-8.3 0-2.5 2.5-2.5 6.4 0 8.6 22.8 22.8 87.3 22.8 110.2 0 2.5-2.2 2.5-6.1 0-8.6-2.2-2.2-6.1-2.2-8.3 0zm7.7-75c-13.6 0-24.6 11.1-24.6 24.9 0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.1 24.9-24.6 0-13.8-11-24.9-24.9-24.9z\"],\n    \"reddit-alien\": [512, 512, [], \"f281\", \"M440.3 203.5c-15 0-28.2 6.2-37.9 15.9-35.7-24.7-83.8-40.6-137.1-42.3L293 52.3l88.2 19.8c0 21.6 17.6 39.2 39.2 39.2 22 0 39.7-18.1 39.7-39.7s-17.6-39.7-39.7-39.7c-15.4 0-28.7 9.3-35.3 22l-97.4-21.6c-4.9-1.3-9.7 2.2-11 7.1L246.3 177c-52.9 2.2-100.5 18.1-136.3 42.8-9.7-10.1-23.4-16.3-38.4-16.3-55.6 0-73.8 74.6-22.9 100.1-1.8 7.9-2.6 16.3-2.6 24.7 0 83.8 94.4 151.7 210.3 151.7 116.4 0 210.8-67.9 210.8-151.7 0-8.4-.9-17.2-3.1-25.1 49.9-25.6 31.5-99.7-23.8-99.7zM129.4 308.9c0-22 17.6-39.7 39.7-39.7 21.6 0 39.2 17.6 39.2 39.7 0 21.6-17.6 39.2-39.2 39.2-22 .1-39.7-17.6-39.7-39.2zm214.3 93.5c-36.4 36.4-139.1 36.4-175.5 0-4-3.5-4-9.7 0-13.7 3.5-3.5 9.7-3.5 13.2 0 27.8 28.5 120 29 149 0 3.5-3.5 9.7-3.5 13.2 0 4.1 4 4.1 10.2.1 13.7zm-.8-54.2c-21.6 0-39.2-17.6-39.2-39.2 0-22 17.6-39.7 39.2-39.7 22 0 39.7 17.6 39.7 39.7-.1 21.5-17.7 39.2-39.7 39.2z\"],\n    \"reddit-square\": [448, 512, [], \"f1a2\", \"M283.2 345.5c2.7 2.7 2.7 6.8 0 9.2-24.5 24.5-93.8 24.6-118.4 0-2.7-2.4-2.7-6.5 0-9.2 2.4-2.4 6.5-2.4 8.9 0 18.7 19.2 81 19.6 100.5 0 2.4-2.3 6.6-2.3 9 0zm-91.3-53.8c0-14.9-11.9-26.8-26.5-26.8-14.9 0-26.8 11.9-26.8 26.8 0 14.6 11.9 26.5 26.8 26.5 14.6 0 26.5-11.9 26.5-26.5zm90.7-26.8c-14.6 0-26.5 11.9-26.5 26.8 0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-11.9 26.8-26.5 0-14.9-11.9-26.8-26.8-26.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-99.7 140.6c-10.1 0-19 4.2-25.6 10.7-24.1-16.7-56.5-27.4-92.5-28.6l18.7-84.2 59.5 13.4c0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-12.2 26.8-26.8 0-14.6-11.9-26.8-26.8-26.8-10.4 0-19.3 6.2-23.8 14.9l-65.7-14.6c-3.3-.9-6.5 1.5-7.4 4.8l-20.5 92.8c-35.7 1.5-67.8 12.2-91.9 28.9-6.5-6.8-15.8-11-25.9-11-37.5 0-49.8 50.4-15.5 67.5-1.2 5.4-1.8 11-1.8 16.7 0 56.5 63.7 102.3 141.9 102.3 78.5 0 142.2-45.8 142.2-102.3 0-5.7-.6-11.6-2.1-17 33.6-17.2 21.2-67.2-16.1-67.2z\"],\n    \"redhat\": [512, 512, [], \"f7bc\", \"M341.52 285.56c33.65 0 82.34-6.94 82.34-47 .22-6.74.86-1.82-20.88-96.24-4.62-19.15-8.68-27.84-42.31-44.65-26.09-13.34-82.92-35.37-99.73-35.37-15.66 0-20.2 20.17-38.87 20.17-18 0-31.31-15.06-48.12-15.06-16.14 0-26.66 11-34.78 33.62-27.5 77.55-26.28 74.27-26.12 78.27 0 24.8 97.64 106.11 228.47 106.11M429 254.84c4.65 22 4.65 24.35 4.65 27.25 0 37.66-42.33 58.56-98 58.56-125.74.08-235.91-73.65-235.91-122.33a49.55 49.55 0 0 1 4.06-19.72C58.56 200.86 0 208.93 0 260.63c0 84.67 200.63 189 359.49 189 121.79 0 152.51-55.08 152.51-98.58 0-34.21-29.59-73.05-82.93-96.24\"],\n    \"renren\": [512, 512, [], \"f18b\", \"M214 169.1c0 110.4-61 205.4-147.6 247.4C30 373.2 8 317.7 8 256.6 8 133.9 97.1 32.2 214 12.5v156.6zM255 504c-42.9 0-83.3-11-118.5-30.4C193.7 437.5 239.9 382.9 255 319c15.5 63.9 61.7 118.5 118.8 154.7C338.7 493 298.3 504 255 504zm190.6-87.5C359 374.5 298 279.6 298 169.1V12.5c116.9 19.7 206 121.4 206 244.1 0 61.1-22 116.6-58.4 159.9z\"],\n    \"replyd\": [448, 512, [], \"f3e6\", \"M320 480H128C57.6 480 0 422.4 0 352V160C0 89.6 57.6 32 128 32h192c70.4 0 128 57.6 128 128v192c0 70.4-57.6 128-128 128zM193.4 273.2c-6.1-2-11.6-3.1-16.4-3.1-7.2 0-13.5 1.9-18.9 5.6-5.4 3.7-9.6 9-12.8 15.8h-1.1l-4.2-18.3h-28v138.9h36.1v-89.7c1.5-5.4 4.4-9.8 8.7-13.2 4.3-3.4 9.8-5.1 16.2-5.1 4.6 0 9.8 1 15.6 3.1l4.8-34zm115.2 103.4c-3.2 2.4-7.7 4.8-13.7 7.1-6 2.3-12.8 3.5-20.4 3.5-12.2 0-21.1-3-26.5-8.9-5.5-5.9-8.5-14.7-9-26.4h83.3c.9-4.8 1.6-9.4 2.1-13.9.5-4.4.7-8.6.7-12.5 0-10.7-1.6-19.7-4.7-26.9-3.2-7.2-7.3-13-12.5-17.2-5.2-4.3-11.1-7.3-17.8-9.2-6.7-1.8-13.5-2.8-20.6-2.8-21.1 0-37.5 6.1-49.2 18.3s-17.5 30.5-17.5 55c0 22.8 5.2 40.7 15.6 53.7 10.4 13.1 26.8 19.6 49.2 19.6 10.7 0 20.9-1.5 30.4-4.6 9.5-3.1 17.1-6.8 22.6-11.2l-12-23.6zm-21.8-70.3c3.8 5.4 5.3 13.1 4.6 23.1h-51.7c.9-9.4 3.7-17 8.2-22.6 4.5-5.6 11.5-8.5 21-8.5 8.2-.1 14.1 2.6 17.9 8zm79.9 2.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4s2 11.7 6.1 15.6zm0 100.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4 0 6.6 2 11.7 6.1 15.6z\"],\n    \"researchgate\": [448, 512, [], \"f4f8\", \"M0 32v448h448V32H0zm262.2 334.4c-6.6 3-33.2 6-50-14.2-9.2-10.6-25.3-33.3-42.2-63.6-8.9 0-14.7 0-21.4-.6v46.4c0 23.5 6 21.2 25.8 23.9v8.1c-6.9-.3-23.1-.8-35.6-.8-13.1 0-26.1.6-33.6.8v-8.1c15.5-2.9 22-1.3 22-23.9V225c0-22.6-6.4-21-22-23.9V193c25.8 1 53.1-.6 70.9-.6 31.7 0 55.9 14.4 55.9 45.6 0 21.1-16.7 42.2-39.2 47.5 13.6 24.2 30 45.6 42.2 58.9 7.2 7.8 17.2 14.7 27.2 14.7v7.3zm22.9-135c-23.3 0-32.2-15.7-32.2-32.2V167c0-12.2 8.8-30.4 34-30.4s30.4 17.9 30.4 17.9l-10.7 7.2s-5.5-12.5-19.7-12.5c-7.9 0-19.7 7.3-19.7 19.7v26.8c0 13.4 6.6 23.3 17.9 23.3 14.1 0 21.5-10.9 21.5-26.8h-17.9v-10.7h30.4c0 20.5 4.7 49.9-34 49.9zm-116.5 44.7c-9.4 0-13.6-.3-20-.8v-69.7c6.4-.6 15-.6 22.5-.6 23.3 0 37.2 12.2 37.2 34.5 0 21.9-15 36.6-39.7 36.6z\"],\n    \"resolving\": [496, 512, [], \"f3e7\", \"M281.2 278.2c46-13.3 49.6-23.5 44-43.4L314 195.5c-6.1-20.9-18.4-28.1-71.1-12.8L54.7 236.8l28.6 98.6 197.9-57.2zM248.5 8C131.4 8 33.2 88.7 7.2 197.5l221.9-63.9c34.8-10.2 54.2-11.7 79.3-8.2 36.3 6.1 52.7 25 61.4 55.2l10.7 37.8c8.2 28.1 1 50.6-23.5 73.6-19.4 17.4-31.2 24.5-61.4 33.2L203 351.8l220.4 27.1 9.7 34.2-48.1 13.3-286.8-37.3 23 80.2c36.8 22 80.3 34.7 126.3 34.7 137 0 248.5-111.4 248.5-248.3C497 119.4 385.5 8 248.5 8zM38.3 388.6L0 256.8c0 48.5 14.3 93.4 38.3 131.8z\"],\n    \"rev\": [448, 512, [], \"f5b2\", \"M289.67 274.89a65.57 65.57 0 1 1-65.56-65.56 65.64 65.64 0 0 1 65.56 65.56zm139.55-5.05h-.13a204.69 204.69 0 0 0-74.32-153l-45.38 26.2a157.07 157.07 0 0 1 71.81 131.84C381.2 361.5 310.73 432 224.11 432S67 361.5 67 274.88c0-81.88 63-149.27 143-156.43v39.12l108.77-62.79L210 32v38.32c-106.7 7.25-191 96-191 204.57 0 111.59 89.12 202.29 200.06 205v.11h210.16V269.84z\"],\n    \"rocketchat\": [576, 512, [], \"f3e8\", \"M486.41 107.57c-76.93-50.83-179.18-62.4-264.12-47.07C127.26-31.16 20.77 11 0 23.12c0 0 73.08 62.1 61.21 116.49-86.52 88.2-45.39 186.4 0 232.77C73.08 426.77 0 488.87 0 488.87c20.57 12.16 126.77 54.19 222.29-37 84.75 15.23 187 3.76 264.12-47.16 119.26-76.14 119.65-220.61 0-297.15zM294.18 404.22a339.53 339.53 0 0 1-88.11-11.37l-19.77 19.09a179.74 179.74 0 0 1-36.59 27.39A143.14 143.14 0 0 1 98 454.06c1-1.78 1.88-3.56 2.77-5.24q29.67-55 16-98.69c-32.53-25.61-52-58.34-52-94.13 0-82 102.74-148.43 229.41-148.43S523.59 174 523.59 256 420.85 404.22 294.18 404.22zM184.12 291.3a34.32 34.32 0 0 1-34.8-33.72c-.7-45.39 67.83-46.38 68.52-1.09v.51a34 34 0 0 1-33.72 34.32zm73.77-33.72c-.79-45.39 67.74-46.48 68.53-1.19v.61c.39 45.08-67.74 45.57-68.53.58zm143.38 33.72a34.33 34.33 0 0 1-34.81-33.72c-.69-45.39 67.84-46.38 68.53-1.09v.51a33.89 33.89 0 0 1-33.72 34.32z\"],\n    \"rockrms\": [496, 512, [], \"f3e9\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm157.4 419.5h-90l-112-131.3c-17.9-20.4-3.9-56.1 26.6-56.1h75.3l-84.6-99.3-84.3 98.9h-90L193.5 67.2c14.4-18.4 41.3-17.3 54.5 0l157.7 185.1c19 22.8 2 57.2-27.6 56.1-.6 0-74.2.2-74.2.2l101.5 118.9z\"],\n    \"safari\": [512, 512, [], \"f267\", \"M236.9 256.8c0-9.1 6.6-17.7 16.3-17.7 8.9 0 17.4 6.4 17.4 16.1 0 9.1-6.4 17.7-16.1 17.7-9 0-17.6-6.7-17.6-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-26.6 0c0-122.3-99.1-221.4-221.4-221.4S34.6 133.7 34.6 256 133.7 477.4 256 477.4 477.4 378.3 477.4 256zm-72.5 96.6c0 3.6 13 10.2 16.3 12.2-27.4 41.5-69.8 71.4-117.9 83.3l-4.4-18.5c-.3-2.5-1.9-2.8-4.2-2.8-1.9 0-3 2.8-2.8 4.2l4.4 18.8c-13.3 2.8-26.8 4.2-40.4 4.2-36.3 0-72-10.2-103-29.1 1.7-2.8 12.2-18 12.2-20.2 0-1.9-1.7-3.6-3.6-3.6-3.9 0-12.2 16.6-14.7 19.9-41.8-27.7-72-70.6-83.6-119.6l19.1-4.2c2.2-.6 2.8-2.2 2.8-4.2 0-1.9-2.8-3-4.4-2.8L62 294.5c-2.5-12.7-3.9-25.5-3.9-38.5 0-37.1 10.5-73.6 30.2-104.9 2.8 1.7 16.1 10.8 18.3 10.8 1.9 0 3.6-1.4 3.6-3.3 0-3.9-14.7-11.3-18-13.6 28.2-41.2 71.1-70.9 119.8-81.9l4.2 18.5c.6 2.2 2.2 2.8 4.2 2.8s3-2.8 2.8-4.4L219 61.7c12.2-2.2 24.6-3.6 37.1-3.6 37.1 0 73.3 10.5 104.9 30.2-1.9 2.8-10.8 15.8-10.8 18 0 1.9 1.4 3.6 3.3 3.6 3.9 0 11.3-14.4 13.3-17.7 41 27.7 70.3 70 81.7 118.2l-15.5 3.3c-2.5.6-2.8 2.2-2.8 4.4 0 1.9 2.8 3 4.2 2.8l15.8-3.6c2.5 12.7 3.9 25.7 3.9 38.7 0 36.3-10 72-28.8 102.7-2.8-1.4-14.4-9.7-16.6-9.7-2.1 0-3.8 1.7-3.8 3.6zm-33.2-242.2c-13 12.2-134.2 123.7-137.6 129.5l-96.6 160.5c12.7-11.9 134.2-124 137.3-129.3l96.9-160.7z\"],\n    \"salesforce\": [640, 512, [], \"f83b\", \"M248.89 245.64h-26.35c.69-5.16 3.32-14.12 13.64-14.12 6.75 0 11.97 3.82 12.71 14.12zm136.66-13.88c-.47 0-14.11-1.77-14.11 20s13.63 20 14.11 20c13 0 14.11-13.54 14.11-20 0-21.76-13.66-20-14.11-20zm-243.22 23.76a8.63 8.63 0 0 0-3.29 7.29c0 4.78 2.08 6.05 3.29 7.05 4.7 3.7 15.07 2.12 20.93.95v-16.94c-5.32-1.07-16.73-1.96-20.93 1.65zM640 232c0 87.58-80 154.39-165.36 136.43-18.37 33-70.73 70.75-132.2 41.63-41.16 96.05-177.89 92.18-213.81-5.17C8.91 428.78-50.19 266.52 53.36 205.61 18.61 126.18 76 32 167.67 32a124.24 124.24 0 0 1 98.56 48.7c20.7-21.4 49.4-34.81 81.15-34.81 42.34 0 79 23.52 98.8 58.57C539 63.78 640 132.69 640 232zm-519.55 31.8c0-11.76-11.69-15.17-17.87-17.17-5.27-2.11-13.41-3.51-13.41-8.94 0-9.46 17-6.66 25.17-2.12 0 0 1.17.71 1.64-.47.24-.7 2.36-6.58 2.59-7.29a1.13 1.13 0 0 0-.7-1.41c-12.33-7.63-40.7-8.51-40.7 12.7 0 12.46 11.49 15.44 17.88 17.17 4.72 1.58 13.17 3 13.17 8.7 0 4-3.53 7.06-9.17 7.06a31.76 31.76 0 0 1-19-6.35c-.47-.23-1.42-.71-1.65.71l-2.4 7.47c-.47.94.23 1.18.23 1.41 1.75 1.4 10.3 6.59 22.82 6.59 13.17 0 21.4-7.06 21.4-18.11zm32-42.58c-10.13 0-18.66 3.17-21.4 5.18a1 1 0 0 0-.24 1.41l2.59 7.06a1 1 0 0 0 1.18.7c.65 0 6.8-4 16.93-4 4 0 7.06.71 9.18 2.36 3.6 2.8 3.06 8.29 3.06 10.58-4.79-.3-19.11-3.44-29.41 3.76a16.92 16.92 0 0 0-7.34 14.54c0 5.9 1.51 10.4 6.59 14.35 12.24 8.16 36.28 2 38.1 1.41 1.58-.32 3.53-.66 3.53-1.88v-33.88c.04-4.61.32-21.64-22.78-21.64zM199 200.24a1.11 1.11 0 0 0-1.18-1.18H188a1.11 1.11 0 0 0-1.17 1.18v79a1.11 1.11 0 0 0 1.17 1.18h9.88a1.11 1.11 0 0 0 1.18-1.18zm55.75 28.93c-2.1-2.31-6.79-7.53-17.65-7.53-3.51 0-14.16.23-20.7 8.94-6.35 7.63-6.58 18.11-6.58 21.41 0 3.12.15 14.26 7.06 21.17 2.64 2.91 9.06 8.23 22.81 8.23 10.82 0 16.47-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.35-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.94-16.7h37.17a1.23 1.23 0 0 0 1.17-.94c-.29 0 2.07-14.7-6.09-24.23zm36.69 52.69c13.17 0 21.41-7.06 21.41-18.11 0-11.76-11.7-15.17-17.88-17.17-4.14-1.66-13.41-3.38-13.41-8.94 0-3.76 3.29-6.35 8.47-6.35a38.11 38.11 0 0 1 16.7 4.23s1.18.71 1.65-.47c.23-.7 2.35-6.58 2.58-7.29a1.13 1.13 0 0 0-.7-1.41c-7.91-4.9-16.74-4.94-20.23-4.94-12 0-20.46 7.29-20.46 17.64 0 12.46 11.48 15.44 17.87 17.17 6.11 2 13.17 3.26 13.17 8.7 0 4-3.52 7.06-9.17 7.06a31.8 31.8 0 0 1-19-6.35 1 1 0 0 0-1.65.71l-2.35 7.52c-.47.94.23 1.18.23 1.41 1.72 1.4 10.33 6.59 22.79 6.59zM357.09 224c0-.71-.24-1.18-1.18-1.18h-11.76c0-.14.94-8.94 4.47-12.47 4.16-4.15 11.76-1.64 12-1.64 1.17.47 1.41 0 1.64-.47l2.83-7.77c.7-.94 0-1.17-.24-1.41-5.09-2-17.35-2.87-24.46 4.24-5.48 5.48-7 13.92-8 19.52h-8.47a1.28 1.28 0 0 0-1.17 1.18l-1.42 7.76c0 .7.24 1.17 1.18 1.17h8.23c-8.51 47.9-8.75 50.21-10.35 55.52-1.08 3.62-3.29 6.9-5.88 7.76-.09 0-3.88 1.68-9.64-.24 0 0-.94-.47-1.41.71-.24.71-2.59 6.82-2.83 7.53s0 1.41.47 1.41c5.11 2 13 1.77 17.88 0 6.28-2.28 9.72-7.89 11.53-12.94 2.75-7.71 2.81-9.79 11.76-59.74h12.23a1.29 1.29 0 0 0 1.18-1.18zm53.39 16c-.56-1.68-5.1-18.11-25.17-18.11-15.25 0-23 10-25.16 18.11-1 3-3.18 14 0 23.52.09.3 4.41 18.12 25.16 18.12 14.95 0 22.9-9.61 25.17-18.12 3.21-9.61 1.01-20.52 0-23.52zm45.4-16.7c-5-1.65-16.62-1.9-22.11 5.41v-4.47a1.11 1.11 0 0 0-1.18-1.17h-9.4a1.11 1.11 0 0 0-1.18 1.17v55.28a1.12 1.12 0 0 0 1.18 1.18h9.64a1.12 1.12 0 0 0 1.18-1.18v-27.77c0-2.91.05-11.37 4.46-15.05 4.9-4.9 12-3.36 13.41-3.06a1.57 1.57 0 0 0 1.41-.94 74 74 0 0 0 3.06-8 1.16 1.16 0 0 0-.47-1.41zm46.81 54.1l-2.12-7.29c-.47-1.18-1.41-.71-1.41-.71-4.23 1.82-10.15 1.89-11.29 1.89-4.64 0-17.17-1.13-17.17-19.76 0-6.23 1.85-19.76 16.47-19.76a34.85 34.85 0 0 1 11.52 1.65s.94.47 1.18-.71c.94-2.59 1.64-4.47 2.59-7.53.23-.94-.47-1.17-.71-1.17-11.59-3.87-22.34-2.53-27.76 0-1.59.74-16.23 6.49-16.23 27.52 0 2.9-.58 30.11 28.94 30.11a44.45 44.45 0 0 0 15.52-2.83 1.3 1.3 0 0 0 .47-1.42zm53.87-39.52c-.8-3-5.37-16.23-22.35-16.23-16 0-23.52 10.11-25.64 18.59a38.58 38.58 0 0 0-1.65 11.76c0 25.87 18.84 29.4 29.88 29.4 10.82 0 16.46-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.36-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.93-16.7h37.16a1.25 1.25 0 0 0 1.18-.94c-.24-.01.94-7.07-1.41-15.54zm-23.29-6.35c-10.33 0-13 9-13.64 14.12H546c-.88-11.92-7.62-14.13-12.73-14.13z\"],\n    \"sass\": [640, 512, [], \"f41e\", \"M301.84 378.92c-.3.6-.6 1.08 0 0zm249.13-87a131.16 131.16 0 0 0-58 13.5c-5.9-11.9-12-22.3-13-30.1-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.3-6.7-24 2.5-25.29 5.9a122.83 122.83 0 0 0-5.3 19.1c-2.3 11.7-25.79 53.5-39.09 75.3-4.4-8.5-8.1-16-8.9-22-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.29-6.7-24 2.5-25.3 5.9-2.7 11.4-5.3 19.1-33.89 77.3-42.08 95.4c-4.2 9.2-7.8 16.6-10.4 21.6-.4.8-.7 1.3-.9 1.7.3-.5.5-1 .5-.8-2.2 4.3-3.5 6.7-3.5 6.7v.1c-1.7 3.2-3.6 6.1-4.5 6.1-.6 0-1.9-8.4.3-19.9 4.7-24.2 15.8-61.8 15.7-63.1-.1-.7 2.1-7.2-7.3-10.7-9.1-3.3-12.4 2.2-13.2 2.2s-1.4 2-1.4 2 10.1-42.4-19.39-42.4c-18.4 0-44 20.2-56.58 38.5-7.9 4.3-25 13.6-43 23.5-6.9 3.8-14 7.7-20.7 11.4-.5-.5-.9-1-1.4-1.5-35.79-38.2-101.87-65.2-99.07-116.5 1-18.7 7.5-67.8 127.07-127.4 98-48.8 176.35-35.4 189.84-5.6 19.4 42.5-41.89 121.6-143.66 133-38.79 4.3-59.18-10.7-64.28-16.3-5.3-5.9-6.1-6.2-8.1-5.1-3.3 1.8-1.2 7 0 10.1 3 7.9 15.5 21.9 36.79 28.9 18.7 6.1 64.18 9.5 119.17-11.8 61.78-23.8 109.87-90.1 95.77-145.6C386.52 18.32 293-.18 204.57 31.22c-52.69 18.7-109.67 48.1-150.66 86.4-48.69 45.6-56.48 85.3-53.28 101.9 11.39 58.9 92.57 97.3 125.06 125.7-1.6.9-3.1 1.7-4.5 2.5-16.29 8.1-78.18 40.5-93.67 74.7-17.5 38.8 2.9 66.6 16.29 70.4 41.79 11.6 84.58-9.3 107.57-43.6s20.2-79.1 9.6-99.5c-.1-.3-.3-.5-.4-.8 4.2-2.5 8.5-5 12.8-7.5 8.29-4.9 16.39-9.4 23.49-13.3-4 10.8-6.9 23.8-8.4 42.6-1.8 22 7.3 50.5 19.1 61.7 5.2 4.9 11.49 5 15.39 5 13.8 0 20-11.4 26.89-25 8.5-16.6 16-35.9 16-35.9s-9.4 52.2 16.3 52.2c9.39 0 18.79-12.1 23-18.3v.1s.2-.4.7-1.2c1-1.5 1.5-2.4 1.5-2.4v-.3c3.8-6.5 12.1-21.4 24.59-46 16.2-31.8 31.69-71.5 31.69-71.5a201.24 201.24 0 0 0 6.2 25.8c2.8 9.5 8.7 19.9 13.4 30-3.8 5.2-6.1 8.2-6.1 8.2a.31.31 0 0 0 .1.2c-3 4-6.4 8.3-9.9 12.5-12.79 15.2-28 32.6-30 37.6-2.4 5.9-1.8 10.3 2.8 13.7 3.4 2.6 9.4 3 15.69 2.5 11.5-.8 19.6-3.6 23.5-5.4a82.2 82.2 0 0 0 20.19-10.6c12.5-9.2 20.1-22.4 19.4-39.8-.4-9.6-3.5-19.2-7.3-28.2 1.1-1.6 2.3-3.3 3.4-5C434.8 301.72 450.1 270 450.1 270a201.24 201.24 0 0 0 6.2 25.8c2.4 8.1 7.09 17 11.39 25.7-18.59 15.1-30.09 32.6-34.09 44.1-7.4 21.3-1.6 30.9 9.3 33.1 4.9 1 11.9-1.3 17.1-3.5a79.46 79.46 0 0 0 21.59-11.1c12.5-9.2 24.59-22.1 23.79-39.6-.3-7.9-2.5-15.8-5.4-23.4 15.7-6.6 36.09-10.2 62.09-7.2 55.68 6.5 66.58 41.3 64.48 55.8s-13.8 22.6-17.7 25-5.1 3.3-4.8 5.1c.5 2.6 2.3 2.5 5.6 1.9 4.6-.8 29.19-11.8 30.29-38.7 1.6-34-31.09-71.4-89-71.1zm-429.18 144.7c-18.39 20.1-44.19 27.7-55.28 21.3C54.61 451 59.31 421.42 82 400c13.8-13 31.59-25 43.39-32.4 2.7-1.6 6.6-4 11.4-6.9.8-.5 1.2-.7 1.2-.7.9-.6 1.9-1.1 2.9-1.7 8.29 30.4.3 57.2-19.1 78.3zm134.36-91.4c-6.4 15.7-19.89 55.7-28.09 53.6-7-1.8-11.3-32.3-1.4-62.3 5-15.1 15.6-33.1 21.9-40.1 10.09-11.3 21.19-14.9 23.79-10.4 3.5 5.9-12.2 49.4-16.2 59.2zm111 53c-2.7 1.4-5.2 2.3-6.4 1.6-.9-.5 1.1-2.4 1.1-2.4s13.9-14.9 19.4-21.7c3.2-4 6.9-8.7 10.89-13.9 0 .5.1 1 .1 1.6-.13 17.9-17.32 30-25.12 34.8zm85.58-19.5c-2-1.4-1.7-6.1 5-20.7 2.6-5.7 8.59-15.3 19-24.5a36.18 36.18 0 0 1 1.9 10.8c-.1 22.5-16.2 30.9-25.89 34.4z\"],\n    \"schlix\": [448, 512, [], \"f3ea\", \"M350.5 157.7l-54.2-46.1 73.4-39 78.3 44.2-97.5 40.9zM192 122.1l45.7-28.2 34.7 34.6-55.4 29-25-35.4zm-65.1 6.6l31.9-22.1L176 135l-36.7 22.5-12.4-28.8zm-23.3 88.2l-8.8-34.8 29.6-18.3 13.1 35.3-33.9 17.8zm-21.2-83.7l23.9-18.1 8.9 24-26.7 18.3-6.1-24.2zM59 206.5l-3.6-28.4 22.3-15.5 6.1 28.7L59 206.5zm-30.6 16.6l20.8-12.8 3.3 33.4-22.9 12-1.2-32.6zM1.4 268l19.2-10.2.4 38.2-21 8.8L1.4 268zm59.1 59.3l-28.3 8.3-1.6-46.8 25.1-10.7 4.8 49.2zM99 263.2l-31.1 13-5.2-40.8L90.1 221l8.9 42.2zM123.2 377l-41.6 5.9-8.1-63.5 35.2-10.8 14.5 68.4zm28.5-139.9l21.2 57.1-46.2 13.6-13.7-54.1 38.7-16.6zm85.7 230.5l-70.9-3.3-24.3-95.8 55.2-8.6 40 107.7zm-84.9-279.7l42.2-22.4 28 45.9-50.8 21.3-19.4-44.8zm41 94.9l61.3-18.7 52.8 86.6-79.8 11.3-34.3-79.2zm51.4-85.6l67.3-28.8 65.5 65.4-88.6 26.2-44.2-62.8z\"],\n    \"scribd\": [384, 512, [], \"f28a\", \"M42.3 252.7c-16.1-19-24.7-45.9-24.8-79.9 0-100.4 75.2-153.1 167.2-153.1 98.6-1.6 156.8 49 184.3 70.6l-50.5 72.1-37.3-24.6 26.9-38.6c-36.5-24-79.4-36.5-123-35.8-50.7-.8-111.7 27.2-111.7 76.2 0 18.7 11.2 20.7 28.6 15.6 23.3-5.3 41.9.6 55.8 14 26.4 24.3 23.2 67.6-.7 91.9-29.2 29.5-85.2 27.3-114.8-8.4zm317.7 5.9c-15.5-18.8-38.9-29.4-63.2-28.6-38.1-2-71.1 28-70.5 67.2-.7 16.8 6 33 18.4 44.3 14.1 13.9 33 19.7 56.3 14.4 17.4-5.1 28.6-3.1 28.6 15.6 0 4.3-.5 8.5-1.4 12.7-16.7 40.9-59.5 64.4-121.4 64.4-51.9.2-102.4-16.4-144.1-47.3l33.7-39.4-35.6-27.4L0 406.3l15.4 13.8c52.5 46.8 120.4 72.5 190.7 72.2 51.4 0 94.4-10.5 133.6-44.1 57.1-51.4 54.2-149.2 20.3-189.6z\"],\n    \"searchengin\": [460, 512, [], \"f3eb\", \"M220.6 130.3l-67.2 28.2V43.2L98.7 233.5l54.7-24.2v130.3l67.2-209.3zm-83.2-96.7l-1.3 4.7-15.2 52.9C80.6 106.7 52 145.8 52 191.5c0 52.3 34.3 95.9 83.4 105.5v53.6C57.5 340.1 0 272.4 0 191.6c0-80.5 59.8-147.2 137.4-158zm311.4 447.2c-11.2 11.2-23.1 12.3-28.6 10.5-5.4-1.8-27.1-19.9-60.4-44.4-33.3-24.6-33.6-35.7-43-56.7-9.4-20.9-30.4-42.6-57.5-52.4l-9.7-14.7c-24.7 16.9-53 26.9-81.3 28.7l2.1-6.6 15.9-49.5c46.5-11.9 80.9-54 80.9-104.2 0-54.5-38.4-102.1-96-107.1V32.3C254.4 37.4 320 106.8 320 191.6c0 33.6-11.2 64.7-29 90.4l14.6 9.6c9.8 27.1 31.5 48 52.4 57.4s32.2 9.7 56.8 43c24.6 33.2 42.7 54.9 44.5 60.3s.7 17.3-10.5 28.5zm-9.9-17.9c0-4.4-3.6-8-8-8s-8 3.6-8 8 3.6 8 8 8 8-3.6 8-8z\"],\n    \"sellcast\": [448, 512, [], \"f2da\", \"M353.4 32H94.7C42.6 32 0 74.6 0 126.6v258.7C0 437.4 42.6 480 94.7 480h258.7c52.1 0 94.7-42.6 94.7-94.6V126.6c0-52-42.6-94.6-94.7-94.6zm-50 316.4c-27.9 48.2-89.9 64.9-138.2 37.2-22.9 39.8-54.9 8.6-42.3-13.2l15.7-27.2c5.9-10.3 19.2-13.9 29.5-7.9 18.6 10.8-.1-.1 18.5 10.7 27.6 15.9 63.4 6.3 79.4-21.3 15.9-27.6 6.3-63.4-21.3-79.4-17.8-10.2-.6-.4-18.6-10.6-24.6-14.2-3.4-51.9 21.6-37.5 18.6 10.8-.1-.1 18.5 10.7 48.4 28 65.1 90.3 37.2 138.5zm21.8-208.8c-17 29.5-16.3 28.8-19 31.5-6.5 6.5-16.3 8.7-26.5 3.6-18.6-10.8.1.1-18.5-10.7-27.6-15.9-63.4-6.3-79.4 21.3s-6.3 63.4 21.3 79.4c0 0 18.5 10.6 18.6 10.6 24.6 14.2 3.4 51.9-21.6 37.5-18.6-10.8.1.1-18.5-10.7-48.2-27.8-64.9-90.1-37.1-138.4 27.9-48.2 89.9-64.9 138.2-37.2l4.8-8.4c14.3-24.9 52-3.3 37.7 21.5z\"],\n    \"sellsy\": [640, 512, [], \"f213\", \"M539.71 237.308c3.064-12.257 4.29-24.821 4.29-37.384C544 107.382 468.618 32 376.076 32c-77.22 0-144.634 53.012-163.02 127.781-15.322-13.176-34.934-20.53-55.157-20.53-46.271 0-83.962 37.69-83.962 83.961 0 7.354.92 15.015 3.065 22.369-42.9 20.225-70.785 63.738-70.785 111.234C6.216 424.843 61.68 480 129.401 480h381.198c67.72 0 123.184-55.157 123.184-123.184.001-56.384-38.916-106.025-94.073-119.508zM199.88 401.554c0 8.274-7.048 15.321-15.321 15.321H153.61c-8.274 0-15.321-7.048-15.321-15.321V290.626c0-8.273 7.048-15.321 15.321-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v110.928zm89.477 0c0 8.274-7.048 15.321-15.322 15.321h-30.949c-8.274 0-15.321-7.048-15.321-15.321V270.096c0-8.274 7.048-15.321 15.321-15.321h30.949c8.274 0 15.322 7.048 15.322 15.321v131.458zm89.477 0c0 8.274-7.047 15.321-15.321 15.321h-30.949c-8.274 0-15.322-7.048-15.322-15.321V238.84c0-8.274 7.048-15.321 15.322-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v162.714zm87.027 0c0 8.274-7.048 15.321-15.322 15.321h-28.497c-8.274 0-15.321-7.048-15.321-15.321V176.941c0-8.579 7.047-15.628 15.321-15.628h28.497c8.274 0 15.322 7.048 15.322 15.628v224.613z\"],\n    \"servicestack\": [496, 512, [], \"f3ec\", \"M88 216c81.7 10.2 273.7 102.3 304 232H0c99.5-8.1 184.5-137 88-232zm32-152c32.3 35.6 47.7 83.9 46.4 133.6C249.3 231.3 373.7 321.3 400 448h96C455.3 231.9 222.8 79.5 120 64z\"],\n    \"shirtsinbulk\": [448, 512, [], \"f214\", \"M100 410.3l30.6 13.4 4.4-9.9-30.6-13.4zm39.4 17.5l30.6 13.4 4.4-9.9-30.6-13.4zm172.1-14l4.4 9.9 30.6-13.4-4.4-9.9zM179.1 445l30.3 13.7 4.4-9.9-30.3-13.4zM60.4 392.8L91 406.2l4.4-9.6-30.6-13.7zm211.4 38.5l4.4 9.9 30.6-13.4-4.4-9.9zm-39.3 17.5l4.4 9.9 30.6-13.7-4.4-9.6zm118.4-52.2l4.4 9.6 30.6-13.4-4.4-9.9zM170 46.6h-33.5v10.5H170zm-47.2 0H89.2v10.5h33.5zm-47.3 0H42.3v10.5h33.3zm141.5 0h-33.2v10.5H217zm94.5 0H278v10.5h33.5zm47.3 0h-33.5v10.5h33.5zm-94.6 0H231v10.5h33.2zm141.5 0h-33.3v10.5h33.3zM52.8 351.1H42v33.5h10.8zm70-215.9H89.2v10.5h33.5zm-70 10.6h22.8v-10.5H42v33.5h10.8zm168.9 228.6c50.5 0 91.3-40.8 91.3-91.3 0-50.2-40.8-91.3-91.3-91.3-50.2 0-91.3 41.1-91.3 91.3 0 50.5 41.1 91.3 91.3 91.3zm-48.2-111.1c0-25.4 29.5-31.8 49.6-31.8 16.9 0 29.2 5.8 44.3 12l-8.8 16.9h-.9c-6.4-9.9-24.8-13.1-35.6-13.1-9 0-29.8 1.8-29.8 14.9 0 21.6 78.5-10.2 78.5 37.9 0 25.4-31.5 31.2-51 31.2-18.1 0-32.4-2.9-47.2-12.2l9-18.4h.9c6.1 12.2 23.6 14.9 35.9 14.9 8.7 0 32.7-1.2 32.7-14.3 0-26.1-77.6 6.3-77.6-38zM52.8 178.4H42V212h10.8zm342.4 206.2H406v-33.5h-10.8zM52.8 307.9H42v33.5h10.8zM0 3.7v406l221.7 98.6L448 409.7V3.7zm418.8 387.1L222 476.5 29.2 390.8V120.7h389.7v270.1zm0-299.3H29.2V32.9h389.7v58.6zm-366 130.1H42v33.5h10.8zm0 43.2H42v33.5h10.8zM170 135.2h-33.5v10.5H170zm225.2 163.1H406v-33.5h-10.8zm0-43.2H406v-33.5h-10.8zM217 135.2h-33.2v10.5H217zM395.2 212H406v-33.5h-10.8zm0 129.5H406V308h-10.8zm-131-206.3H231v10.5h33.2zm47.3 0H278v10.5h33.5zm83.7 33.6H406v-33.5h-33.5v10.5h22.8zm-36.4-33.6h-33.5v10.5h33.5z\"],\n    \"shopware\": [512, 512, [], \"f5b5\", \"M403.5 455.41A246.17 246.17 0 0 1 256 504C118.81 504 8 393 8 256 8 118.81 119 8 256 8a247.39 247.39 0 0 1 165.7 63.5 3.57 3.57 0 0 1-2.86 6.18A418.62 418.62 0 0 0 362.13 74c-129.36 0-222.4 53.47-222.4 155.35 0 109 92.13 145.88 176.83 178.73 33.64 13 65.4 25.36 87 41.59a3.58 3.58 0 0 1 0 5.72zM503 233.09a3.64 3.64 0 0 0-1.27-2.44c-51.76-43-93.62-60.48-144.48-60.48-84.13 0-80.25 52.17-80.25 53.63 0 42.6 52.06 62 112.34 84.49 31.07 11.59 63.19 23.57 92.68 39.93a3.57 3.57 0 0 0 5-1.82A249 249 0 0 0 503 233.09z\"],\n    \"simplybuilt\": [512, 512, [], \"f215\", \"M481.2 64h-106c-14.5 0-26.6 11.8-26.6 26.3v39.6H163.3V90.3c0-14.5-12-26.3-26.6-26.3h-106C16.1 64 4.3 75.8 4.3 90.3v331.4c0 14.5 11.8 26.3 26.6 26.3h450.4c14.8 0 26.6-11.8 26.6-26.3V90.3c-.2-14.5-12-26.3-26.7-26.3zM149.8 355.8c-36.6 0-66.4-29.7-66.4-66.4 0-36.9 29.7-66.6 66.4-66.6 36.9 0 66.6 29.7 66.6 66.6 0 36.7-29.7 66.4-66.6 66.4zm212.4 0c-36.9 0-66.6-29.7-66.6-66.6 0-36.6 29.7-66.4 66.6-66.4 36.6 0 66.4 29.7 66.4 66.4 0 36.9-29.8 66.6-66.4 66.6z\"],\n    \"sistrix\": [448, 512, [], \"f3ee\", \"M448 449L301.2 300.2c20-27.9 31.9-62.2 31.9-99.2 0-93.1-74.7-168.9-166.5-168.9C74.7 32 0 107.8 0 200.9s74.7 168.9 166.5 168.9c39.8 0 76.3-14.2 105-37.9l146 148.1 30.5-31zM166.5 330.8c-70.6 0-128.1-58.3-128.1-129.9S95.9 71 166.5 71s128.1 58.3 128.1 129.9-57.4 129.9-128.1 129.9z\"],\n    \"sith\": [448, 512, [], \"f512\", \"M0 32l69.71 118.75-58.86-11.52 69.84 91.03a146.741 146.741 0 0 0 0 51.45l-69.84 91.03 58.86-11.52L0 480l118.75-69.71-11.52 58.86 91.03-69.84c17.02 3.04 34.47 3.04 51.48 0l91.03 69.84-11.52-58.86L448 480l-69.71-118.78 58.86 11.52-69.84-91.03c3.03-17.01 3.04-34.44 0-51.45l69.84-91.03-58.86 11.52L448 32l-118.75 69.71 11.52-58.9-91.06 69.87c-8.5-1.52-17.1-2.29-25.71-2.29s-17.21.78-25.71 2.29l-91.06-69.87 11.52 58.9L0 32zm224 99.78c31.8 0 63.6 12.12 87.85 36.37 48.5 48.5 48.49 127.21 0 175.7s-127.2 48.46-175.7-.03c-48.5-48.5-48.49-127.21 0-175.7 24.24-24.25 56.05-36.34 87.85-36.34zm0 36.66c-22.42 0-44.83 8.52-61.92 25.61-34.18 34.18-34.19 89.68 0 123.87s89.65 34.18 123.84 0c34.18-34.18 34.19-89.68 0-123.87-17.09-17.09-39.5-25.61-61.92-25.61z\"],\n    \"sketch\": [512, 512, [], \"f7c6\", \"M27.5 162.2L9 187.1h90.5l6.9-130.7-78.9 105.8zM396.3 45.7L267.7 32l135.7 147.2-7.1-133.5zM112.2 218.3l-11.2-22H9.9L234.8 458zm2-31.2h284l-81.5-88.5L256.3 33zm297.3 9.1L277.6 458l224.8-261.7h-90.9zM415.4 69L406 56.4l.9 17.3 6.1 113.4h90.3zM113.5 93.5l-4.6 85.6L244.7 32 116.1 45.7zm287.7 102.7h-290l42.4 82.9L256.3 480l144.9-283.8z\"],\n    \"skyatlas\": [640, 512, [], \"f216\", \"M640 329.3c0 65.9-52.5 114.4-117.5 114.4-165.9 0-196.6-249.7-359.7-249.7-146.9 0-147.1 212.2 5.6 212.2 42.5 0 90.9-17.8 125.3-42.5 5.6-4.1 16.9-16.3 22.8-16.3s10.9 5 10.9 10.9c0 7.8-13.1 19.1-18.7 24.1-40.9 35.6-100.3 61.2-154.7 61.2-83.4.1-154-59-154-144.9s67.5-149.1 152.8-149.1c185.3 0 222.5 245.9 361.9 245.9 99.9 0 94.8-139.7 3.4-139.7-17.5 0-35 11.6-46.9 11.6-8.4 0-15.9-7.2-15.9-15.6 0-11.6 5.3-23.7 5.3-36.3 0-66.6-50.9-114.7-116.9-114.7-53.1 0-80 36.9-88.8 36.9-6.2 0-11.2-5-11.2-11.2 0-5.6 4.1-10.3 7.8-14.4 25.3-28.8 64.7-43.7 102.8-43.7 79.4 0 139.1 58.4 139.1 137.8 0 6.9-.3 13.7-1.2 20.6 11.9-3.1 24.1-4.7 35.9-4.7 60.7 0 111.9 45.3 111.9 107.2z\"],\n    \"skype\": [448, 512, [], \"f17e\", \"M424.7 299.8c2.9-14 4.7-28.9 4.7-43.8 0-113.5-91.9-205.3-205.3-205.3-14.9 0-29.7 1.7-43.8 4.7C161.3 40.7 137.7 32 112 32 50.2 32 0 82.2 0 144c0 25.7 8.7 49.3 23.3 68.2-2.9 14-4.7 28.9-4.7 43.8 0 113.5 91.9 205.3 205.3 205.3 14.9 0 29.7-1.7 43.8-4.7 19 14.6 42.6 23.3 68.2 23.3 61.8 0 112-50.2 112-112 .1-25.6-8.6-49.2-23.2-68.1zm-194.6 91.5c-65.6 0-120.5-29.2-120.5-65 0-16 9-30.6 29.5-30.6 31.2 0 34.1 44.9 88.1 44.9 25.7 0 42.3-11.4 42.3-26.3 0-18.7-16-21.6-42-28-62.5-15.4-117.8-22-117.8-87.2 0-59.2 58.6-81.1 109.1-81.1 55.1 0 110.8 21.9 110.8 55.4 0 16.9-11.4 31.8-30.3 31.8-28.3 0-29.2-33.5-75-33.5-25.7 0-42 7-42 22.5 0 19.8 20.8 21.8 69.1 33 41.4 9.3 90.7 26.8 90.7 77.6 0 59.1-57.1 86.5-112 86.5z\"],\n    \"slack\": [448, 512, [], \"f198\", \"M94.12 315.1c0 25.9-21.16 47.06-47.06 47.06S0 341 0 315.1c0-25.9 21.16-47.06 47.06-47.06h47.06v47.06zm23.72 0c0-25.9 21.16-47.06 47.06-47.06s47.06 21.16 47.06 47.06v117.84c0 25.9-21.16 47.06-47.06 47.06s-47.06-21.16-47.06-47.06V315.1zm47.06-188.98c-25.9 0-47.06-21.16-47.06-47.06S139 32 164.9 32s47.06 21.16 47.06 47.06v47.06H164.9zm0 23.72c25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06H47.06C21.16 243.96 0 222.8 0 196.9s21.16-47.06 47.06-47.06H164.9zm188.98 47.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06h-47.06V196.9zm-23.72 0c0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06V79.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06V196.9zM283.1 385.88c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06v-47.06h47.06zm0-23.72c-25.9 0-47.06-21.16-47.06-47.06 0-25.9 21.16-47.06 47.06-47.06h117.84c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06H283.1z\"],\n    \"slack-hash\": [448, 512, [], \"f3ef\", \"M446.2 270.4c-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-30.3-90 45.4-15.1c19.1-6.2 29.1-26.8 23-45.9-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-93.4 31.2-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-45.3 15c-19.1 6.2-29.1 26.8-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l30.3 90L78 354.8c-19 6.2-29.1 26.9-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 93.6-31.3 15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 45.4-15.1c19-6 29.1-26.7 22.9-45.7zm-254.1 47.2l-30.3-90.2 93.5-31.3 30.3 90.2-93.5 31.3z\"],\n    \"slideshare\": [512, 512, [], \"f1e7\", \"M187.7 153.7c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7s61.7-26 61.7-57.7c0-32-27.7-57.7-61.7-57.7zm143.4 0c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7 34.3 0 61.7-26 61.7-57.7.1-32-27.4-57.7-61.7-57.7zm156.6 90l-6 4.3V49.7c0-27.4-20.6-49.7-46-49.7H76.6c-25.4 0-46 22.3-46 49.7V248c-2-1.4-4.3-2.9-6.3-4.3-15.1-10.6-25.1 4-16 17.7 18.3 22.6 53.1 50.3 106.3 72C58.3 525.1 252 555.7 248.9 457.5c0-.7.3-56.6.3-96.6 5.1 1.1 9.4 2.3 13.7 3.1 0 39.7.3 92.8.3 93.5-3.1 98.3 190.6 67.7 134.3-124 53.1-21.7 88-49.4 106.3-72 9.1-13.8-.9-28.3-16.1-17.8zm-30.5 19.2c-68.9 37.4-128.3 31.1-160.6 29.7-23.7-.9-32.6 9.1-33.7 24.9-10.3-7.7-18.6-15.5-20.3-17.1-5.1-5.4-13.7-8-27.1-7.7-31.7 1.1-89.7 7.4-157.4-28V72.3c0-34.9 8.9-45.7 40.6-45.7h317.7c30.3 0 40.9 12.9 40.9 45.7v190.6z\"],\n    \"snapchat\": [496, 512, [], \"f2ab\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm169.5 338.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C183.1 100 230.7 96 244.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"snapchat-ghost\": [512, 512, [], \"f2ac\", \"M510.846 392.673c-5.211 12.157-27.239 21.089-67.36 27.318-2.064 2.786-3.775 14.686-6.507 23.956-1.625 5.566-5.623 8.869-12.128 8.869l-.297-.005c-9.395 0-19.203-4.323-38.852-4.323-26.521 0-35.662 6.043-56.254 20.588-21.832 15.438-42.771 28.764-74.027 27.399-31.646 2.334-58.025-16.908-72.871-27.404-20.714-14.643-29.828-20.582-56.241-20.582-18.864 0-30.736 4.72-38.852 4.72-8.073 0-11.213-4.922-12.422-9.04-2.703-9.189-4.404-21.263-6.523-24.13-20.679-3.209-67.31-11.344-68.498-32.15a10.627 10.627 0 0 1 8.877-11.069c69.583-11.455 100.924-82.901 102.227-85.934.074-.176.155-.344.237-.515 3.713-7.537 4.544-13.849 2.463-18.753-5.05-11.896-26.872-16.164-36.053-19.796-23.715-9.366-27.015-20.128-25.612-27.504 2.437-12.836 21.725-20.735 33.002-15.453 8.919 4.181 16.843 6.297 23.547 6.297 5.022 0 8.212-1.204 9.96-2.171-2.043-35.936-7.101-87.29 5.687-115.969C158.122 21.304 229.705 15.42 250.826 15.42c.944 0 9.141-.089 10.11-.089 52.148 0 102.254 26.78 126.723 81.643 12.777 28.65 7.749 79.792 5.695 116.009 1.582.872 4.357 1.942 8.599 2.139 6.397-.286 13.815-2.389 22.069-6.257 6.085-2.846 14.406-2.461 20.48.058l.029.01c9.476 3.385 15.439 10.215 15.589 17.87.184 9.747-8.522 18.165-25.878 25.018-2.118.835-4.694 1.655-7.434 2.525-9.797 3.106-24.6 7.805-28.616 17.271-2.079 4.904-1.256 11.211 2.46 18.748.087.168.166.342.239.515 1.301 3.03 32.615 74.46 102.23 85.934 6.427 1.058 11.163 7.877 7.725 15.859z\"],\n    \"snapchat-square\": [448, 512, [], \"f2ad\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6.5 314.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C159.1 100 206.7 96 220.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"soundcloud\": [640, 512, [], \"f1be\", \"M111.4 256.3l5.8 65-5.8 68.3c-.3 2.5-2.2 4.4-4.4 4.4s-4.2-1.9-4.2-4.4l-5.6-68.3 5.6-65c0-2.2 1.9-4.2 4.2-4.2 2.2 0 4.1 2 4.4 4.2zm21.4-45.6c-2.8 0-4.7 2.2-5 5l-5 105.6 5 68.3c.3 2.8 2.2 5 5 5 2.5 0 4.7-2.2 4.7-5l5.8-68.3-5.8-105.6c0-2.8-2.2-5-4.7-5zm25.5-24.1c-3.1 0-5.3 2.2-5.6 5.3l-4.4 130 4.4 67.8c.3 3.1 2.5 5.3 5.6 5.3 2.8 0 5.3-2.2 5.3-5.3l5.3-67.8-5.3-130c0-3.1-2.5-5.3-5.3-5.3zM7.2 283.2c-1.4 0-2.2 1.1-2.5 2.5L0 321.3l4.7 35c.3 1.4 1.1 2.5 2.5 2.5s2.2-1.1 2.5-2.5l5.6-35-5.6-35.6c-.3-1.4-1.1-2.5-2.5-2.5zm23.6-21.9c-1.4 0-2.5 1.1-2.5 2.5l-6.4 57.5 6.4 56.1c0 1.7 1.1 2.8 2.5 2.8s2.5-1.1 2.8-2.5l7.2-56.4-7.2-57.5c-.3-1.4-1.4-2.5-2.8-2.5zm25.3-11.4c-1.7 0-3.1 1.4-3.3 3.3L47 321.3l5.8 65.8c.3 1.7 1.7 3.1 3.3 3.1 1.7 0 3.1-1.4 3.1-3.1l6.9-65.8-6.9-68.1c0-1.9-1.4-3.3-3.1-3.3zm25.3-2.2c-1.9 0-3.6 1.4-3.6 3.6l-5.8 70 5.8 67.8c0 2.2 1.7 3.6 3.6 3.6s3.6-1.4 3.9-3.6l6.4-67.8-6.4-70c-.3-2.2-2-3.6-3.9-3.6zm241.4-110.9c-1.1-.8-2.8-1.4-4.2-1.4-2.2 0-4.2.8-5.6 1.9-1.9 1.7-3.1 4.2-3.3 6.7v.8l-3.3 176.7 1.7 32.5 1.7 31.7c.3 4.7 4.2 8.6 8.9 8.6s8.6-3.9 8.6-8.6l3.9-64.2-3.9-177.5c-.4-3-2-5.8-4.5-7.2zm-26.7 15.3c-1.4-.8-2.8-1.4-4.4-1.4s-3.1.6-4.4 1.4c-2.2 1.4-3.6 3.9-3.6 6.7l-.3 1.7-2.8 160.8s0 .3 3.1 65.6v.3c0 1.7.6 3.3 1.7 4.7 1.7 1.9 3.9 3.1 6.4 3.1 2.2 0 4.2-1.1 5.6-2.5 1.7-1.4 2.5-3.3 2.5-5.6l.3-6.7 3.1-58.6-3.3-162.8c-.3-2.8-1.7-5.3-3.9-6.7zm-111.4 22.5c-3.1 0-5.8 2.8-5.8 6.1l-4.4 140.6 4.4 67.2c.3 3.3 2.8 5.8 5.8 5.8 3.3 0 5.8-2.5 6.1-5.8l5-67.2-5-140.6c-.2-3.3-2.7-6.1-6.1-6.1zm376.7 62.8c-10.8 0-21.1 2.2-30.6 6.1-6.4-70.8-65.8-126.4-138.3-126.4-17.8 0-35 3.3-50.3 9.4-6.1 2.2-7.8 4.4-7.8 9.2v249.7c0 5 3.9 8.6 8.6 9.2h218.3c43.3 0 78.6-35 78.6-78.3.1-43.6-35.2-78.9-78.5-78.9zm-296.7-60.3c-4.2 0-7.5 3.3-7.8 7.8l-3.3 136.7 3.3 65.6c.3 4.2 3.6 7.5 7.8 7.5 4.2 0 7.5-3.3 7.5-7.5l3.9-65.6-3.9-136.7c-.3-4.5-3.3-7.8-7.5-7.8zm-53.6-7.8c-3.3 0-6.4 3.1-6.4 6.7l-3.9 145.3 3.9 66.9c.3 3.6 3.1 6.4 6.4 6.4 3.6 0 6.4-2.8 6.7-6.4l4.4-66.9-4.4-145.3c-.3-3.6-3.1-6.7-6.7-6.7zm26.7 3.4c-3.9 0-6.9 3.1-6.9 6.9L227 321.3l3.9 66.4c.3 3.9 3.1 6.9 6.9 6.9s6.9-3.1 6.9-6.9l4.2-66.4-4.2-141.7c0-3.9-3-6.9-6.9-6.9z\"],\n    \"sourcetree\": [448, 512, [], \"f7d3\", \"M427.2 203c0-112.1-90.9-203-203-203C112.1-.2 21.2 90.6 21 202.6A202.86 202.86 0 0 0 161.5 396v101.7a14.3 14.3 0 0 0 14.3 14.3h96.4a14.3 14.3 0 0 0 14.3-14.3V396.1A203.18 203.18 0 0 0 427.2 203zm-271.6 0c0-90.8 137.3-90.8 137.3 0-.1 89.9-137.3 91-137.3 0z\"],\n    \"speakap\": [448, 512, [], \"f3f3\", \"M64 391.78C-15.41 303.59-8 167.42 80.64 87.64s224.8-73 304.21 15.24 72 224.36-16.64 304.14c-18.74 16.87 64 43.09 42 52.26-82.06 34.21-253.91 35-346.23-67.5zm213.31-211.6l38.5-40.86c-9.61-8.89-32-26.83-76.17-27.6-52.33-.91-95.86 28.3-96.77 80-.2 11.33.29 36.72 29.42 54.83 34.46 21.42 86.52 21.51 86 52.26-.37 21.28-26.42 25.81-38.59 25.6-3-.05-30.23-.46-47.61-24.62l-40 42.61c28.16 27 59 32.62 83.49 33.05 10.23.18 96.42.33 97.84-81 .28-15.81-2.07-39.72-28.86-56.59-34.36-21.64-85-19.45-84.43-49.75.41-23.25 31-25.37 37.53-25.26.43 0 26.62.26 39.62 17.37z\"],\n    \"speaker-deck\": [512, 512, [], \"f83c\", \"M213.86 296H100a100 100 0 0 1 0-200h132.84a40 40 0 0 1 0 80H98c-26.47 0-26.45 40 0 40h113.82a100 100 0 0 1 0 200H40a40 40 0 0 1 0-80h173.86c26.48 0 26.46-40 0-40zM298 416a120.21 120.21 0 0 0 51.11-80h64.55a19.83 19.83 0 0 0 19.66-20V196a19.83 19.83 0 0 0-19.66-20H296.42a60.77 60.77 0 0 0 0-80h136.93c43.44 0 78.65 35.82 78.65 80v160c0 44.18-35.21 80-78.65 80z\"],\n    \"spotify\": [496, 512, [], \"f1bc\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm100.7 364.9c-4.2 0-6.8-1.3-10.7-3.6-62.4-37.6-135-39.2-206.7-24.5-3.9 1-9 2.6-11.9 2.6-9.7 0-15.8-7.7-15.8-15.8 0-10.3 6.1-15.2 13.6-16.8 81.9-18.1 165.6-16.5 237 26.2 6.1 3.9 9.7 7.4 9.7 16.5s-7.1 15.4-15.2 15.4zm26.9-65.6c-5.2 0-8.7-2.3-12.3-4.2-62.5-37-155.7-51.9-238.6-29.4-4.8 1.3-7.4 2.6-11.9 2.6-10.7 0-19.4-8.7-19.4-19.4s5.2-17.8 15.5-20.7c27.8-7.8 56.2-13.6 97.8-13.6 64.9 0 127.6 16.1 177 45.5 8.1 4.8 11.3 11 11.3 19.7-.1 10.8-8.5 19.5-19.4 19.5zm31-76.2c-5.2 0-8.4-1.3-12.9-3.9-71.2-42.5-198.5-52.7-280.9-29.7-3.6 1-8.1 2.6-12.9 2.6-13.2 0-23.3-10.3-23.3-23.6 0-13.6 8.4-21.3 17.4-23.9 35.2-10.3 74.6-15.2 117.5-15.2 73 0 149.5 15.2 205.4 47.8 7.8 4.5 12.9 10.7 12.9 22.6 0 13.6-11 23.3-23.2 23.3z\"],\n    \"squarespace\": [512, 512, [], \"f5be\", \"M186.12 343.34c-9.65 9.65-9.65 25.29 0 34.94 9.65 9.65 25.29 9.65 34.94 0L378.24 221.1c19.29-19.29 50.57-19.29 69.86 0s19.29 50.57 0 69.86L293.95 445.1c19.27 19.29 50.53 19.31 69.82.04l.04-.04 119.25-119.24c38.59-38.59 38.59-101.14 0-139.72-38.59-38.59-101.15-38.59-139.72 0l-157.22 157.2zm244.53-104.8c-9.65-9.65-25.29-9.65-34.93 0l-157.2 157.18c-19.27 19.29-50.53 19.31-69.82.05l-.05-.05c-9.64-9.64-25.27-9.65-34.92-.01l-.01.01c-9.65 9.64-9.66 25.28-.02 34.93l.02.02c38.58 38.57 101.14 38.57 139.72 0l157.2-157.2c9.65-9.65 9.65-25.29.01-34.93zm-261.99 87.33l157.18-157.18c9.64-9.65 9.64-25.29 0-34.94-9.64-9.64-25.27-9.64-34.91 0L133.72 290.93c-19.28 19.29-50.56 19.3-69.85.01l-.01-.01c-19.29-19.28-19.31-50.54-.03-69.84l.03-.03L218.03 66.89c-19.28-19.29-50.55-19.3-69.85-.02l-.02.02L28.93 186.14c-38.58 38.59-38.58 101.14 0 139.72 38.6 38.59 101.13 38.59 139.73.01zm-87.33-52.4c9.64 9.64 25.27 9.64 34.91 0l157.21-157.19c19.28-19.29 50.55-19.3 69.84-.02l.02.02c9.65 9.65 25.29 9.65 34.93 0 9.65-9.65 9.65-25.29 0-34.93-38.59-38.59-101.13-38.59-139.72 0L81.33 238.54c-9.65 9.64-9.65 25.28-.01 34.93h.01z\"],\n    \"stack-exchange\": [448, 512, [], \"f18d\", \"M17.7 332.3h412.7v22c0 37.7-29.3 68-65.3 68h-19L259.3 512v-89.7H83c-36 0-65.3-30.3-65.3-68v-22zm0-23.6h412.7v-85H17.7v85zm0-109.4h412.7v-85H17.7v85zM365 0H83C47 0 17.7 30.3 17.7 67.7V90h412.7V67.7C430.3 30.3 401 0 365 0z\"],\n    \"stack-overflow\": [384, 512, [], \"f16c\", \"M290.7 311L95 269.7 86.8 309l195.7 41zm51-87L188.2 95.7l-25.5 30.8 153.5 128.3zm-31.2 39.7L129.2 179l-16.7 36.5L293.7 300zM262 32l-32 24 119.3 160.3 32-24zm20.5 328h-200v39.7h200zm39.7 80H42.7V320h-40v160h359.5V320h-40z\"],\n    \"stackpath\": [448, 512, [], \"f842\", \"M244.6 232.4c0 8.5-4.26 20.49-21.34 20.49h-19.61v-41.47h19.61c17.13 0 21.34 12.36 21.34 20.98zM448 32v448H0V32zM151.3 287.84c0-21.24-12.12-34.54-46.72-44.85-20.57-7.41-26-10.91-26-18.63s7-14.61 20.41-14.61c14.09 0 20.79 8.45 20.79 18.35h30.7l.19-.57c.5-19.57-15.06-41.65-51.12-41.65-23.37 0-52.55 10.75-52.55 38.29 0 19.4 9.25 31.29 50.74 44.37 17.26 6.15 21.91 10.4 21.91 19.48 0 15.2-19.13 14.23-19.47 14.23-20.4 0-25.65-9.1-25.65-21.9h-30.8l-.18.56c-.68 31.32 28.38 45.22 56.63 45.22 29.98 0 51.12-13.55 51.12-38.29zm125.38-55.63c0-25.3-18.43-45.46-53.42-45.46h-51.78v138.18h32.17v-47.36h19.61c30.25 0 53.42-15.95 53.42-45.36zM297.94 325L347 186.78h-31.09L268 325zm106.52-138.22h-31.09L325.46 325h29.94z\"],\n    \"staylinked\": [440, 512, [], \"f3f5\", \"M382.7 292.5l2.7 2.7-170-167.3c-3.5-3.5-9.7-3.7-13.8-.5L144.3 171c-4.2 3.2-4.6 8.7-1.1 12.2l68.1 64.3c3.6 3.5 9.9 3.7 14 .5l.1-.1c4.1-3.2 10.4-3 14 .5l84 81.3c3.6 3.5 3.2 9-.9 12.2l-93.2 74c-4.2 3.3-10.5 3.1-14.2-.4L63.2 268c-3.5-3.5-9.7-3.7-13.9-.5L3.5 302.4c-4.2 3.2-4.7 8.7-1.2 12.2L211 510.7s7.4 6.8 17.3-.8l198-163.9c4-3.2 4.4-8.7.7-12.2zm54.5-83.4L226.7 2.5c-1.5-1.2-8-5.5-16.3 1.1L3.6 165.7c-4.2 3.2-4.8 8.7-1.2 12.2l42.3 41.7 171.7 165.1c3.7 3.5 10.1 3.7 14.3.4l50.2-38.8-.3-.3 7.7-6c4.2-3.2 4.6-8.7.9-12.2l-57.1-54.4c-3.6-3.5-10-3.7-14.2-.5l-.1.1c-4.2 3.2-10.5 3.1-14.2-.4L109 180.8c-3.6-3.5-3.1-8.9 1.1-12.2l92.2-71.5c4.1-3.2 10.3-3 13.9.5l160.4 159c3.7 3.5 10 3.7 14.1.5l45.8-35.8c4.1-3.2 4.4-8.7.7-12.2z\"],\n    \"steam\": [496, 512, [], \"f1b6\", \"M496 256c0 137-111.2 248-248.4 248-113.8 0-209.6-76.3-239-180.4l95.2 39.3c6.4 32.1 34.9 56.4 68.9 56.4 39.2 0 71.9-32.4 70.2-73.5l84.5-60.2c52.1 1.3 95.8-40.9 95.8-93.5 0-51.6-42-93.5-93.7-93.5s-93.7 42-93.7 93.5v1.2L176.6 279c-15.5-.9-30.7 3.4-43.5 12.1L0 236.1C10.2 108.4 117.1 8 247.6 8 384.8 8 496 119 496 256zM155.7 384.3l-30.5-12.6a52.79 52.79 0 0 0 27.2 25.8c26.9 11.2 57.8-1.6 69-28.4 5.4-13 5.5-27.3.1-40.3-5.4-13-15.5-23.2-28.5-28.6-12.9-5.4-26.7-5.2-38.9-.6l31.5 13c19.8 8.2 29.2 30.9 20.9 50.7-8.3 19.9-31 29.2-50.8 21zm173.8-129.9c-34.4 0-62.4-28-62.4-62.3s28-62.3 62.4-62.3 62.4 28 62.4 62.3-27.9 62.3-62.4 62.3zm.1-15.6c25.9 0 46.9-21 46.9-46.8 0-25.9-21-46.8-46.9-46.8s-46.9 21-46.9 46.8c.1 25.8 21.1 46.8 46.9 46.8z\"],\n    \"steam-square\": [448, 512, [], \"f1b7\", \"M185.2 356.5c7.7-18.5-1-39.7-19.6-47.4l-29.5-12.2c11.4-4.3 24.3-4.5 36.4.5 12.2 5.1 21.6 14.6 26.7 26.7 5 12.2 5 25.6-.1 37.7-10.5 25.1-39.4 37-64.6 26.5-11.6-4.8-20.4-13.6-25.4-24.2l28.5 11.8c18.6 7.8 39.9-.9 47.6-19.4zM400 32H48C21.5 32 0 53.5 0 80v160.7l116.6 48.1c12-8.2 26.2-12.1 40.7-11.3l55.4-80.2v-1.1c0-48.2 39.3-87.5 87.6-87.5s87.6 39.3 87.6 87.5c0 49.2-40.9 88.7-89.6 87.5l-79 56.3c1.6 38.5-29.1 68.8-65.7 68.8-31.8 0-58.5-22.7-64.5-52.7L0 319.2V432c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-99.7 222.5c-32.2 0-58.4-26.1-58.4-58.3s26.2-58.3 58.4-58.3 58.4 26.2 58.4 58.3-26.2 58.3-58.4 58.3zm.1-14.6c24.2 0 43.9-19.6 43.9-43.8 0-24.2-19.6-43.8-43.9-43.8-24.2 0-43.9 19.6-43.9 43.8 0 24.2 19.7 43.8 43.9 43.8z\"],\n    \"steam-symbol\": [448, 512, [], \"f3f6\", \"M395.5 177.5c0 33.8-27.5 61-61 61-33.8 0-61-27.3-61-61s27.3-61 61-61c33.5 0 61 27.2 61 61zm52.5.2c0 63-51 113.8-113.7 113.8L225 371.3c-4 43-40.5 76.8-84.5 76.8-40.5 0-74.7-28.8-83-67L0 358V250.7L97.2 290c15.1-9.2 32.2-13.3 52-11.5l71-101.7c.5-62.3 51.5-112.8 114-112.8C397 64 448 115 448 177.7zM203 363c0-34.7-27.8-62.5-62.5-62.5-4.5 0-9 .5-13.5 1.5l26 10.5c25.5 10.2 38 39 27.7 64.5-10.2 25.5-39.2 38-64.7 27.5-10.2-4-20.5-8.3-30.7-12.2 10.5 19.7 31.2 33.2 55.2 33.2 34.7 0 62.5-27.8 62.5-62.5zm207.5-185.3c0-42-34.3-76.2-76.2-76.2-42.3 0-76.5 34.2-76.5 76.2 0 42.2 34.3 76.2 76.5 76.2 41.9.1 76.2-33.9 76.2-76.2z\"],\n    \"sticker-mule\": [576, 512, [], \"f3f7\", \"M561.7 199.6c-1.3.3.3 0 0 0zm-6.2-77.4c-7.7-22.3-5.1-7.2-13.4-36.9-1.6-6.5-3.6-14.5-6.2-20-4.4-8.7-4.6-7.5-4.6-9.5 0-5.3 30.7-45.3 19-46.9-5.7-.6-12.2 11.6-20.6 17-8.6 4.2-8 5-10.3 5-2.6 0-5.7-3-6.2-5-2-5.7 1.9-25.9-3.6-25.9-3.6 0-12.3 24.8-17 25.8-5.2 1.3-27.9-11.4-75.1 18-25.3 13.2-86.9 65.2-87 65.3-6.7 4.7-20 4.7-35.5 16-44.4 30.1-109.6 9.4-110.7 9-110.6-26.8-128-15.2-159 11.5-20.8 17.9-23.7 36.5-24.2 38.9-4.2 20.4 5.2 48.3 6.7 64.3 1.8 19.3-2.7 17.7 7.7 98.3.5 1 4.1 0 5.1 1.5 0 8.4-3.8 12.1-4.1 13-1.5 4.5-1.5 10.5 0 16 2.3 8.2 8.2 37.2 8.2 46.9 0 41.8.4 44 2.6 49.4 3.9 10 12.5 9.1 17 12 3.1 3.5-.5 8.5 1 12.5.5 2 3.6 4 6.2 5 9.2 3.6 27 .3 29.9-2.5 1.6-1.5.5-4.5 3.1-5 5.1 0 10.8-.5 14.4-2.5 5.1-2.5 4.1-6 1.5-10.5-.4-.8-7-13.3-9.8-16-2.1-2-5.1-3-7.2-4.5-5.8-4.9-10.3-19.4-10.3-19.5-4.6-19.4-10.3-46.3-4.1-66.8 4.6-17.2 39.5-87.7 39.6-87.8 4.1-6.5 17-11.5 27.3-7 6 1.9 19.3 22 65.4 30.9 47.9 8.7 97.4-2 112.2-2 2.8 2-1.9 13-.5 38.9 0 26.4-.4 13.7-4.1 29.9-2.2 9.7 3.4 23.2-1.5 46.9-1.4 9.8-9.9 32.7-8.2 43.4.5 1 1 2 1.5 3.5.5 4.5 1.5 8.5 4.6 10 7.3 3.6 12-3.5 9.8 11.5-.7 3.1-2.6 12 1.5 15 4.4 3.7 30.6 3.4 36.5.5 2.6-1.5 1.6-4.5 6.4-7.4 1.9-.9 11.3-.4 11.3-6.5.3-1.8-9.2-19.9-9.3-20-2.6-3.5-9.2-4.5-11.3-8-6.9-10.1-1.7-52.6.5-59.4 3-11 5.6-22.4 8.7-32.4 11-42.5 10.3-50.6 16.5-68.3.8-1.8 6.4-23.1 10.3-29.9 9.3-17 21.7-32.4 33.5-47.4 18-22.9 34-46.9 52-69.8 6.1-7 8.2-13.7 18-8 10.8 5.7 21.6 7 31.9 17 14.6 12.8 10.2 18.2 11.8 22.9 1.5 5 7.7 10.5 14.9 9.5 10.4-2 13-2.5 13.4-2.5 2.6-.5 5.7-5 7.2-8 3.1-5.5 7.2-9 7.2-16.5 0-7.7-.4-2.8-20.6-52.9z\"],\n    \"strava\": [384, 512, [], \"f428\", \"M158.4 0L7 292h89.2l62.2-116.1L220.1 292h88.5zm150.2 292l-43.9 88.2-44.6-88.2h-67.6l112.2 220 111.5-220z\"],\n    \"stripe\": [640, 512, [], \"f429\", \"M165 144.7l-43.3 9.2-.2 142.4c0 26.3 19.8 43.3 46.1 43.3 14.6 0 25.3-2.7 31.2-5.9v-33.8c-5.7 2.3-33.7 10.5-33.7-15.7V221h33.7v-37.8h-33.7zm89.1 51.6l-2.7-13.1H213v153.2h44.3V233.3c10.5-13.8 28.2-11.1 33.9-9.3v-40.8c-6-2.1-26.7-6-37.1 13.1zm92.3-72.3l-44.6 9.5v36.2l44.6-9.5zM44.9 228.3c0-6.9 5.8-9.6 15.1-9.7 13.5 0 30.7 4.1 44.2 11.4v-41.8c-14.7-5.8-29.4-8.1-44.1-8.1-36 0-60 18.8-60 50.2 0 49.2 67.5 41.2 67.5 62.4 0 8.2-7.1 10.9-17 10.9-14.7 0-33.7-6.1-48.6-14.2v40c16.5 7.1 33.2 10.1 48.5 10.1 36.9 0 62.3-15.8 62.3-47.8 0-52.9-67.9-43.4-67.9-63.4zM640 261.6c0-45.5-22-81.4-64.2-81.4s-67.9 35.9-67.9 81.1c0 53.5 30.3 78.2 73.5 78.2 21.2 0 37.1-4.8 49.2-11.5v-33.4c-12.1 6.1-26 9.8-43.6 9.8-17.3 0-32.5-6.1-34.5-26.9h86.9c.2-2.3.6-11.6.6-15.9zm-87.9-16.8c0-20 12.3-28.4 23.4-28.4 10.9 0 22.5 8.4 22.5 28.4zm-112.9-64.6c-17.4 0-28.6 8.2-34.8 13.9l-2.3-11H363v204.8l44.4-9.4.1-50.2c6.4 4.7 15.9 11.2 31.4 11.2 31.8 0 60.8-23.2 60.8-79.6.1-51.6-29.3-79.7-60.5-79.7zm-10.6 122.5c-10.4 0-16.6-3.8-20.9-8.4l-.3-66c4.6-5.1 11-8.8 21.2-8.8 16.2 0 27.4 18.2 27.4 41.4.1 23.9-10.9 41.8-27.4 41.8zm-126.7 33.7h44.6V183.2h-44.6z\"],\n    \"stripe-s\": [384, 512, [], \"f42a\", \"M155.3 154.6c0-22.3 18.6-30.9 48.4-30.9 43.4 0 98.5 13.3 141.9 36.7V26.1C298.3 7.2 251.1 0 203.8 0 88.1 0 11 60.4 11 161.4c0 157.9 216.8 132.3 216.8 200.4 0 26.4-22.9 34.9-54.7 34.9-47.2 0-108.2-19.5-156.1-45.5v128.5a396.09 396.09 0 0 0 156 32.4c118.6 0 200.3-51 200.3-153.6 0-170.2-218-139.7-218-203.9z\"],\n    \"studiovinari\": [512, 512, [], \"f3f8\", \"M480.3 187.7l4.2 28v28l-25.1 44.1-39.8 78.4-56.1 67.5-79.1 37.8-17.7 24.5-7.7 12-9.6 4s17.3-63.6 19.4-63.6c2.1 0 20.3.7 20.3.7l66.7-38.6-92.5 26.1-55.9 36.8-22.8 28-6.6 1.4 20.8-73.6 6.9-5.5 20.7 12.9 88.3-45.2 56.8-51.5 14.8-68.4-125.4 23.3 15.2-18.2-173.4-53.3 81.9-10.5-166-122.9L133.5 108 32.2 0l252.9 126.6-31.5-38L378 163 234.7 64l18.7 38.4-49.6-18.1L158.3 0l194.6 122L310 66.2l108 96.4 12-8.9-21-16.4 4.2-37.8L451 89.1l29.2 24.7 11.5 4.2-7 6.2 8.5 12-13.1 7.4-10.3 20.2 10.5 23.9z\"],\n    \"stumbleupon\": [512, 512, [], \"f1a4\", \"M502.9 266v69.7c0 62.1-50.3 112.4-112.4 112.4-61.8 0-112.4-49.8-112.4-111.3v-70.2l34.3 16 51.1-15.2V338c0 14.7 12 26.5 26.7 26.5S417 352.7 417 338v-72h85.9zm-224.7-58.2l34.3 16 51.1-15.2V173c0-60.5-51.1-109-112.1-109-60.8 0-112.1 48.2-112.1 108.2v162.4c0 14.9-12 26.7-26.7 26.7S86 349.5 86 334.6V266H0v69.7C0 397.7 50.3 448 112.4 448c61.6 0 112.4-49.5 112.4-110.8V176.9c0-14.7 12-26.7 26.7-26.7s26.7 12 26.7 26.7v30.9z\"],\n    \"stumbleupon-circle\": [496, 512, [], \"f1a3\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 177.5c-9.8 0-17.8 8-17.8 17.8v106.9c0 40.9-33.9 73.9-74.9 73.9-41.4 0-74.9-33.5-74.9-74.9v-46.5h57.3v45.8c0 10 8 17.8 17.8 17.8s17.8-7.9 17.8-17.8V200.1c0-40 34.2-72.1 74.7-72.1 40.7 0 74.7 32.3 74.7 72.6v23.7l-34.1 10.1-22.9-10.7v-20.6c.1-9.6-7.9-17.6-17.7-17.6zm167.6 123.6c0 41.4-33.5 74.9-74.9 74.9-41.2 0-74.9-33.2-74.9-74.2V263l22.9 10.7 34.1-10.1v47.1c0 9.8 8 17.6 17.8 17.6s17.8-7.9 17.8-17.6v-48h57.3c-.1 45.9-.1 46.4-.1 46.4z\"],\n    \"superpowers\": [448, 512, [], \"f2dd\", \"M448 32c-83.3 11-166.8 22-250 33-92 12.5-163.3 86.7-169 180-3.3 55.5 18 109.5 57.8 148.2L0 480c83.3-11 166.5-22 249.8-33 91.8-12.5 163.3-86.8 168.7-179.8 3.5-55.5-18-109.5-57.7-148.2L448 32zm-79.7 232.3c-4.2 79.5-74 139.2-152.8 134.5-79.5-4.7-140.7-71-136.3-151 4.5-79.2 74.3-139.3 153-134.5 79.3 4.7 140.5 71 136.1 151z\"],\n    \"supple\": [640, 512, [], \"f3f9\", \"M640 262.5c0 64.1-109 116.1-243.5 116.1-24.8 0-48.6-1.8-71.1-5 7.7.4 15.5.6 23.4.6 134.5 0 243.5-56.9 243.5-127.1 0-29.4-19.1-56.4-51.2-78 60 21.1 98.9 55.1 98.9 93.4zM47.7 227.9c-.1-70.2 108.8-127.3 243.3-127.6 7.9 0 15.6.2 23.3.5-22.5-3.2-46.3-4.9-71-4.9C108.8 96.3-.1 148.5 0 212.6c.1 38.3 39.1 72.3 99.3 93.3-32.3-21.5-51.5-48.6-51.6-78zm60.2 39.9s10.5 13.2 29.3 13.2c17.9 0 28.4-11.5 28.4-25.1 0-28-40.2-25.1-40.2-39.7 0-5.4 5.3-9.1 12.5-9.1 5.7 0 11.3 2.6 11.3 6.6v3.9h14.2v-7.9c0-12.1-15.4-16.8-25.4-16.8-16.5 0-28.5 10.2-28.5 24.1 0 26.6 40.2 25.4 40.2 39.9 0 6.6-5.8 10.1-12.3 10.1-11.9 0-20.7-10.1-20.7-10.1l-8.8 10.9zm120.8-73.6v54.4c0 11.3-7.1 17.8-17.8 17.8-10.7 0-17.8-6.5-17.8-17.7v-54.5h-15.8v55c0 18.9 13.4 31.9 33.7 31.9 20.1 0 33.4-13 33.4-31.9v-55h-15.7zm34.4 85.4h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.8-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5.1 14.7-14 14.7h-12.6zm57 43h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.7-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5 14.7-14 14.7h-12.6zm57.1 34.8c0 5.8 2.4 8.2 8.2 8.2h37.6c5.8 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-18.6c-1.7 0-2.6-1-2.6-2.6v-61.2c0-5.7-2.4-8.2-8.2-8.2H401v13.4h5.2c1.7 0 2.6 1 2.6 2.6v61.2zm63.4 0c0 5.8 2.4 8.2 8.2 8.2H519c5.7 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-19.7c-1.7 0-2.6-1-2.6-2.6v-20.3h27.7v-13.4H488v-22.4h19.2c1.7 0 2.6 1 2.6 2.6v5.2H524v-13c0-5.7-2.5-8.2-8.2-8.2h-51.6v13.4h7.8v63.9zm58.9-76v5.9h1.6v-5.9h2.7v-1.2h-7v1.2h2.7zm5.7-1.2v7.1h1.5v-5.7l2.3 5.7h1.3l2.3-5.7v5.7h1.5v-7.1h-2.3l-2.1 5.1-2.1-5.1h-2.4z\"],\n    \"suse\": [640, 512, [], \"f7d6\", \"M471.08 102.66s-.3 18.3-.3 20.3c-9.1-3-74.4-24.1-135.7-26.3-51.9-1.8-122.8-4.3-223 57.3-19.4 12.4-73.9 46.1-99.6 109.7C7 277-.12 307 7 335.06a111 111 0 0 0 16.5 35.7c17.4 25 46.6 41.6 78.1 44.4 44.4 3.9 78.1-16 90-53.3 8.2-25.8 0-63.6-31.5-82.9-25.6-15.7-53.3-12.1-69.2-1.6-13.9 9.2-21.8 23.5-21.6 39.2.3 27.8 24.3 42.6 41.5 42.6a49 49 0 0 0 15.8-2.7c6.5-1.8 13.3-6.5 13.3-14.9 0-12.1-11.6-14.8-16.8-13.9-2.9.5-4.5 2-11.8 2.4-2-.2-12-3.1-12-14V316c.2-12.3 13.2-18 25.5-16.9 32.3 2.8 47.7 40.7 28.5 65.7-18.3 23.7-76.6 23.2-99.7-20.4-26-49.2 12.7-111.2 87-98.4 33.2 5.7 83.6 35.5 102.4 104.3h45.9c-5.7-17.6-8.9-68.3 42.7-68.3 56.7 0 63.9 39.9 79.8 68.3H460c-12.8-18.3-21.7-38.7-18.9-55.8 5.6-33.8 39.7-18.4 82.4-17.4 66.5.4 102.1-27 103.1-28 3.7-3.1 6.5-15.8 7-17.7 1.3-5.1-3.2-2.4-3.2-2.4-8.7 5.2-30.5 15.2-50.9 15.6-25.3.5-76.2-25.4-81.6-28.2-.3-.4.1 1.2-11-25.5 88.4 58.3 118.3 40.5 145.2 21.7.8-.6 4.3-2.9 3.6-5.7-13.8-48.1-22.4-62.7-34.5-69.6-37-21.6-125-34.7-129.2-35.3.1-.1-.9-.3-.9.7zm60.4 72.8a37.54 37.54 0 0 1 38.9-36.3c33.4 1.2 48.8 42.3 24.4 65.2-24.2 22.7-64.4 4.6-63.3-28.9zm38.6-25.3a26.27 26.27 0 1 0 25.4 27.2 26.19 26.19 0 0 0-25.4-27.2zm4.3 28.8c-15.4 0-15.4-15.6 0-15.6s15.4 15.64 0 15.64z\"],\n    \"symfony\": [512, 512, [], \"f83d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm133.74 143.54c-11.47.41-19.4-6.45-19.77-16.87-.27-9.18 6.68-13.44 6.53-18.85-.23-6.55-10.16-6.82-12.87-6.67-39.78 1.29-48.59 57-58.89 113.85 21.43 3.15 36.65-.72 45.14-6.22 12-7.75-3.34-15.72-1.42-24.56 4-18.16 32.55-19 32 5.3-.36 17.86-25.92 41.81-77.6 35.7-10.76 59.52-18.35 115-58.2 161.72-29 34.46-58.4 39.82-71.58 40.26-24.65.85-41-12.31-41.58-29.84-.56-17 14.45-26.26 24.31-26.59 21.89-.75 30.12 25.67 14.88 34-12.09 9.71.11 12.61 2.05 12.55 10.42-.36 17.34-5.51 22.18-9 24-20 33.24-54.86 45.35-118.35 8.19-49.66 17-78 18.23-82-16.93-12.75-27.08-28.55-49.85-34.72-15.61-4.23-25.12-.63-31.81 7.83-7.92 10-5.29 23 2.37 30.7l12.63 14c15.51 17.93 24 31.87 20.8 50.62-5.06 29.93-40.72 52.9-82.88 39.94-36-11.11-42.7-36.56-38.38-50.62 7.51-24.15 42.36-11.72 34.62 13.6-2.79 8.6-4.92 8.68-6.28 13.07-4.56 14.77 41.85 28.4 51-1.39 4.47-14.52-5.3-21.71-22.25-39.85-28.47-31.75-16-65.49 2.95-79.67C204.23 140.13 251.94 197 262 205.29c37.17-109 100.53-105.46 102.43-105.53 25.16-.81 44.19 10.59 44.83 28.65.25 7.69-4.17 22.59-19.52 23.13z\"],\n    \"teamspeak\": [512, 512, [], \"f4f9\", \"M244.2 346.79c2.4-12.3-12-30-32.4-48.7-20.9-19.2-48.2-39.1-63.4-46.6-21.7-12-41.7-1.8-46.3 22.7-5 26.2 0 51.4 14.5 73.9 10.2 15.5 25.4 22.7 43.4 24 11.6.6 52.5 2.2 61.7-1 11.9-4.3 20.1-11.8 22.5-24.3zm205 20.8a5.22 5.22 0 0 0-8.3 2.4c-8 25.4-44.7 112.5-172.1 121.5-149.7 10.5 80.3 43.6 145.4-6.4 22.7-17.4 47.6-35 46.6-85.4-.4-10.1-4.9-26.69-11.6-32.1zm62-122.4c-.3-18.9-8.6-33.4-26-42.2-2.9-1.3-5-2.7-5.9-6.4A222.64 222.64 0 0 0 438.9 103c-1.1-1.5-3.5-3.2-2.2-5 8.5-11.5-.3-18-7-24.4Q321.4-31.11 177.4 13.09c-40.1 12.3-73.9 35.6-102 67.4-4 4.3-6.7 9.1-3 14.5 3 4 1.3 6.2-1 9.3C51.6 132 38.2 162.59 32.1 196c-.7 4.3-2.9 6-6.4 7.8-14.2 7-22.5 18.5-24.9 34L0 264.29v20.9c0 30.8 21 50.4 51.8 49 7.7-.3 11.7-4.3 12-11.5 2-77.5-2.4-95.4 3.7-125.8C92.1 72.39 234.3 5 345.3 65.39 411.4 102 445.7 159 447.6 234.79c.8 28.2 0 56.5 0 84.6 0 7 2.2 12.5 9.4 14.2 24.1 5 49.2-12 53.2-36.7 2.9-17.1 1-34.5 1-51.7zm-159.6 131.5c36.5 2.8 59.3-28.5 58.4-60.5-2.1-45.2-66.2-16.5-87.8-8-73.2 28.1-45 54.9-22.2 60.8z\"],\n    \"telegram\": [496, 512, [], \"f2c6\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm121.8 169.9l-40.7 191.8c-3 13.6-11.1 16.9-22.4 10.5l-62-45.7-29.9 28.8c-3.3 3.3-6.1 6.1-12.5 6.1l4.4-63.1 114.9-103.8c5-4.4-1.1-6.9-7.7-2.5l-142 89.4-61.2-19.1c-13.3-4.2-13.6-13.3 2.8-19.7l239.1-92.2c11.1-4 20.8 2.7 17.2 19.5z\"],\n    \"telegram-plane\": [448, 512, [], \"f3fe\", \"M446.7 98.6l-67.6 318.8c-5.1 22.5-18.4 28.1-37.3 17.5l-103-75.9-49.7 47.8c-5.5 5.5-10.1 10.1-20.7 10.1l7.4-104.9 190.9-172.5c8.3-7.4-1.8-11.5-12.9-4.1L117.8 284 16.2 252.2c-22.1-6.9-22.5-22.1 4.6-32.7L418.2 66.4c18.4-6.9 34.5 4.1 28.5 32.2z\"],\n    \"tencent-weibo\": [384, 512, [], \"f1d5\", \"M72.3 495.8c1.4 19.9-27.6 22.2-29.7 2.9C31 368.8 73.7 259.2 144 185.5c-15.6-34 9.2-77.1 50.6-77.1 30.3 0 55.1 24.6 55.1 55.1 0 44-49.5 70.8-86.9 45.1-65.7 71.3-101.4 169.8-90.5 287.2zM192 .1C66.1.1-12.3 134.3 43.7 242.4 52.4 259.8 79 246.9 70 229 23.7 136.4 91 29.8 192 29.8c75.4 0 136.9 61.4 136.9 136.9 0 90.8-86.9 153.9-167.7 133.1-19.1-4.1-25.6 24.4-6.6 29.1 110.7 23.2 204-60 204-162.3C358.6 74.7 284 .1 192 .1z\"],\n    \"the-red-yeti\": [512, 512, [], \"f69d\", \"M488.23 241.7l20.7 7.1c-9.6-23.9-23.9-37-31.7-44.8l7.1-18.2c.2 0 12.3-27.8-2.5-30.7-.6-11.3-6.6-27-18.4-27-7.6-10.6-17.7-12.3-30.7-5.9a122.2 122.2 0 0 0-25.3 16.5c-5.3-6.4-3 .4-3-29.8-37.1-24.3-45.4-11.7-74.8 3l.5.5a239.36 239.36 0 0 0-68.4-13.3c-5.5-8.7-18.6-19.1-25.1-25.1l24.8 7.1c-5.5-5.5-26.8-12.9-34.2-15.2 18.2-4.1 29.8-20.8 42.5-33-34.9-10.1-67.9-5.9-97.9 11.8l12-44.2L182 0c-31.6 24.2-33 41.9-33.7 45.5-.9-2.4-6.3-19.6-15.2-27a35.12 35.12 0 0 0-.5 25.3c3 8.4 5.9 14.8 8.4 18.9-16-3.3-28.3-4.9-49.2 0h-3.7l33 14.3a194.26 194.26 0 0 0-46.7 67.4l-1.7 8.4 1.7 1.7 7.6-4.7c-3.3 11.6-5.3 19.4-6.6 25.8a200.18 200.18 0 0 0-27.8 40.3c-15 1-31.8 10.8-40.3 14.3l3 3.4 28.8 1c-.5 1-.7 2.2-1.2 3.2-7.3 6.4-39.8 37.7-33 80.7l20.2-22.4c.5 1.7.7 3.4 1.2 5.2 0 25.5.4 89.6 64.9 150.5 43.6 40 96 60.2 157.5 60.2 121.7 0 223-87.3 223-211.5 6.8-9.7-1.2 3 16.7-25.1l13 14.3 2.5-.5A181.84 181.84 0 0 0 495 255a44.74 44.74 0 0 0-6.8-13.3zM398 111.2l-.5 21.9c5.5 18.1 16.9 17.2 22.4 17.2l-3.4-4.7 22.4-5.4a242.44 242.44 0 0 1-27 0c12.8-2.1 33.3-29 43-11.3 3.4 7.6 6.4 17.2 9.3 27.8l1.7-5.9a56.38 56.38 0 0 1-1.7-15.2c5.4.5 8.8 3.4 9.3 10.1.5 6.4 1.7 14.8 3.4 25.3l4.7-11.3c4.6 0 4.5-3.6-2.5 20.7-20.9-8.7-35.1-8.4-46.5-8.4l18.2-16c-25.3 8.2-33 10.8-54.8 20.9-1.1-5.4-5-13.5-16-19.9-3.2 3.8-2.8.9-.7 14.8h-2.5a62.32 62.32 0 0 0-8.4-23.1l4.2-3.4c8.4-7.1 11.8-14.3 10.6-21.9-.5-6.4-5.4-13.5-13.5-20.7 5.6-3.4 15.2-.4 28.3 8.5zm-39.6-10.1c2.7 1.9 11.4 5.4 18.9 17.2 4.2 8.4 4 9.8 3.4 11.1-.5 2.4-.5 4.3-3 7.1-1.7 2.5-5.4 4.7-11.8 7.6-7.6-13-16.5-23.6-27.8-31.2zM91 143.1l1.2-1.7c1.2-2.9 4.2-7.6 9.3-15.2l2.5-3.4-13 12.3 5.4-4.7-10.1 9.3-4.2 1.2c12.3-24.1 23.1-41.3 32.5-50.2 9.3-9.3 16-16 20.2-19.4l-6.4 1.2c-11.3-4.2-19.4-7.1-24.8-8.4 2.5-.5 3.7-.5 3.2-.5 10.3 0 17.5.5 20.9 1.2a52.35 52.35 0 0 0 16 2.5l.5-1.7-8.4-35.8 13.5 29a42.89 42.89 0 0 0 5.9-14.3c1.7-6.4 5.4-13 10.1-19.4s7.6-10.6 9.3-11.3a234.68 234.68 0 0 0-6.4 25.3l-1.7 7.1-.5 4.7 2.5 2.5C190.4 39.9 214 34 239.8 34.5l21.1.5c-11.8 13.5-27.8 21.9-48.5 24.8a201.26 201.26 0 0 1-23.4 2.9l-.2-.5-2.5-1.2a20.75 20.75 0 0 0-14 2c-2.5-.2-4.9-.5-7.1-.7l-2.5 1.7.5 1.2c2 .2 3.9.5 6.2.7l-2 3.4 3.4-.5-10.6 11.3c-4.2 3-5.4 6.4-4.2 9.3l5.4-3.4h1.2a39.4 39.4 0 0 1 25.3-15.2v-3c6.4.5 13 1 19.4 1.2 6.4 0 8.4.5 5.4 1.2a189.6 189.6 0 0 1 20.7 13.5c13.5 10.1 23.6 21.9 30 35.4 8.8 18.2 13.5 37.1 13.5 56.6a141.13 141.13 0 0 1-3 28.3 209.91 209.91 0 0 1-16 46l2.5.5c18.2-19.7 41.9-16 49.2-16l-6.4 5.9 22.4 17.7-1.7 30.7c-5.4-12.3-16.5-21.1-33-27.8 16.5 14.8 23.6 21.1 21.9 20.2-4.8-2.8-3.5-1.9-10.8-3.7 4.1 4.1 17.5 18.8 18.2 20.7l.2.2-.2.2c0 1.8 1.6-1.2-14 22.9-75.2-15.3-106.27-42.7-141.2-63.2l11.8 1.2c-11.8-18.5-15.6-17.7-38.4-26.1L149 225c-8.8-3-18.2-3-28.3.5l7.6-10.6-1.2-1.7c-14.9 4.3-19.8 9.2-22.6 11.3-1.1-5.5-2.8-12.4-12.3-28.8l-1.2 27-13.2-5c1.5-25.2 5.4-50.5 13.2-74.6zm276.5 330c-49.9 25-56.1 22.4-59 23.9-29.8-11.8-50.9-31.7-63.5-58.8l30 16.5c-9.8-9.3-18.3-16.5-38.4-44.3l11.8 23.1-17.7-7.6c14.2 21.1 23.5 51.7 66.6 73.5-120.8 24.2-199-72.1-200.9-74.3a262.57 262.57 0 0 0 35.4 24.8c3.4 1.7 7.1 2.5 10.1 1.2l-16-20.7c9.2 4.2 9.5 4.5 69.1 29-42.5-20.7-73.8-40.8-93.2-60.2-.5 6.4-1.2 10.1-1.2 10.1a80.25 80.25 0 0 1 20.7 26.6c-39-18.9-57.6-47.6-71.3-82.6 49.9 55.1 118.9 37.5 120.5 37.1 34.8 16.4 69.9 23.6 113.9 10.6 3.3 0 20.3 17 25.3 39.1l4.2-3-2.5-23.6c9 9 24.9 22.6 34.4 13-15.6-5.3-23.5-9.5-29.5-31.7 4.6 4.2 7.6 9 27.8 15l1.2-1.2-10.5-14.2c11.7-4.8-3.5 1 32-10.8 4.3 34.3 9 49.2.7 89.5zm115.3-214.4l-2.5.5 3 9.3c-3.5 5.9-23.7 44.3-71.6 79.7-39.5 29.8-76.6 39.1-80.9 40.3l-7.6-7.1-1.2 3 14.3 16-7.1-4.7 3.4 4.2h-1.2l-21.9-13.5 9.3 26.6-19-27.9-1.2 2.5 7.6 29c-6.1-8.2-21-32.6-56.8-39.6l32.5 21.2a214.82 214.82 0 0 1-93.2-6.4c-4.2-1.2-8.9-2.5-13.5-4.2l1.2-3-44.8-22.4 26.1 22.4c-57.7 9.1-113-25.4-126.4-83.4l-2.5-16.4-22.27 22.3c19.5-57.5 25.6-57.9 51.4-70.1-9.1-5.3-1.6-3.3-38.4-9.3 15.8-5.8 33-15.4 73 5.2a18.5 18.5 0 0 1 3.7-1.7c.6-3.2.4-.8 1-11.8 3.9 10 3.6 8.7 3 9.3l1.7.5c12.7-6.5 8.9-4.5 17-8.9l-5.4 13.5 22.3-5.8-8.4 8.4 2.5 2.5c4.5-1.8 30.3 3.4 40.8 16l-23.6-2.5c39.4 23 51.5 54 55.8 69.6l1.7-1.2c-2.8-22.3-12.4-33.9-16-40.1 4.2 5 39.2 34.6 110.4 46-11.3-.5-23.1 5.4-34.9 18.9l46.7-20.2-9.3 21.9c7.6-10.1 14.8-23.6 21.2-39.6v-.5l1.2-3-1.2 16c13.5-41.8 25.3-78.5 35.4-109.7l13.5-27.8v-2l-5.4-4.2h10.1l5.9 4.2 2.5-1.2-3.4-16 12.3 18.9 41.8-20.2-14.8 13 .5 2.9 17.7-.5a184 184 0 0 1 33 4.2l-23.6 2.5-1.2 3 26.6 23.1a254.21 254.21 0 0 1 27 32c-11.2-3.3-10.3-3.4-21.2-3.4l12.3 32.5zm-6.1-71.3l-3.9 13-14.3-11.8zm-254.8 7.1c1.7 10.6 4.7 17.7 8.8 21.9-9.3 6.6-27.5 13.9-46.5 16l.5 1.2a50.22 50.22 0 0 0 24.8-2.5l-7.1 13c4.2-1.7 10.1-7.1 17.7-14.8 11.9-5.5 12.7-5.1 20.2-16-12.7-6.4-15.7-13.7-18.4-18.8zm3.7-102.3c-6.4-3.4-10.6 3-12.3 18.9s2.5 29.5 11.8 39.6 18.2 10.6 26.1 3 3.4-23.6-11.3-47.7a39.57 39.57 0 0 0-14.27-13.8zm-4.7 46.3c5.4 2.2 10.5 1.9 12.3-10.6v-4.7l-1.2.5c-4.3-3.1-2.5-4.5-1.7-6.2l.5-.5c-.9-1.2-5-8.1-12.5 4.7-.5-13.5.5-21.9 3-24.8 1.2-2.5 4.7-1.2 11.3 4.2 6.4 5.4 11.3 16 15.2 32.5 6.5 28-19.8 26.2-26.9 4.9zm-45-5.5c1.6.3 9.3-1.1 9.3-14.8h-.5c-5.4-1.1-2.2-5.5-.7-5.9-1.7-3-3.4-4.2-5.4-4.7-8.1 0-11.6 12.7-8.1 21.2a7.51 7.51 0 0 0 5.43 4.2zM216 82.9l-2.5.5.5 3a48.94 48.94 0 0 1 26.1 5.9c-2.5-5.5-10-14.3-28.3-14.3l.5 2.5zm-71.8 49.4c21.7 16.8 16.5 21.4 46.5 23.6l-2.9-4.7a42.67 42.67 0 0 0 14.8-28.3c1.7-16-1.2-29.5-8.8-41.3l13-7.6a2.26 2.26 0 0 0-.5-1.7 14.21 14.21 0 0 0-13.5 1.7c-12.7 6.7-28 20.9-29 22.4-1.7 1.7-3.4 5.9-5.4 13.5a99.61 99.61 0 0 0-2.9 23.6c-4.7-8-10.5-6.4-19.9-5.9l7.1 7.6c-16.5 0-23.3 15.4-23.6 16 6.8 0 4.6-7.6 30-12.3-4.3-6.3-3.3-5-4.9-6.6zm18.7-18.7c1.2-7.6 3.4-13 6.4-17.2 5.4-6.4 10.6-10.1 16-11.8 4.2-1.7 7.1 1.2 10.1 9.3a72.14 72.14 0 0 1 3 25.3c-.5 9.3-3.4 17.2-8.4 23.1-2.9 3.4-5.4 5.9-6.4 7.6a39.21 39.21 0 0 1-11.3-.5l-7.1-3.4-5.4-6.4c.8-10 1.3-18.8 3.1-26zm42 56.1c-34.8 14.4-34.7 14-36.1 14.3-20.8 4.7-19-24.4-18.9-24.8l5.9-1.2-.5-2.5c-20.2-2.6-31 4.2-32.5 4.9.5.5 3 3.4 5.9 9.3 4.2-6.4 8.8-10.1 15.2-10.6a83.47 83.47 0 0 0 1.7 33.7c.1.5 2.6 17.4 27.5 24.1 11.3 3 27 1.2 48.9-5.4l-9.2.5c-4.2-14.8-6.4-24.8-5.9-29.5 11.3-8.8 21.9-11.3 30.7-7.6h2.5l-11.8-7.6-7.1.5c-5.9 1.2-12.3 4.2-19.4 8.4z\"],\n    \"themeco\": [448, 512, [], \"f5c6\", \"M202.9 8.43c9.9-5.73 26-5.82 35.95-.21L430 115.85c10 5.6 18 19.44 18 30.86V364c0 11.44-8.06 25.29-18 31L238.81 503.74c-9.93 5.66-26 5.57-35.85-.21L17.86 395.12C8 389.34 0 375.38 0 364V146.71c0-11.44 8-25.36 17.91-31.08zm-77.4 199.83c-15.94 0-31.89.14-47.83.14v101.45H96.8V280h28.7c49.71 0 49.56-71.74 0-71.74zm140.14 100.29l-30.73-34.64c37-7.51 34.8-65.23-10.87-65.51-16.09 0-32.17-.14-48.26-.14v101.59h19.13v-33.91h18.41l29.56 33.91h22.76zm-41.59-82.32c23.34 0 23.26 32.46 0 32.46h-29.13v-32.46zm-95.56-1.6c21.18 0 21.11 38.85 0 38.85H96.18v-38.84zm192.65-18.25c-68.46 0-71 105.8 0 105.8 69.48-.01 69.41-105.8 0-105.8zm0 17.39c44.12 0 44.8 70.86 0 70.86s-44.43-70.86 0-70.86z\"],\n    \"themeisle\": [512, 512, [], \"f2b2\", \"M208 88.286c0-10 6.286-21.714 17.715-21.714 11.142 0 17.714 11.714 17.714 21.714 0 10.285-6.572 21.714-17.714 21.714C214.286 110 208 98.571 208 88.286zm304 160c0 36.001-11.429 102.286-36.286 129.714-22.858 24.858-87.428 61.143-120.857 70.572l-1.143.286v32.571c0 16.286-12.572 30.571-29.143 30.571-10 0-19.429-5.714-24.572-14.286-5.427 8.572-14.856 14.286-24.856 14.286-10 0-19.429-5.714-24.858-14.286-5.142 8.572-14.571 14.286-24.57 14.286-10.286 0-19.429-5.714-24.858-14.286-5.143 8.572-14.571 14.286-24.571 14.286-18.857 0-29.429-15.714-29.429-32.857-16.286 12.285-35.715 19.428-56.571 19.428-22 0-43.429-8.285-60.286-22.857 10.285-.286 20.571-2.286 30.285-5.714-20.857-5.714-39.428-18.857-52-36.286 21.37 4.645 46.209 1.673 67.143-11.143-22-22-56.571-58.857-68.572-87.428C1.143 321.714 0 303.714 0 289.429c0-49.714 20.286-160 86.286-160 10.571 0 18.857 4.858 23.143 14.857a158.792 158.792 0 0 1 12-15.428c2-2.572 5.714-5.429 7.143-8.286 7.999-12.571 11.714-21.142 21.714-34C182.571 45.428 232 17.143 285.143 17.143c6 0 12 .285 17.714 1.143C313.714 6.571 328.857 0 344.572 0c14.571 0 29.714 6 40 16.286.857.858 1.428 2.286 1.428 3.428 0 3.714-10.285 13.429-12.857 16.286 4.286 1.429 15.714 6.858 15.714 12 0 2.857-2.857 5.143-4.571 7.143 31.429 27.714 49.429 67.143 56.286 108 4.286-5.143 10.285-8.572 17.143-8.572 10.571 0 20.857 7.144 28.571 14.001C507.143 187.143 512 221.714 512 248.286zM188 89.428c0 18.286 12.571 37.143 32.286 37.143 19.714 0 32.285-18.857 32.285-37.143 0-18-12.571-36.857-32.285-36.857-19.715 0-32.286 18.858-32.286 36.857zM237.714 194c0-19.714 3.714-39.143 8.571-58.286-52.039 79.534-13.531 184.571 68.858 184.571 21.428 0 42.571-7.714 60-20 2-7.429 3.714-14.857 3.714-22.572 0-14.286-6.286-21.428-20.572-21.428-4.571 0-9.143.857-13.429 1.714-63.343 12.668-107.142 3.669-107.142-63.999zm-41.142 254.858c0-11.143-8.858-20.857-20.286-20.857-11.429 0-20 9.715-20 20.857v32.571c0 11.143 8.571 21.142 20 21.142 11.428 0 20.286-9.715 20.286-21.142v-32.571zm49.143 0c0-11.143-8.572-20.857-20-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20-10 20-21.142v-32.571zm49.713 0c0-11.143-8.857-20.857-20.285-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20.285-9.715 20.285-21.142v-32.571zm49.715 0c0-11.143-8.857-20.857-20.286-20.857-11.428 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.858 21.142 20.286 21.142 11.429 0 20.286-10 20.286-21.142v-32.571zM421.714 286c-30.857 59.142-90.285 102.572-158.571 102.572-96.571 0-160.571-84.572-160.571-176.572 0-16.857 2-33.429 6-49.714-20 33.715-29.714 72.572-29.714 111.429 0 60.286 24.857 121.715 71.429 160.857 5.143-9.714 14.857-16.286 26-16.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.571-14.286 24.858-14.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.857-14.286 24.858-14.286 10 0 19.428 5.714 24.857 14.286 5.143-8.571 14.571-14.286 24.572-14.286 10.857 0 20.857 6.572 25.714 16 43.427-36.286 68.569-92 71.426-148.286zm10.572-99.714c0-53.714-34.571-105.714-92.572-105.714-30.285 0-58.571 15.143-78.857 36.857C240.862 183.812 233.41 254 302.286 254c28.805 0 97.357-28.538 84.286 36.857 28.857-26 45.714-65.714 45.714-104.571z\"],\n    \"think-peaks\": [576, 512, [], \"f731\", \"M465.4 409.4l87.1-150.2-32-.3-55.1 95L259.2 0 23 407.4l32 .3L259.2 55.6zm-355.3-44.1h32.1l117.4-202.5L463 511.9l32.5.1-235.8-404.6z\"],\n    \"trade-federation\": [496, 512, [], \"f513\", \"M248 8.8c-137 0-248 111-248 248s111 248 248 248 248-111 248-248-111-248-248-248zm0 482.8c-129.7 0-234.8-105.1-234.8-234.8S118.3 22 248 22s234.8 105.1 234.8 234.8S377.7 491.6 248 491.6zm155.1-328.5v-46.8H209.3V198H54.2l36.7 46h117.7v196.8h48.8V245h83.3v-47h-83.3v-34.8h145.7zm-73.3 45.1v23.9h-82.9v197.4h-26.8V232.1H96.3l-20.1-23.9h143.9v-80.6h171.8V152h-145v56.2zm-161.3-69l-12.4-20.7 2.1 23.8-23.5 5.4 23.3 5.4-2.1 24 12.3-20.5 22.2 9.5-15.7-18.1 15.8-18.1zm-29.6-19.7l9.3-11.5-12.7 5.9-8-12.4 1.7 13.9-14.3 3.8 13.7 2.7-.8 14.7 6.8-12.2 13.8 5.3zm165.4 145.2l-13.1 5.6-7.3-12.2 1.3 14.2-13.9 3.2 13.9 3.2-1.2 14.2 7.3-12.2 13.1 5.5-9.4-10.7zm106.9-77.2l-20.9 9.1-12-19.6 2.2 22.7-22.3 5.4 22.2 4.9-1.8 22.9 11.5-19.6 21.2 8.8-15.1-17zM248 29.9c-125.3 0-226.9 101.6-226.9 226.9S122.7 483.7 248 483.7s226.9-101.6 226.9-226.9S373.3 29.9 248 29.9zM342.6 196v51h-83.3v195.7h-52.7V245.9H89.9l-40-49.9h157.4v-81.6h197.8v50.7H259.4V196zM248 43.2c60.3 0 114.8 25 153.6 65.2H202.5V190H45.1C73.1 104.8 153.4 43.2 248 43.2zm0 427.1c-117.9 0-213.6-95.6-213.6-213.5 0-21.2 3.1-41.8 8.9-61.1L87.1 252h114.7v196.8h64.6V253h83.3v-62.7h-83.2v-19.2h145.6v-50.8c30.8 37 49.3 84.6 49.3 136.5.1 117.9-95.5 213.5-213.4 213.5zM178.8 275l-11-21.4 1.7 24.5-23.7 3.9 23.8 5.9-3.7 23.8 13-20.9 21.5 10.8-15.8-18.8 16.9-17.1z\"],\n    \"trello\": [448, 512, [], \"f181\", \"M392.3 32H56.1C25.1 32 0 57.1 0 88c-.1 0 0-4 0 336 0 30.9 25.1 56 56 56h336.2c30.8-.2 55.7-25.2 55.7-56V88c.1-30.8-24.8-55.8-55.6-56zM197 371.3c-.2 14.7-12.1 26.6-26.9 26.6H87.4c-14.8.1-26.9-11.8-27-26.6V117.1c0-14.8 12-26.9 26.9-26.9h82.9c14.8 0 26.9 12 26.9 26.9v254.2zm193.1-112c0 14.8-12 26.9-26.9 26.9h-81c-14.8 0-26.9-12-26.9-26.9V117.2c0-14.8 12-26.9 26.8-26.9h81.1c14.8 0 26.9 12 26.9 26.9v142.1z\"],\n    \"tripadvisor\": [576, 512, [], \"f262\", \"M166.4 280.521c0 13.236-10.73 23.966-23.966 23.966s-23.966-10.73-23.966-23.966 10.73-23.966 23.966-23.966 23.966 10.729 23.966 23.966zm264.962-23.956c-13.23 0-23.956 10.725-23.956 23.956 0 13.23 10.725 23.956 23.956 23.956 13.23 0 23.956-10.725 23.956-23.956-.001-13.231-10.726-23.956-23.956-23.956zm89.388 139.49c-62.667 49.104-153.276 38.109-202.379-24.559l-30.979 46.325-30.683-45.939c-48.277 60.39-135.622 71.891-197.885 26.055-64.058-47.158-77.759-137.316-30.601-201.374A186.762 186.762 0 0 0 0 139.416l90.286-.05a358.48 358.48 0 0 1 197.065-54.03 350.382 350.382 0 0 1 192.181 53.349l96.218.074a185.713 185.713 0 0 0-28.352 57.649c46.793 62.747 34.964 151.37-26.648 199.647zM259.366 281.761c-.007-63.557-51.535-115.075-115.092-115.068C80.717 166.7 29.2 218.228 29.206 281.785c.007 63.557 51.535 115.075 115.092 115.068 63.513-.075 114.984-51.539 115.068-115.052v-.04zm28.591-10.455c5.433-73.44 65.51-130.884 139.12-133.022a339.146 339.146 0 0 0-139.727-27.812 356.31 356.31 0 0 0-140.164 27.253c74.344 1.582 135.299 59.424 140.771 133.581zm251.706-28.767c-21.992-59.634-88.162-90.148-147.795-68.157-59.634 21.992-90.148 88.162-68.157 147.795v.032c22.038 59.607 88.198 90.091 147.827 68.113 59.615-22.004 90.113-88.162 68.125-147.783zm-326.039 37.975v.115c-.057 39.328-31.986 71.163-71.314 71.106-39.328-.057-71.163-31.986-71.106-71.314.057-39.328 31.986-71.163 71.314-71.106 39.259.116 71.042 31.94 71.106 71.199zm-24.512 0v-.084c-.051-25.784-20.994-46.645-46.778-46.594-25.784.051-46.645 20.994-46.594 46.777.051 25.784 20.994 46.645 46.777 46.594 25.726-.113 46.537-20.968 46.595-46.693zm313.423 0v.048c-.02 39.328-31.918 71.194-71.247 71.173s-71.194-31.918-71.173-71.247c.02-39.328 31.918-71.194 71.247-71.173 39.29.066 71.121 31.909 71.173 71.199zm-24.504-.008c-.009-25.784-20.918-46.679-46.702-46.67-25.784.009-46.679 20.918-46.67 46.702.009 25.784 20.918 46.678 46.702 46.67 25.765-.046 46.636-20.928 46.67-46.693v-.009z\"],\n    \"tumblr\": [320, 512, [], \"f173\", \"M309.8 480.3c-13.6 14.5-50 31.7-97.4 31.7-120.8 0-147-88.8-147-140.6v-144H17.9c-5.5 0-10-4.5-10-10v-68c0-7.2 4.5-13.6 11.3-16 62-21.8 81.5-76 84.3-117.1.8-11 6.5-16.3 16.1-16.3h70.9c5.5 0 10 4.5 10 10v115.2h83c5.5 0 10 4.4 10 9.9v81.7c0 5.5-4.5 10-10 10h-83.4V360c0 34.2 23.7 53.6 68 35.8 4.8-1.9 9-3.2 12.7-2.2 3.5.9 5.8 3.4 7.4 7.9l22 64.3c1.8 5 3.3 10.6-.4 14.5z\"],\n    \"tumblr-square\": [448, 512, [], \"f174\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-82.3 364.2c-8.5 9.1-31.2 19.8-60.9 19.8-75.5 0-91.9-55.5-91.9-87.9v-90h-29.7c-3.4 0-6.2-2.8-6.2-6.2v-42.5c0-4.5 2.8-8.5 7.1-10 38.8-13.7 50.9-47.5 52.7-73.2.5-6.9 4.1-10.2 10-10.2h44.3c3.4 0 6.2 2.8 6.2 6.2v72h51.9c3.4 0 6.2 2.8 6.2 6.2v51.1c0 3.4-2.8 6.2-6.2 6.2h-52.1V321c0 21.4 14.8 33.5 42.5 22.4 3-1.2 5.6-2 8-1.4 2.2.5 3.6 2.1 4.6 4.9l13.8 40.2c1 3.2 2 6.7-.3 9.1z\"],\n    \"twitch\": [448, 512, [], \"f1e8\", \"M40.1 32L10 108.9v314.3h107V480h60.2l56.8-56.8h87l117-117V32H40.1zm357.8 254.1L331 353H224l-56.8 56.8V353H76.9V72.1h321v214zM331 149v116.9h-40.1V149H331zm-107 0v116.9h-40.1V149H224z\"],\n    \"twitter\": [512, 512, [], \"f099\", \"M459.37 151.716c.325 4.548.325 9.097.325 13.645 0 138.72-105.583 298.558-298.558 298.558-59.452 0-114.68-17.219-161.137-47.106 8.447.974 16.568 1.299 25.34 1.299 49.055 0 94.213-16.568 130.274-44.832-46.132-.975-84.792-31.188-98.112-72.772 6.498.974 12.995 1.624 19.818 1.624 9.421 0 18.843-1.3 27.614-3.573-48.081-9.747-84.143-51.98-84.143-102.985v-1.299c13.969 7.797 30.214 12.67 47.431 13.319-28.264-18.843-46.781-51.005-46.781-87.391 0-19.492 5.197-37.36 14.294-52.954 51.655 63.675 129.3 105.258 216.365 109.807-1.624-7.797-2.599-15.918-2.599-24.04 0-57.828 46.782-104.934 104.934-104.934 30.213 0 57.502 12.67 76.67 33.137 23.715-4.548 46.456-13.32 66.599-25.34-7.798 24.366-24.366 44.833-46.132 57.827 21.117-2.273 41.584-8.122 60.426-16.243-14.292 20.791-32.161 39.308-52.628 54.253z\"],\n    \"twitter-square\": [448, 512, [], \"f081\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-48.9 158.8c.2 2.8.2 5.7.2 8.5 0 86.7-66 186.6-186.6 186.6-37.2 0-71.7-10.8-100.7-29.4 5.3.6 10.4.8 15.8.8 30.7 0 58.9-10.4 81.4-28-28.8-.6-53-19.5-61.3-45.5 10.1 1.5 19.2 1.5 29.6-1.2-30-6.1-52.5-32.5-52.5-64.4v-.8c8.7 4.9 18.9 7.9 29.6 8.3a65.447 65.447 0 0 1-29.2-54.6c0-12.2 3.2-23.4 8.9-33.1 32.3 39.8 80.8 65.8 135.2 68.6-9.3-44.5 24-80.6 64-80.6 18.9 0 35.9 7.9 47.9 20.7 14.8-2.8 29-8.3 41.6-15.8-4.9 15.2-15.2 28-28.8 36.1 13.2-1.4 26-5.1 37.8-10.2-8.9 13.1-20.1 24.7-32.9 34z\"],\n    \"typo3\": [448, 512, [], \"f42b\", \"M178.7 78.4c0-24.7 5.4-32.4 13.9-39.4-69.5 8.5-149.3 34-176.3 66.4-5.4 7.7-9.3 20.8-9.3 37.1C7 246 113.8 480 191.1 480c36.3 0 97.3-59.5 146.7-139-7 2.3-11.6 2.3-18.5 2.3-57.2 0-140.6-198.5-140.6-264.9zM301.5 32c-30.1 0-41.7 5.4-41.7 36.3 0 66.4 53.8 198.5 101.7 198.5 26.3 0 78.8-99.7 78.8-182.3 0-40.9-67-52.5-138.8-52.5z\"],\n    \"uber\": [448, 512, [], \"f402\", \"M414.1 32H33.9C15.2 32 0 47.2 0 65.9V446c0 18.8 15.2 34 33.9 34H414c18.7 0 33.9-15.2 33.9-33.9V65.9C448 47.2 432.8 32 414.1 32zM237.6 391.1C163 398.6 96.4 344.2 88.9 269.6h94.4V290c0 3.7 3 6.8 6.8 6.8H258c3.7 0 6.8-3 6.8-6.8v-67.9c0-3.7-3-6.8-6.8-6.8h-67.9c-3.7 0-6.8 3-6.8 6.8v20.4H88.9c7-69.4 65.4-122.2 135.1-122.2 69.7 0 128.1 52.8 135.1 122.2 7.5 74.5-46.9 141.1-121.5 148.6z\"],\n    \"ubuntu\": [496, 512, [], \"f7df\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm52.7 93c8.8-15.2 28.3-20.5 43.5-11.7 15.3 8.8 20.5 28.3 11.7 43.6-8.8 15.2-28.3 20.5-43.5 11.7-15.3-8.9-20.5-28.4-11.7-43.6zM87.4 287.9c-17.6 0-31.9-14.3-31.9-31.9 0-17.6 14.3-31.9 31.9-31.9 17.6 0 31.9 14.3 31.9 31.9 0 17.6-14.3 31.9-31.9 31.9zm28.1 3.1c22.3-17.9 22.4-51.9 0-69.9 8.6-32.8 29.1-60.7 56.5-79.1l23.7 39.6c-51.5 36.3-51.5 112.5 0 148.8L172 370c-27.4-18.3-47.8-46.3-56.5-79zm228.7 131.7c-15.3 8.8-34.7 3.6-43.5-11.7-8.8-15.3-3.6-34.8 11.7-43.6 15.2-8.8 34.7-3.6 43.5 11.7 8.8 15.3 3.6 34.8-11.7 43.6zm.3-69.5c-26.7-10.3-56.1 6.6-60.5 35-5.2 1.4-48.9 14.3-96.7-9.4l22.5-40.3c57 26.5 123.4-11.7 128.9-74.4l46.1.7c-2.3 34.5-17.3 65.5-40.3 88.4zm-5.9-105.3c-5.4-62-71.3-101.2-128.9-74.4l-22.5-40.3c47.9-23.7 91.5-10.8 96.7-9.4 4.4 28.3 33.8 45.3 60.5 35 23.1 22.9 38 53.9 40.2 88.5l-46 .6z\"],\n    \"uikit\": [448, 512, [], \"f403\", \"M443.9 128v256L218 512 0 384V169.7l87.6 45.1v117l133.5 75.5 135.8-75.5v-151l-101.1-57.6 87.6-53.1L443.9 128zM308.6 49.1L223.8 0l-88.6 54.8 86 47.3 87.4-53z\"],\n    \"uniregistry\": [384, 512, [], \"f404\", \"M192 480c39.5 0 76.2-11.8 106.8-32.2H85.3C115.8 468.2 152.5 480 192 480zm-89.1-193.1v-12.4H0v12.4c0 2.5 0 5 .1 7.4h103.1c-.2-2.4-.3-4.9-.3-7.4zm20.5 57H8.5c2.6 8.5 5.8 16.8 9.6 24.8h138.3c-12.9-5.7-24.1-14.2-33-24.8zm-17.7-34.7H1.3c.9 7.6 2.2 15 3.9 22.3h109.7c-4-6.9-7.2-14.4-9.2-22.3zm-2.8-69.3H0v17.3h102.9zm0-173.2H0v4.9h102.9zm0-34.7H0v2.5h102.9zm0 69.3H0v7.4h102.9zm0 104H0v14.8h102.9zm0-69.3H0v9.9h102.9zm0 34.6H0V183h102.9zm166.2 160.9h109.7c1.8-7.3 3.1-14.7 3.9-22.3H278.3c-2.1 7.9-5.2 15.4-9.2 22.3zm12-185.7H384V136H281.1zm0 37.2H384v-12.4H281.1zm0-74.3H384v-7.4H281.1zm0-76.7v2.5H384V32zm-203 410.9h227.7c11.8-8.7 22.7-18.6 32.2-29.7H44.9c9.6 11 21.4 21 33.2 29.7zm203-371.3H384v-4.9H281.1zm0 148.5H384v-14.8H281.1zM38.8 405.7h305.3c6.7-8.5 12.6-17.6 17.8-27.2H23c5.2 9.6 9.2 18.7 15.8 27.2zm188.8-37.1H367c3.7-8 5.8-16.2 8.5-24.8h-115c-8.8 10.7-20.1 19.2-32.9 24.8zm53.5-81.7c0 2.5-.1 5-.4 7.4h103.1c.1-2.5.2-4.9.2-7.4v-12.4H281.1zm0-29.7H384v-17.3H281.1z\"],\n    \"untappd\": [640, 512, [], \"f405\", \"M401.3 49.9c-79.8 160.1-84.6 152.5-87.9 173.2l-5.2 32.8c-1.9 12-6.6 23.5-13.7 33.4L145.6 497.1c-7.6 10.6-20.4 16.2-33.4 14.6-40.3-5-77.8-32.2-95.3-68.5-5.7-11.8-4.5-25.8 3.1-36.4l148.9-207.9c7.1-9.9 16.4-18 27.2-23.7l29.3-15.5c18.5-9.8 9.7-11.9 135.6-138.9 1-4.8 1-7.3 3.6-8 3-.7 6.6-1 6.3-4.6l-.4-4.6c-.2-1.9 1.3-3.6 3.2-3.6 4.5-.1 13.2 1.2 25.6 10 12.3 8.9 16.4 16.8 17.7 21.1.6 1.8-.6 3.7-2.4 4.2l-4.5 1.1c-3.4.9-2.5 4.4-2.3 7.4.1 2.8-2.3 3.6-6.5 6.1zM230.1 36.4c3.4.9 2.5 4.4 2.3 7.4-.2 2.7 2.1 3.5 6.4 6 7.9 15.9 15.3 30.5 22.2 44 .7 1.3 2.3 1.5 3.3.5 11.2-12 24.6-26.2 40.5-42.6 1.3-1.4 1.4-3.5.1-4.9-8-8.2-16.5-16.9-25.6-26.1-1-4.7-1-7.3-3.6-8-3-.8-6.6-1-6.3-4.6.3-3.3 1.4-8.1-2.8-8.2-4.5-.1-13.2 1.1-25.6 10-12.3 8.9-16.4 16.8-17.7 21.1-1.4 4.2 3.6 4.6 6.8 5.4zM620 406.7L471.2 198.8c-13.2-18.5-26.6-23.4-56.4-39.1-11.2-5.9-14.2-10.9-30.5-28.9-1-1.1-2.9-.9-3.6.5-46.3 88.8-47.1 82.8-49 94.8-1.7 10.7-1.3 20 .3 29.8 1.9 12 6.6 23.5 13.7 33.4l148.9 207.9c7.6 10.6 20.2 16.2 33.1 14.7 40.3-4.9 78-32 95.7-68.6 5.4-11.9 4.3-25.9-3.4-36.6z\"],\n    \"ups\": [384, 512, [], \"f7e0\", \"M103.2 303c-5.2 3.6-32.6 13.1-32.6-19V180H37.9v102.6c0 74.9 80.2 51.1 97.9 39V180h-32.6zM4 74.82v220.9c0 103.7 74.9 135.2 187.7 184.1 112.4-48.9 187.7-80.2 187.7-184.1V74.82c-116.3-61.6-281.8-49.6-375.4 0zm358.1 220.9c0 86.6-53.2 113.6-170.4 165.3-117.5-51.8-170.5-78.7-170.5-165.3v-126.4c102.3-93.8 231.6-100 340.9-89.8zm-209.6-107.4v212.8h32.7v-68.7c24.4 7.3 71.7-2.6 71.7-78.5 0-97.4-80.7-80.92-104.4-65.6zm32.7 117.3v-100.3c8.4-4.2 38.4-12.7 38.4 49.3 0 67.9-36.4 51.8-38.4 51zm79.1-86.4c.1 47.3 51.6 42.5 52.2 70.4.6 23.5-30.4 23-50.8 4.9v30.1c36.2 21.5 81.9 8.1 83.2-33.5 1.7-51.5-54.1-46.6-53.4-73.2.6-20.3 30.6-20.5 48.5-2.2v-28.4c-28.5-22-79.9-9.2-79.7 31.9z\"],\n    \"usb\": [640, 512, [], \"f287\", \"M641.5 256c0 3.1-1.7 6.1-4.5 7.5L547.9 317c-1.4.8-2.8 1.4-4.5 1.4-1.4 0-3.1-.3-4.5-1.1-2.8-1.7-4.5-4.5-4.5-7.8v-35.6H295.7c25.3 39.6 40.5 106.9 69.6 106.9H392V354c0-5 3.9-8.9 8.9-8.9H490c5 0 8.9 3.9 8.9 8.9v89.1c0 5-3.9 8.9-8.9 8.9h-89.1c-5 0-8.9-3.9-8.9-8.9v-26.7h-26.7c-75.4 0-81.1-142.5-124.7-142.5H140.3c-8.1 30.6-35.9 53.5-69 53.5C32 327.3 0 295.3 0 256s32-71.3 71.3-71.3c33.1 0 61 22.8 69 53.5 39.1 0 43.9 9.5 74.6-60.4C255 88.7 273 95.7 323.8 95.7c7.5-20.9 27-35.6 50.4-35.6 29.5 0 53.5 23.9 53.5 53.5s-23.9 53.5-53.5 53.5c-23.4 0-42.9-14.8-50.4-35.6H294c-29.1 0-44.3 67.4-69.6 106.9h310.1v-35.6c0-3.3 1.7-6.1 4.5-7.8 2.8-1.7 6.4-1.4 8.9.3l89.1 53.5c2.8 1.1 4.5 4.1 4.5 7.2z\"],\n    \"usps\": [576, 512, [], \"f7e1\", \"M460.3 241.7c25.8-41.3 15.2-48.8-11.7-48.8h-27c-.1 0-1.5-1.4-10.9 8-11.2 5.6-37.9 6.3-37.9 8.7 0 4.5 70.3-3.1 88.1 0 9.5 1.5-1.5 20.4-4.4 32-.5 4.5 2.4 2.3 3.8.1zm-112.1 22.6c64-21.3 97.3-23.9 102-26.2 4.4-2.9-4.4-6.6-26.2-5.8-51.7 2.2-137.6 37.1-172.6 53.9l-30.7-93.3h196.6c-2.7-28.2-152.9-22.6-337.9-22.6L27 415.8c196.4-97.3 258.9-130.3 321.2-151.5zM94.7 96c253.3 53.7 330 65.7 332.1 85.2 36.4 0 45.9 0 52.4 6.6 21.1 19.7-14.6 67.7-14.6 67.7-4.4 2.9-406.4 160.2-406.4 160.2h423.1L549 96z\"],\n    \"ussunnah\": [512, 512, [], \"f407\", \"M156.8 285.1l5.7 14.4h-8.2c-1.3-3.2-3.1-7.7-3.8-9.5-2.5-6.3-1.1-8.4 0-10 1.9-2.7 3.2-4.4 3.6-5.2 0 2.2.8 5.7 2.7 10.3zm297.3 18.8c-2.1 13.8-5.7 27.1-10.5 39.7l43 23.4-44.8-18.8c-5.3 13.2-12 25.6-19.9 37.2l34.2 30.2-36.8-26.4c-8.4 11.8-18 22.6-28.7 32.3l24.9 34.7-28.1-31.8c-11 9.6-23.1 18-36.1 25.1l15.7 37.2-19.3-35.3c-13.1 6.8-27 12.1-41.6 15.9l6.7 38.4-10.5-37.4c-14.3 3.4-29.2 5.3-44.5 5.4L256 512l-1.9-38.4c-15.3-.1-30.2-2-44.5-5.3L199 505.6l6.7-38.2c-14.6-3.7-28.6-9.1-41.7-15.8l-19.2 35.1 15.6-37c-13-7-25.2-15.4-36.2-25.1l-27.9 31.6 24.7-34.4c-10.7-9.7-20.4-20.5-28.8-32.3l-36.5 26.2 33.9-29.9c-7.9-11.6-14.6-24.1-20-37.3l-44.4 18.7L67.8 344c-4.8-12.7-8.4-26.1-10.5-39.9l-51 9 50.3-14.2c-1.1-8.5-1.7-17.1-1.7-25.9 0-4.7.2-9.4.5-14.1L0 256l56-2.8c1.3-13.1 3.8-25.8 7.5-38.1L6.4 199l58.9 10.4c4-12 9.1-23.5 15.2-34.4l-55.1-30 58.3 24.6C90 159 97.2 149.2 105.3 140L55.8 96.4l53.9 38.7c8.1-8.6 17-16.5 26.6-23.6l-40-55.6 45.6 51.6c9.5-6.6 19.7-12.3 30.3-17.2l-27.3-64.9 33.8 62.1c10.5-4.4 21.4-7.9 32.7-10.4L199 6.4l19.5 69.2c11-2.1 22.3-3.2 33.8-3.4L256 0l3.6 72.2c11.5.2 22.8 1.4 33.8 3.5L313 6.4l-12.4 70.7c11.3 2.6 22.2 6.1 32.6 10.5l33.9-62.2-27.4 65.1c10.6 4.9 20.7 10.7 30.2 17.2l45.8-51.8-40.1 55.9c9.5 7.1 18.4 15 26.5 23.6l54.2-38.9-49.7 43.9c8 9.1 15.2 18.9 21.5 29.4l58.7-24.7-55.5 30.2c6.1 10.9 11.1 22.3 15.1 34.3l59.3-10.4-57.5 16.2c3.7 12.2 6.2 24.9 7.5 37.9L512 256l-56 2.8c.3 4.6.5 9.3.5 14.1 0 8.7-.6 17.3-1.6 25.8l50.7 14.3-51.5-9.1zm-21.8-31c0-97.5-79-176.5-176.5-176.5s-176.5 79-176.5 176.5 79 176.5 176.5 176.5 176.5-79 176.5-176.5zm-24 0c0 84.3-68.3 152.6-152.6 152.6s-152.6-68.3-152.6-152.6 68.3-152.6 152.6-152.6 152.6 68.3 152.6 152.6zM195 241c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-40.7-19c0 2.1 1.3 3.8 3.6 5.1 3.5 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-19 0c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.4 6.8-9.6 10.9-9.6 12.6zm204.9 87.9c-8.4-3-8.7-6.8-8.7-15.6V182c-8.2 12.5-14.2 18.6-18 18.6 6.3 14.4 9.5 23.9 9.5 28.3v64.3c0 2.2-2.2 6.5-4.7 6.5h-18c-2.8-7.5-10.2-26.9-15.3-40.3-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3 2.6 6.7 6.4 16.5 7.9 20.2h-9.2c-3.9-10.4-9.6-25.4-11.8-31.1-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3.8 2 2.8 7.3 4.3 10.9H256c-1.5-4.1-5.6-14.6-8.4-22-2 2.5-7.2 9.2-10.7 13.7 2.5 1.6 4.3 3.6 5.2 6.3.2.6.5 1.4.6 1.7H225c-4.6-13.9-11.4-27.7-11.4-34.1 0-2.2.3-5.1 1.1-8.2-8.8 10.8-14 15.9-14 25 0 7.5 10.4 28.3 10.4 33.3 0 1.7-.5 3.3-1.4 4.9-9.6-12.7-15.5-20.7-18.8-20.7h-12l-11.2-28c-3.8-9.6-5.7-16-5.7-18.8 0-3.8.5-7.7 1.7-12.2-1 1.3-3.7 4.7-5.5 7.1-.8-2.1-3.1-7.7-4.6-11.5-2.1 2.5-7.5 9.1-11.2 13.6.9 2.3 3.3 8.1 4.9 12.2-2.5 3.3-9.1 11.8-13.6 17.7-4 5.3-5.8 13.3-2.7 21.8 2.5 6.7 2 7.9-1.7 14.1H191c5.5 0 14.3 14 15.5 22 13.2-16 15.4-19.6 16.8-21.6h107c3.9 0 7.2-1.9 9.9-5.8zm20.1-26.6V181.7c-9 12.5-15.9 18.6-20.7 18.6 7.1 14.4 10.7 23.9 10.7 28.3v66.3c0 17.5 8.6 20.4 24 20.4 8.1 0 12.5-.8 13.7-2.7-4.3-1.6-7.6-2.5-9.9-3.3-8.1-3.2-17.8-7.4-17.8-26z\"],\n    \"vaadin\": [448, 512, [], \"f408\", \"M224.5 140.7c1.5-17.6 4.9-52.7 49.8-52.7h98.6c20.7 0 32.1-7.8 32.1-21.6V54.1c0-12.2 9.3-22.1 21.5-22.1S448 41.9 448 54.1v36.5c0 42.9-21.5 62-66.8 62H280.7c-30.1 0-33 14.7-33 27.1 0 1.3-.1 2.5-.2 3.7-.7 12.3-10.9 22.2-23.4 22.2s-22.7-9.8-23.4-22.2c-.1-1.2-.2-2.4-.2-3.7 0-12.3-3-27.1-33-27.1H66.8c-45.3 0-66.8-19.1-66.8-62V54.1C0 41.9 9.4 32 21.6 32s21.5 9.9 21.5 22.1v12.3C43.1 80.2 54.5 88 75.2 88h98.6c44.8 0 48.3 35.1 49.8 52.7h.9zM224 456c11.5 0 21.4-7 25.7-16.3 1.1-1.8 97.1-169.6 98.2-171.4 11.9-19.6-3.2-44.3-27.2-44.3-13.9 0-23.3 6.4-29.8 20.3L224 362l-66.9-117.7c-6.4-13.9-15.9-20.3-29.8-20.3-24 0-39.1 24.6-27.2 44.3 1.1 1.9 97.1 169.6 98.2 171.4 4.3 9.3 14.2 16.3 25.7 16.3z\"],\n    \"viacoin\": [384, 512, [], \"f237\", \"M384 32h-64l-80.7 192h-94.5L64 32H0l48 112H0v48h68.5l13.8 32H0v48h102.8L192 480l89.2-208H384v-48h-82.3l13.8-32H384v-48h-48l48-112zM192 336l-27-64h54l-27 64z\"],\n    \"viadeo\": [448, 512, [], \"f2a9\", \"M276.2 150.5v.7C258.3 98.6 233.6 47.8 205.4 0c43.3 29.2 67 100 70.8 150.5zm32.7 121.7c7.6 18.2 11 37.5 11 57 0 77.7-57.8 141-137.8 139.4l3.8-.3c74.2-46.7 109.3-118.6 109.3-205.1 0-38.1-6.5-75.9-18.9-112 1 11.7 1 23.7 1 35.4 0 91.8-18.1 241.6-116.6 280C95 455.2 49.4 398 49.4 329.2c0-75.6 57.4-142.3 135.4-142.3 16.8 0 33.7 3.1 49.1 9.6 1.7-15.1 6.5-29.9 13.4-43.3-19.9-7.2-41.2-10.7-62.5-10.7-161.5 0-238.7 195.9-129.9 313.7 67.9 74.6 192 73.9 259.8 0 56.6-61.3 60.9-142.4 36.4-201-12.7 8-27.1 13.9-42.2 17zM418.1 11.7c-31 66.5-81.3 47.2-115.8 80.1-12.4 12-20.6 34-20.6 50.5 0 14.1 4.5 27.1 12 38.8 47.4-11 98.3-46 118.2-90.7-.7 5.5-4.8 14.4-7.2 19.2-20.3 35.7-64.6 65.6-99.7 84.9 14.8 14.4 33.7 25.8 55 25.8 79 0 110.1-134.6 58.1-208.6z\"],\n    \"viadeo-square\": [448, 512, [], \"f2aa\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM280.7 381.2c-42.4 46.2-120 46.6-162.4 0-68-73.6-19.8-196.1 81.2-196.1 13.3 0 26.6 2.1 39.1 6.7-4.3 8.4-7.3 17.6-8.4 27.1-9.7-4.1-20.2-6-30.7-6-48.8 0-84.6 41.7-84.6 88.9 0 43 28.5 78.7 69.5 85.9 61.5-24 72.9-117.6 72.9-175 0-7.3 0-14.8-.6-22.1-11.2-32.9-26.6-64.6-44.2-94.5 27.1 18.3 41.9 62.5 44.2 94.1v.4c7.7 22.5 11.8 46.2 11.8 70 0 54.1-21.9 99-68.3 128.2l-2.4.2c50 1 86.2-38.6 86.2-87.2 0-12.2-2.1-24.3-6.9-35.7 9.5-1.9 18.5-5.6 26.4-10.5 15.3 36.6 12.6 87.3-22.8 125.6zM309 233.7c-13.3 0-25.1-7.1-34.4-16.1 21.9-12 49.6-30.7 62.3-53 1.5-3 4.1-8.6 4.5-12-12.5 27.9-44.2 49.8-73.9 56.7-4.7-7.3-7.5-15.5-7.5-24.3 0-10.3 5.2-24.1 12.9-31.6 21.6-20.5 53-8.5 72.4-50 32.5 46.2 13.1 130.3-36.3 130.3z\"],\n    \"viber\": [512, 512, [], \"f409\", \"M444 49.9C431.3 38.2 379.9.9 265.3.4c0 0-135.1-8.1-200.9 52.3C27.8 89.3 14.9 143 13.5 209.5c-1.4 66.5-3.1 191.1 117 224.9h.1l-.1 51.6s-.8 20.9 13 25.1c16.6 5.2 26.4-10.7 42.3-27.8 8.7-9.4 20.7-23.2 29.8-33.7 82.2 6.9 145.3-8.9 152.5-11.2 16.6-5.4 110.5-17.4 125.7-142 15.8-128.6-7.6-209.8-49.8-246.5zM457.9 287c-12.9 104-89 110.6-103 115.1-6 1.9-61.5 15.7-131.2 11.2 0 0-52 62.7-68.2 79-5.3 5.3-11.1 4.8-11-5.7 0-6.9.4-85.7.4-85.7-.1 0-.1 0 0 0-101.8-28.2-95.8-134.3-94.7-189.8 1.1-55.5 11.6-101 42.6-131.6 55.7-50.5 170.4-43 170.4-43 96.9.4 143.3 29.6 154.1 39.4 35.7 30.6 53.9 103.8 40.6 211.1zm-139-80.8c.4 8.6-12.5 9.2-12.9.6-1.1-22-11.4-32.7-32.6-33.9-8.6-.5-7.8-13.4.7-12.9 27.9 1.5 43.4 17.5 44.8 46.2zm20.3 11.3c1-42.4-25.5-75.6-75.8-79.3-8.5-.6-7.6-13.5.9-12.9 58 4.2 88.9 44.1 87.8 92.5-.1 8.6-13.1 8.2-12.9-.3zm47 13.4c.1 8.6-12.9 8.7-12.9.1-.6-81.5-54.9-125.9-120.8-126.4-8.5-.1-8.5-12.9 0-12.9 73.7.5 133 51.4 133.7 139.2zM374.9 329v.2c-10.8 19-31 40-51.8 33.3l-.2-.3c-21.1-5.9-70.8-31.5-102.2-56.5-16.2-12.8-31-27.9-42.4-42.4-10.3-12.9-20.7-28.2-30.8-46.6-21.3-38.5-26-55.7-26-55.7-6.7-20.8 14.2-41 33.3-51.8h.2c9.2-4.8 18-3.2 23.9 3.9 0 0 12.4 14.8 17.7 22.1 5 6.8 11.7 17.7 15.2 23.8 6.1 10.9 2.3 22-3.7 26.6l-12 9.6c-6.1 4.9-5.3 14-5.3 14s17.8 67.3 84.3 84.3c0 0 9.1.8 14-5.3l9.6-12c4.6-6 15.7-9.8 26.6-3.7 14.7 8.3 33.4 21.2 45.8 32.9 7 5.7 8.6 14.4 3.8 23.6z\"],\n    \"vimeo\": [448, 512, [], \"f40a\", \"M403.2 32H44.8C20.1 32 0 52.1 0 76.8v358.4C0 459.9 20.1 480 44.8 480h358.4c24.7 0 44.8-20.1 44.8-44.8V76.8c0-24.7-20.1-44.8-44.8-44.8zM377 180.8c-1.4 31.5-23.4 74.7-66 129.4-44 57.2-81.3 85.8-111.7 85.8-18.9 0-34.8-17.4-47.9-52.3-25.5-93.3-36.4-148-57.4-148-2.4 0-10.9 5.1-25.4 15.2l-15.2-19.6c37.3-32.8 72.9-69.2 95.2-71.2 25.2-2.4 40.7 14.8 46.5 51.7 20.7 131.2 29.9 151 67.6 91.6 13.5-21.4 20.8-37.7 21.8-48.9 3.5-33.2-25.9-30.9-45.8-22.4 15.9-52.1 46.3-77.4 91.2-76 33.3.9 49 22.5 47.1 64.7z\"],\n    \"vimeo-square\": [448, 512, [], \"f194\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16.2 149.6c-1.4 31.1-23.2 73.8-65.3 127.9-43.5 56.5-80.3 84.8-110.4 84.8-18.7 0-34.4-17.2-47.3-51.6-25.2-92.3-35.9-146.4-56.7-146.4-2.4 0-10.8 5-25.1 15.1L64 192c36.9-32.4 72.1-68.4 94.1-70.4 24.9-2.4 40.2 14.6 46 51.1 20.5 129.6 29.6 149.2 66.8 90.5 13.4-21.2 20.6-37.2 21.5-48.3 3.4-32.8-25.6-30.6-45.2-22.2 15.7-51.5 45.8-76.5 90.1-75.1 32.9 1 48.4 22.4 46.5 64z\"],\n    \"vimeo-v\": [448, 512, [], \"f27d\", \"M447.8 153.6c-2 43.6-32.4 103.3-91.4 179.1-60.9 79.2-112.4 118.8-154.6 118.8-26.1 0-48.2-24.1-66.3-72.3C100.3 250 85.3 174.3 56.2 174.3c-3.4 0-15.1 7.1-35.2 21.1L0 168.2c51.6-45.3 100.9-95.7 131.8-98.5 34.9-3.4 56.3 20.5 64.4 71.5 28.7 181.5 41.4 208.9 93.6 126.7 18.7-29.6 28.8-52.1 30.2-67.6 4.8-45.9-35.8-42.8-63.3-31 22-72.1 64.1-107.1 126.2-105.1 45.8 1.2 67.5 31.1 64.9 89.4z\"],\n    \"vine\": [384, 512, [], \"f1ca\", \"M384 254.7v52.1c-18.4 4.2-36.9 6.1-52.1 6.1-36.9 77.4-103 143.8-125.1 156.2-14 7.9-27.1 8.4-42.7-.8C137 452 34.2 367.7 0 102.7h74.5C93.2 261.8 139 343.4 189.3 404.5c27.9-27.9 54.8-65.1 75.6-106.9-49.8-25.3-80.1-80.9-80.1-145.6 0-65.6 37.7-115.1 102.2-115.1 114.9 0 106.2 127.9 81.6 181.5 0 0-46.4 9.2-63.5-20.5 3.4-11.3 8.2-30.8 8.2-48.5 0-31.3-11.3-46.6-28.4-46.6-18.2 0-30.8 17.1-30.8 50 .1 79.2 59.4 118.7 129.9 101.9z\"],\n    \"vk\": [576, 512, [], \"f189\", \"M545 117.7c3.7-12.5 0-21.7-17.8-21.7h-58.9c-15 0-21.9 7.9-25.6 16.7 0 0-30 73.1-72.4 120.5-13.7 13.7-20 18.1-27.5 18.1-3.7 0-9.4-4.4-9.4-16.9V117.7c0-15-4.2-21.7-16.6-21.7h-92.6c-9.4 0-15 7-15 13.5 0 14.2 21.2 17.5 23.4 57.5v86.8c0 19-3.4 22.5-10.9 22.5-20 0-68.6-73.4-97.4-157.4-5.8-16.3-11.5-22.9-26.6-22.9H38.8c-16.8 0-20.2 7.9-20.2 16.7 0 15.6 20 93.1 93.1 195.5C160.4 378.1 229 416 291.4 416c37.5 0 42.1-8.4 42.1-22.9 0-66.8-3.4-73.1 15.4-73.1 8.7 0 23.7 4.4 58.7 38.1 40 40 46.6 57.9 69 57.9h58.9c16.8 0 25.3-8.4 20.4-25-11.2-34.9-86.9-106.7-90.3-111.5-8.7-11.2-6.2-16.2 0-26.2.1-.1 72-101.3 79.4-135.6z\"],\n    \"vnv\": [640, 512, [], \"f40b\", \"M104.9 352c-34.1 0-46.4-30.4-46.4-30.4L2.6 210.1S-7.8 192 13 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.7-74.5c5.6-9.5 8.4-18.1 18.8-18.1h32.8c20.8 0 10.4 18.1 10.4 18.1l-55.8 111.5S174.2 352 140 352h-35.1zm395 0c-34.1 0-46.4-30.4-46.4-30.4l-55.9-111.5S387.2 192 408 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.8-74.5c5.6-9.5 8.4-18.1 18.8-18.1H627c20.8 0 10.4 18.1 10.4 18.1l-55.9 111.5S569.3 352 535.1 352h-35.2zM337.6 192c34.1 0 46.4 30.4 46.4 30.4l55.9 111.5s10.4 18.1-10.4 18.1h-32.8c-10.4 0-13.2-8.7-18.8-18.1l-36.7-74.5s-5.2-13.1-21.1-13.1c-15.9 0-21.1 13.1-21.1 13.1l-36.7 74.5c-5.6 9.4-8.4 18.1-18.8 18.1h-32.9c-20.8 0-10.4-18.1-10.4-18.1l55.9-111.5s12.2-30.4 46.4-30.4h35.1z\"],\n    \"vuejs\": [448, 512, [], \"f41f\", \"M356.9 64.3H280l-56 88.6-48-88.6H0L224 448 448 64.3h-91.1zm-301.2 32h53.8L224 294.5 338.4 96.3h53.8L224 384.5 55.7 96.3z\"],\n    \"waze\": [512, 512, [], \"f83f\", \"M502.17 201.67C516.69 287.53 471.23 369.59 389 409.8c13 34.1-12.4 70.2-48.32 70.2a51.68 51.68 0 0 1-51.57-49c-6.44.19-64.2 0-76.33-.64A51.69 51.69 0 0 1 159 479.92c-33.86-1.36-57.95-34.84-47-67.92-37.21-13.11-72.54-34.87-99.62-70.8-13-17.28-.48-41.8 20.84-41.8 46.31 0 32.22-54.17 43.15-110.26C94.8 95.2 193.12 32 288.09 32c102.48 0 197.15 70.67 214.08 169.67zM373.51 388.28c42-19.18 81.33-56.71 96.29-102.14 40.48-123.09-64.15-228-181.71-228-83.45 0-170.32 55.42-186.07 136-9.53 48.91 5 131.35-68.75 131.35C58.21 358.6 91.6 378.11 127 389.54c24.66-21.8 63.87-15.47 79.83 14.34 14.22 1 79.19 1.18 87.9.82a51.69 51.69 0 0 1 78.78-16.42zM205.12 187.13c0-34.74 50.84-34.75 50.84 0s-50.84 34.74-50.84 0zm116.57 0c0-34.74 50.86-34.75 50.86 0s-50.86 34.75-50.86 0zm-122.61 70.69c-3.44-16.94 22.18-22.18 25.62-5.21l.06.28c4.14 21.42 29.85 44 64.12 43.07 35.68-.94 59.25-22.21 64.11-42.77 4.46-16.05 28.6-10.36 25.47 6-5.23 22.18-31.21 62-91.46 62.9-42.55 0-80.88-27.84-87.9-64.25z\"],\n    \"weebly\": [512, 512, [], \"f5cc\", \"M425.09 65.83c-39.88 0-73.28 25.73-83.66 64.33-18.16-58.06-65.5-64.33-84.95-64.33-19.78 0-66.8 6.28-85.28 64.33-10.38-38.6-43.45-64.33-83.66-64.33C38.59 65.83 0 99.72 0 143.03c0 28.96 4.18 33.27 77.17 233.48 22.37 60.57 67.77 69.35 92.74 69.35 39.23 0 70.04-19.46 85.93-53.98 15.89 34.83 46.69 54.29 85.93 54.29 24.97 0 70.36-9.1 92.74-69.67 76.55-208.65 77.5-205.58 77.5-227.2.63-48.32-36.01-83.47-86.92-83.47zm26.34 114.81l-65.57 176.44c-7.92 21.49-21.22 37.22-46.24 37.22-23.44 0-37.38-12.41-44.03-33.9l-39.28-117.42h-.95L216.08 360.4c-6.96 21.5-20.9 33.6-44.02 33.6-25.02 0-38.33-15.74-46.24-37.22L60.88 181.55c-5.38-14.83-7.92-23.91-7.92-34.5 0-16.34 15.84-29.36 38.33-29.36 18.69 0 31.99 11.8 36.11 29.05l44.03 139.82h.95l44.66-136.79c6.02-19.67 16.47-32.08 38.96-32.08s32.94 12.11 38.96 32.08l44.66 136.79h.95l44.03-139.82c4.12-17.25 17.42-29.05 36.11-29.05 22.17 0 38.33 13.32 38.33 35.71-.32 7.87-4.12 16.04-7.61 27.24z\"],\n    \"weibo\": [512, 512, [], \"f18a\", \"M407 177.6c7.6-24-13.4-46.8-37.4-41.7-22 4.8-28.8-28.1-7.1-32.8 50.1-10.9 92.3 37.1 76.5 84.8-6.8 21.2-38.8 10.8-32-10.3zM214.8 446.7C108.5 446.7 0 395.3 0 310.4c0-44.3 28-95.4 76.3-143.7C176 67 279.5 65.8 249.9 161c-4 13.1 12.3 5.7 12.3 6 79.5-33.6 140.5-16.8 114 51.4-3.7 9.4 1.1 10.9 8.3 13.1 135.7 42.3 34.8 215.2-169.7 215.2zm143.7-146.3c-5.4-55.7-78.5-94-163.4-85.7-84.8 8.6-148.8 60.3-143.4 116s78.5 94 163.4 85.7c84.8-8.6 148.8-60.3 143.4-116zM347.9 35.1c-25.9 5.6-16.8 43.7 8.3 38.3 72.3-15.2 134.8 52.8 111.7 124-7.4 24.2 29.1 37 37.4 12 31.9-99.8-55.1-195.9-157.4-174.3zm-78.5 311c-17.1 38.8-66.8 60-109.1 46.3-40.8-13.1-58-53.4-40.3-89.7 17.7-35.4 63.1-55.4 103.4-45.1 42 10.8 63.1 50.2 46 88.5zm-86.3-30c-12.9-5.4-30 .3-38 12.9-8.3 12.9-4.3 28 8.6 34 13.1 6 30.8.3 39.1-12.9 8-13.1 3.7-28.3-9.7-34zm32.6-13.4c-5.1-1.7-11.4.6-14.3 5.4-2.9 5.1-1.4 10.6 3.7 12.9 5.1 2 11.7-.3 14.6-5.4 2.8-5.2 1.1-10.9-4-12.9z\"],\n    \"weixin\": [576, 512, [], \"f1d7\", \"M385.2 167.6c6.4 0 12.6.3 18.8 1.1C387.4 90.3 303.3 32 207.7 32 100.5 32 13 104.8 13 197.4c0 53.4 29.3 97.5 77.9 131.6l-19.3 58.6 68-34.1c24.4 4.8 43.8 9.7 68.2 9.7 6.2 0 12.1-.3 18.3-.8-4-12.9-6.2-26.6-6.2-40.8-.1-84.9 72.9-154 165.3-154zm-104.5-52.9c14.5 0 24.2 9.7 24.2 24.4 0 14.5-9.7 24.2-24.2 24.2-14.8 0-29.3-9.7-29.3-24.2.1-14.7 14.6-24.4 29.3-24.4zm-136.4 48.6c-14.5 0-29.3-9.7-29.3-24.2 0-14.8 14.8-24.4 29.3-24.4 14.8 0 24.4 9.7 24.4 24.4 0 14.6-9.6 24.2-24.4 24.2zM563 319.4c0-77.9-77.9-141.3-165.4-141.3-92.7 0-165.4 63.4-165.4 141.3S305 460.7 397.6 460.7c19.3 0 38.9-5.1 58.6-9.9l53.4 29.3-14.8-48.6C534 402.1 563 363.2 563 319.4zm-219.1-24.5c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.8 0 24.4 9.7 24.4 19.3 0 10-9.7 19.6-24.4 19.6zm107.1 0c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.5 0 24.4 9.7 24.4 19.3.1 10-9.9 19.6-24.4 19.6z\"],\n    \"whatsapp\": [448, 512, [], \"f232\", \"M380.9 97.1C339 55.1 283.2 32 223.9 32c-122.4 0-222 99.6-222 222 0 39.1 10.2 77.3 29.6 111L0 480l117.7-30.9c32.4 17.7 68.9 27 106.1 27h.1c122.3 0 224.1-99.6 224.1-222 0-59.3-25.2-115-67.1-157zm-157 341.6c-33.2 0-65.7-8.9-94-25.7l-6.7-4-69.8 18.3L72 359.2l-4.4-7c-18.5-29.4-28.2-63.3-28.2-98.2 0-101.7 82.8-184.5 184.6-184.5 49.3 0 95.6 19.2 130.4 54.1 34.8 34.9 56.2 81.2 56.1 130.5 0 101.8-84.9 184.6-186.6 184.6zm101.2-138.2c-5.5-2.8-32.8-16.2-37.9-18-5.1-1.9-8.8-2.8-12.5 2.8-3.7 5.6-14.3 18-17.6 21.8-3.2 3.7-6.5 4.2-12 1.4-32.6-16.3-54-29.1-75.5-66-5.7-9.8 5.7-9.1 16.3-30.3 1.8-3.7.9-6.9-.5-9.7-1.4-2.8-12.5-30.1-17.1-41.2-4.5-10.8-9.1-9.3-12.5-9.5-3.2-.2-6.9-.2-10.6-.2-3.7 0-9.7 1.4-14.8 6.9-5.1 5.6-19.4 19-19.4 46.3 0 27.3 19.9 53.7 22.6 57.4 2.8 3.7 39.1 59.7 94.8 83.8 35.2 15.2 49 16.5 66.6 13.9 10.7-1.6 32.8-13.4 37.4-26.4 4.6-13 4.6-24.1 3.2-26.4-1.3-2.5-5-3.9-10.5-6.6z\"],\n    \"whatsapp-square\": [448, 512, [], \"f40c\", \"M224 122.8c-72.7 0-131.8 59.1-131.9 131.8 0 24.9 7 49.2 20.2 70.1l3.1 5-13.3 48.6 49.9-13.1 4.8 2.9c20.2 12 43.4 18.4 67.1 18.4h.1c72.6 0 133.3-59.1 133.3-131.8 0-35.2-15.2-68.3-40.1-93.2-25-25-58-38.7-93.2-38.7zm77.5 188.4c-3.3 9.3-19.1 17.7-26.7 18.8-12.6 1.9-22.4.9-47.5-9.9-39.7-17.2-65.7-57.2-67.7-59.8-2-2.6-16.2-21.5-16.2-41s10.2-29.1 13.9-33.1c3.6-4 7.9-5 10.6-5 2.6 0 5.3 0 7.6.1 2.4.1 5.7-.9 8.9 6.8 3.3 7.9 11.2 27.4 12.2 29.4s1.7 4.3.3 6.9c-7.6 15.2-15.7 14.6-11.6 21.6 15.3 26.3 30.6 35.4 53.9 47.1 4 2 6.3 1.7 8.6-1 2.3-2.6 9.9-11.6 12.5-15.5 2.6-4 5.3-3.3 8.9-2 3.6 1.3 23.1 10.9 27.1 12.9s6.6 3 7.6 4.6c.9 1.9.9 9.9-2.4 19.1zM400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM223.9 413.2c-26.6 0-52.7-6.7-75.8-19.3L64 416l22.5-82.2c-13.9-24-21.2-51.3-21.2-79.3C65.4 167.1 136.5 96 223.9 96c42.4 0 82.2 16.5 112.2 46.5 29.9 30 47.9 69.8 47.9 112.2 0 87.4-72.7 158.5-160.1 158.5z\"],\n    \"whmcs\": [448, 512, [], \"f40d\", \"M448 161v-21.3l-28.5-8.8-2.2-10.4 20.1-20.7L427 80.4l-29 7.5-7.2-7.5 7.5-28.2-19.1-11.6-21.3 21-10.7-3.2-7-26.4h-22.6l-6.2 26.4-12.1 3.2-19.7-21-19.4 11 8.1 27.7-8.1 8.4-28.5-7.5-11 19.1 20.7 21-2.9 10.4-28.5 7.8-.3 21.7 28.8 7.5 2.4 12.1-20.1 19.9 10.4 18.5 29.6-7.5 7.2 8.6-8.1 26.9 19.9 11.6 19.4-20.4 11.6 2.9 6.7 28.5 22.6.3 6.7-28.8 11.6-3.5 20.7 21.6 20.4-12.1-8.8-28 7.8-8.1 28.8 8.8 10.3-20.1-20.9-18.8 2.2-12.1 29.1-7zm-119.2 45.2c-31.3 0-56.8-25.4-56.8-56.8s25.4-56.8 56.8-56.8 56.8 25.4 56.8 56.8c0 31.5-25.4 56.8-56.8 56.8zm72.3 16.4l46.9 14.5V277l-55.1 13.4-4.1 22.7 38.9 35.3-19.2 37.9-54-16.7-14.6 15.2 16.7 52.5-38.3 22.7-38.9-40.5-21.7 6.6-12.6 54-42.4-.5-12.6-53.6-21.7-5.6-36.4 38.4-37.4-21.7 15.2-50.5-13.7-16.1-55.5 14.1-19.7-34.8 37.9-37.4-4.8-22.8-54-14.1.5-40.9L54 219.9l5.7-19.7-38.9-39.4L41.5 125l53.6 14.1 15.2-15.7-15.2-52 36.4-20.7 36.8 39.4L191 84l11.6-52H245l11.6 45.9L234 72l-6.3-1.7-3.3 5.7-11 19.1-3.3 5.6 4.6 4.6 17.2 17.4-.3 1-23.8 6.5-6.2 1.7-.1 6.4-.2 12.9C153.8 161.6 118 204 118 254.7c0 58.3 47.3 105.7 105.7 105.7 50.5 0 92.7-35.4 103.2-82.8l13.2.2 6.9.1 1.6-6.7 5.6-24 1.9-.6 17.1 17.8 4.7 4.9 5.8-3.4 20.4-12.1 5.8-3.5-2-6.5-6.8-21.2z\"],\n    \"wikipedia-w\": [640, 512, [], \"f266\", \"M640 51.2l-.3 12.2c-28.1.8-45 15.8-55.8 40.3-25 57.8-103.3 240-155.3 358.6H415l-81.9-193.1c-32.5 63.6-68.3 130-99.2 193.1-.3.3-15 0-15-.3C172 352.3 122.8 243.4 75.8 133.4 64.4 106.7 26.4 63.4.2 63.7c0-3.1-.3-10-.3-14.2h161.9v13.9c-19.2 1.1-52.8 13.3-43.3 34.2 21.9 49.7 103.6 240.3 125.6 288.6 15-29.7 57.8-109.2 75.3-142.8-13.9-28.3-58.6-133.9-72.8-160-9.7-17.8-36.1-19.4-55.8-19.7V49.8l142.5.3v13.1c-19.4.6-38.1 7.8-29.4 26.1 18.9 40 30.6 68.1 48.1 104.7 5.6-10.8 34.7-69.4 48.1-100.8 8.9-20.6-3.9-28.6-38.6-29.4.3-3.6 0-10.3.3-13.6 44.4-.3 111.1-.3 123.1-.6v13.6c-22.5.8-45.8 12.8-58.1 31.7l-59.2 122.8c6.4 16.1 63.3 142.8 69.2 156.7L559.2 91.8c-8.6-23.1-36.4-28.1-47.2-28.3V49.6l127.8 1.1.2.5z\"],\n    \"windows\": [448, 512, [], \"f17a\", \"M0 93.7l183.6-25.3v177.4H0V93.7zm0 324.6l183.6 25.3V268.4H0v149.9zm203.8 28L448 480V268.4H203.8v177.9zm0-380.6v180.1H448V32L203.8 65.7z\"],\n    \"wix\": [640, 512, [], \"f5cf\", \"M393.38 131.69c0 13.03 2.08 32.69-28.68 43.83-9.52 3.45-15.95 9.66-15.95 9.66 0-31 4.72-42.22 17.4-48.86 9.75-5.11 27.23-4.63 27.23-4.63zm-115.8 35.54l-34.24 132.66-28.48-108.57c-7.69-31.99-20.81-48.53-48.43-48.53-27.37 0-40.66 16.18-48.43 48.53L89.52 299.89 55.28 167.23C49.73 140.51 23.86 128.96 0 131.96l65.57 247.93s21.63 1.56 32.46-3.96c14.22-7.25 20.98-12.84 29.59-46.57 7.67-30.07 29.11-118.41 31.12-124.7 4.76-14.94 11.09-13.81 15.4 0 1.97 6.3 23.45 94.63 31.12 124.7 8.6 33.73 15.37 39.32 29.59 46.57 10.82 5.52 32.46 3.96 32.46 3.96l65.57-247.93c-24.42-3.07-49.82 8.93-55.3 35.27zm115.78 5.21s-4.1 6.34-13.46 11.57c-6.01 3.36-11.78 5.64-17.97 8.61-15.14 7.26-13.18 13.95-13.18 35.2v152.07s16.55 2.09 27.37-3.43c13.93-7.1 17.13-13.95 17.26-44.78V181.41l-.02.01v-8.98zm163.44 84.08L640 132.78s-35.11-5.98-52.5 9.85c-13.3 12.1-24.41 29.55-54.18 72.47-.47.73-6.25 10.54-13.07 0-29.29-42.23-40.8-60.29-54.18-72.47-17.39-15.83-52.5-9.85-52.5-9.85l83.2 123.74-82.97 123.36s36.57 4.62 53.95-11.21c11.49-10.46 17.58-20.37 52.51-70.72 6.81-10.52 12.57-.77 13.07 0 29.4 42.38 39.23 58.06 53.14 70.72 17.39 15.83 53.32 11.21 53.32 11.21L556.8 256.52z\"],\n    \"wizards-of-the-coast\": [640, 512, [], \"f730\", \"M219.19 345.69c-1.9 1.38-11.07 8.44-.26 23.57 4.64 6.42 14.11 12.79 21.73 6.55 6.5-4.88 7.35-12.92.26-23.04-5.47-7.76-14.28-12.88-21.73-7.08zm336.75 75.94c-.34 1.7-.55 1.67.79 0 2.09-4.19 4.19-10.21 4.98-19.9 3.14-38.49-40.33-71.49-101.34-78.03-54.73-6.02-124.38 9.17-188.8 60.49l-.26 1.57c2.62 4.98 4.98 10.74 3.4 21.21l.79.26c63.89-58.4 131.19-77.25 184.35-73.85 58.4 3.67 100.03 34.04 100.03 68.08-.01 9.96-2.63 15.72-3.94 20.17zM392.28 240.42c.79 7.07 4.19 10.21 9.17 10.47 5.5.26 9.43-2.62 10.47-6.55.79-3.4 2.09-29.85 2.09-29.85s-11.26 6.55-14.93 10.47c-3.66 3.68-7.33 8.39-6.8 15.46zm-50.02-151.1C137.75 89.32 13.1 226.8.79 241.2c-1.05.52-1.31.79.79 1.31 60.49 16.5 155.81 81.18 196.13 202.16l1.05.26c55.25-69.92 140.88-128.05 236.99-128.05 80.92 0 130.15 42.16 130.15 80.39 0 18.33-6.55 33.52-22.26 46.35 0 .96-.2.79.79.79 14.66-10.74 27.5-28.8 27.5-48.18 0-22.78-12.05-38.23-12.05-38.23 7.07 7.07 10.74 16.24 10.74 16.24 5.76-40.85 26.97-62.32 26.97-62.32-2.36-9.69-6.81-17.81-6.81-17.81 7.59 8.12 14.4 27.5 14.4 41.37 0 10.47-3.4 22.78-12.57 31.95l.26.52c8.12-4.98 16.5-16.76 16.5-37.97 0-15.71-4.71-25.92-4.71-25.92 5.76-5.24 11.26-9.17 15.97-11.78.79 3.4 2.09 9.69 2.36 14.93 0 1.05.79 1.83 1.05 0 .79-5.76-.26-16.24-.26-16.5 6.02-3.14 9.69-4.45 9.69-4.45C617.74 176 489.43 89.32 342.26 89.32zm-99.24 289.62c-11.06 8.99-24.2 4.08-30.64-4.19-7.45-9.58-6.76-24.09 4.19-32.47 14.85-11.35 27.08-.49 31.16 5.5.28.39 12.13 16.57-4.71 31.16zm2.09-136.43l9.43-17.81 11.78 70.96-12.57 6.02-24.62-28.8 14.14-26.71 3.67 4.45-1.83-8.11zm18.59 117.58l-.26-.26c2.05-4.1-2.5-6.61-17.54-31.69-1.31-2.36-3.14-2.88-4.45-2.62l-.26-.52c7.86-5.76 15.45-10.21 25.4-15.71l.52.26c1.31 1.83 2.09 2.88 3.4 4.71l-.26.52c-1.05-.26-2.36-.79-5.24.26-2.09.79-7.86 3.67-12.31 7.59v1.31c1.57 2.36 3.93 6.55 5.76 9.69h.26c10.05-6.28 7.56-4.55 11.52-7.86h.26c.52 1.83.52 1.83 1.83 5.5l-.26.26c-3.06.61-4.65.34-11.52 5.5v.26c9.46 17.02 11.01 16.75 12.57 15.97l.26.26c-2.34 1.59-6.27 4.21-9.68 6.57zm55.26-32.47c-3.14 1.57-6.02 2.88-9.95 4.98l-.26-.26c1.29-2.59 1.16-2.71-11.78-32.47l-.26-.26c-.15 0-8.9 3.65-9.95 7.33h-.52l-1.05-5.76.26-.52c7.29-4.56 25.53-11.64 27.76-12.57l.52.26 3.14 4.98-.26.52c-3.53-1.76-7.35.76-12.31 2.62v.26c12.31 32.01 12.67 30.64 14.66 30.64v.25zm44.77-16.5c-4.19 1.05-5.24 1.31-9.69 2.88l-.26-.26.52-4.45c-1.05-3.4-3.14-11.52-3.67-13.62l-.26-.26c-3.4.79-8.9 2.62-12.83 3.93l-.26.26c.79 2.62 3.14 9.95 4.19 13.88.79 2.36 1.83 2.88 2.88 3.14v.52c-3.67 1.05-7.07 2.62-10.21 3.93l-.26-.26c1.05-1.31 1.05-2.88.26-4.98-1.05-3.14-8.12-23.83-9.17-27.23-.52-1.83-1.57-3.14-2.62-3.14v-.52c3.14-1.05 6.02-2.09 10.74-3.4l.26.26-.26 4.71c1.31 3.93 2.36 7.59 3.14 9.69h.26c3.93-1.31 9.43-2.88 12.83-3.93l.26-.26-2.62-9.43c-.52-1.83-1.05-3.4-2.62-3.93v-.26c4.45-1.05 7.33-1.83 10.74-2.36l.26.26c-1.05 1.31-1.05 2.88-.52 4.45 1.57 6.28 4.71 20.43 6.28 26.45.54 2.62 1.85 3.41 2.63 3.93zm32.21-6.81l-.26.26c-4.71.52-14.14 2.36-22.52 4.19l-.26-.26.79-4.19c-1.57-7.86-3.4-18.59-4.98-26.19-.26-1.83-.79-2.88-2.62-3.67l.79-.52c9.17-1.57 20.16-2.36 24.88-2.62l.26.26c.52 2.36.79 3.14 1.57 5.5l-.26.26c-1.14-1.14-3.34-3.2-16.24-.79l-.26.26c.26 1.57 1.05 6.55 1.57 9.95l.26.26c9.52-1.68 4.76-.06 10.74-2.36h.26c0 1.57-.26 1.83-.26 5.24h-.26c-4.81-1.03-2.15-.9-10.21 0l-.26.26c.26 2.09 1.57 9.43 2.09 12.57l.26.26c1.15.38 14.21-.65 16.24-4.71h.26c-.53 2.38-1.05 4.21-1.58 6.04zm10.74-44.51c-4.45 2.36-8.12 2.88-11 2.88-.25.02-11.41 1.09-17.54-9.95-6.74-10.79-.98-25.2 5.5-31.69 8.8-8.12 23.35-10.1 28.54-17.02 8.03-10.33-13.04-22.31-29.59-5.76l-2.62-2.88 5.24-16.24c25.59-1.57 45.2-3.04 50.02 16.24.79 3.14 0 9.43-.26 12.05 0 2.62-1.83 18.85-2.09 23.04-.52 4.19-.79 18.33-.79 20.69.26 2.36.52 4.19 1.57 5.5 1.57 1.83 5.76 1.83 5.76 1.83l-.79 4.71c-11.82-1.07-10.28-.59-20.43-1.05-3.22-5.15-2.23-3.28-4.19-7.86 0 .01-4.19 3.94-7.33 5.51zm37.18 21.21c-6.35-10.58-19.82-7.16-21.73 5.5-2.63 17.08 14.3 19.79 20.69 10.21l.26.26c-.52 1.83-1.83 6.02-1.83 6.28l-.52.52c-10.3 6.87-28.5-2.5-25.66-18.59 1.94-10.87 14.44-18.93 28.8-9.95l.26.52c0 1.06-.27 3.41-.27 5.25zm5.77-87.73v-6.55c.69 0 19.65 3.28 27.76 7.33l-1.57 17.54s10.21-9.43 15.45-10.74c5.24-1.57 14.93 7.33 14.93 7.33l-11.26 11.26c-12.07-6.35-19.59-.08-20.69.79-5.29 38.72-8.6 42.17 4.45 46.09l-.52 4.71c-17.55-4.29-18.53-4.5-36.92-7.33l.79-4.71c7.25 0 7.48-5.32 7.59-6.81 0 0 4.98-53.16 4.98-55.25-.02-2.87-4.99-3.66-4.99-3.66zm10.99 114.44c-8.12-2.09-14.14-11-10.74-20.69 3.14-9.43 12.31-12.31 18.85-10.21 9.17 2.62 12.83 11.78 10.74 19.38-2.61 8.9-9.42 13.87-18.85 11.52zm42.16 9.69c-2.36-.52-7.07-2.36-8.64-2.88v-.26l1.57-1.83c.59-8.24.59-7.27.26-7.59-4.82-1.81-6.66-2.36-7.07-2.36-1.31 1.83-2.88 4.45-3.67 5.5l-.79 3.4v.26c-1.31-.26-3.93-1.31-6.02-1.57v-.26l2.62-1.83c3.4-4.71 9.95-14.14 13.88-20.16v-2.09l.52-.26c2.09.79 5.5 2.09 7.59 2.88.48.48.18-1.87-1.05 25.14-.24 1.81.02 2.6.8 3.91zm-4.71-89.82c11.25-18.27 30.76-16.19 34.04-3.4L539.7 198c2.34-6.25-2.82-9.9-4.45-11.26l1.83-3.67c12.22 10.37 16.38 13.97 22.52 20.43-25.91 73.07-30.76 80.81-24.62 84.32l-1.83 4.45c-6.37-3.35-8.9-4.42-17.81-8.64l2.09-6.81c-.26-.26-3.93 3.93-9.69 3.67-19.06-1.3-22.89-31.75-9.67-52.9zm29.33 79.34c0-5.71-6.34-7.89-7.86-5.24-1.31 2.09 1.05 4.98 2.88 8.38 1.57 2.62 2.62 6.28 1.05 9.43-2.64 6.34-12.4 5.31-15.45-.79 0-.7-.27.09 1.83-4.71l.79-.26c-.57 5.66 6.06 9.61 8.38 4.98 1.05-2.09-.52-5.5-2.09-8.38-1.57-2.62-3.67-6.28-1.83-9.69 2.72-5.06 11.25-4.47 14.66 2.36v.52l-2.36 3.4zm21.21 13.36c-1.96-3.27-.91-2.14-4.45-4.71h-.26c-2.36 4.19-5.76 10.47-8.64 16.24-1.31 2.36-1.05 3.4-.79 3.93l-.26.26-5.76-4.45.26-.26 2.09-1.31c3.14-5.76 6.55-12.05 9.17-17.02v-.26c-2.64-1.98-1.22-1.51-6.02-1.83v-.26l3.14-3.4h.26c3.67 2.36 9.95 6.81 12.31 8.9l.26.26-1.31 3.91zm27.23-44.26l-2.88-2.88c.79-2.36 1.83-4.98 2.09-7.59.75-9.74-11.52-11.84-11.52-4.98 0 4.98 7.86 19.38 7.86 27.76 0 10.21-5.76 15.71-13.88 16.5-8.38.79-20.16-10.47-20.16-10.47l4.98-14.4 2.88 2.09c-2.97 17.8 17.68 20.37 13.35 5.24-1.06-4.02-18.75-34.2 2.09-38.23 13.62-2.36 23.04 16.5 23.04 16.5l-7.85 10.46zm35.62-10.21c-11-30.38-60.49-127.53-191.95-129.62-53.42-1.05-94.27 15.45-132.76 37.97l85.63-9.17-91.39 20.69 25.14 19.64-3.93-16.5c7.5-1.71 39.15-8.45 66.77-8.9l-22.26 80.39c13.61-.7 18.97-8.98 19.64-22.78l4.98-1.05.26 26.71c-22.46 3.21-37.3 6.69-49.49 9.95l13.09-43.21-61.54-36.66 2.36 8.12 10.21 4.98c6.28 18.59 19.38 56.56 20.43 58.66 1.95 4.28 3.16 5.78 12.05 4.45l1.05 4.98c-16.08 4.86-23.66 7.61-39.02 14.4l-2.36-4.71c4.4-2.94 8.73-3.94 5.5-12.83-23.7-62.5-21.48-58.14-22.78-59.44l2.36-4.45 33.52 67.3c-3.84-11.87 1.68 1.69-32.99-78.82l-41.9 88.51 4.71-13.88-35.88-42.16 27.76 93.48-11.78 8.38C95 228.58 101.05 231.87 93.23 231.52c-5.5-.26-13.62 5.5-13.62 5.5L74.63 231c30.56-23.53 31.62-24.33 58.4-42.68l4.19 7.07s-5.76 4.19-7.86 7.07c-5.9 9.28 1.67 13.28 61.8 75.68l-18.85-58.92 39.8-10.21 25.66 30.64 4.45-12.31-4.98-24.62 13.09-3.4.52 3.14 3.67-10.47-94.27 29.33 11.26-4.98-13.62-42.42 17.28-9.17 30.11 36.14 28.54-13.09c-1.41-7.47-2.47-14.5-4.71-19.64l17.28 13.88 4.71-2.09-59.18-42.68 23.08 11.5c18.98-6.07 25.23-7.47 32.21-9.69l2.62 11c-12.55 12.55 1.43 16.82 6.55 19.38l-13.62-61.01 12.05 28.28c4.19-1.31 7.33-2.09 7.33-2.09l2.62 8.64s-3.14 1.05-6.28 2.09l8.9 20.95 33.78-65.73-20.69 61.01c42.42-24.09 81.44-36.66 131.98-35.88 67.04 1.05 167.33 40.85 199.8 139.83.78 2.1-.01 2.63-.79.27zM203.48 152.43s1.83-.52 4.19-1.31l9.43 7.59c-.4 0-3.44-.25-11.26 2.36l-2.36-8.64zm143.76 38.5c-1.57-.6-26.46-4.81-33.26 20.69l21.73 17.02 11.53-37.71zM318.43 67.07c-58.4 0-106.05 12.05-114.96 14.4v.79c8.38 2.09 14.4 4.19 21.21 11.78l1.57.26c6.55-1.83 48.97-13.88 110.24-13.88 180.16 0 301.67 116.79 301.67 223.37v9.95c0 1.31.79 2.62 1.05.52.52-2.09.79-8.64.79-19.64.26-83.79-96.63-227.55-321.57-227.55zm211.06 169.68c1.31-5.76 0-12.31-7.33-13.09-9.62-1.13-16.14 23.79-17.02 33.52-.79 5.5-1.31 14.93 6.02 14.93 4.68-.01 9.72-.91 18.33-35.36zm-61.53 42.95c-2.62-.79-9.43-.79-12.57 10.47-1.83 6.81.52 13.35 6.02 14.66 3.67 1.05 8.9.52 11.78-10.74 2.62-9.94-1.83-13.61-5.23-14.39zM491 300.65c1.83.52 3.14 1.05 5.76 1.83 0-1.83.52-8.38.79-12.05-1.05 1.31-5.5 8.12-6.55 9.95v.27z\"],\n    \"wolf-pack-battalion\": [512, 512, [], \"f514\", \"M267.73 471.53l10.56 15.84 5.28-12.32 5.28 7V512c21.06-7.92 21.11-66.86 25.51-97.21 4.62-31.89-.88-92.81 81.37-149.11-8.88-23.61-12-49.43-2.64-80.05C421 189 447 196.21 456.43 239.73l-30.35 8.36c11.15 23 17 46.76 13.2 72.14L412 313.18l-6.16 33.43-18.47-7-8.8 33.39-19.35-7 26.39 21.11 8.8-28.15L419 364.2l7-35.63 26.39 14.52c.25-20 7-58.06-8.8-84.45l26.39 5.28c4-22.07-2.38-39.21-7.92-56.74l22.43 9.68c-.44-25.07-29.94-56.79-61.58-58.5-20.22-1.09-56.74-25.17-54.1-51.9 2-19.87 17.45-42.62 43.11-49.7-44 36.51-9.68 67.3 5.28 73.46 4.4-11.44 17.54-69.08 0-130.2-40.39 22.87-89.65 65.1-93.2 147.79l-58 38.71-3.52 93.25L369.78 220l7 7-17.59 3.52-44 38.71-15.84-5.28-28.1 49.25-3.52 119.64 21.11 15.84-32.55 15.84-32.55-15.84 21.11-15.84-3.52-119.64-28.15-49.26-15.84 5.28-44-38.71-17.58-3.51 7-7 107.33 59.82-3.52-93.25-58.06-38.71C185 65.1 135.77 22.87 95.3 0c-17.54 61.12-4.4 118.76 0 130.2 15-6.16 49.26-36.95 5.28-73.46 25.66 7.08 41.15 29.83 43.11 49.7 2.63 26.74-33.88 50.81-54.1 51.9-31.65 1.72-61.15 33.44-61.59 58.51l22.43-9.68c-5.54 17.53-11.91 34.67-7.92 56.74l26.39-5.28c-15.76 26.39-9.05 64.43-8.8 84.45l26.39-14.52 7 35.63 24.63-5.28 8.8 28.15L153.35 366 134 373l-8.8-33.43-18.47 7-6.16-33.43-27.27 7c-3.82-25.38 2-49.1 13.2-72.14l-30.35-8.36c9.4-43.52 35.47-50.77 63.34-54.1 9.36 30.62 6.24 56.45-2.64 80.05 82.25 56.3 76.75 117.23 81.37 149.11 4.4 30.35 4.45 89.29 25.51 97.21v-29.83l5.28-7 5.28 12.32 10.56-15.84 11.44 21.11 11.43-21.1zm79.17-95L331.06 366c7.47-4.36 13.76-8.42 19.35-12.32-.6 7.22-.27 13.84-3.51 22.84zm28.15-49.26c-.4 10.94-.9 21.66-1.76 31.67-7.85-1.86-15.57-3.8-21.11-7 8.24-7.94 15.55-16.32 22.87-24.68zm24.63 5.28c0-13.43-2.05-24.21-5.28-33.43a235 235 0 0 1-18.47 27.27zm3.52-80.94c19.44 12.81 27.8 33.66 29.91 56.3-12.32-4.53-24.63-9.31-36.95-10.56 5.06-12 6.65-28.14 7-45.74zm-1.76-45.74c.81 14.3 1.84 28.82 1.76 42.23 19.22-8.11 29.78-9.72 44-14.08-10.61-18.96-27.2-25.53-45.76-28.16zM165.68 376.52L181.52 366c-7.47-4.36-13.76-8.42-19.35-12.32.6 7.26.27 13.88 3.51 22.88zm-28.15-49.26c.4 10.94.9 21.66 1.76 31.67 7.85-1.86 15.57-3.8 21.11-7-8.24-7.93-15.55-16.31-22.87-24.67zm-24.64 5.28c0-13.43 2-24.21 5.28-33.43a235 235 0 0 0 18.47 27.27zm-3.52-80.94c-19.44 12.81-27.8 33.66-29.91 56.3 12.32-4.53 24.63-9.31 37-10.56-5-12-6.65-28.14-7-45.74zm1.76-45.74c-.81 14.3-1.84 28.82-1.76 42.23-19.22-8.11-29.78-9.72-44-14.08 10.63-18.95 27.23-25.52 45.76-28.15z\"],\n    \"wordpress\": [512, 512, [], \"f19a\", \"M61.7 169.4l101.5 278C92.2 413 43.3 340.2 43.3 256c0-30.9 6.6-60.1 18.4-86.6zm337.9 75.9c0-26.3-9.4-44.5-17.5-58.7-10.8-17.5-20.9-32.4-20.9-49.9 0-19.6 14.8-37.8 35.7-37.8.9 0 1.8.1 2.8.2-37.9-34.7-88.3-55.9-143.7-55.9-74.3 0-139.7 38.1-177.8 95.9 5 .2 9.7.3 13.7.3 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l77.5 230.4L249.8 247l-33.1-90.8c-11.5-.7-22.3-2-22.3-2-11.5-.7-10.1-18.2 1.3-17.5 0 0 35.1 2.7 56 2.7 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l76.9 228.7 21.2-70.9c9-29.4 16-50.5 16-68.7zm-139.9 29.3l-63.8 185.5c19.1 5.6 39.2 8.7 60.1 8.7 24.8 0 48.5-4.3 70.6-12.1-.6-.9-1.1-1.9-1.5-2.9l-65.4-179.2zm183-120.7c.9 6.8 1.4 14 1.4 21.9 0 21.6-4 45.8-16.2 76.2l-65 187.9C426.2 403 468.7 334.5 468.7 256c0-37-9.4-71.8-26-102.1zM504 256c0 136.8-111.3 248-248 248C119.2 504 8 392.7 8 256 8 119.2 119.2 8 256 8c136.7 0 248 111.2 248 248zm-11.4 0c0-130.5-106.2-236.6-236.6-236.6C125.5 19.4 19.4 125.5 19.4 256S125.6 492.6 256 492.6c130.5 0 236.6-106.1 236.6-236.6z\"],\n    \"wordpress-simple\": [512, 512, [], \"f411\", \"M256 8C119.3 8 8 119.2 8 256c0 136.7 111.3 248 248 248s248-111.3 248-248C504 119.2 392.7 8 256 8zM33 256c0-32.3 6.9-63 19.3-90.7l106.4 291.4C84.3 420.5 33 344.2 33 256zm223 223c-21.9 0-43-3.2-63-9.1l66.9-194.4 68.5 187.8c.5 1.1 1 2.1 1.6 3.1-23.1 8.1-48 12.6-74 12.6zm30.7-327.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-21.9 0-58.7-2.8-58.7-2.8-12-.7-13.4 17.7-1.4 18.4 0 0 11.4 1.4 23.4 2.1l34.7 95.2L200.6 393l-81.2-241.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-4.2 0-9.1-.1-14.4-.3C109.6 73 178.1 33 256 33c58 0 110.9 22.2 150.6 58.5-1-.1-1.9-.2-2.9-.2-21.9 0-37.4 19.1-37.4 39.6 0 18.4 10.6 33.9 21.9 52.3 8.5 14.8 18.4 33.9 18.4 61.5 0 19.1-7.3 41.2-17 72.1l-22.2 74.3-80.7-239.6zm81.4 297.2l68.1-196.9c12.7-31.8 17-57.2 17-79.9 0-8.2-.5-15.8-1.5-22.9 17.4 31.8 27.3 68.2 27.3 107 0 82.3-44.6 154.1-110.9 192.7z\"],\n    \"wpbeginner\": [512, 512, [], \"f297\", \"M462.799 322.374C519.01 386.682 466.961 480 370.944 480c-39.602 0-78.824-17.687-100.142-50.04-6.887.356-22.702.356-29.59 0C219.848 462.381 180.588 480 141.069 480c-95.49 0-148.348-92.996-91.855-157.626C-29.925 190.523 80.479 32 256.006 32c175.632 0 285.87 158.626 206.793 290.374zm-339.647-82.972h41.529v-58.075h-41.529v58.075zm217.18 86.072v-23.839c-60.506 20.915-132.355 9.198-187.589-33.971l.246 24.897c51.101 46.367 131.746 57.875 187.343 32.913zm-150.753-86.072h166.058v-58.075H189.579v58.075z\"],\n    \"wpexplorer\": [512, 512, [], \"f2de\", \"M512 256c0 141.2-114.7 256-256 256C114.8 512 0 397.3 0 256S114.7 0 256 0s256 114.7 256 256zm-32 0c0-123.2-100.3-224-224-224C132.5 32 32 132.5 32 256s100.5 224 224 224 224-100.5 224-224zM160.9 124.6l86.9 37.1-37.1 86.9-86.9-37.1 37.1-86.9zm110 169.1l46.6 94h-14.6l-50-100-48.9 100h-14l51.1-106.9-22.3-9.4 6-14 68.6 29.1-6 14.3-16.5-7.1zm-11.8-116.3l68.6 29.4-29.4 68.3L230 246l29.1-68.6zm80.3 42.9l54.6 23.1-23.4 54.3-54.3-23.1 23.1-54.3z\"],\n    \"wpforms\": [448, 512, [], \"f298\", \"M448 75.2v361.7c0 24.3-19 43.2-43.2 43.2H43.2C19.3 480 0 461.4 0 436.8V75.2C0 51.1 18.8 32 43.2 32h361.7c24 0 43.1 18.8 43.1 43.2zm-37.3 361.6V75.2c0-3-2.6-5.8-5.8-5.8h-9.3L285.3 144 224 94.1 162.8 144 52.5 69.3h-9.3c-3.2 0-5.8 2.8-5.8 5.8v361.7c0 3 2.6 5.8 5.8 5.8h361.7c3.2.1 5.8-2.7 5.8-5.8zM150.2 186v37H76.7v-37h73.5zm0 74.4v37.3H76.7v-37.3h73.5zm11.1-147.3l54-43.7H96.8l64.5 43.7zm210 72.9v37h-196v-37h196zm0 74.4v37.3h-196v-37.3h196zm-84.6-147.3l64.5-43.7H232.8l53.9 43.7zM371.3 335v37.3h-99.4V335h99.4z\"],\n    \"wpressr\": [496, 512, [], \"f3e4\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm171.33 158.6c-15.18 34.51-30.37 69.02-45.63 103.5-2.44 5.51-6.89 8.24-12.97 8.24-23.02-.01-46.03.06-69.05-.05-5.12-.03-8.25 1.89-10.34 6.72-10.19 23.56-20.63 47-30.95 70.5-1.54 3.51-4.06 5.29-7.92 5.29-45.94-.01-91.87-.02-137.81 0-3.13 0-5.63-1.15-7.72-3.45-11.21-12.33-22.46-24.63-33.68-36.94-2.69-2.95-2.79-6.18-1.21-9.73 8.66-19.54 17.27-39.1 25.89-58.66 12.93-29.35 25.89-58.69 38.75-88.08 1.7-3.88 4.28-5.68 8.54-5.65 14.24.1 28.48.02 42.72.05 6.24.01 9.2 4.84 6.66 10.59-13.6 30.77-27.17 61.55-40.74 92.33-5.72 12.99-11.42 25.99-17.09 39-3.91 8.95 7.08 11.97 10.95 5.6.23-.37-1.42 4.18 30.01-67.69 1.36-3.1 3.41-4.4 6.77-4.39 15.21.08 30.43.02 45.64.04 5.56.01 7.91 3.64 5.66 8.75-8.33 18.96-16.71 37.9-24.98 56.89-4.98 11.43 8.08 12.49 11.28 5.33.04-.08 27.89-63.33 32.19-73.16 2.02-4.61 5.44-6.51 10.35-6.5 26.43.05 52.86 0 79.29.05 12.44.02 13.93-13.65 3.9-13.64-25.26.03-50.52.02-75.78.02-6.27 0-7.84-2.47-5.27-8.27 5.78-13.06 11.59-26.11 17.3-39.21 1.73-3.96 4.52-5.79 8.84-5.78 23.09.06 25.98.02 130.78.03 6.08-.01 8.03 2.79 5.62 8.27z\"],\n    \"xbox\": [512, 512, [], \"f412\", \"M369.9 318.2c44.3 54.3 64.7 98.8 54.4 118.7-7.9 15.1-56.7 44.6-92.6 55.9-29.6 9.3-68.4 13.3-100.4 10.2-38.2-3.7-76.9-17.4-110.1-39C93.3 445.8 87 438.3 87 423.4c0-29.9 32.9-82.3 89.2-142.1 32-33.9 76.5-73.7 81.4-72.6 9.4 2.1 84.3 75.1 112.3 109.5zM188.6 143.8c-29.7-26.9-58.1-53.9-86.4-63.4-15.2-5.1-16.3-4.8-28.7 8.1-29.2 30.4-53.5 79.7-60.3 122.4-5.4 34.2-6.1 43.8-4.2 60.5 5.6 50.5 17.3 85.4 40.5 120.9 9.5 14.6 12.1 17.3 9.3 9.9-4.2-11-.3-37.5 9.5-64 14.3-39 53.9-112.9 120.3-194.4zm311.6 63.5C483.3 127.3 432.7 77 425.6 77c-7.3 0-24.2 6.5-36 13.9-23.3 14.5-41 31.4-64.3 52.8C367.7 197 427.5 283.1 448.2 346c6.8 20.7 9.7 41.1 7.4 52.3-1.7 8.5-1.7 8.5 1.4 4.6 6.1-7.7 19.9-31.3 25.4-43.5 7.4-16.2 15-40.2 18.6-58.7 4.3-22.5 3.9-70.8-.8-93.4zM141.3 43C189 40.5 251 77.5 255.6 78.4c.7.1 10.4-4.2 21.6-9.7 63.9-31.1 94-25.8 107.4-25.2-63.9-39.3-152.7-50-233.9-11.7-23.4 11.1-24 11.9-9.4 11.2z\"],\n    \"xing\": [384, 512, [], \"f168\", \"M162.7 210c-1.8 3.3-25.2 44.4-70.1 123.5-4.9 8.3-10.8 12.5-17.7 12.5H9.8c-7.7 0-12.1-7.5-8.5-14.4l69-121.3c.2 0 .2-.1 0-.3l-43.9-75.6c-4.3-7.8.3-14.1 8.5-14.1H100c7.3 0 13.3 4.1 18 12.2l44.7 77.5zM382.6 46.1l-144 253v.3L330.2 466c3.9 7.1.2 14.1-8.5 14.1h-65.2c-7.6 0-13.6-4-18-12.2l-92.4-168.5c3.3-5.8 51.5-90.8 144.8-255.2 4.6-8.1 10.4-12.2 17.5-12.2h65.7c8 0 12.3 6.7 8.5 14.1z\"],\n    \"xing-square\": [448, 512, [], \"f169\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM140.4 320.2H93.8c-5.5 0-8.7-5.3-6-10.3l49.3-86.7c.1 0 .1-.1 0-.2l-31.4-54c-3-5.6.2-10.1 6-10.1h46.6c5.2 0 9.5 2.9 12.9 8.7l31.9 55.3c-1.3 2.3-18 31.7-50.1 88.2-3.5 6.2-7.7 9.1-12.6 9.1zm219.7-214.1L257.3 286.8v.2l65.5 119c2.8 5.1.1 10.1-6 10.1h-46.6c-5.5 0-9.7-2.9-12.9-8.7l-66-120.3c2.3-4.1 36.8-64.9 103.4-182.3 3.3-5.8 7.4-8.7 12.5-8.7h46.9c5.7-.1 8.8 4.7 6 10z\"],\n    \"y-combinator\": [448, 512, [], \"f23b\", \"M448 32v448H0V32h448zM236 287.5L313.5 142h-32.7L235 233c-4.7 9.3-9 18.3-12.8 26.8L210 233l-45.2-91h-35l76.7 143.8v94.5H236v-92.8z\"],\n    \"yahoo\": [448, 512, [], \"f19e\", \"M252 292l4 220c-12.7-2.2-23.5-3.9-32.3-3.9-8.4 0-19.2 1.7-32.3 3.9l4-220C140.4 197.2 85 95.2 21.4 0c11.9 3.1 23 3.9 33.2 3.9 9 0 20.4-.8 34.1-3.9 40.9 72.2 82.1 138.7 135 225.5C261 163.9 314.8 81.4 358.6 0c11.1 2.9 22 3.9 32.9 3.9 11.5 0 23.2-1 35-3.9C392.1 47.9 294.9 216.9 252 292z\"],\n    \"yammer\": [512, 512, [], \"f840\", \"M421.78 152.17A23.06 23.06 0 0 0 400.9 112c-.83.43-1.71.9-2.63 1.4-15.25 8.4-118.33 80.62-106.69 88.77s82.04-23.61 130.2-50zm0 217.17c-48.16-26.38-118.64-58.1-130.2-50s91.42 80.35 106.69 88.74c.92.51 1.8 1 2.63 1.41a23.07 23.07 0 0 0 20.88-40.15zM464.21 237c-.95 0-1.95-.06-3-.06-17.4 0-142.52 13.76-136.24 26.51s83.3 18.74 138.21 18.76a23 23 0 0 0 1-45.21zM31 96.65a24.88 24.88 0 0 1 46.14-18.4l81 205.06h1.21l77-203.53a23.52 23.52 0 0 1 44.45 15.27L171.2 368.44C152.65 415.66 134.08 448 77.91 448a139.67 139.67 0 0 1-23.81-1.95 21.31 21.31 0 0 1 6.9-41.77c.66.06 10.91.66 13.86.66 30.47 0 43.74-18.94 58.07-59.41z\"],\n    \"yandex\": [256, 512, [], \"f413\", \"M153.1 315.8L65.7 512H2l96-209.8c-45.1-22.9-75.2-64.4-75.2-141.1C22.7 53.7 90.8 0 171.7 0H254v512h-55.1V315.8h-45.8zm45.8-269.3h-29.4c-44.4 0-87.4 29.4-87.4 114.6 0 82.3 39.4 108.8 87.4 108.8h29.4V46.5z\"],\n    \"yandex-international\": [320, 512, [], \"f414\", \"M129.5 512V345.9L18.5 48h55.8l81.8 229.7L250.2 0h51.3L180.8 347.8V512h-51.3z\"],\n    \"yarn\": [496, 512, [], \"f7e3\", \"M393.9 345.2c-39 9.3-48.4 32.1-104 47.4 0 0-2.7 4-10.4 5.8-13.4 3.3-63.9 6-68.5 6.1-12.4.1-19.9-3.2-22-8.2-6.4-15.3 9.2-22 9.2-22-8.1-5-9-9.9-9.8-8.1-2.4 5.8-3.6 20.1-10.1 26.5-8.8 8.9-25.5 5.9-35.3.8-10.8-5.7.8-19.2.8-19.2s-5.8 3.4-10.5-3.6c-6-9.3-17.1-37.3 11.5-62-1.3-10.1-4.6-53.7 40.6-85.6 0 0-20.6-22.8-12.9-43.3 5-13.4 7-13.3 8.6-13.9 5.7-2.2 11.3-4.6 15.4-9.1 20.6-22.2 46.8-18 46.8-18s12.4-37.8 23.9-30.4c3.5 2.3 16.3 30.6 16.3 30.6s13.6-7.9 15.1-5c8.2 16 9.2 46.5 5.6 65.1-6.1 30.6-21.4 47.1-27.6 57.5-1.4 2.4 16.5 10 27.8 41.3 10.4 28.6 1.1 52.7 2.8 55.3.8 1.4 13.7.8 36.4-13.2 12.8-7.9 28.1-16.9 45.4-17 16.7-.5 17.6 19.2 4.9 22.2zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-79.3 75.2c-1.7-13.6-13.2-23-28-22.8-22 .3-40.5 11.7-52.8 19.2-4.8 3-8.9 5.2-12.4 6.8 3.1-44.5-22.5-73.1-28.7-79.4 7.8-11.3 18.4-27.8 23.4-53.2 4.3-21.7 3-55.5-6.9-74.5-1.6-3.1-7.4-11.2-21-7.4-9.7-20-13-22.1-15.6-23.8-1.1-.7-23.6-16.4-41.4 28-12.2.9-31.3 5.3-47.5 22.8-2 2.2-5.9 3.8-10.1 5.4h.1c-8.4 3-12.3 9.9-16.9 22.3-6.5 17.4.2 34.6 6.8 45.7-17.8 15.9-37 39.8-35.7 82.5-34 36-11.8 73-5.6 79.6-1.6 11.1 3.7 19.4 12 23.8 12.6 6.7 30.3 9.6 43.9 2.8 4.9 5.2 13.8 10.1 30 10.1 6.8 0 58-2.9 72.6-6.5 6.8-1.6 11.5-4.5 14.6-7.1 9.8-3.1 36.8-12.3 62.2-28.7 18-11.7 24.2-14.2 37.6-17.4 12.9-3.2 21-15.1 19.4-28.2z\"],\n    \"yelp\": [384, 512, [], \"f1e9\", \"M42.9 240.32l99.62 48.61c19.2 9.4 16.2 37.51-4.5 42.71L30.5 358.45a22.79 22.79 0 0 1-28.21-19.6 197.16 197.16 0 0 1 9-85.32 22.8 22.8 0 0 1 31.61-13.21zm44 239.25a199.45 199.45 0 0 0 79.42 32.11A22.78 22.78 0 0 0 192.94 490l3.9-110.82c.7-21.3-25.5-31.91-39.81-16.1l-74.21 82.4a22.82 22.82 0 0 0 4.09 34.09zm145.34-109.92l58.81 94a22.93 22.93 0 0 0 34 5.5 198.36 198.36 0 0 0 52.71-67.61A23 23 0 0 0 364.17 370l-105.42-34.26c-20.31-6.5-37.81 15.8-26.51 33.91zm148.33-132.23a197.44 197.44 0 0 0-50.41-69.31 22.85 22.85 0 0 0-34 4.4l-62 91.92c-11.9 17.7 4.7 40.61 25.2 34.71L366 268.63a23 23 0 0 0 14.61-31.21zM62.11 30.18a22.86 22.86 0 0 0-9.9 32l104.12 180.44c11.7 20.2 42.61 11.9 42.61-11.4V22.88a22.67 22.67 0 0 0-24.5-22.8 320.37 320.37 0 0 0-112.33 30.1z\"],\n    \"yoast\": [448, 512, [], \"f2b1\", \"M91.3 76h186l-7 18.9h-179c-39.7 0-71.9 31.6-71.9 70.3v205.4c0 35.4 24.9 70.3 84 70.3V460H91.3C41.2 460 0 419.8 0 370.5V165.2C0 115.9 40.7 76 91.3 76zm229.1-56h66.5C243.1 398.1 241.2 418.9 202.2 459.3c-20.8 21.6-49.3 31.7-78.3 32.7v-51.1c49.2-7.7 64.6-49.9 64.6-75.3 0-20.1.6-12.6-82.1-223.2h61.4L218.2 299 320.4 20zM448 161.5V460H234c6.6-9.6 10.7-16.3 12.1-19.4h182.5V161.5c0-32.5-17.1-51.9-48.2-62.9l6.7-17.6c41.7 13.6 60.9 43.1 60.9 80.5z\"],\n    \"youtube\": [576, 512, [], \"f167\", \"M549.655 124.083c-6.281-23.65-24.787-42.276-48.284-48.597C458.781 64 288 64 288 64S117.22 64 74.629 75.486c-23.497 6.322-42.003 24.947-48.284 48.597-11.412 42.867-11.412 132.305-11.412 132.305s0 89.438 11.412 132.305c6.281 23.65 24.787 41.5 48.284 47.821C117.22 448 288 448 288 448s170.78 0 213.371-11.486c23.497-6.321 42.003-24.171 48.284-47.821 11.412-42.867 11.412-132.305 11.412-132.305s0-89.438-11.412-132.305zm-317.51 213.508V175.185l142.739 81.205-142.739 81.201z\"],\n    \"youtube-square\": [448, 512, [], \"f431\", \"M186.8 202.1l95.2 54.1-95.2 54.1V202.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-42 176.3s0-59.6-7.6-88.2c-4.2-15.8-16.5-28.2-32.2-32.4C337.9 128 224 128 224 128s-113.9 0-142.2 7.7c-15.7 4.2-28 16.6-32.2 32.4-7.6 28.5-7.6 88.2-7.6 88.2s0 59.6 7.6 88.2c4.2 15.8 16.5 27.7 32.2 31.9C110.1 384 224 384 224 384s113.9 0 142.2-7.7c15.7-4.2 28-16.1 32.2-31.9 7.6-28.5 7.6-88.1 7.6-88.1z\"],\n    \"zhihu\": [640, 512, [], \"f63f\", \"M170.54 148.13v217.54l23.43.01 7.71 26.37 42.01-26.37h49.53V148.13H170.54zm97.75 193.93h-27.94l-27.9 17.51-5.08-17.47-11.9-.04V171.75h72.82v170.31zm-118.46-94.39H97.5c1.74-27.1 2.2-51.59 2.2-73.46h51.16s1.97-22.56-8.58-22.31h-88.5c3.49-13.12 7.87-26.66 13.12-40.67 0 0-24.07 0-32.27 21.57-3.39 8.9-13.21 43.14-30.7 78.12 5.89-.64 25.37-1.18 36.84-22.21 2.11-5.89 2.51-6.66 5.14-14.53h28.87c0 10.5-1.2 66.88-1.68 73.44H20.83c-11.74 0-15.56 23.62-15.56 23.62h65.58C66.45 321.1 42.83 363.12 0 396.34c20.49 5.85 40.91-.93 51-9.9 0 0 22.98-20.9 35.59-69.25l53.96 64.94s7.91-26.89-1.24-39.99c-7.58-8.92-28.06-33.06-36.79-41.81L87.9 311.95c4.36-13.98 6.99-27.55 7.87-40.67h61.65s-.09-23.62-7.59-23.62v.01zm412.02-1.6c20.83-25.64 44.98-58.57 44.98-58.57s-18.65-14.8-27.38-4.06c-6 8.15-36.83 48.2-36.83 48.2l19.23 14.43zm-150.09-59.09c-9.01-8.25-25.91 2.13-25.91 2.13s39.52 55.04 41.12 57.45l19.46-13.73s-25.67-37.61-34.66-45.86h-.01zM640 258.35c-19.78 0-130.91.93-131.06.93v-101c4.81 0 12.42-.4 22.85-1.2 40.88-2.41 70.13-4 87.77-4.81 0 0 12.22-27.19-.59-33.44-3.07-1.18-23.17 4.58-23.17 4.58s-165.22 16.49-232.36 18.05c1.6 8.82 7.62 17.08 15.78 19.55 13.31 3.48 22.69 1.7 49.15.89 24.83-1.6 43.68-2.43 56.51-2.43v99.81H351.41s2.82 22.31 25.51 22.85h107.94v70.92c0 13.97-11.19 21.99-24.48 21.12-14.08.11-26.08-1.15-41.69-1.81 1.99 3.97 6.33 14.39 19.31 21.84 9.88 4.81 16.17 6.57 26.02 6.57 29.56 0 45.67-17.28 44.89-45.31v-73.32h122.36c9.68 0 8.7-23.78 8.7-23.78l.03-.01z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fab', icons);\n  });\n\n}());\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-68 304H48V48h320v416zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H48V80h480v352zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2zM360 320h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-144c-33.6 0-65.2 14.8-86.8 40.6-8.5 10.2-7.1 25.3 3.1 33.8s25.3 7.2 33.8-3c24.8-29.7 75-29.7 99.8 0 8.1 9.7 23.2 11.9 33.8 3 10.2-8.5 11.5-23.6 3.1-33.8-21.6-25.8-53.2-40.6-86.8-40.6zm-48-72c10.3 0 19.9-6.7 23-17.1 3.8-12.7-3.4-26.1-16.1-29.9l-80-24c-12.8-3.9-26.1 3.4-29.9 16.1-3.8 12.7 3.4 26.1 16.1 29.9l28.2 8.5c-3.1 4.9-5.3 10.4-5.3 16.6 0 17.7 14.3 32 32 32s32-14.4 32-32.1zm199-54.9c-3.8-12.7-17.1-19.9-29.9-16.1l-80 24c-12.7 3.8-19.9 17.2-16.1 29.9 3.1 10.4 12.7 17.1 23 17.1 0 17.7 14.3 32 32 32s32-14.3 32-32c0-6.2-2.2-11.7-5.3-16.6l28.2-8.5c12.7-3.7 19.9-17.1 16.1-29.8z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm-32-316v116h-67c-10.7 0-16 12.9-8.5 20.5l99 99c4.7 4.7 12.3 4.7 17 0l99-99c7.6-7.6 2.2-20.5-8.5-20.5h-67V140c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M8 256c0 137 111 248 248 248s248-111 248-248S393 8 256 8 8 119 8 256zm448 0c0 110.5-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56s200 89.5 200 200zm-72-20v40c0 6.6-5.4 12-12 12H256v67c0 10.7-12.9 16-20.5 8.5l-99-99c-4.7-4.7-4.7-12.3 0-17l99-99c7.6-7.6 20.5-2.2 20.5 8.5v67h116c6.6 0 12 5.4 12 12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm72 20v-40c0-6.6 5.4-12 12-12h116v-67c0-10.7 12.9-16 20.5-8.5l99 99c4.7 4.7 4.7 12.3 0 17l-99 99c-7.6 7.6-20.5 2.2-20.5-8.5v-67H140c-6.6 0-12-5.4-12-12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M256 504c137 0 248-111 248-248S393 8 256 8 8 119 8 256s111 248 248 248zm0-448c110.5 0 200 89.5 200 200s-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56zm20 328h-40c-6.6 0-12-5.4-12-12V256h-67c-10.7 0-16-12.9-8.5-20.5l99-99c4.7-4.7 12.3-4.7 17 0l99 99c7.6 7.6 2.2 20.5-8.5 20.5h-67v116c0 6.6-5.4 12-12 12z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M439.39 362.29c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71zM67.53 368c21.22-27.97 44.42-74.33 44.53-159.42 0-.2-.06-.38-.06-.58 0-61.86 50.14-112 112-112s112 50.14 112 112c0 .2-.06.38-.06.58.11 85.1 23.31 131.46 44.53 159.42H67.53zM224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.99 471.02L36 3.51C29.1-2.01 19.03-.9 13.51 6l-10 12.49C-2.02 25.39-.9 35.46 6 40.98l598 467.51c6.9 5.52 16.96 4.4 22.49-2.49l10-12.49c5.52-6.9 4.41-16.97-2.5-22.49zM163.53 368c16.71-22.03 34.48-55.8 41.4-110.58l-45.47-35.55c-3.27 90.73-36.47 120.68-54.84 140.42-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h279.66l-61.4-48H163.53zM320 96c61.86 0 112 50.14 112 112 0 .2-.06.38-.06.58.02 16.84 1.16 31.77 2.79 45.73l59.53 46.54c-8.31-22.13-14.34-51.49-14.34-92.85 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-26.02 5.41-49.45 16.94-69.13 32.72l38.17 29.84C275 103.18 296.65 96 320 96zm0 416c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M336 0H48C21.49 0 0 21.49 0 48v464l192-112 192 112V48c0-26.51-21.49-48-48-48zm0 428.43l-144-84-144 84V54a6 6 0 0 1 6-6h276c3.314 0 6 2.683 6 5.996V428.43z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M128 148v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12zm140 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-128 96h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm128 0h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-76 84v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm76 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm180 124v36H0v-36c0-6.6 5.4-12 12-12h19.5V24c0-13.3 10.7-24 24-24h337c13.3 0 24 10.7 24 24v440H436c6.6 0 12 5.4 12 12zM79.5 463H192v-67c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v67h112.5V49L80 48l-.5 415z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M400 64h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V160h352v298c0 3.3-2.7 6-6 6z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M148 288h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm108-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 96v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96-260v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M400 64h-48V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H160V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V160h352v298a6 6 0 0 1-6 6zm-52.849-200.65L198.842 404.519c-4.705 4.667-12.303 4.637-16.971-.068l-75.091-75.699c-4.667-4.705-4.637-12.303.068-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l44.104 44.461 111.072-110.181c4.705-4.667 12.303-4.637 16.971.068l22.536 22.718c4.667 4.705 4.636 12.303-.069 16.97z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M124 328c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v24c0 6.6-5.4 12-12 12H124zm324-216v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M336 292v24c0 6.6-5.4 12-12 12h-76v76c0 6.6-5.4 12-12 12h-24c-6.6 0-12-5.4-12-12v-76h-76c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h76v-76c0-6.6 5.4-12 12-12h24c6.6 0 12 5.4 12 12v76h76c6.6 0 12 5.4 12 12zm112-180v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M311.7 374.7l-17 17c-4.7 4.7-12.3 4.7-17 0L224 337.9l-53.7 53.7c-4.7 4.7-12.3 4.7-17 0l-17-17c-4.7-4.7-4.7-12.3 0-17l53.7-53.7-53.7-53.7c-4.7-4.7-4.7-12.3 0-17l17-17c4.7-4.7 12.3-4.7 17 0l53.7 53.7 53.7-53.7c4.7-4.7 12.3-4.7 17 0l17 17c4.7 4.7 4.7 12.3 0 17L257.9 304l53.7 53.7c4.8 4.7 4.8 12.3.1 17zM448 112v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M125.1 208h197.8c10.7 0 16.1 13 8.5 20.5l-98.9 98.3c-4.7 4.7-12.2 4.7-16.9 0l-98.9-98.3c-7.7-7.5-2.3-20.5 8.4-20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M272 157.1v197.8c0 10.7-13 16.1-20.5 8.5l-98.3-98.9c-4.7-4.7-4.7-12.2 0-16.9l98.3-98.9c7.5-7.7 20.5-2.3 20.5 8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M176 354.9V157.1c0-10.7 13-16.1 20.5-8.5l98.3 98.9c4.7 4.7 4.7 12.2 0 16.9l-98.3 98.9c-7.5 7.7-20.5 2.3-20.5-8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M322.9 304H125.1c-10.7 0-16.1-13-8.5-20.5l98.9-98.3c4.7-4.7 12.2-4.7 16.9 0l98.9 98.3c7.7 7.5 2.3 20.5-8.4 20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M396.8 352h22.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-192 0h22.4c6.4 0 12.8-6.4 12.8-12.8V140.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h22.4c6.4 0 12.8-6.4 12.8-12.8V204.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zM496 400H48V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16zm-387.2-48h22.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 48c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m140.204 130.267l-22.536-22.718c-4.667-4.705-12.265-4.736-16.97-.068L215.346 303.697l-59.792-60.277c-4.667-4.705-12.265-4.736-16.97-.069l-22.719 22.536c-4.705 4.667-4.736 12.265-.068 16.971l90.781 91.516c4.667 4.705 12.265 4.736 16.97.068l172.589-171.204c4.704-4.668 4.734-12.266.067-16.971z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm0 400H48V80h352v352zm-35.864-241.724L191.547 361.48c-4.705 4.667-12.303 4.637-16.97-.068l-90.781-91.516c-4.667-4.705-4.637-12.303.069-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l59.792 60.277 141.352-140.216c4.705-4.667 12.303-4.637 16.97.068l22.536 22.718c4.667 4.706 4.637 12.304-.068 16.971z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm144 418c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h42v36c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-36h42c3.3 0 6 2.7 6 6z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm61.8-104.4l-84.9-61.7c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v141.7l66.8 48.6c5.4 3.9 6.5 11.4 2.6 16.8L334.6 349c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0H144c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h320c26.51 0 48-21.49 48-48v-48h48c26.51 0 48-21.49 48-48V48c0-26.51-21.49-48-48-48zM362 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h42v224c0 26.51 21.49 48 48 48h224v42a6 6 0 0 1-6 6zm96-96H150a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h308a6 6 0 0 1 6 6v308a6 6 0 0 1-6 6z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 336H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v276c0 3.3-2.7 6-6 6zm-211.1-85.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7zm190.4 0c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.9-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 220.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 7.1 5.8 12 12 12 2.4 0 4.9-.7 7.1-2.4L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zm16 352c0 8.8-7.2 16-16 16H288l-12.8 9.6L208 428v-60H64c-8.8 0-16-7.2-16-16V64c0-8.8 7.2-16 16-16h384c8.8 0 16 7.2 16 16v288z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M144 208c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zM256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M532 386.2c27.5-27.1 44-61.1 44-98.2 0-80-76.5-146.1-176.2-157.9C368.3 72.5 294.3 32 208 32 93.1 32 0 103.6 0 192c0 37 16.5 71 44 98.2-15.3 30.7-37.3 54.5-37.7 54.9-6.3 6.7-8.1 16.5-4.4 25 3.6 8.5 12 14 21.2 14 53.5 0 96.7-20.2 125.2-38.8 9.2 2.1 18.7 3.7 28.4 4.9C208.1 407.6 281.8 448 368 448c20.8 0 40.8-2.4 59.8-6.8C456.3 459.7 499.4 480 553 480c9.2 0 17.5-5.5 21.2-14 3.6-8.5 1.9-18.3-4.4-25-.4-.3-22.5-24.1-37.8-54.8zm-392.8-92.3L122.1 305c-14.1 9.1-28.5 16.3-43.1 21.4 2.7-4.7 5.4-9.7 8-14.8l15.5-31.1L77.7 256C64.2 242.6 48 220.7 48 192c0-60.7 73.3-112 160-112s160 51.3 160 112-73.3 112-160 112c-16.5 0-33-1.9-49-5.6l-19.8-4.5zM498.3 352l-24.7 24.4 15.5 31.1c2.6 5.1 5.3 10.1 8 14.8-14.6-5.1-29-12.3-43.1-21.4l-17.1-11.1-19.9 4.6c-16 3.7-32.5 5.6-49 5.6-54 0-102.2-20.1-131.3-49.7C338 339.5 416 272.9 416 192c0-3.4-.4-6.7-.7-10C479.7 196.5 528 238.8 528 288c0 28.7-16.2 50.6-29.7 64z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M347.94 129.86L203.6 195.83a31.938 31.938 0 0 0-15.77 15.77l-65.97 144.34c-7.61 16.65 9.54 33.81 26.2 26.2l144.34-65.97a31.938 31.938 0 0 0 15.77-15.77l65.97-144.34c7.61-16.66-9.54-33.81-26.2-26.2zm-77.36 148.72c-12.47 12.47-32.69 12.47-45.16 0-12.47-12.47-12.47-32.69 0-45.16 12.47-12.47 32.69-12.47 45.16 0 12.47 12.47 12.47 32.69 0 45.16zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M433.941 65.941l-51.882-51.882A48 48 0 0 0 348.118 0H176c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48v-48h80c26.51 0 48-21.49 48-48V99.882a48 48 0 0 0-14.059-33.941zM266 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h74v224c0 26.51 21.49 48 48 48h96v42a6 6 0 0 1-6 6zm128-96H182a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h106v88c0 13.255 10.745 24 24 24h88v202a6 6 0 0 1-6 6zm6-256h-64V48h9.632c1.591 0 3.117.632 4.243 1.757l48.368 48.368a6 6 0 0 1 1.757 4.243V112z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm107.351-101.064c-9.614 9.712-45.53 41.396-104.065 41.396-82.43 0-140.484-61.425-140.484-141.567 0-79.152 60.275-139.401 139.762-139.401 55.531 0 88.738 26.62 97.593 34.779a11.965 11.965 0 0 1 1.936 15.322l-18.155 28.113c-3.841 5.95-11.966 7.282-17.499 2.921-8.595-6.776-31.814-22.538-61.708-22.538-48.303 0-77.916 35.33-77.916 80.082 0 41.589 26.888 83.692 78.277 83.692 32.657 0 56.843-19.039 65.726-27.225 5.27-4.857 13.596-4.039 17.82 1.738l19.865 27.17a11.947 11.947 0 0 1-1.152 15.518z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M527.9 32H48.1C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48.1 48h479.8c26.6 0 48.1-21.5 48.1-48V80c0-26.5-21.5-48-48.1-48zM54.1 80h467.8c3.3 0 6 2.7 6 6v42H48.1V86c0-3.3 2.7-6 6-6zm467.8 352H54.1c-3.3 0-6-2.7-6-6V256h479.8v170c0 3.3-2.7 6-6 6zM192 332v40c0 6.6-5.4 12-12 12h-72c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12zm192 0v40c0 6.6-5.4 12-12 12H236c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-33.8-217.9c7.8-7.8 7.8-20.5 0-28.3L196.3 192l17.9-17.9c7.8-7.8 7.8-20.5 0-28.3-7.8-7.8-20.5-7.8-28.3 0L168 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.9 7.7 20.5 7.7 28.4-.2zm160-92.2c-7.8-7.8-20.5-7.8-28.3 0L328 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.8 7.8 20.5 7.8 28.3 0 7.8-7.8 7.8-20.5 0-28.3l-17.8-18 17.9-17.9c7.7-7.8 7.7-20.4 0-28.2zM248 272c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 56c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m0-48C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 168c-44.183 0-80 35.817-80 80s35.817 80 80 80 80-35.817 80-80-35.817-80-80-80z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.3 344.9l32-32c5-5 13.7-1.5 13.7 5.7V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h273.5c7.1 0 10.7 8.6 5.7 13.7l-32 32c-1.5 1.5-3.5 2.3-5.7 2.3H48v352h352V350.5c0-2.1.8-4.1 2.3-5.6zm156.6-201.8L296.3 405.7l-90.4 10c-26.2 2.9-48.5-19.2-45.6-45.6l10-90.4L432.9 17.1c22.9-22.9 59.9-22.9 82.7 0l43.2 43.2c22.9 22.9 22.9 60 .1 82.8zM460.1 174L402 115.9 216.2 301.8l-7.3 65.3 65.3-7.3L460.1 174zm64.8-79.7l-43.2-43.2c-4.1-4.1-10.8-4.1-14.8 0L436 82l58.1 58.1 30.9-30.9c4-4.2 4-10.8-.1-14.9z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm0 48v40.805c-22.422 18.259-58.168 46.651-134.587 106.49-16.841 13.247-50.201 45.072-73.413 44.701-23.208.375-56.579-31.459-73.413-44.701C106.18 199.465 70.425 171.067 48 152.805V112h416zM48 400V214.398c22.914 18.251 55.409 43.862 104.938 82.646 21.857 17.205 60.134 55.186 103.062 54.955 42.717.231 80.509-37.199 103.053-54.947 49.528-38.783 82.032-64.401 104.947-82.653V400H48z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M494.586 164.516c-4.697-3.883-111.723-89.95-135.251-108.657C337.231 38.191 299.437 0 256 0c-43.205 0-80.636 37.717-103.335 55.859-24.463 19.45-131.07 105.195-135.15 108.549A48.004 48.004 0 0 0 0 201.485V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V201.509a48 48 0 0 0-17.414-36.993zM464 458a6 6 0 0 1-6 6H54a6 6 0 0 1-6-6V204.347c0-1.813.816-3.526 2.226-4.665 15.87-12.814 108.793-87.554 132.364-106.293C200.755 78.88 232.398 48 256 48c23.693 0 55.857 31.369 73.41 45.389 23.573 18.741 116.503 93.493 132.366 106.316a5.99 5.99 0 0 1 2.224 4.663V458zm-31.991-187.704c4.249 5.159 3.465 12.795-1.745 16.981-28.975 23.283-59.274 47.597-70.929 56.863C336.636 362.283 299.205 400 256 400c-43.452 0-81.287-38.237-103.335-55.86-11.279-8.967-41.744-33.413-70.927-56.865-5.21-4.187-5.993-11.822-1.745-16.981l15.258-18.528c4.178-5.073 11.657-5.843 16.779-1.726 28.618 23.001 58.566 47.035 70.56 56.571C200.143 320.631 232.307 352 256 352c23.602 0 55.246-30.88 73.41-45.389 11.994-9.535 41.944-33.57 70.563-56.568 5.122-4.116 12.601-3.346 16.778 1.727l15.258 18.526z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M288 144a110.94 110.94 0 0 0-31.24 5 55.4 55.4 0 0 1 7.24 27 56 56 0 0 1-56 56 55.4 55.4 0 0 1-27-7.24A111.71 111.71 0 1 0 288 144zm284.52 97.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400c-98.65 0-189.09-55-237.93-144C98.91 167 189.34 112 288 112s189.09 55 237.93 144C477.1 345 386.66 400 288 400z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M634 471L36 3.51A16 16 0 0 0 13.51 6l-10 12.49A16 16 0 0 0 6 41l598 467.49a16 16 0 0 0 22.49-2.49l10-12.49A16 16 0 0 0 634 471zM296.79 146.47l134.79 105.38C429.36 191.91 380.48 144 320 144a112.26 112.26 0 0 0-23.21 2.47zm46.42 219.07L208.42 260.16C210.65 320.09 259.53 368 320 368a113 113 0 0 0 23.21-2.46zM320 112c98.65 0 189.09 55 237.93 144a285.53 285.53 0 0 1-44 60.2l37.74 29.5a333.7 333.7 0 0 0 52.9-75.11 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64c-36.7 0-71.71 7-104.63 18.81l46.41 36.29c18.94-4.3 38.34-7.1 58.22-7.1zm0 288c-98.65 0-189.08-55-237.93-144a285.47 285.47 0 0 1 44.05-60.19l-37.74-29.5a333.6 333.6 0 0 0-52.89 75.1 32.35 32.35 0 0 0 0 29.19C89.72 376.41 197.08 448 320 448c36.7 0 71.71-7.05 104.63-18.81l-46.41-36.28C359.28 397.2 339.89 400 320 400z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M288 248v28c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-28c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm-12 72H108c-6.6 0-12 5.4-12 12v28c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-28c0-6.6-5.4-12-12-12zm108-188.1V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V48C0 21.5 21.5 0 48 0h204.1C264.8 0 277 5.1 286 14.1L369.9 98c9 8.9 14.1 21.2 14.1 33.9zm-128-80V128h76.1L256 51.9zM336 464V176H232c-13.3 0-24-10.7-24-24V48H48v416h288z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M128.3 160v32h32v-32zm64-96h-32v32h32zm-64 32v32h32V96zm64 32h-32v32h32zm177.6-30.1L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h79.7v16h32V48H208v104c0 13.3 10.7 24 24 24h104zM194.2 265.7c-1.1-5.6-6-9.7-11.8-9.7h-22.1v-32h-32v32l-19.7 97.1C102 385.6 126.8 416 160 416c33.1 0 57.9-30.2 51.5-62.6zm-33.9 124.4c-17.9 0-32.4-12.1-32.4-27s14.5-27 32.4-27 32.4 12.1 32.4 27-14.5 27-32.4 27zm32-198.1h-32v32h32z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm144-76.024c0 10.691-12.926 16.045-20.485 8.485L136 360.486h-28c-6.627 0-12-5.373-12-12v-56c0-6.627 5.373-12 12-12h28l35.515-36.947c7.56-7.56 20.485-2.206 20.485 8.485v135.952zm41.201-47.13c9.051-9.297 9.06-24.133.001-33.439-22.149-22.752 12.235-56.246 34.395-33.481 27.198 27.94 27.212 72.444.001 100.401-21.793 22.386-56.947-10.315-34.397-33.481z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M149.9 349.1l-.2-.2-32.8-28.9 32.8-28.9c3.6-3.2 4-8.8.8-12.4l-.2-.2-17.4-18.6c-3.4-3.6-9-3.7-12.4-.4l-57.7 54.1c-3.7 3.5-3.7 9.4 0 12.8l57.7 54.1c1.6 1.5 3.8 2.4 6 2.4 2.4 0 4.8-1 6.4-2.8l17.4-18.6c3.3-3.5 3.1-9.1-.4-12.4zm220-251.2L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h160v104c0 13.3 10.7 24 24 24h104zM209.6 214c-4.7-1.4-9.5 1.3-10.9 6L144 408.1c-1.4 4.7 1.3 9.6 6 10.9l24.4 7.1c4.7 1.4 9.6-1.4 10.9-6L240 231.9c1.4-4.7-1.3-9.6-6-10.9zm24.5 76.9l.2.2 32.8 28.9-32.8 28.9c-3.6 3.2-4 8.8-.8 12.4l.2.2 17.4 18.6c3.3 3.5 8.9 3.7 12.4.4l57.7-54.1c3.7-3.5 3.7-9.4 0-12.8l-57.7-54.1c-3.5-3.3-9.1-3.2-12.4.4l-17.4 18.6c-3.3 3.5-3.1 9.1.4 12.4z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm212-240h-28.8c-4.4 0-8.4 2.4-10.5 6.3-18 33.1-22.2 42.4-28.6 57.7-13.9-29.1-6.9-17.3-28.6-57.7-2.1-3.9-6.2-6.3-10.6-6.3H124c-9.3 0-15 10-10.4 18l46.3 78-46.3 78c-4.7 8 1.1 18 10.4 18h28.9c4.4 0 8.4-2.4 10.5-6.3 21.7-40 23-45 28.6-57.7 14.9 30.2 5.9 15.9 28.6 57.7 2.1 3.9 6.2 6.3 10.6 6.3H260c9.3 0 15-10 10.4-18L224 320c.7-1.1 30.3-50.5 46.3-78 4.7-8-1.1-18-10.3-18z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm32-48h224V288l-23.5-23.5c-4.7-4.7-12.3-4.7-17 0L176 352l-39.5-39.5c-4.7-4.7-12.3-4.7-17 0L80 352v64zm48-240c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm250.2-143.7c-12.2-12-47-8.7-64.4-6.5-17.2-10.5-28.7-25-36.8-46.3 3.9-16.1 10.1-40.6 5.4-56-4.2-26.2-37.8-23.6-42.6-5.9-4.4 16.1-.4 38.5 7 67.1-10 23.9-24.9 56-35.4 74.4-20 10.3-47 26.2-51 46.2-3.3 15.8 26 55.2 76.1-31.2 22.4-7.4 46.8-16.5 68.4-20.1 18.9 10.2 41 17 55.8 17 25.5 0 28-28.2 17.5-38.7zm-198.1 77.8c5.1-13.7 24.5-29.5 30.4-35-19 30.3-30.4 35.7-30.4 35zm81.6-190.6c7.4 0 6.7 32.1 1.8 40.8-4.4-13.9-4.3-40.8-1.8-40.8zm-24.4 136.6c9.7-16.9 18-37 24.7-54.7 8.3 15.1 18.9 27.2 30.1 35.5-20.8 4.3-38.9 13.1-54.8 19.2zm131.6-5s-5 6-37.3-7.8c35.1-2.6 40.9 5.4 37.3 7.8z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm72-60V236c0-6.6 5.4-12 12-12h69.2c36.7 0 62.8 27 62.8 66.3 0 74.3-68.7 66.5-95.5 66.5V404c0 6.6-5.4 12-12 12H132c-6.6 0-12-5.4-12-12zm48.5-87.4h23c7.9 0 13.9-2.4 18.1-7.2 8.5-9.8 8.4-28.5.1-37.8-4.1-4.6-9.9-7-17.4-7h-23.9v52z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm228.687-211.303L224 305.374V268c0-11.046-8.954-20-20-20H100c-11.046 0-20 8.954-20 20v104c0 11.046 8.954 20 20 20h104c11.046 0 20-8.954 20-20v-37.374l52.687 52.674C286.704 397.318 304 390.28 304 375.986V264.011c0-14.311-17.309-21.319-27.313-11.314z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm220.1-208c-5.7 0-10.6 4-11.7 9.5-20.6 97.7-20.4 95.4-21 103.5-.2-1.2-.4-2.6-.7-4.3-.8-5.1.3.2-23.6-99.5-1.3-5.4-6.1-9.2-11.7-9.2h-13.3c-5.5 0-10.3 3.8-11.7 9.1-24.4 99-24 96.2-24.8 103.7-.1-1.1-.2-2.5-.5-4.2-.7-5.2-14.1-73.3-19.1-99-1.1-5.6-6-9.7-11.8-9.7h-16.8c-7.8 0-13.5 7.3-11.7 14.8 8 32.6 26.7 109.5 33.2 136 1.3 5.4 6.1 9.1 11.7 9.1h25.2c5.5 0 10.3-3.7 11.6-9.1l17.9-71.4c1.5-6.2 2.5-12 3-17.3l2.9 17.3c.1.4 12.6 50.5 17.9 71.4 1.3 5.3 6.1 9.1 11.6 9.1h24.7c5.5 0 10.3-3.7 11.6-9.1 20.8-81.9 30.2-119 34.5-136 1.9-7.6-3.8-14.9-11.6-14.9h-15.8z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M336.174 80c-49.132 0-93.305-32-161.913-32-31.301 0-58.303 6.482-80.721 15.168a48.04 48.04 0 0 0 2.142-20.727C93.067 19.575 74.167 1.594 51.201.104 23.242-1.71 0 20.431 0 48c0 17.764 9.657 33.262 24 41.562V496c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-83.443C109.869 395.28 143.259 384 199.826 384c49.132 0 93.305 32 161.913 32 58.479 0 101.972-22.617 128.548-39.981C503.846 367.161 512 352.051 512 335.855V95.937c0-34.459-35.264-57.768-66.904-44.117C409.193 67.309 371.641 80 336.174 80zM464 336c-21.783 15.412-60.824 32-102.261 32-59.945 0-102.002-32-161.913-32-43.361 0-96.379 9.403-127.826 24V128c21.784-15.412 60.824-32 102.261-32 59.945 0 102.002 32 161.913 32 43.271 0 96.32-17.366 127.826-32v240z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm96-312c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-112 24c0-44.2-35.8-80-80-80s-80 35.8-80 80 35.8 80 80 80 80-35.8 80-80zm-80 48c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm160 144H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-54.63-54.63c-6-6-14.14-9.37-22.63-9.37H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm0 272H48V112h140.12l54.63 54.63c6 6 14.14 9.37 22.63 9.37H464v224z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M527.9 224H480v-48c0-26.5-21.5-48-48-48H272l-64-64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h400c16.5 0 31.9-8.5 40.7-22.6l79.9-128c20-31.9-3-73.4-40.7-73.4zM48 118c0-3.3 2.7-6 6-6h134.1l64 64H426c3.3 0 6 2.7 6 6v42H152c-16.8 0-32.4 8.8-41.1 23.2L48 351.4zm400 282H72l77.2-128H528z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 128c-40.2 0-78 17.7-103.8 48.6-8.5 10.2-7.1 25.3 3.1 33.8 10.2 8.4 25.3 7.1 33.8-3.1 16.6-19.9 41-31.4 66.9-31.4s50.3 11.4 66.9 31.4c8.1 9.7 23.1 11.9 33.8 3.1 10.2-8.5 11.5-23.6 3.1-33.8C326 321.7 288.2 304 248 304z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-48-248c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 112c-35.6 0-88.8 21.3-95.8 61.2-2 11.8 9 21.5 20.5 18.1 31.2-9.6 59.4-15.3 75.3-15.3s44.1 5.7 75.3 15.3c11.4 3.5 22.5-6.3 20.5-18.1-7-39.9-60.2-61.2-95.8-61.2z\"],\n    \"futbol\": [496, 512, [], \"f1e3\", \"M483.8 179.4C449.8 74.6 352.6 8 248.1 8c-25.4 0-51.2 3.9-76.7 12.2C41.2 62.5-30.1 202.4 12.2 332.6 46.2 437.4 143.4 504 247.9 504c25.4 0 51.2-3.9 76.7-12.2 130.2-42.3 201.5-182.2 159.2-312.4zm-74.5 193.7l-52.2 6.4-43.7-60.9 24.4-75.2 71.1-22.1 38.9 36.4c-.2 30.7-7.4 61.1-21.7 89.2-4.7 9.3-10.7 17.8-16.8 26.2zm0-235.4l-10.4 53.1-70.7 22-64.2-46.5V92.5l47.4-26.2c39.2 13 73.4 38 97.9 71.4zM184.9 66.4L232 92.5v73.8l-64.2 46.5-70.6-22-10.1-52.5c24.3-33.4 57.9-58.6 97.8-71.9zM139 379.5L85.9 373c-14.4-20.1-37.3-59.6-37.8-115.3l39-36.4 71.1 22.2 24.3 74.3-43.5 61.7zm48.2 67l-22.4-48.1 43.6-61.7H287l44.3 61.7-22.4 48.1c-6.2 1.8-57.6 20.4-121.7 0z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M464 0H112c-4 0-7.8 2-10 5.4L2 152.6c-2.9 4.4-2.6 10.2.7 14.2l276 340.8c4.8 5.9 13.8 5.9 18.6 0l276-340.8c3.3-4.1 3.6-9.8.7-14.2L474.1 5.4C471.8 2 468.1 0 464 0zm-19.3 48l63.3 96h-68.4l-51.7-96h56.8zm-202.1 0h90.7l51.7 96H191l51.6-96zm-111.3 0h56.8l-51.7 96H68l63.3-96zm-43 144h51.4L208 352 88.3 192zm102.9 0h193.6L288 435.3 191.2 192zM368 352l68.2-160h51.4L368 352z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm16 16H152c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h192c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48zm-168 96h-24c-8.8 0-16-7.2-16-16v-8h40v24zm0-40h-40v-8c0-8.8 7.2-16 16-16h24v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm56 24c0 8.8-7.2 16-16 16h-24v-24h40v8zm0-24h-40v-24h24c8.8 0 16 7.2 16 16v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M200.3 248c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zm128 0c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-235.9-72.9c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3zm160 0c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3z\"],\n    \"grin-beam-sweat\": [496, 512, [], \"f583\", \"M440 160c29.5 0 53.3-26.3 53.3-58.7 0-25-31.7-75.5-46.2-97.3-3.6-5.3-10.7-5.3-14.2 0-14.5 21.8-46.2 72.3-46.2 97.3 0 32.4 23.8 58.7 53.3 58.7zM248 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zm105.3-52.9c-24.6 15.7-46 12.9-46.4 12.9 6.9 20.2 10.8 41.8 10.8 64.3 0 110.3-89.7 200-200 200S48 366.3 48 256 137.7 56 248 56c39.8 0 76.8 11.8 108 31.9 1.7-9.5 6.3-24.1 17.2-45.7C336.4 20.6 293.7 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-27-4.4-52.9-12.4-77.2zM168 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M353.6 304.6c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-152.8-48.9c4.5 1.2 9.2-1.5 10.5-6l19.4-69.9c5.6-20.3-7.4-41.1-28.8-44.5-18.6-3-36.4 9.8-41.5 27.9l-2 7.1-7.1-1.9c-18.2-4.7-38.2 4.3-44.9 22-7.7 20.2 3.8 41.9 24.2 47.2l70.2 18.1zm188.8-65.3c-6.7-17.6-26.7-26.7-44.9-22l-7.1 1.9-2-7.1c-5-18.1-22.8-30.9-41.5-27.9-21.4 3.4-34.4 24.2-28.8 44.5l19.4 69.9c1.2 4.5 5.9 7.2 10.5 6l70.2-18.2c20.4-5.3 31.9-26.9 24.2-47.1zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-234.7-40.8c3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3l-80-48c-5.1-3-11.4-1.9-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11.1.1 15.5zm242.9 2.5c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11-.1-15.5-3.8-4.4-10.2-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M117.1 384.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 479 124.3 420.8 128 395c.8-6.4-4.6-11.8-10.9-10.9zm-41.2-41.7C40.3 268 53 176.1 114.6 114.6 152.4 76.8 202.6 56 256 56c36.2 0 70.8 9.8 101.2 27.7 3.8-20.3 8-36.1 12-48.3C333.8 17.2 294.9 8 256 8 192.5 8 129.1 32.2 80.6 80.6c-74.1 74.1-91.3 183.4-52 274 12.2-4.1 27.7-8.3 47.3-12.2zm352.3-187.6c45 76.6 34.9 176.9-30.8 242.6-37.8 37.8-88 58.6-141.4 58.6-30.5 0-59.8-7-86.4-19.8-3.9 19.5-8 35-12.2 47.2 31.4 13.6 65 20.6 98.7 20.6 63.5 0 126.9-24.2 175.4-72.6 78.1-78.1 93.1-195.4 45.2-288.6-12.3 4-28.2 8.1-48.5 12zm-33.3-26.9c25.8-3.7 84-13.7 100.9-30.6 21.9-21.9 21.5-57.9-.9-80.3s-58.3-22.8-80.3-.9C397.7 33 387.7 91.2 384 117c-.8 6.4 4.6 11.8 10.9 10.9zm-187 108.3c-3-3-7.2-4.2-11.4-3.2L106 255.7c-5.7 1.4-9.5 6.7-9.1 12.6.5 5.8 5.1 10.5 10.9 11l52.3 4.8 4.8 52.3c.5 5.8 5.2 10.4 11 10.9h.9c5.5 0 10.3-3.7 11.7-9.1l22.6-90.5c1-4.2-.2-8.5-3.2-11.5zm39.7-25.1l90.5-22.6c5.7-1.4 9.5-6.7 9.1-12.6-.5-5.8-5.1-10.5-10.9-11l-52.3-4.8-4.8-52.3c-.5-5.8-5.2-10.4-11-10.9-5.6-.1-11.2 3.4-12.6 9.1L233 196.5c-1 4.1.2 8.4 3.2 11.4 5 5 11.3 3.2 11.4 3.2zm52 88.5c-29.1 29.1-59.7 52.9-83.9 65.4-9.2 4.8-10 17.5-1.7 23.4 38.9 27.7 107 6.2 143.7-30.6S416 253 388.3 214.1c-5.8-8.2-18.5-7.6-23.4 1.7-12.3 24.2-36.2 54.7-65.3 83.8z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-227.9-57.5c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.5 1.9-12.2-4.3-13.2l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6.1 34.9zm259.7-72.7l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6 34.9c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.6 1.8-12.2-4.4-13.2z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M117.1 256.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 351 124.3 292.8 128 267c.8-6.4-4.6-11.8-10.9-10.9zm506.7 30.6c-16.9-16.9-75.1-26.9-100.9-30.6-6.3-.9-11.7 4.5-10.8 10.8 3.7 25.8 13.7 84 30.6 100.9 21.9 21.9 57.9 21.5 80.3-.9 22.3-22.3 22.7-58.3.8-80.2zm-126.6 61.7C463.8 412.3 396.9 456 320 456c-76.9 0-143.8-43.7-177.2-107.6-12.5 37.4-25.2 43.9-28.3 46.5C159.1 460.7 234.5 504 320 504s160.9-43.3 205.5-109.1c-3.2-2.7-15.9-9.2-28.3-46.5zM122.7 224.5C137.9 129.2 220.5 56 320 56c99.5 0 182.1 73.2 197.3 168.5 2.1-.2 5.2-2.4 49.5 7C554.4 106 448.7 8 320 8S85.6 106 73.2 231.4c44.5-9.4 47.1-7.2 49.5-6.9zM320 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zM240 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zM168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zm36.9-281.1c-3.8-4.4-10.3-5.5-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zm-162.9 45.5l-80-48c-5-3-11.4-2-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M152 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm176-52c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M328 180c-25.69 0-55.88 16.92-59.86 42.12-1.75 11.22 11.5 18.24 19.83 10.84l9.55-8.48c14.81-13.19 46.16-13.19 60.97 0l9.55 8.48c8.48 7.43 21.56.25 19.83-10.84C383.88 196.92 353.69 180 328 180zm-160 60c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm185.55 64.64c-25.93 8.3-64.4 13.06-105.55 13.06s-79.62-4.75-105.55-13.06c-9.94-3.13-19.4 5.37-17.71 15.34C132.67 367.13 196.06 400 248 400s115.33-32.87 123.26-80.02c1.68-9.89-7.67-18.48-17.71-15.34zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M556.686 290.542L410.328 64.829C397.001 44.272 374.417 32 349.917 32H56C25.121 32 0 57.122 0 88v8c0 44.112 35.888 80 80 80h196.042l-18.333 48H144c-48.523 0-88 39.477-88 88 0 30.879 25.121 56 56 56h131.552c2.987 0 5.914.549 8.697 1.631L352 408.418V480h224V355.829c0-23.225-6.679-45.801-19.314-65.287zM528 432H400v-23.582c0-19.948-12.014-37.508-30.604-44.736l-99.751-38.788A71.733 71.733 0 0 0 243.552 320H112c-4.411 0-8-3.589-8-8 0-22.056 17.944-40 40-40h113.709c19.767 0 37.786-12.407 44.84-30.873l24.552-64.281c8.996-23.553-8.428-48.846-33.63-48.846H80c-17.645 0-32-14.355-32-32v-8c0-4.411 3.589-8 8-8h293.917c8.166 0 15.693 4.09 20.137 10.942l146.358 225.715A71.84 71.84 0 0 1 528 355.829V432z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M372.57 112.641v-10.825c0-43.612-40.52-76.691-83.039-65.546-25.629-49.5-94.09-47.45-117.982.747C130.269 26.456 89.144 57.945 89.144 102v126.13c-19.953-7.427-43.308-5.068-62.083 8.871-29.355 21.796-35.794 63.333-14.55 93.153L132.48 498.569a32 32 0 0 0 26.062 13.432h222.897c14.904 0 27.835-10.289 31.182-24.813l30.184-130.958A203.637 203.637 0 0 0 448 310.564V179c0-40.62-35.523-71.992-75.43-66.359zm27.427 197.922c0 11.731-1.334 23.469-3.965 34.886L368.707 464h-201.92L51.591 302.303c-14.439-20.27 15.023-42.776 29.394-22.605l27.128 38.079c8.995 12.626 29.031 6.287 29.031-9.283V102c0-25.645 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V67c0-25.663 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V101.125c0-25.672 36.57-24.81 36.57.691V256c0 8.837 7.163 16 16 16h6.857c8.837 0 16-7.163 16-16v-76.309c0-26.242 36.57-25.64 36.57-.691v131.563z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M362.146 191.976c-13.71-21.649-38.761-34.016-65.006-30.341V74c0-40.804-32.811-74-73.141-74-40.33 0-73.14 33.196-73.14 74L160 168l-18.679-78.85C126.578 50.843 83.85 32.11 46.209 47.208 8.735 62.238-9.571 104.963 5.008 142.85l55.757 144.927c-30.557 24.956-43.994 57.809-24.733 92.218l54.853 97.999C102.625 498.97 124.73 512 148.575 512h205.702c30.744 0 57.558-21.44 64.555-51.797l27.427-118.999a67.801 67.801 0 0 0 1.729-15.203L448 256c0-44.956-43.263-77.343-85.854-64.024zM399.987 326c0 1.488-.169 2.977-.502 4.423l-27.427 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H148.575c-6.486 0-12.542-3.621-15.805-9.449l-54.854-98c-4.557-8.141-2.619-18.668 4.508-24.488l26.647-21.764a16 16 0 0 0 4.812-18.139l-64.09-166.549C37.226 92.956 84.37 74.837 96.51 106.389l59.784 155.357A16 16 0 0 0 171.227 272h11.632c8.837 0 16-7.163 16-16V74c0-34.375 50.281-34.43 50.281 0v182c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16v-28c0-25.122 36.567-25.159 36.567 0v28c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16 0-25.12 36.567-25.16 36.567 0v70z\"],\n    \"hand-point-down\": [448, 512, [], \"f0a7\", \"M188.8 512c45.616 0 83.2-37.765 83.2-83.2v-35.647a93.148 93.148 0 0 0 22.064-7.929c22.006 2.507 44.978-3.503 62.791-15.985C409.342 368.1 448 331.841 448 269.299V248c0-60.063-40-98.512-40-127.2v-2.679c4.952-5.747 8-13.536 8-22.12V32c0-17.673-12.894-32-28.8-32H156.8C140.894 0 128 14.327 128 32v64c0 8.584 3.048 16.373 8 22.12v2.679c0 6.964-6.193 14.862-23.668 30.183l-.148.129-.146.131c-9.937 8.856-20.841 18.116-33.253 25.851C48.537 195.798 0 207.486 0 252.8c0 56.928 35.286 92 83.2 92 8.026 0 15.489-.814 22.4-2.176V428.8c0 45.099 38.101 83.2 83.2 83.2zm0-48c-18.7 0-35.2-16.775-35.2-35.2V270.4c-17.325 0-35.2 26.4-70.4 26.4-26.4 0-35.2-20.625-35.2-44 0-8.794 32.712-20.445 56.1-34.926 14.575-9.074 27.225-19.524 39.875-30.799 18.374-16.109 36.633-33.836 39.596-59.075h176.752C364.087 170.79 400 202.509 400 248v21.299c0 40.524-22.197 57.124-61.325 50.601-8.001 14.612-33.979 24.151-53.625 12.925-18.225 19.365-46.381 17.787-61.05 4.95V428.8c0 18.975-16.225 35.2-35.2 35.2zM328 64c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M0 220.8C0 266.416 37.765 304 83.2 304h35.647a93.148 93.148 0 0 0 7.929 22.064c-2.507 22.006 3.503 44.978 15.985 62.791C143.9 441.342 180.159 480 242.701 480H264c60.063 0 98.512-40 127.2-40h2.679c5.747 4.952 13.536 8 22.12 8h64c17.673 0 32-12.894 32-28.8V188.8c0-15.906-14.327-28.8-32-28.8h-64c-8.584 0-16.373 3.048-22.12 8H391.2c-6.964 0-14.862-6.193-30.183-23.668l-.129-.148-.131-.146c-8.856-9.937-18.116-20.841-25.851-33.253C316.202 80.537 304.514 32 259.2 32c-56.928 0-92 35.286-92 83.2 0 8.026.814 15.489 2.176 22.4H83.2C38.101 137.6 0 175.701 0 220.8zm48 0c0-18.7 16.775-35.2 35.2-35.2h158.4c0-17.325-26.4-35.2-26.4-70.4 0-26.4 20.625-35.2 44-35.2 8.794 0 20.445 32.712 34.926 56.1 9.074 14.575 19.524 27.225 30.799 39.875 16.109 18.374 33.836 36.633 59.075 39.596v176.752C341.21 396.087 309.491 432 264 432h-21.299c-40.524 0-57.124-22.197-50.601-61.325-14.612-8.001-24.151-33.979-12.925-53.625-19.365-18.225-17.787-46.381-4.95-61.05H83.2C64.225 256 48 239.775 48 220.8zM448 360c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M428.8 137.6h-86.177a115.52 115.52 0 0 0 2.176-22.4c0-47.914-35.072-83.2-92-83.2-45.314 0-57.002 48.537-75.707 78.784-7.735 12.413-16.994 23.317-25.851 33.253l-.131.146-.129.148C135.662 161.807 127.764 168 120.8 168h-2.679c-5.747-4.952-13.536-8-22.12-8H32c-17.673 0-32 12.894-32 28.8v230.4C0 435.106 14.327 448 32 448h64c8.584 0 16.373-3.048 22.12-8h2.679c28.688 0 67.137 40 127.2 40h21.299c62.542 0 98.8-38.658 99.94-91.145 12.482-17.813 18.491-40.785 15.985-62.791A93.148 93.148 0 0 0 393.152 304H428.8c45.435 0 83.2-37.584 83.2-83.2 0-45.099-38.101-83.2-83.2-83.2zm0 118.4h-91.026c12.837 14.669 14.415 42.825-4.95 61.05 11.227 19.646 1.687 45.624-12.925 53.625 6.524 39.128-10.076 61.325-50.6 61.325H248c-45.491 0-77.21-35.913-120-39.676V215.571c25.239-2.964 42.966-21.222 59.075-39.596 11.275-12.65 21.725-25.3 30.799-39.875C232.355 112.712 244.006 80 252.8 80c23.375 0 44 8.8 44 35.2 0 35.2-26.4 53.075-26.4 70.4h158.4c18.425 0 35.2 16.5 35.2 35.2 0 18.975-16.225 35.2-35.2 35.2zM88 384c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"hand-point-up\": [448, 512, [], \"f0a6\", \"M105.6 83.2v86.177a115.52 115.52 0 0 0-22.4-2.176c-47.914 0-83.2 35.072-83.2 92 0 45.314 48.537 57.002 78.784 75.707 12.413 7.735 23.317 16.994 33.253 25.851l.146.131.148.129C129.807 376.338 136 384.236 136 391.2v2.679c-4.952 5.747-8 13.536-8 22.12v64c0 17.673 12.894 32 28.8 32h230.4c15.906 0 28.8-14.327 28.8-32v-64c0-8.584-3.048-16.373-8-22.12V391.2c0-28.688 40-67.137 40-127.2v-21.299c0-62.542-38.658-98.8-91.145-99.94-17.813-12.482-40.785-18.491-62.791-15.985A93.148 93.148 0 0 0 272 118.847V83.2C272 37.765 234.416 0 188.8 0c-45.099 0-83.2 38.101-83.2 83.2zm118.4 0v91.026c14.669-12.837 42.825-14.415 61.05 4.95 19.646-11.227 45.624-1.687 53.625 12.925 39.128-6.524 61.325 10.076 61.325 50.6V264c0 45.491-35.913 77.21-39.676 120H183.571c-2.964-25.239-21.222-42.966-39.596-59.075-12.65-11.275-25.3-21.725-39.875-30.799C80.712 279.645 48 267.994 48 259.2c0-23.375 8.8-44 35.2-44 35.2 0 53.075 26.4 70.4 26.4V83.2c0-18.425 16.5-35.2 35.2-35.2 18.975 0 35.2 16.225 35.2 35.2zM352 424c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M358.182 179.361c-19.493-24.768-52.679-31.945-79.872-19.098-15.127-15.687-36.182-22.487-56.595-19.629V67c0-36.944-29.736-67-66.286-67S89.143 30.056 89.143 67v161.129c-19.909-7.41-43.272-5.094-62.083 8.872-29.355 21.795-35.793 63.333-14.55 93.152l109.699 154.001C134.632 501.59 154.741 512 176 512h178.286c30.802 0 57.574-21.5 64.557-51.797l27.429-118.999A67.873 67.873 0 0 0 448 326v-84c0-46.844-46.625-79.273-89.818-62.639zM80.985 279.697l27.126 38.079c8.995 12.626 29.031 6.287 29.031-9.283V67c0-25.12 36.571-25.16 36.571 0v175c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16v-35c0-25.12 36.571-25.16 36.571 0v35c0 8.836 7.163 16 16 16H272c8.837 0 16-7.164 16-16v-21c0-25.12 36.571-25.16 36.571 0v21c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16 0-25.121 36.571-25.16 36.571 0v84c0 1.488-.169 2.977-.502 4.423l-27.43 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H176c-5.769 0-11.263-2.878-14.697-7.697l-109.712-154c-14.406-20.223 14.994-42.818 29.394-22.606zM176.143 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.733 0-14-7.163-14-16zm75.428 0v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16zM327 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M408.864 79.052c-22.401-33.898-66.108-42.273-98.813-23.588-29.474-31.469-79.145-31.093-108.334-.022-47.16-27.02-108.71 5.055-110.671 60.806C44.846 105.407 0 140.001 0 187.429v56.953c0 32.741 14.28 63.954 39.18 85.634l97.71 85.081c4.252 3.702 3.11 5.573 3.11 32.903 0 17.673 14.327 32 32 32h252c17.673 0 32-14.327 32-32 0-23.513-1.015-30.745 3.982-42.37l42.835-99.656c6.094-14.177 9.183-29.172 9.183-44.568V146.963c0-52.839-54.314-88.662-103.136-67.911zM464 261.406a64.505 64.505 0 0 1-5.282 25.613l-42.835 99.655c-5.23 12.171-7.883 25.04-7.883 38.25V432H188v-10.286c0-16.37-7.14-31.977-19.59-42.817l-97.71-85.08C56.274 281.255 48 263.236 48 244.381v-56.953c0-33.208 52-33.537 52 .677v41.228a16 16 0 0 0 5.493 12.067l7 6.095A16 16 0 0 0 139 235.429V118.857c0-33.097 52-33.725 52 .677v26.751c0 8.836 7.164 16 16 16h7c8.836 0 16-7.164 16-16v-41.143c0-33.134 52-33.675 52 .677v40.466c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16v-27.429c0-33.03 52-33.78 52 .677v26.751c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16 0-33.146 52-33.613 52 .677v114.445z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M256 480l70-.013c5.114 0 10.231-.583 15.203-1.729l118.999-27.427C490.56 443.835 512 417.02 512 386.277V180.575c0-23.845-13.03-45.951-34.005-57.69l-97.999-54.853c-34.409-19.261-67.263-5.824-92.218 24.733L142.85 37.008c-37.887-14.579-80.612 3.727-95.642 41.201-15.098 37.642 3.635 80.37 41.942 95.112L168 192l-94-9.141c-40.804 0-74 32.811-74 73.14 0 40.33 33.196 73.141 74 73.141h87.635c-3.675 26.245 8.692 51.297 30.341 65.006C178.657 436.737 211.044 480 256 480zm0-48.013c-25.16 0-25.12-36.567 0-36.567 8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16h-28c-25.159 0-25.122-36.567 0-36.567h28c8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16H74c-34.43 0-34.375-50.281 0-50.281h182c8.837 0 16-7.163 16-16v-11.632a16 16 0 0 0-10.254-14.933L106.389 128.51c-31.552-12.14-13.432-59.283 19.222-46.717l166.549 64.091a16.001 16.001 0 0 0 18.139-4.812l21.764-26.647c5.82-7.127 16.348-9.064 24.488-4.508l98 54.854c5.828 3.263 9.449 9.318 9.449 15.805v205.701c0 8.491-5.994 15.804-14.576 17.782l-119.001 27.427a19.743 19.743 0 0 1-4.423.502h-70z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M21.096 381.79l129.092 121.513a32 32 0 0 0 21.932 8.698h237.6c14.17 0 26.653-9.319 30.68-22.904l31.815-107.313A115.955 115.955 0 0 0 477 348.811v-36.839c0-4.051.476-8.104 1.414-12.045l31.73-133.41c10.099-42.412-22.316-82.738-65.544-82.525-4.144-24.856-22.543-47.165-49.85-53.992-35.803-8.952-72.227 12.655-81.25 48.75L296.599 184 274.924 52.01c-8.286-36.07-44.303-58.572-80.304-50.296-29.616 6.804-50.138 32.389-51.882 61.295-42.637.831-73.455 40.563-64.071 81.844l31.04 136.508c-27.194-22.515-67.284-19.992-91.482 5.722-25.376 26.961-24.098 69.325 2.871 94.707zm32.068-61.811l.002-.001c7.219-7.672 19.241-7.98 26.856-.813l53.012 49.894C143.225 378.649 160 371.4 160 357.406v-69.479c0-1.193-.134-2.383-.397-3.546l-34.13-150.172c-5.596-24.617 31.502-32.86 37.054-8.421l30.399 133.757a16 16 0 0 0 15.603 12.454h8.604c10.276 0 17.894-9.567 15.594-19.583l-41.62-181.153c-5.623-24.469 31.39-33.076 37.035-8.508l45.22 196.828A16 16 0 0 0 288.956 272h13.217a16 16 0 0 0 15.522-12.119l42.372-169.49c6.104-24.422 42.962-15.159 36.865 9.217L358.805 252.12c-2.521 10.088 5.115 19.88 15.522 19.88h9.694a16 16 0 0 0 15.565-12.295L426.509 146.6c5.821-24.448 42.797-15.687 36.966 8.802L431.72 288.81a100.094 100.094 0 0 0-2.72 23.162v36.839c0 6.548-.943 13.051-2.805 19.328L397.775 464h-219.31L53.978 346.836c-7.629-7.18-7.994-19.229-.814-26.857z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M519.2 127.9l-47.6-47.6A56.252 56.252 0 0 0 432 64H205.2c-14.8 0-29.1 5.9-39.6 16.3L118 127.9H0v255.7h64c17.6 0 31.8-14.2 31.9-31.7h9.1l84.6 76.4c30.9 25.1 73.8 25.7 105.6 3.8 12.5 10.8 26 15.9 41.1 15.9 18.2 0 35.3-7.4 48.8-24 22.1 8.7 48.2 2.6 64-16.8l26.2-32.3c5.6-6.9 9.1-14.8 10.9-23h57.9c.1 17.5 14.4 31.7 31.9 31.7h64V127.9H519.2zM48 351.6c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16zm390-6.9l-26.1 32.2c-2.8 3.4-7.8 4-11.3 1.2l-23.9-19.4-30 36.5c-6 7.3-15 4.8-18 2.4l-36.8-31.5-15.6 19.2c-13.9 17.1-39.2 19.7-55.3 6.6l-97.3-88H96V175.8h41.9l61.7-61.6c2-.8 3.7-1.5 5.7-2.3H262l-38.7 35.5c-29.4 26.9-31.1 72.3-4.4 101.3 14.8 16.2 61.2 41.2 101.5 4.4l8.2-7.5 108.2 87.8c3.4 2.8 3.9 7.9 1.2 11.3zm106-40.8h-69.2c-2.3-2.8-4.9-5.4-7.7-7.7l-102.7-83.4 12.5-11.4c6.5-6 7-16.1 1-22.6L367 167.1c-6-6.5-16.1-6.9-22.6-1l-55.2 50.6c-9.5 8.7-25.7 9.4-34.6 0-9.3-9.9-8.5-25.1 1.2-33.9l65.6-60.1c7.4-6.8 17-10.5 27-10.5l83.7-.2c2.1 0 4.1.8 5.5 2.3l61.7 61.6H544v128zm48 47.7c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M567.403 235.642L462.323 84.589A48 48 0 0 0 422.919 64H153.081a48 48 0 0 0-39.404 20.589L8.597 235.642A48.001 48.001 0 0 0 0 263.054V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V263.054c0-9.801-3-19.366-8.597-27.412zM153.081 112h269.838l77.913 112H75.168l77.913-112zM528 400H48V272h480v128zm-32-64c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32zm-96 0c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M458.4 64.3C400.6 15.7 311.3 23 256 79.3 200.7 23 111.4 15.6 53.6 64.3-21.6 127.6-10.6 230.8 43 285.5l175.4 178.7c10 10.2 23.4 15.9 37.6 15.9 14.3 0 27.6-5.6 37.6-15.8L469 285.6c53.5-54.7 64.7-157.9-10.6-221.3zm-23.6 187.5L259.4 430.5c-2.4 2.4-4.4 2.4-6.8 0L77.2 251.8c-36.5-37.2-43.9-107.6 7.3-150.7 38.9-32.7 98.9-27.8 136.5 10.5l35 35.7 35-35.7c37.8-38.5 97.8-43.2 136.5-10.6 51.1 43.1 43.5 113.9 7.3 150.8z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M128 244v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12zm140 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm-76 84v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm76 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm180 124v36H0v-36c0-6.627 5.373-12 12-12h19.5V85.035C31.5 73.418 42.245 64 55.5 64H144V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v40h88.5c13.255 0 24 9.418 24 21.035V464H436c6.627 0 12 5.373 12 12zM79.5 463H192v-67c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v67h112.5V112H304v24c0 13.255-10.745 24-24 24H168c-13.255 0-24-10.745-24-24v-24H79.5v351zM266 64h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M368 48h4c6.627 0 12-5.373 12-12V12c0-6.627-5.373-12-12-12H12C5.373 0 0 5.373 0 12v24c0 6.627 5.373 12 12 12h4c0 80.564 32.188 165.807 97.18 208C47.899 298.381 16 383.9 16 464h-4c-6.627 0-12 5.373-12 12v24c0 6.627 5.373 12 12 12h360c6.627 0 12-5.373 12-12v-24c0-6.627-5.373-12-12-12h-4c0-80.564-32.188-165.807-97.18-208C336.102 213.619 368 128.1 368 48zM64 48h256c0 101.62-57.307 184-128 184S64 149.621 64 48zm256 416H64c0-101.62 57.308-184 128-184s128 82.38 128 184z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm0 464H48V48h288v416zM144 112h96c8.8 0 16-7.2 16-16s-7.2-16-16-16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16zm48 176c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H303.2c.9-4.5.8 3.6.8-22.4 0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6 0 26-.2 17.9.8 22.4H48V144h480v288zm-168-80h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm-168 96c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 336H54a6 6 0 0 1-6-6V118a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v276a6 6 0 0 1-6 6zM128 152c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zM96 352h320v-80l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L192 304l-39.515-39.515c-4.686-4.686-12.284-4.686-16.971 0L96 304v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v48H54a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6v-10h48zm42-336H150a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6V86a6 6 0 0 0-6-6zm6-48c26.51 0 48 21.49 48 48v256c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h384zM264 144c0 22.091-17.909 40-40 40s-40-17.909-40-40 17.909-40 40-40 40 17.909 40 40zm-72 96l39.515-39.515c4.686-4.686 12.284-4.686 16.971 0L288 240l103.515-103.515c4.686-4.686 12.284-4.686 16.971 0L480 208v80H192v-48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm8 336c0 4.411-3.589 8-8 8H48c-4.411 0-8-3.589-8-8V112c0-4.411 3.589-8 8-8h480c4.411 0 8 3.589 8 8v288zM170 270v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-336 82v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm384 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zM122 188v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-98 158v-16c0-6.627-5.373-12-12-12H180c-6.627 0-12 5.373-12 12v16c0 6.627 5.373 12 12 12h216c6.627 0 12-5.373 12-12z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm136 132c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M168 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm56-148c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zm24-156c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M304 308.5c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36 21.7-9.1 35.1-23.4 35.1-36.4zm70.5-83.5l9.5 8.5c3.8 3.3 9.3 4 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 5.8 3.1 11.2.7 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0zM136 208.5c0 17.7 14.3 32 32 32s32-14.3 32-32-14.3-32-32-32-32 14.3-32 32zm365.1 194c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zM334 436.3c-26.1 12.5-55.2 19.7-86 19.7-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200c0 22.1-3.7 43.3-10.4 63.2 9 6.4 17 14.2 22.6 23.9 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-2.5-7.3 4.3 17.2-13.4-46.8z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 224c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm-160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 152c-23.8 0-52.7 29.3-56 71.4-.7 8.6 10.8 11.9 14.9 4.5l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.1-42.1-32-71.4-55.8-71.4zm-201 75.9l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.6 8.5 10.9 11.9 15.1 4.5zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM343.6 196l33.6-40.3c8.6-10.3-3.8-24.8-15.4-18l-80 48c-7.8 4.7-7.8 15.9 0 20.6l80 48c11.5 6.8 24-7.6 15.4-18L343.6 196zm-209.4 58.3l80-48c7.8-4.7 7.8-15.9 0-20.6l-80-48c-11.6-6.9-24 7.7-15.4 18l33.6 40.3-33.6 40.3c-8.7 10.4 3.8 24.8 15.4 18zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6C68.8 359.6 48 309.4 48 256s20.8-103.6 58.6-141.4C144.4 76.8 194.6 56 248 56s103.6 20.8 141.4 58.6c37.8 37.8 58.6 88 58.6 141.4s-20.8 103.6-58.6 141.4zM328 164c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1zm-160 60c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M484.112 27.889C455.989-.233 416.108-8.057 387.059 8.865 347.604 31.848 223.504-41.111 91.196 91.197-41.277 223.672 31.923 347.472 8.866 387.058c-16.922 29.051-9.1 68.932 19.022 97.054 28.135 28.135 68.011 35.938 97.057 19.021 39.423-22.97 163.557 49.969 295.858-82.329 132.474-132.477 59.273-256.277 82.331-295.861 16.922-29.05 9.1-68.931-19.022-97.054zm-22.405 72.894c-38.8 66.609 45.6 165.635-74.845 286.08-120.44 120.443-219.475 36.048-286.076 74.843-22.679 13.207-64.035-27.241-50.493-50.488 38.8-66.609-45.6-165.635 74.845-286.08C245.573 4.702 344.616 89.086 411.219 50.292c22.73-13.24 64.005 27.288 50.488 50.491zm-169.861 8.736c1.37 10.96-6.404 20.957-17.365 22.327-54.846 6.855-135.779 87.787-142.635 142.635-1.373 10.989-11.399 18.734-22.326 17.365-10.961-1.37-18.735-11.366-17.365-22.326 9.162-73.286 104.167-168.215 177.365-177.365 10.953-1.368 20.956 6.403 22.326 17.364z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 504c136.967 0 248-111.033 248-248S392.967 8 256 8 8 119.033 8 256s111.033 248 248 248zm-103.398-76.72l53.411-53.411c31.806 13.506 68.128 13.522 99.974 0l53.411 53.411c-63.217 38.319-143.579 38.319-206.796 0zM336 256c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zm91.28 103.398l-53.411-53.411c13.505-31.806 13.522-68.128 0-99.974l53.411-53.411c38.319 63.217 38.319 143.579 0 206.796zM359.397 84.72l-53.411 53.411c-31.806-13.505-68.128-13.522-99.973 0L152.602 84.72c63.217-38.319 143.579-38.319 206.795 0zM84.72 152.602l53.411 53.411c-13.506 31.806-13.522 68.128 0 99.974L84.72 359.398c-38.319-63.217-38.319-143.579 0-206.796z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M176 80c-52.94 0-96 43.06-96 96 0 8.84 7.16 16 16 16s16-7.16 16-16c0-35.3 28.72-64 64-64 8.84 0 16-7.16 16-16s-7.16-16-16-16zM96.06 459.17c0 3.15.93 6.22 2.68 8.84l24.51 36.84c2.97 4.46 7.97 7.14 13.32 7.14h78.85c5.36 0 10.36-2.68 13.32-7.14l24.51-36.84c1.74-2.62 2.67-5.7 2.68-8.84l.05-43.18H96.02l.04 43.18zM176 0C73.72 0 0 82.97 0 176c0 44.37 16.45 84.85 43.56 115.78 16.64 18.99 42.74 58.8 52.42 92.16v.06h48v-.12c-.01-4.77-.72-9.51-2.15-14.07-5.59-17.81-22.82-64.77-62.17-109.67-20.54-23.43-31.52-53.15-31.61-84.14-.2-73.64 59.67-128 127.95-128 70.58 0 128 57.42 128 128 0 30.97-11.24 60.85-31.65 84.14-39.11 44.61-56.42 91.47-62.1 109.46a47.507 47.507 0 0 0-2.22 14.3v.1h48v-.05c9.68-33.37 35.78-73.18 52.42-92.16C335.55 260.85 352 220.37 352 176 352 78.8 273.2 0 176 0z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v340a6 6 0 0 1-6 6zm-42-92v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm-252 12c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36z\"],\n    \"map\": [576, 512, [], \"f279\", \"M560.02 32c-1.96 0-3.98.37-5.96 1.16L384.01 96H384L212 35.28A64.252 64.252 0 0 0 191.76 32c-6.69 0-13.37 1.05-19.81 3.14L20.12 87.95A32.006 32.006 0 0 0 0 117.66v346.32C0 473.17 7.53 480 15.99 480c1.96 0 3.97-.37 5.96-1.16L192 416l172 60.71a63.98 63.98 0 0 0 40.05.15l151.83-52.81A31.996 31.996 0 0 0 576 394.34V48.02c0-9.19-7.53-16.02-15.98-16.02zM224 90.42l128 45.19v285.97l-128-45.19V90.42zM48 418.05V129.07l128-44.53v286.2l-.64.23L48 418.05zm480-35.13l-128 44.53V141.26l.64-.24L528 93.95v288.97z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm8 144H160c-13.2 0-24 10.8-24 24s10.8 24 24 24h176c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm88-304c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm0 112c-22.1 0-40-17.9-40-40 0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40zm-104-40c0-39.8-32.2-72-72-72s-72 32.2-72 72 32.2 72 72 72 72-32.2 72-72zm-112 0c0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40s-40-17.9-40-40zm192 128H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M108 284c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h232c6.6 0 12 5.4 12 12v32c0 6.6-5.4 12-12 12H108zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M320 144c-53.02 0-96 50.14-96 112 0 61.85 42.98 112 96 112 53 0 96-50.13 96-112 0-61.86-42.98-112-96-112zm40 168c0 4.42-3.58 8-8 8h-64c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h16v-55.44l-.47.31a7.992 7.992 0 0 1-11.09-2.22l-8.88-13.31a7.992 7.992 0 0 1 2.22-11.09l15.33-10.22a23.99 23.99 0 0 1 13.31-4.03H328c4.42 0 8 3.58 8 8v88h16c4.42 0 8 3.58 8 8v16zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zm-16 272c-35.35 0-64 28.65-64 64H112c0-35.35-28.65-64-64-64V176c35.35 0 64-28.65 64-64h416c0 35.35 28.65 64 64 64v160z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M279.135 512c78.756 0 150.982-35.804 198.844-94.775 28.27-34.831-2.558-85.722-46.249-77.401-82.348 15.683-158.272-47.268-158.272-130.792 0-48.424 26.06-92.292 67.434-115.836 38.745-22.05 28.999-80.788-15.022-88.919A257.936 257.936 0 0 0 279.135 0c-141.36 0-256 114.575-256 256 0 141.36 114.576 256 256 256zm0-464c12.985 0 25.689 1.201 38.016 3.478-54.76 31.163-91.693 90.042-91.693 157.554 0 113.848 103.641 199.2 215.252 177.944C402.574 433.964 344.366 464 279.135 464c-114.875 0-208-93.125-208-208s93.125-208 208-208z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H112c-20.858 0-38.643 13.377-45.248 32H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h496c13.255 0 24-10.745 24-24V88c0-13.255-10.745-24-24-24zM48 392V144h16v248c0 4.411-3.589 8-8 8s-8-3.589-8-8zm480 8H111.422c.374-2.614.578-5.283.578-8V112h416v288zM172 280h136c6.627 0 12-5.373 12-12v-96c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v96c0 6.627 5.373 12 12 12zm28-80h80v40h-80v-40zm-40 140v-24c0-6.627 5.373-12 12-12h136c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H172c-6.627 0-12-5.373-12-12zm192 0v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0-144v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0 72v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M500 128c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v256H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V128h12zm-52-64h32v32h-32V64zM32 64h32v32H32V64zm32 384H32v-32h32v32zm416 0h-32v-32h32v32zm-40-64h-12c-6.627 0-12 5.373-12 12v12H96v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h12v256zm-36-192h-84v-52c0-6.628-5.373-12-12-12H108c-6.627 0-12 5.372-12 12v168c0 6.628 5.373 12 12 12h84v52c0 6.628 5.373 12 12 12h200c6.627 0 12-5.372 12-12V204c0-6.628-5.373-12-12-12zm-268-24h144v112H136V168zm240 176H232v-24h76c6.627 0 12-5.372 12-12v-76h56v112z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M564 224c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12h-88v-24h12c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v160H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h88v24h-12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V224h12zM352 64h32v32h-32V64zm0 256h32v32h-32v-32zM64 352H32v-32h32v32zm0-256H32V64h32v32zm32 216v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h12v160h-12c-6.627 0-12 5.373-12 12v12H96zm128 136h-32v-32h32v32zm280-64h-12c-6.627 0-12 5.373-12 12v12H256v-12c0-6.627-5.373-12-12-12h-12v-24h88v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12v-88h88v12c0 6.627 5.373 12 12 12h12v160zm40 64h-32v-32h32v32zm0-256h-32v-32h32v32z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M440 6.5L24 246.4c-34.4 19.9-31.1 70.8 5.7 85.9L144 379.6V464c0 46.4 59.2 65.5 86.6 28.6l43.8-59.1 111.9 46.2c5.9 2.4 12.1 3.6 18.3 3.6 8.2 0 16.3-2.1 23.6-6.2 12.8-7.2 21.6-20 23.9-34.5l59.4-387.2c6.1-40.1-36.9-68.8-71.5-48.9zM192 464v-64.6l36.6 15.1L192 464zm212.6-28.7l-153.8-63.5L391 169.5c10.7-15.5-9.5-33.5-23.7-21.2L155.8 332.6 48 288 464 48l-59.4 387.3z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm96-280v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16zm-112 0v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M371.7 238l-176-107c-15.8-8.8-35.7 2.5-35.7 21v208c0 18.4 19.8 29.8 35.7 21l176-101c16.4-9.1 16.4-32.8 0-42zM504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M352 240v32c0 6.6-5.4 12-12 12h-88v88c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-88h-88c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h88v-88c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v88h88c6.6 0 12 5.4 12 12zm96-160v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 448c-110.532 0-200-89.431-200-200 0-110.495 89.472-200 200-200 110.491 0 200 89.471 200 200 0 110.53-89.431 200-200 200zm107.244-255.2c0 67.052-72.421 68.084-72.421 92.863V300c0 6.627-5.373 12-12 12h-45.647c-6.627 0-12-5.373-12-12v-8.659c0-35.745 27.1-50.034 47.579-61.516 17.561-9.845 28.324-16.541 28.324-29.579 0-17.246-21.999-28.693-39.784-28.693-23.189 0-33.894 10.977-48.942 29.969-4.057 5.12-11.46 6.071-16.666 2.124l-27.824-21.098c-5.107-3.872-6.251-11.066-2.644-16.363C184.846 131.491 214.94 112 261.794 112c49.071 0 101.45 38.304 101.45 88.8zM298 368c0 23.159-18.841 42-42 42s-42-18.841-42-42 18.841-42 42-42 42 18.841 42 42z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm110.442-81.791c-53.046-96.284-50.25-91.468-53.271-96.085 24.267-13.879 39.482-41.563 39.482-73.176 0-52.503-30.247-85.252-101.498-85.252h-78.667c-6.617 0-12 5.383-12 12V380c0 6.617 5.383 12 12 12h38.568c6.617 0 12-5.383 12-12v-83.663h31.958l47.515 89.303a11.98 11.98 0 0 0 10.593 6.36h42.81c9.14 0 14.914-9.799 10.51-17.791zM256.933 239.906h-33.875v-64.14h27.377c32.417 0 38.929 12.133 38.929 31.709-.001 20.913-11.518 32.431-32.431 32.431z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm144 386.4V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v151.4C315.5 447 282.8 456 248 456s-67.5-9-96-24.6V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v114.4c-34.6-36-56-84.7-56-138.4 0-110.3 89.7-200 200-200s200 89.7 200 200c0 53.7-21.4 102.5-56 138.4zM205.8 234.5c4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.3 7.9 4.8 13.7 1.6zM344 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.5 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm-96 92c-30.9 0-56 28.7-56 64s25.1 64 56 64 56-28.7 56-64-25.1-64-56-64z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm8-152c-13.2 0-24 10.8-24 24s10.8 24 24 24c23.8 0 46.3 10.5 61.6 28.8 8.1 9.8 23.2 11.9 33.8 3.1 10.2-8.5 11.6-23.6 3.1-33.8C330 320.8 294.1 304 256 304zm-88-64c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-165.6 98.8C151 290.1 126 325.4 126 342.9c0 22.7 18.8 41.1 42 41.1s42-18.4 42-41.1c0-17.5-25-52.8-36.4-68.1-2.8-3.7-8.4-3.7-11.2 0z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM272 80v80H144V80h128zm122 352H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h42v104c0 13.255 10.745 24 24 24h176c13.255 0 24-10.745 24-24V83.882l78.243 78.243a6 6 0 0 1 1.757 4.243V426a6 6 0 0 1-6 6zM224 232c-48.523 0-88 39.477-88 88s39.477 88 88 88 88-39.477 88-88-39.477-88-88-88zm0 128c-22.056 0-40-17.944-40-40s17.944-40 40-40 40 17.944 40 40-17.944 40-40 40z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M561.938 158.06L417.94 14.092C387.926-15.922 336 5.097 336 48.032v57.198c-42.45 1.88-84.03 6.55-120.76 17.99-35.17 10.95-63.07 27.58-82.91 49.42C108.22 199.2 96 232.6 96 271.94c0 61.697 33.178 112.455 84.87 144.76 37.546 23.508 85.248-12.651 71.02-55.74-15.515-47.119-17.156-70.923 84.11-78.76V336c0 42.993 51.968 63.913 81.94 33.94l143.998-144c18.75-18.74 18.75-49.14 0-67.88zM384 336V232.16C255.309 234.082 166.492 255.35 206.31 376 176.79 357.55 144 324.08 144 271.94c0-109.334 129.14-118.947 240-119.85V48l144 144-144 144zm24.74 84.493a82.658 82.658 0 0 0 20.974-9.303c7.976-4.952 18.286.826 18.286 10.214V464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h132c6.627 0 12 5.373 12 12v4.486c0 4.917-2.987 9.369-7.569 11.152-13.702 5.331-26.396 11.537-38.05 18.585a12.138 12.138 0 0 1-6.28 1.777H54a6 6 0 0 0-6 6v340a6 6 0 0 0 6 6h340a6 6 0 0 0 6-6v-25.966c0-5.37 3.579-10.059 8.74-11.541z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm4 72.6c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.1-8.4-25.3-7.1-33.8 3.1z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm84-143.4c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.6-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.2-8.4-25.3-7.1-33.8 3.1zM136.5 211c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.4 1.1 7.4-.5 9.3-3.7l9.5-17zM328 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm117.8-146.4c-10.2-8.5-25.3-7.1-33.8 3.1-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-60c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.1 355.2l-39.2-23 34.1-9.3c8.4-2.3 13.4-11.1 11.1-19.6l-4.1-15.5c-2.2-8.5-10.9-13.6-19.3-11.3L343 298.2 271.2 256l71.9-42.2 79.7 21.7c8.4 2.3 17-2.8 19.3-11.3l4.1-15.5c2.2-8.5-2.7-17.3-11.1-19.6l-34.1-9.3 39.2-23c7.5-4.4 10.1-14.2 5.8-21.9l-7.9-13.9c-4.3-7.7-14-10.3-21.5-5.9l-39.2 23 9.1-34.7c2.2-8.5-2.7-17.3-11.1-19.6l-15.2-4.1c-8.4-2.3-17 2.8-19.3 11.3l-21.3 81-71.9 42.2v-84.5L306 70.4c6.1-6.2 6.1-16.4 0-22.6l-11.1-11.3c-6.1-6.2-16.1-6.2-22.2 0l-24.9 25.4V16c0-8.8-7-16-15.7-16h-15.7c-8.7 0-15.7 7.2-15.7 16v46.1l-24.9-25.4c-6.1-6.2-16.1-6.2-22.2 0L142.1 48c-6.1 6.2-6.1 16.4 0 22.6l58.3 59.3v84.5l-71.9-42.2-21.3-81c-2.2-8.5-10.9-13.6-19.3-11.3L72.7 84c-8.4 2.3-13.4 11.1-11.1 19.6l9.1 34.7-39.2-23c-7.5-4.4-17.1-1.8-21.5 5.9l-7.9 13.9c-4.3 7.7-1.8 17.4 5.8 21.9l39.2 23-34.1 9.1c-8.4 2.3-13.4 11.1-11.1 19.6L6 224.2c2.2 8.5 10.9 13.6 19.3 11.3l79.7-21.7 71.9 42.2-71.9 42.2-79.7-21.7c-8.4-2.3-17 2.8-19.3 11.3l-4.1 15.5c-2.2 8.5 2.7 17.3 11.1 19.6l34.1 9.3-39.2 23c-7.5 4.4-10.1 14.2-5.8 21.9L10 391c4.3 7.7 14 10.3 21.5 5.9l39.2-23-9.1 34.7c-2.2 8.5 2.7 17.3 11.1 19.6l15.2 4.1c8.4 2.3 17-2.8 19.3-11.3l21.3-81 71.9-42.2v84.5l-58.3 59.3c-6.1 6.2-6.1 16.4 0 22.6l11.1 11.3c6.1 6.2 16.1 6.2 22.2 0l24.9-25.4V496c0 8.8 7 16 15.7 16h15.7c8.7 0 15.7-7.2 15.7-16v-46.1l24.9 25.4c6.1 6.2 16.1 6.2 22.2 0l11.1-11.3c6.1-6.2 6.1-16.4 0-22.6l-58.3-59.3v-84.5l71.9 42.2 21.3 81c2.2 8.5 10.9 13.6 19.3 11.3L375 428c8.4-2.3 13.4-11.1 11.1-19.6l-9.1-34.7 39.2 23c7.5 4.4 17.1 1.8 21.5-5.9l7.9-13.9c4.6-7.5 2.1-17.3-5.5-21.7z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h340c3.3 0 6 2.7 6 6v340c0 3.3-2.7 6-6 6z\"],\n    \"star\": [576, 512, [], \"f005\", \"M528.1 171.5L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6zM388.6 312.3l23.7 138.4L288 385.4l-124.3 65.3 23.7-138.4-100.6-98 139-20.2 62.2-126 62.2 126 139 20.2-100.6 98z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 385.3l-124.3 65.4 23.7-138.4-100.6-98 139-20.2 62.2-126V0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6v-54.3z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M448 348.106V80c0-26.51-21.49-48-48-48H48C21.49 32 0 53.49 0 80v351.988c0 26.51 21.49 48 48 48h268.118a48 48 0 0 0 33.941-14.059l83.882-83.882A48 48 0 0 0 448 348.106zm-128 80v-76.118h76.118L320 428.106zM400 80v223.988H296c-13.255 0-24 10.745-24 24v104H48V80h352z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm296-80v160c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M494.2 221.9l-59.8-40.5 13.7-71c2.6-13.2-1.6-26.8-11.1-36.4-9.6-9.5-23.2-13.7-36.2-11.1l-70.9 13.7-40.4-59.9c-15.1-22.3-51.9-22.3-67 0l-40.4 59.9-70.8-13.7C98 60.4 84.5 64.5 75 74.1c-9.5 9.6-13.7 23.1-11.1 36.3l13.7 71-59.8 40.5C6.6 229.5 0 242 0 255.5s6.7 26 17.8 33.5l59.8 40.5-13.7 71c-2.6 13.2 1.6 26.8 11.1 36.3 9.5 9.5 22.9 13.7 36.3 11.1l70.8-13.7 40.4 59.9C230 505.3 242.6 512 256 512s26-6.7 33.5-17.8l40.4-59.9 70.9 13.7c13.4 2.7 26.8-1.6 36.3-11.1 9.5-9.5 13.6-23.1 11.1-36.3l-13.7-71 59.8-40.5c11.1-7.5 17.8-20.1 17.8-33.5-.1-13.6-6.7-26.1-17.9-33.7zm-112.9 85.6l17.6 91.2-91-17.6L256 458l-51.9-77-90.9 17.6 17.6-91.2-76.8-52 76.8-52-17.6-91.2 91 17.6L256 53l51.9 76.9 91-17.6-17.6 91.1 76.8 52-76.8 52.1zM256 152c-57.3 0-104 46.7-104 104s46.7 104 104 104 104-46.7 104-104-46.7-104-104-104zm0 160c-30.9 0-56-25.1-56-56s25.1-56 56-56 56 25.1 56 56-25.1 56-56 56z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-176c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm-48-72c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M466.27 225.31c4.674-22.647.864-44.538-8.99-62.99 2.958-23.868-4.021-48.565-17.34-66.99C438.986 39.423 404.117 0 327 0c-7 0-15 .01-22.22.01C201.195.01 168.997 40 128 40h-10.845c-5.64-4.975-13.042-8-21.155-8H32C14.327 32 0 46.327 0 64v240c0 17.673 14.327 32 32 32h64c11.842 0 22.175-6.438 27.708-16h7.052c19.146 16.953 46.013 60.653 68.76 83.4 13.667 13.667 10.153 108.6 71.76 108.6 57.58 0 95.27-31.936 95.27-104.73 0-18.41-3.93-33.73-8.85-46.54h36.48c48.602 0 85.82-41.565 85.82-85.58 0-19.15-4.96-34.99-13.73-49.84zM64 296c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm330.18 16.73H290.19c0 37.82 28.36 55.37 28.36 94.54 0 23.75 0 56.73-47.27 56.73-18.91-18.91-9.46-66.18-37.82-94.54C206.9 342.89 167.28 272 138.92 272H128V85.83c53.611 0 100.001-37.82 171.64-37.82h37.82c35.512 0 60.82 17.12 53.12 65.9 15.2 8.16 26.5 36.44 13.94 57.57 21.581 20.384 18.699 51.065 5.21 65.62 9.45 0 22.36 18.91 22.27 37.81-.09 18.91-16.71 37.82-37.82 37.82z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M466.27 286.69C475.04 271.84 480 256 480 236.85c0-44.015-37.218-85.58-85.82-85.58H357.7c4.92-12.81 8.85-28.13 8.85-46.54C366.55 31.936 328.86 0 271.28 0c-61.607 0-58.093 94.933-71.76 108.6-22.747 22.747-49.615 66.447-68.76 83.4H32c-17.673 0-32 14.327-32 32v240c0 17.673 14.327 32 32 32h64c14.893 0 27.408-10.174 30.978-23.95 44.509 1.001 75.06 39.94 177.802 39.94 7.22 0 15.22.01 22.22.01 77.117 0 111.986-39.423 112.94-95.33 13.319-18.425 20.299-43.122 17.34-66.99 9.854-18.452 13.664-40.343 8.99-62.99zm-61.75 53.83c12.56 21.13 1.26 49.41-13.94 57.57 7.7 48.78-17.608 65.9-53.12 65.9h-37.82c-71.639 0-118.029-37.82-171.64-37.82V240h10.92c28.36 0 67.98-70.89 94.54-97.46 28.36-28.36 18.91-75.63 37.82-94.54 47.27 0 47.27 32.98 47.27 56.73 0 39.17-28.36 56.72-28.36 94.54h103.99c21.11 0 37.73 18.91 37.82 37.82.09 18.9-12.82 37.81-22.27 37.81 13.489 14.555 16.371 45.236-5.21 65.62zM88 432c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm101.8-262.2L295.6 256l62.2 62.2c4.7 4.7 4.7 12.3 0 17l-22.6 22.6c-4.7 4.7-12.3 4.7-17 0L256 295.6l-62.2 62.2c-4.7 4.7-12.3 4.7-17 0l-22.6-22.6c-4.7-4.7-4.7-12.3 0-17l62.2-62.2-62.2-62.2c-4.7-4.7-4.7-12.3 0-17l22.6-22.6c4.7-4.7 12.3-4.7 17 0l62.2 62.2 62.2-62.2c4.7-4.7 12.3-4.7 17 0l22.6 22.6c4.7 4.7 4.7 12.3 0 17z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm129.1-303.8c-3.8-4.4-10.3-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.8 1.6 15.3-2.5 3.8-4.5 3.9-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zM220 208c0-4.2-2.2-8.1-5.8-10.3l-80-48c-5-3-11.5-1.9-15.3 2.5-3.8 4.5-3.9 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.5 4.1 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3zm28 64c-45.4 0-100.9 38.3-107.8 93.3-1.5 11.8 6.9 21.6 15.5 17.9C178.4 373.5 212 368 248 368s69.6 5.5 92.3 15.2c8.5 3.7 17-6 15.5-17.9-6.9-55-62.4-93.3-107.8-93.3z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M268 416h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12zM432 80h-82.41l-34-56.7A48 48 0 0 0 274.41 0H173.59a48 48 0 0 0-41.16 23.3L98.41 80H16A16 16 0 0 0 0 96v16a16 16 0 0 0 16 16h16v336a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128h16a16 16 0 0 0 16-16V96a16 16 0 0 0-16-16zM171.84 50.91A6 6 0 0 1 177 48h94a6 6 0 0 1 5.15 2.91L293.61 80H154.39zM368 464H80V128h288zm-212-48h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12z\"],\n    \"user\": [448, 512, [], \"f007\", \"M313.6 304c-28.7 0-42.5 16-89.6 16-47.1 0-60.8-16-89.6-16C60.2 304 0 364.2 0 438.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-25.6c0-74.2-60.2-134.4-134.4-134.4zM400 464H48v-25.6c0-47.6 38.8-86.4 86.4-86.4 14.6 0 38.3 16 89.6 16 51.7 0 74.9-16 89.6-16 47.6 0 86.4 38.8 86.4 86.4V464zM224 288c79.5 0 144-64.5 144-144S303.5 0 224 0 80 64.5 80 144s64.5 144 144 144zm0-240c52.9 0 96 43.1 96 96s-43.1 96-96 96-96-43.1-96-96 43.1-96 96-96z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 104c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96zm0 144c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-240C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-49.7 0-95.1-18.3-130.1-48.4 14.9-23 40.4-38.6 69.6-39.5 20.8 6.4 40.6 9.6 60.5 9.6s39.7-3.1 60.5-9.6c29.2 1 54.7 16.5 69.6 39.5-35 30.1-80.4 48.4-130.1 48.4zm162.7-84.1c-24.4-31.4-62.1-51.9-105.1-51.9-10.2 0-26 9.6-57.6 9.6-31.5 0-47.4-9.6-57.6-9.6-42.9 0-80.6 20.5-105.1 51.9C61.9 339.2 48 299.2 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 43.2-13.9 83.2-37.3 115.9z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v340zM356.5 194.6L295.1 256l61.4 61.4c4.6 4.6 4.6 12.1 0 16.8l-22.3 22.3c-4.6 4.6-12.1 4.6-16.8 0L256 295.1l-61.4 61.4c-4.6 4.6-12.1 4.6-16.8 0l-22.3-22.3c-4.6-4.6-4.6-12.1 0-16.8l61.4-61.4-61.4-61.4c-4.6-4.6-4.6-12.1 0-16.8l22.3-22.3c4.6-4.6 12.1-4.6 16.8 0l61.4 61.4 61.4-61.4c4.6-4.6 12.1-4.6 16.8 0l22.3 22.3c4.7 4.6 4.7 12.1 0 16.8z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V192h416v234z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M480 480H32c-17.7 0-32-14.3-32-32s14.3-32 32-32h448c17.7 0 32 14.3 32 32s-14.3 32-32 32z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M464 0H144c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v320c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h48c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-96 464H48V256h320v208zm96-96h-48V144c0-26.5-21.5-48-48-48H144V48h320v320z\"]\n  };\n\n  bunker(function () {\n    defineIcons('far', icons);\n  });\n\n}());\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"ad\": [512, 512, [], \"f641\", \"M157.52 272h36.96L176 218.78 157.52 272zM352 256c-13.23 0-24 10.77-24 24s10.77 24 24 24 24-10.77 24-24-10.77-24-24-24zM464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM250.58 352h-16.94c-6.81 0-12.88-4.32-15.12-10.75L211.15 320h-70.29l-7.38 21.25A16 16 0 0 1 118.36 352h-16.94c-11.01 0-18.73-10.85-15.12-21.25L140 176.12A23.995 23.995 0 0 1 162.67 160h26.66A23.99 23.99 0 0 1 212 176.13l53.69 154.62c3.61 10.4-4.11 21.25-15.11 21.25zM424 336c0 8.84-7.16 16-16 16h-16c-4.85 0-9.04-2.27-11.98-5.68-8.62 3.66-18.09 5.68-28.02 5.68-39.7 0-72-32.3-72-72s32.3-72 72-72c8.46 0 16.46 1.73 24 4.42V176c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v160z\"],\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-228-32c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H118.4C106 384 96 375.4 96 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-352 96c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H86.4C74 384 64 375.4 64 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2zM512 312c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"adjust\": [512, 512, [], \"f042\", \"M8 256c0 136.966 111.033 248 248 248s248-111.034 248-248S392.966 8 256 8 8 119.033 8 256zm248 184V72c101.705 0 184 82.311 184 184 0 101.705-82.311 184-184 184z\"],\n    \"air-freshener\": [384, 512, [], \"f5d0\", \"M378.94 321.41L284.7 224h49.22c15.3 0 23.66-16.6 13.86-27.53L234.45 69.96c3.43-6.61 5.55-14 5.55-21.96 0-26.51-21.49-48-48-48s-48 21.49-48 48c0 7.96 2.12 15.35 5.55 21.96L36.22 196.47C26.42 207.4 34.78 224 50.08 224H99.3L5.06 321.41C-6.69 333.56 3.34 352 21.7 352H160v32H48c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h288c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16H224v-32h138.3c18.36 0 28.39-18.44 16.64-30.59zM192 31.98c8.85 0 16.02 7.17 16.02 16.02 0 8.84-7.17 16.02-16.02 16.02S175.98 56.84 175.98 48c0-8.85 7.17-16.02 16.02-16.02zM304 432v32H80v-32h224z\"],\n    \"align-center\": [448, 512, [], \"f037\", \"M432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM108.1 96h231.81A12.09 12.09 0 0 0 352 83.9V44.09A12.09 12.09 0 0 0 339.91 32H108.1A12.09 12.09 0 0 0 96 44.09V83.9A12.1 12.1 0 0 0 108.1 96zm231.81 256A12.09 12.09 0 0 0 352 339.9v-39.81A12.09 12.09 0 0 0 339.91 288H108.1A12.09 12.09 0 0 0 96 300.09v39.81a12.1 12.1 0 0 0 12.1 12.1z\"],\n    \"align-justify\": [448, 512, [], \"f039\", \"M432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"align-left\": [448, 512, [], \"f036\", \"M12.83 352h262.34A12.82 12.82 0 0 0 288 339.17v-38.34A12.82 12.82 0 0 0 275.17 288H12.83A12.82 12.82 0 0 0 0 300.83v38.34A12.82 12.82 0 0 0 12.83 352zm0-256h262.34A12.82 12.82 0 0 0 288 83.17V44.83A12.82 12.82 0 0 0 275.17 32H12.83A12.82 12.82 0 0 0 0 44.83v38.34A12.82 12.82 0 0 0 12.83 96zM432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"align-right\": [448, 512, [], \"f038\", \"M16 224h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm416 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-384H172.83A12.82 12.82 0 0 0 160 44.83v38.34A12.82 12.82 0 0 0 172.83 96h262.34A12.82 12.82 0 0 0 448 83.17V44.83A12.82 12.82 0 0 0 435.17 32zm0 256H172.83A12.82 12.82 0 0 0 160 300.83v38.34A12.82 12.82 0 0 0 172.83 352h262.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288z\"],\n    \"allergies\": [448, 512, [], \"f461\", \"M416 112c-17.6 0-32 14.4-32 32v72c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32s-32 14.4-32 32v152c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V32c0-17.6-14.4-32-32-32s-32 14.4-32 32v184c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32S96 46.4 96 64v241l-23.6-32.5c-13-17.9-38-21.8-55.9-8.8s-21.8 38-8.8 55.9l125.6 172.7c9 12.4 23.5 19.8 38.8 19.8h197.6c22.3 0 41.6-15.3 46.7-37l26.5-112.7c3.2-13.7 4.9-28.3 5.1-42.3V144c0-17.6-14.4-32-32-32zM176 416c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 32c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32-128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"ambulance\": [640, 512, [], \"f0f9\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm144-248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm176 248c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"american-sign-language-interpreting\": [640, 512, [], \"f2a3\", \"M290.547 189.039c-20.295-10.149-44.147-11.199-64.739-3.89 42.606 0 71.208 20.475 85.578 50.576 8.576 17.899-5.148 38.071-23.617 38.071 18.429 0 32.211 20.136 23.617 38.071-14.725 30.846-46.123 50.854-80.298 50.854-.557 0-94.471-8.615-94.471-8.615l-66.406 33.347c-9.384 4.693-19.815.379-23.895-7.781L1.86 290.747c-4.167-8.615-1.111-18.897 6.946-23.621l58.072-33.069L108 159.861c6.39-57.245 34.731-109.767 79.743-146.726 11.391-9.448 28.341-7.781 37.51 3.613 9.446 11.394 7.78 28.067-3.612 37.516-12.503 10.559-23.618 22.509-32.509 35.57 21.672-14.729 46.679-24.732 74.186-28.067 14.725-1.945 28.063 8.336 29.73 23.065 1.945 14.728-8.336 28.067-23.062 29.734-16.116 1.945-31.12 7.503-44.178 15.284 26.114-5.713 58.712-3.138 88.079 11.115 13.336 6.669 18.893 22.509 12.224 35.848-6.389 13.06-22.504 18.617-35.564 12.226zm-27.229 69.472c-6.112-12.505-18.338-20.286-32.231-20.286a35.46 35.46 0 0 0-35.565 35.57c0 21.428 17.808 35.57 35.565 35.57 13.893 0 26.119-7.781 32.231-20.286 4.446-9.449 13.614-15.006 23.339-15.284-9.725-.277-18.893-5.835-23.339-15.284zm374.821-37.237c4.168 8.615 1.111 18.897-6.946 23.621l-58.071 33.069L532 352.16c-6.39 57.245-34.731 109.767-79.743 146.726-10.932 9.112-27.799 8.144-37.51-3.613-9.446-11.394-7.78-28.067 3.613-37.516 12.503-10.559 23.617-22.509 32.508-35.57-21.672 14.729-46.679 24.732-74.186 28.067-10.021 2.506-27.552-5.643-29.73-23.065-1.945-14.728 8.336-28.067 23.062-29.734 16.116-1.946 31.12-7.503 44.178-15.284-26.114 5.713-58.712 3.138-88.079-11.115-13.336-6.669-18.893-22.509-12.224-35.848 6.389-13.061 22.505-18.619 35.565-12.227 20.295 10.149 44.147 11.199 64.739 3.89-42.606 0-71.208-20.475-85.578-50.576-8.576-17.899 5.148-38.071 23.617-38.071-18.429 0-32.211-20.136-23.617-38.071 14.033-29.396 44.039-50.887 81.966-50.854l92.803 8.615 66.406-33.347c9.408-4.704 19.828-.354 23.894 7.781l44.455 88.926zm-229.227-18.618c-13.893 0-26.119 7.781-32.231 20.286-4.446 9.449-13.614 15.006-23.339 15.284 9.725.278 18.893 5.836 23.339 15.284 6.112 12.505 18.338 20.286 32.231 20.286a35.46 35.46 0 0 0 35.565-35.57c0-21.429-17.808-35.57-35.565-35.57z\"],\n    \"anchor\": [576, 512, [], \"f13d\", \"M12.971 352h32.394C67.172 454.735 181.944 512 288 512c106.229 0 220.853-57.38 242.635-160h32.394c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0l-67.029 67.029c-7.56 7.56-2.206 20.485 8.485 20.485h35.146c-20.29 54.317-84.963 86.588-144.117 94.015V256h52c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-52v-5.47c37.281-13.178 63.995-48.725 64-90.518C384.005 43.772 341.605.738 289.37.01 235.723-.739 192 42.525 192 96c0 41.798 26.716 77.35 64 90.53V192h-52c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v190.015c-58.936-7.399-123.82-39.679-144.117-94.015h35.146c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0L4.485 331.515C-3.074 339.074 2.28 352 12.971 352zM288 64c17.645 0 32 14.355 32 32s-14.355 32-32 32-32-14.355-32-32 14.355-32 32-32z\"],\n    \"angle-double-down\": [320, 512, [], \"f103\", \"M143 256.3L7 120.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0L313 86.3c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.4 9.5-24.6 9.5-34 .1zm34 192l136-136c9.4-9.4 9.4-24.6 0-33.9l-22.6-22.6c-9.4-9.4-24.6-9.4-33.9 0L160 352.1l-96.4-96.4c-9.4-9.4-24.6-9.4-33.9 0L7 278.3c-9.4 9.4-9.4 24.6 0 33.9l136 136c9.4 9.5 24.6 9.5 34 .1z\"],\n    \"angle-double-left\": [448, 512, [], \"f100\", \"M223.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L319.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L393.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34zm-192 34l136 136c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9L127.9 256l96.4-96.4c9.4-9.4 9.4-24.6 0-33.9L201.7 103c-9.4-9.4-24.6-9.4-33.9 0l-136 136c-9.5 9.4-9.5 24.6-.1 34z\"],\n    \"angle-double-right\": [448, 512, [], \"f101\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34zm192-34l-136-136c-9.4-9.4-24.6-9.4-33.9 0l-22.6 22.6c-9.4 9.4-9.4 24.6 0 33.9l96.4 96.4-96.4 96.4c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l136-136c9.4-9.2 9.4-24.4 0-33.8z\"],\n    \"angle-double-up\": [320, 512, [], \"f102\", \"M177 255.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 351.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 425.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1zm-34-192L7 199.7c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l96.4-96.4 96.4 96.4c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9l-136-136c-9.2-9.4-24.4-9.4-33.8 0z\"],\n    \"angle-down\": [320, 512, [], \"f107\", \"M143 352.3L7 216.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.2 9.4-24.4 9.4-33.8 0z\"],\n    \"angle-left\": [256, 512, [], \"f104\", \"M31.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L127.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L201.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34z\"],\n    \"angle-right\": [256, 512, [], \"f105\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34z\"],\n    \"angle-up\": [320, 512, [], \"f106\", \"M177 159.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 255.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 329.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 240c0-9.3 4.1-17.5 10.5-23.4l-31-9.3c-8.5-2.5-13.3-11.5-10.7-19.9 2.5-8.5 11.4-13.2 19.9-10.7l80 24c8.5 2.5 13.3 11.5 10.7 19.9-2.1 6.9-8.4 11.4-15.3 11.4-.5 0-1.1-.2-1.7-.2.7 2.7 1.7 5.3 1.7 8.2 0 17.7-14.3 32-32 32S136 257.7 136 240zm168 154.2c-27.8-33.4-84.2-33.4-112.1 0-13.5 16.3-38.2-4.2-24.6-20.5 20-24 49.4-37.8 80.6-37.8s60.6 13.8 80.6 37.8c13.8 16.5-11.1 36.6-24.5 20.5zm76.6-186.9l-31 9.3c6.3 5.8 10.5 14.1 10.5 23.4 0 17.7-14.3 32-32 32s-32-14.3-32-32c0-2.9.9-5.6 1.7-8.2-.6.1-1.1.2-1.7.2-6.9 0-13.2-4.5-15.3-11.4-2.5-8.5 2.3-17.4 10.7-19.9l80-24c8.4-2.5 17.4 2.3 19.9 10.7 2.5 8.5-2.3 17.4-10.8 19.9z\"],\n    \"ankh\": [320, 512, [], \"f644\", \"M296 256h-44.62C272.46 222.01 288 181.65 288 144 288 55.63 230.69 0 160 0S32 55.63 32 144c0 37.65 15.54 78.01 36.62 112H24c-13.25 0-24 10.74-24 24v32c0 13.25 10.75 24 24 24h96v152c0 13.25 10.75 24 24 24h32c13.25 0 24-10.75 24-24V336h96c13.25 0 24-10.75 24-24v-32c0-13.26-10.75-24-24-24zM160 80c29.61 0 48 24.52 48 64 0 34.66-27.14 78.14-48 100.87-20.86-22.72-48-66.21-48-100.87 0-39.48 18.39-64 48-64z\"],\n    \"apple-alt\": [448, 512, [], \"f5d1\", \"M350.85 129c25.97 4.67 47.27 18.67 63.92 42 14.65 20.67 24.64 46.67 29.96 78 4.67 28.67 4.32 57.33-1 86-7.99 47.33-23.97 87-47.94 119-28.64 38.67-64.59 58-107.87 58-10.66 0-22.3-3.33-34.96-10-8.66-5.33-18.31-8-28.97-8s-20.3 2.67-28.97 8c-12.66 6.67-24.3 10-34.96 10-43.28 0-79.23-19.33-107.87-58-23.97-32-39.95-71.67-47.94-119-5.32-28.67-5.67-57.33-1-86 5.32-31.33 15.31-57.33 29.96-78 16.65-23.33 37.95-37.33 63.92-42 15.98-2.67 37.95-.33 65.92 7 23.97 6.67 44.28 14.67 60.93 24 16.65-9.33 36.96-17.33 60.93-24 27.98-7.33 49.96-9.67 65.94-7zm-54.94-41c-9.32 8.67-21.65 15-36.96 19-10.66 3.33-22.3 5-34.96 5l-14.98-1c-1.33-9.33-1.33-20 0-32 2.67-24 10.32-42.33 22.97-55 9.32-8.67 21.65-15 36.96-19 10.66-3.33 22.3-5 34.96-5l14.98 1 1 15c0 12.67-1.67 24.33-4.99 35-3.99 15.33-10.31 27.67-18.98 37z\"],\n    \"archive\": [512, 512, [], \"f187\", \"M32 448c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V160H32v288zm160-212c0-6.6 5.4-12 12-12h104c6.6 0 12 5.4 12 12v8c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-8zM480 32H32C14.3 32 0 46.3 0 64v48c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16V64c0-17.7-14.3-32-32-32z\"],\n    \"archway\": [576, 512, [], \"f557\", \"M560 448h-16V96H32v352H16.02c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16H176c8.84 0 16-7.16 16-16V320c0-53.02 42.98-96 96-96s96 42.98 96 96l.02 160v16c0 8.84 7.16 16 16 16H560c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm0-448H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h544c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM212 140v116h-70.9c-10.7 0-16.1 13-8.5 20.5l114.9 114.3c4.7 4.7 12.2 4.7 16.9 0l114.9-114.3c7.6-7.6 2.2-20.5-8.5-20.5H300V140c0-6.6-5.4-12-12-12h-64c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm116-292H256v-70.9c0-10.7-13-16.1-20.5-8.5L121.2 247.5c-4.7 4.7-4.7 12.2 0 16.9l114.3 114.9c7.6 7.6 20.5 2.2 20.5-8.5V300h116c6.6 0 12-5.4 12-12v-64c0-6.6-5.4-12-12-12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zM140 300h116v70.9c0 10.7 13 16.1 20.5 8.5l114.3-114.9c4.7-4.7 4.7-12.2 0-16.9l-114.3-115c-7.6-7.6-20.5-2.2-20.5 8.5V212H140c-6.6 0-12 5.4-12 12v64c0 6.6 5.4 12 12 12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm292 116V256h70.9c10.7 0 16.1-13 8.5-20.5L264.5 121.2c-4.7-4.7-12.2-4.7-16.9 0l-115 114.3c-7.6 7.6-2.2 20.5 8.5 20.5H212v116c0 6.6 5.4 12 12 12h64c6.6 0 12-5.4 12-12z\"],\n    \"arrow-circle-down\": [512, 512, [], \"f0ab\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-143.6-28.9L288 302.6V120c0-13.3-10.7-24-24-24h-16c-13.3 0-24 10.7-24 24v182.6l-72.4-75.5c-9.3-9.7-24.8-9.9-34.3-.4l-10.9 11c-9.4 9.4-9.4 24.6 0 33.9L239 404.3c9.4 9.4 24.6 9.4 33.9 0l132.7-132.7c9.4-9.4 9.4-24.6 0-33.9l-10.9-11c-9.5-9.5-25-9.3-34.3.4z\"],\n    \"arrow-circle-left\": [512, 512, [], \"f0a8\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm28.9-143.6L209.4 288H392c13.3 0 24-10.7 24-24v-16c0-13.3-10.7-24-24-24H209.4l75.5-72.4c9.7-9.3 9.9-24.8.4-34.3l-11-10.9c-9.4-9.4-24.6-9.4-33.9 0L107.7 239c-9.4 9.4-9.4 24.6 0 33.9l132.7 132.7c9.4 9.4 24.6 9.4 33.9 0l11-10.9c9.5-9.5 9.3-25-.4-34.3z\"],\n    \"arrow-circle-right\": [512, 512, [], \"f0a9\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm-28.9 143.6l75.5 72.4H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h182.6l-75.5 72.4c-9.7 9.3-9.9 24.8-.4 34.3l11 10.9c9.4 9.4 24.6 9.4 33.9 0L404.3 273c9.4-9.4 9.4-24.6 0-33.9L271.6 106.3c-9.4-9.4-24.6-9.4-33.9 0l-11 10.9c-9.5 9.6-9.3 25.1.4 34.4z\"],\n    \"arrow-circle-up\": [512, 512, [], \"f0aa\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm143.6 28.9l72.4-75.5V392c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24V209.4l72.4 75.5c9.3 9.7 24.8 9.9 34.3.4l10.9-11c9.4-9.4 9.4-24.6 0-33.9L273 107.7c-9.4-9.4-24.6-9.4-33.9 0L106.3 240.4c-9.4 9.4-9.4 24.6 0 33.9l10.9 11c9.6 9.5 25.1 9.3 34.4-.4z\"],\n    \"arrow-down\": [448, 512, [], \"f063\", \"M413.1 222.5l22.2 22.2c9.4 9.4 9.4 24.6 0 33.9L241 473c-9.4 9.4-24.6 9.4-33.9 0L12.7 278.6c-9.4-9.4-9.4-24.6 0-33.9l22.2-22.2c9.5-9.5 25-9.3 34.3.4L184 343.4V56c0-13.3 10.7-24 24-24h32c13.3 0 24 10.7 24 24v287.4l114.8-120.5c9.3-9.8 24.8-10 34.3-.4z\"],\n    \"arrow-left\": [448, 512, [], \"f060\", \"M257.5 445.1l-22.2 22.2c-9.4 9.4-24.6 9.4-33.9 0L7 273c-9.4-9.4-9.4-24.6 0-33.9L201.4 44.7c9.4-9.4 24.6-9.4 33.9 0l22.2 22.2c9.5 9.5 9.3 25-.4 34.3L136.6 216H424c13.3 0 24 10.7 24 24v32c0 13.3-10.7 24-24 24H136.6l120.5 114.8c9.8 9.3 10 24.8.4 34.3z\"],\n    \"arrow-right\": [448, 512, [], \"f061\", \"M190.5 66.9l22.2-22.2c9.4-9.4 24.6-9.4 33.9 0L441 239c9.4 9.4 9.4 24.6 0 33.9L246.6 467.3c-9.4 9.4-24.6 9.4-33.9 0l-22.2-22.2c-9.5-9.5-9.3-25 .4-34.3L311.4 296H24c-13.3 0-24-10.7-24-24v-32c0-13.3 10.7-24 24-24h287.4L190.9 101.2c-9.8-9.3-10-24.8-.4-34.3z\"],\n    \"arrow-up\": [448, 512, [], \"f062\", \"M34.9 289.5l-22.2-22.2c-9.4-9.4-9.4-24.6 0-33.9L207 39c9.4-9.4 24.6-9.4 33.9 0l194.3 194.3c9.4 9.4 9.4 24.6 0 33.9L413 289.4c-9.5 9.5-25 9.3-34.3-.4L264 168.6V456c0 13.3-10.7 24-24 24h-32c-13.3 0-24-10.7-24-24V168.6L69.2 289.1c-9.3 9.8-24.8 10-34.3.4z\"],\n    \"arrows-alt\": [512, 512, [], \"f0b2\", \"M352.201 425.775l-79.196 79.196c-9.373 9.373-24.568 9.373-33.941 0l-79.196-79.196c-15.119-15.119-4.411-40.971 16.971-40.97h51.162L228 284H127.196v51.162c0 21.382-25.851 32.09-40.971 16.971L7.029 272.937c-9.373-9.373-9.373-24.569 0-33.941L86.225 159.8c15.119-15.119 40.971-4.411 40.971 16.971V228H228V127.196h-51.23c-21.382 0-32.09-25.851-16.971-40.971l79.196-79.196c9.373-9.373 24.568-9.373 33.941 0l79.196 79.196c15.119 15.119 4.411 40.971-16.971 40.971h-51.162V228h100.804v-51.162c0-21.382 25.851-32.09 40.97-16.971l79.196 79.196c9.373 9.373 9.373 24.569 0 33.941L425.773 352.2c-15.119 15.119-40.971 4.411-40.97-16.971V284H284v100.804h51.23c21.382 0 32.09 25.851 16.971 40.971z\"],\n    \"arrows-alt-h\": [512, 512, [], \"f337\", \"M377.941 169.941V216H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.568 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296h243.882v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.568 0-33.941l-86.059-86.059c-15.119-15.12-40.971-4.412-40.971 16.97z\"],\n    \"arrows-alt-v\": [256, 512, [], \"f338\", \"M214.059 377.941H168V134.059h46.059c21.382 0 32.09-25.851 16.971-40.971L144.971 7.029c-9.373-9.373-24.568-9.373-33.941 0L24.971 93.088c-15.119 15.119-4.411 40.971 16.971 40.971H88v243.882H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.568 9.373 33.941 0l86.059-86.059c15.12-15.119 4.412-40.971-16.97-40.971z\"],\n    \"assistive-listening-systems\": [512, 512, [], \"f2a2\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm-80 236c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zM32 448c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm480-187.993c0-1.518-.012-3.025-.045-4.531C510.076 140.525 436.157 38.47 327.994 1.511c-14.633-4.998-30.549 2.809-35.55 17.442-5 14.633 2.81 30.549 17.442 35.55 85.906 29.354 144.61 110.513 146.077 201.953l.003.188c.026 1.118.033 2.236.033 3.363 0 15.464 12.536 28 28 28s28.001-12.536 28.001-28zM152.971 439.029l-80-80L39.03 392.97l80 80 33.941-33.941z\"],\n    \"asterisk\": [512, 512, [], \"f069\", \"M478.21 334.093L336 256l142.21-78.093c11.795-6.477 15.961-21.384 9.232-33.037l-19.48-33.741c-6.728-11.653-21.72-15.499-33.227-8.523L296 186.718l3.475-162.204C299.763 11.061 288.937 0 275.48 0h-38.96c-13.456 0-24.283 11.061-23.994 24.514L216 186.718 77.265 102.607c-11.506-6.976-26.499-3.13-33.227 8.523l-19.48 33.741c-6.728 11.653-2.562 26.56 9.233 33.037L176 256 33.79 334.093c-11.795 6.477-15.961 21.384-9.232 33.037l19.48 33.741c6.728 11.653 21.721 15.499 33.227 8.523L216 325.282l-3.475 162.204C212.237 500.939 223.064 512 236.52 512h38.961c13.456 0 24.283-11.061 23.995-24.514L296 325.282l138.735 84.111c11.506 6.976 26.499 3.13 33.227-8.523l19.48-33.741c6.728-11.653 2.563-26.559-9.232-33.036z\"],\n    \"at\": [512, 512, [], \"f1fa\", \"M256 8C118.941 8 8 118.919 8 256c0 137.059 110.919 248 248 248 48.154 0 95.342-14.14 135.408-40.223 12.005-7.815 14.625-24.288 5.552-35.372l-10.177-12.433c-7.671-9.371-21.179-11.667-31.373-5.129C325.92 429.757 291.314 440 256 440c-101.458 0-184-82.542-184-184S154.542 72 256 72c100.139 0 184 57.619 184 160 0 38.786-21.093 79.742-58.17 83.693-17.349-.454-16.91-12.857-13.476-30.024l23.433-121.11C394.653 149.75 383.308 136 368.225 136h-44.981a13.518 13.518 0 0 0-13.432 11.993l-.01.092c-14.697-17.901-40.448-21.775-59.971-21.775-74.58 0-137.831 62.234-137.831 151.46 0 65.303 36.785 105.87 96 105.87 26.984 0 57.369-15.637 74.991-38.333 9.522 34.104 40.613 34.103 70.71 34.103C462.609 379.41 504 307.798 504 232 504 95.653 394.023 8 256 8zm-21.68 304.43c-22.249 0-36.07-15.623-36.07-40.771 0-44.993 30.779-72.729 58.63-72.729 22.292 0 35.601 15.241 35.601 40.77 0 45.061-33.875 72.73-58.161 72.73z\"],\n    \"atlas\": [448, 512, [], \"f558\", \"M318.38 208h-39.09c-1.49 27.03-6.54 51.35-14.21 70.41 27.71-13.24 48.02-39.19 53.3-70.41zm0-32c-5.29-31.22-25.59-57.17-53.3-70.41 7.68 19.06 12.72 43.38 14.21 70.41h39.09zM224 97.31c-7.69 7.45-20.77 34.42-23.43 78.69h46.87c-2.67-44.26-15.75-71.24-23.44-78.69zm-41.08 8.28c-27.71 13.24-48.02 39.19-53.3 70.41h39.09c1.49-27.03 6.53-51.35 14.21-70.41zm0 172.82c-7.68-19.06-12.72-43.38-14.21-70.41h-39.09c5.28 31.22 25.59 57.17 53.3 70.41zM247.43 208h-46.87c2.66 44.26 15.74 71.24 23.43 78.69 7.7-7.45 20.78-34.43 23.44-78.69zM448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM224 64c70.69 0 128 57.31 128 128s-57.31 128-128 128S96 262.69 96 192 153.31 64 224 64zm160 384H96c-19.2 0-32-12.8-32-32s16-32 32-32h288v64z\"],\n    \"atom\": [448, 512, [], \"f5d2\", \"M413.03 256c40.13-54.89 41.51-98.62 25.14-128-10.91-19.52-40.54-50.73-116.33-41.88C300.36 34.89 267.64 0 224 0s-76.36 34.89-97.84 86.12C50.43 77.34 20.73 108.48 9.83 128c-16.38 29.4-15 73.09 25.14 128-40.13 54.89-41.51 98.62-25.14 128 29.21 52.34 101.68 43.58 116.33 41.88C147.63 477.1 180.36 512 224 512s76.37-34.9 97.84-86.12c14.64 1.7 87.11 10.46 116.33-41.88 16.38-29.4 15-73.09-25.14-128zM63.38 352c-4.03-7.21-.19-24.8 14.95-48.29 6.96 6.53 14.2 12.89 21.87 19.18 1.71 13.71 4 27.08 6.76 40.08-24.56.89-39.89-4.37-43.58-10.97zm36.82-162.88c-7.66 6.29-14.9 12.65-21.87 19.18-15.13-23.5-18.97-41.09-14.95-48.3 3.41-6.14 16.39-11.47 37.92-11.47 1.71 0 3.87.3 5.69.37a472.191 472.191 0 0 0-6.79 40.22zM224 64c9.47 0 22.2 13.52 33.86 37.26-11.19 3.7-22.44 8-33.86 12.86-11.42-4.86-22.67-9.16-33.86-12.86C201.8 77.52 214.53 64 224 64zm0 384c-9.47 0-22.2-13.52-33.86-37.26 11.19-3.7 22.44-8 33.86-12.86 11.42 4.86 22.67 9.16 33.86 12.86C246.2 434.48 233.47 448 224 448zm62.5-157.33c-26.7 19.08-46.14 29.33-62.5 37.48-16.35-8.14-35.8-18.41-62.5-37.48-1.99-27.79-1.99-41.54 0-69.33 26.67-19.05 46.13-29.32 62.5-37.48 16.39 8.17 35.86 18.44 62.5 37.48 1.98 27.78 1.99 41.53 0 69.33zM384.62 352c-3.67 6.62-19 11.82-43.58 10.95 2.76-13 5.05-26.37 6.76-40.06 7.66-6.29 14.9-12.65 21.87-19.18 15.13 23.49 18.97 41.08 14.95 48.29zm-14.95-143.71c-6.96-6.53-14.2-12.89-21.87-19.18a473.535 473.535 0 0 0-6.79-40.22c1.82-.07 3.97-.37 5.69-.37 21.52 0 34.51 5.34 37.92 11.47 4.02 7.22.18 24.81-14.95 48.3zM224 224c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"audio-description\": [512, 512, [], \"f29e\", \"M162.925 238.709l8.822 30.655h-25.606l9.041-30.652c1.277-4.421 2.651-9.994 3.872-15.245 1.22 5.251 2.594 10.823 3.871 15.242zm166.474-32.099h-14.523v98.781h14.523c29.776 0 46.175-17.678 46.175-49.776 0-32.239-17.49-49.005-46.175-49.005zM512 112v288c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48zM245.459 336.139l-57.097-168A12.001 12.001 0 0 0 177 160h-35.894a12.001 12.001 0 0 0-11.362 8.139l-57.097 168C70.003 343.922 75.789 352 84.009 352h29.133a12 12 0 0 0 11.535-8.693l8.574-29.906h51.367l8.793 29.977A12 12 0 0 0 204.926 352h29.172c8.22 0 14.006-8.078 11.361-15.861zm184.701-80.525c0-58.977-37.919-95.614-98.96-95.614h-57.366c-6.627 0-12 5.373-12 12v168c0 6.627 5.373 12 12 12H331.2c61.041 0 98.96-36.933 98.96-96.386z\"],\n    \"award\": [384, 512, [], \"f559\", \"M97.12 362.63c-8.69-8.69-4.16-6.24-25.12-11.85-9.51-2.55-17.87-7.45-25.43-13.32L1.2 448.7c-4.39 10.77 3.81 22.47 15.43 22.03l52.69-2.01L105.56 507c8 8.44 22.04 5.81 26.43-4.96l52.05-127.62c-10.84 6.04-22.87 9.58-35.31 9.58-19.5 0-37.82-7.59-51.61-21.37zM382.8 448.7l-45.37-111.24c-7.56 5.88-15.92 10.77-25.43 13.32-21.07 5.64-16.45 3.18-25.12 11.85-13.79 13.78-32.12 21.37-51.62 21.37-12.44 0-24.47-3.55-35.31-9.58L252 502.04c4.39 10.77 18.44 13.4 26.43 4.96l36.25-38.28 52.69 2.01c11.62.44 19.82-11.27 15.43-22.03zM263 340c15.28-15.55 17.03-14.21 38.79-20.14 13.89-3.79 24.75-14.84 28.47-28.98 7.48-28.4 5.54-24.97 25.95-45.75 10.17-10.35 14.14-25.44 10.42-39.58-7.47-28.38-7.48-24.42 0-52.83 3.72-14.14-.25-29.23-10.42-39.58-20.41-20.78-18.47-17.36-25.95-45.75-3.72-14.14-14.58-25.19-28.47-28.98-27.88-7.61-24.52-5.62-44.95-26.41-10.17-10.35-25-14.4-38.89-10.61-27.87 7.6-23.98 7.61-51.9 0-13.89-3.79-28.72.25-38.89 10.61-20.41 20.78-17.05 18.8-44.94 26.41-13.89 3.79-24.75 14.84-28.47 28.98-7.47 28.39-5.54 24.97-25.95 45.75-10.17 10.35-14.15 25.44-10.42 39.58 7.47 28.36 7.48 24.4 0 52.82-3.72 14.14.25 29.23 10.42 39.59 20.41 20.78 18.47 17.35 25.95 45.75 3.72 14.14 14.58 25.19 28.47 28.98C104.6 325.96 106.27 325 121 340c13.23 13.47 33.84 15.88 49.74 5.82a39.676 39.676 0 0 1 42.53 0c15.89 10.06 36.5 7.65 49.73-5.82zM97.66 175.96c0-53.03 42.24-96.02 94.34-96.02s94.34 42.99 94.34 96.02-42.24 96.02-94.34 96.02-94.34-42.99-94.34-96.02z\"],\n    \"baby\": [384, 512, [], \"f77c\", \"M192 160c44.2 0 80-35.8 80-80S236.2 0 192 0s-80 35.8-80 80 35.8 80 80 80zm-53.4 248.8l25.6-32-61.5-51.2L56.8 383c-11.4 14.2-11.7 34.4-.8 49l48 64c7.9 10.5 19.9 16 32 16 8.3 0 16.8-2.6 24-8 17.7-13.2 21.2-38.3 8-56l-29.4-39.2zm142.7-83.2l-61.5 51.2 25.6 32L216 448c-13.2 17.7-9.7 42.8 8 56 7.2 5.4 15.6 8 24 8 12.2 0 24.2-5.5 32-16l48-64c10.9-14.6 10.6-34.8-.8-49l-45.9-57.4zM376.7 145c-12.7-18.1-37.6-22.4-55.7-9.8l-40.6 28.5c-52.7 37-124.2 37-176.8 0L63 135.3C44.9 122.6 20 127 7.3 145-5.4 163.1-1 188 17 200.7l40.6 28.5c17 11.9 35.4 20.9 54.4 27.9V288h160v-30.8c19-7 37.4-16 54.4-27.9l40.6-28.5c18.1-12.8 22.4-37.7 9.7-55.8z\"],\n    \"baby-carriage\": [512, 512, [], \"f77d\", \"M144.8 17c-11.3-17.8-37.2-22.8-54-9.4C35.3 51.9 0 118 0 192h256L144.8 17zM496 96h-48c-35.3 0-64 28.7-64 64v64H0c0 50.6 23 96.4 60.3 130.7C25.7 363.6 0 394.7 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-8.9-1.8-17.2-4.4-25.2 21.6 5.9 44.6 9.2 68.4 9.2s46.9-3.3 68.4-9.2c-2.7 8-4.4 16.3-4.4 25.2 0 44.2 35.8 80 80 80s80-35.8 80-80c0-37.3-25.7-68.4-60.3-77.3C425 320.4 448 274.6 448 224v-64h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM80 464c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm320-32c0 17.6-14.4 32-32 32s-32-14.4-32-32 14.4-32 32-32 32 14.4 32 32z\"],\n    \"backspace\": [640, 512, [], \"f55a\", \"M576 64H205.26A63.97 63.97 0 0 0 160 82.75L9.37 233.37c-12.5 12.5-12.5 32.76 0 45.25L160 429.25c12 12 28.28 18.75 45.25 18.75H576c35.35 0 64-28.65 64-64V128c0-35.35-28.65-64-64-64zm-84.69 254.06c6.25 6.25 6.25 16.38 0 22.63l-22.62 22.62c-6.25 6.25-16.38 6.25-22.63 0L384 301.25l-62.06 62.06c-6.25 6.25-16.38 6.25-22.63 0l-22.62-22.62c-6.25-6.25-6.25-16.38 0-22.63L338.75 256l-62.06-62.06c-6.25-6.25-6.25-16.38 0-22.63l22.62-22.62c6.25-6.25 16.38-6.25 22.63 0L384 210.75l62.06-62.06c6.25-6.25 16.38-6.25 22.63 0l22.62 22.62c6.25 6.25 6.25 16.38 0 22.63L429.25 256l62.06 62.06z\"],\n    \"backward\": [512, 512, [], \"f04a\", \"M11.5 280.6l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2zm256 0l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2z\"],\n    \"bacon\": [576, 512, [], \"f7e5\", \"M218.92 336.39c34.89-34.89 44.2-59.7 54.05-86 10.61-28.29 21.59-57.54 61.37-97.34s69.05-50.77 97.35-61.38c23.88-9 46.64-17.68 76.79-45.37L470.81 8.91a31 31 0 0 0-40.18-2.83c-13.64 10.1-25.15 14.39-41 20.3C247 79.52 209.26 191.29 200.65 214.1c-29.75 78.83-89.55 94.68-98.72 98.09-24.86 9.26-54.73 20.38-91.07 50.36C-3 374-3.63 395 9.07 407.61l35.76 35.51C80 410.52 107 400.15 133 390.39c26.27-9.84 51.06-19.12 85.92-54zm348-232l-35.75-35.51c-35.19 32.63-62.18 43-88.25 52.79-26.26 9.85-51.06 19.16-85.95 54s-44.19 59.69-54 86C292.33 290 281.34 319.22 241.55 359s-69 50.73-97.3 61.32c-23.86 9-46.61 17.66-76.72 45.33l37.68 37.43a31 31 0 0 0 40.18 2.82c13.6-10.06 25.09-14.34 40.94-20.24 142.2-53 180-164.1 188.94-187.69C405 219.18 464.8 203.3 474 199.86c24.87-9.27 54.74-20.4 91.11-50.41 13.89-11.4 14.52-32.45 1.82-45.05z\"],\n    \"balance-scale\": [640, 512, [], \"f24e\", \"M256 336h-.02c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0C-2.06 328.75.02 320.33.02 336H0c0 44.18 57.31 80 128 80s128-35.82 128-80zM128 176l72 144H56l72-144zm511.98 160c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 320l72-144 72 144H440zm88 128H352V153.25c23.51-10.29 41.16-31.48 46.39-57.25H528c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H383.64C369.04 12.68 346.09 0 320 0s-49.04 12.68-63.64 32H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h129.61c5.23 25.76 22.87 46.96 46.39 57.25V448H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"balance-scale-left\": [640, 512, [], \"f515\", \"M528 448H352V153.25c20.42-8.94 36.1-26.22 43.38-47.47l132-44.26c8.38-2.81 12.89-11.88 10.08-20.26l-10.17-30.34C524.48 2.54 515.41-1.97 507.03.84L389.11 40.37C375.3 16.36 349.69 0 320 0c-44.18 0-80 35.82-80 80 0 3.43.59 6.71 1.01 10.03l-128.39 43.05c-8.38 2.81-12.89 11.88-10.08 20.26l10.17 30.34c2.81 8.38 11.88 12.89 20.26 10.08l142.05-47.63c4.07 2.77 8.43 5.12 12.99 7.12V496c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16v-32c-.01-8.84-7.17-16-16.01-16zm111.98-144c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 288l72-144 72 144H440zm-269.07-37.51c-17.65-35.29-68.19-35.36-85.87 0C-2.06 424.75.02 416.33.02 432H0c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-16.18 1.34-8.73-85.05-181.51zM56 416l72-144 72 144H56z\"],\n    \"balance-scale-right\": [640, 512, [], \"f516\", \"M96 464v32c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16V153.25c4.56-2 8.92-4.35 12.99-7.12l142.05 47.63c8.38 2.81 17.45-1.71 20.26-10.08l10.17-30.34c2.81-8.38-1.71-17.45-10.08-20.26l-128.4-43.05c.42-3.32 1.01-6.6 1.01-10.03 0-44.18-35.82-80-80-80-29.69 0-55.3 16.36-69.11 40.37L132.96.83c-8.38-2.81-17.45 1.71-20.26 10.08l-10.17 30.34c-2.81 8.38 1.71 17.45 10.08 20.26l132 44.26c7.28 21.25 22.96 38.54 43.38 47.47V448H112c-8.84 0-16 7.16-16 16zM0 304c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0C-1.32 295.27.02 287.82.02 304H0zm56-16l72-144 72 144H56zm328.02 144H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0-86.38 172.78-85.04 165.33-85.04 181.51zM440 416l72-144 72 144H440z\"],\n    \"ban\": [512, 512, [], \"f05e\", \"M256 8C119.034 8 8 119.033 8 256s111.034 248 248 248 248-111.034 248-248S392.967 8 256 8zm130.108 117.892c65.448 65.448 70 165.481 20.677 235.637L150.47 105.216c70.204-49.356 170.226-44.735 235.638 20.676zM125.892 386.108c-65.448-65.448-70-165.481-20.677-235.637L361.53 406.784c-70.203 49.356-170.226 44.736-235.638-20.676z\"],\n    \"band-aid\": [640, 512, [], \"f462\", \"M0 160v192c0 35.3 28.7 64 64 64h96V96H64c-35.3 0-64 28.7-64 64zm576-64h-96v320h96c35.3 0 64-28.7 64-64V160c0-35.3-28.7-64-64-64zM192 416h256V96H192v320zm176-232c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24z\"],\n    \"barcode\": [512, 512, [], \"f02a\", \"M0 448V64h18v384H0zm26.857-.273V64H36v383.727h-9.143zm27.143 0V64h8.857v383.727H54zm44.857 0V64h8.857v383.727h-8.857zm36 0V64h17.714v383.727h-17.714zm44.857 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm35.715 0V64h18v383.727h-18zm44.857 0V64h18v383.727h-18zm35.999 0V64h18.001v383.727h-18.001zm36.001 0V64h18.001v383.727h-18.001zm26.857 0V64h18v383.727h-18zm45.143 0V64h26.857v383.727h-26.857zm35.714 0V64h9.143v383.727H476zm18 .273V64h18v384h-18z\"],\n    \"bars\": [448, 512, [], \"f0c9\", \"M16 132h416c8.837 0 16-7.163 16-16V76c0-8.837-7.163-16-16-16H16C7.163 60 0 67.163 0 76v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16z\"],\n    \"baseball-ball\": [496, 512, [], \"f433\", \"M368.5 363.9l28.8-13.9c11.1 22.9 26 43.2 44.1 60.9 34-42.5 54.5-96.3 54.5-154.9 0-58.5-20.4-112.2-54.2-154.6-17.8 17.3-32.6 37.1-43.6 59.5l-28.7-14.1c12.8-26 30-49 50.8-69C375.6 34.7 315 8 248 8 181.1 8 120.5 34.6 75.9 77.7c20.7 19.9 37.9 42.9 50.7 68.8l-28.7 14.1c-11-22.3-25.7-42.1-43.5-59.4C20.4 143.7 0 197.4 0 256c0 58.6 20.4 112.3 54.4 154.7 18.2-17.7 33.2-38 44.3-61l28.8 13.9c-12.9 26.7-30.3 50.3-51.5 70.7 44.5 43.1 105.1 69.7 172 69.7 66.8 0 127.3-26.5 171.9-69.5-21.1-20.4-38.5-43.9-51.4-70.6zm-228.3-32l-30.5-9.8c14.9-46.4 12.7-93.8-.6-134l30.4-10c15 45.6 18 99.9.7 153.8zm216.3-153.4l30.4 10c-13.2 40.1-15.5 87.5-.6 134l-30.5 9.8c-17.3-54-14.3-108.3.7-153.8z\"],\n    \"basketball-ball\": [496, 512, [], \"f434\", \"M212.3 10.3c-43.8 6.3-86.2 24.1-122.2 53.8l77.4 77.4c27.8-35.8 43.3-81.2 44.8-131.2zM248 222L405.9 64.1c-42.4-35-93.6-53.5-145.5-56.1-1.2 63.9-21.5 122.3-58.7 167.7L248 222zM56.1 98.1c-29.7 36-47.5 78.4-53.8 122.2 50-1.5 95.5-17 131.2-44.8L56.1 98.1zm272.2 204.2c45.3-37.1 103.7-57.4 167.7-58.7-2.6-51.9-21.1-103.1-56.1-145.5L282 256l46.3 46.3zM248 290L90.1 447.9c42.4 34.9 93.6 53.5 145.5 56.1 1.3-64 21.6-122.4 58.7-167.7L248 290zm191.9 123.9c29.7-36 47.5-78.4 53.8-122.2-50.1 1.6-95.5 17.1-131.2 44.8l77.4 77.4zM167.7 209.7C122.3 246.9 63.9 267.3 0 268.4c2.6 51.9 21.1 103.1 56.1 145.5L214 256l-46.3-46.3zm116 292c43.8-6.3 86.2-24.1 122.2-53.8l-77.4-77.4c-27.7 35.7-43.2 81.2-44.8 131.2z\"],\n    \"bath\": [512, 512, [], \"f2cd\", \"M488 256H80V112c0-17.645 14.355-32 32-32 11.351 0 21.332 5.945 27.015 14.88-16.492 25.207-14.687 59.576 6.838 83.035-4.176 4.713-4.021 11.916.491 16.428l11.314 11.314c4.686 4.686 12.284 4.686 16.971 0l95.03-95.029c4.686-4.686 4.686-12.284 0-16.971l-11.314-11.314c-4.512-4.512-11.715-4.666-16.428-.491-17.949-16.469-42.294-21.429-64.178-15.365C163.281 45.667 139.212 32 112 32c-44.112 0-80 35.888-80 80v144h-8c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h8v32c0 28.43 12.362 53.969 32 71.547V456c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-8h256v8c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-32.453c19.638-17.578 32-43.117 32-71.547v-32h8c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"battery-empty\": [640, 512, [], \"f244\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48z\"],\n    \"battery-full\": [640, 512, [], \"f240\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-48 96H96v128h416V192z\"],\n    \"battery-half\": [640, 512, [], \"f242\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-240 96H96v128h224V192z\"],\n    \"battery-quarter\": [640, 512, [], \"f243\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-336 96H96v128h128V192z\"],\n    \"battery-three-quarters\": [640, 512, [], \"f241\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-144 96H96v128h320V192z\"],\n    \"bed\": [640, 512, [], \"f236\", \"M176 256c44.11 0 80-35.89 80-80s-35.89-80-80-80-80 35.89-80 80 35.89 80 80 80zm352-128H304c-8.84 0-16 7.16-16 16v144H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v352c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h512v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V240c0-61.86-50.14-112-112-112z\"],\n    \"beer\": [448, 512, [], \"f0fc\", \"M368 96h-48V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24v-42.11l80.606-35.977C429.396 365.063 448 336.388 448 304.86V176c0-44.112-35.888-80-80-80zm16 208.86a16.018 16.018 0 0 1-9.479 14.611L320 343.805V160h48c8.822 0 16 7.178 16 16v128.86zM208 384c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16zm-96 0c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64zm215.39-149.71c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.82 458.1l-90.62-70.05c.19-1.38.8-2.66.8-4.06.05-7.55-2.61-15.27-8.61-21.71-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-40.33 8.38-74.66 31.07-97.59 62.57L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.35 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.42-6.97 4.17-17.02-2.81-22.45zM157.23 251.54c-8.61 67.96-36.41 93.33-52.62 110.75-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h241.92L157.23 251.54zM320 512c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bezier-curve\": [640, 512, [], \"f55b\", \"M368 32h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM208 88h-84.75C113.75 64.56 90.84 48 64 48 28.66 48 0 76.65 0 112s28.66 64 64 64c26.84 0 49.75-16.56 59.25-40h79.73c-55.37 32.52-95.86 87.32-109.54 152h49.4c11.3-41.61 36.77-77.21 71.04-101.56-3.7-8.08-5.88-16.99-5.88-26.44V88zm-48 232H64c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zM576 48c-26.84 0-49.75 16.56-59.25 40H432v72c0 9.45-2.19 18.36-5.88 26.44 34.27 24.35 59.74 59.95 71.04 101.56h49.4c-13.68-64.68-54.17-119.48-109.54-152h79.73c9.5 23.44 32.41 40 59.25 40 35.34 0 64-28.65 64-64s-28.66-64-64-64zm0 272h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"bible\": [448, 512, [], \"f647\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM144 144c0-8.84 7.16-16 16-16h48V80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v48h48c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-48v112c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V192h-48c-8.84 0-16-7.16-16-16v-32zm236.8 304H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"bicycle\": [640, 512, [], \"f206\", \"M512.509 192.001c-16.373-.064-32.03 2.955-46.436 8.495l-77.68-125.153A24 24 0 0 0 368.001 64h-64c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h50.649l14.896 24H256.002v-16c0-8.837-7.163-16-16-16h-87.459c-13.441 0-24.777 10.999-24.536 24.437.232 13.044 10.876 23.563 23.995 23.563h48.726l-29.417 47.52c-13.433-4.83-27.904-7.483-42.992-7.52C58.094 191.83.412 249.012.002 319.236-.413 390.279 57.055 448 128.002 448c59.642 0 109.758-40.793 123.967-96h52.033a24 24 0 0 0 20.406-11.367L410.37 201.77l14.938 24.067c-25.455 23.448-41.385 57.081-41.307 94.437.145 68.833 57.899 127.051 126.729 127.719 70.606.685 128.181-55.803 129.255-125.996 1.086-70.941-56.526-129.72-127.476-129.996zM186.75 265.772c9.727 10.529 16.673 23.661 19.642 38.228h-43.306l23.664-38.228zM128.002 400c-44.112 0-80-35.888-80-80s35.888-80 80-80c5.869 0 11.586.653 17.099 1.859l-45.505 73.509C89.715 331.327 101.213 352 120.002 352h81.3c-12.37 28.225-40.562 48-73.3 48zm162.63-96h-35.624c-3.96-31.756-19.556-59.894-42.383-80.026L237.371 184h127.547l-74.286 120zm217.057 95.886c-41.036-2.165-74.049-35.692-75.627-76.755-.812-21.121 6.633-40.518 19.335-55.263l44.433 71.586c4.66 7.508 14.524 9.816 22.032 5.156l13.594-8.437c7.508-4.66 9.817-14.524 5.156-22.032l-44.468-71.643a79.901 79.901 0 0 1 19.858-2.497c44.112 0 80 35.888 80 80-.001 45.54-38.252 82.316-84.313 79.885z\"],\n    \"biking\": [640, 512, [], \"f84a\", \"M400 96a48 48 0 1 0-48-48 48 48 0 0 0 48 48zm-4 121a31.9 31.9 0 0 0 20 7h64a32 32 0 0 0 0-64h-52.78L356 103a31.94 31.94 0 0 0-40.81.68l-112 96a32 32 0 0 0 3.08 50.92L288 305.12V416a32 32 0 0 0 64 0V288a32 32 0 0 0-14.25-26.62l-41.36-27.57 58.25-49.92zm116 39a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64zM128 256a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64z\"],\n    \"binoculars\": [512, 512, [], \"f1e5\", \"M416 48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v48h96V48zM63.91 159.99C61.4 253.84 3.46 274.22 0 404v44c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V288h32V128H95.84c-17.63 0-31.45 14.37-31.93 31.99zm384.18 0c-.48-17.62-14.3-31.99-31.93-31.99H320v160h32v160c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-44c-3.46-129.78-61.4-150.16-63.91-244.01zM176 32h-64c-8.84 0-16 7.16-16 16v48h96V48c0-8.84-7.16-16-16-16zm48 256h64V128h-64v160z\"],\n    \"biohazard\": [576, 512, [], \"f780\", \"M287.9 112c18.6 0 36.2 3.8 52.8 9.6 13.3-10.3 23.6-24.3 29.5-40.7-25.2-10.9-53-17-82.2-17-29.1 0-56.9 6-82.1 16.9 5.9 16.4 16.2 30.4 29.5 40.7 16.5-5.7 34-9.5 52.5-9.5zM163.6 438.7c12-11.8 20.4-26.4 24.5-42.4-32.9-26.4-54.8-65.3-58.9-109.6-8.5-2.8-17.2-4.6-26.4-4.6-7.6 0-15.2 1-22.5 3.1 4.1 62.8 35.8 118 83.3 153.5zm224.2-42.6c4.1 16 12.5 30.7 24.5 42.5 47.4-35.5 79.1-90.7 83-153.5-7.2-2-14.7-3-22.2-3-9.2 0-18 1.9-26.6 4.7-4.1 44.2-26 82.9-58.7 109.3zm113.5-205c-17.6-10.4-36.3-16.6-55.3-19.9 6-17.7 10-36.4 10-56.2 0-41-14.5-80.8-41-112.2-2.5-3-6.6-3.7-10-1.8-3.3 1.9-4.8 6-3.6 9.7 4.5 13.8 6.6 26.3 6.6 38.5 0 67.8-53.8 122.9-120 122.9S168 117 168 49.2c0-12.1 2.2-24.7 6.6-38.5 1.2-3.7-.3-7.8-3.6-9.7-3.4-1.9-7.5-1.2-10 1.8C134.6 34.2 120 74 120 115c0 19.8 3.9 38.5 10 56.2-18.9 3.3-37.7 9.5-55.3 19.9-34.6 20.5-61 53.3-74.3 92.4-1.3 3.7.2 7.7 3.5 9.8 3.3 2 7.5 1.3 10-1.6 9.4-10.8 19-19.1 29.2-25.1 57.3-33.9 130.8-13.7 163.9 45 33.1 58.7 13.4 134-43.9 167.9-10.2 6.1-22 10.4-35.8 13.4-3.7.8-6.4 4.2-6.4 8.1.1 4 2.7 7.3 6.5 8 39.7 7.8 80.6.8 115.2-19.7 18-10.6 32.9-24.5 45.3-40.1 12.4 15.6 27.3 29.5 45.3 40.1 34.6 20.5 75.5 27.5 115.2 19.7 3.8-.7 6.4-4 6.5-8 0-3.9-2.6-7.3-6.4-8.1-13.9-2.9-25.6-7.3-35.8-13.4-57.3-33.9-77-109.2-43.9-167.9s106.6-78.9 163.9-45c10.2 6.1 19.8 14.3 29.2 25.1 2.5 2.9 6.7 3.6 10 1.6s4.8-6.1 3.5-9.8c-13.1-39.1-39.5-72-74.1-92.4zm-213.4 129c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"birthday-cake\": [448, 512, [], \"f1fd\", \"M448 384c-28.02 0-31.26-32-74.5-32-43.43 0-46.825 32-74.75 32-27.695 0-31.454-32-74.75-32-42.842 0-47.218 32-74.5 32-28.148 0-31.202-32-74.75-32-43.547 0-46.653 32-74.75 32v-80c0-26.5 21.5-48 48-48h16V112h64v144h64V112h64v144h64V112h64v144h16c26.5 0 48 21.5 48 48v80zm0 128H0v-96c43.356 0 46.767-32 74.75-32 27.951 0 31.253 32 74.75 32 42.843 0 47.217-32 74.5-32 28.148 0 31.201 32 74.75 32 43.357 0 46.767-32 74.75-32 27.488 0 31.252 32 74.5 32v96zM96 96c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40z\"],\n    \"blender\": [512, 512, [], \"f517\", \"M416 384H160c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-128 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm40-416h166.54L512 0H48C21.49 0 0 21.49 0 48v160c0 26.51 21.49 48 48 48h103.27l8.73 96h256l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H328c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM64 192V64h69.82l11.64 128H64z\"],\n    \"blender-phone\": [576, 512, [], \"f6b6\", \"M392 64h166.54L576 0H192v352h288l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H392c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM158.8 335.01l-25.78-63.26c-2.78-6.81-9.8-10.99-17.24-10.26l-45.03 4.42c-17.28-46.94-17.65-99.78 0-147.72l45.03 4.42c7.43.73 14.46-3.46 17.24-10.26l25.78-63.26c3.02-7.39.2-15.85-6.68-20.07l-39.28-24.1C98.51-3.87 80.09-.5 68.95 11.97c-92.57 103.6-92 259.55 2.1 362.49 9.87 10.8 29.12 12.48 41.65 4.8l39.41-24.18c6.89-4.22 9.7-12.67 6.69-20.07zM480 384H192c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-144 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"blind\": [384, 512, [], \"f29d\", \"M380.15 510.837a8 8 0 0 1-10.989-2.687l-125.33-206.427a31.923 31.923 0 0 0 12.958-9.485l126.048 207.608a8 8 0 0 1-2.687 10.991zM142.803 314.338l-32.54 89.485 36.12 88.285c6.693 16.36 25.377 24.192 41.733 17.501 16.357-6.692 24.193-25.376 17.501-41.734l-62.814-153.537zM96 88c24.301 0 44-19.699 44-44S120.301 0 96 0 52 19.699 52 44s19.699 44 44 44zm154.837 169.128l-120-152c-4.733-5.995-11.75-9.108-18.837-9.112V96H80v.026c-7.146.003-14.217 3.161-18.944 9.24L0 183.766v95.694c0 13.455 11.011 24.791 24.464 24.536C37.505 303.748 48 293.1 48 280v-79.766l16-20.571v140.698L9.927 469.055c-6.04 16.609 2.528 34.969 19.138 41.009 16.602 6.039 34.968-2.524 41.009-19.138L136 309.638V202.441l-31.406-39.816a4 4 0 1 1 6.269-4.971l102.3 129.217c9.145 11.584 24.368 11.339 33.708 3.965 10.41-8.216 12.159-23.334 3.966-33.708z\"],\n    \"blog\": [512, 512, [], \"f781\", \"M172.2 226.8c-14.6-2.9-28.2 8.9-28.2 23.8V301c0 10.2 7.1 18.4 16.7 22 18.2 6.8 31.3 24.4 31.3 45 0 26.5-21.5 48-48 48s-48-21.5-48-48V120c0-13.3-10.7-24-24-24H24c-13.3 0-24 10.7-24 24v248c0 89.5 82.1 160.2 175 140.7 54.4-11.4 98.3-55.4 109.7-109.7 17.4-82.9-37-157.2-112.5-172.2zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"bold\": [384, 512, [], \"f032\", \"M333.49 238a122 122 0 0 0 27-65.21C367.87 96.49 308 32 233.42 32H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h31.87v288H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h209.32c70.8 0 134.14-51.75 141-122.4 4.74-48.45-16.39-92.06-50.83-119.6zM145.66 112h87.76a48 48 0 0 1 0 96h-87.76zm87.76 288h-87.76V288h87.76a56 56 0 0 1 0 112z\"],\n    \"bolt\": [320, 512, [], \"f0e7\", \"M296 160H180.6l42.6-129.8C227.2 15 215.7 0 200 0H56C44 0 33.8 8.9 32.2 20.8l-32 240C-1.7 275.2 9.5 288 24 288h118.7L96.6 482.5c-3.6 15.2 8 29.5 23.3 29.5 8.4 0 16.4-4.4 20.8-12l176-304c9.3-15.9-2.2-36-20.7-36z\"],\n    \"bomb\": [512, 512, [], \"f1e2\", \"M440.5 88.5l-52 52L415 167c9.4 9.4 9.4 24.6 0 33.9l-17.4 17.4c11.8 26.1 18.4 55.1 18.4 85.6 0 114.9-93.1 208-208 208S0 418.9 0 304 93.1 96 208 96c30.5 0 59.5 6.6 85.6 18.4L311 97c9.4-9.4 24.6-9.4 33.9 0l26.5 26.5 52-52 17.1 17zM500 60h-24c-6.6 0-12 5.4-12 12s5.4 12 12 12h24c6.6 0 12-5.4 12-12s-5.4-12-12-12zM440 0c-6.6 0-12 5.4-12 12v24c0 6.6 5.4 12 12 12s12-5.4 12-12V12c0-6.6-5.4-12-12-12zm33.9 55l17-17c4.7-4.7 4.7-12.3 0-17-4.7-4.7-12.3-4.7-17 0l-17 17c-4.7 4.7-4.7 12.3 0 17 4.8 4.7 12.4 4.7 17 0zm-67.8 0c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17zm67.8 34c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17zM112 272c0-35.3 28.7-64 64-64 8.8 0 16-7.2 16-16s-7.2-16-16-16c-52.9 0-96 43.1-96 96 0 8.8 7.2 16 16 16s16-7.2 16-16z\"],\n    \"bone\": [640, 512, [], \"f5d7\", \"M598.88 244.56c25.2-12.6 41.12-38.36 41.12-66.53v-7.64C640 129.3 606.7 96 565.61 96c-32.02 0-60.44 20.49-70.57 50.86-7.68 23.03-11.6 45.14-38.11 45.14H183.06c-27.38 0-31.58-25.54-38.11-45.14C134.83 116.49 106.4 96 74.39 96 33.3 96 0 129.3 0 170.39v7.64c0 28.17 15.92 53.93 41.12 66.53 9.43 4.71 9.43 18.17 0 22.88C15.92 280.04 0 305.8 0 333.97v7.64C0 382.7 33.3 416 74.38 416c32.02 0 60.44-20.49 70.57-50.86 7.68-23.03 11.6-45.14 38.11-45.14h273.87c27.38 0 31.58 25.54 38.11 45.14C505.17 395.51 533.6 416 565.61 416c41.08 0 74.38-33.3 74.38-74.39v-7.64c0-28.18-15.92-53.93-41.12-66.53-9.42-4.71-9.42-18.17.01-22.88z\"],\n    \"bong\": [448, 512, [], \"f55c\", \"M302.5 512c23.18 0 44.43-12.58 56-32.66C374.69 451.26 384 418.75 384 384c0-36.12-10.08-69.81-27.44-98.62L400 241.94l9.38 9.38c6.25 6.25 16.38 6.25 22.63 0l11.3-11.32c6.25-6.25 6.25-16.38 0-22.63l-52.69-52.69c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l9.38 9.38-39.41 39.41c-11.56-11.37-24.53-21.33-38.65-29.51V63.74l15.97-.02c8.82-.01 15.97-7.16 15.98-15.98l.04-31.72C320 7.17 312.82-.01 303.97 0L80.03.26c-8.82.01-15.97 7.16-15.98 15.98l-.04 31.73c-.01 8.85 7.17 16.02 16.02 16.01L96 63.96v153.93C38.67 251.1 0 312.97 0 384c0 34.75 9.31 67.27 25.5 95.34C37.08 499.42 58.33 512 81.5 512h221zM120.06 259.43L144 245.56V63.91l96-.11v181.76l23.94 13.87c24.81 14.37 44.12 35.73 56.56 60.57h-257c12.45-24.84 31.75-46.2 56.56-60.57z\"],\n    \"book\": [448, 512, [], \"f02d\", \"M448 360V24c0-13.3-10.7-24-24-24H96C43 0 0 43 0 96v320c0 53 43 96 96 96h328c13.3 0 24-10.7 24-24v-16c0-7.5-3.5-14.3-8.9-18.7-4.2-15.4-4.2-59.3 0-74.7 5.4-4.3 8.9-11.1 8.9-18.6zM128 134c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm0 64c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm253.4 250H96c-17.7 0-32-14.3-32-32 0-17.6 14.4-32 32-32h285.4c-1.9 17.1-1.9 46.9 0 64z\"],\n    \"book-dead\": [448, 512, [], \"f6b7\", \"M272 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm176 222.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM240 56c44.2 0 80 28.7 80 64 0 20.9-12.7 39.2-32 50.9V184c0 8.8-7.2 16-16 16h-64c-8.8 0-16-7.2-16-16v-13.1c-19.3-11.7-32-30-32-50.9 0-35.3 35.8-64 80-64zM124.8 223.3l6.3-14.7c1.7-4.1 6.4-5.9 10.5-4.2l98.3 42.1 98.4-42.1c4.1-1.7 8.8.1 10.5 4.2l6.3 14.7c1.7 4.1-.1 8.8-4.2 10.5L280.6 264l70.3 30.1c4.1 1.7 5.9 6.4 4.2 10.5l-6.3 14.7c-1.7 4.1-6.4 5.9-10.5 4.2L240 281.4l-98.3 42.2c-4.1 1.7-8.8-.1-10.5-4.2l-6.3-14.7c-1.7-4.1.1-8.8 4.2-10.5l70.4-30.1-70.5-30.3c-4.1-1.7-5.9-6.4-4.2-10.5zm256 224.7H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8zM208 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16z\"],\n    \"book-medical\": [448, 512, [], \"f7e6\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16q0-9.6-9.6-19.2c-3.2-16-3.2-60.8 0-73.6q9.6-4.8 9.6-19.2zM144 168a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8v48a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8zm236.8 280H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8z\"],\n    \"book-open\": [576, 512, [], \"f518\", \"M542.22 32.05c-54.8 3.11-163.72 14.43-230.96 55.59-4.64 2.84-7.27 7.89-7.27 13.17v363.87c0 11.55 12.63 18.85 23.28 13.49 69.18-34.82 169.23-44.32 218.7-46.92 16.89-.89 30.02-14.43 30.02-30.66V62.75c.01-17.71-15.35-31.74-33.77-30.7zM264.73 87.64C197.5 46.48 88.58 35.17 33.78 32.05 15.36 31.01 0 45.04 0 62.75V400.6c0 16.24 13.13 29.78 30.02 30.66 49.49 2.6 149.59 12.11 218.77 46.95 10.62 5.35 23.21-1.94 23.21-13.46V100.63c0-5.29-2.62-10.14-7.27-12.99z\"],\n    \"book-reader\": [512, 512, [], \"f5da\", \"M352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96 42.98 96 96 96 96-42.98 96-96zM233.59 241.1c-59.33-36.32-155.43-46.3-203.79-49.05C13.55 191.13 0 203.51 0 219.14v222.8c0 14.33 11.59 26.28 26.49 27.05 43.66 2.29 131.99 10.68 193.04 41.43 9.37 4.72 20.48-1.71 20.48-11.87V252.56c-.01-4.67-2.32-8.95-6.42-11.46zm248.61-49.05c-48.35 2.74-144.46 12.73-203.78 49.05-4.1 2.51-6.41 6.96-6.41 11.63v245.79c0 10.19 11.14 16.63 20.54 11.9 61.04-30.72 149.32-39.11 192.97-41.4 14.9-.78 26.49-12.73 26.49-27.06V219.14c-.01-15.63-13.56-28.01-29.81-27.09z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M0 512V48C0 21.49 21.49 0 48 0h288c26.51 0 48 21.49 48 48v464L192 400 0 512z\"],\n    \"border-all\": [448, 512, [], \"f84c\", \"M416 32H32A32 32 0 0 0 0 64v384a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V64a32 32 0 0 0-32-32zm-32 64v128H256V96zm-192 0v128H64V96zM64 416V288h128v128zm192 0V288h128v128z\"],\n    \"border-none\": [448, 512, [], \"f850\", \"M240 224h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-288 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM240 320h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-384h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM48 224H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"border-style\": [448, 512, [], \"f853\", \"M240 416h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm192 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H32A32 32 0 0 0 0 64v400a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V96h368a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"bowling-ball\": [496, 512, [], \"f436\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM120 192c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64-96c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm48 144c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"box\": [512, 512, [], \"f466\", \"M509.5 184.6L458.9 32.8C452.4 13.2 434.1 0 413.4 0H272v192h238.7c-.4-2.5-.4-5-1.2-7.4zM240 0H98.6c-20.7 0-39 13.2-45.5 32.8L2.5 184.6c-.8 2.4-.8 4.9-1.2 7.4H240V0zM0 224v240c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V224H0z\"],\n    \"box-open\": [640, 512, [], \"f49e\", \"M425.7 256c-16.9 0-32.8-9-41.4-23.4L320 126l-64.2 106.6c-8.7 14.5-24.6 23.5-41.5 23.5-4.5 0-9-.6-13.3-1.9L64 215v178c0 14.7 10 27.5 24.2 31l216.2 54.1c10.2 2.5 20.9 2.5 31 0L551.8 424c14.2-3.6 24.2-16.4 24.2-31V215l-137 39.1c-4.3 1.3-8.8 1.9-13.3 1.9zm212.6-112.2L586.8 41c-3.1-6.2-9.8-9.8-16.7-8.9L320 64l91.7 152.1c3.8 6.3 11.4 9.3 18.5 7.3l197.9-56.5c9.9-2.9 14.7-13.9 10.2-23.1zM53.2 41L1.7 143.8c-4.6 9.2.3 20.2 10.1 23l197.9 56.5c7.1 2 14.7-1 18.5-7.3L320 64 69.8 32.1c-6.9-.8-13.5 2.7-16.6 8.9z\"],\n    \"boxes\": [576, 512, [], \"f468\", \"M560 288h-80v96l-32-21.3-32 21.3v-96h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16zm-384-64h224c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16h-80v96l-32-21.3L256 96V0h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16zm64 64h-80v96l-32-21.3L96 384v-96H16c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16z\"],\n    \"braille\": [640, 512, [], \"f2a1\", \"M128 256c0 35.346-28.654 64-64 64S0 291.346 0 256s28.654-64 64-64 64 28.654 64 64zM64 384c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352C28.654 32 0 60.654 0 96s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm224 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-320c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"brain\": [576, 512, [], \"f5dc\", \"M208 0c-29.9 0-54.7 20.5-61.8 48.2-.8 0-1.4-.2-2.2-.2-35.3 0-64 28.7-64 64 0 4.8.6 9.5 1.7 14C52.5 138 32 166.6 32 200c0 12.6 3.2 24.3 8.3 34.9C16.3 248.7 0 274.3 0 304c0 33.3 20.4 61.9 49.4 73.9-.9 4.6-1.4 9.3-1.4 14.1 0 39.8 32.2 72 72 72 4.1 0 8.1-.5 12-1.2 9.6 28.5 36.2 49.2 68 49.2 39.8 0 72-32.2 72-72V64c0-35.3-28.7-64-64-64zm368 304c0-29.7-16.3-55.3-40.3-69.1 5.2-10.6 8.3-22.3 8.3-34.9 0-33.4-20.5-62-49.7-74 1-4.5 1.7-9.2 1.7-14 0-35.3-28.7-64-64-64-.8 0-1.5.2-2.2.2C422.7 20.5 397.9 0 368 0c-35.3 0-64 28.6-64 64v376c0 39.8 32.2 72 72 72 31.8 0 58.4-20.7 68-49.2 3.9.7 7.9 1.2 12 1.2 39.8 0 72-32.2 72-72 0-4.8-.5-9.5-1.4-14.1 29-12 49.4-40.6 49.4-73.9z\"],\n    \"bread-slice\": [576, 512, [], \"f7ec\", \"M288 0C108 0 0 93.4 0 169.14 0 199.44 24.24 224 64 224v256c0 17.67 16.12 32 36 32h376c19.88 0 36-14.33 36-32V224c39.76 0 64-24.56 64-54.86C576 93.4 468 0 288 0z\"],\n    \"briefcase\": [512, 512, [], \"f0b1\", \"M320 336c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h416c25.6 0 48-22.4 48-48V288H320v48zm144-208h-80V80c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h512v-80c0-25.6-22.4-48-48-48zm-144 0H192V96h128v32z\"],\n    \"briefcase-medical\": [512, 512, [], \"f469\", \"M464 128h-80V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V176c0-26.5-21.5-48-48-48zM192 96h128v32H192V96zm160 248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48z\"],\n    \"broadcast-tower\": [640, 512, [], \"f519\", \"M150.94 192h33.73c11.01 0 18.61-10.83 14.86-21.18-4.93-13.58-7.55-27.98-7.55-42.82s2.62-29.24 7.55-42.82C203.29 74.83 195.68 64 184.67 64h-33.73c-7.01 0-13.46 4.49-15.41 11.23C130.64 92.21 128 109.88 128 128c0 18.12 2.64 35.79 7.54 52.76 1.94 6.74 8.39 11.24 15.4 11.24zM89.92 23.34C95.56 12.72 87.97 0 75.96 0H40.63c-6.27 0-12.14 3.59-14.74 9.31C9.4 45.54 0 85.65 0 128c0 24.75 3.12 68.33 26.69 118.86 2.62 5.63 8.42 9.14 14.61 9.14h34.84c12.02 0 19.61-12.74 13.95-23.37-49.78-93.32-16.71-178.15-.17-209.29zM614.06 9.29C611.46 3.58 605.6 0 599.33 0h-35.42c-11.98 0-19.66 12.66-14.02 23.25 18.27 34.29 48.42 119.42.28 209.23-5.72 10.68 1.8 23.52 13.91 23.52h35.23c6.27 0 12.13-3.58 14.73-9.29C630.57 210.48 640 170.36 640 128s-9.42-82.48-25.94-118.71zM489.06 64h-33.73c-11.01 0-18.61 10.83-14.86 21.18 4.93 13.58 7.55 27.98 7.55 42.82s-2.62 29.24-7.55 42.82c-3.76 10.35 3.85 21.18 14.86 21.18h33.73c7.02 0 13.46-4.49 15.41-11.24 4.9-16.97 7.53-34.64 7.53-52.76 0-18.12-2.64-35.79-7.54-52.76-1.94-6.75-8.39-11.24-15.4-11.24zm-116.3 100.12c7.05-10.29 11.2-22.71 11.2-36.12 0-35.35-28.63-64-63.96-64-35.32 0-63.96 28.65-63.96 64 0 13.41 4.15 25.83 11.2 36.12l-130.5 313.41c-3.4 8.15.46 17.52 8.61 20.92l29.51 12.31c8.15 3.4 17.52-.46 20.91-8.61L244.96 384h150.07l49.2 118.15c3.4 8.16 12.76 12.01 20.91 8.61l29.51-12.31c8.15-3.4 12-12.77 8.61-20.92l-130.5-313.41zM271.62 320L320 203.81 368.38 320h-96.76z\"],\n    \"broom\": [640, 512, [], \"f51a\", \"M256.47 216.77l86.73 109.18s-16.6 102.36-76.57 150.12C206.66 523.85 0 510.19 0 510.19s3.8-23.14 11-55.43l94.62-112.17c3.97-4.7-.87-11.62-6.65-9.5l-60.4 22.09c14.44-41.66 32.72-80.04 54.6-97.47 59.97-47.76 163.3-40.94 163.3-40.94zM636.53 31.03l-19.86-25c-5.49-6.9-15.52-8.05-22.41-2.56l-232.48 177.8-34.14-42.97c-5.09-6.41-15.14-5.21-18.59 2.21l-25.33 54.55 86.73 109.18 58.8-12.45c8-1.69 11.42-11.2 6.34-17.6l-34.09-42.92 232.48-177.8c6.89-5.48 8.04-15.53 2.55-22.44z\"],\n    \"brush\": [384, 512, [], \"f55d\", \"M352 0H32C14.33 0 0 14.33 0 32v224h384V32c0-17.67-14.33-32-32-32zM0 320c0 35.35 28.66 64 64 64h64v64c0 35.35 28.66 64 64 64s64-28.65 64-64v-64h64c35.34 0 64-28.65 64-64v-32H0v32zm192 104c13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24s-24-10.75-24-24c0-13.26 10.75-24 24-24z\"],\n    \"bug\": [512, 512, [], \"f188\", \"M511.988 288.9c-.478 17.43-15.217 31.1-32.653 31.1H424v16c0 21.864-4.882 42.584-13.6 61.145l60.228 60.228c12.496 12.497 12.496 32.758 0 45.255-12.498 12.497-32.759 12.496-45.256 0l-54.736-54.736C345.886 467.965 314.351 480 280 480V236c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v244c-34.351 0-65.886-12.035-90.636-32.108l-54.736 54.736c-12.498 12.497-32.759 12.496-45.256 0-12.496-12.497-12.496-32.758 0-45.255l60.228-60.228C92.882 378.584 88 357.864 88 336v-16H32.666C15.23 320 .491 306.33.013 288.9-.484 270.816 14.028 256 32 256h56v-58.745l-46.628-46.628c-12.496-12.497-12.496-32.758 0-45.255 12.498-12.497 32.758-12.497 45.256 0L141.255 160h229.489l54.627-54.627c12.498-12.497 32.758-12.497 45.256 0 12.496 12.497 12.496 32.758 0 45.255L424 197.255V256h56c17.972 0 32.484 14.816 31.988 32.9zM257 0c-61.856 0-112 50.144-112 112h224C369 50.144 318.856 0 257 0z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M436 480h-20V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v456H12c-6.627 0-12 5.373-12 12v20h448v-20c0-6.627-5.373-12-12-12zM128 76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76zm0 96c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40zm52 148h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12zm76 160h-64v-84c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v84zm64-172c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40z\"],\n    \"bullhorn\": [576, 512, [], \"f0a1\", \"M576 240c0-23.63-12.95-44.04-32-55.12V32.01C544 23.26 537.02 0 512 0c-7.12 0-14.19 2.38-19.98 7.02l-85.03 68.03C364.28 109.19 310.66 128 256 128H64c-35.35 0-64 28.65-64 64v96c0 35.35 28.65 64 64 64h33.7c-1.39 10.48-2.18 21.14-2.18 32 0 39.77 9.26 77.35 25.56 110.94 5.19 10.69 16.52 17.06 28.4 17.06h74.28c26.05 0 41.69-29.84 25.9-50.56-16.4-21.52-26.15-48.36-26.15-77.44 0-11.11 1.62-21.79 4.41-32H256c54.66 0 108.28 18.81 150.98 52.95l85.03 68.03a32.023 32.023 0 0 0 19.98 7.02c24.92 0 32-22.78 32-32V295.13C563.05 284.04 576 263.63 576 240zm-96 141.42l-33.05-26.44C392.95 311.78 325.12 288 256 288v-96c69.12 0 136.95-23.78 190.95-66.98L480 98.58v282.84z\"],\n    \"bullseye\": [496, 512, [], \"f140\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 432c-101.69 0-184-82.29-184-184 0-101.69 82.29-184 184-184 101.69 0 184 82.29 184 184 0 101.69-82.29 184-184 184zm0-312c-70.69 0-128 57.31-128 128s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm0 192c-35.29 0-64-28.71-64-64s28.71-64 64-64 64 28.71 64 64-28.71 64-64 64z\"],\n    \"burn\": [384, 512, [], \"f46a\", \"M192 0C79.7 101.3 0 220.9 0 300.5 0 425 79 512 192 512s192-87 192-211.5c0-79.9-80.2-199.6-192-300.5zm0 448c-56.5 0-96-39-96-94.8 0-13.5 4.6-61.5 96-161.2 91.4 99.7 96 147.7 96 161.2 0 55.8-39.5 94.8-96 94.8z\"],\n    \"bus\": [512, 512, [], \"f207\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM112 400c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm16-112c-17.67 0-32-14.33-32-32V128c0-17.67 14.33-32 32-32h256c17.67 0 32 14.33 32 32v128c0 17.67-14.33 32-32 32H128zm272 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"bus-alt\": [512, 512, [], \"f55e\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM160 72c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H168c-4.42 0-8-3.58-8-8V72zm-48 328c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128-112H128c-17.67 0-32-14.33-32-32v-96c0-17.67 14.33-32 32-32h112v160zm32 0V128h112c17.67 0 32 14.33 32 32v96c0 17.67-14.33 32-32 32H272zm128 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"business-time\": [640, 512, [], \"f64a\", \"M496 224c-79.59 0-144 64.41-144 144s64.41 144 144 144 144-64.41 144-144-64.41-144-144-144zm64 150.29c0 5.34-4.37 9.71-9.71 9.71h-60.57c-5.34 0-9.71-4.37-9.71-9.71v-76.57c0-5.34 4.37-9.71 9.71-9.71h12.57c5.34 0 9.71 4.37 9.71 9.71V352h38.29c5.34 0 9.71 4.37 9.71 9.71v12.58zM496 192c5.4 0 10.72.33 16 .81V144c0-25.6-22.4-48-48-48h-80V48c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h395.12c28.6-20.09 63.35-32 100.88-32zM320 96H192V64h128v32zm6.82 224H208c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h291.43C327.1 423.96 320 396.82 320 368c0-16.66 2.48-32.72 6.82-48z\"],\n    \"calculator\": [448, 512, [], \"f1ec\", \"M400 0H48C22.4 0 0 22.4 0 48v416c0 25.6 22.4 48 48 48h352c25.6 0 48-22.4 48-48V48c0-25.6-22.4-48-48-48zM128 435.2c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8V268.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v166.4zm0-256c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8V76.8C64 70.4 70.4 64 76.8 64h294.4c6.4 0 12.8 6.4 12.8 12.8v102.4z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm436-44v-36c0-26.5-21.5-48-48-48h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v36c0 6.6 5.4 12 12 12h424c6.6 0 12-5.4 12-12z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm320-196c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM192 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM64 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M436 160H12c-6.627 0-12-5.373-12-12v-36c0-26.51 21.49-48 48-48h48V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h128V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h48c26.51 0 48 21.49 48 48v36c0 6.627-5.373 12-12 12zM12 192h424c6.627 0 12 5.373 12 12v260c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V204c0-6.627 5.373-12 12-12zm333.296 95.947l-28.169-28.398c-4.667-4.705-12.265-4.736-16.97-.068L194.12 364.665l-45.98-46.352c-4.667-4.705-12.266-4.736-16.971-.068l-28.397 28.17c-4.705 4.667-4.736 12.265-.068 16.97l82.601 83.269c4.667 4.705 12.265 4.736 16.97.068l142.953-141.805c4.705-4.667 4.736-12.265.068-16.97z\"],\n    \"calendar-day\": [448, 512, [], \"f783\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h96c8.8 0 16 7.2 16 16v96c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-96zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm304 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H132c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h184z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm316 140c0-6.6-5.4-12-12-12h-60v-60c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v60h-60c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h60v60c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-60h60c6.6 0 12-5.4 12-12v-40z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm257.3 160l48.1-48.1c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0L224 306.7l-48.1-48.1c-4.7-4.7-12.3-4.7-17 0l-28.3 28.3c-4.7 4.7-4.7 12.3 0 17l48.1 48.1-48.1 48.1c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l48.1-48.1 48.1 48.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L269.3 352z\"],\n    \"calendar-week\": [448, 512, [], \"f784\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h288c8.8 0 16 7.2 16 16v64c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-64zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"camera\": [512, 512, [], \"f030\", \"M512 144v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V144c0-26.5 21.5-48 48-48h88l12.3-32.9c7-18.7 24.9-31.1 44.9-31.1h125.5c20 0 37.9 12.4 44.9 31.1L376 96h88c26.5 0 48 21.5 48 48zM376 288c0-66.2-53.8-120-120-120s-120 53.8-120 120 53.8 120 120 120 120-53.8 120-120zm-32 0c0 48.5-39.5 88-88 88s-88-39.5-88-88 39.5-88 88-88 88 39.5 88 88z\"],\n    \"camera-retro\": [512, 512, [], \"f083\", \"M48 32C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48H48zm0 32h106c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H38c-3.3 0-6-2.7-6-6V80c0-8.8 7.2-16 16-16zm426 96H38c-3.3 0-6-2.7-6-6v-36c0-3.3 2.7-6 6-6h138l30.2-45.3c1.1-1.7 3-2.7 5-2.7H464c8.8 0 16 7.2 16 16v74c0 3.3-2.7 6-6 6zM256 424c-66.2 0-120-53.8-120-120s53.8-120 120-120 120 53.8 120 120-53.8 120-120 120zm0-208c-48.5 0-88 39.5-88 88s39.5 88 88 88 88-39.5 88-88-39.5-88-88-88zm-48 104c-8.8 0-16-7.2-16-16 0-35.3 28.7-64 64-64 8.8 0 16 7.2 16 16s-7.2 16-16 16c-17.6 0-32 14.4-32 32 0 8.8-7.2 16-16 16z\"],\n    \"campground\": [640, 512, [], \"f6bb\", \"M624 448h-24.68L359.54 117.75l53.41-73.55c5.19-7.15 3.61-17.16-3.54-22.35l-25.9-18.79c-7.15-5.19-17.15-3.61-22.35 3.55L320 63.3 278.83 6.6c-5.19-7.15-15.2-8.74-22.35-3.55l-25.88 18.8c-7.15 5.19-8.74 15.2-3.54 22.35l53.41 73.55L40.68 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM320 288l116.36 160H203.64L320 288z\"],\n    \"candy-cane\": [512, 512, [], \"f786\", \"M497.5 92C469.6 33.1 411.8 0 352.4 0c-27.9 0-56.2 7.3-81.8 22.6L243.1 39c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5l27.5-16.4c5.1-3.1 10.8-4.5 16.4-4.5 10.9 0 21.5 5.6 27.5 15.6 9.1 15.1 4.1 34.8-11 43.9L15.6 397.6c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5L428.6 301c71.7-42.9 104.6-133.5 68.9-209zm-177.7 13l-2.5 1.5L296.8 45c9.7-4.7 19.8-8.1 30.3-10.2l20.6 61.8c-9.8.8-19.4 3.3-27.9 8.4zM145.9 431.8l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm107.5-63.9l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zM364.3 302l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm20.4-197.3l46-46c8.4 6.5 16 14.1 22.6 22.6L407.6 127c-5.7-9.3-13.7-16.9-22.9-22.3zm82.1 107.8l-59.5-19.8c3.2-5.3 5.8-10.9 7.4-17.1 1.1-4.5 1.7-9.1 1.8-13.6l60.4 20.1c-2.1 10.4-5.5 20.6-10.1 30.4z\"],\n    \"cannabis\": [512, 512, [], \"f55f\", \"M503.47 360.25c-1.56-.82-32.39-16.89-76.78-25.81 64.25-75.12 84.05-161.67 84.93-165.64 1.18-5.33-.44-10.9-4.3-14.77-3.03-3.04-7.12-4.7-11.32-4.7-1.14 0-2.29.12-3.44.38-3.88.85-86.54 19.59-160.58 79.76.01-1.46.01-2.93.01-4.4 0-118.79-59.98-213.72-62.53-217.7A15.973 15.973 0 0 0 256 0c-5.45 0-10.53 2.78-13.47 7.37-2.55 3.98-62.53 98.91-62.53 217.7 0 1.47.01 2.94.01 4.4-74.03-60.16-156.69-78.9-160.58-79.76-1.14-.25-2.29-.38-3.44-.38-4.2 0-8.29 1.66-11.32 4.7A15.986 15.986 0 0 0 .38 168.8c.88 3.97 20.68 90.52 84.93 165.64-44.39 8.92-75.21 24.99-76.78 25.81a16.003 16.003 0 0 0-.02 28.29c2.45 1.29 60.76 31.72 133.49 31.72 6.14 0 11.96-.1 17.5-.31-11.37 22.23-16.52 38.31-16.81 39.22-1.8 5.68-.29 11.89 3.91 16.11a16.019 16.019 0 0 0 16.1 3.99c1.83-.57 37.72-11.99 77.3-39.29V504c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-64.01c39.58 27.3 75.47 38.71 77.3 39.29a16.019 16.019 0 0 0 16.1-3.99c4.2-4.22 5.71-10.43 3.91-16.11-.29-.91-5.45-16.99-16.81-39.22 5.54.21 11.37.31 17.5.31 72.72 0 131.04-30.43 133.49-31.72 5.24-2.78 8.52-8.22 8.51-14.15-.01-5.94-3.29-11.39-8.53-14.15z\"],\n    \"capsules\": [576, 512, [], \"f46b\", \"M555.3 300.1L424.2 112.8C401.9 81 366.4 64 330.4 64c-22.6 0-45.5 6.7-65.5 20.7-19.7 13.8-33.7 32.8-41.5 53.8C220.5 79.2 172 32 112 32 50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V218.9c3.3 8.6 7.3 17.1 12.8 25L368 431.2c22.2 31.8 57.7 48.8 93.8 48.8 22.7 0 45.5-6.7 65.5-20.7 51.7-36.2 64.2-107.5 28-159.2zM160 256H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm194.8 44.9l-65.6-93.7c-7.7-11-10.7-24.4-8.3-37.6 2.3-13.2 9.7-24.8 20.7-32.5 8.5-6 18.5-9.1 28.8-9.1 16.5 0 31.9 8 41.3 21.5l65.6 93.7-82.5 57.7z\"],\n    \"car\": [512, 512, [], \"f1b9\", \"M499.99 176h-59.87l-16.64-41.6C406.38 91.63 365.57 64 319.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4L71.87 176H12.01C4.2 176-1.53 183.34.37 190.91l6 24C7.7 220.25 12.5 224 18.01 224h20.07C24.65 235.73 16 252.78 16 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-19.22-8.65-36.27-22.07-48H494c5.51 0 10.31-3.75 11.64-9.09l6-24c1.89-7.57-3.84-14.91-11.65-14.91zm-352.06-17.83c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L384 208H128l19.93-49.83zM96 319.8c-19.2 0-32-12.76-32-31.9S76.8 256 96 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S396.8 256 416 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-alt\": [480, 512, [], \"f5de\", \"M438.66 212.33l-11.24-28.1-19.93-49.83C390.38 91.63 349.57 64 303.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4l-19.93 49.83-11.24 28.1C17.22 221.5 0 244.66 0 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-27.34-17.22-50.5-41.34-59.67zm-306.73-54.16c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L368 208H112l19.93-49.83zM80 319.8c-19.2 0-32-12.76-32-31.9S60.8 256 80 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S380.8 256 400 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-battery\": [512, 512, [], \"f5df\", \"M480 128h-32V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v48H192V80c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v48H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zM192 264c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm256 0c0 4.42-3.58 8-8 8h-40v40c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-40h-40c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h40v-40c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v40h40c4.42 0 8 3.58 8 8v16z\"],\n    \"car-crash\": [640, 512, [], \"f5e1\", \"M143.25 220.81l-12.42 46.37c-3.01 11.25-3.63 22.89-2.41 34.39l-35.2 28.98c-6.57 5.41-16.31-.43-14.62-8.77l15.44-76.68c1.06-5.26-2.66-10.28-8-10.79l-77.86-7.55c-8.47-.82-11.23-11.83-4.14-16.54l65.15-43.3c4.46-2.97 5.38-9.15 1.98-13.29L21.46 93.22c-5.41-6.57.43-16.3 8.78-14.62l76.68 15.44c5.26 1.06 10.28-2.66 10.8-8l7.55-77.86c.82-8.48 11.83-11.23 16.55-4.14l43.3 65.14c2.97 4.46 9.15 5.38 13.29 1.98l60.4-49.71c6.57-5.41 16.3.43 14.62 8.77L262.1 86.38c-2.71 3.05-5.43 6.09-7.91 9.4l-32.15 42.97-10.71 14.32c-32.73 8.76-59.18 34.53-68.08 67.74zm494.57 132.51l-12.42 46.36c-3.13 11.68-9.38 21.61-17.55 29.36a66.876 66.876 0 0 1-8.76 7l-13.99 52.23c-1.14 4.27-3.1 8.1-5.65 11.38-7.67 9.84-20.74 14.68-33.54 11.25L515 502.62c-17.07-4.57-27.2-22.12-22.63-39.19l8.28-30.91-247.28-66.26-8.28 30.91c-4.57 17.07-22.12 27.2-39.19 22.63l-30.91-8.28c-12.8-3.43-21.7-14.16-23.42-26.51-.57-4.12-.35-8.42.79-12.68l13.99-52.23a66.62 66.62 0 0 1-4.09-10.45c-3.2-10.79-3.65-22.52-.52-34.2l12.42-46.37c5.31-19.8 19.36-34.83 36.89-42.21a64.336 64.336 0 0 1 18.49-4.72l18.13-24.23 32.15-42.97c3.45-4.61 7.19-8.9 11.2-12.84 8-7.89 17.03-14.44 26.74-19.51 4.86-2.54 9.89-4.71 15.05-6.49 10.33-3.58 21.19-5.63 32.24-6.04 11.05-.41 22.31.82 33.43 3.8l122.68 32.87c11.12 2.98 21.48 7.54 30.85 13.43a111.11 111.11 0 0 1 34.69 34.5c8.82 13.88 14.64 29.84 16.68 46.99l6.36 53.29 3.59 30.05a64.49 64.49 0 0 1 22.74 29.93c4.39 11.88 5.29 25.19 1.75 38.39zM255.58 234.34c-18.55-4.97-34.21 4.04-39.17 22.53-4.96 18.49 4.11 34.12 22.65 39.09 18.55 4.97 45.54 15.51 50.49-2.98 4.96-18.49-15.43-53.67-33.97-58.64zm290.61 28.17l-6.36-53.29c-.58-4.87-1.89-9.53-3.82-13.86-5.8-12.99-17.2-23.01-31.42-26.82l-122.68-32.87a48.008 48.008 0 0 0-50.86 17.61l-32.15 42.97 172 46.08 75.29 20.18zm18.49 54.65c-18.55-4.97-53.8 15.31-58.75 33.79-4.95 18.49 23.69 22.86 42.24 27.83 18.55 4.97 34.21-4.04 39.17-22.53 4.95-18.48-4.11-34.12-22.66-39.09z\"],\n    \"car-side\": [640, 512, [], \"f5e4\", \"M544 192h-16L419.22 56.02A64.025 64.025 0 0 0 369.24 32H155.33c-26.17 0-49.7 15.93-59.42 40.23L48 194.26C20.44 201.4 0 226.21 0 256v112c0 8.84 7.16 16 16 16h48c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h48c8.84 0 16-7.16 16-16v-80c0-53.02-42.98-96-96-96zM160 432c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm72-240H116.93l38.4-96H232v96zm48 0V96h89.24l76.8 96H280zm200 240c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"caret-down\": [320, 512, [], \"f0d7\", \"M31.3 192h257.3c17.8 0 26.7 21.5 14.1 34.1L174.1 354.8c-7.8 7.8-20.5 7.8-28.3 0L17.2 226.1C4.6 213.5 13.5 192 31.3 192z\"],\n    \"caret-left\": [192, 512, [], \"f0d9\", \"M192 127.338v257.324c0 17.818-21.543 26.741-34.142 14.142L29.196 270.142c-7.81-7.81-7.81-20.474 0-28.284l128.662-128.662c12.599-12.6 34.142-3.676 34.142 14.142z\"],\n    \"caret-right\": [192, 512, [], \"f0da\", \"M0 384.662V127.338c0-17.818 21.543-26.741 34.142-14.142l128.662 128.662c7.81 7.81 7.81 20.474 0 28.284L34.142 398.804C21.543 411.404 0 402.48 0 384.662z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM92.5 220.5l123 123c4.7 4.7 12.3 4.7 17 0l123-123c7.6-7.6 2.2-20.5-8.5-20.5H101c-10.7 0-16.1 12.9-8.5 20.5z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM259.515 124.485l-123.03 123.03c-4.686 4.686-4.686 12.284 0 16.971l123.029 123.029c7.56 7.56 20.485 2.206 20.485-8.485V132.971c.001-10.691-12.925-16.045-20.484-8.486z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M48 32h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48zm140.485 355.515l123.029-123.029c4.686-4.686 4.686-12.284 0-16.971l-123.029-123.03c-7.56-7.56-20.485-2.206-20.485 8.485v246.059c0 10.691 12.926 16.045 20.485 8.486z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M0 432V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48zm355.515-140.485l-123.03-123.03c-4.686-4.686-12.284-4.686-16.971 0L92.485 291.515c-7.56 7.56-2.206 20.485 8.485 20.485h246.059c10.691 0 16.045-12.926 8.486-20.485z\"],\n    \"caret-up\": [320, 512, [], \"f0d8\", \"M288.662 352H31.338c-17.818 0-26.741-21.543-14.142-34.142l128.662-128.662c7.81-7.81 20.474-7.81 28.284 0l128.662 128.662c12.6 12.599 3.676 34.142-14.142 34.142z\"],\n    \"carrot\": [512, 512, [], \"f787\", \"M298.2 156.6c-52.7-25.7-114.5-10.5-150.2 32.8l55.2 55.2c6.3 6.3 6.3 16.4 0 22.6-3.1 3.1-7.2 4.7-11.3 4.7s-8.2-1.6-11.3-4.7L130.4 217 2.3 479.7c-2.9 6-3.1 13.3 0 19.7 5.4 11.1 18.9 15.7 30 10.3l133.6-65.2-49.2-49.2c-6.3-6.2-6.3-16.4 0-22.6 6.3-6.2 16.4-6.2 22.6 0l57 57 102-49.8c24-11.7 44.5-31.3 57.1-57.1 30.1-61.7 4.5-136.1-57.2-166.2zm92.1-34.9C409.8 81 399.7 32.9 360 0c-50.3 41.7-52.5 107.5-7.9 151.9l8 8c44.4 44.6 110.3 42.4 151.9-7.9-32.9-39.7-81-49.8-121.7-30.3z\"],\n    \"cart-arrow-down\": [576, 512, [], \"f218\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM403.029 192H360v-60c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v60h-43.029c-10.691 0-16.045 12.926-8.485 20.485l67.029 67.029c4.686 4.686 12.284 4.686 16.971 0l67.029-67.029c7.559-7.559 2.205-20.485-8.486-20.485z\"],\n    \"cart-plus\": [576, 512, [], \"f217\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM408 168h-48v-40c0-8.837-7.163-16-16-16h-16c-8.837 0-16 7.163-16 16v40h-48c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h48v40c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-40h48c8.837 0 16-7.163 16-16v-16c0-8.837-7.163-16-16-16z\"],\n    \"cash-register\": [512, 512, [], \"f788\", \"M511.1 378.8l-26.7-160c-2.6-15.4-15.9-26.7-31.6-26.7H208v-64h96c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h96v64H59.1c-15.6 0-29 11.3-31.6 26.7L.8 378.7c-.6 3.5-.9 7-.9 10.5V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-90.7c.1-3.5-.2-7-.8-10.5zM280 248c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16zm-32 64h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16zm-32-80c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16zM80 80V48h192v32H80zm40 200h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16zm16 64v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16zm216 112c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16zm24-112c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16zm48-80c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16z\"],\n    \"cat\": [512, 512, [], \"f6be\", \"M290.59 192c-20.18 0-106.82 1.98-162.59 85.95V192c0-52.94-43.06-96-96-96-17.67 0-32 14.33-32 32s14.33 32 32 32c17.64 0 32 14.36 32 32v256c0 35.3 28.7 64 64 64h176c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-32l128-96v144c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V289.86c-10.29 2.67-20.89 4.54-32 4.54-61.81 0-113.52-44.05-125.41-102.4zM448 96h-64l-64-64v134.4c0 53.02 42.98 96 96 96s96-42.98 96-96V32l-64 64zm-72 80c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm80 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"certificate\": [512, 512, [], \"f0a3\", \"M458.622 255.92l45.985-45.005c13.708-12.977 7.316-36.039-10.664-40.339l-62.65-15.99 17.661-62.015c4.991-17.838-11.829-34.663-29.661-29.671l-61.994 17.667-15.984-62.671C337.085.197 313.765-6.276 300.99 7.228L256 53.57 211.011 7.229c-12.63-13.351-36.047-7.234-40.325 10.668l-15.984 62.671-61.995-17.667C74.87 57.907 58.056 74.738 63.046 92.572l17.661 62.015-62.65 15.99C.069 174.878-6.31 197.944 7.392 210.915l45.985 45.005-45.985 45.004c-13.708 12.977-7.316 36.039 10.664 40.339l62.65 15.99-17.661 62.015c-4.991 17.838 11.829 34.663 29.661 29.671l61.994-17.667 15.984 62.671c4.439 18.575 27.696 24.018 40.325 10.668L256 458.61l44.989 46.001c12.5 13.488 35.987 7.486 40.325-10.668l15.984-62.671 61.994 17.667c17.836 4.994 34.651-11.837 29.661-29.671l-17.661-62.015 62.65-15.99c17.987-4.302 24.366-27.367 10.664-40.339l-45.984-45.004z\"],\n    \"chair\": [448, 512, [], \"f6c0\", \"M112 128c0-29.5 16.2-55 40-68.9V256h48V48h48v208h48V59.1c23.8 13.9 40 39.4 40 68.9v128h48V128C384 57.3 326.7 0 256 0h-64C121.3 0 64 57.3 64 128v128h48zm334.3 213.9l-10.7-32c-4.4-13.1-16.6-21.9-30.4-21.9H42.7c-13.8 0-26 8.8-30.4 21.9l-10.7 32C-5.2 362.6 10.2 384 32 384v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384h256v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384c21.8 0 37.2-21.4 30.3-42.1z\"],\n    \"chalkboard\": [640, 512, [], \"f51b\", \"M96 64h448v352h64V40c0-22.06-17.94-40-40-40H72C49.94 0 32 17.94 32 40v376h64V64zm528 384H480v-64H288v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chalkboard-teacher\": [640, 512, [], \"f51c\", \"M208 352c-2.39 0-4.78.35-7.06 1.09C187.98 357.3 174.35 360 160 360c-14.35 0-27.98-2.7-40.95-6.91-2.28-.74-4.66-1.09-7.05-1.09C49.94 352-.33 402.48 0 464.62.14 490.88 21.73 512 48 512h224c26.27 0 47.86-21.12 48-47.38.33-62.14-49.94-112.62-112-112.62zm-48-32c53.02 0 96-42.98 96-96s-42.98-96-96-96-96 42.98-96 96 42.98 96 96 96zM592 0H208c-26.47 0-48 22.25-48 49.59V96c23.42 0 45.1 6.78 64 17.8V64h352v288h-64v-64H384v64h-76.24c19.1 16.69 33.12 38.73 39.69 64H592c26.47 0 48-22.25 48-49.59V49.59C640 22.25 618.47 0 592 0z\"],\n    \"charging-station\": [576, 512, [], \"f5e7\", \"M336 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h320c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm208-320V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-32V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-16c-8.84 0-16 7.16-16 16v32c0 35.76 23.62 65.69 56 75.93v118.49c0 13.95-9.5 26.92-23.26 29.19C431.22 402.5 416 388.99 416 372v-28c0-48.6-39.4-88-88-88h-8V64c0-35.35-28.65-64-64-64H96C60.65 0 32 28.65 32 64v352h288V304h8c22.09 0 40 17.91 40 40v24.61c0 39.67 28.92 75.16 68.41 79.01C481.71 452.05 520 416.41 520 372V251.93c32.38-10.24 56-40.17 56-75.93v-32c0-8.84-7.16-16-16-16h-16zm-283.91 47.76l-93.7 139c-2.2 3.33-6.21 5.24-10.39 5.24-7.67 0-13.47-6.28-11.67-12.92L167.35 224H108c-7.25 0-12.85-5.59-11.89-11.89l16-107C112.9 99.9 117.98 96 124 96h68c7.88 0 13.62 6.54 11.6 13.21L192 160h57.7c9.24 0 15.01 8.78 10.39 15.76z\"],\n    \"chart-area\": [512, 512, [], \"f1fe\", \"M500 384c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v308h436zM372.7 159.5L288 216l-85.3-113.7c-5.1-6.8-15.5-6.3-19.9 1L96 248v104h384l-89.9-187.8c-3.2-6.5-11.4-8.7-17.4-4.7z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M332.8 320h38.4c6.4 0 12.8-6.4 12.8-12.8V172.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V76.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-288 0h38.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zM496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chart-line\": [512, 512, [], \"f201\", \"M496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM464 96H345.94c-21.38 0-32.09 25.85-16.97 40.97l32.4 32.4L288 242.75l-73.37-73.37c-12.5-12.5-32.76-12.5-45.25 0l-68.69 68.69c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L192 237.25l73.37 73.37c12.5 12.5 32.76 12.5 45.25 0l96-96 32.4 32.4c15.12 15.12 40.97 4.41 40.97-16.97V112c.01-8.84-7.15-16-15.99-16z\"],\n    \"chart-pie\": [544, 512, [], \"f200\", \"M527.79 288H290.5l158.03 158.03c6.04 6.04 15.98 6.53 22.19.68 38.7-36.46 65.32-85.61 73.13-140.86 1.34-9.46-6.51-17.85-16.06-17.85zm-15.83-64.8C503.72 103.74 408.26 8.28 288.8.04 279.68-.59 272 7.1 272 16.24V240h223.77c9.14 0 16.82-7.68 16.19-16.8zM224 288V50.71c0-9.55-8.39-17.4-17.84-16.06C86.99 51.49-4.1 155.6.14 280.37 4.5 408.51 114.83 513.59 243.03 511.98c50.4-.63 96.97-16.87 135.26-44.03 7.9-5.6 8.42-17.23 1.57-24.08L224 288z\"],\n    \"check\": [512, 512, [], \"f00c\", \"M173.898 439.404l-166.4-166.4c-9.997-9.997-9.997-26.206 0-36.204l36.203-36.204c9.997-9.998 26.207-9.998 36.204 0L192 312.69 432.095 72.596c9.997-9.997 26.207-9.997 36.204 0l36.203 36.204c9.997 9.997 9.997 26.206 0 36.204l-294.4 294.401c-9.998 9.997-26.207 9.997-36.204-.001z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM227.314 387.314l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.249-16.379-6.249-22.628 0L216 308.118l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.249 16.379 6.249 22.628.001z\"],\n    \"check-double\": [512, 512, [], \"f560\", \"M505 174.8l-39.6-39.6c-9.4-9.4-24.6-9.4-33.9 0L192 374.7 80.6 263.2c-9.4-9.4-24.6-9.4-33.9 0L7 302.9c-9.4 9.4-9.4 24.6 0 34L175 505c9.4 9.4 24.6 9.4 33.9 0l296-296.2c9.4-9.5 9.4-24.7.1-34zm-324.3 106c6.2 6.3 16.4 6.3 22.6 0l208-208.2c6.2-6.3 6.2-16.4 0-22.6L366.1 4.7c-6.2-6.3-16.4-6.3-22.6 0L192 156.2l-55.4-55.5c-6.2-6.3-16.4-6.3-22.6 0L68.7 146c-6.2 6.3-6.2 16.4 0 22.6l112 112.2z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zm-204.686-98.059l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.248-16.379-6.249-22.628 0L184 302.745l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.25 16.379 6.25 22.628.001z\"],\n    \"cheese\": [512, 512, [], \"f7ef\", \"M0 288v160a32 32 0 0 0 32 32h448a32 32 0 0 0 32-32V288zM299.83 32a32 32 0 0 0-21.13 7L0 256h512c0-119.89-94-217.8-212.17-224z\"],\n    \"chess\": [512, 512, [], \"f439\", \"M74 208H64a16 16 0 0 0-16 16v16a16 16 0 0 0 16 16h15.94A535.78 535.78 0 0 1 64 384h128a535.78 535.78 0 0 1-15.94-128H192a16 16 0 0 0 16-16v-16a16 16 0 0 0-16-16h-10l33.89-90.38a16 16 0 0 0-15-21.62H144V64h24a8 8 0 0 0 8-8V40a8 8 0 0 0-8-8h-24V8a8 8 0 0 0-8-8h-16a8 8 0 0 0-8 8v24H88a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h24v32H55.09a16 16 0 0 0-15 21.62zm173.16 251.58L224 448v-16a16 16 0 0 0-16-16H48a16 16 0 0 0-16 16v16L8.85 459.58A16 16 0 0 0 0 473.89V496a16 16 0 0 0 16 16h224a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31zm92.77-157.78l-3.29 82.2h126.72l-3.29-82.21 24.6-20.79A32 32 0 0 0 496 256.54V198a6 6 0 0 0-6-6h-26.38a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H373.1a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H310a6 6 0 0 0-6 6v58.6a32 32 0 0 0 11.36 24.4zM384 304a16 16 0 0 1 32 0v32h-32zm119.16 155.58L480 448v-16a16 16 0 0 0-16-16H336a16 16 0 0 0-16 16v16l-23.15 11.58a16 16 0 0 0-8.85 14.31V496a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31z\"],\n    \"chess-bishop\": [320, 512, [], \"f43a\", \"M8 287.88c0 51.64 22.14 73.83 56 84.6V416h192v-43.52c33.86-10.77 56-33 56-84.6 0-30.61-10.73-67.1-26.69-102.56L185 285.65a8 8 0 0 1-11.31 0l-11.31-11.31a8 8 0 0 1 0-11.31L270.27 155.1c-20.8-37.91-46.47-72.1-70.87-92.59C213.4 59.09 224 47.05 224 32a32 32 0 0 0-32-32h-64a32 32 0 0 0-32 32c0 15 10.6 27.09 24.6 30.51C67.81 106.8 8 214.5 8 287.88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-board\": [512, 512, [], \"f43c\", \"M255.9.2h-64v64h64zM0 64.17v64h64v-64zM128 .2H64v64h64zm64 255.9v64h64v-64zM0 192.12v64h64v-64zM383.85.2h-64v64h64zm128 0h-64v64h64zM128 256.1H64v64h64zM511.8 448v-64h-64v64zm0-128v-64h-64v64zM383.85 512h64v-64h-64zm128-319.88v-64h-64v64zM128 512h64v-64h-64zM0 512h64v-64H0zm255.9 0h64v-64h-64zM0 320.07v64h64v-64zm319.88-191.92v-64h-64v64zm-64 128h64v-64h-64zm-64 128v64h64v-64zm128-64h64v-64h-64zm0-127.95h64v-64h-64zm0 191.93v64h64v-64zM64 384.05v64h64v-64zm128-255.9v-64h-64v64zm191.92 255.9h64v-64h-64zm-128-191.93v-64h-64v64zm128-127.95v64h64v-64zm-128 255.9v64h64v-64zm-64-127.95H128v64h64zm191.92 64h64v-64h-64zM128 128.15H64v64h64zm0 191.92v64h64v-64z\"],\n    \"chess-king\": [448, 512, [], \"f43f\", \"M400 448H48a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm16-288H256v-48h40a8 8 0 0 0 8-8V56a8 8 0 0 0-8-8h-40V8a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v40h-40a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8h40v48H32a32 32 0 0 0-30.52 41.54L74.56 416h298.88l73.08-214.46A32 32 0 0 0 416 160z\"],\n    \"chess-knight\": [384, 512, [], \"f441\", \"M19 272.47l40.63 18.06a32 32 0 0 0 24.88.47l12.78-5.12a32 32 0 0 0 18.76-20.5l9.22-30.65a24 24 0 0 1 12.55-15.65L159.94 208v50.33a48 48 0 0 1-26.53 42.94l-57.22 28.65A80 80 0 0 0 32 401.48V416h319.86V224c0-106-85.92-192-191.92-192H12A12 12 0 0 0 0 44a16.9 16.9 0 0 0 1.79 7.58L16 80l-9 9a24 24 0 0 0-7 17v137.21a32 32 0 0 0 19 29.26zM52 128a20 20 0 1 1-20 20 20 20 0 0 1 20-20zm316 320H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-pawn\": [320, 512, [], \"f443\", \"M105.1 224H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h16v5.49c0 44-4.14 86.6-24 122.51h176c-19.89-35.91-24-78.51-24-122.51V288h16a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-25.1c29.39-18.38 49.1-50.78 49.1-88a104 104 0 0 0-208 0c0 37.22 19.71 69.62 49.1 88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-queen\": [512, 512, [], \"f445\", \"M256 112a56 56 0 1 0-56-56 56 56 0 0 0 56 56zm176 336H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm72.87-263.84l-28.51-15.92c-7.44-5-16.91-2.46-22.29 4.68a47.59 47.59 0 0 1-47.23 18.23C383.7 186.86 368 164.93 368 141.4a13.4 13.4 0 0 0-13.4-13.4h-38.77c-6 0-11.61 4-12.86 9.91a48 48 0 0 1-93.94 0c-1.25-5.92-6.82-9.91-12.86-9.91H157.4a13.4 13.4 0 0 0-13.4 13.4c0 25.69-19 48.75-44.67 50.49a47.5 47.5 0 0 1-41.54-19.15c-5.28-7.09-14.73-9.45-22.09-4.54l-28.57 16a16 16 0 0 0-5.44 20.47L104.24 416h303.52l102.55-211.37a16 16 0 0 0-5.44-20.47z\"],\n    \"chess-rook\": [384, 512, [], \"f447\", \"M368 32h-56a16 16 0 0 0-16 16v48h-48V48a16 16 0 0 0-16-16h-80a16 16 0 0 0-16 16v48H88.1V48a16 16 0 0 0-16-16H16A16 16 0 0 0 0 48v176l64 32c0 48.33-1.54 95-13.21 160h282.42C321.54 351 320 303.72 320 256l64-32V48a16 16 0 0 0-16-16zM224 320h-64v-64a32 32 0 0 1 64 0zm144 128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chevron-circle-down\": [512, 512, [], \"f13a\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM273 369.9l135.5-135.5c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L256 285.1 154.4 183.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L239 369.9c9.4 9.4 24.6 9.4 34 0z\"],\n    \"chevron-circle-left\": [512, 512, [], \"f137\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zM142.1 273l135.5 135.5c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L226.9 256l101.6-101.6c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L142.1 239c-9.4 9.4-9.4 24.6 0 34z\"],\n    \"chevron-circle-right\": [512, 512, [], \"f138\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm113.9 231L234.4 103.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L285.1 256 183.5 357.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L369.9 273c9.4-9.4 9.4-24.6 0-34z\"],\n    \"chevron-circle-up\": [512, 512, [], \"f139\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm231-113.9L103.5 277.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L256 226.9l101.6 101.6c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L273 142.1c-9.4-9.4-24.6-9.4-34 0z\"],\n    \"chevron-down\": [448, 512, [], \"f078\", \"M207.029 381.476L12.686 187.132c-9.373-9.373-9.373-24.569 0-33.941l22.667-22.667c9.357-9.357 24.522-9.375 33.901-.04L224 284.505l154.745-154.021c9.379-9.335 24.544-9.317 33.901.04l22.667 22.667c9.373 9.373 9.373 24.569 0 33.941L240.971 381.476c-9.373 9.372-24.569 9.372-33.942 0z\"],\n    \"chevron-left\": [320, 512, [], \"f053\", \"M34.52 239.03L228.87 44.69c9.37-9.37 24.57-9.37 33.94 0l22.67 22.67c9.36 9.36 9.37 24.52.04 33.9L131.49 256l154.02 154.75c9.34 9.38 9.32 24.54-.04 33.9l-22.67 22.67c-9.37 9.37-24.57 9.37-33.94 0L34.52 272.97c-9.37-9.37-9.37-24.57 0-33.94z\"],\n    \"chevron-right\": [320, 512, [], \"f054\", \"M285.476 272.971L91.132 467.314c-9.373 9.373-24.569 9.373-33.941 0l-22.667-22.667c-9.357-9.357-9.375-24.522-.04-33.901L188.505 256 34.484 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L285.475 239.03c9.373 9.372 9.373 24.568.001 33.941z\"],\n    \"chevron-up\": [448, 512, [], \"f077\", \"M240.971 130.524l194.343 194.343c9.373 9.373 9.373 24.569 0 33.941l-22.667 22.667c-9.357 9.357-24.522 9.375-33.901.04L224 227.495 69.255 381.516c-9.379 9.335-24.544 9.317-33.901-.04l-22.667-22.667c-9.373-9.373-9.373-24.569 0-33.941L207.03 130.525c9.372-9.373 24.568-9.373 33.941-.001z\"],\n    \"child\": [384, 512, [], \"f1ae\", \"M120 72c0-39.765 32.235-72 72-72s72 32.235 72 72c0 39.764-32.235 72-72 72s-72-32.236-72-72zm254.627 1.373c-12.496-12.497-32.758-12.497-45.254 0L242.745 160H141.254L54.627 73.373c-12.496-12.497-32.758-12.497-45.254 0-12.497 12.497-12.497 32.758 0 45.255L104 213.254V480c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V368h16v112c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V213.254l94.627-94.627c12.497-12.497 12.497-32.757 0-45.254z\"],\n    \"church\": [640, 512, [], \"f51d\", \"M464.46 246.68L352 179.2V128h48c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-48V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v48h-48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v51.2l-112.46 67.48A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.65-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.54A32.024 32.024 0 0 0 0 395.96zm620.61-29.42L512 320v192h112c8.84 0 16-7.16 16-16V395.96c0-12.8-7.63-24.37-19.39-29.42z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8z\"],\n    \"circle-notch\": [512, 512, [], \"f1ce\", \"M288 39.056v16.659c0 10.804 7.281 20.159 17.686 23.066C383.204 100.434 440 171.518 440 256c0 101.689-82.295 184-184 184-101.689 0-184-82.295-184-184 0-84.47 56.786-155.564 134.312-177.219C216.719 75.874 224 66.517 224 55.712V39.064c0-15.709-14.834-27.153-30.046-23.234C86.603 43.482 7.394 141.206 8.003 257.332c.72 137.052 111.477 246.956 248.531 246.667C393.255 503.711 504 392.788 504 256c0-115.633-79.14-212.779-186.211-240.236C302.678 11.889 288 23.456 288 39.056z\"],\n    \"city\": [640, 512, [], \"f64f\", \"M616 192H480V24c0-13.26-10.74-24-24-24H312c-13.26 0-24 10.74-24 24v72h-64V16c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v80h-64V16c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v80H24c-13.26 0-24 10.74-24 24v360c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V216c0-13.26-10.75-24-24-24zM128 404c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm128 192c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12V76c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 288c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40z\"],\n    \"clinic-medical\": [576, 512, [], \"f7f2\", \"M288 115L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2zm96 261a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8zm186.69-139.72l-255.94-226a39.85 39.85 0 0 0-53.45 0l-256 226a16 16 0 0 0-1.21 22.6L25.5 282.7a16 16 0 0 0 22.6 1.21L277.42 81.63a16 16 0 0 1 21.17 0L527.91 283.9a16 16 0 0 0 22.6-1.21l21.4-23.82a16 16 0 0 0-1.22-22.59z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M384 112v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h80c0-35.29 28.71-64 64-64s64 28.71 64 64h80c26.51 0 48 21.49 48 48zM192 40c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24m96 114v-20a6 6 0 0 0-6-6H102a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h180a6 6 0 0 0 6-6z\"],\n    \"clipboard-check\": [384, 512, [], \"f46c\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm121.2 231.8l-143 141.8c-4.7 4.7-12.3 4.6-17-.1l-82.6-83.3c-4.7-4.7-4.6-12.3.1-17L99.1 285c4.7-4.7 12.3-4.6 17 .1l46 46.4 106-105.2c4.7-4.7 12.3-4.6 17 .1l28.2 28.4c4.7 4.8 4.6 12.3-.1 17z\"],\n    \"clipboard-list\": [384, 512, [], \"f46d\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM96 424c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm96-192c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm128 368c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm57.1 350.1L224.9 294c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v137.7l63.5 46.2c5.4 3.9 6.5 11.4 2.6 16.8l-28.2 38.8c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48H176c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h288M176 416c-44.112 0-80-35.888-80-80V128H48c-26.51 0-48 21.49-48 48v288c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48v-48H176z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM218.1 287.7c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2.1 48 51.1 70.5 92.3 32.6zm190.4 0c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.5 56.9-172.7 32.1-172.7-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 222.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6z\"],\n    \"cloud\": [640, 512, [], \"f0c2\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4z\"],\n    \"cloud-download-alt\": [640, 512, [], \"f381\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zm-132.9 88.7L299.3 420.7c-6.2 6.2-16.4 6.2-22.6 0L171.3 315.3c-10.1-10.1-2.9-27.3 11.3-27.3H248V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v112h65.4c14.2 0 21.4 17.2 11.3 27.3z\"],\n    \"cloud-meatball\": [512, 512, [], \"f73b\", \"M48 352c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm416 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm-119 11.1c4.6-14.5 1.6-30.8-9.8-42.3-11.5-11.5-27.8-14.4-42.3-9.9-7-13.5-20.7-23-36.9-23s-29.9 9.5-36.9 23c-14.5-4.6-30.8-1.6-42.3 9.9-11.5 11.5-14.4 27.8-9.9 42.3-13.5 7-23 20.7-23 36.9s9.5 29.9 23 36.9c-4.6 14.5-1.6 30.8 9.9 42.3 8.2 8.2 18.9 12.3 29.7 12.3 4.3 0 8.5-1.1 12.6-2.5 7 13.5 20.7 23 36.9 23s29.9-9.5 36.9-23c4.1 1.3 8.3 2.5 12.6 2.5 10.8 0 21.5-4.1 29.7-12.3 11.5-11.5 14.4-27.8 9.8-42.3 13.5-7 23-20.7 23-36.9s-9.5-29.9-23-36.9zM512 224c0-53-43-96-96-96-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h43.4c3.6-8 8.4-15.4 14.8-21.8 13.5-13.5 31.5-21.1 50.8-21.3 13.5-13.2 31.7-20.9 51-20.9s37.5 7.7 51 20.9c19.3.2 37.3 7.8 50.8 21.3 6.4 6.4 11.3 13.8 14.8 21.8H416c53 0 96-43 96-96z\"],\n    \"cloud-moon\": [576, 512, [], \"f6c3\", \"M342.8 352.7c5.7-9.6 9.2-20.7 9.2-32.7 0-35.3-28.7-64-64-64-17.2 0-32.8 6.9-44.3 17.9-16.3-29.6-47.5-49.9-83.7-49.9-53 0-96 43-96 96 0 2 .5 3.8.6 5.7C27.1 338.8 0 374.1 0 416c0 53 43 96 96 96h240c44.2 0 80-35.8 80-80 0-41.9-32.3-75.8-73.2-79.3zm222.5-54.3c-93.1 17.7-178.5-53.7-178.5-147.7 0-54.2 29-104 76.1-130.8 7.3-4.1 5.4-15.1-2.8-16.7C448.4 1.1 436.7 0 425 0 319.1 0 233.1 85.9 233.1 192c0 8.5.7 16.8 1.8 25 5.9 4.3 11.6 8.9 16.7 14.2 11.4-4.7 23.7-7.2 36.4-7.2 52.9 0 96 43.1 96 96 0 3.6-.2 7.2-.6 10.7 23.6 10.8 42.4 29.5 53.5 52.6 54.4-3.4 103.7-29.3 137.1-70.4 5.3-6.5-.5-16.1-8.7-14.5z\"],\n    \"cloud-moon-rain\": [576, 512, [], \"f73c\", \"M350.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C27.6 232.9 0 265.2 0 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm217.4-1.7c-70.4 13.3-135-40.3-135-110.8 0-40.6 21.9-78 57.5-98.1 5.5-3.1 4.1-11.4-2.1-12.5C479.6.8 470.7 0 461.8 0c-77.9 0-141.1 61.2-144.4 137.9 26.7 11.9 48.2 33.8 58.9 61.7 37.1 14.3 64 47.4 70.2 86.8 5.1.5 10 1.5 15.2 1.5 44.7 0 85.6-20.2 112.6-53.3 4.2-4.8-.2-12-6.4-10.8zM364.5 418.1c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-rain\": [512, 512, [], \"f73d\", \"M416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96zM88 374.2c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0z\"],\n    \"cloud-showers-heavy\": [512, 512, [], \"f740\", \"M183.9 370.1c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-192 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm384 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zM416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.2 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96z\"],\n    \"cloud-sun\": [640, 512, [], \"f6c4\", \"M575.2 325.7c.2-1.9.8-3.7.8-5.6 0-35.3-28.7-64-64-64-12.6 0-24.2 3.8-34.1 10-17.6-38.8-56.5-66-101.9-66-61.8 0-112 50.1-112 112 0 3 .7 5.8.9 8.7-49.6 3.7-88.9 44.7-88.9 95.3 0 53 43 96 96 96h272c53 0 96-43 96-96 0-42.1-27.2-77.4-64.8-90.4zm-430.4-22.6c-43.7-43.7-43.7-114.7 0-158.3 43.7-43.7 114.7-43.7 158.4 0 9.7 9.7 16.9 20.9 22.3 32.7 9.8-3.7 20.1-6 30.7-7.5L386 81.1c4-11.9-7.3-23.1-19.2-19.2L279 91.2 237.5 8.4C232-2.8 216-2.8 210.4 8.4L169 91.2 81.1 61.9C69.3 58 58 69.3 61.9 81.1l29.3 87.8-82.8 41.5c-11.2 5.6-11.2 21.5 0 27.1l82.8 41.4-29.3 87.8c-4 11.9 7.3 23.1 19.2 19.2l76.1-25.3c6.1-12.4 14-23.7 23.6-33.5-13.1-5.4-25.4-13.4-36-24zm-4.8-79.2c0 40.8 29.3 74.8 67.9 82.3 8-4.7 16.3-8.8 25.2-11.7 5.4-44.3 31-82.5 67.4-105C287.3 160.4 258 140 224 140c-46.3 0-84 37.6-84 83.9z\"],\n    \"cloud-sun-rain\": [576, 512, [], \"f743\", \"M510.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C187.6 233 160 265.2 160 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm-386.4 34.4c-37.4-37.4-37.4-98.3 0-135.8 34.6-34.6 89.1-36.8 126.7-7.4 20-12.9 43.6-20.7 69.2-20.7.7 0 1.3.2 2 .2l8.9-26.7c3.4-10.2-6.3-19.8-16.5-16.4l-75.3 25.1-35.5-71c-4.8-9.6-18.5-9.6-23.3 0l-35.5 71-75.3-25.1c-10.2-3.4-19.8 6.3-16.4 16.5l25.1 75.3-71 35.5c-9.6 4.8-9.6 18.5 0 23.3l71 35.5-25.1 75.3c-3.4 10.2 6.3 19.8 16.5 16.5l59.2-19.7c-.2-2.4-.7-4.7-.7-7.2 0-12.5 2.3-24.5 6.2-35.9-3.6-2.7-7.1-5.2-10.2-8.3zm69.8-58c4.3-24.5 15.8-46.4 31.9-64-9.8-6.2-21.4-9.9-33.8-9.9-35.3 0-64 28.7-64 64 0 18.7 8.2 35.4 21.1 47.1 11.3-15.9 26.6-28.9 44.8-37.2zm330.6 216.2c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-upload-alt\": [640, 512, [], \"f382\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zM393.4 288H328v112c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V288h-65.4c-14.3 0-21.4-17.2-11.3-27.3l105.4-105.4c6.2-6.2 16.4-6.2 22.6 0l105.4 105.4c10.1 10.1 2.9 27.3-11.3 27.3z\"],\n    \"cocktail\": [576, 512, [], \"f561\", \"M296 464h-56V338.78l168.74-168.73c15.52-15.52 4.53-42.05-17.42-42.05H24.68c-21.95 0-32.94 26.53-17.42 42.05L176 338.78V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM432 0c-62.61 0-115.35 40.2-135.18 96h52.54c16.65-28.55 47.27-48 82.64-48 52.93 0 96 43.06 96 96s-43.07 96-96 96c-14.04 0-27.29-3.2-39.32-8.64l-35.26 35.26C379.23 279.92 404.59 288 432 288c79.53 0 144-64.47 144-144S511.53 0 432 0z\"],\n    \"code\": [640, 512, [], \"f121\", \"M278.9 511.5l-61-17.7c-6.4-1.8-10-8.5-8.2-14.9L346.2 8.7c1.8-6.4 8.5-10 14.9-8.2l61 17.7c6.4 1.8 10 8.5 8.2 14.9L293.8 503.3c-1.9 6.4-8.5 10.1-14.9 8.2zm-114-112.2l43.5-46.4c4.6-4.9 4.3-12.7-.8-17.2L117 256l90.6-79.7c5.1-4.5 5.5-12.3.8-17.2l-43.5-46.4c-4.5-4.8-12.1-5.1-17-.5L3.8 247.2c-5.1 4.7-5.1 12.8 0 17.5l144.1 135.1c4.9 4.6 12.5 4.4 17-.5zm327.2.6l144.1-135.1c5.1-4.7 5.1-12.8 0-17.5L492.1 112.1c-4.8-4.5-12.4-4.3-17 .5L431.6 159c-4.6 4.9-4.3 12.7.8 17.2L523 256l-90.6 79.7c-5.1 4.5-5.5 12.3-.8 17.2l43.5 46.4c4.5 4.9 12.1 5.1 17 .6z\"],\n    \"code-branch\": [384, 512, [], \"f126\", \"M384 144c0-44.2-35.8-80-80-80s-80 35.8-80 80c0 36.4 24.3 67.1 57.5 76.8-.6 16.1-4.2 28.5-11 36.9-15.4 19.2-49.3 22.4-85.2 25.7-28.2 2.6-57.4 5.4-81.3 16.9v-144c32.5-10.2 56-40.5 56-76.3 0-44.2-35.8-80-80-80S0 35.8 0 80c0 35.8 23.5 66.1 56 76.3v199.3C23.5 365.9 0 396.2 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-34-21.2-63.1-51.2-74.6 3.1-5.2 7.8-9.8 14.9-13.4 16.2-8.2 40.4-10.4 66.1-12.8 42.2-3.9 90-8.4 118.2-43.4 14-17.4 21.1-39.8 21.6-67.9 31.6-10.8 54.4-40.7 54.4-75.9zM80 64c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16zm0 384c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm224-320c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16z\"],\n    \"coffee\": [640, 512, [], \"f0f4\", \"M192 384h192c53 0 96-43 96-96h32c70.6 0 128-57.4 128-128S582.6 32 512 32H120c-13.3 0-24 10.7-24 24v232c0 53 43 96 96 96zM512 96c35.3 0 64 28.7 64 64s-28.7 64-64 64h-32V96h32zm47.7 384H48.3c-47.6 0-61-64-36-64h583.3c25 0 11.8 64-35.9 64z\"],\n    \"cog\": [512, 512, [], \"f013\", \"M487.4 315.7l-42.6-24.6c4.3-23.2 4.3-47 0-70.2l42.6-24.6c4.9-2.8 7.1-8.6 5.5-14-11.1-35.6-30-67.8-54.7-94.6-3.8-4.1-10-5.1-14.8-2.3L380.8 110c-17.9-15.4-38.5-27.3-60.8-35.1V25.8c0-5.6-3.9-10.5-9.4-11.7-36.7-8.2-74.3-7.8-109.2 0-5.5 1.2-9.4 6.1-9.4 11.7V75c-22.2 7.9-42.8 19.8-60.8 35.1L88.7 85.5c-4.9-2.8-11-1.9-14.8 2.3-24.7 26.7-43.6 58.9-54.7 94.6-1.7 5.4.6 11.2 5.5 14L67.3 221c-4.3 23.2-4.3 47 0 70.2l-42.6 24.6c-4.9 2.8-7.1 8.6-5.5 14 11.1 35.6 30 67.8 54.7 94.6 3.8 4.1 10 5.1 14.8 2.3l42.6-24.6c17.9 15.4 38.5 27.3 60.8 35.1v49.2c0 5.6 3.9 10.5 9.4 11.7 36.7 8.2 74.3 7.8 109.2 0 5.5-1.2 9.4-6.1 9.4-11.7v-49.2c22.2-7.9 42.8-19.8 60.8-35.1l42.6 24.6c4.9 2.8 11 1.9 14.8-2.3 24.7-26.7 43.6-58.9 54.7-94.6 1.5-5.5-.7-11.3-5.6-14.1zM256 336c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"cogs\": [640, 512, [], \"f085\", \"M512.1 191l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0L552 6.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zm-10.5-58.8c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.7-82.4 14.3-52.8 52.8zM386.3 286.1l33.7 16.8c10.1 5.8 14.5 18.1 10.5 29.1-8.9 24.2-26.4 46.4-42.6 65.8-7.4 8.9-20.2 11.1-30.3 5.3l-29.1-16.8c-16 13.7-34.6 24.6-54.9 31.7v33.6c0 11.6-8.3 21.6-19.7 23.6-24.6 4.2-50.4 4.4-75.9 0-11.5-2-20-11.9-20-23.6V418c-20.3-7.2-38.9-18-54.9-31.7L74 403c-10 5.8-22.9 3.6-30.3-5.3-16.2-19.4-33.3-41.6-42.2-65.7-4-10.9.4-23.2 10.5-29.1l33.3-16.8c-3.9-20.9-3.9-42.4 0-63.4L12 205.8c-10.1-5.8-14.6-18.1-10.5-29 8.9-24.2 26-46.4 42.2-65.8 7.4-8.9 20.2-11.1 30.3-5.3l29.1 16.8c16-13.7 34.6-24.6 54.9-31.7V57.1c0-11.5 8.2-21.5 19.6-23.5 24.6-4.2 50.5-4.4 76-.1 11.5 2 20 11.9 20 23.6v33.6c20.3 7.2 38.9 18 54.9 31.7l29.1-16.8c10-5.8 22.9-3.6 30.3 5.3 16.2 19.4 33.2 41.6 42.1 65.8 4 10.9.1 23.2-10 29.1l-33.7 16.8c3.9 21 3.9 42.5 0 63.5zm-117.6 21.1c59.2-77-28.7-164.9-105.7-105.7-59.2 77 28.7 164.9 105.7 105.7zm243.4 182.7l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0l8.2-14.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zM501.6 431c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.6-82.4 14.3-52.8 52.8z\"],\n    \"coins\": [512, 512, [], \"f51e\", \"M0 405.3V448c0 35.3 86 64 192 64s192-28.7 192-64v-42.7C342.7 434.4 267.2 448 192 448S41.3 434.4 0 405.3zM320 128c106 0 192-28.7 192-64S426 0 320 0 128 28.7 128 64s86 64 192 64zM0 300.4V352c0 35.3 86 64 192 64s192-28.7 192-64v-51.6c-41.3 34-116.9 51.6-192 51.6S41.3 334.4 0 300.4zm416 11c57.3-11.1 96-31.7 96-55.4v-42.7c-23.2 16.4-57.3 27.6-96 34.5v63.6zM192 160C86 160 0 195.8 0 240s86 80 192 80 192-35.8 192-80-86-80-192-80zm219.3 56.3c60-10.8 100.7-32 100.7-56.3v-42.7c-35.5 25.1-96.5 38.6-160.7 41.8 29.5 14.3 51.2 33.5 60 57.2z\"],\n    \"columns\": [512, 512, [], \"f0db\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64V160h160v256zm224 0H288V160h160v256z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 9.8 11.2 15.5 19.1 9.7L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64z\"],\n    \"comment-dollar\": [512, 512, [], \"f651\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95.01 57.02 130.74C44.46 421.05 2.7 465.97 2.2 466.5A7.995 7.995 0 0 0 8 480c66.26 0 115.99-31.75 140.6-51.38C181.29 440.93 217.59 448 256 448c141.38 0 256-93.12 256-208S397.38 32 256 32zm24 302.44V352c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-17.73c-11.42-1.35-22.28-5.19-31.78-11.46-6.22-4.11-6.82-13.11-1.55-18.38l17.52-17.52c3.74-3.74 9.31-4.24 14.11-2.03 3.18 1.46 6.66 2.22 10.26 2.22h32.78c4.66 0 8.44-3.78 8.44-8.42 0-3.75-2.52-7.08-6.12-8.11l-50.07-14.3c-22.25-6.35-40.01-24.71-42.91-47.67-4.05-32.07 19.03-59.43 49.32-63.05V128c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v17.73c11.42 1.35 22.28 5.19 31.78 11.46 6.22 4.11 6.82 13.11 1.55 18.38l-17.52 17.52c-3.74 3.74-9.31 4.24-14.11 2.03a24.516 24.516 0 0 0-10.26-2.22h-32.78c-4.66 0-8.44 3.78-8.44 8.42 0 3.75 2.52 7.08 6.12 8.11l50.07 14.3c22.25 6.36 40.01 24.71 42.91 47.67 4.05 32.06-19.03 59.42-49.32 63.04z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128 272c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"comment-medical\": [512, 512, [], \"f7f5\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95 57 130.74C44.46 421.05 2.7 466 2.2 466.5A8 8 0 0 0 8 480c66.26 0 116-31.75 140.6-51.38A304.66 304.66 0 0 0 256 448c141.39 0 256-93.12 256-208S397.39 32 256 32zm96 232a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8z\"],\n    \"comment-slash\": [640, 512, [], \"f4b3\", \"M64 240c0 49.6 21.4 95 57 130.7-12.6 50.3-54.3 95.2-54.8 95.8-2.2 2.3-2.8 5.7-1.5 8.7 1.3 2.9 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 27.4 0 53.7-3.6 78.4-10L72.9 186.4c-5.6 17.1-8.9 35-8.9 53.6zm569.8 218.1l-114.4-88.4C554.6 334.1 576 289.2 576 240c0-114.9-114.6-208-256-208-65.1 0-124.2 20.1-169.4 52.7L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M416 192c0-88.4-93.1-160-208-160S0 103.6 0 192c0 34.3 14.1 65.9 38 92-13.4 30.2-35.5 54.2-35.8 54.5-2.2 2.3-2.8 5.7-1.5 8.7S4.8 352 8 352c36.6 0 66.9-12.3 88.7-25 32.2 15.7 70.3 25 111.3 25 114.9 0 208-71.6 208-160zm122 220c23.9-26 38-57.7 38-92 0-66.9-53.5-124.2-129.3-148.1.9 6.6 1.3 13.3 1.3 20.1 0 105.9-107.7 192-240 192-10.8 0-21.3-.8-31.7-1.9C207.8 439.6 281.8 480 368 480c41 0 79.1-9.2 111.3-25 21.8 12.7 52.1 25 88.7 25 3.2 0 6.1-1.9 7.3-4.8 1.3-2.9.7-6.3-1.5-8.7-.3-.3-22.4-24.2-35.8-54.5z\"],\n    \"comments-dollar\": [576, 512, [], \"f653\", \"M416 192c0-88.37-93.12-160-208-160S0 103.63 0 192c0 34.27 14.13 65.95 37.97 91.98C24.61 314.22 2.52 338.16 2.2 338.5A7.995 7.995 0 0 0 8 352c36.58 0 66.93-12.25 88.73-24.98C128.93 342.76 167.02 352 208 352c114.88 0 208-71.63 208-160zm-224 96v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V96c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07V288c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm346.01 123.99C561.87 385.96 576 354.27 576 320c0-66.94-53.49-124.2-129.33-148.07.86 6.6 1.33 13.29 1.33 20.07 0 105.87-107.66 192-240 192-10.78 0-21.32-.77-31.73-1.88C207.8 439.63 281.77 480 368 480c40.98 0 79.07-9.24 111.27-24.98C501.07 467.75 531.42 480 568 480c3.2 0 6.09-1.91 7.34-4.84 1.27-2.94.66-6.34-1.55-8.67-.31-.33-22.42-24.24-35.78-54.5z\"],\n    \"compact-disc\": [496, 512, [], \"f51f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 256H56c0-105.9 86.1-192 192-192v32c-88.2 0-160 71.8-160 160zm160 96c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96zm0-128c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M225.38 233.37c-12.5 12.5-12.5 32.76 0 45.25 12.49 12.5 32.76 12.5 45.25 0 12.5-12.5 12.5-32.76 0-45.25-12.5-12.49-32.76-12.49-45.25 0zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm126.14 148.05L308.17 300.4a31.938 31.938 0 0 1-15.77 15.77l-144.34 65.97c-16.65 7.61-33.81-9.55-26.2-26.2l65.98-144.35a31.938 31.938 0 0 1 15.77-15.77l144.34-65.97c16.65-7.6 33.8 9.55 26.19 26.2z\"],\n    \"compress\": [448, 512, [], \"f066\", \"M436 192H312c-13.3 0-24-10.7-24-24V44c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v84h84c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm-276-24V44c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v84H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24zm0 300V344c0-13.3-10.7-24-24-24H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-84h84c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H312c-13.3 0-24 10.7-24 24v124c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"compress-arrows-alt\": [512, 512, [], \"f78c\", \"M200 288H88c-21.4 0-32.1 25.8-17 41l32.9 31-99.2 99.3c-6.2 6.2-6.2 16.4 0 22.6l25.4 25.4c6.2 6.2 16.4 6.2 22.6 0L152 408l31.1 33c15.1 15.1 40.9 4.4 40.9-17V312c0-13.3-10.7-24-24-24zm112-64h112c21.4 0 32.1-25.9 17-41l-33-31 99.3-99.3c6.2-6.2 6.2-16.4 0-22.6L481.9 4.7c-6.2-6.2-16.4-6.2-22.6 0L360 104l-31.1-33C313.8 55.9 288 66.6 288 88v112c0 13.3 10.7 24 24 24zm96 136l33-31.1c15.1-15.1 4.4-40.9-17-40.9H312c-13.3 0-24 10.7-24 24v112c0 21.4 25.9 32.1 41 17l31-32.9 99.3 99.3c6.2 6.2 16.4 6.2 22.6 0l25.4-25.4c6.2-6.2 6.2-16.4 0-22.6L408 360zM183 71.1L152 104 52.7 4.7c-6.2-6.2-16.4-6.2-22.6 0L4.7 30.1c-6.2 6.2-6.2 16.4 0 22.6L104 152l-33 31.1C55.9 198.2 66.6 224 88 224h112c13.3 0 24-10.7 24-24V88c0-21.3-25.9-32-41-16.9z\"],\n    \"concierge-bell\": [512, 512, [], \"f562\", \"M288 130.54V112h16c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h16v18.54C115.49 146.11 32 239.18 32 352h448c0-112.82-83.49-205.89-192-221.46zM496 384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"cookie\": [512, 512, [], \"f563\", \"M510.37 254.79l-12.08-76.26a132.493 132.493 0 0 0-37.16-72.95l-54.76-54.75c-19.73-19.72-45.18-32.7-72.71-37.05l-76.7-12.15c-27.51-4.36-55.69.11-80.52 12.76L107.32 49.6a132.25 132.25 0 0 0-57.79 57.8l-35.1 68.88a132.602 132.602 0 0 0-12.82 80.94l12.08 76.27a132.493 132.493 0 0 0 37.16 72.95l54.76 54.75a132.087 132.087 0 0 0 72.71 37.05l76.7 12.14c27.51 4.36 55.69-.11 80.52-12.75l69.12-35.21a132.302 132.302 0 0 0 57.79-57.8l35.1-68.87c12.71-24.96 17.2-53.3 12.82-80.96zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"cookie-bite\": [512, 512, [], \"f564\", \"M510.52 255.82c-69.97-.85-126.47-57.69-126.47-127.86-70.17 0-127-56.49-127.86-126.45-27.26-4.14-55.13.3-79.72 12.82l-69.13 35.22a132.221 132.221 0 0 0-57.79 57.81l-35.1 68.88a132.645 132.645 0 0 0-12.82 80.95l12.08 76.27a132.521 132.521 0 0 0 37.16 72.96l54.77 54.76a132.036 132.036 0 0 0 72.71 37.06l76.71 12.15c27.51 4.36 55.7-.11 80.53-12.76l69.13-35.21a132.273 132.273 0 0 0 57.79-57.81l35.1-68.88c12.56-24.64 17.01-52.58 12.91-79.91zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M320 448v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V120c0-13.255 10.745-24 24-24h72v296c0 30.879 25.121 56 56 56h168zm0-344V0H152c-13.255 0-24 10.745-24 24v368c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24V128H344c-13.2 0-24-10.8-24-24zm120.971-31.029L375.029 7.029A24 24 0 0 0 358.059 0H352v96h96v-6.059a24 24 0 0 0-7.029-16.97z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm117.134 346.753c-1.592 1.867-39.776 45.731-109.851 45.731-84.692 0-144.484-63.26-144.484-145.567 0-81.303 62.004-143.401 143.762-143.401 66.957 0 101.965 37.315 103.422 38.904a12 12 0 0 1 1.238 14.623l-22.38 34.655c-4.049 6.267-12.774 7.351-18.234 2.295-.233-.214-26.529-23.88-61.88-23.88-46.116 0-73.916 33.575-73.916 76.082 0 39.602 25.514 79.692 74.277 79.692 38.697 0 65.28-28.338 65.544-28.625 5.132-5.565 14.059-5.033 18.508 1.053l24.547 33.572a12.001 12.001 0 0 1-.553 14.866z\"],\n    \"couch\": [640, 512, [], \"f4b8\", \"M160 224v64h320v-64c0-35.3 28.7-64 64-64h32c0-53-43-96-96-96H160c-53 0-96 43-96 96h32c35.3 0 64 28.7 64 64zm416-32h-32c-17.7 0-32 14.3-32 32v96H128v-96c0-17.7-14.3-32-32-32H64c-35.3 0-64 28.7-64 64 0 23.6 13 44 32 55.1V432c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-16h384v16c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V311.1c19-11.1 32-31.5 32-55.1 0-35.3-28.7-64-64-64z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V256H0v176zm192-68c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-40zm-128 0c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM576 80v48H0V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48z\"],\n    \"crop\": [512, 512, [], \"f125\", \"M488 352h-40V109.25l59.31-59.31c6.25-6.25 6.25-16.38 0-22.63L484.69 4.69c-6.25-6.25-16.38-6.25-22.63 0L402.75 64H192v96h114.75L160 306.75V24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v264c0 13.25 10.75 24 24 24h232v-96H205.25L352 205.25V488c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"crop-alt\": [512, 512, [], \"f565\", \"M488 352h-40V96c0-17.67-14.33-32-32-32H192v96h160v328c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24zM160 24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v256c0 17.67 14.33 32 32 32h224v-96H160V24z\"],\n    \"cross\": [384, 512, [], \"f654\", \"M352 128h-96V32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h96v224c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V256h96c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"crosshairs\": [512, 512, [], \"f05b\", \"M500 224h-30.364C455.724 130.325 381.675 56.276 288 42.364V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v30.364C130.325 56.276 56.276 130.325 42.364 224H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h30.364C56.276 381.675 130.325 455.724 224 469.636V500c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-30.364C381.675 455.724 455.724 381.675 469.636 288H500c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zM288 404.634V364c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40.634C165.826 392.232 119.783 346.243 107.366 288H148c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40.634C119.768 165.826 165.757 119.783 224 107.366V148c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40.634C346.174 119.768 392.217 165.757 404.634 224H364c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40.634C392.232 346.174 346.243 392.217 288 404.634zM288 256c0 17.673-14.327 32-32 32s-32-14.327-32-32c0-17.673 14.327-32 32-32s32 14.327 32 32z\"],\n    \"crow\": [640, 512, [], \"f520\", \"M544 32h-16.36C513.04 12.68 490.09 0 464 0c-44.18 0-80 35.82-80 80v20.98L12.09 393.57A30.216 30.216 0 0 0 0 417.74c0 22.46 23.64 37.07 43.73 27.03L165.27 384h96.49l44.41 120.1c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38L312.94 384H352c1.91 0 3.76-.23 5.66-.29l44.51 120.38c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38l-41.24-111.53C485.74 352.8 544 279.26 544 192v-80l96-16c0-35.35-42.98-64-96-64zm-80 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"crown\": [640, 512, [], \"f521\", \"M528 448H112c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h416c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm64-320c-26.5 0-48 21.5-48 48 0 7.1 1.6 13.7 4.4 19.8L476 239.2c-15.4 9.2-35.3 4-44.2-11.6L350.3 85C361 76.2 368 63 368 48c0-26.5-21.5-48-48-48s-48 21.5-48 48c0 15 7 28.2 17.7 37l-81.5 142.6c-8.9 15.6-28.9 20.8-44.2 11.6l-72.3-43.4c2.7-6 4.4-12.7 4.4-19.8 0-26.5-21.5-48-48-48S0 149.5 0 176s21.5 48 48 48c2.6 0 5.2-.4 7.7-.8L128 416h384l72.3-192.8c2.5.4 5.1.8 7.7.8 26.5 0 48-21.5 48-48s-21.5-48-48-48z\"],\n    \"crutch\": [512, 512, [], \"f7f7\", \"M507.31 185.71l-181-181a16 16 0 0 0-22.62 0L281 27.31a16 16 0 0 0 0 22.63l181 181a16 16 0 0 0 22.63 0l22.62-22.63a16 16 0 0 0 .06-22.6zm-179.54 66.41l-67.89-67.89 55.1-55.1-45.25-45.25-109.67 109.67a96.08 96.08 0 0 0-25.67 46.29L106.65 360.1l-102 102a16 16 0 0 0 0 22.63l22.62 22.62a16 16 0 0 0 22.63 0l102-102 120.25-27.75a95.88 95.88 0 0 0 46.29-25.65l109.68-109.68L382.87 197zm-54.57 54.57a32 32 0 0 1-15.45 8.54l-79.3 18.32 18.3-79.3a32.22 32.22 0 0 1 8.56-15.45l9.31-9.31 67.89 67.89z\"],\n    \"cube\": [512, 512, [], \"f1b2\", \"M239.1 6.3l-208 78c-18.7 7-31.1 25-31.1 45v225.1c0 18.2 10.3 34.8 26.5 42.9l208 104c13.5 6.8 29.4 6.8 42.9 0l208-104c16.3-8.1 26.5-24.8 26.5-42.9V129.3c0-20-12.4-37.9-31.1-44.9l-208-78C262 2.2 250 2.2 239.1 6.3zM256 68.4l192 72v1.1l-192 78-192-78v-1.1l192-72zm32 356V275.5l160-65v133.9l-160 80z\"],\n    \"cubes\": [512, 512, [], \"f1b3\", \"M488.6 250.2L392 214V105.5c0-15-9.3-28.4-23.4-33.7l-100-37.5c-8.1-3.1-17.1-3.1-25.3 0l-100 37.5c-14.1 5.3-23.4 18.7-23.4 33.7V214l-96.6 36.2C9.3 255.5 0 268.9 0 283.9V394c0 13.6 7.7 26.1 19.9 32.2l100 50c10.1 5.1 22.1 5.1 32.2 0l103.9-52 103.9 52c10.1 5.1 22.1 5.1 32.2 0l100-50c12.2-6.1 19.9-18.6 19.9-32.2V283.9c0-15-9.3-28.4-23.4-33.7zM358 214.8l-85 31.9v-68.2l85-37v73.3zM154 104.1l102-38.2 102 38.2v.6l-102 41.4-102-41.4v-.6zm84 291.1l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6zm240 112l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6z\"],\n    \"cut\": [448, 512, [], \"f0c4\", \"M278.06 256L444.48 89.57c4.69-4.69 4.69-12.29 0-16.97-32.8-32.8-85.99-32.8-118.79 0L210.18 188.12l-24.86-24.86c4.31-10.92 6.68-22.81 6.68-35.26 0-53.02-42.98-96-96-96S0 74.98 0 128s42.98 96 96 96c4.54 0 8.99-.32 13.36-.93L142.29 256l-32.93 32.93c-4.37-.61-8.83-.93-13.36-.93-53.02 0-96 42.98-96 96s42.98 96 96 96 96-42.98 96-96c0-12.45-2.37-24.34-6.68-35.26l24.86-24.86L325.69 439.4c32.8 32.8 85.99 32.8 118.79 0 4.69-4.68 4.69-12.28 0-16.97L278.06 256zM96 160c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32zm0 256c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"database\": [448, 512, [], \"f1c0\", \"M448 73.143v45.714C448 159.143 347.667 192 224 192S0 159.143 0 118.857V73.143C0 32.857 100.333 0 224 0s224 32.857 224 73.143zM448 176v102.857C448 319.143 347.667 352 224 352S0 319.143 0 278.857V176c48.125 33.143 136.208 48.572 224 48.572S399.874 209.143 448 176zm0 160v102.857C448 479.143 347.667 512 224 512S0 479.143 0 438.857V336c48.125 33.143 136.208 48.572 224 48.572S399.874 369.143 448 336z\"],\n    \"deaf\": [512, 512, [], \"f2a4\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm268.485-52.201L480.2 3.515c-4.687-4.686-12.284-4.686-16.971 0L376.2 90.544c-4.686 4.686-4.686 12.284 0 16.971l28.285 28.285c4.686 4.686 12.284 4.686 16.97 0l87.03-87.029c4.687-4.688 4.687-12.286 0-16.972zM168.97 314.745c-4.686-4.686-12.284-4.686-16.97 0L3.515 463.23c-4.686 4.686-4.686 12.284 0 16.971L31.8 508.485c4.687 4.686 12.284 4.686 16.971 0L197.256 360c4.686-4.686 4.686-12.284 0-16.971l-28.286-28.284z\"],\n    \"democrat\": [640, 512, [], \"f747\", \"M637.3 256.9l-19.6-29.4c-28.2-42.3-75.3-67.5-126.1-67.5H256l-81.2-81.2c20.1-20.1 22.6-51.1 7.5-73.9-3.4-5.2-10.8-5.9-15.2-1.5l-41.8 41.8L82.4 2.4c-3.6-3.6-9.6-3-12.4 1.2-12.3 18.6-10.3 44 6.1 60.4 3.3 3.3 7.3 5.3 11.3 7.5-2.2 1.7-4.7 3.1-6.4 5.4L6.4 176.2c-7.3 9.7-8.4 22.7-3 33.5l14.3 28.6c5.4 10.8 16.5 17.7 28.6 17.7h31c8.5 0 16.6-3.4 22.6-9.4L138 212l54 108h352v-77.8c16.2 12.2 18.3 17.6 40.1 50.3 4.9 7.4 14.8 9.3 22.2 4.4l26.6-17.7c7.3-5 9.3-14.9 4.4-22.3zm-341.1-13.6l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L256 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L368 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L480 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zM192 496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80h160v80c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V352H192v144z\"],\n    \"desktop\": [576, 512, [], \"f108\", \"M528 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h192l-16 48h-72c-13.3 0-24 10.7-24 24s10.7 24 24 24h272c13.3 0 24-10.7 24-24s-10.7-24-24-24h-72l-16-48h192c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h448v288z\"],\n    \"dharmachakra\": [512, 512, [], \"f655\", \"M495 225.06l-17.22 1.08c-5.27-39.49-20.79-75.64-43.86-105.84l12.95-11.43c6.92-6.11 7.25-16.79.73-23.31L426.44 64.4c-6.53-6.53-17.21-6.19-23.31.73L391.7 78.07c-30.2-23.06-66.35-38.58-105.83-43.86L286.94 17c.58-9.21-6.74-17-15.97-17h-29.94c-9.23 0-16.54 7.79-15.97 17l1.08 17.22c-39.49 5.27-75.64 20.79-105.83 43.86l-11.43-12.95c-6.11-6.92-16.79-7.25-23.31-.73L64.4 85.56c-6.53 6.53-6.19 17.21.73 23.31l12.95 11.43c-23.06 30.2-38.58 66.35-43.86 105.84L17 225.06c-9.21-.58-17 6.74-17 15.97v29.94c0 9.23 7.79 16.54 17 15.97l17.22-1.08c5.27 39.49 20.79 75.64 43.86 105.83l-12.95 11.43c-6.92 6.11-7.25 16.79-.73 23.31l21.17 21.17c6.53 6.53 17.21 6.19 23.31-.73l11.43-12.95c30.2 23.06 66.35 38.58 105.84 43.86L225.06 495c-.58 9.21 6.74 17 15.97 17h29.94c9.23 0 16.54-7.79 15.97-17l-1.08-17.22c39.49-5.27 75.64-20.79 105.84-43.86l11.43 12.95c6.11 6.92 16.79 7.25 23.31.73l21.17-21.17c6.53-6.53 6.19-17.21-.73-23.31l-12.95-11.43c23.06-30.2 38.58-66.35 43.86-105.83l17.22 1.08c9.21.58 17-6.74 17-15.97v-29.94c-.01-9.23-7.8-16.54-17.01-15.97zM281.84 98.61c24.81 4.07 47.63 13.66 67.23 27.78l-42.62 48.29c-8.73-5.44-18.32-9.54-28.62-11.95l4.01-64.12zm-51.68 0l4.01 64.12c-10.29 2.41-19.89 6.52-28.62 11.95l-42.62-48.29c19.6-14.12 42.42-23.71 67.23-27.78zm-103.77 64.33l48.3 42.61c-5.44 8.73-9.54 18.33-11.96 28.62l-64.12-4.01c4.07-24.81 13.66-47.62 27.78-67.22zm-27.78 118.9l64.12-4.01c2.41 10.29 6.52 19.89 11.95 28.62l-48.29 42.62c-14.12-19.6-23.71-42.42-27.78-67.23zm131.55 131.55c-24.81-4.07-47.63-13.66-67.23-27.78l42.61-48.3c8.73 5.44 18.33 9.54 28.62 11.96l-4 64.12zM256 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm25.84 125.39l-4.01-64.12c10.29-2.41 19.89-6.52 28.62-11.96l42.61 48.3c-19.6 14.12-42.41 23.71-67.22 27.78zm103.77-64.33l-48.29-42.62c5.44-8.73 9.54-18.32 11.95-28.62l64.12 4.01c-4.07 24.82-13.66 47.64-27.78 67.23zm-36.34-114.89c-2.41-10.29-6.52-19.89-11.96-28.62l48.3-42.61c14.12 19.6 23.71 42.42 27.78 67.23l-64.12 4z\"],\n    \"diagnoses\": [640, 512, [], \"f470\", \"M496 256c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm-176-80c48.5 0 88-39.5 88-88S368.5 0 320 0s-88 39.5-88 88 39.5 88 88 88zM59.8 364c10.2 15.3 29.3 17.8 42.9 9.8 16.2-9.6 56.2-31.7 105.3-48.6V416h224v-90.7c49.1 16.8 89.1 39 105.3 48.6 13.6 8 32.7 5.3 42.9-9.8l17.8-26.7c8.8-13.2 7.6-34.6-10-45.1-11.9-7.1-29.7-17-51.1-27.4-28.1 46.1-99.4 17.8-87.7-35.1C409.3 217.2 365.1 208 320 208c-57 0-112.9 14.5-160 32.2-.2 40.2-47.6 63.3-79.2 36-11.2 6-21.3 11.6-28.7 16-17.6 10.5-18.8 31.8-10 45.1L59.8 364zM368 344c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-160 8c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm512 192H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dice\": [640, 512, [], \"f522\", \"M592 192H473.26c12.69 29.59 7.12 65.2-17 89.32L320 417.58V464c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48V240c0-26.51-21.49-48-48-48zM480 376c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm-46.37-186.7L258.7 14.37c-19.16-19.16-50.23-19.16-69.39 0L14.37 189.3c-19.16 19.16-19.16 50.23 0 69.39L189.3 433.63c19.16 19.16 50.23 19.16 69.39 0L433.63 258.7c19.16-19.17 19.16-50.24 0-69.4zM96 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"dice-d20\": [480, 512, [], \"f6cf\", \"M106.75 215.06L1.2 370.95c-3.08 5 .1 11.5 5.93 12.14l208.26 22.07-108.64-190.1zM7.41 315.43L82.7 193.08 6.06 147.1c-2.67-1.6-6.06.32-6.06 3.43v162.81c0 4.03 5.29 5.53 7.41 2.09zM18.25 423.6l194.4 87.66c5.3 2.45 11.35-1.43 11.35-7.26v-65.67l-203.55-22.3c-4.45-.5-6.23 5.59-2.2 7.57zm81.22-257.78L179.4 22.88c4.34-7.06-3.59-15.25-10.78-11.14L17.81 110.35c-2.47 1.62-2.39 5.26.13 6.78l81.53 48.69zM240 176h109.21L253.63 7.62C250.5 2.54 245.25 0 240 0s-10.5 2.54-13.63 7.62L130.79 176H240zm233.94-28.9l-76.64 45.99 75.29 122.35c2.11 3.44 7.41 1.94 7.41-2.1V150.53c0-3.11-3.39-5.03-6.06-3.43zm-93.41 18.72l81.53-48.7c2.53-1.52 2.6-5.16.13-6.78l-150.81-98.6c-7.19-4.11-15.12 4.08-10.78 11.14l79.93 142.94zm79.02 250.21L256 438.32v65.67c0 5.84 6.05 9.71 11.35 7.26l194.4-87.66c4.03-1.97 2.25-8.06-2.2-7.56zm-86.3-200.97l-108.63 190.1 208.26-22.07c5.83-.65 9.01-7.14 5.93-12.14L373.25 215.06zM240 208H139.57L240 383.75 340.43 208H240z\"],\n    \"dice-d6\": [448, 512, [], \"f6d1\", \"M422.19 109.95L256.21 9.07c-19.91-12.1-44.52-12.1-64.43 0L25.81 109.95c-5.32 3.23-5.29 11.27.06 14.46L224 242.55l198.14-118.14c5.35-3.19 5.38-11.22.05-14.46zm13.84 44.63L240 271.46v223.82c0 12.88 13.39 20.91 24.05 14.43l152.16-92.48c19.68-11.96 31.79-33.94 31.79-57.7v-197.7c0-6.41-6.64-10.43-11.97-7.25zM0 161.83v197.7c0 23.77 12.11 45.74 31.79 57.7l152.16 92.47c10.67 6.48 24.05-1.54 24.05-14.43V271.46L11.97 154.58C6.64 151.4 0 155.42 0 161.83z\"],\n    \"dice-five\": [448, 512, [], \"f523\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-four\": [448, 512, [], \"f524\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-one\": [448, 512, [], \"f525\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM224 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-six\": [448, 512, [], \"f526\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-three\": [448, 512, [], \"f527\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-two\": [448, 512, [], \"f528\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"digital-tachograph\": [640, 512, [], \"f566\", \"M608 96H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128c0-17.67-14.33-32-32-32zM304 352c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8zM72 288v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H80c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm40-64c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-48c0-8.84 7.16-16 16-16h208c8.84 0 16 7.16 16 16v48zm272 128c0 4.42-3.58 8-8 8H344c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8z\"],\n    \"directions\": [512, 512, [], \"f5eb\", \"M502.61 233.32L278.68 9.39c-12.52-12.52-32.83-12.52-45.36 0L9.39 233.32c-12.52 12.53-12.52 32.83 0 45.36l223.93 223.93c12.52 12.53 32.83 12.53 45.36 0l223.93-223.93c12.52-12.53 12.52-32.83 0-45.36zm-100.98 12.56l-84.21 77.73c-5.12 4.73-13.43 1.1-13.43-5.88V264h-96v64c0 4.42-3.58 8-8 8h-32c-4.42 0-8-3.58-8-8v-80c0-17.67 14.33-32 32-32h112v-53.73c0-6.97 8.3-10.61 13.43-5.88l84.21 77.73c3.43 3.17 3.43 8.59 0 11.76z\"],\n    \"divide\": [448, 512, [], \"f529\", \"M224 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm0-192c35.35 0 64-28.65 64-64s-28.65-64-64-64-64 28.65-64 64 28.65 64 64 64zm192 48H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-96 206.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L174.6 192l28.7 28.7c15.2 15.2-7.9 37.4-22.6 22.6L152 214.6zM248 416c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm147.3-195.3c15.2 15.2-7.9 37.4-22.6 22.6L344 214.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L366.6 192l28.7 28.7z\"],\n    \"dna\": [448, 512, [], \"f471\", \"M.1 494.1c-1.1 9.5 6.3 17.8 15.9 17.8l32.3.1c8.1 0 14.9-5.9 16-13.9.7-4.9 1.8-11.1 3.4-18.1H380c1.6 6.9 2.9 13.2 3.5 18.1 1.1 8 7.9 14 16 13.9l32.3-.1c9.6 0 17.1-8.3 15.9-17.8-4.6-37.9-25.6-129-118.9-207.7-17.6 12.4-37.1 24.2-58.5 35.4 6.2 4.6 11.4 9.4 17 14.2H159.7c21.3-18.1 47-35.6 78.7-51.4C410.5 199.1 442.1 65.8 447.9 17.9 449 8.4 441.6.1 432 .1L399.6 0c-8.1 0-14.9 5.9-16 13.9-.7 4.9-1.8 11.1-3.4 18.1H67.8c-1.6-7-2.7-13.1-3.4-18.1-1.1-8-7.9-14-16-13.9L16.1.1C6.5.1-1 8.4.1 17.9 5.3 60.8 31.4 171.8 160 256 31.5 340.2 5.3 451.2.1 494.1zM224 219.6c-25.1-13.7-46.4-28.4-64.3-43.6h128.5c-17.8 15.2-39.1 30-64.2 43.6zM355.1 96c-5.8 10.4-12.8 21.1-21 32H114c-8.3-10.9-15.3-21.6-21-32h262.1zM92.9 416c5.8-10.4 12.8-21.1 21-32h219.4c8.3 10.9 15.4 21.6 21.2 32H92.9z\"],\n    \"dog\": [512, 512, [], \"f6d3\", \"M496 96h-64l-7.16-14.31A32 32 0 0 0 396.22 64H342.6l-27.28-27.28C305.23 26.64 288 33.78 288 48.03v149.84l128 45.71V208h32c35.35 0 64-28.65 64-64v-32c0-8.84-7.16-16-16-16zm-112 48c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM96 224c-17.64 0-32-14.36-32-32 0-17.67-14.33-32-32-32S0 174.33 0 192c0 41.66 26.83 76.85 64 90.1V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V384h160v112c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V277.55L266.05 224H96z\"],\n    \"dollar-sign\": [288, 512, [], \"f155\", \"M209.2 233.4l-108-31.6C88.7 198.2 80 186.5 80 173.5c0-16.3 13.2-29.5 29.5-29.5h66.3c12.2 0 24.2 3.7 34.2 10.5 6.1 4.1 14.3 3.1 19.5-2l34.8-34c7.1-6.9 6.1-18.4-1.8-24.5C238 74.8 207.4 64.1 176 64V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48h-2.5C45.8 64-5.4 118.7.5 183.6c4.2 46.1 39.4 83.6 83.8 96.6l102.5 30c12.5 3.7 21.2 15.3 21.2 28.3 0 16.3-13.2 29.5-29.5 29.5h-66.3C100 368 88 364.3 78 357.5c-6.1-4.1-14.3-3.1-19.5 2l-34.8 34c-7.1 6.9-6.1 18.4 1.8 24.5 24.5 19.2 55.1 29.9 86.5 30v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48.2c46.6-.9 90.3-28.6 105.7-72.7 21.5-61.6-14.6-124.8-72.5-141.7z\"],\n    \"dolly\": [576, 512, [], \"f472\", \"M294.2 277.7c18 5 34.7 13.4 49.5 24.7l161.5-53.8c8.4-2.8 12.9-11.9 10.1-20.2L454.9 47.2c-2.8-8.4-11.9-12.9-20.2-10.1l-61.1 20.4 33.1 99.4L346 177l-33.1-99.4-61.6 20.5c-8.4 2.8-12.9 11.9-10.1 20.2l53 159.4zm281 48.7L565 296c-2.8-8.4-11.9-12.9-20.2-10.1l-213.5 71.2c-17.2-22-43.6-36.4-73.5-37L158.4 21.9C154 8.8 141.8 0 128 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h88.9l92.2 276.7c-26.1 20.4-41.7 53.6-36 90.5 6.1 39.4 37.9 72.3 77.3 79.2 60.2 10.7 112.3-34.8 113.4-92.6l213.3-71.2c8.3-2.8 12.9-11.8 10.1-20.2zM256 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"dolly-flatbed\": [640, 512, [], \"f474\", \"M208 320h384c8.8 0 16-7.2 16-16V48c0-8.8-7.2-16-16-16H448v128l-48-32-48 32V32H208c-8.8 0-16 7.2-16 16v256c0 8.8 7.2 16 16 16zm416 64H128V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h82.9c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H451c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H624c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"donate\": [512, 512, [], \"f4b9\", \"M256 416c114.9 0 208-93.1 208-208S370.9 0 256 0 48 93.1 48 208s93.1 208 208 208zM233.8 97.4V80.6c0-9.2 7.4-16.6 16.6-16.6h11.1c9.2 0 16.6 7.4 16.6 16.6v17c15.5.8 30.5 6.1 43 15.4 5.6 4.1 6.2 12.3 1.2 17.1L306 145.6c-3.8 3.7-9.5 3.8-14 1-5.4-3.4-11.4-5.1-17.8-5.1h-38.9c-9 0-16.3 8.2-16.3 18.3 0 8.2 5 15.5 12.1 17.6l62.3 18.7c25.7 7.7 43.7 32.4 43.7 60.1 0 34-26.4 61.5-59.1 62.4v16.8c0 9.2-7.4 16.6-16.6 16.6h-11.1c-9.2 0-16.6-7.4-16.6-16.6v-17c-15.5-.8-30.5-6.1-43-15.4-5.6-4.1-6.2-12.3-1.2-17.1l16.3-15.5c3.8-3.7 9.5-3.8 14-1 5.4 3.4 11.4 5.1 17.8 5.1h38.9c9 0 16.3-8.2 16.3-18.3 0-8.2-5-15.5-12.1-17.6l-62.3-18.7c-25.7-7.7-43.7-32.4-43.7-60.1.1-34 26.4-61.5 59.1-62.4zM480 352h-32.5c-19.6 26-44.6 47.7-73 64h63.8c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8h63.8c-28.4-16.3-53.3-38-73-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32z\"],\n    \"door-closed\": [640, 512, [], \"f52a\", \"M624 448H512V50.8C512 22.78 490.47 0 464 0H175.99c-26.47 0-48 22.78-48 50.8V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM415.99 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32c.01 17.67-14.32 32-32 32z\"],\n    \"door-open\": [640, 512, [], \"f52b\", \"M624 448h-80V113.45C544 86.19 522.47 64 496 64H384v64h96v384h144c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM312.24 1.01l-192 49.74C105.99 54.44 96 67.7 96 82.92V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h336V33.18c0-21.58-19.56-37.41-39.76-32.17zM264 288c-13.25 0-24-14.33-24-32s10.75-32 24-32 24 14.33 24 32-10.75 32-24 32z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm80 248c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80z\"],\n    \"dove\": [512, 512, [], \"f4ba\", \"M288 167.2v-28.1c-28.2-36.3-47.1-79.3-54.1-125.2-2.1-13.5-19-18.8-27.8-8.3-21.1 24.9-37.7 54.1-48.9 86.5 34.2 38.3 80 64.6 130.8 75.1zM400 64c-44.2 0-80 35.9-80 80.1v59.4C215.6 197.3 127 133 87 41.8c-5.5-12.5-23.2-13.2-29-.9C41.4 76 32 115.2 32 156.6c0 70.8 34.1 136.9 85.1 185.9 13.2 12.7 26.1 23.2 38.9 32.8l-143.9 36C1.4 414-3.4 426.4 2.6 435.7 20 462.6 63 508.2 155.8 512c8 .3 16-2.6 22.1-7.9l65.2-56.1H320c88.4 0 160-71.5 160-159.9V128l32-64H400zm0 96.1c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"download\": [512, 512, [], \"f019\", \"M216 0h80c13.3 0 24 10.7 24 24v168h87.7c17.8 0 26.7 21.5 14.1 34.1L269.7 378.3c-7.5 7.5-19.8 7.5-27.3 0L90.1 226.1c-12.6-12.6-3.7-34.1 14.1-34.1H192V24c0-13.3 10.7-24 24-24zm296 376v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h146.7l49 49c20.1 20.1 52.5 20.1 72.6 0l49-49H488c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"drafting-compass\": [512, 512, [], \"f568\", \"M457.01 344.42c-25.05 20.33-52.63 37.18-82.54 49.05l54.38 94.19 53.95 23.04c9.81 4.19 20.89-2.21 22.17-12.8l7.02-58.25-54.98-95.23zm42.49-94.56c4.86-7.67 1.89-17.99-6.05-22.39l-28.07-15.57c-7.48-4.15-16.61-1.46-21.26 5.72C403.01 281.15 332.25 320 256 320c-23.93 0-47.23-4.25-69.41-11.53l67.36-116.68c.7.02 1.34.21 2.04.21s1.35-.19 2.04-.21l51.09 88.5c31.23-8.96 59.56-25.75 82.61-48.92l-51.79-89.71C347.39 128.03 352 112.63 352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96c0 16.63 4.61 32.03 12.05 45.66l-68.3 118.31c-12.55-11.61-23.96-24.59-33.68-39-4.79-7.1-13.97-9.62-21.38-5.33l-27.75 16.07c-7.85 4.54-10.63 14.9-5.64 22.47 15.57 23.64 34.69 44.21 55.98 62.02L0 439.66l7.02 58.25c1.28 10.59 12.36 16.99 22.17 12.8l53.95-23.04 70.8-122.63C186.13 377.28 220.62 384 256 384c99.05 0 190.88-51.01 243.5-134.14zM256 64c17.67 0 32 14.33 32 32s-14.33 32-32 32-32-14.33-32-32 14.33-32 32-32z\"],\n    \"dragon\": [640, 512, [], \"f6d5\", \"M18.32 255.78L192 223.96l-91.28 68.69c-10.08 10.08-2.94 27.31 11.31 27.31h222.7c-9.44-26.4-14.73-54.47-14.73-83.38v-42.27l-119.73-87.6c-23.82-15.88-55.29-14.01-77.06 4.59L5.81 227.64c-12.38 10.33-3.45 30.42 12.51 28.14zm556.87 34.1l-100.66-50.31A47.992 47.992 0 0 1 448 196.65v-36.69h64l28.09 22.63c6 6 14.14 9.37 22.63 9.37h30.97a32 32 0 0 0 28.62-17.69l14.31-28.62a32.005 32.005 0 0 0-3.02-33.51l-74.53-99.38C553.02 4.7 543.54 0 533.47 0H296.02c-7.13 0-10.7 8.57-5.66 13.61L352 63.96 292.42 88.8c-5.9 2.95-5.9 11.36 0 14.31L352 127.96v108.62c0 72.08 36.03 139.39 96 179.38-195.59 6.81-344.56 41.01-434.1 60.91C5.78 478.67 0 485.88 0 494.2 0 504 7.95 512 17.76 512h499.08c63.29.01 119.61-47.56 122.99-110.76 2.52-47.28-22.73-90.4-64.64-111.36zM489.18 66.25l45.65 11.41c-2.75 10.91-12.47 18.89-24.13 18.26-12.96-.71-25.85-12.53-21.52-29.67z\"],\n    \"draw-polygon\": [448, 512, [], \"f5ee\", \"M384 352c-.35 0-.67.1-1.02.1l-39.2-65.32c5.07-9.17 8.22-19.56 8.22-30.78s-3.14-21.61-8.22-30.78l39.2-65.32c.35.01.67.1 1.02.1 35.35 0 64-28.65 64-64s-28.65-64-64-64c-23.63 0-44.04 12.95-55.12 32H119.12C108.04 44.95 87.63 32 64 32 28.65 32 0 60.65 0 96c0 23.63 12.95 44.04 32 55.12v209.75C12.95 371.96 0 392.37 0 416c0 35.35 28.65 64 64 64 23.63 0 44.04-12.95 55.12-32h209.75c11.09 19.05 31.49 32 55.12 32 35.35 0 64-28.65 64-64 .01-35.35-28.64-64-63.99-64zm-288 8.88V151.12A63.825 63.825 0 0 0 119.12 128h208.36l-38.46 64.1c-.35-.01-.67-.1-1.02-.1-35.35 0-64 28.65-64 64s28.65 64 64 64c.35 0 .67-.1 1.02-.1l38.46 64.1H119.12A63.748 63.748 0 0 0 96 360.88zM272 256c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zM400 96c0 8.82-7.18 16-16 16s-16-7.18-16-16 7.18-16 16-16 16 7.18 16 16zM64 80c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zM48 416c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zm336 16c-8.82 0-16-7.18-16-16s7.18-16 16-16 16 7.18 16 16-7.18 16-16 16z\"],\n    \"drum\": [576, 512, [], \"f569\", \"M458.08 120.88l102.39-61.43c15.16-9.09 20.06-28.75 10.97-43.91C562.34.39 542.7-4.53 527.53 4.57l-160.69 96.41A629.32 629.32 0 0 0 288 96C128.94 96 0 153.31 0 224v160.83c0 30.46 24.03 58.4 64 80.37v-96.37c0-17.6 14.4-32 32-32s32 14.4 32 32v122.41c37.4 11.13 81 18.44 128 20.75V400.84c0-17.6 14.4-32 32-32s32 14.4 32 32V512c47-2.31 90.6-9.62 128-20.75V368.84c0-17.6 14.4-32 32-32s32 14.4 32 32v96.37c39.97-21.97 64-49.91 64-80.37V224.01c-.01-42.38-46.54-79.84-117.92-103.13zM288 304c-132.55 0-240-35.82-240-80s107.45-80 240-80c2.34 0 4.62.1 6.94.12l-87.41 52.44c-15.16 9.09-20.06 28.75-10.97 43.91 9.56 15.93 29.51 19.61 43.91 10.97l162.71-97.62C477.55 167.41 528 193.74 528 224.01 528 268.19 420.54 304 288 304z\"],\n    \"drum-steelpan\": [576, 512, [], \"f56a\", \"M288 32C128.94 32 0 89.31 0 160v192c0 70.69 128.94 128 288 128s288-57.31 288-128V160c0-70.69-128.94-128-288-128zm-82.99 158.36c-4.45 16.61-14.54 30.57-28.31 40.48C100.23 217.46 48 190.78 48 160c0-30.16 50.11-56.39 124.04-70.03l25.6 44.34c9.86 17.09 12.48 36.99 7.37 56.05zM288 240c-21.08 0-41.41-1-60.89-2.7 8.06-26.13 32.15-45.3 60.89-45.3s52.83 19.17 60.89 45.3C329.41 239 309.08 240 288 240zm64-144c0 35.29-28.71 64-64 64s-64-28.71-64-64V82.96c20.4-1.88 41.8-2.96 64-2.96s43.6 1.08 64 2.96V96zm46.93 134.9c-13.81-9.91-23.94-23.9-28.4-40.54-5.11-19.06-2.49-38.96 7.38-56.04l25.65-44.42C477.72 103.5 528 129.79 528 160c0 30.83-52.4 57.54-129.07 70.9z\"],\n    \"drumstick-bite\": [512, 512, [], \"f6d7\", \"M462.8 49.57a169.44 169.44 0 0 0-239.5 0C187.82 85 160.13 128 160.13 192v85.83l-40.62 40.59c-9.7 9.69-24 11.07-36.78 6a60.33 60.33 0 0 0-65 98.72C33 438.39 54.24 442.7 73.85 438.21c-4.5 19.6-.18 40.83 15.1 56.1a60.35 60.35 0 0 0 98.8-65c-5.09-12.73-3.72-27 6-36.75L234.36 352h85.89a187.87 187.87 0 0 0 61.89-10c-39.64-43.89-39.83-110.23 1.05-151.07 34.38-34.36 86.76-39.46 128.74-16.8 1.3-44.96-14.81-90.28-49.13-124.56z\"],\n    \"dumbbell\": [640, 512, [], \"f44b\", \"M104 96H56c-13.3 0-24 10.7-24 24v104H8c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h24v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm528 128h-24V120c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v272c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h24c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zM456 32h-48c-13.3 0-24 10.7-24 24v168H256V56c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v400c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h128v168c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24z\"],\n    \"dumpster\": [576, 512, [], \"f793\", \"M560 160c10.4 0 18-9.8 15.5-19.9l-24-96C549.7 37 543.3 32 536 32h-98.9l25.6 128H560zM272 32H171.5l-25.6 128H272V32zm132.5 0H304v128h126.1L404.5 32zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm544 64h-20l4-32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h320v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16l20-160h28c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dumpster-fire\": [640, 512, [], \"f794\", \"M418.7 104.1l.2-.2-14.4-72H304v128h60.8c16.2-19.3 34.2-38.2 53.9-55.8zM272 32H171.5l-25.6 128H272V32zm189.3 72.1c18.2 16.3 35.5 33.7 51.1 51.5 5.7-5.6 11.4-11.1 17.3-16.3l21.3-19 21.3 19c1.1.9 2.1 2.1 3.1 3.1-.1-.8.2-1.5 0-2.3l-24-96C549.7 37 543.3 32 536 32h-98.9l12.3 61.5 11.9 10.6zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm324.6 32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208.8c-30.2-33.7-48.8-77.9-48.8-126.4 0-35.9 19.9-82.9 52.6-129.6zm210.5-28.8c-14.9 13.3-28.3 27.2-40.2 41.2-19.5-25.8-43.6-52-71-76.4-70.2 62.7-120 144.3-120 193.6 0 87.5 71.6 158.4 160 158.4s160-70.9 160-158.4c.1-36.6-37-112.2-88.8-158.4zm-18.6 229.4c-14.7 10.7-32.9 17-52.5 17-49 0-88.9-33.5-88.9-88 0-27.1 16.5-51 49.4-91.9 4.7 5.6 67.1 88.1 67.1 88.1l39.8-47c2.8 4.8 5.4 9.5 7.7 14 18.6 36.7 10.8 83.6-22.6 107.8z\"],\n    \"dungeon\": [512, 512, [], \"f6d9\", \"M128.73 195.32l-82.81-51.76c-8.04-5.02-18.99-2.17-22.93 6.45A254.19 254.19 0 0 0 .54 239.28C-.05 248.37 7.59 256 16.69 256h97.13c7.96 0 14.08-6.25 15.01-14.16 1.09-9.33 3.24-18.33 6.24-26.94 2.56-7.34.25-15.46-6.34-19.58zM319.03 8C298.86 2.82 277.77 0 256 0s-42.86 2.82-63.03 8c-9.17 2.35-13.91 12.6-10.39 21.39l37.47 104.03A16.003 16.003 0 0 0 235.1 144h41.8c6.75 0 12.77-4.23 15.05-10.58l37.47-104.03c3.52-8.79-1.22-19.03-10.39-21.39zM112 288H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm77.31-283.67l-36.32-90.8c-3.53-8.83-14.13-12.99-22.42-8.31a257.308 257.308 0 0 0-71.61 59.89c-6.06 7.32-3.85 18.48 4.22 23.52l82.93 51.83c6.51 4.07 14.66 2.62 20.11-2.79 5.18-5.15 10.79-9.85 16.79-14.05 6.28-4.41 9.15-12.17 6.3-19.29zM398.18 256h97.13c9.1 0 16.74-7.63 16.15-16.72a254.135 254.135 0 0 0-22.45-89.27c-3.94-8.62-14.89-11.47-22.93-6.45l-82.81 51.76c-6.59 4.12-8.9 12.24-6.34 19.58 3.01 8.61 5.15 17.62 6.24 26.94.93 7.91 7.05 14.16 15.01 14.16zm54.85-162.89a257.308 257.308 0 0 0-71.61-59.89c-8.28-4.68-18.88-.52-22.42 8.31l-36.32 90.8c-2.85 7.12.02 14.88 6.3 19.28 6 4.2 11.61 8.9 16.79 14.05 5.44 5.41 13.6 6.86 20.11 2.79l82.93-51.83c8.07-5.03 10.29-16.19 4.22-23.51zM496 288h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zM240 177.62V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V177.62c-5.23-.89-10.52-1.62-16-1.62s-10.77.73-16 1.62zm-64 41.51V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V189.36c-12.78 7.45-23.84 17.47-32 29.77zm128-29.77V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V219.13c-8.16-12.3-19.22-22.32-32-29.77z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.6 83.2l90.2 90.2c3.8 3.8 3.8 10 0 13.8L274.4 405.6l-92.8 10.3c-12.4 1.4-22.9-9.1-21.5-21.5l10.3-92.8L388.8 83.2c3.8-3.8 10-3.8 13.8 0zm162-22.9l-48.8-48.8c-15.2-15.2-39.9-15.2-55.2 0l-35.4 35.4c-3.8 3.8-3.8 10 0 13.8l90.2 90.2c3.8 3.8 10 3.8 13.8 0l35.4-35.4c15.2-15.3 15.2-40 0-55.2zM384 346.2V448H64V128h229.8c3.2 0 6.2-1.3 8.5-3.5l40-40c7.6-7.6 2.2-20.5-8.5-20.5H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V306.2c0-10.7-12.9-16-20.5-8.5l-40 40c-2.2 2.3-3.5 5.3-3.5 8.5z\"],\n    \"egg\": [384, 512, [], \"f7fb\", \"M192 0C86 0 0 214 0 320s86 192 192 192 192-86 192-192S298 0 192 0z\"],\n    \"eject\": [448, 512, [], \"f052\", \"M448 384v64c0 17.673-14.327 32-32 32H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h384c17.673 0 32 14.327 32 32zM48.053 320h351.886c41.651 0 63.581-49.674 35.383-80.435L259.383 47.558c-19.014-20.743-51.751-20.744-70.767 0L12.67 239.565C-15.475 270.268 6.324 320 48.053 320z\"],\n    \"ellipsis-h\": [512, 512, [], \"f141\", \"M328 256c0 39.8-32.2 72-72 72s-72-32.2-72-72 32.2-72 72-72 72 32.2 72 72zm104-72c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm-352 0c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72z\"],\n    \"ellipsis-v\": [192, 512, [], \"f142\", \"M96 184c39.8 0 72 32.2 72 72s-32.2 72-72 72-72-32.2-72-72 32.2-72 72-72zM24 80c0 39.8 32.2 72 72 72s72-32.2 72-72S135.8 8 96 8 24 40.2 24 80zm0 352c0 39.8 32.2 72 72 72s72-32.2 72-72-32.2-72-72-72-72 32.2-72 72z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M502.3 190.8c3.9-3.1 9.7-.2 9.7 4.7V400c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V195.6c0-5 5.7-7.8 9.7-4.7 22.4 17.4 52.1 39.5 154.1 113.6 21.1 15.4 56.7 47.8 92.2 47.6 35.7.3 72-32.8 92.3-47.6 102-74.1 131.6-96.3 154-113.7zM256 320c23.2.4 56.6-29.2 73.4-41.4 132.7-96.3 142.8-104.7 173.4-128.7 5.8-4.5 9.2-11.5 9.2-18.9v-19c0-26.5-21.5-48-48-48H48C21.5 64 0 85.5 0 112v19c0 7.4 3.4 14.3 9.2 18.9 30.6 23.9 40.7 32.4 173.4 128.7 16.8 12.2 50.2 41.8 73.4 41.4z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M512 464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V200.724a48 48 0 0 1 18.387-37.776c24.913-19.529 45.501-35.365 164.2-121.511C199.412 29.17 232.797-.347 256 .003c23.198-.354 56.596 29.172 73.413 41.433 118.687 86.137 139.303 101.995 164.2 121.512A48 48 0 0 1 512 200.724V464zm-65.666-196.605c-2.563-3.728-7.7-4.595-11.339-1.907-22.845 16.873-55.462 40.705-105.582 77.079-16.825 12.266-50.21 41.781-73.413 41.43-23.211.344-56.559-29.143-73.413-41.43-50.114-36.37-82.734-60.204-105.582-77.079-3.639-2.688-8.776-1.821-11.339 1.907l-9.072 13.196a7.998 7.998 0 0 0 1.839 10.967c22.887 16.899 55.454 40.69 105.303 76.868 20.274 14.781 56.524 47.813 92.264 47.573 35.724.242 71.961-32.771 92.263-47.573 49.85-36.179 82.418-59.97 105.303-76.868a7.998 7.998 0 0 0 1.839-10.967l-9.071-13.196z\"],\n    \"envelope-open-text\": [512, 512, [], \"f658\", \"M176 216h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16zm-16 80c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16zm96 121.13c-16.42 0-32.84-5.06-46.86-15.19L0 250.86V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V250.86L302.86 401.94c-14.02 10.12-30.44 15.19-46.86 15.19zm237.61-254.18c-8.85-6.94-17.24-13.47-29.61-22.81V96c0-26.51-21.49-48-48-48h-77.55c-3.04-2.2-5.87-4.26-9.04-6.56C312.6 29.17 279.2-.35 256 0c-23.2-.35-56.59 29.17-73.41 41.44-3.17 2.3-6 4.36-9.04 6.56H96c-26.51 0-48 21.49-48 48v44.14c-12.37 9.33-20.76 15.87-29.61 22.81A47.995 47.995 0 0 0 0 200.72v10.65l96 69.35V96h320v184.72l96-69.35v-10.65c0-14.74-6.78-28.67-18.39-37.77z\"],\n    \"envelope-square\": [448, 512, [], \"f199\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM178.117 262.104C87.429 196.287 88.353 196.121 64 177.167V152c0-13.255 10.745-24 24-24h272c13.255 0 24 10.745 24 24v25.167c-24.371 18.969-23.434 19.124-114.117 84.938-10.5 7.655-31.392 26.12-45.883 25.894-14.503.218-35.367-18.227-45.883-25.895zM384 217.775V360c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V217.775c13.958 10.794 33.329 25.236 95.303 70.214 14.162 10.341 37.975 32.145 64.694 32.01 26.887.134 51.037-22.041 64.72-32.025 61.958-44.965 81.325-59.406 95.283-70.199z\"],\n    \"equals\": [448, 512, [], \"f52c\", \"M416 304H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32zm0-192H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"eraser\": [512, 512, [], \"f12d\", \"M497.941 273.941c18.745-18.745 18.745-49.137 0-67.882l-160-160c-18.745-18.745-49.136-18.746-67.883 0l-256 256c-18.745 18.745-18.745 49.137 0 67.882l96 96A48.004 48.004 0 0 0 144 480h356c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H355.883l142.058-142.059zm-302.627-62.627l137.373 137.373L265.373 416H150.628l-80-80 124.686-124.686z\"],\n    \"ethernet\": [512, 512, [], \"f796\", \"M496 192h-48v-48c0-8.8-7.2-16-16-16h-48V80c0-8.8-7.2-16-16-16H144c-8.8 0-16 7.2-16 16v48H80c-8.8 0-16 7.2-16 16v48H16c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16h80V320h32v128h64V320h32v128h64V320h32v128h64V320h32v128h80c8.8 0 16-7.2 16-16V208c0-8.8-7.2-16-16-16z\"],\n    \"euro-sign\": [320, 512, [], \"f153\", \"M310.706 413.765c-1.314-6.63-7.835-10.872-14.424-9.369-10.692 2.439-27.422 5.413-45.426 5.413-56.763 0-101.929-34.79-121.461-85.449h113.689a12 12 0 0 0 11.708-9.369l6.373-28.36c1.686-7.502-4.019-14.631-11.708-14.631H115.22c-1.21-14.328-1.414-28.287.137-42.245H261.95a12 12 0 0 0 11.723-9.434l6.512-29.755c1.638-7.484-4.061-14.566-11.723-14.566H130.184c20.633-44.991 62.69-75.03 117.619-75.03 14.486 0 28.564 2.25 37.851 4.145 6.216 1.268 12.347-2.498 14.002-8.623l11.991-44.368c1.822-6.741-2.465-13.616-9.326-14.917C290.217 34.912 270.71 32 249.635 32 152.451 32 74.03 92.252 45.075 176H12c-6.627 0-12 5.373-12 12v29.755c0 6.627 5.373 12 12 12h21.569c-1.009 13.607-1.181 29.287-.181 42.245H12c-6.627 0-12 5.373-12 12v28.36c0 6.627 5.373 12 12 12h30.114C67.139 414.692 145.264 480 249.635 480c26.301 0 48.562-4.544 61.101-7.788 6.167-1.595 10.027-7.708 8.788-13.957l-8.818-44.49z\"],\n    \"exchange-alt\": [512, 512, [], \"f362\", \"M0 168v-16c0-13.255 10.745-24 24-24h360V80c0-21.367 25.899-32.042 40.971-16.971l80 80c9.372 9.373 9.372 24.569 0 33.941l-80 80C409.956 271.982 384 261.456 384 240v-48H24c-13.255 0-24-10.745-24-24zm488 152H128v-48c0-21.314-25.862-32.08-40.971-16.971l-80 80c-9.372 9.373-9.372 24.569 0 33.941l80 80C102.057 463.997 128 453.437 128 432v-48h360c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"exclamation\": [192, 512, [], \"f12a\", \"M176 432c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zM25.26 25.199l13.6 272C39.499 309.972 50.041 320 62.83 320h66.34c12.789 0 23.331-10.028 23.97-22.801l13.6-272C167.425 11.49 156.496 0 142.77 0H49.23C35.504 0 24.575 11.49 25.26 25.199z\"],\n    \"exclamation-circle\": [512, 512, [], \"f06a\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zm-248 50c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"exclamation-triangle\": [576, 512, [], \"f071\", \"M569.517 440.013C587.975 472.007 564.806 512 527.94 512H48.054c-36.937 0-59.999-40.055-41.577-71.987L246.423 23.985c18.467-32.009 64.72-31.951 83.154 0l239.94 416.028zM288 354c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"expand\": [448, 512, [], \"f065\", \"M0 180V56c0-13.3 10.7-24 24-24h124c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H64v84c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12zM288 44v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V56c0-13.3-10.7-24-24-24H300c-6.6 0-12 5.4-12 12zm148 276h-40c-6.6 0-12 5.4-12 12v84h-84c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24V332c0-6.6-5.4-12-12-12zM160 468v-40c0-6.6-5.4-12-12-12H64v-84c0-6.6-5.4-12-12-12H12c-6.6 0-12 5.4-12 12v124c0 13.3 10.7 24 24 24h124c6.6 0 12-5.4 12-12z\"],\n    \"expand-arrows-alt\": [448, 512, [], \"f31e\", \"M448 344v112a23.94 23.94 0 0 1-24 24H312c-21.39 0-32.09-25.9-17-41l36.2-36.2L224 295.6 116.77 402.9 153 439c15.09 15.1 4.39 41-17 41H24a23.94 23.94 0 0 1-24-24V344c0-21.4 25.89-32.1 41-17l36.19 36.2L184.46 256 77.18 148.7 41 185c-15.1 15.1-41 4.4-41-17V56a23.94 23.94 0 0 1 24-24h112c21.39 0 32.09 25.9 17 41l-36.2 36.2L224 216.4l107.23-107.3L295 73c-15.09-15.1-4.39-41 17-41h112a23.94 23.94 0 0 1 24 24v112c0 21.4-25.89 32.1-41 17l-36.19-36.2L263.54 256l107.28 107.3L407 327.1c15.1-15.2 41-4.5 41 16.9z\"],\n    \"external-link-alt\": [576, 512, [], \"f35d\", \"M576 24v127.984c0 21.461-25.96 31.98-40.971 16.971l-35.707-35.709-243.523 243.523c-9.373 9.373-24.568 9.373-33.941 0l-22.627-22.627c-9.373-9.373-9.373-24.569 0-33.941L442.756 76.676l-35.703-35.705C391.982 25.9 402.656 0 424.024 0H552c13.255 0 24 10.745 24 24zM407.029 270.794l-16 16A23.999 23.999 0 0 0 384 303.765V448H64V128h264a24.003 24.003 0 0 0 16.97-7.029l16-16C376.089 89.851 365.381 64 344 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V287.764c0-21.382-25.852-32.09-40.971-16.97z\"],\n    \"external-link-square-alt\": [448, 512, [], \"f360\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-88 16H248.029c-21.313 0-32.08 25.861-16.971 40.971l31.984 31.987L67.515 364.485c-4.686 4.686-4.686 12.284 0 16.971l31.029 31.029c4.687 4.686 12.285 4.686 16.971 0l195.526-195.526 31.988 31.991C358.058 263.977 384 253.425 384 231.979V120c0-13.255-10.745-24-24-24z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M572.52 241.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400a144 144 0 1 1 144-144 143.93 143.93 0 0 1-144 144zm0-240a95.31 95.31 0 0 0-25.31 3.79 47.85 47.85 0 0 1-66.9 66.9A95.78 95.78 0 1 0 288 160z\"],\n    \"eye-dropper\": [512, 512, [], \"f1fb\", \"M50.75 333.25c-12 12-18.75 28.28-18.75 45.26V424L0 480l32 32 56-32h45.49c16.97 0 33.25-6.74 45.25-18.74l126.64-126.62-128-128L50.75 333.25zM483.88 28.12c-37.47-37.5-98.28-37.5-135.75 0l-77.09 77.09-13.1-13.1c-9.44-9.44-24.65-9.31-33.94 0l-40.97 40.97c-9.37 9.37-9.37 24.57 0 33.94l161.94 161.94c9.44 9.44 24.65 9.31 33.94 0L419.88 288c9.37-9.37 9.37-24.57 0-33.94l-13.1-13.1 77.09-77.09c37.51-37.48 37.51-98.26.01-135.75z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M320 400c-75.85 0-137.25-58.71-142.9-133.11L72.2 185.82c-13.79 17.3-26.48 35.59-36.72 55.59a32.35 32.35 0 0 0 0 29.19C89.71 376.41 197.07 448 320 448c26.91 0 52.87-4 77.89-10.46L346 397.39a144.13 144.13 0 0 1-26 2.61zm313.82 58.1l-110.55-85.44a331.25 331.25 0 0 0 81.25-102.07 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64a308.15 308.15 0 0 0-147.32 37.7L45.46 3.37A16 16 0 0 0 23 6.18L3.37 31.45A16 16 0 0 0 6.18 53.9l588.36 454.73a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zm-183.72-142l-39.3-30.38A94.75 94.75 0 0 0 416 256a94.76 94.76 0 0 0-121.31-92.21A47.65 47.65 0 0 1 304 192a46.64 46.64 0 0 1-1.54 10l-73.61-56.89A142.31 142.31 0 0 1 320 112a143.92 143.92 0 0 1 144 144c0 21.63-5.29 41.79-13.9 60.11z\"],\n    \"fan\": [512, 512, [], \"f863\", \"M352.57 128c-28.09 0-54.09 4.52-77.06 12.86l12.41-123.11C289 7.31 279.81-1.18 269.33.13 189.63 10.13 128 77.64 128 159.43c0 28.09 4.52 54.09 12.86 77.06L17.75 224.08C7.31 223-1.18 232.19.13 242.67c10 79.7 77.51 141.33 159.3 141.33 28.09 0 54.09-4.52 77.06-12.86l-12.41 123.11c-1.05 10.43 8.11 18.93 18.59 17.62 79.7-10 141.33-77.51 141.33-159.3 0-28.09-4.52-54.09-12.86-77.06l123.11 12.41c10.44 1.05 18.93-8.11 17.62-18.59-10-79.7-77.51-141.33-159.3-141.33zM256 288a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"fast-backward\": [512, 512, [], \"f049\", \"M0 436V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v151.9L235.5 71.4C256.1 54.3 288 68.6 288 96v131.9L459.5 71.4C480.1 54.3 512 68.6 512 96v320c0 27.4-31.9 41.7-52.5 24.6L288 285.3V416c0 27.4-31.9 41.7-52.5 24.6L64 285.3V436c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12z\"],\n    \"fast-forward\": [512, 512, [], \"f050\", \"M512 76v360c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V284.1L276.5 440.6c-20.6 17.2-52.5 2.8-52.5-24.6V284.1L52.5 440.6C31.9 457.8 0 443.4 0 416V96c0-27.4 31.9-41.7 52.5-24.6L224 226.8V96c0-27.4 31.9-41.7 52.5-24.6L448 226.8V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12z\"],\n    \"fax\": [512, 512, [], \"f1ac\", \"M64 128H32c-17.67 0-32 14.33-32 32v320c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zm416 32V77.25c0-8.49-3.37-16.62-9.37-22.63L425.37 9.37c-6-6-14.14-9.37-22.63-9.37H160c-17.67 0-32 14.33-32 32v448c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zM288 432c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm128 128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm16-112H176V48h208v32c0 8.84 7.16 16 16 16h32v96z\"],\n    \"feather\": [512, 512, [], \"f52d\", \"M467.14 44.84c-62.55-62.48-161.67-64.78-252.28 25.73-78.61 78.52-60.98 60.92-85.75 85.66-60.46 60.39-70.39 150.83-63.64 211.17l178.44-178.25c6.26-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.6 9.37 33.98 0l66.1-66.03C159.42 454.65 279 457.11 353.95 384h-98.19l147.57-49.14c49.99-49.93 36.38-36.18 46.31-46.86h-97.78l131.54-43.8c45.44-74.46 34.31-148.84-16.26-199.36z\"],\n    \"feather-alt\": [512, 512, [], \"f56b\", \"M512 0C460.22 3.56 96.44 38.2 71.01 287.61c-3.09 26.66-4.84 53.44-5.99 80.24l178.87-178.69c6.25-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.59 9.37 33.98 0l57.13-57.07c42.09-.14 84.15-2.53 125.96-7.36 53.48-5.44 97.02-26.47 132.58-56.54H255.74l146.79-48.88c11.25-14.89 21.37-30.71 30.45-47.12h-81.14l106.54-53.21C500.29 132.86 510.19 26.26 512 0z\"],\n    \"female\": [256, 512, [], \"f182\", \"M128 0c35.346 0 64 28.654 64 64s-28.654 64-64 64c-35.346 0-64-28.654-64-64S92.654 0 128 0m119.283 354.179l-48-192A24 24 0 0 0 176 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H80a24 24 0 0 0-23.283 18.179l-48 192C4.935 369.305 16.383 384 32 384h56v104c0 13.255 10.745 24 24 24h32c13.255 0 24-10.745 24-24V384h56c15.591 0 27.071-14.671 23.283-29.821z\"],\n    \"fighter-jet\": [640, 512, [], \"f0fb\", \"M544 224l-128-16-48-16h-24L227.158 44h39.509C278.333 44 288 41.375 288 38s-9.667-6-21.333-6H152v12h16v164h-48l-66.667-80H18.667L8 138.667V208h8v16h48v2.666l-64 8v42.667l64 8V288H16v16H8v69.333L18.667 384h34.667L120 304h48v164h-16v12h114.667c11.667 0 21.333-2.625 21.333-6s-9.667-6-21.333-6h-39.509L344 320h24l48-16 128-16c96-21.333 96-26.583 96-32 0-5.417 0-10.667-96-32z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm160-14.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 236c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-64c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-72v8c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm96-114.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zM128.4 336c-17.9 0-32.4 12.1-32.4 27 0 15 14.6 27 32.5 27s32.4-12.1 32.4-27-14.6-27-32.5-27zM224 136V0h-63.6v32h-32V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM95.9 32h32v32h-32zm32.3 384c-33.2 0-58-30.4-51.4-62.9L96.4 256v-32h32v-32h-32v-32h32v-32h-32V96h32V64h32v32h-32v32h32v32h-32v32h32v32h-32v32h22.1c5.7 0 10.7 4.1 11.8 9.7l17.3 87.7c6.4 32.4-18.4 62.6-51.4 62.6z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-64 268c0 10.7-12.9 16-20.5 8.5L104 376H76c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h28l35.5-36.5c7.6-7.6 20.5-2.2 20.5 8.5v136zm33.2-47.6c9.1-9.3 9.1-24.1 0-33.4-22.1-22.8 12.2-56.2 34.4-33.5 27.2 27.9 27.2 72.4 0 100.4-21.8 22.3-56.9-10.4-34.4-33.5zm86-117.1c54.4 55.9 54.4 144.8 0 200.8-21.8 22.4-57-10.3-34.4-33.5 36.2-37.2 36.3-96.5 0-133.8-22.1-22.8 12.3-56.3 34.4-33.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zM123.206 400.505a5.4 5.4 0 0 1-7.633.246l-64.866-60.812a5.4 5.4 0 0 1 0-7.879l64.866-60.812a5.4 5.4 0 0 1 7.633.246l19.579 20.885a5.4 5.4 0 0 1-.372 7.747L101.65 336l40.763 35.874a5.4 5.4 0 0 1 .372 7.747l-19.579 20.884zm51.295 50.479l-27.453-7.97a5.402 5.402 0 0 1-3.681-6.692l61.44-211.626a5.402 5.402 0 0 1 6.692-3.681l27.452 7.97a5.4 5.4 0 0 1 3.68 6.692l-61.44 211.626a5.397 5.397 0 0 1-6.69 3.681zm160.792-111.045l-64.866 60.812a5.4 5.4 0 0 1-7.633-.246l-19.58-20.885a5.4 5.4 0 0 1 .372-7.747L284.35 336l-40.763-35.874a5.4 5.4 0 0 1-.372-7.747l19.58-20.885a5.4 5.4 0 0 1 7.633-.246l64.866 60.812a5.4 5.4 0 0 1-.001 7.879z\"],\n    \"file-contract\": [384, 512, [], \"f56c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm192.81 248H304c8.84 0 16 7.16 16 16s-7.16 16-16 16h-47.19c-16.45 0-31.27-9.14-38.64-23.86-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34a15.986 15.986 0 0 1-14.31 8.84c-.38 0-.75-.02-1.14-.05-6.45-.45-12-4.75-14.03-10.89L144 354.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.77-16.19 54.05-9.7 66 14.16 2.02 4.06 5.96 6.5 10.16 6.5zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-csv\": [384, 512, [], \"f6dd\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-96 144c0 4.42-3.58 8-8 8h-8c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h8c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-8c-26.51 0-48-21.49-48-48v-32c0-26.51 21.49-48 48-48h8c4.42 0 8 3.58 8 8v16zm44.27 104H160c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h12.27c5.95 0 10.41-3.5 10.41-6.62 0-1.3-.75-2.66-2.12-3.84l-21.89-18.77c-8.47-7.22-13.33-17.48-13.33-28.14 0-21.3 19.02-38.62 42.41-38.62H200c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-12.27c-5.95 0-10.41 3.5-10.41 6.62 0 1.3.75 2.66 2.12 3.84l21.89 18.77c8.47 7.22 13.33 17.48 13.33 28.14.01 21.29-19 38.62-42.39 38.62zM256 264v20.8c0 20.27 5.7 40.17 16 56.88 10.3-16.7 16-36.61 16-56.88V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v20.8c0 35.48-12.88 68.89-36.28 94.09-3.02 3.25-7.27 5.11-11.72 5.11s-8.7-1.86-11.72-5.11c-23.4-25.2-36.28-58.61-36.28-94.09V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8zm121-159L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-download\": [384, 512, [], \"f56d\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm76.45 211.36l-96.42 95.7c-6.65 6.61-17.39 6.61-24.04 0l-96.42-95.7C73.42 337.29 80.54 320 94.82 320H160v-80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v80h65.18c14.28 0 21.4 17.29 11.27 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm60.1 106.5L224 336l60.1 93.5c5.1 8-.6 18.5-10.1 18.5h-34.9c-4.4 0-8.5-2.4-10.6-6.3C208.9 405.5 192 373 192 373c-6.4 14.8-10 20-36.6 68.8-2.1 3.9-6.1 6.3-10.5 6.3H110c-9.5 0-15.2-10.5-10.1-18.5l60.3-93.5-60.3-93.5c-5.2-8 .6-18.5 10.1-18.5h34.8c4.4 0 8.5 2.4 10.6 6.3 26.1 48.8 20 33.6 36.6 68.5 0 0 6.1-11.7 36.6-68.5 2.1-3.9 6.2-6.3 10.6-6.3H274c9.5-.1 15.2 10.4 10.1 18.4zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-export\": [576, 512, [], \"f56e\", \"M384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128zM571 308l-95.7-96.4c-10.1-10.1-27.4-3-27.4 11.3V288h-64v64h64v65.2c0 14.3 17.3 21.4 27.4 11.3L571 332c6.6-6.6 6.6-17.4 0-24zm-379 28v-32c0-8.8 7.2-16 16-16h176V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V352H208c-8.8 0-16-7.2-16-16z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M384 121.941V128H256V0h6.059a24 24 0 0 1 16.97 7.029l97.941 97.941a24.002 24.002 0 0 1 7.03 16.971zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zm-135.455 16c26.51 0 48 21.49 48 48s-21.49 48-48 48-48-21.49-48-48 21.491-48 48-48zm208 240h-256l.485-48.485L104.545 328c4.686-4.686 11.799-4.201 16.485.485L160.545 368 264.06 264.485c4.686-4.686 12.284-4.686 16.971 0L320.545 304v112z\"],\n    \"file-import\": [512, 512, [], \"f56f\", \"M16 288c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h112v-64zm489-183L407.1 7c-4.5-4.5-10.6-7-17-7H384v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H152c-13.3 0-24 10.7-24 24v264h128v-65.2c0-14.3 17.3-21.4 27.4-11.3L379 308c6.6 6.7 6.6 17.4 0 24l-95.7 96.4c-10.1 10.1-27.4 3-27.4-11.3V352H128v136c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H376c-13.2 0-24-10.8-24-24z\"],\n    \"file-invoice\": [384, 512, [], \"f570\", \"M288 256H96v64h192v-64zm89-151L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm256 304c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-200v96c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-96c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16z\"],\n    \"file-invoice-dollar\": [384, 512, [], \"f571\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 80v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8zm144 263.88V440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-24.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V232c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v24.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07z\"],\n    \"file-medical\": [384, 512, [], \"f477\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 160v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8z\"],\n    \"file-medical-alt\": [448, 512, [], \"f478\", \"M288 136V0H88C74.7 0 64 10.7 64 24v232H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h140.9c3 0 5.8 1.7 7.2 4.4l19.9 39.8 56.8-113.7c2.9-5.9 11.4-5.9 14.3 0l34.7 69.5H352c8.8 0 16 7.2 16 16s-7.2 16-16 16h-89.9L240 275.8l-56.8 113.7c-2.9 5.9-11.4 5.9-14.3 0L134.1 320H64v168c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H312c-13.2 0-24-10.8-24-24zm153-31L343.1 7c-4.5-4.5-10.6-7-17-7H320v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M181.9 256.1c-5-16-4.9-46.9-2-46.9 8.4 0 7.6 36.9 2 46.9zm-1.7 47.2c-7.7 20.2-17.3 43.3-28.4 62.7 18.3-7 39-17.2 62.9-21.9-12.7-9.6-24.9-23.4-34.5-40.8zM86.1 428.1c0 .8 13.2-5.4 34.9-40.2-6.7 6.3-29.1 24.5-34.9 40.2zM248 160h136v328c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V24C0 10.7 10.7 0 24 0h200v136c0 13.2 10.8 24 24 24zm-8 171.8c-20-12.2-33.3-29-42.7-53.8 4.5-18.5 11.6-46.6 6.2-64.2-4.7-29.4-42.4-26.5-47.8-6.8-5 18.3-.4 44.1 8.1 77-11.6 27.6-28.7 64.6-40.8 85.8-.1 0-.1.1-.2.1-27.1 13.9-73.6 44.5-54.5 68 5.6 6.9 16 10 21.5 10 17.9 0 35.7-18 61.1-61.8 25.8-8.5 54.1-19.1 79-23.2 21.7 11.8 47.1 19.5 64 19.5 29.2 0 31.2-32 19.7-43.4-13.9-13.6-54.3-9.7-73.6-7.2zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-74.1 255.3c4.1-2.7-2.5-11.9-42.8-9 37.1 15.8 42.8 9 42.8 9z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M193.7 271.2c8.8 0 15.5 2.7 20.3 8.1 9.6 10.9 9.8 32.7-.2 44.1-4.9 5.6-11.9 8.5-21.1 8.5h-26.9v-60.7h27.9zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm53 165.2c0 90.3-88.8 77.6-111.1 77.6V436c0 6.6-5.4 12-12 12h-30.8c-6.6 0-12-5.4-12-12V236.2c0-6.6 5.4-12 12-12h81c44.5 0 72.9 32.8 72.9 77z\"],\n    \"file-prescription\": [384, 512, [], \"f572\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm68.53 179.48l11.31 11.31c6.25 6.25 6.25 16.38 0 22.63l-29.9 29.9L304 409.38c6.25 6.25 6.25 16.38 0 22.63l-11.31 11.31c-6.25 6.25-16.38 6.25-22.63 0L240 413.25l-30.06 30.06c-6.25 6.25-16.38 6.25-22.63 0L176 432c-6.25-6.25-6.25-16.38 0-22.63l30.06-30.06L146.74 320H128v48c0 8.84-7.16 16-16 16H96c-8.84 0-16-7.16-16-16V208c0-8.84 7.16-16 16-16h80c35.35 0 64 28.65 64 64 0 24.22-13.62 45.05-33.46 55.92L240 345.38l29.9-29.9c6.25-6.25 16.38-6.25 22.63 0zM176 272h-48v-32h48c8.82 0 16 7.18 16 16s-7.18 16-16 16zm208-150.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-signature\": [576, 512, [], \"f573\", \"M218.17 424.14c-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34c-6.37 12.78-25.03 11.37-29.48-2.09L144 386.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.75-16.19 54.06-9.7 66 14.16 1.89 3.78 5.49 5.95 9.36 6.26v-82.12l128-127.09V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24v-40l-128-.11c-16.12-.31-30.58-9.28-37.83-23.75zM384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1zm-96 225.06V416h68.99l161.68-162.78-67.88-67.88L288 346.96zm280.54-179.63l-31.87-31.87c-9.94-9.94-26.07-9.94-36.01 0l-27.25 27.25 67.88 67.88 27.25-27.25c9.95-9.94 9.95-26.07 0-36.01z\"],\n    \"file-upload\": [384, 512, [], \"f574\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm65.18 216.01H224v80c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-80H94.82c-14.28 0-21.41-17.29-11.27-27.36l96.42-95.7c6.65-6.61 17.39-6.61 24.04 0l96.42 95.7c10.15 10.07 3.03 27.36-11.25 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM224 136V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248c-13.2 0-24-10.8-24-24zm96 144.016v111.963c0 21.445-25.943 31.998-40.971 16.971L224 353.941V392c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V280c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v38.059l55.029-55.013c15.011-15.01 40.971-4.491 40.971 16.97z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm57.1 120H305c7.7 0 13.4 7.1 11.7 14.7l-38 168c-1.2 5.5-6.1 9.3-11.7 9.3h-38c-5.5 0-10.3-3.8-11.6-9.1-25.8-103.5-20.8-81.2-25.6-110.5h-.5c-1.1 14.3-2.4 17.4-25.6 110.5-1.3 5.3-6.1 9.1-11.6 9.1H117c-5.6 0-10.5-3.9-11.7-9.4l-37.8-168c-1.7-7.5 4-14.6 11.7-14.6h24.5c5.7 0 10.7 4 11.8 9.7 15.6 78 20.1 109.5 21 122.2 1.6-10.2 7.3-32.7 29.4-122.7 1.3-5.4 6.1-9.1 11.7-9.1h29.1c5.6 0 10.4 3.8 11.7 9.2 24 100.4 28.8 124 29.6 129.4-.2-11.2-2.6-17.8 21.6-129.2 1-5.6 5.9-9.5 11.5-9.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"fill\": [512, 512, [], \"f575\", \"M502.63 217.06L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.77c-6.24-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.63l86.19 86.18-94.76 94.76c-37.49 37.49-37.49 98.26 0 135.75l117.19 117.19c18.75 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.88-28.12l221.57-221.57c12.49-12.5 12.49-32.76 0-45.26zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.61 58.6c12.49 12.49 32.75 12.49 45.24 0 12.49-12.49 12.49-32.75 0-45.24l-58.61-58.6 58.95-58.95 162.45 162.44-48.35 48.34z\"],\n    \"fill-drip\": [576, 512, [], \"f576\", \"M512 320s-64 92.65-64 128c0 35.35 28.66 64 64 64s64-28.65 64-64-64-128-64-128zm-9.37-102.94L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.76c-6.25-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.62l86.19 86.18-94.76 94.76c-37.49 37.48-37.49 98.26 0 135.75l117.19 117.19c18.74 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.87-28.12l221.57-221.57c12.5-12.5 12.5-32.75.01-45.25zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.6 58.6c12.49 12.49 32.75 12.49 45.24 0s12.49-32.75 0-45.24l-58.6-58.6 58.95-58.95 162.44 162.44-48.34 48.34z\"],\n    \"film\": [512, 512, [], \"f008\", \"M488 64h-8v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V64H96v20c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12V64h-8C10.7 64 0 74.7 0 88v336c0 13.3 10.7 24 24 24h8v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h320v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h8c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24zM96 372c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm272 208c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm0-168c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm112 152c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"filter\": [512, 512, [], \"f0b0\", \"M487.976 0H24.028C2.71 0-8.047 25.866 7.058 40.971L192 225.941V432c0 7.831 3.821 15.17 10.237 19.662l80 55.98C298.02 518.69 320 507.493 320 487.98V225.941l184.947-184.97C520.021 25.896 509.338 0 487.976 0z\"],\n    \"fingerprint\": [512, 512, [], \"f577\", \"M256.12 245.96c-13.25 0-24 10.74-24 24 1.14 72.25-8.14 141.9-27.7 211.55-2.73 9.72 2.15 30.49 23.12 30.49 10.48 0 20.11-6.92 23.09-17.52 13.53-47.91 31.04-125.41 29.48-224.52.01-13.25-10.73-24-23.99-24zm-.86-81.73C194 164.16 151.25 211.3 152.1 265.32c.75 47.94-3.75 95.91-13.37 142.55-2.69 12.98 5.67 25.69 18.64 28.36 13.05 2.67 25.67-5.66 28.36-18.64 10.34-50.09 15.17-101.58 14.37-153.02-.41-25.95 19.92-52.49 54.45-52.34 31.31.47 57.15 25.34 57.62 55.47.77 48.05-2.81 96.33-10.61 143.55-2.17 13.06 6.69 25.42 19.76 27.58 19.97 3.33 26.81-15.1 27.58-19.77 8.28-50.03 12.06-101.21 11.27-152.11-.88-55.8-47.94-101.88-104.91-102.72zm-110.69-19.78c-10.3-8.34-25.37-6.8-33.76 3.48-25.62 31.5-39.39 71.28-38.75 112 .59 37.58-2.47 75.27-9.11 112.05-2.34 13.05 6.31 25.53 19.36 27.89 20.11 3.5 27.07-14.81 27.89-19.36 7.19-39.84 10.5-80.66 9.86-121.33-.47-29.88 9.2-57.88 28-80.97 8.35-10.28 6.79-25.39-3.49-33.76zm109.47-62.33c-15.41-.41-30.87 1.44-45.78 4.97-12.89 3.06-20.87 15.98-17.83 28.89 3.06 12.89 16 20.83 28.89 17.83 11.05-2.61 22.47-3.77 34-3.69 75.43 1.13 137.73 61.5 138.88 134.58.59 37.88-1.28 76.11-5.58 113.63-1.5 13.17 7.95 25.08 21.11 26.58 16.72 1.95 25.51-11.88 26.58-21.11a929.06 929.06 0 0 0 5.89-119.85c-1.56-98.75-85.07-180.33-186.16-181.83zm252.07 121.45c-2.86-12.92-15.51-21.2-28.61-18.27-12.94 2.86-21.12 15.66-18.26 28.61 4.71 21.41 4.91 37.41 4.7 61.6-.11 13.27 10.55 24.09 23.8 24.2h.2c13.17 0 23.89-10.61 24-23.8.18-22.18.4-44.11-5.83-72.34zm-40.12-90.72C417.29 43.46 337.6 1.29 252.81.02 183.02-.82 118.47 24.91 70.46 72.94 24.09 119.37-.9 181.04.14 246.65l-.12 21.47c-.39 13.25 10.03 24.31 23.28 24.69.23.02.48.02.72.02 12.92 0 23.59-10.3 23.97-23.3l.16-23.64c-.83-52.5 19.16-101.86 56.28-139 38.76-38.8 91.34-59.67 147.68-58.86 69.45 1.03 134.73 35.56 174.62 92.39 7.61 10.86 22.56 13.45 33.42 5.86 10.84-7.62 13.46-22.59 5.84-33.43z\"],\n    \"fire\": [384, 512, [], \"f06d\", \"M216 23.86c0-23.8-30.65-32.77-44.15-13.04C48 191.85 224 200 224 288c0 35.63-29.11 64.46-64.85 63.99-35.17-.45-63.15-29.77-63.15-64.94v-85.51c0-21.7-26.47-32.23-41.43-16.5C27.8 213.16 0 261.33 0 320c0 105.87 86.13 192 192 192s192-86.13 192-192c0-170.29-168-193-168-296.14z\"],\n    \"fire-alt\": [448, 512, [], \"f7e4\", \"M323.56 51.2c-20.8 19.3-39.58 39.59-56.22 59.97C240.08 73.62 206.28 35.53 168 0 69.74 91.17 0 209.96 0 281.6 0 408.85 100.29 512 224 512s224-103.15 224-230.4c0-53.27-51.98-163.14-124.44-230.4zm-19.47 340.65C282.43 407.01 255.72 416 226.86 416 154.71 416 96 368.26 96 290.75c0-38.61 24.31-72.63 72.79-130.75 6.93 7.98 98.83 125.34 98.83 125.34l58.63-66.88c4.14 6.85 7.91 13.55 11.27 19.97 27.35 52.19 15.81 118.97-33.43 153.42z\"],\n    \"fire-extinguisher\": [448, 512, [], \"f134\", \"M434.027 26.329l-168 28C254.693 56.218 256 67.8 256 72h-58.332C208.353 36.108 181.446 0 144 0c-39.435 0-66.368 39.676-52.228 76.203-52.039 13.051-75.381 54.213-90.049 90.884-4.923 12.307 1.063 26.274 13.37 31.197 12.317 4.926 26.279-1.075 31.196-13.37C75.058 112.99 106.964 120 168 120v27.076c-41.543 10.862-72 49.235-72 94.129V488c0 13.255 10.745 24 24 24h144c13.255 0 24-10.745 24-24V240c0-44.731-30.596-82.312-72-92.97V120h40c0 2.974-1.703 15.716 10.027 17.671l168 28C441.342 166.89 448 161.25 448 153.834V38.166c0-7.416-6.658-13.056-13.973-11.837zM144 72c-8.822 0-16-7.178-16-16s7.178-16 16-16 16 7.178 16 16-7.178 16-16 16z\"],\n    \"first-aid\": [576, 512, [], \"f479\", \"M0 80v352c0 26.5 21.5 48 48 48h48V32H48C21.5 32 0 53.5 0 80zm128 400h320V32H128v448zm64-248c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48zM528 32h-48v448h48c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"fish\": [576, 512, [], \"f578\", \"M327.1 96c-89.97 0-168.54 54.77-212.27 101.63L27.5 131.58c-12.13-9.18-30.24.6-27.14 14.66L24.54 256 .35 365.77c-3.1 14.06 15.01 23.83 27.14 14.66l87.33-66.05C158.55 361.23 237.13 416 327.1 416 464.56 416 576 288 576 256S464.56 96 327.1 96zm87.43 184c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24 13.26 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"fist-raised\": [384, 512, [], \"f6de\", \"M255.98 160V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v146.93c5.02-1.78 10.34-2.93 15.97-2.93h48.03zm128 95.99c-.01-35.34-28.66-63.99-63.99-63.99H207.85c-8.78 0-15.9 7.07-15.9 15.85v.56c0 26.27 21.3 47.59 47.57 47.59h35.26c9.68 0 13.2 3.58 13.2 8v16.2c0 4.29-3.59 7.78-7.88 8-44.52 2.28-64.16 24.71-96.05 72.55l-6.31 9.47a7.994 7.994 0 0 1-11.09 2.22l-13.31-8.88a7.994 7.994 0 0 1-2.22-11.09l6.31-9.47c15.73-23.6 30.2-43.26 47.31-58.08-17.27-5.51-31.4-18.12-38.87-34.45-6.59 3.41-13.96 5.52-21.87 5.52h-32c-12.34 0-23.49-4.81-32-12.48C71.48 251.19 60.33 256 48 256H16c-5.64 0-10.97-1.15-16-2.95v77.93c0 33.95 13.48 66.5 37.49 90.51L63.99 448v64h255.98v-63.96l35.91-35.92A96.035 96.035 0 0 0 384 344.21l-.02-88.22zm-32.01-90.09V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v112h32c11.28 0 21.94 2.31 32 5.9zM16 224h32c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v128c0 8.84 7.16 16 16 16zm95.99 0h32c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v160c0 8.84 7.16 16 16 16z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M349.565 98.783C295.978 98.783 251.721 64 184.348 64c-24.955 0-47.309 4.384-68.045 12.013a55.947 55.947 0 0 0 3.586-23.562C118.117 24.015 94.806 1.206 66.338.048 34.345-1.254 8 24.296 8 56c0 19.026 9.497 35.825 24 45.945V488c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-94.4c28.311-12.064 63.582-22.122 114.435-22.122 53.588 0 97.844 34.783 165.217 34.783 48.169 0 86.667-16.294 122.505-40.858C506.84 359.452 512 349.571 512 339.045v-243.1c0-23.393-24.269-38.87-45.485-29.016-34.338 15.948-76.454 31.854-116.95 31.854z\"],\n    \"flag-checkered\": [512, 512, [], \"f11e\", \"M243.2 189.9V258c26.1 5.9 49.3 15.6 73.6 22.3v-68.2c-26-5.8-49.4-15.5-73.6-22.2zm223.3-123c-34.3 15.9-76.5 31.9-117 31.9C296 98.8 251.7 64 184.3 64c-25 0-47.3 4.4-68 12 2.8-7.3 4.1-15.2 3.6-23.6C118.1 24 94.8 1.2 66.3 0 34.3-1.3 8 24.3 8 56c0 19 9.5 35.8 24 45.9V488c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24v-94.4c28.3-12.1 63.6-22.1 114.4-22.1 53.6 0 97.8 34.8 165.2 34.8 48.2 0 86.7-16.3 122.5-40.9 8.7-6 13.8-15.8 13.8-26.4V95.9c.1-23.3-24.2-38.8-45.4-29zM169.6 325.5c-25.8 2.7-50 8.2-73.6 16.6v-70.5c26.2-9.3 47.5-15 73.6-17.4zM464 191c-23.6 9.8-46.3 19.5-73.6 23.9V286c24.8-3.4 51.4-11.8 73.6-26v70.5c-25.1 16.1-48.5 24.7-73.6 27.1V286c-27 3.7-47.9 1.5-73.6-5.6v67.4c-23.9-7.4-47.3-16.7-73.6-21.3V258c-19.7-4.4-40.8-6.8-73.6-3.8v-70c-22.4 3.1-44.6 10.2-73.6 20.9v-70.5c33.2-12.2 50.1-19.8 73.6-22v71.6c27-3.7 48.4-1.3 73.6 5.7v-67.4c23.7 7.4 47.2 16.7 73.6 21.3v68.4c23.7 5.3 47.6 6.9 73.6 2.7V143c27-4.8 52.3-13.6 73.6-22.5z\"],\n    \"flag-usa\": [512, 512, [], \"f74d\", \"M32 0C14.3 0 0 14.3 0 32v464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32C64 14.3 49.7 0 32 0zm267.9 303.6c-57.2-15.1-111.7-28.8-203.9 11.1V384c185.7-92.2 221.7 53.3 397.5-23.1 11.4-5 18.5-16.5 18.5-28.8v-36c-43.6 17.3-80.2 24.1-112.1 24.1-37.4-.1-68.9-8.4-100-16.6zm0-96c-57.2-15.1-111.7-28.8-203.9 11.1v61.5c94.8-37.6 154.6-22.7 212.1-7.6 57.2 15.1 111.7 28.8 203.9-11.1V200c-43.6 17.3-80.2 24.1-112.1 24.1-37.4 0-68.9-8.3-100-16.5zm9.5-125.9c51.8 15.6 97.4 29 202.6-20.1V30.8c0-25.1-26.8-38.1-49.4-26.6C291.3 91.5 305.4-62.2 96 32.4v151.9c94.8-37.5 154.6-22.7 212.1-7.6 57.2 15 111.7 28.7 203.9-11.1V96.7c-53.6 23.5-93.3 31.4-126.1 31.4s-59-7.8-85.7-15.9c-4-1.2-8.1-2.4-12.1-3.5V75.5c7.2 2 14.3 4.1 21.3 6.2zM160 128.1c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16-7.2 16-16 16zm0-55.8c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm64 47.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm0-55.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16z\"],\n    \"flask\": [448, 512, [], \"f0c3\", \"M437.2 403.5L320 215V64h8c13.3 0 24-10.7 24-24V24c0-13.3-10.7-24-24-24H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h8v151L10.8 403.5C-18.5 450.6 15.3 512 70.9 512h306.2c55.7 0 89.4-61.5 60.1-108.5zM137.9 320l48.2-77.6c3.7-5.2 5.8-11.6 5.8-18.4V64h64v160c0 6.9 2.2 13.2 5.8 18.4l48.2 77.6h-172z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M344 200c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-192 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM80 224c0-39.8 32.2-72 72-72s72 32.2 72 72-32.2 72-72 72-72-32.2-72-72zm232 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-104c-39.8 0-72-32.2-72-72s32.2-72 72-72 72 32.2 72 72-32.2 72-72 72z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48z\"],\n    \"folder-minus\": [512, 512, [], \"f65d\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16H160c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h192c8.84 0 16 7.16 16 16v16z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M572.694 292.093L500.27 416.248A63.997 63.997 0 0 1 444.989 448H45.025c-18.523 0-30.064-20.093-20.731-36.093l72.424-124.155A64 64 0 0 1 152 256h399.964c18.523 0 30.064 20.093 20.73 36.093zM152 224h328v-48c0-26.51-21.49-48-48-48H272l-64-64H48C21.49 64 0 85.49 0 112v278.046l69.077-118.418C86.214 242.25 117.989 224 152 224z\"],\n    \"folder-plus\": [512, 512, [], \"f65e\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16h-72v72c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-72h-72c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h72v-72c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v72h72c8.84 0 16 7.16 16 16v16z\"],\n    \"font\": [448, 512, [], \"f031\", \"M432 416h-23.41L277.88 53.69A32 32 0 0 0 247.58 32h-47.16a32 32 0 0 0-30.3 21.69L39.41 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-19.58l23.3-64h152.56l23.3 64H304a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM176.85 272L224 142.51 271.15 272z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"football-ball\": [496, 512, [], \"f44e\", \"M481.5 60.3c-4.8-18.2-19.1-32.5-37.3-37.4C420.3 16.5 383 8.9 339.4 8L496 164.8c-.8-43.5-8.2-80.6-14.5-104.5zm-467 391.4c4.8 18.2 19.1 32.5 37.3 37.4 23.9 6.4 61.2 14 104.8 14.9L0 347.2c.8 43.5 8.2 80.6 14.5 104.5zM4.2 283.4L220.4 500c132.5-19.4 248.8-118.7 271.5-271.4L275.6 12C143.1 31.4 26.8 130.7 4.2 283.4zm317.3-123.6c3.1-3.1 8.2-3.1 11.3 0l11.3 11.3c3.1 3.1 3.1 8.2 0 11.3l-28.3 28.3 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-22.6 22.7 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L248 278.6l-22.6 22.6 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-28.3 28.3c-3.1 3.1-8.2 3.1-11.3 0l-11.3-11.3c-3.1-3.1-3.1-8.2 0-11.3l28.3-28.3-28.3-28.2c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 28.3-28.5z\"],\n    \"forward\": [512, 512, [], \"f04e\", \"M500.5 231.4l-192-160C287.9 54.3 256 68.6 256 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2zm-256 0l-192-160C31.9 54.3 0 68.6 0 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2z\"],\n    \"frog\": [576, 512, [], \"f52e\", \"M446.53 97.43C439.67 60.23 407.19 32 368 32c-39.23 0-71.72 28.29-78.54 65.54C126.75 112.96-.5 250.12 0 416.98.11 451.9 29.08 480 64 480h304c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-79.49l35.8-48.33c24.14-36.23 10.35-88.28-33.71-106.6-23.89-9.93-51.55-4.65-72.24 10.88l-32.76 24.59c-7.06 5.31-17.09 3.91-22.41-3.19-5.3-7.08-3.88-17.11 3.19-22.41l34.78-26.09c36.84-27.66 88.28-27.62 125.13 0 10.87 8.15 45.87 39.06 40.8 93.21L469.62 480H560c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-53.63l-98.52-104.68 154.44-86.65A58.16 58.16 0 0 0 576 189.94c0-21.4-11.72-40.95-30.48-51.23-40.56-22.22-98.99-41.28-98.99-41.28zM368 136c-13.26 0-24-10.75-24-24 0-13.26 10.74-24 24-24 13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm170.2 218.2C315.8 367.4 282.9 352 248 352s-67.8 15.4-90.2 42.2c-13.5 16.3-38.1-4.2-24.6-20.5C161.7 339.6 203.6 320 248 320s86.3 19.6 114.7 53.8c13.6 16.2-11 36.7-24.5 20.4z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm187.3 183.3c-31.2-9.6-59.4-15.3-75.3-15.3s-44.1 5.7-75.3 15.3c-11.5 3.5-22.5-6.3-20.5-18.1 7-40 60.1-61.2 95.8-61.2s88.8 21.3 95.8 61.2c2 11.9-9.1 21.6-20.5 18.1zM328 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"funnel-dollar\": [640, 512, [], \"f662\", \"M433.46 165.94l101.2-111.87C554.61 34.12 540.48 0 512.26 0H31.74C3.52 0-10.61 34.12 9.34 54.07L192 256v155.92c0 12.59 5.93 24.44 16 32l79.99 60c20.86 15.64 48.47 6.97 59.22-13.57C310.8 455.38 288 406.35 288 352c0-89.79 62.05-165.17 145.46-186.06zM480 192c-88.37 0-160 71.63-160 160s71.63 160 160 160 160-71.63 160-160-71.63-160-160-160zm16 239.88V448c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V256c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.04 44.44-42.67 45.07z\"],\n    \"futbol\": [512, 512, [], \"f1e3\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-48 0l-.003-.282-26.064 22.741-62.679-58.5 16.454-84.355 34.303 3.072c-24.889-34.216-60.004-60.089-100.709-73.141l13.651 31.939L256 139l-74.953-41.525 13.651-31.939c-40.631 13.028-75.78 38.87-100.709 73.141l34.565-3.073 16.192 84.355-62.678 58.5-26.064-22.741-.003.282c0 43.015 13.497 83.952 38.472 117.991l7.704-33.897 85.138 10.447 36.301 77.826-29.902 17.786c40.202 13.122 84.29 13.148 124.572 0l-29.902-17.786 36.301-77.826 85.138-10.447 7.704 33.897C442.503 339.952 456 299.015 456 256zm-248.102 69.571l-29.894-91.312L256 177.732l77.996 56.527-29.622 91.312h-96.476z\"],\n    \"gamepad\": [640, 512, [], \"f11b\", \"M480 96H160C71.6 96 0 167.6 0 256s71.6 160 160 160c44.8 0 85.2-18.4 114.2-48h91.5c29 29.6 69.5 48 114.2 48 88.4 0 160-71.6 160-160S568.4 96 480 96zM256 276c0 6.6-5.4 12-12 12h-52v52c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-52H76c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h52v-52c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h52c6.6 0 12 5.4 12 12v40zm184 68c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-80c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"gas-pump\": [512, 512, [], \"f52f\", \"M336 448H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm157.2-340.7l-81-81c-6.2-6.2-16.4-6.2-22.6 0l-11.3 11.3c-6.2 6.2-6.2 16.4 0 22.6L416 97.9V160c0 28.1 20.9 51.3 48 55.2V376c0 13.2-10.8 24-24 24s-24-10.8-24-24v-32c0-48.6-39.4-88-88-88h-8V64c0-35.3-28.7-64-64-64H96C60.7 0 32 28.7 32 64v352h288V304h8c22.1 0 40 17.9 40 40v27.8c0 37.7 27 72 64.5 75.9 43 4.3 79.5-29.5 79.5-71.7V152.6c0-17-6.8-33.3-18.8-45.3zM256 192H96V64h160v128z\"],\n    \"gavel\": [512, 512, [], \"f0e3\", \"M504.971 199.362l-22.627-22.627c-9.373-9.373-24.569-9.373-33.941 0l-5.657 5.657L329.608 69.255l5.657-5.657c9.373-9.373 9.373-24.569 0-33.941L312.638 7.029c-9.373-9.373-24.569-9.373-33.941 0L154.246 131.48c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l5.657-5.657 39.598 39.598-81.04 81.04-5.657-5.657c-12.497-12.497-32.758-12.497-45.255 0L9.373 412.118c-12.497 12.497-12.497 32.758 0 45.255l45.255 45.255c12.497 12.497 32.758 12.497 45.255 0l114.745-114.745c12.497-12.497 12.497-32.758 0-45.255l-5.657-5.657 81.04-81.04 39.598 39.598-5.657 5.657c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l124.451-124.451c9.372-9.372 9.372-24.568 0-33.941z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M485.5 0L576 160H474.9L405.7 0h79.8zm-128 0l69.2 160H149.3L218.5 0h139zm-267 0h79.8l-69.2 160H0L90.5 0zM0 192h100.7l123 251.7c1.5 3.1-2.7 5.9-5 3.3L0 192zm148.2 0h279.6l-137 318.2c-1 2.4-4.5 2.4-5.5 0L148.2 192zm204.1 251.7l123-251.7H576L357.3 446.9c-2.3 2.7-6.5-.1-5-3.2z\"],\n    \"genderless\": [288, 512, [], \"f22d\", \"M144 176c44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80 35.9-80 80-80m0-64C64.5 112 0 176.5 0 256s64.5 144 144 144 144-64.5 144-144-64.5-144-144-144z\"],\n    \"ghost\": [384, 512, [], \"f6e2\", \"M186.1.09C81.01 3.24 0 94.92 0 200.05v263.92c0 14.26 17.23 21.39 27.31 11.31l24.92-18.53c6.66-4.95 16-3.99 21.51 2.21l42.95 48.35c6.25 6.25 16.38 6.25 22.63 0l40.72-45.85c6.37-7.17 17.56-7.17 23.92 0l40.72 45.85c6.25 6.25 16.38 6.25 22.63 0l42.95-48.35c5.51-6.2 14.85-7.17 21.51-2.21l24.92 18.53c10.08 10.08 27.31 2.94 27.31-11.31V192C384 84 294.83-3.17 186.1.09zM128 224c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128 0c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"gift\": [512, 512, [], \"f06b\", \"M32 448c0 17.7 14.3 32 32 32h160V320H32v128zm256 32h160c17.7 0 32-14.3 32-32V320H288v160zm192-320h-42.1c6.2-12.1 10.1-25.5 10.1-40 0-48.5-39.5-88-88-88-41.6 0-68.5 21.3-103 68.3-34.5-47-61.4-68.3-103-68.3-48.5 0-88 39.5-88 88 0 14.5 3.8 27.9 10.1 40H32c-17.7 0-32 14.3-32 32v80c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-80c0-17.7-14.3-32-32-32zm-326.1 0c-22.1 0-40-17.9-40-40s17.9-40 40-40c19.9 0 34.6 3.3 86.1 80h-86.1zm206.1 0h-86.1c51.4-76.5 65.7-80 86.1-80 22.1 0 40 17.9 40 40s-17.9 40-40 40z\"],\n    \"gifts\": [640, 512, [], \"f79c\", \"M240.6 194.1c1.9-30.8 17.3-61.2 44-79.8C279.4 103.5 268.7 96 256 96h-29.4l30.7-22c7.2-5.1 8.9-15.1 3.7-22.3l-9.3-13c-5.1-7.2-15.1-8.9-22.3-3.7l-32 22.9 11.5-30.6c3.1-8.3-1.1-17.5-9.4-20.6l-15-5.6c-8.3-3.1-17.5 1.1-20.6 9.4l-19.9 53-19.9-53.1C121 2.1 111.8-2.1 103.5 1l-15 5.6C80.2 9.7 76 19 79.2 27.2l11.5 30.6L58.6 35c-7.2-5.1-17.2-3.5-22.3 3.7l-9.3 13c-5.1 7.2-3.5 17.2 3.7 22.3l30.7 22H32c-17.7 0-32 14.3-32 32v352c0 17.7 14.3 32 32 32h168.9c-5.5-9.5-8.9-20.3-8.9-32V256c0-29.9 20.8-55 48.6-61.9zM224 480c0 17.7 14.3 32 32 32h160V384H224v96zm224 32h160c17.7 0 32-14.3 32-32v-96H448v128zm160-288h-20.4c2.6-7.6 4.4-15.5 4.4-23.8 0-35.5-27-72.2-72.1-72.2-48.1 0-75.9 47.7-87.9 75.3-12.1-27.6-39.9-75.3-87.9-75.3-45.1 0-72.1 36.7-72.1 72.2 0 8.3 1.7 16.2 4.4 23.8H256c-17.7 0-32 14.3-32 32v96h192V224h15.3l.7-.2.7.2H448v128h192v-96c0-17.7-14.3-32-32-32zm-272 0c-2.7-1.4-5.1-3-7.2-4.8-7.3-6.4-8.8-13.8-8.8-19 0-9.7 6.4-24.2 24.1-24.2 18.7 0 35.6 27.4 44.5 48H336zm199.2-4.8c-2.1 1.8-4.5 3.4-7.2 4.8h-52.6c8.8-20.3 25.8-48 44.5-48 17.7 0 24.1 14.5 24.1 24.2 0 5.2-1.5 12.6-8.8 19z\"],\n    \"glass-cheers\": [640, 512, [], \"f79f\", \"M639.4 433.6c-8.4-20.4-31.8-30.1-52.2-21.6l-22.1 9.2-38.7-101.9c47.9-35 64.8-100.3 34.5-152.8L474.3 16c-8-13.9-25.1-19.7-40-13.6L320 49.8 205.7 2.4c-14.9-6.2-32-.3-40 13.6L79.1 166.5C48.9 219 65.7 284.3 113.6 319.2L74.9 421.1l-22.1-9.2c-20.4-8.5-43.7 1.2-52.2 21.6-1.7 4.1.2 8.8 4.3 10.5l162.3 67.4c4.1 1.7 8.7-.2 10.4-4.3 8.4-20.4-1.2-43.8-21.6-52.3l-22.1-9.2L173.3 342c4.4.5 8.8 1.3 13.1 1.3 51.7 0 99.4-33.1 113.4-85.3l20.2-75.4 20.2 75.4c14 52.2 61.7 85.3 113.4 85.3 4.3 0 8.7-.8 13.1-1.3L506 445.6l-22.1 9.2c-20.4 8.5-30.1 31.9-21.6 52.3 1.7 4.1 6.4 6 10.4 4.3L635.1 444c4-1.7 6-6.3 4.3-10.4zM275.9 162.1l-112.1-46.5 36.5-63.4 94.5 39.2-18.9 70.7zm88.2 0l-18.9-70.7 94.5-39.2 36.5 63.4-112.1 46.5z\"],\n    \"glass-martini\": [512, 512, [], \"f000\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6z\"],\n    \"glass-martini-alt\": [512, 512, [], \"f57b\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6zM443.77 48l-48 48H116.24l-48-48h375.53z\"],\n    \"glass-whiskey\": [512, 512, [], \"f7a0\", \"M480 32H32C12.5 32-2.4 49.2.3 68.5l56 356.5c4.5 31.5 31.5 54.9 63.4 54.9h273c31.8 0 58.9-23.4 63.4-54.9l55.6-356.5C514.4 49.2 499.5 32 480 32zm-37.4 64l-30 192h-313L69.4 96h373.2z\"],\n    \"glasses\": [576, 512, [], \"f530\", \"M574.1 280.37L528.75 98.66c-5.91-23.7-21.59-44.05-43-55.81-21.44-11.73-46.97-14.11-70.19-6.33l-15.25 5.08c-8.39 2.79-12.92 11.86-10.12 20.24l5.06 15.18c2.79 8.38 11.85 12.91 20.23 10.12l13.18-4.39c10.87-3.62 23-3.57 33.16 1.73 10.29 5.37 17.57 14.56 20.37 25.82l38.46 153.82c-22.19-6.81-49.79-12.46-81.2-12.46-34.77 0-73.98 7.02-114.85 26.74h-73.18c-40.87-19.74-80.08-26.75-114.86-26.75-31.42 0-59.02 5.65-81.21 12.46l38.46-153.83c2.79-11.25 10.09-20.45 20.38-25.81 10.16-5.3 22.28-5.35 33.15-1.73l13.17 4.39c8.38 2.79 17.44-1.74 20.23-10.12l5.06-15.18c2.8-8.38-1.73-17.45-10.12-20.24l-15.25-5.08c-23.22-7.78-48.75-5.41-70.19 6.33-21.41 11.77-37.09 32.11-43 55.8L1.9 280.37A64.218 64.218 0 0 0 0 295.86v70.25C0 429.01 51.58 480 115.2 480h37.12c60.28 0 110.37-45.94 114.88-105.37l2.93-38.63h35.75l2.93 38.63C313.31 434.06 363.4 480 423.68 480h37.12c63.62 0 115.2-50.99 115.2-113.88v-70.25c0-5.23-.64-10.43-1.9-15.5zm-370.72 89.42c-1.97 25.91-24.4 46.21-51.06 46.21H115.2C86.97 416 64 393.62 64 366.11v-37.54c18.12-6.49 43.42-12.92 72.58-12.92 23.86 0 47.26 4.33 69.93 12.92l-3.13 41.22zM512 366.12c0 27.51-22.97 49.88-51.2 49.88h-37.12c-26.67 0-49.1-20.3-51.06-46.21l-3.13-41.22c22.67-8.59 46.08-12.92 69.95-12.92 29.12 0 54.43 6.44 72.55 12.93v37.54z\"],\n    \"globe\": [496, 512, [], \"f0ac\", \"M336.5 160C322 70.7 287.8 8 248 8s-74 62.7-88.5 152h177zM152 256c0 22.2 1.2 43.5 3.3 64h185.3c2.1-20.5 3.3-41.8 3.3-64s-1.2-43.5-3.3-64H155.3c-2.1 20.5-3.3 41.8-3.3 64zm324.7-96c-28.6-67.9-86.5-120.4-158-141.6 24.4 33.8 41.2 84.7 50 141.6h108zM177.2 18.4C105.8 39.6 47.8 92.1 19.3 160h108c8.7-56.9 25.5-107.8 49.9-141.6zM487.4 192H372.7c2.1 21 3.3 42.5 3.3 64s-1.2 43-3.3 64h114.6c5.5-20.5 8.6-41.8 8.6-64s-3.1-43.5-8.5-64zM120 256c0-21.5 1.2-43 3.3-64H8.6C3.2 212.5 0 233.8 0 256s3.2 43.5 8.6 64h114.6c-2-21-3.2-42.5-3.2-64zm39.5 96c14.5 89.3 48.7 152 88.5 152s74-62.7 88.5-152h-177zm159.3 141.6c71.4-21.2 129.4-73.7 158-141.6h-108c-8.8 56.9-25.6 107.8-50 141.6zM19.3 352c28.6 67.9 86.5 120.4 158 141.6-24.4-33.8-41.2-84.7-50-141.6h-108z\"],\n    \"globe-africa\": [496, 512, [], \"f57c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm160 215.5v6.93c0 5.87-3.32 11.24-8.57 13.86l-15.39 7.7a15.485 15.485 0 0 1-15.53-.97l-18.21-12.14a15.52 15.52 0 0 0-13.5-1.81l-2.65.88c-9.7 3.23-13.66 14.79-7.99 23.3l13.24 19.86c2.87 4.31 7.71 6.9 12.89 6.9h8.21c8.56 0 15.5 6.94 15.5 15.5v11.34c0 3.35-1.09 6.62-3.1 9.3l-18.74 24.98c-1.42 1.9-2.39 4.1-2.83 6.43l-4.3 22.83c-.62 3.29-2.29 6.29-4.76 8.56a159.608 159.608 0 0 0-25 29.16l-13.03 19.55a27.756 27.756 0 0 1-23.09 12.36c-10.51 0-20.12-5.94-24.82-15.34a78.902 78.902 0 0 1-8.33-35.29V367.5c0-8.56-6.94-15.5-15.5-15.5h-25.88c-14.49 0-28.38-5.76-38.63-16a54.659 54.659 0 0 1-16-38.63v-14.06c0-17.19 8.1-33.38 21.85-43.7l27.58-20.69a54.663 54.663 0 0 1 32.78-10.93h.89c8.48 0 16.85 1.97 24.43 5.77l14.72 7.36c3.68 1.84 7.93 2.14 11.83.84l47.31-15.77c6.33-2.11 10.6-8.03 10.6-14.7 0-8.56-6.94-15.5-15.5-15.5h-10.09c-4.11 0-8.05-1.63-10.96-4.54l-6.92-6.92a15.493 15.493 0 0 0-10.96-4.54H199.5c-8.56 0-15.5-6.94-15.5-15.5v-4.4c0-7.11 4.84-13.31 11.74-15.04l14.45-3.61c3.74-.94 7-3.23 9.14-6.44l8.08-12.11c2.87-4.31 7.71-6.9 12.89-6.9h24.21c8.56 0 15.5-6.94 15.5-15.5v-21.7C359.23 71.63 422.86 131.02 441.93 208H423.5c-8.56 0-15.5 6.94-15.5 15.5z\"],\n    \"globe-americas\": [496, 512, [], \"f57d\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm82.29 357.6c-3.9 3.88-7.99 7.95-11.31 11.28-2.99 3-5.1 6.7-6.17 10.71-1.51 5.66-2.73 11.38-4.77 16.87l-17.39 46.85c-13.76 3-28 4.69-42.65 4.69v-27.38c1.69-12.62-7.64-36.26-22.63-51.25-6-6-9.37-14.14-9.37-22.63v-32.01c0-11.64-6.27-22.34-16.46-27.97-14.37-7.95-34.81-19.06-48.81-26.11-11.48-5.78-22.1-13.14-31.65-21.75l-.8-.72a114.792 114.792 0 0 1-18.06-20.74c-9.38-13.77-24.66-36.42-34.59-51.14 20.47-45.5 57.36-82.04 103.2-101.89l24.01 12.01C203.48 89.74 216 82.01 216 70.11v-11.3c7.99-1.29 16.12-2.11 24.39-2.42l28.3 28.3c6.25 6.25 6.25 16.38 0 22.63L264 112l-10.34 10.34c-3.12 3.12-3.12 8.19 0 11.31l4.69 4.69c3.12 3.12 3.12 8.19 0 11.31l-8 8a8.008 8.008 0 0 1-5.66 2.34h-8.99c-2.08 0-4.08.81-5.58 2.27l-9.92 9.65a8.008 8.008 0 0 0-1.58 9.31l15.59 31.19c2.66 5.32-1.21 11.58-7.15 11.58h-5.64c-1.93 0-3.79-.7-5.24-1.96l-9.28-8.06a16.017 16.017 0 0 0-15.55-3.1l-31.17 10.39a11.95 11.95 0 0 0-8.17 11.34c0 4.53 2.56 8.66 6.61 10.69l11.08 5.54c9.41 4.71 19.79 7.16 30.31 7.16s22.59 27.29 32 32h66.75c8.49 0 16.62 3.37 22.63 9.37l13.69 13.69a30.503 30.503 0 0 1 8.93 21.57 46.536 46.536 0 0 1-13.72 32.98zM417 274.25c-5.79-1.45-10.84-5-14.15-9.97l-17.98-26.97a23.97 23.97 0 0 1 0-26.62l19.59-29.38c2.32-3.47 5.5-6.29 9.24-8.15l12.98-6.49C440.2 193.59 448 223.87 448 256c0 8.67-.74 17.16-1.82 25.54L417 274.25z\"],\n    \"globe-asia\": [496, 512, [], \"f57e\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm-11.34 240.23c-2.89 4.82-8.1 7.77-13.72 7.77h-.31c-4.24 0-8.31 1.69-11.31 4.69l-5.66 5.66c-3.12 3.12-3.12 8.19 0 11.31l5.66 5.66c3 3 4.69 7.07 4.69 11.31V304c0 8.84-7.16 16-16 16h-6.11c-6.06 0-11.6-3.42-14.31-8.85l-22.62-45.23c-2.44-4.88-8.95-5.94-12.81-2.08l-19.47 19.46c-3 3-7.07 4.69-11.31 4.69H50.81C49.12 277.55 48 266.92 48 256c0-110.28 89.72-200 200-200 21.51 0 42.2 3.51 61.63 9.82l-50.16 38.53c-5.11 3.41-4.63 11.06.86 13.81l10.83 5.41c5.42 2.71 8.84 8.25 8.84 14.31V216c0 4.42-3.58 8-8 8h-3.06c-3.03 0-5.8-1.71-7.15-4.42-1.56-3.12-5.96-3.29-7.76-.3l-17.37 28.95zM408 358.43c0 4.24-1.69 8.31-4.69 11.31l-9.57 9.57c-3 3-7.07 4.69-11.31 4.69h-15.16c-4.24 0-8.31-1.69-11.31-4.69l-13.01-13.01a26.767 26.767 0 0 0-25.42-7.04l-21.27 5.32c-1.27.32-2.57.48-3.88.48h-10.34c-4.24 0-8.31-1.69-11.31-4.69l-11.91-11.91a8.008 8.008 0 0 1-2.34-5.66v-10.2c0-3.27 1.99-6.21 5.03-7.43l39.34-15.74c1.98-.79 3.86-1.82 5.59-3.05l23.71-16.89a7.978 7.978 0 0 1 4.64-1.48h12.09c3.23 0 6.15 1.94 7.39 4.93l5.35 12.85a4 4 0 0 0 3.69 2.46h3.8c1.78 0 3.35-1.18 3.84-2.88l4.2-14.47c.5-1.71 2.06-2.88 3.84-2.88h6.06c2.21 0 4 1.79 4 4v12.93c0 2.12.84 4.16 2.34 5.66l11.91 11.91c3 3 4.69 7.07 4.69 11.31v24.6z\"],\n    \"globe-europe\": [496, 512, [], \"f7a2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm200 248c0 22.5-3.9 44.2-10.8 64.4h-20.3c-4.3 0-8.4-1.7-11.4-4.8l-32-32.6c-4.5-4.6-4.5-12.1.1-16.7l12.5-12.5v-8.7c0-3-1.2-5.9-3.3-8l-9.4-9.4c-2.1-2.1-5-3.3-8-3.3h-16c-6.2 0-11.3-5.1-11.3-11.3 0-3 1.2-5.9 3.3-8l9.4-9.4c2.1-2.1 5-3.3 8-3.3h32c6.2 0 11.3-5.1 11.3-11.3v-9.4c0-6.2-5.1-11.3-11.3-11.3h-36.7c-8.8 0-16 7.2-16 16v4.5c0 6.9-4.4 13-10.9 15.2l-31.6 10.5c-3.3 1.1-5.5 4.1-5.5 7.6v2.2c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8s-3.6-8-8-8H247c-3 0-5.8 1.7-7.2 4.4l-9.4 18.7c-2.7 5.4-8.2 8.8-14.3 8.8H194c-8.8 0-16-7.2-16-16V199c0-4.2 1.7-8.3 4.7-11.3l20.1-20.1c4.6-4.6 7.2-10.9 7.2-17.5 0-3.4 2.2-6.5 5.5-7.6l40-13.3c1.7-.6 3.2-1.5 4.4-2.7l26.8-26.8c2.1-2.1 3.3-5 3.3-8 0-6.2-5.1-11.3-11.3-11.3H258l-16 16v8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-20c0-2.5 1.2-4.9 3.2-6.4l28.9-21.7c1.9-.1 3.8-.3 5.7-.3C358.3 56 448 145.7 448 256zM130.1 149.1c0-3 1.2-5.9 3.3-8l25.4-25.4c2.1-2.1 5-3.3 8-3.3 6.2 0 11.3 5.1 11.3 11.3v16c0 3-1.2 5.9-3.3 8l-9.4 9.4c-2.1 2.1-5 3.3-8 3.3h-16c-6.2 0-11.3-5.1-11.3-11.3zm128 306.4v-7.1c0-8.8-7.2-16-16-16h-20.2c-10.8 0-26.7-5.3-35.4-11.8l-22.2-16.7c-11.5-8.6-18.2-22.1-18.2-36.4v-23.9c0-16 8.4-30.8 22.1-39l42.9-25.7c7.1-4.2 15.2-6.5 23.4-6.5h31.2c10.9 0 21.4 3.9 29.6 10.9l43.2 37.1h18.3c8.5 0 16.6 3.4 22.6 9.4l17.3 17.3c3.4 3.4 8.1 5.3 12.9 5.3H423c-32.4 58.9-93.8 99.5-164.9 103.1z\"],\n    \"golf-ball\": [416, 512, [], \"f450\", \"M96 416h224c0 17.7-14.3 32-32 32h-16c-17.7 0-32 14.3-32 32v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-20c0-17.7-14.3-32-32-32h-16c-17.7 0-32-14.3-32-32zm320-208c0 74.2-39 139.2-97.5 176h-221C39 347.2 0 282.2 0 208 0 93.1 93.1 0 208 0s208 93.1 208 208zm-180.1 43.9c18.3 0 33.1-14.8 33.1-33.1 0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1zm49.1 46.9c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1zm64-64c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1z\"],\n    \"gopuram\": [512, 512, [], \"f664\", \"M496 352h-16V240c0-8.8-7.2-16-16-16h-16v-80c0-8.8-7.2-16-16-16h-16V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16S96 7.2 96 16v112H80c-8.8 0-16 7.2-16 16v80H48c-8.8 0-16 7.2-16 16v112H16c-8.8 0-16 7.2-16 16v128c0 8.8 7.2 16 16 16h80V352h32V224h32v-96h32v96h-32v128h-32v160h80v-80c0-8.8 7.2-16 16-16h64c8.8 0 16 7.2 16 16v80h80V352h-32V224h-32v-96h32v96h32v128h32v160h80c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zM232 176c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v48h-48zm56 176h-64v-64c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16z\"],\n    \"graduation-cap\": [640, 512, [], \"f19d\", \"M622.34 153.2L343.4 67.5c-15.2-4.67-31.6-4.67-46.79 0L17.66 153.2c-23.54 7.23-23.54 38.36 0 45.59l48.63 14.94c-10.67 13.19-17.23 29.28-17.88 46.9C38.78 266.15 32 276.11 32 288c0 10.78 5.68 19.85 13.86 25.65L20.33 428.53C18.11 438.52 25.71 448 35.94 448h56.11c10.24 0 17.84-9.48 15.62-19.47L82.14 313.65C90.32 307.85 96 298.78 96 288c0-11.57-6.47-21.25-15.66-26.87.76-15.02 8.44-28.3 20.69-36.72L296.6 284.5c9.06 2.78 26.44 6.25 46.79 0l278.95-85.7c23.55-7.24 23.55-38.36 0-45.6zM352.79 315.09c-28.53 8.76-52.84 3.92-65.59 0l-145.02-44.55L128 384c0 35.35 85.96 64 192 64s192-28.65 192-64l-14.18-113.47-145.03 44.56z\"],\n    \"greater-than\": [384, 512, [], \"f531\", \"M365.52 209.85L59.22 67.01c-16.06-7.49-35.15-.54-42.64 15.52L3.01 111.61c-7.49 16.06-.54 35.15 15.52 42.64L236.96 256.1 18.49 357.99C2.47 365.46-4.46 384.5 3.01 400.52l13.52 29C24 445.54 43.04 452.47 59.06 445l306.47-142.91a32.003 32.003 0 0 0 18.48-29v-34.23c-.01-12.45-7.21-23.76-18.49-29.01z\"],\n    \"greater-than-equal\": [448, 512, [], \"f532\", \"M55.22 107.69l175.56 68.09-175.44 68.05c-18.39 6.03-27.88 24.39-21.2 41l12.09 30.08c6.68 16.61 26.99 25.19 45.38 19.15L393.02 214.2c13.77-4.52 22.98-16.61 22.98-30.17v-15.96c0-13.56-9.21-25.65-22.98-30.17L91.3 17.92c-18.29-6-38.51 2.53-45.15 19.06L34.12 66.9c-6.64 16.53 2.81 34.79 21.1 40.79zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM144 400h-8c-17.7 0-32-14.3-32-32v-8h40v40zm0-56h-40v-8c0-17.7 14.3-32 32-32h8v40zm-8-136c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm72 192h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm-8-104c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64 128c0 17.7-14.3 32-32 32h-8v-40h40v8zm0-24h-40v-40h8c17.7 0 32 14.3 32 32v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm80 256c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm63.7 128.7c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zm-160 0c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 144c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam-sweat\": [504, 512, [], \"f583\", \"M456 128c26.5 0 48-21 48-47 0-20-28.5-60.4-41.6-77.8-3.2-4.3-9.6-4.3-12.8 0C436.5 20.6 408 61 408 81c0 26 21.5 47 48 47zm0 32c-44.1 0-80-35.4-80-79 0-4.4.3-14.2 8.1-32.2C345 23.1 298.3 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-35.1-7.4-68.4-20.5-98.6-6.3 1.5-12.7 2.6-19.5 2.6zm-128-8c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM90.4 183.6c6.7-17.6 26.7-26.7 44.9-21.9l7.1 1.9 2-7.1c5-18.1 22.8-30.9 41.5-27.9 21.4 3.4 34.4 24.2 28.8 44.5L195.3 243c-1.2 4.5-5.9 7.2-10.5 6l-70.2-18.2c-20.4-5.4-31.9-27-24.2-47.2zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm133.4-201.3l-70.2 18.2c-4.5 1.2-9.2-1.5-10.5-6L281.3 173c-5.6-20.3 7.4-41.1 28.8-44.5 18.6-3 36.4 9.8 41.5 27.9l2 7.1 7.1-1.9c18.2-4.7 38.2 4.3 44.9 21.9 7.7 20.3-3.8 41.9-24.2 47.2z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M409.6 111.9c22.6-3.2 73.5-12 88.3-26.8 19.2-19.2 18.9-50.6-.7-70.2S446-5 426.9 14.2c-14.8 14.8-23.5 65.7-26.8 88.3-.8 5.5 3.9 10.2 9.5 9.4zM102.4 400.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm311.7-256.5c-33 3.9-48.6-25.1-45.7-45.7 3.4-24 7.4-42.1 11.5-56.5C285.1-13.4 161.8-.5 80.6 80.6-.5 161.7-13.4 285 41.4 379.9c14.4-4.1 32.4-8 56.5-11.5 33.2-3.9 48.6 25.2 45.7 45.7-3.4 24-7.4 42.1-11.5 56.5 94.8 54.8 218.1 41.9 299.3-39.2s94-204.4 39.2-299.3c-14.4 4.1-32.5 8-56.5 11.5zM255.7 106c3.3-13.2 22.4-11.5 23.6 1.8l4.8 52.3 52.3 4.8c13.4 1.2 14.9 20.3 1.8 23.6l-90.5 22.6c-8.9 2.2-16.7-5.9-14.5-14.5l22.5-90.6zm-90.9 230.3L160 284l-52.3-4.8c-13.4-1.2-14.9-20.3-1.8-23.6l90.5-22.6c8.8-2.2 16.7 5.8 14.5 14.5L188.3 338c-3.1 13.2-22.2 11.7-23.5-1.7zm215.7 44.2c-29.3 29.3-75.7 50.4-116.7 50.4-18.9 0-36.6-4.5-51-14.7-9.8-6.9-8.7-21.8 2-27.2 28.3-14.6 63.9-42.4 97.8-76.3s61.7-69.6 76.3-97.8c5.4-10.5 20.2-11.9 27.3-2 32.3 45.3 7.1 124.7-35.7 167.6z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM94.6 168.9l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.2 1 8.9 8.6 4.3 13.2l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L152 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.6-4.7-1.9-12.3 4.3-13.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm157.7-249.9l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L344 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.5-4.6-1.9-12.2 4.3-13.2l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.3.9 9 8.5 4.4 13.1z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M102.4 256.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm523.4 26.8c-14.8-14.8-65.7-23.5-88.3-26.8-5.5-.8-10.3 3.9-9.5 9.5 3.2 22.6 12 73.5 26.8 88.3 19.2 19.2 50.6 18.9 70.2-.7s20-51.2.8-70.3zm-129.4-12.8c-3.8-26.6 19.1-49.5 45.7-45.7 8.9 1.3 16.8 2.7 24.3 4.1C552.7 104.5 447.7 8 320 8S87.3 104.5 73.6 228.5c7.5-1.4 15.4-2.8 24.3-4.1 33.2-3.9 48.6 25.3 45.7 45.7-11.8 82.3-29.9 100.4-35.8 106.4-.9.9-2 1.6-3 2.5 42.7 74.6 123 125 215.2 125s172.5-50.4 215.2-125.1c-1-.9-2.1-1.5-3-2.5-5.9-5.9-24-24-35.8-106.3zM400 152c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.7 9.2-21.6 20.7-17.9C227.1 330.5 272 336 320 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-34.9 134.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M293.1 374.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-33.8 210.3l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.7 4.7 7.7 15.9 0 20.6zm163 30c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.8-4.7-7.8-15.9 0-20.6l80-48c11.7-6.9 23.9 7.7 15.4 18L343.6 208l33.6 40.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M344 184c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-56 225l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L112 233c-8.5 7.4-21.6.3-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c1.6 11.1-11.6 18.2-20 10.8zm152 39c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm-50.9 102.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm168 25l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.6 11-11.5 18.2-20 10.8zm-243.1 87.8C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6 20.7 17.9-9.2 55-83.2 93.3-143.8 93.3s-134.5-38.3-143.8-93.3c-2-11.9 9.3-21.6 20.7-17.9z\"],\n    \"grip-horizontal\": [448, 512, [], \"f58d\", \"M96 288H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM96 96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"grip-lines\": [512, 512, [], \"f7a4\", \"M496 288H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-128H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"grip-lines-vertical\": [256, 512, [], \"f7a5\", \"M96 496V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16zm128 0V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16z\"],\n    \"grip-vertical\": [320, 512, [], \"f58e\", \"M96 32H32C14.33 32 0 46.33 0 64v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM288 32h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"guitar\": [512, 512, [], \"f7a6\", \"M502.6 54.6L457.4 9.4c-12.5-12.5-32.8-12.5-45.3 0l-67.9 67.9c-12.5 12.5-12.5 32.8 0 45.3L290 176.7c-45.4-29-100.4-28.9-133.5 4.2-9.7 9.7-16.4 21.2-20.5 33.9-6.1 18.8-23.5 33.1-42.7 34.9-24 2.3-46.3 11.6-63.4 28.8C-16.3 324.6-8 407.6 48.2 463.8c56.2 56.2 139.2 64.4 185.3 18.3 17.2-17.1 26.5-39.4 28.8-63.5 1.8-19.1 16.1-36.6 34.9-42.7 12.7-4.1 24.2-10.8 33.9-20.5 33.1-33.1 33.1-88.1 4.2-133.5l54.2-54.2c12.5 12.5 32.8 12.5 45.3 0l67.9-67.9c12.4-12.4 12.4-32.7-.1-45.2zM208 352c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"h-square\": [448, 512, [], \"f0fd\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-112 48h-32c-8.837 0-16 7.163-16 16v80H160v-80c0-8.837-7.163-16-16-16h-32c-8.837 0-16 7.163-16 16v224c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16v-80h128v80c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16V144c0-8.837-7.163-16-16-16z\"],\n    \"hamburger\": [512, 512, [], \"f805\", \"M464 256H48a48 48 0 0 0 0 96h416a48 48 0 0 0 0-96zm16 128H32a16 16 0 0 0-16 16v16a64 64 0 0 0 64 64h352a64 64 0 0 0 64-64v-16a16 16 0 0 0-16-16zM58.64 224h394.72c34.57 0 54.62-43.9 34.82-75.88C448 83.2 359.55 32.1 256 32c-103.54.1-192 51.2-232.18 116.11C4 180.09 24.07 224 58.64 224zM384 112a16 16 0 1 1-16 16 16 16 0 0 1 16-16zM256 80a16 16 0 1 1-16 16 16 16 0 0 1 16-16zm-128 32a16 16 0 1 1-16 16 16 16 0 0 1 16-16z\"],\n    \"hammer\": [576, 512, [], \"f6e3\", \"M571.31 193.94l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31-28.9-28.9c5.63-21.31.36-44.9-16.35-61.61l-45.25-45.25c-62.48-62.48-163.79-62.48-226.28 0l90.51 45.25v18.75c0 16.97 6.74 33.25 18.75 45.25l49.14 49.14c16.71 16.71 40.3 21.98 61.61 16.35l28.9 28.9-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l90.51-90.51c6.23-6.24 6.23-16.37-.02-22.62zm-286.72-15.2c-3.7-3.7-6.84-7.79-9.85-11.95L19.64 404.96c-25.57 23.88-26.26 64.19-1.53 88.93s65.05 24.05 88.93-1.53l238.13-255.07c-3.96-2.91-7.9-5.87-11.44-9.41l-49.14-49.14z\"],\n    \"hamsa\": [512, 512, [], \"f665\", \"M509.34 307.25C504.28 295.56 492.75 288 480 288h-64V80c0-22-18-40-40-40s-40 18-40 40v134c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V40c0-22-18-40-40-40s-40 18-40 40v174c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V80c0-22-18-40-40-40S96 58 96 80v208H32c-12.75 0-24.28 7.56-29.34 19.25a31.966 31.966 0 0 0 5.94 34.58l102.69 110.03C146.97 490.08 199.69 512 256 512s109.03-21.92 144.72-60.14L503.4 341.83a31.966 31.966 0 0 0 5.94-34.58zM256 416c-53.02 0-96-64-96-64s42.98-64 96-64 96 64 96 64-42.98 64-96 64zm0-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"hand-holding\": [576, 512, [], \"f4bd\", \"M565.3 328.1c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-heart\": [576, 512, [], \"f4be\", \"M275.3 250.5c7 7.4 18.4 7.4 25.5 0l108.9-114.2c31.6-33.2 29.8-88.2-5.6-118.8-30.8-26.7-76.7-21.9-104.9 7.7L288 36.9l-11.1-11.6C248.7-4.4 202.8-9.2 172 17.5c-35.3 30.6-37.2 85.6-5.6 118.8l108.9 114.2zm290 77.6c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-usd\": [544, 512, [], \"f4c0\", \"M257.6 144.3l50 14.3c3.6 1 6.1 4.4 6.1 8.1 0 4.6-3.8 8.4-8.4 8.4h-32.8c-3.6 0-7.1-.8-10.3-2.2-4.8-2.2-10.4-1.7-14.1 2l-17.5 17.5c-5.3 5.3-4.7 14.3 1.5 18.4 9.5 6.3 20.3 10.1 31.8 11.5V240c0 8.8 7.2 16 16 16h16c8.8 0 16-7.2 16-16v-17.6c30.3-3.6 53.3-31 49.3-63-2.9-23-20.7-41.3-42.9-47.7l-50-14.3c-3.6-1-6.1-4.4-6.1-8.1 0-4.6 3.8-8.4 8.4-8.4h32.8c3.6 0 7.1.8 10.3 2.2 4.8 2.2 10.4 1.7 14.1-2l17.5-17.5c5.3-5.3 4.7-14.3-1.5-18.4-9.5-6.3-20.3-10.1-31.8-11.5V16c0-8.8-7.2-16-16-16h-16c-8.8 0-16 7.2-16 16v17.6c-30.3 3.6-53.3 31-49.3 63 2.9 23 20.7 41.3 42.9 47.7zm276.3 183.8c-11.2-10.7-28.5-10-40.3 0L406.4 402c-10.7 9.1-24 14-37.8 14H256.9c-8.3 0-15.1-7.2-15.1-16s6.8-16 15.1-16h73.9c15.1 0 29-10.9 31.4-26.6 3.1-20-11.5-37.4-29.8-37.4H181.3c-25.5 0-50.2 9.3-69.9 26.3L67.5 384H15.1C6.8 384 0 391.2 0 400v96c0 8.8 6.8 16 15.1 16H352c13.7 0 27-4.9 37.8-14l142.8-121c14.4-12.1 15.5-35.3 1.3-48.9z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M384 480h192V363.778a95.998 95.998 0 0 0-14.833-51.263L398.127 54.368A48 48 0 0 0 357.544 32H24C10.745 32 0 42.745 0 56v16c0 30.928 25.072 56 56 56h229.981c12.844 0 21.556 13.067 16.615 24.923l-21.41 51.385A32 32 0 0 1 251.648 224H128c-35.346 0-64 28.654-64 64v8c0 13.255 10.745 24 24 24h147.406a47.995 47.995 0 0 1 25.692 7.455l111.748 70.811A24.001 24.001 0 0 1 384 418.539V480z\"],\n    \"hand-middle-finger\": [512, 512, [], \"f806\", \"M479.93 317.12a37.33 37.33 0 0 0-28.28-36.19L416 272v-49.59c0-11.44-9.69-21.29-23.15-23.54l-38.4-6.4C336.63 189.5 320 200.86 320 216v32a8 8 0 0 1-16 0V50c0-26.28-20.25-49.2-46.52-50A48 48 0 0 0 208 48v200a8 8 0 0 1-16 0v-32c0-15.15-16.63-26.51-34.45-23.54l-30.68 5.12c-18 3-30.87 16.12-30.87 31.38V376a8 8 0 0 1-16 0v-76l-27.36 15A37.34 37.34 0 0 0 32 348.4v73.47a37.31 37.31 0 0 0 10.93 26.39l30.93 30.93A112 112 0 0 0 153.05 512h215A112 112 0 0 0 480 400z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M408.781 128.007C386.356 127.578 368 146.36 368 168.79V256h-8V79.79c0-22.43-18.356-41.212-40.781-40.783C297.488 39.423 280 57.169 280 79v177h-8V40.79C272 18.36 253.644-.422 231.219.007 209.488.423 192 18.169 192 40v216h-8V80.79c0-22.43-18.356-41.212-40.781-40.783C121.488 40.423 104 58.169 104 80v235.992l-31.648-43.519c-12.993-17.866-38.009-21.817-55.877-8.823-17.865 12.994-21.815 38.01-8.822 55.877l125.601 172.705A48 48 0 0 0 172.073 512h197.59c22.274 0 41.622-15.324 46.724-37.006l26.508-112.66a192.011 192.011 0 0 0 5.104-43.975V168c.001-21.831-17.487-39.577-39.218-39.993z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M408 216c-22.092 0-40 17.909-40 40h-8v-32c0-22.091-17.908-40-40-40s-40 17.909-40 40v32h-8V48c0-26.51-21.49-48-48-48s-48 21.49-48 48v208h-13.572L92.688 78.449C82.994 53.774 55.134 41.63 30.461 51.324 5.787 61.017-6.356 88.877 3.337 113.551l74.765 190.342-31.09 24.872c-15.381 12.306-19.515 33.978-9.741 51.081l64 112A39.998 39.998 0 0 0 136 512h240c18.562 0 34.686-12.77 38.937-30.838l32-136A39.97 39.97 0 0 0 448 336v-80c0-22.091-17.908-40-40-40z\"],\n    \"hand-point-down\": [384, 512, [], \"f0a7\", \"M91.826 467.2V317.966c-8.248 5.841-16.558 10.57-24.918 14.153C35.098 345.752-.014 322.222 0 288c.008-18.616 10.897-32.203 29.092-40 28.286-12.122 64.329-78.648 77.323-107.534 7.956-17.857 25.479-28.453 43.845-28.464l.001-.002h171.526c11.812 0 21.897 8.596 23.703 20.269 7.25 46.837 38.483 61.76 38.315 123.731-.007 2.724.195 13.254.195 16 0 50.654-22.122 81.574-71.263 72.6-9.297 18.597-39.486 30.738-62.315 16.45-21.177 24.645-53.896 22.639-70.944 6.299V467.2c0 24.15-20.201 44.8-43.826 44.8-23.283 0-43.826-21.35-43.826-44.8zM112 72V24c0-13.255 10.745-24 24-24h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24zm212-24c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M44.8 155.826h149.234c-5.841-8.248-10.57-16.558-14.153-24.918C166.248 99.098 189.778 63.986 224 64c18.616.008 32.203 10.897 40 29.092 12.122 28.286 78.648 64.329 107.534 77.323 17.857 7.956 28.453 25.479 28.464 43.845l.002.001v171.526c0 11.812-8.596 21.897-20.269 23.703-46.837 7.25-61.76 38.483-123.731 38.315-2.724-.007-13.254.195-16 .195-50.654 0-81.574-22.122-72.6-71.263-18.597-9.297-30.738-39.486-16.45-62.315-24.645-21.177-22.639-53.896-6.299-70.944H44.8c-24.15 0-44.8-20.201-44.8-43.826 0-23.283 21.35-43.826 44.8-43.826zM440 176h48c13.255 0 24 10.745 24 24v192c0 13.255-10.745 24-24 24h-48c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24zm24 212c11.046 0 20-8.954 20-20s-8.954-20-20-20-20 8.954-20 20 8.954 20 20 20z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M512 199.652c0 23.625-20.65 43.826-44.8 43.826h-99.851c16.34 17.048 18.346 49.766-6.299 70.944 14.288 22.829 2.147 53.017-16.45 62.315C353.574 425.878 322.654 448 272 448c-2.746 0-13.276-.203-16-.195-61.971.168-76.894-31.065-123.731-38.315C120.596 407.683 112 397.599 112 385.786V214.261l.002-.001c.011-18.366 10.607-35.889 28.464-43.845 28.886-12.994 95.413-49.038 107.534-77.323 7.797-18.194 21.384-29.084 40-29.092 34.222-.014 57.752 35.098 44.119 66.908-3.583 8.359-8.312 16.67-14.153 24.918H467.2c23.45 0 44.8 20.543 44.8 43.826zM96 200v192c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24h48c13.255 0 24 10.745 24 24zM68 368c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-up\": [384, 512, [], \"f0a6\", \"M135.652 0c23.625 0 43.826 20.65 43.826 44.8v99.851c17.048-16.34 49.766-18.346 70.944 6.299 22.829-14.288 53.017-2.147 62.315 16.45C361.878 158.426 384 189.346 384 240c0 2.746-.203 13.276-.195 16 .168 61.971-31.065 76.894-38.315 123.731C343.683 391.404 333.599 400 321.786 400H150.261l-.001-.002c-18.366-.011-35.889-10.607-43.845-28.464C93.421 342.648 57.377 276.122 29.092 264 10.897 256.203.008 242.616 0 224c-.014-34.222 35.098-57.752 66.908-44.119 8.359 3.583 16.67 8.312 24.918 14.153V44.8c0-23.45 20.543-44.8 43.826-44.8zM136 416h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24v-48c0-13.255 10.745-24 24-24zm168 28c-11.046 0-20 8.954-20 20s8.954 20 20 20 20-8.954 20-20-8.954-20-20-20z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M448 240v96c0 3.084-.356 6.159-1.063 9.162l-32 136C410.686 499.23 394.562 512 376 512H168a40.004 40.004 0 0 1-32.35-16.473l-127.997-176c-12.993-17.866-9.043-42.883 8.822-55.876 17.867-12.994 42.884-9.043 55.877 8.823L104 315.992V40c0-22.091 17.908-40 40-40s40 17.909 40 40v200h8v-40c0-22.091 17.908-40 40-40s40 17.909 40 40v40h8v-24c0-22.091 17.908-40 40-40s40 17.909 40 40v24h8c0-22.091 17.908-40 40-40s40 17.909 40 40zm-256 80h-8v96h8v-96zm88 0h-8v96h8v-96zm88 0h-8v96h8v-96z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M464.8 80c-26.9-.4-48.8 21.2-48.8 48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v32h-8V80.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v136l-8-7.1v-48.1c0-26.3-20.9-48.3-47.2-48.8C21.9 127.6 0 149.2 0 176v66.4c0 27.4 11.7 53.5 32.2 71.8l111.7 99.3c10.2 9.1 16.1 22.2 16.1 35.9v6.7c0 13.3 10.7 24 24 24h240c13.3 0 24-10.7 24-24v-2.9c0-12.8 2.6-25.5 7.5-37.3l49-116.3c5-11.8 7.5-24.5 7.5-37.3V128.8c0-26.3-20.9-48.4-47.2-48.8z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M216 440c0-22.092 17.909-40 40-40v-8h-32c-22.091 0-40-17.908-40-40s17.909-40 40-40h32v-8H48c-26.51 0-48-21.49-48-48s21.49-48 48-48h208v-13.572l-177.551-69.74c-24.674-9.694-36.818-37.555-27.125-62.228 9.693-24.674 37.554-36.817 62.228-27.124l190.342 74.765 24.872-31.09c12.306-15.381 33.978-19.515 51.081-9.741l112 64A40.002 40.002 0 0 1 512 168v240c0 18.562-12.77 34.686-30.838 38.937l-136 32A39.982 39.982 0 0 1 336 480h-80c-22.091 0-40-17.908-40-40z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M481.3 97.1c-21.5-5.1-43.1 8.2-48.2 29.6L402.3 256h-11.1l43.6-174.3c5.4-21.4-7.7-43.1-29.1-48.5s-43.1 7.7-48.5 29.1L308.8 256h-15.1L242 31.1c-5-21.6-26.4-35-48-30.1-21.5 4.9-35 26.4-30 47.9l47.6 207h-9.8L167 103.1c-4.9-21.5-26.3-35-47.9-30.1-21.5 4.9-35 26.3-30.1 47.9l39 171.6v79.4l-60.6-57c-16.1-15.1-41.4-14.4-56.5 1.7s-14.4 41.4 1.7 56.5L146.3 499c8.9 8.4 20.7 13 32.9 13h216.7c21.3 0 40-14 46-34.4l26.2-88.3c2.6-8.9 4-18 4-27.3v-42c0-7.5.9-15 2.6-22.2L511 145.3c5-21.5-8.3-43.1-29.7-48.2z\"],\n    \"hands\": [640, 512, [], \"f4c2\", \"M204.8 230.4c-10.6-14.1-30.7-17-44.8-6.4-14.1 10.6-17 30.7-6.4 44.8l38.1 50.8c4.8 6.4 4.1 15.3-1.5 20.9l-12.8 12.8c-6.7 6.7-17.6 6.2-23.6-1.1L64 244.4V96c0-17.7-14.3-32-32-32S0 78.3 0 96v218.4c0 10.9 3.7 21.5 10.5 30l104.1 134.3c5 6.5 8.4 13.9 10.4 21.7 1.8 6.9 8.1 11.6 15.3 11.6H272c8.8 0 16-7.2 16-16V384c0-27.7-9-54.6-25.6-76.8l-57.6-76.8zM608 64c-17.7 0-32 14.3-32 32v148.4l-89.8 107.8c-6 7.2-17 7.7-23.6 1.1l-12.8-12.8c-5.6-5.6-6.3-14.5-1.5-20.9l38.1-50.8c10.6-14.1 7.7-34.2-6.4-44.8-14.1-10.6-34.2-7.7-44.8 6.4l-57.6 76.8C361 329.4 352 356.3 352 384v112c0 8.8 7.2 16 16 16h131.7c7.1 0 13.5-4.7 15.3-11.6 2-7.8 5.4-15.2 10.4-21.7l104.1-134.3c6.8-8.5 10.5-19.1 10.5-30V96c0-17.7-14.3-32-32-32z\"],\n    \"hands-helping\": [640, 512, [], \"f4c4\", \"M488 192H336v56c0 39.7-32.3 72-72 72s-72-32.3-72-72V126.4l-64.9 39C107.8 176.9 96 197.8 96 220.2v47.3l-80 46.2C.7 322.5-4.6 342.1 4.3 357.4l80 138.6c8.8 15.3 28.4 20.5 43.7 11.7L231.4 448H368c35.3 0 64-28.7 64-64h16c17.7 0 32-14.3 32-32v-64h8c13.3 0 24-10.7 24-24v-48c0-13.3-10.7-24-24-24zm147.7-37.4L555.7 16C546.9.7 527.3-4.5 512 4.3L408.6 64H306.4c-12 0-23.7 3.4-33.9 9.7L239 94.6c-9.4 5.8-15 16.1-15 27.1V248c0 22.1 17.9 40 40 40s40-17.9 40-40v-88h184c30.9 0 56 25.1 56 56v28.5l80-46.2c15.3-8.9 20.5-28.4 11.7-43.7z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M434.7 64h-85.9c-8 0-15.7 3-21.6 8.4l-98.3 90c-.1.1-.2.3-.3.4-16.6 15.6-16.3 40.5-2.1 56 12.7 13.9 39.4 17.6 56.1 2.7.1-.1.3-.1.4-.2l79.9-73.2c6.5-5.9 16.7-5.5 22.6 1 6 6.5 5.5 16.6-1 22.6l-26.1 23.9L504 313.8c2.9 2.4 5.5 5 7.9 7.7V128l-54.6-54.6c-5.9-6-14.1-9.4-22.6-9.4zM544 128.2v223.9c0 17.7 14.3 32 32 32h64V128.2h-96zm48 223.9c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM0 384h64c17.7 0 32-14.3 32-32V128.2H0V384zm48-63.9c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16c0-8.9 7.2-16 16-16zm435.9 18.6L334.6 217.5l-30 27.5c-29.7 27.1-75.2 24.5-101.7-4.4-26.9-29.4-24.8-74.9 4.4-101.7L289.1 64h-83.8c-8.5 0-16.6 3.4-22.6 9.4L128 128v223.9h18.3l90.5 81.9c27.4 22.3 67.7 18.1 90-9.3l.2-.2 17.9 15.5c15.9 13 39.4 10.5 52.3-5.4l31.4-38.6 5.4 4.4c13.7 11.1 33.9 9.1 45-4.7l9.5-11.7c11.2-13.8 9.1-33.9-4.6-45.1z\"],\n    \"hanukiah\": [640, 512, [], \"f6e6\", \"M232 160c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm-64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm224 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm88 8c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v120h32V168zm-440-8c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm520 0h-32c-8.84 0-16 7.16-16 16v112c0 17.67-14.33 32-32 32H352V128c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v192H96c-17.67 0-32-14.33-32-32V176c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v112c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V176c0-8.84-7.16-16-16-16zm-16-32c13.25 0 24-11.94 24-26.67S608 48 608 48s-24 38.61-24 53.33S594.75 128 608 128zm-576 0c13.25 0 24-11.94 24-26.67S32 48 32 48 8 86.61 8 101.33 18.75 128 32 128zm288-48c13.25 0 24-11.94 24-26.67S320 0 320 0s-24 38.61-24 53.33S306.75 80 320 80zm-208 48c13.25 0 24-11.94 24-26.67S112 48 112 48s-24 38.61-24 53.33S98.75 128 112 128zm64 0c13.25 0 24-11.94 24-26.67S176 48 176 48s-24 38.61-24 53.33S162.75 128 176 128zm64 0c13.25 0 24-11.94 24-26.67S240 48 240 48s-24 38.61-24 53.33S226.75 128 240 128zm160 0c13.25 0 24-11.94 24-26.67S400 48 400 48s-24 38.61-24 53.33S386.75 128 400 128zm64 0c13.25 0 24-11.94 24-26.67S464 48 464 48s-24 38.61-24 53.33S450.75 128 464 128zm64 0c13.25 0 24-11.94 24-26.67S528 48 528 48s-24 38.61-24 53.33S514.75 128 528 128z\"],\n    \"hard-hat\": [512, 512, [], \"f807\", \"M480 288c0-80.25-49.28-148.92-119.19-177.62L320 192V80a16 16 0 0 0-16-16h-96a16 16 0 0 0-16 16v112l-40.81-81.62C81.28 139.08 32 207.75 32 288v64h448zm16 96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"hashtag\": [448, 512, [], \"f292\", \"M440.667 182.109l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l14.623-81.891C377.123 38.754 371.468 32 363.997 32h-40.632a12 12 0 0 0-11.813 9.891L296.175 128H197.54l14.623-81.891C213.477 38.754 207.822 32 200.35 32h-40.632a12 12 0 0 0-11.813 9.891L132.528 128H53.432a12 12 0 0 0-11.813 9.891l-7.143 40C33.163 185.246 38.818 192 46.289 192h74.81L98.242 320H19.146a12 12 0 0 0-11.813 9.891l-7.143 40C-1.123 377.246 4.532 384 12.003 384h74.81L72.19 465.891C70.877 473.246 76.532 480 84.003 480h40.632a12 12 0 0 0 11.813-9.891L151.826 384h98.634l-14.623 81.891C234.523 473.246 240.178 480 247.65 480h40.632a12 12 0 0 0 11.813-9.891L315.472 384h79.096a12 12 0 0 0 11.813-9.891l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l22.857-128h79.096a12 12 0 0 0 11.813-9.891zM261.889 320h-98.634l22.857-128h98.634l-22.857 128z\"],\n    \"hat-wizard\": [512, 512, [], \"f6e8\", \"M496 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-304-64l-64-32 64-32 32-64 32 64 64 32-64 32-16 32h208l-86.41-201.63a63.955 63.955 0 0 1-1.89-45.45L416 0 228.42 107.19a127.989 127.989 0 0 0-53.46 59.15L64 416h144l-16-32zm64-224l16-32 16 32 32 16-32 16-16 32-16-32-32-16 32-16z\"],\n    \"haykal\": [512, 512, [], \"f666\", \"M496.25 202.52l-110-15.44 41.82-104.34c6.67-16.64-11.6-32.18-26.59-22.63L307.44 120 273.35 12.82C270.64 4.27 263.32 0 256 0c-7.32 0-14.64 4.27-17.35 12.82l-34.09 107.19-94.04-59.89c-14.99-9.55-33.25 5.99-26.59 22.63l41.82 104.34-110 15.43c-17.54 2.46-21.68 26.27-6.03 34.67l98.16 52.66-74.48 83.54c-10.92 12.25-1.72 30.93 13.29 30.93 1.31 0 2.67-.14 4.07-.45l108.57-23.65-4.11 112.55c-.43 11.65 8.87 19.22 18.41 19.22 5.15 0 10.39-2.21 14.2-7.18l68.18-88.9 68.18 88.9c3.81 4.97 9.04 7.18 14.2 7.18 9.54 0 18.84-7.57 18.41-19.22l-4.11-112.55 108.57 23.65c17.36 3.76 29.21-17.2 17.35-30.49l-74.48-83.54 98.16-52.66c15.64-8.39 11.5-32.2-6.04-34.66zM338.51 311.68l-51.89-11.3 1.97 53.79L256 311.68l-32.59 42.49 1.96-53.79-51.89 11.3 35.6-39.93-46.92-25.17 52.57-7.38-19.99-49.87 44.95 28.62L256 166.72l16.29 51.23 44.95-28.62-19.99 49.87 52.57 7.38-46.92 25.17 35.61 39.93z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M576 304v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48zm-48-80a79.557 79.557 0 0 1 30.777 6.165L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L17.223 230.165A79.557 79.557 0 0 1 48 224h480zm-48 96c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm-96 0c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"heading\": [512, 512, [], \"f1dc\", \"M448 96v320h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H320a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V288H160v128h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H32a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V96H32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16h-32v128h192V96h-32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16z\"],\n    \"headphones\": [512, 512, [], \"f025\", \"M256 32C114.52 32 0 146.496 0 288v48a32 32 0 0 0 17.689 28.622l14.383 7.191C34.083 431.903 83.421 480 144 480h24c13.255 0 24-10.745 24-24V280c0-13.255-10.745-24-24-24h-24c-31.342 0-59.671 12.879-80 33.627V288c0-105.869 86.131-192 192-192s192 86.131 192 192v1.627C427.671 268.879 399.342 256 368 256h-24c-13.255 0-24 10.745-24 24v176c0 13.255 10.745 24 24 24h24c60.579 0 109.917-48.098 111.928-108.187l14.382-7.191A32 32 0 0 0 512 336v-48c0-141.479-114.496-256-256-256z\"],\n    \"headphones-alt\": [512, 512, [], \"f58f\", \"M160 288h-16c-35.35 0-64 28.7-64 64.12v63.76c0 35.41 28.65 64.12 64 64.12h16c17.67 0 32-14.36 32-32.06V320.06c0-17.71-14.33-32.06-32-32.06zm208 0h-16c-17.67 0-32 14.35-32 32.06v127.88c0 17.7 14.33 32.06 32 32.06h16c35.35 0 64-28.71 64-64.12v-63.76c0-35.41-28.65-64.12-64-64.12zM256 32C112.91 32 4.57 151.13 0 288v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288c0-114.67 93.33-207.8 208-207.82 114.67.02 208 93.15 208 207.82v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288C507.43 151.13 399.09 32 256 32z\"],\n    \"headset\": [512, 512, [], \"f590\", \"M192 208c0-17.67-14.33-32-32-32h-16c-35.35 0-64 28.65-64 64v48c0 35.35 28.65 64 64 64h16c17.67 0 32-14.33 32-32V208zm176 144c35.35 0 64-28.65 64-64v-48c0-35.35-28.65-64-64-64h-16c-17.67 0-32 14.33-32 32v112c0 17.67 14.33 32 32 32h16zM256 0C113.18 0 4.58 118.83 0 256v16c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-16c0-114.69 93.31-208 208-208s208 93.31 208 208h-.12c.08 2.43.12 165.72.12 165.72 0 23.35-18.93 42.28-42.28 42.28H320c0-26.51-21.49-48-48-48h-32c-26.51 0-48 21.49-48 48s21.49 48 48 48h181.72c49.86 0 90.28-40.42 90.28-90.28V256C507.42 118.83 398.82 0 256 0z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M462.3 62.6C407.5 15.9 326 24.3 275.7 76.2L256 96.5l-19.7-20.3C186.1 24.3 104.5 15.9 49.7 62.6c-62.8 53.6-66.1 149.8-9.9 207.9l193.5 199.8c12.5 12.9 32.8 12.9 45.3 0l193.5-199.8c56.3-58.1 53-154.3-9.8-207.9z\"],\n    \"heart-broken\": [512, 512, [], \"f7a9\", \"M473.7 73.8l-2.4-2.5c-46-47-118-51.7-169.6-14.8L336 159.9l-96 64 48 128-144-144 96-64-28.6-86.5C159.7 19.6 87 24 40.7 71.4l-2.4 2.4C-10.4 123.6-12.5 202.9 31 256l212.1 218.6c7.1 7.3 18.6 7.3 25.7 0L481 255.9c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"heartbeat\": [512, 512, [], \"f21e\", \"M320.2 243.8l-49.7 99.4c-6 12.1-23.4 11.7-28.9-.6l-56.9-126.3-30 71.7H60.6l182.5 186.5c7.1 7.3 18.6 7.3 25.7 0L451.4 288H342.3l-22.1-44.2zM473.7 73.9l-2.4-2.5c-51.5-52.6-135.8-52.6-187.4 0L256 100l-27.9-28.5c-51.5-52.7-135.9-52.7-187.4 0l-2.4 2.4C-10.4 123.7-12.5 203 31 256h102.4l35.9-86.2c5.4-12.9 23.6-13.2 29.4-.4l58.2 129.3 49-97.9c5.9-11.8 22.7-11.8 28.6 0l27.6 55.2H481c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"helicopter\": [640, 512, [], \"f533\", \"M304 384h272c17.67 0 32-14.33 32-32 0-123.71-100.29-224-224-224V64h176c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H144c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h176v64H112L68.8 70.4C65.78 66.37 61.03 64 56 64H16.01C5.6 64-2.04 73.78.49 83.88L32 192l160 64 86.4 115.2A31.992 31.992 0 0 0 304 384zm112-188.49C478.55 208.3 528.03 257.44 540.79 320H416V195.51zm219.37 263.3l-22.15-22.2c-6.25-6.26-16.24-6.1-22.64.01-7.09 6.77-13.84 11.25-24.64 11.25H240c-8.84 0-16 7.18-16 16.03v32.06c0 8.85 7.16 16.03 16 16.03h325.94c14.88 0 35.3-.47 68.45-29.52 7.02-6.14 7.57-17.05.98-23.66z\"],\n    \"highlighter\": [544, 512, [], \"f591\", \"M0 479.98L99.92 512l35.45-35.45-67.04-67.04L0 479.98zm124.61-240.01a36.592 36.592 0 0 0-10.79 38.1l13.05 42.83-50.93 50.94 96.23 96.23 50.86-50.86 42.74 13.08c13.73 4.2 28.65-.01 38.15-10.78l35.55-41.64-173.34-173.34-41.52 35.44zm403.31-160.7l-63.2-63.2c-20.49-20.49-53.38-21.52-75.12-2.35L190.55 183.68l169.77 169.78L530.27 154.4c19.18-21.74 18.15-54.63-2.35-75.13z\"],\n    \"hiking\": [384, 512, [], \"f6ec\", \"M80.95 472.23c-4.28 17.16 6.14 34.53 23.28 38.81 2.61.66 5.22.95 7.8.95 14.33 0 27.37-9.7 31.02-24.23l25.24-100.97-52.78-52.78-34.56 138.22zm14.89-196.12L137 117c2.19-8.42-3.14-16.95-11.92-19.06-43.88-10.52-88.35 15.07-99.32 57.17L.49 253.24c-2.19 8.42 3.14 16.95 11.92 19.06l63.56 15.25c8.79 2.1 17.68-3.02 19.87-11.44zM368 160h-16c-8.84 0-16 7.16-16 16v16h-34.75l-46.78-46.78C243.38 134.11 228.61 128 212.91 128c-27.02 0-50.47 18.3-57.03 44.52l-26.92 107.72a32.012 32.012 0 0 0 8.42 30.39L224 397.25V480c0 17.67 14.33 32 32 32s32-14.33 32-32v-82.75c0-17.09-6.66-33.16-18.75-45.25l-46.82-46.82c.15-.5.49-.89.62-1.41l19.89-79.57 22.43 22.43c6 6 14.14 9.38 22.62 9.38h48v240c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V176c.01-8.84-7.15-16-15.99-16zM240 96c26.51 0 48-21.49 48-48S266.51 0 240 0s-48 21.49-48 48 21.49 48 48 48z\"],\n    \"hippo\": [640, 512, [], \"f6ed\", \"M581.12 96.2c-27.67-.15-52.5 17.58-76.6 26.62C489.98 88.27 455.83 64 416 64c-11.28 0-21.95 2.3-32 5.88V56c0-13.26-10.75-24-24-24h-16c-13.25 0-24 10.74-24 24v48.98C286.01 79.58 241.24 64 192 64 85.96 64 0 135.64 0 224v240c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16v-70.79C128.35 407.57 166.72 416 208 416s79.65-8.43 112-22.79V464c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V288h128v32c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-32c17.67 0 32-14.33 32-32v-92.02c0-34.09-24.79-67.59-58.88-67.78zM448 176c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"history\": [512, 512, [], \"f1da\", \"M504 255.531c.253 136.64-111.18 248.372-247.82 248.468-59.015.042-113.223-20.53-155.822-54.911-11.077-8.94-11.905-25.541-1.839-35.607l11.267-11.267c8.609-8.609 22.353-9.551 31.891-1.984C173.062 425.135 212.781 440 256 440c101.705 0 184-82.311 184-184 0-101.705-82.311-184-184-184-48.814 0-93.149 18.969-126.068 49.932l50.754 50.754c10.08 10.08 2.941 27.314-11.313 27.314H24c-8.837 0-16-7.163-16-16V38.627c0-14.254 17.234-21.393 27.314-11.314l49.372 49.372C129.209 34.136 189.552 8 256 8c136.81 0 247.747 110.78 248 247.531zm-180.912 78.784l9.823-12.63c8.138-10.463 6.253-25.542-4.21-33.679L288 256.349V152c0-13.255-10.745-24-24-24h-16c-13.255 0-24 10.745-24 24v135.651l65.409 50.874c10.463 8.137 25.541 6.253 33.679-4.21z\"],\n    \"hockey-puck\": [512, 512, [], \"f453\", \"M0 160c0-53 114.6-96 256-96s256 43 256 96-114.6 96-256 96S0 213 0 160zm0 82.2V352c0 53 114.6 96 256 96s256-43 256-96V242.2c-113.4 82.3-398.5 82.4-512 0z\"],\n    \"holly-berry\": [448, 512, [], \"f7aa\", \"M144 192c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm112-48c0 26.5 21.5 48 48 48s48-21.5 48-48-21.5-48-48-48-48 21.5-48 48zm-32-48c26.5 0 48-21.5 48-48S250.5 0 224 0s-48 21.5-48 48 21.5 48 48 48zm-16.2 139.1c.1-12.4-13.1-20.1-23.8-13.7-34.3 20.3-71.4 32.7-108.7 36.2-9.7.9-15.6 11.3-11.6 20.2 6.2 13.9 11.1 28.6 14.7 43.8 3.6 15.2-5.3 30.6-20.2 35.1-14.9 4.5-30.1 7.6-45.3 9.1-9.7 1-15.7 11.3-11.7 20.2 15 32.8 22.9 69.5 23 107.7.1 14.4 15.2 23.1 27.6 16 33.2-19 68.9-30.5 104.8-33.9 9.7-.9 15.6-11.3 11.6-20.2-6.2-13.9-11.1-28.6-14.7-43.8-3.6-15.2 5.3-30.6 20.2-35.1 14.9-4.5 30.1-7.6 45.3-9.1 9.7-1 15.7-11.3 11.7-20.2-15.5-34.2-23.3-72.5-22.9-112.3zM435 365.6c-15.2-1.6-30.3-4.7-45.3-9.1-14.9-4.5-23.8-19.9-20.2-35.1 3.6-15.2 8.5-29.8 14.7-43.8 4-8.9-1.9-19.3-11.6-20.2-37.3-3.5-74.4-15.9-108.7-36.2-10.7-6.3-23.9 1.4-23.8 13.7 0 1.6-.2 3.2-.2 4.9.2 33.3 7 65.7 19.9 94 5.7 12.4 5.2 26.6-.6 38.9 4.9 1.2 9.9 2.2 14.8 3.7 14.9 4.5 23.8 19.9 20.2 35.1-3.6 15.2-8.5 29.8-14.7 43.8-4 8.9 1.9 19.3 11.6 20.2 35.9 3.4 71.6 14.9 104.8 33.9 12.5 7.1 27.6-1.6 27.6-16 .2-38.2 8-75 23-107.7 4.3-8.7-1.8-19.1-11.5-20.1z\"],\n    \"home\": [576, 512, [], \"f015\", \"M280.37 148.26L96 300.11V464a16 16 0 0 0 16 16l112.06-.29a16 16 0 0 0 15.92-16V368a16 16 0 0 1 16-16h64a16 16 0 0 1 16 16v95.64a16 16 0 0 0 16 16.05L464 480a16 16 0 0 0 16-16V300L295.67 148.26a12.19 12.19 0 0 0-15.3 0zM571.6 251.47L488 182.56V44.05a12 12 0 0 0-12-12h-56a12 12 0 0 0-12 12v72.61L318.47 43a48 48 0 0 0-61 0L4.34 251.47a12 12 0 0 0-1.6 16.9l25.5 31A12 12 0 0 0 45.15 301l235.22-193.74a12.19 12.19 0 0 1 15.3 0L530.9 301a12 12 0 0 0 16.9-1.6l25.5-31a12 12 0 0 0-1.7-16.93z\"],\n    \"horse\": [576, 512, [], \"f6f0\", \"M575.92 76.6c-.01-8.13-3.02-15.87-8.58-21.8-3.78-4.03-8.58-9.12-13.69-14.5 11.06-6.84 19.5-17.49 22.18-30.66C576.85 4.68 572.96 0 567.9 0H447.92c-70.69 0-128 57.31-128 128H160c-28.84 0-54.4 12.98-72 33.11V160c-48.53 0-88 39.47-88 88v56c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-56c0-13.22 6.87-24.39 16.78-31.68-.21 2.58-.78 5.05-.78 7.68 0 27.64 11.84 52.36 30.54 69.88l-25.72 68.6a63.945 63.945 0 0 0-2.16 37.99l24.85 99.41A15.982 15.982 0 0 0 107.02 512h65.96c10.41 0 18.05-9.78 15.52-19.88l-26.31-105.26 23.84-63.59L320 345.6V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V318.22c19.74-20.19 32-47.75 32-78.22 0-.22-.07-.42-.08-.64V136.89l16 7.11 18.9 37.7c7.45 14.87 25.05 21.55 40.49 15.37l32.55-13.02a31.997 31.997 0 0 0 20.12-29.74l-.06-77.71zm-64 19.4c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"horse-head\": [512, 512, [], \"f7ab\", \"M509.8 332.5l-69.9-164.3c-14.9-41.2-50.4-71-93-79.2 18-10.6 46.3-35.9 34.2-82.3-1.3-5-7.1-7.9-12-6.1L166.9 76.3C35.9 123.4 0 238.9 0 398.8V480c0 17.7 14.3 32 32 32h236.2c23.8 0 39.3-25 28.6-46.3L256 384v-.7c-45.6-3.5-84.6-30.7-104.3-69.6-1.6-3.1-.9-6.9 1.6-9.3l12.1-12.1c3.9-3.9 10.6-2.7 12.9 2.4 14.8 33.7 48.2 57.4 87.4 57.4 17.2 0 33-5.1 46.8-13.2l46 63.9c6 8.4 15.7 13.3 26 13.3h50.3c8.5 0 16.6-3.4 22.6-9.4l45.3-39.8c8.9-9.1 11.7-22.6 7.1-34.4zM328 224c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M448 492v20H0v-20c0-6.627 5.373-12 12-12h20V120c0-13.255 10.745-24 24-24h88V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v72h88c13.255 0 24 10.745 24 24v360h20c6.627 0 12 5.373 12 12zM308 192h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-168 64h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm104 128h-40c-6.627 0-12 5.373-12 12v84h64v-84c0-6.627-5.373-12-12-12zm64-96h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-116 12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40zM182 96h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6z\"],\n    \"hospital-alt\": [576, 512, [], \"f47d\", \"M544 96H416V32c0-17.7-14.3-32-32-32H192c-17.7 0-32 14.3-32 32v64H32c-17.7 0-32 14.3-32 32v368c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16V128c0-17.7-14.3-32-32-32zM160 436c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm160 128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm16-170c0 3.3-2.7 6-6 6h-26v26c0 3.3-2.7 6-6 6h-20c-3.3 0-6-2.7-6-6v-26h-26c-3.3 0-6-2.7-6-6v-20c0-3.3 2.7-6 6-6h26V86c0-3.3 2.7-6 6-6h20c3.3 0 6 2.7 6 6v26h26c3.3 0 6 2.7 6 6v20zm144 298c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"hospital-symbol\": [512, 512, [], \"f47e\", \"M256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm112 376c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-88h-96v88c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8V136c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v88h96v-88c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v240z\"],\n    \"hot-tub\": [512, 512, [], \"f593\", \"M414.21 177.65c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C378.96 6.14 372.22 0 364.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zm-108 0c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C270.96 6.14 264.22 0 256.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zM480 256H256l-110.93-83.2a63.99 63.99 0 0 0-38.4-12.8H64c-35.35 0-64 28.65-64 64v224c0 35.35 28.65 64 64 64h384c35.35 0 64-28.65 64-64V288c0-17.67-14.33-32-32-32zM128 440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zM64 128c35.35 0 64-28.65 64-64S99.35 0 64 0 0 28.65 0 64s28.65 64 64 64z\"],\n    \"hotdog\": [512, 512, [], \"f80f\", \"M488.56 23.44a80 80 0 0 0-113.12 0l-352 352a80 80 0 1 0 113.12 113.12l352-352a80 80 0 0 0 0-113.12zm-49.93 95.19c-19.6 19.59-37.52 22.67-51.93 25.14C373.76 146 364.4 147.6 352 160s-14 21.76-16.23 34.71c-2.48 14.4-5.55 32.33-25.15 51.92s-37.52 22.67-51.92 25.15C245.75 274 236.4 275.6 224 288s-14 21.75-16.23 34.7c-2.47 14.4-5.54 32.33-25.14 51.92s-37.53 22.68-51.93 25.15C117.76 402 108.4 403.6 96 416a16 16 0 0 1-22.63-22.63c19.6-19.59 37.52-22.67 51.92-25.14 13-2.22 22.3-3.82 34.71-16.23s14-21.75 16.22-34.7c2.48-14.4 5.55-32.33 25.15-51.92s37.52-22.67 51.92-25.14c13-2.22 22.3-3.83 34.7-16.23s14-21.76 16.24-34.71c2.47-14.4 5.54-32.33 25.14-51.92s37.52-22.68 51.92-25.15C394.24 110 403.59 108.41 416 96a16 16 0 0 1 22.63 22.63zM31.44 322.18L322.18 31.44l-11.54-11.55c-25-25-63.85-26.66-86.79-3.72L16.17 223.85c-22.94 22.94-21.27 61.79 3.72 86.78zm449.12-132.36L189.82 480.56l11.54 11.55c25 25 63.85 26.66 86.79 3.72l207.68-207.68c22.94-22.94 21.27-61.79-3.72-86.79z\"],\n    \"hotel\": [576, 512, [], \"f594\", \"M560 64c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h15.98v384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h240v-80c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16v80h240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-16V64h16zm-304 44.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm0 96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm-128-96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zM179.2 256h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8zM192 384c0-53.02 42.98-96 96-96s96 42.98 96 96H192zm256-140.8c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-96c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64z\"],\n    \"hourglass-end\": [384, 512, [], \"f253\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64zM192 208c-57.787 0-104-66.518-104-144h208c0 77.945-46.51 144-104 144z\"],\n    \"hourglass-half\": [384, 512, [], \"f252\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-75.078 384H99.08c17.059-46.797 52.096-80 92.92-80 40.821 0 75.862 33.196 92.922 80zm.019-256H99.078C91.988 108.548 88 86.748 88 64h208c0 22.805-3.987 44.587-11.059 64z\"],\n    \"hourglass-start\": [384, 512, [], \"f251\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-64 448H88c0-77.458 46.204-144 104-144 57.786 0 104 66.517 104 144z\"],\n    \"house-damage\": [576, 512, [], \"f6f1\", \"M288 114.96L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496c0 8.84 7.16 16 16 16h149.23L192 439.19l104.11-64-60.16-119.22L384 392.75l-104.11 64L319.81 512H496c8.84 0 16-7.16 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2L288 114.96zm282.69 121.32L512 184.45V48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v51.69L314.75 10.31C307.12 3.45 297.56.01 288 0s-19.1 3.41-26.7 10.27L5.31 236.28c-6.57 5.91-7.12 16.02-1.21 22.6l21.4 23.82c5.9 6.57 16.02 7.12 22.6 1.21L277.42 81.63c6.05-5.33 15.12-5.33 21.17 0L527.91 283.9c6.57 5.9 16.69 5.36 22.6-1.21l21.4-23.82c5.9-6.57 5.36-16.69-1.22-22.59z\"],\n    \"hryvnia\": [384, 512, [], \"f6f2\", \"M368 240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-41.86c13.41-28.63 13.74-63.33-4.13-94.05C303.34 49.84 267.1 32 229.96 32h-78.82c-24.32 0-47.86 8.53-66.54 24.09L72.83 65.9c-10.18 8.49-11.56 23.62-3.07 33.8l20.49 24.59c8.49 10.19 23.62 11.56 33.81 3.07l11.73-9.78c4.32-3.6 9.77-5.57 15.39-5.57h83.62c11.69 0 21.2 9.52 21.2 21.2 0 5.91-2.48 11.58-6.81 15.58L219.7 176H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h134.37l-34.67 32H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h41.86c-13.41 28.63-13.74 63.33 4.13 94.05C80.66 462.15 116.9 480 154.04 480h78.82c24.32 0 47.86-8.53 66.54-24.09l11.77-9.81c10.18-8.49 11.56-23.62 3.07-33.8l-20.49-24.59c-8.49-10.19-23.62-11.56-33.81-3.07l-11.75 9.8a23.992 23.992 0 0 1-15.36 5.56H149.2c-11.69 0-21.2-9.52-21.2-21.2 0-5.91 2.48-11.58 6.81-15.58L164.3 336H368c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H233.63l34.67-32H368z\"],\n    \"i-cursor\": [256, 512, [], \"f246\", \"M256 52.048V12.065C256 5.496 250.726.148 244.158.066 211.621-.344 166.469.011 128 37.959 90.266.736 46.979-.114 11.913.114 5.318.157 0 5.519 0 12.114v39.645c0 6.687 5.458 12.078 12.145 11.998C38.111 63.447 96 67.243 96 112.182V224H60c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h36v112c0 44.932-56.075 48.031-83.95 47.959C5.404 447.942 0 453.306 0 459.952v39.983c0 6.569 5.274 11.917 11.842 11.999 32.537.409 77.689.054 116.158-37.894 37.734 37.223 81.021 38.073 116.087 37.845 6.595-.043 11.913-5.405 11.913-12V460.24c0-6.687-5.458-12.078-12.145-11.998C217.889 448.553 160 444.939 160 400V288h36c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-36V112.182c0-44.932 56.075-48.213 83.95-48.142 6.646.018 12.05-5.346 12.05-11.992z\"],\n    \"ice-cream\": [448, 512, [], \"f810\", \"M368 160h-.94a144 144 0 1 0-286.12 0H80a48 48 0 0 0 0 96h288a48 48 0 0 0 0-96zM195.38 493.69a31.52 31.52 0 0 0 57.24 0L352 288H96z\"],\n    \"icicles\": [512, 512, [], \"f7ad\", \"M511.4 37.9C515.1 18.2 500 0 480 0H32C10.6 0-4.8 20.7 1.4 41.2l87.1 273.4c2.5 7.2 12.7 7.2 15.1 0L140 190.5l44.2 187.3c1.9 8.3 13.7 8.3 15.6 0l46.5-196.9 34.1 133.4c2.3 7.6 13 7.6 15.3 0l45.8-172.5 66.7 363.8c1.7 8.6 14 8.6 15.7 0l87.5-467.7z\"],\n    \"icons\": [512, 512, [], \"f86d\", \"M116.65 219.35a15.68 15.68 0 0 0 22.65 0l96.75-99.83c28.15-29 26.5-77.1-4.91-103.88C203.75-7.7 163-3.5 137.86 22.44L128 32.58l-9.85-10.14C93.05-3.5 52.25-7.7 24.86 15.64c-31.41 26.78-33 74.85-5 103.88zm143.92 100.49h-48l-7.08-14.24a27.39 27.39 0 0 0-25.66-17.78h-71.71a27.39 27.39 0 0 0-25.66 17.78l-7 14.24h-48A27.45 27.45 0 0 0 0 347.3v137.25A27.44 27.44 0 0 0 27.43 512h233.14A27.45 27.45 0 0 0 288 484.55V347.3a27.45 27.45 0 0 0-27.43-27.46zM144 468a52 52 0 1 1 52-52 52 52 0 0 1-52 52zm355.4-115.9h-60.58l22.36-50.75c2.1-6.65-3.93-13.21-12.18-13.21h-75.59c-6.3 0-11.66 3.9-12.5 9.1l-16.8 106.93c-1 6.3 4.88 11.89 12.5 11.89h62.31l-24.2 83c-1.89 6.65 4.2 12.9 12.23 12.9a13.26 13.26 0 0 0 10.92-5.25l92.4-138.91c4.88-6.91-1.16-15.7-10.87-15.7zM478.08.33L329.51 23.17C314.87 25.42 304 38.92 304 54.83V161.6a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V99.66l112-17.22v47.18a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V32c0-19.48-16-34.42-33.92-31.67z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM144 32h96c8.8 0 16 7.2 16 16s-7.2 16-16 16h-96c-8.8 0-16-7.2-16-16s7.2-16 16-16zm48 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 416 80 407.4 80 396.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v16h576V80c0-26.5-21.5-48-48-48zM0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V128H0v304zm352-232c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zM176 192c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zM67.1 396.2C75.5 370.5 99.6 352 128 352h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.9-5.2 19.8-15.6 19.8H82.7c-10.4 0-18.8-10-15.6-19.8z\"],\n    \"id-card-alt\": [576, 512, [], \"f47f\", \"M528 64H384v96H192V64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM288 224c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm93.3 224H194.7c-10.4 0-18.8-10-15.6-19.8 8.3-25.6 32.4-44.2 60.9-44.2h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.8-5.2 19.8-15.6 19.8zM352 32c0-17.7-14.3-32-32-32h-64c-17.7 0-32 14.3-32 32v96h128V32z\"],\n    \"igloo\": [576, 512, [], \"f7ae\", \"M320 33.9c-10.5-1.2-21.2-1.9-32-1.9-99.8 0-187.8 50.8-239.4 128H320V33.9zM96 192H30.3C11.1 230.6 0 274 0 320h96V192zM352 39.4V160h175.4C487.2 99.9 424.8 55.9 352 39.4zM480 320h96c0-46-11.1-89.4-30.3-128H480v128zm-64 64v96h128c17.7 0 32-14.3 32-32v-96H411.5c2.6 10.3 4.5 20.9 4.5 32zm32-192H128v128h49.8c22.2-38.1 63-64 110.2-64s88 25.9 110.2 64H448V192zM0 448c0 17.7 14.3 32 32 32h128v-96c0-11.1 1.9-21.7 4.5-32H0v96zm288-160c-53 0-96 43-96 96v96h192v-96c0-53-43-96-96-96z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM112 120c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56zM64 384h384V272l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L208 320l-55.515-55.515c-4.686-4.686-12.284-4.686-16.971 0L64 336v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v208c0 44.112 35.888 80 80 80h336zm96-80V80c0-26.51-21.49-48-48-48H144c-26.51 0-48 21.49-48 48v256c0 26.51 21.49 48 48 48h384c26.51 0 48-21.49 48-48zM256 128c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-96 144l55.515-55.515c4.686-4.686 12.284-4.686 16.971 0L272 256l135.515-135.515c4.686-4.686 12.284-4.686 16.971 0L512 208v112H160v-48z\"],\n    \"inbox\": [576, 512, [], \"f01c\", \"M567.938 243.908L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L8.062 243.908A47.994 47.994 0 0 0 0 270.533V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V270.533a47.994 47.994 0 0 0-8.062-26.625zM162.252 128h251.497l85.333 128H376l-32 64H232l-32-64H76.918l85.334-128z\"],\n    \"indent\": [448, 512, [], \"f03c\", \"M27.31 363.3l96-96a16 16 0 0 0 0-22.62l-96-96C17.27 138.66 0 145.78 0 160v192c0 14.31 17.33 21.3 27.31 11.3zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"industry\": [512, 512, [], \"f275\", \"M475.115 163.781L336 252.309v-68.28c0-18.916-20.931-30.399-36.885-20.248L160 252.309V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h464c13.255 0 24-10.745 24-24V184.029c0-18.917-20.931-30.399-36.885-20.248z\"],\n    \"infinity\": [640, 512, [], \"f534\", \"M471.1 96C405 96 353.3 137.3 320 174.6 286.7 137.3 235 96 168.9 96 75.8 96 0 167.8 0 256s75.8 160 168.9 160c66.1 0 117.8-41.3 151.1-78.6 33.3 37.3 85 78.6 151.1 78.6 93.1 0 168.9-71.8 168.9-160S564.2 96 471.1 96zM168.9 320c-40.2 0-72.9-28.7-72.9-64s32.7-64 72.9-64c38.2 0 73.4 36.1 94 64-20.4 27.6-55.9 64-94 64zm302.2 0c-38.2 0-73.4-36.1-94-64 20.4-27.6 55.9-64 94-64 40.2 0 72.9 28.7 72.9 64s-32.7 64-72.9 64z\"],\n    \"info\": [192, 512, [], \"f129\", \"M20 424.229h20V279.771H20c-11.046 0-20-8.954-20-20V212c0-11.046 8.954-20 20-20h112c11.046 0 20 8.954 20 20v212.229h20c11.046 0 20 8.954 20 20V492c0 11.046-8.954 20-20 20H20c-11.046 0-20-8.954-20-20v-47.771c0-11.046 8.954-20 20-20zM96 0C56.235 0 24 32.235 24 72s32.235 72 72 72 72-32.235 72-72S135.764 0 96 0z\"],\n    \"info-circle\": [512, 512, [], \"f05a\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 110c23.196 0 42 18.804 42 42s-18.804 42-42 42-42-18.804-42-42 18.804-42 42-42zm56 254c0 6.627-5.373 12-12 12h-88c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h12v-64h-12c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h64c6.627 0 12 5.373 12 12v100h12c6.627 0 12 5.373 12 12v24z\"],\n    \"italic\": [320, 512, [], \"f033\", \"M320 48v32a16 16 0 0 1-16 16h-62.76l-80 320H208a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h62.76l80-320H112a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h192a16 16 0 0 1 16 16z\"],\n    \"jedi\": [544, 512, [], \"f669\", \"M479.99 352l58.88-58.87c3.29-16.8 5.13-34.12 5.13-51.86 0-5.81-.68-11.51-1.05-17.27H496l41.25-41.24c-14.5-64.79-52.43-123.05-107.91-162.27-2.77-1.96-5.97-2.99-9.25-2.99-5.37 0-10.41 2.71-13.49 7.24-3.05 4.49-3.64 9.99-1.61 15.09 6.55 16.46 9.86 33.73 9.86 51.31 0 45.12-21.03 86.57-57.69 113.73-4.02 2.98-6.46 7.5-6.7 12.4-.24 4.92 1.76 9.66 5.49 13.03 32.93 29.75 47.35 73.51 38.57 117.07-9.74 48.35-48.84 87.1-97.31 96.5l-2.5-65.34L321.88 397c2.98 2.06 7.39 1.69 10.02-.8a8.002 8.002 0 0 0 1.34-9.92l-20.11-33.73 42.07-8.72c3.7-.75 6.38-4.05 6.38-7.83 0-3.77-2.69-7.06-6.38-7.83l-42.07-8.73 20.13-33.77c1.92-3.23 1.34-7.31-1.38-9.91-2.7-2.55-6.97-2.89-10-.8l-30.39 20.67L279.96 7.7a7.964 7.964 0 0 0-8-7.7c-4.33 0-7.84 3.38-8 7.67l-11.52 287.97-30.39-20.66c-3.14-2.12-7.27-1.83-10 .78-2.72 2.59-3.3 6.67-1.36 9.94l20.11 33.73-42.07 8.73c-3.7.75-6.38 4.05-6.38 7.83s2.67 7.08 6.38 7.83l42.07 8.72-20.13 33.77c-1.92 3.23-1.34 7.33 1.39 9.94 2.59 2.45 7.03 2.75 10 .75l27.16-18.48-2.5 65.26c-56.94-11.64-99.89-61.89-99.89-121.92 0-35.08 14.62-67.6 41.17-91.58 3.72-3.36 5.72-8.11 5.48-13.01-.24-4.9-2.68-9.41-6.69-12.38-36.67-27.16-57.71-68.62-57.71-113.74 0-17.56 3.31-34.81 9.84-51.26 2.02-5.09 1.43-10.59-1.62-15.09-3.08-4.54-8.13-7.25-13.51-7.25-3.3 0-6.5 1.04-9.27 3-55.87 39.52-93.6 97.37-107.97 162.07L47.93 224H.72c-.63 9.92-.97 19.91-.5 29.99.62 13.43 2.54 26.53 5.11 39.41l58.6 58.6H24.02c41.25 90.23 131.13 154.94 235.1 159.71 4.3.2 8.59.29 12.85.29 110.34 0 205.35-65.83 247.98-160h-39.96z\"],\n    \"joint\": [640, 512, [], \"f595\", \"M444.34 181.1c22.38 15.68 35.66 41.16 35.66 68.59V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-43.24-21.01-83.41-56.34-108.06C463.85 125.02 448 99.34 448 70.31V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v66.4c0 43.69 24.56 81.63 60.34 106.7zM194.97 358.98C126.03 370.07 59.69 394.69 0 432c83.65 52.28 180.3 80 278.94 80h88.57L254.79 380.49c-14.74-17.2-37.45-25.11-59.82-21.51zM553.28 87.09c-5.67-3.8-9.28-9.96-9.28-16.78V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v62.31c0 22.02 10.17 43.41 28.64 55.39C550.79 153.04 576 199.54 576 249.69V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-65.44-32.41-126.19-86.72-162.6zM360.89 352.05c-34.4.06-86.81.15-88.21.17l117.8 137.43A63.987 63.987 0 0 0 439.07 512h88.45L409.57 374.4a63.955 63.955 0 0 0-48.68-22.35zM616 352H432l117.99 137.65A63.987 63.987 0 0 0 598.58 512H616c13.25 0 24-10.75 24-24V376c0-13.26-10.75-24-24-24z\"],\n    \"journal-whills\": [448, 512, [], \"f66a\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM133.08 144.39l21.26 21.26c1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34c3.12-3.12 3.12-8.19 0-11.31l-26.42-26.42c10-20.9 26.24-37.97 46.37-49.26C179.62 88.4 176 99.74 176 112c0 19.96 9.33 37.57 23.66 49.31C190.01 171.37 184 184.96 184 200c0 26.94 19.04 49.4 44.38 54.76l1.36-32.71-10.37 7.04c-.69.45-1.47.69-2.25.69-1 0-1.98-.38-2.75-1.09a4.006 4.006 0 0 1-.69-4.95l8.54-14.31-17.91-3.72c-1.86-.39-3.19-2.03-3.19-3.92s1.33-3.53 3.19-3.92l17.91-3.72-8.54-14.31c-.95-1.61-.67-3.67.69-4.95 1.36-1.3 3.44-1.44 5-.41l12.01 8.16L236 71.83c.09-2.14 1.86-3.83 4-3.83s3.91 1.69 4 3.83l4.68 112.29 14.2-9.65a4.067 4.067 0 0 1 5 .41 4.006 4.006 0 0 1 .69 4.95l-8.54 14.31 17.91 3.72c1.86.39 3.19 2.03 3.19 3.92s-1.33 3.53-3.19 3.92l-17.91 3.72 8.54 14.31c.95 1.61.67 3.67-.69 4.95-.77.72-1.77 1.09-2.75 1.09-.78 0-1.56-.23-2.25-.69l-12.68-8.62 1.43 34.28C276.96 249.4 296 226.94 296 200c0-15.04-6.01-28.63-15.66-38.69C294.67 149.57 304 131.96 304 112c0-12.26-3.62-23.6-9.6-33.33 20.13 11.28 36.37 28.36 46.37 49.26l-26.42 26.42c-3.12 3.12-3.12 8.19 0 11.31 1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34l21.26-21.26c2.97 10.08 5.07 20.55 5.07 31.6 0 .52-.14.99-.15 1.51l-37.11 32.47a7.975 7.975 0 0 0-.75 11.28 7.97 7.97 0 0 0 6.02 2.73c1.88 0 3.75-.66 5.27-1.98l23.59-20.64C337.32 250.96 293.09 288 240 288s-97.32-37.04-108.86-86.62l23.59 20.64A7.957 7.957 0 0 0 160 224c2.22 0 4.44-.92 6.02-2.73 2.92-3.33 2.58-8.38-.75-11.28l-37.11-32.47c-.01-.52-.15-.99-.15-1.51-.01-11.06 2.09-21.53 5.07-31.62zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"kaaba\": [576, 512, [], \"f66b\", \"M554.12 83.51L318.36 4.93a95.962 95.962 0 0 0-60.71 0L21.88 83.51A32.006 32.006 0 0 0 0 113.87v49.01l265.02-79.51c15.03-4.5 30.92-4.5 45.98 0l265 79.51v-49.01c0-13.77-8.81-26-21.88-30.36zm-279.9 30.52L0 196.3v228.38c0 15 10.42 27.98 25.06 31.24l242.12 53.8a95.937 95.937 0 0 0 41.65 0l242.12-53.8c14.64-3.25 25.06-16.24 25.06-31.24V196.29l-274.2-82.26c-9.04-2.72-18.59-2.72-27.59 0zM128 230.11c0 3.61-2.41 6.77-5.89 7.72l-80 21.82C37.02 261.03 32 257.2 32 251.93v-16.58c0-3.61 2.41-6.77 5.89-7.72l80-21.82c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm144-39.28c0 3.61-2.41 6.77-5.89 7.72l-96 26.18c-5.09 1.39-10.11-2.44-10.11-7.72v-16.58c0-3.61 2.41-6.77 5.89-7.72l96-26.18c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm176 22.7c0-5.28 5.02-9.11 10.11-7.72l80 21.82c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-80-21.82a7.997 7.997 0 0 1-5.89-7.72v-16.58zm-144-39.27c0-5.28 5.02-9.11 10.11-7.72l96 26.18c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-96-26.18a7.997 7.997 0 0 1-5.89-7.72v-16.58z\"],\n    \"key\": [512, 512, [], \"f084\", \"M512 176.001C512 273.203 433.202 352 336 352c-11.22 0-22.19-1.062-32.827-3.069l-24.012 27.014A23.999 23.999 0 0 1 261.223 384H224v40c0 13.255-10.745 24-24 24h-40v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-78.059c0-6.365 2.529-12.47 7.029-16.971l161.802-161.802C163.108 213.814 160 195.271 160 176 160 78.798 238.797.001 335.999 0 433.488-.001 512 78.511 512 176.001zM336 128c0 26.51 21.49 48 48 48s48-21.49 48-48-21.49-48-48-48-48 21.49-48 48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM128 180v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"khanda\": [512, 512, [], \"f66d\", \"M415.81 66c-6.37-3.5-14.37-2.33-19.36 3.02a15.974 15.974 0 0 0-1.91 19.52c16.49 26.16 25.2 56.39 25.2 87.41-.19 53.25-26.77 102.69-71.27 132.41l-76.63 53.35v-20.1l44.05-36.09c3.92-4.2 5-10.09 2.81-15.28L310.85 273c33.84-19.26 56.94-55.25 56.94-96.99 0-40.79-22.02-76.13-54.59-95.71l5.22-11.44c2.34-5.53.93-11.83-3.57-16.04L255.86 0l-58.99 52.81c-4.5 4.21-5.9 10.51-3.57 16.04l5.22 11.44c-32.57 19.58-54.59 54.93-54.59 95.72 0 41.75 23.09 77.73 56.94 96.99l-7.85 17.24c-2.19 5.18-1.1 11.07 2.81 15.28l44.05 36.09v19.9l-76.59-53.33C119.02 278.62 92.44 229.19 92.26 176c0-31.08 8.71-61.31 25.2-87.47 3.87-6.16 2.4-13.77-2.59-19.08-5-5.34-13.68-6.2-20.02-2.7C16.32 109.6-22.3 205.3 13.36 295.99c7.07 17.99 17.89 34.38 30.46 49.06l55.97 65.36c4.87 5.69 13.04 7.24 19.65 3.72l79.35-42.23L228 392.23l-47.08 32.78c-1.67-.37-3.23-1.01-5.01-1.01-13.25 0-23.99 10.74-23.99 24 0 13.25 10.74 24 23.99 24 12.1 0 21.69-9.11 23.33-20.76l40.63-28.28v29.95c-9.39 5.57-15.99 15.38-15.99 27.1 0 17.67 14.32 32 31.98 32s31.98-14.33 31.98-32c0-11.71-6.61-21.52-15.99-27.1v-30.15l40.91 28.48C314.41 462.89 324 472 336.09 472c13.25 0 23.99-10.75 23.99-24 0-13.26-10.74-24-23.99-24-1.78 0-3.34.64-5.01 1.01L284 392.23l29.21-20.34 79.35 42.23c6.61 3.52 14.78 1.97 19.65-3.71l52.51-61.31c18.87-22.02 34-47.5 41.25-75.59 21.62-83.66-16.45-167.27-90.16-207.51zm-95.99 110c0 22.3-11.49 41.92-28.83 53.38l-5.65-12.41c-8.75-24.52-8.75-51.04 0-75.56l7.83-17.18c16.07 11.65 26.65 30.45 26.65 51.77zm-127.93 0c0-21.32 10.58-40.12 26.66-51.76l7.83 17.18c8.75 24.52 8.75 51.03 0 75.56l-5.65 12.41c-17.34-11.46-28.84-31.09-28.84-53.39z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm136 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm24-156c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-39 219.9l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5zM304 396c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm65-168.1l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M501.1 402.5c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zm-177.6-4c-5.6-20.3-2.3-42 9-59.7 29.7-46.3 98.7-45.5 127.8 4.3 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-.3-.7-23.9-84.6-23.9-84.6zM168 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm120 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-5.7-12.3 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.8-3.7-4.6-16.6 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C274.6 368.7 288 383 288 396zm16-179c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S400 181 404 206.2c1.7 11.1-11.3 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 217z\"],\n    \"kiwi-bird\": [576, 512, [], \"f535\", \"M575.81 217.98C572.64 157.41 518.28 112 457.63 112h-9.37c-52.82 0-104.25-16.25-147.74-46.24-41.99-28.96-96.04-41.62-153.21-28.7C129.3 41.12-.08 78.24 0 224c.04 70.95 38.68 132.8 95.99 166.01V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-54.26c15.36 3.96 31.4 6.26 48 6.26 5.44 0 10.68-.73 16-1.18V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-59.43c14.24-5.06 27.88-11.39 40.34-19.51C342.07 355.25 393.86 336 448.46 336c25.48 0 16.01-.31 23.05-.78l74.41 136.44c2.86 5.23 8.3 8.34 14.05 8.34 1.31 0 2.64-.16 3.95-.5 7.09-1.8 12.05-8.19 12.05-15.5 0 0 .14-240.24-.16-246.02zM463.97 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm80 153.25l-39.86-73.08c15.12-5.83 28.73-14.6 39.86-25.98v99.06z\"],\n    \"landmark\": [512, 512, [], \"f66f\", \"M501.62 92.11L267.24 2.04a31.958 31.958 0 0 0-22.47 0L10.38 92.11A16.001 16.001 0 0 0 0 107.09V144c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-36.91c0-6.67-4.14-12.64-10.38-14.98zM64 192v160H48c-8.84 0-16 7.16-16 16v48h448v-48c0-8.84-7.16-16-16-16h-16V192h-64v160h-96V192h-64v160h-96V192H64zm432 256H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"language\": [640, 512, [], \"f1ab\", \"M152.1 236.2c-3.5-12.1-7.8-33.2-7.8-33.2h-.5s-4.3 21.1-7.8 33.2l-11.1 37.5H163zM616 96H336v320h280c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm-24 120c0 6.6-5.4 12-12 12h-11.4c-6.9 23.6-21.7 47.4-42.7 69.9 8.4 6.4 17.1 12.5 26.1 18 5.5 3.4 7.3 10.5 4.1 16.2l-7.9 13.9c-3.4 5.9-10.9 7.8-16.7 4.3-12.6-7.8-24.5-16.1-35.4-24.9-10.9 8.7-22.7 17.1-35.4 24.9-5.8 3.5-13.3 1.6-16.7-4.3l-7.9-13.9c-3.2-5.6-1.4-12.8 4.2-16.2 9.3-5.7 18-11.7 26.1-18-7.9-8.4-14.9-17-21-25.7-4-5.7-2.2-13.6 3.7-17.1l6.5-3.9 7.3-4.3c5.4-3.2 12.4-1.7 16 3.4 5 7 10.8 14 17.4 20.9 13.5-14.2 23.8-28.9 30-43.2H412c-6.6 0-12-5.4-12-12v-16c0-6.6 5.4-12 12-12h64v-16c0-6.6 5.4-12 12-12h16c6.6 0 12 5.4 12 12v16h64c6.6 0 12 5.4 12 12zM0 120v272c0 13.3 10.7 24 24 24h280V96H24c-13.3 0-24 10.7-24 24zm58.9 216.1L116.4 167c1.7-4.9 6.2-8.1 11.4-8.1h32.5c5.1 0 9.7 3.3 11.4 8.1l57.5 169.1c2.6 7.8-3.1 15.9-11.4 15.9h-22.9a12 12 0 0 1-11.5-8.6l-9.4-31.9h-60.2l-9.1 31.8c-1.5 5.1-6.2 8.7-11.5 8.7H70.3c-8.2 0-14-8.1-11.4-15.9z\"],\n    \"laptop\": [640, 512, [], \"f109\", \"M624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-code\": [640, 512, [], \"f5fc\", \"M255.03 261.65c6.25 6.25 16.38 6.25 22.63 0l11.31-11.31c6.25-6.25 6.25-16.38 0-22.63L253.25 192l35.71-35.72c6.25-6.25 6.25-16.38 0-22.63l-11.31-11.31c-6.25-6.25-16.38-6.25-22.63 0l-58.34 58.34c-6.25 6.25-6.25 16.38 0 22.63l58.35 58.34zm96.01-11.3l11.31 11.31c6.25 6.25 16.38 6.25 22.63 0l58.34-58.34c6.25-6.25 6.25-16.38 0-22.63l-58.34-58.34c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63L386.75 192l-35.71 35.72c-6.25 6.25-6.25 16.38 0 22.63zM624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-medical\": [640, 512, [], \"f812\", \"M232 224h56v56a8 8 0 0 0 8 8h48a8 8 0 0 0 8-8v-56h56a8 8 0 0 0 8-8v-48a8 8 0 0 0-8-8h-56v-56a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v56h-56a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8zM576 48a48.14 48.14 0 0 0-48-48H112a48.14 48.14 0 0 0-48 48v336h512zm-64 272H128V64h384zm112 96H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33-17.47-32.77-32H16a16 16 0 0 0-16 16v16a64.19 64.19 0 0 0 64 64h512a64.19 64.19 0 0 0 64-64v-16a16 16 0 0 0-16-16z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 152c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm88 272h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18-8.9 71-69.5 126-142.9 126z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm24 199.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.8 4.1-15.1-4.5zm-160 0c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 161.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 180l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm20.1 198.1c4-25.2 34.2-42.1 59.9-42.1s55.9 16.9 59.9 42.1c1.7 11.1-11.4 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 217c-8.4 7.4-21.6.3-19.9-10.9zM168 160c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm230.9 146C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"layer-group\": [512, 512, [], \"f5fd\", \"M12.41 148.02l232.94 105.67c6.8 3.09 14.49 3.09 21.29 0l232.94-105.67c16.55-7.51 16.55-32.52 0-40.03L266.65 2.31a25.607 25.607 0 0 0-21.29 0L12.41 107.98c-16.55 7.51-16.55 32.53 0 40.04zm487.18 88.28l-58.09-26.33-161.64 73.27c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.51 209.97l-58.1 26.33c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 276.3c16.55-7.5 16.55-32.5 0-40zm0 127.8l-57.87-26.23-161.86 73.37c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.29 337.87 12.41 364.1c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 404.1c16.55-7.5 16.55-32.5 0-40z\"],\n    \"leaf\": [576, 512, [], \"f06c\", \"M546.2 9.7c-5.6-12.5-21.6-13-28.3-1.2C486.9 62.4 431.4 96 368 96h-80C182 96 96 182 96 288c0 7 .8 13.7 1.5 20.5C161.3 262.8 253.4 224 384 224c8.8 0 16 7.2 16 16s-7.2 16-16 16C132.6 256 26 410.1 2.4 468c-6.6 16.3 1.2 34.9 17.5 41.6 16.4 6.8 35-1.1 41.8-17.3 1.5-3.6 20.9-47.9 71.9-90.6 32.4 43.9 94 85.8 174.9 77.2C465.5 467.5 576 326.7 576 154.3c0-50.2-10.8-102.2-29.8-144.6z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M489.038 22.963C465.944-.13 434.648-5.93 413.947 6.129c-58.906 34.312-181.25-53.077-321.073 86.746S40.441 355.041 6.129 413.945c-12.059 20.702-6.26 51.999 16.833 75.093 23.095 23.095 54.392 28.891 75.095 16.832 58.901-34.31 181.246 53.079 321.068-86.743S471.56 156.96 505.871 98.056c12.059-20.702 6.261-51.999-16.833-75.093zM243.881 95.522c-58.189 14.547-133.808 90.155-148.358 148.358-1.817 7.27-8.342 12.124-15.511 12.124-1.284 0-2.59-.156-3.893-.481-8.572-2.144-13.784-10.83-11.642-19.403C81.901 166.427 166.316 81.93 236.119 64.478c8.575-2.143 17.261 3.069 19.403 11.642s-3.069 17.259-11.641 19.402z\"],\n    \"less-than\": [384, 512, [], \"f536\", \"M365.46 357.74L147.04 255.89l218.47-101.88c16.02-7.47 22.95-26.51 15.48-42.53l-13.52-29C360 66.46 340.96 59.53 324.94 67L18.48 209.91a32.014 32.014 0 0 0-18.48 29v34.24c0 12.44 7.21 23.75 18.48 29l306.31 142.83c16.06 7.49 35.15.54 42.64-15.52l13.56-29.08c7.49-16.06.54-35.15-15.53-42.64z\"],\n    \"less-than-equal\": [448, 512, [], \"f537\", \"M54.98 214.2l301.41 119.87c18.39 6.03 38.71-2.54 45.38-19.15l12.09-30.08c6.68-16.61-2.82-34.97-21.21-41l-175.44-68.05 175.56-68.09c18.29-6 27.74-24.27 21.1-40.79l-12.03-29.92c-6.64-16.53-26.86-25.06-45.15-19.06L54.98 137.89C41.21 142.41 32 154.5 32 168.07v15.96c0 13.56 9.21 25.65 22.98 30.17zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"level-down-alt\": [320, 512, [], \"f3be\", \"M313.553 392.331L209.587 504.334c-9.485 10.214-25.676 10.229-35.174 0L70.438 392.331C56.232 377.031 67.062 352 88.025 352H152V80H68.024a11.996 11.996 0 0 1-8.485-3.515l-56-56C-4.021 12.926 1.333 0 12.024 0H208c13.255 0 24 10.745 24 24v328h63.966c20.878 0 31.851 24.969 17.587 40.331z\"],\n    \"level-up-alt\": [320, 512, [], \"f3bf\", \"M313.553 119.669L209.587 7.666c-9.485-10.214-25.676-10.229-35.174 0L70.438 119.669C56.232 134.969 67.062 160 88.025 160H152v272H68.024a11.996 11.996 0 0 0-8.485 3.515l-56 56C-4.021 499.074 1.333 512 12.024 512H208c13.255 0 24-10.745 24-24V160h63.966c20.878 0 31.851-24.969 17.587-40.331z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm173.696 119.559l-63.399 63.399c-10.987-18.559-26.67-34.252-45.255-45.255l63.399-63.399a218.396 218.396 0 0 1 45.255 45.255zM256 352c-53.019 0-96-42.981-96-96s42.981-96 96-96 96 42.981 96 96-42.981 96-96 96zM127.559 82.304l63.399 63.399c-18.559 10.987-34.252 26.67-45.255 45.255l-63.399-63.399a218.372 218.372 0 0 1 45.255-45.255zM82.304 384.441l63.399-63.399c10.987 18.559 26.67 34.252 45.255 45.255l-63.399 63.399a218.396 218.396 0 0 1-45.255-45.255zm302.137 45.255l-63.399-63.399c18.559-10.987 34.252-26.67 45.255-45.255l63.399 63.399a218.403 218.403 0 0 1-45.255 45.255z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M96.06 454.35c.01 6.29 1.87 12.45 5.36 17.69l17.09 25.69a31.99 31.99 0 0 0 26.64 14.28h61.71a31.99 31.99 0 0 0 26.64-14.28l17.09-25.69a31.989 31.989 0 0 0 5.36-17.69l.04-38.35H96.01l.05 38.35zM0 176c0 44.37 16.45 84.85 43.56 115.78 16.52 18.85 42.36 58.23 52.21 91.45.04.26.07.52.11.78h160.24c.04-.26.07-.51.11-.78 9.85-33.22 35.69-72.6 52.21-91.45C335.55 260.85 352 220.37 352 176 352 78.61 272.91-.3 175.45 0 73.44.31 0 82.97 0 176zm176-80c-44.11 0-80 35.89-80 80 0 8.84-7.16 16-16 16s-16-7.16-16-16c0-61.76 50.24-112 112-112 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"link\": [512, 512, [], \"f0c1\", \"M326.612 185.391c59.747 59.809 58.927 155.698.36 214.59-.11.12-.24.25-.36.37l-67.2 67.2c-59.27 59.27-155.699 59.262-214.96 0-59.27-59.26-59.27-155.7 0-214.96l37.106-37.106c9.84-9.84 26.786-3.3 27.294 10.606.648 17.722 3.826 35.527 9.69 52.721 1.986 5.822.567 12.262-3.783 16.612l-13.087 13.087c-28.026 28.026-28.905 73.66-1.155 101.96 28.024 28.579 74.086 28.749 102.325.51l67.2-67.19c28.191-28.191 28.073-73.757 0-101.83-3.701-3.694-7.429-6.564-10.341-8.569a16.037 16.037 0 0 1-6.947-12.606c-.396-10.567 3.348-21.456 11.698-29.806l21.054-21.055c5.521-5.521 14.182-6.199 20.584-1.731a152.482 152.482 0 0 1 20.522 17.197zM467.547 44.449c-59.261-59.262-155.69-59.27-214.96 0l-67.2 67.2c-.12.12-.25.25-.36.37-58.566 58.892-59.387 154.781.36 214.59a152.454 152.454 0 0 0 20.521 17.196c6.402 4.468 15.064 3.789 20.584-1.731l21.054-21.055c8.35-8.35 12.094-19.239 11.698-29.806a16.037 16.037 0 0 0-6.947-12.606c-2.912-2.005-6.64-4.875-10.341-8.569-28.073-28.073-28.191-73.639 0-101.83l67.2-67.19c28.239-28.239 74.3-28.069 102.325.51 27.75 28.3 26.872 73.934-1.155 101.96l-13.087 13.087c-4.35 4.35-5.769 10.79-3.783 16.612 5.864 17.194 9.042 34.999 9.69 52.721.509 13.906 17.454 20.446 27.294 10.606l37.106-37.106c59.271-59.259 59.271-155.699.001-214.959z\"],\n    \"lira-sign\": [384, 512, [], \"f195\", \"M371.994 256h-48.019C317.64 256 312 260.912 312 267.246 312 368 230.179 416 144 416V256.781l134.603-29.912A12 12 0 0 0 288 215.155v-40.976c0-7.677-7.109-13.38-14.603-11.714L144 191.219V160.78l134.603-29.912A12 12 0 0 0 288 119.154V78.179c0-7.677-7.109-13.38-14.603-11.714L144 95.219V44c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v68.997L9.397 125.131A12 12 0 0 0 0 136.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 178.558v30.439L9.397 221.131A12 12 0 0 0 0 232.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 274.558V468c0 6.627 5.373 12 12 12h79.583c134.091 0 223.255-77.834 228.408-211.592.261-6.782-5.211-12.408-11.997-12.408z\"],\n    \"list\": [512, 512, [], \"f03a\", \"M80 368H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm0-320H16A16 16 0 0 0 0 64v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16V64a16 16 0 0 0-16-16zm0 160H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm416 176H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM128 120c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm288-136v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12z\"],\n    \"list-ol\": [512, 512, [], \"f0cb\", \"M61.77 401l17.5-20.15a19.92 19.92 0 0 0 5.07-14.19v-3.31C84.34 356 80.5 352 73 352H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h22.83a157.41 157.41 0 0 0-11 12.31l-5.61 7c-4 5.07-5.25 10.13-2.8 14.88l1.05 1.93c3 5.76 6.29 7.88 12.25 7.88h4.73c10.33 0 15.94 2.44 15.94 9.09 0 4.72-4.2 8.22-14.36 8.22a41.54 41.54 0 0 1-15.47-3.12c-6.49-3.88-11.74-3.5-15.6 3.12l-5.59 9.31c-3.72 6.13-3.19 11.72 2.63 15.94 7.71 4.69 20.38 9.44 37 9.44 34.16 0 48.5-22.75 48.5-44.12-.03-14.38-9.12-29.76-28.73-34.88zM496 224H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h64a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H64V40a8 8 0 0 0-8-8H32a8 8 0 0 0-7.14 4.42l-8 16A8 8 0 0 0 24 64h8v64H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8zm-3.91 160H80a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H41.32c3.29-10.29 48.34-18.68 48.34-56.44 0-29.06-25-39.56-44.47-39.56-21.36 0-33.8 10-40.46 18.75-4.37 5.59-3 10.84 2.8 15.37l8.58 6.88c5.61 4.56 11 2.47 16.12-2.44a13.44 13.44 0 0 1 9.46-3.84c3.33 0 9.28 1.56 9.28 8.75C51 248.19 0 257.31 0 304.59v4C0 316 5.08 320 12.09 320z\"],\n    \"list-ul\": [512, 512, [], \"f0ca\", \"M48 48a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm448 16H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"location-arrow\": [512, 512, [], \"f124\", \"M444.52 3.52L28.74 195.42c-47.97 22.39-31.98 92.75 19.19 92.75h175.91v175.91c0 51.17 70.36 67.17 92.75 19.19l191.9-415.78c15.99-38.39-25.59-79.97-63.97-63.97z\"],\n    \"lock\": [448, 512, [], \"f023\", \"M400 224h-24v-72C376 68.2 307.8 0 224 0S72 68.2 72 152v72H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48zm-104 0H152v-72c0-39.7 32.3-72 72-72s72 32.3 72 72v72z\"],\n    \"lock-open\": [576, 512, [], \"f3c1\", \"M423.5 0C339.5.3 272 69.5 272 153.5V224H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48h-48v-71.1c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v80c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-80C576 68 507.5-.3 423.5 0z\"],\n    \"long-arrow-alt-down\": [256, 512, [], \"f309\", \"M168 345.941V44c0-6.627-5.373-12-12-12h-56c-6.627 0-12 5.373-12 12v301.941H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.569 9.373 33.941 0l86.059-86.059c15.119-15.119 4.411-40.971-16.971-40.971H168z\"],\n    \"long-arrow-alt-left\": [448, 512, [], \"f30a\", \"M134.059 296H436c6.627 0 12-5.373 12-12v-56c0-6.627-5.373-12-12-12H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.569 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296z\"],\n    \"long-arrow-alt-right\": [448, 512, [], \"f30b\", \"M313.941 216H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h301.941v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.569 0-33.941l-86.059-86.059c-15.119-15.119-40.971-4.411-40.971 16.971V216z\"],\n    \"long-arrow-alt-up\": [256, 512, [], \"f30c\", \"M88 166.059V468c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12V166.059h46.059c21.382 0 32.09-25.851 16.971-40.971l-86.059-86.059c-9.373-9.373-24.569-9.373-33.941 0l-86.059 86.059c-15.119 15.119-4.411 40.971 16.971 40.971H88z\"],\n    \"low-vision\": [576, 512, [], \"f2a8\", \"M569.344 231.631C512.96 135.949 407.81 72 288 72c-28.468 0-56.102 3.619-82.451 10.409L152.778 10.24c-7.601-10.858-22.564-13.5-33.423-5.9l-13.114 9.178c-10.86 7.601-13.502 22.566-5.9 33.426l43.131 58.395C89.449 131.73 40.228 174.683 6.682 231.581c-.01.017-.023.033-.034.05-8.765 14.875-8.964 33.528 0 48.739 38.5 65.332 99.742 115.862 172.859 141.349L55.316 244.302A272.194 272.194 0 0 1 83.61 208.39l119.4 170.58h.01l40.63 58.04a330.055 330.055 0 0 0 78.94 1.17l-189.98-271.4a277.628 277.628 0 0 1 38.777-21.563l251.836 356.544c7.601 10.858 22.564 13.499 33.423 5.9l13.114-9.178c10.86-7.601 13.502-22.567 5.9-33.426l-43.12-58.377-.007-.009c57.161-27.978 104.835-72.04 136.81-126.301a47.938 47.938 0 0 0 .001-48.739zM390.026 345.94l-19.066-27.23c24.682-32.567 27.711-76.353 8.8-111.68v.03c0 23.65-19.17 42.82-42.82 42.82-23.828 0-42.82-19.349-42.82-42.82 0-23.65 19.17-42.82 42.82-42.82h.03c-24.75-13.249-53.522-15.643-79.51-7.68l-19.068-27.237C253.758 123.306 270.488 120 288 120c75.162 0 136 60.826 136 136 0 34.504-12.833 65.975-33.974 89.94z\"],\n    \"luggage-cart\": [640, 512, [], \"f59d\", \"M224 320h32V96h-32c-17.67 0-32 14.33-32 32v160c0 17.67 14.33 32 32 32zm352-32V128c0-17.67-14.33-32-32-32h-32v224h32c17.67 0 32-14.33 32-32zm48 96H128V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h48v368c0 8.84 7.16 16 16 16h82.94c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16h197.88c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM480 96V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v272h192V96zm-48 0h-96V48h96v48z\"],\n    \"magic\": [512, 512, [], \"f0d0\", \"M224 96l16-32 32-16-32-16-16-32-16 32-32 16 32 16 16 32zM80 160l26.66-53.33L160 80l-53.34-26.67L80 0 53.34 53.33 0 80l53.34 26.67L80 160zm352 128l-26.66 53.33L352 368l53.34 26.67L432 448l26.66-53.33L512 368l-53.34-26.67L432 288zm70.62-193.77L417.77 9.38C411.53 3.12 403.34 0 395.15 0c-8.19 0-16.38 3.12-22.63 9.38L9.38 372.52c-12.5 12.5-12.5 32.76 0 45.25l84.85 84.85c6.25 6.25 14.44 9.37 22.62 9.37 8.19 0 16.38-3.12 22.63-9.37l363.14-363.15c12.5-12.48 12.5-32.75 0-45.24zM359.45 203.46l-50.91-50.91 86.6-86.6 50.91 50.91-86.6 86.6z\"],\n    \"magnet\": [512, 512, [], \"f076\", \"M164.07 148.1H12a12 12 0 0 1-12-12v-80a36 36 0 0 1 36-36h104a36 36 0 0 1 36 36v80a11.89 11.89 0 0 1-11.93 12zm347.93-12V56a36 36 0 0 0-36-36H372a36 36 0 0 0-36 36v80a12 12 0 0 0 12 12h152a11.89 11.89 0 0 0 12-11.9zm-164 44a12 12 0 0 0-12 12v52c0 128.1-160 127.9-160 0v-52a12 12 0 0 0-12-12H12.1a12 12 0 0 0-12 12.1c.1 21.4.6 40.3 0 53.3 0 150.6 136.17 246.6 256.75 246.6s255-96 255-246.7c-.6-12.8-.2-33 0-53.2a12 12 0 0 0-12-12.1z\"],\n    \"mail-bulk\": [576, 512, [], \"f674\", \"M160 448c-25.6 0-51.2-22.4-64-32-64-44.8-83.2-60.8-96-70.4V480c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V345.6c-12.8 9.6-32 25.6-96 70.4-12.8 9.6-38.4 32-64 32zm128-192H32c-17.67 0-32 14.33-32 32v16c25.6 19.2 22.4 19.2 115.2 86.4 9.6 6.4 28.8 25.6 44.8 25.6s35.2-19.2 44.8-22.4c92.8-67.2 89.6-67.2 115.2-86.4V288c0-17.67-14.33-32-32-32zm256-96H224c-17.67 0-32 14.33-32 32v32h96c33.21 0 60.59 25.42 63.71 57.82l.29-.22V416h192c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zm-32 128h-64v-64h64v64zm-352-96c0-35.29 28.71-64 64-64h224V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v192h96v-32z\"],\n    \"male\": [192, 512, [], \"f183\", \"M96 0c35.346 0 64 28.654 64 64s-28.654 64-64 64-64-28.654-64-64S60.654 0 96 0m48 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H48c-26.51 0-48 21.49-48 48v136c0 13.255 10.745 24 24 24h16v136c0 13.255 10.745 24 24 24h64c13.255 0 24-10.745 24-24V352h16c13.255 0 24-10.745 24-24V192c0-26.51-21.49-48-48-48z\"],\n    \"map\": [576, 512, [], \"f279\", \"M0 117.66v346.32c0 11.32 11.43 19.06 21.94 14.86L160 416V32L20.12 87.95A32.006 32.006 0 0 0 0 117.66zM192 416l192 64V96L192 32v384zM554.06 33.16L416 96v384l139.88-55.95A31.996 31.996 0 0 0 576 394.34V48.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked\": [576, 512, [], \"f59f\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked-alt\": [576, 512, [], \"f5a0\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zm0 168c-23.2 0-42-18.8-42-42s18.8-42 42-42 42 18.8 42 42-18.8 42-42 42zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marker\": [384, 512, [], \"f041\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0z\"],\n    \"map-marker-alt\": [384, 512, [], \"f3c5\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0zM192 272c44.183 0 80-35.817 80-80s-35.817-80-80-80-80 35.817-80 80 35.817 80 80 80z\"],\n    \"map-pin\": [288, 512, [], \"f276\", \"M112 316.94v156.69l22.02 33.02c4.75 7.12 15.22 7.12 19.97 0L176 473.63V316.94c-10.39 1.92-21.06 3.06-32 3.06s-21.61-1.14-32-3.06zM144 0C64.47 0 0 64.47 0 144s64.47 144 144 144 144-64.47 144-144S223.53 0 144 0zm0 76c-37.5 0-68 30.5-68 68 0 6.62-5.38 12-12 12s-12-5.38-12-12c0-50.73 41.28-92 92-92 6.62 0 12 5.38 12 12s-5.38 12-12 12z\"],\n    \"map-signs\": [512, 512, [], \"f277\", \"M507.31 84.69L464 41.37c-6-6-14.14-9.37-22.63-9.37H288V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v16H56c-13.25 0-24 10.75-24 24v80c0 13.25 10.75 24 24 24h385.37c8.49 0 16.62-3.37 22.63-9.37l43.31-43.31c6.25-6.26 6.25-16.38 0-22.63zM224 496c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V384h-64v112zm232-272H288v-32h-64v32H70.63c-8.49 0-16.62 3.37-22.63 9.37L4.69 276.69c-6.25 6.25-6.25 16.38 0 22.63L48 342.63c6 6 14.14 9.37 22.63 9.37H456c13.25 0 24-10.75 24-24v-80c0-13.25-10.75-24-24-24z\"],\n    \"marker\": [512, 512, [], \"f5a1\", \"M93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l75.4-75.4-128.02-128.02-75.4 75.4zM485.49 26.51c-35.35-35.35-92.67-35.35-128.02 0l-21.76 21.76-36.56-36.55c-15.62-15.62-40.95-15.62-56.56 0L138.47 115.84c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0l87.15-87.15 19.59 19.59L191.98 192 320 320.02l165.49-165.49c35.35-35.35 35.35-92.66 0-128.02z\"],\n    \"mars\": [384, 512, [], \"f222\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c0-6.6-5.4-12-12-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-double\": [512, 512, [], \"f227\", \"M340 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C198.5 72.1 172.2 64 144 64 64.5 64 0 128.5 0 208s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.5 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 288c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80zm356-128.1h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7c-18.2-11.4-39-18.9-61.5-21.3-2.1 21.8-8.2 43.3-18.4 63.3 1.1 0 2.2-.1 3.2-.1 44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80c0-1.1 0-2.2.1-3.2-20 10.2-41.5 16.4-63.3 18.4C168.4 455.6 229.6 512 304 512c79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12v-79c0-6.7-5.4-12.1-12-12.1z\"],\n    \"mars-stroke\": [384, 512, [], \"f229\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-17.5 17.5-14.1-14.1c-4.7-4.7-12.3-4.7-17 0L224.5 133c-4.7 4.7-4.7 12.3 0 17l14.1 14.1-18 18c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l18-18 14.1 14.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L329.2 164l17.5-17.5 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c-.1-6.6-5.5-12-12.1-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-stroke-h\": [480, 512, [], \"f22b\", \"M476.2 247.5l-55.9-55.9c-7.6-7.6-20.5-2.2-20.5 8.5V224H376v-20c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v20h-27.6c-5.8-25.6-18.7-49.9-38.6-69.8C189.6 98 98.4 98 42.2 154.2c-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 19.9-19.9 32.8-44.2 38.6-69.8H312v20c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-20h23.9v23.9c0 10.7 12.9 16 20.5 8.5l55.9-55.9c4.6-4.7 4.6-12.3-.1-17zm-275.6 65.1c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mars-stroke-v\": [288, 512, [], \"f22a\", \"M245.8 234.2c-19.9-19.9-44.2-32.8-69.8-38.6v-25.4h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V81.4h23.9c10.7 0 16-12.9 8.5-20.5L152.5 5.1c-4.7-4.7-12.3-4.7-17 0L79.6 61c-7.6 7.6-2.2 20.5 8.5 20.5H112v24.7H92c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h20v25.4c-25.6 5.8-49.9 18.7-69.8 38.6-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 56.3-56.2 56.3-147.4 0-203.6zm-45.2 158.4c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mask\": [640, 512, [], \"f6fa\", \"M320.67 64c-442.6 0-357.57 384-158.46 384 39.9 0 77.47-20.69 101.42-55.86l25.73-37.79c15.66-22.99 46.97-22.99 62.63 0l25.73 37.79C401.66 427.31 439.23 448 479.13 448c189.86 0 290.63-384-158.46-384zM184 308.36c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05zm272 0c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05z\"],\n    \"medal\": [512, 512, [], \"f5a2\", \"M223.75 130.75L154.62 15.54A31.997 31.997 0 0 0 127.18 0H16.03C3.08 0-4.5 14.57 2.92 25.18l111.27 158.96c29.72-27.77 67.52-46.83 109.56-53.39zM495.97 0H384.82c-11.24 0-21.66 5.9-27.44 15.54l-69.13 115.21c42.04 6.56 79.84 25.62 109.56 53.38L509.08 25.18C516.5 14.57 508.92 0 495.97 0zM256 160c-97.2 0-176 78.8-176 176s78.8 176 176 176 176-78.8 176-176-78.8-176-176-176zm92.52 157.26l-37.93 36.96 8.97 52.22c1.6 9.36-8.26 16.51-16.65 12.09L256 393.88l-46.9 24.65c-8.4 4.45-18.25-2.74-16.65-12.09l8.97-52.22-37.93-36.96c-6.82-6.64-3.05-18.23 6.35-19.59l52.43-7.64 23.43-47.52c2.11-4.28 6.19-6.39 10.28-6.39 4.11 0 8.22 2.14 10.33 6.39l23.43 47.52 52.43 7.64c9.4 1.36 13.17 12.95 6.35 19.59z\"],\n    \"medkit\": [512, 512, [], \"f0fa\", \"M96 480h320V128h-32V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v48H96v352zm96-384h128v32H192V96zm320 80v256c0 26.51-21.49 48-48 48h-16V128h16c26.51 0 48 21.49 48 48zM64 480H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v352zm288-208v32c0 8.837-7.163 16-16 16h-48v48c0 8.837-7.163 16-16 16h-32c-8.837 0-16-7.163-16-16v-48h-48c-8.837 0-16-7.163-16-16v-32c0-8.837 7.163-16 16-16h48v-48c0-8.837 7.163-16 16-16h32c8.837 0 16 7.163 16 16v48h48c8.837 0 16 7.163 16 16z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm176 192H152c-21.2 0-21.2-32 0-32h192c21.2 0 21.2 32 0 32zm-16-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 224c0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64s-64-28.7-64-64zm224 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-112c-35.3 0-64-28.7-64-64 0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64z\"],\n    \"memory\": [640, 512, [], \"f538\", \"M640 130.94V96c0-17.67-14.33-32-32-32H32C14.33 64 0 78.33 0 96v34.94c18.6 6.61 32 24.19 32 45.06s-13.4 38.45-32 45.06V320h640v-98.94c-18.6-6.61-32-24.19-32-45.06s13.4-38.45 32-45.06zM224 256h-64V128h64v128zm128 0h-64V128h64v128zm128 0h-64V128h64v128zM0 448h64v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h64v-96H0v96z\"],\n    \"menorah\": [640, 512, [], \"f676\", \"M144 128h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm192 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm80-32c17.67 0 32-14.33 32-32S608 0 608 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S512 0 512 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S416 0 416 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S320 0 320 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S224 0 224 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S128 0 128 0 96 46.33 96 64s14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S32 0 32 0 0 46.33 0 64s14.33 32 32 32zm544 192c0 17.67-14.33 32-32 32H352V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v176H96c-17.67 0-32-14.33-32-32V144c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v144c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v144z\"],\n    \"mercury\": [288, 512, [], \"f223\", \"M288 208c0-44.2-19.9-83.7-51.2-110.1 2.5-1.8 4.9-3.8 7.2-5.8 24.7-21.2 39.8-48.8 43.2-78.8.9-7.1-4.7-13.3-11.9-13.3h-40.5C229 0 224.1 4.1 223 9.8c-2.4 12.5-9.6 24.3-20.7 33.8C187 56.8 166.3 64 144 64s-43-7.2-58.4-20.4C74.5 34.1 67.4 22.3 64.9 9.8 63.8 4.1 58.9 0 53.2 0H12.7C5.5 0-.1 6.2.8 13.3 4.2 43.4 19.2 71 44 92.2c2.3 2 4.7 3.9 7.2 5.8C19.9 124.3 0 163.8 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"meteor\": [512, 512, [], \"f753\", \"M491.2.7C452.5 12.3 379.4 35 303.5 62c-2.1-7-4-13.5-5.6-18.6-3-9.7-13.9-14.2-22.9-9.5C232.6 56 122.2 116.5 60.6 176.4c-1.1 1-2.5 2-3.5 3C19 217.4 0 267.3 0 317.2 0 367 19 416.9 57 455c38 38 87.9 57.1 137.8 57 49.9 0 99.8-19 137.9-57.1 1-1 2-2.4 3-3.5 59.8-61.6 120.4-172.1 142.5-214.4 4.7-9 .2-19.9-9.5-22.9-5.2-1.6-11.6-3.5-18.6-5.6 27-76 49.7-149 61.3-187.7C515 8.4 503.6-3 491.2.7zM192 448c-70.7 0-128-57.3-128-128s57.3-128 128-128 128 57.3 128 128-57.3 128-128 128zm-32-192c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm48 96c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16z\"],\n    \"microchip\": [512, 512, [], \"f2db\", \"M416 48v416c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h224c26.51 0 48 21.49 48 48zm96 58v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42V88h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zM30 376h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6z\"],\n    \"microphone\": [352, 512, [], \"f130\", \"M176 352c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96zm160-160h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16z\"],\n    \"microphone-alt\": [352, 512, [], \"f3c9\", \"M336 192h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16zM176 352c53.02 0 96-42.98 96-96h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96z\"],\n    \"microphone-alt-slash\": [640, 512, [], \"f539\", \"M633.82 458.1L476.26 336.33C488.74 312.21 496 284.98 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67h-43.67l-41.4-32H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.78c11.71-1.62 23.1-4.28 33.96-8.08l-50.4-38.96c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microphone-slash\": [640, 512, [], \"f131\", \"M633.82 458.1l-157.8-121.96C488.61 312.13 496 285.01 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67V96c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.77c11.66-1.6 22.85-4.54 33.67-8.31l-50.11-38.73c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microscope\": [512, 512, [], \"f610\", \"M160 320h12v16c0 8.84 7.16 16 16 16h40c8.84 0 16-7.16 16-16v-16h12c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32V16c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v16c-17.67 0-32 14.33-32 32v224c0 17.67 14.33 32 32 32zm304 128h-1.29C493.24 413.99 512 369.2 512 320c0-105.88-86.12-192-192-192v64c70.58 0 128 57.42 128 128s-57.42 128-128 128H48c-26.51 0-48 21.49-48 48 0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48zm-360-32h208c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8H104c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8z\"],\n    \"minus\": [448, 512, [], \"f068\", \"M416 208H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"minus-circle\": [512, 512, [], \"f056\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zM124 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H124z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM92 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H92z\"],\n    \"mitten\": [448, 512, [], \"f7b5\", \"M368 416H48c-8.8 0-16 7.2-16 16v64c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16zm57-209.1c-27.2-22.6-67.5-19-90.1 8.2l-20.9 25-29.6-128.4c-18-77.5-95.4-125.9-172.8-108C34.2 21.6-14.2 98.9 3.7 176.4L51.6 384h309l72.5-87c22.7-27.2 19-67.5-8.1-90.1z\"],\n    \"mobile\": [320, 512, [], \"f10b\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"mobile-alt\": [320, 512, [], \"f3cd\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm112-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v312z\"],\n    \"money-bill\": [640, 512, [], \"f0d6\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 176c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 48h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M352 288h-16v-88c0-4.42-3.58-8-8-8h-13.58c-4.74 0-9.37 1.4-13.31 4.03l-15.33 10.22a7.994 7.994 0 0 0-2.22 11.09l8.88 13.31a7.994 7.994 0 0 0 11.09 2.22l.47-.31V288h-16c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8h64c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 192c-53.02 0-96-50.15-96-112 0-61.86 42.98-112 96-112s96 50.14 96 112c0 61.87-43 112-96 112zm272 32h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-wave\": [640, 512, [], \"f53a\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM48 132.22c20.12 5.04 41.12 7.57 62.72 8.93C104.84 170.54 79 192.69 48 192.69v-60.47zm0 285v-47.78c34.37 0 62.18 27.27 63.71 61.4-22.53-1.81-43.59-6.31-63.71-13.62zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 27.78c-17.52-4.39-35.71-6.85-54.32-8.44 5.87-26.08 27.5-45.88 54.32-49.28v57.72zm0-236.11c-30.89-3.91-54.86-29.7-55.81-61.55 19.54 2.17 38.09 6.23 55.81 12.66v48.89z\"],\n    \"money-bill-wave-alt\": [640, 512, [], \"f53b\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96z\"],\n    \"money-check\": [640, 512, [], \"f53c\", \"M0 448c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128H0v320zm448-208c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-32zm0 120c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H456c-4.42 0-8-3.58-8-8v-16zM64 264c0-4.42 3.58-8 8-8h304c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm0 96c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zM624 32H16C7.16 32 0 39.16 0 48v48h640V48c0-8.84-7.16-16-16-16z\"],\n    \"money-check-alt\": [640, 512, [], \"f53d\", \"M608 32H32C14.33 32 0 46.33 0 64v384c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM176 327.88V344c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V152c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07zM416 312c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm160 0c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h272c4.42 0 8 3.58 8 8v16z\"],\n    \"monument\": [384, 512, [], \"f5a6\", \"M368 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h352c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-78.86-347.26a31.97 31.97 0 0 0-9.21-19.44L203.31 4.69c-6.25-6.25-16.38-6.25-22.63 0l-76.6 76.61a31.97 31.97 0 0 0-9.21 19.44L64 416h256l-30.86-315.26zM240 307.2c0 6.4-6.4 12.8-12.8 12.8h-70.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h70.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M283.211 512c78.962 0 151.079-35.925 198.857-94.792 7.068-8.708-.639-21.43-11.562-19.35-124.203 23.654-238.262-71.576-238.262-196.954 0-72.222 38.662-138.635 101.498-174.394 9.686-5.512 7.25-20.197-3.756-22.23A258.156 258.156 0 0 0 283.211 0c-141.309 0-256 114.511-256 256 0 141.309 114.511 256 256 256z\"],\n    \"mortar-pestle\": [512, 512, [], \"f5a7\", \"M501.54 60.91c17.22-17.22 12.51-46.25-9.27-57.14a35.696 35.696 0 0 0-37.37 3.37L251.09 160h151.37l99.08-99.09zM496 192H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c0 80.98 50.2 150.11 121.13 178.32-12.76 16.87-21.72 36.8-24.95 58.69-1.46 9.92 6.04 18.98 16.07 18.98h223.5c10.03 0 17.53-9.06 16.07-18.98-3.22-21.89-12.18-41.82-24.95-58.69C429.8 406.11 480 336.98 480 256h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"mosque\": [640, 512, [], \"f678\", \"M0 480c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V160H0v320zm579.16-192c17.86-17.39 28.84-37.34 28.84-58.91 0-52.86-41.79-93.79-87.92-122.9-41.94-26.47-80.63-57.77-111.96-96.22L400 0l-8.12 9.97c-31.33 38.45-70.01 69.76-111.96 96.22C233.79 135.3 192 176.23 192 229.09c0 21.57 10.98 41.52 28.84 58.91h358.32zM608 320H192c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h32v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h64v-72c0-48 48-72 48-72s48 24 48 72v72h64v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h32c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM64 0S0 32 0 96v32h128V96c0-64-64-96-64-96z\"],\n    \"motorcycle\": [640, 512, [], \"f21c\", \"M512.9 192c-14.9-.1-29.1 2.3-42.4 6.9L437.6 144H520c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24h-45.3c-6.8 0-13.3 2.9-17.8 7.9l-37.5 41.7-22.8-38C392.2 68.4 384.4 64 376 64h-80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h66.4l19.2 32H227.9c-17.7-23.1-44.9-40-99.9-40H72.5C59 104 47.7 115 48 128.5c.2 13 10.9 23.5 24 23.5h56c24.5 0 38.7 10.9 47.8 24.8l-11.3 20.5c-13-3.9-26.9-5.7-41.3-5.2C55.9 194.5 1.6 249.6 0 317c-1.6 72.1 56.3 131 128 131 59.6 0 109.7-40.8 124-96h84.2c13.7 0 24.6-11.4 24-25.1-2.1-47.1 17.5-93.7 56.2-125l12.5 20.8c-27.6 23.7-45.1 58.9-44.8 98.2.5 69.6 57.2 126.5 126.8 127.1 71.6.7 129.8-57.5 129.2-129.1-.7-69.6-57.6-126.4-127.2-126.9zM128 400c-44.1 0-80-35.9-80-80s35.9-80 80-80c4.2 0 8.4.3 12.5 1L99 316.4c-8.8 16 2.8 35.6 21 35.6h81.3c-12.4 28.2-40.6 48-73.3 48zm463.9-75.6c-2.2 40.6-35 73.4-75.5 75.5-46.1 2.5-84.4-34.3-84.4-79.9 0-21.4 8.4-40.8 22.1-55.1l49.4 82.4c4.5 7.6 14.4 10 22 5.5l13.7-8.2c7.6-4.5 10-14.4 5.5-22l-48.6-80.9c5.2-1.1 10.5-1.6 15.9-1.6 45.6-.1 82.3 38.2 79.9 84.3z\"],\n    \"mountain\": [640, 512, [], \"f6fc\", \"M634.92 462.7l-288-448C341.03 5.54 330.89 0 320 0s-21.03 5.54-26.92 14.7l-288 448a32.001 32.001 0 0 0-1.17 32.64A32.004 32.004 0 0 0 32 512h576c11.71 0 22.48-6.39 28.09-16.67a31.983 31.983 0 0 0-1.17-32.63zM320 91.18L405.39 224H320l-64 64-38.06-38.06L320 91.18z\"],\n    \"mouse-pointer\": [320, 512, [], \"f245\", \"M302.189 329.126H196.105l55.831 135.993c3.889 9.428-.555 19.999-9.444 23.999l-49.165 21.427c-9.165 4-19.443-.571-23.332-9.714l-53.053-129.136-86.664 89.138C18.729 472.71 0 463.554 0 447.977V18.299C0 1.899 19.921-6.096 30.277 5.443l284.412 292.542c11.472 11.179 3.007 31.141-12.5 31.141z\"],\n    \"mug-hot\": [512, 512, [], \"f7b6\", \"M127.1 146.5c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C111.8 5.9 105 0 96.8 0H80.4C70.6 0 63 8.5 64.1 18c3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zm112 0c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C223.8 5.9 217 0 208.8 0h-16.4c-9.8 0-17.5 8.5-16.3 18 3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zM400 192H32c-17.7 0-32 14.3-32 32v192c0 53 43 96 96 96h192c53 0 96-43 96-96h16c61.8 0 112-50.2 112-112s-50.2-112-112-112zm0 160h-16v-96h16c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"music\": [512, 512, [], \"f001\", \"M511.99 32.01c0-21.71-21.1-37.01-41.6-30.51L150.4 96c-13.3 4.2-22.4 16.5-22.4 30.5v261.42c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64V214.31l256-75.02v184.63c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64l-.01-351.99z\"],\n    \"network-wired\": [640, 512, [], \"f6ff\", \"M640 264v-16c0-8.84-7.16-16-16-16H344v-40h72c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H224c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h72v40H16c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h104v40H64c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h304v40h-56c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h104c8.84 0 16-7.16 16-16zM256 128V64h128v64H256zm-64 320H96v-64h96v64zm352 0h-96v-64h96v64z\"],\n    \"neuter\": [288, 512, [], \"f22c\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V468c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V316.4c64.1-14.5 112-71.9 112-140.4zm-144 80c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H88c-13.255 0-24 10.745-24 24v8H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h472c26.51 0 48-21.49 48-48V88c0-13.255-10.745-24-24-24zM56 400a8 8 0 0 1-8-8V144h16v248a8 8 0 0 1-8 8zm236-16H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm-208-96H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm0-96H140c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h360c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12z\"],\n    \"not-equal\": [448, 512, [], \"f53e\", \"M416 208c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32h-23.88l51.87-66.81c5.37-7.02 4.04-17.06-2.97-22.43L415.61 3.3c-7.02-5.38-17.06-4.04-22.44 2.97L311.09 112H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h204.56l-74.53 96H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h55.49l-51.87 66.81c-5.37 7.01-4.04 17.05 2.97 22.43L64 508.7c7.02 5.38 17.06 4.04 22.43-2.97L168.52 400H416c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32H243.05l74.53-96H416z\"],\n    \"notes-medical\": [384, 512, [], \"f481\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm96 304c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm0-192c0 4.4-3.6 8-8 8H104c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M480 128V96h20c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v20H64V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v40c0 6.627 5.373 12 12 12h20v320H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-20h384v20c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-20V128zM96 276V140c0-6.627 5.373-12 12-12h168c6.627 0 12 5.373 12 12v136c0 6.627-5.373 12-12 12H108c-6.627 0-12-5.373-12-12zm320 96c0 6.627-5.373 12-12 12H236c-6.627 0-12-5.373-12-12v-52h72c13.255 0 24-10.745 24-24v-72h84c6.627 0 12 5.373 12 12v136z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M64 320v26a6 6 0 0 1-6 6H6a6 6 0 0 1-6-6v-52a6 6 0 0 1 6-6h26V96H6a6 6 0 0 1-6-6V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v26h288V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-26v192h26a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-52a6 6 0 0 1-6-6v-26H64zm480-64v-32h26a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-52a6 6 0 0 0-6 6v26H408v72h8c13.255 0 24 10.745 24 24v64c0 13.255-10.745 24-24 24h-64c-13.255 0-24-10.745-24-24v-8H192v72h-26a6 6 0 0 0-6 6v52a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-26h288v26a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-26V256z\"],\n    \"oil-can\": [640, 512, [], \"f613\", \"M629.8 160.31L416 224l-50.49-25.24a64.07 64.07 0 0 0-28.62-6.76H280v-48h56c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h56v48h-56L37.72 166.86a31.9 31.9 0 0 0-5.79-.53C14.67 166.33 0 180.36 0 198.34v94.95c0 15.46 11.06 28.72 26.28 31.48L96 337.46V384c0 17.67 14.33 32 32 32h274.63c8.55 0 16.75-3.42 22.76-9.51l212.26-214.75c1.5-1.5 2.34-3.54 2.34-5.66V168c.01-5.31-5.08-9.15-10.19-7.69zM96 288.67l-48-8.73v-62.43l48 8.73v62.43zm453.33 84.66c0 23.56 19.1 42.67 42.67 42.67s42.67-19.1 42.67-42.67S592 288 592 288s-42.67 61.77-42.67 85.33z\"],\n    \"om\": [512, 512, [], \"f679\", \"M360.6 60.94a10.43 10.43 0 0 0 14.76 0l21.57-21.56a10.43 10.43 0 0 0 0-14.76L375.35 3.06c-4.08-4.07-10.68-4.07-14.76 0l-21.57 21.56a10.43 10.43 0 0 0 0 14.76l21.58 21.56zM412.11 192c-26.69 0-51.77 10.39-70.64 29.25l-24.25 24.25c-6.78 6.77-15.78 10.5-25.38 10.5H245c10.54-22.1 14.17-48.11 7.73-75.23-10.1-42.55-46.36-76.11-89.52-83.19-36.15-5.93-70.9 5.04-96.01 28.78-7.36 6.96-6.97 18.85 1.12 24.93l26.15 19.63c5.72 4.3 13.66 4.32 19.2-.21 8.45-6.9 19.02-10.71 30.27-10.71 26.47 0 48.01 21.53 48.01 48s-21.54 48-48.01 48h-31.9c-11.96 0-19.74 12.58-14.39 23.28l16.09 32.17c2.53 5.06 7.6 8.1 13.17 8.55h33.03c35.3 0 64.01 28.7 64.01 64s-28.71 64-64.01 64c-96.02 0-122.35-54.02-145.15-92.03-4.53-7.55-14.77-3.58-14.79 5.22C-.09 416 41.13 512 159.94 512c70.59 0 128.02-57.42 128.02-128 0-23.42-6.78-45.1-17.81-64h21.69c26.69 0 51.77-10.39 70.64-29.25l24.25-24.25c6.78-6.77 15.78-10.5 25.38-10.5 19.78 0 35.88 16.09 35.88 35.88V392c0 13.23-18.77 24-32.01 24-39.4 0-66.67-24.24-81.82-42.89-4.77-5.87-14.2-2.54-14.2 5.02V416s0 64 96.02 64c48.54 0 96.02-39.47 96.02-88V291.88c0-55.08-44.8-99.88-99.89-99.88zm42.18-124.73c-85.55 65.12-169.05 2.75-172.58.05-6.02-4.62-14.44-4.38-20.14.55-5.74 4.92-7.27 13.17-3.66 19.8 1.61 2.95 40.37 72.34 118.8 72.34 79.92 0 98.78-31.36 101.75-37.66 1.02-2.12 1.53-4.47 1.53-6.83V80c0-13.22-15.14-20.69-25.7-12.73z\"],\n    \"otter\": [640, 512, [], \"f700\", \"M608 32h-32l-13.25-13.25A63.97 63.97 0 0 0 517.49 0H497c-11.14 0-22.08 2.91-31.75 8.43L312 96h-56C149.96 96 64 181.96 64 288v1.61c0 32.75-16 62.14-39.56 84.89-18.19 17.58-28.1 43.68-23.19 71.8 6.76 38.8 42.9 65.7 82.28 65.7H192c17.67 0 32-14.33 32-32s-14.33-32-32-32H80c-8.83 0-16-7.17-16-16s7.17-16 16-16h224c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-64l149.49-80.5L448 416h80c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-28.22l-55.11-110.21L521.14 192H544c53.02 0 96-42.98 96-96V64c0-17.67-14.33-32-32-32zm-96 16c8.84 0 16 7.16 16 16s-7.16 16-16 16-16-7.16-16-16 7.16-16 16-16zm32 96h-34.96L407.2 198.84l-13.77-27.55L512 112h77.05c-6.62 18.58-24.22 32-45.05 32z\"],\n    \"outdent\": [448, 512, [], \"f03b\", \"M100.69 363.29c10 10 27.31 2.93 27.31-11.31V160c0-14.32-17.33-21.31-27.31-11.31l-96 96a16 16 0 0 0 0 22.62zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"pager\": [512, 512, [], \"f815\", \"M448 64H64a64 64 0 0 0-64 64v256a64 64 0 0 0 64 64h384a64 64 0 0 0 64-64V128a64 64 0 0 0-64-64zM160 368H80a16 16 0 0 1-16-16v-16a16 16 0 0 1 16-16h80zm128-16a16 16 0 0 1-16 16h-80v-48h80a16 16 0 0 1 16 16zm160-128a32 32 0 0 1-32 32H96a32 32 0 0 1-32-32v-64a32 32 0 0 1 32-32h320a32 32 0 0 1 32 32z\"],\n    \"paint-brush\": [512, 512, [], \"f1fc\", \"M167.02 309.34c-40.12 2.58-76.53 17.86-97.19 72.3-2.35 6.21-8 9.98-14.59 9.98-11.11 0-45.46-27.67-55.25-34.35C0 439.62 37.93 512 128 512c75.86 0 128-43.77 128-120.19 0-3.11-.65-6.08-.97-9.13l-88.01-73.34zM457.89 0c-15.16 0-29.37 6.71-40.21 16.45C213.27 199.05 192 203.34 192 257.09c0 13.7 3.25 26.76 8.73 38.7l63.82 53.18c7.21 1.8 14.64 3.03 22.39 3.03 62.11 0 98.11-45.47 211.16-256.46 7.38-14.35 13.9-29.85 13.9-45.99C512 20.64 486 0 457.89 0z\"],\n    \"paint-roller\": [512, 512, [], \"f5aa\", \"M416 128V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32zm32-64v128c0 17.67-14.33 32-32 32H256c-35.35 0-64 28.65-64 64v32c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32v-32h160c53.02 0 96-42.98 96-96v-64c0-35.35-28.65-64-64-64z\"],\n    \"palette\": [512, 512, [], \"f53f\", \"M204.3 5C104.9 24.4 24.8 104.3 5.2 203.4c-37 187 131.7 326.4 258.8 306.7 41.2-6.4 61.4-54.6 42.5-91.7-23.1-45.4 9.9-98.4 60.9-98.4h79.7c35.8 0 64.8-29.6 64.9-65.3C511.5 97.1 368.1-26.9 204.3 5zM96 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm32-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128-64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"pallet\": [640, 512, [], \"f482\", \"M144 256h352c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H384v128l-64-32-64 32V0H144c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16zm480 128c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h48v64H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16h-48v-64h48zm-336 64H128v-64h160v64zm224 0H352v-64h160v64z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M476 3.2L12.5 270.6c-18.1 10.4-15.8 35.6 2.2 43.2L121 358.4l287.3-253.2c5.5-4.9 13.3 2.6 8.6 8.3L176 407v80.5c0 23.6 28.5 32.9 42.5 15.8L282 426l124.6 52.2c14.2 6 30.4-2.9 33-18.2l72-432C515 7.8 493.3-6.8 476 3.2z\"],\n    \"paperclip\": [448, 512, [], \"f0c6\", \"M43.246 466.142c-58.43-60.289-57.341-157.511 1.386-217.581L254.392 34c44.316-45.332 116.351-45.336 160.671 0 43.89 44.894 43.943 117.329 0 162.276L232.214 383.128c-29.855 30.537-78.633 30.111-107.982-.998-28.275-29.97-27.368-77.473 1.452-106.953l143.743-146.835c6.182-6.314 16.312-6.422 22.626-.241l22.861 22.379c6.315 6.182 6.422 16.312.241 22.626L171.427 319.927c-4.932 5.045-5.236 13.428-.648 18.292 4.372 4.634 11.245 4.711 15.688.165l182.849-186.851c19.613-20.062 19.613-52.725-.011-72.798-19.189-19.627-49.957-19.637-69.154 0L90.39 293.295c-34.763 35.56-35.299 93.12-1.191 128.313 34.01 35.093 88.985 35.137 123.058.286l172.06-175.999c6.177-6.319 16.307-6.433 22.626-.256l22.877 22.364c6.319 6.177 6.434 16.307.256 22.626l-172.06 175.998c-59.576 60.938-155.943 60.216-214.77-.485z\"],\n    \"parachute-box\": [512, 512, [], \"f4cd\", \"M511.9 175c-9.1-75.6-78.4-132.4-158.3-158.7C390 55.7 416 116.9 416 192h28.1L327.5 321.5c-2.5-.6-4.8-1.5-7.5-1.5h-48V192h112C384 76.8 315.1 0 256 0S128 76.8 128 192h112v128h-48c-2.7 0-5 .9-7.5 1.5L67.9 192H96c0-75.1 26-136.3 62.4-175.7C78.5 42.7 9.2 99.5.1 175c-1.1 9.1 6.8 17 16 17h8.7l136.7 151.9c-.7 2.6-1.6 5.2-1.6 8.1v128c0 17.7 14.3 32 32 32h128c17.7 0 32-14.3 32-32V352c0-2.9-.9-5.4-1.6-8.1L487.1 192h8.7c9.3 0 17.2-7.8 16.1-17z\"],\n    \"paragraph\": [448, 512, [], \"f1dd\", \"M448 48v32a16 16 0 0 1-16 16h-48v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V96h-32v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V352h-32a160 160 0 0 1 0-320h240a16 16 0 0 1 16 16z\"],\n    \"parking\": [448, 512, [], \"f540\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM240 320h-48v48c0 8.8-7.2 16-16 16h-32c-8.8 0-16-7.2-16-16V144c0-8.8 7.2-16 16-16h96c52.9 0 96 43.1 96 96s-43.1 96-96 96zm0-128h-48v64h48c17.6 0 32-14.4 32-32s-14.4-32-32-32z\"],\n    \"passport\": [448, 512, [], \"f5ab\", \"M129.62 176h39.09c1.49-27.03 6.54-51.35 14.21-70.41-27.71 13.24-48.02 39.19-53.3 70.41zm0 32c5.29 31.22 25.59 57.17 53.3 70.41-7.68-19.06-12.72-43.38-14.21-70.41h-39.09zM224 286.69c7.69-7.45 20.77-34.42 23.43-78.69h-46.87c2.67 44.26 15.75 71.24 23.44 78.69zM200.57 176h46.87c-2.66-44.26-15.74-71.24-23.43-78.69-7.7 7.45-20.78 34.43-23.44 78.69zm64.51 102.41c27.71-13.24 48.02-39.19 53.3-70.41h-39.09c-1.49 27.03-6.53 51.35-14.21 70.41zM416 0H64C28.65 0 0 28.65 0 64v384c0 35.35 28.65 64 64 64h352c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32zm-80 416H112c-8.8 0-16-7.2-16-16s7.2-16 16-16h224c8.8 0 16 7.2 16 16s-7.2 16-16 16zm-112-96c-70.69 0-128-57.31-128-128S153.31 64 224 64s128 57.31 128 128-57.31 128-128 128zm41.08-214.41c7.68 19.06 12.72 43.38 14.21 70.41h39.09c-5.28-31.22-25.59-57.17-53.3-70.41z\"],\n    \"pastafarianism\": [640, 512, [], \"f67b\", \"M624.54 347.67c-32.7-12.52-57.36 4.25-75.37 16.45-17.06 11.53-23.25 14.42-31.41 11.36-8.12-3.09-10.83-9.38-15.89-29.38-3.33-13.15-7.44-29.32-17.95-42.65 2.24-2.91 4.43-5.79 6.38-8.57C500.47 304.45 513.71 312 532 312c33.95 0 50.87-25.78 62.06-42.83 10.59-16.14 15-21.17 21.94-21.17 13.25 0 24-10.75 24-24s-10.75-24-24-24c-33.95 0-50.87 25.78-62.06 42.83-10.6 16.14-15 21.17-21.94 21.17-17.31 0-37.48-61.43-97.26-101.91l17.25-34.5C485.43 125.5 512 97.98 512 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 13.02 3.94 25.1 10.62 35.21l-18.15 36.3c-16.98-4.6-35.6-7.51-56.46-7.51s-39.49 2.91-56.46 7.51l-18.15-36.3C252.06 89.1 256 77.02 256 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 33.98 26.56 61.5 60.02 63.6l17.25 34.5C145.68 202.44 125.15 264 108 264c-6.94 0-11.34-5.03-21.94-21.17C74.88 225.78 57.96 200 24 200c-13.25 0-24 10.75-24 24s10.75 24 24 24c6.94 0 11.34 5.03 21.94 21.17C57.13 286.22 74.05 312 108 312c18.29 0 31.53-7.55 41.7-17.11 1.95 2.79 4.14 5.66 6.38 8.57-10.51 13.33-14.62 29.5-17.95 42.65-5.06 20-7.77 26.28-15.89 29.38-8.11 3.06-14.33.17-31.41-11.36-18.03-12.2-42.72-28.92-75.37-16.45-12.39 4.72-18.59 18.58-13.87 30.97 4.72 12.41 18.61 18.61 30.97 13.88 8.16-3.09 14.34-.19 31.39 11.36 13.55 9.16 30.83 20.86 52.42 20.84 7.17 0 14.83-1.28 22.97-4.39 32.66-12.44 39.98-41.33 45.33-62.44 2.21-8.72 3.99-14.49 5.95-18.87 16.62 13.61 36.95 25.88 61.64 34.17-9.96 37-32.18 90.8-60.26 90.8-13.25 0-24 10.75-24 24s10.75 24 24 24c66.74 0 97.05-88.63 107.42-129.14 6.69.6 13.42 1.14 20.58 1.14s13.89-.54 20.58-1.14C350.95 423.37 381.26 512 448 512c13.25 0 24-10.75 24-24s-10.75-24-24-24c-27.94 0-50.21-53.81-60.22-90.81 24.69-8.29 45-20.56 61.62-34.16 1.96 4.38 3.74 10.15 5.95 18.87 5.34 21.11 12.67 50 45.33 62.44 8.14 3.11 15.8 4.39 22.97 4.39 21.59 0 38.87-11.69 52.42-20.84 17.05-11.55 23.28-14.45 31.39-11.36 12.39 4.75 26.27-1.47 30.97-13.88 4.71-12.4-1.49-26.26-13.89-30.98zM448 48c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zm-256 0c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16z\"],\n    \"paste\": [448, 512, [], \"f0ea\", \"M128 184c0-30.879 25.122-56 56-56h136V56c0-13.255-10.745-24-24-24h-80.61C204.306 12.89 183.637 0 160 0s-44.306 12.89-55.39 32H24C10.745 32 0 42.745 0 56v336c0 13.255 10.745 24 24 24h104V184zm32-144c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24zm184 248h104v200c0 13.255-10.745 24-24 24H184c-13.255 0-24-10.745-24-24V184c0-13.255 10.745-24 24-24h136v104c0 13.2 10.8 24 24 24zm104-38.059V256h-96v-96h6.059a24 24 0 0 1 16.97 7.029l65.941 65.941a24.002 24.002 0 0 1 7.03 16.971z\"],\n    \"pause\": [448, 512, [], \"f04c\", \"M144 479H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h96c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zm304-48V79c0-26.5-21.5-48-48-48h-96c-26.5 0-48 21.5-48 48v352c0 26.5 21.5 48 48 48h96c26.5 0 48-21.5 48-48z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm-16 328c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160zm112 0c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160z\"],\n    \"paw\": [512, 512, [], \"f1b0\", \"M256 224c-79.41 0-192 122.76-192 200.25 0 34.9 26.81 55.75 71.74 55.75 48.84 0 81.09-25.08 120.26-25.08 39.51 0 71.85 25.08 120.26 25.08 44.93 0 71.74-20.85 71.74-55.75C448 346.76 335.41 224 256 224zm-147.28-12.61c-10.4-34.65-42.44-57.09-71.56-50.13-29.12 6.96-44.29 40.69-33.89 75.34 10.4 34.65 42.44 57.09 71.56 50.13 29.12-6.96 44.29-40.69 33.89-75.34zm84.72-20.78c30.94-8.14 46.42-49.94 34.58-93.36s-46.52-72.01-77.46-63.87-46.42 49.94-34.58 93.36c11.84 43.42 46.53 72.02 77.46 63.87zm281.39-29.34c-29.12-6.96-61.15 15.48-71.56 50.13-10.4 34.65 4.77 68.38 33.89 75.34 29.12 6.96 61.15-15.48 71.56-50.13 10.4-34.65-4.77-68.38-33.89-75.34zm-156.27 29.34c30.94 8.14 65.62-20.45 77.46-63.87 11.84-43.42-3.64-85.21-34.58-93.36s-65.62 20.45-77.46 63.87c-11.84 43.42 3.64 85.22 34.58 93.36z\"],\n    \"peace\": [496, 512, [], \"f67c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm184 248c0 31.93-8.2 61.97-22.57 88.17L280 240.63V74.97c86.23 15.21 152 90.5 152 181.03zM216 437.03c-33.86-5.97-64.49-21.2-89.29-43.02L216 322.57v114.46zm64-114.46L369.29 394c-24.8 21.82-55.43 37.05-89.29 43.02V322.57zm-64-247.6v165.66L86.57 344.17C72.2 317.97 64 287.93 64 256c0-90.53 65.77-165.82 152-181.03z\"],\n    \"pen\": [512, 512, [], \"f304\", \"M290.74 93.24l128.02 128.02-277.99 277.99-114.14 12.6C11.35 513.54-1.56 500.62.14 485.34l12.7-114.22 277.9-277.88zm207.2-19.06l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.76 18.75-49.16 0-67.91z\"],\n    \"pen-alt\": [512, 512, [], \"f305\", \"M497.94 74.17l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91zm-246.8-20.53c-15.62-15.62-40.94-15.62-56.56 0L75.8 172.43c-6.25 6.25-6.25 16.38 0 22.62l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l101.82-101.82 22.63 22.62L93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l196.79-196.79-82.77-82.77-84.85-84.85z\"],\n    \"pen-fancy\": [512, 512, [], \"f5ac\", \"M79.18 282.94a32.005 32.005 0 0 0-20.24 20.24L0 480l4.69 4.69 92.89-92.89c-.66-2.56-1.57-5.03-1.57-7.8 0-17.67 14.33-32 32-32s32 14.33 32 32-14.33 32-32 32c-2.77 0-5.24-.91-7.8-1.57l-92.89 92.89L32 512l176.82-58.94a31.983 31.983 0 0 0 20.24-20.24l33.07-84.07-98.88-98.88-84.07 33.07zM369.25 28.32L186.14 227.81l97.85 97.85 199.49-183.11C568.4 67.48 443.73-55.94 369.25 28.32z\"],\n    \"pen-nib\": [512, 512, [], \"f5ad\", \"M136.6 138.79a64.003 64.003 0 0 0-43.31 41.35L0 460l14.69 14.69L164.8 324.58c-2.99-6.26-4.8-13.18-4.8-20.58 0-26.51 21.49-48 48-48s48 21.49 48 48-21.49 48-48 48c-7.4 0-14.32-1.81-20.58-4.8L37.31 497.31 52 512l279.86-93.29a64.003 64.003 0 0 0 41.35-43.31L416 224 288 96l-151.4 42.79zm361.34-64.62l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91z\"],\n    \"pen-square\": [448, 512, [], \"f14b\", \"M400 480H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zM238.1 177.9L102.4 313.6l-6.3 57.1c-.8 7.6 5.6 14.1 13.3 13.3l57.1-6.3L302.2 242c2.3-2.3 2.3-6.1 0-8.5L246.7 178c-2.5-2.4-6.3-2.4-8.6-.1zM345 165.1L314.9 135c-9.4-9.4-24.6-9.4-33.9 0l-23.1 23.1c-2.3 2.3-2.3 6.1 0 8.5l55.5 55.5c2.3 2.3 6.1 2.3 8.5 0L345 199c9.3-9.3 9.3-24.5 0-33.9z\"],\n    \"pencil-alt\": [512, 512, [], \"f303\", \"M497.9 142.1l-46.1 46.1c-4.7 4.7-12.3 4.7-17 0l-111-111c-4.7-4.7-4.7-12.3 0-17l46.1-46.1c18.7-18.7 49.1-18.7 67.9 0l60.1 60.1c18.8 18.7 18.8 49.1 0 67.9zM284.2 99.8L21.6 362.4.4 483.9c-2.9 16.4 11.4 30.6 27.8 27.8l121.5-21.3 262.6-262.6c4.7-4.7 4.7-12.3 0-17l-111-111c-4.8-4.7-12.4-4.7-17.1 0zM124.1 339.9c-5.5-5.5-5.5-14.3 0-19.8l154-154c5.5-5.5 14.3-5.5 19.8 0s5.5 14.3 0 19.8l-154 154c-5.5 5.5-14.3 5.5-19.8 0zM88 424h48v36.3l-64.5 11.3-31.1-31.1L51.7 376H88v48z\"],\n    \"pencil-ruler\": [512, 512, [], \"f5ae\", \"M109.46 244.04l134.58-134.56-44.12-44.12-61.68 61.68a7.919 7.919 0 0 1-11.21 0l-11.21-11.21c-3.1-3.1-3.1-8.12 0-11.21l61.68-61.68-33.64-33.65C131.47-3.1 111.39-3.1 99 9.29L9.29 99c-12.38 12.39-12.39 32.47 0 44.86l100.17 100.18zm388.47-116.8c18.76-18.76 18.75-49.17 0-67.93l-45.25-45.25c-18.76-18.76-49.18-18.76-67.95 0l-46.02 46.01 113.2 113.2 46.02-46.03zM316.08 82.71l-297 296.96L.32 487.11c-2.53 14.49 10.09 27.11 24.59 24.56l107.45-18.84L429.28 195.9 316.08 82.71zm186.63 285.43l-33.64-33.64-61.68 61.68c-3.1 3.1-8.12 3.1-11.21 0l-11.21-11.21c-3.09-3.1-3.09-8.12 0-11.21l61.68-61.68-44.14-44.14L267.93 402.5l100.21 100.2c12.39 12.39 32.47 12.39 44.86 0l89.71-89.7c12.39-12.39 12.39-32.47 0-44.86z\"],\n    \"people-carry\": [640, 512, [], \"f4ce\", \"M128 96c26.5 0 48-21.5 48-48S154.5 0 128 0 80 21.5 80 48s21.5 48 48 48zm384 0c26.5 0 48-21.5 48-48S538.5 0 512 0s-48 21.5-48 48 21.5 48 48 48zm125.7 372.1l-44-110-41.1 46.4-2 18.2 27.7 69.2c5 12.5 17 20.1 29.7 20.1 4 0 8-.7 11.9-2.3 16.4-6.6 24.4-25.2 17.8-41.6zm-34.2-209.8L585 178.1c-4.6-20-18.6-36.8-37.5-44.9-18.5-8-39-6.7-56.1 3.3-22.7 13.4-39.7 34.5-48.1 59.4L432 229.8 416 240v-96c0-8.8-7.2-16-16-16H240c-8.8 0-16 7.2-16 16v96l-16.1-10.2-11.3-33.9c-8.3-25-25.4-46-48.1-59.4-17.2-10-37.6-11.3-56.1-3.3-18.9 8.1-32.9 24.9-37.5 44.9l-18.4 80.2c-4.6 20 .7 41.2 14.4 56.7l67.2 75.9 10.1 92.6C130 499.8 143.8 512 160 512c1.2 0 2.3-.1 3.5-.2 17.6-1.9 30.2-17.7 28.3-35.3l-10.1-92.8c-1.5-13-6.9-25.1-15.6-35l-43.3-49 17.6-70.3 6.8 20.4c4.1 12.5 11.9 23.4 24.5 32.6l51.1 32.5c4.6 2.9 12.1 4.6 17.2 5h160c5.1-.4 12.6-2.1 17.2-5l51.1-32.5c12.6-9.2 20.4-20 24.5-32.6l6.8-20.4 17.6 70.3-43.3 49c-8.7 9.9-14.1 22-15.6 35l-10.1 92.8c-1.9 17.6 10.8 33.4 28.3 35.3 1.2.1 2.3.2 3.5.2 16.1 0 30-12.1 31.8-28.5l10.1-92.6 67.2-75.9c13.6-15.5 19-36.7 14.4-56.7zM46.3 358.1l-44 110c-6.6 16.4 1.4 35 17.8 41.6 16.8 6.6 35.1-1.7 41.6-17.8l27.7-69.2-2-18.2-41.1-46.4z\"],\n    \"pepper-hot\": [512, 512, [], \"f816\", \"M330.67 263.12V173.4l-52.75-24.22C219.44 218.76 197.58 400 56 400a56 56 0 0 0 0 112c212.64 0 370.65-122.87 419.18-210.34l-37.05-38.54zm131.09-128.37C493.92 74.91 477.18 26.48 458.62 3a8 8 0 0 0-11.93-.59l-22.9 23a8.06 8.06 0 0 0-.89 10.23c6.86 10.36 17.05 35.1-1.4 72.32A142.85 142.85 0 0 0 364.34 96c-28 0-54 8.54-76.34 22.59l74.67 34.29v78.24h89.09L506.44 288c3.26-12.62 5.56-25.63 5.56-39.31a154 154 0 0 0-50.24-113.94z\"],\n    \"percent\": [448, 512, [], \"f295\", \"M112 224c61.9 0 112-50.1 112-112S173.9 0 112 0 0 50.1 0 112s50.1 112 112 112zm0-160c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48 21.5-48 48-48zm224 224c-61.9 0-112 50.1-112 112s50.1 112 112 112 112-50.1 112-112-50.1-112-112-112zm0 160c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zM392.3.2l31.6-.1c19.4-.1 30.9 21.8 19.7 37.8L77.4 501.6a23.95 23.95 0 0 1-19.6 10.2l-33.4.1c-19.5 0-30.9-21.9-19.7-37.8l368-463.7C377.2 4 384.5.2 392.3.2z\"],\n    \"percentage\": [384, 512, [], \"f541\", \"M109.25 173.25c24.99-24.99 24.99-65.52 0-90.51-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 25 25 65.52 25 90.51 0zm256 165.49c-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 24.99 24.99 65.52 24.99 90.51 0 25-24.99 25-65.51 0-90.51zm-1.94-231.43l-22.62-22.62c-12.5-12.5-32.76-12.5-45.25 0L20.69 359.44c-12.5 12.5-12.5 32.76 0 45.25l22.62 22.62c12.5 12.5 32.76 12.5 45.25 0l274.75-274.75c12.5-12.49 12.5-32.75 0-45.25z\"],\n    \"person-booth\": [576, 512, [], \"f756\", \"M192 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320h-64v176zm32-272h-50.9l-45.2-45.3C115.8 166.6 99.7 160 82.7 160H64c-17.1 0-33.2 6.7-45.3 18.8C6.7 190.9 0 207 0 224.1L.2 320 0 480c0 17.7 14.3 32 31.9 32 17.6 0 32-14.3 32-32l.1-100.7c.9.5 1.6 1.3 2.5 1.7l29.1 43v56c0 17.7 14.3 32 32 32s32-14.3 32-32v-56.5c0-9.9-2.3-19.8-6.7-28.6l-41.2-61.3V253l20.9 20.9c9.1 9.1 21.1 14.1 33.9 14.1H224c17.7 0 32-14.3 32-32s-14.3-32-32-32zM64 128c26.5 0 48-21.5 48-48S90.5 32 64 32 16 53.5 16 80s21.5 48 48 48zm224-96l31.5 223.1-30.9 154.6c-4.3 21.6 13 38.3 31.4 38.3 15.2 0 28-9.1 32.3-30.4.9 16.9 14.6 30.4 31.7 30.4 17.7 0 32-14.3 32-32 0 17.7 14.3 32 32 32s32-14.3 32-32V0H288v32zm-96 0v160h64V0h-32c-17.7 0-32 14.3-32 32zM544 0h-32v496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32c0-17.7-14.3-32-32-32z\"],\n    \"phone\": [512, 512, [], \"f095\", \"M493.4 24.6l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-36 76.7-98.9 140.5-177.2 177.2l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48C3.9 366.5-2 378.1.6 389.4l24 104C27.1 504.2 36.7 512 48 512c256.1 0 464-207.5 464-464 0-11.2-7.7-20.9-18.6-23.4z\"],\n    \"phone-alt\": [512, 512, [], \"f879\", \"M497.39 361.8l-112-48a24 24 0 0 0-28 6.9l-49.6 60.6A370.66 370.66 0 0 1 130.6 204.11l60.6-49.6a23.94 23.94 0 0 0 6.9-28l-48-112A24.16 24.16 0 0 0 122.6.61l-104 24A24 24 0 0 0 0 48c0 256.5 207.9 464 464 464a24 24 0 0 0 23.4-18.6l24-104a24.29 24.29 0 0 0-14.01-27.6z\"],\n    \"phone-slash\": [640, 512, [], \"f3dd\", \"M268.2 381.4l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48c-10.7 4.6-16.5 16.1-13.9 27.5l24 104c2.5 10.8 12.1 18.6 23.4 18.6 100.7 0 193.7-32.4 269.7-86.9l-80-61.8c-10.9 6.5-22.1 12.7-33.6 18.1zm365.6 76.7L475.1 335.5C537.9 256.4 576 156.9 576 48c0-11.2-7.7-20.9-18.6-23.4l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-12.2 26.1-27.9 50.3-46 72.8L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"phone-square\": [448, 512, [], \"f098\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM94 416c-7.033 0-13.057-4.873-14.616-11.627l-14.998-65a15 15 0 0 1 8.707-17.16l69.998-29.999a15 15 0 0 1 17.518 4.289l30.997 37.885c48.944-22.963 88.297-62.858 110.781-110.78l-37.886-30.997a15.001 15.001 0 0 1-4.289-17.518l30-69.998a15 15 0 0 1 17.16-8.707l65 14.998A14.997 14.997 0 0 1 384 126c0 160.292-129.945 290-290 290z\"],\n    \"phone-square-alt\": [448, 512, [], \"f87b\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h352a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48zm-16.39 307.37l-15 65A15 15 0 0 1 354 416C194 416 64 286.29 64 126a15.7 15.7 0 0 1 11.63-14.61l65-15A18.23 18.23 0 0 1 144 96a16.27 16.27 0 0 1 13.79 9.09l30 70A17.9 17.9 0 0 1 189 181a17 17 0 0 1-5.5 11.61l-37.89 31a231.91 231.91 0 0 0 110.78 110.78l31-37.89A17 17 0 0 1 299 291a17.85 17.85 0 0 1 5.91 1.21l70 30A16.25 16.25 0 0 1 384 336a17.41 17.41 0 0 1-.39 3.37z\"],\n    \"phone-volume\": [384, 512, [], \"f2a0\", \"M97.333 506.966c-129.874-129.874-129.681-340.252 0-469.933 5.698-5.698 14.527-6.632 21.263-2.422l64.817 40.513a17.187 17.187 0 0 1 6.849 20.958l-32.408 81.021a17.188 17.188 0 0 1-17.669 10.719l-55.81-5.58c-21.051 58.261-20.612 122.471 0 179.515l55.811-5.581a17.188 17.188 0 0 1 17.669 10.719l32.408 81.022a17.188 17.188 0 0 1-6.849 20.958l-64.817 40.513a17.19 17.19 0 0 1-21.264-2.422zM247.126 95.473c11.832 20.047 11.832 45.008 0 65.055-3.95 6.693-13.108 7.959-18.718 2.581l-5.975-5.726c-3.911-3.748-4.793-9.622-2.261-14.41a32.063 32.063 0 0 0 0-29.945c-2.533-4.788-1.65-10.662 2.261-14.41l5.975-5.726c5.61-5.378 14.768-4.112 18.718 2.581zm91.787-91.187c60.14 71.604 60.092 175.882 0 247.428-4.474 5.327-12.53 5.746-17.552.933l-5.798-5.557c-4.56-4.371-4.977-11.529-.93-16.379 49.687-59.538 49.646-145.933 0-205.422-4.047-4.85-3.631-12.008.93-16.379l5.798-5.557c5.022-4.813 13.078-4.394 17.552.933zm-45.972 44.941c36.05 46.322 36.108 111.149 0 157.546-4.39 5.641-12.697 6.251-17.856 1.304l-5.818-5.579c-4.4-4.219-4.998-11.095-1.285-15.931 26.536-34.564 26.534-82.572 0-117.134-3.713-4.836-3.115-11.711 1.285-15.931l5.818-5.579c5.159-4.947 13.466-4.337 17.856 1.304z\"],\n    \"photo-video\": [640, 512, [], \"f87c\", \"M608 0H160a32 32 0 0 0-32 32v96h160V64h192v320h128a32 32 0 0 0 32-32V32a32 32 0 0 0-32-32zM232 103a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm352 208a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm-168 57H32a32 32 0 0 0-32 32v288a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V192a32 32 0 0 0-32-32zM96 224a32 32 0 1 1-32 32 32 32 0 0 1 32-32zm288 224H64v-32l64-64 32 32 128-128 96 96z\"],\n    \"piggy-bank\": [576, 512, [], \"f4d3\", \"M560 224h-29.5c-8.8-20-21.6-37.7-37.4-52.5L512 96h-32c-29.4 0-55.4 13.5-73 34.3-7.6-1.1-15.1-2.3-23-2.3H256c-77.4 0-141.9 55-156.8 128H56c-14.8 0-26.5-13.5-23.5-28.8C34.7 215.8 45.4 208 57 208h1c3.3 0 6-2.7 6-6v-20c0-3.3-2.7-6-6-6-28.5 0-53.9 20.4-57.5 48.6C-3.9 258.8 22.7 288 56 288h40c0 52.2 25.4 98.1 64 127.3V496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-48h128v48c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80.7c11.8-8.9 22.3-19.4 31.3-31.3H560c8.8 0 16-7.2 16-16V240c0-8.8-7.2-16-16-16zm-128 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM256 96h128c5.4 0 10.7.4 15.9.8 0-.3.1-.5.1-.8 0-53-43-96-96-96s-96 43-96 96c0 2.1.5 4.1.6 6.2 15.2-3.9 31-6.2 47.4-6.2z\"],\n    \"pills\": [576, 512, [], \"f484\", \"M112 32C50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V144c0-61.9-50.1-112-112-112zm48 224H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm139.7-29.7c-3.5-3.5-9.4-3.1-12.3.8-45.3 62.5-40.4 150.1 15.9 206.4 56.3 56.3 143.9 61.2 206.4 15.9 4-2.9 4.3-8.8.8-12.3L299.7 226.3zm229.8-19c-56.3-56.3-143.9-61.2-206.4-15.9-4 2.9-4.3 8.8-.8 12.3l210.8 210.8c3.5 3.5 9.4 3.1 12.3-.8 45.3-62.6 40.5-150.1-15.9-206.4z\"],\n    \"pizza-slice\": [512, 512, [], \"f818\", \"M158.87.15c-16.16-1.52-31.2 8.42-35.33 24.12l-14.81 56.27c187.62 5.49 314.54 130.61 322.48 317l56.94-15.78c15.72-4.36 25.49-19.68 23.62-35.9C490.89 165.08 340.78 17.32 158.87.15zm-58.47 112L.55 491.64a16.21 16.21 0 0 0 20 19.75l379-105.1c-4.27-174.89-123.08-292.14-299.15-294.1zM128 416a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm48-152a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm104 104a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"place-of-worship\": [640, 512, [], \"f67f\", \"M620.61 366.55L512 320v192h112c8.84 0 16-7.16 16-16V395.96a32 32 0 0 0-19.39-29.41zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.55A32 32 0 0 0 0 395.96zm464.46-149.28L416 217.6V102.63c0-8.49-3.37-16.62-9.38-22.63L331.31 4.69c-6.25-6.25-16.38-6.25-22.62 0L233.38 80c-6 6-9.38 14.14-9.38 22.63V217.6l-48.46 29.08A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.66-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44z\"],\n    \"plane\": [576, 512, [], \"f072\", \"M480 192H365.71L260.61 8.06A16.014 16.014 0 0 0 246.71 0h-65.5c-10.63 0-18.3 10.17-15.38 20.39L214.86 192H112l-43.2-57.6c-3.02-4.03-7.77-6.4-12.8-6.4H16.01C5.6 128-2.04 137.78.49 147.88L32 256 .49 364.12C-2.04 374.22 5.6 384 16.01 384H56c5.04 0 9.78-2.37 12.8-6.4L112 320h102.86l-49.03 171.6c-2.92 10.22 4.75 20.4 15.38 20.4h65.5c5.74 0 11.04-3.08 13.89-8.06L365.71 320H480c35.35 0 96-28.65 96-64s-60.65-64-96-64z\"],\n    \"plane-arrival\": [640, 512, [], \"f5af\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM44.81 205.66l88.74 80a62.607 62.607 0 0 0 25.47 13.93l287.6 78.35c26.48 7.21 54.56 8.72 81 1.36 29.67-8.27 43.44-21.21 47.25-35.71 3.83-14.5-1.73-32.71-23.37-54.96-19.28-19.82-44.35-32.79-70.83-40l-97.51-26.56L282.8 30.22c-1.51-5.81-5.95-10.35-11.66-11.91L206.05.58c-10.56-2.88-20.9 5.32-20.71 16.44l47.92 164.21-102.2-27.84-27.59-67.88c-1.93-4.89-6.01-8.57-11.02-9.93L52.72 64.75c-10.34-2.82-20.53 5-20.72 15.88l.23 101.78c.19 8.91 6.03 17.34 12.58 23.25z\"],\n    \"plane-departure\": [640, 512, [], \"f5b0\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM80.55 341.27c6.28 6.84 15.1 10.72 24.33 10.71l130.54-.18a65.62 65.62 0 0 0 29.64-7.12l290.96-147.65c26.74-13.57 50.71-32.94 67.02-58.31 18.31-28.48 20.3-49.09 13.07-63.65-7.21-14.57-24.74-25.27-58.25-27.45-29.85-1.94-59.54 5.92-86.28 19.48l-98.51 49.99-218.7-82.06a17.799 17.799 0 0 0-18-1.11L90.62 67.29c-10.67 5.41-13.25 19.65-5.17 28.53l156.22 98.1-103.21 52.38-72.35-36.47a17.804 17.804 0 0 0-16.07.02L9.91 230.22c-10.44 5.3-13.19 19.12-5.57 28.08l76.21 82.97z\"],\n    \"play\": [448, 512, [], \"f04b\", \"M424.4 214.7L72.4 6.6C43.8-10.3 0 6.1 0 47.9V464c0 37.5 40.7 60.1 72.4 41.3l352-208c31.4-18.5 31.5-64.1 0-82.6z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm115.7 272l-176 101c-15.8 8.8-35.7-2.5-35.7-21V152c0-18.4 19.8-29.8 35.7-21l176 107c16.4 9.2 16.4 32.9 0 42z\"],\n    \"plug\": [384, 512, [], \"f1e6\", \"M256 144V32c0-17.673 14.327-32 32-32s32 14.327 32 32v112h-64zm112 16H16c-8.837 0-16 7.163-16 16v32c0 8.837 7.163 16 16 16h16v32c0 77.406 54.969 141.971 128 156.796V512h64v-99.204c73.031-14.825 128-79.39 128-156.796v-32h16c8.837 0 16-7.163 16-16v-32c0-8.837-7.163-16-16-16zm-240-16V32c0-17.673-14.327-32-32-32S64 14.327 64 32v112h64z\"],\n    \"plus\": [448, 512, [], \"f067\", \"M416 208H272V64c0-17.67-14.33-32-32-32h-32c-17.67 0-32 14.33-32 32v144H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h144v144c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V304h144c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"plus-circle\": [512, 512, [], \"f055\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm144 276c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92h-92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-32 252c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92H92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"podcast\": [448, 512, [], \"f2ce\", \"M267.429 488.563C262.286 507.573 242.858 512 224 512c-18.857 0-38.286-4.427-43.428-23.437C172.927 460.134 160 388.898 160 355.75c0-35.156 31.142-43.75 64-43.75s64 8.594 64 43.75c0 32.949-12.871 104.179-20.571 132.813zM156.867 288.554c-18.693-18.308-29.958-44.173-28.784-72.599 2.054-49.724 42.395-89.956 92.124-91.881C274.862 121.958 320 165.807 320 220c0 26.827-11.064 51.116-28.866 68.552-2.675 2.62-2.401 6.986.628 9.187 9.312 6.765 16.46 15.343 21.234 25.363 1.741 3.654 6.497 4.66 9.449 1.891 28.826-27.043 46.553-65.783 45.511-108.565-1.855-76.206-63.595-138.208-139.793-140.369C146.869 73.753 80 139.215 80 220c0 41.361 17.532 78.7 45.55 104.989 2.953 2.771 7.711 1.77 9.453-1.887 4.774-10.021 11.923-18.598 21.235-25.363 3.029-2.2 3.304-6.566.629-9.185zM224 0C100.204 0 0 100.185 0 224c0 89.992 52.602 165.647 125.739 201.408 4.333 2.118 9.267-1.544 8.535-6.31-2.382-15.512-4.342-30.946-5.406-44.339-.146-1.836-1.149-3.486-2.678-4.512-47.4-31.806-78.564-86.016-78.187-147.347.592-96.237 79.29-174.648 175.529-174.899C320.793 47.747 400 126.797 400 224c0 61.932-32.158 116.49-80.65 147.867-.999 14.037-3.069 30.588-5.624 47.23-.732 4.767 4.203 8.429 8.535 6.31C395.227 389.727 448 314.187 448 224 448 100.205 347.815 0 224 0zm0 160c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64z\"],\n    \"poll\": [448, 512, [], \"f681\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM160 368c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V240c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v128zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V144c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v224zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-64c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v64z\"],\n    \"poll-h\": [448, 512, [], \"f682\", \"M448 432V80c0-26.5-21.5-48-48-48H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48zM112 192c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h128c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-64z\"],\n    \"poo\": [512, 512, [], \"f2fe\", \"M451.4 369.1C468.7 356 480 335.4 480 312c0-39.8-32.2-72-72-72h-14.1c13.4-11.7 22.1-28.8 22.1-48 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C250.3 14.6 256 30.6 256 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 19.2 8.7 36.3 22.1 48H104c-39.8 0-72 32.2-72 72 0 23.4 11.3 44 28.6 57.1C26.3 374.6 0 404.1 0 440c0 39.8 32.2 72 72 72h368c39.8 0 72-32.2 72-72 0-35.9-26.3-65.4-60.6-70.9zM192 256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm159.5 139C341 422.9 293 448 256 448s-85-25.1-95.5-53c-2-5.3 2-11 7.8-11h175.4c5.8 0 9.8 5.7 7.8 11zM320 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"poo-storm\": [448, 512, [], \"f75a\", \"M308 336h-57.7l17.3-64.9c2-7.6-3.7-15.1-11.6-15.1h-68c-6 0-11.1 4.5-11.9 10.4l-16 120c-1 7.2 4.6 13.6 11.9 13.6h59.3l-23 97.2c-1.8 7.6 4 14.8 11.7 14.8 4.2 0 8.2-2.2 10.4-6l88-152c4.6-8-1.2-18-10.4-18zm66.4-111.3c5.9-9.6 9.6-20.6 9.6-32.7 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C218.3 14.6 224 30.6 224 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 12.1 3.7 23.1 9.6 32.7C32.6 228 0 262.2 0 304c0 44 36 80 80 80h48.3c.1-.6 0-1.2 0-1.8l16-120c3-21.8 21.7-38.2 43.7-38.2h68c13.8 0 26.5 6.3 34.9 17.2s11.2 24.8 7.6 38.1l-6.6 24.7h16c15.7 0 30.3 8.4 38.1 22 7.8 13.6 7.8 30.5 0 44l-8.1 14h30c44 0 80-36 80-80 .1-41.8-32.5-76-73.5-79.3z\"],\n    \"poop\": [512, 512, [], \"f619\", \"M451.36 369.14C468.66 355.99 480 335.41 480 312c0-39.77-32.24-72-72-72h-14.07c13.42-11.73 22.07-28.78 22.07-48 0-35.35-28.65-64-64-64h-5.88c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96-5.17 0-10.15.74-15.11 1.52C250.31 14.64 256 30.62 256 48c0 44.18-35.82 80-80 80h-16c-35.35 0-64 28.65-64 64 0 19.22 8.65 36.27 22.07 48H104c-39.76 0-72 32.23-72 72 0 23.41 11.34 43.99 28.64 57.14C26.31 374.62 0 404.12 0 440c0 39.76 32.24 72 72 72h368c39.76 0 72-32.24 72-72 0-35.88-26.31-65.38-60.64-70.86z\"],\n    \"portrait\": [384, 512, [], \"f3e0\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM192 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 384 80 375.4 80 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"pound-sign\": [320, 512, [], \"f154\", \"M308 352h-45.495c-6.627 0-12 5.373-12 12v50.848H128V288h84c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-84v-63.556c0-32.266 24.562-57.086 61.792-57.086 23.658 0 45.878 11.505 57.652 18.849 5.151 3.213 11.888 2.051 15.688-2.685l28.493-35.513c4.233-5.276 3.279-13.005-2.119-17.081C273.124 54.56 236.576 32 187.931 32 106.026 32 48 84.742 48 157.961V224H20c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h28v128H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h296c6.627 0 12-5.373 12-12V364c0-6.627-5.373-12-12-12z\"],\n    \"power-off\": [512, 512, [], \"f011\", \"M400 54.1c63 45 104 118.6 104 201.9 0 136.8-110.8 247.7-247.5 248C120 504.3 8.2 393 8 256.4 7.9 173.1 48.9 99.3 111.8 54.2c11.7-8.3 28-4.8 35 7.7L162.6 90c5.9 10.5 3.1 23.8-6.6 31-41.5 30.8-68 79.6-68 134.9-.1 92.3 74.5 168.1 168 168.1 91.6 0 168.6-74.2 168-169.1-.3-51.8-24.7-101.8-68.1-134-9.7-7.2-12.4-20.5-6.5-30.9l15.8-28.1c7-12.4 23.2-16.1 34.8-7.8zM296 264V24c0-13.3-10.7-24-24-24h-32c-13.3 0-24 10.7-24 24v240c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24z\"],\n    \"pray\": [384, 512, [], \"f683\", \"M256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-30.63 169.75c14.06 16.72 39 19.09 55.97 5.22l88-72.02c17.09-13.98 19.59-39.19 5.62-56.28-13.97-17.11-39.19-19.59-56.31-5.62l-57.44 47-38.91-46.31c-15.44-18.39-39.22-27.92-64-25.33-24.19 2.48-45.25 16.27-56.37 36.92l-49.37 92.03c-23.4 43.64-8.69 96.37 34.19 123.75L131.56 432H40c-22.09 0-40 17.91-40 40s17.91 40 40 40h208c34.08 0 53.77-42.79 28.28-68.28L166.42 333.86l34.8-64.87 24.15 28.76z\"],\n    \"praying-hands\": [640, 512, [], \"f684\", \"M272 191.91c-17.6 0-32 14.4-32 32v80c0 8.84-7.16 16-16 16s-16-7.16-16-16v-76.55c0-17.39 4.72-34.47 13.69-49.39l77.75-129.59c9.09-15.16 4.19-34.81-10.97-43.91-14.45-8.67-32.72-4.3-42.3 9.21-.2.23-.62.21-.79.48l-117.26 175.9C117.56 205.9 112 224.31 112 243.29v80.23l-90.12 30.04A31.974 31.974 0 0 0 0 383.91v96c0 10.82 8.52 32 32 32 2.69 0 5.41-.34 8.06-1.03l179.19-46.62C269.16 449.99 304 403.8 304 351.91v-128c0-17.6-14.4-32-32-32zm346.12 161.73L528 323.6v-80.23c0-18.98-5.56-37.39-16.12-53.23L394.62 14.25c-.18-.27-.59-.24-.79-.48-9.58-13.51-27.85-17.88-42.3-9.21-15.16 9.09-20.06 28.75-10.97 43.91l77.75 129.59c8.97 14.92 13.69 32 13.69 49.39V304c0 8.84-7.16 16-16 16s-16-7.16-16-16v-80c0-17.6-14.4-32-32-32s-32 14.4-32 32v128c0 51.89 34.84 98.08 84.75 112.34l179.19 46.62c2.66.69 5.38 1.03 8.06 1.03 23.48 0 32-21.18 32-32v-96c0-13.77-8.81-25.99-21.88-30.35z\"],\n    \"prescription\": [384, 512, [], \"f5b1\", \"M301.26 352l78.06-78.06c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0L256 306.74l-83.96-83.96C219.31 216.8 256 176.89 256 128c0-53.02-42.98-96-96-96H16C7.16 32 0 39.16 0 48v256c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-80h18.75l128 128-78.06 78.06c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0L256 397.25l78.06 78.06c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63L301.26 352zM64 96h96c17.64 0 32 14.36 32 32s-14.36 32-32 32H64V96z\"],\n    \"prescription-bottle\": [384, 512, [], \"f485\", \"M32 192h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v64zM360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24z\"],\n    \"prescription-bottle-alt\": [384, 512, [], \"f486\", \"M360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24zM32 480c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v352zm64-184c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48z\"],\n    \"print\": [512, 512, [], \"f02f\", \"M448 192V77.25c0-8.49-3.37-16.62-9.37-22.63L393.37 9.37c-6-6-14.14-9.37-22.63-9.37H96C78.33 0 64 14.33 64 32v160c-35.35 0-64 28.65-64 64v112c0 8.84 7.16 16 16 16h48v96c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-96h48c8.84 0 16-7.16 16-16V256c0-35.35-28.65-64-64-64zm-64 256H128v-96h256v96zm0-224H128V64h192v48c0 8.84 7.16 16 16 16h48v96zm48 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"procedures\": [640, 512, [], \"f487\", \"M528 224H272c-8.8 0-16 7.2-16 16v144H64V144c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v352c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48h512v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V336c0-61.9-50.1-112-112-112zM136 96h126.1l27.6 55.2c5.9 11.8 22.7 11.8 28.6 0L368 51.8 390.1 96H512c8.8 0 16-7.2 16-16s-7.2-16-16-16H409.9L382.3 8.8C376.4-3 359.6-3 353.7 8.8L304 108.2l-19.9-39.8c-1.4-2.7-4.1-4.4-7.2-4.4H136c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm24 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"project-diagram\": [640, 512, [], \"f542\", \"M384 320H256c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM192 32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v128c0 17.67 14.33 32 32 32h95.72l73.16 128.04C211.98 300.98 232.4 288 256 288h.28L192 175.51V128h224V64H192V32zM608 0H480c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32z\"],\n    \"puzzle-piece\": [576, 512, [], \"f12e\", \"M519.442 288.651c-41.519 0-59.5 31.593-82.058 31.593C377.409 320.244 432 144 432 144s-196.288 80-196.288-3.297c0-35.827 36.288-46.25 36.288-85.985C272 19.216 243.885 0 210.539 0c-34.654 0-66.366 18.891-66.366 56.346 0 41.364 31.711 59.277 31.711 81.75C175.885 207.719 0 166.758 0 166.758v333.237s178.635 41.047 178.635-28.662c0-22.473-40-40.107-40-81.471 0-37.456 29.25-56.346 63.577-56.346 33.673 0 61.788 19.216 61.788 54.717 0 39.735-36.288 50.158-36.288 85.985 0 60.803 129.675 25.73 181.23 25.73 0 0-34.725-120.101 25.827-120.101 35.962 0 46.423 36.152 86.308 36.152C556.712 416 576 387.99 576 354.443c0-34.199-18.962-65.792-56.558-65.792z\"],\n    \"qrcode\": [448, 512, [], \"f029\", \"M0 224h192V32H0v192zM64 96h64v64H64V96zm192-64v192h192V32H256zm128 128h-64V96h64v64zM0 480h192V288H0v192zm64-128h64v64H64v-64zm352-64h32v128h-96v-32h-32v96h-64V288h96v32h64v-32zm0 160h32v32h-32v-32zm-64 0h32v32h-32v-32z\"],\n    \"question\": [384, 512, [], \"f128\", \"M202.021 0C122.202 0 70.503 32.703 29.914 91.026c-7.363 10.58-5.093 25.086 5.178 32.874l43.138 32.709c10.373 7.865 25.132 6.026 33.253-4.148 25.049-31.381 43.63-49.449 82.757-49.449 30.764 0 68.816 19.799 68.816 49.631 0 22.552-18.617 34.134-48.993 51.164-35.423 19.86-82.299 44.576-82.299 106.405V320c0 13.255 10.745 24 24 24h72.471c13.255 0 24-10.745 24-24v-5.773c0-42.86 125.268-44.645 125.268-160.627C377.504 66.256 286.902 0 202.021 0zM192 373.459c-38.196 0-69.271 31.075-69.271 69.271 0 38.195 31.075 69.27 69.271 69.27s69.271-31.075 69.271-69.271-31.075-69.27-69.271-69.27z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zM262.655 90c-54.497 0-89.255 22.957-116.549 63.758-3.536 5.286-2.353 12.415 2.715 16.258l34.699 26.31c5.205 3.947 12.621 3.008 16.665-2.122 17.864-22.658 30.113-35.797 57.303-35.797 20.429 0 45.698 13.148 45.698 32.958 0 14.976-12.363 22.667-32.534 33.976C247.128 238.528 216 254.941 216 296v4c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12v-1.333c0-28.462 83.186-29.647 83.186-106.667 0-58.002-60.165-102-116.531-102zM256 338c-25.365 0-46 20.635-46 46 0 25.364 20.635 46 46 46s46-20.636 46-46c0-25.365-20.635-46-46-46z\"],\n    \"quidditch\": [640, 512, [], \"f458\", \"M256.5 216.8L343.2 326s-16.6 102.4-76.6 150.1C206.7 523.8 0 510.2 0 510.2s3.8-23.1 11-55.4l94.6-112.2c4-4.7-.9-11.6-6.6-9.5l-60.4 22.1c14.4-41.7 32.7-80 54.6-97.5 59.9-47.8 163.3-40.9 163.3-40.9zm238 135c-44 0-79.8 35.8-79.8 79.9 0 44.1 35.7 79.9 79.8 79.9 44.1 0 79.8-35.8 79.8-79.9 0-44.2-35.8-79.9-79.8-79.9zM636.5 31L616.7 6c-5.5-6.9-15.5-8-22.4-2.6L361.8 181.3l-34.1-43c-5.1-6.4-15.1-5.2-18.6 2.2l-25.3 54.6 86.7 109.2 58.8-12.4c8-1.7 11.4-11.2 6.3-17.6l-34.1-42.9L634 53.5c6.9-5.5 8-15.6 2.5-22.5z\"],\n    \"quote-left\": [512, 512, [], \"f10d\", \"M464 256h-80v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8c-88.4 0-160 71.6-160 160v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zm-288 0H96v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8C71.6 32 0 103.6 0 192v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"quote-right\": [512, 512, [], \"f10e\", \"M464 32H336c-26.5 0-48 21.5-48 48v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48zm-288 0H48C21.5 32 0 53.5 0 80v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48z\"],\n    \"quran\": [448, 512, [], \"f687\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM301.08 145.82c.6-1.21 1.76-1.82 2.92-1.82s2.32.61 2.92 1.82l11.18 22.65 25 3.63c2.67.39 3.74 3.67 1.81 5.56l-18.09 17.63 4.27 24.89c.36 2.11-1.31 3.82-3.21 3.82-.5 0-1.02-.12-1.52-.38L304 211.87l-22.36 11.75c-.5.26-1.02.38-1.52.38-1.9 0-3.57-1.71-3.21-3.82l4.27-24.89-18.09-17.63c-1.94-1.89-.87-5.17 1.81-5.56l24.99-3.63 11.19-22.65zm-57.89-69.01c13.67 0 27.26 2.49 40.38 7.41a6.775 6.775 0 1 1-2.38 13.12c-.67 0-3.09-.21-4.13-.21-52.31 0-94.86 42.55-94.86 94.86 0 52.3 42.55 94.86 94.86 94.86 1.03 0 3.48-.21 4.13-.21 3.93 0 6.8 3.14 6.8 6.78 0 2.98-1.94 5.51-4.62 6.42-13.07 4.87-26.59 7.34-40.19 7.34C179.67 307.19 128 255.51 128 192c0-63.52 51.67-115.19 115.19-115.19zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"radiation\": [496, 512, [], \"f7b9\", \"M328.2 255.8h151.6c9.1 0 16.8-7.7 16.2-16.8-5.1-75.8-44.4-142.2-102.5-184.2-7.4-5.3-17.9-2.9-22.7 4.8L290.4 188c22.6 14.3 37.8 39.2 37.8 67.8zm-37.8 67.7c-12.3 7.7-26.8 12.4-42.4 12.4-15.6 0-30-4.7-42.4-12.4L125.2 452c-4.8 7.7-2.4 18.1 5.6 22.4C165.7 493.2 205.6 504 248 504s82.3-10.8 117.2-29.6c8-4.3 10.4-14.8 5.6-22.4l-80.4-128.5zM248 303.8c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm-231.8-48h151.6c0-28.6 15.2-53.5 37.8-67.7L125.2 59.7c-4.8-7.7-15.3-10.2-22.7-4.8C44.4 96.9 5.1 163.3 0 239.1c-.6 9 7.1 16.7 16.2 16.7z\"],\n    \"radiation-alt\": [496, 512, [], \"f7ba\", \"M312 256h79.1c9.2 0 16.9-7.7 16-16.8-4.6-43.6-27-81.8-59.5-107.8-7.6-6.1-18.8-4.5-24 3.8L281.9 202c18 11.2 30.1 31.2 30.1 54zm-97.8 54.1L172.4 377c-4.9 7.8-2.4 18.4 5.8 22.5 21.1 10.4 44.7 16.5 69.8 16.5s48.7-6.1 69.9-16.5c8.2-4.1 10.6-14.7 5.8-22.5l-41.8-66.9c-9.8 6.2-21.4 9.9-33.8 9.9s-24.1-3.7-33.9-9.9zM104.9 256H184c0-22.8 12.1-42.8 30.2-54.1l-41.7-66.8c-5.2-8.3-16.4-9.9-24-3.8-32.6 26-54.9 64.2-59.5 107.8-1.1 9.2 6.7 16.9 15.9 16.9zM248 504c137 0 248-111 248-248S385 8 248 8 0 119 0 256s111 248 248 248zm0-432c101.5 0 184 82.5 184 184s-82.5 184-184 184S64 357.5 64 256 146.5 72 248 72zm0 216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"rainbow\": [576, 512, [], \"f75b\", \"M268.3 32.7C115.4 42.9 0 176.9 0 330.2V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C64 186.8 180.9 80.3 317.5 97.9 430.4 112.4 512 214 512 327.8V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-165.3-140-298.6-307.7-287.3zm-5.6 96.9C166 142 96 229.1 96 326.7V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-74.8 64.5-134.8 140.8-127.4 66.5 6.5 115.2 66.2 115.2 133.1V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-114.2-100.2-205.4-217.3-190.4zm6.2 96.3c-45.6 8.9-76.9 51.5-76.9 97.9V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-17.6 14.3-32 32-32s32 14.4 32 32v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-59.2-53.8-106-115.1-94.1z\"],\n    \"random\": [512, 512, [], \"f074\", \"M504.971 359.029c9.373 9.373 9.373 24.569 0 33.941l-80 79.984c-15.01 15.01-40.971 4.49-40.971-16.971V416h-58.785a12.004 12.004 0 0 1-8.773-3.812l-70.556-75.596 53.333-57.143L352 336h32v-39.981c0-21.438 25.943-31.998 40.971-16.971l80 79.981zM12 176h84l52.781 56.551 53.333-57.143-70.556-75.596A11.999 11.999 0 0 0 122.785 96H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12zm372 0v39.984c0 21.46 25.961 31.98 40.971 16.971l80-79.984c9.373-9.373 9.373-24.569 0-33.941l-80-79.981C409.943 24.021 384 34.582 384 56.019V96h-58.785a12.004 12.004 0 0 0-8.773 3.812L96 336H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h110.785c3.326 0 6.503-1.381 8.773-3.812L352 176h32z\"],\n    \"receipt\": [384, 512, [], \"f543\", \"M358.4 3.2L320 48 265.6 3.2a15.9 15.9 0 0 0-19.2 0L192 48 137.6 3.2a15.9 15.9 0 0 0-19.2 0L64 48 25.6 3.2C15-4.7 0 2.8 0 16v480c0 13.2 15 20.7 25.6 12.8L64 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L192 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L320 464l38.4 44.8c10.5 7.9 25.6.4 25.6-12.8V16c0-13.2-15-20.7-25.6-12.8zM320 360c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16z\"],\n    \"recycle\": [512, 512, [], \"f1b8\", \"M184.561 261.903c3.232 13.997-12.123 24.635-24.068 17.168l-40.736-25.455-50.867 81.402C55.606 356.273 70.96 384 96.012 384H148c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12H96.115c-75.334 0-121.302-83.048-81.408-146.88l50.822-81.388-40.725-25.448c-12.081-7.547-8.966-25.961 4.879-29.158l110.237-25.45c8.611-1.988 17.201 3.381 19.189 11.99l25.452 110.237zm98.561-182.915l41.289 66.076-40.74 25.457c-12.051 7.528-9 25.953 4.879 29.158l110.237 25.45c8.672 1.999 17.215-3.438 19.189-11.99l25.45-110.237c3.197-13.844-11.99-24.719-24.068-17.168l-40.687 25.424-41.263-66.082c-37.521-60.033-125.209-60.171-162.816 0l-17.963 28.766c-3.51 5.62-1.8 13.021 3.82 16.533l33.919 21.195c5.62 3.512 13.024 1.803 16.536-3.817l17.961-28.743c12.712-20.341 41.973-19.676 54.257-.022zM497.288 301.12l-27.515-44.065c-3.511-5.623-10.916-7.334-16.538-3.821l-33.861 21.159c-5.62 3.512-7.33 10.915-3.818 16.536l27.564 44.112c13.257 21.211-2.057 48.96-27.136 48.96H320V336.02c0-14.213-17.242-21.383-27.313-11.313l-80 79.981c-6.249 6.248-6.249 16.379 0 22.627l80 79.989C302.689 517.308 320 510.3 320 495.989V448h95.88c75.274 0 121.335-82.997 81.408-146.88z\"],\n    \"redo\": [512, 512, [], \"f01e\", \"M500.33 0h-47.41a12 12 0 0 0-12 12.57l4 82.76A247.42 247.42 0 0 0 256 8C119.34 8 7.9 119.53 8 256.19 8.1 393.07 119.1 504 256 504a247.1 247.1 0 0 0 166.18-63.91 12 12 0 0 0 .48-17.43l-34-34a12 12 0 0 0-16.38-.55A176 176 0 1 1 402.1 157.8l-101.53-4.87a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12h200.33a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12z\"],\n    \"redo-alt\": [512, 512, [], \"f2f9\", \"M256.455 8c66.269.119 126.437 26.233 170.859 68.685l35.715-35.715C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.75c-30.864-28.899-70.801-44.907-113.23-45.273-92.398-.798-170.283 73.977-169.484 169.442C88.764 348.009 162.184 424 256 424c41.127 0 79.997-14.678 110.629-41.556 4.743-4.161 11.906-3.908 16.368.553l39.662 39.662c4.872 4.872 4.631 12.815-.482 17.433C378.202 479.813 319.926 504 256 504 119.034 504 8.001 392.967 8 256.002 7.999 119.193 119.646 7.755 256.455 8z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M285.363 207.475c0 18.6-9.831 28.431-28.431 28.431h-29.876v-56.14h23.378c28.668 0 34.929 8.773 34.929 27.709zM504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM363.411 360.414c-46.729-84.825-43.299-78.636-44.702-80.98 23.432-15.172 37.945-42.979 37.945-74.486 0-54.244-31.5-89.252-105.498-89.252h-70.667c-13.255 0-24 10.745-24 24V372c0 13.255 10.745 24 24 24h22.567c13.255 0 24-10.745 24-24v-71.663h25.556l44.129 82.937a24.001 24.001 0 0 0 21.188 12.727h24.464c18.261-.001 29.829-19.591 21.018-35.587z\"],\n    \"remove-format\": [640, 512, [], \"f87d\", \"M336 416h-11.17l9.26-27.77L267 336.4 240.49 416H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm297.82 42.1L377 259.59 426.17 112H544v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16H176a16 16 0 0 0-16 16v43.9L45.46 3.38A16 16 0 0 0 23 6.19L3.37 31.46a16 16 0 0 0 2.81 22.45l588.36 454.72a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zM309.91 207.76L224 141.36V112h117.83z\"],\n    \"reply\": [512, 512, [], \"f3e5\", \"M8.309 189.836L184.313 37.851C199.719 24.546 224 35.347 224 56.015v80.053c160.629 1.839 288 34.032 288 186.258 0 61.441-39.581 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 45.344-145.012-21.507-183.51-176.59-185.742V360c0 20.7-24.3 31.453-39.687 18.164l-176.004-152c-11.071-9.562-11.086-26.753 0-36.328z\"],\n    \"reply-all\": [576, 512, [], \"f122\", \"M136.309 189.836L312.313 37.851C327.72 24.546 352 35.348 352 56.015v82.763c129.182 10.231 224 52.212 224 183.548 0 61.441-39.582 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 38.512-123.162-3.922-169.482-112.59-182.015v84.175c0 20.701-24.3 31.453-39.687 18.164L136.309 226.164c-11.071-9.561-11.086-26.753 0-36.328zm-128 36.328L184.313 378.15C199.7 391.439 224 380.687 224 359.986v-15.818l-108.606-93.785A55.96 55.96 0 0 1 96 207.998a55.953 55.953 0 0 1 19.393-42.38L224 71.832V56.015c0-20.667-24.28-31.469-39.687-18.164L8.309 189.836c-11.086 9.575-11.071 26.767 0 36.328z\"],\n    \"republican\": [640, 512, [], \"f75e\", \"M544 192c0-88.4-71.6-160-160-160H160C71.6 32 0 103.6 0 192v64h544v-64zm-367.7-21.6l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L128 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L272 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L416 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zM624 320h-32c-8.8 0-16 7.2-16 16v64c0 8.8-7.2 16-16 16s-16-7.2-16-16V288H0v176c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16v-80h192v80c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16V352h32v43.3c0 41.8 30 80.1 71.6 84.3 47.8 4.9 88.4-32.7 88.4-79.6v-64c0-8.8-7.2-16-16-16z\"],\n    \"restroom\": [640, 512, [], \"f7bd\", \"M128 128c35.3 0 64-28.7 64-64S163.3 0 128 0 64 28.7 64 64s28.7 64 64 64zm384 0c35.3 0 64-28.7 64-64S547.3 0 512 0s-64 28.7-64 64 28.7 64 64 64zm127.3 226.5l-45.6-185.8c-3.3-13.5-15.5-23-29.8-24.2-15 9.7-32.8 15.5-52 15.5-19.2 0-37-5.8-52-15.5-14.3 1.2-26.5 10.7-29.8 24.2l-45.6 185.8C381 369.6 393 384 409.2 384H464v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V384h54.8c16.2 0 28.2-14.4 24.5-29.5zM336 0h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zM180.1 144.4c-15 9.8-32.9 15.6-52.1 15.6-19.2 0-37.1-5.8-52.1-15.6C51.3 146.5 32 166.9 32 192v136c0 13.3 10.7 24 24 24h8v136c0 13.3 10.7 24 24 24h80c13.3 0 24-10.7 24-24V352h8c13.3 0 24-10.7 24-24V192c0-25.1-19.3-45.5-43.9-47.6z\"],\n    \"retweet\": [640, 512, [], \"f079\", \"M629.657 343.598L528.971 444.284c-9.373 9.372-24.568 9.372-33.941 0L394.343 343.598c-9.373-9.373-9.373-24.569 0-33.941l10.823-10.823c9.562-9.562 25.133-9.34 34.419.492L480 342.118V160H292.451a24.005 24.005 0 0 1-16.971-7.029l-16-16C244.361 121.851 255.069 96 276.451 96H520c13.255 0 24 10.745 24 24v222.118l40.416-42.792c9.285-9.831 24.856-10.054 34.419-.492l10.823 10.823c9.372 9.372 9.372 24.569-.001 33.941zm-265.138 15.431A23.999 23.999 0 0 0 347.548 352H160V169.881l40.416 42.792c9.286 9.831 24.856 10.054 34.419.491l10.822-10.822c9.373-9.373 9.373-24.569 0-33.941L144.971 67.716c-9.373-9.373-24.569-9.373-33.941 0L10.343 168.402c-9.373 9.373-9.373 24.569 0 33.941l10.822 10.822c9.562 9.562 25.133 9.34 34.419-.491L96 169.881V392c0 13.255 10.745 24 24 24h243.549c21.382 0 32.09-25.851 16.971-40.971l-16.001-16z\"],\n    \"ribbon\": [448, 512, [], \"f4d6\", \"M6.1 444.3c-9.6 10.8-7.5 27.6 4.5 35.7l68.8 27.9c9.9 6.7 23.3 5 31.3-3.8l91.8-101.9-79.2-87.9-117.2 130zm435.8 0s-292-324.6-295.4-330.1c15.4-8.4 40.2-17.9 77.5-17.9s62.1 9.5 77.5 17.9c-3.3 5.6-56 64.6-56 64.6l79.1 87.7 34.2-38c28.7-31.9 33.3-78.6 11.4-115.5l-43.7-73.5c-4.3-7.2-9.9-13.3-16.8-18-40.7-27.6-127.4-29.7-171.4 0-6.9 4.7-12.5 10.8-16.8 18l-43.6 73.2c-1.5 2.5-37.1 62.2 11.5 116L337.5 504c8 8.9 21.4 10.5 31.3 3.8l68.8-27.9c11.9-8 14-24.8 4.3-35.6z\"],\n    \"ring\": [512, 512, [], \"f70b\", \"M256 64C110.06 64 0 125.91 0 208v98.13C0 384.48 114.62 448 256 448s256-63.52 256-141.87V208c0-82.09-110.06-144-256-144zm0 64c106.04 0 192 35.82 192 80 0 9.26-3.97 18.12-10.91 26.39C392.15 208.21 328.23 192 256 192s-136.15 16.21-181.09 42.39C67.97 226.12 64 217.26 64 208c0-44.18 85.96-80 192-80zM120.43 264.64C155.04 249.93 201.64 240 256 240s100.96 9.93 135.57 24.64C356.84 279.07 308.93 288 256 288s-100.84-8.93-135.57-23.36z\"],\n    \"road\": [576, 512, [], \"f018\", \"M573.19 402.67l-139.79-320C428.43 71.29 417.6 64 405.68 64h-97.59l2.45 23.16c.5 4.72-3.21 8.84-7.96 8.84h-29.16c-4.75 0-8.46-4.12-7.96-8.84L267.91 64h-97.59c-11.93 0-22.76 7.29-27.73 18.67L2.8 402.67C-6.45 423.86 8.31 448 30.54 448h196.84l10.31-97.68c.86-8.14 7.72-14.32 15.91-14.32h68.8c8.19 0 15.05 6.18 15.91 14.32L348.62 448h196.84c22.23 0 36.99-24.14 27.73-45.33zM260.4 135.16a8 8 0 0 1 7.96-7.16h39.29c4.09 0 7.53 3.09 7.96 7.16l4.6 43.58c.75 7.09-4.81 13.26-11.93 13.26h-40.54c-7.13 0-12.68-6.17-11.93-13.26l4.59-43.58zM315.64 304h-55.29c-9.5 0-16.91-8.23-15.91-17.68l5.07-48c.86-8.14 7.72-14.32 15.91-14.32h45.15c8.19 0 15.05 6.18 15.91 14.32l5.07 48c1 9.45-6.41 17.68-15.91 17.68z\"],\n    \"robot\": [640, 512, [], \"f544\", \"M0 256v128c0 17.7 14.3 32 32 32h32V224H32c-17.7 0-32 14.3-32 32zM464 96H352V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v64H176c-44.2 0-80 35.8-80 80v272c0 35.3 28.7 64 64 64h320c35.3 0 64-28.7 64-64V176c0-44.2-35.8-80-80-80zM256 416h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm128 120h-64v-32h64v32zm96 0h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm192-72h-32v192h32c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32z\"],\n    \"rocket\": [512, 512, [], \"f135\", \"M505.05 19.1a15.89 15.89 0 0 0-12.2-12.2C460.65 0 435.46 0 410.36 0c-103.2 0-165.1 55.2-211.29 128H94.87A48 48 0 0 0 52 154.49l-49.42 98.8A24 24 0 0 0 24.07 288h103.77l-22.47 22.47a32 32 0 0 0 0 45.25l50.9 50.91a32 32 0 0 0 45.26 0L224 384.16V488a24 24 0 0 0 34.7 21.49l98.7-49.39a47.91 47.91 0 0 0 26.5-42.9V312.79c72.59-46.3 128-108.4 128-211.09.1-25.2.1-50.4-6.85-82.6zM384 168a40 40 0 1 1 40-40 40 40 0 0 1-40 40z\"],\n    \"route\": [512, 512, [], \"f4d7\", \"M416 320h-96c-17.6 0-32-14.4-32-32s14.4-32 32-32h96s96-107 96-160-43-96-96-96-96 43-96 96c0 25.5 22.2 63.4 45.3 96H320c-52.9 0-96 43.1-96 96s43.1 96 96 96h96c17.6 0 32 14.4 32 32s-14.4 32-32 32H185.5c-16 24.8-33.8 47.7-47.3 64H416c52.9 0 96-43.1 96-96s-43.1-96-96-96zm0-256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM96 256c-53 0-96 43-96 96s96 160 96 160 96-107 96-160-43-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"rss\": [448, 512, [], \"f09e\", \"M128.081 415.959c0 35.369-28.672 64.041-64.041 64.041S0 451.328 0 415.959s28.672-64.041 64.041-64.041 64.04 28.673 64.04 64.041zm175.66 47.25c-8.354-154.6-132.185-278.587-286.95-286.95C7.656 175.765 0 183.105 0 192.253v48.069c0 8.415 6.49 15.472 14.887 16.018 111.832 7.284 201.473 96.702 208.772 208.772.547 8.397 7.604 14.887 16.018 14.887h48.069c9.149.001 16.489-7.655 15.995-16.79zm144.249.288C439.596 229.677 251.465 40.445 16.503 32.01 7.473 31.686 0 38.981 0 48.016v48.068c0 8.625 6.835 15.645 15.453 15.999 191.179 7.839 344.627 161.316 352.465 352.465.353 8.618 7.373 15.453 15.999 15.453h48.068c9.034-.001 16.329-7.474 16.005-16.504z\"],\n    \"rss-square\": [448, 512, [], \"f143\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM112 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm157.533 0h-34.335c-6.011 0-11.051-4.636-11.442-10.634-5.214-80.05-69.243-143.92-149.123-149.123-5.997-.39-10.633-5.431-10.633-11.441v-34.335c0-6.535 5.468-11.777 11.994-11.425 110.546 5.974 198.997 94.536 204.964 204.964.352 6.526-4.89 11.994-11.425 11.994zm103.027 0h-34.334c-6.161 0-11.175-4.882-11.427-11.038-5.598-136.535-115.204-246.161-251.76-251.76C68.882 152.949 64 147.935 64 141.774V107.44c0-6.454 5.338-11.664 11.787-11.432 167.83 6.025 302.21 141.191 308.205 308.205.232 6.449-4.978 11.787-11.432 11.787z\"],\n    \"ruble-sign\": [384, 512, [], \"f158\", \"M239.36 320C324.48 320 384 260.542 384 175.071S324.48 32 239.36 32H76c-6.627 0-12 5.373-12 12v206.632H12c-6.627 0-12 5.373-12 12V308c0 6.627 5.373 12 12 12h52v32H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v52c0 6.627 5.373 12 12 12h58.56c6.627 0 12-5.373 12-12v-52H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H146.56v-32h92.8zm-92.8-219.252h78.72c46.72 0 74.88 29.11 74.88 74.323 0 45.832-28.16 75.561-76.16 75.561h-77.44V100.748z\"],\n    \"ruler\": [640, 512, [], \"f545\", \"M635.7 167.2L556.1 31.7c-8.8-15-28.3-20.1-43.5-11.5l-69 39.1L503.3 161c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L416 75l-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L333.2 122 278 153.3 337.8 255c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-59.7-101.7-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-27.9-47.5-55.2 31.3 59.7 101.7c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L84.9 262.9l-69 39.1C.7 310.7-4.6 329.8 4.2 344.8l79.6 135.6c8.8 15 28.3 20.1 43.5 11.5L624.1 210c15.2-8.6 20.4-27.8 11.6-42.8z\"],\n    \"ruler-combined\": [512, 512, [], \"f546\", \"M160 288h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56v-64h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56V96h-56c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8h56V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 2.77.91 5.24 1.57 7.8L160 329.38V288zm320 64h-32v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-41.37L24.2 510.43c2.56.66 5.04 1.57 7.8 1.57h448c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"ruler-horizontal\": [576, 512, [], \"f547\", \"M544 128h-48v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8H88c-4.42 0-8-3.58-8-8v-88H32c-17.67 0-32 14.33-32 32v192c0 17.67 14.33 32 32 32h512c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32z\"],\n    \"ruler-vertical\": [256, 512, [], \"f548\", \"M168 416c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 17.67 14.33 32 32 32h192c17.67 0 32-14.33 32-32v-64h-88z\"],\n    \"running\": [416, 512, [], \"f70c\", \"M272 96c26.51 0 48-21.49 48-48S298.51 0 272 0s-48 21.49-48 48 21.49 48 48 48zM113.69 317.47l-14.8 34.52H32c-17.67 0-32 14.33-32 32s14.33 32 32 32h77.45c19.25 0 36.58-11.44 44.11-29.09l8.79-20.52-10.67-6.3c-17.32-10.23-30.06-25.37-37.99-42.61zM384 223.99h-44.03l-26.06-53.25c-12.5-25.55-35.45-44.23-61.78-50.94l-71.08-21.14c-28.3-6.8-57.77-.55-80.84 17.14l-39.67 30.41c-14.03 10.75-16.69 30.83-5.92 44.86s30.84 16.66 44.86 5.92l39.69-30.41c7.67-5.89 17.44-8 25.27-6.14l14.7 4.37-37.46 87.39c-12.62 29.48-1.31 64.01 26.3 80.31l84.98 50.17-27.47 87.73c-5.28 16.86 4.11 34.81 20.97 40.09 3.19 1 6.41 1.48 9.58 1.48 13.61 0 26.23-8.77 30.52-22.45l31.64-101.06c5.91-20.77-2.89-43.08-21.64-54.39l-61.24-36.14 31.31-78.28 20.27 41.43c8 16.34 24.92 26.89 43.11 26.89H384c17.67 0 32-14.33 32-32s-14.33-31.99-32-31.99z\"],\n    \"rupee-sign\": [320, 512, [], \"f156\", \"M308 96c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v44.748c0 6.627 5.373 12 12 12h85.28c27.308 0 48.261 9.958 60.97 27.252H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h158.757c-6.217 36.086-32.961 58.632-74.757 58.632H12c-6.627 0-12 5.373-12 12v53.012c0 3.349 1.4 6.546 3.861 8.818l165.052 152.356a12.001 12.001 0 0 0 8.139 3.182h82.562c10.924 0 16.166-13.408 8.139-20.818L116.871 319.906c76.499-2.34 131.144-53.395 138.318-127.906H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-58.69c-3.486-11.541-8.28-22.246-14.252-32H308z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256c0 90.1 48.2 168.7 120 212.1V288c0-8.8 7.2-16 16-16s16 7.2 16 16v196.7c29.5 12.4 62 19.3 96 19.3s66.5-6.9 96-19.3V288c0-8.8 7.2-16 16-16s16 7.2 16 16v180.1C447.8 424.7 496 346 496 256 496 119 385 8 248 8zm-65.5 216.5c-14.8-13.2-46.2-13.2-61 0L112 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c.8 5-1.7 10-6.1 12.4-5.8 3.1-11.2.7-13.7-1.6l-9.7-8.5zM248 416c-26.5 0-48-28.7-48-64s21.5-64 48-64 48 28.7 48 64-21.5 64-48 64zm149.8-181.5c-5.8 3.1-11.2.7-13.7-1.6l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S400 197 404 222.2c.6 4.9-1.8 9.9-6.2 12.3z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM152 416c-26.5 0-48-21-48-47 0-20 28.5-60.4 41.6-77.8 3.2-4.3 9.6-4.3 12.8 0C171.5 308.6 200 349 200 369c0 26-21.5 47-48 47zm16-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm170.2 154.2C315.8 367.4 282.9 352 248 352c-21.2 0-21.2-32 0-32 44.4 0 86.3 19.6 114.7 53.8 13.8 16.4-11.2 36.5-24.5 20.4z\"],\n    \"satellite\": [512, 512, [], \"f7bf\", \"M502.7 265l-80.3-80.4 47.8-47.9c13.1-13.1 13.1-34.4 0-47.5l-47.5-47.5c-13.1-13.1-34.4-13.1-47.5 0l-47.8 47.9-80.3-80.3C240.8 3.1 232.7 0 224.5 0S208.2 3.1 202 9.3L105.3 106c-12.4 12.4-12.4 32.6 0 45.1l80.3 80.4-9.8 9.8C122.1 217 59.6 218.6 7.3 246.7c-8.5 4.6-9.6 16.4-2.8 23.2L112 377.4l-17.8 17.8c-2.6-.7-5-1.6-7.8-1.6-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32c0-2.8-.9-5.2-1.6-7.8l17.8-17.8 107.5 107.5c6.8 6.8 18.7 5.7 23.2-2.8 28.1-52.3 29.7-114.8 5.4-168.5l9.9-9.9 80.3 80.4c6.2 6.2 14.4 9.3 22.5 9.3s16.3-3.1 22.5-9.3l96.7-96.7c12.5-12.4 12.5-32.6.1-45zm-352-136.5l73.8-73.8 68.9 68.9-73.8 73.8-68.9-68.9zm232.8 232.8l-68.9-68.9 73.8-73.8 68.9 68.9-73.8 73.8z\"],\n    \"satellite-dish\": [512, 512, [], \"f7c0\", \"M188.8 345.9l27.4-27.4c2.6.7 5 1.6 7.8 1.6 17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32c0 2.8.9 5.2 1.6 7.8l-27.4 27.4L49.4 206.5c-7.3-7.3-20.1-6.1-25 3-41.8 77.8-29.9 176.7 35.7 242.3 65.6 65.6 164.6 77.5 242.3 35.7 9.2-4.9 10.4-17.7 3-25L188.8 345.9zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM224 416c-35.346 0-64-28.654-64-64 0-35.346 28.654-64 64-64s64 28.654 64 64c0 35.346-28.654 64-64 64zm96-304.52V212c0 6.627-5.373 12-12 12H76c-6.627 0-12-5.373-12-12V108c0-6.627 5.373-12 12-12h228.52c3.183 0 6.235 1.264 8.485 3.515l3.48 3.48A11.996 11.996 0 0 1 320 111.48z\"],\n    \"school\": [640, 512, [], \"f549\", \"M0 224v272c0 8.84 7.16 16 16 16h80V192H32c-17.67 0-32 14.33-32 32zm360-48h-24v-40c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v64c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zm137.75-63.96l-160-106.67a32.02 32.02 0 0 0-35.5 0l-160 106.67A32.002 32.002 0 0 0 128 138.66V512h128V368c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v144h128V138.67c0-10.7-5.35-20.7-14.25-26.63zM320 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm288-64h-64v320h80c8.84 0 16-7.16 16-16V224c0-17.67-14.33-32-32-32z\"],\n    \"screwdriver\": [512, 512, [], \"f54a\", \"M448 0L320 96v62.06l-83.03 83.03c6.79 4.25 13.27 9.06 19.07 14.87 5.8 5.8 10.62 12.28 14.87 19.07L353.94 192H416l96-128-64-64zM128 278.59L10.92 395.67c-14.55 14.55-14.55 38.15 0 52.71l52.7 52.7c14.56 14.56 38.15 14.56 52.71 0L233.41 384c29.11-29.11 29.11-76.3 0-105.41s-76.3-29.11-105.41 0z\"],\n    \"scroll\": [640, 512, [], \"f70e\", \"M48 0C21.53 0 0 21.53 0 48v64c0 8.84 7.16 16 16 16h80V48C96 21.53 74.47 0 48 0zm208 412.57V352h288V96c0-52.94-43.06-96-96-96H111.59C121.74 13.41 128 29.92 128 48v368c0 38.87 34.65 69.65 74.75 63.12C234.22 474 256 444.46 256 412.57zM288 384v32c0 52.93-43.06 96-96 96h336c61.86 0 112-50.14 112-112 0-8.84-7.16-16-16-16H288z\"],\n    \"sd-card\": [384, 512, [], \"f7c2\", \"M320 0H128L0 128v320c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zM160 160h-48V64h48v96zm80 0h-48V64h48v96zm80 0h-48V64h48v96z\"],\n    \"search\": [512, 512, [], \"f002\", \"M505 442.7L405.3 343c-4.5-4.5-10.6-7-17-7H372c27.6-35.3 44-79.7 44-128C416 93.1 322.9 0 208 0S0 93.1 0 208s93.1 208 208 208c48.3 0 92.7-16.4 128-44v16.3c0 6.4 2.5 12.5 7 17l99.7 99.7c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.6.1-34zM208 336c-70.7 0-128-57.2-128-128 0-70.7 57.2-128 128-128 70.7 0 128 57.2 128 128 0 70.7-57.2 128-128 128z\"],\n    \"search-dollar\": [512, 512, [], \"f688\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm27.11-152.54l-45.01-13.5c-5.16-1.55-8.77-6.78-8.77-12.73 0-7.27 5.3-13.19 11.8-13.19h28.11c4.56 0 8.96 1.29 12.82 3.72 3.24 2.03 7.36 1.91 10.13-.73l11.75-11.21c3.53-3.37 3.33-9.21-.57-12.14-9.1-6.83-20.08-10.77-31.37-11.35V112c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v16.12c-23.63.63-42.68 20.55-42.68 45.07 0 19.97 12.99 37.81 31.58 43.39l45.01 13.5c5.16 1.55 8.77 6.78 8.77 12.73 0 7.27-5.3 13.19-11.8 13.19h-28.1c-4.56 0-8.96-1.29-12.82-3.72-3.24-2.03-7.36-1.91-10.13.73l-11.75 11.21c-3.53 3.37-3.33 9.21.57 12.14 9.1 6.83 20.08 10.77 31.37 11.35V304c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-16.12c23.63-.63 42.68-20.54 42.68-45.07 0-19.97-12.99-37.81-31.59-43.39z\"],\n    \"search-location\": [512, 512, [], \"f689\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm.02-239.96c-40.78 0-73.84 33.05-73.84 73.83 0 32.96 48.26 93.05 66.75 114.86a9.24 9.24 0 0 0 14.18 0c18.49-21.81 66.75-81.89 66.75-114.86 0-40.78-33.06-73.83-73.84-73.83zm0 96c-13.26 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"search-minus\": [512, 512, [], \"f010\", \"M304 192v32c0 6.6-5.4 12-12 12H124c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"search-plus\": [512, 512, [], \"f00e\", \"M304 192v32c0 6.6-5.4 12-12 12h-56v56c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-56h-56c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h56v-56c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v56h56c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"seedling\": [512, 512, [], \"f4d8\", \"M64 96H0c0 123.7 100.3 224 224 224v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C288 196.3 187.7 96 64 96zm384-64c-84.2 0-157.4 46.5-195.7 115.2 27.7 30.2 48.2 66.9 59 107.6C424 243.1 512 147.9 512 32h-64z\"],\n    \"server\": [512, 512, [], \"f233\", \"M480 160H32c-17.673 0-32-14.327-32-32V64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24z\"],\n    \"shapes\": [512, 512, [], \"f61f\", \"M512 320v160c0 17.67-14.33 32-32 32H320c-17.67 0-32-14.33-32-32V320c0-17.67 14.33-32 32-32h160c17.67 0 32 14.33 32 32zm-384-64C57.31 256 0 313.31 0 384s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm351.03-32c25.34 0 41.18-26.67 28.51-48L412.51 16c-12.67-21.33-44.35-21.33-57.02 0l-95.03 160c-12.67 21.33 3.17 48 28.51 48h190.06z\"],\n    \"share\": [512, 512, [], \"f064\", \"M503.691 189.836L327.687 37.851C312.281 24.546 288 35.347 288 56.015v80.053C127.371 137.907 0 170.1 0 322.326c0 61.441 39.581 122.309 83.333 154.132 13.653 9.931 33.111-2.533 28.077-18.631C66.066 312.814 132.917 274.316 288 272.085V360c0 20.7 24.3 31.453 39.687 18.164l176.004-152c11.071-9.562 11.086-26.753 0-36.328z\"],\n    \"share-alt\": [448, 512, [], \"f1e0\", \"M352 320c-22.608 0-43.387 7.819-59.79 20.895l-102.486-64.054a96.551 96.551 0 0 0 0-41.683l102.486-64.054C308.613 184.181 329.392 192 352 192c53.019 0 96-42.981 96-96S405.019 0 352 0s-96 42.981-96 96c0 7.158.79 14.13 2.276 20.841L155.79 180.895C139.387 167.819 118.608 160 96 160c-53.019 0-96 42.981-96 96s42.981 96 96 96c22.608 0 43.387-7.819 59.79-20.895l102.486 64.054A96.301 96.301 0 0 0 256 416c0 53.019 42.981 96 96 96s96-42.981 96-96-42.981-96-96-96z\"],\n    \"share-alt-square\": [448, 512, [], \"f1e1\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zM304 296c-14.562 0-27.823 5.561-37.783 14.671l-67.958-40.775a56.339 56.339 0 0 0 0-27.793l67.958-40.775C276.177 210.439 289.438 216 304 216c30.928 0 56-25.072 56-56s-25.072-56-56-56-56 25.072-56 56c0 4.797.605 9.453 1.74 13.897l-67.958 40.775C171.823 205.561 158.562 200 144 200c-30.928 0-56 25.072-56 56s25.072 56 56 56c14.562 0 27.823-5.561 37.783-14.671l67.958 40.775a56.088 56.088 0 0 0-1.74 13.897c0 30.928 25.072 56 56 56s56-25.072 56-56C360 321.072 334.928 296 304 296z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M568.482 177.448L424.479 313.433C409.3 327.768 384 317.14 384 295.985v-71.963c-144.575.97-205.566 35.113-164.775 171.353 4.483 14.973-12.846 26.567-25.006 17.33C155.252 383.105 120 326.488 120 269.339c0-143.937 117.599-172.5 264-173.312V24.012c0-21.174 25.317-31.768 40.479-17.448l144.003 135.988c10.02 9.463 10.028 25.425 0 34.896zM384 379.128V448H64V128h50.916a11.99 11.99 0 0 0 8.648-3.693c14.953-15.568 32.237-27.89 51.014-37.676C185.708 80.83 181.584 64 169.033 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48v-88.806c0-8.288-8.197-14.066-16.011-11.302a71.83 71.83 0 0 1-34.189 3.377c-7.27-1.046-13.8 4.514-13.8 11.859z\"],\n    \"shekel-sign\": [448, 512, [], \"f20b\", \"M248 168v168c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V168c0-75.11-60.89-136-136-136H24C10.75 32 0 42.74 0 56v408c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112h112c30.93 0 56 25.07 56 56zM432 32h-48c-8.84 0-16 7.16-16 16v296c0 30.93-25.07 56-56 56H200V176c0-8.84-7.16-16-16-16h-48c-8.84 0-16 7.16-16 16v280c0 13.25 10.75 24 24 24h168c75.11 0 136-60.89 136-136V48c0-8.84-7.16-16-16-16z\"],\n    \"shield-alt\": [512, 512, [], \"f3ed\", \"M466.5 83.7l-192-80a48.15 48.15 0 0 0-36.9 0l-192 80C27.7 91.1 16 108.6 16 128c0 198.5 114.5 335.7 221.5 380.3 11.8 4.9 25.1 4.9 36.9 0C360.1 472.6 496 349.3 496 128c0-19.4-11.7-36.9-29.5-44.3zM256.1 446.3l-.1-381 175.9 73.3c-3.3 151.4-82.1 261.1-175.8 307.7z\"],\n    \"ship\": [640, 512, [], \"f21a\", \"M496.616 372.639l70.012-70.012c16.899-16.9 9.942-45.771-12.836-53.092L512 236.102V96c0-17.673-14.327-32-32-32h-64V24c0-13.255-10.745-24-24-24H248c-13.255 0-24 10.745-24 24v40h-64c-17.673 0-32 14.327-32 32v140.102l-41.792 13.433c-22.753 7.313-29.754 36.173-12.836 53.092l70.012 70.012C125.828 416.287 85.587 448 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24 61.023 0 107.499-20.61 143.258-59.396C181.677 487.432 216.021 512 256 512h128c39.979 0 74.323-24.568 88.742-59.396C508.495 491.384 554.968 512 616 512c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24-60.817 0-101.542-31.001-119.384-75.361zM192 128h256v87.531l-118.208-37.995a31.995 31.995 0 0 0-19.584 0L192 215.531V128z\"],\n    \"shipping-fast\": [640, 512, [], \"f48b\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H112C85.5 0 64 21.5 64 48v48H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h272c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H40c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H64v128c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"shoe-prints\": [640, 512, [], \"f54b\", \"M192 160h32V32h-32c-35.35 0-64 28.65-64 64s28.65 64 64 64zM0 416c0 35.35 28.65 64 64 64h32V352H64c-35.35 0-64 28.65-64 64zm337.46-128c-34.91 0-76.16 13.12-104.73 32-24.79 16.38-44.52 32-104.73 32v128l57.53 15.97c26.21 7.28 53.01 13.12 80.31 15.05 32.69 2.31 65.6.67 97.58-6.2C472.9 481.3 512 429.22 512 384c0-64-84.18-96-174.54-96zM491.42 7.19C459.44.32 426.53-1.33 393.84.99c-27.3 1.93-54.1 7.77-80.31 15.04L256 32v128c60.2 0 79.94 15.62 104.73 32 28.57 18.88 69.82 32 104.73 32C555.82 224 640 192 640 128c0-45.22-39.1-97.3-148.58-120.81z\"],\n    \"shopping-bag\": [448, 512, [], \"f290\", \"M352 160v-32C352 57.42 294.579 0 224 0 153.42 0 96 57.42 96 128v32H0v272c0 44.183 35.817 80 80 80h288c44.183 0 80-35.817 80-80V160h-96zm-192-32c0-35.29 28.71-64 64-64s64 28.71 64 64v32H160v-32zm160 120c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm-192 0c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24z\"],\n    \"shopping-basket\": [576, 512, [], \"f291\", \"M576 216v16c0 13.255-10.745 24-24 24h-8l-26.113 182.788C514.509 462.435 494.257 480 470.37 480H105.63c-23.887 0-44.139-17.565-47.518-41.212L32 256h-8c-13.255 0-24-10.745-24-24v-16c0-13.255 10.745-24 24-24h67.341l106.78-146.821c10.395-14.292 30.407-17.453 44.701-7.058 14.293 10.395 17.453 30.408 7.058 44.701L170.477 192h235.046L326.12 82.821c-10.395-14.292-7.234-34.306 7.059-44.701 14.291-10.395 34.306-7.235 44.701 7.058L484.659 192H552c13.255 0 24 10.745 24 24zM312 392V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm112 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm-224 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24z\"],\n    \"shopping-cart\": [576, 512, [], \"f07a\", \"M528.12 301.319l47.273-208C578.806 78.301 567.391 64 551.99 64H159.208l-9.166-44.81C147.758 8.021 137.93 0 126.529 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24h69.883l70.248 343.435C147.325 417.1 136 435.222 136 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-15.674-6.447-29.835-16.824-40h209.647C430.447 426.165 424 440.326 424 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-22.172-12.888-41.332-31.579-50.405l5.517-24.276c3.413-15.018-8.002-29.319-23.403-29.319H218.117l-6.545-32h293.145c11.206 0 20.92-7.754 23.403-18.681z\"],\n    \"shower\": [512, 512, [], \"f2cc\", \"M389.66 135.6L231.6 293.66c-9.37 9.37-24.57 9.37-33.94 0l-11.32-11.32c-9.37-9.37-9.37-24.57 0-33.94l.11-.11c-34.03-40.21-35.16-98.94-3.39-140.38-11.97-7.55-26.14-11.91-41.3-11.91C98.88 96 64 130.88 64 173.76V480H0V173.76C0 95.59 63.59 32 141.76 32c36.93 0 70.61 14.2 95.86 37.42 35.9-11.51 76.5-4.5 106.67 21.03l.11-.11c9.37-9.37 24.57-9.37 33.94 0l11.32 11.32c9.37 9.37 9.37 24.57 0 33.94zM384 208c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm48-16c8.837 0 16 7.163 16 16s-7.163 16-16 16-16-7.163-16-16 7.163-16 16-16zm80 16c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-128 32c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-96 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm64 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16z\"],\n    \"shuttle-van\": [640, 512, [], \"f5b6\", \"M628.88 210.65L494.39 49.27A48.01 48.01 0 0 0 457.52 32H32C14.33 32 0 46.33 0 64v288c0 17.67 14.33 32 32 32h32c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h32c17.67 0 32-14.33 32-32V241.38c0-11.23-3.94-22.1-11.12-30.73zM64 192V96h96v96H64zm96 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm160-240h-96V96h96v96zm160 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-96-240V96h66.02l80 96H384z\"],\n    \"sign\": [512, 512, [], \"f4d9\", \"M496 64H128V16c0-8.8-7.2-16-16-16H80c-8.8 0-16 7.2-16 16v48H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V128h368c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16zM160 384h320V160H160v224z\"],\n    \"sign-in-alt\": [512, 512, [], \"f2f6\", \"M416 448h-84c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h84c17.7 0 32-14.3 32-32V160c0-17.7-14.3-32-32-32h-84c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h84c53 0 96 43 96 96v192c0 53-43 96-96 96zm-47-201L201 79c-15-15-41-4.5-41 17v96H24c-13.3 0-24 10.7-24 24v96c0 13.3 10.7 24 24 24h136v96c0 21.5 26 32 41 17l168-168c9.3-9.4 9.3-24.6 0-34z\"],\n    \"sign-language\": [448, 512, [], \"f2a7\", \"M91.434 483.987c-.307-16.018 13.109-29.129 29.13-29.129h62.293v-5.714H56.993c-16.021 0-29.437-13.111-29.13-29.129C28.16 404.491 40.835 392 56.428 392h126.429v-5.714H29.136c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h154.286v-5.714H57.707c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h168.566l-31.085-22.606c-12.762-9.281-15.583-27.149-6.302-39.912 9.281-12.761 27.15-15.582 39.912-6.302l123.361 89.715a34.287 34.287 0 0 1 14.12 27.728v141.136c0 15.91-10.946 29.73-26.433 33.374l-80.471 18.934a137.16 137.16 0 0 1-31.411 3.646H120c-15.593-.001-28.269-12.492-28.566-28.014zm73.249-225.701h36.423l-11.187-8.136c-18.579-13.511-20.313-40.887-3.17-56.536l-13.004-16.7c-9.843-12.641-28.43-15.171-40.88-5.088-12.065 9.771-14.133 27.447-4.553 39.75l36.371 46.71zm283.298-2.103l-5.003-152.452c-.518-15.771-13.722-28.136-29.493-27.619-15.773.518-28.137 13.722-27.619 29.493l1.262 38.415L283.565 11.019c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l76.889 98.745-4.509 3.511-94.79-121.734c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l94.443 121.288-4.509 3.511-77.675-99.754c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l52.053 66.849c12.497-8.257 29.055-8.285 41.69.904l123.36 89.714c10.904 7.93 17.415 20.715 17.415 34.198v16.999l61.064-47.549a34.285 34.285 0 0 0 13.202-28.177z\"],\n    \"sign-out-alt\": [512, 512, [], \"f2f5\", \"M497 273L329 441c-15 15-41 4.5-41-17v-96H152c-13.3 0-24-10.7-24-24v-96c0-13.3 10.7-24 24-24h136V88c0-21.4 25.9-32 41-17l168 168c9.3 9.4 9.3 24.6 0 34zM192 436v-40c0-6.6-5.4-12-12-12H96c-17.7 0-32-14.3-32-32V160c0-17.7 14.3-32 32-32h84c6.6 0 12-5.4 12-12V76c0-6.6-5.4-12-12-12H96c-53 0-96 43-96 96v192c0 53 43 96 96 96h84c6.6 0 12-5.4 12-12z\"],\n    \"signal\": [640, 512, [], \"f012\", \"M216 288h-48c-8.84 0-16 7.16-16 16v192c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V304c0-8.84-7.16-16-16-16zM88 384H40c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16zm256-192h-48c-8.84 0-16 7.16-16 16v288c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V208c0-8.84-7.16-16-16-16zm128-96h-48c-8.84 0-16 7.16-16 16v384c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112c0-8.84-7.16-16-16-16zM600 0h-48c-8.84 0-16 7.16-16 16v480c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"signature\": [640, 512, [], \"f5b7\", \"M623.2 192c-51.8 3.5-125.7 54.7-163.1 71.5-29.1 13.1-54.2 24.4-76.1 24.4-22.6 0-26-16.2-21.3-51.9 1.1-8 11.7-79.2-42.7-76.1-25.1 1.5-64.3 24.8-169.5 126L192 182.2c30.4-75.9-53.2-151.5-129.7-102.8L7.4 116.3C0 121-2.2 130.9 2.5 138.4l17.2 27c4.7 7.5 14.6 9.7 22.1 4.9l58-38.9c18.4-11.7 40.7 7.2 32.7 27.1L34.3 404.1C27.5 421 37 448 64 448c8.3 0 16.5-3.2 22.6-9.4 42.2-42.2 154.7-150.7 211.2-195.8-2.2 28.5-2.1 58.9 20.6 83.8 15.3 16.8 37.3 25.3 65.5 25.3 35.6 0 68-14.6 102.3-30 33-14.8 99-62.6 138.4-65.8 8.5-.7 15.2-7.3 15.2-15.8v-32.1c.2-9.1-7.5-16.8-16.6-16.2z\"],\n    \"sim-card\": [384, 512, [], \"f7c4\", \"M0 64v384c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V128L256 0H64C28.7 0 0 28.7 0 64zm224 192h-64v-64h64v64zm96 0h-64v-64h32c17.7 0 32 14.3 32 32v32zm-64 128h64v32c0 17.7-14.3 32-32 32h-32v-64zm-96 0h64v64h-64v-64zm-96 0h64v64H96c-17.7 0-32-14.3-32-32v-32zm0-96h256v64H64v-64zm0-64c0-17.7 14.3-32 32-32h32v64H64v-32z\"],\n    \"sitemap\": [640, 512, [], \"f0e8\", \"M128 352H32c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm-24-80h192v48h48v-48h192v48h48v-57.59c0-21.17-17.23-38.41-38.41-38.41H344v-64h40c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H256c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h40v64H94.41C73.23 224 56 241.23 56 262.41V320h48v-48zm264 80h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm240 0h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"skating\": [448, 512, [], \"f7c5\", \"M400 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm0 448c-8.8 0-16 7.2-16 16s-7.2 16-16 16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16h96c26.5 0 48-21.5 48-48 0-8.8-7.2-16-16-16zm-282.2 8.6c-6.2 6.2-16.4 6.3-22.6 0l-67.9-67.9c-6.2-6.2-16.4-6.2-22.6 0s-6.2 16.4 0 22.6l67.9 67.9c9.4 9.4 21.7 14 34 14s24.6-4.7 33.9-14c6.2-6.2 6.2-16.4 0-22.6s-16.4-6.3-22.7 0zm56.1-179.8l-93.7 93.7c-12.5 12.5-12.5 32.8 0 45.2 6.2 6.2 14.4 9.4 22.6 9.4s16.4-3.1 22.6-9.4l91.9-91.9-30.2-30.2c-5-5-9.4-10.7-13.2-16.8zM128 160h105.5l-20.1 17.2c-13.5 11.5-21.6 28.4-22.3 46.1-.7 17.8 6.1 35.2 18.7 47.7l78.2 78.2V432c0 17.7 14.3 32 32 32s32-14.3 32-32v-89.4c0-12.6-5.1-25-14.1-33.9l-61-61c.5-.4 1.2-.6 1.7-1.1l82.3-82.3c11.5-11.5 14.9-28.6 8.7-43.6-6.2-15-20.7-24.7-37-24.7H128c-17.7 0-32 14.3-32 32s14.3 32 32 32z\"],\n    \"skiing\": [512, 512, [], \"f7c9\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm73 356.1c-9.4-9.4-24.6-9.4-33.9 0-12.1 12.1-30.5 15.4-45.1 8.7l-135.8-70.2 49.2-73.8c12.7-19 10.2-44.5-6-60.6L293 215.7l-107-53.1c-2.9 19.9 3.4 40 17.7 54.4l75.1 75.2-45.9 68.8L35 258.7c-11.7-6-26.2-1.5-32.3 10.3-6.1 11.8-1.5 26.3 10.3 32.3l391.9 202.5c11.9 5.5 24.5 8.1 37.1 8.1 23.2 0 46-9 63-26 9.3-9.3 9.3-24.5 0-33.8zM120 91.6l-11.5 22.5c14.4 7.3 31.2 4.9 42.8-4.8l47.2 23.4c-.1.1-.1.2-.2.3l114.5 56.8 32.4-13 6.4 19.1c4 12.1 12.6 22 24 27.7l58.1 29c15.9 7.9 35 1.5 42.9-14.3 7.9-15.8 1.5-35-14.3-42.9l-52.1-26.1-17.1-51.2c-8.1-24.2-40.9-56.6-84.5-39.2l-81.2 32.5-62.5-31c.3-14.5-7.2-28.6-20.9-35.6l-11.1 21.7h-.2l-34.4-7c-1.8-.4-3.7.2-5 1.7-1.9 2.2-1.7 5.5.5 7.4l26.2 23z\"],\n    \"skiing-nordic\": [576, 512, [], \"f7ca\", \"M336 96c26.5 0 48-21.5 48-48S362.5 0 336 0s-48 21.5-48 48 21.5 48 48 48zm216 320c-13.2 0-24 10.7-24 24 0 13.2-10.8 24-24 24h-69.5L460 285.6c11.7-4.7 20.1-16.2 20.1-29.6 0-17.7-14.3-32-32-32h-44L378 170.8c-12.5-25.5-35.5-44.2-61.8-50.9L245 98.7c-28.3-6.8-57.8-.5-80.8 17.1l-39.7 30.4c-14 10.7-16.7 30.8-5.9 44.9.7.9 1.7 1.3 2.4 2.1L66.9 464H24c-13.2 0-24 10.7-24 24s10.8 24 24 24h480c39.7 0 72-32.3 72-72 0-13.2-10.8-24-24-24zm-260.5 48h-96.9l43.1-91-22-13c-12.1-7.2-21.9-16.9-29.5-27.8L123.7 464H99.5l52.3-261.4c4.1-1 8.1-2.9 11.7-5.6l39.7-30.4c7.7-5.9 17.4-8 25.3-6.1l14.7 4.4-37.5 87.4c-12.6 29.5-1.3 64 26.3 80.3l85 50.2-25.5 81.2zm110.6 0h-43.6l23.6-75.5c5.9-20.8-2.9-43.1-21.6-54.4L299.3 298l31.3-78.3 20.3 41.4c8 16.3 24.9 26.9 43.1 26.9h33.3l-25.2 176z\"],\n    \"skull\": [512, 512, [], \"f54c\", \"M256 0C114.6 0 0 100.3 0 224c0 70.1 36.9 132.6 94.5 173.7 9.6 6.9 15.2 18.1 13.5 29.9l-9.4 66.2c-1.4 9.6 6 18.2 15.7 18.2H192v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h64v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h77.7c9.7 0 17.1-8.6 15.7-18.2l-9.4-66.2c-1.7-11.7 3.8-23 13.5-29.9C475.1 356.6 512 294.1 512 224 512 100.3 397.4 0 256 0zm-96 320c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm192 0c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64z\"],\n    \"skull-crossbones\": [448, 512, [], \"f714\", \"M439.15 453.06L297.17 384l141.99-69.06c7.9-3.95 11.11-13.56 7.15-21.46L432 264.85c-3.95-7.9-13.56-11.11-21.47-7.16L224 348.41 37.47 257.69c-7.9-3.95-17.51-.75-21.47 7.16L1.69 293.48c-3.95 7.9-.75 17.51 7.15 21.46L150.83 384 8.85 453.06c-7.9 3.95-11.11 13.56-7.15 21.47l14.31 28.63c3.95 7.9 13.56 11.11 21.47 7.15L224 419.59l186.53 90.72c7.9 3.95 17.51.75 21.47-7.15l14.31-28.63c3.95-7.91.74-17.52-7.16-21.47zM150 237.28l-5.48 25.87c-2.67 12.62 5.42 24.85 16.45 24.85h126.08c11.03 0 19.12-12.23 16.45-24.85l-5.5-25.87c41.78-22.41 70-62.75 70-109.28C368 57.31 303.53 0 224 0S80 57.31 80 128c0 46.53 28.22 86.87 70 109.28zM280 112c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32zm-112 0c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32z\"],\n    \"slash\": [640, 512, [], \"f715\", \"M594.53 508.63L6.18 53.9c-6.97-5.42-8.23-15.47-2.81-22.45L23.01 6.18C28.43-.8 38.49-2.06 45.47 3.37L633.82 458.1c6.97 5.42 8.23 15.47 2.81 22.45l-19.64 25.27c-5.42 6.98-15.48 8.23-22.46 2.81z\"],\n    \"sleigh\": [640, 512, [], \"f7cc\", \"M612.7 350.7l-9.3-7.4c-6.9-5.5-17-4.4-22.5 2.5l-10 12.5c-5.5 6.9-4.4 17 2.5 22.5l9.3 7.4c5.9 4.7 9.2 11.7 9.2 19.2 0 13.6-11 24.6-24.6 24.6H48c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h516c39 0 73.7-29.3 75.9-68.3 1.4-23.8-8.7-46.3-27.2-61zM32 224c0 59.6 40.9 109.2 96 123.5V400h64v-48h192v48h64v-48c53 0 96-43 96-96v-96c17.7 0 32-14.3 32-32s-14.3-32-32-32h-96v64c0 35.3-28.7 64-64 64h-20.7c-65.8 0-125.9-37.2-155.3-96-29.4-58.8-89.6-96-155.3-96H32C14.3 32 0 46.3 0 64s14.3 32 32 32v128z\"],\n    \"sliders-h\": [512, 512, [], \"f1de\", \"M496 384H160v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h80v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h336c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160h-80v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h336v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h80c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160H288V48c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h208v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm194.8 170.2C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.6-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.4-16.2 38.1 4.2 24.6 20.5z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM112 223.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zm250.8 122.8C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.3 24.6 20.5zm6.2-118.3l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.6 8.6-11 11.9-15.1 4.5z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm158.5 16.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.7 11.1-11.4 18.3-19.8 10.8l-9.7-8.5zM157.8 325.8C180.2 352.7 213 368 248 368s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.2 24.6 20.5C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11.2-36.7 24.6-20.4z\"],\n    \"smog\": [640, 512, [], \"f75f\", \"M624 368H80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm-480 96H16c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h128c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm416 0H224c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h336c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zM144 288h156.1c22.5 19.7 51.6 32 83.9 32s61.3-12.3 83.9-32H528c61.9 0 112-50.1 112-112S589.9 64 528 64c-18 0-34.7 4.6-49.7 12.1C454 31 406.8 0 352 0c-41 0-77.8 17.3-104 44.8C221.8 17.3 185 0 144 0 64.5 0 0 64.5 0 144s64.5 144 144 144z\"],\n    \"smoking\": [640, 512, [], \"f48d\", \"M632 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8zM553.3 87.1c-5.7-3.8-9.3-10-9.3-16.8V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v62.3c0 22 10.2 43.4 28.6 55.4 42.2 27.3 67.4 73.8 67.4 124V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-65.5-32.4-126.2-86.7-162.6zM432 352H48c-26.5 0-48 21.5-48 48v64c0 26.5 21.5 48 48 48h384c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zm-32 112H224v-64h176v64zm87.7-322.4C463.8 125 448 99.3 448 70.3V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v66.4c0 43.7 24.6 81.6 60.3 106.7 22.4 15.7 35.7 41.2 35.7 68.6V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-43.3-21-83.4-56.3-108.1zM536 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8z\"],\n    \"smoking-ban\": [512, 512, [], \"f54d\", \"M96 304c0 8.8 7.2 16 16 16h117.5l-96-96H112c-8.8 0-16 7.2-16 16v64zM256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm0 448c-105.9 0-192-86.1-192-192 0-41.4 13.3-79.7 35.7-111.1l267.4 267.4C335.7 434.7 297.4 448 256 448zm45.2-192H384v32h-50.8l-32-32zm111.1 111.1L365.2 320H400c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16H269.2L144.9 99.7C176.3 77.3 214.6 64 256 64c105.9 0 192 86.1 192 192 0 41.4-13.3 79.7-35.7 111.1zM320.6 128c-15.6 0-28.6-11.2-31.4-25.9-.7-3.6-4-6.1-7.7-6.1h-16.2c-5 0-8.7 4.5-8 9.4 4.6 30.9 31.2 54.6 63.3 54.6 15.6 0 28.6 11.2 31.4 25.9.7 3.6 4 6.1 7.7 6.1h16.2c5 0 8.7-4.5 8-9.4-4.6-30.9-31.2-54.6-63.3-54.6z\"],\n    \"sms\": [512, 512, [], \"f7cd\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7 1.3 3 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128.2 304H116c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H156c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-19 38.6-42.4 38.6zm191.8-8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-68.2l-24.8 55.8c-2.9 5.9-11.4 5.9-14.3 0L224 227.8V296c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V192c0-8.8 7.2-16 16-16h16c6.1 0 11.6 3.4 14.3 8.8l17.7 35.4 17.7-35.4c2.7-5.4 8.3-8.8 14.3-8.8h16c8.8 0 16 7.2 16 16v104zm48.3 8H356c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H396c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-18.9 38.6-42.3 38.6z\"],\n    \"snowboarding\": [512, 512, [], \"f7ce\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm28.8 153.6c5.8 4.3 12.5 6.4 19.2 6.4 9.7 0 19.3-4.4 25.6-12.8 10.6-14.1 7.8-34.2-6.4-44.8l-111.4-83.5c-13.8-10.3-29.1-18.4-45.4-23.8l-63.7-21.2-26.1-52.1C244.7 2 225.5-4.4 209.7 3.5c-15.8 7.9-22.2 27.1-14.3 42.9l29.1 58.1c5.7 11.4 15.6 19.9 27.7 24l16.4 5.5-41.2 20.6c-21.8 10.9-35.4 32.8-35.4 57.2v53.1l-74.1 24.7c-16.8 5.6-25.8 23.7-20.2 40.5 1.7 5.2 4.9 9.4 8.7 12.9l-38.7-14.1c-9.7-3.5-17.4-10.6-21.8-20-5.6-12-19.9-17.2-31.9-11.6s-17.2 19.9-11.6 31.9c9.8 21 27.1 36.9 48.9 44.8l364.8 132.7c9.7 3.5 19.7 5.3 29.7 5.3 12.5 0 24.9-2.7 36.5-8.2 12-5.6 17.2-19.9 11.6-31.9S474 454.7 462 460.3c-9.3 4.4-19.8 4.8-29.5 1.3l-90.8-33.1c8.7-4.1 15.6-11.8 17.8-21.9l21.9-102c3.9-18.2-3.2-37.2-18.1-48.4l-52-39 66-30.5 83.5 62.9zm-144.4 51.7l-19.7 92c-1.5 7.1-.1 13.9 2.8 20l-169.4-61.6c2.7-.2 5.4-.4 8-1.3l85-28.4c19.6-6.5 32.8-24.8 32.8-45.5V256l60.5 45.3z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.3 345.2l-33.8-19.5 26-7c8.2-2.2 13.1-10.7 10.9-18.9l-4-14.9c-2.2-8.2-10.7-13.1-18.9-10.9l-70.8 19-63.9-37 63.8-36.9 70.8 19c8.2 2.2 16.7-2.7 18.9-10.9l4-14.9c2.2-8.2-2.7-16.7-10.9-18.9l-26-7 33.8-19.5c7.4-4.3 9.9-13.7 5.7-21.1L430.4 119c-4.3-7.4-13.7-9.9-21.1-5.7l-33.8 19.5 7-26c2.2-8.2-2.7-16.7-10.9-18.9l-14.9-4c-8.2-2.2-16.7 2.7-18.9 10.9l-19 70.8-62.8 36.2v-77.5l53.7-53.7c6.2-6.2 6.2-16.4 0-22.6l-11.3-11.3c-6.2-6.2-16.4-6.2-22.6 0L256 56.4V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v40.4l-19.7-19.7c-6.2-6.2-16.4-6.2-22.6 0L138.3 48c-6.3 6.2-6.3 16.4 0 22.6l53.7 53.7v77.5l-62.8-36.2-19-70.8c-2.2-8.2-10.7-13.1-18.9-10.9l-14.9 4c-8.2 2.2-13.1 10.7-10.9 18.9l7 26-33.8-19.5c-7.4-4.3-16.8-1.7-21.1 5.7L2.1 145.7c-4.3 7.4-1.7 16.8 5.7 21.1l33.8 19.5-26 7c-8.3 2.2-13.2 10.7-11 19l4 14.9c2.2 8.2 10.7 13.1 18.9 10.9l70.8-19 63.8 36.9-63.8 36.9-70.8-19c-8.2-2.2-16.7 2.7-18.9 10.9l-4 14.9c-2.2 8.2 2.7 16.7 10.9 18.9l26 7-33.8 19.6c-7.4 4.3-9.9 13.7-5.7 21.1l15.5 26.8c4.3 7.4 13.7 9.9 21.1 5.7l33.8-19.5-7 26c-2.2 8.2 2.7 16.7 10.9 18.9l14.9 4c8.2 2.2 16.7-2.7 18.9-10.9l19-70.8 62.8-36.2v77.5l-53.7 53.7c-6.3 6.2-6.3 16.4 0 22.6l11.3 11.3c6.2 6.2 16.4 6.2 22.6 0l19.7-19.7V496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-40.4l19.7 19.7c6.2 6.2 16.4 6.2 22.6 0l11.3-11.3c6.2-6.2 6.2-16.4 0-22.6L256 387.7v-77.5l62.8 36.2 19 70.8c2.2 8.2 10.7 13.1 18.9 10.9l14.9-4c8.2-2.2 13.1-10.7 10.9-18.9l-7-26 33.8 19.5c7.4 4.3 16.8 1.7 21.1-5.7l15.5-26.8c4.3-7.3 1.8-16.8-5.6-21z\"],\n    \"snowman\": [512, 512, [], \"f7d0\", \"M510.9 152.3l-5.9-14.5c-3.3-8-12.6-11.9-20.8-8.7L456 140.6v-29c0-8.6-7.2-15.6-16-15.6h-16c-8.8 0-16 7-16 15.6v46.9c0 .5.3 1 .3 1.5l-56.4 23c-5.9-10-13.3-18.9-22-26.6 13.6-16.6 22-37.4 22-60.5 0-53-43-96-96-96s-96 43-96 96c0 23.1 8.5 43.9 22 60.5-8.7 7.7-16 16.6-22 26.6l-56.4-23c.1-.5.3-1 .3-1.5v-46.9C104 103 96.8 96 88 96H72c-8.8 0-16 7-16 15.6v29l-28.1-11.5c-8.2-3.2-17.5.7-20.8 8.7l-5.9 14.5c-3.3 8 .7 17.1 8.9 20.3l135.2 55.2c-.4 4-1.2 8-1.2 12.2 0 10.1 1.7 19.6 4.2 28.9C120.9 296.4 104 334.2 104 376c0 54 28.4 100.9 70.8 127.8 9.3 5.9 20.3 8.2 31.3 8.2h99.2c13.3 0 26.3-4.1 37.2-11.7 46.5-32.3 74.4-89.4 62.9-152.6-5.5-30.2-20.5-57.6-41.6-79 2.5-9.2 4.2-18.7 4.2-28.7 0-4.2-.8-8.1-1.2-12.2L502 172.6c8.1-3.1 12.1-12.2 8.9-20.3zM224 96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 272c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-88s-16-23.2-16-32 7.2-16 16-16 16 7.2 16 16-16 32-16 32zm32-56c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"snowplow\": [640, 512, [], \"f7d2\", \"M120 376c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm238.6 49.4c-14.5-14.5-22.6-34.1-22.6-54.6V269.2c0-20.5 8.1-40.1 22.6-54.6l36.7-36.7c6.2-6.2 6.2-16.4 0-22.6l-22.6-22.6c-6.2-6.2-16.4-6.2-22.6 0l-36.7 36.7c-26.5 26.5-41.4 62.4-41.4 99.9V288h-64v-50.9c0-8.7-1.8-17.2-5.2-25.2L364.5 29.1C356.9 11.4 339.6 0 320.3 0H176c-26.5 0-48 21.5-48 48v112h-16c-26.5 0-48 21.5-48 48v91.2C26.3 317.2 0 355.4 0 400c0 61.9 50.1 112 112 112h256c61.9 0 112-50.1 112-112 0-17.3-4.2-33.4-11.2-48H512v18.7c0 37.5 14.9 73.4 41.4 99.9l36.7 36.7c6.2 6.2 16.4 6.2 22.6 0l22.6-22.6c6.2-6.2 6.2-16.4 0-22.6l-36.7-36.7zM192 64h117.8l68.6 160H256l-64-64V64zm176 384H112c-26.5 0-48-21.5-48-48s21.5-48 48-48h256c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"socks\": [512, 512, [], \"f696\", \"M214.66 311.01L288 256V96H128v176l-86.65 64.61c-39.4 29.56-53.86 84.42-29.21 127.06C30.39 495.25 63.27 512 96.08 512c20.03 0 40.25-6.25 57.52-19.2l21.86-16.39c-29.85-55.38-13.54-125.84 39.2-165.4zM288 32c0-11.05 3.07-21.3 8.02-30.38C293.4.92 290.85 0 288 0H160c-17.67 0-32 14.33-32 32v32h160V32zM480 0H352c-17.67 0-32 14.33-32 32v32h192V32c0-17.67-14.33-32-32-32zM320 272l-86.13 64.61c-39.4 29.56-53.86 84.42-29.21 127.06 18.25 31.58 50.61 48.33 83.42 48.33 20.03 0 40.25-6.25 57.52-19.2l115.2-86.4A127.997 127.997 0 0 0 512 304V96H320v176z\"],\n    \"solar-panel\": [640, 512, [], \"f5ba\", \"M431.98 448.01l-47.97.05V416h-128v32.21l-47.98.05c-8.82.01-15.97 7.16-15.98 15.99l-.05 31.73c-.01 8.85 7.17 16.03 16.02 16.02l223.96-.26c8.82-.01 15.97-7.16 15.98-15.98l.04-31.73c.01-8.85-7.17-16.03-16.02-16.02zM585.2 26.74C582.58 11.31 568.99 0 553.06 0H86.93C71 0 57.41 11.31 54.79 26.74-3.32 369.16.04 348.08.03 352c-.03 17.32 14.29 32 32.6 32h574.74c18.23 0 32.51-14.56 32.59-31.79.02-4.08 3.35 16.95-54.76-325.47zM259.83 64h120.33l9.77 96H250.06l9.77-96zm-75.17 256H71.09L90.1 208h105.97l-11.41 112zm16.29-160H98.24l16.29-96h96.19l-9.77 96zm32.82 160l11.4-112h149.65l11.4 112H233.77zm195.5-256h96.19l16.29 96H439.04l-9.77-96zm26.06 256l-11.4-112H549.9l19.01 112H455.33z\"],\n    \"sort\": [320, 512, [], \"f0dc\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41zm255-105L177 64c-9.4-9.4-24.6-9.4-33.9 0L24 183c-15.1 15.1-4.4 41 17 41h238c21.4 0 32.1-25.9 17-41z\"],\n    \"sort-alpha-down\": [448, 512, [], \"f15d\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm240-64H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-down-alt\": [448, 512, [], \"f881\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm112-128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-alpha-up\": [448, 512, [], \"f15e\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm400 128H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-up-alt\": [448, 512, [], \"f882\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm272 64h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-amount-down\": [512, 512, [], \"f160\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-128-64h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm256-192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-down-alt\": [512, 512, [], \"f884\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm-64 0h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-amount-up\": [512, 512, [], \"f161\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.77 160 16 160zm416 0H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-up-alt\": [512, 512, [], \"f885\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.39-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160z\"],\n    \"sort-down\": [320, 512, [], \"f0dd\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41z\"],\n    \"sort-numeric-down\": [448, 512, [], \"f162\", \"M304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zm26.15 162.91a79 79 0 0 0-55 54.17c-14.25 51.05 21.21 97.77 68.85 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zm-176-4h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-numeric-down-alt\": [448, 512, [], \"f886\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm224 64h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-numeric-up\": [448, 512, [], \"f163\", \"M330.17 258.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zM304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zM107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31z\"],\n    \"sort-numeric-up-alt\": [448, 512, [], \"f887\", \"M107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31zM400 416h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-up\": [320, 512, [], \"f0de\", \"M279 224H41c-21.4 0-32.1-25.9-17-41L143 64c9.4-9.4 24.6-9.4 33.9 0l119 119c15.2 15.1 4.5 41-16.9 41z\"],\n    \"spa\": [576, 512, [], \"f5bb\", \"M568.25 192c-29.04.13-135.01 6.16-213.84 83-33.12 29.63-53.36 63.3-66.41 94.86-13.05-31.56-33.29-65.23-66.41-94.86-78.83-76.84-184.8-82.87-213.84-83-4.41-.02-7.79 3.4-7.75 7.82.23 27.92 7.14 126.14 88.77 199.3C172.79 480.94 256 480 288 480s115.19.95 199.23-80.88c81.64-73.17 88.54-171.38 88.77-199.3.04-4.42-3.34-7.84-7.75-7.82zM287.98 302.6c12.82-18.85 27.6-35.78 44.09-50.52 19.09-18.61 39.58-33.3 60.26-45.18-16.44-70.5-51.72-133.05-96.73-172.22-4.11-3.58-11.02-3.58-15.14 0-44.99 39.14-80.27 101.63-96.74 172.07 20.37 11.7 40.5 26.14 59.22 44.39a282.768 282.768 0 0 1 45.04 51.46z\"],\n    \"space-shuttle\": [640, 512, [], \"f197\", \"M592.604 208.244C559.735 192.836 515.777 184 472 184H186.327c-4.952-6.555-10.585-11.978-16.72-16H376C229.157 137.747 219.403 32 96.003 32H96v128H80V32c-26.51 0-48 28.654-48 64v64c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v16c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v64c0 35.346 21.49 64 48 64V352h16v128h.003c123.4 0 133.154-105.747 279.997-136H169.606c6.135-4.022 11.768-9.445 16.72-16H472c43.777 0 87.735-8.836 120.604-24.244C622.282 289.845 640 271.992 640 256s-17.718-33.845-47.396-47.756zM488 296a8 8 0 0 1-8-8v-64a8 8 0 0 1 8-8c31.909 0 31.942 80 0 80z\"],\n    \"spell-check\": [576, 512, [], \"f891\", \"M272 256h91.36c43.2 0 82-32.2 84.51-75.34a79.82 79.82 0 0 0-25.26-63.07 79.81 79.81 0 0 0 9.06-44.91C427.9 30.57 389.3 0 347 0h-75a16 16 0 0 0-16 16v224a16 16 0 0 0 16 16zm40-200h40a24 24 0 0 1 0 48h-40zm0 96h56a24 24 0 0 1 0 48h-56zM155.12 22.25A32 32 0 0 0 124.64 0H99.36a32 32 0 0 0-30.48 22.25L.59 235.73A16 16 0 0 0 16 256h24.93a16 16 0 0 0 15.42-11.73L68.29 208h87.42l11.94 36.27A16 16 0 0 0 183.07 256H208a16 16 0 0 0 15.42-20.27zM89.37 144L112 75.3l22.63 68.7zm482 132.48l-45.21-45.3a15.88 15.88 0 0 0-22.59 0l-151.5 151.5-55.41-55.5a15.88 15.88 0 0 0-22.59 0l-45.3 45.3a16 16 0 0 0 0 22.59l112 112.21a15.89 15.89 0 0 0 22.6 0l208-208.21a16 16 0 0 0-.02-22.59z\"],\n    \"spider\": [576, 512, [], \"f717\", \"M151.17 167.35L177.1 176h4.67l5.22-26.12c.72-3.58 1.8-7.58 3.21-11.79l-20.29-40.58 23.8-71.39c2.79-8.38-1.73-17.44-10.12-20.24L168.42.82c-8.38-2.8-17.45 1.73-20.24 10.12l-25.89 77.68a32.04 32.04 0 0 0 1.73 24.43l27.15 54.3zm422.14 182.03l-52.75-79.12a32.002 32.002 0 0 0-26.62-14.25H416l68.99-24.36a32.03 32.03 0 0 0 16.51-12.61l53.6-80.41c4.9-7.35 2.91-17.29-4.44-22.19l-13.31-8.88c-7.35-4.9-17.29-2.91-22.19 4.44l-50.56 75.83L404.1 208H368l-10.37-51.85C355.44 145.18 340.26 96 288 96c-52.26 0-67.44 49.18-69.63 60.15L208 208h-36.1l-60.49-20.17L60.84 112c-4.9-7.35-14.83-9.34-22.19-4.44l-13.31 8.88c-7.35 4.9-9.34 14.83-4.44 22.19l53.6 80.41a32.03 32.03 0 0 0 16.51 12.61L160 256H82.06a32.02 32.02 0 0 0-26.63 14.25L2.69 349.38c-4.9 7.35-2.92 17.29 4.44 22.19l13.31 8.88c7.35 4.9 17.29 2.91 22.19-4.44l48-72h47.06l-60.83 97.33A31.988 31.988 0 0 0 72 418.3V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-73.11l74.08-118.53c-1.01 14.05-2.08 28.11-2.08 42.21C192 399.64 232.76 448 288 448s96-48.36 96-101.43c0-14.1-1.08-28.16-2.08-42.21L456 422.89V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-77.71c0-6-1.69-11.88-4.86-16.96L438.31 304h47.06l48 72c4.9 7.35 14.84 9.34 22.19 4.44l13.31-8.88c7.36-4.9 9.34-14.83 4.44-22.18zM406.09 97.51l-20.29 40.58c1.41 4.21 2.49 8.21 3.21 11.79l5.22 26.12h4.67l25.93-8.65 27.15-54.3a31.995 31.995 0 0 0 1.73-24.43l-25.89-77.68C425.03 2.56 415.96-1.98 407.58.82l-15.17 5.06c-8.38 2.8-12.91 11.86-10.12 20.24l23.8 71.39z\"],\n    \"spinner\": [512, 512, [], \"f110\", \"M304 48c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-48 368c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm208-208c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zM96 256c0-26.51-21.49-48-48-48S0 229.49 0 256s21.49 48 48 48 48-21.49 48-48zm12.922 99.078c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.491-48-48-48zm294.156 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.49-48-48-48zM108.922 60.922c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.491-48-48-48z\"],\n    \"splotch\": [512, 512, [], \"f5bc\", \"M472.29 195.89l-67.06-22.95c-19.28-6.6-33.54-20.92-38.14-38.3L351.1 74.19c-11.58-43.77-76.57-57.13-109.98-22.62l-46.14 47.67c-13.26 13.71-33.54 20.93-54.2 19.31l-71.88-5.62c-52.05-4.07-86.93 44.88-59.03 82.83l38.54 52.42c11.08 15.07 12.82 33.86 4.64 50.24L24.62 355.4c-20.59 41.25 22.84 84.87 73.49 73.81l69.96-15.28c20.11-4.39 41.45 0 57.07 11.73l54.32 40.83c39.32 29.56 101.04 7.57 104.45-37.22l4.7-61.86c1.35-17.79 12.8-33.86 30.63-42.99l62-31.74c44.88-22.96 39.59-80.17-8.95-96.79z\"],\n    \"spray-can\": [512, 512, [], \"f5bd\", \"M224 32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96h128V32zm256 96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-256 32H96c-53.02 0-96 42.98-96 96v224c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V256c0-53.02-42.98-96-96-96zm-64 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zM480 96c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm-96 32c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-96-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 0c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 192c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"square-full\": [512, 512, [], \"f45c\", \"M512 512H0V0h512v512z\"],\n    \"square-root-alt\": [576, 512, [], \"f698\", \"M571.31 251.31l-22.62-22.62c-6.25-6.25-16.38-6.25-22.63 0L480 274.75l-46.06-46.06c-6.25-6.25-16.38-6.25-22.63 0l-22.62 22.62c-6.25 6.25-6.25 16.38 0 22.63L434.75 320l-46.06 46.06c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L480 365.25l46.06 46.06c6.25 6.25 16.38 6.25 22.63 0l22.62-22.62c6.25-6.25 6.25-16.38 0-22.63L525.25 320l46.06-46.06c6.25-6.25 6.25-16.38 0-22.63zM552 0H307.65c-14.54 0-27.26 9.8-30.95 23.87l-84.79 322.8-58.41-106.1A32.008 32.008 0 0 0 105.47 224H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h43.62l88.88 163.73C168.99 503.5 186.3 512 204.94 512c17.27 0 44.44-9 54.28-41.48L357.03 96H552c13.25 0 24-10.75 24-24V24c0-13.26-10.75-24-24-24z\"],\n    \"stamp\": [512, 512, [], \"f5bf\", \"M32 512h448v-64H32v64zm384-256h-66.56c-16.26 0-29.44-13.18-29.44-29.44v-9.46c0-27.37 8.88-53.41 21.46-77.72 9.11-17.61 12.9-38.39 9.05-60.42-6.77-38.78-38.47-70.7-77.26-77.45C212.62-9.04 160 37.33 160 96c0 14.16 3.12 27.54 8.69 39.58C182.02 164.43 192 194.7 192 226.49v.07c0 16.26-13.18 29.44-29.44 29.44H96c-53.02 0-96 42.98-96 96v32c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-32c0-53.02-42.98-96-96-96z\"],\n    \"star\": [576, 512, [], \"f005\", \"M259.3 17.8L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0z\"],\n    \"star-and-crescent\": [512, 512, [], \"f699\", \"M340.47 466.36c-1.45 0-6.89.46-9.18.46-116.25 0-210.82-94.57-210.82-210.82S215.04 45.18 331.29 45.18c2.32 0 7.7.46 9.18.46 7.13 0 13.33-5.03 14.75-12.07 1.46-7.25-2.55-14.49-9.47-17.09C316.58 5.54 286.39 0 256 0 114.84 0 0 114.84 0 256s114.84 256 256 256c30.23 0 60.28-5.49 89.32-16.32 5.96-2.02 10.28-7.64 10.28-14.26 0-8.09-6.39-15.06-15.13-15.06zm162.99-252.5l-76.38-11.1-34.16-69.21c-1.83-3.7-5.38-5.55-8.93-5.55s-7.1 1.85-8.93 5.55l-34.16 69.21-76.38 11.1c-8.17 1.18-11.43 11.22-5.52 16.99l55.27 53.87-13.05 76.07c-1.11 6.44 4.01 11.66 9.81 11.66 1.53 0 3.11-.36 4.64-1.17L384 335.37l68.31 35.91c1.53.8 3.11 1.17 4.64 1.17 5.8 0 10.92-5.23 9.81-11.66l-13.05-76.07 55.27-53.87c5.91-5.77 2.65-15.81-5.52-16.99z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6V0z\"],\n    \"star-half-alt\": [536, 512, [], \"f5c0\", \"M508.55 171.51L362.18 150.2 296.77 17.81C290.89 5.98 279.42 0 267.95 0c-11.4 0-22.79 5.9-28.69 17.81l-65.43 132.38-146.38 21.29c-26.25 3.8-36.77 36.09-17.74 54.59l105.89 103-25.06 145.48C86.98 495.33 103.57 512 122.15 512c4.93 0 10-1.17 14.87-3.75l130.95-68.68 130.94 68.7c4.86 2.55 9.92 3.71 14.83 3.71 18.6 0 35.22-16.61 31.66-37.4l-25.03-145.49 105.91-102.98c19.04-18.5 8.52-50.8-17.73-54.6zm-121.74 123.2l-18.12 17.62 4.28 24.88 19.52 113.45-102.13-53.59-22.38-11.74.03-317.19 51.03 103.29 11.18 22.63 25.01 3.64 114.23 16.63-82.65 80.38z\"],\n    \"star-of-david\": [464, 512, [], \"f69a\", \"M405.68 256l53.21-89.39C473.3 142.4 455.48 112 426.88 112H319.96l-55.95-93.98C256.86 6.01 244.43 0 232 0s-24.86 6.01-32.01 18.02L144.04 112H37.11c-28.6 0-46.42 30.4-32.01 54.61L58.32 256 5.1 345.39C-9.31 369.6 8.51 400 37.11 400h106.93l55.95 93.98C207.14 505.99 219.57 512 232 512s24.86-6.01 32.01-18.02L319.96 400h106.93c28.6 0 46.42-30.4 32.01-54.61L405.68 256zm-12.78-88l-19.8 33.26L353.3 168h39.6zm-52.39 88l-52.39 88H175.88l-52.39-88 52.38-88h112.25l52.39 88zM232 73.72L254.79 112h-45.57L232 73.72zM71.1 168h39.6l-19.8 33.26L71.1 168zm0 176l19.8-33.26L110.7 344H71.1zM232 438.28L209.21 400h45.57L232 438.28zM353.29 344l19.8-33.26L392.9 344h-39.61z\"],\n    \"star-of-life\": [480, 512, [], \"f621\", \"M471.99 334.43L336.06 256l135.93-78.43c7.66-4.42 10.28-14.2 5.86-21.86l-32.02-55.43c-4.42-7.65-14.21-10.28-21.87-5.86l-135.93 78.43V16c0-8.84-7.17-16-16.01-16h-64.04c-8.84 0-16.01 7.16-16.01 16v156.86L56.04 94.43c-7.66-4.42-17.45-1.79-21.87 5.86L2.15 155.71c-4.42 7.65-1.8 17.44 5.86 21.86L143.94 256 8.01 334.43c-7.66 4.42-10.28 14.21-5.86 21.86l32.02 55.43c4.42 7.65 14.21 10.27 21.87 5.86l135.93-78.43V496c0 8.84 7.17 16 16.01 16h64.04c8.84 0 16.01-7.16 16.01-16V339.14l135.93 78.43c7.66 4.42 17.45 1.8 21.87-5.86l32.02-55.43c4.42-7.65 1.8-17.43-5.86-21.85z\"],\n    \"step-backward\": [448, 512, [], \"f048\", \"M64 468V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v176.4l195.5-181C352.1 22.3 384 36.6 384 64v384c0 27.4-31.9 41.7-52.5 24.6L136 292.7V468c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12z\"],\n    \"step-forward\": [448, 512, [], \"f051\", \"M384 44v424c0 6.6-5.4 12-12 12h-48c-6.6 0-12-5.4-12-12V291.6l-195.5 181C95.9 489.7 64 475.4 64 448V64c0-27.4 31.9-41.7 52.5-24.6L312 219.3V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12z\"],\n    \"stethoscope\": [512, 512, [], \"f0f1\", \"M447.1 112c-34.2.5-62.3 28.4-63 62.6-.5 24.3 12.5 45.6 32 56.8V344c0 57.3-50.2 104-112 104-60 0-109.2-44.1-111.9-99.2C265 333.8 320 269.2 320 192V36.6c0-11.4-8.1-21.3-19.3-23.5L237.8.5c-13-2.6-25.6 5.8-28.2 18.8L206.4 35c-2.6 13 5.8 25.6 18.8 28.2l30.7 6.1v121.4c0 52.9-42.2 96.7-95.1 97.2-53.4.5-96.9-42.7-96.9-96V69.4l30.7-6.1c13-2.6 21.4-15.2 18.8-28.2l-3.1-15.7C107.7 6.4 95.1-2 82.1.6L19.3 13C8.1 15.3 0 25.1 0 36.6V192c0 77.3 55.1 142 128.1 156.8C130.7 439.2 208.6 512 304 512c97 0 176-75.4 176-168V231.4c19.1-11.1 32-31.7 32-55.4 0-35.7-29.2-64.5-64.9-64zm.9 80c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M312 320h136V56c0-13.3-10.7-24-24-24H24C10.7 32 0 42.7 0 56v400c0 13.3 10.7 24 24 24h264V344c0-13.2 10.8-24 24-24zm129 55l-98 98c-4.5 4.5-10.6 7-17 7h-6V352h128v6.1c0 6.3-2.5 12.4-7 16.9z\"],\n    \"stop\": [448, 512, [], \"f04d\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm96 328c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16v160z\"],\n    \"stopwatch\": [448, 512, [], \"f2f2\", \"M432 304c0 114.9-93.1 208-208 208S16 418.9 16 304c0-104 76.3-190.2 176-205.5V64h-28c-6.6 0-12-5.4-12-12V12c0-6.6 5.4-12 12-12h120c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-28v34.5c37.5 5.8 71.7 21.6 99.7 44.6l27.5-27.5c4.7-4.7 12.3-4.7 17 0l28.3 28.3c4.7 4.7 4.7 12.3 0 17l-29.4 29.4-.6.6C419.7 223.3 432 262.2 432 304zm-176 36V188.5c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12V340c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"store\": [616, 512, [], \"f54e\", \"M602 118.6L537.1 15C531.3 5.7 521 0 510 0H106C95 0 84.7 5.7 78.9 15L14 118.6c-33.5 53.5-3.8 127.9 58.8 136.4 4.5.6 9.1.9 13.7.9 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18.1 20.1 44.3 33.1 73.8 33.1 4.7 0 9.2-.3 13.7-.9 62.8-8.4 92.6-82.8 59-136.4zM529.5 288c-10 0-19.9-1.5-29.5-3.8V384H116v-99.8c-9.6 2.2-19.5 3.8-29.5 3.8-6 0-12.1-.4-18-1.2-5.6-.8-11.1-2.1-16.4-3.6V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32V283.2c-5.4 1.6-10.8 2.9-16.4 3.6-6.1.8-12.1 1.2-18.2 1.2z\"],\n    \"store-alt\": [640, 512, [], \"f54f\", \"M320 384H128V224H64v256c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V224h-64v160zm314.6-241.8l-85.3-128c-6-8.9-16-14.2-26.7-14.2H117.4c-10.7 0-20.7 5.3-26.6 14.2l-85.3 128c-14.2 21.3 1 49.8 26.6 49.8H608c25.5 0 40.7-28.5 26.6-49.8zM512 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V224h-64v272z\"],\n    \"stream\": [512, 512, [], \"f550\", \"M16 128h416c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H16C7.16 32 0 39.16 0 48v64c0 8.84 7.16 16 16 16zm480 80H80c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm-64 176H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16z\"],\n    \"street-view\": [512, 512, [], \"f21d\", \"M367.9 329.76c-4.62 5.3-9.78 10.1-15.9 13.65v22.94c66.52 9.34 112 28.05 112 49.65 0 30.93-93.12 56-208 56S48 446.93 48 416c0-21.6 45.48-40.3 112-49.65v-22.94c-6.12-3.55-11.28-8.35-15.9-13.65C58.87 345.34 0 378.05 0 416c0 53.02 114.62 96 256 96s256-42.98 256-96c0-37.95-58.87-70.66-144.1-86.24zM256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-64 192v96c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-96c17.67 0 32-14.33 32-32v-96c0-26.51-21.49-48-48-48h-11.8c-11.07 5.03-23.26 8-36.2 8s-25.13-2.97-36.2-8H208c-26.51 0-48 21.49-48 48v96c0 17.67 14.33 32 32 32z\"],\n    \"strikethrough\": [512, 512, [], \"f0cc\", \"M496 224H293.9l-87.17-26.83A43.55 43.55 0 0 1 219.55 112h66.79A49.89 49.89 0 0 1 331 139.58a16 16 0 0 0 21.46 7.15l42.94-21.47a16 16 0 0 0 7.16-21.46l-.53-1A128 128 0 0 0 287.51 32h-68a123.68 123.68 0 0 0-123 135.64c2 20.89 10.1 39.83 21.78 56.36H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-180.24 96A43 43 0 0 1 336 356.45 43.59 43.59 0 0 1 292.45 400h-66.79A49.89 49.89 0 0 1 181 372.42a16 16 0 0 0-21.46-7.15l-42.94 21.47a16 16 0 0 0-7.16 21.46l.53 1A128 128 0 0 0 224.49 480h68a123.68 123.68 0 0 0 123-135.64 114.25 114.25 0 0 0-5.34-24.36z\"],\n    \"stroopwafel\": [512, 512, [], \"f551\", \"M188.12 210.74L142.86 256l45.25 45.25L233.37 256l-45.25-45.26zm113.13-22.62L256 142.86l-45.25 45.25L256 233.37l45.25-45.25zm-90.5 135.76L256 369.14l45.26-45.26L256 278.63l-45.25 45.25zM256 0C114.62 0 0 114.62 0 256s114.62 256 256 256 256-114.62 256-256S397.38 0 256 0zm186.68 295.6l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-28.29-28.29-45.25 45.25 33.94 33.94 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-33.94-33.94-45.26 45.26 28.29 28.29c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0L256 414.39l-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l28.29-28.29-45.25-45.26-33.94 33.94 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 33.94-33.94-45.25-45.25-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0L69.32 295.6c-3.12-3.12-3.12-8.19 0-11.31L97.61 256l-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l28.29 28.29 45.25-45.26-33.94-33.94-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 33.94 33.94 45.26-45.25-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0L256 97.61l28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-28.29 28.29 45.26 45.25 33.94-33.94-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-33.94 33.94 45.25 45.26 28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31L414.39 256l28.29 28.28a8.015 8.015 0 0 1 0 11.32zM278.63 256l45.26 45.25L369.14 256l-45.25-45.26L278.63 256z\"],\n    \"subscript\": [512, 512, [], \"f12c\", \"M496 448h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 352h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"subway\": [448, 512, [], \"f239\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zM200 232V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm200 0V120c0-13.255-10.745-24-24-24H272c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm-48 56c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm-256 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"suitcase\": [512, 512, [], \"f0f2\", \"M128 480h256V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v400zm64-384h128v32H192V96zm320 80v256c0 26.5-21.5 48-48 48h-48V128h48c26.5 0 48 21.5 48 48zM96 480H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h48v352z\"],\n    \"suitcase-rolling\": [384, 512, [], \"f5c1\", \"M336 160H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h16v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h128v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h16c26.51 0 48-21.49 48-48V208c0-26.51-21.49-48-48-48zm-16 216c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zM144 48h96v80h48V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v80h48V48z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M256 160c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm246.4 80.5l-94.7-47.3 33.5-100.4c4.5-13.6-8.4-26.5-21.9-21.9l-100.4 33.5-47.4-94.8c-6.4-12.8-24.6-12.8-31 0l-47.3 94.7L92.7 70.8c-13.6-4.5-26.5 8.4-21.9 21.9l33.5 100.4-94.7 47.4c-12.8 6.4-12.8 24.6 0 31l94.7 47.3-33.5 100.5c-4.5 13.6 8.4 26.5 21.9 21.9l100.4-33.5 47.3 94.7c6.4 12.8 24.6 12.8 31 0l47.3-94.7 100.4 33.5c13.6 4.5 26.5-8.4 21.9-21.9l-33.5-100.4 94.7-47.3c13-6.5 13-24.7.2-31.1zm-155.9 106c-49.9 49.9-131.1 49.9-181 0-49.9-49.9-49.9-131.1 0-181 49.9-49.9 131.1-49.9 181 0 49.9 49.9 49.9 131.1 0 181z\"],\n    \"superscript\": [512, 512, [], \"f12b\", \"M496 160h-16V16a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 64h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm112 208c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm80-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"swatchbook\": [511, 512, [], \"f5c3\", \"M479.06 320H372.29L186.15 506.51c-2.06 2.07-4.49 3.58-6.67 5.49h299.58c17.64 0 31.94-14.33 31.94-32V352c0-17.67-14.3-32-31.94-32zm-44.5-152.9l-90.33-90.51c-12.47-12.5-32.69-12.5-45.17 0l-75.5 75.65V416c0 2.96-.67 5.73-.87 8.64l211.87-212.28c12.47-12.5 12.47-32.77 0-45.26zM191.62 32c0-17.67-14.3-32-31.94-32H31.94C14.3 0 0 14.33 0 32v384c0 53.02 42.9 96 95.81 96s95.81-42.98 95.81-96V32zM95.81 440c-13.23 0-23.95-10.75-23.95-24 0-13.26 10.73-24 23.95-24s23.95 10.74 23.95 24c.01 13.25-10.72 24-23.95 24zm31.94-184H63.88v-64h63.88v64zm0-128H63.88V64h63.88v64z\"],\n    \"swimmer\": [640, 512, [], \"f5c4\", \"M189.61 310.58c3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c16.02-14.77 34.5-22.58 53.46-22.58h16.3c18.96 0 37.45 7.81 53.46 22.58 3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c14.86-13.71 31.88-21.12 49.39-22.16l-112.84-80.6 18-12.86c3.64-2.58 8.28-3.52 12.62-2.61l100.35 21.53c25.91 5.53 51.44-10.97 57-36.88 5.55-25.92-10.95-51.44-36.88-57L437.68 98.47c-30.73-6.58-63.02.12-88.56 18.38l-80.02 57.17c-10.38 7.39-19.36 16.44-26.72 26.94L173.75 299c5.47 3.23 10.82 6.93 15.86 11.58zM624 352h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 343.58 442.04 352 416 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 343.58 250.04 352 224 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 343.58 58.04 352 32 352H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-512-96c44.18 0 80-35.82 80-80s-35.82-80-80-80-80 35.82-80 80 35.82 80 80 80z\"],\n    \"swimming-pool\": [640, 512, [], \"f5c5\", \"M624 416h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 407.58 442.04 416 416 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 407.58 250.04 416 224 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 407.58 58.04 416 32 416H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-400-32v-96h192v96c19.12 0 30.86-6.16 34.39-9.42 9.17-8.46 19.2-14.34 29.61-18.07V128c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v96H224v-96c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v228.5c10.41 3.73 20.44 9.62 29.61 18.07 3.53 3.27 15.27 9.43 34.39 9.43z\"],\n    \"synagogue\": [640, 512, [], \"f69b\", \"M70 196.51L6.67 268.29A26.643 26.643 0 0 0 0 285.93V512h128V239.58l-38-43.07c-5.31-6.01-14.69-6.01-20 0zm563.33 71.78L570 196.51c-5.31-6.02-14.69-6.02-20 0l-38 43.07V512h128V285.93c0-6.5-2.37-12.77-6.67-17.64zM339.99 7.01c-11.69-9.35-28.29-9.35-39.98 0l-128 102.4A32.005 32.005 0 0 0 160 134.4V512h96v-92.57c0-31.88 21.78-61.43 53.25-66.55C349.34 346.35 384 377.13 384 416v96h96V134.4c0-9.72-4.42-18.92-12.01-24.99l-128-102.4zm52.07 215.55c1.98 3.15-.29 7.24-4 7.24h-38.94L324 269.79c-1.85 2.95-6.15 2.95-8 0l-25.12-39.98h-38.94c-3.72 0-5.98-4.09-4-7.24l19.2-30.56-19.2-30.56c-1.98-3.15.29-7.24 4-7.24h38.94l25.12-40c1.85-2.95 6.15-2.95 8 0l25.12 39.98h38.95c3.71 0 5.98 4.09 4 7.24L372.87 192l19.19 30.56z\"],\n    \"sync\": [512, 512, [], \"f021\", \"M440.65 12.57l4 82.77A247.16 247.16 0 0 0 255.83 8C134.73 8 33.91 94.92 12.29 209.82A12 12 0 0 0 24.09 224h49.05a12 12 0 0 0 11.67-9.26 175.91 175.91 0 0 1 317-56.94l-101.46-4.86a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12H500a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12h-47.37a12 12 0 0 0-11.98 12.57zM255.83 432a175.61 175.61 0 0 1-146-77.8l101.8 4.87a12 12 0 0 0 12.57-12v-47.4a12 12 0 0 0-12-12H12a12 12 0 0 0-12 12V500a12 12 0 0 0 12 12h47.35a12 12 0 0 0 12-12.6l-4.15-82.57A247.17 247.17 0 0 0 255.83 504c121.11 0 221.93-86.92 243.55-201.82a12 12 0 0 0-11.8-14.18h-49.05a12 12 0 0 0-11.67 9.26A175.86 175.86 0 0 1 255.83 432z\"],\n    \"sync-alt\": [512, 512, [], \"f2f1\", \"M370.72 133.28C339.458 104.008 298.888 87.962 255.848 88c-77.458.068-144.328 53.178-162.791 126.85-1.344 5.363-6.122 9.15-11.651 9.15H24.103c-7.498 0-13.194-6.807-11.807-14.176C33.933 94.924 134.813 8 256 8c66.448 0 126.791 26.136 171.315 68.685L463.03 40.97C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.749zM32 296h134.059c21.382 0 32.09 25.851 16.971 40.971l-41.75 41.75c31.262 29.273 71.835 45.319 114.876 45.28 77.418-.07 144.315-53.144 162.787-126.849 1.344-5.363 6.122-9.15 11.651-9.15h57.304c7.498 0 13.194 6.807 11.807 14.176C478.067 417.076 377.187 504 256 504c-66.448 0-126.791-26.136-171.315-68.685L48.97 471.03C33.851 486.149 8 475.441 8 454.059V320c0-13.255 10.745-24 24-24z\"],\n    \"syringe\": [512, 512, [], \"f48e\", \"M201.5 174.8l55.7 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-55.7-55.8-45.3 45.3 55.8 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L111 265.2l-26.4 26.4c-17.3 17.3-25.6 41.1-23 65.4l7.1 63.6L2.3 487c-3.1 3.1-3.1 8.2 0 11.3l11.3 11.3c3.1 3.1 8.2 3.1 11.3 0l66.3-66.3 63.6 7.1c23.9 2.6 47.9-5.4 65.4-23l181.9-181.9-135.7-135.7-64.9 65zm308.2-93.3L430.5 2.3c-3.1-3.1-8.2-3.1-11.3 0l-11.3 11.3c-3.1 3.1-3.1 8.2 0 11.3l28.3 28.3-45.3 45.3-56.6-56.6-17-17c-3.1-3.1-8.2-3.1-11.3 0l-33.9 33.9c-3.1 3.1-3.1 8.2 0 11.3l17 17L424.8 223l17 17c3.1 3.1 8.2 3.1 11.3 0l33.9-34c3.1-3.1 3.1-8.2 0-11.3l-73.5-73.5 45.3-45.3 28.3 28.3c3.1 3.1 8.2 3.1 11.3 0l11.3-11.3c3.1-3.2 3.1-8.2 0-11.4z\"],\n    \"table\": [512, 512, [], \"f0ce\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64v-96h160v96zm0-160H64v-96h160v96zm224 160H288v-96h160v96zm0-160H288v-96h160v96z\"],\n    \"table-tennis\": [512, 512, [], \"f45d\", \"M496.2 296.5C527.7 218.7 512 126.2 449 63.1 365.1-21 229-21 145.1 63.1l-56 56.1 211.5 211.5c46.1-62.1 131.5-77.4 195.6-34.2zm-217.9 79.7L57.9 155.9c-27.3 45.3-21.7 105 17.3 144.1l34.5 34.6L6.7 424c-8.6 7.5-9.1 20.7-1 28.8l53.4 53.5c8 8.1 21.2 7.6 28.7-1L177.1 402l35.7 35.7c19.7 19.7 44.6 30.5 70.3 33.3-7.1-17-11-35.6-11-55.1-.1-13.8 2.5-27 6.2-39.7zM416 320c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96z\"],\n    \"tablet\": [448, 512, [], \"f10a\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"tablet-alt\": [448, 512, [], \"f3fa\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm176-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h328c6.6 0 12 5.4 12 12v312z\"],\n    \"tablets\": [640, 512, [], \"f490\", \"M160 192C78.9 192 12.5 250.5.1 326.7c-.8 4.8 3.3 9.3 8.3 9.3h303.3c5 0 9.1-4.5 8.3-9.3C307.5 250.5 241.1 192 160 192zm151.6 176H8.4c-5 0-9.1 4.5-8.3 9.3C12.5 453.5 78.9 512 160 512s147.5-58.5 159.9-134.7c.8-4.8-3.3-9.3-8.3-9.3zM593.4 46.6c-56.5-56.5-144.2-61.4-206.9-16-4 2.9-4.3 8.9-.8 12.3L597 254.3c3.5 3.5 9.5 3.2 12.3-.8 45.5-62.7 40.6-150.4-15.9-206.9zM363 65.7c-3.5-3.5-9.5-3.2-12.3.8-45.4 62.7-40.5 150.4 15.9 206.9 56.5 56.5 144.2 61.4 206.9 15.9 4-2.9 4.3-8.9.8-12.3L363 65.7z\"],\n    \"tachometer-alt\": [576, 512, [], \"f3fd\", \"M288 32C128.94 32 0 160.94 0 320c0 52.8 14.25 102.26 39.06 144.8 5.61 9.62 16.3 15.2 27.44 15.2h443c11.14 0 21.83-5.58 27.44-15.2C561.75 422.26 576 372.8 576 320c0-159.06-128.94-288-288-288zm0 64c14.71 0 26.58 10.13 30.32 23.65-1.11 2.26-2.64 4.23-3.45 6.67l-9.22 27.67c-5.13 3.49-10.97 6.01-17.64 6.01-17.67 0-32-14.33-32-32S270.33 96 288 96zM96 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm48-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm246.77-72.41l-61.33 184C343.13 347.33 352 364.54 352 384c0 11.72-3.38 22.55-8.88 32H232.88c-5.5-9.45-8.88-20.28-8.88-32 0-33.94 26.5-61.43 59.9-63.59l61.34-184.01c4.17-12.56 17.73-19.45 30.36-15.17 12.57 4.19 19.35 17.79 15.17 30.36zm14.66 57.2l15.52-46.55c3.47-1.29 7.13-2.23 11.05-2.23 17.67 0 32 14.33 32 32s-14.33 32-32 32c-11.38-.01-20.89-6.28-26.57-15.22zM480 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"tag\": [512, 512, [], \"f02b\", \"M0 252.118V48C0 21.49 21.49 0 48 0h204.118a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882L293.823 497.941c-18.745 18.745-49.137 18.745-67.882 0L14.059 286.059A48 48 0 0 1 0 252.118zM112 64c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"tags\": [640, 512, [], \"f02c\", \"M497.941 225.941L286.059 14.059A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v204.118a48 48 0 0 0 14.059 33.941l211.882 211.882c18.744 18.745 49.136 18.746 67.882 0l204.118-204.118c18.745-18.745 18.745-49.137 0-67.882zM112 160c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm513.941 133.823L421.823 497.941c-18.745 18.745-49.137 18.745-67.882 0l-.36-.36L527.64 323.522c16.999-16.999 26.36-39.6 26.36-63.64s-9.362-46.641-26.36-63.64L331.397 0h48.721a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882z\"],\n    \"tape\": [640, 512, [], \"f4db\", \"M224 192c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm400 224H380.6c41.5-40.7 67.4-97.3 67.4-160 0-123.7-100.3-224-224-224S0 132.3 0 256s100.3 224 224 224h400c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400-64c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96z\"],\n    \"tasks\": [512, 512, [], \"f0ae\", \"M139.61 35.5a12 12 0 0 0-17 0L58.93 98.81l-22.7-22.12a12 12 0 0 0-17 0L3.53 92.41a12 12 0 0 0 0 17l47.59 47.4a12.78 12.78 0 0 0 17.61 0l15.59-15.62L156.52 69a12.09 12.09 0 0 0 .09-17zm0 159.19a12 12 0 0 0-17 0l-63.68 63.72-22.7-22.1a12 12 0 0 0-17 0L3.53 252a12 12 0 0 0 0 17L51 316.5a12.77 12.77 0 0 0 17.6 0l15.7-15.69 72.2-72.22a12 12 0 0 0 .09-16.9zM64 368c-26.49 0-48.59 21.5-48.59 48S37.53 464 64 464a48 48 0 0 0 0-96zm432 16H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"taxi\": [512, 512, [], \"f1ba\", \"M462 241.64l-22-84.84c-9.6-35.2-41.6-60.8-76.8-60.8H352V64c0-17.67-14.33-32-32-32H192c-17.67 0-32 14.33-32 32v32h-11.2c-35.2 0-67.2 25.6-76.8 60.8l-22 84.84C21.41 248.04 0 273.47 0 304v48c0 23.63 12.95 44.04 32 55.12V448c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-40.88c19.05-11.09 32-31.5 32-55.12v-48c0-30.53-21.41-55.96-50-62.36zM96 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm20.55-112l17.2-66.36c2.23-8.16 9.59-13.64 15.06-13.64h214.4c5.47 0 12.83 5.48 14.85 12.86L395.45 240h-278.9zM416 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"teeth\": [640, 512, [], \"f62e\", \"M544 0H96C42.98 0 0 42.98 0 96v320c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96zM160 368c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm128 128c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64z\"],\n    \"teeth-open\": [640, 512, [], \"f62f\", \"M544 0H96C42.98 0 0 42.98 0 96v64c0 35.35 28.66 64 64 64h512c35.34 0 64-28.65 64-64V96c0-53.02-42.98-96-96-96zM160 176c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm128 0c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm0 144H64c-35.34 0-64 28.65-64 64v32c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96v-32c0-35.35-28.66-64-64-64zm-416 80c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32zm144-8c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm144 0c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm128 8c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32z\"],\n    \"temperature-high\": [512, 512, [], \"f769\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V112c0-8.8-7.2-16-16-16s-16 7.2-16 16v210.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"temperature-low\": [512, 512, [], \"f76b\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V304c0-8.8-7.2-16-16-16s-16 7.2-16 16v18.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"tenge\": [384, 512, [], \"f7d7\", \"M372 160H12c-6.6 0-12 5.4-12 12v56c0 6.6 5.4 12 12 12h140v228c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12V240h140c6.6 0 12-5.4 12-12v-56c0-6.6-5.4-12-12-12zm0-128H12C5.4 32 0 37.4 0 44v56c0 6.6 5.4 12 12 12h360c6.6 0 12-5.4 12-12V44c0-6.6-5.4-12-12-12z\"],\n    \"terminal\": [640, 512, [], \"f120\", \"M257.981 272.971L63.638 467.314c-9.373 9.373-24.569 9.373-33.941 0L7.029 444.647c-9.357-9.357-9.375-24.522-.04-33.901L161.011 256 6.99 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L257.981 239.03c9.373 9.372 9.373 24.568 0 33.941zM640 456v-32c0-13.255-10.745-24-24-24H312c-13.255 0-24 10.745-24 24v32c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24z\"],\n    \"text-height\": [576, 512, [], \"f034\", \"M304 32H16A16 16 0 0 0 0 48v96a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32h56v304H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h160a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-40V112h56v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm256 336h-48V144h48c14.31 0 21.33-17.31 11.31-27.31l-80-80a16 16 0 0 0-22.62 0l-80 80C379.36 126 384.36 144 400 144h48v224h-48c-14.31 0-21.32 17.31-11.31 27.31l80 80a16 16 0 0 0 22.62 0l80-80C580.64 386 575.64 368 560 368z\"],\n    \"text-width\": [448, 512, [], \"f035\", \"M432 32H16A16 16 0 0 0 0 48v80a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-16h120v112h-24a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-24V112h120v16a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm-68.69 260.69C354 283.36 336 288.36 336 304v48H112v-48c0-14.31-17.31-21.32-27.31-11.31l-80 80a16 16 0 0 0 0 22.62l80 80C94 484.64 112 479.64 112 464v-48h224v48c0 14.31 17.31 21.33 27.31 11.31l80-80a16 16 0 0 0 0-22.62z\"],\n    \"th\": [512, 512, [], \"f00a\", \"M149.333 56v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zm181.334 240v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm32-240v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24zm-32 80V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm-205.334 56H24c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm386.667-56H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm0 160H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zM181.333 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24z\"],\n    \"th-large\": [512, 512, [], \"f009\", \"M296 32h192c13.255 0 24 10.745 24 24v160c0 13.255-10.745 24-24 24H296c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24zm-80 0H24C10.745 32 0 42.745 0 56v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zM0 296v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm296 184h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H296c-13.255 0-24 10.745-24 24v160c0 13.255 10.745 24 24 24z\"],\n    \"th-list\": [512, 512, [], \"f00b\", \"M149.333 216v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-80c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zM125.333 32H24C10.745 32 0 42.745 0 56v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zm80 448H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm-24-424v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24zm24 264H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24z\"],\n    \"theater-masks\": [640, 512, [], \"f630\", \"M206.86 245.15c-35.88 10.45-59.95 41.2-57.53 74.1 11.4-12.72 28.81-23.7 49.9-30.92l7.63-43.18zM95.81 295L64.08 115.49c-.29-1.62.28-2.62.24-2.65 57.76-32.06 123.12-49.01 189.01-49.01 1.61 0 3.23.17 4.85.19 13.95-13.47 31.73-22.83 51.59-26 18.89-3.02 38.05-4.55 57.18-5.32-9.99-13.95-24.48-24.23-41.77-27C301.27 1.89 277.24 0 253.32 0 176.66 0 101.02 19.42 33.2 57.06 9.03 70.48-3.92 98.48 1.05 126.58l31.73 179.51c14.23 80.52 136.33 142.08 204.45 142.08 3.59 0 6.75-.46 10.01-.8-13.52-17.08-28.94-40.48-39.5-67.58-47.61-12.98-106.06-51.62-111.93-84.79zm97.55-137.46c-.73-4.12-2.23-7.87-4.07-11.4-8.25 8.91-20.67 15.75-35.32 18.32-14.65 2.58-28.67.4-39.48-5.17-.52 3.94-.64 7.98.09 12.1 3.84 21.7 24.58 36.19 46.34 32.37 21.75-3.82 36.28-24.52 32.44-46.22zM606.8 120.9c-88.98-49.38-191.43-67.41-291.98-51.35-27.31 4.36-49.08 26.26-54.04 54.36l-31.73 179.51c-15.39 87.05 95.28 196.27 158.31 207.35 63.03 11.09 204.47-53.79 219.86-140.84l31.73-179.51c4.97-28.11-7.98-56.11-32.15-69.52zm-273.24 96.8c3.84-21.7 24.58-36.19 46.34-32.36 21.76 3.83 36.28 24.52 32.45 46.22-.73 4.12-2.23 7.87-4.07 11.4-8.25-8.91-20.67-15.75-35.32-18.32-14.65-2.58-28.67-.4-39.48 5.17-.53-3.95-.65-7.99.08-12.11zm70.47 198.76c-55.68-9.79-93.52-59.27-89.04-112.9 20.6 25.54 56.21 46.17 99.49 53.78 43.28 7.61 83.82.37 111.93-16.6-14.18 51.94-66.71 85.51-122.38 75.72zm130.3-151.34c-8.25-8.91-20.68-15.75-35.33-18.32-14.65-2.58-28.67-.4-39.48 5.17-.52-3.94-.64-7.98.09-12.1 3.84-21.7 24.58-36.19 46.34-32.37 21.75 3.83 36.28 24.52 32.45 46.22-.73 4.13-2.23 7.88-4.07 11.4z\"],\n    \"thermometer\": [512, 512, [], \"f491\", \"M476.8 20.4c-37.5-30.7-95.5-26.3-131.9 10.2l-45.7 46 50.5 50.5c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.4-50.5-45.1 45.4 50.3 50.4c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L209 167.4l-45.1 45.4L214 263c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.1-50.2L96 281.1V382L7 471c-9.4 9.4-9.4 24.6 0 33.9 9.4 9.4 24.6 9.4 33.9 0l89-89h99.9L484 162.6c34.9-34.9 42.2-101.5-7.2-142.2z\"],\n    \"thermometer-empty\": [256, 512, [], \"f2cb\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-35.346 28.654-64 64-64s64 28.654 64 64zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-full\": [256, 512, [], \"f2c7\", \"M224 96c0-53.019-42.981-96-96-96S32 42.981 32 96v203.347C12.225 321.756.166 351.136.002 383.333c-.359 70.303 56.787 128.176 127.089 128.664.299.002.61.003.909.003 70.698 0 128-57.304 128-128 0-32.459-12.088-62.09-32-84.653V96zm-96 368l-.576-.002c-43.86-.304-79.647-36.544-79.423-80.42.173-33.98 19.266-51.652 31.999-66.08V96c0-26.467 21.533-48 48-48s48 21.533 48 48v221.498c12.63 14.312 32 32.164 32 66.502 0 44.112-35.888 80-80 80zm64-80c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V96c0-17.673 14.327-32 32-32s32 14.327 32 32v232.583c19.124 11.068 32 31.732 32 55.417z\"],\n    \"thermometer-half\": [256, 512, [], \"f2c9\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V224c0-17.673 14.327-32 32-32s32 14.327 32 32v104.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-quarter\": [256, 512, [], \"f2ca\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V288c0-17.673 14.327-32 32-32s32 14.327 32 32v40.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-three-quarters\": [256, 512, [], \"f2c8\", \"M192 384c0 35.346-28.654 64-64 64-35.346 0-64-28.654-64-64 0-23.685 12.876-44.349 32-55.417V160c0-17.673 14.327-32 32-32s32 14.327 32 32v168.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M0 56v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56zm40 200c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24zm272 256c-20.183 0-29.485-39.293-33.931-57.795-5.206-21.666-10.589-44.07-25.393-58.902-32.469-32.524-49.503-73.967-89.117-113.111a11.98 11.98 0 0 1-3.558-8.521V59.901c0-6.541 5.243-11.878 11.783-11.998 15.831-.29 36.694-9.079 52.651-16.178C256.189 17.598 295.709.017 343.995 0h2.844c42.777 0 93.363.413 113.774 29.737 8.392 12.057 10.446 27.034 6.148 44.632 16.312 17.053 25.063 48.863 16.382 74.757 17.544 23.432 19.143 56.132 9.308 79.469l.11.11c11.893 11.949 19.523 31.259 19.439 49.197-.156 30.352-26.157 58.098-59.553 58.098H350.723C358.03 364.34 384 388.132 384 430.548 384 504 336 512 312 512z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M104 224H24c-13.255 0-24 10.745-24 24v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V248c0-13.255-10.745-24-24-24zM64 472c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zM384 81.452c0 42.416-25.97 66.208-33.277 94.548h101.723c33.397 0 59.397 27.746 59.553 58.098.084 17.938-7.546 37.249-19.439 49.197l-.11.11c9.836 23.337 8.237 56.037-9.308 79.469 8.681 25.895-.069 57.704-16.382 74.757 4.298 17.598 2.244 32.575-6.148 44.632C440.202 511.587 389.616 512 346.839 512l-2.845-.001c-48.287-.017-87.806-17.598-119.56-31.725-15.957-7.099-36.821-15.887-52.651-16.178-6.54-.12-11.783-5.457-11.783-11.998v-213.77c0-3.2 1.282-6.271 3.558-8.521 39.614-39.144 56.648-80.587 89.117-113.111 14.804-14.832 20.188-37.236 25.393-58.902C282.515 39.293 291.817 0 312 0c24 0 72 8 72 81.452z\"],\n    \"thumbtack\": [384, 512, [], \"f08d\", \"M298.028 214.267L285.793 96H328c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v48c0 13.255 10.745 24 24 24h42.207L85.972 214.267C37.465 236.82 0 277.261 0 328c0 13.255 10.745 24 24 24h136v104.007c0 1.242.289 2.467.845 3.578l24 48c2.941 5.882 11.364 5.893 14.311 0l24-48a8.008 8.008 0 0 0 .845-3.578V352h136c13.255 0 24-10.745 24-24-.001-51.183-37.983-91.42-85.973-113.733z\"],\n    \"ticket-alt\": [576, 512, [], \"f3ff\", \"M128 160h320v192H128V160zm400 96c0 26.51 21.49 48 48 48v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c26.51 0 48-21.49 48-48s-21.49-48-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v96c-26.51 0-48 21.49-48 48zm-48-104c0-13.255-10.745-24-24-24H120c-13.255 0-24 10.745-24 24v208c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V152z\"],\n    \"times\": [352, 512, [], \"f00d\", \"M242.72 256l100.07-100.07c12.28-12.28 12.28-32.19 0-44.48l-22.24-22.24c-12.28-12.28-32.19-12.28-44.48 0L176 189.28 75.93 89.21c-12.28-12.28-32.19-12.28-44.48 0L9.21 111.45c-12.28 12.28-12.28 32.19 0 44.48L109.28 256 9.21 356.07c-12.28 12.28-12.28 32.19 0 44.48l22.24 22.24c12.28 12.28 32.2 12.28 44.48 0L176 322.72l100.07 100.07c12.28 12.28 32.2 12.28 44.48 0l22.24-22.24c12.28-12.28 12.28-32.19 0-44.48L242.72 256z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm121.6 313.1c4.7 4.7 4.7 12.3 0 17L338 377.6c-4.7 4.7-12.3 4.7-17 0L256 312l-65.1 65.6c-4.7 4.7-12.3 4.7-17 0L134.4 338c-4.7-4.7-4.7-12.3 0-17l65.6-65-65.6-65.1c-4.7-4.7-4.7-12.3 0-17l39.6-39.6c4.7-4.7 12.3-4.7 17 0l65 65.7 65.1-65.6c4.7-4.7 12.3-4.7 17 0l39.6 39.6c4.7 4.7 4.7 12.3 0 17L312 256l65.6 65.1z\"],\n    \"tint\": [352, 512, [], \"f043\", \"M205.22 22.09c-7.94-28.78-49.44-30.12-58.44 0C100.01 179.85 0 222.72 0 333.91 0 432.35 78.72 512 176 512s176-79.65 176-178.09c0-111.75-99.79-153.34-146.78-311.82zM176 448c-61.75 0-112-50.25-112-112 0-8.84 7.16-16 16-16s16 7.16 16 16c0 44.11 35.89 80 80 80 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"tint-slash\": [640, 512, [], \"f5c7\", \"M633.82 458.1L494.97 350.78c.52-5.57 1.03-11.16 1.03-16.87 0-111.76-99.79-153.34-146.78-311.82-7.94-28.78-49.44-30.12-58.44 0-15.52 52.34-36.87 91.96-58.49 125.68L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM144 333.91C144 432.35 222.72 512 320 512c44.71 0 85.37-16.96 116.4-44.7L162.72 255.78c-11.41 23.5-18.72 48.35-18.72 78.13z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 288c51.9 0 115.3 43.8 123.2 106.7 1.7 13.6-8 24.6-17.7 20.4-25.9-11.1-64.4-17.4-105.5-17.4s-79.6 6.3-105.5 17.4c-9.8 4.2-19.4-7-17.7-20.4C132.7 331.8 196.1 288 248 288z\"],\n    \"toggle-off\": [576, 512, [], \"f204\", \"M384 64H192C85.961 64 0 149.961 0 256s85.961 192 192 192h192c106.039 0 192-85.961 192-192S490.039 64 384 64zM64 256c0-70.741 57.249-128 128-128 70.741 0 128 57.249 128 128 0 70.741-57.249 128-128 128-70.741 0-128-57.249-128-128zm320 128h-48.905c65.217-72.858 65.236-183.12 0-256H384c70.741 0 128 57.249 128 128 0 70.74-57.249 128-128 128z\"],\n    \"toggle-on\": [576, 512, [], \"f205\", \"M384 64H192C86 64 0 150 0 256s86 192 192 192h192c106 0 192-86 192-192S490 64 384 64zm0 320c-70.8 0-128-57.3-128-128 0-70.8 57.3-128 128-128 70.8 0 128 57.3 128 128 0 70.8-57.3 128-128 128z\"],\n    \"toilet\": [384, 512, [], \"f7d8\", \"M368 48c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v16c0 8.8 7.2 16 16 16h16v156.7C11.8 214.8 0 226.9 0 240c0 67.2 34.6 126.2 86.8 160.5l-21.4 70.2C59.1 491.2 74.5 512 96 512h192c21.5 0 36.9-20.8 30.6-41.3l-21.4-70.2C349.4 366.2 384 307.2 384 240c0-13.1-11.8-25.2-32-35.3V48h16zM80 72c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H88c-4.4 0-8-3.6-8-8V72zm112 200c-77.1 0-139.6-14.3-139.6-32s62.5-32 139.6-32 139.6 14.3 139.6 32-62.5 32-139.6 32z\"],\n    \"toilet-paper\": [576, 512, [], \"f71e\", \"M128 0C74.98 0 32 85.96 32 192v172.07c0 41.12-9.8 62.77-31.17 126.87C-2.62 501.3 5.09 512 16.01 512h280.92c13.77 0 26-8.81 30.36-21.88 12.83-38.48 24.71-72.4 24.71-126.05V192c0-83.6 23.67-153.52 60.44-192H128zM96 224c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM480 0c-53.02 0-96 85.96-96 192s42.98 192 96 192 96-85.96 96-192S533.02 0 480 0zm0 256c-17.67 0-32-28.65-32-64s14.33-64 32-64 32 28.65 32 64-14.33 64-32 64z\"],\n    \"toolbox\": [512, 512, [], \"f552\", \"M502.63 214.63l-45.25-45.25c-6-6-14.14-9.37-22.63-9.37H384V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v80H77.25c-8.49 0-16.62 3.37-22.63 9.37L9.37 214.63c-6 6-9.37 14.14-9.37 22.63V320h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-82.75c0-8.48-3.37-16.62-9.37-22.62zM320 160H192V96h128v64zm64 208c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H192v16c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H0v96c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-96H384v16z\"],\n    \"tools\": [512, 512, [], \"f7d9\", \"M501.1 395.7L384 278.6c-23.1-23.1-57.6-27.6-85.4-13.9L192 158.1V96L64 0 0 64l96 128h62.1l106.6 106.6c-13.6 27.8-9.2 62.3 13.9 85.4l117.1 117.1c14.6 14.6 38.2 14.6 52.7 0l52.7-52.7c14.5-14.6 14.5-38.2 0-52.7zM331.7 225c28.3 0 54.9 11 74.9 31l19.4 19.4c15.8-6.9 30.8-16.5 43.8-29.5 37.1-37.1 49.7-89.3 37.9-136.7-2.2-9-13.5-12.1-20.1-5.5l-74.4 74.4-67.9-11.3L334 98.9l74.4-74.4c6.6-6.6 3.4-17.9-5.7-20.2-47.4-11.7-99.6.9-136.6 37.9-28.5 28.5-41.9 66.1-41.2 103.6l82.1 82.1c8.1-1.9 16.5-2.9 24.7-2.9zm-103.9 82l-56.7-56.7L18.7 402.8c-25 25-25 65.5 0 90.5s65.5 25 90.5 0l123.6-123.6c-7.6-19.9-9.9-41.6-5-62.7zM64 472c-13.2 0-24-10.8-24-24 0-13.3 10.7-24 24-24s24 10.7 24 24c0 13.2-10.7 24-24 24z\"],\n    \"tooth\": [448, 512, [], \"f5c9\", \"M443.98 96.25c-11.01-45.22-47.11-82.06-92.01-93.72-32.19-8.36-63 5.1-89.14 24.33-3.25 2.39-6.96 3.73-10.5 5.48l28.32 18.21c7.42 4.77 9.58 14.67 4.8 22.11-4.46 6.95-14.27 9.86-22.11 4.8L162.83 12.84c-20.7-10.85-43.38-16.4-66.81-10.31-44.9 11.67-81 48.5-92.01 93.72-10.13 41.62-.42 80.81 21.5 110.43 23.36 31.57 32.68 68.66 36.29 107.35 4.4 47.16 10.33 94.16 20.94 140.32l7.8 33.95c3.19 13.87 15.49 23.7 29.67 23.7 13.97 0 26.15-9.55 29.54-23.16l34.47-138.42c4.56-18.32 20.96-31.16 39.76-31.16s35.2 12.85 39.76 31.16l34.47 138.42c3.39 13.61 15.57 23.16 29.54 23.16 14.18 0 26.48-9.83 29.67-23.7l7.8-33.95c10.61-46.15 16.53-93.16 20.94-140.32 3.61-38.7 12.93-75.78 36.29-107.35 21.95-29.61 31.66-68.8 21.53-110.43z\"],\n    \"torah\": [640, 512, [], \"f6a0\", \"M320.05 366.48l17.72-29.64h-35.46zm99.21-166H382.4l18.46 30.82zM48 0C21.49 0 0 14.33 0 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32C96 14.33 74.51 0 48 0zm172.74 311.5h36.85l-18.46-30.82zm161.71 0h36.86l-18.45-30.8zM128 464h384V48H128zm66.77-278.13a21.22 21.22 0 0 1 18.48-10.71h59.45l29.13-48.71a21.13 21.13 0 0 1 18.22-10.37A20.76 20.76 0 0 1 338 126.29l29.25 48.86h59.52a21.12 21.12 0 0 1 18.1 32L415.63 256 445 305a20.69 20.69 0 0 1 .24 21.12 21.25 21.25 0 0 1-18.48 10.72h-59.47l-29.13 48.7a21.13 21.13 0 0 1-18.16 10.4 20.79 20.79 0 0 1-18-10.22l-29.25-48.88h-59.5a21.11 21.11 0 0 1-18.1-32L224.36 256 195 207a20.7 20.7 0 0 1-.23-21.13zM592 0c-26.51 0-48 14.33-48 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32c0-17.67-21.49-32-48-32zM320 145.53l-17.78 29.62h35.46zm-62.45 55h-36.81l18.44 30.8zm29.58 111h65.79L386.09 256l-33.23-55.52h-65.79L253.9 256z\"],\n    \"torii-gate\": [512, 512, [], \"f6a1\", \"M376.45 32h-240.9A303.17 303.17 0 0 1 0 0v96c0 17.67 14.33 32 32 32h32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h256v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h48c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-48v-64h32c17.67 0 32-14.33 32-32V0a303.17 303.17 0 0 1-135.55 32zM128 128h96v64h-96v-64zm256 64h-96v-64h96v64z\"],\n    \"tractor\": [640, 512, [], \"f722\", \"M528 336c-48.6 0-88 39.4-88 88s39.4 88 88 88 88-39.4 88-88-39.4-88-88-88zm0 112c-13.23 0-24-10.77-24-24s10.77-24 24-24 24 10.77 24 24-10.77 24-24 24zm80-288h-64v-40.2c0-14.12 4.7-27.76 13.15-38.84 4.42-5.8 3.55-14.06-1.32-19.49L534.2 37.3c-6.66-7.45-18.32-6.92-24.7.78C490.58 60.9 480 89.81 480 119.8V160H377.67L321.58 29.14A47.914 47.914 0 0 0 277.45 0H144c-26.47 0-48 21.53-48 48v146.52c-8.63-6.73-20.96-6.46-28.89 1.47L36 227.1c-8.59 8.59-8.59 22.52 0 31.11l5.06 5.06c-4.99 9.26-8.96 18.82-11.91 28.72H22c-12.15 0-22 9.85-22 22v44c0 12.15 9.85 22 22 22h7.14c2.96 9.91 6.92 19.46 11.91 28.73l-5.06 5.06c-8.59 8.59-8.59 22.52 0 31.11L67.1 476c8.59 8.59 22.52 8.59 31.11 0l5.06-5.06c9.26 4.99 18.82 8.96 28.72 11.91V490c0 12.15 9.85 22 22 22h44c12.15 0 22-9.85 22-22v-7.14c9.9-2.95 19.46-6.92 28.72-11.91l5.06 5.06c8.59 8.59 22.52 8.59 31.11 0l31.11-31.11c8.59-8.59 8.59-22.52 0-31.11l-5.06-5.06c4.99-9.26 8.96-18.82 11.91-28.72H330c12.15 0 22-9.85 22-22v-6h80.54c21.91-28.99 56.32-48 95.46-48 18.64 0 36.07 4.61 51.8 12.2l50.82-50.82c6-6 9.37-14.14 9.37-22.63V192c.01-17.67-14.32-32-31.99-32zM176 416c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm22-256h-38V64h106.89l41.15 96H198z\"],\n    \"trademark\": [640, 512, [], \"f25c\", \"M260.6 96H12c-6.6 0-12 5.4-12 12v43.1c0 6.6 5.4 12 12 12h85.1V404c0 6.6 5.4 12 12 12h54.3c6.6 0 12-5.4 12-12V163.1h85.1c6.6 0 12-5.4 12-12V108c.1-6.6-5.3-12-11.9-12zM640 403l-24-296c-.5-6.2-5.7-11-12-11h-65.4c-5.1 0-9.7 3.3-11.3 8.1l-43.8 127.1c-7.2 20.6-16.1 52.8-16.1 52.8h-.9s-8.9-32.2-16.1-52.8l-43.8-127.1c-1.7-4.8-6.2-8.1-11.3-8.1h-65.4c-6.2 0-11.4 4.8-12 11l-24.4 296c-.6 7 4.9 13 12 13H360c6.3 0 11.5-4.9 12-11.2l9.1-132.9c1.8-24.2 0-53.7 0-53.7h.9s10.7 33.6 17.9 53.7l30.7 84.7c1.7 4.7 6.2 7.9 11.3 7.9h50.3c5.1 0 9.6-3.2 11.3-7.9l30.7-84.7c7.2-20.1 17.9-53.7 17.9-53.7h.9s-1.8 29.5 0 53.7l9.1 132.9c.4 6.3 5.7 11.2 12 11.2H628c7 0 12.5-6 12-13z\"],\n    \"traffic-light\": [384, 512, [], \"f637\", \"M384 192h-64v-37.88c37.2-13.22 64-48.38 64-90.12h-64V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v32H0c0 41.74 26.8 76.9 64 90.12V192H0c0 41.74 26.8 76.9 64 90.12V320H0c0 42.84 28.25 78.69 66.99 91.05C79.42 468.72 130.6 512 192 512s112.58-43.28 125.01-100.95C355.75 398.69 384 362.84 384 320h-64v-37.88c37.2-13.22 64-48.38 64-90.12zM192 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"train\": [448, 512, [], \"f238\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zm-48 136V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24zm-176 64c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56z\"],\n    \"tram\": [512, 512, [], \"f7da\", \"M288 64c17.7 0 32-14.3 32-32S305.7 0 288 0s-32 14.3-32 32 14.3 32 32 32zm223.5-12.1c-2.3-8.6-11-13.6-19.6-11.3l-480 128c-8.5 2.3-13.6 11-11.3 19.6C2.5 195.3 8.9 200 16 200c1.4 0 2.8-.2 4.1-.5L240 140.8V224H64c-17.7 0-32 14.3-32 32v224c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32H272v-91.7l228.1-60.8c8.6-2.3 13.6-11.1 11.4-19.6zM176 384H80v-96h96v96zm160-96h96v96h-96v-96zm-32 0v96h-96v-96h96zM192 96c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"transgender\": [384, 512, [], \"f224\", \"M372 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C198.5 104.1 172.2 96 144 96 64.5 96 0 160.5 0 240c0 68.5 47.9 125.9 112 140.4V408H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM144 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"transgender-alt\": [480, 512, [], \"f225\", \"M468 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C294.5 104.1 268.2 96 240 96c-28.2 0-54.5 8.1-76.7 22.1l-16.5-16.5 19.8-19.8c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0l-19.8 19.8-19-19 16.9-16.9C107.1 12.9 101.7 0 91 0H12C5.4 0 0 5.4 0 12v79c0 10.7 12.9 16 20.5 8.5l16.9-16.9 19 19-19.8 19.8c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l19.8-19.8 16.5 16.5C104.1 185.5 96 211.8 96 240c0 68.5 47.9 125.9 112 140.4V408h-36c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM240 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"trash\": [448, 512, [], \"f1f8\", \"M432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm272-256a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore\": [448, 512, [], \"f829\", \"M53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32zm70.11-175.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore-alt\": [448, 512, [], \"f82a\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm91.31-172.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"tree\": [384, 512, [], \"f1bb\", \"M378.31 378.49L298.42 288h30.63c9.01 0 16.98-5 20.78-13.06 3.8-8.04 2.55-17.26-3.28-24.05L268.42 160h28.89c9.1 0 17.3-5.35 20.86-13.61 3.52-8.13 1.86-17.59-4.24-24.08L203.66 4.83c-6.03-6.45-17.28-6.45-23.32 0L70.06 122.31c-6.1 6.49-7.75 15.95-4.24 24.08C69.38 154.65 77.59 160 86.69 160h28.89l-78.14 90.91c-5.81 6.78-7.06 15.99-3.27 24.04C37.97 283 45.93 288 54.95 288h30.63L5.69 378.49c-6 6.79-7.36 16.09-3.56 24.26 3.75 8.05 12 13.25 21.01 13.25H160v24.45l-30.29 48.4c-5.32 10.64 2.42 23.16 14.31 23.16h95.96c11.89 0 19.63-12.52 14.31-23.16L224 440.45V416h136.86c9.01 0 17.26-5.2 21.01-13.25 3.8-8.17 2.44-17.47-3.56-24.26z\"],\n    \"trophy\": [576, 512, [], \"f091\", \"M552 64H448V24c0-13.3-10.7-24-24-24H152c-13.3 0-24 10.7-24 24v40H24C10.7 64 0 74.7 0 88v56c0 35.7 22.5 72.4 61.9 100.7 31.5 22.7 69.8 37.1 110 41.7C203.3 338.5 240 360 240 360v72h-48c-35.3 0-64 20.7-64 56v12c0 6.6 5.4 12 12 12h296c6.6 0 12-5.4 12-12v-12c0-35.3-28.7-56-64-56h-48v-72s36.7-21.5 68.1-73.6c40.3-4.6 78.6-19 110-41.7 39.3-28.3 61.9-65 61.9-100.7V88c0-13.3-10.7-24-24-24zM99.3 192.8C74.9 175.2 64 155.6 64 144v-16h64.2c1 32.6 5.8 61.2 12.8 86.2-15.1-5.2-29.2-12.4-41.7-21.4zM512 144c0 16.1-17.7 36.1-35.3 48.8-12.5 9-26.7 16.2-41.8 21.4 7-25 11.8-53.6 12.8-86.2H512v16z\"],\n    \"truck\": [640, 512, [], \"f0d1\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"truck-loading\": [640, 512, [], \"f4de\", \"M50.2 375.6c2.3 8.5 11.1 13.6 19.6 11.3l216.4-58c8.5-2.3 13.6-11.1 11.3-19.6l-49.7-185.5c-2.3-8.5-11.1-13.6-19.6-11.3L151 133.3l24.8 92.7-61.8 16.5-24.8-92.7-77.3 20.7C3.4 172.8-1.7 181.6.6 190.1l49.6 185.5zM384 0c-17.7 0-32 14.3-32 32v323.6L5.9 450c-4.3 1.2-6.8 5.6-5.6 9.8l12.6 46.3c1.2 4.3 5.6 6.8 9.8 5.6l393.7-107.4C418.8 464.1 467.6 512 528 512c61.9 0 112-50.1 112-112V0H384zm144 448c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"truck-monster\": [640, 512, [], \"f63b\", \"M624 224h-16v-64c0-17.67-14.33-32-32-32h-73.6L419.22 24.02A64.025 64.025 0 0 0 369.24 0H256c-17.67 0-32 14.33-32 32v96H48c-8.84 0-16 7.16-16 16v80H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16.72c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64h65.45c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-336-96V64h81.24l51.2 64H288zm304 224h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 512 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67A110.85 110.85 0 0 0 373.2 352H368c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32c-.02-8.84-7.18-16-16.02-16zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-208-80h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 192 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0L58.18 304.8c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67a110.85 110.85 0 0 0-8.65 20.89H48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32C288 359.16 280.84 352 272 352zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"truck-moving\": [640, 512, [], \"f4df\", \"M621.3 237.3l-58.5-58.5c-12-12-28.3-18.7-45.3-18.7H480V64c0-17.7-14.3-32-32-32H32C14.3 32 0 46.3 0 64v336c0 44.2 35.8 80 80 80 26.3 0 49.4-12.9 64-32.4 14.6 19.6 37.7 32.4 64 32.4 44.2 0 80-35.8 80-80 0-5.5-.6-10.8-1.6-16h163.2c-1.1 5.2-1.6 10.5-1.6 16 0 44.2 35.8 80 80 80s80-35.8 80-80c0-5.5-.6-10.8-1.6-16H624c8.8 0 16-7.2 16-16v-85.5c0-17-6.7-33.2-18.7-45.2zM80 432c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm128 0c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm272-224h37.5c4.3 0 8.3 1.7 11.3 4.7l43.3 43.3H480v-48zm48 224c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32z\"],\n    \"truck-pickup\": [640, 512, [], \"f63c\", \"M624 288h-16v-64c0-17.67-14.33-32-32-32h-48L419.22 56.02A64.025 64.025 0 0 0 369.24 32H256c-17.67 0-32 14.33-32 32v128H64c-17.67 0-32 14.33-32 32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h49.61c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16h67.23c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM288 96h81.24l76.8 96H288V96zM176 416c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm288 0c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"tshirt\": [640, 512, [], \"f553\", \"M631.2 96.5L436.5 0C416.4 27.8 371.9 47.2 320 47.2S223.6 27.8 203.5 0L8.8 96.5c-7.9 4-11.1 13.6-7.2 21.5l57.2 114.5c4 7.9 13.6 11.1 21.5 7.2l56.6-27.7c10.6-5.2 23 2.5 23 14.4V480c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V226.3c0-11.8 12.4-19.6 23-14.4l56.6 27.7c7.9 4 17.5.8 21.5-7.2L638.3 118c4-7.9.8-17.6-7.1-21.5z\"],\n    \"tty\": [512, 512, [], \"f1e4\", \"M5.37 103.822c138.532-138.532 362.936-138.326 501.262 0 6.078 6.078 7.074 15.496 2.583 22.681l-43.214 69.138a18.332 18.332 0 0 1-22.356 7.305l-86.422-34.569a18.335 18.335 0 0 1-11.434-18.846L351.741 90c-62.145-22.454-130.636-21.986-191.483 0l5.953 59.532a18.331 18.331 0 0 1-11.434 18.846l-86.423 34.568a18.334 18.334 0 0 1-22.356-7.305L2.787 126.502a18.333 18.333 0 0 1 2.583-22.68zM96 308v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H92c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zM96 500v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H140c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"tv\": [640, 512, [], \"f26c\", \"M592 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h245.1v32h-160c-17.7 0-32 14.3-32 32s14.3 32 32 32h384c17.7 0 32-14.3 32-32s-14.3-32-32-32h-160v-32H592c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h512v288z\"],\n    \"umbrella\": [576, 512, [], \"f0e9\", \"M575.7 280.8C547.1 144.5 437.3 62.6 320 49.9V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v17.9C138.3 62.6 29.5 144.5.3 280.8c-2.2 10.1 8.5 21.3 18.7 11.4 52-55 107.7-52.4 158.6 37 5.3 9.5 14.9 8.6 19.7 0 20.2-35.4 44.9-73.2 90.7-73.2 58.5 0 88.2 68.8 90.7 73.2 4.8 8.6 14.4 9.5 19.7 0 51-89.5 107.1-91.4 158.6-37 10.3 10 20.9-1.3 18.7-11.4zM256 301.7V432c0 8.8-7.2 16-16 16-7.8 0-13.2-5.3-15.1-10.7-5.9-16.7-24.1-25.4-40.8-19.5-16.7 5.9-25.4 24.2-19.5 40.8 11.2 31.9 41.6 53.3 75.4 53.3 44.1 0 80-35.9 80-80V301.6c-9.1-7.9-19.8-13.6-32-13.6-12.3.1-22.4 4.8-32 13.7z\"],\n    \"umbrella-beach\": [640, 512, [], \"f5ca\", \"M115.38 136.9l102.11 37.18c35.19-81.54 86.21-144.29 139-173.7-95.88-4.89-188.78 36.96-248.53 111.8-6.69 8.4-2.66 21.05 7.42 24.72zm132.25 48.16l238.48 86.83c35.76-121.38 18.7-231.66-42.63-253.98-7.4-2.7-15.13-4-23.09-4-58.02.01-128.27 69.17-172.76 171.15zM521.48 60.5c6.22 16.3 10.83 34.6 13.2 55.19 5.74 49.89-1.42 108.23-18.95 166.98l102.62 37.36c10.09 3.67 21.31-3.43 21.57-14.17 2.32-95.69-41.91-187.44-118.44-245.36zM560 447.98H321.06L386 269.5l-60.14-21.9-72.9 200.37H16c-8.84 0-16 7.16-16 16.01v32.01C0 504.83 7.16 512 16 512h544c8.84 0 16-7.17 16-16.01v-32.01c0-8.84-7.16-16-16-16z\"],\n    \"underline\": [448, 512, [], \"f0cd\", \"M32 64h32v160c0 88.22 71.78 160 160 160s160-71.78 160-160V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H272a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32v160a80 80 0 0 1-160 0V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm400 384H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"undo\": [512, 512, [], \"f0e2\", \"M212.333 224.333H12c-6.627 0-12-5.373-12-12V12C0 5.373 5.373 0 12 0h48c6.627 0 12 5.373 12 12v78.112C117.773 39.279 184.26 7.47 258.175 8.007c136.906.994 246.448 111.623 246.157 248.532C504.041 393.258 393.12 504 256.333 504c-64.089 0-122.496-24.313-166.51-64.215-5.099-4.622-5.334-12.554-.467-17.42l33.967-33.967c4.474-4.474 11.662-4.717 16.401-.525C170.76 415.336 211.58 432 256.333 432c97.268 0 176-78.716 176-176 0-97.267-78.716-176-176-176-58.496 0-110.28 28.476-142.274 72.333h98.274c6.627 0 12 5.373 12 12v48c0 6.627-5.373 12-12 12z\"],\n    \"undo-alt\": [512, 512, [], \"f2ea\", \"M255.545 8c-66.269.119-126.438 26.233-170.86 68.685L48.971 40.971C33.851 25.851 8 36.559 8 57.941V192c0 13.255 10.745 24 24 24h134.059c21.382 0 32.09-25.851 16.971-40.971l-41.75-41.75c30.864-28.899 70.801-44.907 113.23-45.273 92.398-.798 170.283 73.977 169.484 169.442C423.236 348.009 349.816 424 256 424c-41.127 0-79.997-14.678-110.63-41.556-4.743-4.161-11.906-3.908-16.368.553L89.34 422.659c-4.872 4.872-4.631 12.815.482 17.433C133.798 479.813 192.074 504 256 504c136.966 0 247.999-111.033 248-247.998C504.001 119.193 392.354 7.755 255.545 8z\"],\n    \"universal-access\": [512, 512, [], \"f29a\", \"M256 48c114.953 0 208 93.029 208 208 0 114.953-93.029 208-208 208-114.953 0-208-93.029-208-208 0-114.953 93.029-208 208-208m0-40C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 56C149.961 64 64 149.961 64 256s85.961 192 192 192 192-85.961 192-192S362.039 64 256 64zm0 44c19.882 0 36 16.118 36 36s-16.118 36-36 36-36-16.118-36-36 16.118-36 36-36zm117.741 98.023c-28.712 6.779-55.511 12.748-82.14 15.807.851 101.023 12.306 123.052 25.037 155.621 3.617 9.26-.957 19.698-10.217 23.315-9.261 3.617-19.699-.957-23.316-10.217-8.705-22.308-17.086-40.636-22.261-78.549h-9.686c-5.167 37.851-13.534 56.208-22.262 78.549-3.615 9.255-14.05 13.836-23.315 10.217-9.26-3.617-13.834-14.056-10.217-23.315 12.713-32.541 24.185-54.541 25.037-155.621-26.629-3.058-53.428-9.027-82.141-15.807-8.6-2.031-13.926-10.648-11.895-19.249s10.647-13.926 19.249-11.895c96.686 22.829 124.283 22.783 220.775 0 8.599-2.03 17.218 3.294 19.249 11.895 2.029 8.601-3.297 17.219-11.897 19.249z\"],\n    \"university\": [512, 512, [], \"f19c\", \"M496 128v16a8 8 0 0 1-8 8h-24v12c0 6.627-5.373 12-12 12H60c-6.627 0-12-5.373-12-12v-12H24a8 8 0 0 1-8-8v-16a8 8 0 0 1 4.941-7.392l232-88a7.996 7.996 0 0 1 6.118 0l232 88A8 8 0 0 1 496 128zm-24 304H40c-13.255 0-24 10.745-24 24v16a8 8 0 0 0 8 8h464a8 8 0 0 0 8-8v-16c0-13.255-10.745-24-24-24zM96 192v192H60c-6.627 0-12 5.373-12 12v20h416v-20c0-6.627-5.373-12-12-12h-36V192h-64v192h-64V192h-64v192h-64V192H96z\"],\n    \"unlink\": [512, 512, [], \"f127\", \"M304.083 405.907c4.686 4.686 4.686 12.284 0 16.971l-44.674 44.674c-59.263 59.262-155.693 59.266-214.961 0-59.264-59.265-59.264-155.696 0-214.96l44.675-44.675c4.686-4.686 12.284-4.686 16.971 0l39.598 39.598c4.686 4.686 4.686 12.284 0 16.971l-44.675 44.674c-28.072 28.073-28.072 73.75 0 101.823 28.072 28.072 73.75 28.073 101.824 0l44.674-44.674c4.686-4.686 12.284-4.686 16.971 0l39.597 39.598zm-56.568-260.216c4.686 4.686 12.284 4.686 16.971 0l44.674-44.674c28.072-28.075 73.75-28.073 101.824 0 28.072 28.073 28.072 73.75 0 101.823l-44.675 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.598 39.598c4.686 4.686 12.284 4.686 16.971 0l44.675-44.675c59.265-59.265 59.265-155.695 0-214.96-59.266-59.264-155.695-59.264-214.961 0l-44.674 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.597 39.598zm234.828 359.28l22.627-22.627c9.373-9.373 9.373-24.569 0-33.941L63.598 7.029c-9.373-9.373-24.569-9.373-33.941 0L7.029 29.657c-9.373 9.373-9.373 24.569 0 33.941l441.373 441.373c9.373 9.372 24.569 9.372 33.941 0z\"],\n    \"unlock\": [448, 512, [], \"f09c\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"unlock-alt\": [448, 512, [], \"f13e\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zM264 408c0 22.1-17.9 40-40 40s-40-17.9-40-40v-48c0-22.1 17.9-40 40-40s40 17.9 40 40v48z\"],\n    \"upload\": [512, 512, [], \"f093\", \"M296 384h-80c-13.3 0-24-10.7-24-24V192h-87.7c-17.8 0-26.7-21.5-14.1-34.1L242.3 5.7c7.5-7.5 19.8-7.5 27.3 0l152.2 152.2c12.6 12.6 3.7 34.1-14.1 34.1H320v168c0 13.3-10.7 24-24 24zm216-8v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h136v8c0 30.9 25.1 56 56 56h80c30.9 0 56-25.1 56-56v-8h136c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"user\": [448, 512, [], \"f007\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-alt\": [512, 512, [], \"f406\", \"M256 288c79.5 0 144-64.5 144-144S335.5 0 256 0 112 64.5 112 144s64.5 144 144 144zm128 32h-55.1c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16H128C57.3 320 0 377.3 0 448v16c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-16c0-70.7-57.3-128-128-128z\"],\n    \"user-alt-slash\": [640, 512, [], \"f4fa\", \"M633.8 458.1L389.6 269.3C433.8 244.7 464 198.1 464 144 464 64.5 399.5 0 320 0c-67.1 0-123 46.1-139 108.2L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM198.4 320C124.2 320 64 380.2 64 454.4v9.6c0 26.5 21.5 48 48 48h382.2L245.8 320h-47.4z\"],\n    \"user-astronaut\": [448, 512, [], \"f4fb\", \"M64 224h13.5c24.7 56.5 80.9 96 146.5 96s121.8-39.5 146.5-96H384c8.8 0 16-7.2 16-16v-96c0-8.8-7.2-16-16-16h-13.5C345.8 39.5 289.6 0 224 0S102.2 39.5 77.5 96H64c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16zm40-88c0-22.1 21.5-40 48-40h144c26.5 0 48 17.9 48 40v24c0 53-43 96-96 96h-48c-53 0-96-43-96-96v-24zm72 72l12-36 36-12-36-12-12-36-12 36-36 12 36 12 12 36zm151.6 113.4C297.7 340.7 262.2 352 224 352s-73.7-11.3-103.6-30.6C52.9 328.5 0 385 0 454.4v9.6c0 26.5 21.5 48 48 48h80v-64c0-17.7 14.3-32 32-32h128c17.7 0 32 14.3 32 32v64h80c26.5 0 48-21.5 48-48v-9.6c0-69.4-52.9-125.9-120.4-133zM272 448c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-96 0c-8.8 0-16 7.2-16 16v48h32v-48c0-8.8-7.2-16-16-16z\"],\n    \"user-check\": [640, 512, [], \"f4fc\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4zm323-128.4l-27.8-28.1c-4.6-4.7-12.1-4.7-16.8-.1l-104.8 104-45.5-45.8c-4.6-4.7-12.1-4.7-16.8-.1l-28.1 27.9c-4.7 4.6-4.7 12.1-.1 16.8l81.7 82.3c4.6 4.7 12.1 4.7 16.8.1l141.3-140.2c4.6-4.7 4.7-12.2.1-16.8z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 96c48.6 0 88 39.4 88 88s-39.4 88-88 88-88-39.4-88-88 39.4-88 88-88zm0 344c-58.7 0-111.3-26.6-146.5-68.2 18.8-35.4 55.6-59.8 98.5-59.8 2.4 0 4.8.4 7.1 1.1 13 4.2 26.6 6.9 40.9 6.9 14.3 0 28-2.7 40.9-6.9 2.3-.7 4.7-1.1 7.1-1.1 42.9 0 79.7 24.4 98.5 59.8C359.3 421.4 306.7 448 248 448z\"],\n    \"user-clock\": [640, 512, [], \"f4fd\", \"M496 224c-79.6 0-144 64.4-144 144s64.4 144 144 144 144-64.4 144-144-64.4-144-144-144zm64 150.3c0 5.3-4.4 9.7-9.7 9.7h-60.6c-5.3 0-9.7-4.4-9.7-9.7v-76.6c0-5.3 4.4-9.7 9.7-9.7h12.6c5.3 0 9.7 4.4 9.7 9.7V352h38.3c5.3 0 9.7 4.4 9.7 9.7v12.6zM320 368c0-27.8 6.7-54.1 18.2-77.5-8-1.5-16.2-2.5-24.6-2.5h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h347.1c-45.3-31.9-75.1-84.5-75.1-144zm-96-112c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128z\"],\n    \"user-cog\": [640, 512, [], \"f4fe\", \"M610.5 373.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 400.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm201.2 226.5c-2.3-1.2-4.6-2.6-6.8-3.9l-7.9 4.6c-6 3.4-12.8 5.3-19.6 5.3-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-5.5-17.7 1.9-36.4 17.9-45.7l7.9-4.6c-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-16-9.2-23.4-28-17.9-45.7.9-2.9 2.2-5.8 3.2-8.7-3.8-.3-7.5-1.2-11.4-1.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c10.1 0 19.5-3.2 27.2-8.5-1.2-3.8-2-7.7-2-11.8v-9.2z\"],\n    \"user-edit\": [640, 512, [], \"f4ff\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h274.9c-2.4-6.8-3.4-14-2.6-21.3l6.8-60.9 1.2-11.1 7.9-7.9 77.3-77.3c-24.5-27.7-60-45.5-99.9-45.5zm45.3 145.3l-6.8 61c-1.1 10.2 7.5 18.8 17.6 17.6l60.9-6.8 137.9-137.9-71.7-71.7-137.9 137.8zM633 268.9L595.1 231c-9.3-9.3-24.5-9.3-33.8 0l-37.8 37.8-4.1 4.1 71.8 71.7 41.8-41.8c9.3-9.4 9.3-24.5 0-33.9z\"],\n    \"user-friends\": [640, 512, [], \"f500\", \"M192 256c61.9 0 112-50.1 112-112S253.9 32 192 32 80 82.1 80 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C51.6 288 0 339.6 0 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zM480 256c53 0 96-43 96-96s-43-96-96-96-96 43-96 96 43 96 96 96zm48 32h-3.8c-13.9 4.8-28.6 8-44.2 8s-30.3-3.2-44.2-8H432c-20.4 0-39.2 5.9-55.7 15.4 24.4 26.3 39.7 61.2 39.7 99.8v38.4c0 2.2-.5 4.3-.6 6.4H592c26.5 0 48-21.5 48-48 0-61.9-50.1-112-112-112z\"],\n    \"user-graduate\": [448, 512, [], \"f501\", \"M319.4 320.6L224 416l-95.4-95.4C57.1 323.7 0 382.2 0 454.4v9.6c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-9.6c0-72.2-57.1-130.7-128.6-133.8zM13.6 79.8l6.4 1.5v58.4c-7 4.2-12 11.5-12 20.3 0 8.4 4.6 15.4 11.1 19.7L3.5 242c-1.7 6.9 2.1 14 7.6 14h41.8c5.5 0 9.3-7.1 7.6-14l-15.6-62.3C51.4 175.4 56 168.4 56 160c0-8.8-5-16.1-12-20.3V87.1l66 15.9c-8.6 17.2-14 36.4-14 57 0 70.7 57.3 128 128 128s128-57.3 128-128c0-20.6-5.3-39.8-14-57l96.3-23.2c18.2-4.4 18.2-27.1 0-31.5l-190.4-46c-13-3.1-26.7-3.1-39.7 0L13.6 48.2c-18.1 4.4-18.1 27.2 0 31.6z\"],\n    \"user-injured\": [448, 512, [], \"f728\", \"M277.37 11.98C261.08 4.47 243.11 0 224 0c-53.69 0-99.5 33.13-118.51 80h81.19l90.69-68.02zM342.51 80c-7.9-19.47-20.67-36.2-36.49-49.52L239.99 80h102.52zM224 256c70.69 0 128-57.31 128-128 0-5.48-.95-10.7-1.61-16H97.61c-.67 5.3-1.61 10.52-1.61 16 0 70.69 57.31 128 128 128zM80 299.7V512h128.26l-98.45-221.52A132.835 132.835 0 0 0 80 299.7zM0 464c0 26.51 21.49 48 48 48V320.24C18.88 344.89 0 381.26 0 422.4V464zm256-48h-55.38l42.67 96H256c26.47 0 48-21.53 48-48s-21.53-48-48-48zm57.6-128h-16.71c-22.24 10.18-46.88 16-72.89 16s-50.65-5.82-72.89-16h-7.37l42.67 96H256c44.11 0 80 35.89 80 80 0 18.08-6.26 34.59-16.41 48H400c26.51 0 48-21.49 48-48v-41.6c0-74.23-60.17-134.4-134.4-134.4z\"],\n    \"user-lock\": [640, 512, [], \"f502\", \"M224 256A128 128 0 1 0 96 128a128 128 0 0 0 128 128zm96 64a63.08 63.08 0 0 1 8.1-30.5c-4.8-.5-9.5-1.5-14.5-1.5h-16.7a174.08 174.08 0 0 1-145.8 0h-16.7A134.43 134.43 0 0 0 0 422.4V464a48 48 0 0 0 48 48h280.9a63.54 63.54 0 0 1-8.9-32zm288-32h-32v-80a80 80 0 0 0-160 0v80h-32a32 32 0 0 0-32 32v160a32 32 0 0 0 32 32h224a32 32 0 0 0 32-32V320a32 32 0 0 0-32-32zM496 432a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm32-144h-64v-80a32 32 0 0 1 64 0z\"],\n    \"user-md\": [448, 512, [], \"f0f0\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zM104 424c0 13.3 10.7 24 24 24s24-10.7 24-24-10.7-24-24-24-24 10.7-24 24zm216-135.4v49c36.5 7.4 64 39.8 64 78.4v41.7c0 7.6-5.4 14.2-12.9 15.7l-32.2 6.4c-4.3.9-8.5-1.9-9.4-6.3l-3.1-15.7c-.9-4.3 1.9-8.6 6.3-9.4l19.3-3.9V416c0-62.8-96-65.1-96 1.9v26.7l19.3 3.9c4.3.9 7.1 5.1 6.3 9.4l-3.1 15.7c-.9 4.3-5.1 7.1-9.4 6.3l-31.2-4.2c-7.9-1.1-13.8-7.8-13.8-15.9V416c0-38.6 27.5-70.9 64-78.4v-45.2c-2.2.7-4.4 1.1-6.6 1.9-18 6.3-37.3 9.8-57.4 9.8s-39.4-3.5-57.4-9.8c-7.4-2.6-14.9-4.2-22.6-5.2v81.6c23.1 6.9 40 28.1 40 53.4 0 30.9-25.1 56-56 56s-56-25.1-56-56c0-25.3 16.9-46.5 40-53.4v-80.4C48.5 301 0 355.8 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-72-56.8-130.3-128-133.8z\"],\n    \"user-minus\": [640, 512, [], \"f503\", \"M624 208H432c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h192c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-ninja\": [448, 512, [], \"f504\", \"M325.4 289.2L224 390.6 122.6 289.2C54 295.3 0 352.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-70.2-54-127.1-122.6-133.2zM32 192c27.3 0 51.8-11.5 69.2-29.7 15.1 53.9 64 93.7 122.8 93.7 70.7 0 128-57.3 128-128S294.7 0 224 0c-50.4 0-93.6 29.4-114.5 71.8C92.1 47.8 64 32 32 32c0 33.4 17.1 62.8 43.1 80-26 17.2-43.1 46.6-43.1 80zm144-96h96c17.7 0 32 14.3 32 32H144c0-17.7 14.3-32 32-32z\"],\n    \"user-nurse\": [448, 512, [], \"f82f\", \"M57.78 288h82.36c22.51 19.68 51.62 32 83.86 32s61.35-12.32 83.86-32h82.36a16 16 0 0 0 14.28-23.18c-15.23-29.85-31.28-62.23-42.15-95.54C354.78 146.09 352 121.59 352 97.2V48L224 0 96 48v49.2c0 24.39-2.75 48.89-10.33 72.08C74.78 202.59 58.73 235 43.5 264.82A16 16 0 0 0 57.78 288zM184 71.67a5 5 0 0 1 5-5h21.67V45a5 5 0 0 1 5-5h16.66a5 5 0 0 1 5 5v21.67H259a5 5 0 0 1 5 5v16.66a5 5 0 0 1-5 5h-21.67V115a5 5 0 0 1-5 5h-16.66a5 5 0 0 1-5-5V93.33H189a5 5 0 0 1-5-5zM144 160h160v32a80 80 0 0 1-160 0zm175.41 160L224 415.39 128.59 320C57.1 323.1 0 381.6 0 453.79A58.21 58.21 0 0 0 58.21 512h331.58A58.21 58.21 0 0 0 448 453.79C448 381.6 390.9 323.1 319.41 320z\"],\n    \"user-plus\": [640, 512, [], \"f234\", \"M624 208h-64v-64c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v64h-64c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h64v64c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-64h64c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-secret\": [448, 512, [], \"f21b\", \"M383.9 308.3l23.9-62.6c4-10.5-3.7-21.7-15-21.7h-58.5c11-18.9 17.8-40.6 17.8-64v-.3c39.2-7.8 64-19.1 64-31.7 0-13.3-27.3-25.1-70.1-33-9.2-32.8-27-65.8-40.6-82.8-9.5-11.9-25.9-15.6-39.5-8.8l-27.6 13.8c-9 4.5-19.6 4.5-28.6 0L182.1 3.4c-13.6-6.8-30-3.1-39.5 8.8-13.5 17-31.4 50-40.6 82.8-42.7 7.9-70 19.7-70 33 0 12.6 24.8 23.9 64 31.7v.3c0 23.4 6.8 45.1 17.8 64H56.3c-11.5 0-19.2 11.7-14.7 22.3l25.8 60.2C27.3 329.8 0 372.7 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-48.4-25.8-90.4-64.1-114.1zM176 480l-41.6-192 49.6 32 24 40-32 120zm96 0l-32-120 24-40 49.6-32L272 480zm41.7-298.5c-3.9 11.9-7 24.6-16.5 33.4-10.1 9.3-48 22.4-64-25-2.8-8.4-15.4-8.4-18.3 0-17 50.2-56 32.4-64 25-9.5-8.8-12.7-21.5-16.5-33.4-.8-2.5-6.3-5.7-6.3-5.8v-10.8c28.3 3.6 61 5.8 96 5.8s67.7-2.1 96-5.8v10.8c-.1.1-5.6 3.2-6.4 5.8z\"],\n    \"user-shield\": [640, 512, [], \"f505\", \"M622.3 271.1l-115.2-45c-4.1-1.6-12.6-3.7-22.2 0l-115.2 45c-10.7 4.2-17.7 14-17.7 24.9 0 111.6 68.7 188.8 132.9 213.9 9.6 3.7 18 1.6 22.2 0C558.4 489.9 640 420.5 640 296c0-10.9-7-20.7-17.7-24.9zM496 462.4V273.3l95.5 37.3c-5.6 87.1-60.9 135.4-95.5 151.8zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm96 40c0-2.5.8-4.8 1.1-7.2-2.5-.1-4.9-.8-7.5-.8h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c6.8 0 13.3-1.5 19.2-4-54-42.9-99.2-116.7-99.2-212z\"],\n    \"user-slash\": [640, 512, [], \"f506\", \"M633.8 458.1L362.3 248.3C412.1 230.7 448 183.8 448 128 448 57.3 390.7 0 320 0c-67.1 0-121.5 51.8-126.9 117.4L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM96 422.4V464c0 26.5 21.5 48 48 48h350.2L207.4 290.3C144.2 301.3 96 356 96 422.4z\"],\n    \"user-tag\": [640, 512, [], \"f507\", \"M630.6 364.9l-90.3-90.2c-12-12-28.3-18.7-45.3-18.7h-79.3c-17.7 0-32 14.3-32 32v79.2c0 17 6.7 33.2 18.7 45.2l90.3 90.2c12.5 12.5 32.8 12.5 45.3 0l92.5-92.5c12.6-12.5 12.6-32.7.1-45.2zm-182.8-21c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24c0 13.2-10.7 24-24 24zm-223.8-88c70.7 0 128-57.3 128-128C352 57.3 294.7 0 224 0S96 57.3 96 128c0 70.6 57.3 127.9 128 127.9zm127.8 111.2V294c-12.2-3.6-24.9-6.2-38.2-6.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 287.9 0 348.1 0 422.3v41.6c0 26.5 21.5 48 48 48h352c15.5 0 29.1-7.5 37.9-18.9l-58-58c-18.1-18.1-28.1-42.2-28.1-67.9z\"],\n    \"user-tie\": [448, 512, [], \"f508\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm95.8 32.6L272 480l-32-136 32-56h-96l32 56-32 136-47.8-191.4C56.9 292 0 350.3 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-72.1-56.9-130.4-128.2-133.8z\"],\n    \"user-times\": [640, 512, [], \"f235\", \"M589.6 240l45.6-45.6c6.3-6.3 6.3-16.5 0-22.8l-22.8-22.8c-6.3-6.3-16.5-6.3-22.8 0L544 194.4l-45.6-45.6c-6.3-6.3-16.5-6.3-22.8 0l-22.8 22.8c-6.3 6.3-6.3 16.5 0 22.8l45.6 45.6-45.6 45.6c-6.3 6.3-6.3 16.5 0 22.8l22.8 22.8c6.3 6.3 16.5 6.3 22.8 0l45.6-45.6 45.6 45.6c6.3 6.3 16.5 6.3 22.8 0l22.8-22.8c6.3-6.3 6.3-16.5 0-22.8L589.6 240zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"users\": [640, 512, [], \"f0c0\", \"M96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm448 0c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm32 32h-64c-17.6 0-33.5 7.1-45.1 18.6 40.3 22.1 68.9 62 75.1 109.4h66c17.7 0 32-14.3 32-32v-32c0-35.3-28.7-64-64-64zm-256 0c61.9 0 112-50.1 112-112S381.9 32 320 32 208 82.1 208 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zm-223.7-13.4C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"users-cog\": [640, 512, [], \"f509\", \"M610.5 341.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 368.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm224 32c1.9 0 3.7-.5 5.6-.6 8.3-21.7 20.5-42.1 36.3-59.2 7.4-8 17.9-12.6 28.9-12.6 6.9 0 13.7 1.8 19.6 5.3l7.9 4.6c.8-.5 1.6-.9 2.4-1.4 7-14.6 11.2-30.8 11.2-48 0-61.9-50.1-112-112-112S208 82.1 208 144c0 61.9 50.1 112 112 112zm105.2 194.5c-2.3-1.2-4.6-2.6-6.8-3.9-8.2 4.8-15.3 9.8-27.5 9.8-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-10.7-34.5 24.9-49.7 25.8-50.3-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-3.8-2.2-7-5-9.8-8.1-3.3.2-6.5.6-9.8.6-24.6 0-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h255.4c-3.7-6-6.2-12.8-6.2-20.3v-9.2zM173.1 274.6C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"utensil-spoon\": [512, 512, [], \"f2e5\", \"M480.1 31.9c-55-55.1-164.9-34.5-227.8 28.5-49.3 49.3-55.1 110-28.8 160.4L9 413.2c-11.6 10.5-12.1 28.5-1 39.5L59.3 504c11 11 29.1 10.5 39.5-1.1l192.4-214.4c50.4 26.3 111.1 20.5 160.4-28.8 63-62.9 83.6-172.8 28.5-227.8z\"],\n    \"utensils\": [416, 512, [], \"f2e7\", \"M207.9 15.2c.8 4.7 16.1 94.5 16.1 128.8 0 52.3-27.8 89.6-68.9 104.6L168 486.7c.7 13.7-10.2 25.3-24 25.3H80c-13.7 0-24.7-11.5-24-25.3l12.9-238.1C27.7 233.6 0 196.2 0 144 0 109.6 15.3 19.9 16.1 15.2 19.3-5.1 61.4-5.4 64 16.3v141.2c1.3 3.4 15.1 3.2 16 0 1.4-25.3 7.9-139.2 8-141.8 3.3-20.8 44.7-20.8 47.9 0 .2 2.7 6.6 116.5 8 141.8.9 3.2 14.8 3.4 16 0V16.3c2.6-21.6 44.8-21.4 48-1.1zm119.2 285.7l-15 185.1c-1.2 14 9.9 26 23.9 26h56c13.3 0 24-10.7 24-24V24c0-13.2-10.7-24-24-24-82.5 0-221.4 178.5-64.9 300.9z\"],\n    \"vector-square\": [512, 512, [], \"f5cb\", \"M512 128V32c0-17.67-14.33-32-32-32h-96c-17.67 0-32 14.33-32 32H160c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32v192c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32h192c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32V160c17.67 0 32-14.33 32-32zm-96-64h32v32h-32V64zM64 64h32v32H64V64zm32 384H64v-32h32v32zm352 0h-32v-32h32v32zm-32-96h-32c-17.67 0-32 14.33-32 32v32H160v-32c0-17.67-14.33-32-32-32H96V160h32c17.67 0 32-14.33 32-32V96h192v32c0 17.67 14.33 32 32 32h32v192z\"],\n    \"venus\": [288, 512, [], \"f221\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"venus-double\": [512, 512, [], \"f226\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80zm336 140.4V368h36c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-36v36c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-36h-36c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h36v-51.6c-21.2-4.8-40.6-14.3-57.2-27.3 14-16.7 25-36 32.1-57.1 14.5 14.8 34.7 24 57.1 24 44.1 0 80-35.9 80-80s-35.9-80-80-80c-22.3 0-42.6 9.2-57.1 24-7.1-21.1-18-40.4-32.1-57.1C303.4 43.6 334.3 32 368 32c79.5 0 144 64.5 144 144 0 68.5-47.9 125.9-112 140.4z\"],\n    \"venus-mars\": [576, 512, [], \"f228\", \"M564 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C422.5 72.1 396.2 64 368 64c-33.7 0-64.6 11.6-89.2 30.9 14 16.7 25 36 32.1 57.1 14.5-14.8 34.7-24 57.1-24 44.1 0 80 35.9 80 80s-35.9 80-80 80c-22.3 0-42.6-9.2-57.1-24-7.1 21.1-18 40.4-32.1 57.1 24.5 19.4 55.5 30.9 89.2 30.9 79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 64C64.5 64 0 128.5 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.6 112-71.9 112-140.4 0-79.5-64.5-144-144-144zm0 224c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"vial\": [480, 512, [], \"f492\", \"M477.7 186.1L309.5 18.3c-3.1-3.1-8.2-3.1-11.3 0l-34 33.9c-3.1 3.1-3.1 8.2 0 11.3l11.2 11.1L33 316.5c-38.8 38.7-45.1 102-9.4 143.5 20.6 24 49.5 36 78.4 35.9 26.4 0 52.8-10 72.9-30.1l246.3-245.7 11.2 11.1c3.1 3.1 8.2 3.1 11.3 0l34-33.9c3.1-3 3.1-8.1 0-11.2zM318 256H161l148-147.7 78.5 78.3L318 256z\"],\n    \"vials\": [640, 512, [], \"f493\", \"M72 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H72c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64zm480 384H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM360 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64z\"],\n    \"video\": [576, 512, [], \"f03d\", \"M336.2 64H47.8C21.4 64 0 85.4 0 111.8v288.4C0 426.6 21.4 448 47.8 448h288.4c26.4 0 47.8-21.4 47.8-47.8V111.8c0-26.4-21.4-47.8-47.8-47.8zm189.4 37.7L416 177.3v157.4l109.6 75.5c21.2 14.6 50.4-.3 50.4-25.8V127.5c0-25.4-29.1-40.4-50.4-25.8z\"],\n    \"video-slash\": [640, 512, [], \"f4e2\", \"M633.8 458.1l-55-42.5c15.4-1.4 29.2-13.7 29.2-31.1v-257c0-25.5-29.1-40.4-50.4-25.8L448 177.3v137.2l-32-24.7v-178c0-26.4-21.4-47.8-47.8-47.8H123.9L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4L42.7 82 416 370.6l178.5 138c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.5-6.9 4.2-17-2.8-22.4zM32 400.2c0 26.4 21.4 47.8 47.8 47.8h288.4c11.2 0 21.4-4 29.6-10.5L32 154.7v245.5z\"],\n    \"vihara\": [640, 512, [], \"f6a7\", \"M632.88 400.71L544 352v-64l55.16-17.69c11.79-5.9 11.79-22.72 0-28.62L480 192v-64l27.31-16.3c7.72-7.72 5.61-20.74-4.16-25.62L320 0 136.85 86.07c-9.77 4.88-11.88 17.9-4.16 25.62L160 128v64L40.84 241.69c-11.79 5.9-11.79 22.72 0 28.62L96 288v64L7.12 400.71c-5.42 3.62-7.7 9.63-7 15.29.62 5.01 3.57 9.75 8.72 12.33L64 448v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48l55.15-19.67c5.16-2.58 8.1-7.32 8.72-12.33.71-5.67-1.57-11.68-6.99-15.29zM224 128h192v64H224v-64zm-64 224v-64h320v64H160z\"],\n    \"voicemail\": [640, 512, [], \"f897\", \"M496 128a144 144 0 0 0-119.74 224H263.74A144 144 0 1 0 144 416h352a144 144 0 0 0 0-288zM64 272a80 80 0 1 1 80 80 80 80 0 0 1-80-80zm432 80a80 80 0 1 1 80-80 80 80 0 0 1-80 80z\"],\n    \"volleyball-ball\": [512, 512, [], \"f45f\", \"M231.39 243.48a285.56 285.56 0 0 0-22.7-105.7c-90.8 42.4-157.5 122.4-180.3 216.8a249 249 0 0 0 56.9 81.1 333.87 333.87 0 0 1 146.1-192.2zm-36.9-134.4a284.23 284.23 0 0 0-57.4-70.7c-91 49.8-144.8 152.9-125 262.2 33.4-83.1 98.4-152 182.4-191.5zm187.6 165.1c8.6-99.8-27.3-197.5-97.5-264.4-14.7-1.7-51.6-5.5-98.9 8.5A333.87 333.87 0 0 1 279.19 241a285 285 0 0 0 102.9 33.18zm-124.7 9.5a286.33 286.33 0 0 0-80.2 72.6c82 57.3 184.5 75.1 277.5 47.8a247.15 247.15 0 0 0 42.2-89.9 336.1 336.1 0 0 1-80.9 10.4c-54.6-.1-108.9-14.1-158.6-40.9zm-98.3 99.7c-15.2 26-25.7 54.4-32.1 84.2a247.07 247.07 0 0 0 289-22.1c-112.9 16.1-203.3-24.8-256.9-62.1zm180.3-360.6c55.3 70.4 82.5 161.2 74.6 253.6a286.59 286.59 0 0 0 89.7-14.2c0-2 .3-4 .3-6 0-107.8-68.7-199.1-164.6-233.4z\"],\n    \"volume-down\": [384, 512, [], \"f027\", \"M215.03 72.04L126.06 161H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V89.02c0-21.47-25.96-31.98-40.97-16.98zm123.2 108.08c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 229.28 336 242.62 336 257c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.87z\"],\n    \"volume-mute\": [512, 512, [], \"f6a9\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zM461.64 256l45.64-45.64c6.3-6.3 6.3-16.52 0-22.82l-22.82-22.82c-6.3-6.3-16.52-6.3-22.82 0L416 210.36l-45.64-45.64c-6.3-6.3-16.52-6.3-22.82 0l-22.82 22.82c-6.3 6.3-6.3 16.52 0 22.82L370.36 256l-45.63 45.63c-6.3 6.3-6.3 16.52 0 22.82l22.82 22.82c6.3 6.3 16.52 6.3 22.82 0L416 301.64l45.64 45.64c6.3 6.3 16.52 6.3 22.82 0l22.82-22.82c6.3-6.3 6.3-16.52 0-22.82L461.64 256z\"],\n    \"volume-off\": [256, 512, [], \"f026\", \"M215 71l-89 89H24a24 24 0 0 0-24 24v144a24 24 0 0 0 24 24h102.06L215 441c15 15 41 4.47 41-17V88c0-21.47-26-32-41-17z\"],\n    \"volume-up\": [576, 512, [], \"f028\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zm233.32-51.08c-11.17-7.33-26.18-4.24-33.51 6.95-7.34 11.17-4.22 26.18 6.95 33.51 66.27 43.49 105.82 116.6 105.82 195.58 0 78.98-39.55 152.09-105.82 195.58-11.17 7.32-14.29 22.34-6.95 33.5 7.04 10.71 21.93 14.56 33.51 6.95C528.27 439.58 576 351.33 576 256S528.27 72.43 448.35 19.97zM480 256c0-63.53-32.06-121.94-85.77-156.24-11.19-7.14-26.03-3.82-33.12 7.46s-3.78 26.21 7.41 33.36C408.27 165.97 432 209.11 432 256s-23.73 90.03-63.48 115.42c-11.19 7.14-14.5 22.07-7.41 33.36 6.51 10.36 21.12 15.14 33.12 7.46C447.94 377.94 480 319.54 480 256zm-141.77-76.87c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 228.28 336 241.63 336 256c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.86z\"],\n    \"vote-yea\": [640, 512, [], \"f772\", \"M608 320h-64v64h22.4c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8H96v-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h576c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32zm-96 64V64.3c0-17.9-14.5-32.3-32.3-32.3H160.4C142.5 32 128 46.5 128 64.3V384h384zM211.2 202l25.5-25.3c4.2-4.2 11-4.2 15.2.1l41.3 41.6 95.2-94.4c4.2-4.2 11-4.2 15.2.1l25.3 25.5c4.2 4.2 4.2 11-.1 15.2L300.5 292c-4.2 4.2-11 4.2-15.2-.1l-74.1-74.7c-4.3-4.2-4.2-11 0-15.2z\"],\n    \"vr-cardboard\": [640, 512, [], \"f729\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h160.22c25.19 0 48.03-14.77 58.36-37.74l27.74-61.64C286.21 331.08 302.35 320 320 320s33.79 11.08 41.68 28.62l27.74 61.64C399.75 433.23 422.6 448 447.78 448H608c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM160 304c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64zm320 0c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64z\"],\n    \"walking\": [320, 512, [], \"f554\", \"M208 96c26.5 0 48-21.5 48-48S234.5 0 208 0s-48 21.5-48 48 21.5 48 48 48zm94.5 149.1l-23.3-11.8-9.7-29.4c-14.7-44.6-55.7-75.8-102.2-75.9-36-.1-55.9 10.1-93.3 25.2-21.6 8.7-39.3 25.2-49.7 46.2L17.6 213c-7.8 15.8-1.5 35 14.2 42.9 15.6 7.9 34.6 1.5 42.5-14.3L81 228c3.5-7 9.3-12.5 16.5-15.4l26.8-10.8-15.2 60.7c-5.2 20.8.4 42.9 14.9 58.8l59.9 65.4c7.2 7.9 12.3 17.4 14.9 27.7l18.3 73.3c4.3 17.1 21.7 27.6 38.8 23.3 17.1-4.3 27.6-21.7 23.3-38.8l-22.2-89c-2.6-10.3-7.7-19.9-14.9-27.7l-45.5-49.7 17.2-68.7 5.5 16.5c5.3 16.1 16.7 29.4 31.7 37l23.3 11.8c15.6 7.9 34.6 1.5 42.5-14.3 7.7-15.7 1.4-35.1-14.3-43zM73.6 385.8c-3.2 8.1-8 15.4-14.2 21.5l-50 50.1c-12.5 12.5-12.5 32.8 0 45.3s32.7 12.5 45.2 0l59.4-59.4c6.1-6.1 10.9-13.4 14.2-21.5l13.5-33.8c-55.3-60.3-38.7-41.8-47.4-53.7l-20.7 51.5z\"],\n    \"wallet\": [512, 512, [], \"f555\", \"M461.2 128H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h384c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h397.2c28.02 0 50.8-21.53 50.8-48V176c0-26.47-22.78-48-50.8-48zM416 336c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"warehouse\": [640, 512, [], \"f494\", \"M504 352H136.4c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0 96H136.1c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8h368c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0-192H136.6c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm106.5-139L338.4 3.7a48.15 48.15 0 0 0-36.9 0L29.5 117C11.7 124.5 0 141.9 0 161.3V504c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V256c0-17.6 14.6-32 32.6-32h382.8c18 0 32.6 14.4 32.6 32v248c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V161.3c0-19.4-11.7-36.8-29.5-44.3z\"],\n    \"water\": [576, 512, [], \"f773\", \"M562.1 383.9c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144C540.6 93.4 520 85.4 504.2 73 490.1 61.9 470 61.7 456 73c-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3z\"],\n    \"wave-square\": [640, 512, [], \"f83e\", \"M476 480H324a36 36 0 0 1-36-36V96h-96v156a36 36 0 0 1-36 36H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h112V68a36 36 0 0 1 36-36h152a36 36 0 0 1 36 36v348h96V260a36 36 0 0 1 36-36h140a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H512v156a36 36 0 0 1-36 36z\"],\n    \"weight\": [512, 512, [], \"f496\", \"M448 64h-25.98C438.44 92.28 448 125.01 448 160c0 105.87-86.13 192-192 192S64 265.87 64 160c0-34.99 9.56-67.72 25.98-96H64C28.71 64 0 92.71 0 128v320c0 35.29 28.71 64 64 64h384c35.29 0 64-28.71 64-64V128c0-35.29-28.71-64-64-64zM256 320c88.37 0 160-71.63 160-160S344.37 0 256 0 96 71.63 96 160s71.63 160 160 160zm-.3-151.94l33.58-78.36c3.5-8.17 12.94-11.92 21.03-8.41 8.12 3.48 11.88 12.89 8.41 21l-33.67 78.55C291.73 188 296 197.45 296 208c0 22.09-17.91 40-40 40s-40-17.91-40-40c0-21.98 17.76-39.77 39.7-39.94z\"],\n    \"weight-hanging\": [512, 512, [], \"f5cd\", \"M510.28 445.86l-73.03-292.13c-3.8-15.19-16.44-25.72-30.87-25.72h-60.25c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96s-96 42.98-96 96c0 11.28 2.3 21.95 5.88 32h-60.25c-14.43 0-27.08 10.54-30.87 25.72L1.72 445.86C-6.61 479.17 16.38 512 48.03 512h415.95c31.64 0 54.63-32.83 46.3-66.14zM256 128c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"wheelchair\": [512, 512, [], \"f193\", \"M496.101 385.669l14.227 28.663c3.929 7.915.697 17.516-7.218 21.445l-65.465 32.886c-16.049 7.967-35.556 1.194-43.189-15.055L331.679 320H192c-15.925 0-29.426-11.71-31.679-27.475C126.433 55.308 128.38 70.044 128 64c0-36.358 30.318-65.635 67.052-63.929 33.271 1.545 60.048 28.905 60.925 62.201.868 32.933-23.152 60.423-54.608 65.039l4.67 32.69H336c8.837 0 16 7.163 16 16v32c0 8.837-7.163 16-16 16H215.182l4.572 32H352a32 32 0 0 1 28.962 18.392L438.477 396.8l36.178-18.349c7.915-3.929 17.517-.697 21.446 7.218zM311.358 352h-24.506c-7.788 54.204-54.528 96-110.852 96-61.757 0-112-50.243-112-112 0-41.505 22.694-77.809 56.324-97.156-3.712-25.965-6.844-47.86-9.488-66.333C45.956 198.464 0 261.963 0 336c0 97.047 78.953 176 176 176 71.87 0 133.806-43.308 161.11-105.192L311.358 352z\"],\n    \"wifi\": [640, 512, [], \"f1eb\", \"M634.91 154.88C457.74-8.99 182.19-8.93 5.09 154.88c-6.66 6.16-6.79 16.59-.35 22.98l34.24 33.97c6.14 6.1 16.02 6.23 22.4.38 145.92-133.68 371.3-133.71 517.25 0 6.38 5.85 16.26 5.71 22.4-.38l34.24-33.97c6.43-6.39 6.3-16.82-.36-22.98zM320 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm202.67-83.59c-115.26-101.93-290.21-101.82-405.34 0-6.9 6.1-7.12 16.69-.57 23.15l34.44 33.99c6 5.92 15.66 6.32 22.05.8 83.95-72.57 209.74-72.41 293.49 0 6.39 5.52 16.05 5.13 22.05-.8l34.44-33.99c6.56-6.46 6.33-17.06-.56-23.15z\"],\n    \"wind\": [512, 512, [], \"f72e\", \"M156.7 256H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h142.2c15.9 0 30.8 10.9 33.4 26.6 3.3 20-12.1 37.4-31.6 37.4-14.1 0-26.1-9.2-30.4-21.9-2.1-6.3-8.6-10.1-15.2-10.1H81.6c-9.8 0-17.7 8.8-15.9 18.4 8.6 44.1 47.6 77.6 94.2 77.6 57.1 0 102.7-50.1 95.2-108.6C249 291 205.4 256 156.7 256zM16 224h336c59.7 0 106.8-54.8 93.8-116.7-7.6-36.2-36.9-65.5-73.1-73.1-55.4-11.6-105.1 24.9-114.9 75.5-1.9 9.6 6.1 18.3 15.8 18.3h32.8c6.7 0 13.1-3.8 15.2-10.1C325.9 105.2 337.9 96 352 96c19.4 0 34.9 17.4 31.6 37.4-2.6 15.7-17.4 26.6-33.4 26.6H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16zm384 32H243.7c19.3 16.6 33.2 38.8 39.8 64H400c26.5 0 48 21.5 48 48s-21.5 48-48 48c-17.9 0-33.3-9.9-41.6-24.4-2.9-5-8.7-7.6-14.5-7.6h-33.8c-10.9 0-19 10.8-15.3 21.1 17.8 50.6 70.5 84.8 129.4 72.3 41.2-8.7 75.1-41.6 84.7-82.7C526 321.5 470.5 256 400 256z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-83.6 290.5c4.8 4.8 4.8 12.6 0 17.4l-40.5 40.5c-4.8 4.8-12.6 4.8-17.4 0L256 313.3l-66.5 67.1c-4.8 4.8-12.6 4.8-17.4 0l-40.5-40.5c-4.8-4.8-4.8-12.6 0-17.4l67.1-66.5-67.1-66.5c-4.8-4.8-4.8-12.6 0-17.4l40.5-40.5c4.8-4.8 12.6-4.8 17.4 0l66.5 67.1 66.5-67.1c4.8-4.8 12.6-4.8 17.4 0l40.5 40.5c4.8 4.8 4.8 12.6 0 17.4L313.3 256l67.1 66.5z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16 160H64v-84c0-6.6 5.4-12 12-12h360c6.6 0 12 5.4 12 12v84z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M464 352H48c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M512 48v288c0 26.5-21.5 48-48 48h-48V176c0-44.1-35.9-80-80-80H128V48c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zM384 176v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zm-68 28c0-6.6-5.4-12-12-12H76c-6.6 0-12 5.4-12 12v52h252v-52z\"],\n    \"wine-bottle\": [512, 512, [], \"f72f\", \"M507.31 72.57L439.43 4.69c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l-76.67 76.67c-46.58-19.7-102.4-10.73-140.37 27.23L18.75 312.23c-24.99 24.99-24.99 65.52 0 90.51l90.51 90.51c24.99 24.99 65.52 24.99 90.51 0l158.39-158.39c37.96-37.96 46.93-93.79 27.23-140.37l76.67-76.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.24-6.24 6.24-16.37-.01-22.62zM179.22 423.29l-90.51-90.51 122.04-122.04 90.51 90.51-122.04 122.04z\"],\n    \"wine-glass\": [288, 512, [], \"f4e3\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40z\"],\n    \"wine-glass-alt\": [288, 512, [], \"f5ce\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM61.75 48h164.5l7.17 80H54.58l7.17-80z\"],\n    \"won-sign\": [576, 512, [], \"f159\", \"M564 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-48l18.6-80.6c1.7-7.5-4-14.7-11.7-14.7h-46.1c-5.7 0-10.6 4-11.7 9.5L450.7 128H340.8l-19.7-86c-1.3-5.5-6.1-9.3-11.7-9.3h-44c-5.6 0-10.4 3.8-11.7 9.3l-20 86H125l-17.5-85.7c-1.1-5.6-6.1-9.6-11.8-9.6H53.6c-7.7 0-13.4 7.1-11.7 14.6L60 128H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h62.3l7.2 32H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h83.9l40.9 182.6c1.2 5.5 6.1 9.4 11.7 9.4h56.8c5.6 0 10.4-3.9 11.7-9.3L259.3 288h55.1l42.4 182.7c1.3 5.4 6.1 9.3 11.7 9.3h56.8c5.6 0 10.4-3.9 11.7-9.3L479.1 288H564c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-70.1l7.4-32zM183.8 342c-6.2 25.8-6.8 47.2-7.3 47.2h-1.1s-1.7-22-6.8-47.2l-11-54h38.8zm27.5-118h-66.8l-6.5-32h80.8zm62.9 0l2-8.6c1.9-8 3.5-16 4.8-23.4h11.8c1.3 7.4 2.9 15.4 4.8 23.4l2 8.6zm130.9 118c-5.1 25.2-6.8 47.2-6.8 47.2h-1.1c-.6 0-1.1-21.4-7.3-47.2l-12.4-54h39.1zm25.2-118h-67.4l-7.3-32h81.6z\"],\n    \"wrench\": [512, 512, [], \"f0ad\", \"M507.73 109.1c-2.24-9.03-13.54-12.09-20.12-5.51l-74.36 74.36-67.88-11.31-11.31-67.88 74.36-74.36c6.62-6.62 3.43-17.9-5.66-20.16-47.38-11.74-99.55.91-136.58 37.93-39.64 39.64-50.55 97.1-34.05 147.2L18.74 402.76c-24.99 24.99-24.99 65.51 0 90.5 24.99 24.99 65.51 24.99 90.5 0l213.21-213.21c50.12 16.71 107.47 5.68 147.37-34.22 37.07-37.07 49.7-89.32 37.91-136.73zM64 472c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"x-ray\": [640, 512, [], \"f497\", \"M240 384c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm160 32c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zM624 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zm0 448h-48V96H64v352H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM480 248c0 4.4-3.6 8-8 8H336v32h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h64c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48v-16h-64v16c0 26.5-21.5 48-48 48s-48-21.5-48-48 21.5-48 48-48h64v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-32H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h136v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-24c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v24h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h136c4.4 0 8 3.6 8 8v16z\"],\n    \"yen-sign\": [384, 512, [], \"f157\", \"M351.2 32h-65.3c-4.6 0-8.8 2.6-10.8 6.7l-55.4 113.2c-14.5 34.7-27.1 71.9-27.1 71.9h-1.3s-12.6-37.2-27.1-71.9L108.8 38.7c-2-4.1-6.2-6.7-10.8-6.7H32.8c-9.1 0-14.8 9.7-10.6 17.6L102.3 200H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h88.2l19.8 37.2V320H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h108v92c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12v-92h108c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12H232v-26.8l19.8-37.2H340c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12h-58.3l80.1-150.4c4.3-7.9-1.5-17.6-10.6-17.6z\"],\n    \"yin-yang\": [496, 512, [], \"f6ad\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 376c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-128c-53.02 0-96 42.98-96 96s42.98 96 96 96c-106.04 0-192-85.96-192-192S141.96 64 248 64c53.02 0 96 42.98 96 96s-42.98 96-96 96zm0-128c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fas', icons);\n  });\n\n}());\n(function () {\n  'use strict';\n\n  function _typeof(obj) {\n    if (typeof Symbol === \"function\" && typeof Symbol.iterator === \"symbol\") {\n      _typeof = function (obj) {\n        return typeof obj;\n      };\n    } else {\n      _typeof = function (obj) {\n        return obj && typeof Symbol === \"function\" && obj.constructor === Symbol && obj !== Symbol.prototype ? \"symbol\" : typeof obj;\n      };\n    }\n\n    return _typeof(obj);\n  }\n\n  function _classCallCheck(instance, Constructor) {\n    if (!(instance instanceof Constructor)) {\n      throw new TypeError(\"Cannot call a class as a function\");\n    }\n  }\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _slicedToArray(arr, i) {\n    return _arrayWithHoles(arr) || _iterableToArrayLimit(arr, i) || _nonIterableRest();\n  }\n\n  function _toConsumableArray(arr) {\n    return _arrayWithoutHoles(arr) || _iterableToArray(arr) || _nonIterableSpread();\n  }\n\n  function _arrayWithoutHoles(arr) {\n    if (Array.isArray(arr)) {\n      for (var i = 0, arr2 = new Array(arr.length); i < arr.length; i++) arr2[i] = arr[i];\n\n      return arr2;\n    }\n  }\n\n  function _arrayWithHoles(arr) {\n    if (Array.isArray(arr)) return arr;\n  }\n\n  function _iterableToArray(iter) {\n    if (Symbol.iterator in Object(iter) || Object.prototype.toString.call(iter) === \"[object Arguments]\") return Array.from(iter);\n  }\n\n  function _iterableToArrayLimit(arr, i) {\n    var _arr = [];\n    var _n = true;\n    var _d = false;\n    var _e = undefined;\n\n    try {\n      for (var _i = arr[Symbol.iterator](), _s; !(_n = (_s = _i.next()).done); _n = true) {\n        _arr.push(_s.value);\n\n        if (i && _arr.length === i) break;\n      }\n    } catch (err) {\n      _d = true;\n      _e = err;\n    } finally {\n      try {\n        if (!_n && _i[\"return\"] != null) _i[\"return\"]();\n      } finally {\n        if (_d) throw _e;\n      }\n    }\n\n    return _arr;\n  }\n\n  function _nonIterableSpread() {\n    throw new TypeError(\"Invalid attempt to spread non-iterable instance\");\n  }\n\n  function _nonIterableRest() {\n    throw new TypeError(\"Invalid attempt to destructure non-iterable instance\");\n  }\n\n  var noop = function noop() {};\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n  var _MUTATION_OBSERVER = null;\n  var _PERFORMANCE = {\n    mark: noop,\n    measure: noop\n  };\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n    if (typeof MutationObserver !== 'undefined') _MUTATION_OBSERVER = MutationObserver;\n    if (typeof performance !== 'undefined') _PERFORMANCE = performance;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var MUTATION_OBSERVER = _MUTATION_OBSERVER;\n  var PERFORMANCE = _PERFORMANCE;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var UNITS_IN_GRID = 16;\n  var DEFAULT_FAMILY_PREFIX = 'fa';\n  var DEFAULT_REPLACEMENT_CLASS = 'svg-inline--fa';\n  var DATA_FA_I2SVG = 'data-fa-i2svg';\n  var DATA_FA_PSEUDO_ELEMENT = 'data-fa-pseudo-element';\n  var DATA_FA_PSEUDO_ELEMENT_PENDING = 'data-fa-pseudo-element-pending';\n  var DATA_PREFIX = 'data-prefix';\n  var DATA_ICON = 'data-icon';\n  var HTML_CLASS_I2SVG_BASE_CLASS = 'fontawesome-i2svg';\n  var MUTATION_APPROACH_ASYNC = 'async';\n  var TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS = ['HTML', 'HEAD', 'STYLE', 'SCRIPT'];\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n  var PREFIX_TO_STYLE = {\n    'fas': 'solid',\n    'far': 'regular',\n    'fal': 'light',\n    'fad': 'duotone',\n    'fab': 'brands',\n    'fa': 'solid'\n  };\n  var STYLE_TO_PREFIX = {\n    'solid': 'fas',\n    'regular': 'far',\n    'light': 'fal',\n    'duotone': 'fad',\n    'brands': 'fab'\n  };\n  var LAYERS_TEXT_CLASSNAME = 'fa-layers-text';\n  var FONT_FAMILY_PATTERN = /Font Awesome 5 (Solid|Regular|Light|Duotone|Brands|Free|Pro)/;\n  var FONT_WEIGHT_TO_PREFIX = {\n    '900': 'fas',\n    '400': 'far',\n    'normal': 'far',\n    '300': 'fal'\n  };\n  var oneToTen = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10];\n  var oneToTwenty = oneToTen.concat([11, 12, 13, 14, 15, 16, 17, 18, 19, 20]);\n  var ATTRIBUTES_WATCHED_FOR_MUTATION = ['class', 'data-prefix', 'data-icon', 'data-fa-transform', 'data-fa-mask'];\n  var DUOTONE_CLASSES = {\n    GROUP: 'group',\n    SWAP_OPACITY: 'swap-opacity',\n    PRIMARY: 'primary',\n    SECONDARY: 'secondary'\n  };\n  var RESERVED_CLASSES = ['xs', 'sm', 'lg', 'fw', 'ul', 'li', 'border', 'pull-left', 'pull-right', 'spin', 'pulse', 'rotate-90', 'rotate-180', 'rotate-270', 'flip-horizontal', 'flip-vertical', 'flip-both', 'stack', 'stack-1x', 'stack-2x', 'inverse', 'layers', 'layers-text', 'layers-counter', DUOTONE_CLASSES.GROUP, DUOTONE_CLASSES.SWAP_OPACITY, DUOTONE_CLASSES.PRIMARY, DUOTONE_CLASSES.SECONDARY].concat(oneToTen.map(function (n) {\n    return \"\".concat(n, \"x\");\n  })).concat(oneToTwenty.map(function (n) {\n    return \"w-\".concat(n);\n  }));\n\n  var initial = WINDOW.FontAwesomeConfig || {};\n\n  function getAttrConfig(attr) {\n    var element = DOCUMENT.querySelector('script[' + attr + ']');\n\n    if (element) {\n      return element.getAttribute(attr);\n    }\n  }\n\n  function coerce(val) {\n    // Getting an empty string will occur if the attribute is set on the HTML tag but without a value\n    // We'll assume that this is an indication that it should be toggled to true\n    // For example <script data-search-pseudo-elements src=\"...\"></script>\n    if (val === '') return true;\n    if (val === 'false') return false;\n    if (val === 'true') return true;\n    return val;\n  }\n\n  if (DOCUMENT && typeof DOCUMENT.querySelector === 'function') {\n    var attrs = [['data-family-prefix', 'familyPrefix'], ['data-replacement-class', 'replacementClass'], ['data-auto-replace-svg', 'autoReplaceSvg'], ['data-auto-add-css', 'autoAddCss'], ['data-auto-a11y', 'autoA11y'], ['data-search-pseudo-elements', 'searchPseudoElements'], ['data-observe-mutations', 'observeMutations'], ['data-mutate-approach', 'mutateApproach'], ['data-keep-original-source', 'keepOriginalSource'], ['data-measure-performance', 'measurePerformance'], ['data-show-missing-icons', 'showMissingIcons']];\n    attrs.forEach(function (_ref) {\n      var _ref2 = _slicedToArray(_ref, 2),\n          attr = _ref2[0],\n          key = _ref2[1];\n\n      var val = coerce(getAttrConfig(attr));\n\n      if (val !== undefined && val !== null) {\n        initial[key] = val;\n      }\n    });\n  }\n\n  var _default = {\n    familyPrefix: DEFAULT_FAMILY_PREFIX,\n    replacementClass: DEFAULT_REPLACEMENT_CLASS,\n    autoReplaceSvg: true,\n    autoAddCss: true,\n    autoA11y: true,\n    searchPseudoElements: false,\n    observeMutations: true,\n    mutateApproach: 'async',\n    keepOriginalSource: true,\n    measurePerformance: false,\n    showMissingIcons: true\n  };\n\n  var _config = _objectSpread({}, _default, initial);\n\n  if (!_config.autoReplaceSvg) _config.observeMutations = false;\n\n  var config = _objectSpread({}, _config);\n\n  WINDOW.FontAwesomeConfig = config;\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  var functions = [];\n\n  var listener = function listener() {\n    DOCUMENT.removeEventListener('DOMContentLoaded', listener);\n    loaded = 1;\n    functions.map(function (fn) {\n      return fn();\n    });\n  };\n\n  var loaded = false;\n\n  if (IS_DOM) {\n    loaded = (DOCUMENT.documentElement.doScroll ? /^loaded|^c/ : /^loaded|^i|^c/).test(DOCUMENT.readyState);\n    if (!loaded) DOCUMENT.addEventListener('DOMContentLoaded', listener);\n  }\n\n  function domready (fn) {\n    if (!IS_DOM) return;\n    loaded ? setTimeout(fn, 0) : functions.push(fn);\n  }\n\n  var PENDING = 'pending';\n  var SETTLED = 'settled';\n  var FULFILLED = 'fulfilled';\n  var REJECTED = 'rejected';\n\n  var NOOP = function NOOP() {};\n\n  var isNode = typeof global !== 'undefined' && typeof global.process !== 'undefined' && typeof global.process.emit === 'function';\n  var asyncSetTimer = typeof setImmediate === 'undefined' ? setTimeout : setImmediate;\n  var asyncQueue = [];\n  var asyncTimer;\n\n  function asyncFlush() {\n    // run promise callbacks\n    for (var i = 0; i < asyncQueue.length; i++) {\n      asyncQueue[i][0](asyncQueue[i][1]);\n    } // reset async asyncQueue\n\n\n    asyncQueue = [];\n    asyncTimer = false;\n  }\n\n  function asyncCall(callback, arg) {\n    asyncQueue.push([callback, arg]);\n\n    if (!asyncTimer) {\n      asyncTimer = true;\n      asyncSetTimer(asyncFlush, 0);\n    }\n  }\n\n  function invokeResolver(resolver, promise) {\n    function resolvePromise(value) {\n      resolve(promise, value);\n    }\n\n    function rejectPromise(reason) {\n      reject(promise, reason);\n    }\n\n    try {\n      resolver(resolvePromise, rejectPromise);\n    } catch (e) {\n      rejectPromise(e);\n    }\n  }\n\n  function invokeCallback(subscriber) {\n    var owner = subscriber.owner;\n    var settled = owner._state;\n    var value = owner._data;\n    var callback = subscriber[settled];\n    var promise = subscriber.then;\n\n    if (typeof callback === 'function') {\n      settled = FULFILLED;\n\n      try {\n        value = callback(value);\n      } catch (e) {\n        reject(promise, e);\n      }\n    }\n\n    if (!handleThenable(promise, value)) {\n      if (settled === FULFILLED) {\n        resolve(promise, value);\n      }\n\n      if (settled === REJECTED) {\n        reject(promise, value);\n      }\n    }\n  }\n\n  function handleThenable(promise, value) {\n    var resolved;\n\n    try {\n      if (promise === value) {\n        throw new TypeError('A promises callback cannot return that same promise.');\n      }\n\n      if (value && (typeof value === 'function' || _typeof(value) === 'object')) {\n        // then should be retrieved only once\n        var then = value.then;\n\n        if (typeof then === 'function') {\n          then.call(value, function (val) {\n            if (!resolved) {\n              resolved = true;\n\n              if (value === val) {\n                fulfill(promise, val);\n              } else {\n                resolve(promise, val);\n              }\n            }\n          }, function (reason) {\n            if (!resolved) {\n              resolved = true;\n              reject(promise, reason);\n            }\n          });\n          return true;\n        }\n      }\n    } catch (e) {\n      if (!resolved) {\n        reject(promise, e);\n      }\n\n      return true;\n    }\n\n    return false;\n  }\n\n  function resolve(promise, value) {\n    if (promise === value || !handleThenable(promise, value)) {\n      fulfill(promise, value);\n    }\n  }\n\n  function fulfill(promise, value) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = value;\n      asyncCall(publishFulfillment, promise);\n    }\n  }\n\n  function reject(promise, reason) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = reason;\n      asyncCall(publishRejection, promise);\n    }\n  }\n\n  function publish(promise) {\n    promise._then = promise._then.forEach(invokeCallback);\n  }\n\n  function publishFulfillment(promise) {\n    promise._state = FULFILLED;\n    publish(promise);\n  }\n\n  function publishRejection(promise) {\n    promise._state = REJECTED;\n    publish(promise);\n\n    if (!promise._handled && isNode) {\n      global.process.emit('unhandledRejection', promise._data, promise);\n    }\n  }\n\n  function notifyRejectionHandled(promise) {\n    global.process.emit('rejectionHandled', promise);\n  }\n  /**\n   * @class\n   */\n\n\n  function P(resolver) {\n    if (typeof resolver !== 'function') {\n      throw new TypeError('Promise resolver ' + resolver + ' is not a function');\n    }\n\n    if (this instanceof P === false) {\n      throw new TypeError('Failed to construct \\'Promise\\': Please use the \\'new\\' operator, this object constructor cannot be called as a function.');\n    }\n\n    this._then = [];\n    invokeResolver(resolver, this);\n  }\n\n  P.prototype = {\n    constructor: P,\n    _state: PENDING,\n    _then: null,\n    _data: undefined,\n    _handled: false,\n    then: function then(onFulfillment, onRejection) {\n      var subscriber = {\n        owner: this,\n        then: new this.constructor(NOOP),\n        fulfilled: onFulfillment,\n        rejected: onRejection\n      };\n\n      if ((onRejection || onFulfillment) && !this._handled) {\n        this._handled = true;\n\n        if (this._state === REJECTED && isNode) {\n          asyncCall(notifyRejectionHandled, this);\n        }\n      }\n\n      if (this._state === FULFILLED || this._state === REJECTED) {\n        // already resolved, call callback async\n        asyncCall(invokeCallback, subscriber);\n      } else {\n        // subscribe\n        this._then.push(subscriber);\n      }\n\n      return subscriber.then;\n    },\n    catch: function _catch(onRejection) {\n      return this.then(null, onRejection);\n    }\n  };\n\n  P.all = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.all().');\n    }\n\n    return new P(function (resolve, reject) {\n      var results = [];\n      var remaining = 0;\n\n      function resolver(index) {\n        remaining++;\n        return function (value) {\n          results[index] = value;\n\n          if (! --remaining) {\n            resolve(results);\n          }\n        };\n      }\n\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolver(i), reject);\n        } else {\n          results[i] = promise;\n        }\n      }\n\n      if (!remaining) {\n        resolve(results);\n      }\n    });\n  };\n\n  P.race = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.race().');\n    }\n\n    return new P(function (resolve, reject) {\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolve, reject);\n        } else {\n          resolve(promise);\n        }\n      }\n    });\n  };\n\n  P.resolve = function (value) {\n    if (value && _typeof(value) === 'object' && value.constructor === P) {\n      return value;\n    }\n\n    return new P(function (resolve) {\n      resolve(value);\n    });\n  };\n\n  P.reject = function (reason) {\n    return new P(function (resolve, reject) {\n      reject(reason);\n    });\n  };\n\n  var picked = typeof Promise === 'function' ? Promise : P;\n\n  var d = UNITS_IN_GRID;\n  var meaninglessTransform = {\n    size: 16,\n    x: 0,\n    y: 0,\n    rotate: 0,\n    flipX: false,\n    flipY: false\n  };\n\n  function isReserved(name) {\n    return ~RESERVED_CLASSES.indexOf(name);\n  }\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n  function insertCss(css) {\n    if (!css || !IS_DOM) {\n      return;\n    }\n\n    var style = DOCUMENT.createElement('style');\n    style.setAttribute('type', 'text/css');\n    style.innerHTML = css;\n    var headChildren = DOCUMENT.head.childNodes;\n    var beforeChild = null;\n\n    for (var i = headChildren.length - 1; i > -1; i--) {\n      var child = headChildren[i];\n      var tagName = (child.tagName || '').toUpperCase();\n\n      if (['STYLE', 'LINK'].indexOf(tagName) > -1) {\n        beforeChild = child;\n      }\n    }\n\n    DOCUMENT.head.insertBefore(style, beforeChild);\n    return css;\n  }\n  var idPool = '0123456789abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ';\n  function nextUniqueId() {\n    var size = 12;\n    var id = '';\n\n    while (size-- > 0) {\n      id += idPool[Math.random() * 62 | 0];\n    }\n\n    return id;\n  }\n  function toArray(obj) {\n    var array = [];\n\n    for (var i = (obj || []).length >>> 0; i--;) {\n      array[i] = obj[i];\n    }\n\n    return array;\n  }\n  function classArray(node) {\n    if (node.classList) {\n      return toArray(node.classList);\n    } else {\n      return (node.getAttribute('class') || '').split(' ').filter(function (i) {\n        return i;\n      });\n    }\n  }\n  function getIconName(familyPrefix, cls) {\n    var parts = cls.split('-');\n    var prefix = parts[0];\n    var iconName = parts.slice(1).join('-');\n\n    if (prefix === familyPrefix && iconName !== '' && !isReserved(iconName)) {\n      return iconName;\n    } else {\n      return null;\n    }\n  }\n  function htmlEscape(str) {\n    return \"\".concat(str).replace(/&/g, '&amp;').replace(/\"/g, '&quot;').replace(/'/g, '&#39;').replace(/</g, '&lt;').replace(/>/g, '&gt;');\n  }\n  function joinAttributes(attributes) {\n    return Object.keys(attributes || {}).reduce(function (acc, attributeName) {\n      return acc + \"\".concat(attributeName, \"=\\\"\").concat(htmlEscape(attributes[attributeName]), \"\\\" \");\n    }, '').trim();\n  }\n  function joinStyles(styles) {\n    return Object.keys(styles || {}).reduce(function (acc, styleName) {\n      return acc + \"\".concat(styleName, \": \").concat(styles[styleName], \";\");\n    }, '');\n  }\n  function transformIsMeaningful(transform) {\n    return transform.size !== meaninglessTransform.size || transform.x !== meaninglessTransform.x || transform.y !== meaninglessTransform.y || transform.rotate !== meaninglessTransform.rotate || transform.flipX || transform.flipY;\n  }\n  function transformForSvg(_ref) {\n    var transform = _ref.transform,\n        containerWidth = _ref.containerWidth,\n        iconWidth = _ref.iconWidth;\n    var outer = {\n      transform: \"translate(\".concat(containerWidth / 2, \" 256)\")\n    };\n    var innerTranslate = \"translate(\".concat(transform.x * 32, \", \").concat(transform.y * 32, \") \");\n    var innerScale = \"scale(\".concat(transform.size / 16 * (transform.flipX ? -1 : 1), \", \").concat(transform.size / 16 * (transform.flipY ? -1 : 1), \") \");\n    var innerRotate = \"rotate(\".concat(transform.rotate, \" 0 0)\");\n    var inner = {\n      transform: \"\".concat(innerTranslate, \" \").concat(innerScale, \" \").concat(innerRotate)\n    };\n    var path = {\n      transform: \"translate(\".concat(iconWidth / 2 * -1, \" -256)\")\n    };\n    return {\n      outer: outer,\n      inner: inner,\n      path: path\n    };\n  }\n  function transformForCss(_ref2) {\n    var transform = _ref2.transform,\n        _ref2$width = _ref2.width,\n        width = _ref2$width === void 0 ? UNITS_IN_GRID : _ref2$width,\n        _ref2$height = _ref2.height,\n        height = _ref2$height === void 0 ? UNITS_IN_GRID : _ref2$height,\n        _ref2$startCentered = _ref2.startCentered,\n        startCentered = _ref2$startCentered === void 0 ? false : _ref2$startCentered;\n    var val = '';\n\n    if (startCentered && IS_IE) {\n      val += \"translate(\".concat(transform.x / d - width / 2, \"em, \").concat(transform.y / d - height / 2, \"em) \");\n    } else if (startCentered) {\n      val += \"translate(calc(-50% + \".concat(transform.x / d, \"em), calc(-50% + \").concat(transform.y / d, \"em)) \");\n    } else {\n      val += \"translate(\".concat(transform.x / d, \"em, \").concat(transform.y / d, \"em) \");\n    }\n\n    val += \"scale(\".concat(transform.size / d * (transform.flipX ? -1 : 1), \", \").concat(transform.size / d * (transform.flipY ? -1 : 1), \") \");\n    val += \"rotate(\".concat(transform.rotate, \"deg) \");\n    return val;\n  }\n\n  var ALL_SPACE = {\n    x: 0,\n    y: 0,\n    width: '100%',\n    height: '100%'\n  };\n\n  function fillBlack(abstract) {\n    var force = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : true;\n\n    if (abstract.attributes && (abstract.attributes.fill || force)) {\n      abstract.attributes.fill = 'black';\n    }\n\n    return abstract;\n  }\n\n  function deGroup(abstract) {\n    if (abstract.tag === 'g') {\n      return abstract.children;\n    } else {\n      return [abstract];\n    }\n  }\n\n  function makeIconMasking (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        mask = _ref.mask,\n        transform = _ref.transform;\n    var mainWidth = main.width,\n        mainPath = main.icon;\n    var maskWidth = mask.width,\n        maskPath = mask.icon;\n    var trans = transformForSvg({\n      transform: transform,\n      containerWidth: maskWidth,\n      iconWidth: mainWidth\n    });\n    var maskRect = {\n      tag: 'rect',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        fill: 'white'\n      })\n    };\n    var maskInnerGroupChildrenMixin = mainPath.children ? {\n      children: mainPath.children.map(fillBlack)\n    } : {};\n    var maskInnerGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.inner),\n      children: [fillBlack(_objectSpread({\n        tag: mainPath.tag,\n        attributes: _objectSpread({}, mainPath.attributes, trans.path)\n      }, maskInnerGroupChildrenMixin))]\n    };\n    var maskOuterGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.outer),\n      children: [maskInnerGroup]\n    };\n    var maskId = \"mask-\".concat(nextUniqueId());\n    var clipId = \"clip-\".concat(nextUniqueId());\n    var maskTag = {\n      tag: 'mask',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        id: maskId,\n        maskUnits: 'userSpaceOnUse',\n        maskContentUnits: 'userSpaceOnUse'\n      }),\n      children: [maskRect, maskOuterGroup]\n    };\n    var defs = {\n      tag: 'defs',\n      children: [{\n        tag: 'clipPath',\n        attributes: {\n          id: clipId\n        },\n        children: deGroup(maskPath)\n      }, maskTag]\n    };\n    children.push(defs, {\n      tag: 'rect',\n      attributes: _objectSpread({\n        fill: 'currentColor',\n        'clip-path': \"url(#\".concat(clipId, \")\"),\n        mask: \"url(#\".concat(maskId, \")\")\n      }, ALL_SPACE)\n    });\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function makeIconStandard (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        transform = _ref.transform,\n        styles = _ref.styles;\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    if (transformIsMeaningful(transform)) {\n      var trans = transformForSvg({\n        transform: transform,\n        containerWidth: main.width,\n        iconWidth: main.width\n      });\n      children.push({\n        tag: 'g',\n        attributes: _objectSpread({}, trans.outer),\n        children: [{\n          tag: 'g',\n          attributes: _objectSpread({}, trans.inner),\n          children: [{\n            tag: main.icon.tag,\n            children: main.icon.children,\n            attributes: _objectSpread({}, main.icon.attributes, trans.path)\n          }]\n        }]\n      });\n    } else {\n      children.push(main.icon);\n    }\n\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function asIcon (_ref) {\n    var children = _ref.children,\n        main = _ref.main,\n        mask = _ref.mask,\n        attributes = _ref.attributes,\n        styles = _ref.styles,\n        transform = _ref.transform;\n\n    if (transformIsMeaningful(transform) && main.found && !mask.found) {\n      var width = main.width,\n          height = main.height;\n      var offset = {\n        x: width / height / 2,\n        y: 0.5\n      };\n      attributes['style'] = joinStyles(_objectSpread({}, styles, {\n        'transform-origin': \"\".concat(offset.x + transform.x / 16, \"em \").concat(offset.y + transform.y / 16, \"em\")\n      }));\n    }\n\n    return [{\n      tag: 'svg',\n      attributes: attributes,\n      children: children\n    }];\n  }\n\n  function asSymbol (_ref) {\n    var prefix = _ref.prefix,\n        iconName = _ref.iconName,\n        children = _ref.children,\n        attributes = _ref.attributes,\n        symbol = _ref.symbol;\n    var id = symbol === true ? \"\".concat(prefix, \"-\").concat(config.familyPrefix, \"-\").concat(iconName) : symbol;\n    return [{\n      tag: 'svg',\n      attributes: {\n        style: 'display: none;'\n      },\n      children: [{\n        tag: 'symbol',\n        attributes: _objectSpread({}, attributes, {\n          id: id\n        }),\n        children: children\n      }]\n    }];\n  }\n\n  function makeInlineSvgAbstract(params) {\n    var _params$icons = params.icons,\n        main = _params$icons.main,\n        mask = _params$icons.mask,\n        prefix = params.prefix,\n        iconName = params.iconName,\n        transform = params.transform,\n        symbol = params.symbol,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable = params.watchable,\n        watchable = _params$watchable === void 0 ? false : _params$watchable;\n\n    var _ref = mask.found ? mask : main,\n        width = _ref.width,\n        height = _ref.height;\n\n    var widthClass = \"fa-w-\".concat(Math.ceil(width / height * 16));\n    var attrClass = [config.replacementClass, iconName ? \"\".concat(config.familyPrefix, \"-\").concat(iconName) : '', widthClass].filter(function (c) {\n      return extra.classes.indexOf(c) === -1;\n    }).concat(extra.classes).join(' ');\n    var content = {\n      children: [],\n      attributes: _objectSpread({}, extra.attributes, {\n        'data-prefix': prefix,\n        'data-icon': iconName,\n        'class': attrClass,\n        'role': extra.attributes.role || 'img',\n        'xmlns': 'http://www.w3.org/2000/svg',\n        'viewBox': \"0 0 \".concat(width, \" \").concat(height)\n      })\n    };\n\n    if (watchable) {\n      content.attributes[DATA_FA_I2SVG] = '';\n    }\n\n    if (title) content.children.push({\n      tag: 'title',\n      attributes: {\n        id: content.attributes['aria-labelledby'] || \"title-\".concat(nextUniqueId())\n      },\n      children: [title]\n    });\n\n    var args = _objectSpread({}, content, {\n      prefix: prefix,\n      iconName: iconName,\n      main: main,\n      mask: mask,\n      transform: transform,\n      symbol: symbol,\n      styles: extra.styles\n    });\n\n    var _ref2 = mask.found && main.found ? makeIconMasking(args) : makeIconStandard(args),\n        children = _ref2.children,\n        attributes = _ref2.attributes;\n\n    args.children = children;\n    args.attributes = attributes;\n\n    if (symbol) {\n      return asSymbol(args);\n    } else {\n      return asIcon(args);\n    }\n  }\n  function makeLayersTextAbstract(params) {\n    var content = params.content,\n        width = params.width,\n        height = params.height,\n        transform = params.transform,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable2 = params.watchable,\n        watchable = _params$watchable2 === void 0 ? false : _params$watchable2;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    if (watchable) {\n      attributes[DATA_FA_I2SVG] = '';\n    }\n\n    var styles = _objectSpread({}, extra.styles);\n\n    if (transformIsMeaningful(transform)) {\n      styles['transform'] = transformForCss({\n        transform: transform,\n        startCentered: true,\n        width: width,\n        height: height\n      });\n      styles['-webkit-transform'] = styles['transform'];\n    }\n\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n  function makeLayersCounterAbstract(params) {\n    var content = params.content,\n        title = params.title,\n        extra = params.extra;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    var styleString = joinStyles(extra.styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n\n  var noop$1 = function noop() {};\n\n  var p = config.measurePerformance && PERFORMANCE && PERFORMANCE.mark && PERFORMANCE.measure ? PERFORMANCE : {\n    mark: noop$1,\n    measure: noop$1\n  };\n  var preamble = \"FA \\\"5.10.2\\\"\";\n\n  var begin = function begin(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" begins\"));\n    return function () {\n      return end(name);\n    };\n  };\n\n  var end = function end(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" ends\"));\n    p.measure(\"\".concat(preamble, \" \").concat(name), \"\".concat(preamble, \" \").concat(name, \" begins\"), \"\".concat(preamble, \" \").concat(name, \" ends\"));\n  };\n\n  var perf = {\n    begin: begin,\n    end: end\n  };\n\n  /**\n   * Internal helper to bind a function known to have 4 arguments\n   * to a given context.\n   */\n\n  var bindInternal4 = function bindInternal4(func, thisContext) {\n    return function (a, b, c, d) {\n      return func.call(thisContext, a, b, c, d);\n    };\n  };\n\n  /**\n   * # Reduce\n   *\n   * A fast object `.reduce()` implementation.\n   *\n   * @param  {Object}   subject      The object to reduce over.\n   * @param  {Function} fn           The reducer function.\n   * @param  {mixed}    initialValue The initial value for the reducer, defaults to subject[0].\n   * @param  {Object}   thisContext  The context for the reducer.\n   * @return {mixed}                 The final result.\n   */\n\n\n  var reduce = function fastReduceObject(subject, fn, initialValue, thisContext) {\n    var keys = Object.keys(subject),\n        length = keys.length,\n        iterator = thisContext !== undefined ? bindInternal4(fn, thisContext) : fn,\n        i,\n        key,\n        result;\n\n    if (initialValue === undefined) {\n      i = 1;\n      result = subject[keys[0]];\n    } else {\n      i = 0;\n      result = initialValue;\n    }\n\n    for (; i < length; i++) {\n      key = keys[i];\n      result = iterator(result, subject[key], key, subject);\n    }\n\n    return result;\n  };\n\n  function toHex(unicode) {\n    var result = '';\n\n    for (var i = 0; i < unicode.length; i++) {\n      var hex = unicode.charCodeAt(i).toString(16);\n      result += ('000' + hex).slice(-4);\n    }\n\n    return result;\n  }\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var styles = namespace.styles,\n      shims = namespace.shims;\n  var _byUnicode = {};\n  var _byLigature = {};\n  var _byOldName = {};\n  var build = function build() {\n    var lookup = function lookup(reducer) {\n      return reduce(styles, function (o, style, prefix) {\n        o[prefix] = reduce(style, reducer, {});\n        return o;\n      }, {});\n    };\n\n    _byUnicode = lookup(function (acc, icon, iconName) {\n      if (icon[3]) {\n        acc[icon[3]] = iconName;\n      }\n\n      return acc;\n    });\n    _byLigature = lookup(function (acc, icon, iconName) {\n      var ligatures = icon[2];\n      acc[iconName] = iconName;\n      ligatures.forEach(function (ligature) {\n        acc[ligature] = iconName;\n      });\n      return acc;\n    });\n    var hasRegular = 'far' in styles;\n    _byOldName = reduce(shims, function (acc, shim) {\n      var oldName = shim[0];\n      var prefix = shim[1];\n      var iconName = shim[2];\n\n      if (prefix === 'far' && !hasRegular) {\n        prefix = 'fas';\n      }\n\n      acc[oldName] = {\n        prefix: prefix,\n        iconName: iconName\n      };\n      return acc;\n    }, {});\n  };\n  build();\n  function byUnicode(prefix, unicode) {\n    return (_byUnicode[prefix] || {})[unicode];\n  }\n  function byLigature(prefix, ligature) {\n    return (_byLigature[prefix] || {})[ligature];\n  }\n  function byOldName(name) {\n    return _byOldName[name] || {\n      prefix: null,\n      iconName: null\n    };\n  }\n\n  var styles$1 = namespace.styles;\n  var emptyCanonicalIcon = function emptyCanonicalIcon() {\n    return {\n      prefix: null,\n      iconName: null,\n      rest: []\n    };\n  };\n  function getCanonicalIcon(values) {\n    return values.reduce(function (acc, cls) {\n      var iconName = getIconName(config.familyPrefix, cls);\n\n      if (styles$1[cls]) {\n        acc.prefix = cls;\n      } else if (config.autoFetchSvg && ['fas', 'far', 'fal', 'fad', 'fab', 'fa'].indexOf(cls) > -1) {\n        acc.prefix = cls;\n      } else if (iconName) {\n        var shim = acc.prefix === 'fa' ? byOldName(iconName) : {};\n        acc.iconName = shim.iconName || iconName;\n        acc.prefix = shim.prefix || acc.prefix;\n      } else if (cls !== config.replacementClass && cls.indexOf('fa-w-') !== 0) {\n        acc.rest.push(cls);\n      }\n\n      return acc;\n    }, emptyCanonicalIcon());\n  }\n  function iconFromMapping(mapping, prefix, iconName) {\n    if (mapping && mapping[prefix] && mapping[prefix][iconName]) {\n      return {\n        prefix: prefix,\n        iconName: iconName,\n        icon: mapping[prefix][iconName]\n      };\n    }\n  }\n\n  function toHtml(abstractNodes) {\n    var tag = abstractNodes.tag,\n        _abstractNodes$attrib = abstractNodes.attributes,\n        attributes = _abstractNodes$attrib === void 0 ? {} : _abstractNodes$attrib,\n        _abstractNodes$childr = abstractNodes.children,\n        children = _abstractNodes$childr === void 0 ? [] : _abstractNodes$childr;\n\n    if (typeof abstractNodes === 'string') {\n      return htmlEscape(abstractNodes);\n    } else {\n      return \"<\".concat(tag, \" \").concat(joinAttributes(attributes), \">\").concat(children.map(toHtml).join(''), \"</\").concat(tag, \">\");\n    }\n  }\n\n  var noop$2 = function noop() {};\n\n  function isWatched(node) {\n    var i2svg = node.getAttribute ? node.getAttribute(DATA_FA_I2SVG) : null;\n    return typeof i2svg === 'string';\n  }\n\n  function getMutator() {\n    if (config.autoReplaceSvg === true) {\n      return mutators.replace;\n    }\n\n    var mutator = mutators[config.autoReplaceSvg];\n    return mutator || mutators.replace;\n  }\n\n  var mutators = {\n    replace: function replace(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1];\n      var newOuterHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n\n      if (node.parentNode && node.outerHTML) {\n        node.outerHTML = newOuterHTML + (config.keepOriginalSource && node.tagName.toLowerCase() !== 'svg' ? \"<!-- \".concat(node.outerHTML, \" -->\") : '');\n      } else if (node.parentNode) {\n        var newNode = document.createElement('span');\n        node.parentNode.replaceChild(newNode, node);\n        newNode.outerHTML = newOuterHTML;\n      }\n    },\n    nest: function nest(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1]; // If we already have a replaced node we do not want to continue nesting within it.\n      // Short-circuit to the standard replacement\n\n      if (~classArray(node).indexOf(config.replacementClass)) {\n        return mutators.replace(mutation);\n      }\n\n      var forSvg = new RegExp(\"\".concat(config.familyPrefix, \"-.*\"));\n      delete abstract[0].attributes.style;\n      var splitClasses = abstract[0].attributes.class.split(' ').reduce(function (acc, cls) {\n        if (cls === config.replacementClass || cls.match(forSvg)) {\n          acc.toSvg.push(cls);\n        } else {\n          acc.toNode.push(cls);\n        }\n\n        return acc;\n      }, {\n        toNode: [],\n        toSvg: []\n      });\n      abstract[0].attributes.class = splitClasses.toSvg.join(' ');\n      var newInnerHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n      node.setAttribute('class', splitClasses.toNode.join(' '));\n      node.setAttribute(DATA_FA_I2SVG, '');\n      node.innerHTML = newInnerHTML;\n    }\n  };\n\n  function performOperationSync(op) {\n    op();\n  }\n\n  function perform(mutations, callback) {\n    var callbackFunction = typeof callback === 'function' ? callback : noop$2;\n\n    if (mutations.length === 0) {\n      callbackFunction();\n    } else {\n      var frame = performOperationSync;\n\n      if (config.mutateApproach === MUTATION_APPROACH_ASYNC) {\n        frame = WINDOW.requestAnimationFrame || performOperationSync;\n      }\n\n      frame(function () {\n        var mutator = getMutator();\n        var mark = perf.begin('mutate');\n        mutations.map(mutator);\n        mark();\n        callbackFunction();\n      });\n    }\n  }\n  var disabled = false;\n  function disableObservation() {\n    disabled = true;\n  }\n  function enableObservation() {\n    disabled = false;\n  }\n  var mo = null;\n  function observe(options) {\n    if (!MUTATION_OBSERVER) {\n      return;\n    }\n\n    if (!config.observeMutations) {\n      return;\n    }\n\n    var treeCallback = options.treeCallback,\n        nodeCallback = options.nodeCallback,\n        pseudoElementsCallback = options.pseudoElementsCallback,\n        _options$observeMutat = options.observeMutationsRoot,\n        observeMutationsRoot = _options$observeMutat === void 0 ? DOCUMENT : _options$observeMutat;\n    mo = new MUTATION_OBSERVER(function (objects) {\n      if (disabled) return;\n      toArray(objects).forEach(function (mutationRecord) {\n        if (mutationRecord.type === 'childList' && mutationRecord.addedNodes.length > 0 && !isWatched(mutationRecord.addedNodes[0])) {\n          if (config.searchPseudoElements) {\n            pseudoElementsCallback(mutationRecord.target);\n          }\n\n          treeCallback(mutationRecord.target);\n        }\n\n        if (mutationRecord.type === 'attributes' && mutationRecord.target.parentNode && config.searchPseudoElements) {\n          pseudoElementsCallback(mutationRecord.target.parentNode);\n        }\n\n        if (mutationRecord.type === 'attributes' && isWatched(mutationRecord.target) && ~ATTRIBUTES_WATCHED_FOR_MUTATION.indexOf(mutationRecord.attributeName)) {\n          if (mutationRecord.attributeName === 'class') {\n            var _getCanonicalIcon = getCanonicalIcon(classArray(mutationRecord.target)),\n                prefix = _getCanonicalIcon.prefix,\n                iconName = _getCanonicalIcon.iconName;\n\n            if (prefix) mutationRecord.target.setAttribute('data-prefix', prefix);\n            if (iconName) mutationRecord.target.setAttribute('data-icon', iconName);\n          } else {\n            nodeCallback(mutationRecord.target);\n          }\n        }\n      });\n    });\n    if (!IS_DOM) return;\n    mo.observe(observeMutationsRoot, {\n      childList: true,\n      attributes: true,\n      characterData: true,\n      subtree: true\n    });\n  }\n  function disconnect() {\n    if (!mo) return;\n    mo.disconnect();\n  }\n\n  function styleParser (node) {\n    var style = node.getAttribute('style');\n    var val = [];\n\n    if (style) {\n      val = style.split(';').reduce(function (acc, style) {\n        var styles = style.split(':');\n        var prop = styles[0];\n        var value = styles.slice(1);\n\n        if (prop && value.length > 0) {\n          acc[prop] = value.join(':').trim();\n        }\n\n        return acc;\n      }, {});\n    }\n\n    return val;\n  }\n\n  function classParser (node) {\n    var existingPrefix = node.getAttribute('data-prefix');\n    var existingIconName = node.getAttribute('data-icon');\n    var innerText = node.innerText !== undefined ? node.innerText.trim() : '';\n    var val = getCanonicalIcon(classArray(node));\n\n    if (existingPrefix && existingIconName) {\n      val.prefix = existingPrefix;\n      val.iconName = existingIconName;\n    }\n\n    if (val.prefix && innerText.length > 1) {\n      val.iconName = byLigature(val.prefix, node.innerText);\n    } else if (val.prefix && innerText.length === 1) {\n      val.iconName = byUnicode(val.prefix, toHex(node.innerText));\n    }\n\n    return val;\n  }\n\n  var parseTransformString = function parseTransformString(transformString) {\n    var transform = {\n      size: 16,\n      x: 0,\n      y: 0,\n      flipX: false,\n      flipY: false,\n      rotate: 0\n    };\n\n    if (!transformString) {\n      return transform;\n    } else {\n      return transformString.toLowerCase().split(' ').reduce(function (acc, n) {\n        var parts = n.toLowerCase().split('-');\n        var first = parts[0];\n        var rest = parts.slice(1).join('-');\n\n        if (first && rest === 'h') {\n          acc.flipX = true;\n          return acc;\n        }\n\n        if (first && rest === 'v') {\n          acc.flipY = true;\n          return acc;\n        }\n\n        rest = parseFloat(rest);\n\n        if (isNaN(rest)) {\n          return acc;\n        }\n\n        switch (first) {\n          case 'grow':\n            acc.size = acc.size + rest;\n            break;\n\n          case 'shrink':\n            acc.size = acc.size - rest;\n            break;\n\n          case 'left':\n            acc.x = acc.x - rest;\n            break;\n\n          case 'right':\n            acc.x = acc.x + rest;\n            break;\n\n          case 'up':\n            acc.y = acc.y - rest;\n            break;\n\n          case 'down':\n            acc.y = acc.y + rest;\n            break;\n\n          case 'rotate':\n            acc.rotate = acc.rotate + rest;\n            break;\n        }\n\n        return acc;\n      }, transform);\n    }\n  };\n  function transformParser (node) {\n    return parseTransformString(node.getAttribute('data-fa-transform'));\n  }\n\n  function symbolParser (node) {\n    var symbol = node.getAttribute('data-fa-symbol');\n    return symbol === null ? false : symbol === '' ? true : symbol;\n  }\n\n  function attributesParser (node) {\n    var extraAttributes = toArray(node.attributes).reduce(function (acc, attr) {\n      if (acc.name !== 'class' && acc.name !== 'style') {\n        acc[attr.name] = attr.value;\n      }\n\n      return acc;\n    }, {});\n    var title = node.getAttribute('title');\n\n    if (config.autoA11y) {\n      if (title) {\n        extraAttributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n      } else {\n        extraAttributes['aria-hidden'] = 'true';\n        extraAttributes['focusable'] = 'false';\n      }\n    }\n\n    return extraAttributes;\n  }\n\n  function maskParser (node) {\n    var mask = node.getAttribute('data-fa-mask');\n\n    if (!mask) {\n      return emptyCanonicalIcon();\n    } else {\n      return getCanonicalIcon(mask.split(' ').map(function (i) {\n        return i.trim();\n      }));\n    }\n  }\n\n  function blankMeta() {\n    return {\n      iconName: null,\n      title: null,\n      prefix: null,\n      transform: meaninglessTransform,\n      symbol: false,\n      mask: null,\n      extra: {\n        classes: [],\n        styles: {},\n        attributes: {}\n      }\n    };\n  }\n  function parseMeta(node) {\n    var _classParser = classParser(node),\n        iconName = _classParser.iconName,\n        prefix = _classParser.prefix,\n        extraClasses = _classParser.rest;\n\n    var extraStyles = styleParser(node);\n    var transform = transformParser(node);\n    var symbol = symbolParser(node);\n    var extraAttributes = attributesParser(node);\n    var mask = maskParser(node);\n    return {\n      iconName: iconName,\n      title: node.getAttribute('title'),\n      prefix: prefix,\n      transform: transform,\n      symbol: symbol,\n      mask: mask,\n      extra: {\n        classes: extraClasses,\n        styles: extraStyles,\n        attributes: extraAttributes\n      }\n    };\n  }\n\n  function MissingIcon(error) {\n    this.name = 'MissingIcon';\n    this.message = error || 'Icon unavailable';\n    this.stack = new Error().stack;\n  }\n  MissingIcon.prototype = Object.create(Error.prototype);\n  MissingIcon.prototype.constructor = MissingIcon;\n\n  var FILL = {\n    fill: 'currentColor'\n  };\n  var ANIMATION_BASE = {\n    attributeType: 'XML',\n    repeatCount: 'indefinite',\n    dur: '2s'\n  };\n  var RING = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      d: 'M156.5,447.7l-12.6,29.5c-18.7-9.5-35.9-21.2-51.5-34.9l22.7-22.7C127.6,430.5,141.5,440,156.5,447.7z M40.6,272H8.5 c1.4,21.2,5.4,41.7,11.7,61.1L50,321.2C45.1,305.5,41.8,289,40.6,272z M40.6,240c1.4-18.8,5.2-37,11.1-54.1l-29.5-12.6 C14.7,194.3,10,216.7,8.5,240H40.6z M64.3,156.5c7.8-14.9,17.2-28.8,28.1-41.5L69.7,92.3c-13.7,15.6-25.5,32.8-34.9,51.5 L64.3,156.5z M397,419.6c-13.9,12-29.4,22.3-46.1,30.4l11.9,29.8c20.7-9.9,39.8-22.6,56.9-37.6L397,419.6z M115,92.4 c13.9-12,29.4-22.3,46.1-30.4l-11.9-29.8c-20.7,9.9-39.8,22.6-56.8,37.6L115,92.4z M447.7,355.5c-7.8,14.9-17.2,28.8-28.1,41.5 l22.7,22.7c13.7-15.6,25.5-32.9,34.9-51.5L447.7,355.5z M471.4,272c-1.4,18.8-5.2,37-11.1,54.1l29.5,12.6 c7.5-21.1,12.2-43.5,13.6-66.8H471.4z M321.2,462c-15.7,5-32.2,8.2-49.2,9.4v32.1c21.2-1.4,41.7-5.4,61.1-11.7L321.2,462z M240,471.4c-18.8-1.4-37-5.2-54.1-11.1l-12.6,29.5c21.1,7.5,43.5,12.2,66.8,13.6V471.4z M462,190.8c5,15.7,8.2,32.2,9.4,49.2h32.1 c-1.4-21.2-5.4-41.7-11.7-61.1L462,190.8z M92.4,397c-12-13.9-22.3-29.4-30.4-46.1l-29.8,11.9c9.9,20.7,22.6,39.8,37.6,56.9 L92.4,397z M272,40.6c18.8,1.4,36.9,5.2,54.1,11.1l12.6-29.5C317.7,14.7,295.3,10,272,8.5V40.6z M190.8,50 c15.7-5,32.2-8.2,49.2-9.4V8.5c-21.2,1.4-41.7,5.4-61.1,11.7L190.8,50z M442.3,92.3L419.6,115c12,13.9,22.3,29.4,30.5,46.1 l29.8-11.9C470,128.5,457.3,109.4,442.3,92.3z M397,92.4l22.7-22.7c-15.6-13.7-32.8-25.5-51.5-34.9l-12.6,29.5 C370.4,72.1,384.4,81.5,397,92.4z'\n    })\n  };\n\n  var OPACITY_ANIMATE = _objectSpread({}, ANIMATION_BASE, {\n    attributeName: 'opacity'\n  });\n\n  var DOT = {\n    tag: 'circle',\n    attributes: _objectSpread({}, FILL, {\n      cx: '256',\n      cy: '364',\n      r: '28'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, ANIMATION_BASE, {\n        attributeName: 'r',\n        values: '28;14;28;28;14;28;'\n      })\n    }, {\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;1;1;0;1;'\n      })\n    }]\n  };\n  var QUESTION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '1',\n      d: 'M263.7,312h-16c-6.6,0-12-5.4-12-12c0-71,77.4-63.9,77.4-107.8c0-20-17.8-40.2-57.4-40.2c-29.1,0-44.3,9.6-59.2,28.7 c-3.9,5-11.1,6-16.2,2.4l-13.1-9.2c-5.6-3.9-6.9-11.8-2.6-17.2c21.2-27.2,46.4-44.7,91.2-44.7c52.3,0,97.4,29.8,97.4,80.2 c0,67.6-77.4,63.5-77.4,107.8C275.7,306.6,270.3,312,263.7,312z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;0;0;0;1;'\n      })\n    }]\n  };\n  var EXCLAMATION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '0',\n      d: 'M232.5,134.5l7,168c0.3,6.4,5.6,11.5,12,11.5h9c6.4,0,11.7-5.1,12-11.5l7-168c0.3-6.8-5.2-12.5-12-12.5h-23 C237.7,122,232.2,127.7,232.5,134.5z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '0;0;1;1;0;0;'\n      })\n    }]\n  };\n  var missing = {\n    tag: 'g',\n    children: [RING, DOT, QUESTION, EXCLAMATION]\n  };\n\n  var styles$2 = namespace.styles;\n  function asFoundIcon(icon) {\n    var width = icon[0];\n    var height = icon[1];\n\n    var _icon$slice = icon.slice(4),\n        _icon$slice2 = _slicedToArray(_icon$slice, 1),\n        vectorData = _icon$slice2[0];\n\n    var element = null;\n\n    if (Array.isArray(vectorData)) {\n      element = {\n        tag: 'g',\n        attributes: {\n          class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.GROUP)\n        },\n        children: [{\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.SECONDARY),\n            fill: 'currentColor',\n            d: vectorData[0]\n          }\n        }, {\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.PRIMARY),\n            fill: 'currentColor',\n            d: vectorData[1]\n          }\n        }]\n      };\n    } else {\n      element = {\n        tag: 'path',\n        attributes: {\n          fill: 'currentColor',\n          d: vectorData\n        }\n      };\n    }\n\n    return {\n      found: true,\n      width: width,\n      height: height,\n      icon: element\n    };\n  }\n  function findIcon(iconName, prefix) {\n    return new picked(function (resolve, reject) {\n      var val = {\n        found: false,\n        width: 512,\n        height: 512,\n        icon: missing\n      };\n\n      if (iconName && prefix && styles$2[prefix] && styles$2[prefix][iconName]) {\n        var icon = styles$2[prefix][iconName];\n        return resolve(asFoundIcon(icon));\n      }\n\n      if (iconName && prefix && !config.showMissingIcons) {\n        reject(new MissingIcon(\"Icon is missing for prefix \".concat(prefix, \" with icon name \").concat(iconName)));\n      } else {\n        resolve(val);\n      }\n    });\n  }\n\n  var styles$3 = namespace.styles;\n\n  function generateSvgReplacementMutation(node, nodeMeta) {\n    var iconName = nodeMeta.iconName,\n        title = nodeMeta.title,\n        prefix = nodeMeta.prefix,\n        transform = nodeMeta.transform,\n        symbol = nodeMeta.symbol,\n        mask = nodeMeta.mask,\n        extra = nodeMeta.extra;\n    return new picked(function (resolve, reject) {\n      picked.all([findIcon(iconName, prefix), findIcon(mask.iconName, mask.prefix)]).then(function (_ref) {\n        var _ref2 = _slicedToArray(_ref, 2),\n            main = _ref2[0],\n            mask = _ref2[1];\n\n        resolve([node, makeInlineSvgAbstract({\n          icons: {\n            main: main,\n            mask: mask\n          },\n          prefix: prefix,\n          iconName: iconName,\n          transform: transform,\n          symbol: symbol,\n          mask: mask,\n          title: title,\n          extra: extra,\n          watchable: true\n        })]);\n      });\n    });\n  }\n\n  function generateLayersText(node, nodeMeta) {\n    var title = nodeMeta.title,\n        transform = nodeMeta.transform,\n        extra = nodeMeta.extra;\n    var width = null;\n    var height = null;\n\n    if (IS_IE) {\n      var computedFontSize = parseInt(getComputedStyle(node).fontSize, 10);\n      var boundingClientRect = node.getBoundingClientRect();\n      width = boundingClientRect.width / computedFontSize;\n      height = boundingClientRect.height / computedFontSize;\n    }\n\n    if (config.autoA11y && !title) {\n      extra.attributes['aria-hidden'] = 'true';\n    }\n\n    return picked.resolve([node, makeLayersTextAbstract({\n      content: node.innerHTML,\n      width: width,\n      height: height,\n      transform: transform,\n      title: title,\n      extra: extra,\n      watchable: true\n    })]);\n  }\n\n  function generateMutation(node) {\n    var nodeMeta = parseMeta(node);\n\n    if (~nodeMeta.extra.classes.indexOf(LAYERS_TEXT_CLASSNAME)) {\n      return generateLayersText(node, nodeMeta);\n    } else {\n      return generateSvgReplacementMutation(node, nodeMeta);\n    }\n  }\n\n  function onTree(root) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    if (!IS_DOM) return;\n    var htmlClassList = DOCUMENT.documentElement.classList;\n\n    var hclAdd = function hclAdd(suffix) {\n      return htmlClassList.add(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var hclRemove = function hclRemove(suffix) {\n      return htmlClassList.remove(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var prefixes = config.autoFetchSvg ? Object.keys(PREFIX_TO_STYLE) : Object.keys(styles$3);\n    var prefixesDomQuery = [\".\".concat(LAYERS_TEXT_CLASSNAME, \":not([\").concat(DATA_FA_I2SVG, \"])\")].concat(prefixes.map(function (p) {\n      return \".\".concat(p, \":not([\").concat(DATA_FA_I2SVG, \"])\");\n    })).join(', ');\n\n    if (prefixesDomQuery.length === 0) {\n      return;\n    }\n\n    var candidates = [];\n\n    try {\n      candidates = toArray(root.querySelectorAll(prefixesDomQuery));\n    } catch (e) {// noop\n    }\n\n    if (candidates.length > 0) {\n      hclAdd('pending');\n      hclRemove('complete');\n    } else {\n      return;\n    }\n\n    var mark = perf.begin('onTree');\n    var mutations = candidates.reduce(function (acc, node) {\n      try {\n        var mutation = generateMutation(node);\n\n        if (mutation) {\n          acc.push(mutation);\n        }\n      } catch (e) {\n        if (!PRODUCTION) {\n          if (e instanceof MissingIcon) {\n            console.error(e);\n          }\n        }\n      }\n\n      return acc;\n    }, []);\n    return new picked(function (resolve, reject) {\n      picked.all(mutations).then(function (resolvedMutations) {\n        perform(resolvedMutations, function () {\n          hclAdd('active');\n          hclAdd('complete');\n          hclRemove('pending');\n          if (typeof callback === 'function') callback();\n          mark();\n          resolve();\n        });\n      }).catch(function () {\n        mark();\n        reject();\n      });\n    });\n  }\n  function onNode(node) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    generateMutation(node).then(function (mutation) {\n      if (mutation) {\n        perform([mutation], callback);\n      }\n    });\n  }\n\n  function replaceForPosition(node, position) {\n    var pendingAttribute = \"\".concat(DATA_FA_PSEUDO_ELEMENT_PENDING).concat(position.replace(':', '-'));\n    return new picked(function (resolve, reject) {\n      if (node.getAttribute(pendingAttribute) !== null) {\n        // This node is already being processed\n        return resolve();\n      }\n\n      var children = toArray(node.children);\n      var alreadyProcessedPseudoElement = children.filter(function (c) {\n        return c.getAttribute(DATA_FA_PSEUDO_ELEMENT) === position;\n      })[0];\n      var styles = WINDOW.getComputedStyle(node, position);\n      var fontFamily = styles.getPropertyValue('font-family').match(FONT_FAMILY_PATTERN);\n      var fontWeight = styles.getPropertyValue('font-weight');\n\n      if (alreadyProcessedPseudoElement && !fontFamily) {\n        // If we've already processed it but the current computed style does not result in a font-family,\n        // that probably means that a class name that was previously present to make the icon has been\n        // removed. So we now should delete the icon.\n        node.removeChild(alreadyProcessedPseudoElement);\n        return resolve();\n      } else if (fontFamily) {\n        var content = styles.getPropertyValue('content');\n        var prefix = ~['Solid', 'Regular', 'Light', 'Duotone', 'Brands'].indexOf(fontFamily[1]) ? STYLE_TO_PREFIX[fontFamily[1].toLowerCase()] : FONT_WEIGHT_TO_PREFIX[fontWeight];\n        var hexValue = toHex(content.length === 3 ? content.substr(1, 1) : content);\n        var iconName = byUnicode(prefix, hexValue);\n        var iconIdentifier = iconName; // Only convert the pseudo element in this :before/:after position into an icon if we haven't\n        // already done so with the same prefix and iconName\n\n        if (iconName && (!alreadyProcessedPseudoElement || alreadyProcessedPseudoElement.getAttribute(DATA_PREFIX) !== prefix || alreadyProcessedPseudoElement.getAttribute(DATA_ICON) !== iconIdentifier)) {\n          node.setAttribute(pendingAttribute, iconIdentifier);\n\n          if (alreadyProcessedPseudoElement) {\n            // Delete the old one, since we're replacing it with a new one\n            node.removeChild(alreadyProcessedPseudoElement);\n          }\n\n          var meta = blankMeta();\n          var extra = meta.extra;\n          extra.attributes[DATA_FA_PSEUDO_ELEMENT] = position;\n          findIcon(iconName, prefix).then(function (main) {\n            var abstract = makeInlineSvgAbstract(_objectSpread({}, meta, {\n              icons: {\n                main: main,\n                mask: emptyCanonicalIcon()\n              },\n              prefix: prefix,\n              iconName: iconIdentifier,\n              extra: extra,\n              watchable: true\n            }));\n            var element = DOCUMENT.createElement('svg');\n\n            if (position === ':before') {\n              node.insertBefore(element, node.firstChild);\n            } else {\n              node.appendChild(element);\n            }\n\n            element.outerHTML = abstract.map(function (a) {\n              return toHtml(a);\n            }).join('\\n');\n            node.removeAttribute(pendingAttribute);\n            resolve();\n          }).catch(reject);\n        } else {\n          resolve();\n        }\n      } else {\n        resolve();\n      }\n    });\n  }\n\n  function replace(node) {\n    return picked.all([replaceForPosition(node, ':before'), replaceForPosition(node, ':after')]);\n  }\n\n  function processable(node) {\n    return node.parentNode !== document.head && !~TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS.indexOf(node.tagName.toUpperCase()) && !node.getAttribute(DATA_FA_PSEUDO_ELEMENT) && (!node.parentNode || node.parentNode.tagName !== 'svg');\n  }\n\n  function searchPseudoElements (root) {\n    if (!IS_DOM) return;\n    return new picked(function (resolve, reject) {\n      var operations = toArray(root.querySelectorAll('*')).filter(processable).map(replace);\n      var end = perf.begin('searchPseudoElements');\n      disableObservation();\n      picked.all(operations).then(function () {\n        end();\n        enableObservation();\n        resolve();\n      }).catch(function () {\n        end();\n        enableObservation();\n        reject();\n      });\n    });\n  }\n\n  var baseStyles = \"svg:not(:root).svg-inline--fa{overflow:visible}.svg-inline--fa{display:inline-block;font-size:inherit;height:1em;overflow:visible;vertical-align:-.125em}.svg-inline--fa.fa-lg{vertical-align:-.225em}.svg-inline--fa.fa-w-1{width:.0625em}.svg-inline--fa.fa-w-2{width:.125em}.svg-inline--fa.fa-w-3{width:.1875em}.svg-inline--fa.fa-w-4{width:.25em}.svg-inline--fa.fa-w-5{width:.3125em}.svg-inline--fa.fa-w-6{width:.375em}.svg-inline--fa.fa-w-7{width:.4375em}.svg-inline--fa.fa-w-8{width:.5em}.svg-inline--fa.fa-w-9{width:.5625em}.svg-inline--fa.fa-w-10{width:.625em}.svg-inline--fa.fa-w-11{width:.6875em}.svg-inline--fa.fa-w-12{width:.75em}.svg-inline--fa.fa-w-13{width:.8125em}.svg-inline--fa.fa-w-14{width:.875em}.svg-inline--fa.fa-w-15{width:.9375em}.svg-inline--fa.fa-w-16{width:1em}.svg-inline--fa.fa-w-17{width:1.0625em}.svg-inline--fa.fa-w-18{width:1.125em}.svg-inline--fa.fa-w-19{width:1.1875em}.svg-inline--fa.fa-w-20{width:1.25em}.svg-inline--fa.fa-pull-left{margin-right:.3em;width:auto}.svg-inline--fa.fa-pull-right{margin-left:.3em;width:auto}.svg-inline--fa.fa-border{height:1.5em}.svg-inline--fa.fa-li{width:2em}.svg-inline--fa.fa-fw{width:1.25em}.fa-layers svg.svg-inline--fa{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.fa-layers{display:inline-block;height:1em;position:relative;text-align:center;vertical-align:-.125em;width:1em}.fa-layers svg.svg-inline--fa{-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter,.fa-layers-text{display:inline-block;position:absolute;text-align:center}.fa-layers-text{left:50%;top:50%;-webkit-transform:translate(-50%,-50%);transform:translate(-50%,-50%);-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter{background-color:#ff253a;border-radius:1em;-webkit-box-sizing:border-box;box-sizing:border-box;color:#fff;height:1.5em;line-height:1;max-width:5em;min-width:1.5em;overflow:hidden;padding:.25em;right:0;text-overflow:ellipsis;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-bottom-right{bottom:0;right:0;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom right;transform-origin:bottom right}.fa-layers-bottom-left{bottom:0;left:0;right:auto;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom left;transform-origin:bottom left}.fa-layers-top-right{right:0;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-top-left{left:0;right:auto;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top left;transform-origin:top left}.fa-lg{font-size:1.3333333333em;line-height:.75em;vertical-align:-.0667em}.fa-xs{font-size:.75em}.fa-sm{font-size:.875em}.fa-1x{font-size:1em}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-6x{font-size:6em}.fa-7x{font-size:7em}.fa-8x{font-size:8em}.fa-9x{font-size:9em}.fa-10x{font-size:10em}.fa-fw{text-align:center;width:1.25em}.fa-ul{list-style-type:none;margin-left:2.5em;padding-left:0}.fa-ul>li{position:relative}.fa-li{left:-2em;position:absolute;text-align:center;width:2em;line-height:inherit}.fa-border{border:solid .08em #eee;border-radius:.1em;padding:.2em .25em .15em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left,.fab.fa-pull-left,.fal.fa-pull-left,.far.fa-pull-left,.fas.fa-pull-left{margin-right:.3em}.fa.fa-pull-right,.fab.fa-pull-right,.fal.fa-pull-right,.far.fa-pull-right,.fas.fa-pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s infinite linear;animation:fa-spin 2s infinite linear}.fa-pulse{-webkit-animation:fa-spin 1s infinite steps(8);animation:fa-spin 1s infinite steps(8)}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}.fa-rotate-90{-webkit-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{-webkit-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{-webkit-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{-webkit-transform:scale(-1,1);transform:scale(-1,1)}.fa-flip-vertical{-webkit-transform:scale(1,-1);transform:scale(1,-1)}.fa-flip-both,.fa-flip-horizontal.fa-flip-vertical{-webkit-transform:scale(-1,-1);transform:scale(-1,-1)}:root .fa-flip-both,:root .fa-flip-horizontal,:root .fa-flip-vertical,:root .fa-rotate-180,:root .fa-rotate-270,:root .fa-rotate-90{-webkit-filter:none;filter:none}.fa-stack{display:inline-block;height:2em;position:relative;width:2.5em}.fa-stack-1x,.fa-stack-2x{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.svg-inline--fa.fa-stack-1x{height:1em;width:1.25em}.svg-inline--fa.fa-stack-2x{height:2em;width:2.5em}.fa-inverse{color:#fff}.sr-only{border:0;clip:rect(0,0,0,0);height:1px;margin:-1px;overflow:hidden;padding:0;position:absolute;width:1px}.sr-only-focusable:active,.sr-only-focusable:focus{clip:auto;height:auto;margin:0;overflow:visible;position:static;width:auto}.svg-inline--fa .fa-primary{fill:var(--fa-primary-color,currentColor);opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa .fa-secondary{fill:var(--fa-secondary-color,currentColor);opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-primary{opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-secondary{opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa mask .fa-primary,.svg-inline--fa mask .fa-secondary{fill:#000}.fad.fa-inverse{color:#fff}\";\n\n  function css () {\n    var dfp = DEFAULT_FAMILY_PREFIX;\n    var drc = DEFAULT_REPLACEMENT_CLASS;\n    var fp = config.familyPrefix;\n    var rc = config.replacementClass;\n    var s = baseStyles;\n\n    if (fp !== dfp || rc !== drc) {\n      var dPatt = new RegExp(\"\\\\.\".concat(dfp, \"\\\\-\"), 'g');\n      var customPropPatt = new RegExp(\"\\\\--\".concat(dfp, \"\\\\-\"), 'g');\n      var rPatt = new RegExp(\"\\\\.\".concat(drc), 'g');\n      s = s.replace(dPatt, \".\".concat(fp, \"-\")).replace(customPropPatt, \"--\".concat(fp, \"-\")).replace(rPatt, \".\".concat(rc));\n    }\n\n    return s;\n  }\n\n  var Library =\n  /*#__PURE__*/\n  function () {\n    function Library() {\n      _classCallCheck(this, Library);\n\n      this.definitions = {};\n    }\n\n    _createClass(Library, [{\n      key: \"add\",\n      value: function add() {\n        var _this = this;\n\n        for (var _len = arguments.length, definitions = new Array(_len), _key = 0; _key < _len; _key++) {\n          definitions[_key] = arguments[_key];\n        }\n\n        var additions = definitions.reduce(this._pullDefinitions, {});\n        Object.keys(additions).forEach(function (key) {\n          _this.definitions[key] = _objectSpread({}, _this.definitions[key] || {}, additions[key]);\n          defineIcons(key, additions[key]);\n          build();\n        });\n      }\n    }, {\n      key: \"reset\",\n      value: function reset() {\n        this.definitions = {};\n      }\n    }, {\n      key: \"_pullDefinitions\",\n      value: function _pullDefinitions(additions, definition) {\n        var normalized = definition.prefix && definition.iconName && definition.icon ? {\n          0: definition\n        } : definition;\n        Object.keys(normalized).map(function (key) {\n          var _normalized$key = normalized[key],\n              prefix = _normalized$key.prefix,\n              iconName = _normalized$key.iconName,\n              icon = _normalized$key.icon;\n          if (!additions[prefix]) additions[prefix] = {};\n          additions[prefix][iconName] = icon;\n        });\n        return additions;\n      }\n    }]);\n\n    return Library;\n  }();\n\n  function ensureCss() {\n    if (config.autoAddCss && !_cssInserted) {\n      insertCss(css());\n\n      _cssInserted = true;\n    }\n  }\n\n  function apiObject(val, abstractCreator) {\n    Object.defineProperty(val, 'abstract', {\n      get: abstractCreator\n    });\n    Object.defineProperty(val, 'html', {\n      get: function get() {\n        return val.abstract.map(function (a) {\n          return toHtml(a);\n        });\n      }\n    });\n    Object.defineProperty(val, 'node', {\n      get: function get() {\n        if (!IS_DOM) return;\n        var container = DOCUMENT.createElement('div');\n        container.innerHTML = val.html;\n        return container.children;\n      }\n    });\n    return val;\n  }\n\n  function findIconDefinition(iconLookup) {\n    var _iconLookup$prefix = iconLookup.prefix,\n        prefix = _iconLookup$prefix === void 0 ? 'fa' : _iconLookup$prefix,\n        iconName = iconLookup.iconName;\n    if (!iconName) return;\n    return iconFromMapping(library.definitions, prefix, iconName) || iconFromMapping(namespace.styles, prefix, iconName);\n  }\n\n  function resolveIcons(next) {\n    return function (maybeIconDefinition) {\n      var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n      var iconDefinition = (maybeIconDefinition || {}).icon ? maybeIconDefinition : findIconDefinition(maybeIconDefinition || {});\n      var mask = params.mask;\n\n      if (mask) {\n        mask = (mask || {}).icon ? mask : findIconDefinition(mask || {});\n      }\n\n      return next(iconDefinition, _objectSpread({}, params, {\n        mask: mask\n      }));\n    };\n  }\n\n  var library = new Library();\n  var noAuto = function noAuto() {\n    config.autoReplaceSvg = false;\n    config.observeMutations = false;\n    disconnect();\n  };\n  var _cssInserted = false;\n  var dom = {\n    i2svg: function i2svg() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n\n      if (IS_DOM) {\n        ensureCss();\n        var _params$node = params.node,\n            node = _params$node === void 0 ? DOCUMENT : _params$node,\n            _params$callback = params.callback,\n            callback = _params$callback === void 0 ? function () {} : _params$callback;\n\n        if (config.searchPseudoElements) {\n          searchPseudoElements(node);\n        }\n\n        return onTree(node, callback);\n      } else {\n        return picked.reject('Operation requires a DOM of some kind.');\n      }\n    },\n    css: css,\n    insertCss: function insertCss$$1() {\n      if (!_cssInserted) {\n        insertCss(css());\n\n        _cssInserted = true;\n      }\n    },\n    watch: function watch() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n      var autoReplaceSvgRoot = params.autoReplaceSvgRoot,\n          observeMutationsRoot = params.observeMutationsRoot;\n\n      if (config.autoReplaceSvg === false) {\n        config.autoReplaceSvg = true;\n      }\n\n      config.observeMutations = true;\n      domready(function () {\n        autoReplace({\n          autoReplaceSvgRoot: autoReplaceSvgRoot\n        });\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements,\n          observeMutationsRoot: observeMutationsRoot\n        });\n      });\n    }\n  };\n  var parse = {\n    transform: function transform(transformString) {\n      return parseTransformString(transformString);\n    }\n  };\n  var icon = resolveIcons(function (iconDefinition) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform = params.transform,\n        transform = _params$transform === void 0 ? meaninglessTransform : _params$transform,\n        _params$symbol = params.symbol,\n        symbol = _params$symbol === void 0 ? false : _params$symbol,\n        _params$mask = params.mask,\n        mask = _params$mask === void 0 ? null : _params$mask,\n        _params$title = params.title,\n        title = _params$title === void 0 ? null : _params$title,\n        _params$classes = params.classes,\n        classes = _params$classes === void 0 ? [] : _params$classes,\n        _params$attributes = params.attributes,\n        attributes = _params$attributes === void 0 ? {} : _params$attributes,\n        _params$styles = params.styles,\n        styles = _params$styles === void 0 ? {} : _params$styles;\n    if (!iconDefinition) return;\n    var prefix = iconDefinition.prefix,\n        iconName = iconDefinition.iconName,\n        icon = iconDefinition.icon;\n    return apiObject(_objectSpread({\n      type: 'icon'\n    }, iconDefinition), function () {\n      ensureCss();\n\n      if (config.autoA11y) {\n        if (title) {\n          attributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n        } else {\n          attributes['aria-hidden'] = 'true';\n          attributes['focusable'] = 'false';\n        }\n      }\n\n      return makeInlineSvgAbstract({\n        icons: {\n          main: asFoundIcon(icon),\n          mask: mask ? asFoundIcon(mask.icon) : {\n            found: false,\n            width: null,\n            height: null,\n            icon: {}\n          }\n        },\n        prefix: prefix,\n        iconName: iconName,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        symbol: symbol,\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: classes\n        }\n      });\n    });\n  });\n  var text = function text(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform2 = params.transform,\n        transform = _params$transform2 === void 0 ? meaninglessTransform : _params$transform2,\n        _params$title2 = params.title,\n        title = _params$title2 === void 0 ? null : _params$title2,\n        _params$classes2 = params.classes,\n        classes = _params$classes2 === void 0 ? [] : _params$classes2,\n        _params$attributes2 = params.attributes,\n        attributes = _params$attributes2 === void 0 ? {} : _params$attributes2,\n        _params$styles2 = params.styles,\n        styles = _params$styles2 === void 0 ? {} : _params$styles2;\n    return apiObject({\n      type: 'text',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersTextAbstract({\n        content: content,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-text\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var counter = function counter(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$title3 = params.title,\n        title = _params$title3 === void 0 ? null : _params$title3,\n        _params$classes3 = params.classes,\n        classes = _params$classes3 === void 0 ? [] : _params$classes3,\n        _params$attributes3 = params.attributes,\n        attributes = _params$attributes3 === void 0 ? {} : _params$attributes3,\n        _params$styles3 = params.styles,\n        styles = _params$styles3 === void 0 ? {} : _params$styles3;\n    return apiObject({\n      type: 'counter',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersCounterAbstract({\n        content: content.toString(),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-counter\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var layer = function layer(assembler) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$classes4 = params.classes,\n        classes = _params$classes4 === void 0 ? [] : _params$classes4;\n    return apiObject({\n      type: 'layer'\n    }, function () {\n      ensureCss();\n      var children = [];\n      assembler(function (args) {\n        Array.isArray(args) ? args.map(function (a) {\n          children = children.concat(a.abstract);\n        }) : children = children.concat(args.abstract);\n      });\n      return [{\n        tag: 'span',\n        attributes: {\n          class: [\"\".concat(config.familyPrefix, \"-layers\")].concat(_toConsumableArray(classes)).join(' ')\n        },\n        children: children\n      }];\n    });\n  };\n  var api = {\n    noAuto: noAuto,\n    config: config,\n    dom: dom,\n    library: library,\n    parse: parse,\n    findIconDefinition: findIconDefinition,\n    icon: icon,\n    text: text,\n    counter: counter,\n    layer: layer,\n    toHtml: toHtml\n  };\n\n  var autoReplace = function autoReplace() {\n    var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n    var _params$autoReplaceSv = params.autoReplaceSvgRoot,\n        autoReplaceSvgRoot = _params$autoReplaceSv === void 0 ? DOCUMENT : _params$autoReplaceSv;\n    if ((Object.keys(namespace.styles).length > 0 || config.autoFetchSvg) && IS_DOM && config.autoReplaceSvg) api.dom.i2svg({\n      node: autoReplaceSvgRoot\n    });\n  };\n\n  function bootstrap() {\n    if (IS_BROWSER) {\n      if (!WINDOW.FontAwesome) {\n        WINDOW.FontAwesome = api;\n      }\n\n      domready(function () {\n        autoReplace();\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements\n        });\n      });\n    }\n\n    namespace.hooks = _objectSpread({}, namespace.hooks, {\n      addPack: function addPack(prefix, icons) {\n        namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, icons);\n        build();\n        autoReplace();\n      },\n      addShims: function addShims(shims) {\n        var _namespace$shims;\n\n        (_namespace$shims = namespace.shims).push.apply(_namespace$shims, _toConsumableArray(shims));\n\n        build();\n        autoReplace();\n      }\n    });\n  }\n\n  bunker(bootstrap);\n\n}());\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/brands.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"500px\": [448, 512, [], \"f26e\", \"M103.3 344.3c-6.5-14.2-6.9-18.3 7.4-23.1 25.6-8 8 9.2 43.2 49.2h.3v-93.9c1.2-50.2 44-92.2 97.7-92.2 53.9 0 97.7 43.5 97.7 96.8 0 63.4-60.8 113.2-128.5 93.3-10.5-4.2-2.1-31.7 8.5-28.6 53 0 89.4-10.1 89.4-64.4 0-61-77.1-89.6-116.9-44.6-23.5 26.4-17.6 42.1-17.6 157.6 50.7 31 118.3 22 160.4-20.1 24.8-24.8 38.5-58 38.5-93 0-35.2-13.8-68.2-38.8-93.3-24.8-24.8-57.8-38.5-93.3-38.5s-68.8 13.8-93.5 38.5c-.3.3-16 16.5-21.2 23.9l-.5.6c-3.3 4.7-6.3 9.1-20.1 6.1-6.9-1.7-14.3-5.8-14.3-11.8V20c0-5 3.9-10.5 10.5-10.5h241.3c8.3 0 8.3 11.6 8.3 15.1 0 3.9 0 15.1-8.3 15.1H130.3v132.9h.3c104.2-109.8 282.8-36 282.8 108.9 0 178.1-244.8 220.3-310.1 62.8zm63.3-260.8c-.5 4.2 4.6 24.5 14.6 20.6C306 56.6 384 144.5 390.6 144.5c4.8 0 22.8-15.3 14.3-22.8-93.2-89-234.5-57-238.3-38.2zM393 414.7C283 524.6 94 475.5 61 310.5c0-12.2-30.4-7.4-28.9 3.3 24 173.4 246 256.9 381.6 121.3 6.9-7.8-12.6-28.4-20.7-20.4zM213.6 306.6c0 4 4.3 7.3 5.5 8.5 3 3 6.1 4.4 8.5 4.4 3.8 0 2.6.2 22.3-19.5 19.6 19.3 19.1 19.5 22.3 19.5 5.4 0 18.5-10.4 10.7-18.2L265.6 284l18.2-18.2c6.3-6.8-10.1-21.8-16.2-15.7L249.7 268c-18.6-18.8-18.4-19.5-21.5-19.5-5 0-18 11.7-12.4 17.3L234 284c-18.1 17.9-20.4 19.2-20.4 22.6z\"],\n    \"accessible-icon\": [448, 512, [], \"f368\", \"M423.9 255.8L411 413.1c-3.3 40.7-63.9 35.1-60.6-4.9l10-122.5-41.1 2.3c10.1 20.7 15.8 43.9 15.8 68.5 0 41.2-16.1 78.7-42.3 106.5l-39.3-39.3c57.9-63.7 13.1-167.2-74-167.2-25.9 0-49.5 9.9-67.2 26L73 243.2c22-20.7 50.1-35.1 81.4-40.2l75.3-85.7-42.6-24.8-51.6 46c-30 26.8-70.6-18.5-40.5-45.4l68-60.7c9.8-8.8 24.1-10.2 35.5-3.6 0 0 139.3 80.9 139.5 81.1 16.2 10.1 20.7 36 6.1 52.6L285.7 229l106.1-5.9c18.5-1.1 33.6 14.4 32.1 32.7zm-64.9-154c28.1 0 50.9-22.8 50.9-50.9C409.9 22.8 387.1 0 359 0c-28.1 0-50.9 22.8-50.9 50.9 0 28.1 22.8 50.9 50.9 50.9zM179.6 456.5c-80.6 0-127.4-90.6-82.7-156.1l-39.7-39.7C36.4 287 24 320.3 24 356.4c0 130.7 150.7 201.4 251.4 122.5l-39.7-39.7c-16 10.9-35.3 17.3-56.1 17.3z\"],\n    \"accusoft\": [640, 512, [], \"f369\", \"M322.1 252v-1l-51.2-65.8s-12 1.6-25 15.1c-9 9.3-242.1 239.1-243.4 240.9-7 10 1.6 6.8 15.7 1.7.8 0 114.5-36.6 114.5-36.6.5-.6-.1-.1.6-.6-.4-5.1-.8-26.2-1-27.7-.6-5.2 2.2-6.9 7-8.9l92.6-33.8c.6-.8 88.5-81.7 90.2-83.3zm160.1 120.1c13.3 16.1 20.7 13.3 30.8 9.3 3.2-1.2 115.4-47.6 117.8-48.9 8-4.3-1.7-16.7-7.2-23.4-2.1-2.5-205.1-245.6-207.2-248.3-9.7-12.2-14.3-12.9-38.4-12.8-10.2 0-106.8.5-116.5.6-19.2.1-32.9-.3-19.2 16.9C250 75 476.5 365.2 482.2 372.1zm152.7 1.6c-2.3-.3-24.6-4.7-38-7.2 0 0-115 50.4-117.5 51.6-16 7.3-26.9-3.2-36.7-14.6l-57.1-74c-5.4-.9-60.4-9.6-65.3-9.3-3.1.2-9.6.8-14.4 2.9-4.9 2.1-145.2 52.8-150.2 54.7-5.1 2-11.4 3.6-11.1 7.6.2 2.5 2 2.6 4.6 3.5 2.7.8 300.9 67.6 308 69.1 15.6 3.3 38.5 10.5 53.6 1.7 2.1-1.2 123.8-76.4 125.8-77.8 5.4-4 4.3-6.8-1.7-8.2z\"],\n    \"acquisitions-incorporated\": [384, 512, [], \"f6af\", \"M357.45 468.2c-1.2-7.7-1.3-7.6-9.6-7.6-99.8.2-111.8-2.4-112.7-2.6-12.3-1.7-20.6-10.5-21-23.1-.1-1.6-.2-71.6-1-129.1-.1-4.7 1.6-6.4 5.9-7.5 12.5-3 24.9-6.1 37.3-9.7 4.3-1.3 6.8-.2 8.4 3.5 4.5 10.3 8.8 20.6 13.2 30.9 1.6 3.7.1 4.4-3.4 4.4-10-.2-20-.1-30.4-.1v27h116c-1.4-9.5-2.7-18.1-4-27.5-7 0-13.8.4-20.4-.1-22.6-1.6-18.3-4.4-84-158.6-8.8-20.1-27.9-62.1-36.5-89.2-4.4-14 5.5-25.4 18.9-26.6 18.6-1.7 37.5-1.6 56.2-2 20.6-.4 41.2-.4 61.8-.5 3.1 0 4-1.4 4.3-4.3 1.2-9.8 2.7-19.5 4-29.2.8-5.3 1.6-10.7 2.4-16.1L23.75 0c-3.6 0-5.3 1.1-4.6 5.3 2.2 13.2-.8.8 6.4 45.3 63.4 0 71.8.9 101.8.5 12.3-.2 37 3.5 37.7 22.1.4 11.4-1.1 11.3-32.6 87.4-53.8 129.8-50.7 120.3-67.3 161-1.7 4.1-3.6 5.2-7.6 5.2-8.5-.2-17-.3-25.4.1-1.9.1-5.2 1.8-5.5 3.2-1.5 8.1-2.2 16.3-3.2 24.9h114.3v-27.6c-6.9 0-33.5.4-35.3-2.9 5.3-12.3 10.4-24.4 15.7-36.7 16.3 4 31.9 7.8 47.6 11.7 3.4.9 4.6 3 4.6 6.8-.1 42.9.1 85.9.2 128.8 0 10.2-5.5 19.1-14.9 23.1-6.5 2.7-3.3 3.4-121.4 2.4-5.3 0-7.1 2-7.6 6.8-1.5 12.9-2.9 25.9-5 38.8-.8 5 1.3 5.7 5.3 5.7 183.2.6-30.7 0 337.1 0-2.5-15-4.4-29.4-6.6-43.7zm-174.9-205.7c-13.3-4.2-26.6-8.2-39.9-12.5a44.53 44.53 0 0 1-5.8-2.9c17.2-44.3 34.2-88.1 51.3-132.1 7.5 2.4 7.9-.8 9.4 0 9.3 22.5 18.1 60.1 27 82.8 6.6 16.7 13 33.5 19.7 50.9a35.78 35.78 0 0 1-3.9 2.1c-13.1 3.9-26.4 7.5-39.4 11.7a27.66 27.66 0 0 1-18.4 0z\"],\n    \"adn\": [496, 512, [], \"f170\", \"M248 167.5l64.9 98.8H183.1l64.9-98.8zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-99.8 82.7L248 115.5 99.8 338.7h30.4l33.6-51.7h168.6l33.6 51.7h30.2z\"],\n    \"adobe\": [512, 512, [], \"f778\", \"M315.5 64h170.9v384L315.5 64zm-119 0H25.6v384L196.5 64zM256 206.1L363.5 448h-73l-30.7-76.8h-78.7L256 206.1z\"],\n    \"adversal\": [512, 512, [], \"f36a\", \"M482.1 32H28.7C5.8 32 0 37.9 0 60.9v390.2C0 474.4 5.8 480 28.7 480h453.4c24.4 0 29.9-5.2 29.9-29.7V62.2c0-24.6-5.4-30.2-29.9-30.2zM178.4 220.3c-27.5-20.2-72.1-8.7-84.2 23.4-4.3 11.1-9.3 9.5-17.5 8.3-9.7-1.5-17.2-3.2-22.5-5.5-28.8-11.4 8.6-55.3 24.9-64.3 41.1-21.4 83.4-22.2 125.3-4.8 40.9 16.8 34.5 59.2 34.5 128.5 2.7 25.8-4.3 58.3 9.3 88.8 1.9 4.4.4 7.9-2.7 10.7-8.4 6.7-39.3 2.2-46.6-7.4-1.9-2.2-1.8-3.6-3.9-6.2-3.6-3.9-7.3-2.2-11.9 1-57.4 36.4-140.3 21.4-147-43.3-3.1-29.3 12.4-57.1 39.6-71 38.2-19.5 112.2-11.8 114-30.9 1.1-10.2-1.9-20.1-11.3-27.3zm286.7 222c0 15.1-11.1 9.9-17.8 9.9H52.4c-7.4 0-18.2 4.8-17.8-10.7.4-13.9 10.5-9.1 17.1-9.1 132.3-.4 264.5-.4 396.8 0 6.8 0 16.6-4.4 16.6 9.9zm3.8-340.5v291c0 5.7-.7 13.9-8.1 13.9-12.4-.4-27.5 7.1-36.1-5.6-5.8-8.7-7.8-4-12.4-1.2-53.4 29.7-128.1 7.1-144.4-85.2-6.1-33.4-.7-67.1 15.7-100 11.8-23.9 56.9-76.1 136.1-30.5v-71c0-26.2-.1-26.2 26-26.2 3.1 0 6.6.4 9.7 0 10.1-.8 13.6 4.4 13.6 14.3-.1.2-.1.3-.1.5zm-51.5 232.3c-19.5 47.6-72.9 43.3-90 5.2-15.1-33.3-15.5-68.2.4-101.5 16.3-34.1 59.7-35.7 81.5-4.8 20.6 28.8 14.9 84.6 8.1 101.1zm-294.8 35.3c-7.5-1.3-33-3.3-33.7-27.8-.4-13.9 7.8-23 19.8-25.8 24.4-5.9 49.3-9.9 73.7-14.7 8.9-2 7.4 4.4 7.8 9.5 1.4 33-26.1 59.2-67.6 58.8z\"],\n    \"affiliatetheme\": [512, 512, [], \"f36b\", \"M159.7 237.4C108.4 308.3 43.1 348.2 14 326.6-15.2 304.9 2.8 230 54.2 159.1c51.3-70.9 116.6-110.8 145.7-89.2 29.1 21.6 11.1 96.6-40.2 167.5zm351.2-57.3C437.1 303.5 319 367.8 246.4 323.7c-25-15.2-41.3-41.2-49-73.8-33.6 64.8-92.8 113.8-164.1 133.2 49.8 59.3 124.1 96.9 207 96.9 150 0 271.6-123.1 271.6-274.9.1-8.5-.3-16.8-1-25z\"],\n    \"airbnb\": [448, 512, [], \"f834\", \"M224 373.12c-25.24-31.67-40.08-59.43-45-83.18-22.55-88 112.61-88 90.06 0-5.45 24.25-20.29 52-45 83.18zm138.15 73.23c-42.06 18.31-83.67-10.88-119.3-50.47 103.9-130.07 46.11-200-18.85-200-54.92 0-85.16 46.51-73.28 100.5 6.93 29.19 25.23 62.39 54.43 99.5-32.53 36.05-60.55 52.69-85.15 54.92-50 7.43-89.11-41.06-71.3-91.09 15.1-39.16 111.72-231.18 115.87-241.56 15.75-30.07 25.56-57.4 59.38-57.4 32.34 0 43.4 25.94 60.37 59.87 36 70.62 89.35 177.48 114.84 239.09 13.17 33.07-1.37 71.29-37.01 86.64zm47-136.12C280.27 35.93 273.13 32 224 32c-45.52 0-64.87 31.67-84.66 72.79C33.18 317.1 22.89 347.19 22 349.81-3.22 419.14 48.74 480 111.63 480c21.71 0 60.61-6.06 112.37-62.4 58.68 63.78 101.26 62.4 112.37 62.4 62.89.05 114.85-60.86 89.61-130.19.02-3.89-16.82-38.9-16.82-39.58z\"],\n    \"algolia\": [448, 512, [], \"f36c\", \"M229.3 182.6c-49.3 0-89.2 39.9-89.2 89.2 0 49.3 39.9 89.2 89.2 89.2s89.2-39.9 89.2-89.2c0-49.3-40-89.2-89.2-89.2zm62.7 56.6l-58.9 30.6c-1.8.9-3.8-.4-3.8-2.3V201c0-1.5 1.3-2.7 2.7-2.6 26.2 1 48.9 15.7 61.1 37.1.7 1.3.2 3-1.1 3.7zM389.1 32H58.9C26.4 32 0 58.4 0 90.9V421c0 32.6 26.4 59 58.9 59H389c32.6 0 58.9-26.4 58.9-58.9V90.9C448 58.4 421.6 32 389.1 32zm-202.6 84.7c0-10.8 8.7-19.5 19.5-19.5h45.3c10.8 0 19.5 8.7 19.5 19.5v15.4c0 1.8-1.7 3-3.3 2.5-12.3-3.4-25.1-5.1-38.1-5.1-13.5 0-26.7 1.8-39.4 5.5-1.7.5-3.4-.8-3.4-2.5v-15.8zm-84.4 37l9.2-9.2c7.6-7.6 19.9-7.6 27.5 0l7.7 7.7c1.1 1.1 1 3-.3 4-6.2 4.5-12.1 9.4-17.6 14.9-5.4 5.4-10.4 11.3-14.8 17.4-1 1.3-2.9 1.5-4 .3l-7.7-7.7c-7.6-7.5-7.6-19.8 0-27.4zm127.2 244.8c-70 0-126.6-56.7-126.6-126.6s56.7-126.6 126.6-126.6c70 0 126.6 56.6 126.6 126.6 0 69.8-56.7 126.6-126.6 126.6z\"],\n    \"alipay\": [448, 512, [], \"f642\", \"M377.74 32H70.26C31.41 32 0 63.41 0 102.26v307.48C0 448.59 31.41 480 70.26 480h307.48c38.52 0 69.76-31.08 70.26-69.6-45.96-25.62-110.59-60.34-171.6-88.44-32.07 43.97-84.14 81-148.62 81-70.59 0-93.73-45.3-97.04-76.37-3.97-39.01 14.88-81.5 99.52-81.5 35.38 0 79.35 10.25 127.13 24.96 16.53-30.09 26.45-60.34 26.45-60.34h-178.2v-16.7h92.08v-31.24H88.28v-19.01h109.44V92.34h50.92v50.42h109.44v19.01H248.63v31.24h88.77s-15.21 46.62-38.35 90.92c48.93 16.7 100.01 36.04 148.62 52.74V102.26C447.83 63.57 416.43 32 377.74 32zM47.28 322.95c.99 20.17 10.25 53.73 69.93 53.73 52.07 0 92.58-39.68 117.87-72.9-44.63-18.68-84.48-31.41-109.44-31.41-67.45 0-79.35 33.06-78.36 50.58z\"],\n    \"amazon\": [448, 512, [], \"f270\", \"M257.2 162.7c-48.7 1.8-169.5 15.5-169.5 117.5 0 109.5 138.3 114 183.5 43.2 6.5 10.2 35.4 37.5 45.3 46.8l56.8-56S341 288.9 341 261.4V114.3C341 89 316.5 32 228.7 32 140.7 32 94 87 94 136.3l73.5 6.8c16.3-49.5 54.2-49.5 54.2-49.5 40.7-.1 35.5 29.8 35.5 69.1zm0 86.8c0 80-84.2 68-84.2 17.2 0-47.2 50.5-56.7 84.2-57.8v40.6zm136 163.5c-7.7 10-70 67-174.5 67S34.2 408.5 9.7 379c-6.8-7.7 1-11.3 5.5-8.3C88.5 415.2 203 488.5 387.7 401c7.5-3.7 13.3 2 5.5 12zm39.8 2.2c-6.5 15.8-16 26.8-21.2 31-5.5 4.5-9.5 2.7-6.5-3.8s19.3-46.5 12.7-55c-6.5-8.3-37-4.3-48-3.2-10.8 1-13 2-14-.3-2.3-5.7 21.7-15.5 37.5-17.5 15.7-1.8 41-.8 46 5.7 3.7 5.1 0 27.1-6.5 43.1z\"],\n    \"amazon-pay\": [640, 512, [], \"f42c\", \"M14 325.3c2.3-4.2 5.2-4.9 9.7-2.5 10.4 5.6 20.6 11.4 31.2 16.7a595.88 595.88 0 0 0 127.4 46.3 616.61 616.61 0 0 0 63.2 11.8 603.33 603.33 0 0 0 95 5.2c17.4-.4 34.8-1.8 52.1-3.8a603.66 603.66 0 0 0 163.3-42.8c2.9-1.2 5.9-2 9.1-1.2 6.7 1.8 9 9 4.1 13.9a70 70 0 0 1-9.6 7.4c-30.7 21.1-64.2 36.4-99.6 47.9a473.31 473.31 0 0 1-75.1 17.6 431 431 0 0 1-53.2 4.8 21.3 21.3 0 0 0-2.5.3H308a21.3 21.3 0 0 0-2.5-.3c-3.6-.2-7.2-.3-10.7-.4a426.3 426.3 0 0 1-50.4-5.3A448.4 448.4 0 0 1 164 420a443.33 443.33 0 0 1-145.6-87c-1.8-1.6-3-3.8-4.4-5.7zM172 65.1l-4.3.6a80.92 80.92 0 0 0-38 15.1c-2.4 1.7-4.6 3.5-7.1 5.4a4.29 4.29 0 0 1-.4-1.4c-.4-2.7-.8-5.5-1.3-8.2-.7-4.6-3-6.6-7.6-6.6h-11.5c-6.9 0-8.2 1.3-8.2 8.2v209.3c0 1 0 2 .1 3 .2 3 2 4.9 4.9 5 7 .1 14.1.1 21.1 0 2.9 0 4.7-2 5-5 .1-1 .1-2 .1-3v-72.4c1.1.9 1.7 1.4 2.2 1.9 17.9 14.9 38.5 19.8 61 15.4 20.4-4 34.6-16.5 43.8-34.9 7-13.9 9.9-28.7 10.3-44.1.5-17.1-1.2-33.9-8.1-49.8-8.5-19.6-22.6-32.5-43.9-36.9-3.2-.7-6.5-1-9.8-1.5-2.8-.1-5.5-.1-8.3-.1zM124.6 107a3.48 3.48 0 0 1 1.7-3.3c13.7-9.5 28.8-14.5 45.6-13.2 14.9 1.1 27.1 8.4 33.5 25.9 3.9 10.7 4.9 21.8 4.9 33 0 10.4-.8 20.6-4 30.6-6.8 21.3-22.4 29.4-42.6 28.5-14-.6-26.2-6-37.4-13.9a3.57 3.57 0 0 1-1.7-3.3c.1-14.1 0-28.1 0-42.2s.1-28 0-42.1zm205.7-41.9c-1 .1-2 .3-2.9.4a148 148 0 0 0-28.9 4.1c-6.1 1.6-12 3.8-17.9 5.8-3.6 1.2-5.4 3.8-5.3 7.7.1 3.3-.1 6.6 0 9.9.1 4.8 2.1 6.1 6.8 4.9 7.8-2 15.6-4.2 23.5-5.7 12.3-2.3 24.7-3.3 37.2-1.4 6.5 1 12.6 2.9 16.8 8.4 3.7 4.8 5.1 10.5 5.3 16.4.3 8.3.2 16.6.3 24.9a7.84 7.84 0 0 1-.2 1.4c-.5-.1-.9 0-1.3-.1a180.56 180.56 0 0 0-32-4.9c-11.3-.6-22.5.1-33.3 3.9-12.9 4.5-23.3 12.3-29.4 24.9-4.7 9.8-5.4 20.2-3.9 30.7 2 14 9 24.8 21.4 31.7 11.9 6.6 24.8 7.4 37.9 5.4 15.1-2.3 28.5-8.7 40.3-18.4a7.36 7.36 0 0 1 1.6-1.1c.6 3.8 1.1 7.4 1.8 11 .6 3.1 2.5 5.1 5.4 5.2 5.4.1 10.9.1 16.3 0a4.84 4.84 0 0 0 4.8-4.7 26.2 26.2 0 0 0 .1-2.8v-106a80 80 0 0 0-.9-12.9c-1.9-12.9-7.4-23.5-19-30.4-6.7-4-14.1-6-21.8-7.1-3.6-.5-7.2-.8-10.8-1.3-3.9.1-7.9.1-11.9.1zm35 127.7a3.33 3.33 0 0 1-1.5 3c-11.2 8.1-23.5 13.5-37.4 14.9-5.7.6-11.4.4-16.8-1.8a20.08 20.08 0 0 1-12.4-13.3 32.9 32.9 0 0 1-.1-19.4c2.5-8.3 8.4-13 16.4-15.6a61.33 61.33 0 0 1 24.8-2.2c8.4.7 16.6 2.3 25 3.4 1.6.2 2.1 1 2.1 2.6-.1 4.8 0 9.5 0 14.3s-.2 9.4-.1 14.1zm259.9 129.4c-1-5-4.8-6.9-9.1-8.3a88.42 88.42 0 0 0-21-3.9 147.32 147.32 0 0 0-39.2 1.9c-14.3 2.7-27.9 7.3-40 15.6a13.75 13.75 0 0 0-3.7 3.5 5.11 5.11 0 0 0-.5 4c.4 1.5 2.1 1.9 3.6 1.8a16.2 16.2 0 0 0 2.2-.1c7.8-.8 15.5-1.7 23.3-2.5 11.4-1.1 22.9-1.8 34.3-.9a71.64 71.64 0 0 1 14.4 2.7c5.1 1.4 7.4 5.2 7.6 10.4.4 8-1.4 15.7-3.5 23.3-4.1 15.4-10 30.3-15.8 45.1a17.6 17.6 0 0 0-1 3c-.5 2.9 1.2 4.8 4.1 4.1a10.56 10.56 0 0 0 4.8-2.5 145.91 145.91 0 0 0 12.7-13.4c12.8-16.4 20.3-35.3 24.7-55.6.8-3.6 1.4-7.3 2.1-10.9v-17.3zM493.1 199q-19.35-53.55-38.7-107.2c-2-5.7-4.2-11.3-6.3-16.9-1.1-2.9-3.2-4.8-6.4-4.8-7.6-.1-15.2-.2-22.9-.1-2.5 0-3.7 2-3.2 4.5a43.1 43.1 0 0 0 1.9 6.1q29.4 72.75 59.1 145.5c1.7 4.1 2.1 7.6.2 11.8-3.3 7.3-5.9 15-9.3 22.3-3 6.5-8 11.4-15.2 13.3a42.13 42.13 0 0 1-15.4 1.1c-2.5-.2-5-.8-7.5-1-3.4-.2-5.1 1.3-5.2 4.8q-.15 5 0 9.9c.1 5.5 2 8 7.4 8.9a108.18 108.18 0 0 0 16.9 2c17.1.4 30.7-6.5 39.5-21.4a131.63 131.63 0 0 0 9.2-18.4q35.55-89.7 70.6-179.6a26.62 26.62 0 0 0 1.6-5.5c.4-2.8-.9-4.4-3.7-4.4-6.6-.1-13.3 0-19.9 0a7.54 7.54 0 0 0-7.7 5.2c-.5 1.4-1.1 2.7-1.6 4.1l-34.8 100c-2.5 7.2-5.1 14.5-7.7 22.2-.4-1.1-.6-1.7-.9-2.4z\"],\n    \"amilia\": [448, 512, [], \"f36d\", \"M240.1 32c-61.9 0-131.5 16.9-184.2 55.4-5.1 3.1-9.1 9.2-7.2 19.4 1.1 5.1 5.1 27.4 10.2 39.6 4.1 10.2 14.2 10.2 20.3 6.1 32.5-22.3 96.5-47.7 152.3-47.7 57.9 0 58.9 28.4 58.9 73.1v38.5C203 227.7 78.2 251 46.7 264.2 11.2 280.5 16.3 357.7 16.3 376s15.2 104 124.9 104c47.8 0 113.7-20.7 153.3-42.1v25.4c0 3 2.1 8.2 6.1 9.1 3.1 1 50.7 2 59.9 2s62.5.3 66.5-.7c4.1-1 5.1-6.1 5.1-9.1V168c-.1-80.3-57.9-136-192-136zm50.2 348c-21.4 13.2-48.7 24.4-79.1 24.4-52.8 0-58.9-33.5-59-44.7 0-12.2-3-42.7 18.3-52.9 24.3-13.2 75.1-29.4 119.8-33.5z\"],\n    \"android\": [448, 512, [], \"f17b\", \"M89.6 204.5v115.8c0 15.4-12.1 27.7-27.5 27.7-15.3 0-30.1-12.4-30.1-27.7V204.5c0-15.1 14.8-27.5 30.1-27.5 15.1 0 27.5 12.4 27.5 27.5zm10.8 157c0 16.4 13.2 29.6 29.6 29.6h19.9l.3 61.1c0 36.9 55.2 36.6 55.2 0v-61.1h37.2v61.1c0 36.7 55.5 36.8 55.5 0v-61.1h20.2c16.2 0 29.4-13.2 29.4-29.6V182.1H100.4v179.4zm248-189.1H99.3c0-42.8 25.6-80 63.6-99.4l-19.1-35.3c-2.8-4.9 4.3-8 6.7-3.8l19.4 35.6c34.9-15.5 75-14.7 108.3 0L297.5 34c2.5-4.3 9.5-1.1 6.7 3.8L285.1 73c37.7 19.4 63.3 56.6 63.3 99.4zm-170.7-55.5c0-5.7-4.6-10.5-10.5-10.5-5.7 0-10.2 4.8-10.2 10.5s4.6 10.5 10.2 10.5c5.9 0 10.5-4.8 10.5-10.5zm113.4 0c0-5.7-4.6-10.5-10.2-10.5-5.9 0-10.5 4.8-10.5 10.5s4.6 10.5 10.5 10.5c5.6 0 10.2-4.8 10.2-10.5zm94.8 60.1c-15.1 0-27.5 12.1-27.5 27.5v115.8c0 15.4 12.4 27.7 27.5 27.7 15.4 0 30.1-12.4 30.1-27.7V204.5c0-15.4-14.8-27.5-30.1-27.5z\"],\n    \"angellist\": [448, 512, [], \"f209\", \"M347.1 215.4c11.7-32.6 45.4-126.9 45.4-157.1 0-26.6-15.7-48.9-43.7-48.9-44.6 0-84.6 131.7-97.1 163.1C242 144 196.6 0 156.6 0c-31.1 0-45.7 22.9-45.7 51.7 0 35.3 34.2 126.8 46.6 162-6.3-2.3-13.1-4.3-20-4.3-23.4 0-48.3 29.1-48.3 52.6 0 8.9 4.9 21.4 8 29.7-36.9 10-51.1 34.6-51.1 71.7C46 435.6 114.4 512 210.6 512c118 0 191.4-88.6 191.4-202.9 0-43.1-6.9-82-54.9-93.7zM311.7 108c4-12.3 21.1-64.3 37.1-64.3 8.6 0 10.9 8.9 10.9 16 0 19.1-38.6 124.6-47.1 148l-34-6 33.1-93.7zM142.3 48.3c0-11.9 14.5-45.7 46.3 47.1l34.6 100.3c-15.6-1.3-27.7-3-35.4 1.4-10.9-28.8-45.5-119.7-45.5-148.8zM140 244c29.3 0 67.1 94.6 67.1 107.4 0 5.1-4.9 11.4-10.6 11.4-20.9 0-76.9-76.9-76.9-97.7.1-7.7 12.7-21.1 20.4-21.1zm184.3 186.3c-29.1 32-66.3 48.6-109.7 48.6-59.4 0-106.3-32.6-128.9-88.3-17.1-43.4 3.8-68.3 20.6-68.3 11.4 0 54.3 60.3 54.3 73.1 0 4.9-7.7 8.3-11.7 8.3-16.1 0-22.4-15.5-51.1-51.4-29.7 29.7 20.5 86.9 58.3 86.9 26.1 0 43.1-24.2 38-42 3.7 0 8.3.3 11.7-.6 1.1 27.1 9.1 59.4 41.7 61.7 0-.9 2-7.1 2-7.4 0-17.4-10.6-32.6-10.6-50.3 0-28.3 21.7-55.7 43.7-71.7 8-6 17.7-9.7 27.1-13.1 9.7-3.7 20-8 27.4-15.4-1.1-11.2-5.7-21.1-16.9-21.1-27.7 0-120.6 4-120.6-39.7 0-6.7.1-13.1 17.4-13.1 32.3 0 114.3 8 138.3 29.1 18.1 16.1 24.3 113.2-31 174.7zm-98.6-126c9.7 3.1 19.7 4 29.7 6-7.4 5.4-14 12-20.3 19.1-2.8-8.5-6.2-16.8-9.4-25.1z\"],\n    \"angrycreative\": [640, 512, [], \"f36e\", \"M640 238.2l-3.2 28.2-34.5 2.3-2 18.1 34.5-2.3-3.2 28.2-34.4 2.2-2.3 20.1 34.4-2.2-3 26.1-64.7 4.1 12.7-113.2L527 365.2l-31.9 2-23.8-117.8 30.3-2 13.6 79.4 31.7-82.4 93.1-6.2zM426.8 371.5l28.3-1.8L468 249.6l-28.4 1.9-12.8 120zM162 388.1l-19.4-36-3.5 37.4-28.2 1.7 2.7-29.1c-11 18-32 34.3-56.9 35.8C23.9 399.9-3 377 .3 339.7c2.6-29.3 26.7-62.8 67.5-65.4 37.7-2.4 47.6 23.2 51.3 28.8l2.8-30.8 38.9-2.5c20.1-1.3 38.7 3.7 42.5 23.7l2.6-26.6 64.8-4.2-2.7 27.9-36.4 2.4-1.7 17.9 36.4-2.3-2.7 27.9-36.4 2.3-1.9 19.9 36.3-2.3-2.1 20.8 55-117.2 23.8-1.6L370.4 369l8.9-85.6-22.3 1.4 2.9-27.9 75-4.9-3 28-24.3 1.6-9.7 91.9-58 3.7-4.3-15.6-39.4 2.5-8 16.3-126.2 7.7zm-44.3-70.2l-26.4 1.7C84.6 307.2 76.9 303 65 303.8c-19 1.2-33.3 17.5-34.6 33.3-1.4 16 7.3 32.5 28.7 31.2 12.8-.8 21.3-8.6 28.9-18.9l27-1.7 2.7-29.8zm56.1-7.7c1.2-12.9-7.6-13.6-26.1-12.4l-2.7 28.5c14.2-.9 27.5-2.1 28.8-16.1zm21.1 70.8l5.8-60c-5 13.5-14.7 21.1-27.9 26.6l22.1 33.4zm135.4-45l-7.9-37.8-15.8 39.3 23.7-1.5zm-170.1-74.6l-4.3-17.5-39.6 2.6-8.1 18.2-31.9 2.1 57-121.9 23.9-1.6 30.7 102 9.9-104.7 27-1.8 37.8 63.6 6.5-66.6 28.5-1.9-4 41.2c7.4-13.5 22.9-44.7 63.6-47.5 40.5-2.8 52.4 29.3 53.4 30.3l3.3-32 39.3-2.7c12.7-.9 27.8.3 36.3 9.7l-4.4-11.9 32.2-2.2 12.9 43.2 23-45.7 31-2.2-43.6 78.4-4.8 44.3-28.4 1.9 4.8-44.3-15.8-43c1 22.3-9.2 40.1-32 49.6l25.2 38.8-36.4 2.4-19.2-36.8-4 38.3-28.4 1.9 3.3-31.5c-6.7 9.3-19.7 35.4-59.6 38-26.2 1.7-45.6-10.3-55.4-39.2l-4 40.3-25 1.6-37.6-63.3-6.3 66.2-56.8 3.7zm276.6-82.1c10.2-.7 17.5-2.1 21.6-4.3 4.5-2.4 7-6.4 7.6-12.1.6-5.3-.6-8.8-3.4-10.4-3.6-2.1-10.6-2.8-22.9-2l-2.9 28.8zM327.7 214c5.6 5.9 12.7 8.5 21.3 7.9 4.7-.3 9.1-1.8 13.3-4.1 5.5-3 10.6-8 15.1-14.3l-34.2 2.3 2.4-23.9 63.1-4.3 1.2-12-31.2 2.1c-4.1-3.7-7.8-6.6-11.1-8.1-4-1.7-8.1-2.8-12.2-2.5-8 .5-15.3 3.6-22 9.2-7.7 6.4-12 14.5-12.9 24.4-1.1 9.6 1.4 17.3 7.2 23.3zm-201.3 8.2l23.8-1.6-8.3-37.6-15.5 39.2z\"],\n    \"angular\": [448, 512, [], \"f420\", \"M185.7 268.1h76.2l-38.1-91.6-38.1 91.6zM223.8 32L16 106.4l31.8 275.7 176 97.9 176-97.9 31.8-275.7zM354 373.8h-48.6l-26.2-65.4H168.6l-26.2 65.4H93.7L223.8 81.5z\"],\n    \"app-store\": [512, 512, [], \"f36f\", \"M255.9 120.9l9.1-15.7c5.6-9.8 18.1-13.1 27.9-7.5 9.8 5.6 13.1 18.1 7.5 27.9l-87.5 151.5h63.3c20.5 0 32 24.1 23.1 40.8H113.8c-11.3 0-20.4-9.1-20.4-20.4 0-11.3 9.1-20.4 20.4-20.4h52l66.6-115.4-20.8-36.1c-5.6-9.8-2.3-22.2 7.5-27.9 9.8-5.6 22.2-2.3 27.9 7.5l8.9 15.7zm-78.7 218l-19.6 34c-5.6 9.8-18.1 13.1-27.9 7.5-9.8-5.6-13.1-18.1-7.5-27.9l14.6-25.2c16.4-5.1 29.8-1.2 40.4 11.6zm168.9-61.7h53.1c11.3 0 20.4 9.1 20.4 20.4 0 11.3-9.1 20.4-20.4 20.4h-29.5l19.9 34.5c5.6 9.8 2.3 22.2-7.5 27.9-9.8 5.6-22.2 2.3-27.9-7.5-33.5-58.1-58.7-101.6-75.4-130.6-17.1-29.5-4.9-59.1 7.2-69.1 13.4 23 33.4 57.7 60.1 104zM256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm216 248c0 118.7-96.1 216-216 216-118.7 0-216-96.1-216-216 0-118.7 96.1-216 216-216 118.7 0 216 96.1 216 216z\"],\n    \"app-store-ios\": [448, 512, [], \"f370\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM127 384.5c-5.5 9.6-17.8 12.8-27.3 7.3-9.6-5.5-12.8-17.8-7.3-27.3l14.3-24.7c16.1-4.9 29.3-1.1 39.6 11.4L127 384.5zm138.9-53.9H84c-11 0-20-9-20-20s9-20 20-20h51l65.4-113.2-20.5-35.4c-5.5-9.6-2.2-21.8 7.3-27.3 9.6-5.5 21.8-2.2 27.3 7.3l8.9 15.4 8.9-15.4c5.5-9.6 17.8-12.8 27.3-7.3 9.6 5.5 12.8 17.8 7.3 27.3l-85.8 148.6h62.1c20.2 0 31.5 23.7 22.7 40zm98.1 0h-29l19.6 33.9c5.5 9.6 2.2 21.8-7.3 27.3-9.6 5.5-21.8 2.2-27.3-7.3-32.9-56.9-57.5-99.7-74-128.1-16.7-29-4.8-58 7.1-67.8 13.1 22.7 32.7 56.7 58.9 102h52c11 0 20 9 20 20 0 11.1-9 20-20 20z\"],\n    \"apper\": [640, 512, [], \"f371\", \"M42.1 239.1c22.2 0 29 2.8 33.5 14.6h.8v-22.9c0-11.3-4.8-15.4-17.9-15.4-11.3 0-14.4 2.5-15.1 12.8H4.8c.3-13.9 1.5-19.1 5.8-24.4C17.9 195 29.5 192 56.7 192c33 0 47.1 5 53.9 18.9 2 4.3 4 15.6 4 23.7v76.3H76.3l1.3-19.1h-1c-5.3 15.6-13.6 20.4-35.5 20.4-30.3 0-41.1-10.1-41.1-37.3 0-25.2 12.3-35.8 42.1-35.8zm17.1 48.1c13.1 0 16.9-3 16.9-13.4 0-9.1-4.3-11.6-19.6-11.6-13.1 0-17.9 3-17.9 12.1-.1 10.4 3.7 12.9 20.6 12.9zm77.8-94.9h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.2 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3H137v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm57.9-60.7h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.3 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3h-39.5v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm53.8-3.8c0-25.4 3.3-37.8 12.3-45.8 8.8-8.1 22.2-11.3 45.1-11.3 42.8 0 55.7 12.8 55.7 55.7v11.1h-75.3c-.3 2-.3 4-.3 4.8 0 16.9 4.5 21.9 20.1 21.9 13.9 0 17.9-3 17.9-13.9h37.5v2.3c0 9.8-2.5 18.9-6.8 24.7-7.3 9.8-19.6 13.6-44.3 13.6-27.5 0-41.6-3.3-50.6-12.3-8.5-8.5-11.3-21.3-11.3-50.8zm76.4-11.6c-.3-1.8-.3-3.3-.3-3.8 0-12.3-3.3-14.6-19.6-14.6-14.4 0-17.1 3-18.1 15.1l-.3 3.3h38.3zm55.6-45.3h38.3l-1.8 19.9h.7c6.8-14.9 14.4-20.2 29.7-20.2 10.8 0 19.1 3.3 23.4 9.3 5.3 7.3 6.8 14.4 6.8 34 0 1.5 0 5 .2 9.3h-35c.3-1.8.3-3.3.3-4 0-15.4-2-19.4-10.3-19.4-6.3 0-10.8 3.3-13.1 9.3-1 3-1 4.3-1 12.3v68h-38.3V192.3z\"],\n    \"apple\": [384, 512, [], \"f179\", \"M318.7 268.7c-.2-36.7 16.4-64.4 50-84.8-18.8-26.9-47.2-41.7-84.7-44.6-35.5-2.8-74.3 20.7-88.5 20.7-15 0-49.4-19.7-76.4-19.7C63.3 141.2 4 184.8 4 273.5q0 39.3 14.4 81.2c12.8 36.7 59 126.7 107.2 125.2 25.2-.6 43-17.9 75.8-17.9 31.8 0 48.3 17.9 76.4 17.9 48.6-.7 90.4-82.5 102.6-119.3-65.2-30.7-61.7-90-61.7-91.9zm-56.6-164.2c27.3-32.4 24.8-61.9 24-72.5-24.1 1.4-52 16.4-67.9 34.9-17.5 19.8-27.8 44.3-25.6 71.9 26.1 2 49.9-11.4 69.5-34.3z\"],\n    \"apple-pay\": [640, 512, [], \"f415\", \"M116.9 158.5c-7.5 8.9-19.5 15.9-31.5 14.9-1.5-12 4.4-24.8 11.3-32.6 7.5-9.1 20.6-15.6 31.3-16.1 1.2 12.4-3.7 24.7-11.1 33.8m10.9 17.2c-17.4-1-32.3 9.9-40.5 9.9-8.4 0-21-9.4-34.8-9.1-17.9.3-34.5 10.4-43.6 26.5-18.8 32.3-4.9 80 13.3 106.3 8.9 13 19.5 27.3 33.5 26.8 13.3-.5 18.5-8.6 34.5-8.6 16.1 0 20.8 8.6 34.8 8.4 14.5-.3 23.6-13 32.5-26 10.1-14.8 14.3-29.1 14.5-29.9-.3-.3-28-10.9-28.3-42.9-.3-26.8 21.9-39.5 22.9-40.3-12.5-18.6-32-20.6-38.8-21.1m100.4-36.2v194.9h30.3v-66.6h41.9c38.3 0 65.1-26.3 65.1-64.3s-26.4-64-64.1-64h-73.2zm30.3 25.5h34.9c26.3 0 41.3 14 41.3 38.6s-15 38.8-41.4 38.8h-34.8V165zm162.2 170.9c19 0 36.6-9.6 44.6-24.9h.6v23.4h28v-97c0-28.1-22.5-46.3-57.1-46.3-32.1 0-55.9 18.4-56.8 43.6h27.3c2.3-12 13.4-19.9 28.6-19.9 18.5 0 28.9 8.6 28.9 24.5v10.8l-37.8 2.3c-35.1 2.1-54.1 16.5-54.1 41.5.1 25.2 19.7 42 47.8 42zm8.2-23.1c-16.1 0-26.4-7.8-26.4-19.6 0-12.3 9.9-19.4 28.8-20.5l33.6-2.1v11c0 18.2-15.5 31.2-36 31.2zm102.5 74.6c29.5 0 43.4-11.3 55.5-45.4L640 193h-30.8l-35.6 115.1h-.6L537.4 193h-31.6L557 334.9l-2.8 8.6c-4.6 14.6-12.1 20.3-25.5 20.3-2.4 0-7-.3-8.9-.5v23.4c1.8.4 9.3.7 11.6.7z\"],\n    \"artstation\": [512, 512, [], \"f77a\", \"M2 377.4l43 74.3A51.35 51.35 0 0 0 90.9 480h285.4l-59.2-102.6zM501.8 350L335.6 59.3A51.38 51.38 0 0 0 290.2 32h-88.4l257.3 447.6 40.7-70.5c1.9-3.2 21-29.7 2-59.1zM275 304.5l-115.5-200L44 304.5z\"],\n    \"asymmetrik\": [576, 512, [], \"f372\", \"M517.5 309.2c38.8-40 58.1-80 58.5-116.1.8-65.5-59.4-118.2-169.4-135C277.9 38.4 118.1 73.6 0 140.5 52 114 110.6 92.3 170.7 82.3c74.5-20.5 153-25.4 221.3-14.8C544.5 91.3 588.8 195 490.8 299.2c-10.2 10.8-22 21.1-35 30.6L304.9 103.4 114.7 388.9c-65.6-29.4-76.5-90.2-19.1-151.2 20.8-22.2 48.3-41.9 79.5-58.1 20-12.2 39.7-22.6 62-30.7-65.1 20.3-122.7 52.9-161.6 92.9-27.7 28.6-41.4 57.1-41.7 82.9-.5 35.1 23.4 65.1 68.4 83l-34.5 51.7h101.6l22-34.4c22.2 1 45.3 0 68.6-2.7l-22.8 37.1h135.5L340 406.3c18.6-5.3 36.9-11.5 54.5-18.7l45.9 71.8H542L468.6 349c18.5-12.1 35-25.5 48.9-39.8zm-187.6 80.5l-25-40.6-32.7 53.3c-23.4 3.5-46.7 5.1-69.2 4.4l101.9-159.3 78.7 123c-17.2 7.4-35.3 13.9-53.7 19.2z\"],\n    \"atlassian\": [512, 512, [], \"f77b\", \"M152.2 236.4c-7.7-8.2-19.7-7.7-24.8 2.8L1.6 490.2c-5 10 2.4 21.7 13.4 21.7h175c5.8.1 11-3.2 13.4-8.4 37.9-77.8 15.1-196.3-51.2-267.1zM244.4 8.1c-122.3 193.4-8.5 348.6 65 495.5 2.5 5.1 7.7 8.4 13.4 8.4H497c11.2 0 18.4-11.8 13.4-21.7 0 0-234.5-470.6-240.4-482.3-5.3-10.6-18.8-10.8-25.6.1z\"],\n    \"audible\": [640, 512, [], \"f373\", \"M640 199.9v54l-320 200L0 254v-54l320 200 320-200.1zm-194.5 72l47.1-29.4c-37.2-55.8-100.7-92.6-172.7-92.6-72 0-135.5 36.7-172.6 92.4h.3c2.5-2.3 5.1-4.5 7.7-6.7 89.7-74.4 219.4-58.1 290.2 36.3zm-220.1 18.8c16.9-11.9 36.5-18.7 57.4-18.7 34.4 0 65.2 18.4 86.4 47.6l45.4-28.4c-20.9-29.9-55.6-49.5-94.8-49.5-38.9 0-73.4 19.4-94.4 49zM103.6 161.1c131.8-104.3 318.2-76.4 417.5 62.1l.7 1 48.8-30.4C517.1 112.1 424.8 58.1 319.9 58.1c-103.5 0-196.6 53.5-250.5 135.6 9.9-10.5 22.7-23.5 34.2-32.6zm467 32.7z\"],\n    \"autoprefixer\": [640, 512, [], \"f41c\", \"M318.4 16l-161 480h77.5l25.4-81.4h119.5L405 496h77.5L318.4 16zm-40.3 341.9l41.2-130.4h1.5l40.9 130.4h-83.6zM640 405l-10-31.4L462.1 358l19.4 56.5L640 405zm-462.1-47L10 373.7 0 405l158.5 9.4 19.4-56.4z\"],\n    \"avianex\": [512, 512, [], \"f374\", \"M453.1 32h-312c-38.9 0-76.2 31.2-83.3 69.7L1.2 410.3C-5.9 448.8 19.9 480 58.9 480h312c38.9 0 76.2-31.2 83.3-69.7l56.7-308.5c7-38.6-18.8-69.8-57.8-69.8zm-58.2 347.3l-32 13.5-115.4-110c-14.7 10-29.2 19.5-41.7 27.1l22.1 64.2-17.9 12.7-40.6-61-52.4-48.1 15.7-15.4 58 31.1c9.3-10.5 20.8-22.6 32.8-34.9L203 228.9l-68.8-99.8 18.8-28.9 8.9-4.8L265 207.8l4.9 4.5c19.4-18.8 33.8-32.4 33.8-32.4 7.7-6.5 21.5-2.9 30.7 7.9 9 10.5 10.6 24.7 2.7 31.3-1.8 1.3-15.5 11.4-35.3 25.6l4.5 7.3 94.9 119.4-6.3 7.9z\"],\n    \"aviato\": [640, 512, [], \"f421\", \"M107.2 283.5l-19-41.8H36.1l-19 41.8H0l62.2-131.4 62.2 131.4h-17.2zm-45-98.1l-19.6 42.5h39.2l-19.6-42.5zm112.7 102.4l-62.2-131.4h17.1l45.1 96 45.1-96h17l-62.1 131.4zm80.6-4.3V156.4H271v127.1h-15.5zm209.1-115.6v115.6h-17.3V167.9h-41.2v-11.5h99.6v11.5h-41.1zM640 218.8c0 9.2-1.7 17.8-5.1 25.8-3.4 8-8.2 15.1-14.2 21.1-6 6-13.1 10.8-21.1 14.2-8 3.4-16.6 5.1-25.8 5.1s-17.8-1.7-25.8-5.1c-8-3.4-15.1-8.2-21.1-14.2-6-6-10.8-13-14.2-21.1-3.4-8-5.1-16.6-5.1-25.8s1.7-17.8 5.1-25.8c3.4-8 8.2-15.1 14.2-21.1 6-6 13-8.4 21.1-11.9 8-3.4 16.6-5.1 25.8-5.1s17.8 1.7 25.8 5.1c8 3.4 15.1 5.8 21.1 11.9 6 6 10.7 13.1 14.2 21.1 3.4 8 5.1 16.6 5.1 25.8zm-15.5 0c0-7.3-1.3-14-3.9-20.3-2.6-6.3-6.2-11.7-10.8-16.3-4.6-4.6-10-8.2-16.2-10.9-6.2-2.7-12.8-4-19.8-4s-13.6 1.3-19.8 4c-6.2 2.7-11.6 6.3-16.2 10.9-4.6 4.6-8.2 10-10.8 16.3-2.6 6.3-3.9 13.1-3.9 20.3 0 7.3 1.3 14 3.9 20.3 2.6 6.3 6.2 11.7 10.8 16.3 4.6 4.6 10 8.2 16.2 10.9 6.2 2.7 12.8 4 19.8 4s13.6-1.3 19.8-4c6.2-2.7 11.6-6.3 16.2-10.9 4.6-4.6 8.2-10 10.8-16.3 2.6-6.3 3.9-13.1 3.9-20.3zm-94.8 96.7v-6.3l88.9-10-242.9 13.4c.6-2.2 1.1-4.6 1.4-7.2.3-2 .5-4.2.6-6.5l64.8-8.1-64.9 1.9c0-.4-.1-.7-.1-1.1-2.8-17.2-25.5-23.7-25.5-23.7l-1.1-26.3h23.8l19 41.8h17.1L348.6 152l-62.2 131.4h17.1l19-41.8h23.6L345 268s-22.7 6.5-25.5 23.7c-.1.3-.1.7-.1 1.1l-64.9-1.9 64.8 8.1c.1 2.3.3 4.4.6 6.5.3 2.6.8 5 1.4 7.2L78.4 299.2l88.9 10v6.3c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4 0-6.2-4.6-11.3-10.5-12.2v-5.8l80.3 9v5.4c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-4.9l28.4 3.2v23.7h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9V323l38.3 4.3c8.1 11.4 19 13.6 19 13.6l-.1 6.7-5.1.2-.1 12.1h4.1l.1-5h5.2l.1 5h4.1l-.1-12.1-5.1-.2-.1-6.7s10.9-2.1 19-13.6l38.3-4.3v23.2h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9v-23.7l28.4-3.2v4.9c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-5.4l80.3-9v5.8c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4-.2-6.3-4.7-11.4-10.7-12.3zm-200.8-87.6l19.6-42.5 19.6 42.5h-17.9l-1.7-40.3-1.7 40.3h-17.9z\"],\n    \"aws\": [640, 512, [], \"f375\", \"M180.41 203.01c-.72 22.65 10.6 32.68 10.88 39.05a8.164 8.164 0 0 1-4.1 6.27l-12.8 8.96a10.66 10.66 0 0 1-5.63 1.92c-.43-.02-8.19 1.83-20.48-25.61a78.608 78.608 0 0 1-62.61 29.45c-16.28.89-60.4-9.24-58.13-56.21-1.59-38.28 34.06-62.06 70.93-60.05 7.1.02 21.6.37 46.99 6.27v-15.62c2.69-26.46-14.7-46.99-44.81-43.91-2.4.01-19.4-.5-45.84 10.11-7.36 3.38-8.3 2.82-10.75 2.82-7.41 0-4.36-21.48-2.94-24.2 5.21-6.4 35.86-18.35 65.94-18.18a76.857 76.857 0 0 1 55.69 17.28 70.285 70.285 0 0 1 17.67 52.36l-.01 69.29zM93.99 235.4c32.43-.47 46.16-19.97 49.29-30.47 2.46-10.05 2.05-16.41 2.05-27.4-9.67-2.32-23.59-4.85-39.56-4.87-15.15-1.14-42.82 5.63-41.74 32.26-1.24 16.79 11.12 31.4 29.96 30.48zm170.92 23.05c-7.86.72-11.52-4.86-12.68-10.37l-49.8-164.65c-.97-2.78-1.61-5.65-1.92-8.58a4.61 4.61 0 0 1 3.86-5.25c.24-.04-2.13 0 22.25 0 8.78-.88 11.64 6.03 12.55 10.37l35.72 140.83 33.16-140.83c.53-3.22 2.94-11.07 12.8-10.24h17.16c2.17-.18 11.11-.5 12.68 10.37l33.42 142.63L420.98 80.1c.48-2.18 2.72-11.37 12.68-10.37h19.72c.85-.13 6.15-.81 5.25 8.58-.43 1.85 3.41-10.66-52.75 169.9-1.15 5.51-4.82 11.09-12.68 10.37h-18.69c-10.94 1.15-12.51-9.66-12.68-10.75L328.67 110.7l-32.78 136.99c-.16 1.09-1.73 11.9-12.68 10.75h-18.3zm273.48 5.63c-5.88.01-33.92-.3-57.36-12.29a12.802 12.802 0 0 1-7.81-11.91v-10.75c0-8.45 6.2-6.9 8.83-5.89 10.04 4.06 16.48 7.14 28.81 9.6 36.65 7.53 52.77-2.3 56.72-4.48 13.15-7.81 14.19-25.68 5.25-34.95-10.48-8.79-15.48-9.12-53.13-21-4.64-1.29-43.7-13.61-43.79-52.36-.61-28.24 25.05-56.18 69.52-55.95 12.67-.01 46.43 4.13 55.57 15.62 1.35 2.09 2.02 4.55 1.92 7.04v10.11c0 4.44-1.62 6.66-4.87 6.66-7.71-.86-21.39-11.17-49.16-10.75-6.89-.36-39.89.91-38.41 24.97-.43 18.96 26.61 26.07 29.7 26.89 36.46 10.97 48.65 12.79 63.12 29.58 17.14 22.25 7.9 48.3 4.35 55.44-19.08 37.49-68.42 34.44-69.26 34.42zm40.2 104.86c-70.03 51.72-171.69 79.25-258.49 79.25A469.127 469.127 0 0 1 2.83 327.46c-6.53-5.89-.77-13.96 7.17-9.47a637.37 637.37 0 0 0 316.88 84.12 630.22 630.22 0 0 0 241.59-49.55c11.78-5 21.77 7.8 10.12 16.38zm29.19-33.29c-8.96-11.52-59.28-5.38-81.81-2.69-6.79.77-7.94-5.12-1.79-9.47 40.07-28.17 105.88-20.1 113.44-10.63 7.55 9.47-2.05 75.41-39.56 106.91-5.76 4.87-11.27 2.3-8.71-4.1 8.44-21.25 27.39-68.49 18.43-80.02z\"],\n    \"bandcamp\": [496, 512, [], \"f2d5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm48.2 326.1h-181L199.9 178h181l-84.7 156.1z\"],\n    \"battle-net\": [512, 512, [], \"f835\", \"M448.61 225.62c26.87.18 35.57-7.43 38.92-12.37 12.47-16.32-7.06-47.6-52.85-71.33 17.76-33.58 30.11-63.68 36.34-85.3 3.38-11.83 1.09-19 .45-20.25-1.72 10.52-15.85 48.46-48.2 100.05-25-11.22-56.52-20.1-93.77-23.8-8.94-16.94-34.88-63.86-60.48-88.93C252.18 7.14 238.7 1.07 228.18.22h-.05c-13.83-1.55-22.67 5.85-27.4 11-17.2 18.53-24.33 48.87-25 84.07-7.24-12.35-17.17-24.63-28.5-25.93h-.18c-20.66-3.48-38.39 29.22-36 81.29-38.36 1.38-71 5.75-93 11.23-9.9 2.45-16.22 7.27-17.76 9.72 1-.38 22.4-9.22 111.56-9.22 5.22 53 29.75 101.82 26 93.19-9.73 15.4-38.24 62.36-47.31 97.7-5.87 22.88-4.37 37.61.15 47.14 5.57 12.75 16.41 16.72 23.2 18.26 25 5.71 55.38-3.63 86.7-21.14-7.53 12.84-13.9 28.51-9.06 39.34 7.31 19.65 44.49 18.66 88.44-9.45 20.18 32.18 40.07 57.94 55.7 74.12a39.79 39.79 0 0 0 8.75 7.09c5.14 3.21 8.58 3.37 8.58 3.37-8.24-6.75-34-38-62.54-91.78 22.22-16 45.65-38.87 67.47-69.27 122.82 4.6 143.29-24.76 148-31.64 14.67-19.88 3.43-57.44-57.32-93.69zm-77.85 106.22c23.81-37.71 30.34-67.77 29.45-92.33 27.86 17.57 47.18 37.58 49.06 58.83 1.14 12.93-8.1 29.12-78.51 33.5zM216.9 387.69c9.76-6.23 19.53-13.12 29.2-20.49 6.68 13.33 13.6 26.1 20.6 38.19-40.6 21.86-68.84 12.76-49.8-17.7zm215-171.35c-10.29-5.34-21.16-10.34-32.38-15.05a722.459 722.459 0 0 0 22.74-36.9c39.06 24.1 45.9 53.18 9.64 51.95zM279.18 398c-5.51-11.35-11-23.5-16.5-36.44 43.25 1.27 62.42-18.73 63.28-20.41 0 .07-25 15.64-62.53 12.25a718.78 718.78 0 0 0 85.06-84q13.06-15.31 24.93-31.11c-.36-.29-1.54-3-16.51-12-51.7 60.27-102.34 98-132.75 115.92-20.59-11.18-40.84-31.78-55.71-61.49-20-39.92-30-82.39-31.57-116.07 12.3.91 25.27 2.17 38.85 3.88-22.29 36.8-14.39 63-13.47 64.23 0-.07-.95-29.17 20.14-59.57a695.23 695.23 0 0 0 44.67 152.84c.93-.38 1.84.88 18.67-8.25-26.33-74.47-33.76-138.17-34-173.43 20-12.42 48.18-19.8 81.63-17.81 44.57 2.67 86.36 15.25 116.32 30.71q-10.69 15.66-23.33 32.47C365.63 152 339.1 145.84 337.5 146c.11 0 25.9 14.07 41.52 47.22a717.63 717.63 0 0 0-115.34-31.71 646.608 646.608 0 0 0-39.39-6.05c-.07.45-1.81 1.85-2.16 20.33C300 190.28 358.78 215.68 389.36 233c.74 23.55-6.95 51.61-25.41 79.57-24.6 37.31-56.39 67.23-84.77 85.43zm27.4-287c-44.56-1.66-73.58 7.43-94.69 20.67 2-52.3 21.31-76.38 38.21-75.28C267 52.15 305 108.55 306.58 111zm-130.65 3.1c.48 12.11 1.59 24.62 3.21 37.28-14.55-.85-28.74-1.25-42.4-1.26-.08 3.24-.12-51 24.67-49.59h.09c5.76 1.09 10.63 6.88 14.43 13.57zm-28.06 162c20.76 39.7 43.3 60.57 65.25 72.31-46.79 24.76-77.53 20-84.92 4.51-.2-.21-11.13-15.3 19.67-76.81zm210.06 74.8\"],\n    \"behance\": [576, 512, [], \"f1b4\", \"M232 237.2c31.8-15.2 48.4-38.2 48.4-74 0-70.6-52.6-87.8-113.3-87.8H0v354.4h171.8c64.4 0 124.9-30.9 124.9-102.9 0-44.5-21.1-77.4-64.7-89.7zM77.9 135.9H151c28.1 0 53.4 7.9 53.4 40.5 0 30.1-19.7 42.2-47.5 42.2h-79v-82.7zm83.3 233.7H77.9V272h84.9c34.3 0 56 14.3 56 50.6 0 35.8-25.9 47-57.6 47zm358.5-240.7H376V94h143.7v34.9zM576 305.2c0-75.9-44.4-139.2-124.9-139.2-78.2 0-131.3 58.8-131.3 135.8 0 79.9 50.3 134.7 131.3 134.7 61.3 0 101-27.6 120.1-86.3H509c-6.7 21.9-34.3 33.5-55.7 33.5-41.3 0-63-24.2-63-65.3h185.1c.3-4.2.6-8.7.6-13.2zM390.4 274c2.3-33.7 24.7-54.8 58.5-54.8 35.4 0 53.2 20.8 56.2 54.8H390.4z\"],\n    \"behance-square\": [448, 512, [], \"f1b5\", \"M186.5 293c0 19.3-14 25.4-31.2 25.4h-45.1v-52.9h46c18.6.1 30.3 7.8 30.3 27.5zm-7.7-82.3c0-17.7-13.7-21.9-28.9-21.9h-39.6v44.8H153c15.1 0 25.8-6.6 25.8-22.9zm132.3 23.2c-18.3 0-30.5 11.4-31.7 29.7h62.2c-1.7-18.5-11.3-29.7-30.5-29.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM271.7 185h77.8v-18.9h-77.8V185zm-43 110.3c0-24.1-11.4-44.9-35-51.6 17.2-8.2 26.2-17.7 26.2-37 0-38.2-28.5-47.5-61.4-47.5H68v192h93.1c34.9-.2 67.6-16.9 67.6-55.9zM380 280.5c0-41.1-24.1-75.4-67.6-75.4-42.4 0-71.1 31.8-71.1 73.6 0 43.3 27.3 73 71.1 73 33.2 0 54.7-14.9 65.1-46.8h-33.7c-3.7 11.9-18.6 18.1-30.2 18.1-22.4 0-34.1-13.1-34.1-35.3h100.2c.1-2.3.3-4.8.3-7.2z\"],\n    \"bimobject\": [448, 512, [], \"f378\", \"M416 32H32C14.4 32 0 46.4 0 64v384c0 17.6 14.4 32 32 32h384c17.6 0 32-14.4 32-32V64c0-17.6-14.4-32-32-32zm-64 257.4c0 49.4-11.4 82.6-103.8 82.6h-16.9c-44.1 0-62.4-14.9-70.4-38.8h-.9V368H96V136h64v74.7h1.1c4.6-30.5 39.7-38.8 69.7-38.8h17.3c92.4 0 103.8 33.1 103.8 82.5v35zm-64-28.9v22.9c0 21.7-3.4 33.8-38.4 33.8h-45.3c-28.9 0-44.1-6.5-44.1-35.7v-19c0-29.3 15.2-35.7 44.1-35.7h45.3c35-.2 38.4 12 38.4 33.7z\"],\n    \"bitbucket\": [512, 512, [], \"f171\", \"M22.2 32A16 16 0 0 0 6 47.8a26.35 26.35 0 0 0 .2 2.8l67.9 412.1a21.77 21.77 0 0 0 21.3 18.2h325.7a16 16 0 0 0 16-13.4L505 50.7a16 16 0 0 0-13.2-18.3 24.58 24.58 0 0 0-2.8-.2L22.2 32zm285.9 297.8h-104l-28.1-147h157.3l-25.2 147z\"],\n    \"bitcoin\": [512, 512, [], \"f379\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-141.651-35.33c4.937-32.999-20.191-50.739-54.55-62.573l11.146-44.702-27.213-6.781-10.851 43.524c-7.154-1.783-14.502-3.464-21.803-5.13l10.929-43.81-27.198-6.781-11.153 44.686c-5.922-1.349-11.735-2.682-17.377-4.084l.031-.14-37.53-9.37-7.239 29.062s20.191 4.627 19.765 4.913c11.022 2.751 13.014 10.044 12.68 15.825l-12.696 50.925c.76.194 1.744.473 2.829.907-.907-.225-1.876-.473-2.876-.713l-17.796 71.338c-1.349 3.348-4.767 8.37-12.471 6.464.271.395-19.78-4.937-19.78-4.937l-13.51 31.147 35.414 8.827c6.588 1.651 13.045 3.379 19.4 5.006l-11.262 45.213 27.182 6.781 11.153-44.733a1038.209 1038.209 0 0 0 21.687 5.627l-11.115 44.523 27.213 6.781 11.262-45.128c46.404 8.781 81.299 5.239 95.986-36.727 11.836-33.79-.589-53.281-25.004-65.991 17.78-4.098 31.174-15.792 34.747-39.949zm-62.177 87.179c-8.41 33.79-65.308 15.523-83.755 10.943l14.944-59.899c18.446 4.603 77.6 13.717 68.811 48.956zm8.417-87.667c-7.673 30.736-55.031 15.12-70.393 11.292l13.548-54.327c15.363 3.828 64.836 10.973 56.845 43.035z\"],\n    \"bity\": [496, 512, [], \"f37a\", \"M78.4 67.2C173.8-22 324.5-24 421.5 71c14.3 14.1-6.4 37.1-22.4 21.5-84.8-82.4-215.8-80.3-298.9-3.2-16.3 15.1-36.5-8.3-21.8-22.1zm98.9 418.6c19.3 5.7 29.3-23.6 7.9-30C73 421.9 9.4 306.1 37.7 194.8c5-19.6-24.9-28.1-30.2-7.1-32.1 127.4 41.1 259.8 169.8 298.1zm148.1-2c121.9-40.2 192.9-166.9 164.4-291-4.5-19.7-34.9-13.8-30 7.9 24.2 107.7-37.1 217.9-143.2 253.4-21.2 7-10.4 36 8.8 29.7zm-62.9-79l.2-71.8c0-8.2-6.6-14.8-14.8-14.8-8.2 0-14.8 6.7-14.8 14.8l-.2 71.8c0 8.2 6.6 14.8 14.8 14.8s14.8-6.6 14.8-14.8zm71-269c2.1 90.9 4.7 131.9-85.5 132.5-92.5-.7-86.9-44.3-85.5-132.5 0-21.8-32.5-19.6-32.5 0v71.6c0 69.3 60.7 90.9 118 90.1 57.3.8 118-20.8 118-90.1v-71.6c0-19.6-32.5-21.8-32.5 0z\"],\n    \"black-tie\": [448, 512, [], \"f27e\", \"M0 32v448h448V32H0zm316.5 325.2L224 445.9l-92.5-88.7 64.5-184-64.5-86.6h184.9L252 173.2l64.5 184z\"],\n    \"blackberry\": [512, 512, [], \"f37b\", \"M166 116.9c0 23.4-16.4 49.1-72.5 49.1H23.4l21-88.8h67.8c42.1 0 53.8 23.3 53.8 39.7zm126.2-39.7h-67.8L205.7 166h70.1c53.8 0 70.1-25.7 70.1-49.1.1-16.4-11.6-39.7-53.7-39.7zM88.8 208.1H21L0 296.9h70.1c56.1 0 72.5-23.4 72.5-49.1 0-16.3-11.7-39.7-53.8-39.7zm180.1 0h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1 0-16.3-11.7-39.7-53.7-39.7zm189.3-53.8h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7zm-28 137.9h-67.8L343.7 381h70.1c56.1 0 70.1-23.4 70.1-49.1 0-16.3-11.6-39.7-53.7-39.7zM240.8 346H173l-18.7 88.8h70.1c56.1 0 70.1-25.7 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7z\"],\n    \"blogger\": [448, 512, [], \"f37c\", \"M162.4 196c4.8-4.9 6.2-5.1 36.4-5.1 27.2 0 28.1.1 32.1 2.1 5.8 2.9 8.3 7 8.3 13.6 0 5.9-2.4 10-7.6 13.4-2.8 1.8-4.5 1.9-31.1 2.1-16.4.1-29.5-.2-31.5-.8-10.3-2.9-14.1-17.7-6.6-25.3zm61.4 94.5c-53.9 0-55.8.2-60.2 4.1-3.5 3.1-5.7 9.4-5.1 13.9.7 4.7 4.8 10.1 9.2 12 2.2 1 14.1 1.7 56.3 1.2l47.9-.6 9.2-1.5c9-5.1 10.5-17.4 3.1-24.4-5.3-4.7-5-4.7-60.4-4.7zm223.4 130.1c-3.5 28.4-23 50.4-51.1 57.5-7.2 1.8-9.7 1.9-172.9 1.8-157.8 0-165.9-.1-172-1.8-8.4-2.2-15.6-5.5-22.3-10-5.6-3.8-13.9-11.8-17-16.4-3.8-5.6-8.2-15.3-10-22C.1 423 0 420.3 0 256.3 0 93.2 0 89.7 1.8 82.6 8.1 57.9 27.7 39 53 33.4c7.3-1.6 332.1-1.9 340-.3 21.2 4.3 37.9 17.1 47.6 36.4 7.7 15.3 7-1.5 7.3 180.6.2 115.8 0 164.5-.7 170.5zm-85.4-185.2c-1.1-5-4.2-9.6-7.7-11.5-1.1-.6-8-1.3-15.5-1.7-12.4-.6-13.8-.8-17.8-3.1-6.2-3.6-7.9-7.6-8-18.3 0-20.4-8.5-39.4-25.3-56.5-12-12.2-25.3-20.5-40.6-25.1-3.6-1.1-11.8-1.5-39.2-1.8-42.9-.5-52.5.4-67.1 6.2-27 10.7-46.3 33.4-53.4 62.4-1.3 5.4-1.6 14.2-1.9 64.3-.4 62.8 0 72.1 4 84.5 9.7 30.7 37.1 53.4 64.6 58.4 9.2 1.7 122.2 2.1 133.7.5 20.1-2.7 35.9-10.8 50.7-25.9 10.7-10.9 17.4-22.8 21.8-38.5 3.2-10.9 2.9-88.4 1.7-93.9z\"],\n    \"blogger-b\": [448, 512, [], \"f37d\", \"M446.6 222.7c-1.8-8-6.8-15.4-12.5-18.5-1.8-1-13-2.2-25-2.7-20.1-.9-22.3-1.3-28.7-5-10.1-5.9-12.8-12.3-12.9-29.5-.1-33-13.8-63.7-40.9-91.3-19.3-19.7-40.9-33-65.5-40.5-5.9-1.8-19.1-2.4-63.3-2.9-69.4-.8-84.8.6-108.4 10C45.9 59.5 14.7 96.1 3.3 142.9 1.2 151.7.7 165.8.2 246.8c-.6 101.5.1 116.4 6.4 136.5 15.6 49.6 59.9 86.3 104.4 94.3 14.8 2.7 197.3 3.3 216 .8 32.5-4.4 58-17.5 81.9-41.9 17.3-17.7 28.1-36.8 35.2-62.1 4.9-17.6 4.5-142.8 2.5-151.7zm-322.1-63.6c7.8-7.9 10-8.2 58.8-8.2 43.9 0 45.4.1 51.8 3.4 9.3 4.7 13.4 11.3 13.4 21.9 0 9.5-3.8 16.2-12.3 21.6-4.6 2.9-7.3 3.1-50.3 3.3-26.5.2-47.7-.4-50.8-1.2-16.6-4.7-22.8-28.5-10.6-40.8zm191.8 199.8l-14.9 2.4-77.5.9c-68.1.8-87.3-.4-90.9-2-7.1-3.1-13.8-11.7-14.9-19.4-1.1-7.3 2.6-17.3 8.2-22.4 7.1-6.4 10.2-6.6 97.3-6.7 89.6-.1 89.1-.1 97.6 7.8 12.1 11.3 9.5 31.2-4.9 39.4z\"],\n    \"bluetooth\": [448, 512, [], \"f293\", \"M292.6 171.1L249.7 214l-.3-86 43.2 43.1m-43.2 219.8l43.1-43.1-42.9-42.9-.2 86zM416 259.4C416 465 344.1 512 230.9 512S32 465 32 259.4 115.4 0 228.6 0 416 53.9 416 259.4zm-158.5 0l79.4-88.6L211.8 36.5v176.9L138 139.6l-27 26.9 92.7 93-92.7 93 26.9 26.9 73.8-73.8 2.3 170 127.4-127.5-83.9-88.7z\"],\n    \"bluetooth-b\": [320, 512, [], \"f294\", \"M196.48 260.023l92.626-103.333L143.125 0v206.33l-86.111-86.111-31.406 31.405 108.061 108.399L25.608 368.422l31.406 31.405 86.111-86.111L145.84 512l148.552-148.644-97.912-103.333zm40.86-102.996l-49.977 49.978-.338-100.295 50.315 50.317zM187.363 313.04l49.977 49.978-50.315 50.316.338-100.294z\"],\n    \"bootstrap\": [448, 512, [], \"f836\", \"M292.3 311.93c0 42.41-39.72 41.43-43.92 41.43h-80.89v-81.69h80.89c42.56 0 43.92 31.9 43.92 40.26zm-50.15-73.13c.67 0 38.44 1 38.44-36.31 0-15.52-3.51-35.87-38.44-35.87h-74.66v72.18h74.66zM448 106.67v298.66A74.89 74.89 0 0 1 373.33 480H74.67A74.89 74.89 0 0 1 0 405.33V106.67A74.89 74.89 0 0 1 74.67 32h298.66A74.89 74.89 0 0 1 448 106.67zM338.05 317.86c0-21.57-6.65-58.29-49.05-67.35v-.73c22.91-9.78 37.34-28.25 37.34-55.64 0-7 2-64.78-77.6-64.78h-127v261.33c128.23 0 139.87 1.68 163.6-5.71 14.21-4.42 52.71-17.98 52.71-67.12z\"],\n    \"btc\": [384, 512, [], \"f15a\", \"M310.204 242.638c27.73-14.18 45.377-39.39 41.28-81.3-5.358-57.351-52.458-76.573-114.85-81.929V0h-48.528v77.203c-12.605 0-25.525.315-38.444.63V0h-48.528v79.409c-17.842.539-38.622.276-97.37 0v51.678c38.314-.678 58.417-3.14 63.023 21.427v217.429c-2.925 19.492-18.524 16.685-53.255 16.071L3.765 443.68c88.481 0 97.37.315 97.37.315V512h48.528v-67.06c13.234.315 26.154.315 38.444.315V512h48.528v-68.005c81.299-4.412 135.647-24.894 142.895-101.467 5.671-61.446-23.32-88.862-69.326-99.89zM150.608 134.553c27.415 0 113.126-8.507 113.126 48.528 0 54.515-85.71 48.212-113.126 48.212v-96.74zm0 251.776V279.821c32.772 0 133.127-9.138 133.127 53.255-.001 60.186-100.355 53.253-133.127 53.253z\"],\n    \"buffer\": [448, 512, [], \"f837\", \"M427.84 380.67l-196.5 97.82a18.6 18.6 0 0 1-14.67 0L20.16 380.67c-4-2-4-5.28 0-7.29L67.22 350a18.65 18.65 0 0 1 14.69 0l134.76 67a18.51 18.51 0 0 0 14.67 0l134.76-67a18.62 18.62 0 0 1 14.68 0l47.06 23.43c4.05 1.96 4.05 5.24 0 7.24zm0-136.53l-47.06-23.43a18.62 18.62 0 0 0-14.68 0l-134.76 67.08a18.68 18.68 0 0 1-14.67 0L81.91 220.71a18.65 18.65 0 0 0-14.69 0l-47.06 23.43c-4 2-4 5.29 0 7.31l196.51 97.8a18.6 18.6 0 0 0 14.67 0l196.5-97.8c4.05-2.02 4.05-5.3 0-7.31zM20.16 130.42l196.5 90.29a20.08 20.08 0 0 0 14.67 0l196.51-90.29c4-1.86 4-4.89 0-6.74L231.33 33.4a19.88 19.88 0 0 0-14.67 0l-196.5 90.28c-4.05 1.85-4.05 4.88 0 6.74z\"],\n    \"buromobelexperte\": [448, 512, [], \"f37f\", \"M0 32v128h128V32H0zm120 120H8V40h112v112zm40-120v128h128V32H160zm120 120H168V40h112v112zm40-120v128h128V32H320zm120 120H328V40h112v112zM0 192v128h128V192H0zm120 120H8V200h112v112zm40-120v128h128V192H160zm120 120H168V200h112v112zm40-120v128h128V192H320zm120 120H328V200h112v112zM0 352v128h128V352H0zm120 120H8V360h112v112zm40-120v128h128V352H160zm120 120H168V360h112v112zm40-120v128h128V352H320z\"],\n    \"buysellads\": [448, 512, [], \"f20d\", \"M224 150.7l42.9 160.7h-85.8L224 150.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-65.3 325.3l-94.5-298.7H159.8L65.3 405.3H156l111.7-91.6 24.2 91.6h90.8z\"],\n    \"canadian-maple-leaf\": [512, 512, [], \"f785\", \"M383.8 351.7c2.5-2.5 105.2-92.4 105.2-92.4l-17.5-7.5c-10-4.9-7.4-11.5-5-17.4 2.4-7.6 20.1-67.3 20.1-67.3s-47.7 10-57.7 12.5c-7.5 2.4-10-2.5-12.5-7.5s-15-32.4-15-32.4-52.6 59.9-55.1 62.3c-10 7.5-20.1 0-17.6-10 0-10 27.6-129.6 27.6-129.6s-30.1 17.4-40.1 22.4c-7.5 5-12.6 5-17.6-5C293.5 72.3 255.9 0 255.9 0s-37.5 72.3-42.5 79.8c-5 10-10 10-17.6 5-10-5-40.1-22.4-40.1-22.4S183.3 182 183.3 192c2.5 10-7.5 17.5-17.6 10-2.5-2.5-55.1-62.3-55.1-62.3S98.1 167 95.6 172s-5 9.9-12.5 7.5C73 177 25.4 167 25.4 167s17.6 59.7 20.1 67.3c2.4 6 5 12.5-5 17.4L23 259.3s102.6 89.9 105.2 92.4c5.1 5 10 7.5 5.1 22.5-5.1 15-10.1 35.1-10.1 35.1s95.2-20.1 105.3-22.6c8.7-.9 18.3 2.5 18.3 12.5S241 512 241 512h30s-5.8-102.7-5.8-112.8 9.5-13.4 18.4-12.5c10 2.5 105.2 22.6 105.2 22.6s-5-20.1-10-35.1 0-17.5 5-22.5z\"],\n    \"cc-amazon-pay\": [576, 512, [], \"f42d\", \"M124.7 201.8c.1-11.8 0-23.5 0-35.3v-35.3c0-1.3.4-2 1.4-2.7 11.5-8 24.1-12.1 38.2-11.1 12.5.9 22.7 7 28.1 21.7 3.3 8.9 4.1 18.2 4.1 27.7 0 8.7-.7 17.3-3.4 25.6-5.7 17.8-18.7 24.7-35.7 23.9-11.7-.5-21.9-5-31.4-11.7-.9-.8-1.4-1.6-1.3-2.8zm154.9 14.6c4.6 1.8 9.3 2 14.1 1.5 11.6-1.2 21.9-5.7 31.3-12.5.9-.6 1.3-1.3 1.3-2.5-.1-3.9 0-7.9 0-11.8 0-4-.1-8 0-12 0-1.4-.4-2-1.8-2.2-7-.9-13.9-2.2-20.9-2.9-7-.6-14-.3-20.8 1.9-6.7 2.2-11.7 6.2-13.7 13.1-1.6 5.4-1.6 10.8.1 16.2 1.6 5.5 5.2 9.2 10.4 11.2zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zm-207.5 23.9c.4 1.7.9 3.4 1.6 5.1 16.5 40.6 32.9 81.3 49.5 121.9 1.4 3.5 1.7 6.4.2 9.9-2.8 6.2-4.9 12.6-7.8 18.7-2.6 5.5-6.7 9.5-12.7 11.2-4.2 1.1-8.5 1.3-12.9.9-2.1-.2-4.2-.7-6.3-.8-2.8-.2-4.2 1.1-4.3 4-.1 2.8-.1 5.6 0 8.3.1 4.6 1.6 6.7 6.2 7.5 4.7.8 9.4 1.6 14.2 1.7 14.3.3 25.7-5.4 33.1-17.9 2.9-4.9 5.6-10.1 7.7-15.4 19.8-50.1 39.5-100.3 59.2-150.5.6-1.5 1.1-3 1.3-4.6.4-2.4-.7-3.6-3.1-3.7-5.6-.1-11.1 0-16.7 0-3.1 0-5.3 1.4-6.4 4.3-.4 1.1-.9 2.3-1.3 3.4l-29.1 83.7c-2.1 6.1-4.2 12.1-6.5 18.6-.4-.9-.6-1.4-.8-1.9-10.8-29.9-21.6-59.9-32.4-89.8-1.7-4.7-3.5-9.5-5.3-14.2-.9-2.5-2.7-4-5.4-4-6.4-.1-12.8-.2-19.2-.1-2.2 0-3.3 1.6-2.8 3.7zM242.4 206c1.7 11.7 7.6 20.8 18 26.6 9.9 5.5 20.7 6.2 31.7 4.6 12.7-1.9 23.9-7.3 33.8-15.5.4-.3.8-.6 1.4-1 .5 3.2.9 6.2 1.5 9.2.5 2.6 2.1 4.3 4.5 4.4 4.6.1 9.1.1 13.7 0 2.3-.1 3.8-1.6 4-3.9.1-.8.1-1.6.1-2.3v-88.8c0-3.6-.2-7.2-.7-10.8-1.6-10.8-6.2-19.7-15.9-25.4-5.6-3.3-11.8-5-18.2-5.9-3-.4-6-.7-9.1-1.1h-10c-.8.1-1.6.3-2.5.3-8.2.4-16.3 1.4-24.2 3.5-5.1 1.3-10 3.2-15 4.9-3 1-4.5 3.2-4.4 6.5.1 2.8-.1 5.6 0 8.3.1 4.1 1.8 5.2 5.7 4.1 6.5-1.7 13.1-3.5 19.7-4.8 10.3-1.9 20.7-2.7 31.1-1.2 5.4.8 10.5 2.4 14.1 7 3.1 4 4.2 8.8 4.4 13.7.3 6.9.2 13.9.3 20.8 0 .4-.1.7-.2 1.2-.4 0-.8 0-1.1-.1-8.8-2.1-17.7-3.6-26.8-4.1-9.5-.5-18.9.1-27.9 3.2-10.8 3.8-19.5 10.3-24.6 20.8-4.1 8.3-4.6 17-3.4 25.8zM98.7 106.9v175.3c0 .8 0 1.7.1 2.5.2 2.5 1.7 4.1 4.1 4.2 5.9.1 11.8.1 17.7 0 2.5 0 4-1.7 4.1-4.1.1-.8.1-1.7.1-2.5v-60.7c.9.7 1.4 1.2 1.9 1.6 15 12.5 32.2 16.6 51.1 12.9 17.1-3.4 28.9-13.9 36.7-29.2 5.8-11.6 8.3-24.1 8.7-37 .5-14.3-1-28.4-6.8-41.7-7.1-16.4-18.9-27.3-36.7-30.9-2.7-.6-5.5-.8-8.2-1.2h-7c-1.2.2-2.4.3-3.6.5-11.7 1.4-22.3 5.8-31.8 12.7-2 1.4-3.9 3-5.9 4.5-.1-.5-.3-.8-.4-1.2-.4-2.3-.7-4.6-1.1-6.9-.6-3.9-2.5-5.5-6.4-5.6h-9.7c-5.9-.1-6.9 1-6.9 6.8zM493.6 339c-2.7-.7-5.1 0-7.6 1-43.9 18.4-89.5 30.2-136.8 35.8-14.5 1.7-29.1 2.8-43.7 3.2-26.6.7-53.2-.8-79.6-4.3-17.8-2.4-35.5-5.7-53-9.9-37-8.9-72.7-21.7-106.7-38.8-8.8-4.4-17.4-9.3-26.1-14-3.8-2.1-6.2-1.5-8.2 2.1v1.7c1.2 1.6 2.2 3.4 3.7 4.8 36 32.2 76.6 56.5 122 72.9 21.9 7.9 44.4 13.7 67.3 17.5 14 2.3 28 3.8 42.2 4.5 3 .1 6 .2 9 .4.7 0 1.4.2 2.1.3h17.7c.7-.1 1.4-.3 2.1-.3 14.9-.4 29.8-1.8 44.6-4 21.4-3.2 42.4-8.1 62.9-14.7 29.6-9.6 57.7-22.4 83.4-40.1 2.8-1.9 5.7-3.8 8-6.2 4.3-4.4 2.3-10.4-3.3-11.9zm50.4-27.7c-.8-4.2-4-5.8-7.6-7-5.7-1.9-11.6-2.8-17.6-3.3-11-.9-22-.4-32.8 1.6-12 2.2-23.4 6.1-33.5 13.1-1.2.8-2.4 1.8-3.1 3-.6.9-.7 2.3-.5 3.4.3 1.3 1.7 1.6 3 1.5.6 0 1.2 0 1.8-.1l19.5-2.1c9.6-.9 19.2-1.5 28.8-.8 4.1.3 8.1 1.2 12 2.2 4.3 1.1 6.2 4.4 6.4 8.7.3 6.7-1.2 13.1-2.9 19.5-3.5 12.9-8.3 25.4-13.3 37.8-.3.8-.7 1.7-.8 2.5-.4 2.5 1 4 3.4 3.5 1.4-.3 3-1.1 4-2.1 3.7-3.6 7.5-7.2 10.6-11.2 10.7-13.8 17-29.6 20.7-46.6.7-3 1.2-6.1 1.7-9.1.2-4.7.2-9.6.2-14.5z\"],\n    \"cc-amex\": [576, 512, [], \"f1f3\", \"M325.1 167.8c0-16.4-14.1-18.4-27.4-18.4l-39.1-.3v69.3H275v-25.1h18c18.4 0 14.5 10.3 14.8 25.1h16.6v-13.5c0-9.2-1.5-15.1-11-18.4 7.4-3 11.8-10.7 11.7-18.7zm-29.4 11.3H275v-15.3h21c5.1 0 10.7 1 10.7 7.4 0 6.6-5.3 7.9-11 7.9zM279 268.6h-52.7l-21 22.8-20.5-22.8h-66.5l-.1 69.3h65.4l21.3-23 20.4 23h32.2l.1-23.3c18.9 0 49.3 4.6 49.3-23.3 0-17.3-12.3-22.7-27.9-22.7zm-103.8 54.7h-40.6v-13.8h36.3v-14.1h-36.3v-12.5h41.7l17.9 20.2zm65.8 8.2l-25.3-28.1L241 276zm37.8-31h-21.2v-17.6h21.5c5.6 0 10.2 2.3 10.2 8.4 0 6.4-4.6 9.2-10.5 9.2zm-31.6-136.7v-14.6h-55.5v69.3h55.5v-14.3h-38.9v-13.8h37.8v-14.1h-37.8v-12.5zM576 255.4h-.2zm-194.6 31.9c0-16.4-14.1-18.7-27.1-18.7h-39.4l-.1 69.3h16.6l.1-25.3h17.6c11 0 14.8 2 14.8 13.8l-.1 11.5h16.6l.1-13.8c0-8.9-1.8-15.1-11-18.4 7.7-3.1 11.8-10.8 11.9-18.4zm-29.2 11.2h-20.7v-15.6h21c5.1 0 10.7 1 10.7 7.4 0 6.9-5.4 8.2-11 8.2zm-172.8-80v-69.3h-27.6l-19.7 47-21.7-47H83.3v65.7l-28.1-65.7H30.7L1 218.5h17.9l6.4-15.3h34.5l6.4 15.3H100v-54.2l24 54.2h14.6l24-54.2v54.2zM31.2 188.8l11.2-27.6 11.5 27.6zm477.4 158.9v-4.5c-10.8 5.6-3.9 4.5-156.7 4.5 0-25.2.1-23.9 0-25.2-1.7-.1-3.2-.1-9.4-.1 0 17.9-.1 6.8-.1 25.3h-39.6c0-12.1.1-15.3.1-29.2-10 6-22.8 6.4-34.3 6.2 0 14.7-.1 8.3-.1 23h-48.9c-5.1-5.7-2.7-3.1-15.4-17.4-3.2 3.5-12.8 13.9-16.1 17.4h-82v-92.3h83.1c5 5.6 2.8 3.1 15.5 17.2 3.2-3.5 12.2-13.4 15.7-17.2h58c9.8 0 18 1.9 24.3 5.6v-5.6c54.3 0 64.3-1.4 75.7 5.1v-5.1h78.2v5.2c11.4-6.9 19.6-5.2 64.9-5.2v5c10.3-5.9 16.6-5.2 54.3-5V80c0-26.5-21.5-48-48-48h-480c-26.5 0-48 21.5-48 48v109.8c9.4-21.9 19.7-46 23.1-53.9h39.7c4.3 10.1 1.6 3.7 9 21.1v-21.1h46c2.9 6.2 11.1 24 13.9 30 5.8-13.6 10.1-23.9 12.6-30h103c0-.1 11.5 0 11.6 0 43.7.2 53.6-.8 64.4 5.3v-5.3H363v9.3c7.6-6.1 17.9-9.3 30.7-9.3h27.6c0 .5 1.9.3 2.3.3H456c4.2 9.8 2.6 6 8.8 20.6v-20.6h43.3c4.9 8-1-1.8 11.2 18.4v-18.4h39.9v92h-41.6c-5.4-9-1.4-2.2-13.2-21.9v21.9h-52.8c-6.4-14.8-.1-.3-6.6-15.3h-19c-4.2 10-2.2 5.2-6.4 15.3h-26.8c-12.3 0-22.3-3-29.7-8.9v8.9h-66.5c-.3-13.9-.1-24.8-.1-24.8-1.8-.3-3.4-.2-9.8-.2v25.1H151.2v-11.4c-2.5 5.6-2.7 5.9-5.1 11.4h-29.5c-4-8.9-2.9-6.4-5.1-11.4v11.4H58.6c-4.2-10.1-2.2-5.3-6.4-15.3H33c-4.2 10-2.2 5.2-6.4 15.3H0V432c0 26.5 21.5 48 48 48h480.1c26.5 0 48-21.5 48-48v-90.4c-12.7 8.3-32.7 6.1-67.5 6.1zm36.3-64.5H575v-14.6h-32.9c-12.8 0-23.8 6.6-23.8 20.7 0 33 42.7 12.8 42.7 27.4 0 5.1-4.3 6.4-8.4 6.4h-32l-.1 14.8h32c8.4 0 17.6-1.8 22.5-8.9v-25.8c-10.5-13.8-39.3-1.3-39.3-13.5 0-5.8 4.6-6.5 9.2-6.5zm-57 39.8h-32.2l-.1 14.8h32.2c14.8 0 26.2-5.6 26.2-22 0-33.2-42.9-11.2-42.9-26.3 0-5.6 4.9-6.4 9.2-6.4h30.4v-14.6h-33.2c-12.8 0-23.5 6.6-23.5 20.7 0 33 42.7 12.5 42.7 27.4-.1 5.4-4.7 6.4-8.8 6.4zm-42.2-40.1v-14.3h-55.2l-.1 69.3h55.2l.1-14.3-38.6-.3v-13.8H445v-14.1h-37.8v-12.5zm-56.3-108.1c-.3.2-1.4 2.2-1.4 7.6 0 6 .9 7.7 1.1 7.9.2.1 1.1.5 3.4.5l7.3-16.9c-1.1 0-2.1-.1-3.1-.1-5.6 0-7 .7-7.3 1zm20.4-10.5h-.1zm-16.2-15.2c-23.5 0-34 12-34 35.3 0 22.2 10.2 34 33 34h19.2l6.4-15.3h34.3l6.6 15.3h33.7v-51.9l31.2 51.9h23.6v-69h-16.9v48.1l-29.1-48.1h-25.3v65.4l-27.9-65.4h-24.8l-23.5 54.5h-7.4c-13.3 0-16.1-8.1-16.1-19.9 0-23.8 15.7-20 33.1-19.7v-15.2zm42.1 12.1l11.2 27.6h-22.8zm-101.1-12v69.3h16.9v-69.3z\"],\n    \"cc-apple-pay\": [576, 512, [], \"f416\", \"M302.2 218.4c0 17.2-10.5 27.1-29 27.1h-24.3v-54.2h24.4c18.4 0 28.9 9.8 28.9 27.1zm47.5 62.6c0 8.3 7.2 13.7 18.5 13.7 14.4 0 25.2-9.1 25.2-21.9v-7.7l-23.5 1.5c-13.3.9-20.2 5.8-20.2 14.4zM576 79v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM127.8 197.2c8.4.7 16.8-4.2 22.1-10.4 5.2-6.4 8.6-15 7.7-23.7-7.4.3-16.6 4.9-21.9 11.3-4.8 5.5-8.9 14.4-7.9 22.8zm60.6 74.5c-.2-.2-19.6-7.6-19.8-30-.2-18.7 15.3-27.7 16-28.2-8.8-13-22.4-14.4-27.1-14.7-12.2-.7-22.6 6.9-28.4 6.9-5.9 0-14.7-6.6-24.3-6.4-12.5.2-24.2 7.3-30.5 18.6-13.1 22.6-3.4 56 9.3 74.4 6.2 9.1 13.7 19.1 23.5 18.7 9.3-.4 13-6 24.2-6 11.3 0 14.5 6 24.3 5.9 10.2-.2 16.5-9.1 22.8-18.2 6.9-10.4 9.8-20.4 10-21zm135.4-53.4c0-26.6-18.5-44.8-44.9-44.8h-51.2v136.4h21.2v-46.6h29.3c26.8 0 45.6-18.4 45.6-45zm90 23.7c0-19.7-15.8-32.4-40-32.4-22.5 0-39.1 12.9-39.7 30.5h19.1c1.6-8.4 9.4-13.9 20-13.9 13 0 20.2 6 20.2 17.2v7.5l-26.4 1.6c-24.6 1.5-37.9 11.6-37.9 29.1 0 17.7 13.7 29.4 33.4 29.4 13.3 0 25.6-6.7 31.2-17.4h.4V310h19.6v-68zM516 210.9h-21.5l-24.9 80.6h-.4l-24.9-80.6H422l35.9 99.3-1.9 6c-3.2 10.2-8.5 14.2-17.9 14.2-1.7 0-4.9-.2-6.2-.3v16.4c1.2.4 6.5.5 8.1.5 20.7 0 30.4-7.9 38.9-31.8L516 210.9z\"],\n    \"cc-diners-club\": [576, 512, [], \"f24c\", \"M239.7 79.9c-96.9 0-175.8 78.6-175.8 175.8 0 96.9 78.9 175.8 175.8 175.8 97.2 0 175.8-78.9 175.8-175.8 0-97.2-78.6-175.8-175.8-175.8zm-39.9 279.6c-41.7-15.9-71.4-56.4-71.4-103.8s29.7-87.9 71.4-104.1v207.9zm79.8.3V151.6c41.7 16.2 71.4 56.7 71.4 104.1s-29.7 87.9-71.4 104.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM329.7 448h-90.3c-106.2 0-193.8-85.5-193.8-190.2C45.6 143.2 133.2 64 239.4 64h90.3c105 0 200.7 79.2 200.7 193.8 0 104.7-95.7 190.2-200.7 190.2z\"],\n    \"cc-discover\": [576, 512, [], \"f1f2\", \"M520.4 196.1c0-7.9-5.5-12.1-15.6-12.1h-4.9v24.9h4.7c10.3 0 15.8-4.4 15.8-12.8zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-44.1 138.9c22.6 0 52.9-4.1 52.9 24.4 0 12.6-6.6 20.7-18.7 23.2l25.8 34.4h-19.6l-22.2-32.8h-2.2v32.8h-16zm-55.9.1h45.3v14H444v18.2h28.3V217H444v22.2h29.3V253H428zm-68.7 0l21.9 55.2 22.2-55.2h17.5l-35.5 84.2h-8.6l-35-84.2zm-55.9-3c24.7 0 44.6 20 44.6 44.6 0 24.7-20 44.6-44.6 44.6-24.7 0-44.6-20-44.6-44.6 0-24.7 20-44.6 44.6-44.6zm-49.3 6.1v19c-20.1-20.1-46.8-4.7-46.8 19 0 25 27.5 38.5 46.8 19.2v19c-29.7 14.3-63.3-5.7-63.3-38.2 0-31.2 33.1-53 63.3-38zm-97.2 66.3c11.4 0 22.4-15.3-3.3-24.4-15-5.5-20.2-11.4-20.2-22.7 0-23.2 30.6-31.4 49.7-14.3l-8.4 10.8c-10.4-11.6-24.9-6.2-24.9 2.5 0 4.4 2.7 6.9 12.3 10.3 18.2 6.6 23.6 12.5 23.6 25.6 0 29.5-38.8 37.4-56.6 11.3l10.3-9.9c3.7 7.1 9.9 10.8 17.5 10.8zM55.4 253H32v-82h23.4c26.1 0 44.1 17 44.1 41.1 0 18.5-13.2 40.9-44.1 40.9zm67.5 0h-16v-82h16zM544 433c0 8.2-6.8 15-15 15H128c189.6-35.6 382.7-139.2 416-160zM74.1 191.6c-5.2-4.9-11.6-6.6-21.9-6.6H48v54.2h4.2c10.3 0 17-2 21.9-6.4 5.7-5.2 8.9-12.8 8.9-20.7s-3.2-15.5-8.9-20.5z\"],\n    \"cc-jcb\": [576, 512, [], \"f24b\", \"M431.5 244.3V212c41.2 0 38.5.2 38.5.2 7.3 1.3 13.3 7.3 13.3 16 0 8.8-6 14.5-13.3 15.8-1.2.4-3.3.3-38.5.3zm42.8 20.2c-2.8-.7-3.3-.5-42.8-.5v35c39.6 0 40 .2 42.8-.5 7.5-1.5 13.5-8 13.5-17 0-8.7-6-15.5-13.5-17zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM182 192.3h-57c0 67.1 10.7 109.7-35.8 109.7-19.5 0-38.8-5.7-57.2-14.8v28c30 8.3 68 8.3 68 8.3 97.9 0 82-47.7 82-131.2zm178.5 4.5c-63.4-16-165-14.9-165 59.3 0 77.1 108.2 73.6 165 59.2V287C312.9 311.7 253 309 253 256s59.8-55.6 107.5-31.2v-28zM544 286.5c0-18.5-16.5-30.5-38-32v-.8c19.5-2.7 30.3-15.5 30.3-30.2 0-19-15.7-30-37-31 0 0 6.3-.3-120.3-.3v127.5h122.7c24.3.1 42.3-12.9 42.3-33.2z\"],\n    \"cc-mastercard\": [576, 512, [], \"f1f1\", \"M482.9 410.3c0 6.8-4.6 11.7-11.2 11.7-6.8 0-11.2-5.2-11.2-11.7 0-6.5 4.4-11.7 11.2-11.7 6.6 0 11.2 5.2 11.2 11.7zm-310.8-11.7c-7.1 0-11.2 5.2-11.2 11.7 0 6.5 4.1 11.7 11.2 11.7 6.5 0 10.9-4.9 10.9-11.7-.1-6.5-4.4-11.7-10.9-11.7zm117.5-.3c-5.4 0-8.7 3.5-9.5 8.7h19.1c-.9-5.7-4.4-8.7-9.6-8.7zm107.8.3c-6.8 0-10.9 5.2-10.9 11.7 0 6.5 4.1 11.7 10.9 11.7 6.8 0 11.2-4.9 11.2-11.7 0-6.5-4.4-11.7-11.2-11.7zm105.9 26.1c0 .3.3.5.3 1.1 0 .3-.3.5-.3 1.1-.3.3-.3.5-.5.8-.3.3-.5.5-1.1.5-.3.3-.5.3-1.1.3-.3 0-.5 0-1.1-.3-.3 0-.5-.3-.8-.5-.3-.3-.5-.5-.5-.8-.3-.5-.3-.8-.3-1.1 0-.5 0-.8.3-1.1 0-.5.3-.8.5-1.1.3-.3.5-.3.8-.5.5-.3.8-.3 1.1-.3.5 0 .8 0 1.1.3.5.3.8.3 1.1.5s.2.6.5 1.1zm-2.2 1.4c.5 0 .5-.3.8-.3.3-.3.3-.5.3-.8 0-.3 0-.5-.3-.8-.3 0-.5-.3-1.1-.3h-1.6v3.5h.8V426h.3l1.1 1.4h.8l-1.1-1.3zM576 81v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V81c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM64 220.6c0 76.5 62.1 138.5 138.5 138.5 27.2 0 53.9-8.2 76.5-23.1-72.9-59.3-72.4-171.2 0-230.5-22.6-15-49.3-23.1-76.5-23.1-76.4-.1-138.5 62-138.5 138.2zm224 108.8c70.5-55 70.2-162.2 0-217.5-70.2 55.3-70.5 162.6 0 217.5zm-142.3 76.3c0-8.7-5.7-14.4-14.7-14.7-4.6 0-9.5 1.4-12.8 6.5-2.4-4.1-6.5-6.5-12.2-6.5-3.8 0-7.6 1.4-10.6 5.4V392h-8.2v36.7h8.2c0-18.9-2.5-30.2 9-30.2 10.2 0 8.2 10.2 8.2 30.2h7.9c0-18.3-2.5-30.2 9-30.2 10.2 0 8.2 10 8.2 30.2h8.2v-23zm44.9-13.7h-7.9v4.4c-2.7-3.3-6.5-5.4-11.7-5.4-10.3 0-18.2 8.2-18.2 19.3 0 11.2 7.9 19.3 18.2 19.3 5.2 0 9-1.9 11.7-5.4v4.6h7.9V392zm40.5 25.6c0-15-22.9-8.2-22.9-15.2 0-5.7 11.9-4.8 18.5-1.1l3.3-6.5c-9.4-6.1-30.2-6-30.2 8.2 0 14.3 22.9 8.3 22.9 15 0 6.3-13.5 5.8-20.7.8l-3.5 6.3c11.2 7.6 32.6 6 32.6-7.5zm35.4 9.3l-2.2-6.8c-3.8 2.1-12.2 4.4-12.2-4.1v-16.6h13.1V392h-13.1v-11.2h-8.2V392h-7.6v7.3h7.6V416c0 17.6 17.3 14.4 22.6 10.9zm13.3-13.4h27.5c0-16.2-7.4-22.6-17.4-22.6-10.6 0-18.2 7.9-18.2 19.3 0 20.5 22.6 23.9 33.8 14.2l-3.8-6c-7.8 6.4-19.6 5.8-21.9-4.9zm59.1-21.5c-4.6-2-11.6-1.8-15.2 4.4V392h-8.2v36.7h8.2V408c0-11.6 9.5-10.1 12.8-8.4l2.4-7.6zm10.6 18.3c0-11.4 11.6-15.1 20.7-8.4l3.8-6.5c-11.6-9.1-32.7-4.1-32.7 15 0 19.8 22.4 23.8 32.7 15l-3.8-6.5c-9.2 6.5-20.7 2.6-20.7-8.6zm66.7-18.3H408v4.4c-8.3-11-29.9-4.8-29.9 13.9 0 19.2 22.4 24.7 29.9 13.9v4.6h8.2V392zm33.7 0c-2.4-1.2-11-2.9-15.2 4.4V392h-7.9v36.7h7.9V408c0-11 9-10.3 12.8-8.4l2.4-7.6zm40.3-14.9h-7.9v19.3c-8.2-10.9-29.9-5.1-29.9 13.9 0 19.4 22.5 24.6 29.9 13.9v4.6h7.9v-51.7zm7.6-75.1v4.6h.8V302h1.9v-.8h-4.6v.8h1.9zm6.6 123.8c0-.5 0-1.1-.3-1.6-.3-.3-.5-.8-.8-1.1-.3-.3-.8-.5-1.1-.8-.5 0-1.1-.3-1.6-.3-.3 0-.8.3-1.4.3-.5.3-.8.5-1.1.8-.5.3-.8.8-.8 1.1-.3.5-.3 1.1-.3 1.6 0 .3 0 .8.3 1.4 0 .3.3.8.8 1.1.3.3.5.5 1.1.8.5.3 1.1.3 1.4.3.5 0 1.1 0 1.6-.3.3-.3.8-.5 1.1-.8.3-.3.5-.8.8-1.1.3-.6.3-1.1.3-1.4zm3.2-124.7h-1.4l-1.6 3.5-1.6-3.5h-1.4v5.4h.8v-4.1l1.6 3.5h1.1l1.4-3.5v4.1h1.1v-5.4zm4.4-80.5c0-76.2-62.1-138.3-138.5-138.3-27.2 0-53.9 8.2-76.5 23.1 72.1 59.3 73.2 171.5 0 230.5 22.6 15 49.5 23.1 76.5 23.1 76.4.1 138.5-61.9 138.5-138.4z\"],\n    \"cc-paypal\": [576, 512, [], \"f1f4\", \"M186.3 258.2c0 12.2-9.7 21.5-22 21.5-9.2 0-16-5.2-16-15 0-12.2 9.5-22 21.7-22 9.3 0 16.3 5.7 16.3 15.5zM80.5 209.7h-4.7c-1.5 0-3 1-3.2 2.7l-4.3 26.7 8.2-.3c11 0 19.5-1.5 21.5-14.2 2.3-13.4-6.2-14.9-17.5-14.9zm284 0H360c-1.8 0-3 1-3.2 2.7l-4.2 26.7 8-.3c13 0 22-3 22-18-.1-10.6-9.6-11.1-18.1-11.1zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM128.3 215.4c0-21-16.2-28-34.7-28h-40c-2.5 0-5 2-5.2 4.7L32 294.2c-.3 2 1.2 4 3.2 4h19c2.7 0 5.2-2.9 5.5-5.7l4.5-26.6c1-7.2 13.2-4.7 18-4.7 28.6 0 46.1-17 46.1-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.2 8.2-5.8-8.5-14.2-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9 0 20.2-4.9 26.5-11.9-.5 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H200c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm40.5 97.9l63.7-92.6c.5-.5.5-1 .5-1.7 0-1.7-1.5-3.5-3.2-3.5h-19.2c-1.7 0-3.5 1-4.5 2.5l-26.5 39-11-37.5c-.8-2.2-3-4-5.5-4h-18.7c-1.7 0-3.2 1.8-3.2 3.5 0 1.2 19.5 56.8 21.2 62.1-2.7 3.8-20.5 28.6-20.5 31.6 0 1.8 1.5 3.2 3.2 3.2h19.2c1.8-.1 3.5-1.1 4.5-2.6zm159.3-106.7c0-21-16.2-28-34.7-28h-39.7c-2.7 0-5.2 2-5.5 4.7l-16.2 102c-.2 2 1.3 4 3.2 4h20.5c2 0 3.5-1.5 4-3.2l4.5-29c1-7.2 13.2-4.7 18-4.7 28.4 0 45.9-17 45.9-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.3 8.2-5.5-8.5-14-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9.3 0 20.5-4.9 26.5-11.9-.3 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H484c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm47.5-33.3c0-2-1.5-3.5-3.2-3.5h-18.5c-1.5 0-3 1.2-3.2 2.7l-16.2 104-.3.5c0 1.8 1.5 3.5 3.5 3.5h16.5c2.5 0 5-2.9 5.2-5.7L544 191.2v-.3zm-90 51.8c-12.2 0-21.7 9.7-21.7 22 0 9.7 7 15 16.2 15 12 0 21.7-9.2 21.7-21.5.1-9.8-6.9-15.5-16.2-15.5z\"],\n    \"cc-stripe\": [576, 512, [], \"f1f5\", \"M492.4 220.8c-8.9 0-18.7 6.7-18.7 22.7h36.7c0-16-9.3-22.7-18-22.7zM375 223.4c-8.2 0-13.3 2.9-17 7l.2 52.8c3.5 3.7 8.5 6.7 16.8 6.7 13.1 0 21.9-14.3 21.9-33.4 0-18.6-9-33.2-21.9-33.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM122.2 281.1c0 25.6-20.3 40.1-49.9 40.3-12.2 0-25.6-2.4-38.8-8.1v-33.9c12 6.4 27.1 11.3 38.9 11.3 7.9 0 13.6-2.1 13.6-8.7 0-17-54-10.6-54-49.9 0-25.2 19.2-40.2 48-40.2 11.8 0 23.5 1.8 35.3 6.5v33.4c-10.8-5.8-24.5-9.1-35.3-9.1-7.5 0-12.1 2.2-12.1 7.7 0 16 54.3 8.4 54.3 50.7zm68.8-56.6h-27V275c0 20.9 22.5 14.4 27 12.6v28.9c-4.7 2.6-13.3 4.7-24.9 4.7-21.1 0-36.9-15.5-36.9-36.5l.2-113.9 34.7-7.4v30.8H191zm74 2.4c-4.5-1.5-18.7-3.6-27.1 7.4v84.4h-35.5V194.2h30.7l2.2 10.5c8.3-15.3 24.9-12.2 29.6-10.5h.1zm44.1 91.8h-35.7V194.2h35.7zm0-142.9l-35.7 7.6v-28.9l35.7-7.6zm74.1 145.5c-12.4 0-20-5.3-25.1-9l-.1 40.2-35.5 7.5V194.2h31.3l1.8 8.8c4.9-4.5 13.9-11.1 27.8-11.1 24.9 0 48.4 22.5 48.4 63.8 0 45.1-23.2 65.5-48.6 65.6zm160.4-51.5h-69.5c1.6 16.6 13.8 21.5 27.6 21.5 14.1 0 25.2-3 34.9-7.9V312c-9.7 5.3-22.4 9.2-39.4 9.2-34.6 0-58.8-21.7-58.8-64.5 0-36.2 20.5-64.9 54.3-64.9 33.7 0 51.3 28.7 51.3 65.1 0 3.5-.3 10.9-.4 12.9z\"],\n    \"cc-visa\": [576, 512, [], \"f1f0\", \"M470.1 231.3s7.6 37.2 9.3 45H446c3.3-8.9 16-43.5 16-43.5-.2.3 3.3-9.1 5.3-14.9l2.8 13.4zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM152.5 331.2L215.7 176h-42.5l-39.3 106-4.3-21.5-14-71.4c-2.3-9.9-9.4-12.7-18.2-13.1H32.7l-.7 3.1c15.8 4 29.9 9.8 42.2 17.1l35.8 135h42.5zm94.4.2L272.1 176h-40.2l-25.1 155.4h40.1zm139.9-50.8c.2-17.7-10.6-31.2-33.7-42.3-14.1-7.1-22.7-11.9-22.7-19.2.2-6.6 7.3-13.4 23.1-13.4 13.1-.3 22.7 2.8 29.9 5.9l3.6 1.7 5.5-33.6c-7.9-3.1-20.5-6.6-36-6.6-39.7 0-67.6 21.2-67.8 51.4-.3 22.3 20 34.7 35.2 42.2 15.5 7.6 20.8 12.6 20.8 19.3-.2 10.4-12.6 15.2-24.1 15.2-16 0-24.6-2.5-37.7-8.3l-5.3-2.5-5.6 34.9c9.4 4.3 26.8 8.1 44.8 8.3 42.2.1 69.7-20.8 70-53zM528 331.4L495.6 176h-31.1c-9.6 0-16.9 2.8-21 12.9l-59.7 142.5H426s6.9-19.2 8.4-23.3H486c1.2 5.5 4.8 23.3 4.8 23.3H528z\"],\n    \"centercode\": [512, 512, [], \"f380\", \"M329.2 268.6c-3.8 35.2-35.4 60.6-70.6 56.8-35.2-3.8-60.6-35.4-56.8-70.6 3.8-35.2 35.4-60.6 70.6-56.8 35.1 3.8 60.6 35.4 56.8 70.6zm-85.8 235.1C96.7 496-8.2 365.5 10.1 224.3c11.2-86.6 65.8-156.9 139.1-192 161-77.1 349.7 37.4 354.7 216.6 4.1 147-118.4 262.2-260.5 254.8zm179.9-180c27.9-118-160.5-205.9-237.2-234.2-57.5 56.3-69.1 188.6-33.8 344.4 68.8 15.8 169.1-26.4 271-110.2z\"],\n    \"centos\": [448, 512, [], \"f789\", \"M289.6 97.5l31.6 31.7-76.3 76.5V97.5zm-162.4 31.7l76.3 76.5V97.5h-44.7zm41.5-41.6h44.7v127.9l10.8 10.8 10.8-10.8V87.6h44.7L224.2 32zm26.2 168.1l-10.8-10.8H55.5v-44.8L0 255.7l55.5 55.6v-44.8h128.6l10.8-10.8zm79.3-20.7h107.9v-44.8l-31.6-31.7zm173.3 20.7L392 200.1v44.8H264.3l-10.8 10.8 10.8 10.8H392v44.8l55.5-55.6zM65.4 176.2l32.5-31.7 90.3 90.5h15.3v-15.3l-90.3-90.5 31.6-31.7H65.4zm316.7-78.7h-78.5l31.6 31.7-90.3 90.5V235h15.3l90.3-90.5 31.6 31.7zM203.5 413.9V305.8l-76.3 76.5 31.6 31.7h44.7zM65.4 235h108.8l-76.3-76.5-32.5 31.7zm316.7 100.2l-31.6 31.7-90.3-90.5h-15.3v15.3l90.3 90.5-31.6 31.7h78.5zm0-58.8H274.2l76.3 76.5 31.6-31.7zm-60.9 105.8l-76.3-76.5v108.1h44.7zM97.9 352.9l76.3-76.5H65.4v44.8zm181.8 70.9H235V295.9l-10.8-10.8-10.8 10.8v127.9h-44.7l55.5 55.6zm-166.5-41.6l90.3-90.5v-15.3h-15.3l-90.3 90.5-32.5-31.7v78.7h79.4z\"],\n    \"chrome\": [496, 512, [], \"f268\", \"M131.5 217.5L55.1 100.1c47.6-59.2 119-91.8 192-92.1 42.3-.3 85.5 10.5 124.8 33.2 43.4 25.2 76.4 61.4 97.4 103L264 133.4c-58.1-3.4-113.4 29.3-132.5 84.1zm32.9 38.5c0 46.2 37.4 83.6 83.6 83.6s83.6-37.4 83.6-83.6-37.4-83.6-83.6-83.6-83.6 37.3-83.6 83.6zm314.9-89.2L339.6 174c37.9 44.3 38.5 108.2 6.6 157.2L234.1 503.6c46.5 2.5 94.4-7.7 137.8-32.9 107.4-62 150.9-192 107.4-303.9zM133.7 303.6L40.4 120.1C14.9 159.1 0 205.9 0 256c0 124 90.8 226.7 209.5 244.9l63.7-124.8c-57.6 10.8-113.2-20.8-139.5-72.5z\"],\n    \"chromecast\": [512, 512, [], \"f838\", \"M447.83 64H64a42.72 42.72 0 0 0-42.72 42.72v63.92H64v-63.92h383.83v298.56H298.64V448H448a42.72 42.72 0 0 0 42.72-42.72V106.72A42.72 42.72 0 0 0 448 64zM21.28 383.58v63.92h63.91a63.91 63.91 0 0 0-63.91-63.92zm0-85.28V341a106.63 106.63 0 0 1 106.64 106.66v.34h42.72a149.19 149.19 0 0 0-149-149.36h-.33zm0-85.27v42.72c106-.1 192 85.75 192.08 191.75v.5h42.72c-.46-129.46-105.34-234.27-234.8-234.64z\"],\n    \"cloudscale\": [448, 512, [], \"f383\", \"M318.1 154l-9.4 7.6c-22.5-19.3-51.5-33.6-83.3-33.6C153.8 128 96 188.8 96 260.3c0 6.6.4 13.1 1.4 19.4-2-56 41.8-97.4 92.6-97.4 24.2 0 46.2 9.4 62.6 24.7l-25.2 20.4c-8.3-.9-16.8 1.8-23.1 8.1-11.1 11-11.1 28.9 0 40 11.1 11 28.9 11 40 0 6.3-6.3 9-14.9 8.1-23.1l75.2-88.8c6.3-6.5-3.3-15.9-9.5-9.6zm-83.8 111.5c-5.6 5.5-14.6 5.5-20.2 0-5.6-5.6-5.6-14.6 0-20.2s14.6-5.6 20.2 0 5.6 14.7 0 20.2zM224 32C100.5 32 0 132.5 0 256s100.5 224 224 224 224-100.5 224-224S347.5 32 224 32zm0 384c-88.2 0-160-71.8-160-160S135.8 96 224 96s160 71.8 160 160-71.8 160-160 160z\"],\n    \"cloudsmith\": [332, 512, [], \"f384\", \"M332.5 419.9c0 46.4-37.6 84.1-84 84.1s-84-37.7-84-84.1 37.6-84 84-84 84 37.6 84 84zm-84-243.9c46.4 0 80-37.6 80-84s-33.6-84-80-84-88 37.6-88 84-29.6 76-76 76-84 41.6-84 88 37.6 80 84 80 84-33.6 84-80 33.6-80 80-80z\"],\n    \"cloudversify\": [616, 512, [], \"f385\", \"M148.6 304c8.2 68.5 67.4 115.5 146 111.3 51.2 43.3 136.8 45.8 186.4-5.6 69.2 1.1 118.5-44.6 131.5-99.5 14.8-62.5-18.2-132.5-92.1-155.1-33-88.1-131.4-101.5-186.5-85-57.3 17.3-84.3 53.2-99.3 109.7-7.8 2.7-26.5 8.9-45 24.1 11.7 0 15.2 8.9 15.2 19.5v20.4c0 10.7-8.7 19.5-19.5 19.5h-20.2c-10.7 0-19.5-6-19.5-16.7V240H98.8C95 240 88 244.3 88 251.9v40.4c0 6.4 5.3 11.8 11.7 11.8h48.9zm227.4 8c-10.7 46.3 21.7 72.4 55.3 86.8C324.1 432.6 259.7 348 296 288c-33.2 21.6-33.7 71.2-29.2 92.9-17.9-12.4-53.8-32.4-57.4-79.8-3-39.9 21.5-75.7 57-93.9C297 191.4 369.9 198.7 400 248c-14.1-48-53.8-70.1-101.8-74.8 30.9-30.7 64.4-50.3 114.2-43.7 69.8 9.3 133.2 82.8 67.7 150.5 35-16.3 48.7-54.4 47.5-76.9l10.5 19.6c11.8 22 15.2 47.6 9.4 72-9.2 39-40.6 68.8-79.7 76.5-32.1 6.3-83.1-5.1-91.8-59.2zM128 208H88.2c-8.9 0-16.2-7.3-16.2-16.2v-39.6c0-8.9 7.3-16.2 16.2-16.2H128c8.9 0 16.2 7.3 16.2 16.2v39.6c0 8.9-7.3 16.2-16.2 16.2zM10.1 168C4.5 168 0 163.5 0 157.9v-27.8c0-5.6 4.5-10.1 10.1-10.1h27.7c5.5 0 10.1 4.5 10.1 10.1v27.8c0 5.6-4.5 10.1-10.1 10.1H10.1zM168 142.7v-21.4c0-5.1 4.2-9.3 9.3-9.3h21.4c5.1 0 9.3 4.2 9.3 9.3v21.4c0 5.1-4.2 9.3-9.3 9.3h-21.4c-5.1 0-9.3-4.2-9.3-9.3zM56 235.5v25c0 6.3-5.1 11.5-11.4 11.5H19.4C13.1 272 8 266.8 8 260.5v-25c0-6.3 5.1-11.5 11.4-11.5h25.1c6.4 0 11.5 5.2 11.5 11.5z\"],\n    \"codepen\": [512, 512, [], \"f1cb\", \"M502.285 159.704l-234-156c-7.987-4.915-16.511-4.96-24.571 0l-234 156C3.714 163.703 0 170.847 0 177.989v155.999c0 7.143 3.714 14.286 9.715 18.286l234 156.022c7.987 4.915 16.511 4.96 24.571 0l234-156.022c6-3.999 9.715-11.143 9.715-18.286V177.989c-.001-7.142-3.715-14.286-9.716-18.285zM278 63.131l172.286 114.858-76.857 51.429L278 165.703V63.131zm-44 0v102.572l-95.429 63.715-76.857-51.429L234 63.131zM44 219.132l55.143 36.857L44 292.846v-73.714zm190 229.715L61.714 333.989l76.857-51.429L234 346.275v102.572zm22-140.858l-77.715-52 77.715-52 77.715 52-77.715 52zm22 140.858V346.275l95.429-63.715 76.857 51.429L278 448.847zm190-156.001l-55.143-36.857L468 219.132v73.714z\"],\n    \"codiepie\": [472, 512, [], \"f284\", \"M422.5 202.9c30.7 0 33.5 53.1-.3 53.1h-10.8v44.3h-26.6v-97.4h37.7zM472 352.6C429.9 444.5 350.4 504 248 504 111 504 0 393 0 256S111 8 248 8c97.4 0 172.8 53.7 218.2 138.4l-186 108.8L472 352.6zm-38.5 12.5l-60.3-30.7c-27.1 44.3-70.4 71.4-122.4 71.4-82.5 0-149.2-66.7-149.2-148.9 0-82.5 66.7-149.2 149.2-149.2 48.4 0 88.9 23.5 116.9 63.4l59.5-34.6c-40.7-62.6-104.7-100-179.2-100-121.2 0-219.5 98.3-219.5 219.5S126.8 475.5 248 475.5c78.6 0 146.5-42.1 185.5-110.4z\"],\n    \"confluence\": [512, 512, [], \"f78d\", \"M2.3 412.2c-4.5 7.6-2.1 17.5 5.5 22.2l105.9 65.2c7.7 4.7 17.7 2.4 22.4-5.3 0-.1.1-.2.1-.2 67.1-112.2 80.5-95.9 280.9-.7 8.1 3.9 17.8.4 21.7-7.7.1-.1.1-.3.2-.4l50.4-114.1c3.6-8.1-.1-17.6-8.1-21.3-22.2-10.4-66.2-31.2-105.9-50.3C127.5 179 44.6 345.3 2.3 412.2zm507.4-312.1c4.5-7.6 2.1-17.5-5.5-22.2L398.4 12.8c-7.5-5-17.6-3.1-22.6 4.4-.2.3-.4.6-.6 1-67.3 112.6-81.1 95.6-280.6.9-8.1-3.9-17.8-.4-21.7 7.7-.1.1-.1.3-.2.4L22.2 141.3c-3.6 8.1.1 17.6 8.1 21.3 22.2 10.4 66.3 31.2 106 50.4 248 120 330.8-45.4 373.4-112.9z\"],\n    \"connectdevelop\": [576, 512, [], \"f20e\", \"M550.5 241l-50.089-86.786c1.071-2.142 1.875-4.553 1.875-7.232 0-8.036-6.696-14.733-14.732-15.001l-55.447-95.893c.536-1.607 1.071-3.214 1.071-4.821 0-8.571-6.964-15.268-15.268-15.268-4.821 0-8.839 2.143-11.786 5.625H299.518C296.839 18.143 292.821 16 288 16s-8.839 2.143-11.518 5.625H170.411C167.464 18.143 163.447 16 158.625 16c-8.303 0-15.268 6.696-15.268 15.268 0 1.607.536 3.482 1.072 4.821l-55.983 97.233c-5.356 2.41-9.107 7.5-9.107 13.661 0 .535.268 1.071.268 1.607l-53.304 92.143c-7.232 1.339-12.59 7.5-12.59 15 0 7.232 5.089 13.393 12.054 15l55.179 95.358c-.536 1.607-.804 2.946-.804 4.821 0 7.232 5.089 13.393 12.054 14.732l51.697 89.732c-.536 1.607-1.071 3.482-1.071 5.357 0 8.571 6.964 15.268 15.268 15.268 4.821 0 8.839-2.143 11.518-5.357h106.875C279.161 493.857 283.447 496 288 496s8.839-2.143 11.518-5.357h107.143c2.678 2.946 6.696 4.821 10.982 4.821 8.571 0 15.268-6.964 15.268-15.268 0-1.607-.267-2.946-.803-4.285l51.697-90.268c6.964-1.339 12.054-7.5 12.054-14.732 0-1.607-.268-3.214-.804-4.821l54.911-95.358c6.964-1.339 12.322-7.5 12.322-15-.002-7.232-5.092-13.393-11.788-14.732zM153.535 450.732l-43.66-75.803h43.66v75.803zm0-83.839h-43.66c-.268-1.071-.804-2.142-1.339-3.214l44.999-47.41v50.624zm0-62.411l-50.357 53.304c-1.339-.536-2.679-1.34-4.018-1.607L43.447 259.75c.535-1.339.535-2.679.535-4.018s0-2.41-.268-3.482l51.965-90c2.679-.268 5.357-1.072 7.768-2.679l50.089 51.965v92.946zm0-102.322l-45.803-47.41c1.339-2.143 2.143-4.821 2.143-7.767 0-.268-.268-.804-.268-1.072l43.928-15.804v72.053zm0-80.625l-43.66 15.804 43.66-75.536v59.732zm326.519 39.108l.804 1.339L445.5 329.125l-63.75-67.232 98.036-101.518.268.268zM291.75 355.107l11.518 11.786H280.5l11.25-11.786zm-.268-11.25l-83.303-85.446 79.553-84.375 83.036 87.589-79.286 82.232zm5.357 5.893l79.286-82.232 67.5 71.25-5.892 28.125H313.714l-16.875-17.143zM410.411 44.393c1.071.536 2.142 1.072 3.482 1.34l57.857 100.714v.536c0 2.946.803 5.624 2.143 7.767L376.393 256l-83.035-87.589L410.411 44.393zm-9.107-2.143L287.732 162.518l-57.054-60.268 166.339-60h4.287zm-123.483 0c2.678 2.678 6.16 4.285 10.179 4.285s7.5-1.607 10.179-4.285h75L224.786 95.821 173.893 42.25h103.928zm-116.249 5.625l1.071-2.142a33.834 33.834 0 0 0 2.679-.804l51.161 53.84-54.911 19.821V47.875zm0 79.286l60.803-21.964 59.732 63.214-79.553 84.107-40.982-42.053v-83.304zm0 92.678L198 257.607l-36.428 38.304v-76.072zm0 87.858l42.053-44.464 82.768 85.982-17.143 17.678H161.572v-59.196zm6.964 162.053c-1.607-1.607-3.482-2.678-5.893-3.482l-1.071-1.607v-89.732h99.91l-91.607 94.821h-1.339zm129.911 0c-2.679-2.41-6.428-4.285-10.447-4.285s-7.767 1.875-10.447 4.285h-96.429l91.607-94.821h38.304l91.607 94.821H298.447zm120-11.786l-4.286 7.5c-1.339.268-2.41.803-3.482 1.339l-89.196-91.875h114.376l-17.412 83.036zm12.856-22.232l12.858-60.803h21.964l-34.822 60.803zm34.822-68.839h-20.357l4.553-21.16 17.143 18.214c-.535.803-1.071 1.874-1.339 2.946zm66.161-107.411l-55.447 96.697c-1.339.535-2.679 1.071-4.018 1.874l-20.625-21.964 34.554-163.928 45.803 79.286c-.267 1.339-.803 2.678-.803 4.285 0 1.339.268 2.411.536 3.75z\"],\n    \"contao\": [512, 512, [], \"f26d\", \"M45.4 305c14.4 67.1 26.4 129 68.2 175H34c-18.7 0-34-15.2-34-34V66c0-18.7 15.2-34 34-34h57.7C77.9 44.6 65.6 59.2 54.8 75.6c-45.4 70-27 146.8-9.4 229.4zM478 32h-90.2c21.4 21.4 39.2 49.5 52.7 84.1l-137.1 29.3c-14.9-29-37.8-53.3-82.6-43.9-24.6 5.3-41 19.3-48.3 34.6-8.8 18.7-13.2 39.8 8.2 140.3 21.1 100.2 33.7 117.7 49.5 131.2 12.9 11.1 33.4 17 58.3 11.7 44.5-9.4 55.7-40.7 57.4-73.2l137.4-29.6c3.2 71.5-18.7 125.2-57.4 163.6H478c18.7 0 34-15.2 34-34V66c0-18.8-15.2-34-34-34z\"],\n    \"cotton-bureau\": [512, 512, [], \"f89e\", \"M474.31 330.41c-23.66 91.85-94.23 144.59-201.9 148.35V429.6c0-48 26.41-74.39 74.39-74.39 62 0 99.2-37.2 99.2-99.21 0-61.37-36.53-98.28-97.38-99.06-33-69.32-146.5-64.65-177.24 0C110.52 157.72 74 194.63 74 256c0 62.13 37.27 99.41 99.4 99.41 48 0 74.55 26.23 74.55 74.39V479c-134.43-5-211.1-85.07-211.1-223 0-141.82 81.35-223.2 223.2-223.2 114.77 0 189.84 53.2 214.69 148.81H500C473.88 71.51 388.22 8 259.82 8 105 8 12 101.19 12 255.82 12 411.14 105.19 504.34 259.82 504c128.27 0 213.87-63.81 239.67-173.59zM357 182.33c41.37 3.45 64.2 29 64.2 73.67 0 48-26.43 74.41-74.4 74.41-28.61 0-49.33-9.59-61.59-27.33 83.06-16.55 75.59-99.67 71.79-120.75zm-81.68 97.36c-2.46-10.34-16.33-87 56.23-97 2.27 10.09 16.52 87.11-56.26 97zM260 132c28.61 0 49 9.67 61.44 27.61-28.36 5.48-49.36 20.59-61.59 43.45-12.23-22.86-33.23-38-61.6-43.45 12.41-17.69 33.27-27.35 61.57-27.35zm-71.52 50.72c73.17 10.57 58.91 86.81 56.49 97-72.41-9.84-59-86.95-56.25-97zM173.2 330.41c-48 0-74.4-26.4-74.4-74.41 0-44.36 22.86-70 64.22-73.67-6.75 37.2-1.38 106.53 71.65 120.75-12.14 17.63-32.84 27.3-61.14 27.3zm53.21 12.39A80.8 80.8 0 0 0 260 309.25c7.77 14.49 19.33 25.54 33.82 33.55a80.28 80.28 0 0 0-33.58 33.83c-8-14.5-19.07-26.23-33.56-33.83z\"],\n    \"cpanel\": [640, 512, [], \"f388\", \"M210.3 220.2c-5.6-24.8-26.9-41.2-51-41.2h-37c-7.1 0-12.5 4.5-14.3 10.9L73.1 320l24.7-.1c6.8 0 12.3-4.5 14.2-10.7l25.8-95.7h19.8c8.4 0 16.2 5.6 18.3 14.8 2.5 10.9-5.9 22.6-18.3 22.6h-10.3c-7 0-12.5 4.6-14.3 10.8l-6.4 23.8h32c37.2 0 58.3-36.2 51.7-65.3zm-156.5 28h18.6c6.9 0 12.4-4.4 14.3-10.9l6.2-23.6h-40C30 213.7 9 227.8 1.7 254.8-7 288.6 18.5 320 52 320h12.4l7.1-26.1c1.2-4.4-2.2-8.3-6.4-8.3H53.8c-24.7 0-24.9-37.4 0-37.4zm247.5-34.8h-77.9l-3.5 13.4c-2.4 9.6 4.5 18.5 14.2 18.5h57.5c4 0 2.4 4.3 2.1 5.3l-8.6 31.8c-.4 1.4-.9 5.3-5.5 5.3h-34.9c-5.3 0-5.3-7.9 0-7.9h21.6c6.8 0 12.3-4.6 14.2-10.8l3.5-13.2h-48.4c-39.2 0-43.6 63.8-.7 63.8l57.5.2c11.2 0 20.6-7.2 23.4-17.8l14-51.8c4.8-19.2-9.7-36.8-28.5-36.8zM633.1 179h-18.9c-4.9 0-9.2 3.2-10.4 7.9L568.2 320c20.7 0 39.8-13.8 44.9-34.5l26.5-98.2c1.2-4.3-2-8.3-6.5-8.3zm-236.3 34.7v.1h-48.3l-26.2 98c-1.2 4.4 2.2 8.3 6.4 8.3h18.9c4.8 0 9.2-3 10.4-7.8l17.2-64H395c12.5 0 21.4 11.8 18.1 23.4l-10.6 40c-1.2 4.3 1.9 8.3 6.4 8.3H428c4.6 0 9.1-2.9 10.3-7.8l8.8-33.1c9-33.1-15.9-65.4-50.3-65.4zm98.3 74.6c-3.6 0-6-3.4-5.1-6.7l8-30c.9-3.9 3.7-6 7.8-6h32.9c2.6 0 4.6 2.4 3.9 5.1l-.7 2.6c-.6 2-1.9 3-3.9 3h-21.6c-7 0-12.6 4.6-14.2 10.8l-3.5 13h53.4c10.5 0 20.3-6.6 23.2-17.6l3.2-12c4.9-19.1-9.3-36.8-28.3-36.8h-47.3c-17.9 0-33.8 12-38.6 29.6l-10.8 40c-5 17.7 8.3 36.7 28.3 36.7h66.7c6.8 0 12.3-4.5 14.2-10.7l5.7-21z\"],\n    \"creative-commons\": [496, 512, [], \"f25e\", \"M245.83 214.87l-33.22 17.28c-9.43-19.58-25.24-19.93-27.46-19.93-22.13 0-33.22 14.61-33.22 43.84 0 23.57 9.21 43.84 33.22 43.84 14.47 0 24.65-7.09 30.57-21.26l30.55 15.5c-6.17 11.51-25.69 38.98-65.1 38.98-22.6 0-73.96-10.32-73.96-77.05 0-58.69 43-77.06 72.63-77.06 30.72-.01 52.7 11.95 65.99 35.86zm143.05 0l-32.78 17.28c-9.5-19.77-25.72-19.93-27.9-19.93-22.14 0-33.22 14.61-33.22 43.84 0 23.55 9.23 43.84 33.22 43.84 14.45 0 24.65-7.09 30.54-21.26l31 15.5c-2.1 3.75-21.39 38.98-65.09 38.98-22.69 0-73.96-9.87-73.96-77.05 0-58.67 42.97-77.06 72.63-77.06 30.71-.01 52.58 11.95 65.56 35.86zM247.56 8.05C104.74 8.05 0 123.11 0 256.05c0 138.49 113.6 248 247.56 248 129.93 0 248.44-100.87 248.44-248 0-137.87-106.62-248-248.44-248zm.87 450.81c-112.54 0-203.7-93.04-203.7-202.81 0-105.42 85.43-203.27 203.72-203.27 112.53 0 202.82 89.46 202.82 203.26-.01 121.69-99.68 202.82-202.84 202.82z\"],\n    \"creative-commons-by\": [496, 512, [], \"f4e7\", \"M314.9 194.4v101.4h-28.3v120.5h-77.1V295.9h-28.3V194.4c0-4.4 1.6-8.2 4.6-11.3 3.1-3.1 6.9-4.7 11.3-4.7H299c4.1 0 7.8 1.6 11.1 4.7 3.1 3.2 4.8 6.9 4.8 11.3zm-101.5-63.7c0-23.3 11.5-35 34.5-35s34.5 11.7 34.5 35c0 23-11.5 34.5-34.5 34.5s-34.5-11.5-34.5-34.5zM247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3z\"],\n    \"creative-commons-nc\": [496, 512, [], \"f4e8\", \"M247.6 8C387.4 8 496 115.9 496 256c0 147.2-118.5 248-248.4 248C113.1 504 0 393.2 0 256 0 123.1 104.7 8 247.6 8zM55.8 189.1c-7.4 20.4-11.1 42.7-11.1 66.9 0 110.9 92.1 202.4 203.7 202.4 122.4 0 177.2-101.8 178.5-104.1l-93.4-41.6c-7.7 37.1-41.2 53-68.2 55.4v38.1h-28.8V368c-27.5-.3-52.6-10.2-75.3-29.7l34.1-34.5c31.7 29.4 86.4 31.8 86.4-2.2 0-6.2-2.2-11.2-6.6-15.1-14.2-6-1.8-.1-219.3-97.4zM248.4 52.3c-38.4 0-112.4 8.7-170.5 93l94.8 42.5c10-31.3 40.4-42.9 63.8-44.3v-38.1h28.8v38.1c22.7 1.2 43.4 8.9 62 23L295 199.7c-42.7-29.9-83.5-8-70 11.1 53.4 24.1 43.8 19.8 93 41.6l127.1 56.7c4.1-17.4 6.2-35.1 6.2-53.1 0-57-19.8-105-59.3-143.9-39.3-39.9-87.2-59.8-143.6-59.8z\"],\n    \"creative-commons-nc-eu\": [496, 512, [], \"f4e9\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.3 111.7 248 247.7 248C377.9 504 496 403.1 496 256 496 117 388.4 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-23.2 3.7-45.2 10.9-66l65.7 29.1h-4.7v29.5h23.3c0 6.2-.4 3.2-.4 19.5h-22.8v29.5h27c11.4 67 67.2 101.3 124.6 101.3 26.6 0 50.6-7.9 64.8-15.8l-10-46.1c-8.7 4.6-28.2 10.8-47.3 10.8-28.2 0-58.1-10.9-67.3-50.2h90.3l128.3 56.8c-1.5 2.1-56.2 104.3-178.8 104.3zm-16.7-190.6l-.5-.4.9.4h-.4zm77.2-19.5h3.7v-29.5h-70.3l-28.6-12.6c2.5-5.5 5.4-10.5 8.8-14.3 12.9-15.8 31.1-22.4 51.1-22.4 18.3 0 35.3 5.4 46.1 10l11.6-47.3c-15-6.6-37-12.4-62.3-12.4-39 0-72.2 15.8-95.9 42.3-5.3 6.1-9.8 12.9-13.9 20.1l-81.6-36.1c64.6-96.8 157.7-93.6 170.7-93.6 113 0 203 90.2 203 203.4 0 18.7-2.1 36.3-6.3 52.9l-136.1-60.5z\"],\n    \"creative-commons-nc-jp\": [496, 512, [], \"f4ea\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.4 111.8 248 247.7 248C377.9 504 496 403.2 496 256 496 117.2 388.5 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-21.1 3-41.2 9-60.3l127 56.5h-27.9v38.6h58.1l5.7 11.8v18.7h-63.8V360h63.8v56h61.7v-56h64.2v-35.7l81 36.1c-1.5 2.2-57.1 98.3-175.2 98.3zm87.6-137.3h-57.6v-18.7l2.9-5.6 54.7 24.3zm6.5-51.4v-17.8h-38.6l63-116H301l-43.4 96-23-10.2-39.6-85.7h-65.8l27.3 51-81.9-36.5c27.8-44.1 82.6-98.1 173.7-98.1 112.8 0 203 90 203 203.4 0 21-2.7 40.6-7.9 59l-101-45.1z\"],\n    \"creative-commons-nd\": [496, 512, [], \"f4eb\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm94 144.3v42.5H162.1V197h180.3zm0 79.8v42.5H162.1v-42.5h180.3z\"],\n    \"creative-commons-pd\": [496, 512, [], \"f4ec\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm0 449.5c-139.2 0-235.8-138-190.2-267.9l78.8 35.1c-2.1 10.5-3.3 21.5-3.3 32.9 0 99 73.9 126.9 120.4 126.9 22.9 0 53.5-6.7 79.4-29.5L297 311.1c-5.5 6.3-17.6 16.7-36.3 16.7-37.8 0-53.7-39.9-53.9-71.9 230.4 102.6 216.5 96.5 217.9 96.8-34.3 62.4-100.6 104.8-176.7 104.8zm194.2-150l-224-100c18.8-34 54.9-30.7 74.7-11l40.4-41.6c-27.1-23.3-58-27.5-78.1-27.5-47.4 0-80.9 20.5-100.7 51.6l-74.9-33.4c36.1-54.9 98.1-91.2 168.5-91.2 111.1 0 201.5 90.4 201.5 201.5 0 18-2.4 35.4-6.8 52-.3-.1-.4-.2-.6-.4z\"],\n    \"creative-commons-pd-alt\": [496, 512, [], \"f4ed\", \"M247.6 8C104.7 8 0 123.1 0 256c0 138.5 113.6 248 247.6 248C377.5 504 496 403.1 496 256 496 118.1 389.4 8 247.6 8zm.8 450.8c-112.5 0-203.7-93-203.7-202.8 0-105.4 85.5-203.3 203.7-203.3 112.6 0 202.9 89.5 202.8 203.3 0 121.7-99.6 202.8-202.8 202.8zM316.7 186h-53.2v137.2h53.2c21.4 0 70-5.1 70-68.6 0-63.4-48.6-68.6-70-68.6zm.8 108.5h-19.9v-79.7l19.4-.1c3.8 0 35-2.1 35 39.9 0 24.6-10.5 39.9-34.5 39.9zM203.7 186h-68.2v137.3h34.6V279h27c54.1 0 57.1-37.5 57.1-46.5 0-31-16.8-46.5-50.5-46.5zm-4.9 67.3h-29.2v-41.6h28.3c30.9 0 28.8 41.6.9 41.6z\"],\n    \"creative-commons-remix\": [496, 512, [], \"f4ee\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm161.7 207.7l4.9 2.2v70c-7.2 3.6-63.4 27.5-67.3 28.8-6.5-1.8-113.7-46.8-137.3-56.2l-64.2 26.6-63.3-27.5v-63.8l59.3-24.8c-.7-.7-.4 5-.4-70.4l67.3-29.7L361 178.5v61.6l49.1 20.3zm-70.4 81.5v-43.8h-.4v-1.8l-113.8-46.5V295l113.8 46.9v-.4l.4.4zm7.5-57.6l39.9-16.4-36.8-15.5-39 16.4 35.9 15.5zm52.3 38.1v-43L355.2 298v43.4l44.3-19z\"],\n    \"creative-commons-sa\": [496, 512, [], \"f4ef\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zM137.7 221c13-83.9 80.5-95.7 108.9-95.7 99.8 0 127.5 82.5 127.5 134.2 0 63.6-41 132.9-128.9 132.9-38.9 0-99.1-20-109.4-97h62.5c1.5 30.1 19.6 45.2 54.5 45.2 23.3 0 58-18.2 58-82.8 0-82.5-49.1-80.6-56.7-80.6-33.1 0-51.7 14.6-55.8 43.8h18.2l-49.2 49.2-49-49.2h19.4z\"],\n    \"creative-commons-sampling\": [496, 512, [], \"f4f0\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm3.6 53.2c2.8-.3 11.5 1 11.5 11.5l6.6 107.2 4.9-59.3c0-6 4.7-10.6 10.6-10.6 5.9 0 10.6 4.7 10.6 10.6 0 2.5-.5-5.7 5.7 81.5l5.8-64.2c.3-2.9 2.9-9.3 10.2-9.3 3.8 0 9.9 2.3 10.6 8.9l11.5 96.5 5.3-12.8c1.8-4.4 5.2-6.6 10.2-6.6h58v21.3h-50.9l-18.2 44.3c-3.9 9.9-19.5 9.1-20.8-3.1l-4-31.9-7.5 92.6c-.3 3-3 9.3-10.2 9.3-3 0-9.8-2.1-10.6-9.3 0-1.9.6 5.8-6.2-77.9l-5.3 72.2c-1.1 4.8-4.8 9.3-10.6 9.3-2.9 0-9.8-2-10.6-9.3 0-1.9.5 6.7-5.8-87.7l-5.8 94.8c0 6.3-3.6 12.4-10.6 12.4-5.2 0-10.6-4.1-10.6-12l-5.8-87.7c-5.8 92.5-5.3 84-5.3 85.9-1.1 4.8-4.8 9.3-10.6 9.3-3 0-9.8-2.1-10.6-9.3 0-.7-.4-1.1-.4-2.6l-6.2-88.6L182 348c-.7 6.5-6.7 9.3-10.6 9.3-5.8 0-9.6-4.1-10.6-8.9L149.7 272c-2 4-3.5 8.4-11.1 8.4H87.2v-21.3H132l13.7-27.9c4.4-9.9 18.2-7.2 19.9 2.7l3.1 20.4 8.4-97.9c0-6 4.8-10.6 10.6-10.6.5 0 10.6-.2 10.6 12.4l4.9 69.1 6.6-92.6c0-10.1 9.5-10.6 10.2-10.6.6 0 10.6.7 10.6 10.6l5.3 80.6 6.2-97.9c.1-1.1-.6-10.3 9.9-11.5z\"],\n    \"creative-commons-sampling-plus\": [496, 512, [], \"f4f1\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm107 205.6c-4.7 0-9 2.8-10.7 7.2l-4 9.5-11-92.8c-1.7-13.9-22-13.4-23.1.4l-4.3 51.4-5.2-68.8c-1.1-14.3-22.1-14.2-23.2 0l-3.5 44.9-5.9-94.3c-.9-14.5-22.3-14.4-23.2 0l-5.1 83.7-4.3-66.3c-.9-14.4-22.2-14.4-23.2 0l-5.3 80.2-4.1-57c-1.1-14.3-22-14.3-23.2-.2l-7.7 89.8-1.8-12.2c-1.7-11.4-17.1-13.6-22-3.3l-13.2 27.7H87.5v23.2h51.3c4.4 0 8.4-2.5 10.4-6.4l10.7 73.1c2 13.5 21.9 13 23.1-.7l3.8-43.6 5.7 78.3c1.1 14.4 22.3 14.2 23.2-.1l4.6-70.4 4.8 73.3c.9 14.4 22.3 14.4 23.2-.1l4.9-80.5 4.5 71.8c.9 14.3 22.1 14.5 23.2.2l4.6-58.6 4.9 64.4c1.1 14.3 22 14.2 23.1.1l6.8-83 2.7 22.3c1.4 11.8 17.7 14.1 22.3 3.1l18-43.4h50.5V258l-58.4.3zm-78 5.2h-21.9v21.9c0 4.1-3.3 7.5-7.5 7.5-4.1 0-7.5-3.3-7.5-7.5v-21.9h-21.9c-4.1 0-7.5-3.3-7.5-7.5 0-4.1 3.4-7.5 7.5-7.5h21.9v-21.9c0-4.1 3.4-7.5 7.5-7.5s7.5 3.3 7.5 7.5v21.9h21.9c4.1 0 7.5 3.3 7.5 7.5 0 4.1-3.4 7.5-7.5 7.5z\"],\n    \"creative-commons-share\": [496, 512, [], \"f4f2\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm101 132.4c7.8 0 13.7 6.1 13.7 13.7v182.5c0 7.7-6.1 13.7-13.7 13.7H214.3c-7.7 0-13.7-6-13.7-13.7v-54h-54c-7.8 0-13.7-6-13.7-13.7V131.1c0-8.2 6.6-12.7 12.4-13.7h136.4c7.7 0 13.7 6 13.7 13.7v54h54zM159.9 300.3h40.7V198.9c0-7.4 5.8-12.6 12-13.7h55.8v-40.3H159.9v155.4zm176.2-88.1H227.6v155.4h108.5V212.2z\"],\n    \"creative-commons-zero\": [496, 512, [], \"f4f3\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm-.4 60.5c-81.9 0-102.5 77.3-102.5 142.8 0 65.5 20.6 142.8 102.5 142.8S350.5 321.5 350.5 256c0-65.5-20.6-142.8-102.5-142.8zm0 53.9c3.3 0 6.4.5 9.2 1.2 5.9 5.1 8.8 12.1 3.1 21.9l-54.5 100.2c-1.7-12.7-1.9-25.1-1.9-34.4 0-28.8 2-88.9 44.1-88.9zm40.8 46.2c2.9 15.4 3.3 31.4 3.3 42.7 0 28.9-2 88.9-44.1 88.9-13.5 0-32.6-7.7-20.1-26.4l60.9-105.2z\"],\n    \"critical-role\": [448, 512, [], \"f6c9\", \"M225.82 0c.26.15 216.57 124.51 217.12 124.72 3 1.18 3.7 3.46 3.7 6.56q-.11 125.17 0 250.36a5.88 5.88 0 0 1-3.38 5.78c-21.37 12-207.86 118.29-218.93 124.58h-3C142 466.34 3.08 386.56 2.93 386.48a3.29 3.29 0 0 1-1.88-3.24c0-.87 0-225.94-.05-253.1a5 5 0 0 1 2.93-4.93C27.19 112.11 213.2 6 224.07 0zM215.4 20.42l-.22-.16Q118.06 75.55 21 130.87c0 .12.08.23.13.35l30.86 11.64c-7.71 6-8.32 6-10.65 5.13-.1 0-24.17-9.28-26.8-10v230.43c.88-1.41 64.07-110.91 64.13-111 1.62-2.82 3-1.92 9.12-1.52 1.4.09 1.48.22.78 1.42-41.19 71.33-36.4 63-67.48 116.94-.81 1.4-.61 1.13 1.25 1.13h186.5c1.44 0 1.69-.23 1.7-1.64v-8.88c0-1.34 2.36-.81-18.37-1-7.46-.07-14.14-3.22-21.38-12.7-7.38-9.66-14.62-19.43-21.85-29.21-2.28-3.08-3.45-2.38-16.76-2.38-1.75 0-1.78 0-1.76 1.82.29 26.21.15 25.27 1 32.66.52 4.37 2.16 4.2 9.69 4.81 3.14.26 3.88 4.08.52 4.92-1.57.39-31.6.51-33.67-.1a2.42 2.42 0 0 1 .3-4.73c3.29-.76 6.16.81 6.66-4.44 1.3-13.66 1.17-9 1.1-79.42 0-10.82-.35-12.58-5.36-13.55-1.22-.24-3.54-.16-4.69-.55-2.88-1-2-4.84 1.77-4.85 33.67 0 46.08-1.07 56.06 4.86 7.74 4.61 12 11.48 12.51 20.4.88 14.59-6.51 22.35-15 32.59a1.46 1.46 0 0 0 0 2.22c2.6 3.25 5 6.63 7.71 9.83 27.56 33.23 24.11 30.54 41.28 33.06.89.13 1-.42 1-1.15v-11c0-1 .32-1.43 1.41-1.26a72.37 72.37 0 0 0 23.58-.3c1.08-.15 1.5.2 1.48 1.33 0 .11.88 26.69.87 26.8-.05 1.52.67 1.62 1.89 1.62h186.71Q386.51 304.6 346 234.33c2.26-.66-.4 0 6.69-1.39 2-.39 2.05-.41 3.11 1.44 7.31 12.64 77.31 134 77.37 134.06V138c-1.72.5-103.3 38.72-105.76 39.68-1.08.42-1.55.2-1.91-.88-.63-1.9-1.34-3.76-2.09-5.62-.32-.79-.09-1.13.65-1.39.1 0 95.53-35.85 103-38.77-65.42-37.57-130.56-75-196-112.6l86.82 150.39-.28.33c-9.57-.9-10.46-1.6-11.8-3.94-1-1.69-73.5-127.71-82-142.16-9.1 14.67-83.56 146.21-85.37 146.32-2.93.17-5.88.08-9.25.08q43.25-74.74 86.18-149zm51.93 129.92a37.68 37.68 0 0 0 5.54-.85c1.69-.3 2.53.2 2.6 1.92 0 .11.07 19.06-.86 20.45s-1.88 1.22-2.6-.19c-5-9.69 6.22-9.66-39.12-12-.7 0-1 .23-1 .93 0 .13 3.72 122 3.73 122.11 0 .89.52 1.2 1.21 1.51a83.92 83.92 0 0 1 8.7 4.05c7.31 4.33 11.38 10.84 12.41 19.31 1.44 11.8-2.77 35.77-32.21 37.14-2.75.13-28.26 1.08-34.14-23.25-4.66-19.26 8.26-32.7 19.89-36.4a2.45 2.45 0 0 0 2-2.66c.1-5.63 3-107.1 3.71-121.35.05-1.08-.62-1.16-1.35-1.15-32.35.52-36.75-.34-40.22 8.52-2.42 6.18-4.14 1.32-3.95.23q1.59-9 3.31-18c.4-2.11 1.43-2.61 3.43-1.86 5.59 2.11 6.72 1.7 37.25 1.92 1.73 0 1.78-.08 1.82-1.85.68-27.49.58-22.59 1-29.55a2.69 2.69 0 0 0-1.63-2.8c-5.6-2.91-8.75-7.55-8.9-13.87-.35-14.81 17.72-21.67 27.38-11.51 6.84 7.19 5.8 18.91-2.45 24.15a4.35 4.35 0 0 0-2.22 4.34c0 .59-.11-4.31 1 30.05 0 .9.43 1.12 1.24 1.11.1 0 23-.09 34.47-.37zM68.27 141.7c19.84-4.51 32.68-.56 52.49 1.69 2.76.31 3.74 1.22 3.62 4-.21 5-1.16 22.33-1.24 23.15a2.65 2.65 0 0 1-1.63 2.34c-4.06 1.7-3.61-4.45-4-7.29-3.13-22.43-73.87-32.7-74.63 25.4-.31 23.92 17 53.63 54.08 50.88 27.24-2 19-20.19 24.84-20.47a2.72 2.72 0 0 1 3 3.36c-1.83 10.85-3.42 18.95-3.45 19.15-1.54 9.17-86.7 22.09-93.35-42.06-2.71-25.85 10.44-53.37 40.27-60.15zm80 87.67h-19.49a2.57 2.57 0 0 1-2.66-1.79c2.38-3.75 5.89.92 5.86-6.14-.08-25.75.21-38 .23-40.1 0-3.42-.53-4.65-3.32-4.94-7-.72-3.11-3.37-1.11-3.38 11.84-.1 22.62-.18 30.05.72 8.77 1.07 16.71 12.63 7.93 22.62-2 2.25-4 4.42-6.14 6.73.95 1.15 6.9 8.82 17.28 19.68 2.66 2.78 6.15 3.51 9.88 3.13a2.21 2.21 0 0 0 2.23-2.12c.3-3.42.26 4.73.45-40.58 0-5.65-.34-6.58-3.23-6.83-3.95-.35-4-2.26-.69-3.37l19.09-.09c.32 0 4.49.53 1 3.38 0 .05-.16 0-.24 0-3.61.26-3.94 1-4 4.62-.27 43.93.07 40.23.41 42.82.11.84.27 2.23 5.1 2.14 2.49 0 3.86 3.37 0 3.4-10.37.08-20.74 0-31.11.07-10.67 0-13.47-6.2-24.21-20.82-1.6-2.18-8.31-2.36-8.2-.37.88 16.47 0 17.78 4 17.67 4.75-.1 4.73 3.57.83 3.55zm275-10.15c-1.21 7.13.17 10.38-5.3 10.34-61.55-.42-47.82-.22-50.72-.31a18.4 18.4 0 0 1-3.63-.73c-2.53-.6 1.48-1.23-.38-5.6-1.43-3.37-2.78-6.78-4.11-10.19a1.94 1.94 0 0 0-2-1.44 138 138 0 0 0-14.58.07 2.23 2.23 0 0 0-1.62 1.06c-1.58 3.62-3.07 7.29-4.51 11-1.27 3.23 7.86 1.32 12.19 2.16 3 .57 4.53 3.72.66 3.73H322.9c-2.92 0-3.09-3.15-.74-3.21a6.3 6.3 0 0 0 5.92-3.47c1.5-3 2.8-6 4.11-9.09 18.18-42.14 17.06-40.17 18.42-41.61a1.83 1.83 0 0 1 3 0c2.93 3.34 18.4 44.71 23.62 51.92 2 2.7 5.74 2 6.36 2 3.61.13 4-1.11 4.13-4.29.09-1.87.08 1.17.07-41.24 0-4.46-2.36-3.74-5.55-4.27-.26 0-2.56-.63-.08-3.06.21-.2-.89-.24 21.7-.15 2.32 0 5.32 2.75-1.21 3.45a2.56 2.56 0 0 0-2.66 2.83c-.07 1.63-.19 38.89.29 41.21a3.06 3.06 0 0 0 3.23 2.43c13.25.43 14.92.44 16-3.41 1.67-5.78 4.13-2.52 3.73-.19zm-104.72 64.37c-4.24 0-4.42-3.39-.61-3.41 35.91-.16 28.11.38 37.19-.65 1.68-.19 2.38.24 2.25 1.89-.26 3.39-.64 6.78-1 10.16-.25 2.16-3.2 2.61-3.4-.15-.38-5.31-2.15-4.45-15.63-5.08-1.58-.07-1.64 0-1.64 1.52V304c0 1.65 0 1.6 1.62 1.47 3.12-.25 10.31.34 15.69-1.52.47-.16 3.3-1.79 3.07 1.76 0 .21-.76 10.35-1.18 11.39-.53 1.29-1.88 1.51-2.58.32-1.17-2 0-5.08-3.71-5.3-15.42-.9-12.91-2.55-12.91 6 0 12.25-.76 16.11 3.89 16.24 16.64.48 14.4 0 16.43-5.71.84-2.37 3.5-1.77 3.18.58-.44 3.21-.85 6.43-1.23 9.64 0 .36-.16 2.4-4.66 2.39-37.16-.08-34.54-.19-35.21-.31-2.72-.51-2.2-3 .22-3.45 1.1-.19 4 .54 4.16-2.56 2.44-56.22-.07-51.34-3.91-51.33zm-.41-109.52c2.46.61 3.13 1.76 2.95 4.65-.33 5.3-.34 9-.55 9.69-.66 2.23-3.15 2.12-3.34-.27-.38-4.81-3.05-7.82-7.57-9.15-26.28-7.73-32.81 15.46-27.17 30.22 5.88 15.41 22 15.92 28.86 13.78 5.92-1.85 5.88-6.5 6.91-7.58 1.23-1.3 2.25-1.84 3.12 1.1 0 .1.57 11.89-6 12.75-1.6.21-19.38 3.69-32.68-3.39-21-11.19-16.74-35.47-6.88-45.33 14-14.06 39.91-7.06 42.32-6.47zM289.8 280.14c3.28 0 3.66 3 .16 3.43-2.61.32-5-.42-5 5.46 0 2-.19 29.05.4 41.45.11 2.29 1.15 3.52 3.44 3.65 22 1.21 14.95-1.65 18.79-6.34 1.83-2.24 2.76.84 2.76 1.08.35 13.62-4 12.39-5.19 12.4l-38.16-.19c-1.93-.23-2.06-3-.42-3.38 2-.48 4.94.4 5.13-2.8 1-15.87.57-44.65.34-47.81-.27-3.77-2.8-3.27-5.68-3.71-2.47-.38-2-3.22.34-3.22 1.45-.02 17.97-.03 23.09-.02zm-31.63-57.79c.07 4.08 2.86 3.46 6 3.58 2.61.1 2.53 3.41-.07 3.43-6.48 0-13.7 0-21.61-.06-3.84 0-3.38-3.35 0-3.37 4.49 0 3.24 1.61 3.41-45.54 0-5.08-3.27-3.54-4.72-4.23-2.58-1.23-1.36-3.09.41-3.15 1.29 0 20.19-.41 21.17.21s1.87 1.65-.42 2.86c-1 .52-3.86-.28-4.15 2.47 0 .21-.82 1.63-.07 43.8zm-36.91 274.27a2.93 2.93 0 0 0 3.26 0c17-9.79 182-103.57 197.42-112.51-.14-.43 11.26-.18-181.52-.27-1.22 0-1.57.37-1.53 1.56 0 .1 1.25 44.51 1.22 50.38a28.33 28.33 0 0 1-1.36 7.71c-.55 1.83.38-.5-13.5 32.23-.73 1.72-1 2.21-2-.08-4.19-10.34-8.28-20.72-12.57-31a23.6 23.6 0 0 1-2-10.79c.16-2.46.8-16.12 1.51-48 0-1.95 0-2-2-2h-183c2.58 1.63 178.32 102.57 196 112.76zm-90.9-188.75c0 2.4.36 2.79 2.76 3 11.54 1.17 21 3.74 25.64-7.32 6-14.46 2.66-34.41-12.48-38.84-2-.59-16-2.76-15.94 1.51.05 8.04.01 11.61.02 41.65zm105.75-15.05c0 2.13 1.07 38.68 1.09 39.13.34 9.94-25.58 5.77-25.23-2.59.08-2 1.37-37.42 1.1-39.43-14.1 7.44-14.42 40.21 6.44 48.8a17.9 17.9 0 0 0 22.39-7.07c4.91-7.76 6.84-29.47-5.43-39a2.53 2.53 0 0 1-.36.12zm-12.28-198c-9.83 0-9.73 14.75-.07 14.87s10.1-14.88.07-14.91zm-80.15 103.83c0 1.8.41 2.4 2.17 2.58 13.62 1.39 12.51-11 12.16-13.36-1.69-11.22-14.38-10.2-14.35-7.81.05 4.5-.03 13.68.02 18.59zm212.32 6.4l-6.1-15.84c-2.16 5.48-4.16 10.57-6.23 15.84z\"],\n    \"css3\": [512, 512, [], \"f13c\", \"M480 32l-64 368-223.3 80L0 400l19.6-94.8h82l-8 40.6L210 390.2l134.1-44.4 18.8-97.1H29.5l16-82h333.7l10.5-52.7H56.3l16.3-82H480z\"],\n    \"css3-alt\": [384, 512, [], \"f38b\", \"M0 32l34.9 395.8L192 480l157.1-52.2L384 32H0zm313.1 80l-4.8 47.3L193 208.6l-.3.1h111.5l-12.8 146.6-98.2 28.7-98.8-29.2-6.4-73.9h48.9l3.2 38.3 52.6 13.3 54.7-15.4 3.7-61.6-166.3-.5v-.1l-.2.1-3.6-46.3L193.1 162l6.5-2.7H76.7L70.9 112h242.2z\"],\n    \"cuttlefish\": [440, 512, [], \"f38c\", \"M344 305.5c-17.5 31.6-57.4 54.5-96 54.5-56.6 0-104-47.4-104-104s47.4-104 104-104c38.6 0 78.5 22.9 96 54.5 13.7-50.9 41.7-93.3 87-117.8C385.7 39.1 320.5 8 248 8 111 8 0 119 0 256s111 248 248 248c72.5 0 137.7-31.1 183-80.7-45.3-24.5-73.3-66.9-87-117.8z\"],\n    \"d-and-d\": [576, 512, [], \"f38d\", \"M82.5 98.9c-.6-17.2 2-33.8 12.7-48.2.3 7.4 1.2 14.5 4.2 21.6 5.9-27.5 19.7-49.3 42.3-65.5-1.9 5.9-3.5 11.8-3 17.7 8.7-7.4 18.8-17.8 44.4-22.7 14.7-2.8 29.7-2 42.1 1 38.5 9.3 61 34.3 69.7 72.3 5.3 23.1.7 45-8.3 66.4-5.2 12.4-12 24.4-20.7 35.1-2-1.9-3.9-3.8-5.8-5.6-42.8-40.8-26.8-25.2-37.4-37.4-1.1-1.2-1-2.2-.1-3.6 8.3-13.5 11.8-28.2 10-44-1.1-9.8-4.3-18.9-11.3-26.2-14.5-15.3-39.2-15-53.5.6-11.4 12.5-14.1 27.4-10.9 43.6.2 1.3.4 2.7 0 3.9-3.4 13.7-4.6 27.6-2.5 41.6.1.5.1 1.1.1 1.6 0 .3-.1.5-.2 1.1-21.8-11-36-28.3-43.2-52.2-8.3 17.8-11.1 35.5-6.6 54.1-15.6-15.2-21.3-34.3-22-55.2zm469.6 123.2c-11.6-11.6-25-20.4-40.1-26.6-12.8-5.2-26-7.9-39.9-7.1-10 .6-19.6 3.1-29 6.4-2.5.9-5.1 1.6-7.7 2.2-4.9 1.2-7.3-3.1-4.7-6.8 3.2-4.6 3.4-4.2 15-12 .6-.4 1.2-.8 2.2-1.5h-2.5c-.6 0-1.2.2-1.9.3-19.3 3.3-30.7 15.5-48.9 29.6-10.4 8.1-13.8 3.8-12-.5 1.4-3.5 3.3-6.7 5.1-10 1-1.8 2.3-3.4 3.5-5.1-.2-.2-.5-.3-.7-.5-27 18.3-46.7 42.4-57.7 73.3.3.3.7.6 1 .9.3-.6.5-1.2.9-1.7 10.4-12.1 22.8-21.8 36.6-29.8 18.2-10.6 37.5-18.3 58.7-20.2 4.3-.4 8.7-.1 13.1-.1-1.8.7-3.5.9-5.3 1.1-18.5 2.4-35.5 9-51.5 18.5-30.2 17.9-54.5 42.2-75.1 70.4-.3.4-.4.9-.7 1.3 14.5 5.3 24 17.3 36.1 25.6.2-.1.3-.2.4-.4l1.2-2.7c12.2-26.9 27-52.3 46.7-74.5 16.7-18.8 38-25.3 62.5-20 5.9 1.3 11.4 4.4 17.2 6.8 2.3-1.4 5.1-3.2 8-4.7 8.4-4.3 17.4-7 26.7-9 14.7-3.1 29.5-4.9 44.5-1.3v-.5c-.5-.4-1.2-.8-1.7-1.4zM316.7 397.6c-39.4-33-22.8-19.5-42.7-35.6-.8.9 0-.2-1.9 3-11.2 19.1-25.5 35.3-44 47.6-10.3 6.8-21.5 11.8-34.1 11.8-21.6 0-38.2-9.5-49.4-27.8-12-19.5-13.3-40.7-8.2-62.6 7.8-33.8 30.1-55.2 38.6-64.3-18.7-6.2-33 1.7-46.4 13.9.8-13.9 4.3-26.2 11.8-37.3-24.3 10.6-45.9 25-64.8 43.9-.3-5.8 5.4-43.7 5.6-44.7.3-2.7-.6-5.3-3-7.4-24.2 24.7-44.5 51.8-56.1 84.6 7.4-5.9 14.9-11.4 23.6-16.2-8.3 22.3-19.6 52.8-7.8 101.1 4.6 19 11.9 36.8 24.1 52.3 2.9 3.7 6.3 6.9 9.5 10.3.2-.2.4-.3.6-.5-1.4-7-2.2-14.1-1.5-21.9 2.2 3.2 3.9 6 5.9 8.6 12.6 16 28.7 27.4 47.2 35.6 25 11.3 51.1 13.3 77.9 8.6 54.9-9.7 90.7-48.6 116-98.8 1-1.8.6-2.9-.9-4.2zm172-46.4c-9.5-3.1-22.2-4.2-28.7-2.9 9.9 4 14.1 6.6 18.8 12 12.6 14.4 10.4 34.7-5.4 45.6-11.7 8.1-24.9 10.5-38.9 9.1-1.2-.1-2.3-.4-3-.6 2.8-3.7 6-7 8.1-10.8 9.4-16.8 5.4-42.1-8.7-56.1-2.1-2.1-4.6-3.9-7-5.9-.3 1.3-.1 2.1.1 2.8 4.2 16.6-8.1 32.4-24.8 31.8-7.6-.3-13.9-3.8-19.6-8.5-19.5-16.1-39.1-32.1-58.5-48.3-5.9-4.9-12.5-8.1-20.1-8.7-4.6-.4-9.3-.6-13.9-.9-5.9-.4-8.8-2.8-10.4-8.4-.9-3.4-1.5-6.8-2.2-10.2-1.5-8.1-6.2-13-14.3-14.2-4.4-.7-8.9-1-13.3-1.5-13-1.4-19.8-7.4-22.6-20.3-5 11-1.6 22.4 7.3 29.9 4.5 3.8 9.3 7.3 13.8 11.2 4.6 3.8 7.4 8.7 7.9 14.8.4 4.7.8 9.5 1.8 14.1 2.2 10.6 8.9 18.4 17 25.1 16.5 13.7 33 27.3 49.5 41.1 17.9 15 13.9 32.8 13 56-.9 22.9 12.2 42.9 33.5 51.2 1 .4 2 .6 3.6 1.1-15.7-18.2-10.1-44.1.7-52.3.3 2.2.4 4.3.9 6.4 9.4 44.1 45.4 64.2 85 56.9 16-2.9 30.6-8.9 42.9-19.8 2-1.8 3.7-4.1 5.9-6.5-19.3 4.6-35.8.1-50.9-10.6.7-.3 1.3-.3 1.9-.3 21.3 1.8 40.6-3.4 57-17.4 19.5-16.6 26.6-42.9 17.4-66-8.3-20.1-23.6-32.3-43.8-38.9zM99.4 179.3c-5.3-9.2-13.2-15.6-22.1-21.3 13.7-.5 26.6.2 39.6 3.7-7-12.2-8.5-24.7-5-38.7 5.3 11.9 13.7 20.1 23.6 26.8 19.7 13.2 35.7 19.6 46.7 30.2 3.4 3.3 6.3 7.1 9.6 10.9-.8-2.1-1.4-4.1-2.2-6-5-10.6-13-18.6-22.6-25-1.8-1.2-2.8-2.5-3.4-4.5-3.3-12.5-3-25.1-.7-37.6 1-5.5 2.8-10.9 4.5-16.3.8-2.4 2.3-4.6 4-6.6.6 6.9 0 25.5 19.6 46 10.8 11.3 22.4 21.9 33.9 32.7 9 8.5 18.3 16.7 25.5 26.8 1.1 1.6 2.2 3.3 3.8 4.7-5-13-14.2-24.1-24.2-33.8-9.6-9.3-19.4-18.4-29.2-27.4-3.3-3-4.6-6.7-5.1-10.9-1.2-10.4 0-20.6 4.3-30.2.5-1 1.1-2 1.9-3.3.5 4.2.6 7.9 1.4 11.6 4.8 23.1 20.4 36.3 49.3 63.5 10 9.4 19.3 19.2 25.6 31.6 4.8 9.3 7.3 19 5.7 29.6-.1.6.5 1.7 1.1 2 6.2 2.6 10 6.9 9.7 14.3 7.7-2.6 12.5-8 16.4-14.5 4.2 20.2-9.1 50.3-27.2 58.7.4-4.5 5-23.4-16.5-27.7-6.8-1.3-12.8-1.3-22.9-2.1 4.7-9 10.4-20.6.5-22.4-24.9-4.6-52.8 1.9-57.8 4.6 8.2.4 16.3 1 23.5 3.3-2 6.5-4 12.7-5.8 18.9-1.9 6.5 2.1 14.6 9.3 9.6 1.2-.9 2.3-1.9 3.3-2.7-3.1 17.9-2.9 15.9-2.8 18.3.3 10.2 9.5 7.8 15.7 7.3-2.5 11.8-29.5 27.3-45.4 25.8 7-4.7 12.7-10.3 15.9-17.9-6.5.8-12.9 1.6-19.2 2.4l-.3-.9c4.7-3.4 8-7.8 10.2-13.1 8.7-21.1-3.6-38-25-39.9-9.1-.8-17.8.8-25.9 5.5 6.2-15.6 17.2-26.6 32.6-34.5-15.2-4.3-8.9-2.7-24.6-6.3 14.6-9.3 30.2-13.2 46.5-14.6-5.2-3.2-48.1-3.6-70.2 20.9 7.9 1.4 15.5 2.8 23.2 4.2-23.8 7-44 19.7-62.4 35.6 1.1-4.8 2.7-9.5 3.3-14.3.6-4.5.8-9.2.1-13.6-1.5-9.4-8.9-15.1-19.7-16.3-7.9-.9-15.6.1-23.3 1.3-.9.1-1.7.3-2.9 0 15.8-14.8 36-21.7 53.1-33.5 6-4.5 6.8-8.2 3-14.9zm128.4 26.8c3.3 16 12.6 25.5 23.8 24.3-4.6-11.3-12.1-19.5-23.8-24.3z\"],\n    \"d-and-d-beyond\": [640, 512, [], \"f6ca\", \"M313.8 241.5c13.8 0 21-10.1 24.8-17.9-1-1.1-5-4.2-7.4-6.6-2.4 4.3-8.2 10.7-13.9 10.7-10.2 0-15.4-14.7-3.2-26.6-.5-.2-4.3-1.8-8 2.4 0-3 1-5.1 2.1-6.6-3.5 1.3-9.8 5.6-11.4 7.9.2-5.8 1.6-7.5.6-9l-.2-.2s-8.5 5.6-9.3 14.7c0 0 1.1-1.6 2.1-1.9.6-.3 1.3 0 .6 1.9-.2.6-5.8 15.7 5.1 26-.6-1.6-1.9-7.6 2.4-1.9-.3.1 5.8 7.1 15.7 7.1zm52.4-21.1c0-4-4.9-4.4-5.6-4.5 2 3.9.9 7.5.2 9 2.5-.4 5.4-1.6 5.4-4.5zm10.3 5.2c0-6.4-6.2-11.4-13.5-10.7 8 1.3 5.6 13.8-5 11.4 3.7-2.6 3.2-9.9-1.3-12.5 1.4 4.2-3 8.2-7.4 4.6-2.4-1.9-8-6.6-10.6-8.6-2.4-2.1-5.5-1-6.6-1.8-1.3-1.1-.5-3.8-2.2-5-1.6-.8-3-.3-4.8-1-1.6-.6-2.7-1.9-2.6-3.5-2.5 4.4 3.4 6.3 4.5 8.5 1 1.9-.8 4.8 4 8.5 14.8 11.6 9.1 8 10.4 18.1.6 4.3 4.2 6.7 6.4 7.4-2.1-1.9-2.9-6.4 0-9.3 0 13.9 19.2 13.3 23.1 6.4-2.4 1.1-7-.2-9-1.9 7.7 1 14.2-4.1 14.6-10.6zm-39.4-18.4c2 .8 1.6.7 6.4 4.5 10.2-24.5 21.7-15.7 22-15.5 2.2-1.9 9.8-3.8 13.8-2.7-2.4-2.7-7.5-6.2-13.3-6.2-4.7 0-7.4 2.2-8 1.3-.8-1.4 3.2-3.4 3.2-3.4-5.4.2-9.6 6.7-11.2 5.9-1.1-.5 1.4-3.7 1.4-3.7-5.1 2.9-9.3 9.1-10.2 13 4.6-5.8 13.8-9.8 19.7-9-10.5.5-19.5 9.7-23.8 15.8zm242.5 51.9c-20.7 0-40 1.3-50.3 2.1l7.4 8.2v77.2l-7.4 8.2c10.4.8 30.9 2.1 51.6 2.1 42.1 0 59.1-20.7 59.1-48.9 0-29.3-23.2-48.9-60.4-48.9zm-15.1 75.6v-53.3c30.1-3.3 46.8 3.8 46.8 26.3 0 25.6-21.4 30.2-46.8 27zM301.6 181c-1-3.4-.2-6.9 1.1-9.4 1 3 2.6 6.4 7.5 9-.5-2.4-.2-5.6.5-8-1.4-5.4 2.1-9.9 6.4-9.9 6.9 0 8.5 8.8 4.7 14.4 2.1 3.2 5.5 5.6 7.7 7.8 3.2-3.7 5.5-9.5 5.5-13.8 0-8.2-5.5-15.9-16.7-16.5-20-.9-20.2 16.6-20 18.9.5 5.2 3.4 7.8 3.3 7.5zm-.4 6c-.5 1.8-7 3.7-10.2 6.9 4.8-1 7-.2 7.8 1.8.5 1.4-.2 3.4-.5 5.6 1.6-1.8 7-5.5 11-6.2-1-.3-3.4-.8-4.3-.8 2.9-3.4 9.3-4.5 12.8-3.7-2.2-.2-6.7 1.1-8.5 2.6 1.6.3 3 .6 4.3 1.1-2.1.8-4.8 3.4-5.8 6.1 7-5 13.1 5.2 7 8.2.8.2 2.7 0 3.5-.5-.3 1.1-1.9 3-3 3.4 2.9 0 7-1.9 8.2-4.6 0 0-1.8.6-2.6-.2s.3-4.3.3-4.3c-2.3 2.9-3.4-1.3-1.3-4.2-1-.3-3.5-.6-4.6-.5 3.2-1.1 10.4-1.8 11.2-.3.6 1.1-1 3.4-1 3.4 4-.5 8.3 1.1 6.7 5.1 2.9-1.4 5.5-5.9 4.8-10.4-.3 1-1.6 2.4-2.9 2.7.2-1.4-1-2.2-1.9-2.6 1.7-9.6-14.6-14.2-14.1-23.9-1 1.3-1.8 5-.8 7.1 2.7 3.2 8.7 6.7 10.1 12.2-2.6-6.4-15.1-11.4-14.6-20.2-1.6 1.6-2.6 7.8-1.3 11 2.4 1.4 4.5 3.8 4.8 6.1-2.2-5.1-11.4-6.1-13.9-12.2-.6 2.2-.3 5 1 6.7 0 0-2.2-.8-7-.6 1.7.6 5.1 3.5 4.8 5.2zm25.9 7.4c-2.7 0-3.5-2.1-4.2-4.3 3.3 1.3 4.2 4.3 4.2 4.3zm38.9 3.7l-1-.6c-1.1-1-2.9-1.4-4.7-1.4-2.9 0-5.8 1.3-7.5 3.4-.8.8-1.4 1.8-2.1 2.6v15.7c3.5 2.6 7.1-2.9 3-7.2 1.5.3 4.6 2.7 5.1 3.2 0 0 2.6-.5 5-.5 2.1 0 3.9.3 5.6 1.1V196c-1.1.5-2.2 1-2.7 1.4zM79.9 305.9c17.2-4.6 16.2-18 16.2-19.9 0-20.6-24.1-25-37-25H3l8.3 8.6v29.5H0l11.4 14.6V346L3 354.6c61.7 0 73.8 1.5 86.4-5.9 6.7-4 9.9-9.8 9.9-17.6 0-5.1 2.6-18.8-19.4-25.2zm-41.3-27.5c20 0 29.6-.8 29.6 9.1v3c0 12.1-19 8.8-29.6 8.8zm0 59.2V315c12.2 0 32.7-2.3 32.7 8.8v4.5h.2c0 11.2-12.5 9.3-32.9 9.3zm101.2-19.3l23.1.2v-.2l14.1-21.2h-37.2v-14.9h52.4l-14.1-21v-.2l-73.5.2 7.4 8.2v77.1l-7.4 8.2h81.2l14.1-21.2-60.1.2zm214.7-60.1c-73.9 0-77.5 99.3-.3 99.3 77.9 0 74.1-99.3.3-99.3zm-.3 77.5c-37.4 0-36.9-55.3.2-55.3 36.8.1 38.8 55.3-.2 55.3zm-91.3-8.3l44.1-66.2h-41.7l6.1 7.2-20.5 37.2h-.3l-21-37.2 6.4-7.2h-44.9l44.1 65.8.2 19.4-7.7 8.2h42.6l-7.2-8.2zm-28.4-151.3c1.6 1.3 2.9 2.4 2.9 6.6v38.8c0 4.2-.8 5.3-2.7 6.4-.1.1-7.5 4.5-7.9 4.6h35.1c10 0 17.4-1.5 26-8.6-.6-5 .2-9.5.8-12 0-.2-1.8 1.4-2.7 3.5 0-5.7 1.6-15.4 9.6-20.5-.1 0-3.7-.8-9 1.1 2-3.1 10-7.9 10.4-7.9-8.2-26-38-22.9-32.2-22.9-30.9 0-32.6.3-39.9-4 .1.8.5 8.2 9.6 14.9zm21.5 5.5c4.6 0 23.1-3.3 23.1 17.3 0 20.7-18.4 17.3-23.1 17.3zm228.9 79.6l7 8.3V312h-.3c-5.4-14.4-42.3-41.5-45.2-50.9h-31.6l7.4 8.5v76.9l-7.2 8.3h39l-7.4-8.2v-47.4h.3c3.7 10.6 44.5 42.9 48.5 55.6h21.3v-85.2l7.4-8.3zm-106.7-96.1c-32.2 0-32.8.2-39.9-4 .1.7.5 8.3 9.6 14.9 3.1 2 2.9 4.3 2.9 9.5 1.8-1.1 3.8-2.2 6.1-3-1.1 1.1-2.7 2.7-3.5 4.5 1-1.1 7.5-5.1 14.6-3.5-1.6.3-4 1.1-6.1 2.9.1 0 2.1-1.1 7.5-.3v-4.3c4.7 0 23.1-3.4 23.1 17.3 0 20.5-18.5 17.3-19.7 17.3 5.7 4.4 5.8 12 2.2 16.3h.3c33.4 0 36.7-27.3 36.7-34 0-3.8-1.1-32-33.8-33.6z\"],\n    \"dashcube\": [448, 512, [], \"f210\", \"M326.6 104H110.4c-51.1 0-91.2 43.3-91.2 93.5V427c0 50.5 40.1 85 91.2 85h227.2c51.1 0 91.2-34.5 91.2-85V0L326.6 104zM153.9 416.5c-17.7 0-32.4-15.1-32.4-32.8V240.8c0-17.7 14.7-32.5 32.4-32.5h140.7c17.7 0 32 14.8 32 32.5v123.5l51.1 52.3H153.9z\"],\n    \"delicious\": [448, 512, [], \"f1a5\", \"M446.5 68c-.4-1.5-.9-3-1.4-4.5-.9-2.5-2-4.8-3.3-7.1-1.4-2.4-3-4.8-4.7-6.9-2.1-2.5-4.4-4.8-6.9-6.8-1.1-.9-2.2-1.7-3.3-2.5-1.3-.9-2.6-1.7-4-2.4-1.8-1-3.6-1.8-5.5-2.5-1.7-.7-3.5-1.3-5.4-1.7-3.8-1-7.9-1.5-12-1.5H48C21.5 32 0 53.5 0 80v352c0 4.1.5 8.2 1.5 12 2 7.7 5.8 14.6 11 20.3 1 1.1 2.1 2.2 3.3 3.3 5.7 5.2 12.6 9 20.3 11 3.8 1 7.9 1.5 12 1.5h352c26.5 0 48-21.5 48-48V80c-.1-4.1-.6-8.2-1.6-12zM416 432c0 8.8-7.2 16-16 16H224V256H32V80c0-8.8 7.2-16 16-16h176v192h192z\"],\n    \"deploydog\": [512, 512, [], \"f38e\", \"M382.2 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.6 0-33.2 16.4-33.2 32.6zM188.5 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.7 0-33.2 16.4-33.2 32.6zM448 96c17.5 0 32 14.4 32 32v256c0 17.5-14.4 32-32 32H64c-17.5 0-32-14.4-32-32V128c0-17.5 14.4-32 32-32h384m0-32H64C28.8 64 0 92.8 0 128v256c0 35.2 28.8 64 64 64h384c35.2 0 64-28.8 64-64V128c0-35.2-28.8-64-64-64z\"],\n    \"deskpro\": [480, 512, [], \"f38f\", \"M205.9 512l31.1-38.4c12.3-.2 25.6-1.4 36.5-6.6 38.9-18.6 38.4-61.9 38.3-63.8-.1-5-.8-4.4-28.9-37.4H362c-.2 50.1-7.3 68.5-10.2 75.7-9.4 23.7-43.9 62.8-95.2 69.4-8.7 1.1-32.8 1.2-50.7 1.1zm200.4-167.7c38.6 0 58.5-13.6 73.7-30.9l-175.5-.3-17.4 31.3 119.2-.1zm-43.6-223.9v168.3h-73.5l-32.7 55.5H250c-52.3 0-58.1-56.5-58.3-58.9-1.2-13.2-21.3-11.6-20.1 1.8 1.4 15.8 8.8 40 26.4 57.1h-91c-25.5 0-110.8-26.8-107-114V16.9C0 .9 9.7.3 15 .1h82c.2 0 .3.1.5.1 4.3-.4 50.1-2.1 50.1 43.7 0 13.3 20.2 13.4 20.2 0 0-18.2-5.5-32.8-15.8-43.7h84.2c108.7-.4 126.5 79.4 126.5 120.2zm-132.5 56l64 29.3c13.3-45.5-42.2-71.7-64-29.3z\"],\n    \"dev\": [448, 512, [], \"f6cc\", \"M120.12 208.29c-3.88-2.9-7.77-4.35-11.65-4.35H91.03v104.47h17.45c3.88 0 7.77-1.45 11.65-4.35 3.88-2.9 5.82-7.25 5.82-13.06v-69.65c-.01-5.8-1.96-10.16-5.83-13.06zM404.1 32H43.9C19.7 32 .06 51.59 0 75.8v360.4C.06 460.41 19.7 480 43.9 480h360.2c24.21 0 43.84-19.59 43.9-43.8V75.8c-.06-24.21-19.7-43.8-43.9-43.8zM154.2 291.19c0 18.81-11.61 47.31-48.36 47.25h-46.4V172.98h47.38c35.44 0 47.36 28.46 47.37 47.28l.01 70.93zm100.68-88.66H201.6v38.42h32.57v29.57H201.6v38.41h53.29v29.57h-62.18c-11.16.29-20.44-8.53-20.72-19.69V193.7c-.27-11.15 8.56-20.41 19.71-20.69h63.19l-.01 29.52zm103.64 115.29c-13.2 30.75-36.85 24.63-47.44 0l-38.53-144.8h32.57l29.71 113.72 29.57-113.72h32.58l-38.46 144.8z\"],\n    \"deviantart\": [320, 512, [], \"f1bd\", \"M320 93.2l-98.2 179.1 7.4 9.5H320v127.7H159.1l-13.5 9.2-43.7 84c-.3 0-8.6 8.6-9.2 9.2H0v-93.2l93.2-179.4-7.4-9.2H0V102.5h156l13.5-9.2 43.7-84c.3 0 8.6-8.6 9.2-9.2H320v93.1z\"],\n    \"dhl\": [640, 512, [], \"f790\", \"M238 301.2h58.7L319 271h-58.7L238 301.2zM0 282.9v6.4h81.8l4.7-6.4H0zM172.9 271c-8.7 0-6-3.6-4.6-5.5 2.8-3.8 7.6-10.4 10.4-14.1 2.8-3.7 2.8-5.9-2.8-5.9h-51l-41.1 55.8h100.1c33.1 0 51.5-22.5 57.2-30.3h-68.2zm317.5-6.9l39.3-53.4h-62.2l-39.3 53.4h62.2zM95.3 271H0v6.4h90.6l4.7-6.4zm111-26.6c-2.8 3.8-7.5 10.4-10.3 14.2-1.4 2-4.1 5.5 4.6 5.5h45.6s7.3-10 13.5-18.4c8.4-11.4.7-35-29.2-35H112.6l-20.4 27.8h111.4c5.6 0 5.5 2.2 2.7 5.9zM0 301.2h73.1l4.7-6.4H0v6.4zm323 0h58.7L404 271h-58.7c-.1 0-22.3 30.2-22.3 30.2zm222 .1h95v-6.4h-90.3l-4.7 6.4zm22.3-30.3l-4.7 6.4H640V271h-72.7zm-13.5 18.3H640v-6.4h-81.5l-4.7 6.4zm-164.2-78.6l-22.5 30.6h-26.2l22.5-30.6h-58.7l-39.3 53.4H409l39.3-53.4h-58.7zm33.5 60.3s-4.3 5.9-6.4 8.7c-7.4 10-.9 21.6 23.2 21.6h94.3l22.3-30.3H423.1z\"],\n    \"diaspora\": [512, 512, [], \"f791\", \"M251.64 354.55c-1.4 0-88 119.9-88.7 119.9S76.34 414 76 413.25s86.6-125.7 86.6-127.4c0-2.2-129.6-44-137.6-47.1-1.3-.5 31.4-101.8 31.7-102.1.6-.7 144.4 47 145.5 47 .4 0 .9-.6 1-1.3.4-2 1-148.6 1.7-149.6.8-1.2 104.5-.7 105.1-.3 1.5 1 3.5 156.1 6.1 156.1 1.4 0 138.7-47 139.3-46.3.8.9 31.9 102.2 31.5 102.6-.9.9-140.2 47.1-140.6 48.8-.3 1.4 82.8 122.1 82.5 122.9s-85.5 63.5-86.3 63.5c-1-.2-89-125.5-90.9-125.5z\"],\n    \"digg\": [512, 512, [], \"f1a6\", \"M81.7 172.3H0v174.4h132.7V96h-51v76.3zm0 133.4H50.9v-92.3h30.8v92.3zm297.2-133.4v174.4h81.8v28.5h-81.8V416H512V172.3H378.9zm81.8 133.4h-30.8v-92.3h30.8v92.3zm-235.6 41h82.1v28.5h-82.1V416h133.3V172.3H225.1v174.4zm51.2-133.3h30.8v92.3h-30.8v-92.3zM153.3 96h51.3v51h-51.3V96zm0 76.3h51.3v174.4h-51.3V172.3z\"],\n    \"digital-ocean\": [512, 512, [], \"f391\", \"M87 481.8h73.7v-73.6H87zM25.4 346.6v61.6H87v-61.6zm466.2-169.7c-23-74.2-82.4-133.3-156.6-156.6C164.9-32.8 8 93.7 8 255.9h95.8c0-101.8 101-180.5 208.1-141.7 39.7 14.3 71.5 46.1 85.8 85.7 39.1 107-39.7 207.8-141.4 208v.3h-.3V504c162.6 0 288.8-156.8 235.6-327.1zm-235.3 231v-95.3h-95.6v95.6H256v-.3z\"],\n    \"discord\": [448, 512, [], \"f392\", \"M297.216 243.2c0 15.616-11.52 28.416-26.112 28.416-14.336 0-26.112-12.8-26.112-28.416s11.52-28.416 26.112-28.416c14.592 0 26.112 12.8 26.112 28.416zm-119.552-28.416c-14.592 0-26.112 12.8-26.112 28.416s11.776 28.416 26.112 28.416c14.592 0 26.112-12.8 26.112-28.416.256-15.616-11.52-28.416-26.112-28.416zM448 52.736V512c-64.494-56.994-43.868-38.128-118.784-107.776l13.568 47.36H52.48C23.552 451.584 0 428.032 0 398.848V52.736C0 23.552 23.552 0 52.48 0h343.04C424.448 0 448 23.552 448 52.736zm-72.96 242.688c0-82.432-36.864-149.248-36.864-149.248-36.864-27.648-71.936-26.88-71.936-26.88l-3.584 4.096c43.52 13.312 63.744 32.512 63.744 32.512-60.811-33.329-132.244-33.335-191.232-7.424-9.472 4.352-15.104 7.424-15.104 7.424s21.248-20.224 67.328-33.536l-2.56-3.072s-35.072-.768-71.936 26.88c0 0-36.864 66.816-36.864 149.248 0 0 21.504 37.12 78.08 38.912 0 0 9.472-11.52 17.152-21.248-32.512-9.728-44.8-30.208-44.8-30.208 3.766 2.636 9.976 6.053 10.496 6.4 43.21 24.198 104.588 32.126 159.744 8.96 8.96-3.328 18.944-8.192 29.44-15.104 0 0-12.8 20.992-46.336 30.464 7.68 9.728 16.896 20.736 16.896 20.736 56.576-1.792 78.336-38.912 78.336-38.912z\"],\n    \"discourse\": [448, 512, [], \"f393\", \"M225.9 32C103.3 32 0 130.5 0 252.1 0 256 .1 480 .1 480l225.8-.2c122.7 0 222.1-102.3 222.1-223.9C448 134.3 348.6 32 225.9 32zM224 384c-19.4 0-37.9-4.3-54.4-12.1L88.5 392l22.9-75c-9.8-18.1-15.4-38.9-15.4-61 0-70.7 57.3-128 128-128s128 57.3 128 128-57.3 128-128 128z\"],\n    \"dochub\": [416, 512, [], \"f394\", \"M397.9 160H256V19.6L397.9 160zM304 192v130c0 66.8-36.5 100.1-113.3 100.1H96V84.8h94.7c12 0 23.1.8 33.1 2.5v-84C212.9 1.1 201.4 0 189.2 0H0v512h189.2C329.7 512 400 447.4 400 318.1V192h-96z\"],\n    \"docker\": [640, 512, [], \"f395\", \"M349.9 236.3h-66.1v-59.4h66.1v59.4zm0-204.3h-66.1v60.7h66.1V32zm78.2 144.8H362v59.4h66.1v-59.4zm-156.3-72.1h-66.1v60.1h66.1v-60.1zm78.1 0h-66.1v60.1h66.1v-60.1zm276.8 100c-14.4-9.7-47.6-13.2-73.1-8.4-3.3-24-16.7-44.9-41.1-63.7l-14-9.3-9.3 14c-18.4 27.8-23.4 73.6-3.7 103.8-8.7 4.7-25.8 11.1-48.4 10.7H2.4c-8.7 50.8 5.8 116.8 44 162.1 37.1 43.9 92.7 66.2 165.4 66.2 157.4 0 273.9-72.5 328.4-204.2 21.4.4 67.6.1 91.3-45.2 1.5-2.5 6.6-13.2 8.5-17.1l-13.3-8.9zm-511.1-27.9h-66v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm-78.1-72.1h-66.1v60.1h66.1v-60.1z\"],\n    \"draft2digital\": [480, 512, [], \"f396\", \"M480 398.1l-144-82.2v64.7h-91.3c30.8-35 81.8-95.9 111.8-149.3 35.2-62.6 16.1-123.4-12.8-153.3-4.4-4.6-62.2-62.9-166-41.2-59.1 12.4-89.4 43.4-104.3 67.3-13.1 20.9-17 39.8-18.2 47.7-5.5 33 19.4 67.1 56.7 67.1 31.7 0 57.3-25.7 57.3-57.4 0-27.1-19.7-52.1-48-56.8 1.8-7.3 17.7-21.1 26.3-24.7 41.1-17.3 78 5.2 83.3 33.5 8.3 44.3-37.1 90.4-69.7 127.6C84.5 328.1 18.3 396.8 0 415.9l336-.1V480zM369.9 371l47.1 27.2-47.1 27.2zM134.2 161.4c0 12.4-10 22.4-22.4 22.4s-22.4-10-22.4-22.4 10-22.4 22.4-22.4 22.4 10.1 22.4 22.4zM82.5 380.5c25.6-27.4 97.7-104.7 150.8-169.9 35.1-43.1 40.3-82.4 28.4-112.7-7.4-18.8-17.5-30.2-24.3-35.7 45.3 2.1 68 23.4 82.2 38.3 0 0 42.4 48.2 5.8 113.3-37 65.9-110.9 147.5-128.5 166.7z\"],\n    \"dribbble\": [512, 512, [], \"f17d\", \"M256 8C119.252 8 8 119.252 8 256s111.252 248 248 248 248-111.252 248-248S392.748 8 256 8zm163.97 114.366c29.503 36.046 47.369 81.957 47.835 131.955-6.984-1.477-77.018-15.682-147.502-6.818-5.752-14.041-11.181-26.393-18.617-41.614 78.321-31.977 113.818-77.482 118.284-83.523zM396.421 97.87c-3.81 5.427-35.697 48.286-111.021 76.519-34.712-63.776-73.185-116.168-79.04-124.008 67.176-16.193 137.966 1.27 190.061 47.489zm-230.48-33.25c5.585 7.659 43.438 60.116 78.537 122.509-99.087 26.313-186.36 25.934-195.834 25.809C62.38 147.205 106.678 92.573 165.941 64.62zM44.17 256.323c0-2.166.043-4.322.108-6.473 9.268.19 111.92 1.513 217.706-30.146 6.064 11.868 11.857 23.915 17.174 35.949-76.599 21.575-146.194 83.527-180.531 142.306C64.794 360.405 44.17 310.73 44.17 256.323zm81.807 167.113c22.127-45.233 82.178-103.622 167.579-132.756 29.74 77.283 42.039 142.053 45.189 160.638-68.112 29.013-150.015 21.053-212.768-27.882zm248.38 8.489c-2.171-12.886-13.446-74.897-41.152-151.033 66.38-10.626 124.7 6.768 131.947 9.055-9.442 58.941-43.273 109.844-90.795 141.978z\"],\n    \"dribbble-square\": [448, 512, [], \"f397\", \"M90.2 228.2c8.9-42.4 37.4-77.7 75.7-95.7 3.6 4.9 28 38.8 50.7 79-64 17-120.3 16.8-126.4 16.7zM314.6 154c-33.6-29.8-79.3-41.1-122.6-30.6 3.8 5.1 28.6 38.9 51 80 48.6-18.3 69.1-45.9 71.6-49.4zM140.1 364c40.5 31.6 93.3 36.7 137.3 18-2-12-10-53.8-29.2-103.6-55.1 18.8-93.8 56.4-108.1 85.6zm98.8-108.2c-3.4-7.8-7.2-15.5-11.1-23.2C159.6 253 93.4 252.2 87.4 252c0 1.4-.1 2.8-.1 4.2 0 35.1 13.3 67.1 35.1 91.4 22.2-37.9 67.1-77.9 116.5-91.8zm34.9 16.3c17.9 49.1 25.1 89.1 26.5 97.4 30.7-20.7 52.5-53.6 58.6-91.6-4.6-1.5-42.3-12.7-85.1-5.8zm-20.3-48.4c4.8 9.8 8.3 17.8 12 26.8 45.5-5.7 90.7 3.4 95.2 4.4-.3-32.3-11.8-61.9-30.9-85.1-2.9 3.9-25.8 33.2-76.3 53.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 176c0-88.2-71.8-160-160-160S64 167.8 64 256s71.8 160 160 160 160-71.8 160-160z\"],\n    \"dropbox\": [528, 512, [], \"f16b\", \"M264.4 116.3l-132 84.3 132 84.3-132 84.3L0 284.1l132.3-84.3L0 116.3 132.3 32l132.1 84.3zM131.6 395.7l132-84.3 132 84.3-132 84.3-132-84.3zm132.8-111.6l132-84.3-132-83.6L395.7 32 528 116.3l-132.3 84.3L528 284.8l-132.3 84.3-131.3-85z\"],\n    \"drupal\": [448, 512, [], \"f1a9\", \"M319.5 114.7c-22.2-14-43.5-19.5-64.7-33.5-13-8.8-31.3-30-46.5-48.3-2.7 29.3-11.5 41.2-22 49.5-21.3 17-34.8 22.2-53.5 32.3C117 123 32 181.5 32 290.5 32 399.7 123.8 480 225.8 480 327.5 480 416 406 416 294c0-112.3-83-171-96.5-179.3zm2.5 325.6c-20.1 20.1-90.1 28.7-116.7 4.2-4.8-4.8.3-12 6.5-12 0 0 17 13.3 51.5 13.3 27 0 46-7.7 54.5-14 6.1-4.6 8.4 4.3 4.2 8.5zm-54.5-52.6c8.7-3.6 29-3.8 36.8 1.3 4.1 2.8 16.1 18.8 6.2 23.7-8.4 4.2-1.2-15.7-26.5-15.7-14.7 0-19.5 5.2-26.7 11-7 6-9.8 8-12.2 4.7-6-8.2 15.9-22.3 22.4-25zM360 405c-15.2-1-45.5-48.8-65-49.5-30.9-.9-104.1 80.7-161.3 42-38.8-26.6-14.6-104.8 51.8-105.2 49.5-.5 83.8 49 108.5 48.5 21.3-.3 61.8-41.8 81.8-41.8 48.7 0 23.3 109.3-15.8 106z\"],\n    \"dyalog\": [416, 512, [], \"f399\", \"M0 32v119.2h64V96h107.2C284.6 96 352 176.2 352 255.9 352 332 293.4 416 171.2 416H0v64h171.2C331.9 480 416 367.3 416 255.9c0-58.7-22.1-113.4-62.3-154.3C308.9 56 245.7 32 171.2 32H0z\"],\n    \"earlybirds\": [480, 512, [], \"f39a\", \"M313.2 47.5c1.2-13 21.3-14 36.6-8.7.9.3 26.2 9.7 19 15.2-27.9-7.4-56.4 18.2-55.6-6.5zm-201 6.9c30.7-8.1 62 20 61.1-7.1-1.3-14.2-23.4-15.3-40.2-9.6-1 .3-28.7 10.5-20.9 16.7zM319.4 160c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-159.7 0c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm318.5 163.2c-9.9 24-40.7 11-63.9-1.2-13.5 69.1-58.1 111.4-126.3 124.2.3.9-2-.1 24 1 33.6 1.4 63.8-3.1 97.4-8-19.8-13.8-11.4-37.1-9.8-38.1 1.4-.9 14.7 1.7 21.6 11.5 8.6-12.5 28.4-14.8 30.2-13.6 1.6 1.1 6.6 20.9-6.9 34.6 4.7-.9 8.2-1.6 9.8-2.1 2.6-.8 17.7 11.3 3.1 13.3-14.3 2.3-22.6 5.1-47.1 10.8-45.9 10.7-85.9 11.8-117.7 12.8l1 11.6c3.8 18.1-23.4 24.3-27.6 6.2.8 17.9-27.1 21.8-28.4-1l-.5 5.3c-.7 18.4-28.4 17.9-28.3-.6-7.5 13.5-28.1 6.8-26.4-8.5l1.2-12.4c-36.7.9-59.7 3.1-61.8 3.1-20.9 0-20.9-31.6 0-31.6 2.4 0 27.7 1.3 63.2 2.8-61.1-15.5-103.7-55-114.9-118.2-25 12.8-57.5 26.8-68.2.8-10.5-25.4 21.5-42.6 66.8-73.4.7-6.6 1.6-13.3 2.7-19.8-14.4-19.6-11.6-36.3-16.1-60.4-16.8 2.4-23.2-9.1-23.6-23.1.3-7.3 2.1-14.9 2.4-15.4 1.1-1.8 10.1-2 12.7-2.6 6-31.7 50.6-33.2 90.9-34.5 19.7-21.8 45.2-41.5 80.9-48.3C203.3 29 215.2 8.5 216.2 8c1.7-.8 21.2 4.3 26.3 23.2 5.2-8.8 18.3-11.4 19.6-10.7 1.1.6 6.4 15-4.9 25.9 40.3 3.5 72.2 24.7 96 50.7 36.1 1.5 71.8 5.9 77.1 34 2.7.6 11.6.8 12.7 2.6.3.5 2.1 8.1 2.4 15.4-.5 13.9-6.8 25.4-23.6 23.1-3.2 17.3-2.7 32.9-8.7 47.7 2.4 11.7 4 23.8 4.8 36.4 37 25.4 70.3 42.5 60.3 66.9zM207.4 159.9c.9-44-37.9-42.2-78.6-40.3-21.7 1-38.9 1.9-45.5 13.9-11.4 20.9 5.9 92.9 23.2 101.2 9.8 4.7 73.4 7.9 86.3-7.1 8.2-9.4 15-49.4 14.6-67.7zm52 58.3c-4.3-12.4-6-30.1-15.3-32.7-2-.5-9-.5-11 0-10 2.8-10.8 22.1-17 37.2 15.4 0 19.3 9.7 23.7 9.7 4.3 0 6.3-11.3 19.6-14.2zm135.7-84.7c-6.6-12.1-24.8-12.9-46.5-13.9-40.2-1.9-78.2-3.8-77.3 40.3-.5 18.3 5 58.3 13.2 67.8 13 14.9 76.6 11.8 86.3 7.1 15.8-7.6 36.5-78.9 24.3-101.3z\"],\n    \"ebay\": [640, 512, [], \"f4f4\", \"M606 189.5l-54.8 109.9-54.9-109.9h-37.5l10.9 20.6c-11.5-19-35.9-26-63.3-26-31.8 0-67.9 8.7-71.5 43.1h33.7c1.4-13.8 15.7-21.8 35-21.8 26 0 41 9.6 41 33v3.4c-12.7 0-28 .1-41.7.4-42.4.9-69.6 10-76.7 34.4 1-5.2 1.5-10.6 1.5-16.2 0-52.1-39.7-76.2-75.4-76.2-21.3 0-43 5.5-58.7 24.2v-80.6h-32.1v169.5c0 10.3-.6 22.9-1.1 33.1h31.5c.7-6.3 1.1-12.9 1.1-19.5 13.6 16.6 35.4 24.9 58.7 24.9 36.9 0 64.9-21.9 73.3-54.2-.5 2.8-.7 5.8-.7 9 0 24.1 21.1 45 60.6 45 26.6 0 45.8-5.7 61.9-25.5 0 6.6.3 13.3 1.1 20.2h29.8c-.7-8.2-1-17.5-1-26.8v-65.6c0-9.3-1.7-17.2-4.8-23.8l61.5 116.1-28.5 54.1h35.9L640 189.5zM243.7 313.8c-29.6 0-50.2-21.5-50.2-53.8 0-32.4 20.6-53.8 50.2-53.8 29.8 0 50.2 21.4 50.2 53.8 0 32.3-20.4 53.8-50.2 53.8zm200.9-47.3c0 30-17.9 48.4-51.6 48.4-25.1 0-35-13.4-35-25.8 0-19.1 18.1-24.4 47.2-25.3 13.1-.5 27.6-.6 39.4-.6zm-411.9 1.6h128.8v-8.5c0-51.7-33.1-75.4-78.4-75.4-56.8 0-83 30.8-83 77.6 0 42.5 25.3 74 82.5 74 31.4 0 68-11.7 74.4-46.1h-33.1c-12 35.8-87.7 36.7-91.2-21.6zm95-21.4H33.3c6.9-56.6 92.1-54.7 94.4 0z\"],\n    \"edge\": [512, 512, [], \"f282\", \"M25.714 228.163c.111-.162.23-.323.342-.485-.021.162-.045.323-.065.485h-.277zm460.572 15.508c0-44.032-7.754-84.465-28.801-122.405C416.498 47.879 343.912 8.001 258.893 8.001 118.962 7.724 40.617 113.214 26.056 227.679c42.429-61.312 117.073-121.376 220.375-124.966 0 0 109.666 0 99.419 104.957H169.997c6.369-37.386 18.554-58.986 34.339-78.926-75.048 34.893-121.85 96.096-120.742 188.315.83 71.448 50.124 144.836 120.743 171.976 83.357 31.847 192.776 7.2 240.132-21.324V363.307c-80.864 56.494-270.871 60.925-272.255-67.572h314.073v-52.064z\"],\n    \"elementor\": [448, 512, [], \"f430\", \"M425.6 32H22.4C10 32 0 42 0 54.4v403.2C0 470 10 480 22.4 480h403.2c12.4 0 22.4-10 22.4-22.4V54.4C448 42 438 32 425.6 32M164.3 355.5h-39.8v-199h39.8v199zm159.3 0H204.1v-39.8h119.5v39.8zm0-79.6H204.1v-39.8h119.5v39.8zm0-79.7H204.1v-39.8h119.5v39.8z\"],\n    \"ello\": [496, 512, [], \"f5f1\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm143.84 285.2C375.31 358.51 315.79 404.8 248 404.8s-127.31-46.29-143.84-111.6c-1.65-7.44 2.48-15.71 9.92-17.36 7.44-1.65 15.71 2.48 17.36 9.92 14.05 52.91 62 90.11 116.56 90.11s102.51-37.2 116.56-90.11c1.65-7.44 9.92-12.4 17.36-9.92 7.44 1.65 12.4 9.92 9.92 17.36z\"],\n    \"ember\": [640, 512, [], \"f423\", \"M639.9 254.6c-1.1-10.7-10.7-6.8-10.7-6.8s-15.6 12.1-29.3 10.7c-13.7-1.3-9.4-32-9.4-32s3-28.1-5.1-30.4c-8.1-2.4-18 7.3-18 7.3s-12.4 13.7-18.3 31.2l-1.6.5s1.9-30.6-.3-37.6c-1.6-3.5-16.4-3.2-18.8 3s-14.2 49.2-15 67.2c0 0-23.1 19.6-43.3 22.8s-25-9.4-25-9.4 54.8-15.3 52.9-59.1-44.2-27.6-49-24c-4.6 3.5-29.4 18.4-36.6 59.7-.2 1.4-.7 7.5-.7 7.5s-21.2 14.2-33 18c0 0 33-55.6-7.3-80.9-11.4-6.8-21.3-.5-27.2 5.3 13.6-17.3 46.4-64.2 36.9-105.2-5.8-24.4-18-27.1-29.2-23.1-17 6.7-23.5 16.7-23.5 16.7s-22 32-27.1 79.5-12.6 105.1-12.6 105.1-10.5 10.2-20.2 10.7-5.4-28.7-5.4-28.7 7.5-44.6 7-52.1-1.1-11.6-9.9-14.2c-8.9-2.7-18.5 8.6-18.5 8.6s-25.5 38.7-27.7 44.6l-1.3 2.4-1.3-1.6s18-52.7.8-53.5-28.5 18.8-28.5 18.8-19.6 32.8-20.4 36.5l-1.3-1.6s8.1-38.2 6.4-47.6c-1.6-9.4-10.5-7.5-10.5-7.5s-11.3-1.3-14.2 5.9-13.7 55.3-15 70.7c0 0-28.2 20.2-46.8 20.4-18.5.3-16.7-11.8-16.7-11.8s68-23.3 49.4-69.2c-8.3-11.8-18-15.5-31.7-15.3-13.7.3-30.3 8.6-41.3 33.3-5.3 11.8-6.8 23-7.8 31.5 0 0-12.3 2.4-18.8-2.9s-10 0-10 0-11.2 14-.1 18.3 28.1 6.1 28.1 6.1c1.6 7.5 6.2 19.5 19.6 29.7 20.2 15.3 58.8-1.3 58.8-1.3l15.9-8.8s.5 14.6 12.1 16.7 16.4 1 36.5-47.9c11.8-25 12.6-23.6 12.6-23.6l1.3-.3s-9.1 46.8-5.6 59.7C187.7 319.4 203 318 203 318s8.3 2.4 15-21.2 19.6-49.9 19.6-49.9h1.6s-5.6 48.1 3 63.7 30.9 5.3 30.9 5.3 15.6-7.8 18-10.2c0 0 18.5 15.8 44.6 12.9 58.3-11.5 79.1-25.9 79.1-25.9s10 24.4 41.1 26.7c35.5 2.7 54.8-18.6 54.8-18.6s-.3 13.5 12.1 18.6 20.7-22.8 20.7-22.8l20.7-57.2h1.9s1.1 37.3 21.5 43.2 47-13.7 47-13.7 6.4-3.5 5.3-14.3zm-578 5.3c.8-32 21.8-45.9 29-39 7.3 7 4.6 22-9.1 31.4-13.7 9.5-19.9 7.6-19.9 7.6zm272.8-123.8s19.1-49.7 23.6-25.5-40 96.2-40 96.2c.5-16.2 16.4-70.7 16.4-70.7zm22.8 138.4c-12.6 33-43.3 19.6-43.3 19.6s-3.5-11.8 6.4-44.9 33.3-20.2 33.3-20.2 16.2 12.4 3.6 45.5zm84.6-14.6s-3-10.5 8.1-30.6c11-20.2 19.6-9.1 19.6-9.1s9.4 10.2-1.3 25.5-26.4 14.2-26.4 14.2z\"],\n    \"empire\": [496, 512, [], \"f1d1\", \"M287.6 54.2c-10.8-2.2-22.1-3.3-33.5-3.6V32.4c78.1 2.2 146.1 44 184.6 106.6l-15.8 9.1c-6.1-9.7-12.7-18.8-20.2-27.1l-18 15.5c-26-29.6-61.4-50.7-101.9-58.4l4.8-23.9zM53.4 322.4l23-7.7c-6.4-18.3-10-38.2-10-58.7s3.3-40.4 9.7-58.7l-22.7-7.7c3.6-10.8 8.3-21.3 13.6-31l-15.8-9.1C34 181 24.1 217.5 24.1 256s10 75 27.1 106.6l15.8-9.1c-5.3-10-9.7-20.3-13.6-31.1zM213.1 434c-40.4-8-75.8-29.1-101.9-58.7l-18 15.8c-7.5-8.6-14.4-17.7-20.2-27.4l-16 9.4c38.5 62.3 106.8 104.3 184.9 106.6v-18.3c-11.3-.3-22.7-1.7-33.5-3.6l4.7-23.8zM93.3 120.9l18 15.5c26-29.6 61.4-50.7 101.9-58.4l-4.7-23.8c10.8-2.2 22.1-3.3 33.5-3.6V32.4C163.9 34.6 95.9 76.4 57.4 139l15.8 9.1c6-9.7 12.6-18.9 20.1-27.2zm309.4 270.2l-18-15.8c-26 29.6-61.4 50.7-101.9 58.7l4.7 23.8c-10.8 1.9-22.1 3.3-33.5 3.6v18.3c78.1-2.2 146.4-44.3 184.9-106.6l-16.1-9.4c-5.7 9.7-12.6 18.8-20.1 27.4zM496 256c0 137-111 248-248 248S0 393 0 256 111 8 248 8s248 111 248 248zm-12.2 0c0-130.1-105.7-235.8-235.8-235.8S12.2 125.9 12.2 256 117.9 491.8 248 491.8 483.8 386.1 483.8 256zm-39-106.6l-15.8 9.1c5.3 9.7 10 20.2 13.6 31l-22.7 7.7c6.4 18.3 9.7 38.2 9.7 58.7s-3.6 40.4-10 58.7l23 7.7c-3.9 10.8-8.3 21-13.6 31l15.8 9.1C462 331 471.9 294.5 471.9 256s-9.9-75-27.1-106.6zm-183 177.7c16.3-3.3 30.4-11.6 40.7-23.5l51.2 44.8c11.9-13.6 21.3-29.3 27.1-46.8l-64.2-22.1c2.5-7.5 3.9-15.2 3.9-23.5s-1.4-16.1-3.9-23.5l64.5-22.1c-6.1-17.4-15.5-33.2-27.4-46.8l-51.2 44.8c-10.2-11.9-24.4-20.5-40.7-23.8l13.3-66.4c-8.6-1.9-17.7-2.8-27.1-2.8-9.4 0-18.5.8-27.1 2.8l13.3 66.4c-16.3 3.3-30.4 11.9-40.7 23.8l-51.2-44.8c-11.9 13.6-21.3 29.3-27.4 46.8l64.5 22.1c-2.5 7.5-3.9 15.2-3.9 23.5s1.4 16.1 3.9 23.5l-64.2 22.1c5.8 17.4 15.2 33.2 27.1 46.8l51.2-44.8c10.2 11.9 24.4 20.2 40.7 23.5l-13.3 66.7c8.6 1.7 17.7 2.8 27.1 2.8 9.4 0 18.5-1.1 27.1-2.8l-13.3-66.7z\"],\n    \"envira\": [448, 512, [], \"f299\", \"M0 32c477.6 0 366.6 317.3 367.1 366.3L448 480h-26l-70.4-71.2c-39 4.2-124.4 34.5-214.4-37C47 300.3 52 214.7 0 32zm79.7 46c-49.7-23.5-5.2 9.2-5.2 9.2 45.2 31.2 66 73.7 90.2 119.9 31.5 60.2 79 139.7 144.2 167.7 65 28 34.2 12.5 6-8.5-28.2-21.2-68.2-87-91-130.2-31.7-60-61-118.6-144.2-158.1z\"],\n    \"erlang\": [640, 512, [], \"f39d\", \"M87.2 53.5H0v405h100.4c-49.7-52.6-78.8-125.3-78.7-212.1-.1-76.7 24-142.7 65.5-192.9zm238.2 9.7c-45.9.1-85.1 33.5-89.2 83.2h169.9c-1.1-49.7-34.5-83.1-80.7-83.2zm230.7-9.6h.3l-.1-.1zm.3 0c31.4 42.7 48.7 97.5 46.2 162.7.5 6 .5 11.7 0 24.1H230.2c-.2 109.7 38.9 194.9 138.6 195.3 68.5-.3 118-51 151.9-106.1l96.4 48.2c-17.4 30.9-36.5 57.8-57.9 80.8H640v-405z\"],\n    \"ethereum\": [320, 512, [], \"f42e\", \"M311.9 260.8L160 353.6 8 260.8 160 0l151.9 260.8zM160 383.4L8 290.6 160 512l152-221.4-152 92.8z\"],\n    \"etsy\": [384, 512, [], \"f2d7\", \"M384 348c-1.75 10.75-13.75 110-15.5 132-117.879-4.299-219.895-4.743-368.5 0v-25.5c45.457-8.948 60.627-8.019 61-35.25 1.793-72.322 3.524-244.143 0-322-1.029-28.46-12.13-26.765-61-36v-25.5c73.886 2.358 255.933 8.551 362.999-3.75-3.5 38.25-7.75 126.5-7.75 126.5H332C320.947 115.665 313.241 68 277.25 68h-137c-10.25 0-10.75 3.5-10.75 9.75V241.5c58 .5 88.5-2.5 88.5-2.5 29.77-.951 27.56-8.502 40.75-65.251h25.75c-4.407 101.351-3.91 61.829-1.75 160.25H257c-9.155-40.086-9.065-61.045-39.501-61.5 0 0-21.5-2-88-2v139c0 26 14.25 38.25 44.25 38.25H263c63.636 0 66.564-24.996 98.751-99.75H384z\"],\n    \"evernote\": [384, 512, [], \"f839\", \"M120.82 132.21c1.6 22.31-17.55 21.59-21.61 21.59-68.93 0-73.64-1-83.58 3.34-.56.22-.74 0-.37-.37L123.79 46.45c.38-.37.6-.22.38.37-4.35 9.99-3.35 15.09-3.35 85.39zm79 308c-14.68-37.08 13-76.93 52.52-76.62 17.49 0 22.6 23.21 7.95 31.42-6.19 3.3-24.95 1.74-25.14 19.2-.05 17.09 19.67 25 31.2 24.89A45.64 45.64 0 0 0 312 393.45v-.08c0-11.63-7.79-47.22-47.54-55.34-7.72-1.54-65-6.35-68.35-50.52-3.74 16.93-17.4 63.49-43.11 69.09-8.74 1.94-69.68 7.64-112.92-36.77 0 0-18.57-15.23-28.23-57.95-3.38-15.75-9.28-39.7-11.14-62 0-18 11.14-30.45 25.07-32.2 81 0 90 2.32 101-7.8 9.82-9.24 7.8-15.5 7.8-102.78 1-8.3 7.79-30.81 53.41-24.14 6 .86 31.91 4.18 37.48 30.64l64.26 11.15c20.43 3.71 70.94 7 80.6 57.94 22.66 121.09 8.91 238.46 7.8 238.46C362.15 485.53 267.06 480 267.06 480c-18.95-.23-54.25-9.4-67.27-39.83zm80.94-204.84c-1 1.92-2.2 6 .85 7 14.09 4.93 39.75 6.84 45.88 5.53 3.11-.25 3.05-4.43 2.48-6.65-3.53-21.85-40.83-26.5-49.24-5.92z\"],\n    \"expeditedssl\": [496, 512, [], \"f23e\", \"M248 43.4C130.6 43.4 35.4 138.6 35.4 256S130.6 468.6 248 468.6 460.6 373.4 460.6 256 365.4 43.4 248 43.4zm-97.4 132.9c0-53.7 43.7-97.4 97.4-97.4s97.4 43.7 97.4 97.4v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6c0-82.1-124-82.1-124 0v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6zM389.7 380c0 9.7-8 17.7-17.7 17.7H124c-9.7 0-17.7-8-17.7-17.7V238.3c0-9.7 8-17.7 17.7-17.7h248c9.7 0 17.7 8 17.7 17.7V380zm-248-137.3v132.9c0 2.5-1.9 4.4-4.4 4.4h-8.9c-2.5 0-4.4-1.9-4.4-4.4V242.7c0-2.5 1.9-4.4 4.4-4.4h8.9c2.5 0 4.4 1.9 4.4 4.4zm141.7 48.7c0 13-7.2 24.4-17.7 30.4v31.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-31.6c-10.5-6.1-17.7-17.4-17.7-30.4 0-19.7 15.8-35.4 35.4-35.4s35.5 15.8 35.5 35.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 478.3C121 486.3 17.7 383 17.7 256S121 25.7 248 25.7 478.3 129 478.3 256 375 486.3 248 486.3z\"],\n    \"facebook\": [512, 512, [], \"f09a\", \"M504 256C504 119 393 8 256 8S8 119 8 256c0 123.78 90.69 226.38 209.25 245V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.28c-30.8 0-40.41 19.12-40.41 38.73V256h68.78l-11 71.69h-57.78V501C413.31 482.38 504 379.78 504 256z\"],\n    \"facebook-f\": [320, 512, [], \"f39e\", \"M279.14 288l14.22-92.66h-88.91v-60.13c0-25.35 12.42-50.06 52.24-50.06h40.42V6.26S260.43 0 225.36 0c-73.22 0-121.08 44.38-121.08 124.72v70.62H22.89V288h81.39v224h100.17V288z\"],\n    \"facebook-messenger\": [512, 512, [], \"f39f\", \"M256.55 8C116.52 8 8 110.34 8 248.57c0 72.3 29.71 134.78 78.07 177.94 8.35 7.51 6.63 11.86 8.05 58.23A19.92 19.92 0 0 0 122 502.31c52.91-23.3 53.59-25.14 62.56-22.7C337.85 521.8 504 423.7 504 248.57 504 110.34 396.59 8 256.55 8zm149.24 185.13l-73 115.57a37.37 37.37 0 0 1-53.91 9.93l-58.08-43.47a15 15 0 0 0-18 0l-78.37 59.44c-10.46 7.93-24.16-4.6-17.11-15.67l73-115.57a37.36 37.36 0 0 1 53.91-9.93l58.06 43.46a15 15 0 0 0 18 0l78.41-59.38c10.44-7.98 24.14 4.54 17.09 15.62z\"],\n    \"facebook-square\": [448, 512, [], \"f082\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h137.25V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.27c-30.81 0-40.42 19.12-40.42 38.73V256h68.78l-11 71.69h-57.78V480H400a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48z\"],\n    \"fantasy-flight-games\": [512, 512, [], \"f6dc\", \"M256 32.86L32.86 256 256 479.14 479.14 256 256 32.86zM88.34 255.83c1.96-2 11.92-12.3 96.49-97.48 41.45-41.75 86.19-43.77 119.77-18.69 24.63 18.4 62.06 58.9 62.15 59 .68.74 1.07 2.86.58 3.38-11.27 11.84-22.68 23.54-33.5 34.69-34.21-32.31-40.52-38.24-48.51-43.95-17.77-12.69-41.4-10.13-56.98 5.1-2.17 2.13-1.79 3.43.12 5.35 2.94 2.95 28.1 28.33 35.09 35.78-11.95 11.6-23.66 22.97-35.69 34.66-12.02-12.54-24.48-25.53-36.54-38.11-21.39 21.09-41.69 41.11-61.85 60.99a42569.01 42569.01 0 0 1-41.13-40.72zm234.82 101.6c-35.49 35.43-78.09 38.14-106.99 20.47-22.08-13.5-39.38-32.08-72.93-66.84 12.05-12.37 23.79-24.42 35.37-36.31 33.02 31.91 37.06 36.01 44.68 42.09 18.48 14.74 42.52 13.67 59.32-1.8 3.68-3.39 3.69-3.64.14-7.24-10.59-10.73-21.19-21.44-31.77-32.18-1.32-1.34-3.03-2.48-.8-4.69 10.79-10.71 21.48-21.52 32.21-32.29.26-.26.65-.38 1.91-1.07 12.37 12.87 24.92 25.92 37.25 38.75 21.01-20.73 41.24-40.68 61.25-60.42 13.68 13.4 27.13 26.58 40.86 40.03-20.17 20.86-81.68 82.71-100.5 101.5zM256 0L0 256l256 256 256-256L256 0zM16 256L256 16l240 240-240 240L16 256z\"],\n    \"fedex\": [640, 512, [], \"f797\", \"M586 284.5l53.3-59.9h-62.4l-21.7 24.8-22.5-24.8H414v-16h56.1v-48.1H318.9V236h-.5c-9.6-11-21.5-14.8-35.4-14.8-28.4 0-49.8 19.4-57.3 44.9-18-59.4-97.4-57.6-121.9-14v-24.2H49v-26.2h60v-41.1H0V345h49v-77.5h48.9c-1.5 5.7-2.3 11.8-2.3 18.2 0 73.1 102.6 91.4 130.2 23.7h-42c-14.7 20.9-45.8 8.9-45.8-14.6h85.5c3.7 30.5 27.4 56.9 60.1 56.9 14.1 0 27-6.9 34.9-18.6h.5V345h212.2l22.1-25 22.3 25H640l-54-60.5zm-446.7-16.6c6.1-26.3 41.7-25.6 46.5 0h-46.5zm153.4 48.9c-34.6 0-34-62.8 0-62.8 32.6 0 34.5 62.8 0 62.8zm167.8 19.1h-94.4V169.4h95v30.2H405v33.9h55.5v28.1h-56.1v44.7h56.1v29.6zm-45.9-39.8v-24.4h56.1v-44l50.7 57-50.7 57v-45.6h-56.1zm138.6 10.3l-26.1 29.5H489l45.6-51.2-45.6-51.2h39.7l26.6 29.3 25.6-29.3h38.5l-45.4 51 46 51.4h-40.5l-26.3-29.5z\"],\n    \"fedora\": [448, 512, [], \"f798\", \"M225 32C101.3 31.7.8 131.7.4 255.4L0 425.7a53.6 53.6 0 0 0 53.6 53.9l170.2.4c123.7.3 224.3-99.7 224.6-223.4S348.7 32.3 225 32zm169.8 157.2L333 126.6c2.3-4.7 3.8-9.2 3.8-14.3v-1.6l55.2 56.1a101 101 0 0 1 2.8 22.4zM331 94.3a106.06 106.06 0 0 1 58.5 63.8l-54.3-54.6a26.48 26.48 0 0 0-4.2-9.2zM118.1 247.2a49.66 49.66 0 0 0-7.7 11.4l-8.5-8.5a85.78 85.78 0 0 1 16.2-2.9zM97 251.4l11.8 11.9-.9 8a34.74 34.74 0 0 0 2.4 12.5l-27-27.2a80.6 80.6 0 0 1 13.7-5.2zm-18.2 7.4l38.2 38.4a53.17 53.17 0 0 0-14.1 4.7L67.6 266a107 107 0 0 1 11.2-7.2zm-15.2 9.8l35.3 35.5a67.25 67.25 0 0 0-10.5 8.5L53.5 278a64.33 64.33 0 0 1 10.1-9.4zm-13.3 12.3l34.9 35a56.84 56.84 0 0 0-7.7 11.4l-35.8-35.9c2.8-3.8 5.7-7.2 8.6-10.5zm-11 14.3l36.4 36.6a48.29 48.29 0 0 0-3.6 15.2l-39.5-39.8a99.81 99.81 0 0 1 6.7-12zm-8.8 16.3l41.3 41.8a63.47 63.47 0 0 0 6.7 26.2L25.8 326c1.4-4.9 2.9-9.6 4.7-14.5zm-7.9 43l61.9 62.2a31.24 31.24 0 0 0-3.6 14.3v1.1l-55.4-55.7a88.27 88.27 0 0 1-2.9-21.9zm5.3 30.7l54.3 54.6a28.44 28.44 0 0 0 4.2 9.2 106.32 106.32 0 0 1-58.5-63.8zm-5.3-37a80.69 80.69 0 0 1 2.1-17l72.2 72.5a37.59 37.59 0 0 0-9.9 8.7zm253.3-51.8l-42.6-.1-.1 56c-.2 69.3-64.4 115.8-125.7 102.9-5.7 0-19.9-8.7-19.9-24.2a24.89 24.89 0 0 1 24.5-24.6c6.3 0 6.3 1.6 15.7 1.6a55.91 55.91 0 0 0 56.1-55.9l.1-47c0-4.5-4.5-9-8.9-9l-33.6-.1c-32.6-.1-32.5-49.4.1-49.3l42.6.1.1-56a105.18 105.18 0 0 1 105.6-105 86.35 86.35 0 0 1 20.2 2.3c11.2 1.8 19.9 11.9 19.9 24 0 15.5-14.9 27.8-30.3 23.9-27.4-5.9-65.9 14.4-66 54.9l-.1 47a8.94 8.94 0 0 0 8.9 9l33.6.1c32.5.2 32.4 49.5-.2 49.4zm23.5-.3a35.58 35.58 0 0 0 7.6-11.4l8.5 8.5a102 102 0 0 1-16.1 2.9zm21-4.2L308.6 280l.9-8.1a34.74 34.74 0 0 0-2.4-12.5l27 27.2a74.89 74.89 0 0 1-13.7 5.3zm18-7.4l-38-38.4c4.9-1.1 9.6-2.4 13.7-4.7l36.2 35.9c-3.8 2.5-7.9 5-11.9 7.2zm15.5-9.8l-35.3-35.5a61.06 61.06 0 0 0 10.5-8.5l34.9 35a124.56 124.56 0 0 1-10.1 9zm13.2-12.3l-34.9-35a63.18 63.18 0 0 0 7.7-11.4l35.8 35.9a130.28 130.28 0 0 1-8.6 10.5zm11-14.3l-36.4-36.6a48.29 48.29 0 0 0 3.6-15.2l39.5 39.8a87.72 87.72 0 0 1-6.7 12zm13.5-30.9a140.63 140.63 0 0 1-4.7 14.3L345.6 190a58.19 58.19 0 0 0-7.1-26.2zm1-5.6l-71.9-72.1a32 32 0 0 0 9.9-9.2l64.3 64.7a90.93 90.93 0 0 1-2.3 16.6z\"],\n    \"figma\": [384, 512, [], \"f799\", \"M277 170.7A85.35 85.35 0 0 0 277 0H106.3a85.3 85.3 0 0 0 0 170.6 85.35 85.35 0 0 0 0 170.7 85.35 85.35 0 1 0 85.3 85.4v-256zm0 0a85.3 85.3 0 1 0 85.3 85.3 85.31 85.31 0 0 0-85.3-85.3z\"],\n    \"firefox\": [480, 512, [], \"f269\", \"M478.1 235.3c-.7-4.5-1.4-7.1-1.4-7.1s-1.8 2-4.7 5.9c-.9-10.7-2.8-21.2-5.8-31.6-3.7-12.9-8.5-25.4-14.5-37.4-3.8-8-8.2-15.6-13.3-22.8-1.8-2.7-3.7-5.4-5.6-7.9-8.8-14.4-19-23.3-30.7-40-7.6-12.8-12.9-26.9-15.4-41.6-3.2 8.9-5.7 18-7.4 27.3-12.1-12.2-22.5-20.8-28.9-26.7C319.4 24.2 323 9.1 323 9.1S264.7 74.2 289.9 142c8.7 23 23.8 43.1 43.4 57.9 24.4 20.2 50.8 36 64.7 76.6-11.2-21.3-28.1-39.2-48.8-51.5 6.2 14.7 9.4 30.6 9.3 46.5 0 61-49.6 110.5-110.6 110.4-8.3 0-16.5-.9-24.5-2.8-9.5-1.8-18.7-4.9-27.4-9.3-12.9-7.8-24-18.1-32.8-30.3l-.2-.3 2 .7c4.6 1.6 9.2 2.8 14 3.7 18.7 4 38.3 1.7 55.6-6.6 17.5-9.7 28-16.9 36.6-14h.2c8.4 2.7 15-5.5 9-14-10.4-13.4-27.4-20-44.2-17-17.5 2.5-33.5 15-56.4 2.9-1.5-.8-2.9-1.6-4.3-2.5-1.6-.9 4.9 1.3 3.4.3-5-2.5-9.8-5.4-14.4-8.6-.3-.3 3.5 1.1 3.1.8-5.9-4-11-9.2-15-15.2-4.1-7.4-4.5-16.4-1-24.1 2.1-3.8 5.4-6.9 9.3-8.7 3 1.5 4.8 2.6 4.8 2.6s-1.3-2.5-2.1-3.8c.3-.1.5 0 .8-.2 2.6 1.1 8.3 4 11.4 5.8 2.1 1.1 3.8 2.7 5.2 4.7 0 0 1-.5.3-2.7-1.1-2.7-2.9-5-5.4-6.6h.2c2.3 1.2 4.5 2.6 6.6 4.1 1.9-4.4 2.8-9.2 2.6-14 .2-2.6-.2-5.3-1.1-7.8-.8-1.6.5-2.2 1.9-.5-.2-1.3-.7-2.5-1.2-3.7v-.1s.8-1.1 1.2-1.5c1-1 2.1-1.9 3.4-2.7 7.2-4.5 14.8-8.4 22.7-11.6 6.4-2.8 11.7-4.9 12.8-5.6 1.6-1 3.1-2.2 4.5-3.5 5.3-4.5 9-10.8 10.2-17.7.1-.9.2-1.8.3-2.8v-1.5c-.9-3.5-6.9-6.1-38.4-9.1-11.1-1.8-20-10.1-22.5-21.1v-.1c6-15.7 16.8-29.1 30.8-38.3.8-.7-3.2.2-2.4-.5 2.7-1.3 5.4-2.5 8.2-3.5 1.4-.6-6-3.4-12.6-2.7-4 .2-8 1.2-11.7 2.8 1.6-1.3 6.2-3.1 5.1-3.1-8.4 1.6-16.5 4.7-23.9 9 0-.8.1-1.5.5-2.2-5.9 2.5-11 6.5-15 11.5.1-.9.2-1.8.2-2.7-2.7 2-5.2 4.3-7.3 6.9l-.1.1c-17.4-6.7-36.3-8.3-54.6-4.7l-.2-.1h.2c-3.8-3.1-7.1-6.7-9.7-10.9l-.2.1-.4-.2c-1.2-1.8-2.4-3.8-3.7-6-.9-1.6-1.8-3.4-2.7-5.2 0-.1-.1-.2-.2-.2-.4 0-.6 1.7-.9 1.3v-.1c-3.2-8.3-4.7-17.2-4.4-26.2l-.2.1c-5.1 3.5-9 8.6-11.1 14.5-.9 2.1-1.6 3.3-2.2 4.5v-.5c.1-1.1.6-3.3.5-3.1s-.2.3-.3.4c-1.5 1.7-2.9 3.7-3.9 5.8-.9 1.9-1.7 3.9-2.3 5.9-.1.3 0-.3 0-1s.1-2 0-1.7l-.3.7c-6.7 14.9-10.9 30.8-12.4 47.1-.4 2.8-.6 5.6-.5 8.3v.2c-4.8 5.2-9 11-12.7 17.1-12.1 20.4-21.1 42.5-26.8 65.6 4-8.8 8.8-17.2 14.3-25.1C5.5 228.5 0 257.4 0 286.6c1.8-8.6 4.2-17 7-25.3-1.7 34.5 4.9 68.9 19.4 100.3 19.4 43.5 51.6 80 92.3 104.7 16.6 11.2 34.7 19.9 53.8 25.8 2.5.9 5.1 1.8 7.7 2.7-.8-.3-1.6-.7-2.4-1 22.6 6.8 46.2 10.3 69.8 10.3 83.7 0 111.3-31.9 113.8-35 4.1-3.7 7.5-8.2 9.9-13.3 1.6-.7 3.2-1.4 4.9-2.1l1-.5 1.9-.9c12.6-5.9 24.5-13.4 35.3-22.1 16.3-11.7 27.9-28.7 32.9-48.1 3-7.1 3.1-15 .4-22.2.9-1.4 1.7-2.8 2.7-4.3 18-28.9 28.2-61.9 29.6-95.9v-2.8c0-7.3-.6-14.5-1.9-21.6zm-299-97.6c-.4 1.1-.9 2.3-1.3 3.5.4-1.2.8-2.3 1.3-3.5z\"],\n    \"first-order\": [448, 512, [], \"f2b0\", \"M12.9 229.2c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4h-.2zM224 96.6c-7.1 0-14.6.6-21.4 1.7l3.7 67.4-22-64c-14.3 3.7-27.7 9.4-40 16.6l29.4 61.4-45.1-50.9c-11.4 8.9-21.7 19.1-30.6 30.9l50.6 45.4-61.1-29.7c-7.1 12.3-12.9 25.7-16.6 40l64.3 22.6-68-4c-.9 7.1-1.4 14.6-1.4 22s.6 14.6 1.4 21.7l67.7-4-64 22.6c3.7 14.3 9.4 27.7 16.6 40.3l61.1-29.7L97.7 352c8.9 11.7 19.1 22.3 30.9 30.9l44.9-50.9-29.5 61.4c12.3 7.4 25.7 13.1 40 16.9l22.3-64.6-4 68c7.1 1.1 14.6 1.7 21.7 1.7 7.4 0 14.6-.6 21.7-1.7l-4-68.6 22.6 65.1c14.3-4 27.7-9.4 40-16.9L274.9 332l44.9 50.9c11.7-8.9 22-19.1 30.6-30.9l-50.6-45.1 61.1 29.4c7.1-12.3 12.9-25.7 16.6-40.3l-64-22.3 67.4 4c1.1-7.1 1.4-14.3 1.4-21.7s-.3-14.9-1.4-22l-67.7 4 64-22.3c-3.7-14.3-9.1-28-16.6-40.3l-60.9 29.7 50.6-45.4c-8.9-11.7-19.1-22-30.6-30.9l-45.1 50.9 29.4-61.1c-12.3-7.4-25.7-13.1-40-16.9L241.7 166l4-67.7c-7.1-1.2-14.3-1.7-21.7-1.7zM443.4 128v256L224 512 4.6 384V128L224 0l219.4 128zm-17.1 10.3L224 20.9 21.7 138.3v235.1L224 491.1l202.3-117.7V138.3zM224 37.1l187.7 109.4v218.9L224 474.9 36.3 365.4V146.6L224 37.1zm0 50.9c-92.3 0-166.9 75.1-166.9 168 0 92.6 74.6 167.7 166.9 167.7 92 0 166.9-75.1 166.9-167.7 0-92.9-74.9-168-166.9-168z\"],\n    \"first-order-alt\": [496, 512, [], \"f50a\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 488.21C115.34 496.21 7.79 388.66 7.79 256S115.34 15.79 248 15.79 488.21 123.34 488.21 256 380.66 496.21 248 496.21zm0-459.92C126.66 36.29 28.29 134.66 28.29 256S126.66 475.71 248 475.71 467.71 377.34 467.71 256 369.34 36.29 248 36.29zm0 431.22c-116.81 0-211.51-94.69-211.51-211.51S131.19 44.49 248 44.49 459.51 139.19 459.51 256 364.81 467.51 248 467.51zm186.23-162.98a191.613 191.613 0 0 1-20.13 48.69l-74.13-35.88 61.48 54.82a193.515 193.515 0 0 1-37.2 37.29l-54.8-61.57 35.88 74.27a190.944 190.944 0 0 1-48.63 20.23l-27.29-78.47 4.79 82.93c-8.61 1.18-17.4 1.8-26.33 1.8s-17.72-.62-26.33-1.8l4.76-82.46-27.15 78.03a191.365 191.365 0 0 1-48.65-20.2l35.93-74.34-54.87 61.64a193.85 193.85 0 0 1-37.22-37.28l61.59-54.9-74.26 35.93a191.638 191.638 0 0 1-20.14-48.69l77.84-27.11-82.23 4.76c-1.16-8.57-1.78-17.32-1.78-26.21 0-9 .63-17.84 1.82-26.51l82.38 4.77-77.94-27.16a191.726 191.726 0 0 1 20.23-48.67l74.22 35.92-61.52-54.86a193.85 193.85 0 0 1 37.28-37.22l54.76 61.53-35.83-74.17a191.49 191.49 0 0 1 48.65-20.13l26.87 77.25-4.71-81.61c8.61-1.18 17.39-1.8 26.32-1.8s17.71.62 26.32 1.8l-4.74 82.16 27.05-77.76c17.27 4.5 33.6 11.35 48.63 20.17l-35.82 74.12 54.72-61.47a193.13 193.13 0 0 1 37.24 37.23l-61.45 54.77 74.12-35.86a191.515 191.515 0 0 1 20.2 48.65l-77.81 27.1 82.24-4.75c1.19 8.66 1.82 17.5 1.82 26.49 0 8.88-.61 17.63-1.78 26.19l-82.12-4.75 77.72 27.09z\"],\n    \"firstdraft\": [384, 512, [], \"f3a1\", \"M384 192h-64v128H192v128H0v-25.6h166.4v-128h128v-128H384V192zm-25.6 38.4v128h-128v128H64V512h192V384h128V230.4h-25.6zm25.6 192h-89.6V512H320v-64h64v-25.6zM0 0v384h128V256h128V128h128V0H0z\"],\n    \"flickr\": [448, 512, [], \"f16e\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM144.5 319c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5zm159 0c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5z\"],\n    \"flipboard\": [448, 512, [], \"f44d\", \"M0 32v448h448V32H0zm358.4 179.2h-89.6v89.6h-89.6v89.6H89.6V121.6h268.8v89.6z\"],\n    \"fly\": [384, 512, [], \"f417\", \"M197.8 427.8c12.9 11.7 33.7 33.3 33.2 50.7 0 .8-.1 1.6-.1 2.5-1.8 19.8-18.8 31.1-39.1 31-25-.1-39.9-16.8-38.7-35.8 1-16.2 20.5-36.7 32.4-47.6 2.3-2.1 2.7-2.7 5.6-3.6 3.4 0 3.9.3 6.7 2.8zM331.9 67.3c-16.3-25.7-38.6-40.6-63.3-52.1C243.1 4.5 214-.2 192 0c-44.1 0-71.2 13.2-81.1 17.3C57.3 45.2 26.5 87.2 28 158.6c7.1 82.2 97 176 155.8 233.8 1.7 1.6 4.5 4.5 6.2 5.1l3.3.1c2.1-.7 1.8-.5 3.5-2.1 52.3-49.2 140.7-145.8 155.9-215.7 7-39.2 3.1-72.5-20.8-112.5zM186.8 351.9c-28-51.1-65.2-130.7-69.3-189-3.4-47.5 11.4-131.2 69.3-136.7v325.7zM328.7 180c-16.4 56.8-77.3 128-118.9 170.3C237.6 298.4 275 217 277 158.4c1.6-45.9-9.8-105.8-48-131.4 88.8 18.3 115.5 98.1 99.7 153z\"],\n    \"font-awesome\": [448, 512, [], \"f2b4\", \"M397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm-45.4 284.3c0 4.2-3.6 6-7.8 7.8-16.7 7.2-34.6 13.7-53.8 13.7-26.9 0-39.4-16.7-71.7-16.7-23.3 0-47.8 8.4-67.5 17.3-1.2.6-2.4.6-3.6 1.2V385c0 1.8 0 3.6-.6 4.8v1.2c-2.4 8.4-10.2 14.3-19.1 14.3-11.3 0-20.3-9-20.3-20.3V166.4c-7.8-6-13.1-15.5-13.1-26.3 0-18.5 14.9-33.5 33.5-33.5 18.5 0 33.5 14.9 33.5 33.5 0 10.8-4.8 20.3-13.1 26.3v18.5c1.8-.6 3.6-1.2 5.4-2.4 18.5-7.8 40.6-14.3 61.5-14.3 22.7 0 40.6 6 60.9 13.7 4.2 1.8 8.4 2.4 13.1 2.4 22.7 0 47.8-16.1 53.8-16.1 4.8 0 9 3.6 9 7.8v140.3z\"],\n    \"font-awesome-alt\": [448, 512, [], \"f35c\", \"M339.3 171.2c-6 0-29.9 15.5-52.6 15.5-4.2 0-8.4-.6-12.5-2.4-19.7-7.8-37-13.7-59.1-13.7-20.3 0-41.8 6.6-59.7 13.7-1.8.6-3.6 1.2-4.8 1.8v-17.9c7.8-6 12.5-14.9 12.5-25.7 0-17.9-14.3-32.3-32.3-32.3s-32.3 14.3-32.3 32.3c0 10.2 4.8 19.7 12.5 25.7v212.1c0 10.8 9 19.7 19.7 19.7 9 0 16.1-6 18.5-13.7V385c.6-1.8.6-3 .6-4.8V336c1.2 0 2.4-.6 3-1.2 19.7-8.4 43-16.7 65.7-16.7 31.1 0 43 16.1 69.3 16.1 18.5 0 36.4-6.6 52-13.7 4.2-1.8 7.2-3.6 7.2-7.8V178.3c1.8-4.1-2.3-7.1-7.7-7.1zM397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm14.3 397.7c0 7.8-6.6 14.3-14.3 14.3H50.2c-7.8 0-14.3-6.6-14.3-14.3V82.2c0-7.8 6.6-14.3 14.3-14.3h347.6v-.1c7.8 0 14.3 6.6 14.3 14.3z\"],\n    \"font-awesome-flag\": [448, 512, [], \"f425\", \"M444.373 359.424c0 7.168-6.144 10.24-13.312 13.312-28.672 12.288-59.392 23.552-92.16 23.552-46.08 0-67.584-28.672-122.88-28.672-39.936 0-81.92 14.336-115.712 29.696-2.048 1.024-4.096 1.024-6.144 2.048v77.824c0 21.405-16.122 34.816-33.792 34.816-19.456 0-34.816-15.36-34.816-34.816V102.4C12.245 92.16 3.029 75.776 3.029 57.344 3.029 25.6 28.629 0 60.373 0s57.344 25.6 57.344 57.344c0 18.432-8.192 34.816-22.528 45.056v31.744c4.124-1.374 58.768-28.672 114.688-28.672 65.27 0 97.676 27.648 126.976 27.648 38.912 0 81.92-27.648 92.16-27.648 8.192 0 15.36 6.144 15.36 13.312v240.64z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"fonticons\": [448, 512, [], \"f280\", \"M0 32v448h448V32zm187 140.9c-18.4 0-19 9.9-19 27.4v23.3c0 2.4-3.5 4.4-.6 4.4h67.4l-11.1 37.3H168v112.9c0 5.8-2 6.7 3.2 7.3l43.5 4.1v25.1H84V389l21.3-2c5.2-.6 6.7-2.3 6.7-7.9V267.7c0-2.3-2.9-2.3-5.8-2.3H84V228h28v-21c0-49.6 26.5-70 77.3-70 34.1 0 64.7 8.2 64.7 52.8l-50.7 6.1c.3-18.7-4.4-23-16.3-23zm74.3 241.8v-25.1l20.4-2.6c5.2-.6 7.6-1.7 7.6-7.3V271.8c0-4.1-2.9-6.7-6.7-7.9l-24.2-6.4 6.7-29.5h80.2v151.7c0 5.8-2.6 6.4 2.9 7.3l15.7 2.6v25.1zm80.8-255.5l9 33.2-7.3 7.3-31.2-16.6-31.2 16.6-7.3-7.3 9-33.2-21.8-24.2 3.5-9.6h27.7l15.5-28h9.3l15.5 28h27.7l3.5 9.6z\"],\n    \"fonticons-fi\": [384, 512, [], \"f3a2\", \"M114.4 224h92.4l-15.2 51.2h-76.4V433c0 8-2.8 9.2 4.4 10l59.6 5.6V483H0v-35.2l29.2-2.8c7.2-.8 9.2-3.2 9.2-10.8V278.4c0-3.2-4-3.2-8-3.2H0V224h38.4v-28.8c0-68 36.4-96 106-96 46.8 0 88.8 11.2 88.8 72.4l-69.6 8.4c.4-25.6-6-31.6-22.4-31.6-25.2 0-26 13.6-26 37.6v32c0 3.2-4.8 6-.8 6zM384 483H243.2v-34.4l28-3.6c7.2-.8 10.4-2.4 10.4-10V287c0-5.6-4-9.2-9.2-10.8l-33.2-8.8 9.2-40.4h110v208c0 8-3.6 8.8 4 10l21.6 3.6V483zm-30-347.2l12.4 45.6-10 10-42.8-22.8-42.8 22.8-10-10 12.4-45.6-30-36.4 4.8-10h38L307.2 51H320l21.2 38.4h38l4.8 13.2-30 33.2z\"],\n    \"fort-awesome\": [512, 512, [], \"f286\", \"M489.2 287.9h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6V146.2c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-6-8-4.6-11.7-4.6v-38c8.3-2 17.1-3.4 25.7-3.4 10.9 0 20.9 4.3 31.4 4.3 4.6 0 27.7-1.1 27.7-8v-60c0-2.6-2-4.6-4.6-4.6-5.1 0-15.1 4.3-24 4.3-9.7 0-20.9-4.3-32.6-4.3-8 0-16 1.1-23.7 2.9v-4.9c5.4-2.6 9.1-8.3 9.1-14.3 0-20.7-31.4-20.8-31.4 0 0 6 3.7 11.7 9.1 14.3v111.7c-3.7 0-11.7-1.4-11.7 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32H128v-32c0-2.6-2-4.6-4.6-4.6H96c-2.6 0-4.6 2-4.6 4.6v178.3H54.8v-32c0-2.6-2-4.6-4.6-4.6H22.8c-2.6 0-4.6 2-4.6 4.6V512h182.9v-96c0-72.6 109.7-72.6 109.7 0v96h182.9V292.5c.1-2.6-1.9-4.6-4.5-4.6zm-288.1-4.5c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64zm146.4 0c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64z\"],\n    \"fort-awesome-alt\": [512, 512, [], \"f3a3\", \"M208 237.4h-22.2c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7H208c2.1 0 3.7-1.6 3.7-3.7v-51.7c0-2.1-1.6-3.7-3.7-3.7zm118.2 0H304c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7h22.2c2.1 0 3.7-1.6 3.7-3.7v-51.7c-.1-2.1-1.7-3.7-3.7-3.7zm132-125.1c-2.3-3.2-4.6-6.4-7.1-9.5-9.8-12.5-20.8-24-32.8-34.4-4.5-3.9-9.1-7.6-13.9-11.2-1.6-1.2-3.2-2.3-4.8-3.5C372 34.1 340.3 20 306 13c-16.2-3.3-32.9-5-50-5s-33.9 1.7-50 5c-34.3 7.1-66 21.2-93.3 40.8-1.6 1.1-3.2 2.3-4.8 3.5-4.8 3.6-9.4 7.3-13.9 11.2-3 2.6-5.9 5.3-8.8 8s-5.7 5.5-8.4 8.4c-5.5 5.7-10.7 11.8-15.6 18-2.4 3.1-4.8 6.3-7.1 9.5C25.2 153 8.3 202.5 8.3 256c0 2 .1 4 .1 6 .1.7.1 1.3.1 2 .1 1.3.1 2.7.2 4 0 .8.1 1.5.1 2.3 0 1.3.1 2.5.2 3.7.1.8.1 1.6.2 2.4.1 1.1.2 2.3.3 3.5 0 .8.1 1.6.2 2.4.1 1.2.3 2.4.4 3.6.1.8.2 1.5.3 2.3.1 1.3.3 2.6.5 3.9.1.6.2 1.3.3 1.9l.9 5.7c.1.6.2 1.1.3 1.7.3 1.3.5 2.7.8 4 .2.8.3 1.6.5 2.4.2 1 .5 2.1.7 3.2.2.9.4 1.7.6 2.6.2 1 .4 2 .7 3 .2.9.5 1.8.7 2.7.3 1 .5 1.9.8 2.9.3.9.5 1.8.8 2.7.2.9.5 1.9.8 2.8s.5 1.8.8 2.7c.3 1 .6 1.9.9 2.8.6 1.6 1.1 3.3 1.7 4.9.4 1 .7 1.9 1 2.8.3 1 .7 2 1.1 3 .3.8.6 1.5.9 2.3l1.2 3c.3.7.6 1.5.9 2.2.4 1 .9 2 1.3 3l.9 2.1c.5 1 .9 2 1.4 3 .3.7.6 1.3.9 2 .5 1 1 2.1 1.5 3.1.2.6.5 1.1.8 1.7.6 1.1 1.1 2.2 1.7 3.3.1.2.2.3.3.5 2.2 4.1 4.4 8.2 6.8 12.2.2.4.5.8.7 1.2.7 1.1 1.3 2.2 2 3.3.3.5.6.9.9 1.4.6 1.1 1.3 2.1 2 3.2.3.5.6.9.9 1.4.7 1.1 1.4 2.1 2.1 3.2.2.4.5.8.8 1.2.7 1.1 1.5 2.2 2.3 3.3.2.2.3.5.5.7 37.5 51.7 94.4 88.5 160 99.4.9.1 1.7.3 2.6.4 1 .2 2.1.4 3.1.5s1.9.3 2.8.4c1 .2 2 .3 3 .4.9.1 1.9.2 2.9.3s1.9.2 2.9.3 2.1.2 3.1.3c.9.1 1.8.1 2.7.2 1.1.1 2.3.1 3.4.2.8 0 1.7.1 2.5.1 1.3 0 2.6.1 3.9.1.7.1 1.4.1 2.1.1 2 .1 4 .1 6 .1s4-.1 6-.1c.7 0 1.4-.1 2.1-.1 1.3 0 2.6 0 3.9-.1.8 0 1.7-.1 2.5-.1 1.1-.1 2.3-.1 3.4-.2.9 0 1.8-.1 2.7-.2 1-.1 2.1-.2 3.1-.3s1.9-.2 2.9-.3c.9-.1 1.9-.2 2.9-.3s2-.3 3-.4 1.9-.3 2.8-.4c1-.2 2.1-.3 3.1-.5.9-.1 1.7-.3 2.6-.4 65.6-11 122.5-47.7 160.1-102.4.2-.2.3-.5.5-.7.8-1.1 1.5-2.2 2.3-3.3.2-.4.5-.8.8-1.2.7-1.1 1.4-2.1 2.1-3.2.3-.5.6-.9.9-1.4.6-1.1 1.3-2.1 2-3.2.3-.5.6-.9.9-1.4.7-1.1 1.3-2.2 2-3.3.2-.4.5-.8.7-1.2 2.4-4 4.6-8.1 6.8-12.2.1-.2.2-.3.3-.5.6-1.1 1.1-2.2 1.7-3.3.2-.6.5-1.1.8-1.7.5-1 1-2.1 1.5-3.1.3-.7.6-1.3.9-2 .5-1 1-2 1.4-3l.9-2.1c.5-1 .9-2 1.3-3 .3-.7.6-1.5.9-2.2l1.2-3c.3-.8.6-1.5.9-2.3.4-1 .7-2 1.1-3s.7-1.9 1-2.8c.6-1.6 1.2-3.3 1.7-4.9.3-1 .6-1.9.9-2.8s.5-1.8.8-2.7c.2-.9.5-1.9.8-2.8s.6-1.8.8-2.7c.3-1 .5-1.9.8-2.9.2-.9.5-1.8.7-2.7.2-1 .5-2 .7-3 .2-.9.4-1.7.6-2.6.2-1 .5-2.1.7-3.2.2-.8.3-1.6.5-2.4.3-1.3.6-2.7.8-4 .1-.6.2-1.1.3-1.7l.9-5.7c.1-.6.2-1.3.3-1.9.1-1.3.3-2.6.5-3.9.1-.8.2-1.5.3-2.3.1-1.2.3-2.4.4-3.6 0-.8.1-1.6.2-2.4.1-1.1.2-2.3.3-3.5.1-.8.1-1.6.2-2.4.1 1.7.1.5.2-.7 0-.8.1-1.5.1-2.3.1-1.3.2-2.7.2-4 .1-.7.1-1.3.1-2 .1-2 .1-4 .1-6 0-53.5-16.9-103-45.8-143.7zM448 371.5c-9.4 15.5-20.6 29.9-33.6 42.9-20.6 20.6-44.5 36.7-71.2 48-13.9 5.8-28.2 10.3-42.9 13.2v-75.8c0-58.6-88.6-58.6-88.6 0v75.8c-14.7-2.9-29-7.3-42.9-13.2-26.7-11.3-50.6-27.4-71.2-48-13-13-24.2-27.4-33.6-42.9v-71.3c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7V326h29.6V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7H208c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-4.8 6.5-3.7 9.5-3.7V88.1c-4.4-2-7.4-6.7-7.4-11.5 0-16.8 25.4-16.8 25.4 0 0 4.8-3 9.4-7.4 11.5V92c6.3-1.4 12.7-2.3 19.2-2.3 9.4 0 18.4 3.5 26.3 3.5 7.2 0 15.2-3.5 19.4-3.5 2.1 0 3.7 1.6 3.7 3.7v48.4c0 5.6-18.7 6.5-22.4 6.5-8.6 0-16.6-3.5-25.4-3.5-7 0-14.1 1.2-20.8 2.8v30.7c3 0 9.5-1.1 9.5 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v144h29.5v-25.8c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7z\"],\n    \"forumbee\": [448, 512, [], \"f211\", \"M5.8 309.7C2 292.7 0 275.5 0 258.3 0 135 99.8 35 223.1 35c16.6 0 33.3 2 49.3 5.5C149 87.5 51.9 186 5.8 309.7zm392.9-189.2C385 103 369 87.8 350.9 75.2c-149.6 44.3-266.3 162.1-309.7 312 12.5 18.1 28 35.6 45.2 49 43.1-151.3 161.2-271.7 312.3-315.7zm15.8 252.7c15.2-25.1 25.4-53.7 29.5-82.8-79.4 42.9-145 110.6-187.6 190.3 30-4.4 58.9-15.3 84.6-31.3 35 13.1 70.9 24.3 107 33.6-9.3-36.5-20.4-74.5-33.5-109.8zm29.7-145.5c-2.6-19.5-7.9-38.7-15.8-56.8C290.5 216.7 182 327.5 137.1 466c18.1 7.6 37 12.5 56.6 15.2C240 367.1 330.5 274.4 444.2 227.7z\"],\n    \"foursquare\": [368, 512, [], \"f180\", \"M323.1 3H49.9C12.4 3 0 31.3 0 49.1v433.8c0 20.3 12.1 27.7 18.2 30.1 6.2 2.5 22.8 4.6 32.9-7.1C180 356.5 182.2 354 182.2 354c3.1-3.4 3.4-3.1 6.8-3.1h83.4c35.1 0 40.6-25.2 44.3-39.7l48.6-243C373.8 25.8 363.1 3 323.1 3zm-16.3 73.8l-11.4 59.7c-1.2 6.5-9.5 13.2-16.9 13.2H172.1c-12 0-20.6 8.3-20.6 20.3v13c0 12 8.6 20.6 20.6 20.6h90.4c8.3 0 16.6 9.2 14.8 18.2-1.8 8.9-10.5 53.8-11.4 58.8-.9 4.9-6.8 13.5-16.9 13.5h-73.5c-13.5 0-17.2 1.8-26.5 12.6 0 0-8.9 11.4-89.5 108.3-.9.9-1.8.6-1.8-.3V75.9c0-7.7 6.8-16.6 16.6-16.6h219c8.2 0 15.6 7.7 13.5 17.5z\"],\n    \"free-code-camp\": [576, 512, [], \"f2c5\", \"M69.3 144.5c-41 68.5-36.4 163 1 227C92.5 409.7 120 423.9 120 438c0 6.8-6 13-12.8 13C87.7 451 8 375.5 8 253.2c0-111.5 78-186 97.1-186 6 0 14.9 4.8 14.9 11.1 0 12.7-28.3 28.6-50.7 66.2zm195.8 213.8c4.5 1.8 12.3 5.2 12.3-1.2 0-2.7-2.2-2.9-4.3-3.6-8.5-3.4-14-7.7-19.1-15.2-8.2-12.1-10.1-24.2-10.1-38.6 0-32.1 44.2-37.9 44.2-70 0-12.3-7.7-15.9-7.7-19.3 0-2.2.7-2.2 2.9-2.2 8 0 19.1 13.3 22.5 19.8 2.2 4.6 2.4 6 2.4 11.1 0 7-.7 14.2-.7 21.3 0 27 31.9 19.8 31.9 6.8 0-6-3.6-11.6-3.6-17.4 0-.7 0-1.2.7-1.2 3.4 0 9.4 7.7 11.1 10.1 5.8 8.9 8.5 20.8 8.5 31.4 0 32.4-29.5 49-29.5 56 0 1 2.9 7.7 12.1 1.9 29.7-15.1 53.1-47.6 53.1-89.8 0-33.6-8.7-57.7-32.1-82.6-3.9-4.1-16.4-16.9-22.5-16.9-8.2 0 7.2 18.6 7.2 31.2 0 7.2-4.8 12.3-12.3 12.3-11.6 0-14.5-25.4-15.9-33.3-5.8-33.8-12.8-58.2-46.4-74.1-10.4-5-36.5-11.8-36.5-2.2 0 2.4 2.7 4.1 4.6 5.1 9.2 5.6 19.6 21.4 19.6 38.2 0 46.1-57.7 88.2-57.7 136.2-.2 40.3 28.1 72.6 65.3 86.2zM470.4 67c-6 0-14.4 6.5-14.4 12.6 0 8.7 12.1 19.6 17.6 25.4 81.6 85.1 78.6 214.3 17.6 291-7 8.9-35.3 35.3-35.3 43.5 0 5.1 8.2 11.4 13.2 11.4 25.4 0 98.8-80.8 98.8-185.7C568 145.9 491.8 67 470.4 67zm-42.3 323.1H167c-9.4 0-15.5 7.5-15.5 16.4 0 8.5 7 15.5 15.5 15.5h261.1c9.4 0 11.9-7.5 11.9-16.4 0-8.5-3.5-15.5-11.9-15.5z\"],\n    \"freebsd\": [448, 512, [], \"f3a4\", \"M303.7 96.2c11.1-11.1 115.5-77 139.2-53.2 23.7 23.7-42.1 128.1-53.2 139.2-11.1 11.1-39.4.9-63.1-22.9-23.8-23.7-34.1-52-22.9-63.1zM109.9 68.1C73.6 47.5 22 24.6 5.6 41.1c-16.6 16.6 7.1 69.4 27.9 105.7 18.5-32.2 44.8-59.3 76.4-78.7zM406.7 174c3.3 11.3 2.7 20.7-2.7 26.1-20.3 20.3-87.5-27-109.3-70.1-18-32.3-11.1-53.4 14.9-48.7 5.7-3.6 12.3-7.6 19.6-11.6-29.8-15.5-63.6-24.3-99.5-24.3-119.1 0-215.6 96.5-215.6 215.6 0 119 96.5 215.6 215.6 215.6S445.3 380.1 445.3 261c0-38.4-10.1-74.5-27.7-105.8-3.9 7-7.6 13.3-10.9 18.8z\"],\n    \"fulcrum\": [320, 512, [], \"f50b\", \"M95.75 164.14l-35.38 43.55L25 164.14l35.38-43.55zM144.23 0l-20.54 198.18L72.72 256l51 57.82L144.23 512V300.89L103.15 256l41.08-44.89zm79.67 164.14l35.38 43.55 35.38-43.55-35.38-43.55zm-48.48 47L216.5 256l-41.08 44.89V512L196 313.82 247 256l-51-57.82L175.42 0z\"],\n    \"galactic-republic\": [496, 512, [], \"f50c\", \"M248 504C111.25 504 0 392.75 0 256S111.25 8 248 8s248 111.25 248 248-111.25 248-248 248zm0-479.47C120.37 24.53 16.53 128.37 16.53 256S120.37 487.47 248 487.47 479.47 383.63 479.47 256 375.63 24.53 248 24.53zm27.62 21.81v24.62a185.933 185.933 0 0 1 83.57 34.54l17.39-17.36c-28.75-22.06-63.3-36.89-100.96-41.8zm-55.37.07c-37.64 4.94-72.16 19.8-100.88 41.85l17.28 17.36h.08c24.07-17.84 52.55-30.06 83.52-34.67V46.41zm12.25 50.17v82.87c-10.04 2.03-19.42 5.94-27.67 11.42l-58.62-58.59-21.93 21.93 58.67 58.67c-5.47 8.23-9.45 17.59-11.47 27.62h-82.9v31h82.9c2.02 10.02 6.01 19.31 11.47 27.54l-58.67 58.69 21.93 21.93 58.62-58.62a77.873 77.873 0 0 0 27.67 11.47v82.9h31v-82.9c10.05-2.03 19.37-6.06 27.62-11.55l58.67 58.69 21.93-21.93-58.67-58.69c5.46-8.23 9.47-17.52 11.5-27.54h82.87v-31h-82.87c-2.02-10.02-6.03-19.38-11.5-27.62l58.67-58.67-21.93-21.93-58.67 58.67c-8.25-5.49-17.57-9.47-27.62-11.5V96.58h-31zm183.24 30.72l-17.36 17.36a186.337 186.337 0 0 1 34.67 83.67h24.62c-4.95-37.69-19.83-72.29-41.93-101.03zm-335.55.13c-22.06 28.72-36.91 63.26-41.85 100.91h24.65c4.6-30.96 16.76-59.45 34.59-83.52l-17.39-17.39zM38.34 283.67c4.92 37.64 19.75 72.18 41.8 100.9l17.36-17.39c-17.81-24.07-29.92-52.57-34.51-83.52H38.34zm394.7 0c-4.61 30.99-16.8 59.5-34.67 83.6l17.36 17.36c22.08-28.74 36.98-63.29 41.93-100.96h-24.62zM136.66 406.38l-17.36 17.36c28.73 22.09 63.3 36.98 100.96 41.93v-24.64c-30.99-4.63-59.53-16.79-83.6-34.65zm222.53.05c-24.09 17.84-52.58 30.08-83.57 34.67v24.57c37.67-4.92 72.21-19.79 100.96-41.85l-17.31-17.39h-.08z\"],\n    \"galactic-senate\": [512, 512, [], \"f50d\", \"M249.86 33.48v26.07C236.28 80.17 226 168.14 225.39 274.9c11.74-15.62 19.13-33.33 19.13-48.24v-16.88c-.03-5.32.75-10.53 2.19-15.65.65-2.14 1.39-4.08 2.62-5.82 1.23-1.75 3.43-3.79 6.68-3.79 3.24 0 5.45 2.05 6.68 3.79 1.23 1.75 1.97 3.68 2.62 5.82 1.44 5.12 2.22 10.33 2.19 15.65v16.88c0 14.91 7.39 32.62 19.13 48.24-.63-106.76-10.91-194.73-24.49-215.35V33.48h-12.28zm-26.34 147.77c-9.52 2.15-18.7 5.19-27.46 9.08 8.9 16.12 9.76 32.64 1.71 37.29-8 4.62-21.85-4.23-31.36-19.82-11.58 8.79-21.88 19.32-30.56 31.09 14.73 9.62 22.89 22.92 18.32 30.66-4.54 7.7-20.03 7.14-35.47-.96-5.78 13.25-9.75 27.51-11.65 42.42 9.68.18 18.67 2.38 26.18 6.04 17.78-.3 32.77-1.96 40.49-4.22 5.55-26.35 23.02-48.23 46.32-59.51.73-25.55 1.88-49.67 3.48-72.07zm64.96 0c1.59 22.4 2.75 46.52 3.47 72.07 23.29 11.28 40.77 33.16 46.32 59.51 7.72 2.26 22.71 3.92 40.49 4.22 7.51-3.66 16.5-5.85 26.18-6.04-1.9-14.91-5.86-29.17-11.65-42.42-15.44 8.1-30.93 8.66-35.47.96-4.57-7.74 3.6-21.05 18.32-30.66-8.68-11.77-18.98-22.3-30.56-31.09-9.51 15.59-23.36 24.44-31.36 19.82-8.05-4.65-7.19-21.16 1.71-37.29a147.49 147.49 0 0 0-27.45-9.08zm-32.48 8.6c-3.23 0-5.86 8.81-6.09 19.93h-.05v16.88c0 41.42-49.01 95.04-93.49 95.04-52 0-122.75-1.45-156.37 29.17v2.51c9.42 17.12 20.58 33.17 33.18 47.97C45.7 380.26 84.77 360.4 141.2 360c45.68 1.02 79.03 20.33 90.76 40.87.01.01-.01.04 0 .05 7.67 2.14 15.85 3.23 24.04 3.21 8.19.02 16.37-1.07 24.04-3.21.01-.01-.01-.04 0-.05 11.74-20.54 45.08-39.85 90.76-40.87 56.43.39 95.49 20.26 108.02 41.35 12.6-14.8 23.76-30.86 33.18-47.97v-2.51c-33.61-30.62-104.37-29.17-156.37-29.17-44.48 0-93.49-53.62-93.49-95.04v-16.88h-.05c-.23-11.12-2.86-19.93-6.09-19.93zm0 96.59c22.42 0 40.6 18.18 40.6 40.6s-18.18 40.65-40.6 40.65-40.6-18.23-40.6-40.65c0-22.42 18.18-40.6 40.6-40.6zm0 7.64c-18.19 0-32.96 14.77-32.96 32.96S237.81 360 256 360s32.96-14.77 32.96-32.96-14.77-32.96-32.96-32.96zm0 6.14c14.81 0 26.82 12.01 26.82 26.82s-12.01 26.82-26.82 26.82-26.82-12.01-26.82-26.82 12.01-26.82 26.82-26.82zm-114.8 66.67c-10.19.07-21.6.36-30.5 1.66.43 4.42 1.51 18.63 7.11 29.76 9.11-2.56 18.36-3.9 27.62-3.9 41.28.94 71.48 34.35 78.26 74.47l.11 4.7c10.4 1.91 21.19 2.94 32.21 2.94 11.03 0 21.81-1.02 32.21-2.94l.11-4.7c6.78-40.12 36.98-73.53 78.26-74.47 9.26 0 18.51 1.34 27.62 3.9 5.6-11.13 6.68-25.34 7.11-29.76-8.9-1.3-20.32-1.58-30.5-1.66-18.76.42-35.19 4.17-48.61 9.67-12.54 16.03-29.16 30.03-49.58 33.07-.09.02-.17.04-.27.05-.05.01-.11.04-.16.05-5.24 1.07-10.63 1.6-16.19 1.6-5.55 0-10.95-.53-16.19-1.6-.05-.01-.11-.04-.16-.05-.1-.02-.17-.04-.27-.05-20.42-3.03-37.03-17.04-49.58-33.07-13.42-5.49-29.86-9.25-48.61-9.67z\"],\n    \"get-pocket\": [448, 512, [], \"f265\", \"M407.6 64h-367C18.5 64 0 82.5 0 104.6v135.2C0 364.5 99.7 464 224.2 464c124 0 223.8-99.5 223.8-224.2V104.6c0-22.4-17.7-40.6-40.4-40.6zm-162 268.5c-12.4 11.8-31.4 11.1-42.4 0C89.5 223.6 88.3 227.4 88.3 209.3c0-16.9 13.8-30.7 30.7-30.7 17 0 16.1 3.8 105.2 89.3 90.6-86.9 88.6-89.3 105.5-89.3 16.9 0 30.7 13.8 30.7 30.7 0 17.8-2.9 15.7-114.8 123.2z\"],\n    \"gg\": [512, 512, [], \"f260\", \"M179.2 230.4l102.4 102.4-102.4 102.4L0 256 179.2 76.8l44.8 44.8-25.6 25.6-19.2-19.2-128 128 128 128 51.5-51.5-77.1-76.5 25.6-25.6zM332.8 76.8L230.4 179.2l102.4 102.4 25.6-25.6-77.1-76.5 51.5-51.5 128 128-128 128-19.2-19.2-25.6 25.6 44.8 44.8L512 256 332.8 76.8z\"],\n    \"gg-circle\": [512, 512, [], \"f261\", \"M257 8C120 8 9 119 9 256s111 248 248 248 248-111 248-248S394 8 257 8zm-49.5 374.8L81.8 257.1l125.7-125.7 35.2 35.4-24.2 24.2-11.1-11.1-77.2 77.2 77.2 77.2 26.6-26.6-53.1-52.9 24.4-24.4 77.2 77.2-75 75.2zm99-2.2l-35.2-35.2 24.1-24.4 11.1 11.1 77.2-77.2-77.2-77.2-26.5 26.5 53.1 52.9-24.4 24.4-77.2-77.2 75-75L432.2 255 306.5 380.6z\"],\n    \"git\": [512, 512, [], \"f1d3\", \"M216.29 158.39H137C97 147.9 6.51 150.63 6.51 233.18c0 30.09 15 51.23 35 61-25.1 23-37 33.85-37 49.21 0 11 4.47 21.14 17.89 26.81C8.13 383.61 0 393.35 0 411.65c0 32.11 28.05 50.82 101.63 50.82 70.75 0 111.79-26.42 111.79-73.18 0-58.66-45.16-56.5-151.63-63l13.43-21.55c27.27 7.58 118.7 10 118.7-67.89 0-18.7-7.73-31.71-15-41.07l37.41-2.84zm-63.42 241.9c0 32.06-104.89 32.1-104.89 2.43 0-8.14 5.27-15 10.57-21.54 77.71 5.3 94.32 3.37 94.32 19.11zm-50.81-134.58c-52.8 0-50.46-71.16 1.2-71.16 49.54 0 50.82 71.16-1.2 71.16zm133.3 100.51v-32.1c26.75-3.66 27.24-2 27.24-11V203.61c0-8.5-2.05-7.38-27.24-16.26l4.47-32.92H324v168.71c0 6.51.4 7.32 6.51 8.14l20.73 2.84v32.1zm52.45-244.31c-23.17 0-36.59-13.43-36.59-36.61s13.42-35.77 36.59-35.77c23.58 0 37 12.62 37 35.77s-13.42 36.61-37 36.61zM512 350.46c-17.49 8.53-43.1 16.26-66.28 16.26-48.38 0-66.67-19.5-66.67-65.46V194.75c0-5.42 1.05-4.06-31.71-4.06V154.5c35.78-4.07 50-22 54.47-66.27h38.63c0 65.83-1.34 61.81 3.26 61.81H501v40.65h-60.56v97.15c0 6.92-4.92 51.41 60.57 26.84z\"],\n    \"git-alt\": [448, 512, [], \"f841\", \"M439.55 236.05L244 40.45a28.87 28.87 0 0 0-40.81 0l-40.66 40.63 51.52 51.52c27.06-9.14 52.68 16.77 43.39 43.68l49.66 49.66c34.23-11.8 61.18 31 35.47 56.69-26.49 26.49-70.21-2.87-56-37.34L240.22 199v121.85c25.3 12.54 22.26 41.85 9.08 55a34.34 34.34 0 0 1-48.55 0c-17.57-17.6-11.07-46.91 11.25-56v-123c-20.8-8.51-24.6-30.74-18.64-45L142.57 101 8.45 235.14a28.86 28.86 0 0 0 0 40.81l195.61 195.6a28.86 28.86 0 0 0 40.8 0l194.69-194.69a28.86 28.86 0 0 0 0-40.81z\"],\n    \"git-square\": [448, 512, [], \"f1d2\", \"M100.59 334.24c48.57 3.31 58.95 2.11 58.95 11.94 0 20-65.55 20.06-65.55 1.52.01-5.09 3.29-9.4 6.6-13.46zm27.95-116.64c-32.29 0-33.75 44.47-.75 44.47 32.51 0 31.71-44.47.75-44.47zM448 80v352a48 48 0 0 1-48 48H48a48 48 0 0 1-48-48V80a48 48 0 0 1 48-48h352a48 48 0 0 1 48 48zm-227 69.31c0 14.49 8.38 22.88 22.86 22.88 14.74 0 23.13-8.39 23.13-22.88S258.62 127 243.88 127c-14.48 0-22.88 7.84-22.88 22.31zM199.18 195h-49.55c-25-6.55-81.56-4.85-81.56 46.75 0 18.8 9.4 32 21.85 38.11C74.23 294.23 66.8 301 66.8 310.6c0 6.87 2.79 13.22 11.18 16.76-8.9 8.4-14 14.48-14 25.92C64 373.35 81.53 385 127.52 385c44.22 0 69.87-16.51 69.87-45.73 0-36.67-28.23-35.32-94.77-39.38l8.38-13.43c17 4.74 74.19 6.23 74.19-42.43 0-11.69-4.83-19.82-9.4-25.67l23.38-1.78zm84.34 109.84l-13-1.78c-3.82-.51-4.07-1-4.07-5.09V192.52h-52.6l-2.79 20.57c15.75 5.55 17 4.86 17 10.17V298c0 5.62-.31 4.58-17 6.87v20.06h72.42zM384 315l-6.87-22.37c-40.93 15.37-37.85-12.41-37.85-16.73v-60.72h37.85v-25.41h-35.82c-2.87 0-2 2.52-2-38.63h-24.18c-2.79 27.7-11.68 38.88-34 41.42v22.62c20.47 0 19.82-.85 19.82 2.54v66.57c0 28.72 11.43 40.91 41.67 40.91 14.45 0 30.45-4.83 41.38-10.2z\"],\n    \"github\": [496, 512, [], \"f09b\", \"M165.9 397.4c0 2-2.3 3.6-5.2 3.6-3.3.3-5.6-1.3-5.6-3.6 0-2 2.3-3.6 5.2-3.6 3-.3 5.6 1.3 5.6 3.6zm-31.1-4.5c-.7 2 1.3 4.3 4.3 4.9 2.6 1 5.6 0 6.2-2s-1.3-4.3-4.3-5.2c-2.6-.7-5.5.3-6.2 2.3zm44.2-1.7c-2.9.7-4.9 2.6-4.6 4.9.3 2 2.9 3.3 5.9 2.6 2.9-.7 4.9-2.6 4.6-4.6-.3-1.9-3-3.2-5.9-2.9zM244.8 8C106.1 8 0 113.3 0 252c0 110.9 69.8 205.8 169.5 239.2 12.8 2.3 17.3-5.6 17.3-12.1 0-6.2-.3-40.4-.3-61.4 0 0-70 15-84.7-29.8 0 0-11.4-29.1-27.8-36.6 0 0-22.9-15.7 1.6-15.4 0 0 24.9 2 38.6 25.8 21.9 38.6 58.6 27.5 72.9 20.9 2.3-16 8.8-27.1 16-33.7-55.9-6.2-112.3-14.3-112.3-110.5 0-27.5 7.6-41.3 23.6-58.9-2.6-6.5-11.1-33.3 2.6-67.9 20.9-6.5 69 27 69 27 20-5.6 41.5-8.5 62.8-8.5s42.8 2.9 62.8 8.5c0 0 48.1-33.6 69-27 13.7 34.7 5.2 61.4 2.6 67.9 16 17.7 25.8 31.5 25.8 58.9 0 96.5-58.9 104.2-114.8 110.5 9.2 7.9 17 22.9 17 46.4 0 33.7-.3 75.4-.3 83.6 0 6.5 4.6 14.4 17.3 12.1C428.2 457.8 496 362.9 496 252 496 113.3 383.5 8 244.8 8zM97.2 352.9c-1.3 1-1 3.3.7 5.2 1.6 1.6 3.9 2.3 5.2 1 1.3-1 1-3.3-.7-5.2-1.6-1.6-3.9-2.3-5.2-1zm-10.8-8.1c-.7 1.3.3 2.9 2.3 3.9 1.6 1 3.6.7 4.3-.7.7-1.3-.3-2.9-2.3-3.9-2-.6-3.6-.3-4.3.7zm32.4 35.6c-1.6 1.3-1 4.3 1.3 6.2 2.3 2.3 5.2 2.6 6.5 1 1.3-1.3.7-4.3-1.3-6.2-2.2-2.3-5.2-2.6-6.5-1zm-11.4-14.7c-1.6 1-1.6 3.6 0 5.9 1.6 2.3 4.3 3.3 5.6 2.3 1.6-1.3 1.6-3.9 0-6.2-1.4-2.3-4-3.3-5.6-2z\"],\n    \"github-alt\": [480, 512, [], \"f113\", \"M186.1 328.7c0 20.9-10.9 55.1-36.7 55.1s-36.7-34.2-36.7-55.1 10.9-55.1 36.7-55.1 36.7 34.2 36.7 55.1zM480 278.2c0 31.9-3.2 65.7-17.5 95-37.9 76.6-142.1 74.8-216.7 74.8-75.8 0-186.2 2.7-225.6-74.8-14.6-29-20.2-63.1-20.2-95 0-41.9 13.9-81.5 41.5-113.6-5.2-15.8-7.7-32.4-7.7-48.8 0-21.5 4.9-32.3 14.6-51.8 45.3 0 74.3 9 108.8 36 29-6.9 58.8-10 88.7-10 27 0 54.2 2.9 80.4 9.2 34-26.7 63-35.2 107.8-35.2 9.8 19.5 14.6 30.3 14.6 51.8 0 16.4-2.6 32.7-7.7 48.2 27.5 32.4 39 72.3 39 114.2zm-64.3 50.5c0-43.9-26.7-82.6-73.5-82.6-18.9 0-37 3.4-56 6-14.9 2.3-29.8 3.2-45.1 3.2-15.2 0-30.1-.9-45.1-3.2-18.7-2.6-37-6-56-6-46.8 0-73.5 38.7-73.5 82.6 0 87.8 80.4 101.3 150.4 101.3h48.2c70.3 0 150.6-13.4 150.6-101.3zm-82.6-55.1c-25.8 0-36.7 34.2-36.7 55.1s10.9 55.1 36.7 55.1 36.7-34.2 36.7-55.1-10.9-55.1-36.7-55.1z\"],\n    \"github-square\": [448, 512, [], \"f092\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM277.3 415.7c-8.4 1.5-11.5-3.7-11.5-8 0-5.4.2-33 .2-55.3 0-15.6-5.2-25.5-11.3-30.7 37-4.1 76-9.2 76-73.1 0-18.2-6.5-27.3-17.1-39 1.7-4.3 7.4-22-1.7-45-13.9-4.3-45.7 17.9-45.7 17.9-13.2-3.7-27.5-5.6-41.6-5.6-14.1 0-28.4 1.9-41.6 5.6 0 0-31.8-22.2-45.7-17.9-9.1 22.9-3.5 40.6-1.7 45-10.6 11.7-15.6 20.8-15.6 39 0 63.6 37.3 69 74.3 73.1-4.8 4.3-9.1 11.7-10.6 22.3-9.5 4.3-33.8 11.7-48.3-13.9-9.1-15.8-25.5-17.1-25.5-17.1-16.2-.2-1.1 10.2-1.1 10.2 10.8 5 18.4 24.2 18.4 24.2 9.7 29.7 56.1 19.7 56.1 19.7 0 13.9.2 36.5.2 40.6 0 4.3-3 9.5-11.5 8-66-22.1-112.2-84.9-112.2-158.3 0-91.8 70.2-161.5 162-161.5S388 165.6 388 257.4c.1 73.4-44.7 136.3-110.7 158.3zm-98.1-61.1c-1.9.4-3.7-.4-3.9-1.7-.2-1.5 1.1-2.8 3-3.2 1.9-.2 3.7.6 3.9 1.9.3 1.3-1 2.6-3 3zm-9.5-.9c0 1.3-1.5 2.4-3.5 2.4-2.2.2-3.7-.9-3.7-2.4 0-1.3 1.5-2.4 3.5-2.4 1.9-.2 3.7.9 3.7 2.4zm-13.7-1.1c-.4 1.3-2.4 1.9-4.1 1.3-1.9-.4-3.2-1.9-2.8-3.2.4-1.3 2.4-1.9 4.1-1.5 2 .6 3.3 2.1 2.8 3.4zm-12.3-5.4c-.9 1.1-2.8.9-4.3-.6-1.5-1.3-1.9-3.2-.9-4.1.9-1.1 2.8-.9 4.3.6 1.3 1.3 1.8 3.3.9 4.1zm-9.1-9.1c-.9.6-2.6 0-3.7-1.5s-1.1-3.2 0-3.9c1.1-.9 2.8-.2 3.7 1.3 1.1 1.5 1.1 3.3 0 4.1zm-6.5-9.7c-.9.9-2.4.4-3.5-.6-1.1-1.3-1.3-2.8-.4-3.5.9-.9 2.4-.4 3.5.6 1.1 1.3 1.3 2.8.4 3.5zm-6.7-7.4c-.4.9-1.7 1.1-2.8.4-1.3-.6-1.9-1.7-1.5-2.6.4-.6 1.5-.9 2.8-.4 1.3.7 1.9 1.8 1.5 2.6z\"],\n    \"gitkraken\": [592, 512, [], \"f3a6\", \"M565.7 118.1c-2.3-6.1-9.3-9.2-15.3-6.6-5.7 2.4-8.5 8.9-6.3 14.6 10.9 29 16.9 60.5 16.9 93.3 0 134.6-100.3 245.7-230.2 262.7V358.4c7.9-1.5 15.5-3.6 23-6.2v104c106.7-25.9 185.9-122.1 185.9-236.8 0-91.8-50.8-171.8-125.8-213.3-5.7-3.2-13-.9-15.9 5-2.7 5.5-.6 12.2 4.7 15.1 67.9 37.6 113.9 110 113.9 193.2 0 93.3-57.9 173.1-139.8 205.4v-92.2c14.2-4.5 24.9-17.7 24.9-33.5 0-13.1-6.8-24.4-17.3-30.5 8.3-79.5 44.5-58.6 44.5-83.9V170c0-38-87.9-161.8-129-164.7-2.5-.2-5-.2-7.6 0C251.1 8.3 163.2 132 163.2 170v14.8c0 25.3 36.3 4.3 44.5 83.9-10.6 6.1-17.3 17.4-17.3 30.5 0 15.8 10.6 29 24.8 33.5v92.2c-81.9-32.2-139.8-112-139.8-205.4 0-83.1 46-155.5 113.9-193.2 5.4-3 7.4-9.6 4.7-15.1-2.9-5.9-10.1-8.2-15.9-5-75 41.5-125.8 121.5-125.8 213.3 0 114.7 79.2 210.8 185.9 236.8v-104c7.6 2.5 15.1 4.6 23 6.2v123.7C131.4 465.2 31 354.1 31 219.5c0-32.8 6-64.3 16.9-93.3 2.2-5.8-.6-12.2-6.3-14.6-6-2.6-13 .4-15.3 6.6C14.5 149.7 8 183.8 8 219.5c0 155.1 122.6 281.6 276.3 287.8V361.4c6.8.4 15 .5 23.4 0v145.8C461.4 501.1 584 374.6 584 219.5c0-35.7-6.5-69.8-18.3-101.4zM365.9 275.5c13 0 23.7 10.5 23.7 23.7 0 13.1-10.6 23.7-23.7 23.7-13 0-23.7-10.5-23.7-23.7 0-13.1 10.6-23.7 23.7-23.7zm-139.8 47.3c-13.2 0-23.7-10.7-23.7-23.7s10.5-23.7 23.7-23.7c13.1 0 23.7 10.6 23.7 23.7 0 13-10.5 23.7-23.7 23.7z\"],\n    \"gitlab\": [512, 512, [], \"f296\", \"M105.2 24.9c-3.1-8.9-15.7-8.9-18.9 0L29.8 199.7h132c-.1 0-56.6-174.8-56.6-174.8zM.9 287.7c-2.6 8 .3 16.9 7.1 22l247.9 184-226.2-294zm160.8-88l94.3 294 94.3-294zm349.4 88l-28.8-88-226.3 294 247.9-184c6.9-5.1 9.7-14 7.2-22zM425.7 24.9c-3.1-8.9-15.7-8.9-18.9 0l-56.6 174.8h132z\"],\n    \"gitter\": [384, 512, [], \"f426\", \"M66.4 322.5H16V0h50.4v322.5zM166.9 76.1h-50.4V512h50.4V76.1zm100.6 0h-50.4V512h50.4V76.1zM368 76h-50.4v247H368V76z\"],\n    \"glide\": [448, 512, [], \"f2a5\", \"M252.8 148.6c0 8.8-1.6 17.7-3.4 26.4-5.8 27.8-11.6 55.8-17.3 83.6-1.4 6.3-8.3 4.9-13.7 4.9-23.8 0-30.5-26-30.5-45.5 0-29.3 11.2-68.1 38.5-83.1 4.3-2.5 9.2-4.2 14.1-4.2 11.4 0 12.3 8.3 12.3 17.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 187c0-5.1-20.8-37.7-25.5-39.5-2.2-.9-7.2-2.3-9.6-2.3-23.1 0-38.7 10.5-58.2 21.5l-.5-.5c4.3-29.4 14.6-57.2 14.6-87.4 0-44.6-23.8-62.7-67.5-62.7-71.7 0-108 70.8-108 123.5 0 54.7 32 85 86.3 85 7.5 0 6.9-.6 6.9 2.3-10.5 80.3-56.5 82.9-56.5 58.9 0-24.4 28-36.5 28.3-38-.2-7.6-29.3-17.2-36.7-17.2-21.1 0-32.7 33-32.7 50.6 0 32.3 20.4 54.7 53.3 54.7 48.2 0 83.4-49.7 94.3-91.7 9.4-37.7 7-39.4 12.3-42.1 20-10.1 35.8-16.8 58.4-16.8 11.1 0 19 2.3 36.7 5.2 1.8.1 4.1-1.7 4.1-3.5z\"],\n    \"glide-g\": [448, 512, [], \"f2a6\", \"M407.1 211.2c-3.5-1.4-11.6-3.8-15.4-3.8-37.1 0-62.2 16.8-93.5 34.5l-.9-.9c7-47.3 23.5-91.9 23.5-140.4C320.8 29.1 282.6 0 212.4 0 97.3 0 39 113.7 39 198.4 39 286.3 90.3 335 177.6 335c12 0 11-1 11 3.8-16.9 128.9-90.8 133.1-90.8 94.6 0-39.2 45-58.6 45.5-61-.3-12.2-47-27.6-58.9-27.6-33.9.1-52.4 51.2-52.4 79.3C32 476 64.8 512 117.5 512c77.4 0 134-77.8 151.4-145.4 15.1-60.5 11.2-63.3 19.7-67.6 32.2-16.2 57.5-27 93.8-27 17.8 0 30.5 3.7 58.9 8.4 2.9 0 6.7-2.9 6.7-5.8 0-8-33.4-60.5-40.9-63.4zm-175.3-84.4c-9.3 44.7-18.6 89.6-27.8 134.3-2.3 10.2-13.3 7.8-22 7.8-38.3 0-49-41.8-49-73.1 0-47 18-109.3 61.8-133.4 7-4.1 14.8-6.7 22.6-6.7 18.6 0 20 13.3 20 28.7-.1 14.3-2.7 28.5-5.6 42.4z\"],\n    \"gofore\": [400, 512, [], \"f3a7\", \"M324 319.8h-13.2v34.7c-24.5 23.1-56.3 35.8-89.9 35.8-73.2 0-132.4-60.2-132.4-134.4 0-74.1 59.2-134.4 132.4-134.4 35.3 0 68.6 14 93.6 39.4l62.3-63.3C335 55.3 279.7 32 220.7 32 98 32 0 132.6 0 256c0 122.5 97 224 220.7 224 63.2 0 124.5-26.2 171-82.5-2-27.6-13.4-77.7-67.7-77.7zm-12.1-112.5H205.6v89H324c33.5 0 60.5 15.1 76 41.8v-30.6c0-65.2-40.4-100.2-88.1-100.2z\"],\n    \"goodreads\": [448, 512, [], \"f3a8\", \"M299.9 191.2c5.1 37.3-4.7 79-35.9 100.7-22.3 15.5-52.8 14.1-70.8 5.7-37.1-17.3-49.5-58.6-46.8-97.2 4.3-60.9 40.9-87.9 75.3-87.5 46.9-.2 71.8 31.8 78.2 78.3zM448 88v336c0 30.9-25.1 56-56 56H56c-30.9 0-56-25.1-56-56V88c0-30.9 25.1-56 56-56h336c30.9 0 56 25.1 56 56zM330 313.2s-.1-34-.1-217.3h-29v40.3c-.8.3-1.2-.5-1.6-1.2-9.6-20.7-35.9-46.3-76-46-51.9.4-87.2 31.2-100.6 77.8-4.3 14.9-5.8 30.1-5.5 45.6 1.7 77.9 45.1 117.8 112.4 115.2 28.9-1.1 54.5-17 69-45.2.5-1 1.1-1.9 1.7-2.9.2.1.4.1.6.2.3 3.8.2 30.7.1 34.5-.2 14.8-2 29.5-7.2 43.5-7.8 21-22.3 34.7-44.5 39.5-17.8 3.9-35.6 3.8-53.2-1.2-21.5-6.1-36.5-19-41.1-41.8-.3-1.6-1.3-1.3-2.3-1.3h-26.8c.8 10.6 3.2 20.3 8.5 29.2 24.2 40.5 82.7 48.5 128.2 37.4 49.9-12.3 67.3-54.9 67.4-106.3z\"],\n    \"goodreads-g\": [384, 512, [], \"f3a9\", \"M42.6 403.3h2.8c12.7 0 25.5 0 38.2.1 1.6 0 3.1-.4 3.6 2.1 7.1 34.9 30 54.6 62.9 63.9 26.9 7.6 54.1 7.8 81.3 1.8 33.8-7.4 56-28.3 68-60.4 8-21.5 10.7-43.8 11-66.5.1-5.8.3-47-.2-52.8l-.9-.3c-.8 1.5-1.7 2.9-2.5 4.4-22.1 43.1-61.3 67.4-105.4 69.1-103 4-169.4-57-172-176.2-.5-23.7 1.8-46.9 8.3-69.7C58.3 47.7 112.3.6 191.6 0c61.3-.4 101.5 38.7 116.2 70.3.5 1.1 1.3 2.3 2.4 1.9V10.6h44.3c0 280.3.1 332.2.1 332.2-.1 78.5-26.7 143.7-103 162.2-69.5 16.9-159 4.8-196-57.2-8-13.5-11.8-28.3-13-44.5zM188.9 36.5c-52.5-.5-108.5 40.7-115 133.8-4.1 59 14.8 122.2 71.5 148.6 27.6 12.9 74.3 15 108.3-8.7 47.6-33.2 62.7-97 54.8-154-9.7-71.1-47.8-120-119.6-119.7z\"],\n    \"google\": [488, 512, [], \"f1a0\", \"M488 261.8C488 403.3 391.1 504 248 504 110.8 504 0 393.2 0 256S110.8 8 248 8c66.8 0 123 24.5 166.3 64.9l-67.5 64.9C258.5 52.6 94.3 116.6 94.3 256c0 86.5 69.1 156.6 153.7 156.6 98.2 0 135-70.4 140.8-106.9H248v-85.3h236.1c2.3 12.7 3.9 24.9 3.9 41.4z\"],\n    \"google-drive\": [512, 512, [], \"f3aa\", \"M339 314.9L175.4 32h161.2l163.6 282.9H339zm-137.5 23.6L120.9 480h310.5L512 338.5H201.5zM154.1 67.4L0 338.5 80.6 480 237 208.8 154.1 67.4z\"],\n    \"google-play\": [512, 512, [], \"f3ab\", \"M325.3 234.3L104.6 13l280.8 161.2-60.1 60.1zM47 0C34 6.8 25.3 19.2 25.3 35.3v441.3c0 16.1 8.7 28.5 21.7 35.3l256.6-256L47 0zm425.2 225.6l-58.9-34.1-65.7 64.5 65.7 64.5 60.1-34.1c18-14.3 18-46.5-1.2-60.8zM104.6 499l280.8-161.2-60.1-60.1L104.6 499z\"],\n    \"google-plus\": [496, 512, [], \"f2b3\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm-70.7 372c-68.8 0-124-55.5-124-124s55.2-124 124-124c31.3 0 60.1 11 83 32.3l-33.6 32.6c-13.2-12.9-31.3-19.1-49.4-19.1-42.9 0-77.2 35.5-77.2 78.1s34.2 78.1 77.2 78.1c32.6 0 64.9-19.1 70.1-53.3h-70.1v-42.6h116.9c1.3 6.8 1.9 13.6 1.9 20.7 0 70.8-47.5 121.2-118.8 121.2zm230.2-106.2v35.5H372v-35.5h-35.5v-35.5H372v-35.5h35.5v35.5h35.2v35.5h-35.2z\"],\n    \"google-plus-g\": [640, 512, [], \"f0d5\", \"M386.061 228.496c1.834 9.692 3.143 19.384 3.143 31.956C389.204 370.205 315.599 448 204.8 448c-106.084 0-192-85.915-192-192s85.916-192 192-192c51.864 0 95.083 18.859 128.611 50.292l-52.126 50.03c-14.145-13.621-39.028-29.599-76.485-29.599-65.484 0-118.92 54.221-118.92 121.277 0 67.056 53.436 121.277 118.92 121.277 75.961 0 104.513-54.745 108.965-82.773H204.8v-66.009h181.261zm185.406 6.437V179.2h-56.001v55.733h-55.733v56.001h55.733v55.733h56.001v-55.733H627.2v-56.001h-55.733z\"],\n    \"google-plus-square\": [448, 512, [], \"f0d4\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM164 356c-55.3 0-100-44.7-100-100s44.7-100 100-100c27 0 49.5 9.8 67 26.2l-27.1 26.1c-7.4-7.1-20.3-15.4-39.8-15.4-34.1 0-61.9 28.2-61.9 63.2 0 34.9 27.8 63.2 61.9 63.2 39.6 0 54.4-28.5 56.8-43.1H164v-34.4h94.4c1 5 1.6 10.1 1.6 16.6 0 57.1-38.3 97.6-96 97.6zm220-81.8h-29v29h-29.2v-29h-29V245h29v-29H355v29h29v29.2z\"],\n    \"google-wallet\": [448, 512, [], \"f1ee\", \"M156.8 126.8c37.6 60.6 64.2 113.1 84.3 162.5-8.3 33.8-18.8 66.5-31.3 98.3-13.2-52.3-26.5-101.3-56-148.5 6.5-36.4 2.3-73.6 3-112.3zM109.3 200H16.1c-6.5 0-10.5 7.5-6.5 12.7C51.8 267 81.3 330.5 101.3 400h103.5c-16.2-69.7-38.7-133.7-82.5-193.5-3-4-8-6.5-13-6.5zm47.8-88c68.5 108 130 234.5 138.2 368H409c-12-138-68.4-265-143.2-368H157.1zm251.8-68.5c-1.8-6.8-8.2-11.5-15.2-11.5h-88.3c-5.3 0-9 5-7.8 10.3 13.2 46.5 22.3 95.5 26.5 146 48.2 86.2 79.7 178.3 90.6 270.8 15.8-60.5 25.3-133.5 25.3-203 0-73.6-12.1-145.1-31.1-212.6z\"],\n    \"gratipay\": [496, 512, [], \"f184\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm114.6 226.4l-113 152.7-112.7-152.7c-8.7-11.9-19.1-50.4 13.6-72 28.1-18.1 54.6-4.2 68.5 11.9 15.9 17.9 46.6 16.9 61.7 0 13.9-16.1 40.4-30 68.1-11.9 32.9 21.6 22.6 60 13.8 72z\"],\n    \"grav\": [512, 512, [], \"f2d6\", \"M301.1 212c4.4 4.4 4.4 11.9 0 16.3l-9.7 9.7c-4.4 4.7-11.9 4.7-16.6 0l-10.5-10.5c-4.4-4.7-4.4-11.9 0-16.6l9.7-9.7c4.4-4.4 11.9-4.4 16.6 0l10.5 10.8zm-30.2-19.7c3-3 3-7.8 0-10.5-2.8-3-7.5-3-10.5 0-2.8 2.8-2.8 7.5 0 10.5 3.1 2.8 7.8 2.8 10.5 0zm-26 5.3c-3 2.8-3 7.5 0 10.2 2.8 3 7.5 3 10.5 0 2.8-2.8 2.8-7.5 0-10.2-3-3-7.7-3-10.5 0zm72.5-13.3c-19.9-14.4-33.8-43.2-11.9-68.1 21.6-24.9 40.7-17.2 59.8.8 11.9 11.3 29.3 24.9 17.2 48.2-12.5 23.5-45.1 33.2-65.1 19.1zm47.7-44.5c-8.9-10-23.3 6.9-15.5 16.1 7.4 9 32.1 2.4 15.5-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-66.2 42.6c2.5-16.1-20.2-16.6-25.2-25.7-13.6-24.1-27.7-36.8-54.5-30.4 11.6-8 23.5-6.1 23.5-6.1.3-6.4 0-13-9.4-24.9 3.9-12.5.3-22.4.3-22.4 15.5-8.6 26.8-24.4 29.1-43.2 3.6-31-18.8-59.2-49.8-62.8-22.1-2.5-43.7 7.7-54.3 25.7-23.2 40.1 1.4 70.9 22.4 81.4-14.4-1.4-34.3-11.9-40.1-34.3-6.6-25.7 2.8-49.8 8.9-61.4 0 0-4.4-5.8-8-8.9 0 0-13.8 0-24.6 5.3 11.9-15.2 25.2-14.4 25.2-14.4 0-6.4-.6-14.9-3.6-21.6-5.4-11-23.8-12.9-31.7 2.8.1-.2.3-.4.4-.5-5 11.9-1.1 55.9 16.9 87.2-2.5 1.4-9.1 6.1-13 10-21.6 9.7-56.2 60.3-56.2 60.3-28.2 10.8-77.2 50.9-70.6 79.7.3 3 1.4 5.5 3 7.5-2.8 2.2-5.5 5-8.3 8.3-11.9 13.8-5.3 35.2 17.7 24.4 15.8-7.2 29.6-20.2 36.3-30.4 0 0-5.5-5-16.3-4.4 27.7-6.6 34.3-9.4 46.2-9.1 8 3.9 8-34.3 8-34.3 0-14.7-2.2-31-11.1-41.5 12.5 12.2 29.1 32.7 28 60.6-.8 18.3-15.2 23-15.2 23-9.1 16.6-43.2 65.9-30.4 106 0 0-9.7-14.9-10.2-22.1-17.4 19.4-46.5 52.3-24.6 64.5 26.6 14.7 108.8-88.6 126.2-142.3 34.6-20.8 55.4-47.3 63.9-65 22 43.5 95.3 94.5 101.1 59z\"],\n    \"gripfire\": [384, 512, [], \"f3ac\", \"M112.5 301.4c0-73.8 105.1-122.5 105.1-203 0-47.1-34-88-39.1-90.4.4 3.3.6 6.7.6 10C179.1 110.1 32 171.9 32 286.6c0 49.8 32.2 79.2 66.5 108.3 65.1 46.7 78.1 71.4 78.1 86.6 0 10.1-4.8 17-4.8 22.3 13.1-16.7 17.4-31.9 17.5-46.4 0-29.6-21.7-56.3-44.2-86.5-16-22.3-32.6-42.6-32.6-69.5zm205.3-39c-12.1-66.8-78-124.4-94.7-130.9l4 7.2c2.4 5.1 3.4 10.9 3.4 17.1 0 44.7-54.2 111.2-56.6 116.7-2.2 5.1-3.2 10.5-3.2 15.8 0 20.1 15.2 42.1 17.9 42.1 2.4 0 56.6-55.4 58.1-87.7 6.4 11.7 9.1 22.6 9.1 33.4 0 41.2-41.8 96.9-41.8 96.9 0 11.6 31.9 53.2 35.5 53.2 1 0 2.2-1.4 3.2-2.4 37.9-39.3 67.3-85 67.3-136.8 0-8-.7-16.2-2.2-24.6z\"],\n    \"grunt\": [384, 512, [], \"f3ad\", \"M61.3 189.3c-1.1 10 5.2 19.1 5.2 19.1.7-7.5 2.2-12.8 4-16.6.4 10.3 3.2 23.5 12.8 34.1 6.9 7.6 35.6 23.3 54.9 6.1 1 2.4 2.1 5.3 3 8.5 2.9 10.3-2.7 25.3-2.7 25.3s15.1-17.1 13.9-32.5c10.8-.5 21.4-8.4 21.1-19.5 0 0-18.9 10.4-35.5-8.8-9.7-11.2-40.9-42-83.1-31.8 4.3 1 8.9 2.4 13.5 4.1h-.1c-4.2 2-6.5 7.1-7 12zm28.3-1.8c19.5 11 37.4 25.7 44.9 37-5.7 3.3-21.7 10.4-38-1.7-10.3-7.6-9.8-26.2-6.9-35.3zm142.1 45.8c-1.2 15.5 13.9 32.5 13.9 32.5s-5.6-15-2.7-25.3c.9-3.2 2-6 3-8.5 19.3 17.3 48 1.5 54.8-6.1 9.6-10.6 12.3-23.8 12.8-34.1 1.8 3.8 3.4 9.1 4 16.6 0 0 6.4-9.1 5.2-19.1-.6-5-2.9-10-7-11.8h-.1c4.6-1.8 9.2-3.2 13.5-4.1-42.3-10.2-73.4 20.6-83.1 31.8-16.7 19.2-35.5 8.8-35.5 8.8-.2 10.9 10.4 18.9 21.2 19.3zm62.7-45.8c3 9.1 3.4 27.7-7 35.4-16.3 12.1-32.2 5-37.9 1.6 7.5-11.4 25.4-26 44.9-37zM160 418.5h-29.4c-5.5 0-8.2 1.6-9.5 2.9-1.9 2-2.2 4.7-.9 8.1 3.5 9.1 11.4 16.5 13.7 18.6 3.1 2.7 7.5 4.3 11.8 4.3 4.4 0 8.3-1.7 11-4.6 7.5-8.2 11.9-17.1 13-19.8.6-1.5 1.3-4.5-.9-6.8-1.8-1.8-4.7-2.7-8.8-2.7zm189.2-101.2c-2.4 17.9-13 33.8-24.6 43.7-3.1-22.7-3.7-55.5-3.7-62.4 0-14.7 9.5-24.5 12.2-26.1 2.5-1.5 5.4-3 8.3-4.6 18-9.6 40.4-21.6 40.4-43.7 0-16.2-9.3-23.2-15.4-27.8-.8-.6-1.5-1.1-2.2-1.7-2.1-1.7-3.7-3-4.3-4.4-4.4-9.8-3.6-34.2-1.7-37.6.6-.6 16.7-20.9 11.8-39.2-2-7.4-6.9-13.3-14.1-17-5.3-2.7-11.9-4.2-19.5-4.5-.1-2-.5-3.9-.9-5.9-.6-2.6-1.1-5.3-.9-8.1.4-4.7.8-9 2.2-11.3 8.4-13.3 28.8-17.6 29-17.6l12.3-2.4-8.1-9.5c-.1-.2-17.3-17.5-46.3-17.5-7.9 0-16 1.3-24.1 3.9-24.2 7.8-42.9 30.5-49.4 39.3-3.1-1-6.3-1.9-9.6-2.7-4.2-15.8 9-38.5 9-38.5s-13.6-3-33.7 15.2c-2.6-6.5-8.1-20.5-1.8-37.2C184.6 10.1 177.2 26 175 40.4c-7.6-5.4-6.7-23.1-7.2-27.6-7.5.9-29.2 21.9-28.2 48.3-2 .5-3.9 1.1-5.9 1.7-6.5-8.8-25.1-31.5-49.4-39.3-7.9-2.2-16-3.5-23.9-3.5-29 0-46.1 17.3-46.3 17.5L6 46.9l12.3 2.4c.2 0 20.6 4.3 29 17.6 1.4 2.2 1.8 6.6 2.2 11.3.2 2.8-.4 5.5-.9 8.1-.4 1.9-.8 3.9-.9 5.9-7.7.3-14.2 1.8-19.5 4.5-7.2 3.7-12.1 9.6-14.1 17-5 18.2 11.2 38.5 11.8 39.2 1.9 3.4 2.7 27.8-1.7 37.6-.6 1.4-2.2 2.7-4.3 4.4-.7.5-1.4 1.1-2.2 1.7-6.1 4.6-15.4 11.7-15.4 27.8 0 22.1 22.4 34.1 40.4 43.7 3 1.6 5.8 3.1 8.3 4.6 2.7 1.6 12.2 11.4 12.2 26.1 0 6.9-.6 39.7-3.7 62.4-11.6-9.9-22.2-25.9-24.6-43.8 0 0-29.2 22.6-20.6 70.8 5.2 29.5 23.2 46.1 47 54.7 8.8 19.1 29.4 45.7 67.3 49.6C143 504.3 163 512 192.2 512h.2c29.1 0 49.1-7.7 63.6-19.5 37.9-3.9 58.5-30.5 67.3-49.6 23.8-8.7 41.7-25.2 47-54.7 8.2-48.4-21.1-70.9-21.1-70.9zM305.7 37.7c5.6-1.8 11.6-2.7 17.7-2.7 11 0 19.9 3 24.7 5-3.1 1.4-6.4 3.2-9.7 5.3-2.4-.4-5.6-.8-9.2-.8-10.5 0-20.5 3.1-28.7 8.9-12.3 8.7-18 16.9-20.7 22.4-2.2-1.3-4.5-2.5-7.1-3.7-1.6-.8-3.1-1.5-4.7-2.2 6.1-9.1 19.9-26.5 37.7-32.2zm21 18.2c-.8 1-1.6 2.1-2.3 3.2-3.3 5.2-3.9 11.6-4.4 17.8-.5 6.4-1.1 12.5-4.4 17-4.2.8-8.1 1.7-11.5 2.7-2.3-3.1-5.6-7-10.5-11.2 1.4-4.8 5.5-16.1 13.5-22.5 5.6-4.3 12.2-6.7 19.6-7zM45.6 45.3c-3.3-2.2-6.6-4-9.7-5.3 4.8-2 13.7-5 24.7-5 6.1 0 12 .9 17.7 2.7 17.8 5.8 31.6 23.2 37.7 32.1-1.6.7-3.2 1.4-4.8 2.2-2.5 1.2-4.9 2.5-7.1 3.7-2.6-5.4-8.3-13.7-20.7-22.4-8.3-5.8-18.2-8.9-28.8-8.9-3.4.1-6.6.5-9 .9zm44.7 40.1c-4.9 4.2-8.3 8-10.5 11.2-3.4-.9-7.3-1.9-11.5-2.7C65 89.5 64.5 83.4 64 77c-.5-6.2-1.1-12.6-4.4-17.8-.7-1.1-1.5-2.2-2.3-3.2 7.4.3 14 2.6 19.5 7 8 6.3 12.1 17.6 13.5 22.4zM58.1 259.9c-2.7-1.6-5.6-3.1-8.4-4.6-14.9-8-30.2-16.3-30.2-30.5 0-11.1 4.3-14.6 8.9-18.2l.5-.4c.7-.6 1.4-1.2 2.2-1.8-.9 7.2-1.9 13.3-2.7 14.9 0 0 12.1-15 15.7-44.3 1.4-11.5-1.1-34.3-5.1-43 .2 4.9 0 9.8-.3 14.4-.4-.8-.8-1.6-1.3-2.2-3.2-4-11.8-17.5-9.4-26.6.9-3.5 3.1-6 6.7-7.8 3.8-1.9 8.8-2.9 15.1-2.9 12.3 0 25.9 3.7 32.9 6 25.1 8 55.4 30.9 64.1 37.7.2.2.4.3.4.3l5.6 3.9-3.5-5.8c-.2-.3-19.1-31.4-53.2-46.5 2-2.9 7.4-8.1 21.6-15.1 21.4-10.5 46.5-15.8 74.3-15.8 27.9 0 52.9 5.3 74.3 15.8 14.2 6.9 19.6 12.2 21.6 15.1-34 15.1-52.9 46.2-53.1 46.5l-3.5 5.8 5.6-3.9s.2-.1.4-.3c8.7-6.8 39-29.8 64.1-37.7 7-2.2 20.6-6 32.9-6 6.3 0 11.3 1 15.1 2.9 3.5 1.8 5.7 4.4 6.7 7.8 2.5 9.1-6.1 22.6-9.4 26.6-.5.6-.9 1.3-1.3 2.2-.3-4.6-.5-9.5-.3-14.4-4 8.8-6.5 31.5-5.1 43 3.6 29.3 15.7 44.3 15.7 44.3-.8-1.6-1.8-7.7-2.7-14.9.7.6 1.5 1.2 2.2 1.8l.5.4c4.6 3.7 8.9 7.1 8.9 18.2 0 14.2-15.4 22.5-30.2 30.5-2.9 1.5-5.7 3.1-8.4 4.6-8.7 5-18 16.7-19.1 34.2-.9 14.6.9 49.9 3.4 75.9-12.4 4.8-26.7 6.4-39.7 6.8-2-4.1-3.9-8.5-5.5-13.1-.7-2-19.6-51.1-26.4-62.2 5.5 39 17.5 73.7 23.5 89.6-3.5-.5-7.3-.7-11.7-.7h-117c-4.4 0-8.3.3-11.7.7 6-15.9 18.1-50.6 23.5-89.6-6.8 11.2-25.7 60.3-26.4 62.2-1.6 4.6-3.5 9-5.5 13.1-13-.4-27.2-2-39.7-6.8 2.5-26 4.3-61.2 3.4-75.9-.9-17.4-10.3-29.2-19-34.2zM34.8 404.6c-12.1-20-8.7-54.1-3.7-59.1 10.9 34.4 47.2 44.3 74.4 45.4-2.7 4.2-5.2 7.6-7 10l-1.4 1.4c-7.2 7.8-8.6 18.5-4.1 31.8-22.7-.1-46.3-9.8-58.2-29.5zm45.7 43.5c6 1.1 12.2 1.9 18.6 2.4 3.5 8 7.4 15.9 12.3 23.1-14.4-5.9-24.4-16-30.9-25.5zM192 498.2c-60.6-.1-78.3-45.8-84.9-64.7-3.7-10.5-3.4-18.2.9-23.1 2.9-3.3 9.5-7.2 24.6-7.2h118.8c15.1 0 21.8 3.9 24.6 7.2 4.2 4.8 4.5 12.6.9 23.1-6.6 18.8-24.3 64.6-84.9 64.7zm80.6-24.6c4.9-7.2 8.8-15.1 12.3-23.1 6.4-.5 12.6-1.3 18.6-2.4-6.5 9.5-16.5 19.6-30.9 25.5zm76.6-69c-12 19.7-35.6 29.3-58.1 29.7 4.5-13.3 3.1-24.1-4.1-31.8-.4-.5-.9-1-1.4-1.5-1.8-2.4-4.3-5.8-7-10 27.2-1.2 63.5-11 74.4-45.4 5 5 8.4 39.1-3.8 59zM191.9 187.7h.2c12.7-.1 27.2-17.8 27.2-17.8-9.9 6-18.8 8.1-27.3 8.3-8.5-.2-17.4-2.3-27.3-8.3 0 0 14.5 17.6 27.2 17.8zm61.7 230.7h-29.4c-4.2 0-7.2.9-8.9 2.7-2.2 2.3-1.5 5.2-.9 6.7 1 2.6 5.5 11.3 13 19.3 2.7 2.9 6.6 4.5 11 4.5s8.7-1.6 11.8-4.2c2.3-2 10.2-9.2 13.7-18.1 1.3-3.3 1-6-.9-7.9-1.3-1.3-4-2.9-9.4-3z\"],\n    \"gulp\": [256, 512, [], \"f3ae\", \"M209.8 391.1l-14.1 24.6-4.6 80.2c0 8.9-28.3 16.1-63.1 16.1s-63.1-7.2-63.1-16.1l-5.8-79.4-14.9-25.4c41.2 17.3 126 16.7 165.6 0zm-196-253.3l13.6 125.5c5.9-20 20.8-47 40-55.2 6.3-2.7 12.7-2.7 18.7.9 5.2 3 9.6 9.3 10.1 11.8 1.2 6.5-2 9.1-4.5 9.1-3 0-5.3-4.6-6.8-7.3-4.1-7.3-10.3-7.6-16.9-2.8-6.9 5-12.9 13.4-17.1 20.7-5.1 8.8-9.4 18.5-12 28.2-1.5 5.6-2.9 14.6-.6 19.9 1 2.2 2.5 3.6 4.9 3.6 5 0 12.3-6.6 15.8-10.1 4.5-4.5 10.3-11.5 12.5-16l5.2-15.5c2.6-6.8 9.9-5.6 9.9 0 0 10.2-3.7 13.6-10 34.7-5.8 19.5-7.6 25.8-7.6 25.8-.7 2.8-3.4 7.5-6.3 7.5-1.2 0-2.1-.4-2.6-1.2-1-1.4-.9-5.3-.8-6.3.2-3.2 6.3-22.2 7.3-25.2-2 2.2-4.1 4.4-6.4 6.6-5.4 5.1-14.1 11.8-21.5 11.8-3.4 0-5.6-.9-7.7-2.4l7.6 79.6c2 5 39.2 17.1 88.2 17.1 49.1 0 86.3-12.2 88.2-17.1l10.9-94.6c-5.7 5.2-12.3 11.6-19.6 14.8-5.4 2.3-17.4 3.8-17.4-5.7 0-5.2 9.1-14.8 14.4-21.5 1.4-1.7 4.7-5.9 4.7-8.1 0-2.9-6-2.2-11.7 2.5-3.2 2.7-6.2 6.3-8.7 9.7-4.3 6-6.6 11.2-8.5 15.5-6.2 14.2-4.1 8.6-9.1 22-5 13.3-4.2 11.8-5.2 14-.9 1.9-2.2 3.5-4 4.5-1.9 1-4.5.9-6.1-.3-.9-.6-1.3-1.9-1.3-3.7 0-.9.1-1.8.3-2.7 1.5-6.1 7.8-18.1 15-34.3 1.6-3.7 1-2.6.8-2.3-6.2 6-10.9 8.9-14.4 10.5-5.8 2.6-13 2.6-14.5-4.1-.1-.4-.1-.8-.2-1.2-11.8 9.2-24.3 11.7-20-8.1-4.6 8.2-12.6 14.9-22.4 14.9-4.1 0-7.1-1.4-8.6-5.1-2.3-5.5 1.3-14.9 4.6-23.8 1.7-4.5 4-9.9 7.1-16.2 1.6-3.4 4.2-5.4 7.6-4.5.6.2 1.1.4 1.6.7 2.6 1.8 1.6 4.5.3 7.2-3.8 7.5-7.1 13-9.3 20.8-.9 3.3-2 9 1.5 9 2.4 0 4.7-.8 6.9-2.4 4.6-3.4 8.3-8.5 11.1-13.5 2-3.6 4.4-8.3 5.6-12.3.5-1.7 1.1-3.3 1.8-4.8 1.1-2.5 2.6-5.1 5.2-5.1 1.3 0 2.4.5 3.2 1.5 1.7 2.2 1.3 4.5.4 6.9-2 5.6-4.7 10.6-6.9 16.7-1.3 3.5-2.7 8-2.7 11.7 0 3.4 3.7 2.6 6.8 1.2 2.4-1.1 4.8-2.8 6.8-4.5 1.2-4.9.9-3.8 26.4-68.2 1.3-3.3 3.7-4.7 6.1-4.7 1.2 0 2.2.4 3.2 1.1 1.7 1.3 1.7 4.1 1 6.2-.7 1.9-.6 1.3-4.5 10.5-5.2 12.1-8.6 20.8-13.2 31.9-1.9 4.6-7.7 18.9-8.7 22.3-.6 2.2-1.3 5.8 1 5.8 5.4 0 19.3-13.1 23.1-17 .2-.3.5-.4.9-.6.6-1.9 1.2-3.7 1.7-5.5 1.4-3.8 2.7-8.2 5.3-11.3.8-1 1.7-1.6 2.7-1.6 2.8 0 4.2 1.2 4.2 4 0 1.1-.7 5.1-1.1 6.2 1.4-1.5 2.9-3 4.5-4.5 15-13.9 25.7-6.8 25.7.2 0 7.4-8.9 17.7-13.8 23.4-1.6 1.9-4.9 5.4-5 6.4 0 1.3.9 1.8 2.2 1.8 2 0 6.4-3.5 8-4.7 5-3.9 11.8-9.9 16.6-14.1l14.8-136.8c-30.5 17.1-197.6 17.2-228.3.2zm229.7-8.5c0 21-231.2 21-231.2 0 0-8.8 51.8-15.9 115.6-15.9 9 0 17.8.1 26.3.4l12.6-48.7L228.1.6c1.4-1.4 5.8-.2 9.9 3.5s6.6 7.9 5.3 9.3l-.1.1L185.9 74l-10 40.7c39.9 2.6 67.6 8.1 67.6 14.6zm-69.4 4.6c0-.8-.9-1.5-2.5-2.1l-.2.8c0 1.3-5 2.4-11.1 2.4s-11.1-1.1-11.1-2.4c0-.1 0-.2.1-.3l.2-.7c-1.8.6-3 1.4-3 2.3 0 2.1 6.2 3.7 13.7 3.7 7.7.1 13.9-1.6 13.9-3.7z\"],\n    \"hacker-news\": [448, 512, [], \"f1d4\", \"M0 32v448h448V32H0zm21.2 197.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hacker-news-square\": [448, 512, [], \"f3af\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.2 229.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hackerrank\": [512, 512, [], \"f5f7\", \"M477.5 128C463 103.05 285.13 0 256.16 0S49.25 102.79 34.84 128s-14.49 230.8 0 256 192.38 128 221.32 128S463 409.08 477.49 384s14.51-231 .01-256zM316.13 414.22c-4 0-40.91-35.77-38-38.69.87-.87 6.26-1.48 17.55-1.83 0-26.23.59-68.59.94-86.32 0-2-.44-3.43-.44-5.85h-79.93c0 7.1-.46 36.2 1.37 72.88.23 4.54-1.58 6-5.74 5.94-10.13 0-20.27-.11-30.41-.08-4.1 0-5.87-1.53-5.74-6.11.92-33.44 3-84-.15-212.67v-3.17c-9.67-.35-16.38-1-17.26-1.84-2.92-2.92 34.54-38.69 38.49-38.69s41.17 35.78 38.27 38.69c-.87.87-7.9 1.49-16.77 1.84v3.16c-2.42 25.75-2 79.59-2.63 105.39h80.26c0-4.55.39-34.74-1.2-83.64-.1-3.39.95-5.17 4.21-5.2 11.07-.08 22.15-.13 33.23-.06 3.46 0 4.57 1.72 4.5 5.38C333 354.64 336 341.29 336 373.69c8.87.35 16.82 1 17.69 1.84 2.88 2.91-33.62 38.69-37.58 38.69z\"],\n    \"hips\": [640, 512, [], \"f452\", \"M251.6 157.6c0-1.9-.9-2.8-2.8-2.8h-40.9c-1.6 0-2.7 1.4-2.7 2.8v201.8c0 1.4 1.1 2.8 2.7 2.8h40.9c1.9 0 2.8-.9 2.8-2.8zM156.5 168c-16.1-11.8-36.3-17.9-60.3-18-18.1-.1-34.6 3.7-49.8 11.4V80.2c0-1.8-.9-2.7-2.8-2.7H2.7c-1.8 0-2.7.9-2.7 2.7v279.2c0 1.9.9 2.8 2.7 2.8h41c1.9 0 2.8-.9 2.8-2.8V223.3c0-.8-2.8-27 45.8-27 48.5 0 45.8 26.1 45.8 27v122.6c0 9 7.3 16.3 16.4 16.3h27.3c1.8 0 2.7-.9 2.7-2.8V223.3c0-23.4-9.3-41.8-28-55.3zm478.4 110.1c-6.8-15.7-18.4-27-34.9-34.1l-57.6-25.3c-8.6-3.6-9.2-11.2-2.6-16.1 7.4-5.5 44.3-13.9 84 6.8 1.7 1 4-.3 4-2.4v-44.7c0-1.3-.6-2.1-1.9-2.6-17.7-6.6-36.1-9.9-55.1-9.9-26.5 0-45.3 5.8-58.5 15.4-.5.4-28.4 20-22.7 53.7 3.4 19.6 15.8 34.2 37.2 43.6l53.6 23.5c11.6 5.1 15.2 13.3 12.2 21.2-3.7 9.1-13.2 13.6-36.5 13.6-24.3 0-44.7-8.9-58.4-19.1-2.1-1.4-4.4.2-4.4 2.3v34.4c0 10.4 4.9 17.3 14.6 20.7 15.6 5.5 31.6 8.2 48.2 8.2 12.7 0 25.8-1.2 36.3-4.3.7-.3 36-8.9 45.6-45.8 3.5-13.5 2.4-26.5-3.1-39.1zM376.2 149.8c-31.7 0-104.2 20.1-104.2 103.5v183.5c0 .8.6 2.7 2.7 2.7h40.9c1.9 0 2.8-.9 2.8-2.7V348c16.5 12.7 35.8 19.1 57.7 19.1 60.5 0 108.7-48.5 108.7-108.7.1-60.3-48.2-108.6-108.6-108.6zm0 170.9c-17.2 0-31.9-6.1-44-18.2-12.2-12.2-18.2-26.8-18.2-44 0-34.5 27.6-62.2 62.2-62.2 34.5 0 62.2 27.6 62.2 62.2.1 34.3-27.3 62.2-62.2 62.2zM228.3 72.5c-15.9 0-28.8 12.9-28.9 28.9 0 15.6 12.7 28.9 28.9 28.9s28.9-13.1 28.9-28.9c0-16.2-13-28.9-28.9-28.9z\"],\n    \"hire-a-helper\": [512, 512, [], \"f3b0\", \"M443.1 0H71.9C67.9 37.3 37.4 67.8 0 71.7v371.5c37.4 4.9 66 32.4 71.9 68.8h372.2c3-36.4 32.5-65.8 67.9-69.8V71.7c-36.4-5.9-65-35.3-68.9-71.7zm-37 404.9c-36.3 0-18.8-2-55.1-2-35.8 0-21 2-56.1 2-5.9 0-4.9-8.2 0-9.8 22.8-7.6 22.9-10.2 24.6-12.8 10.4-15.6 5.9-83 5.9-113 0-5.3-6.4-12.8-13.8-12.8H200.4c-7.4 0-13.8 7.5-13.8 12.8 0 30-4.5 97.4 5.9 113 1.7 2.5 1.8 5.2 24.6 12.8 4.9 1.6 6 9.8 0 9.8-35.1 0-20.3-2-56.1-2-36.3 0-18.8 2-55.1 2-7.9 0-5.8-10.8 0-10.8 10.2-3.4 13.5-3.5 21.7-13.8 7.7-12.9 7.9-44.4 7.9-127.8V151.3c0-22.2-12.2-28.3-28.6-32.4-8.8-2.2-4-11.8 1-11.8 36.5 0 20.6 2 57.1 2 32.7 0 16.5-2 49.2-2 3.3 0 8.5 8.3 1 10.8-4.9 1.6-27.6 3.7-27.6 39.3 0 45.6-.2 55.8 1 68.8 0 1.3 2.3 12.8 12.8 12.8h109.2c10.5 0 12.8-11.5 12.8-12.8 1.2-13 1-23.2 1-68.8 0-35.6-22.7-37.7-27.6-39.3-7.5-2.5-2.3-10.8 1-10.8 32.7 0 16.5 2 49.2 2 36.5 0 20.6-2 57.1-2 4.9 0 9.9 9.6 1 11.8-16.4 4.1-28.6 10.3-28.6 32.4v101.2c0 83.4.1 114.9 7.9 127.8 8.2 10.2 11.4 10.4 21.7 13.8 5.8 0 7.8 10.8 0 10.8z\"],\n    \"hooli\": [640, 512, [], \"f427\", \"M144.5 352l38.3.8c-13.2-4.6-26-10.2-38.3-16.8zm57.7-5.3v5.3l-19.4.8c36.5 12.5 69.9 14.2 94.7 7.2-19.9.2-45.8-2.6-75.3-13.3zm408.9-115.2c15.9 0 28.9-12.9 28.9-28.9s-12.9-24.5-28.9-24.5c-15.9 0-28.9 8.6-28.9 24.5s12.9 28.9 28.9 28.9zm-29 120.5H640V241.5h-57.9zm-73.7 0h57.9V156.7L508.4 184zm-31-119.4c-18.2-18.2-50.4-17.1-50.4-17.1s-32.3-1.1-50.4 17.1c-18.2 18.2-16.8 33.9-16.8 52.6s-1.4 34.3 16.8 52.5 50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.8-33.8 16.8-52.5-.1-18.8 1.3-34.5-16.8-52.6zm-39.8 71.9c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9zm-106.2-71.9c-18.2-18.2-50.4-17.1-50.4-17.1s-32.2-1.1-50.4 17.1c-1.9 1.9-3.7 3.9-5.3 6-38.2-29.6-72.5-46.5-102.1-61.1v-20.7l-22.5 10.6c-54.4-22.1-89-18.2-97.3.1 0 0-24.9 32.8 61.8 110.8V352h57.9v-28.6c-6.5-4.2-13-8.7-19.4-13.6-14.8-11.2-27.4-21.6-38.4-31.4v-31c13.1 14.7 30.5 31.4 53.4 50.3l4.5 3.6v-29.8c0-6.9 1.7-18.2 10.8-18.2s10.6 6.9 10.6 15V317c18 12.2 37.3 22.1 57.7 29.6v-93.9c0-18.7-13.4-37.4-40.6-37.4-15.8-.1-30.5 8.2-38.5 21.9v-54.3c41.9 20.9 83.9 46.5 99.9 58.3-10.2 14.6-9.3 28.1-9.3 43.7 0 18.7-1.4 34.3 16.8 52.5s50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.7-33.8 16.7-52.5 0-18.5 1.5-34.2-16.7-52.3zM65.2 184v63.3c-48.7-54.5-38.9-76-35.2-79.1 13.5-11.4 37.5-8 64.4 2.1zm226.5 120.5c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9z\"],\n    \"hornbill\": [512, 512, [], \"f592\", \"M76.38 370.3a37.8 37.8 0 1 1-32.07-32.42c-78.28-111.35 52-190.53 52-190.53-5.86 43-8.24 91.16-8.24 91.16-67.31 41.49.93 64.06 39.81 72.87a140.38 140.38 0 0 0 131.66 91.94c1.92 0 3.77-.21 5.67-.28l.11 18.86c-99.22 1.39-158.7-29.14-188.94-51.6zm108-327.7A37.57 37.57 0 0 0 181 21.45a37.95 37.95 0 1 0-31.17 54.22c-22.55 29.91-53.83 89.57-52.42 190l21.84-.15c0-.9-.14-1.77-.14-2.68A140.42 140.42 0 0 1 207 132.71c8-37.71 30.7-114.3 73.8-44.29 0 0 48.14 2.38 91.18 8.24 0 0-77.84-128-187.59-54.06zm304.19 134.17a37.94 37.94 0 1 0-53.84-28.7C403 126.13 344.89 99 251.28 100.33l.14 22.5c2.7-.15 5.39-.41 8.14-.41a140.37 140.37 0 0 1 130.49 88.76c39.1 9 105.06 31.58 38.46 72.54 0 0-2.34 48.13-8.21 91.16 0 0 133.45-81.16 49-194.61a37.45 37.45 0 0 0 19.31-3.5zM374.06 436.24c21.43-32.46 46.42-89.69 45.14-179.66l-19.52.14c.08 2.06.3 4.07.3 6.15a140.34 140.34 0 0 1-91.39 131.45c-8.85 38.95-31.44 106.66-72.77 39.49 0 0-48.12-2.34-91.19-8.22 0 0 79.92 131.34 191.9 51a37.5 37.5 0 0 0 3.64 14 37.93 37.93 0 1 0 33.89-54.29z\"],\n    \"hotjar\": [448, 512, [], \"f3b1\", \"M414.9 161.5C340.2 29 121.1 0 121.1 0S222.2 110.4 93 197.7C11.3 252.8-21 324.4 14 402.6c26.8 59.9 83.5 84.3 144.6 93.4-29.2-55.1-6.6-122.4-4.1-129.6 57.1 86.4 165 0 110.8-93.9 71 15.4 81.6 138.6 27.1 215.5 80.5-25.3 134.1-88.9 148.8-145.6 15.5-59.3 3.7-127.9-26.3-180.9z\"],\n    \"houzz\": [448, 512, [], \"f27c\", \"M275.9 330.7H171.3V480H17V32h109.5v104.5l305.1 85.6V480H275.9z\"],\n    \"html5\": [384, 512, [], \"f13b\", \"M0 32l34.9 395.8L191.5 480l157.6-52.2L384 32H0zm308.2 127.9H124.4l4.1 49.4h175.6l-13.6 148.4-97.9 27v.3h-1.1l-98.7-27.3-6-75.8h47.7L138 320l53.5 14.5 53.7-14.5 6-62.2H84.3L71.5 112.2h241.1l-4.4 47.7z\"],\n    \"hubspot\": [512, 512, [], \"f3b2\", \"M267.4 211.6c-25.1 23.7-40.8 57.3-40.8 94.6 0 29.3 9.7 56.3 26 78L203.1 434c-4.4-1.6-9.1-2.5-14-2.5-10.8 0-20.9 4.2-28.5 11.8-7.6 7.6-11.8 17.8-11.8 28.6s4.2 20.9 11.8 28.5c7.6 7.6 17.8 11.6 28.5 11.6 10.8 0 20.9-3.9 28.6-11.6 7.6-7.6 11.8-17.8 11.8-28.5 0-4.2-.6-8.2-1.9-12.1l50-50.2c22 16.9 49.4 26.9 79.3 26.9 71.9 0 130-58.3 130-130.2 0-65.2-47.7-119.2-110.2-128.7V116c17.5-7.4 28.2-23.8 28.2-42.9 0-26.1-20.9-47.9-47-47.9S311.2 47 311.2 73.1c0 19.1 10.7 35.5 28.2 42.9v61.2c-15.2 2.1-29.6 6.7-42.7 13.6-27.6-20.9-117.5-85.7-168.9-124.8 1.2-4.4 2-9 2-13.8C129.8 23.4 106.3 0 77.4 0 48.6 0 25.2 23.4 25.2 52.2c0 28.9 23.4 52.3 52.2 52.3 9.8 0 18.9-2.9 26.8-7.6l163.2 114.7zm89.5 163.6c-38.1 0-69-30.9-69-69s30.9-69 69-69 69 30.9 69 69-30.9 69-69 69z\"],\n    \"imdb\": [448, 512, [], \"f2d8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.3 229.2H21c.1-.1.2-.3.3-.4zM97 319.8H64V192h33zm113.2 0h-28.7v-86.4l-11.6 86.4h-20.6l-12.2-84.5v84.5h-29V192h42.8c3.3 19.8 6 39.9 8.7 59.9l7.6-59.9h43zm11.4 0V192h24.6c17.6 0 44.7-1.6 49 20.9 1.7 7.6 1.4 16.3 1.4 24.4 0 88.5 11.1 82.6-75 82.5zm160.9-29.2c0 15.7-2.4 30.9-22.2 30.9-9 0-15.2-3-20.9-9.8l-1.9 8.1h-29.8V192h31.7v41.7c6-6.5 12-9.2 20.9-9.2 21.4 0 22.2 12.8 22.2 30.1zM265 229.9c0-9.7 1.6-16-10.3-16v83.7c12.2.3 10.3-8.7 10.3-18.4zm85.5 26.1c0-5.4 1.1-12.7-6.2-12.7-6 0-4.9 8.9-4.9 12.7 0 .6-1.1 39.6 1.1 44.7.8 1.6 2.2 2.4 3.8 2.4 7.8 0 6.2-9 6.2-14.4z\"],\n    \"instagram\": [448, 512, [], \"f16d\", \"M224.1 141c-63.6 0-114.9 51.3-114.9 114.9s51.3 114.9 114.9 114.9S339 319.5 339 255.9 287.7 141 224.1 141zm0 189.6c-41.1 0-74.7-33.5-74.7-74.7s33.5-74.7 74.7-74.7 74.7 33.5 74.7 74.7-33.6 74.7-74.7 74.7zm146.4-194.3c0 14.9-12 26.8-26.8 26.8-14.9 0-26.8-12-26.8-26.8s12-26.8 26.8-26.8 26.8 12 26.8 26.8zm76.1 27.2c-1.7-35.9-9.9-67.7-36.2-93.9-26.2-26.2-58-34.4-93.9-36.2-37-2.1-147.9-2.1-184.9 0-35.8 1.7-67.6 9.9-93.9 36.1s-34.4 58-36.2 93.9c-2.1 37-2.1 147.9 0 184.9 1.7 35.9 9.9 67.7 36.2 93.9s58 34.4 93.9 36.2c37 2.1 147.9 2.1 184.9 0 35.9-1.7 67.7-9.9 93.9-36.2 26.2-26.2 34.4-58 36.2-93.9 2.1-37 2.1-147.8 0-184.8zM398.8 388c-7.8 19.6-22.9 34.7-42.6 42.6-29.5 11.7-99.5 9-132.1 9s-102.7 2.6-132.1-9c-19.6-7.8-34.7-22.9-42.6-42.6-11.7-29.5-9-99.5-9-132.1s-2.6-102.7 9-132.1c7.8-19.6 22.9-34.7 42.6-42.6 29.5-11.7 99.5-9 132.1-9s102.7-2.6 132.1 9c19.6 7.8 34.7 22.9 42.6 42.6 11.7 29.5 9 99.5 9 132.1s2.7 102.7-9 132.1z\"],\n    \"intercom\": [448, 512, [], \"f7af\", \"M392 32H56C25.1 32 0 57.1 0 88v336c0 30.9 25.1 56 56 56h336c30.9 0 56-25.1 56-56V88c0-30.9-25.1-56-56-56zm-108.3 82.1c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zm-74.6-7.5c0-19.8 29.9-19.8 29.9 0v216.5c0 19.8-29.9 19.8-29.9 0V106.6zm-74.7 7.5c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zM59.7 144c0-19.8 29.9-19.8 29.9 0v134.3c0 19.8-29.9 19.8-29.9 0V144zm323.4 227.8c-72.8 63-241.7 65.4-318.1 0-15-12.8 4.4-35.5 19.4-22.7 65.9 55.3 216.1 53.9 279.3 0 14.9-12.9 34.3 9.8 19.4 22.7zm5.2-93.5c0 19.8-29.9 19.8-29.9 0V144c0-19.8 29.9-19.8 29.9 0v134.3z\"],\n    \"internet-explorer\": [512, 512, [], \"f26b\", \"M483.049 159.706c10.855-24.575 21.424-60.438 21.424-87.871 0-72.722-79.641-98.371-209.673-38.577-107.632-7.181-211.221 73.67-237.098 186.457 30.852-34.862 78.271-82.298 121.977-101.158C125.404 166.85 79.128 228.002 43.992 291.725 23.246 329.651 0 390.94 0 436.747c0 98.575 92.854 86.5 180.251 42.006 31.423 15.43 66.559 15.573 101.695 15.573 97.124 0 184.249-54.294 216.814-146.022H377.927c-52.509 88.593-196.819 52.996-196.819-47.436H509.9c6.407-43.581-1.655-95.715-26.851-141.162zM64.559 346.877c17.711 51.15 53.703 95.871 100.266 123.304-88.741 48.94-173.267 29.096-100.266-123.304zm115.977-108.873c2-55.151 50.276-94.871 103.98-94.871 53.418 0 101.981 39.72 103.981 94.871H180.536zm184.536-187.6c21.425-10.287 48.563-22.003 72.558-22.003 31.422 0 54.274 21.717 54.274 53.722 0 20.003-7.427 49.007-14.569 67.867-26.28-42.292-65.986-81.584-112.263-99.586z\"],\n    \"invision\": [448, 512, [], \"f7b0\", \"M407.4 32H40.6C18.2 32 0 50.2 0 72.6v366.8C0 461.8 18.2 480 40.6 480h366.8c22.4 0 40.6-18.2 40.6-40.6V72.6c0-22.4-18.2-40.6-40.6-40.6zM176.1 145.6c.4 23.4-22.4 27.3-26.6 27.4-14.9 0-27.1-12-27.1-27 .1-35.2 53.1-35.5 53.7-.4zM332.8 377c-65.6 0-34.1-74-25-106.6 14.1-46.4-45.2-59-59.9.7l-25.8 103.3H177l8.1-32.5c-31.5 51.8-94.6 44.4-94.6-4.3.1-14.3.9-14 23-104.1H81.7l9.7-35.6h76.4c-33.6 133.7-32.6 126.9-32.9 138.2 0 20.9 40.9 13.5 57.4-23.2l19.8-79.4h-32.3l9.7-35.6h68.8l-8.9 40.5c40.5-75.5 127.9-47.8 101.8 38-14.2 51.1-14.6 50.7-14.9 58.8 0 15.5 17.5 22.6 31.8-16.9L386 325c-10.5 36.7-29.4 52-53.2 52z\"],\n    \"ioxhost\": [640, 512, [], \"f208\", \"M616 160h-67.3C511.2 70.7 422.9 8 320 8 183 8 72 119 72 256c0 16.4 1.6 32.5 4.7 48H24c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h67.3c37.5 89.3 125.8 152 228.7 152 137 0 248-111 248-248 0-16.4-1.6-32.5-4.7-48H616c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24zm-96 96c0 110.5-89.5 200-200 200-75.7 0-141.6-42-175.5-104H424c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24H125.8c-3.8-15.4-5.8-31.4-5.8-48 0-110.5 89.5-200 200-200 75.7 0 141.6 42 175.5 104H216c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h298.2c3.8 15.4 5.8 31.4 5.8 48zm-304-24h208c13.3 0 24 10.7 24 24 0 13.2-10.7 24-24 24H216c-13.3 0-24-10.7-24-24 0-13.2 10.7-24 24-24z\"],\n    \"itch-io\": [512, 512, [], \"f83a\", \"M71.92 34.77C50.2 47.67 7.4 96.84 7 109.73v21.34c0 27.06 25.29 50.84 48.25 50.84 27.57 0 50.54-22.85 50.54-50 0 27.12 22.18 50 49.76 50s49-22.85 49-50c0 27.12 23.59 50 51.16 50h.5c27.57 0 51.16-22.85 51.16-50 0 27.12 21.47 50 49 50s49.76-22.85 49.76-50c0 27.12 23 50 50.54 50 23 0 48.25-23.78 48.25-50.84v-21.34c-.4-12.9-43.2-62.07-64.92-75C372.56 32.4 325.76 32 256 32S91.14 33.1 71.92 34.77zm132.32 134.39c-22 38.4-77.9 38.71-99.85.25-13.17 23.14-43.17 32.07-56 27.66-3.87 40.15-13.67 237.13 17.73 269.15 80 18.67 302.08 18.12 379.76 0 31.65-32.27 21.32-232 17.75-269.15-12.92 4.44-42.88-4.6-56-27.66-22 38.52-77.85 38.1-99.85-.24-7.1 12.49-23.05 28.94-51.76 28.94a57.54 57.54 0 0 1-51.75-28.94zm-41.58 53.77c16.47 0 31.09 0 49.22 19.78a436.91 436.91 0 0 1 88.18 0C318.22 223 332.85 223 349.31 223c52.33 0 65.22 77.53 83.87 144.45 17.26 62.15-5.52 63.67-33.95 63.73-42.15-1.57-65.49-32.18-65.49-62.79-39.25 6.43-101.93 8.79-155.55 0 0 30.61-23.34 61.22-65.49 62.79-28.42-.06-51.2-1.58-33.94-63.73 18.67-67 31.56-144.45 83.88-144.45zM256 270.79s-44.38 40.77-52.35 55.21l29-1.17v25.32c0 1.55 21.34.16 23.33.16 11.65.54 23.31 1 23.31-.16v-25.28l29 1.17c-8-14.48-52.35-55.24-52.35-55.24z\"],\n    \"itunes\": [448, 512, [], \"f3b4\", \"M223.6 80.3C129 80.3 52.5 157 52.5 251.5S129 422.8 223.6 422.8s171.2-76.7 171.2-171.2c0-94.6-76.7-171.3-171.2-171.3zm79.4 240c-3.2 13.6-13.5 21.2-27.3 23.8-12.1 2.2-22.2 2.8-31.9-5-11.8-10-12-26.4-1.4-36.8 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 3.2-3.6 2.2-2 2.2-80.8 0-5.6-2.7-7.1-8.4-6.1-4 .7-91.9 17.1-91.9 17.1-5 1.1-6.7 2.6-6.7 8.3 0 116.1.5 110.8-1.2 118.5-2.1 9-7.6 15.8-14.9 19.6-8.3 4.6-23.4 6.6-31.4 5.2-21.4-4-28.9-28.7-14.4-42.9 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 5-5.7.9-127 2.6-133.7.4-2.6 1.5-4.8 3.5-6.4 2.1-1.7 5.8-2.7 6.7-2.7 101-19 113.3-21.4 115.1-21.4 5.7-.4 9 3 9 8.7-.1 170.6.4 161.4-1 167.6zM345.2 32H102.8C45.9 32 0 77.9 0 134.8v242.4C0 434.1 45.9 480 102.8 480h242.4c57 0 102.8-45.9 102.8-102.8V134.8C448 77.9 402.1 32 345.2 32zM223.6 444c-106.3 0-192.5-86.2-192.5-192.5S117.3 59 223.6 59s192.5 86.2 192.5 192.5S329.9 444 223.6 444z\"],\n    \"itunes-note\": [384, 512, [], \"f3b5\", \"M381.9 388.2c-6.4 27.4-27.2 42.8-55.1 48-24.5 4.5-44.9 5.6-64.5-10.2-23.9-20.1-24.2-53.4-2.7-74.4 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 6.4-7.2 4.4-4.1 4.4-163.2 0-11.2-5.5-14.3-17-12.3-8.2 1.4-185.7 34.6-185.7 34.6-10.2 2.2-13.4 5.2-13.4 16.7 0 234.7 1.1 223.9-2.5 239.5-4.2 18.2-15.4 31.9-30.2 39.5-16.8 9.3-47.2 13.4-63.4 10.4-43.2-8.1-58.4-58-29.1-86.6 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 10.1-11.5 1.8-256.6 5.2-270.2.8-5.2 3-9.6 7.1-12.9 4.2-3.5 11.8-5.5 13.4-5.5 204-38.2 228.9-43.1 232.4-43.1 11.5-.8 18.1 6 18.1 17.6.2 344.5 1.1 326-1.8 338.5z\"],\n    \"java\": [384, 512, [], \"f4e4\", \"M277.74 312.9c9.8-6.7 23.4-12.5 23.4-12.5s-38.7 7-77.2 10.2c-47.1 3.9-97.7 4.7-123.1 1.3-60.1-8 33-30.1 33-30.1s-36.1-2.4-80.6 19c-52.5 25.4 130 37 224.5 12.1zm-85.4-32.1c-19-42.7-83.1-80.2 0-145.8C296 53.2 242.84 0 242.84 0c21.5 84.5-75.6 110.1-110.7 162.6-23.9 35.9 11.7 74.4 60.2 118.2zm114.6-176.2c.1 0-175.2 43.8-91.5 140.2 24.7 28.4-6.5 54-6.5 54s62.7-32.4 33.9-72.9c-26.9-37.8-47.5-56.6 64.1-121.3zm-6.1 270.5a12.19 12.19 0 0 1-2 2.6c128.3-33.7 81.1-118.9 19.8-97.3a17.33 17.33 0 0 0-8.2 6.3 70.45 70.45 0 0 1 11-3c31-6.5 75.5 41.5-20.6 91.4zM348 437.4s14.5 11.9-15.9 21.2c-57.9 17.5-240.8 22.8-291.6.7-18.3-7.9 16-19 26.8-21.3 11.2-2.4 17.7-2 17.7-2-20.3-14.3-131.3 28.1-56.4 40.2C232.84 509.4 401 461.3 348 437.4zM124.44 396c-78.7 22 47.9 67.4 148.1 24.5a185.89 185.89 0 0 1-28.2-13.8c-44.7 8.5-65.4 9.1-106 4.5-33.5-3.8-13.9-15.2-13.9-15.2zm179.8 97.2c-78.7 14.8-175.8 13.1-233.3 3.6 0-.1 11.8 9.7 72.4 13.6 92.2 5.9 233.8-3.3 237.1-46.9 0 0-6.4 16.5-76.2 29.7zM260.64 353c-59.2 11.4-93.5 11.1-136.8 6.6-33.5-3.5-11.6-19.7-11.6-19.7-86.8 28.8 48.2 61.4 169.5 25.9a60.37 60.37 0 0 1-21.1-12.8z\"],\n    \"jedi-order\": [448, 512, [], \"f50e\", \"M398.5 373.6c95.9-122.1 17.2-233.1 17.2-233.1 45.4 85.8-41.4 170.5-41.4 170.5 105-171.5-60.5-271.5-60.5-271.5 96.9 72.7-10.1 190.7-10.1 190.7 85.8 158.4-68.6 230.1-68.6 230.1s-.4-16.9-2.2-85.7c4.3 4.5 34.5 36.2 34.5 36.2l-24.2-47.4 62.6-9.1-62.6-9.1 20.2-55.5-31.4 45.9c-2.2-87.7-7.8-305.1-7.9-306.9v-2.4 1-1 2.4c0 1-5.6 219-7.9 306.9l-31.4-45.9 20.2 55.5-62.6 9.1 62.6 9.1-24.2 47.4 34.5-36.2c-1.8 68.8-2.2 85.7-2.2 85.7s-154.4-71.7-68.6-230.1c0 0-107-118.1-10.1-190.7 0 0-165.5 99.9-60.5 271.5 0 0-86.8-84.8-41.4-170.5 0 0-78.7 111 17.2 233.1 0 0-26.2-16.1-49.4-77.7 0 0 16.9 183.3 222 185.7h4.1c205-2.4 222-185.7 222-185.7-23.6 61.5-49.9 77.7-49.9 77.7z\"],\n    \"jenkins\": [512, 512, [], \"f3b6\", \"M487.1 425c-1.4-11.2-19-23.1-28.2-31.9-5.1-5-29-23.1-30.4-29.9-1.4-6.6 9.7-21.5 13.3-28.9 5.1-10.7 8.8-23.7 11.3-32.6 18.8-66.1 20.7-156.9-6.2-211.2-10.2-20.6-38.6-49-56.4-62.5-42-31.7-119.6-35.3-170.1-16.6-14.1 5.2-27.8 9.8-40.1 17.1-33.1 19.4-68.3 32.5-78.1 71.6-24.2 10.8-31.5 41.8-30.3 77.8.2 7 4.1 15.8 2.7 22.4-.7 3.3-5.2 7.6-6.1 9.8-11.6 27.7-2.3 64 11.1 83.7 8.1 11.9 21.5 22.4 39.2 25.2.7 10.6 3.3 19.7 8.2 30.4 3.1 6.8 14.7 19 10.4 27.7-2.2 4.4-21 13.8-27.3 17.6C89 407.2 73.7 415 54.2 429c-12.6 9-32.3 10.2-29.2 31.1 2.1 14.1 10.1 31.6 14.7 45.8.7 2 1.4 4.1 2.1 6h422c4.9-15.3 9.7-30.9 14.6-47.2 3.4-11.4 10.2-27.8 8.7-39.7zM205.9 33.7c1.8-.5 3.4.7 4.9 2.4-.2 5.2-5.4 5.1-8.9 6.8-5.4 6.7-13.4 9.8-20 17.2-6.8 7.5-14.4 27.7-23.4 30-4.5 1.1-9.7-.8-13.6-.5-10.4.7-17.7 6-28.3 7.5 13.6-29.9 56.1-54 89.3-63.4zm-104.8 93.6c13.5-14.9 32.1-24.1 54.8-25.9 11.7 29.7-8.4 65-.9 97.6 2.3 9.9 10.2 25.4-2.4 25.7.3-28.3-34.8-46.3-61.3-29.6-1.8-21.5-4.9-51.7 9.8-67.8zm36.7 200.2c-1-4.1-2.7-12.9-2.3-15.1 1.6-8.7 17.1-12.5 11-24.7-11.3-.1-13.8 10.2-24.1 11.3-26.7 2.6-45.6-35.4-44.4-58.4 1-19.5 17.6-38.2 40.1-35.8 16 1.8 21.4 19.2 24.5 34.7 9.2.5 22.5-.4 26.9-7.6-.6-17.5-8.8-31.6-8.2-47.7 1-30.3 17.5-57.6 4.8-87.4 13.6-30.9 53.5-55.3 83.1-70 36.6-18.3 94.9-3.7 129.3 15.8 19.7 11.1 34.4 32.7 48.3 50.7-19.5-5.8-36.1 4.2-33.1 20.3 16.3-14.9 44.2-.2 52.5 16.4 7.9 15.8 7.8 39.3 9 62.8 2.9 57-10.4 115.9-39.1 157.1-7.7 11-14.1 23-24.9 30.6-26 18.2-65.4 34.7-99.2 23.4-44.7-15-65-44.8-89.5-78.8.7 18.7 13.8 34.1 26.8 48.4 11.3 12.5 25 26.6 39.7 32.4-12.3-2.9-31.1-3.8-36.2 7.2-28.6-1.9-55.1-4.8-68.7-24.2-10.6-15.4-21.4-41.4-26.3-61.4zm222 124.1c4.1-3 11.1-2.9 17.4-3.6-5.4-2.7-13-3.7-19.3-2.2-.1-4.2-2-6.8-3.2-10.2 10.6-3.8 35.5-28.5 49.6-20.3 6.7 3.9 9.5 26.2 10.1 37 .4 9-.8 18-4.5 22.8-18.8-.6-35.8-2.8-50.7-7 .9-6.1-1-12.1.6-16.5zm-17.2-20c-16.8.8-26-1.2-38.3-10.8.2-.8 1.4-.5 1.5-1.4 18 8 40.8-3.3 59-4.9-7.9 5.1-14.6 11.6-22.2 17.1zm-12.1 33.2c-1.6-9.4-3.5-12-2.8-20.2 25-16.6 29.7 28.6 2.8 20.2zM226 438.6c-11.6-.7-48.1-14-38.5-23.7 9.4 6.5 27.5 4.9 41.3 7.3.8 4.4-2.8 10.2-2.8 16.4zM57.7 497.1c-4.3-12.7-9.2-25.1-14.8-36.9 30.8-23.8 65.3-48.9 102.2-63.5 2.8-1.1 23.2 25.4 26.2 27.6 16.5 11.7 37 21 56.2 30.2 1.2 8.8 3.9 20.2 8.7 35.5.7 2.3 1.4 4.7 2.2 7.2H57.7zm240.6 5.7h-.8c.3-.2.5-.4.8-.5v.5zm7.5-5.7c2.1-1.4 4.3-2.8 6.4-4.3 1.1 1.4 2.2 2.8 3.2 4.3h-9.6zm15.1-24.7c-10.8 7.3-20.6 18.3-33.3 25.2-6 3.3-27 11.7-33.4 10.2-3.6-.8-3.9-5.3-5.4-9.5-3.1-9-10.1-23.4-10.8-37-.8-17.2-2.5-46 16-42.4 14.9 2.9 32.3 9.7 43.9 16.1 7.1 3.9 11.1 8.6 21.9 9.5-.1 1.4-.1 2.8-.2 4.3-5.9 3.9-15.3 3.8-21.8 7.1 9.5.4 17 2.7 23.5 5.9-.1 3.4-.3 7-.4 10.6zm53.4 24.7h-14c-.1-3.2-2.8-5.8-6.1-5.8s-5.9 2.6-6.1 5.8h-17.4c-2.8-4.4-5.7-8.6-8.9-12.5 2.1-2.2 4-4.7 6-6.9 9 3.7 14.8-4.9 21.7-4.2 7.9.8 14.2 11.7 25.4 11l-.6 12.6zm8.7 0c.2-4 .4-7.8.6-11.5 15.6-7.3 29 1.3 35.7 11.5H383zm83.4-37c-2.3 11.2-5.8 24-9.9 37.1-.2-.1-.4-.1-.6-.1H428c.6-1.1 1.2-2.2 1.9-3.3-2.6-6.1-9-8.7-10.9-15.5 12.1-22.7 6.5-93.4-24.2-78.5 4.3-6.3 15.6-11.5 20.8-19.3 13 10.4 20.8 20.3 33.2 31.4 6.8 6 20 13.3 21.4 23.1.8 5.5-2.6 18.9-3.8 25.1zM222.2 130.5c5.4-14.9 27.2-34.7 45-32 7.7 1.2 18 8.2 12.2 17.7-30.2-7-45.2 12.6-54.4 33.1-8.1-2-4.9-13.1-2.8-18.8zm184.1 63.1c8.2-3.6 22.4-.7 29.6-5.3-4.2-11.5-10.3-21.4-9.3-37.7.5 0 1 0 1.4.1 6.8 14.2 12.7 29.2 21.4 41.7-5.7 13.5-43.6 25.4-43.1 1.2zm20.4-43zm-117.2 45.7c-6.8-10.9-19-32.5-14.5-45.3 6.5 11.9 8.6 24.4 17.8 33.3 4.1 4 12.2 9 8.2 20.2-.9 2.7-7.8 8.6-11.7 9.7-14.4 4.3-47.9.9-36.6-17.1 11.9.7 27.9 7.8 36.8-.8zm27.3 70c3.8 6.6 1.4 18.7 12.1 20.6 20.2 3.4 43.6-12.3 58.1-17.8 9-15.2-.8-20.7-8.9-30.5-16.6-20-38.8-44.8-38-74.7 6.7-4.9 7.3 7.4 8.2 9.7 8.7 20.3 30.4 46.2 46.3 63.5 3.9 4.3 10.3 8.4 11 11.2 2.1 8.2-5.4 18-4.5 23.5-21.7 13.9-45.8 29.1-81.4 25.6-7.4-6.7-10.3-21.4-2.9-31.1zm-201.3-9.2c-6.8-3.9-8.4-21-16.4-21.4-11.4-.7-9.3 22.2-9.3 35.5-7.8-7.1-9.2-29.1-3.5-40.3-6.6-3.2-9.5 3.6-13.1 5.9 4.7-34.1 49.8-15.8 42.3 20.3zm299.6 28.8c-10.1 19.2-24.4 40.4-54 41-.6-6.2-1.1-15.6 0-19.4 22.7-2.2 36.6-13.7 54-21.6zm-141.9 12.4c18.9 9.9 53.6 11 79.3 10.2 1.4 5.6 1.3 12.6 1.4 19.4-33 1.8-72-6.4-80.7-29.6zm92.2 46.7c-1.7 4.3-5.3 9.3-9.8 11.1-12.1 4.9-45.6 8.7-62.4-.3-10.7-5.7-17.5-18.5-23.4-26-2.8-3.6-16.9-12.9-.2-12.9 13.1 32.7 58 29 95.8 28.1z\"],\n    \"jira\": [496, 512, [], \"f7b1\", \"M490 241.7C417.1 169 320.6 71.8 248.5 0 83 164.9 6 241.7 6 241.7c-7.9 7.9-7.9 20.7 0 28.7C138.8 402.7 67.8 331.9 248.5 512c379.4-378 15.7-16.7 241.5-241.7 8-7.9 8-20.7 0-28.6zm-241.5 90l-76-75.7 76-75.7 76 75.7-76 75.7z\"],\n    \"joget\": [496, 512, [], \"f3b7\", \"M378.1 45C337.6 19.9 292.6 8 248.2 8 165 8 83.8 49.9 36.9 125.9c-71.9 116.6-35.6 269.3 81 341.2s269.3 35.6 341.2-80.9c71.9-116.6 35.6-269.4-81-341.2zm51.8 323.2c-40.4 65.5-110.4 101.5-182 101.5-6.8 0-13.6-.4-20.4-1-9-13.6-19.9-33.3-23.7-42.4-5.7-13.7-27.2-45.6 31.2-67.1 51.7-19.1 176.7-16.5 208.8-17.6-4 9-8.6 17.9-13.9 26.6zm-200.8-86.3c-55.5-1.4-81.7-20.8-58.5-48.2s51.1-40.7 68.9-51.2c17.9-10.5 27.3-33.7-23.6-29.7C87.3 161.5 48.6 252.1 37.6 293c-8.8-49.7-.1-102.7 28.5-149.1C128 43.4 259.6 12.2 360.1 74.1c74.8 46.1 111.2 130.9 99.3 212.7-24.9-.5-179.3-3.6-230.3-4.9zm183.8-54.8c-22.7-6-57 11.3-86.7 27.2-29.7 15.8-31.1 8.2-31.1 8.2s40.2-28.1 50.7-34.5 31.9-14 13.4-24.6c-3.2-1.8-6.7-2.7-10.4-2.7-17.8 0-41.5 18.7-67.5 35.6-31.5 20.5-65.3 31.3-65.3 31.3l169.5-1.6 46.5-23.4s3.6-9.5-19.1-15.5z\"],\n    \"joomla\": [448, 512, [], \"f1aa\", \"M.6 92.1C.6 58.8 27.4 32 60.4 32c30 0 54.5 21.9 59.2 50.2 32.6-7.6 67.1.6 96.5 30l-44.3 44.3c-20.5-20.5-42.6-16.3-55.4-3.5-14.3 14.3-14.3 37.9 0 52.2l99.5 99.5-44 44.3c-87.7-87.2-49.7-49.7-99.8-99.7-26.8-26.5-35-64.8-24.8-98.9C20.4 144.6.6 120.7.6 92.1zm129.5 116.4l44.3 44.3c10-10 89.7-89.7 99.7-99.8 14.3-14.3 37.6-14.3 51.9 0 12.8 12.8 17 35-3.5 55.4l44 44.3c31.2-31.2 38.5-67.6 28.9-101.2 29.2-4.1 51.9-29.2 51.9-59.5 0-33.2-26.8-60.1-59.8-60.1-30.3 0-55.4 22.5-59.5 51.6-33.8-9.9-71.7-1.5-98.3 25.1-18.3 19.1-71.1 71.5-99.6 99.9zm266.3 152.2c8.2-32.7-.9-68.5-26.3-93.9-11.8-12.2 5 4.7-99.5-99.7l-44.3 44.3 99.7 99.7c14.3 14.3 14.3 37.6 0 51.9-12.8 12.8-35 17-55.4-3.5l-44 44.3c27.6 30.2 68 38.8 102.7 28 5.5 27.4 29.7 48.1 58.9 48.1 33 0 59.8-26.8 59.8-60.1 0-30.2-22.5-55-51.6-59.1zm-84.3-53.1l-44-44.3c-87 86.4-50.4 50.4-99.7 99.8-14.3 14.3-37.6 14.3-51.9 0-13.1-13.4-16.9-35.3 3.2-55.4l-44-44.3c-30.2 30.2-38 65.2-29.5 98.3-26.7 6-46.2 29.9-46.2 58.2C0 453.2 26.8 480 59.8 480c28.6 0 52.5-19.8 58.6-46.7 32.7 8.2 68.5-.6 94.2-26 32.1-32 12.2-12.4 99.5-99.7z\"],\n    \"js\": [448, 512, [], \"f3b8\", \"M0 32v448h448V32H0zm243.8 349.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"js-square\": [448, 512, [], \"f3b9\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM243.8 381.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"jsfiddle\": [576, 512, [], \"f1cc\", \"M510.634 237.462c-4.727-2.621-5.664-5.748-6.381-10.776-2.352-16.488-3.539-33.619-9.097-49.095-35.895-99.957-153.99-143.386-246.849-91.646-27.37 15.25-48.971 36.369-65.493 63.903-3.184-1.508-5.458-2.71-7.824-3.686-30.102-12.421-59.049-10.121-85.331 9.167-25.531 18.737-36.422 44.548-32.676 76.408.355 3.025-1.967 7.621-4.514 9.545-39.712 29.992-56.031 78.065-41.902 124.615 13.831 45.569 57.514 79.796 105.608 81.433 30.291 1.031 60.637.546 90.959.539 84.041-.021 168.09.531 252.12-.48 52.664-.634 96.108-36.873 108.212-87.293 11.54-48.074-11.144-97.3-56.832-122.634zm21.107 156.88c-18.23 22.432-42.343 35.253-71.28 35.65-56.874.781-113.767.23-170.652.23 0 .7-163.028.159-163.728.154-43.861-.332-76.739-19.766-95.175-59.995-18.902-41.245-4.004-90.848 34.186-116.106 9.182-6.073 12.505-11.566 10.096-23.136-5.49-26.361 4.453-47.956 26.42-62.981 22.987-15.723 47.422-16.146 72.034-3.083 10.269 5.45 14.607 11.564 22.198-2.527 14.222-26.399 34.557-46.727 60.671-61.294 97.46-54.366 228.37 7.568 230.24 132.697.122 8.15 2.412 12.428 9.848 15.894 57.56 26.829 74.456 96.122 35.142 144.497zm-87.789-80.499c-5.848 31.157-34.622 55.096-66.666 55.095-16.953-.001-32.058-6.545-44.079-17.705-27.697-25.713-71.141-74.98-95.937-93.387-20.056-14.888-41.99-12.333-60.272 3.782-49.996 44.071 15.859 121.775 67.063 77.188 4.548-3.96 7.84-9.543 12.744-12.844 8.184-5.509 20.766-.884 13.168 10.622-17.358 26.284-49.33 38.197-78.863 29.301-28.897-8.704-48.84-35.968-48.626-70.179 1.225-22.485 12.364-43.06 35.414-55.965 22.575-12.638 46.369-13.146 66.991 2.474C295.68 280.7 320.467 323.97 352.185 343.47c24.558 15.099 54.254 7.363 68.823-17.506 28.83-49.209-34.592-105.016-78.868-63.46-3.989 3.744-6.917 8.932-11.41 11.72-10.975 6.811-17.333-4.113-12.809-10.353 20.703-28.554 50.464-40.44 83.271-28.214 31.429 11.714 49.108 44.366 42.76 78.186z\"],\n    \"kaggle\": [320, 512, [], \"f5fa\", \"M304.2 501.5L158.4 320.3 298.2 185c2.6-2.7 1.7-10.5-5.3-10.5h-69.2c-3.5 0-7 1.8-10.5 5.3L80.9 313.5V7.5q0-7.5-7.5-7.5H21.5Q14 0 14 7.5v497q0 7.5 7.5 7.5h51.9q7.5 0 7.5-7.5v-109l30.8-29.3 110.5 140.6c3 3.5 6.5 5.3 10.5 5.3h66.9q5.25 0 6-3z\"],\n    \"keybase\": [448, 512, [], \"f4f5\", \"M286.17,419a18,18,0,1,0,18,18A18,18,0,0,0,286.17,419ZM398.09,271.4c-9.5-14.62-39.37-52.45-87.26-73.71q-9.1-4.06-18.38-7.27A78.43,78.43,0,0,0,244.57,86.29c-12.41-4.1-23.33-6-32.41-5.77-.6-2-1.89-11,9.4-35L198.66,32l-5.48,7.56c-8.69,12.06-16.92,23.55-24.34,34.89a51,51,0,0,0-8.29-1.25c-41.53-2.45-39-2.33-41.06-2.33-50.61,0-50.75,52.12-50.75,45.88l-2.36,36.68c-1.61,27,19.75,50.21,47.63,51.85l8.93.54a214,214,0,0,0-46.29,35.54C14,304.66,14,374,14,429.77v33.64l23.32-29.8a148.6,148.6,0,0,0,14.56,37.56c5.78,10.13,14.87,9.45,19.64,7.33,4.21-1.87,10-6.92,3.75-20.11a178.29,178.29,0,0,1-15.76-53.13l46.82-59.83L81.67,419.54c58.23-42.4,157.38-61.76,236.25-38.59,34.2,10.05,67.45.69,84.74-23.84.72-1,1.2-2.16,1.85-3.22a156.09,156.09,0,0,1,2.8,28.43c0,23.3-3.69,52.93-14.88,81.64-2.52,6.46,1.76,14.5,8.6,15.74,7.42,1.57,15.33-3.1,18.37-11.15C429,443,434,414,434,382.32,434,343.74,421,304.86,398.09,271.4ZM142.37,128.58l-15.7-.93-1.39,21.79,13.13.78a93,93,0,0,0,.32,19.57l-22.38-1.34a12.28,12.28,0,0,1-11.76-12.79L107,119c1-12.17,13.87-11.27,13.26-11.32l29.11,1.73A144.35,144.35,0,0,0,142.37,128.58ZM290.79,300.76a10.51,10.51,0,0,1-14.35-1.39l-9.68-11.49-34.42,27a8.09,8.09,0,0,1-11.13-1.08l-15.78-18.64a7.38,7.38,0,0,1,1.34-10.34l34.57-27.18L227.2,240.9l-17.09,13.45a7.75,7.75,0,0,1-10.59-1s-3.72-4.42-3.8-4.53a7.38,7.38,0,0,1,1.37-10.34L214,225.19s-18.51-22-18.6-22.14a9.56,9.56,0,0,1,1.74-13.42A10.38,10.38,0,0,1,211.44,191l81.09,96.32A9.58,9.58,0,0,1,290.79,300.76ZM187.44,419a18,18,0,1,0,18,18A18,18,0,0,0,187.44,419Z\"],\n    \"keycdn\": [512, 512, [], \"f3ba\", \"M63.8 409.3l60.5-59c32.1 42.8 71.1 66 126.6 67.4 30.5.7 60.3-7 86.4-22.4 5.1 5.3 18.5 19.5 20.9 22-32.2 20.7-69.6 31.1-108.1 30.2-43.3-1.1-84.6-16.7-117.7-44.4.3-.6-38.2 37.5-38.6 37.9 9.5 29.8-13.1 62.4-46.3 62.4C20.7 503.3 0 481.7 0 454.9c0-34.3 33.1-56.6 63.8-45.6zm354.9-252.4c19.1 31.3 29.6 67.4 28.7 104-1.1 44.8-19 87.5-48.6 121 .3.3 23.8 25.2 24.1 25.5 9.6-1.3 19.2 2 25.9 9.1 11.3 12 10.9 30.9-1.1 42.4-12 11.3-30.9 10.9-42.4-1.1-6.7-7-9.4-16.8-7.6-26.3-24.9-26.6-44.4-47.2-44.4-47.2 42.7-34.1 63.3-79.6 64.4-124.2.7-28.9-7.2-57.2-21.1-82.2l22.1-21zM104 53.1c6.7 7 9.4 16.8 7.6 26.3l45.9 48.1c-4.7 3.8-13.3 10.4-22.8 21.3-25.4 28.5-39.6 64.8-40.7 102.9-.7 28.9 6.1 57.2 20 82.4l-22 21.5C72.7 324 63.1 287.9 64.2 250.9c1-44.6 18.3-87.6 47.5-121.1l-25.3-26.4c-9.6 1.3-19.2-2-25.9-9.1-11.3-12-10.9-30.9 1.1-42.4C73.5 40.7 92.2 41 104 53.1zM464.9 8c26 0 47.1 22.4 47.1 48.3S490.9 104 464.9 104c-6.3.1-14-1.1-15.9-1.8l-62.9 59.7c-32.7-43.6-76.7-65.9-126.9-67.2-30.5-.7-60.3 6.8-86.2 22.4l-21.1-22C184.1 74.3 221.5 64 260 64.9c43.3 1.1 84.6 16.7 117.7 44.6l41.1-38.6c-1.5-4.7-2.2-9.6-2.2-14.5C416.5 29.7 438.9 8 464.9 8zM256.7 113.4c5.5 0 10.9.4 16.4 1.1 78.1 9.8 133.4 81.1 123.8 159.1-9.8 78.1-81.1 133.4-159.1 123.8-78.1-9.8-133.4-81.1-123.8-159.2 9.3-72.4 70.1-124.6 142.7-124.8zm-59 119.4c.6 22.7 12.2 41.8 32.4 52.2l-11 51.7h73.7l-11-51.7c20.1-10.9 32.1-29 32.4-52.2-.4-32.8-25.8-57.5-58.3-58.3-32.1.8-57.3 24.8-58.2 58.3zM256 160\"],\n    \"kickstarter\": [448, 512, [], \"f3bb\", \"M400 480H48c-26.4 0-48-21.6-48-48V80c0-26.4 21.6-48 48-48h352c26.4 0 48 21.6 48 48v352c0 26.4-21.6 48-48 48zM199.6 178.5c0-30.7-17.6-45.1-39.7-45.1-25.8 0-40 19.8-40 44.5v154.8c0 25.8 13.7 45.6 40.5 45.6 21.5 0 39.2-14 39.2-45.6v-41.8l60.6 75.7c12.3 14.9 39 16.8 55.8 0 14.6-15.1 14.8-36.8 4-50.4l-49.1-62.8 40.5-58.7c9.4-13.5 9.5-34.5-5.6-49.1-16.4-15.9-44.6-17.3-61.4 7l-44.8 64.7v-38.8z\"],\n    \"kickstarter-k\": [384, 512, [], \"f3bc\", \"M147.3 114.4c0-56.2-32.5-82.4-73.4-82.4C26.2 32 0 68.2 0 113.4v283c0 47.3 25.3 83.4 74.9 83.4 39.8 0 72.4-25.6 72.4-83.4v-76.5l112.1 138.3c22.7 27.2 72.1 30.7 103.2 0 27-27.6 27.3-67.4 7.4-92.2l-90.8-114.8 74.9-107.4c17.4-24.7 17.5-63.1-10.4-89.8-30.3-29-82.4-31.6-113.6 12.8L147.3 185v-70.6z\"],\n    \"korvue\": [446, 512, [], \"f42f\", \"M386.5 34h-327C26.8 34 0 60.8 0 93.5v327.1C0 453.2 26.8 480 59.5 480h327.1c33 0 59.5-26.8 59.5-59.5v-327C446 60.8 419.2 34 386.5 34zM87.1 120.8h96v116l61.8-116h110.9l-81.2 132H87.1v-132zm161.8 272.1l-65.7-113.6v113.6h-96V262.1h191.5l88.6 130.8H248.9z\"],\n    \"laravel\": [640, 512, [], \"f3bd\", \"M637.5 241.6c-4.2-4.8-62.8-78.1-73.1-90.5-10.3-12.4-15.4-10.2-21.7-9.3-6.4.9-80.5 13.4-89.1 14.8-8.6 1.5-14 4.9-8.7 12.3 4.7 6.6 53.4 75.7 64.2 90.9l-193.7 46.4L161.2 48.7c-6.1-9.1-7.4-12.3-21.4-11.6-14 .6-120.9 9.5-128.5 10.2-7.6.6-16 4-8.4 22s129 279.6 132.4 287.2c3.4 7.6 12.2 20 32.8 15 21.1-5.1 94.3-24.2 134.3-34.7 21.1 38.3 64.2 115.9 72.2 127 10.6 14.9 18 12.4 34.3 7.4 12.8-3.9 199.6-71.1 208-74.5 8.4-3.5 13.6-5.9 7.9-14.4-4.2-6.2-53.5-72.2-79.3-106.8 17.7-4.7 80.6-21.4 87.3-23.3 7.9-2 9-5.8 4.7-10.6zm-352.2 72c-2.3.5-110.8 26.5-116.6 27.8-5.8 1.3-5.8.7-6.5-1.3-.7-2-129-266.7-130.8-270-1.8-3.3-1.7-5.9 0-5.9s102.5-9 106-9.2c3.6-.2 3.2.6 4.5 2.8 0 0 142.2 245.4 144.6 249.7 2.6 4.3 1.1 5.6-1.2 6.1zm306 57.4c1.7 2.7 3.5 4.5-2 6.4-5.4 2-183.7 62.1-187.1 63.6-3.5 1.5-6.2 2-10.6-4.5s-62.4-106.8-62.4-106.8L518 280.6c4.7-1.5 6.2-2.5 9.2 2.2 2.9 4.8 62.4 85.5 64.1 88.2zm12.1-134.1c-4.2.9-73.6 18.1-73.6 18.1l-56.7-77.8c-1.6-2.3-2.9-4.5 1.1-5s68.4-12.2 71.3-12.8c2.9-.7 5.4-1.5 9 3.4 3.6 4.9 52.6 67 54.5 69.4 1.8 2.3-1.4 3.7-5.6 4.7z\"],\n    \"lastfm\": [512, 512, [], \"f202\", \"M225.8 367.1l-18.8-51s-30.5 34-76.2 34c-40.5 0-69.2-35.2-69.2-91.5 0-72.1 36.4-97.9 72.1-97.9 66.5 0 74.8 53.3 100.9 134.9 18.8 56.9 54 102.6 155.4 102.6 72.7 0 122-22.3 122-80.9 0-72.9-62.7-80.6-115-92.1-25.8-5.9-33.4-16.4-33.4-34 0-19.9 15.8-31.7 41.6-31.7 28.2 0 43.4 10.6 45.7 35.8l58.6-7c-4.7-52.8-41.1-74.5-100.9-74.5-52.8 0-104.4 19.9-104.4 83.9 0 39.9 19.4 65.1 68 76.8 44.9 10.6 79.8 13.8 79.8 45.7 0 21.7-21.1 30.5-61 30.5-59.2 0-83.9-31.1-97.9-73.9-32-96.8-43.6-163-161.3-163C45.7 113.8 0 168.3 0 261c0 89.1 45.7 137.2 127.9 137.2 66.2 0 97.9-31.1 97.9-31.1z\"],\n    \"lastfm-square\": [448, 512, [], \"f203\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-92.2 312.9c-63.4 0-85.4-28.6-97.1-64.1-16.3-51-21.5-84.3-63-84.3-22.4 0-45.1 16.1-45.1 61.2 0 35.2 18 57.2 43.3 57.2 28.6 0 47.6-21.3 47.6-21.3l11.7 31.9s-19.8 19.4-61.2 19.4c-51.3 0-79.9-30.1-79.9-85.8 0-57.9 28.6-92 82.5-92 73.5 0 80.8 41.4 100.8 101.9 8.8 26.8 24.2 46.2 61.2 46.2 24.9 0 38.1-5.5 38.1-19.1 0-19.9-21.8-22-49.9-28.6-30.4-7.3-42.5-23.1-42.5-48 0-40 32.3-52.4 65.2-52.4 37.4 0 60.1 13.6 63 46.6l-36.7 4.4c-1.5-15.8-11-22.4-28.6-22.4-16.1 0-26 7.3-26 19.8 0 11 4.8 17.6 20.9 21.3 32.7 7.1 71.8 12 71.8 57.5.1 36.7-30.7 50.6-76.1 50.6z\"],\n    \"leanpub\": [576, 512, [], \"f212\", \"M386.539 111.485l15.096 248.955-10.979-.275c-36.232-.824-71.64 8.783-102.657 27.997-31.016-19.214-66.424-27.997-102.657-27.997-45.564 0-82.07 10.705-123.516 27.723L93.117 129.6c28.546-11.803 61.484-18.115 92.226-18.115 41.173 0 73.836 13.175 102.657 42.544 27.723-28.271 59.013-41.721 98.539-42.544zM569.07 448c-25.526 0-47.485-5.215-70.542-15.645-34.31-15.645-69.993-24.978-107.871-24.978-38.977 0-74.934 12.901-102.657 40.623-27.723-27.723-63.68-40.623-102.657-40.623-37.878 0-73.561 9.333-107.871 24.978C55.239 442.236 32.731 448 8.303 448H6.93L49.475 98.859C88.726 76.626 136.486 64 181.775 64 218.83 64 256.984 71.685 288 93.095 319.016 71.685 357.17 64 394.225 64c45.289 0 93.049 12.626 132.3 34.859L569.07 448zm-43.368-44.741l-34.036-280.246c-30.742-13.999-67.248-21.41-101.009-21.41-38.428 0-74.385 12.077-102.657 38.702-28.272-26.625-64.228-38.702-102.657-38.702-33.761 0-70.267 7.411-101.009 21.41L50.298 403.259c47.211-19.487 82.894-33.486 135.045-33.486 37.604 0 70.817 9.606 102.657 29.644 31.84-20.038 65.052-29.644 102.657-29.644 52.151 0 87.834 13.999 135.045 33.486z\"],\n    \"less\": [640, 512, [], \"f41d\", \"M612.7 219c0-20.5 3.2-32.6 3.2-54.6 0-34.2-12.6-45.2-40.5-45.2h-20.5v24.2h6.3c14.2 0 17.3 4.7 17.3 22.1 0 16.3-1.6 32.6-1.6 51.5 0 24.2 7.9 33.6 23.6 37.3v1.6c-15.8 3.7-23.6 13.1-23.6 37.3 0 18.9 1.6 34.2 1.6 51.5 0 17.9-3.7 22.6-17.3 22.6v.5h-6.3V393h20.5c27.8 0 40.5-11 40.5-45.2 0-22.6-3.2-34.2-3.2-54.6 0-11 6.8-22.6 27.3-23.6v-27.3c-20.5-.7-27.3-12.3-27.3-23.3zm-105.6 32c-15.8-6.3-30.5-10-30.5-20.5 0-7.9 6.3-12.6 17.9-12.6s22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-21 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51s-22.5-41-43-47.8zm-358.9 59.4c-3.7 0-8.4-3.2-8.4-13.1V119.1H65.2c-28.4 0-41 11-41 45.2 0 22.6 3.2 35.2 3.2 54.6 0 11-6.8 22.6-27.3 23.6v27.3c20.5.5 27.3 12.1 27.3 23.1 0 19.4-3.2 31-3.2 53.6 0 34.2 12.6 45.2 40.5 45.2h20.5v-24.2h-6.3c-13.1 0-17.3-5.3-17.3-22.6s1.6-32.1 1.6-51.5c0-24.2-7.9-33.6-23.6-37.3v-1.6c15.8-3.7 23.6-13.1 23.6-37.3 0-18.9-1.6-34.2-1.6-51.5s3.7-22.1 17.3-22.1H93v150.8c0 32.1 11 53.1 43.1 53.1 10 0 17.9-1.6 23.6-3.7l-5.3-34.2c-3.1.8-4.6.8-6.2.8zM379.9 251c-16.3-6.3-31-10-31-20.5 0-7.9 6.3-12.6 17.9-12.6 11.6 0 22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-20.5 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51 .1-28.9-22.5-41-43-47.8zm-155-68.8c-38.4 0-75.1 32.1-74.1 82.5 0 52 34.2 82.5 79.3 82.5 18.9 0 39.9-6.8 56.2-17.9l-15.8-27.8c-11.6 6.8-22.6 10-34.2 10-21 0-37.3-10-41.5-34.2H290c.5-3.7 1.6-11 1.6-19.4.6-42.6-22.6-75.7-66.7-75.7zm-30 66.2c3.2-21 15.8-31 30.5-31 18.9 0 26.3 13.1 26.3 31h-56.8z\"],\n    \"line\": [448, 512, [], \"f3c0\", \"M272.1 204.2v71.1c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.1 0-2.1-.6-2.6-1.3l-32.6-44v42.2c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.8 0-3.2-1.4-3.2-3.2v-71.1c0-1.8 1.4-3.2 3.2-3.2H219c1 0 2.1.5 2.6 1.4l32.6 44v-42.2c0-1.8 1.4-3.2 3.2-3.2h11.4c1.8-.1 3.3 1.4 3.3 3.1zm-82-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 1.8 1.4 3.2 3.2 3.2h11.4c1.8 0 3.2-1.4 3.2-3.2v-71.1c0-1.7-1.4-3.2-3.2-3.2zm-27.5 59.6h-31.1v-56.4c0-1.8-1.4-3.2-3.2-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 .9.3 1.6.9 2.2.6.5 1.3.9 2.2.9h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.7-1.4-3.2-3.1-3.2zM332.1 201h-45.7c-1.7 0-3.2 1.4-3.2 3.2v71.1c0 1.7 1.4 3.2 3.2 3.2h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2V234c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2v-11.4c-.1-1.7-1.5-3.2-3.2-3.2zM448 113.7V399c-.1 44.8-36.8 81.1-81.7 81H81c-44.8-.1-81.1-36.9-81-81.7V113c.1-44.8 36.9-81.1 81.7-81H367c44.8.1 81.1 36.8 81 81.7zm-61.6 122.6c0-73-73.2-132.4-163.1-132.4-89.9 0-163.1 59.4-163.1 132.4 0 65.4 58 120.2 136.4 130.6 19.1 4.1 16.9 11.1 12.6 36.8-.7 4.1-3.3 16.1 14.1 8.8 17.4-7.3 93.9-55.3 128.2-94.7 23.6-26 34.9-52.3 34.9-81.5z\"],\n    \"linkedin\": [448, 512, [], \"f08c\", \"M416 32H31.9C14.3 32 0 46.5 0 64.3v383.4C0 465.5 14.3 480 31.9 480H416c17.6 0 32-14.5 32-32.3V64.3c0-17.8-14.4-32.3-32-32.3zM135.4 416H69V202.2h66.5V416zm-33.2-243c-21.3 0-38.5-17.3-38.5-38.5S80.9 96 102.2 96c21.2 0 38.5 17.3 38.5 38.5 0 21.3-17.2 38.5-38.5 38.5zm282.1 243h-66.4V312c0-24.8-.5-56.7-34.5-56.7-34.6 0-39.9 27-39.9 54.9V416h-66.4V202.2h63.7v29.2h.9c8.9-16.8 30.6-34.5 62.9-34.5 67.2 0 79.7 44.3 79.7 101.9V416z\"],\n    \"linkedin-in\": [448, 512, [], \"f0e1\", \"M100.28 448H7.4V148.9h92.88zM53.79 108.1C24.09 108.1 0 83.5 0 53.8a53.79 53.79 0 0 1 107.58 0c0 29.7-24.1 54.3-53.79 54.3zM447.9 448h-92.68V302.4c0-34.7-.7-79.2-48.29-79.2-48.29 0-55.69 37.7-55.69 76.7V448h-92.78V148.9h89.08v40.8h1.3c12.4-23.5 42.69-48.3 87.88-48.3 94 0 111.28 61.9 111.28 142.3V448z\"],\n    \"linode\": [448, 512, [], \"f2b8\", \"M437.4 226.3c-.3-.9-.9-1.4-1.4-2l-70-38.6c-.9-.6-2-.6-3.1 0l-58.9 36c-.9.6-1.4 1.7-1.4 2.6l-.9 31.4-24-16c-.9-.6-2.3-.6-3.1 0L240 260.9l-1.4-35.1c0-.9-.6-2-1.4-2.3l-36-24.3 33.7-17.4c1.1-.6 1.7-1.7 1.7-2.9l-5.7-132.3c0-.9-.9-2-1.7-2.6L138.6.3c-.9-.3-1.7-.3-2.3-.3L12.6 38.6c-1.4.6-2.3 2-2 3.7L38 175.4c.9 3.4 34 27.4 38.6 30.9l-26.9 12.9c-1.4.9-2 2.3-1.7 3.4l20.6 100.3c.6 2.9 23.7 23.1 27.1 26.3l-17.4 10.6c-.9.6-1.7 2-1.4 3.1 1.4 7.1 15.4 77.7 16.9 79.1l65.1 69.1c.6.6 1.4.6 2.3.9.6 0 1.1-.3 1.7-.6l83.7-66.9c.9-.6 1.1-1.4 1.1-2.3l-2-46 28 23.7c1.1.9 2.9.9 4 0l66.9-53.4c.9-.6 1.1-1.4 1.1-2.3l2.3-33.4 20.3 14c1.1.9 2.6.9 3.7 0l54.6-43.7c.6-.3 1.1-1.1 1.1-2 .9-6.5 10.3-70.8 9.7-72.8zm-204.8 4.8l4 92.6-90.6 61.2-14-96.6 100.6-57.2zm-7.7-180l5.4 126-106.6 55.4L104 97.7l120.9-46.6zM44 173.1L18 48l79.7 49.4 19.4 132.9L44 173.1zm30.6 147.8L55.7 230l70 58.3 13.7 93.4-64.8-60.8zm24.3 117.7l-13.7-67.1 61.7 60.9 9.7 67.4-57.7-61.2zm64.5 64.5l-10.6-70.9 85.7-61.4 3.1 70-78.2 62.3zm82-115.1c0-3.4.9-22.9-2-25.1l-24.3-20 22.3-14.9c2.3-1.7 1.1-5.7 1.1-8l29.4 22.6.6 68.3-27.1-22.9zm94.3-25.4l-60.9 48.6-.6-68.6 65.7-46.9-4.2 66.9zm27.7-25.7l-19.1-13.4 2-34c.3-.9-.3-2-1.1-2.6L308 259.7l.6-30 64.6 40.6-5.8 66.6zm54.6-39.8l-48.3 38.3 5.7-65.1 51.1-36.6-8.5 63.4z\"],\n    \"linux\": [448, 512, [], \"f17c\", \"M220.8 123.3c1 .5 1.8 1.7 3 1.7 1.1 0 2.8-.4 2.9-1.5.2-1.4-1.9-2.3-3.2-2.9-1.7-.7-3.9-1-5.5-.1-.4.2-.8.7-.6 1.1.3 1.3 2.3 1.1 3.4 1.7zm-21.9 1.7c1.2 0 2-1.2 3-1.7 1.1-.6 3.1-.4 3.5-1.6.2-.4-.2-.9-.6-1.1-1.6-.9-3.8-.6-5.5.1-1.3.6-3.4 1.5-3.2 2.9.1 1 1.8 1.5 2.8 1.4zM420 403.8c-3.6-4-5.3-11.6-7.2-19.7-1.8-8.1-3.9-16.8-10.5-22.4-1.3-1.1-2.6-2.1-4-2.9-1.3-.8-2.7-1.5-4.1-2 9.2-27.3 5.6-54.5-3.7-79.1-11.4-30.1-31.3-56.4-46.5-74.4-17.1-21.5-33.7-41.9-33.4-72C311.1 85.4 315.7.1 234.8 0 132.4-.2 158 103.4 156.9 135.2c-1.7 23.4-6.4 41.8-22.5 64.7-18.9 22.5-45.5 58.8-58.1 96.7-6 17.9-8.8 36.1-6.2 53.3-6.5 5.8-11.4 14.7-16.6 20.2-4.2 4.3-10.3 5.9-17 8.3s-14 6-18.5 14.5c-2.1 3.9-2.8 8.1-2.8 12.4 0 3.9.6 7.9 1.2 11.8 1.2 8.1 2.5 15.7.8 20.8-5.2 14.4-5.9 24.4-2.2 31.7 3.8 7.3 11.4 10.5 20.1 12.3 17.3 3.6 40.8 2.7 59.3 12.5 19.8 10.4 39.9 14.1 55.9 10.4 11.6-2.6 21.1-9.6 25.9-20.2 12.5-.1 26.3-5.4 48.3-6.6 14.9-1.2 33.6 5.3 55.1 4.1.6 2.3 1.4 4.6 2.5 6.7v.1c8.3 16.7 23.8 24.3 40.3 23 16.6-1.3 34.1-11 48.3-27.9 13.6-16.4 36-23.2 50.9-32.2 7.4-4.5 13.4-10.1 13.9-18.3.4-8.2-4.4-17.3-15.5-29.7zM223.7 87.3c9.8-22.2 34.2-21.8 44-.4 6.5 14.2 3.6 30.9-4.3 40.4-1.6-.8-5.9-2.6-12.6-4.9 1.1-1.2 3.1-2.7 3.9-4.6 4.8-11.8-.2-27-9.1-27.3-7.3-.5-13.9 10.8-11.8 23-4.1-2-9.4-3.5-13-4.4-1-6.9-.3-14.6 2.9-21.8zM183 75.8c10.1 0 20.8 14.2 19.1 33.5-3.5 1-7.1 2.5-10.2 4.6 1.2-8.9-3.3-20.1-9.6-19.6-8.4.7-9.8 21.2-1.8 28.1 1 .8 1.9-.2-5.9 5.5-15.6-14.6-10.5-52.1 8.4-52.1zm-13.6 60.7c6.2-4.6 13.6-10 14.1-10.5 4.7-4.4 13.5-14.2 27.9-14.2 7.1 0 15.6 2.3 25.9 8.9 6.3 4.1 11.3 4.4 22.6 9.3 8.4 3.5 13.7 9.7 10.5 18.2-2.6 7.1-11 14.4-22.7 18.1-11.1 3.6-19.8 16-38.2 14.9-3.9-.2-7-1-9.6-2.1-8-3.5-12.2-10.4-20-15-8.6-4.8-13.2-10.4-14.7-15.3-1.4-4.9 0-9 4.2-12.3zm3.3 334c-2.7 35.1-43.9 34.4-75.3 18-29.9-15.8-68.6-6.5-76.5-21.9-2.4-4.7-2.4-12.7 2.6-26.4v-.2c2.4-7.6.6-16-.6-23.9-1.2-7.8-1.8-15 .9-20 3.5-6.7 8.5-9.1 14.8-11.3 10.3-3.7 11.8-3.4 19.6-9.9 5.5-5.7 9.5-12.9 14.3-18 5.1-5.5 10-8.1 17.7-6.9 8.1 1.2 15.1 6.8 21.9 16l19.6 35.6c9.5 19.9 43.1 48.4 41 68.9zm-1.4-25.9c-4.1-6.6-9.6-13.6-14.4-19.6 7.1 0 14.2-2.2 16.7-8.9 2.3-6.2 0-14.9-7.4-24.9-13.5-18.2-38.3-32.5-38.3-32.5-13.5-8.4-21.1-18.7-24.6-29.9s-3-23.3-.3-35.2c5.2-22.9 18.6-45.2 27.2-59.2 2.3-1.7.8 3.2-8.7 20.8-8.5 16.1-24.4 53.3-2.6 82.4.6-20.7 5.5-41.8 13.8-61.5 12-27.4 37.3-74.9 39.3-112.7 1.1.8 4.6 3.2 6.2 4.1 4.6 2.7 8.1 6.7 12.6 10.3 12.4 10 28.5 9.2 42.4 1.2 6.2-3.5 11.2-7.5 15.9-9 9.9-3.1 17.8-8.6 22.3-15 7.7 30.4 25.7 74.3 37.2 95.7 6.1 11.4 18.3 35.5 23.6 64.6 3.3-.1 7 .4 10.9 1.4 13.8-35.7-11.7-74.2-23.3-84.9-4.7-4.6-4.9-6.6-2.6-6.5 12.6 11.2 29.2 33.7 35.2 59 2.8 11.6 3.3 23.7.4 35.7 16.4 6.8 35.9 17.9 30.7 34.8-2.2-.1-3.2 0-4.2 0 3.2-10.1-3.9-17.6-22.8-26.1-19.6-8.6-36-8.6-38.3 12.5-12.1 4.2-18.3 14.7-21.4 27.3-2.8 11.2-3.6 24.7-4.4 39.9-.5 7.7-3.6 18-6.8 29-32.1 22.9-76.7 32.9-114.3 7.2zm257.4-11.5c-.9 16.8-41.2 19.9-63.2 46.5-13.2 15.7-29.4 24.4-43.6 25.5s-26.5-4.8-33.7-19.3c-4.7-11.1-2.4-23.1 1.1-36.3 3.7-14.2 9.2-28.8 9.9-40.6.8-15.2 1.7-28.5 4.2-38.7 2.6-10.3 6.6-17.2 13.7-21.1.3-.2.7-.3 1-.5.8 13.2 7.3 26.6 18.8 29.5 12.6 3.3 30.7-7.5 38.4-16.3 9-.3 15.7-.9 22.6 5.1 9.9 8.5 7.1 30.3 17.1 41.6 10.6 11.6 14 19.5 13.7 24.6zM173.3 148.7c2 1.9 4.7 4.5 8 7.1 6.6 5.2 15.8 10.6 27.3 10.6 11.6 0 22.5-5.9 31.8-10.8 4.9-2.6 10.9-7 14.8-10.4s5.9-6.3 3.1-6.6-2.6 2.6-6 5.1c-4.4 3.2-9.7 7.4-13.9 9.8-7.4 4.2-19.5 10.2-29.9 10.2s-18.7-4.8-24.9-9.7c-3.1-2.5-5.7-5-7.7-6.9-1.5-1.4-1.9-4.6-4.3-4.9-1.4-.1-1.8 3.7 1.7 6.5z\"],\n    \"lyft\": [512, 512, [], \"f3c3\", \"M0 81.1h77.8v208.7c0 33.1 15 52.8 27.2 61-12.7 11.1-51.2 20.9-80.2-2.8C7.8 334 0 310.7 0 289V81.1zm485.9 173.5v-22h23.8v-76.8h-26.1c-10.1-46.3-51.2-80.7-100.3-80.7-56.6 0-102.7 46-102.7 102.7V357c16 2.3 35.4-.3 51.7-14 17.1-14 24.8-37.2 24.8-59v-6.7h38.8v-76.8h-38.8v-23.3c0-34.6 52.2-34.6 52.2 0v77.1c0 56.6 46 102.7 102.7 102.7v-76.5c-14.5 0-26.1-11.7-26.1-25.9zm-294.3-99v113c0 15.4-23.8 15.4-23.8 0v-113H91v132.7c0 23.8 8 54 45 63.9 37 9.8 58.2-10.6 58.2-10.6-2.1 13.4-14.5 23.3-34.9 25.3-15.5 1.6-35.2-3.6-45-7.8v70.3c25.1 7.5 51.5 9.8 77.6 4.7 47.1-9.1 76.8-48.4 76.8-100.8V155.1h-77.1v.5z\"],\n    \"magento\": [448, 512, [], \"f3c4\", \"M445.7 127.9V384l-63.4 36.5V164.7L223.8 73.1 65.2 164.7l.4 255.9L2.3 384V128.1L224.2 0l221.5 127.9zM255.6 420.5L224 438.9l-31.8-18.2v-256l-63.3 36.6.1 255.9 94.9 54.9 95.1-54.9v-256l-63.4-36.6v255.9z\"],\n    \"mailchimp\": [448, 512, [], \"f59e\", \"M330.61 243.52a36.15 36.15 0 0 1 9.3 0c1.66-3.83 1.95-10.43.45-17.61-2.23-10.67-5.25-17.14-11.48-16.13s-6.47 8.74-4.24 19.42c1.26 6 3.49 11.14 6 14.32zM277.05 252c4.47 2 7.2 3.26 8.28 2.13 1.89-1.94-3.48-9.39-12.12-13.09a31.44 31.44 0 0 0-30.61 3.68c-3 2.18-5.81 5.22-5.41 7.06.85 3.74 10-2.71 22.6-3.48 7-.44 12.8 1.75 17.26 3.71zm-9 5.13c-9.07 1.42-15 6.53-13.47 10.1.9.34 1.17.81 5.21-.81a37 37 0 0 1 18.72-1.95c2.92.34 4.31.52 4.94-.49 1.46-2.22-5.71-8-15.39-6.85zm54.17 17.1c3.38-6.87-10.9-13.93-14.3-7s10.92 13.88 14.32 6.97zm15.66-20.47c-7.66-.13-7.95 15.8-.26 15.93s7.98-15.81.28-15.96zm-218.79 78.9c-1.32.31-6 1.45-8.47-2.35-5.2-8 11.11-20.38 3-35.77-9.1-17.47-27.82-13.54-35.05-5.54-8.71 9.6-8.72 23.54-5 24.08 4.27.57 4.08-6.47 7.38-11.63a12.83 12.83 0 0 1 17.85-3.72c11.59 7.59 1.37 17.76 2.28 28.62 1.39 16.68 18.42 16.37 21.58 9a2.08 2.08 0 0 0-.2-2.33c.03.89.68-1.3-3.35-.39zm299.72-17.07c-3.35-11.73-2.57-9.22-6.78-20.52 2.45-3.67 15.29-24-3.07-43.25-10.4-10.92-33.9-16.54-41.1-18.54-1.5-11.39 4.65-58.7-21.52-83 20.79-21.55 33.76-45.29 33.73-65.65-.06-39.16-48.15-51-107.42-26.47l-12.55 5.33c-.06-.05-22.71-22.27-23.05-22.57C169.5-18-41.77 216.81 25.78 273.85l14.76 12.51a72.49 72.49 0 0 0-4.1 33.5c3.36 33.4 36 60.42 67.53 60.38 57.73 133.06 267.9 133.28 322.29 3 1.74-4.47 9.11-24.61 9.11-42.38s-10.09-25.27-16.53-25.27zm-316 48.16c-22.82-.61-47.46-21.15-49.91-45.51-6.17-61.31 74.26-75.27 84-12.33 4.54 29.64-4.67 58.49-34.12 57.81zM84.3 249.55C69.14 252.5 55.78 261.09 47.6 273c-4.88-4.07-14-12-15.59-15-13.01-24.85 14.24-73 33.3-100.21C112.42 90.56 186.19 39.68 220.36 48.91c5.55 1.57 23.94 22.89 23.94 22.89s-34.15 18.94-65.8 45.35c-42.66 32.85-74.89 80.59-94.2 132.4zM323.18 350.7s-35.74 5.3-69.51-7.07c6.21-20.16 27 6.1 96.4-13.81 15.29-4.38 35.37-13 51-25.35a102.85 102.85 0 0 1 7.12 24.28c3.66-.66 14.25-.52 11.44 18.1-3.29 19.87-11.73 36-25.93 50.84A106.86 106.86 0 0 1 362.55 421a132.45 132.45 0 0 1-20.34 8.58c-53.51 17.48-108.3-1.74-126-43a66.33 66.33 0 0 1-3.55-9.74c-7.53-27.2-1.14-59.83 18.84-80.37 1.23-1.31 2.48-2.85 2.48-4.79a8.45 8.45 0 0 0-1.92-4.54c-7-10.13-31.19-27.4-26.33-60.83 3.5-24 24.49-40.91 44.07-39.91l5 .29c8.48.5 15.89 1.59 22.88 1.88 11.69.5 22.2-1.19 34.64-11.56 4.2-3.5 7.57-6.54 13.26-7.51a17.45 17.45 0 0 1 13.6 2.24c10 6.64 11.4 22.73 11.92 34.49.29 6.72 1.1 23 1.38 27.63.63 10.67 3.43 12.17 9.11 14 3.19 1.05 6.15 1.83 10.51 3.06 13.21 3.71 21 7.48 26 12.31a16.38 16.38 0 0 1 4.74 9.29c1.56 11.37-8.82 25.4-36.31 38.16-46.71 21.68-93.68 14.45-100.48 13.68-20.15-2.71-31.63 23.32-19.55 41.15 22.64 33.41 122.4 20 151.37-21.35.69-1 .12-1.59-.73-1-41.77 28.58-97.06 38.21-128.46 26-4.77-1.85-14.73-6.44-15.94-16.67 43.6 13.49 71 .74 71 .74s2.03-2.79-.56-2.53zm-68.47-5.7zm-83.4-187.5c16.74-19.35 37.36-36.18 55.83-45.63a.73.73 0 0 1 1 1c-1.46 2.66-4.29 8.34-5.19 12.65a.75.75 0 0 0 1.16.79c11.49-7.83 31.48-16.22 49-17.3a.77.77 0 0 1 .52 1.38 41.86 41.86 0 0 0-7.71 7.74.75.75 0 0 0 .59 1.19c12.31.09 29.66 4.4 41 10.74.76.43.22 1.91-.64 1.72-69.55-15.94-123.08 18.53-134.5 26.83a.76.76 0 0 1-1-1.12z\"],\n    \"mandalorian\": [448, 512, [], \"f50f\", \"M232.27 511.89c-1-3.26-1.69-15.83-1.39-24.58.55-15.89 1-24.72 1.4-28.76.64-6.2 2.87-20.72 3.28-21.38.6-1 .4-27.87-.24-33.13-.31-2.58-.63-11.9-.69-20.73-.13-16.47-.53-20.12-2.73-24.76-1.1-2.32-1.23-3.84-1-11.43a92.38 92.38 0 0 0-.34-12.71c-2-13-3.46-27.7-3.25-33.9s.43-7.15 2.06-9.67c3.05-4.71 6.51-14 8.62-23.27 2.26-9.86 3.88-17.18 4.59-20.74a109.54 109.54 0 0 1 4.42-15.05c2.27-6.25 2.49-15.39.37-15.39-.3 0-1.38 1.22-2.41 2.71s-4.76 4.8-8.29 7.36c-8.37 6.08-11.7 9.39-12.66 12.58s-1 7.23-.16 7.76c.34.21 1.29 2.4 2.11 4.88a28.83 28.83 0 0 1 .72 15.36c-.39 1.77-1 5.47-1.46 8.23s-1 6.46-1.25 8.22a9.85 9.85 0 0 1-1.55 4.26c-1 1-1.14.91-2.05-.53a14.87 14.87 0 0 1-1.44-4.75c-.25-1.74-1.63-7.11-3.08-11.93-3.28-10.9-3.52-16.15-1-21a14.24 14.24 0 0 0 1.67-4.61c0-2.39-2.2-5.32-7.41-9.89-7-6.18-8.63-7.92-10.23-11.3-1.71-3.6-3.06-4.06-4.54-1.54-1.78 3-2.6 9.11-3 22l-.34 12.19 2 2.25c3.21 3.7 12.07 16.45 13.78 19.83 3.41 6.74 4.34 11.69 4.41 23.56s.95 22.75 2 24.71c.36.66.51 1.35.34 1.52s.41 2.09 1.29 4.27a38.14 38.14 0 0 1 2.06 9 91 91 0 0 0 1.71 10.37c2.23 9.56 2.77 14.08 2.39 20.14-.2 3.27-.53 11.07-.73 17.32-1.31 41.76-1.85 58-2 61.21-.12 2-.39 11.51-.6 21.07-.36 16.3-1.3 27.37-2.42 28.65-.64.73-8.07-4.91-12.52-9.49-3.75-3.87-4-4.79-2.83-9.95.7-3 2.26-18.29 3.33-32.62.36-4.78.81-10.5 1-12.71.83-9.37 1.66-20.35 2.61-34.78.56-8.46 1.33-16.44 1.72-17.73s.89-9.89 1.13-19.11l.43-16.77-2.26-4.3c-1.72-3.28-4.87-6.94-13.22-15.34-6-6.07-11.84-12.3-12.91-13.85l-1.95-2.81.75-10.9c1.09-15.71 1.1-48.57 0-59.06l-.89-8.7-3.28-4.52c-5.86-8.08-5.8-7.75-6.22-33.27-.1-6.07-.38-11.5-.63-12.06-.83-1.87-3.05-2.66-8.54-3.05-8.86-.62-11-1.9-23.85-14.55-6.15-6-12.34-12-13.75-13.19-2.81-2.42-2.79-2-.56-9.63l1.35-4.65-1.69-3a32.22 32.22 0 0 0-2.59-4.07c-1.33-1.51-5.5-10.89-6-13.49a4.24 4.24 0 0 1 .87-3.9c2.23-2.86 3.4-5.68 4.45-10.73 2.33-11.19 7.74-26.09 10.6-29.22 3.18-3.47 7.7-1 9.41 5 1.34 4.79 1.37 9.79.1 18.55a101.2 101.2 0 0 0-1 11.11c0 4 .19 4.69 2.25 7.39 3.33 4.37 7.73 7.41 15.2 10.52a18.67 18.67 0 0 1 4.72 2.85c11.17 10.72 18.62 16.18 22.95 16.85 5.18.8 8 4.54 10 13.39 1.31 5.65 4 11.14 5.46 11.14a9.38 9.38 0 0 0 3.33-1.39c2-1.22 2.25-1.73 2.25-4.18a132.88 132.88 0 0 0-2-17.84c-.37-1.66-.78-4.06-.93-5.35s-.61-3.85-1-5.69c-2.55-11.16-3.65-15.46-4.1-16-1.55-2-4.08-10.2-4.93-15.92-1.64-11.11-4-14.23-12.91-17.39A43.15 43.15 0 0 1 165.24 78c-1.15-1-4-3.22-6.35-5.06s-4.41-3.53-4.6-3.76a22.7 22.7 0 0 0-2.69-2c-6.24-4.22-8.84-7-11.26-12l-2.44-5-.22-13-.22-13 6.91-6.55c3.95-3.75 8.48-7.35 10.59-8.43 3.31-1.69 4.45-1.89 11.37-2 8.53-.19 10.12 0 11.66 1.56s1.36 6.4-.29 8.5a6.66 6.66 0 0 0-1.34 2.32c0 .58-2.61 4.91-5.42 9a30.39 30.39 0 0 0-2.37 6.82c20.44 13.39 21.55 3.77 14.07 29L194 66.92c3.11-8.66 6.47-17.26 8.61-26.22.29-7.63-12-4.19-15.4-8.68-2.33-5.93 3.13-14.18 6.06-19.2 1.6-2.34 6.62-4.7 8.82-4.15.88.22 4.16-.35 7.37-1.28a45.3 45.3 0 0 1 7.55-1.68 29.57 29.57 0 0 0 6-1.29c3.65-1.11 4.5-1.17 6.35-.4a29.54 29.54 0 0 0 5.82 1.36 18.18 18.18 0 0 1 6 1.91 22.67 22.67 0 0 0 5 2.17c2.51.68 3 .57 7.05-1.67l4.35-2.4L268.32 5c10.44-.4 10.81-.47 15.26-2.68L288.16 0l2.46 1.43c1.76 1 3.14 2.73 4.85 6 2.36 4.51 2.38 4.58 1.37 7.37-.88 2.44-.89 3.3-.1 6.39a35.76 35.76 0 0 0 2.1 5.91 13.55 13.55 0 0 1 1.31 4c.31 4.33 0 5.3-2.41 6.92-2.17 1.47-7 7.91-7 9.34a14.77 14.77 0 0 1-1.07 3c-5 11.51-6.76 13.56-14.26 17-9.2 4.2-12.3 5.19-16.21 5.19-3.1 0-4 .25-4.54 1.26a18.33 18.33 0 0 1-4.09 3.71 13.62 13.62 0 0 0-4.38 4.78 5.89 5.89 0 0 1-2.49 2.91 6.88 6.88 0 0 0-2.45 1.71 67.62 67.62 0 0 1-7 5.38c-3.33 2.34-6.87 5-7.87 6A7.27 7.27 0 0 1 224 100a5.76 5.76 0 0 0-2.13 1.65c-1.31 1.39-1.49 2.11-1.14 4.6a36.45 36.45 0 0 0 1.42 5.88c1.32 3.8 1.31 7.86 0 10.57s-.89 6.65 1.35 9.59c2 2.63 2.16 4.56.71 8.84a33.45 33.45 0 0 0-1.06 8.91c0 4.88.22 6.28 1.46 8.38s1.82 2.48 3.24 2.32c2-.23 2.3-1.05 4.71-12.12 2.18-10 3.71-11.92 13.76-17.08 2.94-1.51 7.46-4 10-5.44s6.79-3.69 9.37-4.91a40.09 40.09 0 0 0 15.22-11.67c7.11-8.79 10-16.22 12.85-33.3a18.37 18.37 0 0 1 2.86-7.73 20.39 20.39 0 0 0 2.89-7.31c1-5.3 2.85-9.08 5.58-11.51 4.7-4.18 6-1.09 4.59 10.87-.46 3.86-1.1 10.33-1.44 14.38l-.61 7.36 4.45 4.09 4.45 4.09.11 8.42c.06 4.63.47 9.53.92 10.89l.82 2.47-6.43 6.28c-8.54 8.33-12.88 13.93-16.76 21.61-1.77 3.49-3.74 7.11-4.38 8-2.18 3.11-6.46 13-8.76 20.26l-2.29 7.22-7 6.49c-3.83 3.57-8 7.25-9.17 8.17-3.05 2.32-4.26 5.15-4.26 10a14.62 14.62 0 0 0 1.59 7.26 42 42 0 0 1 2.09 4.83 9.28 9.28 0 0 0 1.57 2.89c1.4 1.59 1.92 16.12.83 23.22-.68 4.48-3.63 12-4.7 12-1.79 0-4.06 9.27-5.07 20.74-.18 2-.62 5.94-1 8.7s-1 10-1.35 16.05c-.77 12.22-.19 18.77 2 23.15 3.41 6.69.52 12.69-11 22.84l-4 3.49.07 5.19a40.81 40.81 0 0 0 1.14 8.87c4.61 16 4.73 16.92 4.38 37.13-.46 26.4-.26 40.27.63 44.15a61.31 61.31 0 0 1 1.08 7c.17 2 .66 5.33 1.08 7.36.47 2.26.78 11 .79 22.74v19.06l-1.81 2.63c-2.71 3.91-15.11 13.54-15.49 12.29zm29.53-45.11c-.18-.3-.33-6.87-.33-14.59 0-14.06-.89-27.54-2.26-34.45-.4-2-.81-9.7-.9-17.06-.15-11.93-1.4-24.37-2.64-26.38-.66-1.07-3-17.66-3-21.3 0-4.23 1-6 5.28-9.13s4.86-3.14 5.48-.72c.28 1.1 1.45 5.62 2.6 10 3.93 15.12 4.14 16.27 4.05 21.74-.1 5.78-.13 6.13-1.74 17.73-1 7.07-1.17 12.39-1 28.43.17 19.4-.64 35.73-2 41.27-.71 2.78-2.8 5.48-3.43 4.43zm-71-37.58a101 101 0 0 1-1.73-10.79 100.5 100.5 0 0 0-1.73-10.79 37.53 37.53 0 0 1-1-6.49c-.31-3.19-.91-7.46-1.33-9.48-1-4.79-3.35-19.35-3.42-21.07 0-.74-.34-4.05-.7-7.36-.67-6.21-.84-27.67-.22-28.29 1-1 6.63 2.76 11.33 7.43l5.28 5.25-.45 6.47c-.25 3.56-.6 10.23-.78 14.83s-.49 9.87-.67 11.71-.61 9.36-.94 16.72c-.79 17.41-1.94 31.29-2.65 32a.62.62 0 0 1-1-.14zm-87.18-266.59c21.07 12.79 17.84 14.15 28.49 17.66 13 4.29 18.87 7.13 23.15 16.87C111.6 233.28 86.25 255 78.55 268c-31 52-6 101.59 62.75 87.21-14.18 29.23-78 28.63-98.68-4.9-24.68-39.95-22.09-118.3 61-187.66zm210.79 179c56.66 6.88 82.32-37.74 46.54-89.23 0 0-26.87-29.34-64.28-68 3-15.45 9.49-32.12 30.57-53.82 89.2 63.51 92 141.61 92.46 149.36 4.3 70.64-78.7 91.18-105.29 61.71z\"],\n    \"markdown\": [640, 512, [], \"f60f\", \"M593.8 59.1H46.2C20.7 59.1 0 79.8 0 105.2v301.5c0 25.5 20.7 46.2 46.2 46.2h547.7c25.5 0 46.2-20.7 46.1-46.1V105.2c0-25.4-20.7-46.1-46.2-46.1zM338.5 360.6H277v-120l-61.5 76.9-61.5-76.9v120H92.3V151.4h61.5l61.5 76.9 61.5-76.9h61.5v209.2zm135.3 3.1L381.5 256H443V151.4h61.5V256H566z\"],\n    \"mastodon\": [448, 512, [], \"f4f6\", \"M433 179.11c0-97.2-63.71-125.7-63.71-125.7-62.52-28.7-228.56-28.4-290.48 0 0 0-63.72 28.5-63.72 125.7 0 115.7-6.6 259.4 105.63 289.1 40.51 10.7 75.32 13 103.33 11.4 50.81-2.8 79.32-18.1 79.32-18.1l-1.7-36.9s-36.31 11.4-77.12 10.1c-40.41-1.4-83-4.4-89.63-54a102.54 102.54 0 0 1-.9-13.9c85.63 20.9 158.65 9.1 178.75 6.7 56.12-6.7 105-41.3 111.23-72.9 9.8-49.8 9-121.5 9-121.5zm-75.12 125.2h-46.63v-114.2c0-49.7-64-51.6-64 6.9v62.5h-46.33V197c0-58.5-64-56.6-64-6.9v114.2H90.19c0-122.1-5.2-147.9 18.41-175 25.9-28.9 79.82-30.8 103.83 6.1l11.6 19.5 11.6-19.5c24.11-37.1 78.12-34.8 103.83-6.1 23.71 27.3 18.4 53 18.4 175z\"],\n    \"maxcdn\": [512, 512, [], \"f136\", \"M461.1 442.7h-97.4L415.6 200c2.3-10.2.9-19.5-4.4-25.7-5-6.1-13.7-9.6-24.2-9.6h-49.3l-59.5 278h-97.4l59.5-278h-83.4l-59.5 278H0l59.5-278-44.6-95.4H387c39.4 0 75.3 16.3 98.3 44.9 23.3 28.6 31.8 67.4 23.6 105.9l-47.8 222.6z\"],\n    \"medapps\": [320, 512, [], \"f3c6\", \"M118.3 238.4c3.5-12.5 6.9-33.6 13.2-33.6 8.3 1.8 9.6 23.4 18.6 36.6 4.6-23.5 5.3-85.1 14.1-86.7 9-.7 19.7 66.5 22 77.5 9.9 4.1 48.9 6.6 48.9 6.6 1.9 7.3-24 7.6-40 7.8-4.6 14.8-5.4 27.7-11.4 28-4.7.2-8.2-28.8-17.5-49.6l-9.4 65.5c-4.4 13-15.5-22.5-21.9-39.3-3.3-.1-62.4-1.6-47.6-7.8l31-5zM228 448c21.2 0 21.2-32 0-32H92c-21.2 0-21.2 32 0 32h136zm-24 64c21.2 0 21.2-32 0-32h-88c-21.2 0-21.2 32 0 32h88zm34.2-141.5c3.2-18.9 5.2-36.4 11.9-48.8 7.9-14.7 16.1-28.1 24-41 24.6-40.4 45.9-75.2 45.9-125.5C320 69.6 248.2 0 160 0S0 69.6 0 155.2c0 50.2 21.3 85.1 45.9 125.5 7.9 12.9 16 26.3 24 41 6.7 12.5 8.7 29.8 11.9 48.9 3.5 21 36.1 15.7 32.6-5.1-3.6-21.7-5.6-40.7-15.3-58.6C66.5 246.5 33 211.3 33 155.2 33 87.3 90 32 160 32s127 55.3 127 123.2c0 56.1-33.5 91.3-66.1 151.6-9.7 18-11.7 37.4-15.3 58.6-3.4 20.6 29 26.4 32.6 5.1z\"],\n    \"medium\": [448, 512, [], \"f23a\", \"M0 32v448h448V32H0zm372.2 106.1l-24 23c-2.1 1.6-3.1 4.2-2.7 6.7v169.3c-.4 2.6.6 5.2 2.7 6.7l23.5 23v5.1h-118V367l24.3-23.6c2.4-2.4 2.4-3.1 2.4-6.7V199.8l-67.6 171.6h-9.1L125 199.8v115c-.7 4.8 1 9.7 4.4 13.2l31.6 38.3v5.1H71.2v-5.1l31.6-38.3c3.4-3.5 4.9-8.4 4.1-13.2v-133c.4-3.7-1-7.3-3.8-9.8L75 138.1V133h87.3l67.4 148L289 133.1h83.2v5z\"],\n    \"medium-m\": [512, 512, [], \"f3c7\", \"M71.5 142.3c.6-5.9-1.7-11.8-6.1-15.8L20.3 72.1V64h140.2l108.4 237.7L364.2 64h133.7v8.1l-38.6 37c-3.3 2.5-5 6.7-4.3 10.8v272c-.7 4.1 1 8.3 4.3 10.8l37.7 37v8.1H307.3v-8.1l39.1-37.9c3.8-3.8 3.8-5 3.8-10.8V171.2L241.5 447.1h-14.7L100.4 171.2v184.9c-1.1 7.8 1.5 15.6 7 21.2l50.8 61.6v8.1h-144v-8L65 377.3c5.4-5.6 7.9-13.5 6.5-21.2V142.3z\"],\n    \"medrt\": [544, 512, [], \"f3c8\", \"M113.7 256c0 121.8 83.9 222.8 193.5 241.1-18.7 4.5-38.2 6.9-58.2 6.9C111.4 504 0 393 0 256S111.4 8 248.9 8c20.1 0 39.6 2.4 58.2 6.9C197.5 33.2 113.7 134.2 113.7 256m297.4 100.3c-77.7 55.4-179.6 47.5-240.4-14.6 5.5 14.1 12.7 27.7 21.7 40.5 61.6 88.2 182.4 109.3 269.7 47 87.3-62.3 108.1-184.3 46.5-272.6-9-12.9-19.3-24.3-30.5-34.2 37.4 78.8 10.7 178.5-67 233.9m-218.8-244c-1.4 1-2.7 2.1-4 3.1 64.3-17.8 135.9 4 178.9 60.5 35.7 47 42.9 106.6 24.4 158 56.7-56.2 67.6-142.1 22.3-201.8-50-65.5-149.1-74.4-221.6-19.8M296 224c-4.4 0-8-3.6-8-8v-40c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v40c0 4.4-3.6 8-8 8h-40c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h40c4.4 0 8 3.6 8 8v40c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-40c0-4.4 3.6-8 8-8h40c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8h-40z\"],\n    \"meetup\": [512, 512, [], \"f2e0\", \"M99 414.3c1.1 5.7-2.3 11.1-8 12.3-5.4 1.1-10.9-2.3-12-8-1.1-5.4 2.3-11.1 7.7-12.3 5.4-1.2 11.1 2.3 12.3 8zm143.1 71.4c-6.3 4.6-8 13.4-3.7 20 4.6 6.6 13.4 8.3 20 3.7 6.3-4.6 8-13.4 3.4-20-4.2-6.5-13.1-8.3-19.7-3.7zm-86-462.3c6.3-1.4 10.3-7.7 8.9-14-1.1-6.6-7.4-10.6-13.7-9.1-6.3 1.4-10.3 7.7-9.1 14 1.4 6.6 7.6 10.6 13.9 9.1zM34.4 226.3c-10-6.9-23.7-4.3-30.6 6-6.9 10-4.3 24 5.7 30.9 10 7.1 23.7 4.6 30.6-5.7 6.9-10.4 4.3-24.1-5.7-31.2zm272-170.9c10.6-6.3 13.7-20 7.7-30.3-6.3-10.6-19.7-14-30-7.7s-13.7 20-7.4 30.6c6 10.3 19.4 13.7 29.7 7.4zm-191.1 58c7.7-5.4 9.4-16 4.3-23.7s-15.7-9.4-23.1-4.3c-7.7 5.4-9.4 16-4.3 23.7 5.1 7.8 15.6 9.5 23.1 4.3zm372.3 156c-7.4 1.7-12.3 9.1-10.6 16.9 1.4 7.4 8.9 12.3 16.3 10.6 7.4-1.4 12.3-8.9 10.6-16.6-1.5-7.4-8.9-12.3-16.3-10.9zm39.7-56.8c-1.1-5.7-6.6-9.1-12-8-5.7 1.1-9.1 6.9-8 12.6 1.1 5.4 6.6 9.1 12.3 8 5.4-1.5 9.1-6.9 7.7-12.6zM447 138.9c-8.6 6-10.6 17.7-4.9 26.3 5.7 8.6 17.4 10.6 26 4.9 8.3-6 10.3-17.7 4.6-26.3-5.7-8.7-17.4-10.9-25.7-4.9zm-6.3 139.4c26.3 43.1 15.1 100-26.3 129.1-17.4 12.3-37.1 17.7-56.9 17.1-12 47.1-69.4 64.6-105.1 32.6-1.1.9-2.6 1.7-3.7 2.9-39.1 27.1-92.3 17.4-119.4-22.3-9.7-14.3-14.6-30.6-15.1-46.9-65.4-10.9-90-94-41.1-139.7-28.3-46.9.6-107.4 53.4-114.9C151.6 70 234.1 38.6 290.1 82c67.4-22.3 136.3 29.4 130.9 101.1 41.1 12.6 52.8 66.9 19.7 95.2zm-70 74.3c-3.1-20.6-40.9-4.6-43.1-27.1-3.1-32 43.7-101.1 40-128-3.4-24-19.4-29.1-33.4-29.4-13.4-.3-16.9 2-21.4 4.6-2.9 1.7-6.6 4.9-11.7-.3-6.3-6-11.1-11.7-19.4-12.9-12.3-2-17.7 2-26.6 9.7-3.4 2.9-12 12.9-20 9.1-3.4-1.7-15.4-7.7-24-11.4-16.3-7.1-40 4.6-48.6 20-12.9 22.9-38 113.1-41.7 125.1-8.6 26.6 10.9 48.6 36.9 47.1 11.1-.6 18.3-4.6 25.4-17.4 4-7.4 41.7-107.7 44.6-112.6 2-3.4 8.9-8 14.6-5.1 5.7 3.1 6.9 9.4 6 15.1-1.1 9.7-28 70.9-28.9 77.7-3.4 22.9 26.9 26.6 38.6 4 3.7-7.1 45.7-92.6 49.4-98.3 4.3-6.3 7.4-8.3 11.7-8 3.1 0 8.3.9 7.1 10.9-1.4 9.4-35.1 72.3-38.9 87.7-4.6 20.6 6.6 41.4 24.9 50.6 11.4 5.7 62.5 15.7 58.5-11.1zm5.7 92.3c-10.3 7.4-12.9 22-5.7 32.6 7.1 10.6 21.4 13.1 32 6 10.6-7.4 13.1-22 6-32.6-7.4-10.6-21.7-13.5-32.3-6z\"],\n    \"megaport\": [496, 512, [], \"f5a3\", \"M214.5 209.6v66.2l33.5 33.5 33.3-33.3v-66.4l-33.4-33.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm145.1 414.4L367 441.6l-26-19.2v-65.5l-33.4-33.4-33.4 33.4v65.5L248 441.6l-26.1-19.2v-65.5l-33.4-33.4-33.5 33.4v65.5l-26.1 19.2-26.1-19.2v-87l59.5-59.5V188l59.5-59.5V52.9l26.1-19.2L274 52.9v75.6l59.5 59.5v87.6l59.7 59.7v87.1z\"],\n    \"mendeley\": [640, 512, [], \"f7b3\", \"M624.6 325.2c-12.3-12.4-29.7-19.2-48.4-17.2-43.3-1-49.7-34.9-37.5-98.8 22.8-57.5-14.9-131.5-87.4-130.8-77.4.7-81.7 82-130.9 82-48.1 0-54-81.3-130.9-82-72.9-.8-110.1 73.3-87.4 130.8 12.2 63.9 5.8 97.8-37.5 98.8-21.2-2.3-37 6.5-53 22.5-19.9 19.7-19.3 94.8 42.6 102.6 47.1 5.9 81.6-42.9 61.2-87.8-47.3-103.7 185.9-106.1 146.5-8.2-.1.1-.2.2-.3.4-26.8 42.8 6.8 97.4 58.8 95.2 52.1 2.1 85.4-52.6 58.8-95.2-.1-.2-.2-.3-.3-.4-39.4-97.9 193.8-95.5 146.5 8.2-4.6 10-6.7 21.3-5.7 33 4.9 53.4 68.7 74.1 104.9 35.2 17.8-14.8 23.1-65.6 0-88.3zm-303.9-19.1h-.6c-43.4 0-62.8-37.5-62.8-62.8 0-34.7 28.2-62.8 62.8-62.8h.6c34.7 0 62.8 28.1 62.8 62.8 0 25-19.2 62.8-62.8 62.8z\"],\n    \"microsoft\": [448, 512, [], \"f3ca\", \"M0 32h214.6v214.6H0V32zm233.4 0H448v214.6H233.4V32zM0 265.4h214.6V480H0V265.4zm233.4 0H448V480H233.4V265.4z\"],\n    \"mix\": [448, 512, [], \"f3cb\", \"M0 64v348.9c0 56.2 88 58.1 88 0V174.3c7.9-52.9 88-50.4 88 6.5v175.3c0 57.9 96 58 96 0V240c5.3-54.7 88-52.5 88 4.3v23.8c0 59.9 88 56.6 88 0V64H0z\"],\n    \"mixcloud\": [640, 512, [], \"f289\", \"M424.43 219.729C416.124 134.727 344.135 68 256.919 68c-72.266 0-136.224 46.516-159.205 114.074-54.545 8.029-96.63 54.822-96.63 111.582 0 62.298 50.668 112.966 113.243 112.966h289.614c52.329 0 94.969-42.362 94.969-94.693 0-45.131-32.118-83.063-74.48-92.2zm-20.489 144.53H114.327c-39.04 0-70.881-31.564-70.881-70.604s31.841-70.604 70.881-70.604c18.827 0 36.548 7.475 49.838 20.766 19.963 19.963 50.133-10.227 30.18-30.18-14.675-14.398-32.672-24.365-52.053-29.349 19.935-44.3 64.79-73.926 114.628-73.926 69.496 0 125.979 56.483 125.979 125.702 0 13.568-2.215 26.857-6.369 39.594-8.943 27.517 32.133 38.939 40.147 13.29 2.769-8.306 4.984-16.889 6.369-25.472 19.381 7.476 33.502 26.303 33.502 48.453 0 28.795-23.535 52.33-52.607 52.33zm235.069-52.33c0 44.024-12.737 86.386-37.102 122.657-4.153 6.092-10.798 9.414-17.72 9.414-16.317 0-27.127-18.826-17.443-32.949 19.381-29.349 29.903-63.682 29.903-99.122s-10.521-69.773-29.903-98.845c-15.655-22.831 19.361-47.24 35.163-23.534 24.366 35.993 37.102 78.356 37.102 122.379zm-70.88 0c0 31.565-9.137 62.021-26.857 88.325-4.153 6.091-10.798 9.136-17.72 9.136-17.201 0-27.022-18.979-17.443-32.948 13.013-19.104 19.658-41.255 19.658-64.513 0-22.981-6.645-45.408-19.658-64.512-15.761-22.986 19.008-47.095 35.163-23.535 17.719 26.026 26.857 56.483 26.857 88.047z\"],\n    \"mizuni\": [496, 512, [], \"f3cc\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm-80 351.9c-31.4 10.6-58.8 27.3-80 48.2V136c0-22.1 17.9-40 40-40s40 17.9 40 40v223.9zm120-9.9c-12.9-2-26.2-3.1-39.8-3.1-13.8 0-27.2 1.1-40.2 3.1V136c0-22.1 17.9-40 40-40s40 17.9 40 40v214zm120 57.7c-21.2-20.8-48.6-37.4-80-48V136c0-22.1 17.9-40 40-40s40 17.9 40 40v271.7z\"],\n    \"modx\": [448, 512, [], \"f285\", \"M356 241.8l36.7 23.7V480l-133-83.8L356 241.8zM440 75H226.3l-23 37.8 153.5 96.5L440 75zm-89 142.8L55.2 32v214.5l46 29L351 217.8zM97 294.2L8 437h213.7l125-200.5L97 294.2z\"],\n    \"monero\": [496, 512, [], \"f3d0\", \"M352 384h108.4C417 455.9 338.1 504 248 504S79 455.9 35.6 384H144V256.2L248 361l104-105v128zM88 336V128l159.4 159.4L408 128v208h74.8c8.5-25.1 13.2-52 13.2-80C496 119 385 8 248 8S0 119 0 256c0 28 4.6 54.9 13.2 80H88z\"],\n    \"napster\": [496, 512, [], \"f3d2\", \"M298.3 373.6c-14.2 13.6-31.3 24.1-50.4 30.5-19-6.4-36.2-16.9-50.3-30.5h100.7zm44-199.6c20-16.9 43.6-29.2 69.6-36.2V299c0 219.4-328 217.6-328 .3V137.7c25.9 6.9 49.6 19.6 69.5 36.4 56.8-40 132.5-39.9 188.9-.1zm-208.8-58.5c64.4-60 164.3-60.1 228.9-.2-7.1 3.5-13.9 7.3-20.6 11.5-58.7-30.5-129.2-30.4-187.9.1-6.3-4-13.9-8.2-20.4-11.4zM43.8 93.2v69.3c-58.4 36.5-58.4 121.1.1 158.3 26.4 245.1 381.7 240.3 407.6 1.5l.3-1.7c58.7-36.3 58.9-121.7.2-158.2V93.2c-17.3.5-34 3-50.1 7.4-82-91.5-225.5-91.5-307.5.1-16.3-4.4-33.1-7-50.6-7.5zM259.2 352s36-.3 61.3-1.5c10.2-.5 21.1-4 25.5-6.5 26.3-15.1 25.4-39.2 26.2-47.4-79.5-.6-99.9-3.9-113 55.4zm-135.5-55.3c.8 8.2-.1 32.3 26.2 47.4 4.4 2.5 15.2 6 25.5 6.5 25.3 1.1 61.3 1.5 61.3 1.5-13.2-59.4-33.7-56.1-113-55.4zm169.1 123.4c-3.2-5.3-6.9-7.3-6.9-7.3-24.8 7.3-52.2 6.9-75.9 0 0 0-2.9 1.5-6.4 6.6-2.8 4.1-3.7 9.6-3.7 9.6 29.1 17.6 67.1 17.6 96.2 0-.1-.1-.3-4-3.3-8.9z\"],\n    \"neos\": [512, 512, [], \"f612\", \"M415.44 512h-95.11L212.12 357.46v91.1L125.69 512H28V29.82L68.47 0h108.05l123.74 176.13V63.45L386.69 0h97.69v461.5zM38.77 35.27V496l72-52.88V194l215.5 307.64h84.79l52.35-38.17h-78.27L69 13zm82.54 466.61l80-58.78v-101l-79.76-114.4v220.94L49 501.89h72.34zM80.63 10.77l310.6 442.57h82.37V10.77h-79.75v317.56L170.91 10.77zM311 191.65l72 102.81V15.93l-72 53v122.72z\"],\n    \"nimblr\": [384, 512, [], \"f5a8\", \"M246.6 299.29c15.57 0 27.15 11.46 27.15 27s-11.62 27-27.15 27c-15.7 0-27.15-11.57-27.15-27s11.55-27 27.15-27zM113 326.25c0-15.61 11.68-27 27.15-27s27.15 11.46 27.15 27-11.47 27-27.15 27c-15.44 0-27.15-11.31-27.15-27M191.76 159C157 159 89.45 178.77 59.25 227L14 0v335.48C14 433.13 93.61 512 191.76 512s177.76-78.95 177.76-176.52S290.13 159 191.76 159zm0 308.12c-73.27 0-132.51-58.9-132.51-131.59s59.24-131.59 132.51-131.59 132.51 58.86 132.51 131.54S265 467.07 191.76 467.07z\"],\n    \"node\": [640, 512, [], \"f419\", \"M316.3 452c-2.1 0-4.2-.6-6.1-1.6L291 439c-2.9-1.6-1.5-2.2-.5-2.5 3.8-1.3 4.6-1.6 8.7-4 .4-.2 1-.1 1.4.1l14.8 8.8c.5.3 1.3.3 1.8 0L375 408c.5-.3.9-.9.9-1.6v-66.7c0-.7-.3-1.3-.9-1.6l-57.8-33.3c-.5-.3-1.2-.3-1.8 0l-57.8 33.3c-.6.3-.9 1-.9 1.6v66.7c0 .6.4 1.2.9 1.5l15.8 9.1c8.6 4.3 13.9-.8 13.9-5.8v-65.9c0-.9.7-1.7 1.7-1.7h7.3c.9 0 1.7.7 1.7 1.7v65.9c0 11.5-6.2 18-17.1 18-3.3 0-6 0-13.3-3.6l-15.2-8.7c-3.7-2.2-6.1-6.2-6.1-10.5v-66.7c0-4.3 2.3-8.4 6.1-10.5l57.8-33.4c3.7-2.1 8.5-2.1 12.1 0l57.8 33.4c3.7 2.2 6.1 6.2 6.1 10.5v66.7c0 4.3-2.3 8.4-6.1 10.5l-57.8 33.4c-1.7 1.1-3.8 1.7-6 1.7zm46.7-65.8c0-12.5-8.4-15.8-26.2-18.2-18-2.4-19.8-3.6-19.8-7.8 0-3.5 1.5-8.1 14.8-8.1 11.9 0 16.3 2.6 18.1 10.6.2.8.8 1.3 1.6 1.3h7.5c.5 0 .9-.2 1.2-.5.3-.4.5-.8.4-1.3-1.2-13.8-10.3-20.2-28.8-20.2-16.5 0-26.3 7-26.3 18.6 0 12.7 9.8 16.1 25.6 17.7 18.9 1.9 20.4 4.6 20.4 8.3 0 6.5-5.2 9.2-17.4 9.2-15.3 0-18.7-3.8-19.8-11.4-.1-.8-.8-1.4-1.7-1.4h-7.5c-.9 0-1.7.7-1.7 1.7 0 9.7 5.3 21.3 30.6 21.3 18.5 0 29-7.2 29-19.8zm54.5-50.1c0 6.1-5 11.1-11.1 11.1s-11.1-5-11.1-11.1c0-6.3 5.2-11.1 11.1-11.1 6-.1 11.1 4.8 11.1 11.1zm-1.8 0c0-5.2-4.2-9.3-9.4-9.3-5.1 0-9.3 4.1-9.3 9.3 0 5.2 4.2 9.4 9.3 9.4 5.2-.1 9.4-4.3 9.4-9.4zm-4.5 6.2h-2.6c-.1-.6-.5-3.8-.5-3.9-.2-.7-.4-1.1-1.3-1.1h-2.2v5h-2.4v-12.5h4.3c1.5 0 4.4 0 4.4 3.3 0 2.3-1.5 2.8-2.4 3.1 1.7.1 1.8 1.2 2.1 2.8.1 1 .3 2.7.6 3.3zm-2.8-8.8c0-1.7-1.2-1.7-1.8-1.7h-2v3.5h1.9c1.6 0 1.9-1.1 1.9-1.8zM137.3 191c0-2.7-1.4-5.1-3.7-6.4l-61.3-35.3c-1-.6-2.2-.9-3.4-1h-.6c-1.2 0-2.3.4-3.4 1L3.7 184.6C1.4 185.9 0 188.4 0 191l.1 95c0 1.3.7 2.5 1.8 3.2 1.1.7 2.5.7 3.7 0L42 268.3c2.3-1.4 3.7-3.8 3.7-6.4v-44.4c0-2.6 1.4-5.1 3.7-6.4l15.5-8.9c1.2-.7 2.4-1 3.7-1 1.3 0 2.6.3 3.7 1l15.5 8.9c2.3 1.3 3.7 3.8 3.7 6.4v44.4c0 2.6 1.4 5.1 3.7 6.4l36.4 20.9c1.1.7 2.6.7 3.7 0 1.1-.6 1.8-1.9 1.8-3.2l.2-95zM472.5 87.3v176.4c0 2.6-1.4 5.1-3.7 6.4l-61.3 35.4c-2.3 1.3-5.1 1.3-7.4 0l-61.3-35.4c-2.3-1.3-3.7-3.8-3.7-6.4v-70.8c0-2.6 1.4-5.1 3.7-6.4l61.3-35.4c2.3-1.3 5.1-1.3 7.4 0l15.3 8.8c1.7 1 3.9-.3 3.9-2.2v-94c0-2.8 3-4.6 5.5-3.2l36.5 20.4c2.3 1.2 3.8 3.7 3.8 6.4zm-46 128.9c0-.7-.4-1.3-.9-1.6l-21-12.2c-.6-.3-1.3-.3-1.9 0l-21 12.2c-.6.3-.9.9-.9 1.6v24.3c0 .7.4 1.3.9 1.6l21 12.1c.6.3 1.3.3 1.8 0l21-12.1c.6-.3.9-.9.9-1.6v-24.3zm209.8-.7c2.3-1.3 3.7-3.8 3.7-6.4V192c0-2.6-1.4-5.1-3.7-6.4l-60.9-35.4c-2.3-1.3-5.1-1.3-7.4 0l-61.3 35.4c-2.3 1.3-3.7 3.8-3.7 6.4v70.8c0 2.7 1.4 5.1 3.7 6.4l60.9 34.7c2.2 1.3 5 1.3 7.3 0l36.8-20.5c2.5-1.4 2.5-5 0-6.4L550 241.6c-1.2-.7-1.9-1.9-1.9-3.2v-22.2c0-1.3.7-2.5 1.9-3.2l19.2-11.1c1.1-.7 2.6-.7 3.7 0l19.2 11.1c1.1.7 1.9 1.9 1.9 3.2v17.4c0 2.8 3.1 4.6 5.6 3.2l36.7-21.3zM559 219c-.4.3-.7.7-.7 1.2v13.6c0 .5.3 1 .7 1.2l11.8 6.8c.4.3 1 .3 1.4 0L584 235c.4-.3.7-.7.7-1.2v-13.6c0-.5-.3-1-.7-1.2l-11.8-6.8c-.4-.3-1-.3-1.4 0L559 219zm-254.2 43.5v-70.4c0-2.6-1.6-5.1-3.9-6.4l-61.1-35.2c-2.1-1.2-5-1.4-7.4 0l-61.1 35.2c-2.3 1.3-3.9 3.7-3.9 6.4v70.4c0 2.8 1.9 5.2 4 6.4l61.2 35.2c2.4 1.4 5.2 1.3 7.4 0l61-35.2c1.8-1 3.1-2.7 3.6-4.7.1-.5.2-1.1.2-1.7zm-74.3-124.9l-.8.5h1.1l-.3-.5zm76.2 130.2l-.4-.7v.9l.4-.2z\"],\n    \"node-js\": [448, 512, [], \"f3d3\", \"M224 508c-6.7 0-13.5-1.8-19.4-5.2l-61.7-36.5c-9.2-5.2-4.7-7-1.7-8 12.3-4.3 14.8-5.2 27.9-12.7 1.4-.8 3.2-.5 4.6.4l47.4 28.1c1.7 1 4.1 1 5.7 0l184.7-106.6c1.7-1 2.8-3 2.8-5V149.3c0-2.1-1.1-4-2.9-5.1L226.8 37.7c-1.7-1-4-1-5.7 0L36.6 144.3c-1.8 1-2.9 3-2.9 5.1v213.1c0 2 1.1 4 2.9 4.9l50.6 29.2c27.5 13.7 44.3-2.4 44.3-18.7V167.5c0-3 2.4-5.3 5.4-5.3h23.4c2.9 0 5.4 2.3 5.4 5.3V378c0 36.6-20 57.6-54.7 57.6-10.7 0-19.1 0-42.5-11.6l-48.4-27.9C8.1 389.2.7 376.3.7 362.4V149.3c0-13.8 7.4-26.8 19.4-33.7L204.6 9c11.7-6.6 27.2-6.6 38.8 0l184.7 106.7c12 6.9 19.4 19.8 19.4 33.7v213.1c0 13.8-7.4 26.7-19.4 33.7L243.4 502.8c-5.9 3.4-12.6 5.2-19.4 5.2zm149.1-210.1c0-39.9-27-50.5-83.7-58-57.4-7.6-63.2-11.5-63.2-24.9 0-11.1 4.9-25.9 47.4-25.9 37.9 0 51.9 8.2 57.7 33.8.5 2.4 2.7 4.2 5.2 4.2h24c1.5 0 2.9-.6 3.9-1.7s1.5-2.6 1.4-4.1c-3.7-44.1-33-64.6-92.2-64.6-52.7 0-84.1 22.2-84.1 59.5 0 40.4 31.3 51.6 81.8 56.6 60.5 5.9 65.2 14.8 65.2 26.7 0 20.6-16.6 29.4-55.5 29.4-48.9 0-59.6-12.3-63.2-36.6-.4-2.6-2.6-4.5-5.3-4.5h-23.9c-3 0-5.3 2.4-5.3 5.3 0 31.1 16.9 68.2 97.8 68.2 58.4-.1 92-23.2 92-63.4z\"],\n    \"npm\": [576, 512, [], \"f3d4\", \"M288 288h-32v-64h32v64zm288-128v192H288v32H160v-32H0V160h576zm-416 32H32v128h64v-96h32v96h32V192zm160 0H192v160h64v-32h64V192zm224 0H352v128h64v-96h32v96h32v-96h32v96h32V192z\"],\n    \"ns8\": [640, 512, [], \"f3d5\", \"M187.1 159.9l-34.2 113.7-54.5-113.7H49L0 320h44.9L76 213.5 126.6 320h56.9L232 159.9h-44.9zm452.5-.9c-2.9-18-23.9-28.1-42.1-31.3-44.6-7.8-101.9 16.3-88.5 58.8v.1c-43.8 8.7-74.3 26.8-94.2 48.2-3-9.8-13.6-16.6-34-16.6h-87.6c-9.3 0-12.9-2.3-11.5-7.4 1.6-5.5 1.9-6.8 3.7-12.2 2.1-6.4 7.8-7.1 13.3-7.1h133.5l9.7-31.5c-139.7 0-144.5-.5-160.1 1.2-12.3 1.3-23.5 4.8-30.6 15-6.8 9.9-14.4 35.6-17.6 47.1-5.4 19.4-.6 28.6 32.8 28.6h87.3c7.8 0 8.8 2.7 7.7 6.6-1.1 4.4-2.8 10-4.5 14.6-1.6 4.2-4.7 7.4-13.8 7.4H216.3L204.7 320c139.9 0 145.3-.6 160.9-2.3 6.6-.7 13-2.1 18.5-4.9.2 3.7.5 7.3 1.2 10.8 5.4 30.5 27.4 52.3 56.8 59.5 48.6 11.9 108.7-16.8 135.1-68 18.7-36.2 14.1-76.2-3.4-105.5h.1c29.6-5.9 70.3-22 65.7-50.6zM530.7 263.7c-5.9 29.5-36.6 47.8-61.6 43.9-30.9-4.8-38.5-39.5-14.1-64.8 16.2-16.8 45.2-24 68.5-26.9 6.7 14.1 10.3 32 7.2 47.8zm21.8-83.1c-4.2-6-9.8-18.5-2.5-26.3 6.7-7.2 20.9-10.1 31.8-7.7 15.3 3.4 19.7 15.9 4.9 24.4-10.7 6.1-23.6 8.1-34.2 9.6z\"],\n    \"nutritionix\": [400, 512, [], \"f3d6\", \"M88 8.1S221.4-.1 209 112.5c0 0 19.1-74.9 103-40.6 0 0-17.7 74-88 56 0 0 14.6-54.6 66.1-56.6 0 0-39.9-10.3-82.1 48.8 0 0-19.8-94.5-93.6-99.7 0 0 75.2 19.4 77.6 107.5 0 .1-106.4 7-104-119.8zm312 315.6c0 48.5-9.7 95.3-32 132.3-42.2 30.9-105 48-168 48-62.9 0-125.8-17.1-168-48C9.7 419 0 372.2 0 323.7 0 275.3 17.7 229 40 192c42.2-30.9 97.1-48.6 160-48.6 63 0 117.8 17.6 160 48.6 22.3 37 40 83.3 40 131.7zM120 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM192 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM264 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM336 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm24-39.6c-4.8-22.3-7.4-36.9-16-56-38.8-19.9-90.5-32-144-32S94.8 180.1 56 200c-8.8 19.5-11.2 33.9-16 56 42.2-7.9 98.7-14.8 160-14.8s117.8 6.9 160 14.8z\"],\n    \"odnoklassniki\": [320, 512, [], \"f263\", \"M275.1 334c-27.4 17.4-65.1 24.3-90 26.9l20.9 20.6 76.3 76.3c27.9 28.6-17.5 73.3-45.7 45.7-19.1-19.4-47.1-47.4-76.3-76.6L84 503.4c-28.2 27.5-73.6-17.6-45.4-45.7 19.4-19.4 47.1-47.4 76.3-76.3l20.6-20.6c-24.6-2.6-62.9-9.1-90.6-26.9-32.6-21-46.9-33.3-34.3-59 7.4-14.6 27.7-26.9 54.6-5.7 0 0 36.3 28.9 94.9 28.9s94.9-28.9 94.9-28.9c26.9-21.1 47.1-8.9 54.6 5.7 12.4 25.7-1.9 38-34.5 59.1zM30.3 129.7C30.3 58 88.6 0 160 0s129.7 58 129.7 129.7c0 71.4-58.3 129.4-129.7 129.4s-129.7-58-129.7-129.4zm66 0c0 35.1 28.6 63.7 63.7 63.7s63.7-28.6 63.7-63.7c0-35.4-28.6-64-63.7-64s-63.7 28.6-63.7 64z\"],\n    \"odnoklassniki-square\": [448, 512, [], \"f264\", \"M184.2 177.1c0-22.1 17.9-40 39.8-40s39.8 17.9 39.8 40c0 22-17.9 39.8-39.8 39.8s-39.8-17.9-39.8-39.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-305.1 97.1c0 44.6 36.4 80.9 81.1 80.9s81.1-36.2 81.1-80.9c0-44.8-36.4-81.1-81.1-81.1s-81.1 36.2-81.1 81.1zm174.5 90.7c-4.6-9.1-17.3-16.8-34.1-3.6 0 0-22.7 18-59.3 18s-59.3-18-59.3-18c-16.8-13.2-29.5-5.5-34.1 3.6-7.9 16.1 1.1 23.7 21.4 37 17.3 11.1 41.2 15.2 56.6 16.8l-12.9 12.9c-18.2 18-35.5 35.5-47.7 47.7-17.6 17.6 10.7 45.8 28.4 28.6l47.7-47.9c18.2 18.2 35.7 35.7 47.7 47.9 17.6 17.2 46-10.7 28.6-28.6l-47.7-47.7-13-12.9c15.5-1.6 39.1-5.9 56.2-16.8 20.4-13.3 29.3-21 21.5-37z\"],\n    \"old-republic\": [496, 512, [], \"f510\", \"M235.76 10.23c7.5-.31 15-.28 22.5-.09 3.61.14 7.2.4 10.79.73 4.92.27 9.79 1.03 14.67 1.62 2.93.43 5.83.98 8.75 1.46 7.9 1.33 15.67 3.28 23.39 5.4 12.24 3.47 24.19 7.92 35.76 13.21 26.56 12.24 50.94 29.21 71.63 49.88 20.03 20.09 36.72 43.55 48.89 69.19 1.13 2.59 2.44 5.1 3.47 7.74 2.81 6.43 5.39 12.97 7.58 19.63 4.14 12.33 7.34 24.99 9.42 37.83.57 3.14 1.04 6.3 1.4 9.47.55 3.83.94 7.69 1.18 11.56.83 8.34.84 16.73.77 25.1-.07 4.97-.26 9.94-.75 14.89-.24 3.38-.51 6.76-.98 10.12-.39 2.72-.63 5.46-1.11 8.17-.9 5.15-1.7 10.31-2.87 15.41-4.1 18.5-10.3 36.55-18.51 53.63-15.77 32.83-38.83 62.17-67.12 85.12a246.503 246.503 0 0 1-56.91 34.86c-6.21 2.68-12.46 5.25-18.87 7.41-3.51 1.16-7.01 2.38-10.57 3.39-6.62 1.88-13.29 3.64-20.04 5-4.66.91-9.34 1.73-14.03 2.48-5.25.66-10.5 1.44-15.79 1.74-6.69.66-13.41.84-20.12.81-6.82.03-13.65-.12-20.45-.79-3.29-.23-6.57-.5-9.83-.95-2.72-.39-5.46-.63-8.17-1.11-4.12-.72-8.25-1.37-12.35-2.22-4.25-.94-8.49-1.89-12.69-3.02-8.63-2.17-17.08-5.01-25.41-8.13-10.49-4.12-20.79-8.75-30.64-14.25-2.14-1.15-4.28-2.29-6.35-3.57-11.22-6.58-21.86-14.1-31.92-22.34-34.68-28.41-61.41-66.43-76.35-108.7-3.09-8.74-5.71-17.65-7.8-26.68-1.48-6.16-2.52-12.42-3.58-18.66-.4-2.35-.61-4.73-.95-7.09-.6-3.96-.75-7.96-1.17-11.94-.8-9.47-.71-18.99-.51-28.49.14-3.51.34-7.01.7-10.51.31-3.17.46-6.37.92-9.52.41-2.81.65-5.65 1.16-8.44.7-3.94 1.3-7.9 2.12-11.82 3.43-16.52 8.47-32.73 15.26-48.18 1.15-2.92 2.59-5.72 3.86-8.59 8.05-16.71 17.9-32.56 29.49-47.06 20-25.38 45.1-46.68 73.27-62.47 7.5-4.15 15.16-8.05 23.07-11.37 15.82-6.88 32.41-11.95 49.31-15.38 3.51-.67 7.04-1.24 10.56-1.85 2.62-.47 5.28-.7 7.91-1.08 3.53-.53 7.1-.68 10.65-1.04 2.46-.24 4.91-.36 7.36-.51m8.64 24.41c-9.23.1-18.43.99-27.57 2.23-7.3 1.08-14.53 2.6-21.71 4.3-13.91 3.5-27.48 8.34-40.46 14.42-10.46 4.99-20.59 10.7-30.18 17.22-4.18 2.92-8.4 5.8-12.34 9.03-5.08 3.97-9.98 8.17-14.68 12.59-2.51 2.24-4.81 4.7-7.22 7.06-28.22 28.79-48.44 65.39-57.5 104.69-2.04 8.44-3.54 17.02-4.44 25.65-1.1 8.89-1.44 17.85-1.41 26.8.11 7.14.38 14.28 1.22 21.37.62 7.12 1.87 14.16 3.2 21.18 1.07 4.65 2.03 9.32 3.33 13.91 6.29 23.38 16.5 45.7 30.07 65.75 8.64 12.98 18.78 24.93 29.98 35.77 16.28 15.82 35.05 29.04 55.34 39.22 7.28 3.52 14.66 6.87 22.27 9.63 5.04 1.76 10.06 3.57 15.22 4.98 11.26 3.23 22.77 5.6 34.39 7.06 2.91.29 5.81.61 8.72.9 13.82 1.08 27.74 1 41.54-.43 4.45-.6 8.92-.99 13.35-1.78 3.63-.67 7.28-1.25 10.87-2.1 4.13-.98 8.28-1.91 12.36-3.07 26.5-7.34 51.58-19.71 73.58-36.2 15.78-11.82 29.96-25.76 42.12-41.28 3.26-4.02 6.17-8.31 9.13-12.55 3.39-5.06 6.58-10.25 9.6-15.54 2.4-4.44 4.74-8.91 6.95-13.45 5.69-12.05 10.28-24.62 13.75-37.49 2.59-10.01 4.75-20.16 5.9-30.45 1.77-13.47 1.94-27.1 1.29-40.65-.29-3.89-.67-7.77-1-11.66-2.23-19.08-6.79-37.91-13.82-55.8-5.95-15.13-13.53-29.63-22.61-43.13-12.69-18.8-28.24-35.68-45.97-49.83-25.05-20-54.47-34.55-85.65-42.08-7.78-1.93-15.69-3.34-23.63-4.45-3.91-.59-7.85-.82-11.77-1.24-7.39-.57-14.81-.72-22.22-.58zM139.26 83.53c13.3-8.89 28.08-15.38 43.3-20.18-3.17 1.77-6.44 3.38-9.53 5.29-11.21 6.68-21.52 14.9-30.38 24.49-6.8 7.43-12.76 15.73-17.01 24.89-3.29 6.86-5.64 14.19-6.86 21.71-.93 4.85-1.3 9.81-1.17 14.75.13 13.66 4.44 27.08 11.29 38.82 5.92 10.22 13.63 19.33 22.36 27.26 4.85 4.36 10.24 8.09 14.95 12.6 2.26 2.19 4.49 4.42 6.43 6.91 2.62 3.31 4.89 6.99 5.99 11.1.9 3.02.66 6.2.69 9.31.02 4.1-.04 8.2.03 12.3.14 3.54-.02 7.09.11 10.63.08 2.38.02 4.76.05 7.14.16 5.77.06 11.53.15 17.3.11 2.91.02 5.82.13 8.74.03 1.63.13 3.28-.03 4.91-.91.12-1.82.18-2.73.16-10.99 0-21.88-2.63-31.95-6.93-6-2.7-11.81-5.89-17.09-9.83-5.75-4.19-11.09-8.96-15.79-14.31-6.53-7.24-11.98-15.39-16.62-23.95-1.07-2.03-2.24-4.02-3.18-6.12-1.16-2.64-2.62-5.14-3.67-7.82-4.05-9.68-6.57-19.94-8.08-30.31-.49-4.44-1.09-8.88-1.2-13.35-.7-15.73.84-31.55 4.67-46.82 2.12-8.15 4.77-16.18 8.31-23.83 6.32-14.2 15.34-27.18 26.3-38.19 6.28-6.2 13.13-11.84 20.53-16.67zm175.37-20.12c2.74.74 5.41 1.74 8.09 2.68 6.36 2.33 12.68 4.84 18.71 7.96 13.11 6.44 25.31 14.81 35.82 24.97 10.2 9.95 18.74 21.6 25.14 34.34 1.28 2.75 2.64 5.46 3.81 8.26 6.31 15.1 10 31.26 11.23 47.57.41 4.54.44 9.09.45 13.64.07 11.64-1.49 23.25-4.3 34.53-1.97 7.27-4.35 14.49-7.86 21.18-3.18 6.64-6.68 13.16-10.84 19.24-6.94 10.47-15.6 19.87-25.82 27.22-10.48 7.64-22.64 13.02-35.4 15.38-3.51.69-7.08 1.08-10.66 1.21-1.85.06-3.72.16-5.56-.1-.28-2.15 0-4.31-.01-6.46-.03-3.73.14-7.45.1-11.17.19-7.02.02-14.05.21-21.07.03-2.38-.03-4.76.03-7.14.17-5.07-.04-10.14.14-15.21.1-2.99-.24-6.04.51-8.96.66-2.5 1.78-4.86 3.09-7.08 4.46-7.31 11.06-12.96 17.68-18.26 5.38-4.18 10.47-8.77 15.02-13.84 7.68-8.37 14.17-17.88 18.78-28.27 2.5-5.93 4.52-12.1 5.55-18.46.86-4.37 1.06-8.83 1.01-13.27-.02-7.85-1.4-15.65-3.64-23.17-1.75-5.73-4.27-11.18-7.09-16.45-3.87-6.93-8.65-13.31-13.96-19.2-9.94-10.85-21.75-19.94-34.6-27.1-1.85-1.02-3.84-1.82-5.63-2.97zm-100.8 58.45c.98-1.18 1.99-2.33 3.12-3.38-.61.93-1.27 1.81-1.95 2.68-3.1 3.88-5.54 8.31-7.03 13.06-.87 3.27-1.68 6.6-1.73 10-.07 2.52-.08 5.07.32 7.57 1.13 7.63 4.33 14.85 8.77 21.12 2 2.7 4.25 5.27 6.92 7.33 1.62 1.27 3.53 2.09 5.34 3.05 3.11 1.68 6.32 3.23 9.07 5.48 2.67 2.09 4.55 5.33 4.4 8.79-.01 73.67 0 147.34-.01 221.02 0 1.35-.08 2.7.04 4.04.13 1.48.82 2.83 1.47 4.15.86 1.66 1.78 3.34 3.18 4.62.85.77 1.97 1.4 3.15 1.24 1.5-.2 2.66-1.35 3.45-2.57.96-1.51 1.68-3.16 2.28-4.85.76-2.13.44-4.42.54-6.63.14-4.03-.02-8.06.14-12.09.03-5.89.03-11.77.06-17.66.14-3.62.03-7.24.11-10.86.15-4.03-.02-8.06.14-12.09.03-5.99.03-11.98.07-17.97.14-3.62.02-7.24.11-10.86.14-3.93-.02-7.86.14-11.78.03-5.99.03-11.98.06-17.97.16-3.94-.01-7.88.19-11.82.29 1.44.13 2.92.22 4.38.19 3.61.42 7.23.76 10.84.32 3.44.44 6.89.86 10.32.37 3.1.51 6.22.95 9.31.57 4.09.87 8.21 1.54 12.29 1.46 9.04 2.83 18.11 5.09 26.99 1.13 4.82 2.4 9.61 4 14.3 2.54 7.9 5.72 15.67 10.31 22.62 1.73 2.64 3.87 4.98 6.1 7.21.27.25.55.51.88.71.6.25 1.31-.07 1.7-.57.71-.88 1.17-1.94 1.7-2.93 4.05-7.8 8.18-15.56 12.34-23.31.7-1.31 1.44-2.62 2.56-3.61 1.75-1.57 3.84-2.69 5.98-3.63 2.88-1.22 5.9-2.19 9.03-2.42 6.58-.62 13.11.75 19.56 1.85 3.69.58 7.4 1.17 11.13 1.41 3.74.1 7.48.05 11.21-.28 8.55-.92 16.99-2.96 24.94-6.25 5.3-2.24 10.46-4.83 15.31-7.93 11.46-7.21 21.46-16.57 30.04-27.01 1.17-1.42 2.25-2.9 3.46-4.28-1.2 3.24-2.67 6.37-4.16 9.48-1.25 2.9-2.84 5.61-4.27 8.42-5.16 9.63-11.02 18.91-17.75 27.52-4.03 5.21-8.53 10.05-13.33 14.57-6.64 6.05-14.07 11.37-22.43 14.76-8.21 3.37-17.31 4.63-26.09 3.29-3.56-.58-7.01-1.69-10.41-2.88-2.79-.97-5.39-2.38-8.03-3.69-3.43-1.71-6.64-3.81-9.71-6.08 2.71 3.06 5.69 5.86 8.7 8.61 4.27 3.76 8.74 7.31 13.63 10.23 3.98 2.45 8.29 4.4 12.84 5.51 1.46.37 2.96.46 4.45.6-1.25 1.1-2.63 2.04-3.99 2.98-9.61 6.54-20.01 11.86-30.69 16.43-20.86 8.7-43.17 13.97-65.74 15.34-4.66.24-9.32.36-13.98.36-4.98-.11-9.97-.13-14.92-.65-11.2-.76-22.29-2.73-33.17-5.43-10.35-2.71-20.55-6.12-30.3-10.55-8.71-3.86-17.12-8.42-24.99-13.79-1.83-1.31-3.74-2.53-5.37-4.08 6.6-1.19 13.03-3.39 18.99-6.48 5.74-2.86 10.99-6.66 15.63-11.07 2.24-2.19 4.29-4.59 6.19-7.09-3.43 2.13-6.93 4.15-10.62 5.78-4.41 2.16-9.07 3.77-13.81 5.02-5.73 1.52-11.74 1.73-17.61 1.14-8.13-.95-15.86-4.27-22.51-8.98-4.32-2.94-8.22-6.43-11.96-10.06-9.93-10.16-18.2-21.81-25.66-33.86-3.94-6.27-7.53-12.75-11.12-19.22-1.05-2.04-2.15-4.05-3.18-6.1 2.85 2.92 5.57 5.97 8.43 8.88 8.99 8.97 18.56 17.44 29.16 24.48 7.55 4.9 15.67 9.23 24.56 11.03 3.11.73 6.32.47 9.47.81 2.77.28 5.56.2 8.34.3 5.05.06 10.11.04 15.16-.16 3.65-.16 7.27-.66 10.89-1.09 2.07-.25 4.11-.71 6.14-1.2 3.88-.95 8.11-.96 11.83.61 4.76 1.85 8.44 5.64 11.38 9.71 2.16 3.02 4.06 6.22 5.66 9.58 1.16 2.43 2.46 4.79 3.55 7.26 1 2.24 2.15 4.42 3.42 6.52.67 1.02 1.4 2.15 2.62 2.55 1.06-.75 1.71-1.91 2.28-3.03 2.1-4.16 3.42-8.65 4.89-13.05 2.02-6.59 3.78-13.27 5.19-20.02 2.21-9.25 3.25-18.72 4.54-28.13.56-3.98.83-7.99 1.31-11.97.87-10.64 1.9-21.27 2.24-31.94.08-1.86.24-3.71.25-5.57.01-4.35.25-8.69.22-13.03-.01-2.38-.01-4.76 0-7.13.05-5.07-.2-10.14-.22-15.21-.2-6.61-.71-13.2-1.29-19.78-.73-5.88-1.55-11.78-3.12-17.51-2.05-7.75-5.59-15.03-9.8-21.82-3.16-5.07-6.79-9.88-11.09-14.03-3.88-3.86-8.58-7.08-13.94-8.45-1.5-.41-3.06-.45-4.59-.64.07-2.99.7-5.93 1.26-8.85 1.59-7.71 3.8-15.3 6.76-22.6 1.52-4.03 3.41-7.9 5.39-11.72 3.45-6.56 7.62-12.79 12.46-18.46zm31.27 1.7c.35-.06.71-.12 1.07-.19.19 1.79.09 3.58.1 5.37v38.13c-.01 1.74.13 3.49-.15 5.22-.36-.03-.71-.05-1.06-.05-.95-3.75-1.72-7.55-2.62-11.31-.38-1.53-.58-3.09-1.07-4.59-1.7-.24-3.43-.17-5.15-.2-5.06-.01-10.13 0-15.19-.01-1.66-.01-3.32.09-4.98-.03-.03-.39-.26-.91.16-1.18 1.28-.65 2.72-.88 4.06-1.35 3.43-1.14 6.88-2.16 10.31-3.31 1.39-.48 2.9-.72 4.16-1.54.04-.56.02-1.13-.05-1.68-1.23-.55-2.53-.87-3.81-1.28-3.13-1.03-6.29-1.96-9.41-3.02-1.79-.62-3.67-1-5.41-1.79-.03-.37-.07-.73-.11-1.09 5.09-.19 10.2.06 15.3-.12 3.36-.13 6.73.08 10.09-.07.12-.39.26-.77.37-1.16 1.08-4.94 2.33-9.83 3.39-14.75zm5.97-.2c.36.05.72.12 1.08.2.98 3.85 1.73 7.76 2.71 11.61.36 1.42.56 2.88 1.03 4.27 2.53.18 5.07-.01 7.61.05 5.16.12 10.33.12 15.49.07.76-.01 1.52.03 2.28.08-.04.36-.07.72-.1 1.08-1.82.83-3.78 1.25-5.67 1.89-3.73 1.23-7.48 2.39-11.22 3.57-.57.17-1.12.42-1.67.64-.15.55-.18 1.12-.12 1.69.87.48 1.82.81 2.77 1.09 4.88 1.52 9.73 3.14 14.63 4.6.38.13.78.27 1.13.49.4.27.23.79.15 1.18-1.66.13-3.31.03-4.97.04-5.17.01-10.33-.01-15.5.01-1.61.03-3.22-.02-4.82.21-.52 1.67-.72 3.42-1.17 5.11-.94 3.57-1.52 7.24-2.54 10.78-.36.01-.71.02-1.06.06-.29-1.73-.15-3.48-.15-5.22v-38.13c.02-1.78-.08-3.58.11-5.37zM65.05 168.33c1.12-2.15 2.08-4.4 3.37-6.46-1.82 7.56-2.91 15.27-3.62 23-.8 7.71-.85 15.49-.54 23.23 1.05 19.94 5.54 39.83 14.23 57.88 2.99 5.99 6.35 11.83 10.5 17.11 6.12 7.47 12.53 14.76 19.84 21.09 4.8 4.1 9.99 7.78 15.54 10.8 3.27 1.65 6.51 3.39 9.94 4.68 5.01 2.03 10.19 3.61 15.42 4.94 3.83.96 7.78 1.41 11.52 2.71 5 1.57 9.47 4.61 13.03 8.43 4.93 5.23 8.09 11.87 10.2 18.67.99 2.9 1.59 5.91 2.17 8.92.15.75.22 1.52.16 2.29-6.5 2.78-13.26 5.06-20.26 6.18-4.11.78-8.29.99-12.46 1.08-10.25.24-20.47-1.76-30.12-5.12-3.74-1.42-7.49-2.85-11.03-4.72-8.06-3.84-15.64-8.7-22.46-14.46-2.92-2.55-5.83-5.13-8.4-8.03-9.16-9.83-16.3-21.41-21.79-33.65-2.39-5.55-4.61-11.18-6.37-16.96-1.17-3.94-2.36-7.89-3.26-11.91-.75-2.94-1.22-5.95-1.87-8.92-.46-2.14-.69-4.32-1.03-6.48-.85-5.43-1.28-10.93-1.33-16.43.11-6.18.25-12.37 1.07-18.5.4-2.86.67-5.74 1.15-8.6.98-5.7 2.14-11.37 3.71-16.93 3.09-11.65 7.48-22.95 12.69-33.84zm363.73-6.44c1.1 1.66 1.91 3.48 2.78 5.26 2.1 4.45 4.24 8.9 6.02 13.49 7.61 18.76 12.3 38.79 13.04 59.05.02 1.76.07 3.52.11 5.29.13 9.57-1.27 19.09-3.18 28.45-.73 3.59-1.54 7.17-2.58 10.69-4.04 14.72-10 29-18.41 41.78-8.21 12.57-19.01 23.55-31.84 31.41-5.73 3.59-11.79 6.64-18.05 9.19-5.78 2.19-11.71 4.03-17.8 5.11-6.4 1.05-12.91 1.52-19.4 1.23-7.92-.48-15.78-2.07-23.21-4.85-1.94-.8-3.94-1.46-5.84-2.33-.21-1.51.25-2.99.53-4.46 1.16-5.74 3.03-11.36 5.7-16.58 2.37-4.51 5.52-8.65 9.46-11.9 2.43-2.05 5.24-3.61 8.16-4.83 3.58-1.5 7.47-1.97 11.24-2.83 7.23-1.71 14.37-3.93 21.15-7 10.35-4.65 19.71-11.38 27.65-19.46 1.59-1.61 3.23-3.18 4.74-4.87 3.37-3.76 6.71-7.57 9.85-11.53 7.48-10.07 12.82-21.59 16.71-33.48 1.58-5.3 3.21-10.6 4.21-16.05.63-2.87 1.04-5.78 1.52-8.68.87-6.09 1.59-12.22 1.68-18.38.12-6.65.14-13.32-.53-19.94-.73-7.99-1.87-15.96-3.71-23.78z\"],\n    \"opencart\": [640, 512, [], \"f23d\", \"M423.3 440.7c0 25.3-20.3 45.6-45.6 45.6s-45.8-20.3-45.8-45.6 20.6-45.8 45.8-45.8c25.4 0 45.6 20.5 45.6 45.8zm-253.9-45.8c-25.3 0-45.6 20.6-45.6 45.8s20.3 45.6 45.6 45.6 45.8-20.3 45.8-45.6-20.5-45.8-45.8-45.8zm291.7-270C158.9 124.9 81.9 112.1 0 25.7c34.4 51.7 53.3 148.9 373.1 144.2 333.3-5 130 86.1 70.8 188.9 186.7-166.7 319.4-233.9 17.2-233.9z\"],\n    \"openid\": [448, 512, [], \"f19b\", \"M271.5 432l-68 32C88.5 453.7 0 392.5 0 318.2c0-71.5 82.5-131 191.7-144.3v43c-71.5 12.5-124 53-124 101.3 0 51 58.5 93.3 135.7 103v-340l68-33.2v384zM448 291l-131.3-28.5 36.8-20.7c-19.5-11.5-43.5-20-70-24.8v-43c46.2 5.5 87.7 19.5 120.3 39.3l35-19.8L448 291z\"],\n    \"opera\": [496, 512, [], \"f26a\", \"M313.9 32.7c-170.2 0-252.6 223.8-147.5 355.1 36.5 45.4 88.6 75.6 147.5 75.6 36.3 0 70.3-11.1 99.4-30.4-43.8 39.2-101.9 63-165.3 63-3.9 0-8 0-11.9-.3C104.6 489.6 0 381.1 0 248 0 111 111 0 248 0h.8c63.1.3 120.7 24.1 164.4 63.1-29-19.4-63.1-30.4-99.3-30.4zm101.8 397.7c-40.9 24.7-90.7 23.6-132-5.8 56.2-20.5 97.7-91.6 97.7-176.6 0-84.7-41.2-155.8-97.4-176.6 41.8-29.2 91.2-30.3 132.9-5 105.9 98.7 105.5 265.7-1.2 364z\"],\n    \"optin-monster\": [576, 512, [], \"f23c\", \"M572.6 421.4c5.6-9.5 4.7-15.2-5.4-11.6-3-4.9-7-9.5-11.1-13.8 2.9-9.7-.7-14.2-10.8-9.2-4.6-3.2-10.3-6.5-15.9-9.2 0-15.1-11.6-11.6-17.6-5.7-10.4-1.5-18.7-.3-26.8 5.7.3-6.5.3-13 .3-19.7 12.6 0 40.2-11 45.9-36.2 1.4-6.8 1.6-13.8-.3-21.9-3-13.5-14.3-21.3-25.1-25.7-.8-5.9-7.6-14.3-14.9-15.9s-12.4 4.9-14.1 10.3c-8.5 0-19.2 2.8-21.1 8.4-5.4-.5-11.1-1.4-16.8-1.9 2.7-1.9 5.4-3.5 8.4-4.6 5.4-9.2 14.6-11.4 25.7-11.6V256c19.5-.5 43-5.9 53.8-18.1 12.7-13.8 14.6-37.3 12.4-55.1-2.4-17.3-9.7-37.6-24.6-48.1-8.4-5.9-21.6-.8-22.7 9.5-2.2 19.6 1.2 30-38.6 25.1-10.3-23.8-24.6-44.6-42.7-60C341 49.6 242.9 55.5 166.4 71.7c19.7 4.6 41.1 8.6 59.7 16.5-26.2 2.4-52.7 11.3-76.2 23.2-32.8 17-44 29.9-56.7 42.4 14.9-2.2 28.9-5.1 43.8-3.8-9.7 5.4-18.4 12.2-26.5 20-25.8.9-23.8-5.3-26.2-25.9-1.1-10.5-14.3-15.4-22.7-9.7-28.1 19.9-33.5 79.9-12.2 103.5 10.8 12.2 35.1 17.3 54.9 17.8-.3 1.1-.3 1.9-.3 2.7 10.8.5 19.5 2.7 24.6 11.6 3 1.1 5.7 2.7 8.1 4.6-5.4.5-11.1 1.4-16.5 1.9-3.3-6.6-13.7-8.1-21.1-8.1-1.6-5.7-6.5-12.2-14.1-10.3-6.8 1.9-14.1 10-14.9 15.9-22.5 9.5-30.1 26.8-25.1 47.6 5.3 24.8 33 36.2 45.9 36.2v19.7c-6.6-5-14.3-7.5-26.8-5.7-5.5-5.5-17.3-10.1-17.3 5.7-5.9 2.7-11.4 5.9-15.9 9.2-9.8-4.9-13.6-1.7-11.1 9.2-4.1 4.3-7.8 8.6-11.1 13.8-10.2-3.7-11 2.2-5.4 11.6-1.1 3.5-1.6 7-1.9 10.8-.5 31.6 44.6 64 73.5 65.1 17.3.5 34.6-8.4 43-23.5 113.2 4.9 226.7 4.1 340.2 0 8.1 15.1 25.4 24.3 42.7 23.5 29.2-1.1 74.3-33.5 73.5-65.1.2-3.7-.7-7.2-1.7-10.7zm-73.8-254c1.1-3 2.4-8.4 2.4-14.6 0-5.9 6.8-8.1 14.1-.8 11.1 11.6 14.9 40.5 13.8 51.1-4.1-13.6-13-29-30.3-35.7zm-4.6 6.7c19.5 6.2 28.6 27.6 29.7 48.9-1.1 2.7-3 5.4-4.9 7.6-5.7 5.9-15.4 10-26.2 12.2 4.3-21.3.3-47.3-12.7-63 4.9-.8 10.9-2.4 14.1-5.7zm-24.1 6.8c13.8 11.9 20 39.2 14.1 63.5-4.1.5-8.1.8-11.6.8-1.9-21.9-6.8-44-14.3-64.6 3.7.3 8.1.3 11.8.3zM47.5 203c-1.1-10.5 2.4-39.5 13.8-51.1 7-7.3 14.1-5.1 14.1.8 0 6.2 1.4 11.6 2.4 14.6-17.3 6.8-26.2 22.2-30.3 35.7zm9.7 27.6c-1.9-2.2-3.5-4.9-4.9-7.6 1.4-21.3 10.3-42.7 29.7-48.9 3.2 3.2 9.2 4.9 14.1 5.7-13 15.7-17 41.6-12.7 63-10.8-2.2-20.5-6-26.2-12.2zm47.9 14.6c-4.1 0-8.1-.3-12.7-.8-4.6-18.6-1.9-38.9 5.4-53v.3l12.2-5.1c4.9-1.9 9.7-3.8 14.9-4.9-10.7 19.7-17.4 41.3-19.8 63.5zm184-162.7c41.9 0 76.2 34 76.2 75.9 0 42.2-34.3 76.2-76.2 76.2s-76.2-34-76.2-76.2c0-41.8 34.3-75.9 76.2-75.9zm115.6 174.3c-.3 17.8-7 48.9-23 57-13.2 6.6-6.5-7.5-16.5-58.1 13.3.3 26.6.3 39.5 1.1zm-54-1.6c.8 4.9 3.8 40.3-1.6 41.9-11.6 3.5-40 4.3-51.1-1.1-4.1-3-4.6-35.9-4.3-41.1v.3c18.9-.3 38.1-.3 57 0zM278.3 309c-13 3.5-41.6 4.1-54.6-1.6-6.5-2.7-3.8-42.4-1.9-51.6 19.2-.5 38.4-.5 57.8-.8v.3c1.1 8.3 3.3 51.2-1.3 53.7zm-106.5-51.1c12.2-.8 24.6-1.4 36.8-1.6-2.4 15.4-3 43.5-4.9 52.2-1.1 6.8-4.3 6.8-9.7 4.3-21.9-9.8-27.6-35.2-22.2-54.9zm-35.4 31.3c7.8-1.1 15.7-1.9 23.5-2.7 1.6 6.2 3.8 11.9 7 17.6 10 17 44 35.7 45.1 7 6.2 14.9 40.8 12.2 54.9 10.8 15.7-1.4 23.8-1.4 26.8-14.3 12.4 4.3 30.8 4.1 44 3 11.3-.8 20.8-.5 24.6-8.9 1.1 5.1 1.9 11.6 4.6 16.8 10.8 21.3 37.3 1.4 46.8-31.6 8.6.8 17.6 1.9 26.5 2.7-.4 1.3-3.8 7.3 7.3 11.6-47.6 47-95.7 87.8-163.2 107-63.2-20.8-112.1-59.5-155.9-106.5 9.6-3.4 10.4-8.8 8-12.5zm-21.6 172.5c-3.8 17.8-21.9 29.7-39.7 28.9-19.2-.8-46.5-17-59.2-36.5-2.7-31.1 43.8-61.3 66.2-54.6 14.9 4.3 27.8 30.8 33.5 54 0 3-.3 5.7-.8 8.2zm-8.7-66c-.5-13.5-.5-27-.3-40.5h.3c2.7-1.6 5.7-3.8 7.8-6.5 6.5-1.6 13-5.1 15.1-9.2 3.3-7.1-7-7.5-5.4-12.4 2.7-1.1 5.7-2.2 7.8-3.5 29.2 29.2 58.6 56.5 97.3 77-36.8 11.3-72.4 27.6-105.9 47-1.2-18.6-7.7-35.9-16.7-51.9zm337.6 64.6c-103 3.5-206.2 4.1-309.4 0 0 .3 0 .3-.3.3v-.3h.3c35.1-21.6 72.2-39.2 112.4-50.8 11.6 5.1 23 9.5 34.9 13.2 2.2.8 2.2.8 4.3 0 14.3-4.1 28.4-9.2 42.2-15.4 41.5 11.7 78.8 31.7 115.6 53zm10.5-12.4c-35.9-19.5-73-35.9-111.9-47.6 38.1-20 71.9-47.3 103.5-76.7 2.2 1.4 4.6 2.4 7.6 3.2 0 .8.3 1.9.5 2.4-4.6 2.7-7.8 6.2-5.9 10.3 2.2 3.8 8.6 7.6 15.1 8.9 2.4 2.7 5.1 5.1 8.1 6.8 0 13.8-.3 27.6-.8 41.3l.3-.3c-9.3 15.9-15.5 37-16.5 51.7zm105.9 6.2c-12.7 19.5-40 35.7-59.2 36.5-19.3.9-40.5-13.2-40.5-37 5.7-23.2 18.9-49.7 33.5-54 22.7-6.9 69.2 23.4 66.2 54.5zM372.9 75.2c-3.8-72.1-100.8-79.7-126-23.5 44.6-24.3 90.3-15.7 126 23.5zM74.8 407.1c-15.7 1.6-49.5 25.4-49.5 43.2 0 11.6 15.7 19.5 32.2 14.9 12.2-3.2 31.1-17.6 35.9-27.3 6-11.6-3.7-32.7-18.6-30.8zm215.9-176.2c28.6 0 51.9-21.6 51.9-48.4 0-36.1-40.5-58.1-72.2-44.3 9.5 3 16.5 11.6 16.5 21.6 0 23.3-33.3 32-46.5 11.3-7.3 34.1 19.4 59.8 50.3 59.8zM68 474.1c.5 6.5 12.2 12.7 21.6 9.5 6.8-2.7 14.6-10.5 17.3-16.2 3-7-1.1-20-9.7-18.4-8.9 1.6-29.7 16.7-29.2 25.1zm433.2-67c-14.9-1.9-24.6 19.2-18.9 30.8 4.9 9.7 24.1 24.1 36.2 27.3 16.5 4.6 32.2-3.2 32.2-14.9 0-17.8-33.8-41.6-49.5-43.2zM478.8 449c-8.4-1.6-12.4 11.3-9.5 18.4 2.4 5.7 10.3 13.5 17.3 16.2 9.2 3.2 21.1-3 21.3-9.5.9-8.4-20.2-23.5-29.1-25.1z\"],\n    \"osi\": [512, 512, [], \"f41a\", \"M8 266.44C10.3 130.64 105.4 34 221.8 18.34c138.8-18.6 255.6 75.8 278 201.1 21.3 118.8-44 230-151.6 274-9.3 3.8-14.4 1.7-18-7.7q-26.7-69.45-53.4-139c-3.1-8.1-1-13.2 7-16.8 24.2-11 39.3-29.4 43.3-55.8a71.47 71.47 0 0 0-64.5-82.2c-39-3.4-71.8 23.7-77.5 59.7-5.2 33 11.1 63.7 41.9 77.7 9.6 4.4 11.5 8.6 7.8 18.4q-26.85 69.9-53.7 139.9c-2.6 6.9-8.3 9.3-15.5 6.5-52.6-20.3-101.4-61-130.8-119-24.9-49.2-25.2-87.7-26.8-108.7zm20.9-1.9c.4 6.6.6 14.3 1.3 22.1 6.3 71.9 49.6 143.5 131 183.1 3.2 1.5 4.4.8 5.6-2.3q22.35-58.65 45-117.3c1.3-3.3.6-4.8-2.4-6.7-31.6-19.9-47.3-48.5-45.6-86 1-21.6 9.3-40.5 23.8-56.3 30-32.7 77-39.8 115.5-17.6a91.64 91.64 0 0 1 45.2 90.4c-3.6 30.6-19.3 53.9-45.7 69.8-2.7 1.6-3.5 2.9-2.3 6q22.8 58.8 45.2 117.7c1.2 3.1 2.4 3.8 5.6 2.3 35.5-16.6 65.2-40.3 88.1-72 34.8-48.2 49.1-101.9 42.3-161-13.7-117.5-119.4-214.8-255.5-198-106.1 13-195.3 102.5-197.1 225.8z\"],\n    \"page4\": [496, 512, [], \"f3d7\", \"M248 504C111 504 0 393 0 256S111 8 248 8c20.9 0 41.3 2.6 60.7 7.5L42.3 392H248v112zm0-143.6V146.8L98.6 360.4H248zm96 31.6v92.7c45.7-19.2 84.5-51.7 111.4-92.7H344zm57.4-138.2l-21.2 8.4 21.2 8.3v-16.7zm-20.3 54.5c-6.7 0-8 6.3-8 12.9v7.7h16.2v-10c0-5.9-2.3-10.6-8.2-10.6zM496 256c0 37.3-8.2 72.7-23 104.4H344V27.3C433.3 64.8 496 153.1 496 256zM360.4 143.6h68.2V96h-13.9v32.6h-13.9V99h-13.9v29.6h-12.7V96h-13.9v47.6zm68.1 185.3H402v-11c0-15.4-5.6-25.2-20.9-25.2-15.4 0-20.7 10.6-20.7 25.9v25.3h68.2v-15zm0-103l-68.2 29.7V268l68.2 29.5v-16.6l-14.4-5.7v-26.5l14.4-5.9v-16.9zm-4.8-68.5h-35.6V184H402v-12.2h11c8.6 15.8 1.3 35.3-18.6 35.3-22.5 0-28.3-25.3-15.5-37.7l-11.6-10.6c-16.2 17.5-12.2 63.9 27.1 63.9 34 0 44.7-35.9 29.3-65.3z\"],\n    \"pagelines\": [384, 512, [], \"f18c\", \"M384 312.7c-55.1 136.7-187.1 54-187.1 54-40.5 81.8-107.4 134.4-184.6 134.7-16.1 0-16.6-24.4 0-24.4 64.4-.3 120.5-42.7 157.2-110.1-41.1 15.9-118.6 27.9-161.6-82.2 109-44.9 159.1 11.2 178.3 45.5 9.9-24.4 17-50.9 21.6-79.7 0 0-139.7 21.9-149.5-98.1 119.1-47.9 152.6 76.7 152.6 76.7 1.6-16.7 3.3-52.6 3.3-53.4 0 0-106.3-73.7-38.1-165.2 124.6 43 61.4 162.4 61.4 162.4.5 1.6.5 23.8 0 33.4 0 0 45.2-89 136.4-57.5-4.2 134-141.9 106.4-141.9 106.4-4.4 27.4-11.2 53.4-20 77.5 0 0 83-91.8 172-20z\"],\n    \"palfed\": [576, 512, [], \"f3d8\", \"M384.9 193.9c0-47.4-55.2-44.2-95.4-29.8-1.3 39.4-2.5 80.7-3 119.8.7 2.8 2.6 6.2 15.1 6.2 36.8 0 83.4-42.8 83.3-96.2zm-194.5 72.2c.2 0 6.5-2.7 11.2-2.7 26.6 0 20.7 44.1-14.4 44.1-21.5 0-37.1-18.1-37.1-43 0-42 42.9-95.6 100.7-126.5 1-12.4 3-22 10.5-28.2 11.2-9 26.6-3.5 29.5 11.1 72.2-22.2 135.2 1 135.2 72 0 77.9-79.3 152.6-140.1 138.2-.1 39.4.9 74.4 2.7 100v.2c.2 3.4.6 12.5-5.3 19.1-9.6 10.6-33.4 10-36.4-22.3-4.1-44.4.2-206.1 1.4-242.5-21.5 15-58.5 50.3-58.5 75.9.2 2.5.4 4 .6 4.6zM8 181.1s-.1 37.4 38.4 37.4h30l22.4 217.2s0 44.3 44.7 44.3h288.9s44.7-.4 44.7-44.3l22.4-217.2h30s38.4 1.2 38.4-37.4c0 0 .1-37.4-38.4-37.4h-30.1c-7.3-25.6-30.2-74.3-119.4-74.3h-28V50.3s-2.7-18.4-21.1-18.4h-85.8s-21.1 0-21.1 18.4v19.1h-28.1s-105 4.2-120.5 74.3h-29S8 142.5 8 181.1z\"],\n    \"patreon\": [512, 512, [], \"f3d9\", \"M512 194.8c0 101.3-82.4 183.8-183.8 183.8-101.7 0-184.4-82.4-184.4-183.8 0-101.6 82.7-184.3 184.4-184.3C429.6 10.5 512 93.2 512 194.8zM0 501.5h90v-491H0v491z\"],\n    \"paypal\": [384, 512, [], \"f1ed\", \"M111.4 295.9c-3.5 19.2-17.4 108.7-21.5 134-.3 1.8-1 2.5-3 2.5H12.3c-7.6 0-13.1-6.6-12.1-13.9L58.8 46.6c1.5-9.6 10.1-16.9 20-16.9 152.3 0 165.1-3.7 204 11.4 60.1 23.3 65.6 79.5 44 140.3-21.5 62.6-72.5 89.5-140.1 90.3-43.4.7-69.5-7-75.3 24.2zM357.1 152c-1.8-1.3-2.5-1.8-3 1.3-2 11.4-5.1 22.5-8.8 33.6-39.9 113.8-150.5 103.9-204.5 103.9-6.1 0-10.1 3.3-10.9 9.4-22.6 140.4-27.1 169.7-27.1 169.7-1 7.1 3.5 12.9 10.6 12.9h63.5c8.6 0 15.7-6.3 17.4-14.9.7-5.4-1.1 6.1 14.4-91.3 4.6-22 14.3-19.7 29.3-19.7 71 0 126.4-28.8 142.9-112.3 6.5-34.8 4.6-71.4-23.8-92.6z\"],\n    \"penny-arcade\": [640, 512, [], \"f704\", \"M421.91 164.27c-4.49 19.45-1.4 6.06-15.1 65.29l39.73-10.61c-22.34-49.61-17.29-38.41-24.63-54.68zm-206.09 51.11c-20.19 5.4-11.31 3.03-39.63 10.58l4.46 46.19c28.17-7.59 20.62-5.57 34.82-9.34 42.3-9.79 32.85-56.42.35-47.43zm326.16-26.19l-45.47-99.2c-5.69-12.37-19.46-18.84-32.62-15.33-70.27 18.75-38.72 10.32-135.59 36.23a27.618 27.618 0 0 0-18.89 17.41C144.26 113.27 0 153.75 0 226.67c0 33.5 30.67 67.11 80.9 95.37l1.74 17.88a27.891 27.891 0 0 0-17.77 28.67l4.3 44.48c1.39 14.31 13.43 25.21 27.8 25.2 5.18-.01-3.01 1.78 122.53-31.76 12.57-3.37 21.12-15.02 20.58-28.02 216.59 45.5 401.99-5.98 399.89-84.83.01-28.15-22.19-66.56-97.99-104.47zM255.14 298.3l-21.91 5.88-48.44 12.91 2.46 23.55 20.53-5.51 4.51 44.51-115.31 30.78-4.3-44.52 20.02-5.35-11.11-114.64-20.12 5.39-4.35-44.5c178.15-47.54 170.18-46.42 186.22-46.65 56.66-1.13 64.15 71.84 42.55 104.43a86.7 86.7 0 0 1-50.75 33.72zm199.18 16.62l-3.89-39.49 14.9-3.98-6.61-14.68-57.76 15.42-4.1 17.54 19.2-5.12 4.05 39.54-112.85 30.07-4.46-44.43 20.99-5.59 33.08-126.47-17.15 4.56-4.2-44.48c93.36-24.99 65.01-17.41 135.59-36.24l66.67 145.47 20.79-5.56 4.3 44.48-108.55 28.96z\"],\n    \"periscope\": [448, 512, [], \"f3da\", \"M370 63.6C331.4 22.6 280.5 0 226.6 0 111.9 0 18.5 96.2 18.5 214.4c0 75.1 57.8 159.8 82.7 192.7C137.8 455.5 192.6 512 226.6 512c41.6 0 112.9-94.2 120.9-105 24.6-33.1 82-118.3 82-192.6 0-56.5-21.1-110.1-59.5-150.8zM226.6 493.9c-42.5 0-190-167.3-190-279.4 0-107.4 83.9-196.3 190-196.3 100.8 0 184.7 89 184.7 196.3.1 112.1-147.4 279.4-184.7 279.4zM338 206.8c0 59.1-51.1 109.7-110.8 109.7-100.6 0-150.7-108.2-92.9-181.8v.4c0 24.5 20.1 44.4 44.8 44.4 24.7 0 44.8-19.9 44.8-44.4 0-18.2-11.1-33.8-26.9-40.7 76.6-19.2 141 39.3 141 112.4z\"],\n    \"phabricator\": [496, 512, [], \"f3db\", \"M323 262.1l-.1-13s21.7-19.8 21.1-21.2l-9.5-20c-.6-1.4-29.5-.5-29.5-.5l-9.4-9.3s.2-28.5-1.2-29.1l-20.1-9.2c-1.4-.6-20.7 21-20.7 21l-13.1-.2s-20.5-21.4-21.9-20.8l-20 8.3c-1.4.5.2 28.9.2 28.9l-9.1 9.1s-29.2-.9-29.7.4l-8.1 19.8c-.6 1.4 21 21 21 21l.1 12.9s-21.7 19.8-21.1 21.2l9.5 20c.6 1.4 29.5.5 29.5.5l9.4 9.3s-.2 31.8 1.2 32.3l20.1 8.3c1.4.6 20.7-23.5 20.7-23.5l13.1.2s20.5 23.8 21.8 23.3l20-7.5c1.4-.6-.2-32.1-.2-32.1l9.1-9.1s29.2.9 29.7-.5l8.1-19.8c.7-1.1-20.9-20.7-20.9-20.7zm-44.9-8.7c.7 17.1-12.8 31.6-30.1 32.4-17.3.8-32.1-12.5-32.8-29.6-.7-17.1 12.8-31.6 30.1-32.3 17.3-.8 32.1 12.5 32.8 29.5zm201.2-37.9l-97-97-.1.1c-75.1-73.3-195.4-72.8-269.8 1.6-50.9 51-27.8 27.9-95.7 95.3-22.3 22.3-22.3 58.7 0 81 69.9 69.4 46.4 46 97.4 97l.1-.1c75.1 73.3 195.4 72.9 269.8-1.6 51-50.9 27.9-27.9 95.3-95.3 22.3-22.3 22.3-58.7 0-81zM140.4 363.8c-59.6-59.5-59.6-156 0-215.5 59.5-59.6 156-59.5 215.6 0 59.5 59.5 59.6 156 0 215.6-59.6 59.5-156 59.4-215.6-.1z\"],\n    \"phoenix-framework\": [640, 512, [], \"f3dc\", \"M212.9 344.3c3.8-.1 22.8-1.4 25.6-2.2-2.4-2.6-43.6-1-68-49.6-4.3-8.6-7.5-17.6-6.4-27.6 2.9-25.5 32.9-30 52-18.5 36 21.6 63.3 91.3 113.7 97.5 37 4.5 84.6-17 108.2-45.4-.6-.1-.8-.2-1-.1-.4.1-.8.2-1.1.3-33.3 12.1-94.3 9.7-134.7-14.8-37.6-22.8-53.1-58.7-51.8-74.6 1.8-21.3 22.9-23.2 35.9-19.6 14.4 3.9 24.4 17.6 38.9 27.4 15.6 10.4 32.9 13.7 51.3 10.3 14.9-2.7 34.4-12.3 36.5-14.5-1.1-.1-1.8-.1-2.5-.2-6.2-.6-12.4-.8-18.5-1.7C279.8 194.5 262.1 47.4 138.5 37.9 94.2 34.5 39.1 46 2.2 72.9c-.8.6-1.5 1.2-2.2 1.8.1.2.1.3.2.5.8 0 1.6-.1 2.4-.2 6.3-1 12.5-.8 18.7.3 23.8 4.3 47.7 23.1 55.9 76.5 5.3 34.3-.7 50.8 8 86.1 19 77.1 91 107.6 127.7 106.4zM75.3 64.9c-.9-1-.9-1.2-1.3-2 12.1-2.6 24.2-4.1 36.6-4.8-1.1 14.7-22.2 21.3-35.3 6.8zm196.9 350.5c-42.8 1.2-92-26.7-123.5-61.4-4.6-5-16.8-20.2-18.6-23.4l.4-.4c6.6 4.1 25.7 18.6 54.8 27 24.2 7 48.1 6.3 71.6-3.3 22.7-9.3 41-.5 43.1 2.9-18.5 3.8-20.1 4.4-24 7.9-5.1 4.4-4.6 11.7 7 17.2 26.2 12.4 63-2.8 97.2 25.4 2.4 2 8.1 7.8 10.1 10.7-.1.2-.3.3-.4.5-4.8-1.5-16.4-7.5-40.2-9.3-24.7-2-46.3 5.3-77.5 6.2zm174.8-252c16.4-5.2 41.3-13.4 66.5-3.3 16.1 6.5 26.2 18.7 32.1 34.6 3.5 9.4 5.1 19.7 5.1 28.7-.2 0-.4 0-.6.1-.2-.4-.4-.9-.5-1.3-5-22-29.9-43.8-67.6-29.9-50.2 18.6-130.4 9.7-176.9-48-.7-.9-2.4-1.7-1.3-3.2.1-.2 2.1.6 3 1.3 18.1 13.4 38.3 21.9 60.3 26.2 30.5 6.1 54.6 2.9 79.9-5.2zm102.7 117.5c-32.4.2-33.8 50.1-103.6 64.4-18.2 3.7-38.7 4.6-44.9 4.2v-.4c2.8-1.5 14.7-2.6 29.7-16.6 7.9-7.3 15.3-15.1 22.8-22.9 19.5-20.2 41.4-42.2 81.9-39 23.1 1.8 29.3 8.2 36.1 12.7.3.2.4.5.7.9-.5 0-.7.1-.9 0-7-2.7-14.3-3.3-21.8-3.3zm-12.3-24.1c-.1.2-.1.4-.2.6-28.9-4.4-48-7.9-68.5 4-17 9.9-31.4 20.5-62 24.4-27.1 3.4-45.1 2.4-66.1-8-.3-.2-.6-.4-1-.6 0-.2.1-.3.1-.5 24.9 3.8 36.4 5.1 55.5-5.8 22.3-12.9 40.1-26.6 71.3-31 29.6-4.1 51.3 2.5 70.9 16.9zM268.6 97.3c-.6-.6-1.1-1.2-2.1-2.3 7.6 0 29.7-1.2 53.4 8.4 19.7 8 32.2 21 50.2 32.9 11.1 7.3 23.4 9.3 36.4 8.1 4.3-.4 8.5-1.2 12.8-1.7.4-.1.9 0 1.5.3-.6.4-1.2.9-1.8 1.2-8.1 4-16.7 6.3-25.6 7.1-26.1 2.6-50.3-3.7-73.4-15.4-19.3-9.9-36.4-22.9-51.4-38.6zM640 335.7c-3.5 3.1-22.7 11.6-42.7 5.3-12.3-3.9-19.5-14.9-31.6-24.1-10-7.6-20.9-7.9-28.1-8.4.6-.8.9-1.2 1.2-1.4 14.8-9.2 30.5-12.2 47.3-6.5 12.5 4.2 19.2 13.5 30.4 24.2 10.8 10.4 21 9.9 23.1 10.5.1-.1.2 0 .4.4zm-212.5 137c2.2 1.2 1.6 1.5 1.5 2-18.5-1.4-33.9-7.6-46.8-22.2-21.8-24.7-41.7-27.9-48.6-29.7.5-.2.8-.4 1.1-.4 13.1.1 26.1.7 38.9 3.9 25.3 6.4 35 25.4 41.6 35.3 3.2 4.8 7.3 8.3 12.3 11.1z\"],\n    \"phoenix-squadron\": [512, 512, [], \"f511\", \"M96 63.38C142.49 27.25 201.55 7.31 260.51 8.81c29.58-.38 59.11 5.37 86.91 15.33-24.13-4.63-49-6.34-73.38-2.45C231.17 27 191 48.84 162.21 80.87c5.67-1 10.78-3.67 16-5.86 18.14-7.87 37.49-13.26 57.23-14.83 19.74-2.13 39.64-.43 59.28 1.92-14.42 2.79-29.12 4.57-43 9.59-34.43 11.07-65.27 33.16-86.3 62.63-13.8 19.71-23.63 42.86-24.67 67.13-.35 16.49 5.22 34.81 19.83 44a53.27 53.27 0 0 0 37.52 6.74c15.45-2.46 30.07-8.64 43.6-16.33 11.52-6.82 22.67-14.55 32-24.25 3.79-3.22 2.53-8.45 2.62-12.79-2.12-.34-4.38-1.11-6.3.3a203 203 0 0 1-35.82 15.37c-20 6.17-42.16 8.46-62.1.78 12.79 1.73 26.06.31 37.74-5.44 20.23-9.72 36.81-25.2 54.44-38.77a526.57 526.57 0 0 1 88.9-55.31c25.71-12 52.94-22.78 81.57-24.12-15.63 13.72-32.15 26.52-46.78 41.38-14.51 14-27.46 29.5-40.11 45.18-3.52 4.6-8.95 6.94-13.58 10.16a150.7 150.7 0 0 0-51.89 60.1c-9.33 19.68-14.5 41.85-11.77 63.65 1.94 13.69 8.71 27.59 20.9 34.91 12.9 8 29.05 8.07 43.48 5.1 32.8-7.45 61.43-28.89 81-55.84 20.44-27.52 30.52-62.2 29.16-96.35-.52-7.5-1.57-15-1.66-22.49 8 19.48 14.82 39.71 16.65 60.83 2 14.28.75 28.76-1.62 42.9-1.91 11-5.67 21.51-7.78 32.43a165 165 0 0 0 39.34-81.07 183.64 183.64 0 0 0-14.21-104.64c20.78 32 32.34 69.58 35.71 107.48.49 12.73.49 25.51 0 38.23A243.21 243.21 0 0 1 482 371.34c-26.12 47.34-68 85.63-117.19 108-78.29 36.23-174.68 31.32-248-14.68A248.34 248.34 0 0 1 25.36 366 238.34 238.34 0 0 1 0 273.08v-31.34C3.93 172 40.87 105.82 96 63.38m222 80.33a79.13 79.13 0 0 0 16-4.48c5-1.77 9.24-5.94 10.32-11.22-8.96 4.99-17.98 9.92-26.32 15.7z\"],\n    \"php\": [640, 512, [], \"f457\", \"M320 104.5c171.4 0 303.2 72.2 303.2 151.5S491.3 407.5 320 407.5c-171.4 0-303.2-72.2-303.2-151.5S148.7 104.5 320 104.5m0-16.8C143.3 87.7 0 163 0 256s143.3 168.3 320 168.3S640 349 640 256 496.7 87.7 320 87.7zM218.2 242.5c-7.9 40.5-35.8 36.3-70.1 36.3l13.7-70.6c38 0 63.8-4.1 56.4 34.3zM97.4 350.3h36.7l8.7-44.8c41.1 0 66.6 3 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7h-70.7L97.4 350.3zm185.7-213.6h36.5l-8.7 44.8c31.5 0 60.7-2.3 74.8 10.7 14.8 13.6 7.7 31-8.3 113.1h-37c15.4-79.4 18.3-86 12.7-92-5.4-5.8-17.7-4.6-47.4-4.6l-18.8 96.6h-36.5l32.7-168.6zM505 242.5c-8 41.1-36.7 36.3-70.1 36.3l13.7-70.6c38.2 0 63.8-4.1 56.4 34.3zM384.2 350.3H421l8.7-44.8c43.2 0 67.1 2.5 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7H417l-32.8 168.7z\"],\n    \"pied-piper\": [448, 512, [], \"f2ae\", \"M32 419L0 479.2l.8-328C.8 85.3 54 32 120 32h327.2c-93 28.9-189.9 94.2-253.9 168.6C122.7 282 82.6 338 32 419M448 32S305.2 98.8 261.6 199.1c-23.2 53.6-28.9 118.1-71 158.6-28.9 27.8-69.8 38.2-105.3 56.3-23.2 12-66.4 40.5-84.9 66h328.4c66 0 119.3-53.3 119.3-119.2-.1 0-.1-328.8-.1-328.8z\"],\n    \"pied-piper-alt\": [576, 512, [], \"f1a8\", \"M244 246c-3.2-2-6.3-2.9-10.1-2.9-6.6 0-12.6 3.2-19.3 3.7l1.7 4.9zm135.9 197.9c-19 0-64.1 9.5-79.9 19.8l6.9 45.1c35.7 6.1 70.1 3.6 106-9.8-4.8-10-23.5-55.1-33-55.1zM340.8 177c6.6 2.8 11.5 9.2 22.7 22.1 2-1.4 7.5-5.2 7.5-8.6 0-4.9-11.8-13.2-13.2-23 11.2-5.7 25.2-6 37.6-8.9 68.1-16.4 116.3-52.9 146.8-116.7C548.3 29.3 554 16.1 554.6 2l-2 2.6c-28.4 50-33 63.2-81.3 100-31.9 24.4-69.2 40.2-106.6 54.6l-6.3-.3v-21.8c-19.6 1.6-19.7-14.6-31.6-23-18.7 20.6-31.6 40.8-58.9 51.1-12.7 4.8-19.6 10-25.9 21.8 34.9-16.4 91.2-13.5 98.8-10zM555.5 0l-.6 1.1-.3.9.6-.6zm-59.2 382.1c-33.9-56.9-75.3-118.4-150-115.5l-.3-6c-1.1-13.5 32.8 3.2 35.1-31l-14.4 7.2c-19.8-45.7-8.6-54.3-65.5-54.3-14.7 0-26.7 1.7-41.4 4.6 2.9 18.6 2.2 36.7-10.9 50.3l19.5 5.5c-1.7 3.2-2.9 6.3-2.9 9.8 0 21 42.8 2.9 42.8 33.6 0 18.4-36.8 60.1-54.9 60.1-8 0-53.7-50-53.4-60.1l.3-4.6 52.3-11.5c13-2.6 12.3-22.7-2.9-22.7-3.7 0-43.1 9.2-49.4 10.6-2-5.2-7.5-14.1-13.8-14.1-3.2 0-6.3 3.2-9.5 4-9.2 2.6-31 2.9-21.5 20.1L15.9 298.5c-5.5 1.1-8.9 6.3-8.9 11.8 0 6 5.5 10.9 11.5 10.9 8 0 131.3-28.4 147.4-32.2 2.6 3.2 4.6 6.3 7.8 8.6 20.1 14.4 59.8 85.9 76.4 85.9 24.1 0 58-22.4 71.3-41.9 3.2-4.3 6.9-7.5 12.4-6.9.6 13.8-31.6 34.2-33 43.7-1.4 10.2-1 35.2-.3 41.1 26.7 8.1 52-3.6 77.9-2.9 4.3-21 10.6-41.9 9.8-63.5l-.3-9.5c-1.4-34.2-10.9-38.5-34.8-58.6-1.1-1.1-2.6-2.6-3.7-4 2.2-1.4 1.1-1 4.6-1.7 88.5 0 56.3 183.6 111.5 229.9 33.1-15 72.5-27.9 103.5-47.2-29-25.6-52.6-45.7-72.7-79.9zm-196.2 46.1v27.2l11.8-3.4-2.9-23.8zm-68.7-150.4l24.1 61.2 21-13.8-31.3-50.9zm84.4 154.9l2 12.4c9-1.5 58.4-6.6 58.4-14.1 0-1.4-.6-3.2-.9-4.6-26.8 0-36.9 3.8-59.5 6.3z\"],\n    \"pied-piper-hat\": [640, 512, [], \"f4e5\", \"M640 24.9c-80.8 53.6-89.4 92.5-96.4 104.4-6.7 12.2-11.7 60.3-23.3 83.6-11.7 23.6-54.2 42.2-66.1 50-11.7 7.8-28.3 38.1-41.9 64.2-108.1-4.4-167.4 38.8-259.2 93.6 29.4-9.7 43.3-16.7 43.3-16.7 94.2-36 139.3-68.3 281.1-49.2 1.1 0 1.9.6 2.8.8 3.9 2.2 5.3 6.9 3.1 10.8l-53.9 95.8c-2.5 4.7-7.8 7.2-13.1 6.1-126.8-23.8-226.9 17.3-318.9 18.6C24.1 488 0 453.4 0 451.8c0-1.1.6-1.7 1.7-1.7 0 0 38.3 0 103.1-15.3C178.4 294.5 244 245.4 315.4 245.4c0 0 71.7 0 90.6 61.9 22.8-39.7 28.3-49.2 28.3-49.2 5.3-9.4 35-77.2 86.4-141.4 51.5-64 90.4-79.9 119.3-91.8z\"],\n    \"pied-piper-pp\": [448, 512, [], \"f1a7\", \"M205.3 174.6c0 21.1-14.2 38.1-31.7 38.1-7.1 0-12.8-1.2-17.2-3.7v-68c4.4-2.7 10.1-4.2 17.2-4.2 17.5 0 31.7 16.9 31.7 37.8zm52.6 67c-7.1 0-12.8 1.5-17.2 4.2v68c4.4 2.5 10.1 3.7 17.2 3.7 17.4 0 31.7-16.9 31.7-37.8 0-21.1-14.3-38.1-31.7-38.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM185 255.1c41 0 74.2-35.6 74.2-79.6 0-44-33.2-79.6-74.2-79.6-12 0-24.1 3.2-34.6 8.8h-45.7V311l51.8-10.1v-50.6c8.6 3.1 18.1 4.8 28.5 4.8zm158.4 25.3c0-44-33.2-79.6-73.9-79.6-3.2 0-6.4.2-9.6.7-3.7 12.5-10.1 23.8-19.2 33.4-13.8 15-32.2 23.8-51.8 24.8V416l51.8-10.1v-50.6c8.6 3.2 18.2 4.7 28.7 4.7 40.8 0 74-35.6 74-79.6z\"],\n    \"pinterest\": [496, 512, [], \"f0d2\", \"M496 256c0 137-111 248-248 248-25.6 0-50.2-3.9-73.4-11.1 10.1-16.5 25.2-43.5 30.8-65 3-11.6 15.4-59 15.4-59 8.1 15.4 31.7 28.5 56.8 28.5 74.8 0 128.7-68.8 128.7-154.3 0-81.9-66.9-143.2-152.9-143.2-107 0-163.9 71.8-163.9 150.1 0 36.4 19.4 81.7 50.3 96.1 4.7 2.2 7.2 1.2 8.3-3.3.8-3.4 5-20.3 6.9-28.1.6-2.5.3-4.7-1.7-7.1-10.1-12.5-18.3-35.3-18.3-56.6 0-54.7 41.4-107.6 112-107.6 60.9 0 103.6 41.5 103.6 100.9 0 67.1-33.9 113.6-78 113.6-24.3 0-42.6-20.1-36.7-44.8 7-29.5 20.5-61.3 20.5-82.6 0-19-10.2-34.9-31.4-34.9-24.9 0-44.9 25.7-44.9 60.2 0 22 7.4 36.8 7.4 36.8s-24.5 103.8-29 123.2c-5 21.4-3 51.6-.9 71.2C65.4 450.9 0 361.1 0 256 0 119 111 8 248 8s248 111 248 248z\"],\n    \"pinterest-p\": [384, 512, [], \"f231\", \"M204 6.5C101.4 6.5 0 74.9 0 185.6 0 256 39.6 296 63.6 296c9.9 0 15.6-27.6 15.6-35.4 0-9.3-23.7-29.1-23.7-67.8 0-80.4 61.2-137.4 140.4-137.4 68.1 0 118.5 38.7 118.5 109.8 0 53.1-21.3 152.7-90.3 152.7-24.9 0-46.2-18-46.2-43.8 0-37.8 26.4-74.4 26.4-113.4 0-66.2-93.9-54.2-93.9 25.8 0 16.8 2.1 35.4 9.6 50.7-13.8 59.4-42 147.9-42 209.1 0 18.9 2.7 37.5 4.5 56.4 3.4 3.8 1.7 3.4 6.9 1.5 50.4-69 48.6-82.5 71.4-172.8 12.3 23.4 44.1 36 69.3 36 106.2 0 153.9-103.5 153.9-196.8C384 71.3 298.2 6.5 204 6.5z\"],\n    \"pinterest-square\": [448, 512, [], \"f0d3\", \"M448 80v352c0 26.5-21.5 48-48 48H154.4c9.8-16.4 22.4-40 27.4-59.3 3-11.5 15.3-58.4 15.3-58.4 8 15.3 31.4 28.2 56.3 28.2 74.1 0 127.4-68.1 127.4-152.7 0-81.1-66.2-141.8-151.4-141.8-106 0-162.2 71.1-162.2 148.6 0 36 19.2 80.8 49.8 95.1 4.7 2.2 7.1 1.2 8.2-3.3.8-3.4 5-20.1 6.8-27.8.6-2.5.3-4.6-1.7-7-10.1-12.3-18.3-34.9-18.3-56 0-54.2 41-106.6 110.9-106.6 60.3 0 102.6 41.1 102.6 99.9 0 66.4-33.5 112.4-77.2 112.4-24.1 0-42.1-19.9-36.4-44.4 6.9-29.2 20.3-60.7 20.3-81.8 0-53-75.5-45.7-75.5 25 0 21.7 7.3 36.5 7.3 36.5-31.4 132.8-36.1 134.5-29.6 192.6l2.2.8H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48z\"],\n    \"playstation\": [576, 512, [], \"f3df\", \"M570.9 372.3c-11.3 14.2-38.8 24.3-38.8 24.3L327 470.2v-54.3l150.9-53.8c17.1-6.1 19.8-14.8 5.8-19.4-13.9-4.6-39.1-3.3-56.2 2.9L327 381.1v-56.4c23.2-7.8 47.1-13.6 75.7-16.8 40.9-4.5 90.9.6 130.2 15.5 44.2 14 49.2 34.7 38 48.9zm-224.4-92.5v-139c0-16.3-3-31.3-18.3-35.6-11.7-3.8-19 7.1-19 23.4v347.9l-93.8-29.8V32c39.9 7.4 98 24.9 129.2 35.4C424.1 94.7 451 128.7 451 205.2c0 74.5-46 102.8-104.5 74.6zM43.2 410.2c-45.4-12.8-53-39.5-32.3-54.8 19.1-14.2 51.7-24.9 51.7-24.9l134.5-47.8v54.5l-96.8 34.6c-17.1 6.1-19.7 14.8-5.8 19.4 13.9 4.6 39.1 3.3 56.2-2.9l46.4-16.9v48.8c-51.6 9.3-101.4 7.3-153.9-10z\"],\n    \"product-hunt\": [512, 512, [], \"f288\", \"M326.3 218.8c0 20.5-16.7 37.2-37.2 37.2h-70.3v-74.4h70.3c20.5 0 37.2 16.7 37.2 37.2zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-128.1-37.2c0-47.9-38.9-86.8-86.8-86.8H169.2v248h49.6v-74.4h70.3c47.9 0 86.8-38.9 86.8-86.8z\"],\n    \"pushed\": [432, 512, [], \"f3e1\", \"M407 111.9l-98.5-9 14-33.4c10.4-23.5-10.8-40.4-28.7-37L22.5 76.9c-15.1 2.7-26 18.3-21.4 36.6l105.1 348.3c6.5 21.3 36.7 24.2 47.7 7l35.3-80.8 235.2-231.3c16.4-16.8 4.3-42.9-17.4-44.8zM297.6 53.6c5.1-.7 7.5 2.5 5.2 7.4L286 100.9 108.6 84.6l189-31zM22.7 107.9c-3.1-5.1 1-10 6.1-9.1l248.7 22.7-96.9 230.7L22.7 107.9zM136 456.4c-2.6 4-7.9 3.1-9.4-1.2L43.5 179.7l127.7 197.6c-7 15-35.2 79.1-35.2 79.1zm272.8-314.5L210.1 337.3l89.7-213.7 106.4 9.7c4 1.1 5.7 5.3 2.6 8.6z\"],\n    \"python\": [448, 512, [], \"f3e2\", \"M439.8 200.5c-7.7-30.9-22.3-54.2-53.4-54.2h-40.1v47.4c0 36.8-31.2 67.8-66.8 67.8H172.7c-29.2 0-53.4 25-53.4 54.3v101.8c0 29 25.2 46 53.4 54.3 33.8 9.9 66.3 11.7 106.8 0 26.9-7.8 53.4-23.5 53.4-54.3v-40.7H226.2v-13.6h160.2c31.1 0 42.6-21.7 53.4-54.2 11.2-33.5 10.7-65.7 0-108.6zM286.2 404c11.1 0 20.1 9.1 20.1 20.3 0 11.3-9 20.4-20.1 20.4-11 0-20.1-9.2-20.1-20.4.1-11.3 9.1-20.3 20.1-20.3zM167.8 248.1h106.8c29.7 0 53.4-24.5 53.4-54.3V91.9c0-29-24.4-50.7-53.4-55.6-35.8-5.9-74.7-5.6-106.8.1-45.2 8-53.4 24.7-53.4 55.6v40.7h106.9v13.6h-147c-31.1 0-58.3 18.7-66.8 54.2-9.8 40.7-10.2 66.1 0 108.6 7.6 31.6 25.7 54.2 56.8 54.2H101v-48.8c0-35.3 30.5-66.4 66.8-66.4zm-6.7-142.6c-11.1 0-20.1-9.1-20.1-20.3.1-11.3 9-20.4 20.1-20.4 11 0 20.1 9.2 20.1 20.4s-9 20.3-20.1 20.3z\"],\n    \"qq\": [448, 512, [], \"f1d6\", \"M433.754 420.445c-11.526 1.393-44.86-52.741-44.86-52.741 0 31.345-16.136 72.247-51.051 101.786 16.842 5.192 54.843 19.167 45.803 34.421-7.316 12.343-125.51 7.881-159.632 4.037-34.122 3.844-152.316 8.306-159.632-4.037-9.045-15.25 28.918-29.214 45.783-34.415-34.92-29.539-51.059-70.445-51.059-101.792 0 0-33.334 54.134-44.859 52.741-5.37-.65-12.424-29.644 9.347-99.704 10.261-33.024 21.995-60.478 40.144-105.779C60.683 98.063 108.982.006 224 0c113.737.006 163.156 96.133 160.264 214.963 18.118 45.223 29.912 72.85 40.144 105.778 21.768 70.06 14.716 99.053 9.346 99.704z\"],\n    \"quinscape\": [512, 512, [], \"f459\", \"M313.6 474.6h-1a158.1 158.1 0 0 1 0-316.2c94.9 0 168.2 83.1 157 176.6 4 5.1 8.2 9.6 11.2 15.3 13.4-30.3 20.3-62.4 20.3-97.7C501.1 117.5 391.6 8 256.5 8S12 117.5 12 252.6s109.5 244.6 244.5 244.6a237.36 237.36 0 0 0 70.4-10.1c-5.2-3.5-8.9-8.1-13.3-12.5zm-.1-.1l.4.1zm78.4-168.9a99.2 99.2 0 1 0 99.2 99.2 99.18 99.18 0 0 0-99.2-99.2z\"],\n    \"quora\": [448, 512, [], \"f2c4\", \"M440.5 386.7h-29.3c-1.5 13.5-10.5 30.8-33 30.8-20.5 0-35.3-14.2-49.5-35.8 44.2-34.2 74.7-87.5 74.7-153C403.5 111.2 306.8 32 205 32 105.3 32 7.3 111.7 7.3 228.7c0 134.1 131.3 221.6 249 189C276 451.3 302 480 351.5 480c81.8 0 90.8-75.3 89-93.3zM297 329.2C277.5 300 253.3 277 205.5 277c-30.5 0-54.3 10-69 22.8l12.2 24.3c6.2-3 13-4 19.8-4 35.5 0 53.7 30.8 69.2 61.3-10 3-20.7 4.2-32.7 4.2-75 0-107.5-53-107.5-156.7C97.5 124.5 130 71 205 71c76.2 0 108.7 53.5 108.7 157.7.1 41.8-5.4 75.6-16.7 100.5z\"],\n    \"r-project\": [581, 512, [], \"f4f7\", \"M581 226.6C581 119.1 450.9 32 290.5 32S0 119.1 0 226.6C0 322.4 103.3 402 239.4 418.1V480h99.1v-61.5c24.3-2.7 47.6-7.4 69.4-13.9L448 480h112l-67.4-113.7c54.5-35.4 88.4-84.9 88.4-139.7zm-466.8 14.5c0-73.5 98.9-133 220.8-133s211.9 40.7 211.9 133c0 50.1-26.5 85-70.3 106.4-2.4-1.6-4.7-2.9-6.4-3.7-10.2-5.2-27.8-10.5-27.8-10.5s86.6-6.4 86.6-92.7-90.6-87.9-90.6-87.9h-199V361c-74.1-21.5-125.2-67.1-125.2-119.9zm225.1 38.3v-55.6c57.8 0 87.8-6.8 87.8 27.3 0 36.5-38.2 28.3-87.8 28.3zm-.9 72.5H365c10.8 0 18.9 11.7 24 19.2-16.1 1.9-33 2.8-50.6 2.9v-22.1z\"],\n    \"raspberry-pi\": [407, 512, [], \"f7bb\", \"M372 232.5l-3.7-6.5c.1-46.4-21.4-65.3-46.5-79.7 7.6-2 15.4-3.6 17.6-13.2 13.1-3.3 15.8-9.4 17.1-15.8 3.4-2.3 14.8-8.7 13.6-19.7 6.4-4.4 10-10.1 8.1-18.1 6.9-7.5 8.7-13.7 5.8-19.4 8.3-10.3 4.6-15.6 1.1-20.9 6.2-11.2.7-23.2-16.6-21.2-6.9-10.1-21.9-7.8-24.2-7.8-2.6-3.2-6-6-16.5-4.7-6.8-6.1-14.4-5-22.3-2.1-9.3-7.3-15.5-1.4-22.6.8C271.6.6 269 5.5 263.5 7.6c-12.3-2.6-16.1 3-22 8.9l-6.9-.1c-18.6 10.8-27.8 32.8-31.1 44.1-3.3-11.3-12.5-33.3-31.1-44.1l-6.9.1c-5.9-5.9-9.7-11.5-22-8.9-5.6-2-8.1-7-19.4-3.4-4.6-1.4-8.9-4.4-13.9-4.3-2.6.1-5.5 1-8.7 3.5-7.9-3-15.5-4-22.3 2.1-10.5-1.3-14 1.4-16.5 4.7-2.3 0-17.3-2.3-24.2 7.8C21.2 16 15.8 28 22 39.2c-3.5 5.4-7.2 10.7 1.1 20.9-2.9 5.7-1.1 11.9 5.8 19.4-1.8 8 1.8 13.7 8.1 18.1-1.2 11 10.2 17.4 13.6 19.7 1.3 6.4 4 12.4 17.1 15.8 2.2 9.5 10 11.2 17.6 13.2-25.1 14.4-46.6 33.3-46.5 79.7l-3.7 6.5c-28.8 17.2-54.7 72.7-14.2 117.7 2.6 14.1 7.1 24.2 11 35.4 5.9 45.2 44.5 66.3 54.6 68.8 14.9 11.2 30.8 21.8 52.2 29.2C159 504.2 181 512 203 512h1c22.1 0 44-7.8 64.2-28.4 21.5-7.4 37.3-18 52.2-29.2 10.2-2.5 48.7-23.6 54.6-68.8 3.9-11.2 8.4-21.3 11-35.4 40.6-45.1 14.7-100.5-14-117.7zm-22.2-8c-1.5 18.7-98.9-65.1-82.1-67.9 45.7-7.5 83.6 19.2 82.1 67.9zm-43 93.1c-24.5 15.8-59.8 5.6-78.8-22.8s-14.6-64.2 9.9-80c24.5-15.8 59.8-5.6 78.8 22.8s14.6 64.2-9.9 80zM238.9 29.3c.8 4.2 1.8 6.8 2.9 7.6 5.4-5.8 9.8-11.7 16.8-17.3 0 3.3-1.7 6.8 2.5 9.4 3.7-5 8.8-9.5 15.5-13.3-3.2 5.6-.6 7.3 1.2 9.6 5.1-4.4 10-8.8 19.4-12.3-2.6 3.1-6.2 6.2-2.4 9.8 5.3-3.3 10.6-6.6 23.1-8.9-2.8 3.1-8.7 6.3-5.1 9.4 6.6-2.5 14-4.4 22.1-5.4-3.9 3.2-7.1 6.3-3.9 8.8 7.1-2.2 16.9-5.1 26.4-2.6l-6 6.1c-.7.8 14.1.6 23.9.8-3.6 5-7.2 9.7-9.3 18.2 1 1 5.8.4 10.4 0-4.7 9.9-12.8 12.3-14.7 16.6 2.9 2.2 6.8 1.6 11.2.1-3.4 6.9-10.4 11.7-16 17.3 1.4 1 3.9 1.6 9.7.9-5.2 5.5-11.4 10.5-18.8 15 1.3 1.5 5.8 1.5 10 1.6-6.7 6.5-15.3 9.9-23.4 14.2 4 2.7 6.9 2.1 10 2.1-5.7 4.7-15.4 7.1-24.4 10 1.7 2.7 3.4 3.4 7.1 4.1-9.5 5.3-23.2 2.9-27 5.6.9 2.7 3.6 4.4 6.7 5.8-15.4.9-57.3-.6-65.4-32.3 15.7-17.3 44.4-37.5 93.7-62.6-38.4 12.8-73 30-102 53.5-34.3-15.9-10.8-55.9 5.8-71.8zm-34.4 114.6c24.2-.3 54.1 17.8 54 34.7-.1 15-21 27.1-53.8 26.9-32.1-.4-53.7-15.2-53.6-29.8 0-11.9 26.2-32.5 53.4-31.8zm-123-12.8c3.7-.7 5.4-1.5 7.1-4.1-9-2.8-18.7-5.3-24.4-10 3.1 0 6 .7 10-2.1-8.1-4.3-16.7-7.7-23.4-14.2 4.2-.1 8.7 0 10-1.6-7.4-4.5-13.6-9.5-18.8-15 5.8.7 8.3.1 9.7-.9-5.6-5.6-12.7-10.4-16-17.3 4.3 1.5 8.3 2 11.2-.1-1.9-4.2-10-6.7-14.7-16.6 4.6.4 9.4 1 10.4 0-2.1-8.5-5.8-13.3-9.3-18.2 9.8-.1 24.6 0 23.9-.8l-6-6.1c9.5-2.5 19.3.4 26.4 2.6 3.2-2.5-.1-5.6-3.9-8.8 8.1 1.1 15.4 2.9 22.1 5.4 3.5-3.1-2.3-6.3-5.1-9.4 12.5 2.3 17.8 5.6 23.1 8.9 3.8-3.6.2-6.7-2.4-9.8 9.4 3.4 14.3 7.9 19.4 12.3 1.7-2.3 4.4-4 1.2-9.6 6.7 3.8 11.8 8.3 15.5 13.3 4.1-2.6 2.5-6.2 2.5-9.4 7 5.6 11.4 11.5 16.8 17.3 1.1-.8 2-3.4 2.9-7.6 16.6 15.9 40.1 55.9 6 71.8-29-23.5-63.6-40.7-102-53.5 49.3 25 78 45.3 93.7 62.6-8 31.8-50 33.2-65.4 32.3 3.1-1.4 5.8-3.2 6.7-5.8-4-2.8-17.6-.4-27.2-5.6zm60.1 24.1c16.8 2.8-80.6 86.5-82.1 67.9-1.5-48.7 36.5-75.5 82.1-67.9zM38.2 342c-23.7-18.8-31.3-73.7 12.6-98.3 26.5-7 9 107.8-12.6 98.3zm91 98.2c-13.3 7.9-45.8 4.7-68.8-27.9-15.5-27.4-13.5-55.2-2.6-63.4 16.3-9.8 41.5 3.4 60.9 25.6 16.9 20 24.6 55.3 10.5 65.7zm-26.4-119.7c-24.5-15.8-28.9-51.6-9.9-80s54.3-38.6 78.8-22.8 28.9 51.6 9.9 80c-19.1 28.4-54.4 38.6-78.8 22.8zM205 496c-29.4 1.2-58.2-23.7-57.8-32.3-.4-12.7 35.8-22.6 59.3-22 23.7-1 55.6 7.5 55.7 18.9.5 11-28.8 35.9-57.2 35.4zm58.9-124.9c.2 29.7-26.2 53.8-58.8 54-32.6.2-59.2-23.8-59.4-53.4v-.6c-.2-29.7 26.2-53.8 58.8-54 32.6-.2 59.2 23.8 59.4 53.4v.6zm82.2 42.7c-25.3 34.6-59.6 35.9-72.3 26.3-13.3-12.4-3.2-50.9 15.1-72 20.9-23.3 43.3-38.5 58.9-26.6 10.5 10.3 16.7 49.1-1.7 72.3zm22.9-73.2c-21.5 9.4-39-105.3-12.6-98.3 43.9 24.7 36.3 79.6 12.6 98.3z\"],\n    \"ravelry\": [512, 512, [], \"f2d9\", \"M407.4 61.5C331.6 22.1 257.8 31 182.9 66c-11.3 5.2-15.5 10.6-19.9 19-10.3 19.2-16.2 37.4-19.9 52.7-21.2 25.6-36.4 56.1-43.3 89.9-10.6 18-20.9 41.4-23.1 71.4 0 0-.7 7.6-.5 7.9-35.3-4.6-76.2-27-76.2-27 9.1 14.5 61.3 32.3 76.3 37.9 0 0 1.7 98 64.5 131.2-11.3-17.2-13.3-20.2-13.3-20.2S94.8 369 100.4 324.7c.7 0 1.5.2 2.2.2 23.9 87.4 103.2 151.4 196.9 151.4 6.2 0 12.1-.2 18-.7 14 1.5 27.6.5 40.1-3.9 6.9-2.2 13.8-6.4 20.2-10.8 70.2-39.1 100.9-82 123.1-147.7 5.4-16 8.1-35.5 9.8-52.2 8.7-82.3-30.6-161.6-103.3-199.5zM138.8 163.2s-1.2 12.3-.7 19.7c-3.4 2.5-10.1 8.1-18.2 16.7 5.2-12.8 11.3-25.1 18.9-36.4zm-31.2 121.9c4.4-17.2 13.3-39.1 29.8-55.1 0 0 1.7 48 15.8 90.1l-41.4-6.9c-2.2-9.2-3.5-18.5-4.2-28.1zm7.9 42.8c14.8 3.2 34 7.6 43.1 9.1 27.3 76.8 108.3 124.3 108.3 124.3 1 .5 1.7.7 2.7 1-73.1-11.6-132.7-64.7-154.1-134.4zM386 444.1c-14.5 4.7-36.2 8.4-64.7 3.7 0 0-91.1-23.1-127.5-107.8 38.2.7 52.4-.2 78-3.9 39.4-5.7 79-16.2 115-33 11.8-5.4 11.1-19.4 9.6-29.8-2-12.8-11.1-12.1-21.4-4.7 0 0-82 58.6-189.8 53.7-18.7-32-26.8-110.8-26.8-110.8 41.4-35.2 83.2-59.6 168.4-52.4.2-6.4 3-27.1-20.4-28.1 0 0-93.5-11.1-146 33.5 2.5-16.5 5.9-29.3 11.1-39.4 34.2-30.8 79-49.5 128.3-49.5 106.4 0 193 87.1 193 194.5-.2 76-43.8 142-106.8 174z\"],\n    \"react\": [512, 512, [], \"f41b\", \"M418.2 177.2c-5.4-1.8-10.8-3.5-16.2-5.1.9-3.7 1.7-7.4 2.5-11.1 12.3-59.6 4.2-107.5-23.1-123.3-26.3-15.1-69.2.6-112.6 38.4-4.3 3.7-8.5 7.6-12.5 11.5-2.7-2.6-5.5-5.2-8.3-7.7-45.5-40.4-91.1-57.4-118.4-41.5-26.2 15.2-34 60.3-23 116.7 1.1 5.6 2.3 11.1 3.7 16.7-6.4 1.8-12.7 3.8-18.6 5.9C38.3 196.2 0 225.4 0 255.6c0 31.2 40.8 62.5 96.3 81.5 4.5 1.5 9 3 13.6 4.3-1.5 6-2.8 11.9-4 18-10.5 55.5-2.3 99.5 23.9 114.6 27 15.6 72.4-.4 116.6-39.1 3.5-3.1 7-6.3 10.5-9.7 4.4 4.3 9 8.4 13.6 12.4 42.8 36.8 85.1 51.7 111.2 36.6 27-15.6 35.8-62.9 24.4-120.5-.9-4.4-1.9-8.9-3-13.5 3.2-.9 6.3-1.9 9.4-2.9 57.7-19.1 99.5-50 99.5-81.7 0-30.3-39.4-59.7-93.8-78.4zM282.9 92.3c37.2-32.4 71.9-45.1 87.7-36 16.9 9.7 23.4 48.9 12.8 100.4-.7 3.4-1.4 6.7-2.3 10-22.2-5-44.7-8.6-67.3-10.6-13-18.6-27.2-36.4-42.6-53.1 3.9-3.7 7.7-7.2 11.7-10.7zM167.2 307.5c5.1 8.7 10.3 17.4 15.8 25.9-15.6-1.7-31.1-4.2-46.4-7.5 4.4-14.4 9.9-29.3 16.3-44.5 4.6 8.8 9.3 17.5 14.3 26.1zm-30.3-120.3c14.4-3.2 29.7-5.8 45.6-7.8-5.3 8.3-10.5 16.8-15.4 25.4-4.9 8.5-9.7 17.2-14.2 26-6.3-14.9-11.6-29.5-16-43.6zm27.4 68.9c6.6-13.8 13.8-27.3 21.4-40.6s15.8-26.2 24.4-38.9c15-1.1 30.3-1.7 45.9-1.7s31 .6 45.9 1.7c8.5 12.6 16.6 25.5 24.3 38.7s14.9 26.7 21.7 40.4c-6.7 13.8-13.9 27.4-21.6 40.8-7.6 13.3-15.7 26.2-24.2 39-14.9 1.1-30.4 1.6-46.1 1.6s-30.9-.5-45.6-1.4c-8.7-12.7-16.9-25.7-24.6-39s-14.8-26.8-21.5-40.6zm180.6 51.2c5.1-8.8 9.9-17.7 14.6-26.7 6.4 14.5 12 29.2 16.9 44.3-15.5 3.5-31.2 6.2-47 8 5.4-8.4 10.5-17 15.5-25.6zm14.4-76.5c-4.7-8.8-9.5-17.6-14.5-26.2-4.9-8.5-10-16.9-15.3-25.2 16.1 2 31.5 4.7 45.9 8-4.6 14.8-10 29.2-16.1 43.4zM256.2 118.3c10.5 11.4 20.4 23.4 29.6 35.8-19.8-.9-39.7-.9-59.5 0 9.8-12.9 19.9-24.9 29.9-35.8zM140.2 57c16.8-9.8 54.1 4.2 93.4 39 2.5 2.2 5 4.6 7.6 7-15.5 16.7-29.8 34.5-42.9 53.1-22.6 2-45 5.5-67.2 10.4-1.3-5.1-2.4-10.3-3.5-15.5-9.4-48.4-3.2-84.9 12.6-94zm-24.5 263.6c-4.2-1.2-8.3-2.5-12.4-3.9-21.3-6.7-45.5-17.3-63-31.2-10.1-7-16.9-17.8-18.8-29.9 0-18.3 31.6-41.7 77.2-57.6 5.7-2 11.5-3.8 17.3-5.5 6.8 21.7 15 43 24.5 63.6-9.6 20.9-17.9 42.5-24.8 64.5zm116.6 98c-16.5 15.1-35.6 27.1-56.4 35.3-11.1 5.3-23.9 5.8-35.3 1.3-15.9-9.2-22.5-44.5-13.5-92 1.1-5.6 2.3-11.2 3.7-16.7 22.4 4.8 45 8.1 67.9 9.8 13.2 18.7 27.7 36.6 43.2 53.4-3.2 3.1-6.4 6.1-9.6 8.9zm24.5-24.3c-10.2-11-20.4-23.2-30.3-36.3 9.6.4 19.5.6 29.5.6 10.3 0 20.4-.2 30.4-.7-9.2 12.7-19.1 24.8-29.6 36.4zm130.7 30c-.9 12.2-6.9 23.6-16.5 31.3-15.9 9.2-49.8-2.8-86.4-34.2-4.2-3.6-8.4-7.5-12.7-11.5 15.3-16.9 29.4-34.8 42.2-53.6 22.9-1.9 45.7-5.4 68.2-10.5 1 4.1 1.9 8.2 2.7 12.2 4.9 21.6 5.7 44.1 2.5 66.3zm18.2-107.5c-2.8.9-5.6 1.8-8.5 2.6-7-21.8-15.6-43.1-25.5-63.8 9.6-20.4 17.7-41.4 24.5-62.9 5.2 1.5 10.2 3.1 15 4.7 46.6 16 79.3 39.8 79.3 58 0 19.6-34.9 44.9-84.8 61.4zm-149.7-15c25.3 0 45.8-20.5 45.8-45.8s-20.5-45.8-45.8-45.8c-25.3 0-45.8 20.5-45.8 45.8s20.5 45.8 45.8 45.8z\"],\n    \"reacteurope\": [576, 512, [], \"f75d\", \"M250.6 211.74l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm63.7 0l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.2-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm-91.3 50.5h-3.4c-4.8 0-3.8 4-3.8 12.1 0 4.7-2.3 6.1-5.8 6.1s-5.8-1.4-5.8-6.1v-36.6c0-4.7 2.3-6.1 5.8-6.1s5.8 1.4 5.8 6.1c0 7.2-.7 10.5 3.8 10.5h3.4c4.7-.1 3.8-3.9 3.8-12.3 0-9.9-6.7-14.1-16.8-14.1h-.2c-10.1 0-16.8 4.2-16.8 14.1V276c0 10.4 6.7 14.1 16.8 14.1h.2c10.1 0 16.8-3.8 16.8-14.1 0-9.86 1.1-13.76-3.8-13.76zm-80.7 17.4h-14.7v-19.3H139c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-11.4v-18.3H142c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-21.7c-2.4-.1-3.7 1.3-3.7 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h21.9c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8zm-42-18.5c4.6-2 7.3-6 7.3-12.4v-11.9c0-10.1-6.7-14.1-16.8-14.1H77.4c-2.5 0-3.8 1.3-3.8 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5 0 3.8-1.3 3.8-3.8v-22.9h5.6l7.4 23.5a4.1 4.1 0 0 0 4.3 3.2h3.3c2.8 0 4-1.8 3.2-4.4zm-3.8-14c0 4.8-2.5 6.1-6.1 6.1h-5.8v-20.9h5.8c3.6 0 6.1 1.3 6.1 6.1zM176 226a3.82 3.82 0 0 0-4.2-3.4h-6.9a3.68 3.68 0 0 0-4 3.4l-11 59.2c-.5 2.7.9 4.1 3.4 4.1h3a3.74 3.74 0 0 0 4.1-3.5l1.8-11.3h12.2l1.8 11.3a3.74 3.74 0 0 0 4.1 3.5h3.5c2.6 0 3.9-1.4 3.4-4.1zm-12.3 39.3l4.7-29.7 4.7 29.7zm89.3 20.2v-53.2h7.5c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-25.8c-2.5 0-3.8 1.3-3.8 3.8v2.1c0 2.5 1.3 3.8 3.8 3.8h7.3v53.2c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5.04 3.8-1.3 3.8-3.76zm248-.8h-19.4V258h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9H501a1.81 1.81 0 0 0 2-1.9v-.8a1.84 1.84 0 0 0-2-1.96zm-93.1-62.9h-.8c-10.1 0-15.3 4.7-15.3 14.1V276c0 9.3 5.2 14.1 15.3 14.1h.8c10.1 0 15.3-4.8 15.3-14.1v-40.1c0-9.36-5.2-14.06-15.3-14.06zm10.2 52.4c-.1 8-3 11.1-10.5 11.1s-10.5-3.1-10.5-11.1v-36.6c0-7.9 3-11.1 10.5-11.1s10.5 3.2 10.5 11.1zm-46.5-14.5c6.1-1.6 9.2-6.1 9.2-13.3v-9.7c0-9.4-5.2-14.1-15.3-14.1h-13.7a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.9h11.6l10.4 27.2a2.32 2.32 0 0 0 2.3 1.5h1.5c1.4 0 2-1 1.5-2.3zm-6.4-3.9H355v-28.5h10.2c7.5 0 10.5 3.1 10.5 11.1v6.4c0 7.84-3 11.04-10.5 11.04zm85.9-33.1h-13.7a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.1h10.6c10.1 0 15.3-4.8 15.3-14.1v-10.5c0-9.4-5.2-14.1-15.3-14.1zm10.2 22.8c0 7.9-3 11.1-10.5 11.1h-10.2v-29.2h10.2c7.5-.1 10.5 3.1 10.5 11zM259.5 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm227.6-136.1a364.42 364.42 0 0 0-35.6-11.3c19.6-78 11.6-134.7-22.3-153.9C394.7-12.66 343.3 11 291 61.94q5.1 4.95 10.2 10.2c82.5-80 119.6-53.5 120.9-52.8 22.4 12.7 36 55.8 15.5 137.8a587.83 587.83 0 0 0-84.6-13C281.1 43.64 212.4 2 170.8 2 140 2 127 23 123.2 29.74c-18.1 32-13.3 84.2.1 133.8-70.5 20.3-120.7 54.1-120.3 95 .5 59.6 103.2 87.8 122.1 92.8-20.5 81.9-10.1 135.6 22.3 153.9 28 15.8 75.1 6 138.2-55.2q-5.1-4.95-10.2-10.2c-82.5 80-119.7 53.5-120.9 52.8-22.3-12.6-36-55.6-15.5-137.9 12.4 2.9 41.8 9.5 84.6 13 71.9 100.4 140.6 142 182.1 142 30.8 0 43.8-21 47.6-27.7 18-31.9 13.3-84.1-.1-133.8 152.3-43.8 156.2-130.2 33.9-176.3zM135.9 36.84c2.9-5.1 11.9-20.3 34.9-20.3 36.8 0 98.8 39.6 163.3 126.2a714 714 0 0 0-93.9.9 547.76 547.76 0 0 1 42.2-52.4Q277.3 86 272.2 81a598.25 598.25 0 0 0-50.7 64.2 569.69 569.69 0 0 0-84.4 14.6c-.2-1.4-24.3-82.2-1.2-123zm304.8 438.3c-2.9 5.1-11.8 20.3-34.9 20.3-36.7 0-98.7-39.4-163.3-126.2a695.38 695.38 0 0 0 93.9-.9 547.76 547.76 0 0 1-42.2 52.4q5.1 5.25 10.2 10.2a588.47 588.47 0 0 0 50.7-64.2c47.3-4.7 80.3-13.5 84.4-14.6 22.7 84.4 4.5 117 1.2 123zm9.1-138.6c-3.6-11.9-7.7-24.1-12.4-36.4a12.67 12.67 0 0 1-10.7-5.7l-.1.1a19.61 19.61 0 0 1-5.4 3.6c5.7 14.3 10.6 28.4 14.7 42.2a535.3 535.3 0 0 1-72 13c3.5-5.3 17.2-26.2 32.2-54.2a24.6 24.6 0 0 1-6-3.2c-1.1 1.2-3.6 4.2-10.9 4.2-6.2 11.2-17.4 30.9-33.9 55.2a711.91 711.91 0 0 1-112.4 1c-7.9-11.2-21.5-31.1-36.8-57.8a21 21 0 0 1-3-1.5c-1.9 1.6-3.9 3.2-12.6 3.2 6.3 11.2 17.5 30.7 33.8 54.6a548.81 548.81 0 0 1-72.2-11.7q5.85-21 14.1-42.9c-3.2 0-5.4.2-8.4-1a17.58 17.58 0 0 1-6.9 1c-4.9 13.4-9.1 26.5-12.7 39.4C-31.7 297-12.1 216 126.7 175.64c3.6 11.9 7.7 24.1 12.4 36.4 10.4 0 12.9 3.4 14.4 5.3a12 12 0 0 1 2.3-2.2c-5.8-14.7-10.9-29.2-15.2-43.3 7-1.8 32.4-8.4 72-13-15.9 24.3-26.7 43.9-32.8 55.3a14.22 14.22 0 0 1 6.4 8 23.42 23.42 0 0 1 10.2-8.4c6.5-11.7 17.9-31.9 34.8-56.9a711.72 711.72 0 0 1 112.4-1c31.5 44.6 28.9 48.1 42.5 64.5a21.42 21.42 0 0 1 10.4-7.4c-6.4-11.4-17.6-31-34.3-55.5 40.4 4.1 65 10 72.2 11.7-4 14.4-8.9 29.2-14.6 44.2a20.74 20.74 0 0 1 6.8 4.3l.1.1a12.72 12.72 0 0 1 8.9-5.6c4.9-13.4 9.2-26.6 12.8-39.5a359.71 359.71 0 0 1 34.5 11c106.1 39.9 74 87.9 72.6 90.4-19.8 35.1-80.1 55.2-105.7 62.5zm-114.4-114h-1.2a1.74 1.74 0 0 0-1.9 1.9v49.8c0 7.9-2.6 11.1-10.1 11.1s-10.1-3.1-10.1-11.1v-49.8a1.69 1.69 0 0 0-1.9-1.9H309a1.81 1.81 0 0 0-2 1.9v51.5c0 9.6 5 14.1 15.1 14.1h.4c10.1 0 15.1-4.6 15.1-14.1v-51.5a2 2 0 0 0-2.2-1.9zM321.7 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm-31.1 7.4l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm5.1-30.8h-19.4v-26.7h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h22.5a1.77 1.77 0 0 0 2-1.9v-.8a1.83 1.83 0 0 0-2-2.06zm-7.4-99.4L286 192l-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1z\"],\n    \"readme\": [576, 512, [], \"f4d5\", \"M528.3 46.5H388.5c-48.1 0-89.9 33.3-100.4 80.3-10.6-47-52.3-80.3-100.4-80.3H48c-26.5 0-48 21.5-48 48v245.8c0 26.5 21.5 48 48 48h89.7c102.2 0 132.7 24.4 147.3 75 .7 2.8 5.2 2.8 6 0 14.7-50.6 45.2-75 147.3-75H528c26.5 0 48-21.5 48-48V94.6c0-26.4-21.3-47.9-47.7-48.1zM242 311.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5V289c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V251zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm259.3 121.7c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5V228c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.8c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V190z\"],\n    \"rebel\": [512, 512, [], \"f1d0\", \"M256.5 504C117.2 504 9 387.8 13.2 249.9 16 170.7 56.4 97.7 129.7 49.5c.3 0 1.9-.6 1.1.8-5.8 5.5-111.3 129.8-14.1 226.4 49.8 49.5 90 2.5 90 2.5 38.5-50.1-.6-125.9-.6-125.9-10-24.9-45.7-40.1-45.7-40.1l28.8-31.8c24.4 10.5 43.2 38.7 43.2 38.7.8-29.6-21.9-61.4-21.9-61.4L255.1 8l44.3 50.1c-20.5 28.8-21.9 62.6-21.9 62.6 13.8-23 43.5-39.3 43.5-39.3l28.5 31.8c-27.4 8.9-45.4 39.9-45.4 39.9-15.8 28.5-27.1 89.4.6 127.3 32.4 44.6 87.7-2.8 87.7-2.8 102.7-91.9-10.5-225-10.5-225-6.1-5.5.8-2.8.8-2.8 50.1 36.5 114.6 84.4 116.2 204.8C500.9 400.2 399 504 256.5 504z\"],\n    \"red-river\": [448, 512, [], \"f3e3\", \"M353.2 32H94.8C42.4 32 0 74.4 0 126.8v258.4C0 437.6 42.4 480 94.8 480h258.4c52.4 0 94.8-42.4 94.8-94.8V126.8c0-52.4-42.4-94.8-94.8-94.8zM144.9 200.9v56.3c0 27-21.9 48.9-48.9 48.9V151.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9h-56.3c-12.3-.6-24.6 11.6-24 24zm176.3 72h-56.3c-12.3-.6-24.6 11.6-24 24v56.3c0 27-21.9 48.9-48.9 48.9V247.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9z\"],\n    \"reddit\": [512, 512, [], \"f1a1\", \"M201.5 305.5c-13.8 0-24.9-11.1-24.9-24.6 0-13.8 11.1-24.9 24.9-24.9 13.6 0 24.6 11.1 24.6 24.9 0 13.6-11.1 24.6-24.6 24.6zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-132.3-41.2c-9.4 0-17.7 3.9-23.8 10-22.4-15.5-52.6-25.5-86.1-26.6l17.4-78.3 55.4 12.5c0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.3 24.9-24.9s-11.1-24.9-24.9-24.9c-9.7 0-18 5.8-22.1 13.8l-61.2-13.6c-3-.8-6.1 1.4-6.9 4.4l-19.1 86.4c-33.2 1.4-63.1 11.3-85.5 26.8-6.1-6.4-14.7-10.2-24.1-10.2-34.9 0-46.3 46.9-14.4 62.8-1.1 5-1.7 10.2-1.7 15.5 0 52.6 59.2 95.2 132 95.2 73.1 0 132.3-42.6 132.3-95.2 0-5.3-.6-10.8-1.9-15.8 31.3-16 19.8-62.5-14.9-62.5zM302.8 331c-18.2 18.2-76.1 17.9-93.6 0-2.2-2.2-6.1-2.2-8.3 0-2.5 2.5-2.5 6.4 0 8.6 22.8 22.8 87.3 22.8 110.2 0 2.5-2.2 2.5-6.1 0-8.6-2.2-2.2-6.1-2.2-8.3 0zm7.7-75c-13.6 0-24.6 11.1-24.6 24.9 0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.1 24.9-24.6 0-13.8-11-24.9-24.9-24.9z\"],\n    \"reddit-alien\": [512, 512, [], \"f281\", \"M440.3 203.5c-15 0-28.2 6.2-37.9 15.9-35.7-24.7-83.8-40.6-137.1-42.3L293 52.3l88.2 19.8c0 21.6 17.6 39.2 39.2 39.2 22 0 39.7-18.1 39.7-39.7s-17.6-39.7-39.7-39.7c-15.4 0-28.7 9.3-35.3 22l-97.4-21.6c-4.9-1.3-9.7 2.2-11 7.1L246.3 177c-52.9 2.2-100.5 18.1-136.3 42.8-9.7-10.1-23.4-16.3-38.4-16.3-55.6 0-73.8 74.6-22.9 100.1-1.8 7.9-2.6 16.3-2.6 24.7 0 83.8 94.4 151.7 210.3 151.7 116.4 0 210.8-67.9 210.8-151.7 0-8.4-.9-17.2-3.1-25.1 49.9-25.6 31.5-99.7-23.8-99.7zM129.4 308.9c0-22 17.6-39.7 39.7-39.7 21.6 0 39.2 17.6 39.2 39.7 0 21.6-17.6 39.2-39.2 39.2-22 .1-39.7-17.6-39.7-39.2zm214.3 93.5c-36.4 36.4-139.1 36.4-175.5 0-4-3.5-4-9.7 0-13.7 3.5-3.5 9.7-3.5 13.2 0 27.8 28.5 120 29 149 0 3.5-3.5 9.7-3.5 13.2 0 4.1 4 4.1 10.2.1 13.7zm-.8-54.2c-21.6 0-39.2-17.6-39.2-39.2 0-22 17.6-39.7 39.2-39.7 22 0 39.7 17.6 39.7 39.7-.1 21.5-17.7 39.2-39.7 39.2z\"],\n    \"reddit-square\": [448, 512, [], \"f1a2\", \"M283.2 345.5c2.7 2.7 2.7 6.8 0 9.2-24.5 24.5-93.8 24.6-118.4 0-2.7-2.4-2.7-6.5 0-9.2 2.4-2.4 6.5-2.4 8.9 0 18.7 19.2 81 19.6 100.5 0 2.4-2.3 6.6-2.3 9 0zm-91.3-53.8c0-14.9-11.9-26.8-26.5-26.8-14.9 0-26.8 11.9-26.8 26.8 0 14.6 11.9 26.5 26.8 26.5 14.6 0 26.5-11.9 26.5-26.5zm90.7-26.8c-14.6 0-26.5 11.9-26.5 26.8 0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-11.9 26.8-26.5 0-14.9-11.9-26.8-26.8-26.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-99.7 140.6c-10.1 0-19 4.2-25.6 10.7-24.1-16.7-56.5-27.4-92.5-28.6l18.7-84.2 59.5 13.4c0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-12.2 26.8-26.8 0-14.6-11.9-26.8-26.8-26.8-10.4 0-19.3 6.2-23.8 14.9l-65.7-14.6c-3.3-.9-6.5 1.5-7.4 4.8l-20.5 92.8c-35.7 1.5-67.8 12.2-91.9 28.9-6.5-6.8-15.8-11-25.9-11-37.5 0-49.8 50.4-15.5 67.5-1.2 5.4-1.8 11-1.8 16.7 0 56.5 63.7 102.3 141.9 102.3 78.5 0 142.2-45.8 142.2-102.3 0-5.7-.6-11.6-2.1-17 33.6-17.2 21.2-67.2-16.1-67.2z\"],\n    \"redhat\": [512, 512, [], \"f7bc\", \"M341.52 285.56c33.65 0 82.34-6.94 82.34-47 .22-6.74.86-1.82-20.88-96.24-4.62-19.15-8.68-27.84-42.31-44.65-26.09-13.34-82.92-35.37-99.73-35.37-15.66 0-20.2 20.17-38.87 20.17-18 0-31.31-15.06-48.12-15.06-16.14 0-26.66 11-34.78 33.62-27.5 77.55-26.28 74.27-26.12 78.27 0 24.8 97.64 106.11 228.47 106.11M429 254.84c4.65 22 4.65 24.35 4.65 27.25 0 37.66-42.33 58.56-98 58.56-125.74.08-235.91-73.65-235.91-122.33a49.55 49.55 0 0 1 4.06-19.72C58.56 200.86 0 208.93 0 260.63c0 84.67 200.63 189 359.49 189 121.79 0 152.51-55.08 152.51-98.58 0-34.21-29.59-73.05-82.93-96.24\"],\n    \"renren\": [512, 512, [], \"f18b\", \"M214 169.1c0 110.4-61 205.4-147.6 247.4C30 373.2 8 317.7 8 256.6 8 133.9 97.1 32.2 214 12.5v156.6zM255 504c-42.9 0-83.3-11-118.5-30.4C193.7 437.5 239.9 382.9 255 319c15.5 63.9 61.7 118.5 118.8 154.7C338.7 493 298.3 504 255 504zm190.6-87.5C359 374.5 298 279.6 298 169.1V12.5c116.9 19.7 206 121.4 206 244.1 0 61.1-22 116.6-58.4 159.9z\"],\n    \"replyd\": [448, 512, [], \"f3e6\", \"M320 480H128C57.6 480 0 422.4 0 352V160C0 89.6 57.6 32 128 32h192c70.4 0 128 57.6 128 128v192c0 70.4-57.6 128-128 128zM193.4 273.2c-6.1-2-11.6-3.1-16.4-3.1-7.2 0-13.5 1.9-18.9 5.6-5.4 3.7-9.6 9-12.8 15.8h-1.1l-4.2-18.3h-28v138.9h36.1v-89.7c1.5-5.4 4.4-9.8 8.7-13.2 4.3-3.4 9.8-5.1 16.2-5.1 4.6 0 9.8 1 15.6 3.1l4.8-34zm115.2 103.4c-3.2 2.4-7.7 4.8-13.7 7.1-6 2.3-12.8 3.5-20.4 3.5-12.2 0-21.1-3-26.5-8.9-5.5-5.9-8.5-14.7-9-26.4h83.3c.9-4.8 1.6-9.4 2.1-13.9.5-4.4.7-8.6.7-12.5 0-10.7-1.6-19.7-4.7-26.9-3.2-7.2-7.3-13-12.5-17.2-5.2-4.3-11.1-7.3-17.8-9.2-6.7-1.8-13.5-2.8-20.6-2.8-21.1 0-37.5 6.1-49.2 18.3s-17.5 30.5-17.5 55c0 22.8 5.2 40.7 15.6 53.7 10.4 13.1 26.8 19.6 49.2 19.6 10.7 0 20.9-1.5 30.4-4.6 9.5-3.1 17.1-6.8 22.6-11.2l-12-23.6zm-21.8-70.3c3.8 5.4 5.3 13.1 4.6 23.1h-51.7c.9-9.4 3.7-17 8.2-22.6 4.5-5.6 11.5-8.5 21-8.5 8.2-.1 14.1 2.6 17.9 8zm79.9 2.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4s2 11.7 6.1 15.6zm0 100.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4 0 6.6 2 11.7 6.1 15.6z\"],\n    \"researchgate\": [448, 512, [], \"f4f8\", \"M0 32v448h448V32H0zm262.2 334.4c-6.6 3-33.2 6-50-14.2-9.2-10.6-25.3-33.3-42.2-63.6-8.9 0-14.7 0-21.4-.6v46.4c0 23.5 6 21.2 25.8 23.9v8.1c-6.9-.3-23.1-.8-35.6-.8-13.1 0-26.1.6-33.6.8v-8.1c15.5-2.9 22-1.3 22-23.9V225c0-22.6-6.4-21-22-23.9V193c25.8 1 53.1-.6 70.9-.6 31.7 0 55.9 14.4 55.9 45.6 0 21.1-16.7 42.2-39.2 47.5 13.6 24.2 30 45.6 42.2 58.9 7.2 7.8 17.2 14.7 27.2 14.7v7.3zm22.9-135c-23.3 0-32.2-15.7-32.2-32.2V167c0-12.2 8.8-30.4 34-30.4s30.4 17.9 30.4 17.9l-10.7 7.2s-5.5-12.5-19.7-12.5c-7.9 0-19.7 7.3-19.7 19.7v26.8c0 13.4 6.6 23.3 17.9 23.3 14.1 0 21.5-10.9 21.5-26.8h-17.9v-10.7h30.4c0 20.5 4.7 49.9-34 49.9zm-116.5 44.7c-9.4 0-13.6-.3-20-.8v-69.7c6.4-.6 15-.6 22.5-.6 23.3 0 37.2 12.2 37.2 34.5 0 21.9-15 36.6-39.7 36.6z\"],\n    \"resolving\": [496, 512, [], \"f3e7\", \"M281.2 278.2c46-13.3 49.6-23.5 44-43.4L314 195.5c-6.1-20.9-18.4-28.1-71.1-12.8L54.7 236.8l28.6 98.6 197.9-57.2zM248.5 8C131.4 8 33.2 88.7 7.2 197.5l221.9-63.9c34.8-10.2 54.2-11.7 79.3-8.2 36.3 6.1 52.7 25 61.4 55.2l10.7 37.8c8.2 28.1 1 50.6-23.5 73.6-19.4 17.4-31.2 24.5-61.4 33.2L203 351.8l220.4 27.1 9.7 34.2-48.1 13.3-286.8-37.3 23 80.2c36.8 22 80.3 34.7 126.3 34.7 137 0 248.5-111.4 248.5-248.3C497 119.4 385.5 8 248.5 8zM38.3 388.6L0 256.8c0 48.5 14.3 93.4 38.3 131.8z\"],\n    \"rev\": [448, 512, [], \"f5b2\", \"M289.67 274.89a65.57 65.57 0 1 1-65.56-65.56 65.64 65.64 0 0 1 65.56 65.56zm139.55-5.05h-.13a204.69 204.69 0 0 0-74.32-153l-45.38 26.2a157.07 157.07 0 0 1 71.81 131.84C381.2 361.5 310.73 432 224.11 432S67 361.5 67 274.88c0-81.88 63-149.27 143-156.43v39.12l108.77-62.79L210 32v38.32c-106.7 7.25-191 96-191 204.57 0 111.59 89.12 202.29 200.06 205v.11h210.16V269.84z\"],\n    \"rocketchat\": [576, 512, [], \"f3e8\", \"M486.41 107.57c-76.93-50.83-179.18-62.4-264.12-47.07C127.26-31.16 20.77 11 0 23.12c0 0 73.08 62.1 61.21 116.49-86.52 88.2-45.39 186.4 0 232.77C73.08 426.77 0 488.87 0 488.87c20.57 12.16 126.77 54.19 222.29-37 84.75 15.23 187 3.76 264.12-47.16 119.26-76.14 119.65-220.61 0-297.15zM294.18 404.22a339.53 339.53 0 0 1-88.11-11.37l-19.77 19.09a179.74 179.74 0 0 1-36.59 27.39A143.14 143.14 0 0 1 98 454.06c1-1.78 1.88-3.56 2.77-5.24q29.67-55 16-98.69c-32.53-25.61-52-58.34-52-94.13 0-82 102.74-148.43 229.41-148.43S523.59 174 523.59 256 420.85 404.22 294.18 404.22zM184.12 291.3a34.32 34.32 0 0 1-34.8-33.72c-.7-45.39 67.83-46.38 68.52-1.09v.51a34 34 0 0 1-33.72 34.32zm73.77-33.72c-.79-45.39 67.74-46.48 68.53-1.19v.61c.39 45.08-67.74 45.57-68.53.58zm143.38 33.72a34.33 34.33 0 0 1-34.81-33.72c-.69-45.39 67.84-46.38 68.53-1.09v.51a33.89 33.89 0 0 1-33.72 34.32z\"],\n    \"rockrms\": [496, 512, [], \"f3e9\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm157.4 419.5h-90l-112-131.3c-17.9-20.4-3.9-56.1 26.6-56.1h75.3l-84.6-99.3-84.3 98.9h-90L193.5 67.2c14.4-18.4 41.3-17.3 54.5 0l157.7 185.1c19 22.8 2 57.2-27.6 56.1-.6 0-74.2.2-74.2.2l101.5 118.9z\"],\n    \"safari\": [512, 512, [], \"f267\", \"M236.9 256.8c0-9.1 6.6-17.7 16.3-17.7 8.9 0 17.4 6.4 17.4 16.1 0 9.1-6.4 17.7-16.1 17.7-9 0-17.6-6.7-17.6-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-26.6 0c0-122.3-99.1-221.4-221.4-221.4S34.6 133.7 34.6 256 133.7 477.4 256 477.4 477.4 378.3 477.4 256zm-72.5 96.6c0 3.6 13 10.2 16.3 12.2-27.4 41.5-69.8 71.4-117.9 83.3l-4.4-18.5c-.3-2.5-1.9-2.8-4.2-2.8-1.9 0-3 2.8-2.8 4.2l4.4 18.8c-13.3 2.8-26.8 4.2-40.4 4.2-36.3 0-72-10.2-103-29.1 1.7-2.8 12.2-18 12.2-20.2 0-1.9-1.7-3.6-3.6-3.6-3.9 0-12.2 16.6-14.7 19.9-41.8-27.7-72-70.6-83.6-119.6l19.1-4.2c2.2-.6 2.8-2.2 2.8-4.2 0-1.9-2.8-3-4.4-2.8L62 294.5c-2.5-12.7-3.9-25.5-3.9-38.5 0-37.1 10.5-73.6 30.2-104.9 2.8 1.7 16.1 10.8 18.3 10.8 1.9 0 3.6-1.4 3.6-3.3 0-3.9-14.7-11.3-18-13.6 28.2-41.2 71.1-70.9 119.8-81.9l4.2 18.5c.6 2.2 2.2 2.8 4.2 2.8s3-2.8 2.8-4.4L219 61.7c12.2-2.2 24.6-3.6 37.1-3.6 37.1 0 73.3 10.5 104.9 30.2-1.9 2.8-10.8 15.8-10.8 18 0 1.9 1.4 3.6 3.3 3.6 3.9 0 11.3-14.4 13.3-17.7 41 27.7 70.3 70 81.7 118.2l-15.5 3.3c-2.5.6-2.8 2.2-2.8 4.4 0 1.9 2.8 3 4.2 2.8l15.8-3.6c2.5 12.7 3.9 25.7 3.9 38.7 0 36.3-10 72-28.8 102.7-2.8-1.4-14.4-9.7-16.6-9.7-2.1 0-3.8 1.7-3.8 3.6zm-33.2-242.2c-13 12.2-134.2 123.7-137.6 129.5l-96.6 160.5c12.7-11.9 134.2-124 137.3-129.3l96.9-160.7z\"],\n    \"salesforce\": [640, 512, [], \"f83b\", \"M248.89 245.64h-26.35c.69-5.16 3.32-14.12 13.64-14.12 6.75 0 11.97 3.82 12.71 14.12zm136.66-13.88c-.47 0-14.11-1.77-14.11 20s13.63 20 14.11 20c13 0 14.11-13.54 14.11-20 0-21.76-13.66-20-14.11-20zm-243.22 23.76a8.63 8.63 0 0 0-3.29 7.29c0 4.78 2.08 6.05 3.29 7.05 4.7 3.7 15.07 2.12 20.93.95v-16.94c-5.32-1.07-16.73-1.96-20.93 1.65zM640 232c0 87.58-80 154.39-165.36 136.43-18.37 33-70.73 70.75-132.2 41.63-41.16 96.05-177.89 92.18-213.81-5.17C8.91 428.78-50.19 266.52 53.36 205.61 18.61 126.18 76 32 167.67 32a124.24 124.24 0 0 1 98.56 48.7c20.7-21.4 49.4-34.81 81.15-34.81 42.34 0 79 23.52 98.8 58.57C539 63.78 640 132.69 640 232zm-519.55 31.8c0-11.76-11.69-15.17-17.87-17.17-5.27-2.11-13.41-3.51-13.41-8.94 0-9.46 17-6.66 25.17-2.12 0 0 1.17.71 1.64-.47.24-.7 2.36-6.58 2.59-7.29a1.13 1.13 0 0 0-.7-1.41c-12.33-7.63-40.7-8.51-40.7 12.7 0 12.46 11.49 15.44 17.88 17.17 4.72 1.58 13.17 3 13.17 8.7 0 4-3.53 7.06-9.17 7.06a31.76 31.76 0 0 1-19-6.35c-.47-.23-1.42-.71-1.65.71l-2.4 7.47c-.47.94.23 1.18.23 1.41 1.75 1.4 10.3 6.59 22.82 6.59 13.17 0 21.4-7.06 21.4-18.11zm32-42.58c-10.13 0-18.66 3.17-21.4 5.18a1 1 0 0 0-.24 1.41l2.59 7.06a1 1 0 0 0 1.18.7c.65 0 6.8-4 16.93-4 4 0 7.06.71 9.18 2.36 3.6 2.8 3.06 8.29 3.06 10.58-4.79-.3-19.11-3.44-29.41 3.76a16.92 16.92 0 0 0-7.34 14.54c0 5.9 1.51 10.4 6.59 14.35 12.24 8.16 36.28 2 38.1 1.41 1.58-.32 3.53-.66 3.53-1.88v-33.88c.04-4.61.32-21.64-22.78-21.64zM199 200.24a1.11 1.11 0 0 0-1.18-1.18H188a1.11 1.11 0 0 0-1.17 1.18v79a1.11 1.11 0 0 0 1.17 1.18h9.88a1.11 1.11 0 0 0 1.18-1.18zm55.75 28.93c-2.1-2.31-6.79-7.53-17.65-7.53-3.51 0-14.16.23-20.7 8.94-6.35 7.63-6.58 18.11-6.58 21.41 0 3.12.15 14.26 7.06 21.17 2.64 2.91 9.06 8.23 22.81 8.23 10.82 0 16.47-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.35-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.94-16.7h37.17a1.23 1.23 0 0 0 1.17-.94c-.29 0 2.07-14.7-6.09-24.23zm36.69 52.69c13.17 0 21.41-7.06 21.41-18.11 0-11.76-11.7-15.17-17.88-17.17-4.14-1.66-13.41-3.38-13.41-8.94 0-3.76 3.29-6.35 8.47-6.35a38.11 38.11 0 0 1 16.7 4.23s1.18.71 1.65-.47c.23-.7 2.35-6.58 2.58-7.29a1.13 1.13 0 0 0-.7-1.41c-7.91-4.9-16.74-4.94-20.23-4.94-12 0-20.46 7.29-20.46 17.64 0 12.46 11.48 15.44 17.87 17.17 6.11 2 13.17 3.26 13.17 8.7 0 4-3.52 7.06-9.17 7.06a31.8 31.8 0 0 1-19-6.35 1 1 0 0 0-1.65.71l-2.35 7.52c-.47.94.23 1.18.23 1.41 1.72 1.4 10.33 6.59 22.79 6.59zM357.09 224c0-.71-.24-1.18-1.18-1.18h-11.76c0-.14.94-8.94 4.47-12.47 4.16-4.15 11.76-1.64 12-1.64 1.17.47 1.41 0 1.64-.47l2.83-7.77c.7-.94 0-1.17-.24-1.41-5.09-2-17.35-2.87-24.46 4.24-5.48 5.48-7 13.92-8 19.52h-8.47a1.28 1.28 0 0 0-1.17 1.18l-1.42 7.76c0 .7.24 1.17 1.18 1.17h8.23c-8.51 47.9-8.75 50.21-10.35 55.52-1.08 3.62-3.29 6.9-5.88 7.76-.09 0-3.88 1.68-9.64-.24 0 0-.94-.47-1.41.71-.24.71-2.59 6.82-2.83 7.53s0 1.41.47 1.41c5.11 2 13 1.77 17.88 0 6.28-2.28 9.72-7.89 11.53-12.94 2.75-7.71 2.81-9.79 11.76-59.74h12.23a1.29 1.29 0 0 0 1.18-1.18zm53.39 16c-.56-1.68-5.1-18.11-25.17-18.11-15.25 0-23 10-25.16 18.11-1 3-3.18 14 0 23.52.09.3 4.41 18.12 25.16 18.12 14.95 0 22.9-9.61 25.17-18.12 3.21-9.61 1.01-20.52 0-23.52zm45.4-16.7c-5-1.65-16.62-1.9-22.11 5.41v-4.47a1.11 1.11 0 0 0-1.18-1.17h-9.4a1.11 1.11 0 0 0-1.18 1.17v55.28a1.12 1.12 0 0 0 1.18 1.18h9.64a1.12 1.12 0 0 0 1.18-1.18v-27.77c0-2.91.05-11.37 4.46-15.05 4.9-4.9 12-3.36 13.41-3.06a1.57 1.57 0 0 0 1.41-.94 74 74 0 0 0 3.06-8 1.16 1.16 0 0 0-.47-1.41zm46.81 54.1l-2.12-7.29c-.47-1.18-1.41-.71-1.41-.71-4.23 1.82-10.15 1.89-11.29 1.89-4.64 0-17.17-1.13-17.17-19.76 0-6.23 1.85-19.76 16.47-19.76a34.85 34.85 0 0 1 11.52 1.65s.94.47 1.18-.71c.94-2.59 1.64-4.47 2.59-7.53.23-.94-.47-1.17-.71-1.17-11.59-3.87-22.34-2.53-27.76 0-1.59.74-16.23 6.49-16.23 27.52 0 2.9-.58 30.11 28.94 30.11a44.45 44.45 0 0 0 15.52-2.83 1.3 1.3 0 0 0 .47-1.42zm53.87-39.52c-.8-3-5.37-16.23-22.35-16.23-16 0-23.52 10.11-25.64 18.59a38.58 38.58 0 0 0-1.65 11.76c0 25.87 18.84 29.4 29.88 29.4 10.82 0 16.46-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.36-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.93-16.7h37.16a1.25 1.25 0 0 0 1.18-.94c-.24-.01.94-7.07-1.41-15.54zm-23.29-6.35c-10.33 0-13 9-13.64 14.12H546c-.88-11.92-7.62-14.13-12.73-14.13z\"],\n    \"sass\": [640, 512, [], \"f41e\", \"M301.84 378.92c-.3.6-.6 1.08 0 0zm249.13-87a131.16 131.16 0 0 0-58 13.5c-5.9-11.9-12-22.3-13-30.1-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.3-6.7-24 2.5-25.29 5.9a122.83 122.83 0 0 0-5.3 19.1c-2.3 11.7-25.79 53.5-39.09 75.3-4.4-8.5-8.1-16-8.9-22-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.29-6.7-24 2.5-25.3 5.9-2.7 11.4-5.3 19.1-33.89 77.3-42.08 95.4c-4.2 9.2-7.8 16.6-10.4 21.6-.4.8-.7 1.3-.9 1.7.3-.5.5-1 .5-.8-2.2 4.3-3.5 6.7-3.5 6.7v.1c-1.7 3.2-3.6 6.1-4.5 6.1-.6 0-1.9-8.4.3-19.9 4.7-24.2 15.8-61.8 15.7-63.1-.1-.7 2.1-7.2-7.3-10.7-9.1-3.3-12.4 2.2-13.2 2.2s-1.4 2-1.4 2 10.1-42.4-19.39-42.4c-18.4 0-44 20.2-56.58 38.5-7.9 4.3-25 13.6-43 23.5-6.9 3.8-14 7.7-20.7 11.4-.5-.5-.9-1-1.4-1.5-35.79-38.2-101.87-65.2-99.07-116.5 1-18.7 7.5-67.8 127.07-127.4 98-48.8 176.35-35.4 189.84-5.6 19.4 42.5-41.89 121.6-143.66 133-38.79 4.3-59.18-10.7-64.28-16.3-5.3-5.9-6.1-6.2-8.1-5.1-3.3 1.8-1.2 7 0 10.1 3 7.9 15.5 21.9 36.79 28.9 18.7 6.1 64.18 9.5 119.17-11.8 61.78-23.8 109.87-90.1 95.77-145.6C386.52 18.32 293-.18 204.57 31.22c-52.69 18.7-109.67 48.1-150.66 86.4-48.69 45.6-56.48 85.3-53.28 101.9 11.39 58.9 92.57 97.3 125.06 125.7-1.6.9-3.1 1.7-4.5 2.5-16.29 8.1-78.18 40.5-93.67 74.7-17.5 38.8 2.9 66.6 16.29 70.4 41.79 11.6 84.58-9.3 107.57-43.6s20.2-79.1 9.6-99.5c-.1-.3-.3-.5-.4-.8 4.2-2.5 8.5-5 12.8-7.5 8.29-4.9 16.39-9.4 23.49-13.3-4 10.8-6.9 23.8-8.4 42.6-1.8 22 7.3 50.5 19.1 61.7 5.2 4.9 11.49 5 15.39 5 13.8 0 20-11.4 26.89-25 8.5-16.6 16-35.9 16-35.9s-9.4 52.2 16.3 52.2c9.39 0 18.79-12.1 23-18.3v.1s.2-.4.7-1.2c1-1.5 1.5-2.4 1.5-2.4v-.3c3.8-6.5 12.1-21.4 24.59-46 16.2-31.8 31.69-71.5 31.69-71.5a201.24 201.24 0 0 0 6.2 25.8c2.8 9.5 8.7 19.9 13.4 30-3.8 5.2-6.1 8.2-6.1 8.2a.31.31 0 0 0 .1.2c-3 4-6.4 8.3-9.9 12.5-12.79 15.2-28 32.6-30 37.6-2.4 5.9-1.8 10.3 2.8 13.7 3.4 2.6 9.4 3 15.69 2.5 11.5-.8 19.6-3.6 23.5-5.4a82.2 82.2 0 0 0 20.19-10.6c12.5-9.2 20.1-22.4 19.4-39.8-.4-9.6-3.5-19.2-7.3-28.2 1.1-1.6 2.3-3.3 3.4-5C434.8 301.72 450.1 270 450.1 270a201.24 201.24 0 0 0 6.2 25.8c2.4 8.1 7.09 17 11.39 25.7-18.59 15.1-30.09 32.6-34.09 44.1-7.4 21.3-1.6 30.9 9.3 33.1 4.9 1 11.9-1.3 17.1-3.5a79.46 79.46 0 0 0 21.59-11.1c12.5-9.2 24.59-22.1 23.79-39.6-.3-7.9-2.5-15.8-5.4-23.4 15.7-6.6 36.09-10.2 62.09-7.2 55.68 6.5 66.58 41.3 64.48 55.8s-13.8 22.6-17.7 25-5.1 3.3-4.8 5.1c.5 2.6 2.3 2.5 5.6 1.9 4.6-.8 29.19-11.8 30.29-38.7 1.6-34-31.09-71.4-89-71.1zm-429.18 144.7c-18.39 20.1-44.19 27.7-55.28 21.3C54.61 451 59.31 421.42 82 400c13.8-13 31.59-25 43.39-32.4 2.7-1.6 6.6-4 11.4-6.9.8-.5 1.2-.7 1.2-.7.9-.6 1.9-1.1 2.9-1.7 8.29 30.4.3 57.2-19.1 78.3zm134.36-91.4c-6.4 15.7-19.89 55.7-28.09 53.6-7-1.8-11.3-32.3-1.4-62.3 5-15.1 15.6-33.1 21.9-40.1 10.09-11.3 21.19-14.9 23.79-10.4 3.5 5.9-12.2 49.4-16.2 59.2zm111 53c-2.7 1.4-5.2 2.3-6.4 1.6-.9-.5 1.1-2.4 1.1-2.4s13.9-14.9 19.4-21.7c3.2-4 6.9-8.7 10.89-13.9 0 .5.1 1 .1 1.6-.13 17.9-17.32 30-25.12 34.8zm85.58-19.5c-2-1.4-1.7-6.1 5-20.7 2.6-5.7 8.59-15.3 19-24.5a36.18 36.18 0 0 1 1.9 10.8c-.1 22.5-16.2 30.9-25.89 34.4z\"],\n    \"schlix\": [448, 512, [], \"f3ea\", \"M350.5 157.7l-54.2-46.1 73.4-39 78.3 44.2-97.5 40.9zM192 122.1l45.7-28.2 34.7 34.6-55.4 29-25-35.4zm-65.1 6.6l31.9-22.1L176 135l-36.7 22.5-12.4-28.8zm-23.3 88.2l-8.8-34.8 29.6-18.3 13.1 35.3-33.9 17.8zm-21.2-83.7l23.9-18.1 8.9 24-26.7 18.3-6.1-24.2zM59 206.5l-3.6-28.4 22.3-15.5 6.1 28.7L59 206.5zm-30.6 16.6l20.8-12.8 3.3 33.4-22.9 12-1.2-32.6zM1.4 268l19.2-10.2.4 38.2-21 8.8L1.4 268zm59.1 59.3l-28.3 8.3-1.6-46.8 25.1-10.7 4.8 49.2zM99 263.2l-31.1 13-5.2-40.8L90.1 221l8.9 42.2zM123.2 377l-41.6 5.9-8.1-63.5 35.2-10.8 14.5 68.4zm28.5-139.9l21.2 57.1-46.2 13.6-13.7-54.1 38.7-16.6zm85.7 230.5l-70.9-3.3-24.3-95.8 55.2-8.6 40 107.7zm-84.9-279.7l42.2-22.4 28 45.9-50.8 21.3-19.4-44.8zm41 94.9l61.3-18.7 52.8 86.6-79.8 11.3-34.3-79.2zm51.4-85.6l67.3-28.8 65.5 65.4-88.6 26.2-44.2-62.8z\"],\n    \"scribd\": [384, 512, [], \"f28a\", \"M42.3 252.7c-16.1-19-24.7-45.9-24.8-79.9 0-100.4 75.2-153.1 167.2-153.1 98.6-1.6 156.8 49 184.3 70.6l-50.5 72.1-37.3-24.6 26.9-38.6c-36.5-24-79.4-36.5-123-35.8-50.7-.8-111.7 27.2-111.7 76.2 0 18.7 11.2 20.7 28.6 15.6 23.3-5.3 41.9.6 55.8 14 26.4 24.3 23.2 67.6-.7 91.9-29.2 29.5-85.2 27.3-114.8-8.4zm317.7 5.9c-15.5-18.8-38.9-29.4-63.2-28.6-38.1-2-71.1 28-70.5 67.2-.7 16.8 6 33 18.4 44.3 14.1 13.9 33 19.7 56.3 14.4 17.4-5.1 28.6-3.1 28.6 15.6 0 4.3-.5 8.5-1.4 12.7-16.7 40.9-59.5 64.4-121.4 64.4-51.9.2-102.4-16.4-144.1-47.3l33.7-39.4-35.6-27.4L0 406.3l15.4 13.8c52.5 46.8 120.4 72.5 190.7 72.2 51.4 0 94.4-10.5 133.6-44.1 57.1-51.4 54.2-149.2 20.3-189.6z\"],\n    \"searchengin\": [460, 512, [], \"f3eb\", \"M220.6 130.3l-67.2 28.2V43.2L98.7 233.5l54.7-24.2v130.3l67.2-209.3zm-83.2-96.7l-1.3 4.7-15.2 52.9C80.6 106.7 52 145.8 52 191.5c0 52.3 34.3 95.9 83.4 105.5v53.6C57.5 340.1 0 272.4 0 191.6c0-80.5 59.8-147.2 137.4-158zm311.4 447.2c-11.2 11.2-23.1 12.3-28.6 10.5-5.4-1.8-27.1-19.9-60.4-44.4-33.3-24.6-33.6-35.7-43-56.7-9.4-20.9-30.4-42.6-57.5-52.4l-9.7-14.7c-24.7 16.9-53 26.9-81.3 28.7l2.1-6.6 15.9-49.5c46.5-11.9 80.9-54 80.9-104.2 0-54.5-38.4-102.1-96-107.1V32.3C254.4 37.4 320 106.8 320 191.6c0 33.6-11.2 64.7-29 90.4l14.6 9.6c9.8 27.1 31.5 48 52.4 57.4s32.2 9.7 56.8 43c24.6 33.2 42.7 54.9 44.5 60.3s.7 17.3-10.5 28.5zm-9.9-17.9c0-4.4-3.6-8-8-8s-8 3.6-8 8 3.6 8 8 8 8-3.6 8-8z\"],\n    \"sellcast\": [448, 512, [], \"f2da\", \"M353.4 32H94.7C42.6 32 0 74.6 0 126.6v258.7C0 437.4 42.6 480 94.7 480h258.7c52.1 0 94.7-42.6 94.7-94.6V126.6c0-52-42.6-94.6-94.7-94.6zm-50 316.4c-27.9 48.2-89.9 64.9-138.2 37.2-22.9 39.8-54.9 8.6-42.3-13.2l15.7-27.2c5.9-10.3 19.2-13.9 29.5-7.9 18.6 10.8-.1-.1 18.5 10.7 27.6 15.9 63.4 6.3 79.4-21.3 15.9-27.6 6.3-63.4-21.3-79.4-17.8-10.2-.6-.4-18.6-10.6-24.6-14.2-3.4-51.9 21.6-37.5 18.6 10.8-.1-.1 18.5 10.7 48.4 28 65.1 90.3 37.2 138.5zm21.8-208.8c-17 29.5-16.3 28.8-19 31.5-6.5 6.5-16.3 8.7-26.5 3.6-18.6-10.8.1.1-18.5-10.7-27.6-15.9-63.4-6.3-79.4 21.3s-6.3 63.4 21.3 79.4c0 0 18.5 10.6 18.6 10.6 24.6 14.2 3.4 51.9-21.6 37.5-18.6-10.8.1.1-18.5-10.7-48.2-27.8-64.9-90.1-37.1-138.4 27.9-48.2 89.9-64.9 138.2-37.2l4.8-8.4c14.3-24.9 52-3.3 37.7 21.5z\"],\n    \"sellsy\": [640, 512, [], \"f213\", \"M539.71 237.308c3.064-12.257 4.29-24.821 4.29-37.384C544 107.382 468.618 32 376.076 32c-77.22 0-144.634 53.012-163.02 127.781-15.322-13.176-34.934-20.53-55.157-20.53-46.271 0-83.962 37.69-83.962 83.961 0 7.354.92 15.015 3.065 22.369-42.9 20.225-70.785 63.738-70.785 111.234C6.216 424.843 61.68 480 129.401 480h381.198c67.72 0 123.184-55.157 123.184-123.184.001-56.384-38.916-106.025-94.073-119.508zM199.88 401.554c0 8.274-7.048 15.321-15.321 15.321H153.61c-8.274 0-15.321-7.048-15.321-15.321V290.626c0-8.273 7.048-15.321 15.321-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v110.928zm89.477 0c0 8.274-7.048 15.321-15.322 15.321h-30.949c-8.274 0-15.321-7.048-15.321-15.321V270.096c0-8.274 7.048-15.321 15.321-15.321h30.949c8.274 0 15.322 7.048 15.322 15.321v131.458zm89.477 0c0 8.274-7.047 15.321-15.321 15.321h-30.949c-8.274 0-15.322-7.048-15.322-15.321V238.84c0-8.274 7.048-15.321 15.322-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v162.714zm87.027 0c0 8.274-7.048 15.321-15.322 15.321h-28.497c-8.274 0-15.321-7.048-15.321-15.321V176.941c0-8.579 7.047-15.628 15.321-15.628h28.497c8.274 0 15.322 7.048 15.322 15.628v224.613z\"],\n    \"servicestack\": [496, 512, [], \"f3ec\", \"M88 216c81.7 10.2 273.7 102.3 304 232H0c99.5-8.1 184.5-137 88-232zm32-152c32.3 35.6 47.7 83.9 46.4 133.6C249.3 231.3 373.7 321.3 400 448h96C455.3 231.9 222.8 79.5 120 64z\"],\n    \"shirtsinbulk\": [448, 512, [], \"f214\", \"M100 410.3l30.6 13.4 4.4-9.9-30.6-13.4zm39.4 17.5l30.6 13.4 4.4-9.9-30.6-13.4zm172.1-14l4.4 9.9 30.6-13.4-4.4-9.9zM179.1 445l30.3 13.7 4.4-9.9-30.3-13.4zM60.4 392.8L91 406.2l4.4-9.6-30.6-13.7zm211.4 38.5l4.4 9.9 30.6-13.4-4.4-9.9zm-39.3 17.5l4.4 9.9 30.6-13.7-4.4-9.6zm118.4-52.2l4.4 9.6 30.6-13.4-4.4-9.9zM170 46.6h-33.5v10.5H170zm-47.2 0H89.2v10.5h33.5zm-47.3 0H42.3v10.5h33.3zm141.5 0h-33.2v10.5H217zm94.5 0H278v10.5h33.5zm47.3 0h-33.5v10.5h33.5zm-94.6 0H231v10.5h33.2zm141.5 0h-33.3v10.5h33.3zM52.8 351.1H42v33.5h10.8zm70-215.9H89.2v10.5h33.5zm-70 10.6h22.8v-10.5H42v33.5h10.8zm168.9 228.6c50.5 0 91.3-40.8 91.3-91.3 0-50.2-40.8-91.3-91.3-91.3-50.2 0-91.3 41.1-91.3 91.3 0 50.5 41.1 91.3 91.3 91.3zm-48.2-111.1c0-25.4 29.5-31.8 49.6-31.8 16.9 0 29.2 5.8 44.3 12l-8.8 16.9h-.9c-6.4-9.9-24.8-13.1-35.6-13.1-9 0-29.8 1.8-29.8 14.9 0 21.6 78.5-10.2 78.5 37.9 0 25.4-31.5 31.2-51 31.2-18.1 0-32.4-2.9-47.2-12.2l9-18.4h.9c6.1 12.2 23.6 14.9 35.9 14.9 8.7 0 32.7-1.2 32.7-14.3 0-26.1-77.6 6.3-77.6-38zM52.8 178.4H42V212h10.8zm342.4 206.2H406v-33.5h-10.8zM52.8 307.9H42v33.5h10.8zM0 3.7v406l221.7 98.6L448 409.7V3.7zm418.8 387.1L222 476.5 29.2 390.8V120.7h389.7v270.1zm0-299.3H29.2V32.9h389.7v58.6zm-366 130.1H42v33.5h10.8zm0 43.2H42v33.5h10.8zM170 135.2h-33.5v10.5H170zm225.2 163.1H406v-33.5h-10.8zm0-43.2H406v-33.5h-10.8zM217 135.2h-33.2v10.5H217zM395.2 212H406v-33.5h-10.8zm0 129.5H406V308h-10.8zm-131-206.3H231v10.5h33.2zm47.3 0H278v10.5h33.5zm83.7 33.6H406v-33.5h-33.5v10.5h22.8zm-36.4-33.6h-33.5v10.5h33.5z\"],\n    \"shopware\": [512, 512, [], \"f5b5\", \"M403.5 455.41A246.17 246.17 0 0 1 256 504C118.81 504 8 393 8 256 8 118.81 119 8 256 8a247.39 247.39 0 0 1 165.7 63.5 3.57 3.57 0 0 1-2.86 6.18A418.62 418.62 0 0 0 362.13 74c-129.36 0-222.4 53.47-222.4 155.35 0 109 92.13 145.88 176.83 178.73 33.64 13 65.4 25.36 87 41.59a3.58 3.58 0 0 1 0 5.72zM503 233.09a3.64 3.64 0 0 0-1.27-2.44c-51.76-43-93.62-60.48-144.48-60.48-84.13 0-80.25 52.17-80.25 53.63 0 42.6 52.06 62 112.34 84.49 31.07 11.59 63.19 23.57 92.68 39.93a3.57 3.57 0 0 0 5-1.82A249 249 0 0 0 503 233.09z\"],\n    \"simplybuilt\": [512, 512, [], \"f215\", \"M481.2 64h-106c-14.5 0-26.6 11.8-26.6 26.3v39.6H163.3V90.3c0-14.5-12-26.3-26.6-26.3h-106C16.1 64 4.3 75.8 4.3 90.3v331.4c0 14.5 11.8 26.3 26.6 26.3h450.4c14.8 0 26.6-11.8 26.6-26.3V90.3c-.2-14.5-12-26.3-26.7-26.3zM149.8 355.8c-36.6 0-66.4-29.7-66.4-66.4 0-36.9 29.7-66.6 66.4-66.6 36.9 0 66.6 29.7 66.6 66.6 0 36.7-29.7 66.4-66.6 66.4zm212.4 0c-36.9 0-66.6-29.7-66.6-66.6 0-36.6 29.7-66.4 66.6-66.4 36.6 0 66.4 29.7 66.4 66.4 0 36.9-29.8 66.6-66.4 66.6z\"],\n    \"sistrix\": [448, 512, [], \"f3ee\", \"M448 449L301.2 300.2c20-27.9 31.9-62.2 31.9-99.2 0-93.1-74.7-168.9-166.5-168.9C74.7 32 0 107.8 0 200.9s74.7 168.9 166.5 168.9c39.8 0 76.3-14.2 105-37.9l146 148.1 30.5-31zM166.5 330.8c-70.6 0-128.1-58.3-128.1-129.9S95.9 71 166.5 71s128.1 58.3 128.1 129.9-57.4 129.9-128.1 129.9z\"],\n    \"sith\": [448, 512, [], \"f512\", \"M0 32l69.71 118.75-58.86-11.52 69.84 91.03a146.741 146.741 0 0 0 0 51.45l-69.84 91.03 58.86-11.52L0 480l118.75-69.71-11.52 58.86 91.03-69.84c17.02 3.04 34.47 3.04 51.48 0l91.03 69.84-11.52-58.86L448 480l-69.71-118.78 58.86 11.52-69.84-91.03c3.03-17.01 3.04-34.44 0-51.45l69.84-91.03-58.86 11.52L448 32l-118.75 69.71 11.52-58.9-91.06 69.87c-8.5-1.52-17.1-2.29-25.71-2.29s-17.21.78-25.71 2.29l-91.06-69.87 11.52 58.9L0 32zm224 99.78c31.8 0 63.6 12.12 87.85 36.37 48.5 48.5 48.49 127.21 0 175.7s-127.2 48.46-175.7-.03c-48.5-48.5-48.49-127.21 0-175.7 24.24-24.25 56.05-36.34 87.85-36.34zm0 36.66c-22.42 0-44.83 8.52-61.92 25.61-34.18 34.18-34.19 89.68 0 123.87s89.65 34.18 123.84 0c34.18-34.18 34.19-89.68 0-123.87-17.09-17.09-39.5-25.61-61.92-25.61z\"],\n    \"sketch\": [512, 512, [], \"f7c6\", \"M27.5 162.2L9 187.1h90.5l6.9-130.7-78.9 105.8zM396.3 45.7L267.7 32l135.7 147.2-7.1-133.5zM112.2 218.3l-11.2-22H9.9L234.8 458zm2-31.2h284l-81.5-88.5L256.3 33zm297.3 9.1L277.6 458l224.8-261.7h-90.9zM415.4 69L406 56.4l.9 17.3 6.1 113.4h90.3zM113.5 93.5l-4.6 85.6L244.7 32 116.1 45.7zm287.7 102.7h-290l42.4 82.9L256.3 480l144.9-283.8z\"],\n    \"skyatlas\": [640, 512, [], \"f216\", \"M640 329.3c0 65.9-52.5 114.4-117.5 114.4-165.9 0-196.6-249.7-359.7-249.7-146.9 0-147.1 212.2 5.6 212.2 42.5 0 90.9-17.8 125.3-42.5 5.6-4.1 16.9-16.3 22.8-16.3s10.9 5 10.9 10.9c0 7.8-13.1 19.1-18.7 24.1-40.9 35.6-100.3 61.2-154.7 61.2-83.4.1-154-59-154-144.9s67.5-149.1 152.8-149.1c185.3 0 222.5 245.9 361.9 245.9 99.9 0 94.8-139.7 3.4-139.7-17.5 0-35 11.6-46.9 11.6-8.4 0-15.9-7.2-15.9-15.6 0-11.6 5.3-23.7 5.3-36.3 0-66.6-50.9-114.7-116.9-114.7-53.1 0-80 36.9-88.8 36.9-6.2 0-11.2-5-11.2-11.2 0-5.6 4.1-10.3 7.8-14.4 25.3-28.8 64.7-43.7 102.8-43.7 79.4 0 139.1 58.4 139.1 137.8 0 6.9-.3 13.7-1.2 20.6 11.9-3.1 24.1-4.7 35.9-4.7 60.7 0 111.9 45.3 111.9 107.2z\"],\n    \"skype\": [448, 512, [], \"f17e\", \"M424.7 299.8c2.9-14 4.7-28.9 4.7-43.8 0-113.5-91.9-205.3-205.3-205.3-14.9 0-29.7 1.7-43.8 4.7C161.3 40.7 137.7 32 112 32 50.2 32 0 82.2 0 144c0 25.7 8.7 49.3 23.3 68.2-2.9 14-4.7 28.9-4.7 43.8 0 113.5 91.9 205.3 205.3 205.3 14.9 0 29.7-1.7 43.8-4.7 19 14.6 42.6 23.3 68.2 23.3 61.8 0 112-50.2 112-112 .1-25.6-8.6-49.2-23.2-68.1zm-194.6 91.5c-65.6 0-120.5-29.2-120.5-65 0-16 9-30.6 29.5-30.6 31.2 0 34.1 44.9 88.1 44.9 25.7 0 42.3-11.4 42.3-26.3 0-18.7-16-21.6-42-28-62.5-15.4-117.8-22-117.8-87.2 0-59.2 58.6-81.1 109.1-81.1 55.1 0 110.8 21.9 110.8 55.4 0 16.9-11.4 31.8-30.3 31.8-28.3 0-29.2-33.5-75-33.5-25.7 0-42 7-42 22.5 0 19.8 20.8 21.8 69.1 33 41.4 9.3 90.7 26.8 90.7 77.6 0 59.1-57.1 86.5-112 86.5z\"],\n    \"slack\": [448, 512, [], \"f198\", \"M94.12 315.1c0 25.9-21.16 47.06-47.06 47.06S0 341 0 315.1c0-25.9 21.16-47.06 47.06-47.06h47.06v47.06zm23.72 0c0-25.9 21.16-47.06 47.06-47.06s47.06 21.16 47.06 47.06v117.84c0 25.9-21.16 47.06-47.06 47.06s-47.06-21.16-47.06-47.06V315.1zm47.06-188.98c-25.9 0-47.06-21.16-47.06-47.06S139 32 164.9 32s47.06 21.16 47.06 47.06v47.06H164.9zm0 23.72c25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06H47.06C21.16 243.96 0 222.8 0 196.9s21.16-47.06 47.06-47.06H164.9zm188.98 47.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06h-47.06V196.9zm-23.72 0c0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06V79.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06V196.9zM283.1 385.88c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06v-47.06h47.06zm0-23.72c-25.9 0-47.06-21.16-47.06-47.06 0-25.9 21.16-47.06 47.06-47.06h117.84c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06H283.1z\"],\n    \"slack-hash\": [448, 512, [], \"f3ef\", \"M446.2 270.4c-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-30.3-90 45.4-15.1c19.1-6.2 29.1-26.8 23-45.9-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-93.4 31.2-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-45.3 15c-19.1 6.2-29.1 26.8-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l30.3 90L78 354.8c-19 6.2-29.1 26.9-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 93.6-31.3 15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 45.4-15.1c19-6 29.1-26.7 22.9-45.7zm-254.1 47.2l-30.3-90.2 93.5-31.3 30.3 90.2-93.5 31.3z\"],\n    \"slideshare\": [512, 512, [], \"f1e7\", \"M187.7 153.7c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7s61.7-26 61.7-57.7c0-32-27.7-57.7-61.7-57.7zm143.4 0c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7 34.3 0 61.7-26 61.7-57.7.1-32-27.4-57.7-61.7-57.7zm156.6 90l-6 4.3V49.7c0-27.4-20.6-49.7-46-49.7H76.6c-25.4 0-46 22.3-46 49.7V248c-2-1.4-4.3-2.9-6.3-4.3-15.1-10.6-25.1 4-16 17.7 18.3 22.6 53.1 50.3 106.3 72C58.3 525.1 252 555.7 248.9 457.5c0-.7.3-56.6.3-96.6 5.1 1.1 9.4 2.3 13.7 3.1 0 39.7.3 92.8.3 93.5-3.1 98.3 190.6 67.7 134.3-124 53.1-21.7 88-49.4 106.3-72 9.1-13.8-.9-28.3-16.1-17.8zm-30.5 19.2c-68.9 37.4-128.3 31.1-160.6 29.7-23.7-.9-32.6 9.1-33.7 24.9-10.3-7.7-18.6-15.5-20.3-17.1-5.1-5.4-13.7-8-27.1-7.7-31.7 1.1-89.7 7.4-157.4-28V72.3c0-34.9 8.9-45.7 40.6-45.7h317.7c30.3 0 40.9 12.9 40.9 45.7v190.6z\"],\n    \"snapchat\": [496, 512, [], \"f2ab\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm169.5 338.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C183.1 100 230.7 96 244.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"snapchat-ghost\": [512, 512, [], \"f2ac\", \"M510.846 392.673c-5.211 12.157-27.239 21.089-67.36 27.318-2.064 2.786-3.775 14.686-6.507 23.956-1.625 5.566-5.623 8.869-12.128 8.869l-.297-.005c-9.395 0-19.203-4.323-38.852-4.323-26.521 0-35.662 6.043-56.254 20.588-21.832 15.438-42.771 28.764-74.027 27.399-31.646 2.334-58.025-16.908-72.871-27.404-20.714-14.643-29.828-20.582-56.241-20.582-18.864 0-30.736 4.72-38.852 4.72-8.073 0-11.213-4.922-12.422-9.04-2.703-9.189-4.404-21.263-6.523-24.13-20.679-3.209-67.31-11.344-68.498-32.15a10.627 10.627 0 0 1 8.877-11.069c69.583-11.455 100.924-82.901 102.227-85.934.074-.176.155-.344.237-.515 3.713-7.537 4.544-13.849 2.463-18.753-5.05-11.896-26.872-16.164-36.053-19.796-23.715-9.366-27.015-20.128-25.612-27.504 2.437-12.836 21.725-20.735 33.002-15.453 8.919 4.181 16.843 6.297 23.547 6.297 5.022 0 8.212-1.204 9.96-2.171-2.043-35.936-7.101-87.29 5.687-115.969C158.122 21.304 229.705 15.42 250.826 15.42c.944 0 9.141-.089 10.11-.089 52.148 0 102.254 26.78 126.723 81.643 12.777 28.65 7.749 79.792 5.695 116.009 1.582.872 4.357 1.942 8.599 2.139 6.397-.286 13.815-2.389 22.069-6.257 6.085-2.846 14.406-2.461 20.48.058l.029.01c9.476 3.385 15.439 10.215 15.589 17.87.184 9.747-8.522 18.165-25.878 25.018-2.118.835-4.694 1.655-7.434 2.525-9.797 3.106-24.6 7.805-28.616 17.271-2.079 4.904-1.256 11.211 2.46 18.748.087.168.166.342.239.515 1.301 3.03 32.615 74.46 102.23 85.934 6.427 1.058 11.163 7.877 7.725 15.859z\"],\n    \"snapchat-square\": [448, 512, [], \"f2ad\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6.5 314.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C159.1 100 206.7 96 220.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"soundcloud\": [640, 512, [], \"f1be\", \"M111.4 256.3l5.8 65-5.8 68.3c-.3 2.5-2.2 4.4-4.4 4.4s-4.2-1.9-4.2-4.4l-5.6-68.3 5.6-65c0-2.2 1.9-4.2 4.2-4.2 2.2 0 4.1 2 4.4 4.2zm21.4-45.6c-2.8 0-4.7 2.2-5 5l-5 105.6 5 68.3c.3 2.8 2.2 5 5 5 2.5 0 4.7-2.2 4.7-5l5.8-68.3-5.8-105.6c0-2.8-2.2-5-4.7-5zm25.5-24.1c-3.1 0-5.3 2.2-5.6 5.3l-4.4 130 4.4 67.8c.3 3.1 2.5 5.3 5.6 5.3 2.8 0 5.3-2.2 5.3-5.3l5.3-67.8-5.3-130c0-3.1-2.5-5.3-5.3-5.3zM7.2 283.2c-1.4 0-2.2 1.1-2.5 2.5L0 321.3l4.7 35c.3 1.4 1.1 2.5 2.5 2.5s2.2-1.1 2.5-2.5l5.6-35-5.6-35.6c-.3-1.4-1.1-2.5-2.5-2.5zm23.6-21.9c-1.4 0-2.5 1.1-2.5 2.5l-6.4 57.5 6.4 56.1c0 1.7 1.1 2.8 2.5 2.8s2.5-1.1 2.8-2.5l7.2-56.4-7.2-57.5c-.3-1.4-1.4-2.5-2.8-2.5zm25.3-11.4c-1.7 0-3.1 1.4-3.3 3.3L47 321.3l5.8 65.8c.3 1.7 1.7 3.1 3.3 3.1 1.7 0 3.1-1.4 3.1-3.1l6.9-65.8-6.9-68.1c0-1.9-1.4-3.3-3.1-3.3zm25.3-2.2c-1.9 0-3.6 1.4-3.6 3.6l-5.8 70 5.8 67.8c0 2.2 1.7 3.6 3.6 3.6s3.6-1.4 3.9-3.6l6.4-67.8-6.4-70c-.3-2.2-2-3.6-3.9-3.6zm241.4-110.9c-1.1-.8-2.8-1.4-4.2-1.4-2.2 0-4.2.8-5.6 1.9-1.9 1.7-3.1 4.2-3.3 6.7v.8l-3.3 176.7 1.7 32.5 1.7 31.7c.3 4.7 4.2 8.6 8.9 8.6s8.6-3.9 8.6-8.6l3.9-64.2-3.9-177.5c-.4-3-2-5.8-4.5-7.2zm-26.7 15.3c-1.4-.8-2.8-1.4-4.4-1.4s-3.1.6-4.4 1.4c-2.2 1.4-3.6 3.9-3.6 6.7l-.3 1.7-2.8 160.8s0 .3 3.1 65.6v.3c0 1.7.6 3.3 1.7 4.7 1.7 1.9 3.9 3.1 6.4 3.1 2.2 0 4.2-1.1 5.6-2.5 1.7-1.4 2.5-3.3 2.5-5.6l.3-6.7 3.1-58.6-3.3-162.8c-.3-2.8-1.7-5.3-3.9-6.7zm-111.4 22.5c-3.1 0-5.8 2.8-5.8 6.1l-4.4 140.6 4.4 67.2c.3 3.3 2.8 5.8 5.8 5.8 3.3 0 5.8-2.5 6.1-5.8l5-67.2-5-140.6c-.2-3.3-2.7-6.1-6.1-6.1zm376.7 62.8c-10.8 0-21.1 2.2-30.6 6.1-6.4-70.8-65.8-126.4-138.3-126.4-17.8 0-35 3.3-50.3 9.4-6.1 2.2-7.8 4.4-7.8 9.2v249.7c0 5 3.9 8.6 8.6 9.2h218.3c43.3 0 78.6-35 78.6-78.3.1-43.6-35.2-78.9-78.5-78.9zm-296.7-60.3c-4.2 0-7.5 3.3-7.8 7.8l-3.3 136.7 3.3 65.6c.3 4.2 3.6 7.5 7.8 7.5 4.2 0 7.5-3.3 7.5-7.5l3.9-65.6-3.9-136.7c-.3-4.5-3.3-7.8-7.5-7.8zm-53.6-7.8c-3.3 0-6.4 3.1-6.4 6.7l-3.9 145.3 3.9 66.9c.3 3.6 3.1 6.4 6.4 6.4 3.6 0 6.4-2.8 6.7-6.4l4.4-66.9-4.4-145.3c-.3-3.6-3.1-6.7-6.7-6.7zm26.7 3.4c-3.9 0-6.9 3.1-6.9 6.9L227 321.3l3.9 66.4c.3 3.9 3.1 6.9 6.9 6.9s6.9-3.1 6.9-6.9l4.2-66.4-4.2-141.7c0-3.9-3-6.9-6.9-6.9z\"],\n    \"sourcetree\": [448, 512, [], \"f7d3\", \"M427.2 203c0-112.1-90.9-203-203-203C112.1-.2 21.2 90.6 21 202.6A202.86 202.86 0 0 0 161.5 396v101.7a14.3 14.3 0 0 0 14.3 14.3h96.4a14.3 14.3 0 0 0 14.3-14.3V396.1A203.18 203.18 0 0 0 427.2 203zm-271.6 0c0-90.8 137.3-90.8 137.3 0-.1 89.9-137.3 91-137.3 0z\"],\n    \"speakap\": [448, 512, [], \"f3f3\", \"M64 391.78C-15.41 303.59-8 167.42 80.64 87.64s224.8-73 304.21 15.24 72 224.36-16.64 304.14c-18.74 16.87 64 43.09 42 52.26-82.06 34.21-253.91 35-346.23-67.5zm213.31-211.6l38.5-40.86c-9.61-8.89-32-26.83-76.17-27.6-52.33-.91-95.86 28.3-96.77 80-.2 11.33.29 36.72 29.42 54.83 34.46 21.42 86.52 21.51 86 52.26-.37 21.28-26.42 25.81-38.59 25.6-3-.05-30.23-.46-47.61-24.62l-40 42.61c28.16 27 59 32.62 83.49 33.05 10.23.18 96.42.33 97.84-81 .28-15.81-2.07-39.72-28.86-56.59-34.36-21.64-85-19.45-84.43-49.75.41-23.25 31-25.37 37.53-25.26.43 0 26.62.26 39.62 17.37z\"],\n    \"speaker-deck\": [512, 512, [], \"f83c\", \"M213.86 296H100a100 100 0 0 1 0-200h132.84a40 40 0 0 1 0 80H98c-26.47 0-26.45 40 0 40h113.82a100 100 0 0 1 0 200H40a40 40 0 0 1 0-80h173.86c26.48 0 26.46-40 0-40zM298 416a120.21 120.21 0 0 0 51.11-80h64.55a19.83 19.83 0 0 0 19.66-20V196a19.83 19.83 0 0 0-19.66-20H296.42a60.77 60.77 0 0 0 0-80h136.93c43.44 0 78.65 35.82 78.65 80v160c0 44.18-35.21 80-78.65 80z\"],\n    \"spotify\": [496, 512, [], \"f1bc\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm100.7 364.9c-4.2 0-6.8-1.3-10.7-3.6-62.4-37.6-135-39.2-206.7-24.5-3.9 1-9 2.6-11.9 2.6-9.7 0-15.8-7.7-15.8-15.8 0-10.3 6.1-15.2 13.6-16.8 81.9-18.1 165.6-16.5 237 26.2 6.1 3.9 9.7 7.4 9.7 16.5s-7.1 15.4-15.2 15.4zm26.9-65.6c-5.2 0-8.7-2.3-12.3-4.2-62.5-37-155.7-51.9-238.6-29.4-4.8 1.3-7.4 2.6-11.9 2.6-10.7 0-19.4-8.7-19.4-19.4s5.2-17.8 15.5-20.7c27.8-7.8 56.2-13.6 97.8-13.6 64.9 0 127.6 16.1 177 45.5 8.1 4.8 11.3 11 11.3 19.7-.1 10.8-8.5 19.5-19.4 19.5zm31-76.2c-5.2 0-8.4-1.3-12.9-3.9-71.2-42.5-198.5-52.7-280.9-29.7-3.6 1-8.1 2.6-12.9 2.6-13.2 0-23.3-10.3-23.3-23.6 0-13.6 8.4-21.3 17.4-23.9 35.2-10.3 74.6-15.2 117.5-15.2 73 0 149.5 15.2 205.4 47.8 7.8 4.5 12.9 10.7 12.9 22.6 0 13.6-11 23.3-23.2 23.3z\"],\n    \"squarespace\": [512, 512, [], \"f5be\", \"M186.12 343.34c-9.65 9.65-9.65 25.29 0 34.94 9.65 9.65 25.29 9.65 34.94 0L378.24 221.1c19.29-19.29 50.57-19.29 69.86 0s19.29 50.57 0 69.86L293.95 445.1c19.27 19.29 50.53 19.31 69.82.04l.04-.04 119.25-119.24c38.59-38.59 38.59-101.14 0-139.72-38.59-38.59-101.15-38.59-139.72 0l-157.22 157.2zm244.53-104.8c-9.65-9.65-25.29-9.65-34.93 0l-157.2 157.18c-19.27 19.29-50.53 19.31-69.82.05l-.05-.05c-9.64-9.64-25.27-9.65-34.92-.01l-.01.01c-9.65 9.64-9.66 25.28-.02 34.93l.02.02c38.58 38.57 101.14 38.57 139.72 0l157.2-157.2c9.65-9.65 9.65-25.29.01-34.93zm-261.99 87.33l157.18-157.18c9.64-9.65 9.64-25.29 0-34.94-9.64-9.64-25.27-9.64-34.91 0L133.72 290.93c-19.28 19.29-50.56 19.3-69.85.01l-.01-.01c-19.29-19.28-19.31-50.54-.03-69.84l.03-.03L218.03 66.89c-19.28-19.29-50.55-19.3-69.85-.02l-.02.02L28.93 186.14c-38.58 38.59-38.58 101.14 0 139.72 38.6 38.59 101.13 38.59 139.73.01zm-87.33-52.4c9.64 9.64 25.27 9.64 34.91 0l157.21-157.19c19.28-19.29 50.55-19.3 69.84-.02l.02.02c9.65 9.65 25.29 9.65 34.93 0 9.65-9.65 9.65-25.29 0-34.93-38.59-38.59-101.13-38.59-139.72 0L81.33 238.54c-9.65 9.64-9.65 25.28-.01 34.93h.01z\"],\n    \"stack-exchange\": [448, 512, [], \"f18d\", \"M17.7 332.3h412.7v22c0 37.7-29.3 68-65.3 68h-19L259.3 512v-89.7H83c-36 0-65.3-30.3-65.3-68v-22zm0-23.6h412.7v-85H17.7v85zm0-109.4h412.7v-85H17.7v85zM365 0H83C47 0 17.7 30.3 17.7 67.7V90h412.7V67.7C430.3 30.3 401 0 365 0z\"],\n    \"stack-overflow\": [384, 512, [], \"f16c\", \"M290.7 311L95 269.7 86.8 309l195.7 41zm51-87L188.2 95.7l-25.5 30.8 153.5 128.3zm-31.2 39.7L129.2 179l-16.7 36.5L293.7 300zM262 32l-32 24 119.3 160.3 32-24zm20.5 328h-200v39.7h200zm39.7 80H42.7V320h-40v160h359.5V320h-40z\"],\n    \"stackpath\": [448, 512, [], \"f842\", \"M244.6 232.4c0 8.5-4.26 20.49-21.34 20.49h-19.61v-41.47h19.61c17.13 0 21.34 12.36 21.34 20.98zM448 32v448H0V32zM151.3 287.84c0-21.24-12.12-34.54-46.72-44.85-20.57-7.41-26-10.91-26-18.63s7-14.61 20.41-14.61c14.09 0 20.79 8.45 20.79 18.35h30.7l.19-.57c.5-19.57-15.06-41.65-51.12-41.65-23.37 0-52.55 10.75-52.55 38.29 0 19.4 9.25 31.29 50.74 44.37 17.26 6.15 21.91 10.4 21.91 19.48 0 15.2-19.13 14.23-19.47 14.23-20.4 0-25.65-9.1-25.65-21.9h-30.8l-.18.56c-.68 31.32 28.38 45.22 56.63 45.22 29.98 0 51.12-13.55 51.12-38.29zm125.38-55.63c0-25.3-18.43-45.46-53.42-45.46h-51.78v138.18h32.17v-47.36h19.61c30.25 0 53.42-15.95 53.42-45.36zM297.94 325L347 186.78h-31.09L268 325zm106.52-138.22h-31.09L325.46 325h29.94z\"],\n    \"staylinked\": [440, 512, [], \"f3f5\", \"M382.7 292.5l2.7 2.7-170-167.3c-3.5-3.5-9.7-3.7-13.8-.5L144.3 171c-4.2 3.2-4.6 8.7-1.1 12.2l68.1 64.3c3.6 3.5 9.9 3.7 14 .5l.1-.1c4.1-3.2 10.4-3 14 .5l84 81.3c3.6 3.5 3.2 9-.9 12.2l-93.2 74c-4.2 3.3-10.5 3.1-14.2-.4L63.2 268c-3.5-3.5-9.7-3.7-13.9-.5L3.5 302.4c-4.2 3.2-4.7 8.7-1.2 12.2L211 510.7s7.4 6.8 17.3-.8l198-163.9c4-3.2 4.4-8.7.7-12.2zm54.5-83.4L226.7 2.5c-1.5-1.2-8-5.5-16.3 1.1L3.6 165.7c-4.2 3.2-4.8 8.7-1.2 12.2l42.3 41.7 171.7 165.1c3.7 3.5 10.1 3.7 14.3.4l50.2-38.8-.3-.3 7.7-6c4.2-3.2 4.6-8.7.9-12.2l-57.1-54.4c-3.6-3.5-10-3.7-14.2-.5l-.1.1c-4.2 3.2-10.5 3.1-14.2-.4L109 180.8c-3.6-3.5-3.1-8.9 1.1-12.2l92.2-71.5c4.1-3.2 10.3-3 13.9.5l160.4 159c3.7 3.5 10 3.7 14.1.5l45.8-35.8c4.1-3.2 4.4-8.7.7-12.2z\"],\n    \"steam\": [496, 512, [], \"f1b6\", \"M496 256c0 137-111.2 248-248.4 248-113.8 0-209.6-76.3-239-180.4l95.2 39.3c6.4 32.1 34.9 56.4 68.9 56.4 39.2 0 71.9-32.4 70.2-73.5l84.5-60.2c52.1 1.3 95.8-40.9 95.8-93.5 0-51.6-42-93.5-93.7-93.5s-93.7 42-93.7 93.5v1.2L176.6 279c-15.5-.9-30.7 3.4-43.5 12.1L0 236.1C10.2 108.4 117.1 8 247.6 8 384.8 8 496 119 496 256zM155.7 384.3l-30.5-12.6a52.79 52.79 0 0 0 27.2 25.8c26.9 11.2 57.8-1.6 69-28.4 5.4-13 5.5-27.3.1-40.3-5.4-13-15.5-23.2-28.5-28.6-12.9-5.4-26.7-5.2-38.9-.6l31.5 13c19.8 8.2 29.2 30.9 20.9 50.7-8.3 19.9-31 29.2-50.8 21zm173.8-129.9c-34.4 0-62.4-28-62.4-62.3s28-62.3 62.4-62.3 62.4 28 62.4 62.3-27.9 62.3-62.4 62.3zm.1-15.6c25.9 0 46.9-21 46.9-46.8 0-25.9-21-46.8-46.9-46.8s-46.9 21-46.9 46.8c.1 25.8 21.1 46.8 46.9 46.8z\"],\n    \"steam-square\": [448, 512, [], \"f1b7\", \"M185.2 356.5c7.7-18.5-1-39.7-19.6-47.4l-29.5-12.2c11.4-4.3 24.3-4.5 36.4.5 12.2 5.1 21.6 14.6 26.7 26.7 5 12.2 5 25.6-.1 37.7-10.5 25.1-39.4 37-64.6 26.5-11.6-4.8-20.4-13.6-25.4-24.2l28.5 11.8c18.6 7.8 39.9-.9 47.6-19.4zM400 32H48C21.5 32 0 53.5 0 80v160.7l116.6 48.1c12-8.2 26.2-12.1 40.7-11.3l55.4-80.2v-1.1c0-48.2 39.3-87.5 87.6-87.5s87.6 39.3 87.6 87.5c0 49.2-40.9 88.7-89.6 87.5l-79 56.3c1.6 38.5-29.1 68.8-65.7 68.8-31.8 0-58.5-22.7-64.5-52.7L0 319.2V432c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-99.7 222.5c-32.2 0-58.4-26.1-58.4-58.3s26.2-58.3 58.4-58.3 58.4 26.2 58.4 58.3-26.2 58.3-58.4 58.3zm.1-14.6c24.2 0 43.9-19.6 43.9-43.8 0-24.2-19.6-43.8-43.9-43.8-24.2 0-43.9 19.6-43.9 43.8 0 24.2 19.7 43.8 43.9 43.8z\"],\n    \"steam-symbol\": [448, 512, [], \"f3f6\", \"M395.5 177.5c0 33.8-27.5 61-61 61-33.8 0-61-27.3-61-61s27.3-61 61-61c33.5 0 61 27.2 61 61zm52.5.2c0 63-51 113.8-113.7 113.8L225 371.3c-4 43-40.5 76.8-84.5 76.8-40.5 0-74.7-28.8-83-67L0 358V250.7L97.2 290c15.1-9.2 32.2-13.3 52-11.5l71-101.7c.5-62.3 51.5-112.8 114-112.8C397 64 448 115 448 177.7zM203 363c0-34.7-27.8-62.5-62.5-62.5-4.5 0-9 .5-13.5 1.5l26 10.5c25.5 10.2 38 39 27.7 64.5-10.2 25.5-39.2 38-64.7 27.5-10.2-4-20.5-8.3-30.7-12.2 10.5 19.7 31.2 33.2 55.2 33.2 34.7 0 62.5-27.8 62.5-62.5zm207.5-185.3c0-42-34.3-76.2-76.2-76.2-42.3 0-76.5 34.2-76.5 76.2 0 42.2 34.3 76.2 76.5 76.2 41.9.1 76.2-33.9 76.2-76.2z\"],\n    \"sticker-mule\": [576, 512, [], \"f3f7\", \"M561.7 199.6c-1.3.3.3 0 0 0zm-6.2-77.4c-7.7-22.3-5.1-7.2-13.4-36.9-1.6-6.5-3.6-14.5-6.2-20-4.4-8.7-4.6-7.5-4.6-9.5 0-5.3 30.7-45.3 19-46.9-5.7-.6-12.2 11.6-20.6 17-8.6 4.2-8 5-10.3 5-2.6 0-5.7-3-6.2-5-2-5.7 1.9-25.9-3.6-25.9-3.6 0-12.3 24.8-17 25.8-5.2 1.3-27.9-11.4-75.1 18-25.3 13.2-86.9 65.2-87 65.3-6.7 4.7-20 4.7-35.5 16-44.4 30.1-109.6 9.4-110.7 9-110.6-26.8-128-15.2-159 11.5-20.8 17.9-23.7 36.5-24.2 38.9-4.2 20.4 5.2 48.3 6.7 64.3 1.8 19.3-2.7 17.7 7.7 98.3.5 1 4.1 0 5.1 1.5 0 8.4-3.8 12.1-4.1 13-1.5 4.5-1.5 10.5 0 16 2.3 8.2 8.2 37.2 8.2 46.9 0 41.8.4 44 2.6 49.4 3.9 10 12.5 9.1 17 12 3.1 3.5-.5 8.5 1 12.5.5 2 3.6 4 6.2 5 9.2 3.6 27 .3 29.9-2.5 1.6-1.5.5-4.5 3.1-5 5.1 0 10.8-.5 14.4-2.5 5.1-2.5 4.1-6 1.5-10.5-.4-.8-7-13.3-9.8-16-2.1-2-5.1-3-7.2-4.5-5.8-4.9-10.3-19.4-10.3-19.5-4.6-19.4-10.3-46.3-4.1-66.8 4.6-17.2 39.5-87.7 39.6-87.8 4.1-6.5 17-11.5 27.3-7 6 1.9 19.3 22 65.4 30.9 47.9 8.7 97.4-2 112.2-2 2.8 2-1.9 13-.5 38.9 0 26.4-.4 13.7-4.1 29.9-2.2 9.7 3.4 23.2-1.5 46.9-1.4 9.8-9.9 32.7-8.2 43.4.5 1 1 2 1.5 3.5.5 4.5 1.5 8.5 4.6 10 7.3 3.6 12-3.5 9.8 11.5-.7 3.1-2.6 12 1.5 15 4.4 3.7 30.6 3.4 36.5.5 2.6-1.5 1.6-4.5 6.4-7.4 1.9-.9 11.3-.4 11.3-6.5.3-1.8-9.2-19.9-9.3-20-2.6-3.5-9.2-4.5-11.3-8-6.9-10.1-1.7-52.6.5-59.4 3-11 5.6-22.4 8.7-32.4 11-42.5 10.3-50.6 16.5-68.3.8-1.8 6.4-23.1 10.3-29.9 9.3-17 21.7-32.4 33.5-47.4 18-22.9 34-46.9 52-69.8 6.1-7 8.2-13.7 18-8 10.8 5.7 21.6 7 31.9 17 14.6 12.8 10.2 18.2 11.8 22.9 1.5 5 7.7 10.5 14.9 9.5 10.4-2 13-2.5 13.4-2.5 2.6-.5 5.7-5 7.2-8 3.1-5.5 7.2-9 7.2-16.5 0-7.7-.4-2.8-20.6-52.9z\"],\n    \"strava\": [384, 512, [], \"f428\", \"M158.4 0L7 292h89.2l62.2-116.1L220.1 292h88.5zm150.2 292l-43.9 88.2-44.6-88.2h-67.6l112.2 220 111.5-220z\"],\n    \"stripe\": [640, 512, [], \"f429\", \"M165 144.7l-43.3 9.2-.2 142.4c0 26.3 19.8 43.3 46.1 43.3 14.6 0 25.3-2.7 31.2-5.9v-33.8c-5.7 2.3-33.7 10.5-33.7-15.7V221h33.7v-37.8h-33.7zm89.1 51.6l-2.7-13.1H213v153.2h44.3V233.3c10.5-13.8 28.2-11.1 33.9-9.3v-40.8c-6-2.1-26.7-6-37.1 13.1zm92.3-72.3l-44.6 9.5v36.2l44.6-9.5zM44.9 228.3c0-6.9 5.8-9.6 15.1-9.7 13.5 0 30.7 4.1 44.2 11.4v-41.8c-14.7-5.8-29.4-8.1-44.1-8.1-36 0-60 18.8-60 50.2 0 49.2 67.5 41.2 67.5 62.4 0 8.2-7.1 10.9-17 10.9-14.7 0-33.7-6.1-48.6-14.2v40c16.5 7.1 33.2 10.1 48.5 10.1 36.9 0 62.3-15.8 62.3-47.8 0-52.9-67.9-43.4-67.9-63.4zM640 261.6c0-45.5-22-81.4-64.2-81.4s-67.9 35.9-67.9 81.1c0 53.5 30.3 78.2 73.5 78.2 21.2 0 37.1-4.8 49.2-11.5v-33.4c-12.1 6.1-26 9.8-43.6 9.8-17.3 0-32.5-6.1-34.5-26.9h86.9c.2-2.3.6-11.6.6-15.9zm-87.9-16.8c0-20 12.3-28.4 23.4-28.4 10.9 0 22.5 8.4 22.5 28.4zm-112.9-64.6c-17.4 0-28.6 8.2-34.8 13.9l-2.3-11H363v204.8l44.4-9.4.1-50.2c6.4 4.7 15.9 11.2 31.4 11.2 31.8 0 60.8-23.2 60.8-79.6.1-51.6-29.3-79.7-60.5-79.7zm-10.6 122.5c-10.4 0-16.6-3.8-20.9-8.4l-.3-66c4.6-5.1 11-8.8 21.2-8.8 16.2 0 27.4 18.2 27.4 41.4.1 23.9-10.9 41.8-27.4 41.8zm-126.7 33.7h44.6V183.2h-44.6z\"],\n    \"stripe-s\": [384, 512, [], \"f42a\", \"M155.3 154.6c0-22.3 18.6-30.9 48.4-30.9 43.4 0 98.5 13.3 141.9 36.7V26.1C298.3 7.2 251.1 0 203.8 0 88.1 0 11 60.4 11 161.4c0 157.9 216.8 132.3 216.8 200.4 0 26.4-22.9 34.9-54.7 34.9-47.2 0-108.2-19.5-156.1-45.5v128.5a396.09 396.09 0 0 0 156 32.4c118.6 0 200.3-51 200.3-153.6 0-170.2-218-139.7-218-203.9z\"],\n    \"studiovinari\": [512, 512, [], \"f3f8\", \"M480.3 187.7l4.2 28v28l-25.1 44.1-39.8 78.4-56.1 67.5-79.1 37.8-17.7 24.5-7.7 12-9.6 4s17.3-63.6 19.4-63.6c2.1 0 20.3.7 20.3.7l66.7-38.6-92.5 26.1-55.9 36.8-22.8 28-6.6 1.4 20.8-73.6 6.9-5.5 20.7 12.9 88.3-45.2 56.8-51.5 14.8-68.4-125.4 23.3 15.2-18.2-173.4-53.3 81.9-10.5-166-122.9L133.5 108 32.2 0l252.9 126.6-31.5-38L378 163 234.7 64l18.7 38.4-49.6-18.1L158.3 0l194.6 122L310 66.2l108 96.4 12-8.9-21-16.4 4.2-37.8L451 89.1l29.2 24.7 11.5 4.2-7 6.2 8.5 12-13.1 7.4-10.3 20.2 10.5 23.9z\"],\n    \"stumbleupon\": [512, 512, [], \"f1a4\", \"M502.9 266v69.7c0 62.1-50.3 112.4-112.4 112.4-61.8 0-112.4-49.8-112.4-111.3v-70.2l34.3 16 51.1-15.2V338c0 14.7 12 26.5 26.7 26.5S417 352.7 417 338v-72h85.9zm-224.7-58.2l34.3 16 51.1-15.2V173c0-60.5-51.1-109-112.1-109-60.8 0-112.1 48.2-112.1 108.2v162.4c0 14.9-12 26.7-26.7 26.7S86 349.5 86 334.6V266H0v69.7C0 397.7 50.3 448 112.4 448c61.6 0 112.4-49.5 112.4-110.8V176.9c0-14.7 12-26.7 26.7-26.7s26.7 12 26.7 26.7v30.9z\"],\n    \"stumbleupon-circle\": [496, 512, [], \"f1a3\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 177.5c-9.8 0-17.8 8-17.8 17.8v106.9c0 40.9-33.9 73.9-74.9 73.9-41.4 0-74.9-33.5-74.9-74.9v-46.5h57.3v45.8c0 10 8 17.8 17.8 17.8s17.8-7.9 17.8-17.8V200.1c0-40 34.2-72.1 74.7-72.1 40.7 0 74.7 32.3 74.7 72.6v23.7l-34.1 10.1-22.9-10.7v-20.6c.1-9.6-7.9-17.6-17.7-17.6zm167.6 123.6c0 41.4-33.5 74.9-74.9 74.9-41.2 0-74.9-33.2-74.9-74.2V263l22.9 10.7 34.1-10.1v47.1c0 9.8 8 17.6 17.8 17.6s17.8-7.9 17.8-17.6v-48h57.3c-.1 45.9-.1 46.4-.1 46.4z\"],\n    \"superpowers\": [448, 512, [], \"f2dd\", \"M448 32c-83.3 11-166.8 22-250 33-92 12.5-163.3 86.7-169 180-3.3 55.5 18 109.5 57.8 148.2L0 480c83.3-11 166.5-22 249.8-33 91.8-12.5 163.3-86.8 168.7-179.8 3.5-55.5-18-109.5-57.7-148.2L448 32zm-79.7 232.3c-4.2 79.5-74 139.2-152.8 134.5-79.5-4.7-140.7-71-136.3-151 4.5-79.2 74.3-139.3 153-134.5 79.3 4.7 140.5 71 136.1 151z\"],\n    \"supple\": [640, 512, [], \"f3f9\", \"M640 262.5c0 64.1-109 116.1-243.5 116.1-24.8 0-48.6-1.8-71.1-5 7.7.4 15.5.6 23.4.6 134.5 0 243.5-56.9 243.5-127.1 0-29.4-19.1-56.4-51.2-78 60 21.1 98.9 55.1 98.9 93.4zM47.7 227.9c-.1-70.2 108.8-127.3 243.3-127.6 7.9 0 15.6.2 23.3.5-22.5-3.2-46.3-4.9-71-4.9C108.8 96.3-.1 148.5 0 212.6c.1 38.3 39.1 72.3 99.3 93.3-32.3-21.5-51.5-48.6-51.6-78zm60.2 39.9s10.5 13.2 29.3 13.2c17.9 0 28.4-11.5 28.4-25.1 0-28-40.2-25.1-40.2-39.7 0-5.4 5.3-9.1 12.5-9.1 5.7 0 11.3 2.6 11.3 6.6v3.9h14.2v-7.9c0-12.1-15.4-16.8-25.4-16.8-16.5 0-28.5 10.2-28.5 24.1 0 26.6 40.2 25.4 40.2 39.9 0 6.6-5.8 10.1-12.3 10.1-11.9 0-20.7-10.1-20.7-10.1l-8.8 10.9zm120.8-73.6v54.4c0 11.3-7.1 17.8-17.8 17.8-10.7 0-17.8-6.5-17.8-17.7v-54.5h-15.8v55c0 18.9 13.4 31.9 33.7 31.9 20.1 0 33.4-13 33.4-31.9v-55h-15.7zm34.4 85.4h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.8-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5.1 14.7-14 14.7h-12.6zm57 43h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.7-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5 14.7-14 14.7h-12.6zm57.1 34.8c0 5.8 2.4 8.2 8.2 8.2h37.6c5.8 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-18.6c-1.7 0-2.6-1-2.6-2.6v-61.2c0-5.7-2.4-8.2-8.2-8.2H401v13.4h5.2c1.7 0 2.6 1 2.6 2.6v61.2zm63.4 0c0 5.8 2.4 8.2 8.2 8.2H519c5.7 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-19.7c-1.7 0-2.6-1-2.6-2.6v-20.3h27.7v-13.4H488v-22.4h19.2c1.7 0 2.6 1 2.6 2.6v5.2H524v-13c0-5.7-2.5-8.2-8.2-8.2h-51.6v13.4h7.8v63.9zm58.9-76v5.9h1.6v-5.9h2.7v-1.2h-7v1.2h2.7zm5.7-1.2v7.1h1.5v-5.7l2.3 5.7h1.3l2.3-5.7v5.7h1.5v-7.1h-2.3l-2.1 5.1-2.1-5.1h-2.4z\"],\n    \"suse\": [640, 512, [], \"f7d6\", \"M471.08 102.66s-.3 18.3-.3 20.3c-9.1-3-74.4-24.1-135.7-26.3-51.9-1.8-122.8-4.3-223 57.3-19.4 12.4-73.9 46.1-99.6 109.7C7 277-.12 307 7 335.06a111 111 0 0 0 16.5 35.7c17.4 25 46.6 41.6 78.1 44.4 44.4 3.9 78.1-16 90-53.3 8.2-25.8 0-63.6-31.5-82.9-25.6-15.7-53.3-12.1-69.2-1.6-13.9 9.2-21.8 23.5-21.6 39.2.3 27.8 24.3 42.6 41.5 42.6a49 49 0 0 0 15.8-2.7c6.5-1.8 13.3-6.5 13.3-14.9 0-12.1-11.6-14.8-16.8-13.9-2.9.5-4.5 2-11.8 2.4-2-.2-12-3.1-12-14V316c.2-12.3 13.2-18 25.5-16.9 32.3 2.8 47.7 40.7 28.5 65.7-18.3 23.7-76.6 23.2-99.7-20.4-26-49.2 12.7-111.2 87-98.4 33.2 5.7 83.6 35.5 102.4 104.3h45.9c-5.7-17.6-8.9-68.3 42.7-68.3 56.7 0 63.9 39.9 79.8 68.3H460c-12.8-18.3-21.7-38.7-18.9-55.8 5.6-33.8 39.7-18.4 82.4-17.4 66.5.4 102.1-27 103.1-28 3.7-3.1 6.5-15.8 7-17.7 1.3-5.1-3.2-2.4-3.2-2.4-8.7 5.2-30.5 15.2-50.9 15.6-25.3.5-76.2-25.4-81.6-28.2-.3-.4.1 1.2-11-25.5 88.4 58.3 118.3 40.5 145.2 21.7.8-.6 4.3-2.9 3.6-5.7-13.8-48.1-22.4-62.7-34.5-69.6-37-21.6-125-34.7-129.2-35.3.1-.1-.9-.3-.9.7zm60.4 72.8a37.54 37.54 0 0 1 38.9-36.3c33.4 1.2 48.8 42.3 24.4 65.2-24.2 22.7-64.4 4.6-63.3-28.9zm38.6-25.3a26.27 26.27 0 1 0 25.4 27.2 26.19 26.19 0 0 0-25.4-27.2zm4.3 28.8c-15.4 0-15.4-15.6 0-15.6s15.4 15.64 0 15.64z\"],\n    \"symfony\": [512, 512, [], \"f83d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm133.74 143.54c-11.47.41-19.4-6.45-19.77-16.87-.27-9.18 6.68-13.44 6.53-18.85-.23-6.55-10.16-6.82-12.87-6.67-39.78 1.29-48.59 57-58.89 113.85 21.43 3.15 36.65-.72 45.14-6.22 12-7.75-3.34-15.72-1.42-24.56 4-18.16 32.55-19 32 5.3-.36 17.86-25.92 41.81-77.6 35.7-10.76 59.52-18.35 115-58.2 161.72-29 34.46-58.4 39.82-71.58 40.26-24.65.85-41-12.31-41.58-29.84-.56-17 14.45-26.26 24.31-26.59 21.89-.75 30.12 25.67 14.88 34-12.09 9.71.11 12.61 2.05 12.55 10.42-.36 17.34-5.51 22.18-9 24-20 33.24-54.86 45.35-118.35 8.19-49.66 17-78 18.23-82-16.93-12.75-27.08-28.55-49.85-34.72-15.61-4.23-25.12-.63-31.81 7.83-7.92 10-5.29 23 2.37 30.7l12.63 14c15.51 17.93 24 31.87 20.8 50.62-5.06 29.93-40.72 52.9-82.88 39.94-36-11.11-42.7-36.56-38.38-50.62 7.51-24.15 42.36-11.72 34.62 13.6-2.79 8.6-4.92 8.68-6.28 13.07-4.56 14.77 41.85 28.4 51-1.39 4.47-14.52-5.3-21.71-22.25-39.85-28.47-31.75-16-65.49 2.95-79.67C204.23 140.13 251.94 197 262 205.29c37.17-109 100.53-105.46 102.43-105.53 25.16-.81 44.19 10.59 44.83 28.65.25 7.69-4.17 22.59-19.52 23.13z\"],\n    \"teamspeak\": [512, 512, [], \"f4f9\", \"M244.2 346.79c2.4-12.3-12-30-32.4-48.7-20.9-19.2-48.2-39.1-63.4-46.6-21.7-12-41.7-1.8-46.3 22.7-5 26.2 0 51.4 14.5 73.9 10.2 15.5 25.4 22.7 43.4 24 11.6.6 52.5 2.2 61.7-1 11.9-4.3 20.1-11.8 22.5-24.3zm205 20.8a5.22 5.22 0 0 0-8.3 2.4c-8 25.4-44.7 112.5-172.1 121.5-149.7 10.5 80.3 43.6 145.4-6.4 22.7-17.4 47.6-35 46.6-85.4-.4-10.1-4.9-26.69-11.6-32.1zm62-122.4c-.3-18.9-8.6-33.4-26-42.2-2.9-1.3-5-2.7-5.9-6.4A222.64 222.64 0 0 0 438.9 103c-1.1-1.5-3.5-3.2-2.2-5 8.5-11.5-.3-18-7-24.4Q321.4-31.11 177.4 13.09c-40.1 12.3-73.9 35.6-102 67.4-4 4.3-6.7 9.1-3 14.5 3 4 1.3 6.2-1 9.3C51.6 132 38.2 162.59 32.1 196c-.7 4.3-2.9 6-6.4 7.8-14.2 7-22.5 18.5-24.9 34L0 264.29v20.9c0 30.8 21 50.4 51.8 49 7.7-.3 11.7-4.3 12-11.5 2-77.5-2.4-95.4 3.7-125.8C92.1 72.39 234.3 5 345.3 65.39 411.4 102 445.7 159 447.6 234.79c.8 28.2 0 56.5 0 84.6 0 7 2.2 12.5 9.4 14.2 24.1 5 49.2-12 53.2-36.7 2.9-17.1 1-34.5 1-51.7zm-159.6 131.5c36.5 2.8 59.3-28.5 58.4-60.5-2.1-45.2-66.2-16.5-87.8-8-73.2 28.1-45 54.9-22.2 60.8z\"],\n    \"telegram\": [496, 512, [], \"f2c6\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm121.8 169.9l-40.7 191.8c-3 13.6-11.1 16.9-22.4 10.5l-62-45.7-29.9 28.8c-3.3 3.3-6.1 6.1-12.5 6.1l4.4-63.1 114.9-103.8c5-4.4-1.1-6.9-7.7-2.5l-142 89.4-61.2-19.1c-13.3-4.2-13.6-13.3 2.8-19.7l239.1-92.2c11.1-4 20.8 2.7 17.2 19.5z\"],\n    \"telegram-plane\": [448, 512, [], \"f3fe\", \"M446.7 98.6l-67.6 318.8c-5.1 22.5-18.4 28.1-37.3 17.5l-103-75.9-49.7 47.8c-5.5 5.5-10.1 10.1-20.7 10.1l7.4-104.9 190.9-172.5c8.3-7.4-1.8-11.5-12.9-4.1L117.8 284 16.2 252.2c-22.1-6.9-22.5-22.1 4.6-32.7L418.2 66.4c18.4-6.9 34.5 4.1 28.5 32.2z\"],\n    \"tencent-weibo\": [384, 512, [], \"f1d5\", \"M72.3 495.8c1.4 19.9-27.6 22.2-29.7 2.9C31 368.8 73.7 259.2 144 185.5c-15.6-34 9.2-77.1 50.6-77.1 30.3 0 55.1 24.6 55.1 55.1 0 44-49.5 70.8-86.9 45.1-65.7 71.3-101.4 169.8-90.5 287.2zM192 .1C66.1.1-12.3 134.3 43.7 242.4 52.4 259.8 79 246.9 70 229 23.7 136.4 91 29.8 192 29.8c75.4 0 136.9 61.4 136.9 136.9 0 90.8-86.9 153.9-167.7 133.1-19.1-4.1-25.6 24.4-6.6 29.1 110.7 23.2 204-60 204-162.3C358.6 74.7 284 .1 192 .1z\"],\n    \"the-red-yeti\": [512, 512, [], \"f69d\", \"M488.23 241.7l20.7 7.1c-9.6-23.9-23.9-37-31.7-44.8l7.1-18.2c.2 0 12.3-27.8-2.5-30.7-.6-11.3-6.6-27-18.4-27-7.6-10.6-17.7-12.3-30.7-5.9a122.2 122.2 0 0 0-25.3 16.5c-5.3-6.4-3 .4-3-29.8-37.1-24.3-45.4-11.7-74.8 3l.5.5a239.36 239.36 0 0 0-68.4-13.3c-5.5-8.7-18.6-19.1-25.1-25.1l24.8 7.1c-5.5-5.5-26.8-12.9-34.2-15.2 18.2-4.1 29.8-20.8 42.5-33-34.9-10.1-67.9-5.9-97.9 11.8l12-44.2L182 0c-31.6 24.2-33 41.9-33.7 45.5-.9-2.4-6.3-19.6-15.2-27a35.12 35.12 0 0 0-.5 25.3c3 8.4 5.9 14.8 8.4 18.9-16-3.3-28.3-4.9-49.2 0h-3.7l33 14.3a194.26 194.26 0 0 0-46.7 67.4l-1.7 8.4 1.7 1.7 7.6-4.7c-3.3 11.6-5.3 19.4-6.6 25.8a200.18 200.18 0 0 0-27.8 40.3c-15 1-31.8 10.8-40.3 14.3l3 3.4 28.8 1c-.5 1-.7 2.2-1.2 3.2-7.3 6.4-39.8 37.7-33 80.7l20.2-22.4c.5 1.7.7 3.4 1.2 5.2 0 25.5.4 89.6 64.9 150.5 43.6 40 96 60.2 157.5 60.2 121.7 0 223-87.3 223-211.5 6.8-9.7-1.2 3 16.7-25.1l13 14.3 2.5-.5A181.84 181.84 0 0 0 495 255a44.74 44.74 0 0 0-6.8-13.3zM398 111.2l-.5 21.9c5.5 18.1 16.9 17.2 22.4 17.2l-3.4-4.7 22.4-5.4a242.44 242.44 0 0 1-27 0c12.8-2.1 33.3-29 43-11.3 3.4 7.6 6.4 17.2 9.3 27.8l1.7-5.9a56.38 56.38 0 0 1-1.7-15.2c5.4.5 8.8 3.4 9.3 10.1.5 6.4 1.7 14.8 3.4 25.3l4.7-11.3c4.6 0 4.5-3.6-2.5 20.7-20.9-8.7-35.1-8.4-46.5-8.4l18.2-16c-25.3 8.2-33 10.8-54.8 20.9-1.1-5.4-5-13.5-16-19.9-3.2 3.8-2.8.9-.7 14.8h-2.5a62.32 62.32 0 0 0-8.4-23.1l4.2-3.4c8.4-7.1 11.8-14.3 10.6-21.9-.5-6.4-5.4-13.5-13.5-20.7 5.6-3.4 15.2-.4 28.3 8.5zm-39.6-10.1c2.7 1.9 11.4 5.4 18.9 17.2 4.2 8.4 4 9.8 3.4 11.1-.5 2.4-.5 4.3-3 7.1-1.7 2.5-5.4 4.7-11.8 7.6-7.6-13-16.5-23.6-27.8-31.2zM91 143.1l1.2-1.7c1.2-2.9 4.2-7.6 9.3-15.2l2.5-3.4-13 12.3 5.4-4.7-10.1 9.3-4.2 1.2c12.3-24.1 23.1-41.3 32.5-50.2 9.3-9.3 16-16 20.2-19.4l-6.4 1.2c-11.3-4.2-19.4-7.1-24.8-8.4 2.5-.5 3.7-.5 3.2-.5 10.3 0 17.5.5 20.9 1.2a52.35 52.35 0 0 0 16 2.5l.5-1.7-8.4-35.8 13.5 29a42.89 42.89 0 0 0 5.9-14.3c1.7-6.4 5.4-13 10.1-19.4s7.6-10.6 9.3-11.3a234.68 234.68 0 0 0-6.4 25.3l-1.7 7.1-.5 4.7 2.5 2.5C190.4 39.9 214 34 239.8 34.5l21.1.5c-11.8 13.5-27.8 21.9-48.5 24.8a201.26 201.26 0 0 1-23.4 2.9l-.2-.5-2.5-1.2a20.75 20.75 0 0 0-14 2c-2.5-.2-4.9-.5-7.1-.7l-2.5 1.7.5 1.2c2 .2 3.9.5 6.2.7l-2 3.4 3.4-.5-10.6 11.3c-4.2 3-5.4 6.4-4.2 9.3l5.4-3.4h1.2a39.4 39.4 0 0 1 25.3-15.2v-3c6.4.5 13 1 19.4 1.2 6.4 0 8.4.5 5.4 1.2a189.6 189.6 0 0 1 20.7 13.5c13.5 10.1 23.6 21.9 30 35.4 8.8 18.2 13.5 37.1 13.5 56.6a141.13 141.13 0 0 1-3 28.3 209.91 209.91 0 0 1-16 46l2.5.5c18.2-19.7 41.9-16 49.2-16l-6.4 5.9 22.4 17.7-1.7 30.7c-5.4-12.3-16.5-21.1-33-27.8 16.5 14.8 23.6 21.1 21.9 20.2-4.8-2.8-3.5-1.9-10.8-3.7 4.1 4.1 17.5 18.8 18.2 20.7l.2.2-.2.2c0 1.8 1.6-1.2-14 22.9-75.2-15.3-106.27-42.7-141.2-63.2l11.8 1.2c-11.8-18.5-15.6-17.7-38.4-26.1L149 225c-8.8-3-18.2-3-28.3.5l7.6-10.6-1.2-1.7c-14.9 4.3-19.8 9.2-22.6 11.3-1.1-5.5-2.8-12.4-12.3-28.8l-1.2 27-13.2-5c1.5-25.2 5.4-50.5 13.2-74.6zm276.5 330c-49.9 25-56.1 22.4-59 23.9-29.8-11.8-50.9-31.7-63.5-58.8l30 16.5c-9.8-9.3-18.3-16.5-38.4-44.3l11.8 23.1-17.7-7.6c14.2 21.1 23.5 51.7 66.6 73.5-120.8 24.2-199-72.1-200.9-74.3a262.57 262.57 0 0 0 35.4 24.8c3.4 1.7 7.1 2.5 10.1 1.2l-16-20.7c9.2 4.2 9.5 4.5 69.1 29-42.5-20.7-73.8-40.8-93.2-60.2-.5 6.4-1.2 10.1-1.2 10.1a80.25 80.25 0 0 1 20.7 26.6c-39-18.9-57.6-47.6-71.3-82.6 49.9 55.1 118.9 37.5 120.5 37.1 34.8 16.4 69.9 23.6 113.9 10.6 3.3 0 20.3 17 25.3 39.1l4.2-3-2.5-23.6c9 9 24.9 22.6 34.4 13-15.6-5.3-23.5-9.5-29.5-31.7 4.6 4.2 7.6 9 27.8 15l1.2-1.2-10.5-14.2c11.7-4.8-3.5 1 32-10.8 4.3 34.3 9 49.2.7 89.5zm115.3-214.4l-2.5.5 3 9.3c-3.5 5.9-23.7 44.3-71.6 79.7-39.5 29.8-76.6 39.1-80.9 40.3l-7.6-7.1-1.2 3 14.3 16-7.1-4.7 3.4 4.2h-1.2l-21.9-13.5 9.3 26.6-19-27.9-1.2 2.5 7.6 29c-6.1-8.2-21-32.6-56.8-39.6l32.5 21.2a214.82 214.82 0 0 1-93.2-6.4c-4.2-1.2-8.9-2.5-13.5-4.2l1.2-3-44.8-22.4 26.1 22.4c-57.7 9.1-113-25.4-126.4-83.4l-2.5-16.4-22.27 22.3c19.5-57.5 25.6-57.9 51.4-70.1-9.1-5.3-1.6-3.3-38.4-9.3 15.8-5.8 33-15.4 73 5.2a18.5 18.5 0 0 1 3.7-1.7c.6-3.2.4-.8 1-11.8 3.9 10 3.6 8.7 3 9.3l1.7.5c12.7-6.5 8.9-4.5 17-8.9l-5.4 13.5 22.3-5.8-8.4 8.4 2.5 2.5c4.5-1.8 30.3 3.4 40.8 16l-23.6-2.5c39.4 23 51.5 54 55.8 69.6l1.7-1.2c-2.8-22.3-12.4-33.9-16-40.1 4.2 5 39.2 34.6 110.4 46-11.3-.5-23.1 5.4-34.9 18.9l46.7-20.2-9.3 21.9c7.6-10.1 14.8-23.6 21.2-39.6v-.5l1.2-3-1.2 16c13.5-41.8 25.3-78.5 35.4-109.7l13.5-27.8v-2l-5.4-4.2h10.1l5.9 4.2 2.5-1.2-3.4-16 12.3 18.9 41.8-20.2-14.8 13 .5 2.9 17.7-.5a184 184 0 0 1 33 4.2l-23.6 2.5-1.2 3 26.6 23.1a254.21 254.21 0 0 1 27 32c-11.2-3.3-10.3-3.4-21.2-3.4l12.3 32.5zm-6.1-71.3l-3.9 13-14.3-11.8zm-254.8 7.1c1.7 10.6 4.7 17.7 8.8 21.9-9.3 6.6-27.5 13.9-46.5 16l.5 1.2a50.22 50.22 0 0 0 24.8-2.5l-7.1 13c4.2-1.7 10.1-7.1 17.7-14.8 11.9-5.5 12.7-5.1 20.2-16-12.7-6.4-15.7-13.7-18.4-18.8zm3.7-102.3c-6.4-3.4-10.6 3-12.3 18.9s2.5 29.5 11.8 39.6 18.2 10.6 26.1 3 3.4-23.6-11.3-47.7a39.57 39.57 0 0 0-14.27-13.8zm-4.7 46.3c5.4 2.2 10.5 1.9 12.3-10.6v-4.7l-1.2.5c-4.3-3.1-2.5-4.5-1.7-6.2l.5-.5c-.9-1.2-5-8.1-12.5 4.7-.5-13.5.5-21.9 3-24.8 1.2-2.5 4.7-1.2 11.3 4.2 6.4 5.4 11.3 16 15.2 32.5 6.5 28-19.8 26.2-26.9 4.9zm-45-5.5c1.6.3 9.3-1.1 9.3-14.8h-.5c-5.4-1.1-2.2-5.5-.7-5.9-1.7-3-3.4-4.2-5.4-4.7-8.1 0-11.6 12.7-8.1 21.2a7.51 7.51 0 0 0 5.43 4.2zM216 82.9l-2.5.5.5 3a48.94 48.94 0 0 1 26.1 5.9c-2.5-5.5-10-14.3-28.3-14.3l.5 2.5zm-71.8 49.4c21.7 16.8 16.5 21.4 46.5 23.6l-2.9-4.7a42.67 42.67 0 0 0 14.8-28.3c1.7-16-1.2-29.5-8.8-41.3l13-7.6a2.26 2.26 0 0 0-.5-1.7 14.21 14.21 0 0 0-13.5 1.7c-12.7 6.7-28 20.9-29 22.4-1.7 1.7-3.4 5.9-5.4 13.5a99.61 99.61 0 0 0-2.9 23.6c-4.7-8-10.5-6.4-19.9-5.9l7.1 7.6c-16.5 0-23.3 15.4-23.6 16 6.8 0 4.6-7.6 30-12.3-4.3-6.3-3.3-5-4.9-6.6zm18.7-18.7c1.2-7.6 3.4-13 6.4-17.2 5.4-6.4 10.6-10.1 16-11.8 4.2-1.7 7.1 1.2 10.1 9.3a72.14 72.14 0 0 1 3 25.3c-.5 9.3-3.4 17.2-8.4 23.1-2.9 3.4-5.4 5.9-6.4 7.6a39.21 39.21 0 0 1-11.3-.5l-7.1-3.4-5.4-6.4c.8-10 1.3-18.8 3.1-26zm42 56.1c-34.8 14.4-34.7 14-36.1 14.3-20.8 4.7-19-24.4-18.9-24.8l5.9-1.2-.5-2.5c-20.2-2.6-31 4.2-32.5 4.9.5.5 3 3.4 5.9 9.3 4.2-6.4 8.8-10.1 15.2-10.6a83.47 83.47 0 0 0 1.7 33.7c.1.5 2.6 17.4 27.5 24.1 11.3 3 27 1.2 48.9-5.4l-9.2.5c-4.2-14.8-6.4-24.8-5.9-29.5 11.3-8.8 21.9-11.3 30.7-7.6h2.5l-11.8-7.6-7.1.5c-5.9 1.2-12.3 4.2-19.4 8.4z\"],\n    \"themeco\": [448, 512, [], \"f5c6\", \"M202.9 8.43c9.9-5.73 26-5.82 35.95-.21L430 115.85c10 5.6 18 19.44 18 30.86V364c0 11.44-8.06 25.29-18 31L238.81 503.74c-9.93 5.66-26 5.57-35.85-.21L17.86 395.12C8 389.34 0 375.38 0 364V146.71c0-11.44 8-25.36 17.91-31.08zm-77.4 199.83c-15.94 0-31.89.14-47.83.14v101.45H96.8V280h28.7c49.71 0 49.56-71.74 0-71.74zm140.14 100.29l-30.73-34.64c37-7.51 34.8-65.23-10.87-65.51-16.09 0-32.17-.14-48.26-.14v101.59h19.13v-33.91h18.41l29.56 33.91h22.76zm-41.59-82.32c23.34 0 23.26 32.46 0 32.46h-29.13v-32.46zm-95.56-1.6c21.18 0 21.11 38.85 0 38.85H96.18v-38.84zm192.65-18.25c-68.46 0-71 105.8 0 105.8 69.48-.01 69.41-105.8 0-105.8zm0 17.39c44.12 0 44.8 70.86 0 70.86s-44.43-70.86 0-70.86z\"],\n    \"themeisle\": [512, 512, [], \"f2b2\", \"M208 88.286c0-10 6.286-21.714 17.715-21.714 11.142 0 17.714 11.714 17.714 21.714 0 10.285-6.572 21.714-17.714 21.714C214.286 110 208 98.571 208 88.286zm304 160c0 36.001-11.429 102.286-36.286 129.714-22.858 24.858-87.428 61.143-120.857 70.572l-1.143.286v32.571c0 16.286-12.572 30.571-29.143 30.571-10 0-19.429-5.714-24.572-14.286-5.427 8.572-14.856 14.286-24.856 14.286-10 0-19.429-5.714-24.858-14.286-5.142 8.572-14.571 14.286-24.57 14.286-10.286 0-19.429-5.714-24.858-14.286-5.143 8.572-14.571 14.286-24.571 14.286-18.857 0-29.429-15.714-29.429-32.857-16.286 12.285-35.715 19.428-56.571 19.428-22 0-43.429-8.285-60.286-22.857 10.285-.286 20.571-2.286 30.285-5.714-20.857-5.714-39.428-18.857-52-36.286 21.37 4.645 46.209 1.673 67.143-11.143-22-22-56.571-58.857-68.572-87.428C1.143 321.714 0 303.714 0 289.429c0-49.714 20.286-160 86.286-160 10.571 0 18.857 4.858 23.143 14.857a158.792 158.792 0 0 1 12-15.428c2-2.572 5.714-5.429 7.143-8.286 7.999-12.571 11.714-21.142 21.714-34C182.571 45.428 232 17.143 285.143 17.143c6 0 12 .285 17.714 1.143C313.714 6.571 328.857 0 344.572 0c14.571 0 29.714 6 40 16.286.857.858 1.428 2.286 1.428 3.428 0 3.714-10.285 13.429-12.857 16.286 4.286 1.429 15.714 6.858 15.714 12 0 2.857-2.857 5.143-4.571 7.143 31.429 27.714 49.429 67.143 56.286 108 4.286-5.143 10.285-8.572 17.143-8.572 10.571 0 20.857 7.144 28.571 14.001C507.143 187.143 512 221.714 512 248.286zM188 89.428c0 18.286 12.571 37.143 32.286 37.143 19.714 0 32.285-18.857 32.285-37.143 0-18-12.571-36.857-32.285-36.857-19.715 0-32.286 18.858-32.286 36.857zM237.714 194c0-19.714 3.714-39.143 8.571-58.286-52.039 79.534-13.531 184.571 68.858 184.571 21.428 0 42.571-7.714 60-20 2-7.429 3.714-14.857 3.714-22.572 0-14.286-6.286-21.428-20.572-21.428-4.571 0-9.143.857-13.429 1.714-63.343 12.668-107.142 3.669-107.142-63.999zm-41.142 254.858c0-11.143-8.858-20.857-20.286-20.857-11.429 0-20 9.715-20 20.857v32.571c0 11.143 8.571 21.142 20 21.142 11.428 0 20.286-9.715 20.286-21.142v-32.571zm49.143 0c0-11.143-8.572-20.857-20-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20-10 20-21.142v-32.571zm49.713 0c0-11.143-8.857-20.857-20.285-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20.285-9.715 20.285-21.142v-32.571zm49.715 0c0-11.143-8.857-20.857-20.286-20.857-11.428 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.858 21.142 20.286 21.142 11.429 0 20.286-10 20.286-21.142v-32.571zM421.714 286c-30.857 59.142-90.285 102.572-158.571 102.572-96.571 0-160.571-84.572-160.571-176.572 0-16.857 2-33.429 6-49.714-20 33.715-29.714 72.572-29.714 111.429 0 60.286 24.857 121.715 71.429 160.857 5.143-9.714 14.857-16.286 26-16.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.571-14.286 24.858-14.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.857-14.286 24.858-14.286 10 0 19.428 5.714 24.857 14.286 5.143-8.571 14.571-14.286 24.572-14.286 10.857 0 20.857 6.572 25.714 16 43.427-36.286 68.569-92 71.426-148.286zm10.572-99.714c0-53.714-34.571-105.714-92.572-105.714-30.285 0-58.571 15.143-78.857 36.857C240.862 183.812 233.41 254 302.286 254c28.805 0 97.357-28.538 84.286 36.857 28.857-26 45.714-65.714 45.714-104.571z\"],\n    \"think-peaks\": [576, 512, [], \"f731\", \"M465.4 409.4l87.1-150.2-32-.3-55.1 95L259.2 0 23 407.4l32 .3L259.2 55.6zm-355.3-44.1h32.1l117.4-202.5L463 511.9l32.5.1-235.8-404.6z\"],\n    \"trade-federation\": [496, 512, [], \"f513\", \"M248 8.8c-137 0-248 111-248 248s111 248 248 248 248-111 248-248-111-248-248-248zm0 482.8c-129.7 0-234.8-105.1-234.8-234.8S118.3 22 248 22s234.8 105.1 234.8 234.8S377.7 491.6 248 491.6zm155.1-328.5v-46.8H209.3V198H54.2l36.7 46h117.7v196.8h48.8V245h83.3v-47h-83.3v-34.8h145.7zm-73.3 45.1v23.9h-82.9v197.4h-26.8V232.1H96.3l-20.1-23.9h143.9v-80.6h171.8V152h-145v56.2zm-161.3-69l-12.4-20.7 2.1 23.8-23.5 5.4 23.3 5.4-2.1 24 12.3-20.5 22.2 9.5-15.7-18.1 15.8-18.1zm-29.6-19.7l9.3-11.5-12.7 5.9-8-12.4 1.7 13.9-14.3 3.8 13.7 2.7-.8 14.7 6.8-12.2 13.8 5.3zm165.4 145.2l-13.1 5.6-7.3-12.2 1.3 14.2-13.9 3.2 13.9 3.2-1.2 14.2 7.3-12.2 13.1 5.5-9.4-10.7zm106.9-77.2l-20.9 9.1-12-19.6 2.2 22.7-22.3 5.4 22.2 4.9-1.8 22.9 11.5-19.6 21.2 8.8-15.1-17zM248 29.9c-125.3 0-226.9 101.6-226.9 226.9S122.7 483.7 248 483.7s226.9-101.6 226.9-226.9S373.3 29.9 248 29.9zM342.6 196v51h-83.3v195.7h-52.7V245.9H89.9l-40-49.9h157.4v-81.6h197.8v50.7H259.4V196zM248 43.2c60.3 0 114.8 25 153.6 65.2H202.5V190H45.1C73.1 104.8 153.4 43.2 248 43.2zm0 427.1c-117.9 0-213.6-95.6-213.6-213.5 0-21.2 3.1-41.8 8.9-61.1L87.1 252h114.7v196.8h64.6V253h83.3v-62.7h-83.2v-19.2h145.6v-50.8c30.8 37 49.3 84.6 49.3 136.5.1 117.9-95.5 213.5-213.4 213.5zM178.8 275l-11-21.4 1.7 24.5-23.7 3.9 23.8 5.9-3.7 23.8 13-20.9 21.5 10.8-15.8-18.8 16.9-17.1z\"],\n    \"trello\": [448, 512, [], \"f181\", \"M392.3 32H56.1C25.1 32 0 57.1 0 88c-.1 0 0-4 0 336 0 30.9 25.1 56 56 56h336.2c30.8-.2 55.7-25.2 55.7-56V88c.1-30.8-24.8-55.8-55.6-56zM197 371.3c-.2 14.7-12.1 26.6-26.9 26.6H87.4c-14.8.1-26.9-11.8-27-26.6V117.1c0-14.8 12-26.9 26.9-26.9h82.9c14.8 0 26.9 12 26.9 26.9v254.2zm193.1-112c0 14.8-12 26.9-26.9 26.9h-81c-14.8 0-26.9-12-26.9-26.9V117.2c0-14.8 12-26.9 26.8-26.9h81.1c14.8 0 26.9 12 26.9 26.9v142.1z\"],\n    \"tripadvisor\": [576, 512, [], \"f262\", \"M166.4 280.521c0 13.236-10.73 23.966-23.966 23.966s-23.966-10.73-23.966-23.966 10.73-23.966 23.966-23.966 23.966 10.729 23.966 23.966zm264.962-23.956c-13.23 0-23.956 10.725-23.956 23.956 0 13.23 10.725 23.956 23.956 23.956 13.23 0 23.956-10.725 23.956-23.956-.001-13.231-10.726-23.956-23.956-23.956zm89.388 139.49c-62.667 49.104-153.276 38.109-202.379-24.559l-30.979 46.325-30.683-45.939c-48.277 60.39-135.622 71.891-197.885 26.055-64.058-47.158-77.759-137.316-30.601-201.374A186.762 186.762 0 0 0 0 139.416l90.286-.05a358.48 358.48 0 0 1 197.065-54.03 350.382 350.382 0 0 1 192.181 53.349l96.218.074a185.713 185.713 0 0 0-28.352 57.649c46.793 62.747 34.964 151.37-26.648 199.647zM259.366 281.761c-.007-63.557-51.535-115.075-115.092-115.068C80.717 166.7 29.2 218.228 29.206 281.785c.007 63.557 51.535 115.075 115.092 115.068 63.513-.075 114.984-51.539 115.068-115.052v-.04zm28.591-10.455c5.433-73.44 65.51-130.884 139.12-133.022a339.146 339.146 0 0 0-139.727-27.812 356.31 356.31 0 0 0-140.164 27.253c74.344 1.582 135.299 59.424 140.771 133.581zm251.706-28.767c-21.992-59.634-88.162-90.148-147.795-68.157-59.634 21.992-90.148 88.162-68.157 147.795v.032c22.038 59.607 88.198 90.091 147.827 68.113 59.615-22.004 90.113-88.162 68.125-147.783zm-326.039 37.975v.115c-.057 39.328-31.986 71.163-71.314 71.106-39.328-.057-71.163-31.986-71.106-71.314.057-39.328 31.986-71.163 71.314-71.106 39.259.116 71.042 31.94 71.106 71.199zm-24.512 0v-.084c-.051-25.784-20.994-46.645-46.778-46.594-25.784.051-46.645 20.994-46.594 46.777.051 25.784 20.994 46.645 46.777 46.594 25.726-.113 46.537-20.968 46.595-46.693zm313.423 0v.048c-.02 39.328-31.918 71.194-71.247 71.173s-71.194-31.918-71.173-71.247c.02-39.328 31.918-71.194 71.247-71.173 39.29.066 71.121 31.909 71.173 71.199zm-24.504-.008c-.009-25.784-20.918-46.679-46.702-46.67-25.784.009-46.679 20.918-46.67 46.702.009 25.784 20.918 46.678 46.702 46.67 25.765-.046 46.636-20.928 46.67-46.693v-.009z\"],\n    \"tumblr\": [320, 512, [], \"f173\", \"M309.8 480.3c-13.6 14.5-50 31.7-97.4 31.7-120.8 0-147-88.8-147-140.6v-144H17.9c-5.5 0-10-4.5-10-10v-68c0-7.2 4.5-13.6 11.3-16 62-21.8 81.5-76 84.3-117.1.8-11 6.5-16.3 16.1-16.3h70.9c5.5 0 10 4.5 10 10v115.2h83c5.5 0 10 4.4 10 9.9v81.7c0 5.5-4.5 10-10 10h-83.4V360c0 34.2 23.7 53.6 68 35.8 4.8-1.9 9-3.2 12.7-2.2 3.5.9 5.8 3.4 7.4 7.9l22 64.3c1.8 5 3.3 10.6-.4 14.5z\"],\n    \"tumblr-square\": [448, 512, [], \"f174\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-82.3 364.2c-8.5 9.1-31.2 19.8-60.9 19.8-75.5 0-91.9-55.5-91.9-87.9v-90h-29.7c-3.4 0-6.2-2.8-6.2-6.2v-42.5c0-4.5 2.8-8.5 7.1-10 38.8-13.7 50.9-47.5 52.7-73.2.5-6.9 4.1-10.2 10-10.2h44.3c3.4 0 6.2 2.8 6.2 6.2v72h51.9c3.4 0 6.2 2.8 6.2 6.2v51.1c0 3.4-2.8 6.2-6.2 6.2h-52.1V321c0 21.4 14.8 33.5 42.5 22.4 3-1.2 5.6-2 8-1.4 2.2.5 3.6 2.1 4.6 4.9l13.8 40.2c1 3.2 2 6.7-.3 9.1z\"],\n    \"twitch\": [448, 512, [], \"f1e8\", \"M40.1 32L10 108.9v314.3h107V480h60.2l56.8-56.8h87l117-117V32H40.1zm357.8 254.1L331 353H224l-56.8 56.8V353H76.9V72.1h321v214zM331 149v116.9h-40.1V149H331zm-107 0v116.9h-40.1V149H224z\"],\n    \"twitter\": [512, 512, [], \"f099\", \"M459.37 151.716c.325 4.548.325 9.097.325 13.645 0 138.72-105.583 298.558-298.558 298.558-59.452 0-114.68-17.219-161.137-47.106 8.447.974 16.568 1.299 25.34 1.299 49.055 0 94.213-16.568 130.274-44.832-46.132-.975-84.792-31.188-98.112-72.772 6.498.974 12.995 1.624 19.818 1.624 9.421 0 18.843-1.3 27.614-3.573-48.081-9.747-84.143-51.98-84.143-102.985v-1.299c13.969 7.797 30.214 12.67 47.431 13.319-28.264-18.843-46.781-51.005-46.781-87.391 0-19.492 5.197-37.36 14.294-52.954 51.655 63.675 129.3 105.258 216.365 109.807-1.624-7.797-2.599-15.918-2.599-24.04 0-57.828 46.782-104.934 104.934-104.934 30.213 0 57.502 12.67 76.67 33.137 23.715-4.548 46.456-13.32 66.599-25.34-7.798 24.366-24.366 44.833-46.132 57.827 21.117-2.273 41.584-8.122 60.426-16.243-14.292 20.791-32.161 39.308-52.628 54.253z\"],\n    \"twitter-square\": [448, 512, [], \"f081\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-48.9 158.8c.2 2.8.2 5.7.2 8.5 0 86.7-66 186.6-186.6 186.6-37.2 0-71.7-10.8-100.7-29.4 5.3.6 10.4.8 15.8.8 30.7 0 58.9-10.4 81.4-28-28.8-.6-53-19.5-61.3-45.5 10.1 1.5 19.2 1.5 29.6-1.2-30-6.1-52.5-32.5-52.5-64.4v-.8c8.7 4.9 18.9 7.9 29.6 8.3a65.447 65.447 0 0 1-29.2-54.6c0-12.2 3.2-23.4 8.9-33.1 32.3 39.8 80.8 65.8 135.2 68.6-9.3-44.5 24-80.6 64-80.6 18.9 0 35.9 7.9 47.9 20.7 14.8-2.8 29-8.3 41.6-15.8-4.9 15.2-15.2 28-28.8 36.1 13.2-1.4 26-5.1 37.8-10.2-8.9 13.1-20.1 24.7-32.9 34z\"],\n    \"typo3\": [448, 512, [], \"f42b\", \"M178.7 78.4c0-24.7 5.4-32.4 13.9-39.4-69.5 8.5-149.3 34-176.3 66.4-5.4 7.7-9.3 20.8-9.3 37.1C7 246 113.8 480 191.1 480c36.3 0 97.3-59.5 146.7-139-7 2.3-11.6 2.3-18.5 2.3-57.2 0-140.6-198.5-140.6-264.9zM301.5 32c-30.1 0-41.7 5.4-41.7 36.3 0 66.4 53.8 198.5 101.7 198.5 26.3 0 78.8-99.7 78.8-182.3 0-40.9-67-52.5-138.8-52.5z\"],\n    \"uber\": [448, 512, [], \"f402\", \"M414.1 32H33.9C15.2 32 0 47.2 0 65.9V446c0 18.8 15.2 34 33.9 34H414c18.7 0 33.9-15.2 33.9-33.9V65.9C448 47.2 432.8 32 414.1 32zM237.6 391.1C163 398.6 96.4 344.2 88.9 269.6h94.4V290c0 3.7 3 6.8 6.8 6.8H258c3.7 0 6.8-3 6.8-6.8v-67.9c0-3.7-3-6.8-6.8-6.8h-67.9c-3.7 0-6.8 3-6.8 6.8v20.4H88.9c7-69.4 65.4-122.2 135.1-122.2 69.7 0 128.1 52.8 135.1 122.2 7.5 74.5-46.9 141.1-121.5 148.6z\"],\n    \"ubuntu\": [496, 512, [], \"f7df\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm52.7 93c8.8-15.2 28.3-20.5 43.5-11.7 15.3 8.8 20.5 28.3 11.7 43.6-8.8 15.2-28.3 20.5-43.5 11.7-15.3-8.9-20.5-28.4-11.7-43.6zM87.4 287.9c-17.6 0-31.9-14.3-31.9-31.9 0-17.6 14.3-31.9 31.9-31.9 17.6 0 31.9 14.3 31.9 31.9 0 17.6-14.3 31.9-31.9 31.9zm28.1 3.1c22.3-17.9 22.4-51.9 0-69.9 8.6-32.8 29.1-60.7 56.5-79.1l23.7 39.6c-51.5 36.3-51.5 112.5 0 148.8L172 370c-27.4-18.3-47.8-46.3-56.5-79zm228.7 131.7c-15.3 8.8-34.7 3.6-43.5-11.7-8.8-15.3-3.6-34.8 11.7-43.6 15.2-8.8 34.7-3.6 43.5 11.7 8.8 15.3 3.6 34.8-11.7 43.6zm.3-69.5c-26.7-10.3-56.1 6.6-60.5 35-5.2 1.4-48.9 14.3-96.7-9.4l22.5-40.3c57 26.5 123.4-11.7 128.9-74.4l46.1.7c-2.3 34.5-17.3 65.5-40.3 88.4zm-5.9-105.3c-5.4-62-71.3-101.2-128.9-74.4l-22.5-40.3c47.9-23.7 91.5-10.8 96.7-9.4 4.4 28.3 33.8 45.3 60.5 35 23.1 22.9 38 53.9 40.2 88.5l-46 .6z\"],\n    \"uikit\": [448, 512, [], \"f403\", \"M443.9 128v256L218 512 0 384V169.7l87.6 45.1v117l133.5 75.5 135.8-75.5v-151l-101.1-57.6 87.6-53.1L443.9 128zM308.6 49.1L223.8 0l-88.6 54.8 86 47.3 87.4-53z\"],\n    \"uniregistry\": [384, 512, [], \"f404\", \"M192 480c39.5 0 76.2-11.8 106.8-32.2H85.3C115.8 468.2 152.5 480 192 480zm-89.1-193.1v-12.4H0v12.4c0 2.5 0 5 .1 7.4h103.1c-.2-2.4-.3-4.9-.3-7.4zm20.5 57H8.5c2.6 8.5 5.8 16.8 9.6 24.8h138.3c-12.9-5.7-24.1-14.2-33-24.8zm-17.7-34.7H1.3c.9 7.6 2.2 15 3.9 22.3h109.7c-4-6.9-7.2-14.4-9.2-22.3zm-2.8-69.3H0v17.3h102.9zm0-173.2H0v4.9h102.9zm0-34.7H0v2.5h102.9zm0 69.3H0v7.4h102.9zm0 104H0v14.8h102.9zm0-69.3H0v9.9h102.9zm0 34.6H0V183h102.9zm166.2 160.9h109.7c1.8-7.3 3.1-14.7 3.9-22.3H278.3c-2.1 7.9-5.2 15.4-9.2 22.3zm12-185.7H384V136H281.1zm0 37.2H384v-12.4H281.1zm0-74.3H384v-7.4H281.1zm0-76.7v2.5H384V32zm-203 410.9h227.7c11.8-8.7 22.7-18.6 32.2-29.7H44.9c9.6 11 21.4 21 33.2 29.7zm203-371.3H384v-4.9H281.1zm0 148.5H384v-14.8H281.1zM38.8 405.7h305.3c6.7-8.5 12.6-17.6 17.8-27.2H23c5.2 9.6 9.2 18.7 15.8 27.2zm188.8-37.1H367c3.7-8 5.8-16.2 8.5-24.8h-115c-8.8 10.7-20.1 19.2-32.9 24.8zm53.5-81.7c0 2.5-.1 5-.4 7.4h103.1c.1-2.5.2-4.9.2-7.4v-12.4H281.1zm0-29.7H384v-17.3H281.1z\"],\n    \"untappd\": [640, 512, [], \"f405\", \"M401.3 49.9c-79.8 160.1-84.6 152.5-87.9 173.2l-5.2 32.8c-1.9 12-6.6 23.5-13.7 33.4L145.6 497.1c-7.6 10.6-20.4 16.2-33.4 14.6-40.3-5-77.8-32.2-95.3-68.5-5.7-11.8-4.5-25.8 3.1-36.4l148.9-207.9c7.1-9.9 16.4-18 27.2-23.7l29.3-15.5c18.5-9.8 9.7-11.9 135.6-138.9 1-4.8 1-7.3 3.6-8 3-.7 6.6-1 6.3-4.6l-.4-4.6c-.2-1.9 1.3-3.6 3.2-3.6 4.5-.1 13.2 1.2 25.6 10 12.3 8.9 16.4 16.8 17.7 21.1.6 1.8-.6 3.7-2.4 4.2l-4.5 1.1c-3.4.9-2.5 4.4-2.3 7.4.1 2.8-2.3 3.6-6.5 6.1zM230.1 36.4c3.4.9 2.5 4.4 2.3 7.4-.2 2.7 2.1 3.5 6.4 6 7.9 15.9 15.3 30.5 22.2 44 .7 1.3 2.3 1.5 3.3.5 11.2-12 24.6-26.2 40.5-42.6 1.3-1.4 1.4-3.5.1-4.9-8-8.2-16.5-16.9-25.6-26.1-1-4.7-1-7.3-3.6-8-3-.8-6.6-1-6.3-4.6.3-3.3 1.4-8.1-2.8-8.2-4.5-.1-13.2 1.1-25.6 10-12.3 8.9-16.4 16.8-17.7 21.1-1.4 4.2 3.6 4.6 6.8 5.4zM620 406.7L471.2 198.8c-13.2-18.5-26.6-23.4-56.4-39.1-11.2-5.9-14.2-10.9-30.5-28.9-1-1.1-2.9-.9-3.6.5-46.3 88.8-47.1 82.8-49 94.8-1.7 10.7-1.3 20 .3 29.8 1.9 12 6.6 23.5 13.7 33.4l148.9 207.9c7.6 10.6 20.2 16.2 33.1 14.7 40.3-4.9 78-32 95.7-68.6 5.4-11.9 4.3-25.9-3.4-36.6z\"],\n    \"ups\": [384, 512, [], \"f7e0\", \"M103.2 303c-5.2 3.6-32.6 13.1-32.6-19V180H37.9v102.6c0 74.9 80.2 51.1 97.9 39V180h-32.6zM4 74.82v220.9c0 103.7 74.9 135.2 187.7 184.1 112.4-48.9 187.7-80.2 187.7-184.1V74.82c-116.3-61.6-281.8-49.6-375.4 0zm358.1 220.9c0 86.6-53.2 113.6-170.4 165.3-117.5-51.8-170.5-78.7-170.5-165.3v-126.4c102.3-93.8 231.6-100 340.9-89.8zm-209.6-107.4v212.8h32.7v-68.7c24.4 7.3 71.7-2.6 71.7-78.5 0-97.4-80.7-80.92-104.4-65.6zm32.7 117.3v-100.3c8.4-4.2 38.4-12.7 38.4 49.3 0 67.9-36.4 51.8-38.4 51zm79.1-86.4c.1 47.3 51.6 42.5 52.2 70.4.6 23.5-30.4 23-50.8 4.9v30.1c36.2 21.5 81.9 8.1 83.2-33.5 1.7-51.5-54.1-46.6-53.4-73.2.6-20.3 30.6-20.5 48.5-2.2v-28.4c-28.5-22-79.9-9.2-79.7 31.9z\"],\n    \"usb\": [640, 512, [], \"f287\", \"M641.5 256c0 3.1-1.7 6.1-4.5 7.5L547.9 317c-1.4.8-2.8 1.4-4.5 1.4-1.4 0-3.1-.3-4.5-1.1-2.8-1.7-4.5-4.5-4.5-7.8v-35.6H295.7c25.3 39.6 40.5 106.9 69.6 106.9H392V354c0-5 3.9-8.9 8.9-8.9H490c5 0 8.9 3.9 8.9 8.9v89.1c0 5-3.9 8.9-8.9 8.9h-89.1c-5 0-8.9-3.9-8.9-8.9v-26.7h-26.7c-75.4 0-81.1-142.5-124.7-142.5H140.3c-8.1 30.6-35.9 53.5-69 53.5C32 327.3 0 295.3 0 256s32-71.3 71.3-71.3c33.1 0 61 22.8 69 53.5 39.1 0 43.9 9.5 74.6-60.4C255 88.7 273 95.7 323.8 95.7c7.5-20.9 27-35.6 50.4-35.6 29.5 0 53.5 23.9 53.5 53.5s-23.9 53.5-53.5 53.5c-23.4 0-42.9-14.8-50.4-35.6H294c-29.1 0-44.3 67.4-69.6 106.9h310.1v-35.6c0-3.3 1.7-6.1 4.5-7.8 2.8-1.7 6.4-1.4 8.9.3l89.1 53.5c2.8 1.1 4.5 4.1 4.5 7.2z\"],\n    \"usps\": [576, 512, [], \"f7e1\", \"M460.3 241.7c25.8-41.3 15.2-48.8-11.7-48.8h-27c-.1 0-1.5-1.4-10.9 8-11.2 5.6-37.9 6.3-37.9 8.7 0 4.5 70.3-3.1 88.1 0 9.5 1.5-1.5 20.4-4.4 32-.5 4.5 2.4 2.3 3.8.1zm-112.1 22.6c64-21.3 97.3-23.9 102-26.2 4.4-2.9-4.4-6.6-26.2-5.8-51.7 2.2-137.6 37.1-172.6 53.9l-30.7-93.3h196.6c-2.7-28.2-152.9-22.6-337.9-22.6L27 415.8c196.4-97.3 258.9-130.3 321.2-151.5zM94.7 96c253.3 53.7 330 65.7 332.1 85.2 36.4 0 45.9 0 52.4 6.6 21.1 19.7-14.6 67.7-14.6 67.7-4.4 2.9-406.4 160.2-406.4 160.2h423.1L549 96z\"],\n    \"ussunnah\": [512, 512, [], \"f407\", \"M156.8 285.1l5.7 14.4h-8.2c-1.3-3.2-3.1-7.7-3.8-9.5-2.5-6.3-1.1-8.4 0-10 1.9-2.7 3.2-4.4 3.6-5.2 0 2.2.8 5.7 2.7 10.3zm297.3 18.8c-2.1 13.8-5.7 27.1-10.5 39.7l43 23.4-44.8-18.8c-5.3 13.2-12 25.6-19.9 37.2l34.2 30.2-36.8-26.4c-8.4 11.8-18 22.6-28.7 32.3l24.9 34.7-28.1-31.8c-11 9.6-23.1 18-36.1 25.1l15.7 37.2-19.3-35.3c-13.1 6.8-27 12.1-41.6 15.9l6.7 38.4-10.5-37.4c-14.3 3.4-29.2 5.3-44.5 5.4L256 512l-1.9-38.4c-15.3-.1-30.2-2-44.5-5.3L199 505.6l6.7-38.2c-14.6-3.7-28.6-9.1-41.7-15.8l-19.2 35.1 15.6-37c-13-7-25.2-15.4-36.2-25.1l-27.9 31.6 24.7-34.4c-10.7-9.7-20.4-20.5-28.8-32.3l-36.5 26.2 33.9-29.9c-7.9-11.6-14.6-24.1-20-37.3l-44.4 18.7L67.8 344c-4.8-12.7-8.4-26.1-10.5-39.9l-51 9 50.3-14.2c-1.1-8.5-1.7-17.1-1.7-25.9 0-4.7.2-9.4.5-14.1L0 256l56-2.8c1.3-13.1 3.8-25.8 7.5-38.1L6.4 199l58.9 10.4c4-12 9.1-23.5 15.2-34.4l-55.1-30 58.3 24.6C90 159 97.2 149.2 105.3 140L55.8 96.4l53.9 38.7c8.1-8.6 17-16.5 26.6-23.6l-40-55.6 45.6 51.6c9.5-6.6 19.7-12.3 30.3-17.2l-27.3-64.9 33.8 62.1c10.5-4.4 21.4-7.9 32.7-10.4L199 6.4l19.5 69.2c11-2.1 22.3-3.2 33.8-3.4L256 0l3.6 72.2c11.5.2 22.8 1.4 33.8 3.5L313 6.4l-12.4 70.7c11.3 2.6 22.2 6.1 32.6 10.5l33.9-62.2-27.4 65.1c10.6 4.9 20.7 10.7 30.2 17.2l45.8-51.8-40.1 55.9c9.5 7.1 18.4 15 26.5 23.6l54.2-38.9-49.7 43.9c8 9.1 15.2 18.9 21.5 29.4l58.7-24.7-55.5 30.2c6.1 10.9 11.1 22.3 15.1 34.3l59.3-10.4-57.5 16.2c3.7 12.2 6.2 24.9 7.5 37.9L512 256l-56 2.8c.3 4.6.5 9.3.5 14.1 0 8.7-.6 17.3-1.6 25.8l50.7 14.3-51.5-9.1zm-21.8-31c0-97.5-79-176.5-176.5-176.5s-176.5 79-176.5 176.5 79 176.5 176.5 176.5 176.5-79 176.5-176.5zm-24 0c0 84.3-68.3 152.6-152.6 152.6s-152.6-68.3-152.6-152.6 68.3-152.6 152.6-152.6 152.6 68.3 152.6 152.6zM195 241c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-40.7-19c0 2.1 1.3 3.8 3.6 5.1 3.5 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-19 0c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.4 6.8-9.6 10.9-9.6 12.6zm204.9 87.9c-8.4-3-8.7-6.8-8.7-15.6V182c-8.2 12.5-14.2 18.6-18 18.6 6.3 14.4 9.5 23.9 9.5 28.3v64.3c0 2.2-2.2 6.5-4.7 6.5h-18c-2.8-7.5-10.2-26.9-15.3-40.3-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3 2.6 6.7 6.4 16.5 7.9 20.2h-9.2c-3.9-10.4-9.6-25.4-11.8-31.1-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3.8 2 2.8 7.3 4.3 10.9H256c-1.5-4.1-5.6-14.6-8.4-22-2 2.5-7.2 9.2-10.7 13.7 2.5 1.6 4.3 3.6 5.2 6.3.2.6.5 1.4.6 1.7H225c-4.6-13.9-11.4-27.7-11.4-34.1 0-2.2.3-5.1 1.1-8.2-8.8 10.8-14 15.9-14 25 0 7.5 10.4 28.3 10.4 33.3 0 1.7-.5 3.3-1.4 4.9-9.6-12.7-15.5-20.7-18.8-20.7h-12l-11.2-28c-3.8-9.6-5.7-16-5.7-18.8 0-3.8.5-7.7 1.7-12.2-1 1.3-3.7 4.7-5.5 7.1-.8-2.1-3.1-7.7-4.6-11.5-2.1 2.5-7.5 9.1-11.2 13.6.9 2.3 3.3 8.1 4.9 12.2-2.5 3.3-9.1 11.8-13.6 17.7-4 5.3-5.8 13.3-2.7 21.8 2.5 6.7 2 7.9-1.7 14.1H191c5.5 0 14.3 14 15.5 22 13.2-16 15.4-19.6 16.8-21.6h107c3.9 0 7.2-1.9 9.9-5.8zm20.1-26.6V181.7c-9 12.5-15.9 18.6-20.7 18.6 7.1 14.4 10.7 23.9 10.7 28.3v66.3c0 17.5 8.6 20.4 24 20.4 8.1 0 12.5-.8 13.7-2.7-4.3-1.6-7.6-2.5-9.9-3.3-8.1-3.2-17.8-7.4-17.8-26z\"],\n    \"vaadin\": [448, 512, [], \"f408\", \"M224.5 140.7c1.5-17.6 4.9-52.7 49.8-52.7h98.6c20.7 0 32.1-7.8 32.1-21.6V54.1c0-12.2 9.3-22.1 21.5-22.1S448 41.9 448 54.1v36.5c0 42.9-21.5 62-66.8 62H280.7c-30.1 0-33 14.7-33 27.1 0 1.3-.1 2.5-.2 3.7-.7 12.3-10.9 22.2-23.4 22.2s-22.7-9.8-23.4-22.2c-.1-1.2-.2-2.4-.2-3.7 0-12.3-3-27.1-33-27.1H66.8c-45.3 0-66.8-19.1-66.8-62V54.1C0 41.9 9.4 32 21.6 32s21.5 9.9 21.5 22.1v12.3C43.1 80.2 54.5 88 75.2 88h98.6c44.8 0 48.3 35.1 49.8 52.7h.9zM224 456c11.5 0 21.4-7 25.7-16.3 1.1-1.8 97.1-169.6 98.2-171.4 11.9-19.6-3.2-44.3-27.2-44.3-13.9 0-23.3 6.4-29.8 20.3L224 362l-66.9-117.7c-6.4-13.9-15.9-20.3-29.8-20.3-24 0-39.1 24.6-27.2 44.3 1.1 1.9 97.1 169.6 98.2 171.4 4.3 9.3 14.2 16.3 25.7 16.3z\"],\n    \"viacoin\": [384, 512, [], \"f237\", \"M384 32h-64l-80.7 192h-94.5L64 32H0l48 112H0v48h68.5l13.8 32H0v48h102.8L192 480l89.2-208H384v-48h-82.3l13.8-32H384v-48h-48l48-112zM192 336l-27-64h54l-27 64z\"],\n    \"viadeo\": [448, 512, [], \"f2a9\", \"M276.2 150.5v.7C258.3 98.6 233.6 47.8 205.4 0c43.3 29.2 67 100 70.8 150.5zm32.7 121.7c7.6 18.2 11 37.5 11 57 0 77.7-57.8 141-137.8 139.4l3.8-.3c74.2-46.7 109.3-118.6 109.3-205.1 0-38.1-6.5-75.9-18.9-112 1 11.7 1 23.7 1 35.4 0 91.8-18.1 241.6-116.6 280C95 455.2 49.4 398 49.4 329.2c0-75.6 57.4-142.3 135.4-142.3 16.8 0 33.7 3.1 49.1 9.6 1.7-15.1 6.5-29.9 13.4-43.3-19.9-7.2-41.2-10.7-62.5-10.7-161.5 0-238.7 195.9-129.9 313.7 67.9 74.6 192 73.9 259.8 0 56.6-61.3 60.9-142.4 36.4-201-12.7 8-27.1 13.9-42.2 17zM418.1 11.7c-31 66.5-81.3 47.2-115.8 80.1-12.4 12-20.6 34-20.6 50.5 0 14.1 4.5 27.1 12 38.8 47.4-11 98.3-46 118.2-90.7-.7 5.5-4.8 14.4-7.2 19.2-20.3 35.7-64.6 65.6-99.7 84.9 14.8 14.4 33.7 25.8 55 25.8 79 0 110.1-134.6 58.1-208.6z\"],\n    \"viadeo-square\": [448, 512, [], \"f2aa\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM280.7 381.2c-42.4 46.2-120 46.6-162.4 0-68-73.6-19.8-196.1 81.2-196.1 13.3 0 26.6 2.1 39.1 6.7-4.3 8.4-7.3 17.6-8.4 27.1-9.7-4.1-20.2-6-30.7-6-48.8 0-84.6 41.7-84.6 88.9 0 43 28.5 78.7 69.5 85.9 61.5-24 72.9-117.6 72.9-175 0-7.3 0-14.8-.6-22.1-11.2-32.9-26.6-64.6-44.2-94.5 27.1 18.3 41.9 62.5 44.2 94.1v.4c7.7 22.5 11.8 46.2 11.8 70 0 54.1-21.9 99-68.3 128.2l-2.4.2c50 1 86.2-38.6 86.2-87.2 0-12.2-2.1-24.3-6.9-35.7 9.5-1.9 18.5-5.6 26.4-10.5 15.3 36.6 12.6 87.3-22.8 125.6zM309 233.7c-13.3 0-25.1-7.1-34.4-16.1 21.9-12 49.6-30.7 62.3-53 1.5-3 4.1-8.6 4.5-12-12.5 27.9-44.2 49.8-73.9 56.7-4.7-7.3-7.5-15.5-7.5-24.3 0-10.3 5.2-24.1 12.9-31.6 21.6-20.5 53-8.5 72.4-50 32.5 46.2 13.1 130.3-36.3 130.3z\"],\n    \"viber\": [512, 512, [], \"f409\", \"M444 49.9C431.3 38.2 379.9.9 265.3.4c0 0-135.1-8.1-200.9 52.3C27.8 89.3 14.9 143 13.5 209.5c-1.4 66.5-3.1 191.1 117 224.9h.1l-.1 51.6s-.8 20.9 13 25.1c16.6 5.2 26.4-10.7 42.3-27.8 8.7-9.4 20.7-23.2 29.8-33.7 82.2 6.9 145.3-8.9 152.5-11.2 16.6-5.4 110.5-17.4 125.7-142 15.8-128.6-7.6-209.8-49.8-246.5zM457.9 287c-12.9 104-89 110.6-103 115.1-6 1.9-61.5 15.7-131.2 11.2 0 0-52 62.7-68.2 79-5.3 5.3-11.1 4.8-11-5.7 0-6.9.4-85.7.4-85.7-.1 0-.1 0 0 0-101.8-28.2-95.8-134.3-94.7-189.8 1.1-55.5 11.6-101 42.6-131.6 55.7-50.5 170.4-43 170.4-43 96.9.4 143.3 29.6 154.1 39.4 35.7 30.6 53.9 103.8 40.6 211.1zm-139-80.8c.4 8.6-12.5 9.2-12.9.6-1.1-22-11.4-32.7-32.6-33.9-8.6-.5-7.8-13.4.7-12.9 27.9 1.5 43.4 17.5 44.8 46.2zm20.3 11.3c1-42.4-25.5-75.6-75.8-79.3-8.5-.6-7.6-13.5.9-12.9 58 4.2 88.9 44.1 87.8 92.5-.1 8.6-13.1 8.2-12.9-.3zm47 13.4c.1 8.6-12.9 8.7-12.9.1-.6-81.5-54.9-125.9-120.8-126.4-8.5-.1-8.5-12.9 0-12.9 73.7.5 133 51.4 133.7 139.2zM374.9 329v.2c-10.8 19-31 40-51.8 33.3l-.2-.3c-21.1-5.9-70.8-31.5-102.2-56.5-16.2-12.8-31-27.9-42.4-42.4-10.3-12.9-20.7-28.2-30.8-46.6-21.3-38.5-26-55.7-26-55.7-6.7-20.8 14.2-41 33.3-51.8h.2c9.2-4.8 18-3.2 23.9 3.9 0 0 12.4 14.8 17.7 22.1 5 6.8 11.7 17.7 15.2 23.8 6.1 10.9 2.3 22-3.7 26.6l-12 9.6c-6.1 4.9-5.3 14-5.3 14s17.8 67.3 84.3 84.3c0 0 9.1.8 14-5.3l9.6-12c4.6-6 15.7-9.8 26.6-3.7 14.7 8.3 33.4 21.2 45.8 32.9 7 5.7 8.6 14.4 3.8 23.6z\"],\n    \"vimeo\": [448, 512, [], \"f40a\", \"M403.2 32H44.8C20.1 32 0 52.1 0 76.8v358.4C0 459.9 20.1 480 44.8 480h358.4c24.7 0 44.8-20.1 44.8-44.8V76.8c0-24.7-20.1-44.8-44.8-44.8zM377 180.8c-1.4 31.5-23.4 74.7-66 129.4-44 57.2-81.3 85.8-111.7 85.8-18.9 0-34.8-17.4-47.9-52.3-25.5-93.3-36.4-148-57.4-148-2.4 0-10.9 5.1-25.4 15.2l-15.2-19.6c37.3-32.8 72.9-69.2 95.2-71.2 25.2-2.4 40.7 14.8 46.5 51.7 20.7 131.2 29.9 151 67.6 91.6 13.5-21.4 20.8-37.7 21.8-48.9 3.5-33.2-25.9-30.9-45.8-22.4 15.9-52.1 46.3-77.4 91.2-76 33.3.9 49 22.5 47.1 64.7z\"],\n    \"vimeo-square\": [448, 512, [], \"f194\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16.2 149.6c-1.4 31.1-23.2 73.8-65.3 127.9-43.5 56.5-80.3 84.8-110.4 84.8-18.7 0-34.4-17.2-47.3-51.6-25.2-92.3-35.9-146.4-56.7-146.4-2.4 0-10.8 5-25.1 15.1L64 192c36.9-32.4 72.1-68.4 94.1-70.4 24.9-2.4 40.2 14.6 46 51.1 20.5 129.6 29.6 149.2 66.8 90.5 13.4-21.2 20.6-37.2 21.5-48.3 3.4-32.8-25.6-30.6-45.2-22.2 15.7-51.5 45.8-76.5 90.1-75.1 32.9 1 48.4 22.4 46.5 64z\"],\n    \"vimeo-v\": [448, 512, [], \"f27d\", \"M447.8 153.6c-2 43.6-32.4 103.3-91.4 179.1-60.9 79.2-112.4 118.8-154.6 118.8-26.1 0-48.2-24.1-66.3-72.3C100.3 250 85.3 174.3 56.2 174.3c-3.4 0-15.1 7.1-35.2 21.1L0 168.2c51.6-45.3 100.9-95.7 131.8-98.5 34.9-3.4 56.3 20.5 64.4 71.5 28.7 181.5 41.4 208.9 93.6 126.7 18.7-29.6 28.8-52.1 30.2-67.6 4.8-45.9-35.8-42.8-63.3-31 22-72.1 64.1-107.1 126.2-105.1 45.8 1.2 67.5 31.1 64.9 89.4z\"],\n    \"vine\": [384, 512, [], \"f1ca\", \"M384 254.7v52.1c-18.4 4.2-36.9 6.1-52.1 6.1-36.9 77.4-103 143.8-125.1 156.2-14 7.9-27.1 8.4-42.7-.8C137 452 34.2 367.7 0 102.7h74.5C93.2 261.8 139 343.4 189.3 404.5c27.9-27.9 54.8-65.1 75.6-106.9-49.8-25.3-80.1-80.9-80.1-145.6 0-65.6 37.7-115.1 102.2-115.1 114.9 0 106.2 127.9 81.6 181.5 0 0-46.4 9.2-63.5-20.5 3.4-11.3 8.2-30.8 8.2-48.5 0-31.3-11.3-46.6-28.4-46.6-18.2 0-30.8 17.1-30.8 50 .1 79.2 59.4 118.7 129.9 101.9z\"],\n    \"vk\": [576, 512, [], \"f189\", \"M545 117.7c3.7-12.5 0-21.7-17.8-21.7h-58.9c-15 0-21.9 7.9-25.6 16.7 0 0-30 73.1-72.4 120.5-13.7 13.7-20 18.1-27.5 18.1-3.7 0-9.4-4.4-9.4-16.9V117.7c0-15-4.2-21.7-16.6-21.7h-92.6c-9.4 0-15 7-15 13.5 0 14.2 21.2 17.5 23.4 57.5v86.8c0 19-3.4 22.5-10.9 22.5-20 0-68.6-73.4-97.4-157.4-5.8-16.3-11.5-22.9-26.6-22.9H38.8c-16.8 0-20.2 7.9-20.2 16.7 0 15.6 20 93.1 93.1 195.5C160.4 378.1 229 416 291.4 416c37.5 0 42.1-8.4 42.1-22.9 0-66.8-3.4-73.1 15.4-73.1 8.7 0 23.7 4.4 58.7 38.1 40 40 46.6 57.9 69 57.9h58.9c16.8 0 25.3-8.4 20.4-25-11.2-34.9-86.9-106.7-90.3-111.5-8.7-11.2-6.2-16.2 0-26.2.1-.1 72-101.3 79.4-135.6z\"],\n    \"vnv\": [640, 512, [], \"f40b\", \"M104.9 352c-34.1 0-46.4-30.4-46.4-30.4L2.6 210.1S-7.8 192 13 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.7-74.5c5.6-9.5 8.4-18.1 18.8-18.1h32.8c20.8 0 10.4 18.1 10.4 18.1l-55.8 111.5S174.2 352 140 352h-35.1zm395 0c-34.1 0-46.4-30.4-46.4-30.4l-55.9-111.5S387.2 192 408 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.8-74.5c5.6-9.5 8.4-18.1 18.8-18.1H627c20.8 0 10.4 18.1 10.4 18.1l-55.9 111.5S569.3 352 535.1 352h-35.2zM337.6 192c34.1 0 46.4 30.4 46.4 30.4l55.9 111.5s10.4 18.1-10.4 18.1h-32.8c-10.4 0-13.2-8.7-18.8-18.1l-36.7-74.5s-5.2-13.1-21.1-13.1c-15.9 0-21.1 13.1-21.1 13.1l-36.7 74.5c-5.6 9.4-8.4 18.1-18.8 18.1h-32.9c-20.8 0-10.4-18.1-10.4-18.1l55.9-111.5s12.2-30.4 46.4-30.4h35.1z\"],\n    \"vuejs\": [448, 512, [], \"f41f\", \"M356.9 64.3H280l-56 88.6-48-88.6H0L224 448 448 64.3h-91.1zm-301.2 32h53.8L224 294.5 338.4 96.3h53.8L224 384.5 55.7 96.3z\"],\n    \"waze\": [512, 512, [], \"f83f\", \"M502.17 201.67C516.69 287.53 471.23 369.59 389 409.8c13 34.1-12.4 70.2-48.32 70.2a51.68 51.68 0 0 1-51.57-49c-6.44.19-64.2 0-76.33-.64A51.69 51.69 0 0 1 159 479.92c-33.86-1.36-57.95-34.84-47-67.92-37.21-13.11-72.54-34.87-99.62-70.8-13-17.28-.48-41.8 20.84-41.8 46.31 0 32.22-54.17 43.15-110.26C94.8 95.2 193.12 32 288.09 32c102.48 0 197.15 70.67 214.08 169.67zM373.51 388.28c42-19.18 81.33-56.71 96.29-102.14 40.48-123.09-64.15-228-181.71-228-83.45 0-170.32 55.42-186.07 136-9.53 48.91 5 131.35-68.75 131.35C58.21 358.6 91.6 378.11 127 389.54c24.66-21.8 63.87-15.47 79.83 14.34 14.22 1 79.19 1.18 87.9.82a51.69 51.69 0 0 1 78.78-16.42zM205.12 187.13c0-34.74 50.84-34.75 50.84 0s-50.84 34.74-50.84 0zm116.57 0c0-34.74 50.86-34.75 50.86 0s-50.86 34.75-50.86 0zm-122.61 70.69c-3.44-16.94 22.18-22.18 25.62-5.21l.06.28c4.14 21.42 29.85 44 64.12 43.07 35.68-.94 59.25-22.21 64.11-42.77 4.46-16.05 28.6-10.36 25.47 6-5.23 22.18-31.21 62-91.46 62.9-42.55 0-80.88-27.84-87.9-64.25z\"],\n    \"weebly\": [512, 512, [], \"f5cc\", \"M425.09 65.83c-39.88 0-73.28 25.73-83.66 64.33-18.16-58.06-65.5-64.33-84.95-64.33-19.78 0-66.8 6.28-85.28 64.33-10.38-38.6-43.45-64.33-83.66-64.33C38.59 65.83 0 99.72 0 143.03c0 28.96 4.18 33.27 77.17 233.48 22.37 60.57 67.77 69.35 92.74 69.35 39.23 0 70.04-19.46 85.93-53.98 15.89 34.83 46.69 54.29 85.93 54.29 24.97 0 70.36-9.1 92.74-69.67 76.55-208.65 77.5-205.58 77.5-227.2.63-48.32-36.01-83.47-86.92-83.47zm26.34 114.81l-65.57 176.44c-7.92 21.49-21.22 37.22-46.24 37.22-23.44 0-37.38-12.41-44.03-33.9l-39.28-117.42h-.95L216.08 360.4c-6.96 21.5-20.9 33.6-44.02 33.6-25.02 0-38.33-15.74-46.24-37.22L60.88 181.55c-5.38-14.83-7.92-23.91-7.92-34.5 0-16.34 15.84-29.36 38.33-29.36 18.69 0 31.99 11.8 36.11 29.05l44.03 139.82h.95l44.66-136.79c6.02-19.67 16.47-32.08 38.96-32.08s32.94 12.11 38.96 32.08l44.66 136.79h.95l44.03-139.82c4.12-17.25 17.42-29.05 36.11-29.05 22.17 0 38.33 13.32 38.33 35.71-.32 7.87-4.12 16.04-7.61 27.24z\"],\n    \"weibo\": [512, 512, [], \"f18a\", \"M407 177.6c7.6-24-13.4-46.8-37.4-41.7-22 4.8-28.8-28.1-7.1-32.8 50.1-10.9 92.3 37.1 76.5 84.8-6.8 21.2-38.8 10.8-32-10.3zM214.8 446.7C108.5 446.7 0 395.3 0 310.4c0-44.3 28-95.4 76.3-143.7C176 67 279.5 65.8 249.9 161c-4 13.1 12.3 5.7 12.3 6 79.5-33.6 140.5-16.8 114 51.4-3.7 9.4 1.1 10.9 8.3 13.1 135.7 42.3 34.8 215.2-169.7 215.2zm143.7-146.3c-5.4-55.7-78.5-94-163.4-85.7-84.8 8.6-148.8 60.3-143.4 116s78.5 94 163.4 85.7c84.8-8.6 148.8-60.3 143.4-116zM347.9 35.1c-25.9 5.6-16.8 43.7 8.3 38.3 72.3-15.2 134.8 52.8 111.7 124-7.4 24.2 29.1 37 37.4 12 31.9-99.8-55.1-195.9-157.4-174.3zm-78.5 311c-17.1 38.8-66.8 60-109.1 46.3-40.8-13.1-58-53.4-40.3-89.7 17.7-35.4 63.1-55.4 103.4-45.1 42 10.8 63.1 50.2 46 88.5zm-86.3-30c-12.9-5.4-30 .3-38 12.9-8.3 12.9-4.3 28 8.6 34 13.1 6 30.8.3 39.1-12.9 8-13.1 3.7-28.3-9.7-34zm32.6-13.4c-5.1-1.7-11.4.6-14.3 5.4-2.9 5.1-1.4 10.6 3.7 12.9 5.1 2 11.7-.3 14.6-5.4 2.8-5.2 1.1-10.9-4-12.9z\"],\n    \"weixin\": [576, 512, [], \"f1d7\", \"M385.2 167.6c6.4 0 12.6.3 18.8 1.1C387.4 90.3 303.3 32 207.7 32 100.5 32 13 104.8 13 197.4c0 53.4 29.3 97.5 77.9 131.6l-19.3 58.6 68-34.1c24.4 4.8 43.8 9.7 68.2 9.7 6.2 0 12.1-.3 18.3-.8-4-12.9-6.2-26.6-6.2-40.8-.1-84.9 72.9-154 165.3-154zm-104.5-52.9c14.5 0 24.2 9.7 24.2 24.4 0 14.5-9.7 24.2-24.2 24.2-14.8 0-29.3-9.7-29.3-24.2.1-14.7 14.6-24.4 29.3-24.4zm-136.4 48.6c-14.5 0-29.3-9.7-29.3-24.2 0-14.8 14.8-24.4 29.3-24.4 14.8 0 24.4 9.7 24.4 24.4 0 14.6-9.6 24.2-24.4 24.2zM563 319.4c0-77.9-77.9-141.3-165.4-141.3-92.7 0-165.4 63.4-165.4 141.3S305 460.7 397.6 460.7c19.3 0 38.9-5.1 58.6-9.9l53.4 29.3-14.8-48.6C534 402.1 563 363.2 563 319.4zm-219.1-24.5c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.8 0 24.4 9.7 24.4 19.3 0 10-9.7 19.6-24.4 19.6zm107.1 0c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.5 0 24.4 9.7 24.4 19.3.1 10-9.9 19.6-24.4 19.6z\"],\n    \"whatsapp\": [448, 512, [], \"f232\", \"M380.9 97.1C339 55.1 283.2 32 223.9 32c-122.4 0-222 99.6-222 222 0 39.1 10.2 77.3 29.6 111L0 480l117.7-30.9c32.4 17.7 68.9 27 106.1 27h.1c122.3 0 224.1-99.6 224.1-222 0-59.3-25.2-115-67.1-157zm-157 341.6c-33.2 0-65.7-8.9-94-25.7l-6.7-4-69.8 18.3L72 359.2l-4.4-7c-18.5-29.4-28.2-63.3-28.2-98.2 0-101.7 82.8-184.5 184.6-184.5 49.3 0 95.6 19.2 130.4 54.1 34.8 34.9 56.2 81.2 56.1 130.5 0 101.8-84.9 184.6-186.6 184.6zm101.2-138.2c-5.5-2.8-32.8-16.2-37.9-18-5.1-1.9-8.8-2.8-12.5 2.8-3.7 5.6-14.3 18-17.6 21.8-3.2 3.7-6.5 4.2-12 1.4-32.6-16.3-54-29.1-75.5-66-5.7-9.8 5.7-9.1 16.3-30.3 1.8-3.7.9-6.9-.5-9.7-1.4-2.8-12.5-30.1-17.1-41.2-4.5-10.8-9.1-9.3-12.5-9.5-3.2-.2-6.9-.2-10.6-.2-3.7 0-9.7 1.4-14.8 6.9-5.1 5.6-19.4 19-19.4 46.3 0 27.3 19.9 53.7 22.6 57.4 2.8 3.7 39.1 59.7 94.8 83.8 35.2 15.2 49 16.5 66.6 13.9 10.7-1.6 32.8-13.4 37.4-26.4 4.6-13 4.6-24.1 3.2-26.4-1.3-2.5-5-3.9-10.5-6.6z\"],\n    \"whatsapp-square\": [448, 512, [], \"f40c\", \"M224 122.8c-72.7 0-131.8 59.1-131.9 131.8 0 24.9 7 49.2 20.2 70.1l3.1 5-13.3 48.6 49.9-13.1 4.8 2.9c20.2 12 43.4 18.4 67.1 18.4h.1c72.6 0 133.3-59.1 133.3-131.8 0-35.2-15.2-68.3-40.1-93.2-25-25-58-38.7-93.2-38.7zm77.5 188.4c-3.3 9.3-19.1 17.7-26.7 18.8-12.6 1.9-22.4.9-47.5-9.9-39.7-17.2-65.7-57.2-67.7-59.8-2-2.6-16.2-21.5-16.2-41s10.2-29.1 13.9-33.1c3.6-4 7.9-5 10.6-5 2.6 0 5.3 0 7.6.1 2.4.1 5.7-.9 8.9 6.8 3.3 7.9 11.2 27.4 12.2 29.4s1.7 4.3.3 6.9c-7.6 15.2-15.7 14.6-11.6 21.6 15.3 26.3 30.6 35.4 53.9 47.1 4 2 6.3 1.7 8.6-1 2.3-2.6 9.9-11.6 12.5-15.5 2.6-4 5.3-3.3 8.9-2 3.6 1.3 23.1 10.9 27.1 12.9s6.6 3 7.6 4.6c.9 1.9.9 9.9-2.4 19.1zM400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM223.9 413.2c-26.6 0-52.7-6.7-75.8-19.3L64 416l22.5-82.2c-13.9-24-21.2-51.3-21.2-79.3C65.4 167.1 136.5 96 223.9 96c42.4 0 82.2 16.5 112.2 46.5 29.9 30 47.9 69.8 47.9 112.2 0 87.4-72.7 158.5-160.1 158.5z\"],\n    \"whmcs\": [448, 512, [], \"f40d\", \"M448 161v-21.3l-28.5-8.8-2.2-10.4 20.1-20.7L427 80.4l-29 7.5-7.2-7.5 7.5-28.2-19.1-11.6-21.3 21-10.7-3.2-7-26.4h-22.6l-6.2 26.4-12.1 3.2-19.7-21-19.4 11 8.1 27.7-8.1 8.4-28.5-7.5-11 19.1 20.7 21-2.9 10.4-28.5 7.8-.3 21.7 28.8 7.5 2.4 12.1-20.1 19.9 10.4 18.5 29.6-7.5 7.2 8.6-8.1 26.9 19.9 11.6 19.4-20.4 11.6 2.9 6.7 28.5 22.6.3 6.7-28.8 11.6-3.5 20.7 21.6 20.4-12.1-8.8-28 7.8-8.1 28.8 8.8 10.3-20.1-20.9-18.8 2.2-12.1 29.1-7zm-119.2 45.2c-31.3 0-56.8-25.4-56.8-56.8s25.4-56.8 56.8-56.8 56.8 25.4 56.8 56.8c0 31.5-25.4 56.8-56.8 56.8zm72.3 16.4l46.9 14.5V277l-55.1 13.4-4.1 22.7 38.9 35.3-19.2 37.9-54-16.7-14.6 15.2 16.7 52.5-38.3 22.7-38.9-40.5-21.7 6.6-12.6 54-42.4-.5-12.6-53.6-21.7-5.6-36.4 38.4-37.4-21.7 15.2-50.5-13.7-16.1-55.5 14.1-19.7-34.8 37.9-37.4-4.8-22.8-54-14.1.5-40.9L54 219.9l5.7-19.7-38.9-39.4L41.5 125l53.6 14.1 15.2-15.7-15.2-52 36.4-20.7 36.8 39.4L191 84l11.6-52H245l11.6 45.9L234 72l-6.3-1.7-3.3 5.7-11 19.1-3.3 5.6 4.6 4.6 17.2 17.4-.3 1-23.8 6.5-6.2 1.7-.1 6.4-.2 12.9C153.8 161.6 118 204 118 254.7c0 58.3 47.3 105.7 105.7 105.7 50.5 0 92.7-35.4 103.2-82.8l13.2.2 6.9.1 1.6-6.7 5.6-24 1.9-.6 17.1 17.8 4.7 4.9 5.8-3.4 20.4-12.1 5.8-3.5-2-6.5-6.8-21.2z\"],\n    \"wikipedia-w\": [640, 512, [], \"f266\", \"M640 51.2l-.3 12.2c-28.1.8-45 15.8-55.8 40.3-25 57.8-103.3 240-155.3 358.6H415l-81.9-193.1c-32.5 63.6-68.3 130-99.2 193.1-.3.3-15 0-15-.3C172 352.3 122.8 243.4 75.8 133.4 64.4 106.7 26.4 63.4.2 63.7c0-3.1-.3-10-.3-14.2h161.9v13.9c-19.2 1.1-52.8 13.3-43.3 34.2 21.9 49.7 103.6 240.3 125.6 288.6 15-29.7 57.8-109.2 75.3-142.8-13.9-28.3-58.6-133.9-72.8-160-9.7-17.8-36.1-19.4-55.8-19.7V49.8l142.5.3v13.1c-19.4.6-38.1 7.8-29.4 26.1 18.9 40 30.6 68.1 48.1 104.7 5.6-10.8 34.7-69.4 48.1-100.8 8.9-20.6-3.9-28.6-38.6-29.4.3-3.6 0-10.3.3-13.6 44.4-.3 111.1-.3 123.1-.6v13.6c-22.5.8-45.8 12.8-58.1 31.7l-59.2 122.8c6.4 16.1 63.3 142.8 69.2 156.7L559.2 91.8c-8.6-23.1-36.4-28.1-47.2-28.3V49.6l127.8 1.1.2.5z\"],\n    \"windows\": [448, 512, [], \"f17a\", \"M0 93.7l183.6-25.3v177.4H0V93.7zm0 324.6l183.6 25.3V268.4H0v149.9zm203.8 28L448 480V268.4H203.8v177.9zm0-380.6v180.1H448V32L203.8 65.7z\"],\n    \"wix\": [640, 512, [], \"f5cf\", \"M393.38 131.69c0 13.03 2.08 32.69-28.68 43.83-9.52 3.45-15.95 9.66-15.95 9.66 0-31 4.72-42.22 17.4-48.86 9.75-5.11 27.23-4.63 27.23-4.63zm-115.8 35.54l-34.24 132.66-28.48-108.57c-7.69-31.99-20.81-48.53-48.43-48.53-27.37 0-40.66 16.18-48.43 48.53L89.52 299.89 55.28 167.23C49.73 140.51 23.86 128.96 0 131.96l65.57 247.93s21.63 1.56 32.46-3.96c14.22-7.25 20.98-12.84 29.59-46.57 7.67-30.07 29.11-118.41 31.12-124.7 4.76-14.94 11.09-13.81 15.4 0 1.97 6.3 23.45 94.63 31.12 124.7 8.6 33.73 15.37 39.32 29.59 46.57 10.82 5.52 32.46 3.96 32.46 3.96l65.57-247.93c-24.42-3.07-49.82 8.93-55.3 35.27zm115.78 5.21s-4.1 6.34-13.46 11.57c-6.01 3.36-11.78 5.64-17.97 8.61-15.14 7.26-13.18 13.95-13.18 35.2v152.07s16.55 2.09 27.37-3.43c13.93-7.1 17.13-13.95 17.26-44.78V181.41l-.02.01v-8.98zm163.44 84.08L640 132.78s-35.11-5.98-52.5 9.85c-13.3 12.1-24.41 29.55-54.18 72.47-.47.73-6.25 10.54-13.07 0-29.29-42.23-40.8-60.29-54.18-72.47-17.39-15.83-52.5-9.85-52.5-9.85l83.2 123.74-82.97 123.36s36.57 4.62 53.95-11.21c11.49-10.46 17.58-20.37 52.51-70.72 6.81-10.52 12.57-.77 13.07 0 29.4 42.38 39.23 58.06 53.14 70.72 17.39 15.83 53.32 11.21 53.32 11.21L556.8 256.52z\"],\n    \"wizards-of-the-coast\": [640, 512, [], \"f730\", \"M219.19 345.69c-1.9 1.38-11.07 8.44-.26 23.57 4.64 6.42 14.11 12.79 21.73 6.55 6.5-4.88 7.35-12.92.26-23.04-5.47-7.76-14.28-12.88-21.73-7.08zm336.75 75.94c-.34 1.7-.55 1.67.79 0 2.09-4.19 4.19-10.21 4.98-19.9 3.14-38.49-40.33-71.49-101.34-78.03-54.73-6.02-124.38 9.17-188.8 60.49l-.26 1.57c2.62 4.98 4.98 10.74 3.4 21.21l.79.26c63.89-58.4 131.19-77.25 184.35-73.85 58.4 3.67 100.03 34.04 100.03 68.08-.01 9.96-2.63 15.72-3.94 20.17zM392.28 240.42c.79 7.07 4.19 10.21 9.17 10.47 5.5.26 9.43-2.62 10.47-6.55.79-3.4 2.09-29.85 2.09-29.85s-11.26 6.55-14.93 10.47c-3.66 3.68-7.33 8.39-6.8 15.46zm-50.02-151.1C137.75 89.32 13.1 226.8.79 241.2c-1.05.52-1.31.79.79 1.31 60.49 16.5 155.81 81.18 196.13 202.16l1.05.26c55.25-69.92 140.88-128.05 236.99-128.05 80.92 0 130.15 42.16 130.15 80.39 0 18.33-6.55 33.52-22.26 46.35 0 .96-.2.79.79.79 14.66-10.74 27.5-28.8 27.5-48.18 0-22.78-12.05-38.23-12.05-38.23 7.07 7.07 10.74 16.24 10.74 16.24 5.76-40.85 26.97-62.32 26.97-62.32-2.36-9.69-6.81-17.81-6.81-17.81 7.59 8.12 14.4 27.5 14.4 41.37 0 10.47-3.4 22.78-12.57 31.95l.26.52c8.12-4.98 16.5-16.76 16.5-37.97 0-15.71-4.71-25.92-4.71-25.92 5.76-5.24 11.26-9.17 15.97-11.78.79 3.4 2.09 9.69 2.36 14.93 0 1.05.79 1.83 1.05 0 .79-5.76-.26-16.24-.26-16.5 6.02-3.14 9.69-4.45 9.69-4.45C617.74 176 489.43 89.32 342.26 89.32zm-99.24 289.62c-11.06 8.99-24.2 4.08-30.64-4.19-7.45-9.58-6.76-24.09 4.19-32.47 14.85-11.35 27.08-.49 31.16 5.5.28.39 12.13 16.57-4.71 31.16zm2.09-136.43l9.43-17.81 11.78 70.96-12.57 6.02-24.62-28.8 14.14-26.71 3.67 4.45-1.83-8.11zm18.59 117.58l-.26-.26c2.05-4.1-2.5-6.61-17.54-31.69-1.31-2.36-3.14-2.88-4.45-2.62l-.26-.52c7.86-5.76 15.45-10.21 25.4-15.71l.52.26c1.31 1.83 2.09 2.88 3.4 4.71l-.26.52c-1.05-.26-2.36-.79-5.24.26-2.09.79-7.86 3.67-12.31 7.59v1.31c1.57 2.36 3.93 6.55 5.76 9.69h.26c10.05-6.28 7.56-4.55 11.52-7.86h.26c.52 1.83.52 1.83 1.83 5.5l-.26.26c-3.06.61-4.65.34-11.52 5.5v.26c9.46 17.02 11.01 16.75 12.57 15.97l.26.26c-2.34 1.59-6.27 4.21-9.68 6.57zm55.26-32.47c-3.14 1.57-6.02 2.88-9.95 4.98l-.26-.26c1.29-2.59 1.16-2.71-11.78-32.47l-.26-.26c-.15 0-8.9 3.65-9.95 7.33h-.52l-1.05-5.76.26-.52c7.29-4.56 25.53-11.64 27.76-12.57l.52.26 3.14 4.98-.26.52c-3.53-1.76-7.35.76-12.31 2.62v.26c12.31 32.01 12.67 30.64 14.66 30.64v.25zm44.77-16.5c-4.19 1.05-5.24 1.31-9.69 2.88l-.26-.26.52-4.45c-1.05-3.4-3.14-11.52-3.67-13.62l-.26-.26c-3.4.79-8.9 2.62-12.83 3.93l-.26.26c.79 2.62 3.14 9.95 4.19 13.88.79 2.36 1.83 2.88 2.88 3.14v.52c-3.67 1.05-7.07 2.62-10.21 3.93l-.26-.26c1.05-1.31 1.05-2.88.26-4.98-1.05-3.14-8.12-23.83-9.17-27.23-.52-1.83-1.57-3.14-2.62-3.14v-.52c3.14-1.05 6.02-2.09 10.74-3.4l.26.26-.26 4.71c1.31 3.93 2.36 7.59 3.14 9.69h.26c3.93-1.31 9.43-2.88 12.83-3.93l.26-.26-2.62-9.43c-.52-1.83-1.05-3.4-2.62-3.93v-.26c4.45-1.05 7.33-1.83 10.74-2.36l.26.26c-1.05 1.31-1.05 2.88-.52 4.45 1.57 6.28 4.71 20.43 6.28 26.45.54 2.62 1.85 3.41 2.63 3.93zm32.21-6.81l-.26.26c-4.71.52-14.14 2.36-22.52 4.19l-.26-.26.79-4.19c-1.57-7.86-3.4-18.59-4.98-26.19-.26-1.83-.79-2.88-2.62-3.67l.79-.52c9.17-1.57 20.16-2.36 24.88-2.62l.26.26c.52 2.36.79 3.14 1.57 5.5l-.26.26c-1.14-1.14-3.34-3.2-16.24-.79l-.26.26c.26 1.57 1.05 6.55 1.57 9.95l.26.26c9.52-1.68 4.76-.06 10.74-2.36h.26c0 1.57-.26 1.83-.26 5.24h-.26c-4.81-1.03-2.15-.9-10.21 0l-.26.26c.26 2.09 1.57 9.43 2.09 12.57l.26.26c1.15.38 14.21-.65 16.24-4.71h.26c-.53 2.38-1.05 4.21-1.58 6.04zm10.74-44.51c-4.45 2.36-8.12 2.88-11 2.88-.25.02-11.41 1.09-17.54-9.95-6.74-10.79-.98-25.2 5.5-31.69 8.8-8.12 23.35-10.1 28.54-17.02 8.03-10.33-13.04-22.31-29.59-5.76l-2.62-2.88 5.24-16.24c25.59-1.57 45.2-3.04 50.02 16.24.79 3.14 0 9.43-.26 12.05 0 2.62-1.83 18.85-2.09 23.04-.52 4.19-.79 18.33-.79 20.69.26 2.36.52 4.19 1.57 5.5 1.57 1.83 5.76 1.83 5.76 1.83l-.79 4.71c-11.82-1.07-10.28-.59-20.43-1.05-3.22-5.15-2.23-3.28-4.19-7.86 0 .01-4.19 3.94-7.33 5.51zm37.18 21.21c-6.35-10.58-19.82-7.16-21.73 5.5-2.63 17.08 14.3 19.79 20.69 10.21l.26.26c-.52 1.83-1.83 6.02-1.83 6.28l-.52.52c-10.3 6.87-28.5-2.5-25.66-18.59 1.94-10.87 14.44-18.93 28.8-9.95l.26.52c0 1.06-.27 3.41-.27 5.25zm5.77-87.73v-6.55c.69 0 19.65 3.28 27.76 7.33l-1.57 17.54s10.21-9.43 15.45-10.74c5.24-1.57 14.93 7.33 14.93 7.33l-11.26 11.26c-12.07-6.35-19.59-.08-20.69.79-5.29 38.72-8.6 42.17 4.45 46.09l-.52 4.71c-17.55-4.29-18.53-4.5-36.92-7.33l.79-4.71c7.25 0 7.48-5.32 7.59-6.81 0 0 4.98-53.16 4.98-55.25-.02-2.87-4.99-3.66-4.99-3.66zm10.99 114.44c-8.12-2.09-14.14-11-10.74-20.69 3.14-9.43 12.31-12.31 18.85-10.21 9.17 2.62 12.83 11.78 10.74 19.38-2.61 8.9-9.42 13.87-18.85 11.52zm42.16 9.69c-2.36-.52-7.07-2.36-8.64-2.88v-.26l1.57-1.83c.59-8.24.59-7.27.26-7.59-4.82-1.81-6.66-2.36-7.07-2.36-1.31 1.83-2.88 4.45-3.67 5.5l-.79 3.4v.26c-1.31-.26-3.93-1.31-6.02-1.57v-.26l2.62-1.83c3.4-4.71 9.95-14.14 13.88-20.16v-2.09l.52-.26c2.09.79 5.5 2.09 7.59 2.88.48.48.18-1.87-1.05 25.14-.24 1.81.02 2.6.8 3.91zm-4.71-89.82c11.25-18.27 30.76-16.19 34.04-3.4L539.7 198c2.34-6.25-2.82-9.9-4.45-11.26l1.83-3.67c12.22 10.37 16.38 13.97 22.52 20.43-25.91 73.07-30.76 80.81-24.62 84.32l-1.83 4.45c-6.37-3.35-8.9-4.42-17.81-8.64l2.09-6.81c-.26-.26-3.93 3.93-9.69 3.67-19.06-1.3-22.89-31.75-9.67-52.9zm29.33 79.34c0-5.71-6.34-7.89-7.86-5.24-1.31 2.09 1.05 4.98 2.88 8.38 1.57 2.62 2.62 6.28 1.05 9.43-2.64 6.34-12.4 5.31-15.45-.79 0-.7-.27.09 1.83-4.71l.79-.26c-.57 5.66 6.06 9.61 8.38 4.98 1.05-2.09-.52-5.5-2.09-8.38-1.57-2.62-3.67-6.28-1.83-9.69 2.72-5.06 11.25-4.47 14.66 2.36v.52l-2.36 3.4zm21.21 13.36c-1.96-3.27-.91-2.14-4.45-4.71h-.26c-2.36 4.19-5.76 10.47-8.64 16.24-1.31 2.36-1.05 3.4-.79 3.93l-.26.26-5.76-4.45.26-.26 2.09-1.31c3.14-5.76 6.55-12.05 9.17-17.02v-.26c-2.64-1.98-1.22-1.51-6.02-1.83v-.26l3.14-3.4h.26c3.67 2.36 9.95 6.81 12.31 8.9l.26.26-1.31 3.91zm27.23-44.26l-2.88-2.88c.79-2.36 1.83-4.98 2.09-7.59.75-9.74-11.52-11.84-11.52-4.98 0 4.98 7.86 19.38 7.86 27.76 0 10.21-5.76 15.71-13.88 16.5-8.38.79-20.16-10.47-20.16-10.47l4.98-14.4 2.88 2.09c-2.97 17.8 17.68 20.37 13.35 5.24-1.06-4.02-18.75-34.2 2.09-38.23 13.62-2.36 23.04 16.5 23.04 16.5l-7.85 10.46zm35.62-10.21c-11-30.38-60.49-127.53-191.95-129.62-53.42-1.05-94.27 15.45-132.76 37.97l85.63-9.17-91.39 20.69 25.14 19.64-3.93-16.5c7.5-1.71 39.15-8.45 66.77-8.9l-22.26 80.39c13.61-.7 18.97-8.98 19.64-22.78l4.98-1.05.26 26.71c-22.46 3.21-37.3 6.69-49.49 9.95l13.09-43.21-61.54-36.66 2.36 8.12 10.21 4.98c6.28 18.59 19.38 56.56 20.43 58.66 1.95 4.28 3.16 5.78 12.05 4.45l1.05 4.98c-16.08 4.86-23.66 7.61-39.02 14.4l-2.36-4.71c4.4-2.94 8.73-3.94 5.5-12.83-23.7-62.5-21.48-58.14-22.78-59.44l2.36-4.45 33.52 67.3c-3.84-11.87 1.68 1.69-32.99-78.82l-41.9 88.51 4.71-13.88-35.88-42.16 27.76 93.48-11.78 8.38C95 228.58 101.05 231.87 93.23 231.52c-5.5-.26-13.62 5.5-13.62 5.5L74.63 231c30.56-23.53 31.62-24.33 58.4-42.68l4.19 7.07s-5.76 4.19-7.86 7.07c-5.9 9.28 1.67 13.28 61.8 75.68l-18.85-58.92 39.8-10.21 25.66 30.64 4.45-12.31-4.98-24.62 13.09-3.4.52 3.14 3.67-10.47-94.27 29.33 11.26-4.98-13.62-42.42 17.28-9.17 30.11 36.14 28.54-13.09c-1.41-7.47-2.47-14.5-4.71-19.64l17.28 13.88 4.71-2.09-59.18-42.68 23.08 11.5c18.98-6.07 25.23-7.47 32.21-9.69l2.62 11c-12.55 12.55 1.43 16.82 6.55 19.38l-13.62-61.01 12.05 28.28c4.19-1.31 7.33-2.09 7.33-2.09l2.62 8.64s-3.14 1.05-6.28 2.09l8.9 20.95 33.78-65.73-20.69 61.01c42.42-24.09 81.44-36.66 131.98-35.88 67.04 1.05 167.33 40.85 199.8 139.83.78 2.1-.01 2.63-.79.27zM203.48 152.43s1.83-.52 4.19-1.31l9.43 7.59c-.4 0-3.44-.25-11.26 2.36l-2.36-8.64zm143.76 38.5c-1.57-.6-26.46-4.81-33.26 20.69l21.73 17.02 11.53-37.71zM318.43 67.07c-58.4 0-106.05 12.05-114.96 14.4v.79c8.38 2.09 14.4 4.19 21.21 11.78l1.57.26c6.55-1.83 48.97-13.88 110.24-13.88 180.16 0 301.67 116.79 301.67 223.37v9.95c0 1.31.79 2.62 1.05.52.52-2.09.79-8.64.79-19.64.26-83.79-96.63-227.55-321.57-227.55zm211.06 169.68c1.31-5.76 0-12.31-7.33-13.09-9.62-1.13-16.14 23.79-17.02 33.52-.79 5.5-1.31 14.93 6.02 14.93 4.68-.01 9.72-.91 18.33-35.36zm-61.53 42.95c-2.62-.79-9.43-.79-12.57 10.47-1.83 6.81.52 13.35 6.02 14.66 3.67 1.05 8.9.52 11.78-10.74 2.62-9.94-1.83-13.61-5.23-14.39zM491 300.65c1.83.52 3.14 1.05 5.76 1.83 0-1.83.52-8.38.79-12.05-1.05 1.31-5.5 8.12-6.55 9.95v.27z\"],\n    \"wolf-pack-battalion\": [512, 512, [], \"f514\", \"M267.73 471.53l10.56 15.84 5.28-12.32 5.28 7V512c21.06-7.92 21.11-66.86 25.51-97.21 4.62-31.89-.88-92.81 81.37-149.11-8.88-23.61-12-49.43-2.64-80.05C421 189 447 196.21 456.43 239.73l-30.35 8.36c11.15 23 17 46.76 13.2 72.14L412 313.18l-6.16 33.43-18.47-7-8.8 33.39-19.35-7 26.39 21.11 8.8-28.15L419 364.2l7-35.63 26.39 14.52c.25-20 7-58.06-8.8-84.45l26.39 5.28c4-22.07-2.38-39.21-7.92-56.74l22.43 9.68c-.44-25.07-29.94-56.79-61.58-58.5-20.22-1.09-56.74-25.17-54.1-51.9 2-19.87 17.45-42.62 43.11-49.7-44 36.51-9.68 67.3 5.28 73.46 4.4-11.44 17.54-69.08 0-130.2-40.39 22.87-89.65 65.1-93.2 147.79l-58 38.71-3.52 93.25L369.78 220l7 7-17.59 3.52-44 38.71-15.84-5.28-28.1 49.25-3.52 119.64 21.11 15.84-32.55 15.84-32.55-15.84 21.11-15.84-3.52-119.64-28.15-49.26-15.84 5.28-44-38.71-17.58-3.51 7-7 107.33 59.82-3.52-93.25-58.06-38.71C185 65.1 135.77 22.87 95.3 0c-17.54 61.12-4.4 118.76 0 130.2 15-6.16 49.26-36.95 5.28-73.46 25.66 7.08 41.15 29.83 43.11 49.7 2.63 26.74-33.88 50.81-54.1 51.9-31.65 1.72-61.15 33.44-61.59 58.51l22.43-9.68c-5.54 17.53-11.91 34.67-7.92 56.74l26.39-5.28c-15.76 26.39-9.05 64.43-8.8 84.45l26.39-14.52 7 35.63 24.63-5.28 8.8 28.15L153.35 366 134 373l-8.8-33.43-18.47 7-6.16-33.43-27.27 7c-3.82-25.38 2-49.1 13.2-72.14l-30.35-8.36c9.4-43.52 35.47-50.77 63.34-54.1 9.36 30.62 6.24 56.45-2.64 80.05 82.25 56.3 76.75 117.23 81.37 149.11 4.4 30.35 4.45 89.29 25.51 97.21v-29.83l5.28-7 5.28 12.32 10.56-15.84 11.44 21.11 11.43-21.1zm79.17-95L331.06 366c7.47-4.36 13.76-8.42 19.35-12.32-.6 7.22-.27 13.84-3.51 22.84zm28.15-49.26c-.4 10.94-.9 21.66-1.76 31.67-7.85-1.86-15.57-3.8-21.11-7 8.24-7.94 15.55-16.32 22.87-24.68zm24.63 5.28c0-13.43-2.05-24.21-5.28-33.43a235 235 0 0 1-18.47 27.27zm3.52-80.94c19.44 12.81 27.8 33.66 29.91 56.3-12.32-4.53-24.63-9.31-36.95-10.56 5.06-12 6.65-28.14 7-45.74zm-1.76-45.74c.81 14.3 1.84 28.82 1.76 42.23 19.22-8.11 29.78-9.72 44-14.08-10.61-18.96-27.2-25.53-45.76-28.16zM165.68 376.52L181.52 366c-7.47-4.36-13.76-8.42-19.35-12.32.6 7.26.27 13.88 3.51 22.88zm-28.15-49.26c.4 10.94.9 21.66 1.76 31.67 7.85-1.86 15.57-3.8 21.11-7-8.24-7.93-15.55-16.31-22.87-24.67zm-24.64 5.28c0-13.43 2-24.21 5.28-33.43a235 235 0 0 0 18.47 27.27zm-3.52-80.94c-19.44 12.81-27.8 33.66-29.91 56.3 12.32-4.53 24.63-9.31 37-10.56-5-12-6.65-28.14-7-45.74zm1.76-45.74c-.81 14.3-1.84 28.82-1.76 42.23-19.22-8.11-29.78-9.72-44-14.08 10.63-18.95 27.23-25.52 45.76-28.15z\"],\n    \"wordpress\": [512, 512, [], \"f19a\", \"M61.7 169.4l101.5 278C92.2 413 43.3 340.2 43.3 256c0-30.9 6.6-60.1 18.4-86.6zm337.9 75.9c0-26.3-9.4-44.5-17.5-58.7-10.8-17.5-20.9-32.4-20.9-49.9 0-19.6 14.8-37.8 35.7-37.8.9 0 1.8.1 2.8.2-37.9-34.7-88.3-55.9-143.7-55.9-74.3 0-139.7 38.1-177.8 95.9 5 .2 9.7.3 13.7.3 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l77.5 230.4L249.8 247l-33.1-90.8c-11.5-.7-22.3-2-22.3-2-11.5-.7-10.1-18.2 1.3-17.5 0 0 35.1 2.7 56 2.7 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l76.9 228.7 21.2-70.9c9-29.4 16-50.5 16-68.7zm-139.9 29.3l-63.8 185.5c19.1 5.6 39.2 8.7 60.1 8.7 24.8 0 48.5-4.3 70.6-12.1-.6-.9-1.1-1.9-1.5-2.9l-65.4-179.2zm183-120.7c.9 6.8 1.4 14 1.4 21.9 0 21.6-4 45.8-16.2 76.2l-65 187.9C426.2 403 468.7 334.5 468.7 256c0-37-9.4-71.8-26-102.1zM504 256c0 136.8-111.3 248-248 248C119.2 504 8 392.7 8 256 8 119.2 119.2 8 256 8c136.7 0 248 111.2 248 248zm-11.4 0c0-130.5-106.2-236.6-236.6-236.6C125.5 19.4 19.4 125.5 19.4 256S125.6 492.6 256 492.6c130.5 0 236.6-106.1 236.6-236.6z\"],\n    \"wordpress-simple\": [512, 512, [], \"f411\", \"M256 8C119.3 8 8 119.2 8 256c0 136.7 111.3 248 248 248s248-111.3 248-248C504 119.2 392.7 8 256 8zM33 256c0-32.3 6.9-63 19.3-90.7l106.4 291.4C84.3 420.5 33 344.2 33 256zm223 223c-21.9 0-43-3.2-63-9.1l66.9-194.4 68.5 187.8c.5 1.1 1 2.1 1.6 3.1-23.1 8.1-48 12.6-74 12.6zm30.7-327.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-21.9 0-58.7-2.8-58.7-2.8-12-.7-13.4 17.7-1.4 18.4 0 0 11.4 1.4 23.4 2.1l34.7 95.2L200.6 393l-81.2-241.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-4.2 0-9.1-.1-14.4-.3C109.6 73 178.1 33 256 33c58 0 110.9 22.2 150.6 58.5-1-.1-1.9-.2-2.9-.2-21.9 0-37.4 19.1-37.4 39.6 0 18.4 10.6 33.9 21.9 52.3 8.5 14.8 18.4 33.9 18.4 61.5 0 19.1-7.3 41.2-17 72.1l-22.2 74.3-80.7-239.6zm81.4 297.2l68.1-196.9c12.7-31.8 17-57.2 17-79.9 0-8.2-.5-15.8-1.5-22.9 17.4 31.8 27.3 68.2 27.3 107 0 82.3-44.6 154.1-110.9 192.7z\"],\n    \"wpbeginner\": [512, 512, [], \"f297\", \"M462.799 322.374C519.01 386.682 466.961 480 370.944 480c-39.602 0-78.824-17.687-100.142-50.04-6.887.356-22.702.356-29.59 0C219.848 462.381 180.588 480 141.069 480c-95.49 0-148.348-92.996-91.855-157.626C-29.925 190.523 80.479 32 256.006 32c175.632 0 285.87 158.626 206.793 290.374zm-339.647-82.972h41.529v-58.075h-41.529v58.075zm217.18 86.072v-23.839c-60.506 20.915-132.355 9.198-187.589-33.971l.246 24.897c51.101 46.367 131.746 57.875 187.343 32.913zm-150.753-86.072h166.058v-58.075H189.579v58.075z\"],\n    \"wpexplorer\": [512, 512, [], \"f2de\", \"M512 256c0 141.2-114.7 256-256 256C114.8 512 0 397.3 0 256S114.7 0 256 0s256 114.7 256 256zm-32 0c0-123.2-100.3-224-224-224C132.5 32 32 132.5 32 256s100.5 224 224 224 224-100.5 224-224zM160.9 124.6l86.9 37.1-37.1 86.9-86.9-37.1 37.1-86.9zm110 169.1l46.6 94h-14.6l-50-100-48.9 100h-14l51.1-106.9-22.3-9.4 6-14 68.6 29.1-6 14.3-16.5-7.1zm-11.8-116.3l68.6 29.4-29.4 68.3L230 246l29.1-68.6zm80.3 42.9l54.6 23.1-23.4 54.3-54.3-23.1 23.1-54.3z\"],\n    \"wpforms\": [448, 512, [], \"f298\", \"M448 75.2v361.7c0 24.3-19 43.2-43.2 43.2H43.2C19.3 480 0 461.4 0 436.8V75.2C0 51.1 18.8 32 43.2 32h361.7c24 0 43.1 18.8 43.1 43.2zm-37.3 361.6V75.2c0-3-2.6-5.8-5.8-5.8h-9.3L285.3 144 224 94.1 162.8 144 52.5 69.3h-9.3c-3.2 0-5.8 2.8-5.8 5.8v361.7c0 3 2.6 5.8 5.8 5.8h361.7c3.2.1 5.8-2.7 5.8-5.8zM150.2 186v37H76.7v-37h73.5zm0 74.4v37.3H76.7v-37.3h73.5zm11.1-147.3l54-43.7H96.8l64.5 43.7zm210 72.9v37h-196v-37h196zm0 74.4v37.3h-196v-37.3h196zm-84.6-147.3l64.5-43.7H232.8l53.9 43.7zM371.3 335v37.3h-99.4V335h99.4z\"],\n    \"wpressr\": [496, 512, [], \"f3e4\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm171.33 158.6c-15.18 34.51-30.37 69.02-45.63 103.5-2.44 5.51-6.89 8.24-12.97 8.24-23.02-.01-46.03.06-69.05-.05-5.12-.03-8.25 1.89-10.34 6.72-10.19 23.56-20.63 47-30.95 70.5-1.54 3.51-4.06 5.29-7.92 5.29-45.94-.01-91.87-.02-137.81 0-3.13 0-5.63-1.15-7.72-3.45-11.21-12.33-22.46-24.63-33.68-36.94-2.69-2.95-2.79-6.18-1.21-9.73 8.66-19.54 17.27-39.1 25.89-58.66 12.93-29.35 25.89-58.69 38.75-88.08 1.7-3.88 4.28-5.68 8.54-5.65 14.24.1 28.48.02 42.72.05 6.24.01 9.2 4.84 6.66 10.59-13.6 30.77-27.17 61.55-40.74 92.33-5.72 12.99-11.42 25.99-17.09 39-3.91 8.95 7.08 11.97 10.95 5.6.23-.37-1.42 4.18 30.01-67.69 1.36-3.1 3.41-4.4 6.77-4.39 15.21.08 30.43.02 45.64.04 5.56.01 7.91 3.64 5.66 8.75-8.33 18.96-16.71 37.9-24.98 56.89-4.98 11.43 8.08 12.49 11.28 5.33.04-.08 27.89-63.33 32.19-73.16 2.02-4.61 5.44-6.51 10.35-6.5 26.43.05 52.86 0 79.29.05 12.44.02 13.93-13.65 3.9-13.64-25.26.03-50.52.02-75.78.02-6.27 0-7.84-2.47-5.27-8.27 5.78-13.06 11.59-26.11 17.3-39.21 1.73-3.96 4.52-5.79 8.84-5.78 23.09.06 25.98.02 130.78.03 6.08-.01 8.03 2.79 5.62 8.27z\"],\n    \"xbox\": [512, 512, [], \"f412\", \"M369.9 318.2c44.3 54.3 64.7 98.8 54.4 118.7-7.9 15.1-56.7 44.6-92.6 55.9-29.6 9.3-68.4 13.3-100.4 10.2-38.2-3.7-76.9-17.4-110.1-39C93.3 445.8 87 438.3 87 423.4c0-29.9 32.9-82.3 89.2-142.1 32-33.9 76.5-73.7 81.4-72.6 9.4 2.1 84.3 75.1 112.3 109.5zM188.6 143.8c-29.7-26.9-58.1-53.9-86.4-63.4-15.2-5.1-16.3-4.8-28.7 8.1-29.2 30.4-53.5 79.7-60.3 122.4-5.4 34.2-6.1 43.8-4.2 60.5 5.6 50.5 17.3 85.4 40.5 120.9 9.5 14.6 12.1 17.3 9.3 9.9-4.2-11-.3-37.5 9.5-64 14.3-39 53.9-112.9 120.3-194.4zm311.6 63.5C483.3 127.3 432.7 77 425.6 77c-7.3 0-24.2 6.5-36 13.9-23.3 14.5-41 31.4-64.3 52.8C367.7 197 427.5 283.1 448.2 346c6.8 20.7 9.7 41.1 7.4 52.3-1.7 8.5-1.7 8.5 1.4 4.6 6.1-7.7 19.9-31.3 25.4-43.5 7.4-16.2 15-40.2 18.6-58.7 4.3-22.5 3.9-70.8-.8-93.4zM141.3 43C189 40.5 251 77.5 255.6 78.4c.7.1 10.4-4.2 21.6-9.7 63.9-31.1 94-25.8 107.4-25.2-63.9-39.3-152.7-50-233.9-11.7-23.4 11.1-24 11.9-9.4 11.2z\"],\n    \"xing\": [384, 512, [], \"f168\", \"M162.7 210c-1.8 3.3-25.2 44.4-70.1 123.5-4.9 8.3-10.8 12.5-17.7 12.5H9.8c-7.7 0-12.1-7.5-8.5-14.4l69-121.3c.2 0 .2-.1 0-.3l-43.9-75.6c-4.3-7.8.3-14.1 8.5-14.1H100c7.3 0 13.3 4.1 18 12.2l44.7 77.5zM382.6 46.1l-144 253v.3L330.2 466c3.9 7.1.2 14.1-8.5 14.1h-65.2c-7.6 0-13.6-4-18-12.2l-92.4-168.5c3.3-5.8 51.5-90.8 144.8-255.2 4.6-8.1 10.4-12.2 17.5-12.2h65.7c8 0 12.3 6.7 8.5 14.1z\"],\n    \"xing-square\": [448, 512, [], \"f169\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM140.4 320.2H93.8c-5.5 0-8.7-5.3-6-10.3l49.3-86.7c.1 0 .1-.1 0-.2l-31.4-54c-3-5.6.2-10.1 6-10.1h46.6c5.2 0 9.5 2.9 12.9 8.7l31.9 55.3c-1.3 2.3-18 31.7-50.1 88.2-3.5 6.2-7.7 9.1-12.6 9.1zm219.7-214.1L257.3 286.8v.2l65.5 119c2.8 5.1.1 10.1-6 10.1h-46.6c-5.5 0-9.7-2.9-12.9-8.7l-66-120.3c2.3-4.1 36.8-64.9 103.4-182.3 3.3-5.8 7.4-8.7 12.5-8.7h46.9c5.7-.1 8.8 4.7 6 10z\"],\n    \"y-combinator\": [448, 512, [], \"f23b\", \"M448 32v448H0V32h448zM236 287.5L313.5 142h-32.7L235 233c-4.7 9.3-9 18.3-12.8 26.8L210 233l-45.2-91h-35l76.7 143.8v94.5H236v-92.8z\"],\n    \"yahoo\": [448, 512, [], \"f19e\", \"M252 292l4 220c-12.7-2.2-23.5-3.9-32.3-3.9-8.4 0-19.2 1.7-32.3 3.9l4-220C140.4 197.2 85 95.2 21.4 0c11.9 3.1 23 3.9 33.2 3.9 9 0 20.4-.8 34.1-3.9 40.9 72.2 82.1 138.7 135 225.5C261 163.9 314.8 81.4 358.6 0c11.1 2.9 22 3.9 32.9 3.9 11.5 0 23.2-1 35-3.9C392.1 47.9 294.9 216.9 252 292z\"],\n    \"yammer\": [512, 512, [], \"f840\", \"M421.78 152.17A23.06 23.06 0 0 0 400.9 112c-.83.43-1.71.9-2.63 1.4-15.25 8.4-118.33 80.62-106.69 88.77s82.04-23.61 130.2-50zm0 217.17c-48.16-26.38-118.64-58.1-130.2-50s91.42 80.35 106.69 88.74c.92.51 1.8 1 2.63 1.41a23.07 23.07 0 0 0 20.88-40.15zM464.21 237c-.95 0-1.95-.06-3-.06-17.4 0-142.52 13.76-136.24 26.51s83.3 18.74 138.21 18.76a23 23 0 0 0 1-45.21zM31 96.65a24.88 24.88 0 0 1 46.14-18.4l81 205.06h1.21l77-203.53a23.52 23.52 0 0 1 44.45 15.27L171.2 368.44C152.65 415.66 134.08 448 77.91 448a139.67 139.67 0 0 1-23.81-1.95 21.31 21.31 0 0 1 6.9-41.77c.66.06 10.91.66 13.86.66 30.47 0 43.74-18.94 58.07-59.41z\"],\n    \"yandex\": [256, 512, [], \"f413\", \"M153.1 315.8L65.7 512H2l96-209.8c-45.1-22.9-75.2-64.4-75.2-141.1C22.7 53.7 90.8 0 171.7 0H254v512h-55.1V315.8h-45.8zm45.8-269.3h-29.4c-44.4 0-87.4 29.4-87.4 114.6 0 82.3 39.4 108.8 87.4 108.8h29.4V46.5z\"],\n    \"yandex-international\": [320, 512, [], \"f414\", \"M129.5 512V345.9L18.5 48h55.8l81.8 229.7L250.2 0h51.3L180.8 347.8V512h-51.3z\"],\n    \"yarn\": [496, 512, [], \"f7e3\", \"M393.9 345.2c-39 9.3-48.4 32.1-104 47.4 0 0-2.7 4-10.4 5.8-13.4 3.3-63.9 6-68.5 6.1-12.4.1-19.9-3.2-22-8.2-6.4-15.3 9.2-22 9.2-22-8.1-5-9-9.9-9.8-8.1-2.4 5.8-3.6 20.1-10.1 26.5-8.8 8.9-25.5 5.9-35.3.8-10.8-5.7.8-19.2.8-19.2s-5.8 3.4-10.5-3.6c-6-9.3-17.1-37.3 11.5-62-1.3-10.1-4.6-53.7 40.6-85.6 0 0-20.6-22.8-12.9-43.3 5-13.4 7-13.3 8.6-13.9 5.7-2.2 11.3-4.6 15.4-9.1 20.6-22.2 46.8-18 46.8-18s12.4-37.8 23.9-30.4c3.5 2.3 16.3 30.6 16.3 30.6s13.6-7.9 15.1-5c8.2 16 9.2 46.5 5.6 65.1-6.1 30.6-21.4 47.1-27.6 57.5-1.4 2.4 16.5 10 27.8 41.3 10.4 28.6 1.1 52.7 2.8 55.3.8 1.4 13.7.8 36.4-13.2 12.8-7.9 28.1-16.9 45.4-17 16.7-.5 17.6 19.2 4.9 22.2zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-79.3 75.2c-1.7-13.6-13.2-23-28-22.8-22 .3-40.5 11.7-52.8 19.2-4.8 3-8.9 5.2-12.4 6.8 3.1-44.5-22.5-73.1-28.7-79.4 7.8-11.3 18.4-27.8 23.4-53.2 4.3-21.7 3-55.5-6.9-74.5-1.6-3.1-7.4-11.2-21-7.4-9.7-20-13-22.1-15.6-23.8-1.1-.7-23.6-16.4-41.4 28-12.2.9-31.3 5.3-47.5 22.8-2 2.2-5.9 3.8-10.1 5.4h.1c-8.4 3-12.3 9.9-16.9 22.3-6.5 17.4.2 34.6 6.8 45.7-17.8 15.9-37 39.8-35.7 82.5-34 36-11.8 73-5.6 79.6-1.6 11.1 3.7 19.4 12 23.8 12.6 6.7 30.3 9.6 43.9 2.8 4.9 5.2 13.8 10.1 30 10.1 6.8 0 58-2.9 72.6-6.5 6.8-1.6 11.5-4.5 14.6-7.1 9.8-3.1 36.8-12.3 62.2-28.7 18-11.7 24.2-14.2 37.6-17.4 12.9-3.2 21-15.1 19.4-28.2z\"],\n    \"yelp\": [384, 512, [], \"f1e9\", \"M42.9 240.32l99.62 48.61c19.2 9.4 16.2 37.51-4.5 42.71L30.5 358.45a22.79 22.79 0 0 1-28.21-19.6 197.16 197.16 0 0 1 9-85.32 22.8 22.8 0 0 1 31.61-13.21zm44 239.25a199.45 199.45 0 0 0 79.42 32.11A22.78 22.78 0 0 0 192.94 490l3.9-110.82c.7-21.3-25.5-31.91-39.81-16.1l-74.21 82.4a22.82 22.82 0 0 0 4.09 34.09zm145.34-109.92l58.81 94a22.93 22.93 0 0 0 34 5.5 198.36 198.36 0 0 0 52.71-67.61A23 23 0 0 0 364.17 370l-105.42-34.26c-20.31-6.5-37.81 15.8-26.51 33.91zm148.33-132.23a197.44 197.44 0 0 0-50.41-69.31 22.85 22.85 0 0 0-34 4.4l-62 91.92c-11.9 17.7 4.7 40.61 25.2 34.71L366 268.63a23 23 0 0 0 14.61-31.21zM62.11 30.18a22.86 22.86 0 0 0-9.9 32l104.12 180.44c11.7 20.2 42.61 11.9 42.61-11.4V22.88a22.67 22.67 0 0 0-24.5-22.8 320.37 320.37 0 0 0-112.33 30.1z\"],\n    \"yoast\": [448, 512, [], \"f2b1\", \"M91.3 76h186l-7 18.9h-179c-39.7 0-71.9 31.6-71.9 70.3v205.4c0 35.4 24.9 70.3 84 70.3V460H91.3C41.2 460 0 419.8 0 370.5V165.2C0 115.9 40.7 76 91.3 76zm229.1-56h66.5C243.1 398.1 241.2 418.9 202.2 459.3c-20.8 21.6-49.3 31.7-78.3 32.7v-51.1c49.2-7.7 64.6-49.9 64.6-75.3 0-20.1.6-12.6-82.1-223.2h61.4L218.2 299 320.4 20zM448 161.5V460H234c6.6-9.6 10.7-16.3 12.1-19.4h182.5V161.5c0-32.5-17.1-51.9-48.2-62.9l6.7-17.6c41.7 13.6 60.9 43.1 60.9 80.5z\"],\n    \"youtube\": [576, 512, [], \"f167\", \"M549.655 124.083c-6.281-23.65-24.787-42.276-48.284-48.597C458.781 64 288 64 288 64S117.22 64 74.629 75.486c-23.497 6.322-42.003 24.947-48.284 48.597-11.412 42.867-11.412 132.305-11.412 132.305s0 89.438 11.412 132.305c6.281 23.65 24.787 41.5 48.284 47.821C117.22 448 288 448 288 448s170.78 0 213.371-11.486c23.497-6.321 42.003-24.171 48.284-47.821 11.412-42.867 11.412-132.305 11.412-132.305s0-89.438-11.412-132.305zm-317.51 213.508V175.185l142.739 81.205-142.739 81.201z\"],\n    \"youtube-square\": [448, 512, [], \"f431\", \"M186.8 202.1l95.2 54.1-95.2 54.1V202.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-42 176.3s0-59.6-7.6-88.2c-4.2-15.8-16.5-28.2-32.2-32.4C337.9 128 224 128 224 128s-113.9 0-142.2 7.7c-15.7 4.2-28 16.6-32.2 32.4-7.6 28.5-7.6 88.2-7.6 88.2s0 59.6 7.6 88.2c4.2 15.8 16.5 27.7 32.2 31.9C110.1 384 224 384 224 384s113.9 0 142.2-7.7c15.7-4.2 28-16.1 32.2-31.9 7.6-28.5 7.6-88.1 7.6-88.1z\"],\n    \"zhihu\": [640, 512, [], \"f63f\", \"M170.54 148.13v217.54l23.43.01 7.71 26.37 42.01-26.37h49.53V148.13H170.54zm97.75 193.93h-27.94l-27.9 17.51-5.08-17.47-11.9-.04V171.75h72.82v170.31zm-118.46-94.39H97.5c1.74-27.1 2.2-51.59 2.2-73.46h51.16s1.97-22.56-8.58-22.31h-88.5c3.49-13.12 7.87-26.66 13.12-40.67 0 0-24.07 0-32.27 21.57-3.39 8.9-13.21 43.14-30.7 78.12 5.89-.64 25.37-1.18 36.84-22.21 2.11-5.89 2.51-6.66 5.14-14.53h28.87c0 10.5-1.2 66.88-1.68 73.44H20.83c-11.74 0-15.56 23.62-15.56 23.62h65.58C66.45 321.1 42.83 363.12 0 396.34c20.49 5.85 40.91-.93 51-9.9 0 0 22.98-20.9 35.59-69.25l53.96 64.94s7.91-26.89-1.24-39.99c-7.58-8.92-28.06-33.06-36.79-41.81L87.9 311.95c4.36-13.98 6.99-27.55 7.87-40.67h61.65s-.09-23.62-7.59-23.62v.01zm412.02-1.6c20.83-25.64 44.98-58.57 44.98-58.57s-18.65-14.8-27.38-4.06c-6 8.15-36.83 48.2-36.83 48.2l19.23 14.43zm-150.09-59.09c-9.01-8.25-25.91 2.13-25.91 2.13s39.52 55.04 41.12 57.45l19.46-13.73s-25.67-37.61-34.66-45.86h-.01zM640 258.35c-19.78 0-130.91.93-131.06.93v-101c4.81 0 12.42-.4 22.85-1.2 40.88-2.41 70.13-4 87.77-4.81 0 0 12.22-27.19-.59-33.44-3.07-1.18-23.17 4.58-23.17 4.58s-165.22 16.49-232.36 18.05c1.6 8.82 7.62 17.08 15.78 19.55 13.31 3.48 22.69 1.7 49.15.89 24.83-1.6 43.68-2.43 56.51-2.43v99.81H351.41s2.82 22.31 25.51 22.85h107.94v70.92c0 13.97-11.19 21.99-24.48 21.12-14.08.11-26.08-1.15-41.69-1.81 1.99 3.97 6.33 14.39 19.31 21.84 9.88 4.81 16.17 6.57 26.02 6.57 29.56 0 45.67-17.28 44.89-45.31v-73.32h122.36c9.68 0 8.7-23.78 8.7-23.78l.03-.01z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fab', icons);\n  });\n\n}());\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/conflict-detection.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? factory(exports) :\n  typeof define === 'function' && define.amd ? define(['exports'], factory) :\n  (factory((global['fontawesome-free-conflict-detection'] = {})));\n}(this, (function (exports) { 'use strict';\n\n  function _typeof(obj) {\n    if (typeof Symbol === \"function\" && typeof Symbol.iterator === \"symbol\") {\n      _typeof = function (obj) {\n        return typeof obj;\n      };\n    } else {\n      _typeof = function (obj) {\n        return obj && typeof Symbol === \"function\" && obj.constructor === Symbol && obj !== Symbol.prototype ? \"symbol\" : typeof obj;\n      };\n    }\n\n    return _typeof(obj);\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var functions = [];\n\n  var listener = function listener() {\n    DOCUMENT.removeEventListener('DOMContentLoaded', listener);\n    loaded = 1;\n    functions.map(function (fn) {\n      return fn();\n    });\n  };\n\n  var loaded = false;\n\n  if (IS_DOM) {\n    loaded = (DOCUMENT.documentElement.doScroll ? /^loaded|^c/ : /^loaded|^i|^c/).test(DOCUMENT.readyState);\n    if (!loaded) DOCUMENT.addEventListener('DOMContentLoaded', listener);\n  }\n\n  function domready (fn) {\n    if (!IS_DOM) return;\n    loaded ? setTimeout(fn, 0) : functions.push(fn);\n  }\n\n  function report (_ref) {\n    var nodesTested = _ref.nodesTested,\n        nodesFound = _ref.nodesFound;\n    var timedOutTests = {};\n\n    for (var key in nodesFound) {\n      if (!(nodesTested.conflict[key] || nodesTested.noConflict[key])) {\n        timedOutTests[key] = nodesFound[key];\n      }\n    }\n\n    var conflictsCount = Object.keys(nodesTested.conflict).length;\n\n    if (conflictsCount > 0) {\n      console.info(\"%cConflict\".concat(conflictsCount > 1 ? 's' : '', \" found:\"), 'color: darkred; font-size: large');\n      var data = {};\n\n      for (var _key in nodesTested.conflict) {\n        var item = nodesTested.conflict[_key];\n        data[_key] = {\n          'tagName': item.tagName,\n          'src/href': item.src || item.href || 'n/a',\n          'innerText excerpt': item.innerText && item.innerText !== '' ? item.innerText.slice(0, 200) + '...' : '(empty)'\n        };\n      }\n\n      console.table(data);\n    }\n\n    var noConflictsCount = Object.keys(nodesTested.noConflict).length;\n\n    if (noConflictsCount > 0) {\n      console.info(\"%cNo conflict\".concat(noConflictsCount > 1 ? 's' : '', \" found with \").concat(noConflictsCount == 1 ? 'this' : 'these', \":\"), 'color: green; font-size: large');\n      var _data = {};\n\n      for (var _key2 in nodesTested.noConflict) {\n        var _item = nodesTested.noConflict[_key2];\n        _data[_key2] = {\n          'tagName': _item.tagName,\n          'src/href': _item.src || _item.href || 'n/a',\n          'innerText excerpt': _item.innerText && _item.innerText !== '' ? _item.innerText.slice(0, 200) + '...' : '(empty)'\n        };\n      }\n\n      console.table(_data);\n    }\n\n    var timeOutCount = Object.keys(timedOutTests).length;\n\n    if (timeOutCount > 0) {\n      console.info(\"%cLeftovers--we timed out before collecting test results for \".concat(timeOutCount == 1 ? 'this' : 'these', \":\"), 'color: blue; font-size: large');\n      var _data2 = {};\n\n      for (var _key3 in timedOutTests) {\n        var _item2 = timedOutTests[_key3];\n        _data2[_key3] = {\n          'tagName': _item2.tagName,\n          'src/href': _item2.src || _item2.href || 'n/a',\n          'innerText excerpt': _item2.innerText && _item2.innerText !== '' ? _item2.innerText.slice(0, 200) + '...' : '(empty)'\n        };\n      }\n\n      console.table(_data2);\n    }\n  }\n\n  var commonjsGlobal = typeof window !== 'undefined' ? window : typeof global !== 'undefined' ? global : typeof self !== 'undefined' ? self : {};\n\n  function createCommonjsModule(fn, module) {\n  \treturn module = { exports: {} }, fn(module, module.exports), module.exports;\n  }\n\n  var md5 = createCommonjsModule(function (module) {\n\n    (function ($) {\n      /**\n       * Add integers, wrapping at 2^32.\n       * This uses 16-bit operations internally to work around bugs in interpreters.\n       *\n       * @param {number} x First integer\n       * @param {number} y Second integer\n       * @returns {number} Sum\n       */\n\n      function safeAdd(x, y) {\n        var lsw = (x & 0xffff) + (y & 0xffff);\n        var msw = (x >> 16) + (y >> 16) + (lsw >> 16);\n        return msw << 16 | lsw & 0xffff;\n      }\n      /**\n       * Bitwise rotate a 32-bit number to the left.\n       *\n       * @param {number} num 32-bit number\n       * @param {number} cnt Rotation count\n       * @returns {number} Rotated number\n       */\n\n\n      function bitRotateLeft(num, cnt) {\n        return num << cnt | num >>> 32 - cnt;\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} q q\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5cmn(q, a, b, x, s, t) {\n        return safeAdd(bitRotateLeft(safeAdd(safeAdd(a, q), safeAdd(x, t)), s), b);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5ff(a, b, c, d, x, s, t) {\n        return md5cmn(b & c | ~b & d, a, b, x, s, t);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5gg(a, b, c, d, x, s, t) {\n        return md5cmn(b & d | c & ~d, a, b, x, s, t);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5hh(a, b, c, d, x, s, t) {\n        return md5cmn(b ^ c ^ d, a, b, x, s, t);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5ii(a, b, c, d, x, s, t) {\n        return md5cmn(c ^ (b | ~d), a, b, x, s, t);\n      }\n      /**\n       * Calculate the MD5 of an array of little-endian words, and a bit length.\n       *\n       * @param {Array} x Array of little-endian words\n       * @param {number} len Bit length\n       * @returns {Array<number>} MD5 Array\n       */\n\n\n      function binlMD5(x, len) {\n        /* append padding */\n        x[len >> 5] |= 0x80 << len % 32;\n        x[(len + 64 >>> 9 << 4) + 14] = len;\n        var i;\n        var olda;\n        var oldb;\n        var oldc;\n        var oldd;\n        var a = 1732584193;\n        var b = -271733879;\n        var c = -1732584194;\n        var d = 271733878;\n\n        for (i = 0; i < x.length; i += 16) {\n          olda = a;\n          oldb = b;\n          oldc = c;\n          oldd = d;\n          a = md5ff(a, b, c, d, x[i], 7, -680876936);\n          d = md5ff(d, a, b, c, x[i + 1], 12, -389564586);\n          c = md5ff(c, d, a, b, x[i + 2], 17, 606105819);\n          b = md5ff(b, c, d, a, x[i + 3], 22, -1044525330);\n          a = md5ff(a, b, c, d, x[i + 4], 7, -176418897);\n          d = md5ff(d, a, b, c, x[i + 5], 12, 1200080426);\n          c = md5ff(c, d, a, b, x[i + 6], 17, -1473231341);\n          b = md5ff(b, c, d, a, x[i + 7], 22, -45705983);\n          a = md5ff(a, b, c, d, x[i + 8], 7, 1770035416);\n          d = md5ff(d, a, b, c, x[i + 9], 12, -1958414417);\n          c = md5ff(c, d, a, b, x[i + 10], 17, -42063);\n          b = md5ff(b, c, d, a, x[i + 11], 22, -1990404162);\n          a = md5ff(a, b, c, d, x[i + 12], 7, 1804603682);\n          d = md5ff(d, a, b, c, x[i + 13], 12, -40341101);\n          c = md5ff(c, d, a, b, x[i + 14], 17, -1502002290);\n          b = md5ff(b, c, d, a, x[i + 15], 22, 1236535329);\n          a = md5gg(a, b, c, d, x[i + 1], 5, -165796510);\n          d = md5gg(d, a, b, c, x[i + 6], 9, -1069501632);\n          c = md5gg(c, d, a, b, x[i + 11], 14, 643717713);\n          b = md5gg(b, c, d, a, x[i], 20, -373897302);\n          a = md5gg(a, b, c, d, x[i + 5], 5, -701558691);\n          d = md5gg(d, a, b, c, x[i + 10], 9, 38016083);\n          c = md5gg(c, d, a, b, x[i + 15], 14, -660478335);\n          b = md5gg(b, c, d, a, x[i + 4], 20, -405537848);\n          a = md5gg(a, b, c, d, x[i + 9], 5, 568446438);\n          d = md5gg(d, a, b, c, x[i + 14], 9, -1019803690);\n          c = md5gg(c, d, a, b, x[i + 3], 14, -187363961);\n          b = md5gg(b, c, d, a, x[i + 8], 20, 1163531501);\n          a = md5gg(a, b, c, d, x[i + 13], 5, -1444681467);\n          d = md5gg(d, a, b, c, x[i + 2], 9, -51403784);\n          c = md5gg(c, d, a, b, x[i + 7], 14, 1735328473);\n          b = md5gg(b, c, d, a, x[i + 12], 20, -1926607734);\n          a = md5hh(a, b, c, d, x[i + 5], 4, -378558);\n          d = md5hh(d, a, b, c, x[i + 8], 11, -2022574463);\n          c = md5hh(c, d, a, b, x[i + 11], 16, 1839030562);\n          b = md5hh(b, c, d, a, x[i + 14], 23, -35309556);\n          a = md5hh(a, b, c, d, x[i + 1], 4, -1530992060);\n          d = md5hh(d, a, b, c, x[i + 4], 11, 1272893353);\n          c = md5hh(c, d, a, b, x[i + 7], 16, -155497632);\n          b = md5hh(b, c, d, a, x[i + 10], 23, -1094730640);\n          a = md5hh(a, b, c, d, x[i + 13], 4, 681279174);\n          d = md5hh(d, a, b, c, x[i], 11, -358537222);\n          c = md5hh(c, d, a, b, x[i + 3], 16, -722521979);\n          b = md5hh(b, c, d, a, x[i + 6], 23, 76029189);\n          a = md5hh(a, b, c, d, x[i + 9], 4, -640364487);\n          d = md5hh(d, a, b, c, x[i + 12], 11, -421815835);\n          c = md5hh(c, d, a, b, x[i + 15], 16, 530742520);\n          b = md5hh(b, c, d, a, x[i + 2], 23, -995338651);\n          a = md5ii(a, b, c, d, x[i], 6, -198630844);\n          d = md5ii(d, a, b, c, x[i + 7], 10, 1126891415);\n          c = md5ii(c, d, a, b, x[i + 14], 15, -1416354905);\n          b = md5ii(b, c, d, a, x[i + 5], 21, -57434055);\n          a = md5ii(a, b, c, d, x[i + 12], 6, 1700485571);\n          d = md5ii(d, a, b, c, x[i + 3], 10, -1894986606);\n          c = md5ii(c, d, a, b, x[i + 10], 15, -1051523);\n          b = md5ii(b, c, d, a, x[i + 1], 21, -2054922799);\n          a = md5ii(a, b, c, d, x[i + 8], 6, 1873313359);\n          d = md5ii(d, a, b, c, x[i + 15], 10, -30611744);\n          c = md5ii(c, d, a, b, x[i + 6], 15, -1560198380);\n          b = md5ii(b, c, d, a, x[i + 13], 21, 1309151649);\n          a = md5ii(a, b, c, d, x[i + 4], 6, -145523070);\n          d = md5ii(d, a, b, c, x[i + 11], 10, -1120210379);\n          c = md5ii(c, d, a, b, x[i + 2], 15, 718787259);\n          b = md5ii(b, c, d, a, x[i + 9], 21, -343485551);\n          a = safeAdd(a, olda);\n          b = safeAdd(b, oldb);\n          c = safeAdd(c, oldc);\n          d = safeAdd(d, oldd);\n        }\n\n        return [a, b, c, d];\n      }\n      /**\n       * Convert an array of little-endian words to a string\n       *\n       * @param {Array<number>} input MD5 Array\n       * @returns {string} MD5 string\n       */\n\n\n      function binl2rstr(input) {\n        var i;\n        var output = '';\n        var length32 = input.length * 32;\n\n        for (i = 0; i < length32; i += 8) {\n          output += String.fromCharCode(input[i >> 5] >>> i % 32 & 0xff);\n        }\n\n        return output;\n      }\n      /**\n       * Convert a raw string to an array of little-endian words\n       * Characters >255 have their high-byte silently ignored.\n       *\n       * @param {string} input Raw input string\n       * @returns {Array<number>} Array of little-endian words\n       */\n\n\n      function rstr2binl(input) {\n        var i;\n        var output = [];\n        output[(input.length >> 2) - 1] = undefined;\n\n        for (i = 0; i < output.length; i += 1) {\n          output[i] = 0;\n        }\n\n        var length8 = input.length * 8;\n\n        for (i = 0; i < length8; i += 8) {\n          output[i >> 5] |= (input.charCodeAt(i / 8) & 0xff) << i % 32;\n        }\n\n        return output;\n      }\n      /**\n       * Calculate the MD5 of a raw string\n       *\n       * @param {string} s Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rstrMD5(s) {\n        return binl2rstr(binlMD5(rstr2binl(s), s.length * 8));\n      }\n      /**\n       * Calculates the HMAC-MD5 of a key and some data (raw strings)\n       *\n       * @param {string} key HMAC key\n       * @param {string} data Raw input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rstrHMACMD5(key, data) {\n        var i;\n        var bkey = rstr2binl(key);\n        var ipad = [];\n        var opad = [];\n        var hash;\n        ipad[15] = opad[15] = undefined;\n\n        if (bkey.length > 16) {\n          bkey = binlMD5(bkey, key.length * 8);\n        }\n\n        for (i = 0; i < 16; i += 1) {\n          ipad[i] = bkey[i] ^ 0x36363636;\n          opad[i] = bkey[i] ^ 0x5c5c5c5c;\n        }\n\n        hash = binlMD5(ipad.concat(rstr2binl(data)), 512 + data.length * 8);\n        return binl2rstr(binlMD5(opad.concat(hash), 512 + 128));\n      }\n      /**\n       * Convert a raw string to a hex string\n       *\n       * @param {string} input Raw input string\n       * @returns {string} Hex encoded string\n       */\n\n\n      function rstr2hex(input) {\n        var hexTab = '0123456789abcdef';\n        var output = '';\n        var x;\n        var i;\n\n        for (i = 0; i < input.length; i += 1) {\n          x = input.charCodeAt(i);\n          output += hexTab.charAt(x >>> 4 & 0x0f) + hexTab.charAt(x & 0x0f);\n        }\n\n        return output;\n      }\n      /**\n       * Encode a string as UTF-8\n       *\n       * @param {string} input Input string\n       * @returns {string} UTF8 string\n       */\n\n\n      function str2rstrUTF8(input) {\n        return unescape(encodeURIComponent(input));\n      }\n      /**\n       * Encodes input string as raw MD5 string\n       *\n       * @param {string} s Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rawMD5(s) {\n        return rstrMD5(str2rstrUTF8(s));\n      }\n      /**\n       * Encodes input string as Hex encoded string\n       *\n       * @param {string} s Input string\n       * @returns {string} Hex encoded string\n       */\n\n\n      function hexMD5(s) {\n        return rstr2hex(rawMD5(s));\n      }\n      /**\n       * Calculates the raw HMAC-MD5 for the given key and data\n       *\n       * @param {string} k HMAC key\n       * @param {string} d Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rawHMACMD5(k, d) {\n        return rstrHMACMD5(str2rstrUTF8(k), str2rstrUTF8(d));\n      }\n      /**\n       * Calculates the Hex encoded HMAC-MD5 for the given key and data\n       *\n       * @param {string} k HMAC key\n       * @param {string} d Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function hexHMACMD5(k, d) {\n        return rstr2hex(rawHMACMD5(k, d));\n      }\n      /**\n       * Calculates MD5 value for a given string.\n       * If a key is provided, calculates the HMAC-MD5 value.\n       * Returns a Hex encoded string unless the raw argument is given.\n       *\n       * @param {string} string Input string\n       * @param {string} [key] HMAC key\n       * @param {boolean} raw Raw oytput switch\n       * @returns {string} MD5 output\n       */\n\n\n      function md5(string, key, raw) {\n        if (!key) {\n          if (!raw) {\n            return hexMD5(string);\n          }\n\n          return rawMD5(string);\n        }\n\n        if (!raw) {\n          return hexHMACMD5(key, string);\n        }\n\n        return rawHMACMD5(key, string);\n      }\n\n      if (module.exports) {\n        module.exports = md5;\n      } else {\n        $.md5 = md5;\n      }\n    })(commonjsGlobal);\n  });\n\n  function md5ForNode(node) {\n    if (null === node || 'object' !== _typeof(node)) return undefined;\n\n    if (node.src) {\n      return md5(node.src);\n    } else if (node.href) {\n      return md5(node.href);\n    } else if (node.innerText && '' !== node.innerText) {\n      // eslint-disable-line yoda\n      return md5(node.innerText);\n    } else {\n      return undefined;\n    }\n  }\n\n  var diagScriptId = 'fa-kits-diag';\n  var nodeUnderTestId = 'fa-kits-node-under-test';\n  var md5Attr = 'data-md5';\n  var detectionIgnoreAttr = 'data-fa-detection-ignore';\n  var timeoutAttr = 'data-fa-detection-timeout';\n  var resultsCollectionMaxWaitAttr = 'data-fa-detection-results-collection-max-wait';\n\n  function pollUntil(_ref) {\n    var _ref$fn = _ref.fn,\n        fn = _ref$fn === void 0 ? function () {\n      return true;\n    } : _ref$fn,\n        _ref$initialDuration = _ref.initialDuration,\n        initialDuration = _ref$initialDuration === void 0 ? 1 : _ref$initialDuration,\n        _ref$maxDuration = _ref.maxDuration,\n        maxDuration = _ref$maxDuration === void 0 ? WINDOW.FontAwesomeDetection.timeout : _ref$maxDuration,\n        _ref$showProgress = _ref.showProgress,\n        showProgress = _ref$showProgress === void 0 ? false : _ref$showProgress,\n        progressIndicator = _ref.progressIndicator;\n    return new Promise(function (resolve, reject) {\n      // eslint-disable-line compat/compat\n      function poll(duration, cumulativeDuration) {\n        setTimeout(function () {\n          var result = fn();\n\n          if (showProgress) {\n            console.info(progressIndicator);\n          }\n\n          if (!!result) {\n            // eslint-disable-line no-extra-boolean-cast\n            resolve(result);\n          } else {\n            var nextDuration = 250;\n            var nextCumulativeDuration = nextDuration + cumulativeDuration;\n\n            if (nextCumulativeDuration <= maxDuration) {\n              poll(nextDuration, nextCumulativeDuration);\n            } else {\n              reject('timeout'); // eslint-disable-line prefer-promise-reject-errors\n            }\n          }\n        }, duration);\n      }\n\n      poll(initialDuration, 0);\n    });\n  }\n\n  function detectWebfontConflicts() {\n    var linkTags = Array.from(DOCUMENT.getElementsByTagName('link')).filter(function (t) {\n      return !t.hasAttribute(detectionIgnoreAttr);\n    });\n    var styleTags = Array.from(DOCUMENT.getElementsByTagName('style')).filter(function (t) {\n      if (t.hasAttribute(detectionIgnoreAttr)) {\n        return false;\n      } // If the browser has loaded the FA5 CSS, let's not test that <style> element.\n      // Its enough that we'll be testing for traces of the corresponding JS being loaded, and testing\n      // this <style> would only produce a false negative anyway.\n\n\n      if (WINDOW.FontAwesomeConfig && t.innerText.match(new RegExp(\"svg:not\\\\(:root\\\\)\\\\.\".concat(WINDOW.FontAwesomeConfig.replacementClass)))) {\n        return false;\n      }\n\n      return true;\n    });\n\n    function runDiag(scriptOrLinkTag, md5) {\n      var diagFrame = DOCUMENT.createElement('iframe'); // Using \"visibility: hidden; position: absolute\" instead of \"display: none;\" because\n      // Firefox will not return the expected results for getComputedStyle if our iframe has display: none.\n\n      diagFrame.setAttribute('style', 'visibility: hidden; position: absolute; height: 0; width: 0;');\n      var testIconId = 'fa-test-icon-' + md5;\n      var iTag = DOCUMENT.createElement('i');\n      iTag.setAttribute('class', 'fa fa-coffee');\n      iTag.setAttribute('id', testIconId);\n      var diagScript = DOCUMENT.createElement('script');\n      diagScript.setAttribute('id', diagScriptId); // WARNING: this function will be toString()'d and assigned to innerText of the diag script\n      // element that we'll be putting into a diagnostic iframe.\n      // That means that this code won't compile until after the outer script has run and injected\n      // this code into the iframe. There are some compile time errors that might occur there.\n      // For example, using single line (double-slash) comments like this one inside that function\n      // will probably cause it to choke. Chrome will show an error like this:\n      // Uncaught SyntaxError: Unexpected end of input\n\n      var diagScriptFun = function diagScriptFun(nodeUnderTestId, testIconId, md5, parentOrigin) {\n        parent.FontAwesomeDetection.__pollUntil({\n          fn: function fn() {\n            var iEl = document.getElementById(testIconId);\n            var computedStyle = window.getComputedStyle(iEl);\n            var fontFamily = computedStyle.getPropertyValue('font-family');\n\n            if (!!fontFamily.match(/FontAwesome/) || !!fontFamily.match(/Font Awesome 5/)) {\n              return true;\n            } else {\n              return false;\n            }\n          }\n        }).then(function () {\n          var node = document.getElementById(nodeUnderTestId);\n          parent.postMessage({\n            type: 'fontawesome-conflict',\n            technology: 'webfont',\n            href: node.href,\n            innerText: node.innerText,\n            tagName: node.tagName,\n            md5: md5\n          }, parentOrigin);\n        }).catch(function (e) {\n          var node = document.getElementById(nodeUnderTestId);\n\n          if (e === 'timeout') {\n            parent.postMessage({\n              type: 'no-conflict',\n              technology: 'webfont',\n              href: node.src,\n              innerText: node.innerText,\n              tagName: node.tagName,\n              md5: md5\n            }, parentOrigin);\n          } else {\n            console.error(e);\n          }\n        });\n      };\n\n      var parentOrigin = WINDOW.location.origin === 'file://' ? '*' : WINDOW.location.origin;\n      diagScript.innerText = \"(\".concat(diagScriptFun.toString(), \")('\").concat(nodeUnderTestId, \"', '\").concat(testIconId || 'foo', \"', '\").concat(md5, \"', '\").concat(parentOrigin, \"');\");\n\n      diagFrame.onload = function () {\n        diagFrame.contentDocument.head.appendChild(diagScript);\n        diagFrame.contentDocument.head.appendChild(scriptOrLinkTag);\n        diagFrame.contentDocument.body.appendChild(iTag);\n      };\n\n      domready(function () {\n        return DOCUMENT.body.appendChild(diagFrame);\n      });\n    }\n\n    var cssByMD5 = {};\n\n    for (var i = 0; i < linkTags.length; i++) {\n      var linkUnderTest = DOCUMENT.createElement('link');\n      linkUnderTest.setAttribute('id', nodeUnderTestId);\n      linkUnderTest.setAttribute('href', linkTags[i].href);\n      linkUnderTest.setAttribute('rel', linkTags[i].rel);\n      var md5ForLink = md5ForNode(linkTags[i]);\n      linkUnderTest.setAttribute(md5Attr, md5ForLink);\n      cssByMD5[md5ForLink] = linkTags[i];\n      runDiag(linkUnderTest, md5ForLink);\n    }\n\n    for (var _i = 0; _i < styleTags.length; _i++) {\n      var styleUnderTest = DOCUMENT.createElement('style');\n      styleUnderTest.setAttribute('id', nodeUnderTestId);\n      var md5ForStyle = md5ForNode(styleTags[_i]);\n      styleUnderTest.setAttribute(md5Attr, md5ForStyle);\n      styleUnderTest.innerText = styleTags[_i].innerText;\n      cssByMD5[md5ForStyle] = styleTags[_i];\n      runDiag(styleUnderTest, md5ForStyle);\n    }\n\n    return cssByMD5;\n  }\n\n  function detectSvgConflicts(currentScript) {\n    var scripts = Array.from(DOCUMENT.scripts).filter(function (t) {\n      return !t.hasAttribute(detectionIgnoreAttr) && t !== currentScript;\n    });\n    var scriptsByMD5 = {};\n\n    var _loop = function _loop(scriptIdx) {\n      var diagFrame = DOCUMENT.createElement('iframe');\n      diagFrame.setAttribute('style', 'display:none;');\n      var scriptUnderTest = DOCUMENT.createElement('script');\n      scriptUnderTest.setAttribute('id', nodeUnderTestId);\n      var md5ForScript = md5ForNode(scripts[scriptIdx]);\n      scriptUnderTest.setAttribute(md5Attr, md5ForScript);\n      scriptsByMD5[md5ForScript] = scripts[scriptIdx];\n\n      if (scripts[scriptIdx].src !== '') {\n        scriptUnderTest.src = scripts[scriptIdx].src;\n      }\n\n      if (scripts[scriptIdx].innerText !== '') {\n        scriptUnderTest.innerText = scripts[scriptIdx].innerText;\n      }\n\n      scriptUnderTest.async = true;\n      var diagScript = DOCUMENT.createElement('script');\n      diagScript.setAttribute('id', diagScriptId);\n      var parentOrigin = WINDOW.location.origin === 'file://' ? '*' : WINDOW.location.origin;\n\n      var diagScriptFun = function diagScriptFun(nodeUnderTestId, md5, parentOrigin) {\n        parent.FontAwesomeDetection.__pollUntil({\n          fn: function fn() {\n            return !!window.FontAwesomeConfig;\n          }\n        }).then(function () {\n          var scriptNode = document.getElementById(nodeUnderTestId);\n          parent.postMessage({\n            type: 'fontawesome-conflict',\n            technology: 'js',\n            src: scriptNode.src,\n            innerText: scriptNode.innerText,\n            tagName: scriptNode.tagName,\n            md5: md5\n          }, parentOrigin);\n        }).catch(function (e) {\n          var scriptNode = document.getElementById(nodeUnderTestId);\n\n          if (e === 'timeout') {\n            parent.postMessage({\n              type: 'no-conflict',\n              src: scriptNode.src,\n              innerText: scriptNode.innerText,\n              tagName: scriptNode.tagName,\n              md5: md5\n            }, parentOrigin);\n          } else {\n            console.error(e);\n          }\n        });\n      };\n\n      diagScript.innerText = \"(\".concat(diagScriptFun.toString(), \")('\").concat(nodeUnderTestId, \"', '\").concat(md5ForScript, \"', '\").concat(parentOrigin, \"');\");\n\n      diagFrame.onload = function () {\n        diagFrame.contentDocument.head.appendChild(diagScript);\n        diagFrame.contentDocument.head.appendChild(scriptUnderTest);\n      };\n\n      domready(function () {\n        return DOCUMENT.body.appendChild(diagFrame);\n      });\n    };\n\n    for (var scriptIdx = 0; scriptIdx < scripts.length; scriptIdx++) {\n      _loop(scriptIdx);\n    }\n\n    return scriptsByMD5;\n  }\n\n  function setDoneResults(_ref2) {\n    var nodesTested = _ref2.nodesTested,\n        nodesFound = _ref2.nodesFound;\n    WINDOW.FontAwesomeDetection = WINDOW.FontAwesomeDetection || {};\n    WINDOW.FontAwesomeDetection.nodesTested = nodesTested;\n    WINDOW.FontAwesomeDetection.nodesFound = nodesFound;\n    WINDOW.FontAwesomeDetection.detectionDone = true;\n  }\n\n  function conflictDetection() {\n    var report$$1 = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : function () {};\n    var nodesTested = {\n      conflict: {},\n      noConflict: {}\n    };\n\n    WINDOW.onmessage = function (e) {\n      if (WINDOW.location.origin === 'file://' || e.origin === WINDOW.location.origin) {\n        if (e && e.data) {\n          if (e.data.type === 'fontawesome-conflict') {\n            nodesTested.conflict[e.data.md5] = e.data;\n          } else if (e.data.type === 'no-conflict') {\n            nodesTested.noConflict[e.data.md5] = e.data;\n          }\n        }\n      }\n    };\n\n    var scriptsToTest = detectSvgConflicts(DOCUMENT.currentScript);\n    var cssToTest = detectWebfontConflicts();\n\n    var nodesFound = _objectSpread({}, scriptsToTest, cssToTest);\n\n    var testCount = Object.keys(scriptsToTest).length + Object.keys(cssToTest).length; // The resultsCollectionMaxWait allows for the time between when the tests running under\n    // child iframes call postMessage with their results, and when the parent window\n    // receives and handles those events with window.onmessage.\n    // Making it configurable allows us to test the scenario where this timeout is exceeded.\n    // Naming it something very different from \"timeout\" is to help avoid the potential ambiguity between\n    // these two timeout-related settings.\n\n    var masterTimeout = WINDOW.FontAwesomeDetection.timeout + WINDOW.FontAwesomeDetection.resultsCollectionMaxWait;\n    console.group('Font Awesome Detector');\n\n    if (testCount === 0) {\n      console.info('%cAll Good!', 'color: green; font-size: large');\n      console.info('We didn\\'t find anything that needs testing for conflicts. Ergo, no conflicts.');\n    } else {\n      console.info(\"Testing \".concat(testCount, \" possible conflicts.\"));\n      console.info(\"We'll wait about \".concat(Math.round(WINDOW.FontAwesomeDetection.timeout / 10) / 100, \" seconds while testing these and\\n\") + \"then up to another \".concat(Math.round(WINDOW.FontAwesomeDetection.resultsCollectionMaxWait / 10) / 100, \" to allow the browser time\\n\") + \"to accumulate the results. But we'll probably be outta here way before then.\\n\\n\");\n      console.info(\"You can adjust those durations by assigning values to these attributes on the <script> element that loads this detection:\");\n      console.info(\"\\t%c\".concat(timeoutAttr, \"%c: milliseconds to wait for each test before deciding whether it's a conflict.\"), 'font-weight: bold;', 'font-size: normal;');\n      console.info(\"\\t%c\".concat(resultsCollectionMaxWaitAttr, \"%c: milliseconds to wait for the browser to accumulate test results before giving up.\"), 'font-weight: bold;', 'font-size: normal;');\n      pollUntil({\n        // Give this overall timer a little extra cushion\n        maxDuration: masterTimeout,\n        showProgress: true,\n        progressIndicator: 'waiting...',\n        fn: function fn() {\n          return Object.keys(nodesTested.conflict).length + Object.keys(nodesTested.noConflict).length >= testCount;\n        }\n      }).then(function () {\n        console.info('DONE!');\n        setDoneResults({\n          nodesTested: nodesTested,\n          nodesFound: nodesFound\n        });\n        report$$1({\n          nodesTested: nodesTested,\n          nodesFound: nodesFound\n        });\n        console.groupEnd();\n      }).catch(function (e) {\n        if (e === 'timeout') {\n          console.info('TIME OUT! We waited until we got tired. Here\\'s what we found:');\n          setDoneResults({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n          report$$1({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n        } else {\n          console.info('Whoops! We hit an error:', e);\n          console.info('Here\\'s what we\\'d found up until that error:');\n          setDoneResults({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n          report$$1({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n        }\n\n        console.groupEnd();\n      });\n    }\n  } // Allow clients to access, and in some cases, override some properties\n\n  var initialConfig = WINDOW.FontAwesomeDetection || {}; // These can be overridden\n\n  var _default = {\n    report: report,\n    timeout: +(DOCUMENT.currentScript.getAttribute(timeoutAttr) || \"2000\"),\n    resultsCollectionMaxWait: +(DOCUMENT.currentScript.getAttribute(resultsCollectionMaxWaitAttr) || \"5000\")\n  };\n\n  var _config = _objectSpread({}, _default, initialConfig, {\n    // These cannot be overridden\n    __pollUntil: pollUntil,\n    md5ForNode: md5ForNode,\n    detectionDone: false,\n    nodesTested: null,\n    nodesFound: null\n  });\n\n  WINDOW.FontAwesomeDetection = _config;\n\n  var PRODUCTION = function () {\n    try {\n      return process.env.NODE_ENV === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  bunker(function () {\n    if (IS_BROWSER && IS_DOM) {\n      conflictDetection(window.FontAwesomeDetection.report);\n    }\n  });\n\n  exports.conflictDetection = conflictDetection;\n\n  Object.defineProperty(exports, '__esModule', { value: true });\n\n})));\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/fontawesome.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  function _typeof(obj) {\n    if (typeof Symbol === \"function\" && typeof Symbol.iterator === \"symbol\") {\n      _typeof = function (obj) {\n        return typeof obj;\n      };\n    } else {\n      _typeof = function (obj) {\n        return obj && typeof Symbol === \"function\" && obj.constructor === Symbol && obj !== Symbol.prototype ? \"symbol\" : typeof obj;\n      };\n    }\n\n    return _typeof(obj);\n  }\n\n  function _classCallCheck(instance, Constructor) {\n    if (!(instance instanceof Constructor)) {\n      throw new TypeError(\"Cannot call a class as a function\");\n    }\n  }\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _slicedToArray(arr, i) {\n    return _arrayWithHoles(arr) || _iterableToArrayLimit(arr, i) || _nonIterableRest();\n  }\n\n  function _toConsumableArray(arr) {\n    return _arrayWithoutHoles(arr) || _iterableToArray(arr) || _nonIterableSpread();\n  }\n\n  function _arrayWithoutHoles(arr) {\n    if (Array.isArray(arr)) {\n      for (var i = 0, arr2 = new Array(arr.length); i < arr.length; i++) arr2[i] = arr[i];\n\n      return arr2;\n    }\n  }\n\n  function _arrayWithHoles(arr) {\n    if (Array.isArray(arr)) return arr;\n  }\n\n  function _iterableToArray(iter) {\n    if (Symbol.iterator in Object(iter) || Object.prototype.toString.call(iter) === \"[object Arguments]\") return Array.from(iter);\n  }\n\n  function _iterableToArrayLimit(arr, i) {\n    var _arr = [];\n    var _n = true;\n    var _d = false;\n    var _e = undefined;\n\n    try {\n      for (var _i = arr[Symbol.iterator](), _s; !(_n = (_s = _i.next()).done); _n = true) {\n        _arr.push(_s.value);\n\n        if (i && _arr.length === i) break;\n      }\n    } catch (err) {\n      _d = true;\n      _e = err;\n    } finally {\n      try {\n        if (!_n && _i[\"return\"] != null) _i[\"return\"]();\n      } finally {\n        if (_d) throw _e;\n      }\n    }\n\n    return _arr;\n  }\n\n  function _nonIterableSpread() {\n    throw new TypeError(\"Invalid attempt to spread non-iterable instance\");\n  }\n\n  function _nonIterableRest() {\n    throw new TypeError(\"Invalid attempt to destructure non-iterable instance\");\n  }\n\n  var noop = function noop() {};\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n  var _MUTATION_OBSERVER = null;\n  var _PERFORMANCE = {\n    mark: noop,\n    measure: noop\n  };\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n    if (typeof MutationObserver !== 'undefined') _MUTATION_OBSERVER = MutationObserver;\n    if (typeof performance !== 'undefined') _PERFORMANCE = performance;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var MUTATION_OBSERVER = _MUTATION_OBSERVER;\n  var PERFORMANCE = _PERFORMANCE;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var UNITS_IN_GRID = 16;\n  var DEFAULT_FAMILY_PREFIX = 'fa';\n  var DEFAULT_REPLACEMENT_CLASS = 'svg-inline--fa';\n  var DATA_FA_I2SVG = 'data-fa-i2svg';\n  var DATA_FA_PSEUDO_ELEMENT = 'data-fa-pseudo-element';\n  var DATA_FA_PSEUDO_ELEMENT_PENDING = 'data-fa-pseudo-element-pending';\n  var DATA_PREFIX = 'data-prefix';\n  var DATA_ICON = 'data-icon';\n  var HTML_CLASS_I2SVG_BASE_CLASS = 'fontawesome-i2svg';\n  var MUTATION_APPROACH_ASYNC = 'async';\n  var TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS = ['HTML', 'HEAD', 'STYLE', 'SCRIPT'];\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n  var PREFIX_TO_STYLE = {\n    'fas': 'solid',\n    'far': 'regular',\n    'fal': 'light',\n    'fad': 'duotone',\n    'fab': 'brands',\n    'fa': 'solid'\n  };\n  var STYLE_TO_PREFIX = {\n    'solid': 'fas',\n    'regular': 'far',\n    'light': 'fal',\n    'duotone': 'fad',\n    'brands': 'fab'\n  };\n  var LAYERS_TEXT_CLASSNAME = 'fa-layers-text';\n  var FONT_FAMILY_PATTERN = /Font Awesome 5 (Solid|Regular|Light|Duotone|Brands|Free|Pro)/;\n  var FONT_WEIGHT_TO_PREFIX = {\n    '900': 'fas',\n    '400': 'far',\n    'normal': 'far',\n    '300': 'fal'\n  };\n  var oneToTen = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10];\n  var oneToTwenty = oneToTen.concat([11, 12, 13, 14, 15, 16, 17, 18, 19, 20]);\n  var ATTRIBUTES_WATCHED_FOR_MUTATION = ['class', 'data-prefix', 'data-icon', 'data-fa-transform', 'data-fa-mask'];\n  var DUOTONE_CLASSES = {\n    GROUP: 'group',\n    SWAP_OPACITY: 'swap-opacity',\n    PRIMARY: 'primary',\n    SECONDARY: 'secondary'\n  };\n  var RESERVED_CLASSES = ['xs', 'sm', 'lg', 'fw', 'ul', 'li', 'border', 'pull-left', 'pull-right', 'spin', 'pulse', 'rotate-90', 'rotate-180', 'rotate-270', 'flip-horizontal', 'flip-vertical', 'flip-both', 'stack', 'stack-1x', 'stack-2x', 'inverse', 'layers', 'layers-text', 'layers-counter', DUOTONE_CLASSES.GROUP, DUOTONE_CLASSES.SWAP_OPACITY, DUOTONE_CLASSES.PRIMARY, DUOTONE_CLASSES.SECONDARY].concat(oneToTen.map(function (n) {\n    return \"\".concat(n, \"x\");\n  })).concat(oneToTwenty.map(function (n) {\n    return \"w-\".concat(n);\n  }));\n\n  var initial = WINDOW.FontAwesomeConfig || {};\n\n  function getAttrConfig(attr) {\n    var element = DOCUMENT.querySelector('script[' + attr + ']');\n\n    if (element) {\n      return element.getAttribute(attr);\n    }\n  }\n\n  function coerce(val) {\n    // Getting an empty string will occur if the attribute is set on the HTML tag but without a value\n    // We'll assume that this is an indication that it should be toggled to true\n    // For example <script data-search-pseudo-elements src=\"...\"></script>\n    if (val === '') return true;\n    if (val === 'false') return false;\n    if (val === 'true') return true;\n    return val;\n  }\n\n  if (DOCUMENT && typeof DOCUMENT.querySelector === 'function') {\n    var attrs = [['data-family-prefix', 'familyPrefix'], ['data-replacement-class', 'replacementClass'], ['data-auto-replace-svg', 'autoReplaceSvg'], ['data-auto-add-css', 'autoAddCss'], ['data-auto-a11y', 'autoA11y'], ['data-search-pseudo-elements', 'searchPseudoElements'], ['data-observe-mutations', 'observeMutations'], ['data-mutate-approach', 'mutateApproach'], ['data-keep-original-source', 'keepOriginalSource'], ['data-measure-performance', 'measurePerformance'], ['data-show-missing-icons', 'showMissingIcons']];\n    attrs.forEach(function (_ref) {\n      var _ref2 = _slicedToArray(_ref, 2),\n          attr = _ref2[0],\n          key = _ref2[1];\n\n      var val = coerce(getAttrConfig(attr));\n\n      if (val !== undefined && val !== null) {\n        initial[key] = val;\n      }\n    });\n  }\n\n  var _default = {\n    familyPrefix: DEFAULT_FAMILY_PREFIX,\n    replacementClass: DEFAULT_REPLACEMENT_CLASS,\n    autoReplaceSvg: true,\n    autoAddCss: true,\n    autoA11y: true,\n    searchPseudoElements: false,\n    observeMutations: true,\n    mutateApproach: 'async',\n    keepOriginalSource: true,\n    measurePerformance: false,\n    showMissingIcons: true\n  };\n\n  var _config = _objectSpread({}, _default, initial);\n\n  if (!_config.autoReplaceSvg) _config.observeMutations = false;\n\n  var config = _objectSpread({}, _config);\n\n  WINDOW.FontAwesomeConfig = config;\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  var functions = [];\n\n  var listener = function listener() {\n    DOCUMENT.removeEventListener('DOMContentLoaded', listener);\n    loaded = 1;\n    functions.map(function (fn) {\n      return fn();\n    });\n  };\n\n  var loaded = false;\n\n  if (IS_DOM) {\n    loaded = (DOCUMENT.documentElement.doScroll ? /^loaded|^c/ : /^loaded|^i|^c/).test(DOCUMENT.readyState);\n    if (!loaded) DOCUMENT.addEventListener('DOMContentLoaded', listener);\n  }\n\n  function domready (fn) {\n    if (!IS_DOM) return;\n    loaded ? setTimeout(fn, 0) : functions.push(fn);\n  }\n\n  var PENDING = 'pending';\n  var SETTLED = 'settled';\n  var FULFILLED = 'fulfilled';\n  var REJECTED = 'rejected';\n\n  var NOOP = function NOOP() {};\n\n  var isNode = typeof global !== 'undefined' && typeof global.process !== 'undefined' && typeof global.process.emit === 'function';\n  var asyncSetTimer = typeof setImmediate === 'undefined' ? setTimeout : setImmediate;\n  var asyncQueue = [];\n  var asyncTimer;\n\n  function asyncFlush() {\n    // run promise callbacks\n    for (var i = 0; i < asyncQueue.length; i++) {\n      asyncQueue[i][0](asyncQueue[i][1]);\n    } // reset async asyncQueue\n\n\n    asyncQueue = [];\n    asyncTimer = false;\n  }\n\n  function asyncCall(callback, arg) {\n    asyncQueue.push([callback, arg]);\n\n    if (!asyncTimer) {\n      asyncTimer = true;\n      asyncSetTimer(asyncFlush, 0);\n    }\n  }\n\n  function invokeResolver(resolver, promise) {\n    function resolvePromise(value) {\n      resolve(promise, value);\n    }\n\n    function rejectPromise(reason) {\n      reject(promise, reason);\n    }\n\n    try {\n      resolver(resolvePromise, rejectPromise);\n    } catch (e) {\n      rejectPromise(e);\n    }\n  }\n\n  function invokeCallback(subscriber) {\n    var owner = subscriber.owner;\n    var settled = owner._state;\n    var value = owner._data;\n    var callback = subscriber[settled];\n    var promise = subscriber.then;\n\n    if (typeof callback === 'function') {\n      settled = FULFILLED;\n\n      try {\n        value = callback(value);\n      } catch (e) {\n        reject(promise, e);\n      }\n    }\n\n    if (!handleThenable(promise, value)) {\n      if (settled === FULFILLED) {\n        resolve(promise, value);\n      }\n\n      if (settled === REJECTED) {\n        reject(promise, value);\n      }\n    }\n  }\n\n  function handleThenable(promise, value) {\n    var resolved;\n\n    try {\n      if (promise === value) {\n        throw new TypeError('A promises callback cannot return that same promise.');\n      }\n\n      if (value && (typeof value === 'function' || _typeof(value) === 'object')) {\n        // then should be retrieved only once\n        var then = value.then;\n\n        if (typeof then === 'function') {\n          then.call(value, function (val) {\n            if (!resolved) {\n              resolved = true;\n\n              if (value === val) {\n                fulfill(promise, val);\n              } else {\n                resolve(promise, val);\n              }\n            }\n          }, function (reason) {\n            if (!resolved) {\n              resolved = true;\n              reject(promise, reason);\n            }\n          });\n          return true;\n        }\n      }\n    } catch (e) {\n      if (!resolved) {\n        reject(promise, e);\n      }\n\n      return true;\n    }\n\n    return false;\n  }\n\n  function resolve(promise, value) {\n    if (promise === value || !handleThenable(promise, value)) {\n      fulfill(promise, value);\n    }\n  }\n\n  function fulfill(promise, value) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = value;\n      asyncCall(publishFulfillment, promise);\n    }\n  }\n\n  function reject(promise, reason) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = reason;\n      asyncCall(publishRejection, promise);\n    }\n  }\n\n  function publish(promise) {\n    promise._then = promise._then.forEach(invokeCallback);\n  }\n\n  function publishFulfillment(promise) {\n    promise._state = FULFILLED;\n    publish(promise);\n  }\n\n  function publishRejection(promise) {\n    promise._state = REJECTED;\n    publish(promise);\n\n    if (!promise._handled && isNode) {\n      global.process.emit('unhandledRejection', promise._data, promise);\n    }\n  }\n\n  function notifyRejectionHandled(promise) {\n    global.process.emit('rejectionHandled', promise);\n  }\n  /**\n   * @class\n   */\n\n\n  function P(resolver) {\n    if (typeof resolver !== 'function') {\n      throw new TypeError('Promise resolver ' + resolver + ' is not a function');\n    }\n\n    if (this instanceof P === false) {\n      throw new TypeError('Failed to construct \\'Promise\\': Please use the \\'new\\' operator, this object constructor cannot be called as a function.');\n    }\n\n    this._then = [];\n    invokeResolver(resolver, this);\n  }\n\n  P.prototype = {\n    constructor: P,\n    _state: PENDING,\n    _then: null,\n    _data: undefined,\n    _handled: false,\n    then: function then(onFulfillment, onRejection) {\n      var subscriber = {\n        owner: this,\n        then: new this.constructor(NOOP),\n        fulfilled: onFulfillment,\n        rejected: onRejection\n      };\n\n      if ((onRejection || onFulfillment) && !this._handled) {\n        this._handled = true;\n\n        if (this._state === REJECTED && isNode) {\n          asyncCall(notifyRejectionHandled, this);\n        }\n      }\n\n      if (this._state === FULFILLED || this._state === REJECTED) {\n        // already resolved, call callback async\n        asyncCall(invokeCallback, subscriber);\n      } else {\n        // subscribe\n        this._then.push(subscriber);\n      }\n\n      return subscriber.then;\n    },\n    catch: function _catch(onRejection) {\n      return this.then(null, onRejection);\n    }\n  };\n\n  P.all = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.all().');\n    }\n\n    return new P(function (resolve, reject) {\n      var results = [];\n      var remaining = 0;\n\n      function resolver(index) {\n        remaining++;\n        return function (value) {\n          results[index] = value;\n\n          if (! --remaining) {\n            resolve(results);\n          }\n        };\n      }\n\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolver(i), reject);\n        } else {\n          results[i] = promise;\n        }\n      }\n\n      if (!remaining) {\n        resolve(results);\n      }\n    });\n  };\n\n  P.race = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.race().');\n    }\n\n    return new P(function (resolve, reject) {\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolve, reject);\n        } else {\n          resolve(promise);\n        }\n      }\n    });\n  };\n\n  P.resolve = function (value) {\n    if (value && _typeof(value) === 'object' && value.constructor === P) {\n      return value;\n    }\n\n    return new P(function (resolve) {\n      resolve(value);\n    });\n  };\n\n  P.reject = function (reason) {\n    return new P(function (resolve, reject) {\n      reject(reason);\n    });\n  };\n\n  var picked = typeof Promise === 'function' ? Promise : P;\n\n  var d = UNITS_IN_GRID;\n  var meaninglessTransform = {\n    size: 16,\n    x: 0,\n    y: 0,\n    rotate: 0,\n    flipX: false,\n    flipY: false\n  };\n\n  function isReserved(name) {\n    return ~RESERVED_CLASSES.indexOf(name);\n  }\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n  function insertCss(css) {\n    if (!css || !IS_DOM) {\n      return;\n    }\n\n    var style = DOCUMENT.createElement('style');\n    style.setAttribute('type', 'text/css');\n    style.innerHTML = css;\n    var headChildren = DOCUMENT.head.childNodes;\n    var beforeChild = null;\n\n    for (var i = headChildren.length - 1; i > -1; i--) {\n      var child = headChildren[i];\n      var tagName = (child.tagName || '').toUpperCase();\n\n      if (['STYLE', 'LINK'].indexOf(tagName) > -1) {\n        beforeChild = child;\n      }\n    }\n\n    DOCUMENT.head.insertBefore(style, beforeChild);\n    return css;\n  }\n  var idPool = '0123456789abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ';\n  function nextUniqueId() {\n    var size = 12;\n    var id = '';\n\n    while (size-- > 0) {\n      id += idPool[Math.random() * 62 | 0];\n    }\n\n    return id;\n  }\n  function toArray(obj) {\n    var array = [];\n\n    for (var i = (obj || []).length >>> 0; i--;) {\n      array[i] = obj[i];\n    }\n\n    return array;\n  }\n  function classArray(node) {\n    if (node.classList) {\n      return toArray(node.classList);\n    } else {\n      return (node.getAttribute('class') || '').split(' ').filter(function (i) {\n        return i;\n      });\n    }\n  }\n  function getIconName(familyPrefix, cls) {\n    var parts = cls.split('-');\n    var prefix = parts[0];\n    var iconName = parts.slice(1).join('-');\n\n    if (prefix === familyPrefix && iconName !== '' && !isReserved(iconName)) {\n      return iconName;\n    } else {\n      return null;\n    }\n  }\n  function htmlEscape(str) {\n    return \"\".concat(str).replace(/&/g, '&amp;').replace(/\"/g, '&quot;').replace(/'/g, '&#39;').replace(/</g, '&lt;').replace(/>/g, '&gt;');\n  }\n  function joinAttributes(attributes) {\n    return Object.keys(attributes || {}).reduce(function (acc, attributeName) {\n      return acc + \"\".concat(attributeName, \"=\\\"\").concat(htmlEscape(attributes[attributeName]), \"\\\" \");\n    }, '').trim();\n  }\n  function joinStyles(styles) {\n    return Object.keys(styles || {}).reduce(function (acc, styleName) {\n      return acc + \"\".concat(styleName, \": \").concat(styles[styleName], \";\");\n    }, '');\n  }\n  function transformIsMeaningful(transform) {\n    return transform.size !== meaninglessTransform.size || transform.x !== meaninglessTransform.x || transform.y !== meaninglessTransform.y || transform.rotate !== meaninglessTransform.rotate || transform.flipX || transform.flipY;\n  }\n  function transformForSvg(_ref) {\n    var transform = _ref.transform,\n        containerWidth = _ref.containerWidth,\n        iconWidth = _ref.iconWidth;\n    var outer = {\n      transform: \"translate(\".concat(containerWidth / 2, \" 256)\")\n    };\n    var innerTranslate = \"translate(\".concat(transform.x * 32, \", \").concat(transform.y * 32, \") \");\n    var innerScale = \"scale(\".concat(transform.size / 16 * (transform.flipX ? -1 : 1), \", \").concat(transform.size / 16 * (transform.flipY ? -1 : 1), \") \");\n    var innerRotate = \"rotate(\".concat(transform.rotate, \" 0 0)\");\n    var inner = {\n      transform: \"\".concat(innerTranslate, \" \").concat(innerScale, \" \").concat(innerRotate)\n    };\n    var path = {\n      transform: \"translate(\".concat(iconWidth / 2 * -1, \" -256)\")\n    };\n    return {\n      outer: outer,\n      inner: inner,\n      path: path\n    };\n  }\n  function transformForCss(_ref2) {\n    var transform = _ref2.transform,\n        _ref2$width = _ref2.width,\n        width = _ref2$width === void 0 ? UNITS_IN_GRID : _ref2$width,\n        _ref2$height = _ref2.height,\n        height = _ref2$height === void 0 ? UNITS_IN_GRID : _ref2$height,\n        _ref2$startCentered = _ref2.startCentered,\n        startCentered = _ref2$startCentered === void 0 ? false : _ref2$startCentered;\n    var val = '';\n\n    if (startCentered && IS_IE) {\n      val += \"translate(\".concat(transform.x / d - width / 2, \"em, \").concat(transform.y / d - height / 2, \"em) \");\n    } else if (startCentered) {\n      val += \"translate(calc(-50% + \".concat(transform.x / d, \"em), calc(-50% + \").concat(transform.y / d, \"em)) \");\n    } else {\n      val += \"translate(\".concat(transform.x / d, \"em, \").concat(transform.y / d, \"em) \");\n    }\n\n    val += \"scale(\".concat(transform.size / d * (transform.flipX ? -1 : 1), \", \").concat(transform.size / d * (transform.flipY ? -1 : 1), \") \");\n    val += \"rotate(\".concat(transform.rotate, \"deg) \");\n    return val;\n  }\n\n  var ALL_SPACE = {\n    x: 0,\n    y: 0,\n    width: '100%',\n    height: '100%'\n  };\n\n  function fillBlack(abstract) {\n    var force = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : true;\n\n    if (abstract.attributes && (abstract.attributes.fill || force)) {\n      abstract.attributes.fill = 'black';\n    }\n\n    return abstract;\n  }\n\n  function deGroup(abstract) {\n    if (abstract.tag === 'g') {\n      return abstract.children;\n    } else {\n      return [abstract];\n    }\n  }\n\n  function makeIconMasking (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        mask = _ref.mask,\n        transform = _ref.transform;\n    var mainWidth = main.width,\n        mainPath = main.icon;\n    var maskWidth = mask.width,\n        maskPath = mask.icon;\n    var trans = transformForSvg({\n      transform: transform,\n      containerWidth: maskWidth,\n      iconWidth: mainWidth\n    });\n    var maskRect = {\n      tag: 'rect',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        fill: 'white'\n      })\n    };\n    var maskInnerGroupChildrenMixin = mainPath.children ? {\n      children: mainPath.children.map(fillBlack)\n    } : {};\n    var maskInnerGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.inner),\n      children: [fillBlack(_objectSpread({\n        tag: mainPath.tag,\n        attributes: _objectSpread({}, mainPath.attributes, trans.path)\n      }, maskInnerGroupChildrenMixin))]\n    };\n    var maskOuterGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.outer),\n      children: [maskInnerGroup]\n    };\n    var maskId = \"mask-\".concat(nextUniqueId());\n    var clipId = \"clip-\".concat(nextUniqueId());\n    var maskTag = {\n      tag: 'mask',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        id: maskId,\n        maskUnits: 'userSpaceOnUse',\n        maskContentUnits: 'userSpaceOnUse'\n      }),\n      children: [maskRect, maskOuterGroup]\n    };\n    var defs = {\n      tag: 'defs',\n      children: [{\n        tag: 'clipPath',\n        attributes: {\n          id: clipId\n        },\n        children: deGroup(maskPath)\n      }, maskTag]\n    };\n    children.push(defs, {\n      tag: 'rect',\n      attributes: _objectSpread({\n        fill: 'currentColor',\n        'clip-path': \"url(#\".concat(clipId, \")\"),\n        mask: \"url(#\".concat(maskId, \")\")\n      }, ALL_SPACE)\n    });\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function makeIconStandard (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        transform = _ref.transform,\n        styles = _ref.styles;\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    if (transformIsMeaningful(transform)) {\n      var trans = transformForSvg({\n        transform: transform,\n        containerWidth: main.width,\n        iconWidth: main.width\n      });\n      children.push({\n        tag: 'g',\n        attributes: _objectSpread({}, trans.outer),\n        children: [{\n          tag: 'g',\n          attributes: _objectSpread({}, trans.inner),\n          children: [{\n            tag: main.icon.tag,\n            children: main.icon.children,\n            attributes: _objectSpread({}, main.icon.attributes, trans.path)\n          }]\n        }]\n      });\n    } else {\n      children.push(main.icon);\n    }\n\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function asIcon (_ref) {\n    var children = _ref.children,\n        main = _ref.main,\n        mask = _ref.mask,\n        attributes = _ref.attributes,\n        styles = _ref.styles,\n        transform = _ref.transform;\n\n    if (transformIsMeaningful(transform) && main.found && !mask.found) {\n      var width = main.width,\n          height = main.height;\n      var offset = {\n        x: width / height / 2,\n        y: 0.5\n      };\n      attributes['style'] = joinStyles(_objectSpread({}, styles, {\n        'transform-origin': \"\".concat(offset.x + transform.x / 16, \"em \").concat(offset.y + transform.y / 16, \"em\")\n      }));\n    }\n\n    return [{\n      tag: 'svg',\n      attributes: attributes,\n      children: children\n    }];\n  }\n\n  function asSymbol (_ref) {\n    var prefix = _ref.prefix,\n        iconName = _ref.iconName,\n        children = _ref.children,\n        attributes = _ref.attributes,\n        symbol = _ref.symbol;\n    var id = symbol === true ? \"\".concat(prefix, \"-\").concat(config.familyPrefix, \"-\").concat(iconName) : symbol;\n    return [{\n      tag: 'svg',\n      attributes: {\n        style: 'display: none;'\n      },\n      children: [{\n        tag: 'symbol',\n        attributes: _objectSpread({}, attributes, {\n          id: id\n        }),\n        children: children\n      }]\n    }];\n  }\n\n  function makeInlineSvgAbstract(params) {\n    var _params$icons = params.icons,\n        main = _params$icons.main,\n        mask = _params$icons.mask,\n        prefix = params.prefix,\n        iconName = params.iconName,\n        transform = params.transform,\n        symbol = params.symbol,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable = params.watchable,\n        watchable = _params$watchable === void 0 ? false : _params$watchable;\n\n    var _ref = mask.found ? mask : main,\n        width = _ref.width,\n        height = _ref.height;\n\n    var widthClass = \"fa-w-\".concat(Math.ceil(width / height * 16));\n    var attrClass = [config.replacementClass, iconName ? \"\".concat(config.familyPrefix, \"-\").concat(iconName) : '', widthClass].filter(function (c) {\n      return extra.classes.indexOf(c) === -1;\n    }).concat(extra.classes).join(' ');\n    var content = {\n      children: [],\n      attributes: _objectSpread({}, extra.attributes, {\n        'data-prefix': prefix,\n        'data-icon': iconName,\n        'class': attrClass,\n        'role': extra.attributes.role || 'img',\n        'xmlns': 'http://www.w3.org/2000/svg',\n        'viewBox': \"0 0 \".concat(width, \" \").concat(height)\n      })\n    };\n\n    if (watchable) {\n      content.attributes[DATA_FA_I2SVG] = '';\n    }\n\n    if (title) content.children.push({\n      tag: 'title',\n      attributes: {\n        id: content.attributes['aria-labelledby'] || \"title-\".concat(nextUniqueId())\n      },\n      children: [title]\n    });\n\n    var args = _objectSpread({}, content, {\n      prefix: prefix,\n      iconName: iconName,\n      main: main,\n      mask: mask,\n      transform: transform,\n      symbol: symbol,\n      styles: extra.styles\n    });\n\n    var _ref2 = mask.found && main.found ? makeIconMasking(args) : makeIconStandard(args),\n        children = _ref2.children,\n        attributes = _ref2.attributes;\n\n    args.children = children;\n    args.attributes = attributes;\n\n    if (symbol) {\n      return asSymbol(args);\n    } else {\n      return asIcon(args);\n    }\n  }\n  function makeLayersTextAbstract(params) {\n    var content = params.content,\n        width = params.width,\n        height = params.height,\n        transform = params.transform,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable2 = params.watchable,\n        watchable = _params$watchable2 === void 0 ? false : _params$watchable2;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    if (watchable) {\n      attributes[DATA_FA_I2SVG] = '';\n    }\n\n    var styles = _objectSpread({}, extra.styles);\n\n    if (transformIsMeaningful(transform)) {\n      styles['transform'] = transformForCss({\n        transform: transform,\n        startCentered: true,\n        width: width,\n        height: height\n      });\n      styles['-webkit-transform'] = styles['transform'];\n    }\n\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n  function makeLayersCounterAbstract(params) {\n    var content = params.content,\n        title = params.title,\n        extra = params.extra;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    var styleString = joinStyles(extra.styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n\n  var noop$1 = function noop() {};\n\n  var p = config.measurePerformance && PERFORMANCE && PERFORMANCE.mark && PERFORMANCE.measure ? PERFORMANCE : {\n    mark: noop$1,\n    measure: noop$1\n  };\n  var preamble = \"FA \\\"5.10.2\\\"\";\n\n  var begin = function begin(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" begins\"));\n    return function () {\n      return end(name);\n    };\n  };\n\n  var end = function end(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" ends\"));\n    p.measure(\"\".concat(preamble, \" \").concat(name), \"\".concat(preamble, \" \").concat(name, \" begins\"), \"\".concat(preamble, \" \").concat(name, \" ends\"));\n  };\n\n  var perf = {\n    begin: begin,\n    end: end\n  };\n\n  /**\n   * Internal helper to bind a function known to have 4 arguments\n   * to a given context.\n   */\n\n  var bindInternal4 = function bindInternal4(func, thisContext) {\n    return function (a, b, c, d) {\n      return func.call(thisContext, a, b, c, d);\n    };\n  };\n\n  /**\n   * # Reduce\n   *\n   * A fast object `.reduce()` implementation.\n   *\n   * @param  {Object}   subject      The object to reduce over.\n   * @param  {Function} fn           The reducer function.\n   * @param  {mixed}    initialValue The initial value for the reducer, defaults to subject[0].\n   * @param  {Object}   thisContext  The context for the reducer.\n   * @return {mixed}                 The final result.\n   */\n\n\n  var reduce = function fastReduceObject(subject, fn, initialValue, thisContext) {\n    var keys = Object.keys(subject),\n        length = keys.length,\n        iterator = thisContext !== undefined ? bindInternal4(fn, thisContext) : fn,\n        i,\n        key,\n        result;\n\n    if (initialValue === undefined) {\n      i = 1;\n      result = subject[keys[0]];\n    } else {\n      i = 0;\n      result = initialValue;\n    }\n\n    for (; i < length; i++) {\n      key = keys[i];\n      result = iterator(result, subject[key], key, subject);\n    }\n\n    return result;\n  };\n\n  function toHex(unicode) {\n    var result = '';\n\n    for (var i = 0; i < unicode.length; i++) {\n      var hex = unicode.charCodeAt(i).toString(16);\n      result += ('000' + hex).slice(-4);\n    }\n\n    return result;\n  }\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var styles = namespace.styles,\n      shims = namespace.shims;\n  var _byUnicode = {};\n  var _byLigature = {};\n  var _byOldName = {};\n  var build = function build() {\n    var lookup = function lookup(reducer) {\n      return reduce(styles, function (o, style, prefix) {\n        o[prefix] = reduce(style, reducer, {});\n        return o;\n      }, {});\n    };\n\n    _byUnicode = lookup(function (acc, icon, iconName) {\n      if (icon[3]) {\n        acc[icon[3]] = iconName;\n      }\n\n      return acc;\n    });\n    _byLigature = lookup(function (acc, icon, iconName) {\n      var ligatures = icon[2];\n      acc[iconName] = iconName;\n      ligatures.forEach(function (ligature) {\n        acc[ligature] = iconName;\n      });\n      return acc;\n    });\n    var hasRegular = 'far' in styles;\n    _byOldName = reduce(shims, function (acc, shim) {\n      var oldName = shim[0];\n      var prefix = shim[1];\n      var iconName = shim[2];\n\n      if (prefix === 'far' && !hasRegular) {\n        prefix = 'fas';\n      }\n\n      acc[oldName] = {\n        prefix: prefix,\n        iconName: iconName\n      };\n      return acc;\n    }, {});\n  };\n  build();\n  function byUnicode(prefix, unicode) {\n    return (_byUnicode[prefix] || {})[unicode];\n  }\n  function byLigature(prefix, ligature) {\n    return (_byLigature[prefix] || {})[ligature];\n  }\n  function byOldName(name) {\n    return _byOldName[name] || {\n      prefix: null,\n      iconName: null\n    };\n  }\n\n  var styles$1 = namespace.styles;\n  var emptyCanonicalIcon = function emptyCanonicalIcon() {\n    return {\n      prefix: null,\n      iconName: null,\n      rest: []\n    };\n  };\n  function getCanonicalIcon(values) {\n    return values.reduce(function (acc, cls) {\n      var iconName = getIconName(config.familyPrefix, cls);\n\n      if (styles$1[cls]) {\n        acc.prefix = cls;\n      } else if (config.autoFetchSvg && ['fas', 'far', 'fal', 'fad', 'fab', 'fa'].indexOf(cls) > -1) {\n        acc.prefix = cls;\n      } else if (iconName) {\n        var shim = acc.prefix === 'fa' ? byOldName(iconName) : {};\n        acc.iconName = shim.iconName || iconName;\n        acc.prefix = shim.prefix || acc.prefix;\n      } else if (cls !== config.replacementClass && cls.indexOf('fa-w-') !== 0) {\n        acc.rest.push(cls);\n      }\n\n      return acc;\n    }, emptyCanonicalIcon());\n  }\n  function iconFromMapping(mapping, prefix, iconName) {\n    if (mapping && mapping[prefix] && mapping[prefix][iconName]) {\n      return {\n        prefix: prefix,\n        iconName: iconName,\n        icon: mapping[prefix][iconName]\n      };\n    }\n  }\n\n  function toHtml(abstractNodes) {\n    var tag = abstractNodes.tag,\n        _abstractNodes$attrib = abstractNodes.attributes,\n        attributes = _abstractNodes$attrib === void 0 ? {} : _abstractNodes$attrib,\n        _abstractNodes$childr = abstractNodes.children,\n        children = _abstractNodes$childr === void 0 ? [] : _abstractNodes$childr;\n\n    if (typeof abstractNodes === 'string') {\n      return htmlEscape(abstractNodes);\n    } else {\n      return \"<\".concat(tag, \" \").concat(joinAttributes(attributes), \">\").concat(children.map(toHtml).join(''), \"</\").concat(tag, \">\");\n    }\n  }\n\n  var noop$2 = function noop() {};\n\n  function isWatched(node) {\n    var i2svg = node.getAttribute ? node.getAttribute(DATA_FA_I2SVG) : null;\n    return typeof i2svg === 'string';\n  }\n\n  function getMutator() {\n    if (config.autoReplaceSvg === true) {\n      return mutators.replace;\n    }\n\n    var mutator = mutators[config.autoReplaceSvg];\n    return mutator || mutators.replace;\n  }\n\n  var mutators = {\n    replace: function replace(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1];\n      var newOuterHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n\n      if (node.parentNode && node.outerHTML) {\n        node.outerHTML = newOuterHTML + (config.keepOriginalSource && node.tagName.toLowerCase() !== 'svg' ? \"<!-- \".concat(node.outerHTML, \" -->\") : '');\n      } else if (node.parentNode) {\n        var newNode = document.createElement('span');\n        node.parentNode.replaceChild(newNode, node);\n        newNode.outerHTML = newOuterHTML;\n      }\n    },\n    nest: function nest(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1]; // If we already have a replaced node we do not want to continue nesting within it.\n      // Short-circuit to the standard replacement\n\n      if (~classArray(node).indexOf(config.replacementClass)) {\n        return mutators.replace(mutation);\n      }\n\n      var forSvg = new RegExp(\"\".concat(config.familyPrefix, \"-.*\"));\n      delete abstract[0].attributes.style;\n      var splitClasses = abstract[0].attributes.class.split(' ').reduce(function (acc, cls) {\n        if (cls === config.replacementClass || cls.match(forSvg)) {\n          acc.toSvg.push(cls);\n        } else {\n          acc.toNode.push(cls);\n        }\n\n        return acc;\n      }, {\n        toNode: [],\n        toSvg: []\n      });\n      abstract[0].attributes.class = splitClasses.toSvg.join(' ');\n      var newInnerHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n      node.setAttribute('class', splitClasses.toNode.join(' '));\n      node.setAttribute(DATA_FA_I2SVG, '');\n      node.innerHTML = newInnerHTML;\n    }\n  };\n\n  function performOperationSync(op) {\n    op();\n  }\n\n  function perform(mutations, callback) {\n    var callbackFunction = typeof callback === 'function' ? callback : noop$2;\n\n    if (mutations.length === 0) {\n      callbackFunction();\n    } else {\n      var frame = performOperationSync;\n\n      if (config.mutateApproach === MUTATION_APPROACH_ASYNC) {\n        frame = WINDOW.requestAnimationFrame || performOperationSync;\n      }\n\n      frame(function () {\n        var mutator = getMutator();\n        var mark = perf.begin('mutate');\n        mutations.map(mutator);\n        mark();\n        callbackFunction();\n      });\n    }\n  }\n  var disabled = false;\n  function disableObservation() {\n    disabled = true;\n  }\n  function enableObservation() {\n    disabled = false;\n  }\n  var mo = null;\n  function observe(options) {\n    if (!MUTATION_OBSERVER) {\n      return;\n    }\n\n    if (!config.observeMutations) {\n      return;\n    }\n\n    var treeCallback = options.treeCallback,\n        nodeCallback = options.nodeCallback,\n        pseudoElementsCallback = options.pseudoElementsCallback,\n        _options$observeMutat = options.observeMutationsRoot,\n        observeMutationsRoot = _options$observeMutat === void 0 ? DOCUMENT : _options$observeMutat;\n    mo = new MUTATION_OBSERVER(function (objects) {\n      if (disabled) return;\n      toArray(objects).forEach(function (mutationRecord) {\n        if (mutationRecord.type === 'childList' && mutationRecord.addedNodes.length > 0 && !isWatched(mutationRecord.addedNodes[0])) {\n          if (config.searchPseudoElements) {\n            pseudoElementsCallback(mutationRecord.target);\n          }\n\n          treeCallback(mutationRecord.target);\n        }\n\n        if (mutationRecord.type === 'attributes' && mutationRecord.target.parentNode && config.searchPseudoElements) {\n          pseudoElementsCallback(mutationRecord.target.parentNode);\n        }\n\n        if (mutationRecord.type === 'attributes' && isWatched(mutationRecord.target) && ~ATTRIBUTES_WATCHED_FOR_MUTATION.indexOf(mutationRecord.attributeName)) {\n          if (mutationRecord.attributeName === 'class') {\n            var _getCanonicalIcon = getCanonicalIcon(classArray(mutationRecord.target)),\n                prefix = _getCanonicalIcon.prefix,\n                iconName = _getCanonicalIcon.iconName;\n\n            if (prefix) mutationRecord.target.setAttribute('data-prefix', prefix);\n            if (iconName) mutationRecord.target.setAttribute('data-icon', iconName);\n          } else {\n            nodeCallback(mutationRecord.target);\n          }\n        }\n      });\n    });\n    if (!IS_DOM) return;\n    mo.observe(observeMutationsRoot, {\n      childList: true,\n      attributes: true,\n      characterData: true,\n      subtree: true\n    });\n  }\n  function disconnect() {\n    if (!mo) return;\n    mo.disconnect();\n  }\n\n  function styleParser (node) {\n    var style = node.getAttribute('style');\n    var val = [];\n\n    if (style) {\n      val = style.split(';').reduce(function (acc, style) {\n        var styles = style.split(':');\n        var prop = styles[0];\n        var value = styles.slice(1);\n\n        if (prop && value.length > 0) {\n          acc[prop] = value.join(':').trim();\n        }\n\n        return acc;\n      }, {});\n    }\n\n    return val;\n  }\n\n  function classParser (node) {\n    var existingPrefix = node.getAttribute('data-prefix');\n    var existingIconName = node.getAttribute('data-icon');\n    var innerText = node.innerText !== undefined ? node.innerText.trim() : '';\n    var val = getCanonicalIcon(classArray(node));\n\n    if (existingPrefix && existingIconName) {\n      val.prefix = existingPrefix;\n      val.iconName = existingIconName;\n    }\n\n    if (val.prefix && innerText.length > 1) {\n      val.iconName = byLigature(val.prefix, node.innerText);\n    } else if (val.prefix && innerText.length === 1) {\n      val.iconName = byUnicode(val.prefix, toHex(node.innerText));\n    }\n\n    return val;\n  }\n\n  var parseTransformString = function parseTransformString(transformString) {\n    var transform = {\n      size: 16,\n      x: 0,\n      y: 0,\n      flipX: false,\n      flipY: false,\n      rotate: 0\n    };\n\n    if (!transformString) {\n      return transform;\n    } else {\n      return transformString.toLowerCase().split(' ').reduce(function (acc, n) {\n        var parts = n.toLowerCase().split('-');\n        var first = parts[0];\n        var rest = parts.slice(1).join('-');\n\n        if (first && rest === 'h') {\n          acc.flipX = true;\n          return acc;\n        }\n\n        if (first && rest === 'v') {\n          acc.flipY = true;\n          return acc;\n        }\n\n        rest = parseFloat(rest);\n\n        if (isNaN(rest)) {\n          return acc;\n        }\n\n        switch (first) {\n          case 'grow':\n            acc.size = acc.size + rest;\n            break;\n\n          case 'shrink':\n            acc.size = acc.size - rest;\n            break;\n\n          case 'left':\n            acc.x = acc.x - rest;\n            break;\n\n          case 'right':\n            acc.x = acc.x + rest;\n            break;\n\n          case 'up':\n            acc.y = acc.y - rest;\n            break;\n\n          case 'down':\n            acc.y = acc.y + rest;\n            break;\n\n          case 'rotate':\n            acc.rotate = acc.rotate + rest;\n            break;\n        }\n\n        return acc;\n      }, transform);\n    }\n  };\n  function transformParser (node) {\n    return parseTransformString(node.getAttribute('data-fa-transform'));\n  }\n\n  function symbolParser (node) {\n    var symbol = node.getAttribute('data-fa-symbol');\n    return symbol === null ? false : symbol === '' ? true : symbol;\n  }\n\n  function attributesParser (node) {\n    var extraAttributes = toArray(node.attributes).reduce(function (acc, attr) {\n      if (acc.name !== 'class' && acc.name !== 'style') {\n        acc[attr.name] = attr.value;\n      }\n\n      return acc;\n    }, {});\n    var title = node.getAttribute('title');\n\n    if (config.autoA11y) {\n      if (title) {\n        extraAttributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n      } else {\n        extraAttributes['aria-hidden'] = 'true';\n        extraAttributes['focusable'] = 'false';\n      }\n    }\n\n    return extraAttributes;\n  }\n\n  function maskParser (node) {\n    var mask = node.getAttribute('data-fa-mask');\n\n    if (!mask) {\n      return emptyCanonicalIcon();\n    } else {\n      return getCanonicalIcon(mask.split(' ').map(function (i) {\n        return i.trim();\n      }));\n    }\n  }\n\n  function blankMeta() {\n    return {\n      iconName: null,\n      title: null,\n      prefix: null,\n      transform: meaninglessTransform,\n      symbol: false,\n      mask: null,\n      extra: {\n        classes: [],\n        styles: {},\n        attributes: {}\n      }\n    };\n  }\n  function parseMeta(node) {\n    var _classParser = classParser(node),\n        iconName = _classParser.iconName,\n        prefix = _classParser.prefix,\n        extraClasses = _classParser.rest;\n\n    var extraStyles = styleParser(node);\n    var transform = transformParser(node);\n    var symbol = symbolParser(node);\n    var extraAttributes = attributesParser(node);\n    var mask = maskParser(node);\n    return {\n      iconName: iconName,\n      title: node.getAttribute('title'),\n      prefix: prefix,\n      transform: transform,\n      symbol: symbol,\n      mask: mask,\n      extra: {\n        classes: extraClasses,\n        styles: extraStyles,\n        attributes: extraAttributes\n      }\n    };\n  }\n\n  function MissingIcon(error) {\n    this.name = 'MissingIcon';\n    this.message = error || 'Icon unavailable';\n    this.stack = new Error().stack;\n  }\n  MissingIcon.prototype = Object.create(Error.prototype);\n  MissingIcon.prototype.constructor = MissingIcon;\n\n  var FILL = {\n    fill: 'currentColor'\n  };\n  var ANIMATION_BASE = {\n    attributeType: 'XML',\n    repeatCount: 'indefinite',\n    dur: '2s'\n  };\n  var RING = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      d: 'M156.5,447.7l-12.6,29.5c-18.7-9.5-35.9-21.2-51.5-34.9l22.7-22.7C127.6,430.5,141.5,440,156.5,447.7z M40.6,272H8.5 c1.4,21.2,5.4,41.7,11.7,61.1L50,321.2C45.1,305.5,41.8,289,40.6,272z M40.6,240c1.4-18.8,5.2-37,11.1-54.1l-29.5-12.6 C14.7,194.3,10,216.7,8.5,240H40.6z M64.3,156.5c7.8-14.9,17.2-28.8,28.1-41.5L69.7,92.3c-13.7,15.6-25.5,32.8-34.9,51.5 L64.3,156.5z M397,419.6c-13.9,12-29.4,22.3-46.1,30.4l11.9,29.8c20.7-9.9,39.8-22.6,56.9-37.6L397,419.6z M115,92.4 c13.9-12,29.4-22.3,46.1-30.4l-11.9-29.8c-20.7,9.9-39.8,22.6-56.8,37.6L115,92.4z M447.7,355.5c-7.8,14.9-17.2,28.8-28.1,41.5 l22.7,22.7c13.7-15.6,25.5-32.9,34.9-51.5L447.7,355.5z M471.4,272c-1.4,18.8-5.2,37-11.1,54.1l29.5,12.6 c7.5-21.1,12.2-43.5,13.6-66.8H471.4z M321.2,462c-15.7,5-32.2,8.2-49.2,9.4v32.1c21.2-1.4,41.7-5.4,61.1-11.7L321.2,462z M240,471.4c-18.8-1.4-37-5.2-54.1-11.1l-12.6,29.5c21.1,7.5,43.5,12.2,66.8,13.6V471.4z M462,190.8c5,15.7,8.2,32.2,9.4,49.2h32.1 c-1.4-21.2-5.4-41.7-11.7-61.1L462,190.8z M92.4,397c-12-13.9-22.3-29.4-30.4-46.1l-29.8,11.9c9.9,20.7,22.6,39.8,37.6,56.9 L92.4,397z M272,40.6c18.8,1.4,36.9,5.2,54.1,11.1l12.6-29.5C317.7,14.7,295.3,10,272,8.5V40.6z M190.8,50 c15.7-5,32.2-8.2,49.2-9.4V8.5c-21.2,1.4-41.7,5.4-61.1,11.7L190.8,50z M442.3,92.3L419.6,115c12,13.9,22.3,29.4,30.5,46.1 l29.8-11.9C470,128.5,457.3,109.4,442.3,92.3z M397,92.4l22.7-22.7c-15.6-13.7-32.8-25.5-51.5-34.9l-12.6,29.5 C370.4,72.1,384.4,81.5,397,92.4z'\n    })\n  };\n\n  var OPACITY_ANIMATE = _objectSpread({}, ANIMATION_BASE, {\n    attributeName: 'opacity'\n  });\n\n  var DOT = {\n    tag: 'circle',\n    attributes: _objectSpread({}, FILL, {\n      cx: '256',\n      cy: '364',\n      r: '28'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, ANIMATION_BASE, {\n        attributeName: 'r',\n        values: '28;14;28;28;14;28;'\n      })\n    }, {\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;1;1;0;1;'\n      })\n    }]\n  };\n  var QUESTION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '1',\n      d: 'M263.7,312h-16c-6.6,0-12-5.4-12-12c0-71,77.4-63.9,77.4-107.8c0-20-17.8-40.2-57.4-40.2c-29.1,0-44.3,9.6-59.2,28.7 c-3.9,5-11.1,6-16.2,2.4l-13.1-9.2c-5.6-3.9-6.9-11.8-2.6-17.2c21.2-27.2,46.4-44.7,91.2-44.7c52.3,0,97.4,29.8,97.4,80.2 c0,67.6-77.4,63.5-77.4,107.8C275.7,306.6,270.3,312,263.7,312z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;0;0;0;1;'\n      })\n    }]\n  };\n  var EXCLAMATION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '0',\n      d: 'M232.5,134.5l7,168c0.3,6.4,5.6,11.5,12,11.5h9c6.4,0,11.7-5.1,12-11.5l7-168c0.3-6.8-5.2-12.5-12-12.5h-23 C237.7,122,232.2,127.7,232.5,134.5z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '0;0;1;1;0;0;'\n      })\n    }]\n  };\n  var missing = {\n    tag: 'g',\n    children: [RING, DOT, QUESTION, EXCLAMATION]\n  };\n\n  var styles$2 = namespace.styles;\n  function asFoundIcon(icon) {\n    var width = icon[0];\n    var height = icon[1];\n\n    var _icon$slice = icon.slice(4),\n        _icon$slice2 = _slicedToArray(_icon$slice, 1),\n        vectorData = _icon$slice2[0];\n\n    var element = null;\n\n    if (Array.isArray(vectorData)) {\n      element = {\n        tag: 'g',\n        attributes: {\n          class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.GROUP)\n        },\n        children: [{\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.SECONDARY),\n            fill: 'currentColor',\n            d: vectorData[0]\n          }\n        }, {\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.PRIMARY),\n            fill: 'currentColor',\n            d: vectorData[1]\n          }\n        }]\n      };\n    } else {\n      element = {\n        tag: 'path',\n        attributes: {\n          fill: 'currentColor',\n          d: vectorData\n        }\n      };\n    }\n\n    return {\n      found: true,\n      width: width,\n      height: height,\n      icon: element\n    };\n  }\n  function findIcon(iconName, prefix) {\n    return new picked(function (resolve, reject) {\n      var val = {\n        found: false,\n        width: 512,\n        height: 512,\n        icon: missing\n      };\n\n      if (iconName && prefix && styles$2[prefix] && styles$2[prefix][iconName]) {\n        var icon = styles$2[prefix][iconName];\n        return resolve(asFoundIcon(icon));\n      }\n\n      if (iconName && prefix && !config.showMissingIcons) {\n        reject(new MissingIcon(\"Icon is missing for prefix \".concat(prefix, \" with icon name \").concat(iconName)));\n      } else {\n        resolve(val);\n      }\n    });\n  }\n\n  var styles$3 = namespace.styles;\n\n  function generateSvgReplacementMutation(node, nodeMeta) {\n    var iconName = nodeMeta.iconName,\n        title = nodeMeta.title,\n        prefix = nodeMeta.prefix,\n        transform = nodeMeta.transform,\n        symbol = nodeMeta.symbol,\n        mask = nodeMeta.mask,\n        extra = nodeMeta.extra;\n    return new picked(function (resolve, reject) {\n      picked.all([findIcon(iconName, prefix), findIcon(mask.iconName, mask.prefix)]).then(function (_ref) {\n        var _ref2 = _slicedToArray(_ref, 2),\n            main = _ref2[0],\n            mask = _ref2[1];\n\n        resolve([node, makeInlineSvgAbstract({\n          icons: {\n            main: main,\n            mask: mask\n          },\n          prefix: prefix,\n          iconName: iconName,\n          transform: transform,\n          symbol: symbol,\n          mask: mask,\n          title: title,\n          extra: extra,\n          watchable: true\n        })]);\n      });\n    });\n  }\n\n  function generateLayersText(node, nodeMeta) {\n    var title = nodeMeta.title,\n        transform = nodeMeta.transform,\n        extra = nodeMeta.extra;\n    var width = null;\n    var height = null;\n\n    if (IS_IE) {\n      var computedFontSize = parseInt(getComputedStyle(node).fontSize, 10);\n      var boundingClientRect = node.getBoundingClientRect();\n      width = boundingClientRect.width / computedFontSize;\n      height = boundingClientRect.height / computedFontSize;\n    }\n\n    if (config.autoA11y && !title) {\n      extra.attributes['aria-hidden'] = 'true';\n    }\n\n    return picked.resolve([node, makeLayersTextAbstract({\n      content: node.innerHTML,\n      width: width,\n      height: height,\n      transform: transform,\n      title: title,\n      extra: extra,\n      watchable: true\n    })]);\n  }\n\n  function generateMutation(node) {\n    var nodeMeta = parseMeta(node);\n\n    if (~nodeMeta.extra.classes.indexOf(LAYERS_TEXT_CLASSNAME)) {\n      return generateLayersText(node, nodeMeta);\n    } else {\n      return generateSvgReplacementMutation(node, nodeMeta);\n    }\n  }\n\n  function onTree(root) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    if (!IS_DOM) return;\n    var htmlClassList = DOCUMENT.documentElement.classList;\n\n    var hclAdd = function hclAdd(suffix) {\n      return htmlClassList.add(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var hclRemove = function hclRemove(suffix) {\n      return htmlClassList.remove(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var prefixes = config.autoFetchSvg ? Object.keys(PREFIX_TO_STYLE) : Object.keys(styles$3);\n    var prefixesDomQuery = [\".\".concat(LAYERS_TEXT_CLASSNAME, \":not([\").concat(DATA_FA_I2SVG, \"])\")].concat(prefixes.map(function (p) {\n      return \".\".concat(p, \":not([\").concat(DATA_FA_I2SVG, \"])\");\n    })).join(', ');\n\n    if (prefixesDomQuery.length === 0) {\n      return;\n    }\n\n    var candidates = [];\n\n    try {\n      candidates = toArray(root.querySelectorAll(prefixesDomQuery));\n    } catch (e) {// noop\n    }\n\n    if (candidates.length > 0) {\n      hclAdd('pending');\n      hclRemove('complete');\n    } else {\n      return;\n    }\n\n    var mark = perf.begin('onTree');\n    var mutations = candidates.reduce(function (acc, node) {\n      try {\n        var mutation = generateMutation(node);\n\n        if (mutation) {\n          acc.push(mutation);\n        }\n      } catch (e) {\n        if (!PRODUCTION) {\n          if (e instanceof MissingIcon) {\n            console.error(e);\n          }\n        }\n      }\n\n      return acc;\n    }, []);\n    return new picked(function (resolve, reject) {\n      picked.all(mutations).then(function (resolvedMutations) {\n        perform(resolvedMutations, function () {\n          hclAdd('active');\n          hclAdd('complete');\n          hclRemove('pending');\n          if (typeof callback === 'function') callback();\n          mark();\n          resolve();\n        });\n      }).catch(function () {\n        mark();\n        reject();\n      });\n    });\n  }\n  function onNode(node) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    generateMutation(node).then(function (mutation) {\n      if (mutation) {\n        perform([mutation], callback);\n      }\n    });\n  }\n\n  function replaceForPosition(node, position) {\n    var pendingAttribute = \"\".concat(DATA_FA_PSEUDO_ELEMENT_PENDING).concat(position.replace(':', '-'));\n    return new picked(function (resolve, reject) {\n      if (node.getAttribute(pendingAttribute) !== null) {\n        // This node is already being processed\n        return resolve();\n      }\n\n      var children = toArray(node.children);\n      var alreadyProcessedPseudoElement = children.filter(function (c) {\n        return c.getAttribute(DATA_FA_PSEUDO_ELEMENT) === position;\n      })[0];\n      var styles = WINDOW.getComputedStyle(node, position);\n      var fontFamily = styles.getPropertyValue('font-family').match(FONT_FAMILY_PATTERN);\n      var fontWeight = styles.getPropertyValue('font-weight');\n\n      if (alreadyProcessedPseudoElement && !fontFamily) {\n        // If we've already processed it but the current computed style does not result in a font-family,\n        // that probably means that a class name that was previously present to make the icon has been\n        // removed. So we now should delete the icon.\n        node.removeChild(alreadyProcessedPseudoElement);\n        return resolve();\n      } else if (fontFamily) {\n        var content = styles.getPropertyValue('content');\n        var prefix = ~['Solid', 'Regular', 'Light', 'Duotone', 'Brands'].indexOf(fontFamily[1]) ? STYLE_TO_PREFIX[fontFamily[1].toLowerCase()] : FONT_WEIGHT_TO_PREFIX[fontWeight];\n        var hexValue = toHex(content.length === 3 ? content.substr(1, 1) : content);\n        var iconName = byUnicode(prefix, hexValue);\n        var iconIdentifier = iconName; // Only convert the pseudo element in this :before/:after position into an icon if we haven't\n        // already done so with the same prefix and iconName\n\n        if (iconName && (!alreadyProcessedPseudoElement || alreadyProcessedPseudoElement.getAttribute(DATA_PREFIX) !== prefix || alreadyProcessedPseudoElement.getAttribute(DATA_ICON) !== iconIdentifier)) {\n          node.setAttribute(pendingAttribute, iconIdentifier);\n\n          if (alreadyProcessedPseudoElement) {\n            // Delete the old one, since we're replacing it with a new one\n            node.removeChild(alreadyProcessedPseudoElement);\n          }\n\n          var meta = blankMeta();\n          var extra = meta.extra;\n          extra.attributes[DATA_FA_PSEUDO_ELEMENT] = position;\n          findIcon(iconName, prefix).then(function (main) {\n            var abstract = makeInlineSvgAbstract(_objectSpread({}, meta, {\n              icons: {\n                main: main,\n                mask: emptyCanonicalIcon()\n              },\n              prefix: prefix,\n              iconName: iconIdentifier,\n              extra: extra,\n              watchable: true\n            }));\n            var element = DOCUMENT.createElement('svg');\n\n            if (position === ':before') {\n              node.insertBefore(element, node.firstChild);\n            } else {\n              node.appendChild(element);\n            }\n\n            element.outerHTML = abstract.map(function (a) {\n              return toHtml(a);\n            }).join('\\n');\n            node.removeAttribute(pendingAttribute);\n            resolve();\n          }).catch(reject);\n        } else {\n          resolve();\n        }\n      } else {\n        resolve();\n      }\n    });\n  }\n\n  function replace(node) {\n    return picked.all([replaceForPosition(node, ':before'), replaceForPosition(node, ':after')]);\n  }\n\n  function processable(node) {\n    return node.parentNode !== document.head && !~TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS.indexOf(node.tagName.toUpperCase()) && !node.getAttribute(DATA_FA_PSEUDO_ELEMENT) && (!node.parentNode || node.parentNode.tagName !== 'svg');\n  }\n\n  function searchPseudoElements (root) {\n    if (!IS_DOM) return;\n    return new picked(function (resolve, reject) {\n      var operations = toArray(root.querySelectorAll('*')).filter(processable).map(replace);\n      var end = perf.begin('searchPseudoElements');\n      disableObservation();\n      picked.all(operations).then(function () {\n        end();\n        enableObservation();\n        resolve();\n      }).catch(function () {\n        end();\n        enableObservation();\n        reject();\n      });\n    });\n  }\n\n  var baseStyles = \"svg:not(:root).svg-inline--fa{overflow:visible}.svg-inline--fa{display:inline-block;font-size:inherit;height:1em;overflow:visible;vertical-align:-.125em}.svg-inline--fa.fa-lg{vertical-align:-.225em}.svg-inline--fa.fa-w-1{width:.0625em}.svg-inline--fa.fa-w-2{width:.125em}.svg-inline--fa.fa-w-3{width:.1875em}.svg-inline--fa.fa-w-4{width:.25em}.svg-inline--fa.fa-w-5{width:.3125em}.svg-inline--fa.fa-w-6{width:.375em}.svg-inline--fa.fa-w-7{width:.4375em}.svg-inline--fa.fa-w-8{width:.5em}.svg-inline--fa.fa-w-9{width:.5625em}.svg-inline--fa.fa-w-10{width:.625em}.svg-inline--fa.fa-w-11{width:.6875em}.svg-inline--fa.fa-w-12{width:.75em}.svg-inline--fa.fa-w-13{width:.8125em}.svg-inline--fa.fa-w-14{width:.875em}.svg-inline--fa.fa-w-15{width:.9375em}.svg-inline--fa.fa-w-16{width:1em}.svg-inline--fa.fa-w-17{width:1.0625em}.svg-inline--fa.fa-w-18{width:1.125em}.svg-inline--fa.fa-w-19{width:1.1875em}.svg-inline--fa.fa-w-20{width:1.25em}.svg-inline--fa.fa-pull-left{margin-right:.3em;width:auto}.svg-inline--fa.fa-pull-right{margin-left:.3em;width:auto}.svg-inline--fa.fa-border{height:1.5em}.svg-inline--fa.fa-li{width:2em}.svg-inline--fa.fa-fw{width:1.25em}.fa-layers svg.svg-inline--fa{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.fa-layers{display:inline-block;height:1em;position:relative;text-align:center;vertical-align:-.125em;width:1em}.fa-layers svg.svg-inline--fa{-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter,.fa-layers-text{display:inline-block;position:absolute;text-align:center}.fa-layers-text{left:50%;top:50%;-webkit-transform:translate(-50%,-50%);transform:translate(-50%,-50%);-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter{background-color:#ff253a;border-radius:1em;-webkit-box-sizing:border-box;box-sizing:border-box;color:#fff;height:1.5em;line-height:1;max-width:5em;min-width:1.5em;overflow:hidden;padding:.25em;right:0;text-overflow:ellipsis;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-bottom-right{bottom:0;right:0;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom right;transform-origin:bottom right}.fa-layers-bottom-left{bottom:0;left:0;right:auto;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom left;transform-origin:bottom left}.fa-layers-top-right{right:0;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-top-left{left:0;right:auto;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top left;transform-origin:top left}.fa-lg{font-size:1.3333333333em;line-height:.75em;vertical-align:-.0667em}.fa-xs{font-size:.75em}.fa-sm{font-size:.875em}.fa-1x{font-size:1em}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-6x{font-size:6em}.fa-7x{font-size:7em}.fa-8x{font-size:8em}.fa-9x{font-size:9em}.fa-10x{font-size:10em}.fa-fw{text-align:center;width:1.25em}.fa-ul{list-style-type:none;margin-left:2.5em;padding-left:0}.fa-ul>li{position:relative}.fa-li{left:-2em;position:absolute;text-align:center;width:2em;line-height:inherit}.fa-border{border:solid .08em #eee;border-radius:.1em;padding:.2em .25em .15em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left,.fab.fa-pull-left,.fal.fa-pull-left,.far.fa-pull-left,.fas.fa-pull-left{margin-right:.3em}.fa.fa-pull-right,.fab.fa-pull-right,.fal.fa-pull-right,.far.fa-pull-right,.fas.fa-pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s infinite linear;animation:fa-spin 2s infinite linear}.fa-pulse{-webkit-animation:fa-spin 1s infinite steps(8);animation:fa-spin 1s infinite steps(8)}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}.fa-rotate-90{-webkit-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{-webkit-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{-webkit-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{-webkit-transform:scale(-1,1);transform:scale(-1,1)}.fa-flip-vertical{-webkit-transform:scale(1,-1);transform:scale(1,-1)}.fa-flip-both,.fa-flip-horizontal.fa-flip-vertical{-webkit-transform:scale(-1,-1);transform:scale(-1,-1)}:root .fa-flip-both,:root .fa-flip-horizontal,:root .fa-flip-vertical,:root .fa-rotate-180,:root .fa-rotate-270,:root .fa-rotate-90{-webkit-filter:none;filter:none}.fa-stack{display:inline-block;height:2em;position:relative;width:2.5em}.fa-stack-1x,.fa-stack-2x{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.svg-inline--fa.fa-stack-1x{height:1em;width:1.25em}.svg-inline--fa.fa-stack-2x{height:2em;width:2.5em}.fa-inverse{color:#fff}.sr-only{border:0;clip:rect(0,0,0,0);height:1px;margin:-1px;overflow:hidden;padding:0;position:absolute;width:1px}.sr-only-focusable:active,.sr-only-focusable:focus{clip:auto;height:auto;margin:0;overflow:visible;position:static;width:auto}.svg-inline--fa .fa-primary{fill:var(--fa-primary-color,currentColor);opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa .fa-secondary{fill:var(--fa-secondary-color,currentColor);opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-primary{opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-secondary{opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa mask .fa-primary,.svg-inline--fa mask .fa-secondary{fill:#000}.fad.fa-inverse{color:#fff}\";\n\n  function css () {\n    var dfp = DEFAULT_FAMILY_PREFIX;\n    var drc = DEFAULT_REPLACEMENT_CLASS;\n    var fp = config.familyPrefix;\n    var rc = config.replacementClass;\n    var s = baseStyles;\n\n    if (fp !== dfp || rc !== drc) {\n      var dPatt = new RegExp(\"\\\\.\".concat(dfp, \"\\\\-\"), 'g');\n      var customPropPatt = new RegExp(\"\\\\--\".concat(dfp, \"\\\\-\"), 'g');\n      var rPatt = new RegExp(\"\\\\.\".concat(drc), 'g');\n      s = s.replace(dPatt, \".\".concat(fp, \"-\")).replace(customPropPatt, \"--\".concat(fp, \"-\")).replace(rPatt, \".\".concat(rc));\n    }\n\n    return s;\n  }\n\n  var Library =\n  /*#__PURE__*/\n  function () {\n    function Library() {\n      _classCallCheck(this, Library);\n\n      this.definitions = {};\n    }\n\n    _createClass(Library, [{\n      key: \"add\",\n      value: function add() {\n        var _this = this;\n\n        for (var _len = arguments.length, definitions = new Array(_len), _key = 0; _key < _len; _key++) {\n          definitions[_key] = arguments[_key];\n        }\n\n        var additions = definitions.reduce(this._pullDefinitions, {});\n        Object.keys(additions).forEach(function (key) {\n          _this.definitions[key] = _objectSpread({}, _this.definitions[key] || {}, additions[key]);\n          defineIcons(key, additions[key]);\n          build();\n        });\n      }\n    }, {\n      key: \"reset\",\n      value: function reset() {\n        this.definitions = {};\n      }\n    }, {\n      key: \"_pullDefinitions\",\n      value: function _pullDefinitions(additions, definition) {\n        var normalized = definition.prefix && definition.iconName && definition.icon ? {\n          0: definition\n        } : definition;\n        Object.keys(normalized).map(function (key) {\n          var _normalized$key = normalized[key],\n              prefix = _normalized$key.prefix,\n              iconName = _normalized$key.iconName,\n              icon = _normalized$key.icon;\n          if (!additions[prefix]) additions[prefix] = {};\n          additions[prefix][iconName] = icon;\n        });\n        return additions;\n      }\n    }]);\n\n    return Library;\n  }();\n\n  function ensureCss() {\n    if (config.autoAddCss && !_cssInserted) {\n      insertCss(css());\n\n      _cssInserted = true;\n    }\n  }\n\n  function apiObject(val, abstractCreator) {\n    Object.defineProperty(val, 'abstract', {\n      get: abstractCreator\n    });\n    Object.defineProperty(val, 'html', {\n      get: function get() {\n        return val.abstract.map(function (a) {\n          return toHtml(a);\n        });\n      }\n    });\n    Object.defineProperty(val, 'node', {\n      get: function get() {\n        if (!IS_DOM) return;\n        var container = DOCUMENT.createElement('div');\n        container.innerHTML = val.html;\n        return container.children;\n      }\n    });\n    return val;\n  }\n\n  function findIconDefinition(iconLookup) {\n    var _iconLookup$prefix = iconLookup.prefix,\n        prefix = _iconLookup$prefix === void 0 ? 'fa' : _iconLookup$prefix,\n        iconName = iconLookup.iconName;\n    if (!iconName) return;\n    return iconFromMapping(library.definitions, prefix, iconName) || iconFromMapping(namespace.styles, prefix, iconName);\n  }\n\n  function resolveIcons(next) {\n    return function (maybeIconDefinition) {\n      var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n      var iconDefinition = (maybeIconDefinition || {}).icon ? maybeIconDefinition : findIconDefinition(maybeIconDefinition || {});\n      var mask = params.mask;\n\n      if (mask) {\n        mask = (mask || {}).icon ? mask : findIconDefinition(mask || {});\n      }\n\n      return next(iconDefinition, _objectSpread({}, params, {\n        mask: mask\n      }));\n    };\n  }\n\n  var library = new Library();\n  var noAuto = function noAuto() {\n    config.autoReplaceSvg = false;\n    config.observeMutations = false;\n    disconnect();\n  };\n  var _cssInserted = false;\n  var dom = {\n    i2svg: function i2svg() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n\n      if (IS_DOM) {\n        ensureCss();\n        var _params$node = params.node,\n            node = _params$node === void 0 ? DOCUMENT : _params$node,\n            _params$callback = params.callback,\n            callback = _params$callback === void 0 ? function () {} : _params$callback;\n\n        if (config.searchPseudoElements) {\n          searchPseudoElements(node);\n        }\n\n        return onTree(node, callback);\n      } else {\n        return picked.reject('Operation requires a DOM of some kind.');\n      }\n    },\n    css: css,\n    insertCss: function insertCss$$1() {\n      if (!_cssInserted) {\n        insertCss(css());\n\n        _cssInserted = true;\n      }\n    },\n    watch: function watch() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n      var autoReplaceSvgRoot = params.autoReplaceSvgRoot,\n          observeMutationsRoot = params.observeMutationsRoot;\n\n      if (config.autoReplaceSvg === false) {\n        config.autoReplaceSvg = true;\n      }\n\n      config.observeMutations = true;\n      domready(function () {\n        autoReplace({\n          autoReplaceSvgRoot: autoReplaceSvgRoot\n        });\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements,\n          observeMutationsRoot: observeMutationsRoot\n        });\n      });\n    }\n  };\n  var parse = {\n    transform: function transform(transformString) {\n      return parseTransformString(transformString);\n    }\n  };\n  var icon = resolveIcons(function (iconDefinition) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform = params.transform,\n        transform = _params$transform === void 0 ? meaninglessTransform : _params$transform,\n        _params$symbol = params.symbol,\n        symbol = _params$symbol === void 0 ? false : _params$symbol,\n        _params$mask = params.mask,\n        mask = _params$mask === void 0 ? null : _params$mask,\n        _params$title = params.title,\n        title = _params$title === void 0 ? null : _params$title,\n        _params$classes = params.classes,\n        classes = _params$classes === void 0 ? [] : _params$classes,\n        _params$attributes = params.attributes,\n        attributes = _params$attributes === void 0 ? {} : _params$attributes,\n        _params$styles = params.styles,\n        styles = _params$styles === void 0 ? {} : _params$styles;\n    if (!iconDefinition) return;\n    var prefix = iconDefinition.prefix,\n        iconName = iconDefinition.iconName,\n        icon = iconDefinition.icon;\n    return apiObject(_objectSpread({\n      type: 'icon'\n    }, iconDefinition), function () {\n      ensureCss();\n\n      if (config.autoA11y) {\n        if (title) {\n          attributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n        } else {\n          attributes['aria-hidden'] = 'true';\n          attributes['focusable'] = 'false';\n        }\n      }\n\n      return makeInlineSvgAbstract({\n        icons: {\n          main: asFoundIcon(icon),\n          mask: mask ? asFoundIcon(mask.icon) : {\n            found: false,\n            width: null,\n            height: null,\n            icon: {}\n          }\n        },\n        prefix: prefix,\n        iconName: iconName,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        symbol: symbol,\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: classes\n        }\n      });\n    });\n  });\n  var text = function text(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform2 = params.transform,\n        transform = _params$transform2 === void 0 ? meaninglessTransform : _params$transform2,\n        _params$title2 = params.title,\n        title = _params$title2 === void 0 ? null : _params$title2,\n        _params$classes2 = params.classes,\n        classes = _params$classes2 === void 0 ? [] : _params$classes2,\n        _params$attributes2 = params.attributes,\n        attributes = _params$attributes2 === void 0 ? {} : _params$attributes2,\n        _params$styles2 = params.styles,\n        styles = _params$styles2 === void 0 ? {} : _params$styles2;\n    return apiObject({\n      type: 'text',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersTextAbstract({\n        content: content,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-text\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var counter = function counter(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$title3 = params.title,\n        title = _params$title3 === void 0 ? null : _params$title3,\n        _params$classes3 = params.classes,\n        classes = _params$classes3 === void 0 ? [] : _params$classes3,\n        _params$attributes3 = params.attributes,\n        attributes = _params$attributes3 === void 0 ? {} : _params$attributes3,\n        _params$styles3 = params.styles,\n        styles = _params$styles3 === void 0 ? {} : _params$styles3;\n    return apiObject({\n      type: 'counter',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersCounterAbstract({\n        content: content.toString(),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-counter\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var layer = function layer(assembler) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$classes4 = params.classes,\n        classes = _params$classes4 === void 0 ? [] : _params$classes4;\n    return apiObject({\n      type: 'layer'\n    }, function () {\n      ensureCss();\n      var children = [];\n      assembler(function (args) {\n        Array.isArray(args) ? args.map(function (a) {\n          children = children.concat(a.abstract);\n        }) : children = children.concat(args.abstract);\n      });\n      return [{\n        tag: 'span',\n        attributes: {\n          class: [\"\".concat(config.familyPrefix, \"-layers\")].concat(_toConsumableArray(classes)).join(' ')\n        },\n        children: children\n      }];\n    });\n  };\n  var api = {\n    noAuto: noAuto,\n    config: config,\n    dom: dom,\n    library: library,\n    parse: parse,\n    findIconDefinition: findIconDefinition,\n    icon: icon,\n    text: text,\n    counter: counter,\n    layer: layer,\n    toHtml: toHtml\n  };\n\n  var autoReplace = function autoReplace() {\n    var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n    var _params$autoReplaceSv = params.autoReplaceSvgRoot,\n        autoReplaceSvgRoot = _params$autoReplaceSv === void 0 ? DOCUMENT : _params$autoReplaceSv;\n    if ((Object.keys(namespace.styles).length > 0 || config.autoFetchSvg) && IS_DOM && config.autoReplaceSvg) api.dom.i2svg({\n      node: autoReplaceSvgRoot\n    });\n  };\n\n  function bootstrap() {\n    if (IS_BROWSER) {\n      if (!WINDOW.FontAwesome) {\n        WINDOW.FontAwesome = api;\n      }\n\n      domready(function () {\n        autoReplace();\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements\n        });\n      });\n    }\n\n    namespace.hooks = _objectSpread({}, namespace.hooks, {\n      addPack: function addPack(prefix, icons) {\n        namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, icons);\n        build();\n        autoReplace();\n      },\n      addShims: function addShims(shims) {\n        var _namespace$shims;\n\n        (_namespace$shims = namespace.shims).push.apply(_namespace$shims, _toConsumableArray(shims));\n\n        build();\n        autoReplace();\n      }\n    });\n  }\n\n  bunker(bootstrap);\n\n}());\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/regular.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-68 304H48V48h320v416zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H48V80h480v352zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2zM360 320h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-144c-33.6 0-65.2 14.8-86.8 40.6-8.5 10.2-7.1 25.3 3.1 33.8s25.3 7.2 33.8-3c24.8-29.7 75-29.7 99.8 0 8.1 9.7 23.2 11.9 33.8 3 10.2-8.5 11.5-23.6 3.1-33.8-21.6-25.8-53.2-40.6-86.8-40.6zm-48-72c10.3 0 19.9-6.7 23-17.1 3.8-12.7-3.4-26.1-16.1-29.9l-80-24c-12.8-3.9-26.1 3.4-29.9 16.1-3.8 12.7 3.4 26.1 16.1 29.9l28.2 8.5c-3.1 4.9-5.3 10.4-5.3 16.6 0 17.7 14.3 32 32 32s32-14.4 32-32.1zm199-54.9c-3.8-12.7-17.1-19.9-29.9-16.1l-80 24c-12.7 3.8-19.9 17.2-16.1 29.9 3.1 10.4 12.7 17.1 23 17.1 0 17.7 14.3 32 32 32s32-14.3 32-32c0-6.2-2.2-11.7-5.3-16.6l28.2-8.5c12.7-3.7 19.9-17.1 16.1-29.8z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm-32-316v116h-67c-10.7 0-16 12.9-8.5 20.5l99 99c4.7 4.7 12.3 4.7 17 0l99-99c7.6-7.6 2.2-20.5-8.5-20.5h-67V140c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M8 256c0 137 111 248 248 248s248-111 248-248S393 8 256 8 8 119 8 256zm448 0c0 110.5-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56s200 89.5 200 200zm-72-20v40c0 6.6-5.4 12-12 12H256v67c0 10.7-12.9 16-20.5 8.5l-99-99c-4.7-4.7-4.7-12.3 0-17l99-99c7.6-7.6 20.5-2.2 20.5 8.5v67h116c6.6 0 12 5.4 12 12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm72 20v-40c0-6.6 5.4-12 12-12h116v-67c0-10.7 12.9-16 20.5-8.5l99 99c4.7 4.7 4.7 12.3 0 17l-99 99c-7.6 7.6-20.5 2.2-20.5-8.5v-67H140c-6.6 0-12-5.4-12-12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M256 504c137 0 248-111 248-248S393 8 256 8 8 119 8 256s111 248 248 248zm0-448c110.5 0 200 89.5 200 200s-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56zm20 328h-40c-6.6 0-12-5.4-12-12V256h-67c-10.7 0-16-12.9-8.5-20.5l99-99c4.7-4.7 12.3-4.7 17 0l99 99c7.6 7.6 2.2 20.5-8.5 20.5h-67v116c0 6.6-5.4 12-12 12z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M439.39 362.29c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71zM67.53 368c21.22-27.97 44.42-74.33 44.53-159.42 0-.2-.06-.38-.06-.58 0-61.86 50.14-112 112-112s112 50.14 112 112c0 .2-.06.38-.06.58.11 85.1 23.31 131.46 44.53 159.42H67.53zM224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.99 471.02L36 3.51C29.1-2.01 19.03-.9 13.51 6l-10 12.49C-2.02 25.39-.9 35.46 6 40.98l598 467.51c6.9 5.52 16.96 4.4 22.49-2.49l10-12.49c5.52-6.9 4.41-16.97-2.5-22.49zM163.53 368c16.71-22.03 34.48-55.8 41.4-110.58l-45.47-35.55c-3.27 90.73-36.47 120.68-54.84 140.42-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h279.66l-61.4-48H163.53zM320 96c61.86 0 112 50.14 112 112 0 .2-.06.38-.06.58.02 16.84 1.16 31.77 2.79 45.73l59.53 46.54c-8.31-22.13-14.34-51.49-14.34-92.85 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-26.02 5.41-49.45 16.94-69.13 32.72l38.17 29.84C275 103.18 296.65 96 320 96zm0 416c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M336 0H48C21.49 0 0 21.49 0 48v464l192-112 192 112V48c0-26.51-21.49-48-48-48zm0 428.43l-144-84-144 84V54a6 6 0 0 1 6-6h276c3.314 0 6 2.683 6 5.996V428.43z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M128 148v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12zm140 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-128 96h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm128 0h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-76 84v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm76 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm180 124v36H0v-36c0-6.6 5.4-12 12-12h19.5V24c0-13.3 10.7-24 24-24h337c13.3 0 24 10.7 24 24v440H436c6.6 0 12 5.4 12 12zM79.5 463H192v-67c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v67h112.5V49L80 48l-.5 415z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M400 64h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V160h352v298c0 3.3-2.7 6-6 6z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M148 288h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm108-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 96v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96-260v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M400 64h-48V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H160V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V160h352v298a6 6 0 0 1-6 6zm-52.849-200.65L198.842 404.519c-4.705 4.667-12.303 4.637-16.971-.068l-75.091-75.699c-4.667-4.705-4.637-12.303.068-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l44.104 44.461 111.072-110.181c4.705-4.667 12.303-4.637 16.971.068l22.536 22.718c4.667 4.705 4.636 12.303-.069 16.97z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M124 328c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v24c0 6.6-5.4 12-12 12H124zm324-216v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M336 292v24c0 6.6-5.4 12-12 12h-76v76c0 6.6-5.4 12-12 12h-24c-6.6 0-12-5.4-12-12v-76h-76c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h76v-76c0-6.6 5.4-12 12-12h24c6.6 0 12 5.4 12 12v76h76c6.6 0 12 5.4 12 12zm112-180v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M311.7 374.7l-17 17c-4.7 4.7-12.3 4.7-17 0L224 337.9l-53.7 53.7c-4.7 4.7-12.3 4.7-17 0l-17-17c-4.7-4.7-4.7-12.3 0-17l53.7-53.7-53.7-53.7c-4.7-4.7-4.7-12.3 0-17l17-17c4.7-4.7 12.3-4.7 17 0l53.7 53.7 53.7-53.7c4.7-4.7 12.3-4.7 17 0l17 17c4.7 4.7 4.7 12.3 0 17L257.9 304l53.7 53.7c4.8 4.7 4.8 12.3.1 17zM448 112v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M125.1 208h197.8c10.7 0 16.1 13 8.5 20.5l-98.9 98.3c-4.7 4.7-12.2 4.7-16.9 0l-98.9-98.3c-7.7-7.5-2.3-20.5 8.4-20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M272 157.1v197.8c0 10.7-13 16.1-20.5 8.5l-98.3-98.9c-4.7-4.7-4.7-12.2 0-16.9l98.3-98.9c7.5-7.7 20.5-2.3 20.5 8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M176 354.9V157.1c0-10.7 13-16.1 20.5-8.5l98.3 98.9c4.7 4.7 4.7 12.2 0 16.9l-98.3 98.9c-7.5 7.7-20.5 2.3-20.5-8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M322.9 304H125.1c-10.7 0-16.1-13-8.5-20.5l98.9-98.3c4.7-4.7 12.2-4.7 16.9 0l98.9 98.3c7.7 7.5 2.3 20.5-8.4 20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M396.8 352h22.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-192 0h22.4c6.4 0 12.8-6.4 12.8-12.8V140.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h22.4c6.4 0 12.8-6.4 12.8-12.8V204.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zM496 400H48V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16zm-387.2-48h22.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 48c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m140.204 130.267l-22.536-22.718c-4.667-4.705-12.265-4.736-16.97-.068L215.346 303.697l-59.792-60.277c-4.667-4.705-12.265-4.736-16.97-.069l-22.719 22.536c-4.705 4.667-4.736 12.265-.068 16.971l90.781 91.516c4.667 4.705 12.265 4.736 16.97.068l172.589-171.204c4.704-4.668 4.734-12.266.067-16.971z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm0 400H48V80h352v352zm-35.864-241.724L191.547 361.48c-4.705 4.667-12.303 4.637-16.97-.068l-90.781-91.516c-4.667-4.705-4.637-12.303.069-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l59.792 60.277 141.352-140.216c4.705-4.667 12.303-4.637 16.97.068l22.536 22.718c4.667 4.706 4.637 12.304-.068 16.971z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm144 418c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h42v36c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-36h42c3.3 0 6 2.7 6 6z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm61.8-104.4l-84.9-61.7c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v141.7l66.8 48.6c5.4 3.9 6.5 11.4 2.6 16.8L334.6 349c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0H144c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h320c26.51 0 48-21.49 48-48v-48h48c26.51 0 48-21.49 48-48V48c0-26.51-21.49-48-48-48zM362 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h42v224c0 26.51 21.49 48 48 48h224v42a6 6 0 0 1-6 6zm96-96H150a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h308a6 6 0 0 1 6 6v308a6 6 0 0 1-6 6z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 336H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v276c0 3.3-2.7 6-6 6zm-211.1-85.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7zm190.4 0c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.9-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 220.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 7.1 5.8 12 12 12 2.4 0 4.9-.7 7.1-2.4L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zm16 352c0 8.8-7.2 16-16 16H288l-12.8 9.6L208 428v-60H64c-8.8 0-16-7.2-16-16V64c0-8.8 7.2-16 16-16h384c8.8 0 16 7.2 16 16v288z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M144 208c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zM256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M532 386.2c27.5-27.1 44-61.1 44-98.2 0-80-76.5-146.1-176.2-157.9C368.3 72.5 294.3 32 208 32 93.1 32 0 103.6 0 192c0 37 16.5 71 44 98.2-15.3 30.7-37.3 54.5-37.7 54.9-6.3 6.7-8.1 16.5-4.4 25 3.6 8.5 12 14 21.2 14 53.5 0 96.7-20.2 125.2-38.8 9.2 2.1 18.7 3.7 28.4 4.9C208.1 407.6 281.8 448 368 448c20.8 0 40.8-2.4 59.8-6.8C456.3 459.7 499.4 480 553 480c9.2 0 17.5-5.5 21.2-14 3.6-8.5 1.9-18.3-4.4-25-.4-.3-22.5-24.1-37.8-54.8zm-392.8-92.3L122.1 305c-14.1 9.1-28.5 16.3-43.1 21.4 2.7-4.7 5.4-9.7 8-14.8l15.5-31.1L77.7 256C64.2 242.6 48 220.7 48 192c0-60.7 73.3-112 160-112s160 51.3 160 112-73.3 112-160 112c-16.5 0-33-1.9-49-5.6l-19.8-4.5zM498.3 352l-24.7 24.4 15.5 31.1c2.6 5.1 5.3 10.1 8 14.8-14.6-5.1-29-12.3-43.1-21.4l-17.1-11.1-19.9 4.6c-16 3.7-32.5 5.6-49 5.6-54 0-102.2-20.1-131.3-49.7C338 339.5 416 272.9 416 192c0-3.4-.4-6.7-.7-10C479.7 196.5 528 238.8 528 288c0 28.7-16.2 50.6-29.7 64z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M347.94 129.86L203.6 195.83a31.938 31.938 0 0 0-15.77 15.77l-65.97 144.34c-7.61 16.65 9.54 33.81 26.2 26.2l144.34-65.97a31.938 31.938 0 0 0 15.77-15.77l65.97-144.34c7.61-16.66-9.54-33.81-26.2-26.2zm-77.36 148.72c-12.47 12.47-32.69 12.47-45.16 0-12.47-12.47-12.47-32.69 0-45.16 12.47-12.47 32.69-12.47 45.16 0 12.47 12.47 12.47 32.69 0 45.16zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M433.941 65.941l-51.882-51.882A48 48 0 0 0 348.118 0H176c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48v-48h80c26.51 0 48-21.49 48-48V99.882a48 48 0 0 0-14.059-33.941zM266 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h74v224c0 26.51 21.49 48 48 48h96v42a6 6 0 0 1-6 6zm128-96H182a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h106v88c0 13.255 10.745 24 24 24h88v202a6 6 0 0 1-6 6zm6-256h-64V48h9.632c1.591 0 3.117.632 4.243 1.757l48.368 48.368a6 6 0 0 1 1.757 4.243V112z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm107.351-101.064c-9.614 9.712-45.53 41.396-104.065 41.396-82.43 0-140.484-61.425-140.484-141.567 0-79.152 60.275-139.401 139.762-139.401 55.531 0 88.738 26.62 97.593 34.779a11.965 11.965 0 0 1 1.936 15.322l-18.155 28.113c-3.841 5.95-11.966 7.282-17.499 2.921-8.595-6.776-31.814-22.538-61.708-22.538-48.303 0-77.916 35.33-77.916 80.082 0 41.589 26.888 83.692 78.277 83.692 32.657 0 56.843-19.039 65.726-27.225 5.27-4.857 13.596-4.039 17.82 1.738l19.865 27.17a11.947 11.947 0 0 1-1.152 15.518z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M527.9 32H48.1C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48.1 48h479.8c26.6 0 48.1-21.5 48.1-48V80c0-26.5-21.5-48-48.1-48zM54.1 80h467.8c3.3 0 6 2.7 6 6v42H48.1V86c0-3.3 2.7-6 6-6zm467.8 352H54.1c-3.3 0-6-2.7-6-6V256h479.8v170c0 3.3-2.7 6-6 6zM192 332v40c0 6.6-5.4 12-12 12h-72c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12zm192 0v40c0 6.6-5.4 12-12 12H236c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-33.8-217.9c7.8-7.8 7.8-20.5 0-28.3L196.3 192l17.9-17.9c7.8-7.8 7.8-20.5 0-28.3-7.8-7.8-20.5-7.8-28.3 0L168 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.9 7.7 20.5 7.7 28.4-.2zm160-92.2c-7.8-7.8-20.5-7.8-28.3 0L328 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.8 7.8 20.5 7.8 28.3 0 7.8-7.8 7.8-20.5 0-28.3l-17.8-18 17.9-17.9c7.7-7.8 7.7-20.4 0-28.2zM248 272c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 56c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m0-48C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 168c-44.183 0-80 35.817-80 80s35.817 80 80 80 80-35.817 80-80-35.817-80-80-80z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.3 344.9l32-32c5-5 13.7-1.5 13.7 5.7V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h273.5c7.1 0 10.7 8.6 5.7 13.7l-32 32c-1.5 1.5-3.5 2.3-5.7 2.3H48v352h352V350.5c0-2.1.8-4.1 2.3-5.6zm156.6-201.8L296.3 405.7l-90.4 10c-26.2 2.9-48.5-19.2-45.6-45.6l10-90.4L432.9 17.1c22.9-22.9 59.9-22.9 82.7 0l43.2 43.2c22.9 22.9 22.9 60 .1 82.8zM460.1 174L402 115.9 216.2 301.8l-7.3 65.3 65.3-7.3L460.1 174zm64.8-79.7l-43.2-43.2c-4.1-4.1-10.8-4.1-14.8 0L436 82l58.1 58.1 30.9-30.9c4-4.2 4-10.8-.1-14.9z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm0 48v40.805c-22.422 18.259-58.168 46.651-134.587 106.49-16.841 13.247-50.201 45.072-73.413 44.701-23.208.375-56.579-31.459-73.413-44.701C106.18 199.465 70.425 171.067 48 152.805V112h416zM48 400V214.398c22.914 18.251 55.409 43.862 104.938 82.646 21.857 17.205 60.134 55.186 103.062 54.955 42.717.231 80.509-37.199 103.053-54.947 49.528-38.783 82.032-64.401 104.947-82.653V400H48z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M494.586 164.516c-4.697-3.883-111.723-89.95-135.251-108.657C337.231 38.191 299.437 0 256 0c-43.205 0-80.636 37.717-103.335 55.859-24.463 19.45-131.07 105.195-135.15 108.549A48.004 48.004 0 0 0 0 201.485V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V201.509a48 48 0 0 0-17.414-36.993zM464 458a6 6 0 0 1-6 6H54a6 6 0 0 1-6-6V204.347c0-1.813.816-3.526 2.226-4.665 15.87-12.814 108.793-87.554 132.364-106.293C200.755 78.88 232.398 48 256 48c23.693 0 55.857 31.369 73.41 45.389 23.573 18.741 116.503 93.493 132.366 106.316a5.99 5.99 0 0 1 2.224 4.663V458zm-31.991-187.704c4.249 5.159 3.465 12.795-1.745 16.981-28.975 23.283-59.274 47.597-70.929 56.863C336.636 362.283 299.205 400 256 400c-43.452 0-81.287-38.237-103.335-55.86-11.279-8.967-41.744-33.413-70.927-56.865-5.21-4.187-5.993-11.822-1.745-16.981l15.258-18.528c4.178-5.073 11.657-5.843 16.779-1.726 28.618 23.001 58.566 47.035 70.56 56.571C200.143 320.631 232.307 352 256 352c23.602 0 55.246-30.88 73.41-45.389 11.994-9.535 41.944-33.57 70.563-56.568 5.122-4.116 12.601-3.346 16.778 1.727l15.258 18.526z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M288 144a110.94 110.94 0 0 0-31.24 5 55.4 55.4 0 0 1 7.24 27 56 56 0 0 1-56 56 55.4 55.4 0 0 1-27-7.24A111.71 111.71 0 1 0 288 144zm284.52 97.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400c-98.65 0-189.09-55-237.93-144C98.91 167 189.34 112 288 112s189.09 55 237.93 144C477.1 345 386.66 400 288 400z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M634 471L36 3.51A16 16 0 0 0 13.51 6l-10 12.49A16 16 0 0 0 6 41l598 467.49a16 16 0 0 0 22.49-2.49l10-12.49A16 16 0 0 0 634 471zM296.79 146.47l134.79 105.38C429.36 191.91 380.48 144 320 144a112.26 112.26 0 0 0-23.21 2.47zm46.42 219.07L208.42 260.16C210.65 320.09 259.53 368 320 368a113 113 0 0 0 23.21-2.46zM320 112c98.65 0 189.09 55 237.93 144a285.53 285.53 0 0 1-44 60.2l37.74 29.5a333.7 333.7 0 0 0 52.9-75.11 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64c-36.7 0-71.71 7-104.63 18.81l46.41 36.29c18.94-4.3 38.34-7.1 58.22-7.1zm0 288c-98.65 0-189.08-55-237.93-144a285.47 285.47 0 0 1 44.05-60.19l-37.74-29.5a333.6 333.6 0 0 0-52.89 75.1 32.35 32.35 0 0 0 0 29.19C89.72 376.41 197.08 448 320 448c36.7 0 71.71-7.05 104.63-18.81l-46.41-36.28C359.28 397.2 339.89 400 320 400z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M288 248v28c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-28c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm-12 72H108c-6.6 0-12 5.4-12 12v28c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-28c0-6.6-5.4-12-12-12zm108-188.1V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V48C0 21.5 21.5 0 48 0h204.1C264.8 0 277 5.1 286 14.1L369.9 98c9 8.9 14.1 21.2 14.1 33.9zm-128-80V128h76.1L256 51.9zM336 464V176H232c-13.3 0-24-10.7-24-24V48H48v416h288z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M128.3 160v32h32v-32zm64-96h-32v32h32zm-64 32v32h32V96zm64 32h-32v32h32zm177.6-30.1L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h79.7v16h32V48H208v104c0 13.3 10.7 24 24 24h104zM194.2 265.7c-1.1-5.6-6-9.7-11.8-9.7h-22.1v-32h-32v32l-19.7 97.1C102 385.6 126.8 416 160 416c33.1 0 57.9-30.2 51.5-62.6zm-33.9 124.4c-17.9 0-32.4-12.1-32.4-27s14.5-27 32.4-27 32.4 12.1 32.4 27-14.5 27-32.4 27zm32-198.1h-32v32h32z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm144-76.024c0 10.691-12.926 16.045-20.485 8.485L136 360.486h-28c-6.627 0-12-5.373-12-12v-56c0-6.627 5.373-12 12-12h28l35.515-36.947c7.56-7.56 20.485-2.206 20.485 8.485v135.952zm41.201-47.13c9.051-9.297 9.06-24.133.001-33.439-22.149-22.752 12.235-56.246 34.395-33.481 27.198 27.94 27.212 72.444.001 100.401-21.793 22.386-56.947-10.315-34.397-33.481z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M149.9 349.1l-.2-.2-32.8-28.9 32.8-28.9c3.6-3.2 4-8.8.8-12.4l-.2-.2-17.4-18.6c-3.4-3.6-9-3.7-12.4-.4l-57.7 54.1c-3.7 3.5-3.7 9.4 0 12.8l57.7 54.1c1.6 1.5 3.8 2.4 6 2.4 2.4 0 4.8-1 6.4-2.8l17.4-18.6c3.3-3.5 3.1-9.1-.4-12.4zm220-251.2L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h160v104c0 13.3 10.7 24 24 24h104zM209.6 214c-4.7-1.4-9.5 1.3-10.9 6L144 408.1c-1.4 4.7 1.3 9.6 6 10.9l24.4 7.1c4.7 1.4 9.6-1.4 10.9-6L240 231.9c1.4-4.7-1.3-9.6-6-10.9zm24.5 76.9l.2.2 32.8 28.9-32.8 28.9c-3.6 3.2-4 8.8-.8 12.4l.2.2 17.4 18.6c3.3 3.5 8.9 3.7 12.4.4l57.7-54.1c3.7-3.5 3.7-9.4 0-12.8l-57.7-54.1c-3.5-3.3-9.1-3.2-12.4.4l-17.4 18.6c-3.3 3.5-3.1 9.1.4 12.4z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm212-240h-28.8c-4.4 0-8.4 2.4-10.5 6.3-18 33.1-22.2 42.4-28.6 57.7-13.9-29.1-6.9-17.3-28.6-57.7-2.1-3.9-6.2-6.3-10.6-6.3H124c-9.3 0-15 10-10.4 18l46.3 78-46.3 78c-4.7 8 1.1 18 10.4 18h28.9c4.4 0 8.4-2.4 10.5-6.3 21.7-40 23-45 28.6-57.7 14.9 30.2 5.9 15.9 28.6 57.7 2.1 3.9 6.2 6.3 10.6 6.3H260c9.3 0 15-10 10.4-18L224 320c.7-1.1 30.3-50.5 46.3-78 4.7-8-1.1-18-10.3-18z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm32-48h224V288l-23.5-23.5c-4.7-4.7-12.3-4.7-17 0L176 352l-39.5-39.5c-4.7-4.7-12.3-4.7-17 0L80 352v64zm48-240c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm250.2-143.7c-12.2-12-47-8.7-64.4-6.5-17.2-10.5-28.7-25-36.8-46.3 3.9-16.1 10.1-40.6 5.4-56-4.2-26.2-37.8-23.6-42.6-5.9-4.4 16.1-.4 38.5 7 67.1-10 23.9-24.9 56-35.4 74.4-20 10.3-47 26.2-51 46.2-3.3 15.8 26 55.2 76.1-31.2 22.4-7.4 46.8-16.5 68.4-20.1 18.9 10.2 41 17 55.8 17 25.5 0 28-28.2 17.5-38.7zm-198.1 77.8c5.1-13.7 24.5-29.5 30.4-35-19 30.3-30.4 35.7-30.4 35zm81.6-190.6c7.4 0 6.7 32.1 1.8 40.8-4.4-13.9-4.3-40.8-1.8-40.8zm-24.4 136.6c9.7-16.9 18-37 24.7-54.7 8.3 15.1 18.9 27.2 30.1 35.5-20.8 4.3-38.9 13.1-54.8 19.2zm131.6-5s-5 6-37.3-7.8c35.1-2.6 40.9 5.4 37.3 7.8z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm72-60V236c0-6.6 5.4-12 12-12h69.2c36.7 0 62.8 27 62.8 66.3 0 74.3-68.7 66.5-95.5 66.5V404c0 6.6-5.4 12-12 12H132c-6.6 0-12-5.4-12-12zm48.5-87.4h23c7.9 0 13.9-2.4 18.1-7.2 8.5-9.8 8.4-28.5.1-37.8-4.1-4.6-9.9-7-17.4-7h-23.9v52z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm228.687-211.303L224 305.374V268c0-11.046-8.954-20-20-20H100c-11.046 0-20 8.954-20 20v104c0 11.046 8.954 20 20 20h104c11.046 0 20-8.954 20-20v-37.374l52.687 52.674C286.704 397.318 304 390.28 304 375.986V264.011c0-14.311-17.309-21.319-27.313-11.314z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm220.1-208c-5.7 0-10.6 4-11.7 9.5-20.6 97.7-20.4 95.4-21 103.5-.2-1.2-.4-2.6-.7-4.3-.8-5.1.3.2-23.6-99.5-1.3-5.4-6.1-9.2-11.7-9.2h-13.3c-5.5 0-10.3 3.8-11.7 9.1-24.4 99-24 96.2-24.8 103.7-.1-1.1-.2-2.5-.5-4.2-.7-5.2-14.1-73.3-19.1-99-1.1-5.6-6-9.7-11.8-9.7h-16.8c-7.8 0-13.5 7.3-11.7 14.8 8 32.6 26.7 109.5 33.2 136 1.3 5.4 6.1 9.1 11.7 9.1h25.2c5.5 0 10.3-3.7 11.6-9.1l17.9-71.4c1.5-6.2 2.5-12 3-17.3l2.9 17.3c.1.4 12.6 50.5 17.9 71.4 1.3 5.3 6.1 9.1 11.6 9.1h24.7c5.5 0 10.3-3.7 11.6-9.1 20.8-81.9 30.2-119 34.5-136 1.9-7.6-3.8-14.9-11.6-14.9h-15.8z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M336.174 80c-49.132 0-93.305-32-161.913-32-31.301 0-58.303 6.482-80.721 15.168a48.04 48.04 0 0 0 2.142-20.727C93.067 19.575 74.167 1.594 51.201.104 23.242-1.71 0 20.431 0 48c0 17.764 9.657 33.262 24 41.562V496c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-83.443C109.869 395.28 143.259 384 199.826 384c49.132 0 93.305 32 161.913 32 58.479 0 101.972-22.617 128.548-39.981C503.846 367.161 512 352.051 512 335.855V95.937c0-34.459-35.264-57.768-66.904-44.117C409.193 67.309 371.641 80 336.174 80zM464 336c-21.783 15.412-60.824 32-102.261 32-59.945 0-102.002-32-161.913-32-43.361 0-96.379 9.403-127.826 24V128c21.784-15.412 60.824-32 102.261-32 59.945 0 102.002 32 161.913 32 43.271 0 96.32-17.366 127.826-32v240z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm96-312c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-112 24c0-44.2-35.8-80-80-80s-80 35.8-80 80 35.8 80 80 80 80-35.8 80-80zm-80 48c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm160 144H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-54.63-54.63c-6-6-14.14-9.37-22.63-9.37H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm0 272H48V112h140.12l54.63 54.63c6 6 14.14 9.37 22.63 9.37H464v224z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M527.9 224H480v-48c0-26.5-21.5-48-48-48H272l-64-64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h400c16.5 0 31.9-8.5 40.7-22.6l79.9-128c20-31.9-3-73.4-40.7-73.4zM48 118c0-3.3 2.7-6 6-6h134.1l64 64H426c3.3 0 6 2.7 6 6v42H152c-16.8 0-32.4 8.8-41.1 23.2L48 351.4zm400 282H72l77.2-128H528z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 128c-40.2 0-78 17.7-103.8 48.6-8.5 10.2-7.1 25.3 3.1 33.8 10.2 8.4 25.3 7.1 33.8-3.1 16.6-19.9 41-31.4 66.9-31.4s50.3 11.4 66.9 31.4c8.1 9.7 23.1 11.9 33.8 3.1 10.2-8.5 11.5-23.6 3.1-33.8C326 321.7 288.2 304 248 304z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-48-248c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 112c-35.6 0-88.8 21.3-95.8 61.2-2 11.8 9 21.5 20.5 18.1 31.2-9.6 59.4-15.3 75.3-15.3s44.1 5.7 75.3 15.3c11.4 3.5 22.5-6.3 20.5-18.1-7-39.9-60.2-61.2-95.8-61.2z\"],\n    \"futbol\": [496, 512, [], \"f1e3\", \"M483.8 179.4C449.8 74.6 352.6 8 248.1 8c-25.4 0-51.2 3.9-76.7 12.2C41.2 62.5-30.1 202.4 12.2 332.6 46.2 437.4 143.4 504 247.9 504c25.4 0 51.2-3.9 76.7-12.2 130.2-42.3 201.5-182.2 159.2-312.4zm-74.5 193.7l-52.2 6.4-43.7-60.9 24.4-75.2 71.1-22.1 38.9 36.4c-.2 30.7-7.4 61.1-21.7 89.2-4.7 9.3-10.7 17.8-16.8 26.2zm0-235.4l-10.4 53.1-70.7 22-64.2-46.5V92.5l47.4-26.2c39.2 13 73.4 38 97.9 71.4zM184.9 66.4L232 92.5v73.8l-64.2 46.5-70.6-22-10.1-52.5c24.3-33.4 57.9-58.6 97.8-71.9zM139 379.5L85.9 373c-14.4-20.1-37.3-59.6-37.8-115.3l39-36.4 71.1 22.2 24.3 74.3-43.5 61.7zm48.2 67l-22.4-48.1 43.6-61.7H287l44.3 61.7-22.4 48.1c-6.2 1.8-57.6 20.4-121.7 0z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M464 0H112c-4 0-7.8 2-10 5.4L2 152.6c-2.9 4.4-2.6 10.2.7 14.2l276 340.8c4.8 5.9 13.8 5.9 18.6 0l276-340.8c3.3-4.1 3.6-9.8.7-14.2L474.1 5.4C471.8 2 468.1 0 464 0zm-19.3 48l63.3 96h-68.4l-51.7-96h56.8zm-202.1 0h90.7l51.7 96H191l51.6-96zm-111.3 0h56.8l-51.7 96H68l63.3-96zm-43 144h51.4L208 352 88.3 192zm102.9 0h193.6L288 435.3 191.2 192zM368 352l68.2-160h51.4L368 352z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm16 16H152c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h192c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48zm-168 96h-24c-8.8 0-16-7.2-16-16v-8h40v24zm0-40h-40v-8c0-8.8 7.2-16 16-16h24v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm56 24c0 8.8-7.2 16-16 16h-24v-24h40v8zm0-24h-40v-24h24c8.8 0 16 7.2 16 16v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M200.3 248c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zm128 0c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-235.9-72.9c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3zm160 0c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3z\"],\n    \"grin-beam-sweat\": [496, 512, [], \"f583\", \"M440 160c29.5 0 53.3-26.3 53.3-58.7 0-25-31.7-75.5-46.2-97.3-3.6-5.3-10.7-5.3-14.2 0-14.5 21.8-46.2 72.3-46.2 97.3 0 32.4 23.8 58.7 53.3 58.7zM248 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zm105.3-52.9c-24.6 15.7-46 12.9-46.4 12.9 6.9 20.2 10.8 41.8 10.8 64.3 0 110.3-89.7 200-200 200S48 366.3 48 256 137.7 56 248 56c39.8 0 76.8 11.8 108 31.9 1.7-9.5 6.3-24.1 17.2-45.7C336.4 20.6 293.7 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-27-4.4-52.9-12.4-77.2zM168 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M353.6 304.6c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-152.8-48.9c4.5 1.2 9.2-1.5 10.5-6l19.4-69.9c5.6-20.3-7.4-41.1-28.8-44.5-18.6-3-36.4 9.8-41.5 27.9l-2 7.1-7.1-1.9c-18.2-4.7-38.2 4.3-44.9 22-7.7 20.2 3.8 41.9 24.2 47.2l70.2 18.1zm188.8-65.3c-6.7-17.6-26.7-26.7-44.9-22l-7.1 1.9-2-7.1c-5-18.1-22.8-30.9-41.5-27.9-21.4 3.4-34.4 24.2-28.8 44.5l19.4 69.9c1.2 4.5 5.9 7.2 10.5 6l70.2-18.2c20.4-5.3 31.9-26.9 24.2-47.1zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-234.7-40.8c3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3l-80-48c-5.1-3-11.4-1.9-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11.1.1 15.5zm242.9 2.5c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11-.1-15.5-3.8-4.4-10.2-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M117.1 384.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 479 124.3 420.8 128 395c.8-6.4-4.6-11.8-10.9-10.9zm-41.2-41.7C40.3 268 53 176.1 114.6 114.6 152.4 76.8 202.6 56 256 56c36.2 0 70.8 9.8 101.2 27.7 3.8-20.3 8-36.1 12-48.3C333.8 17.2 294.9 8 256 8 192.5 8 129.1 32.2 80.6 80.6c-74.1 74.1-91.3 183.4-52 274 12.2-4.1 27.7-8.3 47.3-12.2zm352.3-187.6c45 76.6 34.9 176.9-30.8 242.6-37.8 37.8-88 58.6-141.4 58.6-30.5 0-59.8-7-86.4-19.8-3.9 19.5-8 35-12.2 47.2 31.4 13.6 65 20.6 98.7 20.6 63.5 0 126.9-24.2 175.4-72.6 78.1-78.1 93.1-195.4 45.2-288.6-12.3 4-28.2 8.1-48.5 12zm-33.3-26.9c25.8-3.7 84-13.7 100.9-30.6 21.9-21.9 21.5-57.9-.9-80.3s-58.3-22.8-80.3-.9C397.7 33 387.7 91.2 384 117c-.8 6.4 4.6 11.8 10.9 10.9zm-187 108.3c-3-3-7.2-4.2-11.4-3.2L106 255.7c-5.7 1.4-9.5 6.7-9.1 12.6.5 5.8 5.1 10.5 10.9 11l52.3 4.8 4.8 52.3c.5 5.8 5.2 10.4 11 10.9h.9c5.5 0 10.3-3.7 11.7-9.1l22.6-90.5c1-4.2-.2-8.5-3.2-11.5zm39.7-25.1l90.5-22.6c5.7-1.4 9.5-6.7 9.1-12.6-.5-5.8-5.1-10.5-10.9-11l-52.3-4.8-4.8-52.3c-.5-5.8-5.2-10.4-11-10.9-5.6-.1-11.2 3.4-12.6 9.1L233 196.5c-1 4.1.2 8.4 3.2 11.4 5 5 11.3 3.2 11.4 3.2zm52 88.5c-29.1 29.1-59.7 52.9-83.9 65.4-9.2 4.8-10 17.5-1.7 23.4 38.9 27.7 107 6.2 143.7-30.6S416 253 388.3 214.1c-5.8-8.2-18.5-7.6-23.4 1.7-12.3 24.2-36.2 54.7-65.3 83.8z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-227.9-57.5c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.5 1.9-12.2-4.3-13.2l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6.1 34.9zm259.7-72.7l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6 34.9c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.6 1.8-12.2-4.4-13.2z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M117.1 256.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 351 124.3 292.8 128 267c.8-6.4-4.6-11.8-10.9-10.9zm506.7 30.6c-16.9-16.9-75.1-26.9-100.9-30.6-6.3-.9-11.7 4.5-10.8 10.8 3.7 25.8 13.7 84 30.6 100.9 21.9 21.9 57.9 21.5 80.3-.9 22.3-22.3 22.7-58.3.8-80.2zm-126.6 61.7C463.8 412.3 396.9 456 320 456c-76.9 0-143.8-43.7-177.2-107.6-12.5 37.4-25.2 43.9-28.3 46.5C159.1 460.7 234.5 504 320 504s160.9-43.3 205.5-109.1c-3.2-2.7-15.9-9.2-28.3-46.5zM122.7 224.5C137.9 129.2 220.5 56 320 56c99.5 0 182.1 73.2 197.3 168.5 2.1-.2 5.2-2.4 49.5 7C554.4 106 448.7 8 320 8S85.6 106 73.2 231.4c44.5-9.4 47.1-7.2 49.5-6.9zM320 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zM240 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zM168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zm36.9-281.1c-3.8-4.4-10.3-5.5-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zm-162.9 45.5l-80-48c-5-3-11.4-2-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M152 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm176-52c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M328 180c-25.69 0-55.88 16.92-59.86 42.12-1.75 11.22 11.5 18.24 19.83 10.84l9.55-8.48c14.81-13.19 46.16-13.19 60.97 0l9.55 8.48c8.48 7.43 21.56.25 19.83-10.84C383.88 196.92 353.69 180 328 180zm-160 60c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm185.55 64.64c-25.93 8.3-64.4 13.06-105.55 13.06s-79.62-4.75-105.55-13.06c-9.94-3.13-19.4 5.37-17.71 15.34C132.67 367.13 196.06 400 248 400s115.33-32.87 123.26-80.02c1.68-9.89-7.67-18.48-17.71-15.34zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M556.686 290.542L410.328 64.829C397.001 44.272 374.417 32 349.917 32H56C25.121 32 0 57.122 0 88v8c0 44.112 35.888 80 80 80h196.042l-18.333 48H144c-48.523 0-88 39.477-88 88 0 30.879 25.121 56 56 56h131.552c2.987 0 5.914.549 8.697 1.631L352 408.418V480h224V355.829c0-23.225-6.679-45.801-19.314-65.287zM528 432H400v-23.582c0-19.948-12.014-37.508-30.604-44.736l-99.751-38.788A71.733 71.733 0 0 0 243.552 320H112c-4.411 0-8-3.589-8-8 0-22.056 17.944-40 40-40h113.709c19.767 0 37.786-12.407 44.84-30.873l24.552-64.281c8.996-23.553-8.428-48.846-33.63-48.846H80c-17.645 0-32-14.355-32-32v-8c0-4.411 3.589-8 8-8h293.917c8.166 0 15.693 4.09 20.137 10.942l146.358 225.715A71.84 71.84 0 0 1 528 355.829V432z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M372.57 112.641v-10.825c0-43.612-40.52-76.691-83.039-65.546-25.629-49.5-94.09-47.45-117.982.747C130.269 26.456 89.144 57.945 89.144 102v126.13c-19.953-7.427-43.308-5.068-62.083 8.871-29.355 21.796-35.794 63.333-14.55 93.153L132.48 498.569a32 32 0 0 0 26.062 13.432h222.897c14.904 0 27.835-10.289 31.182-24.813l30.184-130.958A203.637 203.637 0 0 0 448 310.564V179c0-40.62-35.523-71.992-75.43-66.359zm27.427 197.922c0 11.731-1.334 23.469-3.965 34.886L368.707 464h-201.92L51.591 302.303c-14.439-20.27 15.023-42.776 29.394-22.605l27.128 38.079c8.995 12.626 29.031 6.287 29.031-9.283V102c0-25.645 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V67c0-25.663 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V101.125c0-25.672 36.57-24.81 36.57.691V256c0 8.837 7.163 16 16 16h6.857c8.837 0 16-7.163 16-16v-76.309c0-26.242 36.57-25.64 36.57-.691v131.563z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M362.146 191.976c-13.71-21.649-38.761-34.016-65.006-30.341V74c0-40.804-32.811-74-73.141-74-40.33 0-73.14 33.196-73.14 74L160 168l-18.679-78.85C126.578 50.843 83.85 32.11 46.209 47.208 8.735 62.238-9.571 104.963 5.008 142.85l55.757 144.927c-30.557 24.956-43.994 57.809-24.733 92.218l54.853 97.999C102.625 498.97 124.73 512 148.575 512h205.702c30.744 0 57.558-21.44 64.555-51.797l27.427-118.999a67.801 67.801 0 0 0 1.729-15.203L448 256c0-44.956-43.263-77.343-85.854-64.024zM399.987 326c0 1.488-.169 2.977-.502 4.423l-27.427 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H148.575c-6.486 0-12.542-3.621-15.805-9.449l-54.854-98c-4.557-8.141-2.619-18.668 4.508-24.488l26.647-21.764a16 16 0 0 0 4.812-18.139l-64.09-166.549C37.226 92.956 84.37 74.837 96.51 106.389l59.784 155.357A16 16 0 0 0 171.227 272h11.632c8.837 0 16-7.163 16-16V74c0-34.375 50.281-34.43 50.281 0v182c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16v-28c0-25.122 36.567-25.159 36.567 0v28c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16 0-25.12 36.567-25.16 36.567 0v70z\"],\n    \"hand-point-down\": [448, 512, [], \"f0a7\", \"M188.8 512c45.616 0 83.2-37.765 83.2-83.2v-35.647a93.148 93.148 0 0 0 22.064-7.929c22.006 2.507 44.978-3.503 62.791-15.985C409.342 368.1 448 331.841 448 269.299V248c0-60.063-40-98.512-40-127.2v-2.679c4.952-5.747 8-13.536 8-22.12V32c0-17.673-12.894-32-28.8-32H156.8C140.894 0 128 14.327 128 32v64c0 8.584 3.048 16.373 8 22.12v2.679c0 6.964-6.193 14.862-23.668 30.183l-.148.129-.146.131c-9.937 8.856-20.841 18.116-33.253 25.851C48.537 195.798 0 207.486 0 252.8c0 56.928 35.286 92 83.2 92 8.026 0 15.489-.814 22.4-2.176V428.8c0 45.099 38.101 83.2 83.2 83.2zm0-48c-18.7 0-35.2-16.775-35.2-35.2V270.4c-17.325 0-35.2 26.4-70.4 26.4-26.4 0-35.2-20.625-35.2-44 0-8.794 32.712-20.445 56.1-34.926 14.575-9.074 27.225-19.524 39.875-30.799 18.374-16.109 36.633-33.836 39.596-59.075h176.752C364.087 170.79 400 202.509 400 248v21.299c0 40.524-22.197 57.124-61.325 50.601-8.001 14.612-33.979 24.151-53.625 12.925-18.225 19.365-46.381 17.787-61.05 4.95V428.8c0 18.975-16.225 35.2-35.2 35.2zM328 64c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M0 220.8C0 266.416 37.765 304 83.2 304h35.647a93.148 93.148 0 0 0 7.929 22.064c-2.507 22.006 3.503 44.978 15.985 62.791C143.9 441.342 180.159 480 242.701 480H264c60.063 0 98.512-40 127.2-40h2.679c5.747 4.952 13.536 8 22.12 8h64c17.673 0 32-12.894 32-28.8V188.8c0-15.906-14.327-28.8-32-28.8h-64c-8.584 0-16.373 3.048-22.12 8H391.2c-6.964 0-14.862-6.193-30.183-23.668l-.129-.148-.131-.146c-8.856-9.937-18.116-20.841-25.851-33.253C316.202 80.537 304.514 32 259.2 32c-56.928 0-92 35.286-92 83.2 0 8.026.814 15.489 2.176 22.4H83.2C38.101 137.6 0 175.701 0 220.8zm48 0c0-18.7 16.775-35.2 35.2-35.2h158.4c0-17.325-26.4-35.2-26.4-70.4 0-26.4 20.625-35.2 44-35.2 8.794 0 20.445 32.712 34.926 56.1 9.074 14.575 19.524 27.225 30.799 39.875 16.109 18.374 33.836 36.633 59.075 39.596v176.752C341.21 396.087 309.491 432 264 432h-21.299c-40.524 0-57.124-22.197-50.601-61.325-14.612-8.001-24.151-33.979-12.925-53.625-19.365-18.225-17.787-46.381-4.95-61.05H83.2C64.225 256 48 239.775 48 220.8zM448 360c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M428.8 137.6h-86.177a115.52 115.52 0 0 0 2.176-22.4c0-47.914-35.072-83.2-92-83.2-45.314 0-57.002 48.537-75.707 78.784-7.735 12.413-16.994 23.317-25.851 33.253l-.131.146-.129.148C135.662 161.807 127.764 168 120.8 168h-2.679c-5.747-4.952-13.536-8-22.12-8H32c-17.673 0-32 12.894-32 28.8v230.4C0 435.106 14.327 448 32 448h64c8.584 0 16.373-3.048 22.12-8h2.679c28.688 0 67.137 40 127.2 40h21.299c62.542 0 98.8-38.658 99.94-91.145 12.482-17.813 18.491-40.785 15.985-62.791A93.148 93.148 0 0 0 393.152 304H428.8c45.435 0 83.2-37.584 83.2-83.2 0-45.099-38.101-83.2-83.2-83.2zm0 118.4h-91.026c12.837 14.669 14.415 42.825-4.95 61.05 11.227 19.646 1.687 45.624-12.925 53.625 6.524 39.128-10.076 61.325-50.6 61.325H248c-45.491 0-77.21-35.913-120-39.676V215.571c25.239-2.964 42.966-21.222 59.075-39.596 11.275-12.65 21.725-25.3 30.799-39.875C232.355 112.712 244.006 80 252.8 80c23.375 0 44 8.8 44 35.2 0 35.2-26.4 53.075-26.4 70.4h158.4c18.425 0 35.2 16.5 35.2 35.2 0 18.975-16.225 35.2-35.2 35.2zM88 384c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"hand-point-up\": [448, 512, [], \"f0a6\", \"M105.6 83.2v86.177a115.52 115.52 0 0 0-22.4-2.176c-47.914 0-83.2 35.072-83.2 92 0 45.314 48.537 57.002 78.784 75.707 12.413 7.735 23.317 16.994 33.253 25.851l.146.131.148.129C129.807 376.338 136 384.236 136 391.2v2.679c-4.952 5.747-8 13.536-8 22.12v64c0 17.673 12.894 32 28.8 32h230.4c15.906 0 28.8-14.327 28.8-32v-64c0-8.584-3.048-16.373-8-22.12V391.2c0-28.688 40-67.137 40-127.2v-21.299c0-62.542-38.658-98.8-91.145-99.94-17.813-12.482-40.785-18.491-62.791-15.985A93.148 93.148 0 0 0 272 118.847V83.2C272 37.765 234.416 0 188.8 0c-45.099 0-83.2 38.101-83.2 83.2zm118.4 0v91.026c14.669-12.837 42.825-14.415 61.05 4.95 19.646-11.227 45.624-1.687 53.625 12.925 39.128-6.524 61.325 10.076 61.325 50.6V264c0 45.491-35.913 77.21-39.676 120H183.571c-2.964-25.239-21.222-42.966-39.596-59.075-12.65-11.275-25.3-21.725-39.875-30.799C80.712 279.645 48 267.994 48 259.2c0-23.375 8.8-44 35.2-44 35.2 0 53.075 26.4 70.4 26.4V83.2c0-18.425 16.5-35.2 35.2-35.2 18.975 0 35.2 16.225 35.2 35.2zM352 424c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M358.182 179.361c-19.493-24.768-52.679-31.945-79.872-19.098-15.127-15.687-36.182-22.487-56.595-19.629V67c0-36.944-29.736-67-66.286-67S89.143 30.056 89.143 67v161.129c-19.909-7.41-43.272-5.094-62.083 8.872-29.355 21.795-35.793 63.333-14.55 93.152l109.699 154.001C134.632 501.59 154.741 512 176 512h178.286c30.802 0 57.574-21.5 64.557-51.797l27.429-118.999A67.873 67.873 0 0 0 448 326v-84c0-46.844-46.625-79.273-89.818-62.639zM80.985 279.697l27.126 38.079c8.995 12.626 29.031 6.287 29.031-9.283V67c0-25.12 36.571-25.16 36.571 0v175c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16v-35c0-25.12 36.571-25.16 36.571 0v35c0 8.836 7.163 16 16 16H272c8.837 0 16-7.164 16-16v-21c0-25.12 36.571-25.16 36.571 0v21c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16 0-25.121 36.571-25.16 36.571 0v84c0 1.488-.169 2.977-.502 4.423l-27.43 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H176c-5.769 0-11.263-2.878-14.697-7.697l-109.712-154c-14.406-20.223 14.994-42.818 29.394-22.606zM176.143 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.733 0-14-7.163-14-16zm75.428 0v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16zM327 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M408.864 79.052c-22.401-33.898-66.108-42.273-98.813-23.588-29.474-31.469-79.145-31.093-108.334-.022-47.16-27.02-108.71 5.055-110.671 60.806C44.846 105.407 0 140.001 0 187.429v56.953c0 32.741 14.28 63.954 39.18 85.634l97.71 85.081c4.252 3.702 3.11 5.573 3.11 32.903 0 17.673 14.327 32 32 32h252c17.673 0 32-14.327 32-32 0-23.513-1.015-30.745 3.982-42.37l42.835-99.656c6.094-14.177 9.183-29.172 9.183-44.568V146.963c0-52.839-54.314-88.662-103.136-67.911zM464 261.406a64.505 64.505 0 0 1-5.282 25.613l-42.835 99.655c-5.23 12.171-7.883 25.04-7.883 38.25V432H188v-10.286c0-16.37-7.14-31.977-19.59-42.817l-97.71-85.08C56.274 281.255 48 263.236 48 244.381v-56.953c0-33.208 52-33.537 52 .677v41.228a16 16 0 0 0 5.493 12.067l7 6.095A16 16 0 0 0 139 235.429V118.857c0-33.097 52-33.725 52 .677v26.751c0 8.836 7.164 16 16 16h7c8.836 0 16-7.164 16-16v-41.143c0-33.134 52-33.675 52 .677v40.466c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16v-27.429c0-33.03 52-33.78 52 .677v26.751c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16 0-33.146 52-33.613 52 .677v114.445z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M256 480l70-.013c5.114 0 10.231-.583 15.203-1.729l118.999-27.427C490.56 443.835 512 417.02 512 386.277V180.575c0-23.845-13.03-45.951-34.005-57.69l-97.999-54.853c-34.409-19.261-67.263-5.824-92.218 24.733L142.85 37.008c-37.887-14.579-80.612 3.727-95.642 41.201-15.098 37.642 3.635 80.37 41.942 95.112L168 192l-94-9.141c-40.804 0-74 32.811-74 73.14 0 40.33 33.196 73.141 74 73.141h87.635c-3.675 26.245 8.692 51.297 30.341 65.006C178.657 436.737 211.044 480 256 480zm0-48.013c-25.16 0-25.12-36.567 0-36.567 8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16h-28c-25.159 0-25.122-36.567 0-36.567h28c8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16H74c-34.43 0-34.375-50.281 0-50.281h182c8.837 0 16-7.163 16-16v-11.632a16 16 0 0 0-10.254-14.933L106.389 128.51c-31.552-12.14-13.432-59.283 19.222-46.717l166.549 64.091a16.001 16.001 0 0 0 18.139-4.812l21.764-26.647c5.82-7.127 16.348-9.064 24.488-4.508l98 54.854c5.828 3.263 9.449 9.318 9.449 15.805v205.701c0 8.491-5.994 15.804-14.576 17.782l-119.001 27.427a19.743 19.743 0 0 1-4.423.502h-70z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M21.096 381.79l129.092 121.513a32 32 0 0 0 21.932 8.698h237.6c14.17 0 26.653-9.319 30.68-22.904l31.815-107.313A115.955 115.955 0 0 0 477 348.811v-36.839c0-4.051.476-8.104 1.414-12.045l31.73-133.41c10.099-42.412-22.316-82.738-65.544-82.525-4.144-24.856-22.543-47.165-49.85-53.992-35.803-8.952-72.227 12.655-81.25 48.75L296.599 184 274.924 52.01c-8.286-36.07-44.303-58.572-80.304-50.296-29.616 6.804-50.138 32.389-51.882 61.295-42.637.831-73.455 40.563-64.071 81.844l31.04 136.508c-27.194-22.515-67.284-19.992-91.482 5.722-25.376 26.961-24.098 69.325 2.871 94.707zm32.068-61.811l.002-.001c7.219-7.672 19.241-7.98 26.856-.813l53.012 49.894C143.225 378.649 160 371.4 160 357.406v-69.479c0-1.193-.134-2.383-.397-3.546l-34.13-150.172c-5.596-24.617 31.502-32.86 37.054-8.421l30.399 133.757a16 16 0 0 0 15.603 12.454h8.604c10.276 0 17.894-9.567 15.594-19.583l-41.62-181.153c-5.623-24.469 31.39-33.076 37.035-8.508l45.22 196.828A16 16 0 0 0 288.956 272h13.217a16 16 0 0 0 15.522-12.119l42.372-169.49c6.104-24.422 42.962-15.159 36.865 9.217L358.805 252.12c-2.521 10.088 5.115 19.88 15.522 19.88h9.694a16 16 0 0 0 15.565-12.295L426.509 146.6c5.821-24.448 42.797-15.687 36.966 8.802L431.72 288.81a100.094 100.094 0 0 0-2.72 23.162v36.839c0 6.548-.943 13.051-2.805 19.328L397.775 464h-219.31L53.978 346.836c-7.629-7.18-7.994-19.229-.814-26.857z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M519.2 127.9l-47.6-47.6A56.252 56.252 0 0 0 432 64H205.2c-14.8 0-29.1 5.9-39.6 16.3L118 127.9H0v255.7h64c17.6 0 31.8-14.2 31.9-31.7h9.1l84.6 76.4c30.9 25.1 73.8 25.7 105.6 3.8 12.5 10.8 26 15.9 41.1 15.9 18.2 0 35.3-7.4 48.8-24 22.1 8.7 48.2 2.6 64-16.8l26.2-32.3c5.6-6.9 9.1-14.8 10.9-23h57.9c.1 17.5 14.4 31.7 31.9 31.7h64V127.9H519.2zM48 351.6c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16zm390-6.9l-26.1 32.2c-2.8 3.4-7.8 4-11.3 1.2l-23.9-19.4-30 36.5c-6 7.3-15 4.8-18 2.4l-36.8-31.5-15.6 19.2c-13.9 17.1-39.2 19.7-55.3 6.6l-97.3-88H96V175.8h41.9l61.7-61.6c2-.8 3.7-1.5 5.7-2.3H262l-38.7 35.5c-29.4 26.9-31.1 72.3-4.4 101.3 14.8 16.2 61.2 41.2 101.5 4.4l8.2-7.5 108.2 87.8c3.4 2.8 3.9 7.9 1.2 11.3zm106-40.8h-69.2c-2.3-2.8-4.9-5.4-7.7-7.7l-102.7-83.4 12.5-11.4c6.5-6 7-16.1 1-22.6L367 167.1c-6-6.5-16.1-6.9-22.6-1l-55.2 50.6c-9.5 8.7-25.7 9.4-34.6 0-9.3-9.9-8.5-25.1 1.2-33.9l65.6-60.1c7.4-6.8 17-10.5 27-10.5l83.7-.2c2.1 0 4.1.8 5.5 2.3l61.7 61.6H544v128zm48 47.7c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M567.403 235.642L462.323 84.589A48 48 0 0 0 422.919 64H153.081a48 48 0 0 0-39.404 20.589L8.597 235.642A48.001 48.001 0 0 0 0 263.054V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V263.054c0-9.801-3-19.366-8.597-27.412zM153.081 112h269.838l77.913 112H75.168l77.913-112zM528 400H48V272h480v128zm-32-64c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32zm-96 0c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M458.4 64.3C400.6 15.7 311.3 23 256 79.3 200.7 23 111.4 15.6 53.6 64.3-21.6 127.6-10.6 230.8 43 285.5l175.4 178.7c10 10.2 23.4 15.9 37.6 15.9 14.3 0 27.6-5.6 37.6-15.8L469 285.6c53.5-54.7 64.7-157.9-10.6-221.3zm-23.6 187.5L259.4 430.5c-2.4 2.4-4.4 2.4-6.8 0L77.2 251.8c-36.5-37.2-43.9-107.6 7.3-150.7 38.9-32.7 98.9-27.8 136.5 10.5l35 35.7 35-35.7c37.8-38.5 97.8-43.2 136.5-10.6 51.1 43.1 43.5 113.9 7.3 150.8z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M128 244v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12zm140 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm-76 84v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm76 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm180 124v36H0v-36c0-6.627 5.373-12 12-12h19.5V85.035C31.5 73.418 42.245 64 55.5 64H144V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v40h88.5c13.255 0 24 9.418 24 21.035V464H436c6.627 0 12 5.373 12 12zM79.5 463H192v-67c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v67h112.5V112H304v24c0 13.255-10.745 24-24 24H168c-13.255 0-24-10.745-24-24v-24H79.5v351zM266 64h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M368 48h4c6.627 0 12-5.373 12-12V12c0-6.627-5.373-12-12-12H12C5.373 0 0 5.373 0 12v24c0 6.627 5.373 12 12 12h4c0 80.564 32.188 165.807 97.18 208C47.899 298.381 16 383.9 16 464h-4c-6.627 0-12 5.373-12 12v24c0 6.627 5.373 12 12 12h360c6.627 0 12-5.373 12-12v-24c0-6.627-5.373-12-12-12h-4c0-80.564-32.188-165.807-97.18-208C336.102 213.619 368 128.1 368 48zM64 48h256c0 101.62-57.307 184-128 184S64 149.621 64 48zm256 416H64c0-101.62 57.308-184 128-184s128 82.38 128 184z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm0 464H48V48h288v416zM144 112h96c8.8 0 16-7.2 16-16s-7.2-16-16-16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16zm48 176c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H303.2c.9-4.5.8 3.6.8-22.4 0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6 0 26-.2 17.9.8 22.4H48V144h480v288zm-168-80h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm-168 96c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 336H54a6 6 0 0 1-6-6V118a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v276a6 6 0 0 1-6 6zM128 152c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zM96 352h320v-80l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L192 304l-39.515-39.515c-4.686-4.686-12.284-4.686-16.971 0L96 304v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v48H54a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6v-10h48zm42-336H150a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6V86a6 6 0 0 0-6-6zm6-48c26.51 0 48 21.49 48 48v256c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h384zM264 144c0 22.091-17.909 40-40 40s-40-17.909-40-40 17.909-40 40-40 40 17.909 40 40zm-72 96l39.515-39.515c4.686-4.686 12.284-4.686 16.971 0L288 240l103.515-103.515c4.686-4.686 12.284-4.686 16.971 0L480 208v80H192v-48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm8 336c0 4.411-3.589 8-8 8H48c-4.411 0-8-3.589-8-8V112c0-4.411 3.589-8 8-8h480c4.411 0 8 3.589 8 8v288zM170 270v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-336 82v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm384 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zM122 188v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-98 158v-16c0-6.627-5.373-12-12-12H180c-6.627 0-12 5.373-12 12v16c0 6.627 5.373 12 12 12h216c6.627 0 12-5.373 12-12z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm136 132c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M168 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm56-148c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zm24-156c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M304 308.5c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36 21.7-9.1 35.1-23.4 35.1-36.4zm70.5-83.5l9.5 8.5c3.8 3.3 9.3 4 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 5.8 3.1 11.2.7 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0zM136 208.5c0 17.7 14.3 32 32 32s32-14.3 32-32-14.3-32-32-32-32 14.3-32 32zm365.1 194c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zM334 436.3c-26.1 12.5-55.2 19.7-86 19.7-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200c0 22.1-3.7 43.3-10.4 63.2 9 6.4 17 14.2 22.6 23.9 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-2.5-7.3 4.3 17.2-13.4-46.8z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 224c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm-160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 152c-23.8 0-52.7 29.3-56 71.4-.7 8.6 10.8 11.9 14.9 4.5l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.1-42.1-32-71.4-55.8-71.4zm-201 75.9l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.6 8.5 10.9 11.9 15.1 4.5zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM343.6 196l33.6-40.3c8.6-10.3-3.8-24.8-15.4-18l-80 48c-7.8 4.7-7.8 15.9 0 20.6l80 48c11.5 6.8 24-7.6 15.4-18L343.6 196zm-209.4 58.3l80-48c7.8-4.7 7.8-15.9 0-20.6l-80-48c-11.6-6.9-24 7.7-15.4 18l33.6 40.3-33.6 40.3c-8.7 10.4 3.8 24.8 15.4 18zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6C68.8 359.6 48 309.4 48 256s20.8-103.6 58.6-141.4C144.4 76.8 194.6 56 248 56s103.6 20.8 141.4 58.6c37.8 37.8 58.6 88 58.6 141.4s-20.8 103.6-58.6 141.4zM328 164c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1zm-160 60c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M484.112 27.889C455.989-.233 416.108-8.057 387.059 8.865 347.604 31.848 223.504-41.111 91.196 91.197-41.277 223.672 31.923 347.472 8.866 387.058c-16.922 29.051-9.1 68.932 19.022 97.054 28.135 28.135 68.011 35.938 97.057 19.021 39.423-22.97 163.557 49.969 295.858-82.329 132.474-132.477 59.273-256.277 82.331-295.861 16.922-29.05 9.1-68.931-19.022-97.054zm-22.405 72.894c-38.8 66.609 45.6 165.635-74.845 286.08-120.44 120.443-219.475 36.048-286.076 74.843-22.679 13.207-64.035-27.241-50.493-50.488 38.8-66.609-45.6-165.635 74.845-286.08C245.573 4.702 344.616 89.086 411.219 50.292c22.73-13.24 64.005 27.288 50.488 50.491zm-169.861 8.736c1.37 10.96-6.404 20.957-17.365 22.327-54.846 6.855-135.779 87.787-142.635 142.635-1.373 10.989-11.399 18.734-22.326 17.365-10.961-1.37-18.735-11.366-17.365-22.326 9.162-73.286 104.167-168.215 177.365-177.365 10.953-1.368 20.956 6.403 22.326 17.364z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 504c136.967 0 248-111.033 248-248S392.967 8 256 8 8 119.033 8 256s111.033 248 248 248zm-103.398-76.72l53.411-53.411c31.806 13.506 68.128 13.522 99.974 0l53.411 53.411c-63.217 38.319-143.579 38.319-206.796 0zM336 256c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zm91.28 103.398l-53.411-53.411c13.505-31.806 13.522-68.128 0-99.974l53.411-53.411c38.319 63.217 38.319 143.579 0 206.796zM359.397 84.72l-53.411 53.411c-31.806-13.505-68.128-13.522-99.973 0L152.602 84.72c63.217-38.319 143.579-38.319 206.795 0zM84.72 152.602l53.411 53.411c-13.506 31.806-13.522 68.128 0 99.974L84.72 359.398c-38.319-63.217-38.319-143.579 0-206.796z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M176 80c-52.94 0-96 43.06-96 96 0 8.84 7.16 16 16 16s16-7.16 16-16c0-35.3 28.72-64 64-64 8.84 0 16-7.16 16-16s-7.16-16-16-16zM96.06 459.17c0 3.15.93 6.22 2.68 8.84l24.51 36.84c2.97 4.46 7.97 7.14 13.32 7.14h78.85c5.36 0 10.36-2.68 13.32-7.14l24.51-36.84c1.74-2.62 2.67-5.7 2.68-8.84l.05-43.18H96.02l.04 43.18zM176 0C73.72 0 0 82.97 0 176c0 44.37 16.45 84.85 43.56 115.78 16.64 18.99 42.74 58.8 52.42 92.16v.06h48v-.12c-.01-4.77-.72-9.51-2.15-14.07-5.59-17.81-22.82-64.77-62.17-109.67-20.54-23.43-31.52-53.15-31.61-84.14-.2-73.64 59.67-128 127.95-128 70.58 0 128 57.42 128 128 0 30.97-11.24 60.85-31.65 84.14-39.11 44.61-56.42 91.47-62.1 109.46a47.507 47.507 0 0 0-2.22 14.3v.1h48v-.05c9.68-33.37 35.78-73.18 52.42-92.16C335.55 260.85 352 220.37 352 176 352 78.8 273.2 0 176 0z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v340a6 6 0 0 1-6 6zm-42-92v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm-252 12c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36z\"],\n    \"map\": [576, 512, [], \"f279\", \"M560.02 32c-1.96 0-3.98.37-5.96 1.16L384.01 96H384L212 35.28A64.252 64.252 0 0 0 191.76 32c-6.69 0-13.37 1.05-19.81 3.14L20.12 87.95A32.006 32.006 0 0 0 0 117.66v346.32C0 473.17 7.53 480 15.99 480c1.96 0 3.97-.37 5.96-1.16L192 416l172 60.71a63.98 63.98 0 0 0 40.05.15l151.83-52.81A31.996 31.996 0 0 0 576 394.34V48.02c0-9.19-7.53-16.02-15.98-16.02zM224 90.42l128 45.19v285.97l-128-45.19V90.42zM48 418.05V129.07l128-44.53v286.2l-.64.23L48 418.05zm480-35.13l-128 44.53V141.26l.64-.24L528 93.95v288.97z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm8 144H160c-13.2 0-24 10.8-24 24s10.8 24 24 24h176c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm88-304c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm0 112c-22.1 0-40-17.9-40-40 0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40zm-104-40c0-39.8-32.2-72-72-72s-72 32.2-72 72 32.2 72 72 72 72-32.2 72-72zm-112 0c0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40s-40-17.9-40-40zm192 128H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M108 284c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h232c6.6 0 12 5.4 12 12v32c0 6.6-5.4 12-12 12H108zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M320 144c-53.02 0-96 50.14-96 112 0 61.85 42.98 112 96 112 53 0 96-50.13 96-112 0-61.86-42.98-112-96-112zm40 168c0 4.42-3.58 8-8 8h-64c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h16v-55.44l-.47.31a7.992 7.992 0 0 1-11.09-2.22l-8.88-13.31a7.992 7.992 0 0 1 2.22-11.09l15.33-10.22a23.99 23.99 0 0 1 13.31-4.03H328c4.42 0 8 3.58 8 8v88h16c4.42 0 8 3.58 8 8v16zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zm-16 272c-35.35 0-64 28.65-64 64H112c0-35.35-28.65-64-64-64V176c35.35 0 64-28.65 64-64h416c0 35.35 28.65 64 64 64v160z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M279.135 512c78.756 0 150.982-35.804 198.844-94.775 28.27-34.831-2.558-85.722-46.249-77.401-82.348 15.683-158.272-47.268-158.272-130.792 0-48.424 26.06-92.292 67.434-115.836 38.745-22.05 28.999-80.788-15.022-88.919A257.936 257.936 0 0 0 279.135 0c-141.36 0-256 114.575-256 256 0 141.36 114.576 256 256 256zm0-464c12.985 0 25.689 1.201 38.016 3.478-54.76 31.163-91.693 90.042-91.693 157.554 0 113.848 103.641 199.2 215.252 177.944C402.574 433.964 344.366 464 279.135 464c-114.875 0-208-93.125-208-208s93.125-208 208-208z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H112c-20.858 0-38.643 13.377-45.248 32H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h496c13.255 0 24-10.745 24-24V88c0-13.255-10.745-24-24-24zM48 392V144h16v248c0 4.411-3.589 8-8 8s-8-3.589-8-8zm480 8H111.422c.374-2.614.578-5.283.578-8V112h416v288zM172 280h136c6.627 0 12-5.373 12-12v-96c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v96c0 6.627 5.373 12 12 12zm28-80h80v40h-80v-40zm-40 140v-24c0-6.627 5.373-12 12-12h136c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H172c-6.627 0-12-5.373-12-12zm192 0v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0-144v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0 72v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M500 128c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v256H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V128h12zm-52-64h32v32h-32V64zM32 64h32v32H32V64zm32 384H32v-32h32v32zm416 0h-32v-32h32v32zm-40-64h-12c-6.627 0-12 5.373-12 12v12H96v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h12v256zm-36-192h-84v-52c0-6.628-5.373-12-12-12H108c-6.627 0-12 5.372-12 12v168c0 6.628 5.373 12 12 12h84v52c0 6.628 5.373 12 12 12h200c6.627 0 12-5.372 12-12V204c0-6.628-5.373-12-12-12zm-268-24h144v112H136V168zm240 176H232v-24h76c6.627 0 12-5.372 12-12v-76h56v112z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M564 224c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12h-88v-24h12c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v160H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h88v24h-12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V224h12zM352 64h32v32h-32V64zm0 256h32v32h-32v-32zM64 352H32v-32h32v32zm0-256H32V64h32v32zm32 216v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h12v160h-12c-6.627 0-12 5.373-12 12v12H96zm128 136h-32v-32h32v32zm280-64h-12c-6.627 0-12 5.373-12 12v12H256v-12c0-6.627-5.373-12-12-12h-12v-24h88v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12v-88h88v12c0 6.627 5.373 12 12 12h12v160zm40 64h-32v-32h32v32zm0-256h-32v-32h32v32z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M440 6.5L24 246.4c-34.4 19.9-31.1 70.8 5.7 85.9L144 379.6V464c0 46.4 59.2 65.5 86.6 28.6l43.8-59.1 111.9 46.2c5.9 2.4 12.1 3.6 18.3 3.6 8.2 0 16.3-2.1 23.6-6.2 12.8-7.2 21.6-20 23.9-34.5l59.4-387.2c6.1-40.1-36.9-68.8-71.5-48.9zM192 464v-64.6l36.6 15.1L192 464zm212.6-28.7l-153.8-63.5L391 169.5c10.7-15.5-9.5-33.5-23.7-21.2L155.8 332.6 48 288 464 48l-59.4 387.3z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm96-280v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16zm-112 0v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M371.7 238l-176-107c-15.8-8.8-35.7 2.5-35.7 21v208c0 18.4 19.8 29.8 35.7 21l176-101c16.4-9.1 16.4-32.8 0-42zM504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M352 240v32c0 6.6-5.4 12-12 12h-88v88c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-88h-88c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h88v-88c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v88h88c6.6 0 12 5.4 12 12zm96-160v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 448c-110.532 0-200-89.431-200-200 0-110.495 89.472-200 200-200 110.491 0 200 89.471 200 200 0 110.53-89.431 200-200 200zm107.244-255.2c0 67.052-72.421 68.084-72.421 92.863V300c0 6.627-5.373 12-12 12h-45.647c-6.627 0-12-5.373-12-12v-8.659c0-35.745 27.1-50.034 47.579-61.516 17.561-9.845 28.324-16.541 28.324-29.579 0-17.246-21.999-28.693-39.784-28.693-23.189 0-33.894 10.977-48.942 29.969-4.057 5.12-11.46 6.071-16.666 2.124l-27.824-21.098c-5.107-3.872-6.251-11.066-2.644-16.363C184.846 131.491 214.94 112 261.794 112c49.071 0 101.45 38.304 101.45 88.8zM298 368c0 23.159-18.841 42-42 42s-42-18.841-42-42 18.841-42 42-42 42 18.841 42 42z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm110.442-81.791c-53.046-96.284-50.25-91.468-53.271-96.085 24.267-13.879 39.482-41.563 39.482-73.176 0-52.503-30.247-85.252-101.498-85.252h-78.667c-6.617 0-12 5.383-12 12V380c0 6.617 5.383 12 12 12h38.568c6.617 0 12-5.383 12-12v-83.663h31.958l47.515 89.303a11.98 11.98 0 0 0 10.593 6.36h42.81c9.14 0 14.914-9.799 10.51-17.791zM256.933 239.906h-33.875v-64.14h27.377c32.417 0 38.929 12.133 38.929 31.709-.001 20.913-11.518 32.431-32.431 32.431z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm144 386.4V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v151.4C315.5 447 282.8 456 248 456s-67.5-9-96-24.6V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v114.4c-34.6-36-56-84.7-56-138.4 0-110.3 89.7-200 200-200s200 89.7 200 200c0 53.7-21.4 102.5-56 138.4zM205.8 234.5c4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.3 7.9 4.8 13.7 1.6zM344 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.5 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm-96 92c-30.9 0-56 28.7-56 64s25.1 64 56 64 56-28.7 56-64-25.1-64-56-64z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm8-152c-13.2 0-24 10.8-24 24s10.8 24 24 24c23.8 0 46.3 10.5 61.6 28.8 8.1 9.8 23.2 11.9 33.8 3.1 10.2-8.5 11.6-23.6 3.1-33.8C330 320.8 294.1 304 256 304zm-88-64c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-165.6 98.8C151 290.1 126 325.4 126 342.9c0 22.7 18.8 41.1 42 41.1s42-18.4 42-41.1c0-17.5-25-52.8-36.4-68.1-2.8-3.7-8.4-3.7-11.2 0z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM272 80v80H144V80h128zm122 352H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h42v104c0 13.255 10.745 24 24 24h176c13.255 0 24-10.745 24-24V83.882l78.243 78.243a6 6 0 0 1 1.757 4.243V426a6 6 0 0 1-6 6zM224 232c-48.523 0-88 39.477-88 88s39.477 88 88 88 88-39.477 88-88-39.477-88-88-88zm0 128c-22.056 0-40-17.944-40-40s17.944-40 40-40 40 17.944 40 40-17.944 40-40 40z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M561.938 158.06L417.94 14.092C387.926-15.922 336 5.097 336 48.032v57.198c-42.45 1.88-84.03 6.55-120.76 17.99-35.17 10.95-63.07 27.58-82.91 49.42C108.22 199.2 96 232.6 96 271.94c0 61.697 33.178 112.455 84.87 144.76 37.546 23.508 85.248-12.651 71.02-55.74-15.515-47.119-17.156-70.923 84.11-78.76V336c0 42.993 51.968 63.913 81.94 33.94l143.998-144c18.75-18.74 18.75-49.14 0-67.88zM384 336V232.16C255.309 234.082 166.492 255.35 206.31 376 176.79 357.55 144 324.08 144 271.94c0-109.334 129.14-118.947 240-119.85V48l144 144-144 144zm24.74 84.493a82.658 82.658 0 0 0 20.974-9.303c7.976-4.952 18.286.826 18.286 10.214V464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h132c6.627 0 12 5.373 12 12v4.486c0 4.917-2.987 9.369-7.569 11.152-13.702 5.331-26.396 11.537-38.05 18.585a12.138 12.138 0 0 1-6.28 1.777H54a6 6 0 0 0-6 6v340a6 6 0 0 0 6 6h340a6 6 0 0 0 6-6v-25.966c0-5.37 3.579-10.059 8.74-11.541z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm4 72.6c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.1-8.4-25.3-7.1-33.8 3.1z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm84-143.4c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.6-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.2-8.4-25.3-7.1-33.8 3.1zM136.5 211c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.4 1.1 7.4-.5 9.3-3.7l9.5-17zM328 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm117.8-146.4c-10.2-8.5-25.3-7.1-33.8 3.1-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-60c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.1 355.2l-39.2-23 34.1-9.3c8.4-2.3 13.4-11.1 11.1-19.6l-4.1-15.5c-2.2-8.5-10.9-13.6-19.3-11.3L343 298.2 271.2 256l71.9-42.2 79.7 21.7c8.4 2.3 17-2.8 19.3-11.3l4.1-15.5c2.2-8.5-2.7-17.3-11.1-19.6l-34.1-9.3 39.2-23c7.5-4.4 10.1-14.2 5.8-21.9l-7.9-13.9c-4.3-7.7-14-10.3-21.5-5.9l-39.2 23 9.1-34.7c2.2-8.5-2.7-17.3-11.1-19.6l-15.2-4.1c-8.4-2.3-17 2.8-19.3 11.3l-21.3 81-71.9 42.2v-84.5L306 70.4c6.1-6.2 6.1-16.4 0-22.6l-11.1-11.3c-6.1-6.2-16.1-6.2-22.2 0l-24.9 25.4V16c0-8.8-7-16-15.7-16h-15.7c-8.7 0-15.7 7.2-15.7 16v46.1l-24.9-25.4c-6.1-6.2-16.1-6.2-22.2 0L142.1 48c-6.1 6.2-6.1 16.4 0 22.6l58.3 59.3v84.5l-71.9-42.2-21.3-81c-2.2-8.5-10.9-13.6-19.3-11.3L72.7 84c-8.4 2.3-13.4 11.1-11.1 19.6l9.1 34.7-39.2-23c-7.5-4.4-17.1-1.8-21.5 5.9l-7.9 13.9c-4.3 7.7-1.8 17.4 5.8 21.9l39.2 23-34.1 9.1c-8.4 2.3-13.4 11.1-11.1 19.6L6 224.2c2.2 8.5 10.9 13.6 19.3 11.3l79.7-21.7 71.9 42.2-71.9 42.2-79.7-21.7c-8.4-2.3-17 2.8-19.3 11.3l-4.1 15.5c-2.2 8.5 2.7 17.3 11.1 19.6l34.1 9.3-39.2 23c-7.5 4.4-10.1 14.2-5.8 21.9L10 391c4.3 7.7 14 10.3 21.5 5.9l39.2-23-9.1 34.7c-2.2 8.5 2.7 17.3 11.1 19.6l15.2 4.1c8.4 2.3 17-2.8 19.3-11.3l21.3-81 71.9-42.2v84.5l-58.3 59.3c-6.1 6.2-6.1 16.4 0 22.6l11.1 11.3c6.1 6.2 16.1 6.2 22.2 0l24.9-25.4V496c0 8.8 7 16 15.7 16h15.7c8.7 0 15.7-7.2 15.7-16v-46.1l24.9 25.4c6.1 6.2 16.1 6.2 22.2 0l11.1-11.3c6.1-6.2 6.1-16.4 0-22.6l-58.3-59.3v-84.5l71.9 42.2 21.3 81c2.2 8.5 10.9 13.6 19.3 11.3L375 428c8.4-2.3 13.4-11.1 11.1-19.6l-9.1-34.7 39.2 23c7.5 4.4 17.1 1.8 21.5-5.9l7.9-13.9c4.6-7.5 2.1-17.3-5.5-21.7z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h340c3.3 0 6 2.7 6 6v340c0 3.3-2.7 6-6 6z\"],\n    \"star\": [576, 512, [], \"f005\", \"M528.1 171.5L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6zM388.6 312.3l23.7 138.4L288 385.4l-124.3 65.3 23.7-138.4-100.6-98 139-20.2 62.2-126 62.2 126 139 20.2-100.6 98z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 385.3l-124.3 65.4 23.7-138.4-100.6-98 139-20.2 62.2-126V0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6v-54.3z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M448 348.106V80c0-26.51-21.49-48-48-48H48C21.49 32 0 53.49 0 80v351.988c0 26.51 21.49 48 48 48h268.118a48 48 0 0 0 33.941-14.059l83.882-83.882A48 48 0 0 0 448 348.106zm-128 80v-76.118h76.118L320 428.106zM400 80v223.988H296c-13.255 0-24 10.745-24 24v104H48V80h352z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm296-80v160c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M494.2 221.9l-59.8-40.5 13.7-71c2.6-13.2-1.6-26.8-11.1-36.4-9.6-9.5-23.2-13.7-36.2-11.1l-70.9 13.7-40.4-59.9c-15.1-22.3-51.9-22.3-67 0l-40.4 59.9-70.8-13.7C98 60.4 84.5 64.5 75 74.1c-9.5 9.6-13.7 23.1-11.1 36.3l13.7 71-59.8 40.5C6.6 229.5 0 242 0 255.5s6.7 26 17.8 33.5l59.8 40.5-13.7 71c-2.6 13.2 1.6 26.8 11.1 36.3 9.5 9.5 22.9 13.7 36.3 11.1l70.8-13.7 40.4 59.9C230 505.3 242.6 512 256 512s26-6.7 33.5-17.8l40.4-59.9 70.9 13.7c13.4 2.7 26.8-1.6 36.3-11.1 9.5-9.5 13.6-23.1 11.1-36.3l-13.7-71 59.8-40.5c11.1-7.5 17.8-20.1 17.8-33.5-.1-13.6-6.7-26.1-17.9-33.7zm-112.9 85.6l17.6 91.2-91-17.6L256 458l-51.9-77-90.9 17.6 17.6-91.2-76.8-52 76.8-52-17.6-91.2 91 17.6L256 53l51.9 76.9 91-17.6-17.6 91.1 76.8 52-76.8 52.1zM256 152c-57.3 0-104 46.7-104 104s46.7 104 104 104 104-46.7 104-104-46.7-104-104-104zm0 160c-30.9 0-56-25.1-56-56s25.1-56 56-56 56 25.1 56 56-25.1 56-56 56z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-176c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm-48-72c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M466.27 225.31c4.674-22.647.864-44.538-8.99-62.99 2.958-23.868-4.021-48.565-17.34-66.99C438.986 39.423 404.117 0 327 0c-7 0-15 .01-22.22.01C201.195.01 168.997 40 128 40h-10.845c-5.64-4.975-13.042-8-21.155-8H32C14.327 32 0 46.327 0 64v240c0 17.673 14.327 32 32 32h64c11.842 0 22.175-6.438 27.708-16h7.052c19.146 16.953 46.013 60.653 68.76 83.4 13.667 13.667 10.153 108.6 71.76 108.6 57.58 0 95.27-31.936 95.27-104.73 0-18.41-3.93-33.73-8.85-46.54h36.48c48.602 0 85.82-41.565 85.82-85.58 0-19.15-4.96-34.99-13.73-49.84zM64 296c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm330.18 16.73H290.19c0 37.82 28.36 55.37 28.36 94.54 0 23.75 0 56.73-47.27 56.73-18.91-18.91-9.46-66.18-37.82-94.54C206.9 342.89 167.28 272 138.92 272H128V85.83c53.611 0 100.001-37.82 171.64-37.82h37.82c35.512 0 60.82 17.12 53.12 65.9 15.2 8.16 26.5 36.44 13.94 57.57 21.581 20.384 18.699 51.065 5.21 65.62 9.45 0 22.36 18.91 22.27 37.81-.09 18.91-16.71 37.82-37.82 37.82z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M466.27 286.69C475.04 271.84 480 256 480 236.85c0-44.015-37.218-85.58-85.82-85.58H357.7c4.92-12.81 8.85-28.13 8.85-46.54C366.55 31.936 328.86 0 271.28 0c-61.607 0-58.093 94.933-71.76 108.6-22.747 22.747-49.615 66.447-68.76 83.4H32c-17.673 0-32 14.327-32 32v240c0 17.673 14.327 32 32 32h64c14.893 0 27.408-10.174 30.978-23.95 44.509 1.001 75.06 39.94 177.802 39.94 7.22 0 15.22.01 22.22.01 77.117 0 111.986-39.423 112.94-95.33 13.319-18.425 20.299-43.122 17.34-66.99 9.854-18.452 13.664-40.343 8.99-62.99zm-61.75 53.83c12.56 21.13 1.26 49.41-13.94 57.57 7.7 48.78-17.608 65.9-53.12 65.9h-37.82c-71.639 0-118.029-37.82-171.64-37.82V240h10.92c28.36 0 67.98-70.89 94.54-97.46 28.36-28.36 18.91-75.63 37.82-94.54 47.27 0 47.27 32.98 47.27 56.73 0 39.17-28.36 56.72-28.36 94.54h103.99c21.11 0 37.73 18.91 37.82 37.82.09 18.9-12.82 37.81-22.27 37.81 13.489 14.555 16.371 45.236-5.21 65.62zM88 432c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm101.8-262.2L295.6 256l62.2 62.2c4.7 4.7 4.7 12.3 0 17l-22.6 22.6c-4.7 4.7-12.3 4.7-17 0L256 295.6l-62.2 62.2c-4.7 4.7-12.3 4.7-17 0l-22.6-22.6c-4.7-4.7-4.7-12.3 0-17l62.2-62.2-62.2-62.2c-4.7-4.7-4.7-12.3 0-17l22.6-22.6c4.7-4.7 12.3-4.7 17 0l62.2 62.2 62.2-62.2c4.7-4.7 12.3-4.7 17 0l22.6 22.6c4.7 4.7 4.7 12.3 0 17z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm129.1-303.8c-3.8-4.4-10.3-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.8 1.6 15.3-2.5 3.8-4.5 3.9-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zM220 208c0-4.2-2.2-8.1-5.8-10.3l-80-48c-5-3-11.5-1.9-15.3 2.5-3.8 4.5-3.9 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.5 4.1 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3zm28 64c-45.4 0-100.9 38.3-107.8 93.3-1.5 11.8 6.9 21.6 15.5 17.9C178.4 373.5 212 368 248 368s69.6 5.5 92.3 15.2c8.5 3.7 17-6 15.5-17.9-6.9-55-62.4-93.3-107.8-93.3z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M268 416h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12zM432 80h-82.41l-34-56.7A48 48 0 0 0 274.41 0H173.59a48 48 0 0 0-41.16 23.3L98.41 80H16A16 16 0 0 0 0 96v16a16 16 0 0 0 16 16h16v336a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128h16a16 16 0 0 0 16-16V96a16 16 0 0 0-16-16zM171.84 50.91A6 6 0 0 1 177 48h94a6 6 0 0 1 5.15 2.91L293.61 80H154.39zM368 464H80V128h288zm-212-48h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12z\"],\n    \"user\": [448, 512, [], \"f007\", \"M313.6 304c-28.7 0-42.5 16-89.6 16-47.1 0-60.8-16-89.6-16C60.2 304 0 364.2 0 438.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-25.6c0-74.2-60.2-134.4-134.4-134.4zM400 464H48v-25.6c0-47.6 38.8-86.4 86.4-86.4 14.6 0 38.3 16 89.6 16 51.7 0 74.9-16 89.6-16 47.6 0 86.4 38.8 86.4 86.4V464zM224 288c79.5 0 144-64.5 144-144S303.5 0 224 0 80 64.5 80 144s64.5 144 144 144zm0-240c52.9 0 96 43.1 96 96s-43.1 96-96 96-96-43.1-96-96 43.1-96 96-96z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 104c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96zm0 144c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-240C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-49.7 0-95.1-18.3-130.1-48.4 14.9-23 40.4-38.6 69.6-39.5 20.8 6.4 40.6 9.6 60.5 9.6s39.7-3.1 60.5-9.6c29.2 1 54.7 16.5 69.6 39.5-35 30.1-80.4 48.4-130.1 48.4zm162.7-84.1c-24.4-31.4-62.1-51.9-105.1-51.9-10.2 0-26 9.6-57.6 9.6-31.5 0-47.4-9.6-57.6-9.6-42.9 0-80.6 20.5-105.1 51.9C61.9 339.2 48 299.2 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 43.2-13.9 83.2-37.3 115.9z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v340zM356.5 194.6L295.1 256l61.4 61.4c4.6 4.6 4.6 12.1 0 16.8l-22.3 22.3c-4.6 4.6-12.1 4.6-16.8 0L256 295.1l-61.4 61.4c-4.6 4.6-12.1 4.6-16.8 0l-22.3-22.3c-4.6-4.6-4.6-12.1 0-16.8l61.4-61.4-61.4-61.4c-4.6-4.6-4.6-12.1 0-16.8l22.3-22.3c4.6-4.6 12.1-4.6 16.8 0l61.4 61.4 61.4-61.4c4.6-4.6 12.1-4.6 16.8 0l22.3 22.3c4.7 4.6 4.7 12.1 0 16.8z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V192h416v234z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M480 480H32c-17.7 0-32-14.3-32-32s14.3-32 32-32h448c17.7 0 32 14.3 32 32s-14.3 32-32 32z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M464 0H144c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v320c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h48c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-96 464H48V256h320v208zm96-96h-48V144c0-26.5-21.5-48-48-48H144V48h320v320z\"]\n  };\n\n  bunker(function () {\n    defineIcons('far', icons);\n  });\n\n}());\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/solid.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"ad\": [512, 512, [], \"f641\", \"M157.52 272h36.96L176 218.78 157.52 272zM352 256c-13.23 0-24 10.77-24 24s10.77 24 24 24 24-10.77 24-24-10.77-24-24-24zM464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM250.58 352h-16.94c-6.81 0-12.88-4.32-15.12-10.75L211.15 320h-70.29l-7.38 21.25A16 16 0 0 1 118.36 352h-16.94c-11.01 0-18.73-10.85-15.12-21.25L140 176.12A23.995 23.995 0 0 1 162.67 160h26.66A23.99 23.99 0 0 1 212 176.13l53.69 154.62c3.61 10.4-4.11 21.25-15.11 21.25zM424 336c0 8.84-7.16 16-16 16h-16c-4.85 0-9.04-2.27-11.98-5.68-8.62 3.66-18.09 5.68-28.02 5.68-39.7 0-72-32.3-72-72s32.3-72 72-72c8.46 0 16.46 1.73 24 4.42V176c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v160z\"],\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-228-32c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H118.4C106 384 96 375.4 96 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-352 96c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H86.4C74 384 64 375.4 64 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2zM512 312c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"adjust\": [512, 512, [], \"f042\", \"M8 256c0 136.966 111.033 248 248 248s248-111.034 248-248S392.966 8 256 8 8 119.033 8 256zm248 184V72c101.705 0 184 82.311 184 184 0 101.705-82.311 184-184 184z\"],\n    \"air-freshener\": [384, 512, [], \"f5d0\", \"M378.94 321.41L284.7 224h49.22c15.3 0 23.66-16.6 13.86-27.53L234.45 69.96c3.43-6.61 5.55-14 5.55-21.96 0-26.51-21.49-48-48-48s-48 21.49-48 48c0 7.96 2.12 15.35 5.55 21.96L36.22 196.47C26.42 207.4 34.78 224 50.08 224H99.3L5.06 321.41C-6.69 333.56 3.34 352 21.7 352H160v32H48c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h288c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16H224v-32h138.3c18.36 0 28.39-18.44 16.64-30.59zM192 31.98c8.85 0 16.02 7.17 16.02 16.02 0 8.84-7.17 16.02-16.02 16.02S175.98 56.84 175.98 48c0-8.85 7.17-16.02 16.02-16.02zM304 432v32H80v-32h224z\"],\n    \"align-center\": [448, 512, [], \"f037\", \"M432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM108.1 96h231.81A12.09 12.09 0 0 0 352 83.9V44.09A12.09 12.09 0 0 0 339.91 32H108.1A12.09 12.09 0 0 0 96 44.09V83.9A12.1 12.1 0 0 0 108.1 96zm231.81 256A12.09 12.09 0 0 0 352 339.9v-39.81A12.09 12.09 0 0 0 339.91 288H108.1A12.09 12.09 0 0 0 96 300.09v39.81a12.1 12.1 0 0 0 12.1 12.1z\"],\n    \"align-justify\": [448, 512, [], \"f039\", \"M432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"align-left\": [448, 512, [], \"f036\", \"M12.83 352h262.34A12.82 12.82 0 0 0 288 339.17v-38.34A12.82 12.82 0 0 0 275.17 288H12.83A12.82 12.82 0 0 0 0 300.83v38.34A12.82 12.82 0 0 0 12.83 352zm0-256h262.34A12.82 12.82 0 0 0 288 83.17V44.83A12.82 12.82 0 0 0 275.17 32H12.83A12.82 12.82 0 0 0 0 44.83v38.34A12.82 12.82 0 0 0 12.83 96zM432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"align-right\": [448, 512, [], \"f038\", \"M16 224h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm416 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-384H172.83A12.82 12.82 0 0 0 160 44.83v38.34A12.82 12.82 0 0 0 172.83 96h262.34A12.82 12.82 0 0 0 448 83.17V44.83A12.82 12.82 0 0 0 435.17 32zm0 256H172.83A12.82 12.82 0 0 0 160 300.83v38.34A12.82 12.82 0 0 0 172.83 352h262.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288z\"],\n    \"allergies\": [448, 512, [], \"f461\", \"M416 112c-17.6 0-32 14.4-32 32v72c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32s-32 14.4-32 32v152c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V32c0-17.6-14.4-32-32-32s-32 14.4-32 32v184c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32S96 46.4 96 64v241l-23.6-32.5c-13-17.9-38-21.8-55.9-8.8s-21.8 38-8.8 55.9l125.6 172.7c9 12.4 23.5 19.8 38.8 19.8h197.6c22.3 0 41.6-15.3 46.7-37l26.5-112.7c3.2-13.7 4.9-28.3 5.1-42.3V144c0-17.6-14.4-32-32-32zM176 416c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 32c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32-128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"ambulance\": [640, 512, [], \"f0f9\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm144-248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm176 248c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"american-sign-language-interpreting\": [640, 512, [], \"f2a3\", \"M290.547 189.039c-20.295-10.149-44.147-11.199-64.739-3.89 42.606 0 71.208 20.475 85.578 50.576 8.576 17.899-5.148 38.071-23.617 38.071 18.429 0 32.211 20.136 23.617 38.071-14.725 30.846-46.123 50.854-80.298 50.854-.557 0-94.471-8.615-94.471-8.615l-66.406 33.347c-9.384 4.693-19.815.379-23.895-7.781L1.86 290.747c-4.167-8.615-1.111-18.897 6.946-23.621l58.072-33.069L108 159.861c6.39-57.245 34.731-109.767 79.743-146.726 11.391-9.448 28.341-7.781 37.51 3.613 9.446 11.394 7.78 28.067-3.612 37.516-12.503 10.559-23.618 22.509-32.509 35.57 21.672-14.729 46.679-24.732 74.186-28.067 14.725-1.945 28.063 8.336 29.73 23.065 1.945 14.728-8.336 28.067-23.062 29.734-16.116 1.945-31.12 7.503-44.178 15.284 26.114-5.713 58.712-3.138 88.079 11.115 13.336 6.669 18.893 22.509 12.224 35.848-6.389 13.06-22.504 18.617-35.564 12.226zm-27.229 69.472c-6.112-12.505-18.338-20.286-32.231-20.286a35.46 35.46 0 0 0-35.565 35.57c0 21.428 17.808 35.57 35.565 35.57 13.893 0 26.119-7.781 32.231-20.286 4.446-9.449 13.614-15.006 23.339-15.284-9.725-.277-18.893-5.835-23.339-15.284zm374.821-37.237c4.168 8.615 1.111 18.897-6.946 23.621l-58.071 33.069L532 352.16c-6.39 57.245-34.731 109.767-79.743 146.726-10.932 9.112-27.799 8.144-37.51-3.613-9.446-11.394-7.78-28.067 3.613-37.516 12.503-10.559 23.617-22.509 32.508-35.57-21.672 14.729-46.679 24.732-74.186 28.067-10.021 2.506-27.552-5.643-29.73-23.065-1.945-14.728 8.336-28.067 23.062-29.734 16.116-1.946 31.12-7.503 44.178-15.284-26.114 5.713-58.712 3.138-88.079-11.115-13.336-6.669-18.893-22.509-12.224-35.848 6.389-13.061 22.505-18.619 35.565-12.227 20.295 10.149 44.147 11.199 64.739 3.89-42.606 0-71.208-20.475-85.578-50.576-8.576-17.899 5.148-38.071 23.617-38.071-18.429 0-32.211-20.136-23.617-38.071 14.033-29.396 44.039-50.887 81.966-50.854l92.803 8.615 66.406-33.347c9.408-4.704 19.828-.354 23.894 7.781l44.455 88.926zm-229.227-18.618c-13.893 0-26.119 7.781-32.231 20.286-4.446 9.449-13.614 15.006-23.339 15.284 9.725.278 18.893 5.836 23.339 15.284 6.112 12.505 18.338 20.286 32.231 20.286a35.46 35.46 0 0 0 35.565-35.57c0-21.429-17.808-35.57-35.565-35.57z\"],\n    \"anchor\": [576, 512, [], \"f13d\", \"M12.971 352h32.394C67.172 454.735 181.944 512 288 512c106.229 0 220.853-57.38 242.635-160h32.394c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0l-67.029 67.029c-7.56 7.56-2.206 20.485 8.485 20.485h35.146c-20.29 54.317-84.963 86.588-144.117 94.015V256h52c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-52v-5.47c37.281-13.178 63.995-48.725 64-90.518C384.005 43.772 341.605.738 289.37.01 235.723-.739 192 42.525 192 96c0 41.798 26.716 77.35 64 90.53V192h-52c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v190.015c-58.936-7.399-123.82-39.679-144.117-94.015h35.146c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0L4.485 331.515C-3.074 339.074 2.28 352 12.971 352zM288 64c17.645 0 32 14.355 32 32s-14.355 32-32 32-32-14.355-32-32 14.355-32 32-32z\"],\n    \"angle-double-down\": [320, 512, [], \"f103\", \"M143 256.3L7 120.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0L313 86.3c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.4 9.5-24.6 9.5-34 .1zm34 192l136-136c9.4-9.4 9.4-24.6 0-33.9l-22.6-22.6c-9.4-9.4-24.6-9.4-33.9 0L160 352.1l-96.4-96.4c-9.4-9.4-24.6-9.4-33.9 0L7 278.3c-9.4 9.4-9.4 24.6 0 33.9l136 136c9.4 9.5 24.6 9.5 34 .1z\"],\n    \"angle-double-left\": [448, 512, [], \"f100\", \"M223.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L319.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L393.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34zm-192 34l136 136c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9L127.9 256l96.4-96.4c9.4-9.4 9.4-24.6 0-33.9L201.7 103c-9.4-9.4-24.6-9.4-33.9 0l-136 136c-9.5 9.4-9.5 24.6-.1 34z\"],\n    \"angle-double-right\": [448, 512, [], \"f101\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34zm192-34l-136-136c-9.4-9.4-24.6-9.4-33.9 0l-22.6 22.6c-9.4 9.4-9.4 24.6 0 33.9l96.4 96.4-96.4 96.4c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l136-136c9.4-9.2 9.4-24.4 0-33.8z\"],\n    \"angle-double-up\": [320, 512, [], \"f102\", \"M177 255.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 351.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 425.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1zm-34-192L7 199.7c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l96.4-96.4 96.4 96.4c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9l-136-136c-9.2-9.4-24.4-9.4-33.8 0z\"],\n    \"angle-down\": [320, 512, [], \"f107\", \"M143 352.3L7 216.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.2 9.4-24.4 9.4-33.8 0z\"],\n    \"angle-left\": [256, 512, [], \"f104\", \"M31.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L127.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L201.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34z\"],\n    \"angle-right\": [256, 512, [], \"f105\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34z\"],\n    \"angle-up\": [320, 512, [], \"f106\", \"M177 159.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 255.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 329.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 240c0-9.3 4.1-17.5 10.5-23.4l-31-9.3c-8.5-2.5-13.3-11.5-10.7-19.9 2.5-8.5 11.4-13.2 19.9-10.7l80 24c8.5 2.5 13.3 11.5 10.7 19.9-2.1 6.9-8.4 11.4-15.3 11.4-.5 0-1.1-.2-1.7-.2.7 2.7 1.7 5.3 1.7 8.2 0 17.7-14.3 32-32 32S136 257.7 136 240zm168 154.2c-27.8-33.4-84.2-33.4-112.1 0-13.5 16.3-38.2-4.2-24.6-20.5 20-24 49.4-37.8 80.6-37.8s60.6 13.8 80.6 37.8c13.8 16.5-11.1 36.6-24.5 20.5zm76.6-186.9l-31 9.3c6.3 5.8 10.5 14.1 10.5 23.4 0 17.7-14.3 32-32 32s-32-14.3-32-32c0-2.9.9-5.6 1.7-8.2-.6.1-1.1.2-1.7.2-6.9 0-13.2-4.5-15.3-11.4-2.5-8.5 2.3-17.4 10.7-19.9l80-24c8.4-2.5 17.4 2.3 19.9 10.7 2.5 8.5-2.3 17.4-10.8 19.9z\"],\n    \"ankh\": [320, 512, [], \"f644\", \"M296 256h-44.62C272.46 222.01 288 181.65 288 144 288 55.63 230.69 0 160 0S32 55.63 32 144c0 37.65 15.54 78.01 36.62 112H24c-13.25 0-24 10.74-24 24v32c0 13.25 10.75 24 24 24h96v152c0 13.25 10.75 24 24 24h32c13.25 0 24-10.75 24-24V336h96c13.25 0 24-10.75 24-24v-32c0-13.26-10.75-24-24-24zM160 80c29.61 0 48 24.52 48 64 0 34.66-27.14 78.14-48 100.87-20.86-22.72-48-66.21-48-100.87 0-39.48 18.39-64 48-64z\"],\n    \"apple-alt\": [448, 512, [], \"f5d1\", \"M350.85 129c25.97 4.67 47.27 18.67 63.92 42 14.65 20.67 24.64 46.67 29.96 78 4.67 28.67 4.32 57.33-1 86-7.99 47.33-23.97 87-47.94 119-28.64 38.67-64.59 58-107.87 58-10.66 0-22.3-3.33-34.96-10-8.66-5.33-18.31-8-28.97-8s-20.3 2.67-28.97 8c-12.66 6.67-24.3 10-34.96 10-43.28 0-79.23-19.33-107.87-58-23.97-32-39.95-71.67-47.94-119-5.32-28.67-5.67-57.33-1-86 5.32-31.33 15.31-57.33 29.96-78 16.65-23.33 37.95-37.33 63.92-42 15.98-2.67 37.95-.33 65.92 7 23.97 6.67 44.28 14.67 60.93 24 16.65-9.33 36.96-17.33 60.93-24 27.98-7.33 49.96-9.67 65.94-7zm-54.94-41c-9.32 8.67-21.65 15-36.96 19-10.66 3.33-22.3 5-34.96 5l-14.98-1c-1.33-9.33-1.33-20 0-32 2.67-24 10.32-42.33 22.97-55 9.32-8.67 21.65-15 36.96-19 10.66-3.33 22.3-5 34.96-5l14.98 1 1 15c0 12.67-1.67 24.33-4.99 35-3.99 15.33-10.31 27.67-18.98 37z\"],\n    \"archive\": [512, 512, [], \"f187\", \"M32 448c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V160H32v288zm160-212c0-6.6 5.4-12 12-12h104c6.6 0 12 5.4 12 12v8c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-8zM480 32H32C14.3 32 0 46.3 0 64v48c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16V64c0-17.7-14.3-32-32-32z\"],\n    \"archway\": [576, 512, [], \"f557\", \"M560 448h-16V96H32v352H16.02c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16H176c8.84 0 16-7.16 16-16V320c0-53.02 42.98-96 96-96s96 42.98 96 96l.02 160v16c0 8.84 7.16 16 16 16H560c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm0-448H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h544c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM212 140v116h-70.9c-10.7 0-16.1 13-8.5 20.5l114.9 114.3c4.7 4.7 12.2 4.7 16.9 0l114.9-114.3c7.6-7.6 2.2-20.5-8.5-20.5H300V140c0-6.6-5.4-12-12-12h-64c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm116-292H256v-70.9c0-10.7-13-16.1-20.5-8.5L121.2 247.5c-4.7 4.7-4.7 12.2 0 16.9l114.3 114.9c7.6 7.6 20.5 2.2 20.5-8.5V300h116c6.6 0 12-5.4 12-12v-64c0-6.6-5.4-12-12-12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zM140 300h116v70.9c0 10.7 13 16.1 20.5 8.5l114.3-114.9c4.7-4.7 4.7-12.2 0-16.9l-114.3-115c-7.6-7.6-20.5-2.2-20.5 8.5V212H140c-6.6 0-12 5.4-12 12v64c0 6.6 5.4 12 12 12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm292 116V256h70.9c10.7 0 16.1-13 8.5-20.5L264.5 121.2c-4.7-4.7-12.2-4.7-16.9 0l-115 114.3c-7.6 7.6-2.2 20.5 8.5 20.5H212v116c0 6.6 5.4 12 12 12h64c6.6 0 12-5.4 12-12z\"],\n    \"arrow-circle-down\": [512, 512, [], \"f0ab\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-143.6-28.9L288 302.6V120c0-13.3-10.7-24-24-24h-16c-13.3 0-24 10.7-24 24v182.6l-72.4-75.5c-9.3-9.7-24.8-9.9-34.3-.4l-10.9 11c-9.4 9.4-9.4 24.6 0 33.9L239 404.3c9.4 9.4 24.6 9.4 33.9 0l132.7-132.7c9.4-9.4 9.4-24.6 0-33.9l-10.9-11c-9.5-9.5-25-9.3-34.3.4z\"],\n    \"arrow-circle-left\": [512, 512, [], \"f0a8\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm28.9-143.6L209.4 288H392c13.3 0 24-10.7 24-24v-16c0-13.3-10.7-24-24-24H209.4l75.5-72.4c9.7-9.3 9.9-24.8.4-34.3l-11-10.9c-9.4-9.4-24.6-9.4-33.9 0L107.7 239c-9.4 9.4-9.4 24.6 0 33.9l132.7 132.7c9.4 9.4 24.6 9.4 33.9 0l11-10.9c9.5-9.5 9.3-25-.4-34.3z\"],\n    \"arrow-circle-right\": [512, 512, [], \"f0a9\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm-28.9 143.6l75.5 72.4H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h182.6l-75.5 72.4c-9.7 9.3-9.9 24.8-.4 34.3l11 10.9c9.4 9.4 24.6 9.4 33.9 0L404.3 273c9.4-9.4 9.4-24.6 0-33.9L271.6 106.3c-9.4-9.4-24.6-9.4-33.9 0l-11 10.9c-9.5 9.6-9.3 25.1.4 34.4z\"],\n    \"arrow-circle-up\": [512, 512, [], \"f0aa\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm143.6 28.9l72.4-75.5V392c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24V209.4l72.4 75.5c9.3 9.7 24.8 9.9 34.3.4l10.9-11c9.4-9.4 9.4-24.6 0-33.9L273 107.7c-9.4-9.4-24.6-9.4-33.9 0L106.3 240.4c-9.4 9.4-9.4 24.6 0 33.9l10.9 11c9.6 9.5 25.1 9.3 34.4-.4z\"],\n    \"arrow-down\": [448, 512, [], \"f063\", \"M413.1 222.5l22.2 22.2c9.4 9.4 9.4 24.6 0 33.9L241 473c-9.4 9.4-24.6 9.4-33.9 0L12.7 278.6c-9.4-9.4-9.4-24.6 0-33.9l22.2-22.2c9.5-9.5 25-9.3 34.3.4L184 343.4V56c0-13.3 10.7-24 24-24h32c13.3 0 24 10.7 24 24v287.4l114.8-120.5c9.3-9.8 24.8-10 34.3-.4z\"],\n    \"arrow-left\": [448, 512, [], \"f060\", \"M257.5 445.1l-22.2 22.2c-9.4 9.4-24.6 9.4-33.9 0L7 273c-9.4-9.4-9.4-24.6 0-33.9L201.4 44.7c9.4-9.4 24.6-9.4 33.9 0l22.2 22.2c9.5 9.5 9.3 25-.4 34.3L136.6 216H424c13.3 0 24 10.7 24 24v32c0 13.3-10.7 24-24 24H136.6l120.5 114.8c9.8 9.3 10 24.8.4 34.3z\"],\n    \"arrow-right\": [448, 512, [], \"f061\", \"M190.5 66.9l22.2-22.2c9.4-9.4 24.6-9.4 33.9 0L441 239c9.4 9.4 9.4 24.6 0 33.9L246.6 467.3c-9.4 9.4-24.6 9.4-33.9 0l-22.2-22.2c-9.5-9.5-9.3-25 .4-34.3L311.4 296H24c-13.3 0-24-10.7-24-24v-32c0-13.3 10.7-24 24-24h287.4L190.9 101.2c-9.8-9.3-10-24.8-.4-34.3z\"],\n    \"arrow-up\": [448, 512, [], \"f062\", \"M34.9 289.5l-22.2-22.2c-9.4-9.4-9.4-24.6 0-33.9L207 39c9.4-9.4 24.6-9.4 33.9 0l194.3 194.3c9.4 9.4 9.4 24.6 0 33.9L413 289.4c-9.5 9.5-25 9.3-34.3-.4L264 168.6V456c0 13.3-10.7 24-24 24h-32c-13.3 0-24-10.7-24-24V168.6L69.2 289.1c-9.3 9.8-24.8 10-34.3.4z\"],\n    \"arrows-alt\": [512, 512, [], \"f0b2\", \"M352.201 425.775l-79.196 79.196c-9.373 9.373-24.568 9.373-33.941 0l-79.196-79.196c-15.119-15.119-4.411-40.971 16.971-40.97h51.162L228 284H127.196v51.162c0 21.382-25.851 32.09-40.971 16.971L7.029 272.937c-9.373-9.373-9.373-24.569 0-33.941L86.225 159.8c15.119-15.119 40.971-4.411 40.971 16.971V228H228V127.196h-51.23c-21.382 0-32.09-25.851-16.971-40.971l79.196-79.196c9.373-9.373 24.568-9.373 33.941 0l79.196 79.196c15.119 15.119 4.411 40.971-16.971 40.971h-51.162V228h100.804v-51.162c0-21.382 25.851-32.09 40.97-16.971l79.196 79.196c9.373 9.373 9.373 24.569 0 33.941L425.773 352.2c-15.119 15.119-40.971 4.411-40.97-16.971V284H284v100.804h51.23c21.382 0 32.09 25.851 16.971 40.971z\"],\n    \"arrows-alt-h\": [512, 512, [], \"f337\", \"M377.941 169.941V216H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.568 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296h243.882v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.568 0-33.941l-86.059-86.059c-15.119-15.12-40.971-4.412-40.971 16.97z\"],\n    \"arrows-alt-v\": [256, 512, [], \"f338\", \"M214.059 377.941H168V134.059h46.059c21.382 0 32.09-25.851 16.971-40.971L144.971 7.029c-9.373-9.373-24.568-9.373-33.941 0L24.971 93.088c-15.119 15.119-4.411 40.971 16.971 40.971H88v243.882H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.568 9.373 33.941 0l86.059-86.059c15.12-15.119 4.412-40.971-16.97-40.971z\"],\n    \"assistive-listening-systems\": [512, 512, [], \"f2a2\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm-80 236c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zM32 448c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm480-187.993c0-1.518-.012-3.025-.045-4.531C510.076 140.525 436.157 38.47 327.994 1.511c-14.633-4.998-30.549 2.809-35.55 17.442-5 14.633 2.81 30.549 17.442 35.55 85.906 29.354 144.61 110.513 146.077 201.953l.003.188c.026 1.118.033 2.236.033 3.363 0 15.464 12.536 28 28 28s28.001-12.536 28.001-28zM152.971 439.029l-80-80L39.03 392.97l80 80 33.941-33.941z\"],\n    \"asterisk\": [512, 512, [], \"f069\", \"M478.21 334.093L336 256l142.21-78.093c11.795-6.477 15.961-21.384 9.232-33.037l-19.48-33.741c-6.728-11.653-21.72-15.499-33.227-8.523L296 186.718l3.475-162.204C299.763 11.061 288.937 0 275.48 0h-38.96c-13.456 0-24.283 11.061-23.994 24.514L216 186.718 77.265 102.607c-11.506-6.976-26.499-3.13-33.227 8.523l-19.48 33.741c-6.728 11.653-2.562 26.56 9.233 33.037L176 256 33.79 334.093c-11.795 6.477-15.961 21.384-9.232 33.037l19.48 33.741c6.728 11.653 21.721 15.499 33.227 8.523L216 325.282l-3.475 162.204C212.237 500.939 223.064 512 236.52 512h38.961c13.456 0 24.283-11.061 23.995-24.514L296 325.282l138.735 84.111c11.506 6.976 26.499 3.13 33.227-8.523l19.48-33.741c6.728-11.653 2.563-26.559-9.232-33.036z\"],\n    \"at\": [512, 512, [], \"f1fa\", \"M256 8C118.941 8 8 118.919 8 256c0 137.059 110.919 248 248 248 48.154 0 95.342-14.14 135.408-40.223 12.005-7.815 14.625-24.288 5.552-35.372l-10.177-12.433c-7.671-9.371-21.179-11.667-31.373-5.129C325.92 429.757 291.314 440 256 440c-101.458 0-184-82.542-184-184S154.542 72 256 72c100.139 0 184 57.619 184 160 0 38.786-21.093 79.742-58.17 83.693-17.349-.454-16.91-12.857-13.476-30.024l23.433-121.11C394.653 149.75 383.308 136 368.225 136h-44.981a13.518 13.518 0 0 0-13.432 11.993l-.01.092c-14.697-17.901-40.448-21.775-59.971-21.775-74.58 0-137.831 62.234-137.831 151.46 0 65.303 36.785 105.87 96 105.87 26.984 0 57.369-15.637 74.991-38.333 9.522 34.104 40.613 34.103 70.71 34.103C462.609 379.41 504 307.798 504 232 504 95.653 394.023 8 256 8zm-21.68 304.43c-22.249 0-36.07-15.623-36.07-40.771 0-44.993 30.779-72.729 58.63-72.729 22.292 0 35.601 15.241 35.601 40.77 0 45.061-33.875 72.73-58.161 72.73z\"],\n    \"atlas\": [448, 512, [], \"f558\", \"M318.38 208h-39.09c-1.49 27.03-6.54 51.35-14.21 70.41 27.71-13.24 48.02-39.19 53.3-70.41zm0-32c-5.29-31.22-25.59-57.17-53.3-70.41 7.68 19.06 12.72 43.38 14.21 70.41h39.09zM224 97.31c-7.69 7.45-20.77 34.42-23.43 78.69h46.87c-2.67-44.26-15.75-71.24-23.44-78.69zm-41.08 8.28c-27.71 13.24-48.02 39.19-53.3 70.41h39.09c1.49-27.03 6.53-51.35 14.21-70.41zm0 172.82c-7.68-19.06-12.72-43.38-14.21-70.41h-39.09c5.28 31.22 25.59 57.17 53.3 70.41zM247.43 208h-46.87c2.66 44.26 15.74 71.24 23.43 78.69 7.7-7.45 20.78-34.43 23.44-78.69zM448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM224 64c70.69 0 128 57.31 128 128s-57.31 128-128 128S96 262.69 96 192 153.31 64 224 64zm160 384H96c-19.2 0-32-12.8-32-32s16-32 32-32h288v64z\"],\n    \"atom\": [448, 512, [], \"f5d2\", \"M413.03 256c40.13-54.89 41.51-98.62 25.14-128-10.91-19.52-40.54-50.73-116.33-41.88C300.36 34.89 267.64 0 224 0s-76.36 34.89-97.84 86.12C50.43 77.34 20.73 108.48 9.83 128c-16.38 29.4-15 73.09 25.14 128-40.13 54.89-41.51 98.62-25.14 128 29.21 52.34 101.68 43.58 116.33 41.88C147.63 477.1 180.36 512 224 512s76.37-34.9 97.84-86.12c14.64 1.7 87.11 10.46 116.33-41.88 16.38-29.4 15-73.09-25.14-128zM63.38 352c-4.03-7.21-.19-24.8 14.95-48.29 6.96 6.53 14.2 12.89 21.87 19.18 1.71 13.71 4 27.08 6.76 40.08-24.56.89-39.89-4.37-43.58-10.97zm36.82-162.88c-7.66 6.29-14.9 12.65-21.87 19.18-15.13-23.5-18.97-41.09-14.95-48.3 3.41-6.14 16.39-11.47 37.92-11.47 1.71 0 3.87.3 5.69.37a472.191 472.191 0 0 0-6.79 40.22zM224 64c9.47 0 22.2 13.52 33.86 37.26-11.19 3.7-22.44 8-33.86 12.86-11.42-4.86-22.67-9.16-33.86-12.86C201.8 77.52 214.53 64 224 64zm0 384c-9.47 0-22.2-13.52-33.86-37.26 11.19-3.7 22.44-8 33.86-12.86 11.42 4.86 22.67 9.16 33.86 12.86C246.2 434.48 233.47 448 224 448zm62.5-157.33c-26.7 19.08-46.14 29.33-62.5 37.48-16.35-8.14-35.8-18.41-62.5-37.48-1.99-27.79-1.99-41.54 0-69.33 26.67-19.05 46.13-29.32 62.5-37.48 16.39 8.17 35.86 18.44 62.5 37.48 1.98 27.78 1.99 41.53 0 69.33zM384.62 352c-3.67 6.62-19 11.82-43.58 10.95 2.76-13 5.05-26.37 6.76-40.06 7.66-6.29 14.9-12.65 21.87-19.18 15.13 23.49 18.97 41.08 14.95 48.29zm-14.95-143.71c-6.96-6.53-14.2-12.89-21.87-19.18a473.535 473.535 0 0 0-6.79-40.22c1.82-.07 3.97-.37 5.69-.37 21.52 0 34.51 5.34 37.92 11.47 4.02 7.22.18 24.81-14.95 48.3zM224 224c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"audio-description\": [512, 512, [], \"f29e\", \"M162.925 238.709l8.822 30.655h-25.606l9.041-30.652c1.277-4.421 2.651-9.994 3.872-15.245 1.22 5.251 2.594 10.823 3.871 15.242zm166.474-32.099h-14.523v98.781h14.523c29.776 0 46.175-17.678 46.175-49.776 0-32.239-17.49-49.005-46.175-49.005zM512 112v288c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48zM245.459 336.139l-57.097-168A12.001 12.001 0 0 0 177 160h-35.894a12.001 12.001 0 0 0-11.362 8.139l-57.097 168C70.003 343.922 75.789 352 84.009 352h29.133a12 12 0 0 0 11.535-8.693l8.574-29.906h51.367l8.793 29.977A12 12 0 0 0 204.926 352h29.172c8.22 0 14.006-8.078 11.361-15.861zm184.701-80.525c0-58.977-37.919-95.614-98.96-95.614h-57.366c-6.627 0-12 5.373-12 12v168c0 6.627 5.373 12 12 12H331.2c61.041 0 98.96-36.933 98.96-96.386z\"],\n    \"award\": [384, 512, [], \"f559\", \"M97.12 362.63c-8.69-8.69-4.16-6.24-25.12-11.85-9.51-2.55-17.87-7.45-25.43-13.32L1.2 448.7c-4.39 10.77 3.81 22.47 15.43 22.03l52.69-2.01L105.56 507c8 8.44 22.04 5.81 26.43-4.96l52.05-127.62c-10.84 6.04-22.87 9.58-35.31 9.58-19.5 0-37.82-7.59-51.61-21.37zM382.8 448.7l-45.37-111.24c-7.56 5.88-15.92 10.77-25.43 13.32-21.07 5.64-16.45 3.18-25.12 11.85-13.79 13.78-32.12 21.37-51.62 21.37-12.44 0-24.47-3.55-35.31-9.58L252 502.04c4.39 10.77 18.44 13.4 26.43 4.96l36.25-38.28 52.69 2.01c11.62.44 19.82-11.27 15.43-22.03zM263 340c15.28-15.55 17.03-14.21 38.79-20.14 13.89-3.79 24.75-14.84 28.47-28.98 7.48-28.4 5.54-24.97 25.95-45.75 10.17-10.35 14.14-25.44 10.42-39.58-7.47-28.38-7.48-24.42 0-52.83 3.72-14.14-.25-29.23-10.42-39.58-20.41-20.78-18.47-17.36-25.95-45.75-3.72-14.14-14.58-25.19-28.47-28.98-27.88-7.61-24.52-5.62-44.95-26.41-10.17-10.35-25-14.4-38.89-10.61-27.87 7.6-23.98 7.61-51.9 0-13.89-3.79-28.72.25-38.89 10.61-20.41 20.78-17.05 18.8-44.94 26.41-13.89 3.79-24.75 14.84-28.47 28.98-7.47 28.39-5.54 24.97-25.95 45.75-10.17 10.35-14.15 25.44-10.42 39.58 7.47 28.36 7.48 24.4 0 52.82-3.72 14.14.25 29.23 10.42 39.59 20.41 20.78 18.47 17.35 25.95 45.75 3.72 14.14 14.58 25.19 28.47 28.98C104.6 325.96 106.27 325 121 340c13.23 13.47 33.84 15.88 49.74 5.82a39.676 39.676 0 0 1 42.53 0c15.89 10.06 36.5 7.65 49.73-5.82zM97.66 175.96c0-53.03 42.24-96.02 94.34-96.02s94.34 42.99 94.34 96.02-42.24 96.02-94.34 96.02-94.34-42.99-94.34-96.02z\"],\n    \"baby\": [384, 512, [], \"f77c\", \"M192 160c44.2 0 80-35.8 80-80S236.2 0 192 0s-80 35.8-80 80 35.8 80 80 80zm-53.4 248.8l25.6-32-61.5-51.2L56.8 383c-11.4 14.2-11.7 34.4-.8 49l48 64c7.9 10.5 19.9 16 32 16 8.3 0 16.8-2.6 24-8 17.7-13.2 21.2-38.3 8-56l-29.4-39.2zm142.7-83.2l-61.5 51.2 25.6 32L216 448c-13.2 17.7-9.7 42.8 8 56 7.2 5.4 15.6 8 24 8 12.2 0 24.2-5.5 32-16l48-64c10.9-14.6 10.6-34.8-.8-49l-45.9-57.4zM376.7 145c-12.7-18.1-37.6-22.4-55.7-9.8l-40.6 28.5c-52.7 37-124.2 37-176.8 0L63 135.3C44.9 122.6 20 127 7.3 145-5.4 163.1-1 188 17 200.7l40.6 28.5c17 11.9 35.4 20.9 54.4 27.9V288h160v-30.8c19-7 37.4-16 54.4-27.9l40.6-28.5c18.1-12.8 22.4-37.7 9.7-55.8z\"],\n    \"baby-carriage\": [512, 512, [], \"f77d\", \"M144.8 17c-11.3-17.8-37.2-22.8-54-9.4C35.3 51.9 0 118 0 192h256L144.8 17zM496 96h-48c-35.3 0-64 28.7-64 64v64H0c0 50.6 23 96.4 60.3 130.7C25.7 363.6 0 394.7 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-8.9-1.8-17.2-4.4-25.2 21.6 5.9 44.6 9.2 68.4 9.2s46.9-3.3 68.4-9.2c-2.7 8-4.4 16.3-4.4 25.2 0 44.2 35.8 80 80 80s80-35.8 80-80c0-37.3-25.7-68.4-60.3-77.3C425 320.4 448 274.6 448 224v-64h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM80 464c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm320-32c0 17.6-14.4 32-32 32s-32-14.4-32-32 14.4-32 32-32 32 14.4 32 32z\"],\n    \"backspace\": [640, 512, [], \"f55a\", \"M576 64H205.26A63.97 63.97 0 0 0 160 82.75L9.37 233.37c-12.5 12.5-12.5 32.76 0 45.25L160 429.25c12 12 28.28 18.75 45.25 18.75H576c35.35 0 64-28.65 64-64V128c0-35.35-28.65-64-64-64zm-84.69 254.06c6.25 6.25 6.25 16.38 0 22.63l-22.62 22.62c-6.25 6.25-16.38 6.25-22.63 0L384 301.25l-62.06 62.06c-6.25 6.25-16.38 6.25-22.63 0l-22.62-22.62c-6.25-6.25-6.25-16.38 0-22.63L338.75 256l-62.06-62.06c-6.25-6.25-6.25-16.38 0-22.63l22.62-22.62c6.25-6.25 16.38-6.25 22.63 0L384 210.75l62.06-62.06c6.25-6.25 16.38-6.25 22.63 0l22.62 22.62c6.25 6.25 6.25 16.38 0 22.63L429.25 256l62.06 62.06z\"],\n    \"backward\": [512, 512, [], \"f04a\", \"M11.5 280.6l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2zm256 0l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2z\"],\n    \"bacon\": [576, 512, [], \"f7e5\", \"M218.92 336.39c34.89-34.89 44.2-59.7 54.05-86 10.61-28.29 21.59-57.54 61.37-97.34s69.05-50.77 97.35-61.38c23.88-9 46.64-17.68 76.79-45.37L470.81 8.91a31 31 0 0 0-40.18-2.83c-13.64 10.1-25.15 14.39-41 20.3C247 79.52 209.26 191.29 200.65 214.1c-29.75 78.83-89.55 94.68-98.72 98.09-24.86 9.26-54.73 20.38-91.07 50.36C-3 374-3.63 395 9.07 407.61l35.76 35.51C80 410.52 107 400.15 133 390.39c26.27-9.84 51.06-19.12 85.92-54zm348-232l-35.75-35.51c-35.19 32.63-62.18 43-88.25 52.79-26.26 9.85-51.06 19.16-85.95 54s-44.19 59.69-54 86C292.33 290 281.34 319.22 241.55 359s-69 50.73-97.3 61.32c-23.86 9-46.61 17.66-76.72 45.33l37.68 37.43a31 31 0 0 0 40.18 2.82c13.6-10.06 25.09-14.34 40.94-20.24 142.2-53 180-164.1 188.94-187.69C405 219.18 464.8 203.3 474 199.86c24.87-9.27 54.74-20.4 91.11-50.41 13.89-11.4 14.52-32.45 1.82-45.05z\"],\n    \"balance-scale\": [640, 512, [], \"f24e\", \"M256 336h-.02c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0C-2.06 328.75.02 320.33.02 336H0c0 44.18 57.31 80 128 80s128-35.82 128-80zM128 176l72 144H56l72-144zm511.98 160c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 320l72-144 72 144H440zm88 128H352V153.25c23.51-10.29 41.16-31.48 46.39-57.25H528c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H383.64C369.04 12.68 346.09 0 320 0s-49.04 12.68-63.64 32H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h129.61c5.23 25.76 22.87 46.96 46.39 57.25V448H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"balance-scale-left\": [640, 512, [], \"f515\", \"M528 448H352V153.25c20.42-8.94 36.1-26.22 43.38-47.47l132-44.26c8.38-2.81 12.89-11.88 10.08-20.26l-10.17-30.34C524.48 2.54 515.41-1.97 507.03.84L389.11 40.37C375.3 16.36 349.69 0 320 0c-44.18 0-80 35.82-80 80 0 3.43.59 6.71 1.01 10.03l-128.39 43.05c-8.38 2.81-12.89 11.88-10.08 20.26l10.17 30.34c2.81 8.38 11.88 12.89 20.26 10.08l142.05-47.63c4.07 2.77 8.43 5.12 12.99 7.12V496c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16v-32c-.01-8.84-7.17-16-16.01-16zm111.98-144c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 288l72-144 72 144H440zm-269.07-37.51c-17.65-35.29-68.19-35.36-85.87 0C-2.06 424.75.02 416.33.02 432H0c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-16.18 1.34-8.73-85.05-181.51zM56 416l72-144 72 144H56z\"],\n    \"balance-scale-right\": [640, 512, [], \"f516\", \"M96 464v32c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16V153.25c4.56-2 8.92-4.35 12.99-7.12l142.05 47.63c8.38 2.81 17.45-1.71 20.26-10.08l10.17-30.34c2.81-8.38-1.71-17.45-10.08-20.26l-128.4-43.05c.42-3.32 1.01-6.6 1.01-10.03 0-44.18-35.82-80-80-80-29.69 0-55.3 16.36-69.11 40.37L132.96.83c-8.38-2.81-17.45 1.71-20.26 10.08l-10.17 30.34c-2.81 8.38 1.71 17.45 10.08 20.26l132 44.26c7.28 21.25 22.96 38.54 43.38 47.47V448H112c-8.84 0-16 7.16-16 16zM0 304c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0C-1.32 295.27.02 287.82.02 304H0zm56-16l72-144 72 144H56zm328.02 144H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0-86.38 172.78-85.04 165.33-85.04 181.51zM440 416l72-144 72 144H440z\"],\n    \"ban\": [512, 512, [], \"f05e\", \"M256 8C119.034 8 8 119.033 8 256s111.034 248 248 248 248-111.034 248-248S392.967 8 256 8zm130.108 117.892c65.448 65.448 70 165.481 20.677 235.637L150.47 105.216c70.204-49.356 170.226-44.735 235.638 20.676zM125.892 386.108c-65.448-65.448-70-165.481-20.677-235.637L361.53 406.784c-70.203 49.356-170.226 44.736-235.638-20.676z\"],\n    \"band-aid\": [640, 512, [], \"f462\", \"M0 160v192c0 35.3 28.7 64 64 64h96V96H64c-35.3 0-64 28.7-64 64zm576-64h-96v320h96c35.3 0 64-28.7 64-64V160c0-35.3-28.7-64-64-64zM192 416h256V96H192v320zm176-232c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24z\"],\n    \"barcode\": [512, 512, [], \"f02a\", \"M0 448V64h18v384H0zm26.857-.273V64H36v383.727h-9.143zm27.143 0V64h8.857v383.727H54zm44.857 0V64h8.857v383.727h-8.857zm36 0V64h17.714v383.727h-17.714zm44.857 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm35.715 0V64h18v383.727h-18zm44.857 0V64h18v383.727h-18zm35.999 0V64h18.001v383.727h-18.001zm36.001 0V64h18.001v383.727h-18.001zm26.857 0V64h18v383.727h-18zm45.143 0V64h26.857v383.727h-26.857zm35.714 0V64h9.143v383.727H476zm18 .273V64h18v384h-18z\"],\n    \"bars\": [448, 512, [], \"f0c9\", \"M16 132h416c8.837 0 16-7.163 16-16V76c0-8.837-7.163-16-16-16H16C7.163 60 0 67.163 0 76v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16z\"],\n    \"baseball-ball\": [496, 512, [], \"f433\", \"M368.5 363.9l28.8-13.9c11.1 22.9 26 43.2 44.1 60.9 34-42.5 54.5-96.3 54.5-154.9 0-58.5-20.4-112.2-54.2-154.6-17.8 17.3-32.6 37.1-43.6 59.5l-28.7-14.1c12.8-26 30-49 50.8-69C375.6 34.7 315 8 248 8 181.1 8 120.5 34.6 75.9 77.7c20.7 19.9 37.9 42.9 50.7 68.8l-28.7 14.1c-11-22.3-25.7-42.1-43.5-59.4C20.4 143.7 0 197.4 0 256c0 58.6 20.4 112.3 54.4 154.7 18.2-17.7 33.2-38 44.3-61l28.8 13.9c-12.9 26.7-30.3 50.3-51.5 70.7 44.5 43.1 105.1 69.7 172 69.7 66.8 0 127.3-26.5 171.9-69.5-21.1-20.4-38.5-43.9-51.4-70.6zm-228.3-32l-30.5-9.8c14.9-46.4 12.7-93.8-.6-134l30.4-10c15 45.6 18 99.9.7 153.8zm216.3-153.4l30.4 10c-13.2 40.1-15.5 87.5-.6 134l-30.5 9.8c-17.3-54-14.3-108.3.7-153.8z\"],\n    \"basketball-ball\": [496, 512, [], \"f434\", \"M212.3 10.3c-43.8 6.3-86.2 24.1-122.2 53.8l77.4 77.4c27.8-35.8 43.3-81.2 44.8-131.2zM248 222L405.9 64.1c-42.4-35-93.6-53.5-145.5-56.1-1.2 63.9-21.5 122.3-58.7 167.7L248 222zM56.1 98.1c-29.7 36-47.5 78.4-53.8 122.2 50-1.5 95.5-17 131.2-44.8L56.1 98.1zm272.2 204.2c45.3-37.1 103.7-57.4 167.7-58.7-2.6-51.9-21.1-103.1-56.1-145.5L282 256l46.3 46.3zM248 290L90.1 447.9c42.4 34.9 93.6 53.5 145.5 56.1 1.3-64 21.6-122.4 58.7-167.7L248 290zm191.9 123.9c29.7-36 47.5-78.4 53.8-122.2-50.1 1.6-95.5 17.1-131.2 44.8l77.4 77.4zM167.7 209.7C122.3 246.9 63.9 267.3 0 268.4c2.6 51.9 21.1 103.1 56.1 145.5L214 256l-46.3-46.3zm116 292c43.8-6.3 86.2-24.1 122.2-53.8l-77.4-77.4c-27.7 35.7-43.2 81.2-44.8 131.2z\"],\n    \"bath\": [512, 512, [], \"f2cd\", \"M488 256H80V112c0-17.645 14.355-32 32-32 11.351 0 21.332 5.945 27.015 14.88-16.492 25.207-14.687 59.576 6.838 83.035-4.176 4.713-4.021 11.916.491 16.428l11.314 11.314c4.686 4.686 12.284 4.686 16.971 0l95.03-95.029c4.686-4.686 4.686-12.284 0-16.971l-11.314-11.314c-4.512-4.512-11.715-4.666-16.428-.491-17.949-16.469-42.294-21.429-64.178-15.365C163.281 45.667 139.212 32 112 32c-44.112 0-80 35.888-80 80v144h-8c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h8v32c0 28.43 12.362 53.969 32 71.547V456c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-8h256v8c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-32.453c19.638-17.578 32-43.117 32-71.547v-32h8c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"battery-empty\": [640, 512, [], \"f244\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48z\"],\n    \"battery-full\": [640, 512, [], \"f240\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-48 96H96v128h416V192z\"],\n    \"battery-half\": [640, 512, [], \"f242\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-240 96H96v128h224V192z\"],\n    \"battery-quarter\": [640, 512, [], \"f243\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-336 96H96v128h128V192z\"],\n    \"battery-three-quarters\": [640, 512, [], \"f241\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-144 96H96v128h320V192z\"],\n    \"bed\": [640, 512, [], \"f236\", \"M176 256c44.11 0 80-35.89 80-80s-35.89-80-80-80-80 35.89-80 80 35.89 80 80 80zm352-128H304c-8.84 0-16 7.16-16 16v144H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v352c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h512v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V240c0-61.86-50.14-112-112-112z\"],\n    \"beer\": [448, 512, [], \"f0fc\", \"M368 96h-48V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24v-42.11l80.606-35.977C429.396 365.063 448 336.388 448 304.86V176c0-44.112-35.888-80-80-80zm16 208.86a16.018 16.018 0 0 1-9.479 14.611L320 343.805V160h48c8.822 0 16 7.178 16 16v128.86zM208 384c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16zm-96 0c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64zm215.39-149.71c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.82 458.1l-90.62-70.05c.19-1.38.8-2.66.8-4.06.05-7.55-2.61-15.27-8.61-21.71-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-40.33 8.38-74.66 31.07-97.59 62.57L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.35 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.42-6.97 4.17-17.02-2.81-22.45zM157.23 251.54c-8.61 67.96-36.41 93.33-52.62 110.75-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h241.92L157.23 251.54zM320 512c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bezier-curve\": [640, 512, [], \"f55b\", \"M368 32h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM208 88h-84.75C113.75 64.56 90.84 48 64 48 28.66 48 0 76.65 0 112s28.66 64 64 64c26.84 0 49.75-16.56 59.25-40h79.73c-55.37 32.52-95.86 87.32-109.54 152h49.4c11.3-41.61 36.77-77.21 71.04-101.56-3.7-8.08-5.88-16.99-5.88-26.44V88zm-48 232H64c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zM576 48c-26.84 0-49.75 16.56-59.25 40H432v72c0 9.45-2.19 18.36-5.88 26.44 34.27 24.35 59.74 59.95 71.04 101.56h49.4c-13.68-64.68-54.17-119.48-109.54-152h79.73c9.5 23.44 32.41 40 59.25 40 35.34 0 64-28.65 64-64s-28.66-64-64-64zm0 272h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"bible\": [448, 512, [], \"f647\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM144 144c0-8.84 7.16-16 16-16h48V80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v48h48c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-48v112c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V192h-48c-8.84 0-16-7.16-16-16v-32zm236.8 304H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"bicycle\": [640, 512, [], \"f206\", \"M512.509 192.001c-16.373-.064-32.03 2.955-46.436 8.495l-77.68-125.153A24 24 0 0 0 368.001 64h-64c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h50.649l14.896 24H256.002v-16c0-8.837-7.163-16-16-16h-87.459c-13.441 0-24.777 10.999-24.536 24.437.232 13.044 10.876 23.563 23.995 23.563h48.726l-29.417 47.52c-13.433-4.83-27.904-7.483-42.992-7.52C58.094 191.83.412 249.012.002 319.236-.413 390.279 57.055 448 128.002 448c59.642 0 109.758-40.793 123.967-96h52.033a24 24 0 0 0 20.406-11.367L410.37 201.77l14.938 24.067c-25.455 23.448-41.385 57.081-41.307 94.437.145 68.833 57.899 127.051 126.729 127.719 70.606.685 128.181-55.803 129.255-125.996 1.086-70.941-56.526-129.72-127.476-129.996zM186.75 265.772c9.727 10.529 16.673 23.661 19.642 38.228h-43.306l23.664-38.228zM128.002 400c-44.112 0-80-35.888-80-80s35.888-80 80-80c5.869 0 11.586.653 17.099 1.859l-45.505 73.509C89.715 331.327 101.213 352 120.002 352h81.3c-12.37 28.225-40.562 48-73.3 48zm162.63-96h-35.624c-3.96-31.756-19.556-59.894-42.383-80.026L237.371 184h127.547l-74.286 120zm217.057 95.886c-41.036-2.165-74.049-35.692-75.627-76.755-.812-21.121 6.633-40.518 19.335-55.263l44.433 71.586c4.66 7.508 14.524 9.816 22.032 5.156l13.594-8.437c7.508-4.66 9.817-14.524 5.156-22.032l-44.468-71.643a79.901 79.901 0 0 1 19.858-2.497c44.112 0 80 35.888 80 80-.001 45.54-38.252 82.316-84.313 79.885z\"],\n    \"biking\": [640, 512, [], \"f84a\", \"M400 96a48 48 0 1 0-48-48 48 48 0 0 0 48 48zm-4 121a31.9 31.9 0 0 0 20 7h64a32 32 0 0 0 0-64h-52.78L356 103a31.94 31.94 0 0 0-40.81.68l-112 96a32 32 0 0 0 3.08 50.92L288 305.12V416a32 32 0 0 0 64 0V288a32 32 0 0 0-14.25-26.62l-41.36-27.57 58.25-49.92zm116 39a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64zM128 256a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64z\"],\n    \"binoculars\": [512, 512, [], \"f1e5\", \"M416 48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v48h96V48zM63.91 159.99C61.4 253.84 3.46 274.22 0 404v44c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V288h32V128H95.84c-17.63 0-31.45 14.37-31.93 31.99zm384.18 0c-.48-17.62-14.3-31.99-31.93-31.99H320v160h32v160c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-44c-3.46-129.78-61.4-150.16-63.91-244.01zM176 32h-64c-8.84 0-16 7.16-16 16v48h96V48c0-8.84-7.16-16-16-16zm48 256h64V128h-64v160z\"],\n    \"biohazard\": [576, 512, [], \"f780\", \"M287.9 112c18.6 0 36.2 3.8 52.8 9.6 13.3-10.3 23.6-24.3 29.5-40.7-25.2-10.9-53-17-82.2-17-29.1 0-56.9 6-82.1 16.9 5.9 16.4 16.2 30.4 29.5 40.7 16.5-5.7 34-9.5 52.5-9.5zM163.6 438.7c12-11.8 20.4-26.4 24.5-42.4-32.9-26.4-54.8-65.3-58.9-109.6-8.5-2.8-17.2-4.6-26.4-4.6-7.6 0-15.2 1-22.5 3.1 4.1 62.8 35.8 118 83.3 153.5zm224.2-42.6c4.1 16 12.5 30.7 24.5 42.5 47.4-35.5 79.1-90.7 83-153.5-7.2-2-14.7-3-22.2-3-9.2 0-18 1.9-26.6 4.7-4.1 44.2-26 82.9-58.7 109.3zm113.5-205c-17.6-10.4-36.3-16.6-55.3-19.9 6-17.7 10-36.4 10-56.2 0-41-14.5-80.8-41-112.2-2.5-3-6.6-3.7-10-1.8-3.3 1.9-4.8 6-3.6 9.7 4.5 13.8 6.6 26.3 6.6 38.5 0 67.8-53.8 122.9-120 122.9S168 117 168 49.2c0-12.1 2.2-24.7 6.6-38.5 1.2-3.7-.3-7.8-3.6-9.7-3.4-1.9-7.5-1.2-10 1.8C134.6 34.2 120 74 120 115c0 19.8 3.9 38.5 10 56.2-18.9 3.3-37.7 9.5-55.3 19.9-34.6 20.5-61 53.3-74.3 92.4-1.3 3.7.2 7.7 3.5 9.8 3.3 2 7.5 1.3 10-1.6 9.4-10.8 19-19.1 29.2-25.1 57.3-33.9 130.8-13.7 163.9 45 33.1 58.7 13.4 134-43.9 167.9-10.2 6.1-22 10.4-35.8 13.4-3.7.8-6.4 4.2-6.4 8.1.1 4 2.7 7.3 6.5 8 39.7 7.8 80.6.8 115.2-19.7 18-10.6 32.9-24.5 45.3-40.1 12.4 15.6 27.3 29.5 45.3 40.1 34.6 20.5 75.5 27.5 115.2 19.7 3.8-.7 6.4-4 6.5-8 0-3.9-2.6-7.3-6.4-8.1-13.9-2.9-25.6-7.3-35.8-13.4-57.3-33.9-77-109.2-43.9-167.9s106.6-78.9 163.9-45c10.2 6.1 19.8 14.3 29.2 25.1 2.5 2.9 6.7 3.6 10 1.6s4.8-6.1 3.5-9.8c-13.1-39.1-39.5-72-74.1-92.4zm-213.4 129c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"birthday-cake\": [448, 512, [], \"f1fd\", \"M448 384c-28.02 0-31.26-32-74.5-32-43.43 0-46.825 32-74.75 32-27.695 0-31.454-32-74.75-32-42.842 0-47.218 32-74.5 32-28.148 0-31.202-32-74.75-32-43.547 0-46.653 32-74.75 32v-80c0-26.5 21.5-48 48-48h16V112h64v144h64V112h64v144h64V112h64v144h16c26.5 0 48 21.5 48 48v80zm0 128H0v-96c43.356 0 46.767-32 74.75-32 27.951 0 31.253 32 74.75 32 42.843 0 47.217-32 74.5-32 28.148 0 31.201 32 74.75 32 43.357 0 46.767-32 74.75-32 27.488 0 31.252 32 74.5 32v96zM96 96c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40z\"],\n    \"blender\": [512, 512, [], \"f517\", \"M416 384H160c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-128 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm40-416h166.54L512 0H48C21.49 0 0 21.49 0 48v160c0 26.51 21.49 48 48 48h103.27l8.73 96h256l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H328c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM64 192V64h69.82l11.64 128H64z\"],\n    \"blender-phone\": [576, 512, [], \"f6b6\", \"M392 64h166.54L576 0H192v352h288l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H392c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM158.8 335.01l-25.78-63.26c-2.78-6.81-9.8-10.99-17.24-10.26l-45.03 4.42c-17.28-46.94-17.65-99.78 0-147.72l45.03 4.42c7.43.73 14.46-3.46 17.24-10.26l25.78-63.26c3.02-7.39.2-15.85-6.68-20.07l-39.28-24.1C98.51-3.87 80.09-.5 68.95 11.97c-92.57 103.6-92 259.55 2.1 362.49 9.87 10.8 29.12 12.48 41.65 4.8l39.41-24.18c6.89-4.22 9.7-12.67 6.69-20.07zM480 384H192c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-144 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"blind\": [384, 512, [], \"f29d\", \"M380.15 510.837a8 8 0 0 1-10.989-2.687l-125.33-206.427a31.923 31.923 0 0 0 12.958-9.485l126.048 207.608a8 8 0 0 1-2.687 10.991zM142.803 314.338l-32.54 89.485 36.12 88.285c6.693 16.36 25.377 24.192 41.733 17.501 16.357-6.692 24.193-25.376 17.501-41.734l-62.814-153.537zM96 88c24.301 0 44-19.699 44-44S120.301 0 96 0 52 19.699 52 44s19.699 44 44 44zm154.837 169.128l-120-152c-4.733-5.995-11.75-9.108-18.837-9.112V96H80v.026c-7.146.003-14.217 3.161-18.944 9.24L0 183.766v95.694c0 13.455 11.011 24.791 24.464 24.536C37.505 303.748 48 293.1 48 280v-79.766l16-20.571v140.698L9.927 469.055c-6.04 16.609 2.528 34.969 19.138 41.009 16.602 6.039 34.968-2.524 41.009-19.138L136 309.638V202.441l-31.406-39.816a4 4 0 1 1 6.269-4.971l102.3 129.217c9.145 11.584 24.368 11.339 33.708 3.965 10.41-8.216 12.159-23.334 3.966-33.708z\"],\n    \"blog\": [512, 512, [], \"f781\", \"M172.2 226.8c-14.6-2.9-28.2 8.9-28.2 23.8V301c0 10.2 7.1 18.4 16.7 22 18.2 6.8 31.3 24.4 31.3 45 0 26.5-21.5 48-48 48s-48-21.5-48-48V120c0-13.3-10.7-24-24-24H24c-13.3 0-24 10.7-24 24v248c0 89.5 82.1 160.2 175 140.7 54.4-11.4 98.3-55.4 109.7-109.7 17.4-82.9-37-157.2-112.5-172.2zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"bold\": [384, 512, [], \"f032\", \"M333.49 238a122 122 0 0 0 27-65.21C367.87 96.49 308 32 233.42 32H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h31.87v288H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h209.32c70.8 0 134.14-51.75 141-122.4 4.74-48.45-16.39-92.06-50.83-119.6zM145.66 112h87.76a48 48 0 0 1 0 96h-87.76zm87.76 288h-87.76V288h87.76a56 56 0 0 1 0 112z\"],\n    \"bolt\": [320, 512, [], \"f0e7\", \"M296 160H180.6l42.6-129.8C227.2 15 215.7 0 200 0H56C44 0 33.8 8.9 32.2 20.8l-32 240C-1.7 275.2 9.5 288 24 288h118.7L96.6 482.5c-3.6 15.2 8 29.5 23.3 29.5 8.4 0 16.4-4.4 20.8-12l176-304c9.3-15.9-2.2-36-20.7-36z\"],\n    \"bomb\": [512, 512, [], \"f1e2\", \"M440.5 88.5l-52 52L415 167c9.4 9.4 9.4 24.6 0 33.9l-17.4 17.4c11.8 26.1 18.4 55.1 18.4 85.6 0 114.9-93.1 208-208 208S0 418.9 0 304 93.1 96 208 96c30.5 0 59.5 6.6 85.6 18.4L311 97c9.4-9.4 24.6-9.4 33.9 0l26.5 26.5 52-52 17.1 17zM500 60h-24c-6.6 0-12 5.4-12 12s5.4 12 12 12h24c6.6 0 12-5.4 12-12s-5.4-12-12-12zM440 0c-6.6 0-12 5.4-12 12v24c0 6.6 5.4 12 12 12s12-5.4 12-12V12c0-6.6-5.4-12-12-12zm33.9 55l17-17c4.7-4.7 4.7-12.3 0-17-4.7-4.7-12.3-4.7-17 0l-17 17c-4.7 4.7-4.7 12.3 0 17 4.8 4.7 12.4 4.7 17 0zm-67.8 0c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17zm67.8 34c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17zM112 272c0-35.3 28.7-64 64-64 8.8 0 16-7.2 16-16s-7.2-16-16-16c-52.9 0-96 43.1-96 96 0 8.8 7.2 16 16 16s16-7.2 16-16z\"],\n    \"bone\": [640, 512, [], \"f5d7\", \"M598.88 244.56c25.2-12.6 41.12-38.36 41.12-66.53v-7.64C640 129.3 606.7 96 565.61 96c-32.02 0-60.44 20.49-70.57 50.86-7.68 23.03-11.6 45.14-38.11 45.14H183.06c-27.38 0-31.58-25.54-38.11-45.14C134.83 116.49 106.4 96 74.39 96 33.3 96 0 129.3 0 170.39v7.64c0 28.17 15.92 53.93 41.12 66.53 9.43 4.71 9.43 18.17 0 22.88C15.92 280.04 0 305.8 0 333.97v7.64C0 382.7 33.3 416 74.38 416c32.02 0 60.44-20.49 70.57-50.86 7.68-23.03 11.6-45.14 38.11-45.14h273.87c27.38 0 31.58 25.54 38.11 45.14C505.17 395.51 533.6 416 565.61 416c41.08 0 74.38-33.3 74.38-74.39v-7.64c0-28.18-15.92-53.93-41.12-66.53-9.42-4.71-9.42-18.17.01-22.88z\"],\n    \"bong\": [448, 512, [], \"f55c\", \"M302.5 512c23.18 0 44.43-12.58 56-32.66C374.69 451.26 384 418.75 384 384c0-36.12-10.08-69.81-27.44-98.62L400 241.94l9.38 9.38c6.25 6.25 16.38 6.25 22.63 0l11.3-11.32c6.25-6.25 6.25-16.38 0-22.63l-52.69-52.69c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l9.38 9.38-39.41 39.41c-11.56-11.37-24.53-21.33-38.65-29.51V63.74l15.97-.02c8.82-.01 15.97-7.16 15.98-15.98l.04-31.72C320 7.17 312.82-.01 303.97 0L80.03.26c-8.82.01-15.97 7.16-15.98 15.98l-.04 31.73c-.01 8.85 7.17 16.02 16.02 16.01L96 63.96v153.93C38.67 251.1 0 312.97 0 384c0 34.75 9.31 67.27 25.5 95.34C37.08 499.42 58.33 512 81.5 512h221zM120.06 259.43L144 245.56V63.91l96-.11v181.76l23.94 13.87c24.81 14.37 44.12 35.73 56.56 60.57h-257c12.45-24.84 31.75-46.2 56.56-60.57z\"],\n    \"book\": [448, 512, [], \"f02d\", \"M448 360V24c0-13.3-10.7-24-24-24H96C43 0 0 43 0 96v320c0 53 43 96 96 96h328c13.3 0 24-10.7 24-24v-16c0-7.5-3.5-14.3-8.9-18.7-4.2-15.4-4.2-59.3 0-74.7 5.4-4.3 8.9-11.1 8.9-18.6zM128 134c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm0 64c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm253.4 250H96c-17.7 0-32-14.3-32-32 0-17.6 14.4-32 32-32h285.4c-1.9 17.1-1.9 46.9 0 64z\"],\n    \"book-dead\": [448, 512, [], \"f6b7\", \"M272 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm176 222.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM240 56c44.2 0 80 28.7 80 64 0 20.9-12.7 39.2-32 50.9V184c0 8.8-7.2 16-16 16h-64c-8.8 0-16-7.2-16-16v-13.1c-19.3-11.7-32-30-32-50.9 0-35.3 35.8-64 80-64zM124.8 223.3l6.3-14.7c1.7-4.1 6.4-5.9 10.5-4.2l98.3 42.1 98.4-42.1c4.1-1.7 8.8.1 10.5 4.2l6.3 14.7c1.7 4.1-.1 8.8-4.2 10.5L280.6 264l70.3 30.1c4.1 1.7 5.9 6.4 4.2 10.5l-6.3 14.7c-1.7 4.1-6.4 5.9-10.5 4.2L240 281.4l-98.3 42.2c-4.1 1.7-8.8-.1-10.5-4.2l-6.3-14.7c-1.7-4.1.1-8.8 4.2-10.5l70.4-30.1-70.5-30.3c-4.1-1.7-5.9-6.4-4.2-10.5zm256 224.7H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8zM208 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16z\"],\n    \"book-medical\": [448, 512, [], \"f7e6\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16q0-9.6-9.6-19.2c-3.2-16-3.2-60.8 0-73.6q9.6-4.8 9.6-19.2zM144 168a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8v48a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8zm236.8 280H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8z\"],\n    \"book-open\": [576, 512, [], \"f518\", \"M542.22 32.05c-54.8 3.11-163.72 14.43-230.96 55.59-4.64 2.84-7.27 7.89-7.27 13.17v363.87c0 11.55 12.63 18.85 23.28 13.49 69.18-34.82 169.23-44.32 218.7-46.92 16.89-.89 30.02-14.43 30.02-30.66V62.75c.01-17.71-15.35-31.74-33.77-30.7zM264.73 87.64C197.5 46.48 88.58 35.17 33.78 32.05 15.36 31.01 0 45.04 0 62.75V400.6c0 16.24 13.13 29.78 30.02 30.66 49.49 2.6 149.59 12.11 218.77 46.95 10.62 5.35 23.21-1.94 23.21-13.46V100.63c0-5.29-2.62-10.14-7.27-12.99z\"],\n    \"book-reader\": [512, 512, [], \"f5da\", \"M352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96 42.98 96 96 96 96-42.98 96-96zM233.59 241.1c-59.33-36.32-155.43-46.3-203.79-49.05C13.55 191.13 0 203.51 0 219.14v222.8c0 14.33 11.59 26.28 26.49 27.05 43.66 2.29 131.99 10.68 193.04 41.43 9.37 4.72 20.48-1.71 20.48-11.87V252.56c-.01-4.67-2.32-8.95-6.42-11.46zm248.61-49.05c-48.35 2.74-144.46 12.73-203.78 49.05-4.1 2.51-6.41 6.96-6.41 11.63v245.79c0 10.19 11.14 16.63 20.54 11.9 61.04-30.72 149.32-39.11 192.97-41.4 14.9-.78 26.49-12.73 26.49-27.06V219.14c-.01-15.63-13.56-28.01-29.81-27.09z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M0 512V48C0 21.49 21.49 0 48 0h288c26.51 0 48 21.49 48 48v464L192 400 0 512z\"],\n    \"border-all\": [448, 512, [], \"f84c\", \"M416 32H32A32 32 0 0 0 0 64v384a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V64a32 32 0 0 0-32-32zm-32 64v128H256V96zm-192 0v128H64V96zM64 416V288h128v128zm192 0V288h128v128z\"],\n    \"border-none\": [448, 512, [], \"f850\", \"M240 224h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-288 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM240 320h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-384h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM48 224H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"border-style\": [448, 512, [], \"f853\", \"M240 416h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm192 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H32A32 32 0 0 0 0 64v400a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V96h368a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"bowling-ball\": [496, 512, [], \"f436\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM120 192c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64-96c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm48 144c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"box\": [512, 512, [], \"f466\", \"M509.5 184.6L458.9 32.8C452.4 13.2 434.1 0 413.4 0H272v192h238.7c-.4-2.5-.4-5-1.2-7.4zM240 0H98.6c-20.7 0-39 13.2-45.5 32.8L2.5 184.6c-.8 2.4-.8 4.9-1.2 7.4H240V0zM0 224v240c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V224H0z\"],\n    \"box-open\": [640, 512, [], \"f49e\", \"M425.7 256c-16.9 0-32.8-9-41.4-23.4L320 126l-64.2 106.6c-8.7 14.5-24.6 23.5-41.5 23.5-4.5 0-9-.6-13.3-1.9L64 215v178c0 14.7 10 27.5 24.2 31l216.2 54.1c10.2 2.5 20.9 2.5 31 0L551.8 424c14.2-3.6 24.2-16.4 24.2-31V215l-137 39.1c-4.3 1.3-8.8 1.9-13.3 1.9zm212.6-112.2L586.8 41c-3.1-6.2-9.8-9.8-16.7-8.9L320 64l91.7 152.1c3.8 6.3 11.4 9.3 18.5 7.3l197.9-56.5c9.9-2.9 14.7-13.9 10.2-23.1zM53.2 41L1.7 143.8c-4.6 9.2.3 20.2 10.1 23l197.9 56.5c7.1 2 14.7-1 18.5-7.3L320 64 69.8 32.1c-6.9-.8-13.5 2.7-16.6 8.9z\"],\n    \"boxes\": [576, 512, [], \"f468\", \"M560 288h-80v96l-32-21.3-32 21.3v-96h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16zm-384-64h224c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16h-80v96l-32-21.3L256 96V0h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16zm64 64h-80v96l-32-21.3L96 384v-96H16c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16z\"],\n    \"braille\": [640, 512, [], \"f2a1\", \"M128 256c0 35.346-28.654 64-64 64S0 291.346 0 256s28.654-64 64-64 64 28.654 64 64zM64 384c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352C28.654 32 0 60.654 0 96s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm224 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-320c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"brain\": [576, 512, [], \"f5dc\", \"M208 0c-29.9 0-54.7 20.5-61.8 48.2-.8 0-1.4-.2-2.2-.2-35.3 0-64 28.7-64 64 0 4.8.6 9.5 1.7 14C52.5 138 32 166.6 32 200c0 12.6 3.2 24.3 8.3 34.9C16.3 248.7 0 274.3 0 304c0 33.3 20.4 61.9 49.4 73.9-.9 4.6-1.4 9.3-1.4 14.1 0 39.8 32.2 72 72 72 4.1 0 8.1-.5 12-1.2 9.6 28.5 36.2 49.2 68 49.2 39.8 0 72-32.2 72-72V64c0-35.3-28.7-64-64-64zm368 304c0-29.7-16.3-55.3-40.3-69.1 5.2-10.6 8.3-22.3 8.3-34.9 0-33.4-20.5-62-49.7-74 1-4.5 1.7-9.2 1.7-14 0-35.3-28.7-64-64-64-.8 0-1.5.2-2.2.2C422.7 20.5 397.9 0 368 0c-35.3 0-64 28.6-64 64v376c0 39.8 32.2 72 72 72 31.8 0 58.4-20.7 68-49.2 3.9.7 7.9 1.2 12 1.2 39.8 0 72-32.2 72-72 0-4.8-.5-9.5-1.4-14.1 29-12 49.4-40.6 49.4-73.9z\"],\n    \"bread-slice\": [576, 512, [], \"f7ec\", \"M288 0C108 0 0 93.4 0 169.14 0 199.44 24.24 224 64 224v256c0 17.67 16.12 32 36 32h376c19.88 0 36-14.33 36-32V224c39.76 0 64-24.56 64-54.86C576 93.4 468 0 288 0z\"],\n    \"briefcase\": [512, 512, [], \"f0b1\", \"M320 336c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h416c25.6 0 48-22.4 48-48V288H320v48zm144-208h-80V80c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h512v-80c0-25.6-22.4-48-48-48zm-144 0H192V96h128v32z\"],\n    \"briefcase-medical\": [512, 512, [], \"f469\", \"M464 128h-80V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V176c0-26.5-21.5-48-48-48zM192 96h128v32H192V96zm160 248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48z\"],\n    \"broadcast-tower\": [640, 512, [], \"f519\", \"M150.94 192h33.73c11.01 0 18.61-10.83 14.86-21.18-4.93-13.58-7.55-27.98-7.55-42.82s2.62-29.24 7.55-42.82C203.29 74.83 195.68 64 184.67 64h-33.73c-7.01 0-13.46 4.49-15.41 11.23C130.64 92.21 128 109.88 128 128c0 18.12 2.64 35.79 7.54 52.76 1.94 6.74 8.39 11.24 15.4 11.24zM89.92 23.34C95.56 12.72 87.97 0 75.96 0H40.63c-6.27 0-12.14 3.59-14.74 9.31C9.4 45.54 0 85.65 0 128c0 24.75 3.12 68.33 26.69 118.86 2.62 5.63 8.42 9.14 14.61 9.14h34.84c12.02 0 19.61-12.74 13.95-23.37-49.78-93.32-16.71-178.15-.17-209.29zM614.06 9.29C611.46 3.58 605.6 0 599.33 0h-35.42c-11.98 0-19.66 12.66-14.02 23.25 18.27 34.29 48.42 119.42.28 209.23-5.72 10.68 1.8 23.52 13.91 23.52h35.23c6.27 0 12.13-3.58 14.73-9.29C630.57 210.48 640 170.36 640 128s-9.42-82.48-25.94-118.71zM489.06 64h-33.73c-11.01 0-18.61 10.83-14.86 21.18 4.93 13.58 7.55 27.98 7.55 42.82s-2.62 29.24-7.55 42.82c-3.76 10.35 3.85 21.18 14.86 21.18h33.73c7.02 0 13.46-4.49 15.41-11.24 4.9-16.97 7.53-34.64 7.53-52.76 0-18.12-2.64-35.79-7.54-52.76-1.94-6.75-8.39-11.24-15.4-11.24zm-116.3 100.12c7.05-10.29 11.2-22.71 11.2-36.12 0-35.35-28.63-64-63.96-64-35.32 0-63.96 28.65-63.96 64 0 13.41 4.15 25.83 11.2 36.12l-130.5 313.41c-3.4 8.15.46 17.52 8.61 20.92l29.51 12.31c8.15 3.4 17.52-.46 20.91-8.61L244.96 384h150.07l49.2 118.15c3.4 8.16 12.76 12.01 20.91 8.61l29.51-12.31c8.15-3.4 12-12.77 8.61-20.92l-130.5-313.41zM271.62 320L320 203.81 368.38 320h-96.76z\"],\n    \"broom\": [640, 512, [], \"f51a\", \"M256.47 216.77l86.73 109.18s-16.6 102.36-76.57 150.12C206.66 523.85 0 510.19 0 510.19s3.8-23.14 11-55.43l94.62-112.17c3.97-4.7-.87-11.62-6.65-9.5l-60.4 22.09c14.44-41.66 32.72-80.04 54.6-97.47 59.97-47.76 163.3-40.94 163.3-40.94zM636.53 31.03l-19.86-25c-5.49-6.9-15.52-8.05-22.41-2.56l-232.48 177.8-34.14-42.97c-5.09-6.41-15.14-5.21-18.59 2.21l-25.33 54.55 86.73 109.18 58.8-12.45c8-1.69 11.42-11.2 6.34-17.6l-34.09-42.92 232.48-177.8c6.89-5.48 8.04-15.53 2.55-22.44z\"],\n    \"brush\": [384, 512, [], \"f55d\", \"M352 0H32C14.33 0 0 14.33 0 32v224h384V32c0-17.67-14.33-32-32-32zM0 320c0 35.35 28.66 64 64 64h64v64c0 35.35 28.66 64 64 64s64-28.65 64-64v-64h64c35.34 0 64-28.65 64-64v-32H0v32zm192 104c13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24s-24-10.75-24-24c0-13.26 10.75-24 24-24z\"],\n    \"bug\": [512, 512, [], \"f188\", \"M511.988 288.9c-.478 17.43-15.217 31.1-32.653 31.1H424v16c0 21.864-4.882 42.584-13.6 61.145l60.228 60.228c12.496 12.497 12.496 32.758 0 45.255-12.498 12.497-32.759 12.496-45.256 0l-54.736-54.736C345.886 467.965 314.351 480 280 480V236c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v244c-34.351 0-65.886-12.035-90.636-32.108l-54.736 54.736c-12.498 12.497-32.759 12.496-45.256 0-12.496-12.497-12.496-32.758 0-45.255l60.228-60.228C92.882 378.584 88 357.864 88 336v-16H32.666C15.23 320 .491 306.33.013 288.9-.484 270.816 14.028 256 32 256h56v-58.745l-46.628-46.628c-12.496-12.497-12.496-32.758 0-45.255 12.498-12.497 32.758-12.497 45.256 0L141.255 160h229.489l54.627-54.627c12.498-12.497 32.758-12.497 45.256 0 12.496 12.497 12.496 32.758 0 45.255L424 197.255V256h56c17.972 0 32.484 14.816 31.988 32.9zM257 0c-61.856 0-112 50.144-112 112h224C369 50.144 318.856 0 257 0z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M436 480h-20V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v456H12c-6.627 0-12 5.373-12 12v20h448v-20c0-6.627-5.373-12-12-12zM128 76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76zm0 96c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40zm52 148h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12zm76 160h-64v-84c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v84zm64-172c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40z\"],\n    \"bullhorn\": [576, 512, [], \"f0a1\", \"M576 240c0-23.63-12.95-44.04-32-55.12V32.01C544 23.26 537.02 0 512 0c-7.12 0-14.19 2.38-19.98 7.02l-85.03 68.03C364.28 109.19 310.66 128 256 128H64c-35.35 0-64 28.65-64 64v96c0 35.35 28.65 64 64 64h33.7c-1.39 10.48-2.18 21.14-2.18 32 0 39.77 9.26 77.35 25.56 110.94 5.19 10.69 16.52 17.06 28.4 17.06h74.28c26.05 0 41.69-29.84 25.9-50.56-16.4-21.52-26.15-48.36-26.15-77.44 0-11.11 1.62-21.79 4.41-32H256c54.66 0 108.28 18.81 150.98 52.95l85.03 68.03a32.023 32.023 0 0 0 19.98 7.02c24.92 0 32-22.78 32-32V295.13C563.05 284.04 576 263.63 576 240zm-96 141.42l-33.05-26.44C392.95 311.78 325.12 288 256 288v-96c69.12 0 136.95-23.78 190.95-66.98L480 98.58v282.84z\"],\n    \"bullseye\": [496, 512, [], \"f140\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 432c-101.69 0-184-82.29-184-184 0-101.69 82.29-184 184-184 101.69 0 184 82.29 184 184 0 101.69-82.29 184-184 184zm0-312c-70.69 0-128 57.31-128 128s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm0 192c-35.29 0-64-28.71-64-64s28.71-64 64-64 64 28.71 64 64-28.71 64-64 64z\"],\n    \"burn\": [384, 512, [], \"f46a\", \"M192 0C79.7 101.3 0 220.9 0 300.5 0 425 79 512 192 512s192-87 192-211.5c0-79.9-80.2-199.6-192-300.5zm0 448c-56.5 0-96-39-96-94.8 0-13.5 4.6-61.5 96-161.2 91.4 99.7 96 147.7 96 161.2 0 55.8-39.5 94.8-96 94.8z\"],\n    \"bus\": [512, 512, [], \"f207\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM112 400c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm16-112c-17.67 0-32-14.33-32-32V128c0-17.67 14.33-32 32-32h256c17.67 0 32 14.33 32 32v128c0 17.67-14.33 32-32 32H128zm272 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"bus-alt\": [512, 512, [], \"f55e\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM160 72c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H168c-4.42 0-8-3.58-8-8V72zm-48 328c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128-112H128c-17.67 0-32-14.33-32-32v-96c0-17.67 14.33-32 32-32h112v160zm32 0V128h112c17.67 0 32 14.33 32 32v96c0 17.67-14.33 32-32 32H272zm128 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"business-time\": [640, 512, [], \"f64a\", \"M496 224c-79.59 0-144 64.41-144 144s64.41 144 144 144 144-64.41 144-144-64.41-144-144-144zm64 150.29c0 5.34-4.37 9.71-9.71 9.71h-60.57c-5.34 0-9.71-4.37-9.71-9.71v-76.57c0-5.34 4.37-9.71 9.71-9.71h12.57c5.34 0 9.71 4.37 9.71 9.71V352h38.29c5.34 0 9.71 4.37 9.71 9.71v12.58zM496 192c5.4 0 10.72.33 16 .81V144c0-25.6-22.4-48-48-48h-80V48c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h395.12c28.6-20.09 63.35-32 100.88-32zM320 96H192V64h128v32zm6.82 224H208c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h291.43C327.1 423.96 320 396.82 320 368c0-16.66 2.48-32.72 6.82-48z\"],\n    \"calculator\": [448, 512, [], \"f1ec\", \"M400 0H48C22.4 0 0 22.4 0 48v416c0 25.6 22.4 48 48 48h352c25.6 0 48-22.4 48-48V48c0-25.6-22.4-48-48-48zM128 435.2c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8V268.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v166.4zm0-256c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8V76.8C64 70.4 70.4 64 76.8 64h294.4c6.4 0 12.8 6.4 12.8 12.8v102.4z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm436-44v-36c0-26.5-21.5-48-48-48h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v36c0 6.6 5.4 12 12 12h424c6.6 0 12-5.4 12-12z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm320-196c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM192 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM64 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M436 160H12c-6.627 0-12-5.373-12-12v-36c0-26.51 21.49-48 48-48h48V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h128V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h48c26.51 0 48 21.49 48 48v36c0 6.627-5.373 12-12 12zM12 192h424c6.627 0 12 5.373 12 12v260c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V204c0-6.627 5.373-12 12-12zm333.296 95.947l-28.169-28.398c-4.667-4.705-12.265-4.736-16.97-.068L194.12 364.665l-45.98-46.352c-4.667-4.705-12.266-4.736-16.971-.068l-28.397 28.17c-4.705 4.667-4.736 12.265-.068 16.97l82.601 83.269c4.667 4.705 12.265 4.736 16.97.068l142.953-141.805c4.705-4.667 4.736-12.265.068-16.97z\"],\n    \"calendar-day\": [448, 512, [], \"f783\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h96c8.8 0 16 7.2 16 16v96c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-96zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm304 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H132c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h184z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm316 140c0-6.6-5.4-12-12-12h-60v-60c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v60h-60c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h60v60c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-60h60c6.6 0 12-5.4 12-12v-40z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm257.3 160l48.1-48.1c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0L224 306.7l-48.1-48.1c-4.7-4.7-12.3-4.7-17 0l-28.3 28.3c-4.7 4.7-4.7 12.3 0 17l48.1 48.1-48.1 48.1c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l48.1-48.1 48.1 48.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L269.3 352z\"],\n    \"calendar-week\": [448, 512, [], \"f784\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h288c8.8 0 16 7.2 16 16v64c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-64zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"camera\": [512, 512, [], \"f030\", \"M512 144v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V144c0-26.5 21.5-48 48-48h88l12.3-32.9c7-18.7 24.9-31.1 44.9-31.1h125.5c20 0 37.9 12.4 44.9 31.1L376 96h88c26.5 0 48 21.5 48 48zM376 288c0-66.2-53.8-120-120-120s-120 53.8-120 120 53.8 120 120 120 120-53.8 120-120zm-32 0c0 48.5-39.5 88-88 88s-88-39.5-88-88 39.5-88 88-88 88 39.5 88 88z\"],\n    \"camera-retro\": [512, 512, [], \"f083\", \"M48 32C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48H48zm0 32h106c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H38c-3.3 0-6-2.7-6-6V80c0-8.8 7.2-16 16-16zm426 96H38c-3.3 0-6-2.7-6-6v-36c0-3.3 2.7-6 6-6h138l30.2-45.3c1.1-1.7 3-2.7 5-2.7H464c8.8 0 16 7.2 16 16v74c0 3.3-2.7 6-6 6zM256 424c-66.2 0-120-53.8-120-120s53.8-120 120-120 120 53.8 120 120-53.8 120-120 120zm0-208c-48.5 0-88 39.5-88 88s39.5 88 88 88 88-39.5 88-88-39.5-88-88-88zm-48 104c-8.8 0-16-7.2-16-16 0-35.3 28.7-64 64-64 8.8 0 16 7.2 16 16s-7.2 16-16 16c-17.6 0-32 14.4-32 32 0 8.8-7.2 16-16 16z\"],\n    \"campground\": [640, 512, [], \"f6bb\", \"M624 448h-24.68L359.54 117.75l53.41-73.55c5.19-7.15 3.61-17.16-3.54-22.35l-25.9-18.79c-7.15-5.19-17.15-3.61-22.35 3.55L320 63.3 278.83 6.6c-5.19-7.15-15.2-8.74-22.35-3.55l-25.88 18.8c-7.15 5.19-8.74 15.2-3.54 22.35l53.41 73.55L40.68 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM320 288l116.36 160H203.64L320 288z\"],\n    \"candy-cane\": [512, 512, [], \"f786\", \"M497.5 92C469.6 33.1 411.8 0 352.4 0c-27.9 0-56.2 7.3-81.8 22.6L243.1 39c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5l27.5-16.4c5.1-3.1 10.8-4.5 16.4-4.5 10.9 0 21.5 5.6 27.5 15.6 9.1 15.1 4.1 34.8-11 43.9L15.6 397.6c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5L428.6 301c71.7-42.9 104.6-133.5 68.9-209zm-177.7 13l-2.5 1.5L296.8 45c9.7-4.7 19.8-8.1 30.3-10.2l20.6 61.8c-9.8.8-19.4 3.3-27.9 8.4zM145.9 431.8l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm107.5-63.9l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zM364.3 302l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm20.4-197.3l46-46c8.4 6.5 16 14.1 22.6 22.6L407.6 127c-5.7-9.3-13.7-16.9-22.9-22.3zm82.1 107.8l-59.5-19.8c3.2-5.3 5.8-10.9 7.4-17.1 1.1-4.5 1.7-9.1 1.8-13.6l60.4 20.1c-2.1 10.4-5.5 20.6-10.1 30.4z\"],\n    \"cannabis\": [512, 512, [], \"f55f\", \"M503.47 360.25c-1.56-.82-32.39-16.89-76.78-25.81 64.25-75.12 84.05-161.67 84.93-165.64 1.18-5.33-.44-10.9-4.3-14.77-3.03-3.04-7.12-4.7-11.32-4.7-1.14 0-2.29.12-3.44.38-3.88.85-86.54 19.59-160.58 79.76.01-1.46.01-2.93.01-4.4 0-118.79-59.98-213.72-62.53-217.7A15.973 15.973 0 0 0 256 0c-5.45 0-10.53 2.78-13.47 7.37-2.55 3.98-62.53 98.91-62.53 217.7 0 1.47.01 2.94.01 4.4-74.03-60.16-156.69-78.9-160.58-79.76-1.14-.25-2.29-.38-3.44-.38-4.2 0-8.29 1.66-11.32 4.7A15.986 15.986 0 0 0 .38 168.8c.88 3.97 20.68 90.52 84.93 165.64-44.39 8.92-75.21 24.99-76.78 25.81a16.003 16.003 0 0 0-.02 28.29c2.45 1.29 60.76 31.72 133.49 31.72 6.14 0 11.96-.1 17.5-.31-11.37 22.23-16.52 38.31-16.81 39.22-1.8 5.68-.29 11.89 3.91 16.11a16.019 16.019 0 0 0 16.1 3.99c1.83-.57 37.72-11.99 77.3-39.29V504c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-64.01c39.58 27.3 75.47 38.71 77.3 39.29a16.019 16.019 0 0 0 16.1-3.99c4.2-4.22 5.71-10.43 3.91-16.11-.29-.91-5.45-16.99-16.81-39.22 5.54.21 11.37.31 17.5.31 72.72 0 131.04-30.43 133.49-31.72 5.24-2.78 8.52-8.22 8.51-14.15-.01-5.94-3.29-11.39-8.53-14.15z\"],\n    \"capsules\": [576, 512, [], \"f46b\", \"M555.3 300.1L424.2 112.8C401.9 81 366.4 64 330.4 64c-22.6 0-45.5 6.7-65.5 20.7-19.7 13.8-33.7 32.8-41.5 53.8C220.5 79.2 172 32 112 32 50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V218.9c3.3 8.6 7.3 17.1 12.8 25L368 431.2c22.2 31.8 57.7 48.8 93.8 48.8 22.7 0 45.5-6.7 65.5-20.7 51.7-36.2 64.2-107.5 28-159.2zM160 256H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm194.8 44.9l-65.6-93.7c-7.7-11-10.7-24.4-8.3-37.6 2.3-13.2 9.7-24.8 20.7-32.5 8.5-6 18.5-9.1 28.8-9.1 16.5 0 31.9 8 41.3 21.5l65.6 93.7-82.5 57.7z\"],\n    \"car\": [512, 512, [], \"f1b9\", \"M499.99 176h-59.87l-16.64-41.6C406.38 91.63 365.57 64 319.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4L71.87 176H12.01C4.2 176-1.53 183.34.37 190.91l6 24C7.7 220.25 12.5 224 18.01 224h20.07C24.65 235.73 16 252.78 16 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-19.22-8.65-36.27-22.07-48H494c5.51 0 10.31-3.75 11.64-9.09l6-24c1.89-7.57-3.84-14.91-11.65-14.91zm-352.06-17.83c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L384 208H128l19.93-49.83zM96 319.8c-19.2 0-32-12.76-32-31.9S76.8 256 96 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S396.8 256 416 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-alt\": [480, 512, [], \"f5de\", \"M438.66 212.33l-11.24-28.1-19.93-49.83C390.38 91.63 349.57 64 303.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4l-19.93 49.83-11.24 28.1C17.22 221.5 0 244.66 0 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-27.34-17.22-50.5-41.34-59.67zm-306.73-54.16c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L368 208H112l19.93-49.83zM80 319.8c-19.2 0-32-12.76-32-31.9S60.8 256 80 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S380.8 256 400 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-battery\": [512, 512, [], \"f5df\", \"M480 128h-32V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v48H192V80c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v48H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zM192 264c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm256 0c0 4.42-3.58 8-8 8h-40v40c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-40h-40c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h40v-40c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v40h40c4.42 0 8 3.58 8 8v16z\"],\n    \"car-crash\": [640, 512, [], \"f5e1\", \"M143.25 220.81l-12.42 46.37c-3.01 11.25-3.63 22.89-2.41 34.39l-35.2 28.98c-6.57 5.41-16.31-.43-14.62-8.77l15.44-76.68c1.06-5.26-2.66-10.28-8-10.79l-77.86-7.55c-8.47-.82-11.23-11.83-4.14-16.54l65.15-43.3c4.46-2.97 5.38-9.15 1.98-13.29L21.46 93.22c-5.41-6.57.43-16.3 8.78-14.62l76.68 15.44c5.26 1.06 10.28-2.66 10.8-8l7.55-77.86c.82-8.48 11.83-11.23 16.55-4.14l43.3 65.14c2.97 4.46 9.15 5.38 13.29 1.98l60.4-49.71c6.57-5.41 16.3.43 14.62 8.77L262.1 86.38c-2.71 3.05-5.43 6.09-7.91 9.4l-32.15 42.97-10.71 14.32c-32.73 8.76-59.18 34.53-68.08 67.74zm494.57 132.51l-12.42 46.36c-3.13 11.68-9.38 21.61-17.55 29.36a66.876 66.876 0 0 1-8.76 7l-13.99 52.23c-1.14 4.27-3.1 8.1-5.65 11.38-7.67 9.84-20.74 14.68-33.54 11.25L515 502.62c-17.07-4.57-27.2-22.12-22.63-39.19l8.28-30.91-247.28-66.26-8.28 30.91c-4.57 17.07-22.12 27.2-39.19 22.63l-30.91-8.28c-12.8-3.43-21.7-14.16-23.42-26.51-.57-4.12-.35-8.42.79-12.68l13.99-52.23a66.62 66.62 0 0 1-4.09-10.45c-3.2-10.79-3.65-22.52-.52-34.2l12.42-46.37c5.31-19.8 19.36-34.83 36.89-42.21a64.336 64.336 0 0 1 18.49-4.72l18.13-24.23 32.15-42.97c3.45-4.61 7.19-8.9 11.2-12.84 8-7.89 17.03-14.44 26.74-19.51 4.86-2.54 9.89-4.71 15.05-6.49 10.33-3.58 21.19-5.63 32.24-6.04 11.05-.41 22.31.82 33.43 3.8l122.68 32.87c11.12 2.98 21.48 7.54 30.85 13.43a111.11 111.11 0 0 1 34.69 34.5c8.82 13.88 14.64 29.84 16.68 46.99l6.36 53.29 3.59 30.05a64.49 64.49 0 0 1 22.74 29.93c4.39 11.88 5.29 25.19 1.75 38.39zM255.58 234.34c-18.55-4.97-34.21 4.04-39.17 22.53-4.96 18.49 4.11 34.12 22.65 39.09 18.55 4.97 45.54 15.51 50.49-2.98 4.96-18.49-15.43-53.67-33.97-58.64zm290.61 28.17l-6.36-53.29c-.58-4.87-1.89-9.53-3.82-13.86-5.8-12.99-17.2-23.01-31.42-26.82l-122.68-32.87a48.008 48.008 0 0 0-50.86 17.61l-32.15 42.97 172 46.08 75.29 20.18zm18.49 54.65c-18.55-4.97-53.8 15.31-58.75 33.79-4.95 18.49 23.69 22.86 42.24 27.83 18.55 4.97 34.21-4.04 39.17-22.53 4.95-18.48-4.11-34.12-22.66-39.09z\"],\n    \"car-side\": [640, 512, [], \"f5e4\", \"M544 192h-16L419.22 56.02A64.025 64.025 0 0 0 369.24 32H155.33c-26.17 0-49.7 15.93-59.42 40.23L48 194.26C20.44 201.4 0 226.21 0 256v112c0 8.84 7.16 16 16 16h48c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h48c8.84 0 16-7.16 16-16v-80c0-53.02-42.98-96-96-96zM160 432c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm72-240H116.93l38.4-96H232v96zm48 0V96h89.24l76.8 96H280zm200 240c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"caret-down\": [320, 512, [], \"f0d7\", \"M31.3 192h257.3c17.8 0 26.7 21.5 14.1 34.1L174.1 354.8c-7.8 7.8-20.5 7.8-28.3 0L17.2 226.1C4.6 213.5 13.5 192 31.3 192z\"],\n    \"caret-left\": [192, 512, [], \"f0d9\", \"M192 127.338v257.324c0 17.818-21.543 26.741-34.142 14.142L29.196 270.142c-7.81-7.81-7.81-20.474 0-28.284l128.662-128.662c12.599-12.6 34.142-3.676 34.142 14.142z\"],\n    \"caret-right\": [192, 512, [], \"f0da\", \"M0 384.662V127.338c0-17.818 21.543-26.741 34.142-14.142l128.662 128.662c7.81 7.81 7.81 20.474 0 28.284L34.142 398.804C21.543 411.404 0 402.48 0 384.662z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM92.5 220.5l123 123c4.7 4.7 12.3 4.7 17 0l123-123c7.6-7.6 2.2-20.5-8.5-20.5H101c-10.7 0-16.1 12.9-8.5 20.5z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM259.515 124.485l-123.03 123.03c-4.686 4.686-4.686 12.284 0 16.971l123.029 123.029c7.56 7.56 20.485 2.206 20.485-8.485V132.971c.001-10.691-12.925-16.045-20.484-8.486z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M48 32h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48zm140.485 355.515l123.029-123.029c4.686-4.686 4.686-12.284 0-16.971l-123.029-123.03c-7.56-7.56-20.485-2.206-20.485 8.485v246.059c0 10.691 12.926 16.045 20.485 8.486z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M0 432V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48zm355.515-140.485l-123.03-123.03c-4.686-4.686-12.284-4.686-16.971 0L92.485 291.515c-7.56 7.56-2.206 20.485 8.485 20.485h246.059c10.691 0 16.045-12.926 8.486-20.485z\"],\n    \"caret-up\": [320, 512, [], \"f0d8\", \"M288.662 352H31.338c-17.818 0-26.741-21.543-14.142-34.142l128.662-128.662c7.81-7.81 20.474-7.81 28.284 0l128.662 128.662c12.6 12.599 3.676 34.142-14.142 34.142z\"],\n    \"carrot\": [512, 512, [], \"f787\", \"M298.2 156.6c-52.7-25.7-114.5-10.5-150.2 32.8l55.2 55.2c6.3 6.3 6.3 16.4 0 22.6-3.1 3.1-7.2 4.7-11.3 4.7s-8.2-1.6-11.3-4.7L130.4 217 2.3 479.7c-2.9 6-3.1 13.3 0 19.7 5.4 11.1 18.9 15.7 30 10.3l133.6-65.2-49.2-49.2c-6.3-6.2-6.3-16.4 0-22.6 6.3-6.2 16.4-6.2 22.6 0l57 57 102-49.8c24-11.7 44.5-31.3 57.1-57.1 30.1-61.7 4.5-136.1-57.2-166.2zm92.1-34.9C409.8 81 399.7 32.9 360 0c-50.3 41.7-52.5 107.5-7.9 151.9l8 8c44.4 44.6 110.3 42.4 151.9-7.9-32.9-39.7-81-49.8-121.7-30.3z\"],\n    \"cart-arrow-down\": [576, 512, [], \"f218\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM403.029 192H360v-60c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v60h-43.029c-10.691 0-16.045 12.926-8.485 20.485l67.029 67.029c4.686 4.686 12.284 4.686 16.971 0l67.029-67.029c7.559-7.559 2.205-20.485-8.486-20.485z\"],\n    \"cart-plus\": [576, 512, [], \"f217\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM408 168h-48v-40c0-8.837-7.163-16-16-16h-16c-8.837 0-16 7.163-16 16v40h-48c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h48v40c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-40h48c8.837 0 16-7.163 16-16v-16c0-8.837-7.163-16-16-16z\"],\n    \"cash-register\": [512, 512, [], \"f788\", \"M511.1 378.8l-26.7-160c-2.6-15.4-15.9-26.7-31.6-26.7H208v-64h96c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h96v64H59.1c-15.6 0-29 11.3-31.6 26.7L.8 378.7c-.6 3.5-.9 7-.9 10.5V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-90.7c.1-3.5-.2-7-.8-10.5zM280 248c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16zm-32 64h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16zm-32-80c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16zM80 80V48h192v32H80zm40 200h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16zm16 64v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16zm216 112c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16zm24-112c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16zm48-80c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16z\"],\n    \"cat\": [512, 512, [], \"f6be\", \"M290.59 192c-20.18 0-106.82 1.98-162.59 85.95V192c0-52.94-43.06-96-96-96-17.67 0-32 14.33-32 32s14.33 32 32 32c17.64 0 32 14.36 32 32v256c0 35.3 28.7 64 64 64h176c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-32l128-96v144c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V289.86c-10.29 2.67-20.89 4.54-32 4.54-61.81 0-113.52-44.05-125.41-102.4zM448 96h-64l-64-64v134.4c0 53.02 42.98 96 96 96s96-42.98 96-96V32l-64 64zm-72 80c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm80 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"certificate\": [512, 512, [], \"f0a3\", \"M458.622 255.92l45.985-45.005c13.708-12.977 7.316-36.039-10.664-40.339l-62.65-15.99 17.661-62.015c4.991-17.838-11.829-34.663-29.661-29.671l-61.994 17.667-15.984-62.671C337.085.197 313.765-6.276 300.99 7.228L256 53.57 211.011 7.229c-12.63-13.351-36.047-7.234-40.325 10.668l-15.984 62.671-61.995-17.667C74.87 57.907 58.056 74.738 63.046 92.572l17.661 62.015-62.65 15.99C.069 174.878-6.31 197.944 7.392 210.915l45.985 45.005-45.985 45.004c-13.708 12.977-7.316 36.039 10.664 40.339l62.65 15.99-17.661 62.015c-4.991 17.838 11.829 34.663 29.661 29.671l61.994-17.667 15.984 62.671c4.439 18.575 27.696 24.018 40.325 10.668L256 458.61l44.989 46.001c12.5 13.488 35.987 7.486 40.325-10.668l15.984-62.671 61.994 17.667c17.836 4.994 34.651-11.837 29.661-29.671l-17.661-62.015 62.65-15.99c17.987-4.302 24.366-27.367 10.664-40.339l-45.984-45.004z\"],\n    \"chair\": [448, 512, [], \"f6c0\", \"M112 128c0-29.5 16.2-55 40-68.9V256h48V48h48v208h48V59.1c23.8 13.9 40 39.4 40 68.9v128h48V128C384 57.3 326.7 0 256 0h-64C121.3 0 64 57.3 64 128v128h48zm334.3 213.9l-10.7-32c-4.4-13.1-16.6-21.9-30.4-21.9H42.7c-13.8 0-26 8.8-30.4 21.9l-10.7 32C-5.2 362.6 10.2 384 32 384v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384h256v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384c21.8 0 37.2-21.4 30.3-42.1z\"],\n    \"chalkboard\": [640, 512, [], \"f51b\", \"M96 64h448v352h64V40c0-22.06-17.94-40-40-40H72C49.94 0 32 17.94 32 40v376h64V64zm528 384H480v-64H288v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chalkboard-teacher\": [640, 512, [], \"f51c\", \"M208 352c-2.39 0-4.78.35-7.06 1.09C187.98 357.3 174.35 360 160 360c-14.35 0-27.98-2.7-40.95-6.91-2.28-.74-4.66-1.09-7.05-1.09C49.94 352-.33 402.48 0 464.62.14 490.88 21.73 512 48 512h224c26.27 0 47.86-21.12 48-47.38.33-62.14-49.94-112.62-112-112.62zm-48-32c53.02 0 96-42.98 96-96s-42.98-96-96-96-96 42.98-96 96 42.98 96 96 96zM592 0H208c-26.47 0-48 22.25-48 49.59V96c23.42 0 45.1 6.78 64 17.8V64h352v288h-64v-64H384v64h-76.24c19.1 16.69 33.12 38.73 39.69 64H592c26.47 0 48-22.25 48-49.59V49.59C640 22.25 618.47 0 592 0z\"],\n    \"charging-station\": [576, 512, [], \"f5e7\", \"M336 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h320c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm208-320V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-32V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-16c-8.84 0-16 7.16-16 16v32c0 35.76 23.62 65.69 56 75.93v118.49c0 13.95-9.5 26.92-23.26 29.19C431.22 402.5 416 388.99 416 372v-28c0-48.6-39.4-88-88-88h-8V64c0-35.35-28.65-64-64-64H96C60.65 0 32 28.65 32 64v352h288V304h8c22.09 0 40 17.91 40 40v24.61c0 39.67 28.92 75.16 68.41 79.01C481.71 452.05 520 416.41 520 372V251.93c32.38-10.24 56-40.17 56-75.93v-32c0-8.84-7.16-16-16-16h-16zm-283.91 47.76l-93.7 139c-2.2 3.33-6.21 5.24-10.39 5.24-7.67 0-13.47-6.28-11.67-12.92L167.35 224H108c-7.25 0-12.85-5.59-11.89-11.89l16-107C112.9 99.9 117.98 96 124 96h68c7.88 0 13.62 6.54 11.6 13.21L192 160h57.7c9.24 0 15.01 8.78 10.39 15.76z\"],\n    \"chart-area\": [512, 512, [], \"f1fe\", \"M500 384c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v308h436zM372.7 159.5L288 216l-85.3-113.7c-5.1-6.8-15.5-6.3-19.9 1L96 248v104h384l-89.9-187.8c-3.2-6.5-11.4-8.7-17.4-4.7z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M332.8 320h38.4c6.4 0 12.8-6.4 12.8-12.8V172.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V76.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-288 0h38.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zM496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chart-line\": [512, 512, [], \"f201\", \"M496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM464 96H345.94c-21.38 0-32.09 25.85-16.97 40.97l32.4 32.4L288 242.75l-73.37-73.37c-12.5-12.5-32.76-12.5-45.25 0l-68.69 68.69c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L192 237.25l73.37 73.37c12.5 12.5 32.76 12.5 45.25 0l96-96 32.4 32.4c15.12 15.12 40.97 4.41 40.97-16.97V112c.01-8.84-7.15-16-15.99-16z\"],\n    \"chart-pie\": [544, 512, [], \"f200\", \"M527.79 288H290.5l158.03 158.03c6.04 6.04 15.98 6.53 22.19.68 38.7-36.46 65.32-85.61 73.13-140.86 1.34-9.46-6.51-17.85-16.06-17.85zm-15.83-64.8C503.72 103.74 408.26 8.28 288.8.04 279.68-.59 272 7.1 272 16.24V240h223.77c9.14 0 16.82-7.68 16.19-16.8zM224 288V50.71c0-9.55-8.39-17.4-17.84-16.06C86.99 51.49-4.1 155.6.14 280.37 4.5 408.51 114.83 513.59 243.03 511.98c50.4-.63 96.97-16.87 135.26-44.03 7.9-5.6 8.42-17.23 1.57-24.08L224 288z\"],\n    \"check\": [512, 512, [], \"f00c\", \"M173.898 439.404l-166.4-166.4c-9.997-9.997-9.997-26.206 0-36.204l36.203-36.204c9.997-9.998 26.207-9.998 36.204 0L192 312.69 432.095 72.596c9.997-9.997 26.207-9.997 36.204 0l36.203 36.204c9.997 9.997 9.997 26.206 0 36.204l-294.4 294.401c-9.998 9.997-26.207 9.997-36.204-.001z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM227.314 387.314l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.249-16.379-6.249-22.628 0L216 308.118l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.249 16.379 6.249 22.628.001z\"],\n    \"check-double\": [512, 512, [], \"f560\", \"M505 174.8l-39.6-39.6c-9.4-9.4-24.6-9.4-33.9 0L192 374.7 80.6 263.2c-9.4-9.4-24.6-9.4-33.9 0L7 302.9c-9.4 9.4-9.4 24.6 0 34L175 505c9.4 9.4 24.6 9.4 33.9 0l296-296.2c9.4-9.5 9.4-24.7.1-34zm-324.3 106c6.2 6.3 16.4 6.3 22.6 0l208-208.2c6.2-6.3 6.2-16.4 0-22.6L366.1 4.7c-6.2-6.3-16.4-6.3-22.6 0L192 156.2l-55.4-55.5c-6.2-6.3-16.4-6.3-22.6 0L68.7 146c-6.2 6.3-6.2 16.4 0 22.6l112 112.2z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zm-204.686-98.059l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.248-16.379-6.249-22.628 0L184 302.745l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.25 16.379 6.25 22.628.001z\"],\n    \"cheese\": [512, 512, [], \"f7ef\", \"M0 288v160a32 32 0 0 0 32 32h448a32 32 0 0 0 32-32V288zM299.83 32a32 32 0 0 0-21.13 7L0 256h512c0-119.89-94-217.8-212.17-224z\"],\n    \"chess\": [512, 512, [], \"f439\", \"M74 208H64a16 16 0 0 0-16 16v16a16 16 0 0 0 16 16h15.94A535.78 535.78 0 0 1 64 384h128a535.78 535.78 0 0 1-15.94-128H192a16 16 0 0 0 16-16v-16a16 16 0 0 0-16-16h-10l33.89-90.38a16 16 0 0 0-15-21.62H144V64h24a8 8 0 0 0 8-8V40a8 8 0 0 0-8-8h-24V8a8 8 0 0 0-8-8h-16a8 8 0 0 0-8 8v24H88a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h24v32H55.09a16 16 0 0 0-15 21.62zm173.16 251.58L224 448v-16a16 16 0 0 0-16-16H48a16 16 0 0 0-16 16v16L8.85 459.58A16 16 0 0 0 0 473.89V496a16 16 0 0 0 16 16h224a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31zm92.77-157.78l-3.29 82.2h126.72l-3.29-82.21 24.6-20.79A32 32 0 0 0 496 256.54V198a6 6 0 0 0-6-6h-26.38a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H373.1a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H310a6 6 0 0 0-6 6v58.6a32 32 0 0 0 11.36 24.4zM384 304a16 16 0 0 1 32 0v32h-32zm119.16 155.58L480 448v-16a16 16 0 0 0-16-16H336a16 16 0 0 0-16 16v16l-23.15 11.58a16 16 0 0 0-8.85 14.31V496a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31z\"],\n    \"chess-bishop\": [320, 512, [], \"f43a\", \"M8 287.88c0 51.64 22.14 73.83 56 84.6V416h192v-43.52c33.86-10.77 56-33 56-84.6 0-30.61-10.73-67.1-26.69-102.56L185 285.65a8 8 0 0 1-11.31 0l-11.31-11.31a8 8 0 0 1 0-11.31L270.27 155.1c-20.8-37.91-46.47-72.1-70.87-92.59C213.4 59.09 224 47.05 224 32a32 32 0 0 0-32-32h-64a32 32 0 0 0-32 32c0 15 10.6 27.09 24.6 30.51C67.81 106.8 8 214.5 8 287.88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-board\": [512, 512, [], \"f43c\", \"M255.9.2h-64v64h64zM0 64.17v64h64v-64zM128 .2H64v64h64zm64 255.9v64h64v-64zM0 192.12v64h64v-64zM383.85.2h-64v64h64zm128 0h-64v64h64zM128 256.1H64v64h64zM511.8 448v-64h-64v64zm0-128v-64h-64v64zM383.85 512h64v-64h-64zm128-319.88v-64h-64v64zM128 512h64v-64h-64zM0 512h64v-64H0zm255.9 0h64v-64h-64zM0 320.07v64h64v-64zm319.88-191.92v-64h-64v64zm-64 128h64v-64h-64zm-64 128v64h64v-64zm128-64h64v-64h-64zm0-127.95h64v-64h-64zm0 191.93v64h64v-64zM64 384.05v64h64v-64zm128-255.9v-64h-64v64zm191.92 255.9h64v-64h-64zm-128-191.93v-64h-64v64zm128-127.95v64h64v-64zm-128 255.9v64h64v-64zm-64-127.95H128v64h64zm191.92 64h64v-64h-64zM128 128.15H64v64h64zm0 191.92v64h64v-64z\"],\n    \"chess-king\": [448, 512, [], \"f43f\", \"M400 448H48a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm16-288H256v-48h40a8 8 0 0 0 8-8V56a8 8 0 0 0-8-8h-40V8a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v40h-40a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8h40v48H32a32 32 0 0 0-30.52 41.54L74.56 416h298.88l73.08-214.46A32 32 0 0 0 416 160z\"],\n    \"chess-knight\": [384, 512, [], \"f441\", \"M19 272.47l40.63 18.06a32 32 0 0 0 24.88.47l12.78-5.12a32 32 0 0 0 18.76-20.5l9.22-30.65a24 24 0 0 1 12.55-15.65L159.94 208v50.33a48 48 0 0 1-26.53 42.94l-57.22 28.65A80 80 0 0 0 32 401.48V416h319.86V224c0-106-85.92-192-191.92-192H12A12 12 0 0 0 0 44a16.9 16.9 0 0 0 1.79 7.58L16 80l-9 9a24 24 0 0 0-7 17v137.21a32 32 0 0 0 19 29.26zM52 128a20 20 0 1 1-20 20 20 20 0 0 1 20-20zm316 320H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-pawn\": [320, 512, [], \"f443\", \"M105.1 224H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h16v5.49c0 44-4.14 86.6-24 122.51h176c-19.89-35.91-24-78.51-24-122.51V288h16a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-25.1c29.39-18.38 49.1-50.78 49.1-88a104 104 0 0 0-208 0c0 37.22 19.71 69.62 49.1 88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-queen\": [512, 512, [], \"f445\", \"M256 112a56 56 0 1 0-56-56 56 56 0 0 0 56 56zm176 336H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm72.87-263.84l-28.51-15.92c-7.44-5-16.91-2.46-22.29 4.68a47.59 47.59 0 0 1-47.23 18.23C383.7 186.86 368 164.93 368 141.4a13.4 13.4 0 0 0-13.4-13.4h-38.77c-6 0-11.61 4-12.86 9.91a48 48 0 0 1-93.94 0c-1.25-5.92-6.82-9.91-12.86-9.91H157.4a13.4 13.4 0 0 0-13.4 13.4c0 25.69-19 48.75-44.67 50.49a47.5 47.5 0 0 1-41.54-19.15c-5.28-7.09-14.73-9.45-22.09-4.54l-28.57 16a16 16 0 0 0-5.44 20.47L104.24 416h303.52l102.55-211.37a16 16 0 0 0-5.44-20.47z\"],\n    \"chess-rook\": [384, 512, [], \"f447\", \"M368 32h-56a16 16 0 0 0-16 16v48h-48V48a16 16 0 0 0-16-16h-80a16 16 0 0 0-16 16v48H88.1V48a16 16 0 0 0-16-16H16A16 16 0 0 0 0 48v176l64 32c0 48.33-1.54 95-13.21 160h282.42C321.54 351 320 303.72 320 256l64-32V48a16 16 0 0 0-16-16zM224 320h-64v-64a32 32 0 0 1 64 0zm144 128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chevron-circle-down\": [512, 512, [], \"f13a\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM273 369.9l135.5-135.5c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L256 285.1 154.4 183.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L239 369.9c9.4 9.4 24.6 9.4 34 0z\"],\n    \"chevron-circle-left\": [512, 512, [], \"f137\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zM142.1 273l135.5 135.5c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L226.9 256l101.6-101.6c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L142.1 239c-9.4 9.4-9.4 24.6 0 34z\"],\n    \"chevron-circle-right\": [512, 512, [], \"f138\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm113.9 231L234.4 103.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L285.1 256 183.5 357.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L369.9 273c9.4-9.4 9.4-24.6 0-34z\"],\n    \"chevron-circle-up\": [512, 512, [], \"f139\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm231-113.9L103.5 277.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L256 226.9l101.6 101.6c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L273 142.1c-9.4-9.4-24.6-9.4-34 0z\"],\n    \"chevron-down\": [448, 512, [], \"f078\", \"M207.029 381.476L12.686 187.132c-9.373-9.373-9.373-24.569 0-33.941l22.667-22.667c9.357-9.357 24.522-9.375 33.901-.04L224 284.505l154.745-154.021c9.379-9.335 24.544-9.317 33.901.04l22.667 22.667c9.373 9.373 9.373 24.569 0 33.941L240.971 381.476c-9.373 9.372-24.569 9.372-33.942 0z\"],\n    \"chevron-left\": [320, 512, [], \"f053\", \"M34.52 239.03L228.87 44.69c9.37-9.37 24.57-9.37 33.94 0l22.67 22.67c9.36 9.36 9.37 24.52.04 33.9L131.49 256l154.02 154.75c9.34 9.38 9.32 24.54-.04 33.9l-22.67 22.67c-9.37 9.37-24.57 9.37-33.94 0L34.52 272.97c-9.37-9.37-9.37-24.57 0-33.94z\"],\n    \"chevron-right\": [320, 512, [], \"f054\", \"M285.476 272.971L91.132 467.314c-9.373 9.373-24.569 9.373-33.941 0l-22.667-22.667c-9.357-9.357-9.375-24.522-.04-33.901L188.505 256 34.484 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L285.475 239.03c9.373 9.372 9.373 24.568.001 33.941z\"],\n    \"chevron-up\": [448, 512, [], \"f077\", \"M240.971 130.524l194.343 194.343c9.373 9.373 9.373 24.569 0 33.941l-22.667 22.667c-9.357 9.357-24.522 9.375-33.901.04L224 227.495 69.255 381.516c-9.379 9.335-24.544 9.317-33.901-.04l-22.667-22.667c-9.373-9.373-9.373-24.569 0-33.941L207.03 130.525c9.372-9.373 24.568-9.373 33.941-.001z\"],\n    \"child\": [384, 512, [], \"f1ae\", \"M120 72c0-39.765 32.235-72 72-72s72 32.235 72 72c0 39.764-32.235 72-72 72s-72-32.236-72-72zm254.627 1.373c-12.496-12.497-32.758-12.497-45.254 0L242.745 160H141.254L54.627 73.373c-12.496-12.497-32.758-12.497-45.254 0-12.497 12.497-12.497 32.758 0 45.255L104 213.254V480c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V368h16v112c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V213.254l94.627-94.627c12.497-12.497 12.497-32.757 0-45.254z\"],\n    \"church\": [640, 512, [], \"f51d\", \"M464.46 246.68L352 179.2V128h48c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-48V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v48h-48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v51.2l-112.46 67.48A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.65-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.54A32.024 32.024 0 0 0 0 395.96zm620.61-29.42L512 320v192h112c8.84 0 16-7.16 16-16V395.96c0-12.8-7.63-24.37-19.39-29.42z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8z\"],\n    \"circle-notch\": [512, 512, [], \"f1ce\", \"M288 39.056v16.659c0 10.804 7.281 20.159 17.686 23.066C383.204 100.434 440 171.518 440 256c0 101.689-82.295 184-184 184-101.689 0-184-82.295-184-184 0-84.47 56.786-155.564 134.312-177.219C216.719 75.874 224 66.517 224 55.712V39.064c0-15.709-14.834-27.153-30.046-23.234C86.603 43.482 7.394 141.206 8.003 257.332c.72 137.052 111.477 246.956 248.531 246.667C393.255 503.711 504 392.788 504 256c0-115.633-79.14-212.779-186.211-240.236C302.678 11.889 288 23.456 288 39.056z\"],\n    \"city\": [640, 512, [], \"f64f\", \"M616 192H480V24c0-13.26-10.74-24-24-24H312c-13.26 0-24 10.74-24 24v72h-64V16c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v80h-64V16c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v80H24c-13.26 0-24 10.74-24 24v360c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V216c0-13.26-10.75-24-24-24zM128 404c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm128 192c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12V76c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 288c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40z\"],\n    \"clinic-medical\": [576, 512, [], \"f7f2\", \"M288 115L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2zm96 261a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8zm186.69-139.72l-255.94-226a39.85 39.85 0 0 0-53.45 0l-256 226a16 16 0 0 0-1.21 22.6L25.5 282.7a16 16 0 0 0 22.6 1.21L277.42 81.63a16 16 0 0 1 21.17 0L527.91 283.9a16 16 0 0 0 22.6-1.21l21.4-23.82a16 16 0 0 0-1.22-22.59z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M384 112v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h80c0-35.29 28.71-64 64-64s64 28.71 64 64h80c26.51 0 48 21.49 48 48zM192 40c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24m96 114v-20a6 6 0 0 0-6-6H102a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h180a6 6 0 0 0 6-6z\"],\n    \"clipboard-check\": [384, 512, [], \"f46c\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm121.2 231.8l-143 141.8c-4.7 4.7-12.3 4.6-17-.1l-82.6-83.3c-4.7-4.7-4.6-12.3.1-17L99.1 285c4.7-4.7 12.3-4.6 17 .1l46 46.4 106-105.2c4.7-4.7 12.3-4.6 17 .1l28.2 28.4c4.7 4.8 4.6 12.3-.1 17z\"],\n    \"clipboard-list\": [384, 512, [], \"f46d\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM96 424c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm96-192c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm128 368c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm57.1 350.1L224.9 294c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v137.7l63.5 46.2c5.4 3.9 6.5 11.4 2.6 16.8l-28.2 38.8c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48H176c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h288M176 416c-44.112 0-80-35.888-80-80V128H48c-26.51 0-48 21.49-48 48v288c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48v-48H176z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM218.1 287.7c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2.1 48 51.1 70.5 92.3 32.6zm190.4 0c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.5 56.9-172.7 32.1-172.7-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 222.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6z\"],\n    \"cloud\": [640, 512, [], \"f0c2\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4z\"],\n    \"cloud-download-alt\": [640, 512, [], \"f381\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zm-132.9 88.7L299.3 420.7c-6.2 6.2-16.4 6.2-22.6 0L171.3 315.3c-10.1-10.1-2.9-27.3 11.3-27.3H248V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v112h65.4c14.2 0 21.4 17.2 11.3 27.3z\"],\n    \"cloud-meatball\": [512, 512, [], \"f73b\", \"M48 352c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm416 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm-119 11.1c4.6-14.5 1.6-30.8-9.8-42.3-11.5-11.5-27.8-14.4-42.3-9.9-7-13.5-20.7-23-36.9-23s-29.9 9.5-36.9 23c-14.5-4.6-30.8-1.6-42.3 9.9-11.5 11.5-14.4 27.8-9.9 42.3-13.5 7-23 20.7-23 36.9s9.5 29.9 23 36.9c-4.6 14.5-1.6 30.8 9.9 42.3 8.2 8.2 18.9 12.3 29.7 12.3 4.3 0 8.5-1.1 12.6-2.5 7 13.5 20.7 23 36.9 23s29.9-9.5 36.9-23c4.1 1.3 8.3 2.5 12.6 2.5 10.8 0 21.5-4.1 29.7-12.3 11.5-11.5 14.4-27.8 9.8-42.3 13.5-7 23-20.7 23-36.9s-9.5-29.9-23-36.9zM512 224c0-53-43-96-96-96-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h43.4c3.6-8 8.4-15.4 14.8-21.8 13.5-13.5 31.5-21.1 50.8-21.3 13.5-13.2 31.7-20.9 51-20.9s37.5 7.7 51 20.9c19.3.2 37.3 7.8 50.8 21.3 6.4 6.4 11.3 13.8 14.8 21.8H416c53 0 96-43 96-96z\"],\n    \"cloud-moon\": [576, 512, [], \"f6c3\", \"M342.8 352.7c5.7-9.6 9.2-20.7 9.2-32.7 0-35.3-28.7-64-64-64-17.2 0-32.8 6.9-44.3 17.9-16.3-29.6-47.5-49.9-83.7-49.9-53 0-96 43-96 96 0 2 .5 3.8.6 5.7C27.1 338.8 0 374.1 0 416c0 53 43 96 96 96h240c44.2 0 80-35.8 80-80 0-41.9-32.3-75.8-73.2-79.3zm222.5-54.3c-93.1 17.7-178.5-53.7-178.5-147.7 0-54.2 29-104 76.1-130.8 7.3-4.1 5.4-15.1-2.8-16.7C448.4 1.1 436.7 0 425 0 319.1 0 233.1 85.9 233.1 192c0 8.5.7 16.8 1.8 25 5.9 4.3 11.6 8.9 16.7 14.2 11.4-4.7 23.7-7.2 36.4-7.2 52.9 0 96 43.1 96 96 0 3.6-.2 7.2-.6 10.7 23.6 10.8 42.4 29.5 53.5 52.6 54.4-3.4 103.7-29.3 137.1-70.4 5.3-6.5-.5-16.1-8.7-14.5z\"],\n    \"cloud-moon-rain\": [576, 512, [], \"f73c\", \"M350.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C27.6 232.9 0 265.2 0 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm217.4-1.7c-70.4 13.3-135-40.3-135-110.8 0-40.6 21.9-78 57.5-98.1 5.5-3.1 4.1-11.4-2.1-12.5C479.6.8 470.7 0 461.8 0c-77.9 0-141.1 61.2-144.4 137.9 26.7 11.9 48.2 33.8 58.9 61.7 37.1 14.3 64 47.4 70.2 86.8 5.1.5 10 1.5 15.2 1.5 44.7 0 85.6-20.2 112.6-53.3 4.2-4.8-.2-12-6.4-10.8zM364.5 418.1c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-rain\": [512, 512, [], \"f73d\", \"M416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96zM88 374.2c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0z\"],\n    \"cloud-showers-heavy\": [512, 512, [], \"f740\", \"M183.9 370.1c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-192 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm384 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zM416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.2 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96z\"],\n    \"cloud-sun\": [640, 512, [], \"f6c4\", \"M575.2 325.7c.2-1.9.8-3.7.8-5.6 0-35.3-28.7-64-64-64-12.6 0-24.2 3.8-34.1 10-17.6-38.8-56.5-66-101.9-66-61.8 0-112 50.1-112 112 0 3 .7 5.8.9 8.7-49.6 3.7-88.9 44.7-88.9 95.3 0 53 43 96 96 96h272c53 0 96-43 96-96 0-42.1-27.2-77.4-64.8-90.4zm-430.4-22.6c-43.7-43.7-43.7-114.7 0-158.3 43.7-43.7 114.7-43.7 158.4 0 9.7 9.7 16.9 20.9 22.3 32.7 9.8-3.7 20.1-6 30.7-7.5L386 81.1c4-11.9-7.3-23.1-19.2-19.2L279 91.2 237.5 8.4C232-2.8 216-2.8 210.4 8.4L169 91.2 81.1 61.9C69.3 58 58 69.3 61.9 81.1l29.3 87.8-82.8 41.5c-11.2 5.6-11.2 21.5 0 27.1l82.8 41.4-29.3 87.8c-4 11.9 7.3 23.1 19.2 19.2l76.1-25.3c6.1-12.4 14-23.7 23.6-33.5-13.1-5.4-25.4-13.4-36-24zm-4.8-79.2c0 40.8 29.3 74.8 67.9 82.3 8-4.7 16.3-8.8 25.2-11.7 5.4-44.3 31-82.5 67.4-105C287.3 160.4 258 140 224 140c-46.3 0-84 37.6-84 83.9z\"],\n    \"cloud-sun-rain\": [576, 512, [], \"f743\", \"M510.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C187.6 233 160 265.2 160 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm-386.4 34.4c-37.4-37.4-37.4-98.3 0-135.8 34.6-34.6 89.1-36.8 126.7-7.4 20-12.9 43.6-20.7 69.2-20.7.7 0 1.3.2 2 .2l8.9-26.7c3.4-10.2-6.3-19.8-16.5-16.4l-75.3 25.1-35.5-71c-4.8-9.6-18.5-9.6-23.3 0l-35.5 71-75.3-25.1c-10.2-3.4-19.8 6.3-16.4 16.5l25.1 75.3-71 35.5c-9.6 4.8-9.6 18.5 0 23.3l71 35.5-25.1 75.3c-3.4 10.2 6.3 19.8 16.5 16.5l59.2-19.7c-.2-2.4-.7-4.7-.7-7.2 0-12.5 2.3-24.5 6.2-35.9-3.6-2.7-7.1-5.2-10.2-8.3zm69.8-58c4.3-24.5 15.8-46.4 31.9-64-9.8-6.2-21.4-9.9-33.8-9.9-35.3 0-64 28.7-64 64 0 18.7 8.2 35.4 21.1 47.1 11.3-15.9 26.6-28.9 44.8-37.2zm330.6 216.2c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-upload-alt\": [640, 512, [], \"f382\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zM393.4 288H328v112c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V288h-65.4c-14.3 0-21.4-17.2-11.3-27.3l105.4-105.4c6.2-6.2 16.4-6.2 22.6 0l105.4 105.4c10.1 10.1 2.9 27.3-11.3 27.3z\"],\n    \"cocktail\": [576, 512, [], \"f561\", \"M296 464h-56V338.78l168.74-168.73c15.52-15.52 4.53-42.05-17.42-42.05H24.68c-21.95 0-32.94 26.53-17.42 42.05L176 338.78V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM432 0c-62.61 0-115.35 40.2-135.18 96h52.54c16.65-28.55 47.27-48 82.64-48 52.93 0 96 43.06 96 96s-43.07 96-96 96c-14.04 0-27.29-3.2-39.32-8.64l-35.26 35.26C379.23 279.92 404.59 288 432 288c79.53 0 144-64.47 144-144S511.53 0 432 0z\"],\n    \"code\": [640, 512, [], \"f121\", \"M278.9 511.5l-61-17.7c-6.4-1.8-10-8.5-8.2-14.9L346.2 8.7c1.8-6.4 8.5-10 14.9-8.2l61 17.7c6.4 1.8 10 8.5 8.2 14.9L293.8 503.3c-1.9 6.4-8.5 10.1-14.9 8.2zm-114-112.2l43.5-46.4c4.6-4.9 4.3-12.7-.8-17.2L117 256l90.6-79.7c5.1-4.5 5.5-12.3.8-17.2l-43.5-46.4c-4.5-4.8-12.1-5.1-17-.5L3.8 247.2c-5.1 4.7-5.1 12.8 0 17.5l144.1 135.1c4.9 4.6 12.5 4.4 17-.5zm327.2.6l144.1-135.1c5.1-4.7 5.1-12.8 0-17.5L492.1 112.1c-4.8-4.5-12.4-4.3-17 .5L431.6 159c-4.6 4.9-4.3 12.7.8 17.2L523 256l-90.6 79.7c-5.1 4.5-5.5 12.3-.8 17.2l43.5 46.4c4.5 4.9 12.1 5.1 17 .6z\"],\n    \"code-branch\": [384, 512, [], \"f126\", \"M384 144c0-44.2-35.8-80-80-80s-80 35.8-80 80c0 36.4 24.3 67.1 57.5 76.8-.6 16.1-4.2 28.5-11 36.9-15.4 19.2-49.3 22.4-85.2 25.7-28.2 2.6-57.4 5.4-81.3 16.9v-144c32.5-10.2 56-40.5 56-76.3 0-44.2-35.8-80-80-80S0 35.8 0 80c0 35.8 23.5 66.1 56 76.3v199.3C23.5 365.9 0 396.2 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-34-21.2-63.1-51.2-74.6 3.1-5.2 7.8-9.8 14.9-13.4 16.2-8.2 40.4-10.4 66.1-12.8 42.2-3.9 90-8.4 118.2-43.4 14-17.4 21.1-39.8 21.6-67.9 31.6-10.8 54.4-40.7 54.4-75.9zM80 64c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16zm0 384c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm224-320c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16z\"],\n    \"coffee\": [640, 512, [], \"f0f4\", \"M192 384h192c53 0 96-43 96-96h32c70.6 0 128-57.4 128-128S582.6 32 512 32H120c-13.3 0-24 10.7-24 24v232c0 53 43 96 96 96zM512 96c35.3 0 64 28.7 64 64s-28.7 64-64 64h-32V96h32zm47.7 384H48.3c-47.6 0-61-64-36-64h583.3c25 0 11.8 64-35.9 64z\"],\n    \"cog\": [512, 512, [], \"f013\", \"M487.4 315.7l-42.6-24.6c4.3-23.2 4.3-47 0-70.2l42.6-24.6c4.9-2.8 7.1-8.6 5.5-14-11.1-35.6-30-67.8-54.7-94.6-3.8-4.1-10-5.1-14.8-2.3L380.8 110c-17.9-15.4-38.5-27.3-60.8-35.1V25.8c0-5.6-3.9-10.5-9.4-11.7-36.7-8.2-74.3-7.8-109.2 0-5.5 1.2-9.4 6.1-9.4 11.7V75c-22.2 7.9-42.8 19.8-60.8 35.1L88.7 85.5c-4.9-2.8-11-1.9-14.8 2.3-24.7 26.7-43.6 58.9-54.7 94.6-1.7 5.4.6 11.2 5.5 14L67.3 221c-4.3 23.2-4.3 47 0 70.2l-42.6 24.6c-4.9 2.8-7.1 8.6-5.5 14 11.1 35.6 30 67.8 54.7 94.6 3.8 4.1 10 5.1 14.8 2.3l42.6-24.6c17.9 15.4 38.5 27.3 60.8 35.1v49.2c0 5.6 3.9 10.5 9.4 11.7 36.7 8.2 74.3 7.8 109.2 0 5.5-1.2 9.4-6.1 9.4-11.7v-49.2c22.2-7.9 42.8-19.8 60.8-35.1l42.6 24.6c4.9 2.8 11 1.9 14.8-2.3 24.7-26.7 43.6-58.9 54.7-94.6 1.5-5.5-.7-11.3-5.6-14.1zM256 336c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"cogs\": [640, 512, [], \"f085\", \"M512.1 191l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0L552 6.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zm-10.5-58.8c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.7-82.4 14.3-52.8 52.8zM386.3 286.1l33.7 16.8c10.1 5.8 14.5 18.1 10.5 29.1-8.9 24.2-26.4 46.4-42.6 65.8-7.4 8.9-20.2 11.1-30.3 5.3l-29.1-16.8c-16 13.7-34.6 24.6-54.9 31.7v33.6c0 11.6-8.3 21.6-19.7 23.6-24.6 4.2-50.4 4.4-75.9 0-11.5-2-20-11.9-20-23.6V418c-20.3-7.2-38.9-18-54.9-31.7L74 403c-10 5.8-22.9 3.6-30.3-5.3-16.2-19.4-33.3-41.6-42.2-65.7-4-10.9.4-23.2 10.5-29.1l33.3-16.8c-3.9-20.9-3.9-42.4 0-63.4L12 205.8c-10.1-5.8-14.6-18.1-10.5-29 8.9-24.2 26-46.4 42.2-65.8 7.4-8.9 20.2-11.1 30.3-5.3l29.1 16.8c16-13.7 34.6-24.6 54.9-31.7V57.1c0-11.5 8.2-21.5 19.6-23.5 24.6-4.2 50.5-4.4 76-.1 11.5 2 20 11.9 20 23.6v33.6c20.3 7.2 38.9 18 54.9 31.7l29.1-16.8c10-5.8 22.9-3.6 30.3 5.3 16.2 19.4 33.2 41.6 42.1 65.8 4 10.9.1 23.2-10 29.1l-33.7 16.8c3.9 21 3.9 42.5 0 63.5zm-117.6 21.1c59.2-77-28.7-164.9-105.7-105.7-59.2 77 28.7 164.9 105.7 105.7zm243.4 182.7l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0l8.2-14.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zM501.6 431c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.6-82.4 14.3-52.8 52.8z\"],\n    \"coins\": [512, 512, [], \"f51e\", \"M0 405.3V448c0 35.3 86 64 192 64s192-28.7 192-64v-42.7C342.7 434.4 267.2 448 192 448S41.3 434.4 0 405.3zM320 128c106 0 192-28.7 192-64S426 0 320 0 128 28.7 128 64s86 64 192 64zM0 300.4V352c0 35.3 86 64 192 64s192-28.7 192-64v-51.6c-41.3 34-116.9 51.6-192 51.6S41.3 334.4 0 300.4zm416 11c57.3-11.1 96-31.7 96-55.4v-42.7c-23.2 16.4-57.3 27.6-96 34.5v63.6zM192 160C86 160 0 195.8 0 240s86 80 192 80 192-35.8 192-80-86-80-192-80zm219.3 56.3c60-10.8 100.7-32 100.7-56.3v-42.7c-35.5 25.1-96.5 38.6-160.7 41.8 29.5 14.3 51.2 33.5 60 57.2z\"],\n    \"columns\": [512, 512, [], \"f0db\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64V160h160v256zm224 0H288V160h160v256z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 9.8 11.2 15.5 19.1 9.7L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64z\"],\n    \"comment-dollar\": [512, 512, [], \"f651\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95.01 57.02 130.74C44.46 421.05 2.7 465.97 2.2 466.5A7.995 7.995 0 0 0 8 480c66.26 0 115.99-31.75 140.6-51.38C181.29 440.93 217.59 448 256 448c141.38 0 256-93.12 256-208S397.38 32 256 32zm24 302.44V352c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-17.73c-11.42-1.35-22.28-5.19-31.78-11.46-6.22-4.11-6.82-13.11-1.55-18.38l17.52-17.52c3.74-3.74 9.31-4.24 14.11-2.03 3.18 1.46 6.66 2.22 10.26 2.22h32.78c4.66 0 8.44-3.78 8.44-8.42 0-3.75-2.52-7.08-6.12-8.11l-50.07-14.3c-22.25-6.35-40.01-24.71-42.91-47.67-4.05-32.07 19.03-59.43 49.32-63.05V128c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v17.73c11.42 1.35 22.28 5.19 31.78 11.46 6.22 4.11 6.82 13.11 1.55 18.38l-17.52 17.52c-3.74 3.74-9.31 4.24-14.11 2.03a24.516 24.516 0 0 0-10.26-2.22h-32.78c-4.66 0-8.44 3.78-8.44 8.42 0 3.75 2.52 7.08 6.12 8.11l50.07 14.3c22.25 6.36 40.01 24.71 42.91 47.67 4.05 32.06-19.03 59.42-49.32 63.04z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128 272c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"comment-medical\": [512, 512, [], \"f7f5\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95 57 130.74C44.46 421.05 2.7 466 2.2 466.5A8 8 0 0 0 8 480c66.26 0 116-31.75 140.6-51.38A304.66 304.66 0 0 0 256 448c141.39 0 256-93.12 256-208S397.39 32 256 32zm96 232a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8z\"],\n    \"comment-slash\": [640, 512, [], \"f4b3\", \"M64 240c0 49.6 21.4 95 57 130.7-12.6 50.3-54.3 95.2-54.8 95.8-2.2 2.3-2.8 5.7-1.5 8.7 1.3 2.9 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 27.4 0 53.7-3.6 78.4-10L72.9 186.4c-5.6 17.1-8.9 35-8.9 53.6zm569.8 218.1l-114.4-88.4C554.6 334.1 576 289.2 576 240c0-114.9-114.6-208-256-208-65.1 0-124.2 20.1-169.4 52.7L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M416 192c0-88.4-93.1-160-208-160S0 103.6 0 192c0 34.3 14.1 65.9 38 92-13.4 30.2-35.5 54.2-35.8 54.5-2.2 2.3-2.8 5.7-1.5 8.7S4.8 352 8 352c36.6 0 66.9-12.3 88.7-25 32.2 15.7 70.3 25 111.3 25 114.9 0 208-71.6 208-160zm122 220c23.9-26 38-57.7 38-92 0-66.9-53.5-124.2-129.3-148.1.9 6.6 1.3 13.3 1.3 20.1 0 105.9-107.7 192-240 192-10.8 0-21.3-.8-31.7-1.9C207.8 439.6 281.8 480 368 480c41 0 79.1-9.2 111.3-25 21.8 12.7 52.1 25 88.7 25 3.2 0 6.1-1.9 7.3-4.8 1.3-2.9.7-6.3-1.5-8.7-.3-.3-22.4-24.2-35.8-54.5z\"],\n    \"comments-dollar\": [576, 512, [], \"f653\", \"M416 192c0-88.37-93.12-160-208-160S0 103.63 0 192c0 34.27 14.13 65.95 37.97 91.98C24.61 314.22 2.52 338.16 2.2 338.5A7.995 7.995 0 0 0 8 352c36.58 0 66.93-12.25 88.73-24.98C128.93 342.76 167.02 352 208 352c114.88 0 208-71.63 208-160zm-224 96v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V96c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07V288c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm346.01 123.99C561.87 385.96 576 354.27 576 320c0-66.94-53.49-124.2-129.33-148.07.86 6.6 1.33 13.29 1.33 20.07 0 105.87-107.66 192-240 192-10.78 0-21.32-.77-31.73-1.88C207.8 439.63 281.77 480 368 480c40.98 0 79.07-9.24 111.27-24.98C501.07 467.75 531.42 480 568 480c3.2 0 6.09-1.91 7.34-4.84 1.27-2.94.66-6.34-1.55-8.67-.31-.33-22.42-24.24-35.78-54.5z\"],\n    \"compact-disc\": [496, 512, [], \"f51f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 256H56c0-105.9 86.1-192 192-192v32c-88.2 0-160 71.8-160 160zm160 96c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96zm0-128c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M225.38 233.37c-12.5 12.5-12.5 32.76 0 45.25 12.49 12.5 32.76 12.5 45.25 0 12.5-12.5 12.5-32.76 0-45.25-12.5-12.49-32.76-12.49-45.25 0zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm126.14 148.05L308.17 300.4a31.938 31.938 0 0 1-15.77 15.77l-144.34 65.97c-16.65 7.61-33.81-9.55-26.2-26.2l65.98-144.35a31.938 31.938 0 0 1 15.77-15.77l144.34-65.97c16.65-7.6 33.8 9.55 26.19 26.2z\"],\n    \"compress\": [448, 512, [], \"f066\", \"M436 192H312c-13.3 0-24-10.7-24-24V44c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v84h84c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm-276-24V44c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v84H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24zm0 300V344c0-13.3-10.7-24-24-24H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-84h84c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H312c-13.3 0-24 10.7-24 24v124c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"compress-arrows-alt\": [512, 512, [], \"f78c\", \"M200 288H88c-21.4 0-32.1 25.8-17 41l32.9 31-99.2 99.3c-6.2 6.2-6.2 16.4 0 22.6l25.4 25.4c6.2 6.2 16.4 6.2 22.6 0L152 408l31.1 33c15.1 15.1 40.9 4.4 40.9-17V312c0-13.3-10.7-24-24-24zm112-64h112c21.4 0 32.1-25.9 17-41l-33-31 99.3-99.3c6.2-6.2 6.2-16.4 0-22.6L481.9 4.7c-6.2-6.2-16.4-6.2-22.6 0L360 104l-31.1-33C313.8 55.9 288 66.6 288 88v112c0 13.3 10.7 24 24 24zm96 136l33-31.1c15.1-15.1 4.4-40.9-17-40.9H312c-13.3 0-24 10.7-24 24v112c0 21.4 25.9 32.1 41 17l31-32.9 99.3 99.3c6.2 6.2 16.4 6.2 22.6 0l25.4-25.4c6.2-6.2 6.2-16.4 0-22.6L408 360zM183 71.1L152 104 52.7 4.7c-6.2-6.2-16.4-6.2-22.6 0L4.7 30.1c-6.2 6.2-6.2 16.4 0 22.6L104 152l-33 31.1C55.9 198.2 66.6 224 88 224h112c13.3 0 24-10.7 24-24V88c0-21.3-25.9-32-41-16.9z\"],\n    \"concierge-bell\": [512, 512, [], \"f562\", \"M288 130.54V112h16c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h16v18.54C115.49 146.11 32 239.18 32 352h448c0-112.82-83.49-205.89-192-221.46zM496 384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"cookie\": [512, 512, [], \"f563\", \"M510.37 254.79l-12.08-76.26a132.493 132.493 0 0 0-37.16-72.95l-54.76-54.75c-19.73-19.72-45.18-32.7-72.71-37.05l-76.7-12.15c-27.51-4.36-55.69.11-80.52 12.76L107.32 49.6a132.25 132.25 0 0 0-57.79 57.8l-35.1 68.88a132.602 132.602 0 0 0-12.82 80.94l12.08 76.27a132.493 132.493 0 0 0 37.16 72.95l54.76 54.75a132.087 132.087 0 0 0 72.71 37.05l76.7 12.14c27.51 4.36 55.69-.11 80.52-12.75l69.12-35.21a132.302 132.302 0 0 0 57.79-57.8l35.1-68.87c12.71-24.96 17.2-53.3 12.82-80.96zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"cookie-bite\": [512, 512, [], \"f564\", \"M510.52 255.82c-69.97-.85-126.47-57.69-126.47-127.86-70.17 0-127-56.49-127.86-126.45-27.26-4.14-55.13.3-79.72 12.82l-69.13 35.22a132.221 132.221 0 0 0-57.79 57.81l-35.1 68.88a132.645 132.645 0 0 0-12.82 80.95l12.08 76.27a132.521 132.521 0 0 0 37.16 72.96l54.77 54.76a132.036 132.036 0 0 0 72.71 37.06l76.71 12.15c27.51 4.36 55.7-.11 80.53-12.76l69.13-35.21a132.273 132.273 0 0 0 57.79-57.81l35.1-68.88c12.56-24.64 17.01-52.58 12.91-79.91zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M320 448v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V120c0-13.255 10.745-24 24-24h72v296c0 30.879 25.121 56 56 56h168zm0-344V0H152c-13.255 0-24 10.745-24 24v368c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24V128H344c-13.2 0-24-10.8-24-24zm120.971-31.029L375.029 7.029A24 24 0 0 0 358.059 0H352v96h96v-6.059a24 24 0 0 0-7.029-16.97z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm117.134 346.753c-1.592 1.867-39.776 45.731-109.851 45.731-84.692 0-144.484-63.26-144.484-145.567 0-81.303 62.004-143.401 143.762-143.401 66.957 0 101.965 37.315 103.422 38.904a12 12 0 0 1 1.238 14.623l-22.38 34.655c-4.049 6.267-12.774 7.351-18.234 2.295-.233-.214-26.529-23.88-61.88-23.88-46.116 0-73.916 33.575-73.916 76.082 0 39.602 25.514 79.692 74.277 79.692 38.697 0 65.28-28.338 65.544-28.625 5.132-5.565 14.059-5.033 18.508 1.053l24.547 33.572a12.001 12.001 0 0 1-.553 14.866z\"],\n    \"couch\": [640, 512, [], \"f4b8\", \"M160 224v64h320v-64c0-35.3 28.7-64 64-64h32c0-53-43-96-96-96H160c-53 0-96 43-96 96h32c35.3 0 64 28.7 64 64zm416-32h-32c-17.7 0-32 14.3-32 32v96H128v-96c0-17.7-14.3-32-32-32H64c-35.3 0-64 28.7-64 64 0 23.6 13 44 32 55.1V432c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-16h384v16c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V311.1c19-11.1 32-31.5 32-55.1 0-35.3-28.7-64-64-64z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V256H0v176zm192-68c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-40zm-128 0c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM576 80v48H0V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48z\"],\n    \"crop\": [512, 512, [], \"f125\", \"M488 352h-40V109.25l59.31-59.31c6.25-6.25 6.25-16.38 0-22.63L484.69 4.69c-6.25-6.25-16.38-6.25-22.63 0L402.75 64H192v96h114.75L160 306.75V24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v264c0 13.25 10.75 24 24 24h232v-96H205.25L352 205.25V488c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"crop-alt\": [512, 512, [], \"f565\", \"M488 352h-40V96c0-17.67-14.33-32-32-32H192v96h160v328c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24zM160 24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v256c0 17.67 14.33 32 32 32h224v-96H160V24z\"],\n    \"cross\": [384, 512, [], \"f654\", \"M352 128h-96V32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h96v224c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V256h96c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"crosshairs\": [512, 512, [], \"f05b\", \"M500 224h-30.364C455.724 130.325 381.675 56.276 288 42.364V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v30.364C130.325 56.276 56.276 130.325 42.364 224H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h30.364C56.276 381.675 130.325 455.724 224 469.636V500c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-30.364C381.675 455.724 455.724 381.675 469.636 288H500c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zM288 404.634V364c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40.634C165.826 392.232 119.783 346.243 107.366 288H148c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40.634C119.768 165.826 165.757 119.783 224 107.366V148c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40.634C346.174 119.768 392.217 165.757 404.634 224H364c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40.634C392.232 346.174 346.243 392.217 288 404.634zM288 256c0 17.673-14.327 32-32 32s-32-14.327-32-32c0-17.673 14.327-32 32-32s32 14.327 32 32z\"],\n    \"crow\": [640, 512, [], \"f520\", \"M544 32h-16.36C513.04 12.68 490.09 0 464 0c-44.18 0-80 35.82-80 80v20.98L12.09 393.57A30.216 30.216 0 0 0 0 417.74c0 22.46 23.64 37.07 43.73 27.03L165.27 384h96.49l44.41 120.1c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38L312.94 384H352c1.91 0 3.76-.23 5.66-.29l44.51 120.38c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38l-41.24-111.53C485.74 352.8 544 279.26 544 192v-80l96-16c0-35.35-42.98-64-96-64zm-80 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"crown\": [640, 512, [], \"f521\", \"M528 448H112c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h416c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm64-320c-26.5 0-48 21.5-48 48 0 7.1 1.6 13.7 4.4 19.8L476 239.2c-15.4 9.2-35.3 4-44.2-11.6L350.3 85C361 76.2 368 63 368 48c0-26.5-21.5-48-48-48s-48 21.5-48 48c0 15 7 28.2 17.7 37l-81.5 142.6c-8.9 15.6-28.9 20.8-44.2 11.6l-72.3-43.4c2.7-6 4.4-12.7 4.4-19.8 0-26.5-21.5-48-48-48S0 149.5 0 176s21.5 48 48 48c2.6 0 5.2-.4 7.7-.8L128 416h384l72.3-192.8c2.5.4 5.1.8 7.7.8 26.5 0 48-21.5 48-48s-21.5-48-48-48z\"],\n    \"crutch\": [512, 512, [], \"f7f7\", \"M507.31 185.71l-181-181a16 16 0 0 0-22.62 0L281 27.31a16 16 0 0 0 0 22.63l181 181a16 16 0 0 0 22.63 0l22.62-22.63a16 16 0 0 0 .06-22.6zm-179.54 66.41l-67.89-67.89 55.1-55.1-45.25-45.25-109.67 109.67a96.08 96.08 0 0 0-25.67 46.29L106.65 360.1l-102 102a16 16 0 0 0 0 22.63l22.62 22.62a16 16 0 0 0 22.63 0l102-102 120.25-27.75a95.88 95.88 0 0 0 46.29-25.65l109.68-109.68L382.87 197zm-54.57 54.57a32 32 0 0 1-15.45 8.54l-79.3 18.32 18.3-79.3a32.22 32.22 0 0 1 8.56-15.45l9.31-9.31 67.89 67.89z\"],\n    \"cube\": [512, 512, [], \"f1b2\", \"M239.1 6.3l-208 78c-18.7 7-31.1 25-31.1 45v225.1c0 18.2 10.3 34.8 26.5 42.9l208 104c13.5 6.8 29.4 6.8 42.9 0l208-104c16.3-8.1 26.5-24.8 26.5-42.9V129.3c0-20-12.4-37.9-31.1-44.9l-208-78C262 2.2 250 2.2 239.1 6.3zM256 68.4l192 72v1.1l-192 78-192-78v-1.1l192-72zm32 356V275.5l160-65v133.9l-160 80z\"],\n    \"cubes\": [512, 512, [], \"f1b3\", \"M488.6 250.2L392 214V105.5c0-15-9.3-28.4-23.4-33.7l-100-37.5c-8.1-3.1-17.1-3.1-25.3 0l-100 37.5c-14.1 5.3-23.4 18.7-23.4 33.7V214l-96.6 36.2C9.3 255.5 0 268.9 0 283.9V394c0 13.6 7.7 26.1 19.9 32.2l100 50c10.1 5.1 22.1 5.1 32.2 0l103.9-52 103.9 52c10.1 5.1 22.1 5.1 32.2 0l100-50c12.2-6.1 19.9-18.6 19.9-32.2V283.9c0-15-9.3-28.4-23.4-33.7zM358 214.8l-85 31.9v-68.2l85-37v73.3zM154 104.1l102-38.2 102 38.2v.6l-102 41.4-102-41.4v-.6zm84 291.1l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6zm240 112l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6z\"],\n    \"cut\": [448, 512, [], \"f0c4\", \"M278.06 256L444.48 89.57c4.69-4.69 4.69-12.29 0-16.97-32.8-32.8-85.99-32.8-118.79 0L210.18 188.12l-24.86-24.86c4.31-10.92 6.68-22.81 6.68-35.26 0-53.02-42.98-96-96-96S0 74.98 0 128s42.98 96 96 96c4.54 0 8.99-.32 13.36-.93L142.29 256l-32.93 32.93c-4.37-.61-8.83-.93-13.36-.93-53.02 0-96 42.98-96 96s42.98 96 96 96 96-42.98 96-96c0-12.45-2.37-24.34-6.68-35.26l24.86-24.86L325.69 439.4c32.8 32.8 85.99 32.8 118.79 0 4.69-4.68 4.69-12.28 0-16.97L278.06 256zM96 160c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32zm0 256c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"database\": [448, 512, [], \"f1c0\", \"M448 73.143v45.714C448 159.143 347.667 192 224 192S0 159.143 0 118.857V73.143C0 32.857 100.333 0 224 0s224 32.857 224 73.143zM448 176v102.857C448 319.143 347.667 352 224 352S0 319.143 0 278.857V176c48.125 33.143 136.208 48.572 224 48.572S399.874 209.143 448 176zm0 160v102.857C448 479.143 347.667 512 224 512S0 479.143 0 438.857V336c48.125 33.143 136.208 48.572 224 48.572S399.874 369.143 448 336z\"],\n    \"deaf\": [512, 512, [], \"f2a4\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm268.485-52.201L480.2 3.515c-4.687-4.686-12.284-4.686-16.971 0L376.2 90.544c-4.686 4.686-4.686 12.284 0 16.971l28.285 28.285c4.686 4.686 12.284 4.686 16.97 0l87.03-87.029c4.687-4.688 4.687-12.286 0-16.972zM168.97 314.745c-4.686-4.686-12.284-4.686-16.97 0L3.515 463.23c-4.686 4.686-4.686 12.284 0 16.971L31.8 508.485c4.687 4.686 12.284 4.686 16.971 0L197.256 360c4.686-4.686 4.686-12.284 0-16.971l-28.286-28.284z\"],\n    \"democrat\": [640, 512, [], \"f747\", \"M637.3 256.9l-19.6-29.4c-28.2-42.3-75.3-67.5-126.1-67.5H256l-81.2-81.2c20.1-20.1 22.6-51.1 7.5-73.9-3.4-5.2-10.8-5.9-15.2-1.5l-41.8 41.8L82.4 2.4c-3.6-3.6-9.6-3-12.4 1.2-12.3 18.6-10.3 44 6.1 60.4 3.3 3.3 7.3 5.3 11.3 7.5-2.2 1.7-4.7 3.1-6.4 5.4L6.4 176.2c-7.3 9.7-8.4 22.7-3 33.5l14.3 28.6c5.4 10.8 16.5 17.7 28.6 17.7h31c8.5 0 16.6-3.4 22.6-9.4L138 212l54 108h352v-77.8c16.2 12.2 18.3 17.6 40.1 50.3 4.9 7.4 14.8 9.3 22.2 4.4l26.6-17.7c7.3-5 9.3-14.9 4.4-22.3zm-341.1-13.6l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L256 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L368 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L480 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zM192 496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80h160v80c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V352H192v144z\"],\n    \"desktop\": [576, 512, [], \"f108\", \"M528 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h192l-16 48h-72c-13.3 0-24 10.7-24 24s10.7 24 24 24h272c13.3 0 24-10.7 24-24s-10.7-24-24-24h-72l-16-48h192c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h448v288z\"],\n    \"dharmachakra\": [512, 512, [], \"f655\", \"M495 225.06l-17.22 1.08c-5.27-39.49-20.79-75.64-43.86-105.84l12.95-11.43c6.92-6.11 7.25-16.79.73-23.31L426.44 64.4c-6.53-6.53-17.21-6.19-23.31.73L391.7 78.07c-30.2-23.06-66.35-38.58-105.83-43.86L286.94 17c.58-9.21-6.74-17-15.97-17h-29.94c-9.23 0-16.54 7.79-15.97 17l1.08 17.22c-39.49 5.27-75.64 20.79-105.83 43.86l-11.43-12.95c-6.11-6.92-16.79-7.25-23.31-.73L64.4 85.56c-6.53 6.53-6.19 17.21.73 23.31l12.95 11.43c-23.06 30.2-38.58 66.35-43.86 105.84L17 225.06c-9.21-.58-17 6.74-17 15.97v29.94c0 9.23 7.79 16.54 17 15.97l17.22-1.08c5.27 39.49 20.79 75.64 43.86 105.83l-12.95 11.43c-6.92 6.11-7.25 16.79-.73 23.31l21.17 21.17c6.53 6.53 17.21 6.19 23.31-.73l11.43-12.95c30.2 23.06 66.35 38.58 105.84 43.86L225.06 495c-.58 9.21 6.74 17 15.97 17h29.94c9.23 0 16.54-7.79 15.97-17l-1.08-17.22c39.49-5.27 75.64-20.79 105.84-43.86l11.43 12.95c6.11 6.92 16.79 7.25 23.31.73l21.17-21.17c6.53-6.53 6.19-17.21-.73-23.31l-12.95-11.43c23.06-30.2 38.58-66.35 43.86-105.83l17.22 1.08c9.21.58 17-6.74 17-15.97v-29.94c-.01-9.23-7.8-16.54-17.01-15.97zM281.84 98.61c24.81 4.07 47.63 13.66 67.23 27.78l-42.62 48.29c-8.73-5.44-18.32-9.54-28.62-11.95l4.01-64.12zm-51.68 0l4.01 64.12c-10.29 2.41-19.89 6.52-28.62 11.95l-42.62-48.29c19.6-14.12 42.42-23.71 67.23-27.78zm-103.77 64.33l48.3 42.61c-5.44 8.73-9.54 18.33-11.96 28.62l-64.12-4.01c4.07-24.81 13.66-47.62 27.78-67.22zm-27.78 118.9l64.12-4.01c2.41 10.29 6.52 19.89 11.95 28.62l-48.29 42.62c-14.12-19.6-23.71-42.42-27.78-67.23zm131.55 131.55c-24.81-4.07-47.63-13.66-67.23-27.78l42.61-48.3c8.73 5.44 18.33 9.54 28.62 11.96l-4 64.12zM256 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm25.84 125.39l-4.01-64.12c10.29-2.41 19.89-6.52 28.62-11.96l42.61 48.3c-19.6 14.12-42.41 23.71-67.22 27.78zm103.77-64.33l-48.29-42.62c5.44-8.73 9.54-18.32 11.95-28.62l64.12 4.01c-4.07 24.82-13.66 47.64-27.78 67.23zm-36.34-114.89c-2.41-10.29-6.52-19.89-11.96-28.62l48.3-42.61c14.12 19.6 23.71 42.42 27.78 67.23l-64.12 4z\"],\n    \"diagnoses\": [640, 512, [], \"f470\", \"M496 256c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm-176-80c48.5 0 88-39.5 88-88S368.5 0 320 0s-88 39.5-88 88 39.5 88 88 88zM59.8 364c10.2 15.3 29.3 17.8 42.9 9.8 16.2-9.6 56.2-31.7 105.3-48.6V416h224v-90.7c49.1 16.8 89.1 39 105.3 48.6 13.6 8 32.7 5.3 42.9-9.8l17.8-26.7c8.8-13.2 7.6-34.6-10-45.1-11.9-7.1-29.7-17-51.1-27.4-28.1 46.1-99.4 17.8-87.7-35.1C409.3 217.2 365.1 208 320 208c-57 0-112.9 14.5-160 32.2-.2 40.2-47.6 63.3-79.2 36-11.2 6-21.3 11.6-28.7 16-17.6 10.5-18.8 31.8-10 45.1L59.8 364zM368 344c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-160 8c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm512 192H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dice\": [640, 512, [], \"f522\", \"M592 192H473.26c12.69 29.59 7.12 65.2-17 89.32L320 417.58V464c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48V240c0-26.51-21.49-48-48-48zM480 376c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm-46.37-186.7L258.7 14.37c-19.16-19.16-50.23-19.16-69.39 0L14.37 189.3c-19.16 19.16-19.16 50.23 0 69.39L189.3 433.63c19.16 19.16 50.23 19.16 69.39 0L433.63 258.7c19.16-19.17 19.16-50.24 0-69.4zM96 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"dice-d20\": [480, 512, [], \"f6cf\", \"M106.75 215.06L1.2 370.95c-3.08 5 .1 11.5 5.93 12.14l208.26 22.07-108.64-190.1zM7.41 315.43L82.7 193.08 6.06 147.1c-2.67-1.6-6.06.32-6.06 3.43v162.81c0 4.03 5.29 5.53 7.41 2.09zM18.25 423.6l194.4 87.66c5.3 2.45 11.35-1.43 11.35-7.26v-65.67l-203.55-22.3c-4.45-.5-6.23 5.59-2.2 7.57zm81.22-257.78L179.4 22.88c4.34-7.06-3.59-15.25-10.78-11.14L17.81 110.35c-2.47 1.62-2.39 5.26.13 6.78l81.53 48.69zM240 176h109.21L253.63 7.62C250.5 2.54 245.25 0 240 0s-10.5 2.54-13.63 7.62L130.79 176H240zm233.94-28.9l-76.64 45.99 75.29 122.35c2.11 3.44 7.41 1.94 7.41-2.1V150.53c0-3.11-3.39-5.03-6.06-3.43zm-93.41 18.72l81.53-48.7c2.53-1.52 2.6-5.16.13-6.78l-150.81-98.6c-7.19-4.11-15.12 4.08-10.78 11.14l79.93 142.94zm79.02 250.21L256 438.32v65.67c0 5.84 6.05 9.71 11.35 7.26l194.4-87.66c4.03-1.97 2.25-8.06-2.2-7.56zm-86.3-200.97l-108.63 190.1 208.26-22.07c5.83-.65 9.01-7.14 5.93-12.14L373.25 215.06zM240 208H139.57L240 383.75 340.43 208H240z\"],\n    \"dice-d6\": [448, 512, [], \"f6d1\", \"M422.19 109.95L256.21 9.07c-19.91-12.1-44.52-12.1-64.43 0L25.81 109.95c-5.32 3.23-5.29 11.27.06 14.46L224 242.55l198.14-118.14c5.35-3.19 5.38-11.22.05-14.46zm13.84 44.63L240 271.46v223.82c0 12.88 13.39 20.91 24.05 14.43l152.16-92.48c19.68-11.96 31.79-33.94 31.79-57.7v-197.7c0-6.41-6.64-10.43-11.97-7.25zM0 161.83v197.7c0 23.77 12.11 45.74 31.79 57.7l152.16 92.47c10.67 6.48 24.05-1.54 24.05-14.43V271.46L11.97 154.58C6.64 151.4 0 155.42 0 161.83z\"],\n    \"dice-five\": [448, 512, [], \"f523\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-four\": [448, 512, [], \"f524\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-one\": [448, 512, [], \"f525\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM224 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-six\": [448, 512, [], \"f526\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-three\": [448, 512, [], \"f527\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-two\": [448, 512, [], \"f528\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"digital-tachograph\": [640, 512, [], \"f566\", \"M608 96H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128c0-17.67-14.33-32-32-32zM304 352c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8zM72 288v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H80c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm40-64c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-48c0-8.84 7.16-16 16-16h208c8.84 0 16 7.16 16 16v48zm272 128c0 4.42-3.58 8-8 8H344c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8z\"],\n    \"directions\": [512, 512, [], \"f5eb\", \"M502.61 233.32L278.68 9.39c-12.52-12.52-32.83-12.52-45.36 0L9.39 233.32c-12.52 12.53-12.52 32.83 0 45.36l223.93 223.93c12.52 12.53 32.83 12.53 45.36 0l223.93-223.93c12.52-12.53 12.52-32.83 0-45.36zm-100.98 12.56l-84.21 77.73c-5.12 4.73-13.43 1.1-13.43-5.88V264h-96v64c0 4.42-3.58 8-8 8h-32c-4.42 0-8-3.58-8-8v-80c0-17.67 14.33-32 32-32h112v-53.73c0-6.97 8.3-10.61 13.43-5.88l84.21 77.73c3.43 3.17 3.43 8.59 0 11.76z\"],\n    \"divide\": [448, 512, [], \"f529\", \"M224 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm0-192c35.35 0 64-28.65 64-64s-28.65-64-64-64-64 28.65-64 64 28.65 64 64 64zm192 48H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-96 206.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L174.6 192l28.7 28.7c15.2 15.2-7.9 37.4-22.6 22.6L152 214.6zM248 416c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm147.3-195.3c15.2 15.2-7.9 37.4-22.6 22.6L344 214.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L366.6 192l28.7 28.7z\"],\n    \"dna\": [448, 512, [], \"f471\", \"M.1 494.1c-1.1 9.5 6.3 17.8 15.9 17.8l32.3.1c8.1 0 14.9-5.9 16-13.9.7-4.9 1.8-11.1 3.4-18.1H380c1.6 6.9 2.9 13.2 3.5 18.1 1.1 8 7.9 14 16 13.9l32.3-.1c9.6 0 17.1-8.3 15.9-17.8-4.6-37.9-25.6-129-118.9-207.7-17.6 12.4-37.1 24.2-58.5 35.4 6.2 4.6 11.4 9.4 17 14.2H159.7c21.3-18.1 47-35.6 78.7-51.4C410.5 199.1 442.1 65.8 447.9 17.9 449 8.4 441.6.1 432 .1L399.6 0c-8.1 0-14.9 5.9-16 13.9-.7 4.9-1.8 11.1-3.4 18.1H67.8c-1.6-7-2.7-13.1-3.4-18.1-1.1-8-7.9-14-16-13.9L16.1.1C6.5.1-1 8.4.1 17.9 5.3 60.8 31.4 171.8 160 256 31.5 340.2 5.3 451.2.1 494.1zM224 219.6c-25.1-13.7-46.4-28.4-64.3-43.6h128.5c-17.8 15.2-39.1 30-64.2 43.6zM355.1 96c-5.8 10.4-12.8 21.1-21 32H114c-8.3-10.9-15.3-21.6-21-32h262.1zM92.9 416c5.8-10.4 12.8-21.1 21-32h219.4c8.3 10.9 15.4 21.6 21.2 32H92.9z\"],\n    \"dog\": [512, 512, [], \"f6d3\", \"M496 96h-64l-7.16-14.31A32 32 0 0 0 396.22 64H342.6l-27.28-27.28C305.23 26.64 288 33.78 288 48.03v149.84l128 45.71V208h32c35.35 0 64-28.65 64-64v-32c0-8.84-7.16-16-16-16zm-112 48c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM96 224c-17.64 0-32-14.36-32-32 0-17.67-14.33-32-32-32S0 174.33 0 192c0 41.66 26.83 76.85 64 90.1V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V384h160v112c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V277.55L266.05 224H96z\"],\n    \"dollar-sign\": [288, 512, [], \"f155\", \"M209.2 233.4l-108-31.6C88.7 198.2 80 186.5 80 173.5c0-16.3 13.2-29.5 29.5-29.5h66.3c12.2 0 24.2 3.7 34.2 10.5 6.1 4.1 14.3 3.1 19.5-2l34.8-34c7.1-6.9 6.1-18.4-1.8-24.5C238 74.8 207.4 64.1 176 64V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48h-2.5C45.8 64-5.4 118.7.5 183.6c4.2 46.1 39.4 83.6 83.8 96.6l102.5 30c12.5 3.7 21.2 15.3 21.2 28.3 0 16.3-13.2 29.5-29.5 29.5h-66.3C100 368 88 364.3 78 357.5c-6.1-4.1-14.3-3.1-19.5 2l-34.8 34c-7.1 6.9-6.1 18.4 1.8 24.5 24.5 19.2 55.1 29.9 86.5 30v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48.2c46.6-.9 90.3-28.6 105.7-72.7 21.5-61.6-14.6-124.8-72.5-141.7z\"],\n    \"dolly\": [576, 512, [], \"f472\", \"M294.2 277.7c18 5 34.7 13.4 49.5 24.7l161.5-53.8c8.4-2.8 12.9-11.9 10.1-20.2L454.9 47.2c-2.8-8.4-11.9-12.9-20.2-10.1l-61.1 20.4 33.1 99.4L346 177l-33.1-99.4-61.6 20.5c-8.4 2.8-12.9 11.9-10.1 20.2l53 159.4zm281 48.7L565 296c-2.8-8.4-11.9-12.9-20.2-10.1l-213.5 71.2c-17.2-22-43.6-36.4-73.5-37L158.4 21.9C154 8.8 141.8 0 128 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h88.9l92.2 276.7c-26.1 20.4-41.7 53.6-36 90.5 6.1 39.4 37.9 72.3 77.3 79.2 60.2 10.7 112.3-34.8 113.4-92.6l213.3-71.2c8.3-2.8 12.9-11.8 10.1-20.2zM256 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"dolly-flatbed\": [640, 512, [], \"f474\", \"M208 320h384c8.8 0 16-7.2 16-16V48c0-8.8-7.2-16-16-16H448v128l-48-32-48 32V32H208c-8.8 0-16 7.2-16 16v256c0 8.8 7.2 16 16 16zm416 64H128V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h82.9c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H451c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H624c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"donate\": [512, 512, [], \"f4b9\", \"M256 416c114.9 0 208-93.1 208-208S370.9 0 256 0 48 93.1 48 208s93.1 208 208 208zM233.8 97.4V80.6c0-9.2 7.4-16.6 16.6-16.6h11.1c9.2 0 16.6 7.4 16.6 16.6v17c15.5.8 30.5 6.1 43 15.4 5.6 4.1 6.2 12.3 1.2 17.1L306 145.6c-3.8 3.7-9.5 3.8-14 1-5.4-3.4-11.4-5.1-17.8-5.1h-38.9c-9 0-16.3 8.2-16.3 18.3 0 8.2 5 15.5 12.1 17.6l62.3 18.7c25.7 7.7 43.7 32.4 43.7 60.1 0 34-26.4 61.5-59.1 62.4v16.8c0 9.2-7.4 16.6-16.6 16.6h-11.1c-9.2 0-16.6-7.4-16.6-16.6v-17c-15.5-.8-30.5-6.1-43-15.4-5.6-4.1-6.2-12.3-1.2-17.1l16.3-15.5c3.8-3.7 9.5-3.8 14-1 5.4 3.4 11.4 5.1 17.8 5.1h38.9c9 0 16.3-8.2 16.3-18.3 0-8.2-5-15.5-12.1-17.6l-62.3-18.7c-25.7-7.7-43.7-32.4-43.7-60.1.1-34 26.4-61.5 59.1-62.4zM480 352h-32.5c-19.6 26-44.6 47.7-73 64h63.8c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8h63.8c-28.4-16.3-53.3-38-73-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32z\"],\n    \"door-closed\": [640, 512, [], \"f52a\", \"M624 448H512V50.8C512 22.78 490.47 0 464 0H175.99c-26.47 0-48 22.78-48 50.8V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM415.99 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32c.01 17.67-14.32 32-32 32z\"],\n    \"door-open\": [640, 512, [], \"f52b\", \"M624 448h-80V113.45C544 86.19 522.47 64 496 64H384v64h96v384h144c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM312.24 1.01l-192 49.74C105.99 54.44 96 67.7 96 82.92V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h336V33.18c0-21.58-19.56-37.41-39.76-32.17zM264 288c-13.25 0-24-14.33-24-32s10.75-32 24-32 24 14.33 24 32-10.75 32-24 32z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm80 248c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80z\"],\n    \"dove\": [512, 512, [], \"f4ba\", \"M288 167.2v-28.1c-28.2-36.3-47.1-79.3-54.1-125.2-2.1-13.5-19-18.8-27.8-8.3-21.1 24.9-37.7 54.1-48.9 86.5 34.2 38.3 80 64.6 130.8 75.1zM400 64c-44.2 0-80 35.9-80 80.1v59.4C215.6 197.3 127 133 87 41.8c-5.5-12.5-23.2-13.2-29-.9C41.4 76 32 115.2 32 156.6c0 70.8 34.1 136.9 85.1 185.9 13.2 12.7 26.1 23.2 38.9 32.8l-143.9 36C1.4 414-3.4 426.4 2.6 435.7 20 462.6 63 508.2 155.8 512c8 .3 16-2.6 22.1-7.9l65.2-56.1H320c88.4 0 160-71.5 160-159.9V128l32-64H400zm0 96.1c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"download\": [512, 512, [], \"f019\", \"M216 0h80c13.3 0 24 10.7 24 24v168h87.7c17.8 0 26.7 21.5 14.1 34.1L269.7 378.3c-7.5 7.5-19.8 7.5-27.3 0L90.1 226.1c-12.6-12.6-3.7-34.1 14.1-34.1H192V24c0-13.3 10.7-24 24-24zm296 376v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h146.7l49 49c20.1 20.1 52.5 20.1 72.6 0l49-49H488c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"drafting-compass\": [512, 512, [], \"f568\", \"M457.01 344.42c-25.05 20.33-52.63 37.18-82.54 49.05l54.38 94.19 53.95 23.04c9.81 4.19 20.89-2.21 22.17-12.8l7.02-58.25-54.98-95.23zm42.49-94.56c4.86-7.67 1.89-17.99-6.05-22.39l-28.07-15.57c-7.48-4.15-16.61-1.46-21.26 5.72C403.01 281.15 332.25 320 256 320c-23.93 0-47.23-4.25-69.41-11.53l67.36-116.68c.7.02 1.34.21 2.04.21s1.35-.19 2.04-.21l51.09 88.5c31.23-8.96 59.56-25.75 82.61-48.92l-51.79-89.71C347.39 128.03 352 112.63 352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96c0 16.63 4.61 32.03 12.05 45.66l-68.3 118.31c-12.55-11.61-23.96-24.59-33.68-39-4.79-7.1-13.97-9.62-21.38-5.33l-27.75 16.07c-7.85 4.54-10.63 14.9-5.64 22.47 15.57 23.64 34.69 44.21 55.98 62.02L0 439.66l7.02 58.25c1.28 10.59 12.36 16.99 22.17 12.8l53.95-23.04 70.8-122.63C186.13 377.28 220.62 384 256 384c99.05 0 190.88-51.01 243.5-134.14zM256 64c17.67 0 32 14.33 32 32s-14.33 32-32 32-32-14.33-32-32 14.33-32 32-32z\"],\n    \"dragon\": [640, 512, [], \"f6d5\", \"M18.32 255.78L192 223.96l-91.28 68.69c-10.08 10.08-2.94 27.31 11.31 27.31h222.7c-9.44-26.4-14.73-54.47-14.73-83.38v-42.27l-119.73-87.6c-23.82-15.88-55.29-14.01-77.06 4.59L5.81 227.64c-12.38 10.33-3.45 30.42 12.51 28.14zm556.87 34.1l-100.66-50.31A47.992 47.992 0 0 1 448 196.65v-36.69h64l28.09 22.63c6 6 14.14 9.37 22.63 9.37h30.97a32 32 0 0 0 28.62-17.69l14.31-28.62a32.005 32.005 0 0 0-3.02-33.51l-74.53-99.38C553.02 4.7 543.54 0 533.47 0H296.02c-7.13 0-10.7 8.57-5.66 13.61L352 63.96 292.42 88.8c-5.9 2.95-5.9 11.36 0 14.31L352 127.96v108.62c0 72.08 36.03 139.39 96 179.38-195.59 6.81-344.56 41.01-434.1 60.91C5.78 478.67 0 485.88 0 494.2 0 504 7.95 512 17.76 512h499.08c63.29.01 119.61-47.56 122.99-110.76 2.52-47.28-22.73-90.4-64.64-111.36zM489.18 66.25l45.65 11.41c-2.75 10.91-12.47 18.89-24.13 18.26-12.96-.71-25.85-12.53-21.52-29.67z\"],\n    \"draw-polygon\": [448, 512, [], \"f5ee\", \"M384 352c-.35 0-.67.1-1.02.1l-39.2-65.32c5.07-9.17 8.22-19.56 8.22-30.78s-3.14-21.61-8.22-30.78l39.2-65.32c.35.01.67.1 1.02.1 35.35 0 64-28.65 64-64s-28.65-64-64-64c-23.63 0-44.04 12.95-55.12 32H119.12C108.04 44.95 87.63 32 64 32 28.65 32 0 60.65 0 96c0 23.63 12.95 44.04 32 55.12v209.75C12.95 371.96 0 392.37 0 416c0 35.35 28.65 64 64 64 23.63 0 44.04-12.95 55.12-32h209.75c11.09 19.05 31.49 32 55.12 32 35.35 0 64-28.65 64-64 .01-35.35-28.64-64-63.99-64zm-288 8.88V151.12A63.825 63.825 0 0 0 119.12 128h208.36l-38.46 64.1c-.35-.01-.67-.1-1.02-.1-35.35 0-64 28.65-64 64s28.65 64 64 64c.35 0 .67-.1 1.02-.1l38.46 64.1H119.12A63.748 63.748 0 0 0 96 360.88zM272 256c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zM400 96c0 8.82-7.18 16-16 16s-16-7.18-16-16 7.18-16 16-16 16 7.18 16 16zM64 80c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zM48 416c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zm336 16c-8.82 0-16-7.18-16-16s7.18-16 16-16 16 7.18 16 16-7.18 16-16 16z\"],\n    \"drum\": [576, 512, [], \"f569\", \"M458.08 120.88l102.39-61.43c15.16-9.09 20.06-28.75 10.97-43.91C562.34.39 542.7-4.53 527.53 4.57l-160.69 96.41A629.32 629.32 0 0 0 288 96C128.94 96 0 153.31 0 224v160.83c0 30.46 24.03 58.4 64 80.37v-96.37c0-17.6 14.4-32 32-32s32 14.4 32 32v122.41c37.4 11.13 81 18.44 128 20.75V400.84c0-17.6 14.4-32 32-32s32 14.4 32 32V512c47-2.31 90.6-9.62 128-20.75V368.84c0-17.6 14.4-32 32-32s32 14.4 32 32v96.37c39.97-21.97 64-49.91 64-80.37V224.01c-.01-42.38-46.54-79.84-117.92-103.13zM288 304c-132.55 0-240-35.82-240-80s107.45-80 240-80c2.34 0 4.62.1 6.94.12l-87.41 52.44c-15.16 9.09-20.06 28.75-10.97 43.91 9.56 15.93 29.51 19.61 43.91 10.97l162.71-97.62C477.55 167.41 528 193.74 528 224.01 528 268.19 420.54 304 288 304z\"],\n    \"drum-steelpan\": [576, 512, [], \"f56a\", \"M288 32C128.94 32 0 89.31 0 160v192c0 70.69 128.94 128 288 128s288-57.31 288-128V160c0-70.69-128.94-128-288-128zm-82.99 158.36c-4.45 16.61-14.54 30.57-28.31 40.48C100.23 217.46 48 190.78 48 160c0-30.16 50.11-56.39 124.04-70.03l25.6 44.34c9.86 17.09 12.48 36.99 7.37 56.05zM288 240c-21.08 0-41.41-1-60.89-2.7 8.06-26.13 32.15-45.3 60.89-45.3s52.83 19.17 60.89 45.3C329.41 239 309.08 240 288 240zm64-144c0 35.29-28.71 64-64 64s-64-28.71-64-64V82.96c20.4-1.88 41.8-2.96 64-2.96s43.6 1.08 64 2.96V96zm46.93 134.9c-13.81-9.91-23.94-23.9-28.4-40.54-5.11-19.06-2.49-38.96 7.38-56.04l25.65-44.42C477.72 103.5 528 129.79 528 160c0 30.83-52.4 57.54-129.07 70.9z\"],\n    \"drumstick-bite\": [512, 512, [], \"f6d7\", \"M462.8 49.57a169.44 169.44 0 0 0-239.5 0C187.82 85 160.13 128 160.13 192v85.83l-40.62 40.59c-9.7 9.69-24 11.07-36.78 6a60.33 60.33 0 0 0-65 98.72C33 438.39 54.24 442.7 73.85 438.21c-4.5 19.6-.18 40.83 15.1 56.1a60.35 60.35 0 0 0 98.8-65c-5.09-12.73-3.72-27 6-36.75L234.36 352h85.89a187.87 187.87 0 0 0 61.89-10c-39.64-43.89-39.83-110.23 1.05-151.07 34.38-34.36 86.76-39.46 128.74-16.8 1.3-44.96-14.81-90.28-49.13-124.56z\"],\n    \"dumbbell\": [640, 512, [], \"f44b\", \"M104 96H56c-13.3 0-24 10.7-24 24v104H8c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h24v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm528 128h-24V120c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v272c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h24c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zM456 32h-48c-13.3 0-24 10.7-24 24v168H256V56c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v400c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h128v168c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24z\"],\n    \"dumpster\": [576, 512, [], \"f793\", \"M560 160c10.4 0 18-9.8 15.5-19.9l-24-96C549.7 37 543.3 32 536 32h-98.9l25.6 128H560zM272 32H171.5l-25.6 128H272V32zm132.5 0H304v128h126.1L404.5 32zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm544 64h-20l4-32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h320v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16l20-160h28c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dumpster-fire\": [640, 512, [], \"f794\", \"M418.7 104.1l.2-.2-14.4-72H304v128h60.8c16.2-19.3 34.2-38.2 53.9-55.8zM272 32H171.5l-25.6 128H272V32zm189.3 72.1c18.2 16.3 35.5 33.7 51.1 51.5 5.7-5.6 11.4-11.1 17.3-16.3l21.3-19 21.3 19c1.1.9 2.1 2.1 3.1 3.1-.1-.8.2-1.5 0-2.3l-24-96C549.7 37 543.3 32 536 32h-98.9l12.3 61.5 11.9 10.6zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm324.6 32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208.8c-30.2-33.7-48.8-77.9-48.8-126.4 0-35.9 19.9-82.9 52.6-129.6zm210.5-28.8c-14.9 13.3-28.3 27.2-40.2 41.2-19.5-25.8-43.6-52-71-76.4-70.2 62.7-120 144.3-120 193.6 0 87.5 71.6 158.4 160 158.4s160-70.9 160-158.4c.1-36.6-37-112.2-88.8-158.4zm-18.6 229.4c-14.7 10.7-32.9 17-52.5 17-49 0-88.9-33.5-88.9-88 0-27.1 16.5-51 49.4-91.9 4.7 5.6 67.1 88.1 67.1 88.1l39.8-47c2.8 4.8 5.4 9.5 7.7 14 18.6 36.7 10.8 83.6-22.6 107.8z\"],\n    \"dungeon\": [512, 512, [], \"f6d9\", \"M128.73 195.32l-82.81-51.76c-8.04-5.02-18.99-2.17-22.93 6.45A254.19 254.19 0 0 0 .54 239.28C-.05 248.37 7.59 256 16.69 256h97.13c7.96 0 14.08-6.25 15.01-14.16 1.09-9.33 3.24-18.33 6.24-26.94 2.56-7.34.25-15.46-6.34-19.58zM319.03 8C298.86 2.82 277.77 0 256 0s-42.86 2.82-63.03 8c-9.17 2.35-13.91 12.6-10.39 21.39l37.47 104.03A16.003 16.003 0 0 0 235.1 144h41.8c6.75 0 12.77-4.23 15.05-10.58l37.47-104.03c3.52-8.79-1.22-19.03-10.39-21.39zM112 288H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm77.31-283.67l-36.32-90.8c-3.53-8.83-14.13-12.99-22.42-8.31a257.308 257.308 0 0 0-71.61 59.89c-6.06 7.32-3.85 18.48 4.22 23.52l82.93 51.83c6.51 4.07 14.66 2.62 20.11-2.79 5.18-5.15 10.79-9.85 16.79-14.05 6.28-4.41 9.15-12.17 6.3-19.29zM398.18 256h97.13c9.1 0 16.74-7.63 16.15-16.72a254.135 254.135 0 0 0-22.45-89.27c-3.94-8.62-14.89-11.47-22.93-6.45l-82.81 51.76c-6.59 4.12-8.9 12.24-6.34 19.58 3.01 8.61 5.15 17.62 6.24 26.94.93 7.91 7.05 14.16 15.01 14.16zm54.85-162.89a257.308 257.308 0 0 0-71.61-59.89c-8.28-4.68-18.88-.52-22.42 8.31l-36.32 90.8c-2.85 7.12.02 14.88 6.3 19.28 6 4.2 11.61 8.9 16.79 14.05 5.44 5.41 13.6 6.86 20.11 2.79l82.93-51.83c8.07-5.03 10.29-16.19 4.22-23.51zM496 288h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zM240 177.62V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V177.62c-5.23-.89-10.52-1.62-16-1.62s-10.77.73-16 1.62zm-64 41.51V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V189.36c-12.78 7.45-23.84 17.47-32 29.77zm128-29.77V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V219.13c-8.16-12.3-19.22-22.32-32-29.77z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.6 83.2l90.2 90.2c3.8 3.8 3.8 10 0 13.8L274.4 405.6l-92.8 10.3c-12.4 1.4-22.9-9.1-21.5-21.5l10.3-92.8L388.8 83.2c3.8-3.8 10-3.8 13.8 0zm162-22.9l-48.8-48.8c-15.2-15.2-39.9-15.2-55.2 0l-35.4 35.4c-3.8 3.8-3.8 10 0 13.8l90.2 90.2c3.8 3.8 10 3.8 13.8 0l35.4-35.4c15.2-15.3 15.2-40 0-55.2zM384 346.2V448H64V128h229.8c3.2 0 6.2-1.3 8.5-3.5l40-40c7.6-7.6 2.2-20.5-8.5-20.5H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V306.2c0-10.7-12.9-16-20.5-8.5l-40 40c-2.2 2.3-3.5 5.3-3.5 8.5z\"],\n    \"egg\": [384, 512, [], \"f7fb\", \"M192 0C86 0 0 214 0 320s86 192 192 192 192-86 192-192S298 0 192 0z\"],\n    \"eject\": [448, 512, [], \"f052\", \"M448 384v64c0 17.673-14.327 32-32 32H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h384c17.673 0 32 14.327 32 32zM48.053 320h351.886c41.651 0 63.581-49.674 35.383-80.435L259.383 47.558c-19.014-20.743-51.751-20.744-70.767 0L12.67 239.565C-15.475 270.268 6.324 320 48.053 320z\"],\n    \"ellipsis-h\": [512, 512, [], \"f141\", \"M328 256c0 39.8-32.2 72-72 72s-72-32.2-72-72 32.2-72 72-72 72 32.2 72 72zm104-72c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm-352 0c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72z\"],\n    \"ellipsis-v\": [192, 512, [], \"f142\", \"M96 184c39.8 0 72 32.2 72 72s-32.2 72-72 72-72-32.2-72-72 32.2-72 72-72zM24 80c0 39.8 32.2 72 72 72s72-32.2 72-72S135.8 8 96 8 24 40.2 24 80zm0 352c0 39.8 32.2 72 72 72s72-32.2 72-72-32.2-72-72-72-72 32.2-72 72z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M502.3 190.8c3.9-3.1 9.7-.2 9.7 4.7V400c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V195.6c0-5 5.7-7.8 9.7-4.7 22.4 17.4 52.1 39.5 154.1 113.6 21.1 15.4 56.7 47.8 92.2 47.6 35.7.3 72-32.8 92.3-47.6 102-74.1 131.6-96.3 154-113.7zM256 320c23.2.4 56.6-29.2 73.4-41.4 132.7-96.3 142.8-104.7 173.4-128.7 5.8-4.5 9.2-11.5 9.2-18.9v-19c0-26.5-21.5-48-48-48H48C21.5 64 0 85.5 0 112v19c0 7.4 3.4 14.3 9.2 18.9 30.6 23.9 40.7 32.4 173.4 128.7 16.8 12.2 50.2 41.8 73.4 41.4z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M512 464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V200.724a48 48 0 0 1 18.387-37.776c24.913-19.529 45.501-35.365 164.2-121.511C199.412 29.17 232.797-.347 256 .003c23.198-.354 56.596 29.172 73.413 41.433 118.687 86.137 139.303 101.995 164.2 121.512A48 48 0 0 1 512 200.724V464zm-65.666-196.605c-2.563-3.728-7.7-4.595-11.339-1.907-22.845 16.873-55.462 40.705-105.582 77.079-16.825 12.266-50.21 41.781-73.413 41.43-23.211.344-56.559-29.143-73.413-41.43-50.114-36.37-82.734-60.204-105.582-77.079-3.639-2.688-8.776-1.821-11.339 1.907l-9.072 13.196a7.998 7.998 0 0 0 1.839 10.967c22.887 16.899 55.454 40.69 105.303 76.868 20.274 14.781 56.524 47.813 92.264 47.573 35.724.242 71.961-32.771 92.263-47.573 49.85-36.179 82.418-59.97 105.303-76.868a7.998 7.998 0 0 0 1.839-10.967l-9.071-13.196z\"],\n    \"envelope-open-text\": [512, 512, [], \"f658\", \"M176 216h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16zm-16 80c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16zm96 121.13c-16.42 0-32.84-5.06-46.86-15.19L0 250.86V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V250.86L302.86 401.94c-14.02 10.12-30.44 15.19-46.86 15.19zm237.61-254.18c-8.85-6.94-17.24-13.47-29.61-22.81V96c0-26.51-21.49-48-48-48h-77.55c-3.04-2.2-5.87-4.26-9.04-6.56C312.6 29.17 279.2-.35 256 0c-23.2-.35-56.59 29.17-73.41 41.44-3.17 2.3-6 4.36-9.04 6.56H96c-26.51 0-48 21.49-48 48v44.14c-12.37 9.33-20.76 15.87-29.61 22.81A47.995 47.995 0 0 0 0 200.72v10.65l96 69.35V96h320v184.72l96-69.35v-10.65c0-14.74-6.78-28.67-18.39-37.77z\"],\n    \"envelope-square\": [448, 512, [], \"f199\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM178.117 262.104C87.429 196.287 88.353 196.121 64 177.167V152c0-13.255 10.745-24 24-24h272c13.255 0 24 10.745 24 24v25.167c-24.371 18.969-23.434 19.124-114.117 84.938-10.5 7.655-31.392 26.12-45.883 25.894-14.503.218-35.367-18.227-45.883-25.895zM384 217.775V360c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V217.775c13.958 10.794 33.329 25.236 95.303 70.214 14.162 10.341 37.975 32.145 64.694 32.01 26.887.134 51.037-22.041 64.72-32.025 61.958-44.965 81.325-59.406 95.283-70.199z\"],\n    \"equals\": [448, 512, [], \"f52c\", \"M416 304H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32zm0-192H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"eraser\": [512, 512, [], \"f12d\", \"M497.941 273.941c18.745-18.745 18.745-49.137 0-67.882l-160-160c-18.745-18.745-49.136-18.746-67.883 0l-256 256c-18.745 18.745-18.745 49.137 0 67.882l96 96A48.004 48.004 0 0 0 144 480h356c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H355.883l142.058-142.059zm-302.627-62.627l137.373 137.373L265.373 416H150.628l-80-80 124.686-124.686z\"],\n    \"ethernet\": [512, 512, [], \"f796\", \"M496 192h-48v-48c0-8.8-7.2-16-16-16h-48V80c0-8.8-7.2-16-16-16H144c-8.8 0-16 7.2-16 16v48H80c-8.8 0-16 7.2-16 16v48H16c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16h80V320h32v128h64V320h32v128h64V320h32v128h64V320h32v128h80c8.8 0 16-7.2 16-16V208c0-8.8-7.2-16-16-16z\"],\n    \"euro-sign\": [320, 512, [], \"f153\", \"M310.706 413.765c-1.314-6.63-7.835-10.872-14.424-9.369-10.692 2.439-27.422 5.413-45.426 5.413-56.763 0-101.929-34.79-121.461-85.449h113.689a12 12 0 0 0 11.708-9.369l6.373-28.36c1.686-7.502-4.019-14.631-11.708-14.631H115.22c-1.21-14.328-1.414-28.287.137-42.245H261.95a12 12 0 0 0 11.723-9.434l6.512-29.755c1.638-7.484-4.061-14.566-11.723-14.566H130.184c20.633-44.991 62.69-75.03 117.619-75.03 14.486 0 28.564 2.25 37.851 4.145 6.216 1.268 12.347-2.498 14.002-8.623l11.991-44.368c1.822-6.741-2.465-13.616-9.326-14.917C290.217 34.912 270.71 32 249.635 32 152.451 32 74.03 92.252 45.075 176H12c-6.627 0-12 5.373-12 12v29.755c0 6.627 5.373 12 12 12h21.569c-1.009 13.607-1.181 29.287-.181 42.245H12c-6.627 0-12 5.373-12 12v28.36c0 6.627 5.373 12 12 12h30.114C67.139 414.692 145.264 480 249.635 480c26.301 0 48.562-4.544 61.101-7.788 6.167-1.595 10.027-7.708 8.788-13.957l-8.818-44.49z\"],\n    \"exchange-alt\": [512, 512, [], \"f362\", \"M0 168v-16c0-13.255 10.745-24 24-24h360V80c0-21.367 25.899-32.042 40.971-16.971l80 80c9.372 9.373 9.372 24.569 0 33.941l-80 80C409.956 271.982 384 261.456 384 240v-48H24c-13.255 0-24-10.745-24-24zm488 152H128v-48c0-21.314-25.862-32.08-40.971-16.971l-80 80c-9.372 9.373-9.372 24.569 0 33.941l80 80C102.057 463.997 128 453.437 128 432v-48h360c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"exclamation\": [192, 512, [], \"f12a\", \"M176 432c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zM25.26 25.199l13.6 272C39.499 309.972 50.041 320 62.83 320h66.34c12.789 0 23.331-10.028 23.97-22.801l13.6-272C167.425 11.49 156.496 0 142.77 0H49.23C35.504 0 24.575 11.49 25.26 25.199z\"],\n    \"exclamation-circle\": [512, 512, [], \"f06a\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zm-248 50c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"exclamation-triangle\": [576, 512, [], \"f071\", \"M569.517 440.013C587.975 472.007 564.806 512 527.94 512H48.054c-36.937 0-59.999-40.055-41.577-71.987L246.423 23.985c18.467-32.009 64.72-31.951 83.154 0l239.94 416.028zM288 354c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"expand\": [448, 512, [], \"f065\", \"M0 180V56c0-13.3 10.7-24 24-24h124c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H64v84c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12zM288 44v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V56c0-13.3-10.7-24-24-24H300c-6.6 0-12 5.4-12 12zm148 276h-40c-6.6 0-12 5.4-12 12v84h-84c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24V332c0-6.6-5.4-12-12-12zM160 468v-40c0-6.6-5.4-12-12-12H64v-84c0-6.6-5.4-12-12-12H12c-6.6 0-12 5.4-12 12v124c0 13.3 10.7 24 24 24h124c6.6 0 12-5.4 12-12z\"],\n    \"expand-arrows-alt\": [448, 512, [], \"f31e\", \"M448 344v112a23.94 23.94 0 0 1-24 24H312c-21.39 0-32.09-25.9-17-41l36.2-36.2L224 295.6 116.77 402.9 153 439c15.09 15.1 4.39 41-17 41H24a23.94 23.94 0 0 1-24-24V344c0-21.4 25.89-32.1 41-17l36.19 36.2L184.46 256 77.18 148.7 41 185c-15.1 15.1-41 4.4-41-17V56a23.94 23.94 0 0 1 24-24h112c21.39 0 32.09 25.9 17 41l-36.2 36.2L224 216.4l107.23-107.3L295 73c-15.09-15.1-4.39-41 17-41h112a23.94 23.94 0 0 1 24 24v112c0 21.4-25.89 32.1-41 17l-36.19-36.2L263.54 256l107.28 107.3L407 327.1c15.1-15.2 41-4.5 41 16.9z\"],\n    \"external-link-alt\": [576, 512, [], \"f35d\", \"M576 24v127.984c0 21.461-25.96 31.98-40.971 16.971l-35.707-35.709-243.523 243.523c-9.373 9.373-24.568 9.373-33.941 0l-22.627-22.627c-9.373-9.373-9.373-24.569 0-33.941L442.756 76.676l-35.703-35.705C391.982 25.9 402.656 0 424.024 0H552c13.255 0 24 10.745 24 24zM407.029 270.794l-16 16A23.999 23.999 0 0 0 384 303.765V448H64V128h264a24.003 24.003 0 0 0 16.97-7.029l16-16C376.089 89.851 365.381 64 344 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V287.764c0-21.382-25.852-32.09-40.971-16.97z\"],\n    \"external-link-square-alt\": [448, 512, [], \"f360\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-88 16H248.029c-21.313 0-32.08 25.861-16.971 40.971l31.984 31.987L67.515 364.485c-4.686 4.686-4.686 12.284 0 16.971l31.029 31.029c4.687 4.686 12.285 4.686 16.971 0l195.526-195.526 31.988 31.991C358.058 263.977 384 253.425 384 231.979V120c0-13.255-10.745-24-24-24z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M572.52 241.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400a144 144 0 1 1 144-144 143.93 143.93 0 0 1-144 144zm0-240a95.31 95.31 0 0 0-25.31 3.79 47.85 47.85 0 0 1-66.9 66.9A95.78 95.78 0 1 0 288 160z\"],\n    \"eye-dropper\": [512, 512, [], \"f1fb\", \"M50.75 333.25c-12 12-18.75 28.28-18.75 45.26V424L0 480l32 32 56-32h45.49c16.97 0 33.25-6.74 45.25-18.74l126.64-126.62-128-128L50.75 333.25zM483.88 28.12c-37.47-37.5-98.28-37.5-135.75 0l-77.09 77.09-13.1-13.1c-9.44-9.44-24.65-9.31-33.94 0l-40.97 40.97c-9.37 9.37-9.37 24.57 0 33.94l161.94 161.94c9.44 9.44 24.65 9.31 33.94 0L419.88 288c9.37-9.37 9.37-24.57 0-33.94l-13.1-13.1 77.09-77.09c37.51-37.48 37.51-98.26.01-135.75z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M320 400c-75.85 0-137.25-58.71-142.9-133.11L72.2 185.82c-13.79 17.3-26.48 35.59-36.72 55.59a32.35 32.35 0 0 0 0 29.19C89.71 376.41 197.07 448 320 448c26.91 0 52.87-4 77.89-10.46L346 397.39a144.13 144.13 0 0 1-26 2.61zm313.82 58.1l-110.55-85.44a331.25 331.25 0 0 0 81.25-102.07 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64a308.15 308.15 0 0 0-147.32 37.7L45.46 3.37A16 16 0 0 0 23 6.18L3.37 31.45A16 16 0 0 0 6.18 53.9l588.36 454.73a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zm-183.72-142l-39.3-30.38A94.75 94.75 0 0 0 416 256a94.76 94.76 0 0 0-121.31-92.21A47.65 47.65 0 0 1 304 192a46.64 46.64 0 0 1-1.54 10l-73.61-56.89A142.31 142.31 0 0 1 320 112a143.92 143.92 0 0 1 144 144c0 21.63-5.29 41.79-13.9 60.11z\"],\n    \"fan\": [512, 512, [], \"f863\", \"M352.57 128c-28.09 0-54.09 4.52-77.06 12.86l12.41-123.11C289 7.31 279.81-1.18 269.33.13 189.63 10.13 128 77.64 128 159.43c0 28.09 4.52 54.09 12.86 77.06L17.75 224.08C7.31 223-1.18 232.19.13 242.67c10 79.7 77.51 141.33 159.3 141.33 28.09 0 54.09-4.52 77.06-12.86l-12.41 123.11c-1.05 10.43 8.11 18.93 18.59 17.62 79.7-10 141.33-77.51 141.33-159.3 0-28.09-4.52-54.09-12.86-77.06l123.11 12.41c10.44 1.05 18.93-8.11 17.62-18.59-10-79.7-77.51-141.33-159.3-141.33zM256 288a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"fast-backward\": [512, 512, [], \"f049\", \"M0 436V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v151.9L235.5 71.4C256.1 54.3 288 68.6 288 96v131.9L459.5 71.4C480.1 54.3 512 68.6 512 96v320c0 27.4-31.9 41.7-52.5 24.6L288 285.3V416c0 27.4-31.9 41.7-52.5 24.6L64 285.3V436c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12z\"],\n    \"fast-forward\": [512, 512, [], \"f050\", \"M512 76v360c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V284.1L276.5 440.6c-20.6 17.2-52.5 2.8-52.5-24.6V284.1L52.5 440.6C31.9 457.8 0 443.4 0 416V96c0-27.4 31.9-41.7 52.5-24.6L224 226.8V96c0-27.4 31.9-41.7 52.5-24.6L448 226.8V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12z\"],\n    \"fax\": [512, 512, [], \"f1ac\", \"M64 128H32c-17.67 0-32 14.33-32 32v320c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zm416 32V77.25c0-8.49-3.37-16.62-9.37-22.63L425.37 9.37c-6-6-14.14-9.37-22.63-9.37H160c-17.67 0-32 14.33-32 32v448c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zM288 432c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm128 128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm16-112H176V48h208v32c0 8.84 7.16 16 16 16h32v96z\"],\n    \"feather\": [512, 512, [], \"f52d\", \"M467.14 44.84c-62.55-62.48-161.67-64.78-252.28 25.73-78.61 78.52-60.98 60.92-85.75 85.66-60.46 60.39-70.39 150.83-63.64 211.17l178.44-178.25c6.26-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.6 9.37 33.98 0l66.1-66.03C159.42 454.65 279 457.11 353.95 384h-98.19l147.57-49.14c49.99-49.93 36.38-36.18 46.31-46.86h-97.78l131.54-43.8c45.44-74.46 34.31-148.84-16.26-199.36z\"],\n    \"feather-alt\": [512, 512, [], \"f56b\", \"M512 0C460.22 3.56 96.44 38.2 71.01 287.61c-3.09 26.66-4.84 53.44-5.99 80.24l178.87-178.69c6.25-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.59 9.37 33.98 0l57.13-57.07c42.09-.14 84.15-2.53 125.96-7.36 53.48-5.44 97.02-26.47 132.58-56.54H255.74l146.79-48.88c11.25-14.89 21.37-30.71 30.45-47.12h-81.14l106.54-53.21C500.29 132.86 510.19 26.26 512 0z\"],\n    \"female\": [256, 512, [], \"f182\", \"M128 0c35.346 0 64 28.654 64 64s-28.654 64-64 64c-35.346 0-64-28.654-64-64S92.654 0 128 0m119.283 354.179l-48-192A24 24 0 0 0 176 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H80a24 24 0 0 0-23.283 18.179l-48 192C4.935 369.305 16.383 384 32 384h56v104c0 13.255 10.745 24 24 24h32c13.255 0 24-10.745 24-24V384h56c15.591 0 27.071-14.671 23.283-29.821z\"],\n    \"fighter-jet\": [640, 512, [], \"f0fb\", \"M544 224l-128-16-48-16h-24L227.158 44h39.509C278.333 44 288 41.375 288 38s-9.667-6-21.333-6H152v12h16v164h-48l-66.667-80H18.667L8 138.667V208h8v16h48v2.666l-64 8v42.667l64 8V288H16v16H8v69.333L18.667 384h34.667L120 304h48v164h-16v12h114.667c11.667 0 21.333-2.625 21.333-6s-9.667-6-21.333-6h-39.509L344 320h24l48-16 128-16c96-21.333 96-26.583 96-32 0-5.417 0-10.667-96-32z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm160-14.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 236c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-64c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-72v8c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm96-114.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zM128.4 336c-17.9 0-32.4 12.1-32.4 27 0 15 14.6 27 32.5 27s32.4-12.1 32.4-27-14.6-27-32.5-27zM224 136V0h-63.6v32h-32V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM95.9 32h32v32h-32zm32.3 384c-33.2 0-58-30.4-51.4-62.9L96.4 256v-32h32v-32h-32v-32h32v-32h-32V96h32V64h32v32h-32v32h32v32h-32v32h32v32h-32v32h22.1c5.7 0 10.7 4.1 11.8 9.7l17.3 87.7c6.4 32.4-18.4 62.6-51.4 62.6z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-64 268c0 10.7-12.9 16-20.5 8.5L104 376H76c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h28l35.5-36.5c7.6-7.6 20.5-2.2 20.5 8.5v136zm33.2-47.6c9.1-9.3 9.1-24.1 0-33.4-22.1-22.8 12.2-56.2 34.4-33.5 27.2 27.9 27.2 72.4 0 100.4-21.8 22.3-56.9-10.4-34.4-33.5zm86-117.1c54.4 55.9 54.4 144.8 0 200.8-21.8 22.4-57-10.3-34.4-33.5 36.2-37.2 36.3-96.5 0-133.8-22.1-22.8 12.3-56.3 34.4-33.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zM123.206 400.505a5.4 5.4 0 0 1-7.633.246l-64.866-60.812a5.4 5.4 0 0 1 0-7.879l64.866-60.812a5.4 5.4 0 0 1 7.633.246l19.579 20.885a5.4 5.4 0 0 1-.372 7.747L101.65 336l40.763 35.874a5.4 5.4 0 0 1 .372 7.747l-19.579 20.884zm51.295 50.479l-27.453-7.97a5.402 5.402 0 0 1-3.681-6.692l61.44-211.626a5.402 5.402 0 0 1 6.692-3.681l27.452 7.97a5.4 5.4 0 0 1 3.68 6.692l-61.44 211.626a5.397 5.397 0 0 1-6.69 3.681zm160.792-111.045l-64.866 60.812a5.4 5.4 0 0 1-7.633-.246l-19.58-20.885a5.4 5.4 0 0 1 .372-7.747L284.35 336l-40.763-35.874a5.4 5.4 0 0 1-.372-7.747l19.58-20.885a5.4 5.4 0 0 1 7.633-.246l64.866 60.812a5.4 5.4 0 0 1-.001 7.879z\"],\n    \"file-contract\": [384, 512, [], \"f56c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm192.81 248H304c8.84 0 16 7.16 16 16s-7.16 16-16 16h-47.19c-16.45 0-31.27-9.14-38.64-23.86-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34a15.986 15.986 0 0 1-14.31 8.84c-.38 0-.75-.02-1.14-.05-6.45-.45-12-4.75-14.03-10.89L144 354.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.77-16.19 54.05-9.7 66 14.16 2.02 4.06 5.96 6.5 10.16 6.5zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-csv\": [384, 512, [], \"f6dd\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-96 144c0 4.42-3.58 8-8 8h-8c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h8c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-8c-26.51 0-48-21.49-48-48v-32c0-26.51 21.49-48 48-48h8c4.42 0 8 3.58 8 8v16zm44.27 104H160c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h12.27c5.95 0 10.41-3.5 10.41-6.62 0-1.3-.75-2.66-2.12-3.84l-21.89-18.77c-8.47-7.22-13.33-17.48-13.33-28.14 0-21.3 19.02-38.62 42.41-38.62H200c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-12.27c-5.95 0-10.41 3.5-10.41 6.62 0 1.3.75 2.66 2.12 3.84l21.89 18.77c8.47 7.22 13.33 17.48 13.33 28.14.01 21.29-19 38.62-42.39 38.62zM256 264v20.8c0 20.27 5.7 40.17 16 56.88 10.3-16.7 16-36.61 16-56.88V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v20.8c0 35.48-12.88 68.89-36.28 94.09-3.02 3.25-7.27 5.11-11.72 5.11s-8.7-1.86-11.72-5.11c-23.4-25.2-36.28-58.61-36.28-94.09V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8zm121-159L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-download\": [384, 512, [], \"f56d\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm76.45 211.36l-96.42 95.7c-6.65 6.61-17.39 6.61-24.04 0l-96.42-95.7C73.42 337.29 80.54 320 94.82 320H160v-80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v80h65.18c14.28 0 21.4 17.29 11.27 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm60.1 106.5L224 336l60.1 93.5c5.1 8-.6 18.5-10.1 18.5h-34.9c-4.4 0-8.5-2.4-10.6-6.3C208.9 405.5 192 373 192 373c-6.4 14.8-10 20-36.6 68.8-2.1 3.9-6.1 6.3-10.5 6.3H110c-9.5 0-15.2-10.5-10.1-18.5l60.3-93.5-60.3-93.5c-5.2-8 .6-18.5 10.1-18.5h34.8c4.4 0 8.5 2.4 10.6 6.3 26.1 48.8 20 33.6 36.6 68.5 0 0 6.1-11.7 36.6-68.5 2.1-3.9 6.2-6.3 10.6-6.3H274c9.5-.1 15.2 10.4 10.1 18.4zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-export\": [576, 512, [], \"f56e\", \"M384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128zM571 308l-95.7-96.4c-10.1-10.1-27.4-3-27.4 11.3V288h-64v64h64v65.2c0 14.3 17.3 21.4 27.4 11.3L571 332c6.6-6.6 6.6-17.4 0-24zm-379 28v-32c0-8.8 7.2-16 16-16h176V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V352H208c-8.8 0-16-7.2-16-16z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M384 121.941V128H256V0h6.059a24 24 0 0 1 16.97 7.029l97.941 97.941a24.002 24.002 0 0 1 7.03 16.971zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zm-135.455 16c26.51 0 48 21.49 48 48s-21.49 48-48 48-48-21.49-48-48 21.491-48 48-48zm208 240h-256l.485-48.485L104.545 328c4.686-4.686 11.799-4.201 16.485.485L160.545 368 264.06 264.485c4.686-4.686 12.284-4.686 16.971 0L320.545 304v112z\"],\n    \"file-import\": [512, 512, [], \"f56f\", \"M16 288c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h112v-64zm489-183L407.1 7c-4.5-4.5-10.6-7-17-7H384v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H152c-13.3 0-24 10.7-24 24v264h128v-65.2c0-14.3 17.3-21.4 27.4-11.3L379 308c6.6 6.7 6.6 17.4 0 24l-95.7 96.4c-10.1 10.1-27.4 3-27.4-11.3V352H128v136c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H376c-13.2 0-24-10.8-24-24z\"],\n    \"file-invoice\": [384, 512, [], \"f570\", \"M288 256H96v64h192v-64zm89-151L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm256 304c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-200v96c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-96c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16z\"],\n    \"file-invoice-dollar\": [384, 512, [], \"f571\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 80v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8zm144 263.88V440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-24.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V232c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v24.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07z\"],\n    \"file-medical\": [384, 512, [], \"f477\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 160v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8z\"],\n    \"file-medical-alt\": [448, 512, [], \"f478\", \"M288 136V0H88C74.7 0 64 10.7 64 24v232H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h140.9c3 0 5.8 1.7 7.2 4.4l19.9 39.8 56.8-113.7c2.9-5.9 11.4-5.9 14.3 0l34.7 69.5H352c8.8 0 16 7.2 16 16s-7.2 16-16 16h-89.9L240 275.8l-56.8 113.7c-2.9 5.9-11.4 5.9-14.3 0L134.1 320H64v168c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H312c-13.2 0-24-10.8-24-24zm153-31L343.1 7c-4.5-4.5-10.6-7-17-7H320v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M181.9 256.1c-5-16-4.9-46.9-2-46.9 8.4 0 7.6 36.9 2 46.9zm-1.7 47.2c-7.7 20.2-17.3 43.3-28.4 62.7 18.3-7 39-17.2 62.9-21.9-12.7-9.6-24.9-23.4-34.5-40.8zM86.1 428.1c0 .8 13.2-5.4 34.9-40.2-6.7 6.3-29.1 24.5-34.9 40.2zM248 160h136v328c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V24C0 10.7 10.7 0 24 0h200v136c0 13.2 10.8 24 24 24zm-8 171.8c-20-12.2-33.3-29-42.7-53.8 4.5-18.5 11.6-46.6 6.2-64.2-4.7-29.4-42.4-26.5-47.8-6.8-5 18.3-.4 44.1 8.1 77-11.6 27.6-28.7 64.6-40.8 85.8-.1 0-.1.1-.2.1-27.1 13.9-73.6 44.5-54.5 68 5.6 6.9 16 10 21.5 10 17.9 0 35.7-18 61.1-61.8 25.8-8.5 54.1-19.1 79-23.2 21.7 11.8 47.1 19.5 64 19.5 29.2 0 31.2-32 19.7-43.4-13.9-13.6-54.3-9.7-73.6-7.2zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-74.1 255.3c4.1-2.7-2.5-11.9-42.8-9 37.1 15.8 42.8 9 42.8 9z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M193.7 271.2c8.8 0 15.5 2.7 20.3 8.1 9.6 10.9 9.8 32.7-.2 44.1-4.9 5.6-11.9 8.5-21.1 8.5h-26.9v-60.7h27.9zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm53 165.2c0 90.3-88.8 77.6-111.1 77.6V436c0 6.6-5.4 12-12 12h-30.8c-6.6 0-12-5.4-12-12V236.2c0-6.6 5.4-12 12-12h81c44.5 0 72.9 32.8 72.9 77z\"],\n    \"file-prescription\": [384, 512, [], \"f572\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm68.53 179.48l11.31 11.31c6.25 6.25 6.25 16.38 0 22.63l-29.9 29.9L304 409.38c6.25 6.25 6.25 16.38 0 22.63l-11.31 11.31c-6.25 6.25-16.38 6.25-22.63 0L240 413.25l-30.06 30.06c-6.25 6.25-16.38 6.25-22.63 0L176 432c-6.25-6.25-6.25-16.38 0-22.63l30.06-30.06L146.74 320H128v48c0 8.84-7.16 16-16 16H96c-8.84 0-16-7.16-16-16V208c0-8.84 7.16-16 16-16h80c35.35 0 64 28.65 64 64 0 24.22-13.62 45.05-33.46 55.92L240 345.38l29.9-29.9c6.25-6.25 16.38-6.25 22.63 0zM176 272h-48v-32h48c8.82 0 16 7.18 16 16s-7.18 16-16 16zm208-150.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-signature\": [576, 512, [], \"f573\", \"M218.17 424.14c-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34c-6.37 12.78-25.03 11.37-29.48-2.09L144 386.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.75-16.19 54.06-9.7 66 14.16 1.89 3.78 5.49 5.95 9.36 6.26v-82.12l128-127.09V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24v-40l-128-.11c-16.12-.31-30.58-9.28-37.83-23.75zM384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1zm-96 225.06V416h68.99l161.68-162.78-67.88-67.88L288 346.96zm280.54-179.63l-31.87-31.87c-9.94-9.94-26.07-9.94-36.01 0l-27.25 27.25 67.88 67.88 27.25-27.25c9.95-9.94 9.95-26.07 0-36.01z\"],\n    \"file-upload\": [384, 512, [], \"f574\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm65.18 216.01H224v80c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-80H94.82c-14.28 0-21.41-17.29-11.27-27.36l96.42-95.7c6.65-6.61 17.39-6.61 24.04 0l96.42 95.7c10.15 10.07 3.03 27.36-11.25 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM224 136V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248c-13.2 0-24-10.8-24-24zm96 144.016v111.963c0 21.445-25.943 31.998-40.971 16.971L224 353.941V392c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V280c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v38.059l55.029-55.013c15.011-15.01 40.971-4.491 40.971 16.97z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm57.1 120H305c7.7 0 13.4 7.1 11.7 14.7l-38 168c-1.2 5.5-6.1 9.3-11.7 9.3h-38c-5.5 0-10.3-3.8-11.6-9.1-25.8-103.5-20.8-81.2-25.6-110.5h-.5c-1.1 14.3-2.4 17.4-25.6 110.5-1.3 5.3-6.1 9.1-11.6 9.1H117c-5.6 0-10.5-3.9-11.7-9.4l-37.8-168c-1.7-7.5 4-14.6 11.7-14.6h24.5c5.7 0 10.7 4 11.8 9.7 15.6 78 20.1 109.5 21 122.2 1.6-10.2 7.3-32.7 29.4-122.7 1.3-5.4 6.1-9.1 11.7-9.1h29.1c5.6 0 10.4 3.8 11.7 9.2 24 100.4 28.8 124 29.6 129.4-.2-11.2-2.6-17.8 21.6-129.2 1-5.6 5.9-9.5 11.5-9.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"fill\": [512, 512, [], \"f575\", \"M502.63 217.06L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.77c-6.24-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.63l86.19 86.18-94.76 94.76c-37.49 37.49-37.49 98.26 0 135.75l117.19 117.19c18.75 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.88-28.12l221.57-221.57c12.49-12.5 12.49-32.76 0-45.26zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.61 58.6c12.49 12.49 32.75 12.49 45.24 0 12.49-12.49 12.49-32.75 0-45.24l-58.61-58.6 58.95-58.95 162.45 162.44-48.35 48.34z\"],\n    \"fill-drip\": [576, 512, [], \"f576\", \"M512 320s-64 92.65-64 128c0 35.35 28.66 64 64 64s64-28.65 64-64-64-128-64-128zm-9.37-102.94L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.76c-6.25-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.62l86.19 86.18-94.76 94.76c-37.49 37.48-37.49 98.26 0 135.75l117.19 117.19c18.74 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.87-28.12l221.57-221.57c12.5-12.5 12.5-32.75.01-45.25zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.6 58.6c12.49 12.49 32.75 12.49 45.24 0s12.49-32.75 0-45.24l-58.6-58.6 58.95-58.95 162.44 162.44-48.34 48.34z\"],\n    \"film\": [512, 512, [], \"f008\", \"M488 64h-8v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V64H96v20c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12V64h-8C10.7 64 0 74.7 0 88v336c0 13.3 10.7 24 24 24h8v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h320v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h8c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24zM96 372c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm272 208c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm0-168c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm112 152c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"filter\": [512, 512, [], \"f0b0\", \"M487.976 0H24.028C2.71 0-8.047 25.866 7.058 40.971L192 225.941V432c0 7.831 3.821 15.17 10.237 19.662l80 55.98C298.02 518.69 320 507.493 320 487.98V225.941l184.947-184.97C520.021 25.896 509.338 0 487.976 0z\"],\n    \"fingerprint\": [512, 512, [], \"f577\", \"M256.12 245.96c-13.25 0-24 10.74-24 24 1.14 72.25-8.14 141.9-27.7 211.55-2.73 9.72 2.15 30.49 23.12 30.49 10.48 0 20.11-6.92 23.09-17.52 13.53-47.91 31.04-125.41 29.48-224.52.01-13.25-10.73-24-23.99-24zm-.86-81.73C194 164.16 151.25 211.3 152.1 265.32c.75 47.94-3.75 95.91-13.37 142.55-2.69 12.98 5.67 25.69 18.64 28.36 13.05 2.67 25.67-5.66 28.36-18.64 10.34-50.09 15.17-101.58 14.37-153.02-.41-25.95 19.92-52.49 54.45-52.34 31.31.47 57.15 25.34 57.62 55.47.77 48.05-2.81 96.33-10.61 143.55-2.17 13.06 6.69 25.42 19.76 27.58 19.97 3.33 26.81-15.1 27.58-19.77 8.28-50.03 12.06-101.21 11.27-152.11-.88-55.8-47.94-101.88-104.91-102.72zm-110.69-19.78c-10.3-8.34-25.37-6.8-33.76 3.48-25.62 31.5-39.39 71.28-38.75 112 .59 37.58-2.47 75.27-9.11 112.05-2.34 13.05 6.31 25.53 19.36 27.89 20.11 3.5 27.07-14.81 27.89-19.36 7.19-39.84 10.5-80.66 9.86-121.33-.47-29.88 9.2-57.88 28-80.97 8.35-10.28 6.79-25.39-3.49-33.76zm109.47-62.33c-15.41-.41-30.87 1.44-45.78 4.97-12.89 3.06-20.87 15.98-17.83 28.89 3.06 12.89 16 20.83 28.89 17.83 11.05-2.61 22.47-3.77 34-3.69 75.43 1.13 137.73 61.5 138.88 134.58.59 37.88-1.28 76.11-5.58 113.63-1.5 13.17 7.95 25.08 21.11 26.58 16.72 1.95 25.51-11.88 26.58-21.11a929.06 929.06 0 0 0 5.89-119.85c-1.56-98.75-85.07-180.33-186.16-181.83zm252.07 121.45c-2.86-12.92-15.51-21.2-28.61-18.27-12.94 2.86-21.12 15.66-18.26 28.61 4.71 21.41 4.91 37.41 4.7 61.6-.11 13.27 10.55 24.09 23.8 24.2h.2c13.17 0 23.89-10.61 24-23.8.18-22.18.4-44.11-5.83-72.34zm-40.12-90.72C417.29 43.46 337.6 1.29 252.81.02 183.02-.82 118.47 24.91 70.46 72.94 24.09 119.37-.9 181.04.14 246.65l-.12 21.47c-.39 13.25 10.03 24.31 23.28 24.69.23.02.48.02.72.02 12.92 0 23.59-10.3 23.97-23.3l.16-23.64c-.83-52.5 19.16-101.86 56.28-139 38.76-38.8 91.34-59.67 147.68-58.86 69.45 1.03 134.73 35.56 174.62 92.39 7.61 10.86 22.56 13.45 33.42 5.86 10.84-7.62 13.46-22.59 5.84-33.43z\"],\n    \"fire\": [384, 512, [], \"f06d\", \"M216 23.86c0-23.8-30.65-32.77-44.15-13.04C48 191.85 224 200 224 288c0 35.63-29.11 64.46-64.85 63.99-35.17-.45-63.15-29.77-63.15-64.94v-85.51c0-21.7-26.47-32.23-41.43-16.5C27.8 213.16 0 261.33 0 320c0 105.87 86.13 192 192 192s192-86.13 192-192c0-170.29-168-193-168-296.14z\"],\n    \"fire-alt\": [448, 512, [], \"f7e4\", \"M323.56 51.2c-20.8 19.3-39.58 39.59-56.22 59.97C240.08 73.62 206.28 35.53 168 0 69.74 91.17 0 209.96 0 281.6 0 408.85 100.29 512 224 512s224-103.15 224-230.4c0-53.27-51.98-163.14-124.44-230.4zm-19.47 340.65C282.43 407.01 255.72 416 226.86 416 154.71 416 96 368.26 96 290.75c0-38.61 24.31-72.63 72.79-130.75 6.93 7.98 98.83 125.34 98.83 125.34l58.63-66.88c4.14 6.85 7.91 13.55 11.27 19.97 27.35 52.19 15.81 118.97-33.43 153.42z\"],\n    \"fire-extinguisher\": [448, 512, [], \"f134\", \"M434.027 26.329l-168 28C254.693 56.218 256 67.8 256 72h-58.332C208.353 36.108 181.446 0 144 0c-39.435 0-66.368 39.676-52.228 76.203-52.039 13.051-75.381 54.213-90.049 90.884-4.923 12.307 1.063 26.274 13.37 31.197 12.317 4.926 26.279-1.075 31.196-13.37C75.058 112.99 106.964 120 168 120v27.076c-41.543 10.862-72 49.235-72 94.129V488c0 13.255 10.745 24 24 24h144c13.255 0 24-10.745 24-24V240c0-44.731-30.596-82.312-72-92.97V120h40c0 2.974-1.703 15.716 10.027 17.671l168 28C441.342 166.89 448 161.25 448 153.834V38.166c0-7.416-6.658-13.056-13.973-11.837zM144 72c-8.822 0-16-7.178-16-16s7.178-16 16-16 16 7.178 16 16-7.178 16-16 16z\"],\n    \"first-aid\": [576, 512, [], \"f479\", \"M0 80v352c0 26.5 21.5 48 48 48h48V32H48C21.5 32 0 53.5 0 80zm128 400h320V32H128v448zm64-248c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48zM528 32h-48v448h48c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"fish\": [576, 512, [], \"f578\", \"M327.1 96c-89.97 0-168.54 54.77-212.27 101.63L27.5 131.58c-12.13-9.18-30.24.6-27.14 14.66L24.54 256 .35 365.77c-3.1 14.06 15.01 23.83 27.14 14.66l87.33-66.05C158.55 361.23 237.13 416 327.1 416 464.56 416 576 288 576 256S464.56 96 327.1 96zm87.43 184c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24 13.26 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"fist-raised\": [384, 512, [], \"f6de\", \"M255.98 160V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v146.93c5.02-1.78 10.34-2.93 15.97-2.93h48.03zm128 95.99c-.01-35.34-28.66-63.99-63.99-63.99H207.85c-8.78 0-15.9 7.07-15.9 15.85v.56c0 26.27 21.3 47.59 47.57 47.59h35.26c9.68 0 13.2 3.58 13.2 8v16.2c0 4.29-3.59 7.78-7.88 8-44.52 2.28-64.16 24.71-96.05 72.55l-6.31 9.47a7.994 7.994 0 0 1-11.09 2.22l-13.31-8.88a7.994 7.994 0 0 1-2.22-11.09l6.31-9.47c15.73-23.6 30.2-43.26 47.31-58.08-17.27-5.51-31.4-18.12-38.87-34.45-6.59 3.41-13.96 5.52-21.87 5.52h-32c-12.34 0-23.49-4.81-32-12.48C71.48 251.19 60.33 256 48 256H16c-5.64 0-10.97-1.15-16-2.95v77.93c0 33.95 13.48 66.5 37.49 90.51L63.99 448v64h255.98v-63.96l35.91-35.92A96.035 96.035 0 0 0 384 344.21l-.02-88.22zm-32.01-90.09V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v112h32c11.28 0 21.94 2.31 32 5.9zM16 224h32c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v128c0 8.84 7.16 16 16 16zm95.99 0h32c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v160c0 8.84 7.16 16 16 16z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M349.565 98.783C295.978 98.783 251.721 64 184.348 64c-24.955 0-47.309 4.384-68.045 12.013a55.947 55.947 0 0 0 3.586-23.562C118.117 24.015 94.806 1.206 66.338.048 34.345-1.254 8 24.296 8 56c0 19.026 9.497 35.825 24 45.945V488c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-94.4c28.311-12.064 63.582-22.122 114.435-22.122 53.588 0 97.844 34.783 165.217 34.783 48.169 0 86.667-16.294 122.505-40.858C506.84 359.452 512 349.571 512 339.045v-243.1c0-23.393-24.269-38.87-45.485-29.016-34.338 15.948-76.454 31.854-116.95 31.854z\"],\n    \"flag-checkered\": [512, 512, [], \"f11e\", \"M243.2 189.9V258c26.1 5.9 49.3 15.6 73.6 22.3v-68.2c-26-5.8-49.4-15.5-73.6-22.2zm223.3-123c-34.3 15.9-76.5 31.9-117 31.9C296 98.8 251.7 64 184.3 64c-25 0-47.3 4.4-68 12 2.8-7.3 4.1-15.2 3.6-23.6C118.1 24 94.8 1.2 66.3 0 34.3-1.3 8 24.3 8 56c0 19 9.5 35.8 24 45.9V488c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24v-94.4c28.3-12.1 63.6-22.1 114.4-22.1 53.6 0 97.8 34.8 165.2 34.8 48.2 0 86.7-16.3 122.5-40.9 8.7-6 13.8-15.8 13.8-26.4V95.9c.1-23.3-24.2-38.8-45.4-29zM169.6 325.5c-25.8 2.7-50 8.2-73.6 16.6v-70.5c26.2-9.3 47.5-15 73.6-17.4zM464 191c-23.6 9.8-46.3 19.5-73.6 23.9V286c24.8-3.4 51.4-11.8 73.6-26v70.5c-25.1 16.1-48.5 24.7-73.6 27.1V286c-27 3.7-47.9 1.5-73.6-5.6v67.4c-23.9-7.4-47.3-16.7-73.6-21.3V258c-19.7-4.4-40.8-6.8-73.6-3.8v-70c-22.4 3.1-44.6 10.2-73.6 20.9v-70.5c33.2-12.2 50.1-19.8 73.6-22v71.6c27-3.7 48.4-1.3 73.6 5.7v-67.4c23.7 7.4 47.2 16.7 73.6 21.3v68.4c23.7 5.3 47.6 6.9 73.6 2.7V143c27-4.8 52.3-13.6 73.6-22.5z\"],\n    \"flag-usa\": [512, 512, [], \"f74d\", \"M32 0C14.3 0 0 14.3 0 32v464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32C64 14.3 49.7 0 32 0zm267.9 303.6c-57.2-15.1-111.7-28.8-203.9 11.1V384c185.7-92.2 221.7 53.3 397.5-23.1 11.4-5 18.5-16.5 18.5-28.8v-36c-43.6 17.3-80.2 24.1-112.1 24.1-37.4-.1-68.9-8.4-100-16.6zm0-96c-57.2-15.1-111.7-28.8-203.9 11.1v61.5c94.8-37.6 154.6-22.7 212.1-7.6 57.2 15.1 111.7 28.8 203.9-11.1V200c-43.6 17.3-80.2 24.1-112.1 24.1-37.4 0-68.9-8.3-100-16.5zm9.5-125.9c51.8 15.6 97.4 29 202.6-20.1V30.8c0-25.1-26.8-38.1-49.4-26.6C291.3 91.5 305.4-62.2 96 32.4v151.9c94.8-37.5 154.6-22.7 212.1-7.6 57.2 15 111.7 28.7 203.9-11.1V96.7c-53.6 23.5-93.3 31.4-126.1 31.4s-59-7.8-85.7-15.9c-4-1.2-8.1-2.4-12.1-3.5V75.5c7.2 2 14.3 4.1 21.3 6.2zM160 128.1c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16-7.2 16-16 16zm0-55.8c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm64 47.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm0-55.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16z\"],\n    \"flask\": [448, 512, [], \"f0c3\", \"M437.2 403.5L320 215V64h8c13.3 0 24-10.7 24-24V24c0-13.3-10.7-24-24-24H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h8v151L10.8 403.5C-18.5 450.6 15.3 512 70.9 512h306.2c55.7 0 89.4-61.5 60.1-108.5zM137.9 320l48.2-77.6c3.7-5.2 5.8-11.6 5.8-18.4V64h64v160c0 6.9 2.2 13.2 5.8 18.4l48.2 77.6h-172z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M344 200c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-192 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM80 224c0-39.8 32.2-72 72-72s72 32.2 72 72-32.2 72-72 72-72-32.2-72-72zm232 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-104c-39.8 0-72-32.2-72-72s32.2-72 72-72 72 32.2 72 72-32.2 72-72 72z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48z\"],\n    \"folder-minus\": [512, 512, [], \"f65d\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16H160c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h192c8.84 0 16 7.16 16 16v16z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M572.694 292.093L500.27 416.248A63.997 63.997 0 0 1 444.989 448H45.025c-18.523 0-30.064-20.093-20.731-36.093l72.424-124.155A64 64 0 0 1 152 256h399.964c18.523 0 30.064 20.093 20.73 36.093zM152 224h328v-48c0-26.51-21.49-48-48-48H272l-64-64H48C21.49 64 0 85.49 0 112v278.046l69.077-118.418C86.214 242.25 117.989 224 152 224z\"],\n    \"folder-plus\": [512, 512, [], \"f65e\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16h-72v72c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-72h-72c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h72v-72c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v72h72c8.84 0 16 7.16 16 16v16z\"],\n    \"font\": [448, 512, [], \"f031\", \"M432 416h-23.41L277.88 53.69A32 32 0 0 0 247.58 32h-47.16a32 32 0 0 0-30.3 21.69L39.41 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-19.58l23.3-64h152.56l23.3 64H304a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM176.85 272L224 142.51 271.15 272z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"football-ball\": [496, 512, [], \"f44e\", \"M481.5 60.3c-4.8-18.2-19.1-32.5-37.3-37.4C420.3 16.5 383 8.9 339.4 8L496 164.8c-.8-43.5-8.2-80.6-14.5-104.5zm-467 391.4c4.8 18.2 19.1 32.5 37.3 37.4 23.9 6.4 61.2 14 104.8 14.9L0 347.2c.8 43.5 8.2 80.6 14.5 104.5zM4.2 283.4L220.4 500c132.5-19.4 248.8-118.7 271.5-271.4L275.6 12C143.1 31.4 26.8 130.7 4.2 283.4zm317.3-123.6c3.1-3.1 8.2-3.1 11.3 0l11.3 11.3c3.1 3.1 3.1 8.2 0 11.3l-28.3 28.3 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-22.6 22.7 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L248 278.6l-22.6 22.6 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-28.3 28.3c-3.1 3.1-8.2 3.1-11.3 0l-11.3-11.3c-3.1-3.1-3.1-8.2 0-11.3l28.3-28.3-28.3-28.2c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 28.3-28.5z\"],\n    \"forward\": [512, 512, [], \"f04e\", \"M500.5 231.4l-192-160C287.9 54.3 256 68.6 256 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2zm-256 0l-192-160C31.9 54.3 0 68.6 0 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2z\"],\n    \"frog\": [576, 512, [], \"f52e\", \"M446.53 97.43C439.67 60.23 407.19 32 368 32c-39.23 0-71.72 28.29-78.54 65.54C126.75 112.96-.5 250.12 0 416.98.11 451.9 29.08 480 64 480h304c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-79.49l35.8-48.33c24.14-36.23 10.35-88.28-33.71-106.6-23.89-9.93-51.55-4.65-72.24 10.88l-32.76 24.59c-7.06 5.31-17.09 3.91-22.41-3.19-5.3-7.08-3.88-17.11 3.19-22.41l34.78-26.09c36.84-27.66 88.28-27.62 125.13 0 10.87 8.15 45.87 39.06 40.8 93.21L469.62 480H560c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-53.63l-98.52-104.68 154.44-86.65A58.16 58.16 0 0 0 576 189.94c0-21.4-11.72-40.95-30.48-51.23-40.56-22.22-98.99-41.28-98.99-41.28zM368 136c-13.26 0-24-10.75-24-24 0-13.26 10.74-24 24-24 13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm170.2 218.2C315.8 367.4 282.9 352 248 352s-67.8 15.4-90.2 42.2c-13.5 16.3-38.1-4.2-24.6-20.5C161.7 339.6 203.6 320 248 320s86.3 19.6 114.7 53.8c13.6 16.2-11 36.7-24.5 20.4z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm187.3 183.3c-31.2-9.6-59.4-15.3-75.3-15.3s-44.1 5.7-75.3 15.3c-11.5 3.5-22.5-6.3-20.5-18.1 7-40 60.1-61.2 95.8-61.2s88.8 21.3 95.8 61.2c2 11.9-9.1 21.6-20.5 18.1zM328 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"funnel-dollar\": [640, 512, [], \"f662\", \"M433.46 165.94l101.2-111.87C554.61 34.12 540.48 0 512.26 0H31.74C3.52 0-10.61 34.12 9.34 54.07L192 256v155.92c0 12.59 5.93 24.44 16 32l79.99 60c20.86 15.64 48.47 6.97 59.22-13.57C310.8 455.38 288 406.35 288 352c0-89.79 62.05-165.17 145.46-186.06zM480 192c-88.37 0-160 71.63-160 160s71.63 160 160 160 160-71.63 160-160-71.63-160-160-160zm16 239.88V448c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V256c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.04 44.44-42.67 45.07z\"],\n    \"futbol\": [512, 512, [], \"f1e3\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-48 0l-.003-.282-26.064 22.741-62.679-58.5 16.454-84.355 34.303 3.072c-24.889-34.216-60.004-60.089-100.709-73.141l13.651 31.939L256 139l-74.953-41.525 13.651-31.939c-40.631 13.028-75.78 38.87-100.709 73.141l34.565-3.073 16.192 84.355-62.678 58.5-26.064-22.741-.003.282c0 43.015 13.497 83.952 38.472 117.991l7.704-33.897 85.138 10.447 36.301 77.826-29.902 17.786c40.202 13.122 84.29 13.148 124.572 0l-29.902-17.786 36.301-77.826 85.138-10.447 7.704 33.897C442.503 339.952 456 299.015 456 256zm-248.102 69.571l-29.894-91.312L256 177.732l77.996 56.527-29.622 91.312h-96.476z\"],\n    \"gamepad\": [640, 512, [], \"f11b\", \"M480 96H160C71.6 96 0 167.6 0 256s71.6 160 160 160c44.8 0 85.2-18.4 114.2-48h91.5c29 29.6 69.5 48 114.2 48 88.4 0 160-71.6 160-160S568.4 96 480 96zM256 276c0 6.6-5.4 12-12 12h-52v52c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-52H76c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h52v-52c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h52c6.6 0 12 5.4 12 12v40zm184 68c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-80c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"gas-pump\": [512, 512, [], \"f52f\", \"M336 448H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm157.2-340.7l-81-81c-6.2-6.2-16.4-6.2-22.6 0l-11.3 11.3c-6.2 6.2-6.2 16.4 0 22.6L416 97.9V160c0 28.1 20.9 51.3 48 55.2V376c0 13.2-10.8 24-24 24s-24-10.8-24-24v-32c0-48.6-39.4-88-88-88h-8V64c0-35.3-28.7-64-64-64H96C60.7 0 32 28.7 32 64v352h288V304h8c22.1 0 40 17.9 40 40v27.8c0 37.7 27 72 64.5 75.9 43 4.3 79.5-29.5 79.5-71.7V152.6c0-17-6.8-33.3-18.8-45.3zM256 192H96V64h160v128z\"],\n    \"gavel\": [512, 512, [], \"f0e3\", \"M504.971 199.362l-22.627-22.627c-9.373-9.373-24.569-9.373-33.941 0l-5.657 5.657L329.608 69.255l5.657-5.657c9.373-9.373 9.373-24.569 0-33.941L312.638 7.029c-9.373-9.373-24.569-9.373-33.941 0L154.246 131.48c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l5.657-5.657 39.598 39.598-81.04 81.04-5.657-5.657c-12.497-12.497-32.758-12.497-45.255 0L9.373 412.118c-12.497 12.497-12.497 32.758 0 45.255l45.255 45.255c12.497 12.497 32.758 12.497 45.255 0l114.745-114.745c12.497-12.497 12.497-32.758 0-45.255l-5.657-5.657 81.04-81.04 39.598 39.598-5.657 5.657c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l124.451-124.451c9.372-9.372 9.372-24.568 0-33.941z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M485.5 0L576 160H474.9L405.7 0h79.8zm-128 0l69.2 160H149.3L218.5 0h139zm-267 0h79.8l-69.2 160H0L90.5 0zM0 192h100.7l123 251.7c1.5 3.1-2.7 5.9-5 3.3L0 192zm148.2 0h279.6l-137 318.2c-1 2.4-4.5 2.4-5.5 0L148.2 192zm204.1 251.7l123-251.7H576L357.3 446.9c-2.3 2.7-6.5-.1-5-3.2z\"],\n    \"genderless\": [288, 512, [], \"f22d\", \"M144 176c44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80 35.9-80 80-80m0-64C64.5 112 0 176.5 0 256s64.5 144 144 144 144-64.5 144-144-64.5-144-144-144z\"],\n    \"ghost\": [384, 512, [], \"f6e2\", \"M186.1.09C81.01 3.24 0 94.92 0 200.05v263.92c0 14.26 17.23 21.39 27.31 11.31l24.92-18.53c6.66-4.95 16-3.99 21.51 2.21l42.95 48.35c6.25 6.25 16.38 6.25 22.63 0l40.72-45.85c6.37-7.17 17.56-7.17 23.92 0l40.72 45.85c6.25 6.25 16.38 6.25 22.63 0l42.95-48.35c5.51-6.2 14.85-7.17 21.51-2.21l24.92 18.53c10.08 10.08 27.31 2.94 27.31-11.31V192C384 84 294.83-3.17 186.1.09zM128 224c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128 0c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"gift\": [512, 512, [], \"f06b\", \"M32 448c0 17.7 14.3 32 32 32h160V320H32v128zm256 32h160c17.7 0 32-14.3 32-32V320H288v160zm192-320h-42.1c6.2-12.1 10.1-25.5 10.1-40 0-48.5-39.5-88-88-88-41.6 0-68.5 21.3-103 68.3-34.5-47-61.4-68.3-103-68.3-48.5 0-88 39.5-88 88 0 14.5 3.8 27.9 10.1 40H32c-17.7 0-32 14.3-32 32v80c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-80c0-17.7-14.3-32-32-32zm-326.1 0c-22.1 0-40-17.9-40-40s17.9-40 40-40c19.9 0 34.6 3.3 86.1 80h-86.1zm206.1 0h-86.1c51.4-76.5 65.7-80 86.1-80 22.1 0 40 17.9 40 40s-17.9 40-40 40z\"],\n    \"gifts\": [640, 512, [], \"f79c\", \"M240.6 194.1c1.9-30.8 17.3-61.2 44-79.8C279.4 103.5 268.7 96 256 96h-29.4l30.7-22c7.2-5.1 8.9-15.1 3.7-22.3l-9.3-13c-5.1-7.2-15.1-8.9-22.3-3.7l-32 22.9 11.5-30.6c3.1-8.3-1.1-17.5-9.4-20.6l-15-5.6c-8.3-3.1-17.5 1.1-20.6 9.4l-19.9 53-19.9-53.1C121 2.1 111.8-2.1 103.5 1l-15 5.6C80.2 9.7 76 19 79.2 27.2l11.5 30.6L58.6 35c-7.2-5.1-17.2-3.5-22.3 3.7l-9.3 13c-5.1 7.2-3.5 17.2 3.7 22.3l30.7 22H32c-17.7 0-32 14.3-32 32v352c0 17.7 14.3 32 32 32h168.9c-5.5-9.5-8.9-20.3-8.9-32V256c0-29.9 20.8-55 48.6-61.9zM224 480c0 17.7 14.3 32 32 32h160V384H224v96zm224 32h160c17.7 0 32-14.3 32-32v-96H448v128zm160-288h-20.4c2.6-7.6 4.4-15.5 4.4-23.8 0-35.5-27-72.2-72.1-72.2-48.1 0-75.9 47.7-87.9 75.3-12.1-27.6-39.9-75.3-87.9-75.3-45.1 0-72.1 36.7-72.1 72.2 0 8.3 1.7 16.2 4.4 23.8H256c-17.7 0-32 14.3-32 32v96h192V224h15.3l.7-.2.7.2H448v128h192v-96c0-17.7-14.3-32-32-32zm-272 0c-2.7-1.4-5.1-3-7.2-4.8-7.3-6.4-8.8-13.8-8.8-19 0-9.7 6.4-24.2 24.1-24.2 18.7 0 35.6 27.4 44.5 48H336zm199.2-4.8c-2.1 1.8-4.5 3.4-7.2 4.8h-52.6c8.8-20.3 25.8-48 44.5-48 17.7 0 24.1 14.5 24.1 24.2 0 5.2-1.5 12.6-8.8 19z\"],\n    \"glass-cheers\": [640, 512, [], \"f79f\", \"M639.4 433.6c-8.4-20.4-31.8-30.1-52.2-21.6l-22.1 9.2-38.7-101.9c47.9-35 64.8-100.3 34.5-152.8L474.3 16c-8-13.9-25.1-19.7-40-13.6L320 49.8 205.7 2.4c-14.9-6.2-32-.3-40 13.6L79.1 166.5C48.9 219 65.7 284.3 113.6 319.2L74.9 421.1l-22.1-9.2c-20.4-8.5-43.7 1.2-52.2 21.6-1.7 4.1.2 8.8 4.3 10.5l162.3 67.4c4.1 1.7 8.7-.2 10.4-4.3 8.4-20.4-1.2-43.8-21.6-52.3l-22.1-9.2L173.3 342c4.4.5 8.8 1.3 13.1 1.3 51.7 0 99.4-33.1 113.4-85.3l20.2-75.4 20.2 75.4c14 52.2 61.7 85.3 113.4 85.3 4.3 0 8.7-.8 13.1-1.3L506 445.6l-22.1 9.2c-20.4 8.5-30.1 31.9-21.6 52.3 1.7 4.1 6.4 6 10.4 4.3L635.1 444c4-1.7 6-6.3 4.3-10.4zM275.9 162.1l-112.1-46.5 36.5-63.4 94.5 39.2-18.9 70.7zm88.2 0l-18.9-70.7 94.5-39.2 36.5 63.4-112.1 46.5z\"],\n    \"glass-martini\": [512, 512, [], \"f000\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6z\"],\n    \"glass-martini-alt\": [512, 512, [], \"f57b\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6zM443.77 48l-48 48H116.24l-48-48h375.53z\"],\n    \"glass-whiskey\": [512, 512, [], \"f7a0\", \"M480 32H32C12.5 32-2.4 49.2.3 68.5l56 356.5c4.5 31.5 31.5 54.9 63.4 54.9h273c31.8 0 58.9-23.4 63.4-54.9l55.6-356.5C514.4 49.2 499.5 32 480 32zm-37.4 64l-30 192h-313L69.4 96h373.2z\"],\n    \"glasses\": [576, 512, [], \"f530\", \"M574.1 280.37L528.75 98.66c-5.91-23.7-21.59-44.05-43-55.81-21.44-11.73-46.97-14.11-70.19-6.33l-15.25 5.08c-8.39 2.79-12.92 11.86-10.12 20.24l5.06 15.18c2.79 8.38 11.85 12.91 20.23 10.12l13.18-4.39c10.87-3.62 23-3.57 33.16 1.73 10.29 5.37 17.57 14.56 20.37 25.82l38.46 153.82c-22.19-6.81-49.79-12.46-81.2-12.46-34.77 0-73.98 7.02-114.85 26.74h-73.18c-40.87-19.74-80.08-26.75-114.86-26.75-31.42 0-59.02 5.65-81.21 12.46l38.46-153.83c2.79-11.25 10.09-20.45 20.38-25.81 10.16-5.3 22.28-5.35 33.15-1.73l13.17 4.39c8.38 2.79 17.44-1.74 20.23-10.12l5.06-15.18c2.8-8.38-1.73-17.45-10.12-20.24l-15.25-5.08c-23.22-7.78-48.75-5.41-70.19 6.33-21.41 11.77-37.09 32.11-43 55.8L1.9 280.37A64.218 64.218 0 0 0 0 295.86v70.25C0 429.01 51.58 480 115.2 480h37.12c60.28 0 110.37-45.94 114.88-105.37l2.93-38.63h35.75l2.93 38.63C313.31 434.06 363.4 480 423.68 480h37.12c63.62 0 115.2-50.99 115.2-113.88v-70.25c0-5.23-.64-10.43-1.9-15.5zm-370.72 89.42c-1.97 25.91-24.4 46.21-51.06 46.21H115.2C86.97 416 64 393.62 64 366.11v-37.54c18.12-6.49 43.42-12.92 72.58-12.92 23.86 0 47.26 4.33 69.93 12.92l-3.13 41.22zM512 366.12c0 27.51-22.97 49.88-51.2 49.88h-37.12c-26.67 0-49.1-20.3-51.06-46.21l-3.13-41.22c22.67-8.59 46.08-12.92 69.95-12.92 29.12 0 54.43 6.44 72.55 12.93v37.54z\"],\n    \"globe\": [496, 512, [], \"f0ac\", \"M336.5 160C322 70.7 287.8 8 248 8s-74 62.7-88.5 152h177zM152 256c0 22.2 1.2 43.5 3.3 64h185.3c2.1-20.5 3.3-41.8 3.3-64s-1.2-43.5-3.3-64H155.3c-2.1 20.5-3.3 41.8-3.3 64zm324.7-96c-28.6-67.9-86.5-120.4-158-141.6 24.4 33.8 41.2 84.7 50 141.6h108zM177.2 18.4C105.8 39.6 47.8 92.1 19.3 160h108c8.7-56.9 25.5-107.8 49.9-141.6zM487.4 192H372.7c2.1 21 3.3 42.5 3.3 64s-1.2 43-3.3 64h114.6c5.5-20.5 8.6-41.8 8.6-64s-3.1-43.5-8.5-64zM120 256c0-21.5 1.2-43 3.3-64H8.6C3.2 212.5 0 233.8 0 256s3.2 43.5 8.6 64h114.6c-2-21-3.2-42.5-3.2-64zm39.5 96c14.5 89.3 48.7 152 88.5 152s74-62.7 88.5-152h-177zm159.3 141.6c71.4-21.2 129.4-73.7 158-141.6h-108c-8.8 56.9-25.6 107.8-50 141.6zM19.3 352c28.6 67.9 86.5 120.4 158 141.6-24.4-33.8-41.2-84.7-50-141.6h-108z\"],\n    \"globe-africa\": [496, 512, [], \"f57c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm160 215.5v6.93c0 5.87-3.32 11.24-8.57 13.86l-15.39 7.7a15.485 15.485 0 0 1-15.53-.97l-18.21-12.14a15.52 15.52 0 0 0-13.5-1.81l-2.65.88c-9.7 3.23-13.66 14.79-7.99 23.3l13.24 19.86c2.87 4.31 7.71 6.9 12.89 6.9h8.21c8.56 0 15.5 6.94 15.5 15.5v11.34c0 3.35-1.09 6.62-3.1 9.3l-18.74 24.98c-1.42 1.9-2.39 4.1-2.83 6.43l-4.3 22.83c-.62 3.29-2.29 6.29-4.76 8.56a159.608 159.608 0 0 0-25 29.16l-13.03 19.55a27.756 27.756 0 0 1-23.09 12.36c-10.51 0-20.12-5.94-24.82-15.34a78.902 78.902 0 0 1-8.33-35.29V367.5c0-8.56-6.94-15.5-15.5-15.5h-25.88c-14.49 0-28.38-5.76-38.63-16a54.659 54.659 0 0 1-16-38.63v-14.06c0-17.19 8.1-33.38 21.85-43.7l27.58-20.69a54.663 54.663 0 0 1 32.78-10.93h.89c8.48 0 16.85 1.97 24.43 5.77l14.72 7.36c3.68 1.84 7.93 2.14 11.83.84l47.31-15.77c6.33-2.11 10.6-8.03 10.6-14.7 0-8.56-6.94-15.5-15.5-15.5h-10.09c-4.11 0-8.05-1.63-10.96-4.54l-6.92-6.92a15.493 15.493 0 0 0-10.96-4.54H199.5c-8.56 0-15.5-6.94-15.5-15.5v-4.4c0-7.11 4.84-13.31 11.74-15.04l14.45-3.61c3.74-.94 7-3.23 9.14-6.44l8.08-12.11c2.87-4.31 7.71-6.9 12.89-6.9h24.21c8.56 0 15.5-6.94 15.5-15.5v-21.7C359.23 71.63 422.86 131.02 441.93 208H423.5c-8.56 0-15.5 6.94-15.5 15.5z\"],\n    \"globe-americas\": [496, 512, [], \"f57d\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm82.29 357.6c-3.9 3.88-7.99 7.95-11.31 11.28-2.99 3-5.1 6.7-6.17 10.71-1.51 5.66-2.73 11.38-4.77 16.87l-17.39 46.85c-13.76 3-28 4.69-42.65 4.69v-27.38c1.69-12.62-7.64-36.26-22.63-51.25-6-6-9.37-14.14-9.37-22.63v-32.01c0-11.64-6.27-22.34-16.46-27.97-14.37-7.95-34.81-19.06-48.81-26.11-11.48-5.78-22.1-13.14-31.65-21.75l-.8-.72a114.792 114.792 0 0 1-18.06-20.74c-9.38-13.77-24.66-36.42-34.59-51.14 20.47-45.5 57.36-82.04 103.2-101.89l24.01 12.01C203.48 89.74 216 82.01 216 70.11v-11.3c7.99-1.29 16.12-2.11 24.39-2.42l28.3 28.3c6.25 6.25 6.25 16.38 0 22.63L264 112l-10.34 10.34c-3.12 3.12-3.12 8.19 0 11.31l4.69 4.69c3.12 3.12 3.12 8.19 0 11.31l-8 8a8.008 8.008 0 0 1-5.66 2.34h-8.99c-2.08 0-4.08.81-5.58 2.27l-9.92 9.65a8.008 8.008 0 0 0-1.58 9.31l15.59 31.19c2.66 5.32-1.21 11.58-7.15 11.58h-5.64c-1.93 0-3.79-.7-5.24-1.96l-9.28-8.06a16.017 16.017 0 0 0-15.55-3.1l-31.17 10.39a11.95 11.95 0 0 0-8.17 11.34c0 4.53 2.56 8.66 6.61 10.69l11.08 5.54c9.41 4.71 19.79 7.16 30.31 7.16s22.59 27.29 32 32h66.75c8.49 0 16.62 3.37 22.63 9.37l13.69 13.69a30.503 30.503 0 0 1 8.93 21.57 46.536 46.536 0 0 1-13.72 32.98zM417 274.25c-5.79-1.45-10.84-5-14.15-9.97l-17.98-26.97a23.97 23.97 0 0 1 0-26.62l19.59-29.38c2.32-3.47 5.5-6.29 9.24-8.15l12.98-6.49C440.2 193.59 448 223.87 448 256c0 8.67-.74 17.16-1.82 25.54L417 274.25z\"],\n    \"globe-asia\": [496, 512, [], \"f57e\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm-11.34 240.23c-2.89 4.82-8.1 7.77-13.72 7.77h-.31c-4.24 0-8.31 1.69-11.31 4.69l-5.66 5.66c-3.12 3.12-3.12 8.19 0 11.31l5.66 5.66c3 3 4.69 7.07 4.69 11.31V304c0 8.84-7.16 16-16 16h-6.11c-6.06 0-11.6-3.42-14.31-8.85l-22.62-45.23c-2.44-4.88-8.95-5.94-12.81-2.08l-19.47 19.46c-3 3-7.07 4.69-11.31 4.69H50.81C49.12 277.55 48 266.92 48 256c0-110.28 89.72-200 200-200 21.51 0 42.2 3.51 61.63 9.82l-50.16 38.53c-5.11 3.41-4.63 11.06.86 13.81l10.83 5.41c5.42 2.71 8.84 8.25 8.84 14.31V216c0 4.42-3.58 8-8 8h-3.06c-3.03 0-5.8-1.71-7.15-4.42-1.56-3.12-5.96-3.29-7.76-.3l-17.37 28.95zM408 358.43c0 4.24-1.69 8.31-4.69 11.31l-9.57 9.57c-3 3-7.07 4.69-11.31 4.69h-15.16c-4.24 0-8.31-1.69-11.31-4.69l-13.01-13.01a26.767 26.767 0 0 0-25.42-7.04l-21.27 5.32c-1.27.32-2.57.48-3.88.48h-10.34c-4.24 0-8.31-1.69-11.31-4.69l-11.91-11.91a8.008 8.008 0 0 1-2.34-5.66v-10.2c0-3.27 1.99-6.21 5.03-7.43l39.34-15.74c1.98-.79 3.86-1.82 5.59-3.05l23.71-16.89a7.978 7.978 0 0 1 4.64-1.48h12.09c3.23 0 6.15 1.94 7.39 4.93l5.35 12.85a4 4 0 0 0 3.69 2.46h3.8c1.78 0 3.35-1.18 3.84-2.88l4.2-14.47c.5-1.71 2.06-2.88 3.84-2.88h6.06c2.21 0 4 1.79 4 4v12.93c0 2.12.84 4.16 2.34 5.66l11.91 11.91c3 3 4.69 7.07 4.69 11.31v24.6z\"],\n    \"globe-europe\": [496, 512, [], \"f7a2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm200 248c0 22.5-3.9 44.2-10.8 64.4h-20.3c-4.3 0-8.4-1.7-11.4-4.8l-32-32.6c-4.5-4.6-4.5-12.1.1-16.7l12.5-12.5v-8.7c0-3-1.2-5.9-3.3-8l-9.4-9.4c-2.1-2.1-5-3.3-8-3.3h-16c-6.2 0-11.3-5.1-11.3-11.3 0-3 1.2-5.9 3.3-8l9.4-9.4c2.1-2.1 5-3.3 8-3.3h32c6.2 0 11.3-5.1 11.3-11.3v-9.4c0-6.2-5.1-11.3-11.3-11.3h-36.7c-8.8 0-16 7.2-16 16v4.5c0 6.9-4.4 13-10.9 15.2l-31.6 10.5c-3.3 1.1-5.5 4.1-5.5 7.6v2.2c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8s-3.6-8-8-8H247c-3 0-5.8 1.7-7.2 4.4l-9.4 18.7c-2.7 5.4-8.2 8.8-14.3 8.8H194c-8.8 0-16-7.2-16-16V199c0-4.2 1.7-8.3 4.7-11.3l20.1-20.1c4.6-4.6 7.2-10.9 7.2-17.5 0-3.4 2.2-6.5 5.5-7.6l40-13.3c1.7-.6 3.2-1.5 4.4-2.7l26.8-26.8c2.1-2.1 3.3-5 3.3-8 0-6.2-5.1-11.3-11.3-11.3H258l-16 16v8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-20c0-2.5 1.2-4.9 3.2-6.4l28.9-21.7c1.9-.1 3.8-.3 5.7-.3C358.3 56 448 145.7 448 256zM130.1 149.1c0-3 1.2-5.9 3.3-8l25.4-25.4c2.1-2.1 5-3.3 8-3.3 6.2 0 11.3 5.1 11.3 11.3v16c0 3-1.2 5.9-3.3 8l-9.4 9.4c-2.1 2.1-5 3.3-8 3.3h-16c-6.2 0-11.3-5.1-11.3-11.3zm128 306.4v-7.1c0-8.8-7.2-16-16-16h-20.2c-10.8 0-26.7-5.3-35.4-11.8l-22.2-16.7c-11.5-8.6-18.2-22.1-18.2-36.4v-23.9c0-16 8.4-30.8 22.1-39l42.9-25.7c7.1-4.2 15.2-6.5 23.4-6.5h31.2c10.9 0 21.4 3.9 29.6 10.9l43.2 37.1h18.3c8.5 0 16.6 3.4 22.6 9.4l17.3 17.3c3.4 3.4 8.1 5.3 12.9 5.3H423c-32.4 58.9-93.8 99.5-164.9 103.1z\"],\n    \"golf-ball\": [416, 512, [], \"f450\", \"M96 416h224c0 17.7-14.3 32-32 32h-16c-17.7 0-32 14.3-32 32v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-20c0-17.7-14.3-32-32-32h-16c-17.7 0-32-14.3-32-32zm320-208c0 74.2-39 139.2-97.5 176h-221C39 347.2 0 282.2 0 208 0 93.1 93.1 0 208 0s208 93.1 208 208zm-180.1 43.9c18.3 0 33.1-14.8 33.1-33.1 0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1zm49.1 46.9c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1zm64-64c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1z\"],\n    \"gopuram\": [512, 512, [], \"f664\", \"M496 352h-16V240c0-8.8-7.2-16-16-16h-16v-80c0-8.8-7.2-16-16-16h-16V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16S96 7.2 96 16v112H80c-8.8 0-16 7.2-16 16v80H48c-8.8 0-16 7.2-16 16v112H16c-8.8 0-16 7.2-16 16v128c0 8.8 7.2 16 16 16h80V352h32V224h32v-96h32v96h-32v128h-32v160h80v-80c0-8.8 7.2-16 16-16h64c8.8 0 16 7.2 16 16v80h80V352h-32V224h-32v-96h32v96h32v128h32v160h80c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zM232 176c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v48h-48zm56 176h-64v-64c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16z\"],\n    \"graduation-cap\": [640, 512, [], \"f19d\", \"M622.34 153.2L343.4 67.5c-15.2-4.67-31.6-4.67-46.79 0L17.66 153.2c-23.54 7.23-23.54 38.36 0 45.59l48.63 14.94c-10.67 13.19-17.23 29.28-17.88 46.9C38.78 266.15 32 276.11 32 288c0 10.78 5.68 19.85 13.86 25.65L20.33 428.53C18.11 438.52 25.71 448 35.94 448h56.11c10.24 0 17.84-9.48 15.62-19.47L82.14 313.65C90.32 307.85 96 298.78 96 288c0-11.57-6.47-21.25-15.66-26.87.76-15.02 8.44-28.3 20.69-36.72L296.6 284.5c9.06 2.78 26.44 6.25 46.79 0l278.95-85.7c23.55-7.24 23.55-38.36 0-45.6zM352.79 315.09c-28.53 8.76-52.84 3.92-65.59 0l-145.02-44.55L128 384c0 35.35 85.96 64 192 64s192-28.65 192-64l-14.18-113.47-145.03 44.56z\"],\n    \"greater-than\": [384, 512, [], \"f531\", \"M365.52 209.85L59.22 67.01c-16.06-7.49-35.15-.54-42.64 15.52L3.01 111.61c-7.49 16.06-.54 35.15 15.52 42.64L236.96 256.1 18.49 357.99C2.47 365.46-4.46 384.5 3.01 400.52l13.52 29C24 445.54 43.04 452.47 59.06 445l306.47-142.91a32.003 32.003 0 0 0 18.48-29v-34.23c-.01-12.45-7.21-23.76-18.49-29.01z\"],\n    \"greater-than-equal\": [448, 512, [], \"f532\", \"M55.22 107.69l175.56 68.09-175.44 68.05c-18.39 6.03-27.88 24.39-21.2 41l12.09 30.08c6.68 16.61 26.99 25.19 45.38 19.15L393.02 214.2c13.77-4.52 22.98-16.61 22.98-30.17v-15.96c0-13.56-9.21-25.65-22.98-30.17L91.3 17.92c-18.29-6-38.51 2.53-45.15 19.06L34.12 66.9c-6.64 16.53 2.81 34.79 21.1 40.79zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM144 400h-8c-17.7 0-32-14.3-32-32v-8h40v40zm0-56h-40v-8c0-17.7 14.3-32 32-32h8v40zm-8-136c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm72 192h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm-8-104c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64 128c0 17.7-14.3 32-32 32h-8v-40h40v8zm0-24h-40v-40h8c17.7 0 32 14.3 32 32v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm80 256c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm63.7 128.7c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zm-160 0c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 144c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam-sweat\": [504, 512, [], \"f583\", \"M456 128c26.5 0 48-21 48-47 0-20-28.5-60.4-41.6-77.8-3.2-4.3-9.6-4.3-12.8 0C436.5 20.6 408 61 408 81c0 26 21.5 47 48 47zm0 32c-44.1 0-80-35.4-80-79 0-4.4.3-14.2 8.1-32.2C345 23.1 298.3 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-35.1-7.4-68.4-20.5-98.6-6.3 1.5-12.7 2.6-19.5 2.6zm-128-8c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM90.4 183.6c6.7-17.6 26.7-26.7 44.9-21.9l7.1 1.9 2-7.1c5-18.1 22.8-30.9 41.5-27.9 21.4 3.4 34.4 24.2 28.8 44.5L195.3 243c-1.2 4.5-5.9 7.2-10.5 6l-70.2-18.2c-20.4-5.4-31.9-27-24.2-47.2zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm133.4-201.3l-70.2 18.2c-4.5 1.2-9.2-1.5-10.5-6L281.3 173c-5.6-20.3 7.4-41.1 28.8-44.5 18.6-3 36.4 9.8 41.5 27.9l2 7.1 7.1-1.9c18.2-4.7 38.2 4.3 44.9 21.9 7.7 20.3-3.8 41.9-24.2 47.2z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M409.6 111.9c22.6-3.2 73.5-12 88.3-26.8 19.2-19.2 18.9-50.6-.7-70.2S446-5 426.9 14.2c-14.8 14.8-23.5 65.7-26.8 88.3-.8 5.5 3.9 10.2 9.5 9.4zM102.4 400.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm311.7-256.5c-33 3.9-48.6-25.1-45.7-45.7 3.4-24 7.4-42.1 11.5-56.5C285.1-13.4 161.8-.5 80.6 80.6-.5 161.7-13.4 285 41.4 379.9c14.4-4.1 32.4-8 56.5-11.5 33.2-3.9 48.6 25.2 45.7 45.7-3.4 24-7.4 42.1-11.5 56.5 94.8 54.8 218.1 41.9 299.3-39.2s94-204.4 39.2-299.3c-14.4 4.1-32.5 8-56.5 11.5zM255.7 106c3.3-13.2 22.4-11.5 23.6 1.8l4.8 52.3 52.3 4.8c13.4 1.2 14.9 20.3 1.8 23.6l-90.5 22.6c-8.9 2.2-16.7-5.9-14.5-14.5l22.5-90.6zm-90.9 230.3L160 284l-52.3-4.8c-13.4-1.2-14.9-20.3-1.8-23.6l90.5-22.6c8.8-2.2 16.7 5.8 14.5 14.5L188.3 338c-3.1 13.2-22.2 11.7-23.5-1.7zm215.7 44.2c-29.3 29.3-75.7 50.4-116.7 50.4-18.9 0-36.6-4.5-51-14.7-9.8-6.9-8.7-21.8 2-27.2 28.3-14.6 63.9-42.4 97.8-76.3s61.7-69.6 76.3-97.8c5.4-10.5 20.2-11.9 27.3-2 32.3 45.3 7.1 124.7-35.7 167.6z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM94.6 168.9l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.2 1 8.9 8.6 4.3 13.2l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L152 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.6-4.7-1.9-12.3 4.3-13.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm157.7-249.9l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L344 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.5-4.6-1.9-12.2 4.3-13.2l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.3.9 9 8.5 4.4 13.1z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M102.4 256.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm523.4 26.8c-14.8-14.8-65.7-23.5-88.3-26.8-5.5-.8-10.3 3.9-9.5 9.5 3.2 22.6 12 73.5 26.8 88.3 19.2 19.2 50.6 18.9 70.2-.7s20-51.2.8-70.3zm-129.4-12.8c-3.8-26.6 19.1-49.5 45.7-45.7 8.9 1.3 16.8 2.7 24.3 4.1C552.7 104.5 447.7 8 320 8S87.3 104.5 73.6 228.5c7.5-1.4 15.4-2.8 24.3-4.1 33.2-3.9 48.6 25.3 45.7 45.7-11.8 82.3-29.9 100.4-35.8 106.4-.9.9-2 1.6-3 2.5 42.7 74.6 123 125 215.2 125s172.5-50.4 215.2-125.1c-1-.9-2.1-1.5-3-2.5-5.9-5.9-24-24-35.8-106.3zM400 152c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.7 9.2-21.6 20.7-17.9C227.1 330.5 272 336 320 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-34.9 134.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M293.1 374.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-33.8 210.3l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.7 4.7 7.7 15.9 0 20.6zm163 30c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.8-4.7-7.8-15.9 0-20.6l80-48c11.7-6.9 23.9 7.7 15.4 18L343.6 208l33.6 40.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M344 184c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-56 225l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L112 233c-8.5 7.4-21.6.3-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c1.6 11.1-11.6 18.2-20 10.8zm152 39c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm-50.9 102.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm168 25l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.6 11-11.5 18.2-20 10.8zm-243.1 87.8C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6 20.7 17.9-9.2 55-83.2 93.3-143.8 93.3s-134.5-38.3-143.8-93.3c-2-11.9 9.3-21.6 20.7-17.9z\"],\n    \"grip-horizontal\": [448, 512, [], \"f58d\", \"M96 288H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM96 96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"grip-lines\": [512, 512, [], \"f7a4\", \"M496 288H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-128H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"grip-lines-vertical\": [256, 512, [], \"f7a5\", \"M96 496V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16zm128 0V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16z\"],\n    \"grip-vertical\": [320, 512, [], \"f58e\", \"M96 32H32C14.33 32 0 46.33 0 64v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM288 32h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"guitar\": [512, 512, [], \"f7a6\", \"M502.6 54.6L457.4 9.4c-12.5-12.5-32.8-12.5-45.3 0l-67.9 67.9c-12.5 12.5-12.5 32.8 0 45.3L290 176.7c-45.4-29-100.4-28.9-133.5 4.2-9.7 9.7-16.4 21.2-20.5 33.9-6.1 18.8-23.5 33.1-42.7 34.9-24 2.3-46.3 11.6-63.4 28.8C-16.3 324.6-8 407.6 48.2 463.8c56.2 56.2 139.2 64.4 185.3 18.3 17.2-17.1 26.5-39.4 28.8-63.5 1.8-19.1 16.1-36.6 34.9-42.7 12.7-4.1 24.2-10.8 33.9-20.5 33.1-33.1 33.1-88.1 4.2-133.5l54.2-54.2c12.5 12.5 32.8 12.5 45.3 0l67.9-67.9c12.4-12.4 12.4-32.7-.1-45.2zM208 352c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"h-square\": [448, 512, [], \"f0fd\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-112 48h-32c-8.837 0-16 7.163-16 16v80H160v-80c0-8.837-7.163-16-16-16h-32c-8.837 0-16 7.163-16 16v224c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16v-80h128v80c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16V144c0-8.837-7.163-16-16-16z\"],\n    \"hamburger\": [512, 512, [], \"f805\", \"M464 256H48a48 48 0 0 0 0 96h416a48 48 0 0 0 0-96zm16 128H32a16 16 0 0 0-16 16v16a64 64 0 0 0 64 64h352a64 64 0 0 0 64-64v-16a16 16 0 0 0-16-16zM58.64 224h394.72c34.57 0 54.62-43.9 34.82-75.88C448 83.2 359.55 32.1 256 32c-103.54.1-192 51.2-232.18 116.11C4 180.09 24.07 224 58.64 224zM384 112a16 16 0 1 1-16 16 16 16 0 0 1 16-16zM256 80a16 16 0 1 1-16 16 16 16 0 0 1 16-16zm-128 32a16 16 0 1 1-16 16 16 16 0 0 1 16-16z\"],\n    \"hammer\": [576, 512, [], \"f6e3\", \"M571.31 193.94l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31-28.9-28.9c5.63-21.31.36-44.9-16.35-61.61l-45.25-45.25c-62.48-62.48-163.79-62.48-226.28 0l90.51 45.25v18.75c0 16.97 6.74 33.25 18.75 45.25l49.14 49.14c16.71 16.71 40.3 21.98 61.61 16.35l28.9 28.9-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l90.51-90.51c6.23-6.24 6.23-16.37-.02-22.62zm-286.72-15.2c-3.7-3.7-6.84-7.79-9.85-11.95L19.64 404.96c-25.57 23.88-26.26 64.19-1.53 88.93s65.05 24.05 88.93-1.53l238.13-255.07c-3.96-2.91-7.9-5.87-11.44-9.41l-49.14-49.14z\"],\n    \"hamsa\": [512, 512, [], \"f665\", \"M509.34 307.25C504.28 295.56 492.75 288 480 288h-64V80c0-22-18-40-40-40s-40 18-40 40v134c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V40c0-22-18-40-40-40s-40 18-40 40v174c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V80c0-22-18-40-40-40S96 58 96 80v208H32c-12.75 0-24.28 7.56-29.34 19.25a31.966 31.966 0 0 0 5.94 34.58l102.69 110.03C146.97 490.08 199.69 512 256 512s109.03-21.92 144.72-60.14L503.4 341.83a31.966 31.966 0 0 0 5.94-34.58zM256 416c-53.02 0-96-64-96-64s42.98-64 96-64 96 64 96 64-42.98 64-96 64zm0-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"hand-holding\": [576, 512, [], \"f4bd\", \"M565.3 328.1c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-heart\": [576, 512, [], \"f4be\", \"M275.3 250.5c7 7.4 18.4 7.4 25.5 0l108.9-114.2c31.6-33.2 29.8-88.2-5.6-118.8-30.8-26.7-76.7-21.9-104.9 7.7L288 36.9l-11.1-11.6C248.7-4.4 202.8-9.2 172 17.5c-35.3 30.6-37.2 85.6-5.6 118.8l108.9 114.2zm290 77.6c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-usd\": [544, 512, [], \"f4c0\", \"M257.6 144.3l50 14.3c3.6 1 6.1 4.4 6.1 8.1 0 4.6-3.8 8.4-8.4 8.4h-32.8c-3.6 0-7.1-.8-10.3-2.2-4.8-2.2-10.4-1.7-14.1 2l-17.5 17.5c-5.3 5.3-4.7 14.3 1.5 18.4 9.5 6.3 20.3 10.1 31.8 11.5V240c0 8.8 7.2 16 16 16h16c8.8 0 16-7.2 16-16v-17.6c30.3-3.6 53.3-31 49.3-63-2.9-23-20.7-41.3-42.9-47.7l-50-14.3c-3.6-1-6.1-4.4-6.1-8.1 0-4.6 3.8-8.4 8.4-8.4h32.8c3.6 0 7.1.8 10.3 2.2 4.8 2.2 10.4 1.7 14.1-2l17.5-17.5c5.3-5.3 4.7-14.3-1.5-18.4-9.5-6.3-20.3-10.1-31.8-11.5V16c0-8.8-7.2-16-16-16h-16c-8.8 0-16 7.2-16 16v17.6c-30.3 3.6-53.3 31-49.3 63 2.9 23 20.7 41.3 42.9 47.7zm276.3 183.8c-11.2-10.7-28.5-10-40.3 0L406.4 402c-10.7 9.1-24 14-37.8 14H256.9c-8.3 0-15.1-7.2-15.1-16s6.8-16 15.1-16h73.9c15.1 0 29-10.9 31.4-26.6 3.1-20-11.5-37.4-29.8-37.4H181.3c-25.5 0-50.2 9.3-69.9 26.3L67.5 384H15.1C6.8 384 0 391.2 0 400v96c0 8.8 6.8 16 15.1 16H352c13.7 0 27-4.9 37.8-14l142.8-121c14.4-12.1 15.5-35.3 1.3-48.9z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M384 480h192V363.778a95.998 95.998 0 0 0-14.833-51.263L398.127 54.368A48 48 0 0 0 357.544 32H24C10.745 32 0 42.745 0 56v16c0 30.928 25.072 56 56 56h229.981c12.844 0 21.556 13.067 16.615 24.923l-21.41 51.385A32 32 0 0 1 251.648 224H128c-35.346 0-64 28.654-64 64v8c0 13.255 10.745 24 24 24h147.406a47.995 47.995 0 0 1 25.692 7.455l111.748 70.811A24.001 24.001 0 0 1 384 418.539V480z\"],\n    \"hand-middle-finger\": [512, 512, [], \"f806\", \"M479.93 317.12a37.33 37.33 0 0 0-28.28-36.19L416 272v-49.59c0-11.44-9.69-21.29-23.15-23.54l-38.4-6.4C336.63 189.5 320 200.86 320 216v32a8 8 0 0 1-16 0V50c0-26.28-20.25-49.2-46.52-50A48 48 0 0 0 208 48v200a8 8 0 0 1-16 0v-32c0-15.15-16.63-26.51-34.45-23.54l-30.68 5.12c-18 3-30.87 16.12-30.87 31.38V376a8 8 0 0 1-16 0v-76l-27.36 15A37.34 37.34 0 0 0 32 348.4v73.47a37.31 37.31 0 0 0 10.93 26.39l30.93 30.93A112 112 0 0 0 153.05 512h215A112 112 0 0 0 480 400z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M408.781 128.007C386.356 127.578 368 146.36 368 168.79V256h-8V79.79c0-22.43-18.356-41.212-40.781-40.783C297.488 39.423 280 57.169 280 79v177h-8V40.79C272 18.36 253.644-.422 231.219.007 209.488.423 192 18.169 192 40v216h-8V80.79c0-22.43-18.356-41.212-40.781-40.783C121.488 40.423 104 58.169 104 80v235.992l-31.648-43.519c-12.993-17.866-38.009-21.817-55.877-8.823-17.865 12.994-21.815 38.01-8.822 55.877l125.601 172.705A48 48 0 0 0 172.073 512h197.59c22.274 0 41.622-15.324 46.724-37.006l26.508-112.66a192.011 192.011 0 0 0 5.104-43.975V168c.001-21.831-17.487-39.577-39.218-39.993z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M408 216c-22.092 0-40 17.909-40 40h-8v-32c0-22.091-17.908-40-40-40s-40 17.909-40 40v32h-8V48c0-26.51-21.49-48-48-48s-48 21.49-48 48v208h-13.572L92.688 78.449C82.994 53.774 55.134 41.63 30.461 51.324 5.787 61.017-6.356 88.877 3.337 113.551l74.765 190.342-31.09 24.872c-15.381 12.306-19.515 33.978-9.741 51.081l64 112A39.998 39.998 0 0 0 136 512h240c18.562 0 34.686-12.77 38.937-30.838l32-136A39.97 39.97 0 0 0 448 336v-80c0-22.091-17.908-40-40-40z\"],\n    \"hand-point-down\": [384, 512, [], \"f0a7\", \"M91.826 467.2V317.966c-8.248 5.841-16.558 10.57-24.918 14.153C35.098 345.752-.014 322.222 0 288c.008-18.616 10.897-32.203 29.092-40 28.286-12.122 64.329-78.648 77.323-107.534 7.956-17.857 25.479-28.453 43.845-28.464l.001-.002h171.526c11.812 0 21.897 8.596 23.703 20.269 7.25 46.837 38.483 61.76 38.315 123.731-.007 2.724.195 13.254.195 16 0 50.654-22.122 81.574-71.263 72.6-9.297 18.597-39.486 30.738-62.315 16.45-21.177 24.645-53.896 22.639-70.944 6.299V467.2c0 24.15-20.201 44.8-43.826 44.8-23.283 0-43.826-21.35-43.826-44.8zM112 72V24c0-13.255 10.745-24 24-24h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24zm212-24c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M44.8 155.826h149.234c-5.841-8.248-10.57-16.558-14.153-24.918C166.248 99.098 189.778 63.986 224 64c18.616.008 32.203 10.897 40 29.092 12.122 28.286 78.648 64.329 107.534 77.323 17.857 7.956 28.453 25.479 28.464 43.845l.002.001v171.526c0 11.812-8.596 21.897-20.269 23.703-46.837 7.25-61.76 38.483-123.731 38.315-2.724-.007-13.254.195-16 .195-50.654 0-81.574-22.122-72.6-71.263-18.597-9.297-30.738-39.486-16.45-62.315-24.645-21.177-22.639-53.896-6.299-70.944H44.8c-24.15 0-44.8-20.201-44.8-43.826 0-23.283 21.35-43.826 44.8-43.826zM440 176h48c13.255 0 24 10.745 24 24v192c0 13.255-10.745 24-24 24h-48c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24zm24 212c11.046 0 20-8.954 20-20s-8.954-20-20-20-20 8.954-20 20 8.954 20 20 20z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M512 199.652c0 23.625-20.65 43.826-44.8 43.826h-99.851c16.34 17.048 18.346 49.766-6.299 70.944 14.288 22.829 2.147 53.017-16.45 62.315C353.574 425.878 322.654 448 272 448c-2.746 0-13.276-.203-16-.195-61.971.168-76.894-31.065-123.731-38.315C120.596 407.683 112 397.599 112 385.786V214.261l.002-.001c.011-18.366 10.607-35.889 28.464-43.845 28.886-12.994 95.413-49.038 107.534-77.323 7.797-18.194 21.384-29.084 40-29.092 34.222-.014 57.752 35.098 44.119 66.908-3.583 8.359-8.312 16.67-14.153 24.918H467.2c23.45 0 44.8 20.543 44.8 43.826zM96 200v192c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24h48c13.255 0 24 10.745 24 24zM68 368c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-up\": [384, 512, [], \"f0a6\", \"M135.652 0c23.625 0 43.826 20.65 43.826 44.8v99.851c17.048-16.34 49.766-18.346 70.944 6.299 22.829-14.288 53.017-2.147 62.315 16.45C361.878 158.426 384 189.346 384 240c0 2.746-.203 13.276-.195 16 .168 61.971-31.065 76.894-38.315 123.731C343.683 391.404 333.599 400 321.786 400H150.261l-.001-.002c-18.366-.011-35.889-10.607-43.845-28.464C93.421 342.648 57.377 276.122 29.092 264 10.897 256.203.008 242.616 0 224c-.014-34.222 35.098-57.752 66.908-44.119 8.359 3.583 16.67 8.312 24.918 14.153V44.8c0-23.45 20.543-44.8 43.826-44.8zM136 416h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24v-48c0-13.255 10.745-24 24-24zm168 28c-11.046 0-20 8.954-20 20s8.954 20 20 20 20-8.954 20-20-8.954-20-20-20z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M448 240v96c0 3.084-.356 6.159-1.063 9.162l-32 136C410.686 499.23 394.562 512 376 512H168a40.004 40.004 0 0 1-32.35-16.473l-127.997-176c-12.993-17.866-9.043-42.883 8.822-55.876 17.867-12.994 42.884-9.043 55.877 8.823L104 315.992V40c0-22.091 17.908-40 40-40s40 17.909 40 40v200h8v-40c0-22.091 17.908-40 40-40s40 17.909 40 40v40h8v-24c0-22.091 17.908-40 40-40s40 17.909 40 40v24h8c0-22.091 17.908-40 40-40s40 17.909 40 40zm-256 80h-8v96h8v-96zm88 0h-8v96h8v-96zm88 0h-8v96h8v-96z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M464.8 80c-26.9-.4-48.8 21.2-48.8 48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v32h-8V80.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v136l-8-7.1v-48.1c0-26.3-20.9-48.3-47.2-48.8C21.9 127.6 0 149.2 0 176v66.4c0 27.4 11.7 53.5 32.2 71.8l111.7 99.3c10.2 9.1 16.1 22.2 16.1 35.9v6.7c0 13.3 10.7 24 24 24h240c13.3 0 24-10.7 24-24v-2.9c0-12.8 2.6-25.5 7.5-37.3l49-116.3c5-11.8 7.5-24.5 7.5-37.3V128.8c0-26.3-20.9-48.4-47.2-48.8z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M216 440c0-22.092 17.909-40 40-40v-8h-32c-22.091 0-40-17.908-40-40s17.909-40 40-40h32v-8H48c-26.51 0-48-21.49-48-48s21.49-48 48-48h208v-13.572l-177.551-69.74c-24.674-9.694-36.818-37.555-27.125-62.228 9.693-24.674 37.554-36.817 62.228-27.124l190.342 74.765 24.872-31.09c12.306-15.381 33.978-19.515 51.081-9.741l112 64A40.002 40.002 0 0 1 512 168v240c0 18.562-12.77 34.686-30.838 38.937l-136 32A39.982 39.982 0 0 1 336 480h-80c-22.091 0-40-17.908-40-40z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M481.3 97.1c-21.5-5.1-43.1 8.2-48.2 29.6L402.3 256h-11.1l43.6-174.3c5.4-21.4-7.7-43.1-29.1-48.5s-43.1 7.7-48.5 29.1L308.8 256h-15.1L242 31.1c-5-21.6-26.4-35-48-30.1-21.5 4.9-35 26.4-30 47.9l47.6 207h-9.8L167 103.1c-4.9-21.5-26.3-35-47.9-30.1-21.5 4.9-35 26.3-30.1 47.9l39 171.6v79.4l-60.6-57c-16.1-15.1-41.4-14.4-56.5 1.7s-14.4 41.4 1.7 56.5L146.3 499c8.9 8.4 20.7 13 32.9 13h216.7c21.3 0 40-14 46-34.4l26.2-88.3c2.6-8.9 4-18 4-27.3v-42c0-7.5.9-15 2.6-22.2L511 145.3c5-21.5-8.3-43.1-29.7-48.2z\"],\n    \"hands\": [640, 512, [], \"f4c2\", \"M204.8 230.4c-10.6-14.1-30.7-17-44.8-6.4-14.1 10.6-17 30.7-6.4 44.8l38.1 50.8c4.8 6.4 4.1 15.3-1.5 20.9l-12.8 12.8c-6.7 6.7-17.6 6.2-23.6-1.1L64 244.4V96c0-17.7-14.3-32-32-32S0 78.3 0 96v218.4c0 10.9 3.7 21.5 10.5 30l104.1 134.3c5 6.5 8.4 13.9 10.4 21.7 1.8 6.9 8.1 11.6 15.3 11.6H272c8.8 0 16-7.2 16-16V384c0-27.7-9-54.6-25.6-76.8l-57.6-76.8zM608 64c-17.7 0-32 14.3-32 32v148.4l-89.8 107.8c-6 7.2-17 7.7-23.6 1.1l-12.8-12.8c-5.6-5.6-6.3-14.5-1.5-20.9l38.1-50.8c10.6-14.1 7.7-34.2-6.4-44.8-14.1-10.6-34.2-7.7-44.8 6.4l-57.6 76.8C361 329.4 352 356.3 352 384v112c0 8.8 7.2 16 16 16h131.7c7.1 0 13.5-4.7 15.3-11.6 2-7.8 5.4-15.2 10.4-21.7l104.1-134.3c6.8-8.5 10.5-19.1 10.5-30V96c0-17.7-14.3-32-32-32z\"],\n    \"hands-helping\": [640, 512, [], \"f4c4\", \"M488 192H336v56c0 39.7-32.3 72-72 72s-72-32.3-72-72V126.4l-64.9 39C107.8 176.9 96 197.8 96 220.2v47.3l-80 46.2C.7 322.5-4.6 342.1 4.3 357.4l80 138.6c8.8 15.3 28.4 20.5 43.7 11.7L231.4 448H368c35.3 0 64-28.7 64-64h16c17.7 0 32-14.3 32-32v-64h8c13.3 0 24-10.7 24-24v-48c0-13.3-10.7-24-24-24zm147.7-37.4L555.7 16C546.9.7 527.3-4.5 512 4.3L408.6 64H306.4c-12 0-23.7 3.4-33.9 9.7L239 94.6c-9.4 5.8-15 16.1-15 27.1V248c0 22.1 17.9 40 40 40s40-17.9 40-40v-88h184c30.9 0 56 25.1 56 56v28.5l80-46.2c15.3-8.9 20.5-28.4 11.7-43.7z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M434.7 64h-85.9c-8 0-15.7 3-21.6 8.4l-98.3 90c-.1.1-.2.3-.3.4-16.6 15.6-16.3 40.5-2.1 56 12.7 13.9 39.4 17.6 56.1 2.7.1-.1.3-.1.4-.2l79.9-73.2c6.5-5.9 16.7-5.5 22.6 1 6 6.5 5.5 16.6-1 22.6l-26.1 23.9L504 313.8c2.9 2.4 5.5 5 7.9 7.7V128l-54.6-54.6c-5.9-6-14.1-9.4-22.6-9.4zM544 128.2v223.9c0 17.7 14.3 32 32 32h64V128.2h-96zm48 223.9c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM0 384h64c17.7 0 32-14.3 32-32V128.2H0V384zm48-63.9c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16c0-8.9 7.2-16 16-16zm435.9 18.6L334.6 217.5l-30 27.5c-29.7 27.1-75.2 24.5-101.7-4.4-26.9-29.4-24.8-74.9 4.4-101.7L289.1 64h-83.8c-8.5 0-16.6 3.4-22.6 9.4L128 128v223.9h18.3l90.5 81.9c27.4 22.3 67.7 18.1 90-9.3l.2-.2 17.9 15.5c15.9 13 39.4 10.5 52.3-5.4l31.4-38.6 5.4 4.4c13.7 11.1 33.9 9.1 45-4.7l9.5-11.7c11.2-13.8 9.1-33.9-4.6-45.1z\"],\n    \"hanukiah\": [640, 512, [], \"f6e6\", \"M232 160c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm-64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm224 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm88 8c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v120h32V168zm-440-8c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm520 0h-32c-8.84 0-16 7.16-16 16v112c0 17.67-14.33 32-32 32H352V128c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v192H96c-17.67 0-32-14.33-32-32V176c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v112c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V176c0-8.84-7.16-16-16-16zm-16-32c13.25 0 24-11.94 24-26.67S608 48 608 48s-24 38.61-24 53.33S594.75 128 608 128zm-576 0c13.25 0 24-11.94 24-26.67S32 48 32 48 8 86.61 8 101.33 18.75 128 32 128zm288-48c13.25 0 24-11.94 24-26.67S320 0 320 0s-24 38.61-24 53.33S306.75 80 320 80zm-208 48c13.25 0 24-11.94 24-26.67S112 48 112 48s-24 38.61-24 53.33S98.75 128 112 128zm64 0c13.25 0 24-11.94 24-26.67S176 48 176 48s-24 38.61-24 53.33S162.75 128 176 128zm64 0c13.25 0 24-11.94 24-26.67S240 48 240 48s-24 38.61-24 53.33S226.75 128 240 128zm160 0c13.25 0 24-11.94 24-26.67S400 48 400 48s-24 38.61-24 53.33S386.75 128 400 128zm64 0c13.25 0 24-11.94 24-26.67S464 48 464 48s-24 38.61-24 53.33S450.75 128 464 128zm64 0c13.25 0 24-11.94 24-26.67S528 48 528 48s-24 38.61-24 53.33S514.75 128 528 128z\"],\n    \"hard-hat\": [512, 512, [], \"f807\", \"M480 288c0-80.25-49.28-148.92-119.19-177.62L320 192V80a16 16 0 0 0-16-16h-96a16 16 0 0 0-16 16v112l-40.81-81.62C81.28 139.08 32 207.75 32 288v64h448zm16 96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"hashtag\": [448, 512, [], \"f292\", \"M440.667 182.109l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l14.623-81.891C377.123 38.754 371.468 32 363.997 32h-40.632a12 12 0 0 0-11.813 9.891L296.175 128H197.54l14.623-81.891C213.477 38.754 207.822 32 200.35 32h-40.632a12 12 0 0 0-11.813 9.891L132.528 128H53.432a12 12 0 0 0-11.813 9.891l-7.143 40C33.163 185.246 38.818 192 46.289 192h74.81L98.242 320H19.146a12 12 0 0 0-11.813 9.891l-7.143 40C-1.123 377.246 4.532 384 12.003 384h74.81L72.19 465.891C70.877 473.246 76.532 480 84.003 480h40.632a12 12 0 0 0 11.813-9.891L151.826 384h98.634l-14.623 81.891C234.523 473.246 240.178 480 247.65 480h40.632a12 12 0 0 0 11.813-9.891L315.472 384h79.096a12 12 0 0 0 11.813-9.891l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l22.857-128h79.096a12 12 0 0 0 11.813-9.891zM261.889 320h-98.634l22.857-128h98.634l-22.857 128z\"],\n    \"hat-wizard\": [512, 512, [], \"f6e8\", \"M496 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-304-64l-64-32 64-32 32-64 32 64 64 32-64 32-16 32h208l-86.41-201.63a63.955 63.955 0 0 1-1.89-45.45L416 0 228.42 107.19a127.989 127.989 0 0 0-53.46 59.15L64 416h144l-16-32zm64-224l16-32 16 32 32 16-32 16-16 32-16-32-32-16 32-16z\"],\n    \"haykal\": [512, 512, [], \"f666\", \"M496.25 202.52l-110-15.44 41.82-104.34c6.67-16.64-11.6-32.18-26.59-22.63L307.44 120 273.35 12.82C270.64 4.27 263.32 0 256 0c-7.32 0-14.64 4.27-17.35 12.82l-34.09 107.19-94.04-59.89c-14.99-9.55-33.25 5.99-26.59 22.63l41.82 104.34-110 15.43c-17.54 2.46-21.68 26.27-6.03 34.67l98.16 52.66-74.48 83.54c-10.92 12.25-1.72 30.93 13.29 30.93 1.31 0 2.67-.14 4.07-.45l108.57-23.65-4.11 112.55c-.43 11.65 8.87 19.22 18.41 19.22 5.15 0 10.39-2.21 14.2-7.18l68.18-88.9 68.18 88.9c3.81 4.97 9.04 7.18 14.2 7.18 9.54 0 18.84-7.57 18.41-19.22l-4.11-112.55 108.57 23.65c17.36 3.76 29.21-17.2 17.35-30.49l-74.48-83.54 98.16-52.66c15.64-8.39 11.5-32.2-6.04-34.66zM338.51 311.68l-51.89-11.3 1.97 53.79L256 311.68l-32.59 42.49 1.96-53.79-51.89 11.3 35.6-39.93-46.92-25.17 52.57-7.38-19.99-49.87 44.95 28.62L256 166.72l16.29 51.23 44.95-28.62-19.99 49.87 52.57 7.38-46.92 25.17 35.61 39.93z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M576 304v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48zm-48-80a79.557 79.557 0 0 1 30.777 6.165L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L17.223 230.165A79.557 79.557 0 0 1 48 224h480zm-48 96c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm-96 0c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"heading\": [512, 512, [], \"f1dc\", \"M448 96v320h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H320a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V288H160v128h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H32a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V96H32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16h-32v128h192V96h-32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16z\"],\n    \"headphones\": [512, 512, [], \"f025\", \"M256 32C114.52 32 0 146.496 0 288v48a32 32 0 0 0 17.689 28.622l14.383 7.191C34.083 431.903 83.421 480 144 480h24c13.255 0 24-10.745 24-24V280c0-13.255-10.745-24-24-24h-24c-31.342 0-59.671 12.879-80 33.627V288c0-105.869 86.131-192 192-192s192 86.131 192 192v1.627C427.671 268.879 399.342 256 368 256h-24c-13.255 0-24 10.745-24 24v176c0 13.255 10.745 24 24 24h24c60.579 0 109.917-48.098 111.928-108.187l14.382-7.191A32 32 0 0 0 512 336v-48c0-141.479-114.496-256-256-256z\"],\n    \"headphones-alt\": [512, 512, [], \"f58f\", \"M160 288h-16c-35.35 0-64 28.7-64 64.12v63.76c0 35.41 28.65 64.12 64 64.12h16c17.67 0 32-14.36 32-32.06V320.06c0-17.71-14.33-32.06-32-32.06zm208 0h-16c-17.67 0-32 14.35-32 32.06v127.88c0 17.7 14.33 32.06 32 32.06h16c35.35 0 64-28.71 64-64.12v-63.76c0-35.41-28.65-64.12-64-64.12zM256 32C112.91 32 4.57 151.13 0 288v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288c0-114.67 93.33-207.8 208-207.82 114.67.02 208 93.15 208 207.82v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288C507.43 151.13 399.09 32 256 32z\"],\n    \"headset\": [512, 512, [], \"f590\", \"M192 208c0-17.67-14.33-32-32-32h-16c-35.35 0-64 28.65-64 64v48c0 35.35 28.65 64 64 64h16c17.67 0 32-14.33 32-32V208zm176 144c35.35 0 64-28.65 64-64v-48c0-35.35-28.65-64-64-64h-16c-17.67 0-32 14.33-32 32v112c0 17.67 14.33 32 32 32h16zM256 0C113.18 0 4.58 118.83 0 256v16c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-16c0-114.69 93.31-208 208-208s208 93.31 208 208h-.12c.08 2.43.12 165.72.12 165.72 0 23.35-18.93 42.28-42.28 42.28H320c0-26.51-21.49-48-48-48h-32c-26.51 0-48 21.49-48 48s21.49 48 48 48h181.72c49.86 0 90.28-40.42 90.28-90.28V256C507.42 118.83 398.82 0 256 0z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M462.3 62.6C407.5 15.9 326 24.3 275.7 76.2L256 96.5l-19.7-20.3C186.1 24.3 104.5 15.9 49.7 62.6c-62.8 53.6-66.1 149.8-9.9 207.9l193.5 199.8c12.5 12.9 32.8 12.9 45.3 0l193.5-199.8c56.3-58.1 53-154.3-9.8-207.9z\"],\n    \"heart-broken\": [512, 512, [], \"f7a9\", \"M473.7 73.8l-2.4-2.5c-46-47-118-51.7-169.6-14.8L336 159.9l-96 64 48 128-144-144 96-64-28.6-86.5C159.7 19.6 87 24 40.7 71.4l-2.4 2.4C-10.4 123.6-12.5 202.9 31 256l212.1 218.6c7.1 7.3 18.6 7.3 25.7 0L481 255.9c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"heartbeat\": [512, 512, [], \"f21e\", \"M320.2 243.8l-49.7 99.4c-6 12.1-23.4 11.7-28.9-.6l-56.9-126.3-30 71.7H60.6l182.5 186.5c7.1 7.3 18.6 7.3 25.7 0L451.4 288H342.3l-22.1-44.2zM473.7 73.9l-2.4-2.5c-51.5-52.6-135.8-52.6-187.4 0L256 100l-27.9-28.5c-51.5-52.7-135.9-52.7-187.4 0l-2.4 2.4C-10.4 123.7-12.5 203 31 256h102.4l35.9-86.2c5.4-12.9 23.6-13.2 29.4-.4l58.2 129.3 49-97.9c5.9-11.8 22.7-11.8 28.6 0l27.6 55.2H481c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"helicopter\": [640, 512, [], \"f533\", \"M304 384h272c17.67 0 32-14.33 32-32 0-123.71-100.29-224-224-224V64h176c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H144c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h176v64H112L68.8 70.4C65.78 66.37 61.03 64 56 64H16.01C5.6 64-2.04 73.78.49 83.88L32 192l160 64 86.4 115.2A31.992 31.992 0 0 0 304 384zm112-188.49C478.55 208.3 528.03 257.44 540.79 320H416V195.51zm219.37 263.3l-22.15-22.2c-6.25-6.26-16.24-6.1-22.64.01-7.09 6.77-13.84 11.25-24.64 11.25H240c-8.84 0-16 7.18-16 16.03v32.06c0 8.85 7.16 16.03 16 16.03h325.94c14.88 0 35.3-.47 68.45-29.52 7.02-6.14 7.57-17.05.98-23.66z\"],\n    \"highlighter\": [544, 512, [], \"f591\", \"M0 479.98L99.92 512l35.45-35.45-67.04-67.04L0 479.98zm124.61-240.01a36.592 36.592 0 0 0-10.79 38.1l13.05 42.83-50.93 50.94 96.23 96.23 50.86-50.86 42.74 13.08c13.73 4.2 28.65-.01 38.15-10.78l35.55-41.64-173.34-173.34-41.52 35.44zm403.31-160.7l-63.2-63.2c-20.49-20.49-53.38-21.52-75.12-2.35L190.55 183.68l169.77 169.78L530.27 154.4c19.18-21.74 18.15-54.63-2.35-75.13z\"],\n    \"hiking\": [384, 512, [], \"f6ec\", \"M80.95 472.23c-4.28 17.16 6.14 34.53 23.28 38.81 2.61.66 5.22.95 7.8.95 14.33 0 27.37-9.7 31.02-24.23l25.24-100.97-52.78-52.78-34.56 138.22zm14.89-196.12L137 117c2.19-8.42-3.14-16.95-11.92-19.06-43.88-10.52-88.35 15.07-99.32 57.17L.49 253.24c-2.19 8.42 3.14 16.95 11.92 19.06l63.56 15.25c8.79 2.1 17.68-3.02 19.87-11.44zM368 160h-16c-8.84 0-16 7.16-16 16v16h-34.75l-46.78-46.78C243.38 134.11 228.61 128 212.91 128c-27.02 0-50.47 18.3-57.03 44.52l-26.92 107.72a32.012 32.012 0 0 0 8.42 30.39L224 397.25V480c0 17.67 14.33 32 32 32s32-14.33 32-32v-82.75c0-17.09-6.66-33.16-18.75-45.25l-46.82-46.82c.15-.5.49-.89.62-1.41l19.89-79.57 22.43 22.43c6 6 14.14 9.38 22.62 9.38h48v240c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V176c.01-8.84-7.15-16-15.99-16zM240 96c26.51 0 48-21.49 48-48S266.51 0 240 0s-48 21.49-48 48 21.49 48 48 48z\"],\n    \"hippo\": [640, 512, [], \"f6ed\", \"M581.12 96.2c-27.67-.15-52.5 17.58-76.6 26.62C489.98 88.27 455.83 64 416 64c-11.28 0-21.95 2.3-32 5.88V56c0-13.26-10.75-24-24-24h-16c-13.25 0-24 10.74-24 24v48.98C286.01 79.58 241.24 64 192 64 85.96 64 0 135.64 0 224v240c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16v-70.79C128.35 407.57 166.72 416 208 416s79.65-8.43 112-22.79V464c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V288h128v32c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-32c17.67 0 32-14.33 32-32v-92.02c0-34.09-24.79-67.59-58.88-67.78zM448 176c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"history\": [512, 512, [], \"f1da\", \"M504 255.531c.253 136.64-111.18 248.372-247.82 248.468-59.015.042-113.223-20.53-155.822-54.911-11.077-8.94-11.905-25.541-1.839-35.607l11.267-11.267c8.609-8.609 22.353-9.551 31.891-1.984C173.062 425.135 212.781 440 256 440c101.705 0 184-82.311 184-184 0-101.705-82.311-184-184-184-48.814 0-93.149 18.969-126.068 49.932l50.754 50.754c10.08 10.08 2.941 27.314-11.313 27.314H24c-8.837 0-16-7.163-16-16V38.627c0-14.254 17.234-21.393 27.314-11.314l49.372 49.372C129.209 34.136 189.552 8 256 8c136.81 0 247.747 110.78 248 247.531zm-180.912 78.784l9.823-12.63c8.138-10.463 6.253-25.542-4.21-33.679L288 256.349V152c0-13.255-10.745-24-24-24h-16c-13.255 0-24 10.745-24 24v135.651l65.409 50.874c10.463 8.137 25.541 6.253 33.679-4.21z\"],\n    \"hockey-puck\": [512, 512, [], \"f453\", \"M0 160c0-53 114.6-96 256-96s256 43 256 96-114.6 96-256 96S0 213 0 160zm0 82.2V352c0 53 114.6 96 256 96s256-43 256-96V242.2c-113.4 82.3-398.5 82.4-512 0z\"],\n    \"holly-berry\": [448, 512, [], \"f7aa\", \"M144 192c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm112-48c0 26.5 21.5 48 48 48s48-21.5 48-48-21.5-48-48-48-48 21.5-48 48zm-32-48c26.5 0 48-21.5 48-48S250.5 0 224 0s-48 21.5-48 48 21.5 48 48 48zm-16.2 139.1c.1-12.4-13.1-20.1-23.8-13.7-34.3 20.3-71.4 32.7-108.7 36.2-9.7.9-15.6 11.3-11.6 20.2 6.2 13.9 11.1 28.6 14.7 43.8 3.6 15.2-5.3 30.6-20.2 35.1-14.9 4.5-30.1 7.6-45.3 9.1-9.7 1-15.7 11.3-11.7 20.2 15 32.8 22.9 69.5 23 107.7.1 14.4 15.2 23.1 27.6 16 33.2-19 68.9-30.5 104.8-33.9 9.7-.9 15.6-11.3 11.6-20.2-6.2-13.9-11.1-28.6-14.7-43.8-3.6-15.2 5.3-30.6 20.2-35.1 14.9-4.5 30.1-7.6 45.3-9.1 9.7-1 15.7-11.3 11.7-20.2-15.5-34.2-23.3-72.5-22.9-112.3zM435 365.6c-15.2-1.6-30.3-4.7-45.3-9.1-14.9-4.5-23.8-19.9-20.2-35.1 3.6-15.2 8.5-29.8 14.7-43.8 4-8.9-1.9-19.3-11.6-20.2-37.3-3.5-74.4-15.9-108.7-36.2-10.7-6.3-23.9 1.4-23.8 13.7 0 1.6-.2 3.2-.2 4.9.2 33.3 7 65.7 19.9 94 5.7 12.4 5.2 26.6-.6 38.9 4.9 1.2 9.9 2.2 14.8 3.7 14.9 4.5 23.8 19.9 20.2 35.1-3.6 15.2-8.5 29.8-14.7 43.8-4 8.9 1.9 19.3 11.6 20.2 35.9 3.4 71.6 14.9 104.8 33.9 12.5 7.1 27.6-1.6 27.6-16 .2-38.2 8-75 23-107.7 4.3-8.7-1.8-19.1-11.5-20.1z\"],\n    \"home\": [576, 512, [], \"f015\", \"M280.37 148.26L96 300.11V464a16 16 0 0 0 16 16l112.06-.29a16 16 0 0 0 15.92-16V368a16 16 0 0 1 16-16h64a16 16 0 0 1 16 16v95.64a16 16 0 0 0 16 16.05L464 480a16 16 0 0 0 16-16V300L295.67 148.26a12.19 12.19 0 0 0-15.3 0zM571.6 251.47L488 182.56V44.05a12 12 0 0 0-12-12h-56a12 12 0 0 0-12 12v72.61L318.47 43a48 48 0 0 0-61 0L4.34 251.47a12 12 0 0 0-1.6 16.9l25.5 31A12 12 0 0 0 45.15 301l235.22-193.74a12.19 12.19 0 0 1 15.3 0L530.9 301a12 12 0 0 0 16.9-1.6l25.5-31a12 12 0 0 0-1.7-16.93z\"],\n    \"horse\": [576, 512, [], \"f6f0\", \"M575.92 76.6c-.01-8.13-3.02-15.87-8.58-21.8-3.78-4.03-8.58-9.12-13.69-14.5 11.06-6.84 19.5-17.49 22.18-30.66C576.85 4.68 572.96 0 567.9 0H447.92c-70.69 0-128 57.31-128 128H160c-28.84 0-54.4 12.98-72 33.11V160c-48.53 0-88 39.47-88 88v56c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-56c0-13.22 6.87-24.39 16.78-31.68-.21 2.58-.78 5.05-.78 7.68 0 27.64 11.84 52.36 30.54 69.88l-25.72 68.6a63.945 63.945 0 0 0-2.16 37.99l24.85 99.41A15.982 15.982 0 0 0 107.02 512h65.96c10.41 0 18.05-9.78 15.52-19.88l-26.31-105.26 23.84-63.59L320 345.6V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V318.22c19.74-20.19 32-47.75 32-78.22 0-.22-.07-.42-.08-.64V136.89l16 7.11 18.9 37.7c7.45 14.87 25.05 21.55 40.49 15.37l32.55-13.02a31.997 31.997 0 0 0 20.12-29.74l-.06-77.71zm-64 19.4c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"horse-head\": [512, 512, [], \"f7ab\", \"M509.8 332.5l-69.9-164.3c-14.9-41.2-50.4-71-93-79.2 18-10.6 46.3-35.9 34.2-82.3-1.3-5-7.1-7.9-12-6.1L166.9 76.3C35.9 123.4 0 238.9 0 398.8V480c0 17.7 14.3 32 32 32h236.2c23.8 0 39.3-25 28.6-46.3L256 384v-.7c-45.6-3.5-84.6-30.7-104.3-69.6-1.6-3.1-.9-6.9 1.6-9.3l12.1-12.1c3.9-3.9 10.6-2.7 12.9 2.4 14.8 33.7 48.2 57.4 87.4 57.4 17.2 0 33-5.1 46.8-13.2l46 63.9c6 8.4 15.7 13.3 26 13.3h50.3c8.5 0 16.6-3.4 22.6-9.4l45.3-39.8c8.9-9.1 11.7-22.6 7.1-34.4zM328 224c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M448 492v20H0v-20c0-6.627 5.373-12 12-12h20V120c0-13.255 10.745-24 24-24h88V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v72h88c13.255 0 24 10.745 24 24v360h20c6.627 0 12 5.373 12 12zM308 192h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-168 64h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm104 128h-40c-6.627 0-12 5.373-12 12v84h64v-84c0-6.627-5.373-12-12-12zm64-96h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-116 12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40zM182 96h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6z\"],\n    \"hospital-alt\": [576, 512, [], \"f47d\", \"M544 96H416V32c0-17.7-14.3-32-32-32H192c-17.7 0-32 14.3-32 32v64H32c-17.7 0-32 14.3-32 32v368c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16V128c0-17.7-14.3-32-32-32zM160 436c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm160 128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm16-170c0 3.3-2.7 6-6 6h-26v26c0 3.3-2.7 6-6 6h-20c-3.3 0-6-2.7-6-6v-26h-26c-3.3 0-6-2.7-6-6v-20c0-3.3 2.7-6 6-6h26V86c0-3.3 2.7-6 6-6h20c3.3 0 6 2.7 6 6v26h26c3.3 0 6 2.7 6 6v20zm144 298c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"hospital-symbol\": [512, 512, [], \"f47e\", \"M256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm112 376c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-88h-96v88c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8V136c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v88h96v-88c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v240z\"],\n    \"hot-tub\": [512, 512, [], \"f593\", \"M414.21 177.65c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C378.96 6.14 372.22 0 364.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zm-108 0c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C270.96 6.14 264.22 0 256.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zM480 256H256l-110.93-83.2a63.99 63.99 0 0 0-38.4-12.8H64c-35.35 0-64 28.65-64 64v224c0 35.35 28.65 64 64 64h384c35.35 0 64-28.65 64-64V288c0-17.67-14.33-32-32-32zM128 440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zM64 128c35.35 0 64-28.65 64-64S99.35 0 64 0 0 28.65 0 64s28.65 64 64 64z\"],\n    \"hotdog\": [512, 512, [], \"f80f\", \"M488.56 23.44a80 80 0 0 0-113.12 0l-352 352a80 80 0 1 0 113.12 113.12l352-352a80 80 0 0 0 0-113.12zm-49.93 95.19c-19.6 19.59-37.52 22.67-51.93 25.14C373.76 146 364.4 147.6 352 160s-14 21.76-16.23 34.71c-2.48 14.4-5.55 32.33-25.15 51.92s-37.52 22.67-51.92 25.15C245.75 274 236.4 275.6 224 288s-14 21.75-16.23 34.7c-2.47 14.4-5.54 32.33-25.14 51.92s-37.53 22.68-51.93 25.15C117.76 402 108.4 403.6 96 416a16 16 0 0 1-22.63-22.63c19.6-19.59 37.52-22.67 51.92-25.14 13-2.22 22.3-3.82 34.71-16.23s14-21.75 16.22-34.7c2.48-14.4 5.55-32.33 25.15-51.92s37.52-22.67 51.92-25.14c13-2.22 22.3-3.83 34.7-16.23s14-21.76 16.24-34.71c2.47-14.4 5.54-32.33 25.14-51.92s37.52-22.68 51.92-25.15C394.24 110 403.59 108.41 416 96a16 16 0 0 1 22.63 22.63zM31.44 322.18L322.18 31.44l-11.54-11.55c-25-25-63.85-26.66-86.79-3.72L16.17 223.85c-22.94 22.94-21.27 61.79 3.72 86.78zm449.12-132.36L189.82 480.56l11.54 11.55c25 25 63.85 26.66 86.79 3.72l207.68-207.68c22.94-22.94 21.27-61.79-3.72-86.79z\"],\n    \"hotel\": [576, 512, [], \"f594\", \"M560 64c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h15.98v384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h240v-80c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16v80h240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-16V64h16zm-304 44.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm0 96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm-128-96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zM179.2 256h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8zM192 384c0-53.02 42.98-96 96-96s96 42.98 96 96H192zm256-140.8c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-96c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64z\"],\n    \"hourglass-end\": [384, 512, [], \"f253\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64zM192 208c-57.787 0-104-66.518-104-144h208c0 77.945-46.51 144-104 144z\"],\n    \"hourglass-half\": [384, 512, [], \"f252\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-75.078 384H99.08c17.059-46.797 52.096-80 92.92-80 40.821 0 75.862 33.196 92.922 80zm.019-256H99.078C91.988 108.548 88 86.748 88 64h208c0 22.805-3.987 44.587-11.059 64z\"],\n    \"hourglass-start\": [384, 512, [], \"f251\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-64 448H88c0-77.458 46.204-144 104-144 57.786 0 104 66.517 104 144z\"],\n    \"house-damage\": [576, 512, [], \"f6f1\", \"M288 114.96L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496c0 8.84 7.16 16 16 16h149.23L192 439.19l104.11-64-60.16-119.22L384 392.75l-104.11 64L319.81 512H496c8.84 0 16-7.16 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2L288 114.96zm282.69 121.32L512 184.45V48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v51.69L314.75 10.31C307.12 3.45 297.56.01 288 0s-19.1 3.41-26.7 10.27L5.31 236.28c-6.57 5.91-7.12 16.02-1.21 22.6l21.4 23.82c5.9 6.57 16.02 7.12 22.6 1.21L277.42 81.63c6.05-5.33 15.12-5.33 21.17 0L527.91 283.9c6.57 5.9 16.69 5.36 22.6-1.21l21.4-23.82c5.9-6.57 5.36-16.69-1.22-22.59z\"],\n    \"hryvnia\": [384, 512, [], \"f6f2\", \"M368 240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-41.86c13.41-28.63 13.74-63.33-4.13-94.05C303.34 49.84 267.1 32 229.96 32h-78.82c-24.32 0-47.86 8.53-66.54 24.09L72.83 65.9c-10.18 8.49-11.56 23.62-3.07 33.8l20.49 24.59c8.49 10.19 23.62 11.56 33.81 3.07l11.73-9.78c4.32-3.6 9.77-5.57 15.39-5.57h83.62c11.69 0 21.2 9.52 21.2 21.2 0 5.91-2.48 11.58-6.81 15.58L219.7 176H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h134.37l-34.67 32H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h41.86c-13.41 28.63-13.74 63.33 4.13 94.05C80.66 462.15 116.9 480 154.04 480h78.82c24.32 0 47.86-8.53 66.54-24.09l11.77-9.81c10.18-8.49 11.56-23.62 3.07-33.8l-20.49-24.59c-8.49-10.19-23.62-11.56-33.81-3.07l-11.75 9.8a23.992 23.992 0 0 1-15.36 5.56H149.2c-11.69 0-21.2-9.52-21.2-21.2 0-5.91 2.48-11.58 6.81-15.58L164.3 336H368c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H233.63l34.67-32H368z\"],\n    \"i-cursor\": [256, 512, [], \"f246\", \"M256 52.048V12.065C256 5.496 250.726.148 244.158.066 211.621-.344 166.469.011 128 37.959 90.266.736 46.979-.114 11.913.114 5.318.157 0 5.519 0 12.114v39.645c0 6.687 5.458 12.078 12.145 11.998C38.111 63.447 96 67.243 96 112.182V224H60c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h36v112c0 44.932-56.075 48.031-83.95 47.959C5.404 447.942 0 453.306 0 459.952v39.983c0 6.569 5.274 11.917 11.842 11.999 32.537.409 77.689.054 116.158-37.894 37.734 37.223 81.021 38.073 116.087 37.845 6.595-.043 11.913-5.405 11.913-12V460.24c0-6.687-5.458-12.078-12.145-11.998C217.889 448.553 160 444.939 160 400V288h36c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-36V112.182c0-44.932 56.075-48.213 83.95-48.142 6.646.018 12.05-5.346 12.05-11.992z\"],\n    \"ice-cream\": [448, 512, [], \"f810\", \"M368 160h-.94a144 144 0 1 0-286.12 0H80a48 48 0 0 0 0 96h288a48 48 0 0 0 0-96zM195.38 493.69a31.52 31.52 0 0 0 57.24 0L352 288H96z\"],\n    \"icicles\": [512, 512, [], \"f7ad\", \"M511.4 37.9C515.1 18.2 500 0 480 0H32C10.6 0-4.8 20.7 1.4 41.2l87.1 273.4c2.5 7.2 12.7 7.2 15.1 0L140 190.5l44.2 187.3c1.9 8.3 13.7 8.3 15.6 0l46.5-196.9 34.1 133.4c2.3 7.6 13 7.6 15.3 0l45.8-172.5 66.7 363.8c1.7 8.6 14 8.6 15.7 0l87.5-467.7z\"],\n    \"icons\": [512, 512, [], \"f86d\", \"M116.65 219.35a15.68 15.68 0 0 0 22.65 0l96.75-99.83c28.15-29 26.5-77.1-4.91-103.88C203.75-7.7 163-3.5 137.86 22.44L128 32.58l-9.85-10.14C93.05-3.5 52.25-7.7 24.86 15.64c-31.41 26.78-33 74.85-5 103.88zm143.92 100.49h-48l-7.08-14.24a27.39 27.39 0 0 0-25.66-17.78h-71.71a27.39 27.39 0 0 0-25.66 17.78l-7 14.24h-48A27.45 27.45 0 0 0 0 347.3v137.25A27.44 27.44 0 0 0 27.43 512h233.14A27.45 27.45 0 0 0 288 484.55V347.3a27.45 27.45 0 0 0-27.43-27.46zM144 468a52 52 0 1 1 52-52 52 52 0 0 1-52 52zm355.4-115.9h-60.58l22.36-50.75c2.1-6.65-3.93-13.21-12.18-13.21h-75.59c-6.3 0-11.66 3.9-12.5 9.1l-16.8 106.93c-1 6.3 4.88 11.89 12.5 11.89h62.31l-24.2 83c-1.89 6.65 4.2 12.9 12.23 12.9a13.26 13.26 0 0 0 10.92-5.25l92.4-138.91c4.88-6.91-1.16-15.7-10.87-15.7zM478.08.33L329.51 23.17C314.87 25.42 304 38.92 304 54.83V161.6a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V99.66l112-17.22v47.18a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V32c0-19.48-16-34.42-33.92-31.67z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM144 32h96c8.8 0 16 7.2 16 16s-7.2 16-16 16h-96c-8.8 0-16-7.2-16-16s7.2-16 16-16zm48 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 416 80 407.4 80 396.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v16h576V80c0-26.5-21.5-48-48-48zM0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V128H0v304zm352-232c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zM176 192c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zM67.1 396.2C75.5 370.5 99.6 352 128 352h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.9-5.2 19.8-15.6 19.8H82.7c-10.4 0-18.8-10-15.6-19.8z\"],\n    \"id-card-alt\": [576, 512, [], \"f47f\", \"M528 64H384v96H192V64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM288 224c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm93.3 224H194.7c-10.4 0-18.8-10-15.6-19.8 8.3-25.6 32.4-44.2 60.9-44.2h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.8-5.2 19.8-15.6 19.8zM352 32c0-17.7-14.3-32-32-32h-64c-17.7 0-32 14.3-32 32v96h128V32z\"],\n    \"igloo\": [576, 512, [], \"f7ae\", \"M320 33.9c-10.5-1.2-21.2-1.9-32-1.9-99.8 0-187.8 50.8-239.4 128H320V33.9zM96 192H30.3C11.1 230.6 0 274 0 320h96V192zM352 39.4V160h175.4C487.2 99.9 424.8 55.9 352 39.4zM480 320h96c0-46-11.1-89.4-30.3-128H480v128zm-64 64v96h128c17.7 0 32-14.3 32-32v-96H411.5c2.6 10.3 4.5 20.9 4.5 32zm32-192H128v128h49.8c22.2-38.1 63-64 110.2-64s88 25.9 110.2 64H448V192zM0 448c0 17.7 14.3 32 32 32h128v-96c0-11.1 1.9-21.7 4.5-32H0v96zm288-160c-53 0-96 43-96 96v96h192v-96c0-53-43-96-96-96z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM112 120c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56zM64 384h384V272l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L208 320l-55.515-55.515c-4.686-4.686-12.284-4.686-16.971 0L64 336v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v208c0 44.112 35.888 80 80 80h336zm96-80V80c0-26.51-21.49-48-48-48H144c-26.51 0-48 21.49-48 48v256c0 26.51 21.49 48 48 48h384c26.51 0 48-21.49 48-48zM256 128c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-96 144l55.515-55.515c4.686-4.686 12.284-4.686 16.971 0L272 256l135.515-135.515c4.686-4.686 12.284-4.686 16.971 0L512 208v112H160v-48z\"],\n    \"inbox\": [576, 512, [], \"f01c\", \"M567.938 243.908L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L8.062 243.908A47.994 47.994 0 0 0 0 270.533V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V270.533a47.994 47.994 0 0 0-8.062-26.625zM162.252 128h251.497l85.333 128H376l-32 64H232l-32-64H76.918l85.334-128z\"],\n    \"indent\": [448, 512, [], \"f03c\", \"M27.31 363.3l96-96a16 16 0 0 0 0-22.62l-96-96C17.27 138.66 0 145.78 0 160v192c0 14.31 17.33 21.3 27.31 11.3zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"industry\": [512, 512, [], \"f275\", \"M475.115 163.781L336 252.309v-68.28c0-18.916-20.931-30.399-36.885-20.248L160 252.309V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h464c13.255 0 24-10.745 24-24V184.029c0-18.917-20.931-30.399-36.885-20.248z\"],\n    \"infinity\": [640, 512, [], \"f534\", \"M471.1 96C405 96 353.3 137.3 320 174.6 286.7 137.3 235 96 168.9 96 75.8 96 0 167.8 0 256s75.8 160 168.9 160c66.1 0 117.8-41.3 151.1-78.6 33.3 37.3 85 78.6 151.1 78.6 93.1 0 168.9-71.8 168.9-160S564.2 96 471.1 96zM168.9 320c-40.2 0-72.9-28.7-72.9-64s32.7-64 72.9-64c38.2 0 73.4 36.1 94 64-20.4 27.6-55.9 64-94 64zm302.2 0c-38.2 0-73.4-36.1-94-64 20.4-27.6 55.9-64 94-64 40.2 0 72.9 28.7 72.9 64s-32.7 64-72.9 64z\"],\n    \"info\": [192, 512, [], \"f129\", \"M20 424.229h20V279.771H20c-11.046 0-20-8.954-20-20V212c0-11.046 8.954-20 20-20h112c11.046 0 20 8.954 20 20v212.229h20c11.046 0 20 8.954 20 20V492c0 11.046-8.954 20-20 20H20c-11.046 0-20-8.954-20-20v-47.771c0-11.046 8.954-20 20-20zM96 0C56.235 0 24 32.235 24 72s32.235 72 72 72 72-32.235 72-72S135.764 0 96 0z\"],\n    \"info-circle\": [512, 512, [], \"f05a\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 110c23.196 0 42 18.804 42 42s-18.804 42-42 42-42-18.804-42-42 18.804-42 42-42zm56 254c0 6.627-5.373 12-12 12h-88c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h12v-64h-12c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h64c6.627 0 12 5.373 12 12v100h12c6.627 0 12 5.373 12 12v24z\"],\n    \"italic\": [320, 512, [], \"f033\", \"M320 48v32a16 16 0 0 1-16 16h-62.76l-80 320H208a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h62.76l80-320H112a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h192a16 16 0 0 1 16 16z\"],\n    \"jedi\": [544, 512, [], \"f669\", \"M479.99 352l58.88-58.87c3.29-16.8 5.13-34.12 5.13-51.86 0-5.81-.68-11.51-1.05-17.27H496l41.25-41.24c-14.5-64.79-52.43-123.05-107.91-162.27-2.77-1.96-5.97-2.99-9.25-2.99-5.37 0-10.41 2.71-13.49 7.24-3.05 4.49-3.64 9.99-1.61 15.09 6.55 16.46 9.86 33.73 9.86 51.31 0 45.12-21.03 86.57-57.69 113.73-4.02 2.98-6.46 7.5-6.7 12.4-.24 4.92 1.76 9.66 5.49 13.03 32.93 29.75 47.35 73.51 38.57 117.07-9.74 48.35-48.84 87.1-97.31 96.5l-2.5-65.34L321.88 397c2.98 2.06 7.39 1.69 10.02-.8a8.002 8.002 0 0 0 1.34-9.92l-20.11-33.73 42.07-8.72c3.7-.75 6.38-4.05 6.38-7.83 0-3.77-2.69-7.06-6.38-7.83l-42.07-8.73 20.13-33.77c1.92-3.23 1.34-7.31-1.38-9.91-2.7-2.55-6.97-2.89-10-.8l-30.39 20.67L279.96 7.7a7.964 7.964 0 0 0-8-7.7c-4.33 0-7.84 3.38-8 7.67l-11.52 287.97-30.39-20.66c-3.14-2.12-7.27-1.83-10 .78-2.72 2.59-3.3 6.67-1.36 9.94l20.11 33.73-42.07 8.73c-3.7.75-6.38 4.05-6.38 7.83s2.67 7.08 6.38 7.83l42.07 8.72-20.13 33.77c-1.92 3.23-1.34 7.33 1.39 9.94 2.59 2.45 7.03 2.75 10 .75l27.16-18.48-2.5 65.26c-56.94-11.64-99.89-61.89-99.89-121.92 0-35.08 14.62-67.6 41.17-91.58 3.72-3.36 5.72-8.11 5.48-13.01-.24-4.9-2.68-9.41-6.69-12.38-36.67-27.16-57.71-68.62-57.71-113.74 0-17.56 3.31-34.81 9.84-51.26 2.02-5.09 1.43-10.59-1.62-15.09-3.08-4.54-8.13-7.25-13.51-7.25-3.3 0-6.5 1.04-9.27 3-55.87 39.52-93.6 97.37-107.97 162.07L47.93 224H.72c-.63 9.92-.97 19.91-.5 29.99.62 13.43 2.54 26.53 5.11 39.41l58.6 58.6H24.02c41.25 90.23 131.13 154.94 235.1 159.71 4.3.2 8.59.29 12.85.29 110.34 0 205.35-65.83 247.98-160h-39.96z\"],\n    \"joint\": [640, 512, [], \"f595\", \"M444.34 181.1c22.38 15.68 35.66 41.16 35.66 68.59V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-43.24-21.01-83.41-56.34-108.06C463.85 125.02 448 99.34 448 70.31V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v66.4c0 43.69 24.56 81.63 60.34 106.7zM194.97 358.98C126.03 370.07 59.69 394.69 0 432c83.65 52.28 180.3 80 278.94 80h88.57L254.79 380.49c-14.74-17.2-37.45-25.11-59.82-21.51zM553.28 87.09c-5.67-3.8-9.28-9.96-9.28-16.78V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v62.31c0 22.02 10.17 43.41 28.64 55.39C550.79 153.04 576 199.54 576 249.69V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-65.44-32.41-126.19-86.72-162.6zM360.89 352.05c-34.4.06-86.81.15-88.21.17l117.8 137.43A63.987 63.987 0 0 0 439.07 512h88.45L409.57 374.4a63.955 63.955 0 0 0-48.68-22.35zM616 352H432l117.99 137.65A63.987 63.987 0 0 0 598.58 512H616c13.25 0 24-10.75 24-24V376c0-13.26-10.75-24-24-24z\"],\n    \"journal-whills\": [448, 512, [], \"f66a\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM133.08 144.39l21.26 21.26c1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34c3.12-3.12 3.12-8.19 0-11.31l-26.42-26.42c10-20.9 26.24-37.97 46.37-49.26C179.62 88.4 176 99.74 176 112c0 19.96 9.33 37.57 23.66 49.31C190.01 171.37 184 184.96 184 200c0 26.94 19.04 49.4 44.38 54.76l1.36-32.71-10.37 7.04c-.69.45-1.47.69-2.25.69-1 0-1.98-.38-2.75-1.09a4.006 4.006 0 0 1-.69-4.95l8.54-14.31-17.91-3.72c-1.86-.39-3.19-2.03-3.19-3.92s1.33-3.53 3.19-3.92l17.91-3.72-8.54-14.31c-.95-1.61-.67-3.67.69-4.95 1.36-1.3 3.44-1.44 5-.41l12.01 8.16L236 71.83c.09-2.14 1.86-3.83 4-3.83s3.91 1.69 4 3.83l4.68 112.29 14.2-9.65a4.067 4.067 0 0 1 5 .41 4.006 4.006 0 0 1 .69 4.95l-8.54 14.31 17.91 3.72c1.86.39 3.19 2.03 3.19 3.92s-1.33 3.53-3.19 3.92l-17.91 3.72 8.54 14.31c.95 1.61.67 3.67-.69 4.95-.77.72-1.77 1.09-2.75 1.09-.78 0-1.56-.23-2.25-.69l-12.68-8.62 1.43 34.28C276.96 249.4 296 226.94 296 200c0-15.04-6.01-28.63-15.66-38.69C294.67 149.57 304 131.96 304 112c0-12.26-3.62-23.6-9.6-33.33 20.13 11.28 36.37 28.36 46.37 49.26l-26.42 26.42c-3.12 3.12-3.12 8.19 0 11.31 1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34l21.26-21.26c2.97 10.08 5.07 20.55 5.07 31.6 0 .52-.14.99-.15 1.51l-37.11 32.47a7.975 7.975 0 0 0-.75 11.28 7.97 7.97 0 0 0 6.02 2.73c1.88 0 3.75-.66 5.27-1.98l23.59-20.64C337.32 250.96 293.09 288 240 288s-97.32-37.04-108.86-86.62l23.59 20.64A7.957 7.957 0 0 0 160 224c2.22 0 4.44-.92 6.02-2.73 2.92-3.33 2.58-8.38-.75-11.28l-37.11-32.47c-.01-.52-.15-.99-.15-1.51-.01-11.06 2.09-21.53 5.07-31.62zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"kaaba\": [576, 512, [], \"f66b\", \"M554.12 83.51L318.36 4.93a95.962 95.962 0 0 0-60.71 0L21.88 83.51A32.006 32.006 0 0 0 0 113.87v49.01l265.02-79.51c15.03-4.5 30.92-4.5 45.98 0l265 79.51v-49.01c0-13.77-8.81-26-21.88-30.36zm-279.9 30.52L0 196.3v228.38c0 15 10.42 27.98 25.06 31.24l242.12 53.8a95.937 95.937 0 0 0 41.65 0l242.12-53.8c14.64-3.25 25.06-16.24 25.06-31.24V196.29l-274.2-82.26c-9.04-2.72-18.59-2.72-27.59 0zM128 230.11c0 3.61-2.41 6.77-5.89 7.72l-80 21.82C37.02 261.03 32 257.2 32 251.93v-16.58c0-3.61 2.41-6.77 5.89-7.72l80-21.82c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm144-39.28c0 3.61-2.41 6.77-5.89 7.72l-96 26.18c-5.09 1.39-10.11-2.44-10.11-7.72v-16.58c0-3.61 2.41-6.77 5.89-7.72l96-26.18c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm176 22.7c0-5.28 5.02-9.11 10.11-7.72l80 21.82c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-80-21.82a7.997 7.997 0 0 1-5.89-7.72v-16.58zm-144-39.27c0-5.28 5.02-9.11 10.11-7.72l96 26.18c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-96-26.18a7.997 7.997 0 0 1-5.89-7.72v-16.58z\"],\n    \"key\": [512, 512, [], \"f084\", \"M512 176.001C512 273.203 433.202 352 336 352c-11.22 0-22.19-1.062-32.827-3.069l-24.012 27.014A23.999 23.999 0 0 1 261.223 384H224v40c0 13.255-10.745 24-24 24h-40v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-78.059c0-6.365 2.529-12.47 7.029-16.971l161.802-161.802C163.108 213.814 160 195.271 160 176 160 78.798 238.797.001 335.999 0 433.488-.001 512 78.511 512 176.001zM336 128c0 26.51 21.49 48 48 48s48-21.49 48-48-21.49-48-48-48-48 21.49-48 48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM128 180v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"khanda\": [512, 512, [], \"f66d\", \"M415.81 66c-6.37-3.5-14.37-2.33-19.36 3.02a15.974 15.974 0 0 0-1.91 19.52c16.49 26.16 25.2 56.39 25.2 87.41-.19 53.25-26.77 102.69-71.27 132.41l-76.63 53.35v-20.1l44.05-36.09c3.92-4.2 5-10.09 2.81-15.28L310.85 273c33.84-19.26 56.94-55.25 56.94-96.99 0-40.79-22.02-76.13-54.59-95.71l5.22-11.44c2.34-5.53.93-11.83-3.57-16.04L255.86 0l-58.99 52.81c-4.5 4.21-5.9 10.51-3.57 16.04l5.22 11.44c-32.57 19.58-54.59 54.93-54.59 95.72 0 41.75 23.09 77.73 56.94 96.99l-7.85 17.24c-2.19 5.18-1.1 11.07 2.81 15.28l44.05 36.09v19.9l-76.59-53.33C119.02 278.62 92.44 229.19 92.26 176c0-31.08 8.71-61.31 25.2-87.47 3.87-6.16 2.4-13.77-2.59-19.08-5-5.34-13.68-6.2-20.02-2.7C16.32 109.6-22.3 205.3 13.36 295.99c7.07 17.99 17.89 34.38 30.46 49.06l55.97 65.36c4.87 5.69 13.04 7.24 19.65 3.72l79.35-42.23L228 392.23l-47.08 32.78c-1.67-.37-3.23-1.01-5.01-1.01-13.25 0-23.99 10.74-23.99 24 0 13.25 10.74 24 23.99 24 12.1 0 21.69-9.11 23.33-20.76l40.63-28.28v29.95c-9.39 5.57-15.99 15.38-15.99 27.1 0 17.67 14.32 32 31.98 32s31.98-14.33 31.98-32c0-11.71-6.61-21.52-15.99-27.1v-30.15l40.91 28.48C314.41 462.89 324 472 336.09 472c13.25 0 23.99-10.75 23.99-24 0-13.26-10.74-24-23.99-24-1.78 0-3.34.64-5.01 1.01L284 392.23l29.21-20.34 79.35 42.23c6.61 3.52 14.78 1.97 19.65-3.71l52.51-61.31c18.87-22.02 34-47.5 41.25-75.59 21.62-83.66-16.45-167.27-90.16-207.51zm-95.99 110c0 22.3-11.49 41.92-28.83 53.38l-5.65-12.41c-8.75-24.52-8.75-51.04 0-75.56l7.83-17.18c16.07 11.65 26.65 30.45 26.65 51.77zm-127.93 0c0-21.32 10.58-40.12 26.66-51.76l7.83 17.18c8.75 24.52 8.75 51.03 0 75.56l-5.65 12.41c-17.34-11.46-28.84-31.09-28.84-53.39z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm136 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm24-156c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-39 219.9l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5zM304 396c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm65-168.1l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M501.1 402.5c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zm-177.6-4c-5.6-20.3-2.3-42 9-59.7 29.7-46.3 98.7-45.5 127.8 4.3 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-.3-.7-23.9-84.6-23.9-84.6zM168 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm120 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-5.7-12.3 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.8-3.7-4.6-16.6 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C274.6 368.7 288 383 288 396zm16-179c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S400 181 404 206.2c1.7 11.1-11.3 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 217z\"],\n    \"kiwi-bird\": [576, 512, [], \"f535\", \"M575.81 217.98C572.64 157.41 518.28 112 457.63 112h-9.37c-52.82 0-104.25-16.25-147.74-46.24-41.99-28.96-96.04-41.62-153.21-28.7C129.3 41.12-.08 78.24 0 224c.04 70.95 38.68 132.8 95.99 166.01V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-54.26c15.36 3.96 31.4 6.26 48 6.26 5.44 0 10.68-.73 16-1.18V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-59.43c14.24-5.06 27.88-11.39 40.34-19.51C342.07 355.25 393.86 336 448.46 336c25.48 0 16.01-.31 23.05-.78l74.41 136.44c2.86 5.23 8.3 8.34 14.05 8.34 1.31 0 2.64-.16 3.95-.5 7.09-1.8 12.05-8.19 12.05-15.5 0 0 .14-240.24-.16-246.02zM463.97 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm80 153.25l-39.86-73.08c15.12-5.83 28.73-14.6 39.86-25.98v99.06z\"],\n    \"landmark\": [512, 512, [], \"f66f\", \"M501.62 92.11L267.24 2.04a31.958 31.958 0 0 0-22.47 0L10.38 92.11A16.001 16.001 0 0 0 0 107.09V144c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-36.91c0-6.67-4.14-12.64-10.38-14.98zM64 192v160H48c-8.84 0-16 7.16-16 16v48h448v-48c0-8.84-7.16-16-16-16h-16V192h-64v160h-96V192h-64v160h-96V192H64zm432 256H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"language\": [640, 512, [], \"f1ab\", \"M152.1 236.2c-3.5-12.1-7.8-33.2-7.8-33.2h-.5s-4.3 21.1-7.8 33.2l-11.1 37.5H163zM616 96H336v320h280c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm-24 120c0 6.6-5.4 12-12 12h-11.4c-6.9 23.6-21.7 47.4-42.7 69.9 8.4 6.4 17.1 12.5 26.1 18 5.5 3.4 7.3 10.5 4.1 16.2l-7.9 13.9c-3.4 5.9-10.9 7.8-16.7 4.3-12.6-7.8-24.5-16.1-35.4-24.9-10.9 8.7-22.7 17.1-35.4 24.9-5.8 3.5-13.3 1.6-16.7-4.3l-7.9-13.9c-3.2-5.6-1.4-12.8 4.2-16.2 9.3-5.7 18-11.7 26.1-18-7.9-8.4-14.9-17-21-25.7-4-5.7-2.2-13.6 3.7-17.1l6.5-3.9 7.3-4.3c5.4-3.2 12.4-1.7 16 3.4 5 7 10.8 14 17.4 20.9 13.5-14.2 23.8-28.9 30-43.2H412c-6.6 0-12-5.4-12-12v-16c0-6.6 5.4-12 12-12h64v-16c0-6.6 5.4-12 12-12h16c6.6 0 12 5.4 12 12v16h64c6.6 0 12 5.4 12 12zM0 120v272c0 13.3 10.7 24 24 24h280V96H24c-13.3 0-24 10.7-24 24zm58.9 216.1L116.4 167c1.7-4.9 6.2-8.1 11.4-8.1h32.5c5.1 0 9.7 3.3 11.4 8.1l57.5 169.1c2.6 7.8-3.1 15.9-11.4 15.9h-22.9a12 12 0 0 1-11.5-8.6l-9.4-31.9h-60.2l-9.1 31.8c-1.5 5.1-6.2 8.7-11.5 8.7H70.3c-8.2 0-14-8.1-11.4-15.9z\"],\n    \"laptop\": [640, 512, [], \"f109\", \"M624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-code\": [640, 512, [], \"f5fc\", \"M255.03 261.65c6.25 6.25 16.38 6.25 22.63 0l11.31-11.31c6.25-6.25 6.25-16.38 0-22.63L253.25 192l35.71-35.72c6.25-6.25 6.25-16.38 0-22.63l-11.31-11.31c-6.25-6.25-16.38-6.25-22.63 0l-58.34 58.34c-6.25 6.25-6.25 16.38 0 22.63l58.35 58.34zm96.01-11.3l11.31 11.31c6.25 6.25 16.38 6.25 22.63 0l58.34-58.34c6.25-6.25 6.25-16.38 0-22.63l-58.34-58.34c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63L386.75 192l-35.71 35.72c-6.25 6.25-6.25 16.38 0 22.63zM624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-medical\": [640, 512, [], \"f812\", \"M232 224h56v56a8 8 0 0 0 8 8h48a8 8 0 0 0 8-8v-56h56a8 8 0 0 0 8-8v-48a8 8 0 0 0-8-8h-56v-56a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v56h-56a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8zM576 48a48.14 48.14 0 0 0-48-48H112a48.14 48.14 0 0 0-48 48v336h512zm-64 272H128V64h384zm112 96H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33-17.47-32.77-32H16a16 16 0 0 0-16 16v16a64.19 64.19 0 0 0 64 64h512a64.19 64.19 0 0 0 64-64v-16a16 16 0 0 0-16-16z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 152c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm88 272h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18-8.9 71-69.5 126-142.9 126z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm24 199.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.8 4.1-15.1-4.5zm-160 0c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 161.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 180l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm20.1 198.1c4-25.2 34.2-42.1 59.9-42.1s55.9 16.9 59.9 42.1c1.7 11.1-11.4 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 217c-8.4 7.4-21.6.3-19.9-10.9zM168 160c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm230.9 146C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"layer-group\": [512, 512, [], \"f5fd\", \"M12.41 148.02l232.94 105.67c6.8 3.09 14.49 3.09 21.29 0l232.94-105.67c16.55-7.51 16.55-32.52 0-40.03L266.65 2.31a25.607 25.607 0 0 0-21.29 0L12.41 107.98c-16.55 7.51-16.55 32.53 0 40.04zm487.18 88.28l-58.09-26.33-161.64 73.27c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.51 209.97l-58.1 26.33c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 276.3c16.55-7.5 16.55-32.5 0-40zm0 127.8l-57.87-26.23-161.86 73.37c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.29 337.87 12.41 364.1c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 404.1c16.55-7.5 16.55-32.5 0-40z\"],\n    \"leaf\": [576, 512, [], \"f06c\", \"M546.2 9.7c-5.6-12.5-21.6-13-28.3-1.2C486.9 62.4 431.4 96 368 96h-80C182 96 96 182 96 288c0 7 .8 13.7 1.5 20.5C161.3 262.8 253.4 224 384 224c8.8 0 16 7.2 16 16s-7.2 16-16 16C132.6 256 26 410.1 2.4 468c-6.6 16.3 1.2 34.9 17.5 41.6 16.4 6.8 35-1.1 41.8-17.3 1.5-3.6 20.9-47.9 71.9-90.6 32.4 43.9 94 85.8 174.9 77.2C465.5 467.5 576 326.7 576 154.3c0-50.2-10.8-102.2-29.8-144.6z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M489.038 22.963C465.944-.13 434.648-5.93 413.947 6.129c-58.906 34.312-181.25-53.077-321.073 86.746S40.441 355.041 6.129 413.945c-12.059 20.702-6.26 51.999 16.833 75.093 23.095 23.095 54.392 28.891 75.095 16.832 58.901-34.31 181.246 53.079 321.068-86.743S471.56 156.96 505.871 98.056c12.059-20.702 6.261-51.999-16.833-75.093zM243.881 95.522c-58.189 14.547-133.808 90.155-148.358 148.358-1.817 7.27-8.342 12.124-15.511 12.124-1.284 0-2.59-.156-3.893-.481-8.572-2.144-13.784-10.83-11.642-19.403C81.901 166.427 166.316 81.93 236.119 64.478c8.575-2.143 17.261 3.069 19.403 11.642s-3.069 17.259-11.641 19.402z\"],\n    \"less-than\": [384, 512, [], \"f536\", \"M365.46 357.74L147.04 255.89l218.47-101.88c16.02-7.47 22.95-26.51 15.48-42.53l-13.52-29C360 66.46 340.96 59.53 324.94 67L18.48 209.91a32.014 32.014 0 0 0-18.48 29v34.24c0 12.44 7.21 23.75 18.48 29l306.31 142.83c16.06 7.49 35.15.54 42.64-15.52l13.56-29.08c7.49-16.06.54-35.15-15.53-42.64z\"],\n    \"less-than-equal\": [448, 512, [], \"f537\", \"M54.98 214.2l301.41 119.87c18.39 6.03 38.71-2.54 45.38-19.15l12.09-30.08c6.68-16.61-2.82-34.97-21.21-41l-175.44-68.05 175.56-68.09c18.29-6 27.74-24.27 21.1-40.79l-12.03-29.92c-6.64-16.53-26.86-25.06-45.15-19.06L54.98 137.89C41.21 142.41 32 154.5 32 168.07v15.96c0 13.56 9.21 25.65 22.98 30.17zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"level-down-alt\": [320, 512, [], \"f3be\", \"M313.553 392.331L209.587 504.334c-9.485 10.214-25.676 10.229-35.174 0L70.438 392.331C56.232 377.031 67.062 352 88.025 352H152V80H68.024a11.996 11.996 0 0 1-8.485-3.515l-56-56C-4.021 12.926 1.333 0 12.024 0H208c13.255 0 24 10.745 24 24v328h63.966c20.878 0 31.851 24.969 17.587 40.331z\"],\n    \"level-up-alt\": [320, 512, [], \"f3bf\", \"M313.553 119.669L209.587 7.666c-9.485-10.214-25.676-10.229-35.174 0L70.438 119.669C56.232 134.969 67.062 160 88.025 160H152v272H68.024a11.996 11.996 0 0 0-8.485 3.515l-56 56C-4.021 499.074 1.333 512 12.024 512H208c13.255 0 24-10.745 24-24V160h63.966c20.878 0 31.851-24.969 17.587-40.331z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm173.696 119.559l-63.399 63.399c-10.987-18.559-26.67-34.252-45.255-45.255l63.399-63.399a218.396 218.396 0 0 1 45.255 45.255zM256 352c-53.019 0-96-42.981-96-96s42.981-96 96-96 96 42.981 96 96-42.981 96-96 96zM127.559 82.304l63.399 63.399c-18.559 10.987-34.252 26.67-45.255 45.255l-63.399-63.399a218.372 218.372 0 0 1 45.255-45.255zM82.304 384.441l63.399-63.399c10.987 18.559 26.67 34.252 45.255 45.255l-63.399 63.399a218.396 218.396 0 0 1-45.255-45.255zm302.137 45.255l-63.399-63.399c18.559-10.987 34.252-26.67 45.255-45.255l63.399 63.399a218.403 218.403 0 0 1-45.255 45.255z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M96.06 454.35c.01 6.29 1.87 12.45 5.36 17.69l17.09 25.69a31.99 31.99 0 0 0 26.64 14.28h61.71a31.99 31.99 0 0 0 26.64-14.28l17.09-25.69a31.989 31.989 0 0 0 5.36-17.69l.04-38.35H96.01l.05 38.35zM0 176c0 44.37 16.45 84.85 43.56 115.78 16.52 18.85 42.36 58.23 52.21 91.45.04.26.07.52.11.78h160.24c.04-.26.07-.51.11-.78 9.85-33.22 35.69-72.6 52.21-91.45C335.55 260.85 352 220.37 352 176 352 78.61 272.91-.3 175.45 0 73.44.31 0 82.97 0 176zm176-80c-44.11 0-80 35.89-80 80 0 8.84-7.16 16-16 16s-16-7.16-16-16c0-61.76 50.24-112 112-112 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"link\": [512, 512, [], \"f0c1\", \"M326.612 185.391c59.747 59.809 58.927 155.698.36 214.59-.11.12-.24.25-.36.37l-67.2 67.2c-59.27 59.27-155.699 59.262-214.96 0-59.27-59.26-59.27-155.7 0-214.96l37.106-37.106c9.84-9.84 26.786-3.3 27.294 10.606.648 17.722 3.826 35.527 9.69 52.721 1.986 5.822.567 12.262-3.783 16.612l-13.087 13.087c-28.026 28.026-28.905 73.66-1.155 101.96 28.024 28.579 74.086 28.749 102.325.51l67.2-67.19c28.191-28.191 28.073-73.757 0-101.83-3.701-3.694-7.429-6.564-10.341-8.569a16.037 16.037 0 0 1-6.947-12.606c-.396-10.567 3.348-21.456 11.698-29.806l21.054-21.055c5.521-5.521 14.182-6.199 20.584-1.731a152.482 152.482 0 0 1 20.522 17.197zM467.547 44.449c-59.261-59.262-155.69-59.27-214.96 0l-67.2 67.2c-.12.12-.25.25-.36.37-58.566 58.892-59.387 154.781.36 214.59a152.454 152.454 0 0 0 20.521 17.196c6.402 4.468 15.064 3.789 20.584-1.731l21.054-21.055c8.35-8.35 12.094-19.239 11.698-29.806a16.037 16.037 0 0 0-6.947-12.606c-2.912-2.005-6.64-4.875-10.341-8.569-28.073-28.073-28.191-73.639 0-101.83l67.2-67.19c28.239-28.239 74.3-28.069 102.325.51 27.75 28.3 26.872 73.934-1.155 101.96l-13.087 13.087c-4.35 4.35-5.769 10.79-3.783 16.612 5.864 17.194 9.042 34.999 9.69 52.721.509 13.906 17.454 20.446 27.294 10.606l37.106-37.106c59.271-59.259 59.271-155.699.001-214.959z\"],\n    \"lira-sign\": [384, 512, [], \"f195\", \"M371.994 256h-48.019C317.64 256 312 260.912 312 267.246 312 368 230.179 416 144 416V256.781l134.603-29.912A12 12 0 0 0 288 215.155v-40.976c0-7.677-7.109-13.38-14.603-11.714L144 191.219V160.78l134.603-29.912A12 12 0 0 0 288 119.154V78.179c0-7.677-7.109-13.38-14.603-11.714L144 95.219V44c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v68.997L9.397 125.131A12 12 0 0 0 0 136.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 178.558v30.439L9.397 221.131A12 12 0 0 0 0 232.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 274.558V468c0 6.627 5.373 12 12 12h79.583c134.091 0 223.255-77.834 228.408-211.592.261-6.782-5.211-12.408-11.997-12.408z\"],\n    \"list\": [512, 512, [], \"f03a\", \"M80 368H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm0-320H16A16 16 0 0 0 0 64v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16V64a16 16 0 0 0-16-16zm0 160H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm416 176H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM128 120c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm288-136v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12z\"],\n    \"list-ol\": [512, 512, [], \"f0cb\", \"M61.77 401l17.5-20.15a19.92 19.92 0 0 0 5.07-14.19v-3.31C84.34 356 80.5 352 73 352H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h22.83a157.41 157.41 0 0 0-11 12.31l-5.61 7c-4 5.07-5.25 10.13-2.8 14.88l1.05 1.93c3 5.76 6.29 7.88 12.25 7.88h4.73c10.33 0 15.94 2.44 15.94 9.09 0 4.72-4.2 8.22-14.36 8.22a41.54 41.54 0 0 1-15.47-3.12c-6.49-3.88-11.74-3.5-15.6 3.12l-5.59 9.31c-3.72 6.13-3.19 11.72 2.63 15.94 7.71 4.69 20.38 9.44 37 9.44 34.16 0 48.5-22.75 48.5-44.12-.03-14.38-9.12-29.76-28.73-34.88zM496 224H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h64a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H64V40a8 8 0 0 0-8-8H32a8 8 0 0 0-7.14 4.42l-8 16A8 8 0 0 0 24 64h8v64H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8zm-3.91 160H80a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H41.32c3.29-10.29 48.34-18.68 48.34-56.44 0-29.06-25-39.56-44.47-39.56-21.36 0-33.8 10-40.46 18.75-4.37 5.59-3 10.84 2.8 15.37l8.58 6.88c5.61 4.56 11 2.47 16.12-2.44a13.44 13.44 0 0 1 9.46-3.84c3.33 0 9.28 1.56 9.28 8.75C51 248.19 0 257.31 0 304.59v4C0 316 5.08 320 12.09 320z\"],\n    \"list-ul\": [512, 512, [], \"f0ca\", \"M48 48a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm448 16H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"location-arrow\": [512, 512, [], \"f124\", \"M444.52 3.52L28.74 195.42c-47.97 22.39-31.98 92.75 19.19 92.75h175.91v175.91c0 51.17 70.36 67.17 92.75 19.19l191.9-415.78c15.99-38.39-25.59-79.97-63.97-63.97z\"],\n    \"lock\": [448, 512, [], \"f023\", \"M400 224h-24v-72C376 68.2 307.8 0 224 0S72 68.2 72 152v72H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48zm-104 0H152v-72c0-39.7 32.3-72 72-72s72 32.3 72 72v72z\"],\n    \"lock-open\": [576, 512, [], \"f3c1\", \"M423.5 0C339.5.3 272 69.5 272 153.5V224H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48h-48v-71.1c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v80c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-80C576 68 507.5-.3 423.5 0z\"],\n    \"long-arrow-alt-down\": [256, 512, [], \"f309\", \"M168 345.941V44c0-6.627-5.373-12-12-12h-56c-6.627 0-12 5.373-12 12v301.941H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.569 9.373 33.941 0l86.059-86.059c15.119-15.119 4.411-40.971-16.971-40.971H168z\"],\n    \"long-arrow-alt-left\": [448, 512, [], \"f30a\", \"M134.059 296H436c6.627 0 12-5.373 12-12v-56c0-6.627-5.373-12-12-12H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.569 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296z\"],\n    \"long-arrow-alt-right\": [448, 512, [], \"f30b\", \"M313.941 216H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h301.941v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.569 0-33.941l-86.059-86.059c-15.119-15.119-40.971-4.411-40.971 16.971V216z\"],\n    \"long-arrow-alt-up\": [256, 512, [], \"f30c\", \"M88 166.059V468c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12V166.059h46.059c21.382 0 32.09-25.851 16.971-40.971l-86.059-86.059c-9.373-9.373-24.569-9.373-33.941 0l-86.059 86.059c-15.119 15.119-4.411 40.971 16.971 40.971H88z\"],\n    \"low-vision\": [576, 512, [], \"f2a8\", \"M569.344 231.631C512.96 135.949 407.81 72 288 72c-28.468 0-56.102 3.619-82.451 10.409L152.778 10.24c-7.601-10.858-22.564-13.5-33.423-5.9l-13.114 9.178c-10.86 7.601-13.502 22.566-5.9 33.426l43.131 58.395C89.449 131.73 40.228 174.683 6.682 231.581c-.01.017-.023.033-.034.05-8.765 14.875-8.964 33.528 0 48.739 38.5 65.332 99.742 115.862 172.859 141.349L55.316 244.302A272.194 272.194 0 0 1 83.61 208.39l119.4 170.58h.01l40.63 58.04a330.055 330.055 0 0 0 78.94 1.17l-189.98-271.4a277.628 277.628 0 0 1 38.777-21.563l251.836 356.544c7.601 10.858 22.564 13.499 33.423 5.9l13.114-9.178c10.86-7.601 13.502-22.567 5.9-33.426l-43.12-58.377-.007-.009c57.161-27.978 104.835-72.04 136.81-126.301a47.938 47.938 0 0 0 .001-48.739zM390.026 345.94l-19.066-27.23c24.682-32.567 27.711-76.353 8.8-111.68v.03c0 23.65-19.17 42.82-42.82 42.82-23.828 0-42.82-19.349-42.82-42.82 0-23.65 19.17-42.82 42.82-42.82h.03c-24.75-13.249-53.522-15.643-79.51-7.68l-19.068-27.237C253.758 123.306 270.488 120 288 120c75.162 0 136 60.826 136 136 0 34.504-12.833 65.975-33.974 89.94z\"],\n    \"luggage-cart\": [640, 512, [], \"f59d\", \"M224 320h32V96h-32c-17.67 0-32 14.33-32 32v160c0 17.67 14.33 32 32 32zm352-32V128c0-17.67-14.33-32-32-32h-32v224h32c17.67 0 32-14.33 32-32zm48 96H128V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h48v368c0 8.84 7.16 16 16 16h82.94c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16h197.88c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM480 96V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v272h192V96zm-48 0h-96V48h96v48z\"],\n    \"magic\": [512, 512, [], \"f0d0\", \"M224 96l16-32 32-16-32-16-16-32-16 32-32 16 32 16 16 32zM80 160l26.66-53.33L160 80l-53.34-26.67L80 0 53.34 53.33 0 80l53.34 26.67L80 160zm352 128l-26.66 53.33L352 368l53.34 26.67L432 448l26.66-53.33L512 368l-53.34-26.67L432 288zm70.62-193.77L417.77 9.38C411.53 3.12 403.34 0 395.15 0c-8.19 0-16.38 3.12-22.63 9.38L9.38 372.52c-12.5 12.5-12.5 32.76 0 45.25l84.85 84.85c6.25 6.25 14.44 9.37 22.62 9.37 8.19 0 16.38-3.12 22.63-9.37l363.14-363.15c12.5-12.48 12.5-32.75 0-45.24zM359.45 203.46l-50.91-50.91 86.6-86.6 50.91 50.91-86.6 86.6z\"],\n    \"magnet\": [512, 512, [], \"f076\", \"M164.07 148.1H12a12 12 0 0 1-12-12v-80a36 36 0 0 1 36-36h104a36 36 0 0 1 36 36v80a11.89 11.89 0 0 1-11.93 12zm347.93-12V56a36 36 0 0 0-36-36H372a36 36 0 0 0-36 36v80a12 12 0 0 0 12 12h152a11.89 11.89 0 0 0 12-11.9zm-164 44a12 12 0 0 0-12 12v52c0 128.1-160 127.9-160 0v-52a12 12 0 0 0-12-12H12.1a12 12 0 0 0-12 12.1c.1 21.4.6 40.3 0 53.3 0 150.6 136.17 246.6 256.75 246.6s255-96 255-246.7c-.6-12.8-.2-33 0-53.2a12 12 0 0 0-12-12.1z\"],\n    \"mail-bulk\": [576, 512, [], \"f674\", \"M160 448c-25.6 0-51.2-22.4-64-32-64-44.8-83.2-60.8-96-70.4V480c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V345.6c-12.8 9.6-32 25.6-96 70.4-12.8 9.6-38.4 32-64 32zm128-192H32c-17.67 0-32 14.33-32 32v16c25.6 19.2 22.4 19.2 115.2 86.4 9.6 6.4 28.8 25.6 44.8 25.6s35.2-19.2 44.8-22.4c92.8-67.2 89.6-67.2 115.2-86.4V288c0-17.67-14.33-32-32-32zm256-96H224c-17.67 0-32 14.33-32 32v32h96c33.21 0 60.59 25.42 63.71 57.82l.29-.22V416h192c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zm-32 128h-64v-64h64v64zm-352-96c0-35.29 28.71-64 64-64h224V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v192h96v-32z\"],\n    \"male\": [192, 512, [], \"f183\", \"M96 0c35.346 0 64 28.654 64 64s-28.654 64-64 64-64-28.654-64-64S60.654 0 96 0m48 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H48c-26.51 0-48 21.49-48 48v136c0 13.255 10.745 24 24 24h16v136c0 13.255 10.745 24 24 24h64c13.255 0 24-10.745 24-24V352h16c13.255 0 24-10.745 24-24V192c0-26.51-21.49-48-48-48z\"],\n    \"map\": [576, 512, [], \"f279\", \"M0 117.66v346.32c0 11.32 11.43 19.06 21.94 14.86L160 416V32L20.12 87.95A32.006 32.006 0 0 0 0 117.66zM192 416l192 64V96L192 32v384zM554.06 33.16L416 96v384l139.88-55.95A31.996 31.996 0 0 0 576 394.34V48.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked\": [576, 512, [], \"f59f\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked-alt\": [576, 512, [], \"f5a0\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zm0 168c-23.2 0-42-18.8-42-42s18.8-42 42-42 42 18.8 42 42-18.8 42-42 42zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marker\": [384, 512, [], \"f041\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0z\"],\n    \"map-marker-alt\": [384, 512, [], \"f3c5\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0zM192 272c44.183 0 80-35.817 80-80s-35.817-80-80-80-80 35.817-80 80 35.817 80 80 80z\"],\n    \"map-pin\": [288, 512, [], \"f276\", \"M112 316.94v156.69l22.02 33.02c4.75 7.12 15.22 7.12 19.97 0L176 473.63V316.94c-10.39 1.92-21.06 3.06-32 3.06s-21.61-1.14-32-3.06zM144 0C64.47 0 0 64.47 0 144s64.47 144 144 144 144-64.47 144-144S223.53 0 144 0zm0 76c-37.5 0-68 30.5-68 68 0 6.62-5.38 12-12 12s-12-5.38-12-12c0-50.73 41.28-92 92-92 6.62 0 12 5.38 12 12s-5.38 12-12 12z\"],\n    \"map-signs\": [512, 512, [], \"f277\", \"M507.31 84.69L464 41.37c-6-6-14.14-9.37-22.63-9.37H288V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v16H56c-13.25 0-24 10.75-24 24v80c0 13.25 10.75 24 24 24h385.37c8.49 0 16.62-3.37 22.63-9.37l43.31-43.31c6.25-6.26 6.25-16.38 0-22.63zM224 496c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V384h-64v112zm232-272H288v-32h-64v32H70.63c-8.49 0-16.62 3.37-22.63 9.37L4.69 276.69c-6.25 6.25-6.25 16.38 0 22.63L48 342.63c6 6 14.14 9.37 22.63 9.37H456c13.25 0 24-10.75 24-24v-80c0-13.25-10.75-24-24-24z\"],\n    \"marker\": [512, 512, [], \"f5a1\", \"M93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l75.4-75.4-128.02-128.02-75.4 75.4zM485.49 26.51c-35.35-35.35-92.67-35.35-128.02 0l-21.76 21.76-36.56-36.55c-15.62-15.62-40.95-15.62-56.56 0L138.47 115.84c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0l87.15-87.15 19.59 19.59L191.98 192 320 320.02l165.49-165.49c35.35-35.35 35.35-92.66 0-128.02z\"],\n    \"mars\": [384, 512, [], \"f222\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c0-6.6-5.4-12-12-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-double\": [512, 512, [], \"f227\", \"M340 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C198.5 72.1 172.2 64 144 64 64.5 64 0 128.5 0 208s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.5 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 288c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80zm356-128.1h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7c-18.2-11.4-39-18.9-61.5-21.3-2.1 21.8-8.2 43.3-18.4 63.3 1.1 0 2.2-.1 3.2-.1 44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80c0-1.1 0-2.2.1-3.2-20 10.2-41.5 16.4-63.3 18.4C168.4 455.6 229.6 512 304 512c79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12v-79c0-6.7-5.4-12.1-12-12.1z\"],\n    \"mars-stroke\": [384, 512, [], \"f229\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-17.5 17.5-14.1-14.1c-4.7-4.7-12.3-4.7-17 0L224.5 133c-4.7 4.7-4.7 12.3 0 17l14.1 14.1-18 18c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l18-18 14.1 14.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L329.2 164l17.5-17.5 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c-.1-6.6-5.5-12-12.1-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-stroke-h\": [480, 512, [], \"f22b\", \"M476.2 247.5l-55.9-55.9c-7.6-7.6-20.5-2.2-20.5 8.5V224H376v-20c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v20h-27.6c-5.8-25.6-18.7-49.9-38.6-69.8C189.6 98 98.4 98 42.2 154.2c-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 19.9-19.9 32.8-44.2 38.6-69.8H312v20c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-20h23.9v23.9c0 10.7 12.9 16 20.5 8.5l55.9-55.9c4.6-4.7 4.6-12.3-.1-17zm-275.6 65.1c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mars-stroke-v\": [288, 512, [], \"f22a\", \"M245.8 234.2c-19.9-19.9-44.2-32.8-69.8-38.6v-25.4h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V81.4h23.9c10.7 0 16-12.9 8.5-20.5L152.5 5.1c-4.7-4.7-12.3-4.7-17 0L79.6 61c-7.6 7.6-2.2 20.5 8.5 20.5H112v24.7H92c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h20v25.4c-25.6 5.8-49.9 18.7-69.8 38.6-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 56.3-56.2 56.3-147.4 0-203.6zm-45.2 158.4c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mask\": [640, 512, [], \"f6fa\", \"M320.67 64c-442.6 0-357.57 384-158.46 384 39.9 0 77.47-20.69 101.42-55.86l25.73-37.79c15.66-22.99 46.97-22.99 62.63 0l25.73 37.79C401.66 427.31 439.23 448 479.13 448c189.86 0 290.63-384-158.46-384zM184 308.36c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05zm272 0c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05z\"],\n    \"medal\": [512, 512, [], \"f5a2\", \"M223.75 130.75L154.62 15.54A31.997 31.997 0 0 0 127.18 0H16.03C3.08 0-4.5 14.57 2.92 25.18l111.27 158.96c29.72-27.77 67.52-46.83 109.56-53.39zM495.97 0H384.82c-11.24 0-21.66 5.9-27.44 15.54l-69.13 115.21c42.04 6.56 79.84 25.62 109.56 53.38L509.08 25.18C516.5 14.57 508.92 0 495.97 0zM256 160c-97.2 0-176 78.8-176 176s78.8 176 176 176 176-78.8 176-176-78.8-176-176-176zm92.52 157.26l-37.93 36.96 8.97 52.22c1.6 9.36-8.26 16.51-16.65 12.09L256 393.88l-46.9 24.65c-8.4 4.45-18.25-2.74-16.65-12.09l8.97-52.22-37.93-36.96c-6.82-6.64-3.05-18.23 6.35-19.59l52.43-7.64 23.43-47.52c2.11-4.28 6.19-6.39 10.28-6.39 4.11 0 8.22 2.14 10.33 6.39l23.43 47.52 52.43 7.64c9.4 1.36 13.17 12.95 6.35 19.59z\"],\n    \"medkit\": [512, 512, [], \"f0fa\", \"M96 480h320V128h-32V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v48H96v352zm96-384h128v32H192V96zm320 80v256c0 26.51-21.49 48-48 48h-16V128h16c26.51 0 48 21.49 48 48zM64 480H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v352zm288-208v32c0 8.837-7.163 16-16 16h-48v48c0 8.837-7.163 16-16 16h-32c-8.837 0-16-7.163-16-16v-48h-48c-8.837 0-16-7.163-16-16v-32c0-8.837 7.163-16 16-16h48v-48c0-8.837 7.163-16 16-16h32c8.837 0 16 7.163 16 16v48h48c8.837 0 16 7.163 16 16z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm176 192H152c-21.2 0-21.2-32 0-32h192c21.2 0 21.2 32 0 32zm-16-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 224c0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64s-64-28.7-64-64zm224 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-112c-35.3 0-64-28.7-64-64 0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64z\"],\n    \"memory\": [640, 512, [], \"f538\", \"M640 130.94V96c0-17.67-14.33-32-32-32H32C14.33 64 0 78.33 0 96v34.94c18.6 6.61 32 24.19 32 45.06s-13.4 38.45-32 45.06V320h640v-98.94c-18.6-6.61-32-24.19-32-45.06s13.4-38.45 32-45.06zM224 256h-64V128h64v128zm128 0h-64V128h64v128zm128 0h-64V128h64v128zM0 448h64v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h64v-96H0v96z\"],\n    \"menorah\": [640, 512, [], \"f676\", \"M144 128h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm192 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm80-32c17.67 0 32-14.33 32-32S608 0 608 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S512 0 512 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S416 0 416 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S320 0 320 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S224 0 224 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S128 0 128 0 96 46.33 96 64s14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S32 0 32 0 0 46.33 0 64s14.33 32 32 32zm544 192c0 17.67-14.33 32-32 32H352V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v176H96c-17.67 0-32-14.33-32-32V144c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v144c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v144z\"],\n    \"mercury\": [288, 512, [], \"f223\", \"M288 208c0-44.2-19.9-83.7-51.2-110.1 2.5-1.8 4.9-3.8 7.2-5.8 24.7-21.2 39.8-48.8 43.2-78.8.9-7.1-4.7-13.3-11.9-13.3h-40.5C229 0 224.1 4.1 223 9.8c-2.4 12.5-9.6 24.3-20.7 33.8C187 56.8 166.3 64 144 64s-43-7.2-58.4-20.4C74.5 34.1 67.4 22.3 64.9 9.8 63.8 4.1 58.9 0 53.2 0H12.7C5.5 0-.1 6.2.8 13.3 4.2 43.4 19.2 71 44 92.2c2.3 2 4.7 3.9 7.2 5.8C19.9 124.3 0 163.8 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"meteor\": [512, 512, [], \"f753\", \"M491.2.7C452.5 12.3 379.4 35 303.5 62c-2.1-7-4-13.5-5.6-18.6-3-9.7-13.9-14.2-22.9-9.5C232.6 56 122.2 116.5 60.6 176.4c-1.1 1-2.5 2-3.5 3C19 217.4 0 267.3 0 317.2 0 367 19 416.9 57 455c38 38 87.9 57.1 137.8 57 49.9 0 99.8-19 137.9-57.1 1-1 2-2.4 3-3.5 59.8-61.6 120.4-172.1 142.5-214.4 4.7-9 .2-19.9-9.5-22.9-5.2-1.6-11.6-3.5-18.6-5.6 27-76 49.7-149 61.3-187.7C515 8.4 503.6-3 491.2.7zM192 448c-70.7 0-128-57.3-128-128s57.3-128 128-128 128 57.3 128 128-57.3 128-128 128zm-32-192c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm48 96c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16z\"],\n    \"microchip\": [512, 512, [], \"f2db\", \"M416 48v416c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h224c26.51 0 48 21.49 48 48zm96 58v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42V88h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zM30 376h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6z\"],\n    \"microphone\": [352, 512, [], \"f130\", \"M176 352c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96zm160-160h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16z\"],\n    \"microphone-alt\": [352, 512, [], \"f3c9\", \"M336 192h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16zM176 352c53.02 0 96-42.98 96-96h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96z\"],\n    \"microphone-alt-slash\": [640, 512, [], \"f539\", \"M633.82 458.1L476.26 336.33C488.74 312.21 496 284.98 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67h-43.67l-41.4-32H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.78c11.71-1.62 23.1-4.28 33.96-8.08l-50.4-38.96c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microphone-slash\": [640, 512, [], \"f131\", \"M633.82 458.1l-157.8-121.96C488.61 312.13 496 285.01 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67V96c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.77c11.66-1.6 22.85-4.54 33.67-8.31l-50.11-38.73c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microscope\": [512, 512, [], \"f610\", \"M160 320h12v16c0 8.84 7.16 16 16 16h40c8.84 0 16-7.16 16-16v-16h12c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32V16c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v16c-17.67 0-32 14.33-32 32v224c0 17.67 14.33 32 32 32zm304 128h-1.29C493.24 413.99 512 369.2 512 320c0-105.88-86.12-192-192-192v64c70.58 0 128 57.42 128 128s-57.42 128-128 128H48c-26.51 0-48 21.49-48 48 0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48zm-360-32h208c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8H104c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8z\"],\n    \"minus\": [448, 512, [], \"f068\", \"M416 208H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"minus-circle\": [512, 512, [], \"f056\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zM124 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H124z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM92 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H92z\"],\n    \"mitten\": [448, 512, [], \"f7b5\", \"M368 416H48c-8.8 0-16 7.2-16 16v64c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16zm57-209.1c-27.2-22.6-67.5-19-90.1 8.2l-20.9 25-29.6-128.4c-18-77.5-95.4-125.9-172.8-108C34.2 21.6-14.2 98.9 3.7 176.4L51.6 384h309l72.5-87c22.7-27.2 19-67.5-8.1-90.1z\"],\n    \"mobile\": [320, 512, [], \"f10b\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"mobile-alt\": [320, 512, [], \"f3cd\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm112-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v312z\"],\n    \"money-bill\": [640, 512, [], \"f0d6\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 176c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 48h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M352 288h-16v-88c0-4.42-3.58-8-8-8h-13.58c-4.74 0-9.37 1.4-13.31 4.03l-15.33 10.22a7.994 7.994 0 0 0-2.22 11.09l8.88 13.31a7.994 7.994 0 0 0 11.09 2.22l.47-.31V288h-16c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8h64c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 192c-53.02 0-96-50.15-96-112 0-61.86 42.98-112 96-112s96 50.14 96 112c0 61.87-43 112-96 112zm272 32h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-wave\": [640, 512, [], \"f53a\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM48 132.22c20.12 5.04 41.12 7.57 62.72 8.93C104.84 170.54 79 192.69 48 192.69v-60.47zm0 285v-47.78c34.37 0 62.18 27.27 63.71 61.4-22.53-1.81-43.59-6.31-63.71-13.62zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 27.78c-17.52-4.39-35.71-6.85-54.32-8.44 5.87-26.08 27.5-45.88 54.32-49.28v57.72zm0-236.11c-30.89-3.91-54.86-29.7-55.81-61.55 19.54 2.17 38.09 6.23 55.81 12.66v48.89z\"],\n    \"money-bill-wave-alt\": [640, 512, [], \"f53b\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96z\"],\n    \"money-check\": [640, 512, [], \"f53c\", \"M0 448c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128H0v320zm448-208c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-32zm0 120c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H456c-4.42 0-8-3.58-8-8v-16zM64 264c0-4.42 3.58-8 8-8h304c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm0 96c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zM624 32H16C7.16 32 0 39.16 0 48v48h640V48c0-8.84-7.16-16-16-16z\"],\n    \"money-check-alt\": [640, 512, [], \"f53d\", \"M608 32H32C14.33 32 0 46.33 0 64v384c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM176 327.88V344c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V152c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07zM416 312c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm160 0c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h272c4.42 0 8 3.58 8 8v16z\"],\n    \"monument\": [384, 512, [], \"f5a6\", \"M368 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h352c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-78.86-347.26a31.97 31.97 0 0 0-9.21-19.44L203.31 4.69c-6.25-6.25-16.38-6.25-22.63 0l-76.6 76.61a31.97 31.97 0 0 0-9.21 19.44L64 416h256l-30.86-315.26zM240 307.2c0 6.4-6.4 12.8-12.8 12.8h-70.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h70.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M283.211 512c78.962 0 151.079-35.925 198.857-94.792 7.068-8.708-.639-21.43-11.562-19.35-124.203 23.654-238.262-71.576-238.262-196.954 0-72.222 38.662-138.635 101.498-174.394 9.686-5.512 7.25-20.197-3.756-22.23A258.156 258.156 0 0 0 283.211 0c-141.309 0-256 114.511-256 256 0 141.309 114.511 256 256 256z\"],\n    \"mortar-pestle\": [512, 512, [], \"f5a7\", \"M501.54 60.91c17.22-17.22 12.51-46.25-9.27-57.14a35.696 35.696 0 0 0-37.37 3.37L251.09 160h151.37l99.08-99.09zM496 192H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c0 80.98 50.2 150.11 121.13 178.32-12.76 16.87-21.72 36.8-24.95 58.69-1.46 9.92 6.04 18.98 16.07 18.98h223.5c10.03 0 17.53-9.06 16.07-18.98-3.22-21.89-12.18-41.82-24.95-58.69C429.8 406.11 480 336.98 480 256h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"mosque\": [640, 512, [], \"f678\", \"M0 480c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V160H0v320zm579.16-192c17.86-17.39 28.84-37.34 28.84-58.91 0-52.86-41.79-93.79-87.92-122.9-41.94-26.47-80.63-57.77-111.96-96.22L400 0l-8.12 9.97c-31.33 38.45-70.01 69.76-111.96 96.22C233.79 135.3 192 176.23 192 229.09c0 21.57 10.98 41.52 28.84 58.91h358.32zM608 320H192c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h32v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h64v-72c0-48 48-72 48-72s48 24 48 72v72h64v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h32c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM64 0S0 32 0 96v32h128V96c0-64-64-96-64-96z\"],\n    \"motorcycle\": [640, 512, [], \"f21c\", \"M512.9 192c-14.9-.1-29.1 2.3-42.4 6.9L437.6 144H520c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24h-45.3c-6.8 0-13.3 2.9-17.8 7.9l-37.5 41.7-22.8-38C392.2 68.4 384.4 64 376 64h-80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h66.4l19.2 32H227.9c-17.7-23.1-44.9-40-99.9-40H72.5C59 104 47.7 115 48 128.5c.2 13 10.9 23.5 24 23.5h56c24.5 0 38.7 10.9 47.8 24.8l-11.3 20.5c-13-3.9-26.9-5.7-41.3-5.2C55.9 194.5 1.6 249.6 0 317c-1.6 72.1 56.3 131 128 131 59.6 0 109.7-40.8 124-96h84.2c13.7 0 24.6-11.4 24-25.1-2.1-47.1 17.5-93.7 56.2-125l12.5 20.8c-27.6 23.7-45.1 58.9-44.8 98.2.5 69.6 57.2 126.5 126.8 127.1 71.6.7 129.8-57.5 129.2-129.1-.7-69.6-57.6-126.4-127.2-126.9zM128 400c-44.1 0-80-35.9-80-80s35.9-80 80-80c4.2 0 8.4.3 12.5 1L99 316.4c-8.8 16 2.8 35.6 21 35.6h81.3c-12.4 28.2-40.6 48-73.3 48zm463.9-75.6c-2.2 40.6-35 73.4-75.5 75.5-46.1 2.5-84.4-34.3-84.4-79.9 0-21.4 8.4-40.8 22.1-55.1l49.4 82.4c4.5 7.6 14.4 10 22 5.5l13.7-8.2c7.6-4.5 10-14.4 5.5-22l-48.6-80.9c5.2-1.1 10.5-1.6 15.9-1.6 45.6-.1 82.3 38.2 79.9 84.3z\"],\n    \"mountain\": [640, 512, [], \"f6fc\", \"M634.92 462.7l-288-448C341.03 5.54 330.89 0 320 0s-21.03 5.54-26.92 14.7l-288 448a32.001 32.001 0 0 0-1.17 32.64A32.004 32.004 0 0 0 32 512h576c11.71 0 22.48-6.39 28.09-16.67a31.983 31.983 0 0 0-1.17-32.63zM320 91.18L405.39 224H320l-64 64-38.06-38.06L320 91.18z\"],\n    \"mouse-pointer\": [320, 512, [], \"f245\", \"M302.189 329.126H196.105l55.831 135.993c3.889 9.428-.555 19.999-9.444 23.999l-49.165 21.427c-9.165 4-19.443-.571-23.332-9.714l-53.053-129.136-86.664 89.138C18.729 472.71 0 463.554 0 447.977V18.299C0 1.899 19.921-6.096 30.277 5.443l284.412 292.542c11.472 11.179 3.007 31.141-12.5 31.141z\"],\n    \"mug-hot\": [512, 512, [], \"f7b6\", \"M127.1 146.5c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C111.8 5.9 105 0 96.8 0H80.4C70.6 0 63 8.5 64.1 18c3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zm112 0c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C223.8 5.9 217 0 208.8 0h-16.4c-9.8 0-17.5 8.5-16.3 18 3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zM400 192H32c-17.7 0-32 14.3-32 32v192c0 53 43 96 96 96h192c53 0 96-43 96-96h16c61.8 0 112-50.2 112-112s-50.2-112-112-112zm0 160h-16v-96h16c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"music\": [512, 512, [], \"f001\", \"M511.99 32.01c0-21.71-21.1-37.01-41.6-30.51L150.4 96c-13.3 4.2-22.4 16.5-22.4 30.5v261.42c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64V214.31l256-75.02v184.63c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64l-.01-351.99z\"],\n    \"network-wired\": [640, 512, [], \"f6ff\", \"M640 264v-16c0-8.84-7.16-16-16-16H344v-40h72c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H224c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h72v40H16c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h104v40H64c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h304v40h-56c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h104c8.84 0 16-7.16 16-16zM256 128V64h128v64H256zm-64 320H96v-64h96v64zm352 0h-96v-64h96v64z\"],\n    \"neuter\": [288, 512, [], \"f22c\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V468c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V316.4c64.1-14.5 112-71.9 112-140.4zm-144 80c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H88c-13.255 0-24 10.745-24 24v8H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h472c26.51 0 48-21.49 48-48V88c0-13.255-10.745-24-24-24zM56 400a8 8 0 0 1-8-8V144h16v248a8 8 0 0 1-8 8zm236-16H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm-208-96H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm0-96H140c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h360c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12z\"],\n    \"not-equal\": [448, 512, [], \"f53e\", \"M416 208c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32h-23.88l51.87-66.81c5.37-7.02 4.04-17.06-2.97-22.43L415.61 3.3c-7.02-5.38-17.06-4.04-22.44 2.97L311.09 112H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h204.56l-74.53 96H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h55.49l-51.87 66.81c-5.37 7.01-4.04 17.05 2.97 22.43L64 508.7c7.02 5.38 17.06 4.04 22.43-2.97L168.52 400H416c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32H243.05l74.53-96H416z\"],\n    \"notes-medical\": [384, 512, [], \"f481\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm96 304c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm0-192c0 4.4-3.6 8-8 8H104c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M480 128V96h20c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v20H64V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v40c0 6.627 5.373 12 12 12h20v320H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-20h384v20c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-20V128zM96 276V140c0-6.627 5.373-12 12-12h168c6.627 0 12 5.373 12 12v136c0 6.627-5.373 12-12 12H108c-6.627 0-12-5.373-12-12zm320 96c0 6.627-5.373 12-12 12H236c-6.627 0-12-5.373-12-12v-52h72c13.255 0 24-10.745 24-24v-72h84c6.627 0 12 5.373 12 12v136z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M64 320v26a6 6 0 0 1-6 6H6a6 6 0 0 1-6-6v-52a6 6 0 0 1 6-6h26V96H6a6 6 0 0 1-6-6V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v26h288V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-26v192h26a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-52a6 6 0 0 1-6-6v-26H64zm480-64v-32h26a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-52a6 6 0 0 0-6 6v26H408v72h8c13.255 0 24 10.745 24 24v64c0 13.255-10.745 24-24 24h-64c-13.255 0-24-10.745-24-24v-8H192v72h-26a6 6 0 0 0-6 6v52a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-26h288v26a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-26V256z\"],\n    \"oil-can\": [640, 512, [], \"f613\", \"M629.8 160.31L416 224l-50.49-25.24a64.07 64.07 0 0 0-28.62-6.76H280v-48h56c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h56v48h-56L37.72 166.86a31.9 31.9 0 0 0-5.79-.53C14.67 166.33 0 180.36 0 198.34v94.95c0 15.46 11.06 28.72 26.28 31.48L96 337.46V384c0 17.67 14.33 32 32 32h274.63c8.55 0 16.75-3.42 22.76-9.51l212.26-214.75c1.5-1.5 2.34-3.54 2.34-5.66V168c.01-5.31-5.08-9.15-10.19-7.69zM96 288.67l-48-8.73v-62.43l48 8.73v62.43zm453.33 84.66c0 23.56 19.1 42.67 42.67 42.67s42.67-19.1 42.67-42.67S592 288 592 288s-42.67 61.77-42.67 85.33z\"],\n    \"om\": [512, 512, [], \"f679\", \"M360.6 60.94a10.43 10.43 0 0 0 14.76 0l21.57-21.56a10.43 10.43 0 0 0 0-14.76L375.35 3.06c-4.08-4.07-10.68-4.07-14.76 0l-21.57 21.56a10.43 10.43 0 0 0 0 14.76l21.58 21.56zM412.11 192c-26.69 0-51.77 10.39-70.64 29.25l-24.25 24.25c-6.78 6.77-15.78 10.5-25.38 10.5H245c10.54-22.1 14.17-48.11 7.73-75.23-10.1-42.55-46.36-76.11-89.52-83.19-36.15-5.93-70.9 5.04-96.01 28.78-7.36 6.96-6.97 18.85 1.12 24.93l26.15 19.63c5.72 4.3 13.66 4.32 19.2-.21 8.45-6.9 19.02-10.71 30.27-10.71 26.47 0 48.01 21.53 48.01 48s-21.54 48-48.01 48h-31.9c-11.96 0-19.74 12.58-14.39 23.28l16.09 32.17c2.53 5.06 7.6 8.1 13.17 8.55h33.03c35.3 0 64.01 28.7 64.01 64s-28.71 64-64.01 64c-96.02 0-122.35-54.02-145.15-92.03-4.53-7.55-14.77-3.58-14.79 5.22C-.09 416 41.13 512 159.94 512c70.59 0 128.02-57.42 128.02-128 0-23.42-6.78-45.1-17.81-64h21.69c26.69 0 51.77-10.39 70.64-29.25l24.25-24.25c6.78-6.77 15.78-10.5 25.38-10.5 19.78 0 35.88 16.09 35.88 35.88V392c0 13.23-18.77 24-32.01 24-39.4 0-66.67-24.24-81.82-42.89-4.77-5.87-14.2-2.54-14.2 5.02V416s0 64 96.02 64c48.54 0 96.02-39.47 96.02-88V291.88c0-55.08-44.8-99.88-99.89-99.88zm42.18-124.73c-85.55 65.12-169.05 2.75-172.58.05-6.02-4.62-14.44-4.38-20.14.55-5.74 4.92-7.27 13.17-3.66 19.8 1.61 2.95 40.37 72.34 118.8 72.34 79.92 0 98.78-31.36 101.75-37.66 1.02-2.12 1.53-4.47 1.53-6.83V80c0-13.22-15.14-20.69-25.7-12.73z\"],\n    \"otter\": [640, 512, [], \"f700\", \"M608 32h-32l-13.25-13.25A63.97 63.97 0 0 0 517.49 0H497c-11.14 0-22.08 2.91-31.75 8.43L312 96h-56C149.96 96 64 181.96 64 288v1.61c0 32.75-16 62.14-39.56 84.89-18.19 17.58-28.1 43.68-23.19 71.8 6.76 38.8 42.9 65.7 82.28 65.7H192c17.67 0 32-14.33 32-32s-14.33-32-32-32H80c-8.83 0-16-7.17-16-16s7.17-16 16-16h224c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-64l149.49-80.5L448 416h80c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-28.22l-55.11-110.21L521.14 192H544c53.02 0 96-42.98 96-96V64c0-17.67-14.33-32-32-32zm-96 16c8.84 0 16 7.16 16 16s-7.16 16-16 16-16-7.16-16-16 7.16-16 16-16zm32 96h-34.96L407.2 198.84l-13.77-27.55L512 112h77.05c-6.62 18.58-24.22 32-45.05 32z\"],\n    \"outdent\": [448, 512, [], \"f03b\", \"M100.69 363.29c10 10 27.31 2.93 27.31-11.31V160c0-14.32-17.33-21.31-27.31-11.31l-96 96a16 16 0 0 0 0 22.62zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"pager\": [512, 512, [], \"f815\", \"M448 64H64a64 64 0 0 0-64 64v256a64 64 0 0 0 64 64h384a64 64 0 0 0 64-64V128a64 64 0 0 0-64-64zM160 368H80a16 16 0 0 1-16-16v-16a16 16 0 0 1 16-16h80zm128-16a16 16 0 0 1-16 16h-80v-48h80a16 16 0 0 1 16 16zm160-128a32 32 0 0 1-32 32H96a32 32 0 0 1-32-32v-64a32 32 0 0 1 32-32h320a32 32 0 0 1 32 32z\"],\n    \"paint-brush\": [512, 512, [], \"f1fc\", \"M167.02 309.34c-40.12 2.58-76.53 17.86-97.19 72.3-2.35 6.21-8 9.98-14.59 9.98-11.11 0-45.46-27.67-55.25-34.35C0 439.62 37.93 512 128 512c75.86 0 128-43.77 128-120.19 0-3.11-.65-6.08-.97-9.13l-88.01-73.34zM457.89 0c-15.16 0-29.37 6.71-40.21 16.45C213.27 199.05 192 203.34 192 257.09c0 13.7 3.25 26.76 8.73 38.7l63.82 53.18c7.21 1.8 14.64 3.03 22.39 3.03 62.11 0 98.11-45.47 211.16-256.46 7.38-14.35 13.9-29.85 13.9-45.99C512 20.64 486 0 457.89 0z\"],\n    \"paint-roller\": [512, 512, [], \"f5aa\", \"M416 128V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32zm32-64v128c0 17.67-14.33 32-32 32H256c-35.35 0-64 28.65-64 64v32c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32v-32h160c53.02 0 96-42.98 96-96v-64c0-35.35-28.65-64-64-64z\"],\n    \"palette\": [512, 512, [], \"f53f\", \"M204.3 5C104.9 24.4 24.8 104.3 5.2 203.4c-37 187 131.7 326.4 258.8 306.7 41.2-6.4 61.4-54.6 42.5-91.7-23.1-45.4 9.9-98.4 60.9-98.4h79.7c35.8 0 64.8-29.6 64.9-65.3C511.5 97.1 368.1-26.9 204.3 5zM96 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm32-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128-64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"pallet\": [640, 512, [], \"f482\", \"M144 256h352c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H384v128l-64-32-64 32V0H144c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16zm480 128c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h48v64H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16h-48v-64h48zm-336 64H128v-64h160v64zm224 0H352v-64h160v64z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M476 3.2L12.5 270.6c-18.1 10.4-15.8 35.6 2.2 43.2L121 358.4l287.3-253.2c5.5-4.9 13.3 2.6 8.6 8.3L176 407v80.5c0 23.6 28.5 32.9 42.5 15.8L282 426l124.6 52.2c14.2 6 30.4-2.9 33-18.2l72-432C515 7.8 493.3-6.8 476 3.2z\"],\n    \"paperclip\": [448, 512, [], \"f0c6\", \"M43.246 466.142c-58.43-60.289-57.341-157.511 1.386-217.581L254.392 34c44.316-45.332 116.351-45.336 160.671 0 43.89 44.894 43.943 117.329 0 162.276L232.214 383.128c-29.855 30.537-78.633 30.111-107.982-.998-28.275-29.97-27.368-77.473 1.452-106.953l143.743-146.835c6.182-6.314 16.312-6.422 22.626-.241l22.861 22.379c6.315 6.182 6.422 16.312.241 22.626L171.427 319.927c-4.932 5.045-5.236 13.428-.648 18.292 4.372 4.634 11.245 4.711 15.688.165l182.849-186.851c19.613-20.062 19.613-52.725-.011-72.798-19.189-19.627-49.957-19.637-69.154 0L90.39 293.295c-34.763 35.56-35.299 93.12-1.191 128.313 34.01 35.093 88.985 35.137 123.058.286l172.06-175.999c6.177-6.319 16.307-6.433 22.626-.256l22.877 22.364c6.319 6.177 6.434 16.307.256 22.626l-172.06 175.998c-59.576 60.938-155.943 60.216-214.77-.485z\"],\n    \"parachute-box\": [512, 512, [], \"f4cd\", \"M511.9 175c-9.1-75.6-78.4-132.4-158.3-158.7C390 55.7 416 116.9 416 192h28.1L327.5 321.5c-2.5-.6-4.8-1.5-7.5-1.5h-48V192h112C384 76.8 315.1 0 256 0S128 76.8 128 192h112v128h-48c-2.7 0-5 .9-7.5 1.5L67.9 192H96c0-75.1 26-136.3 62.4-175.7C78.5 42.7 9.2 99.5.1 175c-1.1 9.1 6.8 17 16 17h8.7l136.7 151.9c-.7 2.6-1.6 5.2-1.6 8.1v128c0 17.7 14.3 32 32 32h128c17.7 0 32-14.3 32-32V352c0-2.9-.9-5.4-1.6-8.1L487.1 192h8.7c9.3 0 17.2-7.8 16.1-17z\"],\n    \"paragraph\": [448, 512, [], \"f1dd\", \"M448 48v32a16 16 0 0 1-16 16h-48v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V96h-32v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V352h-32a160 160 0 0 1 0-320h240a16 16 0 0 1 16 16z\"],\n    \"parking\": [448, 512, [], \"f540\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM240 320h-48v48c0 8.8-7.2 16-16 16h-32c-8.8 0-16-7.2-16-16V144c0-8.8 7.2-16 16-16h96c52.9 0 96 43.1 96 96s-43.1 96-96 96zm0-128h-48v64h48c17.6 0 32-14.4 32-32s-14.4-32-32-32z\"],\n    \"passport\": [448, 512, [], \"f5ab\", \"M129.62 176h39.09c1.49-27.03 6.54-51.35 14.21-70.41-27.71 13.24-48.02 39.19-53.3 70.41zm0 32c5.29 31.22 25.59 57.17 53.3 70.41-7.68-19.06-12.72-43.38-14.21-70.41h-39.09zM224 286.69c7.69-7.45 20.77-34.42 23.43-78.69h-46.87c2.67 44.26 15.75 71.24 23.44 78.69zM200.57 176h46.87c-2.66-44.26-15.74-71.24-23.43-78.69-7.7 7.45-20.78 34.43-23.44 78.69zm64.51 102.41c27.71-13.24 48.02-39.19 53.3-70.41h-39.09c-1.49 27.03-6.53 51.35-14.21 70.41zM416 0H64C28.65 0 0 28.65 0 64v384c0 35.35 28.65 64 64 64h352c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32zm-80 416H112c-8.8 0-16-7.2-16-16s7.2-16 16-16h224c8.8 0 16 7.2 16 16s-7.2 16-16 16zm-112-96c-70.69 0-128-57.31-128-128S153.31 64 224 64s128 57.31 128 128-57.31 128-128 128zm41.08-214.41c7.68 19.06 12.72 43.38 14.21 70.41h39.09c-5.28-31.22-25.59-57.17-53.3-70.41z\"],\n    \"pastafarianism\": [640, 512, [], \"f67b\", \"M624.54 347.67c-32.7-12.52-57.36 4.25-75.37 16.45-17.06 11.53-23.25 14.42-31.41 11.36-8.12-3.09-10.83-9.38-15.89-29.38-3.33-13.15-7.44-29.32-17.95-42.65 2.24-2.91 4.43-5.79 6.38-8.57C500.47 304.45 513.71 312 532 312c33.95 0 50.87-25.78 62.06-42.83 10.59-16.14 15-21.17 21.94-21.17 13.25 0 24-10.75 24-24s-10.75-24-24-24c-33.95 0-50.87 25.78-62.06 42.83-10.6 16.14-15 21.17-21.94 21.17-17.31 0-37.48-61.43-97.26-101.91l17.25-34.5C485.43 125.5 512 97.98 512 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 13.02 3.94 25.1 10.62 35.21l-18.15 36.3c-16.98-4.6-35.6-7.51-56.46-7.51s-39.49 2.91-56.46 7.51l-18.15-36.3C252.06 89.1 256 77.02 256 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 33.98 26.56 61.5 60.02 63.6l17.25 34.5C145.68 202.44 125.15 264 108 264c-6.94 0-11.34-5.03-21.94-21.17C74.88 225.78 57.96 200 24 200c-13.25 0-24 10.75-24 24s10.75 24 24 24c6.94 0 11.34 5.03 21.94 21.17C57.13 286.22 74.05 312 108 312c18.29 0 31.53-7.55 41.7-17.11 1.95 2.79 4.14 5.66 6.38 8.57-10.51 13.33-14.62 29.5-17.95 42.65-5.06 20-7.77 26.28-15.89 29.38-8.11 3.06-14.33.17-31.41-11.36-18.03-12.2-42.72-28.92-75.37-16.45-12.39 4.72-18.59 18.58-13.87 30.97 4.72 12.41 18.61 18.61 30.97 13.88 8.16-3.09 14.34-.19 31.39 11.36 13.55 9.16 30.83 20.86 52.42 20.84 7.17 0 14.83-1.28 22.97-4.39 32.66-12.44 39.98-41.33 45.33-62.44 2.21-8.72 3.99-14.49 5.95-18.87 16.62 13.61 36.95 25.88 61.64 34.17-9.96 37-32.18 90.8-60.26 90.8-13.25 0-24 10.75-24 24s10.75 24 24 24c66.74 0 97.05-88.63 107.42-129.14 6.69.6 13.42 1.14 20.58 1.14s13.89-.54 20.58-1.14C350.95 423.37 381.26 512 448 512c13.25 0 24-10.75 24-24s-10.75-24-24-24c-27.94 0-50.21-53.81-60.22-90.81 24.69-8.29 45-20.56 61.62-34.16 1.96 4.38 3.74 10.15 5.95 18.87 5.34 21.11 12.67 50 45.33 62.44 8.14 3.11 15.8 4.39 22.97 4.39 21.59 0 38.87-11.69 52.42-20.84 17.05-11.55 23.28-14.45 31.39-11.36 12.39 4.75 26.27-1.47 30.97-13.88 4.71-12.4-1.49-26.26-13.89-30.98zM448 48c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zm-256 0c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16z\"],\n    \"paste\": [448, 512, [], \"f0ea\", \"M128 184c0-30.879 25.122-56 56-56h136V56c0-13.255-10.745-24-24-24h-80.61C204.306 12.89 183.637 0 160 0s-44.306 12.89-55.39 32H24C10.745 32 0 42.745 0 56v336c0 13.255 10.745 24 24 24h104V184zm32-144c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24zm184 248h104v200c0 13.255-10.745 24-24 24H184c-13.255 0-24-10.745-24-24V184c0-13.255 10.745-24 24-24h136v104c0 13.2 10.8 24 24 24zm104-38.059V256h-96v-96h6.059a24 24 0 0 1 16.97 7.029l65.941 65.941a24.002 24.002 0 0 1 7.03 16.971z\"],\n    \"pause\": [448, 512, [], \"f04c\", \"M144 479H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h96c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zm304-48V79c0-26.5-21.5-48-48-48h-96c-26.5 0-48 21.5-48 48v352c0 26.5 21.5 48 48 48h96c26.5 0 48-21.5 48-48z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm-16 328c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160zm112 0c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160z\"],\n    \"paw\": [512, 512, [], \"f1b0\", \"M256 224c-79.41 0-192 122.76-192 200.25 0 34.9 26.81 55.75 71.74 55.75 48.84 0 81.09-25.08 120.26-25.08 39.51 0 71.85 25.08 120.26 25.08 44.93 0 71.74-20.85 71.74-55.75C448 346.76 335.41 224 256 224zm-147.28-12.61c-10.4-34.65-42.44-57.09-71.56-50.13-29.12 6.96-44.29 40.69-33.89 75.34 10.4 34.65 42.44 57.09 71.56 50.13 29.12-6.96 44.29-40.69 33.89-75.34zm84.72-20.78c30.94-8.14 46.42-49.94 34.58-93.36s-46.52-72.01-77.46-63.87-46.42 49.94-34.58 93.36c11.84 43.42 46.53 72.02 77.46 63.87zm281.39-29.34c-29.12-6.96-61.15 15.48-71.56 50.13-10.4 34.65 4.77 68.38 33.89 75.34 29.12 6.96 61.15-15.48 71.56-50.13 10.4-34.65-4.77-68.38-33.89-75.34zm-156.27 29.34c30.94 8.14 65.62-20.45 77.46-63.87 11.84-43.42-3.64-85.21-34.58-93.36s-65.62 20.45-77.46 63.87c-11.84 43.42 3.64 85.22 34.58 93.36z\"],\n    \"peace\": [496, 512, [], \"f67c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm184 248c0 31.93-8.2 61.97-22.57 88.17L280 240.63V74.97c86.23 15.21 152 90.5 152 181.03zM216 437.03c-33.86-5.97-64.49-21.2-89.29-43.02L216 322.57v114.46zm64-114.46L369.29 394c-24.8 21.82-55.43 37.05-89.29 43.02V322.57zm-64-247.6v165.66L86.57 344.17C72.2 317.97 64 287.93 64 256c0-90.53 65.77-165.82 152-181.03z\"],\n    \"pen\": [512, 512, [], \"f304\", \"M290.74 93.24l128.02 128.02-277.99 277.99-114.14 12.6C11.35 513.54-1.56 500.62.14 485.34l12.7-114.22 277.9-277.88zm207.2-19.06l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.76 18.75-49.16 0-67.91z\"],\n    \"pen-alt\": [512, 512, [], \"f305\", \"M497.94 74.17l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91zm-246.8-20.53c-15.62-15.62-40.94-15.62-56.56 0L75.8 172.43c-6.25 6.25-6.25 16.38 0 22.62l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l101.82-101.82 22.63 22.62L93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l196.79-196.79-82.77-82.77-84.85-84.85z\"],\n    \"pen-fancy\": [512, 512, [], \"f5ac\", \"M79.18 282.94a32.005 32.005 0 0 0-20.24 20.24L0 480l4.69 4.69 92.89-92.89c-.66-2.56-1.57-5.03-1.57-7.8 0-17.67 14.33-32 32-32s32 14.33 32 32-14.33 32-32 32c-2.77 0-5.24-.91-7.8-1.57l-92.89 92.89L32 512l176.82-58.94a31.983 31.983 0 0 0 20.24-20.24l33.07-84.07-98.88-98.88-84.07 33.07zM369.25 28.32L186.14 227.81l97.85 97.85 199.49-183.11C568.4 67.48 443.73-55.94 369.25 28.32z\"],\n    \"pen-nib\": [512, 512, [], \"f5ad\", \"M136.6 138.79a64.003 64.003 0 0 0-43.31 41.35L0 460l14.69 14.69L164.8 324.58c-2.99-6.26-4.8-13.18-4.8-20.58 0-26.51 21.49-48 48-48s48 21.49 48 48-21.49 48-48 48c-7.4 0-14.32-1.81-20.58-4.8L37.31 497.31 52 512l279.86-93.29a64.003 64.003 0 0 0 41.35-43.31L416 224 288 96l-151.4 42.79zm361.34-64.62l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91z\"],\n    \"pen-square\": [448, 512, [], \"f14b\", \"M400 480H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zM238.1 177.9L102.4 313.6l-6.3 57.1c-.8 7.6 5.6 14.1 13.3 13.3l57.1-6.3L302.2 242c2.3-2.3 2.3-6.1 0-8.5L246.7 178c-2.5-2.4-6.3-2.4-8.6-.1zM345 165.1L314.9 135c-9.4-9.4-24.6-9.4-33.9 0l-23.1 23.1c-2.3 2.3-2.3 6.1 0 8.5l55.5 55.5c2.3 2.3 6.1 2.3 8.5 0L345 199c9.3-9.3 9.3-24.5 0-33.9z\"],\n    \"pencil-alt\": [512, 512, [], \"f303\", \"M497.9 142.1l-46.1 46.1c-4.7 4.7-12.3 4.7-17 0l-111-111c-4.7-4.7-4.7-12.3 0-17l46.1-46.1c18.7-18.7 49.1-18.7 67.9 0l60.1 60.1c18.8 18.7 18.8 49.1 0 67.9zM284.2 99.8L21.6 362.4.4 483.9c-2.9 16.4 11.4 30.6 27.8 27.8l121.5-21.3 262.6-262.6c4.7-4.7 4.7-12.3 0-17l-111-111c-4.8-4.7-12.4-4.7-17.1 0zM124.1 339.9c-5.5-5.5-5.5-14.3 0-19.8l154-154c5.5-5.5 14.3-5.5 19.8 0s5.5 14.3 0 19.8l-154 154c-5.5 5.5-14.3 5.5-19.8 0zM88 424h48v36.3l-64.5 11.3-31.1-31.1L51.7 376H88v48z\"],\n    \"pencil-ruler\": [512, 512, [], \"f5ae\", \"M109.46 244.04l134.58-134.56-44.12-44.12-61.68 61.68a7.919 7.919 0 0 1-11.21 0l-11.21-11.21c-3.1-3.1-3.1-8.12 0-11.21l61.68-61.68-33.64-33.65C131.47-3.1 111.39-3.1 99 9.29L9.29 99c-12.38 12.39-12.39 32.47 0 44.86l100.17 100.18zm388.47-116.8c18.76-18.76 18.75-49.17 0-67.93l-45.25-45.25c-18.76-18.76-49.18-18.76-67.95 0l-46.02 46.01 113.2 113.2 46.02-46.03zM316.08 82.71l-297 296.96L.32 487.11c-2.53 14.49 10.09 27.11 24.59 24.56l107.45-18.84L429.28 195.9 316.08 82.71zm186.63 285.43l-33.64-33.64-61.68 61.68c-3.1 3.1-8.12 3.1-11.21 0l-11.21-11.21c-3.09-3.1-3.09-8.12 0-11.21l61.68-61.68-44.14-44.14L267.93 402.5l100.21 100.2c12.39 12.39 32.47 12.39 44.86 0l89.71-89.7c12.39-12.39 12.39-32.47 0-44.86z\"],\n    \"people-carry\": [640, 512, [], \"f4ce\", \"M128 96c26.5 0 48-21.5 48-48S154.5 0 128 0 80 21.5 80 48s21.5 48 48 48zm384 0c26.5 0 48-21.5 48-48S538.5 0 512 0s-48 21.5-48 48 21.5 48 48 48zm125.7 372.1l-44-110-41.1 46.4-2 18.2 27.7 69.2c5 12.5 17 20.1 29.7 20.1 4 0 8-.7 11.9-2.3 16.4-6.6 24.4-25.2 17.8-41.6zm-34.2-209.8L585 178.1c-4.6-20-18.6-36.8-37.5-44.9-18.5-8-39-6.7-56.1 3.3-22.7 13.4-39.7 34.5-48.1 59.4L432 229.8 416 240v-96c0-8.8-7.2-16-16-16H240c-8.8 0-16 7.2-16 16v96l-16.1-10.2-11.3-33.9c-8.3-25-25.4-46-48.1-59.4-17.2-10-37.6-11.3-56.1-3.3-18.9 8.1-32.9 24.9-37.5 44.9l-18.4 80.2c-4.6 20 .7 41.2 14.4 56.7l67.2 75.9 10.1 92.6C130 499.8 143.8 512 160 512c1.2 0 2.3-.1 3.5-.2 17.6-1.9 30.2-17.7 28.3-35.3l-10.1-92.8c-1.5-13-6.9-25.1-15.6-35l-43.3-49 17.6-70.3 6.8 20.4c4.1 12.5 11.9 23.4 24.5 32.6l51.1 32.5c4.6 2.9 12.1 4.6 17.2 5h160c5.1-.4 12.6-2.1 17.2-5l51.1-32.5c12.6-9.2 20.4-20 24.5-32.6l6.8-20.4 17.6 70.3-43.3 49c-8.7 9.9-14.1 22-15.6 35l-10.1 92.8c-1.9 17.6 10.8 33.4 28.3 35.3 1.2.1 2.3.2 3.5.2 16.1 0 30-12.1 31.8-28.5l10.1-92.6 67.2-75.9c13.6-15.5 19-36.7 14.4-56.7zM46.3 358.1l-44 110c-6.6 16.4 1.4 35 17.8 41.6 16.8 6.6 35.1-1.7 41.6-17.8l27.7-69.2-2-18.2-41.1-46.4z\"],\n    \"pepper-hot\": [512, 512, [], \"f816\", \"M330.67 263.12V173.4l-52.75-24.22C219.44 218.76 197.58 400 56 400a56 56 0 0 0 0 112c212.64 0 370.65-122.87 419.18-210.34l-37.05-38.54zm131.09-128.37C493.92 74.91 477.18 26.48 458.62 3a8 8 0 0 0-11.93-.59l-22.9 23a8.06 8.06 0 0 0-.89 10.23c6.86 10.36 17.05 35.1-1.4 72.32A142.85 142.85 0 0 0 364.34 96c-28 0-54 8.54-76.34 22.59l74.67 34.29v78.24h89.09L506.44 288c3.26-12.62 5.56-25.63 5.56-39.31a154 154 0 0 0-50.24-113.94z\"],\n    \"percent\": [448, 512, [], \"f295\", \"M112 224c61.9 0 112-50.1 112-112S173.9 0 112 0 0 50.1 0 112s50.1 112 112 112zm0-160c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48 21.5-48 48-48zm224 224c-61.9 0-112 50.1-112 112s50.1 112 112 112 112-50.1 112-112-50.1-112-112-112zm0 160c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zM392.3.2l31.6-.1c19.4-.1 30.9 21.8 19.7 37.8L77.4 501.6a23.95 23.95 0 0 1-19.6 10.2l-33.4.1c-19.5 0-30.9-21.9-19.7-37.8l368-463.7C377.2 4 384.5.2 392.3.2z\"],\n    \"percentage\": [384, 512, [], \"f541\", \"M109.25 173.25c24.99-24.99 24.99-65.52 0-90.51-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 25 25 65.52 25 90.51 0zm256 165.49c-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 24.99 24.99 65.52 24.99 90.51 0 25-24.99 25-65.51 0-90.51zm-1.94-231.43l-22.62-22.62c-12.5-12.5-32.76-12.5-45.25 0L20.69 359.44c-12.5 12.5-12.5 32.76 0 45.25l22.62 22.62c12.5 12.5 32.76 12.5 45.25 0l274.75-274.75c12.5-12.49 12.5-32.75 0-45.25z\"],\n    \"person-booth\": [576, 512, [], \"f756\", \"M192 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320h-64v176zm32-272h-50.9l-45.2-45.3C115.8 166.6 99.7 160 82.7 160H64c-17.1 0-33.2 6.7-45.3 18.8C6.7 190.9 0 207 0 224.1L.2 320 0 480c0 17.7 14.3 32 31.9 32 17.6 0 32-14.3 32-32l.1-100.7c.9.5 1.6 1.3 2.5 1.7l29.1 43v56c0 17.7 14.3 32 32 32s32-14.3 32-32v-56.5c0-9.9-2.3-19.8-6.7-28.6l-41.2-61.3V253l20.9 20.9c9.1 9.1 21.1 14.1 33.9 14.1H224c17.7 0 32-14.3 32-32s-14.3-32-32-32zM64 128c26.5 0 48-21.5 48-48S90.5 32 64 32 16 53.5 16 80s21.5 48 48 48zm224-96l31.5 223.1-30.9 154.6c-4.3 21.6 13 38.3 31.4 38.3 15.2 0 28-9.1 32.3-30.4.9 16.9 14.6 30.4 31.7 30.4 17.7 0 32-14.3 32-32 0 17.7 14.3 32 32 32s32-14.3 32-32V0H288v32zm-96 0v160h64V0h-32c-17.7 0-32 14.3-32 32zM544 0h-32v496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32c0-17.7-14.3-32-32-32z\"],\n    \"phone\": [512, 512, [], \"f095\", \"M493.4 24.6l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-36 76.7-98.9 140.5-177.2 177.2l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48C3.9 366.5-2 378.1.6 389.4l24 104C27.1 504.2 36.7 512 48 512c256.1 0 464-207.5 464-464 0-11.2-7.7-20.9-18.6-23.4z\"],\n    \"phone-alt\": [512, 512, [], \"f879\", \"M497.39 361.8l-112-48a24 24 0 0 0-28 6.9l-49.6 60.6A370.66 370.66 0 0 1 130.6 204.11l60.6-49.6a23.94 23.94 0 0 0 6.9-28l-48-112A24.16 24.16 0 0 0 122.6.61l-104 24A24 24 0 0 0 0 48c0 256.5 207.9 464 464 464a24 24 0 0 0 23.4-18.6l24-104a24.29 24.29 0 0 0-14.01-27.6z\"],\n    \"phone-slash\": [640, 512, [], \"f3dd\", \"M268.2 381.4l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48c-10.7 4.6-16.5 16.1-13.9 27.5l24 104c2.5 10.8 12.1 18.6 23.4 18.6 100.7 0 193.7-32.4 269.7-86.9l-80-61.8c-10.9 6.5-22.1 12.7-33.6 18.1zm365.6 76.7L475.1 335.5C537.9 256.4 576 156.9 576 48c0-11.2-7.7-20.9-18.6-23.4l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-12.2 26.1-27.9 50.3-46 72.8L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"phone-square\": [448, 512, [], \"f098\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM94 416c-7.033 0-13.057-4.873-14.616-11.627l-14.998-65a15 15 0 0 1 8.707-17.16l69.998-29.999a15 15 0 0 1 17.518 4.289l30.997 37.885c48.944-22.963 88.297-62.858 110.781-110.78l-37.886-30.997a15.001 15.001 0 0 1-4.289-17.518l30-69.998a15 15 0 0 1 17.16-8.707l65 14.998A14.997 14.997 0 0 1 384 126c0 160.292-129.945 290-290 290z\"],\n    \"phone-square-alt\": [448, 512, [], \"f87b\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h352a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48zm-16.39 307.37l-15 65A15 15 0 0 1 354 416C194 416 64 286.29 64 126a15.7 15.7 0 0 1 11.63-14.61l65-15A18.23 18.23 0 0 1 144 96a16.27 16.27 0 0 1 13.79 9.09l30 70A17.9 17.9 0 0 1 189 181a17 17 0 0 1-5.5 11.61l-37.89 31a231.91 231.91 0 0 0 110.78 110.78l31-37.89A17 17 0 0 1 299 291a17.85 17.85 0 0 1 5.91 1.21l70 30A16.25 16.25 0 0 1 384 336a17.41 17.41 0 0 1-.39 3.37z\"],\n    \"phone-volume\": [384, 512, [], \"f2a0\", \"M97.333 506.966c-129.874-129.874-129.681-340.252 0-469.933 5.698-5.698 14.527-6.632 21.263-2.422l64.817 40.513a17.187 17.187 0 0 1 6.849 20.958l-32.408 81.021a17.188 17.188 0 0 1-17.669 10.719l-55.81-5.58c-21.051 58.261-20.612 122.471 0 179.515l55.811-5.581a17.188 17.188 0 0 1 17.669 10.719l32.408 81.022a17.188 17.188 0 0 1-6.849 20.958l-64.817 40.513a17.19 17.19 0 0 1-21.264-2.422zM247.126 95.473c11.832 20.047 11.832 45.008 0 65.055-3.95 6.693-13.108 7.959-18.718 2.581l-5.975-5.726c-3.911-3.748-4.793-9.622-2.261-14.41a32.063 32.063 0 0 0 0-29.945c-2.533-4.788-1.65-10.662 2.261-14.41l5.975-5.726c5.61-5.378 14.768-4.112 18.718 2.581zm91.787-91.187c60.14 71.604 60.092 175.882 0 247.428-4.474 5.327-12.53 5.746-17.552.933l-5.798-5.557c-4.56-4.371-4.977-11.529-.93-16.379 49.687-59.538 49.646-145.933 0-205.422-4.047-4.85-3.631-12.008.93-16.379l5.798-5.557c5.022-4.813 13.078-4.394 17.552.933zm-45.972 44.941c36.05 46.322 36.108 111.149 0 157.546-4.39 5.641-12.697 6.251-17.856 1.304l-5.818-5.579c-4.4-4.219-4.998-11.095-1.285-15.931 26.536-34.564 26.534-82.572 0-117.134-3.713-4.836-3.115-11.711 1.285-15.931l5.818-5.579c5.159-4.947 13.466-4.337 17.856 1.304z\"],\n    \"photo-video\": [640, 512, [], \"f87c\", \"M608 0H160a32 32 0 0 0-32 32v96h160V64h192v320h128a32 32 0 0 0 32-32V32a32 32 0 0 0-32-32zM232 103a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm352 208a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm-168 57H32a32 32 0 0 0-32 32v288a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V192a32 32 0 0 0-32-32zM96 224a32 32 0 1 1-32 32 32 32 0 0 1 32-32zm288 224H64v-32l64-64 32 32 128-128 96 96z\"],\n    \"piggy-bank\": [576, 512, [], \"f4d3\", \"M560 224h-29.5c-8.8-20-21.6-37.7-37.4-52.5L512 96h-32c-29.4 0-55.4 13.5-73 34.3-7.6-1.1-15.1-2.3-23-2.3H256c-77.4 0-141.9 55-156.8 128H56c-14.8 0-26.5-13.5-23.5-28.8C34.7 215.8 45.4 208 57 208h1c3.3 0 6-2.7 6-6v-20c0-3.3-2.7-6-6-6-28.5 0-53.9 20.4-57.5 48.6C-3.9 258.8 22.7 288 56 288h40c0 52.2 25.4 98.1 64 127.3V496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-48h128v48c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80.7c11.8-8.9 22.3-19.4 31.3-31.3H560c8.8 0 16-7.2 16-16V240c0-8.8-7.2-16-16-16zm-128 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM256 96h128c5.4 0 10.7.4 15.9.8 0-.3.1-.5.1-.8 0-53-43-96-96-96s-96 43-96 96c0 2.1.5 4.1.6 6.2 15.2-3.9 31-6.2 47.4-6.2z\"],\n    \"pills\": [576, 512, [], \"f484\", \"M112 32C50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V144c0-61.9-50.1-112-112-112zm48 224H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm139.7-29.7c-3.5-3.5-9.4-3.1-12.3.8-45.3 62.5-40.4 150.1 15.9 206.4 56.3 56.3 143.9 61.2 206.4 15.9 4-2.9 4.3-8.8.8-12.3L299.7 226.3zm229.8-19c-56.3-56.3-143.9-61.2-206.4-15.9-4 2.9-4.3 8.8-.8 12.3l210.8 210.8c3.5 3.5 9.4 3.1 12.3-.8 45.3-62.6 40.5-150.1-15.9-206.4z\"],\n    \"pizza-slice\": [512, 512, [], \"f818\", \"M158.87.15c-16.16-1.52-31.2 8.42-35.33 24.12l-14.81 56.27c187.62 5.49 314.54 130.61 322.48 317l56.94-15.78c15.72-4.36 25.49-19.68 23.62-35.9C490.89 165.08 340.78 17.32 158.87.15zm-58.47 112L.55 491.64a16.21 16.21 0 0 0 20 19.75l379-105.1c-4.27-174.89-123.08-292.14-299.15-294.1zM128 416a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm48-152a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm104 104a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"place-of-worship\": [640, 512, [], \"f67f\", \"M620.61 366.55L512 320v192h112c8.84 0 16-7.16 16-16V395.96a32 32 0 0 0-19.39-29.41zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.55A32 32 0 0 0 0 395.96zm464.46-149.28L416 217.6V102.63c0-8.49-3.37-16.62-9.38-22.63L331.31 4.69c-6.25-6.25-16.38-6.25-22.62 0L233.38 80c-6 6-9.38 14.14-9.38 22.63V217.6l-48.46 29.08A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.66-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44z\"],\n    \"plane\": [576, 512, [], \"f072\", \"M480 192H365.71L260.61 8.06A16.014 16.014 0 0 0 246.71 0h-65.5c-10.63 0-18.3 10.17-15.38 20.39L214.86 192H112l-43.2-57.6c-3.02-4.03-7.77-6.4-12.8-6.4H16.01C5.6 128-2.04 137.78.49 147.88L32 256 .49 364.12C-2.04 374.22 5.6 384 16.01 384H56c5.04 0 9.78-2.37 12.8-6.4L112 320h102.86l-49.03 171.6c-2.92 10.22 4.75 20.4 15.38 20.4h65.5c5.74 0 11.04-3.08 13.89-8.06L365.71 320H480c35.35 0 96-28.65 96-64s-60.65-64-96-64z\"],\n    \"plane-arrival\": [640, 512, [], \"f5af\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM44.81 205.66l88.74 80a62.607 62.607 0 0 0 25.47 13.93l287.6 78.35c26.48 7.21 54.56 8.72 81 1.36 29.67-8.27 43.44-21.21 47.25-35.71 3.83-14.5-1.73-32.71-23.37-54.96-19.28-19.82-44.35-32.79-70.83-40l-97.51-26.56L282.8 30.22c-1.51-5.81-5.95-10.35-11.66-11.91L206.05.58c-10.56-2.88-20.9 5.32-20.71 16.44l47.92 164.21-102.2-27.84-27.59-67.88c-1.93-4.89-6.01-8.57-11.02-9.93L52.72 64.75c-10.34-2.82-20.53 5-20.72 15.88l.23 101.78c.19 8.91 6.03 17.34 12.58 23.25z\"],\n    \"plane-departure\": [640, 512, [], \"f5b0\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM80.55 341.27c6.28 6.84 15.1 10.72 24.33 10.71l130.54-.18a65.62 65.62 0 0 0 29.64-7.12l290.96-147.65c26.74-13.57 50.71-32.94 67.02-58.31 18.31-28.48 20.3-49.09 13.07-63.65-7.21-14.57-24.74-25.27-58.25-27.45-29.85-1.94-59.54 5.92-86.28 19.48l-98.51 49.99-218.7-82.06a17.799 17.799 0 0 0-18-1.11L90.62 67.29c-10.67 5.41-13.25 19.65-5.17 28.53l156.22 98.1-103.21 52.38-72.35-36.47a17.804 17.804 0 0 0-16.07.02L9.91 230.22c-10.44 5.3-13.19 19.12-5.57 28.08l76.21 82.97z\"],\n    \"play\": [448, 512, [], \"f04b\", \"M424.4 214.7L72.4 6.6C43.8-10.3 0 6.1 0 47.9V464c0 37.5 40.7 60.1 72.4 41.3l352-208c31.4-18.5 31.5-64.1 0-82.6z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm115.7 272l-176 101c-15.8 8.8-35.7-2.5-35.7-21V152c0-18.4 19.8-29.8 35.7-21l176 107c16.4 9.2 16.4 32.9 0 42z\"],\n    \"plug\": [384, 512, [], \"f1e6\", \"M256 144V32c0-17.673 14.327-32 32-32s32 14.327 32 32v112h-64zm112 16H16c-8.837 0-16 7.163-16 16v32c0 8.837 7.163 16 16 16h16v32c0 77.406 54.969 141.971 128 156.796V512h64v-99.204c73.031-14.825 128-79.39 128-156.796v-32h16c8.837 0 16-7.163 16-16v-32c0-8.837-7.163-16-16-16zm-240-16V32c0-17.673-14.327-32-32-32S64 14.327 64 32v112h64z\"],\n    \"plus\": [448, 512, [], \"f067\", \"M416 208H272V64c0-17.67-14.33-32-32-32h-32c-17.67 0-32 14.33-32 32v144H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h144v144c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V304h144c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"plus-circle\": [512, 512, [], \"f055\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm144 276c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92h-92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-32 252c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92H92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"podcast\": [448, 512, [], \"f2ce\", \"M267.429 488.563C262.286 507.573 242.858 512 224 512c-18.857 0-38.286-4.427-43.428-23.437C172.927 460.134 160 388.898 160 355.75c0-35.156 31.142-43.75 64-43.75s64 8.594 64 43.75c0 32.949-12.871 104.179-20.571 132.813zM156.867 288.554c-18.693-18.308-29.958-44.173-28.784-72.599 2.054-49.724 42.395-89.956 92.124-91.881C274.862 121.958 320 165.807 320 220c0 26.827-11.064 51.116-28.866 68.552-2.675 2.62-2.401 6.986.628 9.187 9.312 6.765 16.46 15.343 21.234 25.363 1.741 3.654 6.497 4.66 9.449 1.891 28.826-27.043 46.553-65.783 45.511-108.565-1.855-76.206-63.595-138.208-139.793-140.369C146.869 73.753 80 139.215 80 220c0 41.361 17.532 78.7 45.55 104.989 2.953 2.771 7.711 1.77 9.453-1.887 4.774-10.021 11.923-18.598 21.235-25.363 3.029-2.2 3.304-6.566.629-9.185zM224 0C100.204 0 0 100.185 0 224c0 89.992 52.602 165.647 125.739 201.408 4.333 2.118 9.267-1.544 8.535-6.31-2.382-15.512-4.342-30.946-5.406-44.339-.146-1.836-1.149-3.486-2.678-4.512-47.4-31.806-78.564-86.016-78.187-147.347.592-96.237 79.29-174.648 175.529-174.899C320.793 47.747 400 126.797 400 224c0 61.932-32.158 116.49-80.65 147.867-.999 14.037-3.069 30.588-5.624 47.23-.732 4.767 4.203 8.429 8.535 6.31C395.227 389.727 448 314.187 448 224 448 100.205 347.815 0 224 0zm0 160c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64z\"],\n    \"poll\": [448, 512, [], \"f681\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM160 368c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V240c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v128zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V144c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v224zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-64c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v64z\"],\n    \"poll-h\": [448, 512, [], \"f682\", \"M448 432V80c0-26.5-21.5-48-48-48H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48zM112 192c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h128c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-64z\"],\n    \"poo\": [512, 512, [], \"f2fe\", \"M451.4 369.1C468.7 356 480 335.4 480 312c0-39.8-32.2-72-72-72h-14.1c13.4-11.7 22.1-28.8 22.1-48 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C250.3 14.6 256 30.6 256 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 19.2 8.7 36.3 22.1 48H104c-39.8 0-72 32.2-72 72 0 23.4 11.3 44 28.6 57.1C26.3 374.6 0 404.1 0 440c0 39.8 32.2 72 72 72h368c39.8 0 72-32.2 72-72 0-35.9-26.3-65.4-60.6-70.9zM192 256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm159.5 139C341 422.9 293 448 256 448s-85-25.1-95.5-53c-2-5.3 2-11 7.8-11h175.4c5.8 0 9.8 5.7 7.8 11zM320 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"poo-storm\": [448, 512, [], \"f75a\", \"M308 336h-57.7l17.3-64.9c2-7.6-3.7-15.1-11.6-15.1h-68c-6 0-11.1 4.5-11.9 10.4l-16 120c-1 7.2 4.6 13.6 11.9 13.6h59.3l-23 97.2c-1.8 7.6 4 14.8 11.7 14.8 4.2 0 8.2-2.2 10.4-6l88-152c4.6-8-1.2-18-10.4-18zm66.4-111.3c5.9-9.6 9.6-20.6 9.6-32.7 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C218.3 14.6 224 30.6 224 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 12.1 3.7 23.1 9.6 32.7C32.6 228 0 262.2 0 304c0 44 36 80 80 80h48.3c.1-.6 0-1.2 0-1.8l16-120c3-21.8 21.7-38.2 43.7-38.2h68c13.8 0 26.5 6.3 34.9 17.2s11.2 24.8 7.6 38.1l-6.6 24.7h16c15.7 0 30.3 8.4 38.1 22 7.8 13.6 7.8 30.5 0 44l-8.1 14h30c44 0 80-36 80-80 .1-41.8-32.5-76-73.5-79.3z\"],\n    \"poop\": [512, 512, [], \"f619\", \"M451.36 369.14C468.66 355.99 480 335.41 480 312c0-39.77-32.24-72-72-72h-14.07c13.42-11.73 22.07-28.78 22.07-48 0-35.35-28.65-64-64-64h-5.88c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96-5.17 0-10.15.74-15.11 1.52C250.31 14.64 256 30.62 256 48c0 44.18-35.82 80-80 80h-16c-35.35 0-64 28.65-64 64 0 19.22 8.65 36.27 22.07 48H104c-39.76 0-72 32.23-72 72 0 23.41 11.34 43.99 28.64 57.14C26.31 374.62 0 404.12 0 440c0 39.76 32.24 72 72 72h368c39.76 0 72-32.24 72-72 0-35.88-26.31-65.38-60.64-70.86z\"],\n    \"portrait\": [384, 512, [], \"f3e0\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM192 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 384 80 375.4 80 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"pound-sign\": [320, 512, [], \"f154\", \"M308 352h-45.495c-6.627 0-12 5.373-12 12v50.848H128V288h84c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-84v-63.556c0-32.266 24.562-57.086 61.792-57.086 23.658 0 45.878 11.505 57.652 18.849 5.151 3.213 11.888 2.051 15.688-2.685l28.493-35.513c4.233-5.276 3.279-13.005-2.119-17.081C273.124 54.56 236.576 32 187.931 32 106.026 32 48 84.742 48 157.961V224H20c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h28v128H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h296c6.627 0 12-5.373 12-12V364c0-6.627-5.373-12-12-12z\"],\n    \"power-off\": [512, 512, [], \"f011\", \"M400 54.1c63 45 104 118.6 104 201.9 0 136.8-110.8 247.7-247.5 248C120 504.3 8.2 393 8 256.4 7.9 173.1 48.9 99.3 111.8 54.2c11.7-8.3 28-4.8 35 7.7L162.6 90c5.9 10.5 3.1 23.8-6.6 31-41.5 30.8-68 79.6-68 134.9-.1 92.3 74.5 168.1 168 168.1 91.6 0 168.6-74.2 168-169.1-.3-51.8-24.7-101.8-68.1-134-9.7-7.2-12.4-20.5-6.5-30.9l15.8-28.1c7-12.4 23.2-16.1 34.8-7.8zM296 264V24c0-13.3-10.7-24-24-24h-32c-13.3 0-24 10.7-24 24v240c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24z\"],\n    \"pray\": [384, 512, [], \"f683\", \"M256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-30.63 169.75c14.06 16.72 39 19.09 55.97 5.22l88-72.02c17.09-13.98 19.59-39.19 5.62-56.28-13.97-17.11-39.19-19.59-56.31-5.62l-57.44 47-38.91-46.31c-15.44-18.39-39.22-27.92-64-25.33-24.19 2.48-45.25 16.27-56.37 36.92l-49.37 92.03c-23.4 43.64-8.69 96.37 34.19 123.75L131.56 432H40c-22.09 0-40 17.91-40 40s17.91 40 40 40h208c34.08 0 53.77-42.79 28.28-68.28L166.42 333.86l34.8-64.87 24.15 28.76z\"],\n    \"praying-hands\": [640, 512, [], \"f684\", \"M272 191.91c-17.6 0-32 14.4-32 32v80c0 8.84-7.16 16-16 16s-16-7.16-16-16v-76.55c0-17.39 4.72-34.47 13.69-49.39l77.75-129.59c9.09-15.16 4.19-34.81-10.97-43.91-14.45-8.67-32.72-4.3-42.3 9.21-.2.23-.62.21-.79.48l-117.26 175.9C117.56 205.9 112 224.31 112 243.29v80.23l-90.12 30.04A31.974 31.974 0 0 0 0 383.91v96c0 10.82 8.52 32 32 32 2.69 0 5.41-.34 8.06-1.03l179.19-46.62C269.16 449.99 304 403.8 304 351.91v-128c0-17.6-14.4-32-32-32zm346.12 161.73L528 323.6v-80.23c0-18.98-5.56-37.39-16.12-53.23L394.62 14.25c-.18-.27-.59-.24-.79-.48-9.58-13.51-27.85-17.88-42.3-9.21-15.16 9.09-20.06 28.75-10.97 43.91l77.75 129.59c8.97 14.92 13.69 32 13.69 49.39V304c0 8.84-7.16 16-16 16s-16-7.16-16-16v-80c0-17.6-14.4-32-32-32s-32 14.4-32 32v128c0 51.89 34.84 98.08 84.75 112.34l179.19 46.62c2.66.69 5.38 1.03 8.06 1.03 23.48 0 32-21.18 32-32v-96c0-13.77-8.81-25.99-21.88-30.35z\"],\n    \"prescription\": [384, 512, [], \"f5b1\", \"M301.26 352l78.06-78.06c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0L256 306.74l-83.96-83.96C219.31 216.8 256 176.89 256 128c0-53.02-42.98-96-96-96H16C7.16 32 0 39.16 0 48v256c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-80h18.75l128 128-78.06 78.06c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0L256 397.25l78.06 78.06c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63L301.26 352zM64 96h96c17.64 0 32 14.36 32 32s-14.36 32-32 32H64V96z\"],\n    \"prescription-bottle\": [384, 512, [], \"f485\", \"M32 192h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v64zM360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24z\"],\n    \"prescription-bottle-alt\": [384, 512, [], \"f486\", \"M360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24zM32 480c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v352zm64-184c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48z\"],\n    \"print\": [512, 512, [], \"f02f\", \"M448 192V77.25c0-8.49-3.37-16.62-9.37-22.63L393.37 9.37c-6-6-14.14-9.37-22.63-9.37H96C78.33 0 64 14.33 64 32v160c-35.35 0-64 28.65-64 64v112c0 8.84 7.16 16 16 16h48v96c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-96h48c8.84 0 16-7.16 16-16V256c0-35.35-28.65-64-64-64zm-64 256H128v-96h256v96zm0-224H128V64h192v48c0 8.84 7.16 16 16 16h48v96zm48 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"procedures\": [640, 512, [], \"f487\", \"M528 224H272c-8.8 0-16 7.2-16 16v144H64V144c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v352c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48h512v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V336c0-61.9-50.1-112-112-112zM136 96h126.1l27.6 55.2c5.9 11.8 22.7 11.8 28.6 0L368 51.8 390.1 96H512c8.8 0 16-7.2 16-16s-7.2-16-16-16H409.9L382.3 8.8C376.4-3 359.6-3 353.7 8.8L304 108.2l-19.9-39.8c-1.4-2.7-4.1-4.4-7.2-4.4H136c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm24 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"project-diagram\": [640, 512, [], \"f542\", \"M384 320H256c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM192 32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v128c0 17.67 14.33 32 32 32h95.72l73.16 128.04C211.98 300.98 232.4 288 256 288h.28L192 175.51V128h224V64H192V32zM608 0H480c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32z\"],\n    \"puzzle-piece\": [576, 512, [], \"f12e\", \"M519.442 288.651c-41.519 0-59.5 31.593-82.058 31.593C377.409 320.244 432 144 432 144s-196.288 80-196.288-3.297c0-35.827 36.288-46.25 36.288-85.985C272 19.216 243.885 0 210.539 0c-34.654 0-66.366 18.891-66.366 56.346 0 41.364 31.711 59.277 31.711 81.75C175.885 207.719 0 166.758 0 166.758v333.237s178.635 41.047 178.635-28.662c0-22.473-40-40.107-40-81.471 0-37.456 29.25-56.346 63.577-56.346 33.673 0 61.788 19.216 61.788 54.717 0 39.735-36.288 50.158-36.288 85.985 0 60.803 129.675 25.73 181.23 25.73 0 0-34.725-120.101 25.827-120.101 35.962 0 46.423 36.152 86.308 36.152C556.712 416 576 387.99 576 354.443c0-34.199-18.962-65.792-56.558-65.792z\"],\n    \"qrcode\": [448, 512, [], \"f029\", \"M0 224h192V32H0v192zM64 96h64v64H64V96zm192-64v192h192V32H256zm128 128h-64V96h64v64zM0 480h192V288H0v192zm64-128h64v64H64v-64zm352-64h32v128h-96v-32h-32v96h-64V288h96v32h64v-32zm0 160h32v32h-32v-32zm-64 0h32v32h-32v-32z\"],\n    \"question\": [384, 512, [], \"f128\", \"M202.021 0C122.202 0 70.503 32.703 29.914 91.026c-7.363 10.58-5.093 25.086 5.178 32.874l43.138 32.709c10.373 7.865 25.132 6.026 33.253-4.148 25.049-31.381 43.63-49.449 82.757-49.449 30.764 0 68.816 19.799 68.816 49.631 0 22.552-18.617 34.134-48.993 51.164-35.423 19.86-82.299 44.576-82.299 106.405V320c0 13.255 10.745 24 24 24h72.471c13.255 0 24-10.745 24-24v-5.773c0-42.86 125.268-44.645 125.268-160.627C377.504 66.256 286.902 0 202.021 0zM192 373.459c-38.196 0-69.271 31.075-69.271 69.271 0 38.195 31.075 69.27 69.271 69.27s69.271-31.075 69.271-69.271-31.075-69.27-69.271-69.27z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zM262.655 90c-54.497 0-89.255 22.957-116.549 63.758-3.536 5.286-2.353 12.415 2.715 16.258l34.699 26.31c5.205 3.947 12.621 3.008 16.665-2.122 17.864-22.658 30.113-35.797 57.303-35.797 20.429 0 45.698 13.148 45.698 32.958 0 14.976-12.363 22.667-32.534 33.976C247.128 238.528 216 254.941 216 296v4c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12v-1.333c0-28.462 83.186-29.647 83.186-106.667 0-58.002-60.165-102-116.531-102zM256 338c-25.365 0-46 20.635-46 46 0 25.364 20.635 46 46 46s46-20.636 46-46c0-25.365-20.635-46-46-46z\"],\n    \"quidditch\": [640, 512, [], \"f458\", \"M256.5 216.8L343.2 326s-16.6 102.4-76.6 150.1C206.7 523.8 0 510.2 0 510.2s3.8-23.1 11-55.4l94.6-112.2c4-4.7-.9-11.6-6.6-9.5l-60.4 22.1c14.4-41.7 32.7-80 54.6-97.5 59.9-47.8 163.3-40.9 163.3-40.9zm238 135c-44 0-79.8 35.8-79.8 79.9 0 44.1 35.7 79.9 79.8 79.9 44.1 0 79.8-35.8 79.8-79.9 0-44.2-35.8-79.9-79.8-79.9zM636.5 31L616.7 6c-5.5-6.9-15.5-8-22.4-2.6L361.8 181.3l-34.1-43c-5.1-6.4-15.1-5.2-18.6 2.2l-25.3 54.6 86.7 109.2 58.8-12.4c8-1.7 11.4-11.2 6.3-17.6l-34.1-42.9L634 53.5c6.9-5.5 8-15.6 2.5-22.5z\"],\n    \"quote-left\": [512, 512, [], \"f10d\", \"M464 256h-80v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8c-88.4 0-160 71.6-160 160v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zm-288 0H96v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8C71.6 32 0 103.6 0 192v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"quote-right\": [512, 512, [], \"f10e\", \"M464 32H336c-26.5 0-48 21.5-48 48v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48zm-288 0H48C21.5 32 0 53.5 0 80v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48z\"],\n    \"quran\": [448, 512, [], \"f687\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM301.08 145.82c.6-1.21 1.76-1.82 2.92-1.82s2.32.61 2.92 1.82l11.18 22.65 25 3.63c2.67.39 3.74 3.67 1.81 5.56l-18.09 17.63 4.27 24.89c.36 2.11-1.31 3.82-3.21 3.82-.5 0-1.02-.12-1.52-.38L304 211.87l-22.36 11.75c-.5.26-1.02.38-1.52.38-1.9 0-3.57-1.71-3.21-3.82l4.27-24.89-18.09-17.63c-1.94-1.89-.87-5.17 1.81-5.56l24.99-3.63 11.19-22.65zm-57.89-69.01c13.67 0 27.26 2.49 40.38 7.41a6.775 6.775 0 1 1-2.38 13.12c-.67 0-3.09-.21-4.13-.21-52.31 0-94.86 42.55-94.86 94.86 0 52.3 42.55 94.86 94.86 94.86 1.03 0 3.48-.21 4.13-.21 3.93 0 6.8 3.14 6.8 6.78 0 2.98-1.94 5.51-4.62 6.42-13.07 4.87-26.59 7.34-40.19 7.34C179.67 307.19 128 255.51 128 192c0-63.52 51.67-115.19 115.19-115.19zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"radiation\": [496, 512, [], \"f7b9\", \"M328.2 255.8h151.6c9.1 0 16.8-7.7 16.2-16.8-5.1-75.8-44.4-142.2-102.5-184.2-7.4-5.3-17.9-2.9-22.7 4.8L290.4 188c22.6 14.3 37.8 39.2 37.8 67.8zm-37.8 67.7c-12.3 7.7-26.8 12.4-42.4 12.4-15.6 0-30-4.7-42.4-12.4L125.2 452c-4.8 7.7-2.4 18.1 5.6 22.4C165.7 493.2 205.6 504 248 504s82.3-10.8 117.2-29.6c8-4.3 10.4-14.8 5.6-22.4l-80.4-128.5zM248 303.8c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm-231.8-48h151.6c0-28.6 15.2-53.5 37.8-67.7L125.2 59.7c-4.8-7.7-15.3-10.2-22.7-4.8C44.4 96.9 5.1 163.3 0 239.1c-.6 9 7.1 16.7 16.2 16.7z\"],\n    \"radiation-alt\": [496, 512, [], \"f7ba\", \"M312 256h79.1c9.2 0 16.9-7.7 16-16.8-4.6-43.6-27-81.8-59.5-107.8-7.6-6.1-18.8-4.5-24 3.8L281.9 202c18 11.2 30.1 31.2 30.1 54zm-97.8 54.1L172.4 377c-4.9 7.8-2.4 18.4 5.8 22.5 21.1 10.4 44.7 16.5 69.8 16.5s48.7-6.1 69.9-16.5c8.2-4.1 10.6-14.7 5.8-22.5l-41.8-66.9c-9.8 6.2-21.4 9.9-33.8 9.9s-24.1-3.7-33.9-9.9zM104.9 256H184c0-22.8 12.1-42.8 30.2-54.1l-41.7-66.8c-5.2-8.3-16.4-9.9-24-3.8-32.6 26-54.9 64.2-59.5 107.8-1.1 9.2 6.7 16.9 15.9 16.9zM248 504c137 0 248-111 248-248S385 8 248 8 0 119 0 256s111 248 248 248zm0-432c101.5 0 184 82.5 184 184s-82.5 184-184 184S64 357.5 64 256 146.5 72 248 72zm0 216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"rainbow\": [576, 512, [], \"f75b\", \"M268.3 32.7C115.4 42.9 0 176.9 0 330.2V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C64 186.8 180.9 80.3 317.5 97.9 430.4 112.4 512 214 512 327.8V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-165.3-140-298.6-307.7-287.3zm-5.6 96.9C166 142 96 229.1 96 326.7V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-74.8 64.5-134.8 140.8-127.4 66.5 6.5 115.2 66.2 115.2 133.1V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-114.2-100.2-205.4-217.3-190.4zm6.2 96.3c-45.6 8.9-76.9 51.5-76.9 97.9V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-17.6 14.3-32 32-32s32 14.4 32 32v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-59.2-53.8-106-115.1-94.1z\"],\n    \"random\": [512, 512, [], \"f074\", \"M504.971 359.029c9.373 9.373 9.373 24.569 0 33.941l-80 79.984c-15.01 15.01-40.971 4.49-40.971-16.971V416h-58.785a12.004 12.004 0 0 1-8.773-3.812l-70.556-75.596 53.333-57.143L352 336h32v-39.981c0-21.438 25.943-31.998 40.971-16.971l80 79.981zM12 176h84l52.781 56.551 53.333-57.143-70.556-75.596A11.999 11.999 0 0 0 122.785 96H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12zm372 0v39.984c0 21.46 25.961 31.98 40.971 16.971l80-79.984c9.373-9.373 9.373-24.569 0-33.941l-80-79.981C409.943 24.021 384 34.582 384 56.019V96h-58.785a12.004 12.004 0 0 0-8.773 3.812L96 336H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h110.785c3.326 0 6.503-1.381 8.773-3.812L352 176h32z\"],\n    \"receipt\": [384, 512, [], \"f543\", \"M358.4 3.2L320 48 265.6 3.2a15.9 15.9 0 0 0-19.2 0L192 48 137.6 3.2a15.9 15.9 0 0 0-19.2 0L64 48 25.6 3.2C15-4.7 0 2.8 0 16v480c0 13.2 15 20.7 25.6 12.8L64 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L192 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L320 464l38.4 44.8c10.5 7.9 25.6.4 25.6-12.8V16c0-13.2-15-20.7-25.6-12.8zM320 360c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16z\"],\n    \"recycle\": [512, 512, [], \"f1b8\", \"M184.561 261.903c3.232 13.997-12.123 24.635-24.068 17.168l-40.736-25.455-50.867 81.402C55.606 356.273 70.96 384 96.012 384H148c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12H96.115c-75.334 0-121.302-83.048-81.408-146.88l50.822-81.388-40.725-25.448c-12.081-7.547-8.966-25.961 4.879-29.158l110.237-25.45c8.611-1.988 17.201 3.381 19.189 11.99l25.452 110.237zm98.561-182.915l41.289 66.076-40.74 25.457c-12.051 7.528-9 25.953 4.879 29.158l110.237 25.45c8.672 1.999 17.215-3.438 19.189-11.99l25.45-110.237c3.197-13.844-11.99-24.719-24.068-17.168l-40.687 25.424-41.263-66.082c-37.521-60.033-125.209-60.171-162.816 0l-17.963 28.766c-3.51 5.62-1.8 13.021 3.82 16.533l33.919 21.195c5.62 3.512 13.024 1.803 16.536-3.817l17.961-28.743c12.712-20.341 41.973-19.676 54.257-.022zM497.288 301.12l-27.515-44.065c-3.511-5.623-10.916-7.334-16.538-3.821l-33.861 21.159c-5.62 3.512-7.33 10.915-3.818 16.536l27.564 44.112c13.257 21.211-2.057 48.96-27.136 48.96H320V336.02c0-14.213-17.242-21.383-27.313-11.313l-80 79.981c-6.249 6.248-6.249 16.379 0 22.627l80 79.989C302.689 517.308 320 510.3 320 495.989V448h95.88c75.274 0 121.335-82.997 81.408-146.88z\"],\n    \"redo\": [512, 512, [], \"f01e\", \"M500.33 0h-47.41a12 12 0 0 0-12 12.57l4 82.76A247.42 247.42 0 0 0 256 8C119.34 8 7.9 119.53 8 256.19 8.1 393.07 119.1 504 256 504a247.1 247.1 0 0 0 166.18-63.91 12 12 0 0 0 .48-17.43l-34-34a12 12 0 0 0-16.38-.55A176 176 0 1 1 402.1 157.8l-101.53-4.87a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12h200.33a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12z\"],\n    \"redo-alt\": [512, 512, [], \"f2f9\", \"M256.455 8c66.269.119 126.437 26.233 170.859 68.685l35.715-35.715C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.75c-30.864-28.899-70.801-44.907-113.23-45.273-92.398-.798-170.283 73.977-169.484 169.442C88.764 348.009 162.184 424 256 424c41.127 0 79.997-14.678 110.629-41.556 4.743-4.161 11.906-3.908 16.368.553l39.662 39.662c4.872 4.872 4.631 12.815-.482 17.433C378.202 479.813 319.926 504 256 504 119.034 504 8.001 392.967 8 256.002 7.999 119.193 119.646 7.755 256.455 8z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M285.363 207.475c0 18.6-9.831 28.431-28.431 28.431h-29.876v-56.14h23.378c28.668 0 34.929 8.773 34.929 27.709zM504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM363.411 360.414c-46.729-84.825-43.299-78.636-44.702-80.98 23.432-15.172 37.945-42.979 37.945-74.486 0-54.244-31.5-89.252-105.498-89.252h-70.667c-13.255 0-24 10.745-24 24V372c0 13.255 10.745 24 24 24h22.567c13.255 0 24-10.745 24-24v-71.663h25.556l44.129 82.937a24.001 24.001 0 0 0 21.188 12.727h24.464c18.261-.001 29.829-19.591 21.018-35.587z\"],\n    \"remove-format\": [640, 512, [], \"f87d\", \"M336 416h-11.17l9.26-27.77L267 336.4 240.49 416H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm297.82 42.1L377 259.59 426.17 112H544v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16H176a16 16 0 0 0-16 16v43.9L45.46 3.38A16 16 0 0 0 23 6.19L3.37 31.46a16 16 0 0 0 2.81 22.45l588.36 454.72a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zM309.91 207.76L224 141.36V112h117.83z\"],\n    \"reply\": [512, 512, [], \"f3e5\", \"M8.309 189.836L184.313 37.851C199.719 24.546 224 35.347 224 56.015v80.053c160.629 1.839 288 34.032 288 186.258 0 61.441-39.581 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 45.344-145.012-21.507-183.51-176.59-185.742V360c0 20.7-24.3 31.453-39.687 18.164l-176.004-152c-11.071-9.562-11.086-26.753 0-36.328z\"],\n    \"reply-all\": [576, 512, [], \"f122\", \"M136.309 189.836L312.313 37.851C327.72 24.546 352 35.348 352 56.015v82.763c129.182 10.231 224 52.212 224 183.548 0 61.441-39.582 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 38.512-123.162-3.922-169.482-112.59-182.015v84.175c0 20.701-24.3 31.453-39.687 18.164L136.309 226.164c-11.071-9.561-11.086-26.753 0-36.328zm-128 36.328L184.313 378.15C199.7 391.439 224 380.687 224 359.986v-15.818l-108.606-93.785A55.96 55.96 0 0 1 96 207.998a55.953 55.953 0 0 1 19.393-42.38L224 71.832V56.015c0-20.667-24.28-31.469-39.687-18.164L8.309 189.836c-11.086 9.575-11.071 26.767 0 36.328z\"],\n    \"republican\": [640, 512, [], \"f75e\", \"M544 192c0-88.4-71.6-160-160-160H160C71.6 32 0 103.6 0 192v64h544v-64zm-367.7-21.6l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L128 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L272 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L416 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zM624 320h-32c-8.8 0-16 7.2-16 16v64c0 8.8-7.2 16-16 16s-16-7.2-16-16V288H0v176c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16v-80h192v80c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16V352h32v43.3c0 41.8 30 80.1 71.6 84.3 47.8 4.9 88.4-32.7 88.4-79.6v-64c0-8.8-7.2-16-16-16z\"],\n    \"restroom\": [640, 512, [], \"f7bd\", \"M128 128c35.3 0 64-28.7 64-64S163.3 0 128 0 64 28.7 64 64s28.7 64 64 64zm384 0c35.3 0 64-28.7 64-64S547.3 0 512 0s-64 28.7-64 64 28.7 64 64 64zm127.3 226.5l-45.6-185.8c-3.3-13.5-15.5-23-29.8-24.2-15 9.7-32.8 15.5-52 15.5-19.2 0-37-5.8-52-15.5-14.3 1.2-26.5 10.7-29.8 24.2l-45.6 185.8C381 369.6 393 384 409.2 384H464v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V384h54.8c16.2 0 28.2-14.4 24.5-29.5zM336 0h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zM180.1 144.4c-15 9.8-32.9 15.6-52.1 15.6-19.2 0-37.1-5.8-52.1-15.6C51.3 146.5 32 166.9 32 192v136c0 13.3 10.7 24 24 24h8v136c0 13.3 10.7 24 24 24h80c13.3 0 24-10.7 24-24V352h8c13.3 0 24-10.7 24-24V192c0-25.1-19.3-45.5-43.9-47.6z\"],\n    \"retweet\": [640, 512, [], \"f079\", \"M629.657 343.598L528.971 444.284c-9.373 9.372-24.568 9.372-33.941 0L394.343 343.598c-9.373-9.373-9.373-24.569 0-33.941l10.823-10.823c9.562-9.562 25.133-9.34 34.419.492L480 342.118V160H292.451a24.005 24.005 0 0 1-16.971-7.029l-16-16C244.361 121.851 255.069 96 276.451 96H520c13.255 0 24 10.745 24 24v222.118l40.416-42.792c9.285-9.831 24.856-10.054 34.419-.492l10.823 10.823c9.372 9.372 9.372 24.569-.001 33.941zm-265.138 15.431A23.999 23.999 0 0 0 347.548 352H160V169.881l40.416 42.792c9.286 9.831 24.856 10.054 34.419.491l10.822-10.822c9.373-9.373 9.373-24.569 0-33.941L144.971 67.716c-9.373-9.373-24.569-9.373-33.941 0L10.343 168.402c-9.373 9.373-9.373 24.569 0 33.941l10.822 10.822c9.562 9.562 25.133 9.34 34.419-.491L96 169.881V392c0 13.255 10.745 24 24 24h243.549c21.382 0 32.09-25.851 16.971-40.971l-16.001-16z\"],\n    \"ribbon\": [448, 512, [], \"f4d6\", \"M6.1 444.3c-9.6 10.8-7.5 27.6 4.5 35.7l68.8 27.9c9.9 6.7 23.3 5 31.3-3.8l91.8-101.9-79.2-87.9-117.2 130zm435.8 0s-292-324.6-295.4-330.1c15.4-8.4 40.2-17.9 77.5-17.9s62.1 9.5 77.5 17.9c-3.3 5.6-56 64.6-56 64.6l79.1 87.7 34.2-38c28.7-31.9 33.3-78.6 11.4-115.5l-43.7-73.5c-4.3-7.2-9.9-13.3-16.8-18-40.7-27.6-127.4-29.7-171.4 0-6.9 4.7-12.5 10.8-16.8 18l-43.6 73.2c-1.5 2.5-37.1 62.2 11.5 116L337.5 504c8 8.9 21.4 10.5 31.3 3.8l68.8-27.9c11.9-8 14-24.8 4.3-35.6z\"],\n    \"ring\": [512, 512, [], \"f70b\", \"M256 64C110.06 64 0 125.91 0 208v98.13C0 384.48 114.62 448 256 448s256-63.52 256-141.87V208c0-82.09-110.06-144-256-144zm0 64c106.04 0 192 35.82 192 80 0 9.26-3.97 18.12-10.91 26.39C392.15 208.21 328.23 192 256 192s-136.15 16.21-181.09 42.39C67.97 226.12 64 217.26 64 208c0-44.18 85.96-80 192-80zM120.43 264.64C155.04 249.93 201.64 240 256 240s100.96 9.93 135.57 24.64C356.84 279.07 308.93 288 256 288s-100.84-8.93-135.57-23.36z\"],\n    \"road\": [576, 512, [], \"f018\", \"M573.19 402.67l-139.79-320C428.43 71.29 417.6 64 405.68 64h-97.59l2.45 23.16c.5 4.72-3.21 8.84-7.96 8.84h-29.16c-4.75 0-8.46-4.12-7.96-8.84L267.91 64h-97.59c-11.93 0-22.76 7.29-27.73 18.67L2.8 402.67C-6.45 423.86 8.31 448 30.54 448h196.84l10.31-97.68c.86-8.14 7.72-14.32 15.91-14.32h68.8c8.19 0 15.05 6.18 15.91 14.32L348.62 448h196.84c22.23 0 36.99-24.14 27.73-45.33zM260.4 135.16a8 8 0 0 1 7.96-7.16h39.29c4.09 0 7.53 3.09 7.96 7.16l4.6 43.58c.75 7.09-4.81 13.26-11.93 13.26h-40.54c-7.13 0-12.68-6.17-11.93-13.26l4.59-43.58zM315.64 304h-55.29c-9.5 0-16.91-8.23-15.91-17.68l5.07-48c.86-8.14 7.72-14.32 15.91-14.32h45.15c8.19 0 15.05 6.18 15.91 14.32l5.07 48c1 9.45-6.41 17.68-15.91 17.68z\"],\n    \"robot\": [640, 512, [], \"f544\", \"M0 256v128c0 17.7 14.3 32 32 32h32V224H32c-17.7 0-32 14.3-32 32zM464 96H352V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v64H176c-44.2 0-80 35.8-80 80v272c0 35.3 28.7 64 64 64h320c35.3 0 64-28.7 64-64V176c0-44.2-35.8-80-80-80zM256 416h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm128 120h-64v-32h64v32zm96 0h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm192-72h-32v192h32c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32z\"],\n    \"rocket\": [512, 512, [], \"f135\", \"M505.05 19.1a15.89 15.89 0 0 0-12.2-12.2C460.65 0 435.46 0 410.36 0c-103.2 0-165.1 55.2-211.29 128H94.87A48 48 0 0 0 52 154.49l-49.42 98.8A24 24 0 0 0 24.07 288h103.77l-22.47 22.47a32 32 0 0 0 0 45.25l50.9 50.91a32 32 0 0 0 45.26 0L224 384.16V488a24 24 0 0 0 34.7 21.49l98.7-49.39a47.91 47.91 0 0 0 26.5-42.9V312.79c72.59-46.3 128-108.4 128-211.09.1-25.2.1-50.4-6.85-82.6zM384 168a40 40 0 1 1 40-40 40 40 0 0 1-40 40z\"],\n    \"route\": [512, 512, [], \"f4d7\", \"M416 320h-96c-17.6 0-32-14.4-32-32s14.4-32 32-32h96s96-107 96-160-43-96-96-96-96 43-96 96c0 25.5 22.2 63.4 45.3 96H320c-52.9 0-96 43.1-96 96s43.1 96 96 96h96c17.6 0 32 14.4 32 32s-14.4 32-32 32H185.5c-16 24.8-33.8 47.7-47.3 64H416c52.9 0 96-43.1 96-96s-43.1-96-96-96zm0-256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM96 256c-53 0-96 43-96 96s96 160 96 160 96-107 96-160-43-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"rss\": [448, 512, [], \"f09e\", \"M128.081 415.959c0 35.369-28.672 64.041-64.041 64.041S0 451.328 0 415.959s28.672-64.041 64.041-64.041 64.04 28.673 64.04 64.041zm175.66 47.25c-8.354-154.6-132.185-278.587-286.95-286.95C7.656 175.765 0 183.105 0 192.253v48.069c0 8.415 6.49 15.472 14.887 16.018 111.832 7.284 201.473 96.702 208.772 208.772.547 8.397 7.604 14.887 16.018 14.887h48.069c9.149.001 16.489-7.655 15.995-16.79zm144.249.288C439.596 229.677 251.465 40.445 16.503 32.01 7.473 31.686 0 38.981 0 48.016v48.068c0 8.625 6.835 15.645 15.453 15.999 191.179 7.839 344.627 161.316 352.465 352.465.353 8.618 7.373 15.453 15.999 15.453h48.068c9.034-.001 16.329-7.474 16.005-16.504z\"],\n    \"rss-square\": [448, 512, [], \"f143\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM112 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm157.533 0h-34.335c-6.011 0-11.051-4.636-11.442-10.634-5.214-80.05-69.243-143.92-149.123-149.123-5.997-.39-10.633-5.431-10.633-11.441v-34.335c0-6.535 5.468-11.777 11.994-11.425 110.546 5.974 198.997 94.536 204.964 204.964.352 6.526-4.89 11.994-11.425 11.994zm103.027 0h-34.334c-6.161 0-11.175-4.882-11.427-11.038-5.598-136.535-115.204-246.161-251.76-251.76C68.882 152.949 64 147.935 64 141.774V107.44c0-6.454 5.338-11.664 11.787-11.432 167.83 6.025 302.21 141.191 308.205 308.205.232 6.449-4.978 11.787-11.432 11.787z\"],\n    \"ruble-sign\": [384, 512, [], \"f158\", \"M239.36 320C324.48 320 384 260.542 384 175.071S324.48 32 239.36 32H76c-6.627 0-12 5.373-12 12v206.632H12c-6.627 0-12 5.373-12 12V308c0 6.627 5.373 12 12 12h52v32H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v52c0 6.627 5.373 12 12 12h58.56c6.627 0 12-5.373 12-12v-52H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H146.56v-32h92.8zm-92.8-219.252h78.72c46.72 0 74.88 29.11 74.88 74.323 0 45.832-28.16 75.561-76.16 75.561h-77.44V100.748z\"],\n    \"ruler\": [640, 512, [], \"f545\", \"M635.7 167.2L556.1 31.7c-8.8-15-28.3-20.1-43.5-11.5l-69 39.1L503.3 161c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L416 75l-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L333.2 122 278 153.3 337.8 255c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-59.7-101.7-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-27.9-47.5-55.2 31.3 59.7 101.7c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L84.9 262.9l-69 39.1C.7 310.7-4.6 329.8 4.2 344.8l79.6 135.6c8.8 15 28.3 20.1 43.5 11.5L624.1 210c15.2-8.6 20.4-27.8 11.6-42.8z\"],\n    \"ruler-combined\": [512, 512, [], \"f546\", \"M160 288h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56v-64h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56V96h-56c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8h56V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 2.77.91 5.24 1.57 7.8L160 329.38V288zm320 64h-32v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-41.37L24.2 510.43c2.56.66 5.04 1.57 7.8 1.57h448c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"ruler-horizontal\": [576, 512, [], \"f547\", \"M544 128h-48v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8H88c-4.42 0-8-3.58-8-8v-88H32c-17.67 0-32 14.33-32 32v192c0 17.67 14.33 32 32 32h512c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32z\"],\n    \"ruler-vertical\": [256, 512, [], \"f548\", \"M168 416c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 17.67 14.33 32 32 32h192c17.67 0 32-14.33 32-32v-64h-88z\"],\n    \"running\": [416, 512, [], \"f70c\", \"M272 96c26.51 0 48-21.49 48-48S298.51 0 272 0s-48 21.49-48 48 21.49 48 48 48zM113.69 317.47l-14.8 34.52H32c-17.67 0-32 14.33-32 32s14.33 32 32 32h77.45c19.25 0 36.58-11.44 44.11-29.09l8.79-20.52-10.67-6.3c-17.32-10.23-30.06-25.37-37.99-42.61zM384 223.99h-44.03l-26.06-53.25c-12.5-25.55-35.45-44.23-61.78-50.94l-71.08-21.14c-28.3-6.8-57.77-.55-80.84 17.14l-39.67 30.41c-14.03 10.75-16.69 30.83-5.92 44.86s30.84 16.66 44.86 5.92l39.69-30.41c7.67-5.89 17.44-8 25.27-6.14l14.7 4.37-37.46 87.39c-12.62 29.48-1.31 64.01 26.3 80.31l84.98 50.17-27.47 87.73c-5.28 16.86 4.11 34.81 20.97 40.09 3.19 1 6.41 1.48 9.58 1.48 13.61 0 26.23-8.77 30.52-22.45l31.64-101.06c5.91-20.77-2.89-43.08-21.64-54.39l-61.24-36.14 31.31-78.28 20.27 41.43c8 16.34 24.92 26.89 43.11 26.89H384c17.67 0 32-14.33 32-32s-14.33-31.99-32-31.99z\"],\n    \"rupee-sign\": [320, 512, [], \"f156\", \"M308 96c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v44.748c0 6.627 5.373 12 12 12h85.28c27.308 0 48.261 9.958 60.97 27.252H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h158.757c-6.217 36.086-32.961 58.632-74.757 58.632H12c-6.627 0-12 5.373-12 12v53.012c0 3.349 1.4 6.546 3.861 8.818l165.052 152.356a12.001 12.001 0 0 0 8.139 3.182h82.562c10.924 0 16.166-13.408 8.139-20.818L116.871 319.906c76.499-2.34 131.144-53.395 138.318-127.906H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-58.69c-3.486-11.541-8.28-22.246-14.252-32H308z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256c0 90.1 48.2 168.7 120 212.1V288c0-8.8 7.2-16 16-16s16 7.2 16 16v196.7c29.5 12.4 62 19.3 96 19.3s66.5-6.9 96-19.3V288c0-8.8 7.2-16 16-16s16 7.2 16 16v180.1C447.8 424.7 496 346 496 256 496 119 385 8 248 8zm-65.5 216.5c-14.8-13.2-46.2-13.2-61 0L112 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c.8 5-1.7 10-6.1 12.4-5.8 3.1-11.2.7-13.7-1.6l-9.7-8.5zM248 416c-26.5 0-48-28.7-48-64s21.5-64 48-64 48 28.7 48 64-21.5 64-48 64zm149.8-181.5c-5.8 3.1-11.2.7-13.7-1.6l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S400 197 404 222.2c.6 4.9-1.8 9.9-6.2 12.3z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM152 416c-26.5 0-48-21-48-47 0-20 28.5-60.4 41.6-77.8 3.2-4.3 9.6-4.3 12.8 0C171.5 308.6 200 349 200 369c0 26-21.5 47-48 47zm16-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm170.2 154.2C315.8 367.4 282.9 352 248 352c-21.2 0-21.2-32 0-32 44.4 0 86.3 19.6 114.7 53.8 13.8 16.4-11.2 36.5-24.5 20.4z\"],\n    \"satellite\": [512, 512, [], \"f7bf\", \"M502.7 265l-80.3-80.4 47.8-47.9c13.1-13.1 13.1-34.4 0-47.5l-47.5-47.5c-13.1-13.1-34.4-13.1-47.5 0l-47.8 47.9-80.3-80.3C240.8 3.1 232.7 0 224.5 0S208.2 3.1 202 9.3L105.3 106c-12.4 12.4-12.4 32.6 0 45.1l80.3 80.4-9.8 9.8C122.1 217 59.6 218.6 7.3 246.7c-8.5 4.6-9.6 16.4-2.8 23.2L112 377.4l-17.8 17.8c-2.6-.7-5-1.6-7.8-1.6-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32c0-2.8-.9-5.2-1.6-7.8l17.8-17.8 107.5 107.5c6.8 6.8 18.7 5.7 23.2-2.8 28.1-52.3 29.7-114.8 5.4-168.5l9.9-9.9 80.3 80.4c6.2 6.2 14.4 9.3 22.5 9.3s16.3-3.1 22.5-9.3l96.7-96.7c12.5-12.4 12.5-32.6.1-45zm-352-136.5l73.8-73.8 68.9 68.9-73.8 73.8-68.9-68.9zm232.8 232.8l-68.9-68.9 73.8-73.8 68.9 68.9-73.8 73.8z\"],\n    \"satellite-dish\": [512, 512, [], \"f7c0\", \"M188.8 345.9l27.4-27.4c2.6.7 5 1.6 7.8 1.6 17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32c0 2.8.9 5.2 1.6 7.8l-27.4 27.4L49.4 206.5c-7.3-7.3-20.1-6.1-25 3-41.8 77.8-29.9 176.7 35.7 242.3 65.6 65.6 164.6 77.5 242.3 35.7 9.2-4.9 10.4-17.7 3-25L188.8 345.9zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM224 416c-35.346 0-64-28.654-64-64 0-35.346 28.654-64 64-64s64 28.654 64 64c0 35.346-28.654 64-64 64zm96-304.52V212c0 6.627-5.373 12-12 12H76c-6.627 0-12-5.373-12-12V108c0-6.627 5.373-12 12-12h228.52c3.183 0 6.235 1.264 8.485 3.515l3.48 3.48A11.996 11.996 0 0 1 320 111.48z\"],\n    \"school\": [640, 512, [], \"f549\", \"M0 224v272c0 8.84 7.16 16 16 16h80V192H32c-17.67 0-32 14.33-32 32zm360-48h-24v-40c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v64c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zm137.75-63.96l-160-106.67a32.02 32.02 0 0 0-35.5 0l-160 106.67A32.002 32.002 0 0 0 128 138.66V512h128V368c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v144h128V138.67c0-10.7-5.35-20.7-14.25-26.63zM320 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm288-64h-64v320h80c8.84 0 16-7.16 16-16V224c0-17.67-14.33-32-32-32z\"],\n    \"screwdriver\": [512, 512, [], \"f54a\", \"M448 0L320 96v62.06l-83.03 83.03c6.79 4.25 13.27 9.06 19.07 14.87 5.8 5.8 10.62 12.28 14.87 19.07L353.94 192H416l96-128-64-64zM128 278.59L10.92 395.67c-14.55 14.55-14.55 38.15 0 52.71l52.7 52.7c14.56 14.56 38.15 14.56 52.71 0L233.41 384c29.11-29.11 29.11-76.3 0-105.41s-76.3-29.11-105.41 0z\"],\n    \"scroll\": [640, 512, [], \"f70e\", \"M48 0C21.53 0 0 21.53 0 48v64c0 8.84 7.16 16 16 16h80V48C96 21.53 74.47 0 48 0zm208 412.57V352h288V96c0-52.94-43.06-96-96-96H111.59C121.74 13.41 128 29.92 128 48v368c0 38.87 34.65 69.65 74.75 63.12C234.22 474 256 444.46 256 412.57zM288 384v32c0 52.93-43.06 96-96 96h336c61.86 0 112-50.14 112-112 0-8.84-7.16-16-16-16H288z\"],\n    \"sd-card\": [384, 512, [], \"f7c2\", \"M320 0H128L0 128v320c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zM160 160h-48V64h48v96zm80 0h-48V64h48v96zm80 0h-48V64h48v96z\"],\n    \"search\": [512, 512, [], \"f002\", \"M505 442.7L405.3 343c-4.5-4.5-10.6-7-17-7H372c27.6-35.3 44-79.7 44-128C416 93.1 322.9 0 208 0S0 93.1 0 208s93.1 208 208 208c48.3 0 92.7-16.4 128-44v16.3c0 6.4 2.5 12.5 7 17l99.7 99.7c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.6.1-34zM208 336c-70.7 0-128-57.2-128-128 0-70.7 57.2-128 128-128 70.7 0 128 57.2 128 128 0 70.7-57.2 128-128 128z\"],\n    \"search-dollar\": [512, 512, [], \"f688\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm27.11-152.54l-45.01-13.5c-5.16-1.55-8.77-6.78-8.77-12.73 0-7.27 5.3-13.19 11.8-13.19h28.11c4.56 0 8.96 1.29 12.82 3.72 3.24 2.03 7.36 1.91 10.13-.73l11.75-11.21c3.53-3.37 3.33-9.21-.57-12.14-9.1-6.83-20.08-10.77-31.37-11.35V112c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v16.12c-23.63.63-42.68 20.55-42.68 45.07 0 19.97 12.99 37.81 31.58 43.39l45.01 13.5c5.16 1.55 8.77 6.78 8.77 12.73 0 7.27-5.3 13.19-11.8 13.19h-28.1c-4.56 0-8.96-1.29-12.82-3.72-3.24-2.03-7.36-1.91-10.13.73l-11.75 11.21c-3.53 3.37-3.33 9.21.57 12.14 9.1 6.83 20.08 10.77 31.37 11.35V304c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-16.12c23.63-.63 42.68-20.54 42.68-45.07 0-19.97-12.99-37.81-31.59-43.39z\"],\n    \"search-location\": [512, 512, [], \"f689\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm.02-239.96c-40.78 0-73.84 33.05-73.84 73.83 0 32.96 48.26 93.05 66.75 114.86a9.24 9.24 0 0 0 14.18 0c18.49-21.81 66.75-81.89 66.75-114.86 0-40.78-33.06-73.83-73.84-73.83zm0 96c-13.26 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"search-minus\": [512, 512, [], \"f010\", \"M304 192v32c0 6.6-5.4 12-12 12H124c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"search-plus\": [512, 512, [], \"f00e\", \"M304 192v32c0 6.6-5.4 12-12 12h-56v56c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-56h-56c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h56v-56c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v56h56c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"seedling\": [512, 512, [], \"f4d8\", \"M64 96H0c0 123.7 100.3 224 224 224v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C288 196.3 187.7 96 64 96zm384-64c-84.2 0-157.4 46.5-195.7 115.2 27.7 30.2 48.2 66.9 59 107.6C424 243.1 512 147.9 512 32h-64z\"],\n    \"server\": [512, 512, [], \"f233\", \"M480 160H32c-17.673 0-32-14.327-32-32V64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24z\"],\n    \"shapes\": [512, 512, [], \"f61f\", \"M512 320v160c0 17.67-14.33 32-32 32H320c-17.67 0-32-14.33-32-32V320c0-17.67 14.33-32 32-32h160c17.67 0 32 14.33 32 32zm-384-64C57.31 256 0 313.31 0 384s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm351.03-32c25.34 0 41.18-26.67 28.51-48L412.51 16c-12.67-21.33-44.35-21.33-57.02 0l-95.03 160c-12.67 21.33 3.17 48 28.51 48h190.06z\"],\n    \"share\": [512, 512, [], \"f064\", \"M503.691 189.836L327.687 37.851C312.281 24.546 288 35.347 288 56.015v80.053C127.371 137.907 0 170.1 0 322.326c0 61.441 39.581 122.309 83.333 154.132 13.653 9.931 33.111-2.533 28.077-18.631C66.066 312.814 132.917 274.316 288 272.085V360c0 20.7 24.3 31.453 39.687 18.164l176.004-152c11.071-9.562 11.086-26.753 0-36.328z\"],\n    \"share-alt\": [448, 512, [], \"f1e0\", \"M352 320c-22.608 0-43.387 7.819-59.79 20.895l-102.486-64.054a96.551 96.551 0 0 0 0-41.683l102.486-64.054C308.613 184.181 329.392 192 352 192c53.019 0 96-42.981 96-96S405.019 0 352 0s-96 42.981-96 96c0 7.158.79 14.13 2.276 20.841L155.79 180.895C139.387 167.819 118.608 160 96 160c-53.019 0-96 42.981-96 96s42.981 96 96 96c22.608 0 43.387-7.819 59.79-20.895l102.486 64.054A96.301 96.301 0 0 0 256 416c0 53.019 42.981 96 96 96s96-42.981 96-96-42.981-96-96-96z\"],\n    \"share-alt-square\": [448, 512, [], \"f1e1\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zM304 296c-14.562 0-27.823 5.561-37.783 14.671l-67.958-40.775a56.339 56.339 0 0 0 0-27.793l67.958-40.775C276.177 210.439 289.438 216 304 216c30.928 0 56-25.072 56-56s-25.072-56-56-56-56 25.072-56 56c0 4.797.605 9.453 1.74 13.897l-67.958 40.775C171.823 205.561 158.562 200 144 200c-30.928 0-56 25.072-56 56s25.072 56 56 56c14.562 0 27.823-5.561 37.783-14.671l67.958 40.775a56.088 56.088 0 0 0-1.74 13.897c0 30.928 25.072 56 56 56s56-25.072 56-56C360 321.072 334.928 296 304 296z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M568.482 177.448L424.479 313.433C409.3 327.768 384 317.14 384 295.985v-71.963c-144.575.97-205.566 35.113-164.775 171.353 4.483 14.973-12.846 26.567-25.006 17.33C155.252 383.105 120 326.488 120 269.339c0-143.937 117.599-172.5 264-173.312V24.012c0-21.174 25.317-31.768 40.479-17.448l144.003 135.988c10.02 9.463 10.028 25.425 0 34.896zM384 379.128V448H64V128h50.916a11.99 11.99 0 0 0 8.648-3.693c14.953-15.568 32.237-27.89 51.014-37.676C185.708 80.83 181.584 64 169.033 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48v-88.806c0-8.288-8.197-14.066-16.011-11.302a71.83 71.83 0 0 1-34.189 3.377c-7.27-1.046-13.8 4.514-13.8 11.859z\"],\n    \"shekel-sign\": [448, 512, [], \"f20b\", \"M248 168v168c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V168c0-75.11-60.89-136-136-136H24C10.75 32 0 42.74 0 56v408c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112h112c30.93 0 56 25.07 56 56zM432 32h-48c-8.84 0-16 7.16-16 16v296c0 30.93-25.07 56-56 56H200V176c0-8.84-7.16-16-16-16h-48c-8.84 0-16 7.16-16 16v280c0 13.25 10.75 24 24 24h168c75.11 0 136-60.89 136-136V48c0-8.84-7.16-16-16-16z\"],\n    \"shield-alt\": [512, 512, [], \"f3ed\", \"M466.5 83.7l-192-80a48.15 48.15 0 0 0-36.9 0l-192 80C27.7 91.1 16 108.6 16 128c0 198.5 114.5 335.7 221.5 380.3 11.8 4.9 25.1 4.9 36.9 0C360.1 472.6 496 349.3 496 128c0-19.4-11.7-36.9-29.5-44.3zM256.1 446.3l-.1-381 175.9 73.3c-3.3 151.4-82.1 261.1-175.8 307.7z\"],\n    \"ship\": [640, 512, [], \"f21a\", \"M496.616 372.639l70.012-70.012c16.899-16.9 9.942-45.771-12.836-53.092L512 236.102V96c0-17.673-14.327-32-32-32h-64V24c0-13.255-10.745-24-24-24H248c-13.255 0-24 10.745-24 24v40h-64c-17.673 0-32 14.327-32 32v140.102l-41.792 13.433c-22.753 7.313-29.754 36.173-12.836 53.092l70.012 70.012C125.828 416.287 85.587 448 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24 61.023 0 107.499-20.61 143.258-59.396C181.677 487.432 216.021 512 256 512h128c39.979 0 74.323-24.568 88.742-59.396C508.495 491.384 554.968 512 616 512c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24-60.817 0-101.542-31.001-119.384-75.361zM192 128h256v87.531l-118.208-37.995a31.995 31.995 0 0 0-19.584 0L192 215.531V128z\"],\n    \"shipping-fast\": [640, 512, [], \"f48b\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H112C85.5 0 64 21.5 64 48v48H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h272c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H40c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H64v128c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"shoe-prints\": [640, 512, [], \"f54b\", \"M192 160h32V32h-32c-35.35 0-64 28.65-64 64s28.65 64 64 64zM0 416c0 35.35 28.65 64 64 64h32V352H64c-35.35 0-64 28.65-64 64zm337.46-128c-34.91 0-76.16 13.12-104.73 32-24.79 16.38-44.52 32-104.73 32v128l57.53 15.97c26.21 7.28 53.01 13.12 80.31 15.05 32.69 2.31 65.6.67 97.58-6.2C472.9 481.3 512 429.22 512 384c0-64-84.18-96-174.54-96zM491.42 7.19C459.44.32 426.53-1.33 393.84.99c-27.3 1.93-54.1 7.77-80.31 15.04L256 32v128c60.2 0 79.94 15.62 104.73 32 28.57 18.88 69.82 32 104.73 32C555.82 224 640 192 640 128c0-45.22-39.1-97.3-148.58-120.81z\"],\n    \"shopping-bag\": [448, 512, [], \"f290\", \"M352 160v-32C352 57.42 294.579 0 224 0 153.42 0 96 57.42 96 128v32H0v272c0 44.183 35.817 80 80 80h288c44.183 0 80-35.817 80-80V160h-96zm-192-32c0-35.29 28.71-64 64-64s64 28.71 64 64v32H160v-32zm160 120c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm-192 0c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24z\"],\n    \"shopping-basket\": [576, 512, [], \"f291\", \"M576 216v16c0 13.255-10.745 24-24 24h-8l-26.113 182.788C514.509 462.435 494.257 480 470.37 480H105.63c-23.887 0-44.139-17.565-47.518-41.212L32 256h-8c-13.255 0-24-10.745-24-24v-16c0-13.255 10.745-24 24-24h67.341l106.78-146.821c10.395-14.292 30.407-17.453 44.701-7.058 14.293 10.395 17.453 30.408 7.058 44.701L170.477 192h235.046L326.12 82.821c-10.395-14.292-7.234-34.306 7.059-44.701 14.291-10.395 34.306-7.235 44.701 7.058L484.659 192H552c13.255 0 24 10.745 24 24zM312 392V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm112 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm-224 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24z\"],\n    \"shopping-cart\": [576, 512, [], \"f07a\", \"M528.12 301.319l47.273-208C578.806 78.301 567.391 64 551.99 64H159.208l-9.166-44.81C147.758 8.021 137.93 0 126.529 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24h69.883l70.248 343.435C147.325 417.1 136 435.222 136 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-15.674-6.447-29.835-16.824-40h209.647C430.447 426.165 424 440.326 424 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-22.172-12.888-41.332-31.579-50.405l5.517-24.276c3.413-15.018-8.002-29.319-23.403-29.319H218.117l-6.545-32h293.145c11.206 0 20.92-7.754 23.403-18.681z\"],\n    \"shower\": [512, 512, [], \"f2cc\", \"M389.66 135.6L231.6 293.66c-9.37 9.37-24.57 9.37-33.94 0l-11.32-11.32c-9.37-9.37-9.37-24.57 0-33.94l.11-.11c-34.03-40.21-35.16-98.94-3.39-140.38-11.97-7.55-26.14-11.91-41.3-11.91C98.88 96 64 130.88 64 173.76V480H0V173.76C0 95.59 63.59 32 141.76 32c36.93 0 70.61 14.2 95.86 37.42 35.9-11.51 76.5-4.5 106.67 21.03l.11-.11c9.37-9.37 24.57-9.37 33.94 0l11.32 11.32c9.37 9.37 9.37 24.57 0 33.94zM384 208c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm48-16c8.837 0 16 7.163 16 16s-7.163 16-16 16-16-7.163-16-16 7.163-16 16-16zm80 16c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-128 32c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-96 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm64 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16z\"],\n    \"shuttle-van\": [640, 512, [], \"f5b6\", \"M628.88 210.65L494.39 49.27A48.01 48.01 0 0 0 457.52 32H32C14.33 32 0 46.33 0 64v288c0 17.67 14.33 32 32 32h32c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h32c17.67 0 32-14.33 32-32V241.38c0-11.23-3.94-22.1-11.12-30.73zM64 192V96h96v96H64zm96 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm160-240h-96V96h96v96zm160 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-96-240V96h66.02l80 96H384z\"],\n    \"sign\": [512, 512, [], \"f4d9\", \"M496 64H128V16c0-8.8-7.2-16-16-16H80c-8.8 0-16 7.2-16 16v48H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V128h368c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16zM160 384h320V160H160v224z\"],\n    \"sign-in-alt\": [512, 512, [], \"f2f6\", \"M416 448h-84c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h84c17.7 0 32-14.3 32-32V160c0-17.7-14.3-32-32-32h-84c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h84c53 0 96 43 96 96v192c0 53-43 96-96 96zm-47-201L201 79c-15-15-41-4.5-41 17v96H24c-13.3 0-24 10.7-24 24v96c0 13.3 10.7 24 24 24h136v96c0 21.5 26 32 41 17l168-168c9.3-9.4 9.3-24.6 0-34z\"],\n    \"sign-language\": [448, 512, [], \"f2a7\", \"M91.434 483.987c-.307-16.018 13.109-29.129 29.13-29.129h62.293v-5.714H56.993c-16.021 0-29.437-13.111-29.13-29.129C28.16 404.491 40.835 392 56.428 392h126.429v-5.714H29.136c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h154.286v-5.714H57.707c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h168.566l-31.085-22.606c-12.762-9.281-15.583-27.149-6.302-39.912 9.281-12.761 27.15-15.582 39.912-6.302l123.361 89.715a34.287 34.287 0 0 1 14.12 27.728v141.136c0 15.91-10.946 29.73-26.433 33.374l-80.471 18.934a137.16 137.16 0 0 1-31.411 3.646H120c-15.593-.001-28.269-12.492-28.566-28.014zm73.249-225.701h36.423l-11.187-8.136c-18.579-13.511-20.313-40.887-3.17-56.536l-13.004-16.7c-9.843-12.641-28.43-15.171-40.88-5.088-12.065 9.771-14.133 27.447-4.553 39.75l36.371 46.71zm283.298-2.103l-5.003-152.452c-.518-15.771-13.722-28.136-29.493-27.619-15.773.518-28.137 13.722-27.619 29.493l1.262 38.415L283.565 11.019c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l76.889 98.745-4.509 3.511-94.79-121.734c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l94.443 121.288-4.509 3.511-77.675-99.754c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l52.053 66.849c12.497-8.257 29.055-8.285 41.69.904l123.36 89.714c10.904 7.93 17.415 20.715 17.415 34.198v16.999l61.064-47.549a34.285 34.285 0 0 0 13.202-28.177z\"],\n    \"sign-out-alt\": [512, 512, [], \"f2f5\", \"M497 273L329 441c-15 15-41 4.5-41-17v-96H152c-13.3 0-24-10.7-24-24v-96c0-13.3 10.7-24 24-24h136V88c0-21.4 25.9-32 41-17l168 168c9.3 9.4 9.3 24.6 0 34zM192 436v-40c0-6.6-5.4-12-12-12H96c-17.7 0-32-14.3-32-32V160c0-17.7 14.3-32 32-32h84c6.6 0 12-5.4 12-12V76c0-6.6-5.4-12-12-12H96c-53 0-96 43-96 96v192c0 53 43 96 96 96h84c6.6 0 12-5.4 12-12z\"],\n    \"signal\": [640, 512, [], \"f012\", \"M216 288h-48c-8.84 0-16 7.16-16 16v192c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V304c0-8.84-7.16-16-16-16zM88 384H40c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16zm256-192h-48c-8.84 0-16 7.16-16 16v288c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V208c0-8.84-7.16-16-16-16zm128-96h-48c-8.84 0-16 7.16-16 16v384c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112c0-8.84-7.16-16-16-16zM600 0h-48c-8.84 0-16 7.16-16 16v480c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"signature\": [640, 512, [], \"f5b7\", \"M623.2 192c-51.8 3.5-125.7 54.7-163.1 71.5-29.1 13.1-54.2 24.4-76.1 24.4-22.6 0-26-16.2-21.3-51.9 1.1-8 11.7-79.2-42.7-76.1-25.1 1.5-64.3 24.8-169.5 126L192 182.2c30.4-75.9-53.2-151.5-129.7-102.8L7.4 116.3C0 121-2.2 130.9 2.5 138.4l17.2 27c4.7 7.5 14.6 9.7 22.1 4.9l58-38.9c18.4-11.7 40.7 7.2 32.7 27.1L34.3 404.1C27.5 421 37 448 64 448c8.3 0 16.5-3.2 22.6-9.4 42.2-42.2 154.7-150.7 211.2-195.8-2.2 28.5-2.1 58.9 20.6 83.8 15.3 16.8 37.3 25.3 65.5 25.3 35.6 0 68-14.6 102.3-30 33-14.8 99-62.6 138.4-65.8 8.5-.7 15.2-7.3 15.2-15.8v-32.1c.2-9.1-7.5-16.8-16.6-16.2z\"],\n    \"sim-card\": [384, 512, [], \"f7c4\", \"M0 64v384c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V128L256 0H64C28.7 0 0 28.7 0 64zm224 192h-64v-64h64v64zm96 0h-64v-64h32c17.7 0 32 14.3 32 32v32zm-64 128h64v32c0 17.7-14.3 32-32 32h-32v-64zm-96 0h64v64h-64v-64zm-96 0h64v64H96c-17.7 0-32-14.3-32-32v-32zm0-96h256v64H64v-64zm0-64c0-17.7 14.3-32 32-32h32v64H64v-32z\"],\n    \"sitemap\": [640, 512, [], \"f0e8\", \"M128 352H32c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm-24-80h192v48h48v-48h192v48h48v-57.59c0-21.17-17.23-38.41-38.41-38.41H344v-64h40c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H256c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h40v64H94.41C73.23 224 56 241.23 56 262.41V320h48v-48zm264 80h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm240 0h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"skating\": [448, 512, [], \"f7c5\", \"M400 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm0 448c-8.8 0-16 7.2-16 16s-7.2 16-16 16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16h96c26.5 0 48-21.5 48-48 0-8.8-7.2-16-16-16zm-282.2 8.6c-6.2 6.2-16.4 6.3-22.6 0l-67.9-67.9c-6.2-6.2-16.4-6.2-22.6 0s-6.2 16.4 0 22.6l67.9 67.9c9.4 9.4 21.7 14 34 14s24.6-4.7 33.9-14c6.2-6.2 6.2-16.4 0-22.6s-16.4-6.3-22.7 0zm56.1-179.8l-93.7 93.7c-12.5 12.5-12.5 32.8 0 45.2 6.2 6.2 14.4 9.4 22.6 9.4s16.4-3.1 22.6-9.4l91.9-91.9-30.2-30.2c-5-5-9.4-10.7-13.2-16.8zM128 160h105.5l-20.1 17.2c-13.5 11.5-21.6 28.4-22.3 46.1-.7 17.8 6.1 35.2 18.7 47.7l78.2 78.2V432c0 17.7 14.3 32 32 32s32-14.3 32-32v-89.4c0-12.6-5.1-25-14.1-33.9l-61-61c.5-.4 1.2-.6 1.7-1.1l82.3-82.3c11.5-11.5 14.9-28.6 8.7-43.6-6.2-15-20.7-24.7-37-24.7H128c-17.7 0-32 14.3-32 32s14.3 32 32 32z\"],\n    \"skiing\": [512, 512, [], \"f7c9\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm73 356.1c-9.4-9.4-24.6-9.4-33.9 0-12.1 12.1-30.5 15.4-45.1 8.7l-135.8-70.2 49.2-73.8c12.7-19 10.2-44.5-6-60.6L293 215.7l-107-53.1c-2.9 19.9 3.4 40 17.7 54.4l75.1 75.2-45.9 68.8L35 258.7c-11.7-6-26.2-1.5-32.3 10.3-6.1 11.8-1.5 26.3 10.3 32.3l391.9 202.5c11.9 5.5 24.5 8.1 37.1 8.1 23.2 0 46-9 63-26 9.3-9.3 9.3-24.5 0-33.8zM120 91.6l-11.5 22.5c14.4 7.3 31.2 4.9 42.8-4.8l47.2 23.4c-.1.1-.1.2-.2.3l114.5 56.8 32.4-13 6.4 19.1c4 12.1 12.6 22 24 27.7l58.1 29c15.9 7.9 35 1.5 42.9-14.3 7.9-15.8 1.5-35-14.3-42.9l-52.1-26.1-17.1-51.2c-8.1-24.2-40.9-56.6-84.5-39.2l-81.2 32.5-62.5-31c.3-14.5-7.2-28.6-20.9-35.6l-11.1 21.7h-.2l-34.4-7c-1.8-.4-3.7.2-5 1.7-1.9 2.2-1.7 5.5.5 7.4l26.2 23z\"],\n    \"skiing-nordic\": [576, 512, [], \"f7ca\", \"M336 96c26.5 0 48-21.5 48-48S362.5 0 336 0s-48 21.5-48 48 21.5 48 48 48zm216 320c-13.2 0-24 10.7-24 24 0 13.2-10.8 24-24 24h-69.5L460 285.6c11.7-4.7 20.1-16.2 20.1-29.6 0-17.7-14.3-32-32-32h-44L378 170.8c-12.5-25.5-35.5-44.2-61.8-50.9L245 98.7c-28.3-6.8-57.8-.5-80.8 17.1l-39.7 30.4c-14 10.7-16.7 30.8-5.9 44.9.7.9 1.7 1.3 2.4 2.1L66.9 464H24c-13.2 0-24 10.7-24 24s10.8 24 24 24h480c39.7 0 72-32.3 72-72 0-13.2-10.8-24-24-24zm-260.5 48h-96.9l43.1-91-22-13c-12.1-7.2-21.9-16.9-29.5-27.8L123.7 464H99.5l52.3-261.4c4.1-1 8.1-2.9 11.7-5.6l39.7-30.4c7.7-5.9 17.4-8 25.3-6.1l14.7 4.4-37.5 87.4c-12.6 29.5-1.3 64 26.3 80.3l85 50.2-25.5 81.2zm110.6 0h-43.6l23.6-75.5c5.9-20.8-2.9-43.1-21.6-54.4L299.3 298l31.3-78.3 20.3 41.4c8 16.3 24.9 26.9 43.1 26.9h33.3l-25.2 176z\"],\n    \"skull\": [512, 512, [], \"f54c\", \"M256 0C114.6 0 0 100.3 0 224c0 70.1 36.9 132.6 94.5 173.7 9.6 6.9 15.2 18.1 13.5 29.9l-9.4 66.2c-1.4 9.6 6 18.2 15.7 18.2H192v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h64v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h77.7c9.7 0 17.1-8.6 15.7-18.2l-9.4-66.2c-1.7-11.7 3.8-23 13.5-29.9C475.1 356.6 512 294.1 512 224 512 100.3 397.4 0 256 0zm-96 320c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm192 0c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64z\"],\n    \"skull-crossbones\": [448, 512, [], \"f714\", \"M439.15 453.06L297.17 384l141.99-69.06c7.9-3.95 11.11-13.56 7.15-21.46L432 264.85c-3.95-7.9-13.56-11.11-21.47-7.16L224 348.41 37.47 257.69c-7.9-3.95-17.51-.75-21.47 7.16L1.69 293.48c-3.95 7.9-.75 17.51 7.15 21.46L150.83 384 8.85 453.06c-7.9 3.95-11.11 13.56-7.15 21.47l14.31 28.63c3.95 7.9 13.56 11.11 21.47 7.15L224 419.59l186.53 90.72c7.9 3.95 17.51.75 21.47-7.15l14.31-28.63c3.95-7.91.74-17.52-7.16-21.47zM150 237.28l-5.48 25.87c-2.67 12.62 5.42 24.85 16.45 24.85h126.08c11.03 0 19.12-12.23 16.45-24.85l-5.5-25.87c41.78-22.41 70-62.75 70-109.28C368 57.31 303.53 0 224 0S80 57.31 80 128c0 46.53 28.22 86.87 70 109.28zM280 112c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32zm-112 0c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32z\"],\n    \"slash\": [640, 512, [], \"f715\", \"M594.53 508.63L6.18 53.9c-6.97-5.42-8.23-15.47-2.81-22.45L23.01 6.18C28.43-.8 38.49-2.06 45.47 3.37L633.82 458.1c6.97 5.42 8.23 15.47 2.81 22.45l-19.64 25.27c-5.42 6.98-15.48 8.23-22.46 2.81z\"],\n    \"sleigh\": [640, 512, [], \"f7cc\", \"M612.7 350.7l-9.3-7.4c-6.9-5.5-17-4.4-22.5 2.5l-10 12.5c-5.5 6.9-4.4 17 2.5 22.5l9.3 7.4c5.9 4.7 9.2 11.7 9.2 19.2 0 13.6-11 24.6-24.6 24.6H48c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h516c39 0 73.7-29.3 75.9-68.3 1.4-23.8-8.7-46.3-27.2-61zM32 224c0 59.6 40.9 109.2 96 123.5V400h64v-48h192v48h64v-48c53 0 96-43 96-96v-96c17.7 0 32-14.3 32-32s-14.3-32-32-32h-96v64c0 35.3-28.7 64-64 64h-20.7c-65.8 0-125.9-37.2-155.3-96-29.4-58.8-89.6-96-155.3-96H32C14.3 32 0 46.3 0 64s14.3 32 32 32v128z\"],\n    \"sliders-h\": [512, 512, [], \"f1de\", \"M496 384H160v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h80v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h336c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160h-80v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h336v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h80c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160H288V48c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h208v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm194.8 170.2C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.6-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.4-16.2 38.1 4.2 24.6 20.5z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM112 223.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zm250.8 122.8C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.3 24.6 20.5zm6.2-118.3l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.6 8.6-11 11.9-15.1 4.5z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm158.5 16.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.7 11.1-11.4 18.3-19.8 10.8l-9.7-8.5zM157.8 325.8C180.2 352.7 213 368 248 368s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.2 24.6 20.5C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11.2-36.7 24.6-20.4z\"],\n    \"smog\": [640, 512, [], \"f75f\", \"M624 368H80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm-480 96H16c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h128c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm416 0H224c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h336c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zM144 288h156.1c22.5 19.7 51.6 32 83.9 32s61.3-12.3 83.9-32H528c61.9 0 112-50.1 112-112S589.9 64 528 64c-18 0-34.7 4.6-49.7 12.1C454 31 406.8 0 352 0c-41 0-77.8 17.3-104 44.8C221.8 17.3 185 0 144 0 64.5 0 0 64.5 0 144s64.5 144 144 144z\"],\n    \"smoking\": [640, 512, [], \"f48d\", \"M632 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8zM553.3 87.1c-5.7-3.8-9.3-10-9.3-16.8V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v62.3c0 22 10.2 43.4 28.6 55.4 42.2 27.3 67.4 73.8 67.4 124V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-65.5-32.4-126.2-86.7-162.6zM432 352H48c-26.5 0-48 21.5-48 48v64c0 26.5 21.5 48 48 48h384c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zm-32 112H224v-64h176v64zm87.7-322.4C463.8 125 448 99.3 448 70.3V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v66.4c0 43.7 24.6 81.6 60.3 106.7 22.4 15.7 35.7 41.2 35.7 68.6V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-43.3-21-83.4-56.3-108.1zM536 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8z\"],\n    \"smoking-ban\": [512, 512, [], \"f54d\", \"M96 304c0 8.8 7.2 16 16 16h117.5l-96-96H112c-8.8 0-16 7.2-16 16v64zM256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm0 448c-105.9 0-192-86.1-192-192 0-41.4 13.3-79.7 35.7-111.1l267.4 267.4C335.7 434.7 297.4 448 256 448zm45.2-192H384v32h-50.8l-32-32zm111.1 111.1L365.2 320H400c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16H269.2L144.9 99.7C176.3 77.3 214.6 64 256 64c105.9 0 192 86.1 192 192 0 41.4-13.3 79.7-35.7 111.1zM320.6 128c-15.6 0-28.6-11.2-31.4-25.9-.7-3.6-4-6.1-7.7-6.1h-16.2c-5 0-8.7 4.5-8 9.4 4.6 30.9 31.2 54.6 63.3 54.6 15.6 0 28.6 11.2 31.4 25.9.7 3.6 4 6.1 7.7 6.1h16.2c5 0 8.7-4.5 8-9.4-4.6-30.9-31.2-54.6-63.3-54.6z\"],\n    \"sms\": [512, 512, [], \"f7cd\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7 1.3 3 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128.2 304H116c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H156c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-19 38.6-42.4 38.6zm191.8-8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-68.2l-24.8 55.8c-2.9 5.9-11.4 5.9-14.3 0L224 227.8V296c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V192c0-8.8 7.2-16 16-16h16c6.1 0 11.6 3.4 14.3 8.8l17.7 35.4 17.7-35.4c2.7-5.4 8.3-8.8 14.3-8.8h16c8.8 0 16 7.2 16 16v104zm48.3 8H356c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H396c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-18.9 38.6-42.3 38.6z\"],\n    \"snowboarding\": [512, 512, [], \"f7ce\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm28.8 153.6c5.8 4.3 12.5 6.4 19.2 6.4 9.7 0 19.3-4.4 25.6-12.8 10.6-14.1 7.8-34.2-6.4-44.8l-111.4-83.5c-13.8-10.3-29.1-18.4-45.4-23.8l-63.7-21.2-26.1-52.1C244.7 2 225.5-4.4 209.7 3.5c-15.8 7.9-22.2 27.1-14.3 42.9l29.1 58.1c5.7 11.4 15.6 19.9 27.7 24l16.4 5.5-41.2 20.6c-21.8 10.9-35.4 32.8-35.4 57.2v53.1l-74.1 24.7c-16.8 5.6-25.8 23.7-20.2 40.5 1.7 5.2 4.9 9.4 8.7 12.9l-38.7-14.1c-9.7-3.5-17.4-10.6-21.8-20-5.6-12-19.9-17.2-31.9-11.6s-17.2 19.9-11.6 31.9c9.8 21 27.1 36.9 48.9 44.8l364.8 132.7c9.7 3.5 19.7 5.3 29.7 5.3 12.5 0 24.9-2.7 36.5-8.2 12-5.6 17.2-19.9 11.6-31.9S474 454.7 462 460.3c-9.3 4.4-19.8 4.8-29.5 1.3l-90.8-33.1c8.7-4.1 15.6-11.8 17.8-21.9l21.9-102c3.9-18.2-3.2-37.2-18.1-48.4l-52-39 66-30.5 83.5 62.9zm-144.4 51.7l-19.7 92c-1.5 7.1-.1 13.9 2.8 20l-169.4-61.6c2.7-.2 5.4-.4 8-1.3l85-28.4c19.6-6.5 32.8-24.8 32.8-45.5V256l60.5 45.3z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.3 345.2l-33.8-19.5 26-7c8.2-2.2 13.1-10.7 10.9-18.9l-4-14.9c-2.2-8.2-10.7-13.1-18.9-10.9l-70.8 19-63.9-37 63.8-36.9 70.8 19c8.2 2.2 16.7-2.7 18.9-10.9l4-14.9c2.2-8.2-2.7-16.7-10.9-18.9l-26-7 33.8-19.5c7.4-4.3 9.9-13.7 5.7-21.1L430.4 119c-4.3-7.4-13.7-9.9-21.1-5.7l-33.8 19.5 7-26c2.2-8.2-2.7-16.7-10.9-18.9l-14.9-4c-8.2-2.2-16.7 2.7-18.9 10.9l-19 70.8-62.8 36.2v-77.5l53.7-53.7c6.2-6.2 6.2-16.4 0-22.6l-11.3-11.3c-6.2-6.2-16.4-6.2-22.6 0L256 56.4V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v40.4l-19.7-19.7c-6.2-6.2-16.4-6.2-22.6 0L138.3 48c-6.3 6.2-6.3 16.4 0 22.6l53.7 53.7v77.5l-62.8-36.2-19-70.8c-2.2-8.2-10.7-13.1-18.9-10.9l-14.9 4c-8.2 2.2-13.1 10.7-10.9 18.9l7 26-33.8-19.5c-7.4-4.3-16.8-1.7-21.1 5.7L2.1 145.7c-4.3 7.4-1.7 16.8 5.7 21.1l33.8 19.5-26 7c-8.3 2.2-13.2 10.7-11 19l4 14.9c2.2 8.2 10.7 13.1 18.9 10.9l70.8-19 63.8 36.9-63.8 36.9-70.8-19c-8.2-2.2-16.7 2.7-18.9 10.9l-4 14.9c-2.2 8.2 2.7 16.7 10.9 18.9l26 7-33.8 19.6c-7.4 4.3-9.9 13.7-5.7 21.1l15.5 26.8c4.3 7.4 13.7 9.9 21.1 5.7l33.8-19.5-7 26c-2.2 8.2 2.7 16.7 10.9 18.9l14.9 4c8.2 2.2 16.7-2.7 18.9-10.9l19-70.8 62.8-36.2v77.5l-53.7 53.7c-6.3 6.2-6.3 16.4 0 22.6l11.3 11.3c6.2 6.2 16.4 6.2 22.6 0l19.7-19.7V496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-40.4l19.7 19.7c6.2 6.2 16.4 6.2 22.6 0l11.3-11.3c6.2-6.2 6.2-16.4 0-22.6L256 387.7v-77.5l62.8 36.2 19 70.8c2.2 8.2 10.7 13.1 18.9 10.9l14.9-4c8.2-2.2 13.1-10.7 10.9-18.9l-7-26 33.8 19.5c7.4 4.3 16.8 1.7 21.1-5.7l15.5-26.8c4.3-7.3 1.8-16.8-5.6-21z\"],\n    \"snowman\": [512, 512, [], \"f7d0\", \"M510.9 152.3l-5.9-14.5c-3.3-8-12.6-11.9-20.8-8.7L456 140.6v-29c0-8.6-7.2-15.6-16-15.6h-16c-8.8 0-16 7-16 15.6v46.9c0 .5.3 1 .3 1.5l-56.4 23c-5.9-10-13.3-18.9-22-26.6 13.6-16.6 22-37.4 22-60.5 0-53-43-96-96-96s-96 43-96 96c0 23.1 8.5 43.9 22 60.5-8.7 7.7-16 16.6-22 26.6l-56.4-23c.1-.5.3-1 .3-1.5v-46.9C104 103 96.8 96 88 96H72c-8.8 0-16 7-16 15.6v29l-28.1-11.5c-8.2-3.2-17.5.7-20.8 8.7l-5.9 14.5c-3.3 8 .7 17.1 8.9 20.3l135.2 55.2c-.4 4-1.2 8-1.2 12.2 0 10.1 1.7 19.6 4.2 28.9C120.9 296.4 104 334.2 104 376c0 54 28.4 100.9 70.8 127.8 9.3 5.9 20.3 8.2 31.3 8.2h99.2c13.3 0 26.3-4.1 37.2-11.7 46.5-32.3 74.4-89.4 62.9-152.6-5.5-30.2-20.5-57.6-41.6-79 2.5-9.2 4.2-18.7 4.2-28.7 0-4.2-.8-8.1-1.2-12.2L502 172.6c8.1-3.1 12.1-12.2 8.9-20.3zM224 96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 272c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-88s-16-23.2-16-32 7.2-16 16-16 16 7.2 16 16-16 32-16 32zm32-56c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"snowplow\": [640, 512, [], \"f7d2\", \"M120 376c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm238.6 49.4c-14.5-14.5-22.6-34.1-22.6-54.6V269.2c0-20.5 8.1-40.1 22.6-54.6l36.7-36.7c6.2-6.2 6.2-16.4 0-22.6l-22.6-22.6c-6.2-6.2-16.4-6.2-22.6 0l-36.7 36.7c-26.5 26.5-41.4 62.4-41.4 99.9V288h-64v-50.9c0-8.7-1.8-17.2-5.2-25.2L364.5 29.1C356.9 11.4 339.6 0 320.3 0H176c-26.5 0-48 21.5-48 48v112h-16c-26.5 0-48 21.5-48 48v91.2C26.3 317.2 0 355.4 0 400c0 61.9 50.1 112 112 112h256c61.9 0 112-50.1 112-112 0-17.3-4.2-33.4-11.2-48H512v18.7c0 37.5 14.9 73.4 41.4 99.9l36.7 36.7c6.2 6.2 16.4 6.2 22.6 0l22.6-22.6c6.2-6.2 6.2-16.4 0-22.6l-36.7-36.7zM192 64h117.8l68.6 160H256l-64-64V64zm176 384H112c-26.5 0-48-21.5-48-48s21.5-48 48-48h256c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"socks\": [512, 512, [], \"f696\", \"M214.66 311.01L288 256V96H128v176l-86.65 64.61c-39.4 29.56-53.86 84.42-29.21 127.06C30.39 495.25 63.27 512 96.08 512c20.03 0 40.25-6.25 57.52-19.2l21.86-16.39c-29.85-55.38-13.54-125.84 39.2-165.4zM288 32c0-11.05 3.07-21.3 8.02-30.38C293.4.92 290.85 0 288 0H160c-17.67 0-32 14.33-32 32v32h160V32zM480 0H352c-17.67 0-32 14.33-32 32v32h192V32c0-17.67-14.33-32-32-32zM320 272l-86.13 64.61c-39.4 29.56-53.86 84.42-29.21 127.06 18.25 31.58 50.61 48.33 83.42 48.33 20.03 0 40.25-6.25 57.52-19.2l115.2-86.4A127.997 127.997 0 0 0 512 304V96H320v176z\"],\n    \"solar-panel\": [640, 512, [], \"f5ba\", \"M431.98 448.01l-47.97.05V416h-128v32.21l-47.98.05c-8.82.01-15.97 7.16-15.98 15.99l-.05 31.73c-.01 8.85 7.17 16.03 16.02 16.02l223.96-.26c8.82-.01 15.97-7.16 15.98-15.98l.04-31.73c.01-8.85-7.17-16.03-16.02-16.02zM585.2 26.74C582.58 11.31 568.99 0 553.06 0H86.93C71 0 57.41 11.31 54.79 26.74-3.32 369.16.04 348.08.03 352c-.03 17.32 14.29 32 32.6 32h574.74c18.23 0 32.51-14.56 32.59-31.79.02-4.08 3.35 16.95-54.76-325.47zM259.83 64h120.33l9.77 96H250.06l9.77-96zm-75.17 256H71.09L90.1 208h105.97l-11.41 112zm16.29-160H98.24l16.29-96h96.19l-9.77 96zm32.82 160l11.4-112h149.65l11.4 112H233.77zm195.5-256h96.19l16.29 96H439.04l-9.77-96zm26.06 256l-11.4-112H549.9l19.01 112H455.33z\"],\n    \"sort\": [320, 512, [], \"f0dc\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41zm255-105L177 64c-9.4-9.4-24.6-9.4-33.9 0L24 183c-15.1 15.1-4.4 41 17 41h238c21.4 0 32.1-25.9 17-41z\"],\n    \"sort-alpha-down\": [448, 512, [], \"f15d\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm240-64H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-down-alt\": [448, 512, [], \"f881\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm112-128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-alpha-up\": [448, 512, [], \"f15e\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm400 128H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-up-alt\": [448, 512, [], \"f882\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm272 64h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-amount-down\": [512, 512, [], \"f160\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-128-64h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm256-192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-down-alt\": [512, 512, [], \"f884\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm-64 0h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-amount-up\": [512, 512, [], \"f161\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.77 160 16 160zm416 0H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-up-alt\": [512, 512, [], \"f885\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.39-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160z\"],\n    \"sort-down\": [320, 512, [], \"f0dd\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41z\"],\n    \"sort-numeric-down\": [448, 512, [], \"f162\", \"M304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zm26.15 162.91a79 79 0 0 0-55 54.17c-14.25 51.05 21.21 97.77 68.85 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zm-176-4h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-numeric-down-alt\": [448, 512, [], \"f886\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm224 64h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-numeric-up\": [448, 512, [], \"f163\", \"M330.17 258.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zM304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zM107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31z\"],\n    \"sort-numeric-up-alt\": [448, 512, [], \"f887\", \"M107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31zM400 416h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-up\": [320, 512, [], \"f0de\", \"M279 224H41c-21.4 0-32.1-25.9-17-41L143 64c9.4-9.4 24.6-9.4 33.9 0l119 119c15.2 15.1 4.5 41-16.9 41z\"],\n    \"spa\": [576, 512, [], \"f5bb\", \"M568.25 192c-29.04.13-135.01 6.16-213.84 83-33.12 29.63-53.36 63.3-66.41 94.86-13.05-31.56-33.29-65.23-66.41-94.86-78.83-76.84-184.8-82.87-213.84-83-4.41-.02-7.79 3.4-7.75 7.82.23 27.92 7.14 126.14 88.77 199.3C172.79 480.94 256 480 288 480s115.19.95 199.23-80.88c81.64-73.17 88.54-171.38 88.77-199.3.04-4.42-3.34-7.84-7.75-7.82zM287.98 302.6c12.82-18.85 27.6-35.78 44.09-50.52 19.09-18.61 39.58-33.3 60.26-45.18-16.44-70.5-51.72-133.05-96.73-172.22-4.11-3.58-11.02-3.58-15.14 0-44.99 39.14-80.27 101.63-96.74 172.07 20.37 11.7 40.5 26.14 59.22 44.39a282.768 282.768 0 0 1 45.04 51.46z\"],\n    \"space-shuttle\": [640, 512, [], \"f197\", \"M592.604 208.244C559.735 192.836 515.777 184 472 184H186.327c-4.952-6.555-10.585-11.978-16.72-16H376C229.157 137.747 219.403 32 96.003 32H96v128H80V32c-26.51 0-48 28.654-48 64v64c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v16c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v64c0 35.346 21.49 64 48 64V352h16v128h.003c123.4 0 133.154-105.747 279.997-136H169.606c6.135-4.022 11.768-9.445 16.72-16H472c43.777 0 87.735-8.836 120.604-24.244C622.282 289.845 640 271.992 640 256s-17.718-33.845-47.396-47.756zM488 296a8 8 0 0 1-8-8v-64a8 8 0 0 1 8-8c31.909 0 31.942 80 0 80z\"],\n    \"spell-check\": [576, 512, [], \"f891\", \"M272 256h91.36c43.2 0 82-32.2 84.51-75.34a79.82 79.82 0 0 0-25.26-63.07 79.81 79.81 0 0 0 9.06-44.91C427.9 30.57 389.3 0 347 0h-75a16 16 0 0 0-16 16v224a16 16 0 0 0 16 16zm40-200h40a24 24 0 0 1 0 48h-40zm0 96h56a24 24 0 0 1 0 48h-56zM155.12 22.25A32 32 0 0 0 124.64 0H99.36a32 32 0 0 0-30.48 22.25L.59 235.73A16 16 0 0 0 16 256h24.93a16 16 0 0 0 15.42-11.73L68.29 208h87.42l11.94 36.27A16 16 0 0 0 183.07 256H208a16 16 0 0 0 15.42-20.27zM89.37 144L112 75.3l22.63 68.7zm482 132.48l-45.21-45.3a15.88 15.88 0 0 0-22.59 0l-151.5 151.5-55.41-55.5a15.88 15.88 0 0 0-22.59 0l-45.3 45.3a16 16 0 0 0 0 22.59l112 112.21a15.89 15.89 0 0 0 22.6 0l208-208.21a16 16 0 0 0-.02-22.59z\"],\n    \"spider\": [576, 512, [], \"f717\", \"M151.17 167.35L177.1 176h4.67l5.22-26.12c.72-3.58 1.8-7.58 3.21-11.79l-20.29-40.58 23.8-71.39c2.79-8.38-1.73-17.44-10.12-20.24L168.42.82c-8.38-2.8-17.45 1.73-20.24 10.12l-25.89 77.68a32.04 32.04 0 0 0 1.73 24.43l27.15 54.3zm422.14 182.03l-52.75-79.12a32.002 32.002 0 0 0-26.62-14.25H416l68.99-24.36a32.03 32.03 0 0 0 16.51-12.61l53.6-80.41c4.9-7.35 2.91-17.29-4.44-22.19l-13.31-8.88c-7.35-4.9-17.29-2.91-22.19 4.44l-50.56 75.83L404.1 208H368l-10.37-51.85C355.44 145.18 340.26 96 288 96c-52.26 0-67.44 49.18-69.63 60.15L208 208h-36.1l-60.49-20.17L60.84 112c-4.9-7.35-14.83-9.34-22.19-4.44l-13.31 8.88c-7.35 4.9-9.34 14.83-4.44 22.19l53.6 80.41a32.03 32.03 0 0 0 16.51 12.61L160 256H82.06a32.02 32.02 0 0 0-26.63 14.25L2.69 349.38c-4.9 7.35-2.92 17.29 4.44 22.19l13.31 8.88c7.35 4.9 17.29 2.91 22.19-4.44l48-72h47.06l-60.83 97.33A31.988 31.988 0 0 0 72 418.3V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-73.11l74.08-118.53c-1.01 14.05-2.08 28.11-2.08 42.21C192 399.64 232.76 448 288 448s96-48.36 96-101.43c0-14.1-1.08-28.16-2.08-42.21L456 422.89V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-77.71c0-6-1.69-11.88-4.86-16.96L438.31 304h47.06l48 72c4.9 7.35 14.84 9.34 22.19 4.44l13.31-8.88c7.36-4.9 9.34-14.83 4.44-22.18zM406.09 97.51l-20.29 40.58c1.41 4.21 2.49 8.21 3.21 11.79l5.22 26.12h4.67l25.93-8.65 27.15-54.3a31.995 31.995 0 0 0 1.73-24.43l-25.89-77.68C425.03 2.56 415.96-1.98 407.58.82l-15.17 5.06c-8.38 2.8-12.91 11.86-10.12 20.24l23.8 71.39z\"],\n    \"spinner\": [512, 512, [], \"f110\", \"M304 48c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-48 368c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm208-208c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zM96 256c0-26.51-21.49-48-48-48S0 229.49 0 256s21.49 48 48 48 48-21.49 48-48zm12.922 99.078c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.491-48-48-48zm294.156 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.49-48-48-48zM108.922 60.922c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.491-48-48-48z\"],\n    \"splotch\": [512, 512, [], \"f5bc\", \"M472.29 195.89l-67.06-22.95c-19.28-6.6-33.54-20.92-38.14-38.3L351.1 74.19c-11.58-43.77-76.57-57.13-109.98-22.62l-46.14 47.67c-13.26 13.71-33.54 20.93-54.2 19.31l-71.88-5.62c-52.05-4.07-86.93 44.88-59.03 82.83l38.54 52.42c11.08 15.07 12.82 33.86 4.64 50.24L24.62 355.4c-20.59 41.25 22.84 84.87 73.49 73.81l69.96-15.28c20.11-4.39 41.45 0 57.07 11.73l54.32 40.83c39.32 29.56 101.04 7.57 104.45-37.22l4.7-61.86c1.35-17.79 12.8-33.86 30.63-42.99l62-31.74c44.88-22.96 39.59-80.17-8.95-96.79z\"],\n    \"spray-can\": [512, 512, [], \"f5bd\", \"M224 32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96h128V32zm256 96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-256 32H96c-53.02 0-96 42.98-96 96v224c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V256c0-53.02-42.98-96-96-96zm-64 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zM480 96c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm-96 32c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-96-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 0c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 192c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"square-full\": [512, 512, [], \"f45c\", \"M512 512H0V0h512v512z\"],\n    \"square-root-alt\": [576, 512, [], \"f698\", \"M571.31 251.31l-22.62-22.62c-6.25-6.25-16.38-6.25-22.63 0L480 274.75l-46.06-46.06c-6.25-6.25-16.38-6.25-22.63 0l-22.62 22.62c-6.25 6.25-6.25 16.38 0 22.63L434.75 320l-46.06 46.06c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L480 365.25l46.06 46.06c6.25 6.25 16.38 6.25 22.63 0l22.62-22.62c6.25-6.25 6.25-16.38 0-22.63L525.25 320l46.06-46.06c6.25-6.25 6.25-16.38 0-22.63zM552 0H307.65c-14.54 0-27.26 9.8-30.95 23.87l-84.79 322.8-58.41-106.1A32.008 32.008 0 0 0 105.47 224H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h43.62l88.88 163.73C168.99 503.5 186.3 512 204.94 512c17.27 0 44.44-9 54.28-41.48L357.03 96H552c13.25 0 24-10.75 24-24V24c0-13.26-10.75-24-24-24z\"],\n    \"stamp\": [512, 512, [], \"f5bf\", \"M32 512h448v-64H32v64zm384-256h-66.56c-16.26 0-29.44-13.18-29.44-29.44v-9.46c0-27.37 8.88-53.41 21.46-77.72 9.11-17.61 12.9-38.39 9.05-60.42-6.77-38.78-38.47-70.7-77.26-77.45C212.62-9.04 160 37.33 160 96c0 14.16 3.12 27.54 8.69 39.58C182.02 164.43 192 194.7 192 226.49v.07c0 16.26-13.18 29.44-29.44 29.44H96c-53.02 0-96 42.98-96 96v32c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-32c0-53.02-42.98-96-96-96z\"],\n    \"star\": [576, 512, [], \"f005\", \"M259.3 17.8L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0z\"],\n    \"star-and-crescent\": [512, 512, [], \"f699\", \"M340.47 466.36c-1.45 0-6.89.46-9.18.46-116.25 0-210.82-94.57-210.82-210.82S215.04 45.18 331.29 45.18c2.32 0 7.7.46 9.18.46 7.13 0 13.33-5.03 14.75-12.07 1.46-7.25-2.55-14.49-9.47-17.09C316.58 5.54 286.39 0 256 0 114.84 0 0 114.84 0 256s114.84 256 256 256c30.23 0 60.28-5.49 89.32-16.32 5.96-2.02 10.28-7.64 10.28-14.26 0-8.09-6.39-15.06-15.13-15.06zm162.99-252.5l-76.38-11.1-34.16-69.21c-1.83-3.7-5.38-5.55-8.93-5.55s-7.1 1.85-8.93 5.55l-34.16 69.21-76.38 11.1c-8.17 1.18-11.43 11.22-5.52 16.99l55.27 53.87-13.05 76.07c-1.11 6.44 4.01 11.66 9.81 11.66 1.53 0 3.11-.36 4.64-1.17L384 335.37l68.31 35.91c1.53.8 3.11 1.17 4.64 1.17 5.8 0 10.92-5.23 9.81-11.66l-13.05-76.07 55.27-53.87c5.91-5.77 2.65-15.81-5.52-16.99z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6V0z\"],\n    \"star-half-alt\": [536, 512, [], \"f5c0\", \"M508.55 171.51L362.18 150.2 296.77 17.81C290.89 5.98 279.42 0 267.95 0c-11.4 0-22.79 5.9-28.69 17.81l-65.43 132.38-146.38 21.29c-26.25 3.8-36.77 36.09-17.74 54.59l105.89 103-25.06 145.48C86.98 495.33 103.57 512 122.15 512c4.93 0 10-1.17 14.87-3.75l130.95-68.68 130.94 68.7c4.86 2.55 9.92 3.71 14.83 3.71 18.6 0 35.22-16.61 31.66-37.4l-25.03-145.49 105.91-102.98c19.04-18.5 8.52-50.8-17.73-54.6zm-121.74 123.2l-18.12 17.62 4.28 24.88 19.52 113.45-102.13-53.59-22.38-11.74.03-317.19 51.03 103.29 11.18 22.63 25.01 3.64 114.23 16.63-82.65 80.38z\"],\n    \"star-of-david\": [464, 512, [], \"f69a\", \"M405.68 256l53.21-89.39C473.3 142.4 455.48 112 426.88 112H319.96l-55.95-93.98C256.86 6.01 244.43 0 232 0s-24.86 6.01-32.01 18.02L144.04 112H37.11c-28.6 0-46.42 30.4-32.01 54.61L58.32 256 5.1 345.39C-9.31 369.6 8.51 400 37.11 400h106.93l55.95 93.98C207.14 505.99 219.57 512 232 512s24.86-6.01 32.01-18.02L319.96 400h106.93c28.6 0 46.42-30.4 32.01-54.61L405.68 256zm-12.78-88l-19.8 33.26L353.3 168h39.6zm-52.39 88l-52.39 88H175.88l-52.39-88 52.38-88h112.25l52.39 88zM232 73.72L254.79 112h-45.57L232 73.72zM71.1 168h39.6l-19.8 33.26L71.1 168zm0 176l19.8-33.26L110.7 344H71.1zM232 438.28L209.21 400h45.57L232 438.28zM353.29 344l19.8-33.26L392.9 344h-39.61z\"],\n    \"star-of-life\": [480, 512, [], \"f621\", \"M471.99 334.43L336.06 256l135.93-78.43c7.66-4.42 10.28-14.2 5.86-21.86l-32.02-55.43c-4.42-7.65-14.21-10.28-21.87-5.86l-135.93 78.43V16c0-8.84-7.17-16-16.01-16h-64.04c-8.84 0-16.01 7.16-16.01 16v156.86L56.04 94.43c-7.66-4.42-17.45-1.79-21.87 5.86L2.15 155.71c-4.42 7.65-1.8 17.44 5.86 21.86L143.94 256 8.01 334.43c-7.66 4.42-10.28 14.21-5.86 21.86l32.02 55.43c4.42 7.65 14.21 10.27 21.87 5.86l135.93-78.43V496c0 8.84 7.17 16 16.01 16h64.04c8.84 0 16.01-7.16 16.01-16V339.14l135.93 78.43c7.66 4.42 17.45 1.8 21.87-5.86l32.02-55.43c4.42-7.65 1.8-17.43-5.86-21.85z\"],\n    \"step-backward\": [448, 512, [], \"f048\", \"M64 468V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v176.4l195.5-181C352.1 22.3 384 36.6 384 64v384c0 27.4-31.9 41.7-52.5 24.6L136 292.7V468c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12z\"],\n    \"step-forward\": [448, 512, [], \"f051\", \"M384 44v424c0 6.6-5.4 12-12 12h-48c-6.6 0-12-5.4-12-12V291.6l-195.5 181C95.9 489.7 64 475.4 64 448V64c0-27.4 31.9-41.7 52.5-24.6L312 219.3V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12z\"],\n    \"stethoscope\": [512, 512, [], \"f0f1\", \"M447.1 112c-34.2.5-62.3 28.4-63 62.6-.5 24.3 12.5 45.6 32 56.8V344c0 57.3-50.2 104-112 104-60 0-109.2-44.1-111.9-99.2C265 333.8 320 269.2 320 192V36.6c0-11.4-8.1-21.3-19.3-23.5L237.8.5c-13-2.6-25.6 5.8-28.2 18.8L206.4 35c-2.6 13 5.8 25.6 18.8 28.2l30.7 6.1v121.4c0 52.9-42.2 96.7-95.1 97.2-53.4.5-96.9-42.7-96.9-96V69.4l30.7-6.1c13-2.6 21.4-15.2 18.8-28.2l-3.1-15.7C107.7 6.4 95.1-2 82.1.6L19.3 13C8.1 15.3 0 25.1 0 36.6V192c0 77.3 55.1 142 128.1 156.8C130.7 439.2 208.6 512 304 512c97 0 176-75.4 176-168V231.4c19.1-11.1 32-31.7 32-55.4 0-35.7-29.2-64.5-64.9-64zm.9 80c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M312 320h136V56c0-13.3-10.7-24-24-24H24C10.7 32 0 42.7 0 56v400c0 13.3 10.7 24 24 24h264V344c0-13.2 10.8-24 24-24zm129 55l-98 98c-4.5 4.5-10.6 7-17 7h-6V352h128v6.1c0 6.3-2.5 12.4-7 16.9z\"],\n    \"stop\": [448, 512, [], \"f04d\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm96 328c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16v160z\"],\n    \"stopwatch\": [448, 512, [], \"f2f2\", \"M432 304c0 114.9-93.1 208-208 208S16 418.9 16 304c0-104 76.3-190.2 176-205.5V64h-28c-6.6 0-12-5.4-12-12V12c0-6.6 5.4-12 12-12h120c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-28v34.5c37.5 5.8 71.7 21.6 99.7 44.6l27.5-27.5c4.7-4.7 12.3-4.7 17 0l28.3 28.3c4.7 4.7 4.7 12.3 0 17l-29.4 29.4-.6.6C419.7 223.3 432 262.2 432 304zm-176 36V188.5c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12V340c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"store\": [616, 512, [], \"f54e\", \"M602 118.6L537.1 15C531.3 5.7 521 0 510 0H106C95 0 84.7 5.7 78.9 15L14 118.6c-33.5 53.5-3.8 127.9 58.8 136.4 4.5.6 9.1.9 13.7.9 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18.1 20.1 44.3 33.1 73.8 33.1 4.7 0 9.2-.3 13.7-.9 62.8-8.4 92.6-82.8 59-136.4zM529.5 288c-10 0-19.9-1.5-29.5-3.8V384H116v-99.8c-9.6 2.2-19.5 3.8-29.5 3.8-6 0-12.1-.4-18-1.2-5.6-.8-11.1-2.1-16.4-3.6V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32V283.2c-5.4 1.6-10.8 2.9-16.4 3.6-6.1.8-12.1 1.2-18.2 1.2z\"],\n    \"store-alt\": [640, 512, [], \"f54f\", \"M320 384H128V224H64v256c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V224h-64v160zm314.6-241.8l-85.3-128c-6-8.9-16-14.2-26.7-14.2H117.4c-10.7 0-20.7 5.3-26.6 14.2l-85.3 128c-14.2 21.3 1 49.8 26.6 49.8H608c25.5 0 40.7-28.5 26.6-49.8zM512 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V224h-64v272z\"],\n    \"stream\": [512, 512, [], \"f550\", \"M16 128h416c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H16C7.16 32 0 39.16 0 48v64c0 8.84 7.16 16 16 16zm480 80H80c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm-64 176H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16z\"],\n    \"street-view\": [512, 512, [], \"f21d\", \"M367.9 329.76c-4.62 5.3-9.78 10.1-15.9 13.65v22.94c66.52 9.34 112 28.05 112 49.65 0 30.93-93.12 56-208 56S48 446.93 48 416c0-21.6 45.48-40.3 112-49.65v-22.94c-6.12-3.55-11.28-8.35-15.9-13.65C58.87 345.34 0 378.05 0 416c0 53.02 114.62 96 256 96s256-42.98 256-96c0-37.95-58.87-70.66-144.1-86.24zM256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-64 192v96c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-96c17.67 0 32-14.33 32-32v-96c0-26.51-21.49-48-48-48h-11.8c-11.07 5.03-23.26 8-36.2 8s-25.13-2.97-36.2-8H208c-26.51 0-48 21.49-48 48v96c0 17.67 14.33 32 32 32z\"],\n    \"strikethrough\": [512, 512, [], \"f0cc\", \"M496 224H293.9l-87.17-26.83A43.55 43.55 0 0 1 219.55 112h66.79A49.89 49.89 0 0 1 331 139.58a16 16 0 0 0 21.46 7.15l42.94-21.47a16 16 0 0 0 7.16-21.46l-.53-1A128 128 0 0 0 287.51 32h-68a123.68 123.68 0 0 0-123 135.64c2 20.89 10.1 39.83 21.78 56.36H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-180.24 96A43 43 0 0 1 336 356.45 43.59 43.59 0 0 1 292.45 400h-66.79A49.89 49.89 0 0 1 181 372.42a16 16 0 0 0-21.46-7.15l-42.94 21.47a16 16 0 0 0-7.16 21.46l.53 1A128 128 0 0 0 224.49 480h68a123.68 123.68 0 0 0 123-135.64 114.25 114.25 0 0 0-5.34-24.36z\"],\n    \"stroopwafel\": [512, 512, [], \"f551\", \"M188.12 210.74L142.86 256l45.25 45.25L233.37 256l-45.25-45.26zm113.13-22.62L256 142.86l-45.25 45.25L256 233.37l45.25-45.25zm-90.5 135.76L256 369.14l45.26-45.26L256 278.63l-45.25 45.25zM256 0C114.62 0 0 114.62 0 256s114.62 256 256 256 256-114.62 256-256S397.38 0 256 0zm186.68 295.6l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-28.29-28.29-45.25 45.25 33.94 33.94 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-33.94-33.94-45.26 45.26 28.29 28.29c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0L256 414.39l-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l28.29-28.29-45.25-45.26-33.94 33.94 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 33.94-33.94-45.25-45.25-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0L69.32 295.6c-3.12-3.12-3.12-8.19 0-11.31L97.61 256l-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l28.29 28.29 45.25-45.26-33.94-33.94-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 33.94 33.94 45.26-45.25-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0L256 97.61l28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-28.29 28.29 45.26 45.25 33.94-33.94-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-33.94 33.94 45.25 45.26 28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31L414.39 256l28.29 28.28a8.015 8.015 0 0 1 0 11.32zM278.63 256l45.26 45.25L369.14 256l-45.25-45.26L278.63 256z\"],\n    \"subscript\": [512, 512, [], \"f12c\", \"M496 448h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 352h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"subway\": [448, 512, [], \"f239\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zM200 232V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm200 0V120c0-13.255-10.745-24-24-24H272c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm-48 56c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm-256 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"suitcase\": [512, 512, [], \"f0f2\", \"M128 480h256V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v400zm64-384h128v32H192V96zm320 80v256c0 26.5-21.5 48-48 48h-48V128h48c26.5 0 48 21.5 48 48zM96 480H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h48v352z\"],\n    \"suitcase-rolling\": [384, 512, [], \"f5c1\", \"M336 160H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h16v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h128v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h16c26.51 0 48-21.49 48-48V208c0-26.51-21.49-48-48-48zm-16 216c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zM144 48h96v80h48V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v80h48V48z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M256 160c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm246.4 80.5l-94.7-47.3 33.5-100.4c4.5-13.6-8.4-26.5-21.9-21.9l-100.4 33.5-47.4-94.8c-6.4-12.8-24.6-12.8-31 0l-47.3 94.7L92.7 70.8c-13.6-4.5-26.5 8.4-21.9 21.9l33.5 100.4-94.7 47.4c-12.8 6.4-12.8 24.6 0 31l94.7 47.3-33.5 100.5c-4.5 13.6 8.4 26.5 21.9 21.9l100.4-33.5 47.3 94.7c6.4 12.8 24.6 12.8 31 0l47.3-94.7 100.4 33.5c13.6 4.5 26.5-8.4 21.9-21.9l-33.5-100.4 94.7-47.3c13-6.5 13-24.7.2-31.1zm-155.9 106c-49.9 49.9-131.1 49.9-181 0-49.9-49.9-49.9-131.1 0-181 49.9-49.9 131.1-49.9 181 0 49.9 49.9 49.9 131.1 0 181z\"],\n    \"superscript\": [512, 512, [], \"f12b\", \"M496 160h-16V16a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 64h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm112 208c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm80-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"swatchbook\": [511, 512, [], \"f5c3\", \"M479.06 320H372.29L186.15 506.51c-2.06 2.07-4.49 3.58-6.67 5.49h299.58c17.64 0 31.94-14.33 31.94-32V352c0-17.67-14.3-32-31.94-32zm-44.5-152.9l-90.33-90.51c-12.47-12.5-32.69-12.5-45.17 0l-75.5 75.65V416c0 2.96-.67 5.73-.87 8.64l211.87-212.28c12.47-12.5 12.47-32.77 0-45.26zM191.62 32c0-17.67-14.3-32-31.94-32H31.94C14.3 0 0 14.33 0 32v384c0 53.02 42.9 96 95.81 96s95.81-42.98 95.81-96V32zM95.81 440c-13.23 0-23.95-10.75-23.95-24 0-13.26 10.73-24 23.95-24s23.95 10.74 23.95 24c.01 13.25-10.72 24-23.95 24zm31.94-184H63.88v-64h63.88v64zm0-128H63.88V64h63.88v64z\"],\n    \"swimmer\": [640, 512, [], \"f5c4\", \"M189.61 310.58c3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c16.02-14.77 34.5-22.58 53.46-22.58h16.3c18.96 0 37.45 7.81 53.46 22.58 3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c14.86-13.71 31.88-21.12 49.39-22.16l-112.84-80.6 18-12.86c3.64-2.58 8.28-3.52 12.62-2.61l100.35 21.53c25.91 5.53 51.44-10.97 57-36.88 5.55-25.92-10.95-51.44-36.88-57L437.68 98.47c-30.73-6.58-63.02.12-88.56 18.38l-80.02 57.17c-10.38 7.39-19.36 16.44-26.72 26.94L173.75 299c5.47 3.23 10.82 6.93 15.86 11.58zM624 352h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 343.58 442.04 352 416 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 343.58 250.04 352 224 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 343.58 58.04 352 32 352H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-512-96c44.18 0 80-35.82 80-80s-35.82-80-80-80-80 35.82-80 80 35.82 80 80 80z\"],\n    \"swimming-pool\": [640, 512, [], \"f5c5\", \"M624 416h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 407.58 442.04 416 416 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 407.58 250.04 416 224 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 407.58 58.04 416 32 416H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-400-32v-96h192v96c19.12 0 30.86-6.16 34.39-9.42 9.17-8.46 19.2-14.34 29.61-18.07V128c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v96H224v-96c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v228.5c10.41 3.73 20.44 9.62 29.61 18.07 3.53 3.27 15.27 9.43 34.39 9.43z\"],\n    \"synagogue\": [640, 512, [], \"f69b\", \"M70 196.51L6.67 268.29A26.643 26.643 0 0 0 0 285.93V512h128V239.58l-38-43.07c-5.31-6.01-14.69-6.01-20 0zm563.33 71.78L570 196.51c-5.31-6.02-14.69-6.02-20 0l-38 43.07V512h128V285.93c0-6.5-2.37-12.77-6.67-17.64zM339.99 7.01c-11.69-9.35-28.29-9.35-39.98 0l-128 102.4A32.005 32.005 0 0 0 160 134.4V512h96v-92.57c0-31.88 21.78-61.43 53.25-66.55C349.34 346.35 384 377.13 384 416v96h96V134.4c0-9.72-4.42-18.92-12.01-24.99l-128-102.4zm52.07 215.55c1.98 3.15-.29 7.24-4 7.24h-38.94L324 269.79c-1.85 2.95-6.15 2.95-8 0l-25.12-39.98h-38.94c-3.72 0-5.98-4.09-4-7.24l19.2-30.56-19.2-30.56c-1.98-3.15.29-7.24 4-7.24h38.94l25.12-40c1.85-2.95 6.15-2.95 8 0l25.12 39.98h38.95c3.71 0 5.98 4.09 4 7.24L372.87 192l19.19 30.56z\"],\n    \"sync\": [512, 512, [], \"f021\", \"M440.65 12.57l4 82.77A247.16 247.16 0 0 0 255.83 8C134.73 8 33.91 94.92 12.29 209.82A12 12 0 0 0 24.09 224h49.05a12 12 0 0 0 11.67-9.26 175.91 175.91 0 0 1 317-56.94l-101.46-4.86a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12H500a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12h-47.37a12 12 0 0 0-11.98 12.57zM255.83 432a175.61 175.61 0 0 1-146-77.8l101.8 4.87a12 12 0 0 0 12.57-12v-47.4a12 12 0 0 0-12-12H12a12 12 0 0 0-12 12V500a12 12 0 0 0 12 12h47.35a12 12 0 0 0 12-12.6l-4.15-82.57A247.17 247.17 0 0 0 255.83 504c121.11 0 221.93-86.92 243.55-201.82a12 12 0 0 0-11.8-14.18h-49.05a12 12 0 0 0-11.67 9.26A175.86 175.86 0 0 1 255.83 432z\"],\n    \"sync-alt\": [512, 512, [], \"f2f1\", \"M370.72 133.28C339.458 104.008 298.888 87.962 255.848 88c-77.458.068-144.328 53.178-162.791 126.85-1.344 5.363-6.122 9.15-11.651 9.15H24.103c-7.498 0-13.194-6.807-11.807-14.176C33.933 94.924 134.813 8 256 8c66.448 0 126.791 26.136 171.315 68.685L463.03 40.97C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.749zM32 296h134.059c21.382 0 32.09 25.851 16.971 40.971l-41.75 41.75c31.262 29.273 71.835 45.319 114.876 45.28 77.418-.07 144.315-53.144 162.787-126.849 1.344-5.363 6.122-9.15 11.651-9.15h57.304c7.498 0 13.194 6.807 11.807 14.176C478.067 417.076 377.187 504 256 504c-66.448 0-126.791-26.136-171.315-68.685L48.97 471.03C33.851 486.149 8 475.441 8 454.059V320c0-13.255 10.745-24 24-24z\"],\n    \"syringe\": [512, 512, [], \"f48e\", \"M201.5 174.8l55.7 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-55.7-55.8-45.3 45.3 55.8 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L111 265.2l-26.4 26.4c-17.3 17.3-25.6 41.1-23 65.4l7.1 63.6L2.3 487c-3.1 3.1-3.1 8.2 0 11.3l11.3 11.3c3.1 3.1 8.2 3.1 11.3 0l66.3-66.3 63.6 7.1c23.9 2.6 47.9-5.4 65.4-23l181.9-181.9-135.7-135.7-64.9 65zm308.2-93.3L430.5 2.3c-3.1-3.1-8.2-3.1-11.3 0l-11.3 11.3c-3.1 3.1-3.1 8.2 0 11.3l28.3 28.3-45.3 45.3-56.6-56.6-17-17c-3.1-3.1-8.2-3.1-11.3 0l-33.9 33.9c-3.1 3.1-3.1 8.2 0 11.3l17 17L424.8 223l17 17c3.1 3.1 8.2 3.1 11.3 0l33.9-34c3.1-3.1 3.1-8.2 0-11.3l-73.5-73.5 45.3-45.3 28.3 28.3c3.1 3.1 8.2 3.1 11.3 0l11.3-11.3c3.1-3.2 3.1-8.2 0-11.4z\"],\n    \"table\": [512, 512, [], \"f0ce\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64v-96h160v96zm0-160H64v-96h160v96zm224 160H288v-96h160v96zm0-160H288v-96h160v96z\"],\n    \"table-tennis\": [512, 512, [], \"f45d\", \"M496.2 296.5C527.7 218.7 512 126.2 449 63.1 365.1-21 229-21 145.1 63.1l-56 56.1 211.5 211.5c46.1-62.1 131.5-77.4 195.6-34.2zm-217.9 79.7L57.9 155.9c-27.3 45.3-21.7 105 17.3 144.1l34.5 34.6L6.7 424c-8.6 7.5-9.1 20.7-1 28.8l53.4 53.5c8 8.1 21.2 7.6 28.7-1L177.1 402l35.7 35.7c19.7 19.7 44.6 30.5 70.3 33.3-7.1-17-11-35.6-11-55.1-.1-13.8 2.5-27 6.2-39.7zM416 320c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96z\"],\n    \"tablet\": [448, 512, [], \"f10a\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"tablet-alt\": [448, 512, [], \"f3fa\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm176-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h328c6.6 0 12 5.4 12 12v312z\"],\n    \"tablets\": [640, 512, [], \"f490\", \"M160 192C78.9 192 12.5 250.5.1 326.7c-.8 4.8 3.3 9.3 8.3 9.3h303.3c5 0 9.1-4.5 8.3-9.3C307.5 250.5 241.1 192 160 192zm151.6 176H8.4c-5 0-9.1 4.5-8.3 9.3C12.5 453.5 78.9 512 160 512s147.5-58.5 159.9-134.7c.8-4.8-3.3-9.3-8.3-9.3zM593.4 46.6c-56.5-56.5-144.2-61.4-206.9-16-4 2.9-4.3 8.9-.8 12.3L597 254.3c3.5 3.5 9.5 3.2 12.3-.8 45.5-62.7 40.6-150.4-15.9-206.9zM363 65.7c-3.5-3.5-9.5-3.2-12.3.8-45.4 62.7-40.5 150.4 15.9 206.9 56.5 56.5 144.2 61.4 206.9 15.9 4-2.9 4.3-8.9.8-12.3L363 65.7z\"],\n    \"tachometer-alt\": [576, 512, [], \"f3fd\", \"M288 32C128.94 32 0 160.94 0 320c0 52.8 14.25 102.26 39.06 144.8 5.61 9.62 16.3 15.2 27.44 15.2h443c11.14 0 21.83-5.58 27.44-15.2C561.75 422.26 576 372.8 576 320c0-159.06-128.94-288-288-288zm0 64c14.71 0 26.58 10.13 30.32 23.65-1.11 2.26-2.64 4.23-3.45 6.67l-9.22 27.67c-5.13 3.49-10.97 6.01-17.64 6.01-17.67 0-32-14.33-32-32S270.33 96 288 96zM96 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm48-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm246.77-72.41l-61.33 184C343.13 347.33 352 364.54 352 384c0 11.72-3.38 22.55-8.88 32H232.88c-5.5-9.45-8.88-20.28-8.88-32 0-33.94 26.5-61.43 59.9-63.59l61.34-184.01c4.17-12.56 17.73-19.45 30.36-15.17 12.57 4.19 19.35 17.79 15.17 30.36zm14.66 57.2l15.52-46.55c3.47-1.29 7.13-2.23 11.05-2.23 17.67 0 32 14.33 32 32s-14.33 32-32 32c-11.38-.01-20.89-6.28-26.57-15.22zM480 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"tag\": [512, 512, [], \"f02b\", \"M0 252.118V48C0 21.49 21.49 0 48 0h204.118a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882L293.823 497.941c-18.745 18.745-49.137 18.745-67.882 0L14.059 286.059A48 48 0 0 1 0 252.118zM112 64c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"tags\": [640, 512, [], \"f02c\", \"M497.941 225.941L286.059 14.059A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v204.118a48 48 0 0 0 14.059 33.941l211.882 211.882c18.744 18.745 49.136 18.746 67.882 0l204.118-204.118c18.745-18.745 18.745-49.137 0-67.882zM112 160c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm513.941 133.823L421.823 497.941c-18.745 18.745-49.137 18.745-67.882 0l-.36-.36L527.64 323.522c16.999-16.999 26.36-39.6 26.36-63.64s-9.362-46.641-26.36-63.64L331.397 0h48.721a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882z\"],\n    \"tape\": [640, 512, [], \"f4db\", \"M224 192c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm400 224H380.6c41.5-40.7 67.4-97.3 67.4-160 0-123.7-100.3-224-224-224S0 132.3 0 256s100.3 224 224 224h400c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400-64c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96z\"],\n    \"tasks\": [512, 512, [], \"f0ae\", \"M139.61 35.5a12 12 0 0 0-17 0L58.93 98.81l-22.7-22.12a12 12 0 0 0-17 0L3.53 92.41a12 12 0 0 0 0 17l47.59 47.4a12.78 12.78 0 0 0 17.61 0l15.59-15.62L156.52 69a12.09 12.09 0 0 0 .09-17zm0 159.19a12 12 0 0 0-17 0l-63.68 63.72-22.7-22.1a12 12 0 0 0-17 0L3.53 252a12 12 0 0 0 0 17L51 316.5a12.77 12.77 0 0 0 17.6 0l15.7-15.69 72.2-72.22a12 12 0 0 0 .09-16.9zM64 368c-26.49 0-48.59 21.5-48.59 48S37.53 464 64 464a48 48 0 0 0 0-96zm432 16H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"taxi\": [512, 512, [], \"f1ba\", \"M462 241.64l-22-84.84c-9.6-35.2-41.6-60.8-76.8-60.8H352V64c0-17.67-14.33-32-32-32H192c-17.67 0-32 14.33-32 32v32h-11.2c-35.2 0-67.2 25.6-76.8 60.8l-22 84.84C21.41 248.04 0 273.47 0 304v48c0 23.63 12.95 44.04 32 55.12V448c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-40.88c19.05-11.09 32-31.5 32-55.12v-48c0-30.53-21.41-55.96-50-62.36zM96 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm20.55-112l17.2-66.36c2.23-8.16 9.59-13.64 15.06-13.64h214.4c5.47 0 12.83 5.48 14.85 12.86L395.45 240h-278.9zM416 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"teeth\": [640, 512, [], \"f62e\", \"M544 0H96C42.98 0 0 42.98 0 96v320c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96zM160 368c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm128 128c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64z\"],\n    \"teeth-open\": [640, 512, [], \"f62f\", \"M544 0H96C42.98 0 0 42.98 0 96v64c0 35.35 28.66 64 64 64h512c35.34 0 64-28.65 64-64V96c0-53.02-42.98-96-96-96zM160 176c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm128 0c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm0 144H64c-35.34 0-64 28.65-64 64v32c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96v-32c0-35.35-28.66-64-64-64zm-416 80c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32zm144-8c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm144 0c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm128 8c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32z\"],\n    \"temperature-high\": [512, 512, [], \"f769\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V112c0-8.8-7.2-16-16-16s-16 7.2-16 16v210.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"temperature-low\": [512, 512, [], \"f76b\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V304c0-8.8-7.2-16-16-16s-16 7.2-16 16v18.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"tenge\": [384, 512, [], \"f7d7\", \"M372 160H12c-6.6 0-12 5.4-12 12v56c0 6.6 5.4 12 12 12h140v228c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12V240h140c6.6 0 12-5.4 12-12v-56c0-6.6-5.4-12-12-12zm0-128H12C5.4 32 0 37.4 0 44v56c0 6.6 5.4 12 12 12h360c6.6 0 12-5.4 12-12V44c0-6.6-5.4-12-12-12z\"],\n    \"terminal\": [640, 512, [], \"f120\", \"M257.981 272.971L63.638 467.314c-9.373 9.373-24.569 9.373-33.941 0L7.029 444.647c-9.357-9.357-9.375-24.522-.04-33.901L161.011 256 6.99 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L257.981 239.03c9.373 9.372 9.373 24.568 0 33.941zM640 456v-32c0-13.255-10.745-24-24-24H312c-13.255 0-24 10.745-24 24v32c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24z\"],\n    \"text-height\": [576, 512, [], \"f034\", \"M304 32H16A16 16 0 0 0 0 48v96a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32h56v304H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h160a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-40V112h56v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm256 336h-48V144h48c14.31 0 21.33-17.31 11.31-27.31l-80-80a16 16 0 0 0-22.62 0l-80 80C379.36 126 384.36 144 400 144h48v224h-48c-14.31 0-21.32 17.31-11.31 27.31l80 80a16 16 0 0 0 22.62 0l80-80C580.64 386 575.64 368 560 368z\"],\n    \"text-width\": [448, 512, [], \"f035\", \"M432 32H16A16 16 0 0 0 0 48v80a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-16h120v112h-24a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-24V112h120v16a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm-68.69 260.69C354 283.36 336 288.36 336 304v48H112v-48c0-14.31-17.31-21.32-27.31-11.31l-80 80a16 16 0 0 0 0 22.62l80 80C94 484.64 112 479.64 112 464v-48h224v48c0 14.31 17.31 21.33 27.31 11.31l80-80a16 16 0 0 0 0-22.62z\"],\n    \"th\": [512, 512, [], \"f00a\", \"M149.333 56v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zm181.334 240v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm32-240v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24zm-32 80V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm-205.334 56H24c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm386.667-56H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm0 160H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zM181.333 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24z\"],\n    \"th-large\": [512, 512, [], \"f009\", \"M296 32h192c13.255 0 24 10.745 24 24v160c0 13.255-10.745 24-24 24H296c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24zm-80 0H24C10.745 32 0 42.745 0 56v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zM0 296v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm296 184h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H296c-13.255 0-24 10.745-24 24v160c0 13.255 10.745 24 24 24z\"],\n    \"th-list\": [512, 512, [], \"f00b\", \"M149.333 216v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-80c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zM125.333 32H24C10.745 32 0 42.745 0 56v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zm80 448H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm-24-424v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24zm24 264H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24z\"],\n    \"theater-masks\": [640, 512, [], \"f630\", \"M206.86 245.15c-35.88 10.45-59.95 41.2-57.53 74.1 11.4-12.72 28.81-23.7 49.9-30.92l7.63-43.18zM95.81 295L64.08 115.49c-.29-1.62.28-2.62.24-2.65 57.76-32.06 123.12-49.01 189.01-49.01 1.61 0 3.23.17 4.85.19 13.95-13.47 31.73-22.83 51.59-26 18.89-3.02 38.05-4.55 57.18-5.32-9.99-13.95-24.48-24.23-41.77-27C301.27 1.89 277.24 0 253.32 0 176.66 0 101.02 19.42 33.2 57.06 9.03 70.48-3.92 98.48 1.05 126.58l31.73 179.51c14.23 80.52 136.33 142.08 204.45 142.08 3.59 0 6.75-.46 10.01-.8-13.52-17.08-28.94-40.48-39.5-67.58-47.61-12.98-106.06-51.62-111.93-84.79zm97.55-137.46c-.73-4.12-2.23-7.87-4.07-11.4-8.25 8.91-20.67 15.75-35.32 18.32-14.65 2.58-28.67.4-39.48-5.17-.52 3.94-.64 7.98.09 12.1 3.84 21.7 24.58 36.19 46.34 32.37 21.75-3.82 36.28-24.52 32.44-46.22zM606.8 120.9c-88.98-49.38-191.43-67.41-291.98-51.35-27.31 4.36-49.08 26.26-54.04 54.36l-31.73 179.51c-15.39 87.05 95.28 196.27 158.31 207.35 63.03 11.09 204.47-53.79 219.86-140.84l31.73-179.51c4.97-28.11-7.98-56.11-32.15-69.52zm-273.24 96.8c3.84-21.7 24.58-36.19 46.34-32.36 21.76 3.83 36.28 24.52 32.45 46.22-.73 4.12-2.23 7.87-4.07 11.4-8.25-8.91-20.67-15.75-35.32-18.32-14.65-2.58-28.67-.4-39.48 5.17-.53-3.95-.65-7.99.08-12.11zm70.47 198.76c-55.68-9.79-93.52-59.27-89.04-112.9 20.6 25.54 56.21 46.17 99.49 53.78 43.28 7.61 83.82.37 111.93-16.6-14.18 51.94-66.71 85.51-122.38 75.72zm130.3-151.34c-8.25-8.91-20.68-15.75-35.33-18.32-14.65-2.58-28.67-.4-39.48 5.17-.52-3.94-.64-7.98.09-12.1 3.84-21.7 24.58-36.19 46.34-32.37 21.75 3.83 36.28 24.52 32.45 46.22-.73 4.13-2.23 7.88-4.07 11.4z\"],\n    \"thermometer\": [512, 512, [], \"f491\", \"M476.8 20.4c-37.5-30.7-95.5-26.3-131.9 10.2l-45.7 46 50.5 50.5c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.4-50.5-45.1 45.4 50.3 50.4c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L209 167.4l-45.1 45.4L214 263c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.1-50.2L96 281.1V382L7 471c-9.4 9.4-9.4 24.6 0 33.9 9.4 9.4 24.6 9.4 33.9 0l89-89h99.9L484 162.6c34.9-34.9 42.2-101.5-7.2-142.2z\"],\n    \"thermometer-empty\": [256, 512, [], \"f2cb\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-35.346 28.654-64 64-64s64 28.654 64 64zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-full\": [256, 512, [], \"f2c7\", \"M224 96c0-53.019-42.981-96-96-96S32 42.981 32 96v203.347C12.225 321.756.166 351.136.002 383.333c-.359 70.303 56.787 128.176 127.089 128.664.299.002.61.003.909.003 70.698 0 128-57.304 128-128 0-32.459-12.088-62.09-32-84.653V96zm-96 368l-.576-.002c-43.86-.304-79.647-36.544-79.423-80.42.173-33.98 19.266-51.652 31.999-66.08V96c0-26.467 21.533-48 48-48s48 21.533 48 48v221.498c12.63 14.312 32 32.164 32 66.502 0 44.112-35.888 80-80 80zm64-80c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V96c0-17.673 14.327-32 32-32s32 14.327 32 32v232.583c19.124 11.068 32 31.732 32 55.417z\"],\n    \"thermometer-half\": [256, 512, [], \"f2c9\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V224c0-17.673 14.327-32 32-32s32 14.327 32 32v104.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-quarter\": [256, 512, [], \"f2ca\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V288c0-17.673 14.327-32 32-32s32 14.327 32 32v40.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-three-quarters\": [256, 512, [], \"f2c8\", \"M192 384c0 35.346-28.654 64-64 64-35.346 0-64-28.654-64-64 0-23.685 12.876-44.349 32-55.417V160c0-17.673 14.327-32 32-32s32 14.327 32 32v168.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M0 56v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56zm40 200c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24zm272 256c-20.183 0-29.485-39.293-33.931-57.795-5.206-21.666-10.589-44.07-25.393-58.902-32.469-32.524-49.503-73.967-89.117-113.111a11.98 11.98 0 0 1-3.558-8.521V59.901c0-6.541 5.243-11.878 11.783-11.998 15.831-.29 36.694-9.079 52.651-16.178C256.189 17.598 295.709.017 343.995 0h2.844c42.777 0 93.363.413 113.774 29.737 8.392 12.057 10.446 27.034 6.148 44.632 16.312 17.053 25.063 48.863 16.382 74.757 17.544 23.432 19.143 56.132 9.308 79.469l.11.11c11.893 11.949 19.523 31.259 19.439 49.197-.156 30.352-26.157 58.098-59.553 58.098H350.723C358.03 364.34 384 388.132 384 430.548 384 504 336 512 312 512z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M104 224H24c-13.255 0-24 10.745-24 24v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V248c0-13.255-10.745-24-24-24zM64 472c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zM384 81.452c0 42.416-25.97 66.208-33.277 94.548h101.723c33.397 0 59.397 27.746 59.553 58.098.084 17.938-7.546 37.249-19.439 49.197l-.11.11c9.836 23.337 8.237 56.037-9.308 79.469 8.681 25.895-.069 57.704-16.382 74.757 4.298 17.598 2.244 32.575-6.148 44.632C440.202 511.587 389.616 512 346.839 512l-2.845-.001c-48.287-.017-87.806-17.598-119.56-31.725-15.957-7.099-36.821-15.887-52.651-16.178-6.54-.12-11.783-5.457-11.783-11.998v-213.77c0-3.2 1.282-6.271 3.558-8.521 39.614-39.144 56.648-80.587 89.117-113.111 14.804-14.832 20.188-37.236 25.393-58.902C282.515 39.293 291.817 0 312 0c24 0 72 8 72 81.452z\"],\n    \"thumbtack\": [384, 512, [], \"f08d\", \"M298.028 214.267L285.793 96H328c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v48c0 13.255 10.745 24 24 24h42.207L85.972 214.267C37.465 236.82 0 277.261 0 328c0 13.255 10.745 24 24 24h136v104.007c0 1.242.289 2.467.845 3.578l24 48c2.941 5.882 11.364 5.893 14.311 0l24-48a8.008 8.008 0 0 0 .845-3.578V352h136c13.255 0 24-10.745 24-24-.001-51.183-37.983-91.42-85.973-113.733z\"],\n    \"ticket-alt\": [576, 512, [], \"f3ff\", \"M128 160h320v192H128V160zm400 96c0 26.51 21.49 48 48 48v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c26.51 0 48-21.49 48-48s-21.49-48-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v96c-26.51 0-48 21.49-48 48zm-48-104c0-13.255-10.745-24-24-24H120c-13.255 0-24 10.745-24 24v208c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V152z\"],\n    \"times\": [352, 512, [], \"f00d\", \"M242.72 256l100.07-100.07c12.28-12.28 12.28-32.19 0-44.48l-22.24-22.24c-12.28-12.28-32.19-12.28-44.48 0L176 189.28 75.93 89.21c-12.28-12.28-32.19-12.28-44.48 0L9.21 111.45c-12.28 12.28-12.28 32.19 0 44.48L109.28 256 9.21 356.07c-12.28 12.28-12.28 32.19 0 44.48l22.24 22.24c12.28 12.28 32.2 12.28 44.48 0L176 322.72l100.07 100.07c12.28 12.28 32.2 12.28 44.48 0l22.24-22.24c12.28-12.28 12.28-32.19 0-44.48L242.72 256z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm121.6 313.1c4.7 4.7 4.7 12.3 0 17L338 377.6c-4.7 4.7-12.3 4.7-17 0L256 312l-65.1 65.6c-4.7 4.7-12.3 4.7-17 0L134.4 338c-4.7-4.7-4.7-12.3 0-17l65.6-65-65.6-65.1c-4.7-4.7-4.7-12.3 0-17l39.6-39.6c4.7-4.7 12.3-4.7 17 0l65 65.7 65.1-65.6c4.7-4.7 12.3-4.7 17 0l39.6 39.6c4.7 4.7 4.7 12.3 0 17L312 256l65.6 65.1z\"],\n    \"tint\": [352, 512, [], \"f043\", \"M205.22 22.09c-7.94-28.78-49.44-30.12-58.44 0C100.01 179.85 0 222.72 0 333.91 0 432.35 78.72 512 176 512s176-79.65 176-178.09c0-111.75-99.79-153.34-146.78-311.82zM176 448c-61.75 0-112-50.25-112-112 0-8.84 7.16-16 16-16s16 7.16 16 16c0 44.11 35.89 80 80 80 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"tint-slash\": [640, 512, [], \"f5c7\", \"M633.82 458.1L494.97 350.78c.52-5.57 1.03-11.16 1.03-16.87 0-111.76-99.79-153.34-146.78-311.82-7.94-28.78-49.44-30.12-58.44 0-15.52 52.34-36.87 91.96-58.49 125.68L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM144 333.91C144 432.35 222.72 512 320 512c44.71 0 85.37-16.96 116.4-44.7L162.72 255.78c-11.41 23.5-18.72 48.35-18.72 78.13z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 288c51.9 0 115.3 43.8 123.2 106.7 1.7 13.6-8 24.6-17.7 20.4-25.9-11.1-64.4-17.4-105.5-17.4s-79.6 6.3-105.5 17.4c-9.8 4.2-19.4-7-17.7-20.4C132.7 331.8 196.1 288 248 288z\"],\n    \"toggle-off\": [576, 512, [], \"f204\", \"M384 64H192C85.961 64 0 149.961 0 256s85.961 192 192 192h192c106.039 0 192-85.961 192-192S490.039 64 384 64zM64 256c0-70.741 57.249-128 128-128 70.741 0 128 57.249 128 128 0 70.741-57.249 128-128 128-70.741 0-128-57.249-128-128zm320 128h-48.905c65.217-72.858 65.236-183.12 0-256H384c70.741 0 128 57.249 128 128 0 70.74-57.249 128-128 128z\"],\n    \"toggle-on\": [576, 512, [], \"f205\", \"M384 64H192C86 64 0 150 0 256s86 192 192 192h192c106 0 192-86 192-192S490 64 384 64zm0 320c-70.8 0-128-57.3-128-128 0-70.8 57.3-128 128-128 70.8 0 128 57.3 128 128 0 70.8-57.3 128-128 128z\"],\n    \"toilet\": [384, 512, [], \"f7d8\", \"M368 48c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v16c0 8.8 7.2 16 16 16h16v156.7C11.8 214.8 0 226.9 0 240c0 67.2 34.6 126.2 86.8 160.5l-21.4 70.2C59.1 491.2 74.5 512 96 512h192c21.5 0 36.9-20.8 30.6-41.3l-21.4-70.2C349.4 366.2 384 307.2 384 240c0-13.1-11.8-25.2-32-35.3V48h16zM80 72c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H88c-4.4 0-8-3.6-8-8V72zm112 200c-77.1 0-139.6-14.3-139.6-32s62.5-32 139.6-32 139.6 14.3 139.6 32-62.5 32-139.6 32z\"],\n    \"toilet-paper\": [576, 512, [], \"f71e\", \"M128 0C74.98 0 32 85.96 32 192v172.07c0 41.12-9.8 62.77-31.17 126.87C-2.62 501.3 5.09 512 16.01 512h280.92c13.77 0 26-8.81 30.36-21.88 12.83-38.48 24.71-72.4 24.71-126.05V192c0-83.6 23.67-153.52 60.44-192H128zM96 224c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM480 0c-53.02 0-96 85.96-96 192s42.98 192 96 192 96-85.96 96-192S533.02 0 480 0zm0 256c-17.67 0-32-28.65-32-64s14.33-64 32-64 32 28.65 32 64-14.33 64-32 64z\"],\n    \"toolbox\": [512, 512, [], \"f552\", \"M502.63 214.63l-45.25-45.25c-6-6-14.14-9.37-22.63-9.37H384V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v80H77.25c-8.49 0-16.62 3.37-22.63 9.37L9.37 214.63c-6 6-9.37 14.14-9.37 22.63V320h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-82.75c0-8.48-3.37-16.62-9.37-22.62zM320 160H192V96h128v64zm64 208c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H192v16c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H0v96c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-96H384v16z\"],\n    \"tools\": [512, 512, [], \"f7d9\", \"M501.1 395.7L384 278.6c-23.1-23.1-57.6-27.6-85.4-13.9L192 158.1V96L64 0 0 64l96 128h62.1l106.6 106.6c-13.6 27.8-9.2 62.3 13.9 85.4l117.1 117.1c14.6 14.6 38.2 14.6 52.7 0l52.7-52.7c14.5-14.6 14.5-38.2 0-52.7zM331.7 225c28.3 0 54.9 11 74.9 31l19.4 19.4c15.8-6.9 30.8-16.5 43.8-29.5 37.1-37.1 49.7-89.3 37.9-136.7-2.2-9-13.5-12.1-20.1-5.5l-74.4 74.4-67.9-11.3L334 98.9l74.4-74.4c6.6-6.6 3.4-17.9-5.7-20.2-47.4-11.7-99.6.9-136.6 37.9-28.5 28.5-41.9 66.1-41.2 103.6l82.1 82.1c8.1-1.9 16.5-2.9 24.7-2.9zm-103.9 82l-56.7-56.7L18.7 402.8c-25 25-25 65.5 0 90.5s65.5 25 90.5 0l123.6-123.6c-7.6-19.9-9.9-41.6-5-62.7zM64 472c-13.2 0-24-10.8-24-24 0-13.3 10.7-24 24-24s24 10.7 24 24c0 13.2-10.7 24-24 24z\"],\n    \"tooth\": [448, 512, [], \"f5c9\", \"M443.98 96.25c-11.01-45.22-47.11-82.06-92.01-93.72-32.19-8.36-63 5.1-89.14 24.33-3.25 2.39-6.96 3.73-10.5 5.48l28.32 18.21c7.42 4.77 9.58 14.67 4.8 22.11-4.46 6.95-14.27 9.86-22.11 4.8L162.83 12.84c-20.7-10.85-43.38-16.4-66.81-10.31-44.9 11.67-81 48.5-92.01 93.72-10.13 41.62-.42 80.81 21.5 110.43 23.36 31.57 32.68 68.66 36.29 107.35 4.4 47.16 10.33 94.16 20.94 140.32l7.8 33.95c3.19 13.87 15.49 23.7 29.67 23.7 13.97 0 26.15-9.55 29.54-23.16l34.47-138.42c4.56-18.32 20.96-31.16 39.76-31.16s35.2 12.85 39.76 31.16l34.47 138.42c3.39 13.61 15.57 23.16 29.54 23.16 14.18 0 26.48-9.83 29.67-23.7l7.8-33.95c10.61-46.15 16.53-93.16 20.94-140.32 3.61-38.7 12.93-75.78 36.29-107.35 21.95-29.61 31.66-68.8 21.53-110.43z\"],\n    \"torah\": [640, 512, [], \"f6a0\", \"M320.05 366.48l17.72-29.64h-35.46zm99.21-166H382.4l18.46 30.82zM48 0C21.49 0 0 14.33 0 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32C96 14.33 74.51 0 48 0zm172.74 311.5h36.85l-18.46-30.82zm161.71 0h36.86l-18.45-30.8zM128 464h384V48H128zm66.77-278.13a21.22 21.22 0 0 1 18.48-10.71h59.45l29.13-48.71a21.13 21.13 0 0 1 18.22-10.37A20.76 20.76 0 0 1 338 126.29l29.25 48.86h59.52a21.12 21.12 0 0 1 18.1 32L415.63 256 445 305a20.69 20.69 0 0 1 .24 21.12 21.25 21.25 0 0 1-18.48 10.72h-59.47l-29.13 48.7a21.13 21.13 0 0 1-18.16 10.4 20.79 20.79 0 0 1-18-10.22l-29.25-48.88h-59.5a21.11 21.11 0 0 1-18.1-32L224.36 256 195 207a20.7 20.7 0 0 1-.23-21.13zM592 0c-26.51 0-48 14.33-48 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32c0-17.67-21.49-32-48-32zM320 145.53l-17.78 29.62h35.46zm-62.45 55h-36.81l18.44 30.8zm29.58 111h65.79L386.09 256l-33.23-55.52h-65.79L253.9 256z\"],\n    \"torii-gate\": [512, 512, [], \"f6a1\", \"M376.45 32h-240.9A303.17 303.17 0 0 1 0 0v96c0 17.67 14.33 32 32 32h32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h256v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h48c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-48v-64h32c17.67 0 32-14.33 32-32V0a303.17 303.17 0 0 1-135.55 32zM128 128h96v64h-96v-64zm256 64h-96v-64h96v64z\"],\n    \"tractor\": [640, 512, [], \"f722\", \"M528 336c-48.6 0-88 39.4-88 88s39.4 88 88 88 88-39.4 88-88-39.4-88-88-88zm0 112c-13.23 0-24-10.77-24-24s10.77-24 24-24 24 10.77 24 24-10.77 24-24 24zm80-288h-64v-40.2c0-14.12 4.7-27.76 13.15-38.84 4.42-5.8 3.55-14.06-1.32-19.49L534.2 37.3c-6.66-7.45-18.32-6.92-24.7.78C490.58 60.9 480 89.81 480 119.8V160H377.67L321.58 29.14A47.914 47.914 0 0 0 277.45 0H144c-26.47 0-48 21.53-48 48v146.52c-8.63-6.73-20.96-6.46-28.89 1.47L36 227.1c-8.59 8.59-8.59 22.52 0 31.11l5.06 5.06c-4.99 9.26-8.96 18.82-11.91 28.72H22c-12.15 0-22 9.85-22 22v44c0 12.15 9.85 22 22 22h7.14c2.96 9.91 6.92 19.46 11.91 28.73l-5.06 5.06c-8.59 8.59-8.59 22.52 0 31.11L67.1 476c8.59 8.59 22.52 8.59 31.11 0l5.06-5.06c9.26 4.99 18.82 8.96 28.72 11.91V490c0 12.15 9.85 22 22 22h44c12.15 0 22-9.85 22-22v-7.14c9.9-2.95 19.46-6.92 28.72-11.91l5.06 5.06c8.59 8.59 22.52 8.59 31.11 0l31.11-31.11c8.59-8.59 8.59-22.52 0-31.11l-5.06-5.06c4.99-9.26 8.96-18.82 11.91-28.72H330c12.15 0 22-9.85 22-22v-6h80.54c21.91-28.99 56.32-48 95.46-48 18.64 0 36.07 4.61 51.8 12.2l50.82-50.82c6-6 9.37-14.14 9.37-22.63V192c.01-17.67-14.32-32-31.99-32zM176 416c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm22-256h-38V64h106.89l41.15 96H198z\"],\n    \"trademark\": [640, 512, [], \"f25c\", \"M260.6 96H12c-6.6 0-12 5.4-12 12v43.1c0 6.6 5.4 12 12 12h85.1V404c0 6.6 5.4 12 12 12h54.3c6.6 0 12-5.4 12-12V163.1h85.1c6.6 0 12-5.4 12-12V108c.1-6.6-5.3-12-11.9-12zM640 403l-24-296c-.5-6.2-5.7-11-12-11h-65.4c-5.1 0-9.7 3.3-11.3 8.1l-43.8 127.1c-7.2 20.6-16.1 52.8-16.1 52.8h-.9s-8.9-32.2-16.1-52.8l-43.8-127.1c-1.7-4.8-6.2-8.1-11.3-8.1h-65.4c-6.2 0-11.4 4.8-12 11l-24.4 296c-.6 7 4.9 13 12 13H360c6.3 0 11.5-4.9 12-11.2l9.1-132.9c1.8-24.2 0-53.7 0-53.7h.9s10.7 33.6 17.9 53.7l30.7 84.7c1.7 4.7 6.2 7.9 11.3 7.9h50.3c5.1 0 9.6-3.2 11.3-7.9l30.7-84.7c7.2-20.1 17.9-53.7 17.9-53.7h.9s-1.8 29.5 0 53.7l9.1 132.9c.4 6.3 5.7 11.2 12 11.2H628c7 0 12.5-6 12-13z\"],\n    \"traffic-light\": [384, 512, [], \"f637\", \"M384 192h-64v-37.88c37.2-13.22 64-48.38 64-90.12h-64V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v32H0c0 41.74 26.8 76.9 64 90.12V192H0c0 41.74 26.8 76.9 64 90.12V320H0c0 42.84 28.25 78.69 66.99 91.05C79.42 468.72 130.6 512 192 512s112.58-43.28 125.01-100.95C355.75 398.69 384 362.84 384 320h-64v-37.88c37.2-13.22 64-48.38 64-90.12zM192 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"train\": [448, 512, [], \"f238\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zm-48 136V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24zm-176 64c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56z\"],\n    \"tram\": [512, 512, [], \"f7da\", \"M288 64c17.7 0 32-14.3 32-32S305.7 0 288 0s-32 14.3-32 32 14.3 32 32 32zm223.5-12.1c-2.3-8.6-11-13.6-19.6-11.3l-480 128c-8.5 2.3-13.6 11-11.3 19.6C2.5 195.3 8.9 200 16 200c1.4 0 2.8-.2 4.1-.5L240 140.8V224H64c-17.7 0-32 14.3-32 32v224c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32H272v-91.7l228.1-60.8c8.6-2.3 13.6-11.1 11.4-19.6zM176 384H80v-96h96v96zm160-96h96v96h-96v-96zm-32 0v96h-96v-96h96zM192 96c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"transgender\": [384, 512, [], \"f224\", \"M372 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C198.5 104.1 172.2 96 144 96 64.5 96 0 160.5 0 240c0 68.5 47.9 125.9 112 140.4V408H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM144 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"transgender-alt\": [480, 512, [], \"f225\", \"M468 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C294.5 104.1 268.2 96 240 96c-28.2 0-54.5 8.1-76.7 22.1l-16.5-16.5 19.8-19.8c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0l-19.8 19.8-19-19 16.9-16.9C107.1 12.9 101.7 0 91 0H12C5.4 0 0 5.4 0 12v79c0 10.7 12.9 16 20.5 8.5l16.9-16.9 19 19-19.8 19.8c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l19.8-19.8 16.5 16.5C104.1 185.5 96 211.8 96 240c0 68.5 47.9 125.9 112 140.4V408h-36c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM240 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"trash\": [448, 512, [], \"f1f8\", \"M432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm272-256a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore\": [448, 512, [], \"f829\", \"M53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32zm70.11-175.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore-alt\": [448, 512, [], \"f82a\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm91.31-172.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"tree\": [384, 512, [], \"f1bb\", \"M378.31 378.49L298.42 288h30.63c9.01 0 16.98-5 20.78-13.06 3.8-8.04 2.55-17.26-3.28-24.05L268.42 160h28.89c9.1 0 17.3-5.35 20.86-13.61 3.52-8.13 1.86-17.59-4.24-24.08L203.66 4.83c-6.03-6.45-17.28-6.45-23.32 0L70.06 122.31c-6.1 6.49-7.75 15.95-4.24 24.08C69.38 154.65 77.59 160 86.69 160h28.89l-78.14 90.91c-5.81 6.78-7.06 15.99-3.27 24.04C37.97 283 45.93 288 54.95 288h30.63L5.69 378.49c-6 6.79-7.36 16.09-3.56 24.26 3.75 8.05 12 13.25 21.01 13.25H160v24.45l-30.29 48.4c-5.32 10.64 2.42 23.16 14.31 23.16h95.96c11.89 0 19.63-12.52 14.31-23.16L224 440.45V416h136.86c9.01 0 17.26-5.2 21.01-13.25 3.8-8.17 2.44-17.47-3.56-24.26z\"],\n    \"trophy\": [576, 512, [], \"f091\", \"M552 64H448V24c0-13.3-10.7-24-24-24H152c-13.3 0-24 10.7-24 24v40H24C10.7 64 0 74.7 0 88v56c0 35.7 22.5 72.4 61.9 100.7 31.5 22.7 69.8 37.1 110 41.7C203.3 338.5 240 360 240 360v72h-48c-35.3 0-64 20.7-64 56v12c0 6.6 5.4 12 12 12h296c6.6 0 12-5.4 12-12v-12c0-35.3-28.7-56-64-56h-48v-72s36.7-21.5 68.1-73.6c40.3-4.6 78.6-19 110-41.7 39.3-28.3 61.9-65 61.9-100.7V88c0-13.3-10.7-24-24-24zM99.3 192.8C74.9 175.2 64 155.6 64 144v-16h64.2c1 32.6 5.8 61.2 12.8 86.2-15.1-5.2-29.2-12.4-41.7-21.4zM512 144c0 16.1-17.7 36.1-35.3 48.8-12.5 9-26.7 16.2-41.8 21.4 7-25 11.8-53.6 12.8-86.2H512v16z\"],\n    \"truck\": [640, 512, [], \"f0d1\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"truck-loading\": [640, 512, [], \"f4de\", \"M50.2 375.6c2.3 8.5 11.1 13.6 19.6 11.3l216.4-58c8.5-2.3 13.6-11.1 11.3-19.6l-49.7-185.5c-2.3-8.5-11.1-13.6-19.6-11.3L151 133.3l24.8 92.7-61.8 16.5-24.8-92.7-77.3 20.7C3.4 172.8-1.7 181.6.6 190.1l49.6 185.5zM384 0c-17.7 0-32 14.3-32 32v323.6L5.9 450c-4.3 1.2-6.8 5.6-5.6 9.8l12.6 46.3c1.2 4.3 5.6 6.8 9.8 5.6l393.7-107.4C418.8 464.1 467.6 512 528 512c61.9 0 112-50.1 112-112V0H384zm144 448c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"truck-monster\": [640, 512, [], \"f63b\", \"M624 224h-16v-64c0-17.67-14.33-32-32-32h-73.6L419.22 24.02A64.025 64.025 0 0 0 369.24 0H256c-17.67 0-32 14.33-32 32v96H48c-8.84 0-16 7.16-16 16v80H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16.72c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64h65.45c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-336-96V64h81.24l51.2 64H288zm304 224h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 512 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67A110.85 110.85 0 0 0 373.2 352H368c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32c-.02-8.84-7.18-16-16.02-16zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-208-80h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 192 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0L58.18 304.8c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67a110.85 110.85 0 0 0-8.65 20.89H48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32C288 359.16 280.84 352 272 352zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"truck-moving\": [640, 512, [], \"f4df\", \"M621.3 237.3l-58.5-58.5c-12-12-28.3-18.7-45.3-18.7H480V64c0-17.7-14.3-32-32-32H32C14.3 32 0 46.3 0 64v336c0 44.2 35.8 80 80 80 26.3 0 49.4-12.9 64-32.4 14.6 19.6 37.7 32.4 64 32.4 44.2 0 80-35.8 80-80 0-5.5-.6-10.8-1.6-16h163.2c-1.1 5.2-1.6 10.5-1.6 16 0 44.2 35.8 80 80 80s80-35.8 80-80c0-5.5-.6-10.8-1.6-16H624c8.8 0 16-7.2 16-16v-85.5c0-17-6.7-33.2-18.7-45.2zM80 432c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm128 0c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm272-224h37.5c4.3 0 8.3 1.7 11.3 4.7l43.3 43.3H480v-48zm48 224c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32z\"],\n    \"truck-pickup\": [640, 512, [], \"f63c\", \"M624 288h-16v-64c0-17.67-14.33-32-32-32h-48L419.22 56.02A64.025 64.025 0 0 0 369.24 32H256c-17.67 0-32 14.33-32 32v128H64c-17.67 0-32 14.33-32 32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h49.61c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16h67.23c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM288 96h81.24l76.8 96H288V96zM176 416c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm288 0c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"tshirt\": [640, 512, [], \"f553\", \"M631.2 96.5L436.5 0C416.4 27.8 371.9 47.2 320 47.2S223.6 27.8 203.5 0L8.8 96.5c-7.9 4-11.1 13.6-7.2 21.5l57.2 114.5c4 7.9 13.6 11.1 21.5 7.2l56.6-27.7c10.6-5.2 23 2.5 23 14.4V480c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V226.3c0-11.8 12.4-19.6 23-14.4l56.6 27.7c7.9 4 17.5.8 21.5-7.2L638.3 118c4-7.9.8-17.6-7.1-21.5z\"],\n    \"tty\": [512, 512, [], \"f1e4\", \"M5.37 103.822c138.532-138.532 362.936-138.326 501.262 0 6.078 6.078 7.074 15.496 2.583 22.681l-43.214 69.138a18.332 18.332 0 0 1-22.356 7.305l-86.422-34.569a18.335 18.335 0 0 1-11.434-18.846L351.741 90c-62.145-22.454-130.636-21.986-191.483 0l5.953 59.532a18.331 18.331 0 0 1-11.434 18.846l-86.423 34.568a18.334 18.334 0 0 1-22.356-7.305L2.787 126.502a18.333 18.333 0 0 1 2.583-22.68zM96 308v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H92c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zM96 500v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H140c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"tv\": [640, 512, [], \"f26c\", \"M592 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h245.1v32h-160c-17.7 0-32 14.3-32 32s14.3 32 32 32h384c17.7 0 32-14.3 32-32s-14.3-32-32-32h-160v-32H592c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h512v288z\"],\n    \"umbrella\": [576, 512, [], \"f0e9\", \"M575.7 280.8C547.1 144.5 437.3 62.6 320 49.9V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v17.9C138.3 62.6 29.5 144.5.3 280.8c-2.2 10.1 8.5 21.3 18.7 11.4 52-55 107.7-52.4 158.6 37 5.3 9.5 14.9 8.6 19.7 0 20.2-35.4 44.9-73.2 90.7-73.2 58.5 0 88.2 68.8 90.7 73.2 4.8 8.6 14.4 9.5 19.7 0 51-89.5 107.1-91.4 158.6-37 10.3 10 20.9-1.3 18.7-11.4zM256 301.7V432c0 8.8-7.2 16-16 16-7.8 0-13.2-5.3-15.1-10.7-5.9-16.7-24.1-25.4-40.8-19.5-16.7 5.9-25.4 24.2-19.5 40.8 11.2 31.9 41.6 53.3 75.4 53.3 44.1 0 80-35.9 80-80V301.6c-9.1-7.9-19.8-13.6-32-13.6-12.3.1-22.4 4.8-32 13.7z\"],\n    \"umbrella-beach\": [640, 512, [], \"f5ca\", \"M115.38 136.9l102.11 37.18c35.19-81.54 86.21-144.29 139-173.7-95.88-4.89-188.78 36.96-248.53 111.8-6.69 8.4-2.66 21.05 7.42 24.72zm132.25 48.16l238.48 86.83c35.76-121.38 18.7-231.66-42.63-253.98-7.4-2.7-15.13-4-23.09-4-58.02.01-128.27 69.17-172.76 171.15zM521.48 60.5c6.22 16.3 10.83 34.6 13.2 55.19 5.74 49.89-1.42 108.23-18.95 166.98l102.62 37.36c10.09 3.67 21.31-3.43 21.57-14.17 2.32-95.69-41.91-187.44-118.44-245.36zM560 447.98H321.06L386 269.5l-60.14-21.9-72.9 200.37H16c-8.84 0-16 7.16-16 16.01v32.01C0 504.83 7.16 512 16 512h544c8.84 0 16-7.17 16-16.01v-32.01c0-8.84-7.16-16-16-16z\"],\n    \"underline\": [448, 512, [], \"f0cd\", \"M32 64h32v160c0 88.22 71.78 160 160 160s160-71.78 160-160V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H272a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32v160a80 80 0 0 1-160 0V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm400 384H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"undo\": [512, 512, [], \"f0e2\", \"M212.333 224.333H12c-6.627 0-12-5.373-12-12V12C0 5.373 5.373 0 12 0h48c6.627 0 12 5.373 12 12v78.112C117.773 39.279 184.26 7.47 258.175 8.007c136.906.994 246.448 111.623 246.157 248.532C504.041 393.258 393.12 504 256.333 504c-64.089 0-122.496-24.313-166.51-64.215-5.099-4.622-5.334-12.554-.467-17.42l33.967-33.967c4.474-4.474 11.662-4.717 16.401-.525C170.76 415.336 211.58 432 256.333 432c97.268 0 176-78.716 176-176 0-97.267-78.716-176-176-176-58.496 0-110.28 28.476-142.274 72.333h98.274c6.627 0 12 5.373 12 12v48c0 6.627-5.373 12-12 12z\"],\n    \"undo-alt\": [512, 512, [], \"f2ea\", \"M255.545 8c-66.269.119-126.438 26.233-170.86 68.685L48.971 40.971C33.851 25.851 8 36.559 8 57.941V192c0 13.255 10.745 24 24 24h134.059c21.382 0 32.09-25.851 16.971-40.971l-41.75-41.75c30.864-28.899 70.801-44.907 113.23-45.273 92.398-.798 170.283 73.977 169.484 169.442C423.236 348.009 349.816 424 256 424c-41.127 0-79.997-14.678-110.63-41.556-4.743-4.161-11.906-3.908-16.368.553L89.34 422.659c-4.872 4.872-4.631 12.815.482 17.433C133.798 479.813 192.074 504 256 504c136.966 0 247.999-111.033 248-247.998C504.001 119.193 392.354 7.755 255.545 8z\"],\n    \"universal-access\": [512, 512, [], \"f29a\", \"M256 48c114.953 0 208 93.029 208 208 0 114.953-93.029 208-208 208-114.953 0-208-93.029-208-208 0-114.953 93.029-208 208-208m0-40C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 56C149.961 64 64 149.961 64 256s85.961 192 192 192 192-85.961 192-192S362.039 64 256 64zm0 44c19.882 0 36 16.118 36 36s-16.118 36-36 36-36-16.118-36-36 16.118-36 36-36zm117.741 98.023c-28.712 6.779-55.511 12.748-82.14 15.807.851 101.023 12.306 123.052 25.037 155.621 3.617 9.26-.957 19.698-10.217 23.315-9.261 3.617-19.699-.957-23.316-10.217-8.705-22.308-17.086-40.636-22.261-78.549h-9.686c-5.167 37.851-13.534 56.208-22.262 78.549-3.615 9.255-14.05 13.836-23.315 10.217-9.26-3.617-13.834-14.056-10.217-23.315 12.713-32.541 24.185-54.541 25.037-155.621-26.629-3.058-53.428-9.027-82.141-15.807-8.6-2.031-13.926-10.648-11.895-19.249s10.647-13.926 19.249-11.895c96.686 22.829 124.283 22.783 220.775 0 8.599-2.03 17.218 3.294 19.249 11.895 2.029 8.601-3.297 17.219-11.897 19.249z\"],\n    \"university\": [512, 512, [], \"f19c\", \"M496 128v16a8 8 0 0 1-8 8h-24v12c0 6.627-5.373 12-12 12H60c-6.627 0-12-5.373-12-12v-12H24a8 8 0 0 1-8-8v-16a8 8 0 0 1 4.941-7.392l232-88a7.996 7.996 0 0 1 6.118 0l232 88A8 8 0 0 1 496 128zm-24 304H40c-13.255 0-24 10.745-24 24v16a8 8 0 0 0 8 8h464a8 8 0 0 0 8-8v-16c0-13.255-10.745-24-24-24zM96 192v192H60c-6.627 0-12 5.373-12 12v20h416v-20c0-6.627-5.373-12-12-12h-36V192h-64v192h-64V192h-64v192h-64V192H96z\"],\n    \"unlink\": [512, 512, [], \"f127\", \"M304.083 405.907c4.686 4.686 4.686 12.284 0 16.971l-44.674 44.674c-59.263 59.262-155.693 59.266-214.961 0-59.264-59.265-59.264-155.696 0-214.96l44.675-44.675c4.686-4.686 12.284-4.686 16.971 0l39.598 39.598c4.686 4.686 4.686 12.284 0 16.971l-44.675 44.674c-28.072 28.073-28.072 73.75 0 101.823 28.072 28.072 73.75 28.073 101.824 0l44.674-44.674c4.686-4.686 12.284-4.686 16.971 0l39.597 39.598zm-56.568-260.216c4.686 4.686 12.284 4.686 16.971 0l44.674-44.674c28.072-28.075 73.75-28.073 101.824 0 28.072 28.073 28.072 73.75 0 101.823l-44.675 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.598 39.598c4.686 4.686 12.284 4.686 16.971 0l44.675-44.675c59.265-59.265 59.265-155.695 0-214.96-59.266-59.264-155.695-59.264-214.961 0l-44.674 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.597 39.598zm234.828 359.28l22.627-22.627c9.373-9.373 9.373-24.569 0-33.941L63.598 7.029c-9.373-9.373-24.569-9.373-33.941 0L7.029 29.657c-9.373 9.373-9.373 24.569 0 33.941l441.373 441.373c9.373 9.372 24.569 9.372 33.941 0z\"],\n    \"unlock\": [448, 512, [], \"f09c\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"unlock-alt\": [448, 512, [], \"f13e\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zM264 408c0 22.1-17.9 40-40 40s-40-17.9-40-40v-48c0-22.1 17.9-40 40-40s40 17.9 40 40v48z\"],\n    \"upload\": [512, 512, [], \"f093\", \"M296 384h-80c-13.3 0-24-10.7-24-24V192h-87.7c-17.8 0-26.7-21.5-14.1-34.1L242.3 5.7c7.5-7.5 19.8-7.5 27.3 0l152.2 152.2c12.6 12.6 3.7 34.1-14.1 34.1H320v168c0 13.3-10.7 24-24 24zm216-8v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h136v8c0 30.9 25.1 56 56 56h80c30.9 0 56-25.1 56-56v-8h136c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"user\": [448, 512, [], \"f007\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-alt\": [512, 512, [], \"f406\", \"M256 288c79.5 0 144-64.5 144-144S335.5 0 256 0 112 64.5 112 144s64.5 144 144 144zm128 32h-55.1c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16H128C57.3 320 0 377.3 0 448v16c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-16c0-70.7-57.3-128-128-128z\"],\n    \"user-alt-slash\": [640, 512, [], \"f4fa\", \"M633.8 458.1L389.6 269.3C433.8 244.7 464 198.1 464 144 464 64.5 399.5 0 320 0c-67.1 0-123 46.1-139 108.2L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM198.4 320C124.2 320 64 380.2 64 454.4v9.6c0 26.5 21.5 48 48 48h382.2L245.8 320h-47.4z\"],\n    \"user-astronaut\": [448, 512, [], \"f4fb\", \"M64 224h13.5c24.7 56.5 80.9 96 146.5 96s121.8-39.5 146.5-96H384c8.8 0 16-7.2 16-16v-96c0-8.8-7.2-16-16-16h-13.5C345.8 39.5 289.6 0 224 0S102.2 39.5 77.5 96H64c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16zm40-88c0-22.1 21.5-40 48-40h144c26.5 0 48 17.9 48 40v24c0 53-43 96-96 96h-48c-53 0-96-43-96-96v-24zm72 72l12-36 36-12-36-12-12-36-12 36-36 12 36 12 12 36zm151.6 113.4C297.7 340.7 262.2 352 224 352s-73.7-11.3-103.6-30.6C52.9 328.5 0 385 0 454.4v9.6c0 26.5 21.5 48 48 48h80v-64c0-17.7 14.3-32 32-32h128c17.7 0 32 14.3 32 32v64h80c26.5 0 48-21.5 48-48v-9.6c0-69.4-52.9-125.9-120.4-133zM272 448c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-96 0c-8.8 0-16 7.2-16 16v48h32v-48c0-8.8-7.2-16-16-16z\"],\n    \"user-check\": [640, 512, [], \"f4fc\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4zm323-128.4l-27.8-28.1c-4.6-4.7-12.1-4.7-16.8-.1l-104.8 104-45.5-45.8c-4.6-4.7-12.1-4.7-16.8-.1l-28.1 27.9c-4.7 4.6-4.7 12.1-.1 16.8l81.7 82.3c4.6 4.7 12.1 4.7 16.8.1l141.3-140.2c4.6-4.7 4.7-12.2.1-16.8z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 96c48.6 0 88 39.4 88 88s-39.4 88-88 88-88-39.4-88-88 39.4-88 88-88zm0 344c-58.7 0-111.3-26.6-146.5-68.2 18.8-35.4 55.6-59.8 98.5-59.8 2.4 0 4.8.4 7.1 1.1 13 4.2 26.6 6.9 40.9 6.9 14.3 0 28-2.7 40.9-6.9 2.3-.7 4.7-1.1 7.1-1.1 42.9 0 79.7 24.4 98.5 59.8C359.3 421.4 306.7 448 248 448z\"],\n    \"user-clock\": [640, 512, [], \"f4fd\", \"M496 224c-79.6 0-144 64.4-144 144s64.4 144 144 144 144-64.4 144-144-64.4-144-144-144zm64 150.3c0 5.3-4.4 9.7-9.7 9.7h-60.6c-5.3 0-9.7-4.4-9.7-9.7v-76.6c0-5.3 4.4-9.7 9.7-9.7h12.6c5.3 0 9.7 4.4 9.7 9.7V352h38.3c5.3 0 9.7 4.4 9.7 9.7v12.6zM320 368c0-27.8 6.7-54.1 18.2-77.5-8-1.5-16.2-2.5-24.6-2.5h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h347.1c-45.3-31.9-75.1-84.5-75.1-144zm-96-112c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128z\"],\n    \"user-cog\": [640, 512, [], \"f4fe\", \"M610.5 373.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 400.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm201.2 226.5c-2.3-1.2-4.6-2.6-6.8-3.9l-7.9 4.6c-6 3.4-12.8 5.3-19.6 5.3-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-5.5-17.7 1.9-36.4 17.9-45.7l7.9-4.6c-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-16-9.2-23.4-28-17.9-45.7.9-2.9 2.2-5.8 3.2-8.7-3.8-.3-7.5-1.2-11.4-1.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c10.1 0 19.5-3.2 27.2-8.5-1.2-3.8-2-7.7-2-11.8v-9.2z\"],\n    \"user-edit\": [640, 512, [], \"f4ff\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h274.9c-2.4-6.8-3.4-14-2.6-21.3l6.8-60.9 1.2-11.1 7.9-7.9 77.3-77.3c-24.5-27.7-60-45.5-99.9-45.5zm45.3 145.3l-6.8 61c-1.1 10.2 7.5 18.8 17.6 17.6l60.9-6.8 137.9-137.9-71.7-71.7-137.9 137.8zM633 268.9L595.1 231c-9.3-9.3-24.5-9.3-33.8 0l-37.8 37.8-4.1 4.1 71.8 71.7 41.8-41.8c9.3-9.4 9.3-24.5 0-33.9z\"],\n    \"user-friends\": [640, 512, [], \"f500\", \"M192 256c61.9 0 112-50.1 112-112S253.9 32 192 32 80 82.1 80 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C51.6 288 0 339.6 0 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zM480 256c53 0 96-43 96-96s-43-96-96-96-96 43-96 96 43 96 96 96zm48 32h-3.8c-13.9 4.8-28.6 8-44.2 8s-30.3-3.2-44.2-8H432c-20.4 0-39.2 5.9-55.7 15.4 24.4 26.3 39.7 61.2 39.7 99.8v38.4c0 2.2-.5 4.3-.6 6.4H592c26.5 0 48-21.5 48-48 0-61.9-50.1-112-112-112z\"],\n    \"user-graduate\": [448, 512, [], \"f501\", \"M319.4 320.6L224 416l-95.4-95.4C57.1 323.7 0 382.2 0 454.4v9.6c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-9.6c0-72.2-57.1-130.7-128.6-133.8zM13.6 79.8l6.4 1.5v58.4c-7 4.2-12 11.5-12 20.3 0 8.4 4.6 15.4 11.1 19.7L3.5 242c-1.7 6.9 2.1 14 7.6 14h41.8c5.5 0 9.3-7.1 7.6-14l-15.6-62.3C51.4 175.4 56 168.4 56 160c0-8.8-5-16.1-12-20.3V87.1l66 15.9c-8.6 17.2-14 36.4-14 57 0 70.7 57.3 128 128 128s128-57.3 128-128c0-20.6-5.3-39.8-14-57l96.3-23.2c18.2-4.4 18.2-27.1 0-31.5l-190.4-46c-13-3.1-26.7-3.1-39.7 0L13.6 48.2c-18.1 4.4-18.1 27.2 0 31.6z\"],\n    \"user-injured\": [448, 512, [], \"f728\", \"M277.37 11.98C261.08 4.47 243.11 0 224 0c-53.69 0-99.5 33.13-118.51 80h81.19l90.69-68.02zM342.51 80c-7.9-19.47-20.67-36.2-36.49-49.52L239.99 80h102.52zM224 256c70.69 0 128-57.31 128-128 0-5.48-.95-10.7-1.61-16H97.61c-.67 5.3-1.61 10.52-1.61 16 0 70.69 57.31 128 128 128zM80 299.7V512h128.26l-98.45-221.52A132.835 132.835 0 0 0 80 299.7zM0 464c0 26.51 21.49 48 48 48V320.24C18.88 344.89 0 381.26 0 422.4V464zm256-48h-55.38l42.67 96H256c26.47 0 48-21.53 48-48s-21.53-48-48-48zm57.6-128h-16.71c-22.24 10.18-46.88 16-72.89 16s-50.65-5.82-72.89-16h-7.37l42.67 96H256c44.11 0 80 35.89 80 80 0 18.08-6.26 34.59-16.41 48H400c26.51 0 48-21.49 48-48v-41.6c0-74.23-60.17-134.4-134.4-134.4z\"],\n    \"user-lock\": [640, 512, [], \"f502\", \"M224 256A128 128 0 1 0 96 128a128 128 0 0 0 128 128zm96 64a63.08 63.08 0 0 1 8.1-30.5c-4.8-.5-9.5-1.5-14.5-1.5h-16.7a174.08 174.08 0 0 1-145.8 0h-16.7A134.43 134.43 0 0 0 0 422.4V464a48 48 0 0 0 48 48h280.9a63.54 63.54 0 0 1-8.9-32zm288-32h-32v-80a80 80 0 0 0-160 0v80h-32a32 32 0 0 0-32 32v160a32 32 0 0 0 32 32h224a32 32 0 0 0 32-32V320a32 32 0 0 0-32-32zM496 432a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm32-144h-64v-80a32 32 0 0 1 64 0z\"],\n    \"user-md\": [448, 512, [], \"f0f0\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zM104 424c0 13.3 10.7 24 24 24s24-10.7 24-24-10.7-24-24-24-24 10.7-24 24zm216-135.4v49c36.5 7.4 64 39.8 64 78.4v41.7c0 7.6-5.4 14.2-12.9 15.7l-32.2 6.4c-4.3.9-8.5-1.9-9.4-6.3l-3.1-15.7c-.9-4.3 1.9-8.6 6.3-9.4l19.3-3.9V416c0-62.8-96-65.1-96 1.9v26.7l19.3 3.9c4.3.9 7.1 5.1 6.3 9.4l-3.1 15.7c-.9 4.3-5.1 7.1-9.4 6.3l-31.2-4.2c-7.9-1.1-13.8-7.8-13.8-15.9V416c0-38.6 27.5-70.9 64-78.4v-45.2c-2.2.7-4.4 1.1-6.6 1.9-18 6.3-37.3 9.8-57.4 9.8s-39.4-3.5-57.4-9.8c-7.4-2.6-14.9-4.2-22.6-5.2v81.6c23.1 6.9 40 28.1 40 53.4 0 30.9-25.1 56-56 56s-56-25.1-56-56c0-25.3 16.9-46.5 40-53.4v-80.4C48.5 301 0 355.8 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-72-56.8-130.3-128-133.8z\"],\n    \"user-minus\": [640, 512, [], \"f503\", \"M624 208H432c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h192c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-ninja\": [448, 512, [], \"f504\", \"M325.4 289.2L224 390.6 122.6 289.2C54 295.3 0 352.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-70.2-54-127.1-122.6-133.2zM32 192c27.3 0 51.8-11.5 69.2-29.7 15.1 53.9 64 93.7 122.8 93.7 70.7 0 128-57.3 128-128S294.7 0 224 0c-50.4 0-93.6 29.4-114.5 71.8C92.1 47.8 64 32 32 32c0 33.4 17.1 62.8 43.1 80-26 17.2-43.1 46.6-43.1 80zm144-96h96c17.7 0 32 14.3 32 32H144c0-17.7 14.3-32 32-32z\"],\n    \"user-nurse\": [448, 512, [], \"f82f\", \"M57.78 288h82.36c22.51 19.68 51.62 32 83.86 32s61.35-12.32 83.86-32h82.36a16 16 0 0 0 14.28-23.18c-15.23-29.85-31.28-62.23-42.15-95.54C354.78 146.09 352 121.59 352 97.2V48L224 0 96 48v49.2c0 24.39-2.75 48.89-10.33 72.08C74.78 202.59 58.73 235 43.5 264.82A16 16 0 0 0 57.78 288zM184 71.67a5 5 0 0 1 5-5h21.67V45a5 5 0 0 1 5-5h16.66a5 5 0 0 1 5 5v21.67H259a5 5 0 0 1 5 5v16.66a5 5 0 0 1-5 5h-21.67V115a5 5 0 0 1-5 5h-16.66a5 5 0 0 1-5-5V93.33H189a5 5 0 0 1-5-5zM144 160h160v32a80 80 0 0 1-160 0zm175.41 160L224 415.39 128.59 320C57.1 323.1 0 381.6 0 453.79A58.21 58.21 0 0 0 58.21 512h331.58A58.21 58.21 0 0 0 448 453.79C448 381.6 390.9 323.1 319.41 320z\"],\n    \"user-plus\": [640, 512, [], \"f234\", \"M624 208h-64v-64c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v64h-64c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h64v64c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-64h64c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-secret\": [448, 512, [], \"f21b\", \"M383.9 308.3l23.9-62.6c4-10.5-3.7-21.7-15-21.7h-58.5c11-18.9 17.8-40.6 17.8-64v-.3c39.2-7.8 64-19.1 64-31.7 0-13.3-27.3-25.1-70.1-33-9.2-32.8-27-65.8-40.6-82.8-9.5-11.9-25.9-15.6-39.5-8.8l-27.6 13.8c-9 4.5-19.6 4.5-28.6 0L182.1 3.4c-13.6-6.8-30-3.1-39.5 8.8-13.5 17-31.4 50-40.6 82.8-42.7 7.9-70 19.7-70 33 0 12.6 24.8 23.9 64 31.7v.3c0 23.4 6.8 45.1 17.8 64H56.3c-11.5 0-19.2 11.7-14.7 22.3l25.8 60.2C27.3 329.8 0 372.7 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-48.4-25.8-90.4-64.1-114.1zM176 480l-41.6-192 49.6 32 24 40-32 120zm96 0l-32-120 24-40 49.6-32L272 480zm41.7-298.5c-3.9 11.9-7 24.6-16.5 33.4-10.1 9.3-48 22.4-64-25-2.8-8.4-15.4-8.4-18.3 0-17 50.2-56 32.4-64 25-9.5-8.8-12.7-21.5-16.5-33.4-.8-2.5-6.3-5.7-6.3-5.8v-10.8c28.3 3.6 61 5.8 96 5.8s67.7-2.1 96-5.8v10.8c-.1.1-5.6 3.2-6.4 5.8z\"],\n    \"user-shield\": [640, 512, [], \"f505\", \"M622.3 271.1l-115.2-45c-4.1-1.6-12.6-3.7-22.2 0l-115.2 45c-10.7 4.2-17.7 14-17.7 24.9 0 111.6 68.7 188.8 132.9 213.9 9.6 3.7 18 1.6 22.2 0C558.4 489.9 640 420.5 640 296c0-10.9-7-20.7-17.7-24.9zM496 462.4V273.3l95.5 37.3c-5.6 87.1-60.9 135.4-95.5 151.8zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm96 40c0-2.5.8-4.8 1.1-7.2-2.5-.1-4.9-.8-7.5-.8h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c6.8 0 13.3-1.5 19.2-4-54-42.9-99.2-116.7-99.2-212z\"],\n    \"user-slash\": [640, 512, [], \"f506\", \"M633.8 458.1L362.3 248.3C412.1 230.7 448 183.8 448 128 448 57.3 390.7 0 320 0c-67.1 0-121.5 51.8-126.9 117.4L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM96 422.4V464c0 26.5 21.5 48 48 48h350.2L207.4 290.3C144.2 301.3 96 356 96 422.4z\"],\n    \"user-tag\": [640, 512, [], \"f507\", \"M630.6 364.9l-90.3-90.2c-12-12-28.3-18.7-45.3-18.7h-79.3c-17.7 0-32 14.3-32 32v79.2c0 17 6.7 33.2 18.7 45.2l90.3 90.2c12.5 12.5 32.8 12.5 45.3 0l92.5-92.5c12.6-12.5 12.6-32.7.1-45.2zm-182.8-21c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24c0 13.2-10.7 24-24 24zm-223.8-88c70.7 0 128-57.3 128-128C352 57.3 294.7 0 224 0S96 57.3 96 128c0 70.6 57.3 127.9 128 127.9zm127.8 111.2V294c-12.2-3.6-24.9-6.2-38.2-6.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 287.9 0 348.1 0 422.3v41.6c0 26.5 21.5 48 48 48h352c15.5 0 29.1-7.5 37.9-18.9l-58-58c-18.1-18.1-28.1-42.2-28.1-67.9z\"],\n    \"user-tie\": [448, 512, [], \"f508\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm95.8 32.6L272 480l-32-136 32-56h-96l32 56-32 136-47.8-191.4C56.9 292 0 350.3 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-72.1-56.9-130.4-128.2-133.8z\"],\n    \"user-times\": [640, 512, [], \"f235\", \"M589.6 240l45.6-45.6c6.3-6.3 6.3-16.5 0-22.8l-22.8-22.8c-6.3-6.3-16.5-6.3-22.8 0L544 194.4l-45.6-45.6c-6.3-6.3-16.5-6.3-22.8 0l-22.8 22.8c-6.3 6.3-6.3 16.5 0 22.8l45.6 45.6-45.6 45.6c-6.3 6.3-6.3 16.5 0 22.8l22.8 22.8c6.3 6.3 16.5 6.3 22.8 0l45.6-45.6 45.6 45.6c6.3 6.3 16.5 6.3 22.8 0l22.8-22.8c6.3-6.3 6.3-16.5 0-22.8L589.6 240zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"users\": [640, 512, [], \"f0c0\", \"M96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm448 0c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm32 32h-64c-17.6 0-33.5 7.1-45.1 18.6 40.3 22.1 68.9 62 75.1 109.4h66c17.7 0 32-14.3 32-32v-32c0-35.3-28.7-64-64-64zm-256 0c61.9 0 112-50.1 112-112S381.9 32 320 32 208 82.1 208 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zm-223.7-13.4C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"users-cog\": [640, 512, [], \"f509\", \"M610.5 341.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 368.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm224 32c1.9 0 3.7-.5 5.6-.6 8.3-21.7 20.5-42.1 36.3-59.2 7.4-8 17.9-12.6 28.9-12.6 6.9 0 13.7 1.8 19.6 5.3l7.9 4.6c.8-.5 1.6-.9 2.4-1.4 7-14.6 11.2-30.8 11.2-48 0-61.9-50.1-112-112-112S208 82.1 208 144c0 61.9 50.1 112 112 112zm105.2 194.5c-2.3-1.2-4.6-2.6-6.8-3.9-8.2 4.8-15.3 9.8-27.5 9.8-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-10.7-34.5 24.9-49.7 25.8-50.3-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-3.8-2.2-7-5-9.8-8.1-3.3.2-6.5.6-9.8.6-24.6 0-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h255.4c-3.7-6-6.2-12.8-6.2-20.3v-9.2zM173.1 274.6C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"utensil-spoon\": [512, 512, [], \"f2e5\", \"M480.1 31.9c-55-55.1-164.9-34.5-227.8 28.5-49.3 49.3-55.1 110-28.8 160.4L9 413.2c-11.6 10.5-12.1 28.5-1 39.5L59.3 504c11 11 29.1 10.5 39.5-1.1l192.4-214.4c50.4 26.3 111.1 20.5 160.4-28.8 63-62.9 83.6-172.8 28.5-227.8z\"],\n    \"utensils\": [416, 512, [], \"f2e7\", \"M207.9 15.2c.8 4.7 16.1 94.5 16.1 128.8 0 52.3-27.8 89.6-68.9 104.6L168 486.7c.7 13.7-10.2 25.3-24 25.3H80c-13.7 0-24.7-11.5-24-25.3l12.9-238.1C27.7 233.6 0 196.2 0 144 0 109.6 15.3 19.9 16.1 15.2 19.3-5.1 61.4-5.4 64 16.3v141.2c1.3 3.4 15.1 3.2 16 0 1.4-25.3 7.9-139.2 8-141.8 3.3-20.8 44.7-20.8 47.9 0 .2 2.7 6.6 116.5 8 141.8.9 3.2 14.8 3.4 16 0V16.3c2.6-21.6 44.8-21.4 48-1.1zm119.2 285.7l-15 185.1c-1.2 14 9.9 26 23.9 26h56c13.3 0 24-10.7 24-24V24c0-13.2-10.7-24-24-24-82.5 0-221.4 178.5-64.9 300.9z\"],\n    \"vector-square\": [512, 512, [], \"f5cb\", \"M512 128V32c0-17.67-14.33-32-32-32h-96c-17.67 0-32 14.33-32 32H160c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32v192c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32h192c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32V160c17.67 0 32-14.33 32-32zm-96-64h32v32h-32V64zM64 64h32v32H64V64zm32 384H64v-32h32v32zm352 0h-32v-32h32v32zm-32-96h-32c-17.67 0-32 14.33-32 32v32H160v-32c0-17.67-14.33-32-32-32H96V160h32c17.67 0 32-14.33 32-32V96h192v32c0 17.67 14.33 32 32 32h32v192z\"],\n    \"venus\": [288, 512, [], \"f221\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"venus-double\": [512, 512, [], \"f226\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80zm336 140.4V368h36c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-36v36c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-36h-36c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h36v-51.6c-21.2-4.8-40.6-14.3-57.2-27.3 14-16.7 25-36 32.1-57.1 14.5 14.8 34.7 24 57.1 24 44.1 0 80-35.9 80-80s-35.9-80-80-80c-22.3 0-42.6 9.2-57.1 24-7.1-21.1-18-40.4-32.1-57.1C303.4 43.6 334.3 32 368 32c79.5 0 144 64.5 144 144 0 68.5-47.9 125.9-112 140.4z\"],\n    \"venus-mars\": [576, 512, [], \"f228\", \"M564 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C422.5 72.1 396.2 64 368 64c-33.7 0-64.6 11.6-89.2 30.9 14 16.7 25 36 32.1 57.1 14.5-14.8 34.7-24 57.1-24 44.1 0 80 35.9 80 80s-35.9 80-80 80c-22.3 0-42.6-9.2-57.1-24-7.1 21.1-18 40.4-32.1 57.1 24.5 19.4 55.5 30.9 89.2 30.9 79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 64C64.5 64 0 128.5 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.6 112-71.9 112-140.4 0-79.5-64.5-144-144-144zm0 224c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"vial\": [480, 512, [], \"f492\", \"M477.7 186.1L309.5 18.3c-3.1-3.1-8.2-3.1-11.3 0l-34 33.9c-3.1 3.1-3.1 8.2 0 11.3l11.2 11.1L33 316.5c-38.8 38.7-45.1 102-9.4 143.5 20.6 24 49.5 36 78.4 35.9 26.4 0 52.8-10 72.9-30.1l246.3-245.7 11.2 11.1c3.1 3.1 8.2 3.1 11.3 0l34-33.9c3.1-3 3.1-8.1 0-11.2zM318 256H161l148-147.7 78.5 78.3L318 256z\"],\n    \"vials\": [640, 512, [], \"f493\", \"M72 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H72c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64zm480 384H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM360 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64z\"],\n    \"video\": [576, 512, [], \"f03d\", \"M336.2 64H47.8C21.4 64 0 85.4 0 111.8v288.4C0 426.6 21.4 448 47.8 448h288.4c26.4 0 47.8-21.4 47.8-47.8V111.8c0-26.4-21.4-47.8-47.8-47.8zm189.4 37.7L416 177.3v157.4l109.6 75.5c21.2 14.6 50.4-.3 50.4-25.8V127.5c0-25.4-29.1-40.4-50.4-25.8z\"],\n    \"video-slash\": [640, 512, [], \"f4e2\", \"M633.8 458.1l-55-42.5c15.4-1.4 29.2-13.7 29.2-31.1v-257c0-25.5-29.1-40.4-50.4-25.8L448 177.3v137.2l-32-24.7v-178c0-26.4-21.4-47.8-47.8-47.8H123.9L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4L42.7 82 416 370.6l178.5 138c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.5-6.9 4.2-17-2.8-22.4zM32 400.2c0 26.4 21.4 47.8 47.8 47.8h288.4c11.2 0 21.4-4 29.6-10.5L32 154.7v245.5z\"],\n    \"vihara\": [640, 512, [], \"f6a7\", \"M632.88 400.71L544 352v-64l55.16-17.69c11.79-5.9 11.79-22.72 0-28.62L480 192v-64l27.31-16.3c7.72-7.72 5.61-20.74-4.16-25.62L320 0 136.85 86.07c-9.77 4.88-11.88 17.9-4.16 25.62L160 128v64L40.84 241.69c-11.79 5.9-11.79 22.72 0 28.62L96 288v64L7.12 400.71c-5.42 3.62-7.7 9.63-7 15.29.62 5.01 3.57 9.75 8.72 12.33L64 448v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48l55.15-19.67c5.16-2.58 8.1-7.32 8.72-12.33.71-5.67-1.57-11.68-6.99-15.29zM224 128h192v64H224v-64zm-64 224v-64h320v64H160z\"],\n    \"voicemail\": [640, 512, [], \"f897\", \"M496 128a144 144 0 0 0-119.74 224H263.74A144 144 0 1 0 144 416h352a144 144 0 0 0 0-288zM64 272a80 80 0 1 1 80 80 80 80 0 0 1-80-80zm432 80a80 80 0 1 1 80-80 80 80 0 0 1-80 80z\"],\n    \"volleyball-ball\": [512, 512, [], \"f45f\", \"M231.39 243.48a285.56 285.56 0 0 0-22.7-105.7c-90.8 42.4-157.5 122.4-180.3 216.8a249 249 0 0 0 56.9 81.1 333.87 333.87 0 0 1 146.1-192.2zm-36.9-134.4a284.23 284.23 0 0 0-57.4-70.7c-91 49.8-144.8 152.9-125 262.2 33.4-83.1 98.4-152 182.4-191.5zm187.6 165.1c8.6-99.8-27.3-197.5-97.5-264.4-14.7-1.7-51.6-5.5-98.9 8.5A333.87 333.87 0 0 1 279.19 241a285 285 0 0 0 102.9 33.18zm-124.7 9.5a286.33 286.33 0 0 0-80.2 72.6c82 57.3 184.5 75.1 277.5 47.8a247.15 247.15 0 0 0 42.2-89.9 336.1 336.1 0 0 1-80.9 10.4c-54.6-.1-108.9-14.1-158.6-40.9zm-98.3 99.7c-15.2 26-25.7 54.4-32.1 84.2a247.07 247.07 0 0 0 289-22.1c-112.9 16.1-203.3-24.8-256.9-62.1zm180.3-360.6c55.3 70.4 82.5 161.2 74.6 253.6a286.59 286.59 0 0 0 89.7-14.2c0-2 .3-4 .3-6 0-107.8-68.7-199.1-164.6-233.4z\"],\n    \"volume-down\": [384, 512, [], \"f027\", \"M215.03 72.04L126.06 161H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V89.02c0-21.47-25.96-31.98-40.97-16.98zm123.2 108.08c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 229.28 336 242.62 336 257c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.87z\"],\n    \"volume-mute\": [512, 512, [], \"f6a9\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zM461.64 256l45.64-45.64c6.3-6.3 6.3-16.52 0-22.82l-22.82-22.82c-6.3-6.3-16.52-6.3-22.82 0L416 210.36l-45.64-45.64c-6.3-6.3-16.52-6.3-22.82 0l-22.82 22.82c-6.3 6.3-6.3 16.52 0 22.82L370.36 256l-45.63 45.63c-6.3 6.3-6.3 16.52 0 22.82l22.82 22.82c6.3 6.3 16.52 6.3 22.82 0L416 301.64l45.64 45.64c6.3 6.3 16.52 6.3 22.82 0l22.82-22.82c6.3-6.3 6.3-16.52 0-22.82L461.64 256z\"],\n    \"volume-off\": [256, 512, [], \"f026\", \"M215 71l-89 89H24a24 24 0 0 0-24 24v144a24 24 0 0 0 24 24h102.06L215 441c15 15 41 4.47 41-17V88c0-21.47-26-32-41-17z\"],\n    \"volume-up\": [576, 512, [], \"f028\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zm233.32-51.08c-11.17-7.33-26.18-4.24-33.51 6.95-7.34 11.17-4.22 26.18 6.95 33.51 66.27 43.49 105.82 116.6 105.82 195.58 0 78.98-39.55 152.09-105.82 195.58-11.17 7.32-14.29 22.34-6.95 33.5 7.04 10.71 21.93 14.56 33.51 6.95C528.27 439.58 576 351.33 576 256S528.27 72.43 448.35 19.97zM480 256c0-63.53-32.06-121.94-85.77-156.24-11.19-7.14-26.03-3.82-33.12 7.46s-3.78 26.21 7.41 33.36C408.27 165.97 432 209.11 432 256s-23.73 90.03-63.48 115.42c-11.19 7.14-14.5 22.07-7.41 33.36 6.51 10.36 21.12 15.14 33.12 7.46C447.94 377.94 480 319.54 480 256zm-141.77-76.87c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 228.28 336 241.63 336 256c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.86z\"],\n    \"vote-yea\": [640, 512, [], \"f772\", \"M608 320h-64v64h22.4c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8H96v-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h576c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32zm-96 64V64.3c0-17.9-14.5-32.3-32.3-32.3H160.4C142.5 32 128 46.5 128 64.3V384h384zM211.2 202l25.5-25.3c4.2-4.2 11-4.2 15.2.1l41.3 41.6 95.2-94.4c4.2-4.2 11-4.2 15.2.1l25.3 25.5c4.2 4.2 4.2 11-.1 15.2L300.5 292c-4.2 4.2-11 4.2-15.2-.1l-74.1-74.7c-4.3-4.2-4.2-11 0-15.2z\"],\n    \"vr-cardboard\": [640, 512, [], \"f729\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h160.22c25.19 0 48.03-14.77 58.36-37.74l27.74-61.64C286.21 331.08 302.35 320 320 320s33.79 11.08 41.68 28.62l27.74 61.64C399.75 433.23 422.6 448 447.78 448H608c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM160 304c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64zm320 0c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64z\"],\n    \"walking\": [320, 512, [], \"f554\", \"M208 96c26.5 0 48-21.5 48-48S234.5 0 208 0s-48 21.5-48 48 21.5 48 48 48zm94.5 149.1l-23.3-11.8-9.7-29.4c-14.7-44.6-55.7-75.8-102.2-75.9-36-.1-55.9 10.1-93.3 25.2-21.6 8.7-39.3 25.2-49.7 46.2L17.6 213c-7.8 15.8-1.5 35 14.2 42.9 15.6 7.9 34.6 1.5 42.5-14.3L81 228c3.5-7 9.3-12.5 16.5-15.4l26.8-10.8-15.2 60.7c-5.2 20.8.4 42.9 14.9 58.8l59.9 65.4c7.2 7.9 12.3 17.4 14.9 27.7l18.3 73.3c4.3 17.1 21.7 27.6 38.8 23.3 17.1-4.3 27.6-21.7 23.3-38.8l-22.2-89c-2.6-10.3-7.7-19.9-14.9-27.7l-45.5-49.7 17.2-68.7 5.5 16.5c5.3 16.1 16.7 29.4 31.7 37l23.3 11.8c15.6 7.9 34.6 1.5 42.5-14.3 7.7-15.7 1.4-35.1-14.3-43zM73.6 385.8c-3.2 8.1-8 15.4-14.2 21.5l-50 50.1c-12.5 12.5-12.5 32.8 0 45.3s32.7 12.5 45.2 0l59.4-59.4c6.1-6.1 10.9-13.4 14.2-21.5l13.5-33.8c-55.3-60.3-38.7-41.8-47.4-53.7l-20.7 51.5z\"],\n    \"wallet\": [512, 512, [], \"f555\", \"M461.2 128H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h384c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h397.2c28.02 0 50.8-21.53 50.8-48V176c0-26.47-22.78-48-50.8-48zM416 336c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"warehouse\": [640, 512, [], \"f494\", \"M504 352H136.4c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0 96H136.1c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8h368c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0-192H136.6c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm106.5-139L338.4 3.7a48.15 48.15 0 0 0-36.9 0L29.5 117C11.7 124.5 0 141.9 0 161.3V504c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V256c0-17.6 14.6-32 32.6-32h382.8c18 0 32.6 14.4 32.6 32v248c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V161.3c0-19.4-11.7-36.8-29.5-44.3z\"],\n    \"water\": [576, 512, [], \"f773\", \"M562.1 383.9c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144C540.6 93.4 520 85.4 504.2 73 490.1 61.9 470 61.7 456 73c-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3z\"],\n    \"wave-square\": [640, 512, [], \"f83e\", \"M476 480H324a36 36 0 0 1-36-36V96h-96v156a36 36 0 0 1-36 36H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h112V68a36 36 0 0 1 36-36h152a36 36 0 0 1 36 36v348h96V260a36 36 0 0 1 36-36h140a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H512v156a36 36 0 0 1-36 36z\"],\n    \"weight\": [512, 512, [], \"f496\", \"M448 64h-25.98C438.44 92.28 448 125.01 448 160c0 105.87-86.13 192-192 192S64 265.87 64 160c0-34.99 9.56-67.72 25.98-96H64C28.71 64 0 92.71 0 128v320c0 35.29 28.71 64 64 64h384c35.29 0 64-28.71 64-64V128c0-35.29-28.71-64-64-64zM256 320c88.37 0 160-71.63 160-160S344.37 0 256 0 96 71.63 96 160s71.63 160 160 160zm-.3-151.94l33.58-78.36c3.5-8.17 12.94-11.92 21.03-8.41 8.12 3.48 11.88 12.89 8.41 21l-33.67 78.55C291.73 188 296 197.45 296 208c0 22.09-17.91 40-40 40s-40-17.91-40-40c0-21.98 17.76-39.77 39.7-39.94z\"],\n    \"weight-hanging\": [512, 512, [], \"f5cd\", \"M510.28 445.86l-73.03-292.13c-3.8-15.19-16.44-25.72-30.87-25.72h-60.25c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96s-96 42.98-96 96c0 11.28 2.3 21.95 5.88 32h-60.25c-14.43 0-27.08 10.54-30.87 25.72L1.72 445.86C-6.61 479.17 16.38 512 48.03 512h415.95c31.64 0 54.63-32.83 46.3-66.14zM256 128c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"wheelchair\": [512, 512, [], \"f193\", \"M496.101 385.669l14.227 28.663c3.929 7.915.697 17.516-7.218 21.445l-65.465 32.886c-16.049 7.967-35.556 1.194-43.189-15.055L331.679 320H192c-15.925 0-29.426-11.71-31.679-27.475C126.433 55.308 128.38 70.044 128 64c0-36.358 30.318-65.635 67.052-63.929 33.271 1.545 60.048 28.905 60.925 62.201.868 32.933-23.152 60.423-54.608 65.039l4.67 32.69H336c8.837 0 16 7.163 16 16v32c0 8.837-7.163 16-16 16H215.182l4.572 32H352a32 32 0 0 1 28.962 18.392L438.477 396.8l36.178-18.349c7.915-3.929 17.517-.697 21.446 7.218zM311.358 352h-24.506c-7.788 54.204-54.528 96-110.852 96-61.757 0-112-50.243-112-112 0-41.505 22.694-77.809 56.324-97.156-3.712-25.965-6.844-47.86-9.488-66.333C45.956 198.464 0 261.963 0 336c0 97.047 78.953 176 176 176 71.87 0 133.806-43.308 161.11-105.192L311.358 352z\"],\n    \"wifi\": [640, 512, [], \"f1eb\", \"M634.91 154.88C457.74-8.99 182.19-8.93 5.09 154.88c-6.66 6.16-6.79 16.59-.35 22.98l34.24 33.97c6.14 6.1 16.02 6.23 22.4.38 145.92-133.68 371.3-133.71 517.25 0 6.38 5.85 16.26 5.71 22.4-.38l34.24-33.97c6.43-6.39 6.3-16.82-.36-22.98zM320 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm202.67-83.59c-115.26-101.93-290.21-101.82-405.34 0-6.9 6.1-7.12 16.69-.57 23.15l34.44 33.99c6 5.92 15.66 6.32 22.05.8 83.95-72.57 209.74-72.41 293.49 0 6.39 5.52 16.05 5.13 22.05-.8l34.44-33.99c6.56-6.46 6.33-17.06-.56-23.15z\"],\n    \"wind\": [512, 512, [], \"f72e\", \"M156.7 256H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h142.2c15.9 0 30.8 10.9 33.4 26.6 3.3 20-12.1 37.4-31.6 37.4-14.1 0-26.1-9.2-30.4-21.9-2.1-6.3-8.6-10.1-15.2-10.1H81.6c-9.8 0-17.7 8.8-15.9 18.4 8.6 44.1 47.6 77.6 94.2 77.6 57.1 0 102.7-50.1 95.2-108.6C249 291 205.4 256 156.7 256zM16 224h336c59.7 0 106.8-54.8 93.8-116.7-7.6-36.2-36.9-65.5-73.1-73.1-55.4-11.6-105.1 24.9-114.9 75.5-1.9 9.6 6.1 18.3 15.8 18.3h32.8c6.7 0 13.1-3.8 15.2-10.1C325.9 105.2 337.9 96 352 96c19.4 0 34.9 17.4 31.6 37.4-2.6 15.7-17.4 26.6-33.4 26.6H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16zm384 32H243.7c19.3 16.6 33.2 38.8 39.8 64H400c26.5 0 48 21.5 48 48s-21.5 48-48 48c-17.9 0-33.3-9.9-41.6-24.4-2.9-5-8.7-7.6-14.5-7.6h-33.8c-10.9 0-19 10.8-15.3 21.1 17.8 50.6 70.5 84.8 129.4 72.3 41.2-8.7 75.1-41.6 84.7-82.7C526 321.5 470.5 256 400 256z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-83.6 290.5c4.8 4.8 4.8 12.6 0 17.4l-40.5 40.5c-4.8 4.8-12.6 4.8-17.4 0L256 313.3l-66.5 67.1c-4.8 4.8-12.6 4.8-17.4 0l-40.5-40.5c-4.8-4.8-4.8-12.6 0-17.4l67.1-66.5-67.1-66.5c-4.8-4.8-4.8-12.6 0-17.4l40.5-40.5c4.8-4.8 12.6-4.8 17.4 0l66.5 67.1 66.5-67.1c4.8-4.8 12.6-4.8 17.4 0l40.5 40.5c4.8 4.8 4.8 12.6 0 17.4L313.3 256l67.1 66.5z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16 160H64v-84c0-6.6 5.4-12 12-12h360c6.6 0 12 5.4 12 12v84z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M464 352H48c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M512 48v288c0 26.5-21.5 48-48 48h-48V176c0-44.1-35.9-80-80-80H128V48c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zM384 176v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zm-68 28c0-6.6-5.4-12-12-12H76c-6.6 0-12 5.4-12 12v52h252v-52z\"],\n    \"wine-bottle\": [512, 512, [], \"f72f\", \"M507.31 72.57L439.43 4.69c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l-76.67 76.67c-46.58-19.7-102.4-10.73-140.37 27.23L18.75 312.23c-24.99 24.99-24.99 65.52 0 90.51l90.51 90.51c24.99 24.99 65.52 24.99 90.51 0l158.39-158.39c37.96-37.96 46.93-93.79 27.23-140.37l76.67-76.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.24-6.24 6.24-16.37-.01-22.62zM179.22 423.29l-90.51-90.51 122.04-122.04 90.51 90.51-122.04 122.04z\"],\n    \"wine-glass\": [288, 512, [], \"f4e3\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40z\"],\n    \"wine-glass-alt\": [288, 512, [], \"f5ce\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM61.75 48h164.5l7.17 80H54.58l7.17-80z\"],\n    \"won-sign\": [576, 512, [], \"f159\", \"M564 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-48l18.6-80.6c1.7-7.5-4-14.7-11.7-14.7h-46.1c-5.7 0-10.6 4-11.7 9.5L450.7 128H340.8l-19.7-86c-1.3-5.5-6.1-9.3-11.7-9.3h-44c-5.6 0-10.4 3.8-11.7 9.3l-20 86H125l-17.5-85.7c-1.1-5.6-6.1-9.6-11.8-9.6H53.6c-7.7 0-13.4 7.1-11.7 14.6L60 128H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h62.3l7.2 32H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h83.9l40.9 182.6c1.2 5.5 6.1 9.4 11.7 9.4h56.8c5.6 0 10.4-3.9 11.7-9.3L259.3 288h55.1l42.4 182.7c1.3 5.4 6.1 9.3 11.7 9.3h56.8c5.6 0 10.4-3.9 11.7-9.3L479.1 288H564c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-70.1l7.4-32zM183.8 342c-6.2 25.8-6.8 47.2-7.3 47.2h-1.1s-1.7-22-6.8-47.2l-11-54h38.8zm27.5-118h-66.8l-6.5-32h80.8zm62.9 0l2-8.6c1.9-8 3.5-16 4.8-23.4h11.8c1.3 7.4 2.9 15.4 4.8 23.4l2 8.6zm130.9 118c-5.1 25.2-6.8 47.2-6.8 47.2h-1.1c-.6 0-1.1-21.4-7.3-47.2l-12.4-54h39.1zm25.2-118h-67.4l-7.3-32h81.6z\"],\n    \"wrench\": [512, 512, [], \"f0ad\", \"M507.73 109.1c-2.24-9.03-13.54-12.09-20.12-5.51l-74.36 74.36-67.88-11.31-11.31-67.88 74.36-74.36c6.62-6.62 3.43-17.9-5.66-20.16-47.38-11.74-99.55.91-136.58 37.93-39.64 39.64-50.55 97.1-34.05 147.2L18.74 402.76c-24.99 24.99-24.99 65.51 0 90.5 24.99 24.99 65.51 24.99 90.5 0l213.21-213.21c50.12 16.71 107.47 5.68 147.37-34.22 37.07-37.07 49.7-89.32 37.91-136.73zM64 472c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"x-ray\": [640, 512, [], \"f497\", \"M240 384c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm160 32c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zM624 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zm0 448h-48V96H64v352H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM480 248c0 4.4-3.6 8-8 8H336v32h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h64c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48v-16h-64v16c0 26.5-21.5 48-48 48s-48-21.5-48-48 21.5-48 48-48h64v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-32H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h136v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-24c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v24h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h136c4.4 0 8 3.6 8 8v16z\"],\n    \"yen-sign\": [384, 512, [], \"f157\", \"M351.2 32h-65.3c-4.6 0-8.8 2.6-10.8 6.7l-55.4 113.2c-14.5 34.7-27.1 71.9-27.1 71.9h-1.3s-12.6-37.2-27.1-71.9L108.8 38.7c-2-4.1-6.2-6.7-10.8-6.7H32.8c-9.1 0-14.8 9.7-10.6 17.6L102.3 200H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h88.2l19.8 37.2V320H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h108v92c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12v-92h108c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12H232v-26.8l19.8-37.2H340c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12h-58.3l80.1-150.4c4.3-7.9-1.5-17.6-10.6-17.6z\"],\n    \"yin-yang\": [496, 512, [], \"f6ad\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 376c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-128c-53.02 0-96 42.98-96 96s42.98 96 96 96c-106.04 0-192-85.96-192-192S141.96 64 248 64c53.02 0 96 42.98 96 96s-42.98 96-96 96zm0-128c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fas', icons);\n  });\n\n}());\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/v4-shims.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? module.exports = factory() :\n  typeof define === 'function' && define.amd ? define(factory) :\n  (global['fontawesome-free-shims'] = factory());\n}(this, (function () { 'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return process.env.NODE_ENV === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  var shims = [[\"glass\", null, \"glass-martini\"], [\"meetup\", \"fab\", null], [\"star-o\", \"far\", \"star\"], [\"remove\", null, \"times\"], [\"close\", null, \"times\"], [\"gear\", null, \"cog\"], [\"trash-o\", \"far\", \"trash-alt\"], [\"file-o\", \"far\", \"file\"], [\"clock-o\", \"far\", \"clock\"], [\"arrow-circle-o-down\", \"far\", \"arrow-alt-circle-down\"], [\"arrow-circle-o-up\", \"far\", \"arrow-alt-circle-up\"], [\"play-circle-o\", \"far\", \"play-circle\"], [\"repeat\", null, \"redo\"], [\"rotate-right\", null, \"redo\"], [\"refresh\", null, \"sync\"], [\"list-alt\", \"far\", null], [\"dedent\", null, \"outdent\"], [\"video-camera\", null, \"video\"], [\"picture-o\", \"far\", \"image\"], [\"photo\", \"far\", \"image\"], [\"image\", \"far\", \"image\"], [\"pencil\", null, \"pencil-alt\"], [\"map-marker\", null, \"map-marker-alt\"], [\"pencil-square-o\", \"far\", \"edit\"], [\"share-square-o\", \"far\", \"share-square\"], [\"check-square-o\", \"far\", \"check-square\"], [\"arrows\", null, \"arrows-alt\"], [\"times-circle-o\", \"far\", \"times-circle\"], [\"check-circle-o\", \"far\", \"check-circle\"], [\"mail-forward\", null, \"share\"], [\"eye\", \"far\", null], [\"eye-slash\", \"far\", null], [\"warning\", null, \"exclamation-triangle\"], [\"calendar\", null, \"calendar-alt\"], [\"arrows-v\", null, \"arrows-alt-v\"], [\"arrows-h\", null, \"arrows-alt-h\"], [\"bar-chart\", \"far\", \"chart-bar\"], [\"bar-chart-o\", \"far\", \"chart-bar\"], [\"twitter-square\", \"fab\", null], [\"facebook-square\", \"fab\", null], [\"gears\", null, \"cogs\"], [\"thumbs-o-up\", \"far\", \"thumbs-up\"], [\"thumbs-o-down\", \"far\", \"thumbs-down\"], [\"heart-o\", \"far\", \"heart\"], [\"sign-out\", null, \"sign-out-alt\"], [\"linkedin-square\", \"fab\", \"linkedin\"], [\"thumb-tack\", null, \"thumbtack\"], [\"external-link\", null, \"external-link-alt\"], [\"sign-in\", null, \"sign-in-alt\"], [\"github-square\", \"fab\", null], [\"lemon-o\", \"far\", \"lemon\"], [\"square-o\", \"far\", \"square\"], [\"bookmark-o\", \"far\", \"bookmark\"], [\"twitter\", \"fab\", null], [\"facebook\", \"fab\", \"facebook-f\"], [\"facebook-f\", \"fab\", \"facebook-f\"], [\"github\", \"fab\", null], [\"credit-card\", \"far\", null], [\"feed\", null, \"rss\"], [\"hdd-o\", \"far\", \"hdd\"], [\"hand-o-right\", \"far\", \"hand-point-right\"], [\"hand-o-left\", \"far\", \"hand-point-left\"], [\"hand-o-up\", \"far\", \"hand-point-up\"], [\"hand-o-down\", \"far\", \"hand-point-down\"], [\"arrows-alt\", null, \"expand-arrows-alt\"], [\"group\", null, \"users\"], [\"chain\", null, \"link\"], [\"scissors\", null, \"cut\"], [\"files-o\", \"far\", \"copy\"], [\"floppy-o\", \"far\", \"save\"], [\"navicon\", null, \"bars\"], [\"reorder\", null, \"bars\"], [\"pinterest\", \"fab\", null], [\"pinterest-square\", \"fab\", null], [\"google-plus-square\", \"fab\", null], [\"google-plus\", \"fab\", \"google-plus-g\"], [\"money\", \"far\", \"money-bill-alt\"], [\"unsorted\", null, \"sort\"], [\"sort-desc\", null, \"sort-down\"], [\"sort-asc\", null, \"sort-up\"], [\"linkedin\", \"fab\", \"linkedin-in\"], [\"rotate-left\", null, \"undo\"], [\"legal\", null, \"gavel\"], [\"tachometer\", null, \"tachometer-alt\"], [\"dashboard\", null, \"tachometer-alt\"], [\"comment-o\", \"far\", \"comment\"], [\"comments-o\", \"far\", \"comments\"], [\"flash\", null, \"bolt\"], [\"clipboard\", \"far\", null], [\"paste\", \"far\", \"clipboard\"], [\"lightbulb-o\", \"far\", \"lightbulb\"], [\"exchange\", null, \"exchange-alt\"], [\"cloud-download\", null, \"cloud-download-alt\"], [\"cloud-upload\", null, \"cloud-upload-alt\"], [\"bell-o\", \"far\", \"bell\"], [\"cutlery\", null, \"utensils\"], [\"file-text-o\", \"far\", \"file-alt\"], [\"building-o\", \"far\", \"building\"], [\"hospital-o\", \"far\", \"hospital\"], [\"tablet\", null, \"tablet-alt\"], [\"mobile\", null, \"mobile-alt\"], [\"mobile-phone\", null, \"mobile-alt\"], [\"circle-o\", \"far\", \"circle\"], [\"mail-reply\", null, \"reply\"], [\"github-alt\", \"fab\", null], [\"folder-o\", \"far\", \"folder\"], [\"folder-open-o\", \"far\", \"folder-open\"], [\"smile-o\", \"far\", \"smile\"], [\"frown-o\", \"far\", \"frown\"], [\"meh-o\", \"far\", \"meh\"], [\"keyboard-o\", \"far\", \"keyboard\"], [\"flag-o\", \"far\", \"flag\"], [\"mail-reply-all\", null, \"reply-all\"], [\"star-half-o\", \"far\", \"star-half\"], [\"star-half-empty\", \"far\", \"star-half\"], [\"star-half-full\", \"far\", \"star-half\"], [\"code-fork\", null, \"code-branch\"], [\"chain-broken\", null, \"unlink\"], [\"shield\", null, \"shield-alt\"], [\"calendar-o\", \"far\", \"calendar\"], [\"maxcdn\", \"fab\", null], [\"html5\", \"fab\", null], [\"css3\", \"fab\", null], [\"ticket\", null, \"ticket-alt\"], [\"minus-square-o\", \"far\", \"minus-square\"], [\"level-up\", null, \"level-up-alt\"], [\"level-down\", null, \"level-down-alt\"], [\"pencil-square\", null, \"pen-square\"], [\"external-link-square\", null, \"external-link-square-alt\"], [\"compass\", \"far\", null], [\"caret-square-o-down\", \"far\", \"caret-square-down\"], [\"toggle-down\", \"far\", \"caret-square-down\"], [\"caret-square-o-up\", \"far\", \"caret-square-up\"], [\"toggle-up\", \"far\", \"caret-square-up\"], [\"caret-square-o-right\", \"far\", \"caret-square-right\"], [\"toggle-right\", \"far\", \"caret-square-right\"], [\"eur\", null, \"euro-sign\"], [\"euro\", null, \"euro-sign\"], [\"gbp\", null, \"pound-sign\"], [\"usd\", null, \"dollar-sign\"], [\"dollar\", null, \"dollar-sign\"], [\"inr\", null, \"rupee-sign\"], [\"rupee\", null, \"rupee-sign\"], [\"jpy\", null, \"yen-sign\"], [\"cny\", null, \"yen-sign\"], [\"rmb\", null, \"yen-sign\"], [\"yen\", null, \"yen-sign\"], [\"rub\", null, \"ruble-sign\"], [\"ruble\", null, \"ruble-sign\"], [\"rouble\", null, \"ruble-sign\"], [\"krw\", null, \"won-sign\"], [\"won\", null, \"won-sign\"], [\"btc\", \"fab\", null], [\"bitcoin\", \"fab\", \"btc\"], [\"file-text\", null, \"file-alt\"], [\"sort-alpha-asc\", null, \"sort-alpha-down\"], [\"sort-alpha-desc\", null, \"sort-alpha-down-alt\"], [\"sort-amount-asc\", null, \"sort-amount-down\"], [\"sort-amount-desc\", null, \"sort-amount-down-alt\"], [\"sort-numeric-asc\", null, \"sort-numeric-down\"], [\"sort-numeric-desc\", null, \"sort-numeric-down-alt\"], [\"youtube-square\", \"fab\", null], [\"youtube\", \"fab\", null], [\"xing\", \"fab\", null], [\"xing-square\", \"fab\", null], [\"youtube-play\", \"fab\", \"youtube\"], [\"dropbox\", \"fab\", null], [\"stack-overflow\", \"fab\", null], [\"instagram\", \"fab\", null], [\"flickr\", \"fab\", null], [\"adn\", \"fab\", null], [\"bitbucket\", \"fab\", null], [\"bitbucket-square\", \"fab\", \"bitbucket\"], [\"tumblr\", \"fab\", null], [\"tumblr-square\", \"fab\", null], [\"long-arrow-down\", null, \"long-arrow-alt-down\"], [\"long-arrow-up\", null, \"long-arrow-alt-up\"], [\"long-arrow-left\", null, \"long-arrow-alt-left\"], [\"long-arrow-right\", null, \"long-arrow-alt-right\"], [\"apple\", \"fab\", null], [\"windows\", \"fab\", null], [\"android\", \"fab\", null], [\"linux\", \"fab\", null], [\"dribbble\", \"fab\", null], [\"skype\", \"fab\", null], [\"foursquare\", \"fab\", null], [\"trello\", \"fab\", null], [\"gratipay\", \"fab\", null], [\"gittip\", \"fab\", \"gratipay\"], [\"sun-o\", \"far\", \"sun\"], [\"moon-o\", \"far\", \"moon\"], [\"vk\", \"fab\", null], [\"weibo\", \"fab\", null], [\"renren\", \"fab\", null], [\"pagelines\", \"fab\", null], [\"stack-exchange\", \"fab\", null], [\"arrow-circle-o-right\", \"far\", \"arrow-alt-circle-right\"], [\"arrow-circle-o-left\", \"far\", \"arrow-alt-circle-left\"], [\"caret-square-o-left\", \"far\", \"caret-square-left\"], [\"toggle-left\", \"far\", \"caret-square-left\"], [\"dot-circle-o\", \"far\", \"dot-circle\"], [\"vimeo-square\", \"fab\", null], [\"try\", null, \"lira-sign\"], [\"turkish-lira\", null, \"lira-sign\"], [\"plus-square-o\", \"far\", \"plus-square\"], [\"slack\", \"fab\", null], [\"wordpress\", \"fab\", null], [\"openid\", \"fab\", null], [\"institution\", null, \"university\"], [\"bank\", null, \"university\"], [\"mortar-board\", null, \"graduation-cap\"], [\"yahoo\", \"fab\", null], [\"google\", \"fab\", null], [\"reddit\", \"fab\", null], [\"reddit-square\", \"fab\", null], [\"stumbleupon-circle\", \"fab\", null], [\"stumbleupon\", \"fab\", null], [\"delicious\", \"fab\", null], [\"digg\", \"fab\", null], [\"pied-piper-pp\", \"fab\", null], [\"pied-piper-alt\", \"fab\", null], [\"drupal\", \"fab\", null], [\"joomla\", \"fab\", null], [\"spoon\", null, \"utensil-spoon\"], [\"behance\", \"fab\", null], [\"behance-square\", \"fab\", null], [\"steam\", \"fab\", null], [\"steam-square\", \"fab\", null], [\"automobile\", null, \"car\"], [\"cab\", null, \"taxi\"], [\"envelope-o\", \"far\", \"envelope\"], [\"deviantart\", \"fab\", null], [\"soundcloud\", \"fab\", null], [\"file-pdf-o\", \"far\", \"file-pdf\"], [\"file-word-o\", \"far\", \"file-word\"], [\"file-excel-o\", \"far\", \"file-excel\"], [\"file-powerpoint-o\", \"far\", \"file-powerpoint\"], [\"file-image-o\", \"far\", \"file-image\"], [\"file-photo-o\", \"far\", \"file-image\"], [\"file-picture-o\", \"far\", \"file-image\"], [\"file-archive-o\", \"far\", \"file-archive\"], [\"file-zip-o\", \"far\", \"file-archive\"], [\"file-audio-o\", \"far\", \"file-audio\"], [\"file-sound-o\", \"far\", \"file-audio\"], [\"file-video-o\", \"far\", \"file-video\"], [\"file-movie-o\", \"far\", \"file-video\"], [\"file-code-o\", \"far\", \"file-code\"], [\"vine\", \"fab\", null], [\"codepen\", \"fab\", null], [\"jsfiddle\", \"fab\", null], [\"life-ring\", \"far\", null], [\"life-bouy\", \"far\", \"life-ring\"], [\"life-buoy\", \"far\", \"life-ring\"], [\"life-saver\", \"far\", \"life-ring\"], [\"support\", \"far\", \"life-ring\"], [\"circle-o-notch\", null, \"circle-notch\"], [\"rebel\", \"fab\", null], [\"ra\", \"fab\", \"rebel\"], [\"resistance\", \"fab\", \"rebel\"], [\"empire\", \"fab\", null], [\"ge\", \"fab\", \"empire\"], [\"git-square\", \"fab\", null], [\"git\", \"fab\", null], [\"hacker-news\", \"fab\", null], [\"y-combinator-square\", \"fab\", \"hacker-news\"], [\"yc-square\", \"fab\", \"hacker-news\"], [\"tencent-weibo\", \"fab\", null], [\"qq\", \"fab\", null], [\"weixin\", \"fab\", null], [\"wechat\", \"fab\", \"weixin\"], [\"send\", null, \"paper-plane\"], [\"paper-plane-o\", \"far\", \"paper-plane\"], [\"send-o\", \"far\", \"paper-plane\"], [\"circle-thin\", \"far\", \"circle\"], [\"header\", null, \"heading\"], [\"sliders\", null, \"sliders-h\"], [\"futbol-o\", \"far\", \"futbol\"], [\"soccer-ball-o\", \"far\", \"futbol\"], [\"slideshare\", \"fab\", null], [\"twitch\", \"fab\", null], [\"yelp\", \"fab\", null], [\"newspaper-o\", \"far\", \"newspaper\"], [\"paypal\", \"fab\", null], [\"google-wallet\", \"fab\", null], [\"cc-visa\", \"fab\", null], [\"cc-mastercard\", \"fab\", null], [\"cc-discover\", \"fab\", null], [\"cc-amex\", \"fab\", null], [\"cc-paypal\", \"fab\", null], [\"cc-stripe\", \"fab\", null], [\"bell-slash-o\", \"far\", \"bell-slash\"], [\"trash\", null, \"trash-alt\"], [\"copyright\", \"far\", null], [\"eyedropper\", null, \"eye-dropper\"], [\"area-chart\", null, \"chart-area\"], [\"pie-chart\", null, \"chart-pie\"], [\"line-chart\", null, \"chart-line\"], [\"lastfm\", \"fab\", null], [\"lastfm-square\", \"fab\", null], [\"ioxhost\", \"fab\", null], [\"angellist\", \"fab\", null], [\"cc\", \"far\", \"closed-captioning\"], [\"ils\", null, \"shekel-sign\"], [\"shekel\", null, \"shekel-sign\"], [\"sheqel\", null, \"shekel-sign\"], [\"meanpath\", \"fab\", \"font-awesome\"], [\"buysellads\", \"fab\", null], [\"connectdevelop\", \"fab\", null], [\"dashcube\", \"fab\", null], [\"forumbee\", \"fab\", null], [\"leanpub\", \"fab\", null], [\"sellsy\", \"fab\", null], [\"shirtsinbulk\", \"fab\", null], [\"simplybuilt\", \"fab\", null], [\"skyatlas\", \"fab\", null], [\"diamond\", \"far\", \"gem\"], [\"intersex\", null, \"transgender\"], [\"facebook-official\", \"fab\", \"facebook\"], [\"pinterest-p\", \"fab\", null], [\"whatsapp\", \"fab\", null], [\"hotel\", null, \"bed\"], [\"viacoin\", \"fab\", null], [\"medium\", \"fab\", null], [\"y-combinator\", \"fab\", null], [\"yc\", \"fab\", \"y-combinator\"], [\"optin-monster\", \"fab\", null], [\"opencart\", \"fab\", null], [\"expeditedssl\", \"fab\", null], [\"battery-4\", null, \"battery-full\"], [\"battery\", null, \"battery-full\"], [\"battery-3\", null, \"battery-three-quarters\"], [\"battery-2\", null, \"battery-half\"], [\"battery-1\", null, \"battery-quarter\"], [\"battery-0\", null, \"battery-empty\"], [\"object-group\", \"far\", null], [\"object-ungroup\", \"far\", null], [\"sticky-note-o\", \"far\", \"sticky-note\"], [\"cc-jcb\", \"fab\", null], [\"cc-diners-club\", \"fab\", null], [\"clone\", \"far\", null], [\"hourglass-o\", \"far\", \"hourglass\"], [\"hourglass-1\", null, \"hourglass-start\"], [\"hourglass-2\", null, \"hourglass-half\"], [\"hourglass-3\", null, \"hourglass-end\"], [\"hand-rock-o\", \"far\", \"hand-rock\"], [\"hand-grab-o\", \"far\", \"hand-rock\"], [\"hand-paper-o\", \"far\", \"hand-paper\"], [\"hand-stop-o\", \"far\", \"hand-paper\"], [\"hand-scissors-o\", \"far\", \"hand-scissors\"], [\"hand-lizard-o\", \"far\", \"hand-lizard\"], [\"hand-spock-o\", \"far\", \"hand-spock\"], [\"hand-pointer-o\", \"far\", \"hand-pointer\"], [\"hand-peace-o\", \"far\", \"hand-peace\"], [\"registered\", \"far\", null], [\"creative-commons\", \"fab\", null], [\"gg\", \"fab\", null], [\"gg-circle\", \"fab\", null], [\"tripadvisor\", \"fab\", null], [\"odnoklassniki\", \"fab\", null], [\"odnoklassniki-square\", \"fab\", null], [\"get-pocket\", \"fab\", null], [\"wikipedia-w\", \"fab\", null], [\"safari\", \"fab\", null], [\"chrome\", \"fab\", null], [\"firefox\", \"fab\", null], [\"opera\", \"fab\", null], [\"internet-explorer\", \"fab\", null], [\"television\", null, \"tv\"], [\"contao\", \"fab\", null], [\"500px\", \"fab\", null], [\"amazon\", \"fab\", null], [\"calendar-plus-o\", \"far\", \"calendar-plus\"], [\"calendar-minus-o\", \"far\", \"calendar-minus\"], [\"calendar-times-o\", \"far\", \"calendar-times\"], [\"calendar-check-o\", \"far\", \"calendar-check\"], [\"map-o\", \"far\", \"map\"], [\"commenting\", null, \"comment-dots\"], [\"commenting-o\", \"far\", \"comment-dots\"], [\"houzz\", \"fab\", null], [\"vimeo\", \"fab\", \"vimeo-v\"], [\"black-tie\", \"fab\", null], [\"fonticons\", \"fab\", null], [\"reddit-alien\", \"fab\", null], [\"edge\", \"fab\", null], [\"credit-card-alt\", null, \"credit-card\"], [\"codiepie\", \"fab\", null], [\"modx\", \"fab\", null], [\"fort-awesome\", \"fab\", null], [\"usb\", \"fab\", null], [\"product-hunt\", \"fab\", null], [\"mixcloud\", \"fab\", null], [\"scribd\", \"fab\", null], [\"pause-circle-o\", \"far\", \"pause-circle\"], [\"stop-circle-o\", \"far\", \"stop-circle\"], [\"bluetooth\", \"fab\", null], [\"bluetooth-b\", \"fab\", null], [\"gitlab\", \"fab\", null], [\"wpbeginner\", \"fab\", null], [\"wpforms\", \"fab\", null], [\"envira\", \"fab\", null], [\"wheelchair-alt\", \"fab\", \"accessible-icon\"], [\"question-circle-o\", \"far\", \"question-circle\"], [\"volume-control-phone\", null, \"phone-volume\"], [\"asl-interpreting\", null, \"american-sign-language-interpreting\"], [\"deafness\", null, \"deaf\"], [\"hard-of-hearing\", null, \"deaf\"], [\"glide\", \"fab\", null], [\"glide-g\", \"fab\", null], [\"signing\", null, \"sign-language\"], [\"viadeo\", \"fab\", null], [\"viadeo-square\", \"fab\", null], [\"snapchat\", \"fab\", null], [\"snapchat-ghost\", \"fab\", null], [\"snapchat-square\", \"fab\", null], [\"pied-piper\", \"fab\", null], [\"first-order\", \"fab\", null], [\"yoast\", \"fab\", null], [\"themeisle\", \"fab\", null], [\"google-plus-official\", \"fab\", \"google-plus\"], [\"google-plus-circle\", \"fab\", \"google-plus\"], [\"font-awesome\", \"fab\", null], [\"fa\", \"fab\", \"font-awesome\"], [\"handshake-o\", \"far\", \"handshake\"], [\"envelope-open-o\", \"far\", \"envelope-open\"], [\"linode\", \"fab\", null], [\"address-book-o\", \"far\", \"address-book\"], [\"vcard\", null, \"address-card\"], [\"address-card-o\", \"far\", \"address-card\"], [\"vcard-o\", \"far\", \"address-card\"], [\"user-circle-o\", \"far\", \"user-circle\"], [\"user-o\", \"far\", \"user\"], [\"id-badge\", \"far\", null], [\"drivers-license\", null, \"id-card\"], [\"id-card-o\", \"far\", \"id-card\"], [\"drivers-license-o\", \"far\", \"id-card\"], [\"quora\", \"fab\", null], [\"free-code-camp\", \"fab\", null], [\"telegram\", \"fab\", null], [\"thermometer-4\", null, \"thermometer-full\"], [\"thermometer\", null, \"thermometer-full\"], [\"thermometer-3\", null, \"thermometer-three-quarters\"], [\"thermometer-2\", null, \"thermometer-half\"], [\"thermometer-1\", null, \"thermometer-quarter\"], [\"thermometer-0\", null, \"thermometer-empty\"], [\"bathtub\", null, \"bath\"], [\"s15\", null, \"bath\"], [\"window-maximize\", \"far\", null], [\"window-restore\", \"far\", null], [\"times-rectangle\", null, \"window-close\"], [\"window-close-o\", \"far\", \"window-close\"], [\"times-rectangle-o\", \"far\", \"window-close\"], [\"bandcamp\", \"fab\", null], [\"grav\", \"fab\", null], [\"etsy\", \"fab\", null], [\"imdb\", \"fab\", null], [\"ravelry\", \"fab\", null], [\"eercast\", \"fab\", \"sellcast\"], [\"snowflake-o\", \"far\", \"snowflake\"], [\"superpowers\", \"fab\", null], [\"wpexplorer\", \"fab\", null], [\"spotify\", \"fab\", null]];\n  bunker(function () {\n    if (typeof namespace.hooks.addShims === 'function') {\n      namespace.hooks.addShims(shims);\n    } else {\n      var _namespace$shims;\n\n      (_namespace$shims = namespace.shims).push.apply(_namespace$shims, shims);\n    }\n  });\n\n  return shims;\n\n})));\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_animated.less",
    "content": "// Animated Icons\n// --------------------------\n\n.@{fa-css-prefix}-spin {\n  animation: fa-spin 2s infinite linear;\n}\n\n.@{fa-css-prefix}-pulse {\n  animation: fa-spin 1s infinite steps(8);\n}\n\n@keyframes fa-spin {\n  0% {\n    transform: rotate(0deg);\n  }\n  100% {\n    transform: rotate(360deg);\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_bordered-pulled.less",
    "content": "// Bordered & Pulled\n// -------------------------\n\n.@{fa-css-prefix}-border {\n  border-radius: .1em;\n  border: solid .08em @fa-border-color;\n  padding: .2em .25em .15em;\n}\n\n.@{fa-css-prefix}-pull-left { float: left; }\n.@{fa-css-prefix}-pull-right { float: right; }\n\n.@{fa-css-prefix}, .fas, .far, .fal, .fab {\n  &.@{fa-css-prefix}-pull-left { margin-right: .3em; }\n  &.@{fa-css-prefix}-pull-right { margin-left: .3em; }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_core.less",
    "content": "// Base Class Definition\n// -------------------------\n\n.@{fa-css-prefix}, .fas, .far, .fal, .fad, .fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_fixed-width.less",
    "content": "// Fixed Width Icons\n// -------------------------\n.@{fa-css-prefix}-fw {\n  text-align: center;\n  width: (20em / 16);\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_icons.less",
    "content": "/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\n   readers do not read off random characters that represent icons */\n\n.@{fa-css-prefix}-500px:before { content: @fa-var-500px; }\n.@{fa-css-prefix}-accessible-icon:before { content: @fa-var-accessible-icon; }\n.@{fa-css-prefix}-accusoft:before { content: @fa-var-accusoft; }\n.@{fa-css-prefix}-acquisitions-incorporated:before { content: @fa-var-acquisitions-incorporated; }\n.@{fa-css-prefix}-ad:before { content: @fa-var-ad; }\n.@{fa-css-prefix}-address-book:before { content: @fa-var-address-book; }\n.@{fa-css-prefix}-address-card:before { content: @fa-var-address-card; }\n.@{fa-css-prefix}-adjust:before { content: @fa-var-adjust; }\n.@{fa-css-prefix}-adn:before { content: @fa-var-adn; }\n.@{fa-css-prefix}-adobe:before { content: @fa-var-adobe; }\n.@{fa-css-prefix}-adversal:before { content: @fa-var-adversal; }\n.@{fa-css-prefix}-affiliatetheme:before { content: @fa-var-affiliatetheme; }\n.@{fa-css-prefix}-air-freshener:before { content: @fa-var-air-freshener; }\n.@{fa-css-prefix}-airbnb:before { content: @fa-var-airbnb; }\n.@{fa-css-prefix}-algolia:before { content: @fa-var-algolia; }\n.@{fa-css-prefix}-align-center:before { content: @fa-var-align-center; }\n.@{fa-css-prefix}-align-justify:before { content: @fa-var-align-justify; }\n.@{fa-css-prefix}-align-left:before { content: @fa-var-align-left; }\n.@{fa-css-prefix}-align-right:before { content: @fa-var-align-right; }\n.@{fa-css-prefix}-alipay:before { content: @fa-var-alipay; }\n.@{fa-css-prefix}-allergies:before { content: @fa-var-allergies; }\n.@{fa-css-prefix}-amazon:before { content: @fa-var-amazon; }\n.@{fa-css-prefix}-amazon-pay:before { content: @fa-var-amazon-pay; }\n.@{fa-css-prefix}-ambulance:before { content: @fa-var-ambulance; }\n.@{fa-css-prefix}-american-sign-language-interpreting:before { content: @fa-var-american-sign-language-interpreting; }\n.@{fa-css-prefix}-amilia:before { content: @fa-var-amilia; }\n.@{fa-css-prefix}-anchor:before { content: @fa-var-anchor; }\n.@{fa-css-prefix}-android:before { content: @fa-var-android; }\n.@{fa-css-prefix}-angellist:before { content: @fa-var-angellist; }\n.@{fa-css-prefix}-angle-double-down:before { content: @fa-var-angle-double-down; }\n.@{fa-css-prefix}-angle-double-left:before { content: @fa-var-angle-double-left; }\n.@{fa-css-prefix}-angle-double-right:before { content: @fa-var-angle-double-right; }\n.@{fa-css-prefix}-angle-double-up:before { content: @fa-var-angle-double-up; }\n.@{fa-css-prefix}-angle-down:before { content: @fa-var-angle-down; }\n.@{fa-css-prefix}-angle-left:before { content: @fa-var-angle-left; }\n.@{fa-css-prefix}-angle-right:before { content: @fa-var-angle-right; }\n.@{fa-css-prefix}-angle-up:before { content: @fa-var-angle-up; }\n.@{fa-css-prefix}-angry:before { content: @fa-var-angry; }\n.@{fa-css-prefix}-angrycreative:before { content: @fa-var-angrycreative; }\n.@{fa-css-prefix}-angular:before { content: @fa-var-angular; }\n.@{fa-css-prefix}-ankh:before { content: @fa-var-ankh; }\n.@{fa-css-prefix}-app-store:before { content: @fa-var-app-store; }\n.@{fa-css-prefix}-app-store-ios:before { content: @fa-var-app-store-ios; }\n.@{fa-css-prefix}-apper:before { content: @fa-var-apper; }\n.@{fa-css-prefix}-apple:before { content: @fa-var-apple; }\n.@{fa-css-prefix}-apple-alt:before { content: @fa-var-apple-alt; }\n.@{fa-css-prefix}-apple-pay:before { content: @fa-var-apple-pay; }\n.@{fa-css-prefix}-archive:before { content: @fa-var-archive; }\n.@{fa-css-prefix}-archway:before { content: @fa-var-archway; }\n.@{fa-css-prefix}-arrow-alt-circle-down:before { content: @fa-var-arrow-alt-circle-down; }\n.@{fa-css-prefix}-arrow-alt-circle-left:before { content: @fa-var-arrow-alt-circle-left; }\n.@{fa-css-prefix}-arrow-alt-circle-right:before { content: @fa-var-arrow-alt-circle-right; }\n.@{fa-css-prefix}-arrow-alt-circle-up:before { content: @fa-var-arrow-alt-circle-up; }\n.@{fa-css-prefix}-arrow-circle-down:before { content: @fa-var-arrow-circle-down; }\n.@{fa-css-prefix}-arrow-circle-left:before { content: @fa-var-arrow-circle-left; }\n.@{fa-css-prefix}-arrow-circle-right:before { content: @fa-var-arrow-circle-right; }\n.@{fa-css-prefix}-arrow-circle-up:before { content: @fa-var-arrow-circle-up; }\n.@{fa-css-prefix}-arrow-down:before { content: @fa-var-arrow-down; }\n.@{fa-css-prefix}-arrow-left:before { content: @fa-var-arrow-left; }\n.@{fa-css-prefix}-arrow-right:before { content: @fa-var-arrow-right; }\n.@{fa-css-prefix}-arrow-up:before { content: @fa-var-arrow-up; }\n.@{fa-css-prefix}-arrows-alt:before { content: @fa-var-arrows-alt; }\n.@{fa-css-prefix}-arrows-alt-h:before { content: @fa-var-arrows-alt-h; }\n.@{fa-css-prefix}-arrows-alt-v:before { content: @fa-var-arrows-alt-v; }\n.@{fa-css-prefix}-artstation:before { content: @fa-var-artstation; }\n.@{fa-css-prefix}-assistive-listening-systems:before { content: @fa-var-assistive-listening-systems; }\n.@{fa-css-prefix}-asterisk:before { content: @fa-var-asterisk; }\n.@{fa-css-prefix}-asymmetrik:before { content: @fa-var-asymmetrik; }\n.@{fa-css-prefix}-at:before { content: @fa-var-at; }\n.@{fa-css-prefix}-atlas:before { content: @fa-var-atlas; }\n.@{fa-css-prefix}-atlassian:before { content: @fa-var-atlassian; }\n.@{fa-css-prefix}-atom:before { content: @fa-var-atom; }\n.@{fa-css-prefix}-audible:before { content: @fa-var-audible; }\n.@{fa-css-prefix}-audio-description:before { content: @fa-var-audio-description; }\n.@{fa-css-prefix}-autoprefixer:before { content: @fa-var-autoprefixer; }\n.@{fa-css-prefix}-avianex:before { content: @fa-var-avianex; }\n.@{fa-css-prefix}-aviato:before { content: @fa-var-aviato; }\n.@{fa-css-prefix}-award:before { content: @fa-var-award; }\n.@{fa-css-prefix}-aws:before { content: @fa-var-aws; }\n.@{fa-css-prefix}-baby:before { content: @fa-var-baby; }\n.@{fa-css-prefix}-baby-carriage:before { content: @fa-var-baby-carriage; }\n.@{fa-css-prefix}-backspace:before { content: @fa-var-backspace; }\n.@{fa-css-prefix}-backward:before { content: @fa-var-backward; }\n.@{fa-css-prefix}-bacon:before { content: @fa-var-bacon; }\n.@{fa-css-prefix}-balance-scale:before { content: @fa-var-balance-scale; }\n.@{fa-css-prefix}-balance-scale-left:before { content: @fa-var-balance-scale-left; }\n.@{fa-css-prefix}-balance-scale-right:before { content: @fa-var-balance-scale-right; }\n.@{fa-css-prefix}-ban:before { content: @fa-var-ban; }\n.@{fa-css-prefix}-band-aid:before { content: @fa-var-band-aid; }\n.@{fa-css-prefix}-bandcamp:before { content: @fa-var-bandcamp; }\n.@{fa-css-prefix}-barcode:before { content: @fa-var-barcode; }\n.@{fa-css-prefix}-bars:before { content: @fa-var-bars; }\n.@{fa-css-prefix}-baseball-ball:before { content: @fa-var-baseball-ball; }\n.@{fa-css-prefix}-basketball-ball:before { content: @fa-var-basketball-ball; }\n.@{fa-css-prefix}-bath:before { content: @fa-var-bath; }\n.@{fa-css-prefix}-battery-empty:before { content: @fa-var-battery-empty; }\n.@{fa-css-prefix}-battery-full:before { content: @fa-var-battery-full; }\n.@{fa-css-prefix}-battery-half:before { content: @fa-var-battery-half; }\n.@{fa-css-prefix}-battery-quarter:before { content: @fa-var-battery-quarter; }\n.@{fa-css-prefix}-battery-three-quarters:before { content: @fa-var-battery-three-quarters; }\n.@{fa-css-prefix}-battle-net:before { content: @fa-var-battle-net; }\n.@{fa-css-prefix}-bed:before { content: @fa-var-bed; }\n.@{fa-css-prefix}-beer:before { content: @fa-var-beer; }\n.@{fa-css-prefix}-behance:before { content: @fa-var-behance; }\n.@{fa-css-prefix}-behance-square:before { content: @fa-var-behance-square; }\n.@{fa-css-prefix}-bell:before { content: @fa-var-bell; }\n.@{fa-css-prefix}-bell-slash:before { content: @fa-var-bell-slash; }\n.@{fa-css-prefix}-bezier-curve:before { content: @fa-var-bezier-curve; }\n.@{fa-css-prefix}-bible:before { content: @fa-var-bible; }\n.@{fa-css-prefix}-bicycle:before { content: @fa-var-bicycle; }\n.@{fa-css-prefix}-biking:before { content: @fa-var-biking; }\n.@{fa-css-prefix}-bimobject:before { content: @fa-var-bimobject; }\n.@{fa-css-prefix}-binoculars:before { content: @fa-var-binoculars; }\n.@{fa-css-prefix}-biohazard:before { content: @fa-var-biohazard; }\n.@{fa-css-prefix}-birthday-cake:before { content: @fa-var-birthday-cake; }\n.@{fa-css-prefix}-bitbucket:before { content: @fa-var-bitbucket; }\n.@{fa-css-prefix}-bitcoin:before { content: @fa-var-bitcoin; }\n.@{fa-css-prefix}-bity:before { content: @fa-var-bity; }\n.@{fa-css-prefix}-black-tie:before { content: @fa-var-black-tie; }\n.@{fa-css-prefix}-blackberry:before { content: @fa-var-blackberry; }\n.@{fa-css-prefix}-blender:before { content: @fa-var-blender; }\n.@{fa-css-prefix}-blender-phone:before { content: @fa-var-blender-phone; }\n.@{fa-css-prefix}-blind:before { content: @fa-var-blind; }\n.@{fa-css-prefix}-blog:before { content: @fa-var-blog; }\n.@{fa-css-prefix}-blogger:before { content: @fa-var-blogger; }\n.@{fa-css-prefix}-blogger-b:before { content: @fa-var-blogger-b; }\n.@{fa-css-prefix}-bluetooth:before { content: @fa-var-bluetooth; }\n.@{fa-css-prefix}-bluetooth-b:before { content: @fa-var-bluetooth-b; }\n.@{fa-css-prefix}-bold:before { content: @fa-var-bold; }\n.@{fa-css-prefix}-bolt:before { content: @fa-var-bolt; }\n.@{fa-css-prefix}-bomb:before { content: @fa-var-bomb; }\n.@{fa-css-prefix}-bone:before { content: @fa-var-bone; }\n.@{fa-css-prefix}-bong:before { content: @fa-var-bong; }\n.@{fa-css-prefix}-book:before { content: @fa-var-book; }\n.@{fa-css-prefix}-book-dead:before { content: @fa-var-book-dead; }\n.@{fa-css-prefix}-book-medical:before { content: @fa-var-book-medical; }\n.@{fa-css-prefix}-book-open:before { content: @fa-var-book-open; }\n.@{fa-css-prefix}-book-reader:before { content: @fa-var-book-reader; }\n.@{fa-css-prefix}-bookmark:before { content: @fa-var-bookmark; }\n.@{fa-css-prefix}-bootstrap:before { content: @fa-var-bootstrap; }\n.@{fa-css-prefix}-border-all:before { content: @fa-var-border-all; }\n.@{fa-css-prefix}-border-none:before { content: @fa-var-border-none; }\n.@{fa-css-prefix}-border-style:before { content: @fa-var-border-style; }\n.@{fa-css-prefix}-bowling-ball:before { content: @fa-var-bowling-ball; }\n.@{fa-css-prefix}-box:before { content: @fa-var-box; }\n.@{fa-css-prefix}-box-open:before { content: @fa-var-box-open; }\n.@{fa-css-prefix}-boxes:before { content: @fa-var-boxes; }\n.@{fa-css-prefix}-braille:before { content: @fa-var-braille; }\n.@{fa-css-prefix}-brain:before { content: @fa-var-brain; }\n.@{fa-css-prefix}-bread-slice:before { content: @fa-var-bread-slice; }\n.@{fa-css-prefix}-briefcase:before { content: @fa-var-briefcase; }\n.@{fa-css-prefix}-briefcase-medical:before { content: @fa-var-briefcase-medical; }\n.@{fa-css-prefix}-broadcast-tower:before { content: @fa-var-broadcast-tower; }\n.@{fa-css-prefix}-broom:before { content: @fa-var-broom; }\n.@{fa-css-prefix}-brush:before { content: @fa-var-brush; }\n.@{fa-css-prefix}-btc:before { content: @fa-var-btc; }\n.@{fa-css-prefix}-buffer:before { content: @fa-var-buffer; }\n.@{fa-css-prefix}-bug:before { content: @fa-var-bug; }\n.@{fa-css-prefix}-building:before { content: @fa-var-building; }\n.@{fa-css-prefix}-bullhorn:before { content: @fa-var-bullhorn; }\n.@{fa-css-prefix}-bullseye:before { content: @fa-var-bullseye; }\n.@{fa-css-prefix}-burn:before { content: @fa-var-burn; }\n.@{fa-css-prefix}-buromobelexperte:before { content: @fa-var-buromobelexperte; }\n.@{fa-css-prefix}-bus:before { content: @fa-var-bus; }\n.@{fa-css-prefix}-bus-alt:before { content: @fa-var-bus-alt; }\n.@{fa-css-prefix}-business-time:before { content: @fa-var-business-time; }\n.@{fa-css-prefix}-buysellads:before { content: @fa-var-buysellads; }\n.@{fa-css-prefix}-calculator:before { content: @fa-var-calculator; }\n.@{fa-css-prefix}-calendar:before { content: @fa-var-calendar; }\n.@{fa-css-prefix}-calendar-alt:before { content: @fa-var-calendar-alt; }\n.@{fa-css-prefix}-calendar-check:before { content: @fa-var-calendar-check; }\n.@{fa-css-prefix}-calendar-day:before { content: @fa-var-calendar-day; }\n.@{fa-css-prefix}-calendar-minus:before { content: @fa-var-calendar-minus; }\n.@{fa-css-prefix}-calendar-plus:before { content: @fa-var-calendar-plus; }\n.@{fa-css-prefix}-calendar-times:before { content: @fa-var-calendar-times; }\n.@{fa-css-prefix}-calendar-week:before { content: @fa-var-calendar-week; }\n.@{fa-css-prefix}-camera:before { content: @fa-var-camera; }\n.@{fa-css-prefix}-camera-retro:before { content: @fa-var-camera-retro; }\n.@{fa-css-prefix}-campground:before { content: @fa-var-campground; }\n.@{fa-css-prefix}-canadian-maple-leaf:before { content: @fa-var-canadian-maple-leaf; }\n.@{fa-css-prefix}-candy-cane:before { content: @fa-var-candy-cane; }\n.@{fa-css-prefix}-cannabis:before { content: @fa-var-cannabis; }\n.@{fa-css-prefix}-capsules:before { content: @fa-var-capsules; }\n.@{fa-css-prefix}-car:before { content: @fa-var-car; }\n.@{fa-css-prefix}-car-alt:before { content: @fa-var-car-alt; }\n.@{fa-css-prefix}-car-battery:before { content: @fa-var-car-battery; }\n.@{fa-css-prefix}-car-crash:before { content: @fa-var-car-crash; }\n.@{fa-css-prefix}-car-side:before { content: @fa-var-car-side; }\n.@{fa-css-prefix}-caret-down:before { content: @fa-var-caret-down; }\n.@{fa-css-prefix}-caret-left:before { content: @fa-var-caret-left; }\n.@{fa-css-prefix}-caret-right:before { content: @fa-var-caret-right; }\n.@{fa-css-prefix}-caret-square-down:before { content: @fa-var-caret-square-down; }\n.@{fa-css-prefix}-caret-square-left:before { content: @fa-var-caret-square-left; }\n.@{fa-css-prefix}-caret-square-right:before { content: @fa-var-caret-square-right; }\n.@{fa-css-prefix}-caret-square-up:before { content: @fa-var-caret-square-up; }\n.@{fa-css-prefix}-caret-up:before { content: @fa-var-caret-up; }\n.@{fa-css-prefix}-carrot:before { content: @fa-var-carrot; }\n.@{fa-css-prefix}-cart-arrow-down:before { content: @fa-var-cart-arrow-down; }\n.@{fa-css-prefix}-cart-plus:before { content: @fa-var-cart-plus; }\n.@{fa-css-prefix}-cash-register:before { content: @fa-var-cash-register; }\n.@{fa-css-prefix}-cat:before { content: @fa-var-cat; }\n.@{fa-css-prefix}-cc-amazon-pay:before { content: @fa-var-cc-amazon-pay; }\n.@{fa-css-prefix}-cc-amex:before { content: @fa-var-cc-amex; }\n.@{fa-css-prefix}-cc-apple-pay:before { content: @fa-var-cc-apple-pay; }\n.@{fa-css-prefix}-cc-diners-club:before { content: @fa-var-cc-diners-club; }\n.@{fa-css-prefix}-cc-discover:before { content: @fa-var-cc-discover; }\n.@{fa-css-prefix}-cc-jcb:before { content: @fa-var-cc-jcb; }\n.@{fa-css-prefix}-cc-mastercard:before { content: @fa-var-cc-mastercard; }\n.@{fa-css-prefix}-cc-paypal:before { content: @fa-var-cc-paypal; }\n.@{fa-css-prefix}-cc-stripe:before { content: @fa-var-cc-stripe; }\n.@{fa-css-prefix}-cc-visa:before { content: @fa-var-cc-visa; }\n.@{fa-css-prefix}-centercode:before { content: @fa-var-centercode; }\n.@{fa-css-prefix}-centos:before { content: @fa-var-centos; }\n.@{fa-css-prefix}-certificate:before { content: @fa-var-certificate; }\n.@{fa-css-prefix}-chair:before { content: @fa-var-chair; }\n.@{fa-css-prefix}-chalkboard:before { content: @fa-var-chalkboard; }\n.@{fa-css-prefix}-chalkboard-teacher:before { content: @fa-var-chalkboard-teacher; }\n.@{fa-css-prefix}-charging-station:before { content: @fa-var-charging-station; }\n.@{fa-css-prefix}-chart-area:before { content: @fa-var-chart-area; }\n.@{fa-css-prefix}-chart-bar:before { content: @fa-var-chart-bar; }\n.@{fa-css-prefix}-chart-line:before { content: @fa-var-chart-line; }\n.@{fa-css-prefix}-chart-pie:before { content: @fa-var-chart-pie; }\n.@{fa-css-prefix}-check:before { content: @fa-var-check; }\n.@{fa-css-prefix}-check-circle:before { content: @fa-var-check-circle; }\n.@{fa-css-prefix}-check-double:before { content: @fa-var-check-double; }\n.@{fa-css-prefix}-check-square:before { content: @fa-var-check-square; }\n.@{fa-css-prefix}-cheese:before { content: @fa-var-cheese; }\n.@{fa-css-prefix}-chess:before { content: @fa-var-chess; }\n.@{fa-css-prefix}-chess-bishop:before { content: @fa-var-chess-bishop; }\n.@{fa-css-prefix}-chess-board:before { content: @fa-var-chess-board; }\n.@{fa-css-prefix}-chess-king:before { content: @fa-var-chess-king; }\n.@{fa-css-prefix}-chess-knight:before { content: @fa-var-chess-knight; }\n.@{fa-css-prefix}-chess-pawn:before { content: @fa-var-chess-pawn; }\n.@{fa-css-prefix}-chess-queen:before { content: @fa-var-chess-queen; }\n.@{fa-css-prefix}-chess-rook:before { content: @fa-var-chess-rook; }\n.@{fa-css-prefix}-chevron-circle-down:before { content: @fa-var-chevron-circle-down; }\n.@{fa-css-prefix}-chevron-circle-left:before { content: @fa-var-chevron-circle-left; }\n.@{fa-css-prefix}-chevron-circle-right:before { content: @fa-var-chevron-circle-right; }\n.@{fa-css-prefix}-chevron-circle-up:before { content: @fa-var-chevron-circle-up; }\n.@{fa-css-prefix}-chevron-down:before { content: @fa-var-chevron-down; }\n.@{fa-css-prefix}-chevron-left:before { content: @fa-var-chevron-left; }\n.@{fa-css-prefix}-chevron-right:before { content: @fa-var-chevron-right; }\n.@{fa-css-prefix}-chevron-up:before { content: @fa-var-chevron-up; }\n.@{fa-css-prefix}-child:before { content: @fa-var-child; }\n.@{fa-css-prefix}-chrome:before { content: @fa-var-chrome; }\n.@{fa-css-prefix}-chromecast:before { content: @fa-var-chromecast; }\n.@{fa-css-prefix}-church:before { content: @fa-var-church; }\n.@{fa-css-prefix}-circle:before { content: @fa-var-circle; }\n.@{fa-css-prefix}-circle-notch:before { content: @fa-var-circle-notch; }\n.@{fa-css-prefix}-city:before { content: @fa-var-city; }\n.@{fa-css-prefix}-clinic-medical:before { content: @fa-var-clinic-medical; }\n.@{fa-css-prefix}-clipboard:before { content: @fa-var-clipboard; }\n.@{fa-css-prefix}-clipboard-check:before { content: @fa-var-clipboard-check; }\n.@{fa-css-prefix}-clipboard-list:before { content: @fa-var-clipboard-list; }\n.@{fa-css-prefix}-clock:before { content: @fa-var-clock; }\n.@{fa-css-prefix}-clone:before { content: @fa-var-clone; }\n.@{fa-css-prefix}-closed-captioning:before { content: @fa-var-closed-captioning; }\n.@{fa-css-prefix}-cloud:before { content: @fa-var-cloud; }\n.@{fa-css-prefix}-cloud-download-alt:before { content: @fa-var-cloud-download-alt; }\n.@{fa-css-prefix}-cloud-meatball:before { content: @fa-var-cloud-meatball; }\n.@{fa-css-prefix}-cloud-moon:before { content: @fa-var-cloud-moon; }\n.@{fa-css-prefix}-cloud-moon-rain:before { content: @fa-var-cloud-moon-rain; }\n.@{fa-css-prefix}-cloud-rain:before { content: @fa-var-cloud-rain; }\n.@{fa-css-prefix}-cloud-showers-heavy:before { content: @fa-var-cloud-showers-heavy; }\n.@{fa-css-prefix}-cloud-sun:before { content: @fa-var-cloud-sun; }\n.@{fa-css-prefix}-cloud-sun-rain:before { content: @fa-var-cloud-sun-rain; }\n.@{fa-css-prefix}-cloud-upload-alt:before { content: @fa-var-cloud-upload-alt; }\n.@{fa-css-prefix}-cloudscale:before { content: @fa-var-cloudscale; }\n.@{fa-css-prefix}-cloudsmith:before { content: @fa-var-cloudsmith; }\n.@{fa-css-prefix}-cloudversify:before { content: @fa-var-cloudversify; }\n.@{fa-css-prefix}-cocktail:before { content: @fa-var-cocktail; }\n.@{fa-css-prefix}-code:before { content: @fa-var-code; }\n.@{fa-css-prefix}-code-branch:before { content: @fa-var-code-branch; }\n.@{fa-css-prefix}-codepen:before { content: @fa-var-codepen; }\n.@{fa-css-prefix}-codiepie:before { content: @fa-var-codiepie; }\n.@{fa-css-prefix}-coffee:before { content: @fa-var-coffee; }\n.@{fa-css-prefix}-cog:before { content: @fa-var-cog; }\n.@{fa-css-prefix}-cogs:before { content: @fa-var-cogs; }\n.@{fa-css-prefix}-coins:before { content: @fa-var-coins; }\n.@{fa-css-prefix}-columns:before { content: @fa-var-columns; }\n.@{fa-css-prefix}-comment:before { content: @fa-var-comment; }\n.@{fa-css-prefix}-comment-alt:before { content: @fa-var-comment-alt; }\n.@{fa-css-prefix}-comment-dollar:before { content: @fa-var-comment-dollar; }\n.@{fa-css-prefix}-comment-dots:before { content: @fa-var-comment-dots; }\n.@{fa-css-prefix}-comment-medical:before { content: @fa-var-comment-medical; }\n.@{fa-css-prefix}-comment-slash:before { content: @fa-var-comment-slash; }\n.@{fa-css-prefix}-comments:before { content: @fa-var-comments; }\n.@{fa-css-prefix}-comments-dollar:before { content: @fa-var-comments-dollar; }\n.@{fa-css-prefix}-compact-disc:before { content: @fa-var-compact-disc; }\n.@{fa-css-prefix}-compass:before { content: @fa-var-compass; }\n.@{fa-css-prefix}-compress:before { content: @fa-var-compress; }\n.@{fa-css-prefix}-compress-arrows-alt:before { content: @fa-var-compress-arrows-alt; }\n.@{fa-css-prefix}-concierge-bell:before { content: @fa-var-concierge-bell; }\n.@{fa-css-prefix}-confluence:before { content: @fa-var-confluence; }\n.@{fa-css-prefix}-connectdevelop:before { content: @fa-var-connectdevelop; }\n.@{fa-css-prefix}-contao:before { content: @fa-var-contao; }\n.@{fa-css-prefix}-cookie:before { content: @fa-var-cookie; }\n.@{fa-css-prefix}-cookie-bite:before { content: @fa-var-cookie-bite; }\n.@{fa-css-prefix}-copy:before { content: @fa-var-copy; }\n.@{fa-css-prefix}-copyright:before { content: @fa-var-copyright; }\n.@{fa-css-prefix}-cotton-bureau:before { content: @fa-var-cotton-bureau; }\n.@{fa-css-prefix}-couch:before { content: @fa-var-couch; }\n.@{fa-css-prefix}-cpanel:before { content: @fa-var-cpanel; }\n.@{fa-css-prefix}-creative-commons:before { content: @fa-var-creative-commons; }\n.@{fa-css-prefix}-creative-commons-by:before { content: @fa-var-creative-commons-by; }\n.@{fa-css-prefix}-creative-commons-nc:before { content: @fa-var-creative-commons-nc; }\n.@{fa-css-prefix}-creative-commons-nc-eu:before { content: @fa-var-creative-commons-nc-eu; }\n.@{fa-css-prefix}-creative-commons-nc-jp:before { content: @fa-var-creative-commons-nc-jp; }\n.@{fa-css-prefix}-creative-commons-nd:before { content: @fa-var-creative-commons-nd; }\n.@{fa-css-prefix}-creative-commons-pd:before { content: @fa-var-creative-commons-pd; }\n.@{fa-css-prefix}-creative-commons-pd-alt:before { content: @fa-var-creative-commons-pd-alt; }\n.@{fa-css-prefix}-creative-commons-remix:before { content: @fa-var-creative-commons-remix; }\n.@{fa-css-prefix}-creative-commons-sa:before { content: @fa-var-creative-commons-sa; }\n.@{fa-css-prefix}-creative-commons-sampling:before { content: @fa-var-creative-commons-sampling; }\n.@{fa-css-prefix}-creative-commons-sampling-plus:before { content: @fa-var-creative-commons-sampling-plus; }\n.@{fa-css-prefix}-creative-commons-share:before { content: @fa-var-creative-commons-share; }\n.@{fa-css-prefix}-creative-commons-zero:before { content: @fa-var-creative-commons-zero; }\n.@{fa-css-prefix}-credit-card:before { content: @fa-var-credit-card; }\n.@{fa-css-prefix}-critical-role:before { content: @fa-var-critical-role; }\n.@{fa-css-prefix}-crop:before { content: @fa-var-crop; }\n.@{fa-css-prefix}-crop-alt:before { content: @fa-var-crop-alt; }\n.@{fa-css-prefix}-cross:before { content: @fa-var-cross; }\n.@{fa-css-prefix}-crosshairs:before { content: @fa-var-crosshairs; }\n.@{fa-css-prefix}-crow:before { content: @fa-var-crow; }\n.@{fa-css-prefix}-crown:before { content: @fa-var-crown; }\n.@{fa-css-prefix}-crutch:before { content: @fa-var-crutch; }\n.@{fa-css-prefix}-css3:before { content: @fa-var-css3; }\n.@{fa-css-prefix}-css3-alt:before { content: @fa-var-css3-alt; }\n.@{fa-css-prefix}-cube:before { content: @fa-var-cube; }\n.@{fa-css-prefix}-cubes:before { content: @fa-var-cubes; }\n.@{fa-css-prefix}-cut:before { content: @fa-var-cut; }\n.@{fa-css-prefix}-cuttlefish:before { content: @fa-var-cuttlefish; }\n.@{fa-css-prefix}-d-and-d:before { content: @fa-var-d-and-d; }\n.@{fa-css-prefix}-d-and-d-beyond:before { content: @fa-var-d-and-d-beyond; }\n.@{fa-css-prefix}-dashcube:before { content: @fa-var-dashcube; }\n.@{fa-css-prefix}-database:before { content: @fa-var-database; }\n.@{fa-css-prefix}-deaf:before { content: @fa-var-deaf; }\n.@{fa-css-prefix}-delicious:before { content: @fa-var-delicious; }\n.@{fa-css-prefix}-democrat:before { content: @fa-var-democrat; }\n.@{fa-css-prefix}-deploydog:before { content: @fa-var-deploydog; }\n.@{fa-css-prefix}-deskpro:before { content: @fa-var-deskpro; }\n.@{fa-css-prefix}-desktop:before { content: @fa-var-desktop; }\n.@{fa-css-prefix}-dev:before { content: @fa-var-dev; }\n.@{fa-css-prefix}-deviantart:before { content: @fa-var-deviantart; }\n.@{fa-css-prefix}-dharmachakra:before { content: @fa-var-dharmachakra; }\n.@{fa-css-prefix}-dhl:before { content: @fa-var-dhl; }\n.@{fa-css-prefix}-diagnoses:before { content: @fa-var-diagnoses; }\n.@{fa-css-prefix}-diaspora:before { content: @fa-var-diaspora; }\n.@{fa-css-prefix}-dice:before { content: @fa-var-dice; }\n.@{fa-css-prefix}-dice-d20:before { content: @fa-var-dice-d20; }\n.@{fa-css-prefix}-dice-d6:before { content: @fa-var-dice-d6; }\n.@{fa-css-prefix}-dice-five:before { content: @fa-var-dice-five; }\n.@{fa-css-prefix}-dice-four:before { content: @fa-var-dice-four; }\n.@{fa-css-prefix}-dice-one:before { content: @fa-var-dice-one; }\n.@{fa-css-prefix}-dice-six:before { content: @fa-var-dice-six; }\n.@{fa-css-prefix}-dice-three:before { content: @fa-var-dice-three; }\n.@{fa-css-prefix}-dice-two:before { content: @fa-var-dice-two; }\n.@{fa-css-prefix}-digg:before { content: @fa-var-digg; }\n.@{fa-css-prefix}-digital-ocean:before { content: @fa-var-digital-ocean; }\n.@{fa-css-prefix}-digital-tachograph:before { content: @fa-var-digital-tachograph; }\n.@{fa-css-prefix}-directions:before { content: @fa-var-directions; }\n.@{fa-css-prefix}-discord:before { content: @fa-var-discord; }\n.@{fa-css-prefix}-discourse:before { content: @fa-var-discourse; }\n.@{fa-css-prefix}-divide:before { content: @fa-var-divide; }\n.@{fa-css-prefix}-dizzy:before { content: @fa-var-dizzy; }\n.@{fa-css-prefix}-dna:before { content: @fa-var-dna; }\n.@{fa-css-prefix}-dochub:before { content: @fa-var-dochub; }\n.@{fa-css-prefix}-docker:before { content: @fa-var-docker; }\n.@{fa-css-prefix}-dog:before { content: @fa-var-dog; }\n.@{fa-css-prefix}-dollar-sign:before { content: @fa-var-dollar-sign; }\n.@{fa-css-prefix}-dolly:before { content: @fa-var-dolly; }\n.@{fa-css-prefix}-dolly-flatbed:before { content: @fa-var-dolly-flatbed; }\n.@{fa-css-prefix}-donate:before { content: @fa-var-donate; }\n.@{fa-css-prefix}-door-closed:before { content: @fa-var-door-closed; }\n.@{fa-css-prefix}-door-open:before { content: @fa-var-door-open; }\n.@{fa-css-prefix}-dot-circle:before { content: @fa-var-dot-circle; }\n.@{fa-css-prefix}-dove:before { content: @fa-var-dove; }\n.@{fa-css-prefix}-download:before { content: @fa-var-download; }\n.@{fa-css-prefix}-draft2digital:before { content: @fa-var-draft2digital; }\n.@{fa-css-prefix}-drafting-compass:before { content: @fa-var-drafting-compass; }\n.@{fa-css-prefix}-dragon:before { content: @fa-var-dragon; }\n.@{fa-css-prefix}-draw-polygon:before { content: @fa-var-draw-polygon; }\n.@{fa-css-prefix}-dribbble:before { content: @fa-var-dribbble; }\n.@{fa-css-prefix}-dribbble-square:before { content: @fa-var-dribbble-square; }\n.@{fa-css-prefix}-dropbox:before { content: @fa-var-dropbox; }\n.@{fa-css-prefix}-drum:before { content: @fa-var-drum; }\n.@{fa-css-prefix}-drum-steelpan:before { content: @fa-var-drum-steelpan; }\n.@{fa-css-prefix}-drumstick-bite:before { content: @fa-var-drumstick-bite; }\n.@{fa-css-prefix}-drupal:before { content: @fa-var-drupal; }\n.@{fa-css-prefix}-dumbbell:before { content: @fa-var-dumbbell; }\n.@{fa-css-prefix}-dumpster:before { content: @fa-var-dumpster; }\n.@{fa-css-prefix}-dumpster-fire:before { content: @fa-var-dumpster-fire; }\n.@{fa-css-prefix}-dungeon:before { content: @fa-var-dungeon; }\n.@{fa-css-prefix}-dyalog:before { content: @fa-var-dyalog; }\n.@{fa-css-prefix}-earlybirds:before { content: @fa-var-earlybirds; }\n.@{fa-css-prefix}-ebay:before { content: @fa-var-ebay; }\n.@{fa-css-prefix}-edge:before { content: @fa-var-edge; }\n.@{fa-css-prefix}-edit:before { content: @fa-var-edit; }\n.@{fa-css-prefix}-egg:before { content: @fa-var-egg; }\n.@{fa-css-prefix}-eject:before { content: @fa-var-eject; }\n.@{fa-css-prefix}-elementor:before { content: @fa-var-elementor; }\n.@{fa-css-prefix}-ellipsis-h:before { content: @fa-var-ellipsis-h; }\n.@{fa-css-prefix}-ellipsis-v:before { content: @fa-var-ellipsis-v; }\n.@{fa-css-prefix}-ello:before { content: @fa-var-ello; }\n.@{fa-css-prefix}-ember:before { content: @fa-var-ember; }\n.@{fa-css-prefix}-empire:before { content: @fa-var-empire; }\n.@{fa-css-prefix}-envelope:before { content: @fa-var-envelope; }\n.@{fa-css-prefix}-envelope-open:before { content: @fa-var-envelope-open; }\n.@{fa-css-prefix}-envelope-open-text:before { content: @fa-var-envelope-open-text; }\n.@{fa-css-prefix}-envelope-square:before { content: @fa-var-envelope-square; }\n.@{fa-css-prefix}-envira:before { content: @fa-var-envira; }\n.@{fa-css-prefix}-equals:before { content: @fa-var-equals; }\n.@{fa-css-prefix}-eraser:before { content: @fa-var-eraser; }\n.@{fa-css-prefix}-erlang:before { content: @fa-var-erlang; }\n.@{fa-css-prefix}-ethereum:before { content: @fa-var-ethereum; }\n.@{fa-css-prefix}-ethernet:before { content: @fa-var-ethernet; }\n.@{fa-css-prefix}-etsy:before { content: @fa-var-etsy; }\n.@{fa-css-prefix}-euro-sign:before { content: @fa-var-euro-sign; }\n.@{fa-css-prefix}-evernote:before { content: @fa-var-evernote; }\n.@{fa-css-prefix}-exchange-alt:before { content: @fa-var-exchange-alt; }\n.@{fa-css-prefix}-exclamation:before { content: @fa-var-exclamation; }\n.@{fa-css-prefix}-exclamation-circle:before { content: @fa-var-exclamation-circle; }\n.@{fa-css-prefix}-exclamation-triangle:before { content: @fa-var-exclamation-triangle; }\n.@{fa-css-prefix}-expand:before { content: @fa-var-expand; }\n.@{fa-css-prefix}-expand-arrows-alt:before { content: @fa-var-expand-arrows-alt; }\n.@{fa-css-prefix}-expeditedssl:before { content: @fa-var-expeditedssl; }\n.@{fa-css-prefix}-external-link-alt:before { content: @fa-var-external-link-alt; }\n.@{fa-css-prefix}-external-link-square-alt:before { content: @fa-var-external-link-square-alt; }\n.@{fa-css-prefix}-eye:before { content: @fa-var-eye; }\n.@{fa-css-prefix}-eye-dropper:before { content: @fa-var-eye-dropper; }\n.@{fa-css-prefix}-eye-slash:before { content: @fa-var-eye-slash; }\n.@{fa-css-prefix}-facebook:before { content: @fa-var-facebook; }\n.@{fa-css-prefix}-facebook-f:before { content: @fa-var-facebook-f; }\n.@{fa-css-prefix}-facebook-messenger:before { content: @fa-var-facebook-messenger; }\n.@{fa-css-prefix}-facebook-square:before { content: @fa-var-facebook-square; }\n.@{fa-css-prefix}-fan:before { content: @fa-var-fan; }\n.@{fa-css-prefix}-fantasy-flight-games:before { content: @fa-var-fantasy-flight-games; }\n.@{fa-css-prefix}-fast-backward:before { content: @fa-var-fast-backward; }\n.@{fa-css-prefix}-fast-forward:before { content: @fa-var-fast-forward; }\n.@{fa-css-prefix}-fax:before { content: @fa-var-fax; }\n.@{fa-css-prefix}-feather:before { content: @fa-var-feather; }\n.@{fa-css-prefix}-feather-alt:before { content: @fa-var-feather-alt; }\n.@{fa-css-prefix}-fedex:before { content: @fa-var-fedex; }\n.@{fa-css-prefix}-fedora:before { content: @fa-var-fedora; }\n.@{fa-css-prefix}-female:before { content: @fa-var-female; }\n.@{fa-css-prefix}-fighter-jet:before { content: @fa-var-fighter-jet; }\n.@{fa-css-prefix}-figma:before { content: @fa-var-figma; }\n.@{fa-css-prefix}-file:before { content: @fa-var-file; }\n.@{fa-css-prefix}-file-alt:before { content: @fa-var-file-alt; }\n.@{fa-css-prefix}-file-archive:before { content: @fa-var-file-archive; }\n.@{fa-css-prefix}-file-audio:before { content: @fa-var-file-audio; }\n.@{fa-css-prefix}-file-code:before { content: @fa-var-file-code; }\n.@{fa-css-prefix}-file-contract:before { content: @fa-var-file-contract; }\n.@{fa-css-prefix}-file-csv:before { content: @fa-var-file-csv; }\n.@{fa-css-prefix}-file-download:before { content: @fa-var-file-download; }\n.@{fa-css-prefix}-file-excel:before { content: @fa-var-file-excel; }\n.@{fa-css-prefix}-file-export:before { content: @fa-var-file-export; }\n.@{fa-css-prefix}-file-image:before { content: @fa-var-file-image; }\n.@{fa-css-prefix}-file-import:before { content: @fa-var-file-import; }\n.@{fa-css-prefix}-file-invoice:before { content: @fa-var-file-invoice; }\n.@{fa-css-prefix}-file-invoice-dollar:before { content: @fa-var-file-invoice-dollar; }\n.@{fa-css-prefix}-file-medical:before { content: @fa-var-file-medical; }\n.@{fa-css-prefix}-file-medical-alt:before { content: @fa-var-file-medical-alt; }\n.@{fa-css-prefix}-file-pdf:before { content: @fa-var-file-pdf; }\n.@{fa-css-prefix}-file-powerpoint:before { content: @fa-var-file-powerpoint; }\n.@{fa-css-prefix}-file-prescription:before { content: @fa-var-file-prescription; }\n.@{fa-css-prefix}-file-signature:before { content: @fa-var-file-signature; }\n.@{fa-css-prefix}-file-upload:before { content: @fa-var-file-upload; }\n.@{fa-css-prefix}-file-video:before { content: @fa-var-file-video; }\n.@{fa-css-prefix}-file-word:before { content: @fa-var-file-word; }\n.@{fa-css-prefix}-fill:before { content: @fa-var-fill; }\n.@{fa-css-prefix}-fill-drip:before { content: @fa-var-fill-drip; }\n.@{fa-css-prefix}-film:before { content: @fa-var-film; }\n.@{fa-css-prefix}-filter:before { content: @fa-var-filter; }\n.@{fa-css-prefix}-fingerprint:before { content: @fa-var-fingerprint; }\n.@{fa-css-prefix}-fire:before { content: @fa-var-fire; }\n.@{fa-css-prefix}-fire-alt:before { content: @fa-var-fire-alt; }\n.@{fa-css-prefix}-fire-extinguisher:before { content: @fa-var-fire-extinguisher; }\n.@{fa-css-prefix}-firefox:before { content: @fa-var-firefox; }\n.@{fa-css-prefix}-first-aid:before { content: @fa-var-first-aid; }\n.@{fa-css-prefix}-first-order:before { content: @fa-var-first-order; }\n.@{fa-css-prefix}-first-order-alt:before { content: @fa-var-first-order-alt; }\n.@{fa-css-prefix}-firstdraft:before { content: @fa-var-firstdraft; }\n.@{fa-css-prefix}-fish:before { content: @fa-var-fish; }\n.@{fa-css-prefix}-fist-raised:before { content: @fa-var-fist-raised; }\n.@{fa-css-prefix}-flag:before { content: @fa-var-flag; }\n.@{fa-css-prefix}-flag-checkered:before { content: @fa-var-flag-checkered; }\n.@{fa-css-prefix}-flag-usa:before { content: @fa-var-flag-usa; }\n.@{fa-css-prefix}-flask:before { content: @fa-var-flask; }\n.@{fa-css-prefix}-flickr:before { content: @fa-var-flickr; }\n.@{fa-css-prefix}-flipboard:before { content: @fa-var-flipboard; }\n.@{fa-css-prefix}-flushed:before { content: @fa-var-flushed; }\n.@{fa-css-prefix}-fly:before { content: @fa-var-fly; }\n.@{fa-css-prefix}-folder:before { content: @fa-var-folder; }\n.@{fa-css-prefix}-folder-minus:before { content: @fa-var-folder-minus; }\n.@{fa-css-prefix}-folder-open:before { content: @fa-var-folder-open; }\n.@{fa-css-prefix}-folder-plus:before { content: @fa-var-folder-plus; }\n.@{fa-css-prefix}-font:before { content: @fa-var-font; }\n.@{fa-css-prefix}-font-awesome:before { content: @fa-var-font-awesome; }\n.@{fa-css-prefix}-font-awesome-alt:before { content: @fa-var-font-awesome-alt; }\n.@{fa-css-prefix}-font-awesome-flag:before { content: @fa-var-font-awesome-flag; }\n.@{fa-css-prefix}-font-awesome-logo-full:before { content: @fa-var-font-awesome-logo-full; }\n.@{fa-css-prefix}-fonticons:before { content: @fa-var-fonticons; }\n.@{fa-css-prefix}-fonticons-fi:before { content: @fa-var-fonticons-fi; }\n.@{fa-css-prefix}-football-ball:before { content: @fa-var-football-ball; }\n.@{fa-css-prefix}-fort-awesome:before { content: @fa-var-fort-awesome; }\n.@{fa-css-prefix}-fort-awesome-alt:before { content: @fa-var-fort-awesome-alt; }\n.@{fa-css-prefix}-forumbee:before { content: @fa-var-forumbee; }\n.@{fa-css-prefix}-forward:before { content: @fa-var-forward; }\n.@{fa-css-prefix}-foursquare:before { content: @fa-var-foursquare; }\n.@{fa-css-prefix}-free-code-camp:before { content: @fa-var-free-code-camp; }\n.@{fa-css-prefix}-freebsd:before { content: @fa-var-freebsd; }\n.@{fa-css-prefix}-frog:before { content: @fa-var-frog; }\n.@{fa-css-prefix}-frown:before { content: @fa-var-frown; }\n.@{fa-css-prefix}-frown-open:before { content: @fa-var-frown-open; }\n.@{fa-css-prefix}-fulcrum:before { content: @fa-var-fulcrum; }\n.@{fa-css-prefix}-funnel-dollar:before { content: @fa-var-funnel-dollar; }\n.@{fa-css-prefix}-futbol:before { content: @fa-var-futbol; }\n.@{fa-css-prefix}-galactic-republic:before { content: @fa-var-galactic-republic; }\n.@{fa-css-prefix}-galactic-senate:before { content: @fa-var-galactic-senate; }\n.@{fa-css-prefix}-gamepad:before { content: @fa-var-gamepad; }\n.@{fa-css-prefix}-gas-pump:before { content: @fa-var-gas-pump; }\n.@{fa-css-prefix}-gavel:before { content: @fa-var-gavel; }\n.@{fa-css-prefix}-gem:before { content: @fa-var-gem; }\n.@{fa-css-prefix}-genderless:before { content: @fa-var-genderless; }\n.@{fa-css-prefix}-get-pocket:before { content: @fa-var-get-pocket; }\n.@{fa-css-prefix}-gg:before { content: @fa-var-gg; }\n.@{fa-css-prefix}-gg-circle:before { content: @fa-var-gg-circle; }\n.@{fa-css-prefix}-ghost:before { content: @fa-var-ghost; }\n.@{fa-css-prefix}-gift:before { content: @fa-var-gift; }\n.@{fa-css-prefix}-gifts:before { content: @fa-var-gifts; }\n.@{fa-css-prefix}-git:before { content: @fa-var-git; }\n.@{fa-css-prefix}-git-alt:before { content: @fa-var-git-alt; }\n.@{fa-css-prefix}-git-square:before { content: @fa-var-git-square; }\n.@{fa-css-prefix}-github:before { content: @fa-var-github; }\n.@{fa-css-prefix}-github-alt:before { content: @fa-var-github-alt; }\n.@{fa-css-prefix}-github-square:before { content: @fa-var-github-square; }\n.@{fa-css-prefix}-gitkraken:before { content: @fa-var-gitkraken; }\n.@{fa-css-prefix}-gitlab:before { content: @fa-var-gitlab; }\n.@{fa-css-prefix}-gitter:before { content: @fa-var-gitter; }\n.@{fa-css-prefix}-glass-cheers:before { content: @fa-var-glass-cheers; }\n.@{fa-css-prefix}-glass-martini:before { content: @fa-var-glass-martini; }\n.@{fa-css-prefix}-glass-martini-alt:before { content: @fa-var-glass-martini-alt; }\n.@{fa-css-prefix}-glass-whiskey:before { content: @fa-var-glass-whiskey; }\n.@{fa-css-prefix}-glasses:before { content: @fa-var-glasses; }\n.@{fa-css-prefix}-glide:before { content: @fa-var-glide; }\n.@{fa-css-prefix}-glide-g:before { content: @fa-var-glide-g; }\n.@{fa-css-prefix}-globe:before { content: @fa-var-globe; }\n.@{fa-css-prefix}-globe-africa:before { content: @fa-var-globe-africa; }\n.@{fa-css-prefix}-globe-americas:before { content: @fa-var-globe-americas; }\n.@{fa-css-prefix}-globe-asia:before { content: @fa-var-globe-asia; }\n.@{fa-css-prefix}-globe-europe:before { content: @fa-var-globe-europe; }\n.@{fa-css-prefix}-gofore:before { content: @fa-var-gofore; }\n.@{fa-css-prefix}-golf-ball:before { content: @fa-var-golf-ball; }\n.@{fa-css-prefix}-goodreads:before { content: @fa-var-goodreads; }\n.@{fa-css-prefix}-goodreads-g:before { content: @fa-var-goodreads-g; }\n.@{fa-css-prefix}-google:before { content: @fa-var-google; }\n.@{fa-css-prefix}-google-drive:before { content: @fa-var-google-drive; }\n.@{fa-css-prefix}-google-play:before { content: @fa-var-google-play; }\n.@{fa-css-prefix}-google-plus:before { content: @fa-var-google-plus; }\n.@{fa-css-prefix}-google-plus-g:before { content: @fa-var-google-plus-g; }\n.@{fa-css-prefix}-google-plus-square:before { content: @fa-var-google-plus-square; }\n.@{fa-css-prefix}-google-wallet:before { content: @fa-var-google-wallet; }\n.@{fa-css-prefix}-gopuram:before { content: @fa-var-gopuram; }\n.@{fa-css-prefix}-graduation-cap:before { content: @fa-var-graduation-cap; }\n.@{fa-css-prefix}-gratipay:before { content: @fa-var-gratipay; }\n.@{fa-css-prefix}-grav:before { content: @fa-var-grav; }\n.@{fa-css-prefix}-greater-than:before { content: @fa-var-greater-than; }\n.@{fa-css-prefix}-greater-than-equal:before { content: @fa-var-greater-than-equal; }\n.@{fa-css-prefix}-grimace:before { content: @fa-var-grimace; }\n.@{fa-css-prefix}-grin:before { content: @fa-var-grin; }\n.@{fa-css-prefix}-grin-alt:before { content: @fa-var-grin-alt; }\n.@{fa-css-prefix}-grin-beam:before { content: @fa-var-grin-beam; }\n.@{fa-css-prefix}-grin-beam-sweat:before { content: @fa-var-grin-beam-sweat; }\n.@{fa-css-prefix}-grin-hearts:before { content: @fa-var-grin-hearts; }\n.@{fa-css-prefix}-grin-squint:before { content: @fa-var-grin-squint; }\n.@{fa-css-prefix}-grin-squint-tears:before { content: @fa-var-grin-squint-tears; }\n.@{fa-css-prefix}-grin-stars:before { content: @fa-var-grin-stars; }\n.@{fa-css-prefix}-grin-tears:before { content: @fa-var-grin-tears; }\n.@{fa-css-prefix}-grin-tongue:before { content: @fa-var-grin-tongue; }\n.@{fa-css-prefix}-grin-tongue-squint:before { content: @fa-var-grin-tongue-squint; }\n.@{fa-css-prefix}-grin-tongue-wink:before { content: @fa-var-grin-tongue-wink; }\n.@{fa-css-prefix}-grin-wink:before { content: @fa-var-grin-wink; }\n.@{fa-css-prefix}-grip-horizontal:before { content: @fa-var-grip-horizontal; }\n.@{fa-css-prefix}-grip-lines:before { content: @fa-var-grip-lines; }\n.@{fa-css-prefix}-grip-lines-vertical:before { content: @fa-var-grip-lines-vertical; }\n.@{fa-css-prefix}-grip-vertical:before { content: @fa-var-grip-vertical; }\n.@{fa-css-prefix}-gripfire:before { content: @fa-var-gripfire; }\n.@{fa-css-prefix}-grunt:before { content: @fa-var-grunt; }\n.@{fa-css-prefix}-guitar:before { content: @fa-var-guitar; }\n.@{fa-css-prefix}-gulp:before { content: @fa-var-gulp; }\n.@{fa-css-prefix}-h-square:before { content: @fa-var-h-square; }\n.@{fa-css-prefix}-hacker-news:before { content: @fa-var-hacker-news; }\n.@{fa-css-prefix}-hacker-news-square:before { content: @fa-var-hacker-news-square; }\n.@{fa-css-prefix}-hackerrank:before { content: @fa-var-hackerrank; }\n.@{fa-css-prefix}-hamburger:before { content: @fa-var-hamburger; }\n.@{fa-css-prefix}-hammer:before { content: @fa-var-hammer; }\n.@{fa-css-prefix}-hamsa:before { content: @fa-var-hamsa; }\n.@{fa-css-prefix}-hand-holding:before { content: @fa-var-hand-holding; }\n.@{fa-css-prefix}-hand-holding-heart:before { content: @fa-var-hand-holding-heart; }\n.@{fa-css-prefix}-hand-holding-usd:before { content: @fa-var-hand-holding-usd; }\n.@{fa-css-prefix}-hand-lizard:before { content: @fa-var-hand-lizard; }\n.@{fa-css-prefix}-hand-middle-finger:before { content: @fa-var-hand-middle-finger; }\n.@{fa-css-prefix}-hand-paper:before { content: @fa-var-hand-paper; }\n.@{fa-css-prefix}-hand-peace:before { content: @fa-var-hand-peace; }\n.@{fa-css-prefix}-hand-point-down:before { content: @fa-var-hand-point-down; }\n.@{fa-css-prefix}-hand-point-left:before { content: @fa-var-hand-point-left; }\n.@{fa-css-prefix}-hand-point-right:before { content: @fa-var-hand-point-right; }\n.@{fa-css-prefix}-hand-point-up:before { content: @fa-var-hand-point-up; }\n.@{fa-css-prefix}-hand-pointer:before { content: @fa-var-hand-pointer; }\n.@{fa-css-prefix}-hand-rock:before { content: @fa-var-hand-rock; }\n.@{fa-css-prefix}-hand-scissors:before { content: @fa-var-hand-scissors; }\n.@{fa-css-prefix}-hand-spock:before { content: @fa-var-hand-spock; }\n.@{fa-css-prefix}-hands:before { content: @fa-var-hands; }\n.@{fa-css-prefix}-hands-helping:before { content: @fa-var-hands-helping; }\n.@{fa-css-prefix}-handshake:before { content: @fa-var-handshake; }\n.@{fa-css-prefix}-hanukiah:before { content: @fa-var-hanukiah; }\n.@{fa-css-prefix}-hard-hat:before { content: @fa-var-hard-hat; }\n.@{fa-css-prefix}-hashtag:before { content: @fa-var-hashtag; }\n.@{fa-css-prefix}-hat-wizard:before { content: @fa-var-hat-wizard; }\n.@{fa-css-prefix}-haykal:before { content: @fa-var-haykal; }\n.@{fa-css-prefix}-hdd:before { content: @fa-var-hdd; }\n.@{fa-css-prefix}-heading:before { content: @fa-var-heading; }\n.@{fa-css-prefix}-headphones:before { content: @fa-var-headphones; }\n.@{fa-css-prefix}-headphones-alt:before { content: @fa-var-headphones-alt; }\n.@{fa-css-prefix}-headset:before { content: @fa-var-headset; }\n.@{fa-css-prefix}-heart:before { content: @fa-var-heart; }\n.@{fa-css-prefix}-heart-broken:before { content: @fa-var-heart-broken; }\n.@{fa-css-prefix}-heartbeat:before { content: @fa-var-heartbeat; }\n.@{fa-css-prefix}-helicopter:before { content: @fa-var-helicopter; }\n.@{fa-css-prefix}-highlighter:before { content: @fa-var-highlighter; }\n.@{fa-css-prefix}-hiking:before { content: @fa-var-hiking; }\n.@{fa-css-prefix}-hippo:before { content: @fa-var-hippo; }\n.@{fa-css-prefix}-hips:before { content: @fa-var-hips; }\n.@{fa-css-prefix}-hire-a-helper:before { content: @fa-var-hire-a-helper; }\n.@{fa-css-prefix}-history:before { content: @fa-var-history; }\n.@{fa-css-prefix}-hockey-puck:before { content: @fa-var-hockey-puck; }\n.@{fa-css-prefix}-holly-berry:before { content: @fa-var-holly-berry; }\n.@{fa-css-prefix}-home:before { content: @fa-var-home; }\n.@{fa-css-prefix}-hooli:before { content: @fa-var-hooli; }\n.@{fa-css-prefix}-hornbill:before { content: @fa-var-hornbill; }\n.@{fa-css-prefix}-horse:before { content: @fa-var-horse; }\n.@{fa-css-prefix}-horse-head:before { content: @fa-var-horse-head; }\n.@{fa-css-prefix}-hospital:before { content: @fa-var-hospital; }\n.@{fa-css-prefix}-hospital-alt:before { content: @fa-var-hospital-alt; }\n.@{fa-css-prefix}-hospital-symbol:before { content: @fa-var-hospital-symbol; }\n.@{fa-css-prefix}-hot-tub:before { content: @fa-var-hot-tub; }\n.@{fa-css-prefix}-hotdog:before { content: @fa-var-hotdog; }\n.@{fa-css-prefix}-hotel:before { content: @fa-var-hotel; }\n.@{fa-css-prefix}-hotjar:before { content: @fa-var-hotjar; }\n.@{fa-css-prefix}-hourglass:before { content: @fa-var-hourglass; }\n.@{fa-css-prefix}-hourglass-end:before { content: @fa-var-hourglass-end; }\n.@{fa-css-prefix}-hourglass-half:before { content: @fa-var-hourglass-half; }\n.@{fa-css-prefix}-hourglass-start:before { content: @fa-var-hourglass-start; }\n.@{fa-css-prefix}-house-damage:before { content: @fa-var-house-damage; }\n.@{fa-css-prefix}-houzz:before { content: @fa-var-houzz; }\n.@{fa-css-prefix}-hryvnia:before { content: @fa-var-hryvnia; }\n.@{fa-css-prefix}-html5:before { content: @fa-var-html5; }\n.@{fa-css-prefix}-hubspot:before { content: @fa-var-hubspot; }\n.@{fa-css-prefix}-i-cursor:before { content: @fa-var-i-cursor; }\n.@{fa-css-prefix}-ice-cream:before { content: @fa-var-ice-cream; }\n.@{fa-css-prefix}-icicles:before { content: @fa-var-icicles; }\n.@{fa-css-prefix}-icons:before { content: @fa-var-icons; }\n.@{fa-css-prefix}-id-badge:before { content: @fa-var-id-badge; }\n.@{fa-css-prefix}-id-card:before { content: @fa-var-id-card; }\n.@{fa-css-prefix}-id-card-alt:before { content: @fa-var-id-card-alt; }\n.@{fa-css-prefix}-igloo:before { content: @fa-var-igloo; }\n.@{fa-css-prefix}-image:before { content: @fa-var-image; }\n.@{fa-css-prefix}-images:before { content: @fa-var-images; }\n.@{fa-css-prefix}-imdb:before { content: @fa-var-imdb; }\n.@{fa-css-prefix}-inbox:before { content: @fa-var-inbox; }\n.@{fa-css-prefix}-indent:before { content: @fa-var-indent; }\n.@{fa-css-prefix}-industry:before { content: @fa-var-industry; }\n.@{fa-css-prefix}-infinity:before { content: @fa-var-infinity; }\n.@{fa-css-prefix}-info:before { content: @fa-var-info; }\n.@{fa-css-prefix}-info-circle:before { content: @fa-var-info-circle; }\n.@{fa-css-prefix}-instagram:before { content: @fa-var-instagram; }\n.@{fa-css-prefix}-intercom:before { content: @fa-var-intercom; }\n.@{fa-css-prefix}-internet-explorer:before { content: @fa-var-internet-explorer; }\n.@{fa-css-prefix}-invision:before { content: @fa-var-invision; }\n.@{fa-css-prefix}-ioxhost:before { content: @fa-var-ioxhost; }\n.@{fa-css-prefix}-italic:before { content: @fa-var-italic; }\n.@{fa-css-prefix}-itch-io:before { content: @fa-var-itch-io; }\n.@{fa-css-prefix}-itunes:before { content: @fa-var-itunes; }\n.@{fa-css-prefix}-itunes-note:before { content: @fa-var-itunes-note; }\n.@{fa-css-prefix}-java:before { content: @fa-var-java; }\n.@{fa-css-prefix}-jedi:before { content: @fa-var-jedi; }\n.@{fa-css-prefix}-jedi-order:before { content: @fa-var-jedi-order; }\n.@{fa-css-prefix}-jenkins:before { content: @fa-var-jenkins; }\n.@{fa-css-prefix}-jira:before { content: @fa-var-jira; }\n.@{fa-css-prefix}-joget:before { content: @fa-var-joget; }\n.@{fa-css-prefix}-joint:before { content: @fa-var-joint; }\n.@{fa-css-prefix}-joomla:before { content: @fa-var-joomla; }\n.@{fa-css-prefix}-journal-whills:before { content: @fa-var-journal-whills; }\n.@{fa-css-prefix}-js:before { content: @fa-var-js; }\n.@{fa-css-prefix}-js-square:before { content: @fa-var-js-square; }\n.@{fa-css-prefix}-jsfiddle:before { content: @fa-var-jsfiddle; }\n.@{fa-css-prefix}-kaaba:before { content: @fa-var-kaaba; }\n.@{fa-css-prefix}-kaggle:before { content: @fa-var-kaggle; }\n.@{fa-css-prefix}-key:before { content: @fa-var-key; }\n.@{fa-css-prefix}-keybase:before { content: @fa-var-keybase; }\n.@{fa-css-prefix}-keyboard:before { content: @fa-var-keyboard; }\n.@{fa-css-prefix}-keycdn:before { content: @fa-var-keycdn; }\n.@{fa-css-prefix}-khanda:before { content: @fa-var-khanda; }\n.@{fa-css-prefix}-kickstarter:before { content: @fa-var-kickstarter; }\n.@{fa-css-prefix}-kickstarter-k:before { content: @fa-var-kickstarter-k; }\n.@{fa-css-prefix}-kiss:before { content: @fa-var-kiss; }\n.@{fa-css-prefix}-kiss-beam:before { content: @fa-var-kiss-beam; }\n.@{fa-css-prefix}-kiss-wink-heart:before { content: @fa-var-kiss-wink-heart; }\n.@{fa-css-prefix}-kiwi-bird:before { content: @fa-var-kiwi-bird; }\n.@{fa-css-prefix}-korvue:before { content: @fa-var-korvue; }\n.@{fa-css-prefix}-landmark:before { content: @fa-var-landmark; }\n.@{fa-css-prefix}-language:before { content: @fa-var-language; }\n.@{fa-css-prefix}-laptop:before { content: @fa-var-laptop; }\n.@{fa-css-prefix}-laptop-code:before { content: @fa-var-laptop-code; }\n.@{fa-css-prefix}-laptop-medical:before { content: @fa-var-laptop-medical; }\n.@{fa-css-prefix}-laravel:before { content: @fa-var-laravel; }\n.@{fa-css-prefix}-lastfm:before { content: @fa-var-lastfm; }\n.@{fa-css-prefix}-lastfm-square:before { content: @fa-var-lastfm-square; }\n.@{fa-css-prefix}-laugh:before { content: @fa-var-laugh; }\n.@{fa-css-prefix}-laugh-beam:before { content: @fa-var-laugh-beam; }\n.@{fa-css-prefix}-laugh-squint:before { content: @fa-var-laugh-squint; }\n.@{fa-css-prefix}-laugh-wink:before { content: @fa-var-laugh-wink; }\n.@{fa-css-prefix}-layer-group:before { content: @fa-var-layer-group; }\n.@{fa-css-prefix}-leaf:before { content: @fa-var-leaf; }\n.@{fa-css-prefix}-leanpub:before { content: @fa-var-leanpub; }\n.@{fa-css-prefix}-lemon:before { content: @fa-var-lemon; }\n.@{fa-css-prefix}-less:before { content: @fa-var-less; }\n.@{fa-css-prefix}-less-than:before { content: @fa-var-less-than; }\n.@{fa-css-prefix}-less-than-equal:before { content: @fa-var-less-than-equal; }\n.@{fa-css-prefix}-level-down-alt:before { content: @fa-var-level-down-alt; }\n.@{fa-css-prefix}-level-up-alt:before { content: @fa-var-level-up-alt; }\n.@{fa-css-prefix}-life-ring:before { content: @fa-var-life-ring; }\n.@{fa-css-prefix}-lightbulb:before { content: @fa-var-lightbulb; }\n.@{fa-css-prefix}-line:before { content: @fa-var-line; }\n.@{fa-css-prefix}-link:before { content: @fa-var-link; }\n.@{fa-css-prefix}-linkedin:before { content: @fa-var-linkedin; }\n.@{fa-css-prefix}-linkedin-in:before { content: @fa-var-linkedin-in; }\n.@{fa-css-prefix}-linode:before { content: @fa-var-linode; }\n.@{fa-css-prefix}-linux:before { content: @fa-var-linux; }\n.@{fa-css-prefix}-lira-sign:before { content: @fa-var-lira-sign; }\n.@{fa-css-prefix}-list:before { content: @fa-var-list; }\n.@{fa-css-prefix}-list-alt:before { content: @fa-var-list-alt; }\n.@{fa-css-prefix}-list-ol:before { content: @fa-var-list-ol; }\n.@{fa-css-prefix}-list-ul:before { content: @fa-var-list-ul; }\n.@{fa-css-prefix}-location-arrow:before { content: @fa-var-location-arrow; }\n.@{fa-css-prefix}-lock:before { content: @fa-var-lock; }\n.@{fa-css-prefix}-lock-open:before { content: @fa-var-lock-open; }\n.@{fa-css-prefix}-long-arrow-alt-down:before { content: @fa-var-long-arrow-alt-down; }\n.@{fa-css-prefix}-long-arrow-alt-left:before { content: @fa-var-long-arrow-alt-left; }\n.@{fa-css-prefix}-long-arrow-alt-right:before { content: @fa-var-long-arrow-alt-right; }\n.@{fa-css-prefix}-long-arrow-alt-up:before { content: @fa-var-long-arrow-alt-up; }\n.@{fa-css-prefix}-low-vision:before { content: @fa-var-low-vision; }\n.@{fa-css-prefix}-luggage-cart:before { content: @fa-var-luggage-cart; }\n.@{fa-css-prefix}-lyft:before { content: @fa-var-lyft; }\n.@{fa-css-prefix}-magento:before { content: @fa-var-magento; }\n.@{fa-css-prefix}-magic:before { content: @fa-var-magic; }\n.@{fa-css-prefix}-magnet:before { content: @fa-var-magnet; }\n.@{fa-css-prefix}-mail-bulk:before { content: @fa-var-mail-bulk; }\n.@{fa-css-prefix}-mailchimp:before { content: @fa-var-mailchimp; }\n.@{fa-css-prefix}-male:before { content: @fa-var-male; }\n.@{fa-css-prefix}-mandalorian:before { content: @fa-var-mandalorian; }\n.@{fa-css-prefix}-map:before { content: @fa-var-map; }\n.@{fa-css-prefix}-map-marked:before { content: @fa-var-map-marked; }\n.@{fa-css-prefix}-map-marked-alt:before { content: @fa-var-map-marked-alt; }\n.@{fa-css-prefix}-map-marker:before { content: @fa-var-map-marker; }\n.@{fa-css-prefix}-map-marker-alt:before { content: @fa-var-map-marker-alt; }\n.@{fa-css-prefix}-map-pin:before { content: @fa-var-map-pin; }\n.@{fa-css-prefix}-map-signs:before { content: @fa-var-map-signs; }\n.@{fa-css-prefix}-markdown:before { content: @fa-var-markdown; }\n.@{fa-css-prefix}-marker:before { content: @fa-var-marker; }\n.@{fa-css-prefix}-mars:before { content: @fa-var-mars; }\n.@{fa-css-prefix}-mars-double:before { content: @fa-var-mars-double; }\n.@{fa-css-prefix}-mars-stroke:before { content: @fa-var-mars-stroke; }\n.@{fa-css-prefix}-mars-stroke-h:before { content: @fa-var-mars-stroke-h; }\n.@{fa-css-prefix}-mars-stroke-v:before { content: @fa-var-mars-stroke-v; }\n.@{fa-css-prefix}-mask:before { content: @fa-var-mask; }\n.@{fa-css-prefix}-mastodon:before { content: @fa-var-mastodon; }\n.@{fa-css-prefix}-maxcdn:before { content: @fa-var-maxcdn; }\n.@{fa-css-prefix}-medal:before { content: @fa-var-medal; }\n.@{fa-css-prefix}-medapps:before { content: @fa-var-medapps; }\n.@{fa-css-prefix}-medium:before { content: @fa-var-medium; }\n.@{fa-css-prefix}-medium-m:before { content: @fa-var-medium-m; }\n.@{fa-css-prefix}-medkit:before { content: @fa-var-medkit; }\n.@{fa-css-prefix}-medrt:before { content: @fa-var-medrt; }\n.@{fa-css-prefix}-meetup:before { content: @fa-var-meetup; }\n.@{fa-css-prefix}-megaport:before { content: @fa-var-megaport; }\n.@{fa-css-prefix}-meh:before { content: @fa-var-meh; }\n.@{fa-css-prefix}-meh-blank:before { content: @fa-var-meh-blank; }\n.@{fa-css-prefix}-meh-rolling-eyes:before { content: @fa-var-meh-rolling-eyes; }\n.@{fa-css-prefix}-memory:before { content: @fa-var-memory; }\n.@{fa-css-prefix}-mendeley:before { content: @fa-var-mendeley; }\n.@{fa-css-prefix}-menorah:before { content: @fa-var-menorah; }\n.@{fa-css-prefix}-mercury:before { content: @fa-var-mercury; }\n.@{fa-css-prefix}-meteor:before { content: @fa-var-meteor; }\n.@{fa-css-prefix}-microchip:before { content: @fa-var-microchip; }\n.@{fa-css-prefix}-microphone:before { content: @fa-var-microphone; }\n.@{fa-css-prefix}-microphone-alt:before { content: @fa-var-microphone-alt; }\n.@{fa-css-prefix}-microphone-alt-slash:before { content: @fa-var-microphone-alt-slash; }\n.@{fa-css-prefix}-microphone-slash:before { content: @fa-var-microphone-slash; }\n.@{fa-css-prefix}-microscope:before { content: @fa-var-microscope; }\n.@{fa-css-prefix}-microsoft:before { content: @fa-var-microsoft; }\n.@{fa-css-prefix}-minus:before { content: @fa-var-minus; }\n.@{fa-css-prefix}-minus-circle:before { content: @fa-var-minus-circle; }\n.@{fa-css-prefix}-minus-square:before { content: @fa-var-minus-square; }\n.@{fa-css-prefix}-mitten:before { content: @fa-var-mitten; }\n.@{fa-css-prefix}-mix:before { content: @fa-var-mix; }\n.@{fa-css-prefix}-mixcloud:before { content: @fa-var-mixcloud; }\n.@{fa-css-prefix}-mizuni:before { content: @fa-var-mizuni; }\n.@{fa-css-prefix}-mobile:before { content: @fa-var-mobile; }\n.@{fa-css-prefix}-mobile-alt:before { content: @fa-var-mobile-alt; }\n.@{fa-css-prefix}-modx:before { content: @fa-var-modx; }\n.@{fa-css-prefix}-monero:before { content: @fa-var-monero; }\n.@{fa-css-prefix}-money-bill:before { content: @fa-var-money-bill; }\n.@{fa-css-prefix}-money-bill-alt:before { content: @fa-var-money-bill-alt; }\n.@{fa-css-prefix}-money-bill-wave:before { content: @fa-var-money-bill-wave; }\n.@{fa-css-prefix}-money-bill-wave-alt:before { content: @fa-var-money-bill-wave-alt; }\n.@{fa-css-prefix}-money-check:before { content: @fa-var-money-check; }\n.@{fa-css-prefix}-money-check-alt:before { content: @fa-var-money-check-alt; }\n.@{fa-css-prefix}-monument:before { content: @fa-var-monument; }\n.@{fa-css-prefix}-moon:before { content: @fa-var-moon; }\n.@{fa-css-prefix}-mortar-pestle:before { content: @fa-var-mortar-pestle; }\n.@{fa-css-prefix}-mosque:before { content: @fa-var-mosque; }\n.@{fa-css-prefix}-motorcycle:before { content: @fa-var-motorcycle; }\n.@{fa-css-prefix}-mountain:before { content: @fa-var-mountain; }\n.@{fa-css-prefix}-mouse-pointer:before { content: @fa-var-mouse-pointer; }\n.@{fa-css-prefix}-mug-hot:before { content: @fa-var-mug-hot; }\n.@{fa-css-prefix}-music:before { content: @fa-var-music; }\n.@{fa-css-prefix}-napster:before { content: @fa-var-napster; }\n.@{fa-css-prefix}-neos:before { content: @fa-var-neos; }\n.@{fa-css-prefix}-network-wired:before { content: @fa-var-network-wired; }\n.@{fa-css-prefix}-neuter:before { content: @fa-var-neuter; }\n.@{fa-css-prefix}-newspaper:before { content: @fa-var-newspaper; }\n.@{fa-css-prefix}-nimblr:before { content: @fa-var-nimblr; }\n.@{fa-css-prefix}-node:before { content: @fa-var-node; }\n.@{fa-css-prefix}-node-js:before { content: @fa-var-node-js; }\n.@{fa-css-prefix}-not-equal:before { content: @fa-var-not-equal; }\n.@{fa-css-prefix}-notes-medical:before { content: @fa-var-notes-medical; }\n.@{fa-css-prefix}-npm:before { content: @fa-var-npm; }\n.@{fa-css-prefix}-ns8:before { content: @fa-var-ns8; }\n.@{fa-css-prefix}-nutritionix:before { content: @fa-var-nutritionix; }\n.@{fa-css-prefix}-object-group:before { content: @fa-var-object-group; }\n.@{fa-css-prefix}-object-ungroup:before { content: @fa-var-object-ungroup; }\n.@{fa-css-prefix}-odnoklassniki:before { content: @fa-var-odnoklassniki; }\n.@{fa-css-prefix}-odnoklassniki-square:before { content: @fa-var-odnoklassniki-square; }\n.@{fa-css-prefix}-oil-can:before { content: @fa-var-oil-can; }\n.@{fa-css-prefix}-old-republic:before { content: @fa-var-old-republic; }\n.@{fa-css-prefix}-om:before { content: @fa-var-om; }\n.@{fa-css-prefix}-opencart:before { content: @fa-var-opencart; }\n.@{fa-css-prefix}-openid:before { content: @fa-var-openid; }\n.@{fa-css-prefix}-opera:before { content: @fa-var-opera; }\n.@{fa-css-prefix}-optin-monster:before { content: @fa-var-optin-monster; }\n.@{fa-css-prefix}-osi:before { content: @fa-var-osi; }\n.@{fa-css-prefix}-otter:before { content: @fa-var-otter; }\n.@{fa-css-prefix}-outdent:before { content: @fa-var-outdent; }\n.@{fa-css-prefix}-page4:before { content: @fa-var-page4; }\n.@{fa-css-prefix}-pagelines:before { content: @fa-var-pagelines; }\n.@{fa-css-prefix}-pager:before { content: @fa-var-pager; }\n.@{fa-css-prefix}-paint-brush:before { content: @fa-var-paint-brush; }\n.@{fa-css-prefix}-paint-roller:before { content: @fa-var-paint-roller; }\n.@{fa-css-prefix}-palette:before { content: @fa-var-palette; }\n.@{fa-css-prefix}-palfed:before { content: @fa-var-palfed; }\n.@{fa-css-prefix}-pallet:before { content: @fa-var-pallet; }\n.@{fa-css-prefix}-paper-plane:before { content: @fa-var-paper-plane; }\n.@{fa-css-prefix}-paperclip:before { content: @fa-var-paperclip; }\n.@{fa-css-prefix}-parachute-box:before { content: @fa-var-parachute-box; }\n.@{fa-css-prefix}-paragraph:before { content: @fa-var-paragraph; }\n.@{fa-css-prefix}-parking:before { content: @fa-var-parking; }\n.@{fa-css-prefix}-passport:before { content: @fa-var-passport; }\n.@{fa-css-prefix}-pastafarianism:before { content: @fa-var-pastafarianism; }\n.@{fa-css-prefix}-paste:before { content: @fa-var-paste; }\n.@{fa-css-prefix}-patreon:before { content: @fa-var-patreon; }\n.@{fa-css-prefix}-pause:before { content: @fa-var-pause; }\n.@{fa-css-prefix}-pause-circle:before { content: @fa-var-pause-circle; }\n.@{fa-css-prefix}-paw:before { content: @fa-var-paw; }\n.@{fa-css-prefix}-paypal:before { content: @fa-var-paypal; }\n.@{fa-css-prefix}-peace:before { content: @fa-var-peace; }\n.@{fa-css-prefix}-pen:before { content: @fa-var-pen; }\n.@{fa-css-prefix}-pen-alt:before { content: @fa-var-pen-alt; }\n.@{fa-css-prefix}-pen-fancy:before { content: @fa-var-pen-fancy; }\n.@{fa-css-prefix}-pen-nib:before { content: @fa-var-pen-nib; }\n.@{fa-css-prefix}-pen-square:before { content: @fa-var-pen-square; }\n.@{fa-css-prefix}-pencil-alt:before { content: @fa-var-pencil-alt; }\n.@{fa-css-prefix}-pencil-ruler:before { content: @fa-var-pencil-ruler; }\n.@{fa-css-prefix}-penny-arcade:before { content: @fa-var-penny-arcade; }\n.@{fa-css-prefix}-people-carry:before { content: @fa-var-people-carry; }\n.@{fa-css-prefix}-pepper-hot:before { content: @fa-var-pepper-hot; }\n.@{fa-css-prefix}-percent:before { content: @fa-var-percent; }\n.@{fa-css-prefix}-percentage:before { content: @fa-var-percentage; }\n.@{fa-css-prefix}-periscope:before { content: @fa-var-periscope; }\n.@{fa-css-prefix}-person-booth:before { content: @fa-var-person-booth; }\n.@{fa-css-prefix}-phabricator:before { content: @fa-var-phabricator; }\n.@{fa-css-prefix}-phoenix-framework:before { content: @fa-var-phoenix-framework; }\n.@{fa-css-prefix}-phoenix-squadron:before { content: @fa-var-phoenix-squadron; }\n.@{fa-css-prefix}-phone:before { content: @fa-var-phone; }\n.@{fa-css-prefix}-phone-alt:before { content: @fa-var-phone-alt; }\n.@{fa-css-prefix}-phone-slash:before { content: @fa-var-phone-slash; }\n.@{fa-css-prefix}-phone-square:before { content: @fa-var-phone-square; }\n.@{fa-css-prefix}-phone-square-alt:before { content: @fa-var-phone-square-alt; }\n.@{fa-css-prefix}-phone-volume:before { content: @fa-var-phone-volume; }\n.@{fa-css-prefix}-photo-video:before { content: @fa-var-photo-video; }\n.@{fa-css-prefix}-php:before { content: @fa-var-php; }\n.@{fa-css-prefix}-pied-piper:before { content: @fa-var-pied-piper; }\n.@{fa-css-prefix}-pied-piper-alt:before { content: @fa-var-pied-piper-alt; }\n.@{fa-css-prefix}-pied-piper-hat:before { content: @fa-var-pied-piper-hat; }\n.@{fa-css-prefix}-pied-piper-pp:before { content: @fa-var-pied-piper-pp; }\n.@{fa-css-prefix}-piggy-bank:before { content: @fa-var-piggy-bank; }\n.@{fa-css-prefix}-pills:before { content: @fa-var-pills; }\n.@{fa-css-prefix}-pinterest:before { content: @fa-var-pinterest; }\n.@{fa-css-prefix}-pinterest-p:before { content: @fa-var-pinterest-p; }\n.@{fa-css-prefix}-pinterest-square:before { content: @fa-var-pinterest-square; }\n.@{fa-css-prefix}-pizza-slice:before { content: @fa-var-pizza-slice; }\n.@{fa-css-prefix}-place-of-worship:before { content: @fa-var-place-of-worship; }\n.@{fa-css-prefix}-plane:before { content: @fa-var-plane; }\n.@{fa-css-prefix}-plane-arrival:before { content: @fa-var-plane-arrival; }\n.@{fa-css-prefix}-plane-departure:before { content: @fa-var-plane-departure; }\n.@{fa-css-prefix}-play:before { content: @fa-var-play; }\n.@{fa-css-prefix}-play-circle:before { content: @fa-var-play-circle; }\n.@{fa-css-prefix}-playstation:before { content: @fa-var-playstation; }\n.@{fa-css-prefix}-plug:before { content: @fa-var-plug; }\n.@{fa-css-prefix}-plus:before { content: @fa-var-plus; }\n.@{fa-css-prefix}-plus-circle:before { content: @fa-var-plus-circle; }\n.@{fa-css-prefix}-plus-square:before { content: @fa-var-plus-square; }\n.@{fa-css-prefix}-podcast:before { content: @fa-var-podcast; }\n.@{fa-css-prefix}-poll:before { content: @fa-var-poll; }\n.@{fa-css-prefix}-poll-h:before { content: @fa-var-poll-h; }\n.@{fa-css-prefix}-poo:before { content: @fa-var-poo; }\n.@{fa-css-prefix}-poo-storm:before { content: @fa-var-poo-storm; }\n.@{fa-css-prefix}-poop:before { content: @fa-var-poop; }\n.@{fa-css-prefix}-portrait:before { content: @fa-var-portrait; }\n.@{fa-css-prefix}-pound-sign:before { content: @fa-var-pound-sign; }\n.@{fa-css-prefix}-power-off:before { content: @fa-var-power-off; }\n.@{fa-css-prefix}-pray:before { content: @fa-var-pray; }\n.@{fa-css-prefix}-praying-hands:before { content: @fa-var-praying-hands; }\n.@{fa-css-prefix}-prescription:before { content: @fa-var-prescription; }\n.@{fa-css-prefix}-prescription-bottle:before { content: @fa-var-prescription-bottle; }\n.@{fa-css-prefix}-prescription-bottle-alt:before { content: @fa-var-prescription-bottle-alt; }\n.@{fa-css-prefix}-print:before { content: @fa-var-print; }\n.@{fa-css-prefix}-procedures:before { content: @fa-var-procedures; }\n.@{fa-css-prefix}-product-hunt:before { content: @fa-var-product-hunt; }\n.@{fa-css-prefix}-project-diagram:before { content: @fa-var-project-diagram; }\n.@{fa-css-prefix}-pushed:before { content: @fa-var-pushed; }\n.@{fa-css-prefix}-puzzle-piece:before { content: @fa-var-puzzle-piece; }\n.@{fa-css-prefix}-python:before { content: @fa-var-python; }\n.@{fa-css-prefix}-qq:before { content: @fa-var-qq; }\n.@{fa-css-prefix}-qrcode:before { content: @fa-var-qrcode; }\n.@{fa-css-prefix}-question:before { content: @fa-var-question; }\n.@{fa-css-prefix}-question-circle:before { content: @fa-var-question-circle; }\n.@{fa-css-prefix}-quidditch:before { content: @fa-var-quidditch; }\n.@{fa-css-prefix}-quinscape:before { content: @fa-var-quinscape; }\n.@{fa-css-prefix}-quora:before { content: @fa-var-quora; }\n.@{fa-css-prefix}-quote-left:before { content: @fa-var-quote-left; }\n.@{fa-css-prefix}-quote-right:before { content: @fa-var-quote-right; }\n.@{fa-css-prefix}-quran:before { content: @fa-var-quran; }\n.@{fa-css-prefix}-r-project:before { content: @fa-var-r-project; }\n.@{fa-css-prefix}-radiation:before { content: @fa-var-radiation; }\n.@{fa-css-prefix}-radiation-alt:before { content: @fa-var-radiation-alt; }\n.@{fa-css-prefix}-rainbow:before { content: @fa-var-rainbow; }\n.@{fa-css-prefix}-random:before { content: @fa-var-random; }\n.@{fa-css-prefix}-raspberry-pi:before { content: @fa-var-raspberry-pi; }\n.@{fa-css-prefix}-ravelry:before { content: @fa-var-ravelry; }\n.@{fa-css-prefix}-react:before { content: @fa-var-react; }\n.@{fa-css-prefix}-reacteurope:before { content: @fa-var-reacteurope; }\n.@{fa-css-prefix}-readme:before { content: @fa-var-readme; }\n.@{fa-css-prefix}-rebel:before { content: @fa-var-rebel; }\n.@{fa-css-prefix}-receipt:before { content: @fa-var-receipt; }\n.@{fa-css-prefix}-recycle:before { content: @fa-var-recycle; }\n.@{fa-css-prefix}-red-river:before { content: @fa-var-red-river; }\n.@{fa-css-prefix}-reddit:before { content: @fa-var-reddit; }\n.@{fa-css-prefix}-reddit-alien:before { content: @fa-var-reddit-alien; }\n.@{fa-css-prefix}-reddit-square:before { content: @fa-var-reddit-square; }\n.@{fa-css-prefix}-redhat:before { content: @fa-var-redhat; }\n.@{fa-css-prefix}-redo:before { content: @fa-var-redo; }\n.@{fa-css-prefix}-redo-alt:before { content: @fa-var-redo-alt; }\n.@{fa-css-prefix}-registered:before { content: @fa-var-registered; }\n.@{fa-css-prefix}-remove-format:before { content: @fa-var-remove-format; }\n.@{fa-css-prefix}-renren:before { content: @fa-var-renren; }\n.@{fa-css-prefix}-reply:before { content: @fa-var-reply; }\n.@{fa-css-prefix}-reply-all:before { content: @fa-var-reply-all; }\n.@{fa-css-prefix}-replyd:before { content: @fa-var-replyd; }\n.@{fa-css-prefix}-republican:before { content: @fa-var-republican; }\n.@{fa-css-prefix}-researchgate:before { content: @fa-var-researchgate; }\n.@{fa-css-prefix}-resolving:before { content: @fa-var-resolving; }\n.@{fa-css-prefix}-restroom:before { content: @fa-var-restroom; }\n.@{fa-css-prefix}-retweet:before { content: @fa-var-retweet; }\n.@{fa-css-prefix}-rev:before { content: @fa-var-rev; }\n.@{fa-css-prefix}-ribbon:before { content: @fa-var-ribbon; }\n.@{fa-css-prefix}-ring:before { content: @fa-var-ring; }\n.@{fa-css-prefix}-road:before { content: @fa-var-road; }\n.@{fa-css-prefix}-robot:before { content: @fa-var-robot; }\n.@{fa-css-prefix}-rocket:before { content: @fa-var-rocket; }\n.@{fa-css-prefix}-rocketchat:before { content: @fa-var-rocketchat; }\n.@{fa-css-prefix}-rockrms:before { content: @fa-var-rockrms; }\n.@{fa-css-prefix}-route:before { content: @fa-var-route; }\n.@{fa-css-prefix}-rss:before { content: @fa-var-rss; }\n.@{fa-css-prefix}-rss-square:before { content: @fa-var-rss-square; }\n.@{fa-css-prefix}-ruble-sign:before { content: @fa-var-ruble-sign; }\n.@{fa-css-prefix}-ruler:before { content: @fa-var-ruler; }\n.@{fa-css-prefix}-ruler-combined:before { content: @fa-var-ruler-combined; }\n.@{fa-css-prefix}-ruler-horizontal:before { content: @fa-var-ruler-horizontal; }\n.@{fa-css-prefix}-ruler-vertical:before { content: @fa-var-ruler-vertical; }\n.@{fa-css-prefix}-running:before { content: @fa-var-running; }\n.@{fa-css-prefix}-rupee-sign:before { content: @fa-var-rupee-sign; }\n.@{fa-css-prefix}-sad-cry:before { content: @fa-var-sad-cry; }\n.@{fa-css-prefix}-sad-tear:before { content: @fa-var-sad-tear; }\n.@{fa-css-prefix}-safari:before { content: @fa-var-safari; }\n.@{fa-css-prefix}-salesforce:before { content: @fa-var-salesforce; }\n.@{fa-css-prefix}-sass:before { content: @fa-var-sass; }\n.@{fa-css-prefix}-satellite:before { content: @fa-var-satellite; }\n.@{fa-css-prefix}-satellite-dish:before { content: @fa-var-satellite-dish; }\n.@{fa-css-prefix}-save:before { content: @fa-var-save; }\n.@{fa-css-prefix}-schlix:before { content: @fa-var-schlix; }\n.@{fa-css-prefix}-school:before { content: @fa-var-school; }\n.@{fa-css-prefix}-screwdriver:before { content: @fa-var-screwdriver; }\n.@{fa-css-prefix}-scribd:before { content: @fa-var-scribd; }\n.@{fa-css-prefix}-scroll:before { content: @fa-var-scroll; }\n.@{fa-css-prefix}-sd-card:before { content: @fa-var-sd-card; }\n.@{fa-css-prefix}-search:before { content: @fa-var-search; }\n.@{fa-css-prefix}-search-dollar:before { content: @fa-var-search-dollar; }\n.@{fa-css-prefix}-search-location:before { content: @fa-var-search-location; }\n.@{fa-css-prefix}-search-minus:before { content: @fa-var-search-minus; }\n.@{fa-css-prefix}-search-plus:before { content: @fa-var-search-plus; }\n.@{fa-css-prefix}-searchengin:before { content: @fa-var-searchengin; }\n.@{fa-css-prefix}-seedling:before { content: @fa-var-seedling; }\n.@{fa-css-prefix}-sellcast:before { content: @fa-var-sellcast; }\n.@{fa-css-prefix}-sellsy:before { content: @fa-var-sellsy; }\n.@{fa-css-prefix}-server:before { content: @fa-var-server; }\n.@{fa-css-prefix}-servicestack:before { content: @fa-var-servicestack; }\n.@{fa-css-prefix}-shapes:before { content: @fa-var-shapes; }\n.@{fa-css-prefix}-share:before { content: @fa-var-share; }\n.@{fa-css-prefix}-share-alt:before { content: @fa-var-share-alt; }\n.@{fa-css-prefix}-share-alt-square:before { content: @fa-var-share-alt-square; }\n.@{fa-css-prefix}-share-square:before { content: @fa-var-share-square; }\n.@{fa-css-prefix}-shekel-sign:before { content: @fa-var-shekel-sign; }\n.@{fa-css-prefix}-shield-alt:before { content: @fa-var-shield-alt; }\n.@{fa-css-prefix}-ship:before { content: @fa-var-ship; }\n.@{fa-css-prefix}-shipping-fast:before { content: @fa-var-shipping-fast; }\n.@{fa-css-prefix}-shirtsinbulk:before { content: @fa-var-shirtsinbulk; }\n.@{fa-css-prefix}-shoe-prints:before { content: @fa-var-shoe-prints; }\n.@{fa-css-prefix}-shopping-bag:before { content: @fa-var-shopping-bag; }\n.@{fa-css-prefix}-shopping-basket:before { content: @fa-var-shopping-basket; }\n.@{fa-css-prefix}-shopping-cart:before { content: @fa-var-shopping-cart; }\n.@{fa-css-prefix}-shopware:before { content: @fa-var-shopware; }\n.@{fa-css-prefix}-shower:before { content: @fa-var-shower; }\n.@{fa-css-prefix}-shuttle-van:before { content: @fa-var-shuttle-van; }\n.@{fa-css-prefix}-sign:before { content: @fa-var-sign; }\n.@{fa-css-prefix}-sign-in-alt:before { content: @fa-var-sign-in-alt; }\n.@{fa-css-prefix}-sign-language:before { content: @fa-var-sign-language; }\n.@{fa-css-prefix}-sign-out-alt:before { content: @fa-var-sign-out-alt; }\n.@{fa-css-prefix}-signal:before { content: @fa-var-signal; }\n.@{fa-css-prefix}-signature:before { content: @fa-var-signature; }\n.@{fa-css-prefix}-sim-card:before { content: @fa-var-sim-card; }\n.@{fa-css-prefix}-simplybuilt:before { content: @fa-var-simplybuilt; }\n.@{fa-css-prefix}-sistrix:before { content: @fa-var-sistrix; }\n.@{fa-css-prefix}-sitemap:before { content: @fa-var-sitemap; }\n.@{fa-css-prefix}-sith:before { content: @fa-var-sith; }\n.@{fa-css-prefix}-skating:before { content: @fa-var-skating; }\n.@{fa-css-prefix}-sketch:before { content: @fa-var-sketch; }\n.@{fa-css-prefix}-skiing:before { content: @fa-var-skiing; }\n.@{fa-css-prefix}-skiing-nordic:before { content: @fa-var-skiing-nordic; }\n.@{fa-css-prefix}-skull:before { content: @fa-var-skull; }\n.@{fa-css-prefix}-skull-crossbones:before { content: @fa-var-skull-crossbones; }\n.@{fa-css-prefix}-skyatlas:before { content: @fa-var-skyatlas; }\n.@{fa-css-prefix}-skype:before { content: @fa-var-skype; }\n.@{fa-css-prefix}-slack:before { content: @fa-var-slack; }\n.@{fa-css-prefix}-slack-hash:before { content: @fa-var-slack-hash; }\n.@{fa-css-prefix}-slash:before { content: @fa-var-slash; }\n.@{fa-css-prefix}-sleigh:before { content: @fa-var-sleigh; }\n.@{fa-css-prefix}-sliders-h:before { content: @fa-var-sliders-h; }\n.@{fa-css-prefix}-slideshare:before { content: @fa-var-slideshare; }\n.@{fa-css-prefix}-smile:before { content: @fa-var-smile; }\n.@{fa-css-prefix}-smile-beam:before { content: @fa-var-smile-beam; }\n.@{fa-css-prefix}-smile-wink:before { content: @fa-var-smile-wink; }\n.@{fa-css-prefix}-smog:before { content: @fa-var-smog; }\n.@{fa-css-prefix}-smoking:before { content: @fa-var-smoking; }\n.@{fa-css-prefix}-smoking-ban:before { content: @fa-var-smoking-ban; }\n.@{fa-css-prefix}-sms:before { content: @fa-var-sms; }\n.@{fa-css-prefix}-snapchat:before { content: @fa-var-snapchat; }\n.@{fa-css-prefix}-snapchat-ghost:before { content: @fa-var-snapchat-ghost; }\n.@{fa-css-prefix}-snapchat-square:before { content: @fa-var-snapchat-square; }\n.@{fa-css-prefix}-snowboarding:before { content: @fa-var-snowboarding; }\n.@{fa-css-prefix}-snowflake:before { content: @fa-var-snowflake; }\n.@{fa-css-prefix}-snowman:before { content: @fa-var-snowman; }\n.@{fa-css-prefix}-snowplow:before { content: @fa-var-snowplow; }\n.@{fa-css-prefix}-socks:before { content: @fa-var-socks; }\n.@{fa-css-prefix}-solar-panel:before { content: @fa-var-solar-panel; }\n.@{fa-css-prefix}-sort:before { content: @fa-var-sort; }\n.@{fa-css-prefix}-sort-alpha-down:before { content: @fa-var-sort-alpha-down; }\n.@{fa-css-prefix}-sort-alpha-down-alt:before { content: @fa-var-sort-alpha-down-alt; }\n.@{fa-css-prefix}-sort-alpha-up:before { content: @fa-var-sort-alpha-up; }\n.@{fa-css-prefix}-sort-alpha-up-alt:before { content: @fa-var-sort-alpha-up-alt; }\n.@{fa-css-prefix}-sort-amount-down:before { content: @fa-var-sort-amount-down; }\n.@{fa-css-prefix}-sort-amount-down-alt:before { content: @fa-var-sort-amount-down-alt; }\n.@{fa-css-prefix}-sort-amount-up:before { content: @fa-var-sort-amount-up; }\n.@{fa-css-prefix}-sort-amount-up-alt:before { content: @fa-var-sort-amount-up-alt; }\n.@{fa-css-prefix}-sort-down:before { content: @fa-var-sort-down; }\n.@{fa-css-prefix}-sort-numeric-down:before { content: @fa-var-sort-numeric-down; }\n.@{fa-css-prefix}-sort-numeric-down-alt:before { content: @fa-var-sort-numeric-down-alt; }\n.@{fa-css-prefix}-sort-numeric-up:before { content: @fa-var-sort-numeric-up; }\n.@{fa-css-prefix}-sort-numeric-up-alt:before { content: @fa-var-sort-numeric-up-alt; }\n.@{fa-css-prefix}-sort-up:before { content: @fa-var-sort-up; }\n.@{fa-css-prefix}-soundcloud:before { content: @fa-var-soundcloud; }\n.@{fa-css-prefix}-sourcetree:before { content: @fa-var-sourcetree; }\n.@{fa-css-prefix}-spa:before { content: @fa-var-spa; }\n.@{fa-css-prefix}-space-shuttle:before { content: @fa-var-space-shuttle; }\n.@{fa-css-prefix}-speakap:before { content: @fa-var-speakap; }\n.@{fa-css-prefix}-speaker-deck:before { content: @fa-var-speaker-deck; }\n.@{fa-css-prefix}-spell-check:before { content: @fa-var-spell-check; }\n.@{fa-css-prefix}-spider:before { content: @fa-var-spider; }\n.@{fa-css-prefix}-spinner:before { content: @fa-var-spinner; }\n.@{fa-css-prefix}-splotch:before { content: @fa-var-splotch; }\n.@{fa-css-prefix}-spotify:before { content: @fa-var-spotify; }\n.@{fa-css-prefix}-spray-can:before { content: @fa-var-spray-can; }\n.@{fa-css-prefix}-square:before { content: @fa-var-square; }\n.@{fa-css-prefix}-square-full:before { content: @fa-var-square-full; }\n.@{fa-css-prefix}-square-root-alt:before { content: @fa-var-square-root-alt; }\n.@{fa-css-prefix}-squarespace:before { content: @fa-var-squarespace; }\n.@{fa-css-prefix}-stack-exchange:before { content: @fa-var-stack-exchange; }\n.@{fa-css-prefix}-stack-overflow:before { content: @fa-var-stack-overflow; }\n.@{fa-css-prefix}-stackpath:before { content: @fa-var-stackpath; }\n.@{fa-css-prefix}-stamp:before { content: @fa-var-stamp; }\n.@{fa-css-prefix}-star:before { content: @fa-var-star; }\n.@{fa-css-prefix}-star-and-crescent:before { content: @fa-var-star-and-crescent; }\n.@{fa-css-prefix}-star-half:before { content: @fa-var-star-half; }\n.@{fa-css-prefix}-star-half-alt:before { content: @fa-var-star-half-alt; }\n.@{fa-css-prefix}-star-of-david:before { content: @fa-var-star-of-david; }\n.@{fa-css-prefix}-star-of-life:before { content: @fa-var-star-of-life; }\n.@{fa-css-prefix}-staylinked:before { content: @fa-var-staylinked; }\n.@{fa-css-prefix}-steam:before { content: @fa-var-steam; }\n.@{fa-css-prefix}-steam-square:before { content: @fa-var-steam-square; }\n.@{fa-css-prefix}-steam-symbol:before { content: @fa-var-steam-symbol; }\n.@{fa-css-prefix}-step-backward:before { content: @fa-var-step-backward; }\n.@{fa-css-prefix}-step-forward:before { content: @fa-var-step-forward; }\n.@{fa-css-prefix}-stethoscope:before { content: @fa-var-stethoscope; }\n.@{fa-css-prefix}-sticker-mule:before { content: @fa-var-sticker-mule; }\n.@{fa-css-prefix}-sticky-note:before { content: @fa-var-sticky-note; }\n.@{fa-css-prefix}-stop:before { content: @fa-var-stop; }\n.@{fa-css-prefix}-stop-circle:before { content: @fa-var-stop-circle; }\n.@{fa-css-prefix}-stopwatch:before { content: @fa-var-stopwatch; }\n.@{fa-css-prefix}-store:before { content: @fa-var-store; }\n.@{fa-css-prefix}-store-alt:before { content: @fa-var-store-alt; }\n.@{fa-css-prefix}-strava:before { content: @fa-var-strava; }\n.@{fa-css-prefix}-stream:before { content: @fa-var-stream; }\n.@{fa-css-prefix}-street-view:before { content: @fa-var-street-view; }\n.@{fa-css-prefix}-strikethrough:before { content: @fa-var-strikethrough; }\n.@{fa-css-prefix}-stripe:before { content: @fa-var-stripe; }\n.@{fa-css-prefix}-stripe-s:before { content: @fa-var-stripe-s; }\n.@{fa-css-prefix}-stroopwafel:before { content: @fa-var-stroopwafel; }\n.@{fa-css-prefix}-studiovinari:before { content: @fa-var-studiovinari; }\n.@{fa-css-prefix}-stumbleupon:before { content: @fa-var-stumbleupon; }\n.@{fa-css-prefix}-stumbleupon-circle:before { content: @fa-var-stumbleupon-circle; }\n.@{fa-css-prefix}-subscript:before { content: @fa-var-subscript; }\n.@{fa-css-prefix}-subway:before { content: @fa-var-subway; }\n.@{fa-css-prefix}-suitcase:before { content: @fa-var-suitcase; }\n.@{fa-css-prefix}-suitcase-rolling:before { content: @fa-var-suitcase-rolling; }\n.@{fa-css-prefix}-sun:before { content: @fa-var-sun; }\n.@{fa-css-prefix}-superpowers:before { content: @fa-var-superpowers; }\n.@{fa-css-prefix}-superscript:before { content: @fa-var-superscript; }\n.@{fa-css-prefix}-supple:before { content: @fa-var-supple; }\n.@{fa-css-prefix}-surprise:before { content: @fa-var-surprise; }\n.@{fa-css-prefix}-suse:before { content: @fa-var-suse; }\n.@{fa-css-prefix}-swatchbook:before { content: @fa-var-swatchbook; }\n.@{fa-css-prefix}-swimmer:before { content: @fa-var-swimmer; }\n.@{fa-css-prefix}-swimming-pool:before { content: @fa-var-swimming-pool; }\n.@{fa-css-prefix}-symfony:before { content: @fa-var-symfony; }\n.@{fa-css-prefix}-synagogue:before { content: @fa-var-synagogue; }\n.@{fa-css-prefix}-sync:before { content: @fa-var-sync; }\n.@{fa-css-prefix}-sync-alt:before { content: @fa-var-sync-alt; }\n.@{fa-css-prefix}-syringe:before { content: @fa-var-syringe; }\n.@{fa-css-prefix}-table:before { content: @fa-var-table; }\n.@{fa-css-prefix}-table-tennis:before { content: @fa-var-table-tennis; }\n.@{fa-css-prefix}-tablet:before { content: @fa-var-tablet; }\n.@{fa-css-prefix}-tablet-alt:before { content: @fa-var-tablet-alt; }\n.@{fa-css-prefix}-tablets:before { content: @fa-var-tablets; }\n.@{fa-css-prefix}-tachometer-alt:before { content: @fa-var-tachometer-alt; }\n.@{fa-css-prefix}-tag:before { content: @fa-var-tag; }\n.@{fa-css-prefix}-tags:before { content: @fa-var-tags; }\n.@{fa-css-prefix}-tape:before { content: @fa-var-tape; }\n.@{fa-css-prefix}-tasks:before { content: @fa-var-tasks; }\n.@{fa-css-prefix}-taxi:before { content: @fa-var-taxi; }\n.@{fa-css-prefix}-teamspeak:before { content: @fa-var-teamspeak; }\n.@{fa-css-prefix}-teeth:before { content: @fa-var-teeth; }\n.@{fa-css-prefix}-teeth-open:before { content: @fa-var-teeth-open; }\n.@{fa-css-prefix}-telegram:before { content: @fa-var-telegram; }\n.@{fa-css-prefix}-telegram-plane:before { content: @fa-var-telegram-plane; }\n.@{fa-css-prefix}-temperature-high:before { content: @fa-var-temperature-high; }\n.@{fa-css-prefix}-temperature-low:before { content: @fa-var-temperature-low; }\n.@{fa-css-prefix}-tencent-weibo:before { content: @fa-var-tencent-weibo; }\n.@{fa-css-prefix}-tenge:before { content: @fa-var-tenge; }\n.@{fa-css-prefix}-terminal:before { content: @fa-var-terminal; }\n.@{fa-css-prefix}-text-height:before { content: @fa-var-text-height; }\n.@{fa-css-prefix}-text-width:before { content: @fa-var-text-width; }\n.@{fa-css-prefix}-th:before { content: @fa-var-th; }\n.@{fa-css-prefix}-th-large:before { content: @fa-var-th-large; }\n.@{fa-css-prefix}-th-list:before { content: @fa-var-th-list; }\n.@{fa-css-prefix}-the-red-yeti:before { content: @fa-var-the-red-yeti; }\n.@{fa-css-prefix}-theater-masks:before { content: @fa-var-theater-masks; }\n.@{fa-css-prefix}-themeco:before { content: @fa-var-themeco; }\n.@{fa-css-prefix}-themeisle:before { content: @fa-var-themeisle; }\n.@{fa-css-prefix}-thermometer:before { content: @fa-var-thermometer; }\n.@{fa-css-prefix}-thermometer-empty:before { content: @fa-var-thermometer-empty; }\n.@{fa-css-prefix}-thermometer-full:before { content: @fa-var-thermometer-full; }\n.@{fa-css-prefix}-thermometer-half:before { content: @fa-var-thermometer-half; }\n.@{fa-css-prefix}-thermometer-quarter:before { content: @fa-var-thermometer-quarter; }\n.@{fa-css-prefix}-thermometer-three-quarters:before { content: @fa-var-thermometer-three-quarters; }\n.@{fa-css-prefix}-think-peaks:before { content: @fa-var-think-peaks; }\n.@{fa-css-prefix}-thumbs-down:before { content: @fa-var-thumbs-down; }\n.@{fa-css-prefix}-thumbs-up:before { content: @fa-var-thumbs-up; }\n.@{fa-css-prefix}-thumbtack:before { content: @fa-var-thumbtack; }\n.@{fa-css-prefix}-ticket-alt:before { content: @fa-var-ticket-alt; }\n.@{fa-css-prefix}-times:before { content: @fa-var-times; }\n.@{fa-css-prefix}-times-circle:before { content: @fa-var-times-circle; }\n.@{fa-css-prefix}-tint:before { content: @fa-var-tint; }\n.@{fa-css-prefix}-tint-slash:before { content: @fa-var-tint-slash; }\n.@{fa-css-prefix}-tired:before { content: @fa-var-tired; }\n.@{fa-css-prefix}-toggle-off:before { content: @fa-var-toggle-off; }\n.@{fa-css-prefix}-toggle-on:before { content: @fa-var-toggle-on; }\n.@{fa-css-prefix}-toilet:before { content: @fa-var-toilet; }\n.@{fa-css-prefix}-toilet-paper:before { content: @fa-var-toilet-paper; }\n.@{fa-css-prefix}-toolbox:before { content: @fa-var-toolbox; }\n.@{fa-css-prefix}-tools:before { content: @fa-var-tools; }\n.@{fa-css-prefix}-tooth:before { content: @fa-var-tooth; }\n.@{fa-css-prefix}-torah:before { content: @fa-var-torah; }\n.@{fa-css-prefix}-torii-gate:before { content: @fa-var-torii-gate; }\n.@{fa-css-prefix}-tractor:before { content: @fa-var-tractor; }\n.@{fa-css-prefix}-trade-federation:before { content: @fa-var-trade-federation; }\n.@{fa-css-prefix}-trademark:before { content: @fa-var-trademark; }\n.@{fa-css-prefix}-traffic-light:before { content: @fa-var-traffic-light; }\n.@{fa-css-prefix}-train:before { content: @fa-var-train; }\n.@{fa-css-prefix}-tram:before { content: @fa-var-tram; }\n.@{fa-css-prefix}-transgender:before { content: @fa-var-transgender; }\n.@{fa-css-prefix}-transgender-alt:before { content: @fa-var-transgender-alt; }\n.@{fa-css-prefix}-trash:before { content: @fa-var-trash; }\n.@{fa-css-prefix}-trash-alt:before { content: @fa-var-trash-alt; }\n.@{fa-css-prefix}-trash-restore:before { content: @fa-var-trash-restore; }\n.@{fa-css-prefix}-trash-restore-alt:before { content: @fa-var-trash-restore-alt; }\n.@{fa-css-prefix}-tree:before { content: @fa-var-tree; }\n.@{fa-css-prefix}-trello:before { content: @fa-var-trello; }\n.@{fa-css-prefix}-tripadvisor:before { content: @fa-var-tripadvisor; }\n.@{fa-css-prefix}-trophy:before { content: @fa-var-trophy; }\n.@{fa-css-prefix}-truck:before { content: @fa-var-truck; }\n.@{fa-css-prefix}-truck-loading:before { content: @fa-var-truck-loading; }\n.@{fa-css-prefix}-truck-monster:before { content: @fa-var-truck-monster; }\n.@{fa-css-prefix}-truck-moving:before { content: @fa-var-truck-moving; }\n.@{fa-css-prefix}-truck-pickup:before { content: @fa-var-truck-pickup; }\n.@{fa-css-prefix}-tshirt:before { content: @fa-var-tshirt; }\n.@{fa-css-prefix}-tty:before { content: @fa-var-tty; }\n.@{fa-css-prefix}-tumblr:before { content: @fa-var-tumblr; }\n.@{fa-css-prefix}-tumblr-square:before { content: @fa-var-tumblr-square; }\n.@{fa-css-prefix}-tv:before { content: @fa-var-tv; }\n.@{fa-css-prefix}-twitch:before { content: @fa-var-twitch; }\n.@{fa-css-prefix}-twitter:before { content: @fa-var-twitter; }\n.@{fa-css-prefix}-twitter-square:before { content: @fa-var-twitter-square; }\n.@{fa-css-prefix}-typo3:before { content: @fa-var-typo3; }\n.@{fa-css-prefix}-uber:before { content: @fa-var-uber; }\n.@{fa-css-prefix}-ubuntu:before { content: @fa-var-ubuntu; }\n.@{fa-css-prefix}-uikit:before { content: @fa-var-uikit; }\n.@{fa-css-prefix}-umbrella:before { content: @fa-var-umbrella; }\n.@{fa-css-prefix}-umbrella-beach:before { content: @fa-var-umbrella-beach; }\n.@{fa-css-prefix}-underline:before { content: @fa-var-underline; }\n.@{fa-css-prefix}-undo:before { content: @fa-var-undo; }\n.@{fa-css-prefix}-undo-alt:before { content: @fa-var-undo-alt; }\n.@{fa-css-prefix}-uniregistry:before { content: @fa-var-uniregistry; }\n.@{fa-css-prefix}-universal-access:before { content: @fa-var-universal-access; }\n.@{fa-css-prefix}-university:before { content: @fa-var-university; }\n.@{fa-css-prefix}-unlink:before { content: @fa-var-unlink; }\n.@{fa-css-prefix}-unlock:before { content: @fa-var-unlock; }\n.@{fa-css-prefix}-unlock-alt:before { content: @fa-var-unlock-alt; }\n.@{fa-css-prefix}-untappd:before { content: @fa-var-untappd; }\n.@{fa-css-prefix}-upload:before { content: @fa-var-upload; }\n.@{fa-css-prefix}-ups:before { content: @fa-var-ups; }\n.@{fa-css-prefix}-usb:before { content: @fa-var-usb; }\n.@{fa-css-prefix}-user:before { content: @fa-var-user; }\n.@{fa-css-prefix}-user-alt:before { content: @fa-var-user-alt; }\n.@{fa-css-prefix}-user-alt-slash:before { content: @fa-var-user-alt-slash; }\n.@{fa-css-prefix}-user-astronaut:before { content: @fa-var-user-astronaut; }\n.@{fa-css-prefix}-user-check:before { content: @fa-var-user-check; }\n.@{fa-css-prefix}-user-circle:before { content: @fa-var-user-circle; }\n.@{fa-css-prefix}-user-clock:before { content: @fa-var-user-clock; }\n.@{fa-css-prefix}-user-cog:before { content: @fa-var-user-cog; }\n.@{fa-css-prefix}-user-edit:before { content: @fa-var-user-edit; }\n.@{fa-css-prefix}-user-friends:before { content: @fa-var-user-friends; }\n.@{fa-css-prefix}-user-graduate:before { content: @fa-var-user-graduate; }\n.@{fa-css-prefix}-user-injured:before { content: @fa-var-user-injured; }\n.@{fa-css-prefix}-user-lock:before { content: @fa-var-user-lock; }\n.@{fa-css-prefix}-user-md:before { content: @fa-var-user-md; }\n.@{fa-css-prefix}-user-minus:before { content: @fa-var-user-minus; }\n.@{fa-css-prefix}-user-ninja:before { content: @fa-var-user-ninja; }\n.@{fa-css-prefix}-user-nurse:before { content: @fa-var-user-nurse; }\n.@{fa-css-prefix}-user-plus:before { content: @fa-var-user-plus; }\n.@{fa-css-prefix}-user-secret:before { content: @fa-var-user-secret; }\n.@{fa-css-prefix}-user-shield:before { content: @fa-var-user-shield; }\n.@{fa-css-prefix}-user-slash:before { content: @fa-var-user-slash; }\n.@{fa-css-prefix}-user-tag:before { content: @fa-var-user-tag; }\n.@{fa-css-prefix}-user-tie:before { content: @fa-var-user-tie; }\n.@{fa-css-prefix}-user-times:before { content: @fa-var-user-times; }\n.@{fa-css-prefix}-users:before { content: @fa-var-users; }\n.@{fa-css-prefix}-users-cog:before { content: @fa-var-users-cog; }\n.@{fa-css-prefix}-usps:before { content: @fa-var-usps; }\n.@{fa-css-prefix}-ussunnah:before { content: @fa-var-ussunnah; }\n.@{fa-css-prefix}-utensil-spoon:before { content: @fa-var-utensil-spoon; }\n.@{fa-css-prefix}-utensils:before { content: @fa-var-utensils; }\n.@{fa-css-prefix}-vaadin:before { content: @fa-var-vaadin; }\n.@{fa-css-prefix}-vector-square:before { content: @fa-var-vector-square; }\n.@{fa-css-prefix}-venus:before { content: @fa-var-venus; }\n.@{fa-css-prefix}-venus-double:before { content: @fa-var-venus-double; }\n.@{fa-css-prefix}-venus-mars:before { content: @fa-var-venus-mars; }\n.@{fa-css-prefix}-viacoin:before { content: @fa-var-viacoin; }\n.@{fa-css-prefix}-viadeo:before { content: @fa-var-viadeo; }\n.@{fa-css-prefix}-viadeo-square:before { content: @fa-var-viadeo-square; }\n.@{fa-css-prefix}-vial:before { content: @fa-var-vial; }\n.@{fa-css-prefix}-vials:before { content: @fa-var-vials; }\n.@{fa-css-prefix}-viber:before { content: @fa-var-viber; }\n.@{fa-css-prefix}-video:before { content: @fa-var-video; }\n.@{fa-css-prefix}-video-slash:before { content: @fa-var-video-slash; }\n.@{fa-css-prefix}-vihara:before { content: @fa-var-vihara; }\n.@{fa-css-prefix}-vimeo:before { content: @fa-var-vimeo; }\n.@{fa-css-prefix}-vimeo-square:before { content: @fa-var-vimeo-square; }\n.@{fa-css-prefix}-vimeo-v:before { content: @fa-var-vimeo-v; }\n.@{fa-css-prefix}-vine:before { content: @fa-var-vine; }\n.@{fa-css-prefix}-vk:before { content: @fa-var-vk; }\n.@{fa-css-prefix}-vnv:before { content: @fa-var-vnv; }\n.@{fa-css-prefix}-voicemail:before { content: @fa-var-voicemail; }\n.@{fa-css-prefix}-volleyball-ball:before { content: @fa-var-volleyball-ball; }\n.@{fa-css-prefix}-volume-down:before { content: @fa-var-volume-down; }\n.@{fa-css-prefix}-volume-mute:before { content: @fa-var-volume-mute; }\n.@{fa-css-prefix}-volume-off:before { content: @fa-var-volume-off; }\n.@{fa-css-prefix}-volume-up:before { content: @fa-var-volume-up; }\n.@{fa-css-prefix}-vote-yea:before { content: @fa-var-vote-yea; }\n.@{fa-css-prefix}-vr-cardboard:before { content: @fa-var-vr-cardboard; }\n.@{fa-css-prefix}-vuejs:before { content: @fa-var-vuejs; }\n.@{fa-css-prefix}-walking:before { content: @fa-var-walking; }\n.@{fa-css-prefix}-wallet:before { content: @fa-var-wallet; }\n.@{fa-css-prefix}-warehouse:before { content: @fa-var-warehouse; }\n.@{fa-css-prefix}-water:before { content: @fa-var-water; }\n.@{fa-css-prefix}-wave-square:before { content: @fa-var-wave-square; }\n.@{fa-css-prefix}-waze:before { content: @fa-var-waze; }\n.@{fa-css-prefix}-weebly:before { content: @fa-var-weebly; }\n.@{fa-css-prefix}-weibo:before { content: @fa-var-weibo; }\n.@{fa-css-prefix}-weight:before { content: @fa-var-weight; }\n.@{fa-css-prefix}-weight-hanging:before { content: @fa-var-weight-hanging; }\n.@{fa-css-prefix}-weixin:before { content: @fa-var-weixin; }\n.@{fa-css-prefix}-whatsapp:before { content: @fa-var-whatsapp; }\n.@{fa-css-prefix}-whatsapp-square:before { content: @fa-var-whatsapp-square; }\n.@{fa-css-prefix}-wheelchair:before { content: @fa-var-wheelchair; }\n.@{fa-css-prefix}-whmcs:before { content: @fa-var-whmcs; }\n.@{fa-css-prefix}-wifi:before { content: @fa-var-wifi; }\n.@{fa-css-prefix}-wikipedia-w:before { content: @fa-var-wikipedia-w; }\n.@{fa-css-prefix}-wind:before { content: @fa-var-wind; }\n.@{fa-css-prefix}-window-close:before { content: @fa-var-window-close; }\n.@{fa-css-prefix}-window-maximize:before { content: @fa-var-window-maximize; }\n.@{fa-css-prefix}-window-minimize:before { content: @fa-var-window-minimize; }\n.@{fa-css-prefix}-window-restore:before { content: @fa-var-window-restore; }\n.@{fa-css-prefix}-windows:before { content: @fa-var-windows; }\n.@{fa-css-prefix}-wine-bottle:before { content: @fa-var-wine-bottle; }\n.@{fa-css-prefix}-wine-glass:before { content: @fa-var-wine-glass; }\n.@{fa-css-prefix}-wine-glass-alt:before { content: @fa-var-wine-glass-alt; }\n.@{fa-css-prefix}-wix:before { content: @fa-var-wix; }\n.@{fa-css-prefix}-wizards-of-the-coast:before { content: @fa-var-wizards-of-the-coast; }\n.@{fa-css-prefix}-wolf-pack-battalion:before { content: @fa-var-wolf-pack-battalion; }\n.@{fa-css-prefix}-won-sign:before { content: @fa-var-won-sign; }\n.@{fa-css-prefix}-wordpress:before { content: @fa-var-wordpress; }\n.@{fa-css-prefix}-wordpress-simple:before { content: @fa-var-wordpress-simple; }\n.@{fa-css-prefix}-wpbeginner:before { content: @fa-var-wpbeginner; }\n.@{fa-css-prefix}-wpexplorer:before { content: @fa-var-wpexplorer; }\n.@{fa-css-prefix}-wpforms:before { content: @fa-var-wpforms; }\n.@{fa-css-prefix}-wpressr:before { content: @fa-var-wpressr; }\n.@{fa-css-prefix}-wrench:before { content: @fa-var-wrench; }\n.@{fa-css-prefix}-x-ray:before { content: @fa-var-x-ray; }\n.@{fa-css-prefix}-xbox:before { content: @fa-var-xbox; }\n.@{fa-css-prefix}-xing:before { content: @fa-var-xing; }\n.@{fa-css-prefix}-xing-square:before { content: @fa-var-xing-square; }\n.@{fa-css-prefix}-y-combinator:before { content: @fa-var-y-combinator; }\n.@{fa-css-prefix}-yahoo:before { content: @fa-var-yahoo; }\n.@{fa-css-prefix}-yammer:before { content: @fa-var-yammer; }\n.@{fa-css-prefix}-yandex:before { content: @fa-var-yandex; }\n.@{fa-css-prefix}-yandex-international:before { content: @fa-var-yandex-international; }\n.@{fa-css-prefix}-yarn:before { content: @fa-var-yarn; }\n.@{fa-css-prefix}-yelp:before { content: @fa-var-yelp; }\n.@{fa-css-prefix}-yen-sign:before { content: @fa-var-yen-sign; }\n.@{fa-css-prefix}-yin-yang:before { content: @fa-var-yin-yang; }\n.@{fa-css-prefix}-yoast:before { content: @fa-var-yoast; }\n.@{fa-css-prefix}-youtube:before { content: @fa-var-youtube; }\n.@{fa-css-prefix}-youtube-square:before { content: @fa-var-youtube-square; }\n.@{fa-css-prefix}-zhihu:before { content: @fa-var-zhihu; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_larger.less",
    "content": "// Icon Sizes\n// -------------------------\n\n.larger(@factor) when (@factor > 0) {\n  .larger((@factor - 1));\n\n  .@{fa-css-prefix}-@{factor}x {\n    font-size: (@factor * 1em);\n  }\n}\n\n/* makes the font 33% larger relative to the icon container */\n.@{fa-css-prefix}-lg {\n  font-size: (4em / 3);\n  line-height: (3em / 4);\n  vertical-align: -.0667em;\n}\n\n.@{fa-css-prefix}-xs {\n  font-size: .75em;\n}\n\n.@{fa-css-prefix}-sm {\n  font-size: .875em;\n}\n\n.larger(10);\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_list.less",
    "content": "// List Icons\n// -------------------------\n\n.@{fa-css-prefix}-ul {\n  list-style-type: none;\n  margin-left: (@fa-li-width * 5/4);\n  padding-left: 0;\n\n  > li { position: relative; }\n}\n\n.@{fa-css-prefix}-li {\n  left: -@fa-li-width;\n  position: absolute;\n  text-align: center;\n  width: @fa-li-width;\n  line-height: inherit;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_mixins.less",
    "content": "// Mixins\n// --------------------------\n\n.fa-icon() {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  font-weight: normal;\n  line-height: 1;\n}\n\n.fa-icon-rotate(@degrees, @rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=@{rotation})\";\n  transform: rotate(@degrees);\n}\n\n.fa-icon-flip(@horiz, @vert, @rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=@{rotation}, mirror=1)\";\n  transform: scale(@horiz, @vert);\n}\n\n\n// Only display content to screen readers. A la Bootstrap 4.\n//\n// See: http://a11yproject.com/posts/how-to-hide-content/\n\n.sr-only() {\n  border: 0;\n  clip: rect(0,0,0,0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px;\n}\n\n// Use in conjunction with .sr-only to only display content when it's focused.\n//\n// Useful for \"Skip to main content\" links; see http://www.w3.org/TR/2013/NOTE-WCAG20-TECHS-20130905/G1\n//\n// Credit: HTML5 Boilerplate\n\n.sr-only-focusable() {\n  &:active,\n  &:focus {\n    clip: auto;\n    height: auto;\n    margin: 0;\n    overflow: visible;\n    position: static;\n    width: auto;\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_rotated-flipped.less",
    "content": "// Rotated & Flipped Icons\n// -------------------------\n\n.@{fa-css-prefix}-rotate-90  { .fa-icon-rotate(90deg, 1);  }\n.@{fa-css-prefix}-rotate-180 { .fa-icon-rotate(180deg, 2); }\n.@{fa-css-prefix}-rotate-270 { .fa-icon-rotate(270deg, 3); }\n\n.@{fa-css-prefix}-flip-horizontal { .fa-icon-flip(-1, 1, 0); }\n.@{fa-css-prefix}-flip-vertical   { .fa-icon-flip(1, -1, 2); }\n.@{fa-css-prefix}-flip-both, .@{fa-css-prefix}-flip-horizontal.@{fa-css-prefix}-flip-vertical { .fa-icon-flip(-1, -1, 2); }\n\n// Hook for IE8-9\n// -------------------------\n\n:root {\n  .@{fa-css-prefix}-rotate-90,\n  .@{fa-css-prefix}-rotate-180,\n  .@{fa-css-prefix}-rotate-270,\n  .@{fa-css-prefix}-flip-horizontal,\n  .@{fa-css-prefix}-flip-vertical,\n  .@{fa-css-prefix}-flip-both {\n    filter: none;\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_screen-reader.less",
    "content": "// Screen Readers\n// -------------------------\n\n.sr-only { .sr-only(); }\n.sr-only-focusable { .sr-only-focusable(); }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_shims.less",
    "content": ".@{fa-css-prefix}.@{fa-css-prefix}-glass:before { content: @fa-var-glass-martini; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-meetup {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-o:before { content: @fa-var-star; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-remove:before { content: @fa-var-times; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-close:before { content: @fa-var-times; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gear:before { content: @fa-var-cog; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-trash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-trash-o:before { content: @fa-var-trash-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-o:before { content: @fa-var-file; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-clock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-clock-o:before { content: @fa-var-clock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-down:before { content: @fa-var-arrow-alt-circle-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-up:before { content: @fa-var-arrow-alt-circle-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-play-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-play-circle-o:before { content: @fa-var-play-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-repeat:before { content: @fa-var-redo; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rotate-right:before { content: @fa-var-redo; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-refresh:before { content: @fa-var-sync; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-list-alt {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dedent:before { content: @fa-var-outdent; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-video-camera:before { content: @fa-var-video; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-picture-o:before { content: @fa-var-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-photo {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-photo:before { content: @fa-var-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-image {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-image:before { content: @fa-var-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil:before { content: @fa-var-pencil-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-map-marker:before { content: @fa-var-map-marker-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil-square-o:before { content: @fa-var-edit; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-share-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-share-square-o:before { content: @fa-var-share-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-check-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-check-square-o:before { content: @fa-var-check-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows:before { content: @fa-var-arrows-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-times-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-times-circle-o:before { content: @fa-var-times-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-check-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-check-circle-o:before { content: @fa-var-check-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mail-forward:before { content: @fa-var-share; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eye {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eye-slash {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-warning:before { content: @fa-var-exclamation-triangle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar:before { content: @fa-var-calendar-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows-v:before { content: @fa-var-arrows-alt-v; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows-h:before { content: @fa-var-arrows-alt-h; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart:before { content: @fa-var-chart-bar; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart-o:before { content: @fa-var-chart-bar; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-twitter-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gears:before { content: @fa-var-cogs; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-up:before { content: @fa-var-thumbs-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-down:before { content: @fa-var-thumbs-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-heart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-heart-o:before { content: @fa-var-heart; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sign-out:before { content: @fa-var-sign-out-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin-square:before { content: @fa-var-linkedin; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thumb-tack:before { content: @fa-var-thumbtack; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-external-link:before { content: @fa-var-external-link-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sign-in:before { content: @fa-var-sign-in-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-github-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lemon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-lemon-o:before { content: @fa-var-lemon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-square-o:before { content: @fa-var-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bookmark-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bookmark-o:before { content: @fa-var-bookmark; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-twitter {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook:before { content: @fa-var-facebook-f; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-f {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-f:before { content: @fa-var-facebook-f; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-github {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-credit-card {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-feed:before { content: @fa-var-rss; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hdd-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hdd-o:before { content: @fa-var-hdd; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-right:before { content: @fa-var-hand-point-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-left:before { content: @fa-var-hand-point-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-up:before { content: @fa-var-hand-point-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-down:before { content: @fa-var-hand-point-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows-alt:before { content: @fa-var-expand-arrows-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-group:before { content: @fa-var-users; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-chain:before { content: @fa-var-link; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-scissors:before { content: @fa-var-cut; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-files-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-files-o:before { content: @fa-var-copy; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-floppy-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-floppy-o:before { content: @fa-var-save; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-navicon:before { content: @fa-var-bars; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reorder:before { content: @fa-var-bars; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pinterest {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pinterest-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus:before { content: @fa-var-google-plus-g; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-money {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-money:before { content: @fa-var-money-bill-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-unsorted:before { content: @fa-var-sort; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-desc:before { content: @fa-var-sort-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-asc:before { content: @fa-var-sort-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin:before { content: @fa-var-linkedin-in; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rotate-left:before { content: @fa-var-undo; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-legal:before { content: @fa-var-gavel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tachometer:before { content: @fa-var-tachometer-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dashboard:before { content: @fa-var-tachometer-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-comment-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-comment-o:before { content: @fa-var-comment; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-comments-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-comments-o:before { content: @fa-var-comments; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-flash:before { content: @fa-var-bolt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-clipboard {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-paste {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-paste:before { content: @fa-var-clipboard; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lightbulb-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-lightbulb-o:before { content: @fa-var-lightbulb; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-exchange:before { content: @fa-var-exchange-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cloud-download:before { content: @fa-var-cloud-download-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cloud-upload:before { content: @fa-var-cloud-upload-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-o:before { content: @fa-var-bell; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cutlery:before { content: @fa-var-utensils; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-text-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-text-o:before { content: @fa-var-file-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-building-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-building-o:before { content: @fa-var-building; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hospital-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hospital-o:before { content: @fa-var-hospital; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tablet:before { content: @fa-var-tablet-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mobile:before { content: @fa-var-mobile-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mobile-phone:before { content: @fa-var-mobile-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-o:before { content: @fa-var-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mail-reply:before { content: @fa-var-reply; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-github-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-o:before { content: @fa-var-folder; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-open-o:before { content: @fa-var-folder-open; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-smile-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-smile-o:before { content: @fa-var-smile; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-frown-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-frown-o:before { content: @fa-var-frown; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-meh-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-meh-o:before { content: @fa-var-meh; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-keyboard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-keyboard-o:before { content: @fa-var-keyboard; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-flag-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-flag-o:before { content: @fa-var-flag; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mail-reply-all:before { content: @fa-var-reply-all; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-o:before { content: @fa-var-star-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-empty {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-empty:before { content: @fa-var-star-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-full {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-full:before { content: @fa-var-star-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-code-fork:before { content: @fa-var-code-branch; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-chain-broken:before { content: @fa-var-unlink; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-shield:before { content: @fa-var-shield-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-o:before { content: @fa-var-calendar; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-maxcdn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-html5 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-css3 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ticket:before { content: @fa-var-ticket-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-minus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-minus-square-o:before { content: @fa-var-minus-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-level-up:before { content: @fa-var-level-up-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-level-down:before { content: @fa-var-level-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil-square:before { content: @fa-var-pen-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-external-link-square:before { content: @fa-var-external-link-square-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-compass {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-down:before { content: @fa-var-caret-square-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-down:before { content: @fa-var-caret-square-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-up:before { content: @fa-var-caret-square-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-up:before { content: @fa-var-caret-square-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-right:before { content: @fa-var-caret-square-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-right:before { content: @fa-var-caret-square-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eur:before { content: @fa-var-euro-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-euro:before { content: @fa-var-euro-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gbp:before { content: @fa-var-pound-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-usd:before { content: @fa-var-dollar-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dollar:before { content: @fa-var-dollar-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-inr:before { content: @fa-var-rupee-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rupee:before { content: @fa-var-rupee-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-jpy:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cny:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rmb:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yen:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rub:before { content: @fa-var-ruble-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ruble:before { content: @fa-var-ruble-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rouble:before { content: @fa-var-ruble-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-krw:before { content: @fa-var-won-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-won:before { content: @fa-var-won-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-btc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bitcoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bitcoin:before { content: @fa-var-btc; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-text:before { content: @fa-var-file-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-alpha-asc:before { content: @fa-var-sort-alpha-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-alpha-desc:before { content: @fa-var-sort-alpha-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-amount-asc:before { content: @fa-var-sort-amount-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-amount-desc:before { content: @fa-var-sort-amount-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-numeric-asc:before { content: @fa-var-sort-numeric-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-numeric-desc:before { content: @fa-var-sort-numeric-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-xing {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-xing-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube-play {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube-play:before { content: @fa-var-youtube; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dropbox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stack-overflow {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-instagram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-flickr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-adn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bitbucket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bitbucket-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bitbucket-square:before { content: @fa-var-bitbucket; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tumblr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tumblr-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-down:before { content: @fa-var-long-arrow-alt-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-up:before { content: @fa-var-long-arrow-alt-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-left:before { content: @fa-var-long-arrow-alt-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-right:before { content: @fa-var-long-arrow-alt-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-apple {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-windows {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-android {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linux {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dribbble {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-skype {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-foursquare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-trello {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gratipay {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gittip {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-gittip:before { content: @fa-var-gratipay; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sun-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-sun-o:before { content: @fa-var-sun; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-moon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-moon-o:before { content: @fa-var-moon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-renren {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pagelines {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stack-exchange {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-right:before { content: @fa-var-arrow-alt-circle-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-left:before { content: @fa-var-arrow-alt-circle-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-left:before { content: @fa-var-caret-square-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-left:before { content: @fa-var-caret-square-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dot-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-dot-circle-o:before { content: @fa-var-dot-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vimeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-try:before { content: @fa-var-lira-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-turkish-lira:before { content: @fa-var-lira-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-plus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-plus-square-o:before { content: @fa-var-plus-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-slack {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wordpress {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-openid {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-institution:before { content: @fa-var-university; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bank:before { content: @fa-var-university; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mortar-board:before { content: @fa-var-graduation-cap; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yahoo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reddit {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reddit-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stumbleupon-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stumbleupon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-delicious {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-digg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pied-piper-pp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pied-piper-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-drupal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-joomla {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-spoon:before { content: @fa-var-utensil-spoon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-behance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-behance-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-steam {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-steam-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-automobile:before { content: @fa-var-car; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cab:before { content: @fa-var-taxi; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-o:before { content: @fa-var-envelope; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-deviantart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-soundcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-pdf-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-pdf-o:before { content: @fa-var-file-pdf; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-word-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-word-o:before { content: @fa-var-file-word; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-excel-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-excel-o:before { content: @fa-var-file-excel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-powerpoint-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-powerpoint-o:before { content: @fa-var-file-powerpoint; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-image-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-image-o:before { content: @fa-var-file-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-photo-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-photo-o:before { content: @fa-var-file-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-picture-o:before { content: @fa-var-file-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-archive-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-archive-o:before { content: @fa-var-file-archive; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-zip-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-zip-o:before { content: @fa-var-file-archive; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-audio-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-audio-o:before { content: @fa-var-file-audio; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-sound-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-sound-o:before { content: @fa-var-file-audio; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-video-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-video-o:before { content: @fa-var-file-video; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-movie-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-movie-o:before { content: @fa-var-file-video; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-code-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-code-o:before { content: @fa-var-file-code; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vine {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-codepen {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-jsfiddle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-ring {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-bouy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-life-bouy:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-buoy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-life-buoy:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-saver {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-life-saver:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-support {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-support:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-o-notch:before { content: @fa-var-circle-notch; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rebel {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ra {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-ra:before { content: @fa-var-rebel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-resistance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-resistance:before { content: @fa-var-rebel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-empire {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-ge:before { content: @fa-var-empire; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-git-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-git {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hacker-news {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-y-combinator-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-y-combinator-square:before { content: @fa-var-hacker-news; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yc-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-yc-square:before { content: @fa-var-hacker-news; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tencent-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-qq {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-weixin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wechat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-wechat:before { content: @fa-var-weixin; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-send:before { content: @fa-var-paper-plane; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-paper-plane-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-paper-plane-o:before { content: @fa-var-paper-plane; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-send-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-send-o:before { content: @fa-var-paper-plane; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-thin {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-thin:before { content: @fa-var-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-header:before { content: @fa-var-heading; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sliders:before { content: @fa-var-sliders-h; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-futbol-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-futbol-o:before { content: @fa-var-futbol; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-soccer-ball-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-soccer-ball-o:before { content: @fa-var-futbol; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-slideshare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-twitch {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yelp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-newspaper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-newspaper-o:before { content: @fa-var-newspaper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-wallet {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-visa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-mastercard {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-discover {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-amex {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-stripe {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-slash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-slash-o:before { content: @fa-var-bell-slash; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-trash:before { content: @fa-var-trash-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-copyright {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eyedropper:before { content: @fa-var-eye-dropper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-area-chart:before { content: @fa-var-chart-area; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pie-chart:before { content: @fa-var-chart-pie; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-line-chart:before { content: @fa-var-chart-line; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lastfm {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lastfm-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ioxhost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-angellist {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-cc:before { content: @fa-var-closed-captioning; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ils:before { content: @fa-var-shekel-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-shekel:before { content: @fa-var-shekel-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sheqel:before { content: @fa-var-shekel-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-meanpath {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-meanpath:before { content: @fa-var-font-awesome; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-buysellads {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-connectdevelop {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dashcube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-forumbee {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-leanpub {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sellsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-shirtsinbulk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-simplybuilt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-skyatlas {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-diamond {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-diamond:before { content: @fa-var-gem; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-intersex:before { content: @fa-var-transgender; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-official:before { content: @fa-var-facebook; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pinterest-p {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-whatsapp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hotel:before { content: @fa-var-bed; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-viacoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-medium {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-y-combinator {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-yc:before { content: @fa-var-y-combinator; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-optin-monster {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-opencart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-expeditedssl {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-4:before { content: @fa-var-battery-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery:before { content: @fa-var-battery-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-3:before { content: @fa-var-battery-three-quarters; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-2:before { content: @fa-var-battery-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-1:before { content: @fa-var-battery-quarter; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-0:before { content: @fa-var-battery-empty; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-object-group {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-object-ungroup {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sticky-note-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-sticky-note-o:before { content: @fa-var-sticky-note; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-jcb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-diners-club {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-clone {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-o:before { content: @fa-var-hourglass; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-1:before { content: @fa-var-hourglass-start; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-2:before { content: @fa-var-hourglass-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-3:before { content: @fa-var-hourglass-end; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-rock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-rock-o:before { content: @fa-var-hand-rock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-grab-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-grab-o:before { content: @fa-var-hand-rock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-paper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-paper-o:before { content: @fa-var-hand-paper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-stop-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-stop-o:before { content: @fa-var-hand-paper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-scissors-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-scissors-o:before { content: @fa-var-hand-scissors; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-lizard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-lizard-o:before { content: @fa-var-hand-lizard; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-spock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-spock-o:before { content: @fa-var-hand-spock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-pointer-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-pointer-o:before { content: @fa-var-hand-pointer; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-peace-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-peace-o:before { content: @fa-var-hand-peace; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-registered {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-creative-commons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gg-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tripadvisor {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-odnoklassniki {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-odnoklassniki-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-get-pocket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wikipedia-w {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-safari {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-chrome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-firefox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-opera {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-internet-explorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-television:before { content: @fa-var-tv; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-contao {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-500px {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-amazon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-plus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-plus-o:before { content: @fa-var-calendar-plus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-minus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-minus-o:before { content: @fa-var-calendar-minus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-times-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-times-o:before { content: @fa-var-calendar-times; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-check-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-check-o:before { content: @fa-var-calendar-check; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-map-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-map-o:before { content: @fa-var-map; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-commenting:before { content: @fa-var-comment-dots; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-commenting-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-commenting-o:before { content: @fa-var-comment-dots; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-houzz {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vimeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-vimeo:before { content: @fa-var-vimeo-v; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-black-tie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-fonticons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reddit-alien {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-edge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-credit-card-alt:before { content: @fa-var-credit-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-codiepie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-modx {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-fort-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-usb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-product-hunt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mixcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-scribd {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pause-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-pause-circle-o:before { content: @fa-var-pause-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stop-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-stop-circle-o:before { content: @fa-var-stop-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bluetooth {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bluetooth-b {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gitlab {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wpbeginner {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wpforms {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-envira {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wheelchair-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-wheelchair-alt:before { content: @fa-var-accessible-icon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-question-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-question-circle-o:before { content: @fa-var-question-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-volume-control-phone:before { content: @fa-var-phone-volume; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-asl-interpreting:before { content: @fa-var-american-sign-language-interpreting; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-deafness:before { content: @fa-var-deaf; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hard-of-hearing:before { content: @fa-var-deaf; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-glide {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-glide-g {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-signing:before { content: @fa-var-sign-language; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-viadeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-viadeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snapchat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snapchat-ghost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snapchat-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pied-piper {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-first-order {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yoast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-themeisle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-official:before { content: @fa-var-google-plus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-circle:before { content: @fa-var-google-plus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-font-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-fa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-fa:before { content: @fa-var-font-awesome; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-handshake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-handshake-o:before { content: @fa-var-handshake; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-open-o:before { content: @fa-var-envelope-open; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linode {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-address-book-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-address-book-o:before { content: @fa-var-address-book; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vcard:before { content: @fa-var-address-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-address-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-address-card-o:before { content: @fa-var-address-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vcard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-vcard-o:before { content: @fa-var-address-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-user-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-user-circle-o:before { content: @fa-var-user-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-user-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-user-o:before { content: @fa-var-user; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-id-badge {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-drivers-license:before { content: @fa-var-id-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-id-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-id-card-o:before { content: @fa-var-id-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-drivers-license-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-drivers-license-o:before { content: @fa-var-id-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-quora {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-free-code-camp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-telegram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-4:before { content: @fa-var-thermometer-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer:before { content: @fa-var-thermometer-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-3:before { content: @fa-var-thermometer-three-quarters; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-2:before { content: @fa-var-thermometer-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-1:before { content: @fa-var-thermometer-quarter; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-0:before { content: @fa-var-thermometer-empty; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bathtub:before { content: @fa-var-bath; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-s15:before { content: @fa-var-bath; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-window-maximize {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-window-restore {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-times-rectangle:before { content: @fa-var-window-close; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-window-close-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-window-close-o:before { content: @fa-var-window-close; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-times-rectangle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-times-rectangle-o:before { content: @fa-var-window-close; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bandcamp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-grav {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-etsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-imdb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ravelry {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eercast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-eercast:before { content: @fa-var-sellcast; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snowflake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-snowflake-o:before { content: @fa-var-snowflake; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-superpowers {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wpexplorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-spotify {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_stacked.less",
    "content": "// Stacked Icons\n// -------------------------\n\n.@{fa-css-prefix}-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: 2em;\n}\n\n.@{fa-css-prefix}-stack-1x, .@{fa-css-prefix}-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%;\n}\n\n.@{fa-css-prefix}-stack-1x { line-height: inherit; }\n.@{fa-css-prefix}-stack-2x { font-size: 2em; }\n.@{fa-css-prefix}-inverse { color: @fa-inverse; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_variables.less",
    "content": "// Variables\n// --------------------------\n\n@fa-font-path:         \"../webfonts\";\n@fa-font-size-base:    16px;\n@fa-font-display:      auto;\n@fa-line-height-base:  1;\n@fa-css-prefix:        fa;\n@fa-version:           \"5.10.2\";\n@fa-border-color:      #eee;\n@fa-inverse:           #fff;\n@fa-li-width:          2em;\n@fa-primary-opacity:   1;\n@fa-secondary-opacity: .4;\n\n@fa-var-500px: \"\\f26e\";\n@fa-var-accessible-icon: \"\\f368\";\n@fa-var-accusoft: \"\\f369\";\n@fa-var-acquisitions-incorporated: \"\\f6af\";\n@fa-var-ad: \"\\f641\";\n@fa-var-address-book: \"\\f2b9\";\n@fa-var-address-card: \"\\f2bb\";\n@fa-var-adjust: \"\\f042\";\n@fa-var-adn: \"\\f170\";\n@fa-var-adobe: \"\\f778\";\n@fa-var-adversal: \"\\f36a\";\n@fa-var-affiliatetheme: \"\\f36b\";\n@fa-var-air-freshener: \"\\f5d0\";\n@fa-var-airbnb: \"\\f834\";\n@fa-var-algolia: \"\\f36c\";\n@fa-var-align-center: \"\\f037\";\n@fa-var-align-justify: \"\\f039\";\n@fa-var-align-left: \"\\f036\";\n@fa-var-align-right: \"\\f038\";\n@fa-var-alipay: \"\\f642\";\n@fa-var-allergies: \"\\f461\";\n@fa-var-amazon: \"\\f270\";\n@fa-var-amazon-pay: \"\\f42c\";\n@fa-var-ambulance: \"\\f0f9\";\n@fa-var-american-sign-language-interpreting: \"\\f2a3\";\n@fa-var-amilia: \"\\f36d\";\n@fa-var-anchor: \"\\f13d\";\n@fa-var-android: \"\\f17b\";\n@fa-var-angellist: \"\\f209\";\n@fa-var-angle-double-down: \"\\f103\";\n@fa-var-angle-double-left: \"\\f100\";\n@fa-var-angle-double-right: \"\\f101\";\n@fa-var-angle-double-up: \"\\f102\";\n@fa-var-angle-down: \"\\f107\";\n@fa-var-angle-left: \"\\f104\";\n@fa-var-angle-right: \"\\f105\";\n@fa-var-angle-up: \"\\f106\";\n@fa-var-angry: \"\\f556\";\n@fa-var-angrycreative: \"\\f36e\";\n@fa-var-angular: \"\\f420\";\n@fa-var-ankh: \"\\f644\";\n@fa-var-app-store: \"\\f36f\";\n@fa-var-app-store-ios: \"\\f370\";\n@fa-var-apper: \"\\f371\";\n@fa-var-apple: \"\\f179\";\n@fa-var-apple-alt: \"\\f5d1\";\n@fa-var-apple-pay: \"\\f415\";\n@fa-var-archive: \"\\f187\";\n@fa-var-archway: \"\\f557\";\n@fa-var-arrow-alt-circle-down: \"\\f358\";\n@fa-var-arrow-alt-circle-left: \"\\f359\";\n@fa-var-arrow-alt-circle-right: \"\\f35a\";\n@fa-var-arrow-alt-circle-up: \"\\f35b\";\n@fa-var-arrow-circle-down: \"\\f0ab\";\n@fa-var-arrow-circle-left: \"\\f0a8\";\n@fa-var-arrow-circle-right: \"\\f0a9\";\n@fa-var-arrow-circle-up: \"\\f0aa\";\n@fa-var-arrow-down: \"\\f063\";\n@fa-var-arrow-left: \"\\f060\";\n@fa-var-arrow-right: \"\\f061\";\n@fa-var-arrow-up: \"\\f062\";\n@fa-var-arrows-alt: \"\\f0b2\";\n@fa-var-arrows-alt-h: \"\\f337\";\n@fa-var-arrows-alt-v: \"\\f338\";\n@fa-var-artstation: \"\\f77a\";\n@fa-var-assistive-listening-systems: \"\\f2a2\";\n@fa-var-asterisk: \"\\f069\";\n@fa-var-asymmetrik: \"\\f372\";\n@fa-var-at: \"\\f1fa\";\n@fa-var-atlas: \"\\f558\";\n@fa-var-atlassian: \"\\f77b\";\n@fa-var-atom: \"\\f5d2\";\n@fa-var-audible: \"\\f373\";\n@fa-var-audio-description: \"\\f29e\";\n@fa-var-autoprefixer: \"\\f41c\";\n@fa-var-avianex: \"\\f374\";\n@fa-var-aviato: \"\\f421\";\n@fa-var-award: \"\\f559\";\n@fa-var-aws: \"\\f375\";\n@fa-var-baby: \"\\f77c\";\n@fa-var-baby-carriage: \"\\f77d\";\n@fa-var-backspace: \"\\f55a\";\n@fa-var-backward: \"\\f04a\";\n@fa-var-bacon: \"\\f7e5\";\n@fa-var-balance-scale: \"\\f24e\";\n@fa-var-balance-scale-left: \"\\f515\";\n@fa-var-balance-scale-right: \"\\f516\";\n@fa-var-ban: \"\\f05e\";\n@fa-var-band-aid: \"\\f462\";\n@fa-var-bandcamp: \"\\f2d5\";\n@fa-var-barcode: \"\\f02a\";\n@fa-var-bars: \"\\f0c9\";\n@fa-var-baseball-ball: \"\\f433\";\n@fa-var-basketball-ball: \"\\f434\";\n@fa-var-bath: \"\\f2cd\";\n@fa-var-battery-empty: \"\\f244\";\n@fa-var-battery-full: \"\\f240\";\n@fa-var-battery-half: \"\\f242\";\n@fa-var-battery-quarter: \"\\f243\";\n@fa-var-battery-three-quarters: \"\\f241\";\n@fa-var-battle-net: \"\\f835\";\n@fa-var-bed: \"\\f236\";\n@fa-var-beer: \"\\f0fc\";\n@fa-var-behance: \"\\f1b4\";\n@fa-var-behance-square: \"\\f1b5\";\n@fa-var-bell: \"\\f0f3\";\n@fa-var-bell-slash: \"\\f1f6\";\n@fa-var-bezier-curve: \"\\f55b\";\n@fa-var-bible: \"\\f647\";\n@fa-var-bicycle: \"\\f206\";\n@fa-var-biking: \"\\f84a\";\n@fa-var-bimobject: \"\\f378\";\n@fa-var-binoculars: \"\\f1e5\";\n@fa-var-biohazard: \"\\f780\";\n@fa-var-birthday-cake: \"\\f1fd\";\n@fa-var-bitbucket: \"\\f171\";\n@fa-var-bitcoin: \"\\f379\";\n@fa-var-bity: \"\\f37a\";\n@fa-var-black-tie: \"\\f27e\";\n@fa-var-blackberry: \"\\f37b\";\n@fa-var-blender: \"\\f517\";\n@fa-var-blender-phone: \"\\f6b6\";\n@fa-var-blind: \"\\f29d\";\n@fa-var-blog: \"\\f781\";\n@fa-var-blogger: \"\\f37c\";\n@fa-var-blogger-b: \"\\f37d\";\n@fa-var-bluetooth: \"\\f293\";\n@fa-var-bluetooth-b: \"\\f294\";\n@fa-var-bold: \"\\f032\";\n@fa-var-bolt: \"\\f0e7\";\n@fa-var-bomb: \"\\f1e2\";\n@fa-var-bone: \"\\f5d7\";\n@fa-var-bong: \"\\f55c\";\n@fa-var-book: \"\\f02d\";\n@fa-var-book-dead: \"\\f6b7\";\n@fa-var-book-medical: \"\\f7e6\";\n@fa-var-book-open: \"\\f518\";\n@fa-var-book-reader: \"\\f5da\";\n@fa-var-bookmark: \"\\f02e\";\n@fa-var-bootstrap: \"\\f836\";\n@fa-var-border-all: \"\\f84c\";\n@fa-var-border-none: \"\\f850\";\n@fa-var-border-style: \"\\f853\";\n@fa-var-bowling-ball: \"\\f436\";\n@fa-var-box: \"\\f466\";\n@fa-var-box-open: \"\\f49e\";\n@fa-var-boxes: \"\\f468\";\n@fa-var-braille: \"\\f2a1\";\n@fa-var-brain: \"\\f5dc\";\n@fa-var-bread-slice: \"\\f7ec\";\n@fa-var-briefcase: \"\\f0b1\";\n@fa-var-briefcase-medical: \"\\f469\";\n@fa-var-broadcast-tower: \"\\f519\";\n@fa-var-broom: \"\\f51a\";\n@fa-var-brush: \"\\f55d\";\n@fa-var-btc: \"\\f15a\";\n@fa-var-buffer: \"\\f837\";\n@fa-var-bug: \"\\f188\";\n@fa-var-building: \"\\f1ad\";\n@fa-var-bullhorn: \"\\f0a1\";\n@fa-var-bullseye: \"\\f140\";\n@fa-var-burn: \"\\f46a\";\n@fa-var-buromobelexperte: \"\\f37f\";\n@fa-var-bus: \"\\f207\";\n@fa-var-bus-alt: \"\\f55e\";\n@fa-var-business-time: \"\\f64a\";\n@fa-var-buysellads: \"\\f20d\";\n@fa-var-calculator: \"\\f1ec\";\n@fa-var-calendar: \"\\f133\";\n@fa-var-calendar-alt: \"\\f073\";\n@fa-var-calendar-check: \"\\f274\";\n@fa-var-calendar-day: \"\\f783\";\n@fa-var-calendar-minus: \"\\f272\";\n@fa-var-calendar-plus: \"\\f271\";\n@fa-var-calendar-times: \"\\f273\";\n@fa-var-calendar-week: \"\\f784\";\n@fa-var-camera: \"\\f030\";\n@fa-var-camera-retro: \"\\f083\";\n@fa-var-campground: \"\\f6bb\";\n@fa-var-canadian-maple-leaf: \"\\f785\";\n@fa-var-candy-cane: \"\\f786\";\n@fa-var-cannabis: \"\\f55f\";\n@fa-var-capsules: \"\\f46b\";\n@fa-var-car: \"\\f1b9\";\n@fa-var-car-alt: \"\\f5de\";\n@fa-var-car-battery: \"\\f5df\";\n@fa-var-car-crash: \"\\f5e1\";\n@fa-var-car-side: \"\\f5e4\";\n@fa-var-caret-down: \"\\f0d7\";\n@fa-var-caret-left: \"\\f0d9\";\n@fa-var-caret-right: \"\\f0da\";\n@fa-var-caret-square-down: \"\\f150\";\n@fa-var-caret-square-left: \"\\f191\";\n@fa-var-caret-square-right: \"\\f152\";\n@fa-var-caret-square-up: \"\\f151\";\n@fa-var-caret-up: \"\\f0d8\";\n@fa-var-carrot: \"\\f787\";\n@fa-var-cart-arrow-down: \"\\f218\";\n@fa-var-cart-plus: \"\\f217\";\n@fa-var-cash-register: \"\\f788\";\n@fa-var-cat: \"\\f6be\";\n@fa-var-cc-amazon-pay: \"\\f42d\";\n@fa-var-cc-amex: \"\\f1f3\";\n@fa-var-cc-apple-pay: \"\\f416\";\n@fa-var-cc-diners-club: \"\\f24c\";\n@fa-var-cc-discover: \"\\f1f2\";\n@fa-var-cc-jcb: \"\\f24b\";\n@fa-var-cc-mastercard: \"\\f1f1\";\n@fa-var-cc-paypal: \"\\f1f4\";\n@fa-var-cc-stripe: \"\\f1f5\";\n@fa-var-cc-visa: \"\\f1f0\";\n@fa-var-centercode: \"\\f380\";\n@fa-var-centos: \"\\f789\";\n@fa-var-certificate: \"\\f0a3\";\n@fa-var-chair: \"\\f6c0\";\n@fa-var-chalkboard: \"\\f51b\";\n@fa-var-chalkboard-teacher: \"\\f51c\";\n@fa-var-charging-station: \"\\f5e7\";\n@fa-var-chart-area: \"\\f1fe\";\n@fa-var-chart-bar: \"\\f080\";\n@fa-var-chart-line: \"\\f201\";\n@fa-var-chart-pie: \"\\f200\";\n@fa-var-check: \"\\f00c\";\n@fa-var-check-circle: \"\\f058\";\n@fa-var-check-double: \"\\f560\";\n@fa-var-check-square: \"\\f14a\";\n@fa-var-cheese: \"\\f7ef\";\n@fa-var-chess: \"\\f439\";\n@fa-var-chess-bishop: \"\\f43a\";\n@fa-var-chess-board: \"\\f43c\";\n@fa-var-chess-king: \"\\f43f\";\n@fa-var-chess-knight: \"\\f441\";\n@fa-var-chess-pawn: \"\\f443\";\n@fa-var-chess-queen: \"\\f445\";\n@fa-var-chess-rook: \"\\f447\";\n@fa-var-chevron-circle-down: \"\\f13a\";\n@fa-var-chevron-circle-left: \"\\f137\";\n@fa-var-chevron-circle-right: \"\\f138\";\n@fa-var-chevron-circle-up: \"\\f139\";\n@fa-var-chevron-down: \"\\f078\";\n@fa-var-chevron-left: \"\\f053\";\n@fa-var-chevron-right: \"\\f054\";\n@fa-var-chevron-up: \"\\f077\";\n@fa-var-child: \"\\f1ae\";\n@fa-var-chrome: \"\\f268\";\n@fa-var-chromecast: \"\\f838\";\n@fa-var-church: \"\\f51d\";\n@fa-var-circle: \"\\f111\";\n@fa-var-circle-notch: \"\\f1ce\";\n@fa-var-city: \"\\f64f\";\n@fa-var-clinic-medical: \"\\f7f2\";\n@fa-var-clipboard: \"\\f328\";\n@fa-var-clipboard-check: \"\\f46c\";\n@fa-var-clipboard-list: \"\\f46d\";\n@fa-var-clock: \"\\f017\";\n@fa-var-clone: \"\\f24d\";\n@fa-var-closed-captioning: \"\\f20a\";\n@fa-var-cloud: \"\\f0c2\";\n@fa-var-cloud-download-alt: \"\\f381\";\n@fa-var-cloud-meatball: \"\\f73b\";\n@fa-var-cloud-moon: \"\\f6c3\";\n@fa-var-cloud-moon-rain: \"\\f73c\";\n@fa-var-cloud-rain: \"\\f73d\";\n@fa-var-cloud-showers-heavy: \"\\f740\";\n@fa-var-cloud-sun: \"\\f6c4\";\n@fa-var-cloud-sun-rain: \"\\f743\";\n@fa-var-cloud-upload-alt: \"\\f382\";\n@fa-var-cloudscale: \"\\f383\";\n@fa-var-cloudsmith: \"\\f384\";\n@fa-var-cloudversify: \"\\f385\";\n@fa-var-cocktail: \"\\f561\";\n@fa-var-code: \"\\f121\";\n@fa-var-code-branch: \"\\f126\";\n@fa-var-codepen: \"\\f1cb\";\n@fa-var-codiepie: \"\\f284\";\n@fa-var-coffee: \"\\f0f4\";\n@fa-var-cog: \"\\f013\";\n@fa-var-cogs: \"\\f085\";\n@fa-var-coins: \"\\f51e\";\n@fa-var-columns: \"\\f0db\";\n@fa-var-comment: \"\\f075\";\n@fa-var-comment-alt: \"\\f27a\";\n@fa-var-comment-dollar: \"\\f651\";\n@fa-var-comment-dots: \"\\f4ad\";\n@fa-var-comment-medical: \"\\f7f5\";\n@fa-var-comment-slash: \"\\f4b3\";\n@fa-var-comments: \"\\f086\";\n@fa-var-comments-dollar: \"\\f653\";\n@fa-var-compact-disc: \"\\f51f\";\n@fa-var-compass: \"\\f14e\";\n@fa-var-compress: \"\\f066\";\n@fa-var-compress-arrows-alt: \"\\f78c\";\n@fa-var-concierge-bell: \"\\f562\";\n@fa-var-confluence: \"\\f78d\";\n@fa-var-connectdevelop: \"\\f20e\";\n@fa-var-contao: \"\\f26d\";\n@fa-var-cookie: \"\\f563\";\n@fa-var-cookie-bite: \"\\f564\";\n@fa-var-copy: \"\\f0c5\";\n@fa-var-copyright: \"\\f1f9\";\n@fa-var-cotton-bureau: \"\\f89e\";\n@fa-var-couch: \"\\f4b8\";\n@fa-var-cpanel: \"\\f388\";\n@fa-var-creative-commons: \"\\f25e\";\n@fa-var-creative-commons-by: \"\\f4e7\";\n@fa-var-creative-commons-nc: \"\\f4e8\";\n@fa-var-creative-commons-nc-eu: \"\\f4e9\";\n@fa-var-creative-commons-nc-jp: \"\\f4ea\";\n@fa-var-creative-commons-nd: \"\\f4eb\";\n@fa-var-creative-commons-pd: \"\\f4ec\";\n@fa-var-creative-commons-pd-alt: \"\\f4ed\";\n@fa-var-creative-commons-remix: \"\\f4ee\";\n@fa-var-creative-commons-sa: \"\\f4ef\";\n@fa-var-creative-commons-sampling: \"\\f4f0\";\n@fa-var-creative-commons-sampling-plus: \"\\f4f1\";\n@fa-var-creative-commons-share: \"\\f4f2\";\n@fa-var-creative-commons-zero: \"\\f4f3\";\n@fa-var-credit-card: \"\\f09d\";\n@fa-var-critical-role: \"\\f6c9\";\n@fa-var-crop: \"\\f125\";\n@fa-var-crop-alt: \"\\f565\";\n@fa-var-cross: \"\\f654\";\n@fa-var-crosshairs: \"\\f05b\";\n@fa-var-crow: \"\\f520\";\n@fa-var-crown: \"\\f521\";\n@fa-var-crutch: \"\\f7f7\";\n@fa-var-css3: \"\\f13c\";\n@fa-var-css3-alt: \"\\f38b\";\n@fa-var-cube: \"\\f1b2\";\n@fa-var-cubes: \"\\f1b3\";\n@fa-var-cut: \"\\f0c4\";\n@fa-var-cuttlefish: \"\\f38c\";\n@fa-var-d-and-d: \"\\f38d\";\n@fa-var-d-and-d-beyond: \"\\f6ca\";\n@fa-var-dashcube: \"\\f210\";\n@fa-var-database: \"\\f1c0\";\n@fa-var-deaf: \"\\f2a4\";\n@fa-var-delicious: \"\\f1a5\";\n@fa-var-democrat: \"\\f747\";\n@fa-var-deploydog: \"\\f38e\";\n@fa-var-deskpro: \"\\f38f\";\n@fa-var-desktop: \"\\f108\";\n@fa-var-dev: \"\\f6cc\";\n@fa-var-deviantart: \"\\f1bd\";\n@fa-var-dharmachakra: \"\\f655\";\n@fa-var-dhl: \"\\f790\";\n@fa-var-diagnoses: \"\\f470\";\n@fa-var-diaspora: \"\\f791\";\n@fa-var-dice: \"\\f522\";\n@fa-var-dice-d20: \"\\f6cf\";\n@fa-var-dice-d6: \"\\f6d1\";\n@fa-var-dice-five: \"\\f523\";\n@fa-var-dice-four: \"\\f524\";\n@fa-var-dice-one: \"\\f525\";\n@fa-var-dice-six: \"\\f526\";\n@fa-var-dice-three: \"\\f527\";\n@fa-var-dice-two: \"\\f528\";\n@fa-var-digg: \"\\f1a6\";\n@fa-var-digital-ocean: \"\\f391\";\n@fa-var-digital-tachograph: \"\\f566\";\n@fa-var-directions: \"\\f5eb\";\n@fa-var-discord: \"\\f392\";\n@fa-var-discourse: \"\\f393\";\n@fa-var-divide: \"\\f529\";\n@fa-var-dizzy: \"\\f567\";\n@fa-var-dna: \"\\f471\";\n@fa-var-dochub: \"\\f394\";\n@fa-var-docker: \"\\f395\";\n@fa-var-dog: \"\\f6d3\";\n@fa-var-dollar-sign: \"\\f155\";\n@fa-var-dolly: \"\\f472\";\n@fa-var-dolly-flatbed: \"\\f474\";\n@fa-var-donate: \"\\f4b9\";\n@fa-var-door-closed: \"\\f52a\";\n@fa-var-door-open: \"\\f52b\";\n@fa-var-dot-circle: \"\\f192\";\n@fa-var-dove: \"\\f4ba\";\n@fa-var-download: \"\\f019\";\n@fa-var-draft2digital: \"\\f396\";\n@fa-var-drafting-compass: \"\\f568\";\n@fa-var-dragon: \"\\f6d5\";\n@fa-var-draw-polygon: \"\\f5ee\";\n@fa-var-dribbble: \"\\f17d\";\n@fa-var-dribbble-square: \"\\f397\";\n@fa-var-dropbox: \"\\f16b\";\n@fa-var-drum: \"\\f569\";\n@fa-var-drum-steelpan: \"\\f56a\";\n@fa-var-drumstick-bite: \"\\f6d7\";\n@fa-var-drupal: \"\\f1a9\";\n@fa-var-dumbbell: \"\\f44b\";\n@fa-var-dumpster: \"\\f793\";\n@fa-var-dumpster-fire: \"\\f794\";\n@fa-var-dungeon: \"\\f6d9\";\n@fa-var-dyalog: \"\\f399\";\n@fa-var-earlybirds: \"\\f39a\";\n@fa-var-ebay: \"\\f4f4\";\n@fa-var-edge: \"\\f282\";\n@fa-var-edit: \"\\f044\";\n@fa-var-egg: \"\\f7fb\";\n@fa-var-eject: \"\\f052\";\n@fa-var-elementor: \"\\f430\";\n@fa-var-ellipsis-h: \"\\f141\";\n@fa-var-ellipsis-v: \"\\f142\";\n@fa-var-ello: \"\\f5f1\";\n@fa-var-ember: \"\\f423\";\n@fa-var-empire: \"\\f1d1\";\n@fa-var-envelope: \"\\f0e0\";\n@fa-var-envelope-open: \"\\f2b6\";\n@fa-var-envelope-open-text: \"\\f658\";\n@fa-var-envelope-square: \"\\f199\";\n@fa-var-envira: \"\\f299\";\n@fa-var-equals: \"\\f52c\";\n@fa-var-eraser: \"\\f12d\";\n@fa-var-erlang: \"\\f39d\";\n@fa-var-ethereum: \"\\f42e\";\n@fa-var-ethernet: \"\\f796\";\n@fa-var-etsy: \"\\f2d7\";\n@fa-var-euro-sign: \"\\f153\";\n@fa-var-evernote: \"\\f839\";\n@fa-var-exchange-alt: \"\\f362\";\n@fa-var-exclamation: \"\\f12a\";\n@fa-var-exclamation-circle: \"\\f06a\";\n@fa-var-exclamation-triangle: \"\\f071\";\n@fa-var-expand: \"\\f065\";\n@fa-var-expand-arrows-alt: \"\\f31e\";\n@fa-var-expeditedssl: \"\\f23e\";\n@fa-var-external-link-alt: \"\\f35d\";\n@fa-var-external-link-square-alt: \"\\f360\";\n@fa-var-eye: \"\\f06e\";\n@fa-var-eye-dropper: \"\\f1fb\";\n@fa-var-eye-slash: \"\\f070\";\n@fa-var-facebook: \"\\f09a\";\n@fa-var-facebook-f: \"\\f39e\";\n@fa-var-facebook-messenger: \"\\f39f\";\n@fa-var-facebook-square: \"\\f082\";\n@fa-var-fan: \"\\f863\";\n@fa-var-fantasy-flight-games: \"\\f6dc\";\n@fa-var-fast-backward: \"\\f049\";\n@fa-var-fast-forward: \"\\f050\";\n@fa-var-fax: \"\\f1ac\";\n@fa-var-feather: \"\\f52d\";\n@fa-var-feather-alt: \"\\f56b\";\n@fa-var-fedex: \"\\f797\";\n@fa-var-fedora: \"\\f798\";\n@fa-var-female: \"\\f182\";\n@fa-var-fighter-jet: \"\\f0fb\";\n@fa-var-figma: \"\\f799\";\n@fa-var-file: \"\\f15b\";\n@fa-var-file-alt: \"\\f15c\";\n@fa-var-file-archive: \"\\f1c6\";\n@fa-var-file-audio: \"\\f1c7\";\n@fa-var-file-code: \"\\f1c9\";\n@fa-var-file-contract: \"\\f56c\";\n@fa-var-file-csv: \"\\f6dd\";\n@fa-var-file-download: \"\\f56d\";\n@fa-var-file-excel: \"\\f1c3\";\n@fa-var-file-export: \"\\f56e\";\n@fa-var-file-image: \"\\f1c5\";\n@fa-var-file-import: \"\\f56f\";\n@fa-var-file-invoice: \"\\f570\";\n@fa-var-file-invoice-dollar: \"\\f571\";\n@fa-var-file-medical: \"\\f477\";\n@fa-var-file-medical-alt: \"\\f478\";\n@fa-var-file-pdf: \"\\f1c1\";\n@fa-var-file-powerpoint: \"\\f1c4\";\n@fa-var-file-prescription: \"\\f572\";\n@fa-var-file-signature: \"\\f573\";\n@fa-var-file-upload: \"\\f574\";\n@fa-var-file-video: \"\\f1c8\";\n@fa-var-file-word: \"\\f1c2\";\n@fa-var-fill: \"\\f575\";\n@fa-var-fill-drip: \"\\f576\";\n@fa-var-film: \"\\f008\";\n@fa-var-filter: \"\\f0b0\";\n@fa-var-fingerprint: \"\\f577\";\n@fa-var-fire: \"\\f06d\";\n@fa-var-fire-alt: \"\\f7e4\";\n@fa-var-fire-extinguisher: \"\\f134\";\n@fa-var-firefox: \"\\f269\";\n@fa-var-first-aid: \"\\f479\";\n@fa-var-first-order: \"\\f2b0\";\n@fa-var-first-order-alt: \"\\f50a\";\n@fa-var-firstdraft: \"\\f3a1\";\n@fa-var-fish: \"\\f578\";\n@fa-var-fist-raised: \"\\f6de\";\n@fa-var-flag: \"\\f024\";\n@fa-var-flag-checkered: \"\\f11e\";\n@fa-var-flag-usa: \"\\f74d\";\n@fa-var-flask: \"\\f0c3\";\n@fa-var-flickr: \"\\f16e\";\n@fa-var-flipboard: \"\\f44d\";\n@fa-var-flushed: \"\\f579\";\n@fa-var-fly: \"\\f417\";\n@fa-var-folder: \"\\f07b\";\n@fa-var-folder-minus: \"\\f65d\";\n@fa-var-folder-open: \"\\f07c\";\n@fa-var-folder-plus: \"\\f65e\";\n@fa-var-font: \"\\f031\";\n@fa-var-font-awesome: \"\\f2b4\";\n@fa-var-font-awesome-alt: \"\\f35c\";\n@fa-var-font-awesome-flag: \"\\f425\";\n@fa-var-font-awesome-logo-full: \"\\f4e6\";\n@fa-var-fonticons: \"\\f280\";\n@fa-var-fonticons-fi: \"\\f3a2\";\n@fa-var-football-ball: \"\\f44e\";\n@fa-var-fort-awesome: \"\\f286\";\n@fa-var-fort-awesome-alt: \"\\f3a3\";\n@fa-var-forumbee: \"\\f211\";\n@fa-var-forward: \"\\f04e\";\n@fa-var-foursquare: \"\\f180\";\n@fa-var-free-code-camp: \"\\f2c5\";\n@fa-var-freebsd: \"\\f3a4\";\n@fa-var-frog: \"\\f52e\";\n@fa-var-frown: \"\\f119\";\n@fa-var-frown-open: \"\\f57a\";\n@fa-var-fulcrum: \"\\f50b\";\n@fa-var-funnel-dollar: \"\\f662\";\n@fa-var-futbol: \"\\f1e3\";\n@fa-var-galactic-republic: \"\\f50c\";\n@fa-var-galactic-senate: \"\\f50d\";\n@fa-var-gamepad: \"\\f11b\";\n@fa-var-gas-pump: \"\\f52f\";\n@fa-var-gavel: \"\\f0e3\";\n@fa-var-gem: \"\\f3a5\";\n@fa-var-genderless: \"\\f22d\";\n@fa-var-get-pocket: \"\\f265\";\n@fa-var-gg: \"\\f260\";\n@fa-var-gg-circle: \"\\f261\";\n@fa-var-ghost: \"\\f6e2\";\n@fa-var-gift: \"\\f06b\";\n@fa-var-gifts: \"\\f79c\";\n@fa-var-git: \"\\f1d3\";\n@fa-var-git-alt: \"\\f841\";\n@fa-var-git-square: \"\\f1d2\";\n@fa-var-github: \"\\f09b\";\n@fa-var-github-alt: \"\\f113\";\n@fa-var-github-square: \"\\f092\";\n@fa-var-gitkraken: \"\\f3a6\";\n@fa-var-gitlab: \"\\f296\";\n@fa-var-gitter: \"\\f426\";\n@fa-var-glass-cheers: \"\\f79f\";\n@fa-var-glass-martini: \"\\f000\";\n@fa-var-glass-martini-alt: \"\\f57b\";\n@fa-var-glass-whiskey: \"\\f7a0\";\n@fa-var-glasses: \"\\f530\";\n@fa-var-glide: \"\\f2a5\";\n@fa-var-glide-g: \"\\f2a6\";\n@fa-var-globe: \"\\f0ac\";\n@fa-var-globe-africa: \"\\f57c\";\n@fa-var-globe-americas: \"\\f57d\";\n@fa-var-globe-asia: \"\\f57e\";\n@fa-var-globe-europe: \"\\f7a2\";\n@fa-var-gofore: \"\\f3a7\";\n@fa-var-golf-ball: \"\\f450\";\n@fa-var-goodreads: \"\\f3a8\";\n@fa-var-goodreads-g: \"\\f3a9\";\n@fa-var-google: \"\\f1a0\";\n@fa-var-google-drive: \"\\f3aa\";\n@fa-var-google-play: \"\\f3ab\";\n@fa-var-google-plus: \"\\f2b3\";\n@fa-var-google-plus-g: \"\\f0d5\";\n@fa-var-google-plus-square: \"\\f0d4\";\n@fa-var-google-wallet: \"\\f1ee\";\n@fa-var-gopuram: \"\\f664\";\n@fa-var-graduation-cap: \"\\f19d\";\n@fa-var-gratipay: \"\\f184\";\n@fa-var-grav: \"\\f2d6\";\n@fa-var-greater-than: \"\\f531\";\n@fa-var-greater-than-equal: \"\\f532\";\n@fa-var-grimace: \"\\f57f\";\n@fa-var-grin: \"\\f580\";\n@fa-var-grin-alt: \"\\f581\";\n@fa-var-grin-beam: \"\\f582\";\n@fa-var-grin-beam-sweat: \"\\f583\";\n@fa-var-grin-hearts: \"\\f584\";\n@fa-var-grin-squint: \"\\f585\";\n@fa-var-grin-squint-tears: \"\\f586\";\n@fa-var-grin-stars: \"\\f587\";\n@fa-var-grin-tears: \"\\f588\";\n@fa-var-grin-tongue: \"\\f589\";\n@fa-var-grin-tongue-squint: \"\\f58a\";\n@fa-var-grin-tongue-wink: \"\\f58b\";\n@fa-var-grin-wink: \"\\f58c\";\n@fa-var-grip-horizontal: \"\\f58d\";\n@fa-var-grip-lines: \"\\f7a4\";\n@fa-var-grip-lines-vertical: \"\\f7a5\";\n@fa-var-grip-vertical: \"\\f58e\";\n@fa-var-gripfire: \"\\f3ac\";\n@fa-var-grunt: \"\\f3ad\";\n@fa-var-guitar: \"\\f7a6\";\n@fa-var-gulp: \"\\f3ae\";\n@fa-var-h-square: \"\\f0fd\";\n@fa-var-hacker-news: \"\\f1d4\";\n@fa-var-hacker-news-square: \"\\f3af\";\n@fa-var-hackerrank: \"\\f5f7\";\n@fa-var-hamburger: \"\\f805\";\n@fa-var-hammer: \"\\f6e3\";\n@fa-var-hamsa: \"\\f665\";\n@fa-var-hand-holding: \"\\f4bd\";\n@fa-var-hand-holding-heart: \"\\f4be\";\n@fa-var-hand-holding-usd: \"\\f4c0\";\n@fa-var-hand-lizard: \"\\f258\";\n@fa-var-hand-middle-finger: \"\\f806\";\n@fa-var-hand-paper: \"\\f256\";\n@fa-var-hand-peace: \"\\f25b\";\n@fa-var-hand-point-down: \"\\f0a7\";\n@fa-var-hand-point-left: \"\\f0a5\";\n@fa-var-hand-point-right: \"\\f0a4\";\n@fa-var-hand-point-up: \"\\f0a6\";\n@fa-var-hand-pointer: \"\\f25a\";\n@fa-var-hand-rock: \"\\f255\";\n@fa-var-hand-scissors: \"\\f257\";\n@fa-var-hand-spock: \"\\f259\";\n@fa-var-hands: \"\\f4c2\";\n@fa-var-hands-helping: \"\\f4c4\";\n@fa-var-handshake: \"\\f2b5\";\n@fa-var-hanukiah: \"\\f6e6\";\n@fa-var-hard-hat: \"\\f807\";\n@fa-var-hashtag: \"\\f292\";\n@fa-var-hat-wizard: \"\\f6e8\";\n@fa-var-haykal: \"\\f666\";\n@fa-var-hdd: \"\\f0a0\";\n@fa-var-heading: \"\\f1dc\";\n@fa-var-headphones: \"\\f025\";\n@fa-var-headphones-alt: \"\\f58f\";\n@fa-var-headset: \"\\f590\";\n@fa-var-heart: \"\\f004\";\n@fa-var-heart-broken: \"\\f7a9\";\n@fa-var-heartbeat: \"\\f21e\";\n@fa-var-helicopter: \"\\f533\";\n@fa-var-highlighter: \"\\f591\";\n@fa-var-hiking: \"\\f6ec\";\n@fa-var-hippo: \"\\f6ed\";\n@fa-var-hips: \"\\f452\";\n@fa-var-hire-a-helper: \"\\f3b0\";\n@fa-var-history: \"\\f1da\";\n@fa-var-hockey-puck: \"\\f453\";\n@fa-var-holly-berry: \"\\f7aa\";\n@fa-var-home: \"\\f015\";\n@fa-var-hooli: \"\\f427\";\n@fa-var-hornbill: \"\\f592\";\n@fa-var-horse: \"\\f6f0\";\n@fa-var-horse-head: \"\\f7ab\";\n@fa-var-hospital: \"\\f0f8\";\n@fa-var-hospital-alt: \"\\f47d\";\n@fa-var-hospital-symbol: \"\\f47e\";\n@fa-var-hot-tub: \"\\f593\";\n@fa-var-hotdog: \"\\f80f\";\n@fa-var-hotel: \"\\f594\";\n@fa-var-hotjar: \"\\f3b1\";\n@fa-var-hourglass: \"\\f254\";\n@fa-var-hourglass-end: \"\\f253\";\n@fa-var-hourglass-half: \"\\f252\";\n@fa-var-hourglass-start: \"\\f251\";\n@fa-var-house-damage: \"\\f6f1\";\n@fa-var-houzz: \"\\f27c\";\n@fa-var-hryvnia: \"\\f6f2\";\n@fa-var-html5: \"\\f13b\";\n@fa-var-hubspot: \"\\f3b2\";\n@fa-var-i-cursor: \"\\f246\";\n@fa-var-ice-cream: \"\\f810\";\n@fa-var-icicles: \"\\f7ad\";\n@fa-var-icons: \"\\f86d\";\n@fa-var-id-badge: \"\\f2c1\";\n@fa-var-id-card: \"\\f2c2\";\n@fa-var-id-card-alt: \"\\f47f\";\n@fa-var-igloo: \"\\f7ae\";\n@fa-var-image: \"\\f03e\";\n@fa-var-images: \"\\f302\";\n@fa-var-imdb: \"\\f2d8\";\n@fa-var-inbox: \"\\f01c\";\n@fa-var-indent: \"\\f03c\";\n@fa-var-industry: \"\\f275\";\n@fa-var-infinity: \"\\f534\";\n@fa-var-info: \"\\f129\";\n@fa-var-info-circle: \"\\f05a\";\n@fa-var-instagram: \"\\f16d\";\n@fa-var-intercom: \"\\f7af\";\n@fa-var-internet-explorer: \"\\f26b\";\n@fa-var-invision: \"\\f7b0\";\n@fa-var-ioxhost: \"\\f208\";\n@fa-var-italic: \"\\f033\";\n@fa-var-itch-io: \"\\f83a\";\n@fa-var-itunes: \"\\f3b4\";\n@fa-var-itunes-note: \"\\f3b5\";\n@fa-var-java: \"\\f4e4\";\n@fa-var-jedi: \"\\f669\";\n@fa-var-jedi-order: \"\\f50e\";\n@fa-var-jenkins: \"\\f3b6\";\n@fa-var-jira: \"\\f7b1\";\n@fa-var-joget: \"\\f3b7\";\n@fa-var-joint: \"\\f595\";\n@fa-var-joomla: \"\\f1aa\";\n@fa-var-journal-whills: \"\\f66a\";\n@fa-var-js: \"\\f3b8\";\n@fa-var-js-square: \"\\f3b9\";\n@fa-var-jsfiddle: \"\\f1cc\";\n@fa-var-kaaba: \"\\f66b\";\n@fa-var-kaggle: \"\\f5fa\";\n@fa-var-key: \"\\f084\";\n@fa-var-keybase: \"\\f4f5\";\n@fa-var-keyboard: \"\\f11c\";\n@fa-var-keycdn: \"\\f3ba\";\n@fa-var-khanda: \"\\f66d\";\n@fa-var-kickstarter: \"\\f3bb\";\n@fa-var-kickstarter-k: \"\\f3bc\";\n@fa-var-kiss: \"\\f596\";\n@fa-var-kiss-beam: \"\\f597\";\n@fa-var-kiss-wink-heart: \"\\f598\";\n@fa-var-kiwi-bird: \"\\f535\";\n@fa-var-korvue: \"\\f42f\";\n@fa-var-landmark: \"\\f66f\";\n@fa-var-language: \"\\f1ab\";\n@fa-var-laptop: \"\\f109\";\n@fa-var-laptop-code: \"\\f5fc\";\n@fa-var-laptop-medical: \"\\f812\";\n@fa-var-laravel: \"\\f3bd\";\n@fa-var-lastfm: \"\\f202\";\n@fa-var-lastfm-square: \"\\f203\";\n@fa-var-laugh: \"\\f599\";\n@fa-var-laugh-beam: \"\\f59a\";\n@fa-var-laugh-squint: \"\\f59b\";\n@fa-var-laugh-wink: \"\\f59c\";\n@fa-var-layer-group: \"\\f5fd\";\n@fa-var-leaf: \"\\f06c\";\n@fa-var-leanpub: \"\\f212\";\n@fa-var-lemon: \"\\f094\";\n@fa-var-less: \"\\f41d\";\n@fa-var-less-than: \"\\f536\";\n@fa-var-less-than-equal: \"\\f537\";\n@fa-var-level-down-alt: \"\\f3be\";\n@fa-var-level-up-alt: \"\\f3bf\";\n@fa-var-life-ring: \"\\f1cd\";\n@fa-var-lightbulb: \"\\f0eb\";\n@fa-var-line: \"\\f3c0\";\n@fa-var-link: \"\\f0c1\";\n@fa-var-linkedin: \"\\f08c\";\n@fa-var-linkedin-in: \"\\f0e1\";\n@fa-var-linode: \"\\f2b8\";\n@fa-var-linux: \"\\f17c\";\n@fa-var-lira-sign: \"\\f195\";\n@fa-var-list: \"\\f03a\";\n@fa-var-list-alt: \"\\f022\";\n@fa-var-list-ol: \"\\f0cb\";\n@fa-var-list-ul: \"\\f0ca\";\n@fa-var-location-arrow: \"\\f124\";\n@fa-var-lock: \"\\f023\";\n@fa-var-lock-open: \"\\f3c1\";\n@fa-var-long-arrow-alt-down: \"\\f309\";\n@fa-var-long-arrow-alt-left: \"\\f30a\";\n@fa-var-long-arrow-alt-right: \"\\f30b\";\n@fa-var-long-arrow-alt-up: \"\\f30c\";\n@fa-var-low-vision: \"\\f2a8\";\n@fa-var-luggage-cart: \"\\f59d\";\n@fa-var-lyft: \"\\f3c3\";\n@fa-var-magento: \"\\f3c4\";\n@fa-var-magic: \"\\f0d0\";\n@fa-var-magnet: \"\\f076\";\n@fa-var-mail-bulk: \"\\f674\";\n@fa-var-mailchimp: \"\\f59e\";\n@fa-var-male: \"\\f183\";\n@fa-var-mandalorian: \"\\f50f\";\n@fa-var-map: \"\\f279\";\n@fa-var-map-marked: \"\\f59f\";\n@fa-var-map-marked-alt: \"\\f5a0\";\n@fa-var-map-marker: \"\\f041\";\n@fa-var-map-marker-alt: \"\\f3c5\";\n@fa-var-map-pin: \"\\f276\";\n@fa-var-map-signs: \"\\f277\";\n@fa-var-markdown: \"\\f60f\";\n@fa-var-marker: \"\\f5a1\";\n@fa-var-mars: \"\\f222\";\n@fa-var-mars-double: \"\\f227\";\n@fa-var-mars-stroke: \"\\f229\";\n@fa-var-mars-stroke-h: \"\\f22b\";\n@fa-var-mars-stroke-v: \"\\f22a\";\n@fa-var-mask: \"\\f6fa\";\n@fa-var-mastodon: \"\\f4f6\";\n@fa-var-maxcdn: \"\\f136\";\n@fa-var-medal: \"\\f5a2\";\n@fa-var-medapps: \"\\f3c6\";\n@fa-var-medium: \"\\f23a\";\n@fa-var-medium-m: \"\\f3c7\";\n@fa-var-medkit: \"\\f0fa\";\n@fa-var-medrt: \"\\f3c8\";\n@fa-var-meetup: \"\\f2e0\";\n@fa-var-megaport: \"\\f5a3\";\n@fa-var-meh: \"\\f11a\";\n@fa-var-meh-blank: \"\\f5a4\";\n@fa-var-meh-rolling-eyes: \"\\f5a5\";\n@fa-var-memory: \"\\f538\";\n@fa-var-mendeley: \"\\f7b3\";\n@fa-var-menorah: \"\\f676\";\n@fa-var-mercury: \"\\f223\";\n@fa-var-meteor: \"\\f753\";\n@fa-var-microchip: \"\\f2db\";\n@fa-var-microphone: \"\\f130\";\n@fa-var-microphone-alt: \"\\f3c9\";\n@fa-var-microphone-alt-slash: \"\\f539\";\n@fa-var-microphone-slash: \"\\f131\";\n@fa-var-microscope: \"\\f610\";\n@fa-var-microsoft: \"\\f3ca\";\n@fa-var-minus: \"\\f068\";\n@fa-var-minus-circle: \"\\f056\";\n@fa-var-minus-square: \"\\f146\";\n@fa-var-mitten: \"\\f7b5\";\n@fa-var-mix: \"\\f3cb\";\n@fa-var-mixcloud: \"\\f289\";\n@fa-var-mizuni: \"\\f3cc\";\n@fa-var-mobile: \"\\f10b\";\n@fa-var-mobile-alt: \"\\f3cd\";\n@fa-var-modx: \"\\f285\";\n@fa-var-monero: \"\\f3d0\";\n@fa-var-money-bill: \"\\f0d6\";\n@fa-var-money-bill-alt: \"\\f3d1\";\n@fa-var-money-bill-wave: \"\\f53a\";\n@fa-var-money-bill-wave-alt: \"\\f53b\";\n@fa-var-money-check: \"\\f53c\";\n@fa-var-money-check-alt: \"\\f53d\";\n@fa-var-monument: \"\\f5a6\";\n@fa-var-moon: \"\\f186\";\n@fa-var-mortar-pestle: \"\\f5a7\";\n@fa-var-mosque: \"\\f678\";\n@fa-var-motorcycle: \"\\f21c\";\n@fa-var-mountain: \"\\f6fc\";\n@fa-var-mouse-pointer: \"\\f245\";\n@fa-var-mug-hot: \"\\f7b6\";\n@fa-var-music: \"\\f001\";\n@fa-var-napster: \"\\f3d2\";\n@fa-var-neos: \"\\f612\";\n@fa-var-network-wired: \"\\f6ff\";\n@fa-var-neuter: \"\\f22c\";\n@fa-var-newspaper: \"\\f1ea\";\n@fa-var-nimblr: \"\\f5a8\";\n@fa-var-node: \"\\f419\";\n@fa-var-node-js: \"\\f3d3\";\n@fa-var-not-equal: \"\\f53e\";\n@fa-var-notes-medical: \"\\f481\";\n@fa-var-npm: \"\\f3d4\";\n@fa-var-ns8: \"\\f3d5\";\n@fa-var-nutritionix: \"\\f3d6\";\n@fa-var-object-group: \"\\f247\";\n@fa-var-object-ungroup: \"\\f248\";\n@fa-var-odnoklassniki: \"\\f263\";\n@fa-var-odnoklassniki-square: \"\\f264\";\n@fa-var-oil-can: \"\\f613\";\n@fa-var-old-republic: \"\\f510\";\n@fa-var-om: \"\\f679\";\n@fa-var-opencart: \"\\f23d\";\n@fa-var-openid: \"\\f19b\";\n@fa-var-opera: \"\\f26a\";\n@fa-var-optin-monster: \"\\f23c\";\n@fa-var-osi: \"\\f41a\";\n@fa-var-otter: \"\\f700\";\n@fa-var-outdent: \"\\f03b\";\n@fa-var-page4: \"\\f3d7\";\n@fa-var-pagelines: \"\\f18c\";\n@fa-var-pager: \"\\f815\";\n@fa-var-paint-brush: \"\\f1fc\";\n@fa-var-paint-roller: \"\\f5aa\";\n@fa-var-palette: \"\\f53f\";\n@fa-var-palfed: \"\\f3d8\";\n@fa-var-pallet: \"\\f482\";\n@fa-var-paper-plane: \"\\f1d8\";\n@fa-var-paperclip: \"\\f0c6\";\n@fa-var-parachute-box: \"\\f4cd\";\n@fa-var-paragraph: \"\\f1dd\";\n@fa-var-parking: \"\\f540\";\n@fa-var-passport: \"\\f5ab\";\n@fa-var-pastafarianism: \"\\f67b\";\n@fa-var-paste: \"\\f0ea\";\n@fa-var-patreon: \"\\f3d9\";\n@fa-var-pause: \"\\f04c\";\n@fa-var-pause-circle: \"\\f28b\";\n@fa-var-paw: \"\\f1b0\";\n@fa-var-paypal: \"\\f1ed\";\n@fa-var-peace: \"\\f67c\";\n@fa-var-pen: \"\\f304\";\n@fa-var-pen-alt: \"\\f305\";\n@fa-var-pen-fancy: \"\\f5ac\";\n@fa-var-pen-nib: \"\\f5ad\";\n@fa-var-pen-square: \"\\f14b\";\n@fa-var-pencil-alt: \"\\f303\";\n@fa-var-pencil-ruler: \"\\f5ae\";\n@fa-var-penny-arcade: \"\\f704\";\n@fa-var-people-carry: \"\\f4ce\";\n@fa-var-pepper-hot: \"\\f816\";\n@fa-var-percent: \"\\f295\";\n@fa-var-percentage: \"\\f541\";\n@fa-var-periscope: \"\\f3da\";\n@fa-var-person-booth: \"\\f756\";\n@fa-var-phabricator: \"\\f3db\";\n@fa-var-phoenix-framework: \"\\f3dc\";\n@fa-var-phoenix-squadron: \"\\f511\";\n@fa-var-phone: \"\\f095\";\n@fa-var-phone-alt: \"\\f879\";\n@fa-var-phone-slash: \"\\f3dd\";\n@fa-var-phone-square: \"\\f098\";\n@fa-var-phone-square-alt: \"\\f87b\";\n@fa-var-phone-volume: \"\\f2a0\";\n@fa-var-photo-video: \"\\f87c\";\n@fa-var-php: \"\\f457\";\n@fa-var-pied-piper: \"\\f2ae\";\n@fa-var-pied-piper-alt: \"\\f1a8\";\n@fa-var-pied-piper-hat: \"\\f4e5\";\n@fa-var-pied-piper-pp: \"\\f1a7\";\n@fa-var-piggy-bank: \"\\f4d3\";\n@fa-var-pills: \"\\f484\";\n@fa-var-pinterest: \"\\f0d2\";\n@fa-var-pinterest-p: \"\\f231\";\n@fa-var-pinterest-square: \"\\f0d3\";\n@fa-var-pizza-slice: \"\\f818\";\n@fa-var-place-of-worship: \"\\f67f\";\n@fa-var-plane: \"\\f072\";\n@fa-var-plane-arrival: \"\\f5af\";\n@fa-var-plane-departure: \"\\f5b0\";\n@fa-var-play: \"\\f04b\";\n@fa-var-play-circle: \"\\f144\";\n@fa-var-playstation: \"\\f3df\";\n@fa-var-plug: \"\\f1e6\";\n@fa-var-plus: \"\\f067\";\n@fa-var-plus-circle: \"\\f055\";\n@fa-var-plus-square: \"\\f0fe\";\n@fa-var-podcast: \"\\f2ce\";\n@fa-var-poll: \"\\f681\";\n@fa-var-poll-h: \"\\f682\";\n@fa-var-poo: \"\\f2fe\";\n@fa-var-poo-storm: \"\\f75a\";\n@fa-var-poop: \"\\f619\";\n@fa-var-portrait: \"\\f3e0\";\n@fa-var-pound-sign: \"\\f154\";\n@fa-var-power-off: \"\\f011\";\n@fa-var-pray: \"\\f683\";\n@fa-var-praying-hands: \"\\f684\";\n@fa-var-prescription: \"\\f5b1\";\n@fa-var-prescription-bottle: \"\\f485\";\n@fa-var-prescription-bottle-alt: \"\\f486\";\n@fa-var-print: \"\\f02f\";\n@fa-var-procedures: \"\\f487\";\n@fa-var-product-hunt: \"\\f288\";\n@fa-var-project-diagram: \"\\f542\";\n@fa-var-pushed: \"\\f3e1\";\n@fa-var-puzzle-piece: \"\\f12e\";\n@fa-var-python: \"\\f3e2\";\n@fa-var-qq: \"\\f1d6\";\n@fa-var-qrcode: \"\\f029\";\n@fa-var-question: \"\\f128\";\n@fa-var-question-circle: \"\\f059\";\n@fa-var-quidditch: \"\\f458\";\n@fa-var-quinscape: \"\\f459\";\n@fa-var-quora: \"\\f2c4\";\n@fa-var-quote-left: \"\\f10d\";\n@fa-var-quote-right: \"\\f10e\";\n@fa-var-quran: \"\\f687\";\n@fa-var-r-project: \"\\f4f7\";\n@fa-var-radiation: \"\\f7b9\";\n@fa-var-radiation-alt: \"\\f7ba\";\n@fa-var-rainbow: \"\\f75b\";\n@fa-var-random: \"\\f074\";\n@fa-var-raspberry-pi: \"\\f7bb\";\n@fa-var-ravelry: \"\\f2d9\";\n@fa-var-react: \"\\f41b\";\n@fa-var-reacteurope: \"\\f75d\";\n@fa-var-readme: \"\\f4d5\";\n@fa-var-rebel: \"\\f1d0\";\n@fa-var-receipt: \"\\f543\";\n@fa-var-recycle: \"\\f1b8\";\n@fa-var-red-river: \"\\f3e3\";\n@fa-var-reddit: \"\\f1a1\";\n@fa-var-reddit-alien: \"\\f281\";\n@fa-var-reddit-square: \"\\f1a2\";\n@fa-var-redhat: \"\\f7bc\";\n@fa-var-redo: \"\\f01e\";\n@fa-var-redo-alt: \"\\f2f9\";\n@fa-var-registered: \"\\f25d\";\n@fa-var-remove-format: \"\\f87d\";\n@fa-var-renren: \"\\f18b\";\n@fa-var-reply: \"\\f3e5\";\n@fa-var-reply-all: \"\\f122\";\n@fa-var-replyd: \"\\f3e6\";\n@fa-var-republican: \"\\f75e\";\n@fa-var-researchgate: \"\\f4f8\";\n@fa-var-resolving: \"\\f3e7\";\n@fa-var-restroom: \"\\f7bd\";\n@fa-var-retweet: \"\\f079\";\n@fa-var-rev: \"\\f5b2\";\n@fa-var-ribbon: \"\\f4d6\";\n@fa-var-ring: \"\\f70b\";\n@fa-var-road: \"\\f018\";\n@fa-var-robot: \"\\f544\";\n@fa-var-rocket: \"\\f135\";\n@fa-var-rocketchat: \"\\f3e8\";\n@fa-var-rockrms: \"\\f3e9\";\n@fa-var-route: \"\\f4d7\";\n@fa-var-rss: \"\\f09e\";\n@fa-var-rss-square: \"\\f143\";\n@fa-var-ruble-sign: \"\\f158\";\n@fa-var-ruler: \"\\f545\";\n@fa-var-ruler-combined: \"\\f546\";\n@fa-var-ruler-horizontal: \"\\f547\";\n@fa-var-ruler-vertical: \"\\f548\";\n@fa-var-running: \"\\f70c\";\n@fa-var-rupee-sign: \"\\f156\";\n@fa-var-sad-cry: \"\\f5b3\";\n@fa-var-sad-tear: \"\\f5b4\";\n@fa-var-safari: \"\\f267\";\n@fa-var-salesforce: \"\\f83b\";\n@fa-var-sass: \"\\f41e\";\n@fa-var-satellite: \"\\f7bf\";\n@fa-var-satellite-dish: \"\\f7c0\";\n@fa-var-save: \"\\f0c7\";\n@fa-var-schlix: \"\\f3ea\";\n@fa-var-school: \"\\f549\";\n@fa-var-screwdriver: \"\\f54a\";\n@fa-var-scribd: \"\\f28a\";\n@fa-var-scroll: \"\\f70e\";\n@fa-var-sd-card: \"\\f7c2\";\n@fa-var-search: \"\\f002\";\n@fa-var-search-dollar: \"\\f688\";\n@fa-var-search-location: \"\\f689\";\n@fa-var-search-minus: \"\\f010\";\n@fa-var-search-plus: \"\\f00e\";\n@fa-var-searchengin: \"\\f3eb\";\n@fa-var-seedling: \"\\f4d8\";\n@fa-var-sellcast: \"\\f2da\";\n@fa-var-sellsy: \"\\f213\";\n@fa-var-server: \"\\f233\";\n@fa-var-servicestack: \"\\f3ec\";\n@fa-var-shapes: \"\\f61f\";\n@fa-var-share: \"\\f064\";\n@fa-var-share-alt: \"\\f1e0\";\n@fa-var-share-alt-square: \"\\f1e1\";\n@fa-var-share-square: \"\\f14d\";\n@fa-var-shekel-sign: \"\\f20b\";\n@fa-var-shield-alt: \"\\f3ed\";\n@fa-var-ship: \"\\f21a\";\n@fa-var-shipping-fast: \"\\f48b\";\n@fa-var-shirtsinbulk: \"\\f214\";\n@fa-var-shoe-prints: \"\\f54b\";\n@fa-var-shopping-bag: \"\\f290\";\n@fa-var-shopping-basket: \"\\f291\";\n@fa-var-shopping-cart: \"\\f07a\";\n@fa-var-shopware: \"\\f5b5\";\n@fa-var-shower: \"\\f2cc\";\n@fa-var-shuttle-van: \"\\f5b6\";\n@fa-var-sign: \"\\f4d9\";\n@fa-var-sign-in-alt: \"\\f2f6\";\n@fa-var-sign-language: \"\\f2a7\";\n@fa-var-sign-out-alt: \"\\f2f5\";\n@fa-var-signal: \"\\f012\";\n@fa-var-signature: \"\\f5b7\";\n@fa-var-sim-card: \"\\f7c4\";\n@fa-var-simplybuilt: \"\\f215\";\n@fa-var-sistrix: \"\\f3ee\";\n@fa-var-sitemap: \"\\f0e8\";\n@fa-var-sith: \"\\f512\";\n@fa-var-skating: \"\\f7c5\";\n@fa-var-sketch: \"\\f7c6\";\n@fa-var-skiing: \"\\f7c9\";\n@fa-var-skiing-nordic: \"\\f7ca\";\n@fa-var-skull: \"\\f54c\";\n@fa-var-skull-crossbones: \"\\f714\";\n@fa-var-skyatlas: \"\\f216\";\n@fa-var-skype: \"\\f17e\";\n@fa-var-slack: \"\\f198\";\n@fa-var-slack-hash: \"\\f3ef\";\n@fa-var-slash: \"\\f715\";\n@fa-var-sleigh: \"\\f7cc\";\n@fa-var-sliders-h: \"\\f1de\";\n@fa-var-slideshare: \"\\f1e7\";\n@fa-var-smile: \"\\f118\";\n@fa-var-smile-beam: \"\\f5b8\";\n@fa-var-smile-wink: \"\\f4da\";\n@fa-var-smog: \"\\f75f\";\n@fa-var-smoking: \"\\f48d\";\n@fa-var-smoking-ban: \"\\f54d\";\n@fa-var-sms: \"\\f7cd\";\n@fa-var-snapchat: \"\\f2ab\";\n@fa-var-snapchat-ghost: \"\\f2ac\";\n@fa-var-snapchat-square: \"\\f2ad\";\n@fa-var-snowboarding: \"\\f7ce\";\n@fa-var-snowflake: \"\\f2dc\";\n@fa-var-snowman: \"\\f7d0\";\n@fa-var-snowplow: \"\\f7d2\";\n@fa-var-socks: \"\\f696\";\n@fa-var-solar-panel: \"\\f5ba\";\n@fa-var-sort: \"\\f0dc\";\n@fa-var-sort-alpha-down: \"\\f15d\";\n@fa-var-sort-alpha-down-alt: \"\\f881\";\n@fa-var-sort-alpha-up: \"\\f15e\";\n@fa-var-sort-alpha-up-alt: \"\\f882\";\n@fa-var-sort-amount-down: \"\\f160\";\n@fa-var-sort-amount-down-alt: \"\\f884\";\n@fa-var-sort-amount-up: \"\\f161\";\n@fa-var-sort-amount-up-alt: \"\\f885\";\n@fa-var-sort-down: \"\\f0dd\";\n@fa-var-sort-numeric-down: \"\\f162\";\n@fa-var-sort-numeric-down-alt: \"\\f886\";\n@fa-var-sort-numeric-up: \"\\f163\";\n@fa-var-sort-numeric-up-alt: \"\\f887\";\n@fa-var-sort-up: \"\\f0de\";\n@fa-var-soundcloud: \"\\f1be\";\n@fa-var-sourcetree: \"\\f7d3\";\n@fa-var-spa: \"\\f5bb\";\n@fa-var-space-shuttle: \"\\f197\";\n@fa-var-speakap: \"\\f3f3\";\n@fa-var-speaker-deck: \"\\f83c\";\n@fa-var-spell-check: \"\\f891\";\n@fa-var-spider: \"\\f717\";\n@fa-var-spinner: \"\\f110\";\n@fa-var-splotch: \"\\f5bc\";\n@fa-var-spotify: \"\\f1bc\";\n@fa-var-spray-can: \"\\f5bd\";\n@fa-var-square: \"\\f0c8\";\n@fa-var-square-full: \"\\f45c\";\n@fa-var-square-root-alt: \"\\f698\";\n@fa-var-squarespace: \"\\f5be\";\n@fa-var-stack-exchange: \"\\f18d\";\n@fa-var-stack-overflow: \"\\f16c\";\n@fa-var-stackpath: \"\\f842\";\n@fa-var-stamp: \"\\f5bf\";\n@fa-var-star: \"\\f005\";\n@fa-var-star-and-crescent: \"\\f699\";\n@fa-var-star-half: \"\\f089\";\n@fa-var-star-half-alt: \"\\f5c0\";\n@fa-var-star-of-david: \"\\f69a\";\n@fa-var-star-of-life: \"\\f621\";\n@fa-var-staylinked: \"\\f3f5\";\n@fa-var-steam: \"\\f1b6\";\n@fa-var-steam-square: \"\\f1b7\";\n@fa-var-steam-symbol: \"\\f3f6\";\n@fa-var-step-backward: \"\\f048\";\n@fa-var-step-forward: \"\\f051\";\n@fa-var-stethoscope: \"\\f0f1\";\n@fa-var-sticker-mule: \"\\f3f7\";\n@fa-var-sticky-note: \"\\f249\";\n@fa-var-stop: \"\\f04d\";\n@fa-var-stop-circle: \"\\f28d\";\n@fa-var-stopwatch: \"\\f2f2\";\n@fa-var-store: \"\\f54e\";\n@fa-var-store-alt: \"\\f54f\";\n@fa-var-strava: \"\\f428\";\n@fa-var-stream: \"\\f550\";\n@fa-var-street-view: \"\\f21d\";\n@fa-var-strikethrough: \"\\f0cc\";\n@fa-var-stripe: \"\\f429\";\n@fa-var-stripe-s: \"\\f42a\";\n@fa-var-stroopwafel: \"\\f551\";\n@fa-var-studiovinari: \"\\f3f8\";\n@fa-var-stumbleupon: \"\\f1a4\";\n@fa-var-stumbleupon-circle: \"\\f1a3\";\n@fa-var-subscript: \"\\f12c\";\n@fa-var-subway: \"\\f239\";\n@fa-var-suitcase: \"\\f0f2\";\n@fa-var-suitcase-rolling: \"\\f5c1\";\n@fa-var-sun: \"\\f185\";\n@fa-var-superpowers: \"\\f2dd\";\n@fa-var-superscript: \"\\f12b\";\n@fa-var-supple: \"\\f3f9\";\n@fa-var-surprise: \"\\f5c2\";\n@fa-var-suse: \"\\f7d6\";\n@fa-var-swatchbook: \"\\f5c3\";\n@fa-var-swimmer: \"\\f5c4\";\n@fa-var-swimming-pool: \"\\f5c5\";\n@fa-var-symfony: \"\\f83d\";\n@fa-var-synagogue: \"\\f69b\";\n@fa-var-sync: \"\\f021\";\n@fa-var-sync-alt: \"\\f2f1\";\n@fa-var-syringe: \"\\f48e\";\n@fa-var-table: \"\\f0ce\";\n@fa-var-table-tennis: \"\\f45d\";\n@fa-var-tablet: \"\\f10a\";\n@fa-var-tablet-alt: \"\\f3fa\";\n@fa-var-tablets: \"\\f490\";\n@fa-var-tachometer-alt: \"\\f3fd\";\n@fa-var-tag: \"\\f02b\";\n@fa-var-tags: \"\\f02c\";\n@fa-var-tape: \"\\f4db\";\n@fa-var-tasks: \"\\f0ae\";\n@fa-var-taxi: \"\\f1ba\";\n@fa-var-teamspeak: \"\\f4f9\";\n@fa-var-teeth: \"\\f62e\";\n@fa-var-teeth-open: \"\\f62f\";\n@fa-var-telegram: \"\\f2c6\";\n@fa-var-telegram-plane: \"\\f3fe\";\n@fa-var-temperature-high: \"\\f769\";\n@fa-var-temperature-low: \"\\f76b\";\n@fa-var-tencent-weibo: \"\\f1d5\";\n@fa-var-tenge: \"\\f7d7\";\n@fa-var-terminal: \"\\f120\";\n@fa-var-text-height: \"\\f034\";\n@fa-var-text-width: \"\\f035\";\n@fa-var-th: \"\\f00a\";\n@fa-var-th-large: \"\\f009\";\n@fa-var-th-list: \"\\f00b\";\n@fa-var-the-red-yeti: \"\\f69d\";\n@fa-var-theater-masks: \"\\f630\";\n@fa-var-themeco: \"\\f5c6\";\n@fa-var-themeisle: \"\\f2b2\";\n@fa-var-thermometer: \"\\f491\";\n@fa-var-thermometer-empty: \"\\f2cb\";\n@fa-var-thermometer-full: \"\\f2c7\";\n@fa-var-thermometer-half: \"\\f2c9\";\n@fa-var-thermometer-quarter: \"\\f2ca\";\n@fa-var-thermometer-three-quarters: \"\\f2c8\";\n@fa-var-think-peaks: \"\\f731\";\n@fa-var-thumbs-down: \"\\f165\";\n@fa-var-thumbs-up: \"\\f164\";\n@fa-var-thumbtack: \"\\f08d\";\n@fa-var-ticket-alt: \"\\f3ff\";\n@fa-var-times: \"\\f00d\";\n@fa-var-times-circle: \"\\f057\";\n@fa-var-tint: \"\\f043\";\n@fa-var-tint-slash: \"\\f5c7\";\n@fa-var-tired: \"\\f5c8\";\n@fa-var-toggle-off: \"\\f204\";\n@fa-var-toggle-on: \"\\f205\";\n@fa-var-toilet: \"\\f7d8\";\n@fa-var-toilet-paper: \"\\f71e\";\n@fa-var-toolbox: \"\\f552\";\n@fa-var-tools: \"\\f7d9\";\n@fa-var-tooth: \"\\f5c9\";\n@fa-var-torah: \"\\f6a0\";\n@fa-var-torii-gate: \"\\f6a1\";\n@fa-var-tractor: \"\\f722\";\n@fa-var-trade-federation: \"\\f513\";\n@fa-var-trademark: \"\\f25c\";\n@fa-var-traffic-light: \"\\f637\";\n@fa-var-train: \"\\f238\";\n@fa-var-tram: \"\\f7da\";\n@fa-var-transgender: \"\\f224\";\n@fa-var-transgender-alt: \"\\f225\";\n@fa-var-trash: \"\\f1f8\";\n@fa-var-trash-alt: \"\\f2ed\";\n@fa-var-trash-restore: \"\\f829\";\n@fa-var-trash-restore-alt: \"\\f82a\";\n@fa-var-tree: \"\\f1bb\";\n@fa-var-trello: \"\\f181\";\n@fa-var-tripadvisor: \"\\f262\";\n@fa-var-trophy: \"\\f091\";\n@fa-var-truck: \"\\f0d1\";\n@fa-var-truck-loading: \"\\f4de\";\n@fa-var-truck-monster: \"\\f63b\";\n@fa-var-truck-moving: \"\\f4df\";\n@fa-var-truck-pickup: \"\\f63c\";\n@fa-var-tshirt: \"\\f553\";\n@fa-var-tty: \"\\f1e4\";\n@fa-var-tumblr: \"\\f173\";\n@fa-var-tumblr-square: \"\\f174\";\n@fa-var-tv: \"\\f26c\";\n@fa-var-twitch: \"\\f1e8\";\n@fa-var-twitter: \"\\f099\";\n@fa-var-twitter-square: \"\\f081\";\n@fa-var-typo3: \"\\f42b\";\n@fa-var-uber: \"\\f402\";\n@fa-var-ubuntu: \"\\f7df\";\n@fa-var-uikit: \"\\f403\";\n@fa-var-umbrella: \"\\f0e9\";\n@fa-var-umbrella-beach: \"\\f5ca\";\n@fa-var-underline: \"\\f0cd\";\n@fa-var-undo: \"\\f0e2\";\n@fa-var-undo-alt: \"\\f2ea\";\n@fa-var-uniregistry: \"\\f404\";\n@fa-var-universal-access: \"\\f29a\";\n@fa-var-university: \"\\f19c\";\n@fa-var-unlink: \"\\f127\";\n@fa-var-unlock: \"\\f09c\";\n@fa-var-unlock-alt: \"\\f13e\";\n@fa-var-untappd: \"\\f405\";\n@fa-var-upload: \"\\f093\";\n@fa-var-ups: \"\\f7e0\";\n@fa-var-usb: \"\\f287\";\n@fa-var-user: \"\\f007\";\n@fa-var-user-alt: \"\\f406\";\n@fa-var-user-alt-slash: \"\\f4fa\";\n@fa-var-user-astronaut: \"\\f4fb\";\n@fa-var-user-check: \"\\f4fc\";\n@fa-var-user-circle: \"\\f2bd\";\n@fa-var-user-clock: \"\\f4fd\";\n@fa-var-user-cog: \"\\f4fe\";\n@fa-var-user-edit: \"\\f4ff\";\n@fa-var-user-friends: \"\\f500\";\n@fa-var-user-graduate: \"\\f501\";\n@fa-var-user-injured: \"\\f728\";\n@fa-var-user-lock: \"\\f502\";\n@fa-var-user-md: \"\\f0f0\";\n@fa-var-user-minus: \"\\f503\";\n@fa-var-user-ninja: \"\\f504\";\n@fa-var-user-nurse: \"\\f82f\";\n@fa-var-user-plus: \"\\f234\";\n@fa-var-user-secret: \"\\f21b\";\n@fa-var-user-shield: \"\\f505\";\n@fa-var-user-slash: \"\\f506\";\n@fa-var-user-tag: \"\\f507\";\n@fa-var-user-tie: \"\\f508\";\n@fa-var-user-times: \"\\f235\";\n@fa-var-users: \"\\f0c0\";\n@fa-var-users-cog: \"\\f509\";\n@fa-var-usps: \"\\f7e1\";\n@fa-var-ussunnah: \"\\f407\";\n@fa-var-utensil-spoon: \"\\f2e5\";\n@fa-var-utensils: \"\\f2e7\";\n@fa-var-vaadin: \"\\f408\";\n@fa-var-vector-square: \"\\f5cb\";\n@fa-var-venus: \"\\f221\";\n@fa-var-venus-double: \"\\f226\";\n@fa-var-venus-mars: \"\\f228\";\n@fa-var-viacoin: \"\\f237\";\n@fa-var-viadeo: \"\\f2a9\";\n@fa-var-viadeo-square: \"\\f2aa\";\n@fa-var-vial: \"\\f492\";\n@fa-var-vials: \"\\f493\";\n@fa-var-viber: \"\\f409\";\n@fa-var-video: \"\\f03d\";\n@fa-var-video-slash: \"\\f4e2\";\n@fa-var-vihara: \"\\f6a7\";\n@fa-var-vimeo: \"\\f40a\";\n@fa-var-vimeo-square: \"\\f194\";\n@fa-var-vimeo-v: \"\\f27d\";\n@fa-var-vine: \"\\f1ca\";\n@fa-var-vk: \"\\f189\";\n@fa-var-vnv: \"\\f40b\";\n@fa-var-voicemail: \"\\f897\";\n@fa-var-volleyball-ball: \"\\f45f\";\n@fa-var-volume-down: \"\\f027\";\n@fa-var-volume-mute: \"\\f6a9\";\n@fa-var-volume-off: \"\\f026\";\n@fa-var-volume-up: \"\\f028\";\n@fa-var-vote-yea: \"\\f772\";\n@fa-var-vr-cardboard: \"\\f729\";\n@fa-var-vuejs: \"\\f41f\";\n@fa-var-walking: \"\\f554\";\n@fa-var-wallet: \"\\f555\";\n@fa-var-warehouse: \"\\f494\";\n@fa-var-water: \"\\f773\";\n@fa-var-wave-square: \"\\f83e\";\n@fa-var-waze: \"\\f83f\";\n@fa-var-weebly: \"\\f5cc\";\n@fa-var-weibo: \"\\f18a\";\n@fa-var-weight: \"\\f496\";\n@fa-var-weight-hanging: \"\\f5cd\";\n@fa-var-weixin: \"\\f1d7\";\n@fa-var-whatsapp: \"\\f232\";\n@fa-var-whatsapp-square: \"\\f40c\";\n@fa-var-wheelchair: \"\\f193\";\n@fa-var-whmcs: \"\\f40d\";\n@fa-var-wifi: \"\\f1eb\";\n@fa-var-wikipedia-w: \"\\f266\";\n@fa-var-wind: \"\\f72e\";\n@fa-var-window-close: \"\\f410\";\n@fa-var-window-maximize: \"\\f2d0\";\n@fa-var-window-minimize: \"\\f2d1\";\n@fa-var-window-restore: \"\\f2d2\";\n@fa-var-windows: \"\\f17a\";\n@fa-var-wine-bottle: \"\\f72f\";\n@fa-var-wine-glass: \"\\f4e3\";\n@fa-var-wine-glass-alt: \"\\f5ce\";\n@fa-var-wix: \"\\f5cf\";\n@fa-var-wizards-of-the-coast: \"\\f730\";\n@fa-var-wolf-pack-battalion: \"\\f514\";\n@fa-var-won-sign: \"\\f159\";\n@fa-var-wordpress: \"\\f19a\";\n@fa-var-wordpress-simple: \"\\f411\";\n@fa-var-wpbeginner: \"\\f297\";\n@fa-var-wpexplorer: \"\\f2de\";\n@fa-var-wpforms: \"\\f298\";\n@fa-var-wpressr: \"\\f3e4\";\n@fa-var-wrench: \"\\f0ad\";\n@fa-var-x-ray: \"\\f497\";\n@fa-var-xbox: \"\\f412\";\n@fa-var-xing: \"\\f168\";\n@fa-var-xing-square: \"\\f169\";\n@fa-var-y-combinator: \"\\f23b\";\n@fa-var-yahoo: \"\\f19e\";\n@fa-var-yammer: \"\\f840\";\n@fa-var-yandex: \"\\f413\";\n@fa-var-yandex-international: \"\\f414\";\n@fa-var-yarn: \"\\f7e3\";\n@fa-var-yelp: \"\\f1e9\";\n@fa-var-yen-sign: \"\\f157\";\n@fa-var-yin-yang: \"\\f6ad\";\n@fa-var-yoast: \"\\f2b1\";\n@fa-var-youtube: \"\\f167\";\n@fa-var-youtube-square: \"\\f431\";\n@fa-var-zhihu: \"\\f63f\";\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/brands.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: @fa-font-display;\n  src: url('@{fa-font-path}/fa-brands-400.eot');\n  src: url('@{fa-font-path}/fa-brands-400.eot?#iefix') format('embedded-opentype'),\n    url('@{fa-font-path}/fa-brands-400.woff2') format('woff2'),\n    url('@{fa-font-path}/fa-brands-400.woff') format('woff'),\n    url('@{fa-font-path}/fa-brands-400.ttf') format('truetype'),\n    url('@{fa-font-path}/fa-brands-400.svg#fontawesome') format('svg');\n}\n\n.fab {\n  font-family: 'Font Awesome 5 Brands';\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/fontawesome.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n@import \"_mixins.less\";\n@import \"_core.less\";\n@import \"_larger.less\";\n@import \"_fixed-width.less\";\n@import \"_list.less\";\n@import \"_bordered-pulled.less\";\n@import \"_animated.less\";\n@import \"_rotated-flipped.less\";\n@import \"_stacked.less\";\n@import \"_icons.less\";\n@import \"_screen-reader.less\";\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/regular.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: @fa-font-display;\n  src: url('@{fa-font-path}/fa-regular-400.eot');\n  src: url('@{fa-font-path}/fa-regular-400.eot?#iefix') format('embedded-opentype'),\n    url('@{fa-font-path}/fa-regular-400.woff2') format('woff2'),\n    url('@{fa-font-path}/fa-regular-400.woff') format('woff'),\n    url('@{fa-font-path}/fa-regular-400.ttf') format('truetype'),\n    url('@{fa-font-path}/fa-regular-400.svg#fontawesome') format('svg');\n}\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/solid.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: @fa-font-display;\n  src: url('@{fa-font-path}/fa-solid-900.eot');\n  src: url('@{fa-font-path}/fa-solid-900.eot?#iefix') format('embedded-opentype'),\n    url('@{fa-font-path}/fa-solid-900.woff2') format('woff2'),\n    url('@{fa-font-path}/fa-solid-900.woff') format('woff'),\n    url('@{fa-font-path}/fa-solid-900.ttf') format('truetype'),\n    url('@{fa-font-path}/fa-solid-900.svg#fontawesome') format('svg');\n}\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/v4-shims.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import '_variables.less';\n@import '_shims.less';\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_animated.scss",
    "content": "// Animated Icons\n// --------------------------\n\n.#{$fa-css-prefix}-spin {\n  animation: fa-spin 2s infinite linear;\n}\n\n.#{$fa-css-prefix}-pulse {\n  animation: fa-spin 1s infinite steps(8);\n}\n\n@keyframes fa-spin {\n  0% {\n    transform: rotate(0deg);\n  }\n\n  100% {\n    transform: rotate(360deg);\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_bordered-pulled.scss",
    "content": "// Bordered & Pulled\n// -------------------------\n\n.#{$fa-css-prefix}-border {\n  border: solid .08em $fa-border-color;\n  border-radius: .1em;\n  padding: .2em .25em .15em;\n}\n\n.#{$fa-css-prefix}-pull-left { float: left; }\n.#{$fa-css-prefix}-pull-right { float: right; }\n\n.#{$fa-css-prefix},\n.fas,\n.far,\n.fal,\n.fab {\n  &.#{$fa-css-prefix}-pull-left { margin-right: .3em; }\n  &.#{$fa-css-prefix}-pull-right { margin-left: .3em; }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_core.scss",
    "content": "// Base Class Definition\n// -------------------------\n\n.#{$fa-css-prefix},\n.fas,\n.far,\n.fal,\n.fad,\n.fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1;\n}\n\n%fa-icon {\n  @include fa-icon;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_fixed-width.scss",
    "content": "// Fixed Width Icons\n// -------------------------\n.#{$fa-css-prefix}-fw {\n  text-align: center;\n  width: $fa-fw-width;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_icons.scss",
    "content": "/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\nreaders do not read off random characters that represent icons */\n\n.#{$fa-css-prefix}-500px:before { content: fa-content($fa-var-500px); }\n.#{$fa-css-prefix}-accessible-icon:before { content: fa-content($fa-var-accessible-icon); }\n.#{$fa-css-prefix}-accusoft:before { content: fa-content($fa-var-accusoft); }\n.#{$fa-css-prefix}-acquisitions-incorporated:before { content: fa-content($fa-var-acquisitions-incorporated); }\n.#{$fa-css-prefix}-ad:before { content: fa-content($fa-var-ad); }\n.#{$fa-css-prefix}-address-book:before { content: fa-content($fa-var-address-book); }\n.#{$fa-css-prefix}-address-card:before { content: fa-content($fa-var-address-card); }\n.#{$fa-css-prefix}-adjust:before { content: fa-content($fa-var-adjust); }\n.#{$fa-css-prefix}-adn:before { content: fa-content($fa-var-adn); }\n.#{$fa-css-prefix}-adobe:before { content: fa-content($fa-var-adobe); }\n.#{$fa-css-prefix}-adversal:before { content: fa-content($fa-var-adversal); }\n.#{$fa-css-prefix}-affiliatetheme:before { content: fa-content($fa-var-affiliatetheme); }\n.#{$fa-css-prefix}-air-freshener:before { content: fa-content($fa-var-air-freshener); }\n.#{$fa-css-prefix}-airbnb:before { content: fa-content($fa-var-airbnb); }\n.#{$fa-css-prefix}-algolia:before { content: fa-content($fa-var-algolia); }\n.#{$fa-css-prefix}-align-center:before { content: fa-content($fa-var-align-center); }\n.#{$fa-css-prefix}-align-justify:before { content: fa-content($fa-var-align-justify); }\n.#{$fa-css-prefix}-align-left:before { content: fa-content($fa-var-align-left); }\n.#{$fa-css-prefix}-align-right:before { content: fa-content($fa-var-align-right); }\n.#{$fa-css-prefix}-alipay:before { content: fa-content($fa-var-alipay); }\n.#{$fa-css-prefix}-allergies:before { content: fa-content($fa-var-allergies); }\n.#{$fa-css-prefix}-amazon:before { content: fa-content($fa-var-amazon); }\n.#{$fa-css-prefix}-amazon-pay:before { content: fa-content($fa-var-amazon-pay); }\n.#{$fa-css-prefix}-ambulance:before { content: fa-content($fa-var-ambulance); }\n.#{$fa-css-prefix}-american-sign-language-interpreting:before { content: fa-content($fa-var-american-sign-language-interpreting); }\n.#{$fa-css-prefix}-amilia:before { content: fa-content($fa-var-amilia); }\n.#{$fa-css-prefix}-anchor:before { content: fa-content($fa-var-anchor); }\n.#{$fa-css-prefix}-android:before { content: fa-content($fa-var-android); }\n.#{$fa-css-prefix}-angellist:before { content: fa-content($fa-var-angellist); }\n.#{$fa-css-prefix}-angle-double-down:before { content: fa-content($fa-var-angle-double-down); }\n.#{$fa-css-prefix}-angle-double-left:before { content: fa-content($fa-var-angle-double-left); }\n.#{$fa-css-prefix}-angle-double-right:before { content: fa-content($fa-var-angle-double-right); }\n.#{$fa-css-prefix}-angle-double-up:before { content: fa-content($fa-var-angle-double-up); }\n.#{$fa-css-prefix}-angle-down:before { content: fa-content($fa-var-angle-down); }\n.#{$fa-css-prefix}-angle-left:before { content: fa-content($fa-var-angle-left); }\n.#{$fa-css-prefix}-angle-right:before { content: fa-content($fa-var-angle-right); }\n.#{$fa-css-prefix}-angle-up:before { content: fa-content($fa-var-angle-up); }\n.#{$fa-css-prefix}-angry:before { content: fa-content($fa-var-angry); }\n.#{$fa-css-prefix}-angrycreative:before { content: fa-content($fa-var-angrycreative); }\n.#{$fa-css-prefix}-angular:before { content: fa-content($fa-var-angular); }\n.#{$fa-css-prefix}-ankh:before { content: fa-content($fa-var-ankh); }\n.#{$fa-css-prefix}-app-store:before { content: fa-content($fa-var-app-store); }\n.#{$fa-css-prefix}-app-store-ios:before { content: fa-content($fa-var-app-store-ios); }\n.#{$fa-css-prefix}-apper:before { content: fa-content($fa-var-apper); }\n.#{$fa-css-prefix}-apple:before { content: fa-content($fa-var-apple); }\n.#{$fa-css-prefix}-apple-alt:before { content: fa-content($fa-var-apple-alt); }\n.#{$fa-css-prefix}-apple-pay:before { content: fa-content($fa-var-apple-pay); }\n.#{$fa-css-prefix}-archive:before { content: fa-content($fa-var-archive); }\n.#{$fa-css-prefix}-archway:before { content: fa-content($fa-var-archway); }\n.#{$fa-css-prefix}-arrow-alt-circle-down:before { content: fa-content($fa-var-arrow-alt-circle-down); }\n.#{$fa-css-prefix}-arrow-alt-circle-left:before { content: fa-content($fa-var-arrow-alt-circle-left); }\n.#{$fa-css-prefix}-arrow-alt-circle-right:before { content: fa-content($fa-var-arrow-alt-circle-right); }\n.#{$fa-css-prefix}-arrow-alt-circle-up:before { content: fa-content($fa-var-arrow-alt-circle-up); }\n.#{$fa-css-prefix}-arrow-circle-down:before { content: fa-content($fa-var-arrow-circle-down); }\n.#{$fa-css-prefix}-arrow-circle-left:before { content: fa-content($fa-var-arrow-circle-left); }\n.#{$fa-css-prefix}-arrow-circle-right:before { content: fa-content($fa-var-arrow-circle-right); }\n.#{$fa-css-prefix}-arrow-circle-up:before { content: fa-content($fa-var-arrow-circle-up); }\n.#{$fa-css-prefix}-arrow-down:before { content: fa-content($fa-var-arrow-down); }\n.#{$fa-css-prefix}-arrow-left:before { content: fa-content($fa-var-arrow-left); }\n.#{$fa-css-prefix}-arrow-right:before { content: fa-content($fa-var-arrow-right); }\n.#{$fa-css-prefix}-arrow-up:before { content: fa-content($fa-var-arrow-up); }\n.#{$fa-css-prefix}-arrows-alt:before { content: fa-content($fa-var-arrows-alt); }\n.#{$fa-css-prefix}-arrows-alt-h:before { content: fa-content($fa-var-arrows-alt-h); }\n.#{$fa-css-prefix}-arrows-alt-v:before { content: fa-content($fa-var-arrows-alt-v); }\n.#{$fa-css-prefix}-artstation:before { content: fa-content($fa-var-artstation); }\n.#{$fa-css-prefix}-assistive-listening-systems:before { content: fa-content($fa-var-assistive-listening-systems); }\n.#{$fa-css-prefix}-asterisk:before { content: fa-content($fa-var-asterisk); }\n.#{$fa-css-prefix}-asymmetrik:before { content: fa-content($fa-var-asymmetrik); }\n.#{$fa-css-prefix}-at:before { content: fa-content($fa-var-at); }\n.#{$fa-css-prefix}-atlas:before { content: fa-content($fa-var-atlas); }\n.#{$fa-css-prefix}-atlassian:before { content: fa-content($fa-var-atlassian); }\n.#{$fa-css-prefix}-atom:before { content: fa-content($fa-var-atom); }\n.#{$fa-css-prefix}-audible:before { content: fa-content($fa-var-audible); }\n.#{$fa-css-prefix}-audio-description:before { content: fa-content($fa-var-audio-description); }\n.#{$fa-css-prefix}-autoprefixer:before { content: fa-content($fa-var-autoprefixer); }\n.#{$fa-css-prefix}-avianex:before { content: fa-content($fa-var-avianex); }\n.#{$fa-css-prefix}-aviato:before { content: fa-content($fa-var-aviato); }\n.#{$fa-css-prefix}-award:before { content: fa-content($fa-var-award); }\n.#{$fa-css-prefix}-aws:before { content: fa-content($fa-var-aws); }\n.#{$fa-css-prefix}-baby:before { content: fa-content($fa-var-baby); }\n.#{$fa-css-prefix}-baby-carriage:before { content: fa-content($fa-var-baby-carriage); }\n.#{$fa-css-prefix}-backspace:before { content: fa-content($fa-var-backspace); }\n.#{$fa-css-prefix}-backward:before { content: fa-content($fa-var-backward); }\n.#{$fa-css-prefix}-bacon:before { content: fa-content($fa-var-bacon); }\n.#{$fa-css-prefix}-balance-scale:before { content: fa-content($fa-var-balance-scale); }\n.#{$fa-css-prefix}-balance-scale-left:before { content: fa-content($fa-var-balance-scale-left); }\n.#{$fa-css-prefix}-balance-scale-right:before { content: fa-content($fa-var-balance-scale-right); }\n.#{$fa-css-prefix}-ban:before { content: fa-content($fa-var-ban); }\n.#{$fa-css-prefix}-band-aid:before { content: fa-content($fa-var-band-aid); }\n.#{$fa-css-prefix}-bandcamp:before { content: fa-content($fa-var-bandcamp); }\n.#{$fa-css-prefix}-barcode:before { content: fa-content($fa-var-barcode); }\n.#{$fa-css-prefix}-bars:before { content: fa-content($fa-var-bars); }\n.#{$fa-css-prefix}-baseball-ball:before { content: fa-content($fa-var-baseball-ball); }\n.#{$fa-css-prefix}-basketball-ball:before { content: fa-content($fa-var-basketball-ball); }\n.#{$fa-css-prefix}-bath:before { content: fa-content($fa-var-bath); }\n.#{$fa-css-prefix}-battery-empty:before { content: fa-content($fa-var-battery-empty); }\n.#{$fa-css-prefix}-battery-full:before { content: fa-content($fa-var-battery-full); }\n.#{$fa-css-prefix}-battery-half:before { content: fa-content($fa-var-battery-half); }\n.#{$fa-css-prefix}-battery-quarter:before { content: fa-content($fa-var-battery-quarter); }\n.#{$fa-css-prefix}-battery-three-quarters:before { content: fa-content($fa-var-battery-three-quarters); }\n.#{$fa-css-prefix}-battle-net:before { content: fa-content($fa-var-battle-net); }\n.#{$fa-css-prefix}-bed:before { content: fa-content($fa-var-bed); }\n.#{$fa-css-prefix}-beer:before { content: fa-content($fa-var-beer); }\n.#{$fa-css-prefix}-behance:before { content: fa-content($fa-var-behance); }\n.#{$fa-css-prefix}-behance-square:before { content: fa-content($fa-var-behance-square); }\n.#{$fa-css-prefix}-bell:before { content: fa-content($fa-var-bell); }\n.#{$fa-css-prefix}-bell-slash:before { content: fa-content($fa-var-bell-slash); }\n.#{$fa-css-prefix}-bezier-curve:before { content: fa-content($fa-var-bezier-curve); }\n.#{$fa-css-prefix}-bible:before { content: fa-content($fa-var-bible); }\n.#{$fa-css-prefix}-bicycle:before { content: fa-content($fa-var-bicycle); }\n.#{$fa-css-prefix}-biking:before { content: fa-content($fa-var-biking); }\n.#{$fa-css-prefix}-bimobject:before { content: fa-content($fa-var-bimobject); }\n.#{$fa-css-prefix}-binoculars:before { content: fa-content($fa-var-binoculars); }\n.#{$fa-css-prefix}-biohazard:before { content: fa-content($fa-var-biohazard); }\n.#{$fa-css-prefix}-birthday-cake:before { content: fa-content($fa-var-birthday-cake); }\n.#{$fa-css-prefix}-bitbucket:before { content: fa-content($fa-var-bitbucket); }\n.#{$fa-css-prefix}-bitcoin:before { content: fa-content($fa-var-bitcoin); }\n.#{$fa-css-prefix}-bity:before { content: fa-content($fa-var-bity); }\n.#{$fa-css-prefix}-black-tie:before { content: fa-content($fa-var-black-tie); }\n.#{$fa-css-prefix}-blackberry:before { content: fa-content($fa-var-blackberry); }\n.#{$fa-css-prefix}-blender:before { content: fa-content($fa-var-blender); }\n.#{$fa-css-prefix}-blender-phone:before { content: fa-content($fa-var-blender-phone); }\n.#{$fa-css-prefix}-blind:before { content: fa-content($fa-var-blind); }\n.#{$fa-css-prefix}-blog:before { content: fa-content($fa-var-blog); }\n.#{$fa-css-prefix}-blogger:before { content: fa-content($fa-var-blogger); }\n.#{$fa-css-prefix}-blogger-b:before { content: fa-content($fa-var-blogger-b); }\n.#{$fa-css-prefix}-bluetooth:before { content: fa-content($fa-var-bluetooth); }\n.#{$fa-css-prefix}-bluetooth-b:before { content: fa-content($fa-var-bluetooth-b); }\n.#{$fa-css-prefix}-bold:before { content: fa-content($fa-var-bold); }\n.#{$fa-css-prefix}-bolt:before { content: fa-content($fa-var-bolt); }\n.#{$fa-css-prefix}-bomb:before { content: fa-content($fa-var-bomb); }\n.#{$fa-css-prefix}-bone:before { content: fa-content($fa-var-bone); }\n.#{$fa-css-prefix}-bong:before { content: fa-content($fa-var-bong); }\n.#{$fa-css-prefix}-book:before { content: fa-content($fa-var-book); }\n.#{$fa-css-prefix}-book-dead:before { content: fa-content($fa-var-book-dead); }\n.#{$fa-css-prefix}-book-medical:before { content: fa-content($fa-var-book-medical); }\n.#{$fa-css-prefix}-book-open:before { content: fa-content($fa-var-book-open); }\n.#{$fa-css-prefix}-book-reader:before { content: fa-content($fa-var-book-reader); }\n.#{$fa-css-prefix}-bookmark:before { content: fa-content($fa-var-bookmark); }\n.#{$fa-css-prefix}-bootstrap:before { content: fa-content($fa-var-bootstrap); }\n.#{$fa-css-prefix}-border-all:before { content: fa-content($fa-var-border-all); }\n.#{$fa-css-prefix}-border-none:before { content: fa-content($fa-var-border-none); }\n.#{$fa-css-prefix}-border-style:before { content: fa-content($fa-var-border-style); }\n.#{$fa-css-prefix}-bowling-ball:before { content: fa-content($fa-var-bowling-ball); }\n.#{$fa-css-prefix}-box:before { content: fa-content($fa-var-box); }\n.#{$fa-css-prefix}-box-open:before { content: fa-content($fa-var-box-open); }\n.#{$fa-css-prefix}-boxes:before { content: fa-content($fa-var-boxes); }\n.#{$fa-css-prefix}-braille:before { content: fa-content($fa-var-braille); }\n.#{$fa-css-prefix}-brain:before { content: fa-content($fa-var-brain); }\n.#{$fa-css-prefix}-bread-slice:before { content: fa-content($fa-var-bread-slice); }\n.#{$fa-css-prefix}-briefcase:before { content: fa-content($fa-var-briefcase); }\n.#{$fa-css-prefix}-briefcase-medical:before { content: fa-content($fa-var-briefcase-medical); }\n.#{$fa-css-prefix}-broadcast-tower:before { content: fa-content($fa-var-broadcast-tower); }\n.#{$fa-css-prefix}-broom:before { content: fa-content($fa-var-broom); }\n.#{$fa-css-prefix}-brush:before { content: fa-content($fa-var-brush); }\n.#{$fa-css-prefix}-btc:before { content: fa-content($fa-var-btc); }\n.#{$fa-css-prefix}-buffer:before { content: fa-content($fa-var-buffer); }\n.#{$fa-css-prefix}-bug:before { content: fa-content($fa-var-bug); }\n.#{$fa-css-prefix}-building:before { content: fa-content($fa-var-building); }\n.#{$fa-css-prefix}-bullhorn:before { content: fa-content($fa-var-bullhorn); }\n.#{$fa-css-prefix}-bullseye:before { content: fa-content($fa-var-bullseye); }\n.#{$fa-css-prefix}-burn:before { content: fa-content($fa-var-burn); }\n.#{$fa-css-prefix}-buromobelexperte:before { content: fa-content($fa-var-buromobelexperte); }\n.#{$fa-css-prefix}-bus:before { content: fa-content($fa-var-bus); }\n.#{$fa-css-prefix}-bus-alt:before { content: fa-content($fa-var-bus-alt); }\n.#{$fa-css-prefix}-business-time:before { content: fa-content($fa-var-business-time); }\n.#{$fa-css-prefix}-buysellads:before { content: fa-content($fa-var-buysellads); }\n.#{$fa-css-prefix}-calculator:before { content: fa-content($fa-var-calculator); }\n.#{$fa-css-prefix}-calendar:before { content: fa-content($fa-var-calendar); }\n.#{$fa-css-prefix}-calendar-alt:before { content: fa-content($fa-var-calendar-alt); }\n.#{$fa-css-prefix}-calendar-check:before { content: fa-content($fa-var-calendar-check); }\n.#{$fa-css-prefix}-calendar-day:before { content: fa-content($fa-var-calendar-day); }\n.#{$fa-css-prefix}-calendar-minus:before { content: fa-content($fa-var-calendar-minus); }\n.#{$fa-css-prefix}-calendar-plus:before { content: fa-content($fa-var-calendar-plus); }\n.#{$fa-css-prefix}-calendar-times:before { content: fa-content($fa-var-calendar-times); }\n.#{$fa-css-prefix}-calendar-week:before { content: fa-content($fa-var-calendar-week); }\n.#{$fa-css-prefix}-camera:before { content: fa-content($fa-var-camera); }\n.#{$fa-css-prefix}-camera-retro:before { content: fa-content($fa-var-camera-retro); }\n.#{$fa-css-prefix}-campground:before { content: fa-content($fa-var-campground); }\n.#{$fa-css-prefix}-canadian-maple-leaf:before { content: fa-content($fa-var-canadian-maple-leaf); }\n.#{$fa-css-prefix}-candy-cane:before { content: fa-content($fa-var-candy-cane); }\n.#{$fa-css-prefix}-cannabis:before { content: fa-content($fa-var-cannabis); }\n.#{$fa-css-prefix}-capsules:before { content: fa-content($fa-var-capsules); }\n.#{$fa-css-prefix}-car:before { content: fa-content($fa-var-car); }\n.#{$fa-css-prefix}-car-alt:before { content: fa-content($fa-var-car-alt); }\n.#{$fa-css-prefix}-car-battery:before { content: fa-content($fa-var-car-battery); }\n.#{$fa-css-prefix}-car-crash:before { content: fa-content($fa-var-car-crash); }\n.#{$fa-css-prefix}-car-side:before { content: fa-content($fa-var-car-side); }\n.#{$fa-css-prefix}-caret-down:before { content: fa-content($fa-var-caret-down); }\n.#{$fa-css-prefix}-caret-left:before { content: fa-content($fa-var-caret-left); }\n.#{$fa-css-prefix}-caret-right:before { content: fa-content($fa-var-caret-right); }\n.#{$fa-css-prefix}-caret-square-down:before { content: fa-content($fa-var-caret-square-down); }\n.#{$fa-css-prefix}-caret-square-left:before { content: fa-content($fa-var-caret-square-left); }\n.#{$fa-css-prefix}-caret-square-right:before { content: fa-content($fa-var-caret-square-right); }\n.#{$fa-css-prefix}-caret-square-up:before { content: fa-content($fa-var-caret-square-up); }\n.#{$fa-css-prefix}-caret-up:before { content: fa-content($fa-var-caret-up); }\n.#{$fa-css-prefix}-carrot:before { content: fa-content($fa-var-carrot); }\n.#{$fa-css-prefix}-cart-arrow-down:before { content: fa-content($fa-var-cart-arrow-down); }\n.#{$fa-css-prefix}-cart-plus:before { content: fa-content($fa-var-cart-plus); }\n.#{$fa-css-prefix}-cash-register:before { content: fa-content($fa-var-cash-register); }\n.#{$fa-css-prefix}-cat:before { content: fa-content($fa-var-cat); }\n.#{$fa-css-prefix}-cc-amazon-pay:before { content: fa-content($fa-var-cc-amazon-pay); }\n.#{$fa-css-prefix}-cc-amex:before { content: fa-content($fa-var-cc-amex); }\n.#{$fa-css-prefix}-cc-apple-pay:before { content: fa-content($fa-var-cc-apple-pay); }\n.#{$fa-css-prefix}-cc-diners-club:before { content: fa-content($fa-var-cc-diners-club); }\n.#{$fa-css-prefix}-cc-discover:before { content: fa-content($fa-var-cc-discover); }\n.#{$fa-css-prefix}-cc-jcb:before { content: fa-content($fa-var-cc-jcb); }\n.#{$fa-css-prefix}-cc-mastercard:before { content: fa-content($fa-var-cc-mastercard); }\n.#{$fa-css-prefix}-cc-paypal:before { content: fa-content($fa-var-cc-paypal); }\n.#{$fa-css-prefix}-cc-stripe:before { content: fa-content($fa-var-cc-stripe); }\n.#{$fa-css-prefix}-cc-visa:before { content: fa-content($fa-var-cc-visa); }\n.#{$fa-css-prefix}-centercode:before { content: fa-content($fa-var-centercode); }\n.#{$fa-css-prefix}-centos:before { content: fa-content($fa-var-centos); }\n.#{$fa-css-prefix}-certificate:before { content: fa-content($fa-var-certificate); }\n.#{$fa-css-prefix}-chair:before { content: fa-content($fa-var-chair); }\n.#{$fa-css-prefix}-chalkboard:before { content: fa-content($fa-var-chalkboard); }\n.#{$fa-css-prefix}-chalkboard-teacher:before { content: fa-content($fa-var-chalkboard-teacher); }\n.#{$fa-css-prefix}-charging-station:before { content: fa-content($fa-var-charging-station); }\n.#{$fa-css-prefix}-chart-area:before { content: fa-content($fa-var-chart-area); }\n.#{$fa-css-prefix}-chart-bar:before { content: fa-content($fa-var-chart-bar); }\n.#{$fa-css-prefix}-chart-line:before { content: fa-content($fa-var-chart-line); }\n.#{$fa-css-prefix}-chart-pie:before { content: fa-content($fa-var-chart-pie); }\n.#{$fa-css-prefix}-check:before { content: fa-content($fa-var-check); }\n.#{$fa-css-prefix}-check-circle:before { content: fa-content($fa-var-check-circle); }\n.#{$fa-css-prefix}-check-double:before { content: fa-content($fa-var-check-double); }\n.#{$fa-css-prefix}-check-square:before { content: fa-content($fa-var-check-square); }\n.#{$fa-css-prefix}-cheese:before { content: fa-content($fa-var-cheese); }\n.#{$fa-css-prefix}-chess:before { content: fa-content($fa-var-chess); }\n.#{$fa-css-prefix}-chess-bishop:before { content: fa-content($fa-var-chess-bishop); }\n.#{$fa-css-prefix}-chess-board:before { content: fa-content($fa-var-chess-board); }\n.#{$fa-css-prefix}-chess-king:before { content: fa-content($fa-var-chess-king); }\n.#{$fa-css-prefix}-chess-knight:before { content: fa-content($fa-var-chess-knight); }\n.#{$fa-css-prefix}-chess-pawn:before { content: fa-content($fa-var-chess-pawn); }\n.#{$fa-css-prefix}-chess-queen:before { content: fa-content($fa-var-chess-queen); }\n.#{$fa-css-prefix}-chess-rook:before { content: fa-content($fa-var-chess-rook); }\n.#{$fa-css-prefix}-chevron-circle-down:before { content: fa-content($fa-var-chevron-circle-down); }\n.#{$fa-css-prefix}-chevron-circle-left:before { content: fa-content($fa-var-chevron-circle-left); }\n.#{$fa-css-prefix}-chevron-circle-right:before { content: fa-content($fa-var-chevron-circle-right); }\n.#{$fa-css-prefix}-chevron-circle-up:before { content: fa-content($fa-var-chevron-circle-up); }\n.#{$fa-css-prefix}-chevron-down:before { content: fa-content($fa-var-chevron-down); }\n.#{$fa-css-prefix}-chevron-left:before { content: fa-content($fa-var-chevron-left); }\n.#{$fa-css-prefix}-chevron-right:before { content: fa-content($fa-var-chevron-right); }\n.#{$fa-css-prefix}-chevron-up:before { content: fa-content($fa-var-chevron-up); }\n.#{$fa-css-prefix}-child:before { content: fa-content($fa-var-child); }\n.#{$fa-css-prefix}-chrome:before { content: fa-content($fa-var-chrome); }\n.#{$fa-css-prefix}-chromecast:before { content: fa-content($fa-var-chromecast); }\n.#{$fa-css-prefix}-church:before { content: fa-content($fa-var-church); }\n.#{$fa-css-prefix}-circle:before { content: fa-content($fa-var-circle); }\n.#{$fa-css-prefix}-circle-notch:before { content: fa-content($fa-var-circle-notch); }\n.#{$fa-css-prefix}-city:before { content: fa-content($fa-var-city); }\n.#{$fa-css-prefix}-clinic-medical:before { content: fa-content($fa-var-clinic-medical); }\n.#{$fa-css-prefix}-clipboard:before { content: fa-content($fa-var-clipboard); }\n.#{$fa-css-prefix}-clipboard-check:before { content: fa-content($fa-var-clipboard-check); }\n.#{$fa-css-prefix}-clipboard-list:before { content: fa-content($fa-var-clipboard-list); }\n.#{$fa-css-prefix}-clock:before { content: fa-content($fa-var-clock); }\n.#{$fa-css-prefix}-clone:before { content: fa-content($fa-var-clone); }\n.#{$fa-css-prefix}-closed-captioning:before { content: fa-content($fa-var-closed-captioning); }\n.#{$fa-css-prefix}-cloud:before { content: fa-content($fa-var-cloud); }\n.#{$fa-css-prefix}-cloud-download-alt:before { content: fa-content($fa-var-cloud-download-alt); }\n.#{$fa-css-prefix}-cloud-meatball:before { content: fa-content($fa-var-cloud-meatball); }\n.#{$fa-css-prefix}-cloud-moon:before { content: fa-content($fa-var-cloud-moon); }\n.#{$fa-css-prefix}-cloud-moon-rain:before { content: fa-content($fa-var-cloud-moon-rain); }\n.#{$fa-css-prefix}-cloud-rain:before { content: fa-content($fa-var-cloud-rain); }\n.#{$fa-css-prefix}-cloud-showers-heavy:before { content: fa-content($fa-var-cloud-showers-heavy); }\n.#{$fa-css-prefix}-cloud-sun:before { content: fa-content($fa-var-cloud-sun); }\n.#{$fa-css-prefix}-cloud-sun-rain:before { content: fa-content($fa-var-cloud-sun-rain); }\n.#{$fa-css-prefix}-cloud-upload-alt:before { content: fa-content($fa-var-cloud-upload-alt); }\n.#{$fa-css-prefix}-cloudscale:before { content: fa-content($fa-var-cloudscale); }\n.#{$fa-css-prefix}-cloudsmith:before { content: fa-content($fa-var-cloudsmith); }\n.#{$fa-css-prefix}-cloudversify:before { content: fa-content($fa-var-cloudversify); }\n.#{$fa-css-prefix}-cocktail:before { content: fa-content($fa-var-cocktail); }\n.#{$fa-css-prefix}-code:before { content: fa-content($fa-var-code); }\n.#{$fa-css-prefix}-code-branch:before { content: fa-content($fa-var-code-branch); }\n.#{$fa-css-prefix}-codepen:before { content: fa-content($fa-var-codepen); }\n.#{$fa-css-prefix}-codiepie:before { content: fa-content($fa-var-codiepie); }\n.#{$fa-css-prefix}-coffee:before { content: fa-content($fa-var-coffee); }\n.#{$fa-css-prefix}-cog:before { content: fa-content($fa-var-cog); }\n.#{$fa-css-prefix}-cogs:before { content: fa-content($fa-var-cogs); }\n.#{$fa-css-prefix}-coins:before { content: fa-content($fa-var-coins); }\n.#{$fa-css-prefix}-columns:before { content: fa-content($fa-var-columns); }\n.#{$fa-css-prefix}-comment:before { content: fa-content($fa-var-comment); }\n.#{$fa-css-prefix}-comment-alt:before { content: fa-content($fa-var-comment-alt); }\n.#{$fa-css-prefix}-comment-dollar:before { content: fa-content($fa-var-comment-dollar); }\n.#{$fa-css-prefix}-comment-dots:before { content: fa-content($fa-var-comment-dots); }\n.#{$fa-css-prefix}-comment-medical:before { content: fa-content($fa-var-comment-medical); }\n.#{$fa-css-prefix}-comment-slash:before { content: fa-content($fa-var-comment-slash); }\n.#{$fa-css-prefix}-comments:before { content: fa-content($fa-var-comments); }\n.#{$fa-css-prefix}-comments-dollar:before { content: fa-content($fa-var-comments-dollar); }\n.#{$fa-css-prefix}-compact-disc:before { content: fa-content($fa-var-compact-disc); }\n.#{$fa-css-prefix}-compass:before { content: fa-content($fa-var-compass); }\n.#{$fa-css-prefix}-compress:before { content: fa-content($fa-var-compress); }\n.#{$fa-css-prefix}-compress-arrows-alt:before { content: fa-content($fa-var-compress-arrows-alt); }\n.#{$fa-css-prefix}-concierge-bell:before { content: fa-content($fa-var-concierge-bell); }\n.#{$fa-css-prefix}-confluence:before { content: fa-content($fa-var-confluence); }\n.#{$fa-css-prefix}-connectdevelop:before { content: fa-content($fa-var-connectdevelop); }\n.#{$fa-css-prefix}-contao:before { content: fa-content($fa-var-contao); }\n.#{$fa-css-prefix}-cookie:before { content: fa-content($fa-var-cookie); }\n.#{$fa-css-prefix}-cookie-bite:before { content: fa-content($fa-var-cookie-bite); }\n.#{$fa-css-prefix}-copy:before { content: fa-content($fa-var-copy); }\n.#{$fa-css-prefix}-copyright:before { content: fa-content($fa-var-copyright); }\n.#{$fa-css-prefix}-cotton-bureau:before { content: fa-content($fa-var-cotton-bureau); }\n.#{$fa-css-prefix}-couch:before { content: fa-content($fa-var-couch); }\n.#{$fa-css-prefix}-cpanel:before { content: fa-content($fa-var-cpanel); }\n.#{$fa-css-prefix}-creative-commons:before { content: fa-content($fa-var-creative-commons); }\n.#{$fa-css-prefix}-creative-commons-by:before { content: fa-content($fa-var-creative-commons-by); }\n.#{$fa-css-prefix}-creative-commons-nc:before { content: fa-content($fa-var-creative-commons-nc); }\n.#{$fa-css-prefix}-creative-commons-nc-eu:before { content: fa-content($fa-var-creative-commons-nc-eu); }\n.#{$fa-css-prefix}-creative-commons-nc-jp:before { content: fa-content($fa-var-creative-commons-nc-jp); }\n.#{$fa-css-prefix}-creative-commons-nd:before { content: fa-content($fa-var-creative-commons-nd); }\n.#{$fa-css-prefix}-creative-commons-pd:before { content: fa-content($fa-var-creative-commons-pd); }\n.#{$fa-css-prefix}-creative-commons-pd-alt:before { content: fa-content($fa-var-creative-commons-pd-alt); }\n.#{$fa-css-prefix}-creative-commons-remix:before { content: fa-content($fa-var-creative-commons-remix); }\n.#{$fa-css-prefix}-creative-commons-sa:before { content: fa-content($fa-var-creative-commons-sa); }\n.#{$fa-css-prefix}-creative-commons-sampling:before { content: fa-content($fa-var-creative-commons-sampling); }\n.#{$fa-css-prefix}-creative-commons-sampling-plus:before { content: fa-content($fa-var-creative-commons-sampling-plus); }\n.#{$fa-css-prefix}-creative-commons-share:before { content: fa-content($fa-var-creative-commons-share); }\n.#{$fa-css-prefix}-creative-commons-zero:before { content: fa-content($fa-var-creative-commons-zero); }\n.#{$fa-css-prefix}-credit-card:before { content: fa-content($fa-var-credit-card); }\n.#{$fa-css-prefix}-critical-role:before { content: fa-content($fa-var-critical-role); }\n.#{$fa-css-prefix}-crop:before { content: fa-content($fa-var-crop); }\n.#{$fa-css-prefix}-crop-alt:before { content: fa-content($fa-var-crop-alt); }\n.#{$fa-css-prefix}-cross:before { content: fa-content($fa-var-cross); }\n.#{$fa-css-prefix}-crosshairs:before { content: fa-content($fa-var-crosshairs); }\n.#{$fa-css-prefix}-crow:before { content: fa-content($fa-var-crow); }\n.#{$fa-css-prefix}-crown:before { content: fa-content($fa-var-crown); }\n.#{$fa-css-prefix}-crutch:before { content: fa-content($fa-var-crutch); }\n.#{$fa-css-prefix}-css3:before { content: fa-content($fa-var-css3); }\n.#{$fa-css-prefix}-css3-alt:before { content: fa-content($fa-var-css3-alt); }\n.#{$fa-css-prefix}-cube:before { content: fa-content($fa-var-cube); }\n.#{$fa-css-prefix}-cubes:before { content: fa-content($fa-var-cubes); }\n.#{$fa-css-prefix}-cut:before { content: fa-content($fa-var-cut); }\n.#{$fa-css-prefix}-cuttlefish:before { content: fa-content($fa-var-cuttlefish); }\n.#{$fa-css-prefix}-d-and-d:before { content: fa-content($fa-var-d-and-d); }\n.#{$fa-css-prefix}-d-and-d-beyond:before { content: fa-content($fa-var-d-and-d-beyond); }\n.#{$fa-css-prefix}-dashcube:before { content: fa-content($fa-var-dashcube); }\n.#{$fa-css-prefix}-database:before { content: fa-content($fa-var-database); }\n.#{$fa-css-prefix}-deaf:before { content: fa-content($fa-var-deaf); }\n.#{$fa-css-prefix}-delicious:before { content: fa-content($fa-var-delicious); }\n.#{$fa-css-prefix}-democrat:before { content: fa-content($fa-var-democrat); }\n.#{$fa-css-prefix}-deploydog:before { content: fa-content($fa-var-deploydog); }\n.#{$fa-css-prefix}-deskpro:before { content: fa-content($fa-var-deskpro); }\n.#{$fa-css-prefix}-desktop:before { content: fa-content($fa-var-desktop); }\n.#{$fa-css-prefix}-dev:before { content: fa-content($fa-var-dev); }\n.#{$fa-css-prefix}-deviantart:before { content: fa-content($fa-var-deviantart); }\n.#{$fa-css-prefix}-dharmachakra:before { content: fa-content($fa-var-dharmachakra); }\n.#{$fa-css-prefix}-dhl:before { content: fa-content($fa-var-dhl); }\n.#{$fa-css-prefix}-diagnoses:before { content: fa-content($fa-var-diagnoses); }\n.#{$fa-css-prefix}-diaspora:before { content: fa-content($fa-var-diaspora); }\n.#{$fa-css-prefix}-dice:before { content: fa-content($fa-var-dice); }\n.#{$fa-css-prefix}-dice-d20:before { content: fa-content($fa-var-dice-d20); }\n.#{$fa-css-prefix}-dice-d6:before { content: fa-content($fa-var-dice-d6); }\n.#{$fa-css-prefix}-dice-five:before { content: fa-content($fa-var-dice-five); }\n.#{$fa-css-prefix}-dice-four:before { content: fa-content($fa-var-dice-four); }\n.#{$fa-css-prefix}-dice-one:before { content: fa-content($fa-var-dice-one); }\n.#{$fa-css-prefix}-dice-six:before { content: fa-content($fa-var-dice-six); }\n.#{$fa-css-prefix}-dice-three:before { content: fa-content($fa-var-dice-three); }\n.#{$fa-css-prefix}-dice-two:before { content: fa-content($fa-var-dice-two); }\n.#{$fa-css-prefix}-digg:before { content: fa-content($fa-var-digg); }\n.#{$fa-css-prefix}-digital-ocean:before { content: fa-content($fa-var-digital-ocean); }\n.#{$fa-css-prefix}-digital-tachograph:before { content: fa-content($fa-var-digital-tachograph); }\n.#{$fa-css-prefix}-directions:before { content: fa-content($fa-var-directions); }\n.#{$fa-css-prefix}-discord:before { content: fa-content($fa-var-discord); }\n.#{$fa-css-prefix}-discourse:before { content: fa-content($fa-var-discourse); }\n.#{$fa-css-prefix}-divide:before { content: fa-content($fa-var-divide); }\n.#{$fa-css-prefix}-dizzy:before { content: fa-content($fa-var-dizzy); }\n.#{$fa-css-prefix}-dna:before { content: fa-content($fa-var-dna); }\n.#{$fa-css-prefix}-dochub:before { content: fa-content($fa-var-dochub); }\n.#{$fa-css-prefix}-docker:before { content: fa-content($fa-var-docker); }\n.#{$fa-css-prefix}-dog:before { content: fa-content($fa-var-dog); }\n.#{$fa-css-prefix}-dollar-sign:before { content: fa-content($fa-var-dollar-sign); }\n.#{$fa-css-prefix}-dolly:before { content: fa-content($fa-var-dolly); }\n.#{$fa-css-prefix}-dolly-flatbed:before { content: fa-content($fa-var-dolly-flatbed); }\n.#{$fa-css-prefix}-donate:before { content: fa-content($fa-var-donate); }\n.#{$fa-css-prefix}-door-closed:before { content: fa-content($fa-var-door-closed); }\n.#{$fa-css-prefix}-door-open:before { content: fa-content($fa-var-door-open); }\n.#{$fa-css-prefix}-dot-circle:before { content: fa-content($fa-var-dot-circle); }\n.#{$fa-css-prefix}-dove:before { content: fa-content($fa-var-dove); }\n.#{$fa-css-prefix}-download:before { content: fa-content($fa-var-download); }\n.#{$fa-css-prefix}-draft2digital:before { content: fa-content($fa-var-draft2digital); }\n.#{$fa-css-prefix}-drafting-compass:before { content: fa-content($fa-var-drafting-compass); }\n.#{$fa-css-prefix}-dragon:before { content: fa-content($fa-var-dragon); }\n.#{$fa-css-prefix}-draw-polygon:before { content: fa-content($fa-var-draw-polygon); }\n.#{$fa-css-prefix}-dribbble:before { content: fa-content($fa-var-dribbble); }\n.#{$fa-css-prefix}-dribbble-square:before { content: fa-content($fa-var-dribbble-square); }\n.#{$fa-css-prefix}-dropbox:before { content: fa-content($fa-var-dropbox); }\n.#{$fa-css-prefix}-drum:before { content: fa-content($fa-var-drum); }\n.#{$fa-css-prefix}-drum-steelpan:before { content: fa-content($fa-var-drum-steelpan); }\n.#{$fa-css-prefix}-drumstick-bite:before { content: fa-content($fa-var-drumstick-bite); }\n.#{$fa-css-prefix}-drupal:before { content: fa-content($fa-var-drupal); }\n.#{$fa-css-prefix}-dumbbell:before { content: fa-content($fa-var-dumbbell); }\n.#{$fa-css-prefix}-dumpster:before { content: fa-content($fa-var-dumpster); }\n.#{$fa-css-prefix}-dumpster-fire:before { content: fa-content($fa-var-dumpster-fire); }\n.#{$fa-css-prefix}-dungeon:before { content: fa-content($fa-var-dungeon); }\n.#{$fa-css-prefix}-dyalog:before { content: fa-content($fa-var-dyalog); }\n.#{$fa-css-prefix}-earlybirds:before { content: fa-content($fa-var-earlybirds); }\n.#{$fa-css-prefix}-ebay:before { content: fa-content($fa-var-ebay); }\n.#{$fa-css-prefix}-edge:before { content: fa-content($fa-var-edge); }\n.#{$fa-css-prefix}-edit:before { content: fa-content($fa-var-edit); }\n.#{$fa-css-prefix}-egg:before { content: fa-content($fa-var-egg); }\n.#{$fa-css-prefix}-eject:before { content: fa-content($fa-var-eject); }\n.#{$fa-css-prefix}-elementor:before { content: fa-content($fa-var-elementor); }\n.#{$fa-css-prefix}-ellipsis-h:before { content: fa-content($fa-var-ellipsis-h); }\n.#{$fa-css-prefix}-ellipsis-v:before { content: fa-content($fa-var-ellipsis-v); }\n.#{$fa-css-prefix}-ello:before { content: fa-content($fa-var-ello); }\n.#{$fa-css-prefix}-ember:before { content: fa-content($fa-var-ember); }\n.#{$fa-css-prefix}-empire:before { content: fa-content($fa-var-empire); }\n.#{$fa-css-prefix}-envelope:before { content: fa-content($fa-var-envelope); }\n.#{$fa-css-prefix}-envelope-open:before { content: fa-content($fa-var-envelope-open); }\n.#{$fa-css-prefix}-envelope-open-text:before { content: fa-content($fa-var-envelope-open-text); }\n.#{$fa-css-prefix}-envelope-square:before { content: fa-content($fa-var-envelope-square); }\n.#{$fa-css-prefix}-envira:before { content: fa-content($fa-var-envira); }\n.#{$fa-css-prefix}-equals:before { content: fa-content($fa-var-equals); }\n.#{$fa-css-prefix}-eraser:before { content: fa-content($fa-var-eraser); }\n.#{$fa-css-prefix}-erlang:before { content: fa-content($fa-var-erlang); }\n.#{$fa-css-prefix}-ethereum:before { content: fa-content($fa-var-ethereum); }\n.#{$fa-css-prefix}-ethernet:before { content: fa-content($fa-var-ethernet); }\n.#{$fa-css-prefix}-etsy:before { content: fa-content($fa-var-etsy); }\n.#{$fa-css-prefix}-euro-sign:before { content: fa-content($fa-var-euro-sign); }\n.#{$fa-css-prefix}-evernote:before { content: fa-content($fa-var-evernote); }\n.#{$fa-css-prefix}-exchange-alt:before { content: fa-content($fa-var-exchange-alt); }\n.#{$fa-css-prefix}-exclamation:before { content: fa-content($fa-var-exclamation); }\n.#{$fa-css-prefix}-exclamation-circle:before { content: fa-content($fa-var-exclamation-circle); }\n.#{$fa-css-prefix}-exclamation-triangle:before { content: fa-content($fa-var-exclamation-triangle); }\n.#{$fa-css-prefix}-expand:before { content: fa-content($fa-var-expand); }\n.#{$fa-css-prefix}-expand-arrows-alt:before { content: fa-content($fa-var-expand-arrows-alt); }\n.#{$fa-css-prefix}-expeditedssl:before { content: fa-content($fa-var-expeditedssl); }\n.#{$fa-css-prefix}-external-link-alt:before { content: fa-content($fa-var-external-link-alt); }\n.#{$fa-css-prefix}-external-link-square-alt:before { content: fa-content($fa-var-external-link-square-alt); }\n.#{$fa-css-prefix}-eye:before { content: fa-content($fa-var-eye); }\n.#{$fa-css-prefix}-eye-dropper:before { content: fa-content($fa-var-eye-dropper); }\n.#{$fa-css-prefix}-eye-slash:before { content: fa-content($fa-var-eye-slash); }\n.#{$fa-css-prefix}-facebook:before { content: fa-content($fa-var-facebook); }\n.#{$fa-css-prefix}-facebook-f:before { content: fa-content($fa-var-facebook-f); }\n.#{$fa-css-prefix}-facebook-messenger:before { content: fa-content($fa-var-facebook-messenger); }\n.#{$fa-css-prefix}-facebook-square:before { content: fa-content($fa-var-facebook-square); }\n.#{$fa-css-prefix}-fan:before { content: fa-content($fa-var-fan); }\n.#{$fa-css-prefix}-fantasy-flight-games:before { content: fa-content($fa-var-fantasy-flight-games); }\n.#{$fa-css-prefix}-fast-backward:before { content: fa-content($fa-var-fast-backward); }\n.#{$fa-css-prefix}-fast-forward:before { content: fa-content($fa-var-fast-forward); }\n.#{$fa-css-prefix}-fax:before { content: fa-content($fa-var-fax); }\n.#{$fa-css-prefix}-feather:before { content: fa-content($fa-var-feather); }\n.#{$fa-css-prefix}-feather-alt:before { content: fa-content($fa-var-feather-alt); }\n.#{$fa-css-prefix}-fedex:before { content: fa-content($fa-var-fedex); }\n.#{$fa-css-prefix}-fedora:before { content: fa-content($fa-var-fedora); }\n.#{$fa-css-prefix}-female:before { content: fa-content($fa-var-female); }\n.#{$fa-css-prefix}-fighter-jet:before { content: fa-content($fa-var-fighter-jet); }\n.#{$fa-css-prefix}-figma:before { content: fa-content($fa-var-figma); }\n.#{$fa-css-prefix}-file:before { content: fa-content($fa-var-file); }\n.#{$fa-css-prefix}-file-alt:before { content: fa-content($fa-var-file-alt); }\n.#{$fa-css-prefix}-file-archive:before { content: fa-content($fa-var-file-archive); }\n.#{$fa-css-prefix}-file-audio:before { content: fa-content($fa-var-file-audio); }\n.#{$fa-css-prefix}-file-code:before { content: fa-content($fa-var-file-code); }\n.#{$fa-css-prefix}-file-contract:before { content: fa-content($fa-var-file-contract); }\n.#{$fa-css-prefix}-file-csv:before { content: fa-content($fa-var-file-csv); }\n.#{$fa-css-prefix}-file-download:before { content: fa-content($fa-var-file-download); }\n.#{$fa-css-prefix}-file-excel:before { content: fa-content($fa-var-file-excel); }\n.#{$fa-css-prefix}-file-export:before { content: fa-content($fa-var-file-export); }\n.#{$fa-css-prefix}-file-image:before { content: fa-content($fa-var-file-image); }\n.#{$fa-css-prefix}-file-import:before { content: fa-content($fa-var-file-import); }\n.#{$fa-css-prefix}-file-invoice:before { content: fa-content($fa-var-file-invoice); }\n.#{$fa-css-prefix}-file-invoice-dollar:before { content: fa-content($fa-var-file-invoice-dollar); }\n.#{$fa-css-prefix}-file-medical:before { content: fa-content($fa-var-file-medical); }\n.#{$fa-css-prefix}-file-medical-alt:before { content: fa-content($fa-var-file-medical-alt); }\n.#{$fa-css-prefix}-file-pdf:before { content: fa-content($fa-var-file-pdf); }\n.#{$fa-css-prefix}-file-powerpoint:before { content: fa-content($fa-var-file-powerpoint); }\n.#{$fa-css-prefix}-file-prescription:before { content: fa-content($fa-var-file-prescription); }\n.#{$fa-css-prefix}-file-signature:before { content: fa-content($fa-var-file-signature); }\n.#{$fa-css-prefix}-file-upload:before { content: fa-content($fa-var-file-upload); }\n.#{$fa-css-prefix}-file-video:before { content: fa-content($fa-var-file-video); }\n.#{$fa-css-prefix}-file-word:before { content: fa-content($fa-var-file-word); }\n.#{$fa-css-prefix}-fill:before { content: fa-content($fa-var-fill); }\n.#{$fa-css-prefix}-fill-drip:before { content: fa-content($fa-var-fill-drip); }\n.#{$fa-css-prefix}-film:before { content: fa-content($fa-var-film); }\n.#{$fa-css-prefix}-filter:before { content: fa-content($fa-var-filter); }\n.#{$fa-css-prefix}-fingerprint:before { content: fa-content($fa-var-fingerprint); }\n.#{$fa-css-prefix}-fire:before { content: fa-content($fa-var-fire); }\n.#{$fa-css-prefix}-fire-alt:before { content: fa-content($fa-var-fire-alt); }\n.#{$fa-css-prefix}-fire-extinguisher:before { content: fa-content($fa-var-fire-extinguisher); }\n.#{$fa-css-prefix}-firefox:before { content: fa-content($fa-var-firefox); }\n.#{$fa-css-prefix}-first-aid:before { content: fa-content($fa-var-first-aid); }\n.#{$fa-css-prefix}-first-order:before { content: fa-content($fa-var-first-order); }\n.#{$fa-css-prefix}-first-order-alt:before { content: fa-content($fa-var-first-order-alt); }\n.#{$fa-css-prefix}-firstdraft:before { content: fa-content($fa-var-firstdraft); }\n.#{$fa-css-prefix}-fish:before { content: fa-content($fa-var-fish); }\n.#{$fa-css-prefix}-fist-raised:before { content: fa-content($fa-var-fist-raised); }\n.#{$fa-css-prefix}-flag:before { content: fa-content($fa-var-flag); }\n.#{$fa-css-prefix}-flag-checkered:before { content: fa-content($fa-var-flag-checkered); }\n.#{$fa-css-prefix}-flag-usa:before { content: fa-content($fa-var-flag-usa); }\n.#{$fa-css-prefix}-flask:before { content: fa-content($fa-var-flask); }\n.#{$fa-css-prefix}-flickr:before { content: fa-content($fa-var-flickr); }\n.#{$fa-css-prefix}-flipboard:before { content: fa-content($fa-var-flipboard); }\n.#{$fa-css-prefix}-flushed:before { content: fa-content($fa-var-flushed); }\n.#{$fa-css-prefix}-fly:before { content: fa-content($fa-var-fly); }\n.#{$fa-css-prefix}-folder:before { content: fa-content($fa-var-folder); }\n.#{$fa-css-prefix}-folder-minus:before { content: fa-content($fa-var-folder-minus); }\n.#{$fa-css-prefix}-folder-open:before { content: fa-content($fa-var-folder-open); }\n.#{$fa-css-prefix}-folder-plus:before { content: fa-content($fa-var-folder-plus); }\n.#{$fa-css-prefix}-font:before { content: fa-content($fa-var-font); }\n.#{$fa-css-prefix}-font-awesome:before { content: fa-content($fa-var-font-awesome); }\n.#{$fa-css-prefix}-font-awesome-alt:before { content: fa-content($fa-var-font-awesome-alt); }\n.#{$fa-css-prefix}-font-awesome-flag:before { content: fa-content($fa-var-font-awesome-flag); }\n.#{$fa-css-prefix}-font-awesome-logo-full:before { content: fa-content($fa-var-font-awesome-logo-full); }\n.#{$fa-css-prefix}-fonticons:before { content: fa-content($fa-var-fonticons); }\n.#{$fa-css-prefix}-fonticons-fi:before { content: fa-content($fa-var-fonticons-fi); }\n.#{$fa-css-prefix}-football-ball:before { content: fa-content($fa-var-football-ball); }\n.#{$fa-css-prefix}-fort-awesome:before { content: fa-content($fa-var-fort-awesome); }\n.#{$fa-css-prefix}-fort-awesome-alt:before { content: fa-content($fa-var-fort-awesome-alt); }\n.#{$fa-css-prefix}-forumbee:before { content: fa-content($fa-var-forumbee); }\n.#{$fa-css-prefix}-forward:before { content: fa-content($fa-var-forward); }\n.#{$fa-css-prefix}-foursquare:before { content: fa-content($fa-var-foursquare); }\n.#{$fa-css-prefix}-free-code-camp:before { content: fa-content($fa-var-free-code-camp); }\n.#{$fa-css-prefix}-freebsd:before { content: fa-content($fa-var-freebsd); }\n.#{$fa-css-prefix}-frog:before { content: fa-content($fa-var-frog); }\n.#{$fa-css-prefix}-frown:before { content: fa-content($fa-var-frown); }\n.#{$fa-css-prefix}-frown-open:before { content: fa-content($fa-var-frown-open); }\n.#{$fa-css-prefix}-fulcrum:before { content: fa-content($fa-var-fulcrum); }\n.#{$fa-css-prefix}-funnel-dollar:before { content: fa-content($fa-var-funnel-dollar); }\n.#{$fa-css-prefix}-futbol:before { content: fa-content($fa-var-futbol); }\n.#{$fa-css-prefix}-galactic-republic:before { content: fa-content($fa-var-galactic-republic); }\n.#{$fa-css-prefix}-galactic-senate:before { content: fa-content($fa-var-galactic-senate); }\n.#{$fa-css-prefix}-gamepad:before { content: fa-content($fa-var-gamepad); }\n.#{$fa-css-prefix}-gas-pump:before { content: fa-content($fa-var-gas-pump); }\n.#{$fa-css-prefix}-gavel:before { content: fa-content($fa-var-gavel); }\n.#{$fa-css-prefix}-gem:before { content: fa-content($fa-var-gem); }\n.#{$fa-css-prefix}-genderless:before { content: fa-content($fa-var-genderless); }\n.#{$fa-css-prefix}-get-pocket:before { content: fa-content($fa-var-get-pocket); }\n.#{$fa-css-prefix}-gg:before { content: fa-content($fa-var-gg); }\n.#{$fa-css-prefix}-gg-circle:before { content: fa-content($fa-var-gg-circle); }\n.#{$fa-css-prefix}-ghost:before { content: fa-content($fa-var-ghost); }\n.#{$fa-css-prefix}-gift:before { content: fa-content($fa-var-gift); }\n.#{$fa-css-prefix}-gifts:before { content: fa-content($fa-var-gifts); }\n.#{$fa-css-prefix}-git:before { content: fa-content($fa-var-git); }\n.#{$fa-css-prefix}-git-alt:before { content: fa-content($fa-var-git-alt); }\n.#{$fa-css-prefix}-git-square:before { content: fa-content($fa-var-git-square); }\n.#{$fa-css-prefix}-github:before { content: fa-content($fa-var-github); }\n.#{$fa-css-prefix}-github-alt:before { content: fa-content($fa-var-github-alt); }\n.#{$fa-css-prefix}-github-square:before { content: fa-content($fa-var-github-square); }\n.#{$fa-css-prefix}-gitkraken:before { content: fa-content($fa-var-gitkraken); }\n.#{$fa-css-prefix}-gitlab:before { content: fa-content($fa-var-gitlab); }\n.#{$fa-css-prefix}-gitter:before { content: fa-content($fa-var-gitter); }\n.#{$fa-css-prefix}-glass-cheers:before { content: fa-content($fa-var-glass-cheers); }\n.#{$fa-css-prefix}-glass-martini:before { content: fa-content($fa-var-glass-martini); }\n.#{$fa-css-prefix}-glass-martini-alt:before { content: fa-content($fa-var-glass-martini-alt); }\n.#{$fa-css-prefix}-glass-whiskey:before { content: fa-content($fa-var-glass-whiskey); }\n.#{$fa-css-prefix}-glasses:before { content: fa-content($fa-var-glasses); }\n.#{$fa-css-prefix}-glide:before { content: fa-content($fa-var-glide); }\n.#{$fa-css-prefix}-glide-g:before { content: fa-content($fa-var-glide-g); }\n.#{$fa-css-prefix}-globe:before { content: fa-content($fa-var-globe); }\n.#{$fa-css-prefix}-globe-africa:before { content: fa-content($fa-var-globe-africa); }\n.#{$fa-css-prefix}-globe-americas:before { content: fa-content($fa-var-globe-americas); }\n.#{$fa-css-prefix}-globe-asia:before { content: fa-content($fa-var-globe-asia); }\n.#{$fa-css-prefix}-globe-europe:before { content: fa-content($fa-var-globe-europe); }\n.#{$fa-css-prefix}-gofore:before { content: fa-content($fa-var-gofore); }\n.#{$fa-css-prefix}-golf-ball:before { content: fa-content($fa-var-golf-ball); }\n.#{$fa-css-prefix}-goodreads:before { content: fa-content($fa-var-goodreads); }\n.#{$fa-css-prefix}-goodreads-g:before { content: fa-content($fa-var-goodreads-g); }\n.#{$fa-css-prefix}-google:before { content: fa-content($fa-var-google); }\n.#{$fa-css-prefix}-google-drive:before { content: fa-content($fa-var-google-drive); }\n.#{$fa-css-prefix}-google-play:before { content: fa-content($fa-var-google-play); }\n.#{$fa-css-prefix}-google-plus:before { content: fa-content($fa-var-google-plus); }\n.#{$fa-css-prefix}-google-plus-g:before { content: fa-content($fa-var-google-plus-g); }\n.#{$fa-css-prefix}-google-plus-square:before { content: fa-content($fa-var-google-plus-square); }\n.#{$fa-css-prefix}-google-wallet:before { content: fa-content($fa-var-google-wallet); }\n.#{$fa-css-prefix}-gopuram:before { content: fa-content($fa-var-gopuram); }\n.#{$fa-css-prefix}-graduation-cap:before { content: fa-content($fa-var-graduation-cap); }\n.#{$fa-css-prefix}-gratipay:before { content: fa-content($fa-var-gratipay); }\n.#{$fa-css-prefix}-grav:before { content: fa-content($fa-var-grav); }\n.#{$fa-css-prefix}-greater-than:before { content: fa-content($fa-var-greater-than); }\n.#{$fa-css-prefix}-greater-than-equal:before { content: fa-content($fa-var-greater-than-equal); }\n.#{$fa-css-prefix}-grimace:before { content: fa-content($fa-var-grimace); }\n.#{$fa-css-prefix}-grin:before { content: fa-content($fa-var-grin); }\n.#{$fa-css-prefix}-grin-alt:before { content: fa-content($fa-var-grin-alt); }\n.#{$fa-css-prefix}-grin-beam:before { content: fa-content($fa-var-grin-beam); }\n.#{$fa-css-prefix}-grin-beam-sweat:before { content: fa-content($fa-var-grin-beam-sweat); }\n.#{$fa-css-prefix}-grin-hearts:before { content: fa-content($fa-var-grin-hearts); }\n.#{$fa-css-prefix}-grin-squint:before { content: fa-content($fa-var-grin-squint); }\n.#{$fa-css-prefix}-grin-squint-tears:before { content: fa-content($fa-var-grin-squint-tears); }\n.#{$fa-css-prefix}-grin-stars:before { content: fa-content($fa-var-grin-stars); }\n.#{$fa-css-prefix}-grin-tears:before { content: fa-content($fa-var-grin-tears); }\n.#{$fa-css-prefix}-grin-tongue:before { content: fa-content($fa-var-grin-tongue); }\n.#{$fa-css-prefix}-grin-tongue-squint:before { content: fa-content($fa-var-grin-tongue-squint); }\n.#{$fa-css-prefix}-grin-tongue-wink:before { content: fa-content($fa-var-grin-tongue-wink); }\n.#{$fa-css-prefix}-grin-wink:before { content: fa-content($fa-var-grin-wink); }\n.#{$fa-css-prefix}-grip-horizontal:before { content: fa-content($fa-var-grip-horizontal); }\n.#{$fa-css-prefix}-grip-lines:before { content: fa-content($fa-var-grip-lines); }\n.#{$fa-css-prefix}-grip-lines-vertical:before { content: fa-content($fa-var-grip-lines-vertical); }\n.#{$fa-css-prefix}-grip-vertical:before { content: fa-content($fa-var-grip-vertical); }\n.#{$fa-css-prefix}-gripfire:before { content: fa-content($fa-var-gripfire); }\n.#{$fa-css-prefix}-grunt:before { content: fa-content($fa-var-grunt); }\n.#{$fa-css-prefix}-guitar:before { content: fa-content($fa-var-guitar); }\n.#{$fa-css-prefix}-gulp:before { content: fa-content($fa-var-gulp); }\n.#{$fa-css-prefix}-h-square:before { content: fa-content($fa-var-h-square); }\n.#{$fa-css-prefix}-hacker-news:before { content: fa-content($fa-var-hacker-news); }\n.#{$fa-css-prefix}-hacker-news-square:before { content: fa-content($fa-var-hacker-news-square); }\n.#{$fa-css-prefix}-hackerrank:before { content: fa-content($fa-var-hackerrank); }\n.#{$fa-css-prefix}-hamburger:before { content: fa-content($fa-var-hamburger); }\n.#{$fa-css-prefix}-hammer:before { content: fa-content($fa-var-hammer); }\n.#{$fa-css-prefix}-hamsa:before { content: fa-content($fa-var-hamsa); }\n.#{$fa-css-prefix}-hand-holding:before { content: fa-content($fa-var-hand-holding); }\n.#{$fa-css-prefix}-hand-holding-heart:before { content: fa-content($fa-var-hand-holding-heart); }\n.#{$fa-css-prefix}-hand-holding-usd:before { content: fa-content($fa-var-hand-holding-usd); }\n.#{$fa-css-prefix}-hand-lizard:before { content: fa-content($fa-var-hand-lizard); }\n.#{$fa-css-prefix}-hand-middle-finger:before { content: fa-content($fa-var-hand-middle-finger); }\n.#{$fa-css-prefix}-hand-paper:before { content: fa-content($fa-var-hand-paper); }\n.#{$fa-css-prefix}-hand-peace:before { content: fa-content($fa-var-hand-peace); }\n.#{$fa-css-prefix}-hand-point-down:before { content: fa-content($fa-var-hand-point-down); }\n.#{$fa-css-prefix}-hand-point-left:before { content: fa-content($fa-var-hand-point-left); }\n.#{$fa-css-prefix}-hand-point-right:before { content: fa-content($fa-var-hand-point-right); }\n.#{$fa-css-prefix}-hand-point-up:before { content: fa-content($fa-var-hand-point-up); }\n.#{$fa-css-prefix}-hand-pointer:before { content: fa-content($fa-var-hand-pointer); }\n.#{$fa-css-prefix}-hand-rock:before { content: fa-content($fa-var-hand-rock); }\n.#{$fa-css-prefix}-hand-scissors:before { content: fa-content($fa-var-hand-scissors); }\n.#{$fa-css-prefix}-hand-spock:before { content: fa-content($fa-var-hand-spock); }\n.#{$fa-css-prefix}-hands:before { content: fa-content($fa-var-hands); }\n.#{$fa-css-prefix}-hands-helping:before { content: fa-content($fa-var-hands-helping); }\n.#{$fa-css-prefix}-handshake:before { content: fa-content($fa-var-handshake); }\n.#{$fa-css-prefix}-hanukiah:before { content: fa-content($fa-var-hanukiah); }\n.#{$fa-css-prefix}-hard-hat:before { content: fa-content($fa-var-hard-hat); }\n.#{$fa-css-prefix}-hashtag:before { content: fa-content($fa-var-hashtag); }\n.#{$fa-css-prefix}-hat-wizard:before { content: fa-content($fa-var-hat-wizard); }\n.#{$fa-css-prefix}-haykal:before { content: fa-content($fa-var-haykal); }\n.#{$fa-css-prefix}-hdd:before { content: fa-content($fa-var-hdd); }\n.#{$fa-css-prefix}-heading:before { content: fa-content($fa-var-heading); }\n.#{$fa-css-prefix}-headphones:before { content: fa-content($fa-var-headphones); }\n.#{$fa-css-prefix}-headphones-alt:before { content: fa-content($fa-var-headphones-alt); }\n.#{$fa-css-prefix}-headset:before { content: fa-content($fa-var-headset); }\n.#{$fa-css-prefix}-heart:before { content: fa-content($fa-var-heart); }\n.#{$fa-css-prefix}-heart-broken:before { content: fa-content($fa-var-heart-broken); }\n.#{$fa-css-prefix}-heartbeat:before { content: fa-content($fa-var-heartbeat); }\n.#{$fa-css-prefix}-helicopter:before { content: fa-content($fa-var-helicopter); }\n.#{$fa-css-prefix}-highlighter:before { content: fa-content($fa-var-highlighter); }\n.#{$fa-css-prefix}-hiking:before { content: fa-content($fa-var-hiking); }\n.#{$fa-css-prefix}-hippo:before { content: fa-content($fa-var-hippo); }\n.#{$fa-css-prefix}-hips:before { content: fa-content($fa-var-hips); }\n.#{$fa-css-prefix}-hire-a-helper:before { content: fa-content($fa-var-hire-a-helper); }\n.#{$fa-css-prefix}-history:before { content: fa-content($fa-var-history); }\n.#{$fa-css-prefix}-hockey-puck:before { content: fa-content($fa-var-hockey-puck); }\n.#{$fa-css-prefix}-holly-berry:before { content: fa-content($fa-var-holly-berry); }\n.#{$fa-css-prefix}-home:before { content: fa-content($fa-var-home); }\n.#{$fa-css-prefix}-hooli:before { content: fa-content($fa-var-hooli); }\n.#{$fa-css-prefix}-hornbill:before { content: fa-content($fa-var-hornbill); }\n.#{$fa-css-prefix}-horse:before { content: fa-content($fa-var-horse); }\n.#{$fa-css-prefix}-horse-head:before { content: fa-content($fa-var-horse-head); }\n.#{$fa-css-prefix}-hospital:before { content: fa-content($fa-var-hospital); }\n.#{$fa-css-prefix}-hospital-alt:before { content: fa-content($fa-var-hospital-alt); }\n.#{$fa-css-prefix}-hospital-symbol:before { content: fa-content($fa-var-hospital-symbol); }\n.#{$fa-css-prefix}-hot-tub:before { content: fa-content($fa-var-hot-tub); }\n.#{$fa-css-prefix}-hotdog:before { content: fa-content($fa-var-hotdog); }\n.#{$fa-css-prefix}-hotel:before { content: fa-content($fa-var-hotel); }\n.#{$fa-css-prefix}-hotjar:before { content: fa-content($fa-var-hotjar); }\n.#{$fa-css-prefix}-hourglass:before { content: fa-content($fa-var-hourglass); }\n.#{$fa-css-prefix}-hourglass-end:before { content: fa-content($fa-var-hourglass-end); }\n.#{$fa-css-prefix}-hourglass-half:before { content: fa-content($fa-var-hourglass-half); }\n.#{$fa-css-prefix}-hourglass-start:before { content: fa-content($fa-var-hourglass-start); }\n.#{$fa-css-prefix}-house-damage:before { content: fa-content($fa-var-house-damage); }\n.#{$fa-css-prefix}-houzz:before { content: fa-content($fa-var-houzz); }\n.#{$fa-css-prefix}-hryvnia:before { content: fa-content($fa-var-hryvnia); }\n.#{$fa-css-prefix}-html5:before { content: fa-content($fa-var-html5); }\n.#{$fa-css-prefix}-hubspot:before { content: fa-content($fa-var-hubspot); }\n.#{$fa-css-prefix}-i-cursor:before { content: fa-content($fa-var-i-cursor); }\n.#{$fa-css-prefix}-ice-cream:before { content: fa-content($fa-var-ice-cream); }\n.#{$fa-css-prefix}-icicles:before { content: fa-content($fa-var-icicles); }\n.#{$fa-css-prefix}-icons:before { content: fa-content($fa-var-icons); }\n.#{$fa-css-prefix}-id-badge:before { content: fa-content($fa-var-id-badge); }\n.#{$fa-css-prefix}-id-card:before { content: fa-content($fa-var-id-card); }\n.#{$fa-css-prefix}-id-card-alt:before { content: fa-content($fa-var-id-card-alt); }\n.#{$fa-css-prefix}-igloo:before { content: fa-content($fa-var-igloo); }\n.#{$fa-css-prefix}-image:before { content: fa-content($fa-var-image); }\n.#{$fa-css-prefix}-images:before { content: fa-content($fa-var-images); }\n.#{$fa-css-prefix}-imdb:before { content: fa-content($fa-var-imdb); }\n.#{$fa-css-prefix}-inbox:before { content: fa-content($fa-var-inbox); }\n.#{$fa-css-prefix}-indent:before { content: fa-content($fa-var-indent); }\n.#{$fa-css-prefix}-industry:before { content: fa-content($fa-var-industry); }\n.#{$fa-css-prefix}-infinity:before { content: fa-content($fa-var-infinity); }\n.#{$fa-css-prefix}-info:before { content: fa-content($fa-var-info); }\n.#{$fa-css-prefix}-info-circle:before { content: fa-content($fa-var-info-circle); }\n.#{$fa-css-prefix}-instagram:before { content: fa-content($fa-var-instagram); }\n.#{$fa-css-prefix}-intercom:before { content: fa-content($fa-var-intercom); }\n.#{$fa-css-prefix}-internet-explorer:before { content: fa-content($fa-var-internet-explorer); }\n.#{$fa-css-prefix}-invision:before { content: fa-content($fa-var-invision); }\n.#{$fa-css-prefix}-ioxhost:before { content: fa-content($fa-var-ioxhost); }\n.#{$fa-css-prefix}-italic:before { content: fa-content($fa-var-italic); }\n.#{$fa-css-prefix}-itch-io:before { content: fa-content($fa-var-itch-io); }\n.#{$fa-css-prefix}-itunes:before { content: fa-content($fa-var-itunes); }\n.#{$fa-css-prefix}-itunes-note:before { content: fa-content($fa-var-itunes-note); }\n.#{$fa-css-prefix}-java:before { content: fa-content($fa-var-java); }\n.#{$fa-css-prefix}-jedi:before { content: fa-content($fa-var-jedi); }\n.#{$fa-css-prefix}-jedi-order:before { content: fa-content($fa-var-jedi-order); }\n.#{$fa-css-prefix}-jenkins:before { content: fa-content($fa-var-jenkins); }\n.#{$fa-css-prefix}-jira:before { content: fa-content($fa-var-jira); }\n.#{$fa-css-prefix}-joget:before { content: fa-content($fa-var-joget); }\n.#{$fa-css-prefix}-joint:before { content: fa-content($fa-var-joint); }\n.#{$fa-css-prefix}-joomla:before { content: fa-content($fa-var-joomla); }\n.#{$fa-css-prefix}-journal-whills:before { content: fa-content($fa-var-journal-whills); }\n.#{$fa-css-prefix}-js:before { content: fa-content($fa-var-js); }\n.#{$fa-css-prefix}-js-square:before { content: fa-content($fa-var-js-square); }\n.#{$fa-css-prefix}-jsfiddle:before { content: fa-content($fa-var-jsfiddle); }\n.#{$fa-css-prefix}-kaaba:before { content: fa-content($fa-var-kaaba); }\n.#{$fa-css-prefix}-kaggle:before { content: fa-content($fa-var-kaggle); }\n.#{$fa-css-prefix}-key:before { content: fa-content($fa-var-key); }\n.#{$fa-css-prefix}-keybase:before { content: fa-content($fa-var-keybase); }\n.#{$fa-css-prefix}-keyboard:before { content: fa-content($fa-var-keyboard); }\n.#{$fa-css-prefix}-keycdn:before { content: fa-content($fa-var-keycdn); }\n.#{$fa-css-prefix}-khanda:before { content: fa-content($fa-var-khanda); }\n.#{$fa-css-prefix}-kickstarter:before { content: fa-content($fa-var-kickstarter); }\n.#{$fa-css-prefix}-kickstarter-k:before { content: fa-content($fa-var-kickstarter-k); }\n.#{$fa-css-prefix}-kiss:before { content: fa-content($fa-var-kiss); }\n.#{$fa-css-prefix}-kiss-beam:before { content: fa-content($fa-var-kiss-beam); }\n.#{$fa-css-prefix}-kiss-wink-heart:before { content: fa-content($fa-var-kiss-wink-heart); }\n.#{$fa-css-prefix}-kiwi-bird:before { content: fa-content($fa-var-kiwi-bird); }\n.#{$fa-css-prefix}-korvue:before { content: fa-content($fa-var-korvue); }\n.#{$fa-css-prefix}-landmark:before { content: fa-content($fa-var-landmark); }\n.#{$fa-css-prefix}-language:before { content: fa-content($fa-var-language); }\n.#{$fa-css-prefix}-laptop:before { content: fa-content($fa-var-laptop); }\n.#{$fa-css-prefix}-laptop-code:before { content: fa-content($fa-var-laptop-code); }\n.#{$fa-css-prefix}-laptop-medical:before { content: fa-content($fa-var-laptop-medical); }\n.#{$fa-css-prefix}-laravel:before { content: fa-content($fa-var-laravel); }\n.#{$fa-css-prefix}-lastfm:before { content: fa-content($fa-var-lastfm); }\n.#{$fa-css-prefix}-lastfm-square:before { content: fa-content($fa-var-lastfm-square); }\n.#{$fa-css-prefix}-laugh:before { content: fa-content($fa-var-laugh); }\n.#{$fa-css-prefix}-laugh-beam:before { content: fa-content($fa-var-laugh-beam); }\n.#{$fa-css-prefix}-laugh-squint:before { content: fa-content($fa-var-laugh-squint); }\n.#{$fa-css-prefix}-laugh-wink:before { content: fa-content($fa-var-laugh-wink); }\n.#{$fa-css-prefix}-layer-group:before { content: fa-content($fa-var-layer-group); }\n.#{$fa-css-prefix}-leaf:before { content: fa-content($fa-var-leaf); }\n.#{$fa-css-prefix}-leanpub:before { content: fa-content($fa-var-leanpub); }\n.#{$fa-css-prefix}-lemon:before { content: fa-content($fa-var-lemon); }\n.#{$fa-css-prefix}-less:before { content: fa-content($fa-var-less); }\n.#{$fa-css-prefix}-less-than:before { content: fa-content($fa-var-less-than); }\n.#{$fa-css-prefix}-less-than-equal:before { content: fa-content($fa-var-less-than-equal); }\n.#{$fa-css-prefix}-level-down-alt:before { content: fa-content($fa-var-level-down-alt); }\n.#{$fa-css-prefix}-level-up-alt:before { content: fa-content($fa-var-level-up-alt); }\n.#{$fa-css-prefix}-life-ring:before { content: fa-content($fa-var-life-ring); }\n.#{$fa-css-prefix}-lightbulb:before { content: fa-content($fa-var-lightbulb); }\n.#{$fa-css-prefix}-line:before { content: fa-content($fa-var-line); }\n.#{$fa-css-prefix}-link:before { content: fa-content($fa-var-link); }\n.#{$fa-css-prefix}-linkedin:before { content: fa-content($fa-var-linkedin); }\n.#{$fa-css-prefix}-linkedin-in:before { content: fa-content($fa-var-linkedin-in); }\n.#{$fa-css-prefix}-linode:before { content: fa-content($fa-var-linode); }\n.#{$fa-css-prefix}-linux:before { content: fa-content($fa-var-linux); }\n.#{$fa-css-prefix}-lira-sign:before { content: fa-content($fa-var-lira-sign); }\n.#{$fa-css-prefix}-list:before { content: fa-content($fa-var-list); }\n.#{$fa-css-prefix}-list-alt:before { content: fa-content($fa-var-list-alt); }\n.#{$fa-css-prefix}-list-ol:before { content: fa-content($fa-var-list-ol); }\n.#{$fa-css-prefix}-list-ul:before { content: fa-content($fa-var-list-ul); }\n.#{$fa-css-prefix}-location-arrow:before { content: fa-content($fa-var-location-arrow); }\n.#{$fa-css-prefix}-lock:before { content: fa-content($fa-var-lock); }\n.#{$fa-css-prefix}-lock-open:before { content: fa-content($fa-var-lock-open); }\n.#{$fa-css-prefix}-long-arrow-alt-down:before { content: fa-content($fa-var-long-arrow-alt-down); }\n.#{$fa-css-prefix}-long-arrow-alt-left:before { content: fa-content($fa-var-long-arrow-alt-left); }\n.#{$fa-css-prefix}-long-arrow-alt-right:before { content: fa-content($fa-var-long-arrow-alt-right); }\n.#{$fa-css-prefix}-long-arrow-alt-up:before { content: fa-content($fa-var-long-arrow-alt-up); }\n.#{$fa-css-prefix}-low-vision:before { content: fa-content($fa-var-low-vision); }\n.#{$fa-css-prefix}-luggage-cart:before { content: fa-content($fa-var-luggage-cart); }\n.#{$fa-css-prefix}-lyft:before { content: fa-content($fa-var-lyft); }\n.#{$fa-css-prefix}-magento:before { content: fa-content($fa-var-magento); }\n.#{$fa-css-prefix}-magic:before { content: fa-content($fa-var-magic); }\n.#{$fa-css-prefix}-magnet:before { content: fa-content($fa-var-magnet); }\n.#{$fa-css-prefix}-mail-bulk:before { content: fa-content($fa-var-mail-bulk); }\n.#{$fa-css-prefix}-mailchimp:before { content: fa-content($fa-var-mailchimp); }\n.#{$fa-css-prefix}-male:before { content: fa-content($fa-var-male); }\n.#{$fa-css-prefix}-mandalorian:before { content: fa-content($fa-var-mandalorian); }\n.#{$fa-css-prefix}-map:before { content: fa-content($fa-var-map); }\n.#{$fa-css-prefix}-map-marked:before { content: fa-content($fa-var-map-marked); }\n.#{$fa-css-prefix}-map-marked-alt:before { content: fa-content($fa-var-map-marked-alt); }\n.#{$fa-css-prefix}-map-marker:before { content: fa-content($fa-var-map-marker); }\n.#{$fa-css-prefix}-map-marker-alt:before { content: fa-content($fa-var-map-marker-alt); }\n.#{$fa-css-prefix}-map-pin:before { content: fa-content($fa-var-map-pin); }\n.#{$fa-css-prefix}-map-signs:before { content: fa-content($fa-var-map-signs); }\n.#{$fa-css-prefix}-markdown:before { content: fa-content($fa-var-markdown); }\n.#{$fa-css-prefix}-marker:before { content: fa-content($fa-var-marker); }\n.#{$fa-css-prefix}-mars:before { content: fa-content($fa-var-mars); }\n.#{$fa-css-prefix}-mars-double:before { content: fa-content($fa-var-mars-double); }\n.#{$fa-css-prefix}-mars-stroke:before { content: fa-content($fa-var-mars-stroke); }\n.#{$fa-css-prefix}-mars-stroke-h:before { content: fa-content($fa-var-mars-stroke-h); }\n.#{$fa-css-prefix}-mars-stroke-v:before { content: fa-content($fa-var-mars-stroke-v); }\n.#{$fa-css-prefix}-mask:before { content: fa-content($fa-var-mask); }\n.#{$fa-css-prefix}-mastodon:before { content: fa-content($fa-var-mastodon); }\n.#{$fa-css-prefix}-maxcdn:before { content: fa-content($fa-var-maxcdn); }\n.#{$fa-css-prefix}-medal:before { content: fa-content($fa-var-medal); }\n.#{$fa-css-prefix}-medapps:before { content: fa-content($fa-var-medapps); }\n.#{$fa-css-prefix}-medium:before { content: fa-content($fa-var-medium); }\n.#{$fa-css-prefix}-medium-m:before { content: fa-content($fa-var-medium-m); }\n.#{$fa-css-prefix}-medkit:before { content: fa-content($fa-var-medkit); }\n.#{$fa-css-prefix}-medrt:before { content: fa-content($fa-var-medrt); }\n.#{$fa-css-prefix}-meetup:before { content: fa-content($fa-var-meetup); }\n.#{$fa-css-prefix}-megaport:before { content: fa-content($fa-var-megaport); }\n.#{$fa-css-prefix}-meh:before { content: fa-content($fa-var-meh); }\n.#{$fa-css-prefix}-meh-blank:before { content: fa-content($fa-var-meh-blank); }\n.#{$fa-css-prefix}-meh-rolling-eyes:before { content: fa-content($fa-var-meh-rolling-eyes); }\n.#{$fa-css-prefix}-memory:before { content: fa-content($fa-var-memory); }\n.#{$fa-css-prefix}-mendeley:before { content: fa-content($fa-var-mendeley); }\n.#{$fa-css-prefix}-menorah:before { content: fa-content($fa-var-menorah); }\n.#{$fa-css-prefix}-mercury:before { content: fa-content($fa-var-mercury); }\n.#{$fa-css-prefix}-meteor:before { content: fa-content($fa-var-meteor); }\n.#{$fa-css-prefix}-microchip:before { content: fa-content($fa-var-microchip); }\n.#{$fa-css-prefix}-microphone:before { content: fa-content($fa-var-microphone); }\n.#{$fa-css-prefix}-microphone-alt:before { content: fa-content($fa-var-microphone-alt); }\n.#{$fa-css-prefix}-microphone-alt-slash:before { content: fa-content($fa-var-microphone-alt-slash); }\n.#{$fa-css-prefix}-microphone-slash:before { content: fa-content($fa-var-microphone-slash); }\n.#{$fa-css-prefix}-microscope:before { content: fa-content($fa-var-microscope); }\n.#{$fa-css-prefix}-microsoft:before { content: fa-content($fa-var-microsoft); }\n.#{$fa-css-prefix}-minus:before { content: fa-content($fa-var-minus); }\n.#{$fa-css-prefix}-minus-circle:before { content: fa-content($fa-var-minus-circle); }\n.#{$fa-css-prefix}-minus-square:before { content: fa-content($fa-var-minus-square); }\n.#{$fa-css-prefix}-mitten:before { content: fa-content($fa-var-mitten); }\n.#{$fa-css-prefix}-mix:before { content: fa-content($fa-var-mix); }\n.#{$fa-css-prefix}-mixcloud:before { content: fa-content($fa-var-mixcloud); }\n.#{$fa-css-prefix}-mizuni:before { content: fa-content($fa-var-mizuni); }\n.#{$fa-css-prefix}-mobile:before { content: fa-content($fa-var-mobile); }\n.#{$fa-css-prefix}-mobile-alt:before { content: fa-content($fa-var-mobile-alt); }\n.#{$fa-css-prefix}-modx:before { content: fa-content($fa-var-modx); }\n.#{$fa-css-prefix}-monero:before { content: fa-content($fa-var-monero); }\n.#{$fa-css-prefix}-money-bill:before { content: fa-content($fa-var-money-bill); }\n.#{$fa-css-prefix}-money-bill-alt:before { content: fa-content($fa-var-money-bill-alt); }\n.#{$fa-css-prefix}-money-bill-wave:before { content: fa-content($fa-var-money-bill-wave); }\n.#{$fa-css-prefix}-money-bill-wave-alt:before { content: fa-content($fa-var-money-bill-wave-alt); }\n.#{$fa-css-prefix}-money-check:before { content: fa-content($fa-var-money-check); }\n.#{$fa-css-prefix}-money-check-alt:before { content: fa-content($fa-var-money-check-alt); }\n.#{$fa-css-prefix}-monument:before { content: fa-content($fa-var-monument); }\n.#{$fa-css-prefix}-moon:before { content: fa-content($fa-var-moon); }\n.#{$fa-css-prefix}-mortar-pestle:before { content: fa-content($fa-var-mortar-pestle); }\n.#{$fa-css-prefix}-mosque:before { content: fa-content($fa-var-mosque); }\n.#{$fa-css-prefix}-motorcycle:before { content: fa-content($fa-var-motorcycle); }\n.#{$fa-css-prefix}-mountain:before { content: fa-content($fa-var-mountain); }\n.#{$fa-css-prefix}-mouse-pointer:before { content: fa-content($fa-var-mouse-pointer); }\n.#{$fa-css-prefix}-mug-hot:before { content: fa-content($fa-var-mug-hot); }\n.#{$fa-css-prefix}-music:before { content: fa-content($fa-var-music); }\n.#{$fa-css-prefix}-napster:before { content: fa-content($fa-var-napster); }\n.#{$fa-css-prefix}-neos:before { content: fa-content($fa-var-neos); }\n.#{$fa-css-prefix}-network-wired:before { content: fa-content($fa-var-network-wired); }\n.#{$fa-css-prefix}-neuter:before { content: fa-content($fa-var-neuter); }\n.#{$fa-css-prefix}-newspaper:before { content: fa-content($fa-var-newspaper); }\n.#{$fa-css-prefix}-nimblr:before { content: fa-content($fa-var-nimblr); }\n.#{$fa-css-prefix}-node:before { content: fa-content($fa-var-node); }\n.#{$fa-css-prefix}-node-js:before { content: fa-content($fa-var-node-js); }\n.#{$fa-css-prefix}-not-equal:before { content: fa-content($fa-var-not-equal); }\n.#{$fa-css-prefix}-notes-medical:before { content: fa-content($fa-var-notes-medical); }\n.#{$fa-css-prefix}-npm:before { content: fa-content($fa-var-npm); }\n.#{$fa-css-prefix}-ns8:before { content: fa-content($fa-var-ns8); }\n.#{$fa-css-prefix}-nutritionix:before { content: fa-content($fa-var-nutritionix); }\n.#{$fa-css-prefix}-object-group:before { content: fa-content($fa-var-object-group); }\n.#{$fa-css-prefix}-object-ungroup:before { content: fa-content($fa-var-object-ungroup); }\n.#{$fa-css-prefix}-odnoklassniki:before { content: fa-content($fa-var-odnoklassniki); }\n.#{$fa-css-prefix}-odnoklassniki-square:before { content: fa-content($fa-var-odnoklassniki-square); }\n.#{$fa-css-prefix}-oil-can:before { content: fa-content($fa-var-oil-can); }\n.#{$fa-css-prefix}-old-republic:before { content: fa-content($fa-var-old-republic); }\n.#{$fa-css-prefix}-om:before { content: fa-content($fa-var-om); }\n.#{$fa-css-prefix}-opencart:before { content: fa-content($fa-var-opencart); }\n.#{$fa-css-prefix}-openid:before { content: fa-content($fa-var-openid); }\n.#{$fa-css-prefix}-opera:before { content: fa-content($fa-var-opera); }\n.#{$fa-css-prefix}-optin-monster:before { content: fa-content($fa-var-optin-monster); }\n.#{$fa-css-prefix}-osi:before { content: fa-content($fa-var-osi); }\n.#{$fa-css-prefix}-otter:before { content: fa-content($fa-var-otter); }\n.#{$fa-css-prefix}-outdent:before { content: fa-content($fa-var-outdent); }\n.#{$fa-css-prefix}-page4:before { content: fa-content($fa-var-page4); }\n.#{$fa-css-prefix}-pagelines:before { content: fa-content($fa-var-pagelines); }\n.#{$fa-css-prefix}-pager:before { content: fa-content($fa-var-pager); }\n.#{$fa-css-prefix}-paint-brush:before { content: fa-content($fa-var-paint-brush); }\n.#{$fa-css-prefix}-paint-roller:before { content: fa-content($fa-var-paint-roller); }\n.#{$fa-css-prefix}-palette:before { content: fa-content($fa-var-palette); }\n.#{$fa-css-prefix}-palfed:before { content: fa-content($fa-var-palfed); }\n.#{$fa-css-prefix}-pallet:before { content: fa-content($fa-var-pallet); }\n.#{$fa-css-prefix}-paper-plane:before { content: fa-content($fa-var-paper-plane); }\n.#{$fa-css-prefix}-paperclip:before { content: fa-content($fa-var-paperclip); }\n.#{$fa-css-prefix}-parachute-box:before { content: fa-content($fa-var-parachute-box); }\n.#{$fa-css-prefix}-paragraph:before { content: fa-content($fa-var-paragraph); }\n.#{$fa-css-prefix}-parking:before { content: fa-content($fa-var-parking); }\n.#{$fa-css-prefix}-passport:before { content: fa-content($fa-var-passport); }\n.#{$fa-css-prefix}-pastafarianism:before { content: fa-content($fa-var-pastafarianism); }\n.#{$fa-css-prefix}-paste:before { content: fa-content($fa-var-paste); }\n.#{$fa-css-prefix}-patreon:before { content: fa-content($fa-var-patreon); }\n.#{$fa-css-prefix}-pause:before { content: fa-content($fa-var-pause); }\n.#{$fa-css-prefix}-pause-circle:before { content: fa-content($fa-var-pause-circle); }\n.#{$fa-css-prefix}-paw:before { content: fa-content($fa-var-paw); }\n.#{$fa-css-prefix}-paypal:before { content: fa-content($fa-var-paypal); }\n.#{$fa-css-prefix}-peace:before { content: fa-content($fa-var-peace); }\n.#{$fa-css-prefix}-pen:before { content: fa-content($fa-var-pen); }\n.#{$fa-css-prefix}-pen-alt:before { content: fa-content($fa-var-pen-alt); }\n.#{$fa-css-prefix}-pen-fancy:before { content: fa-content($fa-var-pen-fancy); }\n.#{$fa-css-prefix}-pen-nib:before { content: fa-content($fa-var-pen-nib); }\n.#{$fa-css-prefix}-pen-square:before { content: fa-content($fa-var-pen-square); }\n.#{$fa-css-prefix}-pencil-alt:before { content: fa-content($fa-var-pencil-alt); }\n.#{$fa-css-prefix}-pencil-ruler:before { content: fa-content($fa-var-pencil-ruler); }\n.#{$fa-css-prefix}-penny-arcade:before { content: fa-content($fa-var-penny-arcade); }\n.#{$fa-css-prefix}-people-carry:before { content: fa-content($fa-var-people-carry); }\n.#{$fa-css-prefix}-pepper-hot:before { content: fa-content($fa-var-pepper-hot); }\n.#{$fa-css-prefix}-percent:before { content: fa-content($fa-var-percent); }\n.#{$fa-css-prefix}-percentage:before { content: fa-content($fa-var-percentage); }\n.#{$fa-css-prefix}-periscope:before { content: fa-content($fa-var-periscope); }\n.#{$fa-css-prefix}-person-booth:before { content: fa-content($fa-var-person-booth); }\n.#{$fa-css-prefix}-phabricator:before { content: fa-content($fa-var-phabricator); }\n.#{$fa-css-prefix}-phoenix-framework:before { content: fa-content($fa-var-phoenix-framework); }\n.#{$fa-css-prefix}-phoenix-squadron:before { content: fa-content($fa-var-phoenix-squadron); }\n.#{$fa-css-prefix}-phone:before { content: fa-content($fa-var-phone); }\n.#{$fa-css-prefix}-phone-alt:before { content: fa-content($fa-var-phone-alt); }\n.#{$fa-css-prefix}-phone-slash:before { content: fa-content($fa-var-phone-slash); }\n.#{$fa-css-prefix}-phone-square:before { content: fa-content($fa-var-phone-square); }\n.#{$fa-css-prefix}-phone-square-alt:before { content: fa-content($fa-var-phone-square-alt); }\n.#{$fa-css-prefix}-phone-volume:before { content: fa-content($fa-var-phone-volume); }\n.#{$fa-css-prefix}-photo-video:before { content: fa-content($fa-var-photo-video); }\n.#{$fa-css-prefix}-php:before { content: fa-content($fa-var-php); }\n.#{$fa-css-prefix}-pied-piper:before { content: fa-content($fa-var-pied-piper); }\n.#{$fa-css-prefix}-pied-piper-alt:before { content: fa-content($fa-var-pied-piper-alt); }\n.#{$fa-css-prefix}-pied-piper-hat:before { content: fa-content($fa-var-pied-piper-hat); }\n.#{$fa-css-prefix}-pied-piper-pp:before { content: fa-content($fa-var-pied-piper-pp); }\n.#{$fa-css-prefix}-piggy-bank:before { content: fa-content($fa-var-piggy-bank); }\n.#{$fa-css-prefix}-pills:before { content: fa-content($fa-var-pills); }\n.#{$fa-css-prefix}-pinterest:before { content: fa-content($fa-var-pinterest); }\n.#{$fa-css-prefix}-pinterest-p:before { content: fa-content($fa-var-pinterest-p); }\n.#{$fa-css-prefix}-pinterest-square:before { content: fa-content($fa-var-pinterest-square); }\n.#{$fa-css-prefix}-pizza-slice:before { content: fa-content($fa-var-pizza-slice); }\n.#{$fa-css-prefix}-place-of-worship:before { content: fa-content($fa-var-place-of-worship); }\n.#{$fa-css-prefix}-plane:before { content: fa-content($fa-var-plane); }\n.#{$fa-css-prefix}-plane-arrival:before { content: fa-content($fa-var-plane-arrival); }\n.#{$fa-css-prefix}-plane-departure:before { content: fa-content($fa-var-plane-departure); }\n.#{$fa-css-prefix}-play:before { content: fa-content($fa-var-play); }\n.#{$fa-css-prefix}-play-circle:before { content: fa-content($fa-var-play-circle); }\n.#{$fa-css-prefix}-playstation:before { content: fa-content($fa-var-playstation); }\n.#{$fa-css-prefix}-plug:before { content: fa-content($fa-var-plug); }\n.#{$fa-css-prefix}-plus:before { content: fa-content($fa-var-plus); }\n.#{$fa-css-prefix}-plus-circle:before { content: fa-content($fa-var-plus-circle); }\n.#{$fa-css-prefix}-plus-square:before { content: fa-content($fa-var-plus-square); }\n.#{$fa-css-prefix}-podcast:before { content: fa-content($fa-var-podcast); }\n.#{$fa-css-prefix}-poll:before { content: fa-content($fa-var-poll); }\n.#{$fa-css-prefix}-poll-h:before { content: fa-content($fa-var-poll-h); }\n.#{$fa-css-prefix}-poo:before { content: fa-content($fa-var-poo); }\n.#{$fa-css-prefix}-poo-storm:before { content: fa-content($fa-var-poo-storm); }\n.#{$fa-css-prefix}-poop:before { content: fa-content($fa-var-poop); }\n.#{$fa-css-prefix}-portrait:before { content: fa-content($fa-var-portrait); }\n.#{$fa-css-prefix}-pound-sign:before { content: fa-content($fa-var-pound-sign); }\n.#{$fa-css-prefix}-power-off:before { content: fa-content($fa-var-power-off); }\n.#{$fa-css-prefix}-pray:before { content: fa-content($fa-var-pray); }\n.#{$fa-css-prefix}-praying-hands:before { content: fa-content($fa-var-praying-hands); }\n.#{$fa-css-prefix}-prescription:before { content: fa-content($fa-var-prescription); }\n.#{$fa-css-prefix}-prescription-bottle:before { content: fa-content($fa-var-prescription-bottle); }\n.#{$fa-css-prefix}-prescription-bottle-alt:before { content: fa-content($fa-var-prescription-bottle-alt); }\n.#{$fa-css-prefix}-print:before { content: fa-content($fa-var-print); }\n.#{$fa-css-prefix}-procedures:before { content: fa-content($fa-var-procedures); }\n.#{$fa-css-prefix}-product-hunt:before { content: fa-content($fa-var-product-hunt); }\n.#{$fa-css-prefix}-project-diagram:before { content: fa-content($fa-var-project-diagram); }\n.#{$fa-css-prefix}-pushed:before { content: fa-content($fa-var-pushed); }\n.#{$fa-css-prefix}-puzzle-piece:before { content: fa-content($fa-var-puzzle-piece); }\n.#{$fa-css-prefix}-python:before { content: fa-content($fa-var-python); }\n.#{$fa-css-prefix}-qq:before { content: fa-content($fa-var-qq); }\n.#{$fa-css-prefix}-qrcode:before { content: fa-content($fa-var-qrcode); }\n.#{$fa-css-prefix}-question:before { content: fa-content($fa-var-question); }\n.#{$fa-css-prefix}-question-circle:before { content: fa-content($fa-var-question-circle); }\n.#{$fa-css-prefix}-quidditch:before { content: fa-content($fa-var-quidditch); }\n.#{$fa-css-prefix}-quinscape:before { content: fa-content($fa-var-quinscape); }\n.#{$fa-css-prefix}-quora:before { content: fa-content($fa-var-quora); }\n.#{$fa-css-prefix}-quote-left:before { content: fa-content($fa-var-quote-left); }\n.#{$fa-css-prefix}-quote-right:before { content: fa-content($fa-var-quote-right); }\n.#{$fa-css-prefix}-quran:before { content: fa-content($fa-var-quran); }\n.#{$fa-css-prefix}-r-project:before { content: fa-content($fa-var-r-project); }\n.#{$fa-css-prefix}-radiation:before { content: fa-content($fa-var-radiation); }\n.#{$fa-css-prefix}-radiation-alt:before { content: fa-content($fa-var-radiation-alt); }\n.#{$fa-css-prefix}-rainbow:before { content: fa-content($fa-var-rainbow); }\n.#{$fa-css-prefix}-random:before { content: fa-content($fa-var-random); }\n.#{$fa-css-prefix}-raspberry-pi:before { content: fa-content($fa-var-raspberry-pi); }\n.#{$fa-css-prefix}-ravelry:before { content: fa-content($fa-var-ravelry); }\n.#{$fa-css-prefix}-react:before { content: fa-content($fa-var-react); }\n.#{$fa-css-prefix}-reacteurope:before { content: fa-content($fa-var-reacteurope); }\n.#{$fa-css-prefix}-readme:before { content: fa-content($fa-var-readme); }\n.#{$fa-css-prefix}-rebel:before { content: fa-content($fa-var-rebel); }\n.#{$fa-css-prefix}-receipt:before { content: fa-content($fa-var-receipt); }\n.#{$fa-css-prefix}-recycle:before { content: fa-content($fa-var-recycle); }\n.#{$fa-css-prefix}-red-river:before { content: fa-content($fa-var-red-river); }\n.#{$fa-css-prefix}-reddit:before { content: fa-content($fa-var-reddit); }\n.#{$fa-css-prefix}-reddit-alien:before { content: fa-content($fa-var-reddit-alien); }\n.#{$fa-css-prefix}-reddit-square:before { content: fa-content($fa-var-reddit-square); }\n.#{$fa-css-prefix}-redhat:before { content: fa-content($fa-var-redhat); }\n.#{$fa-css-prefix}-redo:before { content: fa-content($fa-var-redo); }\n.#{$fa-css-prefix}-redo-alt:before { content: fa-content($fa-var-redo-alt); }\n.#{$fa-css-prefix}-registered:before { content: fa-content($fa-var-registered); }\n.#{$fa-css-prefix}-remove-format:before { content: fa-content($fa-var-remove-format); }\n.#{$fa-css-prefix}-renren:before { content: fa-content($fa-var-renren); }\n.#{$fa-css-prefix}-reply:before { content: fa-content($fa-var-reply); }\n.#{$fa-css-prefix}-reply-all:before { content: fa-content($fa-var-reply-all); }\n.#{$fa-css-prefix}-replyd:before { content: fa-content($fa-var-replyd); }\n.#{$fa-css-prefix}-republican:before { content: fa-content($fa-var-republican); }\n.#{$fa-css-prefix}-researchgate:before { content: fa-content($fa-var-researchgate); }\n.#{$fa-css-prefix}-resolving:before { content: fa-content($fa-var-resolving); }\n.#{$fa-css-prefix}-restroom:before { content: fa-content($fa-var-restroom); }\n.#{$fa-css-prefix}-retweet:before { content: fa-content($fa-var-retweet); }\n.#{$fa-css-prefix}-rev:before { content: fa-content($fa-var-rev); }\n.#{$fa-css-prefix}-ribbon:before { content: fa-content($fa-var-ribbon); }\n.#{$fa-css-prefix}-ring:before { content: fa-content($fa-var-ring); }\n.#{$fa-css-prefix}-road:before { content: fa-content($fa-var-road); }\n.#{$fa-css-prefix}-robot:before { content: fa-content($fa-var-robot); }\n.#{$fa-css-prefix}-rocket:before { content: fa-content($fa-var-rocket); }\n.#{$fa-css-prefix}-rocketchat:before { content: fa-content($fa-var-rocketchat); }\n.#{$fa-css-prefix}-rockrms:before { content: fa-content($fa-var-rockrms); }\n.#{$fa-css-prefix}-route:before { content: fa-content($fa-var-route); }\n.#{$fa-css-prefix}-rss:before { content: fa-content($fa-var-rss); }\n.#{$fa-css-prefix}-rss-square:before { content: fa-content($fa-var-rss-square); }\n.#{$fa-css-prefix}-ruble-sign:before { content: fa-content($fa-var-ruble-sign); }\n.#{$fa-css-prefix}-ruler:before { content: fa-content($fa-var-ruler); }\n.#{$fa-css-prefix}-ruler-combined:before { content: fa-content($fa-var-ruler-combined); }\n.#{$fa-css-prefix}-ruler-horizontal:before { content: fa-content($fa-var-ruler-horizontal); }\n.#{$fa-css-prefix}-ruler-vertical:before { content: fa-content($fa-var-ruler-vertical); }\n.#{$fa-css-prefix}-running:before { content: fa-content($fa-var-running); }\n.#{$fa-css-prefix}-rupee-sign:before { content: fa-content($fa-var-rupee-sign); }\n.#{$fa-css-prefix}-sad-cry:before { content: fa-content($fa-var-sad-cry); }\n.#{$fa-css-prefix}-sad-tear:before { content: fa-content($fa-var-sad-tear); }\n.#{$fa-css-prefix}-safari:before { content: fa-content($fa-var-safari); }\n.#{$fa-css-prefix}-salesforce:before { content: fa-content($fa-var-salesforce); }\n.#{$fa-css-prefix}-sass:before { content: fa-content($fa-var-sass); }\n.#{$fa-css-prefix}-satellite:before { content: fa-content($fa-var-satellite); }\n.#{$fa-css-prefix}-satellite-dish:before { content: fa-content($fa-var-satellite-dish); }\n.#{$fa-css-prefix}-save:before { content: fa-content($fa-var-save); }\n.#{$fa-css-prefix}-schlix:before { content: fa-content($fa-var-schlix); }\n.#{$fa-css-prefix}-school:before { content: fa-content($fa-var-school); }\n.#{$fa-css-prefix}-screwdriver:before { content: fa-content($fa-var-screwdriver); }\n.#{$fa-css-prefix}-scribd:before { content: fa-content($fa-var-scribd); }\n.#{$fa-css-prefix}-scroll:before { content: fa-content($fa-var-scroll); }\n.#{$fa-css-prefix}-sd-card:before { content: fa-content($fa-var-sd-card); }\n.#{$fa-css-prefix}-search:before { content: fa-content($fa-var-search); }\n.#{$fa-css-prefix}-search-dollar:before { content: fa-content($fa-var-search-dollar); }\n.#{$fa-css-prefix}-search-location:before { content: fa-content($fa-var-search-location); }\n.#{$fa-css-prefix}-search-minus:before { content: fa-content($fa-var-search-minus); }\n.#{$fa-css-prefix}-search-plus:before { content: fa-content($fa-var-search-plus); }\n.#{$fa-css-prefix}-searchengin:before { content: fa-content($fa-var-searchengin); }\n.#{$fa-css-prefix}-seedling:before { content: fa-content($fa-var-seedling); }\n.#{$fa-css-prefix}-sellcast:before { content: fa-content($fa-var-sellcast); }\n.#{$fa-css-prefix}-sellsy:before { content: fa-content($fa-var-sellsy); }\n.#{$fa-css-prefix}-server:before { content: fa-content($fa-var-server); }\n.#{$fa-css-prefix}-servicestack:before { content: fa-content($fa-var-servicestack); }\n.#{$fa-css-prefix}-shapes:before { content: fa-content($fa-var-shapes); }\n.#{$fa-css-prefix}-share:before { content: fa-content($fa-var-share); }\n.#{$fa-css-prefix}-share-alt:before { content: fa-content($fa-var-share-alt); }\n.#{$fa-css-prefix}-share-alt-square:before { content: fa-content($fa-var-share-alt-square); }\n.#{$fa-css-prefix}-share-square:before { content: fa-content($fa-var-share-square); }\n.#{$fa-css-prefix}-shekel-sign:before { content: fa-content($fa-var-shekel-sign); }\n.#{$fa-css-prefix}-shield-alt:before { content: fa-content($fa-var-shield-alt); }\n.#{$fa-css-prefix}-ship:before { content: fa-content($fa-var-ship); }\n.#{$fa-css-prefix}-shipping-fast:before { content: fa-content($fa-var-shipping-fast); }\n.#{$fa-css-prefix}-shirtsinbulk:before { content: fa-content($fa-var-shirtsinbulk); }\n.#{$fa-css-prefix}-shoe-prints:before { content: fa-content($fa-var-shoe-prints); }\n.#{$fa-css-prefix}-shopping-bag:before { content: fa-content($fa-var-shopping-bag); }\n.#{$fa-css-prefix}-shopping-basket:before { content: fa-content($fa-var-shopping-basket); }\n.#{$fa-css-prefix}-shopping-cart:before { content: fa-content($fa-var-shopping-cart); }\n.#{$fa-css-prefix}-shopware:before { content: fa-content($fa-var-shopware); }\n.#{$fa-css-prefix}-shower:before { content: fa-content($fa-var-shower); }\n.#{$fa-css-prefix}-shuttle-van:before { content: fa-content($fa-var-shuttle-van); }\n.#{$fa-css-prefix}-sign:before { content: fa-content($fa-var-sign); }\n.#{$fa-css-prefix}-sign-in-alt:before { content: fa-content($fa-var-sign-in-alt); }\n.#{$fa-css-prefix}-sign-language:before { content: fa-content($fa-var-sign-language); }\n.#{$fa-css-prefix}-sign-out-alt:before { content: fa-content($fa-var-sign-out-alt); }\n.#{$fa-css-prefix}-signal:before { content: fa-content($fa-var-signal); }\n.#{$fa-css-prefix}-signature:before { content: fa-content($fa-var-signature); }\n.#{$fa-css-prefix}-sim-card:before { content: fa-content($fa-var-sim-card); }\n.#{$fa-css-prefix}-simplybuilt:before { content: fa-content($fa-var-simplybuilt); }\n.#{$fa-css-prefix}-sistrix:before { content: fa-content($fa-var-sistrix); }\n.#{$fa-css-prefix}-sitemap:before { content: fa-content($fa-var-sitemap); }\n.#{$fa-css-prefix}-sith:before { content: fa-content($fa-var-sith); }\n.#{$fa-css-prefix}-skating:before { content: fa-content($fa-var-skating); }\n.#{$fa-css-prefix}-sketch:before { content: fa-content($fa-var-sketch); }\n.#{$fa-css-prefix}-skiing:before { content: fa-content($fa-var-skiing); }\n.#{$fa-css-prefix}-skiing-nordic:before { content: fa-content($fa-var-skiing-nordic); }\n.#{$fa-css-prefix}-skull:before { content: fa-content($fa-var-skull); }\n.#{$fa-css-prefix}-skull-crossbones:before { content: fa-content($fa-var-skull-crossbones); }\n.#{$fa-css-prefix}-skyatlas:before { content: fa-content($fa-var-skyatlas); }\n.#{$fa-css-prefix}-skype:before { content: fa-content($fa-var-skype); }\n.#{$fa-css-prefix}-slack:before { content: fa-content($fa-var-slack); }\n.#{$fa-css-prefix}-slack-hash:before { content: fa-content($fa-var-slack-hash); }\n.#{$fa-css-prefix}-slash:before { content: fa-content($fa-var-slash); }\n.#{$fa-css-prefix}-sleigh:before { content: fa-content($fa-var-sleigh); }\n.#{$fa-css-prefix}-sliders-h:before { content: fa-content($fa-var-sliders-h); }\n.#{$fa-css-prefix}-slideshare:before { content: fa-content($fa-var-slideshare); }\n.#{$fa-css-prefix}-smile:before { content: fa-content($fa-var-smile); }\n.#{$fa-css-prefix}-smile-beam:before { content: fa-content($fa-var-smile-beam); }\n.#{$fa-css-prefix}-smile-wink:before { content: fa-content($fa-var-smile-wink); }\n.#{$fa-css-prefix}-smog:before { content: fa-content($fa-var-smog); }\n.#{$fa-css-prefix}-smoking:before { content: fa-content($fa-var-smoking); }\n.#{$fa-css-prefix}-smoking-ban:before { content: fa-content($fa-var-smoking-ban); }\n.#{$fa-css-prefix}-sms:before { content: fa-content($fa-var-sms); }\n.#{$fa-css-prefix}-snapchat:before { content: fa-content($fa-var-snapchat); }\n.#{$fa-css-prefix}-snapchat-ghost:before { content: fa-content($fa-var-snapchat-ghost); }\n.#{$fa-css-prefix}-snapchat-square:before { content: fa-content($fa-var-snapchat-square); }\n.#{$fa-css-prefix}-snowboarding:before { content: fa-content($fa-var-snowboarding); }\n.#{$fa-css-prefix}-snowflake:before { content: fa-content($fa-var-snowflake); }\n.#{$fa-css-prefix}-snowman:before { content: fa-content($fa-var-snowman); }\n.#{$fa-css-prefix}-snowplow:before { content: fa-content($fa-var-snowplow); }\n.#{$fa-css-prefix}-socks:before { content: fa-content($fa-var-socks); }\n.#{$fa-css-prefix}-solar-panel:before { content: fa-content($fa-var-solar-panel); }\n.#{$fa-css-prefix}-sort:before { content: fa-content($fa-var-sort); }\n.#{$fa-css-prefix}-sort-alpha-down:before { content: fa-content($fa-var-sort-alpha-down); }\n.#{$fa-css-prefix}-sort-alpha-down-alt:before { content: fa-content($fa-var-sort-alpha-down-alt); }\n.#{$fa-css-prefix}-sort-alpha-up:before { content: fa-content($fa-var-sort-alpha-up); }\n.#{$fa-css-prefix}-sort-alpha-up-alt:before { content: fa-content($fa-var-sort-alpha-up-alt); }\n.#{$fa-css-prefix}-sort-amount-down:before { content: fa-content($fa-var-sort-amount-down); }\n.#{$fa-css-prefix}-sort-amount-down-alt:before { content: fa-content($fa-var-sort-amount-down-alt); }\n.#{$fa-css-prefix}-sort-amount-up:before { content: fa-content($fa-var-sort-amount-up); }\n.#{$fa-css-prefix}-sort-amount-up-alt:before { content: fa-content($fa-var-sort-amount-up-alt); }\n.#{$fa-css-prefix}-sort-down:before { content: fa-content($fa-var-sort-down); }\n.#{$fa-css-prefix}-sort-numeric-down:before { content: fa-content($fa-var-sort-numeric-down); }\n.#{$fa-css-prefix}-sort-numeric-down-alt:before { content: fa-content($fa-var-sort-numeric-down-alt); }\n.#{$fa-css-prefix}-sort-numeric-up:before { content: fa-content($fa-var-sort-numeric-up); }\n.#{$fa-css-prefix}-sort-numeric-up-alt:before { content: fa-content($fa-var-sort-numeric-up-alt); }\n.#{$fa-css-prefix}-sort-up:before { content: fa-content($fa-var-sort-up); }\n.#{$fa-css-prefix}-soundcloud:before { content: fa-content($fa-var-soundcloud); }\n.#{$fa-css-prefix}-sourcetree:before { content: fa-content($fa-var-sourcetree); }\n.#{$fa-css-prefix}-spa:before { content: fa-content($fa-var-spa); }\n.#{$fa-css-prefix}-space-shuttle:before { content: fa-content($fa-var-space-shuttle); }\n.#{$fa-css-prefix}-speakap:before { content: fa-content($fa-var-speakap); }\n.#{$fa-css-prefix}-speaker-deck:before { content: fa-content($fa-var-speaker-deck); }\n.#{$fa-css-prefix}-spell-check:before { content: fa-content($fa-var-spell-check); }\n.#{$fa-css-prefix}-spider:before { content: fa-content($fa-var-spider); }\n.#{$fa-css-prefix}-spinner:before { content: fa-content($fa-var-spinner); }\n.#{$fa-css-prefix}-splotch:before { content: fa-content($fa-var-splotch); }\n.#{$fa-css-prefix}-spotify:before { content: fa-content($fa-var-spotify); }\n.#{$fa-css-prefix}-spray-can:before { content: fa-content($fa-var-spray-can); }\n.#{$fa-css-prefix}-square:before { content: fa-content($fa-var-square); }\n.#{$fa-css-prefix}-square-full:before { content: fa-content($fa-var-square-full); }\n.#{$fa-css-prefix}-square-root-alt:before { content: fa-content($fa-var-square-root-alt); }\n.#{$fa-css-prefix}-squarespace:before { content: fa-content($fa-var-squarespace); }\n.#{$fa-css-prefix}-stack-exchange:before { content: fa-content($fa-var-stack-exchange); }\n.#{$fa-css-prefix}-stack-overflow:before { content: fa-content($fa-var-stack-overflow); }\n.#{$fa-css-prefix}-stackpath:before { content: fa-content($fa-var-stackpath); }\n.#{$fa-css-prefix}-stamp:before { content: fa-content($fa-var-stamp); }\n.#{$fa-css-prefix}-star:before { content: fa-content($fa-var-star); }\n.#{$fa-css-prefix}-star-and-crescent:before { content: fa-content($fa-var-star-and-crescent); }\n.#{$fa-css-prefix}-star-half:before { content: fa-content($fa-var-star-half); }\n.#{$fa-css-prefix}-star-half-alt:before { content: fa-content($fa-var-star-half-alt); }\n.#{$fa-css-prefix}-star-of-david:before { content: fa-content($fa-var-star-of-david); }\n.#{$fa-css-prefix}-star-of-life:before { content: fa-content($fa-var-star-of-life); }\n.#{$fa-css-prefix}-staylinked:before { content: fa-content($fa-var-staylinked); }\n.#{$fa-css-prefix}-steam:before { content: fa-content($fa-var-steam); }\n.#{$fa-css-prefix}-steam-square:before { content: fa-content($fa-var-steam-square); }\n.#{$fa-css-prefix}-steam-symbol:before { content: fa-content($fa-var-steam-symbol); }\n.#{$fa-css-prefix}-step-backward:before { content: fa-content($fa-var-step-backward); }\n.#{$fa-css-prefix}-step-forward:before { content: fa-content($fa-var-step-forward); }\n.#{$fa-css-prefix}-stethoscope:before { content: fa-content($fa-var-stethoscope); }\n.#{$fa-css-prefix}-sticker-mule:before { content: fa-content($fa-var-sticker-mule); }\n.#{$fa-css-prefix}-sticky-note:before { content: fa-content($fa-var-sticky-note); }\n.#{$fa-css-prefix}-stop:before { content: fa-content($fa-var-stop); }\n.#{$fa-css-prefix}-stop-circle:before { content: fa-content($fa-var-stop-circle); }\n.#{$fa-css-prefix}-stopwatch:before { content: fa-content($fa-var-stopwatch); }\n.#{$fa-css-prefix}-store:before { content: fa-content($fa-var-store); }\n.#{$fa-css-prefix}-store-alt:before { content: fa-content($fa-var-store-alt); }\n.#{$fa-css-prefix}-strava:before { content: fa-content($fa-var-strava); }\n.#{$fa-css-prefix}-stream:before { content: fa-content($fa-var-stream); }\n.#{$fa-css-prefix}-street-view:before { content: fa-content($fa-var-street-view); }\n.#{$fa-css-prefix}-strikethrough:before { content: fa-content($fa-var-strikethrough); }\n.#{$fa-css-prefix}-stripe:before { content: fa-content($fa-var-stripe); }\n.#{$fa-css-prefix}-stripe-s:before { content: fa-content($fa-var-stripe-s); }\n.#{$fa-css-prefix}-stroopwafel:before { content: fa-content($fa-var-stroopwafel); }\n.#{$fa-css-prefix}-studiovinari:before { content: fa-content($fa-var-studiovinari); }\n.#{$fa-css-prefix}-stumbleupon:before { content: fa-content($fa-var-stumbleupon); }\n.#{$fa-css-prefix}-stumbleupon-circle:before { content: fa-content($fa-var-stumbleupon-circle); }\n.#{$fa-css-prefix}-subscript:before { content: fa-content($fa-var-subscript); }\n.#{$fa-css-prefix}-subway:before { content: fa-content($fa-var-subway); }\n.#{$fa-css-prefix}-suitcase:before { content: fa-content($fa-var-suitcase); }\n.#{$fa-css-prefix}-suitcase-rolling:before { content: fa-content($fa-var-suitcase-rolling); }\n.#{$fa-css-prefix}-sun:before { content: fa-content($fa-var-sun); }\n.#{$fa-css-prefix}-superpowers:before { content: fa-content($fa-var-superpowers); }\n.#{$fa-css-prefix}-superscript:before { content: fa-content($fa-var-superscript); }\n.#{$fa-css-prefix}-supple:before { content: fa-content($fa-var-supple); }\n.#{$fa-css-prefix}-surprise:before { content: fa-content($fa-var-surprise); }\n.#{$fa-css-prefix}-suse:before { content: fa-content($fa-var-suse); }\n.#{$fa-css-prefix}-swatchbook:before { content: fa-content($fa-var-swatchbook); }\n.#{$fa-css-prefix}-swimmer:before { content: fa-content($fa-var-swimmer); }\n.#{$fa-css-prefix}-swimming-pool:before { content: fa-content($fa-var-swimming-pool); }\n.#{$fa-css-prefix}-symfony:before { content: fa-content($fa-var-symfony); }\n.#{$fa-css-prefix}-synagogue:before { content: fa-content($fa-var-synagogue); }\n.#{$fa-css-prefix}-sync:before { content: fa-content($fa-var-sync); }\n.#{$fa-css-prefix}-sync-alt:before { content: fa-content($fa-var-sync-alt); }\n.#{$fa-css-prefix}-syringe:before { content: fa-content($fa-var-syringe); }\n.#{$fa-css-prefix}-table:before { content: fa-content($fa-var-table); }\n.#{$fa-css-prefix}-table-tennis:before { content: fa-content($fa-var-table-tennis); }\n.#{$fa-css-prefix}-tablet:before { content: fa-content($fa-var-tablet); }\n.#{$fa-css-prefix}-tablet-alt:before { content: fa-content($fa-var-tablet-alt); }\n.#{$fa-css-prefix}-tablets:before { content: fa-content($fa-var-tablets); }\n.#{$fa-css-prefix}-tachometer-alt:before { content: fa-content($fa-var-tachometer-alt); }\n.#{$fa-css-prefix}-tag:before { content: fa-content($fa-var-tag); }\n.#{$fa-css-prefix}-tags:before { content: fa-content($fa-var-tags); }\n.#{$fa-css-prefix}-tape:before { content: fa-content($fa-var-tape); }\n.#{$fa-css-prefix}-tasks:before { content: fa-content($fa-var-tasks); }\n.#{$fa-css-prefix}-taxi:before { content: fa-content($fa-var-taxi); }\n.#{$fa-css-prefix}-teamspeak:before { content: fa-content($fa-var-teamspeak); }\n.#{$fa-css-prefix}-teeth:before { content: fa-content($fa-var-teeth); }\n.#{$fa-css-prefix}-teeth-open:before { content: fa-content($fa-var-teeth-open); }\n.#{$fa-css-prefix}-telegram:before { content: fa-content($fa-var-telegram); }\n.#{$fa-css-prefix}-telegram-plane:before { content: fa-content($fa-var-telegram-plane); }\n.#{$fa-css-prefix}-temperature-high:before { content: fa-content($fa-var-temperature-high); }\n.#{$fa-css-prefix}-temperature-low:before { content: fa-content($fa-var-temperature-low); }\n.#{$fa-css-prefix}-tencent-weibo:before { content: fa-content($fa-var-tencent-weibo); }\n.#{$fa-css-prefix}-tenge:before { content: fa-content($fa-var-tenge); }\n.#{$fa-css-prefix}-terminal:before { content: fa-content($fa-var-terminal); }\n.#{$fa-css-prefix}-text-height:before { content: fa-content($fa-var-text-height); }\n.#{$fa-css-prefix}-text-width:before { content: fa-content($fa-var-text-width); }\n.#{$fa-css-prefix}-th:before { content: fa-content($fa-var-th); }\n.#{$fa-css-prefix}-th-large:before { content: fa-content($fa-var-th-large); }\n.#{$fa-css-prefix}-th-list:before { content: fa-content($fa-var-th-list); }\n.#{$fa-css-prefix}-the-red-yeti:before { content: fa-content($fa-var-the-red-yeti); }\n.#{$fa-css-prefix}-theater-masks:before { content: fa-content($fa-var-theater-masks); }\n.#{$fa-css-prefix}-themeco:before { content: fa-content($fa-var-themeco); }\n.#{$fa-css-prefix}-themeisle:before { content: fa-content($fa-var-themeisle); }\n.#{$fa-css-prefix}-thermometer:before { content: fa-content($fa-var-thermometer); }\n.#{$fa-css-prefix}-thermometer-empty:before { content: fa-content($fa-var-thermometer-empty); }\n.#{$fa-css-prefix}-thermometer-full:before { content: fa-content($fa-var-thermometer-full); }\n.#{$fa-css-prefix}-thermometer-half:before { content: fa-content($fa-var-thermometer-half); }\n.#{$fa-css-prefix}-thermometer-quarter:before { content: fa-content($fa-var-thermometer-quarter); }\n.#{$fa-css-prefix}-thermometer-three-quarters:before { content: fa-content($fa-var-thermometer-three-quarters); }\n.#{$fa-css-prefix}-think-peaks:before { content: fa-content($fa-var-think-peaks); }\n.#{$fa-css-prefix}-thumbs-down:before { content: fa-content($fa-var-thumbs-down); }\n.#{$fa-css-prefix}-thumbs-up:before { content: fa-content($fa-var-thumbs-up); }\n.#{$fa-css-prefix}-thumbtack:before { content: fa-content($fa-var-thumbtack); }\n.#{$fa-css-prefix}-ticket-alt:before { content: fa-content($fa-var-ticket-alt); }\n.#{$fa-css-prefix}-times:before { content: fa-content($fa-var-times); }\n.#{$fa-css-prefix}-times-circle:before { content: fa-content($fa-var-times-circle); }\n.#{$fa-css-prefix}-tint:before { content: fa-content($fa-var-tint); }\n.#{$fa-css-prefix}-tint-slash:before { content: fa-content($fa-var-tint-slash); }\n.#{$fa-css-prefix}-tired:before { content: fa-content($fa-var-tired); }\n.#{$fa-css-prefix}-toggle-off:before { content: fa-content($fa-var-toggle-off); }\n.#{$fa-css-prefix}-toggle-on:before { content: fa-content($fa-var-toggle-on); }\n.#{$fa-css-prefix}-toilet:before { content: fa-content($fa-var-toilet); }\n.#{$fa-css-prefix}-toilet-paper:before { content: fa-content($fa-var-toilet-paper); }\n.#{$fa-css-prefix}-toolbox:before { content: fa-content($fa-var-toolbox); }\n.#{$fa-css-prefix}-tools:before { content: fa-content($fa-var-tools); }\n.#{$fa-css-prefix}-tooth:before { content: fa-content($fa-var-tooth); }\n.#{$fa-css-prefix}-torah:before { content: fa-content($fa-var-torah); }\n.#{$fa-css-prefix}-torii-gate:before { content: fa-content($fa-var-torii-gate); }\n.#{$fa-css-prefix}-tractor:before { content: fa-content($fa-var-tractor); }\n.#{$fa-css-prefix}-trade-federation:before { content: fa-content($fa-var-trade-federation); }\n.#{$fa-css-prefix}-trademark:before { content: fa-content($fa-var-trademark); }\n.#{$fa-css-prefix}-traffic-light:before { content: fa-content($fa-var-traffic-light); }\n.#{$fa-css-prefix}-train:before { content: fa-content($fa-var-train); }\n.#{$fa-css-prefix}-tram:before { content: fa-content($fa-var-tram); }\n.#{$fa-css-prefix}-transgender:before { content: fa-content($fa-var-transgender); }\n.#{$fa-css-prefix}-transgender-alt:before { content: fa-content($fa-var-transgender-alt); }\n.#{$fa-css-prefix}-trash:before { content: fa-content($fa-var-trash); }\n.#{$fa-css-prefix}-trash-alt:before { content: fa-content($fa-var-trash-alt); }\n.#{$fa-css-prefix}-trash-restore:before { content: fa-content($fa-var-trash-restore); }\n.#{$fa-css-prefix}-trash-restore-alt:before { content: fa-content($fa-var-trash-restore-alt); }\n.#{$fa-css-prefix}-tree:before { content: fa-content($fa-var-tree); }\n.#{$fa-css-prefix}-trello:before { content: fa-content($fa-var-trello); }\n.#{$fa-css-prefix}-tripadvisor:before { content: fa-content($fa-var-tripadvisor); }\n.#{$fa-css-prefix}-trophy:before { content: fa-content($fa-var-trophy); }\n.#{$fa-css-prefix}-truck:before { content: fa-content($fa-var-truck); }\n.#{$fa-css-prefix}-truck-loading:before { content: fa-content($fa-var-truck-loading); }\n.#{$fa-css-prefix}-truck-monster:before { content: fa-content($fa-var-truck-monster); }\n.#{$fa-css-prefix}-truck-moving:before { content: fa-content($fa-var-truck-moving); }\n.#{$fa-css-prefix}-truck-pickup:before { content: fa-content($fa-var-truck-pickup); }\n.#{$fa-css-prefix}-tshirt:before { content: fa-content($fa-var-tshirt); }\n.#{$fa-css-prefix}-tty:before { content: fa-content($fa-var-tty); }\n.#{$fa-css-prefix}-tumblr:before { content: fa-content($fa-var-tumblr); }\n.#{$fa-css-prefix}-tumblr-square:before { content: fa-content($fa-var-tumblr-square); }\n.#{$fa-css-prefix}-tv:before { content: fa-content($fa-var-tv); }\n.#{$fa-css-prefix}-twitch:before { content: fa-content($fa-var-twitch); }\n.#{$fa-css-prefix}-twitter:before { content: fa-content($fa-var-twitter); }\n.#{$fa-css-prefix}-twitter-square:before { content: fa-content($fa-var-twitter-square); }\n.#{$fa-css-prefix}-typo3:before { content: fa-content($fa-var-typo3); }\n.#{$fa-css-prefix}-uber:before { content: fa-content($fa-var-uber); }\n.#{$fa-css-prefix}-ubuntu:before { content: fa-content($fa-var-ubuntu); }\n.#{$fa-css-prefix}-uikit:before { content: fa-content($fa-var-uikit); }\n.#{$fa-css-prefix}-umbrella:before { content: fa-content($fa-var-umbrella); }\n.#{$fa-css-prefix}-umbrella-beach:before { content: fa-content($fa-var-umbrella-beach); }\n.#{$fa-css-prefix}-underline:before { content: fa-content($fa-var-underline); }\n.#{$fa-css-prefix}-undo:before { content: fa-content($fa-var-undo); }\n.#{$fa-css-prefix}-undo-alt:before { content: fa-content($fa-var-undo-alt); }\n.#{$fa-css-prefix}-uniregistry:before { content: fa-content($fa-var-uniregistry); }\n.#{$fa-css-prefix}-universal-access:before { content: fa-content($fa-var-universal-access); }\n.#{$fa-css-prefix}-university:before { content: fa-content($fa-var-university); }\n.#{$fa-css-prefix}-unlink:before { content: fa-content($fa-var-unlink); }\n.#{$fa-css-prefix}-unlock:before { content: fa-content($fa-var-unlock); }\n.#{$fa-css-prefix}-unlock-alt:before { content: fa-content($fa-var-unlock-alt); }\n.#{$fa-css-prefix}-untappd:before { content: fa-content($fa-var-untappd); }\n.#{$fa-css-prefix}-upload:before { content: fa-content($fa-var-upload); }\n.#{$fa-css-prefix}-ups:before { content: fa-content($fa-var-ups); }\n.#{$fa-css-prefix}-usb:before { content: fa-content($fa-var-usb); }\n.#{$fa-css-prefix}-user:before { content: fa-content($fa-var-user); }\n.#{$fa-css-prefix}-user-alt:before { content: fa-content($fa-var-user-alt); }\n.#{$fa-css-prefix}-user-alt-slash:before { content: fa-content($fa-var-user-alt-slash); }\n.#{$fa-css-prefix}-user-astronaut:before { content: fa-content($fa-var-user-astronaut); }\n.#{$fa-css-prefix}-user-check:before { content: fa-content($fa-var-user-check); }\n.#{$fa-css-prefix}-user-circle:before { content: fa-content($fa-var-user-circle); }\n.#{$fa-css-prefix}-user-clock:before { content: fa-content($fa-var-user-clock); }\n.#{$fa-css-prefix}-user-cog:before { content: fa-content($fa-var-user-cog); }\n.#{$fa-css-prefix}-user-edit:before { content: fa-content($fa-var-user-edit); }\n.#{$fa-css-prefix}-user-friends:before { content: fa-content($fa-var-user-friends); }\n.#{$fa-css-prefix}-user-graduate:before { content: fa-content($fa-var-user-graduate); }\n.#{$fa-css-prefix}-user-injured:before { content: fa-content($fa-var-user-injured); }\n.#{$fa-css-prefix}-user-lock:before { content: fa-content($fa-var-user-lock); }\n.#{$fa-css-prefix}-user-md:before { content: fa-content($fa-var-user-md); }\n.#{$fa-css-prefix}-user-minus:before { content: fa-content($fa-var-user-minus); }\n.#{$fa-css-prefix}-user-ninja:before { content: fa-content($fa-var-user-ninja); }\n.#{$fa-css-prefix}-user-nurse:before { content: fa-content($fa-var-user-nurse); }\n.#{$fa-css-prefix}-user-plus:before { content: fa-content($fa-var-user-plus); }\n.#{$fa-css-prefix}-user-secret:before { content: fa-content($fa-var-user-secret); }\n.#{$fa-css-prefix}-user-shield:before { content: fa-content($fa-var-user-shield); }\n.#{$fa-css-prefix}-user-slash:before { content: fa-content($fa-var-user-slash); }\n.#{$fa-css-prefix}-user-tag:before { content: fa-content($fa-var-user-tag); }\n.#{$fa-css-prefix}-user-tie:before { content: fa-content($fa-var-user-tie); }\n.#{$fa-css-prefix}-user-times:before { content: fa-content($fa-var-user-times); }\n.#{$fa-css-prefix}-users:before { content: fa-content($fa-var-users); }\n.#{$fa-css-prefix}-users-cog:before { content: fa-content($fa-var-users-cog); }\n.#{$fa-css-prefix}-usps:before { content: fa-content($fa-var-usps); }\n.#{$fa-css-prefix}-ussunnah:before { content: fa-content($fa-var-ussunnah); }\n.#{$fa-css-prefix}-utensil-spoon:before { content: fa-content($fa-var-utensil-spoon); }\n.#{$fa-css-prefix}-utensils:before { content: fa-content($fa-var-utensils); }\n.#{$fa-css-prefix}-vaadin:before { content: fa-content($fa-var-vaadin); }\n.#{$fa-css-prefix}-vector-square:before { content: fa-content($fa-var-vector-square); }\n.#{$fa-css-prefix}-venus:before { content: fa-content($fa-var-venus); }\n.#{$fa-css-prefix}-venus-double:before { content: fa-content($fa-var-venus-double); }\n.#{$fa-css-prefix}-venus-mars:before { content: fa-content($fa-var-venus-mars); }\n.#{$fa-css-prefix}-viacoin:before { content: fa-content($fa-var-viacoin); }\n.#{$fa-css-prefix}-viadeo:before { content: fa-content($fa-var-viadeo); }\n.#{$fa-css-prefix}-viadeo-square:before { content: fa-content($fa-var-viadeo-square); }\n.#{$fa-css-prefix}-vial:before { content: fa-content($fa-var-vial); }\n.#{$fa-css-prefix}-vials:before { content: fa-content($fa-var-vials); }\n.#{$fa-css-prefix}-viber:before { content: fa-content($fa-var-viber); }\n.#{$fa-css-prefix}-video:before { content: fa-content($fa-var-video); }\n.#{$fa-css-prefix}-video-slash:before { content: fa-content($fa-var-video-slash); }\n.#{$fa-css-prefix}-vihara:before { content: fa-content($fa-var-vihara); }\n.#{$fa-css-prefix}-vimeo:before { content: fa-content($fa-var-vimeo); }\n.#{$fa-css-prefix}-vimeo-square:before { content: fa-content($fa-var-vimeo-square); }\n.#{$fa-css-prefix}-vimeo-v:before { content: fa-content($fa-var-vimeo-v); }\n.#{$fa-css-prefix}-vine:before { content: fa-content($fa-var-vine); }\n.#{$fa-css-prefix}-vk:before { content: fa-content($fa-var-vk); }\n.#{$fa-css-prefix}-vnv:before { content: fa-content($fa-var-vnv); }\n.#{$fa-css-prefix}-voicemail:before { content: fa-content($fa-var-voicemail); }\n.#{$fa-css-prefix}-volleyball-ball:before { content: fa-content($fa-var-volleyball-ball); }\n.#{$fa-css-prefix}-volume-down:before { content: fa-content($fa-var-volume-down); }\n.#{$fa-css-prefix}-volume-mute:before { content: fa-content($fa-var-volume-mute); }\n.#{$fa-css-prefix}-volume-off:before { content: fa-content($fa-var-volume-off); }\n.#{$fa-css-prefix}-volume-up:before { content: fa-content($fa-var-volume-up); }\n.#{$fa-css-prefix}-vote-yea:before { content: fa-content($fa-var-vote-yea); }\n.#{$fa-css-prefix}-vr-cardboard:before { content: fa-content($fa-var-vr-cardboard); }\n.#{$fa-css-prefix}-vuejs:before { content: fa-content($fa-var-vuejs); }\n.#{$fa-css-prefix}-walking:before { content: fa-content($fa-var-walking); }\n.#{$fa-css-prefix}-wallet:before { content: fa-content($fa-var-wallet); }\n.#{$fa-css-prefix}-warehouse:before { content: fa-content($fa-var-warehouse); }\n.#{$fa-css-prefix}-water:before { content: fa-content($fa-var-water); }\n.#{$fa-css-prefix}-wave-square:before { content: fa-content($fa-var-wave-square); }\n.#{$fa-css-prefix}-waze:before { content: fa-content($fa-var-waze); }\n.#{$fa-css-prefix}-weebly:before { content: fa-content($fa-var-weebly); }\n.#{$fa-css-prefix}-weibo:before { content: fa-content($fa-var-weibo); }\n.#{$fa-css-prefix}-weight:before { content: fa-content($fa-var-weight); }\n.#{$fa-css-prefix}-weight-hanging:before { content: fa-content($fa-var-weight-hanging); }\n.#{$fa-css-prefix}-weixin:before { content: fa-content($fa-var-weixin); }\n.#{$fa-css-prefix}-whatsapp:before { content: fa-content($fa-var-whatsapp); }\n.#{$fa-css-prefix}-whatsapp-square:before { content: fa-content($fa-var-whatsapp-square); }\n.#{$fa-css-prefix}-wheelchair:before { content: fa-content($fa-var-wheelchair); }\n.#{$fa-css-prefix}-whmcs:before { content: fa-content($fa-var-whmcs); }\n.#{$fa-css-prefix}-wifi:before { content: fa-content($fa-var-wifi); }\n.#{$fa-css-prefix}-wikipedia-w:before { content: fa-content($fa-var-wikipedia-w); }\n.#{$fa-css-prefix}-wind:before { content: fa-content($fa-var-wind); }\n.#{$fa-css-prefix}-window-close:before { content: fa-content($fa-var-window-close); }\n.#{$fa-css-prefix}-window-maximize:before { content: fa-content($fa-var-window-maximize); }\n.#{$fa-css-prefix}-window-minimize:before { content: fa-content($fa-var-window-minimize); }\n.#{$fa-css-prefix}-window-restore:before { content: fa-content($fa-var-window-restore); }\n.#{$fa-css-prefix}-windows:before { content: fa-content($fa-var-windows); }\n.#{$fa-css-prefix}-wine-bottle:before { content: fa-content($fa-var-wine-bottle); }\n.#{$fa-css-prefix}-wine-glass:before { content: fa-content($fa-var-wine-glass); }\n.#{$fa-css-prefix}-wine-glass-alt:before { content: fa-content($fa-var-wine-glass-alt); }\n.#{$fa-css-prefix}-wix:before { content: fa-content($fa-var-wix); }\n.#{$fa-css-prefix}-wizards-of-the-coast:before { content: fa-content($fa-var-wizards-of-the-coast); }\n.#{$fa-css-prefix}-wolf-pack-battalion:before { content: fa-content($fa-var-wolf-pack-battalion); }\n.#{$fa-css-prefix}-won-sign:before { content: fa-content($fa-var-won-sign); }\n.#{$fa-css-prefix}-wordpress:before { content: fa-content($fa-var-wordpress); }\n.#{$fa-css-prefix}-wordpress-simple:before { content: fa-content($fa-var-wordpress-simple); }\n.#{$fa-css-prefix}-wpbeginner:before { content: fa-content($fa-var-wpbeginner); }\n.#{$fa-css-prefix}-wpexplorer:before { content: fa-content($fa-var-wpexplorer); }\n.#{$fa-css-prefix}-wpforms:before { content: fa-content($fa-var-wpforms); }\n.#{$fa-css-prefix}-wpressr:before { content: fa-content($fa-var-wpressr); }\n.#{$fa-css-prefix}-wrench:before { content: fa-content($fa-var-wrench); }\n.#{$fa-css-prefix}-x-ray:before { content: fa-content($fa-var-x-ray); }\n.#{$fa-css-prefix}-xbox:before { content: fa-content($fa-var-xbox); }\n.#{$fa-css-prefix}-xing:before { content: fa-content($fa-var-xing); }\n.#{$fa-css-prefix}-xing-square:before { content: fa-content($fa-var-xing-square); }\n.#{$fa-css-prefix}-y-combinator:before { content: fa-content($fa-var-y-combinator); }\n.#{$fa-css-prefix}-yahoo:before { content: fa-content($fa-var-yahoo); }\n.#{$fa-css-prefix}-yammer:before { content: fa-content($fa-var-yammer); }\n.#{$fa-css-prefix}-yandex:before { content: fa-content($fa-var-yandex); }\n.#{$fa-css-prefix}-yandex-international:before { content: fa-content($fa-var-yandex-international); }\n.#{$fa-css-prefix}-yarn:before { content: fa-content($fa-var-yarn); }\n.#{$fa-css-prefix}-yelp:before { content: fa-content($fa-var-yelp); }\n.#{$fa-css-prefix}-yen-sign:before { content: fa-content($fa-var-yen-sign); }\n.#{$fa-css-prefix}-yin-yang:before { content: fa-content($fa-var-yin-yang); }\n.#{$fa-css-prefix}-yoast:before { content: fa-content($fa-var-yoast); }\n.#{$fa-css-prefix}-youtube:before { content: fa-content($fa-var-youtube); }\n.#{$fa-css-prefix}-youtube-square:before { content: fa-content($fa-var-youtube-square); }\n.#{$fa-css-prefix}-zhihu:before { content: fa-content($fa-var-zhihu); }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_larger.scss",
    "content": "// Icon Sizes\n// -------------------------\n\n// makes the font 33% larger relative to the icon container\n.#{$fa-css-prefix}-lg {\n  font-size: (4em / 3);\n  line-height: (3em / 4);\n  vertical-align: -.0667em;\n}\n\n.#{$fa-css-prefix}-xs {\n  font-size: .75em;\n}\n\n.#{$fa-css-prefix}-sm {\n  font-size: .875em;\n}\n\n@for $i from 1 through 10 {\n  .#{$fa-css-prefix}-#{$i}x {\n    font-size: $i * 1em;\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_list.scss",
    "content": "// List Icons\n// -------------------------\n\n.#{$fa-css-prefix}-ul {\n  list-style-type: none;\n  margin-left: $fa-li-width * 5/4;\n  padding-left: 0;\n\n  > li { position: relative; }\n}\n\n.#{$fa-css-prefix}-li {\n  left: -$fa-li-width;\n  position: absolute;\n  text-align: center;\n  width: $fa-li-width;\n  line-height: inherit;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_mixins.scss",
    "content": "// Mixins\n// --------------------------\n\n@mixin fa-icon {\n  -webkit-font-smoothing: antialiased;\n  -moz-osx-font-smoothing: grayscale;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  font-weight: normal;\n  line-height: 1;\n}\n\n@mixin fa-icon-rotate($degrees, $rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=#{$rotation})\";\n  transform: rotate($degrees);\n}\n\n@mixin fa-icon-flip($horiz, $vert, $rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=#{$rotation}, mirror=1)\";\n  transform: scale($horiz, $vert);\n}\n\n\n// Only display content to screen readers. A la Bootstrap 4.\n//\n// See: http://a11yproject.com/posts/how-to-hide-content/\n\n@mixin sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px;\n}\n\n// Use in conjunction with .sr-only to only display content when it's focused.\n//\n// Useful for \"Skip to main content\" links; see http://www.w3.org/TR/2013/NOTE-WCAG20-TECHS-20130905/G1\n//\n// Credit: HTML5 Boilerplate\n\n@mixin sr-only-focusable {\n  &:active,\n  &:focus {\n    clip: auto;\n    height: auto;\n    margin: 0;\n    overflow: visible;\n    position: static;\n    width: auto;\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_rotated-flipped.scss",
    "content": "// Rotated & Flipped Icons\n// -------------------------\n\n.#{$fa-css-prefix}-rotate-90  { @include fa-icon-rotate(90deg, 1);  }\n.#{$fa-css-prefix}-rotate-180 { @include fa-icon-rotate(180deg, 2); }\n.#{$fa-css-prefix}-rotate-270 { @include fa-icon-rotate(270deg, 3); }\n\n.#{$fa-css-prefix}-flip-horizontal { @include fa-icon-flip(-1, 1, 0); }\n.#{$fa-css-prefix}-flip-vertical   { @include fa-icon-flip(1, -1, 2); }\n.#{$fa-css-prefix}-flip-both, .#{$fa-css-prefix}-flip-horizontal.#{$fa-css-prefix}-flip-vertical { @include fa-icon-flip(-1, -1, 2); }\n\n// Hook for IE8-9\n// -------------------------\n\n:root {\n  .#{$fa-css-prefix}-rotate-90,\n  .#{$fa-css-prefix}-rotate-180,\n  .#{$fa-css-prefix}-rotate-270,\n  .#{$fa-css-prefix}-flip-horizontal,\n  .#{$fa-css-prefix}-flip-vertical,\n  .#{$fa-css-prefix}-flip-both {\n    filter: none;\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_screen-reader.scss",
    "content": "// Screen Readers\n// -------------------------\n\n.sr-only { @include sr-only; }\n.sr-only-focusable { @include sr-only-focusable; }\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_shims.scss",
    "content": ".#{$fa-css-prefix}.#{$fa-css-prefix}-glass:before { content: fa-content($fa-var-glass-martini); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meetup {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-o:before { content: fa-content($fa-var-star); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-remove:before { content: fa-content($fa-var-times); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-close:before { content: fa-content($fa-var-times); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gear:before { content: fa-content($fa-var-cog); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trash-o:before { content: fa-content($fa-var-trash-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-o:before { content: fa-content($fa-var-file); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clock-o:before { content: fa-content($fa-var-clock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-down:before { content: fa-content($fa-var-arrow-alt-circle-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-up:before { content: fa-content($fa-var-arrow-alt-circle-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-play-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-play-circle-o:before { content: fa-content($fa-var-play-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-repeat:before { content: fa-content($fa-var-redo); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rotate-right:before { content: fa-content($fa-var-redo); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-refresh:before { content: fa-content($fa-var-sync); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-list-alt {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dedent:before { content: fa-content($fa-var-outdent); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-video-camera:before { content: fa-content($fa-var-video); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-picture-o:before { content: fa-content($fa-var-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-photo {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-photo:before { content: fa-content($fa-var-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-image {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-image:before { content: fa-content($fa-var-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil:before { content: fa-content($fa-var-pencil-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-map-marker:before { content: fa-content($fa-var-map-marker-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil-square-o:before { content: fa-content($fa-var-edit); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-share-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-share-square-o:before { content: fa-content($fa-var-share-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-square-o:before { content: fa-content($fa-var-check-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows:before { content: fa-content($fa-var-arrows-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-circle-o:before { content: fa-content($fa-var-times-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-circle-o:before { content: fa-content($fa-var-check-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mail-forward:before { content: fa-content($fa-var-share); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eye {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eye-slash {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-warning:before { content: fa-content($fa-var-exclamation-triangle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar:before { content: fa-content($fa-var-calendar-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows-v:before { content: fa-content($fa-var-arrows-alt-v); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows-h:before { content: fa-content($fa-var-arrows-alt-h); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart:before { content: fa-content($fa-var-chart-bar); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart-o:before { content: fa-content($fa-var-chart-bar); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-twitter-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gears:before { content: fa-content($fa-var-cogs); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-up:before { content: fa-content($fa-var-thumbs-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-down:before { content: fa-content($fa-var-thumbs-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-heart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-heart-o:before { content: fa-content($fa-var-heart); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sign-out:before { content: fa-content($fa-var-sign-out-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin-square:before { content: fa-content($fa-var-linkedin); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumb-tack:before { content: fa-content($fa-var-thumbtack); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-external-link:before { content: fa-content($fa-var-external-link-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sign-in:before { content: fa-content($fa-var-sign-in-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-github-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lemon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lemon-o:before { content: fa-content($fa-var-lemon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-square-o:before { content: fa-content($fa-var-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bookmark-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bookmark-o:before { content: fa-content($fa-var-bookmark); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-twitter {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook:before { content: fa-content($fa-var-facebook-f); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-f {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-f:before { content: fa-content($fa-var-facebook-f); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-github {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-credit-card {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-feed:before { content: fa-content($fa-var-rss); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hdd-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hdd-o:before { content: fa-content($fa-var-hdd); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-right:before { content: fa-content($fa-var-hand-point-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-left:before { content: fa-content($fa-var-hand-point-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-up:before { content: fa-content($fa-var-hand-point-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-down:before { content: fa-content($fa-var-hand-point-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows-alt:before { content: fa-content($fa-var-expand-arrows-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-group:before { content: fa-content($fa-var-users); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-chain:before { content: fa-content($fa-var-link); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-scissors:before { content: fa-content($fa-var-cut); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-files-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-files-o:before { content: fa-content($fa-var-copy); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-floppy-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-floppy-o:before { content: fa-content($fa-var-save); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-navicon:before { content: fa-content($fa-var-bars); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reorder:before { content: fa-content($fa-var-bars); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pinterest {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pinterest-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus:before { content: fa-content($fa-var-google-plus-g); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-money {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-money:before { content: fa-content($fa-var-money-bill-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-unsorted:before { content: fa-content($fa-var-sort); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-desc:before { content: fa-content($fa-var-sort-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-asc:before { content: fa-content($fa-var-sort-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin:before { content: fa-content($fa-var-linkedin-in); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rotate-left:before { content: fa-content($fa-var-undo); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-legal:before { content: fa-content($fa-var-gavel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tachometer:before { content: fa-content($fa-var-tachometer-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dashboard:before { content: fa-content($fa-var-tachometer-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comment-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comment-o:before { content: fa-content($fa-var-comment); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comments-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comments-o:before { content: fa-content($fa-var-comments); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flash:before { content: fa-content($fa-var-bolt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clipboard {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paste {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paste:before { content: fa-content($fa-var-clipboard); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lightbulb-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lightbulb-o:before { content: fa-content($fa-var-lightbulb); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-exchange:before { content: fa-content($fa-var-exchange-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cloud-download:before { content: fa-content($fa-var-cloud-download-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cloud-upload:before { content: fa-content($fa-var-cloud-upload-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-o:before { content: fa-content($fa-var-bell); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cutlery:before { content: fa-content($fa-var-utensils); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-text-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-text-o:before { content: fa-content($fa-var-file-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-building-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-building-o:before { content: fa-content($fa-var-building); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hospital-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hospital-o:before { content: fa-content($fa-var-hospital); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tablet:before { content: fa-content($fa-var-tablet-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mobile:before { content: fa-content($fa-var-mobile-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mobile-phone:before { content: fa-content($fa-var-mobile-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-o:before { content: fa-content($fa-var-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mail-reply:before { content: fa-content($fa-var-reply); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-github-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-o:before { content: fa-content($fa-var-folder); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-open-o:before { content: fa-content($fa-var-folder-open); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-smile-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-smile-o:before { content: fa-content($fa-var-smile); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-frown-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-frown-o:before { content: fa-content($fa-var-frown); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meh-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meh-o:before { content: fa-content($fa-var-meh); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-keyboard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-keyboard-o:before { content: fa-content($fa-var-keyboard); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flag-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flag-o:before { content: fa-content($fa-var-flag); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mail-reply-all:before { content: fa-content($fa-var-reply-all); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-o:before { content: fa-content($fa-var-star-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-empty {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-empty:before { content: fa-content($fa-var-star-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-full {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-full:before { content: fa-content($fa-var-star-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-code-fork:before { content: fa-content($fa-var-code-branch); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-chain-broken:before { content: fa-content($fa-var-unlink); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-shield:before { content: fa-content($fa-var-shield-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-o:before { content: fa-content($fa-var-calendar); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-maxcdn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-html5 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-css3 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ticket:before { content: fa-content($fa-var-ticket-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-minus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-minus-square-o:before { content: fa-content($fa-var-minus-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-level-up:before { content: fa-content($fa-var-level-up-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-level-down:before { content: fa-content($fa-var-level-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil-square:before { content: fa-content($fa-var-pen-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-external-link-square:before { content: fa-content($fa-var-external-link-square-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-compass {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-down:before { content: fa-content($fa-var-caret-square-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-down:before { content: fa-content($fa-var-caret-square-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-up:before { content: fa-content($fa-var-caret-square-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-up:before { content: fa-content($fa-var-caret-square-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-right:before { content: fa-content($fa-var-caret-square-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-right:before { content: fa-content($fa-var-caret-square-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eur:before { content: fa-content($fa-var-euro-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-euro:before { content: fa-content($fa-var-euro-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gbp:before { content: fa-content($fa-var-pound-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-usd:before { content: fa-content($fa-var-dollar-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dollar:before { content: fa-content($fa-var-dollar-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-inr:before { content: fa-content($fa-var-rupee-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rupee:before { content: fa-content($fa-var-rupee-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-jpy:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cny:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rmb:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yen:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rub:before { content: fa-content($fa-var-ruble-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ruble:before { content: fa-content($fa-var-ruble-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rouble:before { content: fa-content($fa-var-ruble-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-krw:before { content: fa-content($fa-var-won-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-won:before { content: fa-content($fa-var-won-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-btc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitcoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitcoin:before { content: fa-content($fa-var-btc); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-text:before { content: fa-content($fa-var-file-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-alpha-asc:before { content: fa-content($fa-var-sort-alpha-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-alpha-desc:before { content: fa-content($fa-var-sort-alpha-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-amount-asc:before { content: fa-content($fa-var-sort-amount-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-amount-desc:before { content: fa-content($fa-var-sort-amount-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-numeric-asc:before { content: fa-content($fa-var-sort-numeric-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-numeric-desc:before { content: fa-content($fa-var-sort-numeric-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-xing {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-xing-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube-play {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube-play:before { content: fa-content($fa-var-youtube); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dropbox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stack-overflow {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-instagram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flickr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-adn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitbucket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitbucket-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitbucket-square:before { content: fa-content($fa-var-bitbucket); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tumblr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tumblr-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-down:before { content: fa-content($fa-var-long-arrow-alt-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-up:before { content: fa-content($fa-var-long-arrow-alt-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-left:before { content: fa-content($fa-var-long-arrow-alt-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-right:before { content: fa-content($fa-var-long-arrow-alt-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-apple {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-windows {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-android {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linux {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dribbble {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-skype {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-foursquare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trello {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gratipay {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gittip {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gittip:before { content: fa-content($fa-var-gratipay); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sun-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sun-o:before { content: fa-content($fa-var-sun); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-moon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-moon-o:before { content: fa-content($fa-var-moon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-renren {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pagelines {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stack-exchange {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-right:before { content: fa-content($fa-var-arrow-alt-circle-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-left:before { content: fa-content($fa-var-arrow-alt-circle-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-left:before { content: fa-content($fa-var-caret-square-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-left:before { content: fa-content($fa-var-caret-square-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dot-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dot-circle-o:before { content: fa-content($fa-var-dot-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vimeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-try:before { content: fa-content($fa-var-lira-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-turkish-lira:before { content: fa-content($fa-var-lira-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-plus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-plus-square-o:before { content: fa-content($fa-var-plus-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-slack {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wordpress {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-openid {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-institution:before { content: fa-content($fa-var-university); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bank:before { content: fa-content($fa-var-university); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mortar-board:before { content: fa-content($fa-var-graduation-cap); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yahoo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reddit {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reddit-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stumbleupon-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stumbleupon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-delicious {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-digg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pied-piper-pp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pied-piper-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drupal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-joomla {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-spoon:before { content: fa-content($fa-var-utensil-spoon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-behance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-behance-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-steam {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-steam-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-automobile:before { content: fa-content($fa-var-car); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cab:before { content: fa-content($fa-var-taxi); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-o:before { content: fa-content($fa-var-envelope); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-deviantart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-soundcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-pdf-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-pdf-o:before { content: fa-content($fa-var-file-pdf); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-word-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-word-o:before { content: fa-content($fa-var-file-word); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-excel-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-excel-o:before { content: fa-content($fa-var-file-excel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-powerpoint-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-powerpoint-o:before { content: fa-content($fa-var-file-powerpoint); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-image-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-image-o:before { content: fa-content($fa-var-file-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-photo-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-photo-o:before { content: fa-content($fa-var-file-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-picture-o:before { content: fa-content($fa-var-file-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-archive-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-archive-o:before { content: fa-content($fa-var-file-archive); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-zip-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-zip-o:before { content: fa-content($fa-var-file-archive); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-audio-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-audio-o:before { content: fa-content($fa-var-file-audio); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-sound-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-sound-o:before { content: fa-content($fa-var-file-audio); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-video-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-video-o:before { content: fa-content($fa-var-file-video); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-movie-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-movie-o:before { content: fa-content($fa-var-file-video); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-code-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-code-o:before { content: fa-content($fa-var-file-code); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vine {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-codepen {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-jsfiddle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-ring {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-bouy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-bouy:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-buoy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-buoy:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-saver {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-saver:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-support {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-support:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-o-notch:before { content: fa-content($fa-var-circle-notch); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rebel {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ra {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ra:before { content: fa-content($fa-var-rebel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-resistance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-resistance:before { content: fa-content($fa-var-rebel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-empire {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ge:before { content: fa-content($fa-var-empire); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-git-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-git {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hacker-news {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-y-combinator-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-y-combinator-square:before { content: fa-content($fa-var-hacker-news); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc-square:before { content: fa-content($fa-var-hacker-news); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tencent-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-qq {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-weixin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wechat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wechat:before { content: fa-content($fa-var-weixin); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-send:before { content: fa-content($fa-var-paper-plane); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paper-plane-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paper-plane-o:before { content: fa-content($fa-var-paper-plane); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-send-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-send-o:before { content: fa-content($fa-var-paper-plane); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-thin {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-thin:before { content: fa-content($fa-var-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-header:before { content: fa-content($fa-var-heading); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sliders:before { content: fa-content($fa-var-sliders-h); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-futbol-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-futbol-o:before { content: fa-content($fa-var-futbol); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-soccer-ball-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-soccer-ball-o:before { content: fa-content($fa-var-futbol); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-slideshare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-twitch {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yelp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-newspaper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-newspaper-o:before { content: fa-content($fa-var-newspaper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-wallet {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-visa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-mastercard {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-discover {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-amex {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-stripe {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-slash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-slash-o:before { content: fa-content($fa-var-bell-slash); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trash:before { content: fa-content($fa-var-trash-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-copyright {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eyedropper:before { content: fa-content($fa-var-eye-dropper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-area-chart:before { content: fa-content($fa-var-chart-area); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pie-chart:before { content: fa-content($fa-var-chart-pie); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-line-chart:before { content: fa-content($fa-var-chart-line); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lastfm {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lastfm-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ioxhost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-angellist {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc:before { content: fa-content($fa-var-closed-captioning); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ils:before { content: fa-content($fa-var-shekel-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-shekel:before { content: fa-content($fa-var-shekel-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sheqel:before { content: fa-content($fa-var-shekel-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meanpath {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meanpath:before { content: fa-content($fa-var-font-awesome); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-buysellads {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-connectdevelop {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dashcube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-forumbee {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-leanpub {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sellsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-shirtsinbulk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-simplybuilt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-skyatlas {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-diamond {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-diamond:before { content: fa-content($fa-var-gem); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-intersex:before { content: fa-content($fa-var-transgender); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-official:before { content: fa-content($fa-var-facebook); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pinterest-p {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-whatsapp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hotel:before { content: fa-content($fa-var-bed); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-viacoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-medium {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-y-combinator {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc:before { content: fa-content($fa-var-y-combinator); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-optin-monster {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-opencart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-expeditedssl {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-4:before { content: fa-content($fa-var-battery-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery:before { content: fa-content($fa-var-battery-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-3:before { content: fa-content($fa-var-battery-three-quarters); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-2:before { content: fa-content($fa-var-battery-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-1:before { content: fa-content($fa-var-battery-quarter); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-0:before { content: fa-content($fa-var-battery-empty); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-object-group {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-object-ungroup {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sticky-note-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sticky-note-o:before { content: fa-content($fa-var-sticky-note); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-jcb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-diners-club {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clone {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-o:before { content: fa-content($fa-var-hourglass); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-1:before { content: fa-content($fa-var-hourglass-start); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-2:before { content: fa-content($fa-var-hourglass-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-3:before { content: fa-content($fa-var-hourglass-end); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-rock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-rock-o:before { content: fa-content($fa-var-hand-rock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-grab-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-grab-o:before { content: fa-content($fa-var-hand-rock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-paper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-paper-o:before { content: fa-content($fa-var-hand-paper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-stop-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-stop-o:before { content: fa-content($fa-var-hand-paper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-scissors-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-scissors-o:before { content: fa-content($fa-var-hand-scissors); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-lizard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-lizard-o:before { content: fa-content($fa-var-hand-lizard); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-spock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-spock-o:before { content: fa-content($fa-var-hand-spock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-pointer-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-pointer-o:before { content: fa-content($fa-var-hand-pointer); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-peace-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-peace-o:before { content: fa-content($fa-var-hand-peace); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-registered {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-creative-commons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gg-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tripadvisor {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-odnoklassniki {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-odnoklassniki-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-get-pocket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wikipedia-w {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-safari {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-chrome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-firefox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-opera {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-internet-explorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-television:before { content: fa-content($fa-var-tv); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-contao {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-500px {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-amazon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-plus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-plus-o:before { content: fa-content($fa-var-calendar-plus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-minus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-minus-o:before { content: fa-content($fa-var-calendar-minus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-times-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-times-o:before { content: fa-content($fa-var-calendar-times); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-check-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-check-o:before { content: fa-content($fa-var-calendar-check); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-map-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-map-o:before { content: fa-content($fa-var-map); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-commenting:before { content: fa-content($fa-var-comment-dots); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-commenting-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-commenting-o:before { content: fa-content($fa-var-comment-dots); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-houzz {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vimeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vimeo:before { content: fa-content($fa-var-vimeo-v); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-black-tie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fonticons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reddit-alien {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-edge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-credit-card-alt:before { content: fa-content($fa-var-credit-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-codiepie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-modx {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fort-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-usb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-product-hunt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mixcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-scribd {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pause-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pause-circle-o:before { content: fa-content($fa-var-pause-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stop-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stop-circle-o:before { content: fa-content($fa-var-stop-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bluetooth {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bluetooth-b {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gitlab {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wpbeginner {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wpforms {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envira {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wheelchair-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wheelchair-alt:before { content: fa-content($fa-var-accessible-icon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-question-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-question-circle-o:before { content: fa-content($fa-var-question-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-volume-control-phone:before { content: fa-content($fa-var-phone-volume); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-asl-interpreting:before { content: fa-content($fa-var-american-sign-language-interpreting); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-deafness:before { content: fa-content($fa-var-deaf); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hard-of-hearing:before { content: fa-content($fa-var-deaf); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-glide {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-glide-g {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-signing:before { content: fa-content($fa-var-sign-language); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-viadeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-viadeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snapchat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snapchat-ghost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snapchat-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pied-piper {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-first-order {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yoast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-themeisle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-official:before { content: fa-content($fa-var-google-plus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-circle:before { content: fa-content($fa-var-google-plus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-font-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fa:before { content: fa-content($fa-var-font-awesome); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-handshake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-handshake-o:before { content: fa-content($fa-var-handshake); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-open-o:before { content: fa-content($fa-var-envelope-open); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linode {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-book-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-book-o:before { content: fa-content($fa-var-address-book); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vcard:before { content: fa-content($fa-var-address-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-card-o:before { content: fa-content($fa-var-address-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vcard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vcard-o:before { content: fa-content($fa-var-address-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-circle-o:before { content: fa-content($fa-var-user-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-o:before { content: fa-content($fa-var-user); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-id-badge {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drivers-license:before { content: fa-content($fa-var-id-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-id-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-id-card-o:before { content: fa-content($fa-var-id-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drivers-license-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drivers-license-o:before { content: fa-content($fa-var-id-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-quora {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-free-code-camp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-telegram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-4:before { content: fa-content($fa-var-thermometer-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer:before { content: fa-content($fa-var-thermometer-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-3:before { content: fa-content($fa-var-thermometer-three-quarters); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-2:before { content: fa-content($fa-var-thermometer-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-1:before { content: fa-content($fa-var-thermometer-quarter); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-0:before { content: fa-content($fa-var-thermometer-empty); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bathtub:before { content: fa-content($fa-var-bath); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-s15:before { content: fa-content($fa-var-bath); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-maximize {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-restore {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-rectangle:before { content: fa-content($fa-var-window-close); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-close-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-close-o:before { content: fa-content($fa-var-window-close); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-rectangle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-rectangle-o:before { content: fa-content($fa-var-window-close); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bandcamp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-grav {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-etsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-imdb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ravelry {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eercast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eercast:before { content: fa-content($fa-var-sellcast); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snowflake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snowflake-o:before { content: fa-content($fa-var-snowflake); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-superpowers {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wpexplorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-spotify {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_stacked.scss",
    "content": "// Stacked Icons\n// -------------------------\n\n.#{$fa-css-prefix}-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: ($fa-fw-width*2);\n}\n\n.#{$fa-css-prefix}-stack-1x,\n.#{$fa-css-prefix}-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%;\n}\n\n.#{$fa-css-prefix}-stack-1x {\n  line-height: inherit;\n}\n\n.#{$fa-css-prefix}-stack-2x {\n  font-size: 2em;\n}\n\n.#{$fa-css-prefix}-inverse {\n  color: $fa-inverse;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_variables.scss",
    "content": "// Variables\n// --------------------------\n\n$fa-font-path:         \"../webfonts\" !default;\n$fa-font-size-base:    16px !default;\n$fa-font-display:      auto !default;\n$fa-css-prefix:        fa !default;\n$fa-version:           \"5.10.2\" !default;\n$fa-border-color:      #eee !default;\n$fa-inverse:           #fff !default;\n$fa-li-width:          2em !default;\n$fa-fw-width:          (20em / 16);\n$fa-primary-opacity:   1 !default;\n$fa-secondary-opacity: .4 !default;\n\n// Convenience function used to set content property\n@function fa-content($fa-var) {\n  @return unquote(\"\\\"#{ $fa-var }\\\"\");\n}\n\n$fa-var-500px: \\f26e;\n$fa-var-accessible-icon: \\f368;\n$fa-var-accusoft: \\f369;\n$fa-var-acquisitions-incorporated: \\f6af;\n$fa-var-ad: \\f641;\n$fa-var-address-book: \\f2b9;\n$fa-var-address-card: \\f2bb;\n$fa-var-adjust: \\f042;\n$fa-var-adn: \\f170;\n$fa-var-adobe: \\f778;\n$fa-var-adversal: \\f36a;\n$fa-var-affiliatetheme: \\f36b;\n$fa-var-air-freshener: \\f5d0;\n$fa-var-airbnb: \\f834;\n$fa-var-algolia: \\f36c;\n$fa-var-align-center: \\f037;\n$fa-var-align-justify: \\f039;\n$fa-var-align-left: \\f036;\n$fa-var-align-right: \\f038;\n$fa-var-alipay: \\f642;\n$fa-var-allergies: \\f461;\n$fa-var-amazon: \\f270;\n$fa-var-amazon-pay: \\f42c;\n$fa-var-ambulance: \\f0f9;\n$fa-var-american-sign-language-interpreting: \\f2a3;\n$fa-var-amilia: \\f36d;\n$fa-var-anchor: \\f13d;\n$fa-var-android: \\f17b;\n$fa-var-angellist: \\f209;\n$fa-var-angle-double-down: \\f103;\n$fa-var-angle-double-left: \\f100;\n$fa-var-angle-double-right: \\f101;\n$fa-var-angle-double-up: \\f102;\n$fa-var-angle-down: \\f107;\n$fa-var-angle-left: \\f104;\n$fa-var-angle-right: \\f105;\n$fa-var-angle-up: \\f106;\n$fa-var-angry: \\f556;\n$fa-var-angrycreative: \\f36e;\n$fa-var-angular: \\f420;\n$fa-var-ankh: \\f644;\n$fa-var-app-store: \\f36f;\n$fa-var-app-store-ios: \\f370;\n$fa-var-apper: \\f371;\n$fa-var-apple: \\f179;\n$fa-var-apple-alt: \\f5d1;\n$fa-var-apple-pay: \\f415;\n$fa-var-archive: \\f187;\n$fa-var-archway: \\f557;\n$fa-var-arrow-alt-circle-down: \\f358;\n$fa-var-arrow-alt-circle-left: \\f359;\n$fa-var-arrow-alt-circle-right: \\f35a;\n$fa-var-arrow-alt-circle-up: \\f35b;\n$fa-var-arrow-circle-down: \\f0ab;\n$fa-var-arrow-circle-left: \\f0a8;\n$fa-var-arrow-circle-right: \\f0a9;\n$fa-var-arrow-circle-up: \\f0aa;\n$fa-var-arrow-down: \\f063;\n$fa-var-arrow-left: \\f060;\n$fa-var-arrow-right: \\f061;\n$fa-var-arrow-up: \\f062;\n$fa-var-arrows-alt: \\f0b2;\n$fa-var-arrows-alt-h: \\f337;\n$fa-var-arrows-alt-v: \\f338;\n$fa-var-artstation: \\f77a;\n$fa-var-assistive-listening-systems: \\f2a2;\n$fa-var-asterisk: \\f069;\n$fa-var-asymmetrik: \\f372;\n$fa-var-at: \\f1fa;\n$fa-var-atlas: \\f558;\n$fa-var-atlassian: \\f77b;\n$fa-var-atom: \\f5d2;\n$fa-var-audible: \\f373;\n$fa-var-audio-description: \\f29e;\n$fa-var-autoprefixer: \\f41c;\n$fa-var-avianex: \\f374;\n$fa-var-aviato: \\f421;\n$fa-var-award: \\f559;\n$fa-var-aws: \\f375;\n$fa-var-baby: \\f77c;\n$fa-var-baby-carriage: \\f77d;\n$fa-var-backspace: \\f55a;\n$fa-var-backward: \\f04a;\n$fa-var-bacon: \\f7e5;\n$fa-var-balance-scale: \\f24e;\n$fa-var-balance-scale-left: \\f515;\n$fa-var-balance-scale-right: \\f516;\n$fa-var-ban: \\f05e;\n$fa-var-band-aid: \\f462;\n$fa-var-bandcamp: \\f2d5;\n$fa-var-barcode: \\f02a;\n$fa-var-bars: \\f0c9;\n$fa-var-baseball-ball: \\f433;\n$fa-var-basketball-ball: \\f434;\n$fa-var-bath: \\f2cd;\n$fa-var-battery-empty: \\f244;\n$fa-var-battery-full: \\f240;\n$fa-var-battery-half: \\f242;\n$fa-var-battery-quarter: \\f243;\n$fa-var-battery-three-quarters: \\f241;\n$fa-var-battle-net: \\f835;\n$fa-var-bed: \\f236;\n$fa-var-beer: \\f0fc;\n$fa-var-behance: \\f1b4;\n$fa-var-behance-square: \\f1b5;\n$fa-var-bell: \\f0f3;\n$fa-var-bell-slash: \\f1f6;\n$fa-var-bezier-curve: \\f55b;\n$fa-var-bible: \\f647;\n$fa-var-bicycle: \\f206;\n$fa-var-biking: \\f84a;\n$fa-var-bimobject: \\f378;\n$fa-var-binoculars: \\f1e5;\n$fa-var-biohazard: \\f780;\n$fa-var-birthday-cake: \\f1fd;\n$fa-var-bitbucket: \\f171;\n$fa-var-bitcoin: \\f379;\n$fa-var-bity: \\f37a;\n$fa-var-black-tie: \\f27e;\n$fa-var-blackberry: \\f37b;\n$fa-var-blender: \\f517;\n$fa-var-blender-phone: \\f6b6;\n$fa-var-blind: \\f29d;\n$fa-var-blog: \\f781;\n$fa-var-blogger: \\f37c;\n$fa-var-blogger-b: \\f37d;\n$fa-var-bluetooth: \\f293;\n$fa-var-bluetooth-b: \\f294;\n$fa-var-bold: \\f032;\n$fa-var-bolt: \\f0e7;\n$fa-var-bomb: \\f1e2;\n$fa-var-bone: \\f5d7;\n$fa-var-bong: \\f55c;\n$fa-var-book: \\f02d;\n$fa-var-book-dead: \\f6b7;\n$fa-var-book-medical: \\f7e6;\n$fa-var-book-open: \\f518;\n$fa-var-book-reader: \\f5da;\n$fa-var-bookmark: \\f02e;\n$fa-var-bootstrap: \\f836;\n$fa-var-border-all: \\f84c;\n$fa-var-border-none: \\f850;\n$fa-var-border-style: \\f853;\n$fa-var-bowling-ball: \\f436;\n$fa-var-box: \\f466;\n$fa-var-box-open: \\f49e;\n$fa-var-boxes: \\f468;\n$fa-var-braille: \\f2a1;\n$fa-var-brain: \\f5dc;\n$fa-var-bread-slice: \\f7ec;\n$fa-var-briefcase: \\f0b1;\n$fa-var-briefcase-medical: \\f469;\n$fa-var-broadcast-tower: \\f519;\n$fa-var-broom: \\f51a;\n$fa-var-brush: \\f55d;\n$fa-var-btc: \\f15a;\n$fa-var-buffer: \\f837;\n$fa-var-bug: \\f188;\n$fa-var-building: \\f1ad;\n$fa-var-bullhorn: \\f0a1;\n$fa-var-bullseye: \\f140;\n$fa-var-burn: \\f46a;\n$fa-var-buromobelexperte: \\f37f;\n$fa-var-bus: \\f207;\n$fa-var-bus-alt: \\f55e;\n$fa-var-business-time: \\f64a;\n$fa-var-buysellads: \\f20d;\n$fa-var-calculator: \\f1ec;\n$fa-var-calendar: \\f133;\n$fa-var-calendar-alt: \\f073;\n$fa-var-calendar-check: \\f274;\n$fa-var-calendar-day: \\f783;\n$fa-var-calendar-minus: \\f272;\n$fa-var-calendar-plus: \\f271;\n$fa-var-calendar-times: \\f273;\n$fa-var-calendar-week: \\f784;\n$fa-var-camera: \\f030;\n$fa-var-camera-retro: \\f083;\n$fa-var-campground: \\f6bb;\n$fa-var-canadian-maple-leaf: \\f785;\n$fa-var-candy-cane: \\f786;\n$fa-var-cannabis: \\f55f;\n$fa-var-capsules: \\f46b;\n$fa-var-car: \\f1b9;\n$fa-var-car-alt: \\f5de;\n$fa-var-car-battery: \\f5df;\n$fa-var-car-crash: \\f5e1;\n$fa-var-car-side: \\f5e4;\n$fa-var-caret-down: \\f0d7;\n$fa-var-caret-left: \\f0d9;\n$fa-var-caret-right: \\f0da;\n$fa-var-caret-square-down: \\f150;\n$fa-var-caret-square-left: \\f191;\n$fa-var-caret-square-right: \\f152;\n$fa-var-caret-square-up: \\f151;\n$fa-var-caret-up: \\f0d8;\n$fa-var-carrot: \\f787;\n$fa-var-cart-arrow-down: \\f218;\n$fa-var-cart-plus: \\f217;\n$fa-var-cash-register: \\f788;\n$fa-var-cat: \\f6be;\n$fa-var-cc-amazon-pay: \\f42d;\n$fa-var-cc-amex: \\f1f3;\n$fa-var-cc-apple-pay: \\f416;\n$fa-var-cc-diners-club: \\f24c;\n$fa-var-cc-discover: \\f1f2;\n$fa-var-cc-jcb: \\f24b;\n$fa-var-cc-mastercard: \\f1f1;\n$fa-var-cc-paypal: \\f1f4;\n$fa-var-cc-stripe: \\f1f5;\n$fa-var-cc-visa: \\f1f0;\n$fa-var-centercode: \\f380;\n$fa-var-centos: \\f789;\n$fa-var-certificate: \\f0a3;\n$fa-var-chair: \\f6c0;\n$fa-var-chalkboard: \\f51b;\n$fa-var-chalkboard-teacher: \\f51c;\n$fa-var-charging-station: \\f5e7;\n$fa-var-chart-area: \\f1fe;\n$fa-var-chart-bar: \\f080;\n$fa-var-chart-line: \\f201;\n$fa-var-chart-pie: \\f200;\n$fa-var-check: \\f00c;\n$fa-var-check-circle: \\f058;\n$fa-var-check-double: \\f560;\n$fa-var-check-square: \\f14a;\n$fa-var-cheese: \\f7ef;\n$fa-var-chess: \\f439;\n$fa-var-chess-bishop: \\f43a;\n$fa-var-chess-board: \\f43c;\n$fa-var-chess-king: \\f43f;\n$fa-var-chess-knight: \\f441;\n$fa-var-chess-pawn: \\f443;\n$fa-var-chess-queen: \\f445;\n$fa-var-chess-rook: \\f447;\n$fa-var-chevron-circle-down: \\f13a;\n$fa-var-chevron-circle-left: \\f137;\n$fa-var-chevron-circle-right: \\f138;\n$fa-var-chevron-circle-up: \\f139;\n$fa-var-chevron-down: \\f078;\n$fa-var-chevron-left: \\f053;\n$fa-var-chevron-right: \\f054;\n$fa-var-chevron-up: \\f077;\n$fa-var-child: \\f1ae;\n$fa-var-chrome: \\f268;\n$fa-var-chromecast: \\f838;\n$fa-var-church: \\f51d;\n$fa-var-circle: \\f111;\n$fa-var-circle-notch: \\f1ce;\n$fa-var-city: \\f64f;\n$fa-var-clinic-medical: \\f7f2;\n$fa-var-clipboard: \\f328;\n$fa-var-clipboard-check: \\f46c;\n$fa-var-clipboard-list: \\f46d;\n$fa-var-clock: \\f017;\n$fa-var-clone: \\f24d;\n$fa-var-closed-captioning: \\f20a;\n$fa-var-cloud: \\f0c2;\n$fa-var-cloud-download-alt: \\f381;\n$fa-var-cloud-meatball: \\f73b;\n$fa-var-cloud-moon: \\f6c3;\n$fa-var-cloud-moon-rain: \\f73c;\n$fa-var-cloud-rain: \\f73d;\n$fa-var-cloud-showers-heavy: \\f740;\n$fa-var-cloud-sun: \\f6c4;\n$fa-var-cloud-sun-rain: \\f743;\n$fa-var-cloud-upload-alt: \\f382;\n$fa-var-cloudscale: \\f383;\n$fa-var-cloudsmith: \\f384;\n$fa-var-cloudversify: \\f385;\n$fa-var-cocktail: \\f561;\n$fa-var-code: \\f121;\n$fa-var-code-branch: \\f126;\n$fa-var-codepen: \\f1cb;\n$fa-var-codiepie: \\f284;\n$fa-var-coffee: \\f0f4;\n$fa-var-cog: \\f013;\n$fa-var-cogs: \\f085;\n$fa-var-coins: \\f51e;\n$fa-var-columns: \\f0db;\n$fa-var-comment: \\f075;\n$fa-var-comment-alt: \\f27a;\n$fa-var-comment-dollar: \\f651;\n$fa-var-comment-dots: \\f4ad;\n$fa-var-comment-medical: \\f7f5;\n$fa-var-comment-slash: \\f4b3;\n$fa-var-comments: \\f086;\n$fa-var-comments-dollar: \\f653;\n$fa-var-compact-disc: \\f51f;\n$fa-var-compass: \\f14e;\n$fa-var-compress: \\f066;\n$fa-var-compress-arrows-alt: \\f78c;\n$fa-var-concierge-bell: \\f562;\n$fa-var-confluence: \\f78d;\n$fa-var-connectdevelop: \\f20e;\n$fa-var-contao: \\f26d;\n$fa-var-cookie: \\f563;\n$fa-var-cookie-bite: \\f564;\n$fa-var-copy: \\f0c5;\n$fa-var-copyright: \\f1f9;\n$fa-var-cotton-bureau: \\f89e;\n$fa-var-couch: \\f4b8;\n$fa-var-cpanel: \\f388;\n$fa-var-creative-commons: \\f25e;\n$fa-var-creative-commons-by: \\f4e7;\n$fa-var-creative-commons-nc: \\f4e8;\n$fa-var-creative-commons-nc-eu: \\f4e9;\n$fa-var-creative-commons-nc-jp: \\f4ea;\n$fa-var-creative-commons-nd: \\f4eb;\n$fa-var-creative-commons-pd: \\f4ec;\n$fa-var-creative-commons-pd-alt: \\f4ed;\n$fa-var-creative-commons-remix: \\f4ee;\n$fa-var-creative-commons-sa: \\f4ef;\n$fa-var-creative-commons-sampling: \\f4f0;\n$fa-var-creative-commons-sampling-plus: \\f4f1;\n$fa-var-creative-commons-share: \\f4f2;\n$fa-var-creative-commons-zero: \\f4f3;\n$fa-var-credit-card: \\f09d;\n$fa-var-critical-role: \\f6c9;\n$fa-var-crop: \\f125;\n$fa-var-crop-alt: \\f565;\n$fa-var-cross: \\f654;\n$fa-var-crosshairs: \\f05b;\n$fa-var-crow: \\f520;\n$fa-var-crown: \\f521;\n$fa-var-crutch: \\f7f7;\n$fa-var-css3: \\f13c;\n$fa-var-css3-alt: \\f38b;\n$fa-var-cube: \\f1b2;\n$fa-var-cubes: \\f1b3;\n$fa-var-cut: \\f0c4;\n$fa-var-cuttlefish: \\f38c;\n$fa-var-d-and-d: \\f38d;\n$fa-var-d-and-d-beyond: \\f6ca;\n$fa-var-dashcube: \\f210;\n$fa-var-database: \\f1c0;\n$fa-var-deaf: \\f2a4;\n$fa-var-delicious: \\f1a5;\n$fa-var-democrat: \\f747;\n$fa-var-deploydog: \\f38e;\n$fa-var-deskpro: \\f38f;\n$fa-var-desktop: \\f108;\n$fa-var-dev: \\f6cc;\n$fa-var-deviantart: \\f1bd;\n$fa-var-dharmachakra: \\f655;\n$fa-var-dhl: \\f790;\n$fa-var-diagnoses: \\f470;\n$fa-var-diaspora: \\f791;\n$fa-var-dice: \\f522;\n$fa-var-dice-d20: \\f6cf;\n$fa-var-dice-d6: \\f6d1;\n$fa-var-dice-five: \\f523;\n$fa-var-dice-four: \\f524;\n$fa-var-dice-one: \\f525;\n$fa-var-dice-six: \\f526;\n$fa-var-dice-three: \\f527;\n$fa-var-dice-two: \\f528;\n$fa-var-digg: \\f1a6;\n$fa-var-digital-ocean: \\f391;\n$fa-var-digital-tachograph: \\f566;\n$fa-var-directions: \\f5eb;\n$fa-var-discord: \\f392;\n$fa-var-discourse: \\f393;\n$fa-var-divide: \\f529;\n$fa-var-dizzy: \\f567;\n$fa-var-dna: \\f471;\n$fa-var-dochub: \\f394;\n$fa-var-docker: \\f395;\n$fa-var-dog: \\f6d3;\n$fa-var-dollar-sign: \\f155;\n$fa-var-dolly: \\f472;\n$fa-var-dolly-flatbed: \\f474;\n$fa-var-donate: \\f4b9;\n$fa-var-door-closed: \\f52a;\n$fa-var-door-open: \\f52b;\n$fa-var-dot-circle: \\f192;\n$fa-var-dove: \\f4ba;\n$fa-var-download: \\f019;\n$fa-var-draft2digital: \\f396;\n$fa-var-drafting-compass: \\f568;\n$fa-var-dragon: \\f6d5;\n$fa-var-draw-polygon: \\f5ee;\n$fa-var-dribbble: \\f17d;\n$fa-var-dribbble-square: \\f397;\n$fa-var-dropbox: \\f16b;\n$fa-var-drum: \\f569;\n$fa-var-drum-steelpan: \\f56a;\n$fa-var-drumstick-bite: \\f6d7;\n$fa-var-drupal: \\f1a9;\n$fa-var-dumbbell: \\f44b;\n$fa-var-dumpster: \\f793;\n$fa-var-dumpster-fire: \\f794;\n$fa-var-dungeon: \\f6d9;\n$fa-var-dyalog: \\f399;\n$fa-var-earlybirds: \\f39a;\n$fa-var-ebay: \\f4f4;\n$fa-var-edge: \\f282;\n$fa-var-edit: \\f044;\n$fa-var-egg: \\f7fb;\n$fa-var-eject: \\f052;\n$fa-var-elementor: \\f430;\n$fa-var-ellipsis-h: \\f141;\n$fa-var-ellipsis-v: \\f142;\n$fa-var-ello: \\f5f1;\n$fa-var-ember: \\f423;\n$fa-var-empire: \\f1d1;\n$fa-var-envelope: \\f0e0;\n$fa-var-envelope-open: \\f2b6;\n$fa-var-envelope-open-text: \\f658;\n$fa-var-envelope-square: \\f199;\n$fa-var-envira: \\f299;\n$fa-var-equals: \\f52c;\n$fa-var-eraser: \\f12d;\n$fa-var-erlang: \\f39d;\n$fa-var-ethereum: \\f42e;\n$fa-var-ethernet: \\f796;\n$fa-var-etsy: \\f2d7;\n$fa-var-euro-sign: \\f153;\n$fa-var-evernote: \\f839;\n$fa-var-exchange-alt: \\f362;\n$fa-var-exclamation: \\f12a;\n$fa-var-exclamation-circle: \\f06a;\n$fa-var-exclamation-triangle: \\f071;\n$fa-var-expand: \\f065;\n$fa-var-expand-arrows-alt: \\f31e;\n$fa-var-expeditedssl: \\f23e;\n$fa-var-external-link-alt: \\f35d;\n$fa-var-external-link-square-alt: \\f360;\n$fa-var-eye: \\f06e;\n$fa-var-eye-dropper: \\f1fb;\n$fa-var-eye-slash: \\f070;\n$fa-var-facebook: \\f09a;\n$fa-var-facebook-f: \\f39e;\n$fa-var-facebook-messenger: \\f39f;\n$fa-var-facebook-square: \\f082;\n$fa-var-fan: \\f863;\n$fa-var-fantasy-flight-games: \\f6dc;\n$fa-var-fast-backward: \\f049;\n$fa-var-fast-forward: \\f050;\n$fa-var-fax: \\f1ac;\n$fa-var-feather: \\f52d;\n$fa-var-feather-alt: \\f56b;\n$fa-var-fedex: \\f797;\n$fa-var-fedora: \\f798;\n$fa-var-female: \\f182;\n$fa-var-fighter-jet: \\f0fb;\n$fa-var-figma: \\f799;\n$fa-var-file: \\f15b;\n$fa-var-file-alt: \\f15c;\n$fa-var-file-archive: \\f1c6;\n$fa-var-file-audio: \\f1c7;\n$fa-var-file-code: \\f1c9;\n$fa-var-file-contract: \\f56c;\n$fa-var-file-csv: \\f6dd;\n$fa-var-file-download: \\f56d;\n$fa-var-file-excel: \\f1c3;\n$fa-var-file-export: \\f56e;\n$fa-var-file-image: \\f1c5;\n$fa-var-file-import: \\f56f;\n$fa-var-file-invoice: \\f570;\n$fa-var-file-invoice-dollar: \\f571;\n$fa-var-file-medical: \\f477;\n$fa-var-file-medical-alt: \\f478;\n$fa-var-file-pdf: \\f1c1;\n$fa-var-file-powerpoint: \\f1c4;\n$fa-var-file-prescription: \\f572;\n$fa-var-file-signature: \\f573;\n$fa-var-file-upload: \\f574;\n$fa-var-file-video: \\f1c8;\n$fa-var-file-word: \\f1c2;\n$fa-var-fill: \\f575;\n$fa-var-fill-drip: \\f576;\n$fa-var-film: \\f008;\n$fa-var-filter: \\f0b0;\n$fa-var-fingerprint: \\f577;\n$fa-var-fire: \\f06d;\n$fa-var-fire-alt: \\f7e4;\n$fa-var-fire-extinguisher: \\f134;\n$fa-var-firefox: \\f269;\n$fa-var-first-aid: \\f479;\n$fa-var-first-order: \\f2b0;\n$fa-var-first-order-alt: \\f50a;\n$fa-var-firstdraft: \\f3a1;\n$fa-var-fish: \\f578;\n$fa-var-fist-raised: \\f6de;\n$fa-var-flag: \\f024;\n$fa-var-flag-checkered: \\f11e;\n$fa-var-flag-usa: \\f74d;\n$fa-var-flask: \\f0c3;\n$fa-var-flickr: \\f16e;\n$fa-var-flipboard: \\f44d;\n$fa-var-flushed: \\f579;\n$fa-var-fly: \\f417;\n$fa-var-folder: \\f07b;\n$fa-var-folder-minus: \\f65d;\n$fa-var-folder-open: \\f07c;\n$fa-var-folder-plus: \\f65e;\n$fa-var-font: \\f031;\n$fa-var-font-awesome: \\f2b4;\n$fa-var-font-awesome-alt: \\f35c;\n$fa-var-font-awesome-flag: \\f425;\n$fa-var-font-awesome-logo-full: \\f4e6;\n$fa-var-fonticons: \\f280;\n$fa-var-fonticons-fi: \\f3a2;\n$fa-var-football-ball: \\f44e;\n$fa-var-fort-awesome: \\f286;\n$fa-var-fort-awesome-alt: \\f3a3;\n$fa-var-forumbee: \\f211;\n$fa-var-forward: \\f04e;\n$fa-var-foursquare: \\f180;\n$fa-var-free-code-camp: \\f2c5;\n$fa-var-freebsd: \\f3a4;\n$fa-var-frog: \\f52e;\n$fa-var-frown: \\f119;\n$fa-var-frown-open: \\f57a;\n$fa-var-fulcrum: \\f50b;\n$fa-var-funnel-dollar: \\f662;\n$fa-var-futbol: \\f1e3;\n$fa-var-galactic-republic: \\f50c;\n$fa-var-galactic-senate: \\f50d;\n$fa-var-gamepad: \\f11b;\n$fa-var-gas-pump: \\f52f;\n$fa-var-gavel: \\f0e3;\n$fa-var-gem: \\f3a5;\n$fa-var-genderless: \\f22d;\n$fa-var-get-pocket: \\f265;\n$fa-var-gg: \\f260;\n$fa-var-gg-circle: \\f261;\n$fa-var-ghost: \\f6e2;\n$fa-var-gift: \\f06b;\n$fa-var-gifts: \\f79c;\n$fa-var-git: \\f1d3;\n$fa-var-git-alt: \\f841;\n$fa-var-git-square: \\f1d2;\n$fa-var-github: \\f09b;\n$fa-var-github-alt: \\f113;\n$fa-var-github-square: \\f092;\n$fa-var-gitkraken: \\f3a6;\n$fa-var-gitlab: \\f296;\n$fa-var-gitter: \\f426;\n$fa-var-glass-cheers: \\f79f;\n$fa-var-glass-martini: \\f000;\n$fa-var-glass-martini-alt: \\f57b;\n$fa-var-glass-whiskey: \\f7a0;\n$fa-var-glasses: \\f530;\n$fa-var-glide: \\f2a5;\n$fa-var-glide-g: \\f2a6;\n$fa-var-globe: \\f0ac;\n$fa-var-globe-africa: \\f57c;\n$fa-var-globe-americas: \\f57d;\n$fa-var-globe-asia: \\f57e;\n$fa-var-globe-europe: \\f7a2;\n$fa-var-gofore: \\f3a7;\n$fa-var-golf-ball: \\f450;\n$fa-var-goodreads: \\f3a8;\n$fa-var-goodreads-g: \\f3a9;\n$fa-var-google: \\f1a0;\n$fa-var-google-drive: \\f3aa;\n$fa-var-google-play: \\f3ab;\n$fa-var-google-plus: \\f2b3;\n$fa-var-google-plus-g: \\f0d5;\n$fa-var-google-plus-square: \\f0d4;\n$fa-var-google-wallet: \\f1ee;\n$fa-var-gopuram: \\f664;\n$fa-var-graduation-cap: \\f19d;\n$fa-var-gratipay: \\f184;\n$fa-var-grav: \\f2d6;\n$fa-var-greater-than: \\f531;\n$fa-var-greater-than-equal: \\f532;\n$fa-var-grimace: \\f57f;\n$fa-var-grin: \\f580;\n$fa-var-grin-alt: \\f581;\n$fa-var-grin-beam: \\f582;\n$fa-var-grin-beam-sweat: \\f583;\n$fa-var-grin-hearts: \\f584;\n$fa-var-grin-squint: \\f585;\n$fa-var-grin-squint-tears: \\f586;\n$fa-var-grin-stars: \\f587;\n$fa-var-grin-tears: \\f588;\n$fa-var-grin-tongue: \\f589;\n$fa-var-grin-tongue-squint: \\f58a;\n$fa-var-grin-tongue-wink: \\f58b;\n$fa-var-grin-wink: \\f58c;\n$fa-var-grip-horizontal: \\f58d;\n$fa-var-grip-lines: \\f7a4;\n$fa-var-grip-lines-vertical: \\f7a5;\n$fa-var-grip-vertical: \\f58e;\n$fa-var-gripfire: \\f3ac;\n$fa-var-grunt: \\f3ad;\n$fa-var-guitar: \\f7a6;\n$fa-var-gulp: \\f3ae;\n$fa-var-h-square: \\f0fd;\n$fa-var-hacker-news: \\f1d4;\n$fa-var-hacker-news-square: \\f3af;\n$fa-var-hackerrank: \\f5f7;\n$fa-var-hamburger: \\f805;\n$fa-var-hammer: \\f6e3;\n$fa-var-hamsa: \\f665;\n$fa-var-hand-holding: \\f4bd;\n$fa-var-hand-holding-heart: \\f4be;\n$fa-var-hand-holding-usd: \\f4c0;\n$fa-var-hand-lizard: \\f258;\n$fa-var-hand-middle-finger: \\f806;\n$fa-var-hand-paper: \\f256;\n$fa-var-hand-peace: \\f25b;\n$fa-var-hand-point-down: \\f0a7;\n$fa-var-hand-point-left: \\f0a5;\n$fa-var-hand-point-right: \\f0a4;\n$fa-var-hand-point-up: \\f0a6;\n$fa-var-hand-pointer: \\f25a;\n$fa-var-hand-rock: \\f255;\n$fa-var-hand-scissors: \\f257;\n$fa-var-hand-spock: \\f259;\n$fa-var-hands: \\f4c2;\n$fa-var-hands-helping: \\f4c4;\n$fa-var-handshake: \\f2b5;\n$fa-var-hanukiah: \\f6e6;\n$fa-var-hard-hat: \\f807;\n$fa-var-hashtag: \\f292;\n$fa-var-hat-wizard: \\f6e8;\n$fa-var-haykal: \\f666;\n$fa-var-hdd: \\f0a0;\n$fa-var-heading: \\f1dc;\n$fa-var-headphones: \\f025;\n$fa-var-headphones-alt: \\f58f;\n$fa-var-headset: \\f590;\n$fa-var-heart: \\f004;\n$fa-var-heart-broken: \\f7a9;\n$fa-var-heartbeat: \\f21e;\n$fa-var-helicopter: \\f533;\n$fa-var-highlighter: \\f591;\n$fa-var-hiking: \\f6ec;\n$fa-var-hippo: \\f6ed;\n$fa-var-hips: \\f452;\n$fa-var-hire-a-helper: \\f3b0;\n$fa-var-history: \\f1da;\n$fa-var-hockey-puck: \\f453;\n$fa-var-holly-berry: \\f7aa;\n$fa-var-home: \\f015;\n$fa-var-hooli: \\f427;\n$fa-var-hornbill: \\f592;\n$fa-var-horse: \\f6f0;\n$fa-var-horse-head: \\f7ab;\n$fa-var-hospital: \\f0f8;\n$fa-var-hospital-alt: \\f47d;\n$fa-var-hospital-symbol: \\f47e;\n$fa-var-hot-tub: \\f593;\n$fa-var-hotdog: \\f80f;\n$fa-var-hotel: \\f594;\n$fa-var-hotjar: \\f3b1;\n$fa-var-hourglass: \\f254;\n$fa-var-hourglass-end: \\f253;\n$fa-var-hourglass-half: \\f252;\n$fa-var-hourglass-start: \\f251;\n$fa-var-house-damage: \\f6f1;\n$fa-var-houzz: \\f27c;\n$fa-var-hryvnia: \\f6f2;\n$fa-var-html5: \\f13b;\n$fa-var-hubspot: \\f3b2;\n$fa-var-i-cursor: \\f246;\n$fa-var-ice-cream: \\f810;\n$fa-var-icicles: \\f7ad;\n$fa-var-icons: \\f86d;\n$fa-var-id-badge: \\f2c1;\n$fa-var-id-card: \\f2c2;\n$fa-var-id-card-alt: \\f47f;\n$fa-var-igloo: \\f7ae;\n$fa-var-image: \\f03e;\n$fa-var-images: \\f302;\n$fa-var-imdb: \\f2d8;\n$fa-var-inbox: \\f01c;\n$fa-var-indent: \\f03c;\n$fa-var-industry: \\f275;\n$fa-var-infinity: \\f534;\n$fa-var-info: \\f129;\n$fa-var-info-circle: \\f05a;\n$fa-var-instagram: \\f16d;\n$fa-var-intercom: \\f7af;\n$fa-var-internet-explorer: \\f26b;\n$fa-var-invision: \\f7b0;\n$fa-var-ioxhost: \\f208;\n$fa-var-italic: \\f033;\n$fa-var-itch-io: \\f83a;\n$fa-var-itunes: \\f3b4;\n$fa-var-itunes-note: \\f3b5;\n$fa-var-java: \\f4e4;\n$fa-var-jedi: \\f669;\n$fa-var-jedi-order: \\f50e;\n$fa-var-jenkins: \\f3b6;\n$fa-var-jira: \\f7b1;\n$fa-var-joget: \\f3b7;\n$fa-var-joint: \\f595;\n$fa-var-joomla: \\f1aa;\n$fa-var-journal-whills: \\f66a;\n$fa-var-js: \\f3b8;\n$fa-var-js-square: \\f3b9;\n$fa-var-jsfiddle: \\f1cc;\n$fa-var-kaaba: \\f66b;\n$fa-var-kaggle: \\f5fa;\n$fa-var-key: \\f084;\n$fa-var-keybase: \\f4f5;\n$fa-var-keyboard: \\f11c;\n$fa-var-keycdn: \\f3ba;\n$fa-var-khanda: \\f66d;\n$fa-var-kickstarter: \\f3bb;\n$fa-var-kickstarter-k: \\f3bc;\n$fa-var-kiss: \\f596;\n$fa-var-kiss-beam: \\f597;\n$fa-var-kiss-wink-heart: \\f598;\n$fa-var-kiwi-bird: \\f535;\n$fa-var-korvue: \\f42f;\n$fa-var-landmark: \\f66f;\n$fa-var-language: \\f1ab;\n$fa-var-laptop: \\f109;\n$fa-var-laptop-code: \\f5fc;\n$fa-var-laptop-medical: \\f812;\n$fa-var-laravel: \\f3bd;\n$fa-var-lastfm: \\f202;\n$fa-var-lastfm-square: \\f203;\n$fa-var-laugh: \\f599;\n$fa-var-laugh-beam: \\f59a;\n$fa-var-laugh-squint: \\f59b;\n$fa-var-laugh-wink: \\f59c;\n$fa-var-layer-group: \\f5fd;\n$fa-var-leaf: \\f06c;\n$fa-var-leanpub: \\f212;\n$fa-var-lemon: \\f094;\n$fa-var-less: \\f41d;\n$fa-var-less-than: \\f536;\n$fa-var-less-than-equal: \\f537;\n$fa-var-level-down-alt: \\f3be;\n$fa-var-level-up-alt: \\f3bf;\n$fa-var-life-ring: \\f1cd;\n$fa-var-lightbulb: \\f0eb;\n$fa-var-line: \\f3c0;\n$fa-var-link: \\f0c1;\n$fa-var-linkedin: \\f08c;\n$fa-var-linkedin-in: \\f0e1;\n$fa-var-linode: \\f2b8;\n$fa-var-linux: \\f17c;\n$fa-var-lira-sign: \\f195;\n$fa-var-list: \\f03a;\n$fa-var-list-alt: \\f022;\n$fa-var-list-ol: \\f0cb;\n$fa-var-list-ul: \\f0ca;\n$fa-var-location-arrow: \\f124;\n$fa-var-lock: \\f023;\n$fa-var-lock-open: \\f3c1;\n$fa-var-long-arrow-alt-down: \\f309;\n$fa-var-long-arrow-alt-left: \\f30a;\n$fa-var-long-arrow-alt-right: \\f30b;\n$fa-var-long-arrow-alt-up: \\f30c;\n$fa-var-low-vision: \\f2a8;\n$fa-var-luggage-cart: \\f59d;\n$fa-var-lyft: \\f3c3;\n$fa-var-magento: \\f3c4;\n$fa-var-magic: \\f0d0;\n$fa-var-magnet: \\f076;\n$fa-var-mail-bulk: \\f674;\n$fa-var-mailchimp: \\f59e;\n$fa-var-male: \\f183;\n$fa-var-mandalorian: \\f50f;\n$fa-var-map: \\f279;\n$fa-var-map-marked: \\f59f;\n$fa-var-map-marked-alt: \\f5a0;\n$fa-var-map-marker: \\f041;\n$fa-var-map-marker-alt: \\f3c5;\n$fa-var-map-pin: \\f276;\n$fa-var-map-signs: \\f277;\n$fa-var-markdown: \\f60f;\n$fa-var-marker: \\f5a1;\n$fa-var-mars: \\f222;\n$fa-var-mars-double: \\f227;\n$fa-var-mars-stroke: \\f229;\n$fa-var-mars-stroke-h: \\f22b;\n$fa-var-mars-stroke-v: \\f22a;\n$fa-var-mask: \\f6fa;\n$fa-var-mastodon: \\f4f6;\n$fa-var-maxcdn: \\f136;\n$fa-var-medal: \\f5a2;\n$fa-var-medapps: \\f3c6;\n$fa-var-medium: \\f23a;\n$fa-var-medium-m: \\f3c7;\n$fa-var-medkit: \\f0fa;\n$fa-var-medrt: \\f3c8;\n$fa-var-meetup: \\f2e0;\n$fa-var-megaport: \\f5a3;\n$fa-var-meh: \\f11a;\n$fa-var-meh-blank: \\f5a4;\n$fa-var-meh-rolling-eyes: \\f5a5;\n$fa-var-memory: \\f538;\n$fa-var-mendeley: \\f7b3;\n$fa-var-menorah: \\f676;\n$fa-var-mercury: \\f223;\n$fa-var-meteor: \\f753;\n$fa-var-microchip: \\f2db;\n$fa-var-microphone: \\f130;\n$fa-var-microphone-alt: \\f3c9;\n$fa-var-microphone-alt-slash: \\f539;\n$fa-var-microphone-slash: \\f131;\n$fa-var-microscope: \\f610;\n$fa-var-microsoft: \\f3ca;\n$fa-var-minus: \\f068;\n$fa-var-minus-circle: \\f056;\n$fa-var-minus-square: \\f146;\n$fa-var-mitten: \\f7b5;\n$fa-var-mix: \\f3cb;\n$fa-var-mixcloud: \\f289;\n$fa-var-mizuni: \\f3cc;\n$fa-var-mobile: \\f10b;\n$fa-var-mobile-alt: \\f3cd;\n$fa-var-modx: \\f285;\n$fa-var-monero: \\f3d0;\n$fa-var-money-bill: \\f0d6;\n$fa-var-money-bill-alt: \\f3d1;\n$fa-var-money-bill-wave: \\f53a;\n$fa-var-money-bill-wave-alt: \\f53b;\n$fa-var-money-check: \\f53c;\n$fa-var-money-check-alt: \\f53d;\n$fa-var-monument: \\f5a6;\n$fa-var-moon: \\f186;\n$fa-var-mortar-pestle: \\f5a7;\n$fa-var-mosque: \\f678;\n$fa-var-motorcycle: \\f21c;\n$fa-var-mountain: \\f6fc;\n$fa-var-mouse-pointer: \\f245;\n$fa-var-mug-hot: \\f7b6;\n$fa-var-music: \\f001;\n$fa-var-napster: \\f3d2;\n$fa-var-neos: \\f612;\n$fa-var-network-wired: \\f6ff;\n$fa-var-neuter: \\f22c;\n$fa-var-newspaper: \\f1ea;\n$fa-var-nimblr: \\f5a8;\n$fa-var-node: \\f419;\n$fa-var-node-js: \\f3d3;\n$fa-var-not-equal: \\f53e;\n$fa-var-notes-medical: \\f481;\n$fa-var-npm: \\f3d4;\n$fa-var-ns8: \\f3d5;\n$fa-var-nutritionix: \\f3d6;\n$fa-var-object-group: \\f247;\n$fa-var-object-ungroup: \\f248;\n$fa-var-odnoklassniki: \\f263;\n$fa-var-odnoklassniki-square: \\f264;\n$fa-var-oil-can: \\f613;\n$fa-var-old-republic: \\f510;\n$fa-var-om: \\f679;\n$fa-var-opencart: \\f23d;\n$fa-var-openid: \\f19b;\n$fa-var-opera: \\f26a;\n$fa-var-optin-monster: \\f23c;\n$fa-var-osi: \\f41a;\n$fa-var-otter: \\f700;\n$fa-var-outdent: \\f03b;\n$fa-var-page4: \\f3d7;\n$fa-var-pagelines: \\f18c;\n$fa-var-pager: \\f815;\n$fa-var-paint-brush: \\f1fc;\n$fa-var-paint-roller: \\f5aa;\n$fa-var-palette: \\f53f;\n$fa-var-palfed: \\f3d8;\n$fa-var-pallet: \\f482;\n$fa-var-paper-plane: \\f1d8;\n$fa-var-paperclip: \\f0c6;\n$fa-var-parachute-box: \\f4cd;\n$fa-var-paragraph: \\f1dd;\n$fa-var-parking: \\f540;\n$fa-var-passport: \\f5ab;\n$fa-var-pastafarianism: \\f67b;\n$fa-var-paste: \\f0ea;\n$fa-var-patreon: \\f3d9;\n$fa-var-pause: \\f04c;\n$fa-var-pause-circle: \\f28b;\n$fa-var-paw: \\f1b0;\n$fa-var-paypal: \\f1ed;\n$fa-var-peace: \\f67c;\n$fa-var-pen: \\f304;\n$fa-var-pen-alt: \\f305;\n$fa-var-pen-fancy: \\f5ac;\n$fa-var-pen-nib: \\f5ad;\n$fa-var-pen-square: \\f14b;\n$fa-var-pencil-alt: \\f303;\n$fa-var-pencil-ruler: \\f5ae;\n$fa-var-penny-arcade: \\f704;\n$fa-var-people-carry: \\f4ce;\n$fa-var-pepper-hot: \\f816;\n$fa-var-percent: \\f295;\n$fa-var-percentage: \\f541;\n$fa-var-periscope: \\f3da;\n$fa-var-person-booth: \\f756;\n$fa-var-phabricator: \\f3db;\n$fa-var-phoenix-framework: \\f3dc;\n$fa-var-phoenix-squadron: \\f511;\n$fa-var-phone: \\f095;\n$fa-var-phone-alt: \\f879;\n$fa-var-phone-slash: \\f3dd;\n$fa-var-phone-square: \\f098;\n$fa-var-phone-square-alt: \\f87b;\n$fa-var-phone-volume: \\f2a0;\n$fa-var-photo-video: \\f87c;\n$fa-var-php: \\f457;\n$fa-var-pied-piper: \\f2ae;\n$fa-var-pied-piper-alt: \\f1a8;\n$fa-var-pied-piper-hat: \\f4e5;\n$fa-var-pied-piper-pp: \\f1a7;\n$fa-var-piggy-bank: \\f4d3;\n$fa-var-pills: \\f484;\n$fa-var-pinterest: \\f0d2;\n$fa-var-pinterest-p: \\f231;\n$fa-var-pinterest-square: \\f0d3;\n$fa-var-pizza-slice: \\f818;\n$fa-var-place-of-worship: \\f67f;\n$fa-var-plane: \\f072;\n$fa-var-plane-arrival: \\f5af;\n$fa-var-plane-departure: \\f5b0;\n$fa-var-play: \\f04b;\n$fa-var-play-circle: \\f144;\n$fa-var-playstation: \\f3df;\n$fa-var-plug: \\f1e6;\n$fa-var-plus: \\f067;\n$fa-var-plus-circle: \\f055;\n$fa-var-plus-square: \\f0fe;\n$fa-var-podcast: \\f2ce;\n$fa-var-poll: \\f681;\n$fa-var-poll-h: \\f682;\n$fa-var-poo: \\f2fe;\n$fa-var-poo-storm: \\f75a;\n$fa-var-poop: \\f619;\n$fa-var-portrait: \\f3e0;\n$fa-var-pound-sign: \\f154;\n$fa-var-power-off: \\f011;\n$fa-var-pray: \\f683;\n$fa-var-praying-hands: \\f684;\n$fa-var-prescription: \\f5b1;\n$fa-var-prescription-bottle: \\f485;\n$fa-var-prescription-bottle-alt: \\f486;\n$fa-var-print: \\f02f;\n$fa-var-procedures: \\f487;\n$fa-var-product-hunt: \\f288;\n$fa-var-project-diagram: \\f542;\n$fa-var-pushed: \\f3e1;\n$fa-var-puzzle-piece: \\f12e;\n$fa-var-python: \\f3e2;\n$fa-var-qq: \\f1d6;\n$fa-var-qrcode: \\f029;\n$fa-var-question: \\f128;\n$fa-var-question-circle: \\f059;\n$fa-var-quidditch: \\f458;\n$fa-var-quinscape: \\f459;\n$fa-var-quora: \\f2c4;\n$fa-var-quote-left: \\f10d;\n$fa-var-quote-right: \\f10e;\n$fa-var-quran: \\f687;\n$fa-var-r-project: \\f4f7;\n$fa-var-radiation: \\f7b9;\n$fa-var-radiation-alt: \\f7ba;\n$fa-var-rainbow: \\f75b;\n$fa-var-random: \\f074;\n$fa-var-raspberry-pi: \\f7bb;\n$fa-var-ravelry: \\f2d9;\n$fa-var-react: \\f41b;\n$fa-var-reacteurope: \\f75d;\n$fa-var-readme: \\f4d5;\n$fa-var-rebel: \\f1d0;\n$fa-var-receipt: \\f543;\n$fa-var-recycle: \\f1b8;\n$fa-var-red-river: \\f3e3;\n$fa-var-reddit: \\f1a1;\n$fa-var-reddit-alien: \\f281;\n$fa-var-reddit-square: \\f1a2;\n$fa-var-redhat: \\f7bc;\n$fa-var-redo: \\f01e;\n$fa-var-redo-alt: \\f2f9;\n$fa-var-registered: \\f25d;\n$fa-var-remove-format: \\f87d;\n$fa-var-renren: \\f18b;\n$fa-var-reply: \\f3e5;\n$fa-var-reply-all: \\f122;\n$fa-var-replyd: \\f3e6;\n$fa-var-republican: \\f75e;\n$fa-var-researchgate: \\f4f8;\n$fa-var-resolving: \\f3e7;\n$fa-var-restroom: \\f7bd;\n$fa-var-retweet: \\f079;\n$fa-var-rev: \\f5b2;\n$fa-var-ribbon: \\f4d6;\n$fa-var-ring: \\f70b;\n$fa-var-road: \\f018;\n$fa-var-robot: \\f544;\n$fa-var-rocket: \\f135;\n$fa-var-rocketchat: \\f3e8;\n$fa-var-rockrms: \\f3e9;\n$fa-var-route: \\f4d7;\n$fa-var-rss: \\f09e;\n$fa-var-rss-square: \\f143;\n$fa-var-ruble-sign: \\f158;\n$fa-var-ruler: \\f545;\n$fa-var-ruler-combined: \\f546;\n$fa-var-ruler-horizontal: \\f547;\n$fa-var-ruler-vertical: \\f548;\n$fa-var-running: \\f70c;\n$fa-var-rupee-sign: \\f156;\n$fa-var-sad-cry: \\f5b3;\n$fa-var-sad-tear: \\f5b4;\n$fa-var-safari: \\f267;\n$fa-var-salesforce: \\f83b;\n$fa-var-sass: \\f41e;\n$fa-var-satellite: \\f7bf;\n$fa-var-satellite-dish: \\f7c0;\n$fa-var-save: \\f0c7;\n$fa-var-schlix: \\f3ea;\n$fa-var-school: \\f549;\n$fa-var-screwdriver: \\f54a;\n$fa-var-scribd: \\f28a;\n$fa-var-scroll: \\f70e;\n$fa-var-sd-card: \\f7c2;\n$fa-var-search: \\f002;\n$fa-var-search-dollar: \\f688;\n$fa-var-search-location: \\f689;\n$fa-var-search-minus: \\f010;\n$fa-var-search-plus: \\f00e;\n$fa-var-searchengin: \\f3eb;\n$fa-var-seedling: \\f4d8;\n$fa-var-sellcast: \\f2da;\n$fa-var-sellsy: \\f213;\n$fa-var-server: \\f233;\n$fa-var-servicestack: \\f3ec;\n$fa-var-shapes: \\f61f;\n$fa-var-share: \\f064;\n$fa-var-share-alt: \\f1e0;\n$fa-var-share-alt-square: \\f1e1;\n$fa-var-share-square: \\f14d;\n$fa-var-shekel-sign: \\f20b;\n$fa-var-shield-alt: \\f3ed;\n$fa-var-ship: \\f21a;\n$fa-var-shipping-fast: \\f48b;\n$fa-var-shirtsinbulk: \\f214;\n$fa-var-shoe-prints: \\f54b;\n$fa-var-shopping-bag: \\f290;\n$fa-var-shopping-basket: \\f291;\n$fa-var-shopping-cart: \\f07a;\n$fa-var-shopware: \\f5b5;\n$fa-var-shower: \\f2cc;\n$fa-var-shuttle-van: \\f5b6;\n$fa-var-sign: \\f4d9;\n$fa-var-sign-in-alt: \\f2f6;\n$fa-var-sign-language: \\f2a7;\n$fa-var-sign-out-alt: \\f2f5;\n$fa-var-signal: \\f012;\n$fa-var-signature: \\f5b7;\n$fa-var-sim-card: \\f7c4;\n$fa-var-simplybuilt: \\f215;\n$fa-var-sistrix: \\f3ee;\n$fa-var-sitemap: \\f0e8;\n$fa-var-sith: \\f512;\n$fa-var-skating: \\f7c5;\n$fa-var-sketch: \\f7c6;\n$fa-var-skiing: \\f7c9;\n$fa-var-skiing-nordic: \\f7ca;\n$fa-var-skull: \\f54c;\n$fa-var-skull-crossbones: \\f714;\n$fa-var-skyatlas: \\f216;\n$fa-var-skype: \\f17e;\n$fa-var-slack: \\f198;\n$fa-var-slack-hash: \\f3ef;\n$fa-var-slash: \\f715;\n$fa-var-sleigh: \\f7cc;\n$fa-var-sliders-h: \\f1de;\n$fa-var-slideshare: \\f1e7;\n$fa-var-smile: \\f118;\n$fa-var-smile-beam: \\f5b8;\n$fa-var-smile-wink: \\f4da;\n$fa-var-smog: \\f75f;\n$fa-var-smoking: \\f48d;\n$fa-var-smoking-ban: \\f54d;\n$fa-var-sms: \\f7cd;\n$fa-var-snapchat: \\f2ab;\n$fa-var-snapchat-ghost: \\f2ac;\n$fa-var-snapchat-square: \\f2ad;\n$fa-var-snowboarding: \\f7ce;\n$fa-var-snowflake: \\f2dc;\n$fa-var-snowman: \\f7d0;\n$fa-var-snowplow: \\f7d2;\n$fa-var-socks: \\f696;\n$fa-var-solar-panel: \\f5ba;\n$fa-var-sort: \\f0dc;\n$fa-var-sort-alpha-down: \\f15d;\n$fa-var-sort-alpha-down-alt: \\f881;\n$fa-var-sort-alpha-up: \\f15e;\n$fa-var-sort-alpha-up-alt: \\f882;\n$fa-var-sort-amount-down: \\f160;\n$fa-var-sort-amount-down-alt: \\f884;\n$fa-var-sort-amount-up: \\f161;\n$fa-var-sort-amount-up-alt: \\f885;\n$fa-var-sort-down: \\f0dd;\n$fa-var-sort-numeric-down: \\f162;\n$fa-var-sort-numeric-down-alt: \\f886;\n$fa-var-sort-numeric-up: \\f163;\n$fa-var-sort-numeric-up-alt: \\f887;\n$fa-var-sort-up: \\f0de;\n$fa-var-soundcloud: \\f1be;\n$fa-var-sourcetree: \\f7d3;\n$fa-var-spa: \\f5bb;\n$fa-var-space-shuttle: \\f197;\n$fa-var-speakap: \\f3f3;\n$fa-var-speaker-deck: \\f83c;\n$fa-var-spell-check: \\f891;\n$fa-var-spider: \\f717;\n$fa-var-spinner: \\f110;\n$fa-var-splotch: \\f5bc;\n$fa-var-spotify: \\f1bc;\n$fa-var-spray-can: \\f5bd;\n$fa-var-square: \\f0c8;\n$fa-var-square-full: \\f45c;\n$fa-var-square-root-alt: \\f698;\n$fa-var-squarespace: \\f5be;\n$fa-var-stack-exchange: \\f18d;\n$fa-var-stack-overflow: \\f16c;\n$fa-var-stackpath: \\f842;\n$fa-var-stamp: \\f5bf;\n$fa-var-star: \\f005;\n$fa-var-star-and-crescent: \\f699;\n$fa-var-star-half: \\f089;\n$fa-var-star-half-alt: \\f5c0;\n$fa-var-star-of-david: \\f69a;\n$fa-var-star-of-life: \\f621;\n$fa-var-staylinked: \\f3f5;\n$fa-var-steam: \\f1b6;\n$fa-var-steam-square: \\f1b7;\n$fa-var-steam-symbol: \\f3f6;\n$fa-var-step-backward: \\f048;\n$fa-var-step-forward: \\f051;\n$fa-var-stethoscope: \\f0f1;\n$fa-var-sticker-mule: \\f3f7;\n$fa-var-sticky-note: \\f249;\n$fa-var-stop: \\f04d;\n$fa-var-stop-circle: \\f28d;\n$fa-var-stopwatch: \\f2f2;\n$fa-var-store: \\f54e;\n$fa-var-store-alt: \\f54f;\n$fa-var-strava: \\f428;\n$fa-var-stream: \\f550;\n$fa-var-street-view: \\f21d;\n$fa-var-strikethrough: \\f0cc;\n$fa-var-stripe: \\f429;\n$fa-var-stripe-s: \\f42a;\n$fa-var-stroopwafel: \\f551;\n$fa-var-studiovinari: \\f3f8;\n$fa-var-stumbleupon: \\f1a4;\n$fa-var-stumbleupon-circle: \\f1a3;\n$fa-var-subscript: \\f12c;\n$fa-var-subway: \\f239;\n$fa-var-suitcase: \\f0f2;\n$fa-var-suitcase-rolling: \\f5c1;\n$fa-var-sun: \\f185;\n$fa-var-superpowers: \\f2dd;\n$fa-var-superscript: \\f12b;\n$fa-var-supple: \\f3f9;\n$fa-var-surprise: \\f5c2;\n$fa-var-suse: \\f7d6;\n$fa-var-swatchbook: \\f5c3;\n$fa-var-swimmer: \\f5c4;\n$fa-var-swimming-pool: \\f5c5;\n$fa-var-symfony: \\f83d;\n$fa-var-synagogue: \\f69b;\n$fa-var-sync: \\f021;\n$fa-var-sync-alt: \\f2f1;\n$fa-var-syringe: \\f48e;\n$fa-var-table: \\f0ce;\n$fa-var-table-tennis: \\f45d;\n$fa-var-tablet: \\f10a;\n$fa-var-tablet-alt: \\f3fa;\n$fa-var-tablets: \\f490;\n$fa-var-tachometer-alt: \\f3fd;\n$fa-var-tag: \\f02b;\n$fa-var-tags: \\f02c;\n$fa-var-tape: \\f4db;\n$fa-var-tasks: \\f0ae;\n$fa-var-taxi: \\f1ba;\n$fa-var-teamspeak: \\f4f9;\n$fa-var-teeth: \\f62e;\n$fa-var-teeth-open: \\f62f;\n$fa-var-telegram: \\f2c6;\n$fa-var-telegram-plane: \\f3fe;\n$fa-var-temperature-high: \\f769;\n$fa-var-temperature-low: \\f76b;\n$fa-var-tencent-weibo: \\f1d5;\n$fa-var-tenge: \\f7d7;\n$fa-var-terminal: \\f120;\n$fa-var-text-height: \\f034;\n$fa-var-text-width: \\f035;\n$fa-var-th: \\f00a;\n$fa-var-th-large: \\f009;\n$fa-var-th-list: \\f00b;\n$fa-var-the-red-yeti: \\f69d;\n$fa-var-theater-masks: \\f630;\n$fa-var-themeco: \\f5c6;\n$fa-var-themeisle: \\f2b2;\n$fa-var-thermometer: \\f491;\n$fa-var-thermometer-empty: \\f2cb;\n$fa-var-thermometer-full: \\f2c7;\n$fa-var-thermometer-half: \\f2c9;\n$fa-var-thermometer-quarter: \\f2ca;\n$fa-var-thermometer-three-quarters: \\f2c8;\n$fa-var-think-peaks: \\f731;\n$fa-var-thumbs-down: \\f165;\n$fa-var-thumbs-up: \\f164;\n$fa-var-thumbtack: \\f08d;\n$fa-var-ticket-alt: \\f3ff;\n$fa-var-times: \\f00d;\n$fa-var-times-circle: \\f057;\n$fa-var-tint: \\f043;\n$fa-var-tint-slash: \\f5c7;\n$fa-var-tired: \\f5c8;\n$fa-var-toggle-off: \\f204;\n$fa-var-toggle-on: \\f205;\n$fa-var-toilet: \\f7d8;\n$fa-var-toilet-paper: \\f71e;\n$fa-var-toolbox: \\f552;\n$fa-var-tools: \\f7d9;\n$fa-var-tooth: \\f5c9;\n$fa-var-torah: \\f6a0;\n$fa-var-torii-gate: \\f6a1;\n$fa-var-tractor: \\f722;\n$fa-var-trade-federation: \\f513;\n$fa-var-trademark: \\f25c;\n$fa-var-traffic-light: \\f637;\n$fa-var-train: \\f238;\n$fa-var-tram: \\f7da;\n$fa-var-transgender: \\f224;\n$fa-var-transgender-alt: \\f225;\n$fa-var-trash: \\f1f8;\n$fa-var-trash-alt: \\f2ed;\n$fa-var-trash-restore: \\f829;\n$fa-var-trash-restore-alt: \\f82a;\n$fa-var-tree: \\f1bb;\n$fa-var-trello: \\f181;\n$fa-var-tripadvisor: \\f262;\n$fa-var-trophy: \\f091;\n$fa-var-truck: \\f0d1;\n$fa-var-truck-loading: \\f4de;\n$fa-var-truck-monster: \\f63b;\n$fa-var-truck-moving: \\f4df;\n$fa-var-truck-pickup: \\f63c;\n$fa-var-tshirt: \\f553;\n$fa-var-tty: \\f1e4;\n$fa-var-tumblr: \\f173;\n$fa-var-tumblr-square: \\f174;\n$fa-var-tv: \\f26c;\n$fa-var-twitch: \\f1e8;\n$fa-var-twitter: \\f099;\n$fa-var-twitter-square: \\f081;\n$fa-var-typo3: \\f42b;\n$fa-var-uber: \\f402;\n$fa-var-ubuntu: \\f7df;\n$fa-var-uikit: \\f403;\n$fa-var-umbrella: \\f0e9;\n$fa-var-umbrella-beach: \\f5ca;\n$fa-var-underline: \\f0cd;\n$fa-var-undo: \\f0e2;\n$fa-var-undo-alt: \\f2ea;\n$fa-var-uniregistry: \\f404;\n$fa-var-universal-access: \\f29a;\n$fa-var-university: \\f19c;\n$fa-var-unlink: \\f127;\n$fa-var-unlock: \\f09c;\n$fa-var-unlock-alt: \\f13e;\n$fa-var-untappd: \\f405;\n$fa-var-upload: \\f093;\n$fa-var-ups: \\f7e0;\n$fa-var-usb: \\f287;\n$fa-var-user: \\f007;\n$fa-var-user-alt: \\f406;\n$fa-var-user-alt-slash: \\f4fa;\n$fa-var-user-astronaut: \\f4fb;\n$fa-var-user-check: \\f4fc;\n$fa-var-user-circle: \\f2bd;\n$fa-var-user-clock: \\f4fd;\n$fa-var-user-cog: \\f4fe;\n$fa-var-user-edit: \\f4ff;\n$fa-var-user-friends: \\f500;\n$fa-var-user-graduate: \\f501;\n$fa-var-user-injured: \\f728;\n$fa-var-user-lock: \\f502;\n$fa-var-user-md: \\f0f0;\n$fa-var-user-minus: \\f503;\n$fa-var-user-ninja: \\f504;\n$fa-var-user-nurse: \\f82f;\n$fa-var-user-plus: \\f234;\n$fa-var-user-secret: \\f21b;\n$fa-var-user-shield: \\f505;\n$fa-var-user-slash: \\f506;\n$fa-var-user-tag: \\f507;\n$fa-var-user-tie: \\f508;\n$fa-var-user-times: \\f235;\n$fa-var-users: \\f0c0;\n$fa-var-users-cog: \\f509;\n$fa-var-usps: \\f7e1;\n$fa-var-ussunnah: \\f407;\n$fa-var-utensil-spoon: \\f2e5;\n$fa-var-utensils: \\f2e7;\n$fa-var-vaadin: \\f408;\n$fa-var-vector-square: \\f5cb;\n$fa-var-venus: \\f221;\n$fa-var-venus-double: \\f226;\n$fa-var-venus-mars: \\f228;\n$fa-var-viacoin: \\f237;\n$fa-var-viadeo: \\f2a9;\n$fa-var-viadeo-square: \\f2aa;\n$fa-var-vial: \\f492;\n$fa-var-vials: \\f493;\n$fa-var-viber: \\f409;\n$fa-var-video: \\f03d;\n$fa-var-video-slash: \\f4e2;\n$fa-var-vihara: \\f6a7;\n$fa-var-vimeo: \\f40a;\n$fa-var-vimeo-square: \\f194;\n$fa-var-vimeo-v: \\f27d;\n$fa-var-vine: \\f1ca;\n$fa-var-vk: \\f189;\n$fa-var-vnv: \\f40b;\n$fa-var-voicemail: \\f897;\n$fa-var-volleyball-ball: \\f45f;\n$fa-var-volume-down: \\f027;\n$fa-var-volume-mute: \\f6a9;\n$fa-var-volume-off: \\f026;\n$fa-var-volume-up: \\f028;\n$fa-var-vote-yea: \\f772;\n$fa-var-vr-cardboard: \\f729;\n$fa-var-vuejs: \\f41f;\n$fa-var-walking: \\f554;\n$fa-var-wallet: \\f555;\n$fa-var-warehouse: \\f494;\n$fa-var-water: \\f773;\n$fa-var-wave-square: \\f83e;\n$fa-var-waze: \\f83f;\n$fa-var-weebly: \\f5cc;\n$fa-var-weibo: \\f18a;\n$fa-var-weight: \\f496;\n$fa-var-weight-hanging: \\f5cd;\n$fa-var-weixin: \\f1d7;\n$fa-var-whatsapp: \\f232;\n$fa-var-whatsapp-square: \\f40c;\n$fa-var-wheelchair: \\f193;\n$fa-var-whmcs: \\f40d;\n$fa-var-wifi: \\f1eb;\n$fa-var-wikipedia-w: \\f266;\n$fa-var-wind: \\f72e;\n$fa-var-window-close: \\f410;\n$fa-var-window-maximize: \\f2d0;\n$fa-var-window-minimize: \\f2d1;\n$fa-var-window-restore: \\f2d2;\n$fa-var-windows: \\f17a;\n$fa-var-wine-bottle: \\f72f;\n$fa-var-wine-glass: \\f4e3;\n$fa-var-wine-glass-alt: \\f5ce;\n$fa-var-wix: \\f5cf;\n$fa-var-wizards-of-the-coast: \\f730;\n$fa-var-wolf-pack-battalion: \\f514;\n$fa-var-won-sign: \\f159;\n$fa-var-wordpress: \\f19a;\n$fa-var-wordpress-simple: \\f411;\n$fa-var-wpbeginner: \\f297;\n$fa-var-wpexplorer: \\f2de;\n$fa-var-wpforms: \\f298;\n$fa-var-wpressr: \\f3e4;\n$fa-var-wrench: \\f0ad;\n$fa-var-x-ray: \\f497;\n$fa-var-xbox: \\f412;\n$fa-var-xing: \\f168;\n$fa-var-xing-square: \\f169;\n$fa-var-y-combinator: \\f23b;\n$fa-var-yahoo: \\f19e;\n$fa-var-yammer: \\f840;\n$fa-var-yandex: \\f413;\n$fa-var-yandex-international: \\f414;\n$fa-var-yarn: \\f7e3;\n$fa-var-yelp: \\f1e9;\n$fa-var-yen-sign: \\f157;\n$fa-var-yin-yang: \\f6ad;\n$fa-var-yoast: \\f2b1;\n$fa-var-youtube: \\f167;\n$fa-var-youtube-square: \\f431;\n$fa-var-zhihu: \\f63f;\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/brands.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: $fa-font-display;\n  src: url('#{$fa-font-path}/fa-brands-400.eot');\n  src: url('#{$fa-font-path}/fa-brands-400.eot?#iefix') format('embedded-opentype'),\n  url('#{$fa-font-path}/fa-brands-400.woff2') format('woff2'),\n  url('#{$fa-font-path}/fa-brands-400.woff') format('woff'),\n  url('#{$fa-font-path}/fa-brands-400.ttf') format('truetype'),\n  url('#{$fa-font-path}/fa-brands-400.svg#fontawesome') format('svg');\n}\n\n.fab {\n  font-family: 'Font Awesome 5 Brands';\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/fontawesome.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n@import 'mixins';\n@import 'core';\n@import 'larger';\n@import 'fixed-width';\n@import 'list';\n@import 'bordered-pulled';\n@import 'animated';\n@import 'rotated-flipped';\n@import 'stacked';\n@import 'icons';\n@import 'screen-reader';\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/regular.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: $fa-font-display;\n  src: url('#{$fa-font-path}/fa-regular-400.eot');\n  src: url('#{$fa-font-path}/fa-regular-400.eot?#iefix') format('embedded-opentype'),\n  url('#{$fa-font-path}/fa-regular-400.woff2') format('woff2'),\n  url('#{$fa-font-path}/fa-regular-400.woff') format('woff'),\n  url('#{$fa-font-path}/fa-regular-400.ttf') format('truetype'),\n  url('#{$fa-font-path}/fa-regular-400.svg#fontawesome') format('svg');\n}\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/solid.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: $fa-font-display;\n  src: url('#{$fa-font-path}/fa-solid-900.eot');\n  src: url('#{$fa-font-path}/fa-solid-900.eot?#iefix') format('embedded-opentype'),\n  url('#{$fa-font-path}/fa-solid-900.woff2') format('woff2'),\n  url('#{$fa-font-path}/fa-solid-900.woff') format('woff'),\n  url('#{$fa-font-path}/fa-solid-900.ttf') format('truetype'),\n  url('#{$fa-font-path}/fa-solid-900.svg#fontawesome') format('svg');\n}\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/v4-shims.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n@import 'shims';\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/jquery/jquery.js",
    "content": "/*!\n * jQuery JavaScript Library v3.4.1\n * https://jquery.com/\n *\n * Includes Sizzle.js\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://jquery.org/license\n *\n * Date: 2019-05-01T21:04Z\n */\n( function( global, factory ) {\n\n\t\"use strict\";\n\n\tif ( typeof module === \"object\" && typeof module.exports === \"object\" ) {\n\n\t\t// For CommonJS and CommonJS-like environments where a proper `window`\n\t\t// is present, execute the factory and get jQuery.\n\t\t// For environments that do not have a `window` with a `document`\n\t\t// (such as Node.js), expose a factory as module.exports.\n\t\t// This accentuates the need for the creation of a real `window`.\n\t\t// e.g. var jQuery = require(\"jquery\")(window);\n\t\t// See ticket #14549 for more info.\n\t\tmodule.exports = global.document ?\n\t\t\tfactory( global, true ) :\n\t\t\tfunction( w ) {\n\t\t\t\tif ( !w.document ) {\n\t\t\t\t\tthrow new Error( \"jQuery requires a window with a document\" );\n\t\t\t\t}\n\t\t\t\treturn factory( w );\n\t\t\t};\n\t} else {\n\t\tfactory( global );\n\t}\n\n// Pass this if window is not defined yet\n} )( typeof window !== \"undefined\" ? window : this, function( window, noGlobal ) {\n\n// Edge <= 12 - 13+, Firefox <=18 - 45+, IE 10 - 11, Safari 5.1 - 9+, iOS 6 - 9.1\n// throw exceptions when non-strict code (e.g., ASP.NET 4.5) accesses strict mode\n// arguments.callee.caller (trac-13335). But as of jQuery 3.0 (2016), strict mode should be common\n// enough that all such attempts are guarded in a try block.\n\"use strict\";\n\nvar arr = [];\n\nvar document = window.document;\n\nvar getProto = Object.getPrototypeOf;\n\nvar slice = arr.slice;\n\nvar concat = arr.concat;\n\nvar push = arr.push;\n\nvar indexOf = arr.indexOf;\n\nvar class2type = {};\n\nvar toString = class2type.toString;\n\nvar hasOwn = class2type.hasOwnProperty;\n\nvar fnToString = hasOwn.toString;\n\nvar ObjectFunctionString = fnToString.call( Object );\n\nvar support = {};\n\nvar isFunction = function isFunction( obj ) {\n\n      // Support: Chrome <=57, Firefox <=52\n      // In some browsers, typeof returns \"function\" for HTML <object> elements\n      // (i.e., `typeof document.createElement( \"object\" ) === \"function\"`).\n      // We don't want to classify *any* DOM node as a function.\n      return typeof obj === \"function\" && typeof obj.nodeType !== \"number\";\n  };\n\n\nvar isWindow = function isWindow( obj ) {\n\t\treturn obj != null && obj === obj.window;\n\t};\n\n\n\n\n\tvar preservedScriptAttributes = {\n\t\ttype: true,\n\t\tsrc: true,\n\t\tnonce: true,\n\t\tnoModule: true\n\t};\n\n\tfunction DOMEval( code, node, doc ) {\n\t\tdoc = doc || document;\n\n\t\tvar i, val,\n\t\t\tscript = doc.createElement( \"script\" );\n\n\t\tscript.text = code;\n\t\tif ( node ) {\n\t\t\tfor ( i in preservedScriptAttributes ) {\n\n\t\t\t\t// Support: Firefox 64+, Edge 18+\n\t\t\t\t// Some browsers don't support the \"nonce\" property on scripts.\n\t\t\t\t// On the other hand, just using `getAttribute` is not enough as\n\t\t\t\t// the `nonce` attribute is reset to an empty string whenever it\n\t\t\t\t// becomes browsing-context connected.\n\t\t\t\t// See https://github.com/whatwg/html/issues/2369\n\t\t\t\t// See https://html.spec.whatwg.org/#nonce-attributes\n\t\t\t\t// The `node.getAttribute` check was added for the sake of\n\t\t\t\t// `jQuery.globalEval` so that it can fake a nonce-containing node\n\t\t\t\t// via an object.\n\t\t\t\tval = node[ i ] || node.getAttribute && node.getAttribute( i );\n\t\t\t\tif ( val ) {\n\t\t\t\t\tscript.setAttribute( i, val );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tdoc.head.appendChild( script ).parentNode.removeChild( script );\n\t}\n\n\nfunction toType( obj ) {\n\tif ( obj == null ) {\n\t\treturn obj + \"\";\n\t}\n\n\t// Support: Android <=2.3 only (functionish RegExp)\n\treturn typeof obj === \"object\" || typeof obj === \"function\" ?\n\t\tclass2type[ toString.call( obj ) ] || \"object\" :\n\t\ttypeof obj;\n}\n/* global Symbol */\n// Defining this global in .eslintrc.json would create a danger of using the global\n// unguarded in another place, it seems safer to define global only for this module\n\n\n\nvar\n\tversion = \"3.4.1\",\n\n\t// Define a local copy of jQuery\n\tjQuery = function( selector, context ) {\n\n\t\t// The jQuery object is actually just the init constructor 'enhanced'\n\t\t// Need init if jQuery is called (just allow error to be thrown if not included)\n\t\treturn new jQuery.fn.init( selector, context );\n\t},\n\n\t// Support: Android <=4.0 only\n\t// Make sure we trim BOM and NBSP\n\trtrim = /^[\\s\\uFEFF\\xA0]+|[\\s\\uFEFF\\xA0]+$/g;\n\njQuery.fn = jQuery.prototype = {\n\n\t// The current version of jQuery being used\n\tjquery: version,\n\n\tconstructor: jQuery,\n\n\t// The default length of a jQuery object is 0\n\tlength: 0,\n\n\ttoArray: function() {\n\t\treturn slice.call( this );\n\t},\n\n\t// Get the Nth element in the matched element set OR\n\t// Get the whole matched element set as a clean array\n\tget: function( num ) {\n\n\t\t// Return all the elements in a clean array\n\t\tif ( num == null ) {\n\t\t\treturn slice.call( this );\n\t\t}\n\n\t\t// Return just the one element from the set\n\t\treturn num < 0 ? this[ num + this.length ] : this[ num ];\n\t},\n\n\t// Take an array of elements and push it onto the stack\n\t// (returning the new matched element set)\n\tpushStack: function( elems ) {\n\n\t\t// Build a new jQuery matched element set\n\t\tvar ret = jQuery.merge( this.constructor(), elems );\n\n\t\t// Add the old object onto the stack (as a reference)\n\t\tret.prevObject = this;\n\n\t\t// Return the newly-formed element set\n\t\treturn ret;\n\t},\n\n\t// Execute a callback for every element in the matched set.\n\teach: function( callback ) {\n\t\treturn jQuery.each( this, callback );\n\t},\n\n\tmap: function( callback ) {\n\t\treturn this.pushStack( jQuery.map( this, function( elem, i ) {\n\t\t\treturn callback.call( elem, i, elem );\n\t\t} ) );\n\t},\n\n\tslice: function() {\n\t\treturn this.pushStack( slice.apply( this, arguments ) );\n\t},\n\n\tfirst: function() {\n\t\treturn this.eq( 0 );\n\t},\n\n\tlast: function() {\n\t\treturn this.eq( -1 );\n\t},\n\n\teq: function( i ) {\n\t\tvar len = this.length,\n\t\t\tj = +i + ( i < 0 ? len : 0 );\n\t\treturn this.pushStack( j >= 0 && j < len ? [ this[ j ] ] : [] );\n\t},\n\n\tend: function() {\n\t\treturn this.prevObject || this.constructor();\n\t},\n\n\t// For internal use only.\n\t// Behaves like an Array's method, not like a jQuery method.\n\tpush: push,\n\tsort: arr.sort,\n\tsplice: arr.splice\n};\n\njQuery.extend = jQuery.fn.extend = function() {\n\tvar options, name, src, copy, copyIsArray, clone,\n\t\ttarget = arguments[ 0 ] || {},\n\t\ti = 1,\n\t\tlength = arguments.length,\n\t\tdeep = false;\n\n\t// Handle a deep copy situation\n\tif ( typeof target === \"boolean\" ) {\n\t\tdeep = target;\n\n\t\t// Skip the boolean and the target\n\t\ttarget = arguments[ i ] || {};\n\t\ti++;\n\t}\n\n\t// Handle case when target is a string or something (possible in deep copy)\n\tif ( typeof target !== \"object\" && !isFunction( target ) ) {\n\t\ttarget = {};\n\t}\n\n\t// Extend jQuery itself if only one argument is passed\n\tif ( i === length ) {\n\t\ttarget = this;\n\t\ti--;\n\t}\n\n\tfor ( ; i < length; i++ ) {\n\n\t\t// Only deal with non-null/undefined values\n\t\tif ( ( options = arguments[ i ] ) != null ) {\n\n\t\t\t// Extend the base object\n\t\t\tfor ( name in options ) {\n\t\t\t\tcopy = options[ name ];\n\n\t\t\t\t// Prevent Object.prototype pollution\n\t\t\t\t// Prevent never-ending loop\n\t\t\t\tif ( name === \"__proto__\" || target === copy ) {\n\t\t\t\t\tcontinue;\n\t\t\t\t}\n\n\t\t\t\t// Recurse if we're merging plain objects or arrays\n\t\t\t\tif ( deep && copy && ( jQuery.isPlainObject( copy ) ||\n\t\t\t\t\t( copyIsArray = Array.isArray( copy ) ) ) ) {\n\t\t\t\t\tsrc = target[ name ];\n\n\t\t\t\t\t// Ensure proper type for the source value\n\t\t\t\t\tif ( copyIsArray && !Array.isArray( src ) ) {\n\t\t\t\t\t\tclone = [];\n\t\t\t\t\t} else if ( !copyIsArray && !jQuery.isPlainObject( src ) ) {\n\t\t\t\t\t\tclone = {};\n\t\t\t\t\t} else {\n\t\t\t\t\t\tclone = src;\n\t\t\t\t\t}\n\t\t\t\t\tcopyIsArray = false;\n\n\t\t\t\t\t// Never move original objects, clone them\n\t\t\t\t\ttarget[ name ] = jQuery.extend( deep, clone, copy );\n\n\t\t\t\t// Don't bring in undefined values\n\t\t\t\t} else if ( copy !== undefined ) {\n\t\t\t\t\ttarget[ name ] = copy;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Return the modified object\n\treturn target;\n};\n\njQuery.extend( {\n\n\t// Unique for each copy of jQuery on the page\n\texpando: \"jQuery\" + ( version + Math.random() ).replace( /\\D/g, \"\" ),\n\n\t// Assume jQuery is ready without the ready module\n\tisReady: true,\n\n\terror: function( msg ) {\n\t\tthrow new Error( msg );\n\t},\n\n\tnoop: function() {},\n\n\tisPlainObject: function( obj ) {\n\t\tvar proto, Ctor;\n\n\t\t// Detect obvious negatives\n\t\t// Use toString instead of jQuery.type to catch host objects\n\t\tif ( !obj || toString.call( obj ) !== \"[object Object]\" ) {\n\t\t\treturn false;\n\t\t}\n\n\t\tproto = getProto( obj );\n\n\t\t// Objects with no prototype (e.g., `Object.create( null )`) are plain\n\t\tif ( !proto ) {\n\t\t\treturn true;\n\t\t}\n\n\t\t// Objects with prototype are plain iff they were constructed by a global Object function\n\t\tCtor = hasOwn.call( proto, \"constructor\" ) && proto.constructor;\n\t\treturn typeof Ctor === \"function\" && fnToString.call( Ctor ) === ObjectFunctionString;\n\t},\n\n\tisEmptyObject: function( obj ) {\n\t\tvar name;\n\n\t\tfor ( name in obj ) {\n\t\t\treturn false;\n\t\t}\n\t\treturn true;\n\t},\n\n\t// Evaluates a script in a global context\n\tglobalEval: function( code, options ) {\n\t\tDOMEval( code, { nonce: options && options.nonce } );\n\t},\n\n\teach: function( obj, callback ) {\n\t\tvar length, i = 0;\n\n\t\tif ( isArrayLike( obj ) ) {\n\t\t\tlength = obj.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t} else {\n\t\t\tfor ( i in obj ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn obj;\n\t},\n\n\t// Support: Android <=4.0 only\n\ttrim: function( text ) {\n\t\treturn text == null ?\n\t\t\t\"\" :\n\t\t\t( text + \"\" ).replace( rtrim, \"\" );\n\t},\n\n\t// results is for internal usage only\n\tmakeArray: function( arr, results ) {\n\t\tvar ret = results || [];\n\n\t\tif ( arr != null ) {\n\t\t\tif ( isArrayLike( Object( arr ) ) ) {\n\t\t\t\tjQuery.merge( ret,\n\t\t\t\t\ttypeof arr === \"string\" ?\n\t\t\t\t\t[ arr ] : arr\n\t\t\t\t);\n\t\t\t} else {\n\t\t\t\tpush.call( ret, arr );\n\t\t\t}\n\t\t}\n\n\t\treturn ret;\n\t},\n\n\tinArray: function( elem, arr, i ) {\n\t\treturn arr == null ? -1 : indexOf.call( arr, elem, i );\n\t},\n\n\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t// push.apply(_, arraylike) throws on ancient WebKit\n\tmerge: function( first, second ) {\n\t\tvar len = +second.length,\n\t\t\tj = 0,\n\t\t\ti = first.length;\n\n\t\tfor ( ; j < len; j++ ) {\n\t\t\tfirst[ i++ ] = second[ j ];\n\t\t}\n\n\t\tfirst.length = i;\n\n\t\treturn first;\n\t},\n\n\tgrep: function( elems, callback, invert ) {\n\t\tvar callbackInverse,\n\t\t\tmatches = [],\n\t\t\ti = 0,\n\t\t\tlength = elems.length,\n\t\t\tcallbackExpect = !invert;\n\n\t\t// Go through the array, only saving the items\n\t\t// that pass the validator function\n\t\tfor ( ; i < length; i++ ) {\n\t\t\tcallbackInverse = !callback( elems[ i ], i );\n\t\t\tif ( callbackInverse !== callbackExpect ) {\n\t\t\t\tmatches.push( elems[ i ] );\n\t\t\t}\n\t\t}\n\n\t\treturn matches;\n\t},\n\n\t// arg is for internal usage only\n\tmap: function( elems, callback, arg ) {\n\t\tvar length, value,\n\t\t\ti = 0,\n\t\t\tret = [];\n\n\t\t// Go through the array, translating each of the items to their new values\n\t\tif ( isArrayLike( elems ) ) {\n\t\t\tlength = elems.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Go through every key on the object,\n\t\t} else {\n\t\t\tfor ( i in elems ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Flatten any nested arrays\n\t\treturn concat.apply( [], ret );\n\t},\n\n\t// A global GUID counter for objects\n\tguid: 1,\n\n\t// jQuery.support is not used in Core but other projects attach their\n\t// properties to it so it needs to exist.\n\tsupport: support\n} );\n\nif ( typeof Symbol === \"function\" ) {\n\tjQuery.fn[ Symbol.iterator ] = arr[ Symbol.iterator ];\n}\n\n// Populate the class2type map\njQuery.each( \"Boolean Number String Function Array Date RegExp Object Error Symbol\".split( \" \" ),\nfunction( i, name ) {\n\tclass2type[ \"[object \" + name + \"]\" ] = name.toLowerCase();\n} );\n\nfunction isArrayLike( obj ) {\n\n\t// Support: real iOS 8.2 only (not reproducible in simulator)\n\t// `in` check used to prevent JIT error (gh-2145)\n\t// hasOwn isn't used here due to false negatives\n\t// regarding Nodelist length in IE\n\tvar length = !!obj && \"length\" in obj && obj.length,\n\t\ttype = toType( obj );\n\n\tif ( isFunction( obj ) || isWindow( obj ) ) {\n\t\treturn false;\n\t}\n\n\treturn type === \"array\" || length === 0 ||\n\t\ttypeof length === \"number\" && length > 0 && ( length - 1 ) in obj;\n}\nvar Sizzle =\n/*!\n * Sizzle CSS Selector Engine v2.3.4\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://js.foundation/\n *\n * Date: 2019-04-08\n */\n(function( window ) {\n\nvar i,\n\tsupport,\n\tExpr,\n\tgetText,\n\tisXML,\n\ttokenize,\n\tcompile,\n\tselect,\n\toutermostContext,\n\tsortInput,\n\thasDuplicate,\n\n\t// Local document vars\n\tsetDocument,\n\tdocument,\n\tdocElem,\n\tdocumentIsHTML,\n\trbuggyQSA,\n\trbuggyMatches,\n\tmatches,\n\tcontains,\n\n\t// Instance-specific data\n\texpando = \"sizzle\" + 1 * new Date(),\n\tpreferredDoc = window.document,\n\tdirruns = 0,\n\tdone = 0,\n\tclassCache = createCache(),\n\ttokenCache = createCache(),\n\tcompilerCache = createCache(),\n\tnonnativeSelectorCache = createCache(),\n\tsortOrder = function( a, b ) {\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t}\n\t\treturn 0;\n\t},\n\n\t// Instance methods\n\thasOwn = ({}).hasOwnProperty,\n\tarr = [],\n\tpop = arr.pop,\n\tpush_native = arr.push,\n\tpush = arr.push,\n\tslice = arr.slice,\n\t// Use a stripped-down indexOf as it's faster than native\n\t// https://jsperf.com/thor-indexof-vs-for/5\n\tindexOf = function( list, elem ) {\n\t\tvar i = 0,\n\t\t\tlen = list.length;\n\t\tfor ( ; i < len; i++ ) {\n\t\t\tif ( list[i] === elem ) {\n\t\t\t\treturn i;\n\t\t\t}\n\t\t}\n\t\treturn -1;\n\t},\n\n\tbooleans = \"checked|selected|async|autofocus|autoplay|controls|defer|disabled|hidden|ismap|loop|multiple|open|readonly|required|scoped\",\n\n\t// Regular expressions\n\n\t// http://www.w3.org/TR/css3-selectors/#whitespace\n\twhitespace = \"[\\\\x20\\\\t\\\\r\\\\n\\\\f]\",\n\n\t// http://www.w3.org/TR/CSS21/syndata.html#value-def-identifier\n\tidentifier = \"(?:\\\\\\\\.|[\\\\w-]|[^\\0-\\\\xa0])+\",\n\n\t// Attribute selectors: http://www.w3.org/TR/selectors/#attribute-selectors\n\tattributes = \"\\\\[\" + whitespace + \"*(\" + identifier + \")(?:\" + whitespace +\n\t\t// Operator (capture 2)\n\t\t\"*([*^$|!~]?=)\" + whitespace +\n\t\t// \"Attribute values must be CSS identifiers [capture 5] or strings [capture 3 or capture 4]\"\n\t\t\"*(?:'((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\"|(\" + identifier + \"))|)\" + whitespace +\n\t\t\"*\\\\]\",\n\n\tpseudos = \":(\" + identifier + \")(?:\\\\((\" +\n\t\t// To reduce the number of selectors needing tokenize in the preFilter, prefer arguments:\n\t\t// 1. quoted (capture 3; capture 4 or capture 5)\n\t\t\"('((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\")|\" +\n\t\t// 2. simple (capture 6)\n\t\t\"((?:\\\\\\\\.|[^\\\\\\\\()[\\\\]]|\" + attributes + \")*)|\" +\n\t\t// 3. anything else (capture 2)\n\t\t\".*\" +\n\t\t\")\\\\)|)\",\n\n\t// Leading and non-escaped trailing whitespace, capturing some non-whitespace characters preceding the latter\n\trwhitespace = new RegExp( whitespace + \"+\", \"g\" ),\n\trtrim = new RegExp( \"^\" + whitespace + \"+|((?:^|[^\\\\\\\\])(?:\\\\\\\\.)*)\" + whitespace + \"+$\", \"g\" ),\n\n\trcomma = new RegExp( \"^\" + whitespace + \"*,\" + whitespace + \"*\" ),\n\trcombinators = new RegExp( \"^\" + whitespace + \"*([>+~]|\" + whitespace + \")\" + whitespace + \"*\" ),\n\trdescend = new RegExp( whitespace + \"|>\" ),\n\n\trpseudo = new RegExp( pseudos ),\n\tridentifier = new RegExp( \"^\" + identifier + \"$\" ),\n\n\tmatchExpr = {\n\t\t\"ID\": new RegExp( \"^#(\" + identifier + \")\" ),\n\t\t\"CLASS\": new RegExp( \"^\\\\.(\" + identifier + \")\" ),\n\t\t\"TAG\": new RegExp( \"^(\" + identifier + \"|[*])\" ),\n\t\t\"ATTR\": new RegExp( \"^\" + attributes ),\n\t\t\"PSEUDO\": new RegExp( \"^\" + pseudos ),\n\t\t\"CHILD\": new RegExp( \"^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\\\(\" + whitespace +\n\t\t\t\"*(even|odd|(([+-]|)(\\\\d*)n|)\" + whitespace + \"*(?:([+-]|)\" + whitespace +\n\t\t\t\"*(\\\\d+)|))\" + whitespace + \"*\\\\)|)\", \"i\" ),\n\t\t\"bool\": new RegExp( \"^(?:\" + booleans + \")$\", \"i\" ),\n\t\t// For use in libraries implementing .is()\n\t\t// We use this for POS matching in `select`\n\t\t\"needsContext\": new RegExp( \"^\" + whitespace + \"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\\\(\" +\n\t\t\twhitespace + \"*((?:-\\\\d)?\\\\d*)\" + whitespace + \"*\\\\)|)(?=[^-]|$)\", \"i\" )\n\t},\n\n\trhtml = /HTML$/i,\n\trinputs = /^(?:input|select|textarea|button)$/i,\n\trheader = /^h\\d$/i,\n\n\trnative = /^[^{]+\\{\\s*\\[native \\w/,\n\n\t// Easily-parseable/retrievable ID or TAG or CLASS selectors\n\trquickExpr = /^(?:#([\\w-]+)|(\\w+)|\\.([\\w-]+))$/,\n\n\trsibling = /[+~]/,\n\n\t// CSS escapes\n\t// http://www.w3.org/TR/CSS21/syndata.html#escaped-characters\n\trunescape = new RegExp( \"\\\\\\\\([\\\\da-f]{1,6}\" + whitespace + \"?|(\" + whitespace + \")|.)\", \"ig\" ),\n\tfunescape = function( _, escaped, escapedWhitespace ) {\n\t\tvar high = \"0x\" + escaped - 0x10000;\n\t\t// NaN means non-codepoint\n\t\t// Support: Firefox<24\n\t\t// Workaround erroneous numeric interpretation of +\"0x\"\n\t\treturn high !== high || escapedWhitespace ?\n\t\t\tescaped :\n\t\t\thigh < 0 ?\n\t\t\t\t// BMP codepoint\n\t\t\t\tString.fromCharCode( high + 0x10000 ) :\n\t\t\t\t// Supplemental Plane codepoint (surrogate pair)\n\t\t\t\tString.fromCharCode( high >> 10 | 0xD800, high & 0x3FF | 0xDC00 );\n\t},\n\n\t// CSS string/identifier serialization\n\t// https://drafts.csswg.org/cssom/#common-serializing-idioms\n\trcssescape = /([\\0-\\x1f\\x7f]|^-?\\d)|^-$|[^\\0-\\x1f\\x7f-\\uFFFF\\w-]/g,\n\tfcssescape = function( ch, asCodePoint ) {\n\t\tif ( asCodePoint ) {\n\n\t\t\t// U+0000 NULL becomes U+FFFD REPLACEMENT CHARACTER\n\t\t\tif ( ch === \"\\0\" ) {\n\t\t\t\treturn \"\\uFFFD\";\n\t\t\t}\n\n\t\t\t// Control characters and (dependent upon position) numbers get escaped as code points\n\t\t\treturn ch.slice( 0, -1 ) + \"\\\\\" + ch.charCodeAt( ch.length - 1 ).toString( 16 ) + \" \";\n\t\t}\n\n\t\t// Other potentially-special ASCII characters get backslash-escaped\n\t\treturn \"\\\\\" + ch;\n\t},\n\n\t// Used for iframes\n\t// See setDocument()\n\t// Removing the function wrapper causes a \"Permission Denied\"\n\t// error in IE\n\tunloadHandler = function() {\n\t\tsetDocument();\n\t},\n\n\tinDisabledFieldset = addCombinator(\n\t\tfunction( elem ) {\n\t\t\treturn elem.disabled === true && elem.nodeName.toLowerCase() === \"fieldset\";\n\t\t},\n\t\t{ dir: \"parentNode\", next: \"legend\" }\n\t);\n\n// Optimize for push.apply( _, NodeList )\ntry {\n\tpush.apply(\n\t\t(arr = slice.call( preferredDoc.childNodes )),\n\t\tpreferredDoc.childNodes\n\t);\n\t// Support: Android<4.0\n\t// Detect silently failing push.apply\n\tarr[ preferredDoc.childNodes.length ].nodeType;\n} catch ( e ) {\n\tpush = { apply: arr.length ?\n\n\t\t// Leverage slice if possible\n\t\tfunction( target, els ) {\n\t\t\tpush_native.apply( target, slice.call(els) );\n\t\t} :\n\n\t\t// Support: IE<9\n\t\t// Otherwise append directly\n\t\tfunction( target, els ) {\n\t\t\tvar j = target.length,\n\t\t\t\ti = 0;\n\t\t\t// Can't trust NodeList.length\n\t\t\twhile ( (target[j++] = els[i++]) ) {}\n\t\t\ttarget.length = j - 1;\n\t\t}\n\t};\n}\n\nfunction Sizzle( selector, context, results, seed ) {\n\tvar m, i, elem, nid, match, groups, newSelector,\n\t\tnewContext = context && context.ownerDocument,\n\n\t\t// nodeType defaults to 9, since context defaults to document\n\t\tnodeType = context ? context.nodeType : 9;\n\n\tresults = results || [];\n\n\t// Return early from calls with invalid selector or context\n\tif ( typeof selector !== \"string\" || !selector ||\n\t\tnodeType !== 1 && nodeType !== 9 && nodeType !== 11 ) {\n\n\t\treturn results;\n\t}\n\n\t// Try to shortcut find operations (as opposed to filters) in HTML documents\n\tif ( !seed ) {\n\n\t\tif ( ( context ? context.ownerDocument || context : preferredDoc ) !== document ) {\n\t\t\tsetDocument( context );\n\t\t}\n\t\tcontext = context || document;\n\n\t\tif ( documentIsHTML ) {\n\n\t\t\t// If the selector is sufficiently simple, try using a \"get*By*\" DOM method\n\t\t\t// (excepting DocumentFragment context, where the methods don't exist)\n\t\t\tif ( nodeType !== 11 && (match = rquickExpr.exec( selector )) ) {\n\n\t\t\t\t// ID selector\n\t\t\t\tif ( (m = match[1]) ) {\n\n\t\t\t\t\t// Document context\n\t\t\t\t\tif ( nodeType === 9 ) {\n\t\t\t\t\t\tif ( (elem = context.getElementById( m )) ) {\n\n\t\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\t\tif ( elem.id === m ) {\n\t\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t// Element context\n\t\t\t\t\t} else {\n\n\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\tif ( newContext && (elem = newContext.getElementById( m )) &&\n\t\t\t\t\t\t\tcontains( context, elem ) &&\n\t\t\t\t\t\t\telem.id === m ) {\n\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t// Type selector\n\t\t\t\t} else if ( match[2] ) {\n\t\t\t\t\tpush.apply( results, context.getElementsByTagName( selector ) );\n\t\t\t\t\treturn results;\n\n\t\t\t\t// Class selector\n\t\t\t\t} else if ( (m = match[3]) && support.getElementsByClassName &&\n\t\t\t\t\tcontext.getElementsByClassName ) {\n\n\t\t\t\t\tpush.apply( results, context.getElementsByClassName( m ) );\n\t\t\t\t\treturn results;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Take advantage of querySelectorAll\n\t\t\tif ( support.qsa &&\n\t\t\t\t!nonnativeSelectorCache[ selector + \" \" ] &&\n\t\t\t\t(!rbuggyQSA || !rbuggyQSA.test( selector )) &&\n\n\t\t\t\t// Support: IE 8 only\n\t\t\t\t// Exclude object elements\n\t\t\t\t(nodeType !== 1 || context.nodeName.toLowerCase() !== \"object\") ) {\n\n\t\t\t\tnewSelector = selector;\n\t\t\t\tnewContext = context;\n\n\t\t\t\t// qSA considers elements outside a scoping root when evaluating child or\n\t\t\t\t// descendant combinators, which is not what we want.\n\t\t\t\t// In such cases, we work around the behavior by prefixing every selector in the\n\t\t\t\t// list with an ID selector referencing the scope context.\n\t\t\t\t// Thanks to Andrew Dupont for this technique.\n\t\t\t\tif ( nodeType === 1 && rdescend.test( selector ) ) {\n\n\t\t\t\t\t// Capture the context ID, setting it first if necessary\n\t\t\t\t\tif ( (nid = context.getAttribute( \"id\" )) ) {\n\t\t\t\t\t\tnid = nid.replace( rcssescape, fcssescape );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tcontext.setAttribute( \"id\", (nid = expando) );\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prefix every selector in the list\n\t\t\t\t\tgroups = tokenize( selector );\n\t\t\t\t\ti = groups.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tgroups[i] = \"#\" + nid + \" \" + toSelector( groups[i] );\n\t\t\t\t\t}\n\t\t\t\t\tnewSelector = groups.join( \",\" );\n\n\t\t\t\t\t// Expand context for sibling selectors\n\t\t\t\t\tnewContext = rsibling.test( selector ) && testContext( context.parentNode ) ||\n\t\t\t\t\t\tcontext;\n\t\t\t\t}\n\n\t\t\t\ttry {\n\t\t\t\t\tpush.apply( results,\n\t\t\t\t\t\tnewContext.querySelectorAll( newSelector )\n\t\t\t\t\t);\n\t\t\t\t\treturn results;\n\t\t\t\t} catch ( qsaError ) {\n\t\t\t\t\tnonnativeSelectorCache( selector, true );\n\t\t\t\t} finally {\n\t\t\t\t\tif ( nid === expando ) {\n\t\t\t\t\t\tcontext.removeAttribute( \"id\" );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// All others\n\treturn select( selector.replace( rtrim, \"$1\" ), context, results, seed );\n}\n\n/**\n * Create key-value caches of limited size\n * @returns {function(string, object)} Returns the Object data after storing it on itself with\n *\tproperty name the (space-suffixed) string and (if the cache is larger than Expr.cacheLength)\n *\tdeleting the oldest entry\n */\nfunction createCache() {\n\tvar keys = [];\n\n\tfunction cache( key, value ) {\n\t\t// Use (key + \" \") to avoid collision with native prototype properties (see Issue #157)\n\t\tif ( keys.push( key + \" \" ) > Expr.cacheLength ) {\n\t\t\t// Only keep the most recent entries\n\t\t\tdelete cache[ keys.shift() ];\n\t\t}\n\t\treturn (cache[ key + \" \" ] = value);\n\t}\n\treturn cache;\n}\n\n/**\n * Mark a function for special use by Sizzle\n * @param {Function} fn The function to mark\n */\nfunction markFunction( fn ) {\n\tfn[ expando ] = true;\n\treturn fn;\n}\n\n/**\n * Support testing using an element\n * @param {Function} fn Passed the created element and returns a boolean result\n */\nfunction assert( fn ) {\n\tvar el = document.createElement(\"fieldset\");\n\n\ttry {\n\t\treturn !!fn( el );\n\t} catch (e) {\n\t\treturn false;\n\t} finally {\n\t\t// Remove from its parent by default\n\t\tif ( el.parentNode ) {\n\t\t\tel.parentNode.removeChild( el );\n\t\t}\n\t\t// release memory in IE\n\t\tel = null;\n\t}\n}\n\n/**\n * Adds the same handler for all of the specified attrs\n * @param {String} attrs Pipe-separated list of attributes\n * @param {Function} handler The method that will be applied\n */\nfunction addHandle( attrs, handler ) {\n\tvar arr = attrs.split(\"|\"),\n\t\ti = arr.length;\n\n\twhile ( i-- ) {\n\t\tExpr.attrHandle[ arr[i] ] = handler;\n\t}\n}\n\n/**\n * Checks document order of two siblings\n * @param {Element} a\n * @param {Element} b\n * @returns {Number} Returns less than 0 if a precedes b, greater than 0 if a follows b\n */\nfunction siblingCheck( a, b ) {\n\tvar cur = b && a,\n\t\tdiff = cur && a.nodeType === 1 && b.nodeType === 1 &&\n\t\t\ta.sourceIndex - b.sourceIndex;\n\n\t// Use IE sourceIndex if available on both nodes\n\tif ( diff ) {\n\t\treturn diff;\n\t}\n\n\t// Check if b follows a\n\tif ( cur ) {\n\t\twhile ( (cur = cur.nextSibling) ) {\n\t\t\tif ( cur === b ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t}\n\n\treturn a ? 1 : -1;\n}\n\n/**\n * Returns a function to use in pseudos for input types\n * @param {String} type\n */\nfunction createInputPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn name === \"input\" && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for buttons\n * @param {String} type\n */\nfunction createButtonPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn (name === \"input\" || name === \"button\") && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for :enabled/:disabled\n * @param {Boolean} disabled true for :disabled; false for :enabled\n */\nfunction createDisabledPseudo( disabled ) {\n\n\t// Known :disabled false positives: fieldset[disabled] > legend:nth-of-type(n+2) :can-disable\n\treturn function( elem ) {\n\n\t\t// Only certain elements can match :enabled or :disabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-enabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-disabled\n\t\tif ( \"form\" in elem ) {\n\n\t\t\t// Check for inherited disabledness on relevant non-disabled elements:\n\t\t\t// * listed form-associated elements in a disabled fieldset\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#category-listed\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-fe-disabled\n\t\t\t// * option elements in a disabled optgroup\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-option-disabled\n\t\t\t// All such elements have a \"form\" property.\n\t\t\tif ( elem.parentNode && elem.disabled === false ) {\n\n\t\t\t\t// Option elements defer to a parent optgroup if present\n\t\t\t\tif ( \"label\" in elem ) {\n\t\t\t\t\tif ( \"label\" in elem.parentNode ) {\n\t\t\t\t\t\treturn elem.parentNode.disabled === disabled;\n\t\t\t\t\t} else {\n\t\t\t\t\t\treturn elem.disabled === disabled;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Support: IE 6 - 11\n\t\t\t\t// Use the isDisabled shortcut property to check for disabled fieldset ancestors\n\t\t\t\treturn elem.isDisabled === disabled ||\n\n\t\t\t\t\t// Where there is no isDisabled, check manually\n\t\t\t\t\t/* jshint -W018 */\n\t\t\t\t\telem.isDisabled !== !disabled &&\n\t\t\t\t\t\tinDisabledFieldset( elem ) === disabled;\n\t\t\t}\n\n\t\t\treturn elem.disabled === disabled;\n\n\t\t// Try to winnow out elements that can't be disabled before trusting the disabled property.\n\t\t// Some victims get caught in our net (label, legend, menu, track), but it shouldn't\n\t\t// even exist on them, let alone have a boolean value.\n\t\t} else if ( \"label\" in elem ) {\n\t\t\treturn elem.disabled === disabled;\n\t\t}\n\n\t\t// Remaining elements are neither :enabled nor :disabled\n\t\treturn false;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for positionals\n * @param {Function} fn\n */\nfunction createPositionalPseudo( fn ) {\n\treturn markFunction(function( argument ) {\n\t\targument = +argument;\n\t\treturn markFunction(function( seed, matches ) {\n\t\t\tvar j,\n\t\t\t\tmatchIndexes = fn( [], seed.length, argument ),\n\t\t\t\ti = matchIndexes.length;\n\n\t\t\t// Match elements found at the specified indexes\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( seed[ (j = matchIndexes[i]) ] ) {\n\t\t\t\t\tseed[j] = !(matches[j] = seed[j]);\n\t\t\t\t}\n\t\t\t}\n\t\t});\n\t});\n}\n\n/**\n * Checks a node for validity as a Sizzle context\n * @param {Element|Object=} context\n * @returns {Element|Object|Boolean} The input node if acceptable, otherwise a falsy value\n */\nfunction testContext( context ) {\n\treturn context && typeof context.getElementsByTagName !== \"undefined\" && context;\n}\n\n// Expose support vars for convenience\nsupport = Sizzle.support = {};\n\n/**\n * Detects XML nodes\n * @param {Element|Object} elem An element or a document\n * @returns {Boolean} True iff elem is a non-HTML XML node\n */\nisXML = Sizzle.isXML = function( elem ) {\n\tvar namespace = elem.namespaceURI,\n\t\tdocElem = (elem.ownerDocument || elem).documentElement;\n\n\t// Support: IE <=8\n\t// Assume HTML when documentElement doesn't yet exist, such as inside loading iframes\n\t// https://bugs.jquery.com/ticket/4833\n\treturn !rhtml.test( namespace || docElem && docElem.nodeName || \"HTML\" );\n};\n\n/**\n * Sets document-related variables once based on the current document\n * @param {Element|Object} [doc] An element or document object to use to set the document\n * @returns {Object} Returns the current document\n */\nsetDocument = Sizzle.setDocument = function( node ) {\n\tvar hasCompare, subWindow,\n\t\tdoc = node ? node.ownerDocument || node : preferredDoc;\n\n\t// Return early if doc is invalid or already selected\n\tif ( doc === document || doc.nodeType !== 9 || !doc.documentElement ) {\n\t\treturn document;\n\t}\n\n\t// Update global variables\n\tdocument = doc;\n\tdocElem = document.documentElement;\n\tdocumentIsHTML = !isXML( document );\n\n\t// Support: IE 9-11, Edge\n\t// Accessing iframe documents after unload throws \"permission denied\" errors (jQuery #13936)\n\tif ( preferredDoc !== document &&\n\t\t(subWindow = document.defaultView) && subWindow.top !== subWindow ) {\n\n\t\t// Support: IE 11, Edge\n\t\tif ( subWindow.addEventListener ) {\n\t\t\tsubWindow.addEventListener( \"unload\", unloadHandler, false );\n\n\t\t// Support: IE 9 - 10 only\n\t\t} else if ( subWindow.attachEvent ) {\n\t\t\tsubWindow.attachEvent( \"onunload\", unloadHandler );\n\t\t}\n\t}\n\n\t/* Attributes\n\t---------------------------------------------------------------------- */\n\n\t// Support: IE<8\n\t// Verify that getAttribute really returns attributes and not properties\n\t// (excepting IE8 booleans)\n\tsupport.attributes = assert(function( el ) {\n\t\tel.className = \"i\";\n\t\treturn !el.getAttribute(\"className\");\n\t});\n\n\t/* getElement(s)By*\n\t---------------------------------------------------------------------- */\n\n\t// Check if getElementsByTagName(\"*\") returns only elements\n\tsupport.getElementsByTagName = assert(function( el ) {\n\t\tel.appendChild( document.createComment(\"\") );\n\t\treturn !el.getElementsByTagName(\"*\").length;\n\t});\n\n\t// Support: IE<9\n\tsupport.getElementsByClassName = rnative.test( document.getElementsByClassName );\n\n\t// Support: IE<10\n\t// Check if getElementById returns elements by name\n\t// The broken getElementById methods don't pick up programmatically-set names,\n\t// so use a roundabout getElementsByName test\n\tsupport.getById = assert(function( el ) {\n\t\tdocElem.appendChild( el ).id = expando;\n\t\treturn !document.getElementsByName || !document.getElementsByName( expando ).length;\n\t});\n\n\t// ID filter and find\n\tif ( support.getById ) {\n\t\tExpr.filter[\"ID\"] = function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn elem.getAttribute(\"id\") === attrId;\n\t\t\t};\n\t\t};\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar elem = context.getElementById( id );\n\t\t\t\treturn elem ? [ elem ] : [];\n\t\t\t}\n\t\t};\n\t} else {\n\t\tExpr.filter[\"ID\"] =  function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\tvar node = typeof elem.getAttributeNode !== \"undefined\" &&\n\t\t\t\t\telem.getAttributeNode(\"id\");\n\t\t\t\treturn node && node.value === attrId;\n\t\t\t};\n\t\t};\n\n\t\t// Support: IE 6 - 7 only\n\t\t// getElementById is not reliable as a find shortcut\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar node, i, elems,\n\t\t\t\t\telem = context.getElementById( id );\n\n\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t// Verify the id attribute\n\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t}\n\n\t\t\t\t\t// Fall back on getElementsByName\n\t\t\t\t\telems = context.getElementsByName( id );\n\t\t\t\t\ti = 0;\n\t\t\t\t\twhile ( (elem = elems[i++]) ) {\n\t\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn [];\n\t\t\t}\n\t\t};\n\t}\n\n\t// Tag\n\tExpr.find[\"TAG\"] = support.getElementsByTagName ?\n\t\tfunction( tag, context ) {\n\t\t\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\t\t\treturn context.getElementsByTagName( tag );\n\n\t\t\t// DocumentFragment nodes don't have gEBTN\n\t\t\t} else if ( support.qsa ) {\n\t\t\t\treturn context.querySelectorAll( tag );\n\t\t\t}\n\t\t} :\n\n\t\tfunction( tag, context ) {\n\t\t\tvar elem,\n\t\t\t\ttmp = [],\n\t\t\t\ti = 0,\n\t\t\t\t// By happy coincidence, a (broken) gEBTN appears on DocumentFragment nodes too\n\t\t\t\tresults = context.getElementsByTagName( tag );\n\n\t\t\t// Filter out possible comments\n\t\t\tif ( tag === \"*\" ) {\n\t\t\t\twhile ( (elem = results[i++]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\ttmp.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn tmp;\n\t\t\t}\n\t\t\treturn results;\n\t\t};\n\n\t// Class\n\tExpr.find[\"CLASS\"] = support.getElementsByClassName && function( className, context ) {\n\t\tif ( typeof context.getElementsByClassName !== \"undefined\" && documentIsHTML ) {\n\t\t\treturn context.getElementsByClassName( className );\n\t\t}\n\t};\n\n\t/* QSA/matchesSelector\n\t---------------------------------------------------------------------- */\n\n\t// QSA and matchesSelector support\n\n\t// matchesSelector(:active) reports false when true (IE9/Opera 11.5)\n\trbuggyMatches = [];\n\n\t// qSa(:focus) reports false when true (Chrome 21)\n\t// We allow this because of a bug in IE8/9 that throws an error\n\t// whenever `document.activeElement` is accessed on an iframe\n\t// So, we allow :focus to pass through QSA all the time to avoid the IE error\n\t// See https://bugs.jquery.com/ticket/13378\n\trbuggyQSA = [];\n\n\tif ( (support.qsa = rnative.test( document.querySelectorAll )) ) {\n\t\t// Build QSA regex\n\t\t// Regex strategy adopted from Diego Perini\n\t\tassert(function( el ) {\n\t\t\t// Select is set to empty string on purpose\n\t\t\t// This is to test IE's treatment of not explicitly\n\t\t\t// setting a boolean content attribute,\n\t\t\t// since its presence should be enough\n\t\t\t// https://bugs.jquery.com/ticket/12359\n\t\t\tdocElem.appendChild( el ).innerHTML = \"<a id='\" + expando + \"'></a>\" +\n\t\t\t\t\"<select id='\" + expando + \"-\\r\\\\' msallowcapture=''>\" +\n\t\t\t\t\"<option selected=''></option></select>\";\n\n\t\t\t// Support: IE8, Opera 11-12.16\n\t\t\t// Nothing should be selected when empty strings follow ^= or $= or *=\n\t\t\t// The test attribute must be unknown in Opera but \"safe\" for WinRT\n\t\t\t// https://msdn.microsoft.com/en-us/library/ie/hh465388.aspx#attribute_section\n\t\t\tif ( el.querySelectorAll(\"[msallowcapture^='']\").length ) {\n\t\t\t\trbuggyQSA.push( \"[*^$]=\" + whitespace + \"*(?:''|\\\"\\\")\" );\n\t\t\t}\n\n\t\t\t// Support: IE8\n\t\t\t// Boolean attributes and \"value\" are not treated correctly\n\t\t\tif ( !el.querySelectorAll(\"[selected]\").length ) {\n\t\t\t\trbuggyQSA.push( \"\\\\[\" + whitespace + \"*(?:value|\" + booleans + \")\" );\n\t\t\t}\n\n\t\t\t// Support: Chrome<29, Android<4.4, Safari<7.0+, iOS<7.0+, PhantomJS<1.9.8+\n\t\t\tif ( !el.querySelectorAll( \"[id~=\" + expando + \"-]\" ).length ) {\n\t\t\t\trbuggyQSA.push(\"~=\");\n\t\t\t}\n\n\t\t\t// Webkit/Opera - :checked should return selected option elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( !el.querySelectorAll(\":checked\").length ) {\n\t\t\t\trbuggyQSA.push(\":checked\");\n\t\t\t}\n\n\t\t\t// Support: Safari 8+, iOS 8+\n\t\t\t// https://bugs.webkit.org/show_bug.cgi?id=136851\n\t\t\t// In-page `selector#id sibling-combinator selector` fails\n\t\t\tif ( !el.querySelectorAll( \"a#\" + expando + \"+*\" ).length ) {\n\t\t\t\trbuggyQSA.push(\".#.+[+~]\");\n\t\t\t}\n\t\t});\n\n\t\tassert(function( el ) {\n\t\t\tel.innerHTML = \"<a href='' disabled='disabled'></a>\" +\n\t\t\t\t\"<select disabled='disabled'><option/></select>\";\n\n\t\t\t// Support: Windows 8 Native Apps\n\t\t\t// The type and name attributes are restricted during .innerHTML assignment\n\t\t\tvar input = document.createElement(\"input\");\n\t\t\tinput.setAttribute( \"type\", \"hidden\" );\n\t\t\tel.appendChild( input ).setAttribute( \"name\", \"D\" );\n\n\t\t\t// Support: IE8\n\t\t\t// Enforce case-sensitivity of name attribute\n\t\t\tif ( el.querySelectorAll(\"[name=d]\").length ) {\n\t\t\t\trbuggyQSA.push( \"name\" + whitespace + \"*[*^$|!~]?=\" );\n\t\t\t}\n\n\t\t\t// FF 3.5 - :enabled/:disabled and hidden elements (hidden elements are still enabled)\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( el.querySelectorAll(\":enabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Support: IE9-11+\n\t\t\t// IE's :disabled selector does not pick up the children of disabled fieldsets\n\t\t\tdocElem.appendChild( el ).disabled = true;\n\t\t\tif ( el.querySelectorAll(\":disabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Opera 10-11 does not throw on post-comma invalid pseudos\n\t\t\tel.querySelectorAll(\"*,:x\");\n\t\t\trbuggyQSA.push(\",.*:\");\n\t\t});\n\t}\n\n\tif ( (support.matchesSelector = rnative.test( (matches = docElem.matches ||\n\t\tdocElem.webkitMatchesSelector ||\n\t\tdocElem.mozMatchesSelector ||\n\t\tdocElem.oMatchesSelector ||\n\t\tdocElem.msMatchesSelector) )) ) {\n\n\t\tassert(function( el ) {\n\t\t\t// Check to see if it's possible to do matchesSelector\n\t\t\t// on a disconnected node (IE 9)\n\t\t\tsupport.disconnectedMatch = matches.call( el, \"*\" );\n\n\t\t\t// This should fail with an exception\n\t\t\t// Gecko does not error, returns false instead\n\t\t\tmatches.call( el, \"[s!='']:x\" );\n\t\t\trbuggyMatches.push( \"!=\", pseudos );\n\t\t});\n\t}\n\n\trbuggyQSA = rbuggyQSA.length && new RegExp( rbuggyQSA.join(\"|\") );\n\trbuggyMatches = rbuggyMatches.length && new RegExp( rbuggyMatches.join(\"|\") );\n\n\t/* Contains\n\t---------------------------------------------------------------------- */\n\thasCompare = rnative.test( docElem.compareDocumentPosition );\n\n\t// Element contains another\n\t// Purposefully self-exclusive\n\t// As in, an element does not contain itself\n\tcontains = hasCompare || rnative.test( docElem.contains ) ?\n\t\tfunction( a, b ) {\n\t\t\tvar adown = a.nodeType === 9 ? a.documentElement : a,\n\t\t\t\tbup = b && b.parentNode;\n\t\t\treturn a === bup || !!( bup && bup.nodeType === 1 && (\n\t\t\t\tadown.contains ?\n\t\t\t\t\tadown.contains( bup ) :\n\t\t\t\t\ta.compareDocumentPosition && a.compareDocumentPosition( bup ) & 16\n\t\t\t));\n\t\t} :\n\t\tfunction( a, b ) {\n\t\t\tif ( b ) {\n\t\t\t\twhile ( (b = b.parentNode) ) {\n\t\t\t\t\tif ( b === a ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n\n\t/* Sorting\n\t---------------------------------------------------------------------- */\n\n\t// Document order sorting\n\tsortOrder = hasCompare ?\n\tfunction( a, b ) {\n\n\t\t// Flag for duplicate removal\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\t// Sort on method existence if only one input has compareDocumentPosition\n\t\tvar compare = !a.compareDocumentPosition - !b.compareDocumentPosition;\n\t\tif ( compare ) {\n\t\t\treturn compare;\n\t\t}\n\n\t\t// Calculate position if both inputs belong to the same document\n\t\tcompare = ( a.ownerDocument || a ) === ( b.ownerDocument || b ) ?\n\t\t\ta.compareDocumentPosition( b ) :\n\n\t\t\t// Otherwise we know they are disconnected\n\t\t\t1;\n\n\t\t// Disconnected nodes\n\t\tif ( compare & 1 ||\n\t\t\t(!support.sortDetached && b.compareDocumentPosition( a ) === compare) ) {\n\n\t\t\t// Choose the first element that is related to our preferred document\n\t\t\tif ( a === document || a.ownerDocument === preferredDoc && contains(preferredDoc, a) ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t\tif ( b === document || b.ownerDocument === preferredDoc && contains(preferredDoc, b) ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\t// Maintain original order\n\t\t\treturn sortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\t\t}\n\n\t\treturn compare & 4 ? -1 : 1;\n\t} :\n\tfunction( a, b ) {\n\t\t// Exit early if the nodes are identical\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\taup = a.parentNode,\n\t\t\tbup = b.parentNode,\n\t\t\tap = [ a ],\n\t\t\tbp = [ b ];\n\n\t\t// Parentless nodes are either documents or disconnected\n\t\tif ( !aup || !bup ) {\n\t\t\treturn a === document ? -1 :\n\t\t\t\tb === document ? 1 :\n\t\t\t\taup ? -1 :\n\t\t\t\tbup ? 1 :\n\t\t\t\tsortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\n\t\t// If the nodes are siblings, we can do a quick check\n\t\t} else if ( aup === bup ) {\n\t\t\treturn siblingCheck( a, b );\n\t\t}\n\n\t\t// Otherwise we need full lists of their ancestors for comparison\n\t\tcur = a;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tap.unshift( cur );\n\t\t}\n\t\tcur = b;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tbp.unshift( cur );\n\t\t}\n\n\t\t// Walk down the tree looking for a discrepancy\n\t\twhile ( ap[i] === bp[i] ) {\n\t\t\ti++;\n\t\t}\n\n\t\treturn i ?\n\t\t\t// Do a sibling check if the nodes have a common ancestor\n\t\t\tsiblingCheck( ap[i], bp[i] ) :\n\n\t\t\t// Otherwise nodes in our document sort first\n\t\t\tap[i] === preferredDoc ? -1 :\n\t\t\tbp[i] === preferredDoc ? 1 :\n\t\t\t0;\n\t};\n\n\treturn document;\n};\n\nSizzle.matches = function( expr, elements ) {\n\treturn Sizzle( expr, null, null, elements );\n};\n\nSizzle.matchesSelector = function( elem, expr ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tif ( support.matchesSelector && documentIsHTML &&\n\t\t!nonnativeSelectorCache[ expr + \" \" ] &&\n\t\t( !rbuggyMatches || !rbuggyMatches.test( expr ) ) &&\n\t\t( !rbuggyQSA     || !rbuggyQSA.test( expr ) ) ) {\n\n\t\ttry {\n\t\t\tvar ret = matches.call( elem, expr );\n\n\t\t\t// IE 9's matchesSelector returns false on disconnected nodes\n\t\t\tif ( ret || support.disconnectedMatch ||\n\t\t\t\t\t// As well, disconnected nodes are said to be in a document\n\t\t\t\t\t// fragment in IE 9\n\t\t\t\t\telem.document && elem.document.nodeType !== 11 ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\t\t} catch (e) {\n\t\t\tnonnativeSelectorCache( expr, true );\n\t\t}\n\t}\n\n\treturn Sizzle( expr, document, null, [ elem ] ).length > 0;\n};\n\nSizzle.contains = function( context, elem ) {\n\t// Set document vars if needed\n\tif ( ( context.ownerDocument || context ) !== document ) {\n\t\tsetDocument( context );\n\t}\n\treturn contains( context, elem );\n};\n\nSizzle.attr = function( elem, name ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tvar fn = Expr.attrHandle[ name.toLowerCase() ],\n\t\t// Don't get fooled by Object.prototype properties (jQuery #13807)\n\t\tval = fn && hasOwn.call( Expr.attrHandle, name.toLowerCase() ) ?\n\t\t\tfn( elem, name, !documentIsHTML ) :\n\t\t\tundefined;\n\n\treturn val !== undefined ?\n\t\tval :\n\t\tsupport.attributes || !documentIsHTML ?\n\t\t\telem.getAttribute( name ) :\n\t\t\t(val = elem.getAttributeNode(name)) && val.specified ?\n\t\t\t\tval.value :\n\t\t\t\tnull;\n};\n\nSizzle.escape = function( sel ) {\n\treturn (sel + \"\").replace( rcssescape, fcssescape );\n};\n\nSizzle.error = function( msg ) {\n\tthrow new Error( \"Syntax error, unrecognized expression: \" + msg );\n};\n\n/**\n * Document sorting and removing duplicates\n * @param {ArrayLike} results\n */\nSizzle.uniqueSort = function( results ) {\n\tvar elem,\n\t\tduplicates = [],\n\t\tj = 0,\n\t\ti = 0;\n\n\t// Unless we *know* we can detect duplicates, assume their presence\n\thasDuplicate = !support.detectDuplicates;\n\tsortInput = !support.sortStable && results.slice( 0 );\n\tresults.sort( sortOrder );\n\n\tif ( hasDuplicate ) {\n\t\twhile ( (elem = results[i++]) ) {\n\t\t\tif ( elem === results[ i ] ) {\n\t\t\t\tj = duplicates.push( i );\n\t\t\t}\n\t\t}\n\t\twhile ( j-- ) {\n\t\t\tresults.splice( duplicates[ j ], 1 );\n\t\t}\n\t}\n\n\t// Clear input after sorting to release objects\n\t// See https://github.com/jquery/sizzle/pull/225\n\tsortInput = null;\n\n\treturn results;\n};\n\n/**\n * Utility function for retrieving the text value of an array of DOM nodes\n * @param {Array|Element} elem\n */\ngetText = Sizzle.getText = function( elem ) {\n\tvar node,\n\t\tret = \"\",\n\t\ti = 0,\n\t\tnodeType = elem.nodeType;\n\n\tif ( !nodeType ) {\n\t\t// If no nodeType, this is expected to be an array\n\t\twhile ( (node = elem[i++]) ) {\n\t\t\t// Do not traverse comment nodes\n\t\t\tret += getText( node );\n\t\t}\n\t} else if ( nodeType === 1 || nodeType === 9 || nodeType === 11 ) {\n\t\t// Use textContent for elements\n\t\t// innerText usage removed for consistency of new lines (jQuery #11153)\n\t\tif ( typeof elem.textContent === \"string\" ) {\n\t\t\treturn elem.textContent;\n\t\t} else {\n\t\t\t// Traverse its children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tret += getText( elem );\n\t\t\t}\n\t\t}\n\t} else if ( nodeType === 3 || nodeType === 4 ) {\n\t\treturn elem.nodeValue;\n\t}\n\t// Do not include comment or processing instruction nodes\n\n\treturn ret;\n};\n\nExpr = Sizzle.selectors = {\n\n\t// Can be adjusted by the user\n\tcacheLength: 50,\n\n\tcreatePseudo: markFunction,\n\n\tmatch: matchExpr,\n\n\tattrHandle: {},\n\n\tfind: {},\n\n\trelative: {\n\t\t\">\": { dir: \"parentNode\", first: true },\n\t\t\" \": { dir: \"parentNode\" },\n\t\t\"+\": { dir: \"previousSibling\", first: true },\n\t\t\"~\": { dir: \"previousSibling\" }\n\t},\n\n\tpreFilter: {\n\t\t\"ATTR\": function( match ) {\n\t\t\tmatch[1] = match[1].replace( runescape, funescape );\n\n\t\t\t// Move the given value to match[3] whether quoted or unquoted\n\t\t\tmatch[3] = ( match[3] || match[4] || match[5] || \"\" ).replace( runescape, funescape );\n\n\t\t\tif ( match[2] === \"~=\" ) {\n\t\t\t\tmatch[3] = \" \" + match[3] + \" \";\n\t\t\t}\n\n\t\t\treturn match.slice( 0, 4 );\n\t\t},\n\n\t\t\"CHILD\": function( match ) {\n\t\t\t/* matches from matchExpr[\"CHILD\"]\n\t\t\t\t1 type (only|nth|...)\n\t\t\t\t2 what (child|of-type)\n\t\t\t\t3 argument (even|odd|\\d*|\\d*n([+-]\\d+)?|...)\n\t\t\t\t4 xn-component of xn+y argument ([+-]?\\d*n|)\n\t\t\t\t5 sign of xn-component\n\t\t\t\t6 x of xn-component\n\t\t\t\t7 sign of y-component\n\t\t\t\t8 y of y-component\n\t\t\t*/\n\t\t\tmatch[1] = match[1].toLowerCase();\n\n\t\t\tif ( match[1].slice( 0, 3 ) === \"nth\" ) {\n\t\t\t\t// nth-* requires argument\n\t\t\t\tif ( !match[3] ) {\n\t\t\t\t\tSizzle.error( match[0] );\n\t\t\t\t}\n\n\t\t\t\t// numeric x and y parameters for Expr.filter.CHILD\n\t\t\t\t// remember that false/true cast respectively to 0/1\n\t\t\t\tmatch[4] = +( match[4] ? match[5] + (match[6] || 1) : 2 * ( match[3] === \"even\" || match[3] === \"odd\" ) );\n\t\t\t\tmatch[5] = +( ( match[7] + match[8] ) || match[3] === \"odd\" );\n\n\t\t\t// other types prohibit arguments\n\t\t\t} else if ( match[3] ) {\n\t\t\t\tSizzle.error( match[0] );\n\t\t\t}\n\n\t\t\treturn match;\n\t\t},\n\n\t\t\"PSEUDO\": function( match ) {\n\t\t\tvar excess,\n\t\t\t\tunquoted = !match[6] && match[2];\n\n\t\t\tif ( matchExpr[\"CHILD\"].test( match[0] ) ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\t// Accept quoted arguments as-is\n\t\t\tif ( match[3] ) {\n\t\t\t\tmatch[2] = match[4] || match[5] || \"\";\n\n\t\t\t// Strip excess characters from unquoted arguments\n\t\t\t} else if ( unquoted && rpseudo.test( unquoted ) &&\n\t\t\t\t// Get excess from tokenize (recursively)\n\t\t\t\t(excess = tokenize( unquoted, true )) &&\n\t\t\t\t// advance to the next closing parenthesis\n\t\t\t\t(excess = unquoted.indexOf( \")\", unquoted.length - excess ) - unquoted.length) ) {\n\n\t\t\t\t// excess is a negative index\n\t\t\t\tmatch[0] = match[0].slice( 0, excess );\n\t\t\t\tmatch[2] = unquoted.slice( 0, excess );\n\t\t\t}\n\n\t\t\t// Return only captures needed by the pseudo filter method (type and argument)\n\t\t\treturn match.slice( 0, 3 );\n\t\t}\n\t},\n\n\tfilter: {\n\n\t\t\"TAG\": function( nodeNameSelector ) {\n\t\t\tvar nodeName = nodeNameSelector.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn nodeNameSelector === \"*\" ?\n\t\t\t\tfunction() { return true; } :\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn elem.nodeName && elem.nodeName.toLowerCase() === nodeName;\n\t\t\t\t};\n\t\t},\n\n\t\t\"CLASS\": function( className ) {\n\t\t\tvar pattern = classCache[ className + \" \" ];\n\n\t\t\treturn pattern ||\n\t\t\t\t(pattern = new RegExp( \"(^|\" + whitespace + \")\" + className + \"(\" + whitespace + \"|$)\" )) &&\n\t\t\t\tclassCache( className, function( elem ) {\n\t\t\t\t\treturn pattern.test( typeof elem.className === \"string\" && elem.className || typeof elem.getAttribute !== \"undefined\" && elem.getAttribute(\"class\") || \"\" );\n\t\t\t\t});\n\t\t},\n\n\t\t\"ATTR\": function( name, operator, check ) {\n\t\t\treturn function( elem ) {\n\t\t\t\tvar result = Sizzle.attr( elem, name );\n\n\t\t\t\tif ( result == null ) {\n\t\t\t\t\treturn operator === \"!=\";\n\t\t\t\t}\n\t\t\t\tif ( !operator ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\n\t\t\t\tresult += \"\";\n\n\t\t\t\treturn operator === \"=\" ? result === check :\n\t\t\t\t\toperator === \"!=\" ? result !== check :\n\t\t\t\t\toperator === \"^=\" ? check && result.indexOf( check ) === 0 :\n\t\t\t\t\toperator === \"*=\" ? check && result.indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"$=\" ? check && result.slice( -check.length ) === check :\n\t\t\t\t\toperator === \"~=\" ? ( \" \" + result.replace( rwhitespace, \" \" ) + \" \" ).indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"|=\" ? result === check || result.slice( 0, check.length + 1 ) === check + \"-\" :\n\t\t\t\t\tfalse;\n\t\t\t};\n\t\t},\n\n\t\t\"CHILD\": function( type, what, argument, first, last ) {\n\t\t\tvar simple = type.slice( 0, 3 ) !== \"nth\",\n\t\t\t\tforward = type.slice( -4 ) !== \"last\",\n\t\t\t\tofType = what === \"of-type\";\n\n\t\t\treturn first === 1 && last === 0 ?\n\n\t\t\t\t// Shortcut for :nth-*(n)\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn !!elem.parentNode;\n\t\t\t\t} :\n\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tvar cache, uniqueCache, outerCache, node, nodeIndex, start,\n\t\t\t\t\t\tdir = simple !== forward ? \"nextSibling\" : \"previousSibling\",\n\t\t\t\t\t\tparent = elem.parentNode,\n\t\t\t\t\t\tname = ofType && elem.nodeName.toLowerCase(),\n\t\t\t\t\t\tuseCache = !xml && !ofType,\n\t\t\t\t\t\tdiff = false;\n\n\t\t\t\t\tif ( parent ) {\n\n\t\t\t\t\t\t// :(first|last|only)-(child|of-type)\n\t\t\t\t\t\tif ( simple ) {\n\t\t\t\t\t\t\twhile ( dir ) {\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\twhile ( (node = node[ dir ]) ) {\n\t\t\t\t\t\t\t\t\tif ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) {\n\n\t\t\t\t\t\t\t\t\t\treturn false;\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t// Reverse direction for :only-* (if we haven't yet done so)\n\t\t\t\t\t\t\t\tstart = dir = type === \"only\" && !start && \"nextSibling\";\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\tstart = [ forward ? parent.firstChild : parent.lastChild ];\n\n\t\t\t\t\t\t// non-xml :nth-child(...) stores cache data on `parent`\n\t\t\t\t\t\tif ( forward && useCache ) {\n\n\t\t\t\t\t\t\t// Seek `elem` from a previously-cached index\n\n\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\tnode = parent;\n\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\tdiff = nodeIndex && cache[ 2 ];\n\t\t\t\t\t\t\tnode = nodeIndex && parent.childNodes[ nodeIndex ];\n\n\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\n\t\t\t\t\t\t\t\t// Fallback to seeking `elem` from the start\n\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t// When found, cache indexes on `parent` and break\n\t\t\t\t\t\t\t\tif ( node.nodeType === 1 && ++diff && node === elem ) {\n\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, nodeIndex, diff ];\n\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Use previously-cached element index if available\n\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\t\tdiff = nodeIndex;\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t// xml :nth-child(...)\n\t\t\t\t\t\t\t// or :nth-last-child(...) or :nth(-last)?-of-type(...)\n\t\t\t\t\t\t\tif ( diff === false ) {\n\t\t\t\t\t\t\t\t// Use the same loop as above to seek `elem` from the start\n\t\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\t\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t\tif ( ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) &&\n\t\t\t\t\t\t\t\t\t\t++diff ) {\n\n\t\t\t\t\t\t\t\t\t\t// Cache the index of each encountered element\n\t\t\t\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, diff ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\tif ( node === elem ) {\n\t\t\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Incorporate the offset, then check against cycle size\n\t\t\t\t\t\tdiff -= last;\n\t\t\t\t\t\treturn diff === first || ( diff % first === 0 && diff / first >= 0 );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t},\n\n\t\t\"PSEUDO\": function( pseudo, argument ) {\n\t\t\t// pseudo-class names are case-insensitive\n\t\t\t// http://www.w3.org/TR/selectors/#pseudo-classes\n\t\t\t// Prioritize by case sensitivity in case custom pseudos are added with uppercase letters\n\t\t\t// Remember that setFilters inherits from pseudos\n\t\t\tvar args,\n\t\t\t\tfn = Expr.pseudos[ pseudo ] || Expr.setFilters[ pseudo.toLowerCase() ] ||\n\t\t\t\t\tSizzle.error( \"unsupported pseudo: \" + pseudo );\n\n\t\t\t// The user may use createPseudo to indicate that\n\t\t\t// arguments are needed to create the filter function\n\t\t\t// just as Sizzle does\n\t\t\tif ( fn[ expando ] ) {\n\t\t\t\treturn fn( argument );\n\t\t\t}\n\n\t\t\t// But maintain support for old signatures\n\t\t\tif ( fn.length > 1 ) {\n\t\t\t\targs = [ pseudo, pseudo, \"\", argument ];\n\t\t\t\treturn Expr.setFilters.hasOwnProperty( pseudo.toLowerCase() ) ?\n\t\t\t\t\tmarkFunction(function( seed, matches ) {\n\t\t\t\t\t\tvar idx,\n\t\t\t\t\t\t\tmatched = fn( seed, argument ),\n\t\t\t\t\t\t\ti = matched.length;\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tidx = indexOf( seed, matched[i] );\n\t\t\t\t\t\t\tseed[ idx ] = !( matches[ idx ] = matched[i] );\n\t\t\t\t\t\t}\n\t\t\t\t\t}) :\n\t\t\t\t\tfunction( elem ) {\n\t\t\t\t\t\treturn fn( elem, 0, args );\n\t\t\t\t\t};\n\t\t\t}\n\n\t\t\treturn fn;\n\t\t}\n\t},\n\n\tpseudos: {\n\t\t// Potentially complex pseudos\n\t\t\"not\": markFunction(function( selector ) {\n\t\t\t// Trim the selector passed to compile\n\t\t\t// to avoid treating leading and trailing\n\t\t\t// spaces as combinators\n\t\t\tvar input = [],\n\t\t\t\tresults = [],\n\t\t\t\tmatcher = compile( selector.replace( rtrim, \"$1\" ) );\n\n\t\t\treturn matcher[ expando ] ?\n\t\t\t\tmarkFunction(function( seed, matches, context, xml ) {\n\t\t\t\t\tvar elem,\n\t\t\t\t\t\tunmatched = matcher( seed, null, xml, [] ),\n\t\t\t\t\t\ti = seed.length;\n\n\t\t\t\t\t// Match elements unmatched by `matcher`\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = unmatched[i]) ) {\n\t\t\t\t\t\t\tseed[i] = !(matches[i] = elem);\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}) :\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tinput[0] = elem;\n\t\t\t\t\tmatcher( input, null, xml, results );\n\t\t\t\t\t// Don't keep the element (issue #299)\n\t\t\t\t\tinput[0] = null;\n\t\t\t\t\treturn !results.pop();\n\t\t\t\t};\n\t\t}),\n\n\t\t\"has\": markFunction(function( selector ) {\n\t\t\treturn function( elem ) {\n\t\t\t\treturn Sizzle( selector, elem ).length > 0;\n\t\t\t};\n\t\t}),\n\n\t\t\"contains\": markFunction(function( text ) {\n\t\t\ttext = text.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn ( elem.textContent || getText( elem ) ).indexOf( text ) > -1;\n\t\t\t};\n\t\t}),\n\n\t\t// \"Whether an element is represented by a :lang() selector\n\t\t// is based solely on the element's language value\n\t\t// being equal to the identifier C,\n\t\t// or beginning with the identifier C immediately followed by \"-\".\n\t\t// The matching of C against the element's language value is performed case-insensitively.\n\t\t// The identifier C does not have to be a valid language name.\"\n\t\t// http://www.w3.org/TR/selectors/#lang-pseudo\n\t\t\"lang\": markFunction( function( lang ) {\n\t\t\t// lang value must be a valid identifier\n\t\t\tif ( !ridentifier.test(lang || \"\") ) {\n\t\t\t\tSizzle.error( \"unsupported lang: \" + lang );\n\t\t\t}\n\t\t\tlang = lang.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn function( elem ) {\n\t\t\t\tvar elemLang;\n\t\t\t\tdo {\n\t\t\t\t\tif ( (elemLang = documentIsHTML ?\n\t\t\t\t\t\telem.lang :\n\t\t\t\t\t\telem.getAttribute(\"xml:lang\") || elem.getAttribute(\"lang\")) ) {\n\n\t\t\t\t\t\telemLang = elemLang.toLowerCase();\n\t\t\t\t\t\treturn elemLang === lang || elemLang.indexOf( lang + \"-\" ) === 0;\n\t\t\t\t\t}\n\t\t\t\t} while ( (elem = elem.parentNode) && elem.nodeType === 1 );\n\t\t\t\treturn false;\n\t\t\t};\n\t\t}),\n\n\t\t// Miscellaneous\n\t\t\"target\": function( elem ) {\n\t\t\tvar hash = window.location && window.location.hash;\n\t\t\treturn hash && hash.slice( 1 ) === elem.id;\n\t\t},\n\n\t\t\"root\": function( elem ) {\n\t\t\treturn elem === docElem;\n\t\t},\n\n\t\t\"focus\": function( elem ) {\n\t\t\treturn elem === document.activeElement && (!document.hasFocus || document.hasFocus()) && !!(elem.type || elem.href || ~elem.tabIndex);\n\t\t},\n\n\t\t// Boolean properties\n\t\t\"enabled\": createDisabledPseudo( false ),\n\t\t\"disabled\": createDisabledPseudo( true ),\n\n\t\t\"checked\": function( elem ) {\n\t\t\t// In CSS3, :checked should return both checked and selected elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\tvar nodeName = elem.nodeName.toLowerCase();\n\t\t\treturn (nodeName === \"input\" && !!elem.checked) || (nodeName === \"option\" && !!elem.selected);\n\t\t},\n\n\t\t\"selected\": function( elem ) {\n\t\t\t// Accessing this property makes selected-by-default\n\t\t\t// options in Safari work properly\n\t\t\tif ( elem.parentNode ) {\n\t\t\t\telem.parentNode.selectedIndex;\n\t\t\t}\n\n\t\t\treturn elem.selected === true;\n\t\t},\n\n\t\t// Contents\n\t\t\"empty\": function( elem ) {\n\t\t\t// http://www.w3.org/TR/selectors/#empty-pseudo\n\t\t\t// :empty is negated by element (1) or content nodes (text: 3; cdata: 4; entity ref: 5),\n\t\t\t//   but not by others (comment: 8; processing instruction: 7; etc.)\n\t\t\t// nodeType < 6 works because attributes (2) do not appear as children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tif ( elem.nodeType < 6 ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t},\n\n\t\t\"parent\": function( elem ) {\n\t\t\treturn !Expr.pseudos[\"empty\"]( elem );\n\t\t},\n\n\t\t// Element/input types\n\t\t\"header\": function( elem ) {\n\t\t\treturn rheader.test( elem.nodeName );\n\t\t},\n\n\t\t\"input\": function( elem ) {\n\t\t\treturn rinputs.test( elem.nodeName );\n\t\t},\n\n\t\t\"button\": function( elem ) {\n\t\t\tvar name = elem.nodeName.toLowerCase();\n\t\t\treturn name === \"input\" && elem.type === \"button\" || name === \"button\";\n\t\t},\n\n\t\t\"text\": function( elem ) {\n\t\t\tvar attr;\n\t\t\treturn elem.nodeName.toLowerCase() === \"input\" &&\n\t\t\t\telem.type === \"text\" &&\n\n\t\t\t\t// Support: IE<8\n\t\t\t\t// New HTML5 attribute values (e.g., \"search\") appear with elem.type === \"text\"\n\t\t\t\t( (attr = elem.getAttribute(\"type\")) == null || attr.toLowerCase() === \"text\" );\n\t\t},\n\n\t\t// Position-in-collection\n\t\t\"first\": createPositionalPseudo(function() {\n\t\t\treturn [ 0 ];\n\t\t}),\n\n\t\t\"last\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\treturn [ length - 1 ];\n\t\t}),\n\n\t\t\"eq\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\treturn [ argument < 0 ? argument + length : argument ];\n\t\t}),\n\n\t\t\"even\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"odd\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 1;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"lt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ?\n\t\t\t\targument + length :\n\t\t\t\targument > length ?\n\t\t\t\t\tlength :\n\t\t\t\t\targument;\n\t\t\tfor ( ; --i >= 0; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"gt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ? argument + length : argument;\n\t\t\tfor ( ; ++i < length; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t})\n\t}\n};\n\nExpr.pseudos[\"nth\"] = Expr.pseudos[\"eq\"];\n\n// Add button/input type pseudos\nfor ( i in { radio: true, checkbox: true, file: true, password: true, image: true } ) {\n\tExpr.pseudos[ i ] = createInputPseudo( i );\n}\nfor ( i in { submit: true, reset: true } ) {\n\tExpr.pseudos[ i ] = createButtonPseudo( i );\n}\n\n// Easy API for creating new setFilters\nfunction setFilters() {}\nsetFilters.prototype = Expr.filters = Expr.pseudos;\nExpr.setFilters = new setFilters();\n\ntokenize = Sizzle.tokenize = function( selector, parseOnly ) {\n\tvar matched, match, tokens, type,\n\t\tsoFar, groups, preFilters,\n\t\tcached = tokenCache[ selector + \" \" ];\n\n\tif ( cached ) {\n\t\treturn parseOnly ? 0 : cached.slice( 0 );\n\t}\n\n\tsoFar = selector;\n\tgroups = [];\n\tpreFilters = Expr.preFilter;\n\n\twhile ( soFar ) {\n\n\t\t// Comma and first run\n\t\tif ( !matched || (match = rcomma.exec( soFar )) ) {\n\t\t\tif ( match ) {\n\t\t\t\t// Don't consume trailing commas as valid\n\t\t\t\tsoFar = soFar.slice( match[0].length ) || soFar;\n\t\t\t}\n\t\t\tgroups.push( (tokens = []) );\n\t\t}\n\n\t\tmatched = false;\n\n\t\t// Combinators\n\t\tif ( (match = rcombinators.exec( soFar )) ) {\n\t\t\tmatched = match.shift();\n\t\t\ttokens.push({\n\t\t\t\tvalue: matched,\n\t\t\t\t// Cast descendant combinators to space\n\t\t\t\ttype: match[0].replace( rtrim, \" \" )\n\t\t\t});\n\t\t\tsoFar = soFar.slice( matched.length );\n\t\t}\n\n\t\t// Filters\n\t\tfor ( type in Expr.filter ) {\n\t\t\tif ( (match = matchExpr[ type ].exec( soFar )) && (!preFilters[ type ] ||\n\t\t\t\t(match = preFilters[ type ]( match ))) ) {\n\t\t\t\tmatched = match.shift();\n\t\t\t\ttokens.push({\n\t\t\t\t\tvalue: matched,\n\t\t\t\t\ttype: type,\n\t\t\t\t\tmatches: match\n\t\t\t\t});\n\t\t\t\tsoFar = soFar.slice( matched.length );\n\t\t\t}\n\t\t}\n\n\t\tif ( !matched ) {\n\t\t\tbreak;\n\t\t}\n\t}\n\n\t// Return the length of the invalid excess\n\t// if we're just parsing\n\t// Otherwise, throw an error or return tokens\n\treturn parseOnly ?\n\t\tsoFar.length :\n\t\tsoFar ?\n\t\t\tSizzle.error( selector ) :\n\t\t\t// Cache the tokens\n\t\t\ttokenCache( selector, groups ).slice( 0 );\n};\n\nfunction toSelector( tokens ) {\n\tvar i = 0,\n\t\tlen = tokens.length,\n\t\tselector = \"\";\n\tfor ( ; i < len; i++ ) {\n\t\tselector += tokens[i].value;\n\t}\n\treturn selector;\n}\n\nfunction addCombinator( matcher, combinator, base ) {\n\tvar dir = combinator.dir,\n\t\tskip = combinator.next,\n\t\tkey = skip || dir,\n\t\tcheckNonElements = base && key === \"parentNode\",\n\t\tdoneName = done++;\n\n\treturn combinator.first ?\n\t\t// Check against closest ancestor/preceding element\n\t\tfunction( elem, context, xml ) {\n\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\treturn matcher( elem, context, xml );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t} :\n\n\t\t// Check against all ancestor/preceding elements\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar oldCache, uniqueCache, outerCache,\n\t\t\t\tnewCache = [ dirruns, doneName ];\n\n\t\t\t// We can't set arbitrary data on XML nodes, so they don't benefit from combinator caching\n\t\t\tif ( xml ) {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\tif ( matcher( elem, context, xml ) ) {\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\touterCache = elem[ expando ] || (elem[ expando ] = {});\n\n\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\tuniqueCache = outerCache[ elem.uniqueID ] || (outerCache[ elem.uniqueID ] = {});\n\n\t\t\t\t\t\tif ( skip && skip === elem.nodeName.toLowerCase() ) {\n\t\t\t\t\t\t\telem = elem[ dir ] || elem;\n\t\t\t\t\t\t} else if ( (oldCache = uniqueCache[ key ]) &&\n\t\t\t\t\t\t\toldCache[ 0 ] === dirruns && oldCache[ 1 ] === doneName ) {\n\n\t\t\t\t\t\t\t// Assign to newCache so results back-propagate to previous elements\n\t\t\t\t\t\t\treturn (newCache[ 2 ] = oldCache[ 2 ]);\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Reuse newcache so results back-propagate to previous elements\n\t\t\t\t\t\t\tuniqueCache[ key ] = newCache;\n\n\t\t\t\t\t\t\t// A match means we're done; a fail means we have to keep checking\n\t\t\t\t\t\t\tif ( (newCache[ 2 ] = matcher( elem, context, xml )) ) {\n\t\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n}\n\nfunction elementMatcher( matchers ) {\n\treturn matchers.length > 1 ?\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar i = matchers.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( !matchers[i]( elem, context, xml ) ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t} :\n\t\tmatchers[0];\n}\n\nfunction multipleContexts( selector, contexts, results ) {\n\tvar i = 0,\n\t\tlen = contexts.length;\n\tfor ( ; i < len; i++ ) {\n\t\tSizzle( selector, contexts[i], results );\n\t}\n\treturn results;\n}\n\nfunction condense( unmatched, map, filter, context, xml ) {\n\tvar elem,\n\t\tnewUnmatched = [],\n\t\ti = 0,\n\t\tlen = unmatched.length,\n\t\tmapped = map != null;\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (elem = unmatched[i]) ) {\n\t\t\tif ( !filter || filter( elem, context, xml ) ) {\n\t\t\t\tnewUnmatched.push( elem );\n\t\t\t\tif ( mapped ) {\n\t\t\t\t\tmap.push( i );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn newUnmatched;\n}\n\nfunction setMatcher( preFilter, selector, matcher, postFilter, postFinder, postSelector ) {\n\tif ( postFilter && !postFilter[ expando ] ) {\n\t\tpostFilter = setMatcher( postFilter );\n\t}\n\tif ( postFinder && !postFinder[ expando ] ) {\n\t\tpostFinder = setMatcher( postFinder, postSelector );\n\t}\n\treturn markFunction(function( seed, results, context, xml ) {\n\t\tvar temp, i, elem,\n\t\t\tpreMap = [],\n\t\t\tpostMap = [],\n\t\t\tpreexisting = results.length,\n\n\t\t\t// Get initial elements from seed or context\n\t\t\telems = seed || multipleContexts( selector || \"*\", context.nodeType ? [ context ] : context, [] ),\n\n\t\t\t// Prefilter to get matcher input, preserving a map for seed-results synchronization\n\t\t\tmatcherIn = preFilter && ( seed || !selector ) ?\n\t\t\t\tcondense( elems, preMap, preFilter, context, xml ) :\n\t\t\t\telems,\n\n\t\t\tmatcherOut = matcher ?\n\t\t\t\t// If we have a postFinder, or filtered seed, or non-seed postFilter or preexisting results,\n\t\t\t\tpostFinder || ( seed ? preFilter : preexisting || postFilter ) ?\n\n\t\t\t\t\t// ...intermediate processing is necessary\n\t\t\t\t\t[] :\n\n\t\t\t\t\t// ...otherwise use results directly\n\t\t\t\t\tresults :\n\t\t\t\tmatcherIn;\n\n\t\t// Find primary matches\n\t\tif ( matcher ) {\n\t\t\tmatcher( matcherIn, matcherOut, context, xml );\n\t\t}\n\n\t\t// Apply postFilter\n\t\tif ( postFilter ) {\n\t\t\ttemp = condense( matcherOut, postMap );\n\t\t\tpostFilter( temp, [], context, xml );\n\n\t\t\t// Un-match failing elements by moving them back to matcherIn\n\t\t\ti = temp.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( (elem = temp[i]) ) {\n\t\t\t\t\tmatcherOut[ postMap[i] ] = !(matcherIn[ postMap[i] ] = elem);\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\tif ( seed ) {\n\t\t\tif ( postFinder || preFilter ) {\n\t\t\t\tif ( postFinder ) {\n\t\t\t\t\t// Get the final matcherOut by condensing this intermediate into postFinder contexts\n\t\t\t\t\ttemp = [];\n\t\t\t\t\ti = matcherOut.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = matcherOut[i]) ) {\n\t\t\t\t\t\t\t// Restore matcherIn since elem is not yet a final match\n\t\t\t\t\t\t\ttemp.push( (matcherIn[i] = elem) );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tpostFinder( null, (matcherOut = []), temp, xml );\n\t\t\t\t}\n\n\t\t\t\t// Move matched elements from seed to results to keep them synchronized\n\t\t\t\ti = matcherOut.length;\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\tif ( (elem = matcherOut[i]) &&\n\t\t\t\t\t\t(temp = postFinder ? indexOf( seed, elem ) : preMap[i]) > -1 ) {\n\n\t\t\t\t\t\tseed[temp] = !(results[temp] = elem);\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Add elements to results, through postFinder if defined\n\t\t} else {\n\t\t\tmatcherOut = condense(\n\t\t\t\tmatcherOut === results ?\n\t\t\t\t\tmatcherOut.splice( preexisting, matcherOut.length ) :\n\t\t\t\t\tmatcherOut\n\t\t\t);\n\t\t\tif ( postFinder ) {\n\t\t\t\tpostFinder( null, results, matcherOut, xml );\n\t\t\t} else {\n\t\t\t\tpush.apply( results, matcherOut );\n\t\t\t}\n\t\t}\n\t});\n}\n\nfunction matcherFromTokens( tokens ) {\n\tvar checkContext, matcher, j,\n\t\tlen = tokens.length,\n\t\tleadingRelative = Expr.relative[ tokens[0].type ],\n\t\timplicitRelative = leadingRelative || Expr.relative[\" \"],\n\t\ti = leadingRelative ? 1 : 0,\n\n\t\t// The foundational matcher ensures that elements are reachable from top-level context(s)\n\t\tmatchContext = addCombinator( function( elem ) {\n\t\t\treturn elem === checkContext;\n\t\t}, implicitRelative, true ),\n\t\tmatchAnyContext = addCombinator( function( elem ) {\n\t\t\treturn indexOf( checkContext, elem ) > -1;\n\t\t}, implicitRelative, true ),\n\t\tmatchers = [ function( elem, context, xml ) {\n\t\t\tvar ret = ( !leadingRelative && ( xml || context !== outermostContext ) ) || (\n\t\t\t\t(checkContext = context).nodeType ?\n\t\t\t\t\tmatchContext( elem, context, xml ) :\n\t\t\t\t\tmatchAnyContext( elem, context, xml ) );\n\t\t\t// Avoid hanging onto element (issue #299)\n\t\t\tcheckContext = null;\n\t\t\treturn ret;\n\t\t} ];\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (matcher = Expr.relative[ tokens[i].type ]) ) {\n\t\t\tmatchers = [ addCombinator(elementMatcher( matchers ), matcher) ];\n\t\t} else {\n\t\t\tmatcher = Expr.filter[ tokens[i].type ].apply( null, tokens[i].matches );\n\n\t\t\t// Return special upon seeing a positional matcher\n\t\t\tif ( matcher[ expando ] ) {\n\t\t\t\t// Find the next relative operator (if any) for proper handling\n\t\t\t\tj = ++i;\n\t\t\t\tfor ( ; j < len; j++ ) {\n\t\t\t\t\tif ( Expr.relative[ tokens[j].type ] ) {\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn setMatcher(\n\t\t\t\t\ti > 1 && elementMatcher( matchers ),\n\t\t\t\t\ti > 1 && toSelector(\n\t\t\t\t\t\t// If the preceding token was a descendant combinator, insert an implicit any-element `*`\n\t\t\t\t\t\ttokens.slice( 0, i - 1 ).concat({ value: tokens[ i - 2 ].type === \" \" ? \"*\" : \"\" })\n\t\t\t\t\t).replace( rtrim, \"$1\" ),\n\t\t\t\t\tmatcher,\n\t\t\t\t\ti < j && matcherFromTokens( tokens.slice( i, j ) ),\n\t\t\t\t\tj < len && matcherFromTokens( (tokens = tokens.slice( j )) ),\n\t\t\t\t\tj < len && toSelector( tokens )\n\t\t\t\t);\n\t\t\t}\n\t\t\tmatchers.push( matcher );\n\t\t}\n\t}\n\n\treturn elementMatcher( matchers );\n}\n\nfunction matcherFromGroupMatchers( elementMatchers, setMatchers ) {\n\tvar bySet = setMatchers.length > 0,\n\t\tbyElement = elementMatchers.length > 0,\n\t\tsuperMatcher = function( seed, context, xml, results, outermost ) {\n\t\t\tvar elem, j, matcher,\n\t\t\t\tmatchedCount = 0,\n\t\t\t\ti = \"0\",\n\t\t\t\tunmatched = seed && [],\n\t\t\t\tsetMatched = [],\n\t\t\t\tcontextBackup = outermostContext,\n\t\t\t\t// We must always have either seed elements or outermost context\n\t\t\t\telems = seed || byElement && Expr.find[\"TAG\"]( \"*\", outermost ),\n\t\t\t\t// Use integer dirruns iff this is the outermost matcher\n\t\t\t\tdirrunsUnique = (dirruns += contextBackup == null ? 1 : Math.random() || 0.1),\n\t\t\t\tlen = elems.length;\n\n\t\t\tif ( outermost ) {\n\t\t\t\toutermostContext = context === document || context || outermost;\n\t\t\t}\n\n\t\t\t// Add elements passing elementMatchers directly to results\n\t\t\t// Support: IE<9, Safari\n\t\t\t// Tolerate NodeList properties (IE: \"length\"; Safari: <number>) matching elements by id\n\t\t\tfor ( ; i !== len && (elem = elems[i]) != null; i++ ) {\n\t\t\t\tif ( byElement && elem ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\tif ( !context && elem.ownerDocument !== document ) {\n\t\t\t\t\t\tsetDocument( elem );\n\t\t\t\t\t\txml = !documentIsHTML;\n\t\t\t\t\t}\n\t\t\t\t\twhile ( (matcher = elementMatchers[j++]) ) {\n\t\t\t\t\t\tif ( matcher( elem, context || document, xml) ) {\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( outermost ) {\n\t\t\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Track unmatched elements for set filters\n\t\t\t\tif ( bySet ) {\n\t\t\t\t\t// They will have gone through all possible matchers\n\t\t\t\t\tif ( (elem = !matcher && elem) ) {\n\t\t\t\t\t\tmatchedCount--;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Lengthen the array for every element, matched or not\n\t\t\t\t\tif ( seed ) {\n\t\t\t\t\t\tunmatched.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// `i` is now the count of elements visited above, and adding it to `matchedCount`\n\t\t\t// makes the latter nonnegative.\n\t\t\tmatchedCount += i;\n\n\t\t\t// Apply set filters to unmatched elements\n\t\t\t// NOTE: This can be skipped if there are no unmatched elements (i.e., `matchedCount`\n\t\t\t// equals `i`), unless we didn't visit _any_ elements in the above loop because we have\n\t\t\t// no element matchers and no seed.\n\t\t\t// Incrementing an initially-string \"0\" `i` allows `i` to remain a string only in that\n\t\t\t// case, which will result in a \"00\" `matchedCount` that differs from `i` but is also\n\t\t\t// numerically zero.\n\t\t\tif ( bySet && i !== matchedCount ) {\n\t\t\t\tj = 0;\n\t\t\t\twhile ( (matcher = setMatchers[j++]) ) {\n\t\t\t\t\tmatcher( unmatched, setMatched, context, xml );\n\t\t\t\t}\n\n\t\t\t\tif ( seed ) {\n\t\t\t\t\t// Reintegrate element matches to eliminate the need for sorting\n\t\t\t\t\tif ( matchedCount > 0 ) {\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tif ( !(unmatched[i] || setMatched[i]) ) {\n\t\t\t\t\t\t\t\tsetMatched[i] = pop.call( results );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Discard index placeholder values to get only actual matches\n\t\t\t\t\tsetMatched = condense( setMatched );\n\t\t\t\t}\n\n\t\t\t\t// Add matches to results\n\t\t\t\tpush.apply( results, setMatched );\n\n\t\t\t\t// Seedless set matches succeeding multiple successful matchers stipulate sorting\n\t\t\t\tif ( outermost && !seed && setMatched.length > 0 &&\n\t\t\t\t\t( matchedCount + setMatchers.length ) > 1 ) {\n\n\t\t\t\t\tSizzle.uniqueSort( results );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Override manipulation of globals by nested matchers\n\t\t\tif ( outermost ) {\n\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\toutermostContext = contextBackup;\n\t\t\t}\n\n\t\t\treturn unmatched;\n\t\t};\n\n\treturn bySet ?\n\t\tmarkFunction( superMatcher ) :\n\t\tsuperMatcher;\n}\n\ncompile = Sizzle.compile = function( selector, match /* Internal Use Only */ ) {\n\tvar i,\n\t\tsetMatchers = [],\n\t\telementMatchers = [],\n\t\tcached = compilerCache[ selector + \" \" ];\n\n\tif ( !cached ) {\n\t\t// Generate a function of recursive functions that can be used to check each element\n\t\tif ( !match ) {\n\t\t\tmatch = tokenize( selector );\n\t\t}\n\t\ti = match.length;\n\t\twhile ( i-- ) {\n\t\t\tcached = matcherFromTokens( match[i] );\n\t\t\tif ( cached[ expando ] ) {\n\t\t\t\tsetMatchers.push( cached );\n\t\t\t} else {\n\t\t\t\telementMatchers.push( cached );\n\t\t\t}\n\t\t}\n\n\t\t// Cache the compiled function\n\t\tcached = compilerCache( selector, matcherFromGroupMatchers( elementMatchers, setMatchers ) );\n\n\t\t// Save selector and tokenization\n\t\tcached.selector = selector;\n\t}\n\treturn cached;\n};\n\n/**\n * A low-level selection function that works with Sizzle's compiled\n *  selector functions\n * @param {String|Function} selector A selector or a pre-compiled\n *  selector function built with Sizzle.compile\n * @param {Element} context\n * @param {Array} [results]\n * @param {Array} [seed] A set of elements to match against\n */\nselect = Sizzle.select = function( selector, context, results, seed ) {\n\tvar i, tokens, token, type, find,\n\t\tcompiled = typeof selector === \"function\" && selector,\n\t\tmatch = !seed && tokenize( (selector = compiled.selector || selector) );\n\n\tresults = results || [];\n\n\t// Try to minimize operations if there is only one selector in the list and no seed\n\t// (the latter of which guarantees us context)\n\tif ( match.length === 1 ) {\n\n\t\t// Reduce context if the leading compound selector is an ID\n\t\ttokens = match[0] = match[0].slice( 0 );\n\t\tif ( tokens.length > 2 && (token = tokens[0]).type === \"ID\" &&\n\t\t\t\tcontext.nodeType === 9 && documentIsHTML && Expr.relative[ tokens[1].type ] ) {\n\n\t\t\tcontext = ( Expr.find[\"ID\"]( token.matches[0].replace(runescape, funescape), context ) || [] )[0];\n\t\t\tif ( !context ) {\n\t\t\t\treturn results;\n\n\t\t\t// Precompiled matchers will still verify ancestry, so step up a level\n\t\t\t} else if ( compiled ) {\n\t\t\t\tcontext = context.parentNode;\n\t\t\t}\n\n\t\t\tselector = selector.slice( tokens.shift().value.length );\n\t\t}\n\n\t\t// Fetch a seed set for right-to-left matching\n\t\ti = matchExpr[\"needsContext\"].test( selector ) ? 0 : tokens.length;\n\t\twhile ( i-- ) {\n\t\t\ttoken = tokens[i];\n\n\t\t\t// Abort if we hit a combinator\n\t\t\tif ( Expr.relative[ (type = token.type) ] ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tif ( (find = Expr.find[ type ]) ) {\n\t\t\t\t// Search, expanding context for leading sibling combinators\n\t\t\t\tif ( (seed = find(\n\t\t\t\t\ttoken.matches[0].replace( runescape, funescape ),\n\t\t\t\t\trsibling.test( tokens[0].type ) && testContext( context.parentNode ) || context\n\t\t\t\t)) ) {\n\n\t\t\t\t\t// If seed is empty or no tokens remain, we can return early\n\t\t\t\t\ttokens.splice( i, 1 );\n\t\t\t\t\tselector = seed.length && toSelector( tokens );\n\t\t\t\t\tif ( !selector ) {\n\t\t\t\t\t\tpush.apply( results, seed );\n\t\t\t\t\t\treturn results;\n\t\t\t\t\t}\n\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Compile and execute a filtering function if one is not provided\n\t// Provide `match` to avoid retokenization if we modified the selector above\n\t( compiled || compile( selector, match ) )(\n\t\tseed,\n\t\tcontext,\n\t\t!documentIsHTML,\n\t\tresults,\n\t\t!context || rsibling.test( selector ) && testContext( context.parentNode ) || context\n\t);\n\treturn results;\n};\n\n// One-time assignments\n\n// Sort stability\nsupport.sortStable = expando.split(\"\").sort( sortOrder ).join(\"\") === expando;\n\n// Support: Chrome 14-35+\n// Always assume duplicates if they aren't passed to the comparison function\nsupport.detectDuplicates = !!hasDuplicate;\n\n// Initialize against the default document\nsetDocument();\n\n// Support: Webkit<537.32 - Safari 6.0.3/Chrome 25 (fixed in Chrome 27)\n// Detached nodes confoundingly follow *each other*\nsupport.sortDetached = assert(function( el ) {\n\t// Should return 1, but returns 4 (following)\n\treturn el.compareDocumentPosition( document.createElement(\"fieldset\") ) & 1;\n});\n\n// Support: IE<8\n// Prevent attribute/property \"interpolation\"\n// https://msdn.microsoft.com/en-us/library/ms536429%28VS.85%29.aspx\nif ( !assert(function( el ) {\n\tel.innerHTML = \"<a href='#'></a>\";\n\treturn el.firstChild.getAttribute(\"href\") === \"#\" ;\n}) ) {\n\taddHandle( \"type|href|height|width\", function( elem, name, isXML ) {\n\t\tif ( !isXML ) {\n\t\t\treturn elem.getAttribute( name, name.toLowerCase() === \"type\" ? 1 : 2 );\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use defaultValue in place of getAttribute(\"value\")\nif ( !support.attributes || !assert(function( el ) {\n\tel.innerHTML = \"<input/>\";\n\tel.firstChild.setAttribute( \"value\", \"\" );\n\treturn el.firstChild.getAttribute( \"value\" ) === \"\";\n}) ) {\n\taddHandle( \"value\", function( elem, name, isXML ) {\n\t\tif ( !isXML && elem.nodeName.toLowerCase() === \"input\" ) {\n\t\t\treturn elem.defaultValue;\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use getAttributeNode to fetch booleans when getAttribute lies\nif ( !assert(function( el ) {\n\treturn el.getAttribute(\"disabled\") == null;\n}) ) {\n\taddHandle( booleans, function( elem, name, isXML ) {\n\t\tvar val;\n\t\tif ( !isXML ) {\n\t\t\treturn elem[ name ] === true ? name.toLowerCase() :\n\t\t\t\t\t(val = elem.getAttributeNode( name )) && val.specified ?\n\t\t\t\t\tval.value :\n\t\t\t\tnull;\n\t\t}\n\t});\n}\n\nreturn Sizzle;\n\n})( window );\n\n\n\njQuery.find = Sizzle;\njQuery.expr = Sizzle.selectors;\n\n// Deprecated\njQuery.expr[ \":\" ] = jQuery.expr.pseudos;\njQuery.uniqueSort = jQuery.unique = Sizzle.uniqueSort;\njQuery.text = Sizzle.getText;\njQuery.isXMLDoc = Sizzle.isXML;\njQuery.contains = Sizzle.contains;\njQuery.escapeSelector = Sizzle.escape;\n\n\n\n\nvar dir = function( elem, dir, until ) {\n\tvar matched = [],\n\t\ttruncate = until !== undefined;\n\n\twhile ( ( elem = elem[ dir ] ) && elem.nodeType !== 9 ) {\n\t\tif ( elem.nodeType === 1 ) {\n\t\t\tif ( truncate && jQuery( elem ).is( until ) ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tmatched.push( elem );\n\t\t}\n\t}\n\treturn matched;\n};\n\n\nvar siblings = function( n, elem ) {\n\tvar matched = [];\n\n\tfor ( ; n; n = n.nextSibling ) {\n\t\tif ( n.nodeType === 1 && n !== elem ) {\n\t\t\tmatched.push( n );\n\t\t}\n\t}\n\n\treturn matched;\n};\n\n\nvar rneedsContext = jQuery.expr.match.needsContext;\n\n\n\nfunction nodeName( elem, name ) {\n\n  return elem.nodeName && elem.nodeName.toLowerCase() === name.toLowerCase();\n\n};\nvar rsingleTag = ( /^<([a-z][^\\/\\0>:\\x20\\t\\r\\n\\f]*)[\\x20\\t\\r\\n\\f]*\\/?>(?:<\\/\\1>|)$/i );\n\n\n\n// Implement the identical functionality for filter and not\nfunction winnow( elements, qualifier, not ) {\n\tif ( isFunction( qualifier ) ) {\n\t\treturn jQuery.grep( elements, function( elem, i ) {\n\t\t\treturn !!qualifier.call( elem, i, elem ) !== not;\n\t\t} );\n\t}\n\n\t// Single element\n\tif ( qualifier.nodeType ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( elem === qualifier ) !== not;\n\t\t} );\n\t}\n\n\t// Arraylike of elements (jQuery, arguments, Array)\n\tif ( typeof qualifier !== \"string\" ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( indexOf.call( qualifier, elem ) > -1 ) !== not;\n\t\t} );\n\t}\n\n\t// Filtered directly for both simple and complex selectors\n\treturn jQuery.filter( qualifier, elements, not );\n}\n\njQuery.filter = function( expr, elems, not ) {\n\tvar elem = elems[ 0 ];\n\n\tif ( not ) {\n\t\texpr = \":not(\" + expr + \")\";\n\t}\n\n\tif ( elems.length === 1 && elem.nodeType === 1 ) {\n\t\treturn jQuery.find.matchesSelector( elem, expr ) ? [ elem ] : [];\n\t}\n\n\treturn jQuery.find.matches( expr, jQuery.grep( elems, function( elem ) {\n\t\treturn elem.nodeType === 1;\n\t} ) );\n};\n\njQuery.fn.extend( {\n\tfind: function( selector ) {\n\t\tvar i, ret,\n\t\t\tlen = this.length,\n\t\t\tself = this;\n\n\t\tif ( typeof selector !== \"string\" ) {\n\t\t\treturn this.pushStack( jQuery( selector ).filter( function() {\n\t\t\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\t\t\tif ( jQuery.contains( self[ i ], this ) ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} ) );\n\t\t}\n\n\t\tret = this.pushStack( [] );\n\n\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\tjQuery.find( selector, self[ i ], ret );\n\t\t}\n\n\t\treturn len > 1 ? jQuery.uniqueSort( ret ) : ret;\n\t},\n\tfilter: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], false ) );\n\t},\n\tnot: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], true ) );\n\t},\n\tis: function( selector ) {\n\t\treturn !!winnow(\n\t\t\tthis,\n\n\t\t\t// If this is a positional/relative selector, check membership in the returned set\n\t\t\t// so $(\"p:first\").is(\"p:last\") won't return true for a doc with two \"p\".\n\t\t\ttypeof selector === \"string\" && rneedsContext.test( selector ) ?\n\t\t\t\tjQuery( selector ) :\n\t\t\t\tselector || [],\n\t\t\tfalse\n\t\t).length;\n\t}\n} );\n\n\n// Initialize a jQuery object\n\n\n// A central reference to the root jQuery(document)\nvar rootjQuery,\n\n\t// A simple way to check for HTML strings\n\t// Prioritize #id over <tag> to avoid XSS via location.hash (#9521)\n\t// Strict HTML recognition (#11290: must start with <)\n\t// Shortcut simple #id case for speed\n\trquickExpr = /^(?:\\s*(<[\\w\\W]+>)[^>]*|#([\\w-]+))$/,\n\n\tinit = jQuery.fn.init = function( selector, context, root ) {\n\t\tvar match, elem;\n\n\t\t// HANDLE: $(\"\"), $(null), $(undefined), $(false)\n\t\tif ( !selector ) {\n\t\t\treturn this;\n\t\t}\n\n\t\t// Method init() accepts an alternate rootjQuery\n\t\t// so migrate can support jQuery.sub (gh-2101)\n\t\troot = root || rootjQuery;\n\n\t\t// Handle HTML strings\n\t\tif ( typeof selector === \"string\" ) {\n\t\t\tif ( selector[ 0 ] === \"<\" &&\n\t\t\t\tselector[ selector.length - 1 ] === \">\" &&\n\t\t\t\tselector.length >= 3 ) {\n\n\t\t\t\t// Assume that strings that start and end with <> are HTML and skip the regex check\n\t\t\t\tmatch = [ null, selector, null ];\n\n\t\t\t} else {\n\t\t\t\tmatch = rquickExpr.exec( selector );\n\t\t\t}\n\n\t\t\t// Match html or make sure no context is specified for #id\n\t\t\tif ( match && ( match[ 1 ] || !context ) ) {\n\n\t\t\t\t// HANDLE: $(html) -> $(array)\n\t\t\t\tif ( match[ 1 ] ) {\n\t\t\t\t\tcontext = context instanceof jQuery ? context[ 0 ] : context;\n\n\t\t\t\t\t// Option to run scripts is true for back-compat\n\t\t\t\t\t// Intentionally let the error be thrown if parseHTML is not present\n\t\t\t\t\tjQuery.merge( this, jQuery.parseHTML(\n\t\t\t\t\t\tmatch[ 1 ],\n\t\t\t\t\t\tcontext && context.nodeType ? context.ownerDocument || context : document,\n\t\t\t\t\t\ttrue\n\t\t\t\t\t) );\n\n\t\t\t\t\t// HANDLE: $(html, props)\n\t\t\t\t\tif ( rsingleTag.test( match[ 1 ] ) && jQuery.isPlainObject( context ) ) {\n\t\t\t\t\t\tfor ( match in context ) {\n\n\t\t\t\t\t\t\t// Properties of context are called as methods if possible\n\t\t\t\t\t\t\tif ( isFunction( this[ match ] ) ) {\n\t\t\t\t\t\t\t\tthis[ match ]( context[ match ] );\n\n\t\t\t\t\t\t\t// ...and otherwise set as attributes\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tthis.attr( match, context[ match ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\treturn this;\n\n\t\t\t\t// HANDLE: $(#id)\n\t\t\t\t} else {\n\t\t\t\t\telem = document.getElementById( match[ 2 ] );\n\n\t\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t\t// Inject the element directly into the jQuery object\n\t\t\t\t\t\tthis[ 0 ] = elem;\n\t\t\t\t\t\tthis.length = 1;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\n\t\t\t// HANDLE: $(expr, $(...))\n\t\t\t} else if ( !context || context.jquery ) {\n\t\t\t\treturn ( context || root ).find( selector );\n\n\t\t\t// HANDLE: $(expr, context)\n\t\t\t// (which is just equivalent to: $(context).find(expr)\n\t\t\t} else {\n\t\t\t\treturn this.constructor( context ).find( selector );\n\t\t\t}\n\n\t\t// HANDLE: $(DOMElement)\n\t\t} else if ( selector.nodeType ) {\n\t\t\tthis[ 0 ] = selector;\n\t\t\tthis.length = 1;\n\t\t\treturn this;\n\n\t\t// HANDLE: $(function)\n\t\t// Shortcut for document ready\n\t\t} else if ( isFunction( selector ) ) {\n\t\t\treturn root.ready !== undefined ?\n\t\t\t\troot.ready( selector ) :\n\n\t\t\t\t// Execute immediately if ready is not present\n\t\t\t\tselector( jQuery );\n\t\t}\n\n\t\treturn jQuery.makeArray( selector, this );\n\t};\n\n// Give the init function the jQuery prototype for later instantiation\ninit.prototype = jQuery.fn;\n\n// Initialize central reference\nrootjQuery = jQuery( document );\n\n\nvar rparentsprev = /^(?:parents|prev(?:Until|All))/,\n\n\t// Methods guaranteed to produce a unique set when starting from a unique set\n\tguaranteedUnique = {\n\t\tchildren: true,\n\t\tcontents: true,\n\t\tnext: true,\n\t\tprev: true\n\t};\n\njQuery.fn.extend( {\n\thas: function( target ) {\n\t\tvar targets = jQuery( target, this ),\n\t\t\tl = targets.length;\n\n\t\treturn this.filter( function() {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tif ( jQuery.contains( this, targets[ i ] ) ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\tclosest: function( selectors, context ) {\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\tl = this.length,\n\t\t\tmatched = [],\n\t\t\ttargets = typeof selectors !== \"string\" && jQuery( selectors );\n\n\t\t// Positional selectors never match, since there's no _selection_ context\n\t\tif ( !rneedsContext.test( selectors ) ) {\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tfor ( cur = this[ i ]; cur && cur !== context; cur = cur.parentNode ) {\n\n\t\t\t\t\t// Always skip document fragments\n\t\t\t\t\tif ( cur.nodeType < 11 && ( targets ?\n\t\t\t\t\t\ttargets.index( cur ) > -1 :\n\n\t\t\t\t\t\t// Don't pass non-elements to Sizzle\n\t\t\t\t\t\tcur.nodeType === 1 &&\n\t\t\t\t\t\t\tjQuery.find.matchesSelector( cur, selectors ) ) ) {\n\n\t\t\t\t\t\tmatched.push( cur );\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched.length > 1 ? jQuery.uniqueSort( matched ) : matched );\n\t},\n\n\t// Determine the position of an element within the set\n\tindex: function( elem ) {\n\n\t\t// No argument, return index in parent\n\t\tif ( !elem ) {\n\t\t\treturn ( this[ 0 ] && this[ 0 ].parentNode ) ? this.first().prevAll().length : -1;\n\t\t}\n\n\t\t// Index in selector\n\t\tif ( typeof elem === \"string\" ) {\n\t\t\treturn indexOf.call( jQuery( elem ), this[ 0 ] );\n\t\t}\n\n\t\t// Locate the position of the desired element\n\t\treturn indexOf.call( this,\n\n\t\t\t// If it receives a jQuery object, the first element is used\n\t\t\telem.jquery ? elem[ 0 ] : elem\n\t\t);\n\t},\n\n\tadd: function( selector, context ) {\n\t\treturn this.pushStack(\n\t\t\tjQuery.uniqueSort(\n\t\t\t\tjQuery.merge( this.get(), jQuery( selector, context ) )\n\t\t\t)\n\t\t);\n\t},\n\n\taddBack: function( selector ) {\n\t\treturn this.add( selector == null ?\n\t\t\tthis.prevObject : this.prevObject.filter( selector )\n\t\t);\n\t}\n} );\n\nfunction sibling( cur, dir ) {\n\twhile ( ( cur = cur[ dir ] ) && cur.nodeType !== 1 ) {}\n\treturn cur;\n}\n\njQuery.each( {\n\tparent: function( elem ) {\n\t\tvar parent = elem.parentNode;\n\t\treturn parent && parent.nodeType !== 11 ? parent : null;\n\t},\n\tparents: function( elem ) {\n\t\treturn dir( elem, \"parentNode\" );\n\t},\n\tparentsUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"parentNode\", until );\n\t},\n\tnext: function( elem ) {\n\t\treturn sibling( elem, \"nextSibling\" );\n\t},\n\tprev: function( elem ) {\n\t\treturn sibling( elem, \"previousSibling\" );\n\t},\n\tnextAll: function( elem ) {\n\t\treturn dir( elem, \"nextSibling\" );\n\t},\n\tprevAll: function( elem ) {\n\t\treturn dir( elem, \"previousSibling\" );\n\t},\n\tnextUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"nextSibling\", until );\n\t},\n\tprevUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"previousSibling\", until );\n\t},\n\tsiblings: function( elem ) {\n\t\treturn siblings( ( elem.parentNode || {} ).firstChild, elem );\n\t},\n\tchildren: function( elem ) {\n\t\treturn siblings( elem.firstChild );\n\t},\n\tcontents: function( elem ) {\n\t\tif ( typeof elem.contentDocument !== \"undefined\" ) {\n\t\t\treturn elem.contentDocument;\n\t\t}\n\n\t\t// Support: IE 9 - 11 only, iOS 7 only, Android Browser <=4.3 only\n\t\t// Treat the template element as a regular one in browsers that\n\t\t// don't support it.\n\t\tif ( nodeName( elem, \"template\" ) ) {\n\t\t\telem = elem.content || elem;\n\t\t}\n\n\t\treturn jQuery.merge( [], elem.childNodes );\n\t}\n}, function( name, fn ) {\n\tjQuery.fn[ name ] = function( until, selector ) {\n\t\tvar matched = jQuery.map( this, fn, until );\n\n\t\tif ( name.slice( -5 ) !== \"Until\" ) {\n\t\t\tselector = until;\n\t\t}\n\n\t\tif ( selector && typeof selector === \"string\" ) {\n\t\t\tmatched = jQuery.filter( selector, matched );\n\t\t}\n\n\t\tif ( this.length > 1 ) {\n\n\t\t\t// Remove duplicates\n\t\t\tif ( !guaranteedUnique[ name ] ) {\n\t\t\t\tjQuery.uniqueSort( matched );\n\t\t\t}\n\n\t\t\t// Reverse order for parents* and prev-derivatives\n\t\t\tif ( rparentsprev.test( name ) ) {\n\t\t\t\tmatched.reverse();\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched );\n\t};\n} );\nvar rnothtmlwhite = ( /[^\\x20\\t\\r\\n\\f]+/g );\n\n\n\n// Convert String-formatted options into Object-formatted ones\nfunction createOptions( options ) {\n\tvar object = {};\n\tjQuery.each( options.match( rnothtmlwhite ) || [], function( _, flag ) {\n\t\tobject[ flag ] = true;\n\t} );\n\treturn object;\n}\n\n/*\n * Create a callback list using the following parameters:\n *\n *\toptions: an optional list of space-separated options that will change how\n *\t\t\tthe callback list behaves or a more traditional option object\n *\n * By default a callback list will act like an event callback list and can be\n * \"fired\" multiple times.\n *\n * Possible options:\n *\n *\tonce:\t\t\twill ensure the callback list can only be fired once (like a Deferred)\n *\n *\tmemory:\t\t\twill keep track of previous values and will call any callback added\n *\t\t\t\t\tafter the list has been fired right away with the latest \"memorized\"\n *\t\t\t\t\tvalues (like a Deferred)\n *\n *\tunique:\t\t\twill ensure a callback can only be added once (no duplicate in the list)\n *\n *\tstopOnFalse:\tinterrupt callings when a callback returns false\n *\n */\njQuery.Callbacks = function( options ) {\n\n\t// Convert options from String-formatted to Object-formatted if needed\n\t// (we check in cache first)\n\toptions = typeof options === \"string\" ?\n\t\tcreateOptions( options ) :\n\t\tjQuery.extend( {}, options );\n\n\tvar // Flag to know if list is currently firing\n\t\tfiring,\n\n\t\t// Last fire value for non-forgettable lists\n\t\tmemory,\n\n\t\t// Flag to know if list was already fired\n\t\tfired,\n\n\t\t// Flag to prevent firing\n\t\tlocked,\n\n\t\t// Actual callback list\n\t\tlist = [],\n\n\t\t// Queue of execution data for repeatable lists\n\t\tqueue = [],\n\n\t\t// Index of currently firing callback (modified by add/remove as needed)\n\t\tfiringIndex = -1,\n\n\t\t// Fire callbacks\n\t\tfire = function() {\n\n\t\t\t// Enforce single-firing\n\t\t\tlocked = locked || options.once;\n\n\t\t\t// Execute callbacks for all pending executions,\n\t\t\t// respecting firingIndex overrides and runtime changes\n\t\t\tfired = firing = true;\n\t\t\tfor ( ; queue.length; firingIndex = -1 ) {\n\t\t\t\tmemory = queue.shift();\n\t\t\t\twhile ( ++firingIndex < list.length ) {\n\n\t\t\t\t\t// Run callback and check for early termination\n\t\t\t\t\tif ( list[ firingIndex ].apply( memory[ 0 ], memory[ 1 ] ) === false &&\n\t\t\t\t\t\toptions.stopOnFalse ) {\n\n\t\t\t\t\t\t// Jump to end and forget the data so .add doesn't re-fire\n\t\t\t\t\t\tfiringIndex = list.length;\n\t\t\t\t\t\tmemory = false;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Forget the data if we're done with it\n\t\t\tif ( !options.memory ) {\n\t\t\t\tmemory = false;\n\t\t\t}\n\n\t\t\tfiring = false;\n\n\t\t\t// Clean up if we're done firing for good\n\t\t\tif ( locked ) {\n\n\t\t\t\t// Keep an empty list if we have data for future add calls\n\t\t\t\tif ( memory ) {\n\t\t\t\t\tlist = [];\n\n\t\t\t\t// Otherwise, this object is spent\n\t\t\t\t} else {\n\t\t\t\t\tlist = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t},\n\n\t\t// Actual Callbacks object\n\t\tself = {\n\n\t\t\t// Add a callback or a collection of callbacks to the list\n\t\t\tadd: function() {\n\t\t\t\tif ( list ) {\n\n\t\t\t\t\t// If we have memory from a past run, we should fire after adding\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfiringIndex = list.length - 1;\n\t\t\t\t\t\tqueue.push( memory );\n\t\t\t\t\t}\n\n\t\t\t\t\t( function add( args ) {\n\t\t\t\t\t\tjQuery.each( args, function( _, arg ) {\n\t\t\t\t\t\t\tif ( isFunction( arg ) ) {\n\t\t\t\t\t\t\t\tif ( !options.unique || !self.has( arg ) ) {\n\t\t\t\t\t\t\t\t\tlist.push( arg );\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} else if ( arg && arg.length && toType( arg ) !== \"string\" ) {\n\n\t\t\t\t\t\t\t\t// Inspect recursively\n\t\t\t\t\t\t\t\tadd( arg );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} );\n\t\t\t\t\t} )( arguments );\n\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Remove a callback from the list\n\t\t\tremove: function() {\n\t\t\t\tjQuery.each( arguments, function( _, arg ) {\n\t\t\t\t\tvar index;\n\t\t\t\t\twhile ( ( index = jQuery.inArray( arg, list, index ) ) > -1 ) {\n\t\t\t\t\t\tlist.splice( index, 1 );\n\n\t\t\t\t\t\t// Handle firing indexes\n\t\t\t\t\t\tif ( index <= firingIndex ) {\n\t\t\t\t\t\t\tfiringIndex--;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Check if a given callback is in the list.\n\t\t\t// If no argument is given, return whether or not list has callbacks attached.\n\t\t\thas: function( fn ) {\n\t\t\t\treturn fn ?\n\t\t\t\t\tjQuery.inArray( fn, list ) > -1 :\n\t\t\t\t\tlist.length > 0;\n\t\t\t},\n\n\t\t\t// Remove all callbacks from the list\n\t\t\tempty: function() {\n\t\t\t\tif ( list ) {\n\t\t\t\t\tlist = [];\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Disable .fire and .add\n\t\t\t// Abort any current/pending executions\n\t\t\t// Clear all callbacks and values\n\t\t\tdisable: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tlist = memory = \"\";\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tdisabled: function() {\n\t\t\t\treturn !list;\n\t\t\t},\n\n\t\t\t// Disable .fire\n\t\t\t// Also disable .add unless we have memory (since it would have no effect)\n\t\t\t// Abort any pending executions\n\t\t\tlock: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tif ( !memory && !firing ) {\n\t\t\t\t\tlist = memory = \"\";\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tlocked: function() {\n\t\t\t\treturn !!locked;\n\t\t\t},\n\n\t\t\t// Call all callbacks with the given context and arguments\n\t\t\tfireWith: function( context, args ) {\n\t\t\t\tif ( !locked ) {\n\t\t\t\t\targs = args || [];\n\t\t\t\t\targs = [ context, args.slice ? args.slice() : args ];\n\t\t\t\t\tqueue.push( args );\n\t\t\t\t\tif ( !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Call all the callbacks with the given arguments\n\t\t\tfire: function() {\n\t\t\t\tself.fireWith( this, arguments );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// To know if the callbacks have already been called at least once\n\t\t\tfired: function() {\n\t\t\t\treturn !!fired;\n\t\t\t}\n\t\t};\n\n\treturn self;\n};\n\n\nfunction Identity( v ) {\n\treturn v;\n}\nfunction Thrower( ex ) {\n\tthrow ex;\n}\n\nfunction adoptValue( value, resolve, reject, noValue ) {\n\tvar method;\n\n\ttry {\n\n\t\t// Check for promise aspect first to privilege synchronous behavior\n\t\tif ( value && isFunction( ( method = value.promise ) ) ) {\n\t\t\tmethod.call( value ).done( resolve ).fail( reject );\n\n\t\t// Other thenables\n\t\t} else if ( value && isFunction( ( method = value.then ) ) ) {\n\t\t\tmethod.call( value, resolve, reject );\n\n\t\t// Other non-thenables\n\t\t} else {\n\n\t\t\t// Control `resolve` arguments by letting Array#slice cast boolean `noValue` to integer:\n\t\t\t// * false: [ value ].slice( 0 ) => resolve( value )\n\t\t\t// * true: [ value ].slice( 1 ) => resolve()\n\t\t\tresolve.apply( undefined, [ value ].slice( noValue ) );\n\t\t}\n\n\t// For Promises/A+, convert exceptions into rejections\n\t// Since jQuery.when doesn't unwrap thenables, we can skip the extra checks appearing in\n\t// Deferred#then to conditionally suppress rejection.\n\t} catch ( value ) {\n\n\t\t// Support: Android 4.0 only\n\t\t// Strict mode functions invoked without .call/.apply get global-object context\n\t\treject.apply( undefined, [ value ] );\n\t}\n}\n\njQuery.extend( {\n\n\tDeferred: function( func ) {\n\t\tvar tuples = [\n\n\t\t\t\t// action, add listener, callbacks,\n\t\t\t\t// ... .then handlers, argument index, [final state]\n\t\t\t\t[ \"notify\", \"progress\", jQuery.Callbacks( \"memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"memory\" ), 2 ],\n\t\t\t\t[ \"resolve\", \"done\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 0, \"resolved\" ],\n\t\t\t\t[ \"reject\", \"fail\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 1, \"rejected\" ]\n\t\t\t],\n\t\t\tstate = \"pending\",\n\t\t\tpromise = {\n\t\t\t\tstate: function() {\n\t\t\t\t\treturn state;\n\t\t\t\t},\n\t\t\t\talways: function() {\n\t\t\t\t\tdeferred.done( arguments ).fail( arguments );\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\t\t\t\t\"catch\": function( fn ) {\n\t\t\t\t\treturn promise.then( null, fn );\n\t\t\t\t},\n\n\t\t\t\t// Keep pipe for back-compat\n\t\t\t\tpipe: function( /* fnDone, fnFail, fnProgress */ ) {\n\t\t\t\t\tvar fns = arguments;\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\t\t\t\t\t\tjQuery.each( tuples, function( i, tuple ) {\n\n\t\t\t\t\t\t\t// Map tuples (progress, done, fail) to arguments (done, fail, progress)\n\t\t\t\t\t\t\tvar fn = isFunction( fns[ tuple[ 4 ] ] ) && fns[ tuple[ 4 ] ];\n\n\t\t\t\t\t\t\t// deferred.progress(function() { bind to newDefer or newDefer.notify })\n\t\t\t\t\t\t\t// deferred.done(function() { bind to newDefer or newDefer.resolve })\n\t\t\t\t\t\t\t// deferred.fail(function() { bind to newDefer or newDefer.reject })\n\t\t\t\t\t\t\tdeferred[ tuple[ 1 ] ]( function() {\n\t\t\t\t\t\t\t\tvar returned = fn && fn.apply( this, arguments );\n\t\t\t\t\t\t\t\tif ( returned && isFunction( returned.promise ) ) {\n\t\t\t\t\t\t\t\t\treturned.promise()\n\t\t\t\t\t\t\t\t\t\t.progress( newDefer.notify )\n\t\t\t\t\t\t\t\t\t\t.done( newDefer.resolve )\n\t\t\t\t\t\t\t\t\t\t.fail( newDefer.reject );\n\t\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\t\tnewDefer[ tuple[ 0 ] + \"With\" ](\n\t\t\t\t\t\t\t\t\t\tthis,\n\t\t\t\t\t\t\t\t\t\tfn ? [ returned ] : arguments\n\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t} );\n\t\t\t\t\t\tfns = null;\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\t\t\t\tthen: function( onFulfilled, onRejected, onProgress ) {\n\t\t\t\t\tvar maxDepth = 0;\n\t\t\t\t\tfunction resolve( depth, deferred, handler, special ) {\n\t\t\t\t\t\treturn function() {\n\t\t\t\t\t\t\tvar that = this,\n\t\t\t\t\t\t\t\targs = arguments,\n\t\t\t\t\t\t\t\tmightThrow = function() {\n\t\t\t\t\t\t\t\t\tvar returned, then;\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.3\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-59\n\t\t\t\t\t\t\t\t\t// Ignore double-resolution attempts\n\t\t\t\t\t\t\t\t\tif ( depth < maxDepth ) {\n\t\t\t\t\t\t\t\t\t\treturn;\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\treturned = handler.apply( that, args );\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.1\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-48\n\t\t\t\t\t\t\t\t\tif ( returned === deferred.promise() ) {\n\t\t\t\t\t\t\t\t\t\tthrow new TypeError( \"Thenable self-resolution\" );\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ sections 2.3.3.1, 3.5\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-54\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-75\n\t\t\t\t\t\t\t\t\t// Retrieve `then` only once\n\t\t\t\t\t\t\t\t\tthen = returned &&\n\n\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.4\n\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-64\n\t\t\t\t\t\t\t\t\t\t// Only check objects and functions for thenability\n\t\t\t\t\t\t\t\t\t\t( typeof returned === \"object\" ||\n\t\t\t\t\t\t\t\t\t\t\ttypeof returned === \"function\" ) &&\n\t\t\t\t\t\t\t\t\t\treturned.then;\n\n\t\t\t\t\t\t\t\t\t// Handle a returned thenable\n\t\t\t\t\t\t\t\t\tif ( isFunction( then ) ) {\n\n\t\t\t\t\t\t\t\t\t\t// Special processors (notify) just wait for resolution\n\t\t\t\t\t\t\t\t\t\tif ( special ) {\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special )\n\t\t\t\t\t\t\t\t\t\t\t);\n\n\t\t\t\t\t\t\t\t\t\t// Normal processors (resolve) also hook into progress\n\t\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t\t// ...and disregard older resolution values\n\t\t\t\t\t\t\t\t\t\t\tmaxDepth++;\n\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity,\n\t\t\t\t\t\t\t\t\t\t\t\t\tdeferred.notifyWith )\n\t\t\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Handle all other returned values\n\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\tif ( handler !== Identity ) {\n\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\targs = [ returned ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t// Process the value(s)\n\t\t\t\t\t\t\t\t\t\t// Default process is resolve\n\t\t\t\t\t\t\t\t\t\t( special || deferred.resolveWith )( that, args );\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t},\n\n\t\t\t\t\t\t\t\t// Only normal processors (resolve) catch and reject exceptions\n\t\t\t\t\t\t\t\tprocess = special ?\n\t\t\t\t\t\t\t\t\tmightThrow :\n\t\t\t\t\t\t\t\t\tfunction() {\n\t\t\t\t\t\t\t\t\t\ttry {\n\t\t\t\t\t\t\t\t\t\t\tmightThrow();\n\t\t\t\t\t\t\t\t\t\t} catch ( e ) {\n\n\t\t\t\t\t\t\t\t\t\t\tif ( jQuery.Deferred.exceptionHook ) {\n\t\t\t\t\t\t\t\t\t\t\t\tjQuery.Deferred.exceptionHook( e,\n\t\t\t\t\t\t\t\t\t\t\t\t\tprocess.stackTrace );\n\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.4.1\n\t\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-61\n\t\t\t\t\t\t\t\t\t\t\t// Ignore post-resolution exceptions\n\t\t\t\t\t\t\t\t\t\t\tif ( depth + 1 >= maxDepth ) {\n\n\t\t\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\t\t\tif ( handler !== Thrower ) {\n\t\t\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\t\t\targs = [ e ];\n\t\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t\tdeferred.rejectWith( that, args );\n\t\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t};\n\n\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.1\n\t\t\t\t\t\t\t// https://promisesaplus.com/#point-57\n\t\t\t\t\t\t\t// Re-resolve promises immediately to dodge false rejection from\n\t\t\t\t\t\t\t// subsequent errors\n\t\t\t\t\t\t\tif ( depth ) {\n\t\t\t\t\t\t\t\tprocess();\n\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t// Call an optional hook to record the stack, in case of exception\n\t\t\t\t\t\t\t\t// since it's otherwise lost when execution goes async\n\t\t\t\t\t\t\t\tif ( jQuery.Deferred.getStackHook ) {\n\t\t\t\t\t\t\t\t\tprocess.stackTrace = jQuery.Deferred.getStackHook();\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\twindow.setTimeout( process );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t};\n\t\t\t\t\t}\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\n\t\t\t\t\t\t// progress_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 0 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onProgress ) ?\n\t\t\t\t\t\t\t\t\tonProgress :\n\t\t\t\t\t\t\t\t\tIdentity,\n\t\t\t\t\t\t\t\tnewDefer.notifyWith\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// fulfilled_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 1 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onFulfilled ) ?\n\t\t\t\t\t\t\t\t\tonFulfilled :\n\t\t\t\t\t\t\t\t\tIdentity\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// rejected_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 2 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onRejected ) ?\n\t\t\t\t\t\t\t\t\tonRejected :\n\t\t\t\t\t\t\t\t\tThrower\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\n\t\t\t\t// Get a promise for this deferred\n\t\t\t\t// If obj is provided, the promise aspect is added to the object\n\t\t\t\tpromise: function( obj ) {\n\t\t\t\t\treturn obj != null ? jQuery.extend( obj, promise ) : promise;\n\t\t\t\t}\n\t\t\t},\n\t\t\tdeferred = {};\n\n\t\t// Add list-specific methods\n\t\tjQuery.each( tuples, function( i, tuple ) {\n\t\t\tvar list = tuple[ 2 ],\n\t\t\t\tstateString = tuple[ 5 ];\n\n\t\t\t// promise.progress = list.add\n\t\t\t// promise.done = list.add\n\t\t\t// promise.fail = list.add\n\t\t\tpromise[ tuple[ 1 ] ] = list.add;\n\n\t\t\t// Handle state\n\t\t\tif ( stateString ) {\n\t\t\t\tlist.add(\n\t\t\t\t\tfunction() {\n\n\t\t\t\t\t\t// state = \"resolved\" (i.e., fulfilled)\n\t\t\t\t\t\t// state = \"rejected\"\n\t\t\t\t\t\tstate = stateString;\n\t\t\t\t\t},\n\n\t\t\t\t\t// rejected_callbacks.disable\n\t\t\t\t\t// fulfilled_callbacks.disable\n\t\t\t\t\ttuples[ 3 - i ][ 2 ].disable,\n\n\t\t\t\t\t// rejected_handlers.disable\n\t\t\t\t\t// fulfilled_handlers.disable\n\t\t\t\t\ttuples[ 3 - i ][ 3 ].disable,\n\n\t\t\t\t\t// progress_callbacks.lock\n\t\t\t\t\ttuples[ 0 ][ 2 ].lock,\n\n\t\t\t\t\t// progress_handlers.lock\n\t\t\t\t\ttuples[ 0 ][ 3 ].lock\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// progress_handlers.fire\n\t\t\t// fulfilled_handlers.fire\n\t\t\t// rejected_handlers.fire\n\t\t\tlist.add( tuple[ 3 ].fire );\n\n\t\t\t// deferred.notify = function() { deferred.notifyWith(...) }\n\t\t\t// deferred.resolve = function() { deferred.resolveWith(...) }\n\t\t\t// deferred.reject = function() { deferred.rejectWith(...) }\n\t\t\tdeferred[ tuple[ 0 ] ] = function() {\n\t\t\t\tdeferred[ tuple[ 0 ] + \"With\" ]( this === deferred ? undefined : this, arguments );\n\t\t\t\treturn this;\n\t\t\t};\n\n\t\t\t// deferred.notifyWith = list.fireWith\n\t\t\t// deferred.resolveWith = list.fireWith\n\t\t\t// deferred.rejectWith = list.fireWith\n\t\t\tdeferred[ tuple[ 0 ] + \"With\" ] = list.fireWith;\n\t\t} );\n\n\t\t// Make the deferred a promise\n\t\tpromise.promise( deferred );\n\n\t\t// Call given func if any\n\t\tif ( func ) {\n\t\t\tfunc.call( deferred, deferred );\n\t\t}\n\n\t\t// All done!\n\t\treturn deferred;\n\t},\n\n\t// Deferred helper\n\twhen: function( singleValue ) {\n\t\tvar\n\n\t\t\t// count of uncompleted subordinates\n\t\t\tremaining = arguments.length,\n\n\t\t\t// count of unprocessed arguments\n\t\t\ti = remaining,\n\n\t\t\t// subordinate fulfillment data\n\t\t\tresolveContexts = Array( i ),\n\t\t\tresolveValues = slice.call( arguments ),\n\n\t\t\t// the master Deferred\n\t\t\tmaster = jQuery.Deferred(),\n\n\t\t\t// subordinate callback factory\n\t\t\tupdateFunc = function( i ) {\n\t\t\t\treturn function( value ) {\n\t\t\t\t\tresolveContexts[ i ] = this;\n\t\t\t\t\tresolveValues[ i ] = arguments.length > 1 ? slice.call( arguments ) : value;\n\t\t\t\t\tif ( !( --remaining ) ) {\n\t\t\t\t\t\tmaster.resolveWith( resolveContexts, resolveValues );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t\t};\n\n\t\t// Single- and empty arguments are adopted like Promise.resolve\n\t\tif ( remaining <= 1 ) {\n\t\t\tadoptValue( singleValue, master.done( updateFunc( i ) ).resolve, master.reject,\n\t\t\t\t!remaining );\n\n\t\t\t// Use .then() to unwrap secondary thenables (cf. gh-3000)\n\t\t\tif ( master.state() === \"pending\" ||\n\t\t\t\tisFunction( resolveValues[ i ] && resolveValues[ i ].then ) ) {\n\n\t\t\t\treturn master.then();\n\t\t\t}\n\t\t}\n\n\t\t// Multiple arguments are aggregated like Promise.all array elements\n\t\twhile ( i-- ) {\n\t\t\tadoptValue( resolveValues[ i ], updateFunc( i ), master.reject );\n\t\t}\n\n\t\treturn master.promise();\n\t}\n} );\n\n\n// These usually indicate a programmer mistake during development,\n// warn about them ASAP rather than swallowing them by default.\nvar rerrorNames = /^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/;\n\njQuery.Deferred.exceptionHook = function( error, stack ) {\n\n\t// Support: IE 8 - 9 only\n\t// Console exists when dev tools are open, which can happen at any time\n\tif ( window.console && window.console.warn && error && rerrorNames.test( error.name ) ) {\n\t\twindow.console.warn( \"jQuery.Deferred exception: \" + error.message, error.stack, stack );\n\t}\n};\n\n\n\n\njQuery.readyException = function( error ) {\n\twindow.setTimeout( function() {\n\t\tthrow error;\n\t} );\n};\n\n\n\n\n// The deferred used on DOM ready\nvar readyList = jQuery.Deferred();\n\njQuery.fn.ready = function( fn ) {\n\n\treadyList\n\t\t.then( fn )\n\n\t\t// Wrap jQuery.readyException in a function so that the lookup\n\t\t// happens at the time of error handling instead of callback\n\t\t// registration.\n\t\t.catch( function( error ) {\n\t\t\tjQuery.readyException( error );\n\t\t} );\n\n\treturn this;\n};\n\njQuery.extend( {\n\n\t// Is the DOM ready to be used? Set to true once it occurs.\n\tisReady: false,\n\n\t// A counter to track how many items to wait for before\n\t// the ready event fires. See #6781\n\treadyWait: 1,\n\n\t// Handle when the DOM is ready\n\tready: function( wait ) {\n\n\t\t// Abort if there are pending holds or we're already ready\n\t\tif ( wait === true ? --jQuery.readyWait : jQuery.isReady ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Remember that the DOM is ready\n\t\tjQuery.isReady = true;\n\n\t\t// If a normal DOM Ready event fired, decrement, and wait if need be\n\t\tif ( wait !== true && --jQuery.readyWait > 0 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// If there are functions bound, to execute\n\t\treadyList.resolveWith( document, [ jQuery ] );\n\t}\n} );\n\njQuery.ready.then = readyList.then;\n\n// The ready event handler and self cleanup method\nfunction completed() {\n\tdocument.removeEventListener( \"DOMContentLoaded\", completed );\n\twindow.removeEventListener( \"load\", completed );\n\tjQuery.ready();\n}\n\n// Catch cases where $(document).ready() is called\n// after the browser event has already occurred.\n// Support: IE <=9 - 10 only\n// Older IE sometimes signals \"interactive\" too soon\nif ( document.readyState === \"complete\" ||\n\t( document.readyState !== \"loading\" && !document.documentElement.doScroll ) ) {\n\n\t// Handle it asynchronously to allow scripts the opportunity to delay ready\n\twindow.setTimeout( jQuery.ready );\n\n} else {\n\n\t// Use the handy event callback\n\tdocument.addEventListener( \"DOMContentLoaded\", completed );\n\n\t// A fallback to window.onload, that will always work\n\twindow.addEventListener( \"load\", completed );\n}\n\n\n\n\n// Multifunctional method to get and set values of a collection\n// The value/s can optionally be executed if it's a function\nvar access = function( elems, fn, key, value, chainable, emptyGet, raw ) {\n\tvar i = 0,\n\t\tlen = elems.length,\n\t\tbulk = key == null;\n\n\t// Sets many values\n\tif ( toType( key ) === \"object\" ) {\n\t\tchainable = true;\n\t\tfor ( i in key ) {\n\t\t\taccess( elems, fn, i, key[ i ], true, emptyGet, raw );\n\t\t}\n\n\t// Sets one value\n\t} else if ( value !== undefined ) {\n\t\tchainable = true;\n\n\t\tif ( !isFunction( value ) ) {\n\t\t\traw = true;\n\t\t}\n\n\t\tif ( bulk ) {\n\n\t\t\t// Bulk operations run against the entire set\n\t\t\tif ( raw ) {\n\t\t\t\tfn.call( elems, value );\n\t\t\t\tfn = null;\n\n\t\t\t// ...except when executing function values\n\t\t\t} else {\n\t\t\t\tbulk = fn;\n\t\t\t\tfn = function( elem, key, value ) {\n\t\t\t\t\treturn bulk.call( jQuery( elem ), value );\n\t\t\t\t};\n\t\t\t}\n\t\t}\n\n\t\tif ( fn ) {\n\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\tfn(\n\t\t\t\t\telems[ i ], key, raw ?\n\t\t\t\t\tvalue :\n\t\t\t\t\tvalue.call( elems[ i ], i, fn( elems[ i ], key ) )\n\t\t\t\t);\n\t\t\t}\n\t\t}\n\t}\n\n\tif ( chainable ) {\n\t\treturn elems;\n\t}\n\n\t// Gets\n\tif ( bulk ) {\n\t\treturn fn.call( elems );\n\t}\n\n\treturn len ? fn( elems[ 0 ], key ) : emptyGet;\n};\n\n\n// Matches dashed string for camelizing\nvar rmsPrefix = /^-ms-/,\n\trdashAlpha = /-([a-z])/g;\n\n// Used by camelCase as callback to replace()\nfunction fcamelCase( all, letter ) {\n\treturn letter.toUpperCase();\n}\n\n// Convert dashed to camelCase; used by the css and data modules\n// Support: IE <=9 - 11, Edge 12 - 15\n// Microsoft forgot to hump their vendor prefix (#9572)\nfunction camelCase( string ) {\n\treturn string.replace( rmsPrefix, \"ms-\" ).replace( rdashAlpha, fcamelCase );\n}\nvar acceptData = function( owner ) {\n\n\t// Accepts only:\n\t//  - Node\n\t//    - Node.ELEMENT_NODE\n\t//    - Node.DOCUMENT_NODE\n\t//  - Object\n\t//    - Any\n\treturn owner.nodeType === 1 || owner.nodeType === 9 || !( +owner.nodeType );\n};\n\n\n\n\nfunction Data() {\n\tthis.expando = jQuery.expando + Data.uid++;\n}\n\nData.uid = 1;\n\nData.prototype = {\n\n\tcache: function( owner ) {\n\n\t\t// Check if the owner object already has a cache\n\t\tvar value = owner[ this.expando ];\n\n\t\t// If not, create one\n\t\tif ( !value ) {\n\t\t\tvalue = {};\n\n\t\t\t// We can accept data for non-element nodes in modern browsers,\n\t\t\t// but we should not, see #8335.\n\t\t\t// Always return an empty object.\n\t\t\tif ( acceptData( owner ) ) {\n\n\t\t\t\t// If it is a node unlikely to be stringify-ed or looped over\n\t\t\t\t// use plain assignment\n\t\t\t\tif ( owner.nodeType ) {\n\t\t\t\t\towner[ this.expando ] = value;\n\n\t\t\t\t// Otherwise secure it in a non-enumerable property\n\t\t\t\t// configurable must be true to allow the property to be\n\t\t\t\t// deleted when data is removed\n\t\t\t\t} else {\n\t\t\t\t\tObject.defineProperty( owner, this.expando, {\n\t\t\t\t\t\tvalue: value,\n\t\t\t\t\t\tconfigurable: true\n\t\t\t\t\t} );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn value;\n\t},\n\tset: function( owner, data, value ) {\n\t\tvar prop,\n\t\t\tcache = this.cache( owner );\n\n\t\t// Handle: [ owner, key, value ] args\n\t\t// Always use camelCase key (gh-2257)\n\t\tif ( typeof data === \"string\" ) {\n\t\t\tcache[ camelCase( data ) ] = value;\n\n\t\t// Handle: [ owner, { properties } ] args\n\t\t} else {\n\n\t\t\t// Copy the properties one-by-one to the cache object\n\t\t\tfor ( prop in data ) {\n\t\t\t\tcache[ camelCase( prop ) ] = data[ prop ];\n\t\t\t}\n\t\t}\n\t\treturn cache;\n\t},\n\tget: function( owner, key ) {\n\t\treturn key === undefined ?\n\t\t\tthis.cache( owner ) :\n\n\t\t\t// Always use camelCase key (gh-2257)\n\t\t\towner[ this.expando ] && owner[ this.expando ][ camelCase( key ) ];\n\t},\n\taccess: function( owner, key, value ) {\n\n\t\t// In cases where either:\n\t\t//\n\t\t//   1. No key was specified\n\t\t//   2. A string key was specified, but no value provided\n\t\t//\n\t\t// Take the \"read\" path and allow the get method to determine\n\t\t// which value to return, respectively either:\n\t\t//\n\t\t//   1. The entire cache object\n\t\t//   2. The data stored at the key\n\t\t//\n\t\tif ( key === undefined ||\n\t\t\t\t( ( key && typeof key === \"string\" ) && value === undefined ) ) {\n\n\t\t\treturn this.get( owner, key );\n\t\t}\n\n\t\t// When the key is not a string, or both a key and value\n\t\t// are specified, set or extend (existing objects) with either:\n\t\t//\n\t\t//   1. An object of properties\n\t\t//   2. A key and value\n\t\t//\n\t\tthis.set( owner, key, value );\n\n\t\t// Since the \"set\" path can have two possible entry points\n\t\t// return the expected data based on which path was taken[*]\n\t\treturn value !== undefined ? value : key;\n\t},\n\tremove: function( owner, key ) {\n\t\tvar i,\n\t\t\tcache = owner[ this.expando ];\n\n\t\tif ( cache === undefined ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( key !== undefined ) {\n\n\t\t\t// Support array or space separated string of keys\n\t\t\tif ( Array.isArray( key ) ) {\n\n\t\t\t\t// If key is an array of keys...\n\t\t\t\t// We always set camelCase keys, so remove that.\n\t\t\t\tkey = key.map( camelCase );\n\t\t\t} else {\n\t\t\t\tkey = camelCase( key );\n\n\t\t\t\t// If a key with the spaces exists, use it.\n\t\t\t\t// Otherwise, create an array by matching non-whitespace\n\t\t\t\tkey = key in cache ?\n\t\t\t\t\t[ key ] :\n\t\t\t\t\t( key.match( rnothtmlwhite ) || [] );\n\t\t\t}\n\n\t\t\ti = key.length;\n\n\t\t\twhile ( i-- ) {\n\t\t\t\tdelete cache[ key[ i ] ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove the expando if there's no more data\n\t\tif ( key === undefined || jQuery.isEmptyObject( cache ) ) {\n\n\t\t\t// Support: Chrome <=35 - 45\n\t\t\t// Webkit & Blink performance suffers when deleting properties\n\t\t\t// from DOM nodes, so set to undefined instead\n\t\t\t// https://bugs.chromium.org/p/chromium/issues/detail?id=378607 (bug restricted)\n\t\t\tif ( owner.nodeType ) {\n\t\t\t\towner[ this.expando ] = undefined;\n\t\t\t} else {\n\t\t\t\tdelete owner[ this.expando ];\n\t\t\t}\n\t\t}\n\t},\n\thasData: function( owner ) {\n\t\tvar cache = owner[ this.expando ];\n\t\treturn cache !== undefined && !jQuery.isEmptyObject( cache );\n\t}\n};\nvar dataPriv = new Data();\n\nvar dataUser = new Data();\n\n\n\n//\tImplementation Summary\n//\n//\t1. Enforce API surface and semantic compatibility with 1.9.x branch\n//\t2. Improve the module's maintainability by reducing the storage\n//\t\tpaths to a single mechanism.\n//\t3. Use the same single mechanism to support \"private\" and \"user\" data.\n//\t4. _Never_ expose \"private\" data to user code (TODO: Drop _data, _removeData)\n//\t5. Avoid exposing implementation details on user objects (eg. expando properties)\n//\t6. Provide a clear path for implementation upgrade to WeakMap in 2014\n\nvar rbrace = /^(?:\\{[\\w\\W]*\\}|\\[[\\w\\W]*\\])$/,\n\trmultiDash = /[A-Z]/g;\n\nfunction getData( data ) {\n\tif ( data === \"true\" ) {\n\t\treturn true;\n\t}\n\n\tif ( data === \"false\" ) {\n\t\treturn false;\n\t}\n\n\tif ( data === \"null\" ) {\n\t\treturn null;\n\t}\n\n\t// Only convert to a number if it doesn't change the string\n\tif ( data === +data + \"\" ) {\n\t\treturn +data;\n\t}\n\n\tif ( rbrace.test( data ) ) {\n\t\treturn JSON.parse( data );\n\t}\n\n\treturn data;\n}\n\nfunction dataAttr( elem, key, data ) {\n\tvar name;\n\n\t// If nothing was found internally, try to fetch any\n\t// data from the HTML5 data-* attribute\n\tif ( data === undefined && elem.nodeType === 1 ) {\n\t\tname = \"data-\" + key.replace( rmultiDash, \"-$&\" ).toLowerCase();\n\t\tdata = elem.getAttribute( name );\n\n\t\tif ( typeof data === \"string\" ) {\n\t\t\ttry {\n\t\t\t\tdata = getData( data );\n\t\t\t} catch ( e ) {}\n\n\t\t\t// Make sure we set the data so it isn't changed later\n\t\t\tdataUser.set( elem, key, data );\n\t\t} else {\n\t\t\tdata = undefined;\n\t\t}\n\t}\n\treturn data;\n}\n\njQuery.extend( {\n\thasData: function( elem ) {\n\t\treturn dataUser.hasData( elem ) || dataPriv.hasData( elem );\n\t},\n\n\tdata: function( elem, name, data ) {\n\t\treturn dataUser.access( elem, name, data );\n\t},\n\n\tremoveData: function( elem, name ) {\n\t\tdataUser.remove( elem, name );\n\t},\n\n\t// TODO: Now that all calls to _data and _removeData have been replaced\n\t// with direct calls to dataPriv methods, these can be deprecated.\n\t_data: function( elem, name, data ) {\n\t\treturn dataPriv.access( elem, name, data );\n\t},\n\n\t_removeData: function( elem, name ) {\n\t\tdataPriv.remove( elem, name );\n\t}\n} );\n\njQuery.fn.extend( {\n\tdata: function( key, value ) {\n\t\tvar i, name, data,\n\t\t\telem = this[ 0 ],\n\t\t\tattrs = elem && elem.attributes;\n\n\t\t// Gets all values\n\t\tif ( key === undefined ) {\n\t\t\tif ( this.length ) {\n\t\t\t\tdata = dataUser.get( elem );\n\n\t\t\t\tif ( elem.nodeType === 1 && !dataPriv.get( elem, \"hasDataAttrs\" ) ) {\n\t\t\t\t\ti = attrs.length;\n\t\t\t\t\twhile ( i-- ) {\n\n\t\t\t\t\t\t// Support: IE 11 only\n\t\t\t\t\t\t// The attrs elements can be null (#14894)\n\t\t\t\t\t\tif ( attrs[ i ] ) {\n\t\t\t\t\t\t\tname = attrs[ i ].name;\n\t\t\t\t\t\t\tif ( name.indexOf( \"data-\" ) === 0 ) {\n\t\t\t\t\t\t\t\tname = camelCase( name.slice( 5 ) );\n\t\t\t\t\t\t\t\tdataAttr( elem, name, data[ name ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tdataPriv.set( elem, \"hasDataAttrs\", true );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\treturn data;\n\t\t}\n\n\t\t// Sets multiple values\n\t\tif ( typeof key === \"object\" ) {\n\t\t\treturn this.each( function() {\n\t\t\t\tdataUser.set( this, key );\n\t\t\t} );\n\t\t}\n\n\t\treturn access( this, function( value ) {\n\t\t\tvar data;\n\n\t\t\t// The calling jQuery object (element matches) is not empty\n\t\t\t// (and therefore has an element appears at this[ 0 ]) and the\n\t\t\t// `value` parameter was not undefined. An empty jQuery object\n\t\t\t// will result in `undefined` for elem = this[ 0 ] which will\n\t\t\t// throw an exception if an attempt to read a data cache is made.\n\t\t\tif ( elem && value === undefined ) {\n\n\t\t\t\t// Attempt to get data from the cache\n\t\t\t\t// The key will always be camelCased in Data\n\t\t\t\tdata = dataUser.get( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// Attempt to \"discover\" the data in\n\t\t\t\t// HTML5 custom data-* attrs\n\t\t\t\tdata = dataAttr( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// We tried really hard, but the data doesn't exist.\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Set the data...\n\t\t\tthis.each( function() {\n\n\t\t\t\t// We always store the camelCased key\n\t\t\t\tdataUser.set( this, key, value );\n\t\t\t} );\n\t\t}, null, value, arguments.length > 1, null, true );\n\t},\n\n\tremoveData: function( key ) {\n\t\treturn this.each( function() {\n\t\t\tdataUser.remove( this, key );\n\t\t} );\n\t}\n} );\n\n\njQuery.extend( {\n\tqueue: function( elem, type, data ) {\n\t\tvar queue;\n\n\t\tif ( elem ) {\n\t\t\ttype = ( type || \"fx\" ) + \"queue\";\n\t\t\tqueue = dataPriv.get( elem, type );\n\n\t\t\t// Speed up dequeue by getting out quickly if this is just a lookup\n\t\t\tif ( data ) {\n\t\t\t\tif ( !queue || Array.isArray( data ) ) {\n\t\t\t\t\tqueue = dataPriv.access( elem, type, jQuery.makeArray( data ) );\n\t\t\t\t} else {\n\t\t\t\t\tqueue.push( data );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn queue || [];\n\t\t}\n\t},\n\n\tdequeue: function( elem, type ) {\n\t\ttype = type || \"fx\";\n\n\t\tvar queue = jQuery.queue( elem, type ),\n\t\t\tstartLength = queue.length,\n\t\t\tfn = queue.shift(),\n\t\t\thooks = jQuery._queueHooks( elem, type ),\n\t\t\tnext = function() {\n\t\t\t\tjQuery.dequeue( elem, type );\n\t\t\t};\n\n\t\t// If the fx queue is dequeued, always remove the progress sentinel\n\t\tif ( fn === \"inprogress\" ) {\n\t\t\tfn = queue.shift();\n\t\t\tstartLength--;\n\t\t}\n\n\t\tif ( fn ) {\n\n\t\t\t// Add a progress sentinel to prevent the fx queue from being\n\t\t\t// automatically dequeued\n\t\t\tif ( type === \"fx\" ) {\n\t\t\t\tqueue.unshift( \"inprogress\" );\n\t\t\t}\n\n\t\t\t// Clear up the last queue stop function\n\t\t\tdelete hooks.stop;\n\t\t\tfn.call( elem, next, hooks );\n\t\t}\n\n\t\tif ( !startLength && hooks ) {\n\t\t\thooks.empty.fire();\n\t\t}\n\t},\n\n\t// Not public - generate a queueHooks object, or return the current one\n\t_queueHooks: function( elem, type ) {\n\t\tvar key = type + \"queueHooks\";\n\t\treturn dataPriv.get( elem, key ) || dataPriv.access( elem, key, {\n\t\t\tempty: jQuery.Callbacks( \"once memory\" ).add( function() {\n\t\t\t\tdataPriv.remove( elem, [ type + \"queue\", key ] );\n\t\t\t} )\n\t\t} );\n\t}\n} );\n\njQuery.fn.extend( {\n\tqueue: function( type, data ) {\n\t\tvar setter = 2;\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tdata = type;\n\t\t\ttype = \"fx\";\n\t\t\tsetter--;\n\t\t}\n\n\t\tif ( arguments.length < setter ) {\n\t\t\treturn jQuery.queue( this[ 0 ], type );\n\t\t}\n\n\t\treturn data === undefined ?\n\t\t\tthis :\n\t\t\tthis.each( function() {\n\t\t\t\tvar queue = jQuery.queue( this, type, data );\n\n\t\t\t\t// Ensure a hooks for this queue\n\t\t\t\tjQuery._queueHooks( this, type );\n\n\t\t\t\tif ( type === \"fx\" && queue[ 0 ] !== \"inprogress\" ) {\n\t\t\t\t\tjQuery.dequeue( this, type );\n\t\t\t\t}\n\t\t\t} );\n\t},\n\tdequeue: function( type ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.dequeue( this, type );\n\t\t} );\n\t},\n\tclearQueue: function( type ) {\n\t\treturn this.queue( type || \"fx\", [] );\n\t},\n\n\t// Get a promise resolved when queues of a certain type\n\t// are emptied (fx is the type by default)\n\tpromise: function( type, obj ) {\n\t\tvar tmp,\n\t\t\tcount = 1,\n\t\t\tdefer = jQuery.Deferred(),\n\t\t\telements = this,\n\t\t\ti = this.length,\n\t\t\tresolve = function() {\n\t\t\t\tif ( !( --count ) ) {\n\t\t\t\t\tdefer.resolveWith( elements, [ elements ] );\n\t\t\t\t}\n\t\t\t};\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tobj = type;\n\t\t\ttype = undefined;\n\t\t}\n\t\ttype = type || \"fx\";\n\n\t\twhile ( i-- ) {\n\t\t\ttmp = dataPriv.get( elements[ i ], type + \"queueHooks\" );\n\t\t\tif ( tmp && tmp.empty ) {\n\t\t\t\tcount++;\n\t\t\t\ttmp.empty.add( resolve );\n\t\t\t}\n\t\t}\n\t\tresolve();\n\t\treturn defer.promise( obj );\n\t}\n} );\nvar pnum = ( /[+-]?(?:\\d*\\.|)\\d+(?:[eE][+-]?\\d+|)/ ).source;\n\nvar rcssNum = new RegExp( \"^(?:([+-])=|)(\" + pnum + \")([a-z%]*)$\", \"i\" );\n\n\nvar cssExpand = [ \"Top\", \"Right\", \"Bottom\", \"Left\" ];\n\nvar documentElement = document.documentElement;\n\n\n\n\tvar isAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem );\n\t\t},\n\t\tcomposed = { composed: true };\n\n\t// Support: IE 9 - 11+, Edge 12 - 18+, iOS 10.0 - 10.2 only\n\t// Check attachment across shadow DOM boundaries when possible (gh-3504)\n\t// Support: iOS 10.0-10.2 only\n\t// Early iOS 10 versions support `attachShadow` but not `getRootNode`,\n\t// leading to errors. We need to check for `getRootNode`.\n\tif ( documentElement.getRootNode ) {\n\t\tisAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem ) ||\n\t\t\t\telem.getRootNode( composed ) === elem.ownerDocument;\n\t\t};\n\t}\nvar isHiddenWithinTree = function( elem, el ) {\n\n\t\t// isHiddenWithinTree might be called from jQuery#filter function;\n\t\t// in that case, element will be second argument\n\t\telem = el || elem;\n\n\t\t// Inline style trumps all\n\t\treturn elem.style.display === \"none\" ||\n\t\t\telem.style.display === \"\" &&\n\n\t\t\t// Otherwise, check computed style\n\t\t\t// Support: Firefox <=43 - 45\n\t\t\t// Disconnected elements can have computed display: none, so first confirm that elem is\n\t\t\t// in the document.\n\t\t\tisAttached( elem ) &&\n\n\t\t\tjQuery.css( elem, \"display\" ) === \"none\";\n\t};\n\nvar swap = function( elem, options, callback, args ) {\n\tvar ret, name,\n\t\told = {};\n\n\t// Remember the old values, and insert the new ones\n\tfor ( name in options ) {\n\t\told[ name ] = elem.style[ name ];\n\t\telem.style[ name ] = options[ name ];\n\t}\n\n\tret = callback.apply( elem, args || [] );\n\n\t// Revert the old values\n\tfor ( name in options ) {\n\t\telem.style[ name ] = old[ name ];\n\t}\n\n\treturn ret;\n};\n\n\n\n\nfunction adjustCSS( elem, prop, valueParts, tween ) {\n\tvar adjusted, scale,\n\t\tmaxIterations = 20,\n\t\tcurrentValue = tween ?\n\t\t\tfunction() {\n\t\t\t\treturn tween.cur();\n\t\t\t} :\n\t\t\tfunction() {\n\t\t\t\treturn jQuery.css( elem, prop, \"\" );\n\t\t\t},\n\t\tinitial = currentValue(),\n\t\tunit = valueParts && valueParts[ 3 ] || ( jQuery.cssNumber[ prop ] ? \"\" : \"px\" ),\n\n\t\t// Starting value computation is required for potential unit mismatches\n\t\tinitialInUnit = elem.nodeType &&\n\t\t\t( jQuery.cssNumber[ prop ] || unit !== \"px\" && +initial ) &&\n\t\t\trcssNum.exec( jQuery.css( elem, prop ) );\n\n\tif ( initialInUnit && initialInUnit[ 3 ] !== unit ) {\n\n\t\t// Support: Firefox <=54\n\t\t// Halve the iteration target value to prevent interference from CSS upper bounds (gh-2144)\n\t\tinitial = initial / 2;\n\n\t\t// Trust units reported by jQuery.css\n\t\tunit = unit || initialInUnit[ 3 ];\n\n\t\t// Iteratively approximate from a nonzero starting point\n\t\tinitialInUnit = +initial || 1;\n\n\t\twhile ( maxIterations-- ) {\n\n\t\t\t// Evaluate and update our best guess (doubling guesses that zero out).\n\t\t\t// Finish if the scale equals or crosses 1 (making the old*new product non-positive).\n\t\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\t\t\tif ( ( 1 - scale ) * ( 1 - ( scale = currentValue() / initial || 0.5 ) ) <= 0 ) {\n\t\t\t\tmaxIterations = 0;\n\t\t\t}\n\t\t\tinitialInUnit = initialInUnit / scale;\n\n\t\t}\n\n\t\tinitialInUnit = initialInUnit * 2;\n\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\n\t\t// Make sure we update the tween properties later on\n\t\tvalueParts = valueParts || [];\n\t}\n\n\tif ( valueParts ) {\n\t\tinitialInUnit = +initialInUnit || +initial || 0;\n\n\t\t// Apply relative offset (+=/-=) if specified\n\t\tadjusted = valueParts[ 1 ] ?\n\t\t\tinitialInUnit + ( valueParts[ 1 ] + 1 ) * valueParts[ 2 ] :\n\t\t\t+valueParts[ 2 ];\n\t\tif ( tween ) {\n\t\t\ttween.unit = unit;\n\t\t\ttween.start = initialInUnit;\n\t\t\ttween.end = adjusted;\n\t\t}\n\t}\n\treturn adjusted;\n}\n\n\nvar defaultDisplayMap = {};\n\nfunction getDefaultDisplay( elem ) {\n\tvar temp,\n\t\tdoc = elem.ownerDocument,\n\t\tnodeName = elem.nodeName,\n\t\tdisplay = defaultDisplayMap[ nodeName ];\n\n\tif ( display ) {\n\t\treturn display;\n\t}\n\n\ttemp = doc.body.appendChild( doc.createElement( nodeName ) );\n\tdisplay = jQuery.css( temp, \"display\" );\n\n\ttemp.parentNode.removeChild( temp );\n\n\tif ( display === \"none\" ) {\n\t\tdisplay = \"block\";\n\t}\n\tdefaultDisplayMap[ nodeName ] = display;\n\n\treturn display;\n}\n\nfunction showHide( elements, show ) {\n\tvar display, elem,\n\t\tvalues = [],\n\t\tindex = 0,\n\t\tlength = elements.length;\n\n\t// Determine new display value for elements that need to change\n\tfor ( ; index < length; index++ ) {\n\t\telem = elements[ index ];\n\t\tif ( !elem.style ) {\n\t\t\tcontinue;\n\t\t}\n\n\t\tdisplay = elem.style.display;\n\t\tif ( show ) {\n\n\t\t\t// Since we force visibility upon cascade-hidden elements, an immediate (and slow)\n\t\t\t// check is required in this first loop unless we have a nonempty display value (either\n\t\t\t// inline or about-to-be-restored)\n\t\t\tif ( display === \"none\" ) {\n\t\t\t\tvalues[ index ] = dataPriv.get( elem, \"display\" ) || null;\n\t\t\t\tif ( !values[ index ] ) {\n\t\t\t\t\telem.style.display = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t\tif ( elem.style.display === \"\" && isHiddenWithinTree( elem ) ) {\n\t\t\t\tvalues[ index ] = getDefaultDisplay( elem );\n\t\t\t}\n\t\t} else {\n\t\t\tif ( display !== \"none\" ) {\n\t\t\t\tvalues[ index ] = \"none\";\n\n\t\t\t\t// Remember what we're overwriting\n\t\t\t\tdataPriv.set( elem, \"display\", display );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Set the display of the elements in a second loop to avoid constant reflow\n\tfor ( index = 0; index < length; index++ ) {\n\t\tif ( values[ index ] != null ) {\n\t\t\telements[ index ].style.display = values[ index ];\n\t\t}\n\t}\n\n\treturn elements;\n}\n\njQuery.fn.extend( {\n\tshow: function() {\n\t\treturn showHide( this, true );\n\t},\n\thide: function() {\n\t\treturn showHide( this );\n\t},\n\ttoggle: function( state ) {\n\t\tif ( typeof state === \"boolean\" ) {\n\t\t\treturn state ? this.show() : this.hide();\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tif ( isHiddenWithinTree( this ) ) {\n\t\t\t\tjQuery( this ).show();\n\t\t\t} else {\n\t\t\t\tjQuery( this ).hide();\n\t\t\t}\n\t\t} );\n\t}\n} );\nvar rcheckableType = ( /^(?:checkbox|radio)$/i );\n\nvar rtagName = ( /<([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)/i );\n\nvar rscriptType = ( /^$|^module$|\\/(?:java|ecma)script/i );\n\n\n\n// We have to close these tags to support XHTML (#13200)\nvar wrapMap = {\n\n\t// Support: IE <=9 only\n\toption: [ 1, \"<select multiple='multiple'>\", \"</select>\" ],\n\n\t// XHTML parsers do not magically insert elements in the\n\t// same way that tag soup parsers do. So we cannot shorten\n\t// this by omitting <tbody> or other required elements.\n\tthead: [ 1, \"<table>\", \"</table>\" ],\n\tcol: [ 2, \"<table><colgroup>\", \"</colgroup></table>\" ],\n\ttr: [ 2, \"<table><tbody>\", \"</tbody></table>\" ],\n\ttd: [ 3, \"<table><tbody><tr>\", \"</tr></tbody></table>\" ],\n\n\t_default: [ 0, \"\", \"\" ]\n};\n\n// Support: IE <=9 only\nwrapMap.optgroup = wrapMap.option;\n\nwrapMap.tbody = wrapMap.tfoot = wrapMap.colgroup = wrapMap.caption = wrapMap.thead;\nwrapMap.th = wrapMap.td;\n\n\nfunction getAll( context, tag ) {\n\n\t// Support: IE <=9 - 11 only\n\t// Use typeof to avoid zero-argument method invocation on host objects (#15151)\n\tvar ret;\n\n\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\tret = context.getElementsByTagName( tag || \"*\" );\n\n\t} else if ( typeof context.querySelectorAll !== \"undefined\" ) {\n\t\tret = context.querySelectorAll( tag || \"*\" );\n\n\t} else {\n\t\tret = [];\n\t}\n\n\tif ( tag === undefined || tag && nodeName( context, tag ) ) {\n\t\treturn jQuery.merge( [ context ], ret );\n\t}\n\n\treturn ret;\n}\n\n\n// Mark scripts as having already been evaluated\nfunction setGlobalEval( elems, refElements ) {\n\tvar i = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\tdataPriv.set(\n\t\t\telems[ i ],\n\t\t\t\"globalEval\",\n\t\t\t!refElements || dataPriv.get( refElements[ i ], \"globalEval\" )\n\t\t);\n\t}\n}\n\n\nvar rhtml = /<|&#?\\w+;/;\n\nfunction buildFragment( elems, context, scripts, selection, ignored ) {\n\tvar elem, tmp, tag, wrap, attached, j,\n\t\tfragment = context.createDocumentFragment(),\n\t\tnodes = [],\n\t\ti = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\telem = elems[ i ];\n\n\t\tif ( elem || elem === 0 ) {\n\n\t\t\t// Add nodes directly\n\t\t\tif ( toType( elem ) === \"object\" ) {\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, elem.nodeType ? [ elem ] : elem );\n\n\t\t\t// Convert non-html into a text node\n\t\t\t} else if ( !rhtml.test( elem ) ) {\n\t\t\t\tnodes.push( context.createTextNode( elem ) );\n\n\t\t\t// Convert html into DOM nodes\n\t\t\t} else {\n\t\t\t\ttmp = tmp || fragment.appendChild( context.createElement( \"div\" ) );\n\n\t\t\t\t// Deserialize a standard representation\n\t\t\t\ttag = ( rtagName.exec( elem ) || [ \"\", \"\" ] )[ 1 ].toLowerCase();\n\t\t\t\twrap = wrapMap[ tag ] || wrapMap._default;\n\t\t\t\ttmp.innerHTML = wrap[ 1 ] + jQuery.htmlPrefilter( elem ) + wrap[ 2 ];\n\n\t\t\t\t// Descend through wrappers to the right content\n\t\t\t\tj = wrap[ 0 ];\n\t\t\t\twhile ( j-- ) {\n\t\t\t\t\ttmp = tmp.lastChild;\n\t\t\t\t}\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, tmp.childNodes );\n\n\t\t\t\t// Remember the top-level container\n\t\t\t\ttmp = fragment.firstChild;\n\n\t\t\t\t// Ensure the created nodes are orphaned (#12392)\n\t\t\t\ttmp.textContent = \"\";\n\t\t\t}\n\t\t}\n\t}\n\n\t// Remove wrapper from fragment\n\tfragment.textContent = \"\";\n\n\ti = 0;\n\twhile ( ( elem = nodes[ i++ ] ) ) {\n\n\t\t// Skip elements already in the context collection (trac-4087)\n\t\tif ( selection && jQuery.inArray( elem, selection ) > -1 ) {\n\t\t\tif ( ignored ) {\n\t\t\t\tignored.push( elem );\n\t\t\t}\n\t\t\tcontinue;\n\t\t}\n\n\t\tattached = isAttached( elem );\n\n\t\t// Append to fragment\n\t\ttmp = getAll( fragment.appendChild( elem ), \"script\" );\n\n\t\t// Preserve script evaluation history\n\t\tif ( attached ) {\n\t\t\tsetGlobalEval( tmp );\n\t\t}\n\n\t\t// Capture executables\n\t\tif ( scripts ) {\n\t\t\tj = 0;\n\t\t\twhile ( ( elem = tmp[ j++ ] ) ) {\n\t\t\t\tif ( rscriptType.test( elem.type || \"\" ) ) {\n\t\t\t\t\tscripts.push( elem );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn fragment;\n}\n\n\n( function() {\n\tvar fragment = document.createDocumentFragment(),\n\t\tdiv = fragment.appendChild( document.createElement( \"div\" ) ),\n\t\tinput = document.createElement( \"input\" );\n\n\t// Support: Android 4.0 - 4.3 only\n\t// Check state lost if the name is set (#11217)\n\t// Support: Windows Web Apps (WWA)\n\t// `name` and `type` must use .setAttribute for WWA (#14901)\n\tinput.setAttribute( \"type\", \"radio\" );\n\tinput.setAttribute( \"checked\", \"checked\" );\n\tinput.setAttribute( \"name\", \"t\" );\n\n\tdiv.appendChild( input );\n\n\t// Support: Android <=4.1 only\n\t// Older WebKit doesn't clone checked state correctly in fragments\n\tsupport.checkClone = div.cloneNode( true ).cloneNode( true ).lastChild.checked;\n\n\t// Support: IE <=11 only\n\t// Make sure textarea (and checkbox) defaultValue is properly cloned\n\tdiv.innerHTML = \"<textarea>x</textarea>\";\n\tsupport.noCloneChecked = !!div.cloneNode( true ).lastChild.defaultValue;\n} )();\n\n\nvar\n\trkeyEvent = /^key/,\n\trmouseEvent = /^(?:mouse|pointer|contextmenu|drag|drop)|click/,\n\trtypenamespace = /^([^.]*)(?:\\.(.+)|)/;\n\nfunction returnTrue() {\n\treturn true;\n}\n\nfunction returnFalse() {\n\treturn false;\n}\n\n// Support: IE <=9 - 11+\n// focus() and blur() are asynchronous, except when they are no-op.\n// So expect focus to be synchronous when the element is already active,\n// and blur to be synchronous when the element is not already active.\n// (focus and blur are always synchronous in other supported browsers,\n// this just defines when we can count on it).\nfunction expectSync( elem, type ) {\n\treturn ( elem === safeActiveElement() ) === ( type === \"focus\" );\n}\n\n// Support: IE <=9 only\n// Accessing document.activeElement can throw unexpectedly\n// https://bugs.jquery.com/ticket/13393\nfunction safeActiveElement() {\n\ttry {\n\t\treturn document.activeElement;\n\t} catch ( err ) { }\n}\n\nfunction on( elem, types, selector, data, fn, one ) {\n\tvar origFn, type;\n\n\t// Types can be a map of types/handlers\n\tif ( typeof types === \"object\" ) {\n\n\t\t// ( types-Object, selector, data )\n\t\tif ( typeof selector !== \"string\" ) {\n\n\t\t\t// ( types-Object, data )\n\t\t\tdata = data || selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tfor ( type in types ) {\n\t\t\ton( elem, type, selector, data, types[ type ], one );\n\t\t}\n\t\treturn elem;\n\t}\n\n\tif ( data == null && fn == null ) {\n\n\t\t// ( types, fn )\n\t\tfn = selector;\n\t\tdata = selector = undefined;\n\t} else if ( fn == null ) {\n\t\tif ( typeof selector === \"string\" ) {\n\n\t\t\t// ( types, selector, fn )\n\t\t\tfn = data;\n\t\t\tdata = undefined;\n\t\t} else {\n\n\t\t\t// ( types, data, fn )\n\t\t\tfn = data;\n\t\t\tdata = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t}\n\tif ( fn === false ) {\n\t\tfn = returnFalse;\n\t} else if ( !fn ) {\n\t\treturn elem;\n\t}\n\n\tif ( one === 1 ) {\n\t\torigFn = fn;\n\t\tfn = function( event ) {\n\n\t\t\t// Can use an empty set, since event contains the info\n\t\t\tjQuery().off( event );\n\t\t\treturn origFn.apply( this, arguments );\n\t\t};\n\n\t\t// Use same guid so caller can remove using origFn\n\t\tfn.guid = origFn.guid || ( origFn.guid = jQuery.guid++ );\n\t}\n\treturn elem.each( function() {\n\t\tjQuery.event.add( this, types, fn, data, selector );\n\t} );\n}\n\n/*\n * Helper functions for managing events -- not part of the public interface.\n * Props to Dean Edwards' addEvent library for many of the ideas.\n */\njQuery.event = {\n\n\tglobal: {},\n\n\tadd: function( elem, types, handler, data, selector ) {\n\n\t\tvar handleObjIn, eventHandle, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.get( elem );\n\n\t\t// Don't attach events to noData or text/comment nodes (but allow plain objects)\n\t\tif ( !elemData ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Caller can pass in an object of custom data in lieu of the handler\n\t\tif ( handler.handler ) {\n\t\t\thandleObjIn = handler;\n\t\t\thandler = handleObjIn.handler;\n\t\t\tselector = handleObjIn.selector;\n\t\t}\n\n\t\t// Ensure that invalid selectors throw exceptions at attach time\n\t\t// Evaluate against documentElement in case elem is a non-element node (e.g., document)\n\t\tif ( selector ) {\n\t\t\tjQuery.find.matchesSelector( documentElement, selector );\n\t\t}\n\n\t\t// Make sure that the handler has a unique ID, used to find/remove it later\n\t\tif ( !handler.guid ) {\n\t\t\thandler.guid = jQuery.guid++;\n\t\t}\n\n\t\t// Init the element's event structure and main handler, if this is the first\n\t\tif ( !( events = elemData.events ) ) {\n\t\t\tevents = elemData.events = {};\n\t\t}\n\t\tif ( !( eventHandle = elemData.handle ) ) {\n\t\t\teventHandle = elemData.handle = function( e ) {\n\n\t\t\t\t// Discard the second event of a jQuery.event.trigger() and\n\t\t\t\t// when an event is called after a page has unloaded\n\t\t\t\treturn typeof jQuery !== \"undefined\" && jQuery.event.triggered !== e.type ?\n\t\t\t\t\tjQuery.event.dispatch.apply( elem, arguments ) : undefined;\n\t\t\t};\n\t\t}\n\n\t\t// Handle multiple events separated by a space\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// There *must* be a type, no attaching namespace-only handlers\n\t\t\tif ( !type ) {\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\t// If event changes its type, use the special event handlers for the changed type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// If selector defined, determine special event api type, otherwise given type\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\n\t\t\t// Update special based on newly reset type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// handleObj is passed to all event handlers\n\t\t\thandleObj = jQuery.extend( {\n\t\t\t\ttype: type,\n\t\t\t\torigType: origType,\n\t\t\t\tdata: data,\n\t\t\t\thandler: handler,\n\t\t\t\tguid: handler.guid,\n\t\t\t\tselector: selector,\n\t\t\t\tneedsContext: selector && jQuery.expr.match.needsContext.test( selector ),\n\t\t\t\tnamespace: namespaces.join( \".\" )\n\t\t\t}, handleObjIn );\n\n\t\t\t// Init the event handler queue if we're the first\n\t\t\tif ( !( handlers = events[ type ] ) ) {\n\t\t\t\thandlers = events[ type ] = [];\n\t\t\t\thandlers.delegateCount = 0;\n\n\t\t\t\t// Only use addEventListener if the special events handler returns false\n\t\t\t\tif ( !special.setup ||\n\t\t\t\t\tspecial.setup.call( elem, data, namespaces, eventHandle ) === false ) {\n\n\t\t\t\t\tif ( elem.addEventListener ) {\n\t\t\t\t\t\telem.addEventListener( type, eventHandle );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tif ( special.add ) {\n\t\t\t\tspecial.add.call( elem, handleObj );\n\n\t\t\t\tif ( !handleObj.handler.guid ) {\n\t\t\t\t\thandleObj.handler.guid = handler.guid;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Add to the element's handler list, delegates in front\n\t\t\tif ( selector ) {\n\t\t\t\thandlers.splice( handlers.delegateCount++, 0, handleObj );\n\t\t\t} else {\n\t\t\t\thandlers.push( handleObj );\n\t\t\t}\n\n\t\t\t// Keep track of which events have ever been used, for event optimization\n\t\t\tjQuery.event.global[ type ] = true;\n\t\t}\n\n\t},\n\n\t// Detach an event or set of events from an element\n\tremove: function( elem, types, handler, selector, mappedTypes ) {\n\n\t\tvar j, origCount, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.hasData( elem ) && dataPriv.get( elem );\n\n\t\tif ( !elemData || !( events = elemData.events ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Once for each type.namespace in types; type may be omitted\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// Unbind all events (on this namespace, if provided) for the element\n\t\t\tif ( !type ) {\n\t\t\t\tfor ( type in events ) {\n\t\t\t\t\tjQuery.event.remove( elem, type + types[ t ], handler, selector, true );\n\t\t\t\t}\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\t\t\thandlers = events[ type ] || [];\n\t\t\ttmp = tmp[ 2 ] &&\n\t\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" );\n\n\t\t\t// Remove matching events\n\t\t\torigCount = j = handlers.length;\n\t\t\twhile ( j-- ) {\n\t\t\t\thandleObj = handlers[ j ];\n\n\t\t\t\tif ( ( mappedTypes || origType === handleObj.origType ) &&\n\t\t\t\t\t( !handler || handler.guid === handleObj.guid ) &&\n\t\t\t\t\t( !tmp || tmp.test( handleObj.namespace ) ) &&\n\t\t\t\t\t( !selector || selector === handleObj.selector ||\n\t\t\t\t\t\tselector === \"**\" && handleObj.selector ) ) {\n\t\t\t\t\thandlers.splice( j, 1 );\n\n\t\t\t\t\tif ( handleObj.selector ) {\n\t\t\t\t\t\thandlers.delegateCount--;\n\t\t\t\t\t}\n\t\t\t\t\tif ( special.remove ) {\n\t\t\t\t\t\tspecial.remove.call( elem, handleObj );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Remove generic event handler if we removed something and no more handlers exist\n\t\t\t// (avoids potential for endless recursion during removal of special event handlers)\n\t\t\tif ( origCount && !handlers.length ) {\n\t\t\t\tif ( !special.teardown ||\n\t\t\t\t\tspecial.teardown.call( elem, namespaces, elemData.handle ) === false ) {\n\n\t\t\t\t\tjQuery.removeEvent( elem, type, elemData.handle );\n\t\t\t\t}\n\n\t\t\t\tdelete events[ type ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove data and the expando if it's no longer used\n\t\tif ( jQuery.isEmptyObject( events ) ) {\n\t\t\tdataPriv.remove( elem, \"handle events\" );\n\t\t}\n\t},\n\n\tdispatch: function( nativeEvent ) {\n\n\t\t// Make a writable jQuery.Event from the native event object\n\t\tvar event = jQuery.event.fix( nativeEvent );\n\n\t\tvar i, j, ret, matched, handleObj, handlerQueue,\n\t\t\targs = new Array( arguments.length ),\n\t\t\thandlers = ( dataPriv.get( this, \"events\" ) || {} )[ event.type ] || [],\n\t\t\tspecial = jQuery.event.special[ event.type ] || {};\n\n\t\t// Use the fix-ed jQuery.Event rather than the (read-only) native event\n\t\targs[ 0 ] = event;\n\n\t\tfor ( i = 1; i < arguments.length; i++ ) {\n\t\t\targs[ i ] = arguments[ i ];\n\t\t}\n\n\t\tevent.delegateTarget = this;\n\n\t\t// Call the preDispatch hook for the mapped type, and let it bail if desired\n\t\tif ( special.preDispatch && special.preDispatch.call( this, event ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine handlers\n\t\thandlerQueue = jQuery.event.handlers.call( this, event, handlers );\n\n\t\t// Run delegates first; they may want to stop propagation beneath us\n\t\ti = 0;\n\t\twhile ( ( matched = handlerQueue[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tevent.currentTarget = matched.elem;\n\n\t\t\tj = 0;\n\t\t\twhile ( ( handleObj = matched.handlers[ j++ ] ) &&\n\t\t\t\t!event.isImmediatePropagationStopped() ) {\n\n\t\t\t\t// If the event is namespaced, then each handler is only invoked if it is\n\t\t\t\t// specially universal or its namespaces are a superset of the event's.\n\t\t\t\tif ( !event.rnamespace || handleObj.namespace === false ||\n\t\t\t\t\tevent.rnamespace.test( handleObj.namespace ) ) {\n\n\t\t\t\t\tevent.handleObj = handleObj;\n\t\t\t\t\tevent.data = handleObj.data;\n\n\t\t\t\t\tret = ( ( jQuery.event.special[ handleObj.origType ] || {} ).handle ||\n\t\t\t\t\t\thandleObj.handler ).apply( matched.elem, args );\n\n\t\t\t\t\tif ( ret !== undefined ) {\n\t\t\t\t\t\tif ( ( event.result = ret ) === false ) {\n\t\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Call the postDispatch hook for the mapped type\n\t\tif ( special.postDispatch ) {\n\t\t\tspecial.postDispatch.call( this, event );\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\thandlers: function( event, handlers ) {\n\t\tvar i, handleObj, sel, matchedHandlers, matchedSelectors,\n\t\t\thandlerQueue = [],\n\t\t\tdelegateCount = handlers.delegateCount,\n\t\t\tcur = event.target;\n\n\t\t// Find delegate handlers\n\t\tif ( delegateCount &&\n\n\t\t\t// Support: IE <=9\n\t\t\t// Black-hole SVG <use> instance trees (trac-13180)\n\t\t\tcur.nodeType &&\n\n\t\t\t// Support: Firefox <=42\n\t\t\t// Suppress spec-violating clicks indicating a non-primary pointer button (trac-3861)\n\t\t\t// https://www.w3.org/TR/DOM-Level-3-Events/#event-type-click\n\t\t\t// Support: IE 11 only\n\t\t\t// ...but not arrow key \"clicks\" of radio inputs, which can have `button` -1 (gh-2343)\n\t\t\t!( event.type === \"click\" && event.button >= 1 ) ) {\n\n\t\t\tfor ( ; cur !== this; cur = cur.parentNode || this ) {\n\n\t\t\t\t// Don't check non-elements (#13208)\n\t\t\t\t// Don't process clicks on disabled elements (#6911, #8165, #11382, #11764)\n\t\t\t\tif ( cur.nodeType === 1 && !( event.type === \"click\" && cur.disabled === true ) ) {\n\t\t\t\t\tmatchedHandlers = [];\n\t\t\t\t\tmatchedSelectors = {};\n\t\t\t\t\tfor ( i = 0; i < delegateCount; i++ ) {\n\t\t\t\t\t\thandleObj = handlers[ i ];\n\n\t\t\t\t\t\t// Don't conflict with Object.prototype properties (#13203)\n\t\t\t\t\t\tsel = handleObj.selector + \" \";\n\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] === undefined ) {\n\t\t\t\t\t\t\tmatchedSelectors[ sel ] = handleObj.needsContext ?\n\t\t\t\t\t\t\t\tjQuery( sel, this ).index( cur ) > -1 :\n\t\t\t\t\t\t\t\tjQuery.find( sel, this, null, [ cur ] ).length;\n\t\t\t\t\t\t}\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] ) {\n\t\t\t\t\t\t\tmatchedHandlers.push( handleObj );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( matchedHandlers.length ) {\n\t\t\t\t\t\thandlerQueue.push( { elem: cur, handlers: matchedHandlers } );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Add the remaining (directly-bound) handlers\n\t\tcur = this;\n\t\tif ( delegateCount < handlers.length ) {\n\t\t\thandlerQueue.push( { elem: cur, handlers: handlers.slice( delegateCount ) } );\n\t\t}\n\n\t\treturn handlerQueue;\n\t},\n\n\taddProp: function( name, hook ) {\n\t\tObject.defineProperty( jQuery.Event.prototype, name, {\n\t\t\tenumerable: true,\n\t\t\tconfigurable: true,\n\n\t\t\tget: isFunction( hook ) ?\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn hook( this.originalEvent );\n\t\t\t\t\t}\n\t\t\t\t} :\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn this.originalEvent[ name ];\n\t\t\t\t\t}\n\t\t\t\t},\n\n\t\t\tset: function( value ) {\n\t\t\t\tObject.defineProperty( this, name, {\n\t\t\t\t\tenumerable: true,\n\t\t\t\t\tconfigurable: true,\n\t\t\t\t\twritable: true,\n\t\t\t\t\tvalue: value\n\t\t\t\t} );\n\t\t\t}\n\t\t} );\n\t},\n\n\tfix: function( originalEvent ) {\n\t\treturn originalEvent[ jQuery.expando ] ?\n\t\t\toriginalEvent :\n\t\t\tnew jQuery.Event( originalEvent );\n\t},\n\n\tspecial: {\n\t\tload: {\n\n\t\t\t// Prevent triggered image.load events from bubbling to window.load\n\t\t\tnoBubble: true\n\t\t},\n\t\tclick: {\n\n\t\t\t// Utilize native event to ensure correct state for checkable inputs\n\t\t\tsetup: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Claim the first handler\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\t// dataPriv.set( el, \"click\", ... )\n\t\t\t\t\tleverageNative( el, \"click\", returnTrue );\n\t\t\t\t}\n\n\t\t\t\t// Return false to allow normal processing in the caller\n\t\t\t\treturn false;\n\t\t\t},\n\t\t\ttrigger: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Force setup before triggering a click\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\tleverageNative( el, \"click\" );\n\t\t\t\t}\n\n\t\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\t\treturn true;\n\t\t\t},\n\n\t\t\t// For cross-browser consistency, suppress native .click() on links\n\t\t\t// Also prevent it if we're currently inside a leveraged native-event stack\n\t\t\t_default: function( event ) {\n\t\t\t\tvar target = event.target;\n\t\t\t\treturn rcheckableType.test( target.type ) &&\n\t\t\t\t\ttarget.click && nodeName( target, \"input\" ) &&\n\t\t\t\t\tdataPriv.get( target, \"click\" ) ||\n\t\t\t\t\tnodeName( target, \"a\" );\n\t\t\t}\n\t\t},\n\n\t\tbeforeunload: {\n\t\t\tpostDispatch: function( event ) {\n\n\t\t\t\t// Support: Firefox 20+\n\t\t\t\t// Firefox doesn't alert if the returnValue field is not set.\n\t\t\t\tif ( event.result !== undefined && event.originalEvent ) {\n\t\t\t\t\tevent.originalEvent.returnValue = event.result;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n};\n\n// Ensure the presence of an event listener that handles manually-triggered\n// synthetic events by interrupting progress until reinvoked in response to\n// *native* events that it fires directly, ensuring that state changes have\n// already occurred before other listeners are invoked.\nfunction leverageNative( el, type, expectSync ) {\n\n\t// Missing expectSync indicates a trigger call, which must force setup through jQuery.event.add\n\tif ( !expectSync ) {\n\t\tif ( dataPriv.get( el, type ) === undefined ) {\n\t\t\tjQuery.event.add( el, type, returnTrue );\n\t\t}\n\t\treturn;\n\t}\n\n\t// Register the controller as a special universal handler for all event namespaces\n\tdataPriv.set( el, type, false );\n\tjQuery.event.add( el, type, {\n\t\tnamespace: false,\n\t\thandler: function( event ) {\n\t\t\tvar notAsync, result,\n\t\t\t\tsaved = dataPriv.get( this, type );\n\n\t\t\tif ( ( event.isTrigger & 1 ) && this[ type ] ) {\n\n\t\t\t\t// Interrupt processing of the outer synthetic .trigger()ed event\n\t\t\t\t// Saved data should be false in such cases, but might be a leftover capture object\n\t\t\t\t// from an async native handler (gh-4350)\n\t\t\t\tif ( !saved.length ) {\n\n\t\t\t\t\t// Store arguments for use when handling the inner native event\n\t\t\t\t\t// There will always be at least one argument (an event object), so this array\n\t\t\t\t\t// will not be confused with a leftover capture object.\n\t\t\t\t\tsaved = slice.call( arguments );\n\t\t\t\t\tdataPriv.set( this, type, saved );\n\n\t\t\t\t\t// Trigger the native event and capture its result\n\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t// focus() and blur() are asynchronous\n\t\t\t\t\tnotAsync = expectSync( this, type );\n\t\t\t\t\tthis[ type ]();\n\t\t\t\t\tresult = dataPriv.get( this, type );\n\t\t\t\t\tif ( saved !== result || notAsync ) {\n\t\t\t\t\t\tdataPriv.set( this, type, false );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tresult = {};\n\t\t\t\t\t}\n\t\t\t\t\tif ( saved !== result ) {\n\n\t\t\t\t\t\t// Cancel the outer synthetic event\n\t\t\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\treturn result.value;\n\t\t\t\t\t}\n\n\t\t\t\t// If this is an inner synthetic event for an event with a bubbling surrogate\n\t\t\t\t// (focus or blur), assume that the surrogate already propagated from triggering the\n\t\t\t\t// native event and prevent that from happening again here.\n\t\t\t\t// This technically gets the ordering wrong w.r.t. to `.trigger()` (in which the\n\t\t\t\t// bubbling surrogate propagates *after* the non-bubbling base), but that seems\n\t\t\t\t// less bad than duplication.\n\t\t\t\t} else if ( ( jQuery.event.special[ type ] || {} ).delegateType ) {\n\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t}\n\n\t\t\t// If this is a native event triggered above, everything is now in order\n\t\t\t// Fire an inner synthetic event with the original arguments\n\t\t\t} else if ( saved.length ) {\n\n\t\t\t\t// ...and capture the result\n\t\t\t\tdataPriv.set( this, type, {\n\t\t\t\t\tvalue: jQuery.event.trigger(\n\n\t\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t\t// Extend with the prototype to reset the above stopImmediatePropagation()\n\t\t\t\t\t\tjQuery.extend( saved[ 0 ], jQuery.Event.prototype ),\n\t\t\t\t\t\tsaved.slice( 1 ),\n\t\t\t\t\t\tthis\n\t\t\t\t\t)\n\t\t\t\t} );\n\n\t\t\t\t// Abort handling of the native event\n\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t}\n\t\t}\n\t} );\n}\n\njQuery.removeEvent = function( elem, type, handle ) {\n\n\t// This \"if\" is needed for plain objects\n\tif ( elem.removeEventListener ) {\n\t\telem.removeEventListener( type, handle );\n\t}\n};\n\njQuery.Event = function( src, props ) {\n\n\t// Allow instantiation without the 'new' keyword\n\tif ( !( this instanceof jQuery.Event ) ) {\n\t\treturn new jQuery.Event( src, props );\n\t}\n\n\t// Event object\n\tif ( src && src.type ) {\n\t\tthis.originalEvent = src;\n\t\tthis.type = src.type;\n\n\t\t// Events bubbling up the document may have been marked as prevented\n\t\t// by a handler lower down the tree; reflect the correct value.\n\t\tthis.isDefaultPrevented = src.defaultPrevented ||\n\t\t\t\tsrc.defaultPrevented === undefined &&\n\n\t\t\t\t// Support: Android <=2.3 only\n\t\t\t\tsrc.returnValue === false ?\n\t\t\treturnTrue :\n\t\t\treturnFalse;\n\n\t\t// Create target properties\n\t\t// Support: Safari <=6 - 7 only\n\t\t// Target should not be a text node (#504, #13143)\n\t\tthis.target = ( src.target && src.target.nodeType === 3 ) ?\n\t\t\tsrc.target.parentNode :\n\t\t\tsrc.target;\n\n\t\tthis.currentTarget = src.currentTarget;\n\t\tthis.relatedTarget = src.relatedTarget;\n\n\t// Event type\n\t} else {\n\t\tthis.type = src;\n\t}\n\n\t// Put explicitly provided properties onto the event object\n\tif ( props ) {\n\t\tjQuery.extend( this, props );\n\t}\n\n\t// Create a timestamp if incoming event doesn't have one\n\tthis.timeStamp = src && src.timeStamp || Date.now();\n\n\t// Mark it as fixed\n\tthis[ jQuery.expando ] = true;\n};\n\n// jQuery.Event is based on DOM3 Events as specified by the ECMAScript Language Binding\n// https://www.w3.org/TR/2003/WD-DOM-Level-3-Events-20030331/ecma-script-binding.html\njQuery.Event.prototype = {\n\tconstructor: jQuery.Event,\n\tisDefaultPrevented: returnFalse,\n\tisPropagationStopped: returnFalse,\n\tisImmediatePropagationStopped: returnFalse,\n\tisSimulated: false,\n\n\tpreventDefault: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isDefaultPrevented = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.preventDefault();\n\t\t}\n\t},\n\tstopPropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isPropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopPropagation();\n\t\t}\n\t},\n\tstopImmediatePropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isImmediatePropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopImmediatePropagation();\n\t\t}\n\n\t\tthis.stopPropagation();\n\t}\n};\n\n// Includes all common event props including KeyEvent and MouseEvent specific props\njQuery.each( {\n\taltKey: true,\n\tbubbles: true,\n\tcancelable: true,\n\tchangedTouches: true,\n\tctrlKey: true,\n\tdetail: true,\n\teventPhase: true,\n\tmetaKey: true,\n\tpageX: true,\n\tpageY: true,\n\tshiftKey: true,\n\tview: true,\n\t\"char\": true,\n\tcode: true,\n\tcharCode: true,\n\tkey: true,\n\tkeyCode: true,\n\tbutton: true,\n\tbuttons: true,\n\tclientX: true,\n\tclientY: true,\n\toffsetX: true,\n\toffsetY: true,\n\tpointerId: true,\n\tpointerType: true,\n\tscreenX: true,\n\tscreenY: true,\n\ttargetTouches: true,\n\ttoElement: true,\n\ttouches: true,\n\n\twhich: function( event ) {\n\t\tvar button = event.button;\n\n\t\t// Add which for key events\n\t\tif ( event.which == null && rkeyEvent.test( event.type ) ) {\n\t\t\treturn event.charCode != null ? event.charCode : event.keyCode;\n\t\t}\n\n\t\t// Add which for click: 1 === left; 2 === middle; 3 === right\n\t\tif ( !event.which && button !== undefined && rmouseEvent.test( event.type ) ) {\n\t\t\tif ( button & 1 ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\tif ( button & 2 ) {\n\t\t\t\treturn 3;\n\t\t\t}\n\n\t\t\tif ( button & 4 ) {\n\t\t\t\treturn 2;\n\t\t\t}\n\n\t\t\treturn 0;\n\t\t}\n\n\t\treturn event.which;\n\t}\n}, jQuery.event.addProp );\n\njQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( type, delegateType ) {\n\tjQuery.event.special[ type ] = {\n\n\t\t// Utilize native event if possible so blur/focus sequence is correct\n\t\tsetup: function() {\n\n\t\t\t// Claim the first handler\n\t\t\t// dataPriv.set( this, \"focus\", ... )\n\t\t\t// dataPriv.set( this, \"blur\", ... )\n\t\t\tleverageNative( this, type, expectSync );\n\n\t\t\t// Return false to allow normal processing in the caller\n\t\t\treturn false;\n\t\t},\n\t\ttrigger: function() {\n\n\t\t\t// Force setup before trigger\n\t\t\tleverageNative( this, type );\n\n\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\treturn true;\n\t\t},\n\n\t\tdelegateType: delegateType\n\t};\n} );\n\n// Create mouseenter/leave events using mouseover/out and event-time checks\n// so that event delegation works in jQuery.\n// Do the same for pointerenter/pointerleave and pointerover/pointerout\n//\n// Support: Safari 7 only\n// Safari sends mouseenter too often; see:\n// https://bugs.chromium.org/p/chromium/issues/detail?id=470258\n// for the description of the bug (it existed in older Chrome versions as well).\njQuery.each( {\n\tmouseenter: \"mouseover\",\n\tmouseleave: \"mouseout\",\n\tpointerenter: \"pointerover\",\n\tpointerleave: \"pointerout\"\n}, function( orig, fix ) {\n\tjQuery.event.special[ orig ] = {\n\t\tdelegateType: fix,\n\t\tbindType: fix,\n\n\t\thandle: function( event ) {\n\t\t\tvar ret,\n\t\t\t\ttarget = this,\n\t\t\t\trelated = event.relatedTarget,\n\t\t\t\thandleObj = event.handleObj;\n\n\t\t\t// For mouseenter/leave call the handler if related is outside the target.\n\t\t\t// NB: No relatedTarget if the mouse left/entered the browser window\n\t\t\tif ( !related || ( related !== target && !jQuery.contains( target, related ) ) ) {\n\t\t\t\tevent.type = handleObj.origType;\n\t\t\t\tret = handleObj.handler.apply( this, arguments );\n\t\t\t\tevent.type = fix;\n\t\t\t}\n\t\t\treturn ret;\n\t\t}\n\t};\n} );\n\njQuery.fn.extend( {\n\n\ton: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn );\n\t},\n\tone: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn, 1 );\n\t},\n\toff: function( types, selector, fn ) {\n\t\tvar handleObj, type;\n\t\tif ( types && types.preventDefault && types.handleObj ) {\n\n\t\t\t// ( event )  dispatched jQuery.Event\n\t\t\thandleObj = types.handleObj;\n\t\t\tjQuery( types.delegateTarget ).off(\n\t\t\t\thandleObj.namespace ?\n\t\t\t\t\thandleObj.origType + \".\" + handleObj.namespace :\n\t\t\t\t\thandleObj.origType,\n\t\t\t\thandleObj.selector,\n\t\t\t\thandleObj.handler\n\t\t\t);\n\t\t\treturn this;\n\t\t}\n\t\tif ( typeof types === \"object\" ) {\n\n\t\t\t// ( types-object [, selector] )\n\t\t\tfor ( type in types ) {\n\t\t\t\tthis.off( type, selector, types[ type ] );\n\t\t\t}\n\t\t\treturn this;\n\t\t}\n\t\tif ( selector === false || typeof selector === \"function\" ) {\n\n\t\t\t// ( types [, fn] )\n\t\t\tfn = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tif ( fn === false ) {\n\t\t\tfn = returnFalse;\n\t\t}\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.remove( this, types, fn, selector );\n\t\t} );\n\t}\n} );\n\n\nvar\n\n\t/* eslint-disable max-len */\n\n\t// See https://github.com/eslint/eslint/issues/3229\n\trxhtmlTag = /<(?!area|br|col|embed|hr|img|input|link|meta|param)(([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)[^>]*)\\/>/gi,\n\n\t/* eslint-enable */\n\n\t// Support: IE <=10 - 11, Edge 12 - 13 only\n\t// In IE/Edge using regex groups here causes severe slowdowns.\n\t// See https://connect.microsoft.com/IE/feedback/details/1736512/\n\trnoInnerhtml = /<script|<style|<link/i,\n\n\t// checked=\"checked\" or checked\n\trchecked = /checked\\s*(?:[^=]|=\\s*.checked.)/i,\n\trcleanScript = /^\\s*<!(?:\\[CDATA\\[|--)|(?:\\]\\]|--)>\\s*$/g;\n\n// Prefer a tbody over its parent table for containing new rows\nfunction manipulationTarget( elem, content ) {\n\tif ( nodeName( elem, \"table\" ) &&\n\t\tnodeName( content.nodeType !== 11 ? content : content.firstChild, \"tr\" ) ) {\n\n\t\treturn jQuery( elem ).children( \"tbody\" )[ 0 ] || elem;\n\t}\n\n\treturn elem;\n}\n\n// Replace/restore the type attribute of script elements for safe DOM manipulation\nfunction disableScript( elem ) {\n\telem.type = ( elem.getAttribute( \"type\" ) !== null ) + \"/\" + elem.type;\n\treturn elem;\n}\nfunction restoreScript( elem ) {\n\tif ( ( elem.type || \"\" ).slice( 0, 5 ) === \"true/\" ) {\n\t\telem.type = elem.type.slice( 5 );\n\t} else {\n\t\telem.removeAttribute( \"type\" );\n\t}\n\n\treturn elem;\n}\n\nfunction cloneCopyEvent( src, dest ) {\n\tvar i, l, type, pdataOld, pdataCur, udataOld, udataCur, events;\n\n\tif ( dest.nodeType !== 1 ) {\n\t\treturn;\n\t}\n\n\t// 1. Copy private data: events, handlers, etc.\n\tif ( dataPriv.hasData( src ) ) {\n\t\tpdataOld = dataPriv.access( src );\n\t\tpdataCur = dataPriv.set( dest, pdataOld );\n\t\tevents = pdataOld.events;\n\n\t\tif ( events ) {\n\t\t\tdelete pdataCur.handle;\n\t\t\tpdataCur.events = {};\n\n\t\t\tfor ( type in events ) {\n\t\t\t\tfor ( i = 0, l = events[ type ].length; i < l; i++ ) {\n\t\t\t\t\tjQuery.event.add( dest, type, events[ type ][ i ] );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// 2. Copy user data\n\tif ( dataUser.hasData( src ) ) {\n\t\tudataOld = dataUser.access( src );\n\t\tudataCur = jQuery.extend( {}, udataOld );\n\n\t\tdataUser.set( dest, udataCur );\n\t}\n}\n\n// Fix IE bugs, see support tests\nfunction fixInput( src, dest ) {\n\tvar nodeName = dest.nodeName.toLowerCase();\n\n\t// Fails to persist the checked state of a cloned checkbox or radio button.\n\tif ( nodeName === \"input\" && rcheckableType.test( src.type ) ) {\n\t\tdest.checked = src.checked;\n\n\t// Fails to return the selected option to the default selected state when cloning options\n\t} else if ( nodeName === \"input\" || nodeName === \"textarea\" ) {\n\t\tdest.defaultValue = src.defaultValue;\n\t}\n}\n\nfunction domManip( collection, args, callback, ignored ) {\n\n\t// Flatten any nested arrays\n\targs = concat.apply( [], args );\n\n\tvar fragment, first, scripts, hasScripts, node, doc,\n\t\ti = 0,\n\t\tl = collection.length,\n\t\tiNoClone = l - 1,\n\t\tvalue = args[ 0 ],\n\t\tvalueIsFunction = isFunction( value );\n\n\t// We can't cloneNode fragments that contain checked, in WebKit\n\tif ( valueIsFunction ||\n\t\t\t( l > 1 && typeof value === \"string\" &&\n\t\t\t\t!support.checkClone && rchecked.test( value ) ) ) {\n\t\treturn collection.each( function( index ) {\n\t\t\tvar self = collection.eq( index );\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\targs[ 0 ] = value.call( this, index, self.html() );\n\t\t\t}\n\t\t\tdomManip( self, args, callback, ignored );\n\t\t} );\n\t}\n\n\tif ( l ) {\n\t\tfragment = buildFragment( args, collection[ 0 ].ownerDocument, false, collection, ignored );\n\t\tfirst = fragment.firstChild;\n\n\t\tif ( fragment.childNodes.length === 1 ) {\n\t\t\tfragment = first;\n\t\t}\n\n\t\t// Require either new content or an interest in ignored elements to invoke the callback\n\t\tif ( first || ignored ) {\n\t\t\tscripts = jQuery.map( getAll( fragment, \"script\" ), disableScript );\n\t\t\thasScripts = scripts.length;\n\n\t\t\t// Use the original fragment for the last item\n\t\t\t// instead of the first because it can end up\n\t\t\t// being emptied incorrectly in certain situations (#8070).\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tnode = fragment;\n\n\t\t\t\tif ( i !== iNoClone ) {\n\t\t\t\t\tnode = jQuery.clone( node, true, true );\n\n\t\t\t\t\t// Keep references to cloned scripts for later restoration\n\t\t\t\t\tif ( hasScripts ) {\n\n\t\t\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\t\t\tjQuery.merge( scripts, getAll( node, \"script\" ) );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\tcallback.call( collection[ i ], node, i );\n\t\t\t}\n\n\t\t\tif ( hasScripts ) {\n\t\t\t\tdoc = scripts[ scripts.length - 1 ].ownerDocument;\n\n\t\t\t\t// Reenable scripts\n\t\t\t\tjQuery.map( scripts, restoreScript );\n\n\t\t\t\t// Evaluate executable scripts on first document insertion\n\t\t\t\tfor ( i = 0; i < hasScripts; i++ ) {\n\t\t\t\t\tnode = scripts[ i ];\n\t\t\t\t\tif ( rscriptType.test( node.type || \"\" ) &&\n\t\t\t\t\t\t!dataPriv.access( node, \"globalEval\" ) &&\n\t\t\t\t\t\tjQuery.contains( doc, node ) ) {\n\n\t\t\t\t\t\tif ( node.src && ( node.type || \"\" ).toLowerCase()  !== \"module\" ) {\n\n\t\t\t\t\t\t\t// Optional AJAX dependency, but won't run scripts if not present\n\t\t\t\t\t\t\tif ( jQuery._evalUrl && !node.noModule ) {\n\t\t\t\t\t\t\t\tjQuery._evalUrl( node.src, {\n\t\t\t\t\t\t\t\t\tnonce: node.nonce || node.getAttribute( \"nonce\" )\n\t\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\tDOMEval( node.textContent.replace( rcleanScript, \"\" ), node, doc );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn collection;\n}\n\nfunction remove( elem, selector, keepData ) {\n\tvar node,\n\t\tnodes = selector ? jQuery.filter( selector, elem ) : elem,\n\t\ti = 0;\n\n\tfor ( ; ( node = nodes[ i ] ) != null; i++ ) {\n\t\tif ( !keepData && node.nodeType === 1 ) {\n\t\t\tjQuery.cleanData( getAll( node ) );\n\t\t}\n\n\t\tif ( node.parentNode ) {\n\t\t\tif ( keepData && isAttached( node ) ) {\n\t\t\t\tsetGlobalEval( getAll( node, \"script\" ) );\n\t\t\t}\n\t\t\tnode.parentNode.removeChild( node );\n\t\t}\n\t}\n\n\treturn elem;\n}\n\njQuery.extend( {\n\thtmlPrefilter: function( html ) {\n\t\treturn html.replace( rxhtmlTag, \"<$1></$2>\" );\n\t},\n\n\tclone: function( elem, dataAndEvents, deepDataAndEvents ) {\n\t\tvar i, l, srcElements, destElements,\n\t\t\tclone = elem.cloneNode( true ),\n\t\t\tinPage = isAttached( elem );\n\n\t\t// Fix IE cloning issues\n\t\tif ( !support.noCloneChecked && ( elem.nodeType === 1 || elem.nodeType === 11 ) &&\n\t\t\t\t!jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// We eschew Sizzle here for performance reasons: https://jsperf.com/getall-vs-sizzle/2\n\t\t\tdestElements = getAll( clone );\n\t\t\tsrcElements = getAll( elem );\n\n\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\tfixInput( srcElements[ i ], destElements[ i ] );\n\t\t\t}\n\t\t}\n\n\t\t// Copy the events from the original to the clone\n\t\tif ( dataAndEvents ) {\n\t\t\tif ( deepDataAndEvents ) {\n\t\t\t\tsrcElements = srcElements || getAll( elem );\n\t\t\t\tdestElements = destElements || getAll( clone );\n\n\t\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\t\tcloneCopyEvent( srcElements[ i ], destElements[ i ] );\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tcloneCopyEvent( elem, clone );\n\t\t\t}\n\t\t}\n\n\t\t// Preserve script evaluation history\n\t\tdestElements = getAll( clone, \"script\" );\n\t\tif ( destElements.length > 0 ) {\n\t\t\tsetGlobalEval( destElements, !inPage && getAll( elem, \"script\" ) );\n\t\t}\n\n\t\t// Return the cloned set\n\t\treturn clone;\n\t},\n\n\tcleanData: function( elems ) {\n\t\tvar data, elem, type,\n\t\t\tspecial = jQuery.event.special,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = elems[ i ] ) !== undefined; i++ ) {\n\t\t\tif ( acceptData( elem ) ) {\n\t\t\t\tif ( ( data = elem[ dataPriv.expando ] ) ) {\n\t\t\t\t\tif ( data.events ) {\n\t\t\t\t\t\tfor ( type in data.events ) {\n\t\t\t\t\t\t\tif ( special[ type ] ) {\n\t\t\t\t\t\t\t\tjQuery.event.remove( elem, type );\n\n\t\t\t\t\t\t\t// This is a shortcut to avoid jQuery.event.remove's overhead\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tjQuery.removeEvent( elem, type, data.handle );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataPriv.expando ] = undefined;\n\t\t\t\t}\n\t\t\t\tif ( elem[ dataUser.expando ] ) {\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataUser.expando ] = undefined;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n} );\n\njQuery.fn.extend( {\n\tdetach: function( selector ) {\n\t\treturn remove( this, selector, true );\n\t},\n\n\tremove: function( selector ) {\n\t\treturn remove( this, selector );\n\t},\n\n\ttext: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\treturn value === undefined ?\n\t\t\t\tjQuery.text( this ) :\n\t\t\t\tthis.empty().each( function() {\n\t\t\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\t\t\tthis.textContent = value;\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t}, null, value, arguments.length );\n\t},\n\n\tappend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.appendChild( elem );\n\t\t\t}\n\t\t} );\n\t},\n\n\tprepend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.insertBefore( elem, target.firstChild );\n\t\t\t}\n\t\t} );\n\t},\n\n\tbefore: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this );\n\t\t\t}\n\t\t} );\n\t},\n\n\tafter: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this.nextSibling );\n\t\t\t}\n\t\t} );\n\t},\n\n\tempty: function() {\n\t\tvar elem,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = this[ i ] ) != null; i++ ) {\n\t\t\tif ( elem.nodeType === 1 ) {\n\n\t\t\t\t// Prevent memory leaks\n\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\n\t\t\t\t// Remove any remaining nodes\n\t\t\t\telem.textContent = \"\";\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tclone: function( dataAndEvents, deepDataAndEvents ) {\n\t\tdataAndEvents = dataAndEvents == null ? false : dataAndEvents;\n\t\tdeepDataAndEvents = deepDataAndEvents == null ? dataAndEvents : deepDataAndEvents;\n\n\t\treturn this.map( function() {\n\t\t\treturn jQuery.clone( this, dataAndEvents, deepDataAndEvents );\n\t\t} );\n\t},\n\n\thtml: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\tvar elem = this[ 0 ] || {},\n\t\t\t\ti = 0,\n\t\t\t\tl = this.length;\n\n\t\t\tif ( value === undefined && elem.nodeType === 1 ) {\n\t\t\t\treturn elem.innerHTML;\n\t\t\t}\n\n\t\t\t// See if we can take a shortcut and just use innerHTML\n\t\t\tif ( typeof value === \"string\" && !rnoInnerhtml.test( value ) &&\n\t\t\t\t!wrapMap[ ( rtagName.exec( value ) || [ \"\", \"\" ] )[ 1 ].toLowerCase() ] ) {\n\n\t\t\t\tvalue = jQuery.htmlPrefilter( value );\n\n\t\t\t\ttry {\n\t\t\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\t\t\telem = this[ i ] || {};\n\n\t\t\t\t\t\t// Remove element nodes and prevent memory leaks\n\t\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\t\t\t\t\t\t\telem.innerHTML = value;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\telem = 0;\n\n\t\t\t\t// If using innerHTML throws an exception, use the fallback method\n\t\t\t\t} catch ( e ) {}\n\t\t\t}\n\n\t\t\tif ( elem ) {\n\t\t\t\tthis.empty().append( value );\n\t\t\t}\n\t\t}, null, value, arguments.length );\n\t},\n\n\treplaceWith: function() {\n\t\tvar ignored = [];\n\n\t\t// Make the changes, replacing each non-ignored context element with the new content\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tvar parent = this.parentNode;\n\n\t\t\tif ( jQuery.inArray( this, ignored ) < 0 ) {\n\t\t\t\tjQuery.cleanData( getAll( this ) );\n\t\t\t\tif ( parent ) {\n\t\t\t\t\tparent.replaceChild( elem, this );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Force callback invocation\n\t\t}, ignored );\n\t}\n} );\n\njQuery.each( {\n\tappendTo: \"append\",\n\tprependTo: \"prepend\",\n\tinsertBefore: \"before\",\n\tinsertAfter: \"after\",\n\treplaceAll: \"replaceWith\"\n}, function( name, original ) {\n\tjQuery.fn[ name ] = function( selector ) {\n\t\tvar elems,\n\t\t\tret = [],\n\t\t\tinsert = jQuery( selector ),\n\t\t\tlast = insert.length - 1,\n\t\t\ti = 0;\n\n\t\tfor ( ; i <= last; i++ ) {\n\t\t\telems = i === last ? this : this.clone( true );\n\t\t\tjQuery( insert[ i ] )[ original ]( elems );\n\n\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t// .get() because push.apply(_, arraylike) throws on ancient WebKit\n\t\t\tpush.apply( ret, elems.get() );\n\t\t}\n\n\t\treturn this.pushStack( ret );\n\t};\n} );\nvar rnumnonpx = new RegExp( \"^(\" + pnum + \")(?!px)[a-z%]+$\", \"i\" );\n\nvar getStyles = function( elem ) {\n\n\t\t// Support: IE <=11 only, Firefox <=30 (#15098, #14150)\n\t\t// IE throws on elements created in popups\n\t\t// FF meanwhile throws on frame elements through \"defaultView.getComputedStyle\"\n\t\tvar view = elem.ownerDocument.defaultView;\n\n\t\tif ( !view || !view.opener ) {\n\t\t\tview = window;\n\t\t}\n\n\t\treturn view.getComputedStyle( elem );\n\t};\n\nvar rboxStyle = new RegExp( cssExpand.join( \"|\" ), \"i\" );\n\n\n\n( function() {\n\n\t// Executing both pixelPosition & boxSizingReliable tests require only one layout\n\t// so they're executed at the same time to save the second computation.\n\tfunction computeStyleTests() {\n\n\t\t// This is a singleton, we need to execute it only once\n\t\tif ( !div ) {\n\t\t\treturn;\n\t\t}\n\n\t\tcontainer.style.cssText = \"position:absolute;left:-11111px;width:60px;\" +\n\t\t\t\"margin-top:1px;padding:0;border:0\";\n\t\tdiv.style.cssText =\n\t\t\t\"position:relative;display:block;box-sizing:border-box;overflow:scroll;\" +\n\t\t\t\"margin:auto;border:1px;padding:1px;\" +\n\t\t\t\"width:60%;top:1%\";\n\t\tdocumentElement.appendChild( container ).appendChild( div );\n\n\t\tvar divStyle = window.getComputedStyle( div );\n\t\tpixelPositionVal = divStyle.top !== \"1%\";\n\n\t\t// Support: Android 4.0 - 4.3 only, Firefox <=3 - 44\n\t\treliableMarginLeftVal = roundPixelMeasures( divStyle.marginLeft ) === 12;\n\n\t\t// Support: Android 4.0 - 4.3 only, Safari <=9.1 - 10.1, iOS <=7.0 - 9.3\n\t\t// Some styles come back with percentage values, even though they shouldn't\n\t\tdiv.style.right = \"60%\";\n\t\tpixelBoxStylesVal = roundPixelMeasures( divStyle.right ) === 36;\n\n\t\t// Support: IE 9 - 11 only\n\t\t// Detect misreporting of content dimensions for box-sizing:border-box elements\n\t\tboxSizingReliableVal = roundPixelMeasures( divStyle.width ) === 36;\n\n\t\t// Support: IE 9 only\n\t\t// Detect overflow:scroll screwiness (gh-3699)\n\t\t// Support: Chrome <=64\n\t\t// Don't get tricked when zoom affects offsetWidth (gh-4029)\n\t\tdiv.style.position = \"absolute\";\n\t\tscrollboxSizeVal = roundPixelMeasures( div.offsetWidth / 3 ) === 12;\n\n\t\tdocumentElement.removeChild( container );\n\n\t\t// Nullify the div so it wouldn't be stored in the memory and\n\t\t// it will also be a sign that checks already performed\n\t\tdiv = null;\n\t}\n\n\tfunction roundPixelMeasures( measure ) {\n\t\treturn Math.round( parseFloat( measure ) );\n\t}\n\n\tvar pixelPositionVal, boxSizingReliableVal, scrollboxSizeVal, pixelBoxStylesVal,\n\t\treliableMarginLeftVal,\n\t\tcontainer = document.createElement( \"div\" ),\n\t\tdiv = document.createElement( \"div\" );\n\n\t// Finish early in limited (non-browser) environments\n\tif ( !div.style ) {\n\t\treturn;\n\t}\n\n\t// Support: IE <=9 - 11 only\n\t// Style of cloned element affects source element cloned (#8908)\n\tdiv.style.backgroundClip = \"content-box\";\n\tdiv.cloneNode( true ).style.backgroundClip = \"\";\n\tsupport.clearCloneStyle = div.style.backgroundClip === \"content-box\";\n\n\tjQuery.extend( support, {\n\t\tboxSizingReliable: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn boxSizingReliableVal;\n\t\t},\n\t\tpixelBoxStyles: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelBoxStylesVal;\n\t\t},\n\t\tpixelPosition: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelPositionVal;\n\t\t},\n\t\treliableMarginLeft: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn reliableMarginLeftVal;\n\t\t},\n\t\tscrollboxSize: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn scrollboxSizeVal;\n\t\t}\n\t} );\n} )();\n\n\nfunction curCSS( elem, name, computed ) {\n\tvar width, minWidth, maxWidth, ret,\n\n\t\t// Support: Firefox 51+\n\t\t// Retrieving style before computed somehow\n\t\t// fixes an issue with getting wrong values\n\t\t// on detached elements\n\t\tstyle = elem.style;\n\n\tcomputed = computed || getStyles( elem );\n\n\t// getPropertyValue is needed for:\n\t//   .css('filter') (IE 9 only, #12537)\n\t//   .css('--customProperty) (#3144)\n\tif ( computed ) {\n\t\tret = computed.getPropertyValue( name ) || computed[ name ];\n\n\t\tif ( ret === \"\" && !isAttached( elem ) ) {\n\t\t\tret = jQuery.style( elem, name );\n\t\t}\n\n\t\t// A tribute to the \"awesome hack by Dean Edwards\"\n\t\t// Android Browser returns percentage for some values,\n\t\t// but width seems to be reliably pixels.\n\t\t// This is against the CSSOM draft spec:\n\t\t// https://drafts.csswg.org/cssom/#resolved-values\n\t\tif ( !support.pixelBoxStyles() && rnumnonpx.test( ret ) && rboxStyle.test( name ) ) {\n\n\t\t\t// Remember the original values\n\t\t\twidth = style.width;\n\t\t\tminWidth = style.minWidth;\n\t\t\tmaxWidth = style.maxWidth;\n\n\t\t\t// Put in the new values to get a computed value out\n\t\t\tstyle.minWidth = style.maxWidth = style.width = ret;\n\t\t\tret = computed.width;\n\n\t\t\t// Revert the changed values\n\t\t\tstyle.width = width;\n\t\t\tstyle.minWidth = minWidth;\n\t\t\tstyle.maxWidth = maxWidth;\n\t\t}\n\t}\n\n\treturn ret !== undefined ?\n\n\t\t// Support: IE <=9 - 11 only\n\t\t// IE returns zIndex value as an integer.\n\t\tret + \"\" :\n\t\tret;\n}\n\n\nfunction addGetHookIf( conditionFn, hookFn ) {\n\n\t// Define the hook, we'll check on the first run if it's really needed.\n\treturn {\n\t\tget: function() {\n\t\t\tif ( conditionFn() ) {\n\n\t\t\t\t// Hook not needed (or it's not possible to use it due\n\t\t\t\t// to missing dependency), remove it.\n\t\t\t\tdelete this.get;\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Hook needed; redefine it so that the support test is not executed again.\n\t\t\treturn ( this.get = hookFn ).apply( this, arguments );\n\t\t}\n\t};\n}\n\n\nvar cssPrefixes = [ \"Webkit\", \"Moz\", \"ms\" ],\n\temptyStyle = document.createElement( \"div\" ).style,\n\tvendorProps = {};\n\n// Return a vendor-prefixed property or undefined\nfunction vendorPropName( name ) {\n\n\t// Check for vendor prefixed names\n\tvar capName = name[ 0 ].toUpperCase() + name.slice( 1 ),\n\t\ti = cssPrefixes.length;\n\n\twhile ( i-- ) {\n\t\tname = cssPrefixes[ i ] + capName;\n\t\tif ( name in emptyStyle ) {\n\t\t\treturn name;\n\t\t}\n\t}\n}\n\n// Return a potentially-mapped jQuery.cssProps or vendor prefixed property\nfunction finalPropName( name ) {\n\tvar final = jQuery.cssProps[ name ] || vendorProps[ name ];\n\n\tif ( final ) {\n\t\treturn final;\n\t}\n\tif ( name in emptyStyle ) {\n\t\treturn name;\n\t}\n\treturn vendorProps[ name ] = vendorPropName( name ) || name;\n}\n\n\nvar\n\n\t// Swappable if display is none or starts with table\n\t// except \"table\", \"table-cell\", or \"table-caption\"\n\t// See here for display values: https://developer.mozilla.org/en-US/docs/CSS/display\n\trdisplayswap = /^(none|table(?!-c[ea]).+)/,\n\trcustomProp = /^--/,\n\tcssShow = { position: \"absolute\", visibility: \"hidden\", display: \"block\" },\n\tcssNormalTransform = {\n\t\tletterSpacing: \"0\",\n\t\tfontWeight: \"400\"\n\t};\n\nfunction setPositiveNumber( elem, value, subtract ) {\n\n\t// Any relative (+/-) values have already been\n\t// normalized at this point\n\tvar matches = rcssNum.exec( value );\n\treturn matches ?\n\n\t\t// Guard against undefined \"subtract\", e.g., when used as in cssHooks\n\t\tMath.max( 0, matches[ 2 ] - ( subtract || 0 ) ) + ( matches[ 3 ] || \"px\" ) :\n\t\tvalue;\n}\n\nfunction boxModelAdjustment( elem, dimension, box, isBorderBox, styles, computedVal ) {\n\tvar i = dimension === \"width\" ? 1 : 0,\n\t\textra = 0,\n\t\tdelta = 0;\n\n\t// Adjustment may not be necessary\n\tif ( box === ( isBorderBox ? \"border\" : \"content\" ) ) {\n\t\treturn 0;\n\t}\n\n\tfor ( ; i < 4; i += 2 ) {\n\n\t\t// Both box models exclude margin\n\t\tif ( box === \"margin\" ) {\n\t\t\tdelta += jQuery.css( elem, box + cssExpand[ i ], true, styles );\n\t\t}\n\n\t\t// If we get here with a content-box, we're seeking \"padding\" or \"border\" or \"margin\"\n\t\tif ( !isBorderBox ) {\n\n\t\t\t// Add padding\n\t\t\tdelta += jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\n\t\t\t// For \"border\" or \"margin\", add border\n\t\t\tif ( box !== \"padding\" ) {\n\t\t\t\tdelta += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\n\t\t\t// But still keep track of it otherwise\n\t\t\t} else {\n\t\t\t\textra += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\n\t\t// If we get here with a border-box (content + padding + border), we're seeking \"content\" or\n\t\t// \"padding\" or \"margin\"\n\t\t} else {\n\n\t\t\t// For \"content\", subtract padding\n\t\t\tif ( box === \"content\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\t\t\t}\n\n\t\t\t// For \"content\" or \"padding\", subtract border\n\t\t\tif ( box !== \"margin\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Account for positive content-box scroll gutter when requested by providing computedVal\n\tif ( !isBorderBox && computedVal >= 0 ) {\n\n\t\t// offsetWidth/offsetHeight is a rounded sum of content, padding, scroll gutter, and border\n\t\t// Assuming integer scroll gutter, subtract the rest and round down\n\t\tdelta += Math.max( 0, Math.ceil(\n\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\tcomputedVal -\n\t\t\tdelta -\n\t\t\textra -\n\t\t\t0.5\n\n\t\t// If offsetWidth/offsetHeight is unknown, then we can't determine content-box scroll gutter\n\t\t// Use an explicit zero to avoid NaN (gh-3964)\n\t\t) ) || 0;\n\t}\n\n\treturn delta;\n}\n\nfunction getWidthOrHeight( elem, dimension, extra ) {\n\n\t// Start with computed style\n\tvar styles = getStyles( elem ),\n\n\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-4322).\n\t\t// Fake content-box until we know it's needed to know the true value.\n\t\tboxSizingNeeded = !support.boxSizingReliable() || extra,\n\t\tisBorderBox = boxSizingNeeded &&\n\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\tvalueIsBorderBox = isBorderBox,\n\n\t\tval = curCSS( elem, dimension, styles ),\n\t\toffsetProp = \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 );\n\n\t// Support: Firefox <=54\n\t// Return a confounding non-pixel value or feign ignorance, as appropriate.\n\tif ( rnumnonpx.test( val ) ) {\n\t\tif ( !extra ) {\n\t\t\treturn val;\n\t\t}\n\t\tval = \"auto\";\n\t}\n\n\n\t// Fall back to offsetWidth/offsetHeight when value is \"auto\"\n\t// This happens for inline elements with no explicit setting (gh-3571)\n\t// Support: Android <=4.1 - 4.3 only\n\t// Also use offsetWidth/offsetHeight for misreported inline dimensions (gh-3602)\n\t// Support: IE 9-11 only\n\t// Also use offsetWidth/offsetHeight for when box sizing is unreliable\n\t// We use getClientRects() to check for hidden/disconnected.\n\t// In those cases, the computed value can be trusted to be border-box\n\tif ( ( !support.boxSizingReliable() && isBorderBox ||\n\t\tval === \"auto\" ||\n\t\t!parseFloat( val ) && jQuery.css( elem, \"display\", false, styles ) === \"inline\" ) &&\n\t\telem.getClientRects().length ) {\n\n\t\tisBorderBox = jQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\";\n\n\t\t// Where available, offsetWidth/offsetHeight approximate border box dimensions.\n\t\t// Where not available (e.g., SVG), assume unreliable box-sizing and interpret the\n\t\t// retrieved value as a content box dimension.\n\t\tvalueIsBorderBox = offsetProp in elem;\n\t\tif ( valueIsBorderBox ) {\n\t\t\tval = elem[ offsetProp ];\n\t\t}\n\t}\n\n\t// Normalize \"\" and auto\n\tval = parseFloat( val ) || 0;\n\n\t// Adjust for the element's box model\n\treturn ( val +\n\t\tboxModelAdjustment(\n\t\t\telem,\n\t\t\tdimension,\n\t\t\textra || ( isBorderBox ? \"border\" : \"content\" ),\n\t\t\tvalueIsBorderBox,\n\t\t\tstyles,\n\n\t\t\t// Provide the current computed size to request scroll gutter calculation (gh-3589)\n\t\t\tval\n\t\t)\n\t) + \"px\";\n}\n\njQuery.extend( {\n\n\t// Add in style property hooks for overriding the default\n\t// behavior of getting and setting a style property\n\tcssHooks: {\n\t\topacity: {\n\t\t\tget: function( elem, computed ) {\n\t\t\t\tif ( computed ) {\n\n\t\t\t\t\t// We should always get a number back from opacity\n\t\t\t\t\tvar ret = curCSS( elem, \"opacity\" );\n\t\t\t\t\treturn ret === \"\" ? \"1\" : ret;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\t// Don't automatically add \"px\" to these possibly-unitless properties\n\tcssNumber: {\n\t\t\"animationIterationCount\": true,\n\t\t\"columnCount\": true,\n\t\t\"fillOpacity\": true,\n\t\t\"flexGrow\": true,\n\t\t\"flexShrink\": true,\n\t\t\"fontWeight\": true,\n\t\t\"gridArea\": true,\n\t\t\"gridColumn\": true,\n\t\t\"gridColumnEnd\": true,\n\t\t\"gridColumnStart\": true,\n\t\t\"gridRow\": true,\n\t\t\"gridRowEnd\": true,\n\t\t\"gridRowStart\": true,\n\t\t\"lineHeight\": true,\n\t\t\"opacity\": true,\n\t\t\"order\": true,\n\t\t\"orphans\": true,\n\t\t\"widows\": true,\n\t\t\"zIndex\": true,\n\t\t\"zoom\": true\n\t},\n\n\t// Add in properties whose names you wish to fix before\n\t// setting or getting the value\n\tcssProps: {},\n\n\t// Get and set the style property on a DOM Node\n\tstyle: function( elem, name, value, extra ) {\n\n\t\t// Don't set styles on text and comment nodes\n\t\tif ( !elem || elem.nodeType === 3 || elem.nodeType === 8 || !elem.style ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Make sure that we're working with the right name\n\t\tvar ret, type, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name ),\n\t\t\tstyle = elem.style;\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to query the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Gets hook for the prefixed version, then unprefixed version\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// Check if we're setting a value\n\t\tif ( value !== undefined ) {\n\t\t\ttype = typeof value;\n\n\t\t\t// Convert \"+=\" or \"-=\" to relative numbers (#7345)\n\t\t\tif ( type === \"string\" && ( ret = rcssNum.exec( value ) ) && ret[ 1 ] ) {\n\t\t\t\tvalue = adjustCSS( elem, name, ret );\n\n\t\t\t\t// Fixes bug #9237\n\t\t\t\ttype = \"number\";\n\t\t\t}\n\n\t\t\t// Make sure that null and NaN values aren't set (#7116)\n\t\t\tif ( value == null || value !== value ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// If a number was passed in, add the unit (except for certain CSS properties)\n\t\t\t// The isCustomProp check can be removed in jQuery 4.0 when we only auto-append\n\t\t\t// \"px\" to a few hardcoded values.\n\t\t\tif ( type === \"number\" && !isCustomProp ) {\n\t\t\t\tvalue += ret && ret[ 3 ] || ( jQuery.cssNumber[ origName ] ? \"\" : \"px\" );\n\t\t\t}\n\n\t\t\t// background-* props affect original clone's values\n\t\t\tif ( !support.clearCloneStyle && value === \"\" && name.indexOf( \"background\" ) === 0 ) {\n\t\t\t\tstyle[ name ] = \"inherit\";\n\t\t\t}\n\n\t\t\t// If a hook was provided, use that value, otherwise just set the specified value\n\t\t\tif ( !hooks || !( \"set\" in hooks ) ||\n\t\t\t\t( value = hooks.set( elem, value, extra ) ) !== undefined ) {\n\n\t\t\t\tif ( isCustomProp ) {\n\t\t\t\t\tstyle.setProperty( name, value );\n\t\t\t\t} else {\n\t\t\t\t\tstyle[ name ] = value;\n\t\t\t\t}\n\t\t\t}\n\n\t\t} else {\n\n\t\t\t// If a hook was provided get the non-computed value from there\n\t\t\tif ( hooks && \"get\" in hooks &&\n\t\t\t\t( ret = hooks.get( elem, false, extra ) ) !== undefined ) {\n\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\t// Otherwise just get the value from the style object\n\t\t\treturn style[ name ];\n\t\t}\n\t},\n\n\tcss: function( elem, name, extra, styles ) {\n\t\tvar val, num, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name );\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to modify the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Try prefixed name followed by the unprefixed name\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// If a hook was provided get the computed value from there\n\t\tif ( hooks && \"get\" in hooks ) {\n\t\t\tval = hooks.get( elem, true, extra );\n\t\t}\n\n\t\t// Otherwise, if a way to get the computed value exists, use that\n\t\tif ( val === undefined ) {\n\t\t\tval = curCSS( elem, name, styles );\n\t\t}\n\n\t\t// Convert \"normal\" to computed value\n\t\tif ( val === \"normal\" && name in cssNormalTransform ) {\n\t\t\tval = cssNormalTransform[ name ];\n\t\t}\n\n\t\t// Make numeric if forced or a qualifier was provided and val looks numeric\n\t\tif ( extra === \"\" || extra ) {\n\t\t\tnum = parseFloat( val );\n\t\t\treturn extra === true || isFinite( num ) ? num || 0 : val;\n\t\t}\n\n\t\treturn val;\n\t}\n} );\n\njQuery.each( [ \"height\", \"width\" ], function( i, dimension ) {\n\tjQuery.cssHooks[ dimension ] = {\n\t\tget: function( elem, computed, extra ) {\n\t\t\tif ( computed ) {\n\n\t\t\t\t// Certain elements can have dimension info if we invisibly show them\n\t\t\t\t// but it must have a current display style that would benefit\n\t\t\t\treturn rdisplayswap.test( jQuery.css( elem, \"display\" ) ) &&\n\n\t\t\t\t\t// Support: Safari 8+\n\t\t\t\t\t// Table columns in Safari have non-zero offsetWidth & zero\n\t\t\t\t\t// getBoundingClientRect().width unless display is changed.\n\t\t\t\t\t// Support: IE <=11 only\n\t\t\t\t\t// Running getBoundingClientRect on a disconnected node\n\t\t\t\t\t// in IE throws an error.\n\t\t\t\t\t( !elem.getClientRects().length || !elem.getBoundingClientRect().width ) ?\n\t\t\t\t\t\tswap( elem, cssShow, function() {\n\t\t\t\t\t\t\treturn getWidthOrHeight( elem, dimension, extra );\n\t\t\t\t\t\t} ) :\n\t\t\t\t\t\tgetWidthOrHeight( elem, dimension, extra );\n\t\t\t}\n\t\t},\n\n\t\tset: function( elem, value, extra ) {\n\t\t\tvar matches,\n\t\t\t\tstyles = getStyles( elem ),\n\n\t\t\t\t// Only read styles.position if the test has a chance to fail\n\t\t\t\t// to avoid forcing a reflow.\n\t\t\t\tscrollboxSizeBuggy = !support.scrollboxSize() &&\n\t\t\t\t\tstyles.position === \"absolute\",\n\n\t\t\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-3991)\n\t\t\t\tboxSizingNeeded = scrollboxSizeBuggy || extra,\n\t\t\t\tisBorderBox = boxSizingNeeded &&\n\t\t\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\t\t\tsubtract = extra ?\n\t\t\t\t\tboxModelAdjustment(\n\t\t\t\t\t\telem,\n\t\t\t\t\t\tdimension,\n\t\t\t\t\t\textra,\n\t\t\t\t\t\tisBorderBox,\n\t\t\t\t\t\tstyles\n\t\t\t\t\t) :\n\t\t\t\t\t0;\n\n\t\t\t// Account for unreliable border-box dimensions by comparing offset* to computed and\n\t\t\t// faking a content-box to get border and padding (gh-3699)\n\t\t\tif ( isBorderBox && scrollboxSizeBuggy ) {\n\t\t\t\tsubtract -= Math.ceil(\n\t\t\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\t\t\tparseFloat( styles[ dimension ] ) -\n\t\t\t\t\tboxModelAdjustment( elem, dimension, \"border\", false, styles ) -\n\t\t\t\t\t0.5\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// Convert to pixels if value adjustment is needed\n\t\t\tif ( subtract && ( matches = rcssNum.exec( value ) ) &&\n\t\t\t\t( matches[ 3 ] || \"px\" ) !== \"px\" ) {\n\n\t\t\t\telem.style[ dimension ] = value;\n\t\t\t\tvalue = jQuery.css( elem, dimension );\n\t\t\t}\n\n\t\t\treturn setPositiveNumber( elem, value, subtract );\n\t\t}\n\t};\n} );\n\njQuery.cssHooks.marginLeft = addGetHookIf( support.reliableMarginLeft,\n\tfunction( elem, computed ) {\n\t\tif ( computed ) {\n\t\t\treturn ( parseFloat( curCSS( elem, \"marginLeft\" ) ) ||\n\t\t\t\telem.getBoundingClientRect().left -\n\t\t\t\t\tswap( elem, { marginLeft: 0 }, function() {\n\t\t\t\t\t\treturn elem.getBoundingClientRect().left;\n\t\t\t\t\t} )\n\t\t\t\t) + \"px\";\n\t\t}\n\t}\n);\n\n// These hooks are used by animate to expand properties\njQuery.each( {\n\tmargin: \"\",\n\tpadding: \"\",\n\tborder: \"Width\"\n}, function( prefix, suffix ) {\n\tjQuery.cssHooks[ prefix + suffix ] = {\n\t\texpand: function( value ) {\n\t\t\tvar i = 0,\n\t\t\t\texpanded = {},\n\n\t\t\t\t// Assumes a single number if not a string\n\t\t\t\tparts = typeof value === \"string\" ? value.split( \" \" ) : [ value ];\n\n\t\t\tfor ( ; i < 4; i++ ) {\n\t\t\t\texpanded[ prefix + cssExpand[ i ] + suffix ] =\n\t\t\t\t\tparts[ i ] || parts[ i - 2 ] || parts[ 0 ];\n\t\t\t}\n\n\t\t\treturn expanded;\n\t\t}\n\t};\n\n\tif ( prefix !== \"margin\" ) {\n\t\tjQuery.cssHooks[ prefix + suffix ].set = setPositiveNumber;\n\t}\n} );\n\njQuery.fn.extend( {\n\tcss: function( name, value ) {\n\t\treturn access( this, function( elem, name, value ) {\n\t\t\tvar styles, len,\n\t\t\t\tmap = {},\n\t\t\t\ti = 0;\n\n\t\t\tif ( Array.isArray( name ) ) {\n\t\t\t\tstyles = getStyles( elem );\n\t\t\t\tlen = name.length;\n\n\t\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\t\tmap[ name[ i ] ] = jQuery.css( elem, name[ i ], false, styles );\n\t\t\t\t}\n\n\t\t\t\treturn map;\n\t\t\t}\n\n\t\t\treturn value !== undefined ?\n\t\t\t\tjQuery.style( elem, name, value ) :\n\t\t\t\tjQuery.css( elem, name );\n\t\t}, name, value, arguments.length > 1 );\n\t}\n} );\n\n\nfunction Tween( elem, options, prop, end, easing ) {\n\treturn new Tween.prototype.init( elem, options, prop, end, easing );\n}\njQuery.Tween = Tween;\n\nTween.prototype = {\n\tconstructor: Tween,\n\tinit: function( elem, options, prop, end, easing, unit ) {\n\t\tthis.elem = elem;\n\t\tthis.prop = prop;\n\t\tthis.easing = easing || jQuery.easing._default;\n\t\tthis.options = options;\n\t\tthis.start = this.now = this.cur();\n\t\tthis.end = end;\n\t\tthis.unit = unit || ( jQuery.cssNumber[ prop ] ? \"\" : \"px\" );\n\t},\n\tcur: function() {\n\t\tvar hooks = Tween.propHooks[ this.prop ];\n\n\t\treturn hooks && hooks.get ?\n\t\t\thooks.get( this ) :\n\t\t\tTween.propHooks._default.get( this );\n\t},\n\trun: function( percent ) {\n\t\tvar eased,\n\t\t\thooks = Tween.propHooks[ this.prop ];\n\n\t\tif ( this.options.duration ) {\n\t\t\tthis.pos = eased = jQuery.easing[ this.easing ](\n\t\t\t\tpercent, this.options.duration * percent, 0, 1, this.options.duration\n\t\t\t);\n\t\t} else {\n\t\t\tthis.pos = eased = percent;\n\t\t}\n\t\tthis.now = ( this.end - this.start ) * eased + this.start;\n\n\t\tif ( this.options.step ) {\n\t\t\tthis.options.step.call( this.elem, this.now, this );\n\t\t}\n\n\t\tif ( hooks && hooks.set ) {\n\t\t\thooks.set( this );\n\t\t} else {\n\t\t\tTween.propHooks._default.set( this );\n\t\t}\n\t\treturn this;\n\t}\n};\n\nTween.prototype.init.prototype = Tween.prototype;\n\nTween.propHooks = {\n\t_default: {\n\t\tget: function( tween ) {\n\t\t\tvar result;\n\n\t\t\t// Use a property on the element directly when it is not a DOM element,\n\t\t\t// or when there is no matching style property that exists.\n\t\t\tif ( tween.elem.nodeType !== 1 ||\n\t\t\t\ttween.elem[ tween.prop ] != null && tween.elem.style[ tween.prop ] == null ) {\n\t\t\t\treturn tween.elem[ tween.prop ];\n\t\t\t}\n\n\t\t\t// Passing an empty string as a 3rd parameter to .css will automatically\n\t\t\t// attempt a parseFloat and fallback to a string if the parse fails.\n\t\t\t// Simple values such as \"10px\" are parsed to Float;\n\t\t\t// complex values such as \"rotate(1rad)\" are returned as-is.\n\t\t\tresult = jQuery.css( tween.elem, tween.prop, \"\" );\n\n\t\t\t// Empty strings, null, undefined and \"auto\" are converted to 0.\n\t\t\treturn !result || result === \"auto\" ? 0 : result;\n\t\t},\n\t\tset: function( tween ) {\n\n\t\t\t// Use step hook for back compat.\n\t\t\t// Use cssHook if its there.\n\t\t\t// Use .style if available and use plain properties where available.\n\t\t\tif ( jQuery.fx.step[ tween.prop ] ) {\n\t\t\t\tjQuery.fx.step[ tween.prop ]( tween );\n\t\t\t} else if ( tween.elem.nodeType === 1 && (\n\t\t\t\t\tjQuery.cssHooks[ tween.prop ] ||\n\t\t\t\t\ttween.elem.style[ finalPropName( tween.prop ) ] != null ) ) {\n\t\t\t\tjQuery.style( tween.elem, tween.prop, tween.now + tween.unit );\n\t\t\t} else {\n\t\t\t\ttween.elem[ tween.prop ] = tween.now;\n\t\t\t}\n\t\t}\n\t}\n};\n\n// Support: IE <=9 only\n// Panic based approach to setting things on disconnected nodes\nTween.propHooks.scrollTop = Tween.propHooks.scrollLeft = {\n\tset: function( tween ) {\n\t\tif ( tween.elem.nodeType && tween.elem.parentNode ) {\n\t\t\ttween.elem[ tween.prop ] = tween.now;\n\t\t}\n\t}\n};\n\njQuery.easing = {\n\tlinear: function( p ) {\n\t\treturn p;\n\t},\n\tswing: function( p ) {\n\t\treturn 0.5 - Math.cos( p * Math.PI ) / 2;\n\t},\n\t_default: \"swing\"\n};\n\njQuery.fx = Tween.prototype.init;\n\n// Back compat <1.8 extension point\njQuery.fx.step = {};\n\n\n\n\nvar\n\tfxNow, inProgress,\n\trfxtypes = /^(?:toggle|show|hide)$/,\n\trrun = /queueHooks$/;\n\nfunction schedule() {\n\tif ( inProgress ) {\n\t\tif ( document.hidden === false && window.requestAnimationFrame ) {\n\t\t\twindow.requestAnimationFrame( schedule );\n\t\t} else {\n\t\t\twindow.setTimeout( schedule, jQuery.fx.interval );\n\t\t}\n\n\t\tjQuery.fx.tick();\n\t}\n}\n\n// Animations created synchronously will run synchronously\nfunction createFxNow() {\n\twindow.setTimeout( function() {\n\t\tfxNow = undefined;\n\t} );\n\treturn ( fxNow = Date.now() );\n}\n\n// Generate parameters to create a standard animation\nfunction genFx( type, includeWidth ) {\n\tvar which,\n\t\ti = 0,\n\t\tattrs = { height: type };\n\n\t// If we include width, step value is 1 to do all cssExpand values,\n\t// otherwise step value is 2 to skip over Left and Right\n\tincludeWidth = includeWidth ? 1 : 0;\n\tfor ( ; i < 4; i += 2 - includeWidth ) {\n\t\twhich = cssExpand[ i ];\n\t\tattrs[ \"margin\" + which ] = attrs[ \"padding\" + which ] = type;\n\t}\n\n\tif ( includeWidth ) {\n\t\tattrs.opacity = attrs.width = type;\n\t}\n\n\treturn attrs;\n}\n\nfunction createTween( value, prop, animation ) {\n\tvar tween,\n\t\tcollection = ( Animation.tweeners[ prop ] || [] ).concat( Animation.tweeners[ \"*\" ] ),\n\t\tindex = 0,\n\t\tlength = collection.length;\n\tfor ( ; index < length; index++ ) {\n\t\tif ( ( tween = collection[ index ].call( animation, prop, value ) ) ) {\n\n\t\t\t// We're done with this property\n\t\t\treturn tween;\n\t\t}\n\t}\n}\n\nfunction defaultPrefilter( elem, props, opts ) {\n\tvar prop, value, toggle, hooks, oldfire, propTween, restoreDisplay, display,\n\t\tisBox = \"width\" in props || \"height\" in props,\n\t\tanim = this,\n\t\torig = {},\n\t\tstyle = elem.style,\n\t\thidden = elem.nodeType && isHiddenWithinTree( elem ),\n\t\tdataShow = dataPriv.get( elem, \"fxshow\" );\n\n\t// Queue-skipping animations hijack the fx hooks\n\tif ( !opts.queue ) {\n\t\thooks = jQuery._queueHooks( elem, \"fx\" );\n\t\tif ( hooks.unqueued == null ) {\n\t\t\thooks.unqueued = 0;\n\t\t\toldfire = hooks.empty.fire;\n\t\t\thooks.empty.fire = function() {\n\t\t\t\tif ( !hooks.unqueued ) {\n\t\t\t\t\toldfire();\n\t\t\t\t}\n\t\t\t};\n\t\t}\n\t\thooks.unqueued++;\n\n\t\tanim.always( function() {\n\n\t\t\t// Ensure the complete handler is called before this completes\n\t\t\tanim.always( function() {\n\t\t\t\thooks.unqueued--;\n\t\t\t\tif ( !jQuery.queue( elem, \"fx\" ).length ) {\n\t\t\t\t\thooks.empty.fire();\n\t\t\t\t}\n\t\t\t} );\n\t\t} );\n\t}\n\n\t// Detect show/hide animations\n\tfor ( prop in props ) {\n\t\tvalue = props[ prop ];\n\t\tif ( rfxtypes.test( value ) ) {\n\t\t\tdelete props[ prop ];\n\t\t\ttoggle = toggle || value === \"toggle\";\n\t\t\tif ( value === ( hidden ? \"hide\" : \"show\" ) ) {\n\n\t\t\t\t// Pretend to be hidden if this is a \"show\" and\n\t\t\t\t// there is still data from a stopped show/hide\n\t\t\t\tif ( value === \"show\" && dataShow && dataShow[ prop ] !== undefined ) {\n\t\t\t\t\thidden = true;\n\n\t\t\t\t// Ignore all other no-op show/hide data\n\t\t\t\t} else {\n\t\t\t\t\tcontinue;\n\t\t\t\t}\n\t\t\t}\n\t\t\torig[ prop ] = dataShow && dataShow[ prop ] || jQuery.style( elem, prop );\n\t\t}\n\t}\n\n\t// Bail out if this is a no-op like .hide().hide()\n\tpropTween = !jQuery.isEmptyObject( props );\n\tif ( !propTween && jQuery.isEmptyObject( orig ) ) {\n\t\treturn;\n\t}\n\n\t// Restrict \"overflow\" and \"display\" styles during box animations\n\tif ( isBox && elem.nodeType === 1 ) {\n\n\t\t// Support: IE <=9 - 11, Edge 12 - 15\n\t\t// Record all 3 overflow attributes because IE does not infer the shorthand\n\t\t// from identically-valued overflowX and overflowY and Edge just mirrors\n\t\t// the overflowX value there.\n\t\topts.overflow = [ style.overflow, style.overflowX, style.overflowY ];\n\n\t\t// Identify a display type, preferring old show/hide data over the CSS cascade\n\t\trestoreDisplay = dataShow && dataShow.display;\n\t\tif ( restoreDisplay == null ) {\n\t\t\trestoreDisplay = dataPriv.get( elem, \"display\" );\n\t\t}\n\t\tdisplay = jQuery.css( elem, \"display\" );\n\t\tif ( display === \"none\" ) {\n\t\t\tif ( restoreDisplay ) {\n\t\t\t\tdisplay = restoreDisplay;\n\t\t\t} else {\n\n\t\t\t\t// Get nonempty value(s) by temporarily forcing visibility\n\t\t\t\tshowHide( [ elem ], true );\n\t\t\t\trestoreDisplay = elem.style.display || restoreDisplay;\n\t\t\t\tdisplay = jQuery.css( elem, \"display\" );\n\t\t\t\tshowHide( [ elem ] );\n\t\t\t}\n\t\t}\n\n\t\t// Animate inline elements as inline-block\n\t\tif ( display === \"inline\" || display === \"inline-block\" && restoreDisplay != null ) {\n\t\t\tif ( jQuery.css( elem, \"float\" ) === \"none\" ) {\n\n\t\t\t\t// Restore the original display value at the end of pure show/hide animations\n\t\t\t\tif ( !propTween ) {\n\t\t\t\t\tanim.done( function() {\n\t\t\t\t\t\tstyle.display = restoreDisplay;\n\t\t\t\t\t} );\n\t\t\t\t\tif ( restoreDisplay == null ) {\n\t\t\t\t\t\tdisplay = style.display;\n\t\t\t\t\t\trestoreDisplay = display === \"none\" ? \"\" : display;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\tstyle.display = \"inline-block\";\n\t\t\t}\n\t\t}\n\t}\n\n\tif ( opts.overflow ) {\n\t\tstyle.overflow = \"hidden\";\n\t\tanim.always( function() {\n\t\t\tstyle.overflow = opts.overflow[ 0 ];\n\t\t\tstyle.overflowX = opts.overflow[ 1 ];\n\t\t\tstyle.overflowY = opts.overflow[ 2 ];\n\t\t} );\n\t}\n\n\t// Implement show/hide animations\n\tpropTween = false;\n\tfor ( prop in orig ) {\n\n\t\t// General show/hide setup for this element animation\n\t\tif ( !propTween ) {\n\t\t\tif ( dataShow ) {\n\t\t\t\tif ( \"hidden\" in dataShow ) {\n\t\t\t\t\thidden = dataShow.hidden;\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tdataShow = dataPriv.access( elem, \"fxshow\", { display: restoreDisplay } );\n\t\t\t}\n\n\t\t\t// Store hidden/visible for toggle so `.stop().toggle()` \"reverses\"\n\t\t\tif ( toggle ) {\n\t\t\t\tdataShow.hidden = !hidden;\n\t\t\t}\n\n\t\t\t// Show elements before animating them\n\t\t\tif ( hidden ) {\n\t\t\t\tshowHide( [ elem ], true );\n\t\t\t}\n\n\t\t\t/* eslint-disable no-loop-func */\n\n\t\t\tanim.done( function() {\n\n\t\t\t/* eslint-enable no-loop-func */\n\n\t\t\t\t// The final step of a \"hide\" animation is actually hiding the element\n\t\t\t\tif ( !hidden ) {\n\t\t\t\t\tshowHide( [ elem ] );\n\t\t\t\t}\n\t\t\t\tdataPriv.remove( elem, \"fxshow\" );\n\t\t\t\tfor ( prop in orig ) {\n\t\t\t\t\tjQuery.style( elem, prop, orig[ prop ] );\n\t\t\t\t}\n\t\t\t} );\n\t\t}\n\n\t\t// Per-property setup\n\t\tpropTween = createTween( hidden ? dataShow[ prop ] : 0, prop, anim );\n\t\tif ( !( prop in dataShow ) ) {\n\t\t\tdataShow[ prop ] = propTween.start;\n\t\t\tif ( hidden ) {\n\t\t\t\tpropTween.end = propTween.start;\n\t\t\t\tpropTween.start = 0;\n\t\t\t}\n\t\t}\n\t}\n}\n\nfunction propFilter( props, specialEasing ) {\n\tvar index, name, easing, value, hooks;\n\n\t// camelCase, specialEasing and expand cssHook pass\n\tfor ( index in props ) {\n\t\tname = camelCase( index );\n\t\teasing = specialEasing[ name ];\n\t\tvalue = props[ index ];\n\t\tif ( Array.isArray( value ) ) {\n\t\t\teasing = value[ 1 ];\n\t\t\tvalue = props[ index ] = value[ 0 ];\n\t\t}\n\n\t\tif ( index !== name ) {\n\t\t\tprops[ name ] = value;\n\t\t\tdelete props[ index ];\n\t\t}\n\n\t\thooks = jQuery.cssHooks[ name ];\n\t\tif ( hooks && \"expand\" in hooks ) {\n\t\t\tvalue = hooks.expand( value );\n\t\t\tdelete props[ name ];\n\n\t\t\t// Not quite $.extend, this won't overwrite existing keys.\n\t\t\t// Reusing 'index' because we have the correct \"name\"\n\t\t\tfor ( index in value ) {\n\t\t\t\tif ( !( index in props ) ) {\n\t\t\t\t\tprops[ index ] = value[ index ];\n\t\t\t\t\tspecialEasing[ index ] = easing;\n\t\t\t\t}\n\t\t\t}\n\t\t} else {\n\t\t\tspecialEasing[ name ] = easing;\n\t\t}\n\t}\n}\n\nfunction Animation( elem, properties, options ) {\n\tvar result,\n\t\tstopped,\n\t\tindex = 0,\n\t\tlength = Animation.prefilters.length,\n\t\tdeferred = jQuery.Deferred().always( function() {\n\n\t\t\t// Don't match elem in the :animated selector\n\t\t\tdelete tick.elem;\n\t\t} ),\n\t\ttick = function() {\n\t\t\tif ( stopped ) {\n\t\t\t\treturn false;\n\t\t\t}\n\t\t\tvar currentTime = fxNow || createFxNow(),\n\t\t\t\tremaining = Math.max( 0, animation.startTime + animation.duration - currentTime ),\n\n\t\t\t\t// Support: Android 2.3 only\n\t\t\t\t// Archaic crash bug won't allow us to use `1 - ( 0.5 || 0 )` (#12497)\n\t\t\t\ttemp = remaining / animation.duration || 0,\n\t\t\t\tpercent = 1 - temp,\n\t\t\t\tindex = 0,\n\t\t\t\tlength = animation.tweens.length;\n\n\t\t\tfor ( ; index < length; index++ ) {\n\t\t\t\tanimation.tweens[ index ].run( percent );\n\t\t\t}\n\n\t\t\tdeferred.notifyWith( elem, [ animation, percent, remaining ] );\n\n\t\t\t// If there's more to do, yield\n\t\t\tif ( percent < 1 && length ) {\n\t\t\t\treturn remaining;\n\t\t\t}\n\n\t\t\t// If this was an empty animation, synthesize a final progress notification\n\t\t\tif ( !length ) {\n\t\t\t\tdeferred.notifyWith( elem, [ animation, 1, 0 ] );\n\t\t\t}\n\n\t\t\t// Resolve the animation and report its conclusion\n\t\t\tdeferred.resolveWith( elem, [ animation ] );\n\t\t\treturn false;\n\t\t},\n\t\tanimation = deferred.promise( {\n\t\t\telem: elem,\n\t\t\tprops: jQuery.extend( {}, properties ),\n\t\t\topts: jQuery.extend( true, {\n\t\t\t\tspecialEasing: {},\n\t\t\t\teasing: jQuery.easing._default\n\t\t\t}, options ),\n\t\t\toriginalProperties: properties,\n\t\t\toriginalOptions: options,\n\t\t\tstartTime: fxNow || createFxNow(),\n\t\t\tduration: options.duration,\n\t\t\ttweens: [],\n\t\t\tcreateTween: function( prop, end ) {\n\t\t\t\tvar tween = jQuery.Tween( elem, animation.opts, prop, end,\n\t\t\t\t\t\tanimation.opts.specialEasing[ prop ] || animation.opts.easing );\n\t\t\t\tanimation.tweens.push( tween );\n\t\t\t\treturn tween;\n\t\t\t},\n\t\t\tstop: function( gotoEnd ) {\n\t\t\t\tvar index = 0,\n\n\t\t\t\t\t// If we are going to the end, we want to run all the tweens\n\t\t\t\t\t// otherwise we skip this part\n\t\t\t\t\tlength = gotoEnd ? animation.tweens.length : 0;\n\t\t\t\tif ( stopped ) {\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\t\t\t\tstopped = true;\n\t\t\t\tfor ( ; index < length; index++ ) {\n\t\t\t\t\tanimation.tweens[ index ].run( 1 );\n\t\t\t\t}\n\n\t\t\t\t// Resolve when we played the last frame; otherwise, reject\n\t\t\t\tif ( gotoEnd ) {\n\t\t\t\t\tdeferred.notifyWith( elem, [ animation, 1, 0 ] );\n\t\t\t\t\tdeferred.resolveWith( elem, [ animation, gotoEnd ] );\n\t\t\t\t} else {\n\t\t\t\t\tdeferred.rejectWith( elem, [ animation, gotoEnd ] );\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t}\n\t\t} ),\n\t\tprops = animation.props;\n\n\tpropFilter( props, animation.opts.specialEasing );\n\n\tfor ( ; index < length; index++ ) {\n\t\tresult = Animation.prefilters[ index ].call( animation, elem, props, animation.opts );\n\t\tif ( result ) {\n\t\t\tif ( isFunction( result.stop ) ) {\n\t\t\t\tjQuery._queueHooks( animation.elem, animation.opts.queue ).stop =\n\t\t\t\t\tresult.stop.bind( result );\n\t\t\t}\n\t\t\treturn result;\n\t\t}\n\t}\n\n\tjQuery.map( props, createTween, animation );\n\n\tif ( isFunction( animation.opts.start ) ) {\n\t\tanimation.opts.start.call( elem, animation );\n\t}\n\n\t// Attach callbacks from options\n\tanimation\n\t\t.progress( animation.opts.progress )\n\t\t.done( animation.opts.done, animation.opts.complete )\n\t\t.fail( animation.opts.fail )\n\t\t.always( animation.opts.always );\n\n\tjQuery.fx.timer(\n\t\tjQuery.extend( tick, {\n\t\t\telem: elem,\n\t\t\tanim: animation,\n\t\t\tqueue: animation.opts.queue\n\t\t} )\n\t);\n\n\treturn animation;\n}\n\njQuery.Animation = jQuery.extend( Animation, {\n\n\ttweeners: {\n\t\t\"*\": [ function( prop, value ) {\n\t\t\tvar tween = this.createTween( prop, value );\n\t\t\tadjustCSS( tween.elem, prop, rcssNum.exec( value ), tween );\n\t\t\treturn tween;\n\t\t} ]\n\t},\n\n\ttweener: function( props, callback ) {\n\t\tif ( isFunction( props ) ) {\n\t\t\tcallback = props;\n\t\t\tprops = [ \"*\" ];\n\t\t} else {\n\t\t\tprops = props.match( rnothtmlwhite );\n\t\t}\n\n\t\tvar prop,\n\t\t\tindex = 0,\n\t\t\tlength = props.length;\n\n\t\tfor ( ; index < length; index++ ) {\n\t\t\tprop = props[ index ];\n\t\t\tAnimation.tweeners[ prop ] = Animation.tweeners[ prop ] || [];\n\t\t\tAnimation.tweeners[ prop ].unshift( callback );\n\t\t}\n\t},\n\n\tprefilters: [ defaultPrefilter ],\n\n\tprefilter: function( callback, prepend ) {\n\t\tif ( prepend ) {\n\t\t\tAnimation.prefilters.unshift( callback );\n\t\t} else {\n\t\t\tAnimation.prefilters.push( callback );\n\t\t}\n\t}\n} );\n\njQuery.speed = function( speed, easing, fn ) {\n\tvar opt = speed && typeof speed === \"object\" ? jQuery.extend( {}, speed ) : {\n\t\tcomplete: fn || !fn && easing ||\n\t\t\tisFunction( speed ) && speed,\n\t\tduration: speed,\n\t\teasing: fn && easing || easing && !isFunction( easing ) && easing\n\t};\n\n\t// Go to the end state if fx are off\n\tif ( jQuery.fx.off ) {\n\t\topt.duration = 0;\n\n\t} else {\n\t\tif ( typeof opt.duration !== \"number\" ) {\n\t\t\tif ( opt.duration in jQuery.fx.speeds ) {\n\t\t\t\topt.duration = jQuery.fx.speeds[ opt.duration ];\n\n\t\t\t} else {\n\t\t\t\topt.duration = jQuery.fx.speeds._default;\n\t\t\t}\n\t\t}\n\t}\n\n\t// Normalize opt.queue - true/undefined/null -> \"fx\"\n\tif ( opt.queue == null || opt.queue === true ) {\n\t\topt.queue = \"fx\";\n\t}\n\n\t// Queueing\n\topt.old = opt.complete;\n\n\topt.complete = function() {\n\t\tif ( isFunction( opt.old ) ) {\n\t\t\topt.old.call( this );\n\t\t}\n\n\t\tif ( opt.queue ) {\n\t\t\tjQuery.dequeue( this, opt.queue );\n\t\t}\n\t};\n\n\treturn opt;\n};\n\njQuery.fn.extend( {\n\tfadeTo: function( speed, to, easing, callback ) {\n\n\t\t// Show any hidden elements after setting opacity to 0\n\t\treturn this.filter( isHiddenWithinTree ).css( \"opacity\", 0 ).show()\n\n\t\t\t// Animate to the value specified\n\t\t\t.end().animate( { opacity: to }, speed, easing, callback );\n\t},\n\tanimate: function( prop, speed, easing, callback ) {\n\t\tvar empty = jQuery.isEmptyObject( prop ),\n\t\t\toptall = jQuery.speed( speed, easing, callback ),\n\t\t\tdoAnimation = function() {\n\n\t\t\t\t// Operate on a copy of prop so per-property easing won't be lost\n\t\t\t\tvar anim = Animation( this, jQuery.extend( {}, prop ), optall );\n\n\t\t\t\t// Empty animations, or finishing resolves immediately\n\t\t\t\tif ( empty || dataPriv.get( this, \"finish\" ) ) {\n\t\t\t\t\tanim.stop( true );\n\t\t\t\t}\n\t\t\t};\n\t\t\tdoAnimation.finish = doAnimation;\n\n\t\treturn empty || optall.queue === false ?\n\t\t\tthis.each( doAnimation ) :\n\t\t\tthis.queue( optall.queue, doAnimation );\n\t},\n\tstop: function( type, clearQueue, gotoEnd ) {\n\t\tvar stopQueue = function( hooks ) {\n\t\t\tvar stop = hooks.stop;\n\t\t\tdelete hooks.stop;\n\t\t\tstop( gotoEnd );\n\t\t};\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tgotoEnd = clearQueue;\n\t\t\tclearQueue = type;\n\t\t\ttype = undefined;\n\t\t}\n\t\tif ( clearQueue && type !== false ) {\n\t\t\tthis.queue( type || \"fx\", [] );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar dequeue = true,\n\t\t\t\tindex = type != null && type + \"queueHooks\",\n\t\t\t\ttimers = jQuery.timers,\n\t\t\t\tdata = dataPriv.get( this );\n\n\t\t\tif ( index ) {\n\t\t\t\tif ( data[ index ] && data[ index ].stop ) {\n\t\t\t\t\tstopQueue( data[ index ] );\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tfor ( index in data ) {\n\t\t\t\t\tif ( data[ index ] && data[ index ].stop && rrun.test( index ) ) {\n\t\t\t\t\t\tstopQueue( data[ index ] );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tfor ( index = timers.length; index--; ) {\n\t\t\t\tif ( timers[ index ].elem === this &&\n\t\t\t\t\t( type == null || timers[ index ].queue === type ) ) {\n\n\t\t\t\t\ttimers[ index ].anim.stop( gotoEnd );\n\t\t\t\t\tdequeue = false;\n\t\t\t\t\ttimers.splice( index, 1 );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Start the next in the queue if the last step wasn't forced.\n\t\t\t// Timers currently will call their complete callbacks, which\n\t\t\t// will dequeue but only if they were gotoEnd.\n\t\t\tif ( dequeue || !gotoEnd ) {\n\t\t\t\tjQuery.dequeue( this, type );\n\t\t\t}\n\t\t} );\n\t},\n\tfinish: function( type ) {\n\t\tif ( type !== false ) {\n\t\t\ttype = type || \"fx\";\n\t\t}\n\t\treturn this.each( function() {\n\t\t\tvar index,\n\t\t\t\tdata = dataPriv.get( this ),\n\t\t\t\tqueue = data[ type + \"queue\" ],\n\t\t\t\thooks = data[ type + \"queueHooks\" ],\n\t\t\t\ttimers = jQuery.timers,\n\t\t\t\tlength = queue ? queue.length : 0;\n\n\t\t\t// Enable finishing flag on private data\n\t\t\tdata.finish = true;\n\n\t\t\t// Empty the queue first\n\t\t\tjQuery.queue( this, type, [] );\n\n\t\t\tif ( hooks && hooks.stop ) {\n\t\t\t\thooks.stop.call( this, true );\n\t\t\t}\n\n\t\t\t// Look for any active animations, and finish them\n\t\t\tfor ( index = timers.length; index--; ) {\n\t\t\t\tif ( timers[ index ].elem === this && timers[ index ].queue === type ) {\n\t\t\t\t\ttimers[ index ].anim.stop( true );\n\t\t\t\t\ttimers.splice( index, 1 );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Look for any animations in the old queue and finish them\n\t\t\tfor ( index = 0; index < length; index++ ) {\n\t\t\t\tif ( queue[ index ] && queue[ index ].finish ) {\n\t\t\t\t\tqueue[ index ].finish.call( this );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Turn off finishing flag\n\t\t\tdelete data.finish;\n\t\t} );\n\t}\n} );\n\njQuery.each( [ \"toggle\", \"show\", \"hide\" ], function( i, name ) {\n\tvar cssFn = jQuery.fn[ name ];\n\tjQuery.fn[ name ] = function( speed, easing, callback ) {\n\t\treturn speed == null || typeof speed === \"boolean\" ?\n\t\t\tcssFn.apply( this, arguments ) :\n\t\t\tthis.animate( genFx( name, true ), speed, easing, callback );\n\t};\n} );\n\n// Generate shortcuts for custom animations\njQuery.each( {\n\tslideDown: genFx( \"show\" ),\n\tslideUp: genFx( \"hide\" ),\n\tslideToggle: genFx( \"toggle\" ),\n\tfadeIn: { opacity: \"show\" },\n\tfadeOut: { opacity: \"hide\" },\n\tfadeToggle: { opacity: \"toggle\" }\n}, function( name, props ) {\n\tjQuery.fn[ name ] = function( speed, easing, callback ) {\n\t\treturn this.animate( props, speed, easing, callback );\n\t};\n} );\n\njQuery.timers = [];\njQuery.fx.tick = function() {\n\tvar timer,\n\t\ti = 0,\n\t\ttimers = jQuery.timers;\n\n\tfxNow = Date.now();\n\n\tfor ( ; i < timers.length; i++ ) {\n\t\ttimer = timers[ i ];\n\n\t\t// Run the timer and safely remove it when done (allowing for external removal)\n\t\tif ( !timer() && timers[ i ] === timer ) {\n\t\t\ttimers.splice( i--, 1 );\n\t\t}\n\t}\n\n\tif ( !timers.length ) {\n\t\tjQuery.fx.stop();\n\t}\n\tfxNow = undefined;\n};\n\njQuery.fx.timer = function( timer ) {\n\tjQuery.timers.push( timer );\n\tjQuery.fx.start();\n};\n\njQuery.fx.interval = 13;\njQuery.fx.start = function() {\n\tif ( inProgress ) {\n\t\treturn;\n\t}\n\n\tinProgress = true;\n\tschedule();\n};\n\njQuery.fx.stop = function() {\n\tinProgress = null;\n};\n\njQuery.fx.speeds = {\n\tslow: 600,\n\tfast: 200,\n\n\t// Default speed\n\t_default: 400\n};\n\n\n// Based off of the plugin by Clint Helfers, with permission.\n// https://web.archive.org/web/20100324014747/http://blindsignals.com/index.php/2009/07/jquery-delay/\njQuery.fn.delay = function( time, type ) {\n\ttime = jQuery.fx ? jQuery.fx.speeds[ time ] || time : time;\n\ttype = type || \"fx\";\n\n\treturn this.queue( type, function( next, hooks ) {\n\t\tvar timeout = window.setTimeout( next, time );\n\t\thooks.stop = function() {\n\t\t\twindow.clearTimeout( timeout );\n\t\t};\n\t} );\n};\n\n\n( function() {\n\tvar input = document.createElement( \"input\" ),\n\t\tselect = document.createElement( \"select\" ),\n\t\topt = select.appendChild( document.createElement( \"option\" ) );\n\n\tinput.type = \"checkbox\";\n\n\t// Support: Android <=4.3 only\n\t// Default value for a checkbox should be \"on\"\n\tsupport.checkOn = input.value !== \"\";\n\n\t// Support: IE <=11 only\n\t// Must access selectedIndex to make default options select\n\tsupport.optSelected = opt.selected;\n\n\t// Support: IE <=11 only\n\t// An input loses its value after becoming a radio\n\tinput = document.createElement( \"input\" );\n\tinput.value = \"t\";\n\tinput.type = \"radio\";\n\tsupport.radioValue = input.value === \"t\";\n} )();\n\n\nvar boolHook,\n\tattrHandle = jQuery.expr.attrHandle;\n\njQuery.fn.extend( {\n\tattr: function( name, value ) {\n\t\treturn access( this, jQuery.attr, name, value, arguments.length > 1 );\n\t},\n\n\tremoveAttr: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.removeAttr( this, name );\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tattr: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set attributes on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Fallback to prop when attributes are not supported\n\t\tif ( typeof elem.getAttribute === \"undefined\" ) {\n\t\t\treturn jQuery.prop( elem, name, value );\n\t\t}\n\n\t\t// Attribute hooks are determined by the lowercase version\n\t\t// Grab necessary hook if one is defined\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\t\t\thooks = jQuery.attrHooks[ name.toLowerCase() ] ||\n\t\t\t\t( jQuery.expr.match.bool.test( name ) ? boolHook : undefined );\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( value === null ) {\n\t\t\t\tjQuery.removeAttr( elem, name );\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\telem.setAttribute( name, value + \"\" );\n\t\t\treturn value;\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\tret = jQuery.find.attr( elem, name );\n\n\t\t// Non-existent attributes return null, we normalize to undefined\n\t\treturn ret == null ? undefined : ret;\n\t},\n\n\tattrHooks: {\n\t\ttype: {\n\t\t\tset: function( elem, value ) {\n\t\t\t\tif ( !support.radioValue && value === \"radio\" &&\n\t\t\t\t\tnodeName( elem, \"input\" ) ) {\n\t\t\t\t\tvar val = elem.value;\n\t\t\t\t\telem.setAttribute( \"type\", value );\n\t\t\t\t\tif ( val ) {\n\t\t\t\t\t\telem.value = val;\n\t\t\t\t\t}\n\t\t\t\t\treturn value;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\tremoveAttr: function( elem, value ) {\n\t\tvar name,\n\t\t\ti = 0,\n\n\t\t\t// Attribute names can contain non-HTML whitespace characters\n\t\t\t// https://html.spec.whatwg.org/multipage/syntax.html#attributes-2\n\t\t\tattrNames = value && value.match( rnothtmlwhite );\n\n\t\tif ( attrNames && elem.nodeType === 1 ) {\n\t\t\twhile ( ( name = attrNames[ i++ ] ) ) {\n\t\t\t\telem.removeAttribute( name );\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Hooks for boolean attributes\nboolHook = {\n\tset: function( elem, value, name ) {\n\t\tif ( value === false ) {\n\n\t\t\t// Remove boolean attributes when set to false\n\t\t\tjQuery.removeAttr( elem, name );\n\t\t} else {\n\t\t\telem.setAttribute( name, name );\n\t\t}\n\t\treturn name;\n\t}\n};\n\njQuery.each( jQuery.expr.match.bool.source.match( /\\w+/g ), function( i, name ) {\n\tvar getter = attrHandle[ name ] || jQuery.find.attr;\n\n\tattrHandle[ name ] = function( elem, name, isXML ) {\n\t\tvar ret, handle,\n\t\t\tlowercaseName = name.toLowerCase();\n\n\t\tif ( !isXML ) {\n\n\t\t\t// Avoid an infinite loop by temporarily removing this function from the getter\n\t\t\thandle = attrHandle[ lowercaseName ];\n\t\t\tattrHandle[ lowercaseName ] = ret;\n\t\t\tret = getter( elem, name, isXML ) != null ?\n\t\t\t\tlowercaseName :\n\t\t\t\tnull;\n\t\t\tattrHandle[ lowercaseName ] = handle;\n\t\t}\n\t\treturn ret;\n\t};\n} );\n\n\n\n\nvar rfocusable = /^(?:input|select|textarea|button)$/i,\n\trclickable = /^(?:a|area)$/i;\n\njQuery.fn.extend( {\n\tprop: function( name, value ) {\n\t\treturn access( this, jQuery.prop, name, value, arguments.length > 1 );\n\t},\n\n\tremoveProp: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tdelete this[ jQuery.propFix[ name ] || name ];\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tprop: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set properties on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// Fix name and attach hooks\n\t\t\tname = jQuery.propFix[ name ] || name;\n\t\t\thooks = jQuery.propHooks[ name ];\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\treturn ( elem[ name ] = value );\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\treturn elem[ name ];\n\t},\n\n\tpropHooks: {\n\t\ttabIndex: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\t// Support: IE <=9 - 11 only\n\t\t\t\t// elem.tabIndex doesn't always return the\n\t\t\t\t// correct value when it hasn't been explicitly set\n\t\t\t\t// https://web.archive.org/web/20141116233347/http://fluidproject.org/blog/2008/01/09/getting-setting-and-removing-tabindex-values-with-javascript/\n\t\t\t\t// Use proper attribute retrieval(#12072)\n\t\t\t\tvar tabindex = jQuery.find.attr( elem, \"tabindex\" );\n\n\t\t\t\tif ( tabindex ) {\n\t\t\t\t\treturn parseInt( tabindex, 10 );\n\t\t\t\t}\n\n\t\t\t\tif (\n\t\t\t\t\trfocusable.test( elem.nodeName ) ||\n\t\t\t\t\trclickable.test( elem.nodeName ) &&\n\t\t\t\t\telem.href\n\t\t\t\t) {\n\t\t\t\t\treturn 0;\n\t\t\t\t}\n\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t},\n\n\tpropFix: {\n\t\t\"for\": \"htmlFor\",\n\t\t\"class\": \"className\"\n\t}\n} );\n\n// Support: IE <=11 only\n// Accessing the selectedIndex property\n// forces the browser to respect setting selected\n// on the option\n// The getter ensures a default option is selected\n// when in an optgroup\n// eslint rule \"no-unused-expressions\" is disabled for this code\n// since it considers such accessions noop\nif ( !support.optSelected ) {\n\tjQuery.propHooks.selected = {\n\t\tget: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent && parent.parentNode ) {\n\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t}\n\t\t\treturn null;\n\t\t},\n\t\tset: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent ) {\n\t\t\t\tparent.selectedIndex;\n\n\t\t\t\tif ( parent.parentNode ) {\n\t\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t};\n}\n\njQuery.each( [\n\t\"tabIndex\",\n\t\"readOnly\",\n\t\"maxLength\",\n\t\"cellSpacing\",\n\t\"cellPadding\",\n\t\"rowSpan\",\n\t\"colSpan\",\n\t\"useMap\",\n\t\"frameBorder\",\n\t\"contentEditable\"\n], function() {\n\tjQuery.propFix[ this.toLowerCase() ] = this;\n} );\n\n\n\n\n\t// Strip and collapse whitespace according to HTML spec\n\t// https://infra.spec.whatwg.org/#strip-and-collapse-ascii-whitespace\n\tfunction stripAndCollapse( value ) {\n\t\tvar tokens = value.match( rnothtmlwhite ) || [];\n\t\treturn tokens.join( \" \" );\n\t}\n\n\nfunction getClass( elem ) {\n\treturn elem.getAttribute && elem.getAttribute( \"class\" ) || \"\";\n}\n\nfunction classesToArray( value ) {\n\tif ( Array.isArray( value ) ) {\n\t\treturn value;\n\t}\n\tif ( typeof value === \"string\" ) {\n\t\treturn value.match( rnothtmlwhite ) || [];\n\t}\n\treturn [];\n}\n\njQuery.fn.extend( {\n\taddClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).addClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\t\t\t\t\t\tif ( cur.indexOf( \" \" + clazz + \" \" ) < 0 ) {\n\t\t\t\t\t\t\tcur += clazz + \" \";\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tremoveClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).removeClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tif ( !arguments.length ) {\n\t\t\treturn this.attr( \"class\", \"\" );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\n\t\t\t\t// This expression is here for better compressibility (see addClass)\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\n\t\t\t\t\t\t// Remove *all* instances\n\t\t\t\t\t\twhile ( cur.indexOf( \" \" + clazz + \" \" ) > -1 ) {\n\t\t\t\t\t\t\tcur = cur.replace( \" \" + clazz + \" \", \" \" );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\ttoggleClass: function( value, stateVal ) {\n\t\tvar type = typeof value,\n\t\t\tisValidValue = type === \"string\" || Array.isArray( value );\n\n\t\tif ( typeof stateVal === \"boolean\" && isValidValue ) {\n\t\t\treturn stateVal ? this.addClass( value ) : this.removeClass( value );\n\t\t}\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).toggleClass(\n\t\t\t\t\tvalue.call( this, i, getClass( this ), stateVal ),\n\t\t\t\t\tstateVal\n\t\t\t\t);\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar className, i, self, classNames;\n\n\t\t\tif ( isValidValue ) {\n\n\t\t\t\t// Toggle individual class names\n\t\t\t\ti = 0;\n\t\t\t\tself = jQuery( this );\n\t\t\t\tclassNames = classesToArray( value );\n\n\t\t\t\twhile ( ( className = classNames[ i++ ] ) ) {\n\n\t\t\t\t\t// Check each className given, space separated list\n\t\t\t\t\tif ( self.hasClass( className ) ) {\n\t\t\t\t\t\tself.removeClass( className );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tself.addClass( className );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t// Toggle whole class name\n\t\t\t} else if ( value === undefined || type === \"boolean\" ) {\n\t\t\t\tclassName = getClass( this );\n\t\t\t\tif ( className ) {\n\n\t\t\t\t\t// Store className if set\n\t\t\t\t\tdataPriv.set( this, \"__className__\", className );\n\t\t\t\t}\n\n\t\t\t\t// If the element has a class name or if we're passed `false`,\n\t\t\t\t// then remove the whole classname (if there was one, the above saved it).\n\t\t\t\t// Otherwise bring back whatever was previously saved (if anything),\n\t\t\t\t// falling back to the empty string if nothing was stored.\n\t\t\t\tif ( this.setAttribute ) {\n\t\t\t\t\tthis.setAttribute( \"class\",\n\t\t\t\t\t\tclassName || value === false ?\n\t\t\t\t\t\t\"\" :\n\t\t\t\t\t\tdataPriv.get( this, \"__className__\" ) || \"\"\n\t\t\t\t\t);\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\thasClass: function( selector ) {\n\t\tvar className, elem,\n\t\t\ti = 0;\n\n\t\tclassName = \" \" + selector + \" \";\n\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\tif ( elem.nodeType === 1 &&\n\t\t\t\t( \" \" + stripAndCollapse( getClass( elem ) ) + \" \" ).indexOf( className ) > -1 ) {\n\t\t\t\t\treturn true;\n\t\t\t}\n\t\t}\n\n\t\treturn false;\n\t}\n} );\n\n\n\n\nvar rreturn = /\\r/g;\n\njQuery.fn.extend( {\n\tval: function( value ) {\n\t\tvar hooks, ret, valueIsFunction,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !arguments.length ) {\n\t\t\tif ( elem ) {\n\t\t\t\thooks = jQuery.valHooks[ elem.type ] ||\n\t\t\t\t\tjQuery.valHooks[ elem.nodeName.toLowerCase() ];\n\n\t\t\t\tif ( hooks &&\n\t\t\t\t\t\"get\" in hooks &&\n\t\t\t\t\t( ret = hooks.get( elem, \"value\" ) ) !== undefined\n\t\t\t\t) {\n\t\t\t\t\treturn ret;\n\t\t\t\t}\n\n\t\t\t\tret = elem.value;\n\n\t\t\t\t// Handle most common string cases\n\t\t\t\tif ( typeof ret === \"string\" ) {\n\t\t\t\t\treturn ret.replace( rreturn, \"\" );\n\t\t\t\t}\n\n\t\t\t\t// Handle cases where value is null/undef or number\n\t\t\t\treturn ret == null ? \"\" : ret;\n\t\t\t}\n\n\t\t\treturn;\n\t\t}\n\n\t\tvalueIsFunction = isFunction( value );\n\n\t\treturn this.each( function( i ) {\n\t\t\tvar val;\n\n\t\t\tif ( this.nodeType !== 1 ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\tval = value.call( this, i, jQuery( this ).val() );\n\t\t\t} else {\n\t\t\t\tval = value;\n\t\t\t}\n\n\t\t\t// Treat null/undefined as \"\"; convert numbers to string\n\t\t\tif ( val == null ) {\n\t\t\t\tval = \"\";\n\n\t\t\t} else if ( typeof val === \"number\" ) {\n\t\t\t\tval += \"\";\n\n\t\t\t} else if ( Array.isArray( val ) ) {\n\t\t\t\tval = jQuery.map( val, function( value ) {\n\t\t\t\t\treturn value == null ? \"\" : value + \"\";\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\thooks = jQuery.valHooks[ this.type ] || jQuery.valHooks[ this.nodeName.toLowerCase() ];\n\n\t\t\t// If set returns undefined, fall back to normal setting\n\t\t\tif ( !hooks || !( \"set\" in hooks ) || hooks.set( this, val, \"value\" ) === undefined ) {\n\t\t\t\tthis.value = val;\n\t\t\t}\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tvalHooks: {\n\t\toption: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\tvar val = jQuery.find.attr( elem, \"value\" );\n\t\t\t\treturn val != null ?\n\t\t\t\t\tval :\n\n\t\t\t\t\t// Support: IE <=10 - 11 only\n\t\t\t\t\t// option.text throws exceptions (#14686, #14858)\n\t\t\t\t\t// Strip and collapse whitespace\n\t\t\t\t\t// https://html.spec.whatwg.org/#strip-and-collapse-whitespace\n\t\t\t\t\tstripAndCollapse( jQuery.text( elem ) );\n\t\t\t}\n\t\t},\n\t\tselect: {\n\t\t\tget: function( elem ) {\n\t\t\t\tvar value, option, i,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tindex = elem.selectedIndex,\n\t\t\t\t\tone = elem.type === \"select-one\",\n\t\t\t\t\tvalues = one ? null : [],\n\t\t\t\t\tmax = one ? index + 1 : options.length;\n\n\t\t\t\tif ( index < 0 ) {\n\t\t\t\t\ti = max;\n\n\t\t\t\t} else {\n\t\t\t\t\ti = one ? index : 0;\n\t\t\t\t}\n\n\t\t\t\t// Loop through all the selected options\n\t\t\t\tfor ( ; i < max; i++ ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t// IE8-9 doesn't update selected after form reset (#2551)\n\t\t\t\t\tif ( ( option.selected || i === index ) &&\n\n\t\t\t\t\t\t\t// Don't return options that are disabled or in a disabled optgroup\n\t\t\t\t\t\t\t!option.disabled &&\n\t\t\t\t\t\t\t( !option.parentNode.disabled ||\n\t\t\t\t\t\t\t\t!nodeName( option.parentNode, \"optgroup\" ) ) ) {\n\n\t\t\t\t\t\t// Get the specific value for the option\n\t\t\t\t\t\tvalue = jQuery( option ).val();\n\n\t\t\t\t\t\t// We don't need an array for one selects\n\t\t\t\t\t\tif ( one ) {\n\t\t\t\t\t\t\treturn value;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Multi-Selects return an array\n\t\t\t\t\t\tvalues.push( value );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn values;\n\t\t\t},\n\n\t\t\tset: function( elem, value ) {\n\t\t\t\tvar optionSet, option,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tvalues = jQuery.makeArray( value ),\n\t\t\t\t\ti = options.length;\n\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t/* eslint-disable no-cond-assign */\n\n\t\t\t\t\tif ( option.selected =\n\t\t\t\t\t\tjQuery.inArray( jQuery.valHooks.option.get( option ), values ) > -1\n\t\t\t\t\t) {\n\t\t\t\t\t\toptionSet = true;\n\t\t\t\t\t}\n\n\t\t\t\t\t/* eslint-enable no-cond-assign */\n\t\t\t\t}\n\n\t\t\t\t// Force browsers to behave consistently when non-matching value is set\n\t\t\t\tif ( !optionSet ) {\n\t\t\t\t\telem.selectedIndex = -1;\n\t\t\t\t}\n\t\t\t\treturn values;\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Radios and checkboxes getter/setter\njQuery.each( [ \"radio\", \"checkbox\" ], function() {\n\tjQuery.valHooks[ this ] = {\n\t\tset: function( elem, value ) {\n\t\t\tif ( Array.isArray( value ) ) {\n\t\t\t\treturn ( elem.checked = jQuery.inArray( jQuery( elem ).val(), value ) > -1 );\n\t\t\t}\n\t\t}\n\t};\n\tif ( !support.checkOn ) {\n\t\tjQuery.valHooks[ this ].get = function( elem ) {\n\t\t\treturn elem.getAttribute( \"value\" ) === null ? \"on\" : elem.value;\n\t\t};\n\t}\n} );\n\n\n\n\n// Return jQuery for attributes-only inclusion\n\n\nsupport.focusin = \"onfocusin\" in window;\n\n\nvar rfocusMorph = /^(?:focusinfocus|focusoutblur)$/,\n\tstopPropagationCallback = function( e ) {\n\t\te.stopPropagation();\n\t};\n\njQuery.extend( jQuery.event, {\n\n\ttrigger: function( event, data, elem, onlyHandlers ) {\n\n\t\tvar i, cur, tmp, bubbleType, ontype, handle, special, lastElement,\n\t\t\teventPath = [ elem || document ],\n\t\t\ttype = hasOwn.call( event, \"type\" ) ? event.type : event,\n\t\t\tnamespaces = hasOwn.call( event, \"namespace\" ) ? event.namespace.split( \".\" ) : [];\n\n\t\tcur = lastElement = tmp = elem = elem || document;\n\n\t\t// Don't do events on text and comment nodes\n\t\tif ( elem.nodeType === 3 || elem.nodeType === 8 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// focus/blur morphs to focusin/out; ensure we're not firing them right now\n\t\tif ( rfocusMorph.test( type + jQuery.event.triggered ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( type.indexOf( \".\" ) > -1 ) {\n\n\t\t\t// Namespaced trigger; create a regexp to match event type in handle()\n\t\t\tnamespaces = type.split( \".\" );\n\t\t\ttype = namespaces.shift();\n\t\t\tnamespaces.sort();\n\t\t}\n\t\tontype = type.indexOf( \":\" ) < 0 && \"on\" + type;\n\n\t\t// Caller can pass in a jQuery.Event object, Object, or just an event type string\n\t\tevent = event[ jQuery.expando ] ?\n\t\t\tevent :\n\t\t\tnew jQuery.Event( type, typeof event === \"object\" && event );\n\n\t\t// Trigger bitmask: & 1 for native handlers; & 2 for jQuery (always true)\n\t\tevent.isTrigger = onlyHandlers ? 2 : 3;\n\t\tevent.namespace = namespaces.join( \".\" );\n\t\tevent.rnamespace = event.namespace ?\n\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" ) :\n\t\t\tnull;\n\n\t\t// Clean up the event in case it is being reused\n\t\tevent.result = undefined;\n\t\tif ( !event.target ) {\n\t\t\tevent.target = elem;\n\t\t}\n\n\t\t// Clone any incoming data and prepend the event, creating the handler arg list\n\t\tdata = data == null ?\n\t\t\t[ event ] :\n\t\t\tjQuery.makeArray( data, [ event ] );\n\n\t\t// Allow special events to draw outside the lines\n\t\tspecial = jQuery.event.special[ type ] || {};\n\t\tif ( !onlyHandlers && special.trigger && special.trigger.apply( elem, data ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine event propagation path in advance, per W3C events spec (#9951)\n\t\t// Bubble up to document, then to window; watch for a global ownerDocument var (#9724)\n\t\tif ( !onlyHandlers && !special.noBubble && !isWindow( elem ) ) {\n\n\t\t\tbubbleType = special.delegateType || type;\n\t\t\tif ( !rfocusMorph.test( bubbleType + type ) ) {\n\t\t\t\tcur = cur.parentNode;\n\t\t\t}\n\t\t\tfor ( ; cur; cur = cur.parentNode ) {\n\t\t\t\teventPath.push( cur );\n\t\t\t\ttmp = cur;\n\t\t\t}\n\n\t\t\t// Only add window if we got to document (e.g., not plain obj or detached DOM)\n\t\t\tif ( tmp === ( elem.ownerDocument || document ) ) {\n\t\t\t\teventPath.push( tmp.defaultView || tmp.parentWindow || window );\n\t\t\t}\n\t\t}\n\n\t\t// Fire handlers on the event path\n\t\ti = 0;\n\t\twhile ( ( cur = eventPath[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tlastElement = cur;\n\t\t\tevent.type = i > 1 ?\n\t\t\t\tbubbleType :\n\t\t\t\tspecial.bindType || type;\n\n\t\t\t// jQuery handler\n\t\t\thandle = ( dataPriv.get( cur, \"events\" ) || {} )[ event.type ] &&\n\t\t\t\tdataPriv.get( cur, \"handle\" );\n\t\t\tif ( handle ) {\n\t\t\t\thandle.apply( cur, data );\n\t\t\t}\n\n\t\t\t// Native handler\n\t\t\thandle = ontype && cur[ ontype ];\n\t\t\tif ( handle && handle.apply && acceptData( cur ) ) {\n\t\t\t\tevent.result = handle.apply( cur, data );\n\t\t\t\tif ( event.result === false ) {\n\t\t\t\t\tevent.preventDefault();\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tevent.type = type;\n\n\t\t// If nobody prevented the default action, do it now\n\t\tif ( !onlyHandlers && !event.isDefaultPrevented() ) {\n\n\t\t\tif ( ( !special._default ||\n\t\t\t\tspecial._default.apply( eventPath.pop(), data ) === false ) &&\n\t\t\t\tacceptData( elem ) ) {\n\n\t\t\t\t// Call a native DOM method on the target with the same name as the event.\n\t\t\t\t// Don't do default actions on window, that's where global variables be (#6170)\n\t\t\t\tif ( ontype && isFunction( elem[ type ] ) && !isWindow( elem ) ) {\n\n\t\t\t\t\t// Don't re-trigger an onFOO event when we call its FOO() method\n\t\t\t\t\ttmp = elem[ ontype ];\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = null;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prevent re-triggering of the same event, since we already bubbled it above\n\t\t\t\t\tjQuery.event.triggered = type;\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.addEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\telem[ type ]();\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.removeEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\tjQuery.event.triggered = undefined;\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = tmp;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\t// Piggyback on a donor event to simulate a different one\n\t// Used only for `focus(in | out)` events\n\tsimulate: function( type, elem, event ) {\n\t\tvar e = jQuery.extend(\n\t\t\tnew jQuery.Event(),\n\t\t\tevent,\n\t\t\t{\n\t\t\t\ttype: type,\n\t\t\t\tisSimulated: true\n\t\t\t}\n\t\t);\n\n\t\tjQuery.event.trigger( e, null, elem );\n\t}\n\n} );\n\njQuery.fn.extend( {\n\n\ttrigger: function( type, data ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.trigger( type, data, this );\n\t\t} );\n\t},\n\ttriggerHandler: function( type, data ) {\n\t\tvar elem = this[ 0 ];\n\t\tif ( elem ) {\n\t\t\treturn jQuery.event.trigger( type, data, elem, true );\n\t\t}\n\t}\n} );\n\n\n// Support: Firefox <=44\n// Firefox doesn't have focus(in | out) events\n// Related ticket - https://bugzilla.mozilla.org/show_bug.cgi?id=687787\n//\n// Support: Chrome <=48 - 49, Safari <=9.0 - 9.1\n// focus(in | out) events fire after focus & blur events,\n// which is spec violation - http://www.w3.org/TR/DOM-Level-3-Events/#events-focusevent-event-order\n// Related ticket - https://bugs.chromium.org/p/chromium/issues/detail?id=449857\nif ( !support.focusin ) {\n\tjQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( orig, fix ) {\n\n\t\t// Attach a single capturing handler on the document while someone wants focusin/focusout\n\t\tvar handler = function( event ) {\n\t\t\tjQuery.event.simulate( fix, event.target, jQuery.event.fix( event ) );\n\t\t};\n\n\t\tjQuery.event.special[ fix ] = {\n\t\t\tsetup: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix );\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.addEventListener( orig, handler, true );\n\t\t\t\t}\n\t\t\t\tdataPriv.access( doc, fix, ( attaches || 0 ) + 1 );\n\t\t\t},\n\t\t\tteardown: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix ) - 1;\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.removeEventListener( orig, handler, true );\n\t\t\t\t\tdataPriv.remove( doc, fix );\n\n\t\t\t\t} else {\n\t\t\t\t\tdataPriv.access( doc, fix, attaches );\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t} );\n}\nvar location = window.location;\n\nvar nonce = Date.now();\n\nvar rquery = ( /\\?/ );\n\n\n\n// Cross-browser xml parsing\njQuery.parseXML = function( data ) {\n\tvar xml;\n\tif ( !data || typeof data !== \"string\" ) {\n\t\treturn null;\n\t}\n\n\t// Support: IE 9 - 11 only\n\t// IE throws on parseFromString with invalid input.\n\ttry {\n\t\txml = ( new window.DOMParser() ).parseFromString( data, \"text/xml\" );\n\t} catch ( e ) {\n\t\txml = undefined;\n\t}\n\n\tif ( !xml || xml.getElementsByTagName( \"parsererror\" ).length ) {\n\t\tjQuery.error( \"Invalid XML: \" + data );\n\t}\n\treturn xml;\n};\n\n\nvar\n\trbracket = /\\[\\]$/,\n\trCRLF = /\\r?\\n/g,\n\trsubmitterTypes = /^(?:submit|button|image|reset|file)$/i,\n\trsubmittable = /^(?:input|select|textarea|keygen)/i;\n\nfunction buildParams( prefix, obj, traditional, add ) {\n\tvar name;\n\n\tif ( Array.isArray( obj ) ) {\n\n\t\t// Serialize array item.\n\t\tjQuery.each( obj, function( i, v ) {\n\t\t\tif ( traditional || rbracket.test( prefix ) ) {\n\n\t\t\t\t// Treat each array item as a scalar.\n\t\t\t\tadd( prefix, v );\n\n\t\t\t} else {\n\n\t\t\t\t// Item is non-scalar (array or object), encode its numeric index.\n\t\t\t\tbuildParams(\n\t\t\t\t\tprefix + \"[\" + ( typeof v === \"object\" && v != null ? i : \"\" ) + \"]\",\n\t\t\t\t\tv,\n\t\t\t\t\ttraditional,\n\t\t\t\t\tadd\n\t\t\t\t);\n\t\t\t}\n\t\t} );\n\n\t} else if ( !traditional && toType( obj ) === \"object\" ) {\n\n\t\t// Serialize object item.\n\t\tfor ( name in obj ) {\n\t\t\tbuildParams( prefix + \"[\" + name + \"]\", obj[ name ], traditional, add );\n\t\t}\n\n\t} else {\n\n\t\t// Serialize scalar item.\n\t\tadd( prefix, obj );\n\t}\n}\n\n// Serialize an array of form elements or a set of\n// key/values into a query string\njQuery.param = function( a, traditional ) {\n\tvar prefix,\n\t\ts = [],\n\t\tadd = function( key, valueOrFunction ) {\n\n\t\t\t// If value is a function, invoke it and use its return value\n\t\t\tvar value = isFunction( valueOrFunction ) ?\n\t\t\t\tvalueOrFunction() :\n\t\t\t\tvalueOrFunction;\n\n\t\t\ts[ s.length ] = encodeURIComponent( key ) + \"=\" +\n\t\t\t\tencodeURIComponent( value == null ? \"\" : value );\n\t\t};\n\n\tif ( a == null ) {\n\t\treturn \"\";\n\t}\n\n\t// If an array was passed in, assume that it is an array of form elements.\n\tif ( Array.isArray( a ) || ( a.jquery && !jQuery.isPlainObject( a ) ) ) {\n\n\t\t// Serialize the form elements\n\t\tjQuery.each( a, function() {\n\t\t\tadd( this.name, this.value );\n\t\t} );\n\n\t} else {\n\n\t\t// If traditional, encode the \"old\" way (the way 1.3.2 or older\n\t\t// did it), otherwise encode params recursively.\n\t\tfor ( prefix in a ) {\n\t\t\tbuildParams( prefix, a[ prefix ], traditional, add );\n\t\t}\n\t}\n\n\t// Return the resulting serialization\n\treturn s.join( \"&\" );\n};\n\njQuery.fn.extend( {\n\tserialize: function() {\n\t\treturn jQuery.param( this.serializeArray() );\n\t},\n\tserializeArray: function() {\n\t\treturn this.map( function() {\n\n\t\t\t// Can add propHook for \"elements\" to filter or add form elements\n\t\t\tvar elements = jQuery.prop( this, \"elements\" );\n\t\t\treturn elements ? jQuery.makeArray( elements ) : this;\n\t\t} )\n\t\t.filter( function() {\n\t\t\tvar type = this.type;\n\n\t\t\t// Use .is( \":disabled\" ) so that fieldset[disabled] works\n\t\t\treturn this.name && !jQuery( this ).is( \":disabled\" ) &&\n\t\t\t\trsubmittable.test( this.nodeName ) && !rsubmitterTypes.test( type ) &&\n\t\t\t\t( this.checked || !rcheckableType.test( type ) );\n\t\t} )\n\t\t.map( function( i, elem ) {\n\t\t\tvar val = jQuery( this ).val();\n\n\t\t\tif ( val == null ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\tif ( Array.isArray( val ) ) {\n\t\t\t\treturn jQuery.map( val, function( val ) {\n\t\t\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t} ).get();\n\t}\n} );\n\n\nvar\n\tr20 = /%20/g,\n\trhash = /#.*$/,\n\trantiCache = /([?&])_=[^&]*/,\n\trheaders = /^(.*?):[ \\t]*([^\\r\\n]*)$/mg,\n\n\t// #7653, #8125, #8152: local protocol detection\n\trlocalProtocol = /^(?:about|app|app-storage|.+-extension|file|res|widget):$/,\n\trnoContent = /^(?:GET|HEAD)$/,\n\trprotocol = /^\\/\\//,\n\n\t/* Prefilters\n\t * 1) They are useful to introduce custom dataTypes (see ajax/jsonp.js for an example)\n\t * 2) These are called:\n\t *    - BEFORE asking for a transport\n\t *    - AFTER param serialization (s.data is a string if s.processData is true)\n\t * 3) key is the dataType\n\t * 4) the catchall symbol \"*\" can be used\n\t * 5) execution will start with transport dataType and THEN continue down to \"*\" if needed\n\t */\n\tprefilters = {},\n\n\t/* Transports bindings\n\t * 1) key is the dataType\n\t * 2) the catchall symbol \"*\" can be used\n\t * 3) selection will start with transport dataType and THEN go to \"*\" if needed\n\t */\n\ttransports = {},\n\n\t// Avoid comment-prolog char sequence (#10098); must appease lint and evade compression\n\tallTypes = \"*/\".concat( \"*\" ),\n\n\t// Anchor tag for parsing the document origin\n\toriginAnchor = document.createElement( \"a\" );\n\toriginAnchor.href = location.href;\n\n// Base \"constructor\" for jQuery.ajaxPrefilter and jQuery.ajaxTransport\nfunction addToPrefiltersOrTransports( structure ) {\n\n\t// dataTypeExpression is optional and defaults to \"*\"\n\treturn function( dataTypeExpression, func ) {\n\n\t\tif ( typeof dataTypeExpression !== \"string\" ) {\n\t\t\tfunc = dataTypeExpression;\n\t\t\tdataTypeExpression = \"*\";\n\t\t}\n\n\t\tvar dataType,\n\t\t\ti = 0,\n\t\t\tdataTypes = dataTypeExpression.toLowerCase().match( rnothtmlwhite ) || [];\n\n\t\tif ( isFunction( func ) ) {\n\n\t\t\t// For each dataType in the dataTypeExpression\n\t\t\twhile ( ( dataType = dataTypes[ i++ ] ) ) {\n\n\t\t\t\t// Prepend if requested\n\t\t\t\tif ( dataType[ 0 ] === \"+\" ) {\n\t\t\t\t\tdataType = dataType.slice( 1 ) || \"*\";\n\t\t\t\t\t( structure[ dataType ] = structure[ dataType ] || [] ).unshift( func );\n\n\t\t\t\t// Otherwise append\n\t\t\t\t} else {\n\t\t\t\t\t( structure[ dataType ] = structure[ dataType ] || [] ).push( func );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t};\n}\n\n// Base inspection function for prefilters and transports\nfunction inspectPrefiltersOrTransports( structure, options, originalOptions, jqXHR ) {\n\n\tvar inspected = {},\n\t\tseekingTransport = ( structure === transports );\n\n\tfunction inspect( dataType ) {\n\t\tvar selected;\n\t\tinspected[ dataType ] = true;\n\t\tjQuery.each( structure[ dataType ] || [], function( _, prefilterOrFactory ) {\n\t\t\tvar dataTypeOrTransport = prefilterOrFactory( options, originalOptions, jqXHR );\n\t\t\tif ( typeof dataTypeOrTransport === \"string\" &&\n\t\t\t\t!seekingTransport && !inspected[ dataTypeOrTransport ] ) {\n\n\t\t\t\toptions.dataTypes.unshift( dataTypeOrTransport );\n\t\t\t\tinspect( dataTypeOrTransport );\n\t\t\t\treturn false;\n\t\t\t} else if ( seekingTransport ) {\n\t\t\t\treturn !( selected = dataTypeOrTransport );\n\t\t\t}\n\t\t} );\n\t\treturn selected;\n\t}\n\n\treturn inspect( options.dataTypes[ 0 ] ) || !inspected[ \"*\" ] && inspect( \"*\" );\n}\n\n// A special extend for ajax options\n// that takes \"flat\" options (not to be deep extended)\n// Fixes #9887\nfunction ajaxExtend( target, src ) {\n\tvar key, deep,\n\t\tflatOptions = jQuery.ajaxSettings.flatOptions || {};\n\n\tfor ( key in src ) {\n\t\tif ( src[ key ] !== undefined ) {\n\t\t\t( flatOptions[ key ] ? target : ( deep || ( deep = {} ) ) )[ key ] = src[ key ];\n\t\t}\n\t}\n\tif ( deep ) {\n\t\tjQuery.extend( true, target, deep );\n\t}\n\n\treturn target;\n}\n\n/* Handles responses to an ajax request:\n * - finds the right dataType (mediates between content-type and expected dataType)\n * - returns the corresponding response\n */\nfunction ajaxHandleResponses( s, jqXHR, responses ) {\n\n\tvar ct, type, finalDataType, firstDataType,\n\t\tcontents = s.contents,\n\t\tdataTypes = s.dataTypes;\n\n\t// Remove auto dataType and get content-type in the process\n\twhile ( dataTypes[ 0 ] === \"*\" ) {\n\t\tdataTypes.shift();\n\t\tif ( ct === undefined ) {\n\t\t\tct = s.mimeType || jqXHR.getResponseHeader( \"Content-Type\" );\n\t\t}\n\t}\n\n\t// Check if we're dealing with a known content-type\n\tif ( ct ) {\n\t\tfor ( type in contents ) {\n\t\t\tif ( contents[ type ] && contents[ type ].test( ct ) ) {\n\t\t\t\tdataTypes.unshift( type );\n\t\t\t\tbreak;\n\t\t\t}\n\t\t}\n\t}\n\n\t// Check to see if we have a response for the expected dataType\n\tif ( dataTypes[ 0 ] in responses ) {\n\t\tfinalDataType = dataTypes[ 0 ];\n\t} else {\n\n\t\t// Try convertible dataTypes\n\t\tfor ( type in responses ) {\n\t\t\tif ( !dataTypes[ 0 ] || s.converters[ type + \" \" + dataTypes[ 0 ] ] ) {\n\t\t\t\tfinalDataType = type;\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tif ( !firstDataType ) {\n\t\t\t\tfirstDataType = type;\n\t\t\t}\n\t\t}\n\n\t\t// Or just use first one\n\t\tfinalDataType = finalDataType || firstDataType;\n\t}\n\n\t// If we found a dataType\n\t// We add the dataType to the list if needed\n\t// and return the corresponding response\n\tif ( finalDataType ) {\n\t\tif ( finalDataType !== dataTypes[ 0 ] ) {\n\t\t\tdataTypes.unshift( finalDataType );\n\t\t}\n\t\treturn responses[ finalDataType ];\n\t}\n}\n\n/* Chain conversions given the request and the original response\n * Also sets the responseXXX fields on the jqXHR instance\n */\nfunction ajaxConvert( s, response, jqXHR, isSuccess ) {\n\tvar conv2, current, conv, tmp, prev,\n\t\tconverters = {},\n\n\t\t// Work with a copy of dataTypes in case we need to modify it for conversion\n\t\tdataTypes = s.dataTypes.slice();\n\n\t// Create converters map with lowercased keys\n\tif ( dataTypes[ 1 ] ) {\n\t\tfor ( conv in s.converters ) {\n\t\t\tconverters[ conv.toLowerCase() ] = s.converters[ conv ];\n\t\t}\n\t}\n\n\tcurrent = dataTypes.shift();\n\n\t// Convert to each sequential dataType\n\twhile ( current ) {\n\n\t\tif ( s.responseFields[ current ] ) {\n\t\t\tjqXHR[ s.responseFields[ current ] ] = response;\n\t\t}\n\n\t\t// Apply the dataFilter if provided\n\t\tif ( !prev && isSuccess && s.dataFilter ) {\n\t\t\tresponse = s.dataFilter( response, s.dataType );\n\t\t}\n\n\t\tprev = current;\n\t\tcurrent = dataTypes.shift();\n\n\t\tif ( current ) {\n\n\t\t\t// There's only work to do if current dataType is non-auto\n\t\t\tif ( current === \"*\" ) {\n\n\t\t\t\tcurrent = prev;\n\n\t\t\t// Convert response if prev dataType is non-auto and differs from current\n\t\t\t} else if ( prev !== \"*\" && prev !== current ) {\n\n\t\t\t\t// Seek a direct converter\n\t\t\t\tconv = converters[ prev + \" \" + current ] || converters[ \"* \" + current ];\n\n\t\t\t\t// If none found, seek a pair\n\t\t\t\tif ( !conv ) {\n\t\t\t\t\tfor ( conv2 in converters ) {\n\n\t\t\t\t\t\t// If conv2 outputs current\n\t\t\t\t\t\ttmp = conv2.split( \" \" );\n\t\t\t\t\t\tif ( tmp[ 1 ] === current ) {\n\n\t\t\t\t\t\t\t// If prev can be converted to accepted input\n\t\t\t\t\t\t\tconv = converters[ prev + \" \" + tmp[ 0 ] ] ||\n\t\t\t\t\t\t\t\tconverters[ \"* \" + tmp[ 0 ] ];\n\t\t\t\t\t\t\tif ( conv ) {\n\n\t\t\t\t\t\t\t\t// Condense equivalence converters\n\t\t\t\t\t\t\t\tif ( conv === true ) {\n\t\t\t\t\t\t\t\t\tconv = converters[ conv2 ];\n\n\t\t\t\t\t\t\t\t// Otherwise, insert the intermediate dataType\n\t\t\t\t\t\t\t\t} else if ( converters[ conv2 ] !== true ) {\n\t\t\t\t\t\t\t\t\tcurrent = tmp[ 0 ];\n\t\t\t\t\t\t\t\t\tdataTypes.unshift( tmp[ 1 ] );\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Apply converter (if not an equivalence)\n\t\t\t\tif ( conv !== true ) {\n\n\t\t\t\t\t// Unless errors are allowed to bubble, catch and return them\n\t\t\t\t\tif ( conv && s.throws ) {\n\t\t\t\t\t\tresponse = conv( response );\n\t\t\t\t\t} else {\n\t\t\t\t\t\ttry {\n\t\t\t\t\t\t\tresponse = conv( response );\n\t\t\t\t\t\t} catch ( e ) {\n\t\t\t\t\t\t\treturn {\n\t\t\t\t\t\t\t\tstate: \"parsererror\",\n\t\t\t\t\t\t\t\terror: conv ? e : \"No conversion from \" + prev + \" to \" + current\n\t\t\t\t\t\t\t};\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn { state: \"success\", data: response };\n}\n\njQuery.extend( {\n\n\t// Counter for holding the number of active queries\n\tactive: 0,\n\n\t// Last-Modified header cache for next request\n\tlastModified: {},\n\tetag: {},\n\n\tajaxSettings: {\n\t\turl: location.href,\n\t\ttype: \"GET\",\n\t\tisLocal: rlocalProtocol.test( location.protocol ),\n\t\tglobal: true,\n\t\tprocessData: true,\n\t\tasync: true,\n\t\tcontentType: \"application/x-www-form-urlencoded; charset=UTF-8\",\n\n\t\t/*\n\t\ttimeout: 0,\n\t\tdata: null,\n\t\tdataType: null,\n\t\tusername: null,\n\t\tpassword: null,\n\t\tcache: null,\n\t\tthrows: false,\n\t\ttraditional: false,\n\t\theaders: {},\n\t\t*/\n\n\t\taccepts: {\n\t\t\t\"*\": allTypes,\n\t\t\ttext: \"text/plain\",\n\t\t\thtml: \"text/html\",\n\t\t\txml: \"application/xml, text/xml\",\n\t\t\tjson: \"application/json, text/javascript\"\n\t\t},\n\n\t\tcontents: {\n\t\t\txml: /\\bxml\\b/,\n\t\t\thtml: /\\bhtml/,\n\t\t\tjson: /\\bjson\\b/\n\t\t},\n\n\t\tresponseFields: {\n\t\t\txml: \"responseXML\",\n\t\t\ttext: \"responseText\",\n\t\t\tjson: \"responseJSON\"\n\t\t},\n\n\t\t// Data converters\n\t\t// Keys separate source (or catchall \"*\") and destination types with a single space\n\t\tconverters: {\n\n\t\t\t// Convert anything to text\n\t\t\t\"* text\": String,\n\n\t\t\t// Text to html (true = no transformation)\n\t\t\t\"text html\": true,\n\n\t\t\t// Evaluate text as a json expression\n\t\t\t\"text json\": JSON.parse,\n\n\t\t\t// Parse text as xml\n\t\t\t\"text xml\": jQuery.parseXML\n\t\t},\n\n\t\t// For options that shouldn't be deep extended:\n\t\t// you can add your own custom options here if\n\t\t// and when you create one that shouldn't be\n\t\t// deep extended (see ajaxExtend)\n\t\tflatOptions: {\n\t\t\turl: true,\n\t\t\tcontext: true\n\t\t}\n\t},\n\n\t// Creates a full fledged settings object into target\n\t// with both ajaxSettings and settings fields.\n\t// If target is omitted, writes into ajaxSettings.\n\tajaxSetup: function( target, settings ) {\n\t\treturn settings ?\n\n\t\t\t// Building a settings object\n\t\t\tajaxExtend( ajaxExtend( target, jQuery.ajaxSettings ), settings ) :\n\n\t\t\t// Extending ajaxSettings\n\t\t\tajaxExtend( jQuery.ajaxSettings, target );\n\t},\n\n\tajaxPrefilter: addToPrefiltersOrTransports( prefilters ),\n\tajaxTransport: addToPrefiltersOrTransports( transports ),\n\n\t// Main method\n\tajax: function( url, options ) {\n\n\t\t// If url is an object, simulate pre-1.5 signature\n\t\tif ( typeof url === \"object\" ) {\n\t\t\toptions = url;\n\t\t\turl = undefined;\n\t\t}\n\n\t\t// Force options to be an object\n\t\toptions = options || {};\n\n\t\tvar transport,\n\n\t\t\t// URL without anti-cache param\n\t\t\tcacheURL,\n\n\t\t\t// Response headers\n\t\t\tresponseHeadersString,\n\t\t\tresponseHeaders,\n\n\t\t\t// timeout handle\n\t\t\ttimeoutTimer,\n\n\t\t\t// Url cleanup var\n\t\t\turlAnchor,\n\n\t\t\t// Request state (becomes false upon send and true upon completion)\n\t\t\tcompleted,\n\n\t\t\t// To know if global events are to be dispatched\n\t\t\tfireGlobals,\n\n\t\t\t// Loop variable\n\t\t\ti,\n\n\t\t\t// uncached part of the url\n\t\t\tuncached,\n\n\t\t\t// Create the final options object\n\t\t\ts = jQuery.ajaxSetup( {}, options ),\n\n\t\t\t// Callbacks context\n\t\t\tcallbackContext = s.context || s,\n\n\t\t\t// Context for global events is callbackContext if it is a DOM node or jQuery collection\n\t\t\tglobalEventContext = s.context &&\n\t\t\t\t( callbackContext.nodeType || callbackContext.jquery ) ?\n\t\t\t\t\tjQuery( callbackContext ) :\n\t\t\t\t\tjQuery.event,\n\n\t\t\t// Deferreds\n\t\t\tdeferred = jQuery.Deferred(),\n\t\t\tcompleteDeferred = jQuery.Callbacks( \"once memory\" ),\n\n\t\t\t// Status-dependent callbacks\n\t\t\tstatusCode = s.statusCode || {},\n\n\t\t\t// Headers (they are sent all at once)\n\t\t\trequestHeaders = {},\n\t\t\trequestHeadersNames = {},\n\n\t\t\t// Default abort message\n\t\t\tstrAbort = \"canceled\",\n\n\t\t\t// Fake xhr\n\t\t\tjqXHR = {\n\t\t\t\treadyState: 0,\n\n\t\t\t\t// Builds headers hashtable if needed\n\t\t\t\tgetResponseHeader: function( key ) {\n\t\t\t\t\tvar match;\n\t\t\t\t\tif ( completed ) {\n\t\t\t\t\t\tif ( !responseHeaders ) {\n\t\t\t\t\t\t\tresponseHeaders = {};\n\t\t\t\t\t\t\twhile ( ( match = rheaders.exec( responseHeadersString ) ) ) {\n\t\t\t\t\t\t\t\tresponseHeaders[ match[ 1 ].toLowerCase() + \" \" ] =\n\t\t\t\t\t\t\t\t\t( responseHeaders[ match[ 1 ].toLowerCase() + \" \" ] || [] )\n\t\t\t\t\t\t\t\t\t\t.concat( match[ 2 ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t\tmatch = responseHeaders[ key.toLowerCase() + \" \" ];\n\t\t\t\t\t}\n\t\t\t\t\treturn match == null ? null : match.join( \", \" );\n\t\t\t\t},\n\n\t\t\t\t// Raw string\n\t\t\t\tgetAllResponseHeaders: function() {\n\t\t\t\t\treturn completed ? responseHeadersString : null;\n\t\t\t\t},\n\n\t\t\t\t// Caches the header\n\t\t\t\tsetRequestHeader: function( name, value ) {\n\t\t\t\t\tif ( completed == null ) {\n\t\t\t\t\t\tname = requestHeadersNames[ name.toLowerCase() ] =\n\t\t\t\t\t\t\trequestHeadersNames[ name.toLowerCase() ] || name;\n\t\t\t\t\t\trequestHeaders[ name ] = value;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\n\t\t\t\t// Overrides response content-type header\n\t\t\t\toverrideMimeType: function( type ) {\n\t\t\t\t\tif ( completed == null ) {\n\t\t\t\t\t\ts.mimeType = type;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\n\t\t\t\t// Status-dependent callbacks\n\t\t\t\tstatusCode: function( map ) {\n\t\t\t\t\tvar code;\n\t\t\t\t\tif ( map ) {\n\t\t\t\t\t\tif ( completed ) {\n\n\t\t\t\t\t\t\t// Execute the appropriate callbacks\n\t\t\t\t\t\t\tjqXHR.always( map[ jqXHR.status ] );\n\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t// Lazy-add the new callbacks in a way that preserves old ones\n\t\t\t\t\t\t\tfor ( code in map ) {\n\t\t\t\t\t\t\t\tstatusCode[ code ] = [ statusCode[ code ], map[ code ] ];\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\n\t\t\t\t// Cancel the request\n\t\t\t\tabort: function( statusText ) {\n\t\t\t\t\tvar finalText = statusText || strAbort;\n\t\t\t\t\tif ( transport ) {\n\t\t\t\t\t\ttransport.abort( finalText );\n\t\t\t\t\t}\n\t\t\t\t\tdone( 0, finalText );\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\t\t\t};\n\n\t\t// Attach deferreds\n\t\tdeferred.promise( jqXHR );\n\n\t\t// Add protocol if not provided (prefilters might expect it)\n\t\t// Handle falsy url in the settings object (#10093: consistency with old signature)\n\t\t// We also use the url parameter if available\n\t\ts.url = ( ( url || s.url || location.href ) + \"\" )\n\t\t\t.replace( rprotocol, location.protocol + \"//\" );\n\n\t\t// Alias method option to type as per ticket #12004\n\t\ts.type = options.method || options.type || s.method || s.type;\n\n\t\t// Extract dataTypes list\n\t\ts.dataTypes = ( s.dataType || \"*\" ).toLowerCase().match( rnothtmlwhite ) || [ \"\" ];\n\n\t\t// A cross-domain request is in order when the origin doesn't match the current origin.\n\t\tif ( s.crossDomain == null ) {\n\t\t\turlAnchor = document.createElement( \"a\" );\n\n\t\t\t// Support: IE <=8 - 11, Edge 12 - 15\n\t\t\t// IE throws exception on accessing the href property if url is malformed,\n\t\t\t// e.g. http://example.com:80x/\n\t\t\ttry {\n\t\t\t\turlAnchor.href = s.url;\n\n\t\t\t\t// Support: IE <=8 - 11 only\n\t\t\t\t// Anchor's host property isn't correctly set when s.url is relative\n\t\t\t\turlAnchor.href = urlAnchor.href;\n\t\t\t\ts.crossDomain = originAnchor.protocol + \"//\" + originAnchor.host !==\n\t\t\t\t\turlAnchor.protocol + \"//\" + urlAnchor.host;\n\t\t\t} catch ( e ) {\n\n\t\t\t\t// If there is an error parsing the URL, assume it is crossDomain,\n\t\t\t\t// it can be rejected by the transport if it is invalid\n\t\t\t\ts.crossDomain = true;\n\t\t\t}\n\t\t}\n\n\t\t// Convert data if not already a string\n\t\tif ( s.data && s.processData && typeof s.data !== \"string\" ) {\n\t\t\ts.data = jQuery.param( s.data, s.traditional );\n\t\t}\n\n\t\t// Apply prefilters\n\t\tinspectPrefiltersOrTransports( prefilters, s, options, jqXHR );\n\n\t\t// If request was aborted inside a prefilter, stop there\n\t\tif ( completed ) {\n\t\t\treturn jqXHR;\n\t\t}\n\n\t\t// We can fire global events as of now if asked to\n\t\t// Don't fire events if jQuery.event is undefined in an AMD-usage scenario (#15118)\n\t\tfireGlobals = jQuery.event && s.global;\n\n\t\t// Watch for a new set of requests\n\t\tif ( fireGlobals && jQuery.active++ === 0 ) {\n\t\t\tjQuery.event.trigger( \"ajaxStart\" );\n\t\t}\n\n\t\t// Uppercase the type\n\t\ts.type = s.type.toUpperCase();\n\n\t\t// Determine if request has content\n\t\ts.hasContent = !rnoContent.test( s.type );\n\n\t\t// Save the URL in case we're toying with the If-Modified-Since\n\t\t// and/or If-None-Match header later on\n\t\t// Remove hash to simplify url manipulation\n\t\tcacheURL = s.url.replace( rhash, \"\" );\n\n\t\t// More options handling for requests with no content\n\t\tif ( !s.hasContent ) {\n\n\t\t\t// Remember the hash so we can put it back\n\t\t\tuncached = s.url.slice( cacheURL.length );\n\n\t\t\t// If data is available and should be processed, append data to url\n\t\t\tif ( s.data && ( s.processData || typeof s.data === \"string\" ) ) {\n\t\t\t\tcacheURL += ( rquery.test( cacheURL ) ? \"&\" : \"?\" ) + s.data;\n\n\t\t\t\t// #9682: remove data so that it's not used in an eventual retry\n\t\t\t\tdelete s.data;\n\t\t\t}\n\n\t\t\t// Add or update anti-cache param if needed\n\t\t\tif ( s.cache === false ) {\n\t\t\t\tcacheURL = cacheURL.replace( rantiCache, \"$1\" );\n\t\t\t\tuncached = ( rquery.test( cacheURL ) ? \"&\" : \"?\" ) + \"_=\" + ( nonce++ ) + uncached;\n\t\t\t}\n\n\t\t\t// Put hash and anti-cache on the URL that will be requested (gh-1732)\n\t\t\ts.url = cacheURL + uncached;\n\n\t\t// Change '%20' to '+' if this is encoded form body content (gh-2658)\n\t\t} else if ( s.data && s.processData &&\n\t\t\t( s.contentType || \"\" ).indexOf( \"application/x-www-form-urlencoded\" ) === 0 ) {\n\t\t\ts.data = s.data.replace( r20, \"+\" );\n\t\t}\n\n\t\t// Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode.\n\t\tif ( s.ifModified ) {\n\t\t\tif ( jQuery.lastModified[ cacheURL ] ) {\n\t\t\t\tjqXHR.setRequestHeader( \"If-Modified-Since\", jQuery.lastModified[ cacheURL ] );\n\t\t\t}\n\t\t\tif ( jQuery.etag[ cacheURL ] ) {\n\t\t\t\tjqXHR.setRequestHeader( \"If-None-Match\", jQuery.etag[ cacheURL ] );\n\t\t\t}\n\t\t}\n\n\t\t// Set the correct header, if data is being sent\n\t\tif ( s.data && s.hasContent && s.contentType !== false || options.contentType ) {\n\t\t\tjqXHR.setRequestHeader( \"Content-Type\", s.contentType );\n\t\t}\n\n\t\t// Set the Accepts header for the server, depending on the dataType\n\t\tjqXHR.setRequestHeader(\n\t\t\t\"Accept\",\n\t\t\ts.dataTypes[ 0 ] && s.accepts[ s.dataTypes[ 0 ] ] ?\n\t\t\t\ts.accepts[ s.dataTypes[ 0 ] ] +\n\t\t\t\t\t( s.dataTypes[ 0 ] !== \"*\" ? \", \" + allTypes + \"; q=0.01\" : \"\" ) :\n\t\t\t\ts.accepts[ \"*\" ]\n\t\t);\n\n\t\t// Check for headers option\n\t\tfor ( i in s.headers ) {\n\t\t\tjqXHR.setRequestHeader( i, s.headers[ i ] );\n\t\t}\n\n\t\t// Allow custom headers/mimetypes and early abort\n\t\tif ( s.beforeSend &&\n\t\t\t( s.beforeSend.call( callbackContext, jqXHR, s ) === false || completed ) ) {\n\n\t\t\t// Abort if not done already and return\n\t\t\treturn jqXHR.abort();\n\t\t}\n\n\t\t// Aborting is no longer a cancellation\n\t\tstrAbort = \"abort\";\n\n\t\t// Install callbacks on deferreds\n\t\tcompleteDeferred.add( s.complete );\n\t\tjqXHR.done( s.success );\n\t\tjqXHR.fail( s.error );\n\n\t\t// Get transport\n\t\ttransport = inspectPrefiltersOrTransports( transports, s, options, jqXHR );\n\n\t\t// If no transport, we auto-abort\n\t\tif ( !transport ) {\n\t\t\tdone( -1, \"No Transport\" );\n\t\t} else {\n\t\t\tjqXHR.readyState = 1;\n\n\t\t\t// Send global event\n\t\t\tif ( fireGlobals ) {\n\t\t\t\tglobalEventContext.trigger( \"ajaxSend\", [ jqXHR, s ] );\n\t\t\t}\n\n\t\t\t// If request was aborted inside ajaxSend, stop there\n\t\t\tif ( completed ) {\n\t\t\t\treturn jqXHR;\n\t\t\t}\n\n\t\t\t// Timeout\n\t\t\tif ( s.async && s.timeout > 0 ) {\n\t\t\t\ttimeoutTimer = window.setTimeout( function() {\n\t\t\t\t\tjqXHR.abort( \"timeout\" );\n\t\t\t\t}, s.timeout );\n\t\t\t}\n\n\t\t\ttry {\n\t\t\t\tcompleted = false;\n\t\t\t\ttransport.send( requestHeaders, done );\n\t\t\t} catch ( e ) {\n\n\t\t\t\t// Rethrow post-completion exceptions\n\t\t\t\tif ( completed ) {\n\t\t\t\t\tthrow e;\n\t\t\t\t}\n\n\t\t\t\t// Propagate others as results\n\t\t\t\tdone( -1, e );\n\t\t\t}\n\t\t}\n\n\t\t// Callback for when everything is done\n\t\tfunction done( status, nativeStatusText, responses, headers ) {\n\t\t\tvar isSuccess, success, error, response, modified,\n\t\t\t\tstatusText = nativeStatusText;\n\n\t\t\t// Ignore repeat invocations\n\t\t\tif ( completed ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tcompleted = true;\n\n\t\t\t// Clear timeout if it exists\n\t\t\tif ( timeoutTimer ) {\n\t\t\t\twindow.clearTimeout( timeoutTimer );\n\t\t\t}\n\n\t\t\t// Dereference transport for early garbage collection\n\t\t\t// (no matter how long the jqXHR object will be used)\n\t\t\ttransport = undefined;\n\n\t\t\t// Cache response headers\n\t\t\tresponseHeadersString = headers || \"\";\n\n\t\t\t// Set readyState\n\t\t\tjqXHR.readyState = status > 0 ? 4 : 0;\n\n\t\t\t// Determine if successful\n\t\t\tisSuccess = status >= 200 && status < 300 || status === 304;\n\n\t\t\t// Get response data\n\t\t\tif ( responses ) {\n\t\t\t\tresponse = ajaxHandleResponses( s, jqXHR, responses );\n\t\t\t}\n\n\t\t\t// Convert no matter what (that way responseXXX fields are always set)\n\t\t\tresponse = ajaxConvert( s, response, jqXHR, isSuccess );\n\n\t\t\t// If successful, handle type chaining\n\t\t\tif ( isSuccess ) {\n\n\t\t\t\t// Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode.\n\t\t\t\tif ( s.ifModified ) {\n\t\t\t\t\tmodified = jqXHR.getResponseHeader( \"Last-Modified\" );\n\t\t\t\t\tif ( modified ) {\n\t\t\t\t\t\tjQuery.lastModified[ cacheURL ] = modified;\n\t\t\t\t\t}\n\t\t\t\t\tmodified = jqXHR.getResponseHeader( \"etag\" );\n\t\t\t\t\tif ( modified ) {\n\t\t\t\t\t\tjQuery.etag[ cacheURL ] = modified;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// if no content\n\t\t\t\tif ( status === 204 || s.type === \"HEAD\" ) {\n\t\t\t\t\tstatusText = \"nocontent\";\n\n\t\t\t\t// if not modified\n\t\t\t\t} else if ( status === 304 ) {\n\t\t\t\t\tstatusText = \"notmodified\";\n\n\t\t\t\t// If we have data, let's convert it\n\t\t\t\t} else {\n\t\t\t\t\tstatusText = response.state;\n\t\t\t\t\tsuccess = response.data;\n\t\t\t\t\terror = response.error;\n\t\t\t\t\tisSuccess = !error;\n\t\t\t\t}\n\t\t\t} else {\n\n\t\t\t\t// Extract error from statusText and normalize for non-aborts\n\t\t\t\terror = statusText;\n\t\t\t\tif ( status || !statusText ) {\n\t\t\t\t\tstatusText = \"error\";\n\t\t\t\t\tif ( status < 0 ) {\n\t\t\t\t\t\tstatus = 0;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Set data for the fake xhr object\n\t\t\tjqXHR.status = status;\n\t\t\tjqXHR.statusText = ( nativeStatusText || statusText ) + \"\";\n\n\t\t\t// Success/Error\n\t\t\tif ( isSuccess ) {\n\t\t\t\tdeferred.resolveWith( callbackContext, [ success, statusText, jqXHR ] );\n\t\t\t} else {\n\t\t\t\tdeferred.rejectWith( callbackContext, [ jqXHR, statusText, error ] );\n\t\t\t}\n\n\t\t\t// Status-dependent callbacks\n\t\t\tjqXHR.statusCode( statusCode );\n\t\t\tstatusCode = undefined;\n\n\t\t\tif ( fireGlobals ) {\n\t\t\t\tglobalEventContext.trigger( isSuccess ? \"ajaxSuccess\" : \"ajaxError\",\n\t\t\t\t\t[ jqXHR, s, isSuccess ? success : error ] );\n\t\t\t}\n\n\t\t\t// Complete\n\t\t\tcompleteDeferred.fireWith( callbackContext, [ jqXHR, statusText ] );\n\n\t\t\tif ( fireGlobals ) {\n\t\t\t\tglobalEventContext.trigger( \"ajaxComplete\", [ jqXHR, s ] );\n\n\t\t\t\t// Handle the global AJAX counter\n\t\t\t\tif ( !( --jQuery.active ) ) {\n\t\t\t\t\tjQuery.event.trigger( \"ajaxStop\" );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn jqXHR;\n\t},\n\n\tgetJSON: function( url, data, callback ) {\n\t\treturn jQuery.get( url, data, callback, \"json\" );\n\t},\n\n\tgetScript: function( url, callback ) {\n\t\treturn jQuery.get( url, undefined, callback, \"script\" );\n\t}\n} );\n\njQuery.each( [ \"get\", \"post\" ], function( i, method ) {\n\tjQuery[ method ] = function( url, data, callback, type ) {\n\n\t\t// Shift arguments if data argument was omitted\n\t\tif ( isFunction( data ) ) {\n\t\t\ttype = type || callback;\n\t\t\tcallback = data;\n\t\t\tdata = undefined;\n\t\t}\n\n\t\t// The url can be an options object (which then must have .url)\n\t\treturn jQuery.ajax( jQuery.extend( {\n\t\t\turl: url,\n\t\t\ttype: method,\n\t\t\tdataType: type,\n\t\t\tdata: data,\n\t\t\tsuccess: callback\n\t\t}, jQuery.isPlainObject( url ) && url ) );\n\t};\n} );\n\n\njQuery._evalUrl = function( url, options ) {\n\treturn jQuery.ajax( {\n\t\turl: url,\n\n\t\t// Make this explicit, since user can override this through ajaxSetup (#11264)\n\t\ttype: \"GET\",\n\t\tdataType: \"script\",\n\t\tcache: true,\n\t\tasync: false,\n\t\tglobal: false,\n\n\t\t// Only evaluate the response if it is successful (gh-4126)\n\t\t// dataFilter is not invoked for failure responses, so using it instead\n\t\t// of the default converter is kludgy but it works.\n\t\tconverters: {\n\t\t\t\"text script\": function() {}\n\t\t},\n\t\tdataFilter: function( response ) {\n\t\t\tjQuery.globalEval( response, options );\n\t\t}\n\t} );\n};\n\n\njQuery.fn.extend( {\n\twrapAll: function( html ) {\n\t\tvar wrap;\n\n\t\tif ( this[ 0 ] ) {\n\t\t\tif ( isFunction( html ) ) {\n\t\t\t\thtml = html.call( this[ 0 ] );\n\t\t\t}\n\n\t\t\t// The elements to wrap the target around\n\t\t\twrap = jQuery( html, this[ 0 ].ownerDocument ).eq( 0 ).clone( true );\n\n\t\t\tif ( this[ 0 ].parentNode ) {\n\t\t\t\twrap.insertBefore( this[ 0 ] );\n\t\t\t}\n\n\t\t\twrap.map( function() {\n\t\t\t\tvar elem = this;\n\n\t\t\t\twhile ( elem.firstElementChild ) {\n\t\t\t\t\telem = elem.firstElementChild;\n\t\t\t\t}\n\n\t\t\t\treturn elem;\n\t\t\t} ).append( this );\n\t\t}\n\n\t\treturn this;\n\t},\n\n\twrapInner: function( html ) {\n\t\tif ( isFunction( html ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).wrapInner( html.call( this, i ) );\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar self = jQuery( this ),\n\t\t\t\tcontents = self.contents();\n\n\t\t\tif ( contents.length ) {\n\t\t\t\tcontents.wrapAll( html );\n\n\t\t\t} else {\n\t\t\t\tself.append( html );\n\t\t\t}\n\t\t} );\n\t},\n\n\twrap: function( html ) {\n\t\tvar htmlIsFunction = isFunction( html );\n\n\t\treturn this.each( function( i ) {\n\t\t\tjQuery( this ).wrapAll( htmlIsFunction ? html.call( this, i ) : html );\n\t\t} );\n\t},\n\n\tunwrap: function( selector ) {\n\t\tthis.parent( selector ).not( \"body\" ).each( function() {\n\t\t\tjQuery( this ).replaceWith( this.childNodes );\n\t\t} );\n\t\treturn this;\n\t}\n} );\n\n\njQuery.expr.pseudos.hidden = function( elem ) {\n\treturn !jQuery.expr.pseudos.visible( elem );\n};\njQuery.expr.pseudos.visible = function( elem ) {\n\treturn !!( elem.offsetWidth || elem.offsetHeight || elem.getClientRects().length );\n};\n\n\n\n\njQuery.ajaxSettings.xhr = function() {\n\ttry {\n\t\treturn new window.XMLHttpRequest();\n\t} catch ( e ) {}\n};\n\nvar xhrSuccessStatus = {\n\n\t\t// File protocol always yields status code 0, assume 200\n\t\t0: 200,\n\n\t\t// Support: IE <=9 only\n\t\t// #1450: sometimes IE returns 1223 when it should be 204\n\t\t1223: 204\n\t},\n\txhrSupported = jQuery.ajaxSettings.xhr();\n\nsupport.cors = !!xhrSupported && ( \"withCredentials\" in xhrSupported );\nsupport.ajax = xhrSupported = !!xhrSupported;\n\njQuery.ajaxTransport( function( options ) {\n\tvar callback, errorCallback;\n\n\t// Cross domain only allowed if supported through XMLHttpRequest\n\tif ( support.cors || xhrSupported && !options.crossDomain ) {\n\t\treturn {\n\t\t\tsend: function( headers, complete ) {\n\t\t\t\tvar i,\n\t\t\t\t\txhr = options.xhr();\n\n\t\t\t\txhr.open(\n\t\t\t\t\toptions.type,\n\t\t\t\t\toptions.url,\n\t\t\t\t\toptions.async,\n\t\t\t\t\toptions.username,\n\t\t\t\t\toptions.password\n\t\t\t\t);\n\n\t\t\t\t// Apply custom fields if provided\n\t\t\t\tif ( options.xhrFields ) {\n\t\t\t\t\tfor ( i in options.xhrFields ) {\n\t\t\t\t\t\txhr[ i ] = options.xhrFields[ i ];\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Override mime type if needed\n\t\t\t\tif ( options.mimeType && xhr.overrideMimeType ) {\n\t\t\t\t\txhr.overrideMimeType( options.mimeType );\n\t\t\t\t}\n\n\t\t\t\t// X-Requested-With header\n\t\t\t\t// For cross-domain requests, seeing as conditions for a preflight are\n\t\t\t\t// akin to a jigsaw puzzle, we simply never set it to be sure.\n\t\t\t\t// (it can always be set on a per-request basis or even using ajaxSetup)\n\t\t\t\t// For same-domain requests, won't change header if already provided.\n\t\t\t\tif ( !options.crossDomain && !headers[ \"X-Requested-With\" ] ) {\n\t\t\t\t\theaders[ \"X-Requested-With\" ] = \"XMLHttpRequest\";\n\t\t\t\t}\n\n\t\t\t\t// Set headers\n\t\t\t\tfor ( i in headers ) {\n\t\t\t\t\txhr.setRequestHeader( i, headers[ i ] );\n\t\t\t\t}\n\n\t\t\t\t// Callback\n\t\t\t\tcallback = function( type ) {\n\t\t\t\t\treturn function() {\n\t\t\t\t\t\tif ( callback ) {\n\t\t\t\t\t\t\tcallback = errorCallback = xhr.onload =\n\t\t\t\t\t\t\t\txhr.onerror = xhr.onabort = xhr.ontimeout =\n\t\t\t\t\t\t\t\t\txhr.onreadystatechange = null;\n\n\t\t\t\t\t\t\tif ( type === \"abort\" ) {\n\t\t\t\t\t\t\t\txhr.abort();\n\t\t\t\t\t\t\t} else if ( type === \"error\" ) {\n\n\t\t\t\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t\t\t\t// On a manual native abort, IE9 throws\n\t\t\t\t\t\t\t\t// errors on any property access that is not readyState\n\t\t\t\t\t\t\t\tif ( typeof xhr.status !== \"number\" ) {\n\t\t\t\t\t\t\t\t\tcomplete( 0, \"error\" );\n\t\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\t\tcomplete(\n\n\t\t\t\t\t\t\t\t\t\t// File: protocol always yields status 0; see #8605, #14207\n\t\t\t\t\t\t\t\t\t\txhr.status,\n\t\t\t\t\t\t\t\t\t\txhr.statusText\n\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tcomplete(\n\t\t\t\t\t\t\t\t\txhrSuccessStatus[ xhr.status ] || xhr.status,\n\t\t\t\t\t\t\t\t\txhr.statusText,\n\n\t\t\t\t\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t\t\t\t\t// IE9 has no XHR2 but throws on binary (trac-11426)\n\t\t\t\t\t\t\t\t\t// For XHR2 non-text, let the caller handle it (gh-2498)\n\t\t\t\t\t\t\t\t\t( xhr.responseType || \"text\" ) !== \"text\"  ||\n\t\t\t\t\t\t\t\t\ttypeof xhr.responseText !== \"string\" ?\n\t\t\t\t\t\t\t\t\t\t{ binary: xhr.response } :\n\t\t\t\t\t\t\t\t\t\t{ text: xhr.responseText },\n\t\t\t\t\t\t\t\t\txhr.getAllResponseHeaders()\n\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t};\n\t\t\t\t};\n\n\t\t\t\t// Listen to events\n\t\t\t\txhr.onload = callback();\n\t\t\t\terrorCallback = xhr.onerror = xhr.ontimeout = callback( \"error\" );\n\n\t\t\t\t// Support: IE 9 only\n\t\t\t\t// Use onreadystatechange to replace onabort\n\t\t\t\t// to handle uncaught aborts\n\t\t\t\tif ( xhr.onabort !== undefined ) {\n\t\t\t\t\txhr.onabort = errorCallback;\n\t\t\t\t} else {\n\t\t\t\t\txhr.onreadystatechange = function() {\n\n\t\t\t\t\t\t// Check readyState before timeout as it changes\n\t\t\t\t\t\tif ( xhr.readyState === 4 ) {\n\n\t\t\t\t\t\t\t// Allow onerror to be called first,\n\t\t\t\t\t\t\t// but that will not handle a native abort\n\t\t\t\t\t\t\t// Also, save errorCallback to a variable\n\t\t\t\t\t\t\t// as xhr.onerror cannot be accessed\n\t\t\t\t\t\t\twindow.setTimeout( function() {\n\t\t\t\t\t\t\t\tif ( callback ) {\n\t\t\t\t\t\t\t\t\terrorCallback();\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t}\n\t\t\t\t\t};\n\t\t\t\t}\n\n\t\t\t\t// Create the abort callback\n\t\t\t\tcallback = callback( \"abort\" );\n\n\t\t\t\ttry {\n\n\t\t\t\t\t// Do send the request (this may raise an exception)\n\t\t\t\t\txhr.send( options.hasContent && options.data || null );\n\t\t\t\t} catch ( e ) {\n\n\t\t\t\t\t// #14683: Only rethrow if this hasn't been notified as an error yet\n\t\t\t\t\tif ( callback ) {\n\t\t\t\t\t\tthrow e;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t},\n\n\t\t\tabort: function() {\n\t\t\t\tif ( callback ) {\n\t\t\t\t\tcallback();\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t}\n} );\n\n\n\n\n// Prevent auto-execution of scripts when no explicit dataType was provided (See gh-2432)\njQuery.ajaxPrefilter( function( s ) {\n\tif ( s.crossDomain ) {\n\t\ts.contents.script = false;\n\t}\n} );\n\n// Install script dataType\njQuery.ajaxSetup( {\n\taccepts: {\n\t\tscript: \"text/javascript, application/javascript, \" +\n\t\t\t\"application/ecmascript, application/x-ecmascript\"\n\t},\n\tcontents: {\n\t\tscript: /\\b(?:java|ecma)script\\b/\n\t},\n\tconverters: {\n\t\t\"text script\": function( text ) {\n\t\t\tjQuery.globalEval( text );\n\t\t\treturn text;\n\t\t}\n\t}\n} );\n\n// Handle cache's special case and crossDomain\njQuery.ajaxPrefilter( \"script\", function( s ) {\n\tif ( s.cache === undefined ) {\n\t\ts.cache = false;\n\t}\n\tif ( s.crossDomain ) {\n\t\ts.type = \"GET\";\n\t}\n} );\n\n// Bind script tag hack transport\njQuery.ajaxTransport( \"script\", function( s ) {\n\n\t// This transport only deals with cross domain or forced-by-attrs requests\n\tif ( s.crossDomain || s.scriptAttrs ) {\n\t\tvar script, callback;\n\t\treturn {\n\t\t\tsend: function( _, complete ) {\n\t\t\t\tscript = jQuery( \"<script>\" )\n\t\t\t\t\t.attr( s.scriptAttrs || {} )\n\t\t\t\t\t.prop( { charset: s.scriptCharset, src: s.url } )\n\t\t\t\t\t.on( \"load error\", callback = function( evt ) {\n\t\t\t\t\t\tscript.remove();\n\t\t\t\t\t\tcallback = null;\n\t\t\t\t\t\tif ( evt ) {\n\t\t\t\t\t\t\tcomplete( evt.type === \"error\" ? 404 : 200, evt.type );\n\t\t\t\t\t\t}\n\t\t\t\t\t} );\n\n\t\t\t\t// Use native DOM manipulation to avoid our domManip AJAX trickery\n\t\t\t\tdocument.head.appendChild( script[ 0 ] );\n\t\t\t},\n\t\t\tabort: function() {\n\t\t\t\tif ( callback ) {\n\t\t\t\t\tcallback();\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t}\n} );\n\n\n\n\nvar oldCallbacks = [],\n\trjsonp = /(=)\\?(?=&|$)|\\?\\?/;\n\n// Default jsonp settings\njQuery.ajaxSetup( {\n\tjsonp: \"callback\",\n\tjsonpCallback: function() {\n\t\tvar callback = oldCallbacks.pop() || ( jQuery.expando + \"_\" + ( nonce++ ) );\n\t\tthis[ callback ] = true;\n\t\treturn callback;\n\t}\n} );\n\n// Detect, normalize options and install callbacks for jsonp requests\njQuery.ajaxPrefilter( \"json jsonp\", function( s, originalSettings, jqXHR ) {\n\n\tvar callbackName, overwritten, responseContainer,\n\t\tjsonProp = s.jsonp !== false && ( rjsonp.test( s.url ) ?\n\t\t\t\"url\" :\n\t\t\ttypeof s.data === \"string\" &&\n\t\t\t\t( s.contentType || \"\" )\n\t\t\t\t\t.indexOf( \"application/x-www-form-urlencoded\" ) === 0 &&\n\t\t\t\trjsonp.test( s.data ) && \"data\"\n\t\t);\n\n\t// Handle iff the expected data type is \"jsonp\" or we have a parameter to set\n\tif ( jsonProp || s.dataTypes[ 0 ] === \"jsonp\" ) {\n\n\t\t// Get callback name, remembering preexisting value associated with it\n\t\tcallbackName = s.jsonpCallback = isFunction( s.jsonpCallback ) ?\n\t\t\ts.jsonpCallback() :\n\t\t\ts.jsonpCallback;\n\n\t\t// Insert callback into url or form data\n\t\tif ( jsonProp ) {\n\t\t\ts[ jsonProp ] = s[ jsonProp ].replace( rjsonp, \"$1\" + callbackName );\n\t\t} else if ( s.jsonp !== false ) {\n\t\t\ts.url += ( rquery.test( s.url ) ? \"&\" : \"?\" ) + s.jsonp + \"=\" + callbackName;\n\t\t}\n\n\t\t// Use data converter to retrieve json after script execution\n\t\ts.converters[ \"script json\" ] = function() {\n\t\t\tif ( !responseContainer ) {\n\t\t\t\tjQuery.error( callbackName + \" was not called\" );\n\t\t\t}\n\t\t\treturn responseContainer[ 0 ];\n\t\t};\n\n\t\t// Force json dataType\n\t\ts.dataTypes[ 0 ] = \"json\";\n\n\t\t// Install callback\n\t\toverwritten = window[ callbackName ];\n\t\twindow[ callbackName ] = function() {\n\t\t\tresponseContainer = arguments;\n\t\t};\n\n\t\t// Clean-up function (fires after converters)\n\t\tjqXHR.always( function() {\n\n\t\t\t// If previous value didn't exist - remove it\n\t\t\tif ( overwritten === undefined ) {\n\t\t\t\tjQuery( window ).removeProp( callbackName );\n\n\t\t\t// Otherwise restore preexisting value\n\t\t\t} else {\n\t\t\t\twindow[ callbackName ] = overwritten;\n\t\t\t}\n\n\t\t\t// Save back as free\n\t\t\tif ( s[ callbackName ] ) {\n\n\t\t\t\t// Make sure that re-using the options doesn't screw things around\n\t\t\t\ts.jsonpCallback = originalSettings.jsonpCallback;\n\n\t\t\t\t// Save the callback name for future use\n\t\t\t\toldCallbacks.push( callbackName );\n\t\t\t}\n\n\t\t\t// Call if it was a function and we have a response\n\t\t\tif ( responseContainer && isFunction( overwritten ) ) {\n\t\t\t\toverwritten( responseContainer[ 0 ] );\n\t\t\t}\n\n\t\t\tresponseContainer = overwritten = undefined;\n\t\t} );\n\n\t\t// Delegate to script\n\t\treturn \"script\";\n\t}\n} );\n\n\n\n\n// Support: Safari 8 only\n// In Safari 8 documents created via document.implementation.createHTMLDocument\n// collapse sibling forms: the second one becomes a child of the first one.\n// Because of that, this security measure has to be disabled in Safari 8.\n// https://bugs.webkit.org/show_bug.cgi?id=137337\nsupport.createHTMLDocument = ( function() {\n\tvar body = document.implementation.createHTMLDocument( \"\" ).body;\n\tbody.innerHTML = \"<form></form><form></form>\";\n\treturn body.childNodes.length === 2;\n} )();\n\n\n// Argument \"data\" should be string of html\n// context (optional): If specified, the fragment will be created in this context,\n// defaults to document\n// keepScripts (optional): If true, will include scripts passed in the html string\njQuery.parseHTML = function( data, context, keepScripts ) {\n\tif ( typeof data !== \"string\" ) {\n\t\treturn [];\n\t}\n\tif ( typeof context === \"boolean\" ) {\n\t\tkeepScripts = context;\n\t\tcontext = false;\n\t}\n\n\tvar base, parsed, scripts;\n\n\tif ( !context ) {\n\n\t\t// Stop scripts or inline event handlers from being executed immediately\n\t\t// by using document.implementation\n\t\tif ( support.createHTMLDocument ) {\n\t\t\tcontext = document.implementation.createHTMLDocument( \"\" );\n\n\t\t\t// Set the base href for the created document\n\t\t\t// so any parsed elements with URLs\n\t\t\t// are based on the document's URL (gh-2965)\n\t\t\tbase = context.createElement( \"base\" );\n\t\t\tbase.href = document.location.href;\n\t\t\tcontext.head.appendChild( base );\n\t\t} else {\n\t\t\tcontext = document;\n\t\t}\n\t}\n\n\tparsed = rsingleTag.exec( data );\n\tscripts = !keepScripts && [];\n\n\t// Single tag\n\tif ( parsed ) {\n\t\treturn [ context.createElement( parsed[ 1 ] ) ];\n\t}\n\n\tparsed = buildFragment( [ data ], context, scripts );\n\n\tif ( scripts && scripts.length ) {\n\t\tjQuery( scripts ).remove();\n\t}\n\n\treturn jQuery.merge( [], parsed.childNodes );\n};\n\n\n/**\n * Load a url into a page\n */\njQuery.fn.load = function( url, params, callback ) {\n\tvar selector, type, response,\n\t\tself = this,\n\t\toff = url.indexOf( \" \" );\n\n\tif ( off > -1 ) {\n\t\tselector = stripAndCollapse( url.slice( off ) );\n\t\turl = url.slice( 0, off );\n\t}\n\n\t// If it's a function\n\tif ( isFunction( params ) ) {\n\n\t\t// We assume that it's the callback\n\t\tcallback = params;\n\t\tparams = undefined;\n\n\t// Otherwise, build a param string\n\t} else if ( params && typeof params === \"object\" ) {\n\t\ttype = \"POST\";\n\t}\n\n\t// If we have elements to modify, make the request\n\tif ( self.length > 0 ) {\n\t\tjQuery.ajax( {\n\t\t\turl: url,\n\n\t\t\t// If \"type\" variable is undefined, then \"GET\" method will be used.\n\t\t\t// Make value of this field explicit since\n\t\t\t// user can override it through ajaxSetup method\n\t\t\ttype: type || \"GET\",\n\t\t\tdataType: \"html\",\n\t\t\tdata: params\n\t\t} ).done( function( responseText ) {\n\n\t\t\t// Save response for use in complete callback\n\t\t\tresponse = arguments;\n\n\t\t\tself.html( selector ?\n\n\t\t\t\t// If a selector was specified, locate the right elements in a dummy div\n\t\t\t\t// Exclude scripts to avoid IE 'Permission Denied' errors\n\t\t\t\tjQuery( \"<div>\" ).append( jQuery.parseHTML( responseText ) ).find( selector ) :\n\n\t\t\t\t// Otherwise use the full result\n\t\t\t\tresponseText );\n\n\t\t// If the request succeeds, this function gets \"data\", \"status\", \"jqXHR\"\n\t\t// but they are ignored because response was set above.\n\t\t// If it fails, this function gets \"jqXHR\", \"status\", \"error\"\n\t\t} ).always( callback && function( jqXHR, status ) {\n\t\t\tself.each( function() {\n\t\t\t\tcallback.apply( this, response || [ jqXHR.responseText, status, jqXHR ] );\n\t\t\t} );\n\t\t} );\n\t}\n\n\treturn this;\n};\n\n\n\n\n// Attach a bunch of functions for handling common AJAX events\njQuery.each( [\n\t\"ajaxStart\",\n\t\"ajaxStop\",\n\t\"ajaxComplete\",\n\t\"ajaxError\",\n\t\"ajaxSuccess\",\n\t\"ajaxSend\"\n], function( i, type ) {\n\tjQuery.fn[ type ] = function( fn ) {\n\t\treturn this.on( type, fn );\n\t};\n} );\n\n\n\n\njQuery.expr.pseudos.animated = function( elem ) {\n\treturn jQuery.grep( jQuery.timers, function( fn ) {\n\t\treturn elem === fn.elem;\n\t} ).length;\n};\n\n\n\n\njQuery.offset = {\n\tsetOffset: function( elem, options, i ) {\n\t\tvar curPosition, curLeft, curCSSTop, curTop, curOffset, curCSSLeft, calculatePosition,\n\t\t\tposition = jQuery.css( elem, \"position\" ),\n\t\t\tcurElem = jQuery( elem ),\n\t\t\tprops = {};\n\n\t\t// Set position first, in-case top/left are set even on static elem\n\t\tif ( position === \"static\" ) {\n\t\t\telem.style.position = \"relative\";\n\t\t}\n\n\t\tcurOffset = curElem.offset();\n\t\tcurCSSTop = jQuery.css( elem, \"top\" );\n\t\tcurCSSLeft = jQuery.css( elem, \"left\" );\n\t\tcalculatePosition = ( position === \"absolute\" || position === \"fixed\" ) &&\n\t\t\t( curCSSTop + curCSSLeft ).indexOf( \"auto\" ) > -1;\n\n\t\t// Need to be able to calculate position if either\n\t\t// top or left is auto and position is either absolute or fixed\n\t\tif ( calculatePosition ) {\n\t\t\tcurPosition = curElem.position();\n\t\t\tcurTop = curPosition.top;\n\t\t\tcurLeft = curPosition.left;\n\n\t\t} else {\n\t\t\tcurTop = parseFloat( curCSSTop ) || 0;\n\t\t\tcurLeft = parseFloat( curCSSLeft ) || 0;\n\t\t}\n\n\t\tif ( isFunction( options ) ) {\n\n\t\t\t// Use jQuery.extend here to allow modification of coordinates argument (gh-1848)\n\t\t\toptions = options.call( elem, i, jQuery.extend( {}, curOffset ) );\n\t\t}\n\n\t\tif ( options.top != null ) {\n\t\t\tprops.top = ( options.top - curOffset.top ) + curTop;\n\t\t}\n\t\tif ( options.left != null ) {\n\t\t\tprops.left = ( options.left - curOffset.left ) + curLeft;\n\t\t}\n\n\t\tif ( \"using\" in options ) {\n\t\t\toptions.using.call( elem, props );\n\n\t\t} else {\n\t\t\tcurElem.css( props );\n\t\t}\n\t}\n};\n\njQuery.fn.extend( {\n\n\t// offset() relates an element's border box to the document origin\n\toffset: function( options ) {\n\n\t\t// Preserve chaining for setter\n\t\tif ( arguments.length ) {\n\t\t\treturn options === undefined ?\n\t\t\t\tthis :\n\t\t\t\tthis.each( function( i ) {\n\t\t\t\t\tjQuery.offset.setOffset( this, options, i );\n\t\t\t\t} );\n\t\t}\n\n\t\tvar rect, win,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !elem ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Return zeros for disconnected and hidden (display: none) elements (gh-2310)\n\t\t// Support: IE <=11 only\n\t\t// Running getBoundingClientRect on a\n\t\t// disconnected node in IE throws an error\n\t\tif ( !elem.getClientRects().length ) {\n\t\t\treturn { top: 0, left: 0 };\n\t\t}\n\n\t\t// Get document-relative position by adding viewport scroll to viewport-relative gBCR\n\t\trect = elem.getBoundingClientRect();\n\t\twin = elem.ownerDocument.defaultView;\n\t\treturn {\n\t\t\ttop: rect.top + win.pageYOffset,\n\t\t\tleft: rect.left + win.pageXOffset\n\t\t};\n\t},\n\n\t// position() relates an element's margin box to its offset parent's padding box\n\t// This corresponds to the behavior of CSS absolute positioning\n\tposition: function() {\n\t\tif ( !this[ 0 ] ) {\n\t\t\treturn;\n\t\t}\n\n\t\tvar offsetParent, offset, doc,\n\t\t\telem = this[ 0 ],\n\t\t\tparentOffset = { top: 0, left: 0 };\n\n\t\t// position:fixed elements are offset from the viewport, which itself always has zero offset\n\t\tif ( jQuery.css( elem, \"position\" ) === \"fixed\" ) {\n\n\t\t\t// Assume position:fixed implies availability of getBoundingClientRect\n\t\t\toffset = elem.getBoundingClientRect();\n\n\t\t} else {\n\t\t\toffset = this.offset();\n\n\t\t\t// Account for the *real* offset parent, which can be the document or its root element\n\t\t\t// when a statically positioned element is identified\n\t\t\tdoc = elem.ownerDocument;\n\t\t\toffsetParent = elem.offsetParent || doc.documentElement;\n\t\t\twhile ( offsetParent &&\n\t\t\t\t( offsetParent === doc.body || offsetParent === doc.documentElement ) &&\n\t\t\t\tjQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\n\t\t\t\toffsetParent = offsetParent.parentNode;\n\t\t\t}\n\t\t\tif ( offsetParent && offsetParent !== elem && offsetParent.nodeType === 1 ) {\n\n\t\t\t\t// Incorporate borders into its offset, since they are outside its content origin\n\t\t\t\tparentOffset = jQuery( offsetParent ).offset();\n\t\t\t\tparentOffset.top += jQuery.css( offsetParent, \"borderTopWidth\", true );\n\t\t\t\tparentOffset.left += jQuery.css( offsetParent, \"borderLeftWidth\", true );\n\t\t\t}\n\t\t}\n\n\t\t// Subtract parent offsets and element margins\n\t\treturn {\n\t\t\ttop: offset.top - parentOffset.top - jQuery.css( elem, \"marginTop\", true ),\n\t\t\tleft: offset.left - parentOffset.left - jQuery.css( elem, \"marginLeft\", true )\n\t\t};\n\t},\n\n\t// This method will return documentElement in the following cases:\n\t// 1) For the element inside the iframe without offsetParent, this method will return\n\t//    documentElement of the parent window\n\t// 2) For the hidden or detached element\n\t// 3) For body or html element, i.e. in case of the html node - it will return itself\n\t//\n\t// but those exceptions were never presented as a real life use-cases\n\t// and might be considered as more preferable results.\n\t//\n\t// This logic, however, is not guaranteed and can change at any point in the future\n\toffsetParent: function() {\n\t\treturn this.map( function() {\n\t\t\tvar offsetParent = this.offsetParent;\n\n\t\t\twhile ( offsetParent && jQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\t\t\t\toffsetParent = offsetParent.offsetParent;\n\t\t\t}\n\n\t\t\treturn offsetParent || documentElement;\n\t\t} );\n\t}\n} );\n\n// Create scrollLeft and scrollTop methods\njQuery.each( { scrollLeft: \"pageXOffset\", scrollTop: \"pageYOffset\" }, function( method, prop ) {\n\tvar top = \"pageYOffset\" === prop;\n\n\tjQuery.fn[ method ] = function( val ) {\n\t\treturn access( this, function( elem, method, val ) {\n\n\t\t\t// Coalesce documents and windows\n\t\t\tvar win;\n\t\t\tif ( isWindow( elem ) ) {\n\t\t\t\twin = elem;\n\t\t\t} else if ( elem.nodeType === 9 ) {\n\t\t\t\twin = elem.defaultView;\n\t\t\t}\n\n\t\t\tif ( val === undefined ) {\n\t\t\t\treturn win ? win[ prop ] : elem[ method ];\n\t\t\t}\n\n\t\t\tif ( win ) {\n\t\t\t\twin.scrollTo(\n\t\t\t\t\t!top ? val : win.pageXOffset,\n\t\t\t\t\ttop ? val : win.pageYOffset\n\t\t\t\t);\n\n\t\t\t} else {\n\t\t\t\telem[ method ] = val;\n\t\t\t}\n\t\t}, method, val, arguments.length );\n\t};\n} );\n\n// Support: Safari <=7 - 9.1, Chrome <=37 - 49\n// Add the top/left cssHooks using jQuery.fn.position\n// Webkit bug: https://bugs.webkit.org/show_bug.cgi?id=29084\n// Blink bug: https://bugs.chromium.org/p/chromium/issues/detail?id=589347\n// getComputedStyle returns percent when specified for top/left/bottom/right;\n// rather than make the css module depend on the offset module, just check for it here\njQuery.each( [ \"top\", \"left\" ], function( i, prop ) {\n\tjQuery.cssHooks[ prop ] = addGetHookIf( support.pixelPosition,\n\t\tfunction( elem, computed ) {\n\t\t\tif ( computed ) {\n\t\t\t\tcomputed = curCSS( elem, prop );\n\n\t\t\t\t// If curCSS returns percentage, fallback to offset\n\t\t\t\treturn rnumnonpx.test( computed ) ?\n\t\t\t\t\tjQuery( elem ).position()[ prop ] + \"px\" :\n\t\t\t\t\tcomputed;\n\t\t\t}\n\t\t}\n\t);\n} );\n\n\n// Create innerHeight, innerWidth, height, width, outerHeight and outerWidth methods\njQuery.each( { Height: \"height\", Width: \"width\" }, function( name, type ) {\n\tjQuery.each( { padding: \"inner\" + name, content: type, \"\": \"outer\" + name },\n\t\tfunction( defaultExtra, funcName ) {\n\n\t\t// Margin is only for outerHeight, outerWidth\n\t\tjQuery.fn[ funcName ] = function( margin, value ) {\n\t\t\tvar chainable = arguments.length && ( defaultExtra || typeof margin !== \"boolean\" ),\n\t\t\t\textra = defaultExtra || ( margin === true || value === true ? \"margin\" : \"border\" );\n\n\t\t\treturn access( this, function( elem, type, value ) {\n\t\t\t\tvar doc;\n\n\t\t\t\tif ( isWindow( elem ) ) {\n\n\t\t\t\t\t// $( window ).outerWidth/Height return w/h including scrollbars (gh-1729)\n\t\t\t\t\treturn funcName.indexOf( \"outer\" ) === 0 ?\n\t\t\t\t\t\telem[ \"inner\" + name ] :\n\t\t\t\t\t\telem.document.documentElement[ \"client\" + name ];\n\t\t\t\t}\n\n\t\t\t\t// Get document width or height\n\t\t\t\tif ( elem.nodeType === 9 ) {\n\t\t\t\t\tdoc = elem.documentElement;\n\n\t\t\t\t\t// Either scroll[Width/Height] or offset[Width/Height] or client[Width/Height],\n\t\t\t\t\t// whichever is greatest\n\t\t\t\t\treturn Math.max(\n\t\t\t\t\t\telem.body[ \"scroll\" + name ], doc[ \"scroll\" + name ],\n\t\t\t\t\t\telem.body[ \"offset\" + name ], doc[ \"offset\" + name ],\n\t\t\t\t\t\tdoc[ \"client\" + name ]\n\t\t\t\t\t);\n\t\t\t\t}\n\n\t\t\t\treturn value === undefined ?\n\n\t\t\t\t\t// Get width or height on the element, requesting but not forcing parseFloat\n\t\t\t\t\tjQuery.css( elem, type, extra ) :\n\n\t\t\t\t\t// Set width or height on the element\n\t\t\t\t\tjQuery.style( elem, type, value, extra );\n\t\t\t}, type, chainable ? margin : undefined, chainable );\n\t\t};\n\t} );\n} );\n\n\njQuery.each( ( \"blur focus focusin focusout resize scroll click dblclick \" +\n\t\"mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave \" +\n\t\"change select submit keydown keypress keyup contextmenu\" ).split( \" \" ),\n\tfunction( i, name ) {\n\n\t// Handle event binding\n\tjQuery.fn[ name ] = function( data, fn ) {\n\t\treturn arguments.length > 0 ?\n\t\t\tthis.on( name, null, data, fn ) :\n\t\t\tthis.trigger( name );\n\t};\n} );\n\njQuery.fn.extend( {\n\thover: function( fnOver, fnOut ) {\n\t\treturn this.mouseenter( fnOver ).mouseleave( fnOut || fnOver );\n\t}\n} );\n\n\n\n\njQuery.fn.extend( {\n\n\tbind: function( types, data, fn ) {\n\t\treturn this.on( types, null, data, fn );\n\t},\n\tunbind: function( types, fn ) {\n\t\treturn this.off( types, null, fn );\n\t},\n\n\tdelegate: function( selector, types, data, fn ) {\n\t\treturn this.on( types, selector, data, fn );\n\t},\n\tundelegate: function( selector, types, fn ) {\n\n\t\t// ( namespace ) or ( selector, types [, fn] )\n\t\treturn arguments.length === 1 ?\n\t\t\tthis.off( selector, \"**\" ) :\n\t\t\tthis.off( types, selector || \"**\", fn );\n\t}\n} );\n\n// Bind a function to a context, optionally partially applying any\n// arguments.\n// jQuery.proxy is deprecated to promote standards (specifically Function#bind)\n// However, it is not slated for removal any time soon\njQuery.proxy = function( fn, context ) {\n\tvar tmp, args, proxy;\n\n\tif ( typeof context === \"string\" ) {\n\t\ttmp = fn[ context ];\n\t\tcontext = fn;\n\t\tfn = tmp;\n\t}\n\n\t// Quick check to determine if target is callable, in the spec\n\t// this throws a TypeError, but we will just return undefined.\n\tif ( !isFunction( fn ) ) {\n\t\treturn undefined;\n\t}\n\n\t// Simulated bind\n\targs = slice.call( arguments, 2 );\n\tproxy = function() {\n\t\treturn fn.apply( context || this, args.concat( slice.call( arguments ) ) );\n\t};\n\n\t// Set the guid of unique handler to the same of original handler, so it can be removed\n\tproxy.guid = fn.guid = fn.guid || jQuery.guid++;\n\n\treturn proxy;\n};\n\njQuery.holdReady = function( hold ) {\n\tif ( hold ) {\n\t\tjQuery.readyWait++;\n\t} else {\n\t\tjQuery.ready( true );\n\t}\n};\njQuery.isArray = Array.isArray;\njQuery.parseJSON = JSON.parse;\njQuery.nodeName = nodeName;\njQuery.isFunction = isFunction;\njQuery.isWindow = isWindow;\njQuery.camelCase = camelCase;\njQuery.type = toType;\n\njQuery.now = Date.now;\n\njQuery.isNumeric = function( obj ) {\n\n\t// As of jQuery 3.0, isNumeric is limited to\n\t// strings and numbers (primitives or objects)\n\t// that can be coerced to finite numbers (gh-2662)\n\tvar type = jQuery.type( obj );\n\treturn ( type === \"number\" || type === \"string\" ) &&\n\n\t\t// parseFloat NaNs numeric-cast false positives (\"\")\n\t\t// ...but misinterprets leading-number strings, particularly hex literals (\"0x...\")\n\t\t// subtraction forces infinities to NaN\n\t\t!isNaN( obj - parseFloat( obj ) );\n};\n\n\n\n\n// Register as a named AMD module, since jQuery can be concatenated with other\n// files that may use define, but not via a proper concatenation script that\n// understands anonymous AMD modules. A named AMD is safest and most robust\n// way to register. Lowercase jquery is used because AMD module names are\n// derived from file names, and jQuery is normally delivered in a lowercase\n// file name. Do this after creating the global so that if an AMD module wants\n// to call noConflict to hide this version of jQuery, it will work.\n\n// Note that for maximum portability, libraries that are not jQuery should\n// declare themselves as anonymous modules, and avoid setting a global if an\n// AMD loader is present. jQuery is a special case. For more information, see\n// https://github.com/jrburke/requirejs/wiki/Updating-existing-libraries#wiki-anon\n\nif ( typeof define === \"function\" && define.amd ) {\n\tdefine( \"jquery\", [], function() {\n\t\treturn jQuery;\n\t} );\n}\n\n\n\n\nvar\n\n\t// Map over jQuery in case of overwrite\n\t_jQuery = window.jQuery,\n\n\t// Map over the $ in case of overwrite\n\t_$ = window.$;\n\njQuery.noConflict = function( deep ) {\n\tif ( window.$ === jQuery ) {\n\t\twindow.$ = _$;\n\t}\n\n\tif ( deep && window.jQuery === jQuery ) {\n\t\twindow.jQuery = _jQuery;\n\t}\n\n\treturn jQuery;\n};\n\n// Expose jQuery and $ identifiers, even in AMD\n// (#7102#comment:10, https://github.com/jquery/jquery/pull/557)\n// and CommonJS for browser emulators (#13566)\nif ( !noGlobal ) {\n\twindow.jQuery = window.$ = jQuery;\n}\n\n\n\n\nreturn jQuery;\n} );\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/jquery/jquery.slim.js",
    "content": "/*!\n * jQuery JavaScript Library v3.4.1 -ajax,-ajax/jsonp,-ajax/load,-ajax/parseXML,-ajax/script,-ajax/var/location,-ajax/var/nonce,-ajax/var/rquery,-ajax/xhr,-manipulation/_evalUrl,-event/ajax,-effects,-effects/Tween,-effects/animatedSelector\n * https://jquery.com/\n *\n * Includes Sizzle.js\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://jquery.org/license\n *\n * Date: 2019-05-01T21:04Z\n */\n( function( global, factory ) {\n\n\t\"use strict\";\n\n\tif ( typeof module === \"object\" && typeof module.exports === \"object\" ) {\n\n\t\t// For CommonJS and CommonJS-like environments where a proper `window`\n\t\t// is present, execute the factory and get jQuery.\n\t\t// For environments that do not have a `window` with a `document`\n\t\t// (such as Node.js), expose a factory as module.exports.\n\t\t// This accentuates the need for the creation of a real `window`.\n\t\t// e.g. var jQuery = require(\"jquery\")(window);\n\t\t// See ticket #14549 for more info.\n\t\tmodule.exports = global.document ?\n\t\t\tfactory( global, true ) :\n\t\t\tfunction( w ) {\n\t\t\t\tif ( !w.document ) {\n\t\t\t\t\tthrow new Error( \"jQuery requires a window with a document\" );\n\t\t\t\t}\n\t\t\t\treturn factory( w );\n\t\t\t};\n\t} else {\n\t\tfactory( global );\n\t}\n\n// Pass this if window is not defined yet\n} )( typeof window !== \"undefined\" ? window : this, function( window, noGlobal ) {\n\n// Edge <= 12 - 13+, Firefox <=18 - 45+, IE 10 - 11, Safari 5.1 - 9+, iOS 6 - 9.1\n// throw exceptions when non-strict code (e.g., ASP.NET 4.5) accesses strict mode\n// arguments.callee.caller (trac-13335). But as of jQuery 3.0 (2016), strict mode should be common\n// enough that all such attempts are guarded in a try block.\n\"use strict\";\n\nvar arr = [];\n\nvar document = window.document;\n\nvar getProto = Object.getPrototypeOf;\n\nvar slice = arr.slice;\n\nvar concat = arr.concat;\n\nvar push = arr.push;\n\nvar indexOf = arr.indexOf;\n\nvar class2type = {};\n\nvar toString = class2type.toString;\n\nvar hasOwn = class2type.hasOwnProperty;\n\nvar fnToString = hasOwn.toString;\n\nvar ObjectFunctionString = fnToString.call( Object );\n\nvar support = {};\n\nvar isFunction = function isFunction( obj ) {\n\n      // Support: Chrome <=57, Firefox <=52\n      // In some browsers, typeof returns \"function\" for HTML <object> elements\n      // (i.e., `typeof document.createElement( \"object\" ) === \"function\"`).\n      // We don't want to classify *any* DOM node as a function.\n      return typeof obj === \"function\" && typeof obj.nodeType !== \"number\";\n  };\n\n\nvar isWindow = function isWindow( obj ) {\n\t\treturn obj != null && obj === obj.window;\n\t};\n\n\n\n\n\tvar preservedScriptAttributes = {\n\t\ttype: true,\n\t\tsrc: true,\n\t\tnonce: true,\n\t\tnoModule: true\n\t};\n\n\tfunction DOMEval( code, node, doc ) {\n\t\tdoc = doc || document;\n\n\t\tvar i, val,\n\t\t\tscript = doc.createElement( \"script\" );\n\n\t\tscript.text = code;\n\t\tif ( node ) {\n\t\t\tfor ( i in preservedScriptAttributes ) {\n\n\t\t\t\t// Support: Firefox 64+, Edge 18+\n\t\t\t\t// Some browsers don't support the \"nonce\" property on scripts.\n\t\t\t\t// On the other hand, just using `getAttribute` is not enough as\n\t\t\t\t// the `nonce` attribute is reset to an empty string whenever it\n\t\t\t\t// becomes browsing-context connected.\n\t\t\t\t// See https://github.com/whatwg/html/issues/2369\n\t\t\t\t// See https://html.spec.whatwg.org/#nonce-attributes\n\t\t\t\t// The `node.getAttribute` check was added for the sake of\n\t\t\t\t// `jQuery.globalEval` so that it can fake a nonce-containing node\n\t\t\t\t// via an object.\n\t\t\t\tval = node[ i ] || node.getAttribute && node.getAttribute( i );\n\t\t\t\tif ( val ) {\n\t\t\t\t\tscript.setAttribute( i, val );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tdoc.head.appendChild( script ).parentNode.removeChild( script );\n\t}\n\n\nfunction toType( obj ) {\n\tif ( obj == null ) {\n\t\treturn obj + \"\";\n\t}\n\n\t// Support: Android <=2.3 only (functionish RegExp)\n\treturn typeof obj === \"object\" || typeof obj === \"function\" ?\n\t\tclass2type[ toString.call( obj ) ] || \"object\" :\n\t\ttypeof obj;\n}\n/* global Symbol */\n// Defining this global in .eslintrc.json would create a danger of using the global\n// unguarded in another place, it seems safer to define global only for this module\n\n\n\nvar\n\tversion = \"3.4.1 -ajax,-ajax/jsonp,-ajax/load,-ajax/parseXML,-ajax/script,-ajax/var/location,-ajax/var/nonce,-ajax/var/rquery,-ajax/xhr,-manipulation/_evalUrl,-event/ajax,-effects,-effects/Tween,-effects/animatedSelector\",\n\n\t// Define a local copy of jQuery\n\tjQuery = function( selector, context ) {\n\n\t\t// The jQuery object is actually just the init constructor 'enhanced'\n\t\t// Need init if jQuery is called (just allow error to be thrown if not included)\n\t\treturn new jQuery.fn.init( selector, context );\n\t},\n\n\t// Support: Android <=4.0 only\n\t// Make sure we trim BOM and NBSP\n\trtrim = /^[\\s\\uFEFF\\xA0]+|[\\s\\uFEFF\\xA0]+$/g;\n\njQuery.fn = jQuery.prototype = {\n\n\t// The current version of jQuery being used\n\tjquery: version,\n\n\tconstructor: jQuery,\n\n\t// The default length of a jQuery object is 0\n\tlength: 0,\n\n\ttoArray: function() {\n\t\treturn slice.call( this );\n\t},\n\n\t// Get the Nth element in the matched element set OR\n\t// Get the whole matched element set as a clean array\n\tget: function( num ) {\n\n\t\t// Return all the elements in a clean array\n\t\tif ( num == null ) {\n\t\t\treturn slice.call( this );\n\t\t}\n\n\t\t// Return just the one element from the set\n\t\treturn num < 0 ? this[ num + this.length ] : this[ num ];\n\t},\n\n\t// Take an array of elements and push it onto the stack\n\t// (returning the new matched element set)\n\tpushStack: function( elems ) {\n\n\t\t// Build a new jQuery matched element set\n\t\tvar ret = jQuery.merge( this.constructor(), elems );\n\n\t\t// Add the old object onto the stack (as a reference)\n\t\tret.prevObject = this;\n\n\t\t// Return the newly-formed element set\n\t\treturn ret;\n\t},\n\n\t// Execute a callback for every element in the matched set.\n\teach: function( callback ) {\n\t\treturn jQuery.each( this, callback );\n\t},\n\n\tmap: function( callback ) {\n\t\treturn this.pushStack( jQuery.map( this, function( elem, i ) {\n\t\t\treturn callback.call( elem, i, elem );\n\t\t} ) );\n\t},\n\n\tslice: function() {\n\t\treturn this.pushStack( slice.apply( this, arguments ) );\n\t},\n\n\tfirst: function() {\n\t\treturn this.eq( 0 );\n\t},\n\n\tlast: function() {\n\t\treturn this.eq( -1 );\n\t},\n\n\teq: function( i ) {\n\t\tvar len = this.length,\n\t\t\tj = +i + ( i < 0 ? len : 0 );\n\t\treturn this.pushStack( j >= 0 && j < len ? [ this[ j ] ] : [] );\n\t},\n\n\tend: function() {\n\t\treturn this.prevObject || this.constructor();\n\t},\n\n\t// For internal use only.\n\t// Behaves like an Array's method, not like a jQuery method.\n\tpush: push,\n\tsort: arr.sort,\n\tsplice: arr.splice\n};\n\njQuery.extend = jQuery.fn.extend = function() {\n\tvar options, name, src, copy, copyIsArray, clone,\n\t\ttarget = arguments[ 0 ] || {},\n\t\ti = 1,\n\t\tlength = arguments.length,\n\t\tdeep = false;\n\n\t// Handle a deep copy situation\n\tif ( typeof target === \"boolean\" ) {\n\t\tdeep = target;\n\n\t\t// Skip the boolean and the target\n\t\ttarget = arguments[ i ] || {};\n\t\ti++;\n\t}\n\n\t// Handle case when target is a string or something (possible in deep copy)\n\tif ( typeof target !== \"object\" && !isFunction( target ) ) {\n\t\ttarget = {};\n\t}\n\n\t// Extend jQuery itself if only one argument is passed\n\tif ( i === length ) {\n\t\ttarget = this;\n\t\ti--;\n\t}\n\n\tfor ( ; i < length; i++ ) {\n\n\t\t// Only deal with non-null/undefined values\n\t\tif ( ( options = arguments[ i ] ) != null ) {\n\n\t\t\t// Extend the base object\n\t\t\tfor ( name in options ) {\n\t\t\t\tcopy = options[ name ];\n\n\t\t\t\t// Prevent Object.prototype pollution\n\t\t\t\t// Prevent never-ending loop\n\t\t\t\tif ( name === \"__proto__\" || target === copy ) {\n\t\t\t\t\tcontinue;\n\t\t\t\t}\n\n\t\t\t\t// Recurse if we're merging plain objects or arrays\n\t\t\t\tif ( deep && copy && ( jQuery.isPlainObject( copy ) ||\n\t\t\t\t\t( copyIsArray = Array.isArray( copy ) ) ) ) {\n\t\t\t\t\tsrc = target[ name ];\n\n\t\t\t\t\t// Ensure proper type for the source value\n\t\t\t\t\tif ( copyIsArray && !Array.isArray( src ) ) {\n\t\t\t\t\t\tclone = [];\n\t\t\t\t\t} else if ( !copyIsArray && !jQuery.isPlainObject( src ) ) {\n\t\t\t\t\t\tclone = {};\n\t\t\t\t\t} else {\n\t\t\t\t\t\tclone = src;\n\t\t\t\t\t}\n\t\t\t\t\tcopyIsArray = false;\n\n\t\t\t\t\t// Never move original objects, clone them\n\t\t\t\t\ttarget[ name ] = jQuery.extend( deep, clone, copy );\n\n\t\t\t\t// Don't bring in undefined values\n\t\t\t\t} else if ( copy !== undefined ) {\n\t\t\t\t\ttarget[ name ] = copy;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Return the modified object\n\treturn target;\n};\n\njQuery.extend( {\n\n\t// Unique for each copy of jQuery on the page\n\texpando: \"jQuery\" + ( version + Math.random() ).replace( /\\D/g, \"\" ),\n\n\t// Assume jQuery is ready without the ready module\n\tisReady: true,\n\n\terror: function( msg ) {\n\t\tthrow new Error( msg );\n\t},\n\n\tnoop: function() {},\n\n\tisPlainObject: function( obj ) {\n\t\tvar proto, Ctor;\n\n\t\t// Detect obvious negatives\n\t\t// Use toString instead of jQuery.type to catch host objects\n\t\tif ( !obj || toString.call( obj ) !== \"[object Object]\" ) {\n\t\t\treturn false;\n\t\t}\n\n\t\tproto = getProto( obj );\n\n\t\t// Objects with no prototype (e.g., `Object.create( null )`) are plain\n\t\tif ( !proto ) {\n\t\t\treturn true;\n\t\t}\n\n\t\t// Objects with prototype are plain iff they were constructed by a global Object function\n\t\tCtor = hasOwn.call( proto, \"constructor\" ) && proto.constructor;\n\t\treturn typeof Ctor === \"function\" && fnToString.call( Ctor ) === ObjectFunctionString;\n\t},\n\n\tisEmptyObject: function( obj ) {\n\t\tvar name;\n\n\t\tfor ( name in obj ) {\n\t\t\treturn false;\n\t\t}\n\t\treturn true;\n\t},\n\n\t// Evaluates a script in a global context\n\tglobalEval: function( code, options ) {\n\t\tDOMEval( code, { nonce: options && options.nonce } );\n\t},\n\n\teach: function( obj, callback ) {\n\t\tvar length, i = 0;\n\n\t\tif ( isArrayLike( obj ) ) {\n\t\t\tlength = obj.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t} else {\n\t\t\tfor ( i in obj ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn obj;\n\t},\n\n\t// Support: Android <=4.0 only\n\ttrim: function( text ) {\n\t\treturn text == null ?\n\t\t\t\"\" :\n\t\t\t( text + \"\" ).replace( rtrim, \"\" );\n\t},\n\n\t// results is for internal usage only\n\tmakeArray: function( arr, results ) {\n\t\tvar ret = results || [];\n\n\t\tif ( arr != null ) {\n\t\t\tif ( isArrayLike( Object( arr ) ) ) {\n\t\t\t\tjQuery.merge( ret,\n\t\t\t\t\ttypeof arr === \"string\" ?\n\t\t\t\t\t[ arr ] : arr\n\t\t\t\t);\n\t\t\t} else {\n\t\t\t\tpush.call( ret, arr );\n\t\t\t}\n\t\t}\n\n\t\treturn ret;\n\t},\n\n\tinArray: function( elem, arr, i ) {\n\t\treturn arr == null ? -1 : indexOf.call( arr, elem, i );\n\t},\n\n\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t// push.apply(_, arraylike) throws on ancient WebKit\n\tmerge: function( first, second ) {\n\t\tvar len = +second.length,\n\t\t\tj = 0,\n\t\t\ti = first.length;\n\n\t\tfor ( ; j < len; j++ ) {\n\t\t\tfirst[ i++ ] = second[ j ];\n\t\t}\n\n\t\tfirst.length = i;\n\n\t\treturn first;\n\t},\n\n\tgrep: function( elems, callback, invert ) {\n\t\tvar callbackInverse,\n\t\t\tmatches = [],\n\t\t\ti = 0,\n\t\t\tlength = elems.length,\n\t\t\tcallbackExpect = !invert;\n\n\t\t// Go through the array, only saving the items\n\t\t// that pass the validator function\n\t\tfor ( ; i < length; i++ ) {\n\t\t\tcallbackInverse = !callback( elems[ i ], i );\n\t\t\tif ( callbackInverse !== callbackExpect ) {\n\t\t\t\tmatches.push( elems[ i ] );\n\t\t\t}\n\t\t}\n\n\t\treturn matches;\n\t},\n\n\t// arg is for internal usage only\n\tmap: function( elems, callback, arg ) {\n\t\tvar length, value,\n\t\t\ti = 0,\n\t\t\tret = [];\n\n\t\t// Go through the array, translating each of the items to their new values\n\t\tif ( isArrayLike( elems ) ) {\n\t\t\tlength = elems.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Go through every key on the object,\n\t\t} else {\n\t\t\tfor ( i in elems ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Flatten any nested arrays\n\t\treturn concat.apply( [], ret );\n\t},\n\n\t// A global GUID counter for objects\n\tguid: 1,\n\n\t// jQuery.support is not used in Core but other projects attach their\n\t// properties to it so it needs to exist.\n\tsupport: support\n} );\n\nif ( typeof Symbol === \"function\" ) {\n\tjQuery.fn[ Symbol.iterator ] = arr[ Symbol.iterator ];\n}\n\n// Populate the class2type map\njQuery.each( \"Boolean Number String Function Array Date RegExp Object Error Symbol\".split( \" \" ),\nfunction( i, name ) {\n\tclass2type[ \"[object \" + name + \"]\" ] = name.toLowerCase();\n} );\n\nfunction isArrayLike( obj ) {\n\n\t// Support: real iOS 8.2 only (not reproducible in simulator)\n\t// `in` check used to prevent JIT error (gh-2145)\n\t// hasOwn isn't used here due to false negatives\n\t// regarding Nodelist length in IE\n\tvar length = !!obj && \"length\" in obj && obj.length,\n\t\ttype = toType( obj );\n\n\tif ( isFunction( obj ) || isWindow( obj ) ) {\n\t\treturn false;\n\t}\n\n\treturn type === \"array\" || length === 0 ||\n\t\ttypeof length === \"number\" && length > 0 && ( length - 1 ) in obj;\n}\nvar Sizzle =\n/*!\n * Sizzle CSS Selector Engine v2.3.4\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://js.foundation/\n *\n * Date: 2019-04-08\n */\n(function( window ) {\n\nvar i,\n\tsupport,\n\tExpr,\n\tgetText,\n\tisXML,\n\ttokenize,\n\tcompile,\n\tselect,\n\toutermostContext,\n\tsortInput,\n\thasDuplicate,\n\n\t// Local document vars\n\tsetDocument,\n\tdocument,\n\tdocElem,\n\tdocumentIsHTML,\n\trbuggyQSA,\n\trbuggyMatches,\n\tmatches,\n\tcontains,\n\n\t// Instance-specific data\n\texpando = \"sizzle\" + 1 * new Date(),\n\tpreferredDoc = window.document,\n\tdirruns = 0,\n\tdone = 0,\n\tclassCache = createCache(),\n\ttokenCache = createCache(),\n\tcompilerCache = createCache(),\n\tnonnativeSelectorCache = createCache(),\n\tsortOrder = function( a, b ) {\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t}\n\t\treturn 0;\n\t},\n\n\t// Instance methods\n\thasOwn = ({}).hasOwnProperty,\n\tarr = [],\n\tpop = arr.pop,\n\tpush_native = arr.push,\n\tpush = arr.push,\n\tslice = arr.slice,\n\t// Use a stripped-down indexOf as it's faster than native\n\t// https://jsperf.com/thor-indexof-vs-for/5\n\tindexOf = function( list, elem ) {\n\t\tvar i = 0,\n\t\t\tlen = list.length;\n\t\tfor ( ; i < len; i++ ) {\n\t\t\tif ( list[i] === elem ) {\n\t\t\t\treturn i;\n\t\t\t}\n\t\t}\n\t\treturn -1;\n\t},\n\n\tbooleans = \"checked|selected|async|autofocus|autoplay|controls|defer|disabled|hidden|ismap|loop|multiple|open|readonly|required|scoped\",\n\n\t// Regular expressions\n\n\t// http://www.w3.org/TR/css3-selectors/#whitespace\n\twhitespace = \"[\\\\x20\\\\t\\\\r\\\\n\\\\f]\",\n\n\t// http://www.w3.org/TR/CSS21/syndata.html#value-def-identifier\n\tidentifier = \"(?:\\\\\\\\.|[\\\\w-]|[^\\0-\\\\xa0])+\",\n\n\t// Attribute selectors: http://www.w3.org/TR/selectors/#attribute-selectors\n\tattributes = \"\\\\[\" + whitespace + \"*(\" + identifier + \")(?:\" + whitespace +\n\t\t// Operator (capture 2)\n\t\t\"*([*^$|!~]?=)\" + whitespace +\n\t\t// \"Attribute values must be CSS identifiers [capture 5] or strings [capture 3 or capture 4]\"\n\t\t\"*(?:'((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\"|(\" + identifier + \"))|)\" + whitespace +\n\t\t\"*\\\\]\",\n\n\tpseudos = \":(\" + identifier + \")(?:\\\\((\" +\n\t\t// To reduce the number of selectors needing tokenize in the preFilter, prefer arguments:\n\t\t// 1. quoted (capture 3; capture 4 or capture 5)\n\t\t\"('((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\")|\" +\n\t\t// 2. simple (capture 6)\n\t\t\"((?:\\\\\\\\.|[^\\\\\\\\()[\\\\]]|\" + attributes + \")*)|\" +\n\t\t// 3. anything else (capture 2)\n\t\t\".*\" +\n\t\t\")\\\\)|)\",\n\n\t// Leading and non-escaped trailing whitespace, capturing some non-whitespace characters preceding the latter\n\trwhitespace = new RegExp( whitespace + \"+\", \"g\" ),\n\trtrim = new RegExp( \"^\" + whitespace + \"+|((?:^|[^\\\\\\\\])(?:\\\\\\\\.)*)\" + whitespace + \"+$\", \"g\" ),\n\n\trcomma = new RegExp( \"^\" + whitespace + \"*,\" + whitespace + \"*\" ),\n\trcombinators = new RegExp( \"^\" + whitespace + \"*([>+~]|\" + whitespace + \")\" + whitespace + \"*\" ),\n\trdescend = new RegExp( whitespace + \"|>\" ),\n\n\trpseudo = new RegExp( pseudos ),\n\tridentifier = new RegExp( \"^\" + identifier + \"$\" ),\n\n\tmatchExpr = {\n\t\t\"ID\": new RegExp( \"^#(\" + identifier + \")\" ),\n\t\t\"CLASS\": new RegExp( \"^\\\\.(\" + identifier + \")\" ),\n\t\t\"TAG\": new RegExp( \"^(\" + identifier + \"|[*])\" ),\n\t\t\"ATTR\": new RegExp( \"^\" + attributes ),\n\t\t\"PSEUDO\": new RegExp( \"^\" + pseudos ),\n\t\t\"CHILD\": new RegExp( \"^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\\\(\" + whitespace +\n\t\t\t\"*(even|odd|(([+-]|)(\\\\d*)n|)\" + whitespace + \"*(?:([+-]|)\" + whitespace +\n\t\t\t\"*(\\\\d+)|))\" + whitespace + \"*\\\\)|)\", \"i\" ),\n\t\t\"bool\": new RegExp( \"^(?:\" + booleans + \")$\", \"i\" ),\n\t\t// For use in libraries implementing .is()\n\t\t// We use this for POS matching in `select`\n\t\t\"needsContext\": new RegExp( \"^\" + whitespace + \"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\\\(\" +\n\t\t\twhitespace + \"*((?:-\\\\d)?\\\\d*)\" + whitespace + \"*\\\\)|)(?=[^-]|$)\", \"i\" )\n\t},\n\n\trhtml = /HTML$/i,\n\trinputs = /^(?:input|select|textarea|button)$/i,\n\trheader = /^h\\d$/i,\n\n\trnative = /^[^{]+\\{\\s*\\[native \\w/,\n\n\t// Easily-parseable/retrievable ID or TAG or CLASS selectors\n\trquickExpr = /^(?:#([\\w-]+)|(\\w+)|\\.([\\w-]+))$/,\n\n\trsibling = /[+~]/,\n\n\t// CSS escapes\n\t// http://www.w3.org/TR/CSS21/syndata.html#escaped-characters\n\trunescape = new RegExp( \"\\\\\\\\([\\\\da-f]{1,6}\" + whitespace + \"?|(\" + whitespace + \")|.)\", \"ig\" ),\n\tfunescape = function( _, escaped, escapedWhitespace ) {\n\t\tvar high = \"0x\" + escaped - 0x10000;\n\t\t// NaN means non-codepoint\n\t\t// Support: Firefox<24\n\t\t// Workaround erroneous numeric interpretation of +\"0x\"\n\t\treturn high !== high || escapedWhitespace ?\n\t\t\tescaped :\n\t\t\thigh < 0 ?\n\t\t\t\t// BMP codepoint\n\t\t\t\tString.fromCharCode( high + 0x10000 ) :\n\t\t\t\t// Supplemental Plane codepoint (surrogate pair)\n\t\t\t\tString.fromCharCode( high >> 10 | 0xD800, high & 0x3FF | 0xDC00 );\n\t},\n\n\t// CSS string/identifier serialization\n\t// https://drafts.csswg.org/cssom/#common-serializing-idioms\n\trcssescape = /([\\0-\\x1f\\x7f]|^-?\\d)|^-$|[^\\0-\\x1f\\x7f-\\uFFFF\\w-]/g,\n\tfcssescape = function( ch, asCodePoint ) {\n\t\tif ( asCodePoint ) {\n\n\t\t\t// U+0000 NULL becomes U+FFFD REPLACEMENT CHARACTER\n\t\t\tif ( ch === \"\\0\" ) {\n\t\t\t\treturn \"\\uFFFD\";\n\t\t\t}\n\n\t\t\t// Control characters and (dependent upon position) numbers get escaped as code points\n\t\t\treturn ch.slice( 0, -1 ) + \"\\\\\" + ch.charCodeAt( ch.length - 1 ).toString( 16 ) + \" \";\n\t\t}\n\n\t\t// Other potentially-special ASCII characters get backslash-escaped\n\t\treturn \"\\\\\" + ch;\n\t},\n\n\t// Used for iframes\n\t// See setDocument()\n\t// Removing the function wrapper causes a \"Permission Denied\"\n\t// error in IE\n\tunloadHandler = function() {\n\t\tsetDocument();\n\t},\n\n\tinDisabledFieldset = addCombinator(\n\t\tfunction( elem ) {\n\t\t\treturn elem.disabled === true && elem.nodeName.toLowerCase() === \"fieldset\";\n\t\t},\n\t\t{ dir: \"parentNode\", next: \"legend\" }\n\t);\n\n// Optimize for push.apply( _, NodeList )\ntry {\n\tpush.apply(\n\t\t(arr = slice.call( preferredDoc.childNodes )),\n\t\tpreferredDoc.childNodes\n\t);\n\t// Support: Android<4.0\n\t// Detect silently failing push.apply\n\tarr[ preferredDoc.childNodes.length ].nodeType;\n} catch ( e ) {\n\tpush = { apply: arr.length ?\n\n\t\t// Leverage slice if possible\n\t\tfunction( target, els ) {\n\t\t\tpush_native.apply( target, slice.call(els) );\n\t\t} :\n\n\t\t// Support: IE<9\n\t\t// Otherwise append directly\n\t\tfunction( target, els ) {\n\t\t\tvar j = target.length,\n\t\t\t\ti = 0;\n\t\t\t// Can't trust NodeList.length\n\t\t\twhile ( (target[j++] = els[i++]) ) {}\n\t\t\ttarget.length = j - 1;\n\t\t}\n\t};\n}\n\nfunction Sizzle( selector, context, results, seed ) {\n\tvar m, i, elem, nid, match, groups, newSelector,\n\t\tnewContext = context && context.ownerDocument,\n\n\t\t// nodeType defaults to 9, since context defaults to document\n\t\tnodeType = context ? context.nodeType : 9;\n\n\tresults = results || [];\n\n\t// Return early from calls with invalid selector or context\n\tif ( typeof selector !== \"string\" || !selector ||\n\t\tnodeType !== 1 && nodeType !== 9 && nodeType !== 11 ) {\n\n\t\treturn results;\n\t}\n\n\t// Try to shortcut find operations (as opposed to filters) in HTML documents\n\tif ( !seed ) {\n\n\t\tif ( ( context ? context.ownerDocument || context : preferredDoc ) !== document ) {\n\t\t\tsetDocument( context );\n\t\t}\n\t\tcontext = context || document;\n\n\t\tif ( documentIsHTML ) {\n\n\t\t\t// If the selector is sufficiently simple, try using a \"get*By*\" DOM method\n\t\t\t// (excepting DocumentFragment context, where the methods don't exist)\n\t\t\tif ( nodeType !== 11 && (match = rquickExpr.exec( selector )) ) {\n\n\t\t\t\t// ID selector\n\t\t\t\tif ( (m = match[1]) ) {\n\n\t\t\t\t\t// Document context\n\t\t\t\t\tif ( nodeType === 9 ) {\n\t\t\t\t\t\tif ( (elem = context.getElementById( m )) ) {\n\n\t\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\t\tif ( elem.id === m ) {\n\t\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t// Element context\n\t\t\t\t\t} else {\n\n\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\tif ( newContext && (elem = newContext.getElementById( m )) &&\n\t\t\t\t\t\t\tcontains( context, elem ) &&\n\t\t\t\t\t\t\telem.id === m ) {\n\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t// Type selector\n\t\t\t\t} else if ( match[2] ) {\n\t\t\t\t\tpush.apply( results, context.getElementsByTagName( selector ) );\n\t\t\t\t\treturn results;\n\n\t\t\t\t// Class selector\n\t\t\t\t} else if ( (m = match[3]) && support.getElementsByClassName &&\n\t\t\t\t\tcontext.getElementsByClassName ) {\n\n\t\t\t\t\tpush.apply( results, context.getElementsByClassName( m ) );\n\t\t\t\t\treturn results;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Take advantage of querySelectorAll\n\t\t\tif ( support.qsa &&\n\t\t\t\t!nonnativeSelectorCache[ selector + \" \" ] &&\n\t\t\t\t(!rbuggyQSA || !rbuggyQSA.test( selector )) &&\n\n\t\t\t\t// Support: IE 8 only\n\t\t\t\t// Exclude object elements\n\t\t\t\t(nodeType !== 1 || context.nodeName.toLowerCase() !== \"object\") ) {\n\n\t\t\t\tnewSelector = selector;\n\t\t\t\tnewContext = context;\n\n\t\t\t\t// qSA considers elements outside a scoping root when evaluating child or\n\t\t\t\t// descendant combinators, which is not what we want.\n\t\t\t\t// In such cases, we work around the behavior by prefixing every selector in the\n\t\t\t\t// list with an ID selector referencing the scope context.\n\t\t\t\t// Thanks to Andrew Dupont for this technique.\n\t\t\t\tif ( nodeType === 1 && rdescend.test( selector ) ) {\n\n\t\t\t\t\t// Capture the context ID, setting it first if necessary\n\t\t\t\t\tif ( (nid = context.getAttribute( \"id\" )) ) {\n\t\t\t\t\t\tnid = nid.replace( rcssescape, fcssescape );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tcontext.setAttribute( \"id\", (nid = expando) );\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prefix every selector in the list\n\t\t\t\t\tgroups = tokenize( selector );\n\t\t\t\t\ti = groups.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tgroups[i] = \"#\" + nid + \" \" + toSelector( groups[i] );\n\t\t\t\t\t}\n\t\t\t\t\tnewSelector = groups.join( \",\" );\n\n\t\t\t\t\t// Expand context for sibling selectors\n\t\t\t\t\tnewContext = rsibling.test( selector ) && testContext( context.parentNode ) ||\n\t\t\t\t\t\tcontext;\n\t\t\t\t}\n\n\t\t\t\ttry {\n\t\t\t\t\tpush.apply( results,\n\t\t\t\t\t\tnewContext.querySelectorAll( newSelector )\n\t\t\t\t\t);\n\t\t\t\t\treturn results;\n\t\t\t\t} catch ( qsaError ) {\n\t\t\t\t\tnonnativeSelectorCache( selector, true );\n\t\t\t\t} finally {\n\t\t\t\t\tif ( nid === expando ) {\n\t\t\t\t\t\tcontext.removeAttribute( \"id\" );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// All others\n\treturn select( selector.replace( rtrim, \"$1\" ), context, results, seed );\n}\n\n/**\n * Create key-value caches of limited size\n * @returns {function(string, object)} Returns the Object data after storing it on itself with\n *\tproperty name the (space-suffixed) string and (if the cache is larger than Expr.cacheLength)\n *\tdeleting the oldest entry\n */\nfunction createCache() {\n\tvar keys = [];\n\n\tfunction cache( key, value ) {\n\t\t// Use (key + \" \") to avoid collision with native prototype properties (see Issue #157)\n\t\tif ( keys.push( key + \" \" ) > Expr.cacheLength ) {\n\t\t\t// Only keep the most recent entries\n\t\t\tdelete cache[ keys.shift() ];\n\t\t}\n\t\treturn (cache[ key + \" \" ] = value);\n\t}\n\treturn cache;\n}\n\n/**\n * Mark a function for special use by Sizzle\n * @param {Function} fn The function to mark\n */\nfunction markFunction( fn ) {\n\tfn[ expando ] = true;\n\treturn fn;\n}\n\n/**\n * Support testing using an element\n * @param {Function} fn Passed the created element and returns a boolean result\n */\nfunction assert( fn ) {\n\tvar el = document.createElement(\"fieldset\");\n\n\ttry {\n\t\treturn !!fn( el );\n\t} catch (e) {\n\t\treturn false;\n\t} finally {\n\t\t// Remove from its parent by default\n\t\tif ( el.parentNode ) {\n\t\t\tel.parentNode.removeChild( el );\n\t\t}\n\t\t// release memory in IE\n\t\tel = null;\n\t}\n}\n\n/**\n * Adds the same handler for all of the specified attrs\n * @param {String} attrs Pipe-separated list of attributes\n * @param {Function} handler The method that will be applied\n */\nfunction addHandle( attrs, handler ) {\n\tvar arr = attrs.split(\"|\"),\n\t\ti = arr.length;\n\n\twhile ( i-- ) {\n\t\tExpr.attrHandle[ arr[i] ] = handler;\n\t}\n}\n\n/**\n * Checks document order of two siblings\n * @param {Element} a\n * @param {Element} b\n * @returns {Number} Returns less than 0 if a precedes b, greater than 0 if a follows b\n */\nfunction siblingCheck( a, b ) {\n\tvar cur = b && a,\n\t\tdiff = cur && a.nodeType === 1 && b.nodeType === 1 &&\n\t\t\ta.sourceIndex - b.sourceIndex;\n\n\t// Use IE sourceIndex if available on both nodes\n\tif ( diff ) {\n\t\treturn diff;\n\t}\n\n\t// Check if b follows a\n\tif ( cur ) {\n\t\twhile ( (cur = cur.nextSibling) ) {\n\t\t\tif ( cur === b ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t}\n\n\treturn a ? 1 : -1;\n}\n\n/**\n * Returns a function to use in pseudos for input types\n * @param {String} type\n */\nfunction createInputPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn name === \"input\" && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for buttons\n * @param {String} type\n */\nfunction createButtonPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn (name === \"input\" || name === \"button\") && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for :enabled/:disabled\n * @param {Boolean} disabled true for :disabled; false for :enabled\n */\nfunction createDisabledPseudo( disabled ) {\n\n\t// Known :disabled false positives: fieldset[disabled] > legend:nth-of-type(n+2) :can-disable\n\treturn function( elem ) {\n\n\t\t// Only certain elements can match :enabled or :disabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-enabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-disabled\n\t\tif ( \"form\" in elem ) {\n\n\t\t\t// Check for inherited disabledness on relevant non-disabled elements:\n\t\t\t// * listed form-associated elements in a disabled fieldset\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#category-listed\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-fe-disabled\n\t\t\t// * option elements in a disabled optgroup\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-option-disabled\n\t\t\t// All such elements have a \"form\" property.\n\t\t\tif ( elem.parentNode && elem.disabled === false ) {\n\n\t\t\t\t// Option elements defer to a parent optgroup if present\n\t\t\t\tif ( \"label\" in elem ) {\n\t\t\t\t\tif ( \"label\" in elem.parentNode ) {\n\t\t\t\t\t\treturn elem.parentNode.disabled === disabled;\n\t\t\t\t\t} else {\n\t\t\t\t\t\treturn elem.disabled === disabled;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Support: IE 6 - 11\n\t\t\t\t// Use the isDisabled shortcut property to check for disabled fieldset ancestors\n\t\t\t\treturn elem.isDisabled === disabled ||\n\n\t\t\t\t\t// Where there is no isDisabled, check manually\n\t\t\t\t\t/* jshint -W018 */\n\t\t\t\t\telem.isDisabled !== !disabled &&\n\t\t\t\t\t\tinDisabledFieldset( elem ) === disabled;\n\t\t\t}\n\n\t\t\treturn elem.disabled === disabled;\n\n\t\t// Try to winnow out elements that can't be disabled before trusting the disabled property.\n\t\t// Some victims get caught in our net (label, legend, menu, track), but it shouldn't\n\t\t// even exist on them, let alone have a boolean value.\n\t\t} else if ( \"label\" in elem ) {\n\t\t\treturn elem.disabled === disabled;\n\t\t}\n\n\t\t// Remaining elements are neither :enabled nor :disabled\n\t\treturn false;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for positionals\n * @param {Function} fn\n */\nfunction createPositionalPseudo( fn ) {\n\treturn markFunction(function( argument ) {\n\t\targument = +argument;\n\t\treturn markFunction(function( seed, matches ) {\n\t\t\tvar j,\n\t\t\t\tmatchIndexes = fn( [], seed.length, argument ),\n\t\t\t\ti = matchIndexes.length;\n\n\t\t\t// Match elements found at the specified indexes\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( seed[ (j = matchIndexes[i]) ] ) {\n\t\t\t\t\tseed[j] = !(matches[j] = seed[j]);\n\t\t\t\t}\n\t\t\t}\n\t\t});\n\t});\n}\n\n/**\n * Checks a node for validity as a Sizzle context\n * @param {Element|Object=} context\n * @returns {Element|Object|Boolean} The input node if acceptable, otherwise a falsy value\n */\nfunction testContext( context ) {\n\treturn context && typeof context.getElementsByTagName !== \"undefined\" && context;\n}\n\n// Expose support vars for convenience\nsupport = Sizzle.support = {};\n\n/**\n * Detects XML nodes\n * @param {Element|Object} elem An element or a document\n * @returns {Boolean} True iff elem is a non-HTML XML node\n */\nisXML = Sizzle.isXML = function( elem ) {\n\tvar namespace = elem.namespaceURI,\n\t\tdocElem = (elem.ownerDocument || elem).documentElement;\n\n\t// Support: IE <=8\n\t// Assume HTML when documentElement doesn't yet exist, such as inside loading iframes\n\t// https://bugs.jquery.com/ticket/4833\n\treturn !rhtml.test( namespace || docElem && docElem.nodeName || \"HTML\" );\n};\n\n/**\n * Sets document-related variables once based on the current document\n * @param {Element|Object} [doc] An element or document object to use to set the document\n * @returns {Object} Returns the current document\n */\nsetDocument = Sizzle.setDocument = function( node ) {\n\tvar hasCompare, subWindow,\n\t\tdoc = node ? node.ownerDocument || node : preferredDoc;\n\n\t// Return early if doc is invalid or already selected\n\tif ( doc === document || doc.nodeType !== 9 || !doc.documentElement ) {\n\t\treturn document;\n\t}\n\n\t// Update global variables\n\tdocument = doc;\n\tdocElem = document.documentElement;\n\tdocumentIsHTML = !isXML( document );\n\n\t// Support: IE 9-11, Edge\n\t// Accessing iframe documents after unload throws \"permission denied\" errors (jQuery #13936)\n\tif ( preferredDoc !== document &&\n\t\t(subWindow = document.defaultView) && subWindow.top !== subWindow ) {\n\n\t\t// Support: IE 11, Edge\n\t\tif ( subWindow.addEventListener ) {\n\t\t\tsubWindow.addEventListener( \"unload\", unloadHandler, false );\n\n\t\t// Support: IE 9 - 10 only\n\t\t} else if ( subWindow.attachEvent ) {\n\t\t\tsubWindow.attachEvent( \"onunload\", unloadHandler );\n\t\t}\n\t}\n\n\t/* Attributes\n\t---------------------------------------------------------------------- */\n\n\t// Support: IE<8\n\t// Verify that getAttribute really returns attributes and not properties\n\t// (excepting IE8 booleans)\n\tsupport.attributes = assert(function( el ) {\n\t\tel.className = \"i\";\n\t\treturn !el.getAttribute(\"className\");\n\t});\n\n\t/* getElement(s)By*\n\t---------------------------------------------------------------------- */\n\n\t// Check if getElementsByTagName(\"*\") returns only elements\n\tsupport.getElementsByTagName = assert(function( el ) {\n\t\tel.appendChild( document.createComment(\"\") );\n\t\treturn !el.getElementsByTagName(\"*\").length;\n\t});\n\n\t// Support: IE<9\n\tsupport.getElementsByClassName = rnative.test( document.getElementsByClassName );\n\n\t// Support: IE<10\n\t// Check if getElementById returns elements by name\n\t// The broken getElementById methods don't pick up programmatically-set names,\n\t// so use a roundabout getElementsByName test\n\tsupport.getById = assert(function( el ) {\n\t\tdocElem.appendChild( el ).id = expando;\n\t\treturn !document.getElementsByName || !document.getElementsByName( expando ).length;\n\t});\n\n\t// ID filter and find\n\tif ( support.getById ) {\n\t\tExpr.filter[\"ID\"] = function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn elem.getAttribute(\"id\") === attrId;\n\t\t\t};\n\t\t};\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar elem = context.getElementById( id );\n\t\t\t\treturn elem ? [ elem ] : [];\n\t\t\t}\n\t\t};\n\t} else {\n\t\tExpr.filter[\"ID\"] =  function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\tvar node = typeof elem.getAttributeNode !== \"undefined\" &&\n\t\t\t\t\telem.getAttributeNode(\"id\");\n\t\t\t\treturn node && node.value === attrId;\n\t\t\t};\n\t\t};\n\n\t\t// Support: IE 6 - 7 only\n\t\t// getElementById is not reliable as a find shortcut\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar node, i, elems,\n\t\t\t\t\telem = context.getElementById( id );\n\n\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t// Verify the id attribute\n\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t}\n\n\t\t\t\t\t// Fall back on getElementsByName\n\t\t\t\t\telems = context.getElementsByName( id );\n\t\t\t\t\ti = 0;\n\t\t\t\t\twhile ( (elem = elems[i++]) ) {\n\t\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn [];\n\t\t\t}\n\t\t};\n\t}\n\n\t// Tag\n\tExpr.find[\"TAG\"] = support.getElementsByTagName ?\n\t\tfunction( tag, context ) {\n\t\t\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\t\t\treturn context.getElementsByTagName( tag );\n\n\t\t\t// DocumentFragment nodes don't have gEBTN\n\t\t\t} else if ( support.qsa ) {\n\t\t\t\treturn context.querySelectorAll( tag );\n\t\t\t}\n\t\t} :\n\n\t\tfunction( tag, context ) {\n\t\t\tvar elem,\n\t\t\t\ttmp = [],\n\t\t\t\ti = 0,\n\t\t\t\t// By happy coincidence, a (broken) gEBTN appears on DocumentFragment nodes too\n\t\t\t\tresults = context.getElementsByTagName( tag );\n\n\t\t\t// Filter out possible comments\n\t\t\tif ( tag === \"*\" ) {\n\t\t\t\twhile ( (elem = results[i++]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\ttmp.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn tmp;\n\t\t\t}\n\t\t\treturn results;\n\t\t};\n\n\t// Class\n\tExpr.find[\"CLASS\"] = support.getElementsByClassName && function( className, context ) {\n\t\tif ( typeof context.getElementsByClassName !== \"undefined\" && documentIsHTML ) {\n\t\t\treturn context.getElementsByClassName( className );\n\t\t}\n\t};\n\n\t/* QSA/matchesSelector\n\t---------------------------------------------------------------------- */\n\n\t// QSA and matchesSelector support\n\n\t// matchesSelector(:active) reports false when true (IE9/Opera 11.5)\n\trbuggyMatches = [];\n\n\t// qSa(:focus) reports false when true (Chrome 21)\n\t// We allow this because of a bug in IE8/9 that throws an error\n\t// whenever `document.activeElement` is accessed on an iframe\n\t// So, we allow :focus to pass through QSA all the time to avoid the IE error\n\t// See https://bugs.jquery.com/ticket/13378\n\trbuggyQSA = [];\n\n\tif ( (support.qsa = rnative.test( document.querySelectorAll )) ) {\n\t\t// Build QSA regex\n\t\t// Regex strategy adopted from Diego Perini\n\t\tassert(function( el ) {\n\t\t\t// Select is set to empty string on purpose\n\t\t\t// This is to test IE's treatment of not explicitly\n\t\t\t// setting a boolean content attribute,\n\t\t\t// since its presence should be enough\n\t\t\t// https://bugs.jquery.com/ticket/12359\n\t\t\tdocElem.appendChild( el ).innerHTML = \"<a id='\" + expando + \"'></a>\" +\n\t\t\t\t\"<select id='\" + expando + \"-\\r\\\\' msallowcapture=''>\" +\n\t\t\t\t\"<option selected=''></option></select>\";\n\n\t\t\t// Support: IE8, Opera 11-12.16\n\t\t\t// Nothing should be selected when empty strings follow ^= or $= or *=\n\t\t\t// The test attribute must be unknown in Opera but \"safe\" for WinRT\n\t\t\t// https://msdn.microsoft.com/en-us/library/ie/hh465388.aspx#attribute_section\n\t\t\tif ( el.querySelectorAll(\"[msallowcapture^='']\").length ) {\n\t\t\t\trbuggyQSA.push( \"[*^$]=\" + whitespace + \"*(?:''|\\\"\\\")\" );\n\t\t\t}\n\n\t\t\t// Support: IE8\n\t\t\t// Boolean attributes and \"value\" are not treated correctly\n\t\t\tif ( !el.querySelectorAll(\"[selected]\").length ) {\n\t\t\t\trbuggyQSA.push( \"\\\\[\" + whitespace + \"*(?:value|\" + booleans + \")\" );\n\t\t\t}\n\n\t\t\t// Support: Chrome<29, Android<4.4, Safari<7.0+, iOS<7.0+, PhantomJS<1.9.8+\n\t\t\tif ( !el.querySelectorAll( \"[id~=\" + expando + \"-]\" ).length ) {\n\t\t\t\trbuggyQSA.push(\"~=\");\n\t\t\t}\n\n\t\t\t// Webkit/Opera - :checked should return selected option elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( !el.querySelectorAll(\":checked\").length ) {\n\t\t\t\trbuggyQSA.push(\":checked\");\n\t\t\t}\n\n\t\t\t// Support: Safari 8+, iOS 8+\n\t\t\t// https://bugs.webkit.org/show_bug.cgi?id=136851\n\t\t\t// In-page `selector#id sibling-combinator selector` fails\n\t\t\tif ( !el.querySelectorAll( \"a#\" + expando + \"+*\" ).length ) {\n\t\t\t\trbuggyQSA.push(\".#.+[+~]\");\n\t\t\t}\n\t\t});\n\n\t\tassert(function( el ) {\n\t\t\tel.innerHTML = \"<a href='' disabled='disabled'></a>\" +\n\t\t\t\t\"<select disabled='disabled'><option/></select>\";\n\n\t\t\t// Support: Windows 8 Native Apps\n\t\t\t// The type and name attributes are restricted during .innerHTML assignment\n\t\t\tvar input = document.createElement(\"input\");\n\t\t\tinput.setAttribute( \"type\", \"hidden\" );\n\t\t\tel.appendChild( input ).setAttribute( \"name\", \"D\" );\n\n\t\t\t// Support: IE8\n\t\t\t// Enforce case-sensitivity of name attribute\n\t\t\tif ( el.querySelectorAll(\"[name=d]\").length ) {\n\t\t\t\trbuggyQSA.push( \"name\" + whitespace + \"*[*^$|!~]?=\" );\n\t\t\t}\n\n\t\t\t// FF 3.5 - :enabled/:disabled and hidden elements (hidden elements are still enabled)\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( el.querySelectorAll(\":enabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Support: IE9-11+\n\t\t\t// IE's :disabled selector does not pick up the children of disabled fieldsets\n\t\t\tdocElem.appendChild( el ).disabled = true;\n\t\t\tif ( el.querySelectorAll(\":disabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Opera 10-11 does not throw on post-comma invalid pseudos\n\t\t\tel.querySelectorAll(\"*,:x\");\n\t\t\trbuggyQSA.push(\",.*:\");\n\t\t});\n\t}\n\n\tif ( (support.matchesSelector = rnative.test( (matches = docElem.matches ||\n\t\tdocElem.webkitMatchesSelector ||\n\t\tdocElem.mozMatchesSelector ||\n\t\tdocElem.oMatchesSelector ||\n\t\tdocElem.msMatchesSelector) )) ) {\n\n\t\tassert(function( el ) {\n\t\t\t// Check to see if it's possible to do matchesSelector\n\t\t\t// on a disconnected node (IE 9)\n\t\t\tsupport.disconnectedMatch = matches.call( el, \"*\" );\n\n\t\t\t// This should fail with an exception\n\t\t\t// Gecko does not error, returns false instead\n\t\t\tmatches.call( el, \"[s!='']:x\" );\n\t\t\trbuggyMatches.push( \"!=\", pseudos );\n\t\t});\n\t}\n\n\trbuggyQSA = rbuggyQSA.length && new RegExp( rbuggyQSA.join(\"|\") );\n\trbuggyMatches = rbuggyMatches.length && new RegExp( rbuggyMatches.join(\"|\") );\n\n\t/* Contains\n\t---------------------------------------------------------------------- */\n\thasCompare = rnative.test( docElem.compareDocumentPosition );\n\n\t// Element contains another\n\t// Purposefully self-exclusive\n\t// As in, an element does not contain itself\n\tcontains = hasCompare || rnative.test( docElem.contains ) ?\n\t\tfunction( a, b ) {\n\t\t\tvar adown = a.nodeType === 9 ? a.documentElement : a,\n\t\t\t\tbup = b && b.parentNode;\n\t\t\treturn a === bup || !!( bup && bup.nodeType === 1 && (\n\t\t\t\tadown.contains ?\n\t\t\t\t\tadown.contains( bup ) :\n\t\t\t\t\ta.compareDocumentPosition && a.compareDocumentPosition( bup ) & 16\n\t\t\t));\n\t\t} :\n\t\tfunction( a, b ) {\n\t\t\tif ( b ) {\n\t\t\t\twhile ( (b = b.parentNode) ) {\n\t\t\t\t\tif ( b === a ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n\n\t/* Sorting\n\t---------------------------------------------------------------------- */\n\n\t// Document order sorting\n\tsortOrder = hasCompare ?\n\tfunction( a, b ) {\n\n\t\t// Flag for duplicate removal\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\t// Sort on method existence if only one input has compareDocumentPosition\n\t\tvar compare = !a.compareDocumentPosition - !b.compareDocumentPosition;\n\t\tif ( compare ) {\n\t\t\treturn compare;\n\t\t}\n\n\t\t// Calculate position if both inputs belong to the same document\n\t\tcompare = ( a.ownerDocument || a ) === ( b.ownerDocument || b ) ?\n\t\t\ta.compareDocumentPosition( b ) :\n\n\t\t\t// Otherwise we know they are disconnected\n\t\t\t1;\n\n\t\t// Disconnected nodes\n\t\tif ( compare & 1 ||\n\t\t\t(!support.sortDetached && b.compareDocumentPosition( a ) === compare) ) {\n\n\t\t\t// Choose the first element that is related to our preferred document\n\t\t\tif ( a === document || a.ownerDocument === preferredDoc && contains(preferredDoc, a) ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t\tif ( b === document || b.ownerDocument === preferredDoc && contains(preferredDoc, b) ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\t// Maintain original order\n\t\t\treturn sortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\t\t}\n\n\t\treturn compare & 4 ? -1 : 1;\n\t} :\n\tfunction( a, b ) {\n\t\t// Exit early if the nodes are identical\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\taup = a.parentNode,\n\t\t\tbup = b.parentNode,\n\t\t\tap = [ a ],\n\t\t\tbp = [ b ];\n\n\t\t// Parentless nodes are either documents or disconnected\n\t\tif ( !aup || !bup ) {\n\t\t\treturn a === document ? -1 :\n\t\t\t\tb === document ? 1 :\n\t\t\t\taup ? -1 :\n\t\t\t\tbup ? 1 :\n\t\t\t\tsortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\n\t\t// If the nodes are siblings, we can do a quick check\n\t\t} else if ( aup === bup ) {\n\t\t\treturn siblingCheck( a, b );\n\t\t}\n\n\t\t// Otherwise we need full lists of their ancestors for comparison\n\t\tcur = a;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tap.unshift( cur );\n\t\t}\n\t\tcur = b;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tbp.unshift( cur );\n\t\t}\n\n\t\t// Walk down the tree looking for a discrepancy\n\t\twhile ( ap[i] === bp[i] ) {\n\t\t\ti++;\n\t\t}\n\n\t\treturn i ?\n\t\t\t// Do a sibling check if the nodes have a common ancestor\n\t\t\tsiblingCheck( ap[i], bp[i] ) :\n\n\t\t\t// Otherwise nodes in our document sort first\n\t\t\tap[i] === preferredDoc ? -1 :\n\t\t\tbp[i] === preferredDoc ? 1 :\n\t\t\t0;\n\t};\n\n\treturn document;\n};\n\nSizzle.matches = function( expr, elements ) {\n\treturn Sizzle( expr, null, null, elements );\n};\n\nSizzle.matchesSelector = function( elem, expr ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tif ( support.matchesSelector && documentIsHTML &&\n\t\t!nonnativeSelectorCache[ expr + \" \" ] &&\n\t\t( !rbuggyMatches || !rbuggyMatches.test( expr ) ) &&\n\t\t( !rbuggyQSA     || !rbuggyQSA.test( expr ) ) ) {\n\n\t\ttry {\n\t\t\tvar ret = matches.call( elem, expr );\n\n\t\t\t// IE 9's matchesSelector returns false on disconnected nodes\n\t\t\tif ( ret || support.disconnectedMatch ||\n\t\t\t\t\t// As well, disconnected nodes are said to be in a document\n\t\t\t\t\t// fragment in IE 9\n\t\t\t\t\telem.document && elem.document.nodeType !== 11 ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\t\t} catch (e) {\n\t\t\tnonnativeSelectorCache( expr, true );\n\t\t}\n\t}\n\n\treturn Sizzle( expr, document, null, [ elem ] ).length > 0;\n};\n\nSizzle.contains = function( context, elem ) {\n\t// Set document vars if needed\n\tif ( ( context.ownerDocument || context ) !== document ) {\n\t\tsetDocument( context );\n\t}\n\treturn contains( context, elem );\n};\n\nSizzle.attr = function( elem, name ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tvar fn = Expr.attrHandle[ name.toLowerCase() ],\n\t\t// Don't get fooled by Object.prototype properties (jQuery #13807)\n\t\tval = fn && hasOwn.call( Expr.attrHandle, name.toLowerCase() ) ?\n\t\t\tfn( elem, name, !documentIsHTML ) :\n\t\t\tundefined;\n\n\treturn val !== undefined ?\n\t\tval :\n\t\tsupport.attributes || !documentIsHTML ?\n\t\t\telem.getAttribute( name ) :\n\t\t\t(val = elem.getAttributeNode(name)) && val.specified ?\n\t\t\t\tval.value :\n\t\t\t\tnull;\n};\n\nSizzle.escape = function( sel ) {\n\treturn (sel + \"\").replace( rcssescape, fcssescape );\n};\n\nSizzle.error = function( msg ) {\n\tthrow new Error( \"Syntax error, unrecognized expression: \" + msg );\n};\n\n/**\n * Document sorting and removing duplicates\n * @param {ArrayLike} results\n */\nSizzle.uniqueSort = function( results ) {\n\tvar elem,\n\t\tduplicates = [],\n\t\tj = 0,\n\t\ti = 0;\n\n\t// Unless we *know* we can detect duplicates, assume their presence\n\thasDuplicate = !support.detectDuplicates;\n\tsortInput = !support.sortStable && results.slice( 0 );\n\tresults.sort( sortOrder );\n\n\tif ( hasDuplicate ) {\n\t\twhile ( (elem = results[i++]) ) {\n\t\t\tif ( elem === results[ i ] ) {\n\t\t\t\tj = duplicates.push( i );\n\t\t\t}\n\t\t}\n\t\twhile ( j-- ) {\n\t\t\tresults.splice( duplicates[ j ], 1 );\n\t\t}\n\t}\n\n\t// Clear input after sorting to release objects\n\t// See https://github.com/jquery/sizzle/pull/225\n\tsortInput = null;\n\n\treturn results;\n};\n\n/**\n * Utility function for retrieving the text value of an array of DOM nodes\n * @param {Array|Element} elem\n */\ngetText = Sizzle.getText = function( elem ) {\n\tvar node,\n\t\tret = \"\",\n\t\ti = 0,\n\t\tnodeType = elem.nodeType;\n\n\tif ( !nodeType ) {\n\t\t// If no nodeType, this is expected to be an array\n\t\twhile ( (node = elem[i++]) ) {\n\t\t\t// Do not traverse comment nodes\n\t\t\tret += getText( node );\n\t\t}\n\t} else if ( nodeType === 1 || nodeType === 9 || nodeType === 11 ) {\n\t\t// Use textContent for elements\n\t\t// innerText usage removed for consistency of new lines (jQuery #11153)\n\t\tif ( typeof elem.textContent === \"string\" ) {\n\t\t\treturn elem.textContent;\n\t\t} else {\n\t\t\t// Traverse its children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tret += getText( elem );\n\t\t\t}\n\t\t}\n\t} else if ( nodeType === 3 || nodeType === 4 ) {\n\t\treturn elem.nodeValue;\n\t}\n\t// Do not include comment or processing instruction nodes\n\n\treturn ret;\n};\n\nExpr = Sizzle.selectors = {\n\n\t// Can be adjusted by the user\n\tcacheLength: 50,\n\n\tcreatePseudo: markFunction,\n\n\tmatch: matchExpr,\n\n\tattrHandle: {},\n\n\tfind: {},\n\n\trelative: {\n\t\t\">\": { dir: \"parentNode\", first: true },\n\t\t\" \": { dir: \"parentNode\" },\n\t\t\"+\": { dir: \"previousSibling\", first: true },\n\t\t\"~\": { dir: \"previousSibling\" }\n\t},\n\n\tpreFilter: {\n\t\t\"ATTR\": function( match ) {\n\t\t\tmatch[1] = match[1].replace( runescape, funescape );\n\n\t\t\t// Move the given value to match[3] whether quoted or unquoted\n\t\t\tmatch[3] = ( match[3] || match[4] || match[5] || \"\" ).replace( runescape, funescape );\n\n\t\t\tif ( match[2] === \"~=\" ) {\n\t\t\t\tmatch[3] = \" \" + match[3] + \" \";\n\t\t\t}\n\n\t\t\treturn match.slice( 0, 4 );\n\t\t},\n\n\t\t\"CHILD\": function( match ) {\n\t\t\t/* matches from matchExpr[\"CHILD\"]\n\t\t\t\t1 type (only|nth|...)\n\t\t\t\t2 what (child|of-type)\n\t\t\t\t3 argument (even|odd|\\d*|\\d*n([+-]\\d+)?|...)\n\t\t\t\t4 xn-component of xn+y argument ([+-]?\\d*n|)\n\t\t\t\t5 sign of xn-component\n\t\t\t\t6 x of xn-component\n\t\t\t\t7 sign of y-component\n\t\t\t\t8 y of y-component\n\t\t\t*/\n\t\t\tmatch[1] = match[1].toLowerCase();\n\n\t\t\tif ( match[1].slice( 0, 3 ) === \"nth\" ) {\n\t\t\t\t// nth-* requires argument\n\t\t\t\tif ( !match[3] ) {\n\t\t\t\t\tSizzle.error( match[0] );\n\t\t\t\t}\n\n\t\t\t\t// numeric x and y parameters for Expr.filter.CHILD\n\t\t\t\t// remember that false/true cast respectively to 0/1\n\t\t\t\tmatch[4] = +( match[4] ? match[5] + (match[6] || 1) : 2 * ( match[3] === \"even\" || match[3] === \"odd\" ) );\n\t\t\t\tmatch[5] = +( ( match[7] + match[8] ) || match[3] === \"odd\" );\n\n\t\t\t// other types prohibit arguments\n\t\t\t} else if ( match[3] ) {\n\t\t\t\tSizzle.error( match[0] );\n\t\t\t}\n\n\t\t\treturn match;\n\t\t},\n\n\t\t\"PSEUDO\": function( match ) {\n\t\t\tvar excess,\n\t\t\t\tunquoted = !match[6] && match[2];\n\n\t\t\tif ( matchExpr[\"CHILD\"].test( match[0] ) ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\t// Accept quoted arguments as-is\n\t\t\tif ( match[3] ) {\n\t\t\t\tmatch[2] = match[4] || match[5] || \"\";\n\n\t\t\t// Strip excess characters from unquoted arguments\n\t\t\t} else if ( unquoted && rpseudo.test( unquoted ) &&\n\t\t\t\t// Get excess from tokenize (recursively)\n\t\t\t\t(excess = tokenize( unquoted, true )) &&\n\t\t\t\t// advance to the next closing parenthesis\n\t\t\t\t(excess = unquoted.indexOf( \")\", unquoted.length - excess ) - unquoted.length) ) {\n\n\t\t\t\t// excess is a negative index\n\t\t\t\tmatch[0] = match[0].slice( 0, excess );\n\t\t\t\tmatch[2] = unquoted.slice( 0, excess );\n\t\t\t}\n\n\t\t\t// Return only captures needed by the pseudo filter method (type and argument)\n\t\t\treturn match.slice( 0, 3 );\n\t\t}\n\t},\n\n\tfilter: {\n\n\t\t\"TAG\": function( nodeNameSelector ) {\n\t\t\tvar nodeName = nodeNameSelector.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn nodeNameSelector === \"*\" ?\n\t\t\t\tfunction() { return true; } :\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn elem.nodeName && elem.nodeName.toLowerCase() === nodeName;\n\t\t\t\t};\n\t\t},\n\n\t\t\"CLASS\": function( className ) {\n\t\t\tvar pattern = classCache[ className + \" \" ];\n\n\t\t\treturn pattern ||\n\t\t\t\t(pattern = new RegExp( \"(^|\" + whitespace + \")\" + className + \"(\" + whitespace + \"|$)\" )) &&\n\t\t\t\tclassCache( className, function( elem ) {\n\t\t\t\t\treturn pattern.test( typeof elem.className === \"string\" && elem.className || typeof elem.getAttribute !== \"undefined\" && elem.getAttribute(\"class\") || \"\" );\n\t\t\t\t});\n\t\t},\n\n\t\t\"ATTR\": function( name, operator, check ) {\n\t\t\treturn function( elem ) {\n\t\t\t\tvar result = Sizzle.attr( elem, name );\n\n\t\t\t\tif ( result == null ) {\n\t\t\t\t\treturn operator === \"!=\";\n\t\t\t\t}\n\t\t\t\tif ( !operator ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\n\t\t\t\tresult += \"\";\n\n\t\t\t\treturn operator === \"=\" ? result === check :\n\t\t\t\t\toperator === \"!=\" ? result !== check :\n\t\t\t\t\toperator === \"^=\" ? check && result.indexOf( check ) === 0 :\n\t\t\t\t\toperator === \"*=\" ? check && result.indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"$=\" ? check && result.slice( -check.length ) === check :\n\t\t\t\t\toperator === \"~=\" ? ( \" \" + result.replace( rwhitespace, \" \" ) + \" \" ).indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"|=\" ? result === check || result.slice( 0, check.length + 1 ) === check + \"-\" :\n\t\t\t\t\tfalse;\n\t\t\t};\n\t\t},\n\n\t\t\"CHILD\": function( type, what, argument, first, last ) {\n\t\t\tvar simple = type.slice( 0, 3 ) !== \"nth\",\n\t\t\t\tforward = type.slice( -4 ) !== \"last\",\n\t\t\t\tofType = what === \"of-type\";\n\n\t\t\treturn first === 1 && last === 0 ?\n\n\t\t\t\t// Shortcut for :nth-*(n)\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn !!elem.parentNode;\n\t\t\t\t} :\n\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tvar cache, uniqueCache, outerCache, node, nodeIndex, start,\n\t\t\t\t\t\tdir = simple !== forward ? \"nextSibling\" : \"previousSibling\",\n\t\t\t\t\t\tparent = elem.parentNode,\n\t\t\t\t\t\tname = ofType && elem.nodeName.toLowerCase(),\n\t\t\t\t\t\tuseCache = !xml && !ofType,\n\t\t\t\t\t\tdiff = false;\n\n\t\t\t\t\tif ( parent ) {\n\n\t\t\t\t\t\t// :(first|last|only)-(child|of-type)\n\t\t\t\t\t\tif ( simple ) {\n\t\t\t\t\t\t\twhile ( dir ) {\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\twhile ( (node = node[ dir ]) ) {\n\t\t\t\t\t\t\t\t\tif ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) {\n\n\t\t\t\t\t\t\t\t\t\treturn false;\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t// Reverse direction for :only-* (if we haven't yet done so)\n\t\t\t\t\t\t\t\tstart = dir = type === \"only\" && !start && \"nextSibling\";\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\tstart = [ forward ? parent.firstChild : parent.lastChild ];\n\n\t\t\t\t\t\t// non-xml :nth-child(...) stores cache data on `parent`\n\t\t\t\t\t\tif ( forward && useCache ) {\n\n\t\t\t\t\t\t\t// Seek `elem` from a previously-cached index\n\n\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\tnode = parent;\n\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\tdiff = nodeIndex && cache[ 2 ];\n\t\t\t\t\t\t\tnode = nodeIndex && parent.childNodes[ nodeIndex ];\n\n\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\n\t\t\t\t\t\t\t\t// Fallback to seeking `elem` from the start\n\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t// When found, cache indexes on `parent` and break\n\t\t\t\t\t\t\t\tif ( node.nodeType === 1 && ++diff && node === elem ) {\n\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, nodeIndex, diff ];\n\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Use previously-cached element index if available\n\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\t\tdiff = nodeIndex;\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t// xml :nth-child(...)\n\t\t\t\t\t\t\t// or :nth-last-child(...) or :nth(-last)?-of-type(...)\n\t\t\t\t\t\t\tif ( diff === false ) {\n\t\t\t\t\t\t\t\t// Use the same loop as above to seek `elem` from the start\n\t\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\t\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t\tif ( ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) &&\n\t\t\t\t\t\t\t\t\t\t++diff ) {\n\n\t\t\t\t\t\t\t\t\t\t// Cache the index of each encountered element\n\t\t\t\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, diff ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\tif ( node === elem ) {\n\t\t\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Incorporate the offset, then check against cycle size\n\t\t\t\t\t\tdiff -= last;\n\t\t\t\t\t\treturn diff === first || ( diff % first === 0 && diff / first >= 0 );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t},\n\n\t\t\"PSEUDO\": function( pseudo, argument ) {\n\t\t\t// pseudo-class names are case-insensitive\n\t\t\t// http://www.w3.org/TR/selectors/#pseudo-classes\n\t\t\t// Prioritize by case sensitivity in case custom pseudos are added with uppercase letters\n\t\t\t// Remember that setFilters inherits from pseudos\n\t\t\tvar args,\n\t\t\t\tfn = Expr.pseudos[ pseudo ] || Expr.setFilters[ pseudo.toLowerCase() ] ||\n\t\t\t\t\tSizzle.error( \"unsupported pseudo: \" + pseudo );\n\n\t\t\t// The user may use createPseudo to indicate that\n\t\t\t// arguments are needed to create the filter function\n\t\t\t// just as Sizzle does\n\t\t\tif ( fn[ expando ] ) {\n\t\t\t\treturn fn( argument );\n\t\t\t}\n\n\t\t\t// But maintain support for old signatures\n\t\t\tif ( fn.length > 1 ) {\n\t\t\t\targs = [ pseudo, pseudo, \"\", argument ];\n\t\t\t\treturn Expr.setFilters.hasOwnProperty( pseudo.toLowerCase() ) ?\n\t\t\t\t\tmarkFunction(function( seed, matches ) {\n\t\t\t\t\t\tvar idx,\n\t\t\t\t\t\t\tmatched = fn( seed, argument ),\n\t\t\t\t\t\t\ti = matched.length;\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tidx = indexOf( seed, matched[i] );\n\t\t\t\t\t\t\tseed[ idx ] = !( matches[ idx ] = matched[i] );\n\t\t\t\t\t\t}\n\t\t\t\t\t}) :\n\t\t\t\t\tfunction( elem ) {\n\t\t\t\t\t\treturn fn( elem, 0, args );\n\t\t\t\t\t};\n\t\t\t}\n\n\t\t\treturn fn;\n\t\t}\n\t},\n\n\tpseudos: {\n\t\t// Potentially complex pseudos\n\t\t\"not\": markFunction(function( selector ) {\n\t\t\t// Trim the selector passed to compile\n\t\t\t// to avoid treating leading and trailing\n\t\t\t// spaces as combinators\n\t\t\tvar input = [],\n\t\t\t\tresults = [],\n\t\t\t\tmatcher = compile( selector.replace( rtrim, \"$1\" ) );\n\n\t\t\treturn matcher[ expando ] ?\n\t\t\t\tmarkFunction(function( seed, matches, context, xml ) {\n\t\t\t\t\tvar elem,\n\t\t\t\t\t\tunmatched = matcher( seed, null, xml, [] ),\n\t\t\t\t\t\ti = seed.length;\n\n\t\t\t\t\t// Match elements unmatched by `matcher`\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = unmatched[i]) ) {\n\t\t\t\t\t\t\tseed[i] = !(matches[i] = elem);\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}) :\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tinput[0] = elem;\n\t\t\t\t\tmatcher( input, null, xml, results );\n\t\t\t\t\t// Don't keep the element (issue #299)\n\t\t\t\t\tinput[0] = null;\n\t\t\t\t\treturn !results.pop();\n\t\t\t\t};\n\t\t}),\n\n\t\t\"has\": markFunction(function( selector ) {\n\t\t\treturn function( elem ) {\n\t\t\t\treturn Sizzle( selector, elem ).length > 0;\n\t\t\t};\n\t\t}),\n\n\t\t\"contains\": markFunction(function( text ) {\n\t\t\ttext = text.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn ( elem.textContent || getText( elem ) ).indexOf( text ) > -1;\n\t\t\t};\n\t\t}),\n\n\t\t// \"Whether an element is represented by a :lang() selector\n\t\t// is based solely on the element's language value\n\t\t// being equal to the identifier C,\n\t\t// or beginning with the identifier C immediately followed by \"-\".\n\t\t// The matching of C against the element's language value is performed case-insensitively.\n\t\t// The identifier C does not have to be a valid language name.\"\n\t\t// http://www.w3.org/TR/selectors/#lang-pseudo\n\t\t\"lang\": markFunction( function( lang ) {\n\t\t\t// lang value must be a valid identifier\n\t\t\tif ( !ridentifier.test(lang || \"\") ) {\n\t\t\t\tSizzle.error( \"unsupported lang: \" + lang );\n\t\t\t}\n\t\t\tlang = lang.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn function( elem ) {\n\t\t\t\tvar elemLang;\n\t\t\t\tdo {\n\t\t\t\t\tif ( (elemLang = documentIsHTML ?\n\t\t\t\t\t\telem.lang :\n\t\t\t\t\t\telem.getAttribute(\"xml:lang\") || elem.getAttribute(\"lang\")) ) {\n\n\t\t\t\t\t\telemLang = elemLang.toLowerCase();\n\t\t\t\t\t\treturn elemLang === lang || elemLang.indexOf( lang + \"-\" ) === 0;\n\t\t\t\t\t}\n\t\t\t\t} while ( (elem = elem.parentNode) && elem.nodeType === 1 );\n\t\t\t\treturn false;\n\t\t\t};\n\t\t}),\n\n\t\t// Miscellaneous\n\t\t\"target\": function( elem ) {\n\t\t\tvar hash = window.location && window.location.hash;\n\t\t\treturn hash && hash.slice( 1 ) === elem.id;\n\t\t},\n\n\t\t\"root\": function( elem ) {\n\t\t\treturn elem === docElem;\n\t\t},\n\n\t\t\"focus\": function( elem ) {\n\t\t\treturn elem === document.activeElement && (!document.hasFocus || document.hasFocus()) && !!(elem.type || elem.href || ~elem.tabIndex);\n\t\t},\n\n\t\t// Boolean properties\n\t\t\"enabled\": createDisabledPseudo( false ),\n\t\t\"disabled\": createDisabledPseudo( true ),\n\n\t\t\"checked\": function( elem ) {\n\t\t\t// In CSS3, :checked should return both checked and selected elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\tvar nodeName = elem.nodeName.toLowerCase();\n\t\t\treturn (nodeName === \"input\" && !!elem.checked) || (nodeName === \"option\" && !!elem.selected);\n\t\t},\n\n\t\t\"selected\": function( elem ) {\n\t\t\t// Accessing this property makes selected-by-default\n\t\t\t// options in Safari work properly\n\t\t\tif ( elem.parentNode ) {\n\t\t\t\telem.parentNode.selectedIndex;\n\t\t\t}\n\n\t\t\treturn elem.selected === true;\n\t\t},\n\n\t\t// Contents\n\t\t\"empty\": function( elem ) {\n\t\t\t// http://www.w3.org/TR/selectors/#empty-pseudo\n\t\t\t// :empty is negated by element (1) or content nodes (text: 3; cdata: 4; entity ref: 5),\n\t\t\t//   but not by others (comment: 8; processing instruction: 7; etc.)\n\t\t\t// nodeType < 6 works because attributes (2) do not appear as children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tif ( elem.nodeType < 6 ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t},\n\n\t\t\"parent\": function( elem ) {\n\t\t\treturn !Expr.pseudos[\"empty\"]( elem );\n\t\t},\n\n\t\t// Element/input types\n\t\t\"header\": function( elem ) {\n\t\t\treturn rheader.test( elem.nodeName );\n\t\t},\n\n\t\t\"input\": function( elem ) {\n\t\t\treturn rinputs.test( elem.nodeName );\n\t\t},\n\n\t\t\"button\": function( elem ) {\n\t\t\tvar name = elem.nodeName.toLowerCase();\n\t\t\treturn name === \"input\" && elem.type === \"button\" || name === \"button\";\n\t\t},\n\n\t\t\"text\": function( elem ) {\n\t\t\tvar attr;\n\t\t\treturn elem.nodeName.toLowerCase() === \"input\" &&\n\t\t\t\telem.type === \"text\" &&\n\n\t\t\t\t// Support: IE<8\n\t\t\t\t// New HTML5 attribute values (e.g., \"search\") appear with elem.type === \"text\"\n\t\t\t\t( (attr = elem.getAttribute(\"type\")) == null || attr.toLowerCase() === \"text\" );\n\t\t},\n\n\t\t// Position-in-collection\n\t\t\"first\": createPositionalPseudo(function() {\n\t\t\treturn [ 0 ];\n\t\t}),\n\n\t\t\"last\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\treturn [ length - 1 ];\n\t\t}),\n\n\t\t\"eq\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\treturn [ argument < 0 ? argument + length : argument ];\n\t\t}),\n\n\t\t\"even\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"odd\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 1;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"lt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ?\n\t\t\t\targument + length :\n\t\t\t\targument > length ?\n\t\t\t\t\tlength :\n\t\t\t\t\targument;\n\t\t\tfor ( ; --i >= 0; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"gt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ? argument + length : argument;\n\t\t\tfor ( ; ++i < length; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t})\n\t}\n};\n\nExpr.pseudos[\"nth\"] = Expr.pseudos[\"eq\"];\n\n// Add button/input type pseudos\nfor ( i in { radio: true, checkbox: true, file: true, password: true, image: true } ) {\n\tExpr.pseudos[ i ] = createInputPseudo( i );\n}\nfor ( i in { submit: true, reset: true } ) {\n\tExpr.pseudos[ i ] = createButtonPseudo( i );\n}\n\n// Easy API for creating new setFilters\nfunction setFilters() {}\nsetFilters.prototype = Expr.filters = Expr.pseudos;\nExpr.setFilters = new setFilters();\n\ntokenize = Sizzle.tokenize = function( selector, parseOnly ) {\n\tvar matched, match, tokens, type,\n\t\tsoFar, groups, preFilters,\n\t\tcached = tokenCache[ selector + \" \" ];\n\n\tif ( cached ) {\n\t\treturn parseOnly ? 0 : cached.slice( 0 );\n\t}\n\n\tsoFar = selector;\n\tgroups = [];\n\tpreFilters = Expr.preFilter;\n\n\twhile ( soFar ) {\n\n\t\t// Comma and first run\n\t\tif ( !matched || (match = rcomma.exec( soFar )) ) {\n\t\t\tif ( match ) {\n\t\t\t\t// Don't consume trailing commas as valid\n\t\t\t\tsoFar = soFar.slice( match[0].length ) || soFar;\n\t\t\t}\n\t\t\tgroups.push( (tokens = []) );\n\t\t}\n\n\t\tmatched = false;\n\n\t\t// Combinators\n\t\tif ( (match = rcombinators.exec( soFar )) ) {\n\t\t\tmatched = match.shift();\n\t\t\ttokens.push({\n\t\t\t\tvalue: matched,\n\t\t\t\t// Cast descendant combinators to space\n\t\t\t\ttype: match[0].replace( rtrim, \" \" )\n\t\t\t});\n\t\t\tsoFar = soFar.slice( matched.length );\n\t\t}\n\n\t\t// Filters\n\t\tfor ( type in Expr.filter ) {\n\t\t\tif ( (match = matchExpr[ type ].exec( soFar )) && (!preFilters[ type ] ||\n\t\t\t\t(match = preFilters[ type ]( match ))) ) {\n\t\t\t\tmatched = match.shift();\n\t\t\t\ttokens.push({\n\t\t\t\t\tvalue: matched,\n\t\t\t\t\ttype: type,\n\t\t\t\t\tmatches: match\n\t\t\t\t});\n\t\t\t\tsoFar = soFar.slice( matched.length );\n\t\t\t}\n\t\t}\n\n\t\tif ( !matched ) {\n\t\t\tbreak;\n\t\t}\n\t}\n\n\t// Return the length of the invalid excess\n\t// if we're just parsing\n\t// Otherwise, throw an error or return tokens\n\treturn parseOnly ?\n\t\tsoFar.length :\n\t\tsoFar ?\n\t\t\tSizzle.error( selector ) :\n\t\t\t// Cache the tokens\n\t\t\ttokenCache( selector, groups ).slice( 0 );\n};\n\nfunction toSelector( tokens ) {\n\tvar i = 0,\n\t\tlen = tokens.length,\n\t\tselector = \"\";\n\tfor ( ; i < len; i++ ) {\n\t\tselector += tokens[i].value;\n\t}\n\treturn selector;\n}\n\nfunction addCombinator( matcher, combinator, base ) {\n\tvar dir = combinator.dir,\n\t\tskip = combinator.next,\n\t\tkey = skip || dir,\n\t\tcheckNonElements = base && key === \"parentNode\",\n\t\tdoneName = done++;\n\n\treturn combinator.first ?\n\t\t// Check against closest ancestor/preceding element\n\t\tfunction( elem, context, xml ) {\n\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\treturn matcher( elem, context, xml );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t} :\n\n\t\t// Check against all ancestor/preceding elements\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar oldCache, uniqueCache, outerCache,\n\t\t\t\tnewCache = [ dirruns, doneName ];\n\n\t\t\t// We can't set arbitrary data on XML nodes, so they don't benefit from combinator caching\n\t\t\tif ( xml ) {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\tif ( matcher( elem, context, xml ) ) {\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\touterCache = elem[ expando ] || (elem[ expando ] = {});\n\n\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\tuniqueCache = outerCache[ elem.uniqueID ] || (outerCache[ elem.uniqueID ] = {});\n\n\t\t\t\t\t\tif ( skip && skip === elem.nodeName.toLowerCase() ) {\n\t\t\t\t\t\t\telem = elem[ dir ] || elem;\n\t\t\t\t\t\t} else if ( (oldCache = uniqueCache[ key ]) &&\n\t\t\t\t\t\t\toldCache[ 0 ] === dirruns && oldCache[ 1 ] === doneName ) {\n\n\t\t\t\t\t\t\t// Assign to newCache so results back-propagate to previous elements\n\t\t\t\t\t\t\treturn (newCache[ 2 ] = oldCache[ 2 ]);\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Reuse newcache so results back-propagate to previous elements\n\t\t\t\t\t\t\tuniqueCache[ key ] = newCache;\n\n\t\t\t\t\t\t\t// A match means we're done; a fail means we have to keep checking\n\t\t\t\t\t\t\tif ( (newCache[ 2 ] = matcher( elem, context, xml )) ) {\n\t\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n}\n\nfunction elementMatcher( matchers ) {\n\treturn matchers.length > 1 ?\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar i = matchers.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( !matchers[i]( elem, context, xml ) ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t} :\n\t\tmatchers[0];\n}\n\nfunction multipleContexts( selector, contexts, results ) {\n\tvar i = 0,\n\t\tlen = contexts.length;\n\tfor ( ; i < len; i++ ) {\n\t\tSizzle( selector, contexts[i], results );\n\t}\n\treturn results;\n}\n\nfunction condense( unmatched, map, filter, context, xml ) {\n\tvar elem,\n\t\tnewUnmatched = [],\n\t\ti = 0,\n\t\tlen = unmatched.length,\n\t\tmapped = map != null;\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (elem = unmatched[i]) ) {\n\t\t\tif ( !filter || filter( elem, context, xml ) ) {\n\t\t\t\tnewUnmatched.push( elem );\n\t\t\t\tif ( mapped ) {\n\t\t\t\t\tmap.push( i );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn newUnmatched;\n}\n\nfunction setMatcher( preFilter, selector, matcher, postFilter, postFinder, postSelector ) {\n\tif ( postFilter && !postFilter[ expando ] ) {\n\t\tpostFilter = setMatcher( postFilter );\n\t}\n\tif ( postFinder && !postFinder[ expando ] ) {\n\t\tpostFinder = setMatcher( postFinder, postSelector );\n\t}\n\treturn markFunction(function( seed, results, context, xml ) {\n\t\tvar temp, i, elem,\n\t\t\tpreMap = [],\n\t\t\tpostMap = [],\n\t\t\tpreexisting = results.length,\n\n\t\t\t// Get initial elements from seed or context\n\t\t\telems = seed || multipleContexts( selector || \"*\", context.nodeType ? [ context ] : context, [] ),\n\n\t\t\t// Prefilter to get matcher input, preserving a map for seed-results synchronization\n\t\t\tmatcherIn = preFilter && ( seed || !selector ) ?\n\t\t\t\tcondense( elems, preMap, preFilter, context, xml ) :\n\t\t\t\telems,\n\n\t\t\tmatcherOut = matcher ?\n\t\t\t\t// If we have a postFinder, or filtered seed, or non-seed postFilter or preexisting results,\n\t\t\t\tpostFinder || ( seed ? preFilter : preexisting || postFilter ) ?\n\n\t\t\t\t\t// ...intermediate processing is necessary\n\t\t\t\t\t[] :\n\n\t\t\t\t\t// ...otherwise use results directly\n\t\t\t\t\tresults :\n\t\t\t\tmatcherIn;\n\n\t\t// Find primary matches\n\t\tif ( matcher ) {\n\t\t\tmatcher( matcherIn, matcherOut, context, xml );\n\t\t}\n\n\t\t// Apply postFilter\n\t\tif ( postFilter ) {\n\t\t\ttemp = condense( matcherOut, postMap );\n\t\t\tpostFilter( temp, [], context, xml );\n\n\t\t\t// Un-match failing elements by moving them back to matcherIn\n\t\t\ti = temp.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( (elem = temp[i]) ) {\n\t\t\t\t\tmatcherOut[ postMap[i] ] = !(matcherIn[ postMap[i] ] = elem);\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\tif ( seed ) {\n\t\t\tif ( postFinder || preFilter ) {\n\t\t\t\tif ( postFinder ) {\n\t\t\t\t\t// Get the final matcherOut by condensing this intermediate into postFinder contexts\n\t\t\t\t\ttemp = [];\n\t\t\t\t\ti = matcherOut.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = matcherOut[i]) ) {\n\t\t\t\t\t\t\t// Restore matcherIn since elem is not yet a final match\n\t\t\t\t\t\t\ttemp.push( (matcherIn[i] = elem) );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tpostFinder( null, (matcherOut = []), temp, xml );\n\t\t\t\t}\n\n\t\t\t\t// Move matched elements from seed to results to keep them synchronized\n\t\t\t\ti = matcherOut.length;\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\tif ( (elem = matcherOut[i]) &&\n\t\t\t\t\t\t(temp = postFinder ? indexOf( seed, elem ) : preMap[i]) > -1 ) {\n\n\t\t\t\t\t\tseed[temp] = !(results[temp] = elem);\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Add elements to results, through postFinder if defined\n\t\t} else {\n\t\t\tmatcherOut = condense(\n\t\t\t\tmatcherOut === results ?\n\t\t\t\t\tmatcherOut.splice( preexisting, matcherOut.length ) :\n\t\t\t\t\tmatcherOut\n\t\t\t);\n\t\t\tif ( postFinder ) {\n\t\t\t\tpostFinder( null, results, matcherOut, xml );\n\t\t\t} else {\n\t\t\t\tpush.apply( results, matcherOut );\n\t\t\t}\n\t\t}\n\t});\n}\n\nfunction matcherFromTokens( tokens ) {\n\tvar checkContext, matcher, j,\n\t\tlen = tokens.length,\n\t\tleadingRelative = Expr.relative[ tokens[0].type ],\n\t\timplicitRelative = leadingRelative || Expr.relative[\" \"],\n\t\ti = leadingRelative ? 1 : 0,\n\n\t\t// The foundational matcher ensures that elements are reachable from top-level context(s)\n\t\tmatchContext = addCombinator( function( elem ) {\n\t\t\treturn elem === checkContext;\n\t\t}, implicitRelative, true ),\n\t\tmatchAnyContext = addCombinator( function( elem ) {\n\t\t\treturn indexOf( checkContext, elem ) > -1;\n\t\t}, implicitRelative, true ),\n\t\tmatchers = [ function( elem, context, xml ) {\n\t\t\tvar ret = ( !leadingRelative && ( xml || context !== outermostContext ) ) || (\n\t\t\t\t(checkContext = context).nodeType ?\n\t\t\t\t\tmatchContext( elem, context, xml ) :\n\t\t\t\t\tmatchAnyContext( elem, context, xml ) );\n\t\t\t// Avoid hanging onto element (issue #299)\n\t\t\tcheckContext = null;\n\t\t\treturn ret;\n\t\t} ];\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (matcher = Expr.relative[ tokens[i].type ]) ) {\n\t\t\tmatchers = [ addCombinator(elementMatcher( matchers ), matcher) ];\n\t\t} else {\n\t\t\tmatcher = Expr.filter[ tokens[i].type ].apply( null, tokens[i].matches );\n\n\t\t\t// Return special upon seeing a positional matcher\n\t\t\tif ( matcher[ expando ] ) {\n\t\t\t\t// Find the next relative operator (if any) for proper handling\n\t\t\t\tj = ++i;\n\t\t\t\tfor ( ; j < len; j++ ) {\n\t\t\t\t\tif ( Expr.relative[ tokens[j].type ] ) {\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn setMatcher(\n\t\t\t\t\ti > 1 && elementMatcher( matchers ),\n\t\t\t\t\ti > 1 && toSelector(\n\t\t\t\t\t\t// If the preceding token was a descendant combinator, insert an implicit any-element `*`\n\t\t\t\t\t\ttokens.slice( 0, i - 1 ).concat({ value: tokens[ i - 2 ].type === \" \" ? \"*\" : \"\" })\n\t\t\t\t\t).replace( rtrim, \"$1\" ),\n\t\t\t\t\tmatcher,\n\t\t\t\t\ti < j && matcherFromTokens( tokens.slice( i, j ) ),\n\t\t\t\t\tj < len && matcherFromTokens( (tokens = tokens.slice( j )) ),\n\t\t\t\t\tj < len && toSelector( tokens )\n\t\t\t\t);\n\t\t\t}\n\t\t\tmatchers.push( matcher );\n\t\t}\n\t}\n\n\treturn elementMatcher( matchers );\n}\n\nfunction matcherFromGroupMatchers( elementMatchers, setMatchers ) {\n\tvar bySet = setMatchers.length > 0,\n\t\tbyElement = elementMatchers.length > 0,\n\t\tsuperMatcher = function( seed, context, xml, results, outermost ) {\n\t\t\tvar elem, j, matcher,\n\t\t\t\tmatchedCount = 0,\n\t\t\t\ti = \"0\",\n\t\t\t\tunmatched = seed && [],\n\t\t\t\tsetMatched = [],\n\t\t\t\tcontextBackup = outermostContext,\n\t\t\t\t// We must always have either seed elements or outermost context\n\t\t\t\telems = seed || byElement && Expr.find[\"TAG\"]( \"*\", outermost ),\n\t\t\t\t// Use integer dirruns iff this is the outermost matcher\n\t\t\t\tdirrunsUnique = (dirruns += contextBackup == null ? 1 : Math.random() || 0.1),\n\t\t\t\tlen = elems.length;\n\n\t\t\tif ( outermost ) {\n\t\t\t\toutermostContext = context === document || context || outermost;\n\t\t\t}\n\n\t\t\t// Add elements passing elementMatchers directly to results\n\t\t\t// Support: IE<9, Safari\n\t\t\t// Tolerate NodeList properties (IE: \"length\"; Safari: <number>) matching elements by id\n\t\t\tfor ( ; i !== len && (elem = elems[i]) != null; i++ ) {\n\t\t\t\tif ( byElement && elem ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\tif ( !context && elem.ownerDocument !== document ) {\n\t\t\t\t\t\tsetDocument( elem );\n\t\t\t\t\t\txml = !documentIsHTML;\n\t\t\t\t\t}\n\t\t\t\t\twhile ( (matcher = elementMatchers[j++]) ) {\n\t\t\t\t\t\tif ( matcher( elem, context || document, xml) ) {\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( outermost ) {\n\t\t\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Track unmatched elements for set filters\n\t\t\t\tif ( bySet ) {\n\t\t\t\t\t// They will have gone through all possible matchers\n\t\t\t\t\tif ( (elem = !matcher && elem) ) {\n\t\t\t\t\t\tmatchedCount--;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Lengthen the array for every element, matched or not\n\t\t\t\t\tif ( seed ) {\n\t\t\t\t\t\tunmatched.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// `i` is now the count of elements visited above, and adding it to `matchedCount`\n\t\t\t// makes the latter nonnegative.\n\t\t\tmatchedCount += i;\n\n\t\t\t// Apply set filters to unmatched elements\n\t\t\t// NOTE: This can be skipped if there are no unmatched elements (i.e., `matchedCount`\n\t\t\t// equals `i`), unless we didn't visit _any_ elements in the above loop because we have\n\t\t\t// no element matchers and no seed.\n\t\t\t// Incrementing an initially-string \"0\" `i` allows `i` to remain a string only in that\n\t\t\t// case, which will result in a \"00\" `matchedCount` that differs from `i` but is also\n\t\t\t// numerically zero.\n\t\t\tif ( bySet && i !== matchedCount ) {\n\t\t\t\tj = 0;\n\t\t\t\twhile ( (matcher = setMatchers[j++]) ) {\n\t\t\t\t\tmatcher( unmatched, setMatched, context, xml );\n\t\t\t\t}\n\n\t\t\t\tif ( seed ) {\n\t\t\t\t\t// Reintegrate element matches to eliminate the need for sorting\n\t\t\t\t\tif ( matchedCount > 0 ) {\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tif ( !(unmatched[i] || setMatched[i]) ) {\n\t\t\t\t\t\t\t\tsetMatched[i] = pop.call( results );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Discard index placeholder values to get only actual matches\n\t\t\t\t\tsetMatched = condense( setMatched );\n\t\t\t\t}\n\n\t\t\t\t// Add matches to results\n\t\t\t\tpush.apply( results, setMatched );\n\n\t\t\t\t// Seedless set matches succeeding multiple successful matchers stipulate sorting\n\t\t\t\tif ( outermost && !seed && setMatched.length > 0 &&\n\t\t\t\t\t( matchedCount + setMatchers.length ) > 1 ) {\n\n\t\t\t\t\tSizzle.uniqueSort( results );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Override manipulation of globals by nested matchers\n\t\t\tif ( outermost ) {\n\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\toutermostContext = contextBackup;\n\t\t\t}\n\n\t\t\treturn unmatched;\n\t\t};\n\n\treturn bySet ?\n\t\tmarkFunction( superMatcher ) :\n\t\tsuperMatcher;\n}\n\ncompile = Sizzle.compile = function( selector, match /* Internal Use Only */ ) {\n\tvar i,\n\t\tsetMatchers = [],\n\t\telementMatchers = [],\n\t\tcached = compilerCache[ selector + \" \" ];\n\n\tif ( !cached ) {\n\t\t// Generate a function of recursive functions that can be used to check each element\n\t\tif ( !match ) {\n\t\t\tmatch = tokenize( selector );\n\t\t}\n\t\ti = match.length;\n\t\twhile ( i-- ) {\n\t\t\tcached = matcherFromTokens( match[i] );\n\t\t\tif ( cached[ expando ] ) {\n\t\t\t\tsetMatchers.push( cached );\n\t\t\t} else {\n\t\t\t\telementMatchers.push( cached );\n\t\t\t}\n\t\t}\n\n\t\t// Cache the compiled function\n\t\tcached = compilerCache( selector, matcherFromGroupMatchers( elementMatchers, setMatchers ) );\n\n\t\t// Save selector and tokenization\n\t\tcached.selector = selector;\n\t}\n\treturn cached;\n};\n\n/**\n * A low-level selection function that works with Sizzle's compiled\n *  selector functions\n * @param {String|Function} selector A selector or a pre-compiled\n *  selector function built with Sizzle.compile\n * @param {Element} context\n * @param {Array} [results]\n * @param {Array} [seed] A set of elements to match against\n */\nselect = Sizzle.select = function( selector, context, results, seed ) {\n\tvar i, tokens, token, type, find,\n\t\tcompiled = typeof selector === \"function\" && selector,\n\t\tmatch = !seed && tokenize( (selector = compiled.selector || selector) );\n\n\tresults = results || [];\n\n\t// Try to minimize operations if there is only one selector in the list and no seed\n\t// (the latter of which guarantees us context)\n\tif ( match.length === 1 ) {\n\n\t\t// Reduce context if the leading compound selector is an ID\n\t\ttokens = match[0] = match[0].slice( 0 );\n\t\tif ( tokens.length > 2 && (token = tokens[0]).type === \"ID\" &&\n\t\t\t\tcontext.nodeType === 9 && documentIsHTML && Expr.relative[ tokens[1].type ] ) {\n\n\t\t\tcontext = ( Expr.find[\"ID\"]( token.matches[0].replace(runescape, funescape), context ) || [] )[0];\n\t\t\tif ( !context ) {\n\t\t\t\treturn results;\n\n\t\t\t// Precompiled matchers will still verify ancestry, so step up a level\n\t\t\t} else if ( compiled ) {\n\t\t\t\tcontext = context.parentNode;\n\t\t\t}\n\n\t\t\tselector = selector.slice( tokens.shift().value.length );\n\t\t}\n\n\t\t// Fetch a seed set for right-to-left matching\n\t\ti = matchExpr[\"needsContext\"].test( selector ) ? 0 : tokens.length;\n\t\twhile ( i-- ) {\n\t\t\ttoken = tokens[i];\n\n\t\t\t// Abort if we hit a combinator\n\t\t\tif ( Expr.relative[ (type = token.type) ] ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tif ( (find = Expr.find[ type ]) ) {\n\t\t\t\t// Search, expanding context for leading sibling combinators\n\t\t\t\tif ( (seed = find(\n\t\t\t\t\ttoken.matches[0].replace( runescape, funescape ),\n\t\t\t\t\trsibling.test( tokens[0].type ) && testContext( context.parentNode ) || context\n\t\t\t\t)) ) {\n\n\t\t\t\t\t// If seed is empty or no tokens remain, we can return early\n\t\t\t\t\ttokens.splice( i, 1 );\n\t\t\t\t\tselector = seed.length && toSelector( tokens );\n\t\t\t\t\tif ( !selector ) {\n\t\t\t\t\t\tpush.apply( results, seed );\n\t\t\t\t\t\treturn results;\n\t\t\t\t\t}\n\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Compile and execute a filtering function if one is not provided\n\t// Provide `match` to avoid retokenization if we modified the selector above\n\t( compiled || compile( selector, match ) )(\n\t\tseed,\n\t\tcontext,\n\t\t!documentIsHTML,\n\t\tresults,\n\t\t!context || rsibling.test( selector ) && testContext( context.parentNode ) || context\n\t);\n\treturn results;\n};\n\n// One-time assignments\n\n// Sort stability\nsupport.sortStable = expando.split(\"\").sort( sortOrder ).join(\"\") === expando;\n\n// Support: Chrome 14-35+\n// Always assume duplicates if they aren't passed to the comparison function\nsupport.detectDuplicates = !!hasDuplicate;\n\n// Initialize against the default document\nsetDocument();\n\n// Support: Webkit<537.32 - Safari 6.0.3/Chrome 25 (fixed in Chrome 27)\n// Detached nodes confoundingly follow *each other*\nsupport.sortDetached = assert(function( el ) {\n\t// Should return 1, but returns 4 (following)\n\treturn el.compareDocumentPosition( document.createElement(\"fieldset\") ) & 1;\n});\n\n// Support: IE<8\n// Prevent attribute/property \"interpolation\"\n// https://msdn.microsoft.com/en-us/library/ms536429%28VS.85%29.aspx\nif ( !assert(function( el ) {\n\tel.innerHTML = \"<a href='#'></a>\";\n\treturn el.firstChild.getAttribute(\"href\") === \"#\" ;\n}) ) {\n\taddHandle( \"type|href|height|width\", function( elem, name, isXML ) {\n\t\tif ( !isXML ) {\n\t\t\treturn elem.getAttribute( name, name.toLowerCase() === \"type\" ? 1 : 2 );\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use defaultValue in place of getAttribute(\"value\")\nif ( !support.attributes || !assert(function( el ) {\n\tel.innerHTML = \"<input/>\";\n\tel.firstChild.setAttribute( \"value\", \"\" );\n\treturn el.firstChild.getAttribute( \"value\" ) === \"\";\n}) ) {\n\taddHandle( \"value\", function( elem, name, isXML ) {\n\t\tif ( !isXML && elem.nodeName.toLowerCase() === \"input\" ) {\n\t\t\treturn elem.defaultValue;\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use getAttributeNode to fetch booleans when getAttribute lies\nif ( !assert(function( el ) {\n\treturn el.getAttribute(\"disabled\") == null;\n}) ) {\n\taddHandle( booleans, function( elem, name, isXML ) {\n\t\tvar val;\n\t\tif ( !isXML ) {\n\t\t\treturn elem[ name ] === true ? name.toLowerCase() :\n\t\t\t\t\t(val = elem.getAttributeNode( name )) && val.specified ?\n\t\t\t\t\tval.value :\n\t\t\t\tnull;\n\t\t}\n\t});\n}\n\nreturn Sizzle;\n\n})( window );\n\n\n\njQuery.find = Sizzle;\njQuery.expr = Sizzle.selectors;\n\n// Deprecated\njQuery.expr[ \":\" ] = jQuery.expr.pseudos;\njQuery.uniqueSort = jQuery.unique = Sizzle.uniqueSort;\njQuery.text = Sizzle.getText;\njQuery.isXMLDoc = Sizzle.isXML;\njQuery.contains = Sizzle.contains;\njQuery.escapeSelector = Sizzle.escape;\n\n\n\n\nvar dir = function( elem, dir, until ) {\n\tvar matched = [],\n\t\ttruncate = until !== undefined;\n\n\twhile ( ( elem = elem[ dir ] ) && elem.nodeType !== 9 ) {\n\t\tif ( elem.nodeType === 1 ) {\n\t\t\tif ( truncate && jQuery( elem ).is( until ) ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tmatched.push( elem );\n\t\t}\n\t}\n\treturn matched;\n};\n\n\nvar siblings = function( n, elem ) {\n\tvar matched = [];\n\n\tfor ( ; n; n = n.nextSibling ) {\n\t\tif ( n.nodeType === 1 && n !== elem ) {\n\t\t\tmatched.push( n );\n\t\t}\n\t}\n\n\treturn matched;\n};\n\n\nvar rneedsContext = jQuery.expr.match.needsContext;\n\n\n\nfunction nodeName( elem, name ) {\n\n  return elem.nodeName && elem.nodeName.toLowerCase() === name.toLowerCase();\n\n};\nvar rsingleTag = ( /^<([a-z][^\\/\\0>:\\x20\\t\\r\\n\\f]*)[\\x20\\t\\r\\n\\f]*\\/?>(?:<\\/\\1>|)$/i );\n\n\n\n// Implement the identical functionality for filter and not\nfunction winnow( elements, qualifier, not ) {\n\tif ( isFunction( qualifier ) ) {\n\t\treturn jQuery.grep( elements, function( elem, i ) {\n\t\t\treturn !!qualifier.call( elem, i, elem ) !== not;\n\t\t} );\n\t}\n\n\t// Single element\n\tif ( qualifier.nodeType ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( elem === qualifier ) !== not;\n\t\t} );\n\t}\n\n\t// Arraylike of elements (jQuery, arguments, Array)\n\tif ( typeof qualifier !== \"string\" ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( indexOf.call( qualifier, elem ) > -1 ) !== not;\n\t\t} );\n\t}\n\n\t// Filtered directly for both simple and complex selectors\n\treturn jQuery.filter( qualifier, elements, not );\n}\n\njQuery.filter = function( expr, elems, not ) {\n\tvar elem = elems[ 0 ];\n\n\tif ( not ) {\n\t\texpr = \":not(\" + expr + \")\";\n\t}\n\n\tif ( elems.length === 1 && elem.nodeType === 1 ) {\n\t\treturn jQuery.find.matchesSelector( elem, expr ) ? [ elem ] : [];\n\t}\n\n\treturn jQuery.find.matches( expr, jQuery.grep( elems, function( elem ) {\n\t\treturn elem.nodeType === 1;\n\t} ) );\n};\n\njQuery.fn.extend( {\n\tfind: function( selector ) {\n\t\tvar i, ret,\n\t\t\tlen = this.length,\n\t\t\tself = this;\n\n\t\tif ( typeof selector !== \"string\" ) {\n\t\t\treturn this.pushStack( jQuery( selector ).filter( function() {\n\t\t\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\t\t\tif ( jQuery.contains( self[ i ], this ) ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} ) );\n\t\t}\n\n\t\tret = this.pushStack( [] );\n\n\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\tjQuery.find( selector, self[ i ], ret );\n\t\t}\n\n\t\treturn len > 1 ? jQuery.uniqueSort( ret ) : ret;\n\t},\n\tfilter: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], false ) );\n\t},\n\tnot: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], true ) );\n\t},\n\tis: function( selector ) {\n\t\treturn !!winnow(\n\t\t\tthis,\n\n\t\t\t// If this is a positional/relative selector, check membership in the returned set\n\t\t\t// so $(\"p:first\").is(\"p:last\") won't return true for a doc with two \"p\".\n\t\t\ttypeof selector === \"string\" && rneedsContext.test( selector ) ?\n\t\t\t\tjQuery( selector ) :\n\t\t\t\tselector || [],\n\t\t\tfalse\n\t\t).length;\n\t}\n} );\n\n\n// Initialize a jQuery object\n\n\n// A central reference to the root jQuery(document)\nvar rootjQuery,\n\n\t// A simple way to check for HTML strings\n\t// Prioritize #id over <tag> to avoid XSS via location.hash (#9521)\n\t// Strict HTML recognition (#11290: must start with <)\n\t// Shortcut simple #id case for speed\n\trquickExpr = /^(?:\\s*(<[\\w\\W]+>)[^>]*|#([\\w-]+))$/,\n\n\tinit = jQuery.fn.init = function( selector, context, root ) {\n\t\tvar match, elem;\n\n\t\t// HANDLE: $(\"\"), $(null), $(undefined), $(false)\n\t\tif ( !selector ) {\n\t\t\treturn this;\n\t\t}\n\n\t\t// Method init() accepts an alternate rootjQuery\n\t\t// so migrate can support jQuery.sub (gh-2101)\n\t\troot = root || rootjQuery;\n\n\t\t// Handle HTML strings\n\t\tif ( typeof selector === \"string\" ) {\n\t\t\tif ( selector[ 0 ] === \"<\" &&\n\t\t\t\tselector[ selector.length - 1 ] === \">\" &&\n\t\t\t\tselector.length >= 3 ) {\n\n\t\t\t\t// Assume that strings that start and end with <> are HTML and skip the regex check\n\t\t\t\tmatch = [ null, selector, null ];\n\n\t\t\t} else {\n\t\t\t\tmatch = rquickExpr.exec( selector );\n\t\t\t}\n\n\t\t\t// Match html or make sure no context is specified for #id\n\t\t\tif ( match && ( match[ 1 ] || !context ) ) {\n\n\t\t\t\t// HANDLE: $(html) -> $(array)\n\t\t\t\tif ( match[ 1 ] ) {\n\t\t\t\t\tcontext = context instanceof jQuery ? context[ 0 ] : context;\n\n\t\t\t\t\t// Option to run scripts is true for back-compat\n\t\t\t\t\t// Intentionally let the error be thrown if parseHTML is not present\n\t\t\t\t\tjQuery.merge( this, jQuery.parseHTML(\n\t\t\t\t\t\tmatch[ 1 ],\n\t\t\t\t\t\tcontext && context.nodeType ? context.ownerDocument || context : document,\n\t\t\t\t\t\ttrue\n\t\t\t\t\t) );\n\n\t\t\t\t\t// HANDLE: $(html, props)\n\t\t\t\t\tif ( rsingleTag.test( match[ 1 ] ) && jQuery.isPlainObject( context ) ) {\n\t\t\t\t\t\tfor ( match in context ) {\n\n\t\t\t\t\t\t\t// Properties of context are called as methods if possible\n\t\t\t\t\t\t\tif ( isFunction( this[ match ] ) ) {\n\t\t\t\t\t\t\t\tthis[ match ]( context[ match ] );\n\n\t\t\t\t\t\t\t// ...and otherwise set as attributes\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tthis.attr( match, context[ match ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\treturn this;\n\n\t\t\t\t// HANDLE: $(#id)\n\t\t\t\t} else {\n\t\t\t\t\telem = document.getElementById( match[ 2 ] );\n\n\t\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t\t// Inject the element directly into the jQuery object\n\t\t\t\t\t\tthis[ 0 ] = elem;\n\t\t\t\t\t\tthis.length = 1;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\n\t\t\t// HANDLE: $(expr, $(...))\n\t\t\t} else if ( !context || context.jquery ) {\n\t\t\t\treturn ( context || root ).find( selector );\n\n\t\t\t// HANDLE: $(expr, context)\n\t\t\t// (which is just equivalent to: $(context).find(expr)\n\t\t\t} else {\n\t\t\t\treturn this.constructor( context ).find( selector );\n\t\t\t}\n\n\t\t// HANDLE: $(DOMElement)\n\t\t} else if ( selector.nodeType ) {\n\t\t\tthis[ 0 ] = selector;\n\t\t\tthis.length = 1;\n\t\t\treturn this;\n\n\t\t// HANDLE: $(function)\n\t\t// Shortcut for document ready\n\t\t} else if ( isFunction( selector ) ) {\n\t\t\treturn root.ready !== undefined ?\n\t\t\t\troot.ready( selector ) :\n\n\t\t\t\t// Execute immediately if ready is not present\n\t\t\t\tselector( jQuery );\n\t\t}\n\n\t\treturn jQuery.makeArray( selector, this );\n\t};\n\n// Give the init function the jQuery prototype for later instantiation\ninit.prototype = jQuery.fn;\n\n// Initialize central reference\nrootjQuery = jQuery( document );\n\n\nvar rparentsprev = /^(?:parents|prev(?:Until|All))/,\n\n\t// Methods guaranteed to produce a unique set when starting from a unique set\n\tguaranteedUnique = {\n\t\tchildren: true,\n\t\tcontents: true,\n\t\tnext: true,\n\t\tprev: true\n\t};\n\njQuery.fn.extend( {\n\thas: function( target ) {\n\t\tvar targets = jQuery( target, this ),\n\t\t\tl = targets.length;\n\n\t\treturn this.filter( function() {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tif ( jQuery.contains( this, targets[ i ] ) ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\tclosest: function( selectors, context ) {\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\tl = this.length,\n\t\t\tmatched = [],\n\t\t\ttargets = typeof selectors !== \"string\" && jQuery( selectors );\n\n\t\t// Positional selectors never match, since there's no _selection_ context\n\t\tif ( !rneedsContext.test( selectors ) ) {\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tfor ( cur = this[ i ]; cur && cur !== context; cur = cur.parentNode ) {\n\n\t\t\t\t\t// Always skip document fragments\n\t\t\t\t\tif ( cur.nodeType < 11 && ( targets ?\n\t\t\t\t\t\ttargets.index( cur ) > -1 :\n\n\t\t\t\t\t\t// Don't pass non-elements to Sizzle\n\t\t\t\t\t\tcur.nodeType === 1 &&\n\t\t\t\t\t\t\tjQuery.find.matchesSelector( cur, selectors ) ) ) {\n\n\t\t\t\t\t\tmatched.push( cur );\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched.length > 1 ? jQuery.uniqueSort( matched ) : matched );\n\t},\n\n\t// Determine the position of an element within the set\n\tindex: function( elem ) {\n\n\t\t// No argument, return index in parent\n\t\tif ( !elem ) {\n\t\t\treturn ( this[ 0 ] && this[ 0 ].parentNode ) ? this.first().prevAll().length : -1;\n\t\t}\n\n\t\t// Index in selector\n\t\tif ( typeof elem === \"string\" ) {\n\t\t\treturn indexOf.call( jQuery( elem ), this[ 0 ] );\n\t\t}\n\n\t\t// Locate the position of the desired element\n\t\treturn indexOf.call( this,\n\n\t\t\t// If it receives a jQuery object, the first element is used\n\t\t\telem.jquery ? elem[ 0 ] : elem\n\t\t);\n\t},\n\n\tadd: function( selector, context ) {\n\t\treturn this.pushStack(\n\t\t\tjQuery.uniqueSort(\n\t\t\t\tjQuery.merge( this.get(), jQuery( selector, context ) )\n\t\t\t)\n\t\t);\n\t},\n\n\taddBack: function( selector ) {\n\t\treturn this.add( selector == null ?\n\t\t\tthis.prevObject : this.prevObject.filter( selector )\n\t\t);\n\t}\n} );\n\nfunction sibling( cur, dir ) {\n\twhile ( ( cur = cur[ dir ] ) && cur.nodeType !== 1 ) {}\n\treturn cur;\n}\n\njQuery.each( {\n\tparent: function( elem ) {\n\t\tvar parent = elem.parentNode;\n\t\treturn parent && parent.nodeType !== 11 ? parent : null;\n\t},\n\tparents: function( elem ) {\n\t\treturn dir( elem, \"parentNode\" );\n\t},\n\tparentsUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"parentNode\", until );\n\t},\n\tnext: function( elem ) {\n\t\treturn sibling( elem, \"nextSibling\" );\n\t},\n\tprev: function( elem ) {\n\t\treturn sibling( elem, \"previousSibling\" );\n\t},\n\tnextAll: function( elem ) {\n\t\treturn dir( elem, \"nextSibling\" );\n\t},\n\tprevAll: function( elem ) {\n\t\treturn dir( elem, \"previousSibling\" );\n\t},\n\tnextUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"nextSibling\", until );\n\t},\n\tprevUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"previousSibling\", until );\n\t},\n\tsiblings: function( elem ) {\n\t\treturn siblings( ( elem.parentNode || {} ).firstChild, elem );\n\t},\n\tchildren: function( elem ) {\n\t\treturn siblings( elem.firstChild );\n\t},\n\tcontents: function( elem ) {\n\t\tif ( typeof elem.contentDocument !== \"undefined\" ) {\n\t\t\treturn elem.contentDocument;\n\t\t}\n\n\t\t// Support: IE 9 - 11 only, iOS 7 only, Android Browser <=4.3 only\n\t\t// Treat the template element as a regular one in browsers that\n\t\t// don't support it.\n\t\tif ( nodeName( elem, \"template\" ) ) {\n\t\t\telem = elem.content || elem;\n\t\t}\n\n\t\treturn jQuery.merge( [], elem.childNodes );\n\t}\n}, function( name, fn ) {\n\tjQuery.fn[ name ] = function( until, selector ) {\n\t\tvar matched = jQuery.map( this, fn, until );\n\n\t\tif ( name.slice( -5 ) !== \"Until\" ) {\n\t\t\tselector = until;\n\t\t}\n\n\t\tif ( selector && typeof selector === \"string\" ) {\n\t\t\tmatched = jQuery.filter( selector, matched );\n\t\t}\n\n\t\tif ( this.length > 1 ) {\n\n\t\t\t// Remove duplicates\n\t\t\tif ( !guaranteedUnique[ name ] ) {\n\t\t\t\tjQuery.uniqueSort( matched );\n\t\t\t}\n\n\t\t\t// Reverse order for parents* and prev-derivatives\n\t\t\tif ( rparentsprev.test( name ) ) {\n\t\t\t\tmatched.reverse();\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched );\n\t};\n} );\nvar rnothtmlwhite = ( /[^\\x20\\t\\r\\n\\f]+/g );\n\n\n\n// Convert String-formatted options into Object-formatted ones\nfunction createOptions( options ) {\n\tvar object = {};\n\tjQuery.each( options.match( rnothtmlwhite ) || [], function( _, flag ) {\n\t\tobject[ flag ] = true;\n\t} );\n\treturn object;\n}\n\n/*\n * Create a callback list using the following parameters:\n *\n *\toptions: an optional list of space-separated options that will change how\n *\t\t\tthe callback list behaves or a more traditional option object\n *\n * By default a callback list will act like an event callback list and can be\n * \"fired\" multiple times.\n *\n * Possible options:\n *\n *\tonce:\t\t\twill ensure the callback list can only be fired once (like a Deferred)\n *\n *\tmemory:\t\t\twill keep track of previous values and will call any callback added\n *\t\t\t\t\tafter the list has been fired right away with the latest \"memorized\"\n *\t\t\t\t\tvalues (like a Deferred)\n *\n *\tunique:\t\t\twill ensure a callback can only be added once (no duplicate in the list)\n *\n *\tstopOnFalse:\tinterrupt callings when a callback returns false\n *\n */\njQuery.Callbacks = function( options ) {\n\n\t// Convert options from String-formatted to Object-formatted if needed\n\t// (we check in cache first)\n\toptions = typeof options === \"string\" ?\n\t\tcreateOptions( options ) :\n\t\tjQuery.extend( {}, options );\n\n\tvar // Flag to know if list is currently firing\n\t\tfiring,\n\n\t\t// Last fire value for non-forgettable lists\n\t\tmemory,\n\n\t\t// Flag to know if list was already fired\n\t\tfired,\n\n\t\t// Flag to prevent firing\n\t\tlocked,\n\n\t\t// Actual callback list\n\t\tlist = [],\n\n\t\t// Queue of execution data for repeatable lists\n\t\tqueue = [],\n\n\t\t// Index of currently firing callback (modified by add/remove as needed)\n\t\tfiringIndex = -1,\n\n\t\t// Fire callbacks\n\t\tfire = function() {\n\n\t\t\t// Enforce single-firing\n\t\t\tlocked = locked || options.once;\n\n\t\t\t// Execute callbacks for all pending executions,\n\t\t\t// respecting firingIndex overrides and runtime changes\n\t\t\tfired = firing = true;\n\t\t\tfor ( ; queue.length; firingIndex = -1 ) {\n\t\t\t\tmemory = queue.shift();\n\t\t\t\twhile ( ++firingIndex < list.length ) {\n\n\t\t\t\t\t// Run callback and check for early termination\n\t\t\t\t\tif ( list[ firingIndex ].apply( memory[ 0 ], memory[ 1 ] ) === false &&\n\t\t\t\t\t\toptions.stopOnFalse ) {\n\n\t\t\t\t\t\t// Jump to end and forget the data so .add doesn't re-fire\n\t\t\t\t\t\tfiringIndex = list.length;\n\t\t\t\t\t\tmemory = false;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Forget the data if we're done with it\n\t\t\tif ( !options.memory ) {\n\t\t\t\tmemory = false;\n\t\t\t}\n\n\t\t\tfiring = false;\n\n\t\t\t// Clean up if we're done firing for good\n\t\t\tif ( locked ) {\n\n\t\t\t\t// Keep an empty list if we have data for future add calls\n\t\t\t\tif ( memory ) {\n\t\t\t\t\tlist = [];\n\n\t\t\t\t// Otherwise, this object is spent\n\t\t\t\t} else {\n\t\t\t\t\tlist = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t},\n\n\t\t// Actual Callbacks object\n\t\tself = {\n\n\t\t\t// Add a callback or a collection of callbacks to the list\n\t\t\tadd: function() {\n\t\t\t\tif ( list ) {\n\n\t\t\t\t\t// If we have memory from a past run, we should fire after adding\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfiringIndex = list.length - 1;\n\t\t\t\t\t\tqueue.push( memory );\n\t\t\t\t\t}\n\n\t\t\t\t\t( function add( args ) {\n\t\t\t\t\t\tjQuery.each( args, function( _, arg ) {\n\t\t\t\t\t\t\tif ( isFunction( arg ) ) {\n\t\t\t\t\t\t\t\tif ( !options.unique || !self.has( arg ) ) {\n\t\t\t\t\t\t\t\t\tlist.push( arg );\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} else if ( arg && arg.length && toType( arg ) !== \"string\" ) {\n\n\t\t\t\t\t\t\t\t// Inspect recursively\n\t\t\t\t\t\t\t\tadd( arg );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} );\n\t\t\t\t\t} )( arguments );\n\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Remove a callback from the list\n\t\t\tremove: function() {\n\t\t\t\tjQuery.each( arguments, function( _, arg ) {\n\t\t\t\t\tvar index;\n\t\t\t\t\twhile ( ( index = jQuery.inArray( arg, list, index ) ) > -1 ) {\n\t\t\t\t\t\tlist.splice( index, 1 );\n\n\t\t\t\t\t\t// Handle firing indexes\n\t\t\t\t\t\tif ( index <= firingIndex ) {\n\t\t\t\t\t\t\tfiringIndex--;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Check if a given callback is in the list.\n\t\t\t// If no argument is given, return whether or not list has callbacks attached.\n\t\t\thas: function( fn ) {\n\t\t\t\treturn fn ?\n\t\t\t\t\tjQuery.inArray( fn, list ) > -1 :\n\t\t\t\t\tlist.length > 0;\n\t\t\t},\n\n\t\t\t// Remove all callbacks from the list\n\t\t\tempty: function() {\n\t\t\t\tif ( list ) {\n\t\t\t\t\tlist = [];\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Disable .fire and .add\n\t\t\t// Abort any current/pending executions\n\t\t\t// Clear all callbacks and values\n\t\t\tdisable: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tlist = memory = \"\";\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tdisabled: function() {\n\t\t\t\treturn !list;\n\t\t\t},\n\n\t\t\t// Disable .fire\n\t\t\t// Also disable .add unless we have memory (since it would have no effect)\n\t\t\t// Abort any pending executions\n\t\t\tlock: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tif ( !memory && !firing ) {\n\t\t\t\t\tlist = memory = \"\";\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tlocked: function() {\n\t\t\t\treturn !!locked;\n\t\t\t},\n\n\t\t\t// Call all callbacks with the given context and arguments\n\t\t\tfireWith: function( context, args ) {\n\t\t\t\tif ( !locked ) {\n\t\t\t\t\targs = args || [];\n\t\t\t\t\targs = [ context, args.slice ? args.slice() : args ];\n\t\t\t\t\tqueue.push( args );\n\t\t\t\t\tif ( !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Call all the callbacks with the given arguments\n\t\t\tfire: function() {\n\t\t\t\tself.fireWith( this, arguments );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// To know if the callbacks have already been called at least once\n\t\t\tfired: function() {\n\t\t\t\treturn !!fired;\n\t\t\t}\n\t\t};\n\n\treturn self;\n};\n\n\nfunction Identity( v ) {\n\treturn v;\n}\nfunction Thrower( ex ) {\n\tthrow ex;\n}\n\nfunction adoptValue( value, resolve, reject, noValue ) {\n\tvar method;\n\n\ttry {\n\n\t\t// Check for promise aspect first to privilege synchronous behavior\n\t\tif ( value && isFunction( ( method = value.promise ) ) ) {\n\t\t\tmethod.call( value ).done( resolve ).fail( reject );\n\n\t\t// Other thenables\n\t\t} else if ( value && isFunction( ( method = value.then ) ) ) {\n\t\t\tmethod.call( value, resolve, reject );\n\n\t\t// Other non-thenables\n\t\t} else {\n\n\t\t\t// Control `resolve` arguments by letting Array#slice cast boolean `noValue` to integer:\n\t\t\t// * false: [ value ].slice( 0 ) => resolve( value )\n\t\t\t// * true: [ value ].slice( 1 ) => resolve()\n\t\t\tresolve.apply( undefined, [ value ].slice( noValue ) );\n\t\t}\n\n\t// For Promises/A+, convert exceptions into rejections\n\t// Since jQuery.when doesn't unwrap thenables, we can skip the extra checks appearing in\n\t// Deferred#then to conditionally suppress rejection.\n\t} catch ( value ) {\n\n\t\t// Support: Android 4.0 only\n\t\t// Strict mode functions invoked without .call/.apply get global-object context\n\t\treject.apply( undefined, [ value ] );\n\t}\n}\n\njQuery.extend( {\n\n\tDeferred: function( func ) {\n\t\tvar tuples = [\n\n\t\t\t\t// action, add listener, callbacks,\n\t\t\t\t// ... .then handlers, argument index, [final state]\n\t\t\t\t[ \"notify\", \"progress\", jQuery.Callbacks( \"memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"memory\" ), 2 ],\n\t\t\t\t[ \"resolve\", \"done\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 0, \"resolved\" ],\n\t\t\t\t[ \"reject\", \"fail\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 1, \"rejected\" ]\n\t\t\t],\n\t\t\tstate = \"pending\",\n\t\t\tpromise = {\n\t\t\t\tstate: function() {\n\t\t\t\t\treturn state;\n\t\t\t\t},\n\t\t\t\talways: function() {\n\t\t\t\t\tdeferred.done( arguments ).fail( arguments );\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\t\t\t\t\"catch\": function( fn ) {\n\t\t\t\t\treturn promise.then( null, fn );\n\t\t\t\t},\n\n\t\t\t\t// Keep pipe for back-compat\n\t\t\t\tpipe: function( /* fnDone, fnFail, fnProgress */ ) {\n\t\t\t\t\tvar fns = arguments;\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\t\t\t\t\t\tjQuery.each( tuples, function( i, tuple ) {\n\n\t\t\t\t\t\t\t// Map tuples (progress, done, fail) to arguments (done, fail, progress)\n\t\t\t\t\t\t\tvar fn = isFunction( fns[ tuple[ 4 ] ] ) && fns[ tuple[ 4 ] ];\n\n\t\t\t\t\t\t\t// deferred.progress(function() { bind to newDefer or newDefer.notify })\n\t\t\t\t\t\t\t// deferred.done(function() { bind to newDefer or newDefer.resolve })\n\t\t\t\t\t\t\t// deferred.fail(function() { bind to newDefer or newDefer.reject })\n\t\t\t\t\t\t\tdeferred[ tuple[ 1 ] ]( function() {\n\t\t\t\t\t\t\t\tvar returned = fn && fn.apply( this, arguments );\n\t\t\t\t\t\t\t\tif ( returned && isFunction( returned.promise ) ) {\n\t\t\t\t\t\t\t\t\treturned.promise()\n\t\t\t\t\t\t\t\t\t\t.progress( newDefer.notify )\n\t\t\t\t\t\t\t\t\t\t.done( newDefer.resolve )\n\t\t\t\t\t\t\t\t\t\t.fail( newDefer.reject );\n\t\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\t\tnewDefer[ tuple[ 0 ] + \"With\" ](\n\t\t\t\t\t\t\t\t\t\tthis,\n\t\t\t\t\t\t\t\t\t\tfn ? [ returned ] : arguments\n\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t} );\n\t\t\t\t\t\tfns = null;\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\t\t\t\tthen: function( onFulfilled, onRejected, onProgress ) {\n\t\t\t\t\tvar maxDepth = 0;\n\t\t\t\t\tfunction resolve( depth, deferred, handler, special ) {\n\t\t\t\t\t\treturn function() {\n\t\t\t\t\t\t\tvar that = this,\n\t\t\t\t\t\t\t\targs = arguments,\n\t\t\t\t\t\t\t\tmightThrow = function() {\n\t\t\t\t\t\t\t\t\tvar returned, then;\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.3\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-59\n\t\t\t\t\t\t\t\t\t// Ignore double-resolution attempts\n\t\t\t\t\t\t\t\t\tif ( depth < maxDepth ) {\n\t\t\t\t\t\t\t\t\t\treturn;\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\treturned = handler.apply( that, args );\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.1\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-48\n\t\t\t\t\t\t\t\t\tif ( returned === deferred.promise() ) {\n\t\t\t\t\t\t\t\t\t\tthrow new TypeError( \"Thenable self-resolution\" );\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ sections 2.3.3.1, 3.5\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-54\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-75\n\t\t\t\t\t\t\t\t\t// Retrieve `then` only once\n\t\t\t\t\t\t\t\t\tthen = returned &&\n\n\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.4\n\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-64\n\t\t\t\t\t\t\t\t\t\t// Only check objects and functions for thenability\n\t\t\t\t\t\t\t\t\t\t( typeof returned === \"object\" ||\n\t\t\t\t\t\t\t\t\t\t\ttypeof returned === \"function\" ) &&\n\t\t\t\t\t\t\t\t\t\treturned.then;\n\n\t\t\t\t\t\t\t\t\t// Handle a returned thenable\n\t\t\t\t\t\t\t\t\tif ( isFunction( then ) ) {\n\n\t\t\t\t\t\t\t\t\t\t// Special processors (notify) just wait for resolution\n\t\t\t\t\t\t\t\t\t\tif ( special ) {\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special )\n\t\t\t\t\t\t\t\t\t\t\t);\n\n\t\t\t\t\t\t\t\t\t\t// Normal processors (resolve) also hook into progress\n\t\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t\t// ...and disregard older resolution values\n\t\t\t\t\t\t\t\t\t\t\tmaxDepth++;\n\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity,\n\t\t\t\t\t\t\t\t\t\t\t\t\tdeferred.notifyWith )\n\t\t\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Handle all other returned values\n\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\tif ( handler !== Identity ) {\n\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\targs = [ returned ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t// Process the value(s)\n\t\t\t\t\t\t\t\t\t\t// Default process is resolve\n\t\t\t\t\t\t\t\t\t\t( special || deferred.resolveWith )( that, args );\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t},\n\n\t\t\t\t\t\t\t\t// Only normal processors (resolve) catch and reject exceptions\n\t\t\t\t\t\t\t\tprocess = special ?\n\t\t\t\t\t\t\t\t\tmightThrow :\n\t\t\t\t\t\t\t\t\tfunction() {\n\t\t\t\t\t\t\t\t\t\ttry {\n\t\t\t\t\t\t\t\t\t\t\tmightThrow();\n\t\t\t\t\t\t\t\t\t\t} catch ( e ) {\n\n\t\t\t\t\t\t\t\t\t\t\tif ( jQuery.Deferred.exceptionHook ) {\n\t\t\t\t\t\t\t\t\t\t\t\tjQuery.Deferred.exceptionHook( e,\n\t\t\t\t\t\t\t\t\t\t\t\t\tprocess.stackTrace );\n\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.4.1\n\t\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-61\n\t\t\t\t\t\t\t\t\t\t\t// Ignore post-resolution exceptions\n\t\t\t\t\t\t\t\t\t\t\tif ( depth + 1 >= maxDepth ) {\n\n\t\t\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\t\t\tif ( handler !== Thrower ) {\n\t\t\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\t\t\targs = [ e ];\n\t\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t\tdeferred.rejectWith( that, args );\n\t\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t};\n\n\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.1\n\t\t\t\t\t\t\t// https://promisesaplus.com/#point-57\n\t\t\t\t\t\t\t// Re-resolve promises immediately to dodge false rejection from\n\t\t\t\t\t\t\t// subsequent errors\n\t\t\t\t\t\t\tif ( depth ) {\n\t\t\t\t\t\t\t\tprocess();\n\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t// Call an optional hook to record the stack, in case of exception\n\t\t\t\t\t\t\t\t// since it's otherwise lost when execution goes async\n\t\t\t\t\t\t\t\tif ( jQuery.Deferred.getStackHook ) {\n\t\t\t\t\t\t\t\t\tprocess.stackTrace = jQuery.Deferred.getStackHook();\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\twindow.setTimeout( process );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t};\n\t\t\t\t\t}\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\n\t\t\t\t\t\t// progress_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 0 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onProgress ) ?\n\t\t\t\t\t\t\t\t\tonProgress :\n\t\t\t\t\t\t\t\t\tIdentity,\n\t\t\t\t\t\t\t\tnewDefer.notifyWith\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// fulfilled_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 1 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onFulfilled ) ?\n\t\t\t\t\t\t\t\t\tonFulfilled :\n\t\t\t\t\t\t\t\t\tIdentity\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// rejected_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 2 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onRejected ) ?\n\t\t\t\t\t\t\t\t\tonRejected :\n\t\t\t\t\t\t\t\t\tThrower\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\n\t\t\t\t// Get a promise for this deferred\n\t\t\t\t// If obj is provided, the promise aspect is added to the object\n\t\t\t\tpromise: function( obj ) {\n\t\t\t\t\treturn obj != null ? jQuery.extend( obj, promise ) : promise;\n\t\t\t\t}\n\t\t\t},\n\t\t\tdeferred = {};\n\n\t\t// Add list-specific methods\n\t\tjQuery.each( tuples, function( i, tuple ) {\n\t\t\tvar list = tuple[ 2 ],\n\t\t\t\tstateString = tuple[ 5 ];\n\n\t\t\t// promise.progress = list.add\n\t\t\t// promise.done = list.add\n\t\t\t// promise.fail = list.add\n\t\t\tpromise[ tuple[ 1 ] ] = list.add;\n\n\t\t\t// Handle state\n\t\t\tif ( stateString ) {\n\t\t\t\tlist.add(\n\t\t\t\t\tfunction() {\n\n\t\t\t\t\t\t// state = \"resolved\" (i.e., fulfilled)\n\t\t\t\t\t\t// state = \"rejected\"\n\t\t\t\t\t\tstate = stateString;\n\t\t\t\t\t},\n\n\t\t\t\t\t// rejected_callbacks.disable\n\t\t\t\t\t// fulfilled_callbacks.disable\n\t\t\t\t\ttuples[ 3 - i ][ 2 ].disable,\n\n\t\t\t\t\t// rejected_handlers.disable\n\t\t\t\t\t// fulfilled_handlers.disable\n\t\t\t\t\ttuples[ 3 - i ][ 3 ].disable,\n\n\t\t\t\t\t// progress_callbacks.lock\n\t\t\t\t\ttuples[ 0 ][ 2 ].lock,\n\n\t\t\t\t\t// progress_handlers.lock\n\t\t\t\t\ttuples[ 0 ][ 3 ].lock\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// progress_handlers.fire\n\t\t\t// fulfilled_handlers.fire\n\t\t\t// rejected_handlers.fire\n\t\t\tlist.add( tuple[ 3 ].fire );\n\n\t\t\t// deferred.notify = function() { deferred.notifyWith(...) }\n\t\t\t// deferred.resolve = function() { deferred.resolveWith(...) }\n\t\t\t// deferred.reject = function() { deferred.rejectWith(...) }\n\t\t\tdeferred[ tuple[ 0 ] ] = function() {\n\t\t\t\tdeferred[ tuple[ 0 ] + \"With\" ]( this === deferred ? undefined : this, arguments );\n\t\t\t\treturn this;\n\t\t\t};\n\n\t\t\t// deferred.notifyWith = list.fireWith\n\t\t\t// deferred.resolveWith = list.fireWith\n\t\t\t// deferred.rejectWith = list.fireWith\n\t\t\tdeferred[ tuple[ 0 ] + \"With\" ] = list.fireWith;\n\t\t} );\n\n\t\t// Make the deferred a promise\n\t\tpromise.promise( deferred );\n\n\t\t// Call given func if any\n\t\tif ( func ) {\n\t\t\tfunc.call( deferred, deferred );\n\t\t}\n\n\t\t// All done!\n\t\treturn deferred;\n\t},\n\n\t// Deferred helper\n\twhen: function( singleValue ) {\n\t\tvar\n\n\t\t\t// count of uncompleted subordinates\n\t\t\tremaining = arguments.length,\n\n\t\t\t// count of unprocessed arguments\n\t\t\ti = remaining,\n\n\t\t\t// subordinate fulfillment data\n\t\t\tresolveContexts = Array( i ),\n\t\t\tresolveValues = slice.call( arguments ),\n\n\t\t\t// the master Deferred\n\t\t\tmaster = jQuery.Deferred(),\n\n\t\t\t// subordinate callback factory\n\t\t\tupdateFunc = function( i ) {\n\t\t\t\treturn function( value ) {\n\t\t\t\t\tresolveContexts[ i ] = this;\n\t\t\t\t\tresolveValues[ i ] = arguments.length > 1 ? slice.call( arguments ) : value;\n\t\t\t\t\tif ( !( --remaining ) ) {\n\t\t\t\t\t\tmaster.resolveWith( resolveContexts, resolveValues );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t\t};\n\n\t\t// Single- and empty arguments are adopted like Promise.resolve\n\t\tif ( remaining <= 1 ) {\n\t\t\tadoptValue( singleValue, master.done( updateFunc( i ) ).resolve, master.reject,\n\t\t\t\t!remaining );\n\n\t\t\t// Use .then() to unwrap secondary thenables (cf. gh-3000)\n\t\t\tif ( master.state() === \"pending\" ||\n\t\t\t\tisFunction( resolveValues[ i ] && resolveValues[ i ].then ) ) {\n\n\t\t\t\treturn master.then();\n\t\t\t}\n\t\t}\n\n\t\t// Multiple arguments are aggregated like Promise.all array elements\n\t\twhile ( i-- ) {\n\t\t\tadoptValue( resolveValues[ i ], updateFunc( i ), master.reject );\n\t\t}\n\n\t\treturn master.promise();\n\t}\n} );\n\n\n// These usually indicate a programmer mistake during development,\n// warn about them ASAP rather than swallowing them by default.\nvar rerrorNames = /^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/;\n\njQuery.Deferred.exceptionHook = function( error, stack ) {\n\n\t// Support: IE 8 - 9 only\n\t// Console exists when dev tools are open, which can happen at any time\n\tif ( window.console && window.console.warn && error && rerrorNames.test( error.name ) ) {\n\t\twindow.console.warn( \"jQuery.Deferred exception: \" + error.message, error.stack, stack );\n\t}\n};\n\n\n\n\njQuery.readyException = function( error ) {\n\twindow.setTimeout( function() {\n\t\tthrow error;\n\t} );\n};\n\n\n\n\n// The deferred used on DOM ready\nvar readyList = jQuery.Deferred();\n\njQuery.fn.ready = function( fn ) {\n\n\treadyList\n\t\t.then( fn )\n\n\t\t// Wrap jQuery.readyException in a function so that the lookup\n\t\t// happens at the time of error handling instead of callback\n\t\t// registration.\n\t\t.catch( function( error ) {\n\t\t\tjQuery.readyException( error );\n\t\t} );\n\n\treturn this;\n};\n\njQuery.extend( {\n\n\t// Is the DOM ready to be used? Set to true once it occurs.\n\tisReady: false,\n\n\t// A counter to track how many items to wait for before\n\t// the ready event fires. See #6781\n\treadyWait: 1,\n\n\t// Handle when the DOM is ready\n\tready: function( wait ) {\n\n\t\t// Abort if there are pending holds or we're already ready\n\t\tif ( wait === true ? --jQuery.readyWait : jQuery.isReady ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Remember that the DOM is ready\n\t\tjQuery.isReady = true;\n\n\t\t// If a normal DOM Ready event fired, decrement, and wait if need be\n\t\tif ( wait !== true && --jQuery.readyWait > 0 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// If there are functions bound, to execute\n\t\treadyList.resolveWith( document, [ jQuery ] );\n\t}\n} );\n\njQuery.ready.then = readyList.then;\n\n// The ready event handler and self cleanup method\nfunction completed() {\n\tdocument.removeEventListener( \"DOMContentLoaded\", completed );\n\twindow.removeEventListener( \"load\", completed );\n\tjQuery.ready();\n}\n\n// Catch cases where $(document).ready() is called\n// after the browser event has already occurred.\n// Support: IE <=9 - 10 only\n// Older IE sometimes signals \"interactive\" too soon\nif ( document.readyState === \"complete\" ||\n\t( document.readyState !== \"loading\" && !document.documentElement.doScroll ) ) {\n\n\t// Handle it asynchronously to allow scripts the opportunity to delay ready\n\twindow.setTimeout( jQuery.ready );\n\n} else {\n\n\t// Use the handy event callback\n\tdocument.addEventListener( \"DOMContentLoaded\", completed );\n\n\t// A fallback to window.onload, that will always work\n\twindow.addEventListener( \"load\", completed );\n}\n\n\n\n\n// Multifunctional method to get and set values of a collection\n// The value/s can optionally be executed if it's a function\nvar access = function( elems, fn, key, value, chainable, emptyGet, raw ) {\n\tvar i = 0,\n\t\tlen = elems.length,\n\t\tbulk = key == null;\n\n\t// Sets many values\n\tif ( toType( key ) === \"object\" ) {\n\t\tchainable = true;\n\t\tfor ( i in key ) {\n\t\t\taccess( elems, fn, i, key[ i ], true, emptyGet, raw );\n\t\t}\n\n\t// Sets one value\n\t} else if ( value !== undefined ) {\n\t\tchainable = true;\n\n\t\tif ( !isFunction( value ) ) {\n\t\t\traw = true;\n\t\t}\n\n\t\tif ( bulk ) {\n\n\t\t\t// Bulk operations run against the entire set\n\t\t\tif ( raw ) {\n\t\t\t\tfn.call( elems, value );\n\t\t\t\tfn = null;\n\n\t\t\t// ...except when executing function values\n\t\t\t} else {\n\t\t\t\tbulk = fn;\n\t\t\t\tfn = function( elem, key, value ) {\n\t\t\t\t\treturn bulk.call( jQuery( elem ), value );\n\t\t\t\t};\n\t\t\t}\n\t\t}\n\n\t\tif ( fn ) {\n\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\tfn(\n\t\t\t\t\telems[ i ], key, raw ?\n\t\t\t\t\tvalue :\n\t\t\t\t\tvalue.call( elems[ i ], i, fn( elems[ i ], key ) )\n\t\t\t\t);\n\t\t\t}\n\t\t}\n\t}\n\n\tif ( chainable ) {\n\t\treturn elems;\n\t}\n\n\t// Gets\n\tif ( bulk ) {\n\t\treturn fn.call( elems );\n\t}\n\n\treturn len ? fn( elems[ 0 ], key ) : emptyGet;\n};\n\n\n// Matches dashed string for camelizing\nvar rmsPrefix = /^-ms-/,\n\trdashAlpha = /-([a-z])/g;\n\n// Used by camelCase as callback to replace()\nfunction fcamelCase( all, letter ) {\n\treturn letter.toUpperCase();\n}\n\n// Convert dashed to camelCase; used by the css and data modules\n// Support: IE <=9 - 11, Edge 12 - 15\n// Microsoft forgot to hump their vendor prefix (#9572)\nfunction camelCase( string ) {\n\treturn string.replace( rmsPrefix, \"ms-\" ).replace( rdashAlpha, fcamelCase );\n}\nvar acceptData = function( owner ) {\n\n\t// Accepts only:\n\t//  - Node\n\t//    - Node.ELEMENT_NODE\n\t//    - Node.DOCUMENT_NODE\n\t//  - Object\n\t//    - Any\n\treturn owner.nodeType === 1 || owner.nodeType === 9 || !( +owner.nodeType );\n};\n\n\n\n\nfunction Data() {\n\tthis.expando = jQuery.expando + Data.uid++;\n}\n\nData.uid = 1;\n\nData.prototype = {\n\n\tcache: function( owner ) {\n\n\t\t// Check if the owner object already has a cache\n\t\tvar value = owner[ this.expando ];\n\n\t\t// If not, create one\n\t\tif ( !value ) {\n\t\t\tvalue = {};\n\n\t\t\t// We can accept data for non-element nodes in modern browsers,\n\t\t\t// but we should not, see #8335.\n\t\t\t// Always return an empty object.\n\t\t\tif ( acceptData( owner ) ) {\n\n\t\t\t\t// If it is a node unlikely to be stringify-ed or looped over\n\t\t\t\t// use plain assignment\n\t\t\t\tif ( owner.nodeType ) {\n\t\t\t\t\towner[ this.expando ] = value;\n\n\t\t\t\t// Otherwise secure it in a non-enumerable property\n\t\t\t\t// configurable must be true to allow the property to be\n\t\t\t\t// deleted when data is removed\n\t\t\t\t} else {\n\t\t\t\t\tObject.defineProperty( owner, this.expando, {\n\t\t\t\t\t\tvalue: value,\n\t\t\t\t\t\tconfigurable: true\n\t\t\t\t\t} );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn value;\n\t},\n\tset: function( owner, data, value ) {\n\t\tvar prop,\n\t\t\tcache = this.cache( owner );\n\n\t\t// Handle: [ owner, key, value ] args\n\t\t// Always use camelCase key (gh-2257)\n\t\tif ( typeof data === \"string\" ) {\n\t\t\tcache[ camelCase( data ) ] = value;\n\n\t\t// Handle: [ owner, { properties } ] args\n\t\t} else {\n\n\t\t\t// Copy the properties one-by-one to the cache object\n\t\t\tfor ( prop in data ) {\n\t\t\t\tcache[ camelCase( prop ) ] = data[ prop ];\n\t\t\t}\n\t\t}\n\t\treturn cache;\n\t},\n\tget: function( owner, key ) {\n\t\treturn key === undefined ?\n\t\t\tthis.cache( owner ) :\n\n\t\t\t// Always use camelCase key (gh-2257)\n\t\t\towner[ this.expando ] && owner[ this.expando ][ camelCase( key ) ];\n\t},\n\taccess: function( owner, key, value ) {\n\n\t\t// In cases where either:\n\t\t//\n\t\t//   1. No key was specified\n\t\t//   2. A string key was specified, but no value provided\n\t\t//\n\t\t// Take the \"read\" path and allow the get method to determine\n\t\t// which value to return, respectively either:\n\t\t//\n\t\t//   1. The entire cache object\n\t\t//   2. The data stored at the key\n\t\t//\n\t\tif ( key === undefined ||\n\t\t\t\t( ( key && typeof key === \"string\" ) && value === undefined ) ) {\n\n\t\t\treturn this.get( owner, key );\n\t\t}\n\n\t\t// When the key is not a string, or both a key and value\n\t\t// are specified, set or extend (existing objects) with either:\n\t\t//\n\t\t//   1. An object of properties\n\t\t//   2. A key and value\n\t\t//\n\t\tthis.set( owner, key, value );\n\n\t\t// Since the \"set\" path can have two possible entry points\n\t\t// return the expected data based on which path was taken[*]\n\t\treturn value !== undefined ? value : key;\n\t},\n\tremove: function( owner, key ) {\n\t\tvar i,\n\t\t\tcache = owner[ this.expando ];\n\n\t\tif ( cache === undefined ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( key !== undefined ) {\n\n\t\t\t// Support array or space separated string of keys\n\t\t\tif ( Array.isArray( key ) ) {\n\n\t\t\t\t// If key is an array of keys...\n\t\t\t\t// We always set camelCase keys, so remove that.\n\t\t\t\tkey = key.map( camelCase );\n\t\t\t} else {\n\t\t\t\tkey = camelCase( key );\n\n\t\t\t\t// If a key with the spaces exists, use it.\n\t\t\t\t// Otherwise, create an array by matching non-whitespace\n\t\t\t\tkey = key in cache ?\n\t\t\t\t\t[ key ] :\n\t\t\t\t\t( key.match( rnothtmlwhite ) || [] );\n\t\t\t}\n\n\t\t\ti = key.length;\n\n\t\t\twhile ( i-- ) {\n\t\t\t\tdelete cache[ key[ i ] ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove the expando if there's no more data\n\t\tif ( key === undefined || jQuery.isEmptyObject( cache ) ) {\n\n\t\t\t// Support: Chrome <=35 - 45\n\t\t\t// Webkit & Blink performance suffers when deleting properties\n\t\t\t// from DOM nodes, so set to undefined instead\n\t\t\t// https://bugs.chromium.org/p/chromium/issues/detail?id=378607 (bug restricted)\n\t\t\tif ( owner.nodeType ) {\n\t\t\t\towner[ this.expando ] = undefined;\n\t\t\t} else {\n\t\t\t\tdelete owner[ this.expando ];\n\t\t\t}\n\t\t}\n\t},\n\thasData: function( owner ) {\n\t\tvar cache = owner[ this.expando ];\n\t\treturn cache !== undefined && !jQuery.isEmptyObject( cache );\n\t}\n};\nvar dataPriv = new Data();\n\nvar dataUser = new Data();\n\n\n\n//\tImplementation Summary\n//\n//\t1. Enforce API surface and semantic compatibility with 1.9.x branch\n//\t2. Improve the module's maintainability by reducing the storage\n//\t\tpaths to a single mechanism.\n//\t3. Use the same single mechanism to support \"private\" and \"user\" data.\n//\t4. _Never_ expose \"private\" data to user code (TODO: Drop _data, _removeData)\n//\t5. Avoid exposing implementation details on user objects (eg. expando properties)\n//\t6. Provide a clear path for implementation upgrade to WeakMap in 2014\n\nvar rbrace = /^(?:\\{[\\w\\W]*\\}|\\[[\\w\\W]*\\])$/,\n\trmultiDash = /[A-Z]/g;\n\nfunction getData( data ) {\n\tif ( data === \"true\" ) {\n\t\treturn true;\n\t}\n\n\tif ( data === \"false\" ) {\n\t\treturn false;\n\t}\n\n\tif ( data === \"null\" ) {\n\t\treturn null;\n\t}\n\n\t// Only convert to a number if it doesn't change the string\n\tif ( data === +data + \"\" ) {\n\t\treturn +data;\n\t}\n\n\tif ( rbrace.test( data ) ) {\n\t\treturn JSON.parse( data );\n\t}\n\n\treturn data;\n}\n\nfunction dataAttr( elem, key, data ) {\n\tvar name;\n\n\t// If nothing was found internally, try to fetch any\n\t// data from the HTML5 data-* attribute\n\tif ( data === undefined && elem.nodeType === 1 ) {\n\t\tname = \"data-\" + key.replace( rmultiDash, \"-$&\" ).toLowerCase();\n\t\tdata = elem.getAttribute( name );\n\n\t\tif ( typeof data === \"string\" ) {\n\t\t\ttry {\n\t\t\t\tdata = getData( data );\n\t\t\t} catch ( e ) {}\n\n\t\t\t// Make sure we set the data so it isn't changed later\n\t\t\tdataUser.set( elem, key, data );\n\t\t} else {\n\t\t\tdata = undefined;\n\t\t}\n\t}\n\treturn data;\n}\n\njQuery.extend( {\n\thasData: function( elem ) {\n\t\treturn dataUser.hasData( elem ) || dataPriv.hasData( elem );\n\t},\n\n\tdata: function( elem, name, data ) {\n\t\treturn dataUser.access( elem, name, data );\n\t},\n\n\tremoveData: function( elem, name ) {\n\t\tdataUser.remove( elem, name );\n\t},\n\n\t// TODO: Now that all calls to _data and _removeData have been replaced\n\t// with direct calls to dataPriv methods, these can be deprecated.\n\t_data: function( elem, name, data ) {\n\t\treturn dataPriv.access( elem, name, data );\n\t},\n\n\t_removeData: function( elem, name ) {\n\t\tdataPriv.remove( elem, name );\n\t}\n} );\n\njQuery.fn.extend( {\n\tdata: function( key, value ) {\n\t\tvar i, name, data,\n\t\t\telem = this[ 0 ],\n\t\t\tattrs = elem && elem.attributes;\n\n\t\t// Gets all values\n\t\tif ( key === undefined ) {\n\t\t\tif ( this.length ) {\n\t\t\t\tdata = dataUser.get( elem );\n\n\t\t\t\tif ( elem.nodeType === 1 && !dataPriv.get( elem, \"hasDataAttrs\" ) ) {\n\t\t\t\t\ti = attrs.length;\n\t\t\t\t\twhile ( i-- ) {\n\n\t\t\t\t\t\t// Support: IE 11 only\n\t\t\t\t\t\t// The attrs elements can be null (#14894)\n\t\t\t\t\t\tif ( attrs[ i ] ) {\n\t\t\t\t\t\t\tname = attrs[ i ].name;\n\t\t\t\t\t\t\tif ( name.indexOf( \"data-\" ) === 0 ) {\n\t\t\t\t\t\t\t\tname = camelCase( name.slice( 5 ) );\n\t\t\t\t\t\t\t\tdataAttr( elem, name, data[ name ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tdataPriv.set( elem, \"hasDataAttrs\", true );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\treturn data;\n\t\t}\n\n\t\t// Sets multiple values\n\t\tif ( typeof key === \"object\" ) {\n\t\t\treturn this.each( function() {\n\t\t\t\tdataUser.set( this, key );\n\t\t\t} );\n\t\t}\n\n\t\treturn access( this, function( value ) {\n\t\t\tvar data;\n\n\t\t\t// The calling jQuery object (element matches) is not empty\n\t\t\t// (and therefore has an element appears at this[ 0 ]) and the\n\t\t\t// `value` parameter was not undefined. An empty jQuery object\n\t\t\t// will result in `undefined` for elem = this[ 0 ] which will\n\t\t\t// throw an exception if an attempt to read a data cache is made.\n\t\t\tif ( elem && value === undefined ) {\n\n\t\t\t\t// Attempt to get data from the cache\n\t\t\t\t// The key will always be camelCased in Data\n\t\t\t\tdata = dataUser.get( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// Attempt to \"discover\" the data in\n\t\t\t\t// HTML5 custom data-* attrs\n\t\t\t\tdata = dataAttr( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// We tried really hard, but the data doesn't exist.\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Set the data...\n\t\t\tthis.each( function() {\n\n\t\t\t\t// We always store the camelCased key\n\t\t\t\tdataUser.set( this, key, value );\n\t\t\t} );\n\t\t}, null, value, arguments.length > 1, null, true );\n\t},\n\n\tremoveData: function( key ) {\n\t\treturn this.each( function() {\n\t\t\tdataUser.remove( this, key );\n\t\t} );\n\t}\n} );\n\n\njQuery.extend( {\n\tqueue: function( elem, type, data ) {\n\t\tvar queue;\n\n\t\tif ( elem ) {\n\t\t\ttype = ( type || \"fx\" ) + \"queue\";\n\t\t\tqueue = dataPriv.get( elem, type );\n\n\t\t\t// Speed up dequeue by getting out quickly if this is just a lookup\n\t\t\tif ( data ) {\n\t\t\t\tif ( !queue || Array.isArray( data ) ) {\n\t\t\t\t\tqueue = dataPriv.access( elem, type, jQuery.makeArray( data ) );\n\t\t\t\t} else {\n\t\t\t\t\tqueue.push( data );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn queue || [];\n\t\t}\n\t},\n\n\tdequeue: function( elem, type ) {\n\t\ttype = type || \"fx\";\n\n\t\tvar queue = jQuery.queue( elem, type ),\n\t\t\tstartLength = queue.length,\n\t\t\tfn = queue.shift(),\n\t\t\thooks = jQuery._queueHooks( elem, type ),\n\t\t\tnext = function() {\n\t\t\t\tjQuery.dequeue( elem, type );\n\t\t\t};\n\n\t\t// If the fx queue is dequeued, always remove the progress sentinel\n\t\tif ( fn === \"inprogress\" ) {\n\t\t\tfn = queue.shift();\n\t\t\tstartLength--;\n\t\t}\n\n\t\tif ( fn ) {\n\n\t\t\t// Add a progress sentinel to prevent the fx queue from being\n\t\t\t// automatically dequeued\n\t\t\tif ( type === \"fx\" ) {\n\t\t\t\tqueue.unshift( \"inprogress\" );\n\t\t\t}\n\n\t\t\t// Clear up the last queue stop function\n\t\t\tdelete hooks.stop;\n\t\t\tfn.call( elem, next, hooks );\n\t\t}\n\n\t\tif ( !startLength && hooks ) {\n\t\t\thooks.empty.fire();\n\t\t}\n\t},\n\n\t// Not public - generate a queueHooks object, or return the current one\n\t_queueHooks: function( elem, type ) {\n\t\tvar key = type + \"queueHooks\";\n\t\treturn dataPriv.get( elem, key ) || dataPriv.access( elem, key, {\n\t\t\tempty: jQuery.Callbacks( \"once memory\" ).add( function() {\n\t\t\t\tdataPriv.remove( elem, [ type + \"queue\", key ] );\n\t\t\t} )\n\t\t} );\n\t}\n} );\n\njQuery.fn.extend( {\n\tqueue: function( type, data ) {\n\t\tvar setter = 2;\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tdata = type;\n\t\t\ttype = \"fx\";\n\t\t\tsetter--;\n\t\t}\n\n\t\tif ( arguments.length < setter ) {\n\t\t\treturn jQuery.queue( this[ 0 ], type );\n\t\t}\n\n\t\treturn data === undefined ?\n\t\t\tthis :\n\t\t\tthis.each( function() {\n\t\t\t\tvar queue = jQuery.queue( this, type, data );\n\n\t\t\t\t// Ensure a hooks for this queue\n\t\t\t\tjQuery._queueHooks( this, type );\n\n\t\t\t\tif ( type === \"fx\" && queue[ 0 ] !== \"inprogress\" ) {\n\t\t\t\t\tjQuery.dequeue( this, type );\n\t\t\t\t}\n\t\t\t} );\n\t},\n\tdequeue: function( type ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.dequeue( this, type );\n\t\t} );\n\t},\n\tclearQueue: function( type ) {\n\t\treturn this.queue( type || \"fx\", [] );\n\t},\n\n\t// Get a promise resolved when queues of a certain type\n\t// are emptied (fx is the type by default)\n\tpromise: function( type, obj ) {\n\t\tvar tmp,\n\t\t\tcount = 1,\n\t\t\tdefer = jQuery.Deferred(),\n\t\t\telements = this,\n\t\t\ti = this.length,\n\t\t\tresolve = function() {\n\t\t\t\tif ( !( --count ) ) {\n\t\t\t\t\tdefer.resolveWith( elements, [ elements ] );\n\t\t\t\t}\n\t\t\t};\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tobj = type;\n\t\t\ttype = undefined;\n\t\t}\n\t\ttype = type || \"fx\";\n\n\t\twhile ( i-- ) {\n\t\t\ttmp = dataPriv.get( elements[ i ], type + \"queueHooks\" );\n\t\t\tif ( tmp && tmp.empty ) {\n\t\t\t\tcount++;\n\t\t\t\ttmp.empty.add( resolve );\n\t\t\t}\n\t\t}\n\t\tresolve();\n\t\treturn defer.promise( obj );\n\t}\n} );\nvar pnum = ( /[+-]?(?:\\d*\\.|)\\d+(?:[eE][+-]?\\d+|)/ ).source;\n\nvar rcssNum = new RegExp( \"^(?:([+-])=|)(\" + pnum + \")([a-z%]*)$\", \"i\" );\n\n\nvar cssExpand = [ \"Top\", \"Right\", \"Bottom\", \"Left\" ];\n\nvar documentElement = document.documentElement;\n\n\n\n\tvar isAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem );\n\t\t},\n\t\tcomposed = { composed: true };\n\n\t// Support: IE 9 - 11+, Edge 12 - 18+, iOS 10.0 - 10.2 only\n\t// Check attachment across shadow DOM boundaries when possible (gh-3504)\n\t// Support: iOS 10.0-10.2 only\n\t// Early iOS 10 versions support `attachShadow` but not `getRootNode`,\n\t// leading to errors. We need to check for `getRootNode`.\n\tif ( documentElement.getRootNode ) {\n\t\tisAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem ) ||\n\t\t\t\telem.getRootNode( composed ) === elem.ownerDocument;\n\t\t};\n\t}\nvar isHiddenWithinTree = function( elem, el ) {\n\n\t\t// isHiddenWithinTree might be called from jQuery#filter function;\n\t\t// in that case, element will be second argument\n\t\telem = el || elem;\n\n\t\t// Inline style trumps all\n\t\treturn elem.style.display === \"none\" ||\n\t\t\telem.style.display === \"\" &&\n\n\t\t\t// Otherwise, check computed style\n\t\t\t// Support: Firefox <=43 - 45\n\t\t\t// Disconnected elements can have computed display: none, so first confirm that elem is\n\t\t\t// in the document.\n\t\t\tisAttached( elem ) &&\n\n\t\t\tjQuery.css( elem, \"display\" ) === \"none\";\n\t};\n\nvar swap = function( elem, options, callback, args ) {\n\tvar ret, name,\n\t\told = {};\n\n\t// Remember the old values, and insert the new ones\n\tfor ( name in options ) {\n\t\told[ name ] = elem.style[ name ];\n\t\telem.style[ name ] = options[ name ];\n\t}\n\n\tret = callback.apply( elem, args || [] );\n\n\t// Revert the old values\n\tfor ( name in options ) {\n\t\telem.style[ name ] = old[ name ];\n\t}\n\n\treturn ret;\n};\n\n\n\n\nfunction adjustCSS( elem, prop, valueParts, tween ) {\n\tvar adjusted, scale,\n\t\tmaxIterations = 20,\n\t\tcurrentValue = tween ?\n\t\t\tfunction() {\n\t\t\t\treturn tween.cur();\n\t\t\t} :\n\t\t\tfunction() {\n\t\t\t\treturn jQuery.css( elem, prop, \"\" );\n\t\t\t},\n\t\tinitial = currentValue(),\n\t\tunit = valueParts && valueParts[ 3 ] || ( jQuery.cssNumber[ prop ] ? \"\" : \"px\" ),\n\n\t\t// Starting value computation is required for potential unit mismatches\n\t\tinitialInUnit = elem.nodeType &&\n\t\t\t( jQuery.cssNumber[ prop ] || unit !== \"px\" && +initial ) &&\n\t\t\trcssNum.exec( jQuery.css( elem, prop ) );\n\n\tif ( initialInUnit && initialInUnit[ 3 ] !== unit ) {\n\n\t\t// Support: Firefox <=54\n\t\t// Halve the iteration target value to prevent interference from CSS upper bounds (gh-2144)\n\t\tinitial = initial / 2;\n\n\t\t// Trust units reported by jQuery.css\n\t\tunit = unit || initialInUnit[ 3 ];\n\n\t\t// Iteratively approximate from a nonzero starting point\n\t\tinitialInUnit = +initial || 1;\n\n\t\twhile ( maxIterations-- ) {\n\n\t\t\t// Evaluate and update our best guess (doubling guesses that zero out).\n\t\t\t// Finish if the scale equals or crosses 1 (making the old*new product non-positive).\n\t\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\t\t\tif ( ( 1 - scale ) * ( 1 - ( scale = currentValue() / initial || 0.5 ) ) <= 0 ) {\n\t\t\t\tmaxIterations = 0;\n\t\t\t}\n\t\t\tinitialInUnit = initialInUnit / scale;\n\n\t\t}\n\n\t\tinitialInUnit = initialInUnit * 2;\n\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\n\t\t// Make sure we update the tween properties later on\n\t\tvalueParts = valueParts || [];\n\t}\n\n\tif ( valueParts ) {\n\t\tinitialInUnit = +initialInUnit || +initial || 0;\n\n\t\t// Apply relative offset (+=/-=) if specified\n\t\tadjusted = valueParts[ 1 ] ?\n\t\t\tinitialInUnit + ( valueParts[ 1 ] + 1 ) * valueParts[ 2 ] :\n\t\t\t+valueParts[ 2 ];\n\t\tif ( tween ) {\n\t\t\ttween.unit = unit;\n\t\t\ttween.start = initialInUnit;\n\t\t\ttween.end = adjusted;\n\t\t}\n\t}\n\treturn adjusted;\n}\n\n\nvar defaultDisplayMap = {};\n\nfunction getDefaultDisplay( elem ) {\n\tvar temp,\n\t\tdoc = elem.ownerDocument,\n\t\tnodeName = elem.nodeName,\n\t\tdisplay = defaultDisplayMap[ nodeName ];\n\n\tif ( display ) {\n\t\treturn display;\n\t}\n\n\ttemp = doc.body.appendChild( doc.createElement( nodeName ) );\n\tdisplay = jQuery.css( temp, \"display\" );\n\n\ttemp.parentNode.removeChild( temp );\n\n\tif ( display === \"none\" ) {\n\t\tdisplay = \"block\";\n\t}\n\tdefaultDisplayMap[ nodeName ] = display;\n\n\treturn display;\n}\n\nfunction showHide( elements, show ) {\n\tvar display, elem,\n\t\tvalues = [],\n\t\tindex = 0,\n\t\tlength = elements.length;\n\n\t// Determine new display value for elements that need to change\n\tfor ( ; index < length; index++ ) {\n\t\telem = elements[ index ];\n\t\tif ( !elem.style ) {\n\t\t\tcontinue;\n\t\t}\n\n\t\tdisplay = elem.style.display;\n\t\tif ( show ) {\n\n\t\t\t// Since we force visibility upon cascade-hidden elements, an immediate (and slow)\n\t\t\t// check is required in this first loop unless we have a nonempty display value (either\n\t\t\t// inline or about-to-be-restored)\n\t\t\tif ( display === \"none\" ) {\n\t\t\t\tvalues[ index ] = dataPriv.get( elem, \"display\" ) || null;\n\t\t\t\tif ( !values[ index ] ) {\n\t\t\t\t\telem.style.display = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t\tif ( elem.style.display === \"\" && isHiddenWithinTree( elem ) ) {\n\t\t\t\tvalues[ index ] = getDefaultDisplay( elem );\n\t\t\t}\n\t\t} else {\n\t\t\tif ( display !== \"none\" ) {\n\t\t\t\tvalues[ index ] = \"none\";\n\n\t\t\t\t// Remember what we're overwriting\n\t\t\t\tdataPriv.set( elem, \"display\", display );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Set the display of the elements in a second loop to avoid constant reflow\n\tfor ( index = 0; index < length; index++ ) {\n\t\tif ( values[ index ] != null ) {\n\t\t\telements[ index ].style.display = values[ index ];\n\t\t}\n\t}\n\n\treturn elements;\n}\n\njQuery.fn.extend( {\n\tshow: function() {\n\t\treturn showHide( this, true );\n\t},\n\thide: function() {\n\t\treturn showHide( this );\n\t},\n\ttoggle: function( state ) {\n\t\tif ( typeof state === \"boolean\" ) {\n\t\t\treturn state ? this.show() : this.hide();\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tif ( isHiddenWithinTree( this ) ) {\n\t\t\t\tjQuery( this ).show();\n\t\t\t} else {\n\t\t\t\tjQuery( this ).hide();\n\t\t\t}\n\t\t} );\n\t}\n} );\nvar rcheckableType = ( /^(?:checkbox|radio)$/i );\n\nvar rtagName = ( /<([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)/i );\n\nvar rscriptType = ( /^$|^module$|\\/(?:java|ecma)script/i );\n\n\n\n// We have to close these tags to support XHTML (#13200)\nvar wrapMap = {\n\n\t// Support: IE <=9 only\n\toption: [ 1, \"<select multiple='multiple'>\", \"</select>\" ],\n\n\t// XHTML parsers do not magically insert elements in the\n\t// same way that tag soup parsers do. So we cannot shorten\n\t// this by omitting <tbody> or other required elements.\n\tthead: [ 1, \"<table>\", \"</table>\" ],\n\tcol: [ 2, \"<table><colgroup>\", \"</colgroup></table>\" ],\n\ttr: [ 2, \"<table><tbody>\", \"</tbody></table>\" ],\n\ttd: [ 3, \"<table><tbody><tr>\", \"</tr></tbody></table>\" ],\n\n\t_default: [ 0, \"\", \"\" ]\n};\n\n// Support: IE <=9 only\nwrapMap.optgroup = wrapMap.option;\n\nwrapMap.tbody = wrapMap.tfoot = wrapMap.colgroup = wrapMap.caption = wrapMap.thead;\nwrapMap.th = wrapMap.td;\n\n\nfunction getAll( context, tag ) {\n\n\t// Support: IE <=9 - 11 only\n\t// Use typeof to avoid zero-argument method invocation on host objects (#15151)\n\tvar ret;\n\n\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\tret = context.getElementsByTagName( tag || \"*\" );\n\n\t} else if ( typeof context.querySelectorAll !== \"undefined\" ) {\n\t\tret = context.querySelectorAll( tag || \"*\" );\n\n\t} else {\n\t\tret = [];\n\t}\n\n\tif ( tag === undefined || tag && nodeName( context, tag ) ) {\n\t\treturn jQuery.merge( [ context ], ret );\n\t}\n\n\treturn ret;\n}\n\n\n// Mark scripts as having already been evaluated\nfunction setGlobalEval( elems, refElements ) {\n\tvar i = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\tdataPriv.set(\n\t\t\telems[ i ],\n\t\t\t\"globalEval\",\n\t\t\t!refElements || dataPriv.get( refElements[ i ], \"globalEval\" )\n\t\t);\n\t}\n}\n\n\nvar rhtml = /<|&#?\\w+;/;\n\nfunction buildFragment( elems, context, scripts, selection, ignored ) {\n\tvar elem, tmp, tag, wrap, attached, j,\n\t\tfragment = context.createDocumentFragment(),\n\t\tnodes = [],\n\t\ti = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\telem = elems[ i ];\n\n\t\tif ( elem || elem === 0 ) {\n\n\t\t\t// Add nodes directly\n\t\t\tif ( toType( elem ) === \"object\" ) {\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, elem.nodeType ? [ elem ] : elem );\n\n\t\t\t// Convert non-html into a text node\n\t\t\t} else if ( !rhtml.test( elem ) ) {\n\t\t\t\tnodes.push( context.createTextNode( elem ) );\n\n\t\t\t// Convert html into DOM nodes\n\t\t\t} else {\n\t\t\t\ttmp = tmp || fragment.appendChild( context.createElement( \"div\" ) );\n\n\t\t\t\t// Deserialize a standard representation\n\t\t\t\ttag = ( rtagName.exec( elem ) || [ \"\", \"\" ] )[ 1 ].toLowerCase();\n\t\t\t\twrap = wrapMap[ tag ] || wrapMap._default;\n\t\t\t\ttmp.innerHTML = wrap[ 1 ] + jQuery.htmlPrefilter( elem ) + wrap[ 2 ];\n\n\t\t\t\t// Descend through wrappers to the right content\n\t\t\t\tj = wrap[ 0 ];\n\t\t\t\twhile ( j-- ) {\n\t\t\t\t\ttmp = tmp.lastChild;\n\t\t\t\t}\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, tmp.childNodes );\n\n\t\t\t\t// Remember the top-level container\n\t\t\t\ttmp = fragment.firstChild;\n\n\t\t\t\t// Ensure the created nodes are orphaned (#12392)\n\t\t\t\ttmp.textContent = \"\";\n\t\t\t}\n\t\t}\n\t}\n\n\t// Remove wrapper from fragment\n\tfragment.textContent = \"\";\n\n\ti = 0;\n\twhile ( ( elem = nodes[ i++ ] ) ) {\n\n\t\t// Skip elements already in the context collection (trac-4087)\n\t\tif ( selection && jQuery.inArray( elem, selection ) > -1 ) {\n\t\t\tif ( ignored ) {\n\t\t\t\tignored.push( elem );\n\t\t\t}\n\t\t\tcontinue;\n\t\t}\n\n\t\tattached = isAttached( elem );\n\n\t\t// Append to fragment\n\t\ttmp = getAll( fragment.appendChild( elem ), \"script\" );\n\n\t\t// Preserve script evaluation history\n\t\tif ( attached ) {\n\t\t\tsetGlobalEval( tmp );\n\t\t}\n\n\t\t// Capture executables\n\t\tif ( scripts ) {\n\t\t\tj = 0;\n\t\t\twhile ( ( elem = tmp[ j++ ] ) ) {\n\t\t\t\tif ( rscriptType.test( elem.type || \"\" ) ) {\n\t\t\t\t\tscripts.push( elem );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn fragment;\n}\n\n\n( function() {\n\tvar fragment = document.createDocumentFragment(),\n\t\tdiv = fragment.appendChild( document.createElement( \"div\" ) ),\n\t\tinput = document.createElement( \"input\" );\n\n\t// Support: Android 4.0 - 4.3 only\n\t// Check state lost if the name is set (#11217)\n\t// Support: Windows Web Apps (WWA)\n\t// `name` and `type` must use .setAttribute for WWA (#14901)\n\tinput.setAttribute( \"type\", \"radio\" );\n\tinput.setAttribute( \"checked\", \"checked\" );\n\tinput.setAttribute( \"name\", \"t\" );\n\n\tdiv.appendChild( input );\n\n\t// Support: Android <=4.1 only\n\t// Older WebKit doesn't clone checked state correctly in fragments\n\tsupport.checkClone = div.cloneNode( true ).cloneNode( true ).lastChild.checked;\n\n\t// Support: IE <=11 only\n\t// Make sure textarea (and checkbox) defaultValue is properly cloned\n\tdiv.innerHTML = \"<textarea>x</textarea>\";\n\tsupport.noCloneChecked = !!div.cloneNode( true ).lastChild.defaultValue;\n} )();\n\n\nvar\n\trkeyEvent = /^key/,\n\trmouseEvent = /^(?:mouse|pointer|contextmenu|drag|drop)|click/,\n\trtypenamespace = /^([^.]*)(?:\\.(.+)|)/;\n\nfunction returnTrue() {\n\treturn true;\n}\n\nfunction returnFalse() {\n\treturn false;\n}\n\n// Support: IE <=9 - 11+\n// focus() and blur() are asynchronous, except when they are no-op.\n// So expect focus to be synchronous when the element is already active,\n// and blur to be synchronous when the element is not already active.\n// (focus and blur are always synchronous in other supported browsers,\n// this just defines when we can count on it).\nfunction expectSync( elem, type ) {\n\treturn ( elem === safeActiveElement() ) === ( type === \"focus\" );\n}\n\n// Support: IE <=9 only\n// Accessing document.activeElement can throw unexpectedly\n// https://bugs.jquery.com/ticket/13393\nfunction safeActiveElement() {\n\ttry {\n\t\treturn document.activeElement;\n\t} catch ( err ) { }\n}\n\nfunction on( elem, types, selector, data, fn, one ) {\n\tvar origFn, type;\n\n\t// Types can be a map of types/handlers\n\tif ( typeof types === \"object\" ) {\n\n\t\t// ( types-Object, selector, data )\n\t\tif ( typeof selector !== \"string\" ) {\n\n\t\t\t// ( types-Object, data )\n\t\t\tdata = data || selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tfor ( type in types ) {\n\t\t\ton( elem, type, selector, data, types[ type ], one );\n\t\t}\n\t\treturn elem;\n\t}\n\n\tif ( data == null && fn == null ) {\n\n\t\t// ( types, fn )\n\t\tfn = selector;\n\t\tdata = selector = undefined;\n\t} else if ( fn == null ) {\n\t\tif ( typeof selector === \"string\" ) {\n\n\t\t\t// ( types, selector, fn )\n\t\t\tfn = data;\n\t\t\tdata = undefined;\n\t\t} else {\n\n\t\t\t// ( types, data, fn )\n\t\t\tfn = data;\n\t\t\tdata = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t}\n\tif ( fn === false ) {\n\t\tfn = returnFalse;\n\t} else if ( !fn ) {\n\t\treturn elem;\n\t}\n\n\tif ( one === 1 ) {\n\t\torigFn = fn;\n\t\tfn = function( event ) {\n\n\t\t\t// Can use an empty set, since event contains the info\n\t\t\tjQuery().off( event );\n\t\t\treturn origFn.apply( this, arguments );\n\t\t};\n\n\t\t// Use same guid so caller can remove using origFn\n\t\tfn.guid = origFn.guid || ( origFn.guid = jQuery.guid++ );\n\t}\n\treturn elem.each( function() {\n\t\tjQuery.event.add( this, types, fn, data, selector );\n\t} );\n}\n\n/*\n * Helper functions for managing events -- not part of the public interface.\n * Props to Dean Edwards' addEvent library for many of the ideas.\n */\njQuery.event = {\n\n\tglobal: {},\n\n\tadd: function( elem, types, handler, data, selector ) {\n\n\t\tvar handleObjIn, eventHandle, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.get( elem );\n\n\t\t// Don't attach events to noData or text/comment nodes (but allow plain objects)\n\t\tif ( !elemData ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Caller can pass in an object of custom data in lieu of the handler\n\t\tif ( handler.handler ) {\n\t\t\thandleObjIn = handler;\n\t\t\thandler = handleObjIn.handler;\n\t\t\tselector = handleObjIn.selector;\n\t\t}\n\n\t\t// Ensure that invalid selectors throw exceptions at attach time\n\t\t// Evaluate against documentElement in case elem is a non-element node (e.g., document)\n\t\tif ( selector ) {\n\t\t\tjQuery.find.matchesSelector( documentElement, selector );\n\t\t}\n\n\t\t// Make sure that the handler has a unique ID, used to find/remove it later\n\t\tif ( !handler.guid ) {\n\t\t\thandler.guid = jQuery.guid++;\n\t\t}\n\n\t\t// Init the element's event structure and main handler, if this is the first\n\t\tif ( !( events = elemData.events ) ) {\n\t\t\tevents = elemData.events = {};\n\t\t}\n\t\tif ( !( eventHandle = elemData.handle ) ) {\n\t\t\teventHandle = elemData.handle = function( e ) {\n\n\t\t\t\t// Discard the second event of a jQuery.event.trigger() and\n\t\t\t\t// when an event is called after a page has unloaded\n\t\t\t\treturn typeof jQuery !== \"undefined\" && jQuery.event.triggered !== e.type ?\n\t\t\t\t\tjQuery.event.dispatch.apply( elem, arguments ) : undefined;\n\t\t\t};\n\t\t}\n\n\t\t// Handle multiple events separated by a space\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// There *must* be a type, no attaching namespace-only handlers\n\t\t\tif ( !type ) {\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\t// If event changes its type, use the special event handlers for the changed type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// If selector defined, determine special event api type, otherwise given type\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\n\t\t\t// Update special based on newly reset type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// handleObj is passed to all event handlers\n\t\t\thandleObj = jQuery.extend( {\n\t\t\t\ttype: type,\n\t\t\t\torigType: origType,\n\t\t\t\tdata: data,\n\t\t\t\thandler: handler,\n\t\t\t\tguid: handler.guid,\n\t\t\t\tselector: selector,\n\t\t\t\tneedsContext: selector && jQuery.expr.match.needsContext.test( selector ),\n\t\t\t\tnamespace: namespaces.join( \".\" )\n\t\t\t}, handleObjIn );\n\n\t\t\t// Init the event handler queue if we're the first\n\t\t\tif ( !( handlers = events[ type ] ) ) {\n\t\t\t\thandlers = events[ type ] = [];\n\t\t\t\thandlers.delegateCount = 0;\n\n\t\t\t\t// Only use addEventListener if the special events handler returns false\n\t\t\t\tif ( !special.setup ||\n\t\t\t\t\tspecial.setup.call( elem, data, namespaces, eventHandle ) === false ) {\n\n\t\t\t\t\tif ( elem.addEventListener ) {\n\t\t\t\t\t\telem.addEventListener( type, eventHandle );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tif ( special.add ) {\n\t\t\t\tspecial.add.call( elem, handleObj );\n\n\t\t\t\tif ( !handleObj.handler.guid ) {\n\t\t\t\t\thandleObj.handler.guid = handler.guid;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Add to the element's handler list, delegates in front\n\t\t\tif ( selector ) {\n\t\t\t\thandlers.splice( handlers.delegateCount++, 0, handleObj );\n\t\t\t} else {\n\t\t\t\thandlers.push( handleObj );\n\t\t\t}\n\n\t\t\t// Keep track of which events have ever been used, for event optimization\n\t\t\tjQuery.event.global[ type ] = true;\n\t\t}\n\n\t},\n\n\t// Detach an event or set of events from an element\n\tremove: function( elem, types, handler, selector, mappedTypes ) {\n\n\t\tvar j, origCount, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.hasData( elem ) && dataPriv.get( elem );\n\n\t\tif ( !elemData || !( events = elemData.events ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Once for each type.namespace in types; type may be omitted\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// Unbind all events (on this namespace, if provided) for the element\n\t\t\tif ( !type ) {\n\t\t\t\tfor ( type in events ) {\n\t\t\t\t\tjQuery.event.remove( elem, type + types[ t ], handler, selector, true );\n\t\t\t\t}\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\t\t\thandlers = events[ type ] || [];\n\t\t\ttmp = tmp[ 2 ] &&\n\t\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" );\n\n\t\t\t// Remove matching events\n\t\t\torigCount = j = handlers.length;\n\t\t\twhile ( j-- ) {\n\t\t\t\thandleObj = handlers[ j ];\n\n\t\t\t\tif ( ( mappedTypes || origType === handleObj.origType ) &&\n\t\t\t\t\t( !handler || handler.guid === handleObj.guid ) &&\n\t\t\t\t\t( !tmp || tmp.test( handleObj.namespace ) ) &&\n\t\t\t\t\t( !selector || selector === handleObj.selector ||\n\t\t\t\t\t\tselector === \"**\" && handleObj.selector ) ) {\n\t\t\t\t\thandlers.splice( j, 1 );\n\n\t\t\t\t\tif ( handleObj.selector ) {\n\t\t\t\t\t\thandlers.delegateCount--;\n\t\t\t\t\t}\n\t\t\t\t\tif ( special.remove ) {\n\t\t\t\t\t\tspecial.remove.call( elem, handleObj );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Remove generic event handler if we removed something and no more handlers exist\n\t\t\t// (avoids potential for endless recursion during removal of special event handlers)\n\t\t\tif ( origCount && !handlers.length ) {\n\t\t\t\tif ( !special.teardown ||\n\t\t\t\t\tspecial.teardown.call( elem, namespaces, elemData.handle ) === false ) {\n\n\t\t\t\t\tjQuery.removeEvent( elem, type, elemData.handle );\n\t\t\t\t}\n\n\t\t\t\tdelete events[ type ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove data and the expando if it's no longer used\n\t\tif ( jQuery.isEmptyObject( events ) ) {\n\t\t\tdataPriv.remove( elem, \"handle events\" );\n\t\t}\n\t},\n\n\tdispatch: function( nativeEvent ) {\n\n\t\t// Make a writable jQuery.Event from the native event object\n\t\tvar event = jQuery.event.fix( nativeEvent );\n\n\t\tvar i, j, ret, matched, handleObj, handlerQueue,\n\t\t\targs = new Array( arguments.length ),\n\t\t\thandlers = ( dataPriv.get( this, \"events\" ) || {} )[ event.type ] || [],\n\t\t\tspecial = jQuery.event.special[ event.type ] || {};\n\n\t\t// Use the fix-ed jQuery.Event rather than the (read-only) native event\n\t\targs[ 0 ] = event;\n\n\t\tfor ( i = 1; i < arguments.length; i++ ) {\n\t\t\targs[ i ] = arguments[ i ];\n\t\t}\n\n\t\tevent.delegateTarget = this;\n\n\t\t// Call the preDispatch hook for the mapped type, and let it bail if desired\n\t\tif ( special.preDispatch && special.preDispatch.call( this, event ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine handlers\n\t\thandlerQueue = jQuery.event.handlers.call( this, event, handlers );\n\n\t\t// Run delegates first; they may want to stop propagation beneath us\n\t\ti = 0;\n\t\twhile ( ( matched = handlerQueue[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tevent.currentTarget = matched.elem;\n\n\t\t\tj = 0;\n\t\t\twhile ( ( handleObj = matched.handlers[ j++ ] ) &&\n\t\t\t\t!event.isImmediatePropagationStopped() ) {\n\n\t\t\t\t// If the event is namespaced, then each handler is only invoked if it is\n\t\t\t\t// specially universal or its namespaces are a superset of the event's.\n\t\t\t\tif ( !event.rnamespace || handleObj.namespace === false ||\n\t\t\t\t\tevent.rnamespace.test( handleObj.namespace ) ) {\n\n\t\t\t\t\tevent.handleObj = handleObj;\n\t\t\t\t\tevent.data = handleObj.data;\n\n\t\t\t\t\tret = ( ( jQuery.event.special[ handleObj.origType ] || {} ).handle ||\n\t\t\t\t\t\thandleObj.handler ).apply( matched.elem, args );\n\n\t\t\t\t\tif ( ret !== undefined ) {\n\t\t\t\t\t\tif ( ( event.result = ret ) === false ) {\n\t\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Call the postDispatch hook for the mapped type\n\t\tif ( special.postDispatch ) {\n\t\t\tspecial.postDispatch.call( this, event );\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\thandlers: function( event, handlers ) {\n\t\tvar i, handleObj, sel, matchedHandlers, matchedSelectors,\n\t\t\thandlerQueue = [],\n\t\t\tdelegateCount = handlers.delegateCount,\n\t\t\tcur = event.target;\n\n\t\t// Find delegate handlers\n\t\tif ( delegateCount &&\n\n\t\t\t// Support: IE <=9\n\t\t\t// Black-hole SVG <use> instance trees (trac-13180)\n\t\t\tcur.nodeType &&\n\n\t\t\t// Support: Firefox <=42\n\t\t\t// Suppress spec-violating clicks indicating a non-primary pointer button (trac-3861)\n\t\t\t// https://www.w3.org/TR/DOM-Level-3-Events/#event-type-click\n\t\t\t// Support: IE 11 only\n\t\t\t// ...but not arrow key \"clicks\" of radio inputs, which can have `button` -1 (gh-2343)\n\t\t\t!( event.type === \"click\" && event.button >= 1 ) ) {\n\n\t\t\tfor ( ; cur !== this; cur = cur.parentNode || this ) {\n\n\t\t\t\t// Don't check non-elements (#13208)\n\t\t\t\t// Don't process clicks on disabled elements (#6911, #8165, #11382, #11764)\n\t\t\t\tif ( cur.nodeType === 1 && !( event.type === \"click\" && cur.disabled === true ) ) {\n\t\t\t\t\tmatchedHandlers = [];\n\t\t\t\t\tmatchedSelectors = {};\n\t\t\t\t\tfor ( i = 0; i < delegateCount; i++ ) {\n\t\t\t\t\t\thandleObj = handlers[ i ];\n\n\t\t\t\t\t\t// Don't conflict with Object.prototype properties (#13203)\n\t\t\t\t\t\tsel = handleObj.selector + \" \";\n\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] === undefined ) {\n\t\t\t\t\t\t\tmatchedSelectors[ sel ] = handleObj.needsContext ?\n\t\t\t\t\t\t\t\tjQuery( sel, this ).index( cur ) > -1 :\n\t\t\t\t\t\t\t\tjQuery.find( sel, this, null, [ cur ] ).length;\n\t\t\t\t\t\t}\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] ) {\n\t\t\t\t\t\t\tmatchedHandlers.push( handleObj );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( matchedHandlers.length ) {\n\t\t\t\t\t\thandlerQueue.push( { elem: cur, handlers: matchedHandlers } );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Add the remaining (directly-bound) handlers\n\t\tcur = this;\n\t\tif ( delegateCount < handlers.length ) {\n\t\t\thandlerQueue.push( { elem: cur, handlers: handlers.slice( delegateCount ) } );\n\t\t}\n\n\t\treturn handlerQueue;\n\t},\n\n\taddProp: function( name, hook ) {\n\t\tObject.defineProperty( jQuery.Event.prototype, name, {\n\t\t\tenumerable: true,\n\t\t\tconfigurable: true,\n\n\t\t\tget: isFunction( hook ) ?\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn hook( this.originalEvent );\n\t\t\t\t\t}\n\t\t\t\t} :\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn this.originalEvent[ name ];\n\t\t\t\t\t}\n\t\t\t\t},\n\n\t\t\tset: function( value ) {\n\t\t\t\tObject.defineProperty( this, name, {\n\t\t\t\t\tenumerable: true,\n\t\t\t\t\tconfigurable: true,\n\t\t\t\t\twritable: true,\n\t\t\t\t\tvalue: value\n\t\t\t\t} );\n\t\t\t}\n\t\t} );\n\t},\n\n\tfix: function( originalEvent ) {\n\t\treturn originalEvent[ jQuery.expando ] ?\n\t\t\toriginalEvent :\n\t\t\tnew jQuery.Event( originalEvent );\n\t},\n\n\tspecial: {\n\t\tload: {\n\n\t\t\t// Prevent triggered image.load events from bubbling to window.load\n\t\t\tnoBubble: true\n\t\t},\n\t\tclick: {\n\n\t\t\t// Utilize native event to ensure correct state for checkable inputs\n\t\t\tsetup: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Claim the first handler\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\t// dataPriv.set( el, \"click\", ... )\n\t\t\t\t\tleverageNative( el, \"click\", returnTrue );\n\t\t\t\t}\n\n\t\t\t\t// Return false to allow normal processing in the caller\n\t\t\t\treturn false;\n\t\t\t},\n\t\t\ttrigger: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Force setup before triggering a click\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\tleverageNative( el, \"click\" );\n\t\t\t\t}\n\n\t\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\t\treturn true;\n\t\t\t},\n\n\t\t\t// For cross-browser consistency, suppress native .click() on links\n\t\t\t// Also prevent it if we're currently inside a leveraged native-event stack\n\t\t\t_default: function( event ) {\n\t\t\t\tvar target = event.target;\n\t\t\t\treturn rcheckableType.test( target.type ) &&\n\t\t\t\t\ttarget.click && nodeName( target, \"input\" ) &&\n\t\t\t\t\tdataPriv.get( target, \"click\" ) ||\n\t\t\t\t\tnodeName( target, \"a\" );\n\t\t\t}\n\t\t},\n\n\t\tbeforeunload: {\n\t\t\tpostDispatch: function( event ) {\n\n\t\t\t\t// Support: Firefox 20+\n\t\t\t\t// Firefox doesn't alert if the returnValue field is not set.\n\t\t\t\tif ( event.result !== undefined && event.originalEvent ) {\n\t\t\t\t\tevent.originalEvent.returnValue = event.result;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n};\n\n// Ensure the presence of an event listener that handles manually-triggered\n// synthetic events by interrupting progress until reinvoked in response to\n// *native* events that it fires directly, ensuring that state changes have\n// already occurred before other listeners are invoked.\nfunction leverageNative( el, type, expectSync ) {\n\n\t// Missing expectSync indicates a trigger call, which must force setup through jQuery.event.add\n\tif ( !expectSync ) {\n\t\tif ( dataPriv.get( el, type ) === undefined ) {\n\t\t\tjQuery.event.add( el, type, returnTrue );\n\t\t}\n\t\treturn;\n\t}\n\n\t// Register the controller as a special universal handler for all event namespaces\n\tdataPriv.set( el, type, false );\n\tjQuery.event.add( el, type, {\n\t\tnamespace: false,\n\t\thandler: function( event ) {\n\t\t\tvar notAsync, result,\n\t\t\t\tsaved = dataPriv.get( this, type );\n\n\t\t\tif ( ( event.isTrigger & 1 ) && this[ type ] ) {\n\n\t\t\t\t// Interrupt processing of the outer synthetic .trigger()ed event\n\t\t\t\t// Saved data should be false in such cases, but might be a leftover capture object\n\t\t\t\t// from an async native handler (gh-4350)\n\t\t\t\tif ( !saved.length ) {\n\n\t\t\t\t\t// Store arguments for use when handling the inner native event\n\t\t\t\t\t// There will always be at least one argument (an event object), so this array\n\t\t\t\t\t// will not be confused with a leftover capture object.\n\t\t\t\t\tsaved = slice.call( arguments );\n\t\t\t\t\tdataPriv.set( this, type, saved );\n\n\t\t\t\t\t// Trigger the native event and capture its result\n\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t// focus() and blur() are asynchronous\n\t\t\t\t\tnotAsync = expectSync( this, type );\n\t\t\t\t\tthis[ type ]();\n\t\t\t\t\tresult = dataPriv.get( this, type );\n\t\t\t\t\tif ( saved !== result || notAsync ) {\n\t\t\t\t\t\tdataPriv.set( this, type, false );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tresult = {};\n\t\t\t\t\t}\n\t\t\t\t\tif ( saved !== result ) {\n\n\t\t\t\t\t\t// Cancel the outer synthetic event\n\t\t\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\treturn result.value;\n\t\t\t\t\t}\n\n\t\t\t\t// If this is an inner synthetic event for an event with a bubbling surrogate\n\t\t\t\t// (focus or blur), assume that the surrogate already propagated from triggering the\n\t\t\t\t// native event and prevent that from happening again here.\n\t\t\t\t// This technically gets the ordering wrong w.r.t. to `.trigger()` (in which the\n\t\t\t\t// bubbling surrogate propagates *after* the non-bubbling base), but that seems\n\t\t\t\t// less bad than duplication.\n\t\t\t\t} else if ( ( jQuery.event.special[ type ] || {} ).delegateType ) {\n\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t}\n\n\t\t\t// If this is a native event triggered above, everything is now in order\n\t\t\t// Fire an inner synthetic event with the original arguments\n\t\t\t} else if ( saved.length ) {\n\n\t\t\t\t// ...and capture the result\n\t\t\t\tdataPriv.set( this, type, {\n\t\t\t\t\tvalue: jQuery.event.trigger(\n\n\t\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t\t// Extend with the prototype to reset the above stopImmediatePropagation()\n\t\t\t\t\t\tjQuery.extend( saved[ 0 ], jQuery.Event.prototype ),\n\t\t\t\t\t\tsaved.slice( 1 ),\n\t\t\t\t\t\tthis\n\t\t\t\t\t)\n\t\t\t\t} );\n\n\t\t\t\t// Abort handling of the native event\n\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t}\n\t\t}\n\t} );\n}\n\njQuery.removeEvent = function( elem, type, handle ) {\n\n\t// This \"if\" is needed for plain objects\n\tif ( elem.removeEventListener ) {\n\t\telem.removeEventListener( type, handle );\n\t}\n};\n\njQuery.Event = function( src, props ) {\n\n\t// Allow instantiation without the 'new' keyword\n\tif ( !( this instanceof jQuery.Event ) ) {\n\t\treturn new jQuery.Event( src, props );\n\t}\n\n\t// Event object\n\tif ( src && src.type ) {\n\t\tthis.originalEvent = src;\n\t\tthis.type = src.type;\n\n\t\t// Events bubbling up the document may have been marked as prevented\n\t\t// by a handler lower down the tree; reflect the correct value.\n\t\tthis.isDefaultPrevented = src.defaultPrevented ||\n\t\t\t\tsrc.defaultPrevented === undefined &&\n\n\t\t\t\t// Support: Android <=2.3 only\n\t\t\t\tsrc.returnValue === false ?\n\t\t\treturnTrue :\n\t\t\treturnFalse;\n\n\t\t// Create target properties\n\t\t// Support: Safari <=6 - 7 only\n\t\t// Target should not be a text node (#504, #13143)\n\t\tthis.target = ( src.target && src.target.nodeType === 3 ) ?\n\t\t\tsrc.target.parentNode :\n\t\t\tsrc.target;\n\n\t\tthis.currentTarget = src.currentTarget;\n\t\tthis.relatedTarget = src.relatedTarget;\n\n\t// Event type\n\t} else {\n\t\tthis.type = src;\n\t}\n\n\t// Put explicitly provided properties onto the event object\n\tif ( props ) {\n\t\tjQuery.extend( this, props );\n\t}\n\n\t// Create a timestamp if incoming event doesn't have one\n\tthis.timeStamp = src && src.timeStamp || Date.now();\n\n\t// Mark it as fixed\n\tthis[ jQuery.expando ] = true;\n};\n\n// jQuery.Event is based on DOM3 Events as specified by the ECMAScript Language Binding\n// https://www.w3.org/TR/2003/WD-DOM-Level-3-Events-20030331/ecma-script-binding.html\njQuery.Event.prototype = {\n\tconstructor: jQuery.Event,\n\tisDefaultPrevented: returnFalse,\n\tisPropagationStopped: returnFalse,\n\tisImmediatePropagationStopped: returnFalse,\n\tisSimulated: false,\n\n\tpreventDefault: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isDefaultPrevented = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.preventDefault();\n\t\t}\n\t},\n\tstopPropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isPropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopPropagation();\n\t\t}\n\t},\n\tstopImmediatePropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isImmediatePropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopImmediatePropagation();\n\t\t}\n\n\t\tthis.stopPropagation();\n\t}\n};\n\n// Includes all common event props including KeyEvent and MouseEvent specific props\njQuery.each( {\n\taltKey: true,\n\tbubbles: true,\n\tcancelable: true,\n\tchangedTouches: true,\n\tctrlKey: true,\n\tdetail: true,\n\teventPhase: true,\n\tmetaKey: true,\n\tpageX: true,\n\tpageY: true,\n\tshiftKey: true,\n\tview: true,\n\t\"char\": true,\n\tcode: true,\n\tcharCode: true,\n\tkey: true,\n\tkeyCode: true,\n\tbutton: true,\n\tbuttons: true,\n\tclientX: true,\n\tclientY: true,\n\toffsetX: true,\n\toffsetY: true,\n\tpointerId: true,\n\tpointerType: true,\n\tscreenX: true,\n\tscreenY: true,\n\ttargetTouches: true,\n\ttoElement: true,\n\ttouches: true,\n\n\twhich: function( event ) {\n\t\tvar button = event.button;\n\n\t\t// Add which for key events\n\t\tif ( event.which == null && rkeyEvent.test( event.type ) ) {\n\t\t\treturn event.charCode != null ? event.charCode : event.keyCode;\n\t\t}\n\n\t\t// Add which for click: 1 === left; 2 === middle; 3 === right\n\t\tif ( !event.which && button !== undefined && rmouseEvent.test( event.type ) ) {\n\t\t\tif ( button & 1 ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\tif ( button & 2 ) {\n\t\t\t\treturn 3;\n\t\t\t}\n\n\t\t\tif ( button & 4 ) {\n\t\t\t\treturn 2;\n\t\t\t}\n\n\t\t\treturn 0;\n\t\t}\n\n\t\treturn event.which;\n\t}\n}, jQuery.event.addProp );\n\njQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( type, delegateType ) {\n\tjQuery.event.special[ type ] = {\n\n\t\t// Utilize native event if possible so blur/focus sequence is correct\n\t\tsetup: function() {\n\n\t\t\t// Claim the first handler\n\t\t\t// dataPriv.set( this, \"focus\", ... )\n\t\t\t// dataPriv.set( this, \"blur\", ... )\n\t\t\tleverageNative( this, type, expectSync );\n\n\t\t\t// Return false to allow normal processing in the caller\n\t\t\treturn false;\n\t\t},\n\t\ttrigger: function() {\n\n\t\t\t// Force setup before trigger\n\t\t\tleverageNative( this, type );\n\n\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\treturn true;\n\t\t},\n\n\t\tdelegateType: delegateType\n\t};\n} );\n\n// Create mouseenter/leave events using mouseover/out and event-time checks\n// so that event delegation works in jQuery.\n// Do the same for pointerenter/pointerleave and pointerover/pointerout\n//\n// Support: Safari 7 only\n// Safari sends mouseenter too often; see:\n// https://bugs.chromium.org/p/chromium/issues/detail?id=470258\n// for the description of the bug (it existed in older Chrome versions as well).\njQuery.each( {\n\tmouseenter: \"mouseover\",\n\tmouseleave: \"mouseout\",\n\tpointerenter: \"pointerover\",\n\tpointerleave: \"pointerout\"\n}, function( orig, fix ) {\n\tjQuery.event.special[ orig ] = {\n\t\tdelegateType: fix,\n\t\tbindType: fix,\n\n\t\thandle: function( event ) {\n\t\t\tvar ret,\n\t\t\t\ttarget = this,\n\t\t\t\trelated = event.relatedTarget,\n\t\t\t\thandleObj = event.handleObj;\n\n\t\t\t// For mouseenter/leave call the handler if related is outside the target.\n\t\t\t// NB: No relatedTarget if the mouse left/entered the browser window\n\t\t\tif ( !related || ( related !== target && !jQuery.contains( target, related ) ) ) {\n\t\t\t\tevent.type = handleObj.origType;\n\t\t\t\tret = handleObj.handler.apply( this, arguments );\n\t\t\t\tevent.type = fix;\n\t\t\t}\n\t\t\treturn ret;\n\t\t}\n\t};\n} );\n\njQuery.fn.extend( {\n\n\ton: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn );\n\t},\n\tone: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn, 1 );\n\t},\n\toff: function( types, selector, fn ) {\n\t\tvar handleObj, type;\n\t\tif ( types && types.preventDefault && types.handleObj ) {\n\n\t\t\t// ( event )  dispatched jQuery.Event\n\t\t\thandleObj = types.handleObj;\n\t\t\tjQuery( types.delegateTarget ).off(\n\t\t\t\thandleObj.namespace ?\n\t\t\t\t\thandleObj.origType + \".\" + handleObj.namespace :\n\t\t\t\t\thandleObj.origType,\n\t\t\t\thandleObj.selector,\n\t\t\t\thandleObj.handler\n\t\t\t);\n\t\t\treturn this;\n\t\t}\n\t\tif ( typeof types === \"object\" ) {\n\n\t\t\t// ( types-object [, selector] )\n\t\t\tfor ( type in types ) {\n\t\t\t\tthis.off( type, selector, types[ type ] );\n\t\t\t}\n\t\t\treturn this;\n\t\t}\n\t\tif ( selector === false || typeof selector === \"function\" ) {\n\n\t\t\t// ( types [, fn] )\n\t\t\tfn = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tif ( fn === false ) {\n\t\t\tfn = returnFalse;\n\t\t}\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.remove( this, types, fn, selector );\n\t\t} );\n\t}\n} );\n\n\nvar\n\n\t/* eslint-disable max-len */\n\n\t// See https://github.com/eslint/eslint/issues/3229\n\trxhtmlTag = /<(?!area|br|col|embed|hr|img|input|link|meta|param)(([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)[^>]*)\\/>/gi,\n\n\t/* eslint-enable */\n\n\t// Support: IE <=10 - 11, Edge 12 - 13 only\n\t// In IE/Edge using regex groups here causes severe slowdowns.\n\t// See https://connect.microsoft.com/IE/feedback/details/1736512/\n\trnoInnerhtml = /<script|<style|<link/i,\n\n\t// checked=\"checked\" or checked\n\trchecked = /checked\\s*(?:[^=]|=\\s*.checked.)/i,\n\trcleanScript = /^\\s*<!(?:\\[CDATA\\[|--)|(?:\\]\\]|--)>\\s*$/g;\n\n// Prefer a tbody over its parent table for containing new rows\nfunction manipulationTarget( elem, content ) {\n\tif ( nodeName( elem, \"table\" ) &&\n\t\tnodeName( content.nodeType !== 11 ? content : content.firstChild, \"tr\" ) ) {\n\n\t\treturn jQuery( elem ).children( \"tbody\" )[ 0 ] || elem;\n\t}\n\n\treturn elem;\n}\n\n// Replace/restore the type attribute of script elements for safe DOM manipulation\nfunction disableScript( elem ) {\n\telem.type = ( elem.getAttribute( \"type\" ) !== null ) + \"/\" + elem.type;\n\treturn elem;\n}\nfunction restoreScript( elem ) {\n\tif ( ( elem.type || \"\" ).slice( 0, 5 ) === \"true/\" ) {\n\t\telem.type = elem.type.slice( 5 );\n\t} else {\n\t\telem.removeAttribute( \"type\" );\n\t}\n\n\treturn elem;\n}\n\nfunction cloneCopyEvent( src, dest ) {\n\tvar i, l, type, pdataOld, pdataCur, udataOld, udataCur, events;\n\n\tif ( dest.nodeType !== 1 ) {\n\t\treturn;\n\t}\n\n\t// 1. Copy private data: events, handlers, etc.\n\tif ( dataPriv.hasData( src ) ) {\n\t\tpdataOld = dataPriv.access( src );\n\t\tpdataCur = dataPriv.set( dest, pdataOld );\n\t\tevents = pdataOld.events;\n\n\t\tif ( events ) {\n\t\t\tdelete pdataCur.handle;\n\t\t\tpdataCur.events = {};\n\n\t\t\tfor ( type in events ) {\n\t\t\t\tfor ( i = 0, l = events[ type ].length; i < l; i++ ) {\n\t\t\t\t\tjQuery.event.add( dest, type, events[ type ][ i ] );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// 2. Copy user data\n\tif ( dataUser.hasData( src ) ) {\n\t\tudataOld = dataUser.access( src );\n\t\tudataCur = jQuery.extend( {}, udataOld );\n\n\t\tdataUser.set( dest, udataCur );\n\t}\n}\n\n// Fix IE bugs, see support tests\nfunction fixInput( src, dest ) {\n\tvar nodeName = dest.nodeName.toLowerCase();\n\n\t// Fails to persist the checked state of a cloned checkbox or radio button.\n\tif ( nodeName === \"input\" && rcheckableType.test( src.type ) ) {\n\t\tdest.checked = src.checked;\n\n\t// Fails to return the selected option to the default selected state when cloning options\n\t} else if ( nodeName === \"input\" || nodeName === \"textarea\" ) {\n\t\tdest.defaultValue = src.defaultValue;\n\t}\n}\n\nfunction domManip( collection, args, callback, ignored ) {\n\n\t// Flatten any nested arrays\n\targs = concat.apply( [], args );\n\n\tvar fragment, first, scripts, hasScripts, node, doc,\n\t\ti = 0,\n\t\tl = collection.length,\n\t\tiNoClone = l - 1,\n\t\tvalue = args[ 0 ],\n\t\tvalueIsFunction = isFunction( value );\n\n\t// We can't cloneNode fragments that contain checked, in WebKit\n\tif ( valueIsFunction ||\n\t\t\t( l > 1 && typeof value === \"string\" &&\n\t\t\t\t!support.checkClone && rchecked.test( value ) ) ) {\n\t\treturn collection.each( function( index ) {\n\t\t\tvar self = collection.eq( index );\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\targs[ 0 ] = value.call( this, index, self.html() );\n\t\t\t}\n\t\t\tdomManip( self, args, callback, ignored );\n\t\t} );\n\t}\n\n\tif ( l ) {\n\t\tfragment = buildFragment( args, collection[ 0 ].ownerDocument, false, collection, ignored );\n\t\tfirst = fragment.firstChild;\n\n\t\tif ( fragment.childNodes.length === 1 ) {\n\t\t\tfragment = first;\n\t\t}\n\n\t\t// Require either new content or an interest in ignored elements to invoke the callback\n\t\tif ( first || ignored ) {\n\t\t\tscripts = jQuery.map( getAll( fragment, \"script\" ), disableScript );\n\t\t\thasScripts = scripts.length;\n\n\t\t\t// Use the original fragment for the last item\n\t\t\t// instead of the first because it can end up\n\t\t\t// being emptied incorrectly in certain situations (#8070).\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tnode = fragment;\n\n\t\t\t\tif ( i !== iNoClone ) {\n\t\t\t\t\tnode = jQuery.clone( node, true, true );\n\n\t\t\t\t\t// Keep references to cloned scripts for later restoration\n\t\t\t\t\tif ( hasScripts ) {\n\n\t\t\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\t\t\tjQuery.merge( scripts, getAll( node, \"script\" ) );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\tcallback.call( collection[ i ], node, i );\n\t\t\t}\n\n\t\t\tif ( hasScripts ) {\n\t\t\t\tdoc = scripts[ scripts.length - 1 ].ownerDocument;\n\n\t\t\t\t// Reenable scripts\n\t\t\t\tjQuery.map( scripts, restoreScript );\n\n\t\t\t\t// Evaluate executable scripts on first document insertion\n\t\t\t\tfor ( i = 0; i < hasScripts; i++ ) {\n\t\t\t\t\tnode = scripts[ i ];\n\t\t\t\t\tif ( rscriptType.test( node.type || \"\" ) &&\n\t\t\t\t\t\t!dataPriv.access( node, \"globalEval\" ) &&\n\t\t\t\t\t\tjQuery.contains( doc, node ) ) {\n\n\t\t\t\t\t\tif ( node.src && ( node.type || \"\" ).toLowerCase()  !== \"module\" ) {\n\n\t\t\t\t\t\t\t// Optional AJAX dependency, but won't run scripts if not present\n\t\t\t\t\t\t\tif ( jQuery._evalUrl && !node.noModule ) {\n\t\t\t\t\t\t\t\tjQuery._evalUrl( node.src, {\n\t\t\t\t\t\t\t\t\tnonce: node.nonce || node.getAttribute( \"nonce\" )\n\t\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\tDOMEval( node.textContent.replace( rcleanScript, \"\" ), node, doc );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn collection;\n}\n\nfunction remove( elem, selector, keepData ) {\n\tvar node,\n\t\tnodes = selector ? jQuery.filter( selector, elem ) : elem,\n\t\ti = 0;\n\n\tfor ( ; ( node = nodes[ i ] ) != null; i++ ) {\n\t\tif ( !keepData && node.nodeType === 1 ) {\n\t\t\tjQuery.cleanData( getAll( node ) );\n\t\t}\n\n\t\tif ( node.parentNode ) {\n\t\t\tif ( keepData && isAttached( node ) ) {\n\t\t\t\tsetGlobalEval( getAll( node, \"script\" ) );\n\t\t\t}\n\t\t\tnode.parentNode.removeChild( node );\n\t\t}\n\t}\n\n\treturn elem;\n}\n\njQuery.extend( {\n\thtmlPrefilter: function( html ) {\n\t\treturn html.replace( rxhtmlTag, \"<$1></$2>\" );\n\t},\n\n\tclone: function( elem, dataAndEvents, deepDataAndEvents ) {\n\t\tvar i, l, srcElements, destElements,\n\t\t\tclone = elem.cloneNode( true ),\n\t\t\tinPage = isAttached( elem );\n\n\t\t// Fix IE cloning issues\n\t\tif ( !support.noCloneChecked && ( elem.nodeType === 1 || elem.nodeType === 11 ) &&\n\t\t\t\t!jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// We eschew Sizzle here for performance reasons: https://jsperf.com/getall-vs-sizzle/2\n\t\t\tdestElements = getAll( clone );\n\t\t\tsrcElements = getAll( elem );\n\n\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\tfixInput( srcElements[ i ], destElements[ i ] );\n\t\t\t}\n\t\t}\n\n\t\t// Copy the events from the original to the clone\n\t\tif ( dataAndEvents ) {\n\t\t\tif ( deepDataAndEvents ) {\n\t\t\t\tsrcElements = srcElements || getAll( elem );\n\t\t\t\tdestElements = destElements || getAll( clone );\n\n\t\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\t\tcloneCopyEvent( srcElements[ i ], destElements[ i ] );\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tcloneCopyEvent( elem, clone );\n\t\t\t}\n\t\t}\n\n\t\t// Preserve script evaluation history\n\t\tdestElements = getAll( clone, \"script\" );\n\t\tif ( destElements.length > 0 ) {\n\t\t\tsetGlobalEval( destElements, !inPage && getAll( elem, \"script\" ) );\n\t\t}\n\n\t\t// Return the cloned set\n\t\treturn clone;\n\t},\n\n\tcleanData: function( elems ) {\n\t\tvar data, elem, type,\n\t\t\tspecial = jQuery.event.special,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = elems[ i ] ) !== undefined; i++ ) {\n\t\t\tif ( acceptData( elem ) ) {\n\t\t\t\tif ( ( data = elem[ dataPriv.expando ] ) ) {\n\t\t\t\t\tif ( data.events ) {\n\t\t\t\t\t\tfor ( type in data.events ) {\n\t\t\t\t\t\t\tif ( special[ type ] ) {\n\t\t\t\t\t\t\t\tjQuery.event.remove( elem, type );\n\n\t\t\t\t\t\t\t// This is a shortcut to avoid jQuery.event.remove's overhead\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tjQuery.removeEvent( elem, type, data.handle );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataPriv.expando ] = undefined;\n\t\t\t\t}\n\t\t\t\tif ( elem[ dataUser.expando ] ) {\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataUser.expando ] = undefined;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n} );\n\njQuery.fn.extend( {\n\tdetach: function( selector ) {\n\t\treturn remove( this, selector, true );\n\t},\n\n\tremove: function( selector ) {\n\t\treturn remove( this, selector );\n\t},\n\n\ttext: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\treturn value === undefined ?\n\t\t\t\tjQuery.text( this ) :\n\t\t\t\tthis.empty().each( function() {\n\t\t\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\t\t\tthis.textContent = value;\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t}, null, value, arguments.length );\n\t},\n\n\tappend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.appendChild( elem );\n\t\t\t}\n\t\t} );\n\t},\n\n\tprepend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.insertBefore( elem, target.firstChild );\n\t\t\t}\n\t\t} );\n\t},\n\n\tbefore: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this );\n\t\t\t}\n\t\t} );\n\t},\n\n\tafter: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this.nextSibling );\n\t\t\t}\n\t\t} );\n\t},\n\n\tempty: function() {\n\t\tvar elem,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = this[ i ] ) != null; i++ ) {\n\t\t\tif ( elem.nodeType === 1 ) {\n\n\t\t\t\t// Prevent memory leaks\n\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\n\t\t\t\t// Remove any remaining nodes\n\t\t\t\telem.textContent = \"\";\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tclone: function( dataAndEvents, deepDataAndEvents ) {\n\t\tdataAndEvents = dataAndEvents == null ? false : dataAndEvents;\n\t\tdeepDataAndEvents = deepDataAndEvents == null ? dataAndEvents : deepDataAndEvents;\n\n\t\treturn this.map( function() {\n\t\t\treturn jQuery.clone( this, dataAndEvents, deepDataAndEvents );\n\t\t} );\n\t},\n\n\thtml: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\tvar elem = this[ 0 ] || {},\n\t\t\t\ti = 0,\n\t\t\t\tl = this.length;\n\n\t\t\tif ( value === undefined && elem.nodeType === 1 ) {\n\t\t\t\treturn elem.innerHTML;\n\t\t\t}\n\n\t\t\t// See if we can take a shortcut and just use innerHTML\n\t\t\tif ( typeof value === \"string\" && !rnoInnerhtml.test( value ) &&\n\t\t\t\t!wrapMap[ ( rtagName.exec( value ) || [ \"\", \"\" ] )[ 1 ].toLowerCase() ] ) {\n\n\t\t\t\tvalue = jQuery.htmlPrefilter( value );\n\n\t\t\t\ttry {\n\t\t\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\t\t\telem = this[ i ] || {};\n\n\t\t\t\t\t\t// Remove element nodes and prevent memory leaks\n\t\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\t\t\t\t\t\t\telem.innerHTML = value;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\telem = 0;\n\n\t\t\t\t// If using innerHTML throws an exception, use the fallback method\n\t\t\t\t} catch ( e ) {}\n\t\t\t}\n\n\t\t\tif ( elem ) {\n\t\t\t\tthis.empty().append( value );\n\t\t\t}\n\t\t}, null, value, arguments.length );\n\t},\n\n\treplaceWith: function() {\n\t\tvar ignored = [];\n\n\t\t// Make the changes, replacing each non-ignored context element with the new content\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tvar parent = this.parentNode;\n\n\t\t\tif ( jQuery.inArray( this, ignored ) < 0 ) {\n\t\t\t\tjQuery.cleanData( getAll( this ) );\n\t\t\t\tif ( parent ) {\n\t\t\t\t\tparent.replaceChild( elem, this );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Force callback invocation\n\t\t}, ignored );\n\t}\n} );\n\njQuery.each( {\n\tappendTo: \"append\",\n\tprependTo: \"prepend\",\n\tinsertBefore: \"before\",\n\tinsertAfter: \"after\",\n\treplaceAll: \"replaceWith\"\n}, function( name, original ) {\n\tjQuery.fn[ name ] = function( selector ) {\n\t\tvar elems,\n\t\t\tret = [],\n\t\t\tinsert = jQuery( selector ),\n\t\t\tlast = insert.length - 1,\n\t\t\ti = 0;\n\n\t\tfor ( ; i <= last; i++ ) {\n\t\t\telems = i === last ? this : this.clone( true );\n\t\t\tjQuery( insert[ i ] )[ original ]( elems );\n\n\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t// .get() because push.apply(_, arraylike) throws on ancient WebKit\n\t\t\tpush.apply( ret, elems.get() );\n\t\t}\n\n\t\treturn this.pushStack( ret );\n\t};\n} );\nvar rnumnonpx = new RegExp( \"^(\" + pnum + \")(?!px)[a-z%]+$\", \"i\" );\n\nvar getStyles = function( elem ) {\n\n\t\t// Support: IE <=11 only, Firefox <=30 (#15098, #14150)\n\t\t// IE throws on elements created in popups\n\t\t// FF meanwhile throws on frame elements through \"defaultView.getComputedStyle\"\n\t\tvar view = elem.ownerDocument.defaultView;\n\n\t\tif ( !view || !view.opener ) {\n\t\t\tview = window;\n\t\t}\n\n\t\treturn view.getComputedStyle( elem );\n\t};\n\nvar rboxStyle = new RegExp( cssExpand.join( \"|\" ), \"i\" );\n\n\n\n( function() {\n\n\t// Executing both pixelPosition & boxSizingReliable tests require only one layout\n\t// so they're executed at the same time to save the second computation.\n\tfunction computeStyleTests() {\n\n\t\t// This is a singleton, we need to execute it only once\n\t\tif ( !div ) {\n\t\t\treturn;\n\t\t}\n\n\t\tcontainer.style.cssText = \"position:absolute;left:-11111px;width:60px;\" +\n\t\t\t\"margin-top:1px;padding:0;border:0\";\n\t\tdiv.style.cssText =\n\t\t\t\"position:relative;display:block;box-sizing:border-box;overflow:scroll;\" +\n\t\t\t\"margin:auto;border:1px;padding:1px;\" +\n\t\t\t\"width:60%;top:1%\";\n\t\tdocumentElement.appendChild( container ).appendChild( div );\n\n\t\tvar divStyle = window.getComputedStyle( div );\n\t\tpixelPositionVal = divStyle.top !== \"1%\";\n\n\t\t// Support: Android 4.0 - 4.3 only, Firefox <=3 - 44\n\t\treliableMarginLeftVal = roundPixelMeasures( divStyle.marginLeft ) === 12;\n\n\t\t// Support: Android 4.0 - 4.3 only, Safari <=9.1 - 10.1, iOS <=7.0 - 9.3\n\t\t// Some styles come back with percentage values, even though they shouldn't\n\t\tdiv.style.right = \"60%\";\n\t\tpixelBoxStylesVal = roundPixelMeasures( divStyle.right ) === 36;\n\n\t\t// Support: IE 9 - 11 only\n\t\t// Detect misreporting of content dimensions for box-sizing:border-box elements\n\t\tboxSizingReliableVal = roundPixelMeasures( divStyle.width ) === 36;\n\n\t\t// Support: IE 9 only\n\t\t// Detect overflow:scroll screwiness (gh-3699)\n\t\t// Support: Chrome <=64\n\t\t// Don't get tricked when zoom affects offsetWidth (gh-4029)\n\t\tdiv.style.position = \"absolute\";\n\t\tscrollboxSizeVal = roundPixelMeasures( div.offsetWidth / 3 ) === 12;\n\n\t\tdocumentElement.removeChild( container );\n\n\t\t// Nullify the div so it wouldn't be stored in the memory and\n\t\t// it will also be a sign that checks already performed\n\t\tdiv = null;\n\t}\n\n\tfunction roundPixelMeasures( measure ) {\n\t\treturn Math.round( parseFloat( measure ) );\n\t}\n\n\tvar pixelPositionVal, boxSizingReliableVal, scrollboxSizeVal, pixelBoxStylesVal,\n\t\treliableMarginLeftVal,\n\t\tcontainer = document.createElement( \"div\" ),\n\t\tdiv = document.createElement( \"div\" );\n\n\t// Finish early in limited (non-browser) environments\n\tif ( !div.style ) {\n\t\treturn;\n\t}\n\n\t// Support: IE <=9 - 11 only\n\t// Style of cloned element affects source element cloned (#8908)\n\tdiv.style.backgroundClip = \"content-box\";\n\tdiv.cloneNode( true ).style.backgroundClip = \"\";\n\tsupport.clearCloneStyle = div.style.backgroundClip === \"content-box\";\n\n\tjQuery.extend( support, {\n\t\tboxSizingReliable: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn boxSizingReliableVal;\n\t\t},\n\t\tpixelBoxStyles: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelBoxStylesVal;\n\t\t},\n\t\tpixelPosition: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelPositionVal;\n\t\t},\n\t\treliableMarginLeft: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn reliableMarginLeftVal;\n\t\t},\n\t\tscrollboxSize: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn scrollboxSizeVal;\n\t\t}\n\t} );\n} )();\n\n\nfunction curCSS( elem, name, computed ) {\n\tvar width, minWidth, maxWidth, ret,\n\n\t\t// Support: Firefox 51+\n\t\t// Retrieving style before computed somehow\n\t\t// fixes an issue with getting wrong values\n\t\t// on detached elements\n\t\tstyle = elem.style;\n\n\tcomputed = computed || getStyles( elem );\n\n\t// getPropertyValue is needed for:\n\t//   .css('filter') (IE 9 only, #12537)\n\t//   .css('--customProperty) (#3144)\n\tif ( computed ) {\n\t\tret = computed.getPropertyValue( name ) || computed[ name ];\n\n\t\tif ( ret === \"\" && !isAttached( elem ) ) {\n\t\t\tret = jQuery.style( elem, name );\n\t\t}\n\n\t\t// A tribute to the \"awesome hack by Dean Edwards\"\n\t\t// Android Browser returns percentage for some values,\n\t\t// but width seems to be reliably pixels.\n\t\t// This is against the CSSOM draft spec:\n\t\t// https://drafts.csswg.org/cssom/#resolved-values\n\t\tif ( !support.pixelBoxStyles() && rnumnonpx.test( ret ) && rboxStyle.test( name ) ) {\n\n\t\t\t// Remember the original values\n\t\t\twidth = style.width;\n\t\t\tminWidth = style.minWidth;\n\t\t\tmaxWidth = style.maxWidth;\n\n\t\t\t// Put in the new values to get a computed value out\n\t\t\tstyle.minWidth = style.maxWidth = style.width = ret;\n\t\t\tret = computed.width;\n\n\t\t\t// Revert the changed values\n\t\t\tstyle.width = width;\n\t\t\tstyle.minWidth = minWidth;\n\t\t\tstyle.maxWidth = maxWidth;\n\t\t}\n\t}\n\n\treturn ret !== undefined ?\n\n\t\t// Support: IE <=9 - 11 only\n\t\t// IE returns zIndex value as an integer.\n\t\tret + \"\" :\n\t\tret;\n}\n\n\nfunction addGetHookIf( conditionFn, hookFn ) {\n\n\t// Define the hook, we'll check on the first run if it's really needed.\n\treturn {\n\t\tget: function() {\n\t\t\tif ( conditionFn() ) {\n\n\t\t\t\t// Hook not needed (or it's not possible to use it due\n\t\t\t\t// to missing dependency), remove it.\n\t\t\t\tdelete this.get;\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Hook needed; redefine it so that the support test is not executed again.\n\t\t\treturn ( this.get = hookFn ).apply( this, arguments );\n\t\t}\n\t};\n}\n\n\nvar cssPrefixes = [ \"Webkit\", \"Moz\", \"ms\" ],\n\temptyStyle = document.createElement( \"div\" ).style,\n\tvendorProps = {};\n\n// Return a vendor-prefixed property or undefined\nfunction vendorPropName( name ) {\n\n\t// Check for vendor prefixed names\n\tvar capName = name[ 0 ].toUpperCase() + name.slice( 1 ),\n\t\ti = cssPrefixes.length;\n\n\twhile ( i-- ) {\n\t\tname = cssPrefixes[ i ] + capName;\n\t\tif ( name in emptyStyle ) {\n\t\t\treturn name;\n\t\t}\n\t}\n}\n\n// Return a potentially-mapped jQuery.cssProps or vendor prefixed property\nfunction finalPropName( name ) {\n\tvar final = jQuery.cssProps[ name ] || vendorProps[ name ];\n\n\tif ( final ) {\n\t\treturn final;\n\t}\n\tif ( name in emptyStyle ) {\n\t\treturn name;\n\t}\n\treturn vendorProps[ name ] = vendorPropName( name ) || name;\n}\n\n\nvar\n\n\t// Swappable if display is none or starts with table\n\t// except \"table\", \"table-cell\", or \"table-caption\"\n\t// See here for display values: https://developer.mozilla.org/en-US/docs/CSS/display\n\trdisplayswap = /^(none|table(?!-c[ea]).+)/,\n\trcustomProp = /^--/,\n\tcssShow = { position: \"absolute\", visibility: \"hidden\", display: \"block\" },\n\tcssNormalTransform = {\n\t\tletterSpacing: \"0\",\n\t\tfontWeight: \"400\"\n\t};\n\nfunction setPositiveNumber( elem, value, subtract ) {\n\n\t// Any relative (+/-) values have already been\n\t// normalized at this point\n\tvar matches = rcssNum.exec( value );\n\treturn matches ?\n\n\t\t// Guard against undefined \"subtract\", e.g., when used as in cssHooks\n\t\tMath.max( 0, matches[ 2 ] - ( subtract || 0 ) ) + ( matches[ 3 ] || \"px\" ) :\n\t\tvalue;\n}\n\nfunction boxModelAdjustment( elem, dimension, box, isBorderBox, styles, computedVal ) {\n\tvar i = dimension === \"width\" ? 1 : 0,\n\t\textra = 0,\n\t\tdelta = 0;\n\n\t// Adjustment may not be necessary\n\tif ( box === ( isBorderBox ? \"border\" : \"content\" ) ) {\n\t\treturn 0;\n\t}\n\n\tfor ( ; i < 4; i += 2 ) {\n\n\t\t// Both box models exclude margin\n\t\tif ( box === \"margin\" ) {\n\t\t\tdelta += jQuery.css( elem, box + cssExpand[ i ], true, styles );\n\t\t}\n\n\t\t// If we get here with a content-box, we're seeking \"padding\" or \"border\" or \"margin\"\n\t\tif ( !isBorderBox ) {\n\n\t\t\t// Add padding\n\t\t\tdelta += jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\n\t\t\t// For \"border\" or \"margin\", add border\n\t\t\tif ( box !== \"padding\" ) {\n\t\t\t\tdelta += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\n\t\t\t// But still keep track of it otherwise\n\t\t\t} else {\n\t\t\t\textra += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\n\t\t// If we get here with a border-box (content + padding + border), we're seeking \"content\" or\n\t\t// \"padding\" or \"margin\"\n\t\t} else {\n\n\t\t\t// For \"content\", subtract padding\n\t\t\tif ( box === \"content\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\t\t\t}\n\n\t\t\t// For \"content\" or \"padding\", subtract border\n\t\t\tif ( box !== \"margin\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Account for positive content-box scroll gutter when requested by providing computedVal\n\tif ( !isBorderBox && computedVal >= 0 ) {\n\n\t\t// offsetWidth/offsetHeight is a rounded sum of content, padding, scroll gutter, and border\n\t\t// Assuming integer scroll gutter, subtract the rest and round down\n\t\tdelta += Math.max( 0, Math.ceil(\n\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\tcomputedVal -\n\t\t\tdelta -\n\t\t\textra -\n\t\t\t0.5\n\n\t\t// If offsetWidth/offsetHeight is unknown, then we can't determine content-box scroll gutter\n\t\t// Use an explicit zero to avoid NaN (gh-3964)\n\t\t) ) || 0;\n\t}\n\n\treturn delta;\n}\n\nfunction getWidthOrHeight( elem, dimension, extra ) {\n\n\t// Start with computed style\n\tvar styles = getStyles( elem ),\n\n\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-4322).\n\t\t// Fake content-box until we know it's needed to know the true value.\n\t\tboxSizingNeeded = !support.boxSizingReliable() || extra,\n\t\tisBorderBox = boxSizingNeeded &&\n\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\tvalueIsBorderBox = isBorderBox,\n\n\t\tval = curCSS( elem, dimension, styles ),\n\t\toffsetProp = \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 );\n\n\t// Support: Firefox <=54\n\t// Return a confounding non-pixel value or feign ignorance, as appropriate.\n\tif ( rnumnonpx.test( val ) ) {\n\t\tif ( !extra ) {\n\t\t\treturn val;\n\t\t}\n\t\tval = \"auto\";\n\t}\n\n\n\t// Fall back to offsetWidth/offsetHeight when value is \"auto\"\n\t// This happens for inline elements with no explicit setting (gh-3571)\n\t// Support: Android <=4.1 - 4.3 only\n\t// Also use offsetWidth/offsetHeight for misreported inline dimensions (gh-3602)\n\t// Support: IE 9-11 only\n\t// Also use offsetWidth/offsetHeight for when box sizing is unreliable\n\t// We use getClientRects() to check for hidden/disconnected.\n\t// In those cases, the computed value can be trusted to be border-box\n\tif ( ( !support.boxSizingReliable() && isBorderBox ||\n\t\tval === \"auto\" ||\n\t\t!parseFloat( val ) && jQuery.css( elem, \"display\", false, styles ) === \"inline\" ) &&\n\t\telem.getClientRects().length ) {\n\n\t\tisBorderBox = jQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\";\n\n\t\t// Where available, offsetWidth/offsetHeight approximate border box dimensions.\n\t\t// Where not available (e.g., SVG), assume unreliable box-sizing and interpret the\n\t\t// retrieved value as a content box dimension.\n\t\tvalueIsBorderBox = offsetProp in elem;\n\t\tif ( valueIsBorderBox ) {\n\t\t\tval = elem[ offsetProp ];\n\t\t}\n\t}\n\n\t// Normalize \"\" and auto\n\tval = parseFloat( val ) || 0;\n\n\t// Adjust for the element's box model\n\treturn ( val +\n\t\tboxModelAdjustment(\n\t\t\telem,\n\t\t\tdimension,\n\t\t\textra || ( isBorderBox ? \"border\" : \"content\" ),\n\t\t\tvalueIsBorderBox,\n\t\t\tstyles,\n\n\t\t\t// Provide the current computed size to request scroll gutter calculation (gh-3589)\n\t\t\tval\n\t\t)\n\t) + \"px\";\n}\n\njQuery.extend( {\n\n\t// Add in style property hooks for overriding the default\n\t// behavior of getting and setting a style property\n\tcssHooks: {\n\t\topacity: {\n\t\t\tget: function( elem, computed ) {\n\t\t\t\tif ( computed ) {\n\n\t\t\t\t\t// We should always get a number back from opacity\n\t\t\t\t\tvar ret = curCSS( elem, \"opacity\" );\n\t\t\t\t\treturn ret === \"\" ? \"1\" : ret;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\t// Don't automatically add \"px\" to these possibly-unitless properties\n\tcssNumber: {\n\t\t\"animationIterationCount\": true,\n\t\t\"columnCount\": true,\n\t\t\"fillOpacity\": true,\n\t\t\"flexGrow\": true,\n\t\t\"flexShrink\": true,\n\t\t\"fontWeight\": true,\n\t\t\"gridArea\": true,\n\t\t\"gridColumn\": true,\n\t\t\"gridColumnEnd\": true,\n\t\t\"gridColumnStart\": true,\n\t\t\"gridRow\": true,\n\t\t\"gridRowEnd\": true,\n\t\t\"gridRowStart\": true,\n\t\t\"lineHeight\": true,\n\t\t\"opacity\": true,\n\t\t\"order\": true,\n\t\t\"orphans\": true,\n\t\t\"widows\": true,\n\t\t\"zIndex\": true,\n\t\t\"zoom\": true\n\t},\n\n\t// Add in properties whose names you wish to fix before\n\t// setting or getting the value\n\tcssProps: {},\n\n\t// Get and set the style property on a DOM Node\n\tstyle: function( elem, name, value, extra ) {\n\n\t\t// Don't set styles on text and comment nodes\n\t\tif ( !elem || elem.nodeType === 3 || elem.nodeType === 8 || !elem.style ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Make sure that we're working with the right name\n\t\tvar ret, type, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name ),\n\t\t\tstyle = elem.style;\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to query the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Gets hook for the prefixed version, then unprefixed version\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// Check if we're setting a value\n\t\tif ( value !== undefined ) {\n\t\t\ttype = typeof value;\n\n\t\t\t// Convert \"+=\" or \"-=\" to relative numbers (#7345)\n\t\t\tif ( type === \"string\" && ( ret = rcssNum.exec( value ) ) && ret[ 1 ] ) {\n\t\t\t\tvalue = adjustCSS( elem, name, ret );\n\n\t\t\t\t// Fixes bug #9237\n\t\t\t\ttype = \"number\";\n\t\t\t}\n\n\t\t\t// Make sure that null and NaN values aren't set (#7116)\n\t\t\tif ( value == null || value !== value ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// If a number was passed in, add the unit (except for certain CSS properties)\n\t\t\t// The isCustomProp check can be removed in jQuery 4.0 when we only auto-append\n\t\t\t// \"px\" to a few hardcoded values.\n\t\t\tif ( type === \"number\" && !isCustomProp ) {\n\t\t\t\tvalue += ret && ret[ 3 ] || ( jQuery.cssNumber[ origName ] ? \"\" : \"px\" );\n\t\t\t}\n\n\t\t\t// background-* props affect original clone's values\n\t\t\tif ( !support.clearCloneStyle && value === \"\" && name.indexOf( \"background\" ) === 0 ) {\n\t\t\t\tstyle[ name ] = \"inherit\";\n\t\t\t}\n\n\t\t\t// If a hook was provided, use that value, otherwise just set the specified value\n\t\t\tif ( !hooks || !( \"set\" in hooks ) ||\n\t\t\t\t( value = hooks.set( elem, value, extra ) ) !== undefined ) {\n\n\t\t\t\tif ( isCustomProp ) {\n\t\t\t\t\tstyle.setProperty( name, value );\n\t\t\t\t} else {\n\t\t\t\t\tstyle[ name ] = value;\n\t\t\t\t}\n\t\t\t}\n\n\t\t} else {\n\n\t\t\t// If a hook was provided get the non-computed value from there\n\t\t\tif ( hooks && \"get\" in hooks &&\n\t\t\t\t( ret = hooks.get( elem, false, extra ) ) !== undefined ) {\n\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\t// Otherwise just get the value from the style object\n\t\t\treturn style[ name ];\n\t\t}\n\t},\n\n\tcss: function( elem, name, extra, styles ) {\n\t\tvar val, num, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name );\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to modify the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Try prefixed name followed by the unprefixed name\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// If a hook was provided get the computed value from there\n\t\tif ( hooks && \"get\" in hooks ) {\n\t\t\tval = hooks.get( elem, true, extra );\n\t\t}\n\n\t\t// Otherwise, if a way to get the computed value exists, use that\n\t\tif ( val === undefined ) {\n\t\t\tval = curCSS( elem, name, styles );\n\t\t}\n\n\t\t// Convert \"normal\" to computed value\n\t\tif ( val === \"normal\" && name in cssNormalTransform ) {\n\t\t\tval = cssNormalTransform[ name ];\n\t\t}\n\n\t\t// Make numeric if forced or a qualifier was provided and val looks numeric\n\t\tif ( extra === \"\" || extra ) {\n\t\t\tnum = parseFloat( val );\n\t\t\treturn extra === true || isFinite( num ) ? num || 0 : val;\n\t\t}\n\n\t\treturn val;\n\t}\n} );\n\njQuery.each( [ \"height\", \"width\" ], function( i, dimension ) {\n\tjQuery.cssHooks[ dimension ] = {\n\t\tget: function( elem, computed, extra ) {\n\t\t\tif ( computed ) {\n\n\t\t\t\t// Certain elements can have dimension info if we invisibly show them\n\t\t\t\t// but it must have a current display style that would benefit\n\t\t\t\treturn rdisplayswap.test( jQuery.css( elem, \"display\" ) ) &&\n\n\t\t\t\t\t// Support: Safari 8+\n\t\t\t\t\t// Table columns in Safari have non-zero offsetWidth & zero\n\t\t\t\t\t// getBoundingClientRect().width unless display is changed.\n\t\t\t\t\t// Support: IE <=11 only\n\t\t\t\t\t// Running getBoundingClientRect on a disconnected node\n\t\t\t\t\t// in IE throws an error.\n\t\t\t\t\t( !elem.getClientRects().length || !elem.getBoundingClientRect().width ) ?\n\t\t\t\t\t\tswap( elem, cssShow, function() {\n\t\t\t\t\t\t\treturn getWidthOrHeight( elem, dimension, extra );\n\t\t\t\t\t\t} ) :\n\t\t\t\t\t\tgetWidthOrHeight( elem, dimension, extra );\n\t\t\t}\n\t\t},\n\n\t\tset: function( elem, value, extra ) {\n\t\t\tvar matches,\n\t\t\t\tstyles = getStyles( elem ),\n\n\t\t\t\t// Only read styles.position if the test has a chance to fail\n\t\t\t\t// to avoid forcing a reflow.\n\t\t\t\tscrollboxSizeBuggy = !support.scrollboxSize() &&\n\t\t\t\t\tstyles.position === \"absolute\",\n\n\t\t\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-3991)\n\t\t\t\tboxSizingNeeded = scrollboxSizeBuggy || extra,\n\t\t\t\tisBorderBox = boxSizingNeeded &&\n\t\t\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\t\t\tsubtract = extra ?\n\t\t\t\t\tboxModelAdjustment(\n\t\t\t\t\t\telem,\n\t\t\t\t\t\tdimension,\n\t\t\t\t\t\textra,\n\t\t\t\t\t\tisBorderBox,\n\t\t\t\t\t\tstyles\n\t\t\t\t\t) :\n\t\t\t\t\t0;\n\n\t\t\t// Account for unreliable border-box dimensions by comparing offset* to computed and\n\t\t\t// faking a content-box to get border and padding (gh-3699)\n\t\t\tif ( isBorderBox && scrollboxSizeBuggy ) {\n\t\t\t\tsubtract -= Math.ceil(\n\t\t\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\t\t\tparseFloat( styles[ dimension ] ) -\n\t\t\t\t\tboxModelAdjustment( elem, dimension, \"border\", false, styles ) -\n\t\t\t\t\t0.5\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// Convert to pixels if value adjustment is needed\n\t\t\tif ( subtract && ( matches = rcssNum.exec( value ) ) &&\n\t\t\t\t( matches[ 3 ] || \"px\" ) !== \"px\" ) {\n\n\t\t\t\telem.style[ dimension ] = value;\n\t\t\t\tvalue = jQuery.css( elem, dimension );\n\t\t\t}\n\n\t\t\treturn setPositiveNumber( elem, value, subtract );\n\t\t}\n\t};\n} );\n\njQuery.cssHooks.marginLeft = addGetHookIf( support.reliableMarginLeft,\n\tfunction( elem, computed ) {\n\t\tif ( computed ) {\n\t\t\treturn ( parseFloat( curCSS( elem, \"marginLeft\" ) ) ||\n\t\t\t\telem.getBoundingClientRect().left -\n\t\t\t\t\tswap( elem, { marginLeft: 0 }, function() {\n\t\t\t\t\t\treturn elem.getBoundingClientRect().left;\n\t\t\t\t\t} )\n\t\t\t\t) + \"px\";\n\t\t}\n\t}\n);\n\n// These hooks are used by animate to expand properties\njQuery.each( {\n\tmargin: \"\",\n\tpadding: \"\",\n\tborder: \"Width\"\n}, function( prefix, suffix ) {\n\tjQuery.cssHooks[ prefix + suffix ] = {\n\t\texpand: function( value ) {\n\t\t\tvar i = 0,\n\t\t\t\texpanded = {},\n\n\t\t\t\t// Assumes a single number if not a string\n\t\t\t\tparts = typeof value === \"string\" ? value.split( \" \" ) : [ value ];\n\n\t\t\tfor ( ; i < 4; i++ ) {\n\t\t\t\texpanded[ prefix + cssExpand[ i ] + suffix ] =\n\t\t\t\t\tparts[ i ] || parts[ i - 2 ] || parts[ 0 ];\n\t\t\t}\n\n\t\t\treturn expanded;\n\t\t}\n\t};\n\n\tif ( prefix !== \"margin\" ) {\n\t\tjQuery.cssHooks[ prefix + suffix ].set = setPositiveNumber;\n\t}\n} );\n\njQuery.fn.extend( {\n\tcss: function( name, value ) {\n\t\treturn access( this, function( elem, name, value ) {\n\t\t\tvar styles, len,\n\t\t\t\tmap = {},\n\t\t\t\ti = 0;\n\n\t\t\tif ( Array.isArray( name ) ) {\n\t\t\t\tstyles = getStyles( elem );\n\t\t\t\tlen = name.length;\n\n\t\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\t\tmap[ name[ i ] ] = jQuery.css( elem, name[ i ], false, styles );\n\t\t\t\t}\n\n\t\t\t\treturn map;\n\t\t\t}\n\n\t\t\treturn value !== undefined ?\n\t\t\t\tjQuery.style( elem, name, value ) :\n\t\t\t\tjQuery.css( elem, name );\n\t\t}, name, value, arguments.length > 1 );\n\t}\n} );\n\n\n// Based off of the plugin by Clint Helfers, with permission.\n// https://web.archive.org/web/20100324014747/http://blindsignals.com/index.php/2009/07/jquery-delay/\njQuery.fn.delay = function( time, type ) {\n\ttime = jQuery.fx ? jQuery.fx.speeds[ time ] || time : time;\n\ttype = type || \"fx\";\n\n\treturn this.queue( type, function( next, hooks ) {\n\t\tvar timeout = window.setTimeout( next, time );\n\t\thooks.stop = function() {\n\t\t\twindow.clearTimeout( timeout );\n\t\t};\n\t} );\n};\n\n\n( function() {\n\tvar input = document.createElement( \"input\" ),\n\t\tselect = document.createElement( \"select\" ),\n\t\topt = select.appendChild( document.createElement( \"option\" ) );\n\n\tinput.type = \"checkbox\";\n\n\t// Support: Android <=4.3 only\n\t// Default value for a checkbox should be \"on\"\n\tsupport.checkOn = input.value !== \"\";\n\n\t// Support: IE <=11 only\n\t// Must access selectedIndex to make default options select\n\tsupport.optSelected = opt.selected;\n\n\t// Support: IE <=11 only\n\t// An input loses its value after becoming a radio\n\tinput = document.createElement( \"input\" );\n\tinput.value = \"t\";\n\tinput.type = \"radio\";\n\tsupport.radioValue = input.value === \"t\";\n} )();\n\n\nvar boolHook,\n\tattrHandle = jQuery.expr.attrHandle;\n\njQuery.fn.extend( {\n\tattr: function( name, value ) {\n\t\treturn access( this, jQuery.attr, name, value, arguments.length > 1 );\n\t},\n\n\tremoveAttr: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.removeAttr( this, name );\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tattr: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set attributes on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Fallback to prop when attributes are not supported\n\t\tif ( typeof elem.getAttribute === \"undefined\" ) {\n\t\t\treturn jQuery.prop( elem, name, value );\n\t\t}\n\n\t\t// Attribute hooks are determined by the lowercase version\n\t\t// Grab necessary hook if one is defined\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\t\t\thooks = jQuery.attrHooks[ name.toLowerCase() ] ||\n\t\t\t\t( jQuery.expr.match.bool.test( name ) ? boolHook : undefined );\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( value === null ) {\n\t\t\t\tjQuery.removeAttr( elem, name );\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\telem.setAttribute( name, value + \"\" );\n\t\t\treturn value;\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\tret = jQuery.find.attr( elem, name );\n\n\t\t// Non-existent attributes return null, we normalize to undefined\n\t\treturn ret == null ? undefined : ret;\n\t},\n\n\tattrHooks: {\n\t\ttype: {\n\t\t\tset: function( elem, value ) {\n\t\t\t\tif ( !support.radioValue && value === \"radio\" &&\n\t\t\t\t\tnodeName( elem, \"input\" ) ) {\n\t\t\t\t\tvar val = elem.value;\n\t\t\t\t\telem.setAttribute( \"type\", value );\n\t\t\t\t\tif ( val ) {\n\t\t\t\t\t\telem.value = val;\n\t\t\t\t\t}\n\t\t\t\t\treturn value;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\tremoveAttr: function( elem, value ) {\n\t\tvar name,\n\t\t\ti = 0,\n\n\t\t\t// Attribute names can contain non-HTML whitespace characters\n\t\t\t// https://html.spec.whatwg.org/multipage/syntax.html#attributes-2\n\t\t\tattrNames = value && value.match( rnothtmlwhite );\n\n\t\tif ( attrNames && elem.nodeType === 1 ) {\n\t\t\twhile ( ( name = attrNames[ i++ ] ) ) {\n\t\t\t\telem.removeAttribute( name );\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Hooks for boolean attributes\nboolHook = {\n\tset: function( elem, value, name ) {\n\t\tif ( value === false ) {\n\n\t\t\t// Remove boolean attributes when set to false\n\t\t\tjQuery.removeAttr( elem, name );\n\t\t} else {\n\t\t\telem.setAttribute( name, name );\n\t\t}\n\t\treturn name;\n\t}\n};\n\njQuery.each( jQuery.expr.match.bool.source.match( /\\w+/g ), function( i, name ) {\n\tvar getter = attrHandle[ name ] || jQuery.find.attr;\n\n\tattrHandle[ name ] = function( elem, name, isXML ) {\n\t\tvar ret, handle,\n\t\t\tlowercaseName = name.toLowerCase();\n\n\t\tif ( !isXML ) {\n\n\t\t\t// Avoid an infinite loop by temporarily removing this function from the getter\n\t\t\thandle = attrHandle[ lowercaseName ];\n\t\t\tattrHandle[ lowercaseName ] = ret;\n\t\t\tret = getter( elem, name, isXML ) != null ?\n\t\t\t\tlowercaseName :\n\t\t\t\tnull;\n\t\t\tattrHandle[ lowercaseName ] = handle;\n\t\t}\n\t\treturn ret;\n\t};\n} );\n\n\n\n\nvar rfocusable = /^(?:input|select|textarea|button)$/i,\n\trclickable = /^(?:a|area)$/i;\n\njQuery.fn.extend( {\n\tprop: function( name, value ) {\n\t\treturn access( this, jQuery.prop, name, value, arguments.length > 1 );\n\t},\n\n\tremoveProp: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tdelete this[ jQuery.propFix[ name ] || name ];\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tprop: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set properties on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// Fix name and attach hooks\n\t\t\tname = jQuery.propFix[ name ] || name;\n\t\t\thooks = jQuery.propHooks[ name ];\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\treturn ( elem[ name ] = value );\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\treturn elem[ name ];\n\t},\n\n\tpropHooks: {\n\t\ttabIndex: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\t// Support: IE <=9 - 11 only\n\t\t\t\t// elem.tabIndex doesn't always return the\n\t\t\t\t// correct value when it hasn't been explicitly set\n\t\t\t\t// https://web.archive.org/web/20141116233347/http://fluidproject.org/blog/2008/01/09/getting-setting-and-removing-tabindex-values-with-javascript/\n\t\t\t\t// Use proper attribute retrieval(#12072)\n\t\t\t\tvar tabindex = jQuery.find.attr( elem, \"tabindex\" );\n\n\t\t\t\tif ( tabindex ) {\n\t\t\t\t\treturn parseInt( tabindex, 10 );\n\t\t\t\t}\n\n\t\t\t\tif (\n\t\t\t\t\trfocusable.test( elem.nodeName ) ||\n\t\t\t\t\trclickable.test( elem.nodeName ) &&\n\t\t\t\t\telem.href\n\t\t\t\t) {\n\t\t\t\t\treturn 0;\n\t\t\t\t}\n\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t},\n\n\tpropFix: {\n\t\t\"for\": \"htmlFor\",\n\t\t\"class\": \"className\"\n\t}\n} );\n\n// Support: IE <=11 only\n// Accessing the selectedIndex property\n// forces the browser to respect setting selected\n// on the option\n// The getter ensures a default option is selected\n// when in an optgroup\n// eslint rule \"no-unused-expressions\" is disabled for this code\n// since it considers such accessions noop\nif ( !support.optSelected ) {\n\tjQuery.propHooks.selected = {\n\t\tget: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent && parent.parentNode ) {\n\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t}\n\t\t\treturn null;\n\t\t},\n\t\tset: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent ) {\n\t\t\t\tparent.selectedIndex;\n\n\t\t\t\tif ( parent.parentNode ) {\n\t\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t};\n}\n\njQuery.each( [\n\t\"tabIndex\",\n\t\"readOnly\",\n\t\"maxLength\",\n\t\"cellSpacing\",\n\t\"cellPadding\",\n\t\"rowSpan\",\n\t\"colSpan\",\n\t\"useMap\",\n\t\"frameBorder\",\n\t\"contentEditable\"\n], function() {\n\tjQuery.propFix[ this.toLowerCase() ] = this;\n} );\n\n\n\n\n\t// Strip and collapse whitespace according to HTML spec\n\t// https://infra.spec.whatwg.org/#strip-and-collapse-ascii-whitespace\n\tfunction stripAndCollapse( value ) {\n\t\tvar tokens = value.match( rnothtmlwhite ) || [];\n\t\treturn tokens.join( \" \" );\n\t}\n\n\nfunction getClass( elem ) {\n\treturn elem.getAttribute && elem.getAttribute( \"class\" ) || \"\";\n}\n\nfunction classesToArray( value ) {\n\tif ( Array.isArray( value ) ) {\n\t\treturn value;\n\t}\n\tif ( typeof value === \"string\" ) {\n\t\treturn value.match( rnothtmlwhite ) || [];\n\t}\n\treturn [];\n}\n\njQuery.fn.extend( {\n\taddClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).addClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\t\t\t\t\t\tif ( cur.indexOf( \" \" + clazz + \" \" ) < 0 ) {\n\t\t\t\t\t\t\tcur += clazz + \" \";\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tremoveClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).removeClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tif ( !arguments.length ) {\n\t\t\treturn this.attr( \"class\", \"\" );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\n\t\t\t\t// This expression is here for better compressibility (see addClass)\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\n\t\t\t\t\t\t// Remove *all* instances\n\t\t\t\t\t\twhile ( cur.indexOf( \" \" + clazz + \" \" ) > -1 ) {\n\t\t\t\t\t\t\tcur = cur.replace( \" \" + clazz + \" \", \" \" );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\ttoggleClass: function( value, stateVal ) {\n\t\tvar type = typeof value,\n\t\t\tisValidValue = type === \"string\" || Array.isArray( value );\n\n\t\tif ( typeof stateVal === \"boolean\" && isValidValue ) {\n\t\t\treturn stateVal ? this.addClass( value ) : this.removeClass( value );\n\t\t}\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).toggleClass(\n\t\t\t\t\tvalue.call( this, i, getClass( this ), stateVal ),\n\t\t\t\t\tstateVal\n\t\t\t\t);\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar className, i, self, classNames;\n\n\t\t\tif ( isValidValue ) {\n\n\t\t\t\t// Toggle individual class names\n\t\t\t\ti = 0;\n\t\t\t\tself = jQuery( this );\n\t\t\t\tclassNames = classesToArray( value );\n\n\t\t\t\twhile ( ( className = classNames[ i++ ] ) ) {\n\n\t\t\t\t\t// Check each className given, space separated list\n\t\t\t\t\tif ( self.hasClass( className ) ) {\n\t\t\t\t\t\tself.removeClass( className );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tself.addClass( className );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t// Toggle whole class name\n\t\t\t} else if ( value === undefined || type === \"boolean\" ) {\n\t\t\t\tclassName = getClass( this );\n\t\t\t\tif ( className ) {\n\n\t\t\t\t\t// Store className if set\n\t\t\t\t\tdataPriv.set( this, \"__className__\", className );\n\t\t\t\t}\n\n\t\t\t\t// If the element has a class name or if we're passed `false`,\n\t\t\t\t// then remove the whole classname (if there was one, the above saved it).\n\t\t\t\t// Otherwise bring back whatever was previously saved (if anything),\n\t\t\t\t// falling back to the empty string if nothing was stored.\n\t\t\t\tif ( this.setAttribute ) {\n\t\t\t\t\tthis.setAttribute( \"class\",\n\t\t\t\t\t\tclassName || value === false ?\n\t\t\t\t\t\t\"\" :\n\t\t\t\t\t\tdataPriv.get( this, \"__className__\" ) || \"\"\n\t\t\t\t\t);\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\thasClass: function( selector ) {\n\t\tvar className, elem,\n\t\t\ti = 0;\n\n\t\tclassName = \" \" + selector + \" \";\n\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\tif ( elem.nodeType === 1 &&\n\t\t\t\t( \" \" + stripAndCollapse( getClass( elem ) ) + \" \" ).indexOf( className ) > -1 ) {\n\t\t\t\t\treturn true;\n\t\t\t}\n\t\t}\n\n\t\treturn false;\n\t}\n} );\n\n\n\n\nvar rreturn = /\\r/g;\n\njQuery.fn.extend( {\n\tval: function( value ) {\n\t\tvar hooks, ret, valueIsFunction,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !arguments.length ) {\n\t\t\tif ( elem ) {\n\t\t\t\thooks = jQuery.valHooks[ elem.type ] ||\n\t\t\t\t\tjQuery.valHooks[ elem.nodeName.toLowerCase() ];\n\n\t\t\t\tif ( hooks &&\n\t\t\t\t\t\"get\" in hooks &&\n\t\t\t\t\t( ret = hooks.get( elem, \"value\" ) ) !== undefined\n\t\t\t\t) {\n\t\t\t\t\treturn ret;\n\t\t\t\t}\n\n\t\t\t\tret = elem.value;\n\n\t\t\t\t// Handle most common string cases\n\t\t\t\tif ( typeof ret === \"string\" ) {\n\t\t\t\t\treturn ret.replace( rreturn, \"\" );\n\t\t\t\t}\n\n\t\t\t\t// Handle cases where value is null/undef or number\n\t\t\t\treturn ret == null ? \"\" : ret;\n\t\t\t}\n\n\t\t\treturn;\n\t\t}\n\n\t\tvalueIsFunction = isFunction( value );\n\n\t\treturn this.each( function( i ) {\n\t\t\tvar val;\n\n\t\t\tif ( this.nodeType !== 1 ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\tval = value.call( this, i, jQuery( this ).val() );\n\t\t\t} else {\n\t\t\t\tval = value;\n\t\t\t}\n\n\t\t\t// Treat null/undefined as \"\"; convert numbers to string\n\t\t\tif ( val == null ) {\n\t\t\t\tval = \"\";\n\n\t\t\t} else if ( typeof val === \"number\" ) {\n\t\t\t\tval += \"\";\n\n\t\t\t} else if ( Array.isArray( val ) ) {\n\t\t\t\tval = jQuery.map( val, function( value ) {\n\t\t\t\t\treturn value == null ? \"\" : value + \"\";\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\thooks = jQuery.valHooks[ this.type ] || jQuery.valHooks[ this.nodeName.toLowerCase() ];\n\n\t\t\t// If set returns undefined, fall back to normal setting\n\t\t\tif ( !hooks || !( \"set\" in hooks ) || hooks.set( this, val, \"value\" ) === undefined ) {\n\t\t\t\tthis.value = val;\n\t\t\t}\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tvalHooks: {\n\t\toption: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\tvar val = jQuery.find.attr( elem, \"value\" );\n\t\t\t\treturn val != null ?\n\t\t\t\t\tval :\n\n\t\t\t\t\t// Support: IE <=10 - 11 only\n\t\t\t\t\t// option.text throws exceptions (#14686, #14858)\n\t\t\t\t\t// Strip and collapse whitespace\n\t\t\t\t\t// https://html.spec.whatwg.org/#strip-and-collapse-whitespace\n\t\t\t\t\tstripAndCollapse( jQuery.text( elem ) );\n\t\t\t}\n\t\t},\n\t\tselect: {\n\t\t\tget: function( elem ) {\n\t\t\t\tvar value, option, i,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tindex = elem.selectedIndex,\n\t\t\t\t\tone = elem.type === \"select-one\",\n\t\t\t\t\tvalues = one ? null : [],\n\t\t\t\t\tmax = one ? index + 1 : options.length;\n\n\t\t\t\tif ( index < 0 ) {\n\t\t\t\t\ti = max;\n\n\t\t\t\t} else {\n\t\t\t\t\ti = one ? index : 0;\n\t\t\t\t}\n\n\t\t\t\t// Loop through all the selected options\n\t\t\t\tfor ( ; i < max; i++ ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t// IE8-9 doesn't update selected after form reset (#2551)\n\t\t\t\t\tif ( ( option.selected || i === index ) &&\n\n\t\t\t\t\t\t\t// Don't return options that are disabled or in a disabled optgroup\n\t\t\t\t\t\t\t!option.disabled &&\n\t\t\t\t\t\t\t( !option.parentNode.disabled ||\n\t\t\t\t\t\t\t\t!nodeName( option.parentNode, \"optgroup\" ) ) ) {\n\n\t\t\t\t\t\t// Get the specific value for the option\n\t\t\t\t\t\tvalue = jQuery( option ).val();\n\n\t\t\t\t\t\t// We don't need an array for one selects\n\t\t\t\t\t\tif ( one ) {\n\t\t\t\t\t\t\treturn value;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Multi-Selects return an array\n\t\t\t\t\t\tvalues.push( value );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn values;\n\t\t\t},\n\n\t\t\tset: function( elem, value ) {\n\t\t\t\tvar optionSet, option,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tvalues = jQuery.makeArray( value ),\n\t\t\t\t\ti = options.length;\n\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t/* eslint-disable no-cond-assign */\n\n\t\t\t\t\tif ( option.selected =\n\t\t\t\t\t\tjQuery.inArray( jQuery.valHooks.option.get( option ), values ) > -1\n\t\t\t\t\t) {\n\t\t\t\t\t\toptionSet = true;\n\t\t\t\t\t}\n\n\t\t\t\t\t/* eslint-enable no-cond-assign */\n\t\t\t\t}\n\n\t\t\t\t// Force browsers to behave consistently when non-matching value is set\n\t\t\t\tif ( !optionSet ) {\n\t\t\t\t\telem.selectedIndex = -1;\n\t\t\t\t}\n\t\t\t\treturn values;\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Radios and checkboxes getter/setter\njQuery.each( [ \"radio\", \"checkbox\" ], function() {\n\tjQuery.valHooks[ this ] = {\n\t\tset: function( elem, value ) {\n\t\t\tif ( Array.isArray( value ) ) {\n\t\t\t\treturn ( elem.checked = jQuery.inArray( jQuery( elem ).val(), value ) > -1 );\n\t\t\t}\n\t\t}\n\t};\n\tif ( !support.checkOn ) {\n\t\tjQuery.valHooks[ this ].get = function( elem ) {\n\t\t\treturn elem.getAttribute( \"value\" ) === null ? \"on\" : elem.value;\n\t\t};\n\t}\n} );\n\n\n\n\n// Return jQuery for attributes-only inclusion\n\n\nsupport.focusin = \"onfocusin\" in window;\n\n\nvar rfocusMorph = /^(?:focusinfocus|focusoutblur)$/,\n\tstopPropagationCallback = function( e ) {\n\t\te.stopPropagation();\n\t};\n\njQuery.extend( jQuery.event, {\n\n\ttrigger: function( event, data, elem, onlyHandlers ) {\n\n\t\tvar i, cur, tmp, bubbleType, ontype, handle, special, lastElement,\n\t\t\teventPath = [ elem || document ],\n\t\t\ttype = hasOwn.call( event, \"type\" ) ? event.type : event,\n\t\t\tnamespaces = hasOwn.call( event, \"namespace\" ) ? event.namespace.split( \".\" ) : [];\n\n\t\tcur = lastElement = tmp = elem = elem || document;\n\n\t\t// Don't do events on text and comment nodes\n\t\tif ( elem.nodeType === 3 || elem.nodeType === 8 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// focus/blur morphs to focusin/out; ensure we're not firing them right now\n\t\tif ( rfocusMorph.test( type + jQuery.event.triggered ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( type.indexOf( \".\" ) > -1 ) {\n\n\t\t\t// Namespaced trigger; create a regexp to match event type in handle()\n\t\t\tnamespaces = type.split( \".\" );\n\t\t\ttype = namespaces.shift();\n\t\t\tnamespaces.sort();\n\t\t}\n\t\tontype = type.indexOf( \":\" ) < 0 && \"on\" + type;\n\n\t\t// Caller can pass in a jQuery.Event object, Object, or just an event type string\n\t\tevent = event[ jQuery.expando ] ?\n\t\t\tevent :\n\t\t\tnew jQuery.Event( type, typeof event === \"object\" && event );\n\n\t\t// Trigger bitmask: & 1 for native handlers; & 2 for jQuery (always true)\n\t\tevent.isTrigger = onlyHandlers ? 2 : 3;\n\t\tevent.namespace = namespaces.join( \".\" );\n\t\tevent.rnamespace = event.namespace ?\n\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" ) :\n\t\t\tnull;\n\n\t\t// Clean up the event in case it is being reused\n\t\tevent.result = undefined;\n\t\tif ( !event.target ) {\n\t\t\tevent.target = elem;\n\t\t}\n\n\t\t// Clone any incoming data and prepend the event, creating the handler arg list\n\t\tdata = data == null ?\n\t\t\t[ event ] :\n\t\t\tjQuery.makeArray( data, [ event ] );\n\n\t\t// Allow special events to draw outside the lines\n\t\tspecial = jQuery.event.special[ type ] || {};\n\t\tif ( !onlyHandlers && special.trigger && special.trigger.apply( elem, data ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine event propagation path in advance, per W3C events spec (#9951)\n\t\t// Bubble up to document, then to window; watch for a global ownerDocument var (#9724)\n\t\tif ( !onlyHandlers && !special.noBubble && !isWindow( elem ) ) {\n\n\t\t\tbubbleType = special.delegateType || type;\n\t\t\tif ( !rfocusMorph.test( bubbleType + type ) ) {\n\t\t\t\tcur = cur.parentNode;\n\t\t\t}\n\t\t\tfor ( ; cur; cur = cur.parentNode ) {\n\t\t\t\teventPath.push( cur );\n\t\t\t\ttmp = cur;\n\t\t\t}\n\n\t\t\t// Only add window if we got to document (e.g., not plain obj or detached DOM)\n\t\t\tif ( tmp === ( elem.ownerDocument || document ) ) {\n\t\t\t\teventPath.push( tmp.defaultView || tmp.parentWindow || window );\n\t\t\t}\n\t\t}\n\n\t\t// Fire handlers on the event path\n\t\ti = 0;\n\t\twhile ( ( cur = eventPath[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tlastElement = cur;\n\t\t\tevent.type = i > 1 ?\n\t\t\t\tbubbleType :\n\t\t\t\tspecial.bindType || type;\n\n\t\t\t// jQuery handler\n\t\t\thandle = ( dataPriv.get( cur, \"events\" ) || {} )[ event.type ] &&\n\t\t\t\tdataPriv.get( cur, \"handle\" );\n\t\t\tif ( handle ) {\n\t\t\t\thandle.apply( cur, data );\n\t\t\t}\n\n\t\t\t// Native handler\n\t\t\thandle = ontype && cur[ ontype ];\n\t\t\tif ( handle && handle.apply && acceptData( cur ) ) {\n\t\t\t\tevent.result = handle.apply( cur, data );\n\t\t\t\tif ( event.result === false ) {\n\t\t\t\t\tevent.preventDefault();\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tevent.type = type;\n\n\t\t// If nobody prevented the default action, do it now\n\t\tif ( !onlyHandlers && !event.isDefaultPrevented() ) {\n\n\t\t\tif ( ( !special._default ||\n\t\t\t\tspecial._default.apply( eventPath.pop(), data ) === false ) &&\n\t\t\t\tacceptData( elem ) ) {\n\n\t\t\t\t// Call a native DOM method on the target with the same name as the event.\n\t\t\t\t// Don't do default actions on window, that's where global variables be (#6170)\n\t\t\t\tif ( ontype && isFunction( elem[ type ] ) && !isWindow( elem ) ) {\n\n\t\t\t\t\t// Don't re-trigger an onFOO event when we call its FOO() method\n\t\t\t\t\ttmp = elem[ ontype ];\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = null;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prevent re-triggering of the same event, since we already bubbled it above\n\t\t\t\t\tjQuery.event.triggered = type;\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.addEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\telem[ type ]();\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.removeEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\tjQuery.event.triggered = undefined;\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = tmp;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\t// Piggyback on a donor event to simulate a different one\n\t// Used only for `focus(in | out)` events\n\tsimulate: function( type, elem, event ) {\n\t\tvar e = jQuery.extend(\n\t\t\tnew jQuery.Event(),\n\t\t\tevent,\n\t\t\t{\n\t\t\t\ttype: type,\n\t\t\t\tisSimulated: true\n\t\t\t}\n\t\t);\n\n\t\tjQuery.event.trigger( e, null, elem );\n\t}\n\n} );\n\njQuery.fn.extend( {\n\n\ttrigger: function( type, data ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.trigger( type, data, this );\n\t\t} );\n\t},\n\ttriggerHandler: function( type, data ) {\n\t\tvar elem = this[ 0 ];\n\t\tif ( elem ) {\n\t\t\treturn jQuery.event.trigger( type, data, elem, true );\n\t\t}\n\t}\n} );\n\n\n// Support: Firefox <=44\n// Firefox doesn't have focus(in | out) events\n// Related ticket - https://bugzilla.mozilla.org/show_bug.cgi?id=687787\n//\n// Support: Chrome <=48 - 49, Safari <=9.0 - 9.1\n// focus(in | out) events fire after focus & blur events,\n// which is spec violation - http://www.w3.org/TR/DOM-Level-3-Events/#events-focusevent-event-order\n// Related ticket - https://bugs.chromium.org/p/chromium/issues/detail?id=449857\nif ( !support.focusin ) {\n\tjQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( orig, fix ) {\n\n\t\t// Attach a single capturing handler on the document while someone wants focusin/focusout\n\t\tvar handler = function( event ) {\n\t\t\tjQuery.event.simulate( fix, event.target, jQuery.event.fix( event ) );\n\t\t};\n\n\t\tjQuery.event.special[ fix ] = {\n\t\t\tsetup: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix );\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.addEventListener( orig, handler, true );\n\t\t\t\t}\n\t\t\t\tdataPriv.access( doc, fix, ( attaches || 0 ) + 1 );\n\t\t\t},\n\t\t\tteardown: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix ) - 1;\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.removeEventListener( orig, handler, true );\n\t\t\t\t\tdataPriv.remove( doc, fix );\n\n\t\t\t\t} else {\n\t\t\t\t\tdataPriv.access( doc, fix, attaches );\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t} );\n}\n\n\nvar\n\trbracket = /\\[\\]$/,\n\trCRLF = /\\r?\\n/g,\n\trsubmitterTypes = /^(?:submit|button|image|reset|file)$/i,\n\trsubmittable = /^(?:input|select|textarea|keygen)/i;\n\nfunction buildParams( prefix, obj, traditional, add ) {\n\tvar name;\n\n\tif ( Array.isArray( obj ) ) {\n\n\t\t// Serialize array item.\n\t\tjQuery.each( obj, function( i, v ) {\n\t\t\tif ( traditional || rbracket.test( prefix ) ) {\n\n\t\t\t\t// Treat each array item as a scalar.\n\t\t\t\tadd( prefix, v );\n\n\t\t\t} else {\n\n\t\t\t\t// Item is non-scalar (array or object), encode its numeric index.\n\t\t\t\tbuildParams(\n\t\t\t\t\tprefix + \"[\" + ( typeof v === \"object\" && v != null ? i : \"\" ) + \"]\",\n\t\t\t\t\tv,\n\t\t\t\t\ttraditional,\n\t\t\t\t\tadd\n\t\t\t\t);\n\t\t\t}\n\t\t} );\n\n\t} else if ( !traditional && toType( obj ) === \"object\" ) {\n\n\t\t// Serialize object item.\n\t\tfor ( name in obj ) {\n\t\t\tbuildParams( prefix + \"[\" + name + \"]\", obj[ name ], traditional, add );\n\t\t}\n\n\t} else {\n\n\t\t// Serialize scalar item.\n\t\tadd( prefix, obj );\n\t}\n}\n\n// Serialize an array of form elements or a set of\n// key/values into a query string\njQuery.param = function( a, traditional ) {\n\tvar prefix,\n\t\ts = [],\n\t\tadd = function( key, valueOrFunction ) {\n\n\t\t\t// If value is a function, invoke it and use its return value\n\t\t\tvar value = isFunction( valueOrFunction ) ?\n\t\t\t\tvalueOrFunction() :\n\t\t\t\tvalueOrFunction;\n\n\t\t\ts[ s.length ] = encodeURIComponent( key ) + \"=\" +\n\t\t\t\tencodeURIComponent( value == null ? \"\" : value );\n\t\t};\n\n\tif ( a == null ) {\n\t\treturn \"\";\n\t}\n\n\t// If an array was passed in, assume that it is an array of form elements.\n\tif ( Array.isArray( a ) || ( a.jquery && !jQuery.isPlainObject( a ) ) ) {\n\n\t\t// Serialize the form elements\n\t\tjQuery.each( a, function() {\n\t\t\tadd( this.name, this.value );\n\t\t} );\n\n\t} else {\n\n\t\t// If traditional, encode the \"old\" way (the way 1.3.2 or older\n\t\t// did it), otherwise encode params recursively.\n\t\tfor ( prefix in a ) {\n\t\t\tbuildParams( prefix, a[ prefix ], traditional, add );\n\t\t}\n\t}\n\n\t// Return the resulting serialization\n\treturn s.join( \"&\" );\n};\n\njQuery.fn.extend( {\n\tserialize: function() {\n\t\treturn jQuery.param( this.serializeArray() );\n\t},\n\tserializeArray: function() {\n\t\treturn this.map( function() {\n\n\t\t\t// Can add propHook for \"elements\" to filter or add form elements\n\t\t\tvar elements = jQuery.prop( this, \"elements\" );\n\t\t\treturn elements ? jQuery.makeArray( elements ) : this;\n\t\t} )\n\t\t.filter( function() {\n\t\t\tvar type = this.type;\n\n\t\t\t// Use .is( \":disabled\" ) so that fieldset[disabled] works\n\t\t\treturn this.name && !jQuery( this ).is( \":disabled\" ) &&\n\t\t\t\trsubmittable.test( this.nodeName ) && !rsubmitterTypes.test( type ) &&\n\t\t\t\t( this.checked || !rcheckableType.test( type ) );\n\t\t} )\n\t\t.map( function( i, elem ) {\n\t\t\tvar val = jQuery( this ).val();\n\n\t\t\tif ( val == null ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\tif ( Array.isArray( val ) ) {\n\t\t\t\treturn jQuery.map( val, function( val ) {\n\t\t\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t} ).get();\n\t}\n} );\n\n\njQuery.fn.extend( {\n\twrapAll: function( html ) {\n\t\tvar wrap;\n\n\t\tif ( this[ 0 ] ) {\n\t\t\tif ( isFunction( html ) ) {\n\t\t\t\thtml = html.call( this[ 0 ] );\n\t\t\t}\n\n\t\t\t// The elements to wrap the target around\n\t\t\twrap = jQuery( html, this[ 0 ].ownerDocument ).eq( 0 ).clone( true );\n\n\t\t\tif ( this[ 0 ].parentNode ) {\n\t\t\t\twrap.insertBefore( this[ 0 ] );\n\t\t\t}\n\n\t\t\twrap.map( function() {\n\t\t\t\tvar elem = this;\n\n\t\t\t\twhile ( elem.firstElementChild ) {\n\t\t\t\t\telem = elem.firstElementChild;\n\t\t\t\t}\n\n\t\t\t\treturn elem;\n\t\t\t} ).append( this );\n\t\t}\n\n\t\treturn this;\n\t},\n\n\twrapInner: function( html ) {\n\t\tif ( isFunction( html ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).wrapInner( html.call( this, i ) );\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar self = jQuery( this ),\n\t\t\t\tcontents = self.contents();\n\n\t\t\tif ( contents.length ) {\n\t\t\t\tcontents.wrapAll( html );\n\n\t\t\t} else {\n\t\t\t\tself.append( html );\n\t\t\t}\n\t\t} );\n\t},\n\n\twrap: function( html ) {\n\t\tvar htmlIsFunction = isFunction( html );\n\n\t\treturn this.each( function( i ) {\n\t\t\tjQuery( this ).wrapAll( htmlIsFunction ? html.call( this, i ) : html );\n\t\t} );\n\t},\n\n\tunwrap: function( selector ) {\n\t\tthis.parent( selector ).not( \"body\" ).each( function() {\n\t\t\tjQuery( this ).replaceWith( this.childNodes );\n\t\t} );\n\t\treturn this;\n\t}\n} );\n\n\njQuery.expr.pseudos.hidden = function( elem ) {\n\treturn !jQuery.expr.pseudos.visible( elem );\n};\njQuery.expr.pseudos.visible = function( elem ) {\n\treturn !!( elem.offsetWidth || elem.offsetHeight || elem.getClientRects().length );\n};\n\n\n\n\n// Support: Safari 8 only\n// In Safari 8 documents created via document.implementation.createHTMLDocument\n// collapse sibling forms: the second one becomes a child of the first one.\n// Because of that, this security measure has to be disabled in Safari 8.\n// https://bugs.webkit.org/show_bug.cgi?id=137337\nsupport.createHTMLDocument = ( function() {\n\tvar body = document.implementation.createHTMLDocument( \"\" ).body;\n\tbody.innerHTML = \"<form></form><form></form>\";\n\treturn body.childNodes.length === 2;\n} )();\n\n\n// Argument \"data\" should be string of html\n// context (optional): If specified, the fragment will be created in this context,\n// defaults to document\n// keepScripts (optional): If true, will include scripts passed in the html string\njQuery.parseHTML = function( data, context, keepScripts ) {\n\tif ( typeof data !== \"string\" ) {\n\t\treturn [];\n\t}\n\tif ( typeof context === \"boolean\" ) {\n\t\tkeepScripts = context;\n\t\tcontext = false;\n\t}\n\n\tvar base, parsed, scripts;\n\n\tif ( !context ) {\n\n\t\t// Stop scripts or inline event handlers from being executed immediately\n\t\t// by using document.implementation\n\t\tif ( support.createHTMLDocument ) {\n\t\t\tcontext = document.implementation.createHTMLDocument( \"\" );\n\n\t\t\t// Set the base href for the created document\n\t\t\t// so any parsed elements with URLs\n\t\t\t// are based on the document's URL (gh-2965)\n\t\t\tbase = context.createElement( \"base\" );\n\t\t\tbase.href = document.location.href;\n\t\t\tcontext.head.appendChild( base );\n\t\t} else {\n\t\t\tcontext = document;\n\t\t}\n\t}\n\n\tparsed = rsingleTag.exec( data );\n\tscripts = !keepScripts && [];\n\n\t// Single tag\n\tif ( parsed ) {\n\t\treturn [ context.createElement( parsed[ 1 ] ) ];\n\t}\n\n\tparsed = buildFragment( [ data ], context, scripts );\n\n\tif ( scripts && scripts.length ) {\n\t\tjQuery( scripts ).remove();\n\t}\n\n\treturn jQuery.merge( [], parsed.childNodes );\n};\n\n\njQuery.offset = {\n\tsetOffset: function( elem, options, i ) {\n\t\tvar curPosition, curLeft, curCSSTop, curTop, curOffset, curCSSLeft, calculatePosition,\n\t\t\tposition = jQuery.css( elem, \"position\" ),\n\t\t\tcurElem = jQuery( elem ),\n\t\t\tprops = {};\n\n\t\t// Set position first, in-case top/left are set even on static elem\n\t\tif ( position === \"static\" ) {\n\t\t\telem.style.position = \"relative\";\n\t\t}\n\n\t\tcurOffset = curElem.offset();\n\t\tcurCSSTop = jQuery.css( elem, \"top\" );\n\t\tcurCSSLeft = jQuery.css( elem, \"left\" );\n\t\tcalculatePosition = ( position === \"absolute\" || position === \"fixed\" ) &&\n\t\t\t( curCSSTop + curCSSLeft ).indexOf( \"auto\" ) > -1;\n\n\t\t// Need to be able to calculate position if either\n\t\t// top or left is auto and position is either absolute or fixed\n\t\tif ( calculatePosition ) {\n\t\t\tcurPosition = curElem.position();\n\t\t\tcurTop = curPosition.top;\n\t\t\tcurLeft = curPosition.left;\n\n\t\t} else {\n\t\t\tcurTop = parseFloat( curCSSTop ) || 0;\n\t\t\tcurLeft = parseFloat( curCSSLeft ) || 0;\n\t\t}\n\n\t\tif ( isFunction( options ) ) {\n\n\t\t\t// Use jQuery.extend here to allow modification of coordinates argument (gh-1848)\n\t\t\toptions = options.call( elem, i, jQuery.extend( {}, curOffset ) );\n\t\t}\n\n\t\tif ( options.top != null ) {\n\t\t\tprops.top = ( options.top - curOffset.top ) + curTop;\n\t\t}\n\t\tif ( options.left != null ) {\n\t\t\tprops.left = ( options.left - curOffset.left ) + curLeft;\n\t\t}\n\n\t\tif ( \"using\" in options ) {\n\t\t\toptions.using.call( elem, props );\n\n\t\t} else {\n\t\t\tcurElem.css( props );\n\t\t}\n\t}\n};\n\njQuery.fn.extend( {\n\n\t// offset() relates an element's border box to the document origin\n\toffset: function( options ) {\n\n\t\t// Preserve chaining for setter\n\t\tif ( arguments.length ) {\n\t\t\treturn options === undefined ?\n\t\t\t\tthis :\n\t\t\t\tthis.each( function( i ) {\n\t\t\t\t\tjQuery.offset.setOffset( this, options, i );\n\t\t\t\t} );\n\t\t}\n\n\t\tvar rect, win,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !elem ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Return zeros for disconnected and hidden (display: none) elements (gh-2310)\n\t\t// Support: IE <=11 only\n\t\t// Running getBoundingClientRect on a\n\t\t// disconnected node in IE throws an error\n\t\tif ( !elem.getClientRects().length ) {\n\t\t\treturn { top: 0, left: 0 };\n\t\t}\n\n\t\t// Get document-relative position by adding viewport scroll to viewport-relative gBCR\n\t\trect = elem.getBoundingClientRect();\n\t\twin = elem.ownerDocument.defaultView;\n\t\treturn {\n\t\t\ttop: rect.top + win.pageYOffset,\n\t\t\tleft: rect.left + win.pageXOffset\n\t\t};\n\t},\n\n\t// position() relates an element's margin box to its offset parent's padding box\n\t// This corresponds to the behavior of CSS absolute positioning\n\tposition: function() {\n\t\tif ( !this[ 0 ] ) {\n\t\t\treturn;\n\t\t}\n\n\t\tvar offsetParent, offset, doc,\n\t\t\telem = this[ 0 ],\n\t\t\tparentOffset = { top: 0, left: 0 };\n\n\t\t// position:fixed elements are offset from the viewport, which itself always has zero offset\n\t\tif ( jQuery.css( elem, \"position\" ) === \"fixed\" ) {\n\n\t\t\t// Assume position:fixed implies availability of getBoundingClientRect\n\t\t\toffset = elem.getBoundingClientRect();\n\n\t\t} else {\n\t\t\toffset = this.offset();\n\n\t\t\t// Account for the *real* offset parent, which can be the document or its root element\n\t\t\t// when a statically positioned element is identified\n\t\t\tdoc = elem.ownerDocument;\n\t\t\toffsetParent = elem.offsetParent || doc.documentElement;\n\t\t\twhile ( offsetParent &&\n\t\t\t\t( offsetParent === doc.body || offsetParent === doc.documentElement ) &&\n\t\t\t\tjQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\n\t\t\t\toffsetParent = offsetParent.parentNode;\n\t\t\t}\n\t\t\tif ( offsetParent && offsetParent !== elem && offsetParent.nodeType === 1 ) {\n\n\t\t\t\t// Incorporate borders into its offset, since they are outside its content origin\n\t\t\t\tparentOffset = jQuery( offsetParent ).offset();\n\t\t\t\tparentOffset.top += jQuery.css( offsetParent, \"borderTopWidth\", true );\n\t\t\t\tparentOffset.left += jQuery.css( offsetParent, \"borderLeftWidth\", true );\n\t\t\t}\n\t\t}\n\n\t\t// Subtract parent offsets and element margins\n\t\treturn {\n\t\t\ttop: offset.top - parentOffset.top - jQuery.css( elem, \"marginTop\", true ),\n\t\t\tleft: offset.left - parentOffset.left - jQuery.css( elem, \"marginLeft\", true )\n\t\t};\n\t},\n\n\t// This method will return documentElement in the following cases:\n\t// 1) For the element inside the iframe without offsetParent, this method will return\n\t//    documentElement of the parent window\n\t// 2) For the hidden or detached element\n\t// 3) For body or html element, i.e. in case of the html node - it will return itself\n\t//\n\t// but those exceptions were never presented as a real life use-cases\n\t// and might be considered as more preferable results.\n\t//\n\t// This logic, however, is not guaranteed and can change at any point in the future\n\toffsetParent: function() {\n\t\treturn this.map( function() {\n\t\t\tvar offsetParent = this.offsetParent;\n\n\t\t\twhile ( offsetParent && jQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\t\t\t\toffsetParent = offsetParent.offsetParent;\n\t\t\t}\n\n\t\t\treturn offsetParent || documentElement;\n\t\t} );\n\t}\n} );\n\n// Create scrollLeft and scrollTop methods\njQuery.each( { scrollLeft: \"pageXOffset\", scrollTop: \"pageYOffset\" }, function( method, prop ) {\n\tvar top = \"pageYOffset\" === prop;\n\n\tjQuery.fn[ method ] = function( val ) {\n\t\treturn access( this, function( elem, method, val ) {\n\n\t\t\t// Coalesce documents and windows\n\t\t\tvar win;\n\t\t\tif ( isWindow( elem ) ) {\n\t\t\t\twin = elem;\n\t\t\t} else if ( elem.nodeType === 9 ) {\n\t\t\t\twin = elem.defaultView;\n\t\t\t}\n\n\t\t\tif ( val === undefined ) {\n\t\t\t\treturn win ? win[ prop ] : elem[ method ];\n\t\t\t}\n\n\t\t\tif ( win ) {\n\t\t\t\twin.scrollTo(\n\t\t\t\t\t!top ? val : win.pageXOffset,\n\t\t\t\t\ttop ? val : win.pageYOffset\n\t\t\t\t);\n\n\t\t\t} else {\n\t\t\t\telem[ method ] = val;\n\t\t\t}\n\t\t}, method, val, arguments.length );\n\t};\n} );\n\n// Support: Safari <=7 - 9.1, Chrome <=37 - 49\n// Add the top/left cssHooks using jQuery.fn.position\n// Webkit bug: https://bugs.webkit.org/show_bug.cgi?id=29084\n// Blink bug: https://bugs.chromium.org/p/chromium/issues/detail?id=589347\n// getComputedStyle returns percent when specified for top/left/bottom/right;\n// rather than make the css module depend on the offset module, just check for it here\njQuery.each( [ \"top\", \"left\" ], function( i, prop ) {\n\tjQuery.cssHooks[ prop ] = addGetHookIf( support.pixelPosition,\n\t\tfunction( elem, computed ) {\n\t\t\tif ( computed ) {\n\t\t\t\tcomputed = curCSS( elem, prop );\n\n\t\t\t\t// If curCSS returns percentage, fallback to offset\n\t\t\t\treturn rnumnonpx.test( computed ) ?\n\t\t\t\t\tjQuery( elem ).position()[ prop ] + \"px\" :\n\t\t\t\t\tcomputed;\n\t\t\t}\n\t\t}\n\t);\n} );\n\n\n// Create innerHeight, innerWidth, height, width, outerHeight and outerWidth methods\njQuery.each( { Height: \"height\", Width: \"width\" }, function( name, type ) {\n\tjQuery.each( { padding: \"inner\" + name, content: type, \"\": \"outer\" + name },\n\t\tfunction( defaultExtra, funcName ) {\n\n\t\t// Margin is only for outerHeight, outerWidth\n\t\tjQuery.fn[ funcName ] = function( margin, value ) {\n\t\t\tvar chainable = arguments.length && ( defaultExtra || typeof margin !== \"boolean\" ),\n\t\t\t\textra = defaultExtra || ( margin === true || value === true ? \"margin\" : \"border\" );\n\n\t\t\treturn access( this, function( elem, type, value ) {\n\t\t\t\tvar doc;\n\n\t\t\t\tif ( isWindow( elem ) ) {\n\n\t\t\t\t\t// $( window ).outerWidth/Height return w/h including scrollbars (gh-1729)\n\t\t\t\t\treturn funcName.indexOf( \"outer\" ) === 0 ?\n\t\t\t\t\t\telem[ \"inner\" + name ] :\n\t\t\t\t\t\telem.document.documentElement[ \"client\" + name ];\n\t\t\t\t}\n\n\t\t\t\t// Get document width or height\n\t\t\t\tif ( elem.nodeType === 9 ) {\n\t\t\t\t\tdoc = elem.documentElement;\n\n\t\t\t\t\t// Either scroll[Width/Height] or offset[Width/Height] or client[Width/Height],\n\t\t\t\t\t// whichever is greatest\n\t\t\t\t\treturn Math.max(\n\t\t\t\t\t\telem.body[ \"scroll\" + name ], doc[ \"scroll\" + name ],\n\t\t\t\t\t\telem.body[ \"offset\" + name ], doc[ \"offset\" + name ],\n\t\t\t\t\t\tdoc[ \"client\" + name ]\n\t\t\t\t\t);\n\t\t\t\t}\n\n\t\t\t\treturn value === undefined ?\n\n\t\t\t\t\t// Get width or height on the element, requesting but not forcing parseFloat\n\t\t\t\t\tjQuery.css( elem, type, extra ) :\n\n\t\t\t\t\t// Set width or height on the element\n\t\t\t\t\tjQuery.style( elem, type, value, extra );\n\t\t\t}, type, chainable ? margin : undefined, chainable );\n\t\t};\n\t} );\n} );\n\n\njQuery.each( ( \"blur focus focusin focusout resize scroll click dblclick \" +\n\t\"mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave \" +\n\t\"change select submit keydown keypress keyup contextmenu\" ).split( \" \" ),\n\tfunction( i, name ) {\n\n\t// Handle event binding\n\tjQuery.fn[ name ] = function( data, fn ) {\n\t\treturn arguments.length > 0 ?\n\t\t\tthis.on( name, null, data, fn ) :\n\t\t\tthis.trigger( name );\n\t};\n} );\n\njQuery.fn.extend( {\n\thover: function( fnOver, fnOut ) {\n\t\treturn this.mouseenter( fnOver ).mouseleave( fnOut || fnOver );\n\t}\n} );\n\n\n\n\njQuery.fn.extend( {\n\n\tbind: function( types, data, fn ) {\n\t\treturn this.on( types, null, data, fn );\n\t},\n\tunbind: function( types, fn ) {\n\t\treturn this.off( types, null, fn );\n\t},\n\n\tdelegate: function( selector, types, data, fn ) {\n\t\treturn this.on( types, selector, data, fn );\n\t},\n\tundelegate: function( selector, types, fn ) {\n\n\t\t// ( namespace ) or ( selector, types [, fn] )\n\t\treturn arguments.length === 1 ?\n\t\t\tthis.off( selector, \"**\" ) :\n\t\t\tthis.off( types, selector || \"**\", fn );\n\t}\n} );\n\n// Bind a function to a context, optionally partially applying any\n// arguments.\n// jQuery.proxy is deprecated to promote standards (specifically Function#bind)\n// However, it is not slated for removal any time soon\njQuery.proxy = function( fn, context ) {\n\tvar tmp, args, proxy;\n\n\tif ( typeof context === \"string\" ) {\n\t\ttmp = fn[ context ];\n\t\tcontext = fn;\n\t\tfn = tmp;\n\t}\n\n\t// Quick check to determine if target is callable, in the spec\n\t// this throws a TypeError, but we will just return undefined.\n\tif ( !isFunction( fn ) ) {\n\t\treturn undefined;\n\t}\n\n\t// Simulated bind\n\targs = slice.call( arguments, 2 );\n\tproxy = function() {\n\t\treturn fn.apply( context || this, args.concat( slice.call( arguments ) ) );\n\t};\n\n\t// Set the guid of unique handler to the same of original handler, so it can be removed\n\tproxy.guid = fn.guid = fn.guid || jQuery.guid++;\n\n\treturn proxy;\n};\n\njQuery.holdReady = function( hold ) {\n\tif ( hold ) {\n\t\tjQuery.readyWait++;\n\t} else {\n\t\tjQuery.ready( true );\n\t}\n};\njQuery.isArray = Array.isArray;\njQuery.parseJSON = JSON.parse;\njQuery.nodeName = nodeName;\njQuery.isFunction = isFunction;\njQuery.isWindow = isWindow;\njQuery.camelCase = camelCase;\njQuery.type = toType;\n\njQuery.now = Date.now;\n\njQuery.isNumeric = function( obj ) {\n\n\t// As of jQuery 3.0, isNumeric is limited to\n\t// strings and numbers (primitives or objects)\n\t// that can be coerced to finite numbers (gh-2662)\n\tvar type = jQuery.type( obj );\n\treturn ( type === \"number\" || type === \"string\" ) &&\n\n\t\t// parseFloat NaNs numeric-cast false positives (\"\")\n\t\t// ...but misinterprets leading-number strings, particularly hex literals (\"0x...\")\n\t\t// subtraction forces infinities to NaN\n\t\t!isNaN( obj - parseFloat( obj ) );\n};\n\n\n\n\n// Register as a named AMD module, since jQuery can be concatenated with other\n// files that may use define, but not via a proper concatenation script that\n// understands anonymous AMD modules. A named AMD is safest and most robust\n// way to register. Lowercase jquery is used because AMD module names are\n// derived from file names, and jQuery is normally delivered in a lowercase\n// file name. Do this after creating the global so that if an AMD module wants\n// to call noConflict to hide this version of jQuery, it will work.\n\n// Note that for maximum portability, libraries that are not jQuery should\n// declare themselves as anonymous modules, and avoid setting a global if an\n// AMD loader is present. jQuery is a special case. For more information, see\n// https://github.com/jrburke/requirejs/wiki/Updating-existing-libraries#wiki-anon\n\nif ( typeof define === \"function\" && define.amd ) {\n\tdefine( \"jquery\", [], function() {\n\t\treturn jQuery;\n\t} );\n}\n\n\n\n\nvar\n\n\t// Map over jQuery in case of overwrite\n\t_jQuery = window.jQuery,\n\n\t// Map over the $ in case of overwrite\n\t_$ = window.$;\n\njQuery.noConflict = function( deep ) {\n\tif ( window.$ === jQuery ) {\n\t\twindow.$ = _$;\n\t}\n\n\tif ( deep && window.jQuery === jQuery ) {\n\t\twindow.jQuery = _jQuery;\n\t}\n\n\treturn jQuery;\n};\n\n// Expose jQuery and $ identifiers, even in AMD\n// (#7102#comment:10, https://github.com/jquery/jquery/pull/557)\n// and CommonJS for browser emulators (#13566)\nif ( !noGlobal ) {\n\twindow.jQuery = window.$ = jQuery;\n}\n\n\n\n\nreturn jQuery;\n} );\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/js/jqBootstrapValidation.js",
    "content": "/* jqBootstrapValidation\n * A plugin for automating validation on Twitter Bootstrap formatted forms.\n *\n * v1.3.6\n *\n * License: MIT <http://opensource.org/licenses/mit-license.php> - see LICENSE file\n *\n * http://ReactiveRaven.github.com/jqBootstrapValidation/\n */\n\n(function($) {\n\n  var createdElements = [];\n\n  var defaults = {\n    options: {\n      prependExistingHelpBlock: false,\n      sniffHtml: true, // sniff for 'required', 'maxlength', etc\n      preventSubmit: true, // stop the form submit event from firing if validation fails\n      submitError: false, // function called if there is an error when trying to submit\n      submitSuccess: false, // function called just before a successful submit event is sent to the server\n      semanticallyStrict: false, // set to true to tidy up generated HTML output\n      autoAdd: {\n        helpBlocks: true\n      },\n      filter: function() {\n        // return $(this).is(\":visible\"); // only validate elements you can see\n        return true; // validate everything\n      }\n    },\n    methods: {\n      init: function(options) {\n\n        var settings = $.extend(true, {}, defaults);\n\n        settings.options = $.extend(true, settings.options, options);\n\n        var $siblingElements = this;\n\n        var uniqueForms = $.unique(\n          $siblingElements.map(function() {\n            return $(this).parents(\"form\")[0];\n          }).toArray()\n        );\n\n        $(uniqueForms).bind(\"submit\", function(e) {\n          var $form = $(this);\n          var warningsFound = 0;\n          var $inputs = $form.find(\"input,textarea,select\").not(\"[type=submit],[type=image]\").filter(settings.options.filter);\n          $inputs.trigger(\"submit.validation\").trigger(\"validationLostFocus.validation\");\n\n          $inputs.each(function(i, el) {\n            var $this = $(el),\n              $controlGroup = $this.parents(\".form-group\").first();\n            if (\n              $controlGroup.hasClass(\"warning\")\n            ) {\n              $controlGroup.removeClass(\"warning\").addClass(\"error\");\n              warningsFound++;\n            }\n          });\n\n          $inputs.trigger(\"validationLostFocus.validation\");\n\n          if (warningsFound) {\n            if (settings.options.preventSubmit) {\n              e.preventDefault();\n            }\n            $form.addClass(\"error\");\n            if ($.isFunction(settings.options.submitError)) {\n              settings.options.submitError($form, e, $inputs.jqBootstrapValidation(\"collectErrors\", true));\n            }\n          } else {\n            $form.removeClass(\"error\");\n            if ($.isFunction(settings.options.submitSuccess)) {\n              settings.options.submitSuccess($form, e);\n            }\n          }\n        });\n\n        return this.each(function() {\n\n          // Get references to everything we're interested in\n          var $this = $(this),\n            $controlGroup = $this.parents(\".form-group\").first(),\n            $helpBlock = $controlGroup.find(\".help-block\").first(),\n            $form = $this.parents(\"form\").first(),\n            validatorNames = [];\n\n          // create message container if not exists\n          if (!$helpBlock.length && settings.options.autoAdd && settings.options.autoAdd.helpBlocks) {\n            $helpBlock = $('<div class=\"help-block\" />');\n            $controlGroup.find('.controls').append($helpBlock);\n            createdElements.push($helpBlock[0]);\n          }\n\n          // =============================================================\n          //                                     SNIFF HTML FOR VALIDATORS\n          // =============================================================\n\n          // *snort sniff snuffle*\n\n          if (settings.options.sniffHtml) {\n            var message = \"\";\n            // ---------------------------------------------------------\n            //                                                   PATTERN\n            // ---------------------------------------------------------\n            if ($this.attr(\"pattern\") !== undefined) {\n              message = \"Not in the expected format<!-- data-validation-pattern-message to override -->\";\n              if ($this.data(\"validationPatternMessage\")) {\n                message = $this.data(\"validationPatternMessage\");\n              }\n              $this.data(\"validationPatternMessage\", message);\n              $this.data(\"validationPatternRegex\", $this.attr(\"pattern\"));\n            }\n            // ---------------------------------------------------------\n            //                                                       MAX\n            // ---------------------------------------------------------\n            if ($this.attr(\"max\") !== undefined || $this.attr(\"aria-valuemax\") !== undefined) {\n              var max = ($this.attr(\"max\") !== undefined ? $this.attr(\"max\") : $this.attr(\"aria-valuemax\"));\n              message = \"Too high: Maximum of '\" + max + \"'<!-- data-validation-max-message to override -->\";\n              if ($this.data(\"validationMaxMessage\")) {\n                message = $this.data(\"validationMaxMessage\");\n              }\n              $this.data(\"validationMaxMessage\", message);\n              $this.data(\"validationMaxMax\", max);\n            }\n            // ---------------------------------------------------------\n            //                                                       MIN\n            // ---------------------------------------------------------\n            if ($this.attr(\"min\") !== undefined || $this.attr(\"aria-valuemin\") !== undefined) {\n              var min = ($this.attr(\"min\") !== undefined ? $this.attr(\"min\") : $this.attr(\"aria-valuemin\"));\n              message = \"Too low: Minimum of '\" + min + \"'<!-- data-validation-min-message to override -->\";\n              if ($this.data(\"validationMinMessage\")) {\n                message = $this.data(\"validationMinMessage\");\n              }\n              $this.data(\"validationMinMessage\", message);\n              $this.data(\"validationMinMin\", min);\n            }\n            // ---------------------------------------------------------\n            //                                                 MAXLENGTH\n            // ---------------------------------------------------------\n            if ($this.attr(\"maxlength\") !== undefined) {\n              message = \"Too long: Maximum of '\" + $this.attr(\"maxlength\") + \"' characters<!-- data-validation-maxlength-message to override -->\";\n              if ($this.data(\"validationMaxlengthMessage\")) {\n                message = $this.data(\"validationMaxlengthMessage\");\n              }\n              $this.data(\"validationMaxlengthMessage\", message);\n              $this.data(\"validationMaxlengthMaxlength\", $this.attr(\"maxlength\"));\n            }\n            // ---------------------------------------------------------\n            //                                                 MINLENGTH\n            // ---------------------------------------------------------\n            if ($this.attr(\"minlength\") !== undefined) {\n              message = \"Too short: Minimum of '\" + $this.attr(\"minlength\") + \"' characters<!-- data-validation-minlength-message to override -->\";\n              if ($this.data(\"validationMinlengthMessage\")) {\n                message = $this.data(\"validationMinlengthMessage\");\n              }\n              $this.data(\"validationMinlengthMessage\", message);\n              $this.data(\"validationMinlengthMinlength\", $this.attr(\"minlength\"));\n            }\n            // ---------------------------------------------------------\n            //                                                  REQUIRED\n            // ---------------------------------------------------------\n            if ($this.attr(\"required\") !== undefined || $this.attr(\"aria-required\") !== undefined) {\n              message = settings.builtInValidators.required.message;\n              if ($this.data(\"validationRequiredMessage\")) {\n                message = $this.data(\"validationRequiredMessage\");\n              }\n              $this.data(\"validationRequiredMessage\", message);\n            }\n            // ---------------------------------------------------------\n            //                                                    NUMBER\n            // ---------------------------------------------------------\n            if ($this.attr(\"type\") !== undefined && $this.attr(\"type\").toLowerCase() === \"number\") {\n              message = settings.builtInValidators.number.message;\n              if ($this.data(\"validationNumberMessage\")) {\n                message = $this.data(\"validationNumberMessage\");\n              }\n              $this.data(\"validationNumberMessage\", message);\n            }\n            // ---------------------------------------------------------\n            //                                                     EMAIL\n            // ---------------------------------------------------------\n            if ($this.attr(\"type\") !== undefined && $this.attr(\"type\").toLowerCase() === \"email\") {\n              message = \"Not a valid email address<!-- data-validator-validemail-message to override -->\";\n              if ($this.data(\"validationValidemailMessage\")) {\n                message = $this.data(\"validationValidemailMessage\");\n              } else if ($this.data(\"validationEmailMessage\")) {\n                message = $this.data(\"validationEmailMessage\");\n              }\n              $this.data(\"validationValidemailMessage\", message);\n            }\n            // ---------------------------------------------------------\n            //                                                MINCHECKED\n            // ---------------------------------------------------------\n            if ($this.attr(\"minchecked\") !== undefined) {\n              message = \"Not enough options checked; Minimum of '\" + $this.attr(\"minchecked\") + \"' required<!-- data-validation-minchecked-message to override -->\";\n              if ($this.data(\"validationMincheckedMessage\")) {\n                message = $this.data(\"validationMincheckedMessage\");\n              }\n              $this.data(\"validationMincheckedMessage\", message);\n              $this.data(\"validationMincheckedMinchecked\", $this.attr(\"minchecked\"));\n            }\n            // ---------------------------------------------------------\n            //                                                MAXCHECKED\n            // ---------------------------------------------------------\n            if ($this.attr(\"maxchecked\") !== undefined) {\n              message = \"Too many options checked; Maximum of '\" + $this.attr(\"maxchecked\") + \"' required<!-- data-validation-maxchecked-message to override -->\";\n              if ($this.data(\"validationMaxcheckedMessage\")) {\n                message = $this.data(\"validationMaxcheckedMessage\");\n              }\n              $this.data(\"validationMaxcheckedMessage\", message);\n              $this.data(\"validationMaxcheckedMaxchecked\", $this.attr(\"maxchecked\"));\n            }\n          }\n\n          // =============================================================\n          //                                       COLLECT VALIDATOR NAMES\n          // =============================================================\n\n          // Get named validators\n          if ($this.data(\"validation\") !== undefined) {\n            validatorNames = $this.data(\"validation\").split(\",\");\n          }\n\n          // Get extra ones defined on the element's data attributes\n          $.each($this.data(), function(i, el) {\n            var parts = i.replace(/([A-Z])/g, \",$1\").split(\",\");\n            if (parts[0] === \"validation\" && parts[1]) {\n              validatorNames.push(parts[1]);\n            }\n          });\n\n          // =============================================================\n          //                                     NORMALISE VALIDATOR NAMES\n          // =============================================================\n\n          var validatorNamesToInspect = validatorNames;\n          var newValidatorNamesToInspect = [];\n\n          do // repeatedly expand 'shortcut' validators into their real validators\n          {\n            // Uppercase only the first letter of each name\n            $.each(validatorNames, function(i, el) {\n              validatorNames[i] = formatValidatorName(el);\n            });\n\n            // Remove duplicate validator names\n            validatorNames = $.unique(validatorNames);\n\n            // Pull out the new validator names from each shortcut\n            newValidatorNamesToInspect = [];\n            $.each(validatorNamesToInspect, function(i, el) {\n              if ($this.data(\"validation\" + el + \"Shortcut\") !== undefined) {\n                // Are these custom validators?\n                // Pull them out!\n                $.each($this.data(\"validation\" + el + \"Shortcut\").split(\",\"), function(i2, el2) {\n                  newValidatorNamesToInspect.push(el2);\n                });\n              } else if (settings.builtInValidators[el.toLowerCase()]) {\n                // Is this a recognised built-in?\n                // Pull it out!\n                var validator = settings.builtInValidators[el.toLowerCase()];\n                if (validator.type.toLowerCase() === \"shortcut\") {\n                  $.each(validator.shortcut.split(\",\"), function(i, el) {\n                    el = formatValidatorName(el);\n                    newValidatorNamesToInspect.push(el);\n                    validatorNames.push(el);\n                  });\n                }\n              }\n            });\n\n            validatorNamesToInspect = newValidatorNamesToInspect;\n\n          } while (validatorNamesToInspect.length > 0)\n\n          // =============================================================\n          //                                       SET UP VALIDATOR ARRAYS\n          // =============================================================\n\n          var validators = {};\n\n          $.each(validatorNames, function(i, el) {\n            // Set up the 'override' message\n            var message = $this.data(\"validation\" + el + \"Message\");\n            var hasOverrideMessage = (message !== undefined);\n            var foundValidator = false;\n            message =\n              (\n                message ?\n                message :\n                \"'\" + el + \"' validation failed <!-- Add attribute 'data-validation-\" + el.toLowerCase() + \"-message' to input to change this message -->\"\n              );\n\n            $.each(\n              settings.validatorTypes,\n              function(validatorType, validatorTemplate) {\n                if (validators[validatorType] === undefined) {\n                  validators[validatorType] = [];\n                }\n                if (!foundValidator && $this.data(\"validation\" + el + formatValidatorName(validatorTemplate.name)) !== undefined) {\n                  validators[validatorType].push(\n                    $.extend(\n                      true, {\n                        name: formatValidatorName(validatorTemplate.name),\n                        message: message\n                      },\n                      validatorTemplate.init($this, el)\n                    )\n                  );\n                  foundValidator = true;\n                }\n              }\n            );\n\n            if (!foundValidator && settings.builtInValidators[el.toLowerCase()]) {\n\n              var validator = $.extend(true, {}, settings.builtInValidators[el.toLowerCase()]);\n              if (hasOverrideMessage) {\n                validator.message = message;\n              }\n              var validatorType = validator.type.toLowerCase();\n\n              if (validatorType === \"shortcut\") {\n                foundValidator = true;\n              } else {\n                $.each(\n                  settings.validatorTypes,\n                  function(validatorTemplateType, validatorTemplate) {\n                    if (validators[validatorTemplateType] === undefined) {\n                      validators[validatorTemplateType] = [];\n                    }\n                    if (!foundValidator && validatorType === validatorTemplateType.toLowerCase()) {\n                      $this.data(\"validation\" + el + formatValidatorName(validatorTemplate.name), validator[validatorTemplate.name.toLowerCase()]);\n                      validators[validatorType].push(\n                        $.extend(\n                          validator,\n                          validatorTemplate.init($this, el)\n                        )\n                      );\n                      foundValidator = true;\n                    }\n                  }\n                );\n              }\n            }\n\n            if (!foundValidator) {\n              $.error(\"Cannot find validation info for '\" + el + \"'\");\n            }\n          });\n\n          // =============================================================\n          //                                         STORE FALLBACK VALUES\n          // =============================================================\n\n          $helpBlock.data(\n            \"original-contents\",\n            (\n              $helpBlock.data(\"original-contents\") ?\n              $helpBlock.data(\"original-contents\") :\n              $helpBlock.html()\n            )\n          );\n\n          $helpBlock.data(\n            \"original-role\",\n            (\n              $helpBlock.data(\"original-role\") ?\n              $helpBlock.data(\"original-role\") :\n              $helpBlock.attr(\"role\")\n            )\n          );\n\n          $controlGroup.data(\n            \"original-classes\",\n            (\n              $controlGroup.data(\"original-clases\") ?\n              $controlGroup.data(\"original-classes\") :\n              $controlGroup.attr(\"class\")\n            )\n          );\n\n          $this.data(\n            \"original-aria-invalid\",\n            (\n              $this.data(\"original-aria-invalid\") ?\n              $this.data(\"original-aria-invalid\") :\n              $this.attr(\"aria-invalid\")\n            )\n          );\n\n          // =============================================================\n          //                                                    VALIDATION\n          // =============================================================\n\n          $this.bind(\n            \"validation.validation\",\n            function(event, params) {\n\n              var value = getValue($this);\n\n              // Get a list of the errors to apply\n              var errorsFound = [];\n\n              $.each(validators, function(validatorType, validatorTypeArray) {\n                if (value || value.length || (params && params.includeEmpty) || (!!settings.validatorTypes[validatorType].blockSubmit && params && !!params.submitting)) {\n                  $.each(validatorTypeArray, function(i, validator) {\n                    if (settings.validatorTypes[validatorType].validate($this, value, validator)) {\n                      errorsFound.push(validator.message);\n                    }\n                  });\n                }\n              });\n\n              return errorsFound;\n            }\n          );\n\n          $this.bind(\n            \"getValidators.validation\",\n            function() {\n              return validators;\n            }\n          );\n\n          // =============================================================\n          //                                             WATCH FOR CHANGES\n          // =============================================================\n          $this.bind(\n            \"submit.validation\",\n            function() {\n              return $this.triggerHandler(\"change.validation\", {\n                submitting: true\n              });\n            }\n          );\n          $this.bind(\n            [\n              \"keyup\",\n              \"focus\",\n              \"blur\",\n              \"click\",\n              \"keydown\",\n              \"keypress\",\n              \"change\"\n            ].join(\".validation \") + \".validation\",\n            function(e, params) {\n\n              var value = getValue($this);\n\n              var errorsFound = [];\n\n              $controlGroup.find(\"input,textarea,select\").each(function(i, el) {\n                var oldCount = errorsFound.length;\n                $.each($(el).triggerHandler(\"validation.validation\", params), function(j, message) {\n                  errorsFound.push(message);\n                });\n                if (errorsFound.length > oldCount) {\n                  $(el).attr(\"aria-invalid\", \"true\");\n                } else {\n                  var original = $this.data(\"original-aria-invalid\");\n                  $(el).attr(\"aria-invalid\", (original !== undefined ? original : false));\n                }\n              });\n\n              $form.find(\"input,select,textarea\").not($this).not(\"[name=\\\"\" + $this.attr(\"name\") + \"\\\"]\").trigger(\"validationLostFocus.validation\");\n\n              errorsFound = $.unique(errorsFound.sort());\n\n              // Were there any errors?\n              if (errorsFound.length) {\n                // Better flag it up as a warning.\n                $controlGroup.removeClass(\"success error\").addClass(\"warning\");\n\n                // How many errors did we find?\n                if (settings.options.semanticallyStrict && errorsFound.length === 1) {\n                  // Only one? Being strict? Just output it.\n                  $helpBlock.html(errorsFound[0] +\n                    (settings.options.prependExistingHelpBlock ? $helpBlock.data(\"original-contents\") : \"\"));\n                } else {\n                  // Multiple? Being sloppy? Glue them together into an UL.\n                  $helpBlock.html(\"<ul role=\\\"alert\\\"><li>\" + errorsFound.join(\"</li><li>\") + \"</li></ul>\" +\n                    (settings.options.prependExistingHelpBlock ? $helpBlock.data(\"original-contents\") : \"\"));\n                }\n              } else {\n                $controlGroup.removeClass(\"warning error success\");\n                if (value.length > 0) {\n                  $controlGroup.addClass(\"success\");\n                }\n                $helpBlock.html($helpBlock.data(\"original-contents\"));\n              }\n\n              if (e.type === \"blur\") {\n                $controlGroup.removeClass(\"success\");\n              }\n            }\n          );\n          $this.bind(\"validationLostFocus.validation\", function() {\n            $controlGroup.removeClass(\"success\");\n          });\n        });\n      },\n      destroy: function() {\n\n        return this.each(\n          function() {\n\n            var\n              $this = $(this),\n              $controlGroup = $this.parents(\".form-group\").first(),\n              $helpBlock = $controlGroup.find(\".help-block\").first();\n\n            // remove our events\n            $this.unbind('.validation'); // events are namespaced.\n            // reset help text\n            $helpBlock.html($helpBlock.data(\"original-contents\"));\n            // reset classes\n            $controlGroup.attr(\"class\", $controlGroup.data(\"original-classes\"));\n            // reset aria\n            $this.attr(\"aria-invalid\", $this.data(\"original-aria-invalid\"));\n            // reset role\n            $helpBlock.attr(\"role\", $this.data(\"original-role\"));\n            // remove all elements we created\n            if (createdElements.indexOf($helpBlock[0]) > -1) {\n              $helpBlock.remove();\n            }\n\n          }\n        );\n\n      },\n      collectErrors: function(includeEmpty) {\n\n        var errorMessages = {};\n        this.each(function(i, el) {\n          var $el = $(el);\n          var name = $el.attr(\"name\");\n          var errors = $el.triggerHandler(\"validation.validation\", {\n            includeEmpty: true\n          });\n          errorMessages[name] = $.extend(true, errors, errorMessages[name]);\n        });\n\n        $.each(errorMessages, function(i, el) {\n          if (el.length === 0) {\n            delete errorMessages[i];\n          }\n        });\n\n        return errorMessages;\n\n      },\n      hasErrors: function() {\n\n        var errorMessages = [];\n\n        this.each(function(i, el) {\n          errorMessages = errorMessages.concat(\n            $(el).triggerHandler(\"getValidators.validation\") ? $(el).triggerHandler(\"validation.validation\", {\n              submitting: true\n            }) : []\n          );\n        });\n\n        return (errorMessages.length > 0);\n      },\n      override: function(newDefaults) {\n        defaults = $.extend(true, defaults, newDefaults);\n      }\n    },\n    validatorTypes: {\n      callback: {\n        name: \"callback\",\n        init: function($this, name) {\n          return {\n            validatorName: name,\n            callback: $this.data(\"validation\" + name + \"Callback\"),\n            lastValue: $this.val(),\n            lastValid: true,\n            lastFinished: true\n          };\n        },\n        validate: function($this, value, validator) {\n          if (validator.lastValue === value && validator.lastFinished) {\n            return !validator.lastValid;\n          }\n\n          if (validator.lastFinished === true) {\n            validator.lastValue = value;\n            validator.lastValid = true;\n            validator.lastFinished = false;\n\n            var rrjqbvValidator = validator;\n            var rrjqbvThis = $this;\n            executeFunctionByName(\n              validator.callback,\n              window,\n              $this,\n              value,\n              function(data) {\n                if (rrjqbvValidator.lastValue === data.value) {\n                  rrjqbvValidator.lastValid = data.valid;\n                  if (data.message) {\n                    rrjqbvValidator.message = data.message;\n                  }\n                  rrjqbvValidator.lastFinished = true;\n                  rrjqbvThis.data(\"validation\" + rrjqbvValidator.validatorName + \"Message\", rrjqbvValidator.message);\n                  // Timeout is set to avoid problems with the events being considered 'already fired'\n                  setTimeout(function() {\n                    rrjqbvThis.trigger(\"change.validation\");\n                  }, 1); // doesn't need a long timeout, just long enough for the event bubble to burst\n                }\n              }\n            );\n          }\n\n          return false;\n\n        }\n      },\n      ajax: {\n        name: \"ajax\",\n        init: function($this, name) {\n          return {\n            validatorName: name,\n            url: $this.data(\"validation\" + name + \"Ajax\"),\n            lastValue: $this.val(),\n            lastValid: true,\n            lastFinished: true\n          };\n        },\n        validate: function($this, value, validator) {\n          if (\"\" + validator.lastValue === \"\" + value && validator.lastFinished === true) {\n            return validator.lastValid === false;\n          }\n\n          if (validator.lastFinished === true) {\n            validator.lastValue = value;\n            validator.lastValid = true;\n            validator.lastFinished = false;\n            $.ajax({\n              url: validator.url,\n              data: \"value=\" + value + \"&field=\" + $this.attr(\"name\"),\n              dataType: \"json\",\n              success: function(data) {\n                if (\"\" + validator.lastValue === \"\" + data.value) {\n                  validator.lastValid = !!(data.valid);\n                  if (data.message) {\n                    validator.message = data.message;\n                  }\n                  validator.lastFinished = true;\n                  $this.data(\"validation\" + validator.validatorName + \"Message\", validator.message);\n                  // Timeout is set to avoid problems with the events being considered 'already fired'\n                  setTimeout(function() {\n                    $this.trigger(\"change.validation\");\n                  }, 1); // doesn't need a long timeout, just long enough for the event bubble to burst\n                }\n              },\n              failure: function() {\n                validator.lastValid = true;\n                validator.message = \"ajax call failed\";\n                validator.lastFinished = true;\n                $this.data(\"validation\" + validator.validatorName + \"Message\", validator.message);\n                // Timeout is set to avoid problems with the events being considered 'already fired'\n                setTimeout(function() {\n                  $this.trigger(\"change.validation\");\n                }, 1); // doesn't need a long timeout, just long enough for the event bubble to burst\n              }\n            });\n          }\n\n          return false;\n\n        }\n      },\n      regex: {\n        name: \"regex\",\n        init: function($this, name) {\n          return {\n            regex: regexFromString($this.data(\"validation\" + name + \"Regex\"))\n          };\n        },\n        validate: function($this, value, validator) {\n          return (!validator.regex.test(value) && !validator.negative) ||\n            (validator.regex.test(value) && validator.negative);\n        }\n      },\n      required: {\n        name: \"required\",\n        init: function($this, name) {\n          return {};\n        },\n        validate: function($this, value, validator) {\n          return !!(value.length === 0 && !validator.negative) ||\n            !!(value.length > 0 && validator.negative);\n        },\n        blockSubmit: true\n      },\n      match: {\n        name: \"match\",\n        init: function($this, name) {\n          var element = $this.parents(\"form\").first().find(\"[name=\\\"\" + $this.data(\"validation\" + name + \"Match\") + \"\\\"]\").first();\n          element.bind(\"validation.validation\", function() {\n            $this.trigger(\"change.validation\", {\n              submitting: true\n            });\n          });\n          return {\n            \"element\": element\n          };\n        },\n        validate: function($this, value, validator) {\n          return (value !== validator.element.val() && !validator.negative) ||\n            (value === validator.element.val() && validator.negative);\n        },\n        blockSubmit: true\n      },\n      max: {\n        name: \"max\",\n        init: function($this, name) {\n          return {\n            max: $this.data(\"validation\" + name + \"Max\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return (parseFloat(value, 10) > parseFloat(validator.max, 10) && !validator.negative) ||\n            (parseFloat(value, 10) <= parseFloat(validator.max, 10) && validator.negative);\n        }\n      },\n      min: {\n        name: \"min\",\n        init: function($this, name) {\n          return {\n            min: $this.data(\"validation\" + name + \"Min\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return (parseFloat(value) < parseFloat(validator.min) && !validator.negative) ||\n            (parseFloat(value) >= parseFloat(validator.min) && validator.negative);\n        }\n      },\n      maxlength: {\n        name: \"maxlength\",\n        init: function($this, name) {\n          return {\n            maxlength: $this.data(\"validation\" + name + \"Maxlength\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return ((value.length > validator.maxlength) && !validator.negative) ||\n            ((value.length <= validator.maxlength) && validator.negative);\n        }\n      },\n      minlength: {\n        name: \"minlength\",\n        init: function($this, name) {\n          return {\n            minlength: $this.data(\"validation\" + name + \"Minlength\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return ((value.length < validator.minlength) && !validator.negative) ||\n            ((value.length >= validator.minlength) && validator.negative);\n        }\n      },\n      maxchecked: {\n        name: \"maxchecked\",\n        init: function($this, name) {\n          var elements = $this.parents(\"form\").first().find(\"[name=\\\"\" + $this.attr(\"name\") + \"\\\"]\");\n          elements.bind(\"click.validation\", function() {\n            $this.trigger(\"change.validation\", {\n              includeEmpty: true\n            });\n          });\n          return {\n            maxchecked: $this.data(\"validation\" + name + \"Maxchecked\"),\n            elements: elements\n          };\n        },\n        validate: function($this, value, validator) {\n          return (validator.elements.filter(\":checked\").length > validator.maxchecked && !validator.negative) ||\n            (validator.elements.filter(\":checked\").length <= validator.maxchecked && validator.negative);\n        },\n        blockSubmit: true\n      },\n      minchecked: {\n        name: \"minchecked\",\n        init: function($this, name) {\n          var elements = $this.parents(\"form\").first().find(\"[name=\\\"\" + $this.attr(\"name\") + \"\\\"]\");\n          elements.bind(\"click.validation\", function() {\n            $this.trigger(\"change.validation\", {\n              includeEmpty: true\n            });\n          });\n          return {\n            minchecked: $this.data(\"validation\" + name + \"Minchecked\"),\n            elements: elements\n          };\n        },\n        validate: function($this, value, validator) {\n          return (validator.elements.filter(\":checked\").length < validator.minchecked && !validator.negative) ||\n            (validator.elements.filter(\":checked\").length >= validator.minchecked && validator.negative);\n        },\n        blockSubmit: true\n      }\n    },\n    builtInValidators: {\n      email: {\n        name: \"Email\",\n        type: \"shortcut\",\n        shortcut: \"validemail\"\n      },\n      validemail: {\n        name: \"Validemail\",\n        type: \"regex\",\n        regex: \"[A-Za-z0-9._%+-]+@[A-Za-z0-9.-]+\\\\\\.[A-Za-z]{2,4}\",\n        message: \"Not a valid email address<!-- data-validator-validemail-message to override -->\"\n      },\n      passwordagain: {\n        name: \"Passwordagain\",\n        type: \"match\",\n        match: \"password\",\n        message: \"Does not match the given password<!-- data-validator-paswordagain-message to override -->\"\n      },\n      positive: {\n        name: \"Positive\",\n        type: \"shortcut\",\n        shortcut: \"number,positivenumber\"\n      },\n      negative: {\n        name: \"Negative\",\n        type: \"shortcut\",\n        shortcut: \"number,negativenumber\"\n      },\n      number: {\n        name: \"Number\",\n        type: \"regex\",\n        regex: \"([+-]?\\\\\\d+(\\\\\\.\\\\\\d*)?([eE][+-]?[0-9]+)?)?\",\n        message: \"Must be a number<!-- data-validator-number-message to override -->\"\n      },\n      integer: {\n        name: \"Integer\",\n        type: \"regex\",\n        regex: \"[+-]?\\\\\\d+\",\n        message: \"No decimal places allowed<!-- data-validator-integer-message to override -->\"\n      },\n      positivenumber: {\n        name: \"Positivenumber\",\n        type: \"min\",\n        min: 0,\n        message: \"Must be a positive number<!-- data-validator-positivenumber-message to override -->\"\n      },\n      negativenumber: {\n        name: \"Negativenumber\",\n        type: \"max\",\n        max: 0,\n        message: \"Must be a negative number<!-- data-validator-negativenumber-message to override -->\"\n      },\n      required: {\n        name: \"Required\",\n        type: \"required\",\n        message: \"This is required<!-- data-validator-required-message to override -->\"\n      },\n      checkone: {\n        name: \"Checkone\",\n        type: \"minchecked\",\n        minchecked: 1,\n        message: \"Check at least one option<!-- data-validation-checkone-message to override -->\"\n      }\n    }\n  };\n\n  var formatValidatorName = function(name) {\n    return name\n      .toLowerCase()\n      .replace(\n        /(^|\\s)([a-z])/g,\n        function(m, p1, p2) {\n          return p1 + p2.toUpperCase();\n        }\n      );\n  };\n\n  var getValue = function($this) {\n    // Extract the value we're talking about\n    var value = $this.val();\n    var type = $this.attr(\"type\");\n    if (type === \"checkbox\") {\n      value = ($this.is(\":checked\") ? value : \"\");\n    }\n    if (type === \"radio\") {\n      value = ($('input[name=\"' + $this.attr(\"name\") + '\"]:checked').length > 0 ? value : \"\");\n    }\n    return value;\n  };\n\n  function regexFromString(inputstring) {\n    return new RegExp(\"^\" + inputstring + \"$\");\n  }\n\n  /**\n   * Thanks to Jason Bunting via StackOverflow.com\n   *\n   * http://stackoverflow.com/questions/359788/how-to-execute-a-javascript-function-when-i-have-its-name-as-a-string#answer-359910\n   * Short link: http://tinyurl.com/executeFunctionByName\n   **/\n  function executeFunctionByName(functionName, context /*, args*/ ) {\n    var args = Array.prototype.slice.call(arguments).splice(2);\n    var namespaces = functionName.split(\".\");\n    var func = namespaces.pop();\n    for (var i = 0; i < namespaces.length; i++) {\n      context = context[namespaces[i]];\n    }\n    return context[func].apply(this, args);\n  }\n\n  $.fn.jqBootstrapValidation = function(method) {\n\n    if (defaults.methods[method]) {\n      return defaults.methods[method].apply(this, Array.prototype.slice.call(arguments, 1));\n    } else if (typeof method === 'object' || !method) {\n      return defaults.methods.init.apply(this, arguments);\n    } else {\n      $.error('Method ' + method + ' does not exist on jQuery.jqBootstrapValidation');\n      return null;\n    }\n\n  };\n\n  $.jqBootstrapValidation = function(options) {\n    $(\":input\").not(\"[type=image],[type=submit]\").jqBootstrapValidation.apply(this, arguments);\n  };\n\n})(jQuery);\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_bootstrap-overrides.scss",
    "content": "// Bootstrap overrides for this template\n.btn {\n  font-size: 14px;\n  font-weight: 800;\n  padding: 15px 25px;\n  letter-spacing: 1px;\n  text-transform: uppercase;\n  border-radius: 0;\n  @include sans-serif-font;\n}\n\n.btn-primary {\n  background-color: $primary;\n  border-color: $primary;\n  &:hover,\n  &:focus,\n  &:active {\n    color: $white;\n    background-color: darken($primary, 7.5) !important;\n    border-color: darken($primary, 7.5) !important;\n  }\n}\n\n.btn-lg {\n  font-size: 16px;\n  padding: 25px 35px;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_contact.scss",
    "content": "// Styling for the contact page\n.floating-label-form-group {\n  font-size: 14px;\n  position: relative;\n  margin-bottom: 0;\n  padding-bottom: 0.5em;\n  border-bottom: 1px solid $gray-300;\n  input,\n  textarea {\n    font-size: 1.5em;\n    position: relative;\n    z-index: 1;\n    padding: 0;\n    resize: none;\n    border: none;\n    border-radius: 0;\n    background: none;\n    box-shadow: none !important;\n    @include serif-font;\n    &::-webkit-input-placeholder {\n      color: $gray-600;\n      @include serif-font;\n    }\n  }\n  label {\n    font-size: 0.85em;\n    line-height: 1.764705882em;\n    position: relative;\n    z-index: 0;\n    top: 2em;\n    display: block;\n    margin: 0;\n    -webkit-transition: top 0.3s ease, opacity 0.3s ease;\n    -moz-transition: top 0.3s ease, opacity 0.3s ease;\n    -ms-transition: top 0.3s ease, opacity 0.3s ease;\n    transition: top 0.3s ease, opacity 0.3s ease;\n    vertical-align: middle;\n    vertical-align: baseline;\n    opacity: 0;\n  }\n  .help-block {\n    margin: 15px 0;\n  }\n}\n\n.floating-label-form-group-with-value {\n  label {\n    top: 0;\n    opacity: 1;\n  }\n}\n\n.floating-label-form-group-with-focus {\n  label {\n    color: $primary;\n  }\n}\nform .form-group:first-child .floating-label-form-group {\n  border-top: 1px solid $gray-300;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_footer.scss",
    "content": "// Styling for the footer\nfooter {\n  padding: 50px 0 65px;\n  .list-inline {\n    margin: 0;\n    padding: 0;\n  }\n  .copyright {\n    font-size: 14px;\n    margin-bottom: 0;\n    text-align: center;\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_global.scss",
    "content": "// Global styling for this template\nbody {\n  font-size: 20px;\n  color: $gray-900;\n  @include serif-font;\n}\n\np {\n  line-height: 1.5;\n  margin: 30px 0;\n  a {\n    text-decoration: underline;\n  }\n}\n\nh1,\nh2,\nh3,\nh4,\nh5,\nh6 {\n  font-weight: 800;\n  @include sans-serif-font;\n}\n\na {\n  color: $gray-900;\n  @include transition-all;\n  &:focus,\n  &:hover {\n    color: $primary;\n  }\n}\n\nblockquote {\n  font-style: italic;\n  color: $gray-600;\n}\n\n.section-heading {\n  font-size: 36px;\n  font-weight: 700;\n  margin-top: 60px;\n}\n\n.caption {\n  font-size: 14px;\n  font-style: italic;\n  display: block;\n  margin: 0;\n  padding: 10px;\n  text-align: center;\n  border-bottom-right-radius: 5px;\n  border-bottom-left-radius: 5px;\n}\n\n::-moz-selection {\n  color: $white;\n  background: $primary;\n  text-shadow: none;\n}\n\n::selection {\n  color: $white;\n  background: $primary;\n  text-shadow: none;\n}\n\nimg::selection {\n  color: $white;\n  background: transparent;\n}\n\nimg::-moz-selection {\n  color: $white;\n  background: transparent;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_masthead.scss",
    "content": "// Styling for the masthead\nheader.masthead {\n  // TIP: Background images are set within the HTML using inline CSS!\n  margin-bottom: 50px;\n  background: no-repeat center center;\n  background-color: $gray-600;\n  background-attachment: scroll;\n  position: relative;\n  @include background-cover;\n  .overlay {\n    position: absolute;\n    top: 0;\n    left: 0;\n    height: 100%;\n    width: 100%;\n    background-color: $gray-900;\n    opacity: 0.5;\n  }\n  .page-heading,\n  .post-heading,\n  .site-heading {\n    padding: 200px 0 150px;\n    color: white;\n    @media only screen and (min-width: 768px) {\n      padding: 200px 0;\n    }\n  }\n  .page-heading,\n  .site-heading {\n    text-align: center;\n    h1 {\n      font-size: 50px;\n      margin-top: 0;\n    }\n    .subheading {\n      font-size: 24px;\n      font-weight: 300;\n      line-height: 1.1;\n      display: block;\n      margin: 10px 0 0;\n      @include sans-serif-font;\n    }\n    @media only screen and (min-width: 768px) {\n      h1 {\n        font-size: 80px;\n      }\n    }\n  }\n  .post-heading {\n    h1 {\n      font-size: 35px;\n    }\n    .meta,\n    .subheading {\n      line-height: 1.1;\n      display: block;\n    }\n    .subheading {\n      font-size: 24px;\n      font-weight: 600;\n      margin: 10px 0 30px;\n      @include sans-serif-font;\n    }\n    .meta {\n      font-size: 20px;\n      font-weight: 300;\n      font-style: italic;\n      @include serif-font;\n      a {\n        color: $white;\n      }\n    }\n    @media only screen and (min-width: 768px) {\n      h1 {\n        font-size: 55px;\n      }\n      .subheading {\n        font-size: 30px;\n      }\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_mixins.scss",
    "content": "// Mixins\n// Bootstrap Button Variant\n@mixin button-variant($color, $background, $border) {\n  color: $color;\n  border-color: $border;\n  background-color: $background;\n  &.focus,\n  &:focus {\n    color: $color;\n    border-color: darken($border, 25%);\n    background-color: darken($background, 10%);\n  }\n  &:hover {\n    color: $color;\n    border-color: darken($border, 12%);\n    background-color: darken($background, 10%);\n  }\n  &.active,\n  &:active,\n  .open > &.dropdown-toggle {\n    color: $color;\n    border-color: darken($border, 12%);\n    background-color: darken($background, 10%);\n    &.focus,\n    &:focus,\n    &:hover {\n      color: $color;\n      border-color: darken($border, 25%);\n      background-color: darken($background, 17%);\n    }\n  }\n  &.active,\n  &:active,\n  .open > &.dropdown-toggle {\n    background-image: none;\n  }\n  &.disabled,\n  &[disabled],\n  fieldset[disabled] & {\n    &.focus,\n    &:focus,\n    &:hover {\n      border-color: $border;\n      background-color: $background;\n    }\n  }\n  .badge {\n    color: $background;\n    background-color: $color;\n  }\n}\n@mixin transition-all() {\n  -webkit-transition: all 0.2s;\n  -moz-transition: all 0.2s;\n  transition: all 0.2s;\n}\n@mixin background-cover() {\n  -webkit-background-size: cover;\n  -moz-background-size: cover;\n  -o-background-size: cover;\n  background-size: cover;\n}\n@mixin serif-font() {\n  font-family: 'Lora', 'Times New Roman', serif;\n}\n@mixin sans-serif-font() {\n  font-family: 'Open Sans', 'Helvetica Neue', Helvetica, Arial, sans-serif;\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_navbar.scss",
    "content": "// Styling for the navbar\n#mainNav {\n  position: absolute;\n  border-bottom: 1px solid $gray-200;\n  background-color: white;\n  @include sans-serif-font;\n  .navbar-brand {\n    font-weight: 800;\n    color: $gray-800;\n  }\n  .navbar-toggler {\n    font-size: 12px;\n    font-weight: 800;\n    padding: 13px;\n    text-transform: uppercase;\n    color: $gray-800;\n  }\n  .navbar-nav {\n    > li.nav-item {\n      > a {\n        font-size: 12px;\n        font-weight: 800;\n        letter-spacing: 1px;\n        text-transform: uppercase;\n      }\n    }\n  }\n  @media only screen and (min-width: 992px) {\n    border-bottom: 1px solid transparent;\n    background: transparent;\n    .navbar-brand {\n      padding: 10px 20px;\n      color: $white;\n      &:focus,\n      &:hover {\n        color: fade-out($white, .2);\n      }\n    }\n    .navbar-nav {\n      > li.nav-item {\n        > a {\n          padding: 10px 20px;\n          color: $white;\n          &:focus,\n          &:hover {\n            color: fade-out($white, .2);\n          }\n        }\n      }\n    }\n  }\n  @media only screen and (min-width: 992px) {\n    -webkit-transition: background-color 0.2s;\n    -moz-transition: background-color 0.2s;\n    transition: background-color 0.2s;\n    /* Force Hardware Acceleration in WebKit */\n    -webkit-transform: translate3d(0, 0, 0);\n    -moz-transform: translate3d(0, 0, 0);\n    -ms-transform: translate3d(0, 0, 0);\n    -o-transform: translate3d(0, 0, 0);\n    transform: translate3d(0, 0, 0);\n    -webkit-backface-visibility: hidden;\n    &.is-fixed {\n      /* when the user scrolls down, we hide the header right above the viewport */\n      position: fixed;\n      top: -67px;\n      -webkit-transition: -webkit-transform 0.2s;\n      -moz-transition: -moz-transform 0.2s;\n      transition: transform 0.2s;\n      border-bottom: 1px solid darken($white, .05);\n      background-color: fade-out($white, .1);\n      .navbar-brand {\n        color: $gray-900;\n        &:focus,\n        &:hover {\n          color: $primary;\n        }\n      }\n      .navbar-nav {\n        > li.nav-item {\n          > a {\n            color: $gray-900;\n            &:focus,\n            &:hover {\n              color: $primary;\n            }\n          }\n        }\n      }\n    }\n    &.is-visible {\n      /* if the user changes the scrolling direction, we show the header */\n      -webkit-transform: translate3d(0, 100%, 0);\n      -moz-transform: translate3d(0, 100%, 0);\n      -ms-transform: translate3d(0, 100%, 0);\n      -o-transform: translate3d(0, 100%, 0);\n      transform: translate3d(0, 100%, 0);\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_post.scss",
    "content": "// Styling for the post page\n.post-preview {\n  > a {\n    color: $gray-900;\n    &:focus,\n    &:hover {\n      text-decoration: none;\n      color: $primary;\n    }\n    > .post-title {\n      font-size: 30px;\n      margin-top: 30px;\n      margin-bottom: 10px;\n    }\n    > .post-subtitle {\n      font-weight: 300;\n      margin: 0 0 10px;\n    }\n  }\n  > .post-meta {\n    font-size: 18px;\n    font-style: italic;\n    margin-top: 0;\n    color: $gray-600;\n    > a {\n      text-decoration: none;\n      color: $gray-900;\n      &:focus,\n      &:hover {\n        text-decoration: underline;\n        color: $primary;\n      }\n    }\n  }\n  @media only screen and (min-width: 768px) {\n    > a {\n      > .post-title {\n        font-size: 36px;\n      }\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_variables.scss",
    "content": "// Variables\n\n$white:    #fff !default;\n$gray-100: #f8f9fa !default;\n$gray-200: #e9ecef !default;\n$gray-300: #dee2e6 !default;\n$gray-400: #ced4da !default;\n$gray-500: #adb5bd !default;\n$gray-600: #868e96 !default;\n$gray-700: #495057 !default;\n$gray-800: #343a40 !default;\n$gray-900: #212529 !default;\n$black:    #000 !default;\n\n$blue:    #007bff !default;\n$indigo:  #6610f2 !default;\n$purple:  #6f42c1 !default;\n$pink:    #e83e8c !default;\n$red:     #dc3545 !default;\n$orange:  #fd7e14 !default;\n$yellow:  #ffc107 !default;\n$green:   #28a745 !default;\n$teal:    #0085A1 !default;\n$cyan:    #17a2b8 !default;\n\n$primary:       $teal !default;\n$secondary:     $gray-600 !default;\n$success:       $green !default;\n$info:          $cyan !default;\n$warning:       $yellow !default;\n$danger:        $red !default;\n$light:         $gray-100 !default;\n$dark:          $gray-800 !default;\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/clean-blog.scss",
    "content": "@import \"variables.scss\";\n@import \"mixins.scss\";\n@import \"global.scss\";\n@import \"navbar.scss\";\n@import \"masthead.scss\";\n@import \"post.scss\";\n@import \"contact.scss\";\n@import \"footer.scss\";\n@import \"bootstrap-overrides.scss\";\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/contact.html",
    "content": "---\nlayout: page\ntitle: Contact Me\ndescription: Have questions? I have answers.\nbackground: '/img/bg-contact.jpg'\nform: true\n---\n\n<p>Want to get in touch? Fill out the form below to send me a message and I will get back to you as soon as possible!</p>\n<form name=\"sentMessage\" id=\"contactForm\" novalidate>\n  <div class=\"control-group\">\n    <div class=\"form-group floating-label-form-group controls\">\n      <label>Name</label>\n      <input type=\"text\" class=\"form-control\" placeholder=\"Name\" id=\"name\" required data-validation-required-message=\"Please enter your name.\">\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <div class=\"control-group\">\n    <div class=\"form-group floating-label-form-group controls\">\n      <label>Email Address</label>\n      <input type=\"email\" class=\"form-control\" placeholder=\"Email Address\" id=\"email\" required data-validation-required-message=\"Please enter your email address.\">\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <div class=\"control-group\">\n    <div class=\"form-group col-xs-12 floating-label-form-group controls\">\n      <label>Phone Number</label>\n      <input type=\"tel\" class=\"form-control\" placeholder=\"Phone Number\" id=\"phone\" required data-validation-required-message=\"Please enter your phone number.\">\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <div class=\"control-group\">\n    <div class=\"form-group floating-label-form-group controls\">\n      <label>Message</label>\n      <textarea rows=\"5\" class=\"form-control\" placeholder=\"Message\" id=\"message\" required data-validation-required-message=\"Please enter a message.\"></textarea>\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <br>\n  <div id=\"success\"></div>\n  <div class=\"form-group\">\n    <button type=\"submit\" class=\"btn btn-primary\" id=\"sendMessageButton\">Send</button>\n  </div>\n</form>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/get_started.html",
    "content": "---\nlayout: page\ntitle: Getting Started\ndescription: Introduction to the leaderboard.\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/gulpfile.js",
    "content": "// Load plugins\nconst gulp = require(\"gulp\");\n\n// Copy third party libraries from /node_modules into /vendor\ngulp.task('vendor', function(cb) {\n\n  // Start Bootstrap Clean Blog SCSS\n  gulp.src([\n      './node_modules/startbootstrap-clean-blog/scss/**/*'\n    ])\n    .pipe(gulp.dest('./assets/vendor/startbootstrap-clean-blog/scss'))\n\n  // Start Bootstrap Clean Blog JS\n  gulp.src([\n      './node_modules/startbootstrap-clean-blog/js/clean-blog.min.js',\n      './node_modules/startbootstrap-clean-blog/js/jqBootstrapValidation.js'\n    ])\n    .pipe(gulp.dest('./assets/vendor/startbootstrap-clean-blog/js'))\n\n  // Bootstrap\n  gulp.src([\n      './node_modules/bootstrap/dist/**/*',\n      '!./node_modules/bootstrap/dist/css/bootstrap-grid*',\n      '!./node_modules/bootstrap/dist/css/bootstrap-reboot*'\n    ])\n    .pipe(gulp.dest('./assets/vendor/bootstrap'))\n\n  // jQuery\n  gulp.src([\n      './node_modules/jquery/dist/*',\n      '!./node_modules/jquery/dist/core.js'\n    ])\n    .pipe(gulp.dest('./assets/vendor/jquery'))\n\n  // Font Awesome\n  gulp.src([\n      './node_modules/@fortawesome/**/*',\n    ])\n    .pipe(gulp.dest('./assets/vendor'))\n\n  cb();\n\n});\n\ngulp.task(\"default\", gulp.parallel('vendor'));\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/index.html",
    "content": "---\nlayout: home\ntitle: CARLA Leaderboard\ndescription: CARLA Autonomous Driving competition.\nbackground: '/img/carla_header.png'\nimage: 'img/carla_header.png'\n---\n\n\n<h3>Introduction</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\n  The CARLA leaderboard is a way to...\n</p>\n\n<h3>Participation tracks</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\n  The challenge will have four parallel tracks, which differ in the type of input data provided to the agents.\n  In all tracks, the agents will have access to additional measurements, such as a high-level plan of how to reach destinations, and the current speed.\n</p>\n\n<h3>Competition metrics</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\nThe performance of an agent will depend on the number of routes successfully completed. A route is considered successfully completed if no critical infractions were triggered. If the agent triggers a critical infraction, the episode will be automatically terminated and the agent will only get a score proportional to the percentage of the route it completed until the critical infraction. The list of critical infractions is as follows:\n\nHitting the static scenery (poles, traffic signs, etc.).\n\nIf an agent runs out of time to complete a given route the final score will be the percentage of route completed before the timeout.\n\nThe final score will consist of two components:\n\nPoints obtained for route completion.\nPoints lost due to other infractions (e.g., running a red light).\nMinor infractions will have a negative effect on the final score. Each infraction discounts points from the final score, which could get down to 0 in the worst case. These are the points discounted for each infraction:\n</p>\n\n<h3>Participation mechanics</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\n  Participants must create a new team in the EvalAI CARLA AD Challenge contest.\n  Teams will create a docker image using the provided Dockerfile templates.\n  Docker containers will be then pushed to CARLA AD Challenge internal repositories using EvalAI cli scripts. Teams must select the right challenge phase to submit their containers.\n  Docker images will be automatically evaluated in AWS by our evaluation infrastructure and results will be reported to users through the EvalAI CARLA AD Challenge site.\n  For detailed instructions, please visit the Submit section.\n\n  Important considerations\n  Agents will run on a private AWS instance endowed with a multi-processor and a GPU (NVIDIA Tesla K80).\n  Teams will receive a budget of 300 hours for the entire challenge. If a team exceeds its hours, new docker containers won’t be evaluated.\n  The CARLA AD Challenge organization reserves the right to assign further hours to teams due to extraordinary circumstances.\n  Some Autonomous Driving baselines are provided as a reference. Please, read the Get started section for more information.\n  We recommend participants to join our Discord chat to keep up-to-date with challenge news.\n</p>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/jekyll-theme-clean-blog.gemspec",
    "content": "# frozen_string_literal: true\n\nGem::Specification.new do |spec|\n  spec.name          = \"jekyll-theme-clean-blog\"\n  spec.version       = \"4.0.9\"\n  spec.authors       = [\"CARLA Team\"]\n  spec.email         = [\"carla.simulator@gmail.com\"]\n\n  spec.summary       = \"A simple blog theme based on Bootstrap 4 by Start Bootstrap.\"\n  spec.homepage      = \"https://github.com/blackrockdigital/startbootstrap-clean-blog-jekyll\"\n  spec.license       = \"MIT\"\n\n  spec.files         = `git ls-files -z`.split(\"\\x0\").select { |f| f.match(%r{^(assets|_layouts|_includes|_sass|LICENSE|README)}i) }\n\n  spec.add_runtime_dependency \"jekyll\", \"~> 3.8.5\"\n\n  spec.add_development_dependency \"bundler\", \"~> 2.0.1\"\n  spec.add_development_dependency \"rake\", \"~> 12.0\"\nend\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/leaderboard.html",
    "content": "---\nlayout: page\ntitle: Leaderboard\ndescription: \"\"\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/posts/index.html",
    "content": "---\nlayout: page\ntitle: Posts\nbackground: '/img/bg-post.jpg'\n---\n\n{% for post in paginator.posts %}\n\n<article class=\"post-preview\">\n  <a href=\"{{ post.url | prepend: site.baseurl | replace: '//', '/' }}\">\n    <h2 class=\"post-title\">{{ post.title }}</h2>\n    {% if post.subtitle %}\n    <h3 class=\"post-subtitle\">{{ post.subtitle }}</h3>\n    {% else %}\n    <h3 class=\"post-subtitle\">{{ post.excerpt | strip_html | truncatewords: 15 }}</h3>\n    {% endif %}\n  </a>\n  <p class=\"post-meta\">Posted by\n    {% if post.author %}\n    {{ post.author }}\n    {% else %}\n    {{ site.author }}\n    {% endif %}\n    on {{ post.date | date: '%B %d, %Y' }} &middot; {% include read_time.html content=post.content %}\n  </p>\n</article>\n\n<hr>\n\n{% endfor %}\n\n<!-- Pager -->\n{% if paginator.total_pages > 1 %}\n\n<div class=\"clearfix\">\n\n  {% if paginator.previous_page %}\n  <a class=\"btn btn-primary float-left\" href=\"{{ paginator.previous_page_path | prepend: site.baseurl | replace: '//', '/' }}\">&larr;\n    Newer<span class=\"d-none d-md-inline\"> Posts</span></a>\n  {% endif %}\n\n  {% if paginator.next_page %}\n  <a class=\"btn btn-primary float-right\" href=\"{{ paginator.next_page_path | prepend: site.baseurl | replace: '//', '/' }}\">Older<span class=\"d-none d-md-inline\"> Posts</span> &rarr;</a>\n  {% endif %}\n\n</div>\n\n{% endif %}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/docs/submit.html",
    "content": "---\nlayout: page\ntitle: Submit\ndescription: How to submit to the leaderboard.\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/agent_wrapper.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nWrapper for autonomous agents required for tracking and checking of used sensors\n\"\"\"\n\nfrom __future__ import print_function\nimport math\nimport os\nimport time\n\nimport carla\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\nfrom leaderboard.envs.sensor_interface import CallBack, OpenDriveMapReader, SpeedometerReader, SensorConfigurationInvalid\nfrom leaderboard.autoagents.autonomous_agent import Track\nfrom leaderboard.autoagents.ros_base_agent import ROSBaseAgent\n\nIS_BENCH2DRIVE = os.environ.get('SAVE_PATH', None)\nif IS_BENCH2DRIVE:\n    MAX_ALLOWED_RADIUS_SENSOR = 100.0  # for visualize\nelse:\n    MAX_ALLOWED_RADIUS_SENSOR = 3.0\n\nQUALIFIER_SENSORS_LIMITS = {\n    'sensor.camera.rgb': 4,\n    'sensor.lidar.ray_cast': 1,\n    'sensor.other.radar': 2,\n    'sensor.other.gnss': 1,\n    'sensor.other.imu': 1,\n    'sensor.opendrive_map': 1,\n    'sensor.speedometer': 1\n}\nSENSORS_LIMITS = {\n    'sensor.camera.rgb': 8,\n    'sensor.lidar.ray_cast': 2,\n    'sensor.other.radar': 4,\n    'sensor.other.gnss': 1,\n    'sensor.other.imu': 1,\n    'sensor.opendrive_map': 1,\n    'sensor.speedometer': 1\n}\nALLOWED_SENSORS = SENSORS_LIMITS.keys()\n\n\nclass AgentError(Exception):\n    \"\"\"\n    Exceptions thrown when the agent returns an error during the simulation\n    \"\"\"\n\n    def __init__(self, message):\n        super(AgentError, self).__init__(message)\n\n        \nclass TickRuntimeError(Exception):\n    pass\n\nclass AgentWrapperFactory(object):\n\n    @staticmethod\n    def get_wrapper(agent):\n        if isinstance(agent, ROSBaseAgent):\n            return ROSAgentWrapper(agent)\n        else:\n            return AgentWrapper(agent)\n\n\ndef validate_sensor_configuration(sensors, agent_track, selected_track):\n    \"\"\"\n    Ensure that the sensor configuration is valid, in case the challenge mode is used\n    Returns true on valid configuration, false otherwise\n    \"\"\"\n    if Track(selected_track) != agent_track:\n        raise SensorConfigurationInvalid(\"You are submitting to the wrong track [{}]!\".format(Track(selected_track)))\n\n    sensor_count = {}\n    sensor_ids = []\n\n    for sensor in sensors:\n\n        # Check if the is has been already used\n        sensor_id = sensor['id']\n        if sensor_id in sensor_ids:\n            raise SensorConfigurationInvalid(\"Duplicated sensor tag [{}]\".format(sensor_id))\n        else:\n            sensor_ids.append(sensor_id)\n\n        # Check if the sensor is valid\n        if agent_track == Track.SENSORS:\n            if sensor['type'].startswith('sensor.opendrive_map'):\n                raise SensorConfigurationInvalid(\"Illegal sensor 'sensor.opendrive_map' used for Track [{}]!\".format(agent_track))\n\n        # Check the sensors validity\n        if sensor['type'] not in ALLOWED_SENSORS:\n            raise SensorConfigurationInvalid(\"Illegal sensor '{}' used for Track [{}]!\".format(sensor['type'], agent_track))\n\n        # Check the extrinsics of the sensor\n        if 'x' in sensor and 'y' in sensor and 'z' in sensor:\n            if math.sqrt(sensor['x']**2 + sensor['y']**2 + sensor['z']**2) > MAX_ALLOWED_RADIUS_SENSOR:\n                raise SensorConfigurationInvalid(\n                    \"Illegal sensor extrinsics used for sensor '{}'. Max allowed radius is {}m\".format(sensor['id'], MAX_ALLOWED_RADIUS_SENSOR))\n\n        # Check the amount of sensors\n        if sensor['type'] in sensor_count:\n            sensor_count[sensor['type']] += 1\n        else:\n            sensor_count[sensor['type']] = 1\n\n    if agent_track in (Track.SENSORS_QUALIFIER, Track.MAP_QUALIFIER):\n        sensor_limits = QUALIFIER_SENSORS_LIMITS\n    else:\n        sensor_limits = SENSORS_LIMITS\n\n    for sensor_type, max_instances_allowed in sensor_limits.items():\n        if sensor_type in sensor_count and sensor_count[sensor_type] > max_instances_allowed:\n            raise SensorConfigurationInvalid(\n                \"Too many {} used! \"\n                \"Maximum number allowed is {}, but {} were requested.\".format(sensor_type,\n                                                                              max_instances_allowed,\n                                                                              sensor_count[sensor_type]))\n\n\nclass AgentWrapper(object):\n\n    \"\"\"\n    Wrapper for autonomous agents required for tracking and checking of used sensors\n    \"\"\"\n    _agent = None\n    _sensors_list = []\n\n    def __init__(self, agent):\n        \"\"\"\n        Set the autonomous agent\n        \"\"\"\n        self._agent = agent\n\n    def __call__(self):\n        \"\"\"\n        Pass the call directly to the agent\n        \"\"\"\n        return self._agent()\n\n    def _preprocess_sensor_spec(self, sensor_spec):\n        type_ = sensor_spec[\"type\"]\n        id_ = sensor_spec[\"id\"]\n        attributes = {}\n\n        if type_ == 'sensor.opendrive_map':\n            attributes['reading_frequency'] = sensor_spec['reading_frequency']\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        elif type_ == 'sensor.speedometer':\n            delta_time = CarlaDataProvider.get_world().get_settings().fixed_delta_seconds\n            attributes['reading_frequency'] = 1 / delta_time\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        if type_ == 'sensor.camera.rgb':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.lidar.ray_cast':\n            attributes['range'] = str(85)\n            attributes['rotation_frequency'] = str(10)\n            attributes['channels'] = str(64)\n            attributes['upper_fov'] = str(10)\n            attributes['lower_fov'] = str(-30)\n            attributes['points_per_second'] = str(600000)\n            attributes['atmosphere_attenuation_rate'] = str(0.004)\n            attributes['dropoff_general_rate'] = str(0.45)\n            attributes['dropoff_intensity_limit'] = str(0.8)\n            attributes['dropoff_zero_intensity'] = str(0.4)\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.radar':\n            attributes['horizontal_fov'] = str(sensor_spec['horizontal_fov'])  # degrees\n            attributes['vertical_fov'] = str(sensor_spec['vertical_fov'])  # degrees\n            attributes['points_per_second'] = '1500'\n            attributes['range'] = '100'  # meters\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.gnss':\n            attributes['noise_alt_stddev'] = str(0.000005)\n            attributes['noise_lat_stddev'] = str(0.000005)\n            attributes['noise_lon_stddev'] = str(0.000005)\n            attributes['noise_alt_bias'] = str(0.0)\n            attributes['noise_lat_bias'] = str(0.0)\n            attributes['noise_lon_bias'] = str(0.0)\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation()\n\n        elif type_ == 'sensor.other.imu':\n            attributes['noise_accel_stddev_x'] = str(0.001)\n            attributes['noise_accel_stddev_y'] = str(0.001)\n            attributes['noise_accel_stddev_z'] = str(0.015)\n            attributes['noise_gyro_stddev_x'] = str(0.001)\n            attributes['noise_gyro_stddev_y'] = str(0.001)\n            attributes['noise_gyro_stddev_z'] = str(0.001)\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n        sensor_transform = carla.Transform(sensor_location, sensor_rotation)\n\n        return type_, id_, sensor_transform, attributes\n\n    def setup_sensors(self, vehicle):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        world = CarlaDataProvider.get_world()\n        bp_library = world.get_blueprint_library()\n        for sensor_spec in self._agent.sensors():\n            type_, id_, sensor_transform, attributes = self._preprocess_sensor_spec(sensor_spec)\n\n            # These are the pseudosensors (not spawned)\n            if type_ == 'sensor.opendrive_map':\n                sensor = OpenDriveMapReader(vehicle, attributes['reading_frequency'])\n            elif type_ == 'sensor.speedometer':\n                sensor = SpeedometerReader(vehicle, attributes['reading_frequency'])\n\n            # These are the sensors spawned on the carla world\n            else:\n                bp = bp_library.find(type_)\n                for key, value in attributes.items():\n                    bp.set_attribute(str(key), str(value))\n                sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)\n\n            # setup callback\n            sensor.listen(CallBack(id_, type_, sensor, self._agent.sensor_interface))\n            self._sensors_list.append(sensor)\n\n        # Some sensors miss sending data during the first ticks, so tick several times and remove the data\n        for _ in range(10):\n            world.tick()\n\n    def cleanup(self):\n        \"\"\"\n        Remove and destroy all sensors\n        \"\"\"\n        for i, _ in enumerate(self._sensors_list):\n            if self._sensors_list[i] is not None:\n                self._sensors_list[i].stop()\n                self._sensors_list[i].destroy()\n                self._sensors_list[i] = None\n        self._sensors_list = []\n\n        # Tick once to destroy the sensors\n        CarlaDataProvider.get_world().tick()\n\n\nclass ROSAgentWrapper(AgentWrapper):\n\n    SENSOR_TYPE_REMAPS = {\n        \"sensor.opendrive_map\": \"sensor.pseudo.opendrive_map\",\n        \"sensor.speedometer\": \"sensor.pseudo.speedometer\"\n    }\n\n    def __init__(self, agent):\n        super(ROSAgentWrapper, self).__init__(agent)\n\n    def _preprocess_sensor_spec(self, sensor_spec):\n        type_, id_, sensor_transform, attributes = super(ROSAgentWrapper, self)._preprocess_sensor_spec(sensor_spec)\n        new_type = self.SENSOR_TYPE_REMAPS.get(type_, type_)\n        return new_type, id_, sensor_transform, attributes\n\n    def setup_sensors(self, vehicle):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        for sensor_spec in self._agent.sensors():\n            type_, id_, transform, attributes = self._preprocess_sensor_spec(sensor_spec)\n            uid = self._agent.spawn_object(type_, id_, transform, attributes, attach_to=vehicle.id)\n            self._sensors_list.append(uid)\n\n        # Tick once to spawn the sensors\n        CarlaDataProvider.get_world().tick()\n\n    def cleanup(self):\n        for uid in self._sensors_list:\n            self._agent.destroy_object(uid)\n        self._sensors_list.clear()\n\n        # Tick once to destroy the sensors\n        CarlaDataProvider.get_world().tick()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/autonomous_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the base class for all autonomous agents\n\"\"\"\n\nfrom __future__ import print_function\n\nfrom enum import Enum\n\nimport carla\nfrom srunner.scenariomanager.timer import GameTime\n\nfrom leaderboard.utils.route_manipulation import downsample_route\nfrom leaderboard.envs.sensor_interface import SensorInterface\n\n\nclass Track(Enum):\n\n    \"\"\"\n    This enum represents the different tracks of the CARLA AD leaderboard.\n    \"\"\"\n    SENSORS = 'SENSORS'\n    MAP = 'MAP'\n    SENSORS_QUALIFIER = 'SENSORS_QUALIFIER'\n    MAP_QUALIFIER = 'MAP_QUALIFIER'\n\n\nclass AutonomousAgent(object):\n\n    \"\"\"\n    Autonomous agent base class. All user agents have to be derived from this class\n    \"\"\"\n\n    def __init__(self, carla_host, carla_port, debug=False):\n        self.track = Track.SENSORS\n        #  current global plans to reach a destination\n        self._global_plan = None\n        self._global_plan_world_coord = None\n\n        # this data structure will contain all sensor data\n        self.sensor_interface = SensorInterface()\n\n        self.wallclock_t0 = None\n\n        self.get_hero()\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Initialize everything needed by your agent and set the track attribute to the right type:\n            Track.SENSORS : CAMERAS, LIDAR, RADAR, GPS and IMU sensors are allowed\n            Track.MAP : OpenDRIVE map is also allowed\n        \"\"\"\n        pass\n\n    def sensors(self):  # pylint: disable=no-self-use\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n\n        \"\"\"\n        sensors = []\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        :return: control\n        \"\"\"\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        pass\n\n    def __call__(self):\n        \"\"\"\n        Execute the agent call, e.g. agent()\n        Returns the next vehicle controls\n        \"\"\"\n        input_data = self.sensor_interface.get_data(GameTime.get_frame())\n\n        timestamp = GameTime.get_time()\n\n        if not self.wallclock_t0:\n            self.wallclock_t0 = GameTime.get_wallclocktime()\n        wallclock = GameTime.get_wallclocktime()\n        wallclock_diff = (wallclock - self.wallclock_t0).total_seconds()\n        sim_ratio = 0 if wallclock_diff == 0 else timestamp/wallclock_diff\n\n        print('=== [Agent] -- Wallclock = {} -- System time = {} -- Game time = {} -- Ratio = {}x'.format(\n            str(wallclock)[:-3], format(wallclock_diff, '.3f'), format(timestamp, '.3f'), format(sim_ratio, '.3f')), flush=True)\n        #import pdb;pdb.set_trace()\n        control = self.run_step(input_data, timestamp)\n        control.manual_gear_shift = False\n\n        return control\n\n    @staticmethod\n    def get_ros_version():\n        return -1\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        \"\"\"\n        Set the plan (route) for the agent\n        \"\"\"\n        ds_ids = downsample_route(global_plan_world_coord, 50)\n        self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1]) for x in ds_ids]\n        self._global_plan = [global_plan_gps[x] for x in ds_ids]\n        self._plan_gps_HACK = global_plan_gps\n    \n    def get_hero(self):\n        hero_actor = None\n        from srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n        for actor in CarlaDataProvider.get_world().get_actors():\n            if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero':\n                hero_actor = actor\n                break\n        self.hero_actor = hero_actor\n    \n    def get_metric_info(self):\n        \n        def vector2list(vector, rotation=False):\n            if rotation:\n                return [vector.roll, vector.pitch, vector.yaw]\n            else:\n                return [vector.x, vector.y, vector.z]\n\n        output = {}\n        output['acceleration'] = vector2list(self.hero_actor.get_acceleration())\n        output['angular_velocity'] = vector2list(self.hero_actor.get_angular_velocity())\n        output['forward_vector'] = vector2list(self.hero_actor.get_transform().get_forward_vector())\n        output['right_vector'] = vector2list(self.hero_actor.get_transform().get_right_vector())\n        output['location'] = vector2list(self.hero_actor.get_transform().location)\n        output['rotation'] = vector2list(self.hero_actor.get_transform().rotation, rotation=True)\n        return output"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/dummy_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a dummy agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\ndef get_entry_point():\n    return 'DummyAgent'\n\nclass DummyAgent(AutonomousAgent):\n\n    \"\"\"\n    Dummy autonomous agent to control the ego vehicle\n    \"\"\"\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self.track = Track.MAP\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'},\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0,\n             'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'},\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0,\n             'width': 800, 'height': 600, 'fov': 100, 'id': 'Right'},\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n             'yaw': -45.0, 'id': 'LIDAR'},\n            {'type': 'sensor.other.radar', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n             'yaw': -45.0, 'fov': 30, 'id': 'RADAR', 'horizontal_fov' : 30.0, 'vertical_fov' : 30.0},\n            {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'},\n            {'type': 'sensor.other.imu', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n             'yaw': -45.0, 'id': 'IMU'},\n            {'type': 'sensor.opendrive_map', 'reading_frequency': 1, 'id': 'OpenDRIVE'},\n        ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        print(\"=====================>\")\n        for key, val in input_data.items():\n            if hasattr(val[1], 'shape'):\n                shape = val[1].shape\n                print(\"[{} -- {:06d}] with shape {}\".format(key, val[0], shape))\n            else:\n                print(\"[{} -- {:06d}] \".format(key, val[0]))\n        print(\"<=====================\")\n\n        # DO SOMETHING SMART\n\n        # RETURN CONTROL\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/human_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a human agent to control the ego vehicle via keyboard\n\"\"\"\n\nimport numpy as np\nimport json\n\ntry:\n    import pygame\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_UP\n    from pygame.locals import K_a\n    from pygame.locals import K_d\n    from pygame.locals import K_s\n    from pygame.locals import K_w\n    from pygame.locals import K_q\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\nimport carla\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\n\ndef get_entry_point():\n    return 'HumanAgent'\n\nclass HumanInterface(object):\n\n    \"\"\"\n    Class to control a vehicle manually for debugging purposes\n    \"\"\"\n\n    def __init__(self, width, height, side_scale, left_mirror=False, right_mirror=False):\n        self._width = width\n        self._height = height\n        self._scale = side_scale\n        self._surface = None\n\n        self._left_mirror = left_mirror\n        self._right_mirror = right_mirror\n\n        pygame.init()\n        pygame.font.init()\n        self._clock = pygame.time.Clock()\n        self._display = pygame.display.set_mode((self._width, self._height), pygame.HWSURFACE | pygame.DOUBLEBUF)\n        pygame.display.set_caption(\"Human Agent\")\n\n    def run_interface(self, input_data):\n        \"\"\"\n        Run the GUI\n        \"\"\"\n\n        # Process sensor data\n        image_center = input_data['Center'][1][:, :, -2::-1]\n        self._surface = pygame.surfarray.make_surface(image_center.swapaxes(0, 1))\n\n        # Add the left mirror\n        if self._left_mirror:\n            image_left = input_data['Left'][1][:, :, -2::-1]\n            left_surface = pygame.surfarray.make_surface(image_left.swapaxes(0, 1))\n            self._surface.blit(left_surface, (0, (1 - self._scale) * self._height))\n\n        # Add the right mirror\n        if self._right_mirror:\n            image_right = input_data['Right'][1][:, :, -2::-1]\n            right_surface = pygame.surfarray.make_surface(image_right.swapaxes(0, 1))\n            self._surface.blit(right_surface, ((1 - self._scale) * self._width, (1 - self._scale) * self._height))\n\n        # Display image\n        if self._surface is not None:\n            self._display.blit(self._surface, (0, 0))\n        pygame.display.flip()\n\n    def set_black_screen(self):\n        \"\"\"Set the surface to black\"\"\"\n        black_array = np.zeros([self._width, self._height])\n        self._surface = pygame.surfarray.make_surface(black_array)\n        if self._surface is not None:\n            self._display.blit(self._surface, (0, 0))\n        pygame.display.flip()\n\n    def _quit(self):\n        pygame.quit()\n\n\nclass HumanAgent(AutonomousAgent):\n\n    \"\"\"\n    Human agent to control the ego vehicle via keyboard\n    \"\"\"\n\n    current_control = None\n    agent_engaged = False\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self.track = Track.SENSORS\n\n        self.agent_engaged = False\n        self.camera_width = 1280\n        self.camera_height = 720\n        self._side_scale = 0.3\n        self._left_mirror = False\n        self._right_mirror = False\n\n        self._hic = HumanInterface(\n            self.camera_width,\n            self.camera_height,\n            self._side_scale,\n            self._left_mirror,\n            self._right_mirror\n        )\n        self._controller = KeyboardControl(path_to_conf_file)\n        self._prev_timestamp = 0\n\n        self._clock = pygame.time.Clock()\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': self.camera_width, 'height': self.camera_height, 'fov': 100, 'id': 'Center'},\n        ]\n\n        if self._left_mirror:\n            sensors.append(\n                {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -1.0, 'z': 1, 'roll': 0.0, 'pitch': 0.0, 'yaw': 210.0,\n                 'width': self.camera_width * self._side_scale, 'height': self.camera_height * self._side_scale,\n                 'fov': 100, 'id': 'Left'})\n\n        if self._right_mirror:\n            sensors.append(\n                {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 1.0, 'z': 1, 'roll': 0.0, 'pitch': 0.0, 'yaw': 150.0,\n                 'width': self.camera_width * self._side_scale, 'height': self.camera_height * self._side_scale,\n                 'fov': 100, 'id': 'Right'})\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        self._clock.tick_busy_loop(20)\n        self.agent_engaged = True\n        self._hic.run_interface(input_data)\n\n        control = self._controller.parse_events(timestamp - self._prev_timestamp)\n        self._prev_timestamp = timestamp\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Cleanup\n        \"\"\"\n        self._hic.set_black_screen()\n        self._hic._quit = True\n\n\nclass KeyboardControl(object):\n\n    \"\"\"\n    Keyboard control for the human agent\n    \"\"\"\n\n    def __init__(self, path_to_conf_file):\n        \"\"\"\n        Init\n        \"\"\"\n        self._control = carla.VehicleControl()\n        self._steer_cache = 0.0\n        self._clock = pygame.time.Clock()\n\n        # Get the mode\n        if path_to_conf_file:\n\n            with (open(path_to_conf_file, \"r\")) as f:\n                lines = f.read().split(\"\\n\")\n                self._mode = lines[0].split(\" \")[1]\n                self._endpoint = lines[1].split(\" \")[1]\n\n            # Get the needed vars\n            if self._mode == \"log\":\n                self._log_data = {'records': []}\n\n            elif self._mode == \"playback\":\n                self._index = 0\n                self._control_list = []\n\n                with open(self._endpoint) as fd:\n                    try:\n                        self._records = json.load(fd)\n                        self._json_to_control()\n                    except json.JSONDecodeError:\n                        pass\n        else:\n            self._mode = \"normal\"\n            self._endpoint = None\n\n    def _json_to_control(self):\n\n        # transform strs into VehicleControl commands\n        for entry in self._records['records']:\n            control = carla.VehicleControl(throttle=entry['control']['throttle'],\n                                           steer=entry['control']['steer'],\n                                           brake=entry['control']['brake'],\n                                           hand_brake=entry['control']['hand_brake'],\n                                           reverse=entry['control']['reverse'],\n                                           manual_gear_shift=entry['control']['manual_gear_shift'],\n                                           gear=entry['control']['gear'])\n            self._control_list.append(control)\n\n    def parse_events(self, timestamp):\n        \"\"\"\n        Parse the keyboard events and set the vehicle controls accordingly\n        \"\"\"\n        # Move the vehicle\n        if self._mode == \"playback\":\n            self._parse_json_control()\n        else:\n            self._parse_vehicle_keys(pygame.key.get_pressed(), timestamp*1000)\n\n        # Record the control\n        if self._mode == \"log\":\n            self._record_control()\n\n        return self._control\n\n    def _parse_vehicle_keys(self, keys, milliseconds):\n        \"\"\"\n        Calculate new vehicle controls based on input keys\n        \"\"\"\n\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                return \n            elif event.type == pygame.KEYUP:\n                if event.key == K_q:\n                    self._control.gear = 1 if self._control.reverse else -1\n                    self._control.reverse = self._control.gear < 0\n\n        if keys[K_UP] or keys[K_w]:\n            self._control.throttle = 0.8\n        else:\n            self._control.throttle = 0.0\n\n        steer_increment = 3e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n\n        self._control.steer = round(self._steer_cache, 1)\n        self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0\n        self._control.hand_brake = keys[K_SPACE]\n\n    def _parse_json_control(self):\n\n        if self._index < len(self._control_list):\n            self._control = self._control_list[self._index]\n            self._index += 1\n        else:\n            print(\"JSON file has no more entries\")\n\n    def _record_control(self):\n        new_record = {\n            'control': {\n                'throttle': self._control.throttle,\n                'steer': self._control.steer,\n                'brake': self._control.brake,\n                'hand_brake': self._control.hand_brake,\n                'reverse': self._control.reverse,\n                'manual_gear_shift': self._control.manual_gear_shift,\n                'gear': self._control.gear\n            }\n        }\n\n        self._log_data['records'].append(new_record)\n\n    def __del__(self):\n        # Get ready to log user commands\n        if self._mode == \"log\" and self._log_data:\n            with open(self._endpoint, 'w') as fd:\n                json.dump(self._log_data, fd, indent=4, sort_keys=True)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/human_agent_config.txt",
    "content": "mode: log                      # Either 'log' or 'playback'\nfile: test.json                     # path to the file with the controls\n\n\nThis is the configuration file of the human agent. This agent incorporates two modes.\nThe log mode parses the controls given to the vehicle into a dictionary and records them into a .json file.\nThis file can be read by the playback mode to control the vehicle in the same way, resulting in a deterministic agent.\nThe file name can be chosen, and is the second argument of this config file.\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/npc_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an NPC agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\ndef get_entry_point():\n    return 'NpcAgent'\n\nclass NpcAgent(AutonomousAgent):\n\n    \"\"\"\n    NPC autonomous agent to control the ego vehicle\n    \"\"\"\n\n    _agent = None\n    _route_assigned = False\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self.track = Track.SENSORS\n\n        self._agent = None\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n        ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation. \n        \"\"\"\n        if not self._agent:\n\n            # Search for the ego actor\n            hero_actor = None\n            for actor in CarlaDataProvider.get_world().get_actors():\n                if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero':\n                    hero_actor = actor\n                    break\n\n            if not hero_actor:\n                return carla.VehicleControl()\n\n            # Add an agent that follows the route to the ego\n            self._agent = BasicAgent(hero_actor, 30)\n\n            plan = []\n            prev_wp = None\n            for transform, _ in self._global_plan_world_coord:\n                wp = CarlaDataProvider.get_map().get_waypoint(transform.location)\n                if prev_wp:\n                    plan.extend(self._agent.trace_route(prev_wp, wp))\n                prev_wp = wp\n\n            self._agent.set_global_plan(plan)\n\n            return carla.VehicleControl()\n\n        else:\n            return self._agent.run_step()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/ros1_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a ROS autonomous agent interface to control the ego vehicle via a ROS stack\n\"\"\"\n\nfrom __future__ import print_function\n\nimport time\n\nfrom leaderboard.autoagents.ros_base_agent import BridgeHelper, ROSBaseAgent, ROSLauncher\n\nimport roslibpy\n\n\nclass ROS1Server(object):\n    client = roslibpy.Ros(host='localhost', port=9090)\n\n    def __init__(self, debug=True):\n        self._server_process = ROSLauncher(\"server\", ros_version=1, debug=debug)\n\n    def start(self):\n        self._server_process.run(\n            package=\"rosbridge_server\",\n            launch_file=\"rosbridge_websocket.launch\",\n            wait=False\n        )\n        ROS1Server.client.run(30)\n\n    def shutdown(self):\n        self._server_process.terminate()\n        assert not self._server_process.is_alive()\n        ROS1Server.client.close()\n\n\ndef wait_for_message(client, topic, topic_type, timeout=None):\n\n    class _WFM(object):\n        def __init__(self):\n            self.msg = None\n        def cb(self, msg):\n            if self.msg is None:\n                self.msg = msg\n\n    wfm = _WFM()\n    s = None\n    try:\n        s = roslibpy.Topic(client, topic, topic_type, reconnect_on_close=False)\n        s.subscribe(wfm.cb)\n        if timeout is not None:\n            timeout_t = time.time() + timeout\n        while client.is_connected and wfm.msg is None:\n            time.sleep(0.1)\n            if timeout is not None and time.time() >= timeout_t:\n                raise TimeoutError(\"timeout exceeded while waiting for message on topic {}\".format(topic))\n\n    finally:\n        if s is not None:\n            s.unsubscribe()\n\n    return wfm.msg\n\n\ndef wait_for_service(client, service, timeout=None):\n\n    if timeout is not None:\n        timeout_t = time.time() + timeout\n\n    services = client.get_services()\n    while service not in services:\n        time.sleep(0.1)\n        if timeout is not None and time.time() >= timeout_t:\n            raise TimeoutError(\"timeout exceeded while waiting for service {} to be ready\".format(service))\n        services = client.get_services()\n\n\nclass ROS1Agent(ROSBaseAgent):\n\n    ROS_VERSION = 1\n\n    def __init__(self, carla_host, carla_port, debug=False):\n        super(ROS1Agent, self).__init__(self.ROS_VERSION, carla_host, carla_port, debug)\n\n        client = ROS1Server.client\n\n        self._spawn_object_service = roslibpy.Service(client, \"/carla/spawn_object\", \"carla_msgs/SpawnObject\", reconnect_on_close=False)\n        self._destroy_object_service = roslibpy.Service(client, \"/carla/destroy_object\", \"carla_msgs/DestroyObject\", reconnect_on_close=False)\n\n        wait_for_service(client, \"/carla/spawn_object\")\n        wait_for_service(client, \"/carla/destroy_object\")\n\n        self._control_subscriber = roslibpy.Topic(client, \"/carla/hero/vehicle_control_cmd\", \"carla_msgs/CarlaEgoVehicleControl\", queue_length=1, reconnect_on_close=False)\n        self._control_subscriber.subscribe(self._vehicle_control_cmd_callback)\n\n        self._path_publisher = roslibpy.Topic(client, \"/carla/hero/global_plan\", \"carla_msgs/CarlaRoute\", latch=True, reconnect_on_close=False)\n        self._path_gnss_publisher = roslibpy.Topic(client, \"/carla/hero/global_plan_gnss\", \"carla_msgs/CarlaGnssRoute\", latch=True, reconnect_on_close=False)\n\n        wait_for_message(client, \"/carla/hero/status\", \"std_msgs/Bool\")\n\n    @staticmethod\n    def get_ros_version():\n        return ROS1Agent.ROS_VERSION\n\n    def spawn_object(self, type_, id_, transform, attributes, attach_to=0):\n        spawn_point = BridgeHelper.carla2ros_pose(\n            transform.location.x, transform.location.y, transform.location.z,\n            transform.rotation.roll, transform.rotation.pitch, transform.rotation.yaw,\n            to_quat=True\n        )\n        attributes = [{\"key\": str(key), \"value\": str(value)} for key, value in attributes.items()]\n\n        request = roslibpy.ServiceRequest({\n            \"type\": type_,\n            \"id\": id_,\n            \"attach_to\": attach_to,\n            \"transform\": spawn_point,\n            \"random_pose\": False,\n            \"attributes\": attributes,\n        })\n\n        response = self._spawn_object_service.call(request)\n        if response[\"id\"] == -1:\n            raise RuntimeError(\"{} could not be spawned. {}\".format(type_, response[\"error_string\"]))\n        return response[\"id\"]\n\n    def destroy_object(self, uid):\n        request = roslibpy.ServiceRequest({\"id\": uid})\n        response = self._destroy_object_service.call(request)\n        if not response[\"success\"]:\n            raise RuntimeError(\"{} could not be destroyed\".format(uid))\n        return response[\"success\"]\n\n    def run_step(self, input_data, timestamp):\n        return super(ROS1Agent, self).run_step(input_data, timestamp)\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        super(ROS1Agent, self).set_global_plan(global_plan_gps, global_plan_world_coord)\n\n        poses = []\n        for wp in self._global_plan_world_coord:\n            poses.append(BridgeHelper.carla2ros_pose(\n                wp[0].location.x, wp[0].location.y, wp[0].location.z,\n                wp[0].rotation.roll, wp[0].rotation.pitch, wp[0].rotation.yaw,\n                to_quat=True\n            ))\n\n        self._path_publisher.publish(roslibpy.Message(\n            {\n                \"header\": {\n                    \"frame_id\": \"/map\"\n                },\n                \"road_options\": [ int(wp[1]) for wp in self._global_plan_world_coord ],\n                \"poses\": [ pose for pose in poses ]\n            }))\n\n        self._path_gnss_publisher.publish(roslibpy.Message(\n            {\n                \"header\": {\n                    \"frame_id\": \"/map\"\n                },\n                \"road_options\": [ int(wp[1]) for wp in self._global_plan ],\n                \"coordinates\": [ {\"latitude\": wp[0][\"lat\"], \"longitude\": wp[0][\"lon\"], \"altitude\": wp[0][\"z\"]} for wp in self._global_plan ]\n            }))\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        self._control_subscriber.unsubscribe()\n        self._path_publisher.unadvertise()\n        self._spawn_object_service.unadvertise()\n        self._destroy_object_service.unadvertise()\n\n        super(ROS1Agent, self).destroy()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/ros2_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a ROS autonomous agent interface to control the ego vehicle via a ROS2 stack\n\"\"\"\n\nfrom __future__ import print_function\n\nimport threading\n\nimport carla\n\nfrom leaderboard.autoagents.ros_base_agent import BridgeHelper, ROSBaseAgent\n\nimport rclpy\nfrom rclpy.node import Node\nfrom rclpy.qos import DurabilityPolicy, QoSProfile\nfrom rclpy.task import Future\n\nfrom carla_msgs.msg import CarlaEgoVehicleControl, CarlaRoute, CarlaGnssRoute\nfrom carla_msgs.srv import SpawnObject, DestroyObject\nfrom diagnostic_msgs.msg import KeyValue\nfrom geometry_msgs.msg import Point, Pose, Quaternion\nfrom sensor_msgs.msg import NavSatFix\nfrom std_msgs.msg import Bool\n\n\ndef wait_for_message(node, topic, topic_type, timeout=None):\n\n    s = None\n    try:\n        future = Future()\n        s = node.create_subscription(\n            topic_type,\n            topic,\n            lambda msg: future.set_result(msg.data),\n            qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))\n        rclpy.spin_until_future_complete(node, future, timeout)\n\n    finally:\n        if s is not None:\n            node.destroy_subscription(s)\n\n    return future.result()\n\n\nclass ROS2Agent(ROSBaseAgent):\n\n    \"\"\"\n    Autonomous agent base class. All user agents have to be derived from this class\n    \"\"\"\n\n    ROS_VERSION = 2\n\n    def __init__(self, carla_host, carla_port, debug=False):\n        super(ROS2Agent, self).__init__(self.ROS_VERSION, carla_host, carla_port, debug)\n\n        rclpy.init(args=None)\n        self.ros_node = rclpy.create_node(\"leaderboard_node\")\n\n        self._spawn_object_service = self.ros_node.create_client(SpawnObject, \"/carla/spawn_object\")\n        self._destroy_object_service = self.ros_node.create_client(DestroyObject, \"/carla/destroy_object\")\n\n        self._spawn_object_service.wait_for_service()\n        self._destroy_object_service.wait_for_service()\n\n        self._path_publisher = self.ros_node.create_publisher(CarlaRoute, \"/carla/hero/global_plan\", qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))\n        self._path_gnss_publisher = self.ros_node.create_publisher(CarlaGnssRoute, \"/carla/hero/global_plan_gnss\", qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))\n        \n        self.ctrl_subscriber = self.ros_node.create_subscription(CarlaEgoVehicleControl, \"/carla/hero/vehicle_control_cmd\", self._vehicle_control_cmd_callback, qos_profile=QoSProfile(depth=1))\n\n        wait_for_message(self.ros_node, \"/carla/hero/status\", Bool)\n\n        self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros_node,))\n        self.spin_thread.start()\n\n    @staticmethod\n    def get_ros_version():\n        return ROS2Agent.ROS_VERSION\n\n    def spawn_object(self, type_, id_, transform, attributes, attach_to=0):\n        spawn_point = BridgeHelper.carla2ros_pose(\n            transform.location.x, transform.location.y, transform.location.z,\n            transform.rotation.roll, transform.rotation.pitch, transform.rotation.yaw,\n            to_quat=True\n        )\n\n        request = SpawnObject.Request()\n        request.type = type_\n        request.id = id_\n        request.attach_to = attach_to\n        request.transform = Pose(position=Point(**spawn_point[\"position\"]), orientation=Quaternion(**spawn_point[\"orientation\"]))\n        request.random_pose = False\n        request.attributes.extend([\n            KeyValue(key=str(k), value=str(v)) for k,v in attributes.items()\n        ])\n\n        # Call the service synchronously.\n        response = self._spawn_object_service.call(request)\n        if response.id == -1:\n            raise RuntimeError(\"{} could not be spawned. {}\".format(type_, response[\"error_string\"]))\n        return response.id\n\n    def destroy_object(self, uid):\n        request = DestroyObject.Request()\n        request.id = uid\n\n        # Call the servive syncrhonoulsy\n        response = self._destroy_object_service.call(request)\n        if not response.success:\n            raise RuntimeError(\"{} could not be destroyed\".format(uid))\n        return response.success\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        super(ROS2Agent, self).set_global_plan(global_plan_gps, global_plan_world_coord)\n\n        path = CarlaRoute()\n        for wp in self._global_plan_world_coord:\n            path.road_options.append(int(wp[1]))\n            pose = BridgeHelper.carla2ros_pose(\n                wp[0].location.x, wp[0].location.y, wp[0].location.z,\n                wp[0].rotation.roll, wp[0].rotation.pitch, wp[0].rotation.yaw,\n                to_quat=True\n            )\n            path.poses.append(\n                Pose(position=Point(**pose[\"position\"]), orientation=Quaternion(**pose[\"orientation\"])))\n        self._path_publisher.publish(path)\n\n        path_gnss = CarlaGnssRoute()\n        for wp in self._global_plan:\n            path_gnss.road_options.append(wp[1])\n            path.poses.append(\n                NavSatFix(latitude=wp[0][\"lat\"], longitude=wp[0][\"lon\"], altitude=wp[0][\"z\"]))\n        self._path_gnss_publisher.publish(path_gnss)\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        self.ros_node.destroy_node()\n        rclpy.shutdown()\n        self.spin_thread.join()\n\n        super(ROS2Agent, self).destroy()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/autoagents/ros_base_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a base ROS autonomous agent interface to control the ego vehicle via a ROS1/ROS2 stack\n\"\"\"\n\nfrom __future__ import print_function\n\nimport logging\nimport logging.handlers\nimport os\nimport queue\nimport threading\n\nimport carla\nimport pexpect\nimport transforms3d\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\nEPSILON = 0.001\n\n\nclass ROSLogger(object):\n\n    def __init__(self, name):\n        self.name = name\n    \n        self.logger = logging.getLogger(self.name)\n        self.logger.setLevel(logging.INFO)\n\n        logger_path = os.path.join(\"log\", \"ros\")\n        if not os.path.isdir(logger_path):\n            os.makedirs(logger_path)\n\n        self.handler = logging.handlers.RotatingFileHandler(os.path.join(logger_path, self.name + \".log\"), maxBytes=25*1024*1024, backupCount=3)\n        self.handler.setLevel(logging.INFO)\n        self.handler.setFormatter(logging.Formatter(\"%(message)s\"))\n\n        self.logger.addHandler(self.handler)\n\n    def write(self, data):\n        self.logger.info(data.strip())\n\n    def flush(self):\n        pass\n\n    def fileno(self):\n        return self.handler.stream.fileno()\n    \n    def destroy(self):\n        self.logger.removeHandler(self.handler)\n\n\nclass ROSLauncher(object):\n\n    def __init__(self, app_name, ros_version, debug=False):\n        self.app_name = app_name\n        self.ros_version = ros_version\n        # force always debugging\n        self.debug = True\n\n        self._process = None\n\n        self._log_thread = threading.Thread(target=self.log)\n        if self.debug:\n            self._logger = ROSLogger(self.app_name)\n\n    def run(self, package, launch_file, parameters={}, wait=False):\n        cmdline = [\n            \"roslaunch\" if self.ros_version == 1 else \"ros2 launch\",\n            package,\n            launch_file,\n            \" \".join([\"{}:={}\".format(k, v) for k, v in parameters.items()]),\n            \"--wait\" if wait and self.ros_version == 1 else \"\"\n        ]\n        cmdline = \" \".join(cmdline)\n        self._process = pexpect.spawn(cmdline, encoding=\"utf-8\", logfile=self._logger if self.debug else None)\n        self._log_thread.start()\n\n    def log(self):\n        while True:\n            try:\n                self._process.expect([pexpect.TIMEOUT], timeout=0.1)\n            except pexpect.exceptions.EOF as e:\n                break\n\n    def is_alive(self):\n        if self._process is None:\n            return False\n        return self._process.isalive()\n\n    def terminate(self):\n        assert self._process is not None\n        self._process.terminate()\n\n        self._log_thread.join()\n        if self.debug:\n            self._logger.destroy()\n\n\nclass BridgeHelper(object):\n\n    @classmethod\n    def carla2ros_pose(cls, x, y, z, roll, pitch, yaw, to_quat=False):\n        out_position = {\"x\": x, \"y\": -y, \"z\": z}\n        out_orientation = {\"roll\": roll, \"pitch\": -pitch, \"yaw\": -yaw}\n        if to_quat:\n            out_orientation = cls.rpy2quat(\n                out_orientation[\"roll\"], out_orientation[\"pitch\"], out_orientation[\"yaw\"]\n            )\n        return {\n            \"position\": out_position,\n            \"orientation\": out_orientation\n        }\n\n    @staticmethod\n    def rpy2quat(roll, pitch, yaw):\n        quat = transforms3d.euler.euler2quat(roll, pitch, yaw)\n        return {\"x\": quat[1], \"y\": quat[2], \"z\": quat[3], \"w\": quat[0]}\n\n\nclass ROSBaseAgent(AutonomousAgent):\n\n    \"\"\"\n    Base class for ROS-based stacks.\n\n    The sensor data is published using carla-ros-bridge. You can find details about\n    the utilized datatypes there.\n    \"\"\"\n\n    def __init__(self, ros_version, carla_host, carla_port, debug=False):\n        super(ROSBaseAgent, self).__init__(carla_host, carla_port, debug)\n\n        self._bridge_process = ROSLauncher(\"bridge\", ros_version=ros_version, debug=debug)\n        self._bridge_process.run(\n            package=\"carla_ros_bridge\",\n            launch_file=\"carla_ros_bridge.launch\" if ros_version == 1 else \"carla_ros_bridge.launch.py\",\n            parameters={\n                \"host\": carla_host,\n                \"port\": carla_port,\n                \"timeout\": 60,\n                \"synchronous_mode\": True,\n                \"passive\": True,\n                \"register_all_sensors\": False,\n                \"ego_vehicle_role_name\": \"\\\"''\\\"\"\n            },\n            wait=True\n        )\n\n        self._agent_process = ROSLauncher(\"agent\", ros_version=ros_version, debug=debug)\n        self._agent_process.run(\n            **self.get_ros_entrypoint(),\n            wait=True\n        )\n\n        self._control_queue = queue.Queue(1)\n        self._last_control_timestamp = None\n\n    def get_ros_entrypoint(self):\n        raise NotImplementedError\n\n    def spawn_object(self, type_, id_, transform, attributes, attach_to=0):\n        raise NotImplementedError\n\n    def destroy_object(self, uid):\n        raise NotImplementedError\n\n    def _vehicle_control_cmd_callback(self, control_msg):\n        if isinstance(control_msg, dict):\n            control_timestamp = control_msg[\"header\"][\"stamp\"][\"secs\"] + control_msg[\"header\"][\"stamp\"][\"nsecs\"] * 1e-9\n            control = carla.VehicleControl(\n                steer=control_msg[\"steer\"],\n                throttle=control_msg[\"throttle\"],\n                brake=control_msg[\"brake\"],\n                hand_brake=control_msg[\"hand_brake\"],\n                reverse=control_msg[\"reverse\"],\n                manual_gear_shift=control_msg[\"manual_gear_shift\"],\n                gear=control_msg[\"gear\"]\n            )\n        else:\n            control_timestamp = control_msg.header.stamp.sec + control_msg.header.stamp.nanosec * 1e-9\n            control = carla.VehicleControl(\n                steer=control_msg.steer,\n                throttle=control_msg.throttle,\n                brake=control_msg.brake,\n                hand_brake=control_msg.hand_brake,\n                reverse=control_msg.reverse,\n                manual_gear_shift=control_msg.manual_gear_shift,\n                gear=control_msg.gear\n            )\n\n        # Checks that the received control timestamp is not repeated.\n        if self._last_control_timestamp is not None and abs(self._last_control_timestamp - control_timestamp) < EPSILON:\n            print(\n                \"\\033[93mWARNING: A new vehicle command with a repeated timestamp has been received {} .\\033[0m\".format(control_timestamp),\n                \"\\033[93mThis vehicle command will be ignored.\\033[0m\",\n                sep=\" \")\n            return\n\n        # Checks that the received control timestamp is the expected one.\n        # We need to retrieve the simulation time directly from the CARLA snapshot instead of using the GameTime object to avoid\n        # a race condition between the execution of this callback and the update of the GameTime internal variables.\n        carla_timestamp = CarlaDataProvider.get_world().get_snapshot().timestamp.elapsed_seconds\n        if abs(control_timestamp - carla_timestamp) > EPSILON:\n            print(\n                \"\\033[93mWARNING: Expecting a vehicle command with timestamp {} but the timestamp received was {} .\\033[0m\".format(carla_timestamp, control_timestamp),\n                \"\\033[93mThis vehicle command will be ignored.\\033[0m\",\n                sep=\" \")\n            return\n\n        self._last_control_timestamp = control_timestamp\n        try:\n            self._control_queue.put_nowait((control_timestamp, control))\n        except queue.Full:\n            print(\n                \"\\033[93mWARNING: A new vehicle command has been received while the previous one has not been yet processed.\\033[0m\",\n                \"\\033[93mThis vehicle command will be ignored.\\033[0m\",\n                sep=\" \")\n\n\n    def run_step(self, _, timestamp):\n        assert self._bridge_process.is_alive()\n        assert self._agent_process.is_alive()\n\n        #control_timestamp, control = self._control_queue.get(True)\n        try:\n            control_timestamp, control = self._control_queue.get(True, 1.0)\n        except queue.Empty:\n            control_timestamp, control = 0, carla.VehicleControl()\n\n        carla_timestamp = CarlaDataProvider.get_world().get_snapshot().timestamp.elapsed_seconds\n        if abs(control_timestamp - carla_timestamp) > EPSILON:\n            print(\n                \"\\033[93mWARNING: Expecting a vehicle command with timestamp {} but the timestamp received was {} .\\033[0m\".format(carla_timestamp, control_timestamp),\n                 sep=\" \")\n\n        return control\n\n    def destroy(self):\n        self._agent_process.terminate()\n        self._bridge_process.terminate()\n\n        assert not self._agent_process.is_alive()\n        assert not self._bridge_process.is_alive()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/envs/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/envs/sensor_interface.py",
    "content": "import copy\nimport logging\nimport numpy as np\nimport os\nimport time\nfrom threading import Thread\n\nfrom queue import Queue\nfrom queue import Empty\n\nimport carla\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\n\ndef threaded(fn):\n    def wrapper(*args, **kwargs):\n        thread = Thread(target=fn, args=args, kwargs=kwargs)\n        thread.setDaemon(True)\n        thread.start()\n\n        return thread\n    return wrapper\n\n\nclass SensorConfigurationInvalid(Exception):\n    \"\"\"\n    Exceptions thrown when the sensors used by the agent are not allowed for that specific submissions\n    \"\"\"\n\n    def __init__(self, message):\n        super(SensorConfigurationInvalid, self).__init__(message)\n\n\nclass SensorReceivedNoData(Exception):\n    \"\"\"\n    Exceptions thrown when the sensors used by the agent take too long to receive data\n    \"\"\"\n\n    def __init__(self, message):\n        super(SensorReceivedNoData, self).__init__(message)\n\n\nclass GenericMeasurement(object):\n    def __init__(self, data, frame):\n        self.data = data\n        self.frame = frame\n\n\nclass BaseReader(object):\n    def __init__(self, vehicle, reading_frequency=1.0):\n        self._vehicle = vehicle\n        self._reading_frequency = reading_frequency\n        self._callback = None\n        self._run_ps = True\n        self.run()\n\n    def __call__(self):\n        pass\n\n    @threaded\n    def run(self):\n        first_time = True\n        latest_time = GameTime.get_time()\n        while self._run_ps:\n            if self._callback is not None:\n                current_time = GameTime.get_time()\n\n                # Second part forces the sensors to send data at the first tick, regardless of frequency\n                if current_time - latest_time > (1 / self._reading_frequency) \\\n                        or (first_time and GameTime.get_frame() != 0):\n                    self._callback(GenericMeasurement(self.__call__(), GameTime.get_frame()))\n                    latest_time = GameTime.get_time()\n                    first_time = False\n\n                else:\n                    time.sleep(0.001)\n\n    def listen(self, callback):\n        # Tell that this function receives what the producer does.\n        self._callback = callback\n\n    def stop(self):\n        self._run_ps = False\n\n    def destroy(self):\n        self._run_ps = False\n\n\nclass SpeedometerReader(BaseReader):\n    \"\"\"\n    Sensor to measure the speed of the vehicle.\n    \"\"\"\n    MAX_CONNECTION_ATTEMPTS = 10\n\n    def _get_forward_speed(self, transform=None, velocity=None):\n        \"\"\" Convert the vehicle transform directly to forward speed \"\"\"\n        if not velocity:\n            velocity = self._vehicle.get_velocity()\n        if not transform:\n            transform = self._vehicle.get_transform()\n\n        vel_np = np.array([velocity.x, velocity.y, velocity.z])\n        pitch = np.deg2rad(transform.rotation.pitch)\n        yaw = np.deg2rad(transform.rotation.yaw)\n        orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)])\n        speed = np.dot(vel_np, orientation)\n        return speed\n\n    def __call__(self):\n        \"\"\" We convert the vehicle physics information into a convenient dictionary \"\"\"\n\n        # protect this access against timeout\n        attempts = 0\n        while attempts < self.MAX_CONNECTION_ATTEMPTS:\n            try:\n                velocity = self._vehicle.get_velocity()\n                transform = self._vehicle.get_transform()\n                break\n            except Exception:\n                attempts += 1\n                time.sleep(0.2)\n                continue\n\n        return {'speed': self._get_forward_speed(transform=transform, velocity=velocity)}\n\n\nclass OpenDriveMapReader(BaseReader):\n    def __call__(self):\n        return {'opendrive': CarlaDataProvider.get_map().to_opendrive()}\n\n\nclass CallBack(object):\n    def __init__(self, tag, sensor_type, sensor, data_provider):\n        self._tag = tag\n        self._data_provider = data_provider\n\n        self._data_provider.register_sensor(tag, sensor_type, sensor)\n\n    def __call__(self, data):\n        if isinstance(data, carla.libcarla.Image):\n            self._parse_image_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.LidarMeasurement):\n            self._parse_lidar_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.RadarMeasurement):\n            self._parse_radar_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.GnssMeasurement):\n            self._parse_gnss_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.IMUMeasurement):\n            self._parse_imu_cb(data, self._tag)\n        elif isinstance(data, GenericMeasurement):\n            self._parse_pseudosensor(data, self._tag)\n        else:\n            logging.error('No callback method for this sensor.')\n\n    # Parsing CARLA physical Sensors\n    def _parse_image_cb(self, image, tag):\n        array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n        array = copy.deepcopy(array)\n        array = np.reshape(array, (image.height, image.width, 4))\n        self._data_provider.update_sensor(tag, array, image.frame)\n\n    def _parse_lidar_cb(self, lidar_data, tag):\n        points = np.frombuffer(lidar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        self._data_provider.update_sensor(tag, points, lidar_data.frame)\n\n    def _parse_radar_cb(self, radar_data, tag):\n        # [depth, azimuth, altitute, velocity]\n        points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        points = np.flip(points, 1)\n        self._data_provider.update_sensor(tag, points, radar_data.frame)\n\n    def _parse_gnss_cb(self, gnss_data, tag):\n        array = np.array([gnss_data.latitude,\n                          gnss_data.longitude,\n                          gnss_data.altitude], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, gnss_data.frame)\n\n    def _parse_imu_cb(self, imu_data, tag):\n        array = np.array([imu_data.accelerometer.x,\n                          imu_data.accelerometer.y,\n                          imu_data.accelerometer.z,\n                          imu_data.gyroscope.x,\n                          imu_data.gyroscope.y,\n                          imu_data.gyroscope.z,\n                          imu_data.compass,\n                         ], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, imu_data.frame)\n\n    def _parse_pseudosensor(self, package, tag):\n        self._data_provider.update_sensor(tag, package.data, package.frame)\n\n\nclass SensorInterface(object):\n    def __init__(self):\n        self._sensors_objects = {}\n        self._data_buffers = Queue()\n        self._queue_timeout = 300\n\n        # Only sensor that doesn't get the data on tick, needs special treatment\n        self._opendrive_tag = None\n\n    def register_sensor(self, tag, sensor_type, sensor):\n        if tag in self._sensors_objects:\n            raise SensorConfigurationInvalid(\"Duplicated sensor tag [{}]\".format(tag))\n\n        self._sensors_objects[tag] = sensor\n\n        if sensor_type == 'sensor.opendrive_map': \n            self._opendrive_tag = tag\n\n    def update_sensor(self, tag, data, frame):\n        if tag not in self._sensors_objects:\n            raise SensorConfigurationInvalid(\"The sensor with tag [{}] has not been created!\".format(tag))\n\n        self._data_buffers.put((tag, frame, data))\n\n    def get_data(self, frame):\n        \"\"\"Read the queue to get the sensors data\"\"\"\n        try:\n            data_dict = {}\n            while len(data_dict.keys()) < len(self._sensors_objects.keys()):\n                # Don't wait for the opendrive sensor\n                if self._opendrive_tag and self._opendrive_tag not in data_dict.keys() \\\n                        and len(self._sensors_objects.keys()) == len(data_dict.keys()) + 1:\n                    break\n\n                sensor_data = self._data_buffers.get(True, self._queue_timeout)\n                if sensor_data[1] != frame:\n                    continue\n                data_dict[sensor_data[0]] = ((sensor_data[1], sensor_data[2]))\n\n        except Empty:\n            raise SensorReceivedNoData(\"A sensor took too long to send their data\")\n\n        return data_dict\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/leaderboard_evaluator.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Corporation.\n# authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCARLA Challenge Evaluator Routes\n\nProvisional code to evaluate Autonomous Agents for the CARLA Autonomous Driving challenge\n\"\"\"\nfrom __future__ import print_function\n\nimport traceback\nimport argparse\nfrom argparse import RawTextHelpFormatter\nfrom distutils.version import LooseVersion\nimport importlib\nimport os\nimport pkg_resources\nimport sys\nimport carla\nimport signal\n\nfrom srunner.scenariomanager.carla_data_provider import *\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.watchdog import Watchdog\n\nfrom leaderboard.scenarios.scenario_manager import ScenarioManager\nfrom leaderboard.scenarios.route_scenario import RouteScenario\nfrom leaderboard.envs.sensor_interface import SensorConfigurationInvalid\nfrom leaderboard.autoagents.agent_wrapper import AgentError, validate_sensor_configuration, TickRuntimeError\nfrom leaderboard.utils.statistics_manager import StatisticsManager, FAILURE_MESSAGES\nfrom leaderboard.utils.route_indexer import RouteIndexer\nimport atexit\nimport subprocess\nimport time\nimport random\nfrom datetime import datetime\n\nsensors_to_icons = {\n    'sensor.camera.rgb':        'carla_camera',\n    'sensor.lidar.ray_cast':    'carla_lidar',\n    'sensor.other.radar':       'carla_radar',\n    'sensor.other.gnss':        'carla_gnss',\n    'sensor.other.imu':         'carla_imu',\n    'sensor.opendrive_map':     'carla_opendrive_map',\n    'sensor.speedometer':       'carla_speedometer'\n}\n\nimport socket\n\ndef find_free_port(starting_port):\n    port = starting_port\n    while True:\n        try:\n            with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:\n                s.bind((\"localhost\", port))\n                return port\n        except OSError:\n            port += 1\n\ndef get_weather_id(weather_conditions):\n    from xml.etree import ElementTree as ET\n    tree = ET.parse('leaderboard/data/weather.xml')\n    root = tree.getroot()\n    def conditions_match(weather, conditions):\n        for (key, value) in weather:\n            if key == 'route_percentage' : continue\n            if str(getattr(conditions, key))!= value:\n                return False\n        return True\n    for case in root.findall('case'):\n        weather = case[0].items()\n        if conditions_match(weather, weather_conditions):\n            return case.items()[0][1]\n    return None\n\nclass LeaderboardEvaluator(object):\n    \"\"\"\n    Main class of the Leaderboard. Everything is handled from here,\n    from parsing the given files, to preparing the simulation, to running the route.\n    \"\"\"\n\n    # Tunable parameters\n    client_timeout = 300.0  # in seconds\n    frame_rate = 20.0      # in Hz\n\n    def __init__(self, args, statistics_manager):\n        \"\"\"\n        Setup CARLA client and world\n        Setup ScenarioManager\n        \"\"\"\n        self.world = None\n        self.manager = None\n        self.sensors = None\n        self.sensors_initialized = False\n        self.sensor_icons = []\n        self.agent_instance = None\n        self.route_scenario = None\n\n        self.statistics_manager = statistics_manager\n\n        # This is the ROS1 bridge server instance. This is not encapsulated inside the ROS1 agent because the same\n        # instance is used on all the routes (i.e., the server is not restarted between routes). This is done\n        # to avoid reconnection issues between the server and the roslibpy client.\n        self._ros1_server = None\n\n        # Setup the simulation\n        self.client, self.client_timeout, self.traffic_manager = self._setup_simulation(args)\n\n        dist = pkg_resources.get_distribution(\"carla\")\n        if dist.version != 'leaderboard':\n            if LooseVersion(dist.version) < LooseVersion('0.9.10'):\n                raise ImportError(\"CARLA version 0.9.10.1 or newer required. CARLA version found: {}\".format(dist))\n\n        # Load agent\n        module_name = os.path.basename(args.agent).split('.')[0]\n        sys.path.insert(0, os.path.dirname(args.agent))\n        self.module_agent = importlib.import_module(module_name)\n\n        # Create the ScenarioManager\n        self.manager = ScenarioManager(args.timeout, self.statistics_manager, args.debug)\n\n        # Time control for summary purposes\n        self._start_time = GameTime.get_time()\n        self._end_time = None\n\n        # Prepare the agent timer\n        self._agent_watchdog = None\n        signal.signal(signal.SIGINT, self._signal_handler)\n\n        self._client_timed_out = False\n\n    def _signal_handler(self, signum, frame):\n        \"\"\"\n        Terminate scenario ticking when receiving a signal interrupt.\n        Either the agent initialization watchdog is triggered, or the runtime one at scenario manager\n        \"\"\"\n        if self._agent_watchdog and not self._agent_watchdog.get_status():\n            raise RuntimeError(\"Timeout: Agent took longer than {}s to setup\".format(self.client_timeout))\n        elif self.manager:\n            self.manager.signal_handler(signum, frame)\n\n    def __del__(self):\n        \"\"\"\n        Cleanup and delete actors, ScenarioManager and CARLA world\n        \"\"\"\n        if hasattr(self, 'manager') and self.manager:\n            del self.manager\n        if hasattr(self, 'world') and self.world:\n            del self.world\n\n    def _get_running_status(self):\n        \"\"\"\n        returns:\n           bool: False if watchdog exception occured, True otherwise\n        \"\"\"\n        if self._agent_watchdog:\n            return self._agent_watchdog.get_status()\n        return False\n\n    def _cleanup(self):\n        \"\"\"\n        Remove and destroy all actors\n        \"\"\"\n        CarlaDataProvider.cleanup()\n\n        if self._agent_watchdog:\n            self._agent_watchdog.stop()\n\n        try:\n            if self.agent_instance:\n                self.agent_instance.destroy()\n                self.agent_instance = None\n        except Exception as e:\n            print(\"\\n\\033[91mFailed to stop the agent:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n        if self.route_scenario:\n            self.route_scenario.remove_all_actors()\n            self.route_scenario = None\n            if self.statistics_manager:\n                self.statistics_manager.remove_scenario()\n\n        if self.manager:\n            self._client_timed_out = not self.manager.get_running_status()\n            self.manager.cleanup()\n\n        # Make sure no sensors are left streaming\n        alive_sensors = self.world.get_actors().filter('*sensor*')\n        for sensor in alive_sensors:\n            sensor.stop()\n            sensor.destroy()\n\n    def _setup_simulation(self, args):\n        \"\"\"\n        Prepares the simulation by getting the client, and setting up the world and traffic manager settings\n        \"\"\"\n        self.carla_path = os.environ[\"CARLA_ROOT\"]\n        args.port = find_free_port(args.port)\n        cmd1 = f\"{os.path.join(self.carla_path, 'CarlaUE4.sh')} -RenderOffScreen -nosound -carla-rpc-port={args.port} -graphicsadapter={args.gpu_rank}\"\n        self.server = subprocess.Popen(cmd1, shell=True, preexec_fn=os.setsid)\n        print(cmd1, self.server.returncode, flush=True)\n        atexit.register(os.killpg, self.server.pid, signal.SIGKILL)\n        time.sleep(30)\n            \n        attempts = 0\n        num_max_restarts = 20\n        while attempts < num_max_restarts:\n            try:\n                client = carla.Client(args.host, args.port)\n                if args.timeout:\n                    client_timeout = args.timeout\n                client.set_timeout(client_timeout)\n\n                settings = carla.WorldSettings(\n                    synchronous_mode = True,\n                    fixed_delta_seconds = 1.0 / self.frame_rate,\n                    deterministic_ragdolls = True,\n                    spectator_as_ego = False\n                )\n                client.get_world().apply_settings(settings)\n                print(f\"load_world success , attempts={attempts}\", flush=True)\n                break\n            except Exception as e:\n                print(f\"load_world failed , attempts={attempts}\", flush=True)\n                print(e, flush=True)\n                attempts += 1\n                time.sleep(5)\n        attempts = 0\n        num_max_restarts = 40\n        while attempts < num_max_restarts:\n            try:\n                args.traffic_manager_port = find_free_port(args.traffic_manager_port)\n                traffic_manager = client.get_trafficmanager(args.traffic_manager_port)\n                traffic_manager.set_synchronous_mode(True)\n                traffic_manager.set_hybrid_physics_mode(True)\n                print(f\"traffic_manager init success, try_time={attempts}\", flush=True)\n                break\n            except Exception as e:\n                print(f\"traffic_manager init fail, try_time={attempts}\", flush=True)\n                print(e, flush=True)\n                attempts += 1\n                time.sleep(5)\n        return client, client_timeout, traffic_manager\n\n    def _reset_world_settings(self):\n        \"\"\"\n        Changes the modified world settings back to asynchronous\n        \"\"\"\n        # Has simulation failed?\n        if self.world and self.manager and not self._client_timed_out:\n            # Reset to asynchronous mode\n            self.world.tick()  # TODO: Make sure all scenario actors have been destroyed\n            settings = self.world.get_settings()\n            settings.synchronous_mode = False\n            settings.fixed_delta_seconds = None\n            settings.deterministic_ragdolls = False\n            settings.spectator_as_ego = True\n            self.world.apply_settings(settings)\n\n            # Make the TM back to async\n            self.traffic_manager.set_synchronous_mode(False)\n            self.traffic_manager.set_hybrid_physics_mode(False)\n\n    def _load_and_wait_for_world(self, args, town):\n        \"\"\"\n        Load a new CARLA world without changing the settings and provide data to CarlaDataProvider\n        \"\"\"\n        self.world = self.client.load_world(town, reset_settings=False)\n\n        # Large Map settings are always reset, for some reason\n        settings = self.world.get_settings()\n        settings.tile_stream_distance = 650\n        settings.actor_active_distance = 650\n        self.world.apply_settings(settings)\n\n        self.world.reset_all_traffic_lights()\n        CarlaDataProvider.set_client(self.client)\n        CarlaDataProvider.set_traffic_manager_port(args.traffic_manager_port)\n        CarlaDataProvider.set_world(self.world)\n\n        # This must be here so that all route repetitions use the same 'unmodified' seed\n        self.traffic_manager.set_random_device_seed(args.traffic_manager_seed)\n\n        # Wait for the world to be ready\n        self.world.tick()\n\n        map_name = CarlaDataProvider.get_map().name.split(\"/\")[-1]\n        if map_name != town:\n            raise Exception(\"The CARLA server uses the wrong map!\"\n                            \" This scenario requires the use of map {}\".format(town))\n\n    def _register_statistics(self, route_index, entry_status, crash_message=\"\"):\n        \"\"\"\n        Computes and saves the route statistics\n        \"\"\"\n        print(\"\\033[1m> Registering the route statistics\\033[0m\", flush=True)\n        self.statistics_manager.save_entry_status(entry_status)\n        self.statistics_manager.compute_route_statistics(\n            route_index, self.manager.scenario_duration_system, self.manager.scenario_duration_game, crash_message\n        )\n\n    def _load_and_run_scenario(self, args, config):\n        \"\"\"\n        Load and run the scenario given by config.\n\n        Depending on what code fails, the simulation will either stop the route and\n        continue from the next one, or report a crash and stop.\n        \"\"\"\n        crash_message = \"\"\n        entry_status = \"Started\"\n\n        print(\"\\n\\033[1m========= Preparing {} (repetition {}) =========\\033[0m\".format(config.name, config.repetition_index), flush=True)\n\n        # Prepare the statistics of the route\n        route_name = f\"{config.name}_rep{config.repetition_index}\"\n        scenario_name = config.scenario_configs[0].name\n        town_name = str(config.town)\n        weather_id = get_weather_id(config.weather[0][1])\n        currentDateAndTime = datetime.now()\n        currentTime = currentDateAndTime.strftime(\"%m_%d_%H_%M_%S\")\n        save_name = f\"{route_name}_{town_name}_{scenario_name}_{weather_id}_{currentTime}\"\n        self.statistics_manager.create_route_data(route_name, scenario_name, weather_id, save_name, town_name, config.index)\n\n        print(\"\\033[1m> Loading the world\\033[0m\", flush=True)\n\n        # Load the world and the scenario\n        try:\n            self._load_and_wait_for_world(args, config.town)\n            self.route_scenario = RouteScenario(world=self.world, config=config, debug_mode=args.debug)\n            self.statistics_manager.set_scenario(self.route_scenario)\n\n        except Exception:\n            # The scenario is wrong -> set the ejecution to crashed and stop\n            print(\"\\n\\033[91mThe scenario could not be loaded:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Simulation\"]\n            self._register_statistics(config.index, entry_status, crash_message)\n            self._cleanup()\n            return True\n\n        print(\"\\033[1m> Setting up the agent\\033[0m\", flush=True)\n\n        # Set up the user's agent, and the timer to avoid freezing the simulation\n        try:\n            self._agent_watchdog = Watchdog(args.timeout)\n            self._agent_watchdog.start()\n            agent_class_name = getattr(self.module_agent, 'get_entry_point')()\n            agent_class_obj = getattr(self.module_agent, agent_class_name)\n\n            # Start the ROS1 bridge server only for ROS1 based agents.\n            if getattr(agent_class_obj, 'get_ros_version')() == 1 and self._ros1_server is None:\n                from leaderboard.autoagents.ros1_agent import ROS1Server\n                self._ros1_server = ROS1Server()\n                self._ros1_server.start()\n\n            self.agent_instance = agent_class_obj(args.host, args.port, args.debug)\n            self.agent_instance.set_global_plan(self.route_scenario.gps_route, self.route_scenario.route)\n            args.agent_config = args.agent_config + '+' + save_name\n            #import pdb;pdb.set_trace()\n            self.agent_instance.setup(args.agent_config, [3], \"sparsedrive\")\n\n            # Check and store the sensors\n            if not self.sensors:\n                self.sensors = self.agent_instance.sensors()\n                track = self.agent_instance.track\n\n                validate_sensor_configuration(self.sensors, track, args.track)\n\n                self.sensor_icons = [sensors_to_icons[sensor['type']] for sensor in self.sensors]\n                self.statistics_manager.save_sensors(self.sensor_icons)\n                self.statistics_manager.write_statistics()\n\n                self.sensors_initialized = True\n\n            self._agent_watchdog.stop()\n            self._agent_watchdog = None\n\n        except SensorConfigurationInvalid as e:\n            # The sensors are invalid -> set the ejecution to rejected and stop\n            print(\"\\n\\033[91mThe sensor's configuration used is invalid:\", flush=True)\n            print(f\"{e}\\033[0m\\n\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Sensors\"]\n            self._register_statistics(config.index, entry_status, crash_message)\n            self._cleanup()\n            return True\n\n        except Exception as e:\n            # The agent setup has failed -> start the next route\n            print(\"\\n\\033[91mCould not set up the required agent:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n            print(f\"{e}\\033[0m\\n\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Agent_init\"]\n            self._register_statistics(config.index, entry_status, crash_message)\n            self._cleanup()\n            return True\n\n        print(\"\\033[1m> Running the route\\033[0m\", flush=True)\n\n        # Run the scenario\n        try:\n            # Load scenario and run it\n            if args.record:\n                self.client.start_recorder(\"{}/{}_rep{}.log\".format(args.record, config.name, config.repetition_index))\n            self.manager.load_scenario(self.route_scenario, self.agent_instance, config.index, config.repetition_index)\n            self.manager.tick_count = 0\n            self.manager.run_scenario()\n\n        except AgentError:\n            # The agent has failed -> stop the route\n            print(\"\\n\\033[91mStopping the route, the agent has crashed:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\")\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Agent_runtime\"]\n\n        except KeyboardInterrupt:\n            return True\n        \n        except TickRuntimeError:\n            entry_status, crash_message = \"Started\", \"TickRuntime\"\n        \n        except Exception:\n            print(\"\\n\\033[91mError during the simulation:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Simulation\"]\n\n        # Stop the scenario\n        try:\n            print(\"\\033[1m> Stopping the route\\033[0m\", flush=True)\n            self.manager.stop_scenario()\n            self._register_statistics(config.index, entry_status, crash_message)\n\n            if args.record:\n                self.client.stop_recorder()\n\n            self._cleanup()\n\n        except Exception:\n            print(\"\\n\\033[91mFailed to stop the scenario, the statistics might be empty:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n            _, crash_message = FAILURE_MESSAGES[\"Simulation\"]\n\n        # If the simulation crashed, stop the leaderboard, for the rest, move to the next route\n        return crash_message == \"Simulation crashed\"\n\n    def run(self, args):\n        \"\"\"\n        Run the challenge mode\n        \"\"\"\n        route_indexer = RouteIndexer(args.routes, args.repetitions, args.routes_subset)\n\n        #args.resume = True\n        if args.resume:\n            resume = route_indexer.validate_and_resume(args.checkpoint)\n        else:\n            resume = False\n\n        if resume:\n            self.statistics_manager.add_file_records(args.checkpoint)\n        else:\n            self.statistics_manager.clear_records()\n        self.statistics_manager.save_progress(route_indexer.index, route_indexer.total)\n        self.statistics_manager.write_statistics()\n\n        crashed = False\n        t1 = time.time()\n        while route_indexer.peek() and not crashed:\n\n            # Run the scenario\n            config = route_indexer.get_next_config()\n            crashed = self._load_and_run_scenario(args, config)\n            print(crashed, flush=True)\n            # Save the progress and write the route statistics\n            self.statistics_manager.save_progress(route_indexer.index, route_indexer.total)\n            self.statistics_manager.write_statistics()\n            if crashed:\n                print(f'{route_indexer.index} crash, [{route_indexer.index}/{route_indexer.total}], please restart', flush=True)\n                break\n\n        # Shutdown ROS1 bridge server if necessary\n        if self._ros1_server is not None:\n            self._ros1_server.shutdown()\n\n        # Go back to asynchronous mode\n        self._reset_world_settings()\n\n        if not crashed:\n            # Save global statistics\n            print(f\"cost time={time.time()-t1}\", flush=True)\n            print(\"\\033[1m> Registering the global statistics\\033[0m\", flush=True)\n            self.statistics_manager.compute_global_statistics()\n            self.statistics_manager.validate_and_write_statistics(self.sensors_initialized, crashed)\n        \n        if crashed:\n            cmd2 = \"ps -ef | grep '-graphicsadapter=\"+ str(args.gpu_rank) + \"' | grep -v grep | awk '{print $2}' | xargs -r kill -9\"\n            server = subprocess.Popen(cmd2, shell=True, preexec_fn=os.setsid)\n            atexit.register(os.killpg, server.pid, signal.SIGKILL)\n\n        return crashed\n\ndef main():\n    description = \"CARLA AD Leaderboard Evaluation: evaluate your Agent in CARLA scenarios\\n\"\n\n    # general parameters\n    parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter)\n    parser.add_argument('--host', default='localhost',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', default=2000, type=int,\n                        help='TCP port to listen to (default: 2000)')\n    parser.add_argument('--traffic-manager-port', default=8000, type=int,\n                        help='Port to use for the TrafficManager (default: 8000)')\n    parser.add_argument('--traffic-manager-seed', default=0, type=int,\n                        help='Seed used by the TrafficManager (default: 0)')\n    parser.add_argument('--debug', type=int,\n                        help='Run with debug output', default=0)\n    parser.add_argument('--record', type=str, default='',\n                        help='Use CARLA recording feature to create a recording of the scenario')\n    parser.add_argument('--timeout', default=600.0, type=float,\n                        help='Set the CARLA client timeout value in seconds')\n\n    # simulation setup\n    parser.add_argument('--routes', required=True,\n                        help='Name of the routes file to be executed.')\n    parser.add_argument('--routes-subset', default='', type=str,\n                        help='Execute a specific set of routes')\n    parser.add_argument('--repetitions', type=int, default=1,\n                        help='Number of repetitions per route.')\n\n    # agent-related options\n    parser.add_argument(\"-a\", \"--agent\", type=str,\n                        help=\"Path to Agent's py file to evaluate\", required=True)\n    parser.add_argument(\"--agent-config\", type=str,\n                        help=\"Path to Agent's configuration file\", default=\"\")\n\n    parser.add_argument(\"--track\", type=str, default='SENSORS',\n                        help=\"Participation track: SENSORS, MAP\")\n    parser.add_argument('--resume', type=bool, default=False,\n                        help='Resume execution from last checkpoint?')\n    parser.add_argument(\"--checkpoint\", type=str, default='./simulation_results.json',\n                        help=\"Path to checkpoint used for saving statistics and resuming\")\n    parser.add_argument(\"--debug-checkpoint\", type=str, default='./live_results.txt',\n                        help=\"Path to checkpoint used for saving live results\")\n    parser.add_argument(\"--gpu-rank\", type=int, default=0)\n    arguments = parser.parse_args()\n\n    statistics_manager = StatisticsManager(arguments.checkpoint, arguments.debug_checkpoint)\n    leaderboard_evaluator = LeaderboardEvaluator(arguments, statistics_manager)\n    crashed = leaderboard_evaluator.run(arguments)\n\n    del leaderboard_evaluator\n\n    if crashed:\n        sys.exit(-1)\n    else:\n        sys.exit(0)\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/scenarios/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/scenarios/route_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides Challenge routes as standalone scenarios\n\"\"\"\n\nfrom __future__ import print_function\n\nimport glob\nimport os\nimport sys\nimport importlib\nimport inspect\nimport py_trees\nimport traceback\nimport numpy as np\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ScenarioTriggerer, Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitForBlackboardVariable\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest,\n                                                                     InRouteTest,\n                                                                     RouteCompletionTest,\n                                                                     OutsideRouteLanesTest,\n                                                                     RunningRedLightTest,\n                                                                     RunningStopTest,\n                                                                     ActorBlockedTest,\n                                                                     MinimumSpeedRouteTest)\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.scenarios.background_activity import BackgroundBehavior\nfrom srunner.scenariomanager.weather_sim import RouteWeatherBehavior\nfrom srunner.scenariomanager.lights_sim import RouteLightsBehavior\nfrom srunner.scenariomanager.timer import RouteTimeoutBehavior\n\nfrom leaderboard.utils.route_parser import RouteParser, DIST_THRESHOLD\nfrom leaderboard.utils.route_manipulation import interpolate_trajectory\n\nimport leaderboard.utils.parked_vehicles as parked_vehicles\n\n\nclass RouteScenario(BasicScenario):\n\n    \"\"\"\n    Implementation of a RouteScenario, i.e. a scenario that consists of driving along a pre-defined route,\n    along which several smaller scenarios are triggered\n    \"\"\"\n\n    category = \"RouteScenario\"\n    INIT_THRESHOLD = 500 # Runtime initialization trigger distance to ego (m)\n    PARKED_VEHICLES_INIT_THRESHOLD = INIT_THRESHOLD - 50 # Runtime initialization trigger distance to parked vehicles (m)\n\n    def __init__(self, world, config, debug_mode=0, criteria_enable=True):\n        \"\"\"\n        Setup all relevant parameters and create scenarios along route\n        \"\"\"\n        self.client = CarlaDataProvider.get_client()\n        self.config = config\n        self.route = self._get_route(config)\n        self.world = world\n        self.map = CarlaDataProvider.get_map()\n        self.timeout = 10000\n\n        self.all_scenario_classes = None\n        self.ego_data = None\n\n        self.scenario_triggerer = None\n        self.behavior_node = None # behavior node created by _create_behavior()\n        self.criteria_node = None # criteria node created by _create_test_criteria()\n\n        self.list_scenarios = []\n        self.occupied_parking_locations = []\n        self.available_parking_locations = []\n\n        scenario_configurations = self._filter_scenarios(config.scenario_configs)\n        self.scenario_configurations = scenario_configurations\n        self.missing_scenario_configurations = scenario_configurations.copy()\n\n        ego_vehicle = self._spawn_ego_vehicle()\n        if ego_vehicle is None:\n            raise ValueError(\"Shutting down, couldn't spawn the ego vehicle\")\n\n        if debug_mode>0:\n            self._draw_waypoints(self.route, vertical_shift=0.1, size=0.1, downsample=10)\n\n        self._parked_ids = []\n        self._get_parking_slots()\n\n        super(RouteScenario, self).__init__(\n            config.name, [ego_vehicle], config, world, debug_mode > 3, False, criteria_enable\n        )\n\n        # Do it after the 'super', as we need the behavior and criteria tree to be initialized\n        self.build_scenarios(ego_vehicle, debug=debug_mode > 0)\n\n        # Set runtime init mode. Do this after the first set of scenarios has been initialized!\n        CarlaDataProvider.set_runtime_init_mode(True)\n\n    def _get_route(self, config):\n        \"\"\"\n        Gets the route from the configuration, interpolating it to the desired density,\n        saving it to the CarlaDataProvider and sending it to the agent\n\n        Parameters:\n        - world: CARLA world\n        - config: Scenario configuration (RouteConfiguration)\n        - debug_mode: boolean to decide whether or not the route poitns are printed\n        \"\"\"\n\n        # Prepare route's trajectory (interpolate and add the GPS route)\n        self.gps_route, self.route = interpolate_trajectory(config.keypoints)\n        return self.route\n\n    def _filter_scenarios(self, scenario_configs):\n        \"\"\"\n        Given a list of scenarios, filters out does that don't make sense to be triggered,\n        as they are either too far from the route or don't fit with the route shape\n\n        Parameters:\n        - scenario_configs: list of ScenarioConfiguration\n        \"\"\"\n        new_scenarios_config = []\n        for scenario_number, scenario_config in enumerate(scenario_configs):\n            trigger_point = scenario_config.trigger_points[0]\n            if not RouteParser.is_scenario_at_route(trigger_point, self.route):\n                print(\"WARNING: Ignoring scenario '{}' as it is too far from the route\".format(scenario_config.name))\n                continue\n\n            scenario_config.route_var_name = \"ScenarioRouteNumber{}\".format(scenario_number)\n            new_scenarios_config.append(scenario_config)\n\n        return new_scenarios_config\n\n    def _spawn_ego_vehicle(self):\n        \"\"\"Spawn the ego vehicle at the first waypoint of the route\"\"\"\n        elevate_transform = self.route[0][0]\n        elevate_transform.location.z += 0.5\n\n        ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz_2020',\n                                                          elevate_transform,\n                                                          rolename='hero')\n        if not ego_vehicle:\n            return\n\n        spectator = self.world.get_spectator()\n        spectator.set_transform(carla.Transform(elevate_transform.location + carla.Location(z=50),\n                                                    carla.Rotation(pitch=-90)))\n\n        self.world.tick()\n\n        return ego_vehicle\n\n    def _get_parking_slots(self, max_distance=100, route_step=10):\n        \"\"\"Spawn parked vehicles.\"\"\"\n\n        def is_close(slot_location):\n            for i in range(0, len(self.route), route_step):\n                route_transform = self.route[i][0]\n                if route_transform.location.distance(slot_location) < max_distance:\n                    return True\n            return False\n\n        min_x, min_y = float('inf'), float('inf')\n        max_x, max_y = float('-inf'), float('-inf')\n        for route_transform, _ in self.route:\n            min_x = min(min_x, route_transform.location.x - max_distance)\n            min_y = min(min_y, route_transform.location.y - max_distance)\n            max_x = max(max_x, route_transform.location.x + max_distance)\n            max_y = max(max_y, route_transform.location.y + max_distance)\n\n        # Occupied parking locations\n        occupied_parking_locations = []\n        for scenario in self.list_scenarios:\n            occupied_parking_locations.extend(scenario.get_parking_slots())\n\n        available_parking_locations = []\n        map_name = self.map.name.split('/')[-1]\n        available_parking_locations = getattr(parked_vehicles, map_name, [])\n\n        # Exclude parking slots that are too far from the route\n        for slot in available_parking_locations:\n            slot_transform = carla.Transform(\n                location=carla.Location(slot[\"location\"][0], slot[\"location\"][1], slot[\"location\"][2]),\n                rotation=carla.Rotation(slot[\"rotation\"][0], slot[\"rotation\"][1], slot[\"rotation\"][2])\n            )\n\n            in_area = (min_x < slot_transform.location.x < max_x) and (min_y < slot_transform.location.y < max_y)\n            close_to_route = is_close(slot_transform.location)\n            if not in_area or not close_to_route:\n                available_parking_locations.remove(slot)\n                continue\n\n        self.available_parking_locations = available_parking_locations\n\n    def spawn_parked_vehicles(self, ego_vehicle, max_scenario_distance=10):\n        \"\"\"Spawn parked vehicles.\"\"\"\n        def is_close(slot_location, ego_location):\n            return slot_location.distance(ego_location) < self.PARKED_VEHICLES_INIT_THRESHOLD\n        def is_free(slot_location):\n            for occupied_slot in self.occupied_parking_locations:\n                if slot_location.distance(occupied_slot) < max_scenario_distance:\n                    return False\n            return True\n\n        new_parked_vehicles = []\n\n        ego_location = CarlaDataProvider.get_location(ego_vehicle)\n        if ego_location is None:\n            return\n\n        for slot in self.available_parking_locations:\n            slot_transform = carla.Transform(\n                location=carla.Location(slot[\"location\"][0], slot[\"location\"][1], slot[\"location\"][2]),\n                rotation=carla.Rotation(slot[\"rotation\"][0], slot[\"rotation\"][1], slot[\"rotation\"][2])\n            )\n\n            # Add all vehicles that are close to the ego and in a free space\n            if is_close(slot_transform.location, ego_location) and is_free(slot_transform.location):\n                mesh_bp = CarlaDataProvider.get_world().get_blueprint_library().filter(\"static.prop.mesh\")[0]\n                mesh_bp.set_attribute(\"mesh_path\", slot[\"mesh\"])\n                mesh_bp.set_attribute(\"scale\", \"0.9\")\n                new_parked_vehicles.append(carla.command.SpawnActor(mesh_bp, slot_transform))\n                self.available_parking_locations.remove(slot)\n\n        # Add the actors to _parked_ids\n        for response in CarlaDataProvider.get_client().apply_batch_sync(new_parked_vehicles):\n            if not response.error:\n                self._parked_ids.append(response.actor_id)\n\n    # pylint: disable=no-self-use\n    def _draw_waypoints(self, waypoints, vertical_shift, size, downsample=1):\n        \"\"\"\n        Draw a list of waypoints at a certain height given in vertical_shift.\n        \"\"\"\n        for i, w in enumerate(waypoints):\n            if i % downsample != 0:\n                continue\n\n            wp = w[0].location + carla.Location(z=vertical_shift)\n\n            if w[1] == RoadOption.LEFT:  # Yellow\n                color = carla.Color(128, 128, 0)\n            elif w[1] == RoadOption.RIGHT:  # Cyan\n                color = carla.Color(0, 128, 128)\n            elif w[1] == RoadOption.CHANGELANELEFT:  # Orange\n                color = carla.Color(128, 32, 0)\n            elif w[1] == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n                color = carla.Color(0, 32, 128)\n            elif w[1] == RoadOption.STRAIGHT:  # Gray\n                color = carla.Color(64, 64, 64)\n            else:  # LANEFOLLOW\n                color = carla.Color(0, 128, 0)  # Green\n\n            self.world.debug.draw_point(wp, size=size, color=color, life_time=self.timeout)\n\n        self.world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=2*size,\n                                    color=carla.Color(0, 0, 128), life_time=self.timeout)\n        self.world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=2*size,\n                                    color=carla.Color(128, 128, 128), life_time=self.timeout)\n\n    def get_all_scenario_classes(self):\n        \"\"\"\n        Searches through the 'scenarios' folder for all the Python classes\n        \"\"\"\n        # Path of all scenario at \"srunner/scenarios\" folder\n        scenarios_list = glob.glob(\"{}/srunner/scenarios/*.py\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n\n        all_scenario_classes = {}\n\n        for scenario_file in scenarios_list:\n\n            # Get their module\n            module_name = os.path.basename(scenario_file).split('.')[0]\n            sys.path.insert(0, os.path.dirname(scenario_file))\n            scenario_module = importlib.import_module(module_name)\n\n            # And their members of type class\n            for member in inspect.getmembers(scenario_module, inspect.isclass):\n                # TODO: Filter out any class that isn't a child of BasicScenario\n                all_scenario_classes[member[0]] = member[1]\n\n        return all_scenario_classes\n\n    def build_scenarios(self, ego_vehicle, debug=False):\n        \"\"\"\n        Initializes the class of all the scenarios that will be present in the route.\n        If a class fails to be initialized, a warning is printed but the route execution isn't stopped\n        \"\"\"\n        new_scenarios = []\n\n        if self.all_scenario_classes is None:\n            self.all_scenario_classes = self.get_all_scenario_classes()\n        if self.ego_data is None:\n            self.ego_data = ActorConfigurationData(ego_vehicle.type_id, ego_vehicle.get_transform(), 'hero')\n\n        # Part 1. Check all scenarios that haven't been initialized, starting them if close enough to the ego vehicle\n        for scenario_config in self.missing_scenario_configurations:\n            scenario_config.ego_vehicles = [self.ego_data]\n            scenario_config.route = self.route\n\n            try:\n                scenario_class = self.all_scenario_classes[scenario_config.type]\n                trigger_location = scenario_config.trigger_points[0].location\n\n                ego_location = CarlaDataProvider.get_location(ego_vehicle)\n                if ego_location is None:\n                    continue\n\n                # Only init scenarios that are close to ego\n                if trigger_location.distance(ego_location) < self.INIT_THRESHOLD:\n                    scenario_instance = scenario_class(self.world, [ego_vehicle], scenario_config, timeout=self.timeout)\n\n                    # Add new scenarios to list\n                    self.list_scenarios.append(scenario_instance)\n                    new_scenarios.append(scenario_instance)\n                    self.missing_scenario_configurations.remove(scenario_config)\n\n                    self.occupied_parking_locations.extend(scenario_instance.get_parking_slots())\n\n                    if debug:\n                        scenario_loc = scenario_config.trigger_points[0].location\n                        debug_loc = self.map.get_waypoint(scenario_loc).transform.location + carla.Location(z=0.2)\n                        self.world.debug.draw_point(\n                            debug_loc, size=0.2, color=carla.Color(128, 0, 0), life_time=self.timeout\n                        )\n                        self.world.debug.draw_string(\n                            debug_loc, str(scenario_config.name), draw_shadow=False,\n                            color=carla.Color(0, 0, 128), life_time=self.timeout, persistent_lines=True\n                        )\n\n            except Exception as e:\n                print(f\"\\033[93mSkipping scenario '{scenario_config.name}' due to setup error: {e}\")\n                if debug:\n                    print(f\"\\n{traceback.format_exc()}\")\n                print(\"\\033[0m\", end=\"\")\n                self.missing_scenario_configurations.remove(scenario_config)\n                continue\n\n        # Part 2. Add their behavior onto the route's behavior tree\n        for scenario in new_scenarios:\n\n            # Add behavior\n            if scenario.behavior_tree is not None:\n                self.behavior_node.add_child(scenario.behavior_tree)\n                self.scenario_triggerer.add_blackboard(\n                    [scenario.config.route_var_name, scenario.config.trigger_points[0].location]\n                )\n\n            # Add the criteria criteria\n            scenario_criteria = scenario.get_criteria()\n            if len(scenario_criteria) == 0:\n                continue\n\n            self.criteria_node.add_child(\n                self._create_criterion_tree(scenario, scenario_criteria)\n            )\n\n    # pylint: enable=no-self-use\n    def _initialize_actors(self, config):\n        \"\"\"\n        Set other_actors to the superset of all scenario actors\n        \"\"\"\n        # Add all the actors of the specific scenarios to self.other_actors\n        for scenario in self.list_scenarios:\n            self.other_actors.extend(scenario.other_actors)\n\n    def _create_behavior(self):\n        \"\"\"\n        Creates a parallel behavior that runs all of the scenarios part of the route.\n        These subbehaviors have had a trigger condition added so that they wait until\n        the agent is close to their trigger point before activating.\n\n        It also adds the BackgroundActivity scenario, which will be active throughout the whole route.\n        This behavior never ends and the end condition is given by the RouteCompletionTest criterion.\n        \"\"\"\n        scenario_trigger_distance = DIST_THRESHOLD  # Max trigger distance between route and scenario\n\n        behavior = py_trees.composites.Parallel(name=\"Route Behavior\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n\n        self.behavior_node = behavior\n        scenario_behaviors = []\n        blackboard_list = []\n\n        # Add the behavior that manages the scenario trigger conditions\n        scenario_triggerer = ScenarioTriggerer(\n            self.ego_vehicles[0], self.route, blackboard_list, scenario_trigger_distance)\n        behavior.add_child(scenario_triggerer)  # Tick the ScenarioTriggerer before the scenarios\n\n        # register var\n        self.scenario_triggerer = scenario_triggerer\n\n        # Add the Background Activity\n        behavior.add_child(BackgroundBehavior(self.ego_vehicles[0], self.route, name=\"BackgroundActivity\"))\n\n        behavior.add_children(scenario_behaviors)\n        return behavior\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Create the criteria tree. It starts with some route criteria (which are always active),\n        and adds the scenario specific ones, which will only be active during their scenario\n        \"\"\"\n        criteria = py_trees.composites.Parallel(name=\"Criteria\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        self.criteria_node = criteria\n\n        # End condition\n        criteria.add_child(RouteCompletionTest(self.ego_vehicles[0], route=self.route))\n\n        # 'Normal' criteria\n        criteria.add_child(OutsideRouteLanesTest(self.ego_vehicles[0], route=self.route))\n        criteria.add_child(CollisionTest(self.ego_vehicles[0], name=\"CollisionTest\"))\n        criteria.add_child(RunningRedLightTest(self.ego_vehicles[0]))\n        criteria.add_child(RunningStopTest(self.ego_vehicles[0]))\n        criteria.add_child(MinimumSpeedRouteTest(self.ego_vehicles[0], self.route, checkpoints=20, name=\"MinSpeedTest\"))\n\n        # These stop the route early to save computational time\n        criteria.add_child(InRouteTest(\n            self.ego_vehicles[0], route=self.route, offroad_max=30, terminate_on_failure=True))\n        criteria.add_child(ActorBlockedTest(\n            self.ego_vehicles[0], min_speed=0.1, max_time=60.0, terminate_on_failure=True, name=\"AgentBlockedTest\")\n        )\n\n        return criteria\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Create the weather behavior\n        \"\"\"\n        if len(self.config.weather) == 1:\n            return  # Just set the weather at the beginning and done\n        return RouteWeatherBehavior(self.ego_vehicles[0], self.route, self.config.weather)\n\n    def _create_lights_behavior(self):\n        \"\"\"\n        Create the street lights behavior\n        \"\"\"\n        return RouteLightsBehavior(self.ego_vehicles[0], 100)\n\n    def _create_timeout_behavior(self):\n        \"\"\"\n        Create the timeout behavior\n        \"\"\"\n        return RouteTimeoutBehavior(self.ego_vehicles[0], self.route)\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Set the weather\n        \"\"\"\n        # Set the appropriate weather conditions\n        world.set_weather(self.config.weather[0][1])\n\n    def _create_criterion_tree(self, scenario, criteria):\n        \"\"\"\n        We can make use of the blackboard variables used by the behaviors themselves,\n        as we already have an atomic that handles their (de)activation.\n        The criteria will wait until that variable is active (the scenario has started),\n        and will automatically stop when it deactivates (as the scenario has finished)\n        \"\"\"\n        scenario_name = scenario.name\n        var_name = scenario.config.route_var_name\n        check_name = \"WaitForBlackboardVariable: {}\".format(var_name)\n\n        criteria_tree = py_trees.composites.Sequence(name=scenario_name)\n        criteria_tree.add_child(WaitForBlackboardVariable(var_name, True, False, name=check_name))\n\n        scenario_criteria = py_trees.composites.Parallel(name=scenario_name,\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        for criterion in criteria:\n            scenario_criteria.add_child(criterion)\n        scenario_criteria.add_child(WaitForBlackboardVariable(var_name, False, None, name=check_name))\n\n        criteria_tree.add_child(scenario_criteria)\n        criteria_tree.add_child(Idle())  # Avoid the indiviual criteria stopping the simulation\n        return criteria_tree\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.client.apply_batch([carla.command.DestroyActor(x) for x in self._parked_ids])\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/scenarios/scenario_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the ScenarioManager implementations.\nIt must not be modified and is for reference only!\n\"\"\"\n\nfrom __future__ import print_function\nimport signal\nimport sys\nimport time\n\nimport py_trees\nimport carla\nimport threading\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.watchdog import Watchdog\n\nfrom leaderboard.autoagents.agent_wrapper import AgentWrapperFactory, AgentError, TickRuntimeError\nfrom leaderboard.envs.sensor_interface import SensorReceivedNoData\nfrom leaderboard.utils.result_writer import ResultOutputProvider\n\n\nclass ScenarioManager(object):\n\n    \"\"\"\n    Basic scenario manager class. This class holds all functionality\n    required to start, run and stop a scenario.\n\n    The user must not modify this class.\n\n    To use the ScenarioManager:\n    1. Create an object via manager = ScenarioManager()\n    2. Load a scenario via manager.load_scenario()\n    3. Trigger the execution of the scenario manager.run_scenario()\n       This function is designed to explicitly control start and end of\n       the scenario execution\n    4. If needed, cleanup with manager.stop_scenario()\n    \"\"\"\n\n    def __init__(self, timeout, statistics_manager, debug_mode=0):\n        \"\"\"\n        Setups up the parameters, which will be filled at load_scenario()\n        \"\"\"\n        self.route_index = None\n        self.scenario = None\n        self.scenario_tree = None\n        self.ego_vehicles = None\n        self.other_actors = None\n\n        self._debug_mode = debug_mode\n        self._agent_wrapper = None\n        self._running = False\n        self._timestamp_last_run = 0.0\n        self._timeout = float(timeout)\n\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = 0.0\n        self.start_game_time = 0.0\n        self.end_system_time = 0.0\n        self.end_game_time = 0.0\n\n        self._watchdog = None\n        self._agent_watchdog = None\n        self._scenario_thread = None\n\n        self._statistics_manager = statistics_manager\n\n        self.tick_count = 0\n\n        # Use the callback_id inside the signal handler to allow external interrupts\n        signal.signal(signal.SIGINT, self.signal_handler)\n\n    def signal_handler(self, signum, frame):\n        \"\"\"\n        Terminate scenario ticking when receiving a signal interrupt\n        \"\"\"\n        if self._agent_watchdog and not self._agent_watchdog.get_status():\n            raise RuntimeError(\"Agent took longer than {}s to send its command\".format(self._timeout))\n        elif self._watchdog and not self._watchdog.get_status():\n            raise RuntimeError(\"The simulation took longer than {}s to update\".format(self._timeout))\n        self._running = False\n\n    def cleanup(self):\n        \"\"\"\n        Reset all parameters\n        \"\"\"\n        self._timestamp_last_run = 0.0\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = 0.0\n        self.start_game_time = 0.0\n        self.end_system_time = 0.0\n        self.end_game_time = 0.0\n\n        self._spectator = None\n        self._watchdog = None\n        self._agent_watchdog = None\n\n    def load_scenario(self, scenario, agent, route_index, rep_number):\n        \"\"\"\n        Load a new scenario\n        \"\"\"\n\n        GameTime.restart()\n        self._agent_wrapper = AgentWrapperFactory.get_wrapper(agent)\n        self.route_index = route_index\n        self.scenario = scenario\n        self.scenario_tree = scenario.scenario_tree\n        self.ego_vehicles = scenario.ego_vehicles\n        self.other_actors = scenario.other_actors\n        self.repetition_number = rep_number\n\n        self._spectator = CarlaDataProvider.get_world().get_spectator()\n\n        # To print the scenario tree uncomment the next line\n        # py_trees.display.render_dot_tree(self.scenario_tree)\n\n        self._agent_wrapper.setup_sensors(self.ego_vehicles[0])\n\n    def build_scenarios_loop(self, debug):\n        \"\"\"\n        Keep periodically trying to start the scenarios that are close to the ego vehicle\n        Additionally, do the same for the spawned vehicles\n        \"\"\"\n        while self._running:\n            self.scenario.build_scenarios(self.ego_vehicles[0], debug=debug)\n            self.scenario.spawn_parked_vehicles(self.ego_vehicles[0])\n            time.sleep(1)\n\n    def run_scenario(self):\n        \"\"\"\n        Trigger the start of the scenario and wait for it to finish/fail\n        \"\"\"\n        self.start_system_time = time.time()\n        self.start_game_time = GameTime.get_time()\n\n        # Detects if the simulation is down\n        self._watchdog = Watchdog(self._timeout)\n        self._watchdog.start()\n\n        # Stop the agent from freezing the simulation\n        self._agent_watchdog = Watchdog(self._timeout)\n        self._agent_watchdog.start()\n\n        self._running = True\n\n        # Thread for build_scenarios\n        self._scenario_thread = threading.Thread(target=self.build_scenarios_loop, args=(self._debug_mode > 0, ))\n        self._scenario_thread.start()\n\n        while self._running:\n            self._tick_scenario()\n\n    def _tick_scenario(self):\n        \"\"\"\n        Run next tick of scenario and the agent and tick the world.\n        \"\"\"\n        if self._running and self.get_running_status():\n            CarlaDataProvider.get_world().tick(self._timeout)\n\n        timestamp = CarlaDataProvider.get_world().get_snapshot().timestamp\n\n        if self._timestamp_last_run < timestamp.elapsed_seconds and self._running:\n            self._timestamp_last_run = timestamp.elapsed_seconds\n\n            self._watchdog.update()\n            # Update game time and actor information\n            GameTime.on_carla_tick(timestamp)\n            CarlaDataProvider.on_carla_tick()\n            self.tick_count += 1\n            self._watchdog.pause()\n\n            if self.tick_count > 4000:\n                raise TickRuntimeError(\"RuntimeError, tick_count > 4000\")\n\n            try:\n                self._agent_watchdog.resume()\n                self._agent_watchdog.update()\n                ego_action = self._agent_wrapper()\n                self._agent_watchdog.pause()\n\n            # Special exception inside the agent that isn't caused by the agent\n            except SensorReceivedNoData as e:\n                raise RuntimeError(e)\n\n            except Exception as e:\n                raise AgentError(e)\n\n            self._watchdog.resume()\n            self.ego_vehicles[0].apply_control(ego_action)\n\n            # Tick scenario. Add the ego control to the blackboard in case some behaviors want to change it\n            py_trees.blackboard.Blackboard().set(\"AV_control\", ego_action, overwrite=True)\n            self.scenario_tree.tick_once()\n\n            if self._debug_mode > 1:\n                self.compute_duration_time()\n\n                # Update live statistics\n                self._statistics_manager.compute_route_statistics(\n                    self.route_index,\n                    self.scenario_duration_system,\n                    self.scenario_duration_game,\n                    failure_message=\"\"\n                )\n                self._statistics_manager.write_live_results(\n                    self.route_index,\n                    self.ego_vehicles[0].get_velocity().length(),\n                    ego_action,\n                    self.ego_vehicles[0].get_location()\n                )\n\n            if self._debug_mode > 2:\n                print(\"\\n\")\n                py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True)\n                sys.stdout.flush()\n\n            if self.scenario_tree.status != py_trees.common.Status.RUNNING:\n                self._running = False\n\n            ego_trans = self.ego_vehicles[0].get_transform()\n            self._spectator.set_transform(carla.Transform(ego_trans.location + carla.Location(z=70),\n                                                          carla.Rotation(pitch=-90)))\n\n    def get_running_status(self):\n        \"\"\"\n        returns:\n           bool: False if watchdog exception occured, True otherwise\n        \"\"\"\n        if self._watchdog:\n            return self._watchdog.get_status()\n        return True\n\n    def stop_scenario(self):\n        \"\"\"\n        This function triggers a proper termination of a scenario\n        \"\"\"\n        if self._watchdog:\n            self._watchdog.stop()\n\n        if self._agent_watchdog:\n            self._agent_watchdog.stop()\n\n        self.compute_duration_time()\n\n        if self.get_running_status():\n            if self.scenario is not None:\n                self.scenario.terminate()\n\n            if self._agent_wrapper is not None:\n                self._agent_wrapper.cleanup()\n                self._agent_wrapper = None\n\n            self.analyze_scenario()\n\n        # Make sure the scenario thread finishes to avoid blocks\n        self._running = False\n        self._scenario_thread.join()\n        self._scenario_thread = None\n\n    def compute_duration_time(self):\n        \"\"\"\n        Computes system and game duration times\n        \"\"\"\n        self.end_system_time = time.time()\n        self.end_game_time = GameTime.get_time()\n\n        self.scenario_duration_system = self.end_system_time - self.start_system_time\n        self.scenario_duration_game = self.end_game_time - self.start_game_time\n\n    def analyze_scenario(self):\n        \"\"\"\n        Analyzes and prints the results of the route\n        \"\"\"\n        ResultOutputProvider(self)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/checkpoint_tools.py",
    "content": "import json\ntry:\n    import simplejson as json\nexcept ImportError:\n    import json\nimport requests\nimport os.path\n\n\ndef autodetect_proxy():\n    proxies = {}\n\n    proxy_https = os.getenv('HTTPS_PROXY', os.getenv('https_proxy', None))\n    proxy_http = os.getenv('HTTP_PROXY', os.getenv('http_proxy', None))\n\n    if proxy_https:\n        proxies['https'] = proxy_https\n    if proxy_http:\n        proxies['http'] = proxy_http\n\n    return proxies\n\n\ndef fetch_dict(endpoint):\n    data = None\n    if endpoint.startswith(('http:', 'https:', 'ftp:')):\n        proxies = autodetect_proxy()\n\n        if proxies:\n            response = requests.get(url=endpoint, proxies=proxies)\n        else:\n            response = requests.get(url=endpoint)\n\n        try:\n            data = response.json()\n        except json.decoder.JSONDecodeError:\n            data = {}\n    else:\n        data = {}\n        if os.path.exists(endpoint):\n            with open(endpoint) as fd:\n                try:\n                    data = json.load(fd)\n                except json.JSONDecodeError:\n                    data = {}\n\n    return data\n\n\ndef save_dict(endpoint, data):\n    if endpoint.startswith(('http:', 'https:', 'ftp:')):\n        proxies = autodetect_proxy()\n\n        if proxies:\n            _ = requests.patch(url=endpoint, headers={'content-type':'application/json'}, data=json.dumps(data, indent=4, sort_keys=True), proxies=proxies)\n        else:\n            _ = requests.patch(url=endpoint, headers={'content-type':'application/json'}, data=json.dumps(data, indent=4, sort_keys=True))\n    else:\n        with open(endpoint, 'w') as fd:\n            json.dump(data, fd, indent=4)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/parked_vehicles.py",
    "content": "Town12 = [\n {'tilex':2, 'tiley':1, 'location':(-602.3104296900001, 4002.51804688, 371.64960937999996), 'rotation':(-0.598236, -89.864105, -0.61084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.3477734400001, 4018.99757812, 371.80917969), 'rotation':(-0.538605, -89.86499, -0.548798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.36023438, 4024.49070312, 371.85746094), 'rotation':(-0.508789, -89.86554, -0.517883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.3851171900001, 4035.47828125, 371.94628905999997), 'rotation':(-0.448853, -89.866547, -0.455933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.39746094, 4040.97117188, 371.98671875), 'rotation':(-0.418762, -89.866455, -0.424927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.40996094, 4046.46460938, 372.02476562000004), 'rotation':(-0.388916, -89.867432, -0.394226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.42242188, 4051.95796875, 372.06074219000004), 'rotation':(-0.374969, -89.86673, -0.379883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.43492188, 4057.45140625, 372.09535156), 'rotation':(-0.361298, -89.867737, -0.365845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.4473437500001, 4062.94601562, 372.12757812), 'rotation':(-0.336487, -89.868042, -0.340454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.4597656200001, 4068.43921875, 372.15816406), 'rotation':(-0.311218, -89.868347, -0.314606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.53230469, 4100.39546875, 372.30773437999994), 'rotation':(-0.234192, -89.868958, -0.236115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.5446093799999, 4105.83835938, 372.3290625), 'rotation':(-0.234192, -89.868958, -0.236115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.56925781, 4116.7265625, 372.3678125), 'rotation':(-0.192841, -89.869263, -0.194153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.5939843799999, 4127.61375, 372.40175781), 'rotation':(-0.172272, -89.869385, -0.173309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.61871094, 4138.50242188, 372.43351562000004), 'rotation':(-0.166718, -89.869019, -0.167664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.63109375, 4143.94679688, 372.45039062), 'rotation':(-0.176178, -89.869537, -0.177277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.6434375, 4149.39109375, 372.468125), 'rotation':(-0.185699, -89.869476, -0.18689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.66820312, 4160.27976562, 372.50605469000004), 'rotation':(-0.204681, -89.868744, -0.206146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.68058594, 4165.72414062, 372.52632812), 'rotation':(-0.213593, -89.869263, -0.215179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.7053125, 4176.6128125, 372.56925780999995), 'rotation':(-0.232849, -89.869141, -0.234741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.86527344, 4100.43210938, 372.56164062000005), 'rotation':(-0.766205, -90.242493, -0.786896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.76597655999996, 4122.91648438, 372.83417969000004), 'rotation':(-0.676758, -90.244751, -0.692871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-494.71632812, 4134.1596875, 372.95371094), 'rotation':(-0.609192, -90.246124, -0.622223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-494.69152344, 4139.7803125, 373.01101562), 'rotation':(-0.588867, -90.246857, -0.601044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.64183594, 4151.02390625, 373.11710938), 'rotation':(-0.548126, -90.247498, -0.558685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.61703125, 4156.64648438, 373.16691405999995), 'rotation':(-0.507202, -90.24823, -0.516235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.59226562000003, 4162.26757812, 373.21421875), 'rotation':(-0.507202, -90.24823, -0.516235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.54257812000003, 4173.51171875, 373.30402344000004), 'rotation':(-0.445892, -90.249359, -0.452881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.51773438, 4179.13429688, 373.34773437999996), 'rotation':(-0.445892, -90.249359, -0.452881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.29738281, 4002.536875, 370.85113280999997), 'rotation':(-1.25235, -90.224182, -1.308044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-495.27335938, 4007.9856250000003, 370.96808594000004), 'rotation':(-1.237549, -90.226135, -1.291901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.22523437999996, 4018.8828125, 371.19429687999997), 'rotation':(-1.182648, -90.228149, -1.232269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.20121094, 4024.3315625, 371.30359375), 'rotation':(-1.155334, -90.229584, -1.202667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.17714844, 4029.78054688, 371.41035156), 'rotation':(-1.12796, -90.230682, -1.173065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.1290625, 4040.67820312, 371.61613280999995), 'rotation':(-1.073029, -90.232788, -1.113831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.105, 4046.12796875, 371.71539062000005), 'rotation':(-1.045715, -90.233826, -1.084442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.0809375, 4051.5771875, 371.81261719), 'rotation':(-1.031891, -90.234161, -1.06958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.056875, 4057.02539062, 371.90828125), 'rotation':(-1.009155, -90.234894, -1.045197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-495.0328125, 4062.475625, 371.99992188), 'rotation':(-0.963043, -90.236725, -0.995819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.00875, 4067.92382812, 372.0884375), 'rotation':(-0.916931, -90.238007, -0.946655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.93015625, 4073.36351562, 372.22453125), 'rotation':(0.650603, 90.042068, 0.635961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.926875, 4067.915, 372.16148438), 'rotation':(0.650603, 90.042068, 0.635961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.92039062000003, 4057.01734375, 372.02992187999996), 'rotation':(0.706802, 90.04319, 0.689509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.90734375, 4035.22195312, 371.74839844), 'rotation':(0.761867, 90.044632, 0.741798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.90082031, 4024.32398438, 371.60050780999995), 'rotation':(0.787753, 90.045532, 0.76632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.89753906, 4018.87570312, 371.52433594), 'rotation':(0.787753, 90.045532, 0.76632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.89429687999996, 4013.42625, 371.44691406), 'rotation':(0.813687, 90.046089, 0.790816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.89097656, 4007.97828125, 371.36765625), 'rotation':(0.813687, 90.046089, 0.790816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.88769531, 4002.5290625, 371.28773437999996), 'rotation':(0.839608, 90.046814, 0.815265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.99171875, 4175.91109375, 373.14503906), 'rotation':(0.394764, 90.037468, 0.389359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.98839843999997, 4170.47359375, 373.10746094), 'rotation':(0.39499, 90.037209, 0.389567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.98515625000005, 4165.03609375, 373.06910156), 'rotation':(0.401424, 90.037186, 0.39583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.97863281, 4154.16164062, 372.98867187999997), 'rotation':(0.426989, 90.037567, 0.420674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.97203125, 4143.28710938, 372.90324219), 'rotation':(0.452821, 90.037956, 0.445705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.96886718999997, 4137.85007812, 372.85867188), 'rotation':(0.465908, 90.03849, 0.458385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.96558594, 4132.41257812, 372.81285155999996), 'rotation':(0.478728, 90.038712, 0.470777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.96234374999995, 4126.97609375, 372.765625), 'rotation':(0.491453, 90.038605, 0.483071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.95906249999996, 4121.53859375, 372.7171875), 'rotation':(0.510126, 90.039085, 0.50111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.95582031000004, 4116.1015625, 372.66707031), 'rotation':(0.510126, 90.039085, 0.50111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.94605469, 4099.79101562, 372.50859375), 'rotation':(0.558853, 90.040016, 0.548032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.4942968800001, 4180.9721875, 373.00605469000004), 'rotation':(0.318526, 89.73568, 0.314989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.56992188000004, 4164.6709375, 372.91507812000003), 'rotation':(0.318417, 89.735542, 0.314903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.5952343800001, 4159.2378125, 372.88429687999997), 'rotation':(0.324038, 89.735825, 0.320378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.62039061999997, 4153.80375, 372.8525), 'rotation':(0.334631, 89.735939, 0.330742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.645625, 4148.36960938, 372.82035156), 'rotation':(0.334631, 89.735939, 0.330742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.72140625, 4132.06882812, 372.72027344), 'rotation':(0.356379, 89.736008, 0.351963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.74664062, 4126.63523438, 372.68585937999995), 'rotation':(0.361836, 89.736206, 0.357293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.79710938000005, 4115.76804688, 372.6153125), 'rotation':(0.367881, 89.73642, 0.363177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.8224218800001, 4110.33445312, 372.57914062000003), 'rotation':(0.380025, 89.736374, 0.375015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.84765625, 4104.90085938, 372.54191405999995), 'rotation':(0.392148, 89.736549, 0.38682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.8728906199999, 4099.46726562, 372.50410156), 'rotation':(0.392148, 89.736549, 0.38682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.99546875, 4073.0590625, 372.31058594), 'rotation':(0.436231, 89.737267, 0.429619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.02070312, 4067.63304688, 372.26863281), 'rotation':(0.436231, 89.737267, 0.429619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.04593750000004, 4062.2057812499997, 372.2259375), 'rotation':(0.450594, 89.73748, 0.443556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.1215625, 4045.92648438, 372.09175781), 'rotation':(0.479527, 89.737961, 0.471544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-287.14679688, 4040.49976562, 372.04570312000004), 'rotation':(0.486774, 89.738106, 0.47856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.17203125000003, 4035.07328125, 371.99914062000005), 'rotation':(0.486774, 89.738106, 0.47856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.19726561999994, 4029.64671875, 371.95230469), 'rotation':(0.493727, 89.738159, 0.485289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.22249999999997, 4024.2200000000003, 371.90421875), 'rotation':(0.507736, 89.738403, 0.498797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.27296875, 4013.36671875, 371.80601562000004), 'rotation':(0.521949, 89.738663, 0.512506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.68117188000008, 4007.8957812500003, 371.51730469), 'rotation':(-0.635101, -90.243591, -0.649323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.65757811999993, 4013.27515625, 371.57480469), 'rotation':(-0.618713, -90.243958, -0.632202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.63406250000003, 4018.65429688, 371.63078125), 'rotation':(-0.602356, -90.244293, -0.615143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.61046875, 4024.0339062499997, 371.68519531), 'rotation':(-0.585968, -90.244812, -0.598083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.56343749999996, 4034.79273438, 371.78933594), 'rotation':(-0.552917, -90.2453, -0.56369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.53984375000005, 4040.17210938, 371.8390625), 'rotation':(-0.536896, -90.245605, -0.547028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-174.4928125, 4050.93140625, 371.93464844000005), 'rotation':(-0.501251, -90.246277, -0.510071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.44570311999996, 4061.6909375, 372.02570312000006), 'rotation':(-0.479095, -90.246643, -0.487183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-173.98593749999998, 4166.72023438, 372.6359375), 'rotation':(-0.225189, -90.249847, -0.226959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.01046874999997, 4161.11523438, 372.61355469), 'rotation':(-0.232635, -90.249634, -0.234528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.05953124999996, 4149.90429688, 372.56640625), 'rotation':(-0.262817, -90.249451, -0.265259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.08414061999997, 4144.29882812, 372.54109375), 'rotation':(-0.277496, -90.249329, -0.280182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.1086718800001, 4138.69382812, 372.51492188), 'rotation':(-0.277496, -90.249329, -0.280182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.13320311999996, 4133.08835938, 372.48777344), 'rotation':(-0.285156, -90.249268, -0.287994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.15773438000008, 4127.48289062, 372.45988280999995), 'rotation':(-0.297668, -90.249115, -0.300781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.18226561999995, 4121.87796875, 372.43113281), 'rotation':(-0.297668, -90.249115, -0.300781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.23132811999994, 4110.66796875, 372.36980469), 'rotation':(-0.34726, -90.248566, -0.351501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.25585938000006, 4105.06296875, 372.33625), 'rotation':(-0.372131, -90.24823, -0.377014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-174.28039061999993, 4099.45851562, 372.30132812000005), 'rotation':(-0.372131, -90.24823, -0.377014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.90242188000002, 4376.78320312, 373.11617187999997), 'rotation':(0.034472, -90.051086, 0.034445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.91210938000006, 4365.87402344, 373.12300781), 'rotation':(0.037675, -90.051056, 0.03763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.91703125000004, 4360.41992188, 373.12660156), 'rotation':(0.037675, -90.051056, 0.03763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.921875, 4354.96582031, 373.13019531), 'rotation':(0.03036, -90.051147, 0.030327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.92671874999996, 4349.51171875, 373.13351562), 'rotation':(0.03036, -90.051147, 0.030327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.93765625000003, 4338.60351562, 373.13671875), 'rotation':(0.001018, -90.051025, 0.001028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.94140625, 4333.15039062, 373.13609375), 'rotation':(-0.027985, -90.051178, -0.028015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.79171874999997, 4500.80226562, 373.13351562), 'rotation':(-0.041138, -90.051147, -0.041199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.79664061999995, 4495.38914062, 373.12925780999996), 'rotation':(-0.041138, -90.051147, -0.041199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.80140625, 4489.9765625, 373.12535155999996), 'rotation':(-0.034821, -90.051056, -0.034882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.80624999999998, 4484.56398438, 373.12191406), 'rotation':(-0.034821, -90.051056, -0.034882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.82070311999996, 4468.32570312, 373.11335937999996), 'rotation':(-0.025696, -90.051117, -0.025726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.83039062, 4457.50046875, 373.10851562000005), 'rotation':(-0.025696, -90.051117, -0.025726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.84007811999993, 4446.6753125, 373.10367188), 'rotation':(-0.017029, -90.051086, -0.017029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.84484375, 4441.2621875, 373.10175781), 'rotation':(0.001366, -90.051086, 0.001366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.85453125000004, 4430.43601562, 373.10195312), 'rotation':(0.010143, -90.051056, 0.010135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.859375, 4425.0234375, 373.10292969), 'rotation':(0.010143, -90.051208, 0.010135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.68359375, 4607.18261719, 373.26082031), 'rotation':(-0.088745, -90.051025, -0.08902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.6896093800001, 4601.50390625, 373.25203125), 'rotation':(-0.086365, -90.050964, -0.086609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.69562499999995, 4595.82617188, 373.24347656), 'rotation':(-0.082336, -90.051086, -0.082581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.71359374999997, 4578.79054688, 373.21925781), 'rotation':(-0.073914, -90.051117, -0.074097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.71953125000005, 4573.11230469, 373.21179687999995), 'rotation':(-0.073914, -90.051117, -0.074097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.72562500000004, 4567.4340625, 373.20449219), 'rotation':(-0.071899, -90.050934, -0.072083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.73148437999998, 4561.75585938, 373.19734375), 'rotation':(-0.071899, -90.051056, -0.072083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.74351561999993, 4550.39890625, 373.18332031), 'rotation':(-0.065277, -90.051056, -0.06543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.74953125000002, 4544.72023438, 373.1765625), 'rotation':(-0.065277, -90.051056, -0.06543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.75546874999998, 4539.04199219, 373.17011719000004), 'rotation':(-0.061127, -90.051086, -0.061249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.76742188000003, 4527.68507812, 373.158125), 'rotation':(-0.056732, -90.051086, -0.056854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.64453125, 4634.18992188, 373.30203125), 'rotation':(-0.084595, -90.050995, -0.084839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.63867188000006, 4645.15332031, 373.31769531), 'rotation':(-0.082001, -90.050995, -0.082245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.63578125000004, 4650.63574219, 373.32539062), 'rotation':(-0.080536, -90.050964, -0.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.6328125, 4656.11765625, 373.33308594000005), 'rotation':(-0.080261, -90.051086, -0.080505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62984374999996, 4661.59960938, 373.34078125), 'rotation':(-0.080536, -90.050964, -0.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62695311999994, 4667.0815625, 373.34847656), 'rotation':(-0.080536, -90.051086, -0.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62406250000004, 4672.56396484, 373.35613280999996), 'rotation':(-0.079773, -90.051056, -0.079987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62109375, 4678.04589844, 373.36367187999997), 'rotation':(-0.077667, -90.051056, -0.077881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.61812499999996, 4683.52783203, 373.37105469), 'rotation':(-0.077667, -90.051056, -0.077881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.61515625000004, 4689.00976562, 373.37828125), 'rotation':(-0.076172, -90.050903, -0.076355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.61226562000002, 4694.49169922, 373.38535156), 'rotation':(-0.074646, -90.051086, -0.074829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.60929688, 4699.97412109, 373.39238280999996), 'rotation':(-0.073486, -90.051056, -0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.60640624999996, 4705.45605469, 373.39945312000003), 'rotation':(-0.073486, -90.051056, -0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.60343750000004, 4710.93798828, 373.40644531), 'rotation':(-0.073792, -90.051056, -0.073975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.97617188000004, 4322.24757812, 373.13039062), 'rotation':(0.042996, 89.948837, 0.042926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.96148438, 4338.60742188, 373.13667969), 'rotation':(-0.015717, 89.948814, -0.015717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.95664061999992, 4344.06054688, 373.13585937999994), 'rotation':(-0.030365, 89.949013, -0.030396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.94203125, 4360.42140625, 373.12660156), 'rotation':(-0.037506, 89.948853, -0.037567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.93718750000005, 4365.875, 373.12300781), 'rotation':(-0.037506, 89.948853, -0.037567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.9225781199999, 4382.23730469, 373.11335937999996), 'rotation':(-0.021637, 89.948776, -0.021667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.91773438000007, 4387.6909375, 373.11101562000005), 'rotation':(-0.021637, 89.948776, -0.021667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.91281249999997, 4393.14550781, 373.10910156), 'rotation':(-0.015594, 89.948906, -0.015594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.88929688000007, 4419.60890625, 373.10386719), 'rotation':(-0.010132, 89.948952, -0.010132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.87960938000003, 4430.4340625, 373.10195312), 'rotation':(-0.009766, 89.948952, -0.009796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.87476561999995, 4435.8471875, 373.10128906), 'rotation':(-0.001373, 89.948929, -0.001373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.87, 4441.26023438, 373.10175781), 'rotation':(0.017021, 89.948761, 0.017013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.8650781199999, 4446.67335938, 373.10367188), 'rotation':(0.025436, 89.948868, 0.025413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.86031249999996, 4452.0859375, 373.10609375), 'rotation':(0.025688, 89.948868, 0.025676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.85546875, 4457.49851562, 373.10847656), 'rotation':(0.025688, 89.948868, 0.025676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.8458593800001, 4468.32375, 373.11335937999996), 'rotation':(0.028741, 89.948929, 0.028708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.84101562, 4473.73632812, 373.1159375), 'rotation':(0.028741, 89.948929, 0.028708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.83617188000005, 4479.14890625, 373.11867187999997), 'rotation':(0.034841, 89.948837, 0.034794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.83132811999997, 4484.56203125, 373.12191406), 'rotation':(0.041145, 89.948952, 0.041075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.82656250000002, 4489.97460938, 373.12535155999996), 'rotation':(0.041145, 89.948952, 0.041075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.82171874999995, 4495.3871875, 373.12925780999996), 'rotation':(0.047238, 89.948845, 0.047159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.81687499999998, 4500.8003125, 373.13351562), 'rotation':(0.047238, 89.948845, 0.047159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.72195311999997, 4607.18898438, 373.26082031), 'rotation':(0.08843, 89.948967, 0.088166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.72695311999996, 4601.50976562, 373.25203125), 'rotation':(0.088738, 89.94912, 0.088467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.73203124999998, 4595.83105469, 373.24347656), 'rotation':(0.086347, 89.948929, 0.086083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.73710938, 4590.151875, 373.23515625), 'rotation':(0.086347, 89.948929, 0.086083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.74726562, 4578.79445312, 373.21925781), 'rotation':(0.07811, 89.948906, 0.077902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.75234375000002, 4573.11523438, 373.21175781), 'rotation':(0.07811, 89.948906, 0.077902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.75742188000004, 4567.43652344, 373.20445312000004), 'rotation':(0.073882, 89.949005, 0.073696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.76242188000003, 4561.7578125, 373.19734375), 'rotation':(0.071895, 89.948929, 0.071704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.77257811999993, 4550.39941406, 373.18328125), 'rotation':(0.069641, 89.948959, 0.069462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.77765624999995, 4544.72070312, 373.1765625), 'rotation':(0.069641, 89.948959, 0.069462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.78781249999997, 4533.3628125, 373.16398438), 'rotation':(0.06111, 89.948921, 0.060975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.79281249999997, 4527.68359375, 373.158125), 'rotation':(0.06111, 89.948921, 0.060975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.62937499999998, 4710.94433594, 373.40644531), 'rotation':(0.073466, 89.948944, 0.073284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.63429688000008, 4705.46240234, 373.39945312000003), 'rotation':(0.073752, 89.948936, 0.073571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.63914061999992, 4699.98046875, 373.39238280999996), 'rotation':(0.073466, 89.949089, 0.073296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.64890624999998, 4689.01660156, 373.37828125), 'rotation':(0.07464, 89.948914, 0.074446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.66359375000002, 4672.57080078, 373.35613280999996), 'rotation':(0.077646, 89.948936, 0.077436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.66843749999998, 4667.08835938, 373.34847656), 'rotation':(0.079763, 89.949089, 0.079544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.67335938000008, 4661.60644531, 373.34078125), 'rotation':(0.080514, 89.948898, 0.080295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.68804688, 4645.160625, 373.31769531), 'rotation':(0.080514, 89.949036, 0.080298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.69296874999998, 4639.67871094, 373.30992188), 'rotation':(0.080514, 89.949036, 0.080298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.69781250000005, 4634.19726562, 373.30203125), 'rotation':(0.082003, 89.948845, 0.081772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.23986328, 3718.19484375, 366.77601562), 'rotation':(-1.177185, -90.000366, -1.226318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.23265625, 3734.828125, 367.11480469), 'rotation':(-1.157379, -90.00119, -1.204865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2302929699999, 3740.37257812, 367.22664062), 'rotation':(-1.157379, -90.00119, -1.204865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.22546875, 3751.46140625, 367.44835937999994), 'rotation':(-1.143158, -90.002686, -1.189484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2230859399999, 3757.00609375, 367.55792969000004), 'rotation':(-1.131439, -90.002228, -1.176819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2207617199999, 3762.5503125, 367.66613280999997), 'rotation':(-1.131439, -90.002228, -1.176819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.21837891, 3768.09445312, 367.77347656), 'rotation':(-1.109131, -90.003082, -1.15271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2159960900001, 3773.63914062, 367.87871094), 'rotation':(-1.086975, -90.003937, -1.128845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.21363281, 3779.18335938, 367.98289062000003), 'rotation':(-1.086975, -90.003937, -1.128845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2112500000001, 3784.72828125, 368.08601562), 'rotation':(-1.064667, -90.005188, -1.104797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.20642578, 3795.8176562500003, 368.29011719000005), 'rotation':(-1.053528, -90.005188, -1.092804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.20404297, 3801.36257812, 368.39210937999997), 'rotation':(-1.053467, -90.005188, -1.092743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.25390625, 3685.756875, 366.10066406), 'rotation':(-1.201416, -89.999573, -1.252625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2586718800001, 3674.6940624999997, 365.86851562000004), 'rotation':(-1.202759, -89.999268, -1.254089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2634375, 3663.6315624999997, 365.63617187999995), 'rotation':(-1.203064, -89.999237, -1.254425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2658007800001, 3658.1003124999997, 365.52), 'rotation':(-1.202789, -89.999878, -1.25415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.26818359, 3652.56910156, 365.40378906), 'rotation':(-1.202759, -89.999268, -1.254089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.27294922, 3641.50632812, 365.17132812000006), 'rotation':(-1.205017, -89.999268, -1.256561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2753320300001, 3635.97535156, 365.055), 'rotation':(-1.205017, -89.999268, -1.256561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2800976599999, 3624.91285156, 364.82207030999996), 'rotation':(-1.206421, -89.999207, -1.258087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2848437499999, 3613.85035156, 364.58890625), 'rotation':(-1.208832, -89.999451, -1.260681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.294375, 3591.72535156, 364.12195312000006), 'rotation':(-1.208832, -89.999451, -1.260681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.29914062, 3580.66308594, 363.88777344000005), 'rotation':(-1.221527, -89.998718, -1.274506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.30152344, 3575.13183594, 363.77), 'rotation':(-1.221863, -89.998688, -1.274841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.30621094, 3564.06957031, 363.53398438), 'rotation':(-1.221527, -89.998718, -1.274506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.30859375, 3558.53832031, 363.41597656), 'rotation':(-1.222626, -89.998352, -1.275665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.3110351600001, 3553.00707031, 363.29792969000005), 'rotation':(-1.224182, -89.998291, -1.277374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.31580078, 3541.94484375, 363.06125), 'rotation':(-1.227692, -89.998108, -1.281189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.31818359, 3536.41332031, 362.94265625), 'rotation':(-1.229675, -89.998047, -1.283356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.3206250000001, 3530.88234375, 362.82390625), 'rotation':(-1.231293, -89.998627, -1.285095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.32300781, 3525.3513281200003, 362.705), 'rotation':(-1.233185, -89.997894, -1.28714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.32775391, 3514.2890625, 362.46660155999996), 'rotation':(-1.23584, -89.998199, -1.290039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.3301367199999, 3508.7575781200003, 362.3471875), 'rotation':(-1.23587, -89.998199, -1.2901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.33251953, 3503.2265625, 362.2278125), 'rotation':(-1.23587, -89.998199, -1.2901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.30371094, 3685.74953125, 365.57570312), 'rotation':(-1.40332, -89.99881, -1.473389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.306875, 3680.21632812, 365.44066405999996), 'rotation':(-1.40332, -89.99881, -1.473389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31011719, 3674.68335938, 365.30496094), 'rotation':(-1.41864, -89.998474, -1.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31335938, 3669.1496875000003, 365.16785156), 'rotation':(-1.434204, -89.997711, -1.507416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31664062, 3663.61648438, 365.02992187999996), 'rotation':(-1.434204, -89.997711, -1.507416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31984375, 3658.0832812500003, 364.89128905999996), 'rotation':(-1.441833, -89.997284, -1.515839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.32640625, 3647.01609375, 364.61226562), 'rotation':(-1.458771, -89.996552, -1.534546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.32960938, 3641.48316406, 364.47179687999994), 'rotation':(-1.470337, -89.995972, -1.547333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.33601562, 3630.41699219, 364.18738281), 'rotation':(-1.493073, -89.994781, -1.57251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.3490625, 3608.2846875, 363.6046875), 'rotation':(-1.533051, -89.992462, -1.616852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.35546875, 3597.21828125, 363.30839844), 'rotation':(-1.534149, -89.992279, -1.618073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.35871094, 3591.68480469, 363.16007812000004), 'rotation':(-1.536621, -89.992157, -1.620789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.36199219, 3586.15160156, 363.01152344), 'rotation':(-1.539124, -89.992401, -1.623596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.3651562499999, 3580.61839844, 362.86292969000004), 'rotation':(-1.539124, -89.992401, -1.623596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.36839844, 3575.08496094, 362.71417969000004), 'rotation':(-1.541534, -89.991913, -1.626251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.37480469, 3564.01832031, 362.41621094000004), 'rotation':(-1.54248, -89.992188, -1.627319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.37816406, 3558.4841406200003, 362.26761719), 'rotation':(-1.518341, -89.992859, -1.600525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.38132812, 3552.94898438, 362.12195312000006), 'rotation':(-1.469147, -89.996094, -1.546051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.38777344, 3541.87742188, 361.84503906), 'rotation':(-1.37085, -90.000946, -1.437714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.3941796900001, 3530.80617188, 361.58730469), 'rotation':(-1.27298, -90.004822, -1.330536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.39738281, 3525.27, 361.465625), 'rotation':(-1.223999, -90.007629, -1.277161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.4007031200001, 3519.73390625, 361.34871094000005), 'rotation':(-1.174622, -90.009033, -1.223572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.4038281200001, 3514.19875, 361.23589844), 'rotation':(-1.150177, -90.010498, -1.197083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.40703125, 3508.66453125, 361.12476562000006), 'rotation':(-1.150177, -90.010498, -1.197052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.4102734400001, 3503.12964844, 361.01359375), 'rotation':(-0.894958, -89.986023, -0.923248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.27824219, 3729.225625, 366.61851562000004), 'rotation':(-1.351746, -90.001648, -1.416718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2750390599999, 3734.75632812, 366.748125), 'rotation':(-1.342499, -90.002045, -1.406586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2653124999999, 3751.3489062500003, 367.13476562000005), 'rotation':(-1.332703, -90.002319, -1.395844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2620312500001, 3756.879375, 367.26222656), 'rotation':(-1.322083, -90.002808, -1.384216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.25878906, 3762.41015625, 367.38878905999997), 'rotation':(-1.312103, -90.003845, -1.373291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.255625, 3767.9409375, 367.51445312000004), 'rotation':(-1.301422, -90.003723, -1.361633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.24589844, 3784.53367188, 367.88578125), 'rotation':(-1.270172, -90.005157, -1.327484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.24261719, 3790.06445312, 368.00769531), 'rotation':(-1.259613, -90.005615, -1.315948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2362109400001, 3801.12671875, 368.25027344), 'rotation':(-1.254486, -90.006165, -1.310364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.73621094000003, 3798.92820312, 366.71011719), 'rotation':(0.814732, 89.782356, 0.791803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.7578125, 3793.52585938, 366.63328125), 'rotation':(0.814835, 89.782303, 0.791901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.77941405999997, 3788.12351562, 366.55644530999996), 'rotation':(0.814835, 89.782303, 0.791901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.80101562000004, 3782.72070312, 366.47976562), 'rotation':(0.813578, 89.782387, 0.790721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.82261719, 3777.31835938, 366.40324219), 'rotation':(0.811556, 89.782333, 0.78881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.84417969000003, 3771.91578125, 366.32699219), 'rotation':(0.8092, 89.782288, 0.786584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-499.90898438, 3755.70851562, 366.09921875), 'rotation':(0.802561, 89.782082, 0.780311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-499.93058594, 3750.305625, 366.02367187999994), 'rotation':(0.800245, 89.782013, 0.778117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.95222656, 3744.90328125, 365.94832031), 'rotation':(0.797916, 89.781952, 0.77592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.97382812, 3739.50070312, 365.873125), 'rotation':(0.796776, 89.781929, 0.774849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.99539062, 3734.09859375, 365.79757812), 'rotation':(0.802506, 89.78196, 0.780266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.03863280999997, 3723.2946875, 365.64417969000004), 'rotation':(0.813318, 89.782547, 0.790464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.8746875, 3514.1059375, 362.87519531), 'rotation':(0.32052, 89.772644, 0.316957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.85257812000003, 3519.64304688, 362.90289062000005), 'rotation':(0.32052, 89.772644, 0.316957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.83054688, 3525.17796875, 362.93382812000004), 'rotation':(0.408227, 89.77375, 0.402454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-500.80839844, 3530.71679688, 362.96914062), 'rotation':(0.408227, 89.77375, 0.402454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-500.76414062000003, 3541.79101562, 363.05472656), 'rotation':(0.495749, 89.775139, 0.487228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.74210938, 3547.32984375, 363.10328125), 'rotation':(0.58325, 89.776787, 0.571469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.69792969, 3558.40160156, 363.21753906), 'rotation':(0.627332, 89.777657, 0.613695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.65367188, 3569.473125, 363.34113281), 'rotation':(0.657406, 89.778328, 0.642454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-500.54328125, 3597.15578125, 363.70320312), 'rotation':(0.87048, 89.784149, 0.84432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.52113281, 3602.69214844, 363.78496094), 'rotation':(0.87048, 89.784149, 0.84432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.476875, 3613.76171875, 363.95390625), 'rotation':(0.880541, 89.784233, 0.85379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.45472656, 3619.296875, 364.03925781), 'rotation':(0.88703, 89.78476, 0.85987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.43257812, 3624.83179688, 364.12523437999994), 'rotation':(0.89386, 89.784653, 0.866292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.41050780999996, 3630.3669531200003, 364.211875), 'rotation':(0.900724, 89.785172, 0.872728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.38832031, 3635.901875, 364.29917969), 'rotation':(0.907199, 89.78508, 0.878802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.36628906, 3641.43675781, 364.38707030999996), 'rotation':(0.914036, 89.785301, 0.885208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.32195312000005, 3652.50660156, 364.56464844000004), 'rotation':(0.920375, 89.785553, 0.891147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.29980469000003, 3658.04125, 364.65332030999997), 'rotation':(0.912301, 89.785301, 0.883589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.27765625, 3663.5754687500003, 364.74128906), 'rotation':(0.904624, 89.785034, 0.87639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.1890625, 3685.71335938, 365.08558594000004), 'rotation':(0.872837, 89.784035, 0.846544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-396.26269531, 3502.8303125, 365.64453125), 'rotation':(0.359165, 89.619179, 0.354688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.22558594, 3508.37109375, 365.67925780999997), 'rotation':(0.358967, 89.619354, 0.354501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.18859375, 3513.91164062, 365.71402344), 'rotation':(0.376985, 89.619408, 0.372041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.15160156, 3519.4528906200003, 365.74941406), 'rotation':(0.376985, 89.619408, 0.372041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.07757812, 3530.536875, 365.82867187999994), 'rotation':(0.448375, 89.620415, 0.441402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.04058594, 3536.07910156, 365.87351562000003), 'rotation':(0.484035, 89.62101, 0.475912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.89257812000005, 3558.2465625, 366.08789062000005), 'rotation':(0.627093, 89.623764, 0.613491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.85558593999997, 3563.78785156, 366.149375), 'rotation':(0.644811, 89.624199, 0.630423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.81855469000004, 3569.32859375, 366.21238281), 'rotation':(0.658225, 89.624535, 0.643233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.78148437999994, 3574.87035156, 366.27617188), 'rotation':(0.684808, 89.625153, 0.668588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.67054687999996, 3591.49367188, 366.479375), 'rotation':(0.738405, 89.626488, 0.719554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-395.59644531000004, 3602.5746875, 366.623125), 'rotation':(0.752318, 89.626595, 0.732758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.52238280999995, 3613.65527344, 366.76863281), 'rotation':(0.75296, 89.626915, 0.733365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.48535156, 3619.19578125, 366.84148437999994), 'rotation':(0.754148, 89.626945, 0.734487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.41125, 3630.27636719, 366.9875), 'rotation':(0.755678, 89.626984, 0.735933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-395.37425781, 3635.816875, 367.060625), 'rotation':(0.756928, 89.627007, 0.737126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.30015625, 3646.89746094, 367.20714844), 'rotation':(0.758732, 89.627075, 0.738823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-395.26320312000007, 3652.4377343799997, 367.28054688), 'rotation':(0.758656, 89.626892, 0.738764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.22609375, 3657.9775, 367.35316406), 'rotation':(0.747182, 89.626724, 0.727887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.11492188, 3674.59671875, 367.56554687999994), 'rotation':(0.699862, 89.625534, 0.682925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.07789062000006, 3680.1371875, 367.63324219000003), 'rotation':(0.676134, 89.624954, 0.660313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.04082030999996, 3685.67648438, 367.70027344000005), 'rotation':(0.676134, 89.624954, 0.660313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.00378906000003, 3691.21703125, 367.76566406), 'rotation':(0.664065, 89.624825, 0.648805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.30925780999996, 3795.10351562, 368.76171875), 'rotation':(0.458975, 89.61998, 0.451656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.34617187999993, 3789.60007812, 368.71765625), 'rotation':(0.459009, 89.619766, 0.451691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.38304687999994, 3784.09695312, 368.67320312000004), 'rotation':(0.459009, 89.619766, 0.451691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.45683594, 3773.0903125, 368.5821875), 'rotation':(0.468052, 89.619698, 0.460454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.4937890599999, 3767.586875, 368.53542969), 'rotation':(0.486658, 89.619812, 0.478446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.5675, 3756.58109375, 368.4384375), 'rotation':(0.505058, 89.619957, 0.496209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.60449219, 3751.07765625, 368.38820312), 'rotation':(0.523486, 89.620468, 0.51398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.64136719, 3745.57445312, 368.33757812000005), 'rotation':(0.523486, 89.620468, 0.51398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.67820312000003, 3740.07125, 368.28585938), 'rotation':(0.532686, 89.620796, 0.522864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.71519531, 3734.56882812, 368.23332030999995), 'rotation':(0.543417, 89.620834, 0.533176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.75207031, 3729.0651562499997, 368.17902344000004), 'rotation':(0.565376, 89.621498, 0.55431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.78898438, 3723.5625, 368.123125), 'rotation':(0.586918, 89.622147, 0.574997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.8259375, 3718.0598437500003, 368.06597655999997), 'rotation':(0.586918, 89.622147, 0.574997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.62234375, 3718.03148438, 368.57753906), 'rotation':(-0.639435, -90.372314, -0.653839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.5859375, 3723.52882812, 368.6403125), 'rotation':(-0.639435, -90.372314, -0.653839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.54953125, 3729.02585938, 368.70449219), 'rotation':(-0.666229, -90.371704, -0.681854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.51320311999996, 3734.5221874999997, 368.77097656), 'rotation':(-0.692719, -90.37088, -0.709656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.47671875000003, 3740.0190625, 368.8390625), 'rotation':(-0.692719, -90.37088, -0.709656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-280.40398438, 3751.01195312, 368.9784375), 'rotation':(-0.730438, -90.370178, -0.749237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.2947656199999, 3767.49953125, 369.18617187999996), 'rotation':(-0.716949, -90.370514, -0.735046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.2584375, 3772.995625, 369.25441406), 'rotation':(-0.712097, -90.3703, -0.72995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.1491406199999, 3789.48390625, 369.45640625), 'rotation':(-0.698242, -90.370972, -0.715424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.1128125, 3794.98, 369.52316406), 'rotation':(-0.695862, -90.370789, -0.712921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-280.8366406199999, 3685.64085938, 368.24242187999994), 'rotation':(-0.477539, -90.375427, -0.485565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.8734375, 3680.0928125, 368.19441406), 'rotation':(-0.477539, -90.375427, -0.485565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-280.90999999999997, 3674.54734375, 368.14820312000006), 'rotation':(-0.406067, -90.376526, -0.411865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.9466406199999, 3668.99929688, 368.10851562000005), 'rotation':(-0.334595, -90.377472, -0.338531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.02015625, 3657.9053125, 368.03789062000004), 'rotation':(-0.29895, -90.377869, -0.302094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.056875, 3652.35839844, 368.00671875), 'rotation':(-0.29895, -90.377869, -0.302094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.09351561999995, 3646.81152344, 367.97804687999997), 'rotation':(-0.269592, -90.378174, -0.272156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.13023438000005, 3641.2658593799997, 367.95195312000004), 'rotation':(-0.210938, -90.378418, -0.212463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.16695312, 3635.71777344, 367.93066405999997), 'rotation':(-0.152252, -90.379059, -0.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.20367188, 3630.1696875, 367.91359375), 'rotation':(-0.152252, -90.379059, -0.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.27703125000005, 3619.07496094, 367.89195312000004), 'rotation':(-0.064148, -90.379333, -0.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.31375, 3613.52929688, 367.88570312), 'rotation':(-0.064148, -90.379333, -0.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.35046875, 3607.98363281, 367.87953125), 'rotation':(-0.064148, -90.379333, -0.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.3871875, 3602.43796875, 367.87328125), 'rotation':(-0.064148, -90.379364, -0.064301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.4239843800001, 3596.89257812, 367.86710938), 'rotation':(-0.021179, -90.379395, -0.02121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.46054688000004, 3591.34496094, 367.86460938), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.49734375, 3585.79761719, 367.86355469), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.5340625, 3580.2521875, 367.86566406), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.57078125, 3574.70628906, 367.86777344), 'rotation':(0.021447, -90.379395, 0.02144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.60749999999996, 3569.160625, 367.86988281), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.64421875000005, 3563.615, 367.87195312000006), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.71765625, 3552.52390625, 367.87613281), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.754375, 3546.97828125, 367.87824219000004), 'rotation':(0.021447, -90.379395, 0.02144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.7911718800001, 3541.43261719, 367.8803125), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.82789061999995, 3535.88695312, 367.88242188), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.90140625000004, 3524.7971093799997, 367.88175780999995), 'rotation':(-0.066559, -90.379547, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.938125, 3519.25316406, 367.87535155999996), 'rotation':(-0.066559, -90.379272, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-282.01156249999997, 3508.161875, 367.86242187999994), 'rotation':(-0.066559, -90.379272, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-282.04828124999995, 3502.61621094, 367.85601562000005), 'rotation':(-0.066559, -90.379272, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.42562499999997, 3691.20945312, 366.49726562), 'rotation':(-0.951324, -90.365692, -0.983337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.46242188000008, 3685.67382812, 366.40367188), 'rotation':(-0.845551, -90.369019, -0.870789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.49914061999993, 3680.1379687500003, 366.32054687999994), 'rotation':(-0.739685, -90.371948, -0.758972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.57273438000004, 3669.06421875, 366.18601562000003), 'rotation':(-0.528259, -90.376465, -0.538055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.68320311999992, 3652.44800781, 366.06347655999997), 'rotation':(-0.263733, -90.380249, -0.266144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.72000000000003, 3646.91480469, 366.03796875), 'rotation':(-0.263977, -90.380371, -0.266388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.75679688000002, 3641.38132812, 366.0125), 'rotation':(-0.166992, -90.38092, -0.167969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.86703124999997, 3624.75707031, 365.99121094000003), 'rotation':(0.21998, -90.380707, 0.218302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.90374999999995, 3619.21410156, 366.01621094), 'rotation':(0.413875, -90.378418, 0.407934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.94046875000004, 3613.67578125, 366.05710938), 'rotation':(0.510495, -90.376984, 0.501466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.01414061999992, 3602.6091406200003, 366.15578125), 'rotation':(0.510488, -90.376892, 0.501464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.05093750000003, 3597.07324219, 366.20570312), 'rotation':(0.557658, -90.37616, 0.546883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.12460938000004, 3586.00269531, 366.316875), 'rotation':(0.651627, -90.374084, 0.636928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.198125, 3574.931875, 366.44835937999994), 'rotation':(0.745952, -90.371796, 0.726718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.27171875, 3563.86230469, 366.60023437999996), 'rotation':(0.83986, -90.369171, 0.815509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.30843749999997, 3558.32910156, 366.68148438), 'rotation':(0.85249, -90.368683, 0.8274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.38234375000002, 3547.2690625, 366.83742187999997), 'rotation':(0.715934, -90.372589, 0.698207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.41929688000005, 3541.73875, 366.90507812000004), 'rotation':(0.647475, -90.374207, 0.63296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.49312499999996, 3530.67726562, 367.01964844), 'rotation':(0.510529, -90.377014, 0.501497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.52999999999997, 3525.14671875, 367.06660156), 'rotation':(0.442391, -90.378113, 0.435595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.56695312, 3519.61570312, 367.10664062), 'rotation':(0.373557, -90.379089, 0.368709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.640625, 3508.54980469, 367.17402344000004), 'rotation':(0.33944, -90.379456, 0.335431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.67648438000003, 3503.02101562, 367.20675781), 'rotation':(1.022657, -90.493286, 0.986624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.24531249999995, 3718.306875, 367.02347656), 'rotation':(-1.143402, -90.358673, -1.189728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.20773438000003, 3723.95507812, 367.13832031), 'rotation':(-1.160797, -90.357941, -1.208588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.09492188000002, 3740.89796875, 367.49183594000004), 'rotation':(-1.205048, -90.35611, -1.256592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.05734374999997, 3746.54445312, 367.60914062000006), 'rotation':(-1.192505, -90.356689, -1.24295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.98203124999998, 3757.8385937499997, 367.83707031), 'rotation':(-1.14444, -90.358673, -1.190887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.906875, 3769.13210938, 368.05582031), 'rotation':(-1.095795, -90.360443, -1.138367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.83164061999992, 3780.42601562, 368.26574219), 'rotation':(-1.047394, -90.362366, -1.086243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.75640625000005, 3791.72023438, 368.46757812000004), 'rotation':(-1.023529, -90.363098, -1.060638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.71882812, 3797.36789062, 368.56726562000006), 'rotation':(-1.011169, -90.363708, -1.047363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.67617188000008, 3794.18382812, 367.88445312000005), 'rotation':(1.217338, 89.958611, 1.166398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.68898438000008, 3783.29226562, 367.64957031), 'rotation':(1.244358, 89.959763, 1.191161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.70187499999997, 3772.3996875000003, 367.39738280999995), 'rotation':(1.352562, 89.964676, 1.289793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.71492188000002, 3761.51, 367.12566405999996), 'rotation':(1.460793, 89.970009, 1.387648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.73445312000001, 3745.17625, 366.68234375), 'rotation':(1.62303, 89.978691, 1.532917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.74039061999997, 3739.73390625, 366.52550780999997), 'rotation':(1.431198, 90.035789, 1.360968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.74726562000001, 3734.286875, 366.36613280999995), 'rotation':(1.668035, 89.981377, 1.572903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.75374999999997, 3728.84078125, 366.20394531), 'rotation':(1.704358, 89.983459, 1.605088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.76656249999996, 3717.9518749999997, 365.87226562), 'rotation':(1.740407, 89.985649, 1.636934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-73.01625000000001, 3502.73390625, 364.52347656), 'rotation':(-0.551819, 89.938011, -0.562531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-73.00968750000004, 3508.27492188, 364.47007812000004), 'rotation':(-0.551819, 89.938011, -0.562531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-73.00320311999997, 3513.81542969, 364.41671875), 'rotation':(-0.552185, 89.938095, -0.562897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.99671875000001, 3519.35523438, 364.36316406), 'rotation':(-0.578705, 89.938515, -0.590485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.99015625000004, 3524.8940625, 364.30628906), 'rotation':(-0.632904, 89.939735, -0.647003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.98359374999995, 3530.43238281, 364.24382812000005), 'rotation':(-0.687073, 89.940903, -0.703705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.97703124999998, 3535.97070312, 364.17570312000004), 'rotation':(-0.740936, 89.942322, -0.760284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.97054688000003, 3541.50855469, 364.10191405999996), 'rotation':(-0.795074, 89.943687, -0.817383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.96398438000006, 3547.046875, 364.02253906), 'rotation':(-0.903442, 89.946922, -0.932281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.95093750000001, 3558.12183594, 363.84679687999994), 'rotation':(-0.983887, 89.948875, -1.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.94453124999995, 3563.66332031, 363.75660156), 'rotation':(-0.790619, 89.943672, -0.812653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.93812500000001, 3569.20972656, 363.67640625), 'rotation':(-0.66156, 89.940331, -0.676971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.93164061999994, 3574.75632812, 363.6090625), 'rotation':(-0.532196, 89.937637, -0.542145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.92523438, 3580.30371094, 363.55457031), 'rotation':(-0.403137, 89.935532, -0.408844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.90609374999997, 3596.94628906, 363.46796875), 'rotation':(-0.015533, 89.932693, -0.015533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.89320311999995, 3608.03859375, 363.46882812), 'rotation':(0.129432, 89.932983, 0.128855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.88039061999996, 3619.1330468799997, 363.49449219), 'rotation':(0.289381, 89.934158, 0.286477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.87429688000009, 3624.68164062, 363.53046875), 'rotation':(0.610243, 89.939201, 0.597343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.85539061999998, 3641.32421875, 363.74179688), 'rotation':(1.090692, 89.953461, 1.049747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.84914061999996, 3646.87742188, 363.84792969), 'rotation':(1.250724, 89.960022, 1.196978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.83640624999998, 3657.95921875, 364.10035156), 'rotation':(1.398276, 89.966873, 1.331209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.83015624999996, 3663.4965625, 364.23558594), 'rotation':(1.533152, 89.973763, 1.45266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.82359374999999, 3669.03859375, 364.37730469), 'rotation':(1.533152, 89.973763, 1.45266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.80460937999999, 3685.65453125, 364.84679687999994), 'rotation':(1.803149, 89.989571, 1.692155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.79828124999995, 3691.18992188, 365.02125), 'rotation':(1.869539, 89.993706, 1.750316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-495.26792969, 3997.54664062, 370.74253905999996), 'rotation':(-1.251068, -90.225403, -1.306641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-495.30183594000005, 3995.40304688, 370.69566405999996), 'rotation':(-1.251251, -90.225555, -1.306854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-392.89378906, 3997.54148438, 371.21351562), 'rotation':(0.852373, 90.047218, 0.827294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-392.91027343999997, 3992.25804688, 371.13484375), 'rotation':(0.852373, 90.047218, 0.827294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-174.73906250000005, 3994.6667187499997, 371.37035155999996), 'rotation':(-0.64328, -90.243347, -0.657867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(252.03812500000004, 4098.24953125, 369.95632812), 'rotation':(-0.907104, -90.174164, -0.936188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.09367188, 4115.12304688, 370.19902344), 'rotation':(-0.776459, -90.177887, -0.797729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(252.1121875, 4120.74609375, 370.27003906), 'rotation':(-0.710999, -90.179688, -0.728821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.14921875000005, 4131.99757812, 370.40335938), 'rotation':(-0.659637, -90.180878, -0.674957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.16781249999997, 4137.62257812, 370.46449219000004), 'rotation':(-0.622314, -90.181732, -0.635956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.18624999999997, 4143.24804688, 370.52207031), 'rotation':(-0.58551, -90.182617, -0.597565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(252.20484375, 4148.87304688, 370.57605469000003), 'rotation':(-0.548431, -90.183197, -0.559021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(252.22335938000003, 4154.49804688, 370.62640625), 'rotation':(-0.511078, -90.183899, -0.520264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(252.24187500000005, 4160.12304688, 370.67320312000004), 'rotation':(-0.473999, -90.18454, -0.481903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.26046874999997, 4165.74804688, 370.71636719), 'rotation':(-0.436646, -90.18512, -0.443329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(252.2975, 4176.9990625, 370.79359375), 'rotation':(-0.380981, -90.185974, -0.386078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.72296874999995, 4002.5490625, 367.8821875), 'rotation':(-1.610138, -90.142731, -1.702667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.75773438, 4013.12476562, 368.16949219), 'rotation':(-1.551727, -90.146393, -1.637604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(251.79257811999992, 4023.70140625, 368.44207030999996), 'rotation':(-1.471558, -90.150635, -1.548676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(251.8274218800001, 4034.27804688, 368.69984375), 'rotation':(-1.391418, -90.154816, -1.460297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(251.84484375, 4039.56640625, 368.82320312), 'rotation':(-1.351257, -90.156586, -1.416168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.86226562000002, 4044.85453125, 368.94339844), 'rotation':(-1.291748, -90.159088, -1.351013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(251.89703125000005, 4055.43289062, 369.17296875), 'rotation':(-1.259552, -90.160736, -1.315918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(251.91445311999996, 4060.7196875, 369.28347656), 'rotation':(-1.196899, -90.163544, -1.247742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.94929688000002, 4071.29882812, 369.49023437999995), 'rotation':(-1.133728, -90.165985, -1.179291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(352.84375, 4065.66578125, 369.34808594000003), 'rotation':(0.67821, 89.786667, 0.662301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.76234375, 4044.61648438, 369.10199219000003), 'rotation':(0.666271, 89.786194, 0.650907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(352.72175781, 4034.0910937500003, 368.98332030999995), 'rotation':(0.634702, 89.785507, 0.620749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.70148438, 4028.828125, 368.92667969), 'rotation':(0.614655, 89.785088, 0.601573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(352.66082030999996, 4018.30226562, 368.81890625), 'rotation':(0.574917, 89.784248, 0.563471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.64050781000003, 4013.03929688, 368.76777344000004), 'rotation':(0.555226, 89.783852, 0.544537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.62023437999994, 4007.77664062, 368.7184375), 'rotation':(0.535514, 89.783821, 0.525568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(353.28589844, 4179.93601562, 370.43664062000005), 'rotation':(0.333539, 89.780548, 0.329668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(353.26457030999995, 4174.46140625, 370.40472656), 'rotation':(0.333539, 89.780548, 0.329668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.24339843999996, 4168.9878125, 370.37285155999996), 'rotation':(0.333791, 89.780533, 0.329913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.22230469, 4163.51414062, 370.33957031), 'rotation':(0.349043, 89.7808, 0.344819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.17980468999997, 4152.569375, 370.26425781), 'rotation':(0.410358, 89.781593, 0.404507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.15867187999993, 4147.09671875, 370.22203125), 'rotation':(0.441271, 89.781761, 0.434516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(353.13746094, 4141.62351562, 370.17683594000005), 'rotation':(0.471939, 89.782562, 0.464211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(353.09507812000004, 4130.67773438, 370.07746094000004), 'rotation':(0.533158, 89.783333, 0.523297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(353.07398437999996, 4125.20507812, 370.02347656), 'rotation':(0.563832, 89.784218, 0.552814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.05273437999995, 4119.73140625, 369.96714844), 'rotation':(0.591119, 89.784798, 0.579016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(353.03160156, 4114.25828125, 369.90984375), 'rotation':(0.591119, 89.784798, 0.579016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(353.01039062000007, 4108.78421875, 369.85109375), 'rotation':(0.614751, 89.78508, 0.601663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.98917969, 4103.3115625, 369.79027344), 'rotation':(0.638418, 89.785797, 0.624304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.39039062000006, 4176.51710938, 370.73753905999996), 'rotation':(-0.043335, 89.969818, -0.043396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.38746094, 4170.9053125, 370.74179688), 'rotation':(-0.043335, 89.969818, -0.043396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.38160156000004, 4159.68164062, 370.75011719), 'rotation':(-0.041626, 89.96991, -0.041687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.36976562000007, 4137.23484375, 370.76453125), 'rotation':(-0.032532, 89.970108, -0.032593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.36390625, 4126.01171875, 370.77070312), 'rotation':(-0.031097, 89.969841, -0.031158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.3609765599999, 4120.39992188, 370.77363281), 'rotation':(-0.031097, 89.969826, -0.031128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(460.35804687999996, 4114.78859375, 370.77613281), 'rotation':(-0.026764, 89.969887, -0.026794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.35503905999997, 4109.17671875, 370.77789062000005), 'rotation':(-0.018524, 89.970131, -0.018555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.35203125, 4103.56492188, 370.77894531), 'rotation':(-0.01004, 89.969879, -0.01004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.32054687999994, 4071.01101562, 370.77816406), 'rotation':(0.0025, 89.970016, 0.002503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.3141015599999, 4065.74289062, 370.77777344000003), 'rotation':(0.00405, 89.969894, 0.004036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.31281249999995, 4060.47265625, 370.77710937999996), 'rotation':(0.007479, 89.969887, 0.007474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.3103125, 4049.93210938, 370.77535156), 'rotation':(0.010307, 89.970085, 0.010302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(460.30781249999995, 4039.39257812, 370.77289062000006), 'rotation':(0.0, 89.999985, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30652344, 4034.12132812, 370.7715625), 'rotation':(0.014808, 89.969933, 0.014799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30523438, 4028.85109375, 370.77019530999996), 'rotation':(0.014808, 89.969933, 0.014799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30402344000004, 4023.5807812499997, 370.76890625), 'rotation':(0.01435, 89.969933, 0.014346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30273437999995, 4018.3103125, 370.76765625), 'rotation':(0.013462, 89.969933, 0.013454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30152344, 4013.04, 370.76644531), 'rotation':(0.013462, 89.969933, 0.013454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.26640625, 4002.49265625, 371.11972656), 'rotation':(0.105007, -90.146271, 0.104624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.2809374999999, 4008.16820312, 371.10933594), 'rotation':(0.104843, -90.146301, 0.104464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(572.32445312, 4025.1940624999997, 371.07742188), 'rotation':(0.110171, -90.146027, 0.109757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.3389843799999, 4030.86960938, 371.06632812000004), 'rotation':(0.1122, -90.146667, 0.111759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.3534374999999, 4036.54492188, 371.05511719000003), 'rotation':(0.113279, -90.146088, 0.112843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.36796875, 4042.22023438, 371.04390625), 'rotation':(0.113279, -90.146698, 0.112828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.4115625, 4059.24632812, 371.00863281), 'rotation':(0.12153, -90.146576, 0.121024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.42601562, 4064.92140625, 370.99605469), 'rotation':(0.127076, -90.146118, 0.126525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.50957031, 4097.5303125, 370.9175), 'rotation':(0.146316, -90.146362, 0.14557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.52351562, 4102.98195312, 370.9034375), 'rotation':(0.146316, -90.146362, 0.14557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.5374609400001, 4108.4340625, 370.88914062000003), 'rotation':(0.150483, -90.145935, 0.149698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.55140625, 4113.88625, 370.87453125), 'rotation':(0.150483, -90.145935, 0.149698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.56535156, 4119.33789062, 370.85980469000003), 'rotation':(0.154069, -90.146301, 0.153246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.5792968799999, 4124.79, 370.84472655999997), 'rotation':(0.158249, -90.146271, 0.157379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.59320312, 4130.2421875, 370.82960937999997), 'rotation':(0.15999, -90.145813, 0.159109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(572.6350781200001, 4146.59859375, 370.78410155999995), 'rotation':(0.15844, -90.145905, 0.157565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(572.6490625, 4152.05078125, 370.76910155999997), 'rotation':(0.15844, -90.145905, 0.157565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.66296875, 4157.50296875, 370.75414062000004), 'rotation':(0.157142, -90.146362, 0.156288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.67695312, 4162.95460938, 370.73933594000005), 'rotation':(0.155844, -90.145935, 0.155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.6908593799999, 4168.40671875, 370.72453125), 'rotation':(0.155844, -90.145935, 0.155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.71875, 4179.31101562, 370.69496094000004), 'rotation':(0.155271, -90.145935, 0.154431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.99529297, 4113.65382812, 370.64484375), 'rotation':(0.201511, -90.033691, 0.200105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.99865234, 4119.085, 370.62464844000004), 'rotation':(0.212979, -90.033966, 0.2114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.00195312, 4124.515625, 370.60359375), 'rotation':(0.212979, -90.033966, 0.2114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(680.00525391, 4129.94679688, 370.58234375), 'rotation':(0.224433, -90.033875, 0.222674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(680.01177734, 4140.8090625, 370.53816406), 'rotation':(0.233217, -90.033783, 0.231332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.01507812, 4146.24070312, 370.51542969), 'rotation':(0.239781, -90.033722, 0.237786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.02166016, 4157.10304688, 370.46910155999996), 'rotation':(0.246522, -90.033264, 0.244401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.02820312, 4167.96484375, 370.42128906), 'rotation':(0.252895, -90.0336, 0.250675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(679.98529297, 4013.816875, 370.9328125), 'rotation':(0.133353, -90.034363, 0.132733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.98382812, 4019.47703125, 370.91929688), 'rotation':(0.137307, -90.034332, 0.136656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.98101562, 4030.79710938, 370.89140625), 'rotation':(0.141269, -90.034302, 0.140573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97960938, 4036.45726562, 370.87703125), 'rotation':(0.145032, -90.034302, 0.144306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97828125, 4042.11742188, 370.86261719000004), 'rotation':(0.147006, -90.034119, 0.146259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.9768750000001, 4047.77757812, 370.84785156), 'rotation':(0.150073, -90.034302, 0.149292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97546875, 4053.4375, 370.8328125), 'rotation':(0.150073, -90.034302, 0.149292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97400391, 4059.09789062, 370.81742188), 'rotation':(0.155715, -90.034271, 0.154874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.9711914100001, 4070.41773438, 370.7853125), 'rotation':(0.161582, -90.033813, 0.160666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.33718750000003, 4633.76023438, 372.19890625), 'rotation':(0.004686, -90.07962, 0.004676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.34554688000003, 4639.2621875, 372.1984375), 'rotation':(0.004686, -90.07962, 0.004676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.37874999999997, 4661.26953125, 372.19664062000004), 'rotation':(0.004877, -90.07959, 0.004881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.395390619999944, 4672.27296875, 372.1959375), 'rotation':(0.003545, -90.07959, 0.003543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.40367188000005, 4677.77490234, 372.19578125), 'rotation':(0.001462, -90.07959, 0.001457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.41195311999991, 4683.27685547, 372.19574219000003), 'rotation':(0.001462, -90.07959, 0.001457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.42031250000002, 4688.77880859, 372.19570312), 'rotation':(0.000376, -90.07959, 0.000377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.436874999999986, 4699.78222656, 372.19566405999996), 'rotation':(0.000376, -90.07959, 0.000374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.44515624999997, 4705.28417969, 372.19558594), 'rotation':(0.000376, -90.07959, 0.000377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(40.98593749999998, 4381.0034375, 372.21941405999996), 'rotation':(0.009426, -90.079651, 0.009428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.97804688000008, 4375.34132812, 372.22035156), 'rotation':(0.008825, -90.079559, 0.008824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.970156249999945, 4369.67921875, 372.22121094), 'rotation':(0.009091, -90.07959, 0.009089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.962265619999926, 4364.01757812, 372.22210937999995), 'rotation':(0.008825, -90.07959, 0.008827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.938671880000015, 4347.03171875, 372.22464844), 'rotation':(0.004228, -90.07959, 0.004224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(40.922968749999995, 4335.70851562, 372.22546875), 'rotation':(0.002411, -90.07959, 0.002398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.907187499999964, 4324.38429688, 372.2259375), 'rotation':(0.002623, -90.07959, 0.002617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.899374999999964, 4318.72265625, 372.22621094000004), 'rotation':(0.002411, -90.07959, 0.002398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.15164061999997, 4500.31398438, 372.18585937999995), 'rotation':(0.006058, -90.07959, 0.006053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.14414061999992, 4494.90476562, 372.18621094), 'rotation':(0.006058, -90.07959, 0.006053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.12906250000003, 4484.08546875, 372.18789062), 'rotation':(0.017622, -90.07959, 0.017618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.12156249999998, 4478.67578125, 372.18941406), 'rotation':(0.023421, -90.07959, 0.023399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.114062500000045, 4473.26609375, 372.19136719), 'rotation':(0.023421, -90.07959, 0.023399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.09156250000001, 4457.03808594, 372.19835937999994), 'rotation':(0.022765, -90.079559, 0.022756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.08406249999996, 4451.6284375, 372.20054688), 'rotation':(0.021556, -90.07959, 0.021546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.07648438000001, 4446.21921875, 372.20257812000006), 'rotation':(0.02004, -90.07959, 0.02003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.068984380000074, 4440.81007812, 372.20449219), 'rotation':(0.018817, -90.079559, 0.018814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.05398438000009, 4429.99171875, 372.20804688), 'rotation':(0.016085, -90.079559, 0.016085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(41.04648438000004, 4424.58203125, 372.20960937999996), 'rotation':(0.015218, -90.07959, 0.015212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.03890624999997, 4419.17285156, 372.21105469), 'rotation':(0.015163, -90.07959, 0.015144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.29148438000004, 4601.03417969, 372.19796875), 'rotation':(-0.00705, -90.07959, -0.00705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.28359375000002, 4595.35449219, 372.19730469), 'rotation':(-0.007965, -90.07959, -0.007965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.26781249999999, 4583.99460938, 372.195625), 'rotation':(-0.010162, -90.07962, -0.010162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.25992188000009, 4578.31445312, 372.19453125), 'rotation':(-0.01236, -90.079559, -0.01236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.25203124999996, 4572.63476562, 372.19328125), 'rotation':(-0.014282, -90.07959, -0.014282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.24421874999996, 4566.95460938, 372.19175780999996), 'rotation':(-0.015625, -90.07959, -0.015625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(41.23625000000004, 4561.27441406, 372.19023438), 'rotation':(-0.015381, -90.079559, -0.015381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.22835938000003, 4555.59472656, 372.18871094), 'rotation':(-0.015625, -90.07959, -0.015656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.22054688000003, 4549.91453125, 372.18714844000004), 'rotation':(-0.015381, -90.079559, -0.015381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.21257811999999, 4544.23484375, 372.185625), 'rotation':(-0.006256, -90.07959, -0.006226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.20468749999998, 4538.55421875, 372.18449219), 'rotation':(-0.006256, -90.07959, -0.006226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.19687499999998, 4532.87453125, 372.18398437999997), 'rotation':(0.003429, -90.07962, 0.003421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.18898438000008, 4527.19433594, 372.18433594000004), 'rotation':(0.003142, -90.07959, 0.003144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(32.866406249999955, 4313.07125, 372.22648438), 'rotation':(-0.002625, 89.92041, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(32.87429688000009, 4318.7334375, 372.22621094000004), 'rotation':(-0.002625, 89.92041, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(32.889999999999986, 4330.05710938, 372.22570312000005), 'rotation':(-0.002625, 89.920395, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(32.91367188000004, 4347.0425, 372.22464844), 'rotation':(-0.007141, 89.92041, -0.007141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(32.92148438000004, 4352.70410156, 372.22386719), 'rotation':(-0.009094, 89.920395, -0.009094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(32.94507811999995, 4369.68992188, 372.22121094), 'rotation':(-0.00882, 89.920395, -0.00882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(32.95296874999997, 4375.35203125, 372.22035156), 'rotation':(-0.00943, 89.92041, -0.00943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(32.9765625, 4392.33789062, 372.21738281), 'rotation':(-0.01181, 89.920403, -0.01178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.01382811999997, 4419.18359375, 372.21105469), 'rotation':(-0.015228, 89.920403, -0.015228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.02132811999991, 4424.59277344, 372.20960937999996), 'rotation':(-0.016113, 89.920395, -0.016113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.02890624999998, 4430.00242188, 372.20804688), 'rotation':(-0.017303, 89.920418, -0.017334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.043906249999964, 4440.82078125, 372.20449219), 'rotation':(-0.02005, 89.920403, -0.02005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.05148438000003, 4446.23, 372.20257812000006), 'rotation':(-0.021545, 89.920418, -0.021576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.05898438000008, 4451.63964844, 372.20054688), 'rotation':(-0.022766, 89.920395, -0.022797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.06648438000002, 4457.04882812, 372.19835937999994), 'rotation':(-0.024292, 89.920418, -0.024323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.07398438000007, 4462.45851562, 372.19609375), 'rotation':(-0.025818, 89.920418, -0.025848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.081484380000006, 4467.86765625, 372.19363281), 'rotation':(-0.025543, 89.92038, -0.025543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.09648437999999, 4478.68703125, 372.18941406), 'rotation':(-0.017639, 89.920403, -0.017639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.10398438000004, 4484.09667969, 372.18789062), 'rotation':(-0.012115, 89.920395, -0.012115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.11148438000009, 4489.50632812, 372.18675780999996), 'rotation':(-0.006042, 89.920418, -0.006042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.11898438000003, 4494.91601562, 372.18621094), 'rotation':(-0.003235, 89.92041, -0.003235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.12656249999998, 4500.32519531, 372.18585937999995), 'rotation':(-0.003235, 89.92041, -0.003235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.16390624999997, 4527.20507812, 372.18433594000004), 'rotation':(-0.003418, 89.920395, -0.003418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.17171874999997, 4532.88523438, 372.18398437999997), 'rotation':(0.006236, 89.920395, 0.006246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.17960937999999, 4538.56492188, 372.18449219), 'rotation':(0.015368, 89.920403, 0.01537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.1875, 4544.245625, 372.185625), 'rotation':(0.015368, 89.920403, 0.01537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.19546875000003, 4549.9253125, 372.18714844000004), 'rotation':(0.015634, 89.920403, 0.015625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.20328125000003, 4555.60546875, 372.18871094), 'rotation':(0.015368, 89.920395, 0.015365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.21906249999995, 4566.9653125, 372.19179687999997), 'rotation':(0.014282, 89.920395, 0.01427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.22695311999996, 4572.64550781, 372.19328125), 'rotation':(0.012356, 89.920395, 0.012351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.23484374999998, 4578.32519531, 372.19453125), 'rotation':(0.010163, 89.920403, 0.010156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.242812500000014, 4584.00539062, 372.195625), 'rotation':(0.007964, 89.920395, 0.007961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(33.25851561999991, 4595.36523438, 372.19730469), 'rotation':(0.007049, 89.92041, 0.007044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.266484380000065, 4601.04492188, 372.19796875), 'rotation':(0.007049, 89.92041, 0.007044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.418906249999964, 4710.79785156, 372.19554687999994), 'rotation':(-0.000183, 89.920395, -0.000183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.411093749999964, 4705.29589844, 372.19558594), 'rotation':(-0.000183, 89.920395, -0.000183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.403437499999995, 4699.79443359, 372.19566405999996), 'rotation':(-0.000366, 89.92041, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.39570312000001, 4694.29248047, 372.19566405999996), 'rotation':(-0.000366, 89.92041, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(33.38796875000003, 4688.79052734, 372.19570312), 'rotation':(-0.000366, 89.920395, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(33.372499999999945, 4677.78710938, 372.19578125), 'rotation':(-0.000366, 89.92041, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.34937500000001, 4661.28171875, 372.19664062000004), 'rotation':(-0.00354, 89.92041, -0.00354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.34164061999991, 4655.77976562, 372.19707030999996), 'rotation':(-0.004883, 89.920395, -0.004883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.33382811999991, 4650.2778125, 372.1975), 'rotation':(-0.004883, 89.920395, -0.004883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.31070311999997, 4633.77246094, 372.19890625), 'rotation':(-0.004883, 89.920395, -0.004883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.6335156199999, 4392.18015625, 371.17664062000006), 'rotation':(0.044745, -90.045471, 0.04468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.62914061999993, 4386.66945312, 371.18085937999996), 'rotation':(0.048972, -90.045715, 0.048895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.62039061999997, 4375.64695312, 371.19015625), 'rotation':(0.053194, -90.045685, 0.053109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.61593749999997, 4370.13574219, 371.19523438), 'rotation':(0.055202, -90.045593, 0.05509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.6071875, 4359.11375, 371.20585938), 'rotation':(0.055188, -90.045776, 0.055088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.59835938000003, 4348.09226562, 371.21601562), 'rotation':(0.045878, -90.045624, 0.045795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.58953125000005, 4337.07125, 371.22296875), 'rotation':(0.008401, -90.045654, 0.008394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.58507811999993, 4331.56054688, 371.22453125), 'rotation':(0.008401, -90.045654, 0.008394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.57632811999997, 4320.53953125, 371.22417969), 'rotation':(-0.019318, -90.045685, -0.019348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.57187499999998, 4315.02882812, 371.22265625), 'rotation':(-0.019623, -90.045685, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.71703125, 4494.4253125, 371.11566406), 'rotation':(0.034028, -90.045776, 0.033986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.71414061999997, 4489.0190625, 371.11886719), 'rotation':(0.032573, -90.045776, 0.032545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.71117188000005, 4483.6128125, 371.12199219), 'rotation':(0.032573, -90.045776, 0.032545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.70539062, 4472.80078125, 371.128125), 'rotation':(0.031303, -90.045593, 0.031274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.7025, 4467.39453125, 371.13105469000004), 'rotation':(0.03075, -90.045715, 0.030714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.69953124999995, 4461.98828125, 371.13398437999996), 'rotation':(0.03075, -90.045715, 0.030714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.69664061999993, 4456.5825, 371.136875), 'rotation':(0.031002, -90.045654, 0.030974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.68789061999996, 4440.36328125, 371.14589844), 'rotation':(0.033338, -90.045654, 0.033302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.68499999999995, 4434.95703125, 371.1490625), 'rotation':(0.034342, -90.045654, 0.0343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.67914062, 4424.14453125, 371.15566406), 'rotation':(0.036002, -90.045654, 0.035963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.80421875000002, 4606.245625, 371.08050781), 'rotation':(-0.020233, -90.045654, -0.020233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.79515625, 4594.88328125, 371.07648437999995), 'rotation':(-0.000885, -90.045776, -0.000885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.78609374999996, 4583.52, 371.07578125), 'rotation':(0.018674, -90.045593, 0.018656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.78164061999996, 4577.83835938, 371.07757812000006), 'rotation':(0.018455, -90.045807, 0.018437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.77250000000004, 4566.47609375, 371.08128905999996), 'rotation':(0.018674, -90.045807, 0.018649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.7634375, 4555.11375, 371.08496094000003), 'rotation':(0.020217, -90.045715, 0.020202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.75437499999998, 4543.75097656, 371.08886719000003), 'rotation':(0.023434, -90.045715, 0.023413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.74539061999997, 4532.38867188, 371.09371094), 'rotation':(0.02687, -90.045715, 0.026853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.8302343800001, 4638.84570312, 371.09257812000004), 'rotation':(-0.023773, -90.045563, -0.023804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.83460938000007, 4644.36476562, 371.09492187999996), 'rotation':(-0.024475, -90.045563, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.83898438000006, 4649.88378906, 371.09730469000004), 'rotation':(-0.024475, -90.045898, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.84343750000005, 4655.40234375, 371.09964844), 'rotation':(-0.024506, -90.045593, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.8522656199999, 4666.44042969, 371.10441405999995), 'rotation':(-0.024475, -90.045563, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.85664062, 4671.95945312, 371.10675781), 'rotation':(-0.024506, -90.045898, -0.024536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.86101562, 4677.47851562, 371.10910156), 'rotation':(-0.024841, -90.045563, -0.024841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.86546875, 4682.99707031, 371.11074219), 'rotation':(-0.024841, -90.045563, -0.024841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.86984374999997, 4688.51513672, 371.11171875), 'rotation':(-0.012939, -90.045685, -0.012939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.8742968800001, 4694.03369141, 371.11078125), 'rotation':(0.009603, -90.045685, 0.00959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.87874999999997, 4699.55224609, 371.10917969), 'rotation':(0.020853, -90.045807, 0.02084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.88312499999995, 4705.07128906, 371.10714844), 'rotation':(0.021201, -90.045807, 0.021181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.88750000000005, 4710.59033203, 371.10511719000004), 'rotation':(0.020853, -90.045471, 0.020841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.546875, 4315.03515625, 371.22265625), 'rotation':(0.019323, 89.954323, 0.019316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.55562499999996, 4326.05710938, 371.22515625), 'rotation':(-0.008392, 89.95433, -0.008392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.56015624999998, 4331.56734375, 371.22453125), 'rotation':(-0.027344, 89.954239, -0.027374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.56445311999994, 4337.07765625, 371.22296875), 'rotation':(-0.027344, 89.954239, -0.027374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.56890625000005, 4342.58835938, 371.2203125), 'rotation':(-0.045868, 89.954361, -0.045929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.57328125000004, 4348.09863281, 371.21601562), 'rotation':(-0.055206, 89.954292, -0.055298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.58648438, 4364.63132812, 371.20054688), 'rotation':(-0.055206, 89.954384, -0.055298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.59531249999998, 4375.65382812, 371.19015625), 'rotation':(-0.048981, 89.954292, -0.049042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.60398438000004, 4386.67578125, 371.18085937999996), 'rotation':(-0.044739, 89.954407, -0.04483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.60843750000004, 4392.18703125, 371.17664062000006), 'rotation':(-0.040771, 89.954269, -0.040833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.57085938, 4429.558125, 371.15234375), 'rotation':(-0.034332, 89.954338, -0.034393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.5802343800001, 4434.964375, 371.1490625), 'rotation':(-0.033356, 89.954323, -0.033386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.59882812, 4445.776875, 371.14277344000004), 'rotation':(-0.031677, 89.954163, -0.031708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.60812499999997, 4451.18359375, 371.13980469), 'rotation':(-0.031006, 89.954323, -0.031036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.61742188000005, 4456.58984375, 371.136875), 'rotation':(-0.030762, 89.954361, -0.030792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.64546874999996, 4472.808125, 371.128125), 'rotation':(-0.032593, 89.954216, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.65476561999992, 4478.21386719, 371.12507812), 'rotation':(-0.032593, 89.954216, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.68273438000006, 4494.43261719, 371.11566406), 'rotation':(-0.035461, 89.9543, -0.035522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.69210938000003, 4499.83886719, 371.11234375), 'rotation':(-0.035461, 89.9543, -0.035522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.71578124999996, 4526.71484375, 371.09648438), 'rotation':(-0.026886, 89.954292, -0.026886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.72031249999998, 4532.39648438, 371.09371094), 'rotation':(-0.023438, 89.954285, -0.023468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.73390625000002, 4549.441875, 371.08683594), 'rotation':(-0.018646, 89.9543, -0.018677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.7428906199999, 4560.80566406, 371.083125), 'rotation':(-0.018646, 89.9543, -0.018677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.74742188000005, 4566.48730469, 371.08128905999996), 'rotation':(-0.018463, 89.954208, -0.018463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.75656249999997, 4577.85058594, 371.07757812000006), 'rotation':(-0.018646, 89.9543, -0.018677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.76101561999997, 4583.53273438, 371.07578125), 'rotation':(0.000888, 89.954285, 0.000886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.77468750000003, 4600.57910156, 371.07847655999996), 'rotation':(0.020033, 89.954254, 0.020028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(246.7791406199999, 4606.26074219, 371.08050781), 'rotation':(0.020033, 89.954254, 0.020028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.86234375000004, 4710.59814453, 371.10511719000004), 'rotation':(-0.02121, 89.954323, -0.02124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.85796875000005, 4705.07958984, 371.10714844), 'rotation':(-0.020844, 89.954369, -0.020874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.85359374999996, 4699.56152344, 371.10917969), 'rotation':(-0.021179, 89.95417, -0.02121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(246.84921874999998, 4694.04345703, 371.11078125), 'rotation':(-0.020844, 89.954361, -0.020874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.84476561999998, 4688.52490234, 371.11171875), 'rotation':(-0.009583, 89.9543, -0.009613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.84031249999998, 4683.00732422, 371.11074219), 'rotation':(0.012936, 89.954193, 0.012932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.83156250000002, 4666.45070312, 371.10441405999995), 'rotation':(0.0245, 89.954247, 0.024466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.82273438000004, 4660.93457031, 371.10203125), 'rotation':(0.0245, 89.954414, 0.024475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.81835938000006, 4655.41601562, 371.0996875), 'rotation':(0.024486, 89.954247, 0.02447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.80953124999996, 4644.37890625, 371.09492187999996), 'rotation':(0.0245, 89.954247, 0.024466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.80515624999998, 4638.86085938, 371.09257812000004), 'rotation':(0.0245, 89.954414, 0.024475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.80078125, 4633.34226562, 371.09027344000003), 'rotation':(0.023776, 89.954254, 0.023754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(468.95671875000005, 4605.76269531, 370.27242187999997), 'rotation':(0.014494, -90.270996, 0.014483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.90296875, 4594.3984375, 370.27542969), 'rotation':(0.016024, -90.271179, 0.016016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.87609375, 4588.71632812, 370.27699219000004), 'rotation':(0.018168, -90.270996, 0.01816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.8492578099999, 4583.03417969, 370.27882812), 'rotation':(0.020511, -90.270996, 0.020501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(468.82238281, 4577.3515625, 370.28070312000006), 'rotation':(0.020511, -90.270996, 0.020501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(468.79546875000005, 4571.66945312, 370.28273437999997), 'rotation':(0.022861, -90.27121, 0.022848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(468.74171875, 4560.3046875, 370.28726562), 'rotation':(0.024131, -90.270874, 0.024117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.68792969000003, 4548.94042969, 370.29203125), 'rotation':(0.026617, -90.271057, 0.026591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(468.63414062000004, 4537.57617188, 370.29761719000004), 'rotation':(0.036473, -90.271057, 0.036429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.60730469, 4531.89355469, 370.30097656), 'rotation':(0.036473, -90.271057, 0.036429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(468.5804296900001, 4526.21140625, 370.3046875), 'rotation':(0.04165, -90.271027, 0.041584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.45019531, 4709.87011719, 370.25234375), 'rotation':(0.010915, -90.271149, 0.01091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.42652344, 4704.36621094, 370.25339844), 'rotation':(0.010908, -90.270905, 0.01091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.40269531, 4698.86279297, 370.25449219), 'rotation':(0.010908, -90.270905, 0.01091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.35523437999996, 4687.85498047, 370.25660156), 'rotation':(0.010819, -90.271179, 0.010817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(469.30773437999994, 4676.84765625, 370.25859375), 'rotation':(0.010184, -90.271179, 0.01018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(469.28398438, 4671.34375, 370.25957030999996), 'rotation':(0.009863, -90.270874, 0.009857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(469.26023437999993, 4665.8403125, 370.26054688), 'rotation':(0.00987, -90.27121, 0.009864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(469.18898437999997, 4649.32910156, 370.26335937999994), 'rotation':(0.010273, -90.271149, 0.010267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(469.16523438, 4643.82519531, 370.26429687999996), 'rotation':(0.010273, -90.271149, 0.010267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.14148437999995, 4638.32179688, 370.2653125), 'rotation':(0.011509, -90.270935, 0.011514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.55542969, 4526.24953125, 370.3046875), 'rotation':(-0.036469, 89.728928, -0.03653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(460.58234374999995, 4531.93164062, 370.30097656), 'rotation':(-0.031555, 89.728943, -0.031586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.63609375, 4543.29640625, 370.29460937999994), 'rotation':(-0.026611, 89.728943, -0.026642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.66296875, 4548.97898438, 370.29203125), 'rotation':(-0.023865, 89.728851, -0.023895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.71671875000004, 4560.34328125, 370.28726562), 'rotation':(-0.022858, 89.728813, -0.022888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.74367187999997, 4566.02539062, 370.28496094), 'rotation':(-0.022858, 89.728813, -0.022888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.82421875, 4583.07226562, 370.27882812), 'rotation':(-0.018158, 89.729004, -0.018188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(460.85113280999997, 4588.75488281, 370.27699219000004), 'rotation':(-0.016022, 89.728783, -0.016022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.87800781, 4594.43703125, 370.27542969), 'rotation':(-0.015167, 89.728973, -0.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(460.90484375000005, 4600.11914062, 370.27386719000003), 'rotation':(-0.014496, 89.728996, -0.014496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(460.93175781, 4605.80125, 370.27242187999997), 'rotation':(-0.013824, 89.728996, -0.013824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(461.33113281, 4693.3984375, 370.25550781), 'rotation':(-0.010925, 89.729073, -0.010925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(461.08769530999996, 4649.36867188, 370.26335937999994), 'rotation':(-0.009674, 89.728973, -0.009674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(461.05726562000007, 4643.86476562, 370.26429687999996), 'rotation':(-0.009674, 89.728973, -0.009674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.99644531, 4632.85742188, 370.26640625), 'rotation':(-0.010284, 89.728844, -0.010284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1515.96558594, 4000.78835938, 360.75785156), 'rotation':(-0.6427, 0.007206, -0.657257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1513.3287500000001, 4006.36257812, 360.62074219000004), 'rotation':(-0.245544, -80.961365, -0.24765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1504.91003906, 4005.01804688, 360.62074219000004), 'rotation':(0.26997, 99.03846, 0.26743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1716.9056249999999, 4007.3125, 358.52128905999996), 'rotation':(-0.760651, -80.658356, -0.781036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1715.244375, 4017.3503124999997, 358.65773437999997), 'rotation':(-0.767151, -80.657257, -0.787903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1714.41359375, 4022.36914062, 358.72640625), 'rotation':(-0.772949, -80.658112, -0.794037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1713.58296875, 4027.38820312, 358.79539062000003), 'rotation':(-0.772949, -80.658112, -0.794037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1712.75242188, 4032.40695312, 358.86457031), 'rotation':(-0.779388, -80.657166, -0.800812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1711.9217187499999, 4037.42601562, 358.93402344000003), 'rotation':(-0.78241, -80.657898, -0.804016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1703.5084375000001, 4036.03195312, 358.93386719), 'rotation':(0.782145, 99.342094, 0.761017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1705.09289062, 4026.3896875, 358.80070312000004), 'rotation':(0.779393, 99.3423, 0.75841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1706.67734375, 4016.7473437500003, 358.6684375), 'rotation':(0.772959, 99.342651, 0.752303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1707.4696875, 4011.92601562, 358.60273437999996), 'rotation':(0.772959, 99.342651, 0.752303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1708.2618750000001, 4007.10523438, 358.53730469000004), 'rotation':(0.767126, 99.341705, 0.746785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1709.0540624999999, 4002.28367188, 358.47222655999997), 'rotation':(0.760767, 99.342239, 0.740773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1493.58972656, 4125.67671875, 361.73082030999996), 'rotation':(-0.769073, -80.585693, -0.789948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1495.40003906, 4114.745625, 361.58195312000004), 'rotation':(-0.749237, -80.587769, -0.769043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1497.2103124999999, 4103.81492188, 361.43894531), 'rotation':(-0.719116, -80.586487, -0.737335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1498.11546875, 4098.34859375, 361.36921875), 'rotation':(-0.701599, -80.58902, -0.718933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1499.02074219, 4092.88234375, 361.30183594000005), 'rotation':(-0.665009, -80.588196, -0.680573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1499.92601562, 4087.41625, 361.23800781), 'rotation':(-0.628326, -80.590698, -0.642242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1500.83117188, 4081.9496875, 361.17773437999995), 'rotation':(-0.592377, -80.591064, -0.604706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1501.73644531, 4076.48289062, 361.12101562000004), 'rotation':(-0.555725, -80.590515, -0.566589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1502.64171875, 4071.0168750000003, 361.06789062), 'rotation':(-0.519073, -80.592896, -0.528534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1504.4524999999999, 4060.08375, 360.97222655999997), 'rotation':(-0.446442, -80.593719, -0.453461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1505.35765625, 4054.61765625, 360.929375), 'rotation':(-0.428284, -80.593964, -0.434723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1506.2628125, 4049.15234375, 360.88796875), 'rotation':(-0.428314, -80.593658, -0.434753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1489.20484375, 4152.15328125, 362.11421875), 'rotation':(-0.841064, -80.584137, -0.866028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1487.40003906, 4163.05273438, 362.27847656), 'rotation':(-0.852966, -80.58429, -0.878662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1486.4971875, 4168.50296875, 362.36300781), 'rotation':(-0.877228, -80.583282, -0.904388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1485.59484375, 4173.95265625, 362.44804688), 'rotation':(-0.877228, -80.583282, -0.904388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1484.69238281, 4179.401875, 362.53496094), 'rotation':(-0.901489, -80.58255, -0.930206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1483.7899218799998, 4184.85203125, 362.62277344), 'rotation':(-0.901489, -80.58255, -0.930206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1482.8873437500001, 4190.30125, 362.71203125), 'rotation':(-0.925598, -80.581787, -0.955872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1481.98472656, 4195.7509375, 362.80199219), 'rotation':(-0.937836, -80.581787, -0.968933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1481.0825, 4201.1996875, 362.8925), 'rotation':(-0.938538, -80.580994, -0.969666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1478.37511719, 4217.54734375, 363.16484375), 'rotation':(-0.941895, -80.581635, -0.973267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1477.47277344, 4222.9965625, 363.25585937999995), 'rotation':(-0.943604, -80.581543, -0.975098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1474.76574219, 4239.34421875, 363.52992187999996), 'rotation':(-0.948486, -80.58139, -0.980316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1470.34007812, 4266.06789062, 363.97773437999996), 'rotation':(-0.939819, -80.581146, -0.971069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1468.48707031, 4277.25632812, 364.16289062000004), 'rotation':(-0.934204, -80.581909, -0.965027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1465.7076562500001, 4294.04, 364.4375), 'rotation':(-0.922394, -80.581726, -0.952484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1464.78113281, 4299.63429688, 364.52835938), 'rotation':(-0.919525, -80.582672, -0.949402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1462.92847656, 4310.82273438, 364.70726562000004), 'rotation':(-0.902588, -80.582214, -0.931396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1462.00195312, 4316.41703125, 364.795), 'rotation':(-0.891052, -80.583832, -0.919098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1460.14917969, 4327.60546875, 364.96699219000004), 'rotation':(-0.85733, -80.583588, -0.883301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1459.22265625, 4333.1996875, 365.05117187999997), 'rotation':(-0.845764, -80.585205, -0.871033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1457.36976562, 4344.38867188, 365.21652344), 'rotation':(-0.828888, -80.584656, -0.853149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1456.44324219, 4349.98339844, 365.29859375), 'rotation':(-0.828888, -80.584656, -0.853149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1497.85179688, 4047.76125, 360.88800781), 'rotation':(0.428294, 99.406059, 0.421918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1496.94652344, 4053.22703125, 360.92941406), 'rotation':(0.446448, 99.407555, 0.439535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1495.13574219, 4064.16039062, 361.01828125), 'rotation':(0.519067, 99.407097, 0.509733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1494.23035156, 4069.6276562499997, 361.06789062), 'rotation':(0.555725, 99.409454, 0.545022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1493.32496094, 4075.09445312, 361.12105469), 'rotation':(0.592362, 99.408936, 0.580214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1492.4196875, 4080.56179688, 361.1778125), 'rotation':(0.62833, 99.410553, 0.614663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1491.51402344, 4086.0285937500003, 361.23808594), 'rotation':(0.664994, 99.410545, 0.649688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1490.6087499999999, 4091.495625, 361.30191406), 'rotation':(0.701617, 99.4114, 0.684598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1489.70335938, 4096.96242188, 361.36933594000004), 'rotation':(0.719089, 99.413498, 0.701218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1488.79808594, 4102.42875, 361.43902344), 'rotation':(0.729696, 99.411697, 0.711288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1487.8928125, 4107.895, 361.50960938), 'rotation':(0.749279, 99.413765, 0.729884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1486.9876562499999, 4113.36085938, 361.58207031), 'rotation':(0.769018, 99.412727, 0.748581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1486.08238281, 4118.82664062, 361.65585938), 'rotation':(0.788853, 99.414848, 0.767349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1485.17726562, 4124.29296875, 361.7309375), 'rotation':(0.788853, 99.414848, 0.767349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1466.35265625, 4237.961875, 363.53011719), 'rotation':(0.949943, 99.41864, 0.918822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1469.05980469, 4221.61421875, 363.25605469000004), 'rotation':(0.945428, 99.419243, 0.914594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1469.96214844, 4216.165, 363.16496094), 'rotation':(0.943611, 99.419563, 0.912908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1470.86460938, 4210.71578125, 363.07410156), 'rotation':(0.943611, 99.419563, 0.912908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1472.66957031, 4199.81734375, 362.89265625), 'rotation':(0.940148, 99.418312, 0.90968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1474.47472656, 4188.91890625, 362.71222656), 'rotation':(0.937846, 99.41819, 0.907513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1475.37707031, 4183.4696875, 362.62296875), 'rotation':(0.925607, 99.418213, 0.896054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1476.27964844, 4178.01953125, 362.53511719), 'rotation':(0.925607, 99.418213, 0.896054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1477.18210938, 4172.5703125, 362.44816405999995), 'rotation':(0.901537, 99.417908, 0.873501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1478.08460938, 4167.120625, 362.36320312000004), 'rotation':(0.901537, 99.417908, 0.873501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1479.88964844, 4156.22070312, 362.19636719000005), 'rotation':(0.852927, 99.41597, 0.82782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1480.79210938, 4150.77101562, 362.114375), 'rotation':(0.852927, 99.41597, 0.82782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1448.0321093799998, 4348.59179688, 365.29863280999996), 'rotation':(0.829082, 99.414742, 0.805344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1448.95851562, 4342.99757812, 365.2165625), 'rotation':(0.829082, 99.414742, 0.805344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1450.81128906, 4331.80953125, 365.05121094000003), 'rotation':(0.834847, 99.414467, 0.810778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1451.7376562499999, 4326.21578125, 364.96699219000004), 'rotation':(0.84583, 99.416878, 0.82113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1453.5903125, 4315.02828125, 364.79507812), 'rotation':(0.880131, 99.415817, 0.853399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1455.443125, 4303.84132812, 364.61851562000004), 'rotation':(0.902603, 99.416504, 0.874489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1456.369375, 4298.24757812, 364.5284375), 'rotation':(0.913838, 99.418152, 0.885028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1458.2221875, 4287.05953125, 364.34636719), 'rotation':(0.922417, 99.418274, 0.89306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1459.14855469, 4281.46578125, 364.25488280999997), 'rotation':(0.922417, 99.418274, 0.89306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1461.92773438, 4264.6840625, 363.97789062000004), 'rotation':(0.93424, 99.418663, 0.904136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1297.29761719, 4088.56054688, 363.7721875), 'rotation':(0.06406, -80.475769, 0.06392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1298.19787109, 4083.19507812, 363.778125), 'rotation':(0.053617, -80.474426, 0.053521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1300.89880859, 4067.09789062, 363.79238281), 'rotation':(0.04887, -80.475861, 0.048775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1302.69945312, 4056.36625, 363.80167969), 'rotation':(0.04887, -80.474731, 0.048778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1303.59972656, 4051.00023438, 363.80628906), 'rotation':(0.04887, -80.474731, 0.048778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1304.5, 4045.6354687499997, 363.81058594), 'rotation':(0.018783, -80.475555, 0.018758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1309.90125, 4013.44382812, 363.78191405999996), 'rotation':(-0.071777, -80.475128, -0.07196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1290.15857422, 4131.10890625, 363.6903125), 'rotation':(0.129664, -80.475006, 0.129075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1289.244375, 4136.55765625, 363.67941406), 'rotation':(0.106551, -80.474335, 0.106153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1288.33007812, 4142.00585938, 363.67054687999996), 'rotation':(0.083718, -80.474396, 0.083472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1287.41578125, 4147.45460938, 363.66375), 'rotation':(0.060591, -80.47641, 0.060462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1286.50158203, 4152.9028125, 363.6584375), 'rotation':(0.060591, -80.47641, 0.060462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1285.58765625, 4158.350625, 363.65371094), 'rotation':(0.049061, -80.475189, 0.048989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1284.67333984, 4163.79984375, 363.64929687999995), 'rotation':(0.049341, -80.474487, 0.049247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1283.75927734, 4169.24757812, 363.64734375), 'rotation':(0.020634, -80.475708, 0.020616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1281.93029297, 4180.1475, 363.65886719), 'rotation':(-0.093689, -80.474792, -0.093994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1281.01585938, 4185.59765625, 363.67179688), 'rotation':(-0.151123, -80.475281, -0.151917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1280.09960938, 4191.04734375, 363.68957030999997), 'rotation':(-0.208008, -80.474213, -0.209503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1279.18701172, 4196.49703125, 363.71207031), 'rotation':(-0.208008, -80.474213, -0.209503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1278.27246094, 4201.94679688, 363.73929688), 'rotation':(-0.265442, -80.473724, -0.267914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1272.8907421899999, 4234.0190625, 363.98144530999997), 'rotation':(-0.545013, -80.46933, -0.55545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1271.03064453, 4245.10546875, 364.10273437999996), 'rotation':(-0.630707, -80.468445, -0.644714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1270.10095703, 4250.64601562, 364.17300781), 'rotation':(-0.716125, -80.466125, -0.734192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1268.24097656, 4261.7309375, 364.32917969000005), 'rotation':(-0.802063, -80.464142, -0.824768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1267.31140625, 4267.27046875, 364.41132812), 'rotation':(-0.840149, -80.462463, -0.865051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1266.38195312, 4272.81054688, 364.49257812), 'rotation':(-0.831268, -80.463928, -0.855652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1265.45238281, 4278.35007812, 364.57304688), 'rotation':(-0.822388, -80.462982, -0.846252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1262.66382812, 4294.96921875, 364.80914062000005), 'rotation':(-0.795746, -80.464935, -0.818085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1260.8048046899999, 4306.04929688, 364.96234375), 'rotation':(-0.777985, -80.464203, -0.799316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1259.87523438, 4311.58984375, 365.03820312000005), 'rotation':(-0.773499, -80.464722, -0.794586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1258.94568359, 4317.12984375, 365.1140625), 'rotation':(-0.773499, -80.464722, -0.794586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1287.98804688, 4092.52414062, 363.76523438), 'rotation':(-0.083557, 99.524269, -0.083801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1288.88830078, 4087.1584375, 363.7721875), 'rotation':(-0.073822, 99.52562, -0.074005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1289.78857422, 4081.79273438, 363.778125), 'rotation':(-0.064056, 99.523758, -0.064209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1290.68896484, 4076.42648438, 363.783125), 'rotation':(-0.053619, 99.525574, -0.053711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1291.58935547, 4071.06007812, 363.78773437999996), 'rotation':(-0.048859, 99.524132, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1292.48974609, 4065.69359375, 363.79238281), 'rotation':(-0.048859, 99.524132, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1293.39013672, 4060.32742188, 363.79703125), 'rotation':(-0.048859, 99.525238, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1294.29052734, 4054.9609375, 363.80167969), 'rotation':(-0.048859, 99.524956, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1296.09130859, 4044.22898438, 363.81058594), 'rotation':(-0.048859, 99.524956, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1296.99169922, 4038.8628125, 363.81238281), 'rotation':(-0.018768, 99.524796, -0.018799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1298.79175781, 4028.13328125, 363.80238281), 'rotation':(0.072052, 99.524864, 0.071871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1299.69226562, 4022.7668750000003, 363.79554687999996), 'rotation':(0.071772, 99.524506, 0.071601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1268.94847656, 4205.99609375, 363.77140625), 'rotation':(0.379738, 99.527542, 0.374731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1270.77734375, 4195.09671875, 363.71210937999996), 'rotation':(0.265435, 99.526268, 0.262983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1272.60632812, 4184.19679688, 363.67183594), 'rotation':(0.207993, 99.525787, 0.206492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1275.34972656, 4167.8471875, 363.64730469), 'rotation':(0.036808, 99.525055, 0.036758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1276.26378906, 4162.399375, 363.64929687999995), 'rotation':(-0.02063, 99.5243, -0.02066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1278.09203125, 4151.50296875, 363.6584375), 'rotation':(-0.049072, 99.524796, -0.049164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1279.92029297, 4140.6059375, 363.67054687999996), 'rotation':(-0.060577, 99.523598, -0.060699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1280.83472656, 4135.15773438, 363.67941406), 'rotation':(-0.08371, 99.525581, -0.083954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1281.74890625, 4129.70898438, 363.69027344), 'rotation':(-0.106537, 99.524887, -0.106934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1283.57703125, 4118.8134375, 363.71617188), 'rotation':(-0.136139, 99.525787, -0.13678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1252.39648438, 4304.64109375, 364.96238281), 'rotation':(0.773485, 99.53524, 0.752809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1254.25525391, 4293.5625, 364.80921875), 'rotation':(0.786858, 99.534813, 0.765458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1257.04333984, 4276.94484375, 364.57308594), 'rotation':(0.813489, 99.536766, 0.790633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1257.97289062, 4271.40578125, 364.49269531), 'rotation':(0.822382, 99.535805, 0.799015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1258.9022265600001, 4265.86671875, 364.41144531), 'rotation':(0.831254, 99.53727, 0.807394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1259.83166016, 4260.3271875, 364.32929687999996), 'rotation':(0.840147, 99.537521, 0.815765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1261.69140625, 4249.24367188, 364.173125), 'rotation':(0.802062, 99.535851, 0.779831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1262.6209765600001, 4243.70359375, 364.10289062000004), 'rotation':(0.716125, 99.533859, 0.698385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1105.33507812, 4002.26171875, 367.14648437999995), 'rotation':(0.121987, -80.972778, 0.121465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1104.48572266, 4007.6081249999997, 367.13460938), 'rotation':(0.12629, -80.973419, 0.125738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1103.63647461, 4012.9540625, 367.12234375), 'rotation':(0.130477, -80.973389, 0.129893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1101.93798828, 4023.64671875, 367.09675781), 'rotation':(0.138216, -80.972961, 0.13756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1100.239375, 4034.33914062, 367.06960938), 'rotation':(0.145633, -80.973145, 0.144896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1099.39001953, 4039.6848437500003, 367.0553125), 'rotation':(0.145633, -80.973145, 0.144896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1098.54077148, 4045.03125, 367.04054687999997), 'rotation':(0.156589, -80.973083, 0.155744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1097.69152344, 4050.37742188, 367.02492187999997), 'rotation':(0.156589, -80.973083, 0.155744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1096.84240234, 4055.723125, 367.0090625), 'rotation':(0.16736, -80.973022, 0.166392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1090.89685547, 4093.23875, 366.88300781), 'rotation':(0.207248, -80.973328, 0.205746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1090.02917969, 4098.6953125, 366.86253905999996), 'rotation':(0.214632, -80.972534, 0.213019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1088.29394531, 4109.60742188, 366.81996094000004), 'rotation':(0.221749, -80.972137, 0.220044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1086.55847656, 4120.52046875, 366.77648437999994), 'rotation':(0.22526, -80.97229, 0.223505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1084.82299805, 4131.433125, 366.73296875), 'rotation':(0.225861, -80.973175, 0.224088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1082.2199707, 4147.80226562, 366.6671875), 'rotation':(0.227589, -80.97287, 0.225788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1080.48449707, 4158.714375, 366.62324219000004), 'rotation':(0.227794, -80.972107, 0.225981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1079.61694336, 4164.1709375, 366.60074219), 'rotation':(0.231612, -80.972809, 0.229735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1078.74914551, 4169.62648438, 366.57753906), 'rotation':(0.239753, -80.972717, 0.237755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1073.63928223, 4201.78664062, 366.42644530999996), 'rotation':(0.278412, -80.971893, 0.275715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1072.75402832, 4207.35984375, 366.39769530999996), 'rotation':(0.292216, -80.972137, 0.289256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1071.86865234, 4212.93265625, 366.36792969000004), 'rotation':(0.292216, -80.972137, 0.289256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1070.09802246, 4224.0790625, 366.3028125), 'rotation':(0.347069, -80.971527, 0.342891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1069.21276855, 4229.651875, 366.26804688), 'rotation':(0.347069, -80.971527, 0.342891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1068.32739258, 4235.22507812, 366.23121094000004), 'rotation':(0.374383, -80.971161, 0.369524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1067.4420166, 4240.79882812, 366.19386719), 'rotation':(0.381166, -80.970886, 0.376118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1065.67089844, 4251.94726562, 366.12195312000006), 'rotation':(0.352916, -80.972076, 0.348597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1064.78540039, 4257.52148438, 366.08808594000004), 'rotation':(0.339133, -80.972229, 0.335134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1063.01428223, 4268.66992188, 366.02449219000005), 'rotation':(0.310951, -80.971771, 0.307591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1061.24328613, 4279.81835938, 365.9665625), 'rotation':(0.282722, -80.972839, 0.279945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1060.35778809, 4285.39257812, 365.93914062000005), 'rotation':(0.282722, -80.972839, 0.279945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1095.87414062, 4007.48023438, 367.13191406), 'rotation':(-0.130493, 99.026581, -0.131073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1095.04431641, 4012.70382812, 367.11984375), 'rotation':(-0.134338, 99.026619, -0.134979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1094.21435547, 4017.92820312, 367.10746094), 'rotation':(-0.138214, 99.028313, -0.138885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1092.55493164, 4028.37429688, 367.0815625), 'rotation':(-0.14563, 99.026848, -0.146362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1090.89550781, 4038.82078125, 367.05402344000004), 'rotation':(-0.156586, 99.026901, -0.15744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1090.06554688, 4044.04445312, 367.03953125), 'rotation':(-0.167358, 99.02697, -0.168335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1089.23583984, 4049.2678125, 367.02425781), 'rotation':(-0.167358, 99.02697, -0.168335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1087.56970703, 4059.7160937500003, 366.99226562), 'rotation':(-0.183655, 99.025673, -0.184845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1069.46325684, 4173.734375, 366.55363280999995), 'rotation':(-0.255768, 99.027382, -0.258057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1070.32897949, 4168.27734375, 366.57761719), 'rotation':(-0.24762, 99.027328, -0.249756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1071.19470215, 4162.8203125, 366.60078125), 'rotation':(-0.239746, 99.027252, -0.24176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1072.06030273, 4157.36328125, 366.62328125), 'rotation':(-0.231598, 99.027191, -0.23349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1072.92602539, 4151.90671875, 366.6453125), 'rotation':(-0.231598, 99.027191, -0.23349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1074.65734863, 4140.9921875, 366.68921875), 'rotation':(-0.22757, 99.026634, -0.229401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1075.52307129, 4135.53515625, 366.71113281), 'rotation':(-0.22757, 99.026634, -0.229401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1076.38879395, 4130.07765625, 366.73304687999996), 'rotation':(-0.226898, 99.028145, -0.228699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1077.2545166, 4124.620625, 366.75480469), 'rotation':(-0.225861, 99.02681, -0.227631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1078.98596191, 4113.70609375, 366.79828125), 'rotation':(-0.22525, 99.027138, -0.22702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1079.8515625, 4108.2490625, 366.82003906), 'rotation':(-0.22525, 99.027702, -0.227051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1080.71728516, 4102.79203125, 366.8415625), 'rotation':(-0.221741, 99.027176, -0.22345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1081.58288574, 4097.335, 366.86261719000004), 'rotation':(-0.221741, 99.027176, -0.22345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1051.93835449, 4284.05320312, 365.93917969), 'rotation':(-0.275909, 99.027428, -0.278595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1053.70959473, 4272.90382812, 365.99488281), 'rotation':(-0.282745, 99.027939, -0.285553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1054.59521484, 4267.3290625, 366.02453125), 'rotation':(-0.29715, 99.028534, -0.300232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1055.48083496, 4261.754375, 366.05558594), 'rotation':(-0.310944, 99.027435, -0.314331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1056.36645508, 4256.1796875, 366.08808594000004), 'rotation':(-0.325043, 99.027596, -0.328735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1057.25195312, 4250.605, 366.12199219), 'rotation':(-0.339172, 99.029785, -0.343201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1058.13769531, 4245.0303125, 366.15726562000003), 'rotation':(-0.352936, 99.027931, -0.3573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1059.02331543, 4239.45507812, 366.19394531), 'rotation':(-0.367035, 99.029343, -0.371765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1064.33581543, 4206.01320312, 366.39777344000004), 'rotation':(-0.31955, 99.02816, -0.32312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1065.22119141, 4200.43945312, 366.42652344000004), 'rotation':(-0.292236, 99.027863, -0.295197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1041.38195801, 4398.84667969, 365.943125), 'rotation':(-0.268158, -80.481445, -0.270691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1043.21838379, 4387.89304688, 365.89484375), 'rotation':(-0.209351, -80.481934, -0.210876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1044.13647461, 4382.41796875, 365.87457030999997), 'rotation':(-0.150543, -80.481049, -0.151337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1045.9732666, 4371.46289062, 365.84628906), 'rotation':(-0.121277, -80.483002, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1047.80932617, 4360.51074219, 365.82277344), 'rotation':(-0.121033, -80.481995, -0.121552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1048.72741699, 4355.035625, 365.81101562000003), 'rotation':(-0.121277, -80.483002, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1049.64550781, 4349.55957031, 365.79929688), 'rotation':(-0.121277, -80.483002, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1051.48266602, 4338.60351562, 365.79160156), 'rotation':(0.11739, -80.482971, 0.116919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1035.15490723, 4435.98828125, 366.20332031), 'rotation':(-0.460419, -80.478149, -0.467865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1034.25793457, 4441.33789062, 366.25089844), 'rotation':(-0.498535, -80.478424, -0.507294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1033.36132812, 4446.68652344, 366.30171875), 'rotation':(-0.536865, -80.478333, -0.546997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1031.56762695, 4457.38429688, 366.40996094), 'rotation':(-0.574982, -80.476074, -0.586609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1030.67102051, 4462.73242188, 366.46617188), 'rotation':(-0.594299, -80.476868, -0.60672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1029.77441406, 4468.08054688, 366.5234375), 'rotation':(-0.606232, -80.475494, -0.619171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1028.87744141, 4473.42921875, 366.58289062000006), 'rotation':(-0.631012, -80.476257, -0.64502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1027.08398438, 4484.12742188, 366.70878905999996), 'rotation':(-0.679871, -80.475159, -0.696167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1025.29052734, 4494.82519531, 366.84410155999996), 'rotation':(-0.728729, -80.473938, -0.747467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1022.6003418, 4510.87011719, 367.06347655999997), 'rotation':(-0.790131, -80.471222, -0.812164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1021.70385742, 4516.21777344, 367.13828125), 'rotation':(-0.790131, -80.471222, -0.812164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1032.05700684, 4402.90773438, 365.97289062000004), 'rotation':(0.327166, 99.519157, 0.323446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1032.97521973, 4397.4296875, 365.94304687999994), 'rotation':(0.327166, 99.519157, 0.323446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1033.89318848, 4391.95507812, 365.91707031), 'rotation':(0.268174, 99.518547, 0.265668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1034.81152344, 4386.47703125, 365.89484375), 'rotation':(0.268174, 99.518547, 0.265668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1035.7298584, 4381.00148438, 365.87453125), 'rotation':(0.209366, 99.518059, 0.20783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1037.56640625, 4370.04785156, 365.84628906), 'rotation':(0.150551, 99.518204, 0.149759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1039.40234375, 4359.09667969, 365.82273438), 'rotation':(0.121297, 99.516975, 0.12078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1040.3203125, 4353.6215625, 365.81101562000003), 'rotation':(0.121031, 99.517982, 0.12053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1041.23828125, 4348.14648438, 365.79929688), 'rotation':(0.121031, 99.517982, 0.12053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1042.15698242, 4342.66648438, 365.79179688), 'rotation':(0.121304, 99.517647, 0.120784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1043.07519531, 4337.1909375, 365.79160156), 'rotation':(0.001858, 99.517586, 0.001862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1043.99401855, 4331.71046875, 365.79921875), 'rotation':(-0.117401, 99.517029, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1044.9119873, 4326.23585938, 365.81058594), 'rotation':(-0.117401, 99.517876, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1045.82995605, 4320.76023438, 365.82195312000005), 'rotation':(-0.117401, 99.517876, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1014.19256592, 4509.45898438, 367.0634375), 'rotation':(0.789884, 99.528297, 0.768322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1015.98614502, 4498.76074219, 366.91515625), 'rotation':(0.777924, 99.527992, 0.757006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1016.88305664, 4493.41210938, 366.84402344), 'rotation':(0.753172, 99.527321, 0.733559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1017.77984619, 4488.0625, 366.77519530999996), 'rotation':(0.728733, 99.526695, 0.71037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1018.67669678, 4482.71335938, 366.70875), 'rotation':(0.704561, 99.52523, 0.687393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1020.47039795, 4472.01414062, 366.5828125), 'rotation':(0.655111, 99.52491, 0.640259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1021.36737061, 4466.66503906, 366.52335938), 'rotation':(0.630993, 99.524376, 0.617213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1023.16082764, 4455.96875, 366.40988281), 'rotation':(0.594295, 99.52359, 0.58206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1024.95458984, 4445.26953125, 366.30167969), 'rotation':(0.574999, 99.523468, 0.563539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1026.74829102, 4434.57128906, 366.20328125), 'rotation':(0.498556, 99.521591, 0.489922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1437.0711718799998, 4468.0546875, 366.83863281), 'rotation':(-0.703674, -80.722046, -0.72113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1439.70835938, 4451.89550781, 366.6378125), 'rotation':(-0.697571, -80.723358, -0.714752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1440.58753906, 4446.50878906, 366.57136719000005), 'rotation':(-0.693451, -80.722717, -0.710388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1441.4665625, 4441.12207031, 366.50496094000005), 'rotation':(-0.693451, -80.722717, -0.710388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1443.22472656, 4430.34914062, 366.37296875), 'rotation':(-0.689545, -80.723053, -0.706268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1444.10203125, 4424.97507812, 366.30742188), 'rotation':(-0.4422, -81.115906, -0.449097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1444.98277344, 4419.57617188, 366.24132812000005), 'rotation':(-0.70343, -80.723572, -0.720856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1445.86195312, 4414.18992188, 366.17457031), 'rotation':(-0.714813, -80.721191, -0.732849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1446.74085938, 4408.80371094, 366.10671875), 'rotation':(-0.72525, -80.722198, -0.743774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1447.61988281, 4403.4175, 366.03789062000004), 'rotation':(-0.736206, -80.722717, -0.75531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1449.37792969, 4392.64550781, 365.8971875), 'rotation':(-0.757629, -80.722168, -0.777863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1441.84253906, 4385.8871875, 365.82527344000005), 'rotation':(0.7577, 99.279884, 0.737856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1440.96351562, 4391.27296875, 365.8971875), 'rotation':(0.747236, 99.277542, 0.727926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1440.08445312, 4396.65917969, 365.96804688), 'rotation':(0.736267, 99.278076, 0.717526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1439.20542969, 4402.04492188, 366.03789062000004), 'rotation':(0.725168, 99.278236, 0.70699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1437.44761719, 4412.81738281, 366.17457031), 'rotation':(0.703489, 99.278511, 0.68636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1435.68945312, 4423.58984375, 366.30726562), 'rotation':(0.689487, 99.277184, 0.673052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1434.81042969, 4428.9765625, 366.37296875), 'rotation':(0.693449, 99.27655, 0.676814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1433.05226562, 4439.74953125, 366.50496094000005), 'rotation':(0.697615, 99.27787, 0.680795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1432.17320312, 4445.13625, 366.57132812000003), 'rotation':(0.697615, 99.27787, 0.680795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1430.41503906, 4455.90917969, 366.7046875), 'rotation':(0.70368, 99.277, 0.686549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1428.6568750000001, 4466.68210938, 366.83863281), 'rotation':(0.703667, 99.277939, 0.686549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1636.99046875, 4496.8403125, 365.3165625), 'rotation':(-0.729065, -80.819641, -0.747803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1637.8678125000001, 4491.40625, 365.24644530999996), 'rotation':(-0.738403, -80.81897, -0.757599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1638.74511719, 4485.973125, 365.17550781), 'rotation':(-0.747803, -80.820007, -0.767517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1641.37683594, 4469.67089844, 364.95695312000004), 'rotation':(-0.776306, -80.819214, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1642.25414062, 4464.23632812, 364.88226562000006), 'rotation':(-0.781311, -80.818787, -0.802856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1644.00878906, 4453.36765625, 364.73164062), 'rotation':(-0.79364, -80.819031, -0.815826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1644.8860937499999, 4447.93359375, 364.655625), 'rotation':(-0.79364, -80.819031, -0.815826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1647.51792969, 4431.63085938, 364.4246875), 'rotation':(-0.809845, -80.818054, -0.832977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1648.39527344, 4426.19726562, 364.34679687999994), 'rotation':(-0.814117, -80.817566, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1649.2725781200002, 4420.76269531, 364.26855469000003), 'rotation':(-0.814087, -80.818115, -0.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1650.14992188, 4415.328125, 364.19035155999995), 'rotation':(-0.814087, -80.818115, -0.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1618.41136719, 4611.92578125, 366.78183594), 'rotation':(-0.757202, -80.81958, -0.777405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1619.3053125000001, 4606.38867188, 366.70765625), 'rotation':(-0.757202, -80.81958, -0.777405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1621.0931249999999, 4595.31445312, 366.56003906), 'rotation':(-0.741821, -80.819702, -0.76123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1621.98707031, 4589.776875, 366.48707031), 'rotation':(-0.741821, -80.819702, -0.76123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1622.88085938, 4584.24023438, 366.41441405999996), 'rotation':(-0.731323, -80.819946, -0.750183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1623.77492188, 4578.70265625, 366.3428125), 'rotation':(-0.721008, -80.820221, -0.739319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1625.56273438, 4567.62695312, 366.2009375), 'rotation':(-0.715881, -80.819427, -0.733948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1627.3507031200002, 4556.55320312, 366.06070312), 'rotation':(-0.713318, -80.820557, -0.731232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1629.1384375, 4545.47898438, 365.92132812000006), 'rotation':(-0.708405, -80.820984, -0.726074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1630.03234375, 4539.9409375, 365.85203125), 'rotation':(-0.703857, -80.820282, -0.721313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1631.8201953100001, 4528.86671875, 365.71449219000004), 'rotation':(-0.6987, -80.820435, -0.715912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1641.73328125, 4413.96921875, 364.19035155999995), 'rotation':(0.814124, 99.182434, 0.791236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1640.8559375, 4419.40382812, 364.26855469000003), 'rotation':(0.814124, 99.182434, 0.791236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1639.97863281, 4424.83789062, 364.34679687999994), 'rotation':(0.809821, 99.181931, 0.787175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1639.1014453100001, 4430.27246094, 364.4246875), 'rotation':(0.801646, 99.182541, 0.779446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1633.83777344, 4462.87742188, 364.88226562000006), 'rotation':(0.776306, 99.180756, 0.755472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1631.20582031, 4479.1796875, 365.10359375), 'rotation':(0.747783, 99.18, 0.728453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1630.3284765600001, 4484.61476562, 365.17550781), 'rotation':(0.738384, 99.181038, 0.719545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1629.45128906, 4490.04882812, 365.24648437999997), 'rotation':(0.729054, 99.180351, 0.710679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1628.57398438, 4495.48195312, 365.3165625), 'rotation':(0.719274, 99.17926, 0.701382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1627.69679688, 4500.91601562, 365.38566405999995), 'rotation':(0.709486, 99.179474, 0.692077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1609.9947656200002, 4610.5659375, 366.78179687999994), 'rotation':(0.757434, 99.180435, 0.737604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1610.88867188, 4605.02882812, 366.70765625), 'rotation':(0.757434, 99.180435, 0.737604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1612.67652344, 4593.95460938, 366.56003906), 'rotation':(0.752154, 99.18058, 0.732592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1613.5703125, 4588.41699219, 366.48707031), 'rotation':(0.752154, 99.18058, 0.732592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1615.35828125, 4577.34277344, 366.3428125), 'rotation':(0.731322, 99.180023, 0.712831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1616.2521875, 4571.80515625, 366.2715625), 'rotation':(0.731322, 99.180023, 0.712831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1618.03980469, 4560.7309375, 366.13070312), 'rotation':(0.721015, 99.179779, 0.703029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1620.72179688, 4544.11960938, 365.92132812000006), 'rotation':(0.713304, 99.179436, 0.695706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1621.61570312, 4538.58203125, 365.85203125), 'rotation':(0.7084, 99.179024, 0.691043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1623.40355469, 4527.50828125, 365.71449219000004), 'rotation':(0.703844, 99.179703, 0.686711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1834.7790625, 4535.10839844, 363.38140625), 'rotation':(-0.834045, -80.115082, -0.858582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1835.70859375, 4529.76757812, 363.30589844), 'rotation':(-0.834045, -80.115082, -0.858582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1837.568125, 4519.08351562, 363.1459375), 'rotation':(-0.879333, -80.11322, -0.906647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1839.42734375, 4508.39992188, 362.97625), 'rotation':(-0.924774, -80.111755, -0.955017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1840.35726562, 4503.05710938, 362.88871094), 'rotation':(-0.928131, -80.112488, -0.958588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1841.2875, 4497.71335938, 362.80101562000004), 'rotation':(-0.889923, -80.113678, -0.917877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1844.07773438, 4481.68117188, 362.56074219000004), 'rotation':(-0.775299, -80.116089, -0.796509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1845.0080468800002, 4476.33640625, 362.48820312000004), 'rotation':(-0.73764, -80.117981, -0.756836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1846.86828125, 4465.64796875, 362.35449219000003), 'rotation':(-0.660889, -80.118958, -0.6763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1848.728125, 4454.9609375, 362.231875), 'rotation':(-0.641907, -80.119781, -0.656433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1816.0310156199998, 4642.83105469, 364.67191406), 'rotation':(-0.593842, -80.121521, -0.606262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1817.9225781199998, 4631.96242188, 364.55753905999995), 'rotation':(-0.593567, -80.120605, -0.605957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1818.86828125, 4626.5278125, 364.50007812), 'rotation':(-0.603729, -80.120422, -0.616547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1819.8140625, 4621.09375, 364.44191406), 'rotation':(-0.623688, -80.120544, -0.63739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1820.75960938, 4615.6596875, 364.38226562000006), 'rotation':(-0.643738, -80.119537, -0.658325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1821.7053125, 4610.2265625, 364.32171875), 'rotation':(-0.643738, -80.119537, -0.658325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1822.65109375, 4604.79199219, 364.25972656), 'rotation':(-0.663696, -80.119629, -0.679199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1825.4884375000001, 4588.49070312, 364.0671875), 'rotation':(-0.680939, -80.118042, -0.697266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1826.4342187500001, 4583.05617188, 364.00160156), 'rotation':(-0.695679, -80.118958, -0.712738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1827.37984375, 4577.62257812, 363.93464844000005), 'rotation':(-0.7099, -80.118103, -0.727661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1828.32554688, 4572.18898438, 363.8671875), 'rotation':(-0.7099, -80.118103, -0.727661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1829.27132812, 4566.75488281, 363.79882812000005), 'rotation':(-0.724609, -80.118256, -0.743134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1841.2585156199998, 4448.15867188, 362.17113280999996), 'rotation':(0.641908, 99.880219, 0.627649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1839.39804688, 4458.84765625, 362.29273437999996), 'rotation':(0.660834, 99.880096, 0.645727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1837.5375, 4469.53859375, 362.41957031), 'rotation':(0.73766, 99.881996, 0.718849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1836.60703125, 4474.88476562, 362.48835937999996), 'rotation':(0.775226, 99.882988, 0.754448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1834.74609375, 4485.57570312, 362.6371875), 'rotation':(0.852025, 99.885162, 0.826959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1832.88515625, 4496.26757812, 362.80125), 'rotation':(0.928127, 99.888863, 0.898419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1831.9546875, 4501.61328125, 362.88902344), 'rotation':(0.924773, 99.887482, 0.895275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1831.02476562, 4506.9565625, 362.9765625), 'rotation':(0.879284, 99.886269, 0.852596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1830.095, 4512.29929688, 363.06300781), 'rotation':(0.879284, 99.886269, 0.852596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1829.16492188, 4517.64355469, 363.14628905999996), 'rotation':(0.834068, 99.885437, 0.810045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1826.3751562500001, 4533.67285156, 363.38175780999995), 'rotation':(0.788941, 99.884384, 0.767441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1821.81335938, 4559.88574219, 363.72984375), 'rotation':(0.709896, 99.881897, 0.692463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1817.0860937500001, 4587.04734375, 364.06738280999997), 'rotation':(0.674133, 99.878708, 0.658413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1816.1404687499999, 4592.48, 364.13269531), 'rotation':(0.663724, 99.88092, 0.648474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1815.1951562499999, 4597.91210938, 364.19664062000004), 'rotation':(0.643718, 99.88047, 0.62938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1814.2497656199998, 4603.34421875, 364.25992188), 'rotation':(0.643718, 99.88047, 0.62938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1812.3587499999999, 4614.20898438, 364.38234375), 'rotation':(0.623692, 99.879463, 0.610218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1811.4133593800002, 4619.64160156, 364.44203125), 'rotation':(0.603727, 99.879593, 0.591112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1810.46789062, 4625.07421875, 364.50011719), 'rotation':(0.593502, 99.878479, 0.58131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1808.576875, 4635.93945312, 364.61476562), 'rotation':(0.593905, 99.879425, 0.581686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1807.63125, 4641.37207031, 364.67191406), 'rotation':(0.593557, 99.879402, 0.581366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.3899999999999, 4856.73095703, 364.2190625), 'rotation':(-0.277313, -90.229706, -0.280029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.3444531199998, 4845.44726562, 364.16460937999994), 'rotation':(-0.283173, -90.229675, -0.286011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.32164062, 4839.8046875, 364.13675781), 'rotation':(-0.2854, -90.229248, -0.288269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.29882812, 4834.16308594, 364.10859375), 'rotation':(-0.289642, -90.229889, -0.292572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.27601562, 4828.52099609, 364.08007812000005), 'rotation':(-0.296875, -90.229797, -0.299988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.2532812499999, 4822.87890625, 364.05101562000004), 'rotation':(-0.304169, -90.229736, -0.307404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.23046875, 4817.23730469, 364.02144531), 'rotation':(-0.304169, -90.229736, -0.307404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.2077343800001, 4811.59521484, 363.99140625), 'rotation':(-0.311859, -90.229645, -0.315277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.18507812, 4805.953125, 363.96070312000006), 'rotation':(-0.315582, -90.229156, -0.319061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.13953125, 4794.66943359, 363.8984375), 'rotation':(-0.320679, -90.229309, -0.32428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.0939843800002, 4783.38623047, 363.83296875), 'rotation':(-0.353516, -90.228882, -0.35788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.07117188, 4777.74462891, 363.79847656), 'rotation':(-0.364594, -90.230164, -0.369232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.04859375, 4772.10253906, 363.76277344000005), 'rotation':(-0.375305, -90.228638, -0.380249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.00304688, 4760.81982422, 363.68769531), 'rotation':(-0.397125, -90.228333, -0.402679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1966.9802343800002, 4755.17773438, 363.64851562), 'rotation':(-0.402832, -90.228302, -0.408508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1966.9575, 4749.53613281, 363.60882812000006), 'rotation':(-0.402771, -90.228271, -0.408478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.5232812499999, 4889.71923828, 364.36851562000004), 'rotation':(-0.247498, -90.230347, -0.249634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.5462499999999, 4895.40039062, 364.3928125), 'rotation':(-0.247498, -90.230347, -0.249634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.5690625, 4901.08105469, 364.41660156), 'rotation':(-0.239532, -90.230408, -0.241547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.59203125, 4906.76171875, 364.43992188), 'rotation':(-0.239532, -90.230408, -0.241547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.615, 4912.44287109, 364.46292969), 'rotation':(-0.23175, -90.229767, -0.233643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.63796875, 4918.12353516, 364.48527344), 'rotation':(-0.23175, -90.229767, -0.233643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.70664062, 4935.16650391, 364.55226562), 'rotation':(-0.229431, -90.22995, -0.231262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.75242188, 4946.52832031, 364.59949219000003), 'rotation':(-0.242065, -90.229858, -0.24411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.82125, 4963.57177734, 364.67460938), 'rotation':(-0.261017, -90.229675, -0.263397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.84414062, 4969.25244141, 364.70082031), 'rotation':(-0.261017, -90.229675, -0.263397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.8670312499999, 4974.93408203, 364.72746094), 'rotation':(-0.267029, -90.229614, -0.269531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1958.45507812, 4755.21191406, 363.64851562), 'rotation':(0.39708, 89.771675, 0.391614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.5006250000001, 4766.49560547, 363.72589844000004), 'rotation':(0.375298, 89.771362, 0.370411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.5232812499999, 4772.13671875, 363.76277344000005), 'rotation':(0.364602, 89.769836, 0.359996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.54601562, 4777.77880859, 363.79847656), 'rotation':(0.353517, 89.771103, 0.349174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.56882812, 4783.42041016, 363.83296875), 'rotation':(0.342794, 89.770966, 0.33871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.5915625, 4789.06201172, 363.86628906), 'rotation':(0.332063, 89.770844, 0.328236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.614375, 4794.70361328, 363.8984375), 'rotation':(0.315596, 89.770828, 0.312134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.6599218800002, 4805.98681641, 363.96070312000006), 'rotation':(0.31186, 89.770355, 0.308483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.68265625, 4811.62890625, 363.99140625), 'rotation':(0.304148, 89.770279, 0.300918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1958.728125, 4822.91259766, 364.05101562000004), 'rotation':(0.296895, 89.77018, 0.293828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.7509375, 4828.5546875, 364.08007812000005), 'rotation':(0.289627, 89.770126, 0.286705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.86484375, 4856.76464844, 364.2190625), 'rotation':(0.27193, 89.770241, 0.26935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.34179688, 4974.96826172, 364.72746094), 'rotation':(0.270462, 89.769775, 0.267928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1959.27304688, 4957.92480469, 364.64898437999994), 'rotation':(0.261016, 89.770302, 0.258657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.2501562500001, 4952.24365234, 364.62394530999995), 'rotation':(0.254684, 89.769127, 0.252426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1959.2271875000001, 4946.5625, 364.59949219000003), 'rotation':(0.248113, 89.77018, 0.245963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.20421875, 4940.88134766, 364.57558594), 'rotation':(0.242082, 89.770142, 0.240029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.18125, 4935.20019531, 364.55226562), 'rotation':(0.23573, 89.768951, 0.233802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.13546875, 4923.83837891, 364.50746094000004), 'rotation':(0.222828, 89.769997, 0.221092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.0896093800002, 4912.47705078, 364.46292969), 'rotation':(0.223798, 89.769455, 0.222049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.0666406199998, 4906.79638672, 364.43992188), 'rotation':(0.231748, 89.769524, 0.229887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.02085938, 4895.43457031, 364.3928125), 'rotation':(0.239542, 89.770302, 0.237538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1958.99789062, 4889.75341797, 364.36851562000004), 'rotation':(0.239542, 89.770302, 0.237538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.54742432, 5274.33642578, 371.60351562000005), 'rotation':(0.041288, -89.897644, 0.041238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.55743408, 5268.71777344, 371.60769531), 'rotation':(0.041288, -89.897644, 0.041238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.56750488, 5263.09960938, 371.61175781), 'rotation':(0.040155, -89.897552, 0.040094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.58758545, 5251.86279297, 371.61921875), 'rotation':(0.034458, -89.897583, 0.034411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.59759521, 5246.24462891, 371.62257812), 'rotation':(0.03161, -89.897552, 0.03158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.61761475, 5235.0078125, 371.62835937999995), 'rotation':(0.025914, -89.897583, 0.025902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.62762451, 5229.38916016, 371.63082031), 'rotation':(0.023072, -89.897583, 0.023055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.63769531, 5223.77099609, 371.63300781), 'rotation':(0.020224, -89.897583, 0.020214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.64770508, 5218.15283203, 371.635), 'rotation':(0.019002, -89.897766, 0.018992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.65777588, 5212.53417969, 371.63683594), 'rotation':(0.018995, -89.897766, 0.018982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.71795654, 5178.82470703, 371.6428125), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.72796631, 5173.20605469, 371.6415625), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.73803711, 5167.58740234, 371.64035156), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.74804688, 5161.96923828, 371.6390625), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.75811768, 5156.35058594, 371.6378125), 'rotation':(-0.018127, -89.897644, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.76812744, 5150.73242188, 371.63628905999997), 'rotation':(-0.018127, -89.897644, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.77850342, 5145.12011719, 371.63453125), 'rotation':(-0.028839, -89.897644, -0.02887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.78820801, 5139.49560547, 371.63191406), 'rotation':(-0.028839, -89.897644, -0.02887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.8182373, 5122.64160156, 371.62105469), 'rotation':(-0.050293, -89.897614, -0.050385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.82830811, 5117.02294922, 371.61613280999995), 'rotation':(-0.055939, -89.897614, -0.056061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.83831787, 5111.40429688, 371.6109375), 'rotation':(-0.055939, -89.897614, -0.056061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.84832764, 5105.78613281, 371.60539062000004), 'rotation':(-0.059387, -89.897766, -0.059509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.8684082, 5094.54980469, 371.59335938), 'rotation':(-0.066986, -89.8974, -0.067139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.878479, 5088.93115234, 371.58679687999995), 'rotation':(-0.074249, -89.897736, -0.074432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.88848877, 5083.31298828, 371.57972656), 'rotation':(-0.074249, -89.897736, -0.074432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.93859863, 5055.22119141, 371.53914062), 'rotation':(-0.091553, -89.897552, -0.091858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.96868896, 5038.36621094, 371.51082031), 'rotation':(-0.104004, -89.897522, -0.10437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.97875977, 5032.74804688, 371.50058594), 'rotation':(-0.108521, -89.897491, -0.108948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.98876953, 5027.12939453, 371.49003905999996), 'rotation':(-0.112183, -89.896912, -0.11264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.99884033, 5021.51171875, 371.47910156), 'rotation':(-0.116699, -89.897461, -0.117188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(990.0088501, 5015.89306641, 371.46777344000003), 'rotation':(-0.118591, -89.897522, -0.11908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.49951172, 5301.18945312, 371.57667969), 'rotation':(0.069989, -89.897675, 0.069817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.47937012, 5312.46240234, 371.56230469), 'rotation':(0.074394, -89.897522, 0.0742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.46929932, 5318.09912109, 371.55488281), 'rotation':(0.074695, -89.897522, 0.074496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.45922852, 5323.73535156, 371.54691406), 'rotation':(0.078738, -89.897705, 0.078525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.44915771, 5329.37207031, 371.53804687999997), 'rotation':(0.086538, -89.897064, 0.086291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.43914795, 5335.00828125, 371.52839844000005), 'rotation':(0.095015, -89.897675, 0.094703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.42907715, 5340.645, 371.51789062000006), 'rotation':(0.103143, -89.897644, 0.102764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.41906738, 5346.28125, 371.50652344), 'rotation':(0.119405, -89.896942, 0.118913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.40899658, 5351.91796875, 371.49433594000004), 'rotation':(0.127554, -89.897552, 0.12699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.39892578, 5357.55421875, 371.48136719), 'rotation':(0.135361, -89.897522, 0.134707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.38885498, 5363.1909375, 371.46769530999995), 'rotation':(0.139705, -89.897461, 0.139032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.36871338, 5374.46335938, 371.439375), 'rotation':(0.145927, -89.897339, 0.145192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.35864258, 5380.09960938, 371.42402344000004), 'rotation':(0.145927, -89.897339, 0.145192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.32849121, 5397.00929688, 371.37410156), 'rotation':(0.170864, -89.89682, 0.169851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.30834961, 5408.28222656, 371.33753906), 'rotation':(0.189722, -89.897522, 0.188482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.28820801, 5419.55566406, 371.30015625), 'rotation':(0.190514, -89.896942, 0.189254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.27813721, 5425.19238281, 371.28136719), 'rotation':(0.190788, -89.896942, 0.189527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.26806641, 5430.82960938, 371.2625), 'rotation':(0.191396, -89.896912, 0.190113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.25805664, 5436.46582031, 371.24367187999997), 'rotation':(0.191976, -89.897522, 0.190705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.24798584, 5442.10253906, 371.22472655999997), 'rotation':(0.192277, -89.896912, 0.190979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.23791504, 5447.73925781, 371.20582031), 'rotation':(0.192857, -89.896912, 0.19156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.22784424, 5453.37597656, 371.18679688), 'rotation':(0.192857, -89.896912, 0.19156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.20770264, 5464.64941406, 371.14871094), 'rotation':(0.193786, -89.897247, 0.192472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.18756104, 5475.92234375, 371.11035155999997), 'rotation':(0.196996, -89.897125, 0.195652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.17749023, 5481.5590625, 371.09039062000005), 'rotation':(0.203369, -89.897095, 0.20193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.16748047, 5487.1953125, 371.06976562000006), 'rotation':(0.209755, -89.897034, 0.208228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.15740967, 5492.83203125, 371.04847656), 'rotation':(0.216128, -89.896332, 0.214508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.14733887, 5498.46828125, 371.026875), 'rotation':(0.219488, -89.897034, 0.217802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.13726807, 5504.105, 371.00527344), 'rotation':(0.219488, -89.897034, 0.217802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.12719727, 5509.74171875, 370.98371094000004), 'rotation':(0.219474, -89.896667, 0.217806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.11712646, 5515.37792969, 370.96179687999995), 'rotation':(0.223463, -89.896973, 0.221715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.1071167, 5521.01464844, 370.93910156), 'rotation':(0.230936, -89.896942, 0.229085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.0970459, 5526.65136719, 370.91566406), 'rotation':(0.239084, -89.89621, 0.23709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.0869751, 5532.28757812, 370.89132812), 'rotation':(0.246857, -89.89682, 0.24473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.0769043, 5537.92382812, 370.86621094000003), 'rotation':(0.254677, -89.896729, 0.252427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.0668335, 5543.56054688, 370.84027344000003), 'rotation':(0.262491, -89.895996, 0.260093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.05682373, 5549.19679688, 370.81355469000005), 'rotation':(0.270298, -89.896606, 0.267751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.04675293, 5554.83300781, 370.78609375), 'rotation':(0.278084, -89.896515, 0.275389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.03668213, 5560.46972656, 370.75835937999994), 'rotation':(0.281937, -89.896179, 0.279177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.02233887, 5274.34082031, 371.60351562000005), 'rotation':(-0.045013, 90.102646, -0.045074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.07250977, 5246.24707031, 371.62253906), 'rotation':(-0.034454, 90.102432, -0.034485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.08251953, 5240.62841797, 371.62558594), 'rotation':(-0.031616, 90.102432, -0.031647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.0925293, 5235.00927734, 371.62835937999995), 'rotation':(-0.028778, 90.102417, -0.028809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.10253906, 5229.390625, 371.63082031), 'rotation':(-0.025909, 90.102417, -0.02594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.11260986, 5223.77148438, 371.63300781), 'rotation':(-0.023071, 90.102417, -0.023102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.13269043, 5212.53417969, 371.63683594), 'rotation':(-0.019012, 90.102234, -0.019012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.1427002, 5206.91552734, 371.63871094), 'rotation':(-0.019012, 90.102249, -0.019012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(981.15270996, 5201.296875, 371.64054688), 'rotation':(-0.019012, 90.102234, -0.019012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.17279053, 5190.05908203, 371.64382812), 'rotation':(-0.0112, 90.102226, -0.01123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.18286133, 5184.44042969, 371.64390625), 'rotation':(0.004938, 90.10289, 0.004952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.19287109, 5178.82226562, 371.64285156), 'rotation':(0.012786, 90.102295, 0.01278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.21295166, 5167.58447266, 371.64035156), 'rotation':(0.012793, 90.102287, 0.012782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.23303223, 5156.34667969, 371.63785156), 'rotation':(0.012786, 90.102295, 0.01278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.24304199, 5150.72802734, 371.63628905999997), 'rotation':(0.012786, 90.102295, 0.01278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.26312256, 5139.49072266, 371.63191406), 'rotation':(0.018114, 90.102333, 0.018093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.27313232, 5133.87255859, 371.62910156), 'rotation':(0.028837, 90.102341, 0.028801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.30322266, 5117.01611328, 371.61613280999995), 'rotation':(0.050284, 90.102379, 0.050197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.31323242, 5111.39746094, 371.6109375), 'rotation':(0.050284, 90.102379, 0.050197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.33331299, 5100.15966797, 371.59953125), 'rotation':(0.059402, 90.102234, 0.05927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.34332275, 5094.54150391, 371.59335938), 'rotation':(0.059402, 90.102234, 0.05927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.36340332, 5083.30419922, 371.57972656), 'rotation':(0.066997, 90.1026, 0.066844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.37341309, 5077.68505859, 371.57242188), 'rotation':(0.07423, 90.102249, 0.074053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.39349365, 5066.44775391, 371.55632812000005), 'rotation':(0.081853, 90.102287, 0.081616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.40356445, 5060.82910156, 371.54789062000003), 'rotation':(0.08589, 90.102882, 0.085642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.41357422, 5055.21044922, 371.53914062), 'rotation':(0.087604, 90.102432, 0.087338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.42358398, 5049.59179688, 371.53007812000004), 'rotation':(0.091559, 90.10244, 0.091267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(981.44360352, 5038.35449219, 371.51082031), 'rotation':(0.100042, 90.102463, 0.099688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.45367432, 5032.73535156, 371.500625), 'rotation':(0.10399, 90.102486, 0.103616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.47375488, 5021.49804688, 371.47910156), 'rotation':(0.112186, 90.102509, 0.111752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.51159668, 5560.4565625, 370.75835937999994), 'rotation':(-0.282166, 90.103813, -0.284943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.53173828, 5549.18457031, 370.81355469000005), 'rotation':(-0.278076, 90.103477, -0.280792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.54180908, 5543.54785156, 370.84027344000003), 'rotation':(-0.270294, 90.103394, -0.272858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.55187988, 5537.91210938, 370.86617187999997), 'rotation':(-0.262512, 90.10334, -0.264923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.57196045, 5526.640625, 370.915625), 'rotation':(-0.246857, 90.10318, -0.248993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.58203125, 5521.00488281, 370.93910156), 'rotation':(-0.239075, 90.103127, -0.241089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.59204102, 5515.36816406, 370.96175781), 'rotation':(-0.230957, 90.103706, -0.232819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.61218262, 5504.09570312, 371.00523438), 'rotation':(-0.219482, 90.102959, -0.221161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.64239502, 5487.18703125, 371.06976562000006), 'rotation':(-0.216156, 90.102997, -0.217773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.66247559, 5475.91453125, 371.1103125), 'rotation':(-0.2034, 90.103577, -0.204834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.68261719, 5464.64257812, 371.14867187999994), 'rotation':(-0.193542, 90.102715, -0.194855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.69268799, 5459.00632812, 371.16773437999996), 'rotation':(-0.193787, 90.10321, -0.195099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.70275879, 5453.37011719, 371.18675780999996), 'rotation':(-0.193451, 90.103065, -0.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.71282959, 5447.73390625, 371.20574219), 'rotation':(-0.193451, 90.103065, -0.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.72290039, 5442.0971875, 371.2246875), 'rotation':(-0.192871, 90.102501, -0.194153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.74304199, 5430.82519531, 371.2625), 'rotation':(-0.191986, 90.103081, -0.193268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.75305176, 5425.18847656, 371.28128906), 'rotation':(-0.191376, 90.103065, -0.192688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.76312256, 5419.55226562, 371.30007812), 'rotation':(-0.190826, 90.103065, -0.192078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.78326416, 5408.27929688, 371.3375), 'rotation':(-0.189941, 90.102463, -0.191193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.79333496, 5402.64355469, 371.35601562000005), 'rotation':(-0.189728, 90.10318, -0.190979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.83361816, 5380.09863281, 371.42402344000004), 'rotation':(-0.158325, 90.102722, -0.15918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.85375977, 5368.82664062, 371.45371094), 'rotation':(-0.145935, 90.102646, -0.146698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.87384033, 5357.5546875, 371.48128906), 'rotation':(-0.139709, 90.103065, -0.140381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.88391113, 5351.91894531, 371.49433594000004), 'rotation':(-0.135345, 90.102478, -0.135986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.89398193, 5346.28222656, 371.50648437999996), 'rotation':(-0.127563, 90.102455, -0.128113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.9039917, 5340.64648438, 371.51785156), 'rotation':(-0.110962, 90.103027, -0.111389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.9140625, 5335.01023438, 371.52835938), 'rotation':(-0.103149, 90.102341, -0.103516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.93414307, 5323.73828125, 371.546875), 'rotation':(-0.086548, 90.102287, -0.086823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.94421387, 5318.10205078, 371.55488281), 'rotation':(-0.078766, 90.102928, -0.078949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.97442627, 5301.19384766, 371.57664062000003), 'rotation':(-0.074402, 90.10247, -0.074585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.1405078100001, 5273.0390625, 371.17398438), 'rotation':(0.138755, -90.052338, 0.138088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.1251171899999, 5256.21191406, 371.21414062), 'rotation':(0.12892, -90.05191, 0.128329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.12, 5250.60302734, 371.22675781), 'rotation':(0.123312, -90.05191, 0.12279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.10974609, 5239.38525391, 371.25023437999994), 'rotation':(0.111824, -90.053223, 0.111399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.09949219, 5228.16748047, 371.2715625), 'rotation':(0.100329, -90.052002, 0.099983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.09435547, 5222.55810547, 371.28136719), 'rotation':(0.094735, -90.052032, 0.094413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.08410156, 5211.33984375, 371.29957031), 'rotation':(0.086607, -90.051697, 0.086337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.07910156, 5205.73095703, 371.30835937999996), 'rotation':(0.086607, -90.051697, 0.086337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.07398438, 5200.12207031, 371.31683594000003), 'rotation':(0.076109, -90.052551, 0.075916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.06371094, 5188.90429688, 371.33152344), 'rotation':(0.065829, -90.051758, 0.065674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.05333984, 5177.68603516, 371.34351562000006), 'rotation':(0.050127, -90.052124, 0.050037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.04822266, 5172.07714844, 371.34875), 'rotation':(0.050127, -90.052124, 0.050037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.0430859399999, 5166.46777344, 371.35367188), 'rotation':(0.048972, -90.052795, 0.04889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.03796875, 5160.85839844, 371.35847656), 'rotation':(0.046766, -90.051697, 0.046692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.02771484, 5149.640625, 371.36753905999996), 'rotation':(0.042374, -90.051697, 0.0423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.01746094, 5138.42236328, 371.37585937999995), 'rotation':(0.040168, -90.052795, 0.040111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.00720703, 5127.20410156, 371.38335937999994), 'rotation':(0.035763, -90.052795, 0.035717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.00207031, 5121.59521484, 371.38683594), 'rotation':(0.033564, -90.052826, 0.033526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.99181641, 5110.37695312, 371.39332031), 'rotation':(0.0326, -90.052887, 0.032566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.98669922, 5104.76757812, 371.39648437999995), 'rotation':(0.032307, -90.051666, 0.032262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1178.9815625, 5099.15820312, 371.39964844), 'rotation':(0.032307, -90.052887, 0.03226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.9764453100001, 5093.54931641, 371.4028125), 'rotation':(0.018086, -90.051666, 0.018079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.97130859, 5087.94042969, 371.40476562000003), 'rotation':(-0.010345, -90.052979, -0.010345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.9509375, 5065.50537109, 371.39691406), 'rotation':(-0.024689, -90.052185, -0.024719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1178.94066406, 5054.28662109, 371.39210937999997), 'rotation':(-0.036194, -90.052765, -0.036255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.93554688, 5048.67822266, 371.38902344), 'rotation':(-0.036194, -90.052765, -0.036255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.92517578, 5037.46044922, 371.37996094000005), 'rotation':(-0.081085, -90.05191, -0.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.92003906, 5031.85205078, 371.37367187999996), 'rotation':(-0.081085, -90.05191, -0.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1178.91492188, 5026.24267578, 371.36570312000003), 'rotation':(-0.103699, -90.052612, -0.104065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.90466797, 5015.02539062, 371.34628906), 'rotation':(-0.114838, -90.052063, -0.115295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.18042969, 5316.62011719, 371.06125), 'rotation':(0.153536, -90.052185, 0.152716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.19568359, 5333.42625, 371.015), 'rotation':(0.160277, -90.052124, 0.159389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.20080078, 5339.0278125, 370.99910156), 'rotation':(0.160277, -90.052124, 0.159389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.2110546899999, 5350.23242188, 370.96644531), 'rotation':(0.165031, -90.051392, 0.164081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.21619141, 5355.83445312, 370.94988280999996), 'rotation':(0.169594, -90.052063, 0.168592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.22130859, 5361.43652344, 370.93308594), 'rotation':(0.172011, -90.05127, 0.17098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.2264453100001, 5367.03859375, 370.91621094000004), 'rotation':(0.171984, -90.05249, 0.170961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.23167969, 5372.640625, 370.89890625), 'rotation':(0.176943, -90.051727, 0.175855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.23681641, 5378.24265625, 370.88125), 'rotation':(0.176943, -90.051727, 0.175855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.24181641, 5383.84472656, 370.86292969000004), 'rotation':(0.187106, -90.051636, 0.185885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.24695312, 5389.44628906, 370.84402344), 'rotation':(0.187106, -90.051636, 0.185885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.25207031, 5395.04835938, 370.82472656), 'rotation':(0.197263, -90.051575, 0.195912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.26757812, 5411.85449219, 370.76332031), 'rotation':(0.212405, -90.052307, 0.21084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.28296875, 5428.660625, 370.70074219), 'rotation':(0.213833, -90.051331, 0.212254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.28796875, 5434.26269531, 370.67976562), 'rotation':(0.214427, -90.051331, 0.212831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.29822266, 5445.46726562, 370.63777344000005), 'rotation':(0.21526, -90.0513, 0.213645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.30333984, 5451.06933594, 370.61667969), 'rotation':(0.216128, -90.051331, 0.214504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.3084765600001, 5456.67140625, 370.59550780999996), 'rotation':(0.216107, -90.0513, 0.214482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.31359375, 5462.27390625, 370.574375), 'rotation':(0.216107, -90.0513, 0.214482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.32384766, 5473.47804688, 370.53199219000004), 'rotation':(0.216578, -90.051758, 0.21494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.349375, 5501.48828125, 370.42332031), 'rotation':(0.225642, -90.051758, 0.223866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.35960938, 5512.69238281, 370.37921875), 'rotation':(0.225314, -90.051758, 0.22355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.36988281, 5523.89695312, 370.33488280999995), 'rotation':(0.226708, -90.051788, 0.224921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.375, 5529.49851562, 370.31257812), 'rotation':(0.227725, -90.051788, 0.225926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.38011719, 5535.10058594, 370.29019531), 'rotation':(0.228784, -90.050415, 0.226968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.39539062, 5551.90722656, 370.22242187999996), 'rotation':(0.232575, -90.050354, 0.230701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.40050781, 5557.50929688, 370.19964844000003), 'rotation':(0.232868, -90.051575, 0.230986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.40564453, 5563.11132812, 370.176875), 'rotation':(0.232868, -90.051575, 0.230986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.38464844, 5020.64453125, 371.35644530999997), 'rotation':(0.081061, 89.948074, 0.080838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.38976562, 5026.25341797, 371.36570312000003), 'rotation':(0.081061, 89.948074, 0.080838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.40001953, 5037.47167969, 371.37996094000005), 'rotation':(0.058446, 89.947266, 0.058325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.41039062, 5048.68994141, 371.38902344), 'rotation':(0.024691, 89.947815, 0.024665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.41552734, 5054.29931641, 371.39210937999997), 'rotation':(0.024691, 89.947815, 0.024665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.42066406, 5059.90869141, 371.39453125), 'rotation':(0.024677, 89.94783, 0.024667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.42578125, 5065.51855469, 371.39691406), 'rotation':(0.024677, 89.94783, 0.024667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.44103516, 5082.34667969, 371.40410155999996), 'rotation':(0.010334, 89.948311, 0.010332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.45128906, 5093.56445312, 371.4028125), 'rotation':(-0.032318, 89.948326, -0.032349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.45642578, 5099.17382812, 371.39964844), 'rotation':(-0.032318, 89.947098, -0.032349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.46667969, 5110.39306641, 371.39332031), 'rotation':(-0.032318, 89.947098, -0.032349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.47693359, 5121.61230469, 371.38683594), 'rotation':(-0.035767, 89.947197, -0.035828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.4871875, 5132.83105469, 371.3796875), 'rotation':(-0.040161, 89.947197, -0.040222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.4923046899999, 5138.44042969, 371.37585937999995), 'rotation':(-0.042389, 89.948296, -0.04245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5076953100001, 5155.26904297, 371.36308594), 'rotation':(-0.046783, 89.947212, -0.046844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5128125, 5160.87841797, 371.35847656), 'rotation':(-0.048981, 89.948311, -0.049072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.51794922, 5166.48779297, 371.35367188), 'rotation':(-0.05014, 89.947845, -0.050232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.52306641, 5172.09765625, 371.34875), 'rotation':(-0.055328, 89.947388, -0.05545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.52820312, 5177.70703125, 371.34351562000006), 'rotation':(-0.055328, 89.947388, -0.05545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5334375, 5183.31591797, 371.33792969), 'rotation':(-0.065826, 89.948235, -0.065979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.54371094, 5194.53466797, 371.32441406), 'rotation':(-0.076111, 89.947426, -0.076324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.55394531, 5205.75390625, 371.30832031), 'rotation':(-0.091766, 89.948349, -0.092072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.55896484, 5211.36279297, 371.29953125), 'rotation':(-0.091766, 89.948349, -0.092072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.56408203, 5216.97265625, 371.29054687999997), 'rotation':(-0.094727, 89.947975, -0.095062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5743359399999, 5228.19189453, 371.27152344), 'rotation':(-0.105927, 89.948013, -0.106323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.57947266, 5233.80078125, 371.26113281), 'rotation':(-0.111816, 89.948029, -0.112274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.58458984, 5239.41064453, 371.25019531), 'rotation':(-0.117401, 89.948044, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5897265600001, 5245.01953125, 371.23875), 'rotation':(-0.123322, 89.948074, -0.12384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.59484375, 5250.62890625, 371.22671875), 'rotation':(-0.128906, 89.948097, -0.129486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.59998047, 5256.23828125, 371.2140625), 'rotation':(-0.134521, 89.94812, -0.135132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.60509766, 5261.84765625, 371.20097655999996), 'rotation':(-0.137451, 89.948082, -0.138092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.88037109, 5563.12011719, 370.176875), 'rotation':(-0.232635, 89.948425, -0.234558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.87523438, 5557.51855469, 370.19964844000003), 'rotation':(-0.232635, 89.948425, -0.234558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.87011719, 5551.91648438, 370.22242187999996), 'rotation':(-0.23288, 89.949341, -0.234772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.865, 5546.31492188, 370.24511719000003), 'rotation':(-0.232574, 89.948257, -0.234467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.85986328, 5540.71289062, 370.26769530999997), 'rotation':(-0.231232, 89.948242, -0.233093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.84972656, 5529.50976562, 370.31257812), 'rotation':(-0.22879, 89.948219, -0.230621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.84460938, 5523.90820312, 370.33488280999995), 'rotation':(-0.227722, 89.948204, -0.229553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.83947266, 5518.30664062, 370.35707031), 'rotation':(-0.226715, 89.948189, -0.228516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.83435547, 5512.70460938, 370.37917969), 'rotation':(-0.225983, 89.949577, -0.227783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.82921875, 5507.10304688, 370.40125), 'rotation':(-0.225311, 89.948235, -0.227081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.8241015600001, 5501.50148438, 370.42328125), 'rotation':(-0.225647, 89.948242, -0.227417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.81896484, 5495.89941406, 370.44535156), 'rotation':(-0.225647, 89.948242, -0.227417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.81384766, 5490.29785156, 370.46734375), 'rotation':(-0.225311, 89.949509, -0.227081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.80359375, 5479.09421875, 370.51066405999995), 'rotation':(-0.218689, 89.948929, -0.220337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.79333984, 5467.89109375, 370.55316406), 'rotation':(-0.216553, 89.948257, -0.218201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.78832031, 5462.28953125, 370.57433594), 'rotation':(-0.216766, 89.948257, -0.218414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.78320312, 5456.6875, 370.59550780999996), 'rotation':(-0.216766, 89.948257, -0.218414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.77808594, 5451.0859375, 370.61664062000006), 'rotation':(-0.216095, 89.948685, -0.217743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.77294922, 5445.48390625, 370.63773438), 'rotation':(-0.216125, 89.948692, -0.217743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.76269531, 5434.28027344, 370.67976562), 'rotation':(-0.214691, 89.948677, -0.216309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.75757812, 5428.67871094, 370.70070312), 'rotation':(-0.214417, 89.947533, -0.216034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.75244141, 5423.07714844, 370.72160155999995), 'rotation':(-0.213837, 89.948677, -0.215424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.74730469, 5417.47507812, 370.7425), 'rotation':(-0.213287, 89.948662, -0.214874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.7421875, 5411.87351562, 370.76332031), 'rotation':(-0.213013, 89.948654, -0.2146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.73707031, 5406.27195312, 370.78410155999995), 'rotation':(-0.212433, 89.947685, -0.213989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.73193359, 5400.66992188, 370.80449219), 'rotation':(-0.212433, 89.947685, -0.213989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.72693359, 5395.06882812, 370.8246875), 'rotation':(-0.207611, 89.948479, -0.209106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.72191406, 5389.46679688, 370.84398437999994), 'rotation':(-0.197266, 89.94841, -0.198639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.71167969, 5378.26414062, 370.88121094), 'rotation':(-0.187103, 89.948326, -0.188324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.70654297, 5372.66257812, 370.89890625), 'rotation':(-0.187103, 89.948326, -0.188324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.69617188, 5361.45898438, 370.93300781), 'rotation':(-0.171997, 89.948723, -0.173035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.68591797, 5350.25585938, 370.96644531), 'rotation':(-0.169586, 89.947906, -0.170593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.68078125, 5344.65429688, 370.98292969), 'rotation':(-0.169586, 89.947906, -0.170593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.6756640600001, 5339.05273438, 370.99910156), 'rotation':(-0.165039, 89.948624, -0.165985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.66552734, 5327.84914062, 371.030625), 'rotation':(-0.160278, 89.947861, -0.161194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.66039062, 5322.24755859, 371.04597656), 'rotation':(-0.160278, 89.947861, -0.161194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.65527344, 5316.64550781, 371.06117187999996), 'rotation':(-0.155731, 89.947845, -0.156586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.65015625, 5311.04394531, 371.07621094), 'rotation':(-0.153534, 89.949104, -0.154358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.64501953, 5305.44189453, 371.09117188), 'rotation':(-0.153534, 89.947792, -0.154358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.63988281, 5299.84082031, 371.10605469), 'rotation':(-0.1521, 89.948303, -0.152924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.81382812, 5271.62548828, 370.63347655999996), 'rotation':(0.114802, -90.161621, 0.114351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.79785156, 5265.94824219, 370.64492187999997), 'rotation':(0.11347, -90.162354, 0.113016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.76574219, 5254.59375, 370.66730469000004), 'rotation':(0.110314, -90.161621, 0.109882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.74964844, 5248.91601562, 370.67820312000003), 'rotation':(0.103942, -90.161621, 0.103553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.71765625, 5237.56152344, 370.69871094), 'rotation':(0.097945, -90.161652, 0.097608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.70152344, 5231.88427734, 370.70839844), 'rotation':(0.091572, -90.161652, 0.091281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.68554688, 5226.20654297, 370.71769530999995), 'rotation':(0.091572, -90.161652, 0.091281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.66957031, 5220.52929688, 370.72675781), 'rotation':(0.088608, -90.161591, 0.088329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.6534375, 5214.85205078, 370.73554687999996), 'rotation':(0.088615, -90.161621, 0.088338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.63746094, 5209.17431641, 370.74433594000004), 'rotation':(0.084489, -90.161987, 0.084238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.60535156, 5197.81982422, 370.76089844), 'rotation':(0.076423, -90.162048, 0.076217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.57324219, 5186.46533203, 370.77535156), 'rotation':(0.060092, -90.162079, 0.059971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.55726562, 5180.78857422, 370.78191405999996), 'rotation':(0.060092, -90.162079, 0.059971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.54113281, 5175.11083984, 370.78789062000004), 'rotation':(0.055987, -90.161774, 0.055876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.52503906, 5169.43359375, 370.79351562000005), 'rotation':(0.055987, -90.161774, 0.055876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.50902344, 5163.75634766, 370.7990625), 'rotation':(0.055311, -90.161743, 0.0552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.49292969, 5158.07861328, 370.80449219), 'rotation':(0.053658, -90.161743, 0.053555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.47691406, 5152.40136719, 370.80984375), 'rotation':(0.052265, -90.161743, 0.052178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.4609375, 5146.72363281, 370.815), 'rotation':(0.050625, -90.161743, 0.050536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.44484375, 5141.04638672, 370.82003906), 'rotation':(0.048972, -90.161713, 0.048882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.36460938, 5112.65966797, 370.84324219), 'rotation':(0.038413, -90.162292, 0.038364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.34863281, 5106.98193359, 370.84714844), 'rotation':(0.028332, -90.161316, 0.028301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.3326562500001, 5101.30517578, 370.85042969), 'rotation':(0.028332, -90.161316, 0.028301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.31652344, 5095.62792969, 370.85292969), 'rotation':(0.018004, -90.162292, 0.017993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.2845312499999, 5084.27294922, 370.85554687999996), 'rotation':(0.0025, -90.162292, 0.002499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.2684375, 5078.59619141, 370.85589844000003), 'rotation':(0.0025, -90.162292, 0.002499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.25242188, 5072.91845703, 370.85617188), 'rotation':(0.002322, -90.16156, 0.002318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.23632812, 5067.24121094, 370.85636719), 'rotation':(0.002507, -90.161591, 0.002504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.22035156, 5061.56396484, 370.85664062), 'rotation':(0.002507, -90.161591, 0.002504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.1241406200002, 5027.50048828, 370.85359375), 'rotation':(-0.034546, -90.161011, -0.034607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.10804688, 5021.82275391, 370.85015625), 'rotation':(-0.039673, -90.162323, -0.039734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.09203125, 5016.14550781, 370.84621094), 'rotation':(-0.039673, -90.161407, -0.039734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.90601562, 5304.24023438, 370.56257812), 'rotation':(0.130545, -90.160492, 0.129966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.92199219, 5309.88134766, 370.54945312), 'rotation':(0.132588, -90.161835, 0.131991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.93796875, 5315.52197266, 370.53609375), 'rotation':(0.136378, -90.16333, 0.135732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.95386719, 5321.16210938, 370.52238280999995), 'rotation':(0.139158, -90.160645, 0.138482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.96984375, 5326.80273438, 370.50816405999996), 'rotation':(0.14439, -90.161835, 0.143665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.98570312, 5332.44335938, 370.49335937999996), 'rotation':(0.150517, -90.161804, 0.149738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.00171875, 5338.08398438, 370.47800781), 'rotation':(0.155756, -90.160553, 0.154916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.03355469, 5349.36476562, 370.44566405999996), 'rotation':(0.167128, -90.161713, 0.166156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.04945312, 5355.00585938, 370.42863280999995), 'rotation':(0.172954, -90.161682, 0.17191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.06554688, 5360.64648438, 370.41109375), 'rotation':(0.178179, -90.160431, 0.177075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.0814062499999, 5366.28664062, 370.39320312), 'rotation':(0.181266, -90.161743, 0.180121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.09742188, 5371.92773438, 370.37492188), 'rotation':(0.184647, -90.161804, 0.183461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.11328125, 5377.56789062, 370.35597656), 'rotation':(0.191122, -90.160492, 0.189837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.12925781, 5383.20851562, 370.33636719000003), 'rotation':(0.197536, -90.161743, 0.19618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.16113281, 5394.48976562, 370.29511719000004), 'rotation':(0.210766, -90.161652, 0.209225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.17710938, 5400.12988281, 370.27347656), 'rotation':(0.217514, -90.160309, 0.215871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1368.19300781, 5405.77050781, 370.25113281), 'rotation':(0.223989, -90.16156, 0.222239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.22484375, 5417.05175781, 370.20527344000004), 'rotation':(0.233545, -90.161407, 0.23165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.27269531, 5433.97460938, 370.13636719000004), 'rotation':(0.232916, -90.160126, 0.231014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.30457031, 5445.25539062, 370.09054688), 'rotation':(0.232568, -90.161407, 0.230677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1368.32042969, 5450.89601562, 370.06765625), 'rotation':(0.232588, -90.160126, 0.230697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.33640625, 5456.53710938, 370.04480469000003), 'rotation':(0.23194, -90.161438, 0.230068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.35230469, 5462.17773438, 370.02195312000003), 'rotation':(0.231967, -90.160095, 0.230095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.36828125, 5467.81835938, 369.99917969), 'rotation':(0.231782, -90.161438, 0.229915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.38414062, 5473.45945312, 369.97644531), 'rotation':(0.230451, -90.161438, 0.228608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.44800781, 5496.02296875, 369.88671875), 'rotation':(0.22653, -90.161469, 0.224739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.46386719, 5501.66359375, 369.86457031), 'rotation':(0.225574, -90.161499, 0.223797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1368.49574219, 5512.9453125, 369.82054687999994), 'rotation':(0.224392, -90.161255, 0.222645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.52757812, 5524.22703125, 369.7784375), 'rotation':(0.206634, -90.160645, 0.205145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.55945312, 5535.50929688, 369.73929688), 'rotation':(0.192857, -90.160736, 0.191561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.59132812, 5546.79101562, 369.70296875), 'rotation':(0.178753, -90.162109, 0.177642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.63902344, 5563.71386719, 369.65269530999996), 'rotation':(0.168419, -90.161102, 0.167434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1358.5670312500001, 5016.17089844, 370.84621094), 'rotation':(0.03967, 89.838577, 0.039605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1358.58300781, 5021.84863281, 370.85015625), 'rotation':(0.034568, 89.837631, 0.034512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.59914062, 5027.52636719, 370.85359375), 'rotation':(0.023817, 89.837608, 0.023797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.61511719, 5033.203125, 370.85597656), 'rotation':(0.013428, 89.838943, 0.01342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.64722656, 5044.55761719, 370.85734375), 'rotation':(-0.002319, 89.838432, -0.002319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.6632031200002, 5050.23535156, 370.85710937999994), 'rotation':(-0.002502, 89.8377, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.67933594, 5055.91308594, 370.856875), 'rotation':(-0.002502, 89.8377, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.6953125, 5061.59082031, 370.85664062), 'rotation':(-0.002319, 89.838432, -0.002319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.75953125, 5084.30078125, 370.85554687999996), 'rotation':(-0.007446, 89.8377, -0.007446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.77550781, 5089.97851562, 370.85472655999996), 'rotation':(-0.018005, 89.838669, -0.018036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.79148438, 5095.65625, 370.85292969), 'rotation':(-0.02832, 89.8377, -0.028351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.80761719, 5101.33349609, 370.85042969), 'rotation':(-0.038422, 89.838692, -0.038483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1358.83960938, 5112.68798828, 370.84324219), 'rotation':(-0.044159, 89.836784, -0.04422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.85570312, 5118.36621094, 370.83882812), 'rotation':(-0.045959, 89.838249, -0.046021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.8878125, 5129.72070312, 370.82972656), 'rotation':(-0.047607, 89.838249, -0.047668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.90382812, 5135.3984375, 370.82492188), 'rotation':(-0.048981, 89.838257, -0.049072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.9678906200002, 5158.109375, 370.80449219), 'rotation':(-0.055298, 89.837151, -0.05542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.00011719, 5169.46435547, 370.79351562000005), 'rotation':(-0.060089, 89.83873, -0.060211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.03222656, 5180.81982422, 370.781875), 'rotation':(-0.068176, 89.837929, -0.068329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.04820312, 5186.49707031, 370.77535156), 'rotation':(-0.068176, 89.837929, -0.068329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.06433594, 5192.17431641, 370.76847655999995), 'rotation':(-0.076416, 89.837967, -0.07663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.0803125, 5197.85205078, 370.76085937999994), 'rotation':(-0.084503, 89.838783, -0.084747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.09632812, 5203.52978516, 370.75273438), 'rotation':(-0.084503, 89.838783, -0.084747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.1284375, 5214.88427734, 370.73554687999996), 'rotation':(-0.088593, 89.838402, -0.088898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.14453125, 5220.56201172, 370.72675781), 'rotation':(-0.091553, 89.838348, -0.091858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.17652344, 5231.91748047, 370.70839844), 'rotation':(-0.097931, 89.837601, -0.098297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.19261719, 5237.59521484, 370.69867187999995), 'rotation':(-0.103943, 89.838371, -0.104309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.20863281, 5243.27246094, 370.68855469000005), 'rotation':(-0.103943, 89.838371, -0.104309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.22460938, 5248.95019531, 370.67820312000003), 'rotation':(-0.110291, 89.838387, -0.110748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.25671875, 5260.3046875, 370.65621094), 'rotation':(-0.113464, 89.838943, -0.113922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.2728124999999, 5265.98242188, 370.64492187999997), 'rotation':(-0.114807, 89.838379, -0.115265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.28882812, 5271.66015625, 370.6334375), 'rotation':(-0.118103, 89.838387, -0.118591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.09777344, 5558.098125, 369.66929688), 'rotation':(-0.168488, 89.838829, -0.169464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1360.08191406, 5552.4575, 369.68589844), 'rotation':(-0.168427, 89.838875, -0.169434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.0659375, 5546.81640625, 369.70296875), 'rotation':(-0.172211, 89.837799, -0.173248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1360.0501562499999, 5541.17578125, 369.72074219), 'rotation':(-0.178741, 89.83918, -0.179871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.01832031, 5529.8940625, 369.75851562), 'rotation':(-0.192841, 89.839264, -0.194153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.00230469, 5524.2534375, 369.7784375), 'rotation':(-0.199768, 89.839302, -0.201141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.97046875, 5512.97167969, 369.82054687999994), 'rotation':(-0.220428, 89.83947, -0.222107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.90671875, 5490.40917969, 369.90898438), 'rotation':(-0.226532, 89.838509, -0.228333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.89085938, 5484.76855469, 369.93140625), 'rotation':(-0.227539, 89.838524, -0.22934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.87488281, 5479.12792969, 369.95386719000004), 'rotation':(-0.228485, 89.839851, -0.230316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.85902344, 5473.48730469, 369.97644531), 'rotation':(-0.229492, 89.838539, -0.231354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.81117188, 5456.56542969, 370.04476562), 'rotation':(-0.231964, 89.83873, -0.233856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.7634375, 5439.64355469, 370.11339844), 'rotation':(-0.232574, 89.839882, -0.234467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.71558594, 5422.7221875, 370.18226562), 'rotation':(-0.233215, 89.839874, -0.235138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.68371094, 5411.4409375, 370.22828125), 'rotation':(-0.233521, 89.8386, -0.235443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.63597656, 5394.52, 370.29507812), 'rotation':(-0.217529, 89.838402, -0.219177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.60414062, 5383.23925781, 370.33632812), 'rotation':(-0.204315, 89.83831, -0.20578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.588125, 5377.59914062, 370.3559375), 'rotation':(-0.19754, 89.839546, -0.198914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.54039062, 5360.67820312, 370.41109375), 'rotation':(-0.181274, 89.838249, -0.182404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.52441406, 5355.03757812, 370.42863280999995), 'rotation':(-0.178192, 89.838318, -0.179291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.5084375000001, 5349.39695312, 370.445625), 'rotation':(-0.172943, 89.83831, -0.173981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.49242188, 5343.75683594, 370.46207031), 'rotation':(-0.167114, 89.8395, -0.168091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.4765625, 5338.11621094, 370.47796875), 'rotation':(-0.161591, 89.838242, -0.162506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.46058594, 5332.47558594, 370.49335937999996), 'rotation':(-0.155762, 89.838203, -0.156616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.4446874999999, 5326.83544922, 370.50816405999996), 'rotation':(-0.150513, 89.839417, -0.151306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.41285156, 5315.5546875, 370.53605469), 'rotation':(-0.13916, 89.838142, -0.139832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.39683594, 5309.91455078, 370.54941406), 'rotation':(-0.13504, 89.83815, -0.135651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.36511719, 5298.63330078, 370.57542969), 'rotation':(-0.130554, 89.838127, -0.131165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(31.10734375000004, 3502.27660156, 361.24867187999996), 'rotation':(-0.228333, 89.62056, -0.230133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(31.217968749999955, 3518.93824219, 361.1840625), 'rotation':(-0.175598, 89.620201, -0.176666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.254687500000045, 3524.49632812, 361.17050781), 'rotation':(-0.069275, 89.619728, -0.069427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(31.328281250000032, 3535.61351562, 361.17339844), 'rotation':(0.142819, 89.62001, 0.142097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.365078119999907, 3541.17308594, 361.18980469), 'rotation':(0.248516, 89.620735, 0.246377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.401875000000018, 3546.73265625, 361.21632812), 'rotation':(0.354849, 89.621864, 0.350479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.438671880000015, 3552.29222656, 361.25285155999995), 'rotation':(0.46058, 89.623352, 0.453216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(31.475390619999985, 3557.85230469, 361.29933594), 'rotation':(0.566557, 89.625259, 0.55543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.512187499999982, 3563.40941406, 361.35511719000004), 'rotation':(0.6204, 89.62632, 0.607075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.54882811999994, 3568.96679688, 361.41992187999995), 'rotation':(0.802028, 89.630875, 0.779812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(31.622343750000027, 3580.08863281, 361.58335938), 'rotation':(1.044821, 89.638718, 1.007213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(31.658984379999993, 3585.64941406, 361.683125), 'rotation':(1.166166, 89.643402, 1.119386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.73249999999996, 3596.77, 361.91875), 'rotation':(1.408651, 89.654335, 1.340595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.805937500000027, 3607.88914062, 362.20234375), 'rotation':(1.590293, 89.663864, 1.503746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.879374999999982, 3619.0, 362.51585937999994), 'rotation':(1.729868, 89.671959, 1.62763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.916328120000003, 3624.55710938, 362.68125), 'rotation':(1.729868, 89.671959, 1.62763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.952968749999968, 3630.11328125, 362.85195312), 'rotation':(1.82293, 89.677734, 1.70951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(32.026406250000036, 3641.22070312, 363.21402344), 'rotation':(1.962245, 89.686989, 1.831037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.063281250000045, 3646.7736718799997, 363.40222656), 'rotation':(1.962245, 89.686989, 1.831037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.13710938000008, 3657.87429688, 363.78105469), 'rotation':(1.935997, 89.685188, 1.80824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.21101562000001, 3668.9739062500003, 364.1515625), 'rotation':(1.830566, 89.67823, 1.71621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.358515619999935, 3691.17554688, 364.85851562000005), 'rotation':(1.751663, 89.67308, 1.64684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(33.042343749999986, 3794.01242188, 367.33554688), 'rotation':(1.079252, 89.639984, 1.039144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(33.00625000000002, 3788.5746875, 367.23304687999996), 'rotation':(1.07902, 89.639984, 1.03894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.93398438000008, 3777.7009375, 367.02421875), 'rotation':(1.128607, 89.641884, 1.084785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(32.897812499999986, 3772.2646875, 366.91519531), 'rotation':(1.161965, 89.643227, 1.115525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.86171875000002, 3766.82835938, 366.80292969000004), 'rotation':(1.195269, 89.644608, 1.146148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.78945311999996, 3755.9557812499997, 366.56828125), 'rotation':(1.261351, 89.647438, 1.206687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.753281249999986, 3750.51953125, 366.44597655999996), 'rotation':(1.294348, 89.648911, 1.236817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.71718750000002, 3745.08351562, 366.32039062), 'rotation':(1.327352, 89.650421, 1.266872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.681015619999926, 3739.64820312, 366.19257812), 'rotation':(1.34429, 89.65123, 1.282268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.60867188000009, 3728.77664062, 365.92597656), 'rotation':(1.442194, 89.655991, 1.370885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.57265625000002, 3723.34226562, 365.785625), 'rotation':(1.442194, 89.655991, 1.370885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.53640625000003, 3717.90820312, 365.64082031), 'rotation':(1.508085, 89.659401, 1.430179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.60222655999996, 3722.7356250000003, 367.78867188), 'rotation':(-0.335266, -90.029968, -0.339203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.60527344, 3728.2018749999997, 367.81855469000004), 'rotation':(-0.300934, -90.030365, -0.304108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.60832030999995, 3733.66796875, 367.84589844000004), 'rotation':(-0.300934, -90.030365, -0.304108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.61144531, 3739.135, 367.87105469), 'rotation':(-0.267151, -90.030701, -0.269653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.61445312, 3744.60179688, 367.89433594), 'rotation':(-0.249786, -90.030579, -0.251953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.61753906, 3750.068125, 367.91605469), 'rotation':(-0.233856, -90.031128, -0.235779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(358.62367187999996, 3761.0021875, 367.95144531), 'rotation':(-0.168915, -90.031311, -0.169922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.62671875, 3766.46851562, 367.96511719), 'rotation':(-0.136841, -90.031494, -0.137512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.6328125, 3777.40164062, 367.98507812), 'rotation':(-0.104492, -90.031891, -0.104889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.64515625, 3799.26882812, 367.99523437999994), 'rotation':(0.008736, -90.031921, 0.008725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.58128906, 3685.39601562, 367.51414062000003), 'rotation':(-0.510864, -90.027283, -0.52005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.57824218999997, 3679.994375, 367.46640625), 'rotation':(-0.527435, -90.027008, -0.537201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.57519531, 3674.59226562, 367.4171875), 'rotation':(-0.543945, -90.026672, -0.554352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.57226562000005, 3669.1901562499997, 367.36648438), 'rotation':(-0.560791, -90.026367, -0.571838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.56921875, 3663.78859375, 367.31429688), 'rotation':(-0.577026, -90.026062, -0.588745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.563125, 3652.984375, 367.20554688), 'rotation':(-0.593842, -90.025696, -0.606262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.5601953099999, 3647.5825, 367.14921875), 'rotation':(-0.608429, -90.025635, -0.62146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.55710937999993, 3642.18042969, 367.09167969000003), 'rotation':(-0.621613, -90.024994, -0.635223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.55109374999995, 3631.37671875, 366.97285156), 'rotation':(-0.6474, -90.02478, -0.66217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.54511719000004, 3620.5725, 366.84902344), 'rotation':(-0.673523, -90.02417, -0.689484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.54207031, 3615.17089844, 366.78523437999996), 'rotation':(-0.686768, -90.023499, -0.703369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.5390625, 3609.7690625, 366.72023437999997), 'rotation':(-0.69928, -90.023193, -0.716522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.52429687999995, 3583.41039062, 366.38960937999997), 'rotation':(-0.759491, -90.021729, -0.779846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.52128905999996, 3578.00488281, 366.31835937999995), 'rotation':(-0.776276, -90.021515, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.51832031000004, 3572.59914062, 366.24589844), 'rotation':(-0.776276, -90.021515, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.50921874999995, 3556.38160156, 366.02167969000004), 'rotation':(-0.809448, -90.020294, -0.832581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(358.5062109400001, 3550.97558594, 365.94515625), 'rotation':(-0.82608, -90.020111, -0.850159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(358.49714844000005, 3534.75828125, 365.70660155999997), 'rotation':(-0.875, -90.018646, -0.902039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.49421874999996, 3529.35277344, 365.62410156), 'rotation':(-0.891296, -90.017853, -0.919373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(358.49113280999995, 3523.94726562, 365.54011719000005), 'rotation':(-0.907928, -90.017639, -0.937042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(358.48816406000003, 3518.54175781, 365.45472656), 'rotation':(-0.924225, -90.016785, -0.954407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(358.47906250000005, 3502.32445312, 365.19203125), 'rotation':(-0.932373, -90.01651, -0.963104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(465.07105469, 3583.22507812, 368.77511719), 'rotation':(-0.792816, -90.146057, -0.815002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.0413671900001, 3572.39625, 368.62367187999996), 'rotation':(-0.818909, -90.145691, -0.84256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.02648437999994, 3566.98195312, 368.54613280999996), 'rotation':(-0.825348, -90.145386, -0.849365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.01160156000003, 3561.56714844, 368.468125), 'rotation':(-0.831451, -90.145142, -0.855865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.99675780999996, 3556.15234375, 368.38984375), 'rotation':(-0.831451, -90.145142, -0.855865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.98195312000007, 3550.73804688, 368.31097656), 'rotation':(-0.842865, -90.144806, -0.86795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(464.96703125, 3545.32375, 368.23109375), 'rotation':(-0.854828, -90.144745, -0.880646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.95214844, 3539.9096875, 368.15027344000003), 'rotation':(-0.866516, -90.144104, -0.893036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.90753906, 3523.66625, 367.90164062), 'rotation':(-0.901855, -90.143311, -0.930603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.89269531, 3518.25195312, 367.81679687999997), 'rotation':(-0.913544, -90.142639, -0.943054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(464.8778125, 3512.83789062, 367.73101562000005), 'rotation':(-0.913544, -90.142639, -0.943054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.86292969, 3507.42359375, 367.64445312000004), 'rotation':(-0.919189, -90.142426, -0.949036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(464.84808594000003, 3502.00878906, 367.55753905999995), 'rotation':(-0.919525, -90.1427, -0.949402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.35179687999994, 3684.21390625, 369.96523437999997), 'rotation':(-0.56192, -90.151672, -0.572998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(465.28589844, 3661.42359375, 369.73828125), 'rotation':(-0.622894, -90.150452, -0.636536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.27027344, 3655.725625, 369.67632812000005), 'rotation':(-0.638245, -90.150085, -0.652588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(465.25464844, 3650.0278125, 369.61335937999996), 'rotation':(-0.645416, -90.150177, -0.660065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.23902344, 3644.33007812, 369.54933594), 'rotation':(-0.660461, -90.149536, -0.675812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.20765625, 3632.9353125, 369.41707031), 'rotation':(-0.689941, -90.148834, -0.706696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.19203125, 3627.2378125, 369.34871094000005), 'rotation':(-0.705292, -90.148773, -0.722809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.16070312, 3615.84277344, 369.20730469), 'rotation':(-0.734772, -90.147736, -0.753784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.43921875, 3717.19828125, 370.24574219000004), 'rotation':(-0.440063, -90.153809, -0.446838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.51625, 3745.26414062, 370.43242188), 'rotation':(-0.347198, -90.155426, -0.35144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.53171875, 3750.87742188, 370.46425781), 'rotation':(-0.327576, -90.155334, -0.331329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(465.5625, 3762.10398438, 370.52148437999995), 'rotation':(-0.287598, -90.156097, -0.290497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.57792969, 3767.7174999999997, 370.54699219), 'rotation':(-0.267944, -90.155914, -0.270447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.59339844, 3773.3307812499997, 370.57039062), 'rotation':(-0.228333, -90.156281, -0.230133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.60875, 3778.944375, 370.59167969000003), 'rotation':(-0.208344, -90.156769, -0.209869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.62425781, 3784.55789062, 370.61148438), 'rotation':(-0.198547, -90.156494, -0.199951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.63964844, 3790.17210938, 370.6309375), 'rotation':(-0.198547, -90.156494, -0.199951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.4022265599999, 3798.54617188, 371.55351562000004), 'rotation':(-0.057281, 89.922218, -0.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.39195312, 3793.0825, 371.55894530999996), 'rotation':(-0.057281, 89.922218, -0.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.38457031, 3787.618125, 371.56441406), 'rotation':(-0.057281, 89.922218, -0.057373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.35484375, 3765.76195312, 371.58394531), 'rotation':(-0.032043, 89.922134, -0.032074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.33984375, 3754.83617188, 371.58), 'rotation':(0.043556, 89.922249, 0.043493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.3323828099999, 3749.37179688, 371.57582031), 'rotation':(0.043556, 89.922249, 0.043493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.325, 3743.9075000000003, 371.57164062000004), 'rotation':(0.043829, 89.922234, 0.043755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.31757812, 3738.443125, 371.5675), 'rotation':(0.043556, 89.921707, 0.043498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.3026562499999, 3727.51515625, 371.55824219000004), 'rotation':(0.057777, 89.92231, 0.057672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.2952734400001, 3722.05171875, 371.55070312000004), 'rotation':(0.085295, 89.922379, 0.08505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.15777344, 3621.33519531, 370.95925781), 'rotation':(0.534353, 89.926765, 0.524466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.16554688, 3627.0234375, 371.01179687999996), 'rotation':(0.51447, 89.927071, 0.505291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.17335938, 3632.71191406, 371.06214844000004), 'rotation':(0.494287, 89.926048, 0.485827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.18101562, 3638.39992188, 371.11046875), 'rotation':(0.474418, 89.926369, 0.466616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.2042968799999, 3655.46460938, 371.24378906), 'rotation':(0.409395, 89.924477, 0.40358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.21984375, 3666.84078125, 371.32148437999996), 'rotation':(0.362881, 89.92453, 0.358307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.2364062500001, 3678.21804688, 371.38925781), 'rotation':(0.293111, 89.923065, 0.290133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.24308594, 3683.90578125, 371.41941406), 'rotation':(0.269506, 89.9235, 0.266979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(565.9946875, 3501.5034375, 369.57210938), 'rotation':(0.721213, 89.931305, 0.703211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.0020703099999, 3506.93796875, 369.64054688), 'rotation':(0.720926, 89.931305, 0.702949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.01683594, 3517.806875, 369.77734375), 'rotation':(0.716903, 89.930611, 0.699131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.02421875, 3523.24144531, 369.84554688), 'rotation':(0.716903, 89.930611, 0.699131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.0316015599999, 3528.67554688, 369.91335938), 'rotation':(0.708318, 89.930908, 0.69096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.05378906, 3544.97851562, 370.1128125), 'rotation':(0.68709, 89.930183, 0.670769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.06117188, 3550.41285156, 370.17820312000003), 'rotation':(0.68709, 89.930183, 0.670769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.06855469, 3555.84742188, 370.24335937999996), 'rotation':(0.687062, 89.930824, 0.670732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.0758593799999, 3561.28171875, 370.30824219000004), 'rotation':(0.679686, 89.929871, 0.663704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.0907031200001, 3572.15039062, 370.43578125), 'rotation':(0.650856, 89.929199, 0.636198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.098125, 3577.58421875, 370.49796875), 'rotation':(0.636512, 89.929329, 0.622481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.10546875, 3583.01832031, 370.55921875), 'rotation':(0.636512, 89.929329, 0.622481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(671.94097656, 3506.96019531, 371.3134375), 'rotation':(0.455724, 89.578033, 0.448521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(671.98332031, 3512.63453125, 371.35871094000004), 'rotation':(0.435035, 89.577103, 0.428467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.06769531, 3523.9821875, 371.44347655999997), 'rotation':(0.394484, 89.577126, 0.389075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.10992188, 3529.6560156200003, 371.48296875), 'rotation':(0.374062, 89.576263, 0.369205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.15210938, 3535.32984375, 371.52054688), 'rotation':(0.353947, 89.576004, 0.349589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.19433594, 3541.00414062, 371.55617187999997), 'rotation':(0.333224, 89.575752, 0.329367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.23652344, 3546.67796875, 371.58988281), 'rotation':(0.312809, 89.576126, 0.309414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.27875, 3552.3517968799997, 371.62164062000005), 'rotation':(0.302871, 89.575569, 0.299688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.32091797, 3558.02613281, 371.65203125), 'rotation':(0.289627, 89.575211, 0.286721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.3631054699999, 3563.70019531, 371.68125), 'rotation':(0.289627, 89.575211, 0.286721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(672.40527344, 3569.37402344, 371.70894531), 'rotation':(0.26372, 89.575447, 0.261303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.44757812, 3575.04761719, 371.7346875), 'rotation':(0.237786, 89.574753, 0.235822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.4897460899999, 3580.72242188, 371.75824219000003), 'rotation':(0.211879, 89.57502, 0.210312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(672.70582031, 3609.75121094, 371.85109375), 'rotation':(0.137, 89.574394, 0.136343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(672.7479882800001, 3615.43042969, 371.8640625), 'rotation':(0.113757, 89.574318, 0.113304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.83251953, 3626.78832031, 371.88242188), 'rotation':(0.045434, 89.573425, 0.045359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.95921875, 3643.82519531, 371.89101562), 'rotation':(-0.011993, 89.574173, -0.012024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.00140625, 3649.505625, 371.88992188), 'rotation':(-0.011993, 89.574173, -0.012024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.12816406, 3666.54367188, 371.88613281), 'rotation':(-0.027832, 89.574013, -0.027863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.1704101600001, 3672.223125, 371.88339844), 'rotation':(-0.059387, 89.574081, -0.059509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.2971093799999, 3689.25953125, 371.85773437999995), 'rotation':(-0.138702, 89.573959, -0.139374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(674.10857422, 3798.38992188, 371.52910155999996), 'rotation':(-0.184235, 89.574631, -0.185425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(674.0678710899999, 3792.91453125, 371.54667969), 'rotation':(-0.184235, 89.574631, -0.185425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(674.0271679699999, 3787.43921875, 371.56429688), 'rotation':(-0.184235, 89.574631, -0.185425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.9457421899999, 3776.48851562, 371.5996875), 'rotation':(-0.185089, 89.574936, -0.186279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.90503906, 3771.0129687500003, 371.61738281), 'rotation':(-0.185638, 89.574364, -0.186859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.86431641, 3765.53757812, 371.63523438), 'rotation':(-0.186218, 89.574364, -0.187439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.82361328, 3760.06226562, 371.65304688), 'rotation':(-0.186798, 89.574936, -0.188019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.78296875, 3754.5871875000003, 371.6709375), 'rotation':(-0.187378, 89.574379, -0.188599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(673.74224609, 3749.11179688, 371.68886719), 'rotation':(-0.187927, 89.574959, -0.189178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.66095703, 3738.15820312, 371.7246875), 'rotation':(-0.265228, 89.470718, -0.2677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.62011719, 3732.6862499999997, 371.74214844), 'rotation':(-0.183838, 89.5746, -0.184998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.5794140600001, 3727.2109375, 371.75886719000005), 'rotation':(-0.174744, 89.574554, -0.175781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.53869141, 3721.73609375, 371.77488281), 'rotation':(-0.165161, 89.574486, -0.166138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.4979882800001, 3716.26101562, 371.79035156), 'rotation':(-0.165161, 89.574486, -0.166138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(251.70640625, 3997.5659375, 367.74261719000003), 'rotation':(-1.611816, -90.143005, -1.704529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(251.69554688000005, 3994.24679688, 367.64917969000004), 'rotation':(-1.611725, -90.143127, -1.704437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(353.78820312000005, 4000.00046875, 368.64875), 'rotation':(-0.493835, -179.995743, -0.502411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(350.86253906, 4000.00046875, 368.80867187999996), 'rotation':(-0.493835, -179.995743, -0.502411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(460.29449219, 3993.8385937499997, 370.7621875), 'rotation':(0.012943, 89.969887, 0.012944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(460.29640625, 3997.5012500000003, 370.76296875), 'rotation':(0.012199, 89.96949, 0.012192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(572.2674999999999, 3994.3776562499997, 371.13457030999996), 'rotation':(0.104543, -90.146301, 0.104171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(572.2471875, 3991.25828125, 371.14027344000004), 'rotation':(0.104543, -90.146301, 0.104171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(676.9262109399999, 3999.4978125, 370.96628906), 'rotation':(0.131467, -90.034363, 0.130874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(679.30175781, 4000.00023438, 370.96511719), 'rotation':(0.131467, -90.034363, 0.130874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1543.07640625, 3819.32515625, 359.79875), 'rotation':(-0.611664, -80.956879, -0.624847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1542.18601562, 3824.92335938, 359.85824219), 'rotation':(-0.611664, -80.956879, -0.624847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1540.40515625, 3836.1198437499997, 359.96910155999996), 'rotation':(-0.540558, -80.957642, -0.550842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1539.5149999999999, 3841.7178125, 360.01820312), 'rotation':(-0.493195, -80.959473, -0.50174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1538.6248828100001, 3847.3151562499997, 360.06386719), 'rotation':(-0.445557, -80.958984, -0.452545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1537.734375, 3852.91359375, 360.10707031), 'rotation':(-0.445557, -80.958984, -0.452545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1536.8438671899999, 3858.5129687500003, 360.14878905999996), 'rotation':(-0.421722, -80.959167, -0.427948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1535.06296875, 3869.71046875, 360.22902344), 'rotation':(-0.391052, -80.960083, -0.396423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1532.39210938, 3886.504375, 360.32433594), 'rotation':(-0.267944, -80.961517, -0.270447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1531.50183594, 3892.10132812, 360.34867188), 'rotation':(-0.267944, -80.961517, -0.270447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1530.61144531, 3897.70070312, 360.3690625), 'rotation':(-0.206177, -80.962036, -0.207642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1516.365, 3987.2721874999997, 360.55042969000004), 'rotation':(-0.145935, -80.962402, -0.146667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1517.19800781, 3982.03585938, 360.53734375), 'rotation':(-0.096405, -80.962585, -0.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1518.0303906200002, 3976.80101562, 360.5284375), 'rotation':(-0.071472, -80.963135, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1519.6956640600001, 3966.3303125, 360.51429687999996), 'rotation':(-0.071503, -80.96283, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1520.52832031, 3961.09546875, 360.50765625), 'rotation':(-0.071472, -80.963135, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1522.19359375, 3950.6259375, 360.49445312000006), 'rotation':(-0.071503, -80.96283, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1523.85863281, 3940.15625, 360.48023437999996), 'rotation':(-0.102783, -80.963074, -0.103149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1525.52367188, 3929.68820312, 360.46066406), 'rotation':(-0.12384, -80.961945, -0.12439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1526.3560937500001, 3924.4540625, 360.44871094), 'rotation':(-0.144653, -80.963226, -0.145386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1534.661875, 3817.95632812, 359.7984375), 'rotation':(0.587929, 99.043289, 0.575958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1533.77136719, 3823.55445312, 359.85792969), 'rotation':(0.587929, 99.043289, 0.575958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1531.99070312, 3834.7512500000003, 359.96878906), 'rotation':(0.493201, 99.041801, 0.484758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1531.10046875, 3840.34859375, 360.01792969), 'rotation':(0.445561, 99.039749, 0.438669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1530.2100781200002, 3845.94625, 360.06367187999996), 'rotation':(0.421703, 99.040848, 0.415532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1528.4290624999999, 3857.14382812, 360.14859375), 'rotation':(0.421976, 99.03981, 0.415796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1527.53882812, 3862.7421875, 360.19015625), 'rotation':(0.391062, 99.039909, 0.38575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1526.6483203100001, 3868.3415625, 360.22886719), 'rotation':(0.329304, 99.039116, 0.32554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1525.7581640600001, 3873.9384375, 360.26457030999995), 'rotation':(0.329304, 99.039116, 0.32554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1523.08714844, 3890.7321875, 360.34855469), 'rotation':(0.206169, 99.037956, 0.204686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1522.19679688, 3896.3315625, 360.36894530999996), 'rotation':(0.175529, 99.036926, 0.174463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1517.09328125, 3928.4192187500003, 360.46082031), 'rotation':(0.10276, 99.036934, 0.102401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1515.39734375, 3939.0825, 360.48058594), 'rotation':(0.081949, 99.03756, 0.08172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1513.70128906, 3949.74679688, 360.49503905999995), 'rotation':(0.071478, 99.037148, 0.071309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1512.00511719, 3960.4114062500003, 360.50847655999996), 'rotation':(0.071485, 99.03685, 0.071308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1511.15699219, 3965.74390625, 360.51523438), 'rotation':(0.071485, 99.038094, 0.071297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1509.46058594, 3976.40945312, 360.53007812000004), 'rotation':(0.096408, 99.036545, 0.096086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1507.76402344, 3987.07570312, 360.55335937999996), 'rotation':(0.195453, 99.03791, 0.194125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1506.06714844, 3997.74390625, 360.58914062), 'rotation':(0.245197, 99.038841, 0.243111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1153.12695312, 3715.84304688, 367.35386719), 'rotation':(-0.058136, -80.453064, -0.058258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1155.83227539, 3699.7565624999997, 367.33746094), 'rotation':(-0.062958, -80.454041, -0.06311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1156.73413086, 3694.3940625, 367.33148437999995), 'rotation':(-0.067627, -80.453308, -0.06778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1157.63585938, 3689.03171875, 367.32515625), 'rotation':(-0.067627, -80.453308, -0.06778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1158.53759766, 3683.6696875, 367.31875), 'rotation':(-0.069763, -80.453552, -0.069916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1160.34106445, 3672.9453125, 367.30515625), 'rotation':(-0.07605, -80.453674, -0.076233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1161.24279297, 3667.58296875, 367.2978125), 'rotation':(-0.080231, -80.454102, -0.080444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1162.14464844, 3662.2209375, 367.29011719000005), 'rotation':(-0.084106, -80.453644, -0.084351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1163.04626953, 3656.85867188, 367.28199219000004), 'rotation':(-0.088287, -80.452362, -0.088562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1163.948125, 3651.49632812, 367.27351562), 'rotation':(-0.092468, -80.453613, -0.092773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1164.84984375, 3646.13429688, 367.26464844000003), 'rotation':(-0.096344, -80.454041, -0.096649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1165.75171875, 3640.77195312, 367.25539062), 'rotation':(-0.100525, -80.453583, -0.100861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1166.6534375, 3635.4096875, 367.24578125), 'rotation':(-0.102661, -80.453491, -0.103027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1167.55529297, 3630.04734375, 367.23609375), 'rotation':(-0.102356, -80.453491, -0.102722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1133.34607422, 3833.46414062, 367.39796875), 'rotation':(0.0089, -80.454102, 0.008897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1135.15587891, 3822.70289062, 367.39921875), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1136.0607910200001, 3817.32179688, 367.39945312000003), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1136.96570312, 3811.94070312, 367.3996875), 'rotation':(0.002677, -80.453369, 0.002676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1137.87072266, 3806.55953125, 367.39992187999997), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1138.7756347700001, 3801.1784374999997, 367.40019530999996), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1141.49035156, 3785.03609375, 367.39921875), 'rotation':(-0.020142, -80.453156, -0.020203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1143.30029297, 3774.274375, 367.39464844), 'rotation':(-0.027832, -80.453918, -0.027863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1145.11010742, 3763.5121875, 367.38933594), 'rotation':(-0.029358, -80.454163, -0.029388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1146.01501953, 3758.13132812, 367.38644531), 'rotation':(-0.032227, -80.452911, -0.032257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1128.92382812, 3859.7590625000003, 367.37738281), 'rotation':(0.065085, -80.450256, 0.064942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1128.0095214799999, 3865.19578125, 367.37101562000004), 'rotation':(0.065877, -80.453918, 0.065726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1126.18103516, 3876.0690624999997, 367.35757812), 'rotation':(0.072448, -80.452881, 0.072273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1125.26671875, 3881.50585938, 367.35039062000004), 'rotation':(0.072448, -80.452881, 0.072273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1124.35242188, 3886.9426562500003, 367.34296875), 'rotation':(0.07673, -80.454163, 0.076527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1121.609375, 3903.2526562499997, 367.31914062000004), 'rotation':(0.083383, -80.453857, 0.083157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1120.69506836, 3908.68945312, 367.31101562000003), 'rotation':(0.083793, -80.454346, 0.083553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1117.95226562, 3925.0, 367.28601562000006), 'rotation':(0.087324, -80.453064, 0.087071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1117.0378418, 3930.4365625, 367.27746094), 'rotation':(0.087973, -80.453064, 0.087711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1116.12353516, 3935.87328125, 367.26882812), 'rotation':(0.090227, -80.453064, 0.089941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1115.20922852, 3941.31007812, 367.26007812000006), 'rotation':(0.091504, -80.454346, 0.091222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1145.62146484, 3709.066875, 367.34871094000005), 'rotation':(0.053303, 99.545914, 0.053215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1147.42504883, 3698.3424999999997, 367.33746094), 'rotation':(0.058152, 99.546928, 0.058022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1148.3269043, 3692.98, 367.33148437999995), 'rotation':(0.062981, 99.545944, 0.062832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1150.13037109, 3682.255625, 367.31875), 'rotation':(0.067612, 99.5467, 0.067459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1151.03210938, 3676.8932812499997, 367.31207030999997), 'rotation':(0.06975, 99.546463, 0.069593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1153.73742188, 3660.806875, 367.29011719000005), 'rotation':(0.080221, 99.545914, 0.080003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1154.63916016, 3655.44460938, 367.28199219000004), 'rotation':(0.0841, 99.546364, 0.083846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1155.54089844, 3650.08226562, 367.27351562), 'rotation':(0.088273, 99.547638, 0.088011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1156.44262695, 3644.72023438, 367.26464844000003), 'rotation':(0.09246, 99.546371, 0.092171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1157.34448242, 3639.35789062, 367.25539062), 'rotation':(0.096319, 99.545944, 0.096012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1158.24621094, 3633.99585938, 367.24578125), 'rotation':(0.10052, 99.54641, 0.100176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1159.14806641, 3628.63328125, 367.23609375), 'rotation':(0.102671, 99.546494, 0.102304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1124.93738281, 3832.0590625, 367.39796875), 'rotation':(-0.021484, 99.545464, -0.021484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1127.65234375, 3815.9153125000003, 367.39945312000003), 'rotation':(-0.002472, 99.545807, -0.002472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1128.55737305, 3810.53367188, 367.3996875), 'rotation':(-0.002686, 99.546906, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1129.46240234, 3805.15210938, 367.39992187999997), 'rotation':(-0.002686, 99.545807, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1131.27246094, 3794.38890625, 367.40042969), 'rotation':(-0.002686, 99.546906, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1132.17761719, 3789.0078125, 367.40019530999996), 'rotation':(0.005157, 99.545586, 0.00516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1133.08251953, 3783.62671875, 367.39921875), 'rotation':(0.005157, 99.545586, 0.00516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1133.98754883, 3778.24515625, 367.39726562000004), 'rotation':(0.02017, 99.546837, 0.020142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1135.79760742, 3767.4821875, 367.39203125), 'rotation':(0.027833, 99.546387, 0.027819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1136.70263672, 3762.100625, 367.38933594), 'rotation':(0.027826, 99.546082, 0.027805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1137.60753906, 3756.71945312, 367.38644531), 'rotation':(0.029349, 99.54583, 0.029314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1138.51257812, 3751.33789062, 367.38328125), 'rotation':(0.032211, 99.547089, 0.032189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1139.41759766, 3745.9565625, 367.37980469), 'rotation':(0.035401, 99.545837, 0.035358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1107.71606445, 3934.46164062, 367.26882812), 'rotation':(-0.091492, 99.546928, -0.091797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1109.54443359, 3923.589375, 367.28601562000006), 'rotation':(-0.087982, 99.545654, -0.088257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1111.37292969, 3912.7165625, 367.30277344), 'rotation':(-0.08606, 99.545654, -0.086304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1112.28722656, 3907.2803125, 367.31097656), 'rotation':(-0.085083, 99.547333, -0.085358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1113.20141602, 3901.84398438, 367.31910156), 'rotation':(-0.083801, 99.545647, -0.084045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1114.11572266, 3896.40773438, 367.3271875), 'rotation':(-0.083801, 99.545647, -0.084045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1115.02990234, 3890.97171875, 367.33515625), 'rotation':(-0.083405, 99.547089, -0.083649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1115.94421875, 3885.53539062, 367.34296875), 'rotation':(-0.081268, 99.546188, -0.081482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1117.77270508, 3874.6628124999997, 367.35757812), 'rotation':(-0.076752, 99.545853, -0.076935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1119.60095703, 3863.79054688, 367.37101562000004), 'rotation':(-0.068176, 99.54615, -0.068329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1120.51513672, 3858.3542187499997, 367.37738281), 'rotation':(-0.065887, 99.546883, -0.06604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1348.6740625, 3753.79296875, 363.00398437999996), 'rotation':(-0.04068, -80.8302, -0.040741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1351.29796875, 3737.53882812, 362.99742188), 'rotation':(-0.001312, -80.82959, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1352.1725000000001, 3732.12132812, 362.99730469), 'rotation':(-0.001312, -80.829865, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1353.04699219, 3726.70382812, 362.9971875), 'rotation':(-0.001312, -80.829865, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1354.7960156200002, 3715.86867188, 362.99695312000006), 'rotation':(-0.001312, -80.830566, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1355.67054688, 3710.45117188, 362.99679688), 'rotation':(-0.001312, -80.829865, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1357.41980469, 3699.61570312, 362.99695312000006), 'rotation':(0.008278, -80.830048, 0.00828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1358.29429688, 3694.1975, 362.99824219000004), 'rotation':(0.026774, -80.829285, 0.026768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1360.0434375, 3683.36179688, 363.00441406), 'rotation':(0.036582, -80.830078, 0.036538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1360.91796875, 3677.944375, 363.00792969), 'rotation':(0.036582, -80.830078, 0.036538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1363.53675781, 3661.7239062500003, 363.01839844), 'rotation':(7e-06, -81.869873, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1330.61988281, 3865.6328125, 363.28800780999995), 'rotation':(-0.211212, -80.829254, -0.212769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1331.4837499999999, 3860.28171875, 363.26761719), 'rotation':(-0.211212, -80.829254, -0.212769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1332.34765625, 3854.930625, 363.24761719), 'rotation':(-0.198883, -80.829102, -0.200256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1333.21140625, 3849.5793750000003, 363.22847656), 'rotation':(-0.198883, -80.829102, -0.200256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1336.66675781, 3828.1745312499997, 363.15882812), 'rotation':(-0.167511, -80.829926, -0.168488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1343.57738281, 3785.365, 363.05050781), 'rotation':(-0.105682, -80.829895, -0.106079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1344.44117188, 3780.01414062, 363.0409375), 'rotation':(-0.090942, -80.832642, -0.091217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1313.43859375, 3972.06664062, 363.72101562000006), 'rotation':(-0.200317, -80.82959, -0.201721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1314.30322266, 3966.7109375, 363.70207030999995), 'rotation':(-0.204163, -80.82959, -0.205597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1315.16773438, 3961.35546875, 363.68289062), 'rotation':(-0.204163, -80.82959, -0.205597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1316.89660156, 3950.64429688, 363.64320312), 'rotation':(-0.218781, -80.829468, -0.220428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1318.62574219, 3939.933125, 363.60105469), 'rotation':(-0.233398, -80.829346, -0.235291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1320.35472656, 3929.2221875, 363.55628906), 'rotation':(-0.247742, -80.829224, -0.249878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1321.21923828, 3923.86671875, 363.53304688), 'rotation':(-0.255188, -80.829163, -0.257477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1322.08289062, 3918.51078125, 363.50914062000004), 'rotation':(-0.25528, -80.828979, -0.257568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1322.94835938, 3913.15554688, 363.485), 'rotation':(-0.25528, -80.828979, -0.257568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1323.81298828, 3907.7995312499997, 363.46089844), 'rotation':(-0.248352, -80.828369, -0.250519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1324.6775, 3902.44382812, 363.43738281), 'rotation':(-0.241669, -80.829407, -0.243713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1326.40673828, 3891.73195312, 363.39171875), 'rotation':(-0.234985, -80.828827, -0.236908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1354.25132812, 3665.74804688, 363.01492188), 'rotation':(-0.036377, 99.16964, -0.036407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1353.37695312, 3671.16476562, 363.01144531), 'rotation':(-0.036591, 99.16964, -0.036621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1352.50257812, 3676.58132812, 363.00792969), 'rotation':(-0.036591, 99.170494, -0.036621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1351.62816406, 3681.99804688, 363.00441406), 'rotation':(-0.036591, 99.170494, -0.036621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1350.75378906, 3687.41453125, 363.0009375), 'rotation':(-0.026794, 99.169601, -0.026825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1349.00476562, 3698.2490625, 362.99699219), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1347.25597656, 3709.0825, 362.99679688), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1346.38160156, 3714.4990625, 362.99695312000006), 'rotation':(0.001318, 99.169655, 0.001311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1345.5071874999999, 3719.91578125, 362.99707030999997), 'rotation':(0.001318, 99.169655, 0.001311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1344.6328125, 3725.33226562, 362.9971875), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1343.7584375000001, 3730.7487499999997, 362.99730469), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1342.88402344, 3736.16554688, 362.99742188), 'rotation':(0.009159, 99.169746, 0.009151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1342.00953125, 3741.58226562, 362.998125), 'rotation':(0.024746, 99.169319, 0.02473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1340.260625, 3752.4167187499997, 363.00398437999996), 'rotation':(0.056301, 99.170219, 0.056188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1336.0279687500001, 3778.63625, 363.0409375), 'rotation':(0.096039, 99.170502, 0.095729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1335.16417969, 3783.9870312499997, 363.05046875), 'rotation':(0.114986, 99.170151, 0.114518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1334.3003125, 3789.3385937499997, 363.0609375), 'rotation':(0.124617, 99.170639, 0.124083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1332.57261719, 3800.04078125, 363.08464844), 'rotation':(0.143564, 99.170288, 0.142845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1331.70886719, 3805.39234375, 363.09792969), 'rotation':(0.153543, 99.169449, 0.152717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1330.84507812, 3810.7434375000003, 363.11210938), 'rotation':(0.162511, 99.170822, 0.161594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1329.98121094, 3816.0946875, 363.1271875), 'rotation':(0.167517, 99.171028, 0.166538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1329.11742188, 3821.44578125, 363.14292969), 'rotation':(0.167517, 99.171028, 0.166538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1328.25355469, 3826.79664062, 363.15878906), 'rotation':(0.173801, 99.169678, 0.172754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1327.38964844, 3832.14796875, 363.17523437999995), 'rotation':(0.186348, 99.17083, 0.185131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1326.52587891, 3837.4990625, 363.19214844000004), 'rotation':(0.186348, 99.17083, 0.185131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1323.93445312, 3853.55273438, 363.24757812), 'rotation':(0.211189, 99.170998, 0.209646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1323.07054688, 3858.90382812, 363.26753906), 'rotation':(0.217808, 99.170715, 0.216158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1305.02283203, 3970.7053125, 363.72101562000006), 'rotation':(0.200323, 99.170395, 0.19893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1305.88746094, 3965.34859375, 363.70203125), 'rotation':(0.200323, 99.170639, 0.198934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1307.61695312, 3954.6354687499997, 363.66332030999996), 'rotation':(0.204134, 99.170418, 0.202697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1310.2108203100001, 3938.56570312, 363.60101562000006), 'rotation':(0.225642, 99.170586, 0.223884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1311.07556641, 3933.20921875, 363.57890625), 'rotation':(0.233381, 99.170647, 0.231502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1312.8048046899999, 3922.49632812, 363.53300780999996), 'rotation':(0.247717, 99.17189, 0.245588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1313.66955078, 3917.13992188, 363.50910156), 'rotation':(0.255183, 99.17083, 0.252916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1315.39904297, 3906.42625, 363.46085938), 'rotation':(0.255258, 99.170731, 0.252999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1316.26378906, 3901.069375, 363.43730469), 'rotation':(0.248352, 99.171898, 0.246208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1317.99316406, 3890.35546875, 363.39167969000005), 'rotation':(0.241652, 99.170601, 0.239631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1729.5592187500001, 3930.07960938, 357.58035156), 'rotation':(-0.567444, -80.662628, -0.578796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1730.48007812, 3924.47507812, 357.52308594000004), 'rotation':(-0.567444, -80.662628, -0.578796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1731.40109375, 3918.870625, 357.46703125), 'rotation':(-0.543762, -80.662811, -0.554169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1733.2428906199998, 3907.66257812, 357.36078125), 'rotation':(-0.52005, -80.663513, -0.529572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1734.1638281199998, 3902.05859375, 357.30945312000006), 'rotation':(-0.50824, -80.664093, -0.517303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1735.08460938, 3896.45507812, 357.2590625), 'rotation':(-0.504791, -80.663605, -0.513763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1736.00546875, 3890.85132812, 357.20894531), 'rotation':(-0.498322, -80.663452, -0.50705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1736.92625, 3885.2473437500003, 357.15910155999995), 'rotation':(-0.498322, -80.663452, -0.50705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1737.8471875, 3879.6440625, 357.10972655999996), 'rotation':(-0.491821, -80.664642, -0.500305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1738.76804688, 3874.03976562, 357.06085937999995), 'rotation':(-0.485138, -80.663696, -0.493408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1739.68898438, 3868.43601562, 357.01226562000005), 'rotation':(-0.485138, -80.663696, -0.493408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1740.60984375, 3862.83226562, 356.96417969000004), 'rotation':(-0.482147, -80.663513, -0.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1741.5306249999999, 3857.22875, 356.91632812000006), 'rotation':(-0.481781, -80.663971, -0.489929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1742.4515625, 3851.625, 356.86855469), 'rotation':(-0.482117, -80.664886, -0.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1743.37234375, 3846.02125, 356.82078125), 'rotation':(-0.481781, -80.663513, -0.48996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1718.43539062, 3997.77195312, 358.39292969), 'rotation':(-0.757721, -80.658264, -0.777985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1720.96609375, 3982.3715625, 358.18867187999996), 'rotation':(-0.713593, -80.659241, -0.731537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1721.80984375, 3977.23734375, 358.12320312), 'rotation':(-0.713593, -80.659241, -0.731537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1722.65328125, 3972.10398438, 358.05839844), 'rotation':(-0.684357, -80.659729, -0.700867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1724.3405468800001, 3961.83617188, 357.93367187999996), 'rotation':(-0.65509, -80.661133, -0.670227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1721.1452343800001, 3928.7057812499997, 357.58042969), 'rotation':(0.591344, 99.337303, 0.579222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1722.0662499999999, 3923.10085938, 357.523125), 'rotation':(0.591344, 99.337303, 0.579222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1722.98734375, 3917.49585938, 357.46714844), 'rotation':(0.567479, 99.337639, 0.556309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1723.90820312, 3911.8915625, 357.41320312000005), 'rotation':(0.543758, 99.336914, 0.53351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1724.82921875, 3906.286875, 357.36085937999997), 'rotation':(0.543758, 99.336914, 0.53351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1726.6711718800002, 3895.078125, 357.25914062000004), 'rotation':(0.508207, 99.336517, 0.499253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1727.59203125, 3889.47414062, 357.20902344), 'rotation':(0.504799, 99.335846, 0.495965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1728.51304688, 3883.8698437499997, 357.15917969000003), 'rotation':(0.504799, 99.335846, 0.495965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1729.4340625, 3878.265625, 357.10976562), 'rotation':(0.498296, 99.336281, 0.489689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1731.27601562, 3867.05710938, 357.01230469), 'rotation':(0.491835, 99.336426, 0.483439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1732.196875, 3861.45289062, 356.96421875), 'rotation':(0.485121, 99.336037, 0.476969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1734.03867188, 3850.24460938, 356.86855469), 'rotation':(0.481795, 99.336472, 0.47374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1716.77171875, 3955.31882812, 357.87394530999995), 'rotation':(0.684358, 99.340263, 0.668157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1715.8996875, 3960.6262500000003, 357.93574219000004), 'rotation':(0.684358, 99.340263, 0.668157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1714.1555468800002, 3971.23921875, 358.06492188), 'rotation':(0.713618, 99.340958, 0.696009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1713.28359375, 3976.54539062, 358.13191406), 'rotation':(0.74322, 99.341019, 0.724125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1710.6675, 3992.4653125, 358.3403125), 'rotation':(0.757693, 99.3424, 0.737857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1108.40429688, 3982.94070312, 367.18617187999996), 'rotation':(0.108327, -80.973724, 0.107923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1107.62121094, 3987.87085938, 367.1765625), 'rotation':(0.110512, -80.97348, 0.11008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1099.98535156, 3981.59960938, 367.18621094), 'rotation':(-0.110504, 99.026512, -0.110931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1098.27709961, 3992.35375, 367.1646875), 'rotation':(-0.118561, 99.026939, -0.119049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1097.42285156, 3997.73070312, 367.15339844000005), 'rotation':(-0.122162, 99.025688, -0.122681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2023.62320312, 4005.26195312, 357.936875), 'rotation':(-0.806641, -80.748016, -0.82959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2020.99351562, 4021.42554688, 358.15851562000006), 'rotation':(-0.774719, -80.749939, -0.795898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2020.1171875, 4026.81296875, 358.22921875), 'rotation':(-0.742859, -80.749756, -0.762329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2018.3639062500001, 4037.59007812, 358.36417969), 'rotation':(-0.695343, -80.752197, -0.712372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2017.48734375, 4042.97851562, 358.42910156), 'rotation':(-0.678131, -80.750732, -0.694336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2016.61085938, 4048.3659374999997, 358.49121094000003), 'rotation':(-0.643219, -80.753143, -0.657806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2015.734375, 4053.75367188, 358.55015625), 'rotation':(-0.608368, -80.75351, -0.621399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2014.85789062, 4059.14132812, 358.6059375), 'rotation':(-0.574066, -80.752991, -0.585663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2013.98132812, 4064.5290625, 358.65859375), 'rotation':(-0.539185, -80.754913, -0.549408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2013.1048437499999, 4069.9167187499997, 358.70808594000005), 'rotation':(-0.504608, -80.755554, -0.51355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2011.3517968800002, 4080.69210938, 358.79761719000004), 'rotation':(-0.469696, -80.75531, -0.477417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2010.47523438, 4086.08054688, 358.83835938), 'rotation':(-0.435089, -80.756683, -0.441742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2002.9376562500001, 4079.32078125, 358.79761719000004), 'rotation':(0.435083, 99.24292, 0.428513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2004.6907812499999, 4068.5442187500003, 358.70808594000005), 'rotation':(0.469698, 99.243874, 0.462041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2006.44382812, 4057.76757812, 358.60589844000003), 'rotation':(0.539189, 99.245087, 0.529111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2007.3204687500001, 4052.379375, 358.55007812), 'rotation':(0.574077, 99.245773, 0.562664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2008.19703125, 4046.99125, 358.49113280999995), 'rotation':(0.608338, 99.247292, 0.595515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2009.95007812, 4036.21414062, 358.3640625), 'rotation':(0.678135, 99.248047, 0.662228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2010.82679688, 4030.8254687500003, 358.29691406), 'rotation':(0.695327, 99.249924, 0.678612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2012.58023438, 4020.0478125, 358.15839844000004), 'rotation':(0.742851, 99.250244, 0.723774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2014.33351562, 4009.27046875, 358.01269530999997), 'rotation':(0.774728, 99.250832, 0.753989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2035.4759374999999, 4556.77832031, 361.81542969000003), 'rotation':(-0.443787, -80.659302, -0.450714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2037.2576562499999, 4545.93945312, 361.73074219), 'rotation':(-0.433044, -80.659454, -0.439636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2038.1486718800002, 4540.52050781, 361.68921875), 'rotation':(-0.427002, -80.661621, -0.433411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2039.9346875, 4529.65773438, 361.60753905999997), 'rotation':(-0.503571, -79.87088, -0.512451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2040.8215625, 4524.26320312, 361.56753906), 'rotation':(-0.420532, -80.659607, -0.426758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2041.71242188, 4518.84421875, 361.52726562000004), 'rotation':(-0.421143, -80.661682, -0.427368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2043.49414062, 4508.00632812, 361.44640625), 'rotation':(-0.423431, -80.659546, -0.429718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2044.38515625, 4502.58742188, 361.40582030999997), 'rotation':(-0.424347, -80.661652, -0.430664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2045.27601562, 4497.16796875, 361.36515625), 'rotation':(-0.425018, -80.660797, -0.431366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2046.166875, 4491.74902344, 361.32441406), 'rotation':(-0.426239, -80.661621, -0.432648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2047.94875, 4480.91113281, 361.24265625), 'rotation':(-0.426636, -80.661407, -0.433014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2015.8865624999999, 4675.93164062, 362.73976562), 'rotation':(-0.410706, -80.661072, -0.416626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2016.78429688, 4670.47167969, 362.70011719), 'rotation':(-0.410706, -80.661072, -0.416626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2018.57960938, 4659.55125, 362.62066405999997), 'rotation':(-0.415253, -80.661896, -0.421295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2019.4772656199998, 4654.09132812, 362.58054688), 'rotation':(-0.418304, -80.66098, -0.424469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2020.3747656199998, 4648.63183594, 362.54019531), 'rotation':(-0.421692, -80.660919, -0.427917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2021.2725, 4643.17140625, 362.49945312000006), 'rotation':(-0.425049, -80.659546, -0.431396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2022.17015625, 4637.71140625, 362.45835938), 'rotation':(-0.427704, -80.661682, -0.434143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2023.06773438, 4632.25195312, 362.41699219000003), 'rotation':(-0.431122, -80.660767, -0.437653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2024.8630468800002, 4621.3315625, 362.33328125), 'rotation':(-0.43576, -80.660614, -0.442413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2025.760625, 4615.8715625, 362.29121094000004), 'rotation':(-0.43924, -80.660767, -0.446014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2027.55601562, 4604.95214844, 362.20621094), 'rotation':(-0.44574, -80.660278, -0.452728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2038.6452343800001, 4484.94875, 361.28359375), 'rotation':(0.426293, 99.339226, 0.419985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2036.86328125, 4495.78757812, 361.36519531), 'rotation':(0.424373, 99.340454, 0.418124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2035.97226562, 4501.2075, 361.40585938), 'rotation':(0.423417, 99.339172, 0.417189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2035.0813281199999, 4506.62695312, 361.44644531), 'rotation':(0.422092, 99.338326, 0.415917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2034.1903125, 4512.04640625, 361.48691406), 'rotation':(0.421177, 99.340401, 0.415023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2033.29929688, 4517.46582031, 361.52726562000004), 'rotation':(0.420501, 99.338295, 0.414366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2031.51734375, 4528.3046875, 361.60777344), 'rotation':(0.421634, 99.338318, 0.415469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2030.62632812, 4533.72460938, 361.64824219), 'rotation':(0.427044, 99.340454, 0.42072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2029.73523438, 4539.1440625, 361.68925780999996), 'rotation':(0.433054, 99.339287, 0.426546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2027.9532812500001, 4549.98390625, 361.77289062000006), 'rotation':(0.443792, 99.33947, 0.43696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2026.1711718800002, 4560.82324219, 361.85859375), 'rotation':(0.455157, 99.340889, 0.447969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2025.28015625, 4566.24265625, 361.90226562000004), 'rotation':(0.460491, 99.338913, 0.453123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2020.9373437499999, 4592.65773438, 362.11921875), 'rotation':(0.452582, 99.339806, 0.445474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2020.0397656199998, 4598.11671875, 362.16300780999995), 'rotation':(0.445793, 99.339333, 0.438888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2019.14234375, 4603.57664062, 362.20625), 'rotation':(0.439236, 99.340302, 0.432532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2018.24476562, 4609.035625, 362.24898437999997), 'rotation':(0.439236, 99.340302, 0.432532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2015.55210938, 4625.41453125, 362.37535155999996), 'rotation':(0.431081, 99.338333, 0.424629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2014.65453125, 4630.87351562, 362.41703125), 'rotation':(0.427747, 99.340492, 0.421406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2011.96179688, 4647.25195312, 362.54023437999996), 'rotation':(0.418315, 99.340355, 0.412242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2011.06429688, 4652.71140625, 362.58058594), 'rotation':(0.415289, 99.338974, 0.409302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2010.16671875, 4658.17089844, 362.62070312000003), 'rotation':(0.41225, 99.338936, 0.406357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2009.26914062, 4663.63039062, 362.66046875), 'rotation':(0.410706, 99.338936, 0.404853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2232.0598437500003, 4600.07078125, 362.55230469), 'rotation':(-0.679962, -80.440918, -0.696259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2232.98804688, 4594.5625, 362.48601562000005), 'rotation':(-0.674713, -80.440186, -0.690735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2234.84421875, 4583.546875, 362.35515625), 'rotation':(-0.663696, -80.44043, -0.679199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2235.7725, 4578.0390625, 362.29058594), 'rotation':(-0.65802, -80.440582, -0.673279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2236.70070312, 4572.53125, 362.22660156), 'rotation':(-0.652618, -80.438934, -0.667633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2237.62867188, 4567.02296875, 362.16316406), 'rotation':(-0.647339, -80.440796, -0.662109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2238.556875, 4561.51515625, 362.10019531), 'rotation':(-0.64444, -80.439453, -0.659058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2239.48507812, 4556.00734375, 362.03734375), 'rotation':(-0.639832, -80.439087, -0.654236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2240.41359375, 4550.49953125, 361.97472655999997), 'rotation':(-0.639832, -80.439087, -0.654236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2243.1979687499997, 4533.97558594, 361.79074219), 'rotation':(-0.611481, -80.440369, -0.624634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2244.1262500000003, 4528.46777344, 361.73097656), 'rotation':(-0.60675, -80.441742, -0.61969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2245.05445312, 4522.95945312, 361.67167969), 'rotation':(-0.60675, -80.441742, -0.61969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2245.98242188, 4517.45164062, 361.61253905999996), 'rotation':(-0.606689, -80.440765, -0.619659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2213.9184375, 4707.87109375, 363.65429687999995), 'rotation':(-0.441345, -80.444702, -0.448181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2215.74289062, 4697.03027344, 363.56925780999995), 'rotation':(-0.450012, -80.44339, -0.457123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2219.3915625, 4675.34960938, 363.38273438), 'rotation':(-0.522827, -80.444702, -0.53244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2220.30320312, 4669.92921875, 363.33175781), 'rotation':(-0.558929, -80.441467, -0.569916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2221.2153125, 4664.50976562, 363.27894531), 'rotation':(-0.576965, -80.443665, -0.588684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2222.12742188, 4659.089375, 363.22441405999996), 'rotation':(-0.586426, -80.441223, -0.598511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2223.95164062, 4648.24902344, 363.11179688), 'rotation':(-0.596832, -80.44104, -0.609375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2224.86375, 4642.82859375, 363.05417969), 'rotation':(-0.617859, -80.441193, -0.631317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2226.68820312, 4631.98828125, 362.93394530999996), 'rotation':(-0.660187, -80.440857, -0.675537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2237.55539062, 4516.0346875, 361.61253905999996), 'rotation':(0.606726, 99.55825, 0.593981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2232.9209375, 4543.5746875, 361.91265625), 'rotation':(0.639825, 99.560913, 0.625645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2231.99414062, 4549.08300781, 361.97476562), 'rotation':(0.644449, 99.557953, 0.63007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2230.14015625, 4560.09863281, 362.10019531), 'rotation':(0.647352, 99.559189, 0.63284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2229.213125, 4565.60644531, 362.16316406), 'rotation':(0.652631, 99.561043, 0.637884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2228.2864062500003, 4571.11476562, 362.22660156), 'rotation':(0.65802, 99.559418, 0.643045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2227.359375, 4576.62257812, 362.29058594), 'rotation':(0.663689, 99.559555, 0.648454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2226.43265625, 4582.13132812, 362.35519531), 'rotation':(0.669304, 99.561432, 0.653791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2225.505625, 4587.63914062, 362.4203125), 'rotation':(0.6747, 99.559814, 0.65895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2223.651875, 4598.65527344, 362.55230469), 'rotation':(0.685642, 99.559189, 0.669384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2219.19289062, 4625.15382812, 362.871875), 'rotation':(0.639155, 99.559265, 0.625014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2218.28101562, 4630.57375, 362.93394530999996), 'rotation':(0.639155, 99.559265, 0.625014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2214.63234375, 4652.254375, 363.16859375), 'rotation':(0.58642, 99.558769, 0.574504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2212.808125, 4663.09523438, 363.27894531), 'rotation':(0.558989, 99.559364, 0.54816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2211.8957812500003, 4668.51464844, 363.33175781), 'rotation':(0.540883, 99.558174, 0.53074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.98390625, 4673.93505859, 363.38277344), 'rotation':(0.504799, 99.557518, 0.495955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.0715625000003, 4679.35546875, 363.43207031), 'rotation':(0.486419, 99.557198, 0.478211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.2473437500003, 4690.1953125, 363.5253125), 'rotation':(0.45, 99.556602, 0.442972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2207.33546875, 4695.61572266, 363.56925780999995), 'rotation':(0.441353, 99.555283, 0.434593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2419.84644531, 4625.25929688, 364.00375), 'rotation':(-0.931396, -81.108948, -0.962067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2420.70628906, 4619.75390625, 363.913125), 'rotation':(-0.928009, -81.109039, -0.958435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2421.56617188, 4614.24804688, 363.82277344), 'rotation':(-0.924591, -81.106689, -0.954803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2422.42601562, 4608.7421875, 363.73277344), 'rotation':(-0.921173, -81.109253, -0.951172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2425.005625, 4592.22507812, 363.46480469), 'rotation':(-0.912506, -81.110657, -0.941925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2426.72558594, 4581.21289062, 363.28894531), 'rotation':(-0.883118, -81.10791, -0.910675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2428.4455468799997, 4570.20070312, 363.11792969000004), 'rotation':(-0.859222, -81.108643, -0.885284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2429.30566406, 4564.69484375, 363.03433594), 'rotation':(-0.847504, -81.109833, -0.872864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2431.02539062, 4553.68210938, 362.87097656), 'rotation':(-0.823608, -81.110535, -0.847534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2431.88523438, 4548.17625, 362.79101562000005), 'rotation':(-0.817505, -81.11264, -0.841095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2402.16039062, 4738.50146484, 365.50664062000004), 'rotation':(-0.564789, -81.115936, -0.575989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2403.00632812, 4733.08496094, 365.45257812000006), 'rotation':(-0.565125, -81.118591, -0.576355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2403.85230469, 4727.66845703, 365.39851562), 'rotation':(-0.564789, -81.115936, -0.575989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2406.38964844, 4711.42089844, 365.22914062), 'rotation':(-0.633911, -81.116058, -0.648071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2407.23558594, 4706.00439453, 365.16851562000005), 'rotation':(-0.680023, -81.115021, -0.69632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2408.08128906, 4700.58984375, 365.10460937999994), 'rotation':(-0.680023, -81.115021, -0.69632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2408.92699219, 4695.17333984, 365.03953125), 'rotation':(-0.725952, -81.113892, -0.744537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2410.61867188, 4684.34277344, 364.90027344000003), 'rotation':(-0.748871, -81.111694, -0.768646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2411.464375, 4678.92724609, 364.82851562), 'rotation':(-0.765442, -81.113983, -0.786102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2412.3103125, 4673.51123047, 364.75527344), 'rotation':(-0.79837, -81.112457, -0.820862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2414.00171875, 4662.68066406, 364.60148438), 'rotation':(-0.831207, -81.110138, -0.855591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2414.84742188, 4657.265625, 364.52113281), 'rotation':(-0.863831, -81.111176, -0.890167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2423.46214844, 4546.85890625, 362.79101562000005), 'rotation':(0.823666, 98.890305, 0.800241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2422.60253906, 4552.36425781, 362.8709375), 'rotation':(0.835209, 98.887093, 0.811122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2421.74265625, 4557.87011719, 362.95195312000004), 'rotation':(0.847592, 98.891022, 0.822782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2420.8828125, 4563.37597656, 363.03425781), 'rotation':(0.85921, 98.888664, 0.833729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2420.02269531, 4568.88132812, 363.11785155999996), 'rotation':(0.87074, 98.890862, 0.844568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2419.16285156, 4574.3871875, 363.20277344000004), 'rotation':(0.883123, 98.892082, 0.856203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2418.30296875, 4579.89304688, 363.28886719), 'rotation':(0.894666, 98.888908, 0.867035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2417.443125, 4585.39890625, 363.37628906), 'rotation':(0.907042, 98.89283, 0.878652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2416.58324219, 4590.90382812, 363.46472656), 'rotation':(0.914371, 98.890511, 0.885523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2415.72363281, 4596.4096875, 363.55371094000003), 'rotation':(0.917772, 98.893089, 0.888705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2414.86375, 4601.91503906, 363.64304688), 'rotation':(0.921181, 98.890732, 0.891904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2414.00390625, 4607.41992188, 363.73269531), 'rotation':(0.924582, 98.89328, 0.89509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2413.1440625, 4612.9253125, 363.82269531), 'rotation':(0.927997, 98.890945, 0.89829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2411.42429688, 4623.93554688, 364.00363281), 'rotation':(0.934807, 98.893616, 0.904661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2405.57984375, 4661.35695312, 364.60136719), 'rotation':(0.798312, 98.888916, 0.776308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2404.73390625, 4666.77296875, 364.67945312000006), 'rotation':(0.798312, 98.888916, 0.776308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2402.19605469, 4683.02148438, 364.90019530999996), 'rotation':(0.725953, 98.886116, 0.707725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2401.35035156, 4688.4375, 364.97011719), 'rotation':(0.725953, 98.886116, 0.707725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2398.81296875, 4704.68457031, 365.1684375), 'rotation':(0.63391, 98.882477, 0.619999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2397.96703125, 4710.10205078, 365.22914062), 'rotation':(0.587963, 98.882942, 0.575994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2397.12109375, 4715.51757812, 365.28757812000003), 'rotation':(0.587963, 98.882942, 0.575994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2396.27515625, 4720.93457031, 365.34382812), 'rotation':(0.564768, 98.884048, 0.553719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2394.58324219, 4731.76806641, 365.45253906), 'rotation':(0.564768, 98.884048, 0.553719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2393.73730469, 4737.18505859, 365.50660156), 'rotation':(0.564945, 98.881233, 0.553882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3448.25046875, 4797.3671875, 367.96097656), 'rotation':(0.053357, -80.436371, 0.053262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3449.16796875, 4791.92041016, 367.96613281), 'rotation':(0.055639, -80.438049, 0.055528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3450.08546875, 4786.47363281, 367.97148438), 'rotation':(0.058214, -80.438904, 0.058103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3451.0034375, 4781.02587891, 367.97710937999994), 'rotation':(0.060474, -80.438049, 0.060354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3452.83835938, 4770.13232422, 367.98910156), 'rotation':(0.065338, -80.43634, 0.065184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3453.75609375, 4764.68554688, 367.99546875), 'rotation':(0.068247, -80.438049, 0.068093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3454.67359375, 4759.23876953, 368.00203125), 'rotation':(0.069046, -80.437134, 0.06888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3455.59105469, 4753.79150391, 368.00867187999995), 'rotation':(0.069046, -80.439758, 0.068884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3456.50855469, 4748.34472656, 368.01535156), 'rotation':(0.069046, -80.437134, 0.06888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3457.42601562, 4742.89794922, 368.02199219), 'rotation':(0.068384, -80.437134, 0.068219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3458.34375, 4737.45117188, 368.02859375), 'rotation':(0.068384, -80.437134, 0.068219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3459.26125, 4732.00439453, 368.03519531), 'rotation':(0.068377, -80.439758, 0.068224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3460.17871094, 4726.55761719, 368.04175781), 'rotation':(0.068049, -80.437134, 0.067889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3461.09644531, 4721.11035156, 368.04832031), 'rotation':(0.067721, -80.438049, 0.067555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3462.01390625, 4715.66357422, 368.05484375), 'rotation':(0.067674, -80.437622, 0.067527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3443.77417969, 4823.94042969, 367.938125), 'rotation':(0.047955, -80.438751, 0.047876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3442.84472656, 4829.45898438, 367.93347656), 'rotation':(0.047948, -80.437042, 0.047873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3441.91503906, 4834.97705078, 367.9290625), 'rotation':(0.045182, -80.438873, 0.045103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3440.98558594, 4840.49511719, 367.92484375), 'rotation':(0.042996, -80.43866, 0.04293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3439.12648438, 4851.53125, 367.91648438), 'rotation':(0.042996, -80.43866, 0.04293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3438.19679688, 4857.04931641, 367.91230469000004), 'rotation':(0.042996, -80.43866, 0.04293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3436.33765625, 4868.08496094, 367.9034375), 'rotation':(0.044949, -80.437378, 0.044874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3435.40820312, 4873.60302734, 367.89851562), 'rotation':(0.052435, -80.437378, 0.05234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3434.47851562, 4879.12109375, 367.89320312), 'rotation':(0.056021, -80.437378, 0.055908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3433.5490625, 4884.63867188, 367.88753906), 'rotation':(0.059928, -80.439087, 0.059813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3432.61960938, 4890.15673828, 367.88148437999996), 'rotation':(0.0635, -80.437378, 0.063373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3430.76050781, 4901.19287109, 367.86816405999997), 'rotation':(0.071, -80.439911, 0.070829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3453.60570312, 4714.25244141, 368.05484375), 'rotation':(-0.067719, 99.560204, -0.067871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3452.6877343799997, 4719.70068359, 368.04828125), 'rotation':(-0.068054, 99.562828, -0.068207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3451.77, 4725.14892578, 368.04175781), 'rotation':(-0.06839, 99.561951, -0.068542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3449.01683594, 4741.49414062, 368.02195312000003), 'rotation':(-0.069061, 99.560204, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3448.09886719, 4746.94238281, 368.0153125), 'rotation':(-0.069061, 99.562836, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3447.18117188, 4752.390625, 368.00867187999995), 'rotation':(-0.069061, 99.562836, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3445.34546875, 4763.28710938, 367.99542969000004), 'rotation':(-0.065338, 99.561958, -0.065491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3444.42773438, 4768.73535156, 367.9890625), 'rotation':(-0.063385, 99.561089, -0.063538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3442.59226562, 4779.63232422, 367.97707031), 'rotation':(-0.058228, 99.561066, -0.058319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3440.75632812, 4790.52929688, 367.96609375), 'rotation':(-0.053375, 99.561928, -0.053467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3421.42308594, 4905.29833984, 367.86109375), 'rotation':(-0.07309, 99.5616, -0.073273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3422.35230469, 4899.78222656, 367.86816405999997), 'rotation':(-0.07309, 99.5616, -0.073273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3424.2109375, 4888.74902344, 367.88148437999996), 'rotation':(-0.067444, 99.560944, -0.067566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3425.1403906200003, 4883.23242188, 367.88753906), 'rotation':(-0.063507, 99.562637, -0.06366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3426.99851562, 4872.19970703, 367.89851562), 'rotation':(-0.05603, 99.560913, -0.056122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3427.92796875, 4866.68310547, 367.9034375), 'rotation':(-0.048523, 99.562607, -0.048615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3428.8571875, 4861.16699219, 367.90800780999996), 'rotation':(-0.044952, 99.560898, -0.045013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3430.71582031, 4850.13378906, 367.91644531), 'rotation':(-0.042725, 99.562737, -0.042786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3431.645, 4844.6171875, 367.920625), 'rotation':(-0.042999, 99.56131, -0.04306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3432.57445312, 4839.10058594, 367.92484375), 'rotation':(-0.042999, 99.562737, -0.04306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3433.50367188, 4833.58398438, 367.92902344000004), 'rotation':(-0.042999, 99.560593, -0.04306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3216.89671875, 4760.13916016, 367.13617187999995), 'rotation':(-0.119446, -80.86261, -0.119965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3217.77027344, 4754.70751953, 367.12472656), 'rotation':(-0.118805, -80.863708, -0.119293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3219.51734375, 4743.84423828, 367.10195312), 'rotation':(-0.117188, -80.863037, -0.117676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3221.26441406, 4732.98095703, 367.07941406), 'rotation':(-0.117401, -80.863068, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3223.01148438, 4722.11767578, 367.05679688), 'rotation':(-0.119263, -80.861908, -0.119751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3224.75878906, 4711.25537109, 367.03339844000004), 'rotation':(-0.127747, -80.864044, -0.128326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3225.63232422, 4705.82373047, 367.02117187999994), 'rotation':(-0.131592, -80.861877, -0.132202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3227.37939453, 4694.96044922, 366.995625), 'rotation':(-0.139801, -80.861816, -0.140503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3229.12597656, 4684.09765625, 366.96878906), 'rotation':(-0.143921, -80.863953, -0.144653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3230.87304688, 4673.234375, 366.940625), 'rotation':(-0.149963, -80.861542, -0.150757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3211.7678125, 4792.02832031, 367.19773438), 'rotation':(-0.101166, -80.863953, -0.101532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3209.13550781, 4808.39501953, 367.22316406), 'rotation':(-0.085541, -80.862762, -0.085815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3208.25804688, 4813.85058594, 367.23066406), 'rotation':(-0.077576, -80.863861, -0.077789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3207.380625, 4819.30615234, 367.23789062000003), 'rotation':(-0.073639, -80.863556, -0.073822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3206.50316406, 4824.76171875, 367.24519531), 'rotation':(-0.077148, -80.862183, -0.077332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3204.74853516, 4835.67382812, 367.26152344), 'rotation':(-0.084534, -80.862915, -0.084778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3203.87109375, 4841.12988281, 367.27058594000005), 'rotation':(-0.091675, -80.865234, -0.091949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3202.99339844, 4846.58544922, 367.28035156), 'rotation':(-0.098785, -80.862122, -0.099121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3202.11597656, 4852.04150391, 367.29082030999996), 'rotation':(-0.106201, -80.862854, -0.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3201.23851562, 4857.49755859, 367.301875), 'rotation':(-0.113007, -80.865143, -0.113464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3200.36109375, 4862.95361328, 367.31355469000005), 'rotation':(-0.120728, -80.86203, -0.121246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3199.48363281, 4868.40917969, 367.32589844), 'rotation':(-0.127563, -80.862732, -0.128113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3222.45582031, 4671.88039062, 366.940625), 'rotation':(0.148038, 99.136055, 0.147274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3221.58226562, 4677.31201172, 366.95488280999996), 'rotation':(0.143919, 99.138206, 0.143198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3220.70898438, 4682.74365234, 366.96878906), 'rotation':(0.139807, 99.136009, 0.139125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3218.96214844, 4693.60644531, 366.995625), 'rotation':(0.135709, 99.135994, 0.135057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3218.08837891, 4699.03808594, 367.00855469000004), 'rotation':(0.131584, 99.13813, 0.130981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3217.21484375, 4704.46972656, 367.02117187999994), 'rotation':(0.127745, 99.135963, 0.127176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3216.34130859, 4709.90136719, 367.03339844000004), 'rotation':(0.123374, 99.138107, 0.122831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3215.46777344, 4715.33203125, 367.04527344), 'rotation':(0.119241, 99.135925, 0.118752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3212.84716797, 4731.62695312, 367.07941406), 'rotation':(0.117206, 99.136925, 0.116725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3211.09984375, 4742.49023438, 367.10195312), 'rotation':(0.117834, 99.135674, 0.117351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3209.35277344, 4753.35351562, 367.12472656), 'rotation':(0.119467, 99.134636, 0.118965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3208.47925781, 4758.78515625, 367.13617187999995), 'rotation':(0.119521, 99.139053, 0.119022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3192.82128906, 4856.14306641, 367.301875), 'rotation':(0.12073, 99.137207, 0.120215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3193.69873047, 4850.68701172, 367.29082030999996), 'rotation':(0.113026, 99.137932, 0.112581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3195.45386719, 4839.77539062, 367.27058594000005), 'rotation':(0.098771, 99.134789, 0.098438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3196.33128906, 4834.31933594, 367.26152344), 'rotation':(0.091661, 99.137856, 0.091379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3197.21117188, 4828.86523438, 367.25300781), 'rotation':(0.091661, 99.137856, 0.091379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3199.84082031, 4812.49609375, 367.23066406), 'rotation':(0.07365, 99.137199, 0.073457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3200.71826172, 4807.04052734, 367.22316406), 'rotation':(0.07757, 99.135628, 0.077361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3203.35058594, 4790.67382812, 367.19773438), 'rotation':(0.093533, 99.135681, 0.093228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3204.22802734, 4785.21875, 367.18828125), 'rotation':(0.093533, 99.135681, 0.093228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2987.21044922, 4723.1015625, 366.34242187999996), 'rotation':(-0.571289, -80.400848, -0.582764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2988.1315918, 4717.65039062, 366.28730469000004), 'rotation':(-0.574646, -80.401672, -0.586273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2990.89599609, 4701.29541016, 366.1196875), 'rotation':(-0.584625, -80.401489, -0.596649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2992.73901367, 4690.39257812, 366.00621094), 'rotation':(-0.59317, -80.402618, -0.60553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2993.66040039, 4684.94091797, 365.94902344), 'rotation':(-0.592224, -80.399658, -0.604584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2995.50341797, 4674.03759766, 365.83488280999995), 'rotation':(-0.588104, -80.398804, -0.600281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2996.42480469, 4668.5859375, 365.778125), 'rotation':(-0.586029, -80.401611, -0.598114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2999.18920898, 4652.23046875, 365.60917969), 'rotation':(-0.579742, -80.398987, -0.591583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3000.1105957, 4646.77882812, 365.55335937999996), 'rotation':(-0.577637, -80.402679, -0.589355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3001.03222656, 4641.32714844, 365.49761719), 'rotation':(-0.576477, -80.399017, -0.588165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3001.95361328, 4635.87546875, 365.44195312000005), 'rotation':(-0.576721, -80.401825, -0.588409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2982.75, 4749.49072266, 366.60441405999995), 'rotation':(-0.55249, -80.40094, -0.563232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2981.83447266, 4754.90625, 366.65710937999995), 'rotation':(-0.55249, -80.40094, -0.563232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2980.91918945, 4760.32275391, 366.70945312000003), 'rotation':(-0.545868, -80.402649, -0.556366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2980.00366211, 4765.73828125, 366.76125), 'rotation':(-0.539093, -80.400635, -0.549316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2977.25732422, 4781.98632812, 366.91449219000003), 'rotation':(-0.529144, -80.407288, -0.539001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2976.34228516, 4787.40185547, 366.96429687999995), 'rotation':(-0.524109, -80.399902, -0.533783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2975.42675781, 4792.81787109, 367.01320312), 'rotation':(-0.513885, -80.402527, -0.523163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2973.59619141, 4803.64892578, 367.10804687999996), 'rotation':(-0.493408, -80.402893, -0.501984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2972.68066406, 4809.06542969, 367.15410155999996), 'rotation':(-0.483154, -80.401428, -0.491333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2971.76538086, 4814.48095703, 367.19914062000004), 'rotation':(-0.472961, -80.403229, -0.480804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2970.84985352, 4819.89648438, 367.24324219000005), 'rotation':(-0.462738, -80.403381, -0.470245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2969.01928711, 4830.72900391, 367.32941406), 'rotation':(-0.447296, -80.402618, -0.454315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2993.54638672, 4634.45851562, 365.44203125), 'rotation':(0.576441, 99.600281, 0.564927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2992.62475586, 4639.91164062, 365.49769531), 'rotation':(0.57767, 99.598236, 0.566104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2991.703125, 4645.36476562, 365.55339844), 'rotation':(0.579746, 99.601013, 0.568106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2990.78125, 4650.81789062, 365.60929688), 'rotation':(0.581843, 99.598312, 0.570118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2988.93798828, 4661.72414062, 365.72171875), 'rotation':(0.586017, 99.598404, 0.574118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2987.09472656, 4672.63037109, 365.835), 'rotation':(0.590203, 99.59848, 0.578138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2985.2512207, 4683.53662109, 365.94921875), 'rotation':(0.593147, 99.597359, 0.580972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2984.32958984, 4688.98974609, 366.00644531), 'rotation':(0.591884, 99.602264, 0.579748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2983.40795898, 4694.44287109, 366.06335937999995), 'rotation':(0.584623, 99.598495, 0.572786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2982.48632812, 4699.89550781, 366.11992188), 'rotation':(0.581577, 99.602058, 0.569865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2981.56469727, 4705.34814453, 366.17613280999996), 'rotation':(0.577752, 99.598366, 0.566182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2980.64282227, 4710.80126953, 366.23199219), 'rotation':(0.574665, 99.598282, 0.563213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2978.79980469, 4721.70703125, 366.34269530999995), 'rotation':(0.56778, 99.600868, 0.556613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2961.52661133, 4823.89746094, 367.2865625), 'rotation':(0.447295, 99.597374, 0.440352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2962.44116211, 4818.48291016, 367.24332031), 'rotation':(0.452452, 99.598061, 0.445346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2963.35571289, 4813.06835938, 367.19921875), 'rotation':(0.462725, 99.596596, 0.455299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2966.09936523, 4796.82519531, 367.06121094), 'rotation':(0.493427, 99.597107, 0.484973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2967.01416016, 4791.41064453, 367.01332031), 'rotation':(0.503651, 99.599754, 0.494855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2967.92871094, 4785.99658203, 366.96445312000003), 'rotation':(0.513849, 99.596649, 0.504687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2969.7578125, 4775.16796875, 366.86402344000004), 'rotation':(0.529121, 99.604134, 0.519427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2970.67236328, 4769.75292969, 366.81296875), 'rotation':(0.532441, 99.598686, 0.522611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2972.50170898, 4758.92382812, 366.7096875), 'rotation':(0.539093, 99.599358, 0.529013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2973.41650391, 4753.50927734, 366.65734375), 'rotation':(0.545889, 99.597351, 0.53556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2757.99488281, 4686.08984375, 365.07148437999996), 'rotation':(-0.697784, -80.604004, -0.714935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2758.90257812, 4680.6015625, 365.00375), 'rotation':(-0.706909, -80.601196, -0.724518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2761.62523438, 4664.1371875, 364.79496094), 'rotation':(-0.735046, -80.603088, -0.754089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2762.53246094, 4658.64890625, 364.7234375), 'rotation':(-0.744171, -80.600281, -0.763702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2763.44019531, 4653.16015625, 364.65101562), 'rotation':(-0.753326, -80.6026, -0.773346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2764.34765625, 4647.67140625, 364.57785156), 'rotation':(-0.753357, -80.600525, -0.773376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2765.25537109, 4642.18261719, 364.50496094000005), 'rotation':(-0.742859, -80.6008, -0.762329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2768.88574219, 4620.22609375, 364.22324219), 'rotation':(-0.702454, -80.602631, -0.719849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2750.85791016, 4729.25341797, 365.57121094), 'rotation':(-0.617126, -80.604004, -0.630524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2749.94703125, 4734.76269531, 365.63101562), 'rotation':(-0.617126, -80.604004, -0.630524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2748.12523438, 4745.78173828, 365.74777344), 'rotation':(-0.593811, -80.604736, -0.606232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2747.21410156, 4751.29101562, 365.80570312000003), 'rotation':(-0.594269, -80.605316, -0.606689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2746.30322266, 4756.80029297, 365.86386719), 'rotation':(-0.596558, -80.604431, -0.6091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2744.48121094, 4767.81933594, 365.98070312000004), 'rotation':(-0.600067, -80.60437, -0.612732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2742.65894531, 4778.83837891, 366.09828125), 'rotation':(-0.603882, -80.604248, -0.61673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2740.83691406, 4789.85644531, 366.21660155999996), 'rotation':(-0.607666, -80.605042, -0.620667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2739.92601562, 4795.36572266, 366.2759375), 'rotation':(-0.608704, -80.603943, -0.621765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2749.57910156, 4684.72607422, 365.07179687999997), 'rotation':(0.688674, 99.399208, 0.672257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2750.48681641, 4679.23632812, 365.0040625), 'rotation':(0.697765, 99.395981, 0.680924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2751.39453125, 4673.74658203, 364.93542969000003), 'rotation':(0.706911, 99.398781, 0.689625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2752.30224609, 4668.25734375, 364.86578125), 'rotation':(0.716391, 99.399033, 0.698637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2754.11742188, 4657.2778125, 364.72371094000005), 'rotation':(0.735017, 99.39949, 0.716338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2755.93310547, 4646.29734375, 364.57804688), 'rotation':(0.753322, 99.399971, 0.7337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2756.84082031, 4640.80761719, 364.50515625), 'rotation':(0.753288, 99.398636, 0.733677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2757.74878906, 4635.316875, 364.43320312000003), 'rotation':(0.742872, 99.396698, 0.723786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2758.65673828, 4629.82617188, 364.36222655999995), 'rotation':(0.732702, 99.398949, 0.714134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2759.5646875, 4624.3359375, 364.29230469000004), 'rotation':(0.722531, 99.398674, 0.704477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2761.380625, 4613.35449219, 364.15539062000005), 'rotation':(0.702505, 99.398186, 0.685447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2763.19677734, 4602.37402344, 364.02234375), 'rotation':(0.682117, 99.396851, 0.666027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2764.10449219, 4596.88378906, 363.95660155999997), 'rotation':(0.67707, 99.397003, 0.661215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2731.51390625, 4793.97949219, 366.27597656), 'rotation':(0.608713, 99.393356, 0.595896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2732.42457031, 4788.47167969, 366.21667969000003), 'rotation':(0.608659, 99.395164, 0.595827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2733.33544922, 4782.96386719, 366.15742187999996), 'rotation':(0.607709, 99.39579, 0.594925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2734.24609375, 4777.45605469, 366.09835938), 'rotation':(0.605804, 99.39576, 0.593087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2735.15722656, 4771.94775391, 366.03949219000003), 'rotation':(0.603836, 99.39489, 0.591212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2736.97875, 4760.93164062, 365.92230469000003), 'rotation':(0.600005, 99.394791, 0.587549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2737.88941406, 4755.42382812, 365.86402344000004), 'rotation':(0.598147, 99.395599, 0.585765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2738.80029297, 4749.91601562, 365.80585937999996), 'rotation':(0.596508, 99.39473, 0.584177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2739.7109375, 4744.40820312, 365.74796875), 'rotation':(0.594322, 99.395508, 0.582094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2741.53246094, 4733.39257812, 365.63121094), 'rotation':(0.601159, 99.395119, 0.588649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2742.443125, 4727.88476562, 365.57144531), 'rotation':(0.601159, 99.395119, 0.588649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2743.35375, 4722.37744141, 365.51105469000004), 'rotation':(0.617067, 99.39547, 0.60389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2744.26464844, 4716.86962891, 365.44941406), 'rotation':(0.632434, 99.396309, 0.618582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2745.17503906, 4711.36230469, 365.38691406), 'rotation':(0.632434, 99.396309, 0.618582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3484.36425781, 4567.26953125, 367.90417969000003), 'rotation':(0.031801, -81.692657, 0.031758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3485.1794531200003, 4561.68703125, 367.90523437999997), 'rotation':(0.032027, -81.693176, 0.031999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3485.994375, 4556.1059375, 367.90839844000004), 'rotation':(0.032027, -81.693176, 0.031999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3488.43871094, 4539.36425781, 367.9178125), 'rotation':(0.050086, -81.692505, 0.049998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3489.25367188, 4533.78222656, 367.92167969), 'rotation':(0.050086, -81.692505, 0.049998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3491.69824219, 4517.03953125, 367.94246094000005), 'rotation':(0.122226, -81.692688, 0.121703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3492.51367188, 4511.45703125, 367.95441406), 'rotation':(0.158576, -81.692078, 0.157695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3494.1486718799997, 4500.25929688, 367.98304687999996), 'rotation':(0.392442, -80.534973, 0.387099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3496.58714844, 4483.55421875, 368.02507812000005), 'rotation':(0.076184, -81.693115, 0.075988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3497.401875, 4477.97507812, 368.03421875), 'rotation':(0.076184, -81.693115, 0.075988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3499.03125, 4466.81445312, 368.04476562), 'rotation':(0.015921, -81.693268, 0.015908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3499.8459375, 4461.23484375, 368.04703125), 'rotation':(0.015921, -81.693268, 0.015908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3501.47558594, 4450.07375, 368.05019531), 'rotation':(0.016181, -81.692688, 0.016177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3502.29027344, 4444.49316406, 368.05179688), 'rotation':(0.015921, -81.695374, 0.015916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3503.9196875, 4433.33351562, 368.04972655999995), 'rotation':(-0.101074, -81.694122, -0.10141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3504.7341406200003, 4427.75488281, 368.04179688), 'rotation':(-0.101074, -81.693451, -0.10144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3505.5490625, 4422.17382812, 368.031875), 'rotation':(-0.101074, -81.691833, -0.10141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3506.36375, 4416.59328125, 368.02191406), 'rotation':(-0.101074, -81.691833, -0.10141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3507.99316406, 4405.433125, 368.00148437999997), 'rotation':(-0.115997, -81.693024, -0.116455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3508.80785156, 4399.85203125, 367.99003905999996), 'rotation':(-0.145721, -81.692902, -0.146454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3509.62257812, 4394.27246094, 367.97691405999996), 'rotation':(-0.145721, -81.692902, -0.146454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3510.4375, 4388.691875, 367.96257812000005), 'rotation':(-0.175659, -81.692749, -0.176727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3511.25195312, 4383.11230469, 367.94578125), 'rotation':(-0.175659, -81.692749, -0.176727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3512.06664062, 4377.53273438, 367.92832031), 'rotation':(-0.205383, -81.692535, -0.206879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3512.88132812, 4371.95164062, 367.908125), 'rotation':(-0.220703, -81.692291, -0.222412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3480.4611718799997, 4594.0034375, 367.94886719000004), 'rotation':(-0.111877, -81.693451, -0.112305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3479.6440625, 4599.59960938, 367.96035156), 'rotation':(-0.116486, -81.694366, -0.116974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3478.82691406, 4605.19484375, 367.97226562000003), 'rotation':(-0.121368, -81.692078, -0.121857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3478.01, 4610.79054688, 367.98457031), 'rotation':(-0.125946, -81.692078, -0.126495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3477.193125, 4616.38671875, 367.99738281), 'rotation':(-0.130829, -81.694336, -0.131439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3476.37597656, 4621.98195312, 368.01054688), 'rotation':(-0.135406, -81.692017, -0.136047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3473.92480469, 4638.7690625, 368.05265625), 'rotation':(-0.144867, -81.691986, -0.145599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3473.10789062, 4644.36476562, 368.0671875), 'rotation':(-0.147369, -81.6922, -0.148132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3472.29125, 4649.95945312, 368.07828125), 'rotation':(-0.108429, -81.69458, -0.108826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3470.65796875, 4661.14550781, 368.0825), 'rotation':(0.007602, -81.693604, 0.007613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3469.02390625, 4672.33691406, 368.08101562), 'rotation':(0.007336, -81.693604, 0.007343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3504.4455468799997, 4370.71828125, 367.908125), 'rotation':(0.205377, 98.307465, 0.203919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3503.63085938, 4376.29835938, 367.92832031), 'rotation':(0.175652, 98.307266, 0.174572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3502.81640625, 4381.87695312, 367.94578125), 'rotation':(0.145729, 98.307098, 0.144995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3502.00195312, 4387.45554688, 367.96253906), 'rotation':(0.145729, 98.307098, 0.144995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3500.37304688, 4398.61476562, 367.99003905999996), 'rotation':(0.115977, 98.306946, 0.115519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3499.558125, 4404.19484375, 368.00148437999997), 'rotation':(0.10136, 98.306526, 0.101009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3498.74367188, 4409.7734375, 368.01191406), 'rotation':(0.101073, 98.306526, 0.100726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3497.92894531, 4415.35351562, 368.021875), 'rotation':(0.101059, 98.308151, 0.100711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3496.29957031, 4426.51367188, 368.04179688), 'rotation':(0.101073, 98.306526, 0.100726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3495.48511719, 4432.09132812, 368.04972655999995), 'rotation':(0.042443, 98.305832, 0.042376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3493.8559375, 4443.24953125, 368.05179688), 'rotation':(-0.016174, 98.306717, -0.016205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3492.2265625, 4454.4096875, 368.04863280999996), 'rotation':(-0.01593, 98.306717, -0.01593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3491.411875, 4459.98925781, 368.04707031), 'rotation':(-0.01593, 98.306717, -0.01593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3489.78246094, 4471.1484375, 368.04121094000004), 'rotation':(-0.076202, 98.30571, -0.076385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3488.96800781, 4476.72753906, 368.03421875), 'rotation':(-0.116608, 98.307037, -0.117065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3486.51878906, 4493.50046875, 367.99839844), 'rotation':(-0.392456, 99.465012, -0.397858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3484.89476562, 4504.62402344, 367.96742187999996), 'rotation':(-0.122223, 98.307304, -0.122742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3484.08007812, 4510.20507812, 367.95445312000004), 'rotation':(-0.122223, 98.307304, -0.122742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3481.63550781, 4526.94773438, 367.92664062000006), 'rotation':(-0.050079, 98.307083, -0.050171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3480.00609375, 4538.10789062, 367.91785156), 'rotation':(-0.032043, 98.304939, -0.032074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3479.19140625, 4543.68847656, 367.9146875), 'rotation':(-0.031799, 98.30735, -0.03183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3478.37671875, 4549.26855469, 367.9115625), 'rotation':(-0.032043, 98.306801, -0.032074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3462.223125, 4659.90578125, 368.0825), 'rotation':(-0.007355, 98.306389, -0.007355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3464.67382812, 4643.12011719, 368.06714844000004), 'rotation':(0.108416, 98.307777, 0.10801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3465.49097656, 4637.52296875, 368.05257812), 'rotation':(0.147375, 98.306152, 0.146623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3466.308125, 4631.92578125, 368.03820312000005), 'rotation':(0.144875, 98.308022, 0.144147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3467.1252343799997, 4626.32910156, 368.02414062), 'rotation':(0.140285, 98.307983, 0.13961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3467.94261719, 4620.73144531, 368.01050781), 'rotation':(0.140285, 98.307983, 0.13961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3468.76, 4615.13378906, 367.99730469), 'rotation':(0.135415, 98.305695, 0.134777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3469.57714844, 4609.53710938, 367.98457031), 'rotation':(0.130825, 98.307945, 0.130231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3470.39429688, 4603.93898438, 367.9721875), 'rotation':(0.125935, 98.305664, 0.125394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3472.02882812, 4592.74460938, 367.94882812000003), 'rotation':(0.116482, 98.305618, 0.116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3254.09351562, 4530.31054688, 366.10445312), 'rotation':(-0.404144, -80.756256, -0.409882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3255.00048828, 4524.73535156, 366.06457030999997), 'rotation':(-0.397186, -80.754639, -0.40271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3255.90771484, 4519.1596875, 366.0253125), 'rotation':(-0.3909, -80.756439, -0.396271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3256.8146875, 4513.58445312, 365.98675781), 'rotation':(-0.38736, -80.756744, -0.392639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3258.62890625, 4502.43359375, 365.91046875), 'rotation':(-0.382629, -80.755493, -0.387787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3260.44335938, 4491.28367188, 365.83539062000006), 'rotation':(-0.375549, -80.75473, -0.380493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3261.35058594, 4485.70800781, 365.79839844), 'rotation':(-0.372284, -80.755615, -0.377136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3263.16480469, 4474.55761719, 365.72546875), 'rotation':(-0.365479, -80.755707, -0.370178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3264.07177734, 4468.98242188, 365.68953125), 'rotation':(-0.361603, -80.755737, -0.366211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3264.97900391, 4463.40722656, 365.65390625), 'rotation':(-0.360077, -80.757202, -0.364655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3265.88597656, 4457.83203125, 365.61835937999996), 'rotation':(-0.362122, -80.755432, -0.366699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3268.60742188, 4441.10644531, 365.51046875), 'rotation':(-0.370422, -80.756897, -0.375244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3270.42164062, 4429.95703125, 365.43714844000004), 'rotation':(-0.374573, -80.75528, -0.379486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3271.32861328, 4424.38183594, 365.40023438), 'rotation':(-0.376495, -80.755859, -0.38147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3272.23583984, 4418.80664062, 365.363125), 'rotation':(-0.37677, -80.758057, -0.381775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3273.1428125, 4413.23144531, 365.32601562), 'rotation':(-0.37738, -80.755432, -0.382385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3274.05003906, 4407.65625, 365.28878906), 'rotation':(-0.379669, -80.756714, -0.384735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3274.95703125, 4402.08105469, 365.25144531), 'rotation':(-0.379669, -80.756714, -0.384735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3275.86402344, 4396.50585938, 365.21398437999994), 'rotation':(-0.381409, -80.755371, -0.386505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3276.77099609, 4390.93066406, 365.17636719), 'rotation':(-0.383148, -80.757324, -0.388306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3277.67822266, 4385.35546875, 365.13859375), 'rotation':(-0.384277, -80.755219, -0.389465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3278.58519531, 4379.78078125, 365.10070312000005), 'rotation':(-0.377869, -80.756348, -0.382904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3279.49267578, 4374.20507812, 365.06328125), 'rotation':(-0.36438, -80.755707, -0.369049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3281.306875, 4363.05421875, 364.99199219), 'rotation':(-0.337952, -80.759399, -0.341949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3282.21410156, 4357.47851562, 364.95835938), 'rotation':(-0.324768, -80.756195, -0.328461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3284.02832031, 4346.32714844, 364.89523438), 'rotation':(-0.29834, -80.75647, -0.301453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3284.93578125, 4340.75148438, 364.86570312000003), 'rotation':(-0.28479, -80.757416, -0.287628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3248.95679688, 4561.88132812, 366.34007812000004), 'rotation':(-0.426971, -80.754944, -0.43338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3247.21949219, 4572.5590625, 366.42039062000003), 'rotation':(-0.423492, -80.755005, -0.42981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3245.48242188, 4583.23679688, 366.49882812000004), 'rotation':(-0.413208, -80.755798, -0.419189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3242.87646484, 4599.25292969, 366.61320312000004), 'rotation':(-0.401886, -80.754852, -0.407562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3242.0078125, 4604.59132812, 366.64804688), 'rotation':(-0.379059, -80.756836, -0.384094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3240.27050781, 4615.26804688, 366.71136719000003), 'rotation':(-0.333008, -80.757416, -0.336884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3238.53369141, 4625.94484375, 366.76632812), 'rotation':(-0.287598, -80.755432, -0.290497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3237.66480469, 4631.28273438, 366.79066406), 'rotation':(-0.264374, -80.758911, -0.266846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3236.79613281, 4636.6215625, 366.81320312), 'rotation':(-0.241821, -80.756653, -0.243866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3276.52099609, 4339.38328125, 364.86574219), 'rotation':(0.298336, 99.24353, 0.295249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3273.79931641, 4356.11132812, 364.95835938), 'rotation':(0.337965, 99.243965, 0.333998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3271.98486328, 4367.26269531, 365.02695312000003), 'rotation':(0.36435, 99.243462, 0.359744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3269.26318359, 4383.98976562, 365.13859375), 'rotation':(0.383174, 99.245277, 0.378065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3268.35595703, 4389.56492188, 365.17636719), 'rotation':(0.381398, 99.242645, 0.376347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3267.44898438, 4395.14015625, 365.21398437999994), 'rotation':(0.379642, 99.244606, 0.374634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3266.54199219, 4400.71582031, 365.25148437999997), 'rotation':(0.377423, 99.243233, 0.372485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3264.72777344, 4411.86671875, 365.32605469000003), 'rotation':(0.376781, 99.244141, 0.371853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3263.82054688, 4417.441875, 365.36316406), 'rotation':(0.3765, 99.244141, 0.371584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3261.09912109, 4434.1675, 365.47398438), 'rotation':(0.370415, 99.244659, 0.365647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3260.19214844, 4439.74316406, 365.51050781), 'rotation':(0.36646, 99.24305, 0.361801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3259.28492188, 4445.31835938, 365.54667969), 'rotation':(0.362109, 99.242996, 0.357555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3257.47070312, 4456.46921875, 365.61835937999996), 'rotation':(0.360053, 99.244484, 0.355558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3255.65625, 4467.62011719, 365.68957030999997), 'rotation':(0.365524, 99.242561, 0.360883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3254.74925781, 4473.1953125, 365.72550780999995), 'rotation':(0.3684, 99.244331, 0.363694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3253.84203125, 4478.77050781, 365.76179687999996), 'rotation':(0.372279, 99.24437, 0.367477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3252.93480469, 4484.34617188, 365.7984375), 'rotation':(0.375524, 99.241875, 0.370618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3252.02783203, 4489.921875, 365.83546875), 'rotation':(0.378748, 99.244476, 0.373768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3249.30615234, 4506.6484375, 365.94859375), 'rotation':(0.387367, 99.24559, 0.382158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3248.39892578, 4512.22414062, 365.98679688), 'rotation':(0.390871, 99.24276, 0.385579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3246.58472656, 4523.37546875, 366.06464844000004), 'rotation':(0.404122, 99.242943, 0.398446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3228.38134766, 4635.25488281, 366.81320312), 'rotation':(0.230205, 99.243568, 0.228367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3230.11865234, 4624.57910156, 366.76632812), 'rotation':(0.26441, 99.241875, 0.261976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3232.72412109, 4608.56492188, 366.68078125), 'rotation':(0.332979, 99.244247, 0.329127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3234.46117188, 4597.88914062, 366.61324219), 'rotation':(0.379014, 99.244827, 0.374035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3235.32933594, 4592.55125, 366.57636719000004), 'rotation':(0.401916, 99.243462, 0.396315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3236.19800781, 4587.21289062, 366.53792969), 'rotation':(0.401916, 99.243462, 0.396315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3237.9353125, 4576.53613281, 366.45988280999995), 'rotation':(0.413199, 99.244202, 0.407278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3238.80394531, 4571.19726562, 366.42046875), 'rotation':(0.416949, 99.244911, 0.410911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3239.67236328, 4565.85839844, 366.38042969), 'rotation':(0.423458, 99.244118, 0.417237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3241.40966797, 4555.18164062, 366.29988281), 'rotation':(0.426784, 99.245033, 0.420453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3024.48046875, 4493.44578125, 364.0215625), 'rotation':(-0.576263, -81.132507, -0.587952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3025.34692383, 4487.88867188, 363.965), 'rotation':(-0.576782, -81.132507, -0.588501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3026.21337891, 4482.3315625, 363.90839844000004), 'rotation':(-0.576782, -81.132507, -0.588501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3027.9465332, 4471.21726562, 363.79511719000004), 'rotation':(-0.577393, -81.133057, -0.589111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3028.81298828, 4465.66015625, 363.73835937999996), 'rotation':(-0.580902, -81.131714, -0.592773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3030.54614258, 4454.54589844, 363.62382812000004), 'rotation':(-0.587646, -81.131592, -0.599792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3032.27905273, 4443.43210938, 363.50777344), 'rotation':(-0.601349, -81.131287, -0.614075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3033.14550781, 4437.875, 363.44921875), 'rotation':(-0.601349, -81.131287, -0.614075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3034.87866211, 4426.76125, 363.33089844), 'rotation':(-0.605743, -81.130768, -0.618652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3035.74511719, 4421.20410156, 363.27152344), 'rotation':(-0.605743, -81.130768, -0.618652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3036.61157227, 4415.64648438, 363.21203125), 'rotation':(-0.608032, -81.13028, -0.621033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3038.34448242, 4404.53273438, 363.09261719), 'rotation':(-0.610046, -81.132172, -0.623138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3040.07739258, 4393.41796875, 362.97273437999996), 'rotation':(-0.612305, -81.130646, -0.625488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3040.94384766, 4387.86085938, 362.91265625), 'rotation':(-0.613281, -81.130798, -0.626526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3041.81054688, 4382.30371094, 362.85246094), 'rotation':(-0.613251, -81.131409, -0.626495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3043.54345703, 4371.18945312, 362.73210937999994), 'rotation':(-0.609924, -81.128632, -0.623016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3044.41015625, 4365.63183594, 362.67246094), 'rotation':(-0.603119, -81.131348, -0.615936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3045.27661133, 4360.0746875, 362.61347656), 'rotation':(-0.596619, -81.132263, -0.609161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3046.14331055, 4354.51757812, 362.55515625), 'rotation':(-0.589874, -81.131622, -0.602142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3047.00976562, 4348.95996094, 362.49738281), 'rotation':(-0.586792, -81.131653, -0.598907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3047.8762207, 4343.4028125, 362.43980469), 'rotation':(-0.578613, -81.130188, -0.590393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3049.60961914, 4332.28757812, 362.32699219), 'rotation':(-0.546051, -81.131622, -0.556519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3050.47583008, 4326.73, 362.27292969), 'rotation':(-0.530273, -81.13446, -0.540131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3051.3425293, 4321.171875, 362.22050780999996), 'rotation':(-0.513824, -81.132233, -0.523102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3052.20922852, 4315.61375, 362.16972655999996), 'rotation':(-0.497711, -81.132507, -0.506439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3053.94238281, 4304.49851562, 362.07304688), 'rotation':(-0.465546, -81.134796, -0.473175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3054.80883789, 4298.94046875, 362.02722656), 'rotation':(-0.457397, -81.13327, -0.464722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3020.31811523, 4520.14160156, 364.29261719000004), 'rotation':(-0.574188, -81.130737, -0.585785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3019.4440918, 4525.7465625, 364.34921875), 'rotation':(-0.571655, -81.132629, -0.58316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3016.82226562, 4542.56101562, 364.51695312000004), 'rotation':(-0.560699, -81.132324, -0.571747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3015.07446289, 4553.77050781, 364.62707030999997), 'rotation':(-0.555603, -81.131287, -0.566437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3014.20068359, 4559.37546875, 364.68179688), 'rotation':(-0.552673, -81.133118, -0.563416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3013.32666016, 4564.98, 364.73652344000004), 'rotation':(-0.552673, -81.133118, -0.563416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3012.45263672, 4570.58496094, 364.79125), 'rotation':(-0.552979, -81.130615, -0.563721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3011.57885742, 4576.19042969, 364.84609375), 'rotation':(-0.552673, -81.133118, -0.563416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3010.70483398, 4581.79539062, 364.90125), 'rotation':(-0.55545, -81.131989, -0.566315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3009.83081055, 4587.39992188, 364.95683594), 'rotation':(-0.56015, -81.130188, -0.571198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3043.78564453, 4314.29882812, 362.16972655999996), 'rotation':(0.513821, 98.867767, 0.504673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3042.91894531, 4319.85640625, 362.22046875), 'rotation':(0.530303, 98.866318, 0.520553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3041.18579102, 4330.97117188, 362.32695312000004), 'rotation':(0.562459, 98.868675, 0.551496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3039.45263672, 4342.0859375, 362.43972656), 'rotation':(0.586782, 98.871078, 0.574853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3038.58618164, 4347.64304688, 362.49734375), 'rotation':(0.586788, 98.868355, 0.574866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3036.85327148, 4358.75734375, 362.6134375), 'rotation':(0.603126, 98.868645, 0.590533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3035.12011719, 4369.8715625, 362.73207031), 'rotation':(0.613289, 98.871124, 0.600265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3034.25341797, 4375.42820312, 362.7921875), 'rotation':(0.613255, 98.868591, 0.600224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3033.38696289, 4380.98535156, 362.85242187999995), 'rotation':(0.613255, 98.868591, 0.600224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3031.65405273, 4392.10007812, 362.97269531), 'rotation':(0.610086, 98.868294, 0.597195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3027.32177734, 4419.88378906, 363.27140625), 'rotation':(0.604724, 98.868462, 0.592059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3026.45532227, 4425.4409375, 363.33085938), 'rotation':(0.604724, 98.868462, 0.592059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3025.58886719, 4430.99804688, 363.39011719), 'rotation':(0.60135, 98.868713, 0.588822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3023.85595703, 4442.11132812, 363.50773438), 'rotation':(0.594582, 98.868561, 0.582347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3022.98950195, 4447.66796875, 363.56605469000004), 'rotation':(0.587649, 98.869896, 0.575686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3022.12304688, 4453.22460938, 363.62375), 'rotation':(0.580894, 98.868286, 0.569213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3021.2565918, 4458.78171875, 363.68121094), 'rotation':(0.580894, 98.868286, 0.569213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3019.5234375, 4469.895, 363.795), 'rotation':(0.577048, 98.8675, 0.565506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3017.79077148, 4481.00929688, 363.90832030999997), 'rotation':(0.576263, 98.867485, 0.564755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2999.65893555, 4597.29445312, 365.06824219000003), 'rotation':(0.562678, 98.869476, 0.551706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3000.53295898, 4591.68898438, 365.0125), 'rotation':(0.562685, 98.866997, 0.551716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3001.40698242, 4586.08351562, 364.95679687999996), 'rotation':(0.562678, 98.869476, 0.551706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3002.28125, 4580.47804688, 364.90121094), 'rotation':(0.560212, 98.86808, 0.549337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3003.15527344, 4574.87304688, 364.84605469), 'rotation':(0.555451, 98.867981, 0.544758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3004.02929688, 4569.26710938, 364.79121094000004), 'rotation':(0.552624, 98.866104, 0.542045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3004.90332031, 4563.66164062, 364.73648438), 'rotation':(0.552979, 98.869377, 0.542394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3006.65112305, 4552.45070312, 364.62703125), 'rotation':(0.552665, 98.86937, 0.542078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3008.39916992, 4541.24023438, 364.51691406), 'rotation':(0.555629, 98.867554, 0.544932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3009.27319336, 4535.63523438, 364.46136719000003), 'rotation':(0.560663, 98.867149, 0.549774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3010.1472168, 4530.02976562, 364.40539062000005), 'rotation':(0.566202, 98.869438, 0.555082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3011.02124023, 4524.42429688, 364.34914062), 'rotation':(0.566202, 98.869438, 0.555082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3011.89501953, 4518.81882812, 364.2925), 'rotation':(0.571694, 98.867874, 0.560369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2795.71851562, 4456.70117188, 362.30617187999997), 'rotation':(-0.689636, -80.613647, -0.706421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2796.635, 4451.15234375, 362.23847656), 'rotation':(-0.69162, -80.611786, -0.708466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2797.55152344, 4445.60351562, 362.17054687999996), 'rotation':(-0.692322, -80.613678, -0.709229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2799.38453125, 4434.50632812, 362.0346875), 'rotation':(-0.692322, -80.613678, -0.709229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2801.21753906, 4423.40867188, 361.89902344), 'rotation':(-0.685272, -80.612732, -0.701813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2802.13402344, 4417.85984375, 361.8315625), 'rotation':(-0.685272, -80.612732, -0.701813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2803.05054688, 4412.31101562, 361.76425781), 'rotation':(-0.680847, -80.612335, -0.697205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2803.96703125, 4406.7621875, 361.69738280999997), 'rotation':(-0.676025, -80.613953, -0.692139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2805.80003906, 4395.66453125, 361.564375), 'rotation':(-0.67392, -80.614044, -0.689911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2806.7165625, 4390.11570312, 361.498125), 'rotation':(-0.669617, -80.611328, -0.685394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2808.54957031, 4379.01757812, 361.36742187999994), 'rotation':(-0.653015, -80.612579, -0.66806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2810.3828125, 4367.91894531, 361.24042969000004), 'rotation':(-0.636169, -80.615692, -0.650421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2812.21558594, 4356.82078125, 361.11699219), 'rotation':(-0.618988, -80.616058, -0.632477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2814.04859375, 4345.723125, 360.99691406), 'rotation':(-0.598511, -80.615051, -0.611115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2816.79833984, 4329.07570312, 360.82203125), 'rotation':(-0.566559, -80.615234, -0.57785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2817.71484375, 4323.52640625, 360.76550781), 'rotation':(-0.566559, -80.615234, -0.57785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2818.63160156, 4317.9775, 360.70988280999995), 'rotation':(-0.550568, -80.616028, -0.561218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2820.46460938, 4306.87890625, 360.60144531), 'rotation':(-0.54248, -80.615967, -0.552826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2821.38109375, 4301.33007812, 360.54820312000004), 'rotation':(-0.538849, -80.614655, -0.549042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2822.29761719, 4295.78078125, 360.49507812), 'rotation':(-0.538849, -80.614655, -0.549042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2823.21410156, 4290.23195312, 360.4421875), 'rotation':(-0.531097, -80.616486, -0.541016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2824.13085938, 4284.68265625, 360.39), 'rotation':(-0.52359, -80.616638, -0.533203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2825.04736328, 4279.13375, 360.33824219), 'rotation':(-0.52359, -80.616638, -0.533203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2826.88037109, 4268.035625, 360.23625), 'rotation':(-0.512268, -80.61615, -0.521484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2828.71337891, 4256.9375, 360.13554688), 'rotation':(-0.512299, -80.617554, -0.521545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2791.32128906, 4483.32179688, 362.62972656), 'rotation':(-0.68338, -80.61264, -0.699829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2790.400625, 4488.89550781, 362.69648437999996), 'rotation':(-0.677734, -80.613586, -0.693909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2789.48023438, 4494.46875, 362.76269530999997), 'rotation':(-0.672211, -80.612915, -0.688141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2787.63916016, 4505.61570312, 362.89347655999995), 'rotation':(-0.661102, -80.615601, -0.676483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2785.79808594, 4516.76269531, 363.02210937999996), 'rotation':(-0.649933, -80.613434, -0.664795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2784.87792969, 4522.33398438, 363.08558594000004), 'rotation':(-0.650574, -80.530273, -0.665466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2783.03636719, 4533.48390625, 363.21210937999996), 'rotation':(-0.641083, -80.614258, -0.655548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2782.11572266, 4539.05761719, 363.2753125), 'rotation':(-0.641083, -80.614258, -0.655548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2780.27441406, 4550.20460938, 363.4015625), 'rotation':(-0.639771, -80.614288, -0.654175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2778.43335938, 4561.35203125, 363.52769530999996), 'rotation':(-0.639465, -80.610779, -0.65387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2788.22167969, 4449.77246094, 362.23859375), 'rotation':(0.689651, 99.386322, 0.673202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2789.13818359, 4444.223125, 362.17070312000004), 'rotation':(0.691625, 99.388222, 0.675077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2790.0546875, 4438.67429688, 362.10273437999996), 'rotation':(0.691625, 99.388222, 0.675077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2792.80445312, 4422.02734375, 361.89910155999996), 'rotation':(0.690122, 99.387878, 0.673641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2793.7209375, 4416.47804688, 361.83160155999997), 'rotation':(0.690122, 99.387878, 0.673641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2795.55394531, 4405.38039062, 361.69746094000004), 'rotation':(0.680867, 99.386139, 0.664822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2796.47046875, 4399.83105469, 361.63082031), 'rotation':(0.680867, 99.386139, 0.664822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2799.22021484, 4383.1840625, 361.43242188), 'rotation':(0.669604, 99.388695, 0.654085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2800.13671875, 4377.63378906, 361.36753905999996), 'rotation':(0.660944, 99.384865, 0.645829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2801.05322266, 4372.08445312, 361.30351562000004), 'rotation':(0.653034, 99.38739, 0.638269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2801.96996094, 4366.53515625, 361.24046875), 'rotation':(0.644094, 99.384483, 0.629724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2802.88648438, 4360.98632812, 361.17828125), 'rotation':(0.636171, 99.387016, 0.622169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2803.80296875, 4355.43703125, 361.11703125), 'rotation':(0.627565, 99.386841, 0.613938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2805.63623047, 4344.33835938, 360.99695312000006), 'rotation':(0.606692, 99.384842, 0.59394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2806.55273438, 4338.78953125, 360.93796875), 'rotation':(0.606692, 99.384842, 0.59394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2807.46949219, 4333.23921875, 360.87925780999996), 'rotation':(0.598523, 99.384933, 0.58611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2808.38597656, 4327.68992188, 360.82207030999996), 'rotation':(0.582519, 99.384605, 0.570782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2810.21923828, 4316.59179688, 360.70988280999995), 'rotation':(0.566578, 99.384766, 0.555452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2812.0525, 4305.4921875, 360.60148438), 'rotation':(0.550547, 99.383972, 0.540051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2813.88550781, 4294.3940625, 360.49511719000003), 'rotation':(0.542467, 99.384041, 0.53227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2814.80199219, 4288.8446875, 360.4421875), 'rotation':(0.53884, 99.385338, 0.528776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2816.63525391, 4277.74609375, 360.33828125), 'rotation':(0.531102, 99.383499, 0.521317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2817.55199219, 4272.19679688, 360.28691405999996), 'rotation':(0.523568, 99.383369, 0.514067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2818.46851562, 4266.6475, 360.23625), 'rotation':(0.516069, 99.383789, 0.506844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2819.385, 4261.09765625, 360.18582031), 'rotation':(0.512278, 99.383827, 0.503178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2820.30152344, 4255.54882812, 360.13554688), 'rotation':(0.512278, 99.383827, 0.503178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2774.62378906, 4532.09914062, 363.21214844), 'rotation':(0.641088, 99.385735, 0.626868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2777.38525391, 4515.379375, 363.02214844), 'rotation':(0.644667, 99.386444, 0.630282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2778.30566406, 4509.80617188, 362.958125), 'rotation':(0.649927, 99.386559, 0.635313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2779.22632812, 4504.23339844, 362.89355469000003), 'rotation':(0.655821, 99.384262, 0.640934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2780.14648438, 4498.660625, 362.82847655999996), 'rotation':(0.661074, 99.386818, 0.645957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2781.06689453, 4493.08742188, 362.7628125), 'rotation':(0.666968, 99.386963, 0.651567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2781.98753906, 4487.51464844, 362.6965625), 'rotation':(0.672227, 99.387085, 0.656595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2782.90796875, 4481.94140625, 362.62980469), 'rotation':(0.677746, 99.386406, 0.661856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2722.07421875, 4907.63623047, 367.58523438), 'rotation':(-0.674805, -80.962494, -0.690857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2722.93433594, 4902.22412109, 367.52066406), 'rotation':(-0.683807, -80.961304, -0.700287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2724.6540625, 4891.40136719, 367.39019530999997), 'rotation':(-0.692902, -80.960602, -0.709808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2725.51416016, 4885.98974609, 367.32402344), 'rotation':(-0.697235, -80.961609, -0.714355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2727.234375, 4875.16650391, 367.19105469000004), 'rotation':(-0.693756, -80.961334, -0.710724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2729.81494141, 4858.93017578, 366.99460938), 'rotation':(-0.672028, -80.959229, -0.687927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2730.67503906, 4853.51855469, 366.93054687999995), 'rotation':(-0.66507, -80.96283, -0.680634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2732.39501953, 4842.69433594, 366.80453125), 'rotation':(-0.65033, -80.962341, -0.665222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2733.25537109, 4837.28222656, 366.74261719000003), 'rotation':(-0.643372, -80.963318, -0.657928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2734.11546875, 4831.87011719, 366.68121094), 'rotation':(-0.639496, -80.96106, -0.6539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2716.97851562, 4939.70019531, 367.95773438), 'rotation':(-0.635254, -80.963074, -0.649475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2715.20140625, 4950.8828125, 368.07972656), 'rotation':(-0.61322, -80.962341, -0.626465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2714.31273438, 4956.47509766, 368.13816406), 'rotation':(-0.591217, -80.964569, -0.603516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2713.4240625, 4962.06640625, 368.19492188), 'rotation':(-0.569214, -80.963226, -0.580627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2710.75830078, 4978.84082031, 368.35753905999997), 'rotation':(-0.51712, -80.965515, -0.52652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2709.869375, 4984.43164062, 368.40722655999997), 'rotation':(-0.490234, -80.96521, -0.498657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2708.09253906, 4995.61425781, 368.49867187999996), 'rotation':(-0.43573, -80.966095, -0.442383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2706.31542969, 5006.796875, 368.57941406), 'rotation':(-0.408478, -80.966492, -0.414337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2704.53808594, 5017.97998047, 368.65011719), 'rotation':(-0.353973, -80.967224, -0.358368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2712.79541016, 4911.70068359, 367.64910155999996), 'rotation':(0.665752, 99.038742, 0.650417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2713.65550781, 4906.28955078, 367.58511719), 'rotation':(0.665752, 99.038742, 0.650417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2714.51539062, 4900.87792969, 367.52058594000005), 'rotation':(0.674795, 99.037483, 0.659049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2715.37548828, 4895.46728516, 367.45550781), 'rotation':(0.674795, 99.037483, 0.659049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2716.23535156, 4890.05566406, 367.39011719), 'rotation':(0.683811, 99.038704, 0.667633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2717.09546875, 4884.64501953, 367.32394531), 'rotation':(0.692888, 99.039391, 0.676282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2719.67554688, 4868.41064453, 367.12480469), 'rotation':(0.693756, 99.038666, 0.677103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2720.53564453, 4862.99951172, 367.05929688), 'rotation':(0.686454, 99.037674, 0.670153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2721.39550781, 4857.58740234, 366.99453125), 'rotation':(0.679221, 99.037498, 0.663256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2722.255625, 4852.17626953, 366.93046875), 'rotation':(0.671981, 99.03994, 0.656349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2723.11572266, 4846.76464844, 366.86710938), 'rotation':(0.665131, 99.037987, 0.649822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2724.8359375, 4835.94140625, 366.74257812), 'rotation':(0.650261, 99.036812, 0.635632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2726.55589844, 4825.11865234, 366.62003905999995), 'rotation':(0.639504, 99.038918, 0.625344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2696.11839844, 5016.64013672, 368.65011719), 'rotation':(0.340464, 99.033272, 0.336442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2697.00707031, 5011.04736328, 368.61574219), 'rotation':(0.353981, 99.032761, 0.349629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2698.78613281, 4999.86376953, 368.54035156), 'rotation':(0.408473, 99.033485, 0.402687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2700.56152344, 4988.68066406, 368.45425781), 'rotation':(0.435691, 99.033127, 0.429094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2701.45019531, 4983.08886719, 368.4071875), 'rotation':(0.462964, 99.034325, 0.455532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2702.33886719, 4977.49755859, 368.3575), 'rotation':(0.490216, 99.034767, 0.481879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2703.22753906, 4971.90625, 368.30511719000003), 'rotation':(0.517107, 99.034492, 0.507839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2704.11644531, 4966.31347656, 368.25066405999996), 'rotation':(0.557876, 99.034401, 0.547093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2706.78271484, 4949.53759766, 368.07964844), 'rotation':(0.591221, 99.035408, 0.579118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2707.67113281, 4943.9453125, 368.01933594), 'rotation':(0.613214, 99.037666, 0.600193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2952.36181641, 4933.84960938, 367.90125), 'rotation':(-0.175964, -80.950226, -0.177032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2953.22827148, 4928.40966797, 367.88390625), 'rotation':(-0.185577, -80.947449, -0.186768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2954.09448242, 4922.96972656, 367.86558594), 'rotation':(-0.204468, -80.950043, -0.205933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2954.96118164, 4917.52929688, 367.84632812), 'rotation':(-0.209229, -80.948456, -0.210754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2956.6940918, 4906.64941406, 367.80535155999996), 'rotation':(-0.242676, -80.949829, -0.244751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2957.56030273, 4901.21044922, 367.78261719), 'rotation':(-0.264923, -80.948059, -0.267426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2958.42700195, 4895.77099609, 367.75789062), 'rotation':(-0.287231, -80.947845, -0.2901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2960.15966797, 4884.89208984, 367.70273438), 'rotation':(-0.309784, -80.947632, -0.313141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2961.02587891, 4879.453125, 367.67222655999996), 'rotation':(-0.332336, -80.949646, -0.336212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2962.75878906, 4868.57470703, 367.60539062000004), 'rotation':(-0.376862, -80.946808, -0.381866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2944.73339844, 4981.7421875, 368.02183594), 'rotation':(-0.131958, -80.950317, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2943.8828125, 4987.08203125, 368.03433594), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2943.0324707, 4992.42236328, 368.04679688), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2942.18188477, 4997.76220703, 368.05921875), 'rotation':(-0.132141, -80.94986, -0.132751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2941.33129883, 5003.10205078, 368.07167969), 'rotation':(-0.132141, -80.94986, -0.132751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2940.48071289, 5008.44238281, 368.08417969000004), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2939.63012695, 5013.78222656, 368.09660155999995), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2938.77954102, 5019.12207031, 368.10910156), 'rotation':(-0.132172, -80.949554, -0.132782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2937.07861328, 5029.80175781, 368.13445312000005), 'rotation':(-0.136444, -80.949707, -0.137115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2935.37744141, 5040.48242188, 368.16054687999997), 'rotation':(-0.139069, -80.948425, -0.13974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2934.52661133, 5045.82226562, 368.17390625), 'rotation':(-0.141937, -80.950287, -0.14267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2933.67626953, 5051.16259766, 368.18742188), 'rotation':(-0.141937, -80.950287, -0.14267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2931.97509766, 5061.84228516, 368.21449219000004), 'rotation':(-0.14325, -80.949646, -0.143982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2954.33984375, 4867.22998047, 367.60535156), 'rotation':(0.354316, 99.052902, 0.34996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2953.47338867, 4872.66796875, 367.63972656), 'rotation':(0.332357, 99.053368, 0.32852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2952.60742188, 4878.10644531, 367.6721875), 'rotation':(0.309776, 99.050095, 0.306439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2951.74121094, 4883.54443359, 367.70269530999997), 'rotation':(0.28723, 99.052139, 0.284352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2950.875, 4888.98339844, 367.73125), 'rotation':(0.26495, 99.051933, 0.262497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2950.00878906, 4894.42138672, 367.75789062), 'rotation':(0.26495, 99.051933, 0.262497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2949.14233398, 4899.85986328, 367.78257812000004), 'rotation':(0.24269, 99.051727, 0.240622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2948.27636719, 4905.29785156, 367.8053125), 'rotation':(0.220417, 99.049988, 0.218733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2945.67724609, 4921.61572266, 367.86558594), 'rotation':(0.194838, 99.05262, 0.193522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2943.94482422, 4932.49316406, 367.90121094), 'rotation':(0.167005, 99.052437, 0.166036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2941.34594727, 4948.80957031, 367.94734375), 'rotation':(0.138141, 99.052284, 0.137484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2923.54443359, 5060.56396484, 368.21464844), 'rotation':(0.163146, 101.165352, 0.162224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2924.40673828, 5055.15771484, 368.20097655999996), 'rotation':(0.143448, 99.051857, 0.142737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2926.1081543, 5044.47558594, 368.17390625), 'rotation':(0.143448, 99.050354, 0.142738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2927.80981445, 5033.79394531, 368.14738280999995), 'rotation':(0.139076, 99.04969, 0.138399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2928.66064453, 5028.45263672, 368.13441406), 'rotation':(0.139076, 99.04969, 0.138399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2929.51123047, 5023.11181641, 368.12164062000005), 'rotation':(0.136454, 99.052155, 0.135808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2930.36206055, 5017.77050781, 368.1090625), 'rotation':(0.133332, 99.04966, 0.132723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2931.21264648, 5012.4296875, 368.09660155999995), 'rotation':(0.132164, 99.050949, 0.131567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2932.06323242, 5007.08886719, 368.08414062), 'rotation':(0.132164, 99.050949, 0.131567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2933.76464844, 4996.40722656, 368.05921875), 'rotation':(0.131966, 99.049683, 0.131356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2934.61547852, 4991.06640625, 368.04675781), 'rotation':(0.132137, 99.051102, 0.131534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2936.31689453, 4980.38427734, 368.02179687999995), 'rotation':(0.131966, 99.049683, 0.131356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2937.16748047, 4975.04345703, 368.00933594), 'rotation':(0.131959, 99.051102, 0.131356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3182.60667969, 4966.08447266, 367.56953125), 'rotation':(-0.116241, -80.07843, -0.116699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3184.48460938, 4955.35058594, 367.54746094), 'rotation':(-0.125854, -80.076111, -0.126404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3187.30054688, 4939.25, 367.50890625), 'rotation':(-0.141663, -80.078461, -0.142365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3188.23902344, 4933.8828125, 367.49535155999996), 'rotation':(-0.14502, -80.07843, -0.145782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3189.17796875, 4928.515625, 367.48152344000005), 'rotation':(-0.148071, -80.07843, -0.148834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3190.11695312, 4923.14892578, 367.46738281), 'rotation':(-0.151123, -80.077484, -0.151917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3191.05566406, 4917.78222656, 367.45292969), 'rotation':(-0.152527, -80.077087, -0.153351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3192.93310547, 4907.04785156, 367.42390625), 'rotation':(-0.152863, -80.078674, -0.153687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3173.23779297, 5019.64746094, 367.64039062000006), 'rotation':(-0.074463, -80.077606, -0.074646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3172.26246094, 5025.22314453, 367.64878905999996), 'rotation':(-0.083099, -80.078552, -0.083344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3170.31175781, 5036.375, 367.66859375), 'rotation':(-0.10144, -80.078491, -0.101807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3169.33667969, 5041.95117188, 367.68003905999996), 'rotation':(-0.119446, -80.0784, -0.119965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3168.36132812, 5047.52685547, 367.69242188), 'rotation':(-0.128815, -80.078369, -0.129364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3167.38597656, 5053.10302734, 367.705625), 'rotation':(-0.132904, -80.076324, -0.133545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3166.41064453, 5058.67919922, 367.71980469000005), 'rotation':(-0.139374, -80.078278, -0.140045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3164.45947266, 5069.83056641, 367.75195312000005), 'rotation':(-0.164062, -80.078156, -0.165009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3163.484375, 5075.40673828, 367.76988280999996), 'rotation':(-0.176117, -80.078064, -0.177185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3161.53344727, 5086.55908203, 367.80941406), 'rotation':(-0.20047, -80.078796, -0.201874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3160.55859375, 5092.13427734, 367.83109375), 'rotation':(-0.225189, -80.077728, -0.226959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3159.58325195, 5097.70996094, 367.85367188), 'rotation':(-0.225189, -80.077728, -0.226959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3184.53394531, 4905.58837891, 367.42390625), 'rotation':(0.152518, 99.922928, 0.151712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3183.59496094, 4910.95800781, 367.4384375), 'rotation':(0.152539, 99.921303, 0.151729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3177.95996094, 4943.17431641, 367.52230469), 'rotation':(0.135169, 99.921631, 0.134532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3177.02074219, 4948.54345703, 367.53527344), 'rotation':(0.125839, 99.921608, 0.125293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3176.08154297, 4953.91259766, 367.5475), 'rotation':(0.116229, 99.921547, 0.115756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3175.14234375, 4959.28173828, 367.55894530999996), 'rotation':(0.106612, 99.921509, 0.106226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3174.203125, 4964.65087891, 367.56957030999996), 'rotation':(0.106612, 99.921509, 0.106226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3173.26390625, 4970.02001953, 367.579375), 'rotation':(0.096702, 99.92067, 0.096384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3172.32470703, 4975.38964844, 367.58835938), 'rotation':(0.087379, 99.923744, 0.087123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3171.38574219, 4980.75830078, 367.59648438), 'rotation':(0.078062, 99.921417, 0.077861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3152.15917969, 5090.67480469, 367.83113281), 'rotation':(0.231509, 99.92231, 0.22964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3153.1340332, 5085.1015625, 367.80949219), 'rotation':(0.213157, 99.922173, 0.211573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3154.10913086, 5079.52832031, 367.7890625), 'rotation':(0.200487, 99.922073, 0.199088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3155.08398438, 5073.95507812, 367.76992187999997), 'rotation':(0.188445, 99.922005, 0.187216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3157.03393555, 5062.80810547, 367.7353125), 'rotation':(0.164047, 99.920959, 0.163111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3158.00854492, 5057.23486328, 367.71988281), 'rotation':(0.151384, 99.924286, 0.150595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3158.98388672, 5051.66113281, 367.70570312), 'rotation':(0.139356, 99.92173, 0.138683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3163.85839844, 5023.79394531, 367.64886719000003), 'rotation':(0.092433, 99.921494, 0.092148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3409.4340625, 5024.67578125, 367.73875), 'rotation':(-0.011871, -80.185944, -0.011871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3410.40039062, 5019.09082031, 367.73753905999996), 'rotation':(0.01922, -80.184387, 0.019207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3411.36644531, 5013.50439453, 367.73777344), 'rotation':(0.01922, -80.184387, 0.019207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3412.33300781, 5007.91796875, 367.74023437999995), 'rotation':(0.050407, -80.185791, 0.050326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3413.2990625, 5002.33251953, 367.74523437999994), 'rotation':(0.050687, -80.185791, 0.050606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3414.2653906200003, 4996.74804688, 367.75023437999994), 'rotation':(0.050407, -80.185791, 0.050326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3416.19773438, 4985.57714844, 367.76023438), 'rotation':(0.054361, -80.184814, 0.054259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3417.1640625, 4979.99169922, 367.76550781), 'rotation':(0.054361, -80.184814, 0.054259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3418.13039062, 4974.40625, 367.77101562), 'rotation':(0.062148, -80.185303, 0.062011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3419.09667969, 4968.82080078, 367.77714844), 'rotation':(0.070126, -80.185272, 0.069953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3420.06296875, 4963.23583984, 367.78367188), 'rotation':(0.070126, -80.185272, 0.069953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3421.0290625, 4957.65039062, 367.790625), 'rotation':(0.077734, -80.185242, 0.077518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3421.99535156, 4952.06494141, 367.79816406), 'rotation':(0.077734, -80.185242, 0.077518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3422.96140625, 4946.47949219, 367.80589844), 'rotation':(0.081614, -80.186035, 0.081376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3423.92773438, 4940.89453125, 367.81398437999997), 'rotation':(0.081908, -80.185272, 0.081678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3404.79808594, 5051.47314453, 367.74433594000004), 'rotation':(-0.012054, -80.18573, -0.012085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3402.89378906, 5062.48242188, 367.75066405999996), 'rotation':(-0.025482, -80.184998, -0.025482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3401.94164062, 5067.98632812, 367.75582031), 'rotation':(-0.053192, -80.186005, -0.053284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3399.08445312, 5084.50097656, 367.78304688), 'rotation':(-0.108215, -80.184265, -0.108612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3397.18015625, 5095.51025391, 367.80664062000005), 'rotation':(-0.121826, -80.185181, -0.122345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3395.27585938, 5106.51855469, 367.83144531), 'rotation':(-0.129761, -80.187042, -0.130341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3394.32347656, 5112.02246094, 367.84453125), 'rotation':(-0.134888, -80.184784, -0.135529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3393.37109375, 5117.52734375, 367.858125), 'rotation':(-0.14032, -80.184753, -0.140991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3392.41871094, 5123.03076172, 367.87199219), 'rotation':(-0.142822, -80.182648, -0.143524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3391.4665625, 5128.53564453, 367.88589844), 'rotation':(-0.142792, -80.186188, -0.143524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3390.51441406, 5134.03955078, 367.89984375), 'rotation':(-0.142822, -80.185272, -0.143524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3415.52660156, 4939.44287109, 367.81398437999997), 'rotation':(-0.081604, 99.8162, -0.081848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3413.59375, 4950.61523438, 367.798125), 'rotation':(-0.070129, 99.814713, -0.070282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3411.66113281, 4961.78808594, 367.78367188), 'rotation':(-0.062134, 99.814705, -0.062286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3410.69484375, 4967.37451172, 367.77714844), 'rotation':(-0.062134, 99.814705, -0.062286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3409.72828125, 4972.9609375, 367.77101562), 'rotation':(-0.054352, 99.81469, -0.054443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3408.76171875, 4978.54736328, 367.76550781), 'rotation':(-0.050415, 99.814224, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3407.79539062, 4984.13378906, 367.76023438), 'rotation':(-0.050415, 99.814224, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3406.82910156, 4989.71972656, 367.75523438), 'rotation':(-0.050415, 99.815002, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3405.86253906, 4995.30664062, 367.75023437999994), 'rotation':(-0.05069, 99.814224, -0.050781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3404.89625, 5000.89257812, 367.74519531), 'rotation':(-0.050415, 99.816444, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3403.9299218799997, 5006.47851562, 367.74019531), 'rotation':(-0.019226, 99.813049, -0.019226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3402.96335938, 5012.06640625, 367.73777344), 'rotation':(0.011878, 99.815918, 0.011869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3401.99683594, 5017.65332031, 367.73753905999996), 'rotation':(0.011878, 99.815918, 0.011869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3401.03050781, 5023.23974609, 367.73875), 'rotation':(0.011871, 99.814049, 0.01187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3382.11375, 5132.58837891, 367.89984375), 'rotation':(0.142812, 99.81472, 0.142104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3383.06566406, 5127.08544922, 367.8859375), 'rotation':(0.142806, 99.816437, 0.142096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3384.0178125, 5121.58203125, 367.87199219), 'rotation':(0.142812, 99.81472, 0.142104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3384.96972656, 5116.07910156, 367.85816406), 'rotation':(0.142812, 99.81382, 0.142098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3385.921875, 5110.57519531, 367.84453125), 'rotation':(0.140306, 99.815239, 0.139629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3390.68210938, 5083.05859375, 367.78304688), 'rotation':(0.121844, 99.815315, 0.121322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3391.63402344, 5077.55566406, 367.77253906), 'rotation':(0.10819, 99.815186, 0.107782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3392.5861718799997, 5072.05175781, 367.76359375), 'rotation':(0.10819, 99.815186, 0.107782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3393.53859375, 5066.54736328, 367.75582031), 'rotation':(0.08048, 99.814056, 0.080259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3394.49046875, 5061.04443359, 367.75066405999996), 'rotation':(0.053173, 99.81559, 0.053089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3396.39453125, 5050.03710938, 367.744375), 'rotation':(0.02547, 99.815544, 0.025455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.265625, 4862.27978516, 365.21335938), 'rotation':(-0.595245, -89.342529, -0.607697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2209.32835938, 4856.77441406, 365.15648437999994), 'rotation':(-0.595245, -89.342529, -0.607697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.45359375, 4845.76318359, 365.04171875), 'rotation':(-0.600616, -89.342438, -0.613312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.51609375, 4840.25830078, 364.98398438), 'rotation':(-0.605835, -89.342346, -0.618744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.57882812, 4834.75292969, 364.92574219), 'rotation':(-0.608246, -89.338287, -0.621277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.7040625, 4823.7421875, 364.80878906), 'rotation':(-0.613434, -89.341736, -0.626678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.8293750000003, 4812.73095703, 364.69113281), 'rotation':(-0.616516, -89.341675, -0.629883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.8918750000003, 4807.22558594, 364.63199219), 'rotation':(-0.616516, -89.341675, -0.629883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2210.01710938, 4796.21533203, 364.51316406), 'rotation':(-0.617218, -89.342163, -0.630615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2210.07984375, 4790.70947266, 364.45363281), 'rotation':(-0.617218, -89.342163, -0.630615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.26757812, 4774.19238281, 364.2784375), 'rotation':(-0.590942, -89.342773, -0.60321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.33054688, 4768.68652344, 364.2215625), 'rotation':(-0.58197, -89.342926, -0.593903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.4557812499997, 4757.67529297, 364.11), 'rotation':(-0.564636, -89.343262, -0.575867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.5182812499997, 4752.16894531, 364.0553125), 'rotation':(-0.564636, -89.343262, -0.575867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.9582812500003, 4889.32763672, 365.49027344), 'rotation':(-0.59021, -89.342285, -0.602478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.89382812, 4894.98730469, 365.54886719), 'rotation':(-0.59021, -89.342285, -0.602478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.76515625, 4906.30517578, 365.66761719000004), 'rotation':(-0.598267, -89.342102, -0.61084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2208.70070312, 4911.96484375, 365.7275), 'rotation':(-0.606628, -89.341919, -0.619568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2208.63648438, 4917.62402344, 365.78824219), 'rotation':(-0.614441, -89.343262, -0.627716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.57375, 4923.22167969, 365.84832030999996), 'rotation':(-0.650299, -87.390076, -0.665192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2208.44335938, 4934.60009766, 365.9690625), 'rotation':(-0.607239, -89.342621, -0.620209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.37890625, 4940.25878906, 366.02796875), 'rotation':(-0.599884, -89.342712, -0.612549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.25046875, 4951.57666016, 366.14347655999995), 'rotation':(-0.576904, -89.343262, -0.588623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.1215625, 4962.89404297, 366.25578125), 'rotation':(-0.562073, -89.340942, -0.573181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2207.99289062, 4974.21191406, 366.36617187999997), 'rotation':(-0.558105, -89.344452, -0.569061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2202.0559375000003, 4746.57177734, 364.00140625), 'rotation':(0.564645, 90.656731, 0.553597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.993125, 4752.07910156, 364.05539062), 'rotation':(0.573312, 90.656906, 0.561922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.86789062, 4763.09375, 364.16550781), 'rotation':(0.582028, 90.657112, 0.570288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.80539062, 4768.60107422, 364.22167969000003), 'rotation':(0.590927, 90.659485, 0.578838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.74242188, 4774.10839844, 364.27855469), 'rotation':(0.599595, 90.657433, 0.587143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.6171875, 4785.12255859, 364.3946875), 'rotation':(0.617196, 90.657806, 0.604013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.42921875, 4801.64355469, 364.57292969), 'rotation':(0.616507, 90.65831, 0.60334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.30398438, 4812.65771484, 364.69136719), 'rotation':(0.613467, 90.658295, 0.600435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.17875, 4823.671875, 364.8090625), 'rotation':(0.610182, 90.65818, 0.597284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.1159374999997, 4829.17822266, 364.86773437999994), 'rotation':(0.608242, 90.655746, 0.595435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2201.0534374999997, 4834.68505859, 364.92605469), 'rotation':(0.605824, 90.657669, 0.593123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.99070312, 4840.19238281, 364.98429688), 'rotation':(0.600626, 90.659096, 0.588133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.9284374999997, 4845.69921875, 365.04207031), 'rotation':(0.595189, 90.65741, 0.582927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.80320312, 4856.71289062, 365.156875), 'rotation':(0.590183, 90.65731, 0.578117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.74046875, 4862.21972656, 365.21375), 'rotation':(0.590183, 90.65731, 0.578117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.4678125, 4974.11816406, 366.36621094000003), 'rotation':(0.558313, 90.657478, 0.547515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.5964062499997, 4962.8046875, 366.25589844), 'rotation':(0.558108, 90.657524, 0.547326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.66085938, 4957.14794922, 366.20011719), 'rotation':(0.562063, 90.656441, 0.551111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.91796875, 4934.52148438, 365.96925781), 'rotation':(0.59982, 90.657211, 0.58736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.04664062, 4923.20800781, 365.84917969), 'rotation':(0.614997, 90.660126, 0.601898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.1753125, 4911.89501953, 365.7278125), 'rotation':(0.614423, 90.658226, 0.601362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.2395312500003, 4906.23730469, 365.66789062000004), 'rotation':(0.606637, 90.658096, 0.593898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.30398438, 4900.58056641, 365.60828125), 'rotation':(0.606637, 90.658096, 0.593898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.368125, 4894.92333984, 365.54917969), 'rotation':(0.598208, 90.657867, 0.585835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.43265625, 4889.26611328, 365.490625), 'rotation':(0.598208, 90.657867, 0.585835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2041.44273438, 3895.1284375, 356.17269531), 'rotation':(-0.89801, -80.745819, -0.926514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2038.72359375, 3911.8410937500003, 356.43882812000004), 'rotation':(-0.903107, -80.745178, -0.931946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2037.81726562, 3917.41210938, 356.52882812), 'rotation':(-0.912781, -80.744843, -0.9422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2036.0045312500001, 3928.55445312, 356.71183594), 'rotation':(-0.932037, -80.744629, -0.962738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2035.0982812500001, 3934.12546875, 356.80476562), 'rotation':(-0.942047, -80.745117, -0.973419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2034.19179688, 3939.69625, 356.89867187999994), 'rotation':(-0.951691, -80.743591, -0.983704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2033.28554688, 3945.26734375, 356.99351562000004), 'rotation':(-0.961639, -80.743256, -0.994354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2032.38039062, 3950.8307812499997, 357.08898437999994), 'rotation':(-0.941589, -80.522217, -0.972931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2031.47304688, 3956.40820312, 357.18382812000004), 'rotation':(-0.961182, -80.743958, -0.993835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2030.566875, 3961.97804688, 357.27675781), 'rotation':(-0.961182, -80.743958, -0.993835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2028.754375, 3973.11867188, 357.45710937999996), 'rotation':(-0.901154, -80.745911, -0.929871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':2, 'location':(2027.8483593800001, 3978.68820312, 357.54429688), 'rotation':(-0.901154, -80.745911, -0.929871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':2, 'location':(2032.1215625, 3899.32859375, 356.26121094), 'rotation':(0.897999, 99.254189, 0.870175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2030.3090625, 3910.46945312, 356.43875), 'rotation':(0.912759, 99.253914, 0.884027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2028.49648438, 3921.6106250000003, 356.61976562), 'rotation':(0.932068, 99.255745, 0.902106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2027.5900781199998, 3927.18117188, 356.71171875), 'rotation':(0.942026, 99.256081, 0.911421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2026.6838281199998, 3932.75171875, 356.80464844), 'rotation':(0.951637, 99.256012, 0.920407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2024.8713281199998, 3943.8928125, 356.9934375), 'rotation':(0.971287, 99.255836, 0.938773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2023.96523438, 3949.46265625, 357.08902344), 'rotation':(0.961178, 99.256821, 0.929318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2022.1530468800001, 3960.60179688, 357.27664062), 'rotation':(0.931071, 99.255028, 0.901164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2020.3409375, 3971.74148438, 357.45695312000004), 'rotation':(0.87117, 99.253159, 0.844972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n ]\nTown13 = [\n {'tilex':5, 'tiley':2, 'location':(2649.8596093799997, 2022.97703125, 173.62414062), 'rotation':(0.493317, 90.635384, 0.484885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2657.85570312, 2006.53085938, 173.47964843999998), 'rotation':(-0.507233, -89.36438, -0.516296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2657.79515625, 2012.0345312499999, 173.52808593999998), 'rotation':(-0.503723, -89.364441, -0.512634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2657.7346093799997, 2017.5383593800002, 173.57617188), 'rotation':(-0.500214, -89.364471, -0.509003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2657.61351562, 2028.54578125, 173.67142578), 'rotation':(-0.493317, -89.364624, -0.501862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.27050781, 2073.4609375, 174.04148438), 'rotation':(0.433287, 90.633385, 0.426766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.20921875, 2079.015625, 174.08351562), 'rotation':(0.427877, 90.634163, 0.421523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.96460938, 2101.2317187500003, 174.24759766), 'rotation':(0.403186, 90.633789, 0.397554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.53636719, 2140.1106250000003, 174.50421875), 'rotation':(0.349549, 90.633698, 0.345302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.4140625, 2151.2200000000003, 174.57169922), 'rotation':(0.332808, 90.633469, 0.328962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.22949219, 2162.32515625, 174.63564452999998), 'rotation':(0.315917, 90.633263, 0.312456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2656.9060156200003, 2095.7634375, 174.20730468999997), 'rotation':(-0.419769, -89.365967, -0.425934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.84472656, 2101.31710938, 174.24757812), 'rotation':(-0.419769, -89.365967, -0.425934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2656.72242188, 2112.42507812, 174.32484375), 'rotation':(-0.403198, -89.366211, -0.408905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.66113281, 2117.97953125, 174.36234375), 'rotation':(-0.386719, -89.36499, -0.391968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2656.47753906, 2134.6418750000003, 174.46931641), 'rotation':(-0.362, -89.366455, -0.366608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.35546875, 2145.75023438, 174.53839843999998), 'rotation':(-0.349518, -89.366333, -0.353821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.29417969, 2151.30492188, 174.57167969), 'rotation':(-0.340912, -89.366394, -0.345001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.24023438, 2167.9678125, 174.66625), 'rotation':(-0.315918, -89.366699, -0.319427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.68285156, 2205.8559375, 174.85730468999998), 'rotation':(0.257013, 90.632904, 0.254724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.609375, 2217.00828125, 174.90634766), 'rotation':(0.234446, 90.630646, 0.232533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.6013281200003, 2222.58351562, 174.92947266), 'rotation':(0.228743, 90.632446, 0.226927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.566875, 2228.1575000000003, 174.95201172), 'rotation':(0.228743, 90.632446, 0.226927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.50539062, 2233.73265625, 174.97427734000001), 'rotation':(0.228893, 90.632431, 0.22707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.3825781200003, 2244.88234375, 175.01775390999998), 'rotation':(0.204892, 90.632561, 0.203434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.25976562, 2256.0325000000003, 175.05716797000002), 'rotation':(0.188827, 90.632439, 0.187578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.19847656, 2261.60789062, 175.07556641), 'rotation':(0.172968, 90.630653, 0.17192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2655.44703125, 2228.24148438, 174.95199218999997), 'rotation':(-0.234467, -89.369354, -0.236359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2655.07859375, 2261.691875, 175.07554688), 'rotation':(-0.188812, -89.367554, -0.190063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2646.77929688, 2299.64039062, 175.18417968999998), 'rotation':(0.120881, 90.631805, 0.120369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2646.53417969, 2321.92164062, 175.23117188), 'rotation':(0.109549, 90.630554, 0.109131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2646.41136719, 2333.06203125, 175.2521875), 'rotation':(0.100062, 90.630898, 0.099709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2646.10472656, 2360.91453125, 175.29404297000002), 'rotation':(0.068056, 90.630806, 0.067898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.536875, 2310.86476562, 175.209375), 'rotation':(-0.12088, -89.368195, -0.121399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.35304688, 2327.5759375, 175.24179688), 'rotation':(-0.109558, -89.369446, -0.109985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.23023438, 2338.71578125, 175.26189452999998), 'rotation':(-0.100067, -89.36911, -0.100433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.16894531, 2344.28609375, 175.27091797), 'rotation':(-0.093506, -89.369141, -0.093811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.98484375, 2360.9978125, 175.29404297000002), 'rotation':(-0.074646, -89.369171, -0.074829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.92359375, 2366.56835938, 175.30042969), 'rotation':(-0.068054, -89.369202, -0.068207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.55957031, 2409.99851562, 175.33064453), 'rotation':(0.008463, 90.631073, 0.008455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.50292969, 2415.53515625, 175.33148438), 'rotation':(0.008463, 90.63105, 0.008461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.441875, 2421.07375, 175.33228516), 'rotation':(0.008463, 90.63105, 0.008461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.38085938, 2426.61230469, 175.33310547000002), 'rotation':(0.008463, 90.631073, 0.008455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.31984375, 2432.15085938, 175.33394531000002), 'rotation':(0.008463, 90.631073, 0.008455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.25878906, 2437.6896875, 175.33474609), 'rotation':(0.008463, 90.63105, 0.008461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.19773438, 2443.22828125, 175.33556640999998), 'rotation':(0.0, 90.633072, 4e-06), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.01488281, 2459.84179688, 175.33376952999998), 'rotation':(-0.025116, 90.630775, -0.025116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.95386719, 2465.38039062, 175.33136718999998), 'rotation':(-0.024963, 90.63076, -0.024994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.8928125, 2470.91894531, 175.32892578), 'rotation':(-0.024963, 90.630783, -0.024994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.83179688, 2476.4575, 175.32650390999999), 'rotation':(-0.025116, 90.630775, -0.025116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.77101562, 2481.99632812, 175.32408203), 'rotation':(-0.028656, 90.631248, -0.028687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.64890625, 2493.0725, 175.31871094), 'rotation':(-0.03595, 90.631233, -0.036011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2644.40476562, 2515.2265625, 175.30220702999998), 'rotation':(-0.05426, 90.630066, -0.054352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.34375, 2520.76488281, 175.29708984), 'rotation':(-0.054077, 90.632675, -0.054169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.22167969, 2531.84132812, 175.28644531), 'rotation':(-0.056366, 90.630913, -0.056458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.0388281200003, 2548.45703125, 175.26919922000002), 'rotation':(-0.064819, 90.63092, -0.064972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.7946875, 2570.61109375, 175.24294922), 'rotation':(-0.071259, 90.632179, -0.071411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.26125, 2426.6950781200003, 175.33310547000002), 'rotation':(-0.008453, -89.368927, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.20019531, 2432.23363281, 175.33394531000002), 'rotation':(-0.008453, -89.368927, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2653.078125, 2443.31078125, 175.33556640999998), 'rotation':(-0.008453, -89.367371, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.01710938, 2448.84863281, 175.33595703), 'rotation':(-0.008453, -89.367371, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.95605469, 2454.38648438, 175.33546875), 'rotation':(7e-06, -89.368988, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.83398438, 2465.46289062, 175.33136718999998), 'rotation':(0.025087, -89.369202, 0.02508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.5290625, 2493.1540625, 175.31873047000002), 'rotation':(0.028673, -89.368713, 0.028633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.16285156, 2526.38523438, 175.29183593999997), 'rotation':(0.054088, -89.36731, 0.053984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.1017968799997, 2531.92335938, 175.28644531), 'rotation':(0.054088, -89.36731, 0.053984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2651.98, 2543.00046875, 175.27515625), 'rotation':(0.060591, -89.36908, 0.060452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2651.796875, 2559.61570312, 175.25646484), 'rotation':(0.064812, -89.369049, 0.064666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.29515625, 2605.99171875, 175.19671875), 'rotation':(-0.080383, 90.630814, -0.080597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.2534375, 2619.76, 175.17726562), 'rotation':(-0.082764, 90.63166, -0.083008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.00828125, 2642.0121875, 175.14492188), 'rotation':(-0.0849, 90.629608, -0.085175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.88234375, 2653.13746094, 175.12837890999998), 'rotation':(-0.085693, 90.631645, -0.085938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.76292969, 2664.26464844, 175.11164062), 'rotation':(-0.087219, 90.631638, -0.087463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.70164062, 2669.8278906200003, 175.10318359000001), 'rotation':(-0.087494, 90.630386, -0.087738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2651.43089844, 2604.60570312, 175.19878906000002), 'rotation':(0.077755, -89.367798, 0.077544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2651.07226562, 2625.4040625, 175.16925781), 'rotation':(0.08199, -89.368347, 0.081758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.8884375, 2642.09328125, 175.14492188), 'rotation':(0.084291, -89.368347, 0.084043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.82714844, 2647.65625, 175.13667969), 'rotation':(0.084933, -89.370361, 0.084664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.58203125, 2669.9084375, 175.10318359000001), 'rotation':(0.087208, -89.368347, 0.086955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.52050781, 2675.47144531, 175.0946875), 'rotation':(0.087474, -89.369629, 0.087218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2640.0646875, 2945.53979492, 174.69880859), 'rotation':(-0.088806, 90.536217, -0.089081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2640.17089844, 2934.20214844, 174.71613281), 'rotation':(-0.087067, 90.536186, -0.087341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.22414062, 2928.53320312, 174.72460938), 'rotation':(-0.085449, 90.537727, -0.085693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.27710938, 2922.86425781, 174.73300781), 'rotation':(-0.085449, 90.537727, -0.085693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.3303125, 2917.1953125, 174.74128906), 'rotation':(-0.08371, 90.536194, -0.083954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.38328125, 2911.52661133, 174.74951172000002), 'rotation':(-0.08371, 90.536194, -0.083954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.59546875, 2888.85107422, 174.78226562), 'rotation':(-0.082703, 90.537888, -0.082947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.70164062, 2877.51318359, 174.79853516), 'rotation':(-0.082214, 90.53788, -0.082458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.80785156, 2866.17529297, 174.81472656000003), 'rotation':(-0.081848, 90.536758, -0.082062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2641.07300781, 2837.83081055, 174.85521484), 'rotation':(-0.081818, 90.537552, -0.082062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2641.12621094, 2832.161875, 174.86332031), 'rotation':(-0.082062, 90.535522, -0.082306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.33863281, 2809.48609375, 174.89585938), 'rotation':(-0.082275, 90.536873, -0.08252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.55078125, 2786.8103125, 174.92859375), 'rotation':(-0.082947, 90.535828, -0.083191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.60375, 2781.14160156, 174.93683593999998), 'rotation':(-0.083252, 90.535828, -0.083496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2641.65699219, 2775.47265625, 174.94507812), 'rotation':(-0.083527, 90.535828, -0.083801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.8159375, 2758.46582031, 174.97001953), 'rotation':(-0.083984, 90.534668, -0.084229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.86914062, 2752.796875, 174.97835938), 'rotation':(-0.084259, 90.537338, -0.084503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.9221093799997, 2747.12792969, 174.98673828), 'rotation':(-0.084747, 90.534775, -0.084991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.13453125, 2724.45214844, 175.02050781000003), 'rotation':(-0.085876, 90.537361, -0.086151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.96191406, 2730.19628906, 175.01203125), 'rotation':(0.085869, -89.462646, 0.085617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.90867188, 2735.86523438, 175.00357422000002), 'rotation':(0.085555, -89.46521, 0.085304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.85570312, 2741.53394531, 174.99513672), 'rotation':(0.085234, -89.462616, 0.084978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.8025, 2747.20289062, 174.98673828), 'rotation':(0.085063, -89.462646, 0.084816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.74953125, 2752.87183594, 174.97835938), 'rotation':(0.084421, -89.462646, 0.084173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.69628906, 2758.54078125, 174.97001953), 'rotation':(0.084278, -89.462616, 0.084018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.64332031, 2764.20947266, 174.96167968999998), 'rotation':(0.083984, -89.465332, 0.083743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2649.43117188, 2786.885, 174.92861327999998), 'rotation':(0.083246, -89.464172, 0.082999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.37816406, 2792.55394531, 174.92037109), 'rotation':(0.082939, -89.461731, 0.082697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.27195312, 2803.89183594, 174.90400391), 'rotation':(0.082645, -89.464172, 0.082394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.1128125, 2820.8984375, 174.87958984), 'rotation':(0.082283, -89.463104, 0.082048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.00660156, 2832.23609375, 174.86332031), 'rotation':(0.082194, -89.463074, 0.081954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.90039062, 2843.57397461, 174.84710938), 'rotation':(0.081819, -89.462463, 0.081597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.79417969, 2854.91162109, 174.83091797), 'rotation':(0.081819, -89.465088, 0.081596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.68824219, 2866.24951172, 174.81474609), 'rotation':(0.081723, -89.463226, 0.081482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.52882812, 2883.25610352, 174.79042969), 'rotation':(0.082229, -89.46463, 0.08199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.42285156, 2894.59399414, 174.77408203), 'rotation':(0.0827, -89.462097, 0.082459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.26367188, 2911.6003418, 174.74951172000002), 'rotation':(0.082761, -89.463867, 0.08252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.2107031200003, 2917.26928711, 174.74128906), 'rotation':(0.082761, -89.463867, 0.08252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.15746094, 2922.93798828, 174.73300781), 'rotation':(0.083718, -89.46225, 0.08346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.05125, 2934.27587891, 174.71613281), 'rotation':(0.085439, -89.463806, 0.085181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.99828125, 2939.94482422, 174.70751952999998), 'rotation':(0.087071, -89.463806, 0.086802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.89210938, 2951.28198242, 174.69001953), 'rotation':(0.088792, -89.463806, 0.088518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2485.34914062, 2190.62867188, 170.90208984), 'rotation':(1.586093, 0.518347, 1.499994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2496.41648438, 2190.72023438, 171.20707031), 'rotation':(1.554264, 0.517766, 1.471553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2518.55101562, 2190.9040625, 171.79449218999997), 'rotation':(1.459031, 0.511837, 1.386054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2529.61960938, 2190.99609375, 172.076875), 'rotation':(1.446894, 0.513674, 1.375138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2535.15503906, 2191.04203125, 172.21677734000002), 'rotation':(1.4469, 0.511206, 1.37513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2568.36523438, 2191.30421875, 173.04580077999998), 'rotation':(1.405742, 0.511014, 1.337968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2584.97117188, 2191.42234375, 173.45083984000001), 'rotation':(1.32604, 0.50693, 1.265679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2590.50488281, 2191.46828125, 173.58105468999997), 'rotation':(1.32604, 0.50693, 1.265679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2601.57445312, 2191.55953125, 173.82900390999998), 'rotation':(1.227638, 0.500273, 1.175837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2612.64476562, 2191.65164062, 174.06035156000002), 'rotation':(1.129249, 0.498464, 1.085372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2623.71828125, 2191.7434375000003, 174.27417968999998), 'rotation':(1.030696, 0.4925, 0.994098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2634.79078125, 2191.83523438, 174.47267578), 'rotation':(1.005998, 0.493506, 0.971125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2623.84496094, 2183.89625, 174.27535156000002), 'rotation':(-1.079956, -179.505661, -1.121277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2612.77757812, 2183.80421875, 174.06167968999998), 'rotation':(-1.178345, -179.499527, -1.2276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2601.71265625, 2183.71289062, 173.83058594), 'rotation':(-1.276825, -179.497574, -1.334717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2590.64941406, 2183.62109375, 173.58289062), 'rotation':(-1.32605, -179.493073, -1.38855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2574.04957031, 2183.48289062, 173.18378906), 'rotation':(-1.405762, -179.490509, -1.476074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2568.51441406, 2183.43679688, 173.04787109), 'rotation':(-1.417511, -179.488403, -1.489014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2557.44433594, 2183.3450000000003, 172.77433594), 'rotation':(-1.429199, -179.489349, -1.501923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2546.3747656200003, 2183.25320312, 172.49789062), 'rotation':(-1.441071, -179.488754, -1.515015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2540.83960938, 2183.20726562, 172.35857422), 'rotation':(-1.446899, -179.486328, -1.521454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2529.77101562, 2183.11523438, 172.07904297000002), 'rotation':(-1.459076, -179.485977, -1.534912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2518.70433594, 2183.0234375, 171.79677734), 'rotation':(-1.483276, -179.486908, -1.561646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2513.17359375, 2182.9778125000003, 171.65310547), 'rotation':(-1.507355, -179.485657, -1.588318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2502.10523438, 2182.88578125, 171.35933594), 'rotation':(-1.55426, -179.482239, -1.640411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2485.50902344, 2182.74828125, 170.90470703), 'rotation':(-1.590912, -179.478943, -1.681213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2452.88109375, 2190.35960938, 169.97748047000002), 'rotation':(1.668144, 0.524094, 1.573006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2447.21921875, 2190.3125, 169.81044922), 'rotation':(1.685984, 0.525161, 1.588822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2441.55710938, 2190.265625, 169.64166016), 'rotation':(1.703674, 0.526187, 1.604493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2435.89550781, 2190.21851562, 169.47125), 'rotation':(1.721522, 0.527282, 1.620255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2418.90992188, 2190.07742188, 168.95746093999998), 'rotation':(1.730401, 0.528405, 1.628099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2407.58640625, 2189.9834375, 168.60800781), 'rotation':(1.790896, 0.530378, 1.681399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2396.26488281, 2189.8893749999997, 168.25082031000002), 'rotation':(1.811229, 0.533013, 1.699247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2390.60304688, 2189.8424999999997, 168.07160156), 'rotation':(1.811229, 0.533013, 1.699247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.61914062, 2189.70140625, 167.53101562), 'rotation':(1.820846, 0.534111, 1.707684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2367.95703125, 2189.65476562, 167.34890625), 'rotation':(1.840244, 0.533875, 1.724699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2356.63746094, 2189.56078125, 166.98103516), 'rotation':(1.859567, 0.536606, 1.741586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2350.97582031, 2189.51367188, 166.79509765999998), 'rotation':(1.87906, 0.537893, 1.758626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2345.31664062, 2189.4665625, 166.60839843999997), 'rotation':(1.87906, 0.537893, 1.758626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2322.67164062, 2189.2790625, 165.85550781), 'rotation':(1.903505, 0.5392, 1.779953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2300.02929688, 2189.0910937500003, 165.09583984), 'rotation':(1.927138, 0.541031, 1.800548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2288.7065625, 2188.99703125, 164.71439453), 'rotation':(1.927035, 0.541024, 1.800462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2271.723125, 2188.8559375, 164.1421875), 'rotation':(1.928367, 0.539057, 1.801599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2260.40085938, 2188.76195312, 163.75973633), 'rotation':(1.933025, 0.539366, 1.805661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2254.74, 2188.7153125, 163.56819336), 'rotation':(1.935348, 0.542275, 1.807674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2243.4175, 2188.62109375, 163.18489258), 'rotation':(1.936577, 0.541312, 1.808742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2237.75632812, 2188.57421875, 162.99325195), 'rotation':(1.936427, 0.5413, 1.808619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2452.95214844, 2182.4775, 169.97763672000002), 'rotation':(-1.686005, -179.474838, -1.787567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2447.29003906, 2182.43039062, 169.81060547), 'rotation':(-1.703705, -179.473816, -1.807404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2435.9665625, 2182.33664062, 169.47140625), 'rotation':(-1.730316, -179.473236, -1.837341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2430.30394531, 2182.28976562, 169.30017578), 'rotation':(-1.730408, -179.471588, -1.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2424.64136719, 2182.24289062, 169.12894531), 'rotation':(-1.730408, -179.471588, -1.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2418.98070312, 2182.19578125, 168.95761718999998), 'rotation':(-1.750549, -179.470276, -1.860168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2396.3359375, 2182.0078125, 168.25101562), 'rotation':(-1.811096, -179.468506, -1.928497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.68992188, 2181.81984375, 167.53119141), 'rotation':(-1.84021, -179.46463, -1.961456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2368.0278125, 2181.77273438, 167.34908202999998), 'rotation':(-1.859589, -179.464859, -1.98349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2345.38746094, 2181.585, 166.60857422), 'rotation':(-1.895966, -179.461456, -2.02478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2334.0651562499997, 2181.49070312, 166.23246093999998), 'rotation':(-1.903412, -179.460785, -2.033295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2328.4035937500003, 2181.44359375, 166.0440625), 'rotation':(-1.903564, -179.46077, -2.033478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2322.74242188, 2181.39671875, 165.85570312), 'rotation':(-1.903351, -179.463272, -2.033203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2311.42257812, 2181.30273438, 165.47744140999998), 'rotation':(-1.927155, -179.458969, -2.060303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2300.09984375, 2181.20875, 165.09601562), 'rotation':(-1.927155, -179.458969, -2.060303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2288.77710938, 2181.11476562, 164.71458984), 'rotation':(-1.927185, -179.458939, -2.060364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2277.45460938, 2181.0207812500003, 164.33316406000003), 'rotation':(-1.928284, -179.460968, -2.061584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2271.79367188, 2180.97359375, 164.14234375), 'rotation':(-1.930603, -179.458023, -2.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2260.47117188, 2180.8801562500003, 163.75990234), 'rotation':(-1.935425, -179.460464, -2.069763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2249.149375, 2180.78609375, 163.37670898), 'rotation':(-1.936584, -179.458694, -2.071075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2237.82664062, 2180.69234375, 162.99342773), 'rotation':(-1.936584, -179.458694, -2.071075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2231.26632812, 2180.60789062, 162.77150390999998), 'rotation':(-1.931061, -179.459396, -2.064789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2177.2043750000003, 2188.0134375, 160.97357422), 'rotation':(1.889387, 0.722732, 1.767651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2171.67039062, 2187.9496875, 160.79232421999998), 'rotation':(1.873473, 0.721662, 1.753754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2166.13578125, 2187.88601562, 160.61224609), 'rotation':(1.857927, 0.718711, 1.740163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2155.0651562499997, 2187.75851562, 160.25514648), 'rotation':(1.842198, 0.71965, 1.726397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2149.53101562, 2187.69460938, 160.07771484), 'rotation':(1.834268, 0.719699, 1.719444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2138.46046875, 2187.56710938, 159.72389648), 'rotation':(1.827752, 0.717659, 1.71373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2132.92578125, 2187.50320312, 159.54856445), 'rotation':(1.814802, 0.719221, 1.702388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2121.8525, 2187.37546875, 159.20130859), 'rotation':(1.789093, 0.715211, 1.679791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2094.17554688, 2187.05710938, 158.35381836), 'rotation':(1.730968, 0.709839, 1.62859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2083.10109375, 2186.92945312, 158.02272461), 'rotation':(1.713025, 0.711026, 1.612744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2077.56617188, 2186.86570312, 157.86050781), 'rotation':(1.677187, 0.708901, 1.581021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2155.1575000000003, 2179.87671875, 160.25518555), 'rotation':(-1.834259, -179.282974, -1.954742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2149.62351562, 2179.81296875, 160.07777344), 'rotation':(-1.834259, -179.280304, -1.954742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2138.5534374999997, 2179.68554688, 159.72396484), 'rotation':(-1.814819, -179.283173, -1.932709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2133.01882812, 2179.62179688, 159.54864258), 'rotation':(-1.802032, -179.283966, -1.918243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2127.48414062, 2179.558125, 159.37448242), 'rotation':(-1.789093, -179.282394, -1.903625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2116.41085938, 2179.430625, 159.02959961), 'rotation':(-1.763214, -179.286392, -1.87442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2105.3415625, 2179.30320312, 158.68967773), 'rotation':(-1.737335, -179.287994, -1.845245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2094.26976562, 2179.17554688, 158.35391601999999), 'rotation':(-1.713013, -179.288956, -1.817902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2083.19554688, 2179.0481250000003, 158.02283203000002), 'rotation':(-1.677216, -179.291092, -1.777679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2077.660625, 2178.984375, 157.86061523), 'rotation':(-1.641357, -179.293167, -1.737549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2066.58273438, 2178.8567187500003, 157.54061523000001), 'rotation':(-1.605652, -179.295181, -1.697632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2055.51101562, 2178.7292187499997, 157.2284668), 'rotation':(-1.587616, -179.29689, -1.677521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3997.34742188, 2203.13625, 161.43270508), 'rotation':(-1.796753, 0.481027, -1.912262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3991.81226562, 2203.09546875, 161.60711914), 'rotation':(-1.802795, 0.478824, -1.919098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3986.27710938, 2203.05445312, 161.78154297), 'rotation':(-1.803009, 0.4811, -1.919342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3980.74046875, 2203.01367188, 161.95649414), 'rotation':(-1.808533, 0.479905, -1.925629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3975.20507812, 2202.97289062, 162.13200195), 'rotation':(-1.808533, 0.479905, -1.925629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3964.13429688, 2202.89109375, 162.48526367), 'rotation':(-1.83078, 0.481324, -1.950806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3953.0637500000003, 2202.80859375, 162.84133789), 'rotation':(-1.826294, 0.50709, -1.945709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3947.52929688, 2202.76265625, 163.02039062), 'rotation':(-1.849976, 0.53234, -1.972565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3941.99460938, 2202.71679688, 163.19951172), 'rotation':(-1.851685, 0.535929, -1.974487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3936.4596874999997, 2202.6709375, 163.37863281), 'rotation':(-1.851532, 0.535912, -1.974335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3930.9245312499997, 2202.62453125, 163.55796875), 'rotation':(-1.851532, 0.535912, -1.974335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3925.38914062, 2202.57882812, 163.73762695), 'rotation':(-1.854767, 0.535039, -1.977997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3908.78445312, 2202.42601562, 164.27935547), 'rotation':(-1.873505, 0.536261, -1.999268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3897.71507812, 2202.31617188, 164.64226562), 'rotation':(-1.876678, 0.538393, -2.002869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3881.1106250000003, 2202.1784374999997, 165.18691406000002), 'rotation':(-1.876556, 0.538381, -2.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3875.57570312, 2202.13234375, 165.36853516), 'rotation':(-1.876556, 0.538381, -2.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3864.50609375, 2202.04054688, 165.73224609000002), 'rotation':(-1.881104, 0.535815, -2.007874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3864.49070312, 2194.1909375, 165.73490234000002), 'rotation':(1.882605, -179.464218, 1.761727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3870.02390625, 2194.23679688, 165.55296875), 'rotation':(1.881089, -179.462204, 1.760398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3875.55710938, 2194.28296875, 165.37126952999998), 'rotation':(1.878138, -179.462387, 1.757828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3897.68898438, 2194.4665625, 164.64527343999998), 'rotation':(1.876547, -179.463684, 1.75645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3919.82179688, 2194.65039062, 163.92085938), 'rotation':(1.867216, -179.464157, 1.748293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3925.35523438, 2194.69625, 163.74085938), 'rotation':(1.861056, -179.462631, 1.742894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3936.42257812, 2194.788125, 163.38195312), 'rotation':(1.854765, -179.464966, 1.737388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3953.02195312, 2194.92601562, 162.84480469), 'rotation':(1.849977, -179.467651, 1.733202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3958.55882812, 2194.9678125, 162.66624023), 'rotation':(1.841904, -179.517944, 1.726135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3986.22875, 2195.17210938, 161.78489258), 'rotation':(1.8086, -179.520065, 1.696934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3991.7621875, 2195.21289062, 161.61053711), 'rotation':(1.802924, -179.521164, 1.691951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3826.48757812, 2201.88765625, 166.98167969), 'rotation':(-1.874359, 0.53625, -2.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3819.5989062500003, 2201.8303125, 167.20720702999998), 'rotation':(-1.872253, 0.536113, -1.997864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3793.288125, 2201.48242188, 168.06533202999998), 'rotation':(-1.862457, 0.542624, -1.986725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3787.75460938, 2201.4362499999997, 168.24488281), 'rotation':(-1.858124, 0.53601, -1.981781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3776.68703125, 2201.34445312, 168.601875), 'rotation':(-1.841095, 0.534907, -1.962463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3771.1535937500003, 2201.29859375, 168.77933593999998), 'rotation':(-1.832581, 0.534358, -1.95282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3760.08640625, 2201.20679688, 169.13244140999998), 'rotation':(-1.823059, 0.533192, -1.942078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3754.55273438, 2201.16085938, 169.30779297), 'rotation':(-1.812378, 0.532507, -1.929962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3749.01882812, 2201.11914062, 169.48289062), 'rotation':(-1.812378, 0.532507, -1.929962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3834.56734375, 2193.81320312, 166.71898438), 'rotation':(1.876444, -179.461029, 1.756352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3828.92015625, 2193.76632812, 166.90421875), 'rotation':(1.874354, -179.463745, 1.754526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3811.74828125, 2193.66554688, 167.46597656000003), 'rotation':(1.86777, -179.464188, 1.748762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3800.6796875, 2193.6396875, 167.82697266), 'rotation':(1.863433, -179.461868, 1.744975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3787.8134375, 2193.55445312, 168.24509766), 'rotation':(1.849731, -179.464523, 1.732994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3776.745625, 2193.46265625, 168.60208984000002), 'rotation':(1.832635, -179.465622, 1.718026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3771.21164062, 2193.4167187499997, 168.77957031000003), 'rotation':(1.823018, -179.466827, 1.709599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3760.14382812, 2193.32515625, 169.13271484), 'rotation':(1.81237, -179.467484, 1.70026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3754.60960938, 2193.27929688, 169.30806640999998), 'rotation':(1.807029, -179.466614, 1.695562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3707.5807812499997, 2192.8428125, 170.76783203), 'rotation':(1.72172, -179.473526, 1.620433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3700.08890625, 2192.82640625, 170.99359375), 'rotation':(1.72157, -179.4711, 1.620293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3683.4665625, 2192.6884375, 171.49041015999998), 'rotation':(1.676135, -179.474823, 1.580091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3666.84445312, 2192.55078125, 171.97240234), 'rotation':(1.615394, -179.478317, 1.526114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3650.2189843799997, 2192.4128124999997, 172.43955078), 'rotation':(1.600245, -179.481354, 1.512619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3638.87964844, 2192.22851562, 172.75576172), 'rotation':(1.563765, -179.481125, 1.480042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3694.484375, 2200.66210938, 171.16023438), 'rotation':(-1.721558, 0.528889, -1.827515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3683.4035937500003, 2200.5703125, 171.49033203), 'rotation':(-1.706421, 0.525374, -1.810516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3677.86179688, 2200.524375, 171.65265625), 'rotation':(-1.676147, 0.525177, -1.776489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3661.23921875, 2200.38625, 172.12876953), 'rotation':(-1.615387, 0.520078, -1.708527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3639.07300781, 2200.28664062, 172.74853516), 'rotation':(-1.587891, 0.520197, -1.677856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3573.52585938, 2191.77664062, 174.4290625), 'rotation':(1.346592, -179.493149, 1.284359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3556.90796875, 2191.63890625, 174.81015625), 'rotation':(1.276651, -179.495834, 1.220667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3545.82691406, 2191.546875, 175.05720703), 'rotation':(1.258654, -179.495224, 1.204218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3540.28589844, 2191.5009375, 175.17902343999998), 'rotation':(1.222966, -179.498657, 1.171553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3527.40210938, 2191.3307812499997, 175.45306641), 'rotation':(1.187121, -179.500168, 1.138667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3601.16164062, 2199.92796875, 173.74755859), 'rotation':(-1.462952, 0.512973, -1.539185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3590.08886719, 2199.7959375, 174.02689453), 'rotation':(-1.444275, 0.512097, -1.518555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3584.54859375, 2199.75, 174.16306641), 'rotation':(-1.407074, 0.510247, -1.477539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3573.47167969, 2199.65773438, 174.42880859000002), 'rotation':(-1.374451, 0.510379, -1.44162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3567.93359375, 2199.6115625, 174.55810547000002), 'rotation':(-1.346588, 0.506842, -1.411072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3556.85425781, 2199.51976562, 174.80988281), 'rotation':(-1.290619, 0.504261, -1.349823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3540.23265625, 2199.381875, 175.17875), 'rotation':(-1.258667, 0.502887, -1.314911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3529.15453125, 2199.32125, 175.41533203), 'rotation':(-1.222961, 0.501329, -1.276062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3523.61375, 2199.37203125, 175.53017577999998), 'rotation':(-1.187134, 0.501714, -1.237122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3480.24707031, 2190.96703125, 176.35404297000002), 'rotation':(0.967804, -179.507492, 0.935509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3463.64234375, 2190.86523438, 176.63263672000002), 'rotation':(0.905164, -179.51091, 0.876895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3452.56933594, 2190.7734375, 176.80902343999998), 'rotation':(0.882276, -179.510971, 0.855405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3447.03417969, 2190.7275, 176.89498047), 'rotation':(0.882276, -179.510971, 0.855405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3435.96019531, 2190.63578125, 177.06121094), 'rotation':(0.790786, -179.512146, 0.769193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3430.42652344, 2190.58984375, 177.14072266), 'rotation':(0.790786, -179.512146, 0.769193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3424.88867188, 2190.54390625, 177.2171875), 'rotation':(0.745023, -179.514877, 0.725833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3419.35253906, 2190.4978125, 177.2909375), 'rotation':(0.745023, -179.514877, 0.725833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3413.8146875, 2190.4518749999997, 177.36296875), 'rotation':(0.722176, -179.515579, 0.704137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3408.27855469, 2190.40578125, 177.43292968999998), 'rotation':(0.722176, -179.515579, 0.704137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3402.74046875, 2190.35984375, 177.50275391), 'rotation':(0.706522, -179.51622, 0.689261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3480.17554688, 2198.9196875, 176.35414062), 'rotation':(-1.009674, 0.492361, -1.045746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3463.57179688, 2198.74585938, 176.63271484), 'rotation':(-0.926056, 0.489537, -0.95639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3458.03664062, 2198.69992188, 176.72158202999998), 'rotation':(-0.926056, 0.489537, -0.95639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3441.42652344, 2198.56179688, 176.98037109), 'rotation':(-0.882294, 0.489023, -0.90976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3430.35742188, 2198.4700000000003, 177.14078125), 'rotation':(-0.836548, 0.487658, -0.861237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3419.2834375, 2198.3784375, 177.29097656000002), 'rotation':(-0.790802, 0.486362, -0.812866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3402.6716406200003, 2198.24023438, 177.50279297), 'rotation':(-0.722168, 0.484419, -0.74057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3397.13746094, 2198.29929688, 177.57115234), 'rotation':(-0.706512, 0.483787, -0.724121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3353.79589844, 2189.95382812, 178.02324219), 'rotation':(0.530398, -179.519791, 0.520646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3342.72753906, 2189.86179688, 178.12523438), 'rotation':(0.516963, -179.520035, 0.507694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3337.193125, 2189.8159375, 178.17517578), 'rotation':(0.503426, -179.520279, 0.494646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3331.65941406, 2189.77, 178.224375), 'rotation':(0.503426, -179.520279, 0.494646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3320.59105469, 2189.67820312, 178.32060547), 'rotation':(0.490005, -179.519089, 0.481681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3303.99121094, 2189.5403125000003, 178.45951172000002), 'rotation':(0.416648, -179.521713, 0.410628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3292.92945312, 2189.44898438, 178.53636719), 'rotation':(0.328074, -179.522842, 0.324344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3276.33544922, 2189.3112499999997, 178.61695312), 'rotation':(0.195002, -179.521362, 0.193689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3265.26976562, 2189.21945312, 178.64867188), 'rotation':(0.128449, -179.525452, 0.127869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3259.73511719, 2189.17359375, 178.66107422000002), 'rotation':(0.128455, -179.523315, 0.127872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3353.73070312, 2197.83421875, 178.02324219), 'rotation':(-0.537109, 0.481624, -0.547241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3348.19628906, 2197.78835938, 178.07447266), 'rotation':(-0.530396, 0.480202, -0.540283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3326.05957031, 2197.60476562, 178.27298828), 'rotation':(-0.503418, 0.479701, -0.512329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3309.45800781, 2197.46679688, 178.41460938), 'rotation':(-0.483246, 0.48156, -0.491455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3298.39306641, 2197.37476562, 178.50023438), 'rotation':(-0.416687, 0.478307, -0.42276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3287.33349609, 2197.2834375, 178.56775391), 'rotation':(-0.328094, 0.477155, -0.331848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3281.80054688, 2197.23757812, 178.59462890999998), 'rotation':(-0.2836, 0.47666, -0.286407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3276.27001953, 2197.19164062, 178.61695312), 'rotation':(-0.239319, 0.476278, -0.241302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3210.64039062, 2196.64648438, 178.77095702999998), 'rotation':(-0.128448, 0.475288, -0.128998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3199.51390625, 2196.55445312, 178.79345702999998), 'rotation':(-0.112732, 0.475994, -0.113159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3188.38916016, 2196.4621875000003, 178.80570312), 'rotation':(-0.050446, 0.475816, -0.050537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3160.56787109, 2196.23117188, 178.80900391), 'rotation':(-0.003601, 0.475394, -0.003571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3138.31103516, 2196.04640625, 178.80916016), 'rotation':(0.009596, 0.475339, 0.0096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3127.18579102, 2195.9540625, 178.80103516), 'rotation':(0.035934, 0.477417, 0.035893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3121.62133789, 2195.90796875, 178.794375), 'rotation':(0.068678, 0.474636, 0.06852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3093.80126953, 2195.6770312500003, 178.74876953), 'rotation':(0.111851, 0.477483, 0.111421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3077.11035156, 2195.53859375, 178.71103516), 'rotation':(0.140121, 0.477608, 0.139439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3071.54614258, 2195.49242188, 178.69640625), 'rotation':(0.149649, 0.474854, 0.148883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3077.17578125, 2187.65867188, 178.71103516), 'rotation':(-0.149658, -179.525146, -0.150421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3088.30249023, 2187.7509375, 178.73720702999998), 'rotation':(-0.130768, -179.522461, -0.131348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3093.86645508, 2187.79710938, 178.74876953), 'rotation':(-0.121216, -179.525253, -0.121735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3104.99511719, 2187.8893749999997, 178.76886718999998), 'rotation':(-0.102509, -179.525345, -0.102844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3116.12353516, 2187.9817187500003, 178.78625), 'rotation':(-0.088257, -179.523254, -0.088531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3138.37646484, 2188.16648438, 178.80916016), 'rotation':(-0.03595, -179.524643, -0.03598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3143.93969727, 2188.21265625, 178.81005859), 'rotation':(-0.009613, -179.524658, -0.009613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3149.50415039, 2188.25875, 178.80970703), 'rotation':(0.003668, -179.523163, 0.003669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3166.19800781, 2188.3975, 178.80865234), 'rotation':(0.003661, -179.524597, 0.003674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3171.76246094, 2188.44359375, 178.80830078), 'rotation':(0.003572, -179.524597, 0.003585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3177.32714844, 2188.48976562, 178.80792968999998), 'rotation':(0.003572, -179.524597, 0.003585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3188.45484375, 2188.58226562, 178.80570312), 'rotation':(0.019234, -179.524216, 0.019218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3199.57933594, 2188.6745312499997, 178.79345702999998), 'rotation':(0.081662, -179.524109, 0.081431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3210.70556641, 2188.7668750000003, 178.77095702999998), 'rotation':(0.112739, -179.523987, 0.11229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3044.52099609, 2195.26804688, 178.61673828), 'rotation':(0.183794, 0.475101, 0.182621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3022.28393555, 2195.08375, 178.53431641), 'rotation':(0.232513, 0.473957, 0.230642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3016.72412109, 2195.03757812, 178.51144531000003), 'rotation':(0.235601, 0.477172, 0.233673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2988.92797852, 2194.806875, 178.39017578), 'rotation':(0.262149, 0.475473, 0.259772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2983.36816406, 2194.76078125, 178.36304688), 'rotation':(0.279689, 0.477284, 0.276971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2972.24975586, 2194.6684375, 178.30527343999998), 'rotation':(0.297332, 0.47746, 0.29426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2966.68969727, 2194.6223437500003, 178.27556640999998), 'rotation':(0.306177, 0.477141, 0.302912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2916.65722656, 2194.20726562, 177.97078125), 'rotation':(0.386869, 0.478362, 0.381666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2905.5390625, 2194.115, 177.89382812), 'rotation':(0.403869, 0.477983, 0.398213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2877.74511719, 2193.88453125, 177.68074219), 'rotation':(0.459815, 0.478826, 0.452486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3039.02685547, 2187.34179688, 178.59773438), 'rotation':(-0.209686, -179.522476, -0.211212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3033.4675293, 2187.2956249999997, 178.57761718999998), 'rotation':(-0.222778, -179.524582, -0.224518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3027.90795898, 2187.24953125, 178.55642577999998), 'rotation':(-0.232513, -179.52153, -0.234406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2988.99316406, 2186.92625, 178.39017578), 'rotation':(-0.279694, -179.524353, -0.28244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2961.19604492, 2186.69578125, 178.24564453), 'rotation':(-0.321381, -179.522079, -0.324982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2955.63671875, 2186.649375, 178.21490234), 'rotation':(-0.33139, -179.521957, -0.335236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2950.07714844, 2186.60328125, 178.183125), 'rotation':(-0.341431, -179.521851, -0.34552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2938.95922852, 2186.51125, 178.11638672), 'rotation':(-0.361664, -179.521606, -0.366241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2900.04516602, 2186.1884375, 177.85363281000002), 'rotation':(-0.426361, -179.521698, -0.432739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2894.48803711, 2186.14234375, 177.8121875), 'rotation':(-0.437317, -179.52153, -0.444061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2888.92871094, 2186.09617188, 177.76955078), 'rotation':(-0.448669, -179.521347, -0.45575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2883.36938477, 2186.05007812, 177.72572266), 'rotation':(-0.459808, -179.518448, -0.467224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2672.97558594, 2184.30375, 175.14236327999998), 'rotation':(-1.006042, -179.506485, -1.04187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2684.08667969, 2184.39601562, 175.33664062), 'rotation':(-0.994751, -179.509125, -1.029755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2689.6428125, 2184.44210938, 175.43125), 'rotation':(-0.972015, -179.507294, -1.005432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.75464844, 2184.5346875, 175.61361327999998), 'rotation':(-0.926514, -179.508804, -0.956879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2734.08960938, 2184.8112499999997, 176.11080077999998), 'rotation':(-0.824249, -179.512299, -0.848206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2750.75707031, 2184.94945312, 176.34130859), 'rotation':(-0.779297, -179.514175, -0.800751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2756.3146875, 2184.995625, 176.41402344), 'rotation':(-0.749298, -179.514984, -0.769104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2761.87085938, 2185.04148438, 176.48460938), 'rotation':(-0.749298, -179.514984, -0.769104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2778.54175781, 2185.17992188, 176.69033202999998), 'rotation':(-0.704407, -179.516724, -0.721893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2800.76904297, 2185.3645312500003, 176.94863281000002), 'rotation':(-0.649536, -179.518433, -0.664368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2822.99730469, 2185.5490625, 177.18279297), 'rotation':(-0.586792, -179.517258, -0.598907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2839.66943359, 2185.68726562, 177.34712890999998), 'rotation':(-0.556, -179.518692, -0.566864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2845.22680664, 2185.7334375, 177.39939453), 'rotation':(-0.540527, -179.519012, -0.550812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2845.17626953, 2193.61398438, 177.39953125), 'rotation':(0.525105, 0.480696, 0.515546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2834.06201172, 2193.52171875, 177.29369140999998), 'rotation':(0.555998, 0.481297, 0.545281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2828.50464844, 2193.475625, 177.23876952999998), 'rotation':(0.571263, 0.481578, 0.559956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2817.39160156, 2193.38328125, 177.12642577999998), 'rotation':(0.57894, 0.480459, 0.567329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2811.83472656, 2193.3371875000003, 177.06875), 'rotation':(0.586788, 0.482741, 0.574868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2806.27734375, 2193.29125, 177.00953125), 'rotation':(0.618153, 0.483403, 0.604924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2784.05199219, 2193.1067187500003, 176.75742188), 'rotation':(0.681018, 0.484806, 0.66497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2778.49511719, 2193.06054688, 176.69056641), 'rotation':(0.696563, 0.485199, 0.67979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2772.93945312, 2193.0143749999997, 176.62259766), 'rotation':(0.704404, 0.483277, 0.687239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2756.27027344, 2192.8762500000003, 176.41429688), 'rotation':(0.71939, 0.484246, 0.7015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2745.15966797, 2192.7839062499997, 176.26646484), 'rotation':(0.779304, 0.485817, 0.758317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2739.60351562, 2192.7378125, 176.18962890999998), 'rotation':(0.779304, 0.485817, 0.758317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2722.93382812, 2192.599375, 175.95121093999998), 'rotation':(0.82424, 0.487705, 0.80078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2711.82373047, 2192.50734375, 175.78716797), 'rotation':(0.858323, 0.486477, 0.832879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.71800781, 2192.4153125000003, 175.61408203), 'rotation':(0.903777, 0.490456, 0.875587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2689.60644531, 2192.3229687499997, 175.43173828), 'rotation':(0.949266, 0.491926, 0.91819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2684.05029297, 2192.27710938, 175.33714844), 'rotation':(0.972052, 0.490107, 0.939484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2180.8884375, 2472.21460938, 161.24761719), 'rotation':(1.838509, -5.22818, 1.723167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2169.92648438, 2472.93066406, 160.8953418), 'rotation':(1.821673, -3.857788, 1.708406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2164.421875, 2473.27296875, 160.71928711), 'rotation':(1.817623, -3.515411, 1.704855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2142.36960938, 2474.04273438, 160.02303711000002), 'rotation':(1.786135, -0.834381, 1.677198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2136.8410937500003, 2474.08105469, 159.8503418), 'rotation':(1.782133, -0.491028, 1.673686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2125.80539062, 2473.9865625, 159.50895508), 'rotation':(1.757059, 0.925772, 1.651613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2120.28515625, 2473.87988281, 159.33842773), 'rotation':(1.767516, 1.161314, 1.660823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2109.22875, 2473.66601562, 159.00019531), 'rotation':(1.742511, 1.159778, 1.638785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2103.7004687500003, 2473.55933594, 158.83271484), 'rotation':(1.730005, 1.159021, 1.627743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2081.58226562, 2473.13160156, 158.17234375), 'rotation':(1.678328, 1.155894, 1.582027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2070.51929688, 2473.05933594, 157.8515332), 'rotation':(1.660214, 1.157312, 1.565969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2053.9245312499997, 2472.74144531, 157.38286133), 'rotation':(1.6056, 1.15171, 1.517402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2049.23484375, 2464.59375, 157.24862305), 'rotation':(-1.578369, -178.849121, -1.667206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2059.349375, 2464.67359375, 157.5299707), 'rotation':(-1.605621, -178.84584, -1.697601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2064.8671875, 2464.78027344, 157.68571289), 'rotation':(-1.605621, -178.84584, -1.697601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2070.38351562, 2464.89015625, 157.84310546999998), 'rotation':(-1.623779, -178.84726, -1.717926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2120.03445312, 2465.84691406, 159.32587891), 'rotation':(-1.754883, -178.837189, -1.865021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2125.55078125, 2465.9533593799997, 159.4962793), 'rotation':(-1.767517, -178.838684, -1.879272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2136.65578125, 2466.0546875, 159.8449707), 'rotation':(-1.815826, 179.98555, -1.933868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2147.76320312, 2465.91554688, 160.19832030999999), 'rotation':(-1.830933, 178.885712, -1.950958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2153.30539062, 2465.75148438, 160.37570312), 'rotation':(-1.839203, 178.200226, -1.960327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2180.9270312500003, 2464.18285156, 161.27249023000002), 'rotation':(-1.877777, 175.118118, -2.00412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2186.40796875, 2463.6528125, 161.4530957), 'rotation':(-1.886261, 174.430176, -2.013763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2229.0715625000003, 2457.36425781, 162.88359375), 'rotation':(-1.911682, 169.365891, -2.042694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2262.17359375, 2449.69703125, 164.01322266), 'rotation':(-1.901459, 165.561142, -2.031036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2273.13453125, 2446.6753125, 164.38851562), 'rotation':(-1.893036, 164.188675, -2.021484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2284.005625, 2443.41503906, 164.76105468999998), 'rotation':(-1.886627, 163.086761, -2.014191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2294.79757812, 2440.09328125, 165.12816406000002), 'rotation':(-1.859467, 162.95195, -1.983307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2300.19164062, 2438.433125, 165.31162109000002), 'rotation':(-1.859528, 162.952698, -1.983398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2305.58570312, 2436.77269531, 165.49501952999998), 'rotation':(-1.859467, 162.95195, -1.983307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2327.16359375, 2430.13867188, 166.22490234), 'rotation':(-1.84433, 162.949738, -1.966156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2348.79003906, 2423.66015625, 166.95119140999998), 'rotation':(-1.838684, 162.951797, -1.959747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2359.5778906200003, 2420.33960938, 167.31048828), 'rotation':(-1.82666, 162.949738, -1.946106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2375.76, 2415.35863281, 167.84339844), 'rotation':(-1.800354, 162.946579, -1.916351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2381.15527344, 2413.69800781, 168.0196875), 'rotation':(-1.787079, 162.947235, -1.901367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2391.94410156, 2410.37695312, 168.3709375), 'rotation':(-1.780548, 162.946945, -1.893982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.52222656, 2403.73535156, 169.06480469), 'rotation':(-1.736267, 162.946121, -1.844055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2418.91871094, 2402.08203125, 169.235), 'rotation':(-1.707123, 163.102066, -1.811279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2429.744375, 2398.94652344, 169.57095703), 'rotation':(-1.698944, 164.490448, -1.802094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2435.19117188, 2397.46558594, 169.73910156000002), 'rotation':(-1.698669, 164.851379, -1.801788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2446.098125, 2394.6975, 170.07216797), 'rotation':(-1.677002, 166.391724, -1.777496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2240.7934375, 2463.18335938, 163.22496094), 'rotation':(1.867811, -12.193176, 1.748809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2273.5495312499997, 2454.90503906, 164.3275), 'rotation':(1.849151, -15.813477, 1.73248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2278.9575, 2453.33667969, 164.51015625), 'rotation':(1.844294, -16.635925, 1.728238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2284.3584375, 2451.69703125, 164.69275391), 'rotation':(1.86167, -17.047241, 1.743453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2289.75632812, 2450.035625, 164.87652343999997), 'rotation':(1.859362, -17.049713, 1.741414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2305.94484375, 2445.03394531, 165.42720702999998), 'rotation':(1.859621, -17.048035, 1.74164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2343.72804688, 2433.39648438, 166.70412109), 'rotation':(1.838714, -17.050446, 1.723352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2349.12648438, 2431.7346093799997, 166.885625), 'rotation':(1.826591, -17.049805, 1.712731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2354.52464844, 2430.07273438, 167.06591797000002), 'rotation':(1.813354, -17.051086, 1.701123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2370.71875, 2425.088125, 167.60255859), 'rotation':(1.787037, -17.052307, 1.677984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2376.11644531, 2423.42699219, 167.77992188), 'rotation':(1.787037, -17.052307, 1.677984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2386.9138281200003, 2420.10328125, 168.13230468999998), 'rotation':(1.780555, -17.05307, 1.672295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2392.3122656200003, 2418.44164062, 168.30806640999998), 'rotation':(1.77423, -17.053711, 1.666724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2403.10984375, 2415.11816406, 168.65816406000002), 'rotation':(1.761567, -17.054474, 1.655581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.90625, 2411.79492188, 169.00400391), 'rotation':(1.736241, -17.05603, 1.633251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2419.31789062, 2410.13109375, 169.17582031), 'rotation':(1.747832, -16.897064, 1.643488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2430.26804688, 2406.9138281200003, 169.52179688), 'rotation':(1.73928, -15.507721, 1.635937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2435.754375, 2405.40503906, 169.69402344), 'rotation':(1.736487, -14.81134, 1.633479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2441.2814843799997, 2403.95191406, 169.86652343999998), 'rotation':(1.726515, -14.208038, 1.624663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2632.3159375, 2380.38574219, 174.93419922), 'rotation':(-1.252106, -179.972626, -1.30777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2621.2621875, 2380.38597656, 174.69238281000003), 'rotation':(-1.261749, -179.972183, -1.318298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2610.2107031200003, 2380.38597656, 174.44599609), 'rotation':(-1.300995, -179.970428, -1.361115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2604.68507812, 2380.38597656, 174.31978515999998), 'rotation':(-1.320587, -179.969528, -1.382568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2599.1596875, 2380.38597656, 174.19150391), 'rotation':(-1.34021, -179.968613, -1.404053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2571.53367188, 2380.53078125, 173.5225), 'rotation':(-1.422333, -179.964661, -1.494354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2566.01464844, 2380.53050781, 173.38535156), 'rotation':(-1.425598, 179.801376, -1.497955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2560.49511719, 2380.54761719, 173.24759766), 'rotation':(-1.438385, 179.337112, -1.512024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2554.97609375, 2380.62671875, 173.10800781), 'rotation':(-1.450836, 178.869431, -1.525787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2549.47023438, 2380.76148438, 172.96724609), 'rotation':(-1.476135, 177.937302, -1.553741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2543.94382812, 2380.9553125, 172.82445312), 'rotation':(-1.488861, 177.469284, -1.567841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2527.4142968799997, 2381.90699219, 172.38703125), 'rotation':(-1.520477, 175.70752, -1.602875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2500.04640625, 2384.536875, 171.64421875), 'rotation':(-1.588989, 172.465591, -1.679077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2489.22242188, 2386.05371094, 171.33740234), 'rotation':(-1.619873, 171.30658, -1.713562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2494.35890625, 2393.55835938, 171.45113281000002), 'rotation':(1.639457, -7.941803, 1.547529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2510.81859375, 2391.484375, 171.91730468999998), 'rotation':(1.57567, -5.899628, 1.490692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2516.33765625, 2390.9138281200003, 172.06927734), 'rotation':(1.563007, -5.489563, 1.47937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2544.09082031, 2388.98289062, 172.81957031000002), 'rotation':(1.511275, -2.062286, 1.43303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2566.34253906, 2388.556875, 173.39351562), 'rotation':(1.422339, 0.03534, 1.352967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2593.90039062, 2388.556875, 174.06753906000003), 'rotation':(1.359809, 0.032298, 1.296355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2604.92382812, 2388.55664062, 174.32527344), 'rotation':(1.300994, 0.029561, 1.242861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2621.45972656, 2388.37890625, 174.69673827999998), 'rotation':(1.252097, 0.027379, 1.198234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2632.48558594, 2388.37890625, 174.93791016), 'rotation':(1.252069, 0.027378, 1.198202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2670.3669531200003, 2380.4253125, 175.76626953), 'rotation':(-1.252075, -179.972626, -1.307739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2686.95921875, 2380.53050781, 176.12240234), 'rotation':(-1.18866, -179.975327, -1.2388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2698.02027344, 2380.53050781, 176.3415625), 'rotation':(-1.104065, -179.978714, -1.147247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2703.55078125, 2380.53078125, 176.44494140999998), 'rotation':(-1.061798, -179.980316, -1.101715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2714.61376953, 2380.53050781, 176.63933594), 'rotation':(-0.977264, -179.983322, -1.011047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2720.14599609, 2380.53050781, 176.7303125), 'rotation':(-0.934967, -179.984726, -0.965881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2725.67847656, 2380.53050781, 176.81890625), 'rotation':(-0.913849, -179.985413, -0.943359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2731.21265625, 2380.53050781, 176.90720703), 'rotation':(-0.913696, -179.985413, -0.943176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2736.74683594, 2380.53050781, 176.99535156000002), 'rotation':(-0.912323, -179.985458, -0.941742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2769.95140625, 2380.53050781, 177.52066406000003), 'rotation':(-0.901672, -179.985809, -0.93042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2775.48558594, 2380.53050781, 177.60779297000002), 'rotation':(-0.901672, -179.985809, -0.93042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2786.55273438, 2380.525625, 177.779375), 'rotation':(-0.880341, -179.986465, -0.907715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2819.75660156, 2380.56324219, 178.25931641), 'rotation':(-0.795166, -179.988968, -0.817474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2836.35913086, 2380.4533593799997, 178.48623047), 'rotation':(-0.773438, -179.989563, -0.794525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2830.85400391, 2388.41601562, 178.41189452999998), 'rotation':(0.77343, 0.010439, 0.75275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2814.25439453, 2388.41113281, 178.18320312), 'rotation':(0.795157, 0.011034, 0.773312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2808.72046875, 2388.41113281, 178.10542969), 'rotation':(0.809439, 0.011434, 0.786805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2803.18628906, 2388.41113281, 178.02621093999997), 'rotation':(0.823721, 0.011841, 0.800285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2797.65257812, 2388.41136719, 177.94554688), 'rotation':(0.837668, 0.012246, 0.813434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2786.58740234, 2388.41136719, 177.77990234), 'rotation':(0.866013, 0.01309, 0.840127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2781.05419922, 2388.41136719, 177.69482422000002), 'rotation':(0.880343, 0.013527, 0.853588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2775.52148438, 2388.41136719, 177.60833984), 'rotation':(0.894625, 0.013969, 0.866998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2747.85132812, 2388.41136719, 177.17177734), 'rotation':(0.90627, 0.014336, 0.877932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2731.24902344, 2388.41136719, 176.90779297), 'rotation':(0.912336, 0.014529, 0.883618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2725.71533203, 2388.41136719, 176.81951172), 'rotation':(0.913688, 0.014572, 0.88488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2720.18457031, 2388.41136719, 176.73095702999998), 'rotation':(0.913859, 0.014577, 0.885043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2709.125, 2388.41136719, 176.54496093999998), 'rotation':(0.97725, 0.016671, 0.94433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2703.59300781, 2388.41136719, 176.44572266), 'rotation':(1.019624, 0.01815, 0.983799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2692.53441406, 2388.411875, 176.23496093999998), 'rotation':(1.104045, 0.021282, 1.06209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2687.00855469, 2388.411875, 176.1234375), 'rotation':(1.146563, 0.022955, 1.101339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2681.47705078, 2388.411875, 176.00769531000003), 'rotation':(1.188665, 0.024673, 1.140074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2675.95166016, 2388.43261719, 175.88839843999997), 'rotation':(1.230855, 0.026457, 1.178783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2879.89111328, 2380.40085938, 179.03128906), 'rotation':(-0.691345, -179.991669, -0.708191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2913.10253906, 2380.53027344, 179.40433593999998), 'rotation':(-0.618195, -179.993332, -0.631622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2935.24438477, 2380.53003906, 179.63351562), 'rotation':(-0.575104, -179.994232, -0.586731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2946.31542969, 2380.53003906, 179.74214844), 'rotation':(-0.558746, -179.994553, -0.569733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2957.38574219, 2380.53003906, 179.84554688), 'rotation':(-0.542297, -179.994873, -0.552612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2962.92138672, 2380.53003906, 179.89609375), 'rotation':(-0.523438, -179.995224, -0.533081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2968.45751953, 2380.53027344, 179.94566406), 'rotation':(-0.513031, -179.995407, -0.522278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2979.52905273, 2380.53027344, 180.043125), 'rotation':(-0.500946, -179.995621, -0.509735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2985.06445312, 2380.53027344, 180.09001952999998), 'rotation':(-0.500946, -179.995621, -0.509735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2990.60083008, 2380.53027344, 180.13611328), 'rotation':(-0.476929, -179.996033, -0.484894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3012.7421875, 2380.53027344, 180.30628906), 'rotation':(-0.42868, -179.996796, -0.43515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3018.27856445, 2380.53027344, 180.34654297), 'rotation':(-0.416718, -179.996979, -0.422821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3023.81445312, 2380.53027344, 180.38648438), 'rotation':(-0.416687, -179.996979, -0.422791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3029.35083008, 2380.53027344, 180.42572266), 'rotation':(-0.406067, -179.997131, -0.411835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3040.42138672, 2380.53027344, 180.49878906), 'rotation':(-0.38504, -179.997406, -0.390228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3045.95703125, 2380.53027344, 180.53330078), 'rotation':(-0.363922, -179.997696, -0.368591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3045.96313477, 2388.41039062, 180.53332031000002), 'rotation':(0.342657, 0.002044, 0.338579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3040.42700195, 2388.410625, 180.49882811999998), 'rotation':(0.363919, 0.002307, 0.359331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3034.89306641, 2388.410625, 180.46296875), 'rotation':(0.363919, 0.002307, 0.359331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3029.35766602, 2388.410625, 180.42576172), 'rotation':(0.385031, 0.002583, 0.379891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3018.28588867, 2388.410625, 180.34658202999998), 'rotation':(0.416703, 0.003026, 0.410674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3007.21459961, 2388.410625, 180.26525390999998), 'rotation':(0.416723, 0.003026, 0.410693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3001.6784668, 2388.410625, 180.22380859), 'rotation':(0.428683, 0.003203, 0.422307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2968.46728516, 2388.410625, 179.94576172), 'rotation':(0.500933, 0.004375, 0.492227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2962.93139648, 2388.410625, 179.89617188), 'rotation':(0.513029, 0.004589, 0.503906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2957.39599609, 2388.41089844, 179.84564453), 'rotation':(0.523445, 0.004778, 0.51395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2951.86279297, 2388.41089844, 179.79464843999997), 'rotation':(0.523445, 0.004778, 0.51395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2946.32666016, 2388.41089844, 179.74226562), 'rotation':(0.542283, 0.005128, 0.532089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2935.25561523, 2388.41089844, 179.63361328), 'rotation':(0.55875, 0.005445, 0.54793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2929.72021484, 2388.41089844, 179.57775390999998), 'rotation':(0.575095, 0.005768, 0.56364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2924.18383789, 2388.41113281, 179.52058594), 'rotation':(0.591692, 0.006106, 0.579556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2913.11547852, 2388.41113281, 179.40447265999998), 'rotation':(0.606111, 0.006408, 0.593386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2902.04443359, 2388.41113281, 179.28488281000003), 'rotation':(0.630392, 0.006932, 0.616638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2879.90600586, 2388.54078125, 179.03146484), 'rotation':(0.679126, 0.008047, 0.663169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3094.95581055, 2380.53003906, 180.78646484), 'rotation':(-0.243347, -179.998978, -0.245422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3106.06079102, 2380.53003906, 180.82949219), 'rotation':(-0.210846, -179.999237, -0.212402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3111.61303711, 2380.53003906, 180.84886719), 'rotation':(-0.194489, -179.999344, -0.195831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3128.26831055, 2380.53003906, 180.90181640999998), 'rotation':(-0.186401, -179.99939, -0.187592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3144.91967773, 2380.52976562, 180.93013672), 'rotation':(-0.071045, -179.999908, -0.071228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3150.47290039, 2380.52976562, 180.93328125), 'rotation':(-0.03244, -179.999985, -0.032471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3161.5793457, 2380.52976562, 180.93960938), 'rotation':(-0.032593, -179.999985, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3167.13257812, 2380.52976562, 180.94275391), 'rotation':(-0.03244, -179.999985, -0.032471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3178.23876953, 2380.52976562, 180.9490625), 'rotation':(-0.032593, -179.999985, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3183.79199219, 2380.52976562, 180.95222656), 'rotation':(-0.032593, -179.999985, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3178.23779297, 2388.41015625, 180.9490625), 'rotation':(0.032594, 1.4e-05, 0.032554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3172.68480469, 2388.41015625, 180.94589843999998), 'rotation':(0.032594, 1.4e-05, 0.032555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3161.57836914, 2388.41015625, 180.93958984), 'rotation':(0.032437, 1.3e-05, 0.032395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3150.47216797, 2388.41015625, 180.93328125), 'rotation':(0.032594, 1.4e-05, 0.032555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3133.82080078, 2388.41015625, 180.91615234), 'rotation':(0.071048, 8.3e-05, 0.070872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3117.16430664, 2388.41039062, 180.86728516), 'rotation':(0.186382, 0.000601, 0.185175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3094.95532227, 2388.41039062, 180.78646484), 'rotation':(0.227179, 0.000896, 0.225379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3255.01806641, 2380.52953125, 180.76390625), 'rotation':(0.298691, -179.998459, 0.295591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3260.55957031, 2380.52953125, 180.73173828), 'rotation':(0.328607, -179.998123, 0.324851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3266.10009766, 2380.52953125, 180.69931641), 'rotation':(0.335089, -179.998047, 0.331179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3271.63941406, 2380.52953125, 180.66572266), 'rotation':(0.349023, -179.997879, 0.344793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3293.79273438, 2380.52929688, 180.50335938), 'rotation':(0.459733, -179.996323, 0.452403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3299.32984375, 2380.52929688, 180.45566406), 'rotation':(0.487546, -179.99585, 0.479311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3310.40820312, 2380.5290625, 180.35222656000002), 'rotation':(0.542925, -179.994858, 0.53271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3315.94677734, 2380.5290625, 180.29826172), 'rotation':(0.556975, -179.994583, 0.546232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3349.17308594, 2380.52882812, 179.91619140999998), 'rotation':(0.750522, -179.990173, 0.731043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3349.18285156, 2388.4096875, 179.91607422), 'rotation':(-0.780396, 0.010628, -0.80188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3343.64601562, 2388.4096875, 179.98761718999998), 'rotation':(-0.750519, 0.009829, -0.770386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3327.03076172, 2388.4096875, 180.18341797000002), 'rotation':(-0.631317, 0.006953, -0.645355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3282.72021484, 2388.4096875, 180.59023438), 'rotation':(-0.43222, 0.003256, -0.438782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3271.64332031, 2388.4096875, 180.66570312), 'rotation':(-0.376709, 0.002472, -0.381683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3255.0234375, 2388.40992188, 180.76386718999998), 'rotation':(-0.328644, 0.00188, -0.332428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3243.94482422, 2388.40992188, 180.81894531), 'rotation':(-0.298706, 0.001552, -0.301819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3238.40771484, 2388.40992188, 180.84246094), 'rotation':(-0.251831, 0.001102, -0.254059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3221.78882812, 2388.40992188, 180.89314453), 'rotation':(-0.158295, 0.000432, -0.15918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3403.76464844, 2380.5178125, 179.07064452999998), 'rotation':(1.028927, -179.981506, 0.992465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3414.86375, 2380.52832031, 178.86576172000002), 'rotation':(1.070796, -179.979965, 1.031312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3420.41480469, 2380.52808594, 178.76005859), 'rotation':(1.10326, -179.978745, 1.06136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3431.51390625, 2380.52808594, 178.53851562), 'rotation':(1.168099, -179.976166, 1.121175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3442.60742188, 2380.52808594, 178.30341797), 'rotation':(1.232945, -179.973434, 1.180696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3453.70679688, 2380.52808594, 178.05445312), 'rotation':(1.297763, -179.970581, 1.239926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3459.2580468799997, 2380.5278125, 177.92705078), 'rotation':(1.314053, -179.969833, 1.254768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3470.35472656, 2380.5278125, 177.66585938), 'rotation':(1.340397, -179.968613, 1.278735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3475.90578125, 2380.5278125, 177.53078125), 'rotation':(1.393215, -179.966095, 1.326638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3453.75121094, 2388.40917969, 178.05341797), 'rotation':(-1.314056, 0.030159, -1.375427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3448.2009375, 2388.40917969, 178.17951172000002), 'rotation':(-1.29776, 0.029415, -1.357605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3437.1017968799997, 2388.40941406, 178.42181641), 'rotation':(-1.232941, 0.026547, -1.286896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3426.00097656, 2388.40941406, 178.65023438), 'rotation':(-1.168121, 0.023826, -1.216492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3414.89941406, 2388.40941406, 178.86509766), 'rotation':(-1.103271, 0.021252, -1.146393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3602.78027344, 2388.43433594, 173.69638672000002), 'rotation':(-2.01358, 0.103057, -2.159149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3586.13523438, 2388.42503906, 174.27542968999998), 'rotation':(-1.987274, 0.100536, -2.128998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3580.58445312, 2388.421875, 174.46310547000002), 'rotation':(-1.934265, 0.096893, -2.06842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3569.48804688, 2388.41601562, 174.83033203), 'rotation':(-1.881287, 0.093352, -2.008118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3563.93921875, 2388.41308594, 175.00875), 'rotation':(-1.881287, 0.093352, -2.008118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3558.3903906200003, 2388.41015625, 175.18603516), 'rotation':(-1.828308, 0.088479, -1.947998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3552.838125, 2388.40917969, 175.3609375), 'rotation':(-1.801941, 0.05676, -1.918152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3541.73730469, 2388.41722656, 175.70722656), 'rotation':(-1.776947, 0.055193, -1.889923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3536.1877343799997, 2388.41992188, 175.87566406000002), 'rotation':(-1.726929, 0.052126, -1.833588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3530.63820312, 2388.4221093799997, 176.04189452999998), 'rotation':(-1.726929, 0.052126, -1.833588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3525.08667969, 2388.38792969, 176.20458984), 'rotation':(-1.677063, 0.049153, -1.777527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3525.0434375, 2380.52734375, 176.20585938), 'rotation':(1.627135, -179.95372, 1.536564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3541.6909375, 2380.52710938, 175.70867188), 'rotation':(1.726959, -179.947861, 1.625049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3547.2424218799997, 2380.52710938, 175.53628906000003), 'rotation':(1.776949, -179.944809, 1.669122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3558.3403125, 2380.52808594, 175.18773438), 'rotation':(1.80177, -179.905228, 1.69095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3563.88820312, 2380.53078125, 175.01052734), 'rotation':(1.828373, -179.911499, 1.714281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3574.98730469, 2380.53664062, 174.64962891), 'rotation':(1.881307, -179.906647, 1.760581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3586.0803125, 2380.54273438, 174.27744141), 'rotation':(1.934255, -179.903107, 1.806725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3640.78785156, 2380.57203125, 172.31742188), 'rotation':(2.161174, -179.888077, 2.002379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3668.53421875, 2380.58691406, 171.25958984000002), 'rotation':(2.190052, -179.884995, 2.02704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3674.08421875, 2380.58984375, 171.04443359), 'rotation':(2.216792, -179.882935, 2.049831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3690.72632812, 2380.59886719, 170.38769531000003), 'rotation':(2.270246, -179.878738, 2.095237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3696.27539062, 2380.6017968799997, 170.16605468999998), 'rotation':(2.283517, -179.877319, 2.106489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3701.82328125, 2380.605, 169.944375), 'rotation':(2.283667, -179.877304, 2.106613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3712.92117188, 2380.61085938, 169.49886718999997), 'rotation':(2.291508, -179.878006, 2.113251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3712.97898438, 2388.49390625, 169.49636718999997), 'rotation':(-2.30722, 0.124748, -2.499176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3690.78078125, 2388.48195312, 170.38535156), 'rotation':(-2.283539, 0.122679, -2.471497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3685.2317187500003, 2388.47898438, 170.60599609000002), 'rotation':(-2.270264, 0.121264, -2.455994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3679.683125, 2388.47582031, 170.82507812), 'rotation':(-2.270264, 0.121264, -2.455994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3657.48460938, 2388.46386719, 171.68212891), 'rotation':(-2.190125, 0.114995, -2.362793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3646.38328125, 2388.46507812, 172.10470703), 'rotation':(-2.176697, 0.113354, -2.347229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3640.83324219, 2388.42847656, 172.31552734000002), 'rotation':(-2.176697, 0.113354, -2.347229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3745.4340625, 2380.6284375, 168.17316406), 'rotation':(2.35535, -179.872757, 2.167145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3756.5065624999997, 2380.63429688, 167.71599609), 'rotation':(2.361067, -179.87085, 2.171952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3767.5793750000003, 2380.64015625, 167.25855468999998), 'rotation':(2.361087, -179.872421, 2.171982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3773.11570312, 2380.64332031, 167.02962890999999), 'rotation':(2.363075, -179.870804, 2.173651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3789.72460938, 2380.65210938, 166.34142577999998), 'rotation':(2.369536, -179.869064, 2.179081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3795.26101562, 2380.65503906, 166.11197266), 'rotation':(2.369529, -179.871796, 2.17908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3800.79734375, 2380.65820312, 165.88246094), 'rotation':(2.369474, -179.869064, 2.179037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3811.8723437500003, 2380.6642968799997, 165.42462891), 'rotation':(2.360909, -179.871765, 2.171838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3817.4089062499997, 2380.6675, 165.19666016), 'rotation':(2.35537, -179.872223, 2.167176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3828.48265625, 2380.67335938, 164.74248047), 'rotation':(2.338247, -179.873642, 2.15273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3839.55617188, 2380.6794531200003, 164.29078125), 'rotation':(2.326984, -179.874557, 2.143232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3845.09007812, 2380.62425781, 164.06574218999998), 'rotation':(2.326984, -179.874557, 2.143232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3850.10226562, 2380.55566406, 163.86199219), 'rotation':(2.323965, -179.87471, 2.140683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3839.6640625, 2388.5627343799997, 164.28619141), 'rotation':(-2.323914, 0.125279, -2.518707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3834.12796875, 2388.55980469, 164.51171875), 'rotation':(-2.327087, 0.125452, -2.52243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3828.5915625, 2388.55664062, 164.73785156000002), 'rotation':(-2.33252, 0.125892, -2.528778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3823.05539062, 2388.55371094, 164.96458984), 'rotation':(-2.343964, 0.126829, -2.542175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3817.5190625, 2388.55078125, 165.19193359000002), 'rotation':(-2.349487, 0.127287, -2.548676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3789.8385937499997, 2388.53953125, 166.33652343999998), 'rotation':(-2.369537, 0.128208, -2.572205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3778.7668750000003, 2388.49683594, 166.79541016), 'rotation':(-2.369659, 0.128215, -2.572327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3773.2309375, 2388.49367188, 167.02466797), 'rotation':(-2.36731, 0.129538, -2.56958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3762.15945312, 2388.48730469, 167.48232422), 'rotation':(-2.363159, 0.129193, -2.564697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3751.08765625, 2388.48144531, 167.93960938), 'rotation':(-2.361084, 0.127573, -2.562286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.36304688, 2034.39296875, 161.41496094000001), 'rotation':(0.259588, 90.59185, 0.25724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2204.41773438, 2029.0787500000001, 161.39057617), 'rotation':(0.262949, 90.591103, 0.260542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2204.52734375, 2018.4503125, 161.34055664), 'rotation':(0.269301, 90.592865, 0.266785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.243125, 2034.47445312, 161.41496094000001), 'rotation':(-0.262939, -89.407166, -0.265381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.2981250000003, 2029.150625, 161.39054688), 'rotation':(-0.269318, -89.407104, -0.271851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.35304688, 2023.826875, 161.36561523), 'rotation':(-0.275879, -89.408752, -0.278534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.40796875, 2018.5032812499999, 161.34041992000002), 'rotation':(-0.275879, -89.408752, -0.278534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.46289062, 2013.1795312499999, 161.31480469), 'rotation':(-0.282227, -89.407013, -0.285034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.57273438, 2002.53257812, 161.26245117), 'rotation':(-0.285461, -89.407806, -0.2883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.02882812, 2066.75804688, 161.55864258), 'rotation':(0.236284, 90.590584, 0.234343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.97171875, 2072.29617188, 161.58169922), 'rotation':(0.22931, 90.592491, 0.227472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.91453125, 2077.83421875, 161.60426758), 'rotation':(0.22931, 90.592491, 0.227472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.85742188, 2083.3723437500003, 161.62635742), 'rotation':(0.222575, 90.592445, 0.220842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.8003125, 2088.91085938, 161.64787109), 'rotation':(0.218996, 90.591888, 0.217331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.743125, 2094.44875, 161.66910156), 'rotation':(0.218996, 90.591888, 0.217331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.68601562, 2099.98632812, 161.69020508), 'rotation':(0.213833, 90.592567, 0.212245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.62890625, 2105.52492188, 161.71085938), 'rotation':(0.203362, 90.591011, 0.201924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.5146875, 2116.60109375, 161.75076171999999), 'rotation':(0.192919, 90.592438, 0.191611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.45726562, 2122.1393749999997, 161.76969727), 'rotation':(0.192919, 90.592438, 0.191611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.34304688, 2133.21554688, 161.80598633), 'rotation':(0.177182, 90.590424, 0.176093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.22875, 2144.29148438, 161.84060546999999), 'rotation':(0.177168, 90.592987, 0.176091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.1535937500003, 2149.82859375, 161.85761719), 'rotation':(0.173459, 90.590813, 0.17241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2202.87085938, 2166.44289062, 161.90560546999998), 'rotation':(0.150524, 90.590706, 0.149731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2211.0425, 2163.36625, 161.89688476999999), 'rotation':(-0.165833, -89.40921, -0.166779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.069375, 2151.70164062, 161.86303711), 'rotation':(-0.173462, -89.407043, -0.1745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.109375, 2144.35570312, 161.84055664), 'rotation':(-0.177185, -89.406982, -0.178284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2211.33789062, 2122.20289062, 161.76963867), 'rotation':(-0.203369, -89.407501, -0.204834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.50929688, 2105.588125, 161.71080078), 'rotation':(-0.213837, -89.408875, -0.215454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.56640625, 2100.04929688, 161.69012695), 'rotation':(-0.218994, -89.408112, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.62351562, 2094.51195312, 161.6690332), 'rotation':(-0.222565, -89.407532, -0.224304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.680625, 2088.9739062500003, 161.64779296999998), 'rotation':(-0.222565, -89.407532, -0.224304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.7378125, 2083.43554688, 161.62629883), 'rotation':(-0.229309, -89.407501, -0.23114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.79492188, 2077.89695312, 161.60418945), 'rotation':(-0.236267, -89.40744, -0.238251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.90921875, 2066.82078125, 161.55856445), 'rotation':(-0.243134, -89.409363, -0.245209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2202.035625, 2259.9426562500003, 162.08918945), 'rotation':(0.068036, 90.590195, 0.067878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2202.15039062, 2248.8215625000003, 162.0746875), 'rotation':(0.07643, 90.59227, 0.076242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2202.26515625, 2237.70070312, 162.05789062), 'rotation':(0.088738, 90.592995, 0.088465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2202.29539062, 2232.14132812, 162.04888671999998), 'rotation':(0.088738, 90.592995, 0.088465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2202.316875, 2226.58054688, 162.03974609), 'rotation':(0.09412, 90.591331, 0.093811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2210.5793750000003, 2208.25710938, 162.00453125), 'rotation':(-0.126617, -89.408539, -0.127167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2210.23023438, 2232.20703125, 162.04885742), 'rotation':(-0.094116, -89.408661, -0.094421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2210.03078125, 2248.88742188, 162.07467773), 'rotation':(-0.084564, -89.407715, -0.084839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.97335938, 2254.4479687499997, 162.08222656), 'rotation':(-0.076416, -89.40976, -0.07663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.91601562, 2260.00875, 162.08916992000002), 'rotation':(-0.076416, -89.40976, -0.07663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.3893749999997, 2419.4765625, 162.08369141), 'rotation':(-0.071686, 90.591309, -0.071869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.44625, 2413.94996094, 162.08984375), 'rotation':(-0.063232, 90.591309, -0.063385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.5034375, 2408.42335938, 162.09570312), 'rotation':(-0.063232, 90.591309, -0.063385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2200.61742188, 2397.37011719, 162.10600586), 'rotation':(-0.050537, 90.591057, -0.050629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.6745312499997, 2391.84328125, 162.11086914), 'rotation':(-0.050537, 90.591057, -0.050629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.73140625, 2386.31761719, 162.11553711), 'rotation':(-0.050537, 90.591064, -0.050629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.84570312, 2375.26441406, 162.12298828000002), 'rotation':(-0.033203, 90.591347, -0.033234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2200.90257812, 2369.73804688, 162.12535156), 'rotation':(-0.021576, 90.591339, -0.021576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.9596874999997, 2364.21140625, 162.12695312), 'rotation':(-0.021576, 90.591339, -0.021576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2201.07375, 2353.15867188, 162.12823242000002), 'rotation':(-0.004303, 90.591484, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.13085938, 2347.63183594, 162.12864258), 'rotation':(-0.004303, 90.591484, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.18773438, 2342.105, 162.12907227), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.2448437499997, 2336.578125, 162.12948242000002), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.30171875, 2331.05101562, 162.12990234), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.35890625, 2325.52414062, 162.1303125), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.41578125, 2319.9973437500003, 162.13074219), 'rotation':(-0.004242, 90.590065, -0.004242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2201.586875, 2303.41992188, 162.12519531), 'rotation':(0.028448, 90.591087, 0.028412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.6440625, 2297.89304688, 162.12141602), 'rotation':(0.039233, 90.59185, 0.039182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.4674999999997, 2303.48734375, 162.12519531), 'rotation':(-0.039246, -89.410126, -0.039307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.1823437499997, 2331.11914062, 162.12990234), 'rotation':(0.004228, -89.408508, 0.00422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2209.12523438, 2336.64625, 162.12948242000002), 'rotation':(0.004317, -89.408508, 0.004307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.068125, 2342.1731250000003, 162.12907227), 'rotation':(0.004317, -89.408508, 0.004307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.01101562, 2347.70019531, 162.12864258), 'rotation':(0.004317, -89.408508, 0.004309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.9540625, 2353.22730469, 162.12823242000002), 'rotation':(0.004317, -89.408508, 0.004309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2208.89695312, 2358.75414062, 162.1278418), 'rotation':(0.004317, -89.408508, 0.004307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.6120312499997, 2386.3871875, 162.11555664), 'rotation':(0.044704, -89.40863, 0.044644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.3840625000003, 2408.49339844, 162.09572265999998), 'rotation':(0.054799, -89.408691, 0.054697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.26976562, 2419.546875, 162.08371094), 'rotation':(0.063248, -89.408722, 0.063113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.15578125, 2430.60058594, 162.06952148), 'rotation':(0.071683, -89.408691, 0.071515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.98460938, 2447.18066406, 162.04557617), 'rotation':(0.084462, -89.40802, 0.084219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.67875, 2573.76097656, 161.77206055), 'rotation':(0.152047, -89.40863, 0.151252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2206.79296875, 2562.6753125, 161.80167969000001), 'rotation':(0.147744, -89.40863, 0.14698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.85007812, 2557.13207031, 161.81597656), 'rotation':(0.143229, -89.408661, 0.142507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.96460938, 2546.0466406200003, 161.84397461), 'rotation':(0.141214, -89.406281, 0.140521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2207.02171875, 2540.50367188, 161.85766602), 'rotation':(0.141043, -89.408966, 0.140349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.0790625, 2534.9607031200003, 161.87130859), 'rotation':(0.13799, -89.409302, 0.137326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.365, 2507.24707031, 161.93495117), 'rotation':(0.118914, -89.407837, 0.118413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.4792187499997, 2496.16136719, 161.95782227), 'rotation':(0.115888, -89.409424, 0.115424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2207.5364062500003, 2490.61839844, 161.96902344), 'rotation':(0.115758, -89.407227, 0.115294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2198.9700000000003, 2557.05859375, 161.8159668), 'rotation':(-0.147736, 90.591347, -0.148499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.02710938, 2551.51609375, 161.83009765999998), 'rotation':(-0.147736, 90.591347, -0.148499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.25585938, 2529.34546875, 161.8846582), 'rotation':(-0.138, 90.592255, -0.138672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.37039062, 2518.26023438, 161.91055663999998), 'rotation':(-0.131531, 90.592201, -0.132141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.48484375, 2507.17480469, 161.93494141), 'rotation':(-0.125366, 90.590614, -0.125916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2199.54203125, 2501.63207031, 161.94644531), 'rotation':(-0.118896, 90.592155, -0.119415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.65601562, 2490.546875, 161.96901367), 'rotation':(-0.115906, 90.590569, -0.116364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.07398438, 2837.7109375, 160.91826172), 'rotation':(-0.197754, 90.592552, -0.199097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.2487499999997, 2820.77246094, 160.97671875), 'rotation':(-0.197723, 90.59256, -0.199097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2196.306875, 2815.12695312, 160.99618164), 'rotation':(-0.197418, 90.592552, -0.198792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.42359375, 2803.83447266, 161.03503906), 'rotation':(-0.197144, 90.590225, -0.198486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.59835938, 2786.89625, 161.09321289), 'rotation':(-0.196686, 90.593445, -0.198059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2196.65648438, 2781.25, 161.11260742000002), 'rotation':(-0.196838, 90.591339, -0.198181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.77320312, 2769.95800781, 161.15134766), 'rotation':(-0.196411, 90.591324, -0.197754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.06445312, 2741.72753906, 161.24736328), 'rotation':(-0.194092, 90.592819, -0.195404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.23921875, 2724.78955078, 161.30453125), 'rotation':(-0.192719, 90.59169, -0.194031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.47242188, 2702.2053125, 161.3796582), 'rotation':(-0.189362, 90.59166, -0.190613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.53054688, 2696.55908203, 161.39822266), 'rotation':(-0.188507, 90.59166, -0.189728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.58890625, 2690.91285156, 161.41671875), 'rotation':(-0.187469, 90.594009, -0.18869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.64695312, 2685.26683594, 161.43516602), 'rotation':(-0.187103, 90.590561, -0.188324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.82179688, 2668.32886719, 161.48993164), 'rotation':(-0.18338, 90.591957, -0.18457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2198.46265625, 2606.22265625, 161.68039062), 'rotation':(-0.167786, 90.590721, -0.168762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2206.16820312, 2623.2341406200003, 161.63029297), 'rotation':(0.171451, -89.407837, 0.170429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.11007812, 2628.88011719, 161.61314453), 'rotation':(0.171451, -89.407837, 0.170429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2206.05171875, 2634.52660156, 161.59588867), 'rotation':(0.175215, -89.409241, 0.17415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.9934375000003, 2640.17261719, 161.57844727), 'rotation':(0.1771, -89.406555, 0.176004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.93507812, 2645.81859375, 161.56098633), 'rotation':(0.176943, -89.408997, 0.175852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.81859375, 2657.11085938, 161.52576172), 'rotation':(0.17837, -89.40802, 0.177269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.7021875, 2668.40332031, 161.48996094), 'rotation':(0.180822, -89.408051, 0.179692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2205.64382812, 2674.04931641, 161.471875), 'rotation':(0.183391, -89.40802, 0.182214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.52734375, 2685.3415625, 161.43517578), 'rotation':(0.185843, -89.409515, 0.18464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.41085938, 2696.63402344, 161.39825195), 'rotation':(0.187461, -89.408325, 0.186241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.2942187500003, 2707.92652344, 161.36102539), 'rotation':(0.189374, -89.408325, 0.188129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.17773438, 2719.21875, 161.3234375), 'rotation':(0.191122, -89.408325, 0.189856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.119375, 2724.86523438, 161.30455078), 'rotation':(0.191997, -89.408295, 0.190712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2205.06101562, 2730.51123047, 161.28556641), 'rotation':(0.192727, -89.405945, 0.191436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.94460938, 2741.80371094, 161.24737305), 'rotation':(0.19421, -89.409119, 0.192898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.88625, 2747.44970703, 161.22824219), 'rotation':(0.19421, -89.409119, 0.192898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.828125, 2753.09619141, 161.20910156), 'rotation':(0.194087, -89.407166, 0.19277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.59523438, 2775.68115234, 161.13200195), 'rotation':(0.196402, -89.408691, 0.195061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.536875, 2781.32714844, 161.11262695), 'rotation':(0.196696, -89.406555, 0.195351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2204.47875, 2786.97339844, 161.09321289), 'rotation':(0.196826, -89.408691, 0.195479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.42039062, 2792.61988281, 161.07383789), 'rotation':(0.196696, -89.408691, 0.195346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.30398438, 2803.91210938, 161.03504883), 'rotation':(0.196839, -89.409729, 0.195507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.1875, 2815.20484375, 160.99618164), 'rotation':(0.19714, -89.40744, 0.195793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.12914062, 2820.85082031, 160.97672852), 'rotation':(0.197433, -89.40744, 0.196079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.01242188, 2832.14306641, 160.93776367), 'rotation':(0.197734, -89.407471, 0.196382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.9543750000003, 2837.78955078, 160.91826172), 'rotation':(0.197864, -89.407471, 0.196502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2480.27613281, 2007.73789062, 169.78128906), 'rotation':(0.202174, 99.520744, 0.200748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2477.25976562, 2024.2423437500001, 169.8290625), 'rotation':(0.140716, 100.911774, 0.140021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2475.15257812, 2035.19273438, 169.85640625), 'rotation':(0.138967, 100.728981, 0.13829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2489.11035156, 2002.74914062, 169.75697266), 'rotation':(-0.236023, -81.304108, -0.237976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2488.18285156, 2008.23226562, 169.77841797000002), 'rotation':(-0.209961, -80.754822, -0.211517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2487.24757812, 2013.7142187499999, 169.79693359), 'rotation':(-0.184265, -80.198914, -0.185455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2485.2065625, 2024.6516406199999, 169.82634765999998), 'rotation':(-0.140747, -79.088409, -0.141449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2484.1872656200003, 2030.1396875, 169.84005859), 'rotation':(-0.140747, -79.088409, -0.141449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2483.23558594, 2035.64101562, 169.85376953), 'rotation':(-0.140717, -79.088226, -0.141418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.31398438, 2072.75710938, 169.97052734000002), 'rotation':(0.209093, 96.192558, 0.207578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.86449219, 2078.26125, 169.99066406000003), 'rotation':(0.209093, 95.607422, 0.207576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.45019531, 2094.80492188, 170.05347656), 'rotation':(0.232042, 93.839989, 0.230178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.10007812, 2100.336875, 170.07638672000002), 'rotation':(0.242424, 93.254059, 0.240392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2466.81054688, 2105.87476562, 170.10037109), 'rotation':(0.252498, 92.663353, 0.250287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2466.20972656, 2133.59859375, 170.23519531000002), 'rotation':(0.280987, 90.448204, 0.278246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2466.16648438, 2139.14914062, 170.2628125), 'rotation':(0.271855, 90.448112, 0.269282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2466.12351562, 2144.70015625, 170.28949218999998), 'rotation':(0.262539, 90.445274, 0.260146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2466.0803125, 2150.2512500000003, 170.31517578), 'rotation':(0.253236, 90.447952, 0.250999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.8728125, 2161.51125, 170.36402343999998), 'rotation':(-0.24411, -89.552124, -0.246185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.95945312, 2150.4426562500003, 170.31576172), 'rotation':(-0.262543, -89.551941, -0.264954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2474.04566406, 2139.3723437500003, 170.26361328), 'rotation':(-0.280975, -89.551788, -0.283752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2474.43554688, 2117.19234375, 170.15166016), 'rotation':(-0.279449, -88.520844, -0.282196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2474.83546875, 2106.06617188, 170.09955078), 'rotation':(-0.253021, -87.042114, -0.25528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2475.48265625, 2094.96460938, 170.05185547000002), 'rotation':(-0.232086, -85.864532, -0.233948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2475.79566406, 2089.4153125000003, 170.02972656000003), 'rotation':(-0.221771, -85.269714, -0.223511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2476.23632812, 2083.88132812, 170.00865234), 'rotation':(-0.21405, -84.678711, -0.215668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2477.38039062, 2072.85765625, 169.96759766), 'rotation':(-0.209595, -83.415527, -0.211121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2465.17820312, 2266.03367188, 170.67324219), 'rotation':(0.090295, 90.445869, 0.09001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2465.26488281, 2254.90773438, 170.65275391), 'rotation':(0.106742, 90.445961, 0.106339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2465.3513281200003, 2243.78273438, 170.62886719), 'rotation':(0.131249, 90.446075, 0.13064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2465.43824219, 2232.65695312, 170.60160156), 'rotation':(0.147518, 90.448814, 0.14677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.058125, 2266.0950000000003, 170.67326172), 'rotation':(-0.098511, -89.551392, -0.098846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.18796875, 2249.4071875, 170.64123047), 'rotation':(-0.123169, -89.553955, -0.123718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.23121094, 2243.84421875, 170.62888672), 'rotation':(-0.139465, -89.553894, -0.140137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.36132812, 2227.15578125, 170.58701172000002), 'rotation':(-0.151733, -89.551636, -0.152527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.40476562, 2221.5924999999997, 170.57226562), 'rotation':(-0.151733, -89.551636, -0.152527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.46191406, 2216.03148438, 170.55744141), 'rotation':(-0.157166, -89.555115, -0.15802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.57640625, 2210.47023438, 170.54189452999998), 'rotation':(-0.167877, -89.552307, -0.168854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.3203125, 2376.14257812, 170.71810547), 'rotation':(-0.038788, 90.446022, -0.038818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.36351562, 2370.5915625, 170.72185547), 'rotation':(-0.038605, 90.446037, -0.038666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.57984375, 2342.84007812, 170.72927734), 'rotation':(0.015204, 90.446571, 0.015186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.62304688, 2337.2890625, 170.72777344), 'rotation':(0.015204, 90.446571, 0.015186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2464.92578125, 2298.4340625, 170.71458984), 'rotation':(0.025306, 90.446915, 0.02528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.24339844, 2370.65308594, 170.72185547), 'rotation':(0.038782, -89.551208, 0.038732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.33007812, 2359.55273438, 170.72894531000003), 'rotation':(0.025183, -89.555115, 0.025166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.37304688, 2354.00242188, 170.7309375), 'rotation':(-0.001801, -89.552948, -0.001801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2472.41625, 2348.453125, 170.73076172), 'rotation':(-0.015198, -89.553406, -0.015228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.45972656, 2342.90210938, 170.72927734), 'rotation':(-0.015289, -89.553436, -0.015289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.50292969, 2337.35109375, 170.72777344), 'rotation':(-0.015289, -89.553436, -0.015289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.54613281, 2331.80007812, 170.72630859), 'rotation':(-0.015198, -89.553406, -0.015228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.6328125, 2320.6979687499997, 170.72335938), 'rotation':(-0.015289, -89.553436, -0.015289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2463.88328125, 2415.56984375, 170.68042968999998), 'rotation':(-0.086456, 90.447166, -0.0867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.85230469, 2436.16234375, 170.64796875), 'rotation':(-0.099304, 90.44632, -0.09964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.80933594, 2441.69066406, 170.63839843999997), 'rotation':(-0.103699, 90.44632, -0.104095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2463.68042969, 2458.27585938, 170.60685547), 'rotation':(-0.11731, 90.446365, -0.117798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.59449219, 2469.3325, 170.58351562), 'rotation':(-0.126312, 90.446404, -0.126892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2463.37890625, 2496.97265625, 170.51945312), 'rotation':(-0.142212, 90.446159, -0.142944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.3359375, 2502.50097656, 170.505625), 'rotation':(-0.14621, 90.448601, -0.146942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.2497656200003, 2513.55738281, 170.47685547), 'rotation':(-0.153992, 90.446198, -0.154846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.20679688, 2519.0859375, 170.46193359), 'rotation':(-0.15799, 90.446213, -0.158844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.12035156, 2530.14183594, 170.43125), 'rotation':(-0.162231, 90.447266, -0.163177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.99121094, 2546.7265625, 170.38402344), 'rotation':(-0.17157, 90.447296, -0.172577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2462.75609375, 2568.83472656, 170.31707031000002), 'rotation':(-0.178619, 90.446922, -0.179718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.7419531200003, 2563.37378906, 170.33416015999998), 'rotation':(0.176294, -89.552673, 0.175223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.78492188, 2557.84570312, 170.35115234), 'rotation':(0.171547, -89.552704, 0.170526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.828125, 2552.31714844, 170.36771484000002), 'rotation':(0.166882, -89.552734, 0.165925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.87109375, 2546.7890625, 170.38402344), 'rotation':(0.166882, -89.552734, 0.165925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2470.9142968799997, 2541.26074219, 170.40007812), 'rotation':(0.162231, -89.552734, 0.161315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.9575, 2535.73242188, 170.41574218999997), 'rotation':(0.159861, -89.553772, 0.158971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.00046875, 2530.20410156, 170.43125), 'rotation':(0.159861, -89.553772, 0.158971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.12964844, 2513.61960938, 170.47685547), 'rotation':(0.150039, -89.553772, 0.149248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.21582031, 2502.56296875, 170.505625), 'rotation':(0.142225, -89.553833, 0.141517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.30199219, 2491.50660156, 170.53291016), 'rotation':(0.134411, -89.553894, 0.133791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.34496094, 2485.97828125, 170.54599609000002), 'rotation':(0.13058, -89.553894, 0.129995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.38820312, 2480.45019531, 170.55875), 'rotation':(0.128571, -89.552917, 0.127998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.51710938, 2463.86597656, 170.59541016), 'rotation':(0.117315, -89.553619, 0.116827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.56007812, 2458.33765625, 170.60685547), 'rotation':(0.112725, -89.55365, 0.112284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2471.64625, 2447.2810156200003, 170.62833984), 'rotation':(0.103703, -89.55368, 0.103335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.68945312, 2441.75292969, 170.63839843999997), 'rotation':(0.099284, -89.553711, 0.098947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.775625, 2430.69703125, 170.65705078), 'rotation':(0.092399, -89.553436, 0.092102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2472.02246094, 2415.6328125, 170.68042968999998), 'rotation':(0.074005, -89.552856, 0.07383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.40308594, 2750.53369141, 169.70882812), 'rotation':(-0.192383, 90.446037, -0.193695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.53246094, 2733.94605469, 169.76492188), 'rotation':(-0.194427, 90.447693, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.57542969, 2728.41699219, 169.78375), 'rotation':(-0.194427, 90.447693, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2461.66164062, 2717.35816406, 169.82152344), 'rotation':(-0.195862, 90.447411, -0.197174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.70484375, 2711.82910156, 169.84044922), 'rotation':(-0.195862, 90.447411, -0.197174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.92015625, 2684.18310547, 169.93501952999998), 'rotation':(-0.196106, 90.448143, -0.197449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.00632812, 2673.12451172, 169.97287109), 'rotation':(-0.196106, 90.44632, -0.197449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2462.22167969, 2645.47828125, 170.06716797), 'rotation':(-0.193481, 90.444885, -0.194794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.26488281, 2639.94921875, 170.08578125), 'rotation':(-0.192474, 90.447624, -0.193756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.35082031, 2628.8908593799997, 170.12285156000002), 'rotation':(-0.191925, 90.44696, -0.193237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2462.43703125, 2617.83277344, 170.15984375), 'rotation':(-0.191925, 90.44696, -0.193237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.5234375, 2606.77417969, 170.19646484), 'rotation':(-0.188965, 90.446335, -0.190216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.56640625, 2601.24511719, 170.21451172000002), 'rotation':(-0.186981, 90.446312, -0.188202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.28320312, 2750.59570312, 169.70882812), 'rotation':(0.19352, -89.553955, 0.192207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.32617188, 2745.06640625, 169.72748047000002), 'rotation':(0.19352, -89.553955, 0.192207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.41234375, 2734.0078125, 169.76492188), 'rotation':(0.195466, -89.552307, 0.194146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.49851562, 2722.94945312, 169.80263672), 'rotation':(0.195856, -89.554169, 0.194522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.58472656, 2711.89111328, 169.84044922), 'rotation':(0.195951, -89.552582, 0.194618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.62769531, 2706.36207031, 169.85935547), 'rotation':(0.196013, -89.553223, 0.194677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2469.67089844, 2700.83251953, 169.87826172), 'rotation':(0.196013, -89.551514, 0.194688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.8003125, 2684.24488281, 169.93501952999998), 'rotation':(0.196095, -89.551849, 0.194766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.84328125, 2678.71558594, 169.95394531000002), 'rotation':(0.196095, -89.551849, 0.194766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2470.14476562, 2640.01125, 170.08578125), 'rotation':(0.191942, -89.55304, 0.190654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.2309375, 2628.953125, 170.12285156000002), 'rotation':(0.191942, -89.55304, 0.190654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.30101562, 3020.32592773, 168.87845703), 'rotation':(-0.163971, 90.446831, -0.164917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2459.38914062, 3009.01464844, 168.91085938), 'rotation':(-0.163971, 90.446831, -0.164917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.47730469, 2997.70361328, 168.94328125), 'rotation':(-0.164429, 90.44706, -0.165344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.52125, 2992.04760742, 168.95955078), 'rotation':(-0.164429, 90.44706, -0.165344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2459.56542969, 2986.39233398, 168.97587891), 'rotation':(-0.165314, 90.447083, -0.16629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2459.78589844, 2958.11450195, 169.05775391), 'rotation':(-0.166504, 90.446434, -0.16745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.96191406, 2935.4921875, 169.12421875), 'rotation':(-0.169281, 90.446465, -0.170258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2460.00609375, 2929.83691406, 169.14105468999998), 'rotation':(-0.170746, 90.447952, -0.171753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.09105469, 2918.52319336, 169.17486327999998), 'rotation':(-0.171387, 90.446106, -0.172394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.13820312, 2912.87011719, 169.19177734000002), 'rotation':(-0.171387, 90.448463, -0.172394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.18238281, 2907.21435547, 169.20869141), 'rotation':(-0.171387, 90.446083, -0.172394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.40257812, 2878.93652344, 169.29476562), 'rotation':(-0.17627, 90.447823, -0.177338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.44679688, 2873.28076172, 169.3121875), 'rotation':(-0.17627, 90.445496, -0.177368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.57886719, 2856.31396484, 169.36457031), 'rotation':(-0.177399, 90.446236, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.66699219, 2845.00292969, 169.4), 'rotation':(-0.179382, 90.447693, -0.180511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.84328125, 2822.38037109, 169.47226562), 'rotation':(-0.184601, 90.447655, -0.185791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2460.93140625, 2811.06910156, 169.50869140999998), 'rotation':(-0.184601, 90.447655, -0.185791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2460.97558594, 2805.41382812, 169.52689453), 'rotation':(-0.184448, 90.447678, -0.185638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.01953125, 2799.75804688, 169.54525390999999), 'rotation':(-0.186005, 90.446198, -0.187225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.98753906, 2788.50707031, 169.58242188), 'rotation':(0.190439, -89.552979, 0.189183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.89941406, 2799.818125, 169.54525390999999), 'rotation':(0.188875, -89.553772, 0.187642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.85546875, 2805.4709375, 169.52691406000002), 'rotation':(0.186007, -89.552124, 0.184803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.81128906, 2811.12914062, 169.50869140999998), 'rotation':(0.184436, -89.554932, 0.183258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.76734375, 2816.78492188, 169.49046875), 'rotation':(0.1846, -89.552338, 0.183416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.635, 2833.75195312, 169.4359375), 'rotation':(0.183452, -89.553741, 0.182293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2468.546875, 2845.0625, 169.4), 'rotation':(0.181464, -89.552277, 0.180315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.45875, 2856.37426758, 169.36457031), 'rotation':(0.179388, -89.553741, 0.178259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.370625, 2867.68505859, 169.32957031), 'rotation':(0.17738, -89.552307, 0.176286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.32664062, 2873.34106445, 169.3121875), 'rotation':(0.176417, -89.554504, 0.175338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.28273438, 2878.99633789, 169.29476562), 'rotation':(0.176253, -89.552155, 0.175188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.10644531, 2901.61865234, 169.22564452999998), 'rotation':(0.172578, -89.554138, 0.171552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.01832031, 2912.93017578, 169.19177734000002), 'rotation':(0.171369, -89.553894, 0.17035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.88597656, 2929.89672852, 169.14105468999998), 'rotation':(0.171369, -89.551514, 0.170353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2467.79785156, 2941.20825195, 169.1075), 'rotation':(0.169266, -89.553528, 0.16827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.70972656, 2952.51904297, 169.07425781), 'rotation':(0.16779, -89.552063, 0.16681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.66578125, 2958.17456055, 169.05775391), 'rotation':(0.16779, -89.552063, 0.16681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2467.6215625, 2963.83032227, 169.04132812), 'rotation':(0.166493, -89.553558, 0.165529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.48925781, 2980.79711914, 168.99222656), 'rotation':(0.165694, -89.554016, 0.164736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.3571875, 2997.76416016, 168.94328125), 'rotation':(0.165318, -89.554749, 0.16437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.26929688, 3009.07519531, 168.91085938), 'rotation':(0.164136, -89.553162, 0.163193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.22507812, 3014.73071289, 168.89466797), 'rotation':(0.163986, -89.553192, 0.163045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.18117188, 3020.38623047, 168.87845703), 'rotation':(0.164, -89.553162, 0.163051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2868.17211914, 2040.15039062, 176.24130859000002), 'rotation':(-0.516022, -83.506897, -0.52536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2871.11035156, 2018.65539062, 176.04748047), 'rotation':(-0.512817, -81.134888, -0.522064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2871.95581055, 2013.29835938, 175.99908202999998), 'rotation':(-0.512817, -80.546692, -0.522064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2872.70703125, 2007.9415625000001, 175.95101562), 'rotation':(-0.512634, -80.402649, -0.521851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.59399414, 2075.70632812, 176.56617188), 'rotation':(-0.526703, -87.861572, -0.536438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.02075195, 2173.19875, 177.40873047000002), 'rotation':(0.460416, 90.191574, 0.453052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.0390625, 2167.59835938, 177.36373047), 'rotation':(0.460416, 90.191574, 0.453052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.12060547, 2161.99804688, 177.31873047000002), 'rotation':(0.460416, 90.193161, 0.453054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.17260742, 2150.7978125, 177.22751953), 'rotation':(0.469712, 90.19278, 0.462063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.20751953, 2145.19773438, 177.18105469), 'rotation':(0.475928, 90.192879, 0.468073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.25878906, 2139.59789062, 177.13400391), 'rotation':(0.482129, 90.190567, 0.474058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2857.38671875, 2105.99804688, 176.84017577999998), 'rotation':(0.510024, 90.193962, 0.501019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.42333984, 2094.79734375, 176.73998047), 'rotation':(0.514006, 90.192497, 0.504852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.45092773, 2089.20382812, 176.68990234), 'rotation':(0.510099, 90.412117, 0.501075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.52587891, 2083.6184375000003, 176.63986328), 'rotation':(0.511451, 90.8452, 0.502386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2865.40307617, 2083.85328125, 176.64060547), 'rotation':(-0.524567, -88.717102, -0.534271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.33007812, 2089.45140625, 176.6915625), 'rotation':(-0.523621, -89.153168, -0.533264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.21166992, 2122.975625, 176.990625), 'rotation':(-0.506958, -89.80658, -0.515991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.19311523, 2128.5598437500003, 177.03927734), 'rotation':(-0.500732, -89.806702, -0.509552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2865.15625, 2139.72703125, 177.13486328), 'rotation':(-0.488342, -89.806885, -0.496704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2865.13793945, 2145.31101562, 177.18177734), 'rotation':(-0.482117, -89.807007, -0.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.11914062, 2150.895, 177.228125), 'rotation':(-0.475952, -89.807098, -0.483917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.72363281, 2268.03609375, 178.10859375), 'rotation':(0.370326, 90.18988, 0.365564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.76928711, 2260.33421875, 178.05855469), 'rotation':(0.371883, 90.191963, 0.367082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.94628906, 2239.80789062, 177.92324219), 'rotation':(0.385202, 90.192062, 0.380066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.96484375, 2234.16382812, 177.88443359000001), 'rotation':(0.385202, 90.192062, 0.380066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.00195312, 2222.8728125, 177.80310547000002), 'rotation':(0.419524, 90.192719, 0.41342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.02050781, 2217.2275, 177.76037109), 'rotation':(0.435828, 90.191086, 0.429247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.03930664, 2211.58226562, 177.7165625), 'rotation':(0.435828, 90.191086, 0.429247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.05786133, 2205.93796875, 177.67183594), 'rotation':(0.452247, 90.193207, 0.445143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.93798828, 2205.96390625, 177.67183594), 'rotation':(-0.460327, -89.806274, -0.467773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.91943359, 2211.6081249999997, 177.7165625), 'rotation':(-0.452271, -89.808655, -0.459442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.88208008, 2222.89867188, 177.80310547000002), 'rotation':(-0.435822, -89.807037, -0.442505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.8449707, 2234.1896875, 177.88443359000001), 'rotation':(-0.403107, -89.807526, -0.408813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.79760742, 2249.0703125, 177.98480468999998), 'rotation':(-0.375732, -89.809937, -0.380707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.86303711, 2268.0625, 178.10859375), 'rotation':(-0.371887, -89.808044, -0.37674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2856.70825195, 2312.10226562, 178.38837891), 'rotation':(0.347984, 90.192223, 0.34379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.68969727, 2317.74242188, 178.4225), 'rotation':(0.342063, 90.190056, 0.337988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2856.65258789, 2329.02273438, 178.48955078), 'rotation':(0.335704, 90.18927, 0.331781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.6340332, 2334.6628124999997, 178.52269531000002), 'rotation':(0.328928, 90.190155, 0.325177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.57836914, 2351.58324219, 178.61908203), 'rotation':(0.315241, 90.189995, 0.311787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.55981445, 2357.22339844, 178.65003906), 'rotation':(0.308533, 90.189934, 0.305222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.52270508, 2368.50367188, 178.71046875), 'rotation':(0.305193, 90.191742, 0.301971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.62548828, 2300.8464062499997, 178.31869140999999), 'rotation':(-0.359741, -89.809723, -0.364288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.60693359, 2306.4870312499997, 178.35376953), 'rotation':(-0.359741, -89.809723, -0.364288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.58837891, 2312.1271875, 178.38835938), 'rotation':(-0.353821, -89.807709, -0.358215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.57006836, 2317.76757812, 178.4225), 'rotation':(-0.348022, -89.809875, -0.352264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.55151367, 2323.40773438, 178.45615234000002), 'rotation':(-0.342072, -89.809937, -0.346161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.53295898, 2329.04859375, 178.48955078), 'rotation':(-0.339081, -89.808838, -0.343109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.49584961, 2340.32859375, 178.55541015999998), 'rotation':(-0.335724, -89.808594, -0.339661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.47729492, 2345.9689843799997, 178.58751952999998), 'rotation':(-0.328918, -89.809814, -0.332733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.42163086, 2362.89015625, 178.68042968999998), 'rotation':(-0.308533, -89.810059, -0.311859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.375, 2332.1042187499997, 179.03287109000001), 'rotation':(0.526075, 90.452911, 0.51648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3374.50539062, 2315.47046875, 178.87863281000003), 'rotation':(0.532413, 90.453049, 0.522586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.54859375, 2309.92554688, 178.82693359), 'rotation':(0.534121, 90.452812, 0.524236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.63550781, 2298.83617188, 178.72367188), 'rotation':(0.533322, 90.452156, 0.52345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.67894531, 2293.29148438, 178.67207031), 'rotation':(0.533001, 90.454475, 0.523163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.8090625, 2276.6575000000003, 178.51753906000002), 'rotation':(0.531703, 90.452126, 0.521913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.89601562, 2265.568125, 178.41472656000002), 'rotation':(0.530829, 90.454437, 0.52106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.98265625, 2254.4778125000003, 178.31232422000002), 'rotation':(0.529114, 90.453415, 0.519414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3375.02613281, 2248.933125, 178.26154297000002), 'rotation':(0.526143, 90.453362, 0.516545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3375.1996875, 2226.75367188, 178.06117188), 'rotation':(0.513678, 90.453125, 0.504535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3383.16699219, 2215.71679688, 177.96259766), 'rotation':(-0.506134, -89.546478, -0.515167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3383.0803125, 2226.80664062, 178.06109375), 'rotation':(-0.510712, -89.546875, -0.519867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.6896875, 2276.7096874999997, 178.51746093999998), 'rotation':(-0.531403, -89.547882, -0.541351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3382.64625, 2282.25460938, 178.56894531), 'rotation':(-0.531677, -89.545532, -0.541626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.5158593799997, 2298.88867188, 178.72357422000002), 'rotation':(-0.53302, -89.547852, -0.542999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.2990625, 2326.61179688, 178.98154297000002), 'rotation':(-0.53241, -89.546936, -0.542389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.21214844, 2337.70070312, 179.08388672), 'rotation':(-0.529236, -89.546997, -0.539093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.16871094, 2343.24539062, 179.13480468999998), 'rotation':(-0.526093, -89.545654, -0.535828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3382.08203125, 2354.33472656, 179.23613281000002), 'rotation':(-0.522827, -89.547119, -0.53244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.03859375, 2359.87890625, 179.28662109), 'rotation':(-0.521271, -89.546326, -0.530823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.06957031, 2367.23167969, 179.35337891), 'rotation':(-0.519287, -89.548096, -0.528748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3371.61035156, 2685.38134766, 181.17951172000002), 'rotation':(0.028557, 90.446693, 0.028537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3371.69875, 2674.10253906, 181.17234375), 'rotation':(0.042224, 90.447563, 0.042171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3371.74292969, 2668.46191406, 181.16550781), 'rotation':(0.069641, 90.449806, 0.069474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.05152344, 2628.98363281, 181.07347656000002), 'rotation':(0.166363, 90.450401, 0.165402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.13988281, 2617.70460938, 181.03796875), 'rotation':(0.189087, 90.450539, 0.187853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.22828125, 2606.42480469, 180.99757812), 'rotation':(0.211989, 90.450691, 0.210428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.27246094, 2600.78492188, 180.97552734), 'rotation':(0.223443, 90.448097, 0.221701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.31664062, 2595.14550781, 180.95292969), 'rotation':(0.229057, 90.450401, 0.227227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.36085938, 2589.50511719, 180.92966797), 'rotation':(0.234433, 90.447968, 0.232539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.49292969, 2572.5859375, 180.85310547), 'rotation':(0.266418, 90.450951, 0.26395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.53710938, 2566.9455468799997, 180.8253125), 'rotation':(0.28779, 90.451164, 0.28492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.62546875, 2555.66527344, 180.76634765999998), 'rotation':(0.308984, 90.448677, 0.305677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.66945312, 2550.02585938, 180.73554688000002), 'rotation':(0.314414, 90.450188, 0.310984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.71363281, 2544.38625, 180.70425781000003), 'rotation':(0.314414, 90.450188, 0.310984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.7578125, 2538.745625, 180.67244141), 'rotation':(0.323205, 90.451195, 0.31957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.80199219, 2533.1059375, 180.63941406), 'rotation':(0.323205, 90.451195, 0.31957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3372.84617188, 2527.46507812, 180.60585938), 'rotation':(0.340956, 90.449951, 0.336922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.93433594, 2516.18675781, 180.53476562), 'rotation':(0.358605, 90.450157, 0.354132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.02246094, 2504.9064843799997, 180.46017578), 'rotation':(0.376166, 90.451851, 0.371241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.11085938, 2493.62671875, 180.38361328), 'rotation':(0.389068, 90.451256, 0.383805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3373.15503906, 2487.9865625, 180.34423827999998), 'rotation':(0.397107, 90.451363, 0.391628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.19898438, 2482.34667969, 180.3040625), 'rotation':(0.404948, 90.451447, 0.399263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.24316406, 2476.70777344, 180.26304688), 'rotation':(0.420692, 90.451668, 0.414542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.28710938, 2471.06789062, 180.22119141), 'rotation':(0.428902, 90.451813, 0.422531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.4196875, 2454.14796875, 180.09099609), 'rotation':(0.444604, 90.452034, 0.437763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.55226562, 2437.22851562, 179.95697266), 'rotation':(0.453887, 90.451759, 0.446738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.59617188, 2431.58835938, 179.91123047000002), 'rotation':(0.464548, 90.45195, 0.457066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3373.6403906200003, 2425.94800781, 179.86443359), 'rotation':(0.475074, 90.45211, 0.467261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.68457031, 2420.308125, 179.81712890999998), 'rotation':(0.475074, 90.45211, 0.467261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.81566406, 2403.55273438, 179.67400390999998), 'rotation':(0.491015, 90.452057, 0.482666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.65332031, 2409.08082031, 179.72085938), 'rotation':(-0.491028, -89.545441, -0.499512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.56519531, 2420.36058594, 179.81705078), 'rotation':(-0.485748, -89.547699, -0.494049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3381.52101562, 2426.00046875, 179.86435547000002), 'rotation':(-0.485748, -89.547699, -0.494049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3381.43261719, 2437.2810156200003, 179.95689453), 'rotation':(-0.464539, -89.548065, -0.472137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.3884375, 2442.92089844, 180.00208984), 'rotation':(-0.464539, -89.548065, -0.472137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.21191406, 2465.48070312, 180.17847656), 'rotation':(-0.444641, -89.547974, -0.451569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.07960938, 2482.400625, 180.30400391), 'rotation':(-0.412811, -89.548401, -0.418793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.99144531, 2493.68089844, 180.38355468999998), 'rotation':(-0.397095, -89.548645, -0.402649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.85890625, 2510.60082031, 180.49767577999998), 'rotation':(-0.385101, -89.547668, -0.390289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.7263281200003, 2527.52027344, 180.60582031), 'rotation':(-0.358612, -89.54837, -0.363098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.68238281, 2533.16136719, 180.63939453), 'rotation':(-0.340942, -89.550049, -0.345032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.6384375, 2538.80101562, 180.67240234000002), 'rotation':(-0.340942, -89.550049, -0.345032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.50609375, 2555.72144531, 180.76630859), 'rotation':(-0.314423, -89.549805, -0.317871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.46191406, 2561.36179688, 180.79636718999998), 'rotation':(-0.30899, -89.548615, -0.312347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3380.4175, 2567.00171875, 180.82529297000002), 'rotation':(-0.298401, -89.548737, -0.301514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.37328125, 2572.64210938, 180.85306641), 'rotation':(-0.277008, -89.54895, -0.279724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.19652344, 2595.20238281, 180.95291016), 'rotation':(-0.234436, -89.549316, -0.236359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.15234375, 2600.84226562, 180.97550781), 'rotation':(-0.229065, -89.549591, -0.230896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.10816406, 2606.48265625, 180.99755859), 'rotation':(-0.22345, -89.55191, -0.225189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.97582031, 2623.40210938, 181.05632812), 'rotation':(-0.189087, -89.552155, -0.190338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3379.88769531, 2634.68261719, 181.08945312), 'rotation':(-0.166351, -89.552277, -0.167328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.66675781, 2662.88328125, 181.15626953), 'rotation':(-0.124207, -89.552216, -0.124725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.57859375, 2674.16308594, 181.17234375), 'rotation':(-0.069641, -89.552399, -0.069824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.53441406, 2679.80296875, 181.17652343999998), 'rotation':(-0.042236, -89.550232, -0.042297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.49023438, 2685.443125, 181.17951172000002), 'rotation':(-0.028564, -89.553284, -0.028595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.44628906, 2691.08349609, 181.18234375), 'rotation':(-0.028564, -89.55072, -0.028595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3379.40210938, 2696.724375, 181.18515625), 'rotation':(-0.028717, -89.55069, -0.028748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.21507812, 2756.79736328, 183.73201172), 'rotation':(0.138994, 90.200233, 0.138324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.23486328, 2751.13476562, 183.71775391), 'rotation':(0.14523, 90.198875, 0.144497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.25439453, 2745.47167969, 183.70238281000002), 'rotation':(0.15749, 90.198959, 0.156626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.27417969, 2739.80859375, 183.68574218999998), 'rotation':(0.169566, 90.199028, 0.168584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.29371094, 2734.14550781, 183.66785156000003), 'rotation':(0.181984, 90.199104, 0.180838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.33300781, 2722.82128906, 183.62833984), 'rotation':(0.206326, 90.199265, 0.204853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.39208984, 2705.83349609, 183.55982422), 'rotation':(0.241249, 90.198051, 0.239236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.41162109, 2700.17041016, 183.53494141), 'rotation':(0.249848, 90.200836, 0.247689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.4509375, 2688.84521484, 183.48246093999998), 'rotation':(0.266726, 90.200989, 0.264251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.47070312, 2683.18212891, 183.45484375), 'rotation':(0.283617, 90.198463, 0.280812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.49023438, 2677.51904297, 183.42632812), 'rotation':(0.292032, 90.201233, 0.289068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.51, 2671.8559375, 183.39689453), 'rotation':(0.300638, 90.201324, 0.297497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.52953125, 2666.19335938, 183.366875), 'rotation':(0.304879, 90.200661, 0.301649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.58837891, 2649.20507812, 183.27177734), 'rotation':(0.331018, 90.200218, 0.327211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.62769531, 2637.88039062, 183.20357422), 'rotation':(0.348401, 90.201881, 0.344182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.66675781, 2626.55515625, 183.13113281000003), 'rotation':(0.365962, 90.20063, 0.361331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.78466797, 2592.57933594, 182.89625), 'rotation':(0.414948, 90.202003, 0.408971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.80445312, 2586.91625, 182.85363281000002), 'rotation':(0.431053, 90.202225, 0.424608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.82398438, 2581.25390625, 182.81083984), 'rotation':(0.431053, 90.202225, 0.424608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.84375, 2575.59226562, 182.76712891), 'rotation':(0.439229, 90.203537, 0.432541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.86351562, 2569.92921875, 182.72298827999998), 'rotation':(0.446271, 90.201752, 0.439361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.88304688, 2564.26636719, 182.67789062), 'rotation':(0.446271, 90.201752, 0.439361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.92236328, 2552.94042969, 182.58550781000002), 'rotation':(0.474835, 90.203621, 0.467012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.94189453, 2547.2778125, 182.53830078), 'rotation':(0.474835, 90.203621, 0.467012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.96142578, 2541.61449219, 182.48994141), 'rotation':(0.489151, 90.202454, 0.480861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.98095703, 2535.9533593799997, 182.44130859), 'rotation':(0.489151, 90.202454, 0.480861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.04003906, 2518.96558594, 182.29193359), 'rotation':(0.502572, 90.202499, 0.493819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.05957031, 2513.30320312, 182.24091797), 'rotation':(0.514723, 90.204285, 0.505551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.11865234, 2496.31445312, 182.08271484), 'rotation':(0.539489, 90.204735, 0.529401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.15771484, 2484.99171875, 181.97478515999998), 'rotation':(0.545602, 90.204613, 0.53528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.21679688, 2468.00316406, 181.80966797000002), 'rotation':(0.560137, 90.204391, 0.549256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.23632812, 2462.3403125, 181.75333984), 'rotation':(0.569665, 90.204575, 0.558424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.275625, 2451.0158593799997, 181.63882812), 'rotation':(0.579241, 90.204758, 0.567617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.31494141, 2439.6909375, 181.52302734), 'rotation':(0.583981, 90.20401, 0.572174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.35400391, 2428.36546875, 181.40572265999998), 'rotation':(0.597157, 90.204842, 0.584829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.39332031, 2417.03980469, 181.28644531), 'rotation':(0.605913, 90.205017, 0.593199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.41308594, 2411.37742188, 181.2259375), 'rotation':(0.605913, 90.205017, 0.593199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.45238281, 2400.05273438, 181.10396484), 'rotation':(0.619013, 90.204346, 0.605748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.31371094, 2405.71972656, 181.16492188), 'rotation':(-0.619019, -89.795654, -0.632507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.27417969, 2417.04394531, 181.28619141), 'rotation':(-0.614594, -89.793304, -0.627899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.17601562, 2445.35765625, 181.58085938), 'rotation':(-0.588409, -89.795349, -0.600586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.13671875, 2456.683125, 181.69603515999998), 'rotation':(-0.583984, -89.79599, -0.595978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.1171875, 2462.3459375, 181.753125), 'rotation':(-0.579254, -89.795227, -0.591034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.09765625, 2468.00878906, 181.80943359), 'rotation':(-0.569672, -89.79541, -0.581085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.05835938, 2479.33421875, 181.92015625), 'rotation':(-0.56012, -89.795593, -0.571167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.01904297, 2490.6596875, 182.02859375), 'rotation':(-0.545593, -89.79538, -0.556061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.95996094, 2507.64796875, 182.18863281000003), 'rotation':(-0.53949, -89.796844, -0.549713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.94042969, 2513.31078125, 182.24074219), 'rotation':(-0.527222, -89.795471, -0.536987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.90113281, 2524.63648438, 182.34226562), 'rotation':(-0.514771, -89.797272, -0.524048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.86181641, 2535.96214844, 182.44115234), 'rotation':(-0.496185, -89.798584, -0.504852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.84228516, 2541.62453125, 182.48978516), 'rotation':(-0.496185, -89.798584, -0.504852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.80296875, 2552.95019531, 182.58535156000002), 'rotation':(-0.489166, -89.796112, -0.497559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.78296875, 2558.61304688, 182.63222656000002), 'rotation':(-0.474854, -89.797791, -0.482758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.66503906, 2592.59058594, 182.89613281), 'rotation':(-0.431061, -89.79776, -0.437592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.56689453, 2620.90503906, 183.09376953), 'rotation':(-0.382721, -89.798462, -0.387878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.52978516, 2632.23121094, 183.16744140999998), 'rotation':(-0.374603, -89.799988, -0.379517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.37451172, 2671.87257812, 183.39683594), 'rotation':(-0.304871, -89.799316, -0.308105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.30273438, 2688.86207031, 183.48238281000002), 'rotation':(-0.275177, -89.801605, -0.277832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.2790625, 2694.52490234, 183.50910156), 'rotation':(-0.266724, -89.798981, -0.269226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.23925781, 2705.8515625, 183.55978516), 'rotation':(-0.249878, -89.801849, -0.252045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.21972656, 2711.51441406, 183.58375), 'rotation':(-0.241272, -89.799225, -0.243286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.19996094, 2717.17773438, 183.60666016), 'rotation':(-0.230835, -89.800537, -0.232697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.18017578, 2722.84082031, 183.62832031000002), 'rotation':(-0.21875, -89.800629, -0.220398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.16064453, 2728.50341797, 183.64869141), 'rotation':(-0.206329, -89.80072, -0.207825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.08203125, 2751.15601562, 183.71773438), 'rotation':(-0.157501, -89.798492, -0.158356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3061.81616211, 2007.62710938, 176.75921875), 'rotation':(-0.582153, -89.216187, -0.594055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3061.6784668, 2017.76828125, 176.86236327999998), 'rotation':(-0.582397, -89.216675, -0.59433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3061.60961914, 2022.83898438, 176.91396484), 'rotation':(-0.582855, -89.215088, -0.594818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3061.54077148, 2027.9096875, 176.96556640999998), 'rotation':(-0.582855, -89.215088, -0.594818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3061.42749023, 2038.04929688, 177.06880859), 'rotation':(-0.583496, -89.215393, -0.595459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.89135742, 2075.6965625000003, 177.45378906000002), 'rotation':(-0.588715, -89.216187, -0.600891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.73974609, 2086.848125, 177.56839843999998), 'rotation':(-0.588745, -89.216095, -0.600952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.58813477, 2097.99976562, 177.68304688), 'rotation':(-0.589294, -89.217163, -0.601532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.51245117, 2103.57570312, 177.74050781000003), 'rotation':(-0.590607, -89.214539, -0.602875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3060.43676758, 2109.15140625, 177.79808594), 'rotation':(-0.591766, -89.214539, -0.604065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.36108398, 2114.7275, 177.85578125), 'rotation':(-0.592896, -89.217133, -0.605255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.28515625, 2120.30320312, 177.91355468999998), 'rotation':(-0.593597, -89.214935, -0.606018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.20947266, 2125.87914062, 177.97134766), 'rotation':(-0.593597, -89.214935, -0.606018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.13378906, 2131.45507812, 178.02912109000002), 'rotation':(-0.593506, -89.214935, -0.605896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3059.90625, 2148.1823437499997, 178.20246093999998), 'rotation':(-0.593506, -89.216675, -0.605896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3059.83032227, 2153.75828125, 178.26017578), 'rotation':(-0.593384, -89.213287, -0.605743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3059.75463867, 2159.33398438, 178.31789062), 'rotation':(-0.592896, -89.215515, -0.605255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3059.67895508, 2164.90992188, 178.37560547), 'rotation':(-0.592896, -89.215515, -0.605255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2451.08105469, 2050.0246875000003, 169.21173828), 'rotation':(-1.642456, -179.273926, -1.73877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2439.74511719, 2049.89039062, 168.88509765999999), 'rotation':(-1.669769, -179.273193, -1.769379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2417.06859375, 2049.62179688, 168.21298828), 'rotation':(-1.711243, -179.271027, -1.815887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2411.40039062, 2049.55492188, 168.04328125), 'rotation':(-1.723267, -179.269318, -1.829437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2400.06203125, 2049.4209375, 167.70033203), 'rotation':(-1.747345, -179.268707, -1.856537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2394.39648438, 2049.35375, 167.52703125), 'rotation':(-1.771515, -179.267181, -1.883789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2388.7267968799997, 2049.28664062, 167.35150391), 'rotation':(-1.795746, -179.264862, -1.911133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2383.05859375, 2049.21945312, 167.17457031), 'rotation':(-1.795746, -179.264862, -1.911133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2377.39136719, 2049.15234375, 166.99662109000002), 'rotation':(-1.807709, -179.264786, -1.924683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2366.05296875, 2049.01804688, 166.63839843999997), 'rotation':(-1.807709, -179.264786, -1.924683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2360.38378906, 2048.95117188, 166.45925781000003), 'rotation':(-1.807709, -179.264786, -1.924683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2337.71390625, 2048.6823437499997, 165.73414062), 'rotation':(-1.858643, -179.261185, -1.982391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2303.70289062, 2048.2799999999997, 164.62736328), 'rotation':(-1.871155, -179.260849, -1.996582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2269.69289062, 2047.87757812, 163.50921875), 'rotation':(-1.887238, -179.259338, -2.014862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2264.02414062, 2047.81039062, 163.3222168), 'rotation':(-1.887146, -179.259384, -2.014771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2247.01539062, 2047.60898438, 162.76258789), 'rotation':(-1.872192, -179.260269, -1.997803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2235.67773438, 2047.47476562, 162.39154297), 'rotation':(-1.872192, -179.260269, -1.997803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2224.3403125, 2047.3405468800001, 162.02052734), 'rotation':(-1.872253, -179.261154, -1.997864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2229.69945312, 2055.29, 162.19895508), 'rotation':(1.872257, 0.740657, 1.752699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2235.36890625, 2055.35375, 162.38449219), 'rotation':(1.872209, 0.738809, 1.752649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2241.03734375, 2055.4209375, 162.56999023), 'rotation':(1.872209, 0.738809, 1.752649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2275.0495312499997, 2055.82375, 163.68899414), 'rotation':(1.887229, 0.740648, 1.765762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2303.3918750000003, 2056.1262500000003, 164.62023438), 'rotation':(1.86736, 0.740166, 1.748409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2314.72875, 2056.2604687499997, 164.99019531000002), 'rotation':(1.860298, 0.739702, 1.742233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2320.3971874999997, 2056.32765625, 165.17460938), 'rotation':(1.858542, 0.738794, 1.7407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2326.06617188, 2056.39476562, 165.35878906000002), 'rotation':(1.858542, 0.738794, 1.7407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2331.73460938, 2056.46164062, 165.54292969), 'rotation':(1.858583, 0.738777, 1.740745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2337.4035937500003, 2056.52882812, 165.72708984000002), 'rotation':(1.845824, 0.73761, 1.729562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2354.40894531, 2056.72976562, 166.27322266), 'rotation':(1.807705, 0.73397, 1.696163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2360.07859375, 2056.796875, 166.45255859), 'rotation':(1.80763, 0.736425, 1.69609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2365.7478125, 2056.86398438, 166.63167968999997), 'rotation':(1.807712, 0.736458, 1.696163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2377.0857031200003, 2056.99828125, 166.98990234000001), 'rotation':(1.795732, 0.735132, 1.685651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2399.76414062, 2057.2665625, 167.69408203), 'rotation':(1.723277, 0.730672, 1.621799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2405.43285156, 2057.33375, 167.86638672), 'rotation':(1.723277, 0.730672, 1.621799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2416.77296875, 2057.46804688, 168.20691406000003), 'rotation':(1.711215, 0.728976, 1.611142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2428.11351562, 2057.60226562, 168.54548828), 'rotation':(1.697438, 0.729266, 1.598951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2433.78320312, 2057.66945312, 168.71367188), 'rotation':(1.669817, 0.727655, 1.574484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2445.12546875, 2057.80375, 169.04355468999998), 'rotation':(1.642455, 0.724395, 1.550194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2456.464375, 2057.93796875, 169.36625), 'rotation':(1.60101, 0.721758, 1.513298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2505.80371094, 2058.5546875, 170.70382812), 'rotation':(1.460294, 0.71602, 1.387201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2527.99121094, 2058.81734375, 171.26505859), 'rotation':(1.396937, 0.712501, 1.330008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2539.0825, 2058.94851562, 171.53591797), 'rotation':(1.361735, 0.710823, 1.298107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2555.72507812, 2059.14523438, 171.92439453), 'rotation':(1.308719, 0.708125, 1.249909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2561.2736718799997, 2059.2109375, 172.05123047), 'rotation':(1.308794, 0.708106, 1.249977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2577.91699219, 2059.40773438, 172.42728516), 'rotation':(1.249091, 0.70554, 1.195484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2583.46582031, 2059.47335938, 172.54833984), 'rotation':(1.209387, 0.703833, 1.159099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2600.10863281, 2059.6706249999997, 172.89609375), 'rotation':(1.149678, 0.701226, 1.104208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2611.20460938, 2059.8020312500003, 173.119375), 'rotation':(1.133914, 0.700333, 1.089664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2633.39671875, 2060.16601562, 173.54740234000002), 'rotation':(1.03894, 0.696726, 1.001754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2505.90039062, 2050.67359375, 170.70390625), 'rotation':(-1.481079, -179.285263, -1.559235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2522.53980469, 2050.870625, 171.12632812), 'rotation':(-1.449951, -179.285233, -1.524811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2544.72730469, 2051.13304688, 171.66796875), 'rotation':(-1.361694, -179.289185, -1.427643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2550.27464844, 2051.19875, 171.79683594), 'rotation':(-1.326447, -179.290863, -1.388977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2555.82128906, 2051.2643749999997, 171.92447266), 'rotation':(-1.326447, -179.290863, -1.388977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2578.01320312, 2051.52710938, 172.42734375), 'rotation':(-1.288818, -179.292709, -1.347839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2583.5622656200003, 2051.59304688, 172.54841797), 'rotation':(-1.249084, -179.294449, -1.304504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2589.10789062, 2051.6584375, 172.66650391), 'rotation':(-1.249084, -179.294449, -1.304504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2594.65550781, 2051.724375, 172.78277343999997), 'rotation':(-1.209381, -179.296158, -1.261292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2600.20484375, 2051.79, 172.89613281), 'rotation':(-1.169556, -179.297821, -1.218079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2605.75269531, 2051.85570312, 173.00804688), 'rotation':(-1.169556, -179.297821, -1.218079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2616.85007812, 2051.9870312499997, 173.22931641), 'rotation':(-1.133911, -179.299667, -1.179504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2628.67796875, 2052.10328125, 173.45742188), 'rotation':(-1.102203, -179.300888, -1.145264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2837.83203125, 2062.48390625, 176.22111328), 'rotation':(0.458982, 0.681275, 0.451676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2815.64867188, 2062.22117188, 176.02830078), 'rotation':(0.518077, 0.682251, 0.508762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2810.10253906, 2062.15554688, 175.97634766), 'rotation':(0.532864, 0.68255, 0.523032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2799.01123047, 2062.02414062, 175.86820312), 'rotation':(0.562384, 0.685742, 0.551434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2793.46410156, 2061.95851562, 175.81302734000002), 'rotation':(0.569665, 0.683418, 0.558433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2782.37328125, 2061.8271875, 175.69947266), 'rotation':(0.584794, 0.684051, 0.572935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2776.82691406, 2061.76171875, 175.63992188), 'rotation':(0.615099, 0.684681, 0.602005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2771.28369141, 2061.69601562, 175.57851562), 'rotation':(0.615099, 0.684681, 0.602005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2765.73828125, 2061.63039062, 175.51580077999998), 'rotation':(0.645419, 0.685349, 0.630999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2749.10058594, 2061.43359375, 175.31734375), 'rotation':(0.690846, 0.686877, 0.674334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2732.46558594, 2061.2365625, 175.10884765999998), 'rotation':(0.737339, 0.688211, 0.718537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2721.37792969, 2061.10523438, 174.96041015999998), 'rotation':(0.774823, 0.689202, 0.754065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2715.83226562, 2061.03953125, 174.88335938), 'rotation':(0.793463, 0.689709, 0.771723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2710.286875, 2060.97414062, 174.80445312), 'rotation':(0.81213, 0.69023, 0.789354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2704.74292969, 2060.9084375, 174.72384766), 'rotation':(0.830947, 0.690773, 0.807104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2699.19703125, 2060.84328125, 174.64248047), 'rotation':(0.8401, 0.688545, 0.81573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2682.56273438, 2060.64648438, 174.39146484), 'rotation':(0.89345, 0.692002, 0.865902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2677.02246094, 2060.5807812499997, 174.30318359), 'rotation':(0.89345, 0.692002, 0.865902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2837.92358398, 2054.60375, 176.22109375), 'rotation':(-0.473755, -179.315826, -0.481659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2832.37769531, 2054.538125, 176.17513672), 'rotation':(-0.488373, -179.318237, -0.496765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2821.286875, 2054.40671875, 176.07875), 'rotation':(-0.518097, -179.317734, -0.527527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2810.19410156, 2054.27539062, 175.97632812), 'rotation':(-0.547455, -179.3172, -0.557983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2804.64794922, 2054.2096874999997, 175.92287109), 'rotation':(-0.562408, -179.316879, -0.573547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2754.73828125, 2053.61914062, 175.38421875), 'rotation':(-0.690857, -179.313095, -0.707672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2749.19164062, 2053.55320312, 175.31732422000002), 'rotation':(-0.700165, -179.315384, -0.717438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2738.10107422, 2053.42210938, 175.18017577999998), 'rotation':(-0.737335, -179.311768, -0.7565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2727.01390625, 2053.29078125, 175.03554688), 'rotation':(-0.774811, -179.310791, -0.79599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2715.92236328, 2053.15945312, 174.88332031000002), 'rotation':(-0.812134, -179.312393, -0.835419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2704.83300781, 2053.0285937500003, 174.72378906000003), 'rotation':(-0.840118, -179.308823, -0.865021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2699.28710938, 2052.96289062, 174.64244141), 'rotation':(-0.840271, -179.308823, -0.865204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2682.65257812, 2052.76585938, 174.39140625), 'rotation':(-0.929077, -179.306885, -0.959595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2677.11207031, 2052.70015625, 174.303125), 'rotation':(-0.929077, -179.306885, -0.959595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2892.50708008, 2063.13109375, 176.61798828), 'rotation':(0.357834, 0.680114, 0.353384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2903.60375977, 2063.2621875, 176.68726562), 'rotation':(0.347124, 0.67998, 0.342935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2909.15234375, 2063.32789062, 176.72041016), 'rotation':(0.336571, 0.679853, 0.332638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2920.24780273, 2063.45921875, 176.78345703), 'rotation':(0.304592, 0.6795, 0.30136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2936.89355469, 2063.65648438, 176.86986328), 'rotation':(0.277866, 0.678102, 0.275187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2964.63549805, 2063.98460938, 177.00082031000002), 'rotation':(0.242718, 0.678424, 0.240669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2970.18359375, 2064.0503125, 177.02447266), 'rotation':(0.228572, 0.680086, 0.226754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2981.2800293, 2064.18164062, 177.06949218999998), 'rotation':(0.221592, 0.678472, 0.219889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2992.37719727, 2064.31296875, 177.11191406), 'rotation':(0.207727, 0.67911, 0.20622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2997.92602539, 2064.37867188, 177.13208984000002), 'rotation':(0.198513, 0.679069, 0.197148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3009.0234375, 2064.51, 177.17001953), 'rotation':(0.179934, 0.678945, 0.178819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3020.11962891, 2064.64132812, 177.20476562), 'rotation':(0.170727, 0.678888, 0.169715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3025.66845703, 2064.70703125, 177.2209375), 'rotation':(0.161513, 0.678811, 0.160594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3036.76367188, 2064.85375, 177.25099609), 'rotation':(0.147607, 0.677144, 0.146842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3042.31030273, 2065.00757812, 177.26529297000002), 'rotation':(0.147689, 0.678775, 0.146941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3039.16577148, 2056.93382812, 177.25693359000002), 'rotation':(-0.152283, -179.321228, -0.153107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3031.3112793, 2056.8928125, 177.23632812), 'rotation':(-0.161499, -179.321152, -0.162415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3025.76245117, 2056.8268749999997, 177.2209375), 'rotation':(-0.170715, -179.321106, -0.171753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3003.56933594, 2056.56421875, 177.15146484000002), 'rotation':(-0.198517, -179.320953, -0.19989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2998.02050781, 2056.49851562, 177.13208984000002), 'rotation':(-0.207733, -179.320862, -0.209259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2981.37475586, 2056.30148438, 177.06949218999998), 'rotation':(-0.228577, -179.321671, -0.230408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2970.27856445, 2056.17015625, 177.02447266), 'rotation':(-0.242737, -179.319794, -0.244781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2942.53662109, 2055.84179688, 176.896875), 'rotation':(-0.277863, -179.319427, -0.280548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2936.98876953, 2055.77640625, 176.86986328), 'rotation':(-0.283173, -179.320724, -0.28598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2931.44018555, 2055.71070312, 176.84216797000002), 'rotation':(-0.293884, -179.320602, -0.296906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2925.89160156, 2055.645, 176.81337890999998), 'rotation':(-0.304596, -179.320496, -0.307861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2920.34326172, 2055.5793750000003, 176.78347656000003), 'rotation':(-0.315155, -179.320389, -0.318604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2898.15087891, 2055.31664062, 176.65300781000002), 'rotation':(-0.363159, -179.318527, -0.367798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2892.60327148, 2055.2509375, 176.61800781000002), 'rotation':(-0.363159, -179.318527, -0.367798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2883.88427734, 2055.0676562500003, 176.56203125), 'rotation':(-0.389984, -179.318817, -0.395294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2446.98511719, 2286.75296875, 170.06927734), 'rotation':(1.632552, 0.537204, 1.541386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2435.74730469, 2286.65671875, 169.74677734), 'rotation':(1.632511, 0.535753, 1.541354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2424.50953125, 2286.56078125, 169.41316406), 'rotation':(1.728256, 0.542968, 1.626198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2418.89671875, 2286.51265625, 169.24019531000002), 'rotation':(1.728256, 0.542968, 1.626198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.27929688, 2286.46460938, 169.06414062), 'rotation':(1.79205, 0.545262, 1.682399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2396.42652344, 2286.32078125, 168.5128125), 'rotation':(1.887919, 0.551423, 1.766366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.95042969, 2286.1284375, 167.77076172), 'rotation':(1.889169, 0.553898, 1.767469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2362.71265625, 2286.0321875, 167.39957031000003), 'rotation':(1.889701, 0.551543, 1.767909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2351.47460938, 2285.9362499999997, 167.02822265999998), 'rotation':(1.890583, 0.5516, 1.768685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2323.38375, 2285.69625, 166.09291016), 'rotation':(1.922056, 0.555238, 1.796113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2317.76609375, 2285.64820312, 165.90378906), 'rotation':(1.926646, 0.554917, 1.80011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2312.1475, 2285.60007812, 165.71455078), 'rotation':(1.926557, 0.554884, 1.800041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2300.9114062500003, 2285.50390625, 165.33558594), 'rotation':(1.930867, 0.555416, 1.803792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2289.6740625, 2285.40796875, 164.95539062), 'rotation':(1.936522, 0.555802, 1.808697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2284.055625, 2285.35984375, 164.76486328), 'rotation':(1.939432, 0.555998, 1.811224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2278.43703125, 2285.31179688, 164.57404297000002), 'rotation':(1.942164, 0.556184, 1.81361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2244.72507812, 2285.02320312, 163.42751953), 'rotation':(1.941952, 0.556793, 1.813428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2239.1067187500003, 2284.9753124999997, 163.23728516), 'rotation':(1.937151, 0.556472, 1.809241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2233.48804688, 2284.92726562, 163.04744141), 'rotation':(1.932131, 0.554413, 1.804881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2222.2487499999997, 2284.83109375, 162.66818359), 'rotation':(1.929761, 0.555528, 1.802816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2222.14625, 2276.94726562, 162.66244140999999), 'rotation':(-1.929688, -179.444489, -2.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2227.76515625, 2276.99539062, 162.85199219), 'rotation':(-1.929688, -179.444489, -2.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2244.62179688, 2277.1396875, 163.42173828), 'rotation':(-1.937164, -179.443512, -2.071716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2255.85960938, 2277.23585938, 163.80313476999999), 'rotation':(-1.941956, -179.444916, -2.077209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2278.33398438, 2277.42820312, 164.56824218999998), 'rotation':(-1.945068, -179.443619, -2.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2300.80835938, 2277.62039062, 165.32982422), 'rotation':(-1.933807, -179.444366, -2.067871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2306.4270312500003, 2277.66820312, 165.51949219), 'rotation':(-1.930878, -179.444595, -2.064575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2317.66429688, 2277.7643749999997, 165.89810547000002), 'rotation':(-1.926575, -179.445114, -2.059631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2323.28296875, 2277.80640625, 166.08726562), 'rotation':(-1.926575, -179.445114, -2.059631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2334.51953125, 2277.94140625, 166.46384766), 'rotation':(-1.913116, -179.447723, -2.044312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2351.37597656, 2278.0859375, 167.02275391), 'rotation':(-1.890533, -179.447372, -2.018616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2356.99488281, 2278.1340625000003, 167.2084375), 'rotation':(-1.890656, -179.445999, -2.018768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2362.61402344, 2278.18210938, 167.39408203), 'rotation':(-1.890137, -179.448425, -2.018188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.8517968799997, 2278.27804688, 167.7653125), 'rotation':(-1.889771, -179.44606, -2.017761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2401.94703125, 2278.51859375, 168.69277344), 'rotation':(-1.887787, -179.446518, -2.015503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.18675781, 2278.61476562, 169.05898438), 'rotation':(-1.855927, -179.449005, -1.979309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2430.04835938, 2278.7590625000003, 169.57837891), 'rotation':(-1.728241, -179.457031, -1.835022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2441.2888281200003, 2278.855, 169.90486328), 'rotation':(-1.66449, -179.4608, -1.763458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2446.90941406, 2278.90328125, 170.06519531), 'rotation':(-1.632507, -179.464249, -1.727661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2485.24953125, 2287.08007812, 171.16076172), 'rotation':(1.616064, 0.536299, 1.526723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2490.77613281, 2287.12742188, 171.31681641), 'rotation':(1.583108, 0.534449, 1.497337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2518.4138281200003, 2287.36375, 172.07386719), 'rotation':(1.517238, 0.530881, 1.438391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2523.943125, 2287.41109375, 172.22044922), 'rotation':(1.490839, 0.527709, 1.414685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2540.52710938, 2287.55296875, 172.64837891), 'rotation':(1.460609, 0.528072, 1.38749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2546.05640625, 2287.6003124999997, 172.78945312), 'rotation':(1.438547, 0.525321, 1.367596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2562.64183594, 2287.743125, 173.20144531000003), 'rotation':(1.369063, 0.527222, 1.304765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2568.16992188, 2287.7903125000003, 173.33494141), 'rotation':(1.366577, 0.522246, 1.3025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2573.6996875, 2287.84523438, 173.46693359), 'rotation':(1.352377, 0.522981, 1.289613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2584.7578125, 2287.89820312, 173.72808593999997), 'rotation':(1.323991, 0.519849, 1.263827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2595.81714844, 2287.99265625, 173.98162109), 'rotation':(1.267485, 0.517289, 1.212292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2606.87648438, 2288.08742188, 174.22802734), 'rotation':(1.24388, 0.517087, 1.190719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2617.93554688, 2288.181875, 174.46603516), 'rotation':(1.206648, 0.515497, 1.156588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2623.46558594, 2288.22898438, 174.58214843999997), 'rotation':(1.187975, 0.514692, 1.139441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2629.1171875, 2280.42898438, 174.69769531000003), 'rotation':(-1.188019, -179.485291, -1.238098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2612.52832031, 2280.28710938, 174.34916016), 'rotation':(-1.243835, -179.482941, -1.298767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2606.99851562, 2280.24, 174.22921875), 'rotation':(-1.267517, -179.480881, -1.324585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2590.41453125, 2280.098125, 173.85734375), 'rotation':(-1.324036, -179.478317, -1.386353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2579.35570312, 2280.0034375, 173.59949218999998), 'rotation':(-1.366547, -179.476181, -1.432953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2573.82765625, 2279.95609375, 173.46837890999998), 'rotation':(-1.366547, -179.476181, -1.432953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2562.77101562, 2279.86132812, 173.20294922000002), 'rotation':(-1.394501, -179.475388, -1.463684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2557.24144531, 2279.81398438, 173.06826172), 'rotation':(-1.438538, -179.47319, -1.512238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2546.18703125, 2279.71921875, 172.79105468999998), 'rotation':(-1.460602, -179.47467, -1.536591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2540.65746094, 2279.67210938, 172.64998047), 'rotation':(-1.460785, -179.471909, -1.536774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2501.9665625, 2279.34132812, 171.62699218999998), 'rotation':(-1.583099, -179.46698, -1.672516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2485.38429688, 2279.19945312, 171.16267578), 'rotation':(-1.632538, -179.46347, -1.727692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2845.1472168, 2290.15796875, 178.058125), 'rotation':(0.616131, 0.497363, 0.602982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2834.02125, 2290.06273438, 177.93708984), 'rotation':(0.625215, 0.497099, 0.611676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2828.45703125, 2290.01539062, 177.87457031000002), 'rotation':(0.643534, 0.49752, 0.629201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2811.76953125, 2289.87257812, 177.67808594), 'rotation':(0.679993, 0.498367, 0.663997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2795.08154297, 2289.72976562, 177.46900391), 'rotation':(0.732121, 0.503517, 0.713587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2789.51757812, 2289.68210938, 177.39691406000003), 'rotation':(0.742223, 0.49892, 0.723173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2783.95433594, 2289.63453125, 177.32316406), 'rotation':(0.762591, 0.501206, 0.742496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2772.82958984, 2289.53929688, 177.17230468999998), 'rotation':(0.782856, 0.500001, 0.761678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2733.88916016, 2289.20632812, 176.60980468999998), 'rotation':(0.841472, 0.501748, 0.817015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2728.32542969, 2289.1589062499997, 176.52742188), 'rotation':(0.848057, 0.503369, 0.823225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2711.63623047, 2289.01609375, 176.27851562), 'rotation':(0.859258, 0.501737, 0.833764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2706.07666016, 2288.96851562, 176.19251953), 'rotation':(0.859258, 0.501737, 0.833764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.5134375, 2288.9206249999997, 176.10519531000003), 'rotation':(0.899106, 0.50534, 0.871216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2678.28636719, 2288.7309375, 175.70595702999998), 'rotation':(1.058802, 0.509366, 1.020197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2672.72363281, 2288.68359375, 175.5953125), 'rotation':(1.138668, 0.513866, 1.09407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2667.16578125, 2288.63601562, 175.48224609000002), 'rotation':(1.138668, 0.513866, 1.09407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2667.1877343799997, 2280.75460938, 175.48130859), 'rotation':(-1.17868, -179.48555, -1.227966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2672.74755859, 2280.80226562, 175.59445312), 'rotation':(-1.17868, -179.48555, -1.227966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.54638672, 2281.03976562, 176.10466797), 'rotation':(-0.979004, -179.493469, -1.012909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2706.10960938, 2281.08765625, 176.19199218999998), 'rotation':(-0.899109, -179.496094, -0.927673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2711.67066406, 2281.13523438, 176.27800781000002), 'rotation':(-0.899109, -179.496094, -0.927673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2722.79736328, 2281.23046875, 176.44431641), 'rotation':(-0.854828, -179.496429, -0.880646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2728.36058594, 2281.27804688, 176.52695312), 'rotation':(-0.854828, -179.496429, -0.880646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2756.1775, 2281.51609375, 176.93482422), 'rotation':(-0.831268, -179.500656, -0.855652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2767.30322266, 2281.61132812, 177.09392577999998), 'rotation':(-0.822388, -179.497086, -0.846222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2778.43017578, 2281.70632812, 177.24791016), 'rotation':(-0.782867, -179.49823, -0.804474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2783.99292969, 2281.75390625, 177.32277344), 'rotation':(-0.782867, -179.49823, -0.804474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2789.55589844, 2281.80148438, 177.39652343999998), 'rotation':(-0.762573, -179.500549, -0.783081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2806.24658203, 2281.9387500000003, 177.60966797), 'rotation':(-0.721375, -179.499863, -0.739716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2817.3728125, 2282.04984375, 177.74470703), 'rotation':(-0.699829, -179.502151, -0.717072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2822.93603516, 2282.10695312, 177.81021484000001), 'rotation':(-0.679993, -179.501617, -0.696289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2834.06347656, 2282.2153125, 177.93679688), 'rotation':(-0.643524, -179.502472, -0.658112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.75242188, 2211.34226562, 175.95236328), 'rotation':(-0.249847, -89.585388, -0.252014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.67234375, 2222.47609375, 176.00125), 'rotation':(-0.25174, -89.588348, -0.253967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.59226562, 2233.60914062, 176.05134766), 'rotation':(-0.26001, -89.586182, -0.26236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3509.55226562, 2239.17578125, 176.07691406), 'rotation':(-0.263916, -89.586121, -0.266357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.43210938, 2255.87570312, 176.15546875), 'rotation':(-0.272034, -89.588165, -0.274628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.35203125, 2267.00875, 176.20951172000002), 'rotation':(-0.280273, -89.585968, -0.283051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.27195312, 2278.1428125, 176.26431641), 'rotation':(-0.282196, -89.586395, -0.284973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.23195312, 2283.70921875, 176.29179688), 'rotation':(-0.282196, -89.586395, -0.284973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.15160156, 2294.84203125, 176.34710938), 'rotation':(-0.28598, -89.585388, -0.288849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.1115625, 2300.40867188, 176.37496094), 'rotation':(-0.287109, -89.586792, -0.290009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3509.03171875, 2311.54148438, 176.43074219), 'rotation':(-0.287109, -89.586792, -0.290009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.99171875, 2317.1081249999997, 176.45855468999997), 'rotation':(-0.286194, -89.585327, -0.289062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3508.91164062, 2328.24125, 176.51365234000002), 'rotation':(-0.28244, -89.585327, -0.285248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.83128906, 2339.3740625, 176.56816406000002), 'rotation':(-0.280487, -89.587402, -0.283234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.7111718799997, 2356.07300781, 176.64880859000002), 'rotation':(-0.27475, -89.585388, -0.277405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.67113281, 2361.63964844, 176.67537109), 'rotation':(-0.272827, -89.587494, -0.275452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3508.63109375, 2367.20582031, 176.70181641), 'rotation':(-0.272827, -89.587494, -0.275452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3500.79101562, 2361.5857031200003, 176.67537109), 'rotation':(0.271937, 90.412849, 0.269374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3500.87109375, 2350.4528906200003, 176.62210938), 'rotation':(0.274765, 90.412506, 0.272148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3500.99121094, 2333.75320312, 176.54099609000002), 'rotation':(0.280489, 90.414642, 0.277746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.07152344, 2322.620625, 176.48617188), 'rotation':(0.282428, 90.41259, 0.279656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.1115625, 2317.05421875, 176.45857422), 'rotation':(0.284389, 90.41468, 0.281566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.19164062, 2305.92140625, 176.40287109000002), 'rotation':(0.287107, 90.41317, 0.284238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.23167969, 2300.355, 176.37496094), 'rotation':(0.287107, 90.41317, 0.284238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.27171875, 2294.78835938, 176.34712890999998), 'rotation':(0.287121, 90.413193, 0.284249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.31175781, 2289.22171875, 176.31933593999997), 'rotation':(0.28598, 90.414635, 0.283137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.3908593799997, 2278.08890625, 176.26433594), 'rotation':(0.282176, 90.413574, 0.279419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.431875, 2272.52195312, 176.23691406), 'rotation':(0.282176, 90.413574, 0.279419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.55199219, 2255.8215625000003, 176.15548828), 'rotation':(0.27622, 90.413979, 0.273566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.59203125, 2250.25484375, 176.12896484), 'rotation':(0.272026, 90.413918, 0.269457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.63207031, 2244.68820312, 176.10277344), 'rotation':(0.268105, 90.413887, 0.265608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.71214844, 2233.5546875, 176.05136718999998), 'rotation':(0.263905, 90.411743, 0.26148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.7521875, 2227.98828125, 176.02611328), 'rotation':(0.259984, 90.413811, 0.257642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.15867188, 2367.36816406, 173.09376953), 'rotation':(-0.030853, 90.384315, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.27050781, 2350.6877343799997, 173.10257812), 'rotation':(-0.03009, 90.384781, -0.030121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.30785156, 2345.12769531, 173.10541016), 'rotation':(-0.02951, 90.384804, -0.029541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.3825781200003, 2334.00710938, 173.11097656), 'rotation':(-0.028473, 90.384781, -0.028503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.41992188, 2328.44679688, 173.11367188), 'rotation':(-0.028046, 90.384781, -0.028046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3616.49460938, 2317.32664062, 173.11896484000002), 'rotation':(-0.027008, 90.384804, -0.027039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.53222656, 2311.76585938, 173.1215625), 'rotation':(-0.026794, 90.386124, -0.026825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3616.60695312, 2300.64523438, 173.12722656000003), 'rotation':(-0.029602, 90.385918, -0.029633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.64429688, 2295.085, 173.13033202999998), 'rotation':(-0.031616, 90.385895, -0.031647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.79371094, 2272.84375, 173.14488281), 'rotation':(-0.041412, 90.385918, -0.041473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3616.83082031, 2267.28273438, 173.14894531000002), 'rotation':(-0.042419, 90.384125, -0.04248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.86816406, 2261.7221875, 173.15316406000002), 'rotation':(-0.044312, 90.386406, -0.044373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.90550781, 2256.16164062, 173.15769531), 'rotation':(-0.047791, 90.383644, -0.047852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3617.20433594, 2211.67820312, 173.20740234000002), 'rotation':(-0.074432, 90.385605, -0.074615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.08445312, 2211.7309375, 173.20740234000002), 'rotation':(0.080419, -89.614349, 0.080193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3625.0471093799997, 2217.29148438, 173.20013672000002), 'rotation':(0.074429, -89.61438, 0.07424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.89769531, 2239.5334375, 173.17371093999998), 'rotation':(0.062373, -89.613525, 0.062236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.82300781, 2250.65429688, 173.16263672000002), 'rotation':(0.055072, -89.613556, 0.054965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.67382812, 2272.89695312, 173.14488281), 'rotation':(0.042422, -89.615845, 0.042357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.63648438, 2278.45679688, 173.1409375), 'rotation':(0.039417, -89.614075, 0.03936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3624.59914062, 2284.01734375, 173.13722656000002), 'rotation':(0.037416, -89.61676, 0.037368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.56175781, 2289.57742188, 173.13369140999998), 'rotation':(0.035592, -89.614075, 0.035552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.41234375, 2311.8190624999997, 173.1215625), 'rotation':(0.027772, -89.61676, 0.02775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.33742188, 2322.93945312, 173.11634766), 'rotation':(0.026993, -89.615204, 0.026973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.22535156, 2339.62015625, 173.10822266), 'rotation':(0.028468, -89.615204, 0.028446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3624.18796875, 2345.18042969, 173.10542969), 'rotation':(0.029062, -89.615204, 0.029036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3624.11351562, 2356.30054688, 173.0996875), 'rotation':(0.029506, -89.615173, 0.029479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.07617188, 2361.86085938, 173.09673827999998), 'rotation':(0.030107, -89.615204, 0.030066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.0388281200003, 2367.42113281, 173.09376953), 'rotation':(0.030538, -89.615204, 0.030508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.30320312, 2179.1706249999997, 173.26115234), 'rotation':(0.108675, -89.614655, 0.108266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.3415625, 2173.47117188, 173.27203125), 'rotation':(0.111817, -89.615814, 0.111377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.41820312, 2162.07273438, 173.2953125), 'rotation':(0.124303, -89.615784, 0.123781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.4565625, 2156.37328125, 173.30796875), 'rotation':(0.130634, -89.615784, 0.13005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.57152344, 2139.27539062, 173.34996094), 'rotation':(0.15581, -89.612946, 0.154967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.72460938, 2116.4765625, 173.41392578), 'rotation':(0.178712, -89.615051, 0.177599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.76292969, 2110.77757812, 173.43167968999998), 'rotation':(0.191997, -89.61496, 0.190712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3625.839375, 2099.37890625, 173.46929688), 'rotation':(0.205199, -89.613281, 0.203732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.91601562, 2087.97953125, 173.51042969), 'rotation':(0.211825, -89.614563, 0.210274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.95433594, 2082.2803125, 173.53148438), 'rotation':(0.218293, -89.615112, 0.216639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3626.0310156200003, 2070.880625, 173.57511719), 'rotation':(0.231523, -89.613556, 0.229667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.14574219, 2053.7834375, 173.64617188), 'rotation':(0.257635, -89.613342, 0.255328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.26050781, 2036.68453125, 173.72384766), 'rotation':(0.276882, -89.613525, 0.27422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.33714844, 2025.28601562, 173.77888672), 'rotation':(0.285051, -89.613434, 0.282228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.41359375, 2013.8869531199998, 173.83708984), 'rotation':(0.301969, -89.613281, 0.298804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3618.60984375, 2002.4693750000001, 173.89832031000003), 'rotation':(-0.310303, 90.386833, -0.31366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.57152344, 2008.1673437499999, 173.86722656), 'rotation':(-0.301971, 90.386703, -0.305176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.45679688, 2025.26257812, 173.77873047), 'rotation':(-0.276886, 90.386482, -0.279572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.38039062, 2036.65867188, 173.72371094), 'rotation':(-0.26825, 90.384048, -0.270813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.22703125, 2059.45242188, 173.62173828), 'rotation':(-0.231537, 90.386406, -0.233398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3618.150625, 2070.84789062, 173.57503906000002), 'rotation':(-0.218323, 90.384888, -0.219971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.11230469, 2076.54664062, 173.55304688), 'rotation':(-0.218323, 90.384888, -0.219971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3617.84449219, 2116.43453125, 173.41388672000002), 'rotation':(-0.165497, 90.384872, -0.166473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.80617188, 2122.13328125, 173.39728516), 'rotation':(-0.158722, 90.38607, -0.159607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.7678125, 2127.8325, 173.38103515999998), 'rotation':(-0.158722, 90.38607, -0.159607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.61476562, 2150.62546875, 173.32128906000003), 'rotation':(-0.13681, 90.384254, -0.137451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.57640625, 2156.32375, 173.30794922), 'rotation':(-0.124329, 90.384232, -0.124847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3617.53808594, 2162.02171875, 173.2953125), 'rotation':(-0.117981, 90.384186, -0.118469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.42308594, 2179.11671875, 173.26115234), 'rotation':(-0.106537, 90.382812, -0.106964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.3854687499997, 2218.16796875, 169.90158203), 'rotation':(0.432235, -89.80838, 0.425758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2942187500003, 2245.90453125, 169.69707031000002), 'rotation':(0.41324, -89.810669, 0.407312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2760937499997, 2251.45164062, 169.65775391), 'rotation':(0.408001, -89.808105, 0.402234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2578125, 2256.9990625, 169.61898438), 'rotation':(0.402421, -89.808167, 0.396807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2214062499997, 2268.09398438, 169.54294922), 'rotation':(0.391595, -89.810944, 0.38628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.203125, 2273.64085938, 169.5053125), 'rotation':(0.388911, -89.80899, 0.383671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.1848437500003, 2279.1884375, 169.46785156), 'rotation':(0.388911, -89.80899, 0.383671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.16648438, 2284.7356250000003, 169.430625), 'rotation':(0.385762, -89.808441, 0.380586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.1484375, 2290.28273438, 169.39390625), 'rotation':(0.379267, -89.808563, 0.37428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.11179688, 2301.37695312, 169.32169922), 'rotation':(0.372792, -89.810303, 0.367965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3733.9475, 2351.30199219, 169.00941406), 'rotation':(0.349829, -89.809479, 0.345568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3733.91109375, 2362.39671875, 168.94236328), 'rotation':(0.345082, -89.80954, 0.340942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.04882812, 2356.82570312, 168.97576172), 'rotation':(-0.345093, 90.190445, -0.349274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.12203125, 2334.6371875, 169.11162109), 'rotation':(-0.354706, 90.190567, -0.359131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.14039062, 2329.0903125, 169.14615234000001), 'rotation':(-0.356995, 90.190598, -0.361481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.17671875, 2317.99609375, 169.21585938), 'rotation':(-0.361755, 90.190659, -0.366333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.21335938, 2306.90085938, 169.28623047000002), 'rotation':(-0.363068, 90.191605, -0.367706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.2317187500003, 2301.35375, 169.32167969), 'rotation':(-0.366272, 90.189575, -0.371002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.26804688, 2290.25953125, 169.39388672), 'rotation':(-0.372772, 90.191376, -0.377655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.30445312, 2279.165, 169.46783202999998), 'rotation':(-0.385742, 90.191544, -0.390991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.32273438, 2273.61742188, 169.50529297), 'rotation':(-0.385742, 90.191544, -0.390991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.3410937500003, 2268.07054688, 169.54292969), 'rotation':(-0.388947, 90.190994, -0.394226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.37742188, 2256.97585938, 169.61896484000002), 'rotation':(-0.397186, 90.18914, -0.40271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.43210938, 2240.33398438, 169.73691406), 'rotation':(-0.413269, 90.191971, -0.41925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.52320312, 2212.59789062, 169.94341797), 'rotation':(-0.432251, 90.191612, -0.438812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.21414062, 2002.4493750000001, 171.97642578), 'rotation':(-0.671906, 90.196579, -0.687805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.19578125, 2008.0, 171.91140625), 'rotation':(-0.66153, 90.196342, -0.676941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.14109375, 2024.6528125, 171.72126953), 'rotation':(-0.645905, 90.196983, -0.660583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3727.04984375, 2052.40648438, 171.41314452999998), 'rotation':(-0.611298, 90.193939, -0.624451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.03148438, 2057.95875, 171.35361328), 'rotation':(-0.603668, 90.196373, -0.616486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3727.0134375, 2063.50953125, 171.29488281000002), 'rotation':(-0.595856, 90.193604, -0.608337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.97679688, 2074.61109375, 171.17970703), 'rotation':(-0.58432, 90.193954, -0.596313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.9401562499997, 2085.713125, 171.06636719), 'rotation':(-0.584473, 90.19603, -0.596466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.9035937500003, 2096.81570312, 170.9540625), 'rotation':(-0.566864, 90.19384, -0.578156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.88523438, 2102.36671875, 170.89917968999998), 'rotation':(-0.555084, 90.193596, -0.565918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.86695312, 2107.91726562, 170.84539062), 'rotation':(-0.543457, 90.193382, -0.553864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.81226562, 2124.57125, 170.68830078), 'rotation':(-0.53363, 90.192802, -0.54364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.7942187500003, 2130.12304688, 170.63650391), 'rotation':(-0.525879, 90.192673, -0.535614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.77585938, 2135.67382812, 170.58537109), 'rotation':(-0.518036, 90.19252, -0.527466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.7395312500003, 2146.775625, 170.48525390999998), 'rotation':(-0.502289, 90.194633, -0.511139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.6848437500003, 2163.43039062, 170.34039062), 'rotation':(-0.486664, 90.191971, -0.494995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.6484375, 2174.5334375, 170.24726562), 'rotation':(-0.475037, 90.193207, -0.482971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.6301562500003, 2180.08421875, 170.20126953), 'rotation':(-0.471069, 90.191872, -0.478851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.54710938, 2169.01882812, 170.29345702999998), 'rotation':(0.486685, -89.808014, 0.478462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.56546875, 2163.46726562, 170.34029297), 'rotation':(0.494547, -89.807861, 0.486071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.58351562, 2157.91601562, 170.38787109), 'rotation':(0.502278, -89.807739, 0.493537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.62015625, 2146.81179688, 170.48517578), 'rotation':(0.51016, -89.807587, 0.501129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.71140625, 2119.05421875, 170.7403125), 'rotation':(0.537652, -89.805267, 0.527639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.7478125, 2107.95070312, 170.8453125), 'rotation':(0.555096, -89.806396, 0.544411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.78445312, 2096.84789062, 170.95398438), 'rotation':(0.578462, -89.805908, 0.56689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.8025, 2091.29664062, 171.00984375), 'rotation':(0.584432, -89.80603, 0.572601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.82078125, 2085.7448437499997, 171.06630859), 'rotation':(0.584323, -89.80603, 0.572492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.83914062, 2080.19382812, 171.12292968999998), 'rotation':(0.584323, -89.80603, 0.572492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.87570312, 2069.09078125, 171.23685547000002), 'rotation':(0.595838, -89.806396, 0.583544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.91234375, 2057.98828125, 171.35357422), 'rotation':(0.611295, -89.803467, 0.598353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.96703125, 2041.33359375, 171.53443359000002), 'rotation':(0.634388, -89.802948, 0.620462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3735.0034375, 2030.2310937500001, 171.65865234), 'rotation':(0.645876, -89.803009, 0.63144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3735.02171875, 2024.6803125000001, 171.72125), 'rotation':(0.645897, -89.805389, 0.631468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2427.88867188, 2586.04296875, 169.05853516), 'rotation':(-1.796478, 179.989639, -1.911957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2422.23195312, 2586.04957031, 168.88166016), 'rotation':(-1.796478, 179.989639, -1.911957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2405.26292969, 2586.06957031, 168.34509766), 'rotation':(-1.822418, 179.990829, -1.941345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2393.9496875, 2586.08277344, 167.98439453), 'rotation':(-1.834778, 179.991638, -1.955322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2388.29296875, 2586.08910156, 167.80320312), 'rotation':(-1.841187, 179.99205, -1.962585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2382.63648438, 2586.09570312, 167.62144531), 'rotation':(-1.847168, 179.992432, -1.96936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2371.32496094, 2586.1091406200003, 167.25625), 'rotation':(-1.853516, 179.992844, -1.976562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2360.01148438, 2586.12230469, 166.88869140999998), 'rotation':(-1.865906, 179.993637, -1.990662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2354.3559375, 2586.12890625, 166.70414062), 'rotation':(-1.869049, 179.9935, -1.994202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2348.69921875, 2586.13574219, 166.51935547000002), 'rotation':(-1.869202, 179.9935, -1.994354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2320.41773438, 2586.16894531, 165.59148438), 'rotation':(-1.884613, 179.995331, -2.011871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2314.76125, 2586.17554688, 165.40515625), 'rotation':(-1.884613, 179.995331, -2.011871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2309.10453125, 2586.18210938, 165.21880859), 'rotation':(-1.884705, 179.995346, -2.011993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2297.79125, 2586.1955468799997, 164.84615234), 'rotation':(-1.886017, 179.996063, -2.013489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2292.13476562, 2586.20214844, 164.65976562), 'rotation':(-1.886017, 179.996063, -2.013489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2286.47804688, 2586.20851562, 164.47328125), 'rotation':(-1.887512, 179.99559, -2.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2280.82203125, 2586.2153125, 164.28671875), 'rotation':(-1.88736, 179.993439, -2.015015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2269.50875, 2586.22851562, 163.91351562), 'rotation':(-1.887512, 179.99559, -2.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2258.193125, 2586.24171875, 163.54030273), 'rotation':(-1.883636, 179.995331, -2.010803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2252.53664062, 2586.24851562, 163.3540625), 'rotation':(-1.875977, 179.992981, -2.002075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2246.87960938, 2586.25511719, 163.16851562), 'rotation':(-1.868561, 179.994324, -1.993622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2235.56570312, 2586.26832031, 162.79890625), 'rotation':(-1.861053, 179.993835, -1.985107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2615.84375, 2585.82226562, 174.42771484000002), 'rotation':(-1.455902, 179.970673, -1.531372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2604.77757812, 2585.83546875, 174.14417969), 'rotation':(-1.486084, 179.972229, -1.564758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2599.24339844, 2585.84179688, 174.00048827999998), 'rotation':(-1.501373, 179.97081, -1.581696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2593.70972656, 2585.84839844, 173.85537109), 'rotation':(-1.516418, 179.973816, -1.598358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2566.04320312, 2585.88085938, 173.11427734), 'rotation':(-1.55368, 179.973999, -1.639771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2560.51, 2585.8871875, 172.96392577999998), 'rotation':(-1.582825, 179.977081, -1.672211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2554.9763281200003, 2585.89378906, 172.81087890999999), 'rotation':(-1.597565, 179.978149, -1.688629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2516.24535156, 2585.93921875, 171.71992188000002), 'rotation':(-1.657043, 179.979019, -1.755127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2505.18335938, 2585.95214844, 171.39900391), 'rotation':(-1.683441, 179.982803, -1.784698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2494.1171875, 2585.9653125, 171.07351562), 'rotation':(-1.696533, 179.983582, -1.799408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2488.58640625, 2585.97191406, 170.90935547), 'rotation':(-1.7034, 179.984039, -1.807098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.2956249999997, 363.0452734400001, 157.57901367), 'rotation':(-0.018127, -89.870178, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.24414062, 385.81281249999995, 157.58602539), 'rotation':(-0.018127, -89.870178, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.2053125, 402.88820312000007, 157.58546875), 'rotation':(0.00849, -89.868774, 0.008482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.19234375, 408.5803125, 157.58462891), 'rotation':(0.00849, -89.87027, 0.008481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.17945312, 414.27246094, 157.58378906), 'rotation':(0.00849, -89.87027, 0.008481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.16648438, 419.96460937999996, 157.58295898), 'rotation':(0.00849, -89.87027, 0.008481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.140625, 431.348125, 157.58125), 'rotation':(0.008381, -89.868774, 0.008392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.11476562, 442.73210938, 157.57849609000002), 'rotation':(0.012233, -89.870544, 0.012231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.10179688, 448.4241796900001, 157.57655273), 'rotation':(0.01963, -89.868958, 0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.05007812, 471.19109375000005, 157.56380859), 'rotation':(0.038256, -89.870911, 0.038202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.99828125, 493.95914062, 157.54629882999998), 'rotation':(0.046903, -89.86908, 0.04684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.95945312, 511.03523437999996, 157.53038086), 'rotation':(0.056766, -89.869049, 0.056653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.93359375, 522.41871094, 157.51881836), 'rotation':(0.058139, -89.869598, 0.058023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.90773438, 533.80273438, 157.50645508), 'rotation':(0.064252, -89.868286, 0.064115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.78195312, 589.10566406, 157.43226562), 'rotation':(0.083943, -89.869751, 0.083696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.7690625, 594.7865625, 157.42352539), 'rotation':(0.088144, -89.869751, 0.087877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.743125, 606.14769531, 157.40519531), 'rotation':(0.092255, -89.869751, 0.091968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.73023438, 611.8284765599999, 157.39583984), 'rotation':(0.094243, -89.870575, 0.093951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.71726562, 617.50902344, 157.38644531), 'rotation':(0.094257, -89.868042, 0.093941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.69140625, 628.8705468799999, 157.36710938), 'rotation':(0.098799, -89.870453, 0.098456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.66578125, 640.23199219, 157.34675780999999), 'rotation':(0.104734, -89.870422, 0.104346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.6528125, 645.91257812, 157.33631836), 'rotation':(0.106182, -89.868896, 0.105794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.61398438, 662.9547265599999, 157.30452148), 'rotation':(0.108586, -89.870239, 0.108173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.60109375, 668.63539062, 157.29365234), 'rotation':(0.110171, -89.867706, 0.109754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.57515625, 679.99701172, 157.27145508), 'rotation':(0.11334, -89.870239, 0.112898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.5625, 685.67773438, 157.26009765999999), 'rotation':(0.114774, -89.867676, 0.114316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.5495312499997, 691.3585156199999, 157.24859375), 'rotation':(0.116516, -89.870239, 0.116052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.536875, 697.0392968799999, 157.23693359), 'rotation':(0.117957, -89.870209, 0.117465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.51101562, 708.40070312, 157.21339844), 'rotation':(0.118797, -89.871094, 0.118295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.4853125, 719.7620312500001, 157.18953125), 'rotation':(0.121386, -89.870544, 0.120886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.47242188, 725.4428125, 157.17738281), 'rotation':(0.121386, -89.870544, 0.120886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.39476562, 759.52740234, 157.10269531), 'rotation':(0.126816, -89.869324, 0.126251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.2578125, 819.68957031, 156.96612305), 'rotation':(0.13131, -89.869781, 0.130715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.23265625, 830.74078125, 156.94075195), 'rotation':(0.131741, -89.868073, 0.131143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.18265625, 852.84356445, 156.88994141), 'rotation':(0.13172, -89.870789, 0.131115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.1575000000003, 863.89483398, 156.86463867), 'rotation':(0.13114, -89.870178, 0.13055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.09445312, 891.52332031, 156.80198242), 'rotation':(0.129432, -89.869965, 0.128864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.04445312, 913.62609375, 156.75304688), 'rotation':(0.125225, -89.869965, 0.124677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.03445312, 931.08374023, 156.71554688), 'rotation':(0.122315, -89.869995, 0.121784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.9275, 524.1565625000001, 159.06637695), 'rotation':(-0.049225, 90.543251, -0.049316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.98, 518.61480469, 159.07091796999998), 'rotation':(-0.047211, 90.544357, -0.047272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.13765625, 501.9909375, 159.08205078), 'rotation':(-0.034668, 90.541718, -0.034729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.1901562499997, 496.44972656, 159.08493164), 'rotation':(-0.030426, 90.544319, -0.030457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.29539062, 485.36730468999997, 159.08944336000002), 'rotation':(-0.022125, 90.544334, -0.022156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.34789062, 479.8265234400001, 159.09112305), 'rotation':(-0.017883, 90.544319, -0.017914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.40039062, 474.28515625, 159.09266602), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.45289062, 468.74367187999997, 159.09418945), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.50539062, 463.20226562000005, 159.09573242), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.55789062, 457.66089844, 159.09725586000002), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.6103125, 452.12046875, 159.09857422), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.7678125, 435.4971875, 159.09692383), 'rotation':(0.011406, 90.541801, 0.011395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.8203125, 429.95585938, 159.09581055), 'rotation':(0.0114, 90.544518, 0.011403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.87304688, 424.41437499999995, 159.09470703), 'rotation':(0.011577, 90.541794, 0.011565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.92554688, 418.87304687999995, 159.09359375), 'rotation':(0.0114, 90.544518, 0.011393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.97804688, 413.3315625, 159.09248047), 'rotation':(0.011406, 90.541801, 0.011391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2236.08296875, 402.24976562000006, 159.09010742), 'rotation':(0.011406, 90.541801, 0.011395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2236.2934375, 380.08539062, 159.0768457), 'rotation':(0.049478, 90.544647, 0.049382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2236.4509375, 363.46214843999996, 159.06094726999999), 'rotation':(0.054894, 90.54409, 0.054795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.09695312, 717.27984375, 158.77083984), 'rotation':(-0.118958, 90.543137, -0.119446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.30664062, 695.12054688, 158.81583984), 'rotation':(-0.11319, 90.544235, -0.113617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.5690624999997, 667.42132812, 158.86849609), 'rotation':(-0.105835, 90.54335, -0.106232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.62179688, 661.88140625, 158.87874023), 'rotation':(-0.105988, 90.54335, -0.106384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.72679688, 650.80195312, 158.89871094), 'rotation':(-0.104034, 90.5439, -0.104431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.77929688, 645.26195312, 158.90841797), 'rotation':(-0.10025, 90.543892, -0.100616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.83179688, 639.72203125, 158.91780273), 'rotation':(-0.096558, 90.542267, -0.096863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.93703125, 628.6424609400001, 158.93600586), 'rotation':(-0.092743, 90.543861, -0.093048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.1996875, 600.94359375, 158.97868164), 'rotation':(-0.084106, 90.542976, -0.084351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.5146875, 567.70464844, 159.02189453), 'rotation':(-0.069061, 90.542427, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.56710938, 562.16484375, 159.02847656), 'rotation':(-0.069061, 90.542427, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.26539062, 910.49212891, 158.34681641), 'rotation':(-0.120575, 90.542747, -0.121094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.4228125, 893.86016602, 158.3821582), 'rotation':(-0.122589, 90.543266, -0.123108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.63304688, 871.68432617, 158.43046875), 'rotation':(-0.126129, 90.543289, -0.126678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.73828125, 860.59637695, 158.45509765999998), 'rotation':(-0.127289, 90.543633, -0.127838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2231.94851562, 838.4205957, 158.50456055), 'rotation':(-0.128052, 90.544662, -0.128632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.0534374999997, 827.33263672, 158.52948242), 'rotation':(-0.128571, 90.543045, -0.12915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.15867188, 816.24474609, 158.55449219), 'rotation':(-0.129456, 90.544327, -0.130035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.21117188, 810.70085938, 158.56701171999998), 'rotation':(-0.129456, 90.544327, -0.130035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.36890625, 794.06916016, 158.6044043), 'rotation':(-0.128113, 90.542236, -0.128693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2232.47414062, 782.98132812, 158.62910156), 'rotation':(-0.127472, 90.54393, -0.128052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2232.5790625, 771.89355469, 158.65362305), 'rotation':(-0.126617, 90.543938, -0.127167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2229.8525, 1059.50476074, 158.09428711), 'rotation':(-0.063934, 90.542557, -0.064087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2229.9049999999997, 1053.95324707, 158.10049805), 'rotation':(-0.063934, 90.544174, -0.064056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.11546875, 1031.74902344, 158.12819336), 'rotation':(-0.076202, 90.544014, -0.076416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.16796875, 1026.19787598, 158.13600586), 'rotation':(-0.079498, 90.541405, -0.079712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.37867188, 1003.99316406, 158.17039062), 'rotation':(-0.092834, 90.54158, -0.09314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.48390625, 992.89105225, 158.1887793), 'rotation':(-0.096771, 90.54158, -0.097107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.53664062, 987.34014893, 158.19827148000002), 'rotation':(-0.098755, 90.544205, -0.099091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.58914062, 981.78912354, 158.20797851999998), 'rotation':(-0.100861, 90.544228, -0.101227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.6418750000003, 976.23809814, 158.21786133), 'rotation':(-0.102661, 90.541588, -0.103027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.694375, 970.68713379, 158.22794922), 'rotation':(-0.104797, 90.544243, -0.105164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.77320312, 948.71459961, 158.26928711), 'rotation':(-0.109009, 90.542625, -0.109436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.33296875, 378.24914062000005, 160.59979492), 'rotation':(-0.089966, -89.6185, -0.090271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.26929688, 386.00660156000004, 160.61134765999998), 'rotation':(-0.084656, -89.617218, -0.0849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2340.0846874999997, 413.64093749999995, 160.64207031), 'rotation':(-0.052917, -89.61731, -0.053009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.04757812, 419.16820312000004, 160.64666992), 'rotation':(-0.047668, -89.615631, -0.04776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.93703125, 435.74890625, 160.6593457), 'rotation':(-0.042786, -89.618744, -0.042847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.89992188, 441.27617188, 160.66251953), 'rotation':(-0.03299, -89.616943, -0.03302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.75242188, 463.38378906, 160.66867188), 'rotation':(-0.008514, -89.617676, -0.008514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.7153125, 468.91105469, 160.66949219), 'rotation':(-0.008514, -89.617676, -0.008514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2339.6784374999997, 474.43835937999995, 160.67032226999999), 'rotation':(-0.008606, -89.617676, -0.008606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.53078125, 496.54644530999997, 160.67345703), 'rotation':(-0.008606, -89.616211, -0.008606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.49390625, 502.07378905999997, 160.67288086), 'rotation':(0.006024, -89.617981, 0.00603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.16726562, 551.02082031, 160.65327148), 'rotation':(0.031733, -89.617584, 0.031695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2339.09351562, 562.0660937499999, 160.6452832), 'rotation':(0.039062, -89.617584, 0.039014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.05664062, 567.5882031200001, 160.64078125), 'rotation':(0.046698, -89.617554, 0.046614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.01953125, 573.1109765599999, 160.6359082), 'rotation':(0.050263, -89.616364, 0.050176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.98265625, 578.63328125, 160.6309375), 'rotation':(0.051773, -89.617737, 0.051694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.94578125, 584.1559374999999, 160.62571289), 'rotation':(0.054566, -89.617706, 0.054456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.9089062499997, 589.67863281, 160.62025391), 'rotation':(0.057333, -89.617737, 0.057219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.87203125, 595.2012890599999, 160.61452148), 'rotation':(0.059955, -89.615234, 0.059827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.72460938, 617.29207031, 160.58898438), 'rotation':(0.071205, -89.617706, 0.071028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.68773438, 622.8143749999999, 160.58205078), 'rotation':(0.072352, -89.61673, 0.072174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.61375, 633.85957031, 160.56791992), 'rotation':(0.07449, -89.616547, 0.074307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.50320312, 650.42753906, 160.54495117), 'rotation':(0.082597, -89.616516, 0.082364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.42945312, 661.47265625, 160.52820312), 'rotation':(0.086784, -89.618408, 0.08652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.35570312, 672.5180664100001, 160.51106445), 'rotation':(0.088758, -89.617828, 0.088477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.28171875, 683.56347656, 160.49348633), 'rotation':(0.092119, -89.617615, 0.091818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.20796875, 694.60876953, 160.47521484), 'rotation':(0.094332, -89.615601, 0.094017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.91796875, 738.0379101599999, 160.39799805), 'rotation':(0.105567, -89.617004, 0.105177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.84421875, 749.08660156, 160.37738281), 'rotation':(0.107384, -89.616974, 0.10699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.73367188, 765.65949219, 160.34573242), 'rotation':(0.110089, -89.618286, 0.109661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.69679688, 771.18382812, 160.33511719), 'rotation':(0.110089, -89.618286, 0.109661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.65992188, 776.708125, 160.32451172), 'rotation':(0.110191, -89.616669, 0.109763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.5859375, 787.75683594, 160.30317383), 'rotation':(0.11084, -89.618286, 0.110418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.5490625, 793.28107422, 160.29245117), 'rotation':(0.111428, -89.615936, 0.110982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.4753124999997, 804.32984375, 160.27087891), 'rotation':(0.111851, -89.618256, 0.111419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.40164062, 815.37853516, 160.24926758), 'rotation':(0.112227, -89.61618, 0.11178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.32765625, 826.42730469, 160.22769531), 'rotation':(0.111735, -89.61734, 0.11129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.18015625, 848.52490234, 160.18505859), 'rotation':(0.110014, -89.61734, 0.109581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.10640625, 859.57367188, 160.16401367), 'rotation':(0.109194, -89.61734, 0.108774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.06960938, 865.09808594, 160.15354492), 'rotation':(0.108812, -89.617004, 0.108397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.66890625, 925.075625, 160.046875), 'rotation':(0.096449, -89.617767, 0.096128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.55835938, 941.65234375, 160.0202832), 'rotation':(0.089107, -89.617767, 0.088837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.52148438, 947.17785645, 160.01196289), 'rotation':(0.085493, -89.617798, 0.085247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.4475, 958.22912598, 159.99574219), 'rotation':(0.083629, -89.61676, 0.083393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.3737499999997, 969.28070068, 159.97996094), 'rotation':(0.079722, -89.618744, 0.079494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.29984375, 980.33184814, 159.96511719), 'rotation':(0.074422, -89.618744, 0.074234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.22609375, 991.38293457, 159.95125977), 'rotation':(0.069285, -89.616272, 0.069116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.11523438, 1007.96002197, 159.93229492), 'rotation':(0.063999, -89.616272, 0.06385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.04148438, 1019.01177979, 159.92076172), 'rotation':(0.05846, -89.618042, 0.058334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2335.9678125, 1030.06335449, 159.91094727), 'rotation':(0.050175, -89.618073, 0.050085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2335.8940625, 1041.11462402, 159.90327148), 'rotation':(0.041794, -89.616516, 0.041727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2335.91210938, 1057.78637695, 159.89428711), 'rotation':(0.029261, -89.617188, 0.029231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.69628906, 498.29, 162.22680664), 'rotation':(-0.004059, 90.286415, -0.004059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.81957031, 487.12902343999997, 162.2259082), 'rotation':(0.004166, 90.287025, 0.004161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.87546875, 475.96386719, 162.22079102), 'rotation':(0.028823, 90.286591, 0.028796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.90355469, 470.38085937999995, 162.21796875), 'rotation':(0.02868, 90.288841, 0.028657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.95972656, 459.21484375, 162.21237305), 'rotation':(0.02868, 90.288841, 0.028657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.015625, 448.04992187999994, 162.20548828), 'rotation':(0.033133, 90.288589, 0.033102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2426.04371094, 442.46710938, 162.20128906), 'rotation':(0.041814, 90.286797, 0.041757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.09984375, 431.30140625, 162.19078125), 'rotation':(0.059279, 90.286819, 0.059168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.1840625, 414.55363280999995, 162.17211914), 'rotation':(0.066902, 90.286278, 0.066756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.21214844, 408.97082031, 162.16505859), 'rotation':(0.073179, 90.288475, 0.073005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.24023438, 403.38812499999995, 162.15745117), 'rotation':(0.079483, 90.288498, 0.079252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.26832031, 397.8053125, 162.14932617), 'rotation':(0.085896, 90.288521, 0.085632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.29640625, 392.22343750000005, 162.14067383), 'rotation':(0.085896, 90.288521, 0.085632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2426.380625, 375.47507812000003, 162.11155273), 'rotation':(0.104878, 90.288574, 0.104482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.75902344, 675.9975, 162.10049805), 'rotation':(-0.079865, 90.287132, -0.080109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.92652344, 664.84242188, 162.11540039), 'rotation':(-0.077026, 90.288811, -0.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.95433594, 659.263125, 162.12275391), 'rotation':(-0.075714, 90.287476, -0.075928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.03859375, 642.52433594, 162.14364258), 'rotation':(-0.06897, 90.287849, -0.069122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.06664062, 636.94488281, 162.15012695), 'rotation':(-0.06897, 90.287849, -0.069122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.12257812, 625.78589844, 162.16232422), 'rotation':(-0.064453, 90.287865, -0.064575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.150625, 620.20660156, 162.16813477), 'rotation':(-0.060028, 90.287849, -0.06015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.17871094, 614.6270312500001, 162.1737793), 'rotation':(-0.057709, 90.288727, -0.057831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.29101562, 592.30933594, 162.19404297), 'rotation':(-0.048309, 90.287239, -0.04837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.40308594, 569.99152344, 162.20999023000002), 'rotation':(-0.037384, 90.287224, -0.037415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.45898438, 558.83292969, 162.21668945), 'rotation':(-0.032074, 90.287819, -0.032104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.54320312, 542.09453125, 162.223125), 'rotation':(-0.016052, 90.287811, -0.016022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.599375, 530.93628906, 162.22449219), 'rotation':(-0.00412, 90.286934, -0.00412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2423.9216406200003, 864.82049805, 161.79919922), 'rotation':(-0.08963, 90.286903, -0.089905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2423.97777344, 853.66503906, 161.81665039), 'rotation':(-0.089691, 90.28833, -0.089996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.005625, 848.08709961, 161.82539062), 'rotation':(-0.089691, 90.28833, -0.089996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.08984375, 831.35375, 161.85210938), 'rotation':(-0.092621, 90.288383, -0.092926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.11792969, 825.7759375, 161.86119141), 'rotation':(-0.093475, 90.288383, -0.093781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.17382812, 814.62035156, 161.87960938), 'rotation':(-0.095184, 90.288391, -0.09549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.20191406, 809.0425390600001, 161.88894531), 'rotation':(-0.096039, 90.288399, -0.096344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.23, 803.46472656, 161.89833008), 'rotation':(-0.096405, 90.288109, -0.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.2580468799997, 797.88695312, 161.90771484), 'rotation':(-0.096405, 90.288109, -0.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.37011719, 775.57599609, 161.94511719), 'rotation':(-0.09552, 90.287018, -0.095825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.4821875, 753.26507812, 161.98214844), 'rotation':(-0.095154, 90.287659, -0.095459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.51023438, 747.6875, 161.99131836), 'rotation':(-0.094208, 90.287666, -0.094543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.53832031, 742.1098046899999, 162.00045898), 'rotation':(-0.094208, 90.287666, -0.094543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.62230469, 725.37664062, 162.02712891), 'rotation':(-0.090637, 90.287674, -0.090942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.67847656, 714.22130859, 162.0444043), 'rotation':(-0.088074, 90.28775, -0.088348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.7065625, 708.64355469, 162.05295898), 'rotation':(-0.088074, 90.28775, -0.088348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.13890625, 371.37980469, 163.67946289), 'rotation':(-0.126556, -90.6138, -0.127136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.13328125, 382.45238281, 163.70363281), 'rotation':(-0.126678, -90.615387, -0.127228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.25242188, 393.52769531, 163.72575195), 'rotation':(-0.107391, -90.614258, -0.107758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.37109375, 404.60304687999997, 163.74493164), 'rotation':(-0.094666, -90.614319, -0.095001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.49, 415.67718749999995, 163.76106445), 'rotation':(-0.081757, -90.614349, -0.082001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.54929688, 421.21507812000004, 163.76833984), 'rotation':(-0.07547, -90.614899, -0.075684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.66820312, 432.29023438, 163.78269531), 'rotation':(-0.07547, -90.614899, -0.075684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.78710938, 443.36578125000005, 163.79576172), 'rotation':(-0.063812, -90.614868, -0.063934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.90578125, 454.44128906000003, 163.80701172), 'rotation':(-0.056122, -90.614868, -0.056213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.9653125, 459.9788671900001, 163.81176758), 'rotation':(-0.048431, -90.613312, -0.048492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2533.02464844, 465.51609375, 163.81632812), 'rotation':(-0.048431, -90.613312, -0.048492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.3359375, 485.13750000000005, 163.82957031), 'rotation':(-0.029968, -90.615662, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2533.13695312, 474.06347656, 163.82273438), 'rotation':(-0.044525, -90.615051, -0.044586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.45117188, 493.20265625, 163.8330957), 'rotation':(-0.029968, -90.615662, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.87378906, 531.1730468799999, 163.83902344), 'rotation':(-0.00592, -90.614716, -0.00592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.93335938, 536.71003906, 163.83959961), 'rotation':(-0.00592, -90.614716, -0.00592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.05226562, 547.78363281, 163.84009766), 'rotation':(0.000266, -90.615448, 0.00027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2534.1115625, 553.3196875, 163.8390332), 'rotation':(0.012554, -90.613342, 0.012553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.23023438, 564.39324219, 163.83558594), 'rotation':(0.01881, -90.614563, 0.018801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2534.42726562, 592.07867188, 163.82508789), 'rotation':(0.025593, -90.614075, 0.025562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.44800781, 597.6160156200001, 163.82209961), 'rotation':(0.030128, -90.614075, 0.030093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.50046875, 603.15234375, 163.81869140999999), 'rotation':(0.034527, -90.614105, 0.034491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.55152344, 608.68675781, 163.81486328), 'rotation':(0.039793, -90.527527, 0.039746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.45019531, 675.08099609, 163.74265625), 'rotation':(0.080835, -89.089722, 0.080617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.73632812, 707.53699219, 163.69088867), 'rotation':(0.099892, -88.455231, 0.099558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2533.40699219, 718.59375, 163.67108398), 'rotation':(0.103033, -88.277588, 0.102664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.11230469, 724.1168749999999, 163.6609082), 'rotation':(0.104263, -88.143799, 0.103893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.88550781, 729.64275391, 163.65046875), 'rotation':(0.107152, -88.028229, 0.106762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.46386719, 740.69605469, 163.62874023), 'rotation':(0.112773, -87.797058, 0.112326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.99683594, 751.74804688, 163.60592773), 'rotation':(0.118381, -87.56842, 0.117903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.48363281, 762.79802734, 163.58208008), 'rotation':(0.124009, -87.337189, 0.123466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2530.92578125, 773.84240234, 163.5578418), 'rotation':(0.125389, -87.00351, 0.124838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.66257812, 779.37042969, 163.54571289), 'rotation':(0.125389, -87.00351, 0.124838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2530.16308594, 790.4227343800001, 163.5215625), 'rotation':(0.125081, -86.818054, 0.124529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2529.57375, 801.48236328, 163.49744141), 'rotation':(0.12476, -86.999969, 0.12422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2529.03417969, 812.5464453100001, 163.47336914), 'rotation':(0.124767, -87.197784, 0.124227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2528.78273438, 818.08154297, 163.46161132999998), 'rotation':(0.123039, -87.359009, 0.122512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2528.54273438, 823.61566406, 163.45017578), 'rotation':(0.119576, -87.477631, 0.119084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2528.31542969, 829.15039062, 163.43910156), 'rotation':(0.115977, -87.598785, 0.1155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2528.10007812, 834.68537109, 163.42837891), 'rotation':(0.112514, -87.717346, 0.112072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.70554688, 845.76006836, 163.40795898), 'rotation':(0.102139, -88.078186, 0.101783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.22753906, 856.82751953, 163.38886719), 'rotation':(0.096941, -88.312866, 0.09662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.05980469, 862.36291016, 163.37966796999999), 'rotation':(0.094878, -88.426453, 0.094565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.39964844, 894.6418457, 163.33360352), 'rotation':(0.074101, -89.067139, 0.073898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2526.38964844, 900.17950195, 163.32701172), 'rotation':(0.068206, -89.250214, 0.068049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.41234375, 905.7175293, 163.32066406), 'rotation':(0.065303, -89.412384, 0.065145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.36449219, 911.25415039, 163.31436523), 'rotation':(0.065153, -89.553741, 0.065018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.29371094, 927.86401367, 163.29833984), 'rotation':(0.050325, -89.833374, 0.05023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.30640625, 938.94140625, 163.29177734), 'rotation':(0.030654, -90.108734, 0.030619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.41796875, 955.55493164, 163.28429688), 'rotation':(0.025804, -90.527283, 0.025779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.47949219, 961.09307861, 163.28182617000002), 'rotation':(0.025798, -90.66864, 0.025779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.63453125, 972.16546631, 163.2790332), 'rotation':(0.017772, -90.809479, 0.017774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.71921875, 977.70019531, 163.27921875), 'rotation':(0.000492, -90.876007, 0.000486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2526.80394531, 983.23223877, 163.28008789), 'rotation':(-0.008881, -90.877258, -0.008881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.88867188, 988.76416016, 163.28094726999998), 'rotation':(-0.00885, -90.877258, -0.008881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.22730469, 1010.89208984, 163.28436523), 'rotation':(-0.008728, -90.877258, -0.008698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.42113281, 1033.02355957, 163.29050781), 'rotation':(-0.026917, -90.87561, -0.026947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.50585938, 1038.55615234, 163.29410156), 'rotation':(-0.039185, -90.877563, -0.039246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.70359375, 1049.61889648, 163.30360352), 'rotation':(-0.051056, -90.877563, -0.051147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.0158593799997, 487.64179688, 165.25582031000002), 'rotation':(0.010396, 89.730972, 0.010396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.98976562, 482.09363281000003, 165.25439452999998), 'rotation':(0.010396, 89.730972, 0.010396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.8596093799997, 454.34984375, 165.24580078), 'rotation':(0.017294, 89.731392, 0.017284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.83351562, 448.80132812, 165.24345703), 'rotation':(0.02174, 89.731621, 0.021719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.75511719, 432.15527344, 165.23222656000002), 'rotation':(0.040155, 89.731636, 0.040104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.72925781, 426.6071875, 165.22734375), 'rotation':(0.049259, 89.729752, 0.049168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2617.703125, 421.05835937999996, 165.22212890999998), 'rotation':(0.053931, 89.731102, 0.053832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.625, 404.41277344, 165.20482422), 'rotation':(0.066369, 89.730667, 0.066216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.59886719, 398.86406250000005, 165.19808593999997), 'rotation':(0.071594, 89.730667, 0.071429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.57273438, 393.3153125, 165.19085938), 'rotation':(0.076498, 89.730675, 0.076306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.52074219, 382.21789062000005, 165.17484375), 'rotation':(0.086634, 89.730721, 0.086385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.49460938, 376.66917968999996, 165.16611328), 'rotation':(0.091538, 89.730728, 0.091254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.76734375, 675.23503906, 165.13373047000002), 'rotation':(-0.06665, 89.730721, -0.066803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.82128906, 669.86101562, 165.13986328), 'rotation':(-0.065247, 89.730721, -0.065399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.84546875, 664.31707031, 165.14617188), 'rotation':(-0.065247, 89.730721, -0.065399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.81933594, 658.77125, 165.15242188), 'rotation':(-0.064667, 89.731247, -0.064819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.7934375, 653.22546875, 165.15859375), 'rotation':(-0.064667, 89.731239, -0.064819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.68921875, 631.04167969, 165.18181640999998), 'rotation':(-0.057495, 89.730408, -0.057587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.66332031, 625.49589844, 165.18712890999998), 'rotation':(-0.054688, 89.732063, -0.05481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.61132812, 614.4042187499999, 165.19751953), 'rotation':(-0.053162, 89.731041, -0.053253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.5590625, 603.31257812, 165.20748047), 'rotation':(-0.050476, 89.730042, -0.050537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.53320312, 597.76667969, 165.21222656), 'rotation':(-0.048676, 89.732651, -0.048737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.4809375, 586.67488281, 165.22109375), 'rotation':(-0.044891, 89.730019, -0.044952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.45507812, 581.12898438, 165.22525391), 'rotation':(-0.043243, 89.732643, -0.043304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.4028125, 570.03742188, 165.23302734), 'rotation':(-0.03949, 89.732635, -0.039551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.37671875, 564.4919531200001, 165.23662109), 'rotation':(-0.038452, 89.730255, -0.038513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.35082031, 558.94597656, 165.24), 'rotation':(-0.035004, 89.730919, -0.035065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.27269531, 542.30851562, 165.24732422), 'rotation':(-0.020477, 89.730904, -0.020477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.7790625, 863.10949219, 164.92076172), 'rotation':(-0.050293, 89.731804, -0.050385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.7009375, 846.47748047, 164.93539062), 'rotation':(-0.050293, 89.729179, -0.050385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.64890625, 835.38958984, 164.945625), 'rotation':(-0.052246, 89.731239, -0.052338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.54492188, 813.21380859, 164.96851562), 'rotation':(-0.059784, 89.731247, -0.059906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.49265625, 802.12566406, 164.98099609000002), 'rotation':(-0.065399, 89.729828, -0.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.4665625, 796.58166016, 164.98732422), 'rotation':(-0.065399, 89.729828, -0.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.3884375, 779.94996094, 165.00666016), 'rotation':(-0.067139, 89.730705, -0.067291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.28441406, 757.77441406, 165.03351562), 'rotation':(-0.07016, 89.731323, -0.070343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2619.12816406, 724.51105469, 165.07431641), 'rotation':(-0.070465, 89.73288, -0.070618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.05003906, 707.87939453, 165.09480469), 'rotation':(-0.070557, 89.730385, -0.07074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.89039062, 493.99929688, 166.61132812), 'rotation':(-0.035217, 90.334564, -0.035248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.11695312, 477.40699219, 166.61958984), 'rotation':(-0.026611, 90.334564, -0.026642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2712.18164062, 466.344375, 166.62431641), 'rotation':(-0.024384, 90.334953, -0.024414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.24632812, 455.28257812000004, 166.62837890999998), 'rotation':(-0.017181, 90.336113, -0.017212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2712.27855469, 449.75171875, 166.6290625), 'rotation':(-0.002808, 90.334053, -0.002808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2712.34326172, 438.69000000000005, 166.62859375), 'rotation':(0.00433, 90.336021, 0.004332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.37574219, 433.15863281, 166.62818359000002), 'rotation':(0.00433, 90.333473, 0.004321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.44042969, 422.09613281, 166.62734375), 'rotation':(0.00433, 90.336021, 0.004332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.53734375, 405.5023046900001, 166.62607422000002), 'rotation':(0.00433, 90.336021, 0.004332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.60205078, 394.44109375000005, 166.62367188), 'rotation':(0.021351, 90.336166, 0.021333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.63453125, 388.91015625, 166.62085938), 'rotation':(0.032703, 90.333473, 0.032672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.556875, 382.3046875, 166.61595703), 'rotation':(-0.049744, -89.664917, -0.049835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.51464844, 388.95617187999994, 166.62085938), 'rotation':(-0.044067, -89.663788, -0.044128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.4821875, 394.4871875, 166.62367188), 'rotation':(-0.032684, -89.666504, -0.032745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.41748047, 405.54835937999997, 166.62607422000002), 'rotation':(-0.01001, -89.666534, -0.009979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.38525391, 411.07953124999995, 166.62650391), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.35277344, 416.6109765599999, 166.62693359000002), 'rotation':(-0.004333, -89.666504, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.32007812, 422.14238280999996, 166.62734375), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.28808594, 427.6734765599999, 166.62775391), 'rotation':(-0.004333, -89.666504, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.25585938, 433.2047265599999, 166.62816406000002), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.22339844, 438.73609375, 166.62859375), 'rotation':(-0.004333, -89.666504, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.19117188, 444.26726562, 166.62900391), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.12646484, 455.32859375, 166.62837890999998), 'rotation':(0.0028, -89.665924, 0.002808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.02953125, 471.92175781000003, 166.62195312), 'rotation':(0.024486, -89.666565, 0.024466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.99730469, 477.45300781000003, 166.61958984), 'rotation':(0.024384, -89.665039, 0.024369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.02978516, 494.04691406, 166.61132812), 'rotation':(0.0309, -89.665405, 0.030863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.82886719, 675.65337891, 166.40589844), 'rotation':(-0.080444, 90.33429, -0.080658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.95410156, 666.89, 166.41820312), 'rotation':(-0.080292, 90.33429, -0.080505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.11988281, 648.01367188, 166.44443359000002), 'rotation':(-0.078674, 90.335495, -0.078888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.15210938, 642.48558594, 166.45199218999997), 'rotation':(-0.078064, 90.33548, -0.078278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.21679688, 631.4294531200001, 166.46689453), 'rotation':(-0.07666, 90.33548, -0.076843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.28125, 620.37324219, 166.48158203), 'rotation':(-0.075409, 90.335487, -0.075592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.31371094, 614.84515625, 166.48882812), 'rotation':(-0.075409, 90.335487, -0.075592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.34619141, 609.3172656200001, 166.49603516), 'rotation':(-0.075012, 90.336395, -0.075195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.41064453, 598.26109375, 166.51005859), 'rotation':(-0.073761, 90.33371, -0.073944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.50757812, 581.676875, 166.53011718999997), 'rotation':(-0.068573, 90.335152, -0.068726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.57226562, 570.62085938, 166.54277344), 'rotation':(-0.06601, 90.335152, -0.066162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.66917969, 554.03691406, 166.5609375), 'rotation':(-0.061798, 90.336906, -0.061951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.73363281, 542.9807812500001, 166.57212891), 'rotation':(-0.055786, 90.334221, -0.055908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.76611328, 537.4528124999999, 166.57742188), 'rotation':(-0.053986, 90.336899, -0.054077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.67847656, 531.97070312, 166.58251952999998), 'rotation':(0.050127, -89.665771, 0.05004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.64625, 537.49871094, 166.57742188), 'rotation':(0.051964, -89.665802, 0.051872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.51683594, 559.61089844, 166.55507812), 'rotation':(0.061827, -89.663086, 0.061691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.41992188, 576.19464844, 166.53648438), 'rotation':(0.064607, -89.664948, 0.064454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.35546875, 587.25085938, 166.52355468999997), 'rotation':(0.066014, -89.664856, 0.065856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.29078125, 598.3069921900001, 166.51005859), 'rotation':(0.071116, -89.66629, 0.070935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.25855469, 603.83507812, 166.503125), 'rotation':(0.071116, -89.66629, 0.070935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.22632812, 609.3631640599999, 166.49601562), 'rotation':(0.073752, -89.664795, 0.073567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.09691406, 631.47535156, 166.46689453), 'rotation':(0.076013, -89.667023, 0.075818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.03222656, 642.5313671900001, 166.45199218999997), 'rotation':(0.077277, -89.66449, 0.077068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.96777344, 653.58757812, 166.43681641), 'rotation':(0.078684, -89.66449, 0.078468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2718.75244141, 708.78753906, 166.35962891), 'rotation':(0.080029, -89.664307, 0.079802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.51976562, 730.20056641, 166.33001953), 'rotation':(0.078199, -89.665588, 0.07798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.4553125, 741.25335938, 166.31507812), 'rotation':(0.076812, -89.664124, 0.076616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.42308594, 746.77972656, 166.30771484000002), 'rotation':(0.076812, -89.664124, 0.076616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2718.26123047, 774.41222656, 166.27197266), 'rotation':(0.07143, -89.666229, 0.071249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.16455078, 790.99158203, 166.25201172), 'rotation':(0.067086, -89.663757, 0.066917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.13207031, 796.51806641, 166.24564453), 'rotation':(0.065522, -89.66626, 0.065371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2718.06761719, 807.57111328, 166.23326172), 'rotation':(0.064129, -89.663757, 0.063981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.00292969, 818.62425781, 166.22123047000002), 'rotation':(0.061759, -89.665741, 0.061633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2717.97070312, 824.15082031, 166.21546875), 'rotation':(0.061759, -89.665741, 0.061633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.90601562, 835.20373047, 166.20451172), 'rotation':(0.055167, -89.665771, 0.05506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.84130859, 846.2565918, 166.19435547), 'rotation':(0.051862, -89.664185, 0.051772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2709.86449219, 862.79064453, 166.18046875), 'rotation':(-0.043671, 90.336174, -0.043762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.89671875, 857.26404297, 166.18486328), 'rotation':(-0.043671, 90.336174, -0.043762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.92894531, 851.73760742, 166.18949218999998), 'rotation':(-0.047974, 90.334503, -0.048065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.02587891, 835.15783203, 166.20451172), 'rotation':(-0.05188, 90.335831, -0.051971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.05810547, 829.63134766, 166.20984375), 'rotation':(-0.055176, 90.334229, -0.055267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.09058594, 824.10492188, 166.21546875), 'rotation':(-0.058472, 90.335831, -0.058594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.15503906, 813.05193359, 166.22716797), 'rotation':(-0.061768, 90.334251, -0.06189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.21972656, 801.99853516, 166.23939453), 'rotation':(-0.063385, 90.334534, -0.063538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.28441406, 790.9457421899999, 166.25201172), 'rotation':(-0.065521, 90.333733, -0.065674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.31664062, 785.419375, 166.25853515999998), 'rotation':(-0.067078, 90.336235, -0.06723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.44580078, 763.31347656, 166.28595703), 'rotation':(-0.072845, 90.336258, -0.073029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2710.47828125, 757.78679688, 166.29316406), 'rotation':(-0.074249, 90.333771, -0.074432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.63964844, 730.15466797, 166.33001953), 'rotation':(-0.076813, 90.334381, -0.077026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2710.671875, 724.62830078, 166.33755859000001), 'rotation':(-0.078186, 90.335854, -0.0784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2710.70605469, 713.5772656199999, 166.35289062), 'rotation':(-0.079376, 90.334396, -0.07959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.65015625, 708.05175781, 166.36058594), 'rotation':(-0.079926, 90.335693, -0.080139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2717.32886719, 933.94726562, 166.14769531000002), 'rotation':(-9.2e-05, -89.665527, -9.2e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.26441406, 945.00140625, 166.14769531000002), 'rotation':(-9.2e-05, -89.664124, -9.2e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.10277344, 972.63763428, 166.14808594), 'rotation':(-0.004181, -89.665375, -0.004181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.03808594, 983.69238281, 166.15087891), 'rotation':(-0.020477, -89.662964, -0.020477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.00585938, 989.21984863, 166.15339844), 'rotation':(-0.028534, -89.665344, -0.028564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.97339844, 994.74768066, 166.15640625), 'rotation':(-0.028534, -89.665344, -0.028564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.74730469, 1033.43908691, 166.1853125), 'rotation':(-0.06012, -89.665222, -0.060242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.8671875, 1033.39318848, 166.1853125), 'rotation':(0.071177, 90.336411, 0.071017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.89941406, 1027.8659668, 166.17951172000002), 'rotation':(0.060119, 90.334763, 0.059989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.931875, 1022.33843994, 166.17441406), 'rotation':(0.060119, 90.334763, 0.059989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.99632812, 1011.28387451, 166.16609375), 'rotation':(0.038078, 90.334724, 0.038037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.22265625, 972.59161377, 166.14808594), 'rotation':(0.012247, 90.334602, 0.012239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.25488281, 967.06378174, 166.14773438), 'rotation':(0.004187, 90.33461, 0.004184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.28734375, 961.53668213, 166.14771484000002), 'rotation':(7.5e-05, 90.334488, 8.8e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2709.31957031, 956.00958008, 166.14771484000002), 'rotation':(7.5e-05, 90.334488, 8.8e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.41650391, 939.42834473, 166.14769531000002), 'rotation':(8.9e-05, 90.335884, 8.4e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.48095703, 928.37408203, 166.14769531000002), 'rotation':(7.5e-05, 90.334488, 8.8e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.5134375, 922.8463134799999, 166.14826172000002), 'rotation':(-0.006683, 90.335136, -0.006683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.578125, 911.7909570300001, 166.15238281), 'rotation':(-0.019745, 90.335152, -0.019775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.34057617, 379.40539062000005, 170.16193359000002), 'rotation':(0.09634, -90.588562, 0.096022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.51416016, 396.28710937999995, 170.13277344), 'rotation':(0.10233, -90.588989, 0.101971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2982.57177734, 401.91417968999997, 170.12251952999998), 'rotation':(0.104939, -90.586212, 0.104547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.62963867, 407.54148437999993, 170.11203125), 'rotation':(0.107343, -90.588989, 0.106953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.8034668, 424.42285156, 170.07892578), 'rotation':(0.115765, -90.586304, 0.115301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.77026367, 446.91820312000004, 170.03230469), 'rotation':(0.121782, -90.098206, 0.121261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2982.63574219, 469.42234375, 169.98140625), 'rotation':(0.133899, -89.417725, 0.133278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.36791992, 486.30480468999997, 169.94136719), 'rotation':(0.136706, -88.920471, 0.136059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.24731445, 491.93914062000005, 169.92769531000002), 'rotation':(0.136706, -88.920471, 0.136059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.11450195, 497.56644531, 169.91386719), 'rotation':(0.140128, -88.689545, 0.13944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2981.79516602, 508.81671875, 169.88541016), 'rotation':(0.146753, -88.229309, 0.146001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2981.61499023, 514.45039062, 169.87091797000002), 'rotation':(0.146753, -88.229309, 0.146001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2981.20507812, 525.6988671900001, 169.84173828), 'rotation':(0.148447, -87.815338, 0.14768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2980.97387695, 531.3236718799999, 169.82705077999998), 'rotation':(0.149458, -87.59906, 0.148683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2980.73071289, 536.95433594, 169.81228516), 'rotation':(0.149458, -87.59906, 0.148683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2979.6003418, 559.4371874999999, 169.75193359000002), 'rotation':(0.155271, -86.902863, 0.154453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2979.27758789, 565.0540625, 169.7365625), 'rotation':(0.15637, -86.694214, 0.155508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2978.94116211, 570.67039062, 169.72121094), 'rotation':(0.15635, -86.527313, 0.155509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2977.98120117, 587.5194140599999, 169.67511718999998), 'rotation':(0.156357, -86.098511, 0.15551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2977.16650391, 598.735, 169.64443359), 'rotation':(0.15635, -85.809784, 0.155506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2976.73608398, 604.33941406, 169.62908202999998), 'rotation':(0.156186, -85.666718, 0.155329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2975.45239258, 621.18644531, 169.583125), 'rotation':(0.155175, -85.755493, 0.154334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.67382812, 632.4395312500001, 169.55400391), 'rotation':(0.14715, -86.075867, 0.146398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.96118164, 643.7008593799999, 169.52654297), 'rotation':(0.139295, -86.396118, 0.138624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.31420898, 654.97441406, 169.50066406000002), 'rotation':(0.127178, -86.873657, 0.126619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.0144043, 660.60945312, 169.48824219), 'rotation':(0.125395, -87.013763, 0.124851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2964.43115234, 671.9371874999999, 169.46355469), 'rotation':(-0.113312, 92.50412, -0.11377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.82885742, 660.6941406200001, 169.48714843999997), 'rotation':(-0.122253, 92.848267, -0.122772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.12646484, 655.0775, 169.49945312), 'rotation':(-0.124634, 92.990799, -0.125183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2966.47338867, 632.63300781, 169.55216797), 'rotation':(-0.142334, 93.76442, -0.143066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2966.85107422, 627.025625, 169.56634766), 'rotation':(-0.14624, 93.923615, -0.147003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2967.65527344, 615.8180468799999, 169.59595703), 'rotation':(-0.154236, 94.244637, -0.15506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2968.08300781, 610.21699219, 169.61123047), 'rotation':(-0.155396, 94.325706, -0.156219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.95288086, 599.00105469, 169.64199219), 'rotation':(-0.157257, 94.477531, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2969.37133789, 593.37574219, 169.65746094), 'rotation':(-0.157257, 94.186981, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.8894043, 570.86402344, 169.71931641), 'rotation':(-0.157257, 93.614532, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2971.55371094, 559.6065625, 169.75023438), 'rotation':(-0.157288, 93.305969, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.43359375, 542.6839453099999, 169.79609375), 'rotation':(-0.154266, 92.864075, -0.155121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.93798828, 531.4117578099999, 169.8259375), 'rotation':(-0.152252, 92.633492, -0.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.38598633, 520.13023438, 169.85542969), 'rotation':(-0.149323, 92.183464, -0.150085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.58374023, 514.48304688, 169.87013672), 'rotation':(-0.14917, 91.9869, -0.149963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.76538086, 508.83992187999996, 169.88472656000002), 'rotation':(-0.14917, 91.9869, -0.149963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.70947266, 458.03691405999996, 170.00757812), 'rotation':(-0.132141, 90.445862, -0.132751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.73510742, 452.3968359400001, 170.02027343999998), 'rotation':(-0.129791, 90.308952, -0.130341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.74023438, 441.11460937999993, 170.04476562), 'rotation':(-0.122498, 89.901237, -0.123016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.68237305, 429.83472656000004, 170.06816406000002), 'rotation':(-0.117401, 89.630409, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.63061523, 424.20179687999996, 170.07955077999998), 'rotation':(-0.116272, 89.487808, -0.11676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.34130859, 396.07484375, 170.13328125), 'rotation':(-0.10495, 89.411018, -0.105316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.28344727, 390.44984375, 170.14324219), 'rotation':(-0.102356, 89.410988, -0.102692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.16796875, 379.19984375, 170.16242188), 'rotation':(-0.097504, 89.410995, -0.097839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.43652344, 837.51085938, 169.30771484000002), 'rotation':(0.003893, 89.116989, 0.003894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.26538086, 826.41234375, 169.30716797000002), 'rotation':(0.001127, 89.116188, 0.001129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.09399414, 815.31396484, 169.30841797000002), 'rotation':(-0.010773, 89.116188, -0.010742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.92285156, 804.21539062, 169.31175781000002), 'rotation':(-0.019623, 89.116966, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.8371582, 798.66638672, 169.31367188000002), 'rotation':(-0.019623, 89.116966, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.75170898, 793.11724609, 169.31560547), 'rotation':(-0.019592, 89.115143, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2962.49291992, 770.92578125, 169.32716797), 'rotation':(-0.03833, 89.598129, -0.038391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.48339844, 748.73474609, 169.34642578), 'rotation':(-0.057007, 90.267006, -0.057129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.57592773, 737.63757812, 169.35841797), 'rotation':(-0.063507, 90.533195, -0.06366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.83398438, 721.0063476600001, 169.37978515999998), 'rotation':(-0.080414, 91.1334, -0.080658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.95166016, 715.46289062, 169.3878125), 'rotation':(-0.084595, 91.281372, -0.084869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.96777344, 709.92865234, 169.39658203), 'rotation':(0.091586, -88.430237, 0.09129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.67211914, 732.11224609, 169.36519531000002), 'rotation':(0.072496, -89.165802, 0.07231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.60180664, 737.6582617199999, 169.35849609000002), 'rotation':(0.068268, -89.314697, 0.068122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.50854492, 748.75408203, 169.34644531), 'rotation':(0.059675, -89.612366, 0.059552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.48803711, 754.30394531, 169.34095703), 'rotation':(0.055488, -89.850952, 0.055377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.49121094, 765.39898438, 169.33121093999998), 'rotation':(0.047121, -90.124634, 0.047057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.6940918, 787.59435547, 169.31769531), 'rotation':(0.02603, -90.814819, 0.02601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.20532227, 820.83947266, 169.3075), 'rotation':(0.010758, -90.88382, 0.010759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.29077148, 826.38, 169.30716797000002), 'rotation':(0.004979, -90.883789, 0.004982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.3762207, 831.92029297, 169.30734375), 'rotation':(-0.001129, -90.88382, -0.001129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.46166992, 837.46026367, 169.30771484000002), 'rotation':(-0.003906, -90.883026, -0.003906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.57324219, 854.08282227, 169.30884766), 'rotation':(-0.003998, -90.884796, -0.003998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2966.07470703, 1008.59387207, 169.44416016), 'rotation':(0.098662, 89.116859, 0.09832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.98925781, 1003.04907227, 169.43519531), 'rotation':(0.098662, 89.116859, 0.09832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.90356445, 997.50384521, 169.42652343999998), 'rotation':(0.090138, 89.116814, 0.089864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.64697266, 980.87005615, 169.40205078), 'rotation':(0.082516, 89.117088, 0.082282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.56152344, 975.32537842, 169.39443359), 'rotation':(0.082516, 89.117088, 0.082282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.390625, 964.23620605, 169.38029297), 'rotation':(0.075692, 89.117065, 0.075487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.30493164, 958.69170898, 169.37363281), 'rotation':(0.068937, 89.115654, 0.06877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.1340332, 947.60199219, 169.36164062), 'rotation':(0.062189, 89.117035, 0.062058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.96313477, 936.51245117, 169.35054688), 'rotation':(0.055687, 89.116264, 0.05558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.87768555, 930.96783203, 169.34529297), 'rotation':(0.055687, 89.116264, 0.05558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2964.70654297, 919.87866211, 169.33599609), 'rotation':(0.049355, 89.116257, 0.049275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.62109375, 914.33428711, 169.33181641), 'rotation':(0.043112, 89.117683, 0.043057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.53564453, 908.78960938, 169.32808594), 'rotation':(0.043112, 89.117683, 0.043057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.36450195, 897.70007812, 169.32125), 'rotation':(0.033598, 89.116707, 0.033561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2972.32958984, 903.1319531199999, 169.32453125), 'rotation':(-0.0336, -90.883301, -0.03363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.50048828, 914.22051758, 169.33183594), 'rotation':(-0.036896, -90.883728, -0.036926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.58618164, 919.76464844, 169.33599609), 'rotation':(-0.043121, -90.883759, -0.043182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2972.67163086, 925.30902344, 169.34050781000002), 'rotation':(-0.043121, -90.883759, -0.043182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.09912109, 953.03100586, 169.36759766), 'rotation':(-0.058777, -90.883301, -0.058899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.18457031, 958.57549805, 169.37363281), 'rotation':(-0.062195, -90.884369, -0.062347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2973.27001953, 964.11956787, 169.3803125), 'rotation':(-0.068939, -90.882935, -0.069092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.35571289, 969.66394043, 169.38712891), 'rotation':(-0.068939, -90.882935, -0.069092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.44116211, 975.20800781, 169.39445312), 'rotation':(-0.075684, -90.882935, -0.075897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.52661133, 980.75244141, 169.40205078), 'rotation':(-0.075684, -90.882935, -0.075897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.78320312, 997.38537598, 169.42654297), 'rotation':(-0.085938, -90.882812, -0.086182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.21069336, 1025.10766602, 169.47441406000002), 'rotation':(-0.107269, -90.883118, -0.107666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.45166016, 1036.19213867, 169.49707031000003), 'rotation':(-0.120026, -90.881989, -0.120514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3152.83056641, 380.999375, 172.22105469), 'rotation':(0.183486, -89.100708, 0.182316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3152.47314453, 397.57378905999997, 172.16806641), 'rotation':(0.182858, -89.101654, 0.181691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3152.38647461, 403.09984375, 172.15056640999998), 'rotation':(0.181628, -89.100037, 0.180484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.95288086, 430.73058593999997, 172.06400391), 'rotation':(0.178247, -89.10141, 0.177148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3151.60620117, 452.8353125, 171.99572265999998), 'rotation':(0.173432, -89.100037, 0.172386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.17285156, 480.4664453099999, 171.9146875), 'rotation':(0.165577, -89.100525, 0.164622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.99951172, 491.51878905999996, 171.88296875), 'rotation':(0.163474, -89.101379, 0.162544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3152.98706055, 373.07164062000004, 172.24646484000002), 'rotation':(0.183636, -89.100708, 0.182479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.11914062, 491.46152344, 171.88277344), 'rotation':(-0.159485, 90.898537, -0.16037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.20581055, 485.92921875, 171.89857422), 'rotation':(-0.163483, 90.898613, -0.164398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.46630859, 469.33179687999996, 171.94652344), 'rotation':(-0.165588, 90.899467, -0.166534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.63989258, 458.26703124999995, 171.97904297000002), 'rotation':(-0.17041, 90.897911, -0.171417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.7265625, 452.73460937999994, 171.99566406000002), 'rotation':(-0.17041, 90.897911, -0.171417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.90014648, 441.6695703099999, 172.02958984), 'rotation':(-0.176575, 90.897957, -0.177704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.98681641, 436.13734375, 172.04679688), 'rotation':(-0.178253, 90.900055, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.07373047, 430.60503905999997, 172.06400391), 'rotation':(-0.178253, 90.900055, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.16040039, 425.07269531, 172.08123047), 'rotation':(-0.178253, 90.898567, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.24731445, 419.54027343999996, 172.09847656000002), 'rotation':(-0.178253, 90.898567, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.73706055, 386.3471875, 172.20353516), 'rotation':(-0.182831, 90.898323, -0.184021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.40209961, 529.6129296900001, 171.78080078), 'rotation':(0.146248, -89.100342, 0.145492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.87988281, 562.9096093799999, 171.69980468999998), 'rotation':(0.133325, -89.10022, 0.132706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.61865234, 579.5582421900001, 171.663125), 'rotation':(0.124685, -89.100281, 0.124156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.53149414, 585.10773438, 171.65125), 'rotation':(0.123326, -89.101227, 0.122799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.65112305, 585.0569531200001, 171.65109375), 'rotation':(-0.120972, 90.899162, -0.12149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.91308594, 568.35625, 171.68726562), 'rotation':(-0.124695, 90.899742, -0.125244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3142.00048828, 562.7893750000001, 171.69978516), 'rotation':(-0.130341, 90.897118, -0.13092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.08764648, 557.22265625, 171.71261718999997), 'rotation':(-0.133331, 90.89978, -0.133942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.17504883, 551.6558984400001, 171.72574218999998), 'rotation':(-0.136139, 90.89978, -0.13678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.34960938, 540.5222656200001, 171.75287109), 'rotation':(-0.141937, 90.899818, -0.142639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.43701172, 534.955625, 171.766875), 'rotation':(-0.144775, 90.899841, -0.145508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.52416992, 529.38847656, 171.78107422000002), 'rotation':(-0.146118, 90.899544, -0.146851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.80053711, 639.68488281, 171.54994141), 'rotation':(-0.092865, 90.8106, -0.09317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.58862305, 656.35484375, 171.5246875), 'rotation':(-0.077728, 90.606339, -0.077942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.5300293, 661.9102734400001, 171.51716797), 'rotation':(-0.070099, 90.504242, -0.070251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.47924805, 667.4665625, 171.51021484), 'rotation':(-0.066376, 90.40844, -0.066498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.39257812, 678.58117188, 171.49705078), 'rotation':(-0.062317, 90.311211, -0.062439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.36083984, 684.14007812, 171.4909375), 'rotation':(-0.062317, 90.311211, -0.062439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.93701172, 622.9957812499999, 171.57826172), 'rotation':(0.099106, -89.101562, 0.09877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.85009766, 628.55144531, 171.56871094), 'rotation':(0.099106, -89.101562, 0.09877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.76318359, 634.106875, 171.55933593999998), 'rotation':(0.096804, -89.10144, 0.096475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.68188477, 639.66339844, 171.55015625), 'rotation':(0.096886, -89.118286, 0.096557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.53735352, 650.7808984400001, 171.53283202999998), 'rotation':(0.085507, -89.291443, 0.08525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.24145508, 684.12810547, 171.49099609), 'rotation':(0.066526, -89.590576, 0.066358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.23706055, 733.07097656, 171.45402344), 'rotation':(0.030114, -90.1828, 0.030078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.34008789, 744.13152344, 171.44886719), 'rotation':(0.030019, -90.276794, 0.029982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.50244141, 755.19548828, 171.4465625), 'rotation':(0.00517, -90.478455, 0.005162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.55322266, 760.72705078, 171.44650391), 'rotation':(-0.003021, -90.55835, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.546875, 766.2580468799999, 171.44679688), 'rotation':(-0.003021, -90.620087, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.65087891, 777.31580078, 171.44738281000002), 'rotation':(-0.003174, -90.648407, -0.003143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.70263672, 782.84423828, 171.44769531000003), 'rotation':(-0.003021, -90.650452, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.75439453, 788.37255859, 171.44796875), 'rotation':(-0.003021, -90.648438, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.96606445, 810.486875, 171.4509375), 'rotation':(-0.014557, -90.648376, -0.014587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.02880859, 816.01544922, 171.45271484), 'rotation':(-0.014557, -90.648376, -0.014587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.09155273, 821.54371094, 171.45484375), 'rotation':(-0.022156, -90.649963, -0.022186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.15405273, 827.07208984, 171.45767578), 'rotation':(-0.029724, -90.648346, -0.029785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3149.2878418, 838.12890625, 171.46396484000002), 'rotation':(-0.03363, -90.649384, -0.033691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.39477539, 843.65625, 171.46738281), 'rotation':(-0.035828, -90.648956, -0.035858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.50146484, 849.18365234, 171.47115234), 'rotation':(-0.035828, -90.648956, -0.035858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.61328125, 856.15478516, 171.47626953), 'rotation':(-0.040131, -90.648956, -0.040192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.50512695, 860.3215332, 171.47945312), 'rotation':(0.048972, 89.351044, 0.048896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3141.42773438, 849.26068359, 171.47115234), 'rotation':(0.040127, 89.349297, 0.040076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3141.35986328, 838.20043945, 171.46394531), 'rotation':(0.035804, 89.351013, 0.035771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.30834961, 832.67035156, 171.46064453), 'rotation':(0.033639, 89.350594, 0.033595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.27368164, 827.13947266, 171.45765625), 'rotation':(0.033639, 89.350594, 0.033595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.96044922, 799.48957031, 171.44880859), 'rotation':(0.006885, 89.350029, 0.006883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.89770508, 793.95904297, 171.44828125), 'rotation':(0.006885, 89.350029, 0.006883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.83520508, 788.4292578100001, 171.44796875), 'rotation':(0.003026, 89.351578, 0.003033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.77246094, 782.89947266, 171.44767578), 'rotation':(0.003026, 89.351578, 0.003033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.70996094, 777.36957031, 171.44738281000002), 'rotation':(0.003033, 89.349548, 0.00303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.58642578, 766.31, 171.44681641), 'rotation':(0.003149, 89.351578, 0.003159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.52954102, 760.78107422, 171.44650391), 'rotation':(0.003012, 89.381371, 0.003018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.47753906, 755.25238281, 171.4465625), 'rotation':(0.003019, 89.440292, 0.003013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.39331055, 744.19695312, 171.44884765999998), 'rotation':(-0.02179, 89.625298, -0.02179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.33227539, 733.1394726599999, 171.45400390999998), 'rotation':(-0.029938, 89.723869, -0.029968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.10253906, 899.33587891, 171.51691406), 'rotation':(-0.060638, -90.649414, -0.06076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.23120117, 914.71880859, 171.53519531), 'rotation':(-0.071198, -90.649445, -0.071381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.25415039, 920.2491455100001, 171.54234375), 'rotation':(-0.071198, -90.649445, -0.071381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.39794922, 936.8392334, 171.56503906), 'rotation':(-0.080475, -90.648499, -0.080688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.5859375, 953.42950195, 171.58945312), 'rotation':(-0.085785, -90.65094, -0.08606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.6484375, 958.95941406, 171.59810547), 'rotation':(-0.088531, -90.648499, -0.088806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.77392578, 970.01959229, 171.61617188), 'rotation':(-0.094025, -90.648468, -0.09433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.83642578, 975.54974365, 171.62558593999998), 'rotation':(-0.096771, -90.650909, -0.097107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.96191406, 986.61004639, 171.64494141), 'rotation':(-0.1008, -90.649414, -0.101166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3151.0246582, 992.14050293, 171.65484375), 'rotation':(-0.1008, -90.649414, -0.101166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3151.27490234, 1014.26074219, 171.69734375), 'rotation':(-0.115204, -90.648834, -0.115692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.33764648, 1019.79101562, 171.70888672), 'rotation':(-0.115204, -90.648834, -0.115692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.57275391, 1030.84643555, 171.73253906000002), 'rotation':(-0.123962, -90.649353, -0.124512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.50390625, 1026.07751465, 171.72205078), 'rotation':(0.123954, 89.350632, 0.123422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.33227539, 1008.81787109, 171.68621094), 'rotation':(0.115205, 89.351158, 0.114742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.14428711, 992.22650146, 171.65484375), 'rotation':(0.103689, 89.35112, 0.103309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.89355469, 970.10424805, 171.61617188), 'rotation':(0.096777, 89.351532, 0.09645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.45507812, 931.39105469, 171.55732422), 'rotation':(0.080466, 89.351471, 0.080246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.38793945, 925.86138672, 171.54970702999998), 'rotation':(0.079018, 89.351974, 0.078815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.28564453, 920.33178711, 171.54232422), 'rotation':(0.076437, 89.350548, 0.076241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.16455078, 913.79449219, 171.53394531), 'rotation':(0.076437, 89.350548, 0.076241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.41648438, 498.44351562, 174.23935547000002), 'rotation':(-0.111938, 90.147209, -0.112366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.43066406, 492.89144531, 174.25072265999998), 'rotation':(-0.116364, 90.144501, -0.116852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.45898438, 481.78722656, 174.27472656), 'rotation':(-0.125214, 90.144524, -0.125763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.47289062, 476.23542969000005, 174.28707031000002), 'rotation':(-0.127228, 90.144951, -0.127808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.55710938, 442.92320312000004, 174.36699219), 'rotation':(-0.150757, 90.144836, -0.15152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.6271875, 415.16273437999996, 174.44224609), 'rotation':(-0.160126, 90.146751, -0.161011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.64109375, 409.61070312000004, 174.45820312), 'rotation':(-0.16391, 90.14402, -0.164856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.683125, 392.95484375, 174.50857422), 'rotation':(-0.175812, 90.144089, -0.17691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.54957031, 398.52613281000004, 174.49138672), 'rotation':(0.175816, -89.855896, 0.174739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.52148438, 409.63, 174.45820312), 'rotation':(0.167879, -89.855957, 0.166893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.47925781, 426.28644531, 174.41160156), 'rotation':(0.155967, -89.853271, 0.155131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.45117188, 437.39015625, 174.38173827999998), 'rotation':(0.154157, -89.854126, 0.153338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.4372656200003, 442.9425, 174.36699219), 'rotation':(0.154157, -89.854126, 0.153338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.39527344, 459.59851562000006, 174.32509765999998), 'rotation':(0.137362, -89.855194, 0.13671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.3671875, 470.70300781000003, 174.29941406), 'rotation':(0.130627, -89.855255, 0.130021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.339375, 481.80664062000005, 174.27472656), 'rotation':(0.12724, -89.855042, 0.126679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.32519531, 487.35890625, 174.26253906000002), 'rotation':(0.125225, -89.855438, 0.124679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.296875, 498.46289062000005, 174.23935547000002), 'rotation':(0.116373, -89.855469, 0.115908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.20777344, 581.2189843799999, 174.11542968999998), 'rotation':(-0.059784, 90.143173, -0.059906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.23585938, 570.04316406, 174.12755859), 'rotation':(-0.062012, 90.145576, -0.062134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.25, 564.455625, 174.13400391), 'rotation':(-0.06601, 90.143997, -0.066162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.27808594, 553.28046875, 174.14800781000002), 'rotation':(-0.073883, 90.145546, -0.074066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.29222656, 547.69261719, 174.15585938), 'rotation':(-0.081726, 90.144043, -0.08197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.14429688, 558.88777344, 174.14082031), 'rotation':(0.073855, -89.854462, 0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.13039062, 564.47550781, 174.13400391), 'rotation':(0.073855, -89.854462, 0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.07375, 586.82660156, 174.10962891), 'rotation':(0.059778, -89.856812, 0.059656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.0971875, 624.8770312500001, 174.08136718999998), 'rotation':(-0.03125, 90.145073, -0.031281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.04101562, 647.2033593799999, 174.07125), 'rotation':(-0.011658, 90.144417, -0.011658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.95042969, 663.94683594, 174.06990234), 'rotation':(0.000212, 90.146111, 0.000223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.8903906200003, 669.5276562500001, 174.06992188), 'rotation':(0.000212, 90.146111, 0.000223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.82691406, 680.69177734, 174.06994140999998), 'rotation':(0.000109, 90.144318, 0.000116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.97875, 675.75212891, 174.06992188), 'rotation':(-0.000214, -89.855652, -0.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.95921875, 669.54796875, 174.06992188), 'rotation':(-0.000244, -89.853882, -0.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.89527344, 658.38597656, 174.06986328), 'rotation':(0.003791, -89.855591, 0.003786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.90722656, 652.8049218799999, 174.07021484), 'rotation':(0.011652, -89.85556, 0.011644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.92140625, 647.22332031, 174.07125), 'rotation':(0.01935, -89.855591, 0.019358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.9353125, 641.64171875, 174.07298828), 'rotation':(0.027218, -89.85556, 0.027204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.97753906, 624.8968359400001, 174.08136718999998), 'rotation':(0.031241, -89.854919, 0.031205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.7267968799997, 724.27105469, 174.0775), 'rotation':(-0.025299, -89.855194, -0.02533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.71265625, 729.8184179699999, 174.08025390999998), 'rotation':(-0.028809, -89.855316, -0.028809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.68457031, 740.91345703, 174.08609375), 'rotation':(-0.030121, -89.853485, -0.030182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.67066406, 746.46099609, 174.08939453), 'rotation':(-0.032806, -89.85611, -0.032837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.64671875, 757.55773438, 174.09677734000002), 'rotation':(-0.041138, -89.853455, -0.041168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.61449219, 768.65076172, 174.10529297000002), 'rotation':(-0.046448, -89.85611, -0.046539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.54445312, 796.38849609, 174.13033202999998), 'rotation':(-0.056305, -89.855225, -0.056427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.474375, 824.12580078, 174.16083984), 'rotation':(-0.067566, -89.855194, -0.067749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.46046875, 829.67316406, 174.1675), 'rotation':(-0.068787, -89.855865, -0.068939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.49097656, 838.36834961, 174.17816406000003), 'rotation':(-0.071564, -89.853302, -0.071777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.53027344, 853.3190332, 174.19757812), 'rotation':(-0.076935, -89.856049, -0.077148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.51515625, 859.3574804699999, 174.20582031), 'rotation':(-0.078857, -89.853271, -0.079071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.36671875, 862.93787109, 174.21083984), 'rotation':(0.080576, 90.143974, 0.080345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.3825781200003, 856.60625977, 174.20205077999998), 'rotation':(0.078841, 90.146729, 0.078629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.48875, 840.23779297, 174.18050781000002), 'rotation':(0.073308, 90.146713, 0.07312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.58007812, 829.65332031, 174.1675), 'rotation':(0.069682, 90.143913, 0.069518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.59421875, 824.10607422, 174.16083984), 'rotation':(0.068773, 90.146126, 0.068615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.65039062, 801.91601562, 174.13595703), 'rotation':(0.060925, 90.14476, 0.060785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.67847656, 790.8211718800001, 174.12494141), 'rotation':(0.056315, 90.144753, 0.056202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.69238281, 785.2737500000001, 174.11978516), 'rotation':(0.053918, 90.144745, 0.053822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.72046875, 774.17822266, 174.10996093999998), 'rotation':(0.050557, 90.144691, 0.050455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.74828125, 763.08337891, 174.10089843999998), 'rotation':(0.046452, 90.143875, 0.046375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.77660156, 751.9885937500001, 174.09294922), 'rotation':(0.03829, 90.143852, 0.038236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.79027344, 746.4410937499999, 174.08939453), 'rotation':(0.035456, 90.143867, 0.035414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.83226562, 729.79851562, 174.08025390999998), 'rotation':(0.028782, 90.14463, 0.028772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.84644531, 724.25121094, 174.0775), 'rotation':(0.028782, 90.14463, 0.028772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.77, 718.70740234, 174.075), 'rotation':(0.025313, 90.144806, 0.025293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.06421875, 1017.6427002, 174.47060547), 'rotation':(0.10735, 90.145081, 0.106943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.11960938, 1012.0880127, 174.46021484000002), 'rotation':(0.10735, 90.145081, 0.106943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.14769531, 1000.97406006, 174.43960938), 'rotation':(0.105786, 90.143654, 0.105398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.17578125, 989.86029053, 174.41925781), 'rotation':(0.104611, 90.145363, 0.104234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.1896875, 984.30334473, 174.40921875), 'rotation':(0.103648, 90.14537, 0.103278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.20359375, 978.74639893, 174.39917968999998), 'rotation':(0.103648, 90.14537, 0.103278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.24585938, 962.07537842, 174.36939453), 'rotation':(0.101476, 90.144127, 0.101117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.25976562, 956.51836914, 174.35962891), 'rotation':(0.100452, 90.144119, 0.100092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.27390625, 950.96148438, 174.35), 'rotation':(0.099407, 90.146484, 0.099067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.28785156, 945.40454102, 174.34042968999998), 'rotation':(0.098232, 90.144119, 0.097894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.30199219, 939.84753418, 174.33095702999998), 'rotation':(0.097207, 90.144112, 0.096868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.31347656, 912.06415039, 174.28490234), 'rotation':(0.093546, 90.14505, 0.093244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.27074219, 900.94818359, 174.26722656), 'rotation':(0.089667, 90.142967, 0.089392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.41015625, 900.96863281, 174.26722656), 'rotation':(-0.087738, -89.85495, -0.087982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.31128906, 912.08410156, 174.28490234), 'rotation':(-0.091614, -89.854919, -0.091888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.224375, 923.19628906, 174.303125), 'rotation':(-0.094513, -89.855042, -0.094818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.19628906, 934.31030273, 174.32160156), 'rotation':(-0.095123, -89.853516, -0.095459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.18238281, 939.86737305, 174.33095702999998), 'rotation':(-0.096161, -89.855865, -0.096497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.15429688, 950.98120117, 174.35), 'rotation':(-0.098236, -89.853516, -0.098572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.098125, 973.20892334, 174.38919922000002), 'rotation':(-0.102509, -89.855835, -0.102875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.08398438, 978.76605225, 174.39917968999998), 'rotation':(-0.103088, -89.854736, -0.103455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.06984375, 984.32305908, 174.40921875), 'rotation':(-0.103088, -89.854736, -0.103455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.05589844, 989.88006592, 174.41925781), 'rotation':(-0.103668, -89.856323, -0.104034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.04199219, 995.43695068, 174.42939453), 'rotation':(-0.104614, -89.854614, -0.105011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.01390625, 1006.55078125, 174.44986328), 'rotation':(-0.105774, -89.854614, -0.106171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.0, 1012.10784912, 174.46021484000002), 'rotation':(-0.10675, -89.856323, -0.107147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.02734375, 1017.66278076, 174.47060547), 'rotation':(-0.10675, -89.856323, -0.107147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.0959375, 1023.21868896, 174.48099609000002), 'rotation':(-0.107361, -89.854919, -0.107758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3619.8259375, 499.9884375, 177.57283203), 'rotation':(-0.002625, 91.01828, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.92480469, 494.43121094, 177.57363281000002), 'rotation':(-0.002625, 91.01828, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.0234375, 488.87472656, 177.575625), 'rotation':(-0.020508, 91.016693, -0.020538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.12207031, 483.31726562000006, 177.57826172), 'rotation':(-0.020508, 91.016693, -0.020538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.2209375, 477.76074219, 177.58113281), 'rotation':(-0.02948, 91.018509, -0.02951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.41820312, 466.6468359400001, 177.58708984), 'rotation':(-0.029572, 91.01693, -0.029602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.51683594, 461.0903125, 177.59042968999998), 'rotation':(-0.034424, 91.017616, -0.034485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.714375, 449.9765625, 177.599375), 'rotation':(-0.044403, 91.017632, -0.044464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.91164062, 438.86316406000003, 177.61068359), 'rotation':(-0.064392, 91.01767, -0.064545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3621.01050781, 433.30578125, 177.61703125), 'rotation':(-0.064392, 91.01767, -0.064545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.30664062, 416.63523437999993, 177.63763672000002), 'rotation':(-0.075226, 91.017471, -0.075409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3621.40527344, 411.07824218999997, 177.64529297), 'rotation':(-0.075226, 91.017471, -0.075409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.60253906, 399.96484375, 177.66316406), 'rotation':(-0.099213, 91.01754, -0.099548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.70117188, 394.40789062, 177.67318359), 'rotation':(-0.099213, 91.01754, -0.099548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.79980469, 388.85144531000003, 177.68398438), 'rotation':(-0.111267, 91.017593, -0.111694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3629.7053125, 387.84691406, 177.68623047), 'rotation':(0.117158, -88.982941, 0.116693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.48023438, 400.10414062000007, 177.66316406), 'rotation':(0.111264, -88.982391, 0.110842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.3828125, 405.66164062000007, 177.65375), 'rotation':(0.099215, -88.982452, 0.098876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.28417969, 411.21808594000004, 177.64529297), 'rotation':(0.087256, -88.980774, 0.087003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.18554688, 416.7750390599999, 177.63763672000002), 'rotation':(0.087256, -88.980774, 0.087003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3629.08667969, 422.33265625, 177.63046875), 'rotation':(0.075214, -88.982513, 0.075009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.98804688, 427.88914062000003, 177.62375), 'rotation':(0.069272, -88.9823, 0.0691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.79078125, 439.00300781, 177.61068359), 'rotation':(0.069265, -88.9823, 0.069097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.59328125, 450.11644531, 177.599375), 'rotation':(0.054341, -88.982361, 0.054241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.39601562, 461.23023437999996, 177.59042968999998), 'rotation':(0.044383, -88.982361, 0.044318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.19875, 472.34410156, 177.58398438), 'rotation':(0.034445, -88.982361, 0.034394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3628.10007812, 477.900625, 177.58111327999998), 'rotation':(0.029575, -88.983032, 0.029543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.00121094, 483.45714843999997, 177.57826172), 'rotation':(0.029479, -88.983032, 0.029445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3627.90257812, 489.01464844000003, 177.575625), 'rotation':(0.029479, -88.983032, 0.029445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.73121094, 554.96417969, 177.58175781000003), 'rotation':(-0.024719, -88.983429, -0.02475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.63160156, 560.5636718799999, 177.58457031), 'rotation':(-0.029907, -88.983429, -0.029938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.43261719, 571.76277344, 177.59177734000002), 'rotation':(-0.040405, -88.983398, -0.040466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.13429688, 588.56203125, 177.60578125), 'rotation':(-0.05011, -88.981995, -0.050201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.18480469, 537.9415234400001, 177.57648438), 'rotation':(0.014227, 91.019142, 0.014223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.08546875, 543.5409374999999, 177.57769531000002), 'rotation':(0.019568, 91.016563, 0.019548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3618.3903906200003, 582.67382812, 177.60076172), 'rotation':(0.050113, 91.017982, 0.050022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3618.29125, 588.26128906, 177.60564452999998), 'rotation':(0.054027, 91.01796, 0.053925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3616.58640625, 682.39373047, 177.73123047), 'rotation':(0.097474, 91.0186, 0.097149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3616.78492188, 671.2066796900001, 177.71253906), 'rotation':(0.095841, 91.016647, 0.095516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3616.88429688, 665.6133984400001, 177.70341797), 'rotation':(0.094598, 91.019775, 0.094281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3616.98363281, 660.0198437500001, 177.69457031000002), 'rotation':(0.09147, 91.017128, 0.09119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3617.18238281, 648.83308594, 177.67777343999998), 'rotation':(0.083089, 91.017105, 0.082862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3617.28171875, 643.2398828099999, 177.66980468999998), 'rotation':(0.080316, 91.019737, 0.080088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3617.38109375, 637.64628906, 177.66214843999998), 'rotation':(0.077352, 91.01709, 0.077146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3617.57960938, 626.4590625000001, 177.64755859000002), 'rotation':(0.07322, 91.017166, 0.073039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.45875, 626.59894531, 177.64755859000002), 'rotation':(-0.070709, -88.982697, -0.070862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3625.3596093799997, 632.19261719, 177.65474609), 'rotation':(-0.073212, -88.980347, -0.073425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.26023438, 637.78621094, 177.66214843999998), 'rotation':(-0.074707, -88.98291, -0.074921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.16089844, 643.37964844, 177.66980468999998), 'rotation':(-0.077362, -88.98291, -0.077576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.06152344, 648.9730078099999, 177.67777343999998), 'rotation':(-0.080322, -88.98291, -0.080536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3624.96214844, 654.56617188, 177.68603516), 'rotation':(-0.08606, -88.980255, -0.086304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3624.6640625, 671.3465625, 177.71253906), 'rotation':(-0.094604, -88.982849, -0.09491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3624.5646875, 676.9403125, 177.72185547), 'rotation':(-0.094604, -88.982849, -0.09491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3614.9175, 776.33990234, 177.91253906000003), 'rotation':(0.120068, 91.017876, 0.119568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3615.4140625, 748.37914062, 177.85482422), 'rotation':(0.115977, 91.01828, 0.115514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3615.5134375, 742.78693359, 177.84371094), 'rotation':(0.113825, 91.018265, 0.113375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3615.6128125, 737.19482422, 177.83267578), 'rotation':(0.113825, 91.018265, 0.113375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3615.71214844, 731.60259766, 177.82179688), 'rotation':(0.111476, 91.016624, 0.111038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3615.81152344, 726.01037109, 177.81099609), 'rotation':(0.110273, 91.018982, 0.109854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3615.91089844, 720.4182812500001, 177.80021484), 'rotation':(0.110273, 91.018982, 0.109854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3623.39257812, 742.92669922, 177.84371094), 'rotation':(-0.111481, -88.98175, -0.111908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3622.99535156, 765.29552734, 177.88917969), 'rotation':(-0.118225, -88.98172, -0.118713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3622.79640625, 776.47972656, 177.91253906000003), 'rotation':(-0.119537, -88.982117, -0.120026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3613.74390625, 842.40099609, 178.05322266), 'rotation':(0.121284, 91.017693, 0.120771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3613.84328125, 836.80902344, 178.04128906000003), 'rotation':(0.12226, 91.0177, 0.121729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3614.04175781, 825.62482422, 178.01730468999997), 'rotation':(0.123032, 91.017677, 0.122516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3614.09449219, 820.03369141, 178.00527344), 'rotation':(0.123401, 91.019073, 0.12288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3614.21046875, 808.84625, 177.98130859), 'rotation':(0.122513, 91.019127, 0.121992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3622.31324219, 810.97705078, 177.98554688000002), 'rotation':(-0.122528, -88.983276, -0.123047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.62304688, 842.54083008, 178.05322266), 'rotation':(-0.122253, -88.982269, -0.122772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.42429688, 853.72498047, 178.07695311999998), 'rotation':(-0.121307, -88.980896, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3610.9924218799997, 997.31799316, 178.34691406000002), 'rotation':(0.079128, 91.017944, 0.078912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.09105469, 991.76013184, 178.33867188), 'rotation':(0.085063, 91.017975, 0.084813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.48609375, 969.52880859, 178.3028125), 'rotation':(0.096654, 91.016556, 0.096323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.68359375, 958.41375977, 178.28345703), 'rotation':(0.100458, 91.016525, 0.100107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3611.88109375, 947.29797363, 178.26363281000002), 'rotation':(0.103395, 91.016556, 0.103018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.97972656, 941.74017578, 178.25351562), 'rotation':(0.104939, 91.016556, 0.104564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3612.17726562, 930.62451172, 178.23273438), 'rotation':(0.108047, 91.016579, 0.107647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3612.27585938, 925.06677246, 178.22208984), 'rotation':(0.109604, 91.019318, 0.109186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3612.473125, 913.95117188, 178.20044922), 'rotation':(0.111769, 91.017639, 0.111322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.45117188, 908.53308594, 178.18953125), 'rotation':(-0.112854, -88.982758, -0.113312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.15503906, 925.2064209, 178.22208984), 'rotation':(-0.110992, -88.983398, -0.11142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.05617188, 930.7642822299999, 178.23271484), 'rotation':(-0.109619, -88.983398, -0.110016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.85890625, 941.87988281, 178.25349609), 'rotation':(-0.106506, -88.983429, -0.106903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3619.36523438, 969.66851807, 178.3028125), 'rotation':(-0.09964, -88.982666, -0.100006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3619.06910156, 986.34197998, 178.33019531000002), 'rotation':(-0.090912, -88.981995, -0.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3618.68945312, 1008.57104492, 178.36230468999997), 'rotation':(-0.079132, -88.982025, -0.079346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3618.68675781, 1014.12908936, 178.36970703), 'rotation':(-0.076294, -88.982788, -0.076477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.20289062, 502.2590625, 179.55226562), 'rotation':(0.063398, 90.248123, 0.063272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.2473437500003, 496.69691406, 179.54669922000002), 'rotation':(0.058753, 90.245628, 0.058642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3872.42796875, 480.02148437999995, 179.53226562), 'rotation':(0.047203, 90.246155, 0.04712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.69070312, 418.86601562, 179.51664062), 'rotation':(0.002411, 90.245895, 0.002405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.76515625, 385.50867187999995, 179.52914062), 'rotation':(-0.048431, 90.24678, -0.048523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.86328125, 381.00132812000004, 179.53298827999998), 'rotation':(0.048522, -89.753235, 0.048438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.703125, 390.08355469, 179.52529297), 'rotation':(0.048419, -89.754639, 0.048346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.64257812, 402.21921875, 179.51791015999999), 'rotation':(0.029506, -89.754639, 0.029464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.5946875, 413.33910156, 179.51642578), 'rotation':(0.004002, -89.752014, 0.003996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.57078125, 418.89832031000003, 179.51664062), 'rotation':(-0.002502, -89.754089, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.52320312, 430.01660156, 179.51710938), 'rotation':(-0.002411, -89.754089, -0.002411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.4753124999997, 441.13488281, 179.51759765999998), 'rotation':(-0.002411, -89.754089, -0.002411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.42773438, 452.25414062000004, 179.51833984), 'rotation':(-0.002502, -89.754089, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.37984375, 463.37292969, 179.52125), 'rotation':(-0.019226, -89.754944, -0.019226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.3559375, 468.93242188, 179.52419922), 'rotation':(-0.030396, -89.752899, -0.030426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.33226562, 474.49207031000003, 179.52796875), 'rotation':(-0.041565, -89.754883, -0.041626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.28445312, 485.61121094, 179.536875), 'rotation':(-0.047211, -89.753845, -0.047272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.30539062, 491.16914062, 179.54160156), 'rotation':(-0.049622, -89.754395, -0.049683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.34546875, 496.72789062000004, 179.54669922000002), 'rotation':(-0.054108, -89.751892, -0.054199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.0012500000003, 551.54734375, 179.61814453), 'rotation':(-0.089905, -89.753601, -0.09021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.97703125, 557.14972656, 179.62736328), 'rotation':(-0.089905, -89.753601, -0.09021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.953125, 562.7520703099999, 179.63683593999997), 'rotation':(-0.096802, -89.753601, -0.097107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.92898438, 568.35414062, 179.64699219), 'rotation':(-0.103668, -89.75354, -0.104034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.88085938, 579.5589062500001, 179.66773438), 'rotation':(-0.107178, -89.753998, -0.107574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.8325, 590.76347656, 179.68914062), 'rotation':(-0.109222, -89.753998, -0.10965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.95242188, 590.73601562, 179.68914062), 'rotation':(0.113518, 90.24601, 0.11307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3872.00046875, 579.5311328099999, 179.66773438), 'rotation':(0.109228, 90.245987, 0.108814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.024375, 573.92890625, 179.65726562), 'rotation':(0.107179, 90.245979, 0.106778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.09671875, 557.12128906, 179.62736328), 'rotation':(0.096791, 90.246399, 0.09647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3872.16890625, 540.31398438, 179.60107422000002), 'rotation':(0.089926, 90.246391, 0.089646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.63867188, 679.1536328100001, 179.89076172), 'rotation':(0.144998, 90.058434, 0.144269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.64453125, 673.56390625, 179.87675781000002), 'rotation':(0.143571, 90.059952, 0.14286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.65015625, 667.97375, 179.86283203), 'rotation':(0.142785, 90.057114, 0.142061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.65601562, 662.38410156, 179.84904297), 'rotation':(0.141228, 90.059807, 0.140533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.69234375, 651.21003906, 179.82201172), 'rotation':(0.137587, 90.244926, 0.136932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.7165625, 645.62019531, 179.80882812), 'rotation':(0.135012, 90.24678, 0.134392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.74046875, 640.03039062, 179.79580077999998), 'rotation':(0.135012, 90.24678, 0.134392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.7643749999997, 634.4405468799999, 179.78292968999997), 'rotation':(0.132232, 90.246765, 0.131608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.8125, 623.26074219, 179.75777344), 'rotation':(0.128182, 90.246582, 0.127615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.6926562500003, 623.28253906, 179.75775391), 'rotation':(-0.127289, -89.754333, -0.127869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.620625, 640.049375, 179.79576172), 'rotation':(-0.132233, -89.753235, -0.132843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.59671875, 645.63824219, 179.80876952999998), 'rotation':(-0.132233, -89.753235, -0.132843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.57273438, 651.22722656, 179.82197266), 'rotation':(-0.13504, -89.753235, -0.135651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.5190625, 679.17833984, 179.89080077999998), 'rotation':(-0.143585, -89.941559, -0.144287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.51320312, 684.76726562, 179.90488281), 'rotation':(-0.143585, -89.941559, -0.144287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.48, 717.28441406, 179.98859375), 'rotation':(-0.149841, -89.940735, -0.150635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.474375, 722.87927734, 180.00324218999998), 'rotation':(-0.150299, -89.941071, -0.151062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.44578125, 750.85345703, 180.07634765999998), 'rotation':(-0.149292, -89.941071, -0.150055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.43429688, 762.04308594, 180.10542969), 'rotation':(-0.148834, -89.941071, -0.149597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.53757812, 773.22869141, 180.13439452999998), 'rotation':(-0.148407, -89.939575, -0.14917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.55953125, 756.43298828, 180.09085938), 'rotation':(0.14883, 90.058907, 0.148065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.57101562, 745.24292969, 180.06175781000002), 'rotation':(0.14926, 90.058907, 0.148495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.5825, 734.05296875, 180.03253906), 'rotation':(0.149848, 90.058929, 0.149077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.588125, 728.45800781, 180.01789062), 'rotation':(0.149848, 90.058929, 0.149077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.59398438, 722.8629687499999, 180.00322266), 'rotation':(0.150141, 90.058929, 0.149363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.44601562, 867.21923828, 180.36205078), 'rotation':(0.124665, 90.05838, 0.124123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.4518749999997, 861.62445312, 180.34978515999998), 'rotation':(0.127212, 90.059502, 0.126642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.46335938, 850.43481445, 180.32466797), 'rotation':(0.129972, 90.06105, 0.129381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.47484375, 839.24481445, 180.29878906000002), 'rotation':(0.133933, 90.058434, 0.133309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.48632812, 828.0549218799999, 180.27214844), 'rotation':(0.137567, 90.058449, 0.136919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.3723437500003, 822.47351562, 180.25855468999998), 'rotation':(-0.141357, -89.941528, -0.142059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.35523438, 839.25792969, 180.29878906000002), 'rotation':(-0.135742, -89.941528, -0.136414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.349375, 844.85259766, 180.31183593999998), 'rotation':(-0.133942, -89.941559, -0.134583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.33226562, 861.63683594, 180.34978515999998), 'rotation':(-0.128174, -89.941589, -0.128723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.32640625, 867.23144531, 180.36207031), 'rotation':(-0.127197, -89.940491, -0.127777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.1770312500003, 1004.00067139, 180.56853515999998), 'rotation':(0.036255, 90.058151, 0.036208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.31617188, 994.32543945, 180.56240234), 'rotation':(0.036255, 90.058151, 0.036211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.32203125, 988.76147461, 180.55835938), 'rotation':(0.041589, 90.059723, 0.041533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.32765625, 983.19781494, 180.55373047), 'rotation':(0.041589, 90.059723, 0.041533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.35617188, 955.37933594, 180.52046875), 'rotation':(0.079169, 90.058006, 0.078952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.3620312499997, 949.81591797, 180.51269531000003), 'rotation':(0.079319, 90.060539, 0.079104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.401875, 910.86895508, 180.44912109), 'rotation':(0.10455, 90.058815, 0.104167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.413125, 899.74115234, 180.42851561999998), 'rotation':(0.106189, 90.058624, 0.105807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2878124999997, 905.31640625, 180.43890625), 'rotation':(-0.106201, -89.941345, -0.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2821875, 910.88006836, 180.44912109), 'rotation':(-0.106201, -89.941345, -0.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.27640625, 916.44335938, 180.45916015999998), 'rotation':(-0.104553, -89.941162, -0.104919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2707812500003, 922.00726562, 180.46900391), 'rotation':(-0.10144, -89.941681, -0.101807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.26492188, 927.57092285, 180.47845703), 'rotation':(-0.10144, -89.941681, -0.101807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.25929688, 933.13446289, 180.48769531000002), 'rotation':(-0.095032, -89.940186, -0.095367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2478125, 944.26202148, 180.50470703), 'rotation':(-0.088745, -89.941742, -0.088989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.21945312, 972.07965088, 180.54236328), 'rotation':(-0.073883, -89.941956, -0.074066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.1965625000003, 994.33428955, 180.56240234), 'rotation':(-0.041595, -89.940277, -0.041656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2990625, 1002.61431885, 180.56765625), 'rotation':(-0.036255, -89.941833, -0.036285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2123.92648438, 344.78296875, 157.28583007999998), 'rotation':(-0.84198, -179.499496, -0.867004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2112.75976562, 344.78859375, 157.1221582), 'rotation':(-0.837311, -179.499619, -0.862061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2084.83960938, 344.55062499999997, 156.71650391), 'rotation':(-0.822815, -179.500107, -0.846741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2079.25585938, 344.50320311999997, 156.63630859), 'rotation':(-0.817108, -179.500259, -0.840668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2063.80664062, 344.28140625000003, 156.41609375), 'rotation':(-0.814117, -179.500305, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2123.85351562, 352.8648828099999, 157.28576171999998), 'rotation':(0.845181, 0.500603, 0.820532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2107.10398438, 352.62144531, 157.04046875), 'rotation':(0.837327, 0.500395, 0.813121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2084.7665625, 352.43117187999997, 156.71642578), 'rotation':(0.82868, 0.500057, 0.804963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2073.598125, 352.33601562, 156.55645508), 'rotation':(0.817089, 0.499914, 0.794033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2068.01609375, 352.30828125000005, 156.47689453), 'rotation':(0.817089, 0.499914, 0.794033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2062.43265625, 352.35242187999995, 156.39753905999999), 'rotation':(0.814288, 0.499507, 0.791387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2161.97460938, 353.08898437999994, 157.85286133), 'rotation':(0.860809, 0.501138, 0.835227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2167.56296875, 353.13660156000003, 157.9368457), 'rotation':(0.860822, 0.500936, 0.835254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2173.15140625, 353.18421875, 158.02083984), 'rotation':(0.862339, 0.500984, 0.836661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2178.74, 353.23179687999993, 158.10492188), 'rotation':(0.865419, 0.5014, 0.839566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2195.50539062, 353.37464844, 158.35880859), 'rotation':(0.873007, 0.501665, 0.846694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2206.68210938, 353.46984375, 158.52913086), 'rotation':(0.873001, 0.501312, 0.846704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2217.85890625, 353.56507812000007, 158.69951172), 'rotation':(0.874783, 0.501632, 0.848365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2223.44703125, 353.61265625, 158.78486328), 'rotation':(0.878321, 0.501455, 0.851707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2223.52320312, 345.7321875, 158.785), 'rotation':(-0.874786, -179.498611, -0.901825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2206.7565624999997, 345.589375, 158.52924805), 'rotation':(-0.873016, -179.498672, -0.899933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2201.16773438, 345.54175781000004, 158.4440625), 'rotation':(-0.873016, -179.498672, -0.899933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2189.98921875, 345.44652343999996, 158.27395508), 'rotation':(-0.8685, -179.498489, -0.895142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2184.40039062, 345.39890625, 158.18931641), 'rotation':(-0.865417, -179.498901, -0.891876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2173.2221875, 345.30371094, 158.02088867), 'rotation':(-0.860809, -179.498856, -0.886993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2323.004375, 354.39820312000006, 160.34195312), 'rotation':(0.906503, 0.405557, 0.878145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2317.4245312499997, 354.36011719, 160.25364258), 'rotation':(0.906503, 0.405557, 0.878145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2300.68453125, 354.24585937999996, 159.98871094), 'rotation':(0.906503, 0.405557, 0.878145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2295.10453125, 354.20777344, 159.90052734), 'rotation':(0.904973, 0.405189, 0.87671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2283.94578125, 354.12804687999994, 159.72490234), 'rotation':(0.889823, 0.452758, 0.862502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2278.36765625, 354.08054687999993, 159.63737305), 'rotation':(0.898655, 0.502394, 0.8708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2250.46726562, 353.84289062000005, 159.20198242), 'rotation':(0.893655, 0.501967, 0.866098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2317.49242188, 346.47960937999994, 160.25387695), 'rotation':(-0.906464, -179.594452, -0.935516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2289.5924999999997, 346.28914062, 159.81276367), 'rotation':(-0.911102, -179.544418, -0.94046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2284.01101562, 346.24757812000007, 159.72487305), 'rotation':(-0.898651, -179.497849, -0.927155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2272.85179688, 346.15246093999997, 159.55009766), 'rotation':(-0.893768, -179.498016, -0.921997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2261.6926562500003, 346.05738281000004, 159.37591797), 'rotation':(-0.893677, -179.497818, -0.921875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2250.53320312, 345.96226562000004, 159.20196289), 'rotation':(-0.891205, -179.498062, -0.919281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2401.51757812, 347.0530859400001, 161.59660156), 'rotation':(-0.922699, -179.594147, -0.952789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2410.40210938, 346.99101562, 161.73986328), 'rotation':(-0.923737, -179.59404, -0.953888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2389.17773438, 346.96886718999997, 161.39792969), 'rotation':(-0.920563, -179.594009, -0.950531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2377.98851562, 346.89250000000004, 161.21832031), 'rotation':(-0.916412, -179.594147, -0.946075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2366.80101562, 346.81230469, 161.03922852), 'rotation':(-0.915375, -179.594193, -0.944977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2361.20824219, 346.7025, 160.94984375), 'rotation':(-0.915405, -179.594528, -0.945007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2355.61109375, 346.61023437999995, 160.86038086), 'rotation':(-0.915405, -179.594177, -0.945007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2400.30199219, 354.92589843999997, 161.57788086), 'rotation':(0.923728, 0.405968, 0.894304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2394.70726562, 354.88769531, 161.48774414), 'rotation':(0.92269, 0.406061, 0.893319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2355.54199219, 354.74992188, 160.86015625), 'rotation':(0.915402, 0.405821, 0.886495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2511.05054688, 347.80078125, 163.36444336), 'rotation':(-0.923431, -179.593842, -0.953552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2477.57445312, 347.57226562000005, 162.82451172), 'rotation':(-0.925446, -179.594025, -0.955719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2466.41578125, 347.49609375, 162.64422851999998), 'rotation':(-0.925323, -179.594025, -0.955597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2455.25707031, 347.41992187999995, 162.46394530999999), 'rotation':(-0.925415, -179.593826, -0.955688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2449.6775, 347.38183594, 162.37379883), 'rotation':(-0.925323, -179.594025, -0.955597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.09839844, 347.34375, 162.28364258), 'rotation':(-0.92511, -179.593918, -0.955353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.24925781, 355.56726562000006, 163.09442382999998), 'rotation':(0.923428, 0.406151, 0.894006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2471.93164062, 355.41492187999995, 162.73421875), 'rotation':(0.925429, 0.406182, 0.89589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2466.35203125, 355.37683594, 162.64407227), 'rotation':(0.925429, 0.406182, 0.89589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2455.19335938, 355.30058594, 162.46378906), 'rotation':(0.925327, 0.405977, 0.895785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2449.61425781, 355.26250000000005, 162.37364258), 'rotation':(0.925395, 0.405966, 0.895862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.0346875, 355.22441405999996, 162.28347656), 'rotation':(0.925327, 0.406178, 0.895794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2582.75464844, 348.29027343999996, 164.51375), 'rotation':(-0.911652, -179.594559, -0.94101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2577.16601562, 348.2521875, 164.42482422), 'rotation':(-0.9133, -179.594208, -0.94278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2560.39992188, 348.13769531, 164.15716797000002), 'rotation':(-0.916656, -179.594391, -0.94632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2549.22265625, 348.06140625, 163.97818359000001), 'rotation':(-0.917603, -179.594299, -0.947357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2593.8728125, 356.2471875, 164.69107422000002), 'rotation':(0.906646, 0.405288, 0.878287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2582.6953125, 356.17089844, 164.51367188), 'rotation':(0.909979, 0.405396, 0.881404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2577.10644531, 356.1328125, 164.42472656), 'rotation':(0.911639, 0.405724, 0.88297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2571.51757812, 356.09460937999995, 164.33564453), 'rotation':(0.913271, 0.405761, 0.884497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2554.75171875, 355.98023437999996, 164.06759766), 'rotation':(0.916632, 0.405882, 0.887651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2543.57398438, 355.9039453099999, 163.88855468999998), 'rotation':(0.917458, 0.405711, 0.888428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.06005859, 357.06007812000007, 166.3234375), 'rotation':(0.867577, 0.404147, 0.841592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2693.48167969, 356.92707031, 166.23888672), 'rotation':(0.867577, 0.404442, 0.841592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.89794922, 356.88898438, 166.15410156000002), 'rotation':(0.869708, 0.404145, 0.8436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2671.14722656, 356.77464843999996, 165.89755859000002), 'rotation':(0.878219, 0.40439, 0.851605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.98046875, 356.69843749999995, 165.72525391), 'rotation':(0.884537, 0.404797, 0.857534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2648.81347656, 356.6221875, 165.55265625), 'rotation':(0.886026, 0.404838, 0.858939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2637.64625, 356.54601562000005, 165.37927734000002), 'rotation':(0.888922, 0.404679, 0.86166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2632.0625, 356.50792968999997, 165.29222656000002), 'rotation':(0.892084, 0.405029, 0.864627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.11890625, 348.98949218999996, 166.32347656000002), 'rotation':(-0.867584, -179.59584, -0.894165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.78808594, 348.93210937999993, 165.9834375), 'rotation':(-0.882355, -179.595459, -0.909851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2665.62085938, 348.8559375, 165.81152343999997), 'rotation':(-0.884521, -179.5952, -0.91217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2648.86988281, 348.7415625, 165.55269531000002), 'rotation':(-0.888947, -179.595062, -0.91684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2637.70265625, 348.66539062000004, 165.37929688), 'rotation':(-0.89209, -179.594971, -0.920197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2956.36206055, 350.78539062000004, 169.92509766), 'rotation':(-0.737091, -179.599655, -0.756256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2947.66259766, 350.78105469, 169.81324218999998), 'rotation':(-0.740875, -179.599274, -0.760223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2930.59838867, 350.66453125, 169.59169922), 'rotation':(-0.752106, -179.598984, -0.772034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2913.53491211, 350.54808593999996, 169.36714844), 'rotation':(-0.759338, -179.598801, -0.779694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2902.15942383, 350.47046875, 169.21580078), 'rotation':(-0.765045, -179.598679, -0.785675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2896.47143555, 350.43164062000005, 169.13986328), 'rotation':(-0.764893, -179.598694, -0.785522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2890.78344727, 350.3928125, 169.06388672), 'rotation':(-0.767517, -179.598541, -0.7883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2885.09594727, 350.35398437999993, 168.98769531000002), 'rotation':(-0.772339, -179.598419, -0.793365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.3449707, 350.19875, 168.67835938), 'rotation':(-0.78479, -179.598022, -0.806519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2856.65698242, 350.15984375000005, 168.60044922), 'rotation':(-0.786652, -179.598297, -0.808472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2850.9699707, 350.12101562, 168.52238281), 'rotation':(-0.790466, -179.597916, -0.812531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2833.90673828, 350.00464844, 168.28638672), 'rotation':(-0.798218, -179.597717, -0.820709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2822.53076172, 349.92695312, 168.12740234), 'rotation':(-0.805878, -179.597488, -0.828796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2805.46728516, 349.81046875000004, 167.88628906000002), 'rotation':(-0.815369, -179.597214, -0.838837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2742.90941406, 349.32617187999995, 166.98013672000002), 'rotation':(-0.846832, -179.596329, -0.872131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2953.29174805, 358.7025, 169.88638672000002), 'rotation':(0.735242, 0.400546, 0.716548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2947.60546875, 358.66164062000007, 169.81322265999998), 'rotation':(0.737087, 0.400626, 0.718306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2941.91748047, 358.6228125, 169.73970702999998), 'rotation':(0.740871, 0.400724, 0.721898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2913.47753906, 358.42859375, 169.36708984), 'rotation':(0.755583, 0.40111, 0.735858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2885.03808594, 358.23457031, 168.98763672), 'rotation':(0.767508, 0.401445, 0.74714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2873.66235352, 358.156875, 168.83382812), 'rotation':(0.777453, 0.401408, 0.756563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2867.97460938, 358.11804687999995, 168.75619140999999), 'rotation':(0.782282, 0.401839, 0.761131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.28686523, 358.07929688, 168.67830078), 'rotation':(0.784638, 0.401971, 0.763374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2856.59887695, 358.04039062000004, 168.60037109), 'rotation':(0.784789, 0.401694, 0.763505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2845.22387695, 357.96281250000004, 168.44398438), 'rotation':(0.790465, 0.40208, 0.768886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2839.53588867, 357.92402344000004, 168.36533203), 'rotation':(0.790465, 0.40208, 0.768886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2833.84839844, 357.8851171900001, 168.28634766), 'rotation':(0.794296, 0.401917, 0.77249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2799.72144531, 357.65222656000003, 167.80533203), 'rotation':(0.815402, 0.402806, 0.792433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2788.34667969, 357.57457031, 167.64279297000002), 'rotation':(0.818332, 0.40271, 0.795208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2782.65869141, 357.53578125, 167.5609375), 'rotation':(0.824253, 0.403081, 0.800784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2776.97119141, 357.49695312000006, 167.47880859), 'rotation':(0.824253, 0.403081, 0.800784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2765.59546875, 357.41929687999993, 167.31341797000002), 'rotation':(0.836042, 0.403234, 0.811902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2759.90869141, 357.3805078099999, 167.23035156000003), 'rotation':(0.836042, 0.403234, 0.811902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2754.22070312, 357.34167969, 167.14701172000002), 'rotation':(0.839014, 0.403665, 0.814706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3119.06225586, 359.92625, 171.94140625), 'rotation':(0.689794, 0.3994, 0.673334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3113.51586914, 359.84226562000003, 171.87455078), 'rotation':(0.689794, 0.3994, 0.673334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3102.42260742, 359.71828125, 171.74046875), 'rotation':(0.692725, 0.39953, 0.67613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3096.87548828, 359.68042969, 171.67339843999997), 'rotation':(0.692697, 0.399515, 0.676096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3091.328125, 359.64257812000005, 171.60632812), 'rotation':(0.692725, 0.39953, 0.67613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.59130859, 359.45324218999997, 171.27216797), 'rotation':(0.687479, 0.399428, 0.67112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3052.49633789, 359.37742187999993, 171.13900390999999), 'rotation':(0.687506, 0.399443, 0.671152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3035.85644531, 359.26390625, 170.93777343999997), 'rotation':(0.693517, 0.39938, 0.676879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3030.30908203, 359.22609375, 170.86945312), 'rotation':(0.70536, 0.399856, 0.688159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3019.21508789, 359.15039062000005, 170.73107422), 'rotation':(0.717375, 0.399977, 0.699582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3013.66821289, 359.11249999999995, 170.66074218999998), 'rotation':(0.717375, 0.399977, 0.699582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3008.12084961, 359.0746875, 170.59011718999997), 'rotation':(0.729218, 0.400453, 0.710828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3002.57788086, 359.10902344, 170.51898438), 'rotation':(0.73527, 0.400551, 0.716574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3130.04150391, 351.89648437999995, 172.07271484), 'rotation':(-0.687866, -179.600662, -0.704529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3118.95825195, 351.85722655999996, 171.93949218999998), 'rotation':(-0.691803, -179.600571, -0.708649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3107.87670898, 351.87382812, 171.80580078), 'rotation':(-0.692719, -179.600464, -0.709625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3080.17382812, 351.68562499999996, 171.47087890999998), 'rotation':(-0.688812, -179.60051, -0.705505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3074.6328125, 351.64777344000004, 171.40414062), 'rotation':(-0.688812, -179.60051, -0.705505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3058.01000977, 351.53429687999994, 171.20455077999998), 'rotation':(-0.6875, -179.600845, -0.704163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3052.46923828, 351.49644531, 171.13802734), 'rotation':(-0.6875, -179.600845, -0.704163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3041.38916016, 351.42089844, 171.00443359000002), 'rotation':(-0.705383, -179.600327, -0.7229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3035.84887695, 351.38304687999994, 170.93701172000002), 'rotation':(-0.705383, -179.600327, -0.7229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3019.22705078, 351.26960938, 170.73056641), 'rotation':(-0.729218, -179.599716, -0.747955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3013.68701172, 351.23175781, 170.6603125), 'rotation':(-0.729218, -179.599716, -0.747955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3006.92822266, 351.17015625, 170.57412109), 'rotation':(-0.735291, -179.599426, -0.754364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2998.29321289, 350.99707031, 170.46328125), 'rotation':(-0.735168, -179.599442, -0.754242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3328.54835938, 353.38097656, 174.42201172), 'rotation':(-0.673462, -179.601303, -0.689453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3323.01269531, 353.34328125, 174.35697266), 'rotation':(-0.673462, -179.601303, -0.689453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3317.47679688, 353.30542969, 174.29189452999998), 'rotation':(-0.674652, -179.600723, -0.690704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3311.94117188, 353.26769531, 174.22669922), 'rotation':(-0.67453, -179.601181, -0.690552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3306.40527344, 353.22984375, 174.16150391), 'rotation':(-0.67453, -179.601181, -0.690552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3295.33375, 353.15429687999995, 174.03113281000003), 'rotation':(-0.67453, -179.601181, -0.690552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3289.79808594, 353.11644531, 173.9659375), 'rotation':(-0.674988, -179.600845, -0.69104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3273.19066406, 353.00312499999995, 173.77025390999998), 'rotation':(-0.675934, -179.601196, -0.692047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3228.90453125, 352.7008203099999, 173.24761718999997), 'rotation':(-0.677734, -179.600327, -0.693909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3212.29761719, 352.5875390599999, 173.05107422), 'rotation':(-0.678375, -179.600754, -0.69458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3206.76148438, 352.5496875, 172.98550781000003), 'rotation':(-0.678406, -179.600739, -0.694611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3195.68994141, 352.47414062000007, 172.85439452999998), 'rotation':(-0.678925, -179.601288, -0.69516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3190.15453125, 352.43632812, 172.78882812), 'rotation':(-0.678925, -179.601288, -0.69516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3173.546875, 352.32300781000004, 172.59171875), 'rotation':(-0.682129, -179.600723, -0.698517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3328.9216406200003, 361.26441406000004, 174.42701172), 'rotation':(0.671394, 0.398837, 0.655796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3317.83300781, 361.18871093999996, 174.29669922000002), 'rotation':(0.67347, 0.399105, 0.657766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3312.28857422, 361.15085937999993, 174.23140625), 'rotation':(0.674631, 0.399037, 0.6589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3290.11083984, 360.99953125, 173.97025391), 'rotation':(0.674556, 0.399053, 0.658804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3262.38890625, 360.81023438, 173.6434375), 'rotation':(0.675943, 0.399199, 0.660135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3251.30003906, 360.73457031, 173.51259765999998), 'rotation':(0.675943, 0.399001, 0.660137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3201.40087891, 360.39390625, 172.92267578), 'rotation':(0.678381, 0.399252, 0.662467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3195.85667969, 360.35609375, 172.85701172), 'rotation':(0.678381, 0.399011, 0.66247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3179.22339844, 360.24253906, 172.65982422000002), 'rotation':(0.679973, 0.399213, 0.663984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3599.17285156, 363.10902344, 177.47037109000001), 'rotation':(0.584049, 0.39703, 0.572229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3587.85230469, 363.03171875, 177.35427734), 'rotation':(0.588755, 0.39703, 0.57676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3582.191875, 362.99308594, 177.29546875), 'rotation':(0.588755, 0.39703, 0.57676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3570.87085938, 362.91582030999996, 177.17644531000002), 'rotation':(0.607047, 0.397599, 0.594291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3565.21019531, 362.8771875, 177.11626952999998), 'rotation':(0.607047, 0.397599, 0.594291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3559.54957031, 362.83863281000004, 177.05537109), 'rotation':(0.616261, 0.397614, 0.603106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3542.56835938, 362.72265625, 176.87158202999998), 'rotation':(0.620851, 0.397867, 0.607501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3531.2478125, 362.64539062000006, 176.74830078), 'rotation':(0.623234, 0.397885, 0.609783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3525.58742188, 362.60679687999993, 176.68619141), 'rotation':(0.627817, 0.397982, 0.614174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3485.96386719, 362.33628906, 176.24419922), 'rotation':(0.642693, 0.398499, 0.628398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3474.6428125, 362.25902343999996, 176.11634766), 'rotation':(0.647283, 0.398586, 0.632785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3463.32179688, 362.18175781, 175.98761718999998), 'rotation':(0.651627, 0.398401, 0.636939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3457.66113281, 362.14320312000007, 175.92294922000002), 'rotation':(0.653984, 0.398737, 0.639189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3452.00121094, 362.10449219, 175.85808594), 'rotation':(0.656258, 0.398509, 0.641344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3446.34058594, 362.06585938, 175.79314452999998), 'rotation':(0.657242, 0.398714, 0.642299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3429.3591406200003, 361.94996094, 175.59810547), 'rotation':(0.659523, 0.398786, 0.644474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3423.69875, 361.91136718999996, 175.53267577999998), 'rotation':(0.659523, 0.398786, 0.644474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3412.37769531, 361.83406249999996, 175.40115234), 'rotation':(0.666312, 0.398822, 0.650956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3406.71726562, 361.79539062000003, 175.3353125), 'rotation':(0.666312, 0.398822, 0.650956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3401.05664062, 361.75675780999995, 175.26947266), 'rotation':(0.666292, 0.399001, 0.650938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3395.39601562, 361.718125, 175.20363281000002), 'rotation':(0.666305, 0.398813, 0.650936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3389.73535156, 361.67945312000006, 175.13779297000002), 'rotation':(0.666305, 0.398813, 0.650936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3384.0746875, 361.64085937999994, 175.07195312), 'rotation':(0.666305, 0.398813, 0.650936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3372.75390625, 361.56359375, 174.93996094), 'rotation':(0.669304, 0.398861, 0.653795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3361.43285156, 361.48632812000005, 174.80751952999998), 'rotation':(0.670164, 0.3989, 0.654625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3604.12425781, 355.26203124999995, 177.5203125), 'rotation':(-0.584045, -179.602768, -0.596039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3598.47046875, 355.22339844, 177.46265625), 'rotation':(-0.588776, -179.602966, -0.600952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3592.81761719, 355.18480468999996, 177.40474609), 'rotation':(-0.588776, -179.602966, -0.600952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3587.16359375, 355.14625, 177.34664062), 'rotation':(-0.597931, -179.602768, -0.610504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3564.54980469, 354.99195312000006, 177.10857422), 'rotation':(-0.616272, -179.602386, -0.629639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3547.58960938, 354.87609375, 176.92542969), 'rotation':(-0.62085, -179.602127, -0.63443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3541.93578125, 354.8375390599999, 176.86416015999998), 'rotation':(-0.62323, -179.602112, -0.636902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3536.28273438, 354.79894531, 176.80269531000002), 'rotation':(-0.627808, -179.60202, -0.641693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3530.62914062, 354.76039062000007, 176.7409375), 'rotation':(-0.627808, -179.60202, -0.641693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3513.6684375, 354.64460938, 176.55351561999998), 'rotation':(-0.639404, -179.601913, -0.653809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3502.36179688, 354.56746094000005, 176.42734375), 'rotation':(-0.640594, -179.601257, -0.655029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3491.0549218799997, 354.49023437999995, 176.30082031), 'rotation':(-0.645081, -179.601746, -0.659729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3485.40136719, 354.45164062000003, 176.23726562), 'rotation':(-0.647278, -179.601715, -0.662048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3474.09449219, 354.37453125, 176.10951172), 'rotation':(-0.649567, -179.601639, -0.664398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3468.4409375, 354.3359375, 176.0453125), 'rotation':(-0.651642, -179.600998, -0.666595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3445.82714844, 354.18156250000004, 175.78664062), 'rotation':(-0.657379, -179.601456, -0.672577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3428.86671875, 354.06578125, 175.59179688), 'rotation':(-0.664001, -179.601105, -0.679535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3417.55980469, 353.98863281, 175.46080078), 'rotation':(-0.666321, -179.601181, -0.681946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3400.59914062, 353.8728125, 175.26351562), 'rotation':(-0.66629, -179.601181, -0.681946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3383.63820312, 353.75707031, 175.06623047000002), 'rotation':(-0.667358, -179.600861, -0.683044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3377.9846093799997, 353.71843750000005, 175.00039062), 'rotation':(-0.669312, -179.600815, -0.685089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3372.33105469, 353.67980468999997, 174.93439453), 'rotation':(-0.670166, -179.601318, -0.686005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3857.9096875, 356.89929687999995, 179.47611328), 'rotation':(-0.253387, -179.607498, -0.255615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3852.2370312499997, 356.95539062, 179.4509375), 'rotation':(-0.263214, -179.607635, -0.265625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3846.56054688, 356.91664062000007, 179.42484375), 'rotation':(-0.274109, -179.607742, -0.276764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3840.885, 356.87792969, 179.39826172000002), 'rotation':(-0.274109, -179.607742, -0.276764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3818.1823437499997, 356.72300781, 179.28107422000002), 'rotation':(-0.339508, -179.607025, -0.343567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.5065624999997, 356.68433594, 179.24855469), 'rotation':(-0.339508, -179.607025, -0.343567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.83007812, 356.64558594000005, 179.21492188), 'rotation':(-0.350464, -179.606583, -0.354767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3789.8034374999997, 356.52929687999995, 179.11027344), 'rotation':(-0.365356, -179.6064, -0.370056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3778.45164062, 356.45183594, 179.03630859), 'rotation':(-0.385162, -179.606155, -0.390381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3750.07375, 356.25816406, 178.83314453), 'rotation':(-0.429901, -179.605865, -0.436371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.72242188, 356.18074219000005, 178.74724609), 'rotation':(-0.453247, -179.605194, -0.460449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3733.04640625, 356.14195312000004, 178.70335938), 'rotation':(-0.453247, -179.605194, -0.460449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.37039062, 356.10320312, 178.65845703), 'rotation':(-0.468811, -179.605331, -0.476562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.69578125, 356.06445312000005, 178.61248047), 'rotation':(-0.468811, -179.605331, -0.476562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3716.02046875, 356.0257421900001, 178.5659375), 'rotation':(-0.484406, -179.604691, -0.492645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3710.34398438, 355.98707031000004, 178.51792969), 'rotation':(-0.492188, -179.604675, -0.500671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3704.66890625, 355.94832031, 178.46958984), 'rotation':(-0.492188, -179.604675, -0.500671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3698.99390625, 355.90953125, 178.42078125), 'rotation':(-0.495819, -179.604584, -0.504456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3693.3176562500003, 355.87085937999996, 178.37158202999998), 'rotation':(-0.503052, -179.604462, -0.511963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3687.6418750000003, 355.83210938, 178.32171875), 'rotation':(-0.510132, -179.60434, -0.519287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3676.28976562, 355.75457030999996, 178.21992188000002), 'rotation':(-0.524506, -179.604065, -0.534149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3659.2634375, 355.6384375, 178.0621875), 'rotation':(-0.546234, -179.603653, -0.556702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3653.58765625, 355.59960937999995, 178.00826172), 'rotation':(-0.549866, -179.603973, -0.560516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3642.23632812, 355.52214844, 177.89941406000003), 'rotation':(-0.549896, -179.603409, -0.560516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3858.92484375, 364.99644531, 179.48085938), 'rotation':(0.233565, 0.392094, 0.231672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3853.24414062, 364.85144531000003, 179.45574219), 'rotation':(0.253386, 0.391997, 0.251148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3847.56320312, 364.80421875, 179.42970703), 'rotation':(0.263201, 0.392347, 0.260795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3841.88085938, 364.76539062000006, 179.40328125), 'rotation':(0.263201, 0.392347, 0.260795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3824.83132812, 364.6490625, 179.31818359000002), 'rotation':(0.295973, 0.392653, 0.292928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3813.4674999999997, 364.57148438, 179.25457031000002), 'rotation':(0.317734, 0.392887, 0.31423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3802.10179688, 364.49390625, 179.18650391), 'rotation':(0.339515, 0.39296, 0.335513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3768.00539062, 364.26125, 178.96488281), 'rotation':(0.395106, 0.393656, 0.389682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3762.3225, 364.22246094, 178.92427734), 'rotation':(0.40501, 0.394107, 0.399312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3756.6396875, 364.18371093999997, 178.88259766), 'rotation':(0.424988, 0.394398, 0.418731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3750.9575, 364.14496094000003, 178.84017577999998), 'rotation':(0.429892, 0.394128, 0.423475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3745.27367188, 364.10613280999996, 178.79751953), 'rotation':(0.429892, 0.394468, 0.423474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3739.5915625, 364.06738281, 178.75427734000002), 'rotation':(0.429892, 0.394468, 0.423474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3728.2253124999997, 363.98976562000007, 178.66564452999998), 'rotation':(0.453238, 0.3948, 0.446109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3722.5442187500003, 363.95097655999996, 178.61988281), 'rotation':(0.453238, 0.3948, 0.446109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3716.86085938, 363.91222656, 178.57335938), 'rotation':(0.468817, 0.394856, 0.461206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3711.17820312, 363.8733984400001, 178.52542968999998), 'rotation':(0.484417, 0.395118, 0.476271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3694.130625, 363.75707031, 178.37914062), 'rotation':(0.495824, 0.395426, 0.487288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3688.4475, 363.71828125, 178.32927734), 'rotation':(0.503057, 0.395548, 0.494289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3671.40015625, 363.60191406, 178.17568359), 'rotation':(0.524483, 0.395932, 0.514961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3660.03445312, 363.52441406, 178.06992188), 'rotation':(0.53912, 0.396206, 0.529045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3642.98632812, 363.40808594, 177.90712890999998), 'rotation':(0.549871, 0.396565, 0.539391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3997.4553125, 359.58167969, 179.68173828), 'rotation':(-0.117188, -5.580261, -0.117676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3986.3293750000003, 360.60863281, 179.70404297000002), 'rotation':(-0.105042, -5.014008, -0.105408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3975.18554688, 361.53222656, 179.71894531), 'rotation':(-0.056458, -4.547119, -0.05658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3964.02195312, 362.22070312000005, 179.72283202999998), 'rotation':(-0.008057, -4.080811, -0.008087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3952.85570312, 362.91882812000006, 179.71572265999998), 'rotation':(0.040332, -3.613525, 0.040272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3947.2690625, 363.23445312, 179.70878906000002), 'rotation':(0.064702, -3.379486, 0.064558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3936.09546875, 363.7946875, 179.69365234), 'rotation':(0.076853, -2.775848, 0.076652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3924.92554688, 364.39019530999997, 179.6753125), 'rotation':(0.103307, -2.140778, 0.10293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3913.74, 364.73644531, 179.65109375), 'rotation':(0.120833, -1.825104, 0.120331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3991.84523438, 352.05226562000007, 179.69175781), 'rotation':(0.118272, 174.719727, 0.117789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3980.56640625, 353.04613281, 179.71216797), 'rotation':(0.057018, 175.452621, 0.05691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3974.92578125, 353.50242187999993, 179.71857422000002), 'rotation':(0.03258, 175.686371, 0.032547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.28171875, 353.9325, 179.72224609), 'rotation':(0.008148, 175.920151, 0.008146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3957.9865625, 354.70769530999996, 179.72066406000002), 'rotation':(-0.040741, 176.386826, -0.040771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3946.67578125, 355.33167969, 179.70855468999997), 'rotation':(-0.077637, 176.89978, -0.07785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3929.6975, 356.18089843999996, 179.68451172000002), 'rotation':(-0.10434, 177.859344, -0.104706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3924.03539062, 356.39257812000005, 179.67421875), 'rotation':(-0.12204, 178.174561, -0.122559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3912.7160937500003, 356.73546875, 179.64910156000002), 'rotation':(-0.148773, 178.749725, -0.149536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3901.40453125, 356.97613280999997, 179.62015625), 'rotation':(-0.148773, 179.158585, -0.149567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3895.74953125, 357.05296875, 179.60550781), 'rotation':(-0.148773, 179.362244, -0.149536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3324.18871094, 518.39800781, 173.94878906000002), 'rotation':(0.705996, 0.595005, 0.688755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3318.64039062, 518.34117188, 173.88056641), 'rotation':(0.704397, 0.594945, 0.687243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3285.34984375, 518.00046875, 173.47277343999997), 'rotation':(0.695791, 0.594997, 0.679048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3257.60791016, 517.7165625, 173.13703125), 'rotation':(0.693141, 0.594734, 0.676519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3246.51097656, 517.60304688, 173.00324218999998), 'rotation':(0.689029, 0.594402, 0.672606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3207.67164062, 517.20550781, 172.53951172), 'rotation':(0.681988, 0.594309, 0.665893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3191.02636719, 517.03515625, 172.34259766), 'rotation':(0.676721, 0.59401, 0.660886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3185.47802734, 516.97832031, 172.27740234), 'rotation':(0.673211, 0.594393, 0.657521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3174.380625, 516.86480469, 172.14775391), 'rotation':(0.668068, 0.593652, 0.652624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3168.83226562, 516.8080468799999, 172.08304688), 'rotation':(0.668033, 0.594303, 0.652594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3163.28393555, 516.75128906, 172.01833984), 'rotation':(0.668068, 0.594333, 0.652622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3163.34545898, 508.87082031, 172.01810547000002), 'rotation':(-0.667877, -179.40567, -0.683594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3168.89378906, 508.92761719000003, 172.0828125), 'rotation':(-0.66806, -179.406006, -0.683777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3191.08740234, 509.15476562000003, 172.34238281), 'rotation':(-0.673218, -179.405838, -0.689178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3202.18433594, 509.26832031, 172.47339843999998), 'rotation':(-0.676727, -179.405762, -0.692871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3207.73265625, 509.32503906, 172.53927734), 'rotation':(-0.680267, -179.405685, -0.696564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3218.82933594, 509.43863281, 172.67134765999998), 'rotation':(-0.681976, -179.405472, -0.698364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3224.37769531, 509.49539062, 172.73740234000002), 'rotation':(-0.681976, -179.405685, -0.698364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3229.92626953, 509.5521875, 172.80359375), 'rotation':(-0.68338, -179.405502, -0.699829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3241.02294922, 509.66578125, 172.93632811999998), 'rotation':(-0.686096, -179.405472, -0.702667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3252.119375, 509.77929687999995, 173.06978515999998), 'rotation':(-0.689056, -179.40538, -0.70575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3263.21605469, 509.89285156, 173.20386718999998), 'rotation':(-0.693146, -179.405548, -0.710083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3274.31273438, 510.00644531, 173.33814453), 'rotation':(-0.693176, -179.405228, -0.710114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3279.86083984, 510.06320312, 173.4053125), 'rotation':(-0.693146, -179.405243, -0.710083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3285.40917969, 510.12, 173.47251953), 'rotation':(-0.693146, -179.405243, -0.710083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3290.95751953, 510.17675780999997, 173.53992188), 'rotation':(-0.69577, -179.405243, -0.71283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3296.50609375, 510.23351562000005, 173.60779297000002), 'rotation':(-0.701141, -179.40509, -0.718475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3302.05445312, 510.29027344, 173.67582031), 'rotation':(-0.703583, -179.405289, -0.721008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3307.60253906, 510.34707031, 173.74396484000002), 'rotation':(-0.703796, -179.404907, -0.721252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3324.24730469, 510.51289062, 173.94851562), 'rotation':(-0.704437, -179.405029, -0.721924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3329.79566406, 510.56566405999996, 174.01681641), 'rotation':(-0.704437, -179.405029, -0.721924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3606.09742188, 521.28265625, 177.37931641), 'rotation':(0.640795, 0.592036, 0.626576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3600.4275, 521.22460938, 177.31546875), 'rotation':(0.643363, 0.593956, 0.629033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3577.7465625, 520.9925390599999, 177.05603516), 'rotation':(0.66039, 0.59434, 0.645304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3566.4064843799997, 520.87648438, 176.92386718999998), 'rotation':(0.668969, 0.593948, 0.653497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3543.7267968799997, 520.64433594, 176.65623047), 'rotation':(0.677883, 0.594097, 0.661988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3538.05664062, 520.58636719, 176.58863281), 'rotation':(0.682875, 0.594642, 0.666755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3526.7165625, 520.4703515599999, 176.45246093999998), 'rotation':(0.687902, 0.594319, 0.671531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3521.04640625, 520.41242188, 176.38388672000002), 'rotation':(0.692834, 0.594902, 0.676224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3515.37671875, 520.354375, 176.31507812), 'rotation':(0.695327, 0.594687, 0.678608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3509.70703125, 520.29640625, 176.24623047), 'rotation':(0.695327, 0.594687, 0.678608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3504.036875, 520.23835938, 176.17726562), 'rotation':(0.696351, 0.594809, 0.679573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3492.69628906, 520.12230469, 176.03876953), 'rotation':(0.700238, 0.594902, 0.683274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3487.02660156, 520.06425781, 175.96927734000002), 'rotation':(0.702109, 0.594948, 0.685054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3464.34570312, 519.83222656, 175.689375), 'rotation':(0.710025, 0.595145, 0.692582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.32542969, 519.4840624999999, 175.26677734), 'rotation':(0.712177, 0.595309, 0.694649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3396.30421875, 519.13597656, 174.84304688), 'rotation':(0.713488, 0.595062, 0.695879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3390.63402344, 519.07792969, 174.77246093999997), 'rotation':(0.713051, 0.595372, 0.695473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3373.62351562, 518.9038281200001, 174.5609375), 'rotation':(0.711993, 0.59491, 0.694457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3362.28296875, 518.78773438, 174.41994140999998), 'rotation':(0.712156, 0.595589, 0.694619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3368.00390625, 510.96515625, 174.49005859000002), 'rotation':(-0.712158, -179.405075, -0.730042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3379.34421875, 511.08121094, 174.63103515999998), 'rotation':(-0.711975, -179.404739, -0.729858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3385.01464844, 511.13925781, 174.70154297000002), 'rotation':(-0.712158, -179.405075, -0.730042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3390.68457031, 511.19730469, 174.77207031), 'rotation':(-0.712433, -179.404892, -0.730316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3424.70554688, 511.54542969, 175.19578125), 'rotation':(-0.713379, -179.404938, -0.731323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3453.05640625, 511.83554688, 175.54824219), 'rotation':(-0.710999, -179.404892, -0.72879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3464.39671875, 511.9515625, 175.68900391), 'rotation':(-0.710999, -179.404877, -0.728821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3470.06640625, 512.00953125, 175.75923827999998), 'rotation':(-0.710022, -179.404846, -0.727783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3475.73679688, 512.06757812, 175.82931641), 'rotation':(-0.70816, -179.404892, -0.72583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3481.40671875, 512.125625, 175.89919922), 'rotation':(-0.706146, -179.404953, -0.723724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3487.07738281, 512.18367188, 175.96890625), 'rotation':(-0.704132, -179.405243, -0.721619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3504.08765625, 512.3577734400001, 176.17691406000003), 'rotation':(-0.698242, -179.405136, -0.715393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3509.7575781200003, 512.41570312, 176.24585938), 'rotation':(-0.696381, -179.405151, -0.71347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3515.42773438, 512.47375, 176.31472656000003), 'rotation':(-0.696381, -179.405151, -0.71347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3526.7678125, 512.58976562, 176.45210938), 'rotation':(-0.69281, -179.405334, -0.709717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3549.44847656, 512.81648438, 176.72304688), 'rotation':(-0.677887, -179.405685, -0.694061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3555.11839844, 512.87171875, 176.79), 'rotation':(-0.677887, -179.405685, -0.694061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3566.45851562, 513.0178906200001, 176.92353516), 'rotation':(-0.673309, -179.40564, -0.68927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3577.79882812, 513.145, 177.05570312), 'rotation':(-0.664734, -179.405823, -0.680267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3583.4689843799997, 513.20304688, 177.12117188), 'rotation':(-0.6604, -179.40625, -0.675751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3594.80933594, 513.31910156, 177.25091797000002), 'rotation':(-0.651825, -179.406418, -0.666809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3606.14964844, 513.43511719, 177.37900391), 'rotation':(-0.643402, -179.406311, -0.657959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3655.59695312, 513.89191406, 177.91416016), 'rotation':(-0.595978, -179.407501, -0.60849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3678.35203125, 514.1409375000001, 178.1465625), 'rotation':(-0.574646, -179.408173, -0.586273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3689.72953125, 514.25738281, 178.25810547), 'rotation':(-0.559753, -179.408447, -0.57077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3706.79734375, 514.4319531200001, 178.41960938), 'rotation':(-0.533997, -179.408813, -0.544037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3712.4870312499997, 514.4901171900001, 178.47263672), 'rotation':(-0.53418, -179.408783, -0.54422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3729.5546875, 514.66480469, 178.6275), 'rotation':(-0.50708, -179.409134, -0.516113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3735.24265625, 514.7230078099999, 178.67671875), 'rotation':(-0.50708, -179.409134, -0.516113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3752.31078125, 514.89765625, 178.81791016), 'rotation':(-0.4617, -179.409653, -0.469208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3763.6896875, 515.01410156, 178.90921875), 'rotation':(-0.456665, -179.409668, -0.463989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3786.4465625000003, 515.2469531200001, 179.08037109), 'rotation':(-0.415527, -179.41095, -0.42157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3803.51492188, 515.4215624999999, 179.19732422), 'rotation':(-0.384583, -179.410751, -0.389771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3820.58273438, 515.5961718799999, 179.30472656), 'rotation':(-0.339111, -179.411621, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3843.339375, 515.82902344, 179.4253125), 'rotation':(-0.274811, -179.412918, -0.277466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3849.02882812, 515.8871875, 179.45134765999998), 'rotation':(-0.258789, -179.412445, -0.261139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3854.71804688, 515.94539062, 179.47638672000002), 'rotation':(-0.250702, -179.412445, -0.252899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3848.95359375, 523.76734375, 179.45136718999998), 'rotation':(0.250688, 0.587106, 0.248514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3843.26414062, 523.7091015599999, 179.42533203), 'rotation':(0.258789, 0.58754, 0.256458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3837.57492188, 523.6509375, 179.39767578), 'rotation':(0.274806, 0.587715, 0.272178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3831.8854687499997, 523.59269531, 179.36833984), 'rotation':(0.290952, 0.587852, 0.288006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3826.19851562, 523.53449219, 179.33738281), 'rotation':(0.307126, 0.588047, 0.303846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3820.50875, 523.4762499999999, 179.30478516), 'rotation':(0.323116, 0.587561, 0.31949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3809.12984375, 523.35992188, 179.23458984), 'rotation':(0.355279, 0.588576, 0.3509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3797.7526562499997, 523.24347656, 179.159375), 'rotation':(0.384594, 0.588612, 0.379458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3780.68429688, 523.06898438, 179.03931641), 'rotation':(0.415515, 0.589044, 0.409515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3757.92921875, 522.83613281, 178.86384766), 'rotation':(0.456673, 0.589669, 0.449441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3752.2395312500003, 522.7778906200001, 178.81796875), 'rotation':(0.461707, 0.590339, 0.454305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3740.86109375, 522.66144531, 178.72507812), 'rotation':(0.470846, 0.590251, 0.463162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.171875, 522.60320312, 178.67681641), 'rotation':(0.488796, 0.590554, 0.480516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3723.79492188, 522.48695312, 178.57724609000002), 'rotation':(0.507053, 0.590854, 0.49814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3718.1059375, 522.42871094, 178.52527343999998), 'rotation':(0.525023, 0.590778, 0.515465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3712.4175, 522.37046875, 178.47275391), 'rotation':(0.525023, 0.590778, 0.515465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3706.7278125000003, 522.3122656200001, 178.41970702999998), 'rotation':(0.534162, 0.591188, 0.524266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3689.66039062, 522.1375781200001, 178.25820312), 'rotation':(0.552549, 0.591413, 0.541968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3672.59398438, 521.96308594, 178.0896875), 'rotation':(0.574672, 0.591847, 0.563233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3661.2160937500003, 521.84660156, 177.97324218999998), 'rotation':(0.589227, 0.592115, 0.577196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3654.09277344, 521.8058593799999, 177.89933594), 'rotation':(0.593079, 0.592223, 0.580911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3644.14769531, 521.80152344, 177.79501953), 'rotation':(0.602033, 0.59233, 0.589483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2984.32397461, 691.18201172, 169.60773438), 'rotation':(-0.641052, -173.744156, -0.655518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3000.7890625, 692.85552734, 169.79363281000002), 'rotation':(-0.648804, -174.44281, -0.663635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3006.31518555, 693.34423828, 169.85617188), 'rotation':(-0.64856, -174.908936, -0.663361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3022.95507812, 694.44585938, 170.04716797), 'rotation':(-0.665527, -177.017471, -0.681152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3028.50952148, 694.6873242199999, 170.11154297000002), 'rotation':(-0.665558, -177.635803, -0.681152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.62573242, 694.9829101600001, 170.24025390999998), 'rotation':(-0.665497, -178.872101, -0.681122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.7019043, 695.05285156, 170.36857422), 'rotation':(-0.667542, -179.658875, -0.683258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3056.22412109, 695.0646875, 170.43244141), 'rotation':(-0.66214, -179.868759, -0.677582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3105.86425781, 695.31646484, 171.0153125), 'rotation':(-0.679352, -179.868622, -0.695618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3111.37988281, 695.3283007800001, 171.08101562), 'rotation':(-0.68158, -179.868576, -0.697937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3122.41088867, 695.35974609, 171.21304688), 'rotation':(-0.685852, -179.868469, -0.702423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3127.34179688, 703.3881835899999, 171.27251952999998), 'rotation':(0.690102, 0.131625, 0.673619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.27514648, 703.364375, 171.13972656), 'rotation':(0.685833, 0.131523, 0.669556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3105.20849609, 703.34050781, 171.00771484), 'rotation':(0.681605, 0.131426, 0.66552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3099.67504883, 703.3285546899999, 170.94205078), 'rotation':(0.679358, 0.131366, 0.663386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3083.07446289, 703.2927929699999, 170.74619141), 'rotation':(0.674092, 0.131009, 0.658374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3077.54150391, 703.28033203, 170.68125), 'rotation':(0.672316, 0.131473, 0.656666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3055.40795898, 703.0884375, 170.42316406), 'rotation':(0.665506, 0.131314, 0.650171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3044.34619141, 703.05779297, 170.29560547), 'rotation':(0.652037, 0.341491, 0.637316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3038.82104492, 702.99828125, 170.23251953), 'rotation':(0.650883, 0.762179, 0.636236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3027.79052734, 702.69128906, 170.10679688), 'rotation':(0.650357, 2.054985, 0.635709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.26171875, 701.9198632800001, 169.91890625), 'rotation':(0.645863, 3.682369, 0.631432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2983.90161133, 699.28460938, 169.61289062), 'rotation':(0.641184, 6.255831, 0.626948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.28637695, 695.43365234, 171.67183594), 'rotation':(-0.702271, -179.867966, -0.719666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3171.32933594, 695.4574609399999, 171.80796875), 'rotation':(-0.708221, -179.867813, -0.725891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3182.37207031, 695.48121094, 171.94492188), 'rotation':(-0.711121, -179.867874, -0.728943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.89404297, 695.49310547, 172.01353516), 'rotation':(-0.711121, -179.867874, -0.728943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.93652344, 695.5169140600001, 172.15166016), 'rotation':(-0.719574, -179.867493, -0.737823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3209.97949219, 695.54070312, 172.29119140999998), 'rotation':(-0.726288, -179.868011, -0.744904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.50074219, 695.55261719, 172.36150390999998), 'rotation':(-0.729797, -179.867233, -0.748566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3226.54394531, 695.57640625, 172.50320312), 'rotation':(-0.736572, -179.86705, -0.755676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3232.06519531, 695.58826172, 172.57433593999997), 'rotation':(-0.73819, -179.866974, -0.757416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.58617188, 695.60015625, 172.64548828), 'rotation':(-0.738342, -179.866974, -0.757568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3248.62914062, 695.62396484, 172.78794922), 'rotation':(-0.73819, -179.867661, -0.757416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3254.15039062, 695.63580078, 172.85955077999998), 'rotation':(-0.742004, -179.866959, -0.761414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3276.23535156, 695.68335938, 173.14951172000002), 'rotation':(-0.753174, -179.866638, -0.773193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3281.75707031, 695.6953125, 173.22212890999998), 'rotation':(-0.753174, -179.866638, -0.773193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.32080078, 695.73095703, 173.44144531), 'rotation':(-0.760498, -179.866455, -0.780884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.36304688, 695.75470703, 173.58910156000002), 'rotation':(-0.766235, -179.866302, -0.786926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3320.05640625, 703.65857422, 173.73341797), 'rotation':(0.775021, 0.13329, 0.754261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3314.53125, 703.64666016, 173.65882812), 'rotation':(0.771914, 0.133856, 0.751331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.00660156, 703.63476562, 173.58455078), 'rotation':(0.769148, 0.133782, 0.748704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3303.48167969, 703.62287109, 173.51054688), 'rotation':(0.766204, 0.133703, 0.745922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3297.95703125, 703.61089844, 173.43683593999998), 'rotation':(0.763267, 0.133624, 0.74314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3275.85693359, 703.56330078, 173.14476562), 'rotation':(0.754633, 0.133395, 0.734942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3270.33203125, 703.55138672, 173.07210938), 'rotation':(0.753172, 0.133351, 0.733567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3264.80738281, 703.5394921899999, 172.99947265999998), 'rotation':(0.753103, 0.132994, 0.73351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3259.28222656, 703.52757812, 172.92691406000003), 'rotation':(0.753103, 0.132994, 0.73351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3248.23242188, 703.50384766, 172.78304688), 'rotation':(0.741963, 0.133029, 0.722936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.18238281, 703.47998047, 172.64052734), 'rotation':(0.738193, 0.13302, 0.719345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3226.13257812, 703.45617188, 172.498125), 'rotation':(0.738193, 0.13302, 0.719345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3220.60667969, 703.44427734, 172.42705078), 'rotation':(0.736554, 0.132946, 0.717812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.08203125, 703.43238281, 172.35638672000002), 'rotation':(0.733091, 0.132167, 0.714513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.50707031, 703.39666016, 172.14646484000002), 'rotation':(0.722825, 0.132592, 0.70477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3176.40648438, 703.3490625, 171.87105469), 'rotation':(0.711118, 0.132119, 0.693621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3165.35595703, 703.32525391, 171.73433594), 'rotation':(0.708209, 0.132179, 0.690859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3363.83351562, 695.87207031, 174.32884765999998), 'rotation':(-0.786041, -179.865891, -0.807831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3392.06398438, 695.93285156, 174.71626952999998), 'rotation':(-0.786041, -179.865891, -0.807831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3397.70996094, 695.9449999999999, 174.79384765999998), 'rotation':(-0.787476, -179.865509, -0.809326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.3559375, 695.95714844, 174.87173828), 'rotation':(-0.790161, -179.865952, -0.812164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3414.6482031200003, 695.98150391, 175.02777343999998), 'rotation':(-0.791595, -179.865631, -0.81369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3425.93992188, 696.00585938, 175.18380859), 'rotation':(-0.791626, -179.865631, -0.813721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3431.5859375, 696.01800781, 175.26183593999997), 'rotation':(-0.791595, -179.865631, -0.81369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3437.2321875, 696.03015625, 175.33986328), 'rotation':(-0.791595, -179.865631, -0.81369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3471.10816406, 696.10308594, 175.80634766), 'rotation':(-0.78775, -179.865646, -0.809662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3476.75390625, 696.11523438, 175.88392578), 'rotation':(-0.787903, -179.86618, -0.809784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3482.39992188, 696.1274414100001, 175.96138672), 'rotation':(-0.785767, -179.865814, -0.807526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3493.69164062, 696.15173828, 176.11558594), 'rotation':(-0.781494, -179.865921, -0.80304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3499.33789062, 696.1638281200001, 176.19220703), 'rotation':(-0.777405, -179.866043, -0.798706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3504.98363281, 696.17601562, 176.26867188), 'rotation':(-0.777405, -179.866043, -0.798706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3521.9216406200003, 696.2035546899999, 176.49697265999998), 'rotation':(-0.771057, -179.866119, -0.792053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3533.21335938, 696.26335938, 176.64841797), 'rotation':(-0.767975, -179.866226, -0.788788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3555.79734375, 696.31853516, 176.94664062), 'rotation':(-0.749237, -179.86673, -0.769043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3578.38160156, 696.19703125, 177.23978516), 'rotation':(-0.738251, -179.867004, -0.757477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3584.0278125, 696.20916016, 177.31193359), 'rotation':(-0.732849, -179.867142, -0.751801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3595.3200781200003, 696.2335156199999, 177.45455077999998), 'rotation':(-0.722321, -179.867416, -0.740692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3600.96605469, 696.24560547, 177.52505859000001), 'rotation':(-0.71698, -179.867554, -0.735107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3595.24878906, 704.38068359, 177.45388672), 'rotation':(0.716944, 0.132441, 0.699174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3578.29296875, 704.2840039099999, 177.23888672), 'rotation':(0.732859, 0.132844, 0.714289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3572.64109375, 704.2378515600001, 177.16611328), 'rotation':(0.738255, 0.132339, 0.719407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3566.98976562, 704.1917187500001, 177.09283202999998), 'rotation':(0.743411, 0.133115, 0.724309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3555.6875, 704.16601562, 176.94542968999997), 'rotation':(0.746082, 0.133377, 0.726847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3527.42796875, 704.1051562499999, 176.57113281000002), 'rotation':(0.767973, 0.133769, 0.7476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3516.12453125, 704.08082031, 176.41916016), 'rotation':(0.771067, 0.133873, 0.750521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3499.16917969, 704.04431641, 176.19015625), 'rotation':(0.773123, 0.13385, 0.752464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3487.86546875, 704.02001953, 176.03632812), 'rotation':(0.781483, 0.134077, 0.760374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3482.21335938, 704.0078125, 175.95904297), 'rotation':(0.781483, 0.134077, 0.760374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3470.91039062, 703.9835156199999, 175.80386718999998), 'rotation':(0.787862, 0.134359, 0.766407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3465.25855469, 703.97130859, 175.72613281000002), 'rotation':(0.787862, 0.134359, 0.766407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3436.99878906, 703.9104687500001, 175.336875), 'rotation':(0.791612, 0.134374, 0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.3471875, 703.8982617199999, 175.25876953), 'rotation':(0.791612, 0.134374, 0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3414.39109375, 703.86175781, 175.02445312), 'rotation':(0.791612, 0.134374, 0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3408.73902344, 703.8495507800001, 174.94632812), 'rotation':(0.791592, 0.13437, 0.769939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3391.78320312, 703.81310547, 174.71263672), 'rotation':(0.787466, 0.133983, 0.766045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3386.130625, 703.80089844, 174.63503906000003), 'rotation':(0.786032, 0.134545, 0.764686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3380.47875, 703.7887499999999, 174.5575), 'rotation':(0.786032, 0.134545, 0.764686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.17480469, 703.76441406, 174.40238281), 'rotation':(0.786052, 0.13411, 0.764703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3636.23875, 704.4689257800001, 177.95544922000002), 'rotation':(0.67388, 0.13152, 0.658154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3859.5051562500003, 704.8222070300001, 179.87433593999998), 'rotation':(0.247615, 0.124363, 0.245483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3848.19164062, 704.79529297, 179.82542969), 'rotation':(0.247615, 0.124363, 0.245483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3842.53539062, 704.78308594, 179.79984375), 'rotation':(0.257266, 0.124665, 0.254965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3819.913125, 704.7345507800001, 179.67707031), 'rotation':(0.334276, 0.125461, 0.330403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3802.94554688, 704.698125, 179.5640625), 'rotation':(0.392012, 0.126196, 0.386667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3797.29, 704.68591797, 179.52408203), 'rotation':(0.40156, 0.126274, 0.39597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3780.32273438, 704.64941406, 179.39769531000002), 'rotation':(0.434632, 0.126724, 0.428078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3769.01023438, 704.62511719, 179.30623047), 'rotation':(0.456516, 0.127065, 0.449283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3763.355, 704.61291016, 179.25892578), 'rotation':(0.478482, 0.127417, 0.470545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3752.0425, 704.58849609, 179.16210938), 'rotation':(0.489472, 0.127791, 0.481164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3746.38648438, 704.57634766, 179.11275390999998), 'rotation':(0.49495, 0.127341, 0.486465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.07398438, 704.5520703100001, 179.01046875), 'rotation':(0.528629, 0.128629, 0.518943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3729.4196875, 704.53986328, 178.95755859000002), 'rotation':(0.539824, 0.128154, 0.529718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3689.82835938, 704.45464844, 178.55847656000003), 'rotation':(0.601419, 0.129763, 0.588896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3672.86179688, 704.4182812500001, 178.37427734000002), 'rotation':(0.628371, 0.130341, 0.614707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3667.20609375, 704.4060742199999, 178.31103516), 'rotation':(0.637298, 0.130542, 0.62324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3655.89429688, 704.38171875, 178.18279297), 'rotation':(0.650692, 0.130864, 0.63604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3650.24121094, 704.4019140600001, 178.11833984), 'rotation':(0.655466, 0.130466, 0.640599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3638.88160156, 696.33484375, 177.98632812), 'rotation':(-0.683044, -179.868271, -0.699493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3655.85304688, 696.50091797, 178.18212891), 'rotation':(-0.650848, -179.869125, -0.665771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3661.5104687499997, 696.51306641, 178.24638672), 'rotation':(-0.650696, -179.869125, -0.665619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3667.16796875, 696.52527344, 178.31041016), 'rotation':(-0.64624, -179.869247, -0.66095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3678.48289062, 696.5496875, 178.43605469), 'rotation':(-0.628418, -179.869644, -0.642303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3712.4275, 696.62273438, 178.79103515999998), 'rotation':(-0.578979, -179.870865, -0.590759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3718.08445312, 696.63488281, 178.84763672), 'rotation':(-0.573303, -179.870514, -0.584839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3723.74585938, 696.64513672, 178.90306640999998), 'rotation':(-0.562256, -179.871414, -0.573364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3740.71414062, 696.68359375, 179.06191406000002), 'rotation':(-0.528595, -179.871368, -0.538422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3746.37179688, 696.69580078, 179.11248047), 'rotation':(-0.506348, -179.871765, -0.51535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3752.02929688, 696.70794922, 179.16185547), 'rotation':(-0.494965, -179.87265, -0.503571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3757.68703125, 696.72015625, 179.21037109), 'rotation':(-0.494965, -179.87265, -0.503571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3774.6596875, 696.7566601599999, 179.35244140999998), 'rotation':(-0.478516, -179.872971, -0.486542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3780.318125, 696.76878906, 179.39751952999998), 'rotation':(-0.456512, -179.872925, -0.463806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3785.97484375, 696.7809374999999, 179.44082031000002), 'rotation':(-0.434631, -179.87326, -0.441284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3791.63234375, 696.7931445300001, 179.48320311999998), 'rotation':(-0.434631, -179.87326, -0.441284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3797.29078125, 696.80529297, 179.52396484000002), 'rotation':(-0.412659, -179.873596, -0.41864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3819.9206249999997, 696.8540039100001, 179.67701172), 'rotation':(-0.353577, -179.874298, -0.357971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3825.57859375, 696.86621094, 179.71080078), 'rotation':(-0.33429, -179.875198, -0.338196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3831.2356250000003, 696.87830078, 179.74253906), 'rotation':(-0.315002, -179.874741, -0.318481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3836.89359375, 696.89050781, 179.77222656), 'rotation':(-0.295685, -179.874954, -0.298767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3848.20875, 696.91486328, 179.82542969), 'rotation':(-0.257263, -179.875336, -0.259583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3853.86648438, 696.92699219, 179.84988281000003), 'rotation':(-0.24762, -179.875641, -0.249756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3840.58890625, 795.24414062, 180.03359375), 'rotation':(0.296635, 0.062004, 0.293576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3829.23484375, 795.23210938, 179.97136719), 'rotation':(0.312707, 0.062228, 0.309304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.87914062, 795.22015625, 179.90425781000002), 'rotation':(0.327139, 0.062805, 0.323415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.20359375, 795.21417969, 179.86890625), 'rotation':(0.35603, 0.062796, 0.351624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.52515625, 795.20818359, 179.83074219), 'rotation':(0.384717, 0.063164, 0.379586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3789.49289062, 795.19025391, 179.70902343999998), 'rotation':(0.413595, 0.063565, 0.407669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3778.13820312, 795.17822266, 179.62267577999998), 'rotation':(0.43511, 0.064097, 0.428543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3772.46023438, 795.17224609, 179.57759765999998), 'rotation':(0.449187, 0.064313, 0.442189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.10742188, 795.16021484, 179.48316406), 'rotation':(0.477382, 0.064767, 0.469485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3744.07398438, 795.14220703, 179.33082031), 'rotation':(0.533779, 0.065763, 0.523904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3732.72070312, 795.13019531, 179.22373047000002), 'rotation':(0.540999, 0.065889, 0.530864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.36523438, 795.11816406, 179.11345702999998), 'rotation':(0.550991, 0.065693, 0.540467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3715.68703125, 795.11224609, 179.056875), 'rotation':(0.570963, 0.066457, 0.559657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3698.65601562, 795.0941796899999, 178.87908202999998), 'rotation':(0.61109, 0.066919, 0.598161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3687.30296875, 795.0823437500001, 178.75644531), 'rotation':(0.621131, 0.067637, 0.607766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3675.9479687499997, 795.0703125, 178.63107422000002), 'rotation':(0.636758, 0.068047, 0.622723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3670.27046875, 795.06427734, 178.56677734000002), 'rotation':(0.647099, 0.067645, 0.632612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3658.91796875, 795.05224609, 178.43501952999998), 'rotation':(0.668013, 0.068761, 0.652577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3653.24023438, 795.04626953, 178.36751952999998), 'rotation':(0.678525, 0.068373, 0.662598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3641.88648438, 795.03429688, 178.22951172), 'rotation':(0.699439, 0.068871, 0.682527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3636.20851562, 795.02826172, 178.15966797000002), 'rotation':(0.704753, 0.069336, 0.687577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3641.87085938, 787.15349609, 178.22921875), 'rotation':(-0.704773, -179.930649, -0.72226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3653.22414062, 787.16558594, 178.36722656), 'rotation':(-0.688995, -179.931366, -0.70575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3670.25414062, 787.18353516, 178.56648438), 'rotation':(-0.657745, -179.931473, -0.672974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3675.93117188, 787.18957031, 178.63078125), 'rotation':(-0.647125, -179.932343, -0.661865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3681.6081249999997, 787.1955468799999, 178.69400391), 'rotation':(-0.63678, -179.931946, -0.651031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3692.9621875000003, 787.20757812, 178.81773438), 'rotation':(-0.621124, -179.93277, -0.634705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3704.31617188, 787.21966797, 178.93935547), 'rotation':(-0.611115, -179.932709, -0.624237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.3471875, 787.23761719, 179.11320312), 'rotation':(-0.570953, -179.933533, -0.582428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3732.70164062, 787.2496874999999, 179.22345703), 'rotation':(-0.550995, -179.933914, -0.561676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.37867188, 787.255625, 179.27730469), 'rotation':(-0.541016, -179.934097, -0.5513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3749.73265625, 787.26763672, 179.38277344), 'rotation':(-0.519867, -179.934479, -0.529358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3755.40992188, 787.2736718799999, 179.43355469), 'rotation':(-0.505585, -179.934738, -0.514557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.0871875000003, 787.27960938, 179.48292969), 'rotation':(-0.491516, -179.934967, -0.5), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3766.76367188, 787.28564453, 179.53085938), 'rotation':(-0.477386, -179.935211, -0.485382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3778.118125, 787.29767578, 179.62246094), 'rotation':(-0.449188, -179.935684, -0.456268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3783.7956249999997, 787.30365234, 179.66613281000002), 'rotation':(-0.43512, -179.935883, -0.441772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3800.82765625, 787.32166016, 179.7915625), 'rotation':(-0.413605, -179.936432, -0.419586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.504375, 787.32763672, 179.83054688), 'rotation':(-0.413605, -179.936432, -0.419586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.1823437499997, 787.33375, 179.86869141), 'rotation':(-0.384735, -179.936493, -0.389923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3823.535625, 787.34570312, 179.93878906), 'rotation':(-0.356018, -179.937195, -0.360474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3829.21414062, 787.35167969, 179.97121094), 'rotation':(-0.327148, -179.937561, -0.330902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3851.92335938, 787.37566406, 180.08953125), 'rotation':(-0.264404, -179.938309, -0.266876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3991.83109375, 794.37798828, 180.15460938), 'rotation':(-0.259369, -0.454132, -0.261749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3986.17359375, 794.42308594, 180.17789062), 'rotation':(-0.237, -0.454895, -0.238983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3974.85351562, 794.513125, 180.21613281), 'rotation':(-0.209564, -0.454895, -0.21109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.19851562, 794.5581640600001, 180.23078125), 'rotation':(-0.154449, -0.455658, -0.155273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3957.87820312, 794.64826172, 180.24697265999998), 'rotation':(-0.099426, -0.455475, -0.099762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3952.2196875, 794.69335938, 180.25089844), 'rotation':(-0.044312, -0.455627, -0.044373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3940.89773438, 794.7834375, 180.25421875), 'rotation':(-0.016754, -0.45575, -0.016754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3935.2365625, 794.82849609, 180.25587890999998), 'rotation':(-0.016846, -0.45578, -0.016846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3912.5964062499997, 795.00861328, 180.26050781), 'rotation':(-0.016846, -0.45575, -0.016846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3906.93820312, 795.05365234, 180.25697266), 'rotation':(0.019705, -0.45578, 0.019688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3901.27734375, 795.09880859, 180.24783202999998), 'rotation':(0.092638, -0.455627, 0.092336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3893.24976562, 795.25769531, 180.22757812), 'rotation':(0.153727, -0.390411, 0.152899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3935.21, 786.94792969, 180.25585938), 'rotation':(0.016741, 179.544235, 0.016729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3940.87179688, 786.90294922, 180.25421875), 'rotation':(0.016843, 179.544235, 0.016823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3946.53367188, 786.85791016, 180.25253906), 'rotation':(0.016843, 179.544235, 0.016823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.17625, 786.67767578, 180.23070312), 'rotation':(0.09942, 179.54451, 0.099078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3980.49195312, 786.58757812, 180.19841797), 'rotation':(0.154437, 179.544754, 0.153607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3161.47729492, 596.79375, 171.81083984), 'rotation':(-0.680115, -179.320404, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3167.015625, 596.85863281, 171.87658202999998), 'rotation':(-0.680115, -179.320404, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3172.55419922, 596.92359375, 171.94234375), 'rotation':(-0.680115, -179.320801, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3178.09300781, 596.98847656, 172.00832031000002), 'rotation':(-0.680115, -179.320801, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3200.24755859, 597.2479687499999, 172.27482422), 'rotation':(-0.692902, -179.32048, -0.709808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.32470703, 597.3778125, 172.40996094), 'rotation':(-0.698181, -179.320343, -0.715363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3227.93945312, 597.57246094, 172.61320312), 'rotation':(-0.700623, -179.320145, -0.717926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3233.47828125, 597.63738281, 172.68113281), 'rotation':(-0.702545, -179.320068, -0.71991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3244.55566406, 597.76714844, 172.81804688), 'rotation':(-0.710083, -179.31987, -0.727875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3250.09398438, 597.83203125, 172.88705077999998), 'rotation':(-0.71405, -179.319748, -0.732025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3255.6328125, 597.89695312, 172.95623047), 'rotation':(-0.71582, -179.319717, -0.733887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3261.17113281, 597.96183594, 173.02546875), 'rotation':(-0.71582, -179.319717, -0.733887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3266.70972656, 598.02671875, 173.0946875), 'rotation':(-0.715942, -179.319717, -0.734009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3277.78636719, 598.1565625000001, 173.23357422), 'rotation':(-0.719543, -179.320282, -0.737793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3283.32496094, 598.22144531, 173.30341797), 'rotation':(-0.722076, -179.31955, -0.740479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3299.94019531, 598.4161328099999, 173.51447266), 'rotation':(-0.729584, -179.319351, -0.748322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3322.09398438, 598.67570312, 173.79865234000002), 'rotation':(-0.735687, -179.31897, -0.754761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3327.63232422, 598.7405859400001, 173.86980469), 'rotation':(-0.735687, -179.31955, -0.754761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3321.94214844, 606.55511719, 173.79789062), 'rotation':(0.735686, 0.681027, 0.716967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3310.86962891, 606.42535156, 173.65570312), 'rotation':(0.735536, 0.681023, 0.716832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3305.33277344, 606.36046875, 173.58464844), 'rotation':(0.734505, 0.680776, 0.71585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3294.26050781, 606.2307812500001, 173.44324218999998), 'rotation':(0.729573, 0.679965, 0.711172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3277.65136719, 606.03613281, 173.23302734), 'rotation':(0.722088, 0.680458, 0.704058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3272.11474609, 605.97132812, 173.16349609), 'rotation':(0.719533, 0.680398, 0.701624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3261.04175781, 605.8415625, 173.025), 'rotation':(0.715927, 0.680274, 0.698208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3249.96851562, 605.71179688, 172.88664062), 'rotation':(0.715817, 0.680271, 0.698108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3238.89599609, 605.58210938, 172.7490625), 'rotation':(0.710087, 0.679523, 0.692649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3222.28613281, 605.3875, 172.54515625), 'rotation':(0.700627, 0.679848, 0.683637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3216.75, 605.3226171900001, 172.47744140999998), 'rotation':(0.700627, 0.679848, 0.683637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3200.14013672, 605.12800781, 172.27464844), 'rotation':(0.698168, 0.680054, 0.68131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3189.06714844, 604.99828125, 172.14080077999998), 'rotation':(0.692875, 0.679519, 0.676273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.99414062, 604.86847656, 172.00822266), 'rotation':(0.682705, 0.679684, 0.666575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3166.92089844, 604.73871094, 171.8765625), 'rotation':(0.680116, 0.679197, 0.664114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3363.91210938, 607.17640625, 174.34125), 'rotation':(0.744538, 0.681032, 0.725381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3601.63207031, 609.83210938, 177.38644531000003), 'rotation':(0.677159, 0.679212, 0.661285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3591.70191406, 609.71582031, 177.26755859000002), 'rotation':(0.688763, 0.67982, 0.672341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3580.40113281, 609.58335938, 177.13072266), 'rotation':(0.697506, 0.680028, 0.680687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3529.54859375, 608.98753906, 176.49683593999998), 'rotation':(0.724512, 0.680419, 0.706351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3518.24757812, 608.8551171900001, 176.35246094), 'rotation':(0.734245, 0.680665, 0.715609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3495.64648438, 608.5903125, 176.06175781000002), 'rotation':(0.736602, 0.680944, 0.717847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3473.04492188, 608.32550781, 175.76894531000002), 'rotation':(0.744989, 0.681223, 0.725799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3467.39453125, 608.2594140599999, 175.69511719), 'rotation':(0.748343, 0.680866, 0.728985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3456.0939843799997, 608.12695312, 175.54722656), 'rotation':(0.750037, 0.681338, 0.730588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3444.79296875, 607.99457031, 175.39923828), 'rotation':(0.75003, 0.680764, 0.730589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3439.14234375, 607.92835938, 175.32523438), 'rotation':(0.750064, 0.681366, 0.730615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3427.8415625, 607.79597656, 175.17716797), 'rotation':(0.750747, 0.681316, 0.731258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3416.54054688, 607.66351562, 175.02898438), 'rotation':(0.75113, 0.68106, 0.731637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3410.89015625, 607.5973437499999, 174.95488281000002), 'rotation':(0.751116, 0.681033, 0.731619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3405.23976562, 607.5311328099999, 174.88078125), 'rotation':(0.75113, 0.68106, 0.731637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3393.93847656, 607.3987500000001, 174.73261718999998), 'rotation':(0.750221, 0.681138, 0.730761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3376.98679688, 607.2000781200001, 174.51125), 'rotation':(0.746929, 0.681026, 0.727642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3376.96140625, 599.31855469, 174.50970703), 'rotation':(-0.745392, -179.319, -0.764984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3382.6247656200003, 599.3848828099999, 174.58351562), 'rotation':(-0.746948, -179.31897, -0.766602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3388.28832031, 599.45136719, 174.65748047), 'rotation':(-0.74881, -179.318893, -0.768585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3405.27882812, 599.6503124999999, 174.88007812), 'rotation':(-0.751251, -179.318954, -0.771149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3433.59644531, 599.9821093799999, 175.25138672), 'rotation':(-0.750763, -179.319122, -0.77066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3439.26, 600.04851562, 175.32558594), 'rotation':(-0.750305, -179.318665, -0.770142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3444.92335938, 600.1148828099999, 175.39974609), 'rotation':(-0.750031, -179.319229, -0.769867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3456.25046875, 600.2475781200001, 175.54806641), 'rotation':(-0.750031, -179.318649, -0.769867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3467.57714844, 600.38023438, 175.69630859), 'rotation':(-0.750031, -179.319229, -0.769867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3478.9040625, 600.51300781, 175.84396484), 'rotation':(-0.744995, -179.319183, -0.764557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3484.56789062, 600.57933594, 175.91746093999998), 'rotation':(-0.744995, -179.319183, -0.764557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3490.23070312, 600.64570312, 175.99076172000002), 'rotation':(-0.741699, -179.318878, -0.761078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3507.22117188, 600.84480469, 176.20951172000002), 'rotation':(-0.736633, -179.319412, -0.755737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3512.88476562, 600.91113281, 176.28234375), 'rotation':(-0.736603, -179.319046, -0.755737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3518.54808594, 600.9730078099999, 176.35511719), 'rotation':(-0.736603, -179.319046, -0.755737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3529.8747656200003, 601.12089844, 176.49982422000002), 'rotation':(-0.729462, -179.319458, -0.748199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3546.86476562, 601.34226562, 176.71371093999997), 'rotation':(-0.717377, -179.319519, -0.735504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3558.191875, 601.4749609400001, 176.85550781), 'rotation':(-0.717346, -179.320053, -0.735504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3563.85546875, 601.5413281200001, 176.92603516), 'rotation':(-0.715179, -179.319534, -0.733215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3580.8459375, 601.7403515599999, 177.135), 'rotation':(-0.702057, -179.319855, -0.719421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3586.50929688, 601.8067578099999, 177.20378906000002), 'rotation':(-0.69751, -179.320602, -0.714661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3592.17234375, 601.8731250000001, 177.27212891), 'rotation':(-0.693298, -179.320084, -0.710236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3601.7221875, 601.98503906, 177.38640625), 'rotation':(-0.681702, -179.319611, -0.69809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3833.88351562, 611.11207031, 179.52818359), 'rotation':(0.299114, 0.28829, 0.295998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3822.53492188, 611.05535156, 179.46392577999998), 'rotation':(0.32774, 0.288599, 0.32402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3811.18773438, 610.99859375, 179.39355468999997), 'rotation':(0.370613, 0.288451, 0.36585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3805.5134375, 610.97027344, 179.35607422), 'rotation':(0.384867, 0.289325, 0.379725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3799.839375, 610.941875, 179.31707031000002), 'rotation':(0.399081, 0.289508, 0.393551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3794.16554688, 610.9134375, 179.27703125), 'rotation':(0.406198, 0.289714, 0.400467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3782.81710938, 610.85667969, 179.195), 'rotation':(0.422625, 0.289617, 0.416429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3771.46726562, 610.7999218799999, 179.10832031), 'rotation':(0.444768, 0.290647, 0.4379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3754.44726562, 610.71484375, 178.96892577999998), 'rotation':(0.477799, 0.290483, 0.469888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3743.10007812, 610.6580859400001, 178.87117188), 'rotation':(0.494369, 0.291281, 0.485887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3737.42601562, 610.6296875, 178.82138672000002), 'rotation':(0.499403, 0.290954, 0.490756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3686.36109375, 610.374375, 178.32962891), 'rotation':(0.581194, 0.29253, 0.569489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3680.68679688, 610.3460156200001, 178.27117188), 'rotation':(0.581194, 0.29253, 0.569489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3663.66429688, 610.2608593799999, 178.09085938), 'rotation':(0.609663, 0.293111, 0.596789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3652.31714844, 610.20417969, 177.96673828), 'rotation':(0.630987, 0.293383, 0.617204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3641.89722656, 610.2815625000001, 177.85113281000002), 'rotation':(0.635932, 0.293658, 0.621925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3650.68992188, 602.3035156200001, 177.94830077999998), 'rotation':(-0.635925, -179.706345, -0.650177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3658.54367188, 602.35457031, 178.03466797000002), 'rotation':(-0.630981, -179.706604, -0.64502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3664.22359375, 602.3829296900001, 178.09650391), 'rotation':(-0.623871, -179.706573, -0.637543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3669.9028125, 602.41136719, 178.15738281000003), 'rotation':(-0.623871, -179.706573, -0.637543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3698.30007812, 602.55339844, 178.44974609000002), 'rotation':(-0.574005, -179.707382, -0.585602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3703.97898438, 602.58183594, 178.50644531), 'rotation':(-0.574005, -179.707382, -0.585602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3709.6584375, 602.61023438, 178.56238281000003), 'rotation':(-0.569092, -179.707748, -0.580475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.01757812, 602.66707031, 178.67119141), 'rotation':(-0.539185, -179.708313, -0.549408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3726.69625, 602.69539062, 178.72402344), 'rotation':(-0.529327, -179.708511, -0.539154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3732.3759375, 602.72386719, 178.77583984), 'rotation':(-0.519135, -179.708694, -0.528595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.055625, 602.7523046900001, 178.82662109), 'rotation':(-0.50943, -179.708862, -0.518555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3749.41476562, 602.80902344, 178.92546875), 'rotation':(-0.494385, -179.709244, -0.50296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3760.7734375, 602.86578125, 179.02171875), 'rotation':(-0.477814, -179.709503, -0.48584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3766.45242188, 602.8942187499999, 179.068125), 'rotation':(-0.466919, -179.709702, -0.474548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3772.1315624999997, 602.92265625, 179.11318359), 'rotation':(-0.455841, -179.709869, -0.463135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3783.4909374999997, 602.97941406, 179.19966797), 'rotation':(-0.433868, -179.709518, -0.440491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.56859375, 603.14984375, 179.43365234), 'rotation':(-0.356232, -179.711044, -0.360657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3828.9275, 603.2066796900001, 179.50070312), 'rotation':(-0.327759, -179.711395, -0.331512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3834.6071875, 603.23503906, 179.53191406000002), 'rotation':(-0.313354, -179.711563, -0.316772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3840.2864062500003, 603.2634375, 179.56160156), 'rotation':(-0.299103, -179.712372, -0.302246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3992.06398438, 611.90300781, 179.79724609000002), 'rotation':(-0.150696, 0.28686, -0.151489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3986.64429688, 611.87578125, 179.81148438), 'rotation':(-0.150604, 0.287292, -0.151398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3981.22585938, 611.84871094, 179.82519531000003), 'rotation':(-0.150604, 0.287292, -0.151398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3943.29664062, 611.6590625, 179.86148438), 'rotation':(-0.012177, 0.286532, -0.012177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3932.4596874999997, 611.6049218799999, 179.85703125), 'rotation':(0.036542, 0.286565, 0.036485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3921.62351562, 611.55070312, 179.84443359), 'rotation':(0.085391, 0.286652, 0.085141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3916.20460938, 611.52363281, 179.83509766), 'rotation':(0.085391, 0.286652, 0.085141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3897.12648438, 603.4815625, 179.78667968999997), 'rotation':(-0.170654, -179.713242, -0.171661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3906.66773438, 603.59546875, 179.81388672), 'rotation':(-0.158447, -179.713028, -0.159332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3918.0207812500003, 603.6522265599999, 179.83851562), 'rotation':(-0.109589, -179.712677, -0.110016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3935.05078125, 603.73738281, 179.85867188), 'rotation':(-0.03653, -179.71344, -0.036591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3946.40304688, 603.79414062, 179.8609375), 'rotation':(-0.012177, -179.713455, -0.012177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3957.7578125, 603.85089844, 179.85683594), 'rotation':(0.024418, -179.713867, 0.024387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3963.43453125, 603.8792578099999, 179.85351562), 'rotation':(0.040298, -179.713501, 0.040232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.11132812, 603.90765625, 179.84779297), 'rotation':(0.071621, -179.713425, 0.071446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3980.463125, 603.96441406, 179.82708984), 'rotation':(0.134883, -179.713196, 0.134248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3991.8176562500003, 604.0211718799999, 179.79798828), 'rotation':(0.150592, -179.713135, 0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3997.495625, 604.04957031, 179.78304688), 'rotation':(0.150927, -179.712372, 0.150136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.97802734, 883.74267578, 171.12859375), 'rotation':(0.727101, 0.284404, 0.708813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3111.45141602, 883.71612305, 171.05867188), 'rotation':(0.727101, 0.284404, 0.708813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3105.92456055, 883.68957031, 170.98902343999998), 'rotation':(0.722081, 0.284266, 0.704051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3100.39746094, 883.66302734, 170.91972656000002), 'rotation':(0.722081, 0.284266, 0.704051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3094.87036133, 883.6365332, 170.85054688), 'rotation':(0.716917, 0.283784, 0.699132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3089.34350586, 883.60992188, 170.78164062), 'rotation':(0.714499, 0.284236, 0.696833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3083.81616211, 883.5834375, 170.7128125), 'rotation':(0.712976, 0.28357, 0.695403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3072.76245117, 883.53033203, 170.5759375), 'rotation':(0.707676, 0.283438, 0.69036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3056.18164062, 883.45074219, 170.37255859), 'rotation':(0.699726, 0.283869, 0.682786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3045.12792969, 883.39770508, 170.23822266), 'rotation':(0.694425, 0.283118, 0.677732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3039.60058594, 883.37115234, 170.17130859), 'rotation':(0.692923, 0.283646, 0.676319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3034.07397461, 883.34466797, 170.10445312), 'rotation':(0.693114, 0.283013, 0.676502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3028.54711914, 883.31811523, 170.03757812), 'rotation':(0.69308, 0.28365, 0.676474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.96606445, 883.23852539, 169.83796875), 'rotation':(0.688681, 0.283001, 0.672278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2995.38549805, 883.15893555, 169.63988281000002), 'rotation':(0.68433, 0.28312, 0.668129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2989.85888672, 883.13244141, 169.57386719), 'rotation':(0.68444, 0.283131, 0.668236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2984.33178711, 883.10589844, 169.50785156), 'rotation':(0.68444, 0.283131, 0.668236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2984.35424805, 875.22521484, 169.50765625), 'rotation':(-0.684357, -179.716873, -0.700836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2995.40795898, 875.27826172, 169.63970702999998), 'rotation':(-0.684418, -179.716476, -0.700928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.98852539, 875.35785156, 169.83779297), 'rotation':(-0.684357, -179.716873, -0.700836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.67797852, 875.54364258, 170.30507812), 'rotation':(-0.694427, -179.716263, -0.711395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3056.20483398, 875.57012695, 170.37238281), 'rotation':(-0.697083, -179.716187, -0.714203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3061.73193359, 875.59667969, 170.43990234), 'rotation':(-0.699768, -179.716736, -0.71701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3072.78564453, 875.6497168, 170.57576172), 'rotation':(-0.705017, -179.716629, -0.722534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3078.3125, 875.67626953, 170.64408203), 'rotation':(-0.707672, -179.715927, -0.725342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3089.36645508, 875.72930664, 170.78144531), 'rotation':(-0.712982, -179.715805, -0.730896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3111.47363281, 875.83740234, 171.05849609), 'rotation':(-0.722076, -179.715729, -0.740479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3122.52807617, 875.88848633, 171.19855468999998), 'rotation':(-0.727112, -179.715958, -0.745728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3171.49535156, 876.03033203, 171.83068359), 'rotation':(-0.754059, -179.714737, -0.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.01878906, 876.11707031, 171.90359375), 'rotation':(-0.754059, -179.714737, -0.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3182.54125, 876.17664062, 171.97679688), 'rotation':(-0.758179, -179.71463, -0.778442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3188.06519531, 876.203125, 172.05011718999998), 'rotation':(-0.760315, -179.715057, -0.780701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.59007812, 876.22960938, 172.12357422000002), 'rotation':(-0.762207, -179.714447, -0.782684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3210.16259766, 876.30919922, 172.34605469), 'rotation':(-0.773315, -179.714172, -0.794403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3226.73511719, 876.38878906, 172.57208984000002), 'rotation':(-0.78421, -179.714569, -0.805908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.78320312, 876.44183594, 172.72429688), 'rotation':(-0.789764, -179.713913, -0.811768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3254.35570312, 876.52136719, 172.95306641), 'rotation':(-0.793884, -179.71402, -0.816132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.4040625, 876.5744043, 173.10738281000002), 'rotation':(-0.802277, -179.713776, -0.824982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3270.92822266, 876.60095703, 173.18517577999998), 'rotation':(-0.806549, -179.713654, -0.829498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3276.45191406, 876.62744141, 173.26292969), 'rotation':(-0.806549, -179.713654, -0.829498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3287.5, 876.6805468800001, 173.41859375), 'rotation':(-0.808014, -179.713593, -0.831055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3293.02367188, 876.70703125, 173.49669922), 'rotation':(-0.811249, -179.713516, -0.834473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.54761719, 876.7335156199999, 173.57513672000002), 'rotation':(-0.814331, -179.713425, -0.837738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3315.119375, 876.82525391, 173.81226562), 'rotation':(-0.823639, -179.713135, -0.847595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3326.16748047, 876.89916992, 173.97191406000002), 'rotation':(-0.829895, -179.712952, -0.854187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.58277344, 884.66736328, 173.73326172), 'rotation':(0.823639, 0.286845, 0.800212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3304.05882812, 884.64086914, 173.65421875), 'rotation':(0.820572, 0.286767, 0.797327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3287.48730469, 884.56133789, 173.41894531000003), 'rotation':(0.811235, 0.286492, 0.788506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3281.96289062, 884.53478516, 173.34105469), 'rotation':(0.807977, 0.2864, 0.785425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.39111328, 884.45526367, 173.10773438), 'rotation':(0.806529, 0.286343, 0.784053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3259.86669922, 884.42871094, 173.0303125), 'rotation':(0.802301, 0.286222, 0.780071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3254.34253906, 884.40228516, 172.95341797), 'rotation':(0.802301, 0.286222, 0.780071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3232.24632812, 884.29608398, 172.64849609), 'rotation':(0.789782, 0.28608, 0.768218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3221.19726562, 884.2430468800001, 172.49667968999998), 'rotation':(0.784215, 0.286137, 0.762966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.67333984, 884.21649414, 172.42134765999998), 'rotation':(0.780574, 0.28534, 0.759529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3204.625, 884.16345703, 172.27183594), 'rotation':(0.773287, 0.285142, 0.752641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.57691406, 884.11041016, 172.12390625), 'rotation':(0.765849, 0.284949, 0.74557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3188.05152344, 884.0839257800001, 172.05042969), 'rotation':(0.762201, 0.285541, 0.742131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3177.00585938, 884.06366211, 171.90392577999998), 'rotation':(0.758158, 0.285367, 0.738288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3171.4821875, 884.09735352, 171.83101562), 'rotation':(0.758158, 0.285367, 0.738288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3165.95386719, 884.1073632800001, 171.75841797), 'rotation':(0.754026, 0.284658, 0.734358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3584.36058594, 885.9863867199999, 177.70615234000002), 'rotation':(0.763519, 0.285559, 0.743368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3573.0646875, 885.9321875, 177.55240234000001), 'rotation':(0.784707, 0.285751, 0.763421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3544.8259375, 885.79657227, 177.16128906000003), 'rotation':(0.80099, 0.286124, 0.778827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3539.17796875, 885.76953125, 177.08166015999998), 'rotation':(0.808264, 0.286331, 0.785705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3533.53003906, 885.74243164, 177.00164062), 'rotation':(0.808264, 0.286331, 0.785705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3522.234375, 885.68823242, 176.84044922), 'rotation':(0.819158, 0.286482, 0.795986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3516.58691406, 885.66113281, 176.75966797), 'rotation':(0.819336, 0.286487, 0.796145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3510.93871094, 885.6340332, 176.67867188), 'rotation':(0.820531, 0.287042, 0.797266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3505.29078125, 885.60693359, 176.59742188), 'rotation':(0.823284, 0.28711, 0.79988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3493.99488281, 885.55273438, 176.43410156000002), 'rotation':(0.828584, 0.287263, 0.804868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3488.3459375, 885.52789062, 176.35201172), 'rotation':(0.833911, 0.286769, 0.809891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3482.69898438, 885.49841797, 176.26966797), 'rotation':(0.836514, 0.287491, 0.812354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3454.45972656, 885.36285156, 175.85556641), 'rotation':(0.8404, 0.287634, 0.816014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3448.81175781, 885.33582031, 175.77259766), 'rotation':(0.8404, 0.287634, 0.816014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3443.1640625, 885.30865234, 175.68939453), 'rotation':(0.842777, 0.287182, 0.818249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3414.92382812, 885.1730957, 175.27271484000002), 'rotation':(0.845058, 0.287505, 0.820393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.62742188, 885.11883789, 175.10611328), 'rotation':(0.844259, 0.287386, 0.819657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3392.33128906, 885.06463867, 174.93990234), 'rotation':(0.84264, 0.287859, 0.818122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.03539062, 885.01037109, 174.77388672), 'rotation':(0.841664, 0.287499, 0.817203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3375.3871875, 884.98333984, 174.69087890999998), 'rotation':(0.841664, 0.287499, 0.817203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3364.09644531, 877.04828125, 174.52439453), 'rotation':(-0.839539, -179.712585, -0.864441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.744375, 877.07538086, 174.60738281000002), 'rotation':(-0.841766, -179.712952, -0.86676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.04078125, 877.12969727, 174.77339844), 'rotation':(-0.841797, -179.712479, -0.866791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3386.68898438, 877.15679688, 174.85640625), 'rotation':(-0.841644, -179.712494, -0.866638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3392.33691406, 877.18383789, 174.93941406000002), 'rotation':(-0.841797, -179.712479, -0.866791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3397.98511719, 877.21099609, 175.02248047), 'rotation':(-0.842621, -179.712646, -0.867676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3426.22582031, 877.3465625, 175.43892577999998), 'rotation':(-0.845093, -179.712479, -0.8703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.87402344, 877.37359375, 175.52224609), 'rotation':(-0.845184, -179.712479, -0.870392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3437.52171875, 877.40069336, 175.60556641), 'rotation':(-0.845184, -179.712479, -0.870392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3460.11402344, 877.50921875, 175.93798827999998), 'rotation':(-0.840424, -179.712936, -0.865387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3471.41039062, 877.56341797, 176.10375), 'rotation':(-0.840393, -179.712952, -0.865326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3482.70628906, 877.61767578, 176.26921875), 'rotation':(-0.838989, -179.712433, -0.863831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3494.00195312, 877.67181641, 176.43365234), 'rotation':(-0.831055, -179.712662, -0.855438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3505.29808594, 877.72601562, 176.59699218999998), 'rotation':(-0.825775, -179.712814, -0.849854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3533.53859375, 877.8943457, 177.00123047), 'rotation':(-0.815552, -179.71347, -0.83902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3539.18628906, 877.92175781, 177.08125), 'rotation':(-0.815552, -179.71347, -0.83902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3544.83445312, 877.94884766, 177.16087890999998), 'rotation':(-0.808258, -179.713669, -0.831329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3567.42726562, 878.05731445, 177.47443359000002), 'rotation':(-0.789917, -179.713989, -0.81192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3573.07542969, 878.08447266, 177.55203125), 'rotation':(-0.789917, -179.713989, -0.81192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3578.72363281, 878.11157227, 177.62939452999998), 'rotation':(-0.784698, -179.714249, -0.806427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3590.01953125, 878.16571289, 177.78181641), 'rotation':(-0.774109, -179.714539, -0.795258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3601.3159375, 878.2199707, 177.93167968999998), 'rotation':(-0.763519, -179.714828, -0.784058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3633.7478125, 878.38910156, 178.34972656000002), 'rotation':(-0.723358, -179.5746, -0.741821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3639.40332031, 878.43017578, 178.42015625), 'rotation':(-0.710693, -179.574905, -0.728516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3645.0590625, 878.47125, 178.48978516), 'rotation':(-0.710693, -179.574905, -0.728516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3656.37039062, 878.5534668, 178.62628906), 'rotation':(-0.685638, -179.575516, -0.702179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3662.025625, 878.59454102, 178.69349609), 'rotation':(-0.685638, -179.575516, -0.702179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3678.99195312, 878.71783203, 178.89191406), 'rotation':(-0.669067, -179.575806, -0.684845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3684.64820312, 878.75897461, 178.95595702999998), 'rotation':(-0.648621, -179.576294, -0.663422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3690.3025, 878.80004883, 179.01882812), 'rotation':(-0.648621, -179.576294, -0.663422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3695.95875, 878.84112305, 179.08083984), 'rotation':(-0.628113, -179.577103, -0.642029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3701.61421875, 878.88220703, 179.14123047), 'rotation':(-0.628113, -179.577103, -0.642029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3707.26953125, 878.92322266, 179.20119140999998), 'rotation':(-0.607635, -179.577179, -0.620667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.54757812, 879.12866211, 179.48691406), 'rotation':(-0.559784, -179.578293, -0.570801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3763.82765625, 879.33410156, 179.73992188), 'rotation':(-0.497101, -179.579605, -0.505768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3786.44992188, 879.49841797, 179.92333984), 'rotation':(-0.458832, -179.579758, -0.466217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3797.7621875, 879.580625, 180.00603515999998), 'rotation':(-0.407715, -179.580902, -0.413544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3831.6965625000003, 879.82703125, 180.21734375), 'rotation':(-0.295532, -179.58226, -0.298584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3843.00851562, 879.90917969, 180.26982422), 'rotation':(-0.251404, -179.582687, -0.253601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3859.97703125, 880.0324707, 180.33554688), 'rotation':(-0.21817, -179.582733, -0.219849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3848.61328125, 887.83056641, 180.29251953), 'rotation':(0.21817, 0.417245, 0.216519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3842.95945312, 887.78949219, 180.26986327999998), 'rotation':(0.229248, 0.41712, 0.227421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3831.64773438, 887.70733398, 180.21738281), 'rotation':(0.273371, 0.41751, 0.270779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3825.99515625, 887.66625977, 180.18763672), 'rotation':(0.295529, 0.418402, 0.292491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3814.68382812, 887.58422852, 180.12105469), 'rotation':(0.339658, 0.418222, 0.335648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3809.0278125, 887.54308594, 180.08421875), 'rotation':(0.383959, 0.418781, 0.378838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3792.06203125, 887.4198632800001, 179.96585938), 'rotation':(0.407701, 0.419069, 0.401937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3786.40671875, 887.37878906, 179.92345702999998), 'rotation':(0.433218, 0.419841, 0.426702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3780.7534375, 887.33770508, 179.88007812), 'rotation':(0.433218, 0.419841, 0.426702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3775.09695312, 887.29675781, 179.83478516), 'rotation':(0.458818, 0.419855, 0.451511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3758.1328125, 887.17279297, 179.69099609), 'rotation':(0.497115, 0.421048, 0.488538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3746.819375, 887.09130859, 179.59140625), 'rotation':(0.509648, 0.420774, 0.500645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3741.1640625, 887.05023438, 179.53990234), 'rotation':(0.509648, 0.420774, 0.500645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.5078125, 887.00916016, 179.48710938), 'rotation':(0.534756, 0.42122, 0.524844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3729.85476562, 886.96807617, 179.43224609), 'rotation':(0.559789, 0.42171, 0.548931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3724.19945312, 886.92700195, 179.37654297), 'rotation':(0.559789, 0.42171, 0.548931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3701.578125, 886.76269531, 179.14146484), 'rotation':(0.607668, 0.422824, 0.594876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3684.61375, 886.63946289, 178.95621093999998), 'rotation':(0.628118, 0.423252, 0.614472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3673.3025, 886.55731445, 178.82679688), 'rotation':(0.648595, 0.42371, 0.634043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3656.338125, 886.43408203, 178.62658202999998), 'rotation':(0.679331, 0.424664, 0.66336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3639.37132812, 886.31084961, 178.42048828), 'rotation':(0.698168, 0.424781, 0.681305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2657.98804688, 1997.5484375, 173.39988281), 'rotation':(-0.51413, -89.364227, -0.523407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.23535156, 1975.071875, 173.195625), 'rotation':(-0.557159, -89.364502, -0.568085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.42089844, 1958.21726562, 173.02904297), 'rotation':(-0.612183, -89.361938, -0.625397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2658.5446875, 1946.97953125, 172.91070312), 'rotation':(-0.625946, -89.362183, -0.63974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.60667969, 1941.36171875, 172.84988281000003), 'rotation':(-0.625946, -89.362183, -0.63974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.35472656, 1975.02585938, 173.19599609), 'rotation':(0.529599, 90.636398, 0.519869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.54078125, 1958.15625, 173.02929688), 'rotation':(0.584637, 90.637482, 0.572799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.66453125, 1946.90835938, 172.91087890999998), 'rotation':(0.612203, 90.638031, 0.599226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2650.7263281200003, 1941.2853125000001, 172.85), 'rotation':(0.612203, 90.638031, 0.599226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.85035156, 1930.03625, 172.72708984000002), 'rotation':(0.625959, 90.637817, 0.612386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2651.24804688, 1890.78039062, 172.29810547), 'rotation':(0.625959, 90.637497, 0.612402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2651.63914062, 1858.41890625, 171.9378125), 'rotation':(0.646955, 90.638519, 0.632476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2651.76195312, 1847.25695312, 171.80992188), 'rotation':(0.65548, 90.638702, 0.640619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.2732031200003, 1880.8288281199998, 172.18789062), 'rotation':(-0.638611, -89.361664, -0.652985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.33472656, 1875.24734375, 172.12605469), 'rotation':(-0.638611, -89.361664, -0.652985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2659.39625, 1869.66554688, 172.06382812), 'rotation':(-0.646973, -89.361481, -0.661682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.51929688, 1858.50257812, 171.93777343999997), 'rotation':(-0.655487, -89.361267, -0.670624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.58082031, 1852.92078125, 171.87390625), 'rotation':(-0.659668, -89.361511, -0.675018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.64234375, 1847.3400000000001, 171.80988281), 'rotation':(-0.659668, -89.361511, -0.675018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.36570312, 1792.4646093800002, 171.17064453), 'rotation':(0.676448, 90.639359, 0.660621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.42726562, 1786.8784375, 171.10460938), 'rotation':(0.677425, 90.639389, 0.661546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2652.48875, 1781.2922656199999, 171.03849609), 'rotation':(0.678204, 90.636856, 0.662284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.67335938, 1764.53390625, 170.83966797000002), 'rotation':(0.680772, 90.639473, 0.664746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.79640625, 1753.36171875, 170.70667969), 'rotation':(0.682513, 90.639519, 0.666401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2660.55371094, 1764.6109375, 170.83955078), 'rotation':(-0.681732, -89.360474, -0.69812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2660.61523438, 1759.02453125, 170.77308594), 'rotation':(-0.682526, -89.360474, -0.698944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2660.73828125, 1747.8517187500001, 170.63996093999998), 'rotation':(-0.682983, -89.361359, -0.699432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2653.31664062, 1692.9871875, 169.98943359), 'rotation':(0.678511, 90.639366, 0.662596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2653.74535156, 1654.06398438, 169.53318359000002), 'rotation':(0.667309, 90.638451, 0.651894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2654.01269531, 1642.94410156, 169.40439453), 'rotation':(0.661538, 90.638504, 0.646392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2654.19628906, 1626.26269531, 169.21396484000002), 'rotation':(0.649783, 90.638245, 0.635175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2654.44140625, 1604.02, 168.965), 'rotation':(0.635884, 90.638145, 0.621897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2654.51953125, 1598.4635156200002, 168.90353516), 'rotation':(0.631608, 90.756744, 0.617796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2654.63160156, 1592.9175, 168.84263672), 'rotation':(0.627018, 91.223045, 0.613397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2654.93238281, 1581.8284765600001, 168.725), 'rotation':(0.591303, 92.125046, 0.579194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2661.37351562, 1690.1784375, 169.95511718999998), 'rotation':(-0.677124, -89.362183, -0.693298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2661.59546875, 1670.853125, 169.7278125), 'rotation':(-0.668732, -89.359924, -0.684479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2661.68554688, 1665.296875, 169.66298827999998), 'rotation':(-0.66745, -89.361542, -0.683136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2661.76683594, 1659.740625, 169.59826172), 'rotation':(-0.667297, -89.361542, -0.682983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.03710938, 1643.07128906, 169.40482422000002), 'rotation':(-0.657532, -89.359192, -0.67276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.09839844, 1637.51464844, 169.34105469), 'rotation':(-0.653656, -89.361664, -0.668701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.1596875, 1631.95777344, 169.27761718999997), 'rotation':(-0.64978, -89.361755, -0.664642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2662.28199219, 1620.8441015600001, 169.15181640999998), 'rotation':(-0.641907, -89.361938, -0.656403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2662.46558594, 1604.16980469, 168.96566406000002), 'rotation':(-0.640747, -89.24469, -0.655182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.65699219, 1593.03125, 168.84179688), 'rotation':(-0.627075, -88.554443, -0.64093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.90820312, 1581.88769531, 168.72255859), 'rotation':(-0.590851, -87.64798, -0.603149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2657.60863281, 1538.18566406, 168.30095702999998), 'rotation':(0.522011, 94.949226, 0.512569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.8278906200003, 1527.1328125, 168.20363281000002), 'rotation':(0.493304, 95.746567, 0.484876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2660.05371094, 1516.06921875, 168.11158203), 'rotation':(0.464391, 96.545189, 0.456912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2662.17359375, 1499.49757812, 167.97902344), 'rotation':(0.441551, 97.754501, 0.434789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.95433594, 1493.9715625, 167.93691406000002), 'rotation':(0.429469, 98.090187, 0.42306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2663.775625, 1488.45777344, 167.89638672), 'rotation':(0.417345, 98.422806, 0.411304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2665.52660156, 1477.44910156, 167.81933593999997), 'rotation':(0.392975, 99.092636, 0.387607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2667.41945312, 1466.47523438, 167.74738281), 'rotation':(0.362594, 100.04805, 0.358021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2668.42261719, 1461.004375, 167.71207031000003), 'rotation':(0.362854, 100.524345, 0.358279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2671.51125, 1444.59886719, 167.61119141), 'rotation':(0.333081, 101.443039, 0.32923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2665.65578125, 1538.65320312, 168.29863281000002), 'rotation':(-0.519867, -84.786316, -0.529358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2666.29027344, 1533.1139062500001, 168.24871094), 'rotation':(-0.500427, -84.251953, -0.509216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2666.8515625, 1527.57152344, 168.20029297000002), 'rotation':(-0.490723, -83.988129, -0.499207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2667.44921875, 1522.02492188, 168.153125), 'rotation':(-0.4711, -83.456696, -0.478912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2668.76125, 1510.9420312500001, 168.06193359), 'rotation':(-0.460205, -82.579346, -0.467651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2670.22144531, 1499.87597656, 167.97333984), 'rotation':(-0.435638, -81.91098, -0.442322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2671.01074219, 1494.35375, 167.93119141), 'rotation':(-0.42337, -81.576233, -0.429657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2671.83691406, 1488.83726562, 167.89042969), 'rotation':(-0.411102, -81.241302, -0.417023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2673.60082031, 1477.81433594, 167.81289062), 'rotation':(-0.374054, -80.237488, -0.378998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2675.50976562, 1466.83789062, 167.74050781000003), 'rotation':(-0.367828, -79.713104, -0.372559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2678.5134375, 1450.41039062, 167.63578125), 'rotation':(-0.337891, -78.555267, -0.341888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2679.63623047, 1444.95386719, 167.60392578), 'rotation':(-0.297852, -77.80307, -0.300964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2680.23902344, 1407.58070312, 167.43222656), 'rotation':(0.24726, 104.251015, 0.245134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2681.49339844, 1402.17726562, 167.40863281000003), 'rotation':(0.243182, 104.565308, 0.241121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2685.70751953, 1386.02882812, 167.34003906), 'rotation':(0.229474, 104.122993, 0.227657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.04492188, 1380.61742188, 167.31804688), 'rotation':(0.226223, 103.866447, 0.224442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2690.82445312, 1364.31066406, 167.25443359000002), 'rotation':(0.216749, 102.621918, 0.21511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2693.14820312, 1353.39257812, 167.21167968999998), 'rotation':(0.221687, 101.723366, 0.219983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2696.33226562, 1336.96851562, 167.14595702999998), 'rotation':(0.228654, 100.377701, 0.226834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.29613281, 1320.53455078, 167.07851562), 'rotation':(0.23418, 99.284912, 0.232266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2700.15576172, 1315.04601562, 167.05591797), 'rotation':(0.233729, 98.991104, 0.231827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2700.97582031, 1309.55333984, 167.0334375), 'rotation':(0.232732, 98.591545, 0.230846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2688.40429688, 1408.05628906, 167.42546875), 'rotation':(-0.246704, -75.434692, -0.24881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2689.81957031, 1402.65589844, 167.40160156000002), 'rotation':(-0.242554, -75.125031, -0.244629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2693.87085938, 1386.46886719, 167.33388672), 'rotation':(-0.222839, -76.134827, -0.224548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2695.19238281, 1381.06898438, 167.31236328), 'rotation':(-0.216614, -76.65271, -0.218262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2697.72730469, 1370.22816406, 167.27052734), 'rotation':(-0.21347, -77.378998, -0.215088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2700.10328125, 1359.35460938, 167.22863281000002), 'rotation':(-0.218353, -78.273926, -0.220001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2702.3259375, 1348.4444531200002, 167.18589844), 'rotation':(-0.221771, -78.946472, -0.223511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2703.37816406, 1342.98390625, 167.16423827999998), 'rotation':(-0.22406, -79.394104, -0.22583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2704.39039062, 1337.5184375, 167.14240234000002), 'rotation':(-0.226624, -79.840851, -0.228424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2705.50488281, 1332.07347656, 167.12033203), 'rotation':(-0.228943, -80.291748, -0.230774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2707.32910156, 1321.1173046899999, 167.07570312), 'rotation':(-0.230194, -81.01004, -0.232056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.18285156, 1315.63757812, 167.05339844), 'rotation':(-0.229218, -81.406128, -0.231079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.99683594, 1310.15710938, 167.03121094), 'rotation':(-0.228271, -81.806732, -0.230103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.52808594, 1087.62255859, 166.26625), 'rotation':(0.1125, 89.771744, 0.112064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.56396484, 1116.73583984, 166.32873047), 'rotation':(0.140483, 89.771873, 0.139797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.5859375, 1122.2800293, 166.34253906), 'rotation':(0.147546, 89.771904, 0.146793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.60816406, 1127.82433594, 166.35693359), 'rotation':(0.154608, 89.769646, 0.15378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.630625, 1133.36853516, 166.37195312), 'rotation':(0.161391, 89.771988, 0.160488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.65257812, 1138.9123535200001, 166.38757812), 'rotation':(0.165031, 89.770851, 0.164081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.69703125, 1150.0, 166.42007812), 'rotation':(0.183281, 89.769508, 0.18211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.71923828, 1155.54443359, 166.43720703), 'rotation':(0.183281, 89.769508, 0.18211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.74169922, 1161.10058594, 166.455), 'rotation':(0.195589, 89.771301, 0.194264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.76390625, 1166.63257812, 166.47386719), 'rotation':(0.207692, 89.771378, 0.206193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.80835938, 1177.72130859, 166.51351562), 'rotation':(0.213744, 89.772438, 0.212157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.8303125, 1183.26488281, 166.53421875), 'rotation':(0.213901, 89.769814, 0.212309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.85277344, 1188.80859375, 166.55490234), 'rotation':(0.215014, 89.77092, 0.213419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.88232422, 1199.92785156, 166.59691406000002), 'rotation':(0.220192, 90.21286, 0.218511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.85009766, 1205.50304688, 166.61833984), 'rotation':(0.223053, 90.803055, 0.221337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.78076172, 1211.06921875, 166.63994141), 'rotation':(0.224618, 91.09996, 0.222858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.66722656, 1216.64697266, 166.66179688), 'rotation':(0.226161, 91.393372, 0.224386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.32398438, 1227.7940625, 166.70603516), 'rotation':(0.229727, 92.27668, 0.227892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.09033203, 1233.3631640600001, 166.72833984000002), 'rotation':(0.229535, 92.900681, 0.227696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2707.15429688, 1250.03710938, 166.79501953), 'rotation':(0.22862, 93.989197, 0.226813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2705.85693359, 1266.64234375, 166.86123047), 'rotation':(0.22791, 95.079163, 0.226116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2705.3459375, 1272.17150391, 166.88328125), 'rotation':(0.227507, 95.764717, 0.225716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2714.06787109, 1266.54455078, 166.85802734), 'rotation':(-0.22467, -85.283783, -0.22644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2714.53199219, 1261.03980469, 166.83632812), 'rotation':(-0.225006, -85.649139, -0.226776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2715.20068359, 1249.99767578, 166.79275391), 'rotation':(-0.225555, -86.376617, -0.227325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2715.85277344, 1238.93994141, 166.74900391), 'rotation':(-0.226074, -87.103577, -0.227844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.12207031, 1233.4034375, 166.72707031000002), 'rotation':(-0.226288, -87.428162, -0.228058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.54125, 1222.32384766, 166.68326172000002), 'rotation':(-0.22406, -88.310822, -0.2258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.80445312, 1211.23498047, 166.64005859), 'rotation':(-0.219727, -89.195129, -0.221405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.87402344, 1205.6873828100001, 166.61875), 'rotation':(-0.218414, -89.490997, -0.220062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.90673828, 1200.14917969, 166.59769531), 'rotation':(-0.215576, -90.082733, -0.217194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.90087891, 1194.59546875, 166.57675781), 'rotation':(-0.215027, -90.229065, -0.216644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.85644531, 1183.49353516, 166.53519531), 'rotation':(-0.213745, -90.230164, -0.215332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.83421875, 1177.94238281, 166.51447266), 'rotation':(-0.207703, -90.228607, -0.209198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.78980469, 1166.83875, 166.4746875), 'rotation':(-0.195587, -90.228699, -0.19693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.76757812, 1161.28759766, 166.45574219), 'rotation':(-0.183289, -90.22879, -0.184448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.74535156, 1155.73632812, 166.43792968999998), 'rotation':(-0.171143, -90.228851, -0.17218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.72314453, 1150.18494141, 166.42072266), 'rotation':(-0.171143, -90.228851, -0.17218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.82324219, 1139.0809375, 166.38814452999998), 'rotation':(-0.161407, -90.230316, -0.162292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.734375, 1116.87475586, 166.32916016), 'rotation':(-0.133545, -90.228149, -0.134186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.68994141, 1105.77160156, 166.30333984), 'rotation':(-0.126465, -90.230469, -0.127045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.66773438, 1100.2199707, 166.29136719), 'rotation':(-0.119568, -90.22821, -0.120056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.64574219, 1094.66833984, 166.28), 'rotation':(-0.112488, -90.23056, -0.112946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3303.86207031, 1719.37109375, 175.34667968999997), 'rotation':(-0.250671, -179.462601, -0.252869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3314.95824219, 1719.47484375, 175.39439453), 'rotation':(-0.246277, -179.462631, -0.248413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3320.50634766, 1719.5267187499999, 175.41783203), 'rotation':(-0.242035, -179.462708, -0.24408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3326.0546875, 1719.5787500000001, 175.44105469), 'rotation':(-0.239868, -179.462769, -0.241882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3331.60230469, 1719.630625, 175.46421875), 'rotation':(-0.239868, -179.462769, -0.241882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3337.15039062, 1719.6825, 175.48707031), 'rotation':(-0.237671, -179.462952, -0.239655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3342.69824219, 1719.7345312500001, 175.50953125), 'rotation':(-0.233459, -179.462997, -0.235382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.2465625, 1719.78640625, 175.53152343999997), 'rotation':(-0.229218, -179.463043, -0.231079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3359.34253906, 1719.89015625, 175.57427734), 'rotation':(-0.216431, -179.463135, -0.218079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3364.8908593799997, 1719.9420312500001, 175.59501953), 'rotation':(-0.212189, -179.46315, -0.213776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3375.9865625, 1720.0459375, 175.63533203), 'rotation':(-0.207825, -179.463211, -0.20932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.53492188, 1720.0978125000001, 175.65525391), 'rotation':(-0.205719, -179.462799, -0.207214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3392.63109375, 1720.20164062, 175.69464843999998), 'rotation':(-0.201569, -179.463028, -0.203003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.72703125, 1720.3053906199998, 175.73183594), 'rotation':(-0.193146, -179.463089, -0.194458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3409.27492188, 1720.35742188, 175.74955078), 'rotation':(-0.184967, -179.463135, -0.186188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.4665625, 1720.56484375, 175.81650391), 'rotation':(-0.172546, -179.463776, -0.173584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3437.01488281, 1720.61671875, 175.83246093999998), 'rotation':(-0.164642, -179.463058, -0.165588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3442.5627343799997, 1720.6685937500001, 175.84742188), 'rotation':(-0.164642, -179.463058, -0.165588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3459.20582031, 1720.8243750000001, 175.8875), 'rotation':(-0.133453, -179.463257, -0.134094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3481.32496094, 1729.04164062, 175.93125), 'rotation':(0.109925, 0.53635, 0.109512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3459.13328125, 1728.70445312, 175.8875), 'rotation':(0.117821, 0.535945, 0.117341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.39453125, 1728.44484375, 175.81652343999997), 'rotation':(0.164649, 0.536925, 0.163704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3414.75121094, 1728.2890625, 175.76666016), 'rotation':(0.172408, 0.537167, 0.171375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.65503906, 1728.18554688, 175.73183594), 'rotation':(0.184968, 0.535885, 0.183792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3398.1071875, 1728.13367188, 175.71353516), 'rotation':(0.184968, 0.535885, 0.183792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.463125, 1727.97789062, 175.65525391), 'rotation':(0.205725, 0.537186, 0.204257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3370.3671875, 1727.87414062, 175.61533203), 'rotation':(0.205725, 0.536172, 0.204257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3364.81933594, 1727.82210938, 175.59503906), 'rotation':(0.207808, 0.536776, 0.206318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3359.27101562, 1727.7702343800001, 175.57427734), 'rotation':(0.2122, 0.538132, 0.21064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3353.72289062, 1727.71835938, 175.553125), 'rotation':(0.220636, 0.536873, 0.218942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.17503906, 1727.66640625, 175.53152343999997), 'rotation':(0.22485, 0.536931, 0.223101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3342.62671875, 1727.61453125, 175.50953125), 'rotation':(0.229228, 0.53694, 0.227404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3337.07859375, 1727.5626562500001, 175.48708984), 'rotation':(0.233456, 0.537, 0.231562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3325.98316406, 1727.45875, 175.44107422000002), 'rotation':(0.237663, 0.537008, 0.235706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.33886719, 1727.30296875, 175.37068359), 'rotation':(0.242028, 0.536377, 0.239982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3260.17261719, 1726.84289062, 175.14992188), 'rotation':(0.26273, 0.537204, 0.26034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3254.60277344, 1726.79085938, 175.12402343999997), 'rotation':(0.266268, 0.537223, 0.263802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3249.03320312, 1726.73875, 175.09789062), 'rotation':(0.270072, 0.537272, 0.267539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3243.463125, 1726.68664062, 175.07148438000002), 'rotation':(0.270072, 0.537272, 0.267539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3232.32398438, 1726.58242188, 175.01808594), 'rotation':(0.275571, 0.537019, 0.272927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3210.0446875, 1726.37390625, 174.91041016), 'rotation':(0.279403, 0.537784, 0.276687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3204.47509766, 1726.32179688, 174.88314452999998), 'rotation':(0.281131, 0.537799, 0.27838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.90527344, 1726.2696875000001, 174.85570312), 'rotation':(0.28251, 0.537813, 0.279732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3187.765625, 1726.16554688, 174.80029297000002), 'rotation':(0.285775, 0.537847, 0.282938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3176.62646484, 1726.06125, 174.74431640999998), 'rotation':(0.288056, 0.53746, 0.285173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3260.24658203, 1718.96289062, 175.14992188), 'rotation':(-0.266266, -179.462769, -0.268768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3249.1071875, 1718.8586718800002, 175.09789062), 'rotation':(-0.273621, -179.462692, -0.276245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3243.53710938, 1718.80648438, 175.07148438000002), 'rotation':(-0.273621, -179.462692, -0.276245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3232.39794922, 1718.70226562, 175.01808594), 'rotation':(-0.275482, -179.462036, -0.278107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3221.25830078, 1718.59804688, 174.96445312), 'rotation':(-0.277863, -179.462234, -0.280548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.97875, 1718.38953125, 174.85568359), 'rotation':(-0.284241, -179.462158, -0.287048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.40917969, 1718.33742188, 174.82808594), 'rotation':(-0.285767, -179.462143, -0.288635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.83910156, 1718.2853906199998, 174.80029297000002), 'rotation':(-0.287323, -179.462128, -0.290222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3176.69996094, 1718.18117188, 174.74431640999998), 'rotation':(-0.289154, -179.462585, -0.292053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.06518555, 1725.75671875, 174.57759765999998), 'rotation':(0.297878, 0.537778, 0.294799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3127.31494141, 1725.6, 174.48982422), 'rotation':(0.300699, 0.537794, 0.297556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3121.73144531, 1725.54773438, 174.46039062), 'rotation':(0.302154, 0.537365, 0.298973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3104.98120117, 1725.39101562, 174.37181640999998), 'rotation':(0.304756, 0.53685, 0.301541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3144.13867188, 1717.8765625, 174.57759765999998), 'rotation':(-0.30069, -179.462921, -0.303864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3138.55517578, 1717.8243750000001, 174.54849609000001), 'rotation':(-0.30069, -179.462921, -0.303864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3127.38842773, 1717.72, 174.48982422), 'rotation':(-0.302155, -179.461929, -0.305359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3121.80493164, 1717.6677343800002, 174.46039062), 'rotation':(-0.302063, -179.462616, -0.305267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3105.0546875, 1717.51085938, 174.37181640999998), 'rotation':(-0.309845, -179.461807, -0.313202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3088.3046875, 1717.35414062, 174.28072265999998), 'rotation':(-0.312378, -179.461899, -0.315796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3077.13818359, 1717.2497656199998, 174.21980469), 'rotation':(-0.314209, -179.461517, -0.317657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.14624023, 1716.9971875, 174.06888672000002), 'rotation':(-0.329193, -179.461578, -0.333008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.0402832, 1716.89320312, 174.00472656000002), 'rotation':(-0.335999, -179.461472, -0.339966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3027.93432617, 1716.7892968800002, 173.93955078), 'rotation':(-0.339569, -179.462616, -0.343597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.27587891, 1716.6334375000001, 173.83996093999997), 'rotation':(-0.350555, -179.461105, -0.354858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2994.6171875, 1716.4775, 173.73689453), 'rotation':(-0.361542, -179.462311, -0.366119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2989.06420898, 1716.4255468800002, 173.70175781), 'rotation':(-0.365295, -179.460922, -0.369995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2983.51196289, 1716.37367188, 173.66630859), 'rotation':(-0.367218, -179.461258, -0.371918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2977.95996094, 1716.32164062, 173.63070312), 'rotation':(-0.370117, -179.461975, -0.374939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2972.40698242, 1716.2696875000001, 173.59482422000002), 'rotation':(-0.376099, -179.461884, -0.381042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2966.85424805, 1716.2178125, 173.55835938), 'rotation':(-0.382019, -179.460571, -0.387177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2955.7487793, 1716.11375, 173.48367188), 'rotation':(-0.394165, -179.461655, -0.399597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2950.19604492, 1716.0618749999999, 173.44546875), 'rotation':(-0.399963, -179.460312, -0.405579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2939.09033203, 1715.95796875, 173.36728516), 'rotation':(-0.412079, -179.460144, -0.41803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2922.43261719, 1715.80226562, 173.24693359), 'rotation':(-0.4216, -179.460236, -0.427826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2911.32861328, 1715.69835938, 173.16496094), 'rotation':(-0.434875, -179.46109, -0.441498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2900.22363281, 1715.59421875, 173.07890625), 'rotation':(-0.461609, -179.45961, -0.469116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3038.96630859, 1724.7732812499999, 174.00472656000002), 'rotation':(0.332678, 0.537367, 0.328834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3033.41333008, 1724.72132812, 173.97222656000002), 'rotation':(0.336025, 0.538516, 0.33209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3011.20214844, 1724.51351562, 173.83994141), 'rotation':(0.346953, 0.53885, 0.342764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3000.09619141, 1724.4096875, 173.77166015999998), 'rotation':(0.354343, 0.538965, 0.349982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2994.54345703, 1724.35765625, 173.73689453), 'rotation':(0.357916, 0.537612, 0.353479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2988.99047852, 1724.305625, 173.70175781), 'rotation':(0.361549, 0.539057, 0.357005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2977.88623047, 1724.20179688, 173.63070312), 'rotation':(0.367191, 0.53874, 0.362515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.33325195, 1724.14976562, 173.59482422000002), 'rotation':(0.370121, 0.538035, 0.365354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2966.78051758, 1724.0978906199998, 173.55835938), 'rotation':(0.376084, 0.53937, 0.371171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2961.2277832, 1724.0459375, 173.52130859000002), 'rotation':(0.382047, 0.538169, 0.376969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2955.67504883, 1723.99390625, 173.48367188), 'rotation':(0.388023, 0.538267, 0.382809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2950.12231445, 1723.9420312500001, 173.44546875), 'rotation':(0.394157, 0.539611, 0.388765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2944.56933594, 1723.8899999999999, 173.40666016), 'rotation':(0.399976, 0.538435, 0.394417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2939.01660156, 1723.83804688, 173.36730468999997), 'rotation':(0.405945, 0.539775, 0.400226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2927.91186523, 1723.7342187499999, 173.28714843999998), 'rotation':(0.414995, 0.538824, 0.409016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2916.80737305, 1723.63039062, 173.20634766), 'rotation':(0.414995, 0.538824, 0.409016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2905.70239258, 1723.52648438, 173.12248047), 'rotation':(0.434858, 0.538896, 0.428302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2673.49316406, 1721.354375, 170.52980469), 'rotation':(0.879366, 0.549396, 0.852677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2679.03929688, 1721.4060937499999, 170.61496093999997), 'rotation':(0.879366, 0.549396, 0.852677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2690.13011719, 1721.51015625, 170.78441406000002), 'rotation':(0.852046, 0.549517, 0.826983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2701.22144531, 1721.61375, 170.94816406), 'rotation':(0.815777, 0.547279, 0.792781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2706.76734375, 1721.66554688, 171.02751952999998), 'rotation':(0.797349, 0.547939, 0.775394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.31078125, 1721.71742188, 171.10513672000002), 'rotation':(0.779284, 0.546237, 0.758289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2723.40234375, 1721.8210156199998, 171.25541016), 'rotation':(0.742838, 0.545291, 0.723761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2756.67822266, 1722.13242188, 171.67710938), 'rotation':(0.675308, 0.544306, 0.659536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2762.22314453, 1722.1842968800001, 171.74308594), 'rotation':(0.675308, 0.544306, 0.659536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2767.76904297, 1722.23609375, 171.80824219), 'rotation':(0.652017, 0.542997, 0.637301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2784.4084375, 1722.391875, 171.99599609), 'rotation':(0.634415, 0.543445, 0.620472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2801.04736328, 1722.5475000000001, 172.17761718999998), 'rotation':(0.599083, 0.542682, 0.586652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2812.14039062, 1722.65140625, 172.29283203), 'rotation':(0.57532, 0.540874, 0.563843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2828.77929688, 1722.81015625, 172.45666015999998), 'rotation':(0.545958, 0.541525, 0.535627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2845.41992188, 1722.9728906199998, 172.61414062), 'rotation':(0.522318, 0.541126, 0.512858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2856.51293945, 1723.04148438, 172.71451172000002), 'rotation':(0.50652, 0.540843, 0.497624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.05957031, 1723.08546875, 172.76349609000002), 'rotation':(0.490838, 0.539715, 0.482478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2867.60668945, 1723.13710938, 172.81099609), 'rotation':(0.479384, 0.539825, 0.471419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2862.15161133, 1715.2380468800002, 172.76363281000002), 'rotation':(-0.506531, -179.459152, -0.515533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2851.05859375, 1715.134375, 172.66488281000002), 'rotation':(-0.522308, -179.459732, -0.531921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2839.96508789, 1715.0306249999999, 172.56220703), 'rotation':(-0.545959, -179.458466, -0.556427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2834.41943359, 1714.97875, 172.50972656000002), 'rotation':(-0.545959, -179.458466, -0.556427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2828.87255859, 1714.926875, 172.45685547000002), 'rotation':(-0.55191, -179.458237, -0.562592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2817.78076172, 1714.82296875, 172.34886719), 'rotation':(-0.575317, -179.457794, -0.586945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2812.23414062, 1714.77109375, 172.29302734), 'rotation':(-0.587219, -179.457535, -0.599365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2806.68945312, 1714.71921875, 172.23603516), 'rotation':(-0.599091, -179.457306, -0.611725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2795.59667969, 1714.61546875, 172.1184375), 'rotation':(-0.622528, -179.456802, -0.636169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2778.95800781, 1714.46, 171.93423828), 'rotation':(-0.652008, -179.456223, -0.666992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2773.41285156, 1714.40804688, 171.87164062), 'rotation':(-0.652008, -179.456223, -0.666992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2751.22998047, 1714.20046875, 171.60974609000002), 'rotation':(-0.721985, -179.454529, -0.740387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2740.13769531, 1714.09671875, 171.47076172), 'rotation':(-0.733704, -179.454376, -0.752686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2729.04859375, 1713.9928906199998, 171.32835938), 'rotation':(-0.742859, -179.454697, -0.762299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2723.50269531, 1713.9411718800002, 171.25576172), 'rotation':(-0.761047, -179.454254, -0.781464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2701.32421875, 1713.73351562, 170.94859375), 'rotation':(-0.833801, -179.452209, -0.858368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2695.77832031, 1713.68148438, 170.86757812), 'rotation':(-0.852051, -179.451675, -0.877686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2690.23265625, 1713.62984375, 170.78486328), 'rotation':(-0.8703, -179.449936, -0.897034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2684.68945312, 1713.5779687499999, 170.70058594), 'rotation':(-0.879364, -179.450607, -0.906708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2673.59691406, 1713.47414062, 170.53025391), 'rotation':(-0.879456, -179.450623, -0.906769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2641.04589844, 1721.05078125, 170.03162109000002), 'rotation':(0.879394, 0.550136, 0.8527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2635.51855469, 1720.99914062, 169.94673827999998), 'rotation':(0.879359, 0.549082, 0.852667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2624.46726562, 1720.89578125, 169.77175781000003), 'rotation':(0.939875, 0.550869, 0.909411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2618.94410156, 1720.84414062, 169.67908203), 'rotation':(0.980084, 0.553436, 0.94697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2591.32300781, 1720.5859375, 169.15949218999998), 'rotation':(1.141167, 0.559406, 1.096362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2574.74683594, 1720.4309375, 168.81257812), 'rotation':(1.205057, 0.561423, 1.155144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2563.69457031, 1720.3274218800002, 168.57898438), 'rotation':(1.211935, 0.561717, 1.161448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2541.59082031, 1720.120625, 168.10720702999998), 'rotation':(1.225985, 0.562328, 1.17433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2536.06445312, 1720.06898438, 167.98855468999997), 'rotation':(1.229434, 0.561822, 1.17749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2519.48925781, 1719.9140625, 167.62851562), 'rotation':(1.259179, 0.563529, 1.204703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2513.96363281, 1719.86242188, 167.5053125), 'rotation':(1.279014, 0.56441, 1.222808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2513.99683594, 1711.9809375, 167.50439452999998), 'rotation':(-1.298737, -179.434677, -1.358673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2519.52171875, 1712.03273438, 167.62761719), 'rotation':(-1.278992, -179.435577, -1.337128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2552.67480469, 1712.3430468800002, 168.34300781000002), 'rotation':(-1.226013, -179.437668, -1.279327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2563.7265625, 1712.44640625, 168.57808594), 'rotation':(-1.219086, -179.437973, -1.27182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2574.77832031, 1712.54984375, 168.81169922), 'rotation':(-1.211945, -179.438263, -1.264069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2585.8303125, 1712.6530468800001, 169.04402344), 'rotation':(-1.201599, -179.438889, -1.252808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2591.35546875, 1712.7046875, 169.15861328), 'rotation':(-1.181335, -179.438965, -1.230865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2602.40527344, 1712.79929688, 169.37775391), 'rotation':(-1.10083, -179.442169, -1.143768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2607.9299218799997, 1712.8787499999999, 169.48173828), 'rotation':(-1.060699, -179.444885, -1.100525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2630.03222656, 1713.09960938, 169.86019531000002), 'rotation':(-0.93988, -179.447906, -0.9711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2635.55882812, 1713.15125, 169.94625), 'rotation':(-0.899567, -179.450394, -0.928162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2641.0861718799997, 1713.2029687499999, 170.03109375), 'rotation':(-0.879364, -179.449875, -0.906677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2459.276875, 1711.4689843800002, 166.21548828), 'rotation':(-1.410767, -179.429199, -1.481598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2442.31296875, 1711.3103125, 165.79363281000002), 'rotation':(-1.44281, -179.427017, -1.516907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2436.65746094, 1711.25742188, 165.65109375), 'rotation':(-1.442657, -179.428177, -1.516754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2431.00242188, 1711.20445312, 165.50857422), 'rotation':(-1.452209, -179.427399, -1.527313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.34914062, 1711.1516406199999, 165.36521484000002), 'rotation':(-1.471222, -179.425415, -1.548309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2419.69484375, 1711.09875, 165.22050781000002), 'rotation':(-1.490112, -179.425446, -1.569214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2414.04054688, 1711.04578125, 165.07439452999998), 'rotation':(-1.490112, -179.425446, -1.569214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2408.38597656, 1710.9928906199998, 164.92691406000003), 'rotation':(-1.509064, -179.424438, -1.59021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2402.73070312, 1710.94007812, 164.7778125), 'rotation':(-1.518494, -179.423553, -1.600677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2391.42382812, 1710.83421875, 164.47792969), 'rotation':(-1.518585, -179.423538, -1.600769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2385.76878906, 1710.78125, 164.32792969), 'rotation':(-1.524902, -179.422699, -1.607819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2380.11570312, 1710.72835938, 164.17769531000002), 'rotation':(-1.524902, -179.422699, -1.607819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2363.15257812, 1710.5696093800002, 163.72208984), 'rotation':(-1.562897, -179.420639, -1.649994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2357.49804688, 1710.516875, 163.56825195), 'rotation':(-1.562897, -179.420639, -1.649994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2351.84570312, 1710.46398438, 163.41374023), 'rotation':(-1.569366, -179.420746, -1.657227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.5364062500003, 1710.358125, 163.10367188), 'rotation':(-1.569275, -179.420761, -1.657104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2323.5725, 1710.1993750000001, 162.63855469), 'rotation':(-1.577118, -179.420486, -1.665833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2317.9192187500003, 1710.14648438, 162.48295898), 'rotation':(-1.584839, -179.420334, -1.674469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2306.61109375, 1710.040625, 162.1700293), 'rotation':(-1.584991, -179.41954, -1.674622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2300.9565625, 1709.9878125, 162.01344727), 'rotation':(-1.584839, -179.420334, -1.674469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2295.3020312500003, 1709.93484375, 161.85685547), 'rotation':(-1.584839, -179.420334, -1.674469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2278.33742188, 1709.7775000000001, 161.38712891), 'rotation':(-1.584167, -179.419724, -1.673706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2261.3740625, 1709.6173437500001, 160.91842773), 'rotation':(-1.578308, -179.420349, -1.667175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2245.828125, 1709.34226562, 160.4896875), 'rotation':(-1.578369, -179.420303, -1.667267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2470.50390625, 1719.579375, 166.490625), 'rotation':(1.368039, 0.568724, 1.303814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2459.19875, 1719.35007812, 166.21537109000002), 'rotation':(1.389452, 0.569755, 1.323223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2453.54296875, 1719.29734375, 166.07599609000002), 'rotation':(1.410776, 0.5708, 1.342509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2442.2341406200003, 1719.1915625000001, 165.79349609000002), 'rotation':(1.43199, 0.571857, 1.361678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2436.57886719, 1719.13851562, 165.65097656), 'rotation':(1.442768, 0.572963, 1.37142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2430.92359375, 1719.08554688, 165.50845703), 'rotation':(1.442652, 0.572959, 1.371289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.27, 1719.03273438, 165.36509766), 'rotation':(1.452221, 0.572605, 1.379932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2419.61570312, 1718.9797656199999, 165.22039062), 'rotation':(1.471161, 0.573575, 1.396992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2413.9611718799997, 1718.926875, 165.07427734), 'rotation':(1.471161, 0.573575, 1.396992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2408.306875, 1718.87390625, 164.92677734), 'rotation':(1.490163, 0.575559, 1.414084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2402.65136719, 1718.8210156199998, 164.77767577999998), 'rotation':(1.509041, 0.575547, 1.431047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2391.34375, 1718.7153125, 164.47777344), 'rotation':(1.518494, 0.576448, 1.439518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2380.035625, 1718.6095312500001, 164.17753906000002), 'rotation':(1.518583, 0.576453, 1.439596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2374.38132812, 1718.55664062, 164.02675781000002), 'rotation':(1.524928, 0.576341, 1.445282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2368.72609375, 1718.5037499999999, 163.87484375), 'rotation':(1.53753, 0.577, 1.456571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2357.4175, 1718.39804688, 163.56806641), 'rotation':(1.550234, 0.578669, 1.467952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2351.76488281, 1718.34523438, 163.41354492), 'rotation':(1.569468, 0.583017, 1.48515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2346.10984375, 1718.2923437499999, 163.25849609), 'rotation':(1.569373, 0.579256, 1.485072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2329.1457812500003, 1718.13367188, 162.79337891), 'rotation':(1.56925, 0.579249, 1.484969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2317.83742188, 1718.0278125, 162.48272461), 'rotation':(1.577097, 0.579526, 1.491963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2300.87453125, 1717.86914062, 162.01323242), 'rotation':(1.584986, 0.579672, 1.499005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2283.91039062, 1717.7103124999999, 161.54345703), 'rotation':(1.584898, 0.580451, 1.498919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2272.600625, 1717.60453125, 161.23046875), 'rotation':(1.582459, 0.578774, 1.496748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2261.29101562, 1717.49875, 160.91816406), 'rotation':(1.579174, 0.579981, 1.493814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2255.64109375, 1717.5076562499999, 160.76237305), 'rotation':(1.578293, 0.579661, 1.493039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2062.8762500000003, 1707.3982812499999, 155.82804688), 'rotation':(-1.246552, -179.28389, -1.301727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2079.44382812, 1707.5974999999999, 156.20106445), 'rotation':(-1.316193, -179.280746, -1.377747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2090.48757812, 1707.7303124999999, 156.45871094), 'rotation':(-1.350983, -179.279129, -1.415863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2096.00929688, 1707.7966406199998, 156.59024413999998), 'rotation':(-1.368286, -179.278351, -1.434875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2107.05296875, 1707.92929688, 156.85609375), 'rotation':(-1.382568, -179.277008, -1.450562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2123.61695312, 1708.12851562, 157.26185547), 'rotation':(-1.416718, -179.275299, -1.488159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2129.1384375, 1708.19492188, 157.39932617), 'rotation':(-1.427917, -179.276047, -1.500488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2140.180625, 1708.30773438, 157.67750977), 'rotation':(-1.450592, -179.273636, -1.525543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2145.7018749999997, 1708.3626562499999, 157.81825195), 'rotation':(-1.461945, -179.274292, -1.538055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2151.22195312, 1708.4803124999999, 157.95966797), 'rotation':(-1.467468, -179.273392, -1.544189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2178.82515625, 1708.82515625, 158.6755957), 'rotation':(-1.510376, -179.271408, -1.591675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2184.3464062499997, 1708.8915625, 158.82240234), 'rotation':(-1.527588, -179.270508, -1.610779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2189.86625, 1708.95789062, 158.97001953), 'rotation':(-1.527588, -179.270508, -1.610779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2195.3879687500003, 1709.0197656199998, 159.11827148), 'rotation':(-1.537872, -179.3078, -1.622192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2200.90820312, 1709.0787500000001, 159.26654297), 'rotation':(-1.537872, -179.3078, -1.622192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2211.9540625, 1709.01773438, 159.56336914), 'rotation':(-1.540405, -179.422943, -1.625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2189.87796875, 1716.8075, 158.97287109), 'rotation':(1.534313, 0.69155, 1.453696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2184.35640625, 1716.74109375, 158.82517578), 'rotation':(1.536068, 0.730324, 1.455273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2167.79320312, 1716.54171875, 158.38869140999998), 'rotation':(1.493387, 0.727694, 1.416978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2162.27171875, 1716.47523438, 158.24584961), 'rotation':(1.476052, 0.726792, 1.401389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2140.18359375, 1716.2096875, 157.67999023000002), 'rotation':(1.461865, 0.726942, 1.388614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2112.57226562, 1715.8778125, 156.99251953), 'rotation':(1.405291, 0.722858, 1.337567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2107.05054688, 1715.81140625, 156.85832031), 'rotation':(1.393966, 0.722271, 1.327322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2090.48046875, 1715.6121875, 156.46078125), 'rotation':(1.368367, 0.721698, 1.304118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2068.385, 1715.34640625, 155.95239258), 'rotation':(1.281569, 0.717676, 1.225161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2057.3403125, 1715.21351562, 155.7090918), 'rotation':(1.246619, 0.716132, 1.193211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2051.82125, 1715.2336718800002, 155.58957031), 'rotation':(1.238033, 0.71471, 1.185353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2199.13890625, 1288.56103516, 157.47300781), 'rotation':(1.123334, 0.5052, 1.079914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2182.44335938, 1288.42015625, 157.1478418), 'rotation':(1.106634, 0.506077, 1.064481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2176.8784375, 1288.37316406, 157.04071289), 'rotation':(1.100043, 0.504567, 1.058397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2160.18164062, 1288.23230469, 156.72317383), 'rotation':(1.079989, 0.503806, 1.039824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2154.61648438, 1288.1853125, 156.61863281), 'rotation':(1.073412, 0.503556, 1.033731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2143.48507812, 1288.09130859, 156.41073242000002), 'rotation':(1.066561, 0.503567, 1.027385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2126.7890625, 1287.95042969, 156.10356445), 'rotation':(1.044759, 0.502737, 1.007163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2110.09132812, 1287.80957031, 155.80348633), 'rotation':(1.023067, 0.501975, 0.987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2104.52492188, 1287.76246094, 155.70486328), 'rotation':(1.015745, 0.501714, 0.980204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2098.95796875, 1287.71544922, 155.60660156), 'rotation':(1.012343, 0.501054, 0.977021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2093.39234375, 1287.66857422, 155.50908203), 'rotation':(1.006476, 0.502242, 0.971581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2087.82664062, 1287.62158203, 155.41271484), 'rotation':(0.994831, 0.500525, 0.960713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2071.12648438, 1287.48046875, 155.13053711), 'rotation':(0.960188, 0.499361, 0.928399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2059.99460938, 1287.3866015600001, 154.94824219), 'rotation':(0.937075, 0.498574, 0.906786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2054.43359375, 1287.39794922, 154.85866211), 'rotation':(0.925292, 0.498193, 0.895756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2210.3385937499997, 1280.77429688, 157.69170898000002), 'rotation':(-1.126801, -179.494705, -1.171814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2204.7734375, 1280.72730469, 157.58224609), 'rotation':(-1.123352, -179.493927, -1.16806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2199.20875, 1280.68029297, 157.47308594), 'rotation':(-1.119965, -179.494675, -1.164398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2188.078125, 1280.58630859, 157.25567383), 'rotation':(-1.106628, -179.495178, -1.150024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2176.9479687499997, 1280.4923046899999, 157.04077148), 'rotation':(-1.093323, -179.495697, -1.135651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2165.81640625, 1280.3984375, 156.82842773000002), 'rotation':(-1.080048, -179.49617, -1.121368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2132.42359375, 1280.11669922, 156.20521484), 'rotation':(-1.04483, -179.497238, -1.083466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2126.8581249999997, 1280.06982422, 156.10360352), 'rotation':(-1.037506, -179.497498, -1.075623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2115.725625, 1279.97582031, 155.90275391), 'rotation':(-1.023071, -179.498016, -1.06012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2110.15992188, 1279.92882812, 155.80351561999998), 'rotation':(-1.015747, -179.498276, -1.052277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2099.02664062, 1279.83484375, 155.60663086), 'rotation':(-1.006439, -179.499069, -1.042297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2093.46117188, 1279.78796875, 155.50912109), 'rotation':(-0.994873, -179.499451, -1.029907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2087.89523438, 1279.74097656, 155.41276367), 'rotation':(-0.983215, -179.499878, -1.017395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2082.32960938, 1279.69384766, 155.31756836), 'rotation':(-0.971771, -179.498962, -1.005157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2076.7604687499997, 1279.64671875, 155.22344727), 'rotation':(-0.960144, -179.500671, -0.992737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2071.19507812, 1279.59984375, 155.13056641), 'rotation':(-0.948578, -179.501022, -0.980377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2060.06296875, 1279.50597656, 154.94829102), 'rotation':(-0.925293, -179.501801, -0.955566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2248.40820312, 1289.00757812, 158.45388671999999), 'rotation':(1.155443, 0.556538, 1.109513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2282.4582812500003, 1289.32470703, 159.14444336), 'rotation':(1.172552, 0.557198, 1.125267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2293.80789062, 1289.43042969, 159.37673828), 'rotation':(1.17247, 0.55816, 1.125195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2305.1575000000003, 1289.53601562, 159.60915039), 'rotation':(1.172586, 0.557217, 1.125303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2310.83226562, 1289.58886719, 159.72536133), 'rotation':(1.172586, 0.557217, 1.125303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2344.88085938, 1289.90601562, 160.42227538999998), 'rotation':(1.17191, 0.557378, 1.124683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2356.23023438, 1290.01171875, 160.6544043), 'rotation':(1.167443, 0.558008, 1.120567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2361.90476562, 1290.06457031, 160.77018555), 'rotation':(1.164465, 0.556793, 1.117829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2384.60398438, 1290.24292969, 161.23086913999998), 'rotation':(1.157198, 0.557077, 1.111133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2401.6284375, 1290.40148438, 161.57416992), 'rotation':(1.14616, 0.555939, 1.100972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2412.97804688, 1290.50707031, 161.8012207), 'rotation':(1.137247, 0.555582, 1.092755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2418.65257812, 1290.55980469, 161.91414062), 'rotation':(1.137247, 0.555582, 1.092755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.32765625, 1290.61267578, 162.02666992000002), 'rotation':(1.132869, 0.556543, 1.088706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2452.70238281, 1290.87707031, 162.5840332), 'rotation':(1.116961, 0.555807, 1.07403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2458.37695312, 1290.92992188, 162.69450195), 'rotation':(1.107372, 0.554447, 1.065172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2469.7267968799997, 1291.03564453, 162.91305664), 'rotation':(1.08807, 0.553708, 1.04731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2481.07691406, 1291.14136719, 163.12876953), 'rotation':(1.083309, 0.55406, 1.042897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.7521875, 1291.19421875, 163.23613281), 'rotation':(1.083254, 0.554038, 1.042872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2498.10058594, 1291.46996094, 163.45052734), 'rotation':(1.071062, 0.553018, 1.031558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2503.77585938, 1291.52283203, 163.55694336), 'rotation':(1.062818, 0.553827, 1.023918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2498.69824219, 1283.40673828, 163.46039062), 'rotation':(-1.079346, -179.44664, -1.120605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2492.58472656, 1283.40001953, 163.34509766), 'rotation':(-1.083282, -179.445953, -1.124847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2464.21167969, 1283.13585938, 162.8059082), 'rotation':(-1.107391, -179.444565, -1.150818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2447.18824219, 1282.97730469, 162.47479492), 'rotation':(-1.121704, -179.44455, -1.166321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2441.5134375, 1282.92443359, 162.36361328), 'rotation':(-1.124054, -179.444962, -1.168823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2435.83960938, 1282.87158203, 162.25228515999999), 'rotation':(-1.128326, -179.443634, -1.173462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2407.4665625, 1282.60730469, 161.6897168), 'rotation':(-1.146179, -179.442917, -1.192749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2396.1171875, 1282.50158203, 161.46186523), 'rotation':(-1.154907, -179.442581, -1.202209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2373.42039062, 1282.29027344, 161.00290039), 'rotation':(-1.164459, -179.443192, -1.212555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2367.74609375, 1282.23742188, 160.88760742), 'rotation':(-1.16745, -179.443054, -1.21579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2356.39695312, 1282.13171875, 160.65630859), 'rotation':(-1.17038, -179.441864, -1.218964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2350.72289062, 1282.07886719, 160.5403125), 'rotation':(-1.171906, -179.442612, -1.220612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2345.04808594, 1282.02599609, 160.42416015999999), 'rotation':(-1.171783, -179.442627, -1.22049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2322.349375, 1281.81457031, 159.95962891), 'rotation':(-1.172272, -179.443039, -1.221008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2305.32515625, 1281.6561328100001, 159.61106445), 'rotation':(-1.172546, -179.442795, -1.221313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2293.97609375, 1281.55041016, 159.37868164), 'rotation':(-1.172546, -179.441849, -1.221313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2288.30125, 1281.49755859, 159.26245117), 'rotation':(-1.170441, -179.442688, -1.219025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2282.62570312, 1281.44470703, 159.14636719), 'rotation':(-1.170441, -179.442688, -1.219025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2276.95070312, 1281.39183594, 159.03046875), 'rotation':(-1.16626, -179.442856, -1.214478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2265.60109375, 1281.28613281, 158.79978516), 'rotation':(-1.157623, -179.442245, -1.205139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2254.25023438, 1281.18042969, 158.5703125), 'rotation':(-1.155426, -179.443451, -1.202789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.63623047, 1285.11376953, 166.48472656), 'rotation':(-0.868805, -179.453613, -0.895477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2686.11351562, 1285.07640625, 166.62714843999998), 'rotation':(-0.860779, -179.453049, -0.886963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2664.67382812, 1285.00255859, 166.30265625), 'rotation':(-0.884399, -179.452438, -0.912048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2647.97191406, 1284.84705078, 166.04216797), 'rotation':(-0.915955, -179.451431, -0.945618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2636.83742188, 1284.74339844, 165.86408203), 'rotation':(-0.923798, -179.451935, -0.953949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2631.26976562, 1284.6915234399999, 165.77427734), 'rotation':(-0.923798, -179.451935, -0.953949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2609.00097656, 1284.48414062, 165.41185547), 'rotation':(-0.955994, -179.450302, -0.988312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2597.86597656, 1284.38037109, 165.22505859), 'rotation':(-0.975403, -179.450027, -1.009064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2592.29980469, 1284.32861328, 165.13060547), 'rotation':(-0.97522, -179.450043, -1.008881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2581.16578125, 1284.22509766, 164.94082031000002), 'rotation':(-0.985229, -179.44928, -1.019592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2575.59863281, 1284.17322266, 164.8453125), 'rotation':(-0.992004, -179.449051, -1.026825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2570.03125, 1284.12132812, 164.74912109000002), 'rotation':(-0.998718, -179.45015, -1.034027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2558.89648438, 1284.01769531, 164.55470703), 'rotation':(-1.011963, -179.448334, -1.048187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2553.32910156, 1283.96582031, 164.45646484), 'rotation':(-1.018829, -179.44812, -1.055573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2547.76171875, 1283.9139453100001, 164.35753906000002), 'rotation':(-1.025482, -179.447861, -1.062714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2670.1640625, 1292.93494141, 166.38767578), 'rotation':(0.868807, 0.546382, 0.842746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2636.76074219, 1292.62390625, 165.86402343999998), 'rotation':(0.915969, 0.548572, 0.887027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2625.625, 1292.52027344, 165.68441406000002), 'rotation':(0.92379, 0.549, 0.894347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2620.05859375, 1292.46837891, 165.59427734000002), 'rotation':(0.92379, 0.549, 0.894347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2608.92382812, 1292.36474609, 165.41179688), 'rotation':(0.94301, 0.548284, 0.912342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2603.35621094, 1292.31287109, 165.31886719), 'rotation':(0.955981, 0.54969, 0.924467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2597.7892968799997, 1292.26097656, 165.225), 'rotation':(0.968773, 0.550137, 0.936417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2592.22289062, 1292.20921875, 165.13054688), 'rotation':(0.975385, 0.549967, 0.94259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2581.08910156, 1292.10546875, 164.94078125), 'rotation':(0.978643, 0.550498, 0.945623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2569.95460938, 1292.00183594, 164.7490625), 'rotation':(0.991996, 0.550959, 0.958081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2564.3871875, 1291.94996094, 164.65220703), 'rotation':(0.998724, 0.551168, 0.96434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2558.81984375, 1291.89806641, 164.55464844), 'rotation':(1.005356, 0.551422, 0.970534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2553.25242188, 1291.84619141, 164.45640625), 'rotation':(1.011961, 0.551656, 0.976674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2547.6853125, 1291.79455078, 164.3575), 'rotation':(1.018846, 0.550555, 0.983074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2852.24316406, 1286.74925781, 168.90923827999998), 'rotation':(-0.724762, -179.456909, -0.743286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2830.11279297, 1286.54320312, 168.62667968999997), 'rotation':(-0.737823, -179.457138, -0.757019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2819.04736328, 1286.44019531, 168.48417969), 'rotation':(-0.737305, -179.45636, -0.756439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2813.51441406, 1286.38867188, 168.41296875), 'rotation':(-0.736359, -179.457214, -0.755463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2807.98167969, 1286.33714844, 168.34185547), 'rotation':(-0.735291, -179.45723, -0.754333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2802.44898438, 1286.28552734, 168.27078125), 'rotation':(-0.735291, -179.45723, -0.754333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2774.78662109, 1286.02808594, 167.91542969), 'rotation':(-0.757599, -179.456161, -0.777832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2758.19042969, 1285.87341797, 167.69273438), 'rotation':(-0.805298, -179.455963, -0.828186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2752.661875, 1285.82189453, 167.61587891), 'rotation':(-0.805298, -179.455963, -0.828186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2747.12988281, 1285.77027344, 167.53763672000002), 'rotation':(-0.821045, -179.454407, -0.844849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2741.59789062, 1285.71875, 167.45804688), 'rotation':(-0.837128, -179.453934, -0.861877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2736.06591797, 1285.66722656, 167.37712890999998), 'rotation':(-0.852966, -179.453461, -0.878632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2730.5334375, 1285.61572266, 167.29474609000002), 'rotation':(-0.860779, -179.4534, -0.886932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2725.00316406, 1285.56433594, 167.21167968999998), 'rotation':(-0.860931, -179.4534, -0.887115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2730.44482422, 1293.4962109399999, 167.29451172), 'rotation':(0.852947, 0.546533, 0.827835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2735.97777344, 1293.54773438, 167.37691406000002), 'rotation':(0.837122, 0.546049, 0.812921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2741.51, 1293.59923828, 167.45783203), 'rotation':(0.82105, 0.544464, 0.797763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2747.04273438, 1293.650625, 167.53742188), 'rotation':(0.8053, 0.545153, 0.782887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2752.57470703, 1293.70214844, 167.61568359), 'rotation':(0.789461, 0.544695, 0.767922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2758.10498047, 1293.75367188, 167.69255859), 'rotation':(0.789461, 0.544695, 0.767922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2763.63720703, 1293.80505859, 167.76814453), 'rotation':(0.773382, 0.544256, 0.752711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2769.1696875, 1293.8565625, 167.84238281), 'rotation':(0.757591, 0.542717, 0.737743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2774.70214844, 1293.90808594, 167.9153125), 'rotation':(0.741683, 0.543437, 0.722662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2780.23388672, 1293.95958984, 167.98689453), 'rotation':(0.733726, 0.54297, 0.715111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2791.30029297, 1294.06273438, 168.12871094), 'rotation':(0.734252, 0.542727, 0.71561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2796.83349609, 1294.11425781, 168.19964843999998), 'rotation':(0.73527, 0.543574, 0.716587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2802.36644531, 1294.16578125, 168.27066406000003), 'rotation':(0.736356, 0.54278, 0.717619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2813.42919922, 1294.26904297, 168.41283203), 'rotation':(0.737292, 0.54282, 0.718498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2818.96582031, 1294.3203125, 168.48408203), 'rotation':(0.737831, 0.543564, 0.718997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2824.49902344, 1294.37183594, 168.55533203), 'rotation':(0.737831, 0.543564, 0.718997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2830.03199219, 1294.42345703, 168.62658202999998), 'rotation':(0.735925, 0.542046, 0.717197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2846.63061523, 1294.5780078100001, 168.8390625), 'rotation':(0.724758, 0.543079, 0.706584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2857.69677734, 1294.68115234, 168.97888672000002), 'rotation':(0.717361, 0.54289, 0.699564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2863.22998047, 1294.73265625, 169.04824219), 'rotation':(0.713543, 0.542772, 0.695937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3045.09130859, 1289.09814453, 171.23769531000002), 'rotation':(-0.680847, -179.233276, -0.697144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.56005859, 1289.02490234, 171.17197266), 'rotation':(-0.679413, -179.233353, -0.695648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3028.49731445, 1288.87841797, 171.04080077999998), 'rotation':(-0.679016, -179.233078, -0.695251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3022.96606445, 1288.80517578, 170.97525391), 'rotation':(-0.679016, -179.233078, -0.695251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.90332031, 1288.65869141, 170.8440625), 'rotation':(-0.679657, -179.233063, -0.695953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3006.37207031, 1288.58544922, 170.77841797000002), 'rotation':(-0.679993, -179.233063, -0.696289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3000.84057617, 1288.51232422, 170.71273438), 'rotation':(-0.680298, -179.233093, -0.696594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2995.30957031, 1288.43908203, 170.64703125), 'rotation':(-0.681, -179.233032, -0.697327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2989.77832031, 1288.36583984, 170.58128906000002), 'rotation':(-0.681488, -179.233017, -0.697845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2973.18432617, 1288.14611328, 170.38388672000002), 'rotation':(-0.681427, -179.232971, -0.697784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2967.65283203, 1288.07287109, 170.31804688), 'rotation':(-0.68161, -179.232971, -0.697968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2962.12182617, 1287.99962891, 170.25224609), 'rotation':(-0.684235, -179.233978, -0.700714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2945.52905273, 1287.77990234, 170.05324219), 'rotation':(-0.692383, -179.233368, -0.70929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2928.93505859, 1287.5603125, 169.85261719), 'rotation':(-0.692505, -179.233368, -0.709412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2906.8137207, 1287.26746094, 169.58482422), 'rotation':(-0.691284, -179.347321, -0.70813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2901.28686523, 1287.20605469, 169.51748047), 'rotation':(-0.703217, -179.457352, -0.720642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2906.734375, 1295.14783203, 169.58513672), 'rotation':(0.695614, 0.766672, 0.678882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2912.265625, 1295.2209375, 169.65230469), 'rotation':(0.692506, 0.766637, 0.675913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2923.32788086, 1295.36742188, 169.78609375), 'rotation':(0.692506, 0.767475, 0.675914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2939.92114258, 1295.58714844, 169.98671875), 'rotation':(0.692424, 0.766653, 0.675839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2950.98291016, 1295.73351562, 170.12023438), 'rotation':(0.684228, 0.767055, 0.668033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2956.51416016, 1295.806875, 170.18658202999998), 'rotation':(0.684228, 0.767055, 0.668033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2967.57592773, 1295.9532421899999, 170.31839843999998), 'rotation':(0.681468, 0.767068, 0.6654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2978.63818359, 1296.09972656, 170.45001953), 'rotation':(0.681427, 0.765741, 0.665362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2984.16943359, 1296.17296875, 170.51580077999998), 'rotation':(0.681496, 0.766979, 0.665417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.82495117, 1296.5391796899999, 170.84435547), 'rotation':(0.67918, 0.766923, 0.663221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3028.41845703, 1296.75890625, 171.04109375), 'rotation':(0.67877, 0.766768, 0.662823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.48071289, 1296.90527344, 171.17226562), 'rotation':(0.680806, 0.766692, 0.664763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.54321289, 1297.05175781, 171.30378906), 'rotation':(0.681981, 0.766721, 0.665883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3083.00488281, 1297.4815625, 171.69171875), 'rotation':(0.685915, 0.766598, 0.669626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3099.68994141, 1297.70251953, 171.89179688000002), 'rotation':(0.693462, 0.766542, 0.676831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.37548828, 1297.92333984, 172.09375), 'rotation':(0.696037, 0.767939, 0.679281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3127.4987793, 1298.07068359, 172.22890625), 'rotation':(0.695846, 0.766648, 0.679103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3133.06054688, 1298.14429688, 172.29648438), 'rotation':(0.698073, 0.767008, 0.681211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.18408203, 1298.29150391, 172.43199219), 'rotation':(0.701986, 0.767047, 0.684936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3138.68457031, 1290.33740234, 172.36371093999998), 'rotation':(-0.695892, -179.232056, -0.712952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3127.5612793, 1290.19005859, 172.22841797), 'rotation':(-0.696014, -179.233337, -0.713074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.4387207, 1290.0428515600001, 172.09324218999998), 'rotation':(-0.696045, -179.233307, -0.713104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3110.87744141, 1289.96923828, 172.02572265999999), 'rotation':(-0.693451, -179.232727, -0.710419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3099.75415039, 1289.82189453, 171.89130859), 'rotation':(-0.688477, -179.233337, -0.7052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3088.6315918, 1289.6746875, 171.75785156), 'rotation':(-0.685913, -179.233398, -0.702484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.50097656, 1292.01623047, 173.95478516), 'rotation':(-0.735779, -179.231812, -0.754883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3259.953125, 1291.94287109, 173.88326172), 'rotation':(-0.735779, -179.231812, -0.754883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3215.56910156, 1291.35523438, 173.31761719), 'rotation':(-0.724792, -179.232376, -0.743317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3193.37695312, 1291.06140625, 173.03867188), 'rotation':(-0.712402, -179.232697, -0.730286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.82933594, 1290.98804688, 172.9696875), 'rotation':(-0.710327, -179.232666, -0.728088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3176.66455078, 1298.7215625, 172.83246093999998), 'rotation':(0.710312, 0.767322, 0.692865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.76148438, 1298.86853516, 172.97015625), 'rotation':(0.712402, 0.767297, 0.694852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.30957031, 1298.94189453, 173.03914062), 'rotation':(0.716528, 0.768244, 0.698783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3198.85816406, 1299.01539062, 173.10853516), 'rotation':(0.720558, 0.767502, 0.702598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.50341797, 1299.23583984, 173.318125), 'rotation':(0.726848, 0.767714, 0.70858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.69703125, 1299.52966797, 173.59984375), 'rotation':(0.73208, 0.76738, 0.713547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3243.24535156, 1299.60314453, 173.67050781), 'rotation':(0.73208, 0.76738, 0.713547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3248.79371094, 1299.67664062, 173.74144531000002), 'rotation':(0.735789, 0.768181, 0.717063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.43871094, 1299.89697266, 173.95533203), 'rotation':(0.739224, 0.768267, 0.720332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.33886719, 1300.75757812, 176.76416016), 'rotation':(0.735762, 0.092824, 0.717039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3463.75097656, 1300.6368359399999, 176.55111327999998), 'rotation':(0.735762, 0.092824, 0.717039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3452.69484375, 1300.58777344, 176.40865234), 'rotation':(0.737947, 0.092484, 0.719113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.57960938, 1300.55554688, 176.11914062), 'rotation':(0.753636, 0.093726, 0.733997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3425.05054688, 1300.54748047, 176.04640625), 'rotation':(0.75352, 0.093723, 0.733897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3419.52171875, 1300.53929688, 175.97367188), 'rotation':(0.753903, 0.093204, 0.734255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3413.99292969, 1300.53125, 175.90087891), 'rotation':(0.754053, 0.093208, 0.734402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3402.93507812, 1300.51513672, 175.75519531), 'rotation':(0.754674, 0.094466, 0.734994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3391.8771875, 1300.49902344, 175.60939453), 'rotation':(0.755439, 0.093243, 0.73573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.76148438, 1300.46679688, 175.31734375), 'rotation':(0.756764, 0.093373, 0.736977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3364.23265625, 1300.45875, 175.24427734), 'rotation':(0.756874, 0.093376, 0.737084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3358.70359375, 1300.45068359, 175.17128906000002), 'rotation':(0.755924, 0.093541, 0.736173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3336.58714844, 1300.41833984, 174.88066406000002), 'rotation':(0.750112, 0.092551, 0.730666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3331.05835938, 1300.4102734399999, 174.80826172000002), 'rotation':(0.750119, 0.093929, 0.730668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3325.52929688, 1300.4022265600001, 174.73585938), 'rotation':(0.750112, 0.092551, 0.730666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3303.41210938, 1300.36853516, 174.44681641), 'rotation':(0.747339, 0.093498, 0.728037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3297.93994141, 1300.32726562, 174.37615234), 'rotation':(0.736595, 0.600996, 0.717833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.35277344, 1292.61767578, 176.76419922000002), 'rotation':(-0.735748, -179.907166, -0.754852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3452.714375, 1292.70703125, 176.40875), 'rotation':(-0.742493, -179.907394, -0.761932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3441.65894531, 1292.69091797, 176.26462891), 'rotation':(-0.753601, -179.906265, -0.773621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3419.54808594, 1292.65869141, 175.97384766), 'rotation':(-0.754059, -179.906784, -0.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3414.02027344, 1292.650625, 175.90109375), 'rotation':(-0.754669, -179.906784, -0.77475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3391.90941406, 1292.61828125, 175.60966797), 'rotation':(-0.755768, -179.906754, -0.775909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3380.85375, 1292.60216797, 175.46371093999997), 'rotation':(-0.756531, -179.905472, -0.776733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3375.32617188, 1292.59412109, 175.39070312), 'rotation':(-0.756775, -179.906631, -0.776947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.79835938, 1292.5860546899999, 175.31767578), 'rotation':(-0.756866, -179.906616, -0.777069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3364.27050781, 1292.5780078100001, 175.24462891), 'rotation':(-0.75592, -179.906448, -0.776093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3331.10328125, 1292.52966797, 174.80869141), 'rotation':(-0.750122, -179.90744, -0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.04957031, 1292.44726562, 174.37621094), 'rotation':(-0.743835, -179.231827, -0.763306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2052.95609375, 1545.31382812, 155.14123046999998), 'rotation':(-1.090576, -179.089035, -1.13269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2058.475625, 1545.39964844, 155.24712891), 'rotation':(-1.098511, -179.088226, -1.141266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2080.64914062, 1545.744375, 155.68633789), 'rotation':(-1.162292, -179.085724, -1.210175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2086.19164062, 1545.83054688, 155.79958008), 'rotation':(-1.162292, -179.085724, -1.210175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2113.90453125, 1546.26125, 156.38408203), 'rotation':(-1.226532, -179.082901, -1.279938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2119.44726562, 1546.3473046899999, 156.50358398), 'rotation':(-1.226532, -179.082901, -1.279938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2124.98898438, 1546.4334765600001, 156.62396484), 'rotation':(-1.243652, -179.082962, -1.298584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2130.5321875, 1546.5196484399999, 156.7459082), 'rotation':(-1.260712, -179.08223, -1.317169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2141.61570312, 1546.691875, 156.99227539), 'rotation':(-1.27774, -179.080643, -1.335724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2163.7839062499997, 1547.0228124999999, 157.49378906), 'rotation':(-1.309601, -179.080307, -1.370514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2180.40867188, 1547.3277734399999, 157.87765625), 'rotation':(-1.328186, -179.078354, -1.3909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2185.95015625, 1547.4139453100001, 158.00710938), 'rotation':(-1.337433, -179.079056, -1.401031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2197.0339062499997, 1547.5862890600001, 158.26858398000002), 'rotation':(-1.35611, -179.07814, -1.421509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2202.5768749999997, 1547.66945312, 158.40039062), 'rotation':(-1.362122, -179.124603, -1.428101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2208.0546875, 1555.59914062, 158.53376953), 'rotation':(1.366912, 0.874919, 1.302793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2191.4296875, 1555.3482812500001, 158.13888672), 'rotation':(1.3561, 0.922936, 1.292993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2185.88765625, 1555.2620703100001, 158.00851562), 'rotation':(1.346743, 0.92246, 1.2845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2180.34570312, 1555.17601562, 157.87902344), 'rotation':(1.337494, 0.920982, 1.276086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2163.7174999999997, 1554.9176171899999, 157.49506836), 'rotation':(1.318834, 0.920078, 1.259124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2158.17578125, 1554.8314062499999, 157.36862305), 'rotation':(1.309593, 0.92077, 1.250693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2152.63328125, 1554.74535156, 157.24289062), 'rotation':(1.300222, 0.920312, 1.242165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2141.54710938, 1554.573125, 156.99348633), 'rotation':(1.286343, 0.919384, 1.22951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2136.0051562500003, 1554.4869531200002, 156.86978516), 'rotation':(1.277723, 0.918536, 1.221654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2130.46242188, 1554.40074219, 156.74708984), 'rotation':(1.277723, 0.918536, 1.221654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2119.37570312, 1554.22839844, 156.50469727), 'rotation':(1.24362, 0.917009, 1.19047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2108.29078125, 1554.05617188, 156.26643555), 'rotation':(1.226558, 0.917115, 1.174857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2102.74703125, 1553.96996094, 156.14849609), 'rotation':(1.218055, 0.915835, 1.167068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2097.20289062, 1553.8836718799998, 156.03120117), 'rotation':(1.210091, 0.916253, 1.159756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2086.11671875, 1553.71140625, 155.80055664), 'rotation':(1.178064, 0.914921, 1.130339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2075.02640625, 1553.5389453100001, 155.5753125), 'rotation':(1.16228, 0.914273, 1.115808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2069.4831249999997, 1553.4527734399999, 155.46482422), 'rotation':(1.146331, 0.91363, 1.101125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2257.29078125, 1556.3225, 159.72727539), 'rotation':(1.402798, 0.875768, 1.335315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2262.9674999999997, 1556.4058984399999, 159.86629883), 'rotation':(1.405284, 0.875892, 1.337548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2274.32101562, 1556.57261719, 160.14506836), 'rotation':(1.409573, 0.876104, 1.341427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2279.9978125, 1556.6561328100001, 160.28482422), 'rotation':(1.412046, 0.876228, 1.343659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2297.02828125, 1556.90625, 160.70540039), 'rotation':(1.415495, 0.876361, 1.346783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2308.3815624999997, 1557.07300781, 160.98613281), 'rotation':(1.415434, 0.876318, 1.346733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2314.058125, 1557.1563671899999, 161.12649414), 'rotation':(1.412128, 0.876986, 1.343741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2319.73460938, 1557.23988281, 161.26652344000001), 'rotation':(1.408972, 0.875408, 1.340895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2353.7946875, 1557.70726562, 162.10414062), 'rotation':(1.397368, 0.87584, 1.330397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2359.47167969, 1557.79054688, 162.24270508), 'rotation':(1.388864, 0.875446, 1.32269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2393.53171875, 1558.29101562, 163.06394531), 'rotation':(1.367684, 0.874176, 1.303507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2399.20875, 1558.3743749999999, 163.19957031), 'rotation':(1.361578, 0.873588, 1.297962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.5625, 1558.54113281, 163.46926758), 'rotation':(1.349195, 0.873954, 1.286724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2416.23902344, 1558.62453125, 163.60289062), 'rotation':(1.336852, 0.872447, 1.275513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2421.91601562, 1558.70800781, 163.73543945), 'rotation':(1.324544, 0.872803, 1.264314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2433.27050781, 1558.87476562, 163.99800781000002), 'rotation':(1.318356, 0.872011, 1.258688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2438.94773438, 1558.95824219, 164.12873047000002), 'rotation':(1.318329, 0.871982, 1.258654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.62453125, 1559.0416406200002, 164.25945312), 'rotation':(1.309497, 0.871683, 1.250616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2450.30226562, 1559.1248828100001, 164.38949218999997), 'rotation':(1.291541, 0.870843, 1.234245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2251.74070312, 1548.3587499999999, 159.58875977), 'rotation':(-1.397247, -179.123993, -1.466736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2257.4175, 1548.44214844, 159.72753906), 'rotation':(-1.400665, -179.123001, -1.470459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2280.125, 1548.77574219, 160.28509766), 'rotation':(-1.409637, -179.12384, -1.480347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2285.80171875, 1548.85914062, 160.42507812), 'rotation':(-1.412048, -179.122452, -1.483002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2314.1853125, 1549.27613281, 161.12676758), 'rotation':(-1.415436, -179.123688, -1.486725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2319.8620312499997, 1549.35960938, 161.26681641), 'rotation':(-1.41214, -179.123749, -1.483093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2348.24511719, 1549.79113281, 161.96533203), 'rotation':(-1.405212, -179.123932, -1.475494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2359.59839844, 1549.97632812, 162.24299805), 'rotation':(-1.3974, -179.124146, -1.466888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2365.27464844, 1550.05980469, 162.38102539), 'rotation':(-1.3974, -179.124146, -1.466888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2370.95164062, 1550.1432031200002, 162.51875), 'rotation':(-1.388824, -179.124573, -1.457458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2376.62816406, 1550.2265625, 162.65570312), 'rotation':(-1.380402, -179.124954, -1.448181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2382.3046875, 1550.3099218799998, 162.79236328000002), 'rotation':(-1.380402, -179.124954, -1.448181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.68921875, 1550.72703125, 163.46954102), 'rotation':(-1.361572, -179.125458, -1.427521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2422.04296875, 1550.89378906, 163.73573242), 'rotation':(-1.336853, -179.126587, -1.400391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2427.71949219, 1550.97703125, 163.86726562), 'rotation':(-1.324554, -179.128143, -1.386902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.75121094, 1551.22730469, 164.25972656000002), 'rotation':(-1.318329, -179.128006, -1.380096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2450.42894531, 1551.31066406, 164.38976562), 'rotation':(-1.309509, -179.128311, -1.370453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2473.13769531, 1551.64429688, 164.89962891), 'rotation':(-1.273804, -179.129959, -1.331451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2516.80710938, 1552.2528125, 165.83931640999998), 'rotation':(-1.198761, -179.133301, -1.249725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.89941406, 1552.41578125, 166.06666016), 'rotation':(-1.168457, -179.134537, -1.216888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.44679688, 1552.4971875, 166.17916015999998), 'rotation':(-1.160889, -179.13475, -1.208649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2538.994375, 1552.5787500000001, 166.29162109), 'rotation':(-1.160706, -179.134781, -1.208466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2555.63453125, 1552.82324219, 166.62419922), 'rotation':(-1.132172, -179.135284, -1.177612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2561.18015625, 1552.90464844, 166.73261718999998), 'rotation':(-1.120789, -179.137115, -1.165314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2566.72730469, 1552.98621094, 166.83988281), 'rotation':(-1.109436, -179.136139, -1.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2583.36890625, 1553.2305859399999, 167.15474609), 'rotation':(-1.075012, -179.138855, -1.115967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2588.91578125, 1553.3121484399999, 167.25824218999998), 'rotation':(-1.069275, -179.137939, -1.109772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2594.463125, 1553.39355469, 167.36087891), 'rotation':(-1.062378, -179.139542, -1.102356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2600.01023438, 1553.47523438, 167.46207031000003), 'rotation':(-1.048157, -179.138733, -1.087067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2616.651875, 1553.7196093799998, 167.75673827999998), 'rotation':(-0.991669, -179.140747, -1.026459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2627.74683594, 1553.8824609399999, 167.94583984000002), 'rotation':(-0.963562, -179.143036, -0.996399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2633.29445312, 1553.96398438, 168.03869140999998), 'rotation':(-0.956665, -179.141449, -0.989014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2638.84253906, 1554.04554688, 168.13138672000002), 'rotation':(-0.956512, -179.142792, -0.988892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2633.1955468799997, 1561.8443750000001, 168.03896484), 'rotation':(0.95652, 0.857198, 0.924962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2622.10109375, 1561.68128906, 167.85232422), 'rotation':(0.963562, 0.858326, 0.931556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2616.55347656, 1561.59984375, 167.75705078), 'rotation':(0.977844, 0.858773, 0.94489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2605.4607031200003, 1561.4368749999999, 167.56208984), 'rotation':(1.020055, 0.860286, 0.984205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2572.17820312, 1560.94824219, 166.94632812), 'rotation':(1.086587, 0.861573, 1.045942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2566.63085938, 1560.86671875, 166.84025391), 'rotation':(1.097809, 0.863369, 1.056321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2561.08375, 1560.7852734399999, 166.73298828), 'rotation':(1.109434, 0.863855, 1.067069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2549.9919531200003, 1560.6221875, 166.51492188), 'rotation':(1.132165, 0.86471, 1.088061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2544.44484375, 1560.54066406, 166.40400391), 'rotation':(1.143749, 0.863804, 1.098735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.80394531, 1560.29640625, 166.06708984), 'rotation':(1.160866, 0.865257, 1.114516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.25878906, 1560.2149609399999, 165.95410156000003), 'rotation':(1.168468, 0.865454, 1.121506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2516.71214844, 1560.1334375000001, 165.83974609), 'rotation':(1.183549, 0.866039, 1.135375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2511.16527344, 1560.051875, 165.72388672), 'rotation':(1.198746, 0.866704, 1.149345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2864.65917969, 1557.3628125, 171.14316406), 'rotation':(-0.60611, -179.151459, -0.619019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2858.96801758, 1557.27917969, 171.08375), 'rotation':(-0.60611, -179.151459, -0.619019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2853.27734375, 1557.19554688, 171.02339844), 'rotation':(-0.618835, -179.152161, -0.632294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2841.89526367, 1557.0284375, 170.89943359), 'rotation':(-0.638184, -179.151108, -0.652527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2807.75074219, 1556.526875, 170.51341797), 'rotation':(-0.677551, -179.150696, -0.693726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2802.06152344, 1556.44335938, 170.44640625), 'rotation':(-0.686157, -179.149261, -0.702759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2796.37060547, 1556.3597265600001, 170.37851562), 'rotation':(-0.695099, -179.150284, -0.712128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2790.67945312, 1556.27613281, 170.30974609), 'rotation':(-0.703735, -179.150055, -0.721191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2773.60791016, 1556.02527344, 170.09947266), 'rotation':(-0.70929, -179.149353, -0.727051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2762.22582031, 1555.85804688, 169.95837891), 'rotation':(-0.711365, -179.15004, -0.729187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2756.53466797, 1555.77441406, 169.88767578), 'rotation':(-0.713684, -179.149246, -0.731628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2750.84351562, 1555.6907812499999, 169.81679688), 'rotation':(-0.715729, -179.149216, -0.733765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2745.15257812, 1555.6071875, 169.74583984), 'rotation':(-0.715729, -179.149216, -0.733765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2739.46142578, 1555.5235546899999, 169.67470702999998), 'rotation':(-0.716888, -179.149124, -0.734985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2728.07958984, 1555.35632812, 169.53228516), 'rotation':(-0.731903, -179.148895, -0.750793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2722.39208984, 1555.2728124999999, 169.45957031), 'rotation':(-0.761841, -179.148117, -0.782318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.70556641, 1555.18945312, 169.38361328), 'rotation':(-0.791779, -179.148621, -0.813904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2693.95458984, 1554.85523438, 169.04802734), 'rotation':(-0.91156, -179.143753, -0.940918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2682.57738281, 1554.68796875, 168.86191406), 'rotation':(-0.956665, -179.141647, -0.989014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.74339844, 1562.48414062, 168.76638672), 'rotation':(0.956602, 0.857355, 0.925059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2682.43382812, 1562.56761719, 168.86142578), 'rotation':(0.941651, 0.857224, 0.911077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2688.12255859, 1562.65125, 168.95574219), 'rotation':(0.91155, 0.856253, 0.882884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.49951172, 1562.81824219, 169.13626953), 'rotation':(0.85167, 0.854409, 0.82663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.87695312, 1562.98535156, 169.30412109), 'rotation':(0.79179, 0.852691, 0.770125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.56664062, 1563.06882812, 169.38330077999998), 'rotation':(0.761839, 0.851876, 0.741785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2722.25464844, 1563.15234375, 169.45929688), 'rotation':(0.731903, 0.851099, 0.713369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2727.943125, 1563.23597656, 169.53203125), 'rotation':(0.716876, 0.850875, 0.699107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2750.70726562, 1563.5704296899999, 169.81652343999997), 'rotation':(0.713666, 0.850738, 0.696051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2762.08960938, 1563.73753906, 169.958125), 'rotation':(0.709315, 0.850653, 0.691904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2790.54417969, 1564.15550781, 170.30951172000002), 'rotation':(0.695101, 0.850951, 0.678396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2796.23511719, 1564.23914062, 170.37828125), 'rotation':(0.686168, 0.849503, 0.669883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2801.92601562, 1564.32273438, 170.44619140999998), 'rotation':(0.677527, 0.849301, 0.661651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2813.30738281, 1564.49, 170.57935547), 'rotation':(0.65996, 0.848887, 0.644899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2830.38011719, 1564.74085938, 170.77275391), 'rotation':(0.638001, 0.848885, 0.623917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2836.07128906, 1564.82445312, 170.83615234), 'rotation':(0.638179, 0.84756, 0.624078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2841.76196289, 1564.90808594, 170.89923828), 'rotation':(0.631704, 0.849093, 0.617896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2847.453125, 1564.9915624999999, 170.96173828), 'rotation':(0.618822, 0.848785, 0.605558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2858.83520508, 1565.1588281200002, 171.08355468999997), 'rotation':(0.593325, 0.848245, 0.581127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2864.52612305, 1565.24242188, 171.14298828), 'rotation':(0.593325, 0.848245, 0.581127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2902.45239258, 1565.92921875, 171.52673828), 'rotation':(0.562924, 0.847212, 0.551941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2913.51220703, 1566.03601562, 171.63466797), 'rotation':(0.547426, 0.846909, 0.537043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2919.04101562, 1566.0628515600001, 171.68759766), 'rotation':(0.543567, 0.846833, 0.533329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2924.56933594, 1566.12453125, 171.74019531000002), 'rotation':(0.543567, 0.846833, 0.533329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2941.15576172, 1566.3680468799998, 171.89671875), 'rotation':(0.532208, 0.845539, 0.522386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.27148438, 1566.69289062, 172.10023438), 'rotation':(0.518671, 0.846419, 0.509341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.80029297, 1566.77417969, 172.15015625), 'rotation':(0.514149, 0.846336, 0.504995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.3293457, 1566.8553515600001, 172.1996875), 'rotation':(0.509491, 0.846224, 0.500477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2985.38696289, 1567.0178125, 172.2978125), 'rotation':(0.50736, 0.846287, 0.498426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2990.91601562, 1567.0989843799998, 172.34679688), 'rotation':(0.505618, 0.846384, 0.496758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3013.03222656, 1567.42394531, 172.54056641), 'rotation':(0.493754, 0.846109, 0.485295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3029.62060547, 1567.66566406, 172.68361328), 'rotation':(0.492525, 0.846074, 0.484109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3035.14892578, 1567.74890625, 172.73123047), 'rotation':(0.492525, 0.846074, 0.484109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3046.20654297, 1567.91136719, 172.82601562), 'rotation':(0.487566, 0.845987, 0.479331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3051.86083984, 1560.1129296899999, 172.87314453), 'rotation':(-0.487579, -179.154007, -0.495911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3029.74414062, 1559.78796875, 172.68367188), 'rotation':(-0.493744, -179.153885, -0.502319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3024.21508789, 1559.7066796899999, 172.63601562), 'rotation':(-0.493744, -179.1539, -0.502319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3018.68579102, 1559.62546875, 172.58835938), 'rotation':(-0.4953, -179.153793, -0.503906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3013.15698242, 1559.5442968799998, 172.54064452999998), 'rotation':(-0.4953, -179.153793, -0.503906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2985.51171875, 1559.13820312, 172.29789062), 'rotation':(-0.507385, -179.153687, -0.516418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.4543457, 1558.9757031200002, 172.19978516), 'rotation':(-0.51413, -179.153687, -0.523438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2957.86743164, 1558.73195312, 172.05001953), 'rotation':(-0.523193, -179.153503, -0.532806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2946.80932617, 1558.5696874999999, 171.94828125), 'rotation':(-0.532196, -179.15332, -0.542175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2919.16723633, 1558.1440625, 171.68771484), 'rotation':(-0.547455, -179.153061, -0.557983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2908.11206055, 1557.87316406, 171.58117188), 'rotation':(-0.562958, -179.152771, -0.574097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3095.27832031, 1568.63234375, 173.23800781000003), 'rotation':(0.477669, 0.845561, 0.469753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3100.84179688, 1568.71398438, 173.28439453), 'rotation':(0.477382, 0.845554, 0.469479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3106.4050293, 1568.79578125, 173.33078125), 'rotation':(0.477382, 0.845554, 0.469479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3111.96826172, 1568.87742188, 173.37712890999998), 'rotation':(0.477246, 0.845537, 0.469346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3123.09472656, 1569.04089844, 173.46984375), 'rotation':(0.477341, 0.845538, 0.469437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3128.65795898, 1569.12269531, 173.51621093999998), 'rotation':(0.477253, 0.845563, 0.469351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3134.22119141, 1569.20445312, 173.56255859), 'rotation':(0.477253, 0.845563, 0.469351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3139.78442383, 1569.28613281, 173.60890625), 'rotation':(0.477246, 0.846297, 0.469337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3139.90356445, 1561.4063671899999, 173.60892578), 'rotation':(-0.477234, -179.154449, -0.485229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3134.34057617, 1561.3245703100001, 173.56259766), 'rotation':(-0.477356, -179.154449, -0.485352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3123.21386719, 1561.16113281, 173.46988281000003), 'rotation':(-0.477234, -179.154449, -0.485229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3106.52416992, 1560.91589844, 173.33082031), 'rotation':(-0.477692, -179.154434, -0.485687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3084.27099609, 1560.58898438, 173.14523438), 'rotation':(-0.477844, -179.154343, -0.48587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3250.00609375, 1563.02390625, 174.52642577999998), 'rotation':(-0.477753, -179.153671, -0.485779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3244.46070312, 1562.94238281, 174.48017578), 'rotation':(-0.477814, -179.154739, -0.48584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3238.91503906, 1562.86097656, 174.43390625), 'rotation':(-0.477814, -179.154007, -0.48584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.18847656, 1562.45359375, 174.20263672000002), 'rotation':(-0.4776, -179.154602, -0.485626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3205.64306641, 1562.3721875, 174.15638672), 'rotation':(-0.477142, -179.154617, -0.485168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3194.5525, 1562.20921875, 174.06400391), 'rotation':(-0.476959, -179.153473, -0.484955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3172.25195312, 1569.76320312, 173.87929688), 'rotation':(0.476945, 0.845607, 0.469056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.79710938, 1569.8446093799998, 173.92546875), 'rotation':(0.476945, 0.845607, 0.469056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3194.43359375, 1570.08898438, 174.06398438), 'rotation':(0.47715, 0.845372, 0.469253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3205.52417969, 1570.25195312, 174.15634766), 'rotation':(0.477628, 0.845379, 0.4697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.06957031, 1570.3333593799998, 174.20261718999998), 'rotation':(0.477813, 0.845985, 0.4699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3216.61474609, 1570.41480469, 174.24886718999997), 'rotation':(0.477901, 0.845987, 0.469988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3222.16015625, 1570.49632812, 174.29511718999998), 'rotation':(0.477901, 0.845987, 0.469988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3233.25074219, 1570.65929688, 174.38763672000002), 'rotation':(0.477813, 0.845985, 0.4699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3238.79613281, 1570.74070312, 174.43390625), 'rotation':(0.477813, 0.845985, 0.4699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3260.97412109, 1571.12621094, 174.61882812), 'rotation':(0.477328, 0.84492, 0.469423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3310.57910156, 1563.9139453100001, 175.03046875), 'rotation':(-0.47467, -179.154495, -0.482574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3321.96289062, 1564.08117188, 175.12451172000002), 'rotation':(-0.473083, -179.154251, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3327.65453125, 1564.16480469, 175.17152344), 'rotation':(-0.473053, -179.155197, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3333.34617188, 1564.24839844, 175.21847656000003), 'rotation':(-0.473053, -179.155197, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3339.03785156, 1564.33203125, 175.2653125), 'rotation':(-0.470459, -179.153976, -0.47821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3356.11328125, 1564.58289062, 175.40462890999999), 'rotation':(-0.46521, -179.154068, -0.472809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3361.80515625, 1564.66648438, 175.45072266), 'rotation':(-0.463531, -179.155396, -0.471069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3367.49683594, 1564.7501171899999, 175.49660156000002), 'rotation':(-0.462006, -179.154083, -0.469513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3373.18847656, 1564.83375, 175.54230468999998), 'rotation':(-0.460144, -179.155502, -0.46756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3378.880625, 1564.9173437499999, 175.58792968999998), 'rotation':(-0.459259, -179.154617, -0.466644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3401.64746094, 1565.25183594, 175.76927734), 'rotation':(-0.453094, -179.154663, -0.460297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3407.33910156, 1565.33546875, 175.81388672), 'rotation':(-0.449005, -179.154739, -0.456085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3413.0310156200003, 1565.4190625, 175.85818359), 'rotation':(-0.444916, -179.154785, -0.451874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3418.72265625, 1565.50269531, 175.90228516), 'rotation':(-0.444916, -179.154785, -0.451874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3424.41453125, 1565.5862890600001, 175.94626953), 'rotation':(-0.44281, -179.154602, -0.449707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.10621094, 1565.66992188, 175.99027343999998), 'rotation':(-0.442841, -179.155441, -0.449707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3435.79808594, 1565.7535546899999, 176.03394531), 'rotation':(-0.442841, -179.155441, -0.449707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3483.22703125, 1566.3206640600001, 176.37716797000002), 'rotation':(-0.401733, -179.155609, -0.40741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3464.14992188, 1574.05125, 176.24382812), 'rotation':(0.401902, 0.844423, 0.396293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3452.76636719, 1573.88414062, 176.16181641), 'rotation':(0.417222, 0.844333, 0.411187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3447.07496094, 1573.80054688, 176.11986328), 'rotation':(0.417222, 0.844333, 0.411187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3441.3830468799997, 1573.71691406, 176.07738281000002), 'rotation':(0.427454, 0.845253, 0.421107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.00046875, 1573.5496875, 175.99035156000002), 'rotation':(0.437644, 0.844615, 0.431003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3412.9253125, 1573.29882812, 175.85824218999997), 'rotation':(0.442822, 0.844527, 0.436014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3401.54175781, 1573.13160156, 175.76935547000002), 'rotation':(0.448996, 0.845266, 0.442007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3390.1584375, 1572.964375, 175.67914062), 'rotation':(0.453087, 0.845331, 0.445969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3367.39183594, 1572.62988281, 175.49667968999998), 'rotation':(0.460109, 0.845854, 0.452781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3361.69996094, 1572.5462499999999, 175.45080077999998), 'rotation':(0.462001, 0.84457, 0.454606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3333.24121094, 1572.12816406, 175.21857422000002), 'rotation':(0.470429, 0.846023, 0.462767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3327.54980469, 1572.04457031, 175.17160156000003), 'rotation':(0.472157, 0.844738, 0.464424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3299.09058594, 1571.62648438, 174.93621094), 'rotation':(0.475456, 0.845486, 0.467613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3293.39917969, 1571.5428515600001, 174.88892578), 'rotation':(0.475456, 0.845486, 0.467613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.06398438, 1110.59386719, 158.02313476999998), 'rotation':(-0.035675, 90.221283, -0.035736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.02710938, 1132.70361328, 158.01324219), 'rotation':(-0.002747, 90.223701, -0.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.005625, 1138.23193359, 158.01283203), 'rotation':(-0.002747, 90.223701, -0.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.96265625, 1149.2868652299999, 158.01231445), 'rotation':(-0.002747, 90.223717, -0.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.83351562, 1182.45263672, 158.01150391), 'rotation':(0.011345, 90.222633, 0.011335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2227.81179688, 1187.9803515600001, 158.01275391), 'rotation':(0.020873, 90.225052, 0.02086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.7903125000003, 1193.50804688, 158.01487305), 'rotation':(0.030094, 90.222641, 0.030065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.72585938, 1210.09130859, 158.02455078), 'rotation':(0.039718, 90.22242, 0.039664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.7043750000003, 1215.61962891, 158.0280957), 'rotation':(0.039718, 90.22242, 0.039664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.6396875, 1232.20203125, 158.04107421999998), 'rotation':(0.058849, 90.222466, 0.058732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.45554688, 1248.81591797, 158.05902344), 'rotation':(-0.068604, -89.777496, -0.068756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.54148438, 1226.70544922, 158.03631836), 'rotation':(-0.039703, -89.776123, -0.039764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.56320312, 1221.17773438, 158.03192382999998), 'rotation':(-0.039703, -89.776123, -0.039764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.6276562499997, 1204.59484375, 158.02121094), 'rotation':(-0.034943, -89.777191, -0.034973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.6706249999997, 1193.5390625, 158.01487305), 'rotation':(-0.020874, -89.777344, -0.020905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.69210938, 1188.01123047, 158.01275391), 'rotation':(-0.011353, -89.777344, -0.011353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.7135937499997, 1182.48351562, 158.01150391), 'rotation':(-0.001953, -89.777374, -0.001953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.7565624999997, 1171.42736328, 158.01125977), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.77804688, 1165.89990234, 158.01152344), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.82101562, 1154.84509766, 158.01204102), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.8428125, 1149.31762695, 158.01231445), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.86421875, 1143.7902832, 158.01257812), 'rotation':(0.002725, -89.776276, 0.002728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.9071875, 1132.73449219, 158.01324219), 'rotation':(0.007506, -89.776031, 0.007515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.97195312, 1116.15125, 158.01939453), 'rotation':(0.040401, -89.776611, 0.040344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.87695312, 1397.38441406, 158.39224609000001), 'rotation':(-0.193176, -89.776184, -0.194489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.94164062, 1380.7728124999999, 158.33839844), 'rotation':(-0.173309, -89.776306, -0.174347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.00632812, 1364.16125, 158.28930664), 'rotation':(-0.158112, -89.776398, -0.158997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.0278125, 1358.62316406, 158.2740332), 'rotation':(-0.155762, -89.776947, -0.156586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.07078125, 1347.54820312, 158.24412109000002), 'rotation':(-0.147552, -89.776398, -0.148315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.0924999999997, 1342.01125, 158.2297168), 'rotation':(-0.142303, -89.776428, -0.143005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.11398438, 1336.47386719, 158.21586914), 'rotation':(-0.137054, -89.776428, -0.137695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.1354687499997, 1330.9366406200002, 158.20254882999998), 'rotation':(-0.131653, -89.776489, -0.132233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.1571875, 1325.39941406, 158.18974609), 'rotation':(-0.126221, -89.776489, -0.12677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.17875, 1319.86230469, 158.17749023), 'rotation':(-0.120972, -89.77652, -0.12149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.2004687500003, 1314.32496094, 158.16577148), 'rotation':(-0.115723, -89.77655, -0.11618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.2221875, 1308.78673828, 158.15458984), 'rotation':(-0.113068, -89.777039, -0.113495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.24367188, 1303.24976562, 158.14367188), 'rotation':(-0.109467, -89.776428, -0.109863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.95359375, 1408.41992188, 158.42998047), 'rotation':(0.1977, 90.221619, 0.196342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.99679688, 1397.34570312, 158.39220703), 'rotation':(0.195822, 90.224083, 0.194483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.03976562, 1386.27148438, 158.35577148000002), 'rotation':(0.183227, 90.223732, 0.182074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.14773438, 1358.58558594, 158.27400391), 'rotation':(0.158133, 90.223595, 0.15727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2227.19070312, 1347.51085938, 158.24411133), 'rotation':(0.152962, 90.22361, 0.152166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.21242188, 1341.97386719, 158.22970703000001), 'rotation':(0.147553, 90.223587, 0.1468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.23390625, 1336.4368749999999, 158.21584961), 'rotation':(0.1423, 90.223564, 0.141602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.25539062, 1330.89964844, 158.2025293), 'rotation':(0.137055, 90.223534, 0.136402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2227.34179688, 1308.75048828, 158.15457031), 'rotation':(0.115703, 90.223442, 0.115252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.50414062, 1523.93601562, 158.92296875), 'rotation':(0.29335, 90.225304, 0.290361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.5903125, 1501.78078125, 158.81564453000001), 'rotation':(0.274273, 90.22422, 0.271659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.61179688, 1496.24121094, 158.78916992), 'rotation':(0.274382, 90.224228, 0.271766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.63328125, 1490.70265625, 158.763125), 'rotation':(0.269362, 90.22467, 0.266843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.6549999999997, 1485.16359375, 158.73744141), 'rotation':(0.269362, 90.22467, 0.266843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.7196875, 1468.54734375, 158.66375976999998), 'rotation':(0.249671, 90.224503, 0.247506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.74125, 1463.0084375000001, 158.64054688), 'rotation':(0.239781, 90.224396, 0.237772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.805625, 1446.39097656, 158.57209961), 'rotation':(0.234829, 90.222237, 0.232911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.8489062500003, 1435.31347656, 158.52801757999998), 'rotation':(0.230082, 90.224419, 0.228255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.70773438, 1440.89074219, 158.54988280999999), 'rotation':(-0.220551, -89.777222, -0.22226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.59984375, 1468.58628906, 158.66379883), 'rotation':(-0.239777, -89.777069, -0.241791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.578125, 1474.125, 158.68792969), 'rotation':(-0.249664, -89.775482, -0.251862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.5134375, 1490.74195312, 158.76316406), 'rotation':(-0.259491, -89.775421, -0.261841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.49195312, 1496.2806249999999, 158.78921875), 'rotation':(-0.269379, -89.77533, -0.271912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.47046875, 1501.82019531, 158.81569336), 'rotation':(-0.274384, -89.775757, -0.277008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.44875, 1507.35902344, 158.84220703), 'rotation':(-0.274384, -89.775757, -0.277008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.42726562, 1512.89769531, 158.86873047), 'rotation':(-0.274261, -89.775757, -0.276917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.3410937500003, 1535.0538281200002, 158.97952148000002), 'rotation':(-0.293335, -89.776733, -0.296356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.8371875000003, 1689.09421875, 159.88907226999999), 'rotation':(0.375879, 90.226173, 0.370971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.88257812, 1683.56515625, 159.85294922), 'rotation':(0.373686, 90.225388, 0.368851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.92554688, 1672.5032031199999, 159.78170898), 'rotation':(0.369329, 90.225342, 0.364597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.94703125, 1666.9720312499999, 159.74664062), 'rotation':(0.364821, 90.225281, 0.360207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.96875, 1661.4409375, 159.71188476999998), 'rotation':(0.360613, 90.225227, 0.356098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.01171875, 1650.3790234399999, 159.64268555), 'rotation':(0.358414, 90.224739, 0.353953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.03320312, 1644.84839844, 159.6080957), 'rotation':(0.358312, 90.226143, 0.353861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.0546875, 1639.316875, 159.57365234), 'rotation':(0.358312, 90.226143, 0.353861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.09789062, 1628.25488281, 159.5055957), 'rotation':(0.349965, 90.225601, 0.345711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.14109375, 1617.1927343799998, 159.43887695), 'rotation':(0.344412, 90.225517, 0.340286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.24851562, 1589.53675781, 159.27683594), 'rotation':(0.332849, 90.225357, 0.328995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.27023438, 1584.00585938, 159.24533203000001), 'rotation':(0.326497, 90.225281, 0.322788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.83742188, 1694.67015625, 159.92544922), 'rotation':(-0.375885, -89.775665, -0.380829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.76265625, 1683.61109375, 159.85305664), 'rotation':(-0.369324, -89.774658, -0.374146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.8271875, 1667.01734375, 159.74673828000002), 'rotation':(-0.360596, -89.77478, -0.365173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.8918750000003, 1650.4240625, 159.64277344), 'rotation':(-0.358337, -89.775238, -0.362823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.91335938, 1644.8928125, 159.60817383), 'rotation':(-0.355621, -89.774323, -0.360046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.9348437500003, 1639.36132812, 159.57375), 'rotation':(-0.355621, -89.774323, -0.360046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.95632812, 1633.83007812, 159.53946288999998), 'rotation':(-0.349945, -89.774414, -0.354248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.97828125, 1628.2990625, 159.50567383), 'rotation':(-0.344421, -89.776123, -0.348572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.99976562, 1622.7678125, 159.4721875), 'rotation':(-0.344421, -89.776123, -0.348572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.04273438, 1611.70554688, 159.40623047), 'rotation':(-0.33606, -89.774811, -0.340027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.0859375, 1600.64269531, 159.3412207), 'rotation':(-0.332855, -89.774628, -0.336731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.10742188, 1595.11109375, 159.30900391), 'rotation':(-0.332855, -89.774628, -0.336731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.12890625, 1589.57996094, 159.27691406), 'rotation':(-0.326477, -89.776245, -0.330231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.21507812, 1567.45507812, 159.15275391), 'rotation':(-0.313751, -89.774841, -0.3172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.39992188, 1793.69265625, 160.58720703), 'rotation':(0.391664, 90.226212, 0.386342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.4753124999997, 1788.1365624999999, 160.54926758), 'rotation':(0.391664, 90.226212, 0.386342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.49703125, 1782.5774999999999, 160.51136719), 'rotation':(0.390578, 90.225739, 0.385283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.58375, 1760.3415625, 160.36125), 'rotation':(0.384403, 90.225647, 0.379272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.60523438, 1754.7821875, 160.32400391), 'rotation':(0.383474, 90.225929, 0.37836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.62695312, 1749.2233593800001, 160.28680664), 'rotation':(0.383474, 90.225929, 0.37836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.67015625, 1738.10546875, 160.21240234), 'rotation':(0.383474, 90.225929, 0.37836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2225.61234375, 1732.5503125, 160.17529297), 'rotation':(0.382415, 90.227104, 0.377336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.55054688, 1738.1403906199998, 160.21243164), 'rotation':(-0.382416, -89.775055, -0.387543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.4206249999997, 1771.50148438, 160.43612305), 'rotation':(-0.386505, -89.774323, -0.391754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.35570312, 1788.18210938, 160.54936523), 'rotation':(-0.390564, -89.774261, -0.395935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.38820312, 1793.74, 160.58731445), 'rotation':(-0.390564, -89.774261, -0.395935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2216.28367188, 1897.6, 160.99893555), 'rotation':(0.034506, 101.403885, 0.03447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2218.27046875, 1886.64367188, 160.99226562), 'rotation':(0.034513, 100.187187, 0.034464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2220.06859375, 1875.64296875, 160.98526367), 'rotation':(0.034506, 98.975456, 0.034475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2224.01078125, 1842.4446093800002, 160.87428711), 'rotation':(0.261528, 94.631805, 0.259147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2224.73898438, 1831.37453125, 160.82224609000002), 'rotation':(0.281588, 93.289124, 0.278825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.3090625, 1859.38851562, 160.94558594), 'rotation':(-0.213623, -83.589966, -0.21521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2229.6496875000003, 1864.92875, 160.96362305), 'rotation':(-0.185822, -83.227203, -0.187042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.92578125, 1870.44921875, 160.97658203), 'rotation':(-0.130524, -82.496033, -0.131104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.13695312, 1875.95945312, 160.98453125), 'rotation':(-0.074921, -81.768494, -0.075104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.36328125, 1886.93859375, 160.99161132999998), 'rotation':(-0.033386, -80.210571, -0.033447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2225.37820312, 1892.4172656199999, 160.99489258), 'rotation':(-0.033661, -79.813599, -0.033691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2207.6510937499997, 1950.12460938, 161.06849609), 'rotation':(0.128899, 96.306984, 0.128316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2206.60617188, 1960.5782812500001, 161.09323242), 'rotation':(0.152771, 95.000145, 0.15195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2206.1706249999997, 1965.8146875, 161.10804688), 'rotation':(0.172046, 94.433807, 0.171016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2205.46898438, 1976.2834375, 161.14335938), 'rotation':(0.219693, 93.011032, 0.218008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2204.6996875, 1991.9815625, 161.21067383), 'rotation':(0.277162, 91.31089, 0.27449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2204.60476562, 1997.20015625, 161.23632812), 'rotation':(0.285229, 90.59446, 0.2824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2212.62476562, 1997.68125, 161.23826172), 'rotation':(-0.289032, -89.262756, -0.291962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2212.89648438, 1986.3001562499999, 161.18304688), 'rotation':(-0.254608, -87.839233, -0.256866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2213.51414062, 1974.9060937499999, 161.13650391), 'rotation':(-0.205383, -86.418457, -0.206848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2214.40695312, 1963.51757812, 161.09939453), 'rotation':(-0.156555, -85.00116, -0.15741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2214.9196875, 1957.83164062, 161.08439453), 'rotation':(-0.137177, -84.438354, -0.137817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2216.005625, 1946.4609375, 161.05802734), 'rotation':(-0.131836, -82.888489, -0.132446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2217.50320312, 1935.1646875000001, 161.03369141), 'rotation':(-0.103912, -81.694, -0.104279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2218.3528125000003, 1929.5325, 161.02419921999999), 'rotation':(-0.079346, -80.843689, -0.079559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.82300781, 1104.40014648, 163.40893555), 'rotation':(0.089981, 89.222206, 0.089707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.12304688, 1126.50353516, 163.44755859), 'rotation':(0.120389, 89.222313, 0.119881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.348125, 1143.08019531, 163.48399414), 'rotation':(0.139199, 89.222206, 0.138535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.49828125, 1154.13232422, 163.51120117), 'rotation':(0.145251, 89.220901, 0.144533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.72363281, 1170.70910156, 163.55578125), 'rotation':(0.169184, 89.222427, 0.16818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2523.87402344, 1181.75976562, 163.58886719), 'rotation':(0.181102, 89.2211, 0.179962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2524.099375, 1198.33728516, 163.64222656), 'rotation':(0.191006, 89.223885, 0.189742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2524.39964844, 1220.44019531, 163.72072265999998), 'rotation':(0.221018, 89.224098, 0.21933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2524.70019531, 1242.54236328, 163.81130859), 'rotation':(0.247526, 89.221725, 0.245399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2525.00046875, 1264.64476562, 163.90998047000002), 'rotation':(0.272443, 89.224251, 0.26986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.95554688, 1270.0646875, 163.93626953), 'rotation':(-0.27243, -90.77771, -0.275055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.88039062, 1264.5391796899999, 163.90998047000002), 'rotation':(-0.262482, -90.777802, -0.264893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.80515625, 1259.01367188, 163.88439452999998), 'rotation':(-0.252533, -90.777893, -0.254761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.73, 1253.48791016, 163.85949218999997), 'rotation':(-0.252533, -90.777893, -0.254761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.4294531200003, 1231.38525391, 163.76456055), 'rotation':(-0.228699, -90.775818, -0.23056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.27929688, 1220.33447266, 163.72072265999998), 'rotation':(-0.213684, -90.778625, -0.215302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.12914062, 1209.28246094, 163.67995117), 'rotation':(-0.198334, -90.778717, -0.199738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.97898438, 1198.23121094, 163.64222656), 'rotation':(-0.187103, -90.77829, -0.188354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.82859375, 1187.17882812, 163.60633789), 'rotation':(-0.181122, -90.777496, -0.182251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.67847656, 1176.12792969, 163.57209961), 'rotation':(-0.169189, -90.777588, -0.170197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.52832031, 1165.07726562, 163.54039062), 'rotation':(-0.157196, -90.779053, -0.158051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.4533593799997, 1159.551875, 163.52522461), 'rotation':(-0.145264, -90.777679, -0.145996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.22804688, 1142.97363281, 163.48399414), 'rotation':(-0.135498, -90.777588, -0.136169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.15308594, 1137.448125, 163.47113281), 'rotation':(-0.127808, -90.777649, -0.128387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.0778906200003, 1131.92236328, 163.45898438), 'rotation':(-0.120392, -90.777679, -0.120911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.00292969, 1126.39708984, 163.44755859), 'rotation':(-0.112671, -90.780151, -0.113129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.85277344, 1115.34460938, 163.42681641), 'rotation':(-0.097717, -90.777771, -0.098022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.77757812, 1109.81921875, 163.4175293), 'rotation':(-0.089966, -90.780273, -0.090271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.70265625, 1104.29345703, 163.40893555), 'rotation':(-0.082581, -90.777771, -0.082794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2530.63890625, 1098.76977539, 163.40099609), 'rotation':(-0.078796, -90.778503, -0.07901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.66699219, 1093.24511719, 163.3934375), 'rotation':(-0.078674, -90.778503, -0.078888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.04003906, 1308.62132812, 164.12814453), 'rotation':(-0.259857, -87.638733, -0.262207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.8246875, 1324.91931641, 164.195625), 'rotation':(-0.218689, -84.470062, -0.220367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.21921875, 1330.3836718799998, 164.21576172000002), 'rotation':(-0.207214, -83.566406, -0.20874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.37425781, 1335.81605469, 164.23462891), 'rotation':(-0.189697, -82.209839, -0.190948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.67015625, 1352.17542969, 164.28654297), 'rotation':(-0.16214, -79.463654, -0.163055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.5746875, 1357.58386719, 164.30039062), 'rotation':(-0.132629, -78.064941, -0.13324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2525.38011719, 1362.984375, 164.31216797000002), 'rotation':(-0.112823, -77.132965, -0.113281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2524.09132812, 1368.35765625, 164.32185547), 'rotation':(-0.093384, -76.196655, -0.093689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.73144531, 1373.7037500000001, 164.32933594), 'rotation':(-0.073608, -75.267761, -0.073792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2521.3669531200003, 1379.03808594, 164.33474609), 'rotation':(-0.054169, -74.335327, -0.05426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2519.80371094, 1384.28648438, 164.33818359), 'rotation':(-0.029297, -72.93927, -0.029327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2514.58835938, 1399.7662500000001, 164.34660156), 'rotation':(-0.029663, -70.221558, -0.029694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.703125, 1324.03064453, 164.19537109), 'rotation':(0.221387, 95.982758, 0.219665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.08960938, 1329.56007812, 164.21628906), 'rotation':(0.209099, 96.887283, 0.207582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.37207031, 1335.10351562, 164.2359375), 'rotation':(0.193793, 98.191063, 0.192492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2519.5859375, 1351.70628906, 164.28949218999998), 'rotation':(0.147962, 101.469421, 0.147196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2511.25683594, 1384.2493749999999, 164.33951172000002), 'rotation':(0.030463, 107.968842, 0.030427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2507.723125, 1394.73082031, 164.34535156), 'rotation':(0.030838, 109.778976, 0.030804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2496.47972656, 1474.3131250000001, 164.5715625), 'rotation':(-0.367218, -83.103485, -0.371948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.46046875, 1507.83484375, 164.83060547000002), 'rotation':(-0.486145, -89.519745, -0.494446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.45898438, 1513.3665624999999, 164.87867188), 'rotation':(-0.493134, -89.890747, -0.501678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.4665625, 1518.8721875, 164.92705078), 'rotation':(-0.503235, -90.076111, -0.512115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.47460938, 1524.37390625, 164.97814452999998), 'rotation':(-0.534851, -90.075531, -0.544891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.42308594, 1529.8746484399999, 165.02988281), 'rotation':(-0.534851, -90.075531, -0.544891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.35277344, 1540.87390625, 165.13556641), 'rotation':(-0.550476, -90.074341, -0.561127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.32664062, 1540.52964844, 165.13214843999998), 'rotation':(0.550486, 89.925629, 0.539985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.31910156, 1534.99097656, 165.07892578), 'rotation':(0.550486, 89.925629, 0.539985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.29566406, 1518.37109375, 164.92253906000002), 'rotation':(0.534838, 89.924461, 0.524928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.43945312, 1507.2940625, 164.82654297000002), 'rotation':(0.475005, 90.105095, 0.467166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.99632812, 1490.7178906200002, 164.69765625), 'rotation':(0.423943, 93.199463, 0.41771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2488.42039062, 1474.1517187499999, 164.57648438), 'rotation':(0.384751, 96.207191, 0.379616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2489.08519531, 1468.6640625, 164.54216797), 'rotation':(0.337965, 97.250694, 0.333996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2490.55640625, 1457.7265625, 164.48677734), 'rotation':(0.244364, 99.338486, 0.242295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2491.50074219, 1452.31410156, 164.46560547), 'rotation':(0.198007, 100.382851, 0.196638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.51734375, 1573.1596875, 165.45175781), 'rotation':(0.576536, 89.925896, 0.565035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.54078125, 1589.76246094, 165.61888672), 'rotation':(0.578592, 89.926605, 0.567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.54835938, 1595.29640625, 165.67490234000002), 'rotation':(0.583052, 89.926704, 0.571277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.57152344, 1611.89867188, 165.84556641), 'rotation':(0.595756, 89.924332, 0.583459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.59472656, 1628.5008593799998, 166.02011718999998), 'rotation':(0.610913, 89.92662, 0.597978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.60230469, 1634.03539062, 166.07904297000002), 'rotation':(0.610913, 89.92662, 0.597978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.61011719, 1639.56933594, 166.13806641), 'rotation':(0.613126, 89.925087, 0.600118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.63328125, 1656.17140625, 166.31626953), 'rotation':(0.622121, 89.926735, 0.608716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.64109375, 1661.70546875, 166.37615234), 'rotation':(0.622121, 89.926735, 0.608716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.65671875, 1672.7734375, 166.49667968999998), 'rotation':(0.626588, 89.926834, 0.612981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.68015625, 1689.3752343800002, 166.67871093999997), 'rotation':(0.629648, 89.926201, 0.615919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.60644531, 1694.90734375, 166.73949219), 'rotation':(0.631226, 89.928078, 0.617438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.40550781, 1578.68554688, 165.50748047000002), 'rotation':(-0.576538, -90.074097, -0.588226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.41332031, 1584.21949219, 165.56316406000002), 'rotation':(-0.576569, -90.074097, -0.588257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.42113281, 1589.75414062, 165.61890625), 'rotation':(-0.576569, -90.074097, -0.588257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.44433594, 1606.3565625, 165.78826172), 'rotation':(-0.587189, -90.075836, -0.599304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.45214844, 1611.8905078100001, 165.84560547), 'rotation':(-0.591644, -90.07312, -0.603943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.45996094, 1617.42480469, 165.90333984), 'rotation':(-0.595764, -90.075684, -0.608246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.46777344, 1622.95886719, 165.96152343999998), 'rotation':(-0.60434, -90.072845, -0.617188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.49878906, 1645.09570312, 166.19730468999998), 'rotation':(-0.613129, -90.073425, -0.626343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.51414062, 1656.16367188, 166.31630859), 'rotation':(-0.617584, -90.074799, -0.631012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.52976562, 1667.23171875, 166.43628906), 'rotation':(-0.622131, -90.073242, -0.635773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.53757812, 1672.7657812500001, 166.49669922), 'rotation':(-0.622131, -90.073242, -0.635773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.55320312, 1683.83375, 166.61798828), 'rotation':(-0.628754, -90.072876, -0.64267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.82226562, 1790.69351562, 167.80066406000003), 'rotation':(0.632059, 89.92717, 0.618231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.72828125, 1797.2459374999999, 167.87294922), 'rotation':(0.627804, 89.927086, 0.61415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.80347656, 1777.29882812, 167.65240234), 'rotation':(0.634053, 89.926292, 0.620148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.79566406, 1771.74109375, 167.59089844), 'rotation':(0.634053, 89.926292, 0.620148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.78003906, 1760.62546875, 167.46779297), 'rotation':(0.634723, 89.926537, 0.620779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.74878906, 1738.39453125, 167.22087890999998), 'rotation':(0.636642, 89.925644, 0.622625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.74097656, 1732.83703125, 167.15914062), 'rotation':(0.636662, 89.92804, 0.622626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.62183594, 1732.82679688, 167.15914062), 'rotation':(-0.636627, -90.074341, -0.650909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.62964844, 1738.384375, 167.22089843999998), 'rotation':(-0.636688, -90.07196, -0.65094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.63746094, 1743.94234375, 167.28267577999998), 'rotation':(-0.636627, -90.074341, -0.650909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.65308594, 1755.05773438, 167.40615234), 'rotation':(-0.636078, -90.073425, -0.650299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.66089844, 1760.61546875, 167.4678125), 'rotation':(-0.636078, -90.073425, -0.650299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.67625, 1771.7309375, 167.59089844), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.6840625, 1777.28867188, 167.65242188), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.6996875, 1788.40414062, 167.77544922), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.75902344, 1793.95945312, 167.83681640999998), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.85082031, 1843.0080468800002, 168.36923828), 'rotation':(0.614369, 89.925415, 0.601287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.93457031, 1870.8157812499999, 168.66310547), 'rotation':(0.593612, 89.925804, 0.581418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.95019531, 1881.9407031199999, 168.77835938), 'rotation':(0.589896, 89.925476, 0.577852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.9409375, 1887.50171875, 168.83587891), 'rotation':(0.589896, 89.925476, 0.577852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.8471875, 1900.8282812500001, 168.97150391), 'rotation':(0.567923, 89.925041, 0.556755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.89210938, 1837.4353125, 168.30931640999998), 'rotation':(-0.61731, -90.074402, -0.630737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.82105469, 1842.9967968800001, 168.36923828), 'rotation':(-0.61731, -90.072876, -0.630737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.83105469, 1881.93203125, 168.77837891), 'rotation':(-0.593597, -90.074188, -0.606018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.92652344, 1893.0548437500001, 168.89300781000003), 'rotation':(-0.589874, -90.074493, -0.602142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.98558594, 1899.79796875, 168.96126952999998), 'rotation':(-0.582581, -90.074646, -0.594513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.9396875, 1930.81726562, 169.26294922), 'rotation':(0.549393, 90.632812, 0.538924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.61816406, 1941.96984375, 169.36742188), 'rotation':(0.506288, 91.972, 0.497402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2485.8049218799997, 1958.70273438, 169.50408202999998), 'rotation':(0.421272, 93.823685, 0.415111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2484.42675781, 1975.40273438, 169.61542968999998), 'rotation':(0.354125, 95.942574, 0.349767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2483.84449219, 1980.94679688, 169.64974609), 'rotation':(0.347657, 96.479561, 0.343463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2482.63476562, 1992.0193749999999, 169.71240234), 'rotation':(0.281493, 97.864281, 0.278739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.86914062, 1931.1071875, 169.26501953), 'rotation':(-0.536255, -89.654449, -0.546356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.7846875, 1936.64734375, 169.31693359000002), 'rotation':(-0.530426, -88.821777, -0.540314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.640625, 1942.19875, 169.36720703), 'rotation':(-0.506836, -88.295349, -0.515869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.16648438, 1953.2967187499999, 169.45929688), 'rotation':(-0.446991, -86.972412, -0.454041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2493.83863281, 1958.8483593800001, 169.50134766), 'rotation':(-0.423065, -86.439209, -0.429352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2493.4475, 1964.3939062499999, 169.54044922), 'rotation':(-0.399536, -85.911377, -0.405121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2492.99804688, 1969.92539062, 169.576875), 'rotation':(-0.363983, -85.119476, -0.368622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2492.48585938, 1975.45859375, 169.61089843999997), 'rotation':(-0.346252, -84.593323, -0.350433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2491.9142968799997, 1980.9728906199998, 169.64453125), 'rotation':(-0.345886, -83.793488, -0.350067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2489.98265625, 1997.4719531199999, 169.73371093999998), 'rotation':(-0.274933, -82.135223, -0.277588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.77954102, 1318.23621094, 169.46904297), 'rotation':(0.331599, 90.098579, 0.32778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.76977539, 1323.83044922, 169.50121094), 'rotation':(0.338456, 90.101265, 0.334486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.72167969, 1351.80210938, 169.67253906000002), 'rotation':(0.372559, 90.101677, 0.367748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.71191406, 1357.39613281, 169.70890625), 'rotation':(0.3762, 90.099442, 0.371272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.70263672, 1362.99070312, 169.74564453), 'rotation':(0.380141, 90.102409, 0.375125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.68334961, 1374.17921875, 169.81992188), 'rotation':(0.388146, 90.100624, 0.382907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.6640625, 1385.3671875, 169.89644531000002), 'rotation':(0.40406, 90.100861, 0.398372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.63525391, 1402.14992188, 170.01552734), 'rotation':(0.415474, 90.1017, 0.409487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.62573242, 1407.74367188, 170.05609375), 'rotation':(0.415303, 90.098938, 0.409312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.50610352, 1407.76039062, 170.05611327999998), 'rotation':(-0.415466, -89.898285, -0.421539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.515625, 1402.16675781, 170.01554688), 'rotation':(-0.411804, -89.898865, -0.417755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.53491211, 1390.97789062, 169.93564453), 'rotation':(-0.396027, -89.899231, -0.40155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.56347656, 1374.19566406, 169.81996094), 'rotation':(-0.380127, -89.899475, -0.385223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.57324219, 1368.60144531, 169.78261719), 'rotation':(-0.376221, -89.898743, -0.381165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.58276367, 1363.00683594, 169.74564453), 'rotation':(-0.376221, -89.898743, -0.381165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.59228516, 1357.41234375, 169.70894531000002), 'rotation':(-0.372589, -89.898285, -0.377441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.60180664, 1351.81824219, 169.67257812), 'rotation':(-0.365906, -89.901001, -0.370575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.61157227, 1346.22398438, 169.63689452999998), 'rotation':(-0.359009, -89.898499, -0.363525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.640625, 1329.44042969, 169.53408202999998), 'rotation':(-0.33847, -89.898712, -0.342468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.67895508, 1307.06347656, 169.40609375), 'rotation':(-0.32135, -89.8992, -0.324982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.51220703, 1474.0006250000001, 170.57027344), 'rotation':(0.481399, 90.101082, 0.473354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.50268555, 1479.59875, 170.61654297), 'rotation':(0.481399, 90.101082, 0.473354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.49316406, 1485.19664062, 170.66359375), 'rotation':(0.491036, 90.102661, 0.482655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.47387695, 1496.39292969, 170.75902344), 'rotation':(0.495783, 90.104462, 0.487253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.46411133, 1501.9913281200002, 170.80732422), 'rotation':(0.495708, 90.102058, 0.487197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.42578125, 1524.3836718799998, 171.00386719), 'rotation':(0.515925, 90.101906, 0.50669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.40649414, 1535.57960938, 171.10490234), 'rotation':(0.52488, 90.102058, 0.515313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.39697266, 1541.1775, 171.15611328), 'rotation':(0.529258, 90.102135, 0.519548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.28735352, 1535.59742188, 171.10494140999998), 'rotation':(-0.520142, -89.89801, -0.529663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.30639648, 1524.40148438, 171.00390625), 'rotation':(-0.511383, -89.898193, -0.520569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.33496094, 1507.60742188, 170.85589843999998), 'rotation':(-0.495728, -89.897949, -0.504364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.37353516, 1485.21398438, 170.66363281000002), 'rotation':(-0.481384, -89.898926, -0.489532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.38305664, 1479.61597656, 170.61658203), 'rotation':(-0.471924, -89.897644, -0.479767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.46606445, 1448.6221875, 170.36542968999998), 'rotation':(-0.453857, -89.898682, -0.46106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.33154297, 1579.4096875, 171.51480468999998), 'rotation':(0.557541, 90.104034, 0.54678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.32177734, 1584.99839844, 171.56886719), 'rotation':(0.557541, 90.104034, 0.54678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.31225586, 1590.58691406, 171.62326172000002), 'rotation':(0.561674, 90.10321, 0.550755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.2644043, 1618.53050781, 171.89820312), 'rotation':(0.569221, 90.103195, 0.557992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.25488281, 1624.11902344, 171.95373047), 'rotation':(0.572158, 90.103264, 0.560818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.24707031, 1629.70851562, 172.00953125), 'rotation':(0.575198, 90.105049, 0.563735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.2355957, 1635.2962499999999, 172.06546875), 'rotation':(0.575198, 90.105049, 0.563735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.22607422, 1640.88476562, 172.1215625), 'rotation':(0.57683, 90.102722, 0.565301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.20703125, 1652.06273438, 172.23445312), 'rotation':(0.584651, 90.10421, 0.572824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.1875, 1663.23984375, 172.34912109), 'rotation':(0.595388, 90.104424, 0.583123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.17797852, 1668.82859375, 172.40720703), 'rotation':(0.600469, 90.10453, 0.58797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.16845703, 1674.41710938, 172.46582031000003), 'rotation':(0.605838, 90.10466, 0.593115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.15893555, 1680.00570312, 172.52494141), 'rotation':(0.61122, 90.104774, 0.598291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.14916992, 1685.5944531199998, 172.58455078), 'rotation':(0.616418, 90.104866, 0.603263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.00146484, 1702.38546875, 172.76558594), 'rotation':(-0.619141, -89.895355, -0.632629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.02050781, 1691.2077343800001, 172.64478516), 'rotation':(-0.616425, -89.895142, -0.629822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.03979492, 1680.0306249999999, 172.52505859000001), 'rotation':(-0.605835, -89.895355, -0.618744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.06835938, 1663.2646875, 172.34923827999998), 'rotation':(-0.589874, -89.895691, -0.602112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.078125, 1657.6759375000001, 172.29164062), 'rotation':(-0.584656, -89.895782, -0.59668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.08764648, 1652.08742188, 172.23455077999998), 'rotation':(-0.579437, -89.895874, -0.591248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.11645508, 1635.32007812, 172.06556641), 'rotation':(-0.572174, -89.894989, -0.583679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.12597656, 1629.73144531, 172.00960938), 'rotation':(-0.572174, -89.894989, -0.583679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.14526367, 1618.55445312, 171.89832031000003), 'rotation':(-0.566071, -89.896851, -0.577332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.93579102, 1740.66171875, 173.17923828), 'rotation':(-0.619049, -89.894409, -0.632538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.88769531, 1768.72875, 173.48373047), 'rotation':(-0.624908, -89.894989, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.87817383, 1774.34226562, 173.54511718999998), 'rotation':(-0.624908, -89.894989, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.84936523, 1791.18234375, 173.72976562), 'rotation':(-0.62851, -89.894836, -0.642395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.84936523, 1796.79421875, 173.79132812), 'rotation':(-0.628387, -89.894836, -0.642303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.06469727, 1735.03609375, 173.11859375), 'rotation':(0.619136, 90.104073, 0.605865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.05493164, 1740.64953125, 173.17925781000002), 'rotation':(0.619136, 90.104073, 0.605865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.03588867, 1751.87648438, 173.30066406000003), 'rotation':(0.62027, 90.104919, 0.60696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.02612305, 1757.49, 173.36150390999998), 'rotation':(0.622585, 90.104958, 0.609177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.01660156, 1763.10351562, 173.42251953), 'rotation':(0.624908, 90.105003, 0.611401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.00683594, 1768.71679688, 173.48375), 'rotation':(0.627209, 90.105064, 0.613611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2879.98779297, 1779.94382812, 173.60662109), 'rotation':(0.628487, 90.105148, 0.614817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.97802734, 1785.55726562, 173.66820312), 'rotation':(0.628405, 90.105156, 0.61474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2879.96850586, 1791.17054688, 173.72978516), 'rotation':(0.628405, 90.105156, 0.61474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.88378906, 1840.58359375, 174.27242188), 'rotation':(0.628705, 90.106033, 0.615025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.80493164, 1851.8201562499999, 174.39560547000002), 'rotation':(0.626683, 90.104507, 0.613102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.69091797, 1868.6751562499999, 174.57960938), 'rotation':(0.622988, 90.105896, 0.609554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.68115234, 1874.2932031199998, 174.64068359), 'rotation':(0.621691, 90.097359, 0.608311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2879.59741211, 1885.57226562, 174.76392578), 'rotation':(0.627059, 91.301765, 0.613442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.13720703, 1902.48265625, 174.94585938), 'rotation':(0.603789, 93.129616, 0.59117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.8996582, 1846.27609375, 174.33474609), 'rotation':(-0.628723, -89.895447, -0.642639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.88037109, 1857.5378125, 174.45802734), 'rotation':(-0.626678, -89.895477, -0.640503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.81445312, 1863.1647656199998, 174.51941406000003), 'rotation':(-0.624939, -89.894043, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.74609375, 1868.79421875, 174.58074219), 'rotation':(-0.624939, -89.894043, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.39306641, 1896.8759375, 174.88289062), 'rotation':(-0.603546, -87.970642, -0.616364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2874.953125, 1945.20617188, 175.3803125), 'rotation':(0.555813, 98.268021, 0.54512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2874.19702148, 1950.45078125, 175.43162109000002), 'rotation':(0.550773, 98.647171, 0.540273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2873.38134766, 1955.69796875, 175.48226562), 'rotation':(0.54119, 99.410355, 0.531047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2870.75537109, 1971.33773438, 175.62851562), 'rotation':(0.52001, 99.599358, 0.510641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2869.87475586, 1976.54773438, 175.67646484), 'rotation':(0.520016, 99.59951, 0.510646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2868.99414062, 1981.7575781199998, 175.72443359000002), 'rotation':(0.519784, 99.600815, 0.510419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2867.37548828, 1992.20101562, 175.82011719), 'rotation':(0.516711, 99.599762, 0.507449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2866.49462891, 1997.41101562, 175.86777343999998), 'rotation':(0.510113, 99.59996, 0.501098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2878.10351562, 1976.88632812, 175.66705077999998), 'rotation':(-0.52002, -80.398804, -0.52951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2878.88476562, 1971.65054688, 175.61900391), 'rotation':(-0.526093, -80.401428, -0.535828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2881.45727539, 1956.01320312, 175.47324218999998), 'rotation':(-0.537994, -81.353485, -0.548157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2883.00390625, 1945.5788281199998, 175.37322265999998), 'rotation':(-0.552521, -82.492126, -0.563263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3160.40722656, 1309.49841797, 172.73232422), 'rotation':(0.194736, 90.642365, 0.193411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.28051758, 1320.81921875, 172.77082031), 'rotation':(0.196839, 90.640884, 0.195482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.15405273, 1332.1397656200002, 172.80988281), 'rotation':(0.201231, 90.640923, 0.199818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.09057617, 1337.80003906, 172.82976562), 'rotation':(0.205343, 90.640953, 0.20388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.96411133, 1349.120625, 172.87021484000002), 'rotation':(0.209748, 90.642403, 0.208214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.64794922, 1377.42234375, 172.97482422000002), 'rotation':(0.216858, 90.639664, 0.215225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.58447266, 1383.08289062, 172.99623047), 'rotation':(0.218614, 90.64225, 0.216965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3159.45800781, 1394.4034375, 173.03966797), 'rotation':(0.222487, 90.642303, 0.220765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.33129883, 1405.72386719, 173.08390625), 'rotation':(0.226516, 90.642311, 0.224739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3159.078125, 1428.36535156, 173.17416015999999), 'rotation':(0.233524, 90.64119, 0.231621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.95166016, 1439.68601562, 173.22048827999998), 'rotation':(0.237472, 90.64122, 0.235514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.76171875, 1456.66699219, 173.2915625), 'rotation':(0.243537, 90.642624, 0.241475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3158.69848633, 1462.32714844, 173.315625), 'rotation':(0.245675, 90.64167, 0.243576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.63500977, 1467.9876562499999, 173.33974609), 'rotation':(0.245675, 90.64167, 0.243576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.50854492, 1479.308125, 173.38857422), 'rotation':(0.250162, 90.641701, 0.247989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.12890625, 1513.2698828100001, 173.54056641), 'rotation':(0.263481, 90.642578, 0.261064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3158.06567383, 1518.93015625, 173.56650391), 'rotation':(0.263481, 90.642578, 0.261064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.00219727, 1524.5903125, 173.59253906), 'rotation':(0.268085, 90.641144, 0.265583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.8125, 1541.5711718799998, 173.67248047), 'rotation':(0.277176, 90.641235, 0.274513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3154.85083008, 1806.39023438, 175.22439452999998), 'rotation':(0.408561, 90.643074, 0.402769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.22436523, 1772.98828125, 174.99089844), 'rotation':(0.391199, 90.641205, 0.385885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.28662109, 1767.4216406199998, 174.95333984), 'rotation':(0.38719, 90.643799, 0.381978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.59790039, 1739.5861718800002, 174.77039062), 'rotation':(0.369288, 90.643478, 0.364554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3153.63134766, 1905.6374218800001, 175.99242188), 'rotation':(0.477772, 90.645645, 0.469857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3153.77905273, 1900.07296875, 175.94599609), 'rotation':(0.477772, 90.643997, 0.469862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3153.86572266, 1894.5080468800002, 175.89974609), 'rotation':(0.475299, 90.643433, 0.467472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3154.05249023, 1877.80765625, 175.76371093999998), 'rotation':(0.4603, 90.645729, 0.452945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3154.42578125, 1844.40585938, 175.50414062), 'rotation':(0.43746, 90.644157, 0.430825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3154.48803711, 1838.8392187499999, 175.461875), 'rotation':(0.435247, 90.644089, 0.428684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2469.88039062, 1425.38695312, 163.70475586), 'rotation':(1.173303, 0.728776, 1.125953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2447.12109375, 1425.1071875, 163.23079102), 'rotation':(1.204374, 0.730066, 1.154497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2441.43117188, 1425.03722656, 163.11035156), 'rotation':(1.212085, 0.73039, 1.161592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2430.05152344, 1424.89734375, 162.86867188), 'rotation':(1.216006, 0.729766, 1.165173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2418.6721093799997, 1424.75734375, 162.62550781), 'rotation':(1.229694, 0.731072, 1.177726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2412.98242188, 1424.68738281, 162.50262695), 'rotation':(1.239044, 0.731474, 1.186282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2407.29273438, 1424.61742188, 162.37888672), 'rotation':(1.24808, 0.73187, 1.194553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2395.91359375, 1424.4774218799998, 162.13007812), 'rotation':(1.252698, 0.731392, 1.198779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2356.0857031200003, 1423.9876562499999, 161.25287109), 'rotation':(1.273509, 0.732964, 1.217795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2316.256875, 1423.4978125, 160.36401367), 'rotation':(1.281193, 0.733341, 1.224821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2293.4965625, 1423.21800781, 159.85418945), 'rotation':(1.28148, 0.732714, 1.225076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2287.806875, 1423.14796875, 159.72702148), 'rotation':(1.279028, 0.733917, 1.222833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2282.11671875, 1423.07800781, 159.60011719), 'rotation':(1.276583, 0.732498, 1.220589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2276.42671875, 1423.00804688, 159.4734668), 'rotation':(1.273796, 0.733682, 1.218057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2253.66601562, 1422.72804688, 158.96958984), 'rotation':(1.263646, 0.733233, 1.208793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2247.97609375, 1422.65808594, 158.84413086), 'rotation':(1.26254, 0.731468, 1.207777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2653.02929688, 1427.63890625, 167.07583984000001), 'rotation':(0.903327, 0.718963, 0.875171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2647.46386719, 1427.57054688, 166.98541016), 'rotation':(0.934035, 0.719927, 0.903946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2608.49925781, 1427.0915625, 166.33361327999998), 'rotation':(0.974484, 0.720835, 0.941745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2597.36839844, 1426.95460938, 166.14068359), 'rotation':(0.994482, 0.722632, 0.960405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2575.10472656, 1426.68089844, 165.74447265999999), 'rotation':(1.033715, 0.722118, 0.996907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2552.84132812, 1426.4071093799998, 165.33478516), 'rotation':(1.067511, 0.724705, 1.028271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2547.27539062, 1426.33863281, 165.23019531000003), 'rotation':(1.075823, 0.724984, 1.035967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2541.70945312, 1426.2701562500001, 165.12474609), 'rotation':(1.084224, 0.725332, 1.043753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.57765625, 1426.13316406, 164.91185547), 'rotation':(1.096997, 0.726679, 1.055557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2519.44628906, 1425.99632812, 164.69796875), 'rotation':(1.102201, 0.725948, 1.060377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2713.42164062, 1428.38160156, 167.99746094), 'rotation':(0.820572, 0.716795, 0.797304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2730.10863281, 1428.5867968799998, 168.23630859000002), 'rotation':(0.809534, 0.715987, 0.786895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2741.234375, 1428.72351562, 168.39292969), 'rotation':(0.794863, 0.715577, 0.773035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2757.92164062, 1428.92871094, 168.62210938), 'rotation':(0.772576, 0.714934, 0.751955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2763.48460938, 1428.9971875, 168.69703125), 'rotation':(0.765364, 0.714775, 0.745116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2769.04736328, 1429.06554688, 168.77126952999998), 'rotation':(0.761696, 0.713903, 0.741646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2774.609375, 1429.13390625, 168.84511719), 'rotation':(0.758629, 0.714615, 0.738736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2780.17261719, 1429.20238281, 168.91855468999998), 'rotation':(0.752093, 0.714442, 0.732552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2785.73535156, 1429.27074219, 168.99132812), 'rotation':(0.745911, 0.714281, 0.726679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2807.98779297, 1429.54445312, 169.27591797000002), 'rotation':(0.714281, 0.713474, 0.696643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2819.11328125, 1429.68128906, 169.41458984000002), 'rotation':(0.711248, 0.713525, 0.693754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2824.67675781, 1429.74964844, 169.48363281000002), 'rotation':(0.7059, 0.713323, 0.68866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2830.23949219, 1429.818125, 169.55220702999998), 'rotation':(0.695115, 0.713037, 0.678404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2835.8025, 1429.88648438, 169.62021484000002), 'rotation':(0.695115, 0.713037, 0.678404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2863.61474609, 1430.3303125, 169.95011719), 'rotation':(0.66845, 0.712084, 0.652992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2470.24121094, 1821.401875, 167.58382812), 'rotation':(1.448307, 0.495441, 1.376394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.44605469, 1821.06546875, 166.91427734), 'rotation':(1.498946, 0.498394, 1.42198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2438.78296875, 1821.0202343800001, 166.76525390999998), 'rotation':(1.512019, 0.499087, 1.433703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2416.13523438, 1820.83859375, 166.15558593999998), 'rotation':(1.563621, 0.501859, 1.479929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.47265625, 1820.7932031199998, 165.99972656000003), 'rotation':(1.576346, 0.502563, 1.491298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2404.8122656200003, 1820.74789062, 165.84253906), 'rotation':(1.589494, 0.503314, 1.503021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2393.4865625, 1820.65710938, 165.52673828), 'rotation':(1.595833, 0.50348, 1.508679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2382.1640625, 1820.56640625, 165.20988281), 'rotation':(1.603291, 0.503525, 1.515341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2370.839375, 1820.47570312, 164.88818359), 'rotation':(1.633201, 0.506324, 1.541967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.86960938, 1820.2033593800002, 163.90568359), 'rotation':(1.663732, 0.507136, 1.569077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2325.54539062, 1820.1125781199999, 163.57482421999998), 'rotation':(1.674004, 0.507734, 1.5782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2319.88328125, 1820.0671093800001, 163.40852539), 'rotation':(1.679414, 0.508052, 1.582985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2308.5590625, 1819.9763281199998, 163.07416016), 'rotation':(1.695089, 0.510374, 1.59688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2302.89914062, 1819.93101562, 162.90633789), 'rotation':(1.69776, 0.509189, 1.599242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2285.9114062500003, 1819.79476562, 162.40293945), 'rotation':(1.693593, 0.508979, 1.595565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2280.2487499999997, 1819.74953125, 162.23543945), 'rotation':(1.693593, 0.508979, 1.595565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2268.9240625, 1819.65867188, 161.90085938), 'rotation':(1.690526, 0.508815, 1.592843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2263.26171875, 1819.61328125, 161.73379882999998), 'rotation':(1.688887, 0.5087, 1.591389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2257.59914062, 1819.56789062, 161.56686523), 'rotation':(1.687323, 0.509757, 1.589992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2246.27367188, 1819.4771875000001, 161.23334961), 'rotation':(1.685028, 0.509431, 1.58797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2251.8290625, 1811.63953125, 161.39504883), 'rotation':(-1.684967, -179.490585, -1.786407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2263.15429688, 1811.7303124999999, 161.72875977), 'rotation':(-1.687378, -179.490204, -1.789124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2268.816875, 1811.77578125, 161.89583984), 'rotation':(-1.688873, -179.491287, -1.790802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2274.47898438, 1811.82117188, 162.06303711), 'rotation':(-1.69046, -179.490051, -1.792572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2280.1415625, 1811.8664843800002, 162.23039062), 'rotation':(-1.6922, -179.491089, -1.794495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2291.46632812, 1811.9572656199998, 162.56553711), 'rotation':(-1.693665, -179.490982, -1.796173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2297.12890625, 1812.00265625, 162.73333984), 'rotation':(-1.695312, -179.489746, -1.798035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2302.79101562, 1812.048125, 162.90125), 'rotation':(-1.696899, -179.490814, -1.799805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2308.453125, 1812.0935156199998, 163.06914061999998), 'rotation':(-1.697754, -179.489487, -1.800751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2314.11546875, 1812.13890625, 163.23665039), 'rotation':(-1.695099, -179.491013, -1.79776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2325.43992188, 1812.2258593800002, 163.56987305), 'rotation':(-1.679413, -179.491959, -1.780182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2331.10203125, 1812.26648438, 163.73561523), 'rotation':(-1.674011, -179.490875, -1.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2365.07640625, 1812.58046875, 164.72060547), 'rotation':(-1.655762, -179.492813, -1.753693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2382.06347656, 1812.7165625, 165.20525390999998), 'rotation':(-1.618347, -179.494522, -1.711853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2387.72558594, 1812.7619531199998, 165.36412109), 'rotation':(-1.603363, -179.495361, -1.695099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2404.71460938, 1812.8982031199998, 165.83806640999998), 'rotation':(-1.595825, -179.496521, -1.686707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.3784375, 1812.94359375, 165.99539062), 'rotation':(-1.589417, -179.496704, -1.679565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2421.7028906200003, 1813.0344531199999, 166.30578125), 'rotation':(-1.56369, -179.498108, -1.650909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2427.36765625, 1813.07984375, 166.45902343999998), 'rotation':(-1.55072, -179.49884, -1.636475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2433.03050781, 1813.125, 166.61080077999998), 'rotation':(-1.537659, -179.499527, -1.621948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2455.68433594, 1813.30679688, 167.20597656), 'rotation':(-1.492584, -179.501709, -1.57196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2461.349375, 1813.18203125, 167.35339843999998), 'rotation':(-1.492432, -179.501709, -1.571777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2472.67726562, 1813.2728124999999, 167.64380859000002), 'rotation':(-1.466003, -179.503677, -1.542572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2510.77101562, 1813.7153125, 168.57300781), 'rotation':(-1.371948, -179.507797, -1.438904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2521.848125, 1813.8040624999999, 168.83238281), 'rotation':(-1.336761, -179.509491, -1.400299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.92382812, 1813.8928125, 169.08488281), 'rotation':(-1.301636, -179.511108, -1.361816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2538.46265625, 1813.93710938, 169.20861327999998), 'rotation':(-1.284058, -179.511917, -1.342621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2549.54078125, 1814.02609375, 169.45117188), 'rotation':(-1.248932, -179.513474, -1.304291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2566.15773438, 1814.1594531199999, 169.80662109000002), 'rotation':(-1.213043, -179.514725, -1.265289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2571.69703125, 1814.2037500000001, 169.92177734), 'rotation':(-1.195129, -179.515442, -1.245819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2577.23558594, 1814.24820312, 170.03517578), 'rotation':(-1.177124, -179.516205, -1.226288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2582.77492188, 1814.2925, 170.14679688), 'rotation':(-1.159149, -179.518204, -1.206787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2604.9340625, 1814.46695312, 170.57732422), 'rotation':(-1.096191, -179.519913, -1.138763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2610.47363281, 1814.50539062, 170.68195312), 'rotation':(-1.096191, -179.519913, -1.138763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2616.01269531, 1814.57703125, 170.78607422000002), 'rotation':(-1.07843, -179.520645, -1.119629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2627.09226562, 1814.680625, 170.98685547000002), 'rotation':(-1.042969, -179.521225, -1.081482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2632.6330468799997, 1814.72507812, 171.08433594), 'rotation':(-1.007568, -179.523209, -1.043488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2638.150625, 1822.6174218800002, 171.18068359), 'rotation':(0.972154, 0.475558, 0.939584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2632.61085938, 1822.573125, 171.08505859000002), 'rotation':(0.972154, 0.475558, 0.939584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2627.0705468799997, 1822.52867188, 170.98757812), 'rotation':(1.007569, 0.477503, 0.97258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2604.91578125, 1822.35117188, 170.57818359), 'rotation':(1.078466, 0.479368, 1.038418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2599.3752343799997, 1822.306875, 170.47212890999998), 'rotation':(1.096177, 0.480901, 1.054808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2593.83714844, 1822.2624218800001, 170.36558594), 'rotation':(1.105159, 0.479641, 1.063113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2577.2185156200003, 1822.129375, 170.03611328), 'rotation':(1.159145, 0.483067, 1.112917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2571.68285156, 1822.085, 169.9228125), 'rotation':(1.177142, 0.483799, 1.129479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2549.5278125, 1821.90734375, 169.45226562), 'rotation':(1.240123, 0.486014, 1.187269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2543.99046875, 1821.8630468800002, 169.33175781000003), 'rotation':(1.248921, 0.486531, 1.19532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2538.45117188, 1821.81875, 169.20974609), 'rotation':(1.266488, 0.487303, 1.211383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.91210938, 1821.774375, 169.08603516), 'rotation':(1.284048, 0.488086, 1.227426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.37328125, 1821.73, 168.960625), 'rotation':(1.301629, 0.488882, 1.243442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2521.83910156, 1821.68570312, 168.83363281), 'rotation':(1.319251, 0.48971, 1.259494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.10863281, 1823.0228124999999, 171.79873047), 'rotation':(0.871136, 0.471978, 0.844939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2681.640625, 1822.97804688, 171.88287109), 'rotation':(0.846096, 0.472108, 0.821379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.1696875, 1823.01023438, 171.96484375), 'rotation':(0.82092, 0.471374, 0.797649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2709.29761719, 1823.1876562500001, 172.28037109000002), 'rotation':(0.784324, 0.47004, 0.763069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2731.42503906, 1823.36484375, 172.57353516), 'rotation':(0.720619, 0.468345, 0.702659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2736.95777344, 1823.40921875, 172.64267578), 'rotation':(0.704657, 0.467965, 0.687482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2770.15308594, 1823.6753125, 173.03337890999998), 'rotation':(0.63087, 0.46647, 0.617105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2781.21800781, 1823.7640625, 173.15335938), 'rotation':(0.602313, 0.465835, 0.589752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2786.75097656, 1823.80820312, 173.21111327999998), 'rotation':(0.588332, 0.465567, 0.576346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2792.28394531, 1823.8525, 173.26734375), 'rotation':(0.573975, 0.463894, 0.562565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2836.54760742, 1824.2116406199998, 173.68267577999998), 'rotation':(0.484008, 0.462954, 0.475877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2842.08056641, 1824.2578125, 173.72894531000003), 'rotation':(0.471222, 0.464079, 0.463519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2864.14770508, 1824.558125, 173.90679688), 'rotation':(0.436763, 0.462127, 0.43014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2854.83789062, 1816.473125, 173.83226562), 'rotation':(-0.464783, -179.537109, -0.472382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.67822266, 1816.42773438, 173.89460938), 'rotation':(-0.455505, -179.536835, -0.462769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2842.16113281, 1816.3715625, 173.72910156), 'rotation':(-0.483978, -179.53569, -0.492218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2808.96533203, 1816.1053124999999, 173.43160156000002), 'rotation':(-0.560364, -179.534317, -0.571411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2803.43310547, 1816.06101562, 173.37738281000003), 'rotation':(-0.566833, -179.5354, -0.578125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2797.89964844, 1816.01671875, 173.32263672000002), 'rotation':(-0.573975, -179.534729, -0.585571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2786.83472656, 1815.92796875, 173.21130859000002), 'rotation':(-0.602356, -179.534134, -0.615112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2781.30199219, 1815.8835156199998, 173.15355469), 'rotation':(-0.616699, -179.533829, -0.630096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2753.6428125, 1815.66210938, 172.84238281), 'rotation':(-0.680664, -179.532791, -0.696991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2742.57835938, 1815.57335938, 172.71044922000002), 'rotation':(-0.704651, -179.532028, -0.722137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2737.04613281, 1815.5290625, 172.64296875), 'rotation':(-0.720642, -179.531631, -0.738953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2714.91992188, 1815.3517187500001, 172.35658203), 'rotation':(-0.784332, -179.529953, -0.80603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2703.85742188, 1815.26296875, 172.20335938), 'rotation':(-0.808319, -179.530121, -0.83136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.26195312, 1815.13, 171.96529297), 'rotation':(-0.8461, -179.527893, -0.871368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2678.00074219, 1814.98398438, 171.82654297000002), 'rotation':(-0.89624, -179.526352, -0.924622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3018.52636719, 1825.66585938, 174.81632812), 'rotation':(0.258448, 0.460326, 0.256128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3012.98657227, 1825.62148438, 174.79107422), 'rotation':(0.258448, 0.460326, 0.256128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3001.90795898, 1825.53273438, 174.7390625), 'rotation':(0.27247, 0.459666, 0.269897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2990.8293457, 1825.44398438, 174.68603516), 'rotation':(0.272497, 0.46099, 0.269908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.21069336, 1825.31070312, 174.60306641), 'rotation':(0.290426, 0.460366, 0.287483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.6706543, 1825.26648438, 174.57382812), 'rotation':(0.302386, 0.461214, 0.299198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2957.59130859, 1825.17757812, 174.51382812), 'rotation':(0.31425, 0.460612, 0.310824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2952.05249023, 1825.13320312, 174.48310547), 'rotation':(0.32035, 0.461612, 0.316781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2946.51269531, 1825.08875, 174.45214843999997), 'rotation':(0.320199, 0.461631, 0.316641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2907.73828125, 1824.7778125, 174.21583984), 'rotation':(0.377429, 0.462332, 0.372474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2904.72973633, 1816.8674218800002, 174.19556641), 'rotation':(-0.385651, -179.537857, -0.390839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2918.87524414, 1816.98648438, 174.28761719), 'rotation':(-0.377441, -179.538376, -0.382446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2924.4152832, 1817.03085938, 174.32255859), 'rotation':(-0.361084, -179.538574, -0.365631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2946.5715332, 1817.20851562, 174.45210938), 'rotation':(-0.3284, -179.538254, -0.332184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2957.65063477, 1817.29734375, 174.51380859), 'rotation':(-0.320374, -179.538361, -0.323975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.72998047, 1817.3860937499999, 174.57380859), 'rotation':(-0.31427, -179.539383, -0.317719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2996.42749023, 1817.60804688, 174.71267577999998), 'rotation':(-0.278534, -179.539749, -0.281281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3007.5065918, 1817.696875, 174.76517578), 'rotation':(-0.272491, -179.539001, -0.275085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3013.04663086, 1817.74132812, 174.79105468999998), 'rotation':(-0.267853, -179.539566, -0.270386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3018.58642578, 1817.7857812500001, 174.81630859), 'rotation':(-0.267853, -179.539566, -0.270386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3040.74536133, 1817.96335938, 174.91259766), 'rotation':(-0.239624, -179.539825, -0.241638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3046.28222656, 1817.9641406199999, 174.93560547), 'rotation':(-0.239624, -179.539825, -0.241638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3089.88696289, 1818.3318749999999, 175.10728516), 'rotation':(-0.210388, -179.540527, -0.211945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3101.03198242, 1818.44679688, 175.14789062), 'rotation':(-0.20813, -179.539505, -0.209656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3112.17871094, 1818.53609375, 175.18789062), 'rotation':(-0.203522, -179.540329, -0.204987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3117.75244141, 1818.58070312, 175.20748047), 'rotation':(-0.200562, -179.540329, -0.201965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3123.32592773, 1818.62539062, 175.22673827999998), 'rotation':(-0.197418, -179.539108, -0.198761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3128.89916992, 1818.67007812, 175.24568359), 'rotation':(-0.194427, -179.540359, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3128.83691406, 1826.5501562499999, 175.24570312), 'rotation':(0.191109, 0.459584, 0.189844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3123.26318359, 1826.50546875, 175.22673827999998), 'rotation':(0.194428, 0.460882, 0.193112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3112.11645508, 1826.41625, 175.18789062), 'rotation':(0.200541, 0.459649, 0.199145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3084.25146484, 1826.28640625, 175.08666015999998), 'rotation':(0.210383, 0.460758, 0.208843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3178.05640625, 1818.93445312, 175.40214844), 'rotation':(-0.172729, -179.540405, -0.173767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3194.72900391, 1819.19765625, 175.450625), 'rotation':(-0.16449, -179.53952, -0.165436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3200.28710938, 1819.2421875, 175.46638672), 'rotation':(-0.162506, -179.540894, -0.163422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.40257812, 1819.3313281199999, 175.49759766), 'rotation':(-0.158386, -179.540237, -0.159271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3216.96044922, 1819.37585938, 175.51269531000003), 'rotation':(-0.158386, -179.540237, -0.159271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3222.51855469, 1819.42039062, 175.52724609), 'rotation':(-0.149933, -179.540314, -0.150726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3239.19261719, 1819.5540624999999, 175.56761719), 'rotation':(-0.133484, -179.540375, -0.134094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3244.74878906, 1819.55507812, 175.58023438), 'rotation':(-0.129089, -179.539963, -0.1297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3250.30712891, 1819.5434375, 175.59277343999997), 'rotation':(-0.129242, -179.541046, -0.129822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3255.80273438, 1827.6975, 175.6053125), 'rotation':(0.129234, 0.460039, 0.128648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3250.24267578, 1827.62320312, 175.59277343999997), 'rotation':(0.129234, 0.460039, 0.128648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3239.13011719, 1827.4342968800001, 175.56761719), 'rotation':(0.129111, 0.458948, 0.128517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3228.01416016, 1827.34523438, 175.54115234), 'rotation':(0.133482, 0.459629, 0.132861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3216.89820312, 1827.25609375, 175.51269531000003), 'rotation':(0.149943, 0.459709, 0.149165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3211.34007812, 1827.2115625000001, 175.49759766), 'rotation':(0.149943, 0.459709, 0.149165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3200.22484375, 1827.12242188, 175.46640625), 'rotation':(0.162504, 0.460165, 0.161575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3194.66675781, 1827.07773438, 175.450625), 'rotation':(0.162483, 0.460145, 0.161576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3189.10986328, 1827.07289062, 175.43470703), 'rotation':(0.164491, 0.459553, 0.163542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3183.55199219, 1827.07617188, 175.41855468999998), 'rotation':(0.164491, 0.459553, 0.163542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.9921875, 1827.07375, 175.40214844), 'rotation':(0.168549, 0.459579, 0.167557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.06274414, 1547.89429688, 172.86677734), 'rotation':(-0.37442, -89.218597, -0.379333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.13867188, 1542.3211718799998, 172.83033203), 'rotation':(-0.372528, -89.219147, -0.377411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.21435547, 1536.7474218799998, 172.79404297000002), 'rotation':(-0.368713, -89.219177, -0.373474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.44165039, 1520.02757812, 172.68710938), 'rotation':(-0.357056, -89.21933, -0.361511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.59301758, 1508.88085938, 172.61757812), 'rotation':(-0.353241, -89.21936, -0.357574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.66894531, 1503.30761719, 172.58335938), 'rotation':(-0.349396, -89.219421, -0.353668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.74462891, 1497.73425781, 172.54949219), 'rotation':(-0.345398, -89.219482, -0.349579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.8203125, 1492.16039062, 172.51591797), 'rotation':(-0.342926, -89.219604, -0.347046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.97192383, 1481.0134375, 172.44919922), 'rotation':(-0.340607, -89.218628, -0.344696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.04760742, 1475.44019531, 172.41611328), 'rotation':(-0.33606, -89.221283, -0.340027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3069.19897461, 1464.29332031, 172.35134766), 'rotation':(-0.326935, -89.218781, -0.330688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.50195312, 1441.99964844, 172.22548827999998), 'rotation':(-0.314453, -89.219299, -0.317932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.57763672, 1436.42625, 172.1946875), 'rotation':(-0.314453, -89.219299, -0.317932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.72924805, 1425.27820312, 172.13396484), 'rotation':(-0.306458, -89.22113, -0.309753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3070.10766602, 1397.41175781, 171.98800781000003), 'rotation':(-0.292969, -89.219849, -0.29599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3070.25927734, 1386.26488281, 171.93117188), 'rotation':(-0.286469, -89.221893, -0.289368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3070.63793945, 1358.39769531, 171.79501953), 'rotation':(-0.271973, -89.220703, -0.274567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3070.94091797, 1336.10316406, 171.69109375), 'rotation':(-0.255951, -89.220825, -0.25824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3071.01660156, 1330.52976562, 171.66607422), 'rotation':(-0.251892, -89.220856, -0.254089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3071.09228516, 1324.95642578, 171.64142578), 'rotation':(-0.247803, -89.220886, -0.249939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3071.31933594, 1308.23523438, 171.56957031000002), 'rotation':(-0.241821, -89.219269, -0.243866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3065.94287109, 1703.9296875, 173.99476562), 'rotation':(-0.468597, -89.219666, -0.476318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3066.01904297, 1698.32460938, 173.94890625), 'rotation':(-0.468597, -89.21698, -0.476318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.32763672, 1675.90367188, 173.769375), 'rotation':(-0.437134, -89.218323, -0.443848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3066.3996582, 1670.2961718800002, 173.72714843999998), 'rotation':(-0.418732, -89.217896, -0.424866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.55224609, 1659.08546875, 173.64492188), 'rotation':(-0.41925, -89.219604, -0.425446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.62817383, 1653.48046875, 173.60388672000002), 'rotation':(-0.420502, -89.219574, -0.426697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.7043457, 1647.8751171899999, 173.56271484), 'rotation':(-0.421539, -89.216797, -0.427765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.78051758, 1642.27027344, 173.52142578), 'rotation':(-0.42276, -89.219543, -0.429047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.93286133, 1631.0603125, 173.4384375), 'rotation':(-0.426788, -89.218018, -0.433167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3067.3137207, 1603.03367188, 173.23269531000003), 'rotation':(-0.394165, -89.21933, -0.399597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3067.38989258, 1597.426875, 173.19351562), 'rotation':(-0.394165, -89.21933, -0.399597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3067.46606445, 1591.82152344, 173.15494141), 'rotation':(-0.381104, -89.219543, -0.3862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3067.61816406, 1580.6100000000001, 173.080625), 'rotation':(-0.37442, -89.219177, -0.379333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3065.03881836, 1770.4521875, 174.54367188), 'rotation':(-0.482574, -89.216156, -0.490753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3064.85791016, 1791.770625, 174.72695312), 'rotation':(-0.496918, -89.21756, -0.505585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3064.72363281, 1803.2003125, 174.82673828), 'rotation':(-0.500977, -89.217468, -0.509796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3064.05859375, 1842.60070312, 175.17796875), 'rotation':(-0.518219, -89.218964, -0.527649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.98217773, 1848.2267187500001, 175.22931641), 'rotation':(-0.518219, -89.218964, -0.527649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3063.8293457, 1859.47765625, 175.33224609), 'rotation':(-0.524048, -89.217529, -0.533722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.60009766, 1876.3547656199999, 175.48759766), 'rotation':(-0.530762, -89.218506, -0.540649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.52368164, 1881.9803124999999, 175.53994140999998), 'rotation':(-0.533478, -89.215729, -0.543488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.14135742, 1910.1086718800002, 175.80580078), 'rotation':(-0.545532, -89.216858, -0.556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.77319336, 1937.2109375, 176.06394531), 'rotation':(-0.545715, -89.21521, -0.556183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.69873047, 1942.69703125, 176.11619141), 'rotation':(-0.545593, -89.217041, -0.556061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.40039062, 1964.6407812500001, 176.32572266), 'rotation':(-0.545593, -89.217041, -0.556061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.2512207, 1975.61289062, 176.43410156000002), 'rotation':(-0.572815, -89.214661, -0.584351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3062.17675781, 1981.09976562, 176.48966797), 'rotation':(-0.58194, -89.216125, -0.593842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.10229492, 1986.5853124999999, 176.54541016), 'rotation':(-0.581848, -89.21579, -0.593781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3061.953125, 1997.55679688, 176.65685547), 'rotation':(-0.58197, -89.21579, -0.593903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.18210938, 1436.6673437499999, 176.64849609), 'rotation':(0.600428, 0.468658, 0.587947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3451.71921875, 1436.3884375, 176.34681641), 'rotation':(0.61469, 0.469054, 0.601613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3446.025625, 1436.34253906, 176.28554688), 'rotation':(0.617907, 0.469144, 0.604685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3440.33226562, 1436.29640625, 176.22396484), 'rotation':(0.621055, 0.469192, 0.60771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3434.63867188, 1436.2506250000001, 176.16208984000002), 'rotation':(0.624279, 0.469281, 0.610784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3428.94628906, 1436.20460938, 176.09996094), 'rotation':(0.626438, 0.469986, 0.612851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3423.25242188, 1436.15867188, 176.03763672000002), 'rotation':(0.627421, 0.468634, 0.613798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3417.5590625, 1436.1126562499999, 175.97519531), 'rotation':(0.628432, 0.470005, 0.614758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3406.1721093799997, 1436.02074219, 175.85), 'rotation':(0.630611, 0.470052, 0.616852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3400.47851562, 1435.97472656, 175.78722656000002), 'rotation':(0.631792, 0.47008, 0.617975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3377.70460938, 1435.79089844, 175.53523438), 'rotation':(0.634367, 0.469109, 0.62043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3372.01125, 1435.745, 175.47220703), 'rotation':(0.634361, 0.469824, 0.620427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3366.31761719, 1435.69910156, 175.40904297), 'rotation':(0.635652, 0.469334, 0.621672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3360.62402344, 1435.65308594, 175.34578125), 'rotation':(0.635652, 0.469334, 0.621672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.23730469, 1435.56117188, 175.21917968999998), 'rotation':(0.636908, 0.470286, 0.622867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3326.463125, 1435.37730469, 174.96597656000003), 'rotation':(0.636287, 0.469573, 0.622269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3297.994375, 1435.27699219, 174.65048828), 'rotation':(0.634477, 0.470319, 0.620545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.03929688, 1427.1373437500001, 174.65027343999998), 'rotation':(-0.634369, -179.529678, -0.648499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3320.8125, 1427.45070312, 174.90253906), 'rotation':(-0.63504, -179.530457, -0.649231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3326.50585938, 1427.4965625, 174.96574219), 'rotation':(-0.63504, -179.530457, -0.649231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.28050781, 1427.6805468799998, 175.21894531), 'rotation':(-0.637024, -179.530563, -0.651306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3372.0544531200003, 1427.864375, 175.47197266), 'rotation':(-0.635651, -179.53067, -0.649872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3389.13476562, 1428.00230469, 175.66109375), 'rotation':(-0.634369, -179.530167, -0.648529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3400.52195312, 1428.09421875, 175.78701172), 'rotation':(-0.632629, -179.529907, -0.646729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3406.2153125, 1428.14015625, 175.84978515999998), 'rotation':(-0.631805, -179.531235, -0.645874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3411.90867188, 1428.18617188, 175.91244140999999), 'rotation':(-0.630615, -179.529953, -0.644623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3417.60230469, 1428.23207031, 175.975), 'rotation':(-0.629456, -179.531326, -0.643372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3423.29589844, 1428.27808594, 176.03742188), 'rotation':(-0.628479, -179.529968, -0.642365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3428.98949219, 1428.32398438, 176.09972656000002), 'rotation':(-0.627411, -179.531357, -0.641266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3434.69800781, 1428.36960938, 176.16203125), 'rotation':(0.0, 179.999985, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3440.37597656, 1428.41589844, 176.22375), 'rotation':(-0.624237, -179.530731, -0.63797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3446.06933594, 1428.4617968799998, 176.28533202999998), 'rotation':(-0.621094, -179.530792, -0.634674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3451.76292969, 1428.5078125, 176.34660156), 'rotation':(-0.617889, -179.530853, -0.631348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3463.14992188, 1428.59972656, 176.46820312), 'rotation':(-0.611542, -179.530991, -0.624695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3468.84300781, 1428.645625, 176.52853516), 'rotation':(-0.60849, -179.531082, -0.62149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.22972656, 1428.68882812, 176.64832031000003), 'rotation':(-0.602112, -179.531219, -0.614868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.54808594, 1993.868125, 173.94705077999998), 'rotation':(0.331332, -89.612732, 0.327532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.66601562, 1988.54054688, 173.97773438000002), 'rotation':(0.331332, -89.612732, 0.327532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.11132812, 1997.4553125, 172.03585938), 'rotation':(0.685519, -89.799774, 0.669243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.7239062500003, 1839.19640625, 174.075), 'rotation':(0.778109, -89.801056, 0.75718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.60226562, 1848.08460938, 173.95433594), 'rotation':(0.778109, -89.802551, 0.757201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.5659375, 1859.18929688, 173.80423828), 'rotation':(0.775814, -89.80072, 0.755017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.43796875, 1898.05679688, 173.28595703), 'rotation':(0.759667, -89.801758, 0.739719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.4196875, 1903.60976562, 173.21236327999998), 'rotation':(0.759667, -89.801758, 0.739719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.40140625, 1909.16234375, 173.13919922000002), 'rotation':(0.756519, -89.800079, 0.736744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3735.365, 1920.26757812, 172.99482422), 'rotation':(0.744149, -89.800415, 0.724998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.3103125, 1936.9264843800001, 172.78101562), 'rotation':(0.734826, -89.803619, 0.716165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.23734375, 1959.13710938, 172.50066406000002), 'rotation':(0.716132, -89.802399, 0.698388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.63476562, 1836.95609375, 174.10507812), 'rotation':(-0.778107, 90.198929, -0.799469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.69359375, 1842.5078125, 174.02964844), 'rotation':(-0.775818, 90.199265, -0.797058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.7214062499997, 1848.0587500000001, 173.95433594), 'rotation':(-0.775818, 90.199265, -0.797058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.703125, 1853.6109375, 173.87914062), 'rotation':(-0.771149, 90.199135, -0.792114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.6667187499997, 1864.7159375, 173.72945312), 'rotation':(-0.766632, 90.197571, -0.787384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.6301562500003, 1875.82117188, 173.58087891), 'rotation':(-0.761963, 90.198883, -0.78244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.59375, 1886.9260156199998, 173.43322265999998), 'rotation':(-0.759674, 90.198227, -0.780029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.48414062, 1920.2419531199998, 172.99480469), 'rotation':(-0.737885, 90.199425, -0.75708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.46578125, 1925.79492188, 172.9234375), 'rotation':(-0.734833, 90.196342, -0.753876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3727.44773438, 1931.3474999999999, 172.85222656000002), 'rotation':(-0.734833, 90.198441, -0.753876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.42945312, 1936.90085938, 172.78101562), 'rotation':(-0.73111, 90.197975, -0.749939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.41109375, 1942.4533593800002, 172.71013672), 'rotation':(-0.723663, 90.197792, -0.742126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.37476562, 1953.5588281199998, 172.57), 'rotation':(-0.716125, 90.197594, -0.734192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3873.29296875, 1301.33007812, 179.90822265999998), 'rotation':(-0.030853, 0.083801, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3863.1354687499997, 1301.30773438, 179.91367188), 'rotation':(-0.030853, 0.083801, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3846.37015625, 1301.1639453100001, 179.92273438), 'rotation':(-0.030853, 0.083036, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3823.5950000000003, 1301.12816406, 179.88537109), 'rotation':(0.150831, 0.084995, 0.150029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.944375, 1301.11988281, 179.87050781000002), 'rotation':(0.150647, 0.083607, 0.149857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.64523438, 1301.10339844, 179.83960938), 'rotation':(0.161233, 0.084426, 0.16032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3784.04882812, 1301.07068359, 179.75421875), 'rotation':(0.243216, 0.085, 0.241162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.45140625, 1301.03785156, 179.63669922), 'rotation':(0.322679, 0.085828, 0.319068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3750.1510937499997, 1301.02136719, 179.56957031000002), 'rotation':(0.352663, 0.086186, 0.348337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3744.5009375, 1301.01306641, 179.53357422000002), 'rotation':(0.368079, 0.08638, 0.363364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3733.2043750000003, 1300.99658203, 179.45664062), 'rotation':(0.39805, 0.085422, 0.392554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.55445312, 1300.9883984399999, 179.41566406), 'rotation':(0.413302, 0.086997, 0.407359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.90554688, 1300.98023438, 179.37326172000002), 'rotation':(0.428191, 0.087214, 0.421831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3704.9557812499997, 1300.95544922, 179.24283203), 'rotation':(0.446715, 0.087272, 0.439791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3688.00851562, 1300.93078125, 179.10107422000002), 'rotation':(0.491241, 0.087899, 0.482876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3671.0612499999997, 1300.90601562, 178.94730468999998), 'rotation':(0.527161, 0.088687, 0.517525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3665.41164062, 1300.89794922, 178.89472656), 'rotation':(0.532789, 0.088786, 0.522957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3642.81445312, 1300.865, 178.67439453), 'rotation':(0.577772, 0.089659, 0.566222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3637.16453125, 1300.85667969, 178.61695312), 'rotation':(0.577772, 0.089659, 0.566222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3631.51488281, 1300.84851562, 178.55855469), 'rotation':(0.588926, 0.089888, 0.576916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.21460938, 1300.83203125, 178.43890625), 'rotation':(0.611493, 0.089282, 0.598552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3614.56738281, 1300.82373047, 178.37808593999998), 'rotation':(0.617224, 0.090967, 0.604022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3586.31789062, 1300.78246094, 178.06712890999998), 'rotation':(0.637079, 0.090848, 0.623028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3563.72070312, 1300.74951172, 177.81072265999998), 'rotation':(0.649203, 0.091701, 0.634603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3558.0705468799997, 1300.74144531, 177.745625), 'rotation':(0.65996, 0.091342, 0.644881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3546.775625, 1300.72498047, 177.61078125), 'rotation':(0.681571, 0.091132, 0.665508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3541.12574219, 1300.71679688, 177.54140625), 'rotation':(0.703305, 0.092373, 0.686201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3529.82691406, 1300.7003125, 177.39951172000002), 'rotation':(0.724861, 0.092908, 0.70669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3512.87914062, 1300.80517578, 177.18210938), 'rotation':(0.735823, 0.092475, 0.717111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3868.7995312499997, 1293.18408203, 179.91064452999998), 'rotation':(0.030845, -179.916199, 0.030814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3863.1475, 1293.18335938, 179.91367188), 'rotation':(0.030845, -179.916962, 0.030806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3840.5490625, 1293.27257812, 179.92154297000002), 'rotation':(-0.105469, -179.91597, -0.105835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3834.90453125, 1293.26427734, 179.91320312), 'rotation':(-0.150818, -179.916397, -0.151611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3823.60640625, 1293.2478125, 179.88537109), 'rotation':(-0.150635, -179.914993, -0.151459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.9557812499997, 1293.23949219, 179.87050781000002), 'rotation':(-0.150818, -179.916397, -0.151642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.306875, 1293.23132812, 179.855625), 'rotation':(-0.161224, -179.915573, -0.16214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3784.0603125, 1293.19005859, 179.75421875), 'rotation':(-0.263733, -179.914825, -0.266174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3778.410625, 1293.181875, 179.72751953), 'rotation':(-0.284241, -179.914612, -0.287048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3772.7604687499997, 1293.17382812, 179.69869140999998), 'rotation':(-0.304871, -179.914413, -0.308136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.46289062, 1293.15722656, 179.63669922), 'rotation':(-0.337738, -179.914001, -0.341766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3755.81273438, 1293.14892578, 179.60394531000003), 'rotation':(-0.352661, -179.913818, -0.357025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3750.16234375, 1293.1407421899999, 179.56957031000002), 'rotation':(-0.368073, -179.91362, -0.372833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3744.51265625, 1293.13244141, 179.53357422000002), 'rotation':(-0.382965, -179.914764, -0.388123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.86523438, 1293.12425781, 179.49597656000003), 'rotation':(-0.398071, -179.913208, -0.403595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3733.2160937500003, 1293.11609375, 179.45664062), 'rotation':(-0.4133, -179.912994, -0.419281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.5659375, 1293.10791016, 179.41566406), 'rotation':(-0.428192, -179.914124, -0.434631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3721.91726562, 1293.09972656, 179.37326172000002), 'rotation':(-0.435944, -179.91275, -0.442596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3716.2665625, 1293.09142578, 179.33027343999998), 'rotation':(-0.435944, -179.91275, -0.442596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3699.3176562500003, 1293.06664062, 179.19679688), 'rotation':(-0.491272, -179.912094, -0.499725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3693.67039062, 1293.0584765600001, 179.14951172000002), 'rotation':(-0.491272, -179.912094, -0.499725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3688.01976562, 1293.05017578, 179.10105468999998), 'rotation':(-0.515167, -179.911667, -0.524506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3682.370625, 1293.04210938, 179.05052734), 'rotation':(-0.527161, -179.911301, -0.536926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3631.52636719, 1292.96789062, 178.55855469), 'rotation':(-0.60022, -179.91095, -0.612885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3597.62890625, 1292.91845703, 178.193125), 'rotation':(-0.637085, -179.909134, -0.651367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3591.97898438, 1292.9102734399999, 178.1303125), 'rotation':(-0.645111, -179.908966, -0.65976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3586.32960938, 1292.90197266, 178.06712890999998), 'rotation':(-0.645111, -179.908966, -0.65976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3580.67921875, 1292.89378906, 178.00349609), 'rotation':(-0.6492, -179.909409, -0.664032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3575.03050781, 1292.885625, 177.93951172), 'rotation':(-0.64917, -179.909424, -0.664001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3552.433125, 1292.85253906, 177.67845703), 'rotation':(-0.703308, -179.907623, -0.720734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3546.78734375, 1292.84423828, 177.61078125), 'rotation':(-0.703308, -179.907623, -0.720734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3541.13746094, 1292.8359375, 177.54140625), 'rotation':(-0.724854, -179.907089, -0.743378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3535.48828125, 1292.82775391, 177.47101562), 'rotation':(-0.724854, -179.907089, -0.743378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3524.19410156, 1292.76416016, 177.32728516), 'rotation':(-0.735687, -179.906311, -0.754761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.40820312, 1577.70519531, 173.84923827999998), 'rotation':(0.288582, 90.640945, 0.285685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.28491211, 1588.7196093799998, 173.90507811999998), 'rotation':(0.296096, 90.641014, 0.293054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.22338867, 1594.22679688, 173.93341797000002), 'rotation':(0.296096, 90.641014, 0.293054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3157.16186523, 1599.73414062, 173.96197266), 'rotation':(0.299859, 90.642937, 0.29673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.10058594, 1605.24109375, 173.99080078), 'rotation':(0.301689, 90.641235, 0.298538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.03857422, 1610.74867188, 174.01978516), 'rotation':(0.301689, 90.643723, 0.298523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.85375977, 1627.27074219, 174.10755859), 'rotation':(0.309811, 90.641808, 0.306488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.73071289, 1638.28492188, 174.16769531000003), 'rotation':(0.320616, 90.64193, 0.317049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.66918945, 1643.79222656, 174.19833984000002), 'rotation':(0.323259, 90.641808, 0.319631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.60766602, 1649.29980469, 174.22923828), 'rotation':(0.323259, 90.641808, 0.319631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.54589844, 1654.806875, 174.2603125), 'rotation':(0.323252, 90.643494, 0.319634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.484375, 1660.31398438, 174.29138672000002), 'rotation':(0.326326, 90.642189, 0.322627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.23803711, 1682.34328125, 174.41791016), 'rotation':(0.338975, 90.642342, 0.334986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.11499023, 1693.35765625, 174.48349609000002), 'rotation':(0.345362, 90.642426, 0.341214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.0534668, 1698.86507812, 174.51673828), 'rotation':(0.348394, 90.642319, 0.344186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.99194336, 1704.3721875, 174.55023438), 'rotation':(0.350095, 90.644478, 0.345836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3155.93017578, 1709.8747656199998, 174.58380859000002), 'rotation':(0.3425, 90.500244, 0.338426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4777.06005859, 4004.83523438, 156.93963867), 'rotation':(-0.368042, 89.545334, -0.372772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4777.37548828, 4044.20507812, 156.67168945), 'rotation':(-0.424469, 89.543701, -0.430786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.42041016, 4049.8303125, 156.63), 'rotation':(-0.44101, 89.546745, -0.447845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.46533203, 4055.45484375, 156.58738281), 'rotation':(-0.44101, 89.546745, -0.447845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4777.51074219, 4061.07960938, 156.54410156), 'rotation':(-0.449127, 89.54203, -0.456207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.60058594, 4072.32765625, 156.45586914), 'rotation':(-0.459839, 89.545303, -0.467255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.69091797, 4083.5771875, 156.3653418), 'rotation':(-0.474152, 89.545525, -0.482056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.73583984, 4089.2018749999997, 156.31893555), 'rotation':(-0.481323, 89.545654, -0.489441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.91601562, 4111.69773438, 156.12586914), 'rotation':(-0.506378, 89.545761, -0.515411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.09619141, 4134.19625, 155.92458008), 'rotation':(-0.52417, 89.549454, -0.533844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.23144531, 4151.06882812, 155.76808594), 'rotation':(-0.544403, 89.544342, -0.55481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.32177734, 4162.31789062, 155.66119141), 'rotation':(-0.548859, 89.543388, -0.559418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.41162109, 4173.56640625, 155.55316406), 'rotation':(-0.556274, 89.548401, -0.567139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.68212891, 4207.3134375, 155.22058594), 'rotation':(-0.576324, 89.543892, -0.588013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.7265625, 4212.9375, 155.1640332), 'rotation':(-0.577393, 89.545456, -0.589111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.81689453, 4224.18601562, 155.05047851999998), 'rotation':(-0.58078, 89.545532, -0.592621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.86181641, 4229.81101562, 154.99342773), 'rotation':(-0.582642, 89.545563, -0.594574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.90722656, 4235.43601562, 154.93617188), 'rotation':(-0.58432, 89.545593, -0.596344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.99707031, 4246.68507812, 154.82113281), 'rotation':(-0.58786, 89.545677, -0.600037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4779.08740234, 4257.9340625, 154.70540039), 'rotation':(-0.590454, 89.548828, -0.602722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4779.13232422, 4263.558125, 154.64743164), 'rotation':(-0.590454, 89.543259, -0.602722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.26757812, 4280.43210938, 154.47347656), 'rotation':(-0.592072, 89.546768, -0.604401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.3125, 4286.05710938, 154.41539062), 'rotation':(-0.592438, 89.546654, -0.604797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.40283203, 4297.30664062, 154.29907227), 'rotation':(-0.592438, 89.549652, -0.604797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4779.44775391, 4302.93164062, 154.24088867), 'rotation':(-0.592438, 89.549652, -0.604797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.49267578, 4308.55617188, 154.18272461), 'rotation':(-0.591766, 89.545265, -0.604095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.53808594, 4314.180625, 154.12466797), 'rotation':(-0.590149, 89.545288, -0.602386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.62792969, 4325.430625, 154.00895508), 'rotation':(-0.587189, 89.545174, -0.599304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.71826172, 4336.680625, 153.89384766), 'rotation':(-0.584137, 89.550224, -0.59613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.76318359, 4342.3046875, 153.8365332), 'rotation':(-0.582764, 89.54509, -0.594696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4788.09863281, 4336.6396875, 153.89358398000002), 'rotation':(0.585552, -90.454803, 0.573668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.82861328, 4302.890625, 154.24061523), 'rotation':(0.592444, -90.453339, 0.580284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.73828125, 4291.64109375, 154.35696289), 'rotation':(0.592041, -90.453186, 0.579883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.55810547, 4269.14210938, 154.58919921999998), 'rotation':(0.590463, -90.451172, 0.578381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4787.46777344, 4257.89257812, 154.70513671999998), 'rotation':(0.590463, -90.451172, 0.578381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.24267578, 4229.76953125, 154.99316406), 'rotation':(0.58075, -90.449036, 0.569079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.0625, 4207.27195312, 155.22032227), 'rotation':(0.574603, -90.456085, 0.563187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4786.92724609, 4190.3975, 155.38823242), 'rotation':(0.563422, -90.451416, 0.552424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.83740234, 4179.1484375, 155.49839844), 'rotation':(0.556203, -90.456451, 0.545485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.79248047, 4173.5234375, 155.55292969), 'rotation':(0.552576, -90.45166, 0.541984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.65673828, 4156.65039062, 155.71459961), 'rotation':(0.544407, -90.455627, 0.534142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.61181641, 4151.02492188, 155.76787109), 'rotation':(0.539448, -90.450256, 0.529347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.52197266, 4139.77585938, 155.87275391), 'rotation':(0.524183, -90.450531, 0.514648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.4765625, 4134.151875, 155.924375), 'rotation':(0.519149, -90.456055, 0.509813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.43164062, 4128.52734375, 155.97544922), 'rotation':(0.513883, -90.456177, 0.504745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.38671875, 4122.901875, 156.0259668), 'rotation':(0.508917, -90.450806, 0.499956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.34179688, 4117.27828125, 156.07594727), 'rotation':(0.506349, -90.454193, 0.497449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.29638672, 4111.6528125, 156.12567382999998), 'rotation':(0.502818, -90.453979, 0.494045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.25146484, 4106.02828125, 156.17507812), 'rotation':(0.49581, -90.459412, 0.487295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.11669922, 4089.15476562, 156.31876953), 'rotation':(0.474165, -90.454468, 0.46638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.07519531, 4083.5299999999997, 156.36517578000002), 'rotation':(0.467158, -90.454559, 0.459581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.03222656, 4077.9053125, 156.41081055), 'rotation':(0.459856, -90.454712, 0.452513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.98876953, 4072.28078125, 156.45570312), 'rotation':(0.452828, -90.454803, 0.44572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4785.94580078, 4066.65578125, 156.50001953), 'rotation':(0.449126, -90.453918, 0.442135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.82763672, 4055.40625, 156.58724609), 'rotation':(0.424476, -90.456299, 0.418224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.6328125, 4032.9075000000003, 156.75225586), 'rotation':(0.391643, -90.456757, 0.386328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.49755859, 4016.0334375, 156.86683594), 'rotation':(0.378372, -90.454529, 0.373398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4980.60253906, 4352.48828125, 156.2037793), 'rotation':(0.626813, -90.46991, 0.613218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4980.29785156, 4330.06007812, 156.44957031), 'rotation':(0.630543, -90.473419, 0.616775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4980.06298828, 4302.01859375, 156.75883789), 'rotation':(0.632571, -90.471893, 0.618716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4980.01611328, 4296.41015625, 156.82077148), 'rotation':(0.631574, -90.471924, 0.617759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.92236328, 4285.19382812, 156.94433594), 'rotation':(0.629907, -90.471924, 0.616167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.87548828, 4279.58546875, 157.00597656), 'rotation':(0.628917, -90.471985, 0.61521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.82861328, 4273.97804688, 157.06751953), 'rotation':(0.627913, -90.471985, 0.61426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.73486328, 4262.76171875, 157.1903418), 'rotation':(0.626246, -90.472015, 0.61267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4979.5, 4234.72023438, 157.49577148), 'rotation':(0.614177, -90.472656, 0.601122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.21826172, 4201.07125, 157.85416016), 'rotation':(0.603078, -90.474487, 0.590491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.17138672, 4195.46289062, 157.91319336), 'rotation':(0.594834, -90.471558, 0.5826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.07763672, 4184.2465625, 158.0300293), 'rotation':(0.58657, -90.474792, 0.57466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.93945312, 4167.421875, 158.20130859), 'rotation':(0.5742, -90.478271, 0.562791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.73632812, 4144.98976562, 158.42510742000002), 'rotation':(0.556763, -90.475281, 0.546026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.625, 4133.77390625, 158.53375), 'rotation':(0.545281, -90.475494, 0.534981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4978.43408203, 4111.3403125, 158.74387695), 'rotation':(0.527762, -90.475433, 0.51812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.34033203, 4100.12351562, 158.84646484), 'rotation':(0.505495, -90.472961, 0.496648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.24609375, 4088.9071875, 158.94631836), 'rotation':(0.490578, -90.476196, 0.482235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.19921875, 4083.2990625, 158.99473633), 'rotation':(0.490578, -90.476196, 0.482235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4978.05859375, 4066.4739062500003, 159.13549805), 'rotation':(0.46836, -90.475616, 0.460736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4977.96435547, 4055.256875, 159.2265625), 'rotation':(0.459487, -90.475372, 0.452157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4977.72998047, 4027.2153125, 159.44037109), 'rotation':(0.406799, -90.478973, 0.401047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4977.68261719, 4021.60640625, 159.48019531), 'rotation':(0.398104, -90.471893, 0.392605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4969.19433594, 4004.82984375, 159.59592773), 'rotation':(-0.388275, 89.525246, -0.393555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.24121094, 4010.43820312, 159.55791992000002), 'rotation':(-0.398132, 89.522293, -0.403687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.42919922, 4032.870625, 159.39962891), 'rotation':(-0.424408, 89.524063, -0.430695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.5703125, 4049.69359375, 159.27174805), 'rotation':(-0.459473, 89.524605, -0.466919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.6171875, 4055.30226562, 159.22675781), 'rotation':(-0.468353, 89.524406, -0.476044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.6640625, 4060.90992188, 159.18155273), 'rotation':(-0.468353, 89.524406, -0.476044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.7109375, 4066.5182812499997, 159.13571289), 'rotation':(-0.475677, 89.523537, -0.483612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4969.89892578, 4088.94992188, 158.9465625), 'rotation':(-0.505493, 89.527061, -0.514465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4969.99267578, 4100.16601562, 158.84670898000002), 'rotation':(-0.520416, 89.524315, -0.529938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.08642578, 4111.38132812, 158.74416015999998), 'rotation':(-0.5336, 89.52713, -0.54361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.32128906, 4139.42140625, 158.47992188), 'rotation':(-0.556732, 89.52475, -0.567657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.36816406, 4145.02976562, 158.42541015999998), 'rotation':(-0.56842, 89.527779, -0.579803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.50878906, 4161.85304688, 158.25794922), 'rotation':(-0.574188, 89.521706, -0.585815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.55566406, 4167.46046875, 158.20163086), 'rotation':(-0.578339, 89.528122, -0.590118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.74365234, 4189.89359375, 157.97211914), 'rotation':(-0.603058, 89.525528, -0.615845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.79052734, 4195.5009375, 157.91352539), 'rotation':(-0.603058, 89.525528, -0.615845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4970.83740234, 4201.109375, 157.85449219), 'rotation':(-0.60733, 89.528793, -0.6203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4970.97802734, 4217.933125, 157.67618163999998), 'rotation':(-0.609558, 89.527229, -0.62262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.02490234, 4223.54148438, 157.61650391), 'rotation':(-0.614166, 89.527336, -0.627441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4971.07226562, 4229.149375, 157.55645508), 'rotation':(-0.618805, 89.527412, -0.632263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.26025391, 4251.5815625, 157.31326171999999), 'rotation':(-0.625732, 89.529327, -0.639526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.35400391, 4262.79734375, 157.19072266), 'rotation':(-0.627106, 89.527985, -0.64093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.40087891, 4268.40578125, 157.1293457), 'rotation':(-0.627899, 89.522682, -0.641785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.44775391, 4274.01414062, 157.06790039), 'rotation':(-0.628845, 89.528076, -0.642761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.49462891, 4279.62203125, 157.00634766), 'rotation':(-0.629913, 89.528061, -0.64389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.54150391, 4285.23046875, 156.9447168), 'rotation':(-0.630585, 89.528061, -0.644562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.58886719, 4290.83890625, 156.88296875), 'rotation':(-0.631561, 89.528084, -0.645599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.63574219, 4296.44679688, 156.82113281), 'rotation':(-0.632538, 89.528107, -0.646637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.82324219, 4318.87984375, 156.5734082), 'rotation':(-0.630493, 89.526619, -0.644501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.87011719, 4324.4878125, 156.51164062), 'rotation':(-0.62912, 89.526566, -0.643036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.96386719, 4335.70507812, 156.38834961), 'rotation':(-0.627502, 89.526535, -0.641327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.98876953, 4352.52390625, 156.20417969), 'rotation':(-0.626709, 89.52636, -0.640533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.40185547, 4008.17554688, 160.24273438), 'rotation':(-0.277679, 89.845947, -0.280365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.43212891, 4019.5525, 160.18796875), 'rotation':(-0.284271, 89.847649, -0.287079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.46289062, 4030.9309375000003, 160.1309082), 'rotation':(-0.297516, 89.850861, -0.300598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.49316406, 4042.30882812, 160.07068359000002), 'rotation':(-0.324219, 89.848045, -0.327911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.5390625, 4059.375, 159.97460938), 'rotation':(-0.330841, 89.845253, -0.334686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.56933594, 4070.75242188, 159.90860351999999), 'rotation':(-0.336609, 89.849632, -0.340576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.61474609, 4087.81960938, 159.80561523), 'rotation':(-0.359314, 89.849915, -0.363831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.62988281, 4093.50875, 159.76994141), 'rotation':(-0.370636, 89.846863, -0.375427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.64501953, 4099.19726562, 159.73328125), 'rotation':(-0.376373, 89.852631, -0.381348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.67578125, 4110.57421875, 159.65890625), 'rotation':(-0.378906, 89.849075, -0.383942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.69091797, 4116.26265625, 159.6212793), 'rotation':(-0.384033, 89.849129, -0.389191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.72119141, 4127.64109375, 159.54446289), 'rotation':(-0.394531, 89.849258, -0.399963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.75146484, 4139.0190625, 159.465625), 'rotation':(-0.404999, 89.849403, -0.410767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.78173828, 4150.39695312, 159.38478515999998), 'rotation':(-0.415344, 89.849571, -0.421387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.84277344, 4173.15140625, 159.21837890999998), 'rotation':(-0.42868, 89.852791, -0.43512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.87353516, 4184.52929688, 159.13287109), 'rotation':(-0.435822, 89.849907, -0.442474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.88867188, 4190.21828125, 159.08958008), 'rotation':(-0.443054, 89.850006, -0.449921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.97998047, 4224.3515625, 158.82380859), 'rotation':(-0.453491, 89.852974, -0.460724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.02539062, 4241.4184375, 158.68725586), 'rotation':(-0.465332, 89.85437, -0.4729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.04052734, 4247.10695312, 158.64109375), 'rotation':(-0.465332, 89.849564, -0.4729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.07128906, 4258.484375, 158.54861328), 'rotation':(-0.468109, 89.85244, -0.47583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.1015625, 4269.8628125, 158.45556641), 'rotation':(-0.471832, 89.847778, -0.479645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.13183594, 4281.24023438, 158.36179688), 'rotation':(-0.475525, 89.852562, -0.483459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.16259766, 4292.61867188, 158.26733398), 'rotation':(-0.47937, 89.852623, -0.487427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.20800781, 4309.68507812, 158.12453125), 'rotation':(-0.480194, 89.848396, -0.488281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.23828125, 4321.0634375, 158.02914062), 'rotation':(-0.480927, 89.851006, -0.489044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.25927734, 4332.43898438, 157.93351562), 'rotation':(-0.482666, 89.850487, -0.490845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.17773438, 4343.81640625, 157.83766602), 'rotation':(-0.482666, 89.850487, -0.490845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.80175781, 4343.8125, 157.83749023000001), 'rotation':(0.482662, -90.149536, 0.474589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.73046875, 4338.12453125, 157.88541992), 'rotation':(0.482655, -90.145264, 0.474588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.63427734, 4326.74851562, 157.9812207), 'rotation':(0.480893, -90.148987, 0.472879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.60400391, 4315.37109375, 158.07667969), 'rotation':(0.480169, -90.14859, 0.472184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.58886719, 4309.68265625, 158.12435546999998), 'rotation':(0.480169, -90.14859, 0.472184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.55859375, 4298.30515625, 158.21967773), 'rotation':(0.477437, -90.15213, 0.469526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.52832031, 4286.92726562, 158.31450195), 'rotation':(0.475511, -90.14743, 0.467681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.51269531, 4281.23875, 158.36163086), 'rotation':(0.473756, -90.147461, 0.465971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.48242188, 4269.86132812, 158.45540039), 'rotation':(0.47004, -90.147522, 0.462395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.43701172, 4252.79539062, 158.59470703), 'rotation':(0.465354, -90.150452, 0.457832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.42138672, 4247.10742188, 158.64091797), 'rotation':(0.4653, -90.150452, 0.457805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.40625, 4241.41796875, 158.68708984), 'rotation':(0.462937, -90.146851, 0.455512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.39111328, 4235.72898438, 158.73302734), 'rotation':(0.45834, -90.151245, 0.451047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.37597656, 4230.04054688, 158.77853516), 'rotation':(0.453538, -90.147034, 0.446392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.33056641, 4212.97507812, 158.91271484), 'rotation':(0.446612, -90.149719, 0.439685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.29980469, 4201.5971875, 159.00141602), 'rotation':(0.443088, -90.149963, 0.436259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.26953125, 4190.2196875, 159.0894043), 'rotation':(0.435807, -90.150085, 0.429229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.25439453, 4184.53078125, 159.13269531), 'rotation':(0.428683, -90.150177, 0.4223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.20849609, 4167.464375, 159.26019531), 'rotation':(0.418103, -90.147186, 0.412034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.19335938, 4161.77640625, 159.30197266), 'rotation':(0.418103, -90.147186, 0.412034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.16259766, 4150.39890625, 159.38460938), 'rotation':(0.410085, -90.150513, 0.404257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.14746094, 4144.71046875, 159.42529297), 'rotation':(0.404982, -90.150574, 0.399315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.13232422, 4139.02148438, 159.46544921999998), 'rotation':(0.399764, -90.150665, 0.394202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.07617188, 4116.2665625, 159.62109375), 'rotation':(0.378918, -90.15094, 0.373948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.01806641, 4093.51195312, 159.76979492), 'rotation':(0.359309, -90.150085, 0.354829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.98974609, 4082.13375, 159.84049805), 'rotation':(0.348012, -90.150208, 0.343788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.91748047, 4065.06734375, 159.94160156), 'rotation':(0.330841, -90.150146, 0.327042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.87744141, 4053.6901562499997, 160.00710938), 'rotation':(0.324209, -90.151917, 0.320564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.85742188, 4048.0012500000003, 160.03928711), 'rotation':(0.310965, -90.152069, 0.307589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5225.82568359, 4036.6240625, 160.10123047), 'rotation':(0.297509, -90.152222, 0.294429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.81054688, 4030.93453125, 160.13078125), 'rotation':(0.284231, -90.149261, 0.281438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.76513672, 4013.868125, 160.21544921999998), 'rotation':(0.270715, -90.149872, 0.268153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.74951172, 4008.17921875, 160.24261719), 'rotation':(0.270715, -90.149872, 0.268153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5757.319375, 5223.87744141, 161.66050781), 'rotation':(1.082243, 0.227805, 1.041912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5751.796875, 5223.85693359, 161.55613281), 'rotation':(1.082394, 0.232868, 1.042059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5746.2734375, 5223.83691406, 161.45173828), 'rotation':(1.082339, 0.227823, 1.04201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5740.75046875, 5223.81640625, 161.34732422), 'rotation':(1.082237, 0.232862, 1.041912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5718.65820312, 5223.73535156, 160.92863281), 'rotation':(1.085843, 0.229042, 1.045249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5696.5659375, 5223.65429688, 160.50979492), 'rotation':(1.08574, 0.229038, 1.04516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5691.0434375, 5223.63427734, 160.40515625), 'rotation':(1.085324, 0.231298, 1.044767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5685.52046875, 5223.61425781, 160.30053711), 'rotation':(1.085324, 0.231298, 1.044767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.95117188, 5223.55322266, 159.9869043), 'rotation':(1.083924, 0.230431, 1.04346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5657.90429688, 5223.51269531, 159.77786133), 'rotation':(1.083746, 0.230423, 1.043304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5652.38039062, 5223.49267578, 159.67350586), 'rotation':(1.082667, 0.22719, 1.042312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5646.85789062, 5223.47216797, 159.56944336), 'rotation':(1.080058, 0.232674, 1.039899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.81101562, 5223.43164062, 159.36208984), 'rotation':(1.072565, 0.226807, 1.03295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5624.76515625, 5223.39111328, 159.15579102), 'rotation':(1.067675, 0.232213, 1.028421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5613.72414062, 5223.44824219, 158.95052734), 'rotation':(1.063857, 0.230961, 1.024885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5619.22363281, 5214.99072266, 159.05210938), 'rotation':(-1.063843, -179.769043, -1.103943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5624.7465625, 5215.01074219, 159.15487305), 'rotation':(-1.065063, -179.767883, -1.105255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.7934375, 5215.05126953, 159.36117188), 'rotation':(-1.069946, -179.7677, -1.110504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5646.83984375, 5215.09130859, 159.56852539), 'rotation':(-1.077454, -179.767426, -1.118561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5657.88671875, 5215.13183594, 159.77694336000002), 'rotation':(-1.082672, -179.767242, -1.124207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5663.41015625, 5215.15234375, 159.88143555), 'rotation':(-1.08374, -179.769577, -1.125366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.933125, 5215.17236328, 159.98597656), 'rotation':(-1.08374, -179.769577, -1.125366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5685.50296875, 5215.23291016, 160.29963867), 'rotation':(-1.08429, -179.771744, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5691.02640625, 5215.25341797, 160.40424805), 'rotation':(-1.08429, -179.771744, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5696.54929688, 5215.27392578, 160.50890625), 'rotation':(-1.085327, -179.768692, -1.127045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5707.59523438, 5215.31445312, 160.71832031), 'rotation':(-1.085754, -179.767899, -1.127502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5713.11914062, 5215.33447266, 160.82305664), 'rotation':(-1.085785, -179.770966, -1.127533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5724.165, 5215.36962891, 161.0324707), 'rotation':(-1.085846, -179.767899, -1.127594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5729.68796875, 5215.38525391, 161.13717773), 'rotation':(-1.085846, -179.767899, -1.127594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5740.734375, 5215.46875, 161.34643555), 'rotation':(-1.084137, -179.771011, -1.125793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5800.84570312, 5215.65576172, 162.48024414), 'rotation':(-1.073608, -179.769501, -1.114441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.46484375, 5215.67626953, 162.58542969), 'rotation':(-1.072052, -179.77272, -1.112762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5812.08296875, 5215.69677734, 162.69058594), 'rotation':(-1.072235, -179.767395, -1.112946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5817.70265625, 5215.71728516, 162.79567383), 'rotation':(-1.071075, -179.771667, -1.111725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5885.13039062, 5215.96484375, 164.04382812), 'rotation':(-1.049622, -179.771027, -1.088654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5890.74953125, 5215.98535156, 164.1465625), 'rotation':(-1.049622, -179.771027, -1.088654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5901.98734375, 5216.01855469, 164.35111328), 'rotation':(-1.04129, -179.771332, -1.079651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5907.60640625, 5216.06396484, 164.45308594), 'rotation':(-1.039032, -179.7715, -1.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5913.22507812, 5216.10058594, 164.55501952999998), 'rotation':(-1.039032, -179.7715, -1.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.46335938, 5216.14160156, 164.75892578), 'rotation':(-1.039032, -179.767944, -1.077271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5935.70164062, 5216.18310547, 164.96261718999997), 'rotation':(-1.039093, -179.771484, -1.077332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5946.93992188, 5216.22412109, 165.16509766), 'rotation':(-1.029663, -179.770035, -1.067169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.17875, 5216.26513672, 165.36714844), 'rotation':(-1.029663, -179.77388, -1.0672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5963.79734375, 5216.28564453, 165.46816406000002), 'rotation':(-1.029663, -179.770035, -1.067169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.035625, 5216.32714844, 165.67005859), 'rotation':(-1.027771, -179.772324, -1.065186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.274375, 5216.36865234, 165.87125), 'rotation':(-1.024078, -179.772461, -1.061218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5997.5121875, 5216.40966797, 166.07132812), 'rotation':(-1.016754, -179.771027, -1.053345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5795.2075, 5224.10351562, 162.37511719), 'rotation':(1.073617, 0.226679, 1.033923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5800.82375, 5224.03662109, 162.48041016), 'rotation':(1.07206, 0.232588, 1.03248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.44335938, 5224.05712891, 162.58560547), 'rotation':(1.07223, 0.227279, 1.032638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5812.06296875, 5224.07763672, 162.69078125), 'rotation':(1.071076, 0.232496, 1.031576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5823.30273438, 5224.11914062, 162.90080078), 'rotation':(1.067046, 0.232345, 1.027842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5834.54148438, 5224.16015625, 163.11008789), 'rotation':(1.063023, 0.228031, 1.024101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5840.16109375, 5224.18066406, 163.21451172), 'rotation':(1.063023, 0.228031, 1.024101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.78078125, 5224.20117188, 163.31875976999999), 'rotation':(1.061015, 0.232139, 1.022242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5851.40039062, 5224.22167969, 163.42285156), 'rotation':(1.05885, 0.227875, 1.020247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5857.02046875, 5224.2421875, 163.52677734), 'rotation':(1.056985, 0.231992, 1.018501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5862.6396875, 5224.26318359, 163.63050781), 'rotation':(1.055961, 0.227981, 1.017556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5879.49851562, 5224.32470703, 163.94115234), 'rotation':(1.049636, 0.228966, 1.011691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5890.73828125, 5224.36621094, 164.14691406000003), 'rotation':(1.045326, 0.228794, 1.007686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5907.5971875, 5224.42773438, 164.45345702999998), 'rotation':(1.03909, 0.228517, 1.001895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5913.21679688, 5224.44824219, 164.55542968999998), 'rotation':(1.03909, 0.228517, 1.001895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.4565625, 5224.48974609, 164.75935547), 'rotation':(1.03909, 0.228517, 1.001895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.0771875, 5224.51611328, 164.86134765999998), 'rotation':(1.034377, 0.230195, 0.997516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5935.69679688, 5224.54199219, 164.96308593999998), 'rotation':(1.034377, 0.230195, 0.997516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.316875, 5224.52685547, 165.06455078), 'rotation':(1.029658, 0.229958, 0.993131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5963.79539062, 5224.60058594, 165.46869141), 'rotation':(1.029576, 0.226099, 0.993063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.27492188, 5224.68310547, 165.87179688), 'rotation':(1.020403, 0.22741, 0.984528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.89453125, 5224.70361328, 165.97193359000002), 'rotation':(1.016708, 0.227114, 0.98109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.81734375, 4339.89796875, 160.64285156), 'rotation':(0.277688, 90.858124, 0.275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.06492188, 4323.2821875, 160.56230469), 'rotation':(0.277845, 90.853348, 0.275167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.14796875, 4317.74367188, 160.53542969), 'rotation':(0.277845, 90.853348, 0.275167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.56054688, 4290.05078125, 160.40109375), 'rotation':(0.277941, 90.855347, 0.275252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.64304688, 4284.51265625, 160.37426758), 'rotation':(0.27749, 90.854836, 0.274809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.890625, 4267.89648438, 160.29414062), 'rotation':(0.275858, 90.854813, 0.273213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.973125, 4262.3584375, 160.26754883), 'rotation':(0.275031, 90.858002, 0.272403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.055625, 4256.819375, 160.2409668), 'rotation':(0.275031, 90.858002, 0.272403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.30320312, 4240.20359375, 160.16132812), 'rotation':(0.274676, 90.853912, 0.272049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.38578125, 4234.665, 160.13476562), 'rotation':(0.274553, 90.85862, 0.271935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.46828125, 4229.12648438, 160.10834961), 'rotation':(0.273208, 90.855125, 0.270618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.63328125, 4218.04929688, 160.0559668), 'rotation':(0.270291, 90.855156, 0.267748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.71578125, 4212.51078125, 160.0299707), 'rotation':(0.268925, 90.854004, 0.266403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5785.88085938, 4201.43359375, 159.97797852), 'rotation':(0.268932, 90.854065, 0.266423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.96335938, 4195.895, 159.95198242), 'rotation':(0.268925, 90.854004, 0.266403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.04640625, 4190.35640625, 159.92608398000002), 'rotation':(0.26745, 90.856506, 0.264954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.12890625, 4184.816875, 159.9002832), 'rotation':(0.26745, 90.856506, 0.264954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5786.21140625, 4179.27828125, 159.87469726999998), 'rotation':(0.264793, 90.853485, 0.262359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.51757812, 4157.12648438, 159.77378906), 'rotation':(0.259267, 90.853401, 0.256927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5786.50976562, 4151.58789062, 159.74886719), 'rotation':(0.257874, 90.858139, 0.255558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.27929688, 4334.48390625, 160.61599609), 'rotation':(-0.277863, -89.146606, -0.280579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.444375, 4323.40671875, 160.56230469), 'rotation':(-0.277954, -89.144653, -0.28064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.52734375, 4317.868125, 160.53542969), 'rotation':(-0.277954, -89.144653, -0.28064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.69234375, 4306.79148438, 160.48168945), 'rotation':(-0.277954, -89.144653, -0.28064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.77492188, 4301.25242188, 160.45481445), 'rotation':(-0.277954, -89.144592, -0.28067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5792.93992188, 4290.1753125, 160.40109375), 'rotation':(-0.277496, -89.145203, -0.280182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5793.0225, 4284.63671875, 160.37424805), 'rotation':(-0.276672, -89.145172, -0.279358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5793.105, 4279.098125, 160.34751953), 'rotation':(-0.275848, -89.141968, -0.278503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5793.3525, 4262.48289062, 160.26754883), 'rotation':(-0.274689, -89.146027, -0.277344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5793.60007812, 4245.86671875, 160.18787109000002), 'rotation':(-0.274689, -89.146027, -0.277344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5793.84765625, 4229.2509375, 160.10834961), 'rotation':(-0.270264, -89.144897, -0.272827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.01265625, 4218.17382812, 160.05595703), 'rotation':(-0.268921, -89.145905, -0.271484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.3428125, 4196.01953125, 159.95198242), 'rotation':(-0.267456, -89.146515, -0.269958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.50828125, 4184.94140625, 159.9002832), 'rotation':(-0.264801, -89.143494, -0.267242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5794.59078125, 4179.4028125, 159.87469726999998), 'rotation':(-0.262115, -89.146576, -0.264526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.83835938, 4162.78710938, 159.79882812), 'rotation':(-0.257874, -89.145386, -0.260223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.54984375, 4483.37648438, 161.32052734), 'rotation':(0.255709, 90.851395, 0.253445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.1753125, 4450.07714844, 161.16832031), 'rotation':(0.265387, 90.856606, 0.262947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.42382812, 4433.42625, 161.09092773), 'rotation':(0.266862, 90.856613, 0.264383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.58890625, 4422.32519531, 161.03881836), 'rotation':(0.268973, 90.856621, 0.266468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.67140625, 4416.77492188, 161.01250977), 'rotation':(0.270674, 90.852097, 0.268137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.836875, 4405.67429688, 160.95955078), 'rotation':(0.273604, 90.856201, 0.271004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.00296875, 4394.57375, 160.90654297), 'rotation':(0.273617, 90.853249, 0.27103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5783.16796875, 4383.473125, 160.85339844), 'rotation':(0.274669, 90.855133, 0.272055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.2509375, 4377.92234375, 160.82673828), 'rotation':(0.274669, 90.855133, 0.272055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.71289062, 4372.49460938, 160.80001953000001), 'rotation':(-0.276154, -89.144867, -0.278809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.63039062, 4378.04492188, 160.82673828), 'rotation':(-0.275482, -89.144867, -0.278137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.46484375, 4389.14601562, 160.8799707), 'rotation':(-0.274689, -89.144867, -0.277313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5791.21679688, 4405.796875, 160.95955078), 'rotation':(-0.273621, -89.146729, -0.276245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.05125, 4416.89746094, 161.0125), 'rotation':(-0.272644, -89.143341, -0.275269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5790.96875, 4422.44773438, 161.03879883), 'rotation':(-0.270691, -89.147888, -0.273254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.80320312, 4433.54882812, 161.0909082), 'rotation':(-0.268982, -89.143311, -0.271545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.5546875, 4450.1996875, 161.16830078), 'rotation':(-0.265991, -89.144562, -0.268463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.4409375, 4461.29929688, 161.21963867), 'rotation':(-0.263641, -89.143494, -0.266052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.390625, 4466.85058594, 161.24508789), 'rotation':(-0.261932, -89.148468, -0.264313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.25390625, 4479.08398438, 161.30064453), 'rotation':(-0.258911, -89.143433, -0.261261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.17234375, 4484.56347656, 161.3252832), 'rotation':(-0.257172, -89.14859, -0.25946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.09078125, 4490.04492188, 161.34977539), 'rotation':(-0.255768, -89.143463, -0.258026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.81296875, 4742.828125, 162.25583008), 'rotation':(0.135866, 90.853363, 0.135215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5777.8975, 4737.14599609, 162.24212891), 'rotation':(0.137826, 90.856926, 0.137165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5777.98242188, 4731.46435547, 162.22800781), 'rotation':(0.141481, 90.851631, 0.140787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.066875, 4725.78271484, 162.21348633), 'rotation':(0.145483, 90.857056, 0.144759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.151875, 4720.10058594, 162.19856445), 'rotation':(0.149137, 90.851669, 0.148354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.32125, 4708.73681641, 162.16746094), 'rotation':(0.160598, 90.857048, 0.159708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.57515625, 4691.69287109, 162.11833008), 'rotation':(0.166431, 90.854691, 0.165471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5778.6596875, 4686.01074219, 162.10151367), 'rotation':(0.167995, 90.857025, 0.167019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5778.9140625, 4668.9653125, 162.04879883), 'rotation':(0.182311, 90.857117, 0.181151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.08351562, 4657.60203125, 162.01176758), 'rotation':(0.189387, 90.857239, 0.188152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.25242188, 4646.23875, 161.97338867), 'rotation':(0.194613, 90.856934, 0.193293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.50632812, 4629.19382812, 161.91459961), 'rotation':(0.197474, 90.856506, 0.196121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.59132812, 4623.5121875, 161.89445312), 'rotation':(0.20298, 90.853409, 0.201556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.76023438, 4612.14890625, 161.85286133), 'rotation':(0.208703, 90.853447, 0.207186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.9296875, 4600.785625, 161.81013672), 'rotation':(0.214311, 90.856583, 0.21272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5780.0146875, 4595.10398438, 161.78857422), 'rotation':(0.217125, 90.85273, 0.215486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.09914062, 4589.42234375, 161.76686523), 'rotation':(0.218498, 90.856956, 0.216841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5780.26859375, 4578.05859375, 161.72260742), 'rotation':(0.223764, 90.856995, 0.222023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.5225, 4561.01269531, 161.65426758), 'rotation':(0.231796, 90.852104, 0.229939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.691875, 4549.64941406, 161.60739258), 'rotation':(0.237055, 90.852158, 0.235108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.84179688, 4532.6059375, 161.53610351999998), 'rotation':(0.242062, 90.859016, 0.240027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5789.50390625, 4529.3828125, 161.52189453), 'rotation':(-0.244507, -89.145813, -0.246582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5789.15578125, 4544.089375, 161.5837207), 'rotation':(-0.239777, -89.140991, -0.241791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5789.07078125, 4549.77148438, 161.60737305), 'rotation':(-0.238525, -89.147461, -0.24054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.73289062, 4572.49851562, 161.70008789), 'rotation':(-0.229034, -89.147827, -0.230865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.47851562, 4589.54445312, 161.7668457), 'rotation':(-0.22113, -89.147949, -0.222839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.3090625, 4600.90773438, 161.81011719), 'rotation':(-0.217133, -89.147308, -0.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.14015625, 4612.27101562, 161.85286133), 'rotation':(-0.214325, -89.143402, -0.215942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.05515625, 4617.95265625, 161.87375977), 'rotation':(-0.214325, -89.143402, -0.215942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5787.97070312, 4623.63476562, 161.89444336), 'rotation':(-0.20871, -89.146515, -0.210236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5787.631875, 4646.36132812, 161.97336914), 'rotation':(-0.194458, -89.148376, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5787.46289062, 4657.72507812, 162.01176758), 'rotation':(-0.192749, -89.148193, -0.194061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5787.2934375, 4669.08789062, 162.0487793), 'rotation':(-0.185669, -89.148254, -0.18689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.87015625, 4697.49707031, 162.13488281), 'rotation':(-0.166443, -89.145294, -0.167389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5786.53125, 4720.22363281, 162.19854492000002), 'rotation':(-0.152954, -89.148285, -0.153778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.36179688, 4731.58740234, 162.22800781), 'rotation':(-0.145477, -89.148315, -0.14621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.276875, 4737.26904297, 162.24212891), 'rotation':(-0.141479, -89.142975, -0.142212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5773.45898438, 5034.97314453, 162.42604492), 'rotation':(-0.079224, 90.852577, -0.079437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5773.71140625, 5018.02978516, 162.44691406), 'rotation':(-0.066345, 90.858047, -0.066498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5773.79539062, 5012.38183594, 162.45291016), 'rotation':(-0.062225, 90.852448, -0.062347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5773.96390625, 5001.0859375, 162.46365234), 'rotation':(-0.053619, 90.857925, -0.053711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.13234375, 4989.79003906, 162.47326171999998), 'rotation':(-0.045959, 90.855362, -0.046021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.21679688, 4984.14257812, 162.47729492), 'rotation':(-0.045959, 90.855362, -0.046021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5774.38476562, 4972.84667969, 162.48318359), 'rotation':(-0.024261, 90.855347, -0.024292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.55320312, 4961.55078125, 162.48640625), 'rotation':(-0.013367, 90.852051, -0.013367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5774.8896875, 4938.95898438, 162.48955078), 'rotation':(-0.007812, 90.852013, -0.007812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.97414062, 4933.31054688, 162.49032227), 'rotation':(-0.007904, 90.854919, -0.007904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.31054688, 4910.71972656, 162.48962891), 'rotation':(0.019616, 90.852089, 0.019603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.395, 4905.07177734, 162.48683594), 'rotation':(0.02868, 90.854362, 0.028644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.47898438, 4899.42382812, 162.48399414), 'rotation':(0.02881, 90.854294, 0.028784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.6475, 4888.12744141, 162.47833008), 'rotation':(0.028673, 90.854294, 0.028643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.8159375, 4876.83251953, 162.47189453000001), 'rotation':(0.033673, 90.854828, 0.033644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5775.98390625, 4865.53662109, 162.46287109000002), 'rotation':(0.043597, 90.851662, 0.043533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.06835938, 4859.88818359, 162.45760742000002), 'rotation':(0.053515, 90.854805, 0.05342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.40476562, 4837.29736328, 162.43142578), 'rotation':(0.06822, 90.856834, 0.068061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.48875, 4831.64941406, 162.42428711), 'rotation':(0.072666, 90.853897, 0.072477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.9096875, 4803.40966797, 162.38083008), 'rotation':(0.09845, 90.853973, 0.098117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5776.99414062, 4797.76220703, 162.37089844), 'rotation':(0.09845, 90.853973, 0.098117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.13625, 4784.84570312, 162.34749023), 'rotation':(0.102719, 90.854012, 0.102353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.95265625, 4826.12597656, 162.41648438), 'rotation':(-0.081207, -89.146057, -0.081421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.78421875, 4837.42236328, 162.43142578), 'rotation':(-0.072662, -89.146088, -0.072845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.36375, 4865.66113281, 162.46287109000002), 'rotation':(-0.053528, -89.148315, -0.053619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.1953125, 4876.95703125, 162.47189453000001), 'rotation':(-0.04361, -89.145203, -0.043671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.11132812, 4882.60546875, 162.47521484), 'rotation':(-0.033691, -89.145203, -0.033722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.026875, 4888.25244141, 162.47833008), 'rotation':(-0.033691, -89.145203, -0.033722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.0165625, 4956.02832031, 162.4872168), 'rotation':(0.007821, -89.145081, 0.007816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.93265625, 4961.67578125, 162.48640625), 'rotation':(0.007903, -89.145081, 0.007907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.84859375, 4967.32421875, 162.48507812), 'rotation':(0.01336, -89.147949, 0.013355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.68015625, 4978.61962891, 162.48074219), 'rotation':(0.024268, -89.144623, 0.024246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.09078125, 5018.15478516, 162.44691406), 'rotation':(0.062216, -89.147461, 0.06208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.006875, 5023.80273438, 162.44042969), 'rotation':(0.066335, -89.147522, 0.066181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.92234375, 5029.45068359, 162.43347656), 'rotation':(0.070631, -89.141937, 0.070455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5781.83835938, 5035.09863281, 162.42602539), 'rotation':(0.075112, -89.14743, 0.074908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.5859375, 5052.04248047, 162.40134766), 'rotation':(0.085712, -89.144562, 0.085463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5771.06789062, 5195.39453125, 162.06765625), 'rotation':(-0.174103, 90.852814, -0.175171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5771.15085938, 5189.84423828, 162.08445312), 'rotation':(-0.174103, 90.852814, -0.175171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5771.31640625, 5178.74316406, 162.11723633), 'rotation':(-0.165771, 90.853752, -0.166748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.06054688, 5128.79052734, 162.24964844), 'rotation':(-0.144318, 90.855789, -0.14505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.14304688, 5123.24023438, 162.26291992), 'rotation':(-0.13678, 90.852867, -0.137451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5772.22609375, 5117.69042969, 162.2756543), 'rotation':(-0.13678, 90.852867, -0.137451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.47414062, 5101.04003906, 162.31167969), 'rotation':(-0.121918, 90.852745, -0.122406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.10203125, 5084.51269531, 162.34567383), 'rotation':(0.109283, -89.145782, 0.108869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.77101562, 5106.71386719, 162.2999707), 'rotation':(0.118053, -89.144012, 0.117574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.52296875, 5123.36425781, 162.26291992), 'rotation':(0.129439, -89.144226, 0.128849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.44046875, 5128.91455078, 162.24964844), 'rotation':(0.136775, -89.147156, 0.136129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.35742188, 5134.46533203, 162.23599609000001), 'rotation':(0.136775, -89.147156, 0.136129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5780.109375, 5151.11523438, 162.19337890999998), 'rotation':(0.14801, -89.146423, 0.147247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5779.94382812, 5162.21630859, 162.16390625), 'rotation':(0.15301, -89.146393, 0.152192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.86132812, 5167.76660156, 162.14868164), 'rotation':(0.156172, -89.146301, 0.155325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.77828125, 5173.31689453, 162.13311523000002), 'rotation':(0.159294, -89.146362, 0.15842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.44726562, 5195.51806641, 162.06765625), 'rotation':(0.172387, -89.146301, 0.171358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.36914062, 5200.76367188, 162.05172851999998), 'rotation':(0.174102, -89.147156, 0.173054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5766.5434375, 5499.00734375, 160.97911133), 'rotation':(-0.200897, 90.853966, -0.202332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5766.7959375, 5482.04589844, 161.03874023), 'rotation':(-0.202454, 90.854652, -0.203888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5766.964375, 5470.73828125, 161.07902344000001), 'rotation':(-0.205292, 90.854721, -0.206787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5767.04882812, 5465.08496094, 161.09942383), 'rotation':(-0.205292, 90.854721, -0.206787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.30171875, 5448.12351562, 161.16160156), 'rotation':(-0.21109, 90.854721, -0.212646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.4696875, 5436.8159375, 161.20356445), 'rotation':(-0.212555, 90.858223, -0.214142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5767.63867188, 5425.50828125, 161.24568359), 'rotation':(-0.213074, 90.854637, -0.214661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.80710938, 5414.20070312, 161.28808594), 'rotation':(-0.214294, 90.854637, -0.215912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.89109375, 5408.546875, 161.30935546999999), 'rotation':(-0.215515, 90.854652, -0.217133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.3125, 5380.27882812, 161.41641601999999), 'rotation':(-0.216919, 90.85511, -0.218597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.4809375, 5368.97117188, 161.45912109), 'rotation':(-0.216217, 90.855087, -0.217865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.56546875, 5363.31738281, 161.48038086), 'rotation':(-0.215515, 90.85228, -0.217163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.90234375, 5340.70265625, 161.56520508), 'rotation':(-0.214539, 90.854179, -0.216156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.98679688, 5335.04929688, 161.58636719), 'rotation':(-0.214508, 90.859558, -0.216125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.1553125, 5323.74267578, 161.62858398), 'rotation':(-0.213104, 90.85244, -0.214661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5769.23976562, 5318.08886719, 161.64953125), 'rotation':(-0.213104, 90.85244, -0.214661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.40820312, 5306.78125, 161.6909375), 'rotation':(-0.210083, 90.855339, -0.211639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.4921875, 5301.12744141, 161.71151367000002), 'rotation':(-0.208679, 90.855095, -0.210175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.8290625, 5278.51269531, 161.79313477), 'rotation':(-0.203796, 90.857819, -0.205231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5769.99757812, 5267.20654297, 161.83291992), 'rotation':(-0.201599, 90.853157, -0.203033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5770.25046875, 5250.24511719, 161.8912207), 'rotation':(-0.19577, 90.853119, -0.197113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5770.39890625, 5240.27929688, 161.92483398000002), 'rotation':(-0.192688, 90.856255, -0.19397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.006875, 5493.47753906, 160.99894531), 'rotation':(0.200917, -89.14267, 0.199509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5775.09132812, 5487.82375, 161.0187793), 'rotation':(0.20244, -89.145294, 0.201016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.1753125, 5482.16992188, 161.03874023), 'rotation':(0.205302, -89.148193, 0.203832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.93359375, 5431.28664062, 161.22458984000002), 'rotation':(0.214277, -89.145325, 0.212687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.01804688, 5425.63234375, 161.24568359), 'rotation':(0.214277, -89.145325, 0.212687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.1865625, 5414.32519531, 161.28808594), 'rotation':(0.215499, -89.145325, 0.213882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.355, 5403.01804688, 161.33073242), 'rotation':(0.217255, -89.145966, 0.215612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.43945312, 5397.36425781, 161.3521582), 'rotation':(0.217255, -89.145966, 0.215612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.86085938, 5369.09570312, 161.45912109), 'rotation':(0.21552, -89.144897, 0.213896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5776.94484375, 5363.44238281, 161.48038086), 'rotation':(0.214891, -89.147766, 0.213294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.11328125, 5352.13476562, 161.5228418), 'rotation':(0.214536, -89.145813, 0.212927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.61914062, 5318.21289062, 161.64953125), 'rotation':(0.210069, -89.147583, 0.208543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.78757812, 5306.90625, 161.6909375), 'rotation':(0.208649, -89.144958, 0.207135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5777.95554688, 5295.59863281, 161.73211914), 'rotation':(0.207713, -89.14679, 0.206214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.12453125, 5284.29150391, 161.77296875), 'rotation':(0.203779, -89.14682, 0.202343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5778.20851562, 5278.63769531, 161.79313477), 'rotation':(0.2016, -89.146851, 0.200195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.29296875, 5272.98388672, 161.813125), 'rotation':(0.199701, -89.146851, 0.198325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.62984375, 5250.36962891, 161.8912207), 'rotation':(0.193745, -89.146912, 0.192443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5587.11132812, 5060.3828125, 158.78357422), 'rotation':(-1.028687, -179.25386, -1.066132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5598.19140625, 5060.52294922, 158.98393555), 'rotation':(-1.033478, -179.255325, -1.071289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5614.80859375, 5060.73339844, 159.28863281), 'rotation':(-1.053284, -179.254593, -1.09256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5620.348125, 5060.80322266, 159.39148438), 'rotation':(-1.063049, -179.254227, -1.103088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5631.42675781, 5060.94384766, 159.59792969), 'rotation':(-1.068115, -179.253311, -1.108521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5653.58351562, 5061.22412109, 160.01191406), 'rotation':(-1.072113, -179.253998, -1.112823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5659.12257812, 5061.29443359, 160.11645508), 'rotation':(-1.080353, -179.253754, -1.121704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5670.20117188, 5061.43457031, 160.32625), 'rotation':(-1.084381, -179.256378, -1.126038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5675.73976562, 5061.50488281, 160.43113281), 'rotation':(-1.08429, -179.251617, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5686.81789062, 5061.64501953, 160.64109375), 'rotation':(-1.086517, -179.252777, -1.128326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5708.97414062, 5061.92578125, 161.06358398), 'rotation':(-1.095154, -179.255493, -1.137634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5742.20703125, 5062.37988281, 161.70261719), 'rotation':(-1.101685, -179.252274, -1.144714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5747.74609375, 5062.45019531, 161.80924805), 'rotation':(-1.102356, -179.255859, -1.145416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5753.2846875, 5062.52001953, 161.91599609000002), 'rotation':(-1.103546, -179.252548, -1.146729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5758.82617188, 5062.42041016, 162.02279296999998), 'rotation':(-1.104462, -179.252731, -1.147705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5747.69289062, 5070.79833984, 161.81027344), 'rotation':(1.103629, 0.747476, 1.0617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5708.92039062, 5070.30761719, 161.06457031), 'rotation':(1.09951, 0.747716, 1.057894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5703.381875, 5070.23730469, 160.95865234000001), 'rotation':(1.095146, 0.744508, 1.053861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5697.84226562, 5070.16699219, 160.85286133), 'rotation':(1.095146, 0.744508, 1.053861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5681.22507812, 5069.95654297, 160.53702148), 'rotation':(1.086505, 0.74722, 1.045869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5675.6865625, 5069.88623047, 160.43214844), 'rotation':(1.084443, 0.743563, 1.043949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5664.6084375, 5069.74609375, 160.22235351999998), 'rotation':(1.084292, 0.743557, 1.04381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5659.06984375, 5069.67626953, 160.11748047), 'rotation':(1.084388, 0.748439, 1.043899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5647.99070312, 5069.53564453, 159.90899414), 'rotation':(1.072135, 0.745989, 1.032548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5636.91113281, 5069.39550781, 159.70219727), 'rotation':(1.06805, 0.742034, 1.028767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5631.37257812, 5069.32519531, 159.59889648), 'rotation':(1.06805, 0.742034, 1.028767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5620.29296875, 5069.18505859, 159.39242188), 'rotation':(1.06805, 0.746751, 1.028769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5614.754375, 5069.11474609, 159.28960938), 'rotation':(1.063057, 0.745755, 1.024144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5609.2153125, 5069.04443359, 159.18751953), 'rotation':(1.063057, 0.745755, 1.024144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5598.13671875, 5068.90429688, 158.98488281), 'rotation':(1.043462, 0.745036, 1.005962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5587.058125, 5068.76318359, 158.78453125), 'rotation':(1.033469, 0.741506, 0.996674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5796.88085938, 5063.03955078, 162.75662109), 'rotation':(-1.103912, -179.25415, -1.147095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5802.45460938, 5063.10986328, 162.86393555), 'rotation':(-1.102783, -179.249023, -1.145874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5808.02828125, 5063.18066406, 162.97124023), 'rotation':(-1.102295, -179.254333, -1.145355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5835.89648438, 5063.53369141, 163.50764648), 'rotation':(-1.102386, -179.254333, -1.145447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5841.47023438, 5063.60449219, 163.61483398000001), 'rotation':(-1.101135, -179.251663, -1.144104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5847.04390625, 5063.67480469, 163.72183594), 'rotation':(-1.101135, -179.251663, -1.144104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5852.6171875, 5063.74560547, 163.82875), 'rotation':(-1.098602, -179.254868, -1.141357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.19140625, 5063.81591797, 163.93558593999998), 'rotation':(-1.097565, -179.25177, -1.140228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5863.76515625, 5063.88671875, 164.04240234), 'rotation':(-1.097565, -179.25177, -1.140228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5880.4853125, 5064.09814453, 164.36253906000002), 'rotation':(-1.095459, -179.249146, -1.137939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5908.35453125, 5064.45117188, 164.89349609), 'rotation':(-1.088623, -179.249405, -1.130585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.50148438, 5064.59228516, 165.10501953), 'rotation':(-1.086487, -179.255402, -1.128296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.649375, 5064.72460938, 165.31644531), 'rotation':(-1.086487, -179.252045, -1.128296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5947.36960938, 5064.97851562, 165.63205078), 'rotation':(-1.078705, -179.25386, -1.119904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5952.94335938, 5065.04931641, 165.73677734), 'rotation':(-1.07608, -179.25592, -1.117096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.8125, 5065.40234375, 166.26046875), 'rotation':(-1.075989, -179.252655, -1.116974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56101562, 5073.96337891, 166.57578125), 'rotation':(1.069327, 0.748385, 1.02997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.68164062, 5073.61035156, 166.05330078), 'rotation':(1.07598, 0.747351, 1.036122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.52976562, 5073.46875, 165.84375), 'rotation':(1.07598, 0.747351, 1.036122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.80226562, 5073.25683594, 165.52917968999998), 'rotation':(1.078637, 0.746098, 1.038579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.65085938, 5073.11572266, 165.31845703), 'rotation':(1.083842, 0.746334, 1.043398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5925.07515625, 5073.04492188, 165.21279297), 'rotation':(1.083842, 0.746334, 1.043398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.348125, 5072.83349609, 164.89539062), 'rotation':(1.087141, 0.745333, 1.046449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.19625, 5072.69189453, 164.68335938), 'rotation':(1.089907, 0.745439, 1.049007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.62015625, 5072.62158203, 164.57712891), 'rotation':(1.091307, 0.745556, 1.050308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5880.46875, 5072.48046875, 164.36427734), 'rotation':(1.094142, 0.745596, 1.05293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5874.89359375, 5072.40966797, 164.25763672000002), 'rotation':(1.095439, 0.750858, 1.054135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5869.31789062, 5072.33935547, 164.15087891), 'rotation':(1.096901, 0.745701, 1.05549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5863.7421875, 5072.26855469, 164.04402344), 'rotation':(1.09755, 0.744917, 1.056086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5858.16601562, 5072.19775391, 163.93712890999998), 'rotation':(1.09755, 0.744917, 1.056086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5824.711875, 5071.77392578, 163.29445312), 'rotation':(1.102399, 0.745673, 1.06056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5819.13625, 5071.70361328, 163.18711914), 'rotation':(1.10229, 0.749052, 1.060465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5807.98390625, 5071.56201172, 162.97243164), 'rotation':(1.10229, 0.745669, 1.060462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.930625, 4353.41796875, 163.50040038999998), 'rotation':(-0.931824, -179.93602, -0.962524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5964.29492188, 4353.40476562, 163.23107421999998), 'rotation':(-0.916718, -179.939941, -0.946411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.75, 4353.40039062, 163.14233398), 'rotation':(-0.916656, -179.939941, -0.94635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5942.11421875, 4353.38769531, 162.87706055), 'rotation':(-0.895264, -179.940262, -0.923584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.93359375, 4353.37011719, 162.53255859), 'rotation':(-0.866516, -179.944, -0.893036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5914.38914062, 4353.36570312, 162.44868164), 'rotation':(-0.859558, -179.939407, -0.88562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.84179688, 4353.36132812, 162.3649707), 'rotation':(-0.859558, -179.939407, -0.88562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.7509375, 4353.35304688, 162.19957031), 'rotation':(-0.847107, -179.942062, -0.872437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5892.20609375, 4353.34863281, 162.1178418), 'rotation':(-0.83902, -179.946838, -0.863892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5886.660625, 4353.34421875, 162.03681641), 'rotation':(-0.830719, -179.942535, -0.855103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5858.93265625, 4353.32273438, 161.64251953000002), 'rotation':(-0.793854, -179.949753, -0.816101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5842.29390625, 4353.30957031, 161.4147168), 'rotation':(-0.765533, -179.946304, -0.786224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5836.74757812, 4353.30515625, 161.34104492), 'rotation':(-0.753937, -179.946625, -0.773987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5831.19921875, 4353.30078125, 161.26855469), 'rotation':(-0.731049, -179.947205, -0.749878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5820.1084375, 4353.29199219, 161.12714844), 'rotation':(-0.708313, -179.947784, -0.725983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5814.5625, 4353.28757812, 161.05821289), 'rotation':(-0.702698, -179.945999, -0.720093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5803.4696875, 4353.27882812, 160.92201172), 'rotation':(-0.702698, -179.945999, -0.720093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56203125, 4361.81152344, 163.77701172), 'rotation':(0.925784, 0.014961, 0.896226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5992.01859375, 4361.80710938, 163.684375), 'rotation':(0.956985, 0.061185, 0.925406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.47359375, 4361.80273438, 163.59204102), 'rotation':(0.951944, 0.059749, 0.920692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5975.3828125, 4361.79445312, 163.40982422), 'rotation':(0.931836, 0.059089, 0.901876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5942.11085938, 4361.76855469, 162.87710938), 'rotation':(0.90946, 0.057331, 0.880918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.9296875, 4361.75097656, 162.53260742), 'rotation':(0.880848, 0.059296, 0.85406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.83789062, 4361.7421875, 162.36500977), 'rotation':(0.866512, 0.055997, 0.8406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.7465625, 4361.73390625, 162.19959961), 'rotation':(0.855181, 0.058168, 0.829941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5892.20117188, 4361.72949219, 162.11787109), 'rotation':(0.847107, 0.057927, 0.822333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5886.65625, 4361.72507812, 162.03686523), 'rotation':(0.839096, 0.053156, 0.814781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5875.5634375, 4361.71632812, 161.87689453000002), 'rotation':(0.822642, 0.057219, 0.799273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5870.01804688, 4361.71191406, 161.79804688000002), 'rotation':(0.814363, 0.056979, 0.791452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5864.47265625, 4361.7075, 161.71994141), 'rotation':(0.806276, 0.05675, 0.783821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5842.288125, 4361.69042969, 161.41473632999998), 'rotation':(0.776838, 0.053983, 0.755978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5836.74171875, 4361.68601562, 161.34106445), 'rotation':(0.765548, 0.053684, 0.745284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5831.19335938, 4361.68164062, 161.26857422), 'rotation':(0.742646, 0.05851, 0.723579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5825.6475, 4361.67726562, 161.19726562), 'rotation':(0.731049, 0.052777, 0.712559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5814.55617188, 4361.66796875, 161.05821289), 'rotation':(0.708304, 0.052205, 0.690956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5809.00828125, 4361.66359375, 160.99001953), 'rotation':(0.702731, 0.053994, 0.685641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5803.46289062, 4361.65917969, 160.92201172), 'rotation':(0.702731, 0.053994, 0.685641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5510.05617188, 4503.75734375, 158.28889648), 'rotation':(-0.454193, -179.930908, -0.461456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5515.70265625, 4503.76367188, 158.33369141), 'rotation':(-0.454224, -179.935577, -0.461487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5521.34914062, 4503.77, 158.37907227), 'rotation':(-0.458923, -179.932068, -0.466309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5532.64210938, 4503.78273438, 158.47291992), 'rotation':(-0.478149, -179.931747, -0.486176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5543.93507812, 4503.79539062, 158.57083008), 'rotation':(-0.49762, -179.931427, -0.506317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5549.5815625, 4503.80125, 158.62131836), 'rotation':(-0.516785, -179.931076, -0.526184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5555.22753906, 4503.80761719, 158.67282226999998), 'rotation':(-0.52655, -179.930908, -0.536285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5583.45800781, 4503.839375, 158.93893555), 'rotation':(-0.555023, -179.932251, -0.565857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5589.105, 4503.84570312, 158.9946875), 'rotation':(-0.555023, -179.932251, -0.565857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5594.75097656, 4503.85203125, 159.05097656), 'rotation':(-0.570984, -179.92897, -0.582458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5600.39648438, 4503.85789062, 159.10880859), 'rotation':(-0.586945, -179.931625, -0.59906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5606.0434375, 4503.86425781, 159.16693359), 'rotation':(-0.586945, -179.931625, -0.59906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5617.33496094, 4503.87695312, 159.28445312), 'rotation':(-0.594849, -179.929855, -0.6073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5622.9809375, 4503.88328125, 159.34404297), 'rotation':(-0.604492, -179.930542, -0.617371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5628.62695312, 4503.88964844, 159.40475586), 'rotation':(-0.604492, -179.930542, -0.617371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5651.2109375, 4503.91453125, 159.65831055), 'rotation':(-0.662506, -179.92926, -0.677948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5673.79390625, 4503.93992188, 159.92385742), 'rotation':(-0.680786, -179.926743, -0.697113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5679.43992188, 4503.94628906, 159.99213867), 'rotation':(-0.680786, -179.926743, -0.697113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5690.73140625, 4503.95898438, 160.13157227), 'rotation':(-0.714996, -179.929016, -0.733032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5696.37742188, 4503.9653125, 160.20292969), 'rotation':(-0.714996, -179.929016, -0.733032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5713.3134375, 4503.9809375, 160.42123046999998), 'rotation':(-0.740631, -179.927811, -0.759949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5730.25, 4504.03027344, 160.64580078), 'rotation':(-0.765594, -179.92363, -0.786285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5735.89601562, 4504.0425, 160.72251953), 'rotation':(-0.775452, -179.928101, -0.796631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5747.1865625, 4504.05515625, 160.87874023), 'rotation':(-0.795349, -179.927551, -0.817657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5752.83203125, 4504.06101562, 160.95827148), 'rotation':(-0.805206, -179.922562, -0.828094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5764.12257812, 4504.07375, 161.11951172), 'rotation':(-0.82019, -179.921005, -0.843933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.76757812, 4504.08007812, 161.20045898), 'rotation':(-0.820251, -179.926193, -0.843994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5752.85546875, 4512.40917969, 160.95874023), 'rotation':(0.81532, 0.073007, 0.792351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5747.21, 4512.40332031, 160.87920898000002), 'rotation':(0.805218, 0.077441, 0.782814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5735.91945312, 4512.390625, 160.72295898000002), 'rotation':(0.785369, 0.076893, 0.764058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5724.62648438, 4512.37792969, 160.57041992), 'rotation':(0.765603, 0.076357, 0.745349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5707.6884375, 4512.35890625, 160.34838867), 'rotation':(0.745631, 0.075827, 0.726409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5690.7509375, 4512.33984375, 160.13194336), 'rotation':(0.732053, 0.074504, 0.713525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.16796875, 4512.31445312, 159.85708984000001), 'rotation':(0.680792, 0.073242, 0.664755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5628.64304688, 4512.27050781, 159.4050293), 'rotation':(0.623822, 0.072726, 0.610347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5622.9965625, 4512.26414062, 159.34429688), 'rotation':(0.623822, 0.072726, 0.610347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5617.35109375, 4512.2578125, 159.28472656), 'rotation':(0.604499, 0.069446, 0.591857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5611.70359375, 4512.25148438, 159.22580078000001), 'rotation':(0.594841, 0.070138, 0.582594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5589.11960938, 4512.2265625, 158.99495117), 'rotation':(0.570983, 0.071017, 0.559686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5583.47070312, 4512.22023438, 158.93915039), 'rotation':(0.570983, 0.071017, 0.559686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5572.17921875, 4512.2075, 158.83076172), 'rotation':(0.555035, 0.06773, 0.54436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5566.53367188, 4512.20117188, 158.77763672), 'rotation':(0.53923, 0.070394, 0.529159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5532.651875, 4512.16308594, 158.47306641), 'rotation':(0.48786, 0.068402, 0.4796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56445312, 4512.68210938, 165.01263672000002), 'rotation':(1.053707, 0.086572, 1.015457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.98585938, 4512.67578125, 164.91029297), 'rotation':(1.049438, 0.083299, 1.011512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.24851562, 4512.65722656, 164.60509765999998), 'rotation':(1.040873, 0.08298, 1.003555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.61328125, 4512.60742188, 163.80584961), 'rotation':(1.013491, 0.083247, 0.978107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.4540625, 4512.59472656, 163.61072266), 'rotation':(0.996852, 0.079035, 0.962601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5902.71578125, 4512.57617188, 163.32040039), 'rotation':(0.992659, 0.080826, 0.958701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.5546875, 4512.56398438, 163.12804688), 'rotation':(0.986313, 0.081539, 0.952776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5885.975625, 4512.55761719, 163.03325195), 'rotation':(0.973404, 0.081093, 0.940734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5869.23679688, 4512.5390625, 162.75276367), 'rotation':(0.960441, 0.080653, 0.928643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.07664062, 4512.526875, 162.56882812), 'rotation':(0.941261, 0.080607, 0.910703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5846.91648438, 4512.51414062, 162.38604492000002), 'rotation':(0.937382, 0.07636, 0.907079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5841.33640625, 4512.5078125, 162.29573242), 'rotation':(0.929589, 0.081656, 0.899779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5830.1753125, 4512.49511719, 162.11759766), 'rotation':(0.906387, 0.08091, 0.878039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5819.015625, 4512.48289062, 161.9428125), 'rotation':(0.8908, 0.08042, 0.863414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5807.85453125, 4512.47023438, 161.77094727), 'rotation':(0.879114, 0.077815, 0.852448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5802.27539062, 4512.464375, 161.68533203), 'rotation':(0.879114, 0.077815, 0.852448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5807.828125, 4504.089375, 161.77041992), 'rotation':(-0.87912, -179.92218, -0.906433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5813.40820312, 4504.09570312, 161.85607421999998), 'rotation':(-0.87912, -179.92218, -0.906433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5863.62453125, 4504.151875, 162.65985351999998), 'rotation':(-0.941254, -179.919388, -0.972565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5869.20460938, 4504.15820312, 162.75207031), 'rotation':(-0.947723, -179.922836, -0.979492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5880.36328125, 4504.17039062, 162.93823242), 'rotation':(-0.960449, -179.919342, -0.993073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.52195312, 4504.18261719, 163.12735351999999), 'rotation':(-0.973419, -179.9189, -1.006927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5902.68117188, 4504.1953125, 163.3196582), 'rotation':(-0.986328, -179.918457, -1.020721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.99757812, 4504.22023438, 163.70713867), 'rotation':(-0.996857, -179.920975, -1.032013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.7353125, 4504.234375, 164.00253906), 'rotation':(-1.013489, -179.916748, -1.049835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5947.31398438, 4504.254375, 164.10208984000002), 'rotation':(-1.021881, -179.920074, -1.058838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.47171875, 4504.29054688, 164.30212891), 'rotation':(-1.028137, -179.917465, -1.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5964.05078125, 4504.296875, 164.4025), 'rotation':(-1.028137, -179.917465, -1.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.629375, 4504.30320312, 164.50318359000002), 'rotation':(-1.032379, -179.917328, -1.070099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.20851562, 4504.3090625, 164.60419922), 'rotation':(-1.036621, -179.921173, -1.074677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.36625, 4504.32179688, 164.80734375), 'rotation':(-1.045258, -179.916855, -1.083923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.9453125, 4504.328125, 164.909375), 'rotation':(-1.045258, -179.916855, -1.083923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.52390625, 4504.33398438, 165.01173828), 'rotation':(-1.049438, -179.916702, -1.08844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5765.37203125, 4764.97314453, 161.99801758), 'rotation':(1.05314, 0.370782, 1.014947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5748.38039062, 4764.86914062, 161.69026367), 'rotation':(1.031502, 0.366815, 0.99485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5731.390625, 4764.765625, 161.38638672), 'rotation':(1.024303, 0.370801, 0.988151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5725.72703125, 4764.73046875, 161.28524414), 'rotation':(1.021202, 0.372082, 0.985266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5714.39890625, 4764.66113281, 161.08473633), 'rotation':(1.00871, 0.36616, 0.973638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5708.73632812, 4764.62646484, 160.98551758), 'rotation':(1.002672, 0.371423, 0.968037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5697.40820312, 4764.55712891, 160.78914062), 'rotation':(0.990268, 0.370997, 0.956468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5686.07960938, 4764.48779297, 160.59535156), 'rotation':(0.977701, 0.370563, 0.944744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5657.75875, 4764.31445312, 160.11723633), 'rotation':(0.955004, 0.365055, 0.923544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5629.43945312, 4764.14111328, 159.65803711), 'rotation':(0.92213, 0.366124, 0.892784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5623.7734375, 4764.10644531, 159.56730469000001), 'rotation':(0.92213, 0.366124, 0.892784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5606.78125, 4764.00244141, 159.29896484), 'rotation':(0.901701, 0.366723, 0.873646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5601.1171875, 4763.96777344, 159.21113281), 'rotation':(0.888027, 0.363424, 0.860819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5595.453125, 4763.93310547, 159.12416016), 'rotation':(0.888027, 0.363424, 0.860819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5584.12304688, 4763.86376953, 158.95181641), 'rotation':(0.867625, 0.365906, 0.841642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5578.4575, 4763.82910156, 158.86626953), 'rotation':(0.863029, 0.36281, 0.837306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5555.79785156, 4763.69042969, 158.53234375), 'rotation':(0.826248, 0.36665, 0.802677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5550.13328125, 4763.65576172, 158.45114258), 'rotation':(0.817246, 0.361497, 0.794177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5544.46875, 4763.62109375, 158.37083008), 'rotation':(0.807943, 0.361203, 0.785395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5538.80761719, 4755.20556641, 158.29077148), 'rotation':(-0.794189, -179.641113, -0.816437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5550.13523438, 4755.27490234, 158.45041992), 'rotation':(-0.808014, -179.638763, -0.831055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5555.79980469, 4755.30957031, 158.53163086), 'rotation':(-0.817169, -179.638535, -0.840759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5567.129375, 4755.37890625, 158.69675781), 'rotation':(-0.83548, -179.638016, -0.860138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5578.4575, 4755.44824219, 158.86549805), 'rotation':(-0.85379, -179.632538, -0.879547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5589.78710938, 4755.51757812, 159.03688477), 'rotation':(-0.867584, -179.637787, -0.894165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5595.45070312, 4755.55224609, 159.12334961), 'rotation':(-0.874359, -179.634125, -0.901367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5612.44335938, 4755.65625, 159.38683594), 'rotation':(-0.888031, -179.636566, -0.915894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5618.10695312, 4755.69091797, 159.47601562), 'rotation':(-0.901703, -179.636154, -0.93042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5623.77101562, 4755.72558594, 159.56645508), 'rotation':(-0.915314, -179.632828, -0.944946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5635.09863281, 4755.79492188, 159.74832031), 'rotation':(-0.922119, -179.633865, -0.952179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5640.76269531, 4755.82958984, 159.83951172), 'rotation':(-0.922119, -179.637527, -0.952179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5652.0903125, 4755.89892578, 160.02316406), 'rotation':(-0.928741, -179.632111, -0.959229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5663.41796875, 4755.96826172, 160.21058594), 'rotation':(-0.954987, -179.631241, -0.987244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5669.08203125, 4756.00292969, 160.30574219), 'rotation':(-0.954987, -179.631241, -0.987244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5674.74609375, 4756.03564453, 160.40161133), 'rotation':(-0.968018, -179.634521, -1.00119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5691.73632812, 4756.16894531, 160.6909668), 'rotation':(-0.977722, -179.634888, -1.011505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5697.399375, 4756.20898438, 160.78810547), 'rotation':(-0.983917, -179.629272, -1.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5703.06398438, 4756.24365234, 160.8859375), 'rotation':(-0.990295, -179.634445, -1.024963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5708.72703125, 4756.27832031, 160.98445312), 'rotation':(-0.996399, -179.628799, -1.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5714.39109375, 4756.31298828, 161.08371094), 'rotation':(-1.002594, -179.634064, -1.038147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5742.7075, 4756.48632812, 161.58787109000002), 'rotation':(-1.024384, -179.634659, -1.061554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5754.03421875, 4756.55566406, 161.79104492), 'rotation':(-1.031494, -179.630005, -1.069183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5759.69773438, 4756.59033203, 161.89344727), 'rotation':(-1.031494, -179.630005, -1.069183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5797.87257812, 4756.79199219, 162.59607422), 'rotation':(-1.064362, -179.629852, -1.104462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5808.964375, 4756.85986328, 162.80325195), 'rotation':(-1.073303, -179.629517, -1.114105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5820.05617188, 4756.92724609, 163.01234375), 'rotation':(-1.082092, -179.629196, -1.123566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5825.6015625, 4756.96142578, 163.11767578), 'rotation':(-1.082092, -179.629196, -1.123566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5836.69382812, 4757.02929688, 163.32936523), 'rotation':(-1.095398, -179.628647, -1.137909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.87648438, 4757.16455078, 163.75420898000002), 'rotation':(-1.102264, -179.627853, -1.145325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5864.4228125, 4757.19873047, 163.86128906000002), 'rotation':(-1.102264, -179.627853, -1.145325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5869.96875, 4757.23291016, 163.96871094), 'rotation':(-1.109009, -179.628799, -1.152557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5875.5146875, 4757.26660156, 164.07611328), 'rotation':(-1.109009, -179.628799, -1.152557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5881.05953125, 4757.30078125, 164.18349609), 'rotation':(-1.109009, -179.628799, -1.152557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5892.15085938, 4757.36865234, 164.39826172000002), 'rotation':(-1.108887, -179.628799, -1.152466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5897.69625, 4757.40234375, 164.50576172), 'rotation':(-1.108887, -179.628799, -1.152466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5903.24171875, 4757.43310547, 164.6134375), 'rotation':(-1.110931, -179.626938, -1.154663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.78664062, 4757.45996094, 164.72142578), 'rotation':(-1.114624, -179.626801, -1.158661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5914.33296875, 4757.52929688, 164.82974609000001), 'rotation':(-1.118469, -179.631042, -1.162811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.87796875, 4757.57080078, 164.93841797000002), 'rotation':(-1.122162, -179.626495, -1.166809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5925.42335938, 4757.60498047, 165.04724609000002), 'rotation':(-1.124146, -179.627838, -1.168945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.96875, 4757.63867188, 165.15607422000002), 'rotation':(-1.123993, -179.627838, -1.168762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5936.5146875, 4757.67285156, 165.26496093999998), 'rotation':(-1.123993, -179.62262, -1.168762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5947.6059375, 4757.74072266, 165.48273438), 'rotation':(-1.124908, -179.6297, -1.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5953.151875, 4757.77490234, 165.59179688), 'rotation':(-1.124908, -179.6297, -1.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5964.2421875, 4757.84277344, 165.81017577999998), 'rotation':(-1.128296, -179.626038, -1.173431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.33296875, 4757.91064453, 166.02904297), 'rotation':(-1.130188, -179.625977, -1.175446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.879375, 4757.94433594, 166.13857422), 'rotation':(-1.131012, -179.627975, -1.176361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.515625, 4758.04638672, 166.46716797000002), 'rotation':(-1.131042, -179.627991, -1.176392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56789062, 4766.39501953, 166.46919922), 'rotation':(1.131066, 0.368807, 1.087042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.47507812, 4766.32714844, 166.25011718999997), 'rotation':(1.131059, 0.37199, 1.087032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5980.92875, 4766.29345703, 166.14056641), 'rotation':(1.131018, 0.375692, 1.086994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.381875, 4766.25927734, 166.03101562), 'rotation':(1.130943, 0.371986, 1.086926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5953.19578125, 4766.12353516, 165.59365234), 'rotation':(1.12681, 0.373913, 1.083115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5936.555625, 4766.02148438, 165.26677734), 'rotation':(1.124153, 0.372162, 1.080657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5931.00929688, 4765.98730469, 165.15789062), 'rotation':(1.123996, 0.372153, 1.08051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5925.46242188, 4765.95361328, 165.04900390999998), 'rotation':(1.123996, 0.372153, 1.08051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.91554688, 4765.91943359, 164.94015625), 'rotation':(1.124256, 0.372193, 1.08076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5914.36867188, 4765.88574219, 164.83144531000002), 'rotation':(1.122084, 0.37346, 1.078753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.82179688, 4765.8515625, 164.72310547), 'rotation':(1.118464, 0.373349, 1.075407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.72804688, 4765.78369141, 164.50736328), 'rotation':(1.110923, 0.373052, 1.068447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5886.63375, 4765.71582031, 164.29244140999998), 'rotation':(1.108874, 0.371196, 1.066553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5875.54054688, 4765.64794922, 164.07759765999998), 'rotation':(1.10897, 0.371199, 1.066652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5864.44773438, 4765.58007812, 163.86277343999998), 'rotation':(1.109052, 0.374556, 1.066705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.89992188, 4765.54638672, 163.75566406), 'rotation':(1.109052, 0.374556, 1.066705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5853.3525, 4765.51220703, 163.64898438), 'rotation':(1.102188, 0.372124, 1.060372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.80617188, 4765.47851562, 163.54289062), 'rotation':(1.095474, 0.371383, 1.054169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5814.52390625, 4765.27441406, 162.90876953), 'rotation':(1.082066, 0.370806, 1.041754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5808.97609375, 4765.24072266, 162.80444336), 'rotation':(1.082066, 0.370806, 1.041754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5797.88234375, 4765.17236328, 162.5972168), 'rotation':(1.073316, 0.370487, 1.033648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5733.10546875, 5518.66894531, 160.218125), 'rotation':(1.08546, 0.270561, 1.044903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5743.390625, 5518.79539062, 160.41319336), 'rotation':(1.083159, 0.273882, 1.042767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5691.08109375, 5518.43992188, 159.41905273), 'rotation':(1.089265, 0.270588, 1.048408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5685.538125, 5518.41554688, 159.31363281), 'rotation':(1.089265, 0.270588, 1.048408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5679.995625, 5518.39160156, 159.20819336), 'rotation':(1.089354, 0.270272, 1.048494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.91015625, 5518.34328125, 158.99733398), 'rotation':(1.089354, 0.273642, 1.0485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5663.36765625, 5518.31882812, 158.89189453), 'rotation':(1.089313, 0.270284, 1.048458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5657.8246875, 5518.29445312, 158.78645508), 'rotation':(1.089354, 0.270272, 1.048494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5646.73925781, 5518.24609375, 158.57614258), 'rotation':(1.086936, 0.275592, 1.046264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5641.19773438, 5518.23390625, 158.47149414), 'rotation':(1.082155, 0.271165, 1.041839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.65527344, 5518.26125, 158.36700195), 'rotation':(1.079662, 0.269864, 1.039522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5624.566875, 5518.27882812, 158.15793945), 'rotation':(1.07973, 0.269886, 1.039589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5624.56492188, 5509.63867188, 158.15719726999998), 'rotation':(-1.079773, -179.730118, -1.121094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5630.10984375, 5509.67625, 158.26173828), 'rotation':(-1.079742, -179.730103, -1.121033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.65234375, 5509.75242188, 158.36624023000002), 'rotation':(-1.079773, -179.730118, -1.121094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5641.19433594, 5509.828125, 158.47073242), 'rotation':(-1.079651, -179.726105, -1.120941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5646.73679688, 5509.86523438, 158.57541016), 'rotation':(-1.082184, -179.728821, -1.123657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5652.27929688, 5509.88914062, 158.68040039), 'rotation':(-1.082184, -179.728821, -1.123657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.90820312, 5509.96242188, 158.99658203), 'rotation':(-1.089325, -179.726334, -1.131348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5674.45117188, 5509.98632812, 159.10202148), 'rotation':(-1.089325, -179.726334, -1.131348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5685.53710938, 5510.03515625, 159.31290038999998), 'rotation':(-1.089355, -179.729721, -1.131409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5713.25148438, 5510.15625, 159.84), 'rotation':(-1.088867, -179.727737, -1.13089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5718.79390625, 5510.18066406, 159.94537109), 'rotation':(-1.089081, -179.727722, -1.131073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5724.336875, 5510.20507812, 160.05080078), 'rotation':(-1.08905, -179.733322, -1.131073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5732.27101562, 5510.20214844, 160.20157226999999), 'rotation':(-1.08786, -179.725937, -1.129791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5743.35640625, 5510.16257812, 160.41181641), 'rotation':(-1.08548, -179.729431, -1.127197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5986.34375, 5519.73242188, 164.83732422), 'rotation':(0.99354, 0.26696, 0.95952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5963.91257812, 5519.63429688, 164.44630859), 'rotation':(0.999496, 0.268399, 0.965065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5952.69773438, 5519.58546875, 164.2496875), 'rotation':(1.00457, 0.267944, 0.969793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5941.48195312, 5519.53613281, 164.05179688), 'rotation':(1.011155, 0.268178, 0.975922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.65921875, 5519.46242188, 163.75259766), 'rotation':(1.020874, 0.2685, 0.984966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.05171875, 5519.43796875, 163.65228516), 'rotation':(1.024337, 0.268648, 0.988176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5907.8359375, 5519.38867188, 163.45136719), 'rotation':(1.025949, 0.266559, 0.989679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5902.22851562, 5519.36425781, 163.35091796999998), 'rotation':(1.025853, 0.271498, 0.989594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.01367188, 5519.31542969, 163.14921875), 'rotation':(1.032417, 0.268669, 0.995685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5885.40671875, 5519.29101562, 163.0475), 'rotation':(1.039288, 0.270522, 1.002078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5879.79882812, 5519.26609375, 162.94574219), 'rotation':(1.039118, 0.270516, 1.001926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5851.76171875, 5519.14355469, 162.43563477), 'rotation':(1.046563, 0.271867, 1.008837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5840.5459375, 5519.09421875, 162.22986328000002), 'rotation':(1.052587, 0.27209, 1.014423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5834.93796875, 5519.06984375, 162.12658203), 'rotation':(1.055606, 0.267607, 1.017215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.90429688, 5518.98144531, 161.60699219), 'rotation':(1.064895, 0.270082, 1.025833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5801.296875, 5519.00683594, 161.50259766), 'rotation':(1.064895, 0.270082, 1.025833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.96046875, 5511.37648438, 164.93412109000002), 'rotation':(-0.993561, -179.733047, -1.028473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.74609375, 5511.32714844, 164.73935547000002), 'rotation':(-0.997559, -179.732895, -1.032776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.53171875, 5511.2778125, 164.54378906000002), 'rotation':(-1.001221, -179.732162, -1.036682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5963.9253125, 5511.2534375, 164.44589843999998), 'rotation':(-1.001221, -179.732162, -1.036682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5952.71140625, 5511.20460938, 164.24927734000002), 'rotation':(-1.00769, -179.731964, -1.04364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5947.10453125, 5511.1796875, 164.15050781000002), 'rotation':(-1.011169, -179.726913, -1.047333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5935.890625, 5511.13085938, 163.95203125), 'rotation':(-1.017609, -179.731598, -1.05426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.06984375, 5511.05761719, 163.65194336000002), 'rotation':(-1.025848, -179.733475, -1.06311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5913.46289062, 5511.03273438, 163.55151367), 'rotation':(-1.02594, -179.72847, -1.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5902.2490625, 5510.98339844, 163.35063477), 'rotation':(-1.02594, -179.72847, -1.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5885.42921875, 5510.9096875, 163.04725586), 'rotation':(-1.039124, -179.729477, -1.077362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5879.82179688, 5510.88523438, 162.94549805), 'rotation':(-1.039307, -179.729462, -1.077545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5868.60890625, 5510.83640625, 162.74200195), 'rotation':(-1.04068, -179.732941, -1.07901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5840.57421875, 5510.71335938, 162.22970703000001), 'rotation':(-1.055603, -179.727783, -1.095062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5823.75390625, 5510.63964844, 161.91911133), 'rotation':(-1.062927, -179.726349, -1.102936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5801.33054688, 5510.4575, 161.5025293), 'rotation':(-1.068604, -179.729767, -1.10907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5795.7221875, 5510.38769531, 161.39786132999998), 'rotation':(-1.072144, -179.72966, -1.112854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.11523438, 5510.36328125, 161.29288086), 'rotation':(-1.07605, -179.725647, -1.117096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56101562, 5727.20015625, 164.925), 'rotation':(1.080222, 0.562874, 1.040054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.64109375, 5727.04148438, 164.60263672000002), 'rotation':(1.095091, 0.560405, 1.05381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5918.6025, 5726.46, 163.39764648), 'rotation':(1.130273, 0.559502, 1.086324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5884.76414062, 5726.14359375, 162.72496094), 'rotation':(1.148018, 0.558943, 1.102681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5879.12453125, 5726.0903125, 162.61189453), 'rotation':(1.148018, 0.558943, 1.102681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5873.48484375, 5726.03757812, 162.49882811999998), 'rotation':(1.148025, 0.563131, 1.102678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5867.8446875, 5725.98484375, 162.385625), 'rotation':(1.148025, 0.563131, 1.102678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5867.88375, 5717.60304688, 162.38482421999998), 'rotation':(-1.150604, -179.439011, -1.19754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5879.15921875, 5717.70851562, 162.61102539), 'rotation':(-1.148041, -179.44104, -1.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5890.43453125, 5717.81445312, 162.83708008), 'rotation':(-1.148041, -179.44104, -1.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5896.07179688, 5717.8671875, 162.95008789), 'rotation':(-1.14801, -179.436859, -1.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5907.34523438, 5717.97359375, 163.17390625), 'rotation':(-1.13028, -179.440491, -1.175568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5918.620625, 5718.0790625, 163.39645508), 'rotation':(-1.13028, -179.440491, -1.175568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5929.89546875, 5718.18507812, 163.61878906), 'rotation':(-1.128143, -179.441925, -1.173248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.17039062, 5718.29054688, 163.83975586), 'rotation':(-1.119202, -179.437744, -1.163605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5946.808125, 5718.34328125, 163.94962891), 'rotation':(-1.11496, -179.442444, -1.158997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5952.44578125, 5718.39601562, 164.05912109000002), 'rotation':(-1.110321, -179.442673, -1.154022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5963.72070312, 5718.50195312, 164.27691406000002), 'rotation':(-1.106018, -179.442795, -1.149353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.35789062, 5718.5503125, 164.38521484), 'rotation':(-1.101532, -179.438477, -1.144531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5974.99609375, 5718.60351562, 164.49320312), 'rotation':(-1.097229, -179.44313, -1.139893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5997.54640625, 5718.85203125, 164.92324219), 'rotation':(-1.08609, -179.445206, -1.127869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5627.18898438, 5715.28515625, 157.44571288999998), 'rotation':(-1.155579, -179.439743, -1.202911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5636.65382812, 5715.43601562, 157.6369043), 'rotation':(-1.157074, -179.440033, -1.204529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5648.00828125, 5715.5425, 157.86729492), 'rotation':(-1.163757, -179.439758, -1.211792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5659.36328125, 5715.64890625, 158.09884766), 'rotation':(-1.170197, -179.439499, -1.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5665.04101562, 5715.7021875, 158.21508789), 'rotation':(-1.173431, -179.439407, -1.22229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5676.39601562, 5715.80859375, 158.4484082), 'rotation':(-1.17688, -179.439224, -1.226013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5682.07375, 5715.86179688, 158.56545898000002), 'rotation':(-1.180084, -179.439087, -1.229492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5699.1059375, 5716.02101562, 158.91694336), 'rotation':(-1.181732, -179.440552, -1.231262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5716.13820312, 5716.180625, 159.26922851999998), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5727.49367188, 5716.2778125, 159.50428711), 'rotation':(-1.185394, -179.440292, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5733.16945312, 5716.36328125, 159.62179688), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5738.8471875, 5716.42726562, 159.7393457), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5744.524375, 5716.48046875, 159.856875), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5755.879375, 5716.58640625, 160.09170898), 'rotation':(-1.184418, -179.439026, -1.234192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5761.55664062, 5716.6396875, 160.20893555), 'rotation':(-1.182739, -179.439102, -1.232361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.234375, 5716.69289062, 160.32609375), 'rotation':(-1.181671, -179.438232, -1.231201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.910625, 5716.74609375, 160.44327148), 'rotation':(-1.181793, -179.438232, -1.231323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.26609375, 5716.85304688, 160.67762695), 'rotation':(-1.181732, -179.438202, -1.231293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5789.94289062, 5716.90625, 160.79478516), 'rotation':(-1.181793, -179.438232, -1.231323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5806.97609375, 5717.06546875, 161.14532227), 'rotation':(-1.174225, -179.439758, -1.223145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5812.65382812, 5717.11867188, 161.26168945), 'rotation':(-1.174225, -179.439758, -1.223145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5818.33007812, 5717.171875, 161.3778418), 'rotation':(-1.171783, -179.436676, -1.22049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5630.89746094, 5723.76367188, 157.5221582), 'rotation':(1.157068, 0.559965, 1.111011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5636.57570312, 5723.816875, 157.63691406), 'rotation':(1.160333, 0.560055, 1.114011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5642.25292969, 5723.87015625, 157.75197265999998), 'rotation':(1.163755, 0.564706, 1.117179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5647.9296875, 5723.92335938, 157.86729492), 'rotation':(1.166958, 0.560368, 1.120129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5676.316875, 5724.18945312, 158.4484082), 'rotation':(1.180086, 0.560905, 1.132192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5687.6709375, 5724.2959375, 158.68259766), 'rotation':(1.181623, 0.559397, 1.133615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5699.02585938, 5724.401875, 158.91693359), 'rotation':(1.181739, 0.564698, 1.133709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5733.089375, 5724.6884375, 159.62176757999998), 'rotation':(1.185393, 0.559704, 1.137075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5744.444375, 5724.79492188, 159.8568457), 'rotation':(1.184416, 0.565085, 1.136178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5750.12109375, 5724.848125, 159.97430664), 'rotation':(1.18275, 0.56089, 1.134639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5755.79835938, 5724.90140625, 160.09166016), 'rotation':(1.18275, 0.56089, 1.134639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.1528125, 5725.0078125, 160.32605469), 'rotation':(1.181773, 0.561769, 1.133747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5772.83007812, 5725.06101562, 160.44320312), 'rotation':(1.181664, 0.561765, 1.133651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.18359375, 5725.1675, 160.67754883), 'rotation':(1.181841, 0.558484, 1.133814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5795.5390625, 5725.27390625, 160.91181641), 'rotation':(1.179273, 0.563742, 1.131438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.89359375, 5725.38039062, 161.14524414), 'rotation':(1.171671, 0.563249, 1.124458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.35546875, 5736.80765625, 162.04470703), 'rotation':(-0.054932, 90.530998, -0.055054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.20117188, 5753.5225, 162.02921875), 'rotation':(-0.0495, 90.530952, -0.049591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.14992188, 5759.09375, 162.02450195), 'rotation':(-0.046844, 90.52652, -0.046936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.99609375, 5775.80859375, 162.01174805), 'rotation':(-0.038605, 90.526512, -0.038666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5846.94484375, 5781.37984375, 162.00797852), 'rotation':(-0.03598, 90.526451, -0.036011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.89304688, 5786.95164062, 162.00445312), 'rotation':(-0.034668, 90.530479, -0.034698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.84179688, 5792.5234375, 162.00106445), 'rotation':(-0.034668, 90.530479, -0.034698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.79054688, 5798.0946875, 161.99771484000001), 'rotation':(-0.033722, 90.528191, -0.033752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5846.73921875, 5803.66648438, 161.99444336), 'rotation':(-0.03183, 90.528214, -0.03183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.68796875, 5809.23828125, 161.99128905999999), 'rotation':(-0.03183, 90.528214, -0.03183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.43117188, 5837.09570312, 161.97710938), 'rotation':(-0.026978, 90.531715, -0.027008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.37984375, 5842.66703125, 161.97447266), 'rotation':(-0.026672, 90.527008, -0.026703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.02, 5881.66703125, 161.95681641), 'rotation':(-0.02478, 90.527, -0.02478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.9175, 5892.81007812, 161.95201172), 'rotation':(-0.025513, 90.526863, -0.025543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.81492188, 5903.95265625, 161.94691406), 'rotation':(-0.028473, 90.531609, -0.028503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.76367188, 5909.52390625, 161.94415039), 'rotation':(-0.029968, 90.526863, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.71242188, 5915.09570312, 161.94125), 'rotation':(-0.031433, 90.52681, -0.031464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5845.66109375, 5920.66703125, 161.93820312), 'rotation':(-0.032928, 90.526855, -0.032959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.60984375, 5926.2378125, 161.93503906), 'rotation':(-0.034546, 90.531616, -0.034607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.558125, 5931.80953125, 161.93171875), 'rotation':(-0.036041, 90.526825, -0.036072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5855.73585938, 5736.88476562, 162.04470703), 'rotation':(0.056301, -89.471161, 0.056183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5855.47898438, 5764.743125, 162.02001953), 'rotation':(0.046855, -89.47348, 0.046769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5855.2734375, 5787.02882812, 162.00445312), 'rotation':(0.035975, -89.47348, 0.035928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5855.2221875, 5792.60007812, 162.00106445), 'rotation':(0.035975, -89.47348, 0.035928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5855.06835938, 5809.31546875, 161.99128905999999), 'rotation':(0.033714, -89.471802, 0.033678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.96578125, 5820.45851562, 161.98529297), 'rotation':(0.029889, -89.471802, 0.029862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.70898438, 5848.31546875, 161.97186523), 'rotation':(0.026966, -89.472961, 0.026939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.6571875, 5853.88671875, 161.96929688), 'rotation':(0.026672, -89.472992, 0.026648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.5546875, 5865.02976562, 161.96421875), 'rotation':(0.026091, -89.472992, 0.026066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.5034375, 5870.60109375, 161.96172852), 'rotation':(0.025784, -89.468323, 0.025775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5854.40039062, 5881.74414062, 161.95681641), 'rotation':(0.02506, -89.472992, 0.025047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.2465625, 5898.45851562, 161.94954102), 'rotation':(0.025504, -89.473145, 0.025492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.04148438, 5920.74414062, 161.93821289), 'rotation':(0.031439, -89.473145, 0.031413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5853.9384375, 5931.88671875, 161.93171875), 'rotation':(0.034568, -89.468384, 0.034515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5853.8871875, 5937.45796875, 161.92827148), 'rotation':(0.036036, -89.473114, 0.036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4145.39109375, 2204.22828125, 156.9969043), 'rotation':(-1.622162, 0.467897, -1.716095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4123.40039062, 2204.0659375, 157.62112305), 'rotation':(-1.631561, 0.470357, -1.726593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4106.90773438, 2203.94460938, 158.09942383), 'rotation':(-1.668518, 0.47042, -1.767944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4101.40921875, 2203.9040625, 158.26155273), 'rotation':(-1.68692, 0.47357, -1.788605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4095.91164062, 2203.86351562, 158.42450195), 'rotation':(-1.69632, 0.472024, -1.799164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4090.4153125000003, 2203.8229687499997, 158.58742188), 'rotation':(-1.696136, 0.474024, -1.79895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4079.4206249999997, 2203.74171875, 158.91422852), 'rotation':(-1.70694, 0.472918, -1.811066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4068.42671875, 2203.66039062, 159.24365234), 'rotation':(-1.721222, 0.476377, -1.827118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4062.92945312, 2203.6198437499997, 159.40944336), 'rotation':(-1.728363, 0.474205, -1.835144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4040.94289062, 2203.42484375, 160.07931641), 'rotation':(-1.749756, 0.478114, -1.859253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4018.9565625, 2203.26265625, 160.75671875), 'rotation':(-1.771973, 0.478567, -1.884308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4002.4665625, 2203.14109375, 161.27185547), 'rotation':(-1.796783, 0.478194, -1.912323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4007.9075000000003, 2195.33179688, 161.1028125), 'rotation':(1.796674, -179.521149, 1.686477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4018.9053125, 2195.413125, 160.76009765999999), 'rotation':(1.784305, -179.52066, 1.675592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4051.89867188, 2195.65648438, 159.74603516), 'rotation':(1.749758, -179.524475, 1.645173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4057.3971874999997, 2195.69703125, 159.5787793), 'rotation':(1.74262, -179.524933, 1.638875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4068.39601562, 2195.77828125, 159.24633789), 'rotation':(1.728345, -179.523193, 1.626278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4073.89523438, 2195.81882812, 159.08119141), 'rotation':(1.721214, -179.52623, 1.619975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4079.39429688, 2195.859375, 158.91676758), 'rotation':(1.714077, -179.526642, 1.613666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4090.39304688, 2195.94046875, 158.58981445), 'rotation':(1.699795, -179.524902, 1.601041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4101.39109375, 2196.02171875, 158.26382812), 'rotation':(1.696318, -179.52594, 1.597968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4106.89304688, 2196.06226562, 158.1015625), 'rotation':(1.686927, -179.528488, 1.589647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4123.3915625, 2196.1840625, 157.62302734000002), 'rotation':(1.650215, -179.528534, 1.557081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4128.8940625, 2196.22460938, 157.46617188), 'rotation':(1.631541, -179.531723, 1.540492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4139.89304688, 2196.305625, 157.154375), 'rotation':(1.622334, -179.532089, 1.532287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4145.39210938, 2196.34617188, 156.99850586), 'rotation':(1.622464, -179.532043, 1.532414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.47414062, 2182.39601562, 156.92179688), 'rotation':(-1.226837, 89.829018, -1.280243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.45460938, 2176.77273438, 157.04310547), 'rotation':(-1.234222, 89.827484, -1.2883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.41554688, 2165.52710938, 157.2877832), 'rotation':(-1.247101, 89.828789, -1.302338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.37648438, 2154.28078125, 157.53619141), 'rotation':(-1.27301, 89.829933, -1.330566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.35695312, 2148.65820312, 157.66177734000001), 'rotation':(-1.281494, 89.830292, -1.339813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.23976562, 2114.9231250000003, 158.43329101999998), 'rotation':(-1.326538, 89.835213, -1.389069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.12304688, 2081.18898438, 159.235), 'rotation':(-1.377899, 89.832024, -1.445435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4157.08398438, 2069.94484375, 159.50672852), 'rotation':(-1.383698, 89.833809, -1.451813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.0390625, 2047.4572656199998, 160.06178711), 'rotation':(-1.424713, 89.837029, -1.496948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.00046875, 2036.21398438, 160.34173828000002), 'rotation':(-1.424683, 89.837044, -1.496948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4156.9028125, 2008.1052343800002, 161.05197266), 'rotation':(-1.45636, 89.838455, -1.531921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4164.77046875, 2013.5771875, 160.91154297), 'rotation':(1.468853, -90.160889, 1.394914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4164.82859375, 2030.35976562, 160.48739258), 'rotation':(1.443581, -90.16217, 1.37215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4164.86765625, 2041.54921875, 160.20814453), 'rotation':(1.431034, -90.162811, 1.360828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4164.88671875, 2047.14320312, 160.06892578), 'rotation':(1.424689, -90.162933, 1.355088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4164.94484375, 2063.9275, 159.6530957), 'rotation':(1.407149, -90.165039, 1.339246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4164.964375, 2069.52195312, 159.51635742), 'rotation':(1.395394, -90.165619, 1.328601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.00632812, 2080.71046875, 159.24586914), 'rotation':(1.377916, -90.167969, 1.312752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.0225, 2086.30664062, 159.11117188), 'rotation':(1.377888, -90.162659, 1.312758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.04203125, 2091.9028125, 158.97680664), 'rotation':(1.373244, -90.167358, 1.308566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.0590625, 2097.49828125, 158.84318359), 'rotation':(1.363996, -90.167786, 1.300163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.08054688, 2103.09179688, 158.71047852), 'rotation':(1.354481, -90.163483, 1.291518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.09960938, 2108.6865625, 158.57861328), 'rotation':(1.345117, -90.168671, 1.283008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.11671875, 2114.285625, 158.44750977), 'rotation':(1.345117, -90.168671, 1.283008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.17773438, 2131.0690624999997, 158.05978516), 'rotation':(1.316997, -90.169983, 1.25745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.19679688, 2136.66554688, 157.93210938), 'rotation':(1.30333, -90.175873, 1.244993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.21632812, 2142.26171875, 157.80511719), 'rotation':(1.298658, -90.168915, 1.24074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.23585938, 2147.85695312, 157.67911132999998), 'rotation':(1.290175, -90.169281, 1.233005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.25539062, 2153.45164062, 157.55401367000002), 'rotation':(1.281473, -90.169678, 1.225076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.29390625, 2164.64523438, 157.30652344), 'rotation':(1.264302, -90.170441, 1.209378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4181.6371875, 2408.57910156, 152.34600586), 'rotation':(-1.148987, 72.104126, -1.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4179.99851562, 2403.348125, 152.45646484), 'rotation':(-1.149017, 72.823311, -1.195831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4176.85789062, 2392.71949219, 152.67963867), 'rotation':(-1.148987, 73.907257, -1.195801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4172.56789062, 2376.57347656, 153.01779297), 'rotation':(-1.157166, 76.055382, -1.204651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4167.66554688, 2354.62328125, 153.47423828), 'rotation':(-1.156372, 78.574532, -1.203796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4162.85695312, 2326.68796875, 154.04490234000002), 'rotation':(-1.141846, 81.56237, -1.188049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4162.0815625, 2321.0590625, 154.15852539), 'rotation':(-1.141022, 82.309853, -1.187195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4160.72804688, 2309.8098437500003, 154.38481445), 'rotation':(-1.136169, 83.579033, -1.181946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4160.14796875, 2304.19460938, 154.49655273), 'rotation':(-1.126617, 84.388161, -1.1716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4159.6259375, 2298.51953125, 154.60867188), 'rotation':(-1.120392, 84.922913, -1.164886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4158.78273438, 2287.2721874999997, 154.82831055), 'rotation':(-1.104431, 86.252892, -1.147644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.77734375, 2259.16257812, 155.36709961), 'rotation':(-1.09024, 89.446373, -1.132355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.65773438, 2225.9653125, 156.02069336), 'rotation':(-1.137726, 89.823753, -1.183594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.55953125, 2220.49804688, 156.12958984), 'rotation':(-1.137726, 89.823753, -1.183594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.50195312, 2225.03101562, 156.03869140999998), 'rotation':(1.145231, -90.175659, 1.100111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.70554688, 2241.97679688, 155.70222655999999), 'rotation':(1.137684, -90.173126, 1.09315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.84570312, 2264.66601562, 155.25894531), 'rotation':(1.116531, -90.811279, 1.073625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4166.19773438, 2276.15476562, 155.03580078000002), 'rotation':(1.116183, -92.147186, 1.073305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4167.71046875, 2299.21117188, 154.58114258), 'rotation':(1.143599, -94.808258, 1.098608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4168.87351562, 2310.74289062, 154.348125), 'rotation':(1.159841, -96.147339, 1.113565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4170.30765625, 2322.25171875, 154.11257812), 'rotation':(1.168126, -97.696136, 1.121187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4171.12546875, 2327.99046875, 153.9947168), 'rotation':(1.168092, -98.041504, 1.12117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4173.9765625, 2345.14453125, 153.63962891), 'rotation':(1.177504, -100.139465, 1.129825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4176.20015625, 2356.4607031200003, 153.40232422), 'rotation':(1.183911, -101.429871, 1.135714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4178.67921875, 2367.70507812, 153.16496094000001), 'rotation':(1.185031, -102.881348, 1.136743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4182.85640625, 2384.32714844, 152.81171875), 'rotation':(1.181507, -105.011902, 1.133502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4184.36523438, 2389.79957031, 152.69537109), 'rotation':(1.179649, -105.369614, 1.131794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5991.92921875, 2779.68310547, 154.32901367), 'rotation':(0.514539, -0.157379, 0.505367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.4809375, 2779.74658203, 154.13544922), 'rotation':(0.484083, -0.157654, 0.47596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5958.256875, 2779.77808594, 154.04475586), 'rotation':(0.457295, -0.158112, 0.450044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.64257812, 2779.79394531, 154.00162109000001), 'rotation':(0.443669, -0.158295, 0.436835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5947.03125, 2779.80980469, 153.95998047), 'rotation':(0.430254, -0.158508, 0.423824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.41890625, 2779.82568359, 153.91978516), 'rotation':(0.40307, -0.158905, 0.397426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5935.80765625, 2779.8415625, 153.88105469), 'rotation':(0.389649, -0.159088, 0.384374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5913.3584375, 2779.90478516, 153.73505859), 'rotation':(0.352499, -0.160706, 0.348179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5902.1328125, 2779.93628906, 153.66870117), 'rotation':(0.328238, -0.16098, 0.324487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5890.90867188, 2779.96777344, 153.60711914), 'rotation':(0.303773, -0.161255, 0.300573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5862.848125, 2780.04710938, 153.47032227), 'rotation':(0.260094, -0.160767, 0.257744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5857.2334375, 2780.06273438, 153.44582031), 'rotation':(0.249828, -0.160858, 0.247665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5840.39890625, 2780.11035156, 153.37864258), 'rotation':(0.218983, -0.161133, 0.217317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5834.78609375, 2780.12621094, 153.35824219), 'rotation':(0.208847, -0.161194, 0.207329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5812.33890625, 2780.1896875, 153.28225586), 'rotation':(0.184763, -0.16095, 0.183584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.72507812, 2780.20556641, 153.26515625), 'rotation':(0.176868, -0.161011, 0.175784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5801.11328125, 2780.22144531, 153.24886719), 'rotation':(0.169457, -0.161041, 0.16846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5784.276875, 2780.26878906, 153.20457031), 'rotation':(0.142765, -0.161133, 0.142052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5778.66453125, 2780.28466797, 153.19072266), 'rotation':(0.142765, -0.161133, 0.142052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5773.05226562, 2780.30054688, 153.17724609), 'rotation':(0.134719, -0.160034, 0.134073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5750.60546875, 2780.36376953, 153.12885742), 'rotation':(0.113688, -0.160126, 0.113239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5739.381875, 2780.39550781, 153.10792969), 'rotation':(0.10317, -0.162811, 0.102806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5733.774375, 2780.4978125, 153.09805663999998), 'rotation':(0.100493, -0.160248, 0.100146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5997.53367188, 2771.28662109, 154.38025391), 'rotation':(-0.53009, 179.842239, -0.539978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.921875, 2771.3025, 154.32915039), 'rotation':(-0.498749, 179.842361, -0.507507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.31007812, 2771.31835938, 154.27964844), 'rotation':(-0.490967, 179.843002, -0.49942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.69625, 2771.33447266, 154.2312207), 'rotation':(-0.490967, 179.843002, -0.49942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5975.085, 2771.35035156, 154.18313477), 'rotation':(-0.48407, 179.842361, -0.49231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.6328125, 2771.41357422, 154.00172852), 'rotation':(-0.430237, 179.841492, -0.436737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5947.02101562, 2771.42945312, 153.96007812), 'rotation':(-0.416718, 179.841278, -0.422791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5935.79640625, 2771.46117188, 153.88115234), 'rotation':(-0.383026, 179.841766, -0.388153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5918.95851562, 2771.50855469, 153.77009766), 'rotation':(-0.352509, 179.839294, -0.356873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5907.73390625, 2771.54003906, 153.70135742), 'rotation':(-0.328247, 179.841507, -0.332001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5896.50734375, 2771.57177734, 153.63737305), 'rotation':(-0.303772, 179.841248, -0.307007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5885.28320312, 2771.60351562, 153.57818359), 'rotation':(-0.285767, 179.84108, -0.288635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5874.05710938, 2771.635, 153.52244141), 'rotation':(-0.270233, 179.83931, -0.272797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5857.21726562, 2771.68261719, 153.44584961), 'rotation':(-0.239532, 179.83905, -0.241547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5845.99414062, 2771.71435547, 153.40001953), 'rotation':(-0.218994, 179.838867, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5829.1553125, 2771.76171875, 153.33833008), 'rotation':(-0.199768, 179.839111, -0.201172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5823.54390625, 2771.77757812, 153.31884766), 'rotation':(-0.192169, 179.839096, -0.193451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5817.93164062, 2771.79345703, 153.30015625), 'rotation':(-0.184784, 179.839035, -0.185944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.70554688, 2771.82519531, 153.26516602), 'rotation':(-0.169464, 179.838943, -0.170441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5801.09328125, 2771.84105469, 153.24888672), 'rotation':(-0.161896, 179.838882, -0.162811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5789.86867188, 2771.8728125, 153.2187207), 'rotation':(-0.142761, 179.838852, -0.143494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5778.64304688, 2771.90453125, 153.19072266), 'rotation':(-0.140137, 179.839981, -0.140839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5767.4184375, 2771.93628906, 153.16433594), 'rotation':(-0.124207, 179.83728, -0.124756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5744.9696875, 2771.99925781, 153.11811523), 'rotation':(-0.10318, 179.837189, -0.103546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5733.74953125, 2771.94433594, 153.09805663999998), 'rotation':(-0.100372, 179.839752, -0.100708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5993.94484375, 2875.85400391, 155.05930664), 'rotation':(-0.271576, -73.230774, -0.27417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5989.04882812, 2892.10180664, 155.14040039), 'rotation':(-0.27655, -73.232117, -0.279236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5987.41703125, 2897.51757812, 155.16796875), 'rotation':(-0.279907, -73.227814, -0.282654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5984.1528125, 2908.34912109, 155.22390625), 'rotation':(-0.283142, -73.231415, -0.28595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.88914062, 2919.18066406, 155.28013672), 'rotation':(-0.284851, -73.229858, -0.287689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5977.62546875, 2930.01220703, 155.33645508), 'rotation':(-0.285248, -73.227142, -0.288116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.36132812, 2940.84375, 155.39292969), 'rotation':(-0.286102, -73.230042, -0.288971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.46578125, 2957.09106445, 155.47802734), 'rotation':(-0.287842, -73.230042, -0.290741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5966.20164062, 2967.92260742, 155.53493164), 'rotation':(-0.2883, -73.22998, -0.291199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5962.93796875, 2978.75390625, 155.5918457), 'rotation':(-0.2883, -73.22998, -0.291199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5959.67429688, 2989.58544922, 155.64866211), 'rotation':(-0.287903, -73.230713, -0.290802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5954.77882812, 3005.83251953, 155.7337207), 'rotation':(-0.286957, -73.228027, -0.289825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.14695312, 3011.24853516, 155.76205078), 'rotation':(-0.287048, -73.231354, -0.289948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5949.88328125, 3022.07958984, 155.81849609), 'rotation':(-0.284637, -73.227966, -0.287476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5946.61914062, 3032.91113281, 155.874375), 'rotation':(-0.281433, -73.228027, -0.28421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5944.98734375, 3038.3269043, 155.90207031), 'rotation':(-0.279755, -73.232727, -0.282501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.72359375, 3049.15844727, 155.95700195), 'rotation':(-0.276703, -73.228058, -0.279388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5938.45945312, 3059.98974609, 156.01134765999998), 'rotation':(-0.275024, -73.232788, -0.277679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5930.43898438, 3057.56079102, 156.01130859), 'rotation':(0.274314, 106.769073, 0.271688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5933.66554688, 3046.85400391, 155.95757812), 'rotation':(0.275024, 106.771904, 0.272391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5938.50484375, 3030.79370117, 155.87591797), 'rotation':(0.279737, 106.771957, 0.277026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.118125, 3025.43969727, 155.84838867), 'rotation':(0.281445, 106.767296, 0.278683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.7309375, 3020.08642578, 155.82071288999998), 'rotation':(0.283098, 106.77198, 0.280312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5943.34421875, 3014.73266602, 155.79288086), 'rotation':(0.284648, 106.772697, 0.281829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5944.9575, 3009.37963867, 155.76492188), 'rotation':(0.286158, 106.767334, 0.283318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5949.796875, 2993.31933594, 155.68088867), 'rotation':(0.286957, 106.769058, 0.284095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.0234375, 2982.61230469, 155.62478516), 'rotation':(0.287353, 106.772545, 0.284485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5956.24953125, 2971.9050293, 155.56855469), 'rotation':(0.288275, 106.770012, 0.285388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5957.8628125, 2966.55175781, 155.54043945), 'rotation':(0.288118, 106.769318, 0.285232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5962.70265625, 2950.4909668, 155.45608398000002), 'rotation':(0.287831, 106.769958, 0.284947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5964.31546875, 2945.13745117, 155.42802734), 'rotation':(0.287831, 106.769958, 0.284947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5967.54203125, 2934.43017578, 155.37208984), 'rotation':(0.28697, 106.769958, 0.284107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.15476562, 2929.07666016, 155.34416016), 'rotation':(0.286117, 106.769928, 0.283267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5970.76804688, 2923.72314453, 155.31631836), 'rotation':(0.285256, 106.769936, 0.282426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5977.22070312, 2902.30859375, 155.20509765999998), 'rotation':(0.28486, 106.770149, 0.282043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5983.67335938, 2880.89428711, 155.09630859), 'rotation':(0.273208, 106.768494, 0.270615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.89992188, 2870.18676758, 155.04323242), 'rotation':(0.271582, 106.772972, 0.269017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.73976562, 2854.1262207, 154.96373047), 'rotation':(0.271582, 106.772972, 0.269017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5994.96578125, 2843.41894531, 154.91113281), 'rotation':(0.26872, 106.769127, 0.266209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5996.5790625, 2838.06518555, 154.88537109), 'rotation':(0.263154, 106.769539, 0.26075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4749.39111328, 3561.55125, 155.78344727), 'rotation':(-1.049927, 179.817749, -1.088959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4736.54736328, 3561.68898438, 155.54695312), 'rotation':(-1.065155, 179.818314, -1.105316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4725.49804688, 3561.76441406, 155.34063477), 'rotation':(-1.075531, 179.818848, -1.116516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4719.97363281, 3561.78394531, 155.23689453), 'rotation':(-1.080841, 179.821609, -1.122223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4708.92285156, 3561.8225, 155.02788086), 'rotation':(-1.091492, 179.819458, -1.133698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.87207031, 3561.86132812, 154.81677734000002), 'rotation':(-1.102173, 179.81987, -1.145203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.82080078, 3561.90015625, 154.60360352), 'rotation':(-1.112823, 179.820297, -1.156708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4681.29492188, 3561.91917969, 154.49623047), 'rotation':(-1.11554, 179.820374, -1.159637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4675.77099609, 3561.93898438, 154.38864258), 'rotation':(-1.11554, 179.820374, -1.159637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4659.19484375, 3561.99707031, 154.06569336), 'rotation':(-1.116486, 179.820999, -1.160675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4653.66894531, 3562.01660156, 153.95789062), 'rotation':(-1.118622, 179.821091, -1.162964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4648.14355469, 3562.03589844, 153.84996094), 'rotation':(-1.119781, 179.819107, -1.164215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4637.09226562, 3562.0746875, 153.63389648), 'rotation':(-1.119507, 179.821655, -1.16394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4631.566875, 3562.09421875, 153.52584961), 'rotation':(-1.119781, 179.819107, -1.164215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4637.08789062, 3570.45605469, 153.63322266), 'rotation':(1.119789, -0.180878, 1.076633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4642.61328125, 3570.43675781, 153.74125977), 'rotation':(1.119789, -0.178345, 1.076624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4653.66503906, 3570.39796875, 153.95722656), 'rotation':(1.116497, -0.180786, 1.073588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4681.29248047, 3570.30101562, 154.49560547), 'rotation':(1.112904, -0.179718, 1.070284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.81787109, 3570.2814843799997, 154.60297852), 'rotation':(1.107399, -0.179932, 1.065199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4692.34326172, 3570.2621875, 154.70980469), 'rotation':(1.10216, -0.180115, 1.060347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.86914062, 3570.24265625, 154.81616211), 'rotation':(1.096744, -0.180328, 1.055345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4951.10351562, 3560.23070312, 158.72325195), 'rotation':(-0.581024, 179.42923, -0.592896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4945.60888672, 3560.37453125, 158.6675293), 'rotation':(-0.612335, 179.429916, -0.625549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4934.57128906, 3560.526875, 158.55072266), 'rotation':(-0.643829, 179.428848, -0.658447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4929.04931641, 3560.5825, 158.48866211), 'rotation':(-0.659668, 179.430725, -0.674988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4923.52880859, 3560.63820312, 158.42567383), 'rotation':(-0.659668, 179.430725, -0.674988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4912.48730469, 3560.70117188, 158.29763671999999), 'rotation':(-0.68576, 179.431717, -0.702332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4901.44335938, 3560.7892968799997, 158.16386719), 'rotation':(-0.720428, 179.430176, -0.738708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4890.40380859, 3560.90746094, 158.02378906), 'rotation':(-0.755249, 179.433472, -0.77536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4879.36132812, 3560.93824219, 157.87739258), 'rotation':(-0.790192, 179.432007, -0.812225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4873.84228516, 3561.07691406, 157.8018457), 'rotation':(-0.798706, 179.434708, -0.821198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4862.79443359, 3561.10523438, 157.64712891), 'rotation':(-0.836578, 179.623611, -0.861267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4851.74804688, 3561.2421875, 157.48710938), 'rotation':(-0.861908, 179.811844, -0.888123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4840.70849609, 3561.3459375, 157.32174805), 'rotation':(-0.882507, 179.812469, -0.910034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4835.18701172, 3561.36328125, 157.23667969), 'rotation':(-0.903015, 179.81311, -0.931824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4829.66699219, 3561.3986718799997, 157.15003906), 'rotation':(-0.913391, 179.812668, -0.942871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4824.14697266, 3561.41820312, 157.06254883), 'rotation':(-0.913391, 179.812668, -0.942871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4818.62548828, 3561.4377343799997, 156.97450195), 'rotation':(-0.922607, 179.813538, -0.952698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4807.5859375, 3561.38820312, 156.79605469), 'rotation':(-0.940857, 179.814163, -0.972137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4796.54394531, 3561.38523438, 156.61259766), 'rotation':(-0.977783, 179.817291, -1.011597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4796.56396484, 3570.04054688, 156.61242188), 'rotation':(0.959471, -0.185242, 0.92773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4802.08691406, 3570.02101562, 156.70494141), 'rotation':(0.940913, -0.185852, 0.91038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4807.60693359, 3570.00195312, 156.79589844), 'rotation':(0.922601, -0.186462, 0.893235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4813.12890625, 3569.91527344, 156.88568359), 'rotation':(0.922601, -0.186462, 0.893235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4818.64990234, 3569.85449219, 156.97441406), 'rotation':(0.913387, -0.185822, 0.884601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4835.21533203, 3569.76414062, 157.23666015999999), 'rotation':(0.882501, -0.187531, 0.855628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4846.25927734, 3569.72144531, 157.40510742), 'rotation':(0.841274, -0.188782, 0.816836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4862.8125, 3569.630625, 157.64618164), 'rotation':(0.810388, -0.564911, 0.787701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4868.33447266, 3569.57519531, 157.72417969), 'rotation':(0.798695, -0.565277, 0.776662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4879.37841797, 3569.484375, 157.87646484), 'rotation':(0.772569, -0.568451, 0.751939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4884.89990234, 3569.4450781200003, 157.95048828), 'rotation':(0.755241, -0.566528, 0.735521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4890.42236328, 3569.40429688, 158.02292969), 'rotation':(0.737913, -0.566986, 0.719084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4895.94433594, 3569.33742188, 158.09379883), 'rotation':(0.720496, -0.567474, 0.70254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4918.03369141, 3569.21921875, 158.36135742), 'rotation':(0.65966, -0.569275, 0.644605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4940.12304688, 3568.9965625, 158.609375), 'rotation':(0.581024, -0.57251, 0.569321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4945.64453125, 3568.9409375, 158.66702148000002), 'rotation':(0.581024, -0.57251, 0.569321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4989.00048828, 3559.870625, 159.06695312), 'rotation':(-0.484528, 179.427216, -0.492767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5005.98046875, 3559.80738281, 159.19564453), 'rotation':(-0.429291, 179.4263, -0.43576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5011.640625, 3559.75046875, 159.2350293), 'rotation':(-0.401672, 179.425934, -0.407318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5039.94726562, 3559.4653125, 159.4112207), 'rotation':(-0.322144, 179.424408, -0.325806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5045.60595703, 3559.40820312, 159.44128906), 'rotation':(-0.303497, 179.42424, -0.306732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5062.58984375, 3559.23730469, 159.52107422), 'rotation':(-0.247192, 179.423691, -0.249329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5068.25097656, 3559.18015625, 159.54484375), 'rotation':(-0.247192, 179.423691, -0.249329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5073.91308594, 3559.12304688, 159.56833984000002), 'rotation':(-0.237732, 179.423492, -0.239716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5090.89550781, 3558.95214844, 159.62869141), 'rotation':(-0.21048, 179.423935, -0.212006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5096.55273438, 3558.89527344, 159.64401367), 'rotation':(-0.155792, 179.423584, -0.156647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5102.21777344, 3558.838125, 159.65670898), 'rotation':(-0.128448, 179.421738, -0.129028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5113.54199219, 3558.72414062, 159.68210938), 'rotation':(-0.128448, 179.424118, -0.128998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5119.20410156, 3558.66699219, 159.69480469), 'rotation':(-0.128448, 179.421738, -0.129028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5130.52294922, 3558.55273438, 159.71405273), 'rotation':(-0.096619, 179.424149, -0.096954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5136.18505859, 3558.49585938, 159.71730469), 'rotation':(-0.032928, 179.422577, -0.03299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5141.84472656, 3558.43871094, 159.71939453000002), 'rotation':(-0.032928, 179.422577, -0.03299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5147.50683594, 3558.38160156, 159.71950195), 'rotation':(-0.001068, 179.423248, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5153.16894531, 3558.3246875, 159.71958984), 'rotation':(-0.001068, 179.423248, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5175.81787109, 3558.09644531, 159.72001953), 'rotation':(-0.001068, 179.423233, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5181.47900391, 3558.03953125, 159.71957031), 'rotation':(-0.001068, 179.423233, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5192.80029297, 3557.92554688, 159.71311523), 'rotation':(0.038311, 179.422897, 0.038269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5204.12255859, 3557.81128906, 159.69740234), 'rotation':(0.09093, 179.423019, 0.09065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4992.8671875, 3568.36304688, 159.09710938), 'rotation':(0.429277, -0.5737, 0.42288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5000.37695312, 3568.24488281, 159.15457031), 'rotation':(0.401663, -0.574066, 0.396061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5006.03808594, 3568.1877343799997, 159.19546875), 'rotation':(0.401663, -0.574066, 0.396061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5017.359375, 3568.07398438, 159.27299805), 'rotation':(0.378413, -0.57486, 0.373457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5023.02148438, 3568.01683594, 159.31014648000001), 'rotation':(0.359691, -0.575165, 0.355194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5028.68212891, 3567.95972656, 159.34556641), 'rotation':(0.341045, -0.575348, 0.337003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5045.66552734, 3567.7888281200003, 159.44116211), 'rotation':(0.284593, -0.575958, 0.281774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5062.65039062, 3567.61765625, 159.5209668), 'rotation':(0.237725, -0.574921, 0.235757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5079.63427734, 3567.44652344, 159.59077148), 'rotation':(0.210452, -0.57605, 0.208917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5090.95654297, 3567.3325, 159.62863281), 'rotation':(0.155776, -0.576416, 0.154944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5113.60351562, 3567.10449219, 159.68205078), 'rotation':(0.128449, -0.575928, 0.127875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5124.92626953, 3566.99023438, 159.7049707), 'rotation':(0.096627, -0.577271, 0.096302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5130.58496094, 3566.933125, 159.7140332), 'rotation':(0.032922, -0.577393, 0.032893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5147.5703125, 3566.7621875, 159.71950195), 'rotation':(0.001072, -0.576752, 0.001067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5170.21972656, 3566.53417969, 159.71991211), 'rotation':(0.001072, -0.576752, 0.001067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5204.18798828, 3566.191875, 159.69743164), 'rotation':(-0.104095, -0.577484, -0.104492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5247.54150391, 3557.37402344, 159.60069336), 'rotation':(0.153734, 179.423233, 0.152916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5258.58496094, 3557.26269531, 159.56708984), 'rotation':(0.179607, 179.423386, 0.178485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5264.10595703, 3557.20703125, 159.54920898), 'rotation':(0.185972, 179.423218, 0.184775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5275.14794922, 3557.0959375, 159.51177734), 'rotation':(0.199476, 179.423477, 0.198107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5286.19091797, 3556.98484375, 159.47125), 'rotation':(0.217603, 179.425842, 0.21597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5297.23291016, 3556.87328125, 159.42759766), 'rotation':(0.226817, 179.423965, 0.225028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5302.75439453, 3556.81761719, 159.40473633), 'rotation':(0.236065, 179.424011, 0.234114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5313.796875, 3556.7065625, 159.35810547), 'rotation':(0.243366, 179.423264, 0.241302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5319.31884766, 3556.65085938, 159.33419922), 'rotation':(0.248708, 179.425903, 0.246561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5330.36132812, 3556.53980469, 159.28483398), 'rotation':(0.259397, 179.423416, 0.257049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5346.92578125, 3556.3728125, 159.20681641), 'rotation':(0.275421, 179.423553, 0.272789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5357.96777344, 3556.26171875, 159.15240234), 'rotation':(0.283337, 179.426025, 0.28055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5363.48976562, 3556.20605469, 159.12489258), 'rotation':(0.284716, 179.425583, 0.281908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5374.53222656, 3556.09496094, 159.06911133), 'rotation':(0.289955, 179.425629, 0.287039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5391.098125, 3555.92796875, 158.98348633), 'rotation':(0.297885, 179.423172, 0.294803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5402.14015625, 3555.816875, 158.92518555), 'rotation':(0.304647, 179.421799, 0.301423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5236.56494141, 3565.86546875, 159.63061523), 'rotation':(-0.153748, -0.576752, -0.154572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5247.60791016, 3565.75414062, 159.60074219), 'rotation':(-0.166656, -0.576691, -0.167633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5253.12890625, 3565.69875, 159.58444336), 'rotation':(-0.179596, -0.576599, -0.180756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5258.65087891, 3565.64304688, 159.56713867), 'rotation':(-0.185974, -0.574158, -0.187195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5264.17236328, 3565.58765625, 159.54928711), 'rotation':(-0.19043, -0.576599, -0.191711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5269.69335938, 3565.53199219, 159.53092773), 'rotation':(-0.199493, -0.576538, -0.200867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5275.21533203, 3565.4763281200003, 159.51183594), 'rotation':(-0.208557, -0.576477, -0.210052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5280.73681641, 3565.42066406, 159.49197266), 'rotation':(-0.21759, -0.576385, -0.219238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5286.25830078, 3565.365, 159.47132812), 'rotation':(-0.226837, -0.57608, -0.228638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5297.30078125, 3565.25390625, 159.42767578000002), 'rotation':(-0.236053, -0.575989, -0.238007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5313.86474609, 3565.08714844, 159.35818359), 'rotation':(-0.248718, -0.576691, -0.250885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5319.38671875, 3565.0314843799997, 159.33427734), 'rotation':(-0.254059, -0.57663, -0.256317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5335.95214844, 3564.86449219, 159.25943359000001), 'rotation':(-0.27005, -0.576447, -0.272614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5346.99511719, 3564.7534375, 159.206875), 'rotation':(-0.280762, -0.576385, -0.283539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5358.03757812, 3564.64210938, 159.15248047), 'rotation':(-0.284729, -0.574432, -0.287567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5374.60304688, 3564.47535156, 159.06916992), 'rotation':(-0.292694, -0.574402, -0.295685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5380.125, 3564.4196875, 159.04089844), 'rotation':(-0.295349, -0.576843, -0.298401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5391.1684375, 3564.30859375, 158.98356445), 'rotation':(-0.300598, -0.576843, -0.303772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5402.21140625, 3564.19726562, 158.92524414), 'rotation':(-0.304718, -0.575775, -0.307983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5781.73976562, 3551.994375, 157.72501953), 'rotation':(-0.077057, 179.422272, -0.077271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5776.04734375, 3552.05152344, 157.71614258), 'rotation':(-0.077057, 179.422272, -0.077271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5764.6596875, 3552.16625, 157.70558594), 'rotation':(-0.018524, 179.42421, -0.018524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5747.58296875, 3552.338125, 157.70306641), 'rotation':(-0.003784, 179.422546, -0.003784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5736.1996875, 3552.4528906200003, 157.70231445), 'rotation':(-0.003784, 179.423996, -0.003784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5719.12257812, 3552.6247656200003, 157.70144531), 'rotation':(0.007472, 179.423523, 0.007471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5707.73828125, 3552.73949219, 157.70591797), 'rotation':(0.052572, 179.42363, 0.05248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5702.04539062, 3552.796875, 157.71134766), 'rotation':(0.074989, 179.42363, 0.074787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5690.660625, 3552.91164062, 157.72743164), 'rotation':(0.086368, 179.42186, 0.086105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5684.96875, 3552.9689843799997, 157.73602539), 'rotation':(0.095001, 179.42363, 0.094682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5662.19921875, 3553.19773438, 157.7771582), 'rotation':(0.130108, 179.42215, 0.129526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5645.12304688, 3553.36988281, 157.81945312), 'rotation':(0.156527, 179.42395, 0.155677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5633.73925781, 3553.484375, 157.85081055), 'rotation':(0.167913, 179.423584, 0.166933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5622.35546875, 3553.59914062, 157.88470703000002), 'rotation':(0.183124, 179.421021, 0.181965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5616.66210938, 3553.6564843799997, 157.90296875), 'rotation':(0.190917, 179.423782, 0.189656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5610.97070312, 3553.71386719, 157.92207031), 'rotation':(0.19856, 179.423782, 0.197185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5588.203125, 3553.94289062, 158.00578125), 'rotation':(0.22319, 179.422897, 0.221456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5576.81882812, 3554.05761719, 158.05055664), 'rotation':(0.234316, 179.424515, 0.2324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5565.43601562, 3554.17234375, 158.09795898000002), 'rotation':(0.245416, 179.423111, 0.243328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5536.9765625, 3554.45898438, 158.22610352), 'rotation':(0.268222, 179.424698, 0.265719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5514.21046875, 3554.68824219, 158.33547852), 'rotation':(0.283876, 179.42485, 0.281082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5502.82664062, 3554.80296875, 158.39274414), 'rotation':(0.293753, 179.425812, 0.290745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5497.13476562, 3554.86035156, 158.421875), 'rotation':(0.293746, 179.423447, 0.290752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5468.67726562, 3555.14671875, 158.56956055), 'rotation':(0.306006, 179.426346, 0.302748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5451.60253906, 3555.31859375, 158.66085938), 'rotation':(0.307406, 179.425461, 0.304117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5445.91113281, 3555.37597656, 158.69142578), 'rotation':(0.30727, 179.425415, 0.303993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5434.52832031, 3555.49070312, 158.75239258), 'rotation':(0.306498, 179.422913, 0.303224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5440.28710938, 3563.81371094, 158.72201171999998), 'rotation':(-0.307281, -0.577087, -0.310577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5445.97898438, 3563.75632812, 158.69149414), 'rotation':(-0.307404, -0.574524, -0.31073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5457.36179688, 3563.64183594, 158.63037109), 'rotation':(-0.306, -0.5755, -0.309296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5468.74609375, 3563.52710938, 158.5696582), 'rotation':(-0.302551, -0.575531, -0.305756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5491.51269531, 3563.29785156, 158.45114258), 'rotation':(-0.293732, -0.574188, -0.296783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5497.20460938, 3563.24046875, 158.42195312), 'rotation':(-0.293762, -0.576569, -0.296783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5502.89695312, 3563.18335938, 158.39282227), 'rotation':(-0.291962, -0.575073, -0.294952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5519.9721875, 3563.01125, 158.30756836), 'rotation':(-0.27597, -0.575226, -0.278625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5525.6640625, 3562.95410156, 158.28000977), 'rotation':(-0.271912, -0.575226, -0.274475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5531.35644531, 3562.89671875, 158.25288086), 'rotation':(-0.268188, -0.575256, -0.270721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5542.73976562, 3562.78222656, 158.19989257999998), 'rotation':(-0.262115, -0.577271, -0.264526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5554.125, 3562.66722656, 158.14805664), 'rotation':(-0.256622, -0.575287, -0.258942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5565.5078125, 3562.55273438, 158.09802734000002), 'rotation':(-0.234314, -0.576996, -0.236237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5571.20019531, 3562.49535156, 158.07388672), 'rotation':(-0.234314, -0.576996, -0.236237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5593.96828125, 3562.26609375, 157.98420898), 'rotation':(-0.213776, -0.57605, -0.215363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5599.66113281, 3562.20875, 157.96280273), 'rotation':(-0.206177, -0.576111, -0.207642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5628.12304688, 3561.9221093799997, 157.86737305), 'rotation':(-0.167908, -0.576416, -0.168915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5633.81542969, 3561.86476562, 157.85084961), 'rotation':(-0.160126, -0.576385, -0.161011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5645.1996875, 3561.75, 157.81947266), 'rotation':(-0.147675, -0.576141, -0.148438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5650.89304688, 3561.69289062, 157.80450195), 'rotation':(-0.147675, -0.576141, -0.148438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5702.1259375, 3561.17699219, 157.71136719), 'rotation':(-0.052551, -0.576355, -0.052673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5713.51125, 3561.0622656200003, 157.70263672), 'rotation':(-0.007477, -0.578796, -0.007477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5741.973125, 3560.77585938, 157.70269531), 'rotation':(0.003798, -0.577454, 0.003785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5753.35695312, 3560.66113281, 157.70344727), 'rotation':(0.003791, -0.576019, 0.00379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5759.04882812, 3560.60398438, 157.70382812), 'rotation':(0.018517, -0.57785, 0.018501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5764.74265625, 3560.5466406200003, 157.70558594), 'rotation':(0.047723, -0.57782, 0.047639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5980.87695312, 3555.53808594, 158.7330957), 'rotation':(0.492129, -2.082672, 0.483725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.09375, 3556.55078125, 158.50703125), 'rotation':(0.443013, -2.081818, 0.436201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5947.53757812, 3556.7534375, 158.4653125), 'rotation':(0.431682, -2.084778, 0.42521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.98195312, 3556.95582031, 158.42482422), 'rotation':(0.420555, -2.085175, 0.414426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5930.86867188, 3557.36085938, 158.34744141), 'rotation':(0.386582, -2.083344, 0.3814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5891.97703125, 3558.77855469, 158.09150391), 'rotation':(0.373174, -2.086121, 0.368335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5886.42140625, 3558.9809375, 158.05557617), 'rotation':(0.370155, -2.084564, 0.365403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5880.86421875, 3559.18359375, 158.02056641), 'rotation':(0.357041, -2.087646, 0.352605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5875.3003125, 3559.36011719, 157.98830078), 'rotation':(0.332521, -1.893555, 0.328681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5858.64304688, 3559.60109375, 157.90811523), 'rotation':(0.257553, -0.575897, 0.255246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5847.52101562, 3559.713125, 157.86860352), 'rotation':(0.179511, -0.576508, 0.178388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5841.9609375, 3559.7690625, 157.85273438000002), 'rotation':(0.179511, -0.576508, 0.178388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5830.84671875, 3559.94214844, 157.82748046999998), 'rotation':(0.121051, -0.578125, 0.120545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5836.25875, 3551.30078125, 157.8390918), 'rotation':(-0.121063, 179.424118, -0.121552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5852.94289062, 3551.1325781200003, 157.88669922), 'rotation':(-0.179504, 179.423492, -0.180634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5858.50195312, 3551.07664062, 157.90790039), 'rotation':(-0.218475, 179.423752, -0.220154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5864.0634375, 3551.02074219, 157.93239258), 'rotation':(-0.257538, 179.424088, -0.259888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5880.80765625, 3550.65476562, 158.0221582), 'rotation':(-0.34082, 178.10231, -0.344879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5903.04, 3549.84449219, 158.16543945), 'rotation':(-0.373138, 177.915482, -0.378052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5925.26515625, 3549.03441406, 158.31198242), 'rotation':(-0.378967, 177.915558, -0.384003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.93507812, 3548.42675781, 158.42670898), 'rotation':(-0.40918, 177.917664, -0.41507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5947.4921875, 3548.224375, 158.46726562), 'rotation':(-0.420532, 177.915024, -0.426727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.04929688, 3548.02171875, 158.5090332), 'rotation':(-0.431671, 177.915207, -0.438232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5964.16359375, 3547.61621094, 158.59629883), 'rotation':(-0.454193, 177.915558, -0.461426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.72023438, 3547.4138281200003, 158.64175781), 'rotation':(-0.465332, 177.915726, -0.472961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.83789062, 3547.14453125, 158.73538086), 'rotation':(-0.482239, 177.916275, -0.490387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.39453125, 3546.9509375, 158.78314453000002), 'rotation':(-0.492157, 177.915451, -0.500671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.93453125, 3546.77976562, 158.83198242), 'rotation':(-0.508087, 178.482285, -0.517151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.19140625, 3786.49289062, 159.64396484), 'rotation':(0.572602, -0.554382, 0.56125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.51125, 3786.54859375, 159.58805664), 'rotation':(0.561496, -0.554596, 0.550575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.83109375, 3786.60398438, 159.53335938), 'rotation':(0.550226, -0.55481, 0.53974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5957.788125, 3786.77046875, 159.37489258), 'rotation':(0.533274, -0.553833, 0.52342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5946.42726562, 3786.88132812, 159.27381836), 'rotation':(0.497641, -0.555328, 0.489066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.74460938, 3786.93703125, 159.22507812), 'rotation':(0.497641, -0.555328, 0.489066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.70359375, 3787.10328125, 159.08780273), 'rotation':(0.449843, -0.556122, 0.442821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5912.34078125, 3787.214375, 159.00086914), 'rotation':(0.437904, -0.556519, 0.431252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5900.97953125, 3787.3254687500003, 158.91737305), 'rotation':(0.426518, -0.555786, 0.420215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5883.93554688, 3787.49195312, 158.80180664), 'rotation':(0.380537, -0.556427, 0.375512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5855.52929688, 3787.76929688, 158.63416016), 'rotation':(0.30563, -0.556305, 0.302398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5844.16453125, 3787.88039062, 158.57712891), 'rotation':(0.273091, -0.559113, 0.270494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.4834375, 3787.93578125, 158.55105469), 'rotation':(0.256856, -0.556732, 0.254569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.75929688, 3788.15773438, 158.46055664), 'rotation':(0.216387, -0.55838, 0.214763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5810.0790625, 3788.21335938, 158.43912109000001), 'rotation':(0.216216, -0.55835, 0.214594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.6753125, 3779.77734375, 158.46053711000002), 'rotation':(-0.216248, 179.441605, -0.217865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5821.35742188, 3779.72195312, 158.48199219), 'rotation':(-0.21637, 179.44165, -0.218018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5832.723125, 3779.61085938, 158.5265918), 'rotation':(-0.224335, 179.442978, -0.226074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.4053125, 3779.55539062, 158.55107422), 'rotation':(-0.24054, 179.440598, -0.242554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5861.13867188, 3779.33351562, 158.66512695), 'rotation':(-0.305664, 179.441238, -0.308929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5872.504375, 3779.2221875, 158.7315332), 'rotation':(-0.338043, 179.444061, -0.342041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5889.55171875, 3779.0559375000003, 158.83930664), 'rotation':(-0.380554, 179.442032, -0.385651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5900.91796875, 3778.94484375, 158.91750977), 'rotation':(-0.403473, 179.443863, -0.40921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5912.28273438, 3778.83398438, 159.00105469), 'rotation':(-0.426544, 179.444199, -0.432922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5917.96578125, 3778.7785937500003, 159.04435547), 'rotation':(-0.437897, 179.443451, -0.444641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5923.64890625, 3778.72289062, 159.08800781), 'rotation':(-0.437897, 179.443451, -0.444641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5974.79054688, 3778.22335938, 159.53375), 'rotation':(-0.539124, 179.444977, -0.549316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.4721875, 3778.16796875, 159.58848633), 'rotation':(-0.550232, 179.447845, -0.560883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.836875, 3778.05710938, 159.70154297), 'rotation':(-0.572632, 179.445618, -0.584137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4765.40429688, 3981.28585938, 156.76623046999998), 'rotation':(-1.08429, 179.728531, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4759.70849609, 3981.3146875, 156.65983398), 'rotation':(-1.08429, 179.728531, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4731.22851562, 3981.45945312, 156.10876953000002), 'rotation':(-1.134827, 179.730652, -1.180481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4725.53125, 3981.48851562, 155.99586914), 'rotation':(-1.14151, 179.731567, -1.187714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4714.13916016, 3981.54664062, 155.76899414), 'rotation':(-1.15509, 179.732132, -1.202393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4679.96289062, 3981.72023438, 155.07012695), 'rotation':(-1.188721, 179.733093, -1.238861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4668.56984375, 3981.77828125, 154.83357422), 'rotation':(-1.188843, 179.733078, -1.238953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4657.17773438, 3981.83617188, 154.59675780999999), 'rotation':(-1.200714, 179.735199, -1.251862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4645.78515625, 3981.8940625, 154.35817383), 'rotation':(-1.204742, 179.733795, -1.256256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4640.08886719, 3981.9231250000003, 154.23833008), 'rotation':(-1.204651, 179.73378, -1.256134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4634.39257812, 3981.9518749999997, 154.11848633), 'rotation':(-1.204651, 179.73378, -1.256134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4611.60695312, 3982.06789062, 153.63913086), 'rotation':(-1.20401, 179.733185, -1.255432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4588.82078125, 3982.18382812, 153.16035156), 'rotation':(-1.202332, 179.734909, -1.253632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4577.42726562, 3982.24171875, 152.9212207), 'rotation':(-1.199188, 179.732681, -1.250214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4560.33640625, 3982.32859375, 152.56575195), 'rotation':(-1.178864, 179.731873, -1.228149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4554.63769531, 3982.35765625, 152.4484082), 'rotation':(-1.172272, 179.733856, -1.221008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4543.24414062, 3982.41578125, 152.21580078), 'rotation':(-1.158813, 179.733292, -1.206421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4520.45164062, 3982.53148438, 151.75686523000002), 'rotation':(-1.140961, 179.730896, -1.187103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4514.75539062, 3982.56054688, 151.64339844), 'rotation':(-1.124817, 179.730301, -1.169647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4503.36035156, 3982.6184375000003, 151.41945312), 'rotation':(-1.109009, 179.72966, -1.152588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4497.6640625, 3982.6475, 151.30914062), 'rotation':(-1.092865, 179.730759, -1.135193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4486.26515625, 3982.7053125, 151.09157227), 'rotation':(-1.084991, 179.729523, -1.126709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4463.47167969, 3982.8215625000003, 150.66498047), 'rotation':(-1.027161, 179.728226, -1.064514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4429.28273438, 3982.90867188, 150.07220703000002), 'rotation':(-0.95285, 179.725571, -0.984955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4429.55957031, 3991.45632812, 150.07609375), 'rotation':(0.952846, -0.274445, 0.921538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4434.91308594, 3991.34742188, 150.16539062), 'rotation':(0.961212, -0.276611, 0.929363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4440.61132812, 3991.31859375, 150.26150391), 'rotation':(0.977584, -0.273499, 0.944631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4457.7065625, 3991.2317187500003, 150.56005859), 'rotation':(1.027151, -0.274323, 0.990804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4497.58984375, 3991.02929688, 151.30686523), 'rotation':(1.108943, -0.270325, 1.066617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4503.28613281, 3991.00023438, 151.41717773), 'rotation':(1.124809, -0.269714, 1.081263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4508.98339844, 3990.9714062499997, 151.52867188), 'rotation':(1.140956, -0.267395, 1.096166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4526.07519531, 3990.88429688, 151.86875977), 'rotation':(1.152349, -0.266968, 1.106673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4531.77148438, 3990.85523438, 151.98313477), 'rotation':(1.152349, -0.266968, 1.106673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4543.16554688, 3990.80710938, 152.21332031), 'rotation':(1.165681, -0.268677, 1.118948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4548.86132812, 3990.74460938, 152.32929688000002), 'rotation':(1.172279, -0.266144, 1.125016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4560.254375, 3990.6775, 152.56320312), 'rotation':(1.185755, -0.265594, 1.137399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4571.64796875, 3990.619375, 152.79951172), 'rotation':(1.199169, -0.265045, 1.149729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4577.34523438, 3990.5903125, 152.91862305), 'rotation':(1.202318, -0.266785, 1.152621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4588.7378125, 3990.5325000000003, 153.15771484), 'rotation':(1.202434, -0.266785, 1.15272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4594.4340625, 3990.50367188, 153.27732422), 'rotation':(1.203028, -0.265137, 1.15327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4600.13039062, 3990.47460938, 153.39697266), 'rotation':(1.203028, -0.265137, 1.15327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4611.52390625, 3990.4167187499997, 153.63649414), 'rotation':(1.204681, -0.266205, 1.15479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4622.91648438, 3990.35867188, 153.87614258), 'rotation':(1.204743, -0.264587, 1.154852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4634.30957031, 3990.30078125, 154.11583984), 'rotation':(1.204743, -0.266205, 1.154847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4640.00585938, 3990.27171875, 154.23568359), 'rotation':(1.204743, -0.266205, 1.154847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4645.70214844, 3990.24265625, 154.35552734), 'rotation':(1.200699, -0.266724, 1.151142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4674.18408203, 3990.09789062, 154.94926758), 'rotation':(1.188822, -0.264465, 1.140225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4679.88085938, 3990.0690624999997, 155.06754883), 'rotation':(1.188726, -0.266907, 1.140132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4685.57861328, 3990.04, 155.18570312), 'rotation':(1.182114, -0.268188, 1.134065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4691.27539062, 3990.01101562, 155.30331055), 'rotation':(1.16857, -0.267334, 1.121611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4696.97119141, 3989.9821875, 155.42025390999999), 'rotation':(1.16857, -0.267334, 1.121611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4702.66748047, 3989.953125, 155.53648438), 'rotation':(1.155128, -0.267883, 1.109235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4719.75732422, 3989.86625, 155.88014648), 'rotation':(1.134843, -0.269348, 1.09052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4748.2421875, 3989.7214062499997, 156.44056641), 'rotation':(1.084292, -0.271454, 1.043818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4759.63769531, 3989.66359375, 156.65769531), 'rotation':(1.063986, -0.270691, 1.025005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4797.78955078, 3981.12109375, 157.35479492000002), 'rotation':(-1.014282, 179.725571, -1.05069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4814.35351562, 3981.036875, 157.64025390999998), 'rotation':(-0.972076, 179.72583, -1.005524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.875, 3981.00875, 157.73242188), 'rotation':(-0.950745, 179.723404, -0.982697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4847.484375, 3980.8684375000003, 158.17875977), 'rotation':(-0.896332, 179.722778, -0.924744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4869.57177734, 3980.75585938, 158.50767578), 'rotation':(-0.826447, 179.720673, -0.850525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4897.18212891, 3980.61523438, 158.88820312), 'rotation':(-0.782166, 179.719391, -0.803741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4908.2265625, 3980.5590625, 159.02878906), 'rotation':(-0.710236, 179.717514, -0.728027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4924.79443359, 3980.47484375, 159.22523438), 'rotation':(-0.656311, 179.714417, -0.671478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4935.83984375, 3980.4140625, 159.35070312), 'rotation':(-0.641235, 179.715881, -0.655701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4941.36181641, 3980.38351562, 159.41150391), 'rotation':(-0.641235, 179.715881, -0.655701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4957.93017578, 3980.32789062, 159.58094727), 'rotation':(-0.580658, 179.7146, -0.592499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4803.35302734, 3989.47359375, 157.45123046999998), 'rotation':(0.993171, -0.275177, 0.959175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4808.87304688, 3989.44554688, 157.54652344), 'rotation':(0.972031, -0.274139, 0.939455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.91699219, 3989.3893749999997, 157.73242188), 'rotation':(0.940237, -0.275208, 0.909751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4825.43896484, 3989.36132812, 157.8237793), 'rotation':(0.940237, -0.275208, 0.909751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4830.95996094, 3989.3332812500003, 157.91439453), 'rotation':(0.931385, -0.276123, 0.901468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4836.48144531, 3989.30515625, 158.00417969), 'rotation':(0.913913, -0.276672, 0.885101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4842.00439453, 3989.27710938, 158.09230469), 'rotation':(0.89636, -0.277222, 0.868624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4875.13525391, 3989.1084375, 158.58572266), 'rotation':(0.800047, -0.280975, 0.777934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4880.65771484, 3989.0803125, 158.66291992), 'rotation':(0.782152, -0.280609, 0.761017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4891.70214844, 3989.02390625, 158.81496094), 'rotation':(0.746143, -0.281555, 0.7269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4924.8359375, 3988.85570312, 159.22523438), 'rotation':(0.656361, -0.282898, 0.641458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4941.40380859, 3988.7785937500003, 159.41150391), 'rotation':(0.610926, -0.28476, 0.598017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4946.92724609, 3988.75242188, 159.47040039), 'rotation':(0.580648, -0.2854, 0.568966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4990.33251953, 3980.14132812, 159.86749023000002), 'rotation':(-0.475861, 179.713776, -0.483826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5007.31835938, 3980.05515625, 159.99666016), 'rotation':(-0.401855, 179.710922, -0.407501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5012.98095703, 3980.02640625, 160.03464844), 'rotation':(-0.401855, 179.710922, -0.407501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5018.64306641, 3979.99757812, 160.07064453), 'rotation':(-0.364868, 179.710403, -0.369537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5024.30664062, 3979.96898438, 160.10489257999998), 'rotation':(-0.346497, 179.710663, -0.350708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5035.63232422, 3979.91109375, 160.17209961), 'rotation':(-0.336487, 179.708298, -0.340424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5041.29589844, 3979.88234375, 160.20300781), 'rotation':(-0.316925, 179.7108, -0.320435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5046.95898438, 3979.85351562, 160.23177734), 'rotation':(-0.297211, 179.710602, -0.300293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5075.27294922, 3979.70945312, 160.34453125), 'rotation':(-0.188904, 179.709991, -0.190155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5092.26123047, 3979.6228125, 160.39817383), 'rotation':(-0.17038, 179.710129, -0.171387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5097.92529297, 3979.59398438, 160.41132812), 'rotation':(-0.132904, 179.70784, -0.133514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5103.58642578, 3979.5651562499997, 160.42132812), 'rotation':(-0.095703, 179.709778, -0.096008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5114.91162109, 3979.50757812, 160.43318359), 'rotation':(-0.058502, 179.707596, -0.058594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5120.57568359, 3979.47875, 160.43711914), 'rotation':(-0.039734, 179.709457, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5131.90380859, 3979.42117188, 160.44496094), 'rotation':(-0.039734, 179.707855, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5137.56787109, 3979.39234375, 160.44889648), 'rotation':(-0.039734, 179.709457, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5143.23193359, 3979.36351562, 160.45283203), 'rotation':(-0.039734, 179.707855, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5148.89355469, 3979.3346874999997, 160.45583984), 'rotation':(-0.039734, 179.707855, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5160.21972656, 3979.27710938, 160.45410156), 'rotation':(-0.011993, 179.70932, -0.012024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5194.20019531, 3979.1042187499997, 160.41386719), 'rotation':(0.070918, 179.707855, 0.07074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4996.03710938, 3988.4934375000003, 159.91325195), 'rotation':(0.438997, -0.288544, 0.432303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5007.36083984, 3988.43554688, 159.99666016), 'rotation':(0.364848, -0.287872, 0.360226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5018.68554688, 3988.3776562499997, 160.07064453), 'rotation':(0.346489, -0.289337, 0.342327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5024.34912109, 3988.3489062500003, 160.10489257999998), 'rotation':(0.346338, -0.289337, 0.342176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5030.01171875, 3988.32007812, 160.13908203), 'rotation':(0.336469, -0.288971, 0.33253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5041.33837891, 3988.26242188, 160.20300781), 'rotation':(0.297209, -0.289398, 0.294139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5047.00146484, 3988.23367188, 160.23177734), 'rotation':(0.277517, -0.289612, 0.274846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5052.66259766, 3988.20484375, 160.25841796999998), 'rotation':(0.257785, -0.289764, 0.255475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5075.31542969, 3988.08960938, 160.34453125), 'rotation':(0.188896, -0.290009, 0.187661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5080.97949219, 3988.06078125, 160.36320312), 'rotation':(0.188896, -0.290009, 0.187661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5086.64111328, 3988.03195312, 160.38148438), 'rotation':(0.170365, -0.291962, 0.169362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5092.30371094, 3988.00320312, 160.39817383), 'rotation':(0.132915, -0.29007, 0.132291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5103.62890625, 3987.94554688, 160.42132812), 'rotation':(0.058494, -0.290314, 0.058369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5109.29150391, 3987.9167187499997, 160.42833008), 'rotation':(0.039731, -0.292145, 0.039672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5114.95410156, 3987.8879687500003, 160.43318359), 'rotation':(0.039731, -0.292145, 0.039672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5120.61816406, 3987.85914062, 160.43711914), 'rotation':(0.039731, -0.290527, 0.039676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5126.28222656, 3987.8303125, 160.44103515999998), 'rotation':(0.039731, -0.292145, 0.039683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5131.94628906, 3987.80148438, 160.44496094), 'rotation':(0.039731, -0.292145, 0.039683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5143.27441406, 3987.74390625, 160.45283203), 'rotation':(0.012007, -0.292206, 0.012009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5154.60009766, 3987.6862499999997, 160.45705078), 'rotation':(-0.043274, -0.290649, -0.043335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5160.26220703, 3987.6575000000003, 160.45410156), 'rotation':(-0.043274, -0.290649, -0.043335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5165.92382812, 3987.62867188, 160.44935547), 'rotation':(-0.070923, -0.292145, -0.071075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5194.24267578, 3987.484375, 160.41386719), 'rotation':(-0.087311, -0.290283, -0.087585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5199.90673828, 3987.4553125, 160.40524414), 'rotation':(-0.11969, -0.291656, -0.120178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5205.56982422, 3987.42648438, 160.39451172), 'rotation':(-0.11969, -0.291656, -0.120178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5237.91064453, 3978.881875, 160.30390625), 'rotation':(0.180795, 179.709412, 0.179653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5243.43457031, 3978.85375, 160.28591796999999), 'rotation':(0.189285, 179.709488, 0.188047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5254.48291016, 3978.79757812, 160.24733398), 'rotation':(0.206497, 179.709579, 0.20502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5260.00537109, 3978.76953125, 160.22672852), 'rotation':(0.215014, 179.70697, 0.213412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5265.52978516, 3978.74125, 160.20526367), 'rotation':(0.223511, 179.709732, 0.221769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5276.57714844, 3978.68507812, 160.15969727), 'rotation':(0.24073, 179.709854, 0.23871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5287.62597656, 3978.62890625, 160.11244141), 'rotation':(0.245033, 179.708679, 0.242954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5309.72119141, 3978.51632812, 160.01293945), 'rotation':(0.269342, 179.709244, 0.266813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5315.24511719, 3978.48828125, 159.98626953000002), 'rotation':(0.279095, 179.709351, 0.276394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5326.29248047, 3978.4323437499997, 159.93177734), 'rotation':(0.283951, 179.710785, 0.281156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5331.816875, 3978.40429688, 159.9044043), 'rotation':(0.283938, 179.7108, 0.281139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5348.38914062, 3978.32007812, 159.82124023), 'rotation':(0.290105, 179.71167, 0.287179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5364.96140625, 3978.2356250000003, 159.73585938), 'rotation':(0.297605, 179.711746, 0.294528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5370.48585938, 3978.2075, 159.70691406), 'rotation':(0.300084, 179.709137, 0.296953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5381.53320312, 3978.15140625, 159.6484375), 'rotation':(0.303807, 179.70993, 0.300602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5387.05566406, 3978.06445312, 159.61924805), 'rotation':(0.303014, 179.709152, 0.29983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5396.73242188, 3977.94460938, 159.56837890999998), 'rotation':(0.299968, 179.709106, 0.296847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5398.15332031, 3986.57664062, 159.56115234), 'rotation':(-0.298676, -0.288574, -0.301788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5376.05566406, 3986.55953125, 159.67771484000002), 'rotation':(-0.303802, -0.29007, -0.307037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5370.53171875, 3986.58765625, 159.70689453), 'rotation':(-0.302338, -0.290802, -0.305542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5359.48289062, 3986.64382812, 159.76456055), 'rotation':(-0.297607, -0.290863, -0.30072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5348.43554688, 3986.69992188, 159.82123047), 'rotation':(-0.292572, -0.290924, -0.295593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5331.8628125, 3986.78445312, 159.90438477), 'rotation':(-0.285217, -0.290985, -0.288055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5315.29101562, 3986.86765625, 159.98625), 'rotation':(-0.283936, -0.291168, -0.286774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5293.19482422, 3986.9809375, 160.0884668), 'rotation':(-0.259552, -0.290833, -0.261902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5254.52783203, 3987.17773438, 160.24731445), 'rotation':(-0.215027, -0.290344, -0.216644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5249.00390625, 3987.2057812499997, 160.26704102), 'rotation':(-0.206512, -0.290405, -0.208008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5243.47949219, 3987.23390625, 160.28591796999999), 'rotation':(-0.197815, -0.290436, -0.199158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5237.95556641, 3987.26195312, 160.30390625), 'rotation':(-0.189301, -0.290527, -0.190582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5755.04984375, 3976.2521875, 158.87109375), 'rotation':(-0.191986, 179.709915, -0.193268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5743.6553125, 3976.3103125, 158.83386719), 'rotation':(-0.166016, 179.708344, -0.166962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5737.95898438, 3976.339375, 158.81736328), 'rotation':(-0.153015, 179.708832, -0.153839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5703.77390625, 3976.51265625, 158.73797851999998), 'rotation':(-0.076752, 179.708893, -0.076935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.285625, 3976.6575000000003, 158.71037109), 'rotation':(-0.017487, 179.708313, -0.017487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5669.586875, 3976.6865625, 158.70865234000001), 'rotation':(-0.017334, 179.708298, -0.017365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5652.49707031, 3976.77367188, 158.70344727), 'rotation':(0.001694, 179.709213, 0.001697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5606.91648438, 3977.00539062, 158.74203125), 'rotation':(0.086648, 179.70723, 0.086388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5595.52101562, 3977.06296875, 158.76131836000002), 'rotation':(0.120129, 179.707321, 0.11963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5578.4296875, 3977.14992188, 158.79956055), 'rotation':(0.148085, 179.708633, 0.147319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5567.0346875, 3977.20796875, 158.82954102), 'rotation':(0.155906, 179.709351, 0.155058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5561.33789062, 3977.23679688, 158.84504883), 'rotation':(0.171424, 179.709473, 0.170399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5544.2465625, 3977.32375, 158.89814453), 'rotation':(0.202659, 179.708252, 0.201228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5532.85203125, 3977.381875, 158.93771484), 'rotation':(0.210513, 179.710037, 0.20898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5521.4575, 3977.4396875, 158.97951172), 'rotation':(0.213819, 179.708679, 0.212215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5515.76074219, 3977.46875, 159.00103516), 'rotation':(0.221073, 179.711334, 0.219368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5504.3671875, 3977.525625, 159.04629882999998), 'rotation':(0.241966, 179.708862, 0.239927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5492.973125, 3977.58445312, 159.09454102), 'rotation':(0.256091, 179.709, 0.253822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5481.57960938, 3977.64257812, 159.14578125), 'rotation':(0.266603, 179.709991, 0.26413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5475.88183594, 3977.67140625, 159.17222656), 'rotation':(0.266569, 179.709991, 0.264114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5464.48875, 3977.72953125, 159.22541992), 'rotation':(0.26982, 179.709305, 0.267284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5458.79199219, 3977.75828125, 159.25244141), 'rotation':(0.276636, 179.711258, 0.273979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5755.09179688, 3984.63234375, 158.87109375), 'rotation':(0.218013, -0.289886, 0.216362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.395, 3984.6614062500003, 158.85199219), 'rotation':(0.191969, -0.291504, 0.190693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5738.0009375, 3984.71945312, 158.81736328), 'rotation':(0.165994, -0.290222, 0.165039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5726.60453125, 3984.77734375, 158.78648438), 'rotation':(0.153017, -0.291168, 0.152215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5715.2109375, 3984.83523438, 158.75925781), 'rotation':(0.127656, -0.290924, 0.127098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5692.41890625, 3984.9509375, 158.72253906), 'rotation':(0.076737, -0.291107, 0.076529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.32765625, 3985.0378124999997, 158.71037109), 'rotation':(0.025941, -0.291199, 0.025919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5669.62890625, 3985.066875, 158.70865234000001), 'rotation':(0.017492, -0.291656, 0.01748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5658.23585938, 3985.12476562, 158.70516602), 'rotation':(0.017492, -0.291687, 0.017478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5652.5390625, 3985.15382812, 158.70344727), 'rotation':(0.017492, -0.291656, 0.01748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5646.8403125, 3985.18265625, 158.70332031), 'rotation':(-0.001709, -0.290741, -0.001678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5641.14257812, 3985.21164062, 158.70568359), 'rotation':(-0.001709, -0.290741, -0.001678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5629.7465625, 3985.26953125, 158.71608398), 'rotation':(-0.058685, -0.291626, -0.058777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5624.04980469, 3985.29859375, 158.7219043), 'rotation':(-0.058685, -0.291626, -0.058777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5618.35304688, 3985.32742188, 158.72773438000002), 'rotation':(-0.058655, -0.290131, -0.058777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5612.65578125, 3985.35640625, 158.73426758), 'rotation':(-0.064178, -0.292847, -0.064301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5595.56296875, 3985.44335938, 158.76131836000002), 'rotation':(-0.108948, -0.292694, -0.109375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5578.47167969, 3985.5299999999997, 158.79956055), 'rotation':(-0.142456, -0.289795, -0.143158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5572.77390625, 3985.5590625, 158.81426758), 'rotation':(-0.148102, -0.291351, -0.148865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5561.37988281, 3985.61695312, 158.84504883), 'rotation':(-0.155914, -0.290619, -0.156738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5555.68261719, 3985.64601562, 158.86208984), 'rotation':(-0.171417, -0.290527, -0.172455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5544.28808594, 3985.70382812, 158.89814453), 'rotation':(-0.187042, -0.29187, -0.188263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5532.8940625, 3985.76195312, 158.93771484), 'rotation':(-0.202667, -0.290314, -0.204102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5504.4096875, 3985.90671875, 159.04629882999998), 'rotation':(-0.235046, -0.291168, -0.236969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5475.92382812, 3986.05148438, 159.17222656), 'rotation':(-0.266602, -0.289978, -0.269073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5470.22753906, 3986.08054688, 159.19873047), 'rotation':(-0.266602, -0.289978, -0.269073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5453.1371875, 3986.1675, 159.27995117), 'rotation':(-0.276672, -0.290649, -0.279327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5447.4409375, 3986.1965625000003, 159.30808594), 'rotation':(-0.283234, -0.288666, -0.286041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5441.74414062, 3986.225625, 159.33669921999999), 'rotation':(-0.289948, -0.290497, -0.292877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5810.234375, 3975.84203125, 159.12469726999998), 'rotation':(-0.324677, 179.710297, -0.328369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.913125, 3975.84328125, 159.15768555), 'rotation':(-0.324677, 179.710297, -0.328369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.61476562, 3975.82765625, 159.30089844), 'rotation':(-0.371368, 179.708908, -0.376221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5844.29, 3975.79882812, 159.33916016), 'rotation':(-0.384216, 179.711685, -0.389374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5849.9653125, 3975.77, 159.37874023), 'rotation':(-0.396912, 179.711823, -0.402435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5872.66890625, 3975.6540625, 159.5503125), 'rotation':(-0.447662, 179.712601, -0.454712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5884.02101562, 3975.5964062499997, 159.6428418), 'rotation':(-0.473053, 179.711563, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5889.69625, 3975.5676562500003, 159.69040039), 'rotation':(-0.485626, 179.714157, -0.493927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5901.04640625, 3975.50976562, 159.78921875), 'rotation':(-0.510956, 179.712204, -0.520111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5912.39796875, 3975.4521875, 159.89292969), 'rotation':(-0.523834, 179.714828, -0.533478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.74851562, 3975.39429688, 160.00158203), 'rotation':(-0.549042, 179.715286, -0.559631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5929.42429688, 3975.36546875, 160.0575), 'rotation':(-0.561707, 179.713135, -0.572815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5946.45015625, 3975.2790625, 160.22916992), 'rotation':(-0.578186, 179.715073, -0.589966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.12453125, 3975.25023438, 160.2884668), 'rotation':(-0.598724, 179.713974, -0.611359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5957.80125, 3975.2214062499997, 160.34938477), 'rotation':(-0.598724, 179.713974, -0.611359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5969.15039062, 3975.16359375, 160.47441406), 'rotation':(-0.639618, 179.714844, -0.654022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.82570312, 3975.13453125, 160.53834961), 'rotation':(-0.649933, 179.71582, -0.664825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.17578125, 3975.0768749999997, 160.66758789), 'rotation':(-0.64978, 179.71582, -0.664673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5997.52585938, 3975.01929688, 160.79985352), 'rotation':(-0.680847, 179.718155, -0.697205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5810.2778125, 3984.48140625, 159.12469726999998), 'rotation':(0.340902, -0.28952, 0.336868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.95554688, 3984.42257812, 159.15766602), 'rotation':(0.340902, -0.28952, 0.336868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5832.97804688, 3984.2365625, 159.26394531), 'rotation':(0.371412, -0.288513, 0.366627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.65234375, 3984.20773438, 159.30086914), 'rotation':(0.384205, -0.290924, 0.379072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5844.3271875, 3984.17898438, 159.33913086), 'rotation':(0.396861, -0.288147, 0.39139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5850.00148438, 3984.15015625, 159.37869141), 'rotation':(0.409518, -0.287964, 0.403699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5855.67773438, 3984.12109375, 159.41961914), 'rotation':(0.422345, -0.287781, 0.416148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5884.05125, 3983.97703125, 159.64273438), 'rotation':(0.485585, -0.285828, 0.477409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5895.39992188, 3983.91945312, 159.7390625), 'rotation':(0.510946, -0.28537, 0.501896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5901.07421875, 3983.890625, 159.78908203), 'rotation':(0.523807, -0.287598, 0.514307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5912.42382812, 3983.83273438, 159.89277344), 'rotation':(0.536347, -0.287354, 0.526383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.77296875, 3983.77515625, 160.00140625), 'rotation':(0.561715, -0.286865, 0.550772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5935.12257812, 3983.71726562, 160.11358398000002), 'rotation':(0.578189, -0.284912, 0.566607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5940.7959375, 3983.6887500000003, 160.17083984), 'rotation':(0.598762, -0.286041, 0.586342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.1440625, 3983.63109375, 160.28822266), 'rotation':(0.619177, -0.284058, 0.605906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5974.84179688, 3983.515625, 160.53803711), 'rotation':(0.64979, -0.28418, 0.635178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.515625, 3983.4865625, 160.60242188), 'rotation':(0.64979, -0.28418, 0.635178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5986.18992188, 3983.45773438, 160.66725586), 'rotation':(0.660254, -0.284607, 0.645166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.86328125, 3983.42898438, 160.73263672), 'rotation':(0.680758, -0.282471, 0.664731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4942.96777344, 3327.94261719, 155.69584961), 'rotation':(-0.596069, 179.88179, -0.608551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4937.34228516, 3327.95484375, 155.63714844), 'rotation':(-0.60614, 179.88472, -0.61908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4931.71826172, 3327.96703125, 155.57739258), 'rotation':(-0.616455, 179.882233, -0.629822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4926.09179688, 3327.97898438, 155.51652344000001), 'rotation':(-0.626404, 179.885147, -0.640228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4920.46630859, 3327.99121094, 155.45458984), 'rotation':(-0.63678, 179.88266, -0.651062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4914.84082031, 3328.0034375, 155.39157226999998), 'rotation':(-0.652008, 179.885315, -0.666962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4909.21582031, 3328.0153906200003, 155.32777344), 'rotation':(-0.652008, 179.885315, -0.666962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4903.59082031, 3328.02734375, 155.26365234000002), 'rotation':(-0.65686, 179.884354, -0.672028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4897.96435547, 3328.03953125, 155.19888672), 'rotation':(-0.66687, 179.884598, -0.682556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4886.71386719, 3328.06371094, 155.06624023), 'rotation':(-0.686615, 179.885056, -0.703217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4881.08935547, 3328.0759375, 154.99836914), 'rotation':(-0.706329, 179.885544, -0.723938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4869.83789062, 3328.10007812, 154.85948242), 'rotation':(-0.726074, 179.883362, -0.744659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4858.58789062, 3328.12425781, 154.71681640999998), 'rotation':(-0.73111, 179.885864, -0.749939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4852.96191406, 3328.13648438, 154.645), 'rotation':(-0.73111, 179.885864, -0.749939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4836.08691406, 3328.17261719, 154.42667969000001), 'rotation':(-0.764679, 179.887039, -0.785309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4830.46191406, 3328.18480469, 154.35194336), 'rotation':(-0.777954, 179.885468, -0.799316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.21289062, 3328.20921875, 154.19973633), 'rotation':(-0.784698, 179.889175, -0.806396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4813.58691406, 3328.22117188, 154.12267578), 'rotation':(-0.784698, 179.887085, -0.806427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4807.95996094, 3328.23316406, 154.0455957), 'rotation':(-0.78772, 179.88652, -0.809631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4785.4609375, 3328.28199219, 153.73293945), 'rotation':(-0.811737, 179.889771, -0.834991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4768.58447266, 3328.318125, 153.49196289), 'rotation':(-0.829773, 179.887711, -0.854095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4762.96044922, 3328.3303125, 153.41044922), 'rotation':(-0.832825, 179.888901, -0.85733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4757.33544922, 3328.34253906, 153.32866211), 'rotation':(-0.832886, 179.888901, -0.857361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4751.70947266, 3328.35449219, 153.2468457), 'rotation':(-0.832886, 179.888901, -0.857361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4746.08398438, 3328.36671875, 153.16503906), 'rotation':(-0.838104, 179.889008, -0.862885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4740.45996094, 3328.37867188, 153.0828418), 'rotation':(-0.848602, 179.889313, -0.874023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4729.20947266, 3328.4028125, 152.91697266), 'rotation':(-0.853882, 179.889145, -0.879608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4717.95898438, 3328.42699219, 152.74946289), 'rotation':(-0.853882, 179.889145, -0.879608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4706.70800781, 3328.45117188, 152.58176758), 'rotation':(-0.85379, 179.890701, -0.879517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4695.45703125, 3328.47558594, 152.41404297), 'rotation':(-0.853241, 179.888733, -0.878937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4689.83105469, 3328.48753906, 152.33018555), 'rotation':(-0.853241, 179.888733, -0.878937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4684.20556641, 3328.4997656200003, 152.24638672), 'rotation':(-0.852631, 179.888748, -0.878296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4678.58300781, 3328.47875, 152.16267578), 'rotation':(-0.852692, 179.89061, -0.878357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4672.91943359, 3336.98753906, 152.0780957), 'rotation':(0.852626, -0.109375, 0.827525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4678.54443359, 3336.92652344, 152.16183594), 'rotation':(0.852626, -0.109375, 0.827525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4689.79443359, 3336.86867188, 152.329375), 'rotation':(0.853883, -0.11084, 0.828712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4706.67138672, 3336.83226562, 152.58094727), 'rotation':(0.853876, -0.109283, 0.828711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4712.296875, 3336.8200781200003, 152.66481445), 'rotation':(0.853876, -0.109283, 0.828711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4717.92236328, 3336.808125, 152.74865234), 'rotation':(0.853883, -0.11084, 0.828712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4757.30078125, 3336.72339844, 153.32788086), 'rotation':(0.832832, -0.111115, 0.808869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4762.92626953, 3336.7111718799997, 153.4096875), 'rotation':(0.829779, -0.112305, 0.806006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4768.55175781, 3336.69898438, 153.49123047), 'rotation':(0.823871, -0.109894, 0.800432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4779.80273438, 3336.67699219, 153.65250977), 'rotation':(0.811734, -0.112823, 0.788977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4785.42773438, 3336.66648438, 153.73222656), 'rotation':(0.805846, -0.110382, 0.783413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4791.05371094, 3336.6560156200003, 153.81130859), 'rotation':(0.799699, -0.113159, 0.777607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4802.3046875, 3336.63550781, 153.96765625), 'rotation':(0.787726, -0.113464, 0.766288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4807.93017578, 3336.59984375, 154.04494140999998), 'rotation':(0.784693, -0.112915, 0.763407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4813.55615234, 3336.5759375, 154.12201172), 'rotation':(0.784693, -0.112915, 0.763407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4824.80761719, 3336.5446875, 154.27560547), 'rotation':(0.764674, -0.112976, 0.744469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4830.43261719, 3336.53273438, 154.35129883), 'rotation':(0.764674, -0.112976, 0.744469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4836.05810547, 3336.52050781, 154.42607422), 'rotation':(0.751143, -0.113342, 0.731646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4841.68408203, 3336.50855469, 154.49988281), 'rotation':(0.737913, -0.113678, 0.719096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4847.30908203, 3336.49632812, 154.57238281), 'rotation':(0.73111, -0.114136, 0.712631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4852.93505859, 3336.484375, 154.64444336), 'rotation':(0.731165, -0.114136, 0.712667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4858.56103516, 3336.4721875, 154.71623047), 'rotation':(0.731165, -0.114136, 0.712667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4875.43798828, 3336.43578125, 154.92890625), 'rotation':(0.706344, -0.114441, 0.689089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4881.06445312, 3336.42382812, 154.99785156), 'rotation':(0.696481, -0.114685, 0.679702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4892.31640625, 3336.39964844, 155.13259766), 'rotation':(0.666879, -0.115387, 0.651486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4920.44580078, 3336.33910156, 155.45416016), 'rotation':(0.626424, -0.114838, 0.612831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4926.07177734, 3336.32691406, 155.51611328), 'rotation':(0.616452, -0.117767, 0.60329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4931.69775391, 3336.31492188, 155.57698242), 'rotation':(0.606138, -0.117981, 0.593419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4937.32470703, 3336.30273438, 155.63676758), 'rotation':(0.596016, -0.115479, 0.583701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4942.95019531, 3336.29027344, 155.69547852), 'rotation':(0.585921, -0.118408, 0.574036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4948.57617188, 3336.27832031, 155.7530957), 'rotation':(0.575566, -0.115906, 0.564089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5179.08789062, 3327.43433594, 157.28860352), 'rotation':(-0.196594, 179.877548, -0.197937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5156.43115234, 3327.48339844, 157.20607422), 'rotation':(-0.227722, 179.879059, -0.229523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5145.10009766, 3327.50757812, 157.16104492), 'rotation':(-0.23642, 179.876373, -0.238373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5133.77197266, 3327.53199219, 157.11392578000002), 'rotation':(-0.253754, 179.878876, -0.255981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5116.77929688, 3327.56859375, 157.031875), 'rotation':(-0.297394, 179.877243, -0.300537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5111.11376953, 3327.58082031, 157.0024707), 'rotation':(-0.297272, 179.879349, -0.300385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5099.78466797, 3327.60498047, 156.94311523), 'rotation':(-0.31543, 179.878311, -0.318939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5094.11962891, 3327.6171875, 156.91197266), 'rotation':(-0.327362, 179.878433, -0.331116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5082.79052734, 3327.64183594, 156.84610351999999), 'rotation':(-0.351379, 179.878738, -0.355713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5077.12841797, 3327.6540625, 156.81141602), 'rotation':(-0.363556, 179.878891, -0.368225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5071.46337891, 3327.66625, 156.77550781), 'rotation':(-0.37561, 179.879044, -0.380554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5043.14160156, 3327.72703125, 156.58194336), 'rotation':(-0.426605, 179.880692, -0.432983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5031.81201172, 3327.75148438, 156.49833984), 'rotation':(-0.448669, 179.879578, -0.455719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5026.15039062, 3327.76367188, 156.45408203), 'rotation':(-0.470612, 179.881378, -0.478394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4997.83105469, 3327.77757812, 156.21975586), 'rotation':(-0.50174, 179.879868, -0.510559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4992.16748047, 3327.72804688, 156.17054688), 'rotation':(-0.514954, 179.882446, -0.524261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5190.43554688, 3335.79054688, 157.32248047), 'rotation':(0.155086, -0.122711, 0.15426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5179.10546875, 3335.8146875, 157.28860352), 'rotation':(0.175884, -0.122589, 0.174808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5167.77783203, 3335.83910156, 157.24957031), 'rotation':(0.196586, -0.122467, 0.195243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5162.11230469, 3335.8513281200003, 157.22808594), 'rotation':(0.217282, -0.122314, 0.215651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5150.78320312, 3335.87574219, 157.18354492), 'rotation':(0.227698, -0.122589, 0.2259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5145.11767578, 3335.88792969, 157.16102539), 'rotation':(0.227718, -0.122589, 0.225909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5133.78955078, 3335.91234375, 157.11390625), 'rotation':(0.2364, -0.121277, 0.234461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5116.79638672, 3335.94898438, 157.031875), 'rotation':(0.288555, -0.123138, 0.285667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5111.13085938, 3335.9611718799997, 157.0024707), 'rotation':(0.297427, -0.120636, 0.294341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5099.80175781, 3335.98535156, 156.9430957), 'rotation':(0.30326, -0.121826, 0.300072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5082.80761719, 3336.02195312, 156.84610351999999), 'rotation':(0.339508, -0.121399, 0.335498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5077.14550781, 3336.03441406, 156.81141602), 'rotation':(0.351386, -0.121246, 0.34709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5065.81591797, 3336.05882812, 156.73839844), 'rotation':(0.375599, -0.120941, 0.370695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5037.49462891, 3336.11960938, 156.54050781), 'rotation':(0.404641, -0.121063, 0.398964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5020.50292969, 3336.15625, 156.40915039), 'rotation':(0.448627, -0.120422, 0.441649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4997.84814453, 3336.25195312, 156.21974609), 'rotation':(0.488358, -0.118011, 0.480089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4992.18505859, 3336.3259375, 156.17054688), 'rotation':(0.501712, -0.120148, 0.492985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4986.51855469, 3336.3591406200003, 156.12005859), 'rotation':(0.514921, -0.117554, 0.50574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5399.879375, 3326.95921875, 157.45195311999998), 'rotation':(0.070344, 179.876755, 0.070167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5383.30273438, 3326.99488281, 157.47030273000001), 'rotation':(0.047306, 179.876694, 0.04723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5322.52392578, 3327.12574219, 157.49899414), 'rotation':(-0.015167, 179.876144, -0.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5289.37060547, 3327.19703125, 157.48991211), 'rotation':(-0.028717, 179.876923, -0.028748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5283.84472656, 3327.20898438, 157.48741211), 'rotation':(-0.037445, 179.876923, -0.037506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5278.31933594, 3327.22070312, 157.48399414), 'rotation':(-0.046478, 179.876953, -0.04657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5272.79443359, 3327.23265625, 157.4796582), 'rotation':(-0.055237, 179.876953, -0.055328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5267.27001953, 3327.244375, 157.47439453), 'rotation':(-0.06427, 179.876984, -0.064423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5256.21923828, 3327.26832031, 157.46099609), 'rotation':(-0.082031, 179.877029, -0.082306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5245.16894531, 3327.29199219, 157.44466796999998), 'rotation':(-0.092651, 179.875778, -0.092957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5239.64697266, 3327.21582031, 157.43581055), 'rotation':(-0.105377, 179.877792, -0.105743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5394.3715625, 3335.3513281200003, 157.45874023), 'rotation':(-0.070343, -0.121826, -0.070526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5383.32078125, 3335.375, 157.47030273000001), 'rotation':(-0.058899, -0.12326, -0.059021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5372.26953125, 3335.39890625, 157.47919922), 'rotation':(-0.047302, -0.123291, -0.047394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5361.21972656, 3335.42261719, 157.48586914), 'rotation':(-0.035889, -0.123291, -0.035919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5355.69382812, 3335.43457031, 157.48878906), 'rotation':(-0.03009, -0.124084, -0.030121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5350.16796875, 3335.44652344, 157.49167969), 'rotation':(-0.03009, -0.124084, -0.030121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5339.11671875, 3335.47023438, 157.49748047), 'rotation':(-0.029968, -0.124084, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5333.59179688, 3335.4821875, 157.49961914), 'rotation':(-0.01886, -0.122162, -0.01886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5328.06640625, 3335.49414062, 157.50001953), 'rotation':(0.004043, -0.124542, 0.004041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5305.96484375, 3335.54148438, 157.49458008), 'rotation':(0.015259, -0.12384, 0.015262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5300.43896484, 3335.55347656, 157.49311523), 'rotation':(0.015265, -0.12384, 0.015266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5294.91357422, 3335.56519531, 157.49164062), 'rotation':(0.015272, -0.122162, 0.015261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5289.38867188, 3335.57714844, 157.48991211), 'rotation':(0.019657, -0.123077, 0.019641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5278.33740234, 3335.60109375, 157.48399414), 'rotation':(0.037429, -0.123047, 0.037383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5267.28808594, 3335.6247656200003, 157.47439453), 'rotation':(0.055208, -0.123016, 0.055104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5261.76318359, 3335.63671875, 157.46817382999998), 'rotation':(0.064286, -0.123016, 0.064129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5250.71240234, 3335.66039062, 157.45300781), 'rotation':(0.082037, -0.122955, 0.081812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5245.18701172, 3335.67234375, 157.44466796999998), 'rotation':(0.086491, -0.122589, 0.08623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5834.55273438, 3326.02441406, 157.07856445), 'rotation':(-0.164246, 179.875671, -0.165192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5817.54640625, 3326.06103516, 157.03303711), 'rotation':(-0.122284, 179.876999, -0.122803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.20898438, 3326.08496094, 157.00911133), 'rotation':(-0.111725, 179.877548, -0.112152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5800.54101562, 3326.09716797, 156.99806640999998), 'rotation':(-0.100891, 179.876785, -0.101227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5789.203125, 3326.12158203, 156.97827148), 'rotation':(-0.079132, 179.876724, -0.079346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5777.86421875, 3326.14599609, 156.96365234), 'rotation':(-0.057281, 179.876663, -0.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5772.19625, 3326.15820312, 156.95797851999998), 'rotation':(-0.035614, 179.876633, -0.035645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5766.5278125, 3326.17041016, 156.95404297), 'rotation':(-0.035614, 179.876633, -0.035645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5760.85890625, 3326.18261719, 156.9506543), 'rotation':(-0.024597, 179.877686, -0.024628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5749.52296875, 3326.20703125, 156.94575195), 'rotation':(-0.024719, 179.876007, -0.02475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5743.855, 3326.21923828, 156.94331055), 'rotation':(-0.024719, 179.877701, -0.024719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5726.84914062, 3326.255625, 156.93661133), 'rotation':(0.002677, 179.876572, 0.002679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5721.17921875, 3326.2678125, 156.93755859), 'rotation':(0.030053, 179.877274, 0.030028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5715.51125, 3326.28003906, 156.94050780999999), 'rotation':(0.029957, 179.87561, 0.029927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5687.16992188, 3326.34105469, 156.95556641), 'rotation':(0.036931, 179.875824, 0.03689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5681.50195312, 3326.35328125, 156.95922852), 'rotation':(0.050858, 179.877335, 0.050781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.83351562, 3326.36546875, 156.96375977), 'rotation':(0.050858, 179.877335, 0.050781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5670.16554688, 3326.37769531, 156.96879883), 'rotation':(0.064709, 179.877365, 0.064565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5641.82375, 3326.43847656, 157.0065625), 'rotation':(0.088123, 179.876266, 0.087861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5630.48730469, 3326.46289062, 157.02415039), 'rotation':(0.093642, 179.876297, 0.093351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5619.15085938, 3326.48730469, 157.04319336), 'rotation':(0.104379, 179.876328, 0.104002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5596.47851562, 3326.53613281, 157.08493164), 'rotation':(0.107978, 179.876114, 0.107576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5585.14210938, 3326.56054688, 157.10661133), 'rotation':(0.111489, 179.878479, 0.11106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5573.80617188, 3326.58496094, 157.12899414), 'rotation':(0.11515, 179.876129, 0.114693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5568.13820312, 3326.59691406, 157.14042969), 'rotation':(0.116899, 179.878494, 0.116424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5562.47070312, 3326.60914062, 157.15202148), 'rotation':(0.118811, 179.876144, 0.118324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5551.13429688, 3326.63355469, 157.17572266), 'rotation':(0.121475, 179.875809, 0.120965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5545.46632812, 3326.64574219, 157.18774414), 'rotation':(0.120847, 179.877441, 0.120346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5534.13039062, 3326.67015625, 157.21162109), 'rotation':(0.119877, 179.87587, 0.119385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5522.79492188, 3326.69433594, 157.23526367), 'rotation':(0.118811, 179.877441, 0.118323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5511.45898438, 3326.71875, 157.25867188), 'rotation':(0.117404, 179.87677, 0.116919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5477.45214844, 3326.79222656, 157.32688477), 'rotation':(0.107282, 179.87616, 0.106874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5460.44824219, 3326.82886719, 157.358125), 'rotation':(0.101312, 179.876694, 0.100963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5454.78027344, 3326.84105469, 157.36818359), 'rotation':(0.101312, 179.876694, 0.100963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5439.78757812, 3326.74365234, 157.39416015999998), 'rotation':(0.092201, 179.877075, 0.0919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5439.80617188, 3335.3830468799997, 157.39416015999998), 'rotation':(-0.098267, -0.122894, -0.098602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5449.13085938, 3335.23804688, 157.37817383), 'rotation':(-0.101318, -0.123291, -0.101685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5454.79734375, 3335.22144531, 157.36818359), 'rotation':(-0.101318, -0.123291, -0.101685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5460.46484375, 3335.20921875, 157.35813477), 'rotation':(-0.103363, -0.12384, -0.103729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5466.1328125, 3335.19703125, 157.34791992), 'rotation':(-0.107269, -0.122284, -0.107697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5494.4721875, 3335.13574219, 157.2934082), 'rotation':(-0.117249, -0.12323, -0.117737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5500.13964844, 3335.12351562, 157.281875), 'rotation':(-0.117401, -0.12323, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5539.81542969, 3335.03832031, 157.19970703), 'rotation':(-0.12085, -0.122559, -0.121368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5551.15136719, 3335.01367188, 157.17573242), 'rotation':(-0.120544, -0.12149, -0.121063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5562.48730469, 3334.98925781, 157.15202148), 'rotation':(-0.116913, -0.12384, -0.117371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5568.15527344, 3334.97753906, 157.14042969), 'rotation':(-0.115143, -0.121521, -0.115601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5573.82324219, 3334.9653125, 157.12899414), 'rotation':(-0.113403, -0.12384, -0.113831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5579.49121094, 3334.953125, 157.11772461), 'rotation':(-0.111481, -0.123871, -0.111908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5585.15917969, 3334.9409375, 157.10663086), 'rotation':(-0.109741, -0.121521, -0.110138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5590.82765625, 3334.92871094, 157.09568359000002), 'rotation':(-0.107971, -0.123871, -0.108398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5602.16359375, 3334.90429688, 157.07427734), 'rotation':(-0.107056, -0.122772, -0.107452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5630.504375, 3334.84328125, 157.02415039), 'rotation':(-0.088135, -0.123718, -0.088379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5653.17820312, 3334.7946875, 156.98983398000001), 'rotation':(-0.078552, -0.124084, -0.078766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5658.84617188, 3334.78246094, 156.98207031), 'rotation':(-0.064728, -0.12262, -0.06485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.85109375, 3334.74585938, 156.96375977), 'rotation':(-0.036926, -0.122681, -0.036987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5687.1875, 3334.72144531, 156.95556641), 'rotation':(-0.029968, -0.122711, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5715.52882812, 3334.66039062, 156.94050780999999), 'rotation':(-0.03006, -0.122711, -0.03009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5721.19679688, 3334.6482031200003, 156.93755859), 'rotation':(-0.002686, -0.123413, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5732.53710938, 3334.62378906, 156.93842773), 'rotation':(0.024712, -0.122314, 0.024698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5738.20507812, 3334.6115625, 156.94086914), 'rotation':(0.024712, -0.122314, 0.024698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.54101562, 3334.58714844, 156.94575195), 'rotation':(0.024602, -0.123993, 0.024586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5766.54640625, 3334.55054688, 156.95404297), 'rotation':(0.057278, -0.123322, 0.057162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5789.22171875, 3334.50195312, 156.97827148), 'rotation':(0.100875, -0.123199, 0.100532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5800.55953125, 3334.47753906, 156.99806640999998), 'rotation':(0.111721, -0.124084, 0.111294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.2275, 3334.46558594, 157.00911133), 'rotation':(0.122295, -0.122986, 0.121761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5811.89648438, 3334.4533593799997, 157.02083984), 'rotation':(0.122295, -0.122986, 0.121761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5817.56546875, 3334.44117188, 157.03304688), 'rotation':(0.143181, -0.122894, 0.142466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5823.2334375, 3334.42894531, 157.04720703), 'rotation':(0.164259, -0.122772, 0.163321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5828.90382812, 3334.41675781, 157.06231445), 'rotation':(0.164259, -0.122772, 0.163321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5834.57179688, 3334.40453125, 157.07856445), 'rotation':(0.185146, -0.12265, 0.183967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5991.84617188, 3325.68603516, 157.96142578), 'rotation':(-0.483887, 179.881516, -0.492096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.47414062, 3325.71070312, 157.86694336), 'rotation':(-0.459198, 179.878387, -0.466614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.10203125, 3325.73511719, 157.77783203), 'rotation':(-0.43454, 179.880722, -0.441162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5963.41648438, 3325.74730469, 157.73529297), 'rotation':(-0.409851, 179.87764, -0.415741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5957.7309375, 3325.75953125, 157.69411133), 'rotation':(-0.39743, 179.880188, -0.402954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.67335938, 3325.79613281, 157.5769043), 'rotation':(-0.372131, 179.879395, -0.377014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5934.9878125, 3325.80835938, 157.53974609), 'rotation':(-0.359436, 179.879242, -0.363983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.61421875, 3325.83251953, 157.46958984), 'rotation':(-0.333893, 179.876266, -0.337799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5917.92875, 3325.84472656, 157.43663086), 'rotation':(-0.321198, 179.878784, -0.324799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5906.55765625, 3325.869375, 157.37480469), 'rotation':(-0.295776, 179.87851, -0.298859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5889.50195312, 3325.87671875, 157.28860352), 'rotation':(-0.281738, 179.878723, -0.284515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5883.81640625, 3325.82300781, 157.26131836000002), 'rotation':(-0.266724, 179.878586, -0.269226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.8515625, 3334.06664062, 157.96131836), 'rotation':(0.489847, -0.119354, 0.481533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5986.16554688, 3334.07886719, 157.9134082), 'rotation':(0.483878, -0.118469, 0.47575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.79640625, 3334.10328125, 157.82164062), 'rotation':(0.459146, -0.118866, 0.451837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.10984375, 3334.11546875, 157.77775391), 'rotation':(0.446606, -0.121796, 0.439685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.68453125, 3334.17652344, 157.57685547), 'rotation':(0.384874, -0.120422, 0.379734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5929.31398438, 3334.2009375, 157.50392578), 'rotation':(0.359446, -0.120758, 0.354965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5900.88625, 3334.26195312, 157.34567383), 'rotation':(0.295788, -0.12149, 0.292747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5895.20117188, 3334.27417969, 157.31695312), 'rotation':(0.289368, -0.120728, 0.286459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5883.83398438, 3334.3940625, 157.26131836000002), 'rotation':(0.281738, -0.123779, 0.278977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.63085938, 3778.90453125, 157.49297852), 'rotation':(-0.115723, -90.457825, -0.11618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.54199219, 3767.81203125, 157.47056641), 'rotation':(-0.127899, -90.460632, -0.128448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.49755859, 3762.26734375, 157.45898438), 'rotation':(-0.127899, -90.460632, -0.128448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.453125, 3756.72195312, 157.44648438000002), 'rotation':(-0.1521, -90.456543, -0.152924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4783.40869141, 3751.17601562, 157.43174805), 'rotation':(-0.176453, -90.460388, -0.177521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.31982422, 3740.0871875000003, 157.39688476999999), 'rotation':(-0.200653, -90.456238, -0.202057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.23095703, 3728.9965625, 157.3565625), 'rotation':(-0.212769, -90.458984, -0.214355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4783.14208984, 3717.90625, 157.3147168), 'rotation':(-0.232544, -90.456757, -0.234436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4783.09765625, 3712.36109375, 157.29205078), 'rotation':(-0.246033, -90.462067, -0.248138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.05322266, 3706.8151562499997, 157.26804688), 'rotation':(-0.259308, -90.456543, -0.261658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4782.91992188, 3690.180625, 157.18783203), 'rotation':(-0.299011, -90.456177, -0.302155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4782.87548828, 3684.6354687499997, 157.15838867), 'rotation':(-0.312134, -90.461395, -0.315552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.56445312, 3645.8203125, 156.92662109), 'rotation':(-0.39447, -90.454773, -0.399902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.47558594, 3634.73, 156.84983398), 'rotation':(-0.405243, -90.456909, -0.41098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.20898438, 3601.46167969, 156.59976562), 'rotation':(-0.496033, -90.45285, -0.504669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.12011719, 3590.37109375, 156.50545898000001), 'rotation':(-0.508881, -90.457336, -0.518005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4773.56982422, 3583.17847656, 156.44142578), 'rotation':(0.508911, 89.542625, 0.499937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4773.74023438, 3590.4997656200003, 156.50599609), 'rotation':(0.496015, 89.547127, 0.487493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4773.78466797, 3596.04371094, 156.55400391), 'rotation':(0.470074, 89.543694, 0.462413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4774.00634766, 3623.7578125, 156.77128906), 'rotation':(0.405187, 89.543114, 0.399498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.18408203, 3645.93066406, 156.92691406), 'rotation':(0.37284, 89.54187, 0.368015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.22851562, 3651.47386719, 156.96311523), 'rotation':(0.351188, 89.544662, 0.34691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.31738281, 3662.55953125, 157.03257812), 'rotation':(0.329659, 89.54438, 0.325893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.36181641, 3668.1025, 157.06526367), 'rotation':(0.329659, 89.54438, 0.325893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.40625, 3673.64671875, 157.09714844), 'rotation':(0.318847, 89.542091, 0.315315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.62841797, 3701.3628125, 157.24279296999998), 'rotation':(0.259315, 89.543442, 0.256977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.67285156, 3706.90476562, 157.26814453), 'rotation':(0.246017, 89.537949, 0.243903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.80615234, 3723.53492188, 157.33601562), 'rotation':(0.212747, 89.541016, 0.211171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4774.89501953, 3734.6228125, 157.3772168), 'rotation':(0.20065, 89.543747, 0.199253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.07275391, 3756.79492188, 157.44650391), 'rotation':(0.127895, 89.539352, 0.12732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.16162109, 3767.8815624999997, 157.47056641), 'rotation':(0.115717, 89.542198, 0.115246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.20605469, 3773.42578125, 157.48177734), 'rotation':(0.115717, 89.542198, 0.11525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.25048828, 3778.9696875, 157.49296875), 'rotation':(0.107883, 89.539871, 0.107482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.97998047, 3822.4973437500003, 157.52165039), 'rotation':(0.001571, -90.458954, 0.001584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.06933594, 3833.5946875, 157.52134766), 'rotation':(0.001489, -90.458984, 0.001494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.11376953, 3839.14359375, 157.52119141), 'rotation':(0.001489, -90.458984, 0.001494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.15820312, 3844.6896875, 157.52101562), 'rotation':(0.001489, -90.458954, 0.001491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.20214844, 3850.23734375, 157.51925781), 'rotation':(0.015252, -90.460602, 0.015239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.33544922, 3866.879375, 157.49728516), 'rotation':(0.09733, -90.460419, 0.096993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4784.42431641, 3877.97679688, 157.47580078000001), 'rotation':(0.110854, -90.458984, 0.110424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.51318359, 3889.07273438, 157.45188477), 'rotation':(0.130525, -90.454956, 0.129928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.60205078, 3900.16945312, 157.42300781), 'rotation':(0.156794, -90.459747, 0.155941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4784.64648438, 3905.71578125, 157.40670898), 'rotation':(0.169942, -90.454742, 0.168933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.69091797, 3911.26414062, 157.38916016), 'rotation':(0.183083, -90.459625, 0.181926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.86914062, 3933.45507812, 157.30772461), 'rotation':(0.226025, -90.460205, 0.224252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.95800781, 3944.55171875, 157.26145508), 'rotation':(0.246399, -90.45697, 0.244279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4785.09179688, 3961.19460938, 157.1827832), 'rotation':(0.286929, -90.456604, 0.28407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.51074219, 3811.4665625, 157.52194336), 'rotation':(-0.001495, 89.541046, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.59960938, 3822.56421875, 157.52165039), 'rotation':(-0.001495, 89.541046, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.64453125, 3828.1128125, 157.52150390999998), 'rotation':(-0.001495, 89.541046, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.68896484, 3833.66164062, 157.52134766), 'rotation':(-0.001495, 89.541023, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.82177734, 3850.30445312, 157.51925781), 'rotation':(-0.042511, 89.544907, -0.042572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.95507812, 3866.94625, 157.49728516), 'rotation':(-0.11087, 89.540977, -0.111298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4776.04394531, 3878.0442187500003, 157.47580078000001), 'rotation':(-0.117523, 89.544991, -0.118011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.08837891, 3883.59179688, 157.46444336000002), 'rotation':(-0.130524, 89.540085, -0.131104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.1328125, 3889.14015625, 157.45188477), 'rotation':(-0.143799, 89.540161, -0.144531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.17724609, 3894.68796875, 157.43807617000002), 'rotation':(-0.156799, 89.540207, -0.157654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.35498047, 3916.87914062, 157.37036133), 'rotation':(-0.209381, 89.540573, -0.210907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.39941406, 3922.42726562, 157.3503125), 'rotation':(-0.216034, 89.545151, -0.217682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.44433594, 3927.97484375, 157.32953125), 'rotation':(-0.226044, 89.542839, -0.227814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.57763672, 3944.61890625, 157.26145508), 'rotation':(-0.266571, 89.543205, -0.269073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.66650391, 3955.7135937499997, 157.21055664), 'rotation':(-0.286926, 89.543396, -0.289825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4961.55029297, 3095.22729492, 152.47675781), 'rotation':(0.794003, 89.531105, 0.772225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4962.10644531, 3158.17407227, 153.37109375), 'rotation':(0.832853, 89.529823, 0.808899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.24902344, 3175.18480469, 153.61929688), 'rotation':(0.839703, 89.535385, 0.815362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.29638672, 3180.85449219, 153.70248046999998), 'rotation':(0.841848, 89.530121, 0.817368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4962.34375, 3186.52441406, 153.78594727), 'rotation':(0.845407, 89.531532, 0.82073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.58105469, 3214.875, 154.20448242), 'rotation':(0.849853, 89.533775, 0.824907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.81787109, 3243.22509766, 154.626875), 'rotation':(0.854245, 89.530243, 0.82906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4962.90332031, 3254.56542969, 154.79600586), 'rotation':(0.853118, 89.535767, 0.82798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.98046875, 3260.23511719, 154.88050781), 'rotation':(0.853118, 89.535767, 0.82798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4963.04101562, 3265.90453125, 154.96492188), 'rotation':(0.851089, 89.53186, 0.826073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.08837891, 3271.57470703, 155.04916015999999), 'rotation':(0.849997, 89.534637, 0.82506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.18359375, 3282.91455078, 155.2174707), 'rotation':(0.850024, 89.531403, 0.825084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.23095703, 3288.58472656, 155.30162109), 'rotation':(0.849921, 89.534622, 0.824985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.27832031, 3294.25439453, 155.38576172), 'rotation':(0.849997, 89.531403, 0.825065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.67333984, 3299.89183594, 155.47043945), 'rotation':(-0.849915, -90.465363, -0.875397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.57861328, 3288.55175781, 155.3021582), 'rotation':(-0.850037, -90.468628, -0.875519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.53076172, 3282.88160156, 155.21799805), 'rotation':(-0.850037, -90.465363, -0.875549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.48339844, 3277.21167969, 155.13386719), 'rotation':(-0.850037, -90.465363, -0.875549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4971.38867188, 3265.87158203, 154.96546875), 'rotation':(-0.853119, -90.464233, -0.878815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4971.34130859, 3260.20214844, 154.88107422), 'rotation':(-0.854279, -90.466736, -0.880035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.29394531, 3254.53246094, 154.79655273), 'rotation':(-0.854279, -90.466736, -0.880035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4971.00927734, 3220.51246094, 154.28917969), 'rotation':(-0.849823, -90.466217, -0.875336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.96191406, 3214.8415625, 154.2050293), 'rotation':(-0.845276, -90.463715, -0.870514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.86669922, 3203.50171875, 154.03749023), 'rotation':(-0.845276, -90.468475, -0.870514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.81933594, 3197.83179688, 153.95380859), 'rotation':(-0.845276, -90.468475, -0.870514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.77197266, 3192.161875, 153.87013672), 'rotation':(-0.845428, -90.468475, -0.870636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.53466797, 3163.81030273, 153.45410156), 'rotation':(-0.832825, -90.470154, -0.8573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.43945312, 3152.47021484, 153.28936523000002), 'rotation':(-0.828339, -90.470306, -0.85257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.29736328, 3135.45800781, 153.0440332), 'rotation':(-0.820618, -90.46817, -0.84436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.25, 3129.78759766, 152.96293945), 'rotation':(-0.816162, -90.468292, -0.839661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.15478516, 3118.44726562, 152.80202148), 'rotation':(-0.807251, -90.468536, -0.830231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.10742188, 3112.77685547, 152.7221875), 'rotation':(-0.802917, -90.468628, -0.825653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.06005859, 3107.10644531, 152.64277344), 'rotation':(-0.798645, -90.46875, -0.821136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.01269531, 3101.4362793, 152.5637793), 'rotation':(-0.794037, -90.468903, -0.816284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4969.97900391, 3095.77172852, 152.48526367), 'rotation':(-0.79187, -90.470642, -0.813995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4972.0859375, 3349.17015625, 156.19275391), 'rotation':(-0.831482, -90.467987, -0.855896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.18115234, 3360.53785156, 156.35673828), 'rotation':(-0.824219, -90.465332, -0.848206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4972.27636719, 3371.9064843799997, 156.51912109), 'rotation':(-0.816956, -90.468384, -0.840485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4972.51416016, 3400.32542969, 156.91775391), 'rotation':(-0.796753, -90.468567, -0.819153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.56152344, 3406.00929688, 156.99592773), 'rotation':(-0.790619, -90.46875, -0.812683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.70410156, 3423.06054688, 157.22682617), 'rotation':(-0.771881, -90.469238, -0.792908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.75146484, 3428.74460938, 157.30261719), 'rotation':(-0.765747, -90.469421, -0.786438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.84667969, 3440.1128125, 157.45291016), 'rotation':(-0.756348, -90.468872, -0.77655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.89404297, 3445.7966406200003, 157.52786133), 'rotation':(-0.756348, -90.468872, -0.77655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.03710938, 3462.84839844, 157.74763672), 'rotation':(-0.725586, -90.473724, -0.744141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4973.08447266, 3468.53246094, 157.81871094), 'rotation':(-0.713318, -90.469727, -0.731262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.18017578, 3479.90015625, 157.95916992), 'rotation':(-0.707153, -90.470032, -0.724762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.22753906, 3485.58421875, 158.02875), 'rotation':(-0.70166, -90.472839, -0.718994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4973.27539062, 3491.26832031, 158.09730469), 'rotation':(-0.690887, -90.468964, -0.707733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.32324219, 3496.95265625, 158.16495117), 'rotation':(-0.680145, -90.473389, -0.696442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.37060547, 3502.63625, 158.23170898), 'rotation':(-0.66925, -90.469482, -0.685028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.41845703, 3508.3203125, 158.29760742), 'rotation':(-0.66925, -90.469482, -0.685028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.46582031, 3514.00464844, 158.36262695), 'rotation':(-0.658478, -90.473877, -0.673767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.56103516, 3525.37328125, 158.48999023), 'rotation':(-0.636871, -90.474365, -0.651154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.61083984, 3531.05710938, 158.5521875), 'rotation':(-0.626099, -90.470459, -0.639893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.75927734, 3548.11011719, 158.73478516), 'rotation':(-0.611694, -90.473022, -0.624847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.03857422, 3389.02417969, 156.75955078), 'rotation':(0.803039, 89.531601, 0.780765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.18115234, 3406.0759375, 156.99587891), 'rotation':(0.784338, 89.531075, 0.763072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.22900391, 3411.75929688, 157.0734375), 'rotation':(0.778034, 89.530907, 0.757115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.32373047, 3423.1271875, 157.22677734), 'rotation':(0.765746, 89.530571, 0.745493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.37109375, 3428.81128906, 157.30256836), 'rotation':(0.759305, 89.530403, 0.739384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.51367188, 3445.86328125, 157.5278125), 'rotation':(0.750119, 89.531174, 0.73067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.60888672, 3457.23144531, 157.67545898), 'rotation':(0.725578, 89.526253, 0.707378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.70410156, 3468.59914062, 157.81868164), 'rotation':(0.707116, 89.529976, 0.689824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.75195312, 3474.28320312, 157.88910156), 'rotation':(0.707116, 89.529976, 0.689824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.94287109, 3497.02, 158.16492188), 'rotation':(0.669283, 89.530487, 0.653778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.17089844, 3525.4409375, 158.48996094), 'rotation':(0.626076, 89.529533, 0.612518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.29736328, 3536.8090625, 158.61388671999998), 'rotation':(0.611684, 89.526962, 0.598732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.92822266, 3614.7621875, 159.35677734), 'rotation':(0.460457, 89.523224, 0.453104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.97558594, 3620.45238281, 159.40255859), 'rotation':(0.447473, 89.52301, 0.440522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.11865234, 3637.52027344, 159.53404297), 'rotation':(0.429373, 89.524811, 0.422974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.35693359, 3665.96898438, 159.72856445), 'rotation':(0.348476, 89.522728, 0.344248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.45214844, 3677.34835938, 159.79782226999998), 'rotation':(0.333757, 89.521423, 0.329893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.59521484, 3694.41773438, 159.89396484), 'rotation':(0.2751, 89.520805, 0.272471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.64257812, 3700.10523438, 159.92295898), 'rotation':(0.2751, 89.520805, 0.272471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.69042969, 3705.7959375, 159.95027344), 'rotation':(0.245791, 89.520523, 0.243681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4966.83349609, 3722.86570312, 160.02308594), 'rotation':(0.231168, 89.524422, 0.229312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.92919922, 3734.245625, 160.06835938), 'rotation':(0.218136, 89.521843, 0.216481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.9765625, 3739.9353125, 160.08941406), 'rotation':(0.192379, 89.517723, 0.19109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.64257812, 3774.00585938, 160.1784668), 'rotation':(-0.127747, -90.48114, -0.128296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.54785156, 3762.62476562, 160.1530957), 'rotation':(-0.140717, -90.478638, -0.141418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.45214844, 3751.245625, 160.12510742), 'rotation':(-0.166351, -90.478516, -0.167328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.40429688, 3745.5573437499997, 160.10853516), 'rotation':(-0.192383, -90.478333, -0.193665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.35693359, 3739.8671875, 160.08941406), 'rotation':(-0.21814, -90.482086, -0.219818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.30908203, 3734.1770312500003, 160.06835938), 'rotation':(-0.231171, -90.475555, -0.233032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.16601562, 3717.1084375, 160.0000293), 'rotation':(-0.245789, -90.479431, -0.247894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.11816406, 3711.4175, 159.97563477), 'rotation':(-0.275116, -90.476379, -0.277771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.02294922, 3700.03757812, 159.92295898), 'rotation':(-0.304443, -90.478912, -0.307678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.97558594, 3694.350625, 159.89398438), 'rotation':(-0.304443, -90.478912, -0.307678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.92773438, 3688.6596875, 159.86374023), 'rotation':(-0.333771, -90.478577, -0.337677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.83251953, 3677.28148438, 159.79785156), 'rotation':(-0.348328, -90.477264, -0.35257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.78515625, 3671.59132812, 159.76323242), 'rotation':(-0.34848, -90.477295, -0.352753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.68994141, 3660.21117188, 159.69282227), 'rotation':(-0.383087, -90.47583, -0.388214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.59423828, 3648.83421875, 159.61683594), 'rotation':(-0.406189, -90.479095, -0.411957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.49902344, 3637.45386719, 159.53407227), 'rotation':(-0.440796, -90.476074, -0.447632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.45166016, 3631.76515625, 159.49083008), 'rotation':(-0.440796, -90.476074, -0.447632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.40380859, 3626.07617188, 159.44705078), 'rotation':(-0.447449, -90.476959, -0.454498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.35644531, 3620.38648438, 159.40258789), 'rotation':(-0.460449, -90.476746, -0.467896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.30859375, 3614.69628906, 159.35681641), 'rotation':(-0.473755, -90.476562, -0.481659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.16601562, 3597.62964844, 159.2115918), 'rotation':(-0.513245, -90.475891, -0.522491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.02294922, 3580.56128906, 159.05457031), 'rotation':(-0.546112, -90.472778, -0.55661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.87695312, 3966.911875, 159.82166992), 'rotation':(-0.312134, 89.520859, -0.315552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.83105469, 3961.37890625, 159.85133789), 'rotation':(-0.306976, 89.5214, -0.310272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.78466797, 3955.84671875, 159.8799707), 'rotation':(-0.296082, 89.520935, -0.299164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4968.64550781, 3939.25070312, 159.95938476999999), 'rotation':(-0.2742, 89.523811, -0.276825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.55273438, 3928.1848437500003, 160.00587890999998), 'rotation':(-0.230499, 89.520348, -0.232361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.45996094, 3917.1198437499997, 160.04888671999998), 'rotation':(-0.219543, 89.522476, -0.221252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.41357422, 3911.58789062, 160.0690625), 'rotation':(-0.219543, 89.522476, -0.221252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.32080078, 3900.52273438, 160.10609375), 'rotation':(-0.179474, 89.519028, -0.180603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4968.27441406, 3894.9921875, 160.1225), 'rotation':(-0.179474, 89.519028, -0.180603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.08935547, 3872.86132812, 160.17353516), 'rotation':(-0.112732, 89.520767, -0.11319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4967.95019531, 3856.26320312, 160.20494141), 'rotation':(-0.098236, 89.516937, -0.098572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4967.85791016, 3845.2018749999997, 160.21495117), 'rotation':(-0.040619, 89.522346, -0.04068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4967.63476562, 3828.605, 160.21522461), 'rotation':(0.002561, 89.520264, 0.002558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4967.45361328, 3812.37429688, 160.21449219), 'rotation':(0.002657, 89.520248, 0.002656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.09277344, 3812.3020312500003, 160.21449219), 'rotation':(-0.002563, -90.476807, -0.002563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.16650391, 3821.1015625, 160.21489258), 'rotation':(-0.002655, -90.479736, -0.002655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.19238281, 3834.06710938, 160.21548828000002), 'rotation':(-0.002655, -90.479736, -0.002655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.20117188, 3839.600625, 160.21574219000001), 'rotation':(-0.002563, -90.479736, -0.002563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.23828125, 3845.1315624999997, 160.21495117), 'rotation':(0.011803, -90.483215, 0.011798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.28417969, 3850.66359375, 160.21148438), 'rotation':(0.040605, -90.477661, 0.040552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.46972656, 3872.79101562, 160.17353516), 'rotation':(0.11263, -90.479218, 0.112188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.51611328, 3878.32273438, 160.16254883), 'rotation':(0.112739, -90.479248, 0.11229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.56201172, 3883.85617188, 160.15037109000002), 'rotation':(0.125983, -90.478333, 0.125431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.70117188, 3900.45140625, 160.10609375), 'rotation':(0.152757, -90.47818, 0.151953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.79394531, 3911.51710938, 160.0690625), 'rotation':(0.206162, -90.477844, 0.204684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4977.02587891, 3939.17921875, 159.95938476999999), 'rotation':(0.252403, -90.479492, 0.250184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4977.11865234, 3950.24289062, 159.90790039), 'rotation':(0.274205, -90.479309, 0.27158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4977.16503906, 3955.77515625, 159.8799707), 'rotation':(0.274205, -90.479309, 0.27158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4977.21142578, 3961.306875, 159.85133789), 'rotation':(0.296089, -90.475952, 0.293033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4977.2578125, 3966.84007812, 159.82168945), 'rotation':(0.306962, -90.478638, 0.303687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5436.73976562, 3791.85914062, 159.38009766), 'rotation':(-0.381805, -0.55661, -0.386932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5447.14992188, 3791.75757812, 159.31103516), 'rotation':(-0.37619, -0.556671, -0.381165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5452.84765625, 3791.7018749999997, 159.27380859000002), 'rotation':(-0.370331, -0.556763, -0.375153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5458.54539062, 3791.64625, 159.23700195), 'rotation':(-0.364624, -0.558807, -0.369263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5464.24316406, 3791.59054688, 159.20073242), 'rotation':(-0.361755, -0.556213, -0.366364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5475.63769531, 3791.4792187499997, 159.12874023), 'rotation':(-0.361664, -0.558105, -0.366241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5492.73144531, 3791.31226562, 159.02250977), 'rotation':(-0.345337, -0.558258, -0.349518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5498.42871094, 3791.256875, 158.98816406), 'rotation':(-0.334534, -0.556946, -0.33844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5509.8246875, 3791.14546875, 158.92133789), 'rotation':(-0.323486, -0.558502, -0.327148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5515.52195312, 3791.08960938, 158.88916016), 'rotation':(-0.318176, -0.558502, -0.321747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5521.22070312, 3791.0339062499997, 158.85711914), 'rotation':(-0.318176, -0.558502, -0.321747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5526.91796875, 3790.97828125, 158.82548828), 'rotation':(-0.313873, -0.556305, -0.317322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5532.61621094, 3790.92257812, 158.79424805), 'rotation':(-0.306061, -0.55899, -0.309326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5549.71140625, 3790.75585938, 158.70568359), 'rotation':(-0.281647, -0.559296, -0.284393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5561.10742188, 3790.64429688, 158.6509375), 'rotation':(-0.26532, -0.559418, -0.267761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5572.5034375, 3790.53296875, 158.59944336), 'rotation':(-0.253143, -0.557892, -0.255402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5606.69238281, 3790.19921875, 158.46194336), 'rotation':(-0.19397, -0.561096, -0.195282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5612.390625, 3790.14359375, 158.44251953), 'rotation':(-0.184723, -0.55835, -0.185944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5618.08886719, 3790.08789062, 158.42412109), 'rotation':(-0.180267, -0.558319, -0.181396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5623.78664062, 3790.0321875, 158.40620117), 'rotation':(-0.168762, -0.560272, -0.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5629.48585938, 3789.9765625, 158.38897461), 'rotation':(-0.168762, -0.560272, -0.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5635.18359375, 3789.9209375, 158.3721875), 'rotation':(-0.145813, -0.558899, -0.146545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5646.58300781, 3789.80953125, 158.34376953), 'rotation':(-0.122833, -0.55899, -0.123383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5652.28078125, 3789.75414062, 158.33154297), 'rotation':(-0.099884, -0.559113, -0.10022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5657.97898438, 3789.69851562, 158.32078125), 'rotation':(-0.099884, -0.559113, -0.10022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5663.67625, 3789.6428125, 158.31084961), 'rotation':(-0.088379, -0.560669, -0.088684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5680.77046875, 3789.47585938, 158.28445312), 'rotation':(-0.076996, -0.559357, -0.077209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5686.4696875, 3789.42015625, 158.27655273), 'rotation':(-0.076996, -0.559357, -0.077209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5703.56546875, 3789.25320312, 158.25919922), 'rotation':(-0.042938, -0.559326, -0.042999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5732.05320312, 3788.97484375, 158.23788086000002), 'rotation':(-0.042938, -0.559326, -0.042999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5737.7509375, 3788.9192187500003, 158.23362305), 'rotation':(-0.010437, -0.558777, -0.010437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.1528125, 3788.80789062, 158.23332031), 'rotation':(0.054259, -0.560913, 0.054154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5760.55953125, 3788.69679688, 158.25483398), 'rotation':(0.183916, -0.558136, 0.182742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5771.95703125, 3788.6667187499997, 158.29521484), 'rotation':(0.216244, -0.558899, 0.214627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5779.27492188, 3780.00367188, 158.3231543), 'rotation':(-0.216278, 179.441055, -0.217926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5771.8715625, 3780.12429688, 158.29521484), 'rotation':(-0.216125, 179.441055, -0.217743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5760.475625, 3780.31664062, 158.25483398), 'rotation':(-0.11911, 179.441498, -0.119598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.07078125, 3780.42773438, 158.23332031), 'rotation':(0.01043, 179.439011, 0.010428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5737.66992188, 3780.5390625, 158.23362305), 'rotation':(0.042935, 179.440613, 0.042875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5709.18164062, 3780.81734375, 158.25494141), 'rotation':(0.042935, 179.440613, 0.042875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5697.78515625, 3780.9284374999997, 158.26394531), 'rotation':(0.054259, 179.439041, 0.054158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5692.08742188, 3780.984375, 158.26933594), 'rotation':(0.076997, 179.440659, 0.076786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5686.38867188, 3781.04, 158.27655273), 'rotation':(0.088396, 179.440872, 0.088131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5674.99265625, 3781.15140625, 158.29323242), 'rotation':(0.088396, 179.440872, 0.088131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5663.59570312, 3781.26242188, 158.31084961), 'rotation':(0.099871, 179.440887, 0.099536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5646.50242188, 3781.42945312, 158.34376953), 'rotation':(0.145797, 179.441086, 0.145073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5640.80226562, 3781.48507812, 158.35758789), 'rotation':(0.145797, 179.441086, 0.145073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5629.40625, 3781.59617188, 158.38896484), 'rotation':(0.180249, 179.439972, 0.179126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5618.00976562, 3781.70773438, 158.42410156), 'rotation':(0.184743, 179.44165, 0.183553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5612.31152344, 3781.7634375, 158.4425), 'rotation':(0.19395, 179.441727, 0.192639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5600.91554688, 3781.87476562, 158.48239258), 'rotation':(0.212193, 179.439072, 0.210626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5595.21679688, 3781.93039062, 158.50384766), 'rotation':(0.221243, 179.441864, 0.219554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5561.02929688, 3782.26414062, 158.65092773), 'rotation':(0.273453, 179.440674, 0.270855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5532.53710938, 3782.54273438, 158.79423828), 'rotation':(0.313868, 179.441086, 0.310444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5521.14355469, 3782.6535937500003, 158.85708984000001), 'rotation':(0.323471, 179.441498, 0.319834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5481.25929688, 3783.0434375, 159.09283203), 'rotation':(0.361679, 179.443756, 0.357128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5464.16699219, 3783.21023438, 159.20070312), 'rotation':(0.364589, 179.443192, 0.359967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5458.46921875, 3783.26585938, 159.23695312), 'rotation':(0.370319, 179.443253, 0.365563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5447.07375, 3783.3771875, 159.31098633), 'rotation':(0.381808, 179.441437, 0.376749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5441.37695312, 3783.43289062, 159.34863281), 'rotation':(0.381808, 179.441437, 0.376749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5396.58546875, 3783.87039062, 159.64950195), 'rotation':(0.387647, 179.442184, 0.382426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5370.145, 3784.12867188, 159.82807617), 'rotation':(0.3829, 179.441528, 0.377816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5359.09375, 3784.2365625, 159.9015625), 'rotation':(0.376555, 179.441452, 0.371631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5353.56789062, 3784.29054688, 159.93788086), 'rotation':(0.373386, 179.443619, 0.368543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5342.51609375, 3784.3984375, 160.00973633), 'rotation':(0.367177, 179.441345, 0.36249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5336.99070312, 3784.45242188, 160.04527344), 'rotation':(0.364001, 179.443497, 0.359396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5331.46484375, 3784.50632812, 160.08054688), 'rotation':(0.364001, 179.443497, 0.359396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5320.41308594, 3784.6145312500003, 160.15055664), 'rotation':(0.356563, 179.442947, 0.352148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5309.36279297, 3784.72265625, 160.21879883), 'rotation':(0.344802, 179.44281, 0.340673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5298.31152344, 3784.8303125, 160.28415039), 'rotation':(0.32119, 179.440826, 0.317608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5287.26123047, 3784.93820312, 160.34663086), 'rotation':(0.315391, 179.442169, 0.311934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5281.73486328, 3784.9921875, 160.37704102), 'rotation':(0.315282, 179.442139, 0.311827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5276.20947266, 3785.04617188, 160.40745117), 'rotation':(0.310384, 179.441406, 0.307043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5270.68359375, 3785.1003124999997, 160.43755859), 'rotation':(0.300433, 179.443863, 0.297294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5265.15820312, 3785.15429688, 160.46682617), 'rotation':(0.290584, 179.441208, 0.287651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5259.6328125, 3785.2082812500003, 160.49511719), 'rotation':(0.280598, 179.441101, 0.277867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5254.10693359, 3785.2621875, 160.52243164), 'rotation':(0.27081, 179.440964, 0.268269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5396.6675, 3792.25070312, 159.64949219), 'rotation':(-0.386322, -0.557831, -0.391571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5386.80421875, 3792.3471875, 159.71623047), 'rotation':(-0.387634, -0.556244, -0.392914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5381.27882812, 3792.4010937499997, 159.75361328), 'rotation':(-0.387634, -0.55777, -0.392883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5359.17625, 3792.61695312, 159.90155273), 'rotation':(-0.379852, -0.558502, -0.384918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5348.12453125, 3792.72484375, 159.97393555), 'rotation':(-0.373383, -0.556366, -0.378265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5326.02148438, 3792.94070312, 160.11560547), 'rotation':(-0.364014, -0.558716, -0.368652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5320.49609375, 3792.99460938, 160.15054688), 'rotation':(-0.362488, -0.555878, -0.367096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5309.4453125, 3793.1025, 160.21879883), 'rotation':(-0.356567, -0.558746, -0.361023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5303.91992188, 3793.15648438, 160.25203125), 'rotation':(-0.344818, -0.55719, -0.348999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5298.39404297, 3793.21070312, 160.28415039), 'rotation':(-0.332947, -0.557312, -0.336853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5292.86865234, 3793.2643749999997, 160.3156543), 'rotation':(-0.332947, -0.557312, -0.336853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5287.34375, 3793.31835938, 160.34662109), 'rotation':(-0.321198, -0.557465, -0.324799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5276.29199219, 3793.42625, 160.40745117), 'rotation':(-0.315247, -0.557831, -0.318726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5270.76611328, 3793.48023438, 160.43754883), 'rotation':(-0.310425, -0.558655, -0.313782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5248.66650391, 3793.74851562, 160.54874023), 'rotation':(-0.270813, -0.55899, -0.273376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5182.50292969, 3785.96140625, 160.78876953), 'rotation':(0.149028, 179.440826, 0.148247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5148.52001953, 3786.29390625, 160.84299805), 'rotation':(0.007418, 179.444626, 0.007416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5142.85742188, 3786.34960938, 160.84396484), 'rotation':(0.007254, 179.427383, 0.007255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5125.86230469, 3786.51953125, 160.84613281), 'rotation':(0.007254, 179.427383, 0.007255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5114.53173828, 3786.6328125, 160.84756836), 'rotation':(-0.012054, 179.427673, -0.012054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5103.20507812, 3786.74609375, 160.84556641), 'rotation':(-0.050568, 179.427704, -0.050659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5091.87939453, 3786.85960938, 160.83137695), 'rotation':(-0.127869, 179.427948, -0.128448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5086.21582031, 3786.91601562, 160.81884766), 'rotation':(-0.147125, 179.426727, -0.147888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5080.55224609, 3786.97289062, 160.80460938), 'rotation':(-0.147095, 179.426758, -0.147858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5046.56982422, 3787.3125, 160.69470703000002), 'rotation':(-0.283722, 179.429688, -0.28656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5018.25097656, 3787.59570312, 160.54888671999998), 'rotation':(-0.323181, 179.428711, -0.326843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5006.92236328, 3787.70898438, 160.48039062), 'rotation':(-0.402893, 179.429718, -0.4086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5001.26220703, 3787.765625, 160.44180663999998), 'rotation':(-0.402893, 179.429718, -0.4086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4995.59912109, 3787.82226562, 160.40112305), 'rotation':(-0.442719, 179.430298, -0.449585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4989.93457031, 3787.87890625, 160.35734375), 'rotation':(-0.462616, 179.430618, -0.470123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5205.24316406, 3794.12039062, 160.72494140999999), 'rotation':(-0.189758, -0.560242, -0.19101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5188.25097656, 3794.2864062500003, 160.77404296999998), 'rotation':(-0.149017, -0.559174, -0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5182.5859375, 3794.34179688, 160.78876953), 'rotation':(-0.149017, -0.559174, -0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5176.92041016, 3794.3971874999997, 160.80349609), 'rotation':(-0.149017, -0.559174, -0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5165.59423828, 3794.50804688, 160.82706055), 'rotation':(-0.095886, -0.560822, -0.096191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5142.93798828, 3794.73, 160.84396484), 'rotation':(-0.007721, -0.617401, -0.007721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5137.27441406, 3794.78664062, 160.84467773), 'rotation':(-0.007263, -0.572601, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5125.94433594, 3794.89992188, 160.84613281), 'rotation':(-0.007263, -0.572662, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5114.61425781, 3795.01320312, 160.84756836), 'rotation':(-0.007263, -0.572662, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5108.95166016, 3795.06960938, 160.84760742), 'rotation':(-0.007263, -0.572662, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5097.62695312, 3795.18289062, 160.84017578), 'rotation':(0.050584, -0.572296, 0.050482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5086.29833984, 3795.29640625, 160.81884766), 'rotation':(0.127861, -0.572052, 0.127292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5069.30761719, 3795.46632812, 160.77514648), 'rotation':(0.147109, -0.573242, 0.146361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5046.65283203, 3795.69289062, 160.69470703000002), 'rotation':(0.24478, -0.572327, 0.242714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5035.32617188, 3795.80617188, 160.64010742), 'rotation':(0.283747, -0.57196, 0.280947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5018.33398438, 3795.97609375, 160.54888671999998), 'rotation':(0.303336, -0.571716, 0.300142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5012.67089844, 3796.0325000000003, 160.51629882999998), 'rotation':(0.323198, -0.571289, 0.319568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4995.68261719, 3796.20242188, 160.40112305), 'rotation':(0.402906, -0.570282, 0.397274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4990.01757812, 3796.2590625000003, 160.35734375), 'rotation':(0.442699, -0.568024, 0.435903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4941.06933594, 3796.7487499999997, 159.91470703000002), 'rotation':(0.597771, -0.566376, 0.585401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4930.02197266, 3796.859375, 159.79307617), 'rotation':(0.638247, -0.566376, 0.624151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4907.92724609, 3797.08007812, 159.53540039), 'rotation':(0.693517, -0.563354, 0.676872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4891.35986328, 3797.24585938, 159.31931641), 'rotation':(0.767283, -0.563049, 0.746924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4874.79296875, 3797.41164062, 159.09144531), 'rotation':(0.795259, -0.560211, 0.773404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4852.70410156, 3797.63257812, 158.76597656), 'rotation':(0.872154, -0.560425, 0.845897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4847.18066406, 3797.68796875, 158.68000977), 'rotation':(0.891381, -0.557312, 0.863971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4841.65722656, 3797.7434375000003, 158.59217773), 'rotation':(0.91071, -0.559265, 0.882093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.56787109, 3797.964375, 158.22921875), 'rotation':(0.95415, -0.556915, 0.922758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4814.04541016, 3798.01929688, 158.13539062), 'rotation':(0.95415, -0.556915, 0.922758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4808.52636719, 3798.07445312, 158.04009766), 'rotation':(0.983766, -0.555908, 0.95041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4803.00341797, 3798.12960938, 157.94238281), 'rotation':(1.013286, -0.554871, 0.977903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4797.48046875, 3798.1848437500003, 157.84266602), 'rotation':(1.013286, -0.554871, 0.977903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4952.02832031, 3788.1770312500003, 160.02813477), 'rotation':(-0.570648, 179.433075, -0.582092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4940.98681641, 3788.36867188, 159.9147168), 'rotation':(-0.624634, 179.434204, -0.638367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4929.93847656, 3788.47898438, 159.79307617), 'rotation':(-0.656738, 179.434204, -0.671906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4913.36865234, 3788.64476562, 159.60229492), 'rotation':(-0.693481, 179.435104, -0.710419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4891.27587891, 3788.86570312, 159.31931641), 'rotation':(-0.785736, 179.438004, -0.807495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4885.75390625, 3788.9209375, 159.24405273), 'rotation':(-0.785736, 179.438004, -0.807495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4874.70849609, 3789.03148438, 159.09144531), 'rotation':(-0.814575, 179.437881, -0.838013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4869.18457031, 3789.08664062, 159.0127832), 'rotation':(-0.833679, 179.440948, -0.858215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4858.14208984, 3789.19726562, 158.85007812), 'rotation':(-0.872223, 179.442047, -0.899109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4852.61914062, 3789.25242188, 158.76594727), 'rotation':(-0.891388, 179.44017, -0.919464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4847.09521484, 3789.3073437499997, 158.67998047), 'rotation':(-0.910614, 179.440781, -0.939941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4841.57177734, 3789.36257812, 158.59214844), 'rotation':(-0.929932, 179.443848, -0.96051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4825.00585938, 3789.52828125, 158.32123047), 'rotation':(-0.954163, 179.443085, -0.986359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4808.43994141, 3789.69359375, 158.04005859), 'rotation':(-1.013275, 179.445129, -1.049622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4797.39404297, 3789.80421875, 157.84261719), 'rotation':(-1.042786, 179.446182, -1.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4759.47509766, 3790.05398438, 157.1347168), 'rotation':(-1.108215, 179.447632, -1.151733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4742.68554688, 3790.33296875, 156.80476562), 'rotation':(-1.149902, 179.450546, -1.196777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4753.94580078, 3790.11742188, 157.02748047), 'rotation':(-1.124847, 179.450256, -1.169678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4725.69580078, 3790.52125, 156.46234375), 'rotation':(-1.171906, 179.451874, -1.220612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4720.06494141, 3790.57742188, 156.34741211), 'rotation':(-1.180634, 179.452225, -1.230103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4703.17578125, 3790.74632812, 155.99820312), 'rotation':(-1.198303, 179.452972, -1.249237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.54589844, 3790.8025, 155.8802832), 'rotation':(-1.206909, 179.453323, -1.258606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.28515625, 3790.915, 155.64207031), 'rotation':(-1.220215, 179.451736, -1.273041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4675.02539062, 3791.0278125, 155.40220703), 'rotation':(-1.222931, 179.45192, -1.276001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4669.39601562, 3791.08398438, 155.28198242), 'rotation':(-1.228821, 179.454285, -1.28244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4618.72363281, 3791.59054688, 154.18513672), 'rotation':(-1.242157, 179.452835, -1.296936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4613.09375, 3791.64695312, 154.06300781), 'rotation':(-1.240051, 179.454987, -1.294647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4601.8325, 3791.75953125, 153.81915039), 'rotation':(-1.239105, 179.453903, -1.293579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4590.57179688, 3791.8723437500003, 153.57546875), 'rotation':(-1.239166, 179.453888, -1.293701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4579.31101562, 3791.98484375, 153.33175781), 'rotation':(-1.235138, 179.454132, -1.289307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4568.04835938, 3792.09742188, 153.08916992000002), 'rotation':(-1.227539, 179.453766, -1.281036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4562.41699219, 3792.1535937500003, 152.96858398), 'rotation':(-1.219727, 179.45343, -1.272552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4545.5234375, 3792.3225, 152.61024414), 'rotation':(-1.208099, 179.451828, -1.259888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4539.89304688, 3792.37890625, 152.49143555), 'rotation':(-1.202271, 179.453857, -1.253571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4517.36671875, 3792.60398438, 152.02362305), 'rotation':(-1.155151, 179.449478, -1.202454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4506.09863281, 3792.7165625, 151.79626953000002), 'rotation':(-1.143616, 179.451385, -1.189972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4500.46726562, 3792.77296875, 151.68432617), 'rotation':(-1.131714, 179.448532, -1.177124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4494.81835938, 3801.21117188, 151.5715332), 'rotation':(1.131728, -0.549042, 1.087658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4511.71191406, 3801.04226562, 151.90727539), 'rotation':(1.155149, -0.548096, 1.109241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4539.86914062, 3800.7604687499997, 152.48916992), 'rotation':(1.208103, -0.545441, 1.157929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4545.5, 3800.7043750000003, 152.60799805), 'rotation':(1.208226, -0.548218, 1.15803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4556.7621875, 3800.59179688, 152.84634766), 'rotation':(1.219667, -0.546539, 1.168524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4568.02390625, 3800.4792187499997, 153.08685547), 'rotation':(1.235219, -0.545898, 1.182789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4573.65429688, 3800.4228125, 153.20789062), 'rotation':(1.235219, -0.545898, 1.182789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4584.91601562, 3800.3103125, 153.45125), 'rotation':(1.239078, -0.546082, 1.186329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4596.17726562, 3800.1975, 153.69496094), 'rotation':(1.239174, -0.546112, 1.186399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4601.80761719, 3800.14132812, 153.81681641), 'rotation':(1.239174, -0.546112, 1.186399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4613.06835938, 3800.01171875, 154.06063477), 'rotation':(1.242159, -0.544922, 1.189129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4618.69875, 3799.93945312, 154.1827832), 'rotation':(1.243129, -0.547028, 1.190027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4624.32960938, 3799.88304688, 154.30501953), 'rotation':(1.243012, -0.545166, 1.189912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4635.59082031, 3799.77046875, 154.54951172), 'rotation':(1.243047, -0.545135, 1.189951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4641.22070312, 3799.714375, 154.67173828), 'rotation':(1.243129, -0.547028, 1.190027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4663.74265625, 3799.48921875, 155.15898438), 'rotation':(1.228833, -0.547882, 1.176928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4669.37257812, 3799.43289062, 155.27969726999999), 'rotation':(1.222918, -0.545898, 1.171511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.26513672, 3799.26414062, 155.63987305), 'rotation':(1.215657, -0.546295, 1.164858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.52587891, 3799.15140625, 155.87811523), 'rotation':(1.198282, -0.547028, 1.148921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4725.6796875, 3798.8698437499997, 156.4603418), 'rotation':(1.16314, -0.548492, 1.116603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4731.31054688, 3798.8134375, 156.57454102), 'rotation':(1.154521, -0.551025, 1.108667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4736.94189453, 3798.75734375, 156.68803711), 'rotation':(1.15004, -0.5495, 1.104534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4742.57519531, 3798.87109375, 156.80085938), 'rotation':(1.141693, -0.549072, 1.096846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4748.20556641, 3798.81492188, 156.91300781), 'rotation':(1.124816, -0.551727, 1.08129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5214.97949219, 3102.50195312, 154.57261719), 'rotation':(0.713447, 89.85791, 0.69585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5214.99462891, 3108.17895508, 154.64328125), 'rotation':(0.714287, 89.857918, 0.696646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.00976562, 3113.85546875, 154.71405273), 'rotation':(0.715462, 89.852547, 0.697766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.02490234, 3119.53320312, 154.78491211), 'rotation':(0.716138, 89.857971, 0.698412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.05517578, 3130.88720703, 154.92695312), 'rotation':(0.71816, 89.858025, 0.700323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.08544922, 3142.24121094, 155.06942383), 'rotation':(0.719704, 89.857086, 0.701788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.11572266, 3153.59521484, 155.21207031), 'rotation':(0.719547, 89.857086, 0.701658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.13085938, 3159.27197266, 155.28338867), 'rotation':(0.719704, 89.857086, 0.701788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.14599609, 3164.94921875, 155.3546875), 'rotation':(0.719349, 89.856216, 0.701447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.19140625, 3181.98023438, 155.5684082), 'rotation':(0.71842, 89.855927, 0.700563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.25244141, 3204.68847656, 155.85305664), 'rotation':(0.71536, 89.859093, 0.697657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.28271484, 3216.04199219, 155.99481445), 'rotation':(0.713092, 89.853485, 0.695507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.31298828, 3227.39599609, 156.13603516), 'rotation':(0.710497, 89.853409, 0.693039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.38916016, 3255.78076172, 156.48704102), 'rotation':(0.702533, 89.855667, 0.685475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.40429688, 3261.45800781, 156.55666992), 'rotation':(0.698291, 89.855583, 0.68142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.41943359, 3267.135, 156.62614258), 'rotation':(0.698291, 89.855583, 0.68142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.44384766, 3278.48902344, 156.76427734), 'rotation':(0.694173, 89.855461, 0.6775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.49560547, 3289.84300781, 156.90166992000002), 'rotation':(0.689692, 89.855438, 0.673226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.47460938, 3295.51976562, 156.97015625), 'rotation':(0.689692, 89.855438, 0.673226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.43701172, 3301.19677734, 157.03841796999998), 'rotation':(0.684911, 89.855324, 0.668687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.89746094, 3295.52367188, 156.97047852), 'rotation':(-0.692078, -90.143951, -0.708954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.86083984, 3289.84839844, 156.90201172), 'rotation':(-0.692078, -90.143951, -0.708954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.84570312, 3284.17138672, 156.83341797), 'rotation':(-0.694183, -90.144501, -0.711121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.81542969, 3272.81761719, 156.69569336), 'rotation':(-0.698334, -90.144409, -0.715485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.80029297, 3267.140625, 156.62648438), 'rotation':(-0.702545, -90.144318, -0.71994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.78515625, 3261.46363281, 156.55702148), 'rotation':(-0.702545, -90.144318, -0.71994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.73974609, 3244.43310547, 156.34732422), 'rotation':(-0.708801, -90.143921, -0.726501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.70898438, 3233.07933594, 156.20680664), 'rotation':(-0.71051, -90.146576, -0.728302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5223.6484375, 3210.37109375, 155.92436523), 'rotation':(-0.715302, -90.1409, -0.733337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.58789062, 3187.66382812, 155.63995117000002), 'rotation':(-0.718475, -90.144073, -0.736633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.57275391, 3181.9865625, 155.56875976999999), 'rotation':(-0.718414, -90.144073, -0.736603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5223.54248047, 3170.6328125, 155.42632812), 'rotation':(-0.71933, -90.143768, -0.737579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5223.52734375, 3164.95556641, 155.35505859), 'rotation':(-0.719696, -90.142883, -0.737946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.49658203, 3153.6015625, 155.21243164), 'rotation':(-0.719727, -90.142883, -0.738007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.45117188, 3136.57006836, 154.99850586), 'rotation':(-0.71817, -90.141968, -0.736359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.43603516, 3130.89331055, 154.92732422), 'rotation':(-0.717316, -90.1474, -0.735474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.42089844, 3125.21606445, 154.85625), 'rotation':(-0.716125, -90.142029, -0.734222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.390625, 3113.86157227, 154.7144043), 'rotation':(-0.714294, -90.142059, -0.732269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.14550781, 3538.5346875, 159.48570312), 'rotation':(0.463073, 89.853554, 0.455632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.11523438, 3527.14160156, 159.39208984), 'rotation':(0.473653, 89.851578, 0.465871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.06933594, 3510.05273438, 159.24714844), 'rotation':(0.490927, 89.847527, 0.482564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.03857422, 3498.66113281, 159.14675781), 'rotation':(0.508316, 89.852188, 0.499355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.0234375, 3492.96460938, 159.09537109000001), 'rotation':(0.516895, 89.852333, 0.50763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.99316406, 3481.57179688, 158.99025390999998), 'rotation':(0.534285, 89.852654, 0.524386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.97753906, 3475.8771875, 158.93678711), 'rotation':(0.538615, 89.847679, 0.528559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.90185547, 3447.39601562, 158.65983398), 'rotation':(0.56793, 89.852371, 0.55674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.88671875, 3441.69921875, 158.6021875), 'rotation':(0.579787, 89.8526, 0.568142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.84082031, 3424.61207031, 158.42757812), 'rotation':(0.588407, 89.851578, 0.576423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.82568359, 3418.91625, 158.36845703), 'rotation':(0.594295, 89.857224, 0.582065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.78027344, 3401.82714844, 158.18716797), 'rotation':(0.611493, 89.852074, 0.598561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.76464844, 3396.13085938, 158.12545898), 'rotation':(0.623214, 89.85231, 0.609779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.74951172, 3390.43480469, 158.063125), 'rotation':(0.628931, 89.85244, 0.61524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.71923828, 3379.04320312, 157.93755859), 'rotation':(0.631772, 89.853767, 0.617955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.68847656, 3367.651875, 157.81092773), 'rotation':(0.635918, 89.853714, 0.621925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.65820312, 3356.25929688, 157.68209961), 'rotation':(0.652317, 89.854088, 0.637587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.02392578, 3350.52390625, 157.61667969), 'rotation':(-0.6604, -90.145721, -0.675751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.0390625, 3356.21996094, 157.68191406), 'rotation':(-0.6604, -90.145721, -0.675751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.09960938, 3379.004375, 157.93738281), 'rotation':(-0.635956, -90.146271, -0.650177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.14550781, 3396.09253906, 158.12529297), 'rotation':(-0.628937, -90.147552, -0.642853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.16064453, 3401.7888281200003, 158.18699219), 'rotation':(-0.617371, -90.147797, -0.630798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.20654297, 3418.87792969, 158.36828125), 'rotation':(-0.600006, -90.148163, -0.61264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.23681641, 3430.26953125, 158.48589844), 'rotation':(-0.58844, -90.148407, -0.600616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.25195312, 3435.96632812, 158.54413086), 'rotation':(-0.585571, -90.147369, -0.597656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.28222656, 3447.3591406200003, 158.6596875), 'rotation':(-0.579773, -90.1474, -0.591614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.29736328, 3453.0549218799997, 158.71628906), 'rotation':(-0.567902, -90.147644, -0.579254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.328125, 3464.44773438, 158.82785156), 'rotation':(-0.556244, -90.147858, -0.567139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.34326172, 3470.14378906, 158.88250976999998), 'rotation':(-0.556244, -90.147858, -0.567139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.45019531, 3510.0178125, 159.24702148), 'rotation':(-0.499603, -90.147949, -0.508392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.49560547, 3527.10695312, 159.39198242), 'rotation':(-0.482239, -90.148254, -0.490387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.51074219, 3532.80347656, 159.43893555), 'rotation':(-0.473633, -90.148407, -0.481506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.54150391, 3544.19679688, 159.53166016), 'rotation':(-0.463104, -90.150879, -0.470642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.24707031, 3576.68507812, 159.77482422), 'rotation':(0.405522, 89.849533, 0.399827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.29296875, 3593.77417969, 159.89453125), 'rotation':(0.38499, 89.849258, 0.379841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.33886719, 3610.86328125, 160.00537109), 'rotation':(0.354384, 89.848862, 0.35002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.35400391, 3616.56007812, 160.04026367), 'rotation':(0.344023, 89.84874, 0.339917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.36914062, 3622.25683594, 160.07416016), 'rotation':(0.333983, 89.84861, 0.330106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.39941406, 3633.65015625, 160.13986328000001), 'rotation':(0.320281, 89.848267, 0.316709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.49121094, 3667.828125, 160.31464844), 'rotation':(0.260941, 89.846359, 0.258575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.50634766, 3673.525625, 160.3405957), 'rotation':(0.260941, 89.846359, 0.258575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.52148438, 3679.22195312, 160.36613281), 'rotation':(0.250176, 89.849327, 0.248004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.56738281, 3696.3125, 160.43728516), 'rotation':(0.207501, 89.848999, 0.206003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.59814453, 3707.7043750000003, 160.47848633), 'rotation':(0.186068, 89.846031, 0.184869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.61328125, 3713.40164062, 160.49699219000001), 'rotation':(0.175392, 89.847404, 0.174328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.65917969, 3730.4921875, 160.5499707), 'rotation':(0.16637, 89.847366, 0.165395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.67431641, 3736.18820312, 160.5665625), 'rotation':(0.148338, 89.847252, 0.147562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.68945312, 3741.885, 160.5818457), 'rotation':(0.130416, 89.84716, 0.129831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.70458984, 3747.5815625, 160.59579102), 'rotation':(0.130416, 89.84716, 0.129831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.71972656, 3753.27828125, 160.60837891), 'rotation':(0.112261, 89.847092, 0.111828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.14648438, 3770.34789062, 160.64011719), 'rotation':(-0.10321, -90.152893, -0.103607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.13134766, 3764.650625, 160.62985351999998), 'rotation':(-0.10321, -90.152893, -0.103607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.11572266, 3758.95484375, 160.61955078), 'rotation':(-0.112274, -90.152893, -0.112701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.10058594, 3753.25734375, 160.60837891), 'rotation':(-0.130432, -90.152832, -0.131012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.0703125, 3741.86421875, 160.5818457), 'rotation':(-0.148315, -90.15274, -0.149109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.05517578, 3736.16773438, 160.5665625), 'rotation':(-0.166382, -90.156555, -0.167328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.97900391, 3707.68429688, 160.47849609000002), 'rotation':(-0.20752, -90.153809, -0.209015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.94824219, 3696.29296875, 160.43730469), 'rotation':(-0.228851, -90.150818, -0.230652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.91748047, 3684.8996875000003, 160.39100586), 'rotation':(-0.250183, -90.153473, -0.25235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.90234375, 3679.20242188, 160.36613281), 'rotation':(-0.260956, -90.148804, -0.263336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.88720703, 3673.50632812, 160.3405957), 'rotation':(-0.260956, -90.153625, -0.263336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.84130859, 3656.41726562, 160.26109375), 'rotation':(-0.286377, -90.152069, -0.289246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.81103516, 3645.0234375, 160.20274414), 'rotation':(-0.320282, -90.148132, -0.323883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.79589844, 3639.32691406, 160.17179688), 'rotation':(-0.320282, -90.148132, -0.323883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.76513672, 3627.93480469, 160.10720703), 'rotation':(-0.333984, -90.151367, -0.337891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.71972656, 3610.84523438, 160.00540039), 'rotation':(-0.364594, -90.151001, -0.369232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.68896484, 3599.45359375, 159.93253906), 'rotation':(-0.384979, -90.150757, -0.390167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.65869141, 3588.0603125, 159.85555664), 'rotation':(-0.405518, -90.150452, -0.411316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.64355469, 3582.36351562, 159.81554688), 'rotation':(-0.410583, -90.148132, -0.416473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.26660156, 3957.8776562499997, 160.44946289), 'rotation':(-0.21109, 89.848442, -0.212646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.23730469, 3946.7990625, 160.48770507999998), 'rotation':(-0.203247, 89.845871, -0.204681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.20751953, 3935.72117188, 160.52235352), 'rotation':(-0.171448, 89.845657, -0.172485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5217.19287109, 3930.18210938, 160.53838867000002), 'rotation':(-0.171448, 89.845657, -0.172485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.16308594, 3919.10328125, 160.56791992), 'rotation':(-0.155609, 89.84861, -0.156464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5217.1484375, 3913.56492188, 160.58195312), 'rotation':(-0.147614, 89.846977, -0.148376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.11865234, 3902.48609375, 160.60760742), 'rotation':(-0.137726, 89.847641, -0.138367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.10400391, 3896.94625, 160.61902344), 'rotation':(-0.118073, 89.847565, -0.118561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.07421875, 3885.86914062, 160.63821289), 'rotation':(-0.098267, 89.844551, -0.098602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.04492188, 3874.79078125, 160.65307617), 'rotation':(-0.078552, 89.847427, -0.078766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.00048828, 3858.17140625, 160.67300781), 'rotation':(-0.068665, 89.846657, -0.068817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.98583984, 3852.63375, 160.67797852), 'rotation':(-0.049133, 89.847328, -0.049225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.97070312, 3847.09546875, 160.68112305), 'rotation':(-0.049133, 89.847328, -0.049225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.94140625, 3836.01804688, 160.68117188), 'rotation':(0.009924, 89.848381, 0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.91162109, 3824.9387500000003, 160.67925781), 'rotation':(0.009931, 89.845505, 0.009921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.86669922, 3808.319375, 160.67638671999998), 'rotation':(0.009835, 89.848373, 0.009829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.26269531, 3813.83742188, 160.67735352), 'rotation':(-0.009918, -90.151611, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.27734375, 3819.3771875, 160.67830078), 'rotation':(-0.009827, -90.15448, -0.009827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.30664062, 3830.4565625, 160.68022461), 'rotation':(-0.009918, -90.151611, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.32177734, 3835.99632812, 160.68117188), 'rotation':(-0.009918, -90.151611, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.33642578, 3841.53367188, 160.68207031), 'rotation':(-0.009918, -90.15448, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.3515625, 3847.07351562, 160.68112305), 'rotation':(0.00976, -90.15271, 0.009756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.38134766, 3858.14914062, 160.67300781), 'rotation':(0.049123, -90.152649, 0.049048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.39599609, 3863.68898438, 160.66634765999999), 'rotation':(0.06865, -90.15332, 0.068485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.44042969, 3880.3073437499997, 160.64583008), 'rotation':(0.068732, -90.15332, 0.068573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.45507812, 3885.84695312, 160.63821289), 'rotation':(0.078527, -90.152588, 0.078331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.47021484, 3891.38601562, 160.62887695), 'rotation':(0.098266, -90.152527, 0.097939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.49951172, 3902.4635937499997, 160.60760742), 'rotation':(0.11808, -90.155365, 0.117606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.51416016, 3908.0026562499997, 160.59529297), 'rotation':(0.11808, -90.155365, 0.117606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.57373047, 3930.15945312, 160.53838867000002), 'rotation':(0.155592, -90.151398, 0.154757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.61816406, 3946.77640625, 160.48770507999998), 'rotation':(0.187304, -90.151184, 0.18607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.6328125, 3952.3151562499997, 160.46912109000002), 'rotation':(0.187304, -90.151184, 0.18607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.66259766, 3963.39359375, 160.42931640999998), 'rotation':(0.203225, -90.151093, 0.201787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.56933594, 3103.70996094, 155.47054688), 'rotation':(0.543663, 90.307266, 0.533417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5416.5390625, 3109.39038086, 155.52432617), 'rotation':(0.539093, 90.307152, 0.529031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.41894531, 3132.11157227, 155.73683594), 'rotation':(0.529674, 90.306999, 0.519952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.38867188, 3137.79150391, 155.78927734), 'rotation':(0.527379, 90.306938, 0.517743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.35890625, 3143.47192383, 155.84152344), 'rotation':(0.526075, 90.312126, 0.5165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.32859375, 3149.15209961, 155.89369141), 'rotation':(0.523739, 90.308029, 0.514227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.08835938, 3194.59423828, 156.3022168), 'rotation':(0.506281, 90.308029, 0.497393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.058125, 3200.27441406, 156.35232421999999), 'rotation':(0.503501, 90.308174, 0.494708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.02832031, 3205.95458984, 156.40225586), 'rotation':(0.497866, 90.305069, 0.489273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.90773438, 3228.67601562, 156.59854492), 'rotation':(0.486774, 90.307884, 0.478559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.84765625, 3240.03662109, 156.69485352), 'rotation':(0.483885, 90.307335, 0.475777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.72703125, 3262.7578125, 156.8850293), 'rotation':(0.467007, 90.308243, 0.459447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.69726562, 3268.43824219, 156.9315918), 'rotation':(0.467007, 90.308243, 0.459447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.66699219, 3274.11839844, 156.97787109), 'rotation':(0.460266, 90.308151, 0.452932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.6371875, 3279.79882812, 157.02351562), 'rotation':(0.45681, 90.305771, 0.449573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.51660156, 3302.52050781, 157.20477539), 'rotation':(0.451708, 90.308586, 0.444632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.4565625, 3313.88109375, 157.29378906), 'rotation':(0.441558, 90.305588, 0.434786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.89746094, 3302.57666016, 157.20486328), 'rotation':(-0.456909, -89.691071, -0.464264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5423.92773438, 3296.89697266, 157.1597168), 'rotation':(-0.456909, -89.691071, -0.464264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5423.98730469, 3285.53589844, 157.06912109), 'rotation':(-0.460297, -89.691864, -0.467743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.01757812, 3279.85570312, 157.02362305), 'rotation':(-0.460297, -89.691864, -0.467743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.04785156, 3274.17529297, 156.97797852), 'rotation':(-0.46701, -89.694824, -0.47467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.07765625, 3268.49511719, 156.93168945), 'rotation':(-0.473816, -89.69162, -0.48172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.10789062, 3262.81494141, 156.88513672), 'rotation':(-0.473816, -89.69162, -0.48172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.16796875, 3251.45410156, 156.79066406), 'rotation':(-0.480652, -89.694611, -0.48877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5424.19824219, 3245.77464844, 156.74294921999999), 'rotation':(-0.483917, -89.692657, -0.492126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.28808594, 3228.73339844, 156.59865234), 'rotation':(-0.49234, -89.692017, -0.500854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5424.40867188, 3206.01246094, 156.40236328), 'rotation':(-0.50351, -89.691803, -0.512421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.43847656, 3200.33179688, 156.35245117), 'rotation':(-0.506256, -89.691956, -0.515289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.49851562, 3188.97167969, 156.25214844), 'rotation':(-0.508698, -89.692261, -0.517761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.55859375, 3177.6115625, 156.15133789), 'rotation':(-0.513763, -89.692139, -0.523041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5424.58886719, 3171.93089844, 156.10039061999998), 'rotation':(-0.518768, -89.692047, -0.528229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.64890625, 3160.57055664, 155.99775391), 'rotation':(-0.523712, -89.691986, -0.533356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.73925781, 3143.5300293, 155.84166016), 'rotation':(-0.527405, -89.693054, -0.53717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.76953125, 3137.85009766, 155.78939453), 'rotation':(-0.529694, -89.687378, -0.539551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.82960938, 3126.48974609, 155.68423828000002), 'rotation':(-0.534393, -89.692902, -0.544403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.88964844, 3115.12915039, 155.57798828), 'rotation':(-0.539093, -89.692841, -0.549316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.9496875, 3103.76855469, 155.47067383), 'rotation':(-0.543671, -89.692749, -0.554047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.70410156, 3534.65671875, 158.71674805), 'rotation':(-0.292847, -89.694092, -0.295868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.69824219, 3529.12207031, 158.68861328), 'rotation':(-0.292847, -89.694092, -0.295868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.78613281, 3512.51195312, 158.60255859), 'rotation':(-0.306671, -89.693817, -0.309967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.84472656, 3501.43824219, 158.54285156), 'rotation':(-0.315765, -89.693695, -0.319244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5422.90382812, 3490.36476562, 158.48115234), 'rotation':(-0.324829, -89.696472, -0.328522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.96242188, 3479.29148438, 158.41791992), 'rotation':(-0.331696, -89.694244, -0.335541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.02101562, 3468.2185156200003, 158.3534082), 'rotation':(-0.341003, -89.694122, -0.345093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.0503125, 3462.681875, 158.32049805), 'rotation':(-0.345856, -89.694061, -0.350037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.25488281, 3423.9253125, 158.07818359), 'rotation':(-0.370636, -89.695953, -0.375458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.28417969, 3418.3884375, 158.04236328000002), 'rotation':(-0.378479, -89.692932, -0.383514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.31398438, 3412.8517968799997, 158.00581055), 'rotation':(-0.386353, -89.69577, -0.391602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.43117188, 3390.70484375, 157.8559082), 'rotation':(-0.398071, -89.693481, -0.403625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.46046875, 3385.16871094, 157.81753906), 'rotation':(-0.399963, -89.692719, -0.405579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.48925781, 3379.6325781200003, 157.77899414), 'rotation':(-0.399963, -89.692719, -0.405579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.57765625, 3363.02246094, 157.66115234), 'rotation':(-0.415894, -89.692474, -0.421967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5423.63625, 3351.94921875, 157.58051758), 'rotation':(-0.423859, -89.697876, -0.430176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.3471875, 3523.54125, 158.66029297), 'rotation':(0.292858, 90.30265, 0.289882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.37648438, 3518.00414062, 158.63154297), 'rotation':(0.29753, 90.306091, 0.294451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.40578125, 3512.46753906, 158.60255859), 'rotation':(0.29753, 90.306091, 0.294451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5414.464375, 3501.39378906, 158.54285156), 'rotation':(0.306696, 90.303322, 0.30341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5414.49367188, 3495.85695312, 158.51232421999998), 'rotation':(0.31576, 90.306282, 0.312305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.52296875, 3490.3200781200003, 158.48114257999998), 'rotation':(0.31576, 90.306282, 0.312305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.55175781, 3484.78246094, 158.44973633), 'rotation':(0.32483, 90.303528, 0.321153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.5815625, 3479.24730469, 158.41791992), 'rotation':(0.329557, 90.309181, 0.325775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.64015625, 3468.17382812, 158.3534082), 'rotation':(0.336517, 90.300842, 0.332586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.90382812, 3418.34375, 158.04236328000002), 'rotation':(0.37062, 90.306938, 0.365854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.96242188, 3407.27074219, 157.96905273000002), 'rotation':(0.378481, 90.304115, 0.373507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.07960938, 3385.12425781, 157.81753906), 'rotation':(0.398043, 90.306511, 0.392553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.19679688, 3362.97777344, 157.66115234), 'rotation':(0.411901, 90.301903, 0.40602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.22609375, 3357.44140625, 157.62104492), 'rotation':(0.415897, 90.307526, 0.409895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.2846875, 3346.36792969, 157.53953125), 'rotation':(0.423847, 90.307632, 0.417628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.02882812, 3583.67308594, 158.94568359000002), 'rotation':(0.248195, 90.302498, 0.246062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.99953125, 3589.21019531, 158.96967773), 'rotation':(0.238128, 90.305443, 0.236159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.94140625, 3600.28367188, 159.01583984), 'rotation':(0.227951, 90.305351, 0.226153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.88234375, 3611.35789062, 159.05949219000001), 'rotation':(0.217692, 90.302254, 0.216045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.85304688, 3616.895, 159.08054688), 'rotation':(0.212658, 90.304848, 0.211089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.82375, 3622.43140625, 159.10123047), 'rotation':(0.212658, 90.304848, 0.211089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.765625, 3633.50488281, 159.14200195), 'rotation':(0.207597, 90.301987, 0.206099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.67726562, 3650.11570312, 159.19976562), 'rotation':(0.187468, 90.305023, 0.186259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.53078125, 3677.79984375, 159.2853418), 'rotation':(0.164157, 90.301743, 0.163214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.50148438, 3683.33664062, 159.30138671999998), 'rotation':(0.158857, 90.301704, 0.157971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.4721875, 3688.8737499999997, 159.316875), 'rotation':(0.153365, 90.307175, 0.15256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5413.38429688, 3705.48460938, 159.35994141), 'rotation':(0.137116, 90.307091, 0.136468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.23828125, 3733.16945312, 159.42242188), 'rotation':(0.113852, 90.302841, 0.113412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.20898438, 3738.70632812, 159.43345703), 'rotation':(0.103833, 90.305817, 0.103464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.17921875, 3744.243125, 159.44417969), 'rotation':(0.103833, 90.305817, 0.103464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.120625, 3755.31710938, 159.46362305), 'rotation':(0.093731, 90.302765, 0.093412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.06203125, 3766.39085938, 159.4812793), 'rotation':(0.084845, 90.303162, 0.084601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.41359375, 3771.973125, 159.48972656), 'rotation':(-0.088684, -89.695343, -0.088959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.44289062, 3766.43601562, 159.4812793), 'rotation':(-0.088684, -89.695343, -0.088959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5421.47167969, 3760.8996875000003, 159.47268555), 'rotation':(-0.093719, -89.697235, -0.094025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.55957031, 3744.28835938, 159.44417969), 'rotation':(-0.113861, -89.697144, -0.114319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.589375, 3738.75171875, 159.43345703), 'rotation':(-0.113861, -89.697144, -0.114319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.61867188, 3733.21460938, 159.42242188), 'rotation':(-0.124084, -89.694092, -0.124603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.67726562, 3722.14109375, 159.39828125), 'rotation':(-0.128998, -89.696106, -0.129578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.76515625, 3705.5303125, 159.35994141), 'rotation':(-0.142609, -89.692871, -0.143311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.82375, 3694.45679688, 159.33180664), 'rotation':(-0.153381, -89.698303, -0.154205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5421.85304688, 3688.91945312, 159.316875), 'rotation':(-0.158844, -89.69281, -0.159729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.9409375, 3672.30953125, 159.26884766), 'rotation':(-0.172302, -89.695862, -0.17334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.97023438, 3666.7721874999997, 159.25217773), 'rotation':(-0.177368, -89.695038, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.99953125, 3661.23585938, 159.23518555), 'rotation':(-0.177368, -89.695038, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.058125, 3650.161875, 159.19978516), 'rotation':(-0.197601, -89.698059, -0.198975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.20460938, 3622.47777344, 159.10124023), 'rotation':(-0.212677, -89.699951, -0.214233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.26320312, 3611.40453125, 159.05951172), 'rotation':(-0.227966, -89.694641, -0.229767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.32128906, 3600.3303125, 159.01583984), 'rotation':(-0.238129, -89.697571, -0.240112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5422.35058594, 3594.79394531, 158.99291992), 'rotation':(-0.24823, -89.694458, -0.250366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5422.37988281, 3589.25683594, 158.96967773), 'rotation':(-0.24823, -89.694458, -0.250366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.40917969, 3583.71972656, 158.94568359000002), 'rotation':(-0.253357, -89.695557, -0.255615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5420.39109375, 3965.12203125, 159.49078125), 'rotation':(0.079941, -89.69809, 0.079724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5420.4496875, 3954.04054688, 159.50605469), 'rotation':(0.074517, -89.697845, 0.074318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.53757812, 3937.4184375, 159.52516602), 'rotation':(0.053296, -89.697906, 0.053207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.59617188, 3926.33640625, 159.53436523), 'rotation':(0.037416, -89.69519, 0.037368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.62546875, 3920.79664062, 159.53814453), 'rotation':(0.037409, -89.695221, 0.037364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.88964844, 3870.92945312, 159.55457031), 'rotation':(-0.002533, -89.696381, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.91894531, 3865.3884375, 159.55431640999998), 'rotation':(-0.002502, -89.696381, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.00683594, 3848.76539062, 159.55360352), 'rotation':(-0.007965, -89.698975, -0.007965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.06542969, 3837.68453125, 159.55203125), 'rotation':(-0.019135, -89.693878, -0.019135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.09472656, 3832.14382812, 159.54980469), 'rotation':(-0.030121, -89.698975, -0.030151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.12402344, 3826.60304688, 159.54650390999998), 'rotation':(-0.041138, -89.693848, -0.041199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5421.183125, 3815.52195312, 159.53779297), 'rotation':(-0.046661, -89.69632, -0.046722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.24171875, 3804.4401562499997, 159.52848633), 'rotation':(-0.051849, -89.69574, -0.051941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.01023438, 3965.07789062, 159.49078125), 'rotation':(-0.079834, 90.301872, -0.080048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.03953125, 3959.536875, 159.49851562), 'rotation':(-0.079926, 90.301895, -0.08017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.18601562, 3931.8332812500003, 159.53022461), 'rotation':(-0.053314, 90.305656, -0.053406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.2153125, 3926.29226562, 159.53436523), 'rotation':(-0.042664, 90.302094, -0.042694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.24460938, 3920.7521875, 159.53814453), 'rotation':(-0.037415, 90.304794, -0.037476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.30371094, 3909.66992188, 159.54538086), 'rotation':(-0.037262, 90.304779, -0.037292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.33300781, 3904.12890625, 159.54898438), 'rotation':(-0.037415, 90.304779, -0.037476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.36230469, 3898.58914062, 159.55166992), 'rotation':(-0.027435, 90.302002, -0.027466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.39160156, 3893.04859375, 159.55398438), 'rotation':(-0.027435, 90.302002, -0.027466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.45019531, 3881.9674999999997, 159.55505859000002), 'rotation':(-0.007416, 90.304802, -0.007416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.50878906, 3870.88523438, 159.55457031), 'rotation':(0.002507, 90.303589, 0.002504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.53808594, 3865.34421875, 159.55431640999998), 'rotation':(0.002514, 90.300735, 0.002511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.62648438, 3848.7209375, 159.55360352), 'rotation':(0.002589, 90.303589, 0.002593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.80226562, 3815.4778125000003, 159.53779297), 'rotation':(0.046766, 90.303658, 0.046688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.86085938, 3804.39601562, 159.52848633), 'rotation':(0.04665, 90.303673, 0.046572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4002.14773438, 351.05218749999995, 179.67042969), 'rotation':(0.072093, 174.374222, 0.071911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4024.7317187500003, 348.38519531, 179.61855469), 'rotation':(0.158051, 173.116562, 0.157176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4041.66554688, 346.15429687999995, 179.55853516), 'rotation':(0.231352, 172.072632, 0.229491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4047.30617188, 345.34406249999995, 179.53492188), 'rotation':(0.238811, 171.848923, 0.236828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4052.94601562, 344.50125, 179.51119140999998), 'rotation':(0.238811, 171.373627, 0.236817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4058.58054688, 343.62765625, 179.48744141), 'rotation':(0.238585, 171.137238, 0.236608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4069.8293750000003, 341.77828124999996, 179.43546875), 'rotation':(0.281513, 170.360275, 0.278749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4081.0534374999997, 339.8033593800001, 179.37517577999998), 'rotation':(0.315773, 169.835556, 0.312309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4086.651875, 338.76578125000003, 179.34169922), 'rotation':(0.333026, 169.572372, 0.329164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4108.9853125, 334.2990625, 179.19445312), 'rotation':(0.37592, 168.192902, 0.371012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4131.19289062, 329.46929688, 179.02396484000002), 'rotation':(0.479165, 166.729767, 0.471201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4008.36007812, 358.4765625, 179.65929688), 'rotation':(-0.117126, -6.178955, -0.117584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4019.28296875, 357.26429687999996, 179.63570312), 'rotation':(-0.141479, -6.673859, -0.142181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4030.17875, 355.79003906, 179.60480468999998), 'rotation':(-0.185059, -7.301147, -0.186249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4062.8645312500003, 351.06824219, 179.47431641), 'rotation':(-0.261353, -9.37561, -0.263733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4068.30101562, 350.17640625, 179.44953125), 'rotation':(-0.278198, -9.639648, -0.280884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4079.16210938, 348.2975, 179.39373047), 'rotation':(-0.312042, -10.164215, -0.31546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4084.57445312, 347.31542969, 179.36300781000003), 'rotation':(-0.345917, -10.690369, -0.350098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4089.98898438, 346.30273437999995, 179.33029297000002), 'rotation':(-0.362732, -10.952087, -0.36734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4100.80226562, 344.18640625, 179.25990234), 'rotation':(-0.371155, -11.392487, -0.376007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4111.578125, 341.951875, 179.18814453), 'rotation':(-0.380524, -12.03125, -0.38562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4116.94679688, 340.79312500000003, 179.15054688), 'rotation':(-0.417908, -12.527802, -0.424042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4133.04101562, 337.27882811999996, 179.02394531000002), 'rotation':(-0.491943, -13.516907, -0.500458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4138.38039062, 336.00304688000006, 178.97726562), 'rotation':(-0.51062, -13.764709, -0.519775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4007.7370312499997, 794.25158203, 180.08177734), 'rotation':(-0.304382, -0.454285, -0.307617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4012.9856250000003, 794.20972656, 180.05388672), 'rotation':(-0.349152, -0.453796, -0.353424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4018.22976562, 794.16796875, 180.02244141), 'rotation':(-0.394043, -0.45282, -0.399506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4023.4765625, 794.12621094, 179.98974609), 'rotation':(-0.394043, -0.45282, -0.399506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4002.4714062499997, 786.41271484, 180.10769531000003), 'rotation':(0.259383, 179.545288, 0.257047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4012.9557812499997, 786.32933594, 180.05371093999997), 'rotation':(0.304387, 179.545685, 0.301167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4018.19359375, 786.28759766, 180.02228516), 'rotation':(0.349166, 179.5466, 0.344922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4077.77976562, 785.81330078, 179.52695312), 'rotation':(0.589438, 179.550186, 0.577402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4111.046875, 785.54839844, 179.13171875), 'rotation':(0.734252, 179.553452, 0.715626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4122.13820312, 785.4600781199999, 178.97707031000002), 'rotation':(0.788142, 179.555252, 0.766671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4144.3159375, 785.28351562, 178.64208984), 'rotation':(0.886559, 179.558334, 0.859435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4155.401875, 785.19525391, 178.45970703), 'rotation':(0.95723, 179.560608, 0.925632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4183.11476562, 784.97455078, 177.94251953), 'rotation':(1.13377, 179.567062, 1.089544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4072.29226562, 793.73779297, 179.58554688), 'rotation':(-0.632019, -0.448914, -0.646088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4088.930625, 793.60535156, 179.40277343999998), 'rotation':(-0.680359, -0.447876, -0.696655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4100.0234375, 793.51708984, 179.27263672), 'rotation':(-0.734253, -0.446167, -0.753265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4105.56789062, 793.47302734, 179.20302734), 'rotation':(-0.734253, -0.446167, -0.753265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4122.20117188, 793.34058594, 178.97707031000002), 'rotation':(-0.842102, -0.443207, -0.867126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4127.74804688, 793.2964453100001, 178.89550781000003), 'rotation':(-0.86911, -0.442688, -0.895782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4138.836875, 793.20818359, 178.72798827999998), 'rotation':(-0.886566, -0.442322, -0.914337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4144.381875, 793.16417969, 178.64205077999998), 'rotation':(-0.92215, -0.440552, -0.952179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4149.92382812, 793.12, 178.55263672), 'rotation':(-0.957245, -0.440033, -0.989655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4155.46828125, 793.0759375, 178.45962891), 'rotation':(-0.992645, -0.438171, -1.027496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4161.01078125, 793.03173828, 178.36316406000003), 'rotation':(-1.027893, -0.437592, -1.065308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4166.55515625, 792.98767578, 178.263125), 'rotation':(-1.063293, -0.435638, -1.103333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4172.09617188, 792.94353516, 178.15962890999998), 'rotation':(-1.098541, -0.434967, -1.141296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4188.72953125, 792.81128906, 177.83087891), 'rotation':(-1.15152, -0.432434, -1.198517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4028.223125, 604.07359375, 179.66820312), 'rotation':(0.266166, -179.712006, 0.263705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4023.1896875, 604.11792969, 179.69158202999998), 'rotation':(0.219994, -179.712402, 0.218309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4018.01953125, 604.15214844, 179.71494141), 'rotation':(0.219994, -179.712402, 0.218309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4012.84328125, 604.12632812, 179.73480468999998), 'rotation':(0.173726, -179.713104, 0.172675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4002.4934375000003, 604.07464844, 179.76892578), 'rotation':(0.111134, -179.752823, 0.1107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4018.08664062, 611.99992188, 179.71453125), 'rotation':(-0.266174, 0.287983, -0.268646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4181.80375, 612.6876171900001, 178.09115234), 'rotation':(-0.902344, -2.49646, -0.931122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4165.2534375, 612.76878906, 178.34234375), 'rotation':(-0.84549, -0.015961, -0.870728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4143.0825, 612.67820312, 178.64658203), 'rotation':(-0.739624, 0.296382, -0.758911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4115.35398438, 612.66414062, 178.98078125), 'rotation':(-0.633026, 0.293779, -0.647095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4109.8090625, 612.6364062499999, 179.04035156), 'rotation':(-0.607269, 0.293251, -0.620239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4098.71828125, 612.58097656, 179.15167968999998), 'rotation':(-0.555603, 0.292174, -0.566437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4093.17257812, 612.55320312, 179.2034375), 'rotation':(-0.529785, 0.291688, -0.539642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4087.6262500000003, 612.5254687500001, 179.25365234), 'rotation':(-0.516815, 0.291369, -0.526215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4076.53296875, 612.4699218799999, 179.35152344), 'rotation':(-0.497711, 0.290963, -0.506409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4177.32179688, 604.65730469, 178.15804688), 'rotation':(0.912117, 178.727142, 0.883408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4144.00242188, 604.6370312500001, 178.63523438), 'rotation':(0.723542, -179.704193, 0.705435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4138.4575, 604.60929688, 178.70595702999998), 'rotation':(0.723542, -179.704193, 0.705435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4127.36671875, 604.55382812, 178.84332031000002), 'rotation':(0.68461, -179.705032, 0.668398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4110.73242188, 604.4707812500001, 179.03099609), 'rotation':(0.581563, -179.707306, 0.56984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4088.55125, 604.42597656, 179.24566406000002), 'rotation':(0.516813, -179.708633, 0.507553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4077.45945312, 604.3941796900001, 179.34382812), 'rotation':(0.459248, -179.709686, 0.451934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4219.0078125, 608.8200781200001, 177.4665625), 'rotation':(-1.021667, -9.434418, -1.058624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4229.65382812, 606.91734375, 177.26994141), 'rotation':(-1.058807, -11.340302, -1.098511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4240.3628125, 604.61210938, 177.06537109), 'rotation':(-1.063751, -13.241241, -1.103821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4245.70554688, 603.3158593799999, 176.96246093999997), 'rotation':(-1.073181, -14.378174, -1.113983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4261.91015625, 598.75828125, 176.6409375), 'rotation':(-1.103729, -17.253906, -1.146912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4272.68015625, 595.1973437500001, 176.41876953), 'rotation':(-1.124817, -19.40451, -1.169678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4283.36570312, 591.22589844, 176.19345703), 'rotation':(-1.124908, -21.493256, -1.169739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4299.17726562, 584.50886719, 175.85369140999998), 'rotation':(-1.126129, -24.730316, -1.171082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4304.30664062, 582.10332031, 175.74160156000002), 'rotation':(-1.126923, -25.985748, -1.171936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4324.44921875, 571.5133203099999, 175.29078125), 'rotation':(-1.113525, -30.201996, -1.157501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4329.359375, 568.63609375, 175.17951172000002), 'rotation':(-1.093964, -31.426422, -1.136383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4348.151875, 556.46367188, 174.75847656000002), 'rotation':(-1.034882, -35.10498, -1.072815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4356.99265625, 550.0410937500001, 174.56261718999997), 'rotation':(-0.995331, -37.546173, -1.030365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4361.31789062, 546.72535156, 174.46712890999999), 'rotation':(-0.985809, -38.162659, -1.020172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4365.50390625, 543.40476562, 174.37503906), 'rotation':(-0.970764, -39.249725, -1.004089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4360.30761719, 537.2846093799999, 174.37837890999998), 'rotation':(1.014167, 141.226959, 0.978723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4355.95996094, 540.73585938, 174.47658203), 'rotation':(1.034234, 142.451477, 0.997401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4337.57273438, 553.97941406, 174.89541015999998), 'rotation':(1.106026, 146.737366, 1.063915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4327.78171875, 560.21953125, 175.12076172000002), 'rotation':(1.146611, 149.188354, 1.101373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4317.67726562, 566.13414062, 175.35564452999998), 'rotation':(1.172381, 151.007309, 1.125104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4291.29734375, 579.2530468799999, 175.95478516), 'rotation':(1.169376, 156.519821, 1.122349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4285.90476562, 581.55253906, 176.07376953), 'rotation':(1.168816, 157.776321, 1.121817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4269.36914062, 587.8615625, 176.43283203), 'rotation':(1.166405, 160.95079, 1.119609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4263.83054688, 589.7315625, 176.55074219), 'rotation':(1.15478, 162.025085, 1.108908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4241.60109375, 596.07304688, 177.00503906000003), 'rotation':(1.106955, 166.346878, 1.064792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4236.06445312, 597.3712109400001, 177.11408203), 'rotation':(1.105111, 167.710266, 1.063069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4230.54882812, 598.5590625, 177.22234375), 'rotation':(1.100111, 168.660385, 1.05845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4217.3603125, 992.95812988, 176.77472656), 'rotation':(0.306723, -92.704651, 0.303447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4217.0971875, 987.37988281, 176.80490234), 'rotation':(0.299196, -92.704712, 0.296083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4216.83351562, 981.80145264, 176.83435547000002), 'rotation':(0.291369, -92.700104, 0.288429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4215.79148438, 959.48864746, 176.94515625), 'rotation':(0.268515, -92.705017, 0.266001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4215.27195312, 948.33190918, 176.99644531), 'rotation':(0.256822, -92.703003, 0.254533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4215.04203125, 942.75238281, 177.02115234000001), 'rotation':(0.252123, -92.702515, 0.249915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.7978125, 937.17297363, 177.04572266), 'rotation':(0.241966, -92.705414, 0.239926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.5615625, 931.59338379, 177.06933593999997), 'rotation':(0.231967, -92.702637, 0.230113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.34328125, 926.013125, 177.09273438), 'rotation':(0.231967, -92.702637, 0.230113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.0790625, 920.43451172, 177.11535156000002), 'rotation':(0.222002, -92.702728, 0.220286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4213.8159375, 914.8565625, 177.13757812), 'rotation':(0.222002, -92.702728, 0.220286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4212.76171875, 892.54242188, 177.22242188), 'rotation':(0.205022, -92.70282, 0.203565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4212.49804688, 886.96429688, 177.24277343999998), 'rotation':(0.205022, -92.70282, 0.203565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4211.97117188, 875.8075, 177.28201172), 'rotation':(0.189183, -92.702942, 0.187949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4211.17820312, 859.07166016, 177.33748047), 'rotation':(0.179689, -92.702576, 0.178574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4210.65382812, 847.91522461, 177.37292968999998), 'rotation':(0.168665, -92.702606, 0.167669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4210.12695312, 836.75927734, 177.40556641), 'rotation':(0.157613, -92.706238, 0.156751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4209.59960938, 825.59789062, 177.43519531), 'rotation':(0.140927, -92.558533, 0.140234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4209.14992188, 814.40148438, 177.46232422), 'rotation':(0.131263, -91.51947, 0.130667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4209.34914062, 993.44970703, 176.77412109), 'rotation':(-0.314392, 87.295425, -0.317871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.82125, 982.27459717, 176.83384766), 'rotation':(-0.299194, 87.29528, -0.302338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.02929688, 965.51190186, 176.91818359), 'rotation':(-0.283844, 87.295105, -0.286682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.765625, 959.92443848, 176.94488281000002), 'rotation':(-0.276184, 87.299728, -0.27887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4207.50148438, 954.33672852, 176.97089843999998), 'rotation':(-0.268494, 87.294991, -0.271027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.97359375, 943.16107422, 177.02103516), 'rotation':(-0.256836, 87.296997, -0.259155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.70945312, 937.57287598, 177.04564453), 'rotation':(-0.252106, 87.29467, -0.254364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.18210938, 926.39794922, 177.09275391), 'rotation':(-0.241974, 87.297417, -0.244019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4205.65429688, 915.22241211, 177.13765625), 'rotation':(-0.231995, 87.297325, -0.233856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4205.1259375, 904.04638672, 177.18068359), 'rotation':(-0.222015, 87.297256, -0.223724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4204.125, 881.69195312, 177.26304688), 'rotation':(-0.205048, 87.297142, -0.206512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4203.63671875, 870.5144043, 177.30123047), 'rotation':(-0.197266, 87.297104, -0.198639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4203.399375, 864.92517578, 177.31972656000002), 'rotation':(-0.189178, 87.297035, -0.19043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4201.839375, 831.39527344, 177.42134765999998), 'rotation':(-0.157623, 87.297295, -0.158478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4201.12890625, 814.65863281, 177.46228516), 'rotation':(-0.130859, 88.176445, -0.13147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.85109375, 809.09082031, 177.47464843999998), 'rotation':(-0.125244, 88.780983, -0.125793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.44140625, 768.68396484, 177.54798828), 'rotation':(-0.087921, 89.224083, -0.088165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.31835938, 759.5850781199999, 177.56113281), 'rotation':(-0.082733, 89.223831, -0.082977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.16648438, 748.39708984, 177.57724609000002), 'rotation':(-0.082733, 89.223839, -0.082977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.01515625, 737.2089257800001, 177.59294922), 'rotation':(-0.07962, 89.221352, -0.079834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.78757812, 720.4271875, 177.61597656), 'rotation':(-0.078369, 89.227287, -0.078583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.63625, 709.23908203, 177.63095703), 'rotation':(-0.076355, 89.223373, -0.076538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4199.484375, 698.05089844, 177.64541015999998), 'rotation':(-0.073578, 89.223381, -0.073761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.33296875, 686.8629687499999, 177.65933593999998), 'rotation':(-0.070831, 89.223373, -0.070984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.10546875, 670.08105469, 177.67929688), 'rotation':(-0.067169, 89.225212, -0.067322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.02976562, 664.48695312, 177.68585938), 'rotation':(-0.067169, 89.225212, -0.067322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4198.87796875, 653.2987109400001, 177.69900391), 'rotation':(-0.067383, 89.225525, -0.067535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4198.7265625, 642.11046875, 177.71220703), 'rotation':(-0.067505, 89.221794, -0.067657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4198.65039062, 636.51648438, 177.71878906), 'rotation':(-0.067719, 89.225525, -0.067871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4198.4990625, 625.32832031, 177.73203125), 'rotation':(-0.067749, 89.223503, -0.067902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.27296875, 765.0, 177.55316406000003), 'rotation':(0.082734, -90.776154, 0.082497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.19726562, 759.40851562, 177.56123047), 'rotation':(0.082734, -90.776154, 0.082497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.04539062, 748.22576172, 177.57732422), 'rotation':(0.081655, -90.778656, 0.081427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.81835938, 731.45134766, 177.60074218999998), 'rotation':(0.078349, -90.776794, 0.078147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.74265625, 725.85998047, 177.60837891), 'rotation':(0.078349, -90.776794, 0.078147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.66703125, 720.26873047, 177.61603516), 'rotation':(0.077728, -90.776611, 0.077526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.59132812, 714.67712891, 177.62359375), 'rotation':(0.076341, -90.771729, 0.076148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4207.51515625, 709.08587891, 177.63103515999998), 'rotation':(0.074961, -90.776611, 0.074772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.288125, 692.31152344, 177.6525), 'rotation':(0.070815, -90.776642, 0.070646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.13671875, 681.1287304699999, 177.66613281000002), 'rotation':(0.067892, -90.776642, 0.06774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.98484375, 669.94605469, 177.67931640999998), 'rotation':(0.067373, -90.778198, 0.067212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.90921875, 664.35457031, 177.68587890999999), 'rotation':(0.067373, -90.778198, 0.067212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.68164062, 647.5799609400001, 177.70560547000002), 'rotation':(0.067728, -90.774475, 0.067568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.6059375, 641.98847656, 177.71222656), 'rotation':(0.067728, -90.774475, 0.067568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.45460938, 630.80554688, 177.72542968999997), 'rotation':(0.067742, -90.776489, 0.06758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.37890625, 625.21410156, 177.73203125), 'rotation':(0.067742, -90.776489, 0.06758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.7981250000003, 623.1331250000001, 179.60867188), 'rotation':(-0.082184, -89.302368, -0.082397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.52757812, 645.31140625, 179.64119141), 'rotation':(-0.08551, -89.301178, -0.085785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.256875, 667.48949219, 179.67546875), 'rotation':(-0.089539, -89.301147, -0.089844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.1215625, 678.5785546899999, 179.69320312), 'rotation':(-0.092407, -89.301147, -0.092712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.91867188, 695.2122265600001, 179.72021484), 'rotation':(-0.093079, -89.300049, -0.093384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.78320312, 706.30132812, 179.73826172), 'rotation':(-0.093201, -89.300018, -0.093475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4045.71554688, 711.84587891, 179.74730469), 'rotation':(-0.093292, -89.301788, -0.093597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.58054688, 722.93457031, 179.7653125), 'rotation':(-0.092865, -89.299255, -0.09314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4045.51265625, 728.4790625, 179.77423828), 'rotation':(-0.092865, -89.299255, -0.09314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.3098437500003, 745.11242188, 179.80042969), 'rotation':(-0.089508, -89.299255, -0.089783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.2421875, 750.65705078, 179.80898438), 'rotation':(-0.088409, -89.301483, -0.088684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.1067187500003, 761.74597656, 179.82580077999998), 'rotation':(-0.086334, -89.301514, -0.086578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4045.0390625, 767.29041016, 179.83408203), 'rotation':(-0.085052, -89.299286, -0.085327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4044.9714062499997, 772.83484375, 179.84228516), 'rotation':(-0.084686, -89.301941, -0.08493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6623.98867188, 4233.895, 172.98279297000002), 'rotation':(-0.582001, -89.477234, -0.593903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6624.06335938, 4211.3271875, 172.75441406000002), 'rotation':(-0.572205, -89.477875, -0.58371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.21617188, 4194.40039062, 172.58564453), 'rotation':(-0.566376, -89.476227, -0.577667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.26695312, 4188.75828125, 172.52982422000002), 'rotation':(-0.566498, -89.476227, -0.577759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.31773438, 4183.11625, 172.47404297), 'rotation':(-0.566498, -89.476227, -0.577759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.36851562, 4177.47414062, 172.41824218999997), 'rotation':(-0.564636, -89.476685, -0.575836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.47058594, 4166.18898438, 172.30708984), 'rotation':(-0.560852, -89.480347, -0.571899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.57265625, 4154.90476562, 172.19695312), 'rotation':(-0.553436, -89.476929, -0.564209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6624.6234375, 4149.26265625, 172.14226562), 'rotation':(-0.553436, -89.476929, -0.564209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.8275, 4126.69289062, 171.92503906000002), 'rotation':(-0.546783, -89.481018, -0.557281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.03113281, 4104.1240625, 171.711875), 'rotation':(-0.533752, -89.481232, -0.543762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.18398438, 4087.19679688, 171.55539062), 'rotation':(-0.525696, -89.478088, -0.535431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.28554688, 4075.91234375, 171.45183594), 'rotation':(-0.525604, -89.478088, -0.535309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.38757812, 4064.6276562499997, 171.34865234), 'rotation':(-0.513092, -89.47644, -0.522339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6625.69324219, 4030.7725, 171.04691406), 'rotation':(-0.503143, -89.477875, -0.512024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.74402344, 4025.13039062, 170.99732422), 'rotation':(-0.499359, -89.477936, -0.508118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6625.84609375, 4013.84570312, 170.89929688), 'rotation':(-0.491669, -89.478058, -0.500153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.896875, 4008.20335938, 170.85082031000002), 'rotation':(-0.487732, -89.478149, -0.496094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.51648438, 4008.17015625, 170.85117188), 'rotation':(0.491671, 90.521935, 0.48329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.41445312, 4019.4518749999997, 170.94847656000002), 'rotation':(0.499348, 90.522057, 0.490711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6617.36367188, 4025.0928125, 170.99765625), 'rotation':(0.503139, 90.517288, 0.494355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.21082031, 4042.0165625, 171.14728516), 'rotation':(0.508876, 90.522476, 0.499887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6617.16003906, 4047.6575000000003, 171.19738281000002), 'rotation':(0.508876, 90.522476, 0.499887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.05796875, 4058.93921875, 171.29796875), 'rotation':(0.521478, 90.520119, 0.512055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.0071875, 4064.5803125, 171.34890625), 'rotation':(0.521478, 90.520119, 0.512055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6616.9559375, 4070.22171875, 171.4003125), 'rotation':(0.525597, 90.521912, 0.516028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.90515625, 4075.8628125, 171.45208984), 'rotation':(0.525665, 90.521896, 0.516108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.803125, 4087.14429688, 171.55560547000002), 'rotation':(0.52725, 90.52372, 0.517619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.7015625, 4098.42625, 171.65958984), 'rotation':(0.533745, 90.518738, 0.523867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.65027344, 4104.066875, 171.71205078), 'rotation':(0.537133, 90.523949, 0.527121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.34507812, 4137.913125, 172.03357422000002), 'rotation':(0.551599, 90.525703, 0.541055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6616.03894531, 4171.75828125, 172.36259766), 'rotation':(0.564631, 90.523293, 0.553584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6615.93738281, 4183.03953125, 172.47402344), 'rotation':(0.566339, 90.523727, 0.555229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6615.73328125, 4205.60304688, 172.69785156), 'rotation':(0.576161, 90.525711, 0.564659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6615.63171875, 4216.88476562, 172.81107422000002), 'rotation':(0.580115, 90.522285, 0.568453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.791875, 4104.00539062, 163.00803711), 'rotation':(0.48786, 90.433594, 0.479604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.96078125, 4081.453125, 162.81922852), 'rotation':(0.47282, 90.431145, 0.465076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.08726562, 4064.53976562, 162.6825), 'rotation':(0.459986, 90.430939, 0.452646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.17171875, 4053.26390625, 162.593125), 'rotation':(0.453538, 90.433311, 0.446405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.21375, 4047.6262500000003, 162.54847656), 'rotation':(0.453429, 90.429306, 0.446292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.34023438, 4030.7121875000003, 162.41723633), 'rotation':(0.436579, 90.430443, 0.429971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.3821875, 4025.07445312, 162.37466797), 'rotation':(0.436579, 90.430443, 0.429971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.46671875, 4013.79859375, 162.29055664), 'rotation':(0.426286, 90.431618, 0.419976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.50867188, 4008.16085938, 162.24861328), 'rotation':(0.426286, 90.431618, 0.419976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6095.88953125, 4008.18164062, 162.24829102), 'rotation':(-0.422302, -89.567963, -0.428558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.84703125, 4013.8215625000003, 162.29025391), 'rotation':(-0.42627, -89.568359, -0.432648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.80507812, 4019.46140625, 162.33222656), 'rotation':(-0.4263, -89.568359, -0.432678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.67859375, 4036.38257812, 162.46017578000001), 'rotation':(-0.436584, -89.56955, -0.443268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.63609375, 4042.02273438, 162.50395508), 'rotation':(-0.443207, -89.569427, -0.450104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.59414062, 4047.663125, 162.54828125), 'rotation':(-0.450195, -89.569336, -0.457306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.55210938, 4053.30296875, 162.59292969), 'rotation':(-0.45343, -89.566681, -0.460632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6095.51015625, 4058.943125, 162.63757812), 'rotation':(-0.453552, -89.56665, -0.460785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.425625, 4070.22335938, 162.72748047), 'rotation':(-0.460022, -89.569031, -0.467438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.25671875, 4092.78367188, 162.91267578), 'rotation':(-0.477051, -89.568756, -0.485046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.2146875, 4098.42429688, 162.96012695), 'rotation':(-0.481476, -89.568665, -0.489624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.13023438, 4109.7040625, 163.05603516), 'rotation':(-0.487854, -89.566406, -0.496216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6012.98765625, 5224.81396484, 166.34632812), 'rotation':(1.014877, 0.230017, 0.979399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6033.81625, 5224.89013672, 166.71515625), 'rotation':(1.011401, 0.230601, 0.976142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6059.84898438, 5225.11328125, 167.17447266), 'rotation':(1.009283, 0.22726, 0.974178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6002.58289062, 5216.39501953, 166.16136719), 'rotation':(-1.016693, -179.775345, -1.053253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6012.99984375, 5216.43310547, 166.34599609), 'rotation':(-1.015045, -179.769958, -1.051514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6018.2103125, 5216.45214844, 166.43832031000002), 'rotation':(-1.014893, -179.772995, -1.051331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6023.41882812, 5216.47119141, 166.53060547), 'rotation':(-1.014893, -179.772995, -1.051331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6033.83726562, 5216.50927734, 166.715), 'rotation':(-1.012787, -179.773132, -1.049072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6059.88125, 5216.47705078, 167.17449219), 'rotation':(-1.009369, -179.77272, -1.045441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6126.144375, 5216.84765625, 168.34058593999998), 'rotation':(-1.006989, -179.771362, -1.042877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6131.81921875, 5216.86816406, 168.44037109), 'rotation':(-1.006989, -179.771362, -1.042877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6143.16734375, 5216.91015625, 168.63996093999998), 'rotation':(-1.007477, -179.771423, -1.043365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6160.19078125, 5216.97216797, 168.93949218999998), 'rotation':(-1.00769, -179.771942, -1.04361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6182.88859375, 5217.05566406, 169.33888672), 'rotation':(-1.008392, -179.775314, -1.044373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6194.23671875, 5217.09716797, 169.53896484), 'rotation':(-1.01001, -179.770935, -1.046112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6216.93492188, 5217.18017578, 169.93955078), 'rotation':(-1.010651, -179.77327, -1.046814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6228.28359375, 5217.21923828, 170.13988281000002), 'rotation':(-1.010834, -179.773254, -1.046997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6239.6321875, 5217.27929688, 170.34050781000002), 'rotation':(-1.011719, -179.772202, -1.047913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6245.30601562, 5217.31494141, 170.44095703), 'rotation':(-1.013733, -179.772125, -1.05011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6262.32945312, 5217.37939453, 170.74255859000002), 'rotation':(-1.014618, -179.77182, -1.051056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6273.678125, 5217.42089844, 170.94361328), 'rotation':(-1.01474, -179.77182, -1.051208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6285.0271875, 5217.46289062, 171.14488281), 'rotation':(-1.016388, -179.772797, -1.052979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6097.74203125, 5225.12402344, 167.84175781000002), 'rotation':(1.006818, 0.22537, 0.971892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6103.416875, 5225.14501953, 167.94154297), 'rotation':(1.006968, 0.228632, 0.972038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6126.11414062, 5225.22851562, 168.34058593999998), 'rotation':(1.007091, 0.228553, 0.97214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6131.78890625, 5225.24902344, 168.44037109), 'rotation':(1.007091, 0.228553, 0.97214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6154.48625, 5225.33251953, 168.83966797000002), 'rotation':(1.007678, 0.228063, 0.972687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6165.834375, 5225.37402344, 169.03931641), 'rotation':(1.007576, 0.224968, 0.972593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6171.50914062, 5225.39453125, 169.13916016), 'rotation':(1.007576, 0.224968, 0.972593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6177.18398438, 5225.41552734, 169.23900390999998), 'rotation':(1.008395, 0.229, 0.97335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6182.8578125, 5225.43603516, 169.33888672), 'rotation':(1.010007, 0.229057, 0.974853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6188.53257812, 5225.45703125, 169.43888672), 'rotation':(1.010007, 0.229057, 0.974853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6211.2303125, 5225.54003906, 169.83941406000002), 'rotation':(1.010725, 0.230051, 0.975518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6222.57851562, 5225.58203125, 170.0396875), 'rotation':(1.011701, 0.227793, 0.976435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6233.92710938, 5225.63134766, 170.24013672), 'rotation':(1.013723, 0.227865, 0.978324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6262.29921875, 5225.69433594, 170.74255859000002), 'rotation':(1.014625, 0.228165, 0.979148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6267.97398438, 5225.71533203, 170.84308593999998), 'rotation':(1.014748, 0.22817, 0.979257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6284.99648438, 5225.77734375, 171.14488281), 'rotation':(1.017322, 0.227216, 0.981651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6290.67078125, 5225.79833984, 171.24570312), 'rotation':(1.01849, 0.227257, 0.982741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6339.82265625, 5226.01123047, 172.1203125), 'rotation':(1.020369, 0.226735, 0.984499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6345.34460938, 5226.03125, 172.21869141), 'rotation':(1.020369, 0.226735, 0.984499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6350.86757812, 5226.05175781, 172.31708984), 'rotation':(1.020533, 0.230013, 0.984644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6367.4359375, 5226.11230469, 172.61230468999997), 'rotation':(1.020533, 0.230013, 0.984644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6372.95789062, 5226.1328125, 172.71070312), 'rotation':(1.020533, 0.230013, 0.984644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6378.47984375, 5226.15283203, 172.80910156000002), 'rotation':(1.02043, 0.227561, 0.984543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6400.57019531, 5226.23388672, 173.20267578), 'rotation':(1.020369, 0.225548, 0.984485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6411.61609375, 5226.27441406, 173.39949219), 'rotation':(1.020369, 0.230262, 0.984483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6417.13804688, 5226.29492188, 173.49785156000002), 'rotation':(1.019761, 0.229084, 0.983934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6422.66003906, 5226.31494141, 173.59615234), 'rotation':(1.018231, 0.226046, 0.98251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6428.18296875, 5226.33496094, 173.69439452999998), 'rotation':(1.018231, 0.226046, 0.98251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6433.7059375, 5226.35546875, 173.79257812), 'rotation':(1.016749, 0.228965, 0.981127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6439.22789062, 5226.37548828, 173.890625), 'rotation':(1.01526, 0.228912, 0.979747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6444.75039062, 5226.39550781, 173.98865234000002), 'rotation':(1.01526, 0.228912, 0.979747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6466.84023438, 5226.44580078, 174.38007812), 'rotation':(1.014584, 0.227062, 0.979111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6472.36316406, 5226.46386719, 174.47792969), 'rotation':(1.014659, 0.227084, 0.979179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6328.8084375, 5217.58984375, 171.92365234000002), 'rotation':(-1.019104, -179.76976, -1.055847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6345.37632812, 5217.65087891, 172.21871094), 'rotation':(-1.02002, -179.772354, -1.056854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6356.42175781, 5217.69140625, 172.41550781), 'rotation':(-1.020538, -179.773239, -1.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6367.46667969, 5217.73144531, 172.61230468999997), 'rotation':(-1.020416, -179.773239, -1.057281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6378.51109375, 5217.77197266, 172.80910156000002), 'rotation':(-1.020538, -179.769989, -1.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6389.55652344, 5217.81298828, 173.00589843999998), 'rotation':(-1.020294, -179.772446, -1.057159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6406.124375, 5217.87353516, 173.30109375), 'rotation':(-1.020447, -179.774429, -1.057312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6417.16929688, 5217.9140625, 173.49785156000002), 'rotation':(-1.020355, -179.774445, -1.05722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6433.73671875, 5217.97460938, 173.79257812), 'rotation':(-1.01825, -179.770981, -1.054932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6439.25867188, 5217.99462891, 173.89064453), 'rotation':(-1.016754, -179.774002, -1.053345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6444.78164062, 5218.01464844, 173.98865234000002), 'rotation':(-1.016754, -179.774002, -1.053345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6455.8265625, 5218.046875, 174.18439453), 'rotation':(-1.015259, -179.771088, -1.051727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6461.34949219, 5218.09228516, 174.28226562), 'rotation':(-1.014648, -179.772903, -1.051117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6472.39492188, 5218.14941406, 174.47792969), 'rotation':(-1.014587, -179.772934, -1.051025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.33335938, 5218.25537109, 175.14804688), 'rotation':(-1.00946, -179.76973, -1.045502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6521.61757812, 5218.29638672, 175.34658202999998), 'rotation':(-1.007507, -179.773972, -1.043427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6544.18398438, 5218.37939453, 175.74167968999998), 'rotation':(-0.999695, -179.774246, -1.035065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6555.4671875, 5218.42041016, 175.93828125), 'rotation':(-0.997742, -179.770142, -1.032959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6561.10925781, 5218.44140625, 176.03636719), 'rotation':(-0.995789, -179.774384, -1.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.959375, 5218.56542969, 176.62240234), 'rotation':(-0.985535, -179.773895, -1.019867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6611.88515625, 5218.62695312, 176.91363281000002), 'rotation':(-0.985535, -179.773895, -1.019867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6617.52671875, 5218.64355469, 177.010625), 'rotation':(-0.984436, -179.774368, -1.018738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6628.80992188, 5218.70800781, 177.20390625), 'rotation':(-0.980316, -179.769012, -1.014313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6640.09414062, 5218.76367188, 177.39628906000002), 'rotation':(-0.976227, -179.774658, -1.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6651.37632812, 5218.80517578, 177.58775391), 'rotation':(-0.970062, -179.769363, -1.003326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6662.66101562, 5218.84619141, 177.77871094), 'rotation':(-0.968842, -179.778214, -1.002014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6679.58679688, 5218.90820312, 178.06404297), 'rotation':(-0.962463, -179.775208, -0.995209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6690.86951172, 5218.94970703, 178.25300781), 'rotation':(-0.958038, -179.772202, -0.990509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6702.15417969, 5218.99072266, 178.44089843999998), 'rotation':(-0.953766, -179.775482, -0.985931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6713.43738281, 5219.03222656, 178.62837890999998), 'rotation':(-0.951599, -179.773376, -0.983612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6730.36365234, 5219.09423828, 178.90921875), 'rotation':(-0.948944, -179.773819, -0.980774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6736.00525391, 5219.11474609, 179.00232422000002), 'rotation':(-0.948944, -179.773819, -0.980774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6747.28992188, 5218.98632812, 179.18792968999998), 'rotation':(-0.940674, -179.774475, -0.971954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.303125, 5226.63574219, 175.14804688), 'rotation':(1.007501, 0.230186, 0.972523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6515.94519531, 5226.65625, 175.24738281), 'rotation':(1.007501, 0.230186, 0.972523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6527.22742188, 5226.69775391, 175.44558593999997), 'rotation':(1.003607, 0.225884, 0.968891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6538.51109375, 5226.73925781, 175.64314453), 'rotation':(0.999701, 0.225747, 0.965258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6544.15320312, 5226.75976562, 175.74166015999998), 'rotation':(0.997747, 0.229844, 0.963443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6555.43640625, 5226.80126953, 175.93828125), 'rotation':(0.995801, 0.225614, 0.961618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6572.36171875, 5226.86328125, 176.23234375), 'rotation':(0.994824, 0.225044, 0.960708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6578.00429688, 5226.88378906, 176.33035156000003), 'rotation':(0.990131, 0.22881, 0.956345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6583.64492188, 5226.90429688, 176.42796875), 'rotation':(0.985507, 0.226097, 0.952029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6589.28648438, 5226.92480469, 176.52533203), 'rotation':(0.985507, 0.226097, 0.952029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.928125, 5226.94580078, 176.62240234), 'rotation':(0.985507, 0.226097, 0.952029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6611.85390625, 5227.0078125, 176.91363281000002), 'rotation':(0.984442, 0.225625, 0.951035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6623.13757812, 5227.05810547, 177.10738281000002), 'rotation':(0.980323, 0.225484, 0.947199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6634.42125, 5227.05761719, 177.30019531000002), 'rotation':(0.976212, 0.225341, 0.943363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6640.06335938, 5227.078125, 177.39630859000002), 'rotation':(0.974156, 0.225273, 0.941441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6656.98867188, 5227.14013672, 177.68324219), 'rotation':(0.968828, 0.226553, 0.936475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6662.63074219, 5227.16064453, 177.77871094), 'rotation':(0.966875, 0.228101, 0.934652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6673.91443359, 5227.20214844, 177.96923827999998), 'rotation':(0.962435, 0.224792, 0.930504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6679.55603516, 5227.22314453, 178.06404297), 'rotation':(0.95805, 0.227797, 0.926393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6685.19763672, 5227.24365234, 178.15865234), 'rotation':(0.95805, 0.227797, 0.926393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6707.76550781, 5227.32617188, 178.53462890999998), 'rotation':(0.951596, 0.226618, 0.920364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6730.33386719, 5227.40917969, 178.90921875), 'rotation':(0.943324, 0.225976, 0.912631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6741.61707031, 5227.45068359, 179.09525391), 'rotation':(0.94066, 0.225518, 0.910145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(7006.03748047, 5219.97851562, 183.22103515999999), 'rotation':(-0.829865, -179.778198, -0.854187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6994.71912109, 5220.02978516, 183.05675781000002), 'rotation':(-0.836334, -179.778214, -0.861023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6989.05798828, 5220.00927734, 182.97398438), 'rotation':(-0.840454, -179.778091, -0.865387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6977.73523438, 5219.96777344, 182.80707031000003), 'rotation':(-0.85318, -179.777725, -0.878906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6972.07507812, 5219.94677734, 182.72292968999997), 'rotation':(-0.857574, -179.777557, -0.883545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6955.09167969, 5219.88476562, 182.46789062), 'rotation':(-0.863647, -179.774811, -0.889984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6949.43201172, 5219.86376953, 182.38251953), 'rotation':(-0.866364, -179.777786, -0.892883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6938.10974609, 5219.82226562, 182.21111327999998), 'rotation':(-0.871063, -179.777649, -0.897858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6932.448125, 5219.80175781, 182.125), 'rotation':(-0.876129, -179.777496, -0.903229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6926.78796875, 5219.78076172, 182.03853515999998), 'rotation':(-0.876129, -179.777496, -0.903229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6921.12585938, 5219.76025391, 181.95191406), 'rotation':(-0.880951, -179.774353, -0.908386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6898.48279297, 5219.67724609, 181.60306641), 'rotation':(-0.883423, -179.77684, -0.911011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6875.83923828, 5219.59423828, 181.25136719), 'rotation':(-0.902863, -179.772003, -0.931671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6870.17859375, 5219.57373047, 181.16220703), 'rotation':(-0.905701, -179.777161, -0.934662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6864.51892578, 5219.55273438, 181.07275391), 'rotation':(-0.905579, -179.777161, -0.93454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6847.53552734, 5219.49023438, 180.80423828), 'rotation':(-0.905579, -179.777161, -0.93454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6836.21326172, 5219.44873047, 180.62517577999998), 'rotation':(-0.9086, -179.775253, -0.937744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6830.55310547, 5219.42822266, 180.53525391), 'rotation':(-0.914337, -179.77507, -0.943848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6824.89197266, 5219.40722656, 180.44482422000002), 'rotation':(-0.917328, -179.774597, -0.947052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6813.57019531, 5219.36572266, 180.26349609000002), 'rotation':(-0.917328, -179.774597, -0.947052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6802.25183594, 5219.32226562, 180.08220702999998), 'rotation':(-0.918732, -179.774551, -0.948578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6790.92761719, 5219.15332031, 179.90017577999998), 'rotation':(-0.924469, -179.774353, -0.954681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6796.51794922, 5227.75830078, 179.99068359), 'rotation':(0.918729, 0.220055, 0.889611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6802.17859375, 5227.70800781, 180.08152343999998), 'rotation':(0.917308, 0.225399, 0.888288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6813.49890625, 5227.74658203, 180.26285156000003), 'rotation':(0.91739, 0.225422, 0.888352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6824.82068359, 5227.78808594, 180.44416016), 'rotation':(0.914323, 0.224927, 0.885476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6836.14148438, 5227.82958984, 180.62451172000002), 'rotation':(0.905587, 0.222835, 0.877289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6841.80261719, 5227.85058594, 180.7140625), 'rotation':(0.90569, 0.222842, 0.877384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6847.46375, 5227.87109375, 180.80357422), 'rotation':(0.90569, 0.222842, 0.877384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6864.44714844, 5227.93359375, 181.07210938), 'rotation':(0.90569, 0.222842, 0.877384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6870.10730469, 5227.95410156, 181.1615625), 'rotation':(0.902848, 0.223349, 0.874735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6875.76892578, 5227.97509766, 181.25074218999998), 'rotation':(0.897343, 0.227829, 0.869549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6887.09070312, 5228.01611328, 181.42751952999998), 'rotation':(0.886101, 0.222812, 0.858999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6892.75085938, 5228.03710938, 181.51511718999998), 'rotation':(0.88343, 0.22316, 0.856495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6904.073125, 5228.07861328, 181.68976562), 'rotation':(0.88343, 0.22316, 0.856495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6909.73425781, 5228.09960938, 181.77708984), 'rotation':(0.880958, 0.222652, 0.854175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6921.05701172, 5228.14111328, 181.95132812), 'rotation':(0.876115, 0.225493, 0.849612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6949.3621875, 5228.24560547, 182.38193359000002), 'rotation':(0.86365, 0.225187, 0.837895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6955.02234375, 5228.26904297, 182.46732422000002), 'rotation':(0.863814, 0.219889, 0.838047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6960.68396484, 5228.29394531, 182.55265625), 'rotation':(0.86171, 0.222548, 0.836083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6966.34460938, 5228.29345703, 182.63773438), 'rotation':(0.857496, 0.222404, 0.832111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.23085938, 4171.27539062, 163.59333984), 'rotation':(0.519409, 90.608437, 0.510064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.17078125, 4176.95851562, 163.64426758), 'rotation':(0.519409, 90.608437, 0.510064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.050625, 4188.32570312, 163.74791016), 'rotation':(0.525535, 90.608688, 0.515955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.990625, 4194.00875, 163.80004883), 'rotation':(0.525535, 90.608688, 0.515955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.93101562, 4199.691875, 163.8521875), 'rotation':(0.526293, 90.611145, 0.516703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.8109375, 4211.058125, 163.95671875), 'rotation':(0.529394, 90.611282, 0.519676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6085.69125, 4222.42429688, 164.06183593999998), 'rotation':(0.532768, 90.606194, 0.522927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.57164062, 4233.79054688, 164.16763672000002), 'rotation':(0.535985, 90.606255, 0.526018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.4515625, 4245.1571875, 164.27410156000002), 'rotation':(0.538308, 90.60672, 0.528266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.39195312, 4250.8403125, 164.3275), 'rotation':(0.538192, 90.609932, 0.528165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.271875, 4262.2065625, 164.43431640999998), 'rotation':(0.538868, 90.607475, 0.528798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6085.15171875, 4273.57226562, 164.54128906000003), 'rotation':(0.540698, 90.607506, 0.530572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6085.03210938, 4284.9384375, 164.64869141), 'rotation':(0.54218, 90.611885, 0.532004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.97203125, 4290.6215625, 164.7025), 'rotation':(0.542112, 90.608299, 0.531934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6084.9125, 4296.3046875, 164.75628906000003), 'rotation':(0.542201, 90.608253, 0.532003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6084.85242188, 4301.9878125, 164.81007812), 'rotation':(0.542201, 90.608253, 0.532003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.79234375, 4307.6709375, 164.86386718999998), 'rotation':(0.542201, 90.608253, 0.532003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6084.67273438, 4319.03664062, 164.97140625), 'rotation':(0.541176, 90.60833, 0.531037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.553125, 4330.4028125, 165.07884765999998), 'rotation':(0.540917, 90.607788, 0.530786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.49304688, 4336.0859375, 165.1325), 'rotation':(0.540958, 90.611351, 0.53082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.43296875, 4341.7690625, 165.18617188), 'rotation':(0.540958, 90.611351, 0.53082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.97984375, 4148.63234375, 163.39381836), 'rotation':(-0.501099, -89.394409, -0.509918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.90171875, 4154.31734375, 163.44354492), 'rotation':(-0.50116, -89.389954, -0.509979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.78359375, 4159.99953125, 163.49325195), 'rotation':(-0.50116, -89.389954, -0.509979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.550625, 4177.046875, 163.64426758), 'rotation':(-0.507202, -89.388641, -0.516235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.43101562, 4188.4140625, 163.74792969), 'rotation':(-0.525543, -89.391296, -0.535248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6094.25132812, 4205.46390625, 163.904375), 'rotation':(-0.526367, -89.393921, -0.536102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.19125, 4211.14648438, 163.95671875), 'rotation':(-0.527893, -89.388794, -0.537689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.07164062, 4222.51265625, 164.06183593999998), 'rotation':(-0.531158, -89.388672, -0.541077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.0115625, 4228.19578125, 164.11464844), 'rotation':(-0.532776, -89.393799, -0.542755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.9515625, 4233.87890625, 164.16765625), 'rotation':(-0.53421, -89.388611, -0.54425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.89148438, 4239.56203125, 164.22078125), 'rotation':(-0.53598, -89.38858, -0.546082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.6521875, 4262.29492188, 164.43431640999998), 'rotation':(-0.538208, -89.390045, -0.548401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6093.4125, 4285.026875, 164.64869141), 'rotation':(-0.541687, -89.392456, -0.552032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.35242188, 4290.71, 164.7025), 'rotation':(-0.542206, -89.391724, -0.552521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.2328125, 4302.07617188, 164.81007812), 'rotation':(-0.542114, -89.391724, -0.55246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.053125, 4319.12546875, 164.97140625), 'rotation':(-0.541901, -89.391693, -0.552216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.99304688, 4324.808125, 165.02515625), 'rotation':(-0.541901, -89.391693, -0.552216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.033125, 4379.7075, 165.5415625), 'rotation':(0.528643, 90.61174, 0.518962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.975, 4385.24023438, 165.59271484), 'rotation':(0.528643, 90.61174, 0.518962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.7996875, 4401.83789062, 165.74523438), 'rotation':(0.525201, 90.608971, 0.515636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.7415625, 4407.370625, 165.79597656), 'rotation':(0.525201, 90.608971, 0.515636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.68296875, 4412.90332031, 165.84669922), 'rotation':(0.521068, 90.60952, 0.51165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.50820312, 4429.50046875, 165.99664062), 'rotation':(0.508603, 90.612015, 0.499626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.44960938, 4435.03273438, 166.04582031), 'rotation':(0.508719, 90.608086, 0.499753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.39148438, 4440.56542969, 166.09494141), 'rotation':(0.508719, 90.608086, 0.499753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.15953125, 4456.85644531, 166.23865234000002), 'rotation':(0.497149, 90.606606, 0.48858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.32945312, 4445.79148438, 166.14128906000002), 'rotation':(0.506288, 90.606758, 0.497412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.030625, 4465.24609375, 166.31146484), 'rotation':(0.492532, 90.606476, 0.484128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6082.92171875, 4472.79003906, 166.37621094), 'rotation':(0.488003, 90.610634, 0.479742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.82703125, 4481.79054688, 166.45255859), 'rotation':(0.478858, 90.610481, 0.470901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.73234375, 4490.79148438, 166.52800781000002), 'rotation':(0.474131, 90.606171, 0.466321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6092.29625, 4390.86230469, 165.64371093999998), 'rotation':(-0.528656, -89.392334, -0.538452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.238125, 4396.395, 165.69453125), 'rotation':(-0.526367, -89.392395, -0.536102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.12148438, 4407.4609375, 165.79599609000002), 'rotation':(-0.525177, -89.391052, -0.534851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.00476562, 4418.52492188, 165.89708984), 'rotation':(-0.521088, -89.390472, -0.530609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.94664062, 4424.058125, 165.94714843999998), 'rotation':(-0.521088, -89.390472, -0.530609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.83, 4435.12257812, 166.04583984), 'rotation':(-0.508606, -89.391907, -0.5177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.77140625, 4440.65527344, 166.09496094), 'rotation':(-0.508606, -89.391907, -0.5177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.64882812, 4458.8984375, 166.25566406000002), 'rotation':(-0.501801, -89.393372, -0.510651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.5853125, 4469.96335938, 166.35125), 'rotation':(-0.492554, -89.389343, -0.501068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6091.47789062, 4480.78125, 166.44328125), 'rotation':(-0.488007, -89.393555, -0.496368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.3553125, 4528.25878906, 166.83175781000003), 'rotation':(0.440868, 90.607208, 0.434129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.2875, 4545.24902344, 166.96160156000002), 'rotation':(0.435787, 90.605026, 0.429191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.16835938, 4556.57664062, 167.04720702999998), 'rotation':(0.418308, 90.608009, 0.412234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.9290625, 4579.23289062, 167.21173828), 'rotation':(0.394997, 90.607697, 0.389573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.80992188, 4590.56101562, 167.29), 'rotation':(0.389191, 90.607719, 0.38393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.75039062, 4596.22558594, 167.32845702999998), 'rotation':(0.38566, 90.605774, 0.380507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.57117188, 4613.21777344, 167.44142578), 'rotation':(0.365046, 90.605499, 0.360419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.331875, 4635.87351562, 167.58226562), 'rotation':(0.337534, 90.60524, 0.333579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.97351562, 4669.85789062, 167.77525391), 'rotation':(0.300911, 90.605125, 0.297763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.79484375, 4686.85107422, 167.86181641), 'rotation':(0.278856, 90.604897, 0.276158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.67515625, 4698.17919922, 167.91644531000003), 'rotation':(0.275127, 90.604355, 0.27249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.61515625, 4703.84277344, 167.94326172), 'rotation':(0.267491, 90.605583, 0.265011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.4959375, 4715.17138672, 167.99472656), 'rotation':(0.236741, 90.605309, 0.234786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.376875, 4726.50048828, 168.04251953), 'rotation':(0.221271, 90.605217, 0.219563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.25765625, 4737.828125, 168.08650391), 'rotation':(0.21358, 90.601303, 0.212003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6080.19765625, 4743.49267578, 168.10759765999998), 'rotation':(0.213764, 90.606247, 0.212178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.92515625, 4529.57128906, 166.84117188), 'rotation':(-0.451141, -89.392639, -0.458313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.72742188, 4539.671875, 166.91851562), 'rotation':(-0.435669, -89.39151, -0.442352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.60828125, 4551.00097656, 167.00466797), 'rotation':(-0.435791, -89.391541, -0.442444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6090.4290625, 4567.99265625, 167.13080078), 'rotation':(-0.418304, -89.391998, -0.424438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6090.30945312, 4579.32078125, 167.21173828), 'rotation':(-0.406555, -89.392151, -0.412384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.13023438, 4596.31296875, 167.32845702999998), 'rotation':(-0.389191, -89.395538, -0.394501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.95109375, 4613.30566406, 167.44142578), 'rotation':(-0.371857, -89.394348, -0.376709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.831875, 4624.6328125, 167.51326172), 'rotation':(-0.358124, -89.394562, -0.36264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.77234375, 4630.296875, 167.54810547), 'rotation':(-0.351379, -89.394653, -0.355682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.65273438, 4641.62546875, 167.61568359), 'rotation':(-0.337524, -89.389587, -0.341553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.59265625, 4647.28953125, 167.64875), 'rotation':(-0.334045, -89.397095, -0.337952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6089.533125, 4652.953125, 167.68148438), 'rotation':(-0.3302, -89.394531, -0.334045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.47351562, 4658.61765625, 167.71355469), 'rotation':(-0.32312, -89.389313, -0.326752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6089.41390625, 4664.28222656, 167.74480469), 'rotation':(-0.315582, -89.394714, -0.319061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6089.35390625, 4669.9453125, 167.77525391), 'rotation':(-0.308289, -89.394836, -0.311615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.29429688, 4675.60986328, 167.80488281), 'rotation':(-0.300903, -89.394897, -0.304077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.23421875, 4681.2734375, 167.83375), 'rotation':(-0.293518, -89.394958, -0.296509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.11515625, 4692.60205078, 167.88923828), 'rotation':(-0.27887, -89.395081, -0.281586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6088.9359375, 4709.59570312, 167.9696875), 'rotation':(-0.267487, -89.397522, -0.269989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6088.87632812, 4715.25927734, 167.99472656), 'rotation':(-0.252136, -89.394531, -0.254364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6088.69664062, 4732.25195312, 168.06476562), 'rotation':(-0.236755, -89.394684, -0.238708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6088.57796875, 4743.58056641, 168.10759765999998), 'rotation':(-0.213593, -89.393799, -0.215179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.00820312, 5046.02929688, 168.19578125), 'rotation':(-0.158203, 90.606834, -0.159088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.18640625, 5029.13720703, 168.2415625), 'rotation':(-0.152863, 90.60466, -0.153656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.24546875, 5023.50634766, 168.25550781), 'rotation':(-0.141815, 90.604614, -0.142517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.36460938, 5012.24462891, 168.28195312), 'rotation':(-0.130951, 90.604553, -0.131561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.48328125, 5000.98339844, 168.30582031000003), 'rotation':(-0.120087, 90.604485, -0.120605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.541875, 4995.35302734, 168.31693359000002), 'rotation':(-0.114563, 90.604462, -0.115051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.60140625, 4989.72265625, 168.32751953), 'rotation':(-0.11026, 90.60331, -0.110687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.72007812, 4978.46044922, 168.34632812), 'rotation':(-0.093353, 90.607986, -0.093658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.89828125, 4961.56933594, 168.36861327999998), 'rotation':(-0.067963, 90.60321, -0.068146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.01695312, 4950.30712891, 168.37945312), 'rotation':(-0.050903, 90.607887, -0.050995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6078.19515625, 4933.41455078, 168.39326172), 'rotation':(-0.046844, 90.603226, -0.046906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.314375, 4922.15478516, 168.40109375), 'rotation':(-0.046722, 90.603226, -0.046783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.3734375, 4916.52539062, 168.40189453), 'rotation':(-0.017975, 90.60463, -0.017975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.49203125, 4905.26318359, 168.39976562), 'rotation':(0.010867, 90.609085, 0.010875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.55164062, 4899.63183594, 168.39867188), 'rotation':(0.011044, 90.603653, 0.011043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.78890625, 4877.10888672, 168.39435547000002), 'rotation':(0.010874, 90.603653, 0.010873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.9671875, 4860.21630859, 168.38464843999998), 'rotation':(0.039239, 90.604042, 0.039196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.08578125, 4848.95507812, 168.37140625), 'rotation':(0.076881, 90.604126, 0.076681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.20445312, 4837.69482422, 168.35478516), 'rotation':(0.086457, 90.605026, 0.086203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.2640625, 4832.06445312, 168.34623047000002), 'rotation':(0.086334, 90.604988, 0.086081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.323125, 4826.43359375, 168.33701172000002), 'rotation':(0.093792, 90.601875, 0.093483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.5609375, 4803.91064453, 168.28992188), 'rotation':(0.138591, 90.60202, 0.137927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6079.67953125, 4792.64990234, 168.26154297000002), 'rotation':(0.146016, 90.603149, 0.145274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6079.68984375, 4781.39111328, 168.23222656000002), 'rotation':(0.15217, 90.603111, 0.151361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.94078125, 4803.99951172, 168.28992188), 'rotation':(-0.146027, -89.39682, -0.146759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.70351562, 4826.52246094, 168.33701172000002), 'rotation':(-0.108765, -89.398102, -0.109161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.58484375, 4837.78369141, 168.35478516), 'rotation':(-0.086334, -89.394989, -0.086609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.5253125, 4843.41455078, 168.36328125), 'rotation':(-0.086456, -89.398926, -0.086731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.2284375, 4871.56640625, 168.39234375), 'rotation':(-0.039246, -89.392273, -0.039307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.050625, 4888.45800781, 168.39652343999998), 'rotation':(-0.011047, -89.396362, -0.011047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.99109375, 4894.08886719, 168.39757812), 'rotation':(-0.010895, -89.396393, -0.010864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.87242188, 4905.35107422, 168.39976562), 'rotation':(-0.011047, -89.396362, -0.011047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.75328125, 4916.61328125, 168.40189453), 'rotation':(-0.010895, -89.396332, -0.010895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.69421875, 4922.24316406, 168.40109375), 'rotation':(0.01795, -89.395386, 0.01795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.57554688, 4933.50292969, 168.39326172), 'rotation':(0.046705, -89.396759, 0.046633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.456875, 4944.76513672, 168.3840625), 'rotation':(0.046835, -89.392334, 0.046775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.21960938, 4967.2890625, 168.36199219), 'rotation':(0.06796, -89.396851, 0.067799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.16, 4972.91894531, 168.35455077999998), 'rotation':(0.076423, -89.392059, 0.076217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.10046875, 4978.54882812, 168.34632812), 'rotation':(0.084879, -89.39679, 0.08463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.92226562, 4995.44091797, 168.31693359000002), 'rotation':(0.110253, -89.396729, 0.109829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.863125, 5001.07177734, 168.30582031000003), 'rotation':(0.114583, -89.395538, 0.114124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.80359375, 5006.70214844, 168.29404297000002), 'rotation':(0.120095, -89.395508, 0.119589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.68492188, 5017.96386719, 168.26908203), 'rotation':(0.130955, -89.395447, 0.130356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.56625, 5029.22509766, 168.2415625), 'rotation':(0.141802, -89.395386, 0.141109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.4471875, 5040.48632812, 168.21134766), 'rotation':(0.152866, -89.395325, 0.152045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.38804688, 5046.1171875, 168.19578125), 'rotation':(0.158214, -89.393158, 0.157345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.44125, 5194.68115234, 167.63638672000002), 'rotation':(-0.256958, 90.605675, -0.259277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.49984375, 5189.1484375, 167.66113281000003), 'rotation':(-0.256134, 90.605164, -0.258453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6075.79140625, 5161.48291016, 167.78134766), 'rotation':(-0.24353, 90.607712, -0.245605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.84953125, 5155.95019531, 167.80451172000002), 'rotation':(-0.240631, 90.602234, -0.242645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.96617188, 5144.88427734, 167.85003906000003), 'rotation':(-0.235107, 90.60218, -0.23703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.02382812, 5139.35107422, 167.87261718999997), 'rotation':(-0.233765, 90.609047, -0.235687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.54875, 5089.55371094, 168.05996094), 'rotation':(-0.202179, 90.605797, -0.203613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.8709375, 5095.17382812, 168.04042969), 'rotation':(0.202174, -89.398438, 0.200752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.57898438, 5122.83886719, 167.93871094), 'rotation':(0.214092, -89.397247, 0.212492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.4628125, 5133.90478516, 167.89498047), 'rotation':(0.229884, -89.394104, 0.228038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.40421875, 5139.4375, 167.87263672), 'rotation':(0.229884, -89.394104, 0.228038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.345625, 5144.97119141, 167.85005859), 'rotation':(0.233756, -89.396179, 0.231866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.93789062, 5183.70166016, 167.68576172000002), 'rotation':(0.251829, -89.392151, 0.249618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.9828125, 5238.13818359, 167.43830078), 'rotation':(-0.266113, 90.602806, -0.268616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.92320312, 5243.77490234, 167.41210938), 'rotation':(-0.266632, 90.605278, -0.269104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.86414062, 5249.41162109, 167.38585938), 'rotation':(-0.266602, 90.605225, -0.269104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.745, 5260.68457031, 167.33339844), 'rotation':(-0.266174, 90.605484, -0.268646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6074.32945312, 5300.14111328, 167.15101562), 'rotation':(-0.263, 90.603928, -0.265411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.26992188, 5305.77783203, 167.12515625), 'rotation':(-0.25943, 90.606972, -0.26178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.2103125, 5311.41455078, 167.09955078), 'rotation':(-0.25943, 90.606972, -0.26178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.15125, 5317.05078125, 167.07408203), 'rotation':(-0.256165, 90.603851, -0.258453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.9725, 5333.96046875, 166.99902343999997), 'rotation':(-0.250885, 90.602043, -0.253113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.8534375, 5345.234375, 166.94960938), 'rotation':(-0.247772, 90.604942, -0.249908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.79429688, 5350.8715625, 166.92515625), 'rotation':(-0.247772, 90.604942, -0.249908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.67515625, 5362.145, 166.87707031000002), 'rotation':(-0.234894, 90.604828, -0.236816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6073.31875, 5395.96582031, 166.74109375), 'rotation':(-0.2211, 90.605103, -0.222839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.14046875, 5412.87648438, 166.67693359), 'rotation':(-0.204498, 90.604988, -0.205994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.0809375, 5418.51320312, 166.65650391), 'rotation':(-0.204498, 90.604988, -0.205994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.02140625, 5424.14941406, 166.63640625), 'rotation':(-0.196106, 90.604889, -0.197449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6072.84265625, 5441.06054688, 166.57894531000002), 'rotation':(-0.189026, 90.605995, -0.190277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6072.60484375, 5463.609375, 166.50789062), 'rotation':(-0.165527, 90.605827, -0.166473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6072.36757812, 5486.15773438, 166.44625), 'rotation':(-0.144958, 90.604851, -0.145691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6080.62875, 5497.52148438, 166.41773438), 'rotation':(0.144827, -89.395142, 0.144087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.68835938, 5491.88476562, 166.43199219), 'rotation':(0.144964, -89.399384, 0.144234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.74796875, 5486.24804688, 166.44625), 'rotation':(0.14771, -89.394226, 0.146949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.8665625, 5474.97414062, 166.47589843999998), 'rotation':(0.159546, -89.394135, 0.158665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.92617188, 5469.33691406, 166.49158203), 'rotation':(0.165523, -89.3992, 0.164569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.04484375, 5458.06296875, 166.52476562), 'rotation':(0.17736, -89.394043, 0.176272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.104375, 5452.42625, 166.54224609000002), 'rotation':(0.183179, -89.394043, 0.18201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.16390625, 5446.7890625, 166.5603125), 'rotation':(0.189019, -89.399048, 0.18777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.40125, 5424.24121094, 166.63638672000002), 'rotation':(0.204516, -89.39502, 0.203054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.46078125, 5418.60449219, 166.65648438), 'rotation':(0.212801, -89.394989, 0.21123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.52039062, 5412.96828125, 166.67691406000003), 'rotation':(0.212801, -89.394989, 0.21123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.69859375, 5396.05761719, 166.74107422), 'rotation':(0.225294, -89.399109, 0.223524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.81773438, 5384.78417969, 166.78539062), 'rotation':(0.228415, -89.395203, 0.226602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.876875, 5379.14746094, 166.80785156000002), 'rotation':(0.234897, -89.395172, 0.232982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.05554688, 5362.23679688, 166.87705078), 'rotation':(0.241358, -89.395142, 0.239334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.1746875, 5350.96386719, 166.92513672), 'rotation':(0.25103, -89.397949, 0.248833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.29335938, 5339.69042969, 166.97429688), 'rotation':(0.25088, -89.393524, 0.248704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.41203125, 5328.41648438, 167.02386718999998), 'rotation':(0.256153, -89.393036, 0.253864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.4715625, 5322.78027344, 167.04886718999998), 'rotation':(0.256153, -89.393036, 0.253864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6082.76890625, 5294.59765625, 167.17697266), 'rotation':(0.264608, -89.393311, 0.262185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.88757812, 5283.32421875, 167.22904297000002), 'rotation':(0.264636, -89.39325, 0.262203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.9471875, 5277.6875, 167.25507812), 'rotation':(0.264622, -89.397583, 0.26219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.18492188, 5255.14111328, 167.35960938), 'rotation':(0.266623, -89.394714, 0.264153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.24453125, 5249.50439453, 167.38583984000002), 'rotation':(0.266623, -89.394714, 0.264153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.363125, 5238.23144531, 167.43830078), 'rotation':(0.264923, -89.397217, 0.262468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6071.70640625, 5536.56007812, 166.33707031000003), 'rotation':(-0.099609, 90.604362, -0.099945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6071.7328125, 5546.38039062, 166.32013672000002), 'rotation':(-0.09259, 90.603531, -0.092865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.6746875, 5551.90382812, 166.31121094), 'rotation':(-0.078033, 90.603493, -0.078278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6071.44125, 5574.0, 166.28560547), 'rotation':(-0.042175, 90.602852, -0.042236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.32507812, 5585.04882812, 166.27724609), 'rotation':(-0.042175, 90.602852, -0.042236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.1503125, 5601.62011719, 166.26503906000002), 'rotation':(-0.029114, 90.601044, -0.029144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.03359375, 5612.66992188, 166.26080077999998), 'rotation':(-0.002991, 90.604988, -0.002991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.91734375, 5623.71875, 166.26189452999998), 'rotation':(0.010006, 90.60228, 0.010001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.85875, 5629.2421875, 166.26287109), 'rotation':(0.010006, 90.60228, 0.010001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.800625, 5634.76609375, 166.26382812), 'rotation':(0.010006, 90.605232, 0.009994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6070.27625, 5684.48195312, 166.28697266), 'rotation':(0.069326, 90.605133, 0.069166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.218125, 5690.006875, 166.29333984000002), 'rotation':(0.069176, 90.605133, 0.069009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.10195312, 5701.05515625, 166.30691406000003), 'rotation':(0.073363, 90.603455, 0.073175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6080.345625, 5536.65136719, 166.33707031000003), 'rotation':(0.099693, -89.39563, 0.09936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.1278125, 5545.2421875, 166.32212891), 'rotation':(0.099598, -89.39563, 0.09926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.87976562, 5568.56542969, 166.29035156), 'rotation':(0.06376, -89.396484, 0.063634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6079.82164062, 5574.08886719, 166.28560547), 'rotation':(0.049375, -89.396545, 0.049284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.705, 5585.13769531, 166.27724609), 'rotation':(0.04219, -89.397156, 0.042124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.35585938, 5618.28367188, 166.26091797), 'rotation':(0.002992, -89.39502, 0.002981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.24109375, 5629.33203125, 166.26287109), 'rotation':(-0.01001, -89.397675, -0.01001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.00625, 5651.42578125, 166.26669922000002), 'rotation':(-0.01001, -89.394775, -0.01001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.94765625, 5656.95070312, 166.26794922000002), 'rotation':(-0.01001, -89.394775, -0.01001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.88953125, 5662.47414062, 166.26962891), 'rotation':(-0.017395, -89.394653, -0.017395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6078.65664062, 5684.57078125, 166.28697266), 'rotation':(-0.061768, -89.394592, -0.06192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.42375, 5706.66703125, 166.31414062), 'rotation':(-0.073364, -89.396545, -0.073547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6067.666875, 5932.04882812, 166.89994141), 'rotation':(0.17042, 90.602409, 0.169399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6067.84609375, 5915.01320312, 166.84867188), 'rotation':(0.173255, 90.603256, 0.172211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6067.90609375, 5909.335, 166.83136718999998), 'rotation':(0.175276, 90.603218, 0.174206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.02578125, 5897.97804688, 166.79634765999998), 'rotation':(0.177496, 90.603294, 0.176396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6068.26546875, 5875.26414062, 166.72558593999997), 'rotation':(0.177817, 90.605766, 0.176715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.32507812, 5869.58546875, 166.70808594), 'rotation':(0.177817, 90.605766, 0.176715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.4446875, 5858.22804688, 166.67357422), 'rotation':(0.172551, 90.605736, 0.171516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.50476562, 5852.54929688, 166.65654297), 'rotation':(0.172551, 90.605736, 0.171516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.624375, 5841.191875, 166.62296875), 'rotation':(0.168542, 90.602882, 0.167562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6068.86367188, 5818.4765625, 166.55736328), 'rotation':(0.160093, 90.603386, 0.159211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6069.22304688, 5784.40382812, 166.46757811999998), 'rotation':(0.145941, 90.602493, 0.145196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6069.283125, 5778.72507812, 166.45347656), 'rotation':(0.143632, 90.608459, 0.142914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6069.34265625, 5773.0459375, 166.43988281000003), 'rotation':(0.139008, 90.602951, 0.138338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6069.40273438, 5767.36765625, 166.42677734), 'rotation':(0.129938, 90.608391, 0.12935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6069.58242188, 5750.33109375, 166.39044922000002), 'rotation':(0.116243, 90.602844, 0.115775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.2259375, 5915.1015625, 166.84867188), 'rotation':(-0.174103, -89.391296, -0.175171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.28601562, 5909.42335938, 166.83136718999998), 'rotation':(-0.176483, -89.396698, -0.177551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.34609375, 5903.74515625, 166.81392577999998), 'rotation':(-0.17749, -89.396729, -0.178589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.52578125, 5886.70898438, 166.7609375), 'rotation':(-0.179077, -89.392822, -0.180206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.5853125, 5881.03078125, 166.74320312), 'rotation':(-0.177826, -89.397339, -0.178925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6076.70546875, 5869.67335938, 166.70808594), 'rotation':(-0.175079, -89.394226, -0.176147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.765, 5863.99460938, 166.69072266), 'rotation':(-0.172546, -89.394257, -0.173584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6076.88515625, 5852.63765625, 166.6565625), 'rotation':(-0.16983, -89.397369, -0.170837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.00476562, 5841.27976562, 166.62296875), 'rotation':(-0.168549, -89.397095, -0.169556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.064375, 5835.6015625, 166.60626953), 'rotation':(-0.165741, -89.396576, -0.166718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.18398438, 5824.24414062, 166.57328125), 'rotation':(-0.160095, -89.393707, -0.161011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.2440625, 5818.56492188, 166.55736328), 'rotation':(-0.154388, -89.396667, -0.155212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.3040625, 5812.88671875, 166.54160156), 'rotation':(-0.154388, -89.396667, -0.155212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.42375, 5801.52882812, 166.51126953), 'rotation':(-0.148712, -89.396667, -0.149506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.54335938, 5790.17140625, 166.48201172), 'rotation':(-0.143646, -89.397003, -0.144348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.6634375, 5778.8134375, 166.45347656), 'rotation':(-0.139008, -89.391571, -0.139679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.72304688, 5773.13429688, 166.43988281000003), 'rotation':(-0.134552, -89.397034, -0.135193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.783125, 5767.45609375, 166.42677734), 'rotation':(-0.125305, -89.397095, -0.125854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.08242188, 5739.0615625, 166.36849609), 'rotation':(-0.109344, -89.395691, -0.109772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6062.39, 5074.85791016, 167.78097656000003), 'rotation':(1.058727, 0.745556, 1.020129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6056.95640625, 5074.71582031, 167.68048828), 'rotation':(1.058645, 0.745488, 1.020046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.5184375, 5074.64697266, 167.57986327999998), 'rotation':(1.059403, 0.744604, 1.020755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6046.08, 5074.578125, 167.47912109), 'rotation':(1.06066, 0.7446, 1.021911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6040.64148438, 5074.50927734, 167.37826172), 'rotation':(1.061992, 0.744644, 1.023154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6024.32703125, 5074.30224609, 167.07509765999998), 'rotation':(1.064867, 0.749069, 1.025818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6062.4915625, 5066.33056641, 167.78085938), 'rotation':(-1.058746, -179.25444, -1.098419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.6053125, 5066.265625, 167.57951172), 'rotation':(-1.060669, -179.255402, -1.100525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6040.71671875, 5066.12792969, 167.37769531), 'rotation':(-1.063416, -179.255249, -1.103455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.38367188, 5065.92089844, 167.07416016), 'rotation':(-1.065979, -179.255203, -1.106232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6018.939375, 5065.85205078, 166.97277343999997), 'rotation':(-1.067444, -179.255142, -1.107788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.1971875, 5066.83544922, 168.58658203), 'rotation':(-1.05368, -179.254761, -1.092957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6128.97351562, 5067.24560547, 169.00542968999997), 'rotation':(-1.05246, -179.254654, -1.091675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6157.448125, 5067.60644531, 169.52734375), 'rotation':(-1.049225, -179.253174, -1.088196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6168.83828125, 5067.75097656, 169.73603516), 'rotation':(-1.049225, -179.253174, -1.088196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.92320312, 5067.96728516, 170.04845702999998), 'rotation':(-1.045654, -179.255829, -1.084381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6197.31335938, 5068.11132812, 170.25644531), 'rotation':(-1.045807, -179.25293, -1.084534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6203.00867188, 5068.18310547, 170.36042969), 'rotation':(-1.045227, -179.258408, -1.083893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6220.09265625, 5068.42626953, 170.67199218999997), 'rotation':(-1.044128, -179.253647, -1.082733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6231.4828125, 5068.57714844, 170.87939452999998), 'rotation':(-1.042816, -179.253708, -1.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6237.17765625, 5068.64941406, 170.98298828), 'rotation':(-1.04184, -179.253799, -1.080261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6248.56773438, 5068.79345703, 171.19001953), 'rotation':(-1.040619, -179.253784, -1.078918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6254.26257812, 5068.86572266, 171.29345702999998), 'rotation':(-1.040375, -179.25415, -1.078674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6259.95742188, 5068.93798828, 171.39691406000003), 'rotation':(-1.040253, -179.257568, -1.078552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6265.65273438, 5069.00976562, 171.5003125), 'rotation':(-1.040253, -179.257568, -1.078552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6271.3475, 5069.08203125, 171.60365234), 'rotation':(-1.039001, -179.255692, -1.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.77820312, 5077.79101562, 172.11986328), 'rotation':(1.035648, 0.743526, 0.998706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6294.08335938, 5077.71923828, 172.01685547), 'rotation':(1.035525, 0.743523, 0.998582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6282.69328125, 5077.57470703, 171.81087890999999), 'rotation':(1.035648, 0.743526, 0.998706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6248.52328125, 5077.14208984, 171.19113281000003), 'rotation':(1.04034, 0.745846, 1.003066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6231.43835938, 5076.92578125, 170.88050781), 'rotation':(1.041843, 0.746208, 1.004449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6225.74351562, 5076.85351562, 170.77685547000002), 'rotation':(1.042806, 0.7463, 1.005357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6208.65859375, 5076.63720703, 170.46544922), 'rotation':(1.044725, 0.746368, 1.007138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6191.5740625, 5076.42089844, 170.15357422), 'rotation':(1.045736, 0.747036, 1.008079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.87929688, 5076.34912109, 170.04958984), 'rotation':(1.045736, 0.747036, 1.008079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6180.18445312, 5076.27685547, 169.94560547), 'rotation':(1.045654, 0.744167, 1.007997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6174.48914062, 5076.20458984, 169.84142577999998), 'rotation':(1.047567, 0.74588, 1.009773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6163.09898438, 5076.06005859, 169.6328125), 'rotation':(1.049172, 0.743487, 1.01125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6157.40421875, 5075.98828125, 169.52847656000003), 'rotation':(1.049329, 0.743532, 1.011406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6151.709375, 5075.91601562, 169.42414062), 'rotation':(1.049329, 0.743532, 1.011406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6123.23421875, 5075.55517578, 168.90193359), 'rotation':(1.052464, 0.745328, 1.014313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.15273438, 5075.45996094, 168.58777343999998), 'rotation':(1.053536, 0.745217, 1.015306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6100.45351562, 5075.39648438, 168.48291016), 'rotation':(1.053584, 0.745172, 1.015347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.21960938, 5744.12304688, 170.32771484), 'rotation':(0.165837, 90.901688, 0.16488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.0409375, 5755.49460938, 170.36085938), 'rotation':(0.171451, 90.90181, 0.17043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6300.9515625, 5761.18015625, 170.37798827999998), 'rotation':(0.183008, 90.898155, 0.18186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.7728125, 5772.55078125, 170.41517578), 'rotation':(0.205876, 90.898323, 0.204408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.6834375, 5778.23632812, 170.43501952999998), 'rotation':(0.205876, 90.898323, 0.204408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.59414062, 5783.92234375, 170.45556641), 'rotation':(0.211633, 90.90448, 0.210086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6300.50523438, 5789.60789062, 170.4765625), 'rotation':(0.211633, 90.899513, 0.210079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.3265625, 5800.97898438, 170.51896484), 'rotation':(0.219235, 90.9039, 0.21757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6299.79039062, 5835.0903125, 170.6578125), 'rotation':(0.249944, 90.899178, 0.247776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.4325, 5857.83203125, 170.75818359000002), 'rotation':(0.260647, 90.900993, 0.258272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6299.25429688, 5869.20265625, 170.8103125), 'rotation':(0.271391, 90.9011, 0.268829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.07554688, 5880.57328125, 170.86398438), 'rotation':(0.274171, 90.901024, 0.27156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.98625, 5886.25828125, 170.89121093999998), 'rotation':(0.27415, 90.900963, 0.271545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.896875, 5891.94335938, 170.91841797), 'rotation':(0.274287, 90.901009, 0.271679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6298.718125, 5903.3134375, 170.97283202999998), 'rotation':(0.27415, 90.900963, 0.271545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.62929688, 5908.99851562, 171.00003906), 'rotation':(0.276507, 90.90287, 0.273853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.53992188, 5914.6840625, 171.0275), 'rotation':(0.278938, 90.900658, 0.276238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.08140625, 5935.64695312, 171.12943359000002), 'rotation':(0.278918, 90.904465, 0.276223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.720625, 5935.69234375, 171.12900391), 'rotation':(-0.278809, -89.099365, -0.281525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.8690625, 5918.32179688, 171.04443359), 'rotation':(-0.27652, -89.10022, -0.279205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.7928125, 5929.69289062, 171.09978515999998), 'rotation':(-0.278809, -89.099365, -0.281525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.00820312, 5909.13375, 171.00005859), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.0975, 5903.44828125, 170.97283202999998), 'rotation':(-0.274292, -89.095184, -0.276917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.186875, 5897.76320312, 170.945625), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.27625, 5892.078125, 170.91841797), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.365625, 5886.39304688, 170.89121093999998), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.54429688, 5875.0225, 170.83699219), 'rotation':(-0.266022, -89.098938, -0.268494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.7225, 5863.651875, 170.78404297), 'rotation':(-0.26062, -89.098999, -0.263031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.811875, 5857.96679688, 170.75818359000002), 'rotation':(-0.255005, -89.09906, -0.257294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.90125, 5852.28171875, 170.73285156000003), 'rotation':(-0.25238, -89.10144, -0.254608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6308.34851562, 5823.85351562, 170.60949218999997), 'rotation':(-0.234436, -89.100922, -0.236359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.43734375, 5818.16890625, 170.58611327999998), 'rotation':(-0.229462, -89.096069, -0.231293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.52671875, 5812.484375, 170.56322265999998), 'rotation':(-0.224365, -89.101013, -0.226135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.61609375, 5806.79835938, 170.54083984000002), 'rotation':(-0.219238, -89.096069, -0.220917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.70546875, 5801.11328125, 170.51898438), 'rotation':(-0.214111, -89.101166, -0.215729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.88414062, 5789.74125, 170.47658203), 'rotation':(-0.211639, -89.100494, -0.213196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.97351562, 5784.05664062, 170.45556641), 'rotation':(-0.205872, -89.0979, -0.207367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6309.06289062, 5778.37015625, 170.43501952999998), 'rotation':(-0.194427, -89.098022, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6309.2415625, 5766.9990625, 170.39613281), 'rotation':(-0.183014, -89.101837, -0.184174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6309.41984375, 5755.6284375, 170.36087891), 'rotation':(-0.165833, -89.098328, -0.166809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.87875, 5700.68898438, 170.22242188), 'rotation':(0.113053, 90.898552, 0.112605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.98867188, 5695.16554688, 170.21191406000003), 'rotation':(0.113053, 90.898552, 0.112605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.1625, 5684.11375, 170.19201172), 'rotation':(0.098444, 90.900833, 0.098112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.24890625, 5678.58789062, 170.18363281), 'rotation':(0.098444, 90.900833, 0.098112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.5096875, 5662.01078125, 170.16597656000002), 'rotation':(0.043433, 90.900742, 0.043368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6302.76992188, 5645.43457031, 170.15564453), 'rotation':(0.034247, 90.898438, 0.034214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.85632812, 5639.90917969, 170.15234375), 'rotation':(0.034247, 90.902122, 0.034209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.03015625, 5628.85695312, 170.14587891), 'rotation':(0.034247, 90.898438, 0.034214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.1165625, 5623.33203125, 170.14404297000002), 'rotation':(0.018824, 90.900299, 0.018826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.29039062, 5612.27882812, 170.14630859000002), 'rotation':(-0.012177, 90.900337, -0.012177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6303.37734375, 5606.7534375, 170.14896484000002), 'rotation':(-0.027527, 90.898773, -0.027557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.72453125, 5584.6528125, 170.15960938), 'rotation':(-0.027527, 90.898827, -0.027557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.81140625, 5579.12792969, 170.16228515999998), 'rotation':(-0.027618, 90.898773, -0.027649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.98476562, 5568.07570312, 170.17066406), 'rotation':(-0.046448, 90.901329, -0.046539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.15859375, 5557.02195312, 170.18662109000002), 'rotation':(-0.08432, 90.898605, -0.084564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.41882812, 5540.44679688, 170.21648438), 'rotation':(-0.103241, 90.898819, -0.103607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.3040625, 5700.82078125, 170.22242188), 'rotation':(-0.107605, -89.098602, -0.108002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.62828125, 5678.71921875, 170.18363281), 'rotation':(-0.080139, -89.099213, -0.080383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.23570312, 5640.04003906, 170.15234375), 'rotation':(-0.034241, -89.097809, -0.034271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.32265625, 5634.51515625, 170.14904297), 'rotation':(-0.034241, -89.097809, -0.034271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.40953125, 5628.9878125, 170.14587891), 'rotation':(-0.01886, -89.099701, -0.018829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.4959375, 5623.46289062, 170.14404297000002), 'rotation':(0.012158, -89.099701, 0.012155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.84359375, 5601.35984375, 170.15162109000002), 'rotation':(0.027621, -89.101166, 0.027595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.93007812, 5595.83445312, 170.15429688), 'rotation':(0.027512, -89.098206, 0.027505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.10390625, 5584.78417969, 170.15960938), 'rotation':(0.027621, -89.101166, 0.027595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.19078125, 5579.25929688, 170.16228515999998), 'rotation':(0.046473, -89.098663, 0.046396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.71179688, 5546.10253906, 170.20652343999998), 'rotation':(0.103245, -89.101166, 0.10286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.99890625, 5248.92626953, 171.49783202999998), 'rotation':(-0.329773, 90.902222, -0.333588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6308.91, 5254.56396484, 171.46537109000002), 'rotation':(-0.329865, 90.899261, -0.333679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6308.644375, 5271.47802734, 171.36806640999998), 'rotation':(-0.326752, 90.901352, -0.330505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.9359375, 5316.58203125, 171.11412109), 'rotation':(-0.312744, 90.902184, -0.316162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6307.75867188, 5327.85890625, 171.05234375), 'rotation':(-0.307037, 90.902153, -0.310333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.49304688, 5344.77296875, 170.96234375), 'rotation':(-0.298553, 90.900734, -0.301666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6307.31578125, 5356.04929688, 170.90345703), 'rotation':(-0.298462, 90.900803, -0.301575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6307.22742188, 5361.6875, 170.87408202999998), 'rotation':(-0.294342, 90.901489, -0.297394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.96179688, 5378.60253906, 170.78859375), 'rotation':(-0.277863, 90.901321, -0.280548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.78453125, 5389.87890625, 170.73478516), 'rotation':(-0.265533, 90.904068, -0.267975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.60734375, 5401.15625, 170.68244141), 'rotation':(-0.265503, 90.900429, -0.267975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.51890625, 5406.79492188, 170.65636718999997), 'rotation':(-0.259613, 90.900574, -0.261963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.34171875, 5418.07179688, 170.60578125), 'rotation':(-0.247925, 90.900459, -0.250092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.16445312, 5429.348125, 170.55785156000002), 'rotation':(-0.236145, 90.900352, -0.238098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.98671875, 5440.62453125, 170.51263672000002), 'rotation':(-0.218628, 90.90033, -0.220276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.89828125, 5446.26320312, 170.49078125), 'rotation':(-0.218628, 90.90033, -0.220276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.72109375, 5457.54101562, 170.44800781), 'rotation':(-0.20813, 90.899536, -0.209656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.63265625, 5463.1796875, 170.42746093999997), 'rotation':(-0.201233, 90.899399, -0.202637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6313.65757812, 5485.86816406, 170.35302734), 'rotation':(0.180549, -89.100708, 0.179423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.74648438, 5480.22949219, 170.37050781000002), 'rotation':(0.187291, -89.100616, 0.186072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6313.92320312, 5468.953125, 170.40771484), 'rotation':(0.201231, -89.100586, 0.199822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6314.10046875, 5457.67625, 170.44800781), 'rotation':(0.215199, -89.100403, 0.213598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.27773438, 5446.39890625, 170.49076172000002), 'rotation':(0.224563, -89.09671, 0.222819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.63265625, 5423.84570312, 170.58134766), 'rotation':(0.247929, -89.099518, 0.24579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.89828125, 5406.93117188, 170.65634766), 'rotation':(0.26551, -89.099548, 0.263066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.98671875, 5401.2925, 170.68242188), 'rotation':(0.265503, -89.095917, 0.26306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.16390625, 5390.01515625, 170.73476562), 'rotation':(0.269601, -89.098755, 0.267071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.25234375, 5384.37742188, 170.76126953), 'rotation':(0.277845, -89.098663, 0.27517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.34070312, 5378.73976562, 170.78857422000002), 'rotation':(0.286089, -89.098572, 0.283248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.42953125, 5373.10109375, 170.81648438), 'rotation':(0.29434, -89.098511, 0.291337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.60679688, 5361.82375, 170.8740625), 'rotation':(0.298452, -89.099243, 0.295346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.69515625, 5356.18601562, 170.90341797000002), 'rotation':(0.298561, -89.099182, 0.29547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.78359375, 5350.54785156, 170.9328125), 'rotation':(0.301307, -89.097931, 0.298145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.87195312, 5344.91015625, 170.96230469), 'rotation':(0.301307, -89.097931, 0.298145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.13804688, 5327.995625, 171.05230468999997), 'rotation':(0.312741, -89.100769, 0.309347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6316.40367188, 5311.08105469, 171.14542969), 'rotation':(0.321347, -89.095917, 0.317761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.49257812, 5305.44287109, 171.17697266), 'rotation':(0.321347, -89.095917, 0.317761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.66929688, 5294.16699219, 171.24019531000002), 'rotation':(0.322364, -89.098694, 0.318758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6316.75765625, 5288.52929688, 171.27191406000003), 'rotation':(0.324468, -89.098724, 0.320806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.93492188, 5277.25292969, 171.33583984), 'rotation':(0.326722, -89.098724, 0.323029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.1121875, 5265.97705078, 171.40041015999998), 'rotation':(0.329884, -89.097748, 0.326113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.55507812, 5237.78759766, 171.56251953), 'rotation':(0.327644, -89.097412, 0.323915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.03257812, 5183.11279297, 171.86980469), 'rotation':(-0.315338, 90.900093, -0.318848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.11953125, 5177.578125, 171.90005859000001), 'rotation':(-0.313019, 90.900146, -0.316467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.38023438, 5160.97509766, 171.98931641), 'rotation':(-0.305756, 90.899986, -0.309052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.4671875, 5155.44042969, 172.01875), 'rotation':(-0.304718, 90.902725, -0.307983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.5540625, 5149.90673828, 172.04800781000003), 'rotation':(-0.304718, 90.902725, -0.307983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.72789062, 5138.83740234, 172.10556641), 'rotation':(-0.300873, 90.902084, -0.304047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6310.81484375, 5133.30322266, 172.13375), 'rotation':(-0.293274, 90.902077, -0.296295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.16296875, 5111.16601562, 172.24195312), 'rotation':(-0.274231, 90.900352, -0.276825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.24984375, 5105.63085938, 172.2684375), 'rotation':(-0.274353, 90.905151, -0.277008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.33679688, 5100.09667969, 172.2946875), 'rotation':(-0.271271, 90.90126, -0.273865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.803125, 5094.69335938, 172.32037109), 'rotation':(0.259274, -89.098877, 0.256937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.62929688, 5105.76220703, 172.2684375), 'rotation':(0.271275, -89.098755, 0.268716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.54234375, 5111.296875, 172.24195312), 'rotation':(0.274355, -89.099609, 0.271748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6319.36851562, 5122.36523438, 172.18855469), 'rotation':(0.278071, -89.098145, 0.275392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.19421875, 5133.43457031, 172.13375), 'rotation':(0.285679, -89.098022, 0.282849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.02039062, 5144.50292969, 172.07708984), 'rotation':(0.293268, -89.101105, 0.290286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.9334375, 5150.03759766, 172.04802734), 'rotation':(0.300877, -89.097839, 0.297739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.67273438, 5166.64013672, 171.95978516), 'rotation':(0.305753, -89.100006, 0.302512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.58578125, 5172.17480469, 171.93005859000002), 'rotation':(0.308308, -89.099884, 0.30501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.49890625, 5177.70898438, 171.90005859000001), 'rotation':(0.310466, -89.094574, 0.307116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.32507812, 5188.77832031, 171.83931640999998), 'rotation':(0.315336, -89.099884, 0.311884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.23765625, 5194.31298828, 171.80859375), 'rotation':(0.317727, -89.094421, 0.314215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.06382812, 5205.38134766, 171.74644531), 'rotation':(0.322405, -89.099792, 0.318793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.10734375, 5051.00292969, 172.50283202999998), 'rotation':(-0.229767, 90.898247, -0.231598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.19570312, 5045.37255859, 172.52474609), 'rotation':(-0.223175, 90.900284, -0.224915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.2840625, 5039.74267578, 172.54546875), 'rotation':(-0.210022, 90.903999, -0.211578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.54921875, 5022.85498047, 172.60232422), 'rotation':(-0.183807, 90.899956, -0.184998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.63804688, 5017.22460938, 172.61974609), 'rotation':(-0.177216, 90.898819, -0.178314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.72640625, 5011.59521484, 172.63716797), 'rotation':(-0.177216, 90.898819, -0.178314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.81484375, 5005.96679688, 172.65447265999998), 'rotation':(-0.177216, 90.902245, -0.178314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6312.90320312, 5000.33691406, 172.67119141), 'rotation':(-0.170166, 90.899452, -0.171173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6313.345625, 4972.19091797, 172.74179688), 'rotation':(-0.127197, 90.899246, -0.127777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.52234375, 4960.93017578, 172.76517578), 'rotation':(-0.120087, 90.901237, -0.120575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.61070312, 4955.30029297, 172.77613281), 'rotation':(-0.111481, 90.90036, -0.111908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.7875, 4944.04101562, 172.79539062), 'rotation':(-0.094452, 90.900352, -0.094757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.9646875, 4932.78320312, 172.8103125), 'rotation':(-0.077301, 90.900246, -0.077515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.14148438, 4921.52392578, 172.82164062), 'rotation':(-0.060181, 90.897263, -0.060303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.22984375, 4915.89404297, 172.82669922000002), 'rotation':(-0.051544, 90.90284, -0.051636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.40664062, 4904.63378906, 172.83685547000002), 'rotation':(-0.051666, 90.899025, -0.051758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.760625, 4882.11914062, 172.84142577999998), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6314.84898438, 4876.48925781, 172.83833984), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6314.93734375, 4870.859375, 172.83525391), 'rotation':(0.031494, 90.90036, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.02578125, 4865.22949219, 172.83214843999997), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.11414062, 4859.59912109, 172.8290625), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.2909375, 4848.34033203, 172.82203125), 'rotation':(0.041698, 90.898911, 0.041631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.37929688, 4842.71191406, 172.81742188), 'rotation':(0.041698, 90.898911, 0.041631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.468125, 4837.08154297, 172.81134766), 'rotation':(0.062155, 90.902039, 0.062008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.5565625, 4831.453125, 172.80388672), 'rotation':(0.062155, 90.902039, 0.062008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.64492188, 4825.82421875, 172.79564453), 'rotation':(0.082516, 90.898994, 0.082265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.73328125, 4820.19433594, 172.78552734000002), 'rotation':(0.102958, 90.899078, 0.10259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.82164062, 4814.56494141, 172.77492188), 'rotation':(0.102958, 90.899078, 0.10259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.91054688, 4808.93603516, 172.76359375), 'rotation':(0.11319, 90.90065, 0.11275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.99890625, 4803.30664062, 172.75171875), 'rotation':(0.120765, 90.900795, 0.120264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.175625, 4792.04785156, 172.72527344), 'rotation':(0.136214, 90.900871, 0.135563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.2640625, 4786.41796875, 172.71041015999998), 'rotation':(0.151453, 90.90094, 0.150651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6324.73179688, 4780.92041016, 172.69474609), 'rotation':(-0.166809, -89.098969, -0.167755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.55507812, 4792.18017578, 172.72527344), 'rotation':(-0.151428, -89.102234, -0.152252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.46671875, 4797.80908203, 172.73880859000002), 'rotation':(-0.1362, -89.099152, -0.136871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.20109375, 4814.69775391, 172.77494141), 'rotation':(-0.11319, -89.099335, -0.113647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.11265625, 4820.32617188, 172.78552734000002), 'rotation':(-0.11319, -89.099335, -0.113647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.9359375, 4831.58496094, 172.80388672), 'rotation':(-0.08252, -89.097839, -0.082733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.8475, 4837.21337891, 172.81134766), 'rotation':(-0.08252, -89.097839, -0.082733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.75867188, 4842.84326172, 172.81742188), 'rotation':(-0.062134, -89.101074, -0.062286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6323.40515625, 4865.36132812, 172.83214843999997), 'rotation':(-0.031494, -89.09967, -0.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.14, 4882.25146484, 172.84142577999998), 'rotation':(-0.031494, -89.09967, -0.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.05164062, 4887.88134766, 172.84451172), 'rotation':(-0.031494, -89.09967, -0.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.96328125, 4893.50830078, 172.84550781000002), 'rotation':(0.009965, -89.09906, 0.009962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6322.874375, 4899.13574219, 172.84191406000002), 'rotation':(0.009965, -89.09906, 0.009962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.78601562, 4904.765625, 172.83685547000002), 'rotation':(0.051657, -89.100983, 0.051564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.69765625, 4910.39550781, 172.83177734), 'rotation':(0.05167, -89.100922, 0.051571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.52085938, 4921.65576172, 172.82164062), 'rotation':(0.051547, -89.097076, 0.051457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.34414062, 4932.91455078, 172.8103125), 'rotation':(0.060167, -89.099792, 0.06004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.166875, 4944.17285156, 172.79539062), 'rotation':(0.077311, -89.099701, 0.077108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.99015625, 4955.43115234, 172.77613281), 'rotation':(0.094441, -89.102661, 0.09414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.90171875, 4961.06103516, 172.76517578), 'rotation':(0.111489, -89.099609, 0.111058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.81335938, 4966.69091797, 172.75361328), 'rotation':(0.111489, -89.099609, 0.111058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6321.72453125, 4972.32226562, 172.74179688), 'rotation':(0.120075, -89.098755, 0.11958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.19421875, 5006.09814453, 172.65447265999998), 'rotation':(0.17016, -89.100525, 0.169152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.10585938, 5011.72607422, 172.63716797), 'rotation':(0.17723, -89.097687, 0.176131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6320.92859375, 5022.98583984, 172.60232422), 'rotation':(0.177223, -89.101227, 0.176121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.6634375, 5039.87402344, 172.54546875), 'rotation':(0.196969, -89.09613, 0.195613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6320.57507812, 5045.50341797, 172.52474609), 'rotation':(0.210028, -89.099792, 0.208488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.48671875, 5051.13330078, 172.50283202999998), 'rotation':(0.223176, -89.099701, 0.221455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.30554688, 4720.08740234, 172.47470703), 'rotation':(0.250087, 90.90065, 0.247918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.394375, 4714.42578125, 172.44916016), 'rotation':(0.257334, 90.904724, 0.255027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.48328125, 4708.76464844, 172.42300781000003), 'rotation':(0.261863, 90.898354, 0.259481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.66101562, 4697.44140625, 172.36794922), 'rotation':(0.279703, 90.898537, 0.276988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.74984375, 4691.78125, 172.33904297), 'rotation':(0.288958, 90.903778, 0.286063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.83875, 4686.12011719, 172.30923828), 'rotation':(0.297694, 90.898712, 0.294622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.01695312, 4674.796875, 172.24683593999998), 'rotation':(0.324782, 90.904091, 0.321115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.10585938, 4669.13574219, 172.21447265999998), 'rotation':(0.329413, 90.901634, 0.325639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.1946875, 4663.47363281, 172.18193359), 'rotation':(0.32927, 90.901718, 0.325511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.37242188, 4652.15234375, 172.11505859000002), 'rotation':(0.337111, 90.902496, 0.333168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.46179688, 4646.49070312, 172.08019531000002), 'rotation':(0.35269, 90.902733, 0.348373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.550625, 4640.82960938, 172.04396484), 'rotation':(0.368243, 90.899414, 0.36354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.63953125, 4635.1684375, 172.00679688), 'rotation':(0.368243, 90.899414, 0.36354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.7284375, 4629.5078125, 171.96878906), 'rotation':(0.383706, 90.90313, 0.378592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.81726562, 4623.84617188, 171.93009766), 'rotation':(0.391411, 90.902901, 0.38609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.90664062, 4618.18457031, 171.89140625), 'rotation':(0.391547, 90.902885, 0.386221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.17320312, 4601.20070312, 171.77175781000003), 'rotation':(0.413821, 90.903358, 0.407862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.2615625, 4595.54148438, 171.73042969), 'rotation':(0.413821, 90.903358, 0.407862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.439375, 4584.21828125, 171.64482422), 'rotation':(0.428656, 90.903519, 0.422282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.88414062, 4555.91308594, 171.42068359), 'rotation':(0.467643, 90.903076, 0.460062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6319.97304688, 4550.25195312, 171.3740625), 'rotation':(0.474165, 90.903183, 0.466364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6320.061875, 4544.58984375, 171.32669922000002), 'rotation':(0.480722, 90.903374, 0.472718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.15078125, 4538.92921875, 171.27867188), 'rotation':(0.487368, 90.903412, 0.479132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.23960938, 4533.26757812, 171.22992188), 'rotation':(0.494055, 90.908882, 0.48559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.32507812, 4527.83300781, 171.18244141), 'rotation':(0.500578, 90.903641, 0.491899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.59609375, 4725.87890625, 172.49951172000002), 'rotation':(-0.250092, -89.099365, -0.252258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.9515625, 4703.234375, 172.3959375), 'rotation':(-0.279724, -89.096283, -0.282471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.12929688, 4691.91259766, 172.33904297), 'rotation':(-0.297729, -89.101288, -0.300812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6326.3075, 4680.58886719, 172.27847656000003), 'rotation':(-0.315857, -89.101105, -0.319366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.5740625, 4663.605, 172.18193359), 'rotation':(-0.337128, -89.097443, -0.341125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.66296875, 4657.94484375, 172.14884766), 'rotation':(-0.352692, -89.100769, -0.357056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.84117188, 4646.62207031, 172.08017578), 'rotation':(-0.368256, -89.097046, -0.373016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.93007812, 4640.96046875, 172.04396484), 'rotation':(-0.383698, -89.096863, -0.388855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.1078125, 4629.63914062, 171.96878906), 'rotation':(-0.391418, -89.097107, -0.39679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6327.19664062, 4623.97753906, 171.93009766), 'rotation':(-0.391541, -89.097107, -0.396942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.28601562, 4618.3159375, 171.89140625), 'rotation':(-0.398926, -89.096893, -0.40451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.72984375, 4590.01074219, 171.68802734000002), 'rotation':(-0.443542, -89.099091, -0.450439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.90757812, 4578.6875, 171.60097656000002), 'rotation':(-0.450958, -89.093384, -0.458099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6327.99648438, 4573.02734375, 171.55654297), 'rotation':(-0.454468, -89.097046, -0.461731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6328.44125, 4544.72117188, 171.32669922000002), 'rotation':(-0.487366, -89.096588, -0.495728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6328.53015625, 4539.06054688, 171.27867188), 'rotation':(-0.49411, -89.096405, -0.502686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6321.01109375, 4484.16308594, 170.78740234), 'rotation':(0.538328, 90.904564, 0.528286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.18492188, 4473.09523438, 170.68257812), 'rotation':(0.542488, 90.905098, 0.532283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.35875, 4462.02734375, 170.57724609000002), 'rotation':(0.546504, 90.905426, 0.536156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.44570312, 4456.49367188, 170.52390625), 'rotation':(0.546504, 90.905426, 0.536156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.61953125, 4445.42578125, 170.41589843999998), 'rotation':(0.562548, 90.905739, 0.551579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.70640625, 4439.89210938, 170.36115234000002), 'rotation':(0.562548, 90.905739, 0.551579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.88078125, 4428.82421875, 170.25054688), 'rotation':(0.57459, 90.903397, 0.563154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.14148438, 4412.223125, 170.08330078), 'rotation':(0.578988, 90.904541, 0.567381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.2284375, 4406.68898438, 170.02697265999998), 'rotation':(0.581953, 90.904602, 0.570215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.4021875, 4395.62109375, 169.91347656000002), 'rotation':(0.587847, 90.909973, 0.575891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.66296875, 4379.01953125, 169.74105468999997), 'rotation':(0.596719, 90.9049, 0.584392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6322.74984375, 4373.48535156, 169.68324219), 'rotation':(0.598338, 90.908684, 0.58595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6329.39046875, 4484.29640625, 170.78742188), 'rotation':(-0.54248, -89.094879, -0.552826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6329.82507812, 4456.62695312, 170.52392577999998), 'rotation':(-0.554413, -89.094421, -0.565247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.08578125, 4440.02539062, 170.36115234000002), 'rotation':(-0.570557, -89.094086, -0.582031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.43398438, 4417.89109375, 170.13933594), 'rotation':(-0.579041, -89.090118, -0.590851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.52085938, 4412.35695312, 170.08332031), 'rotation':(-0.58194, -89.095367, -0.593872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6330.6078125, 4406.82324219, 170.02701172000002), 'rotation':(-0.585083, -89.095337, -0.597107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.6946875, 4401.28953125, 169.97041016), 'rotation':(-0.58786, -89.095276, -0.600037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.95546875, 4384.68796875, 169.79880859000002), 'rotation':(-0.596802, -89.095001, -0.609314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.48625, 4353.45164062, 164.22880859), 'rotation':(-0.969025, -179.938156, -1.002228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6008.05117188, 4361.81984375, 163.95224609000002), 'rotation':(0.96098, 0.058542, 0.929126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.52867188, 4361.82421875, 164.04412109), 'rotation':(0.968999, 0.061839, 0.93664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6019.00625, 4361.82859375, 164.13621093999998), 'rotation':(0.968999, 0.061839, 0.93664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.4828125, 4361.8325, 164.22886719), 'rotation':(0.976997, 0.062107, 0.944096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6029.9603125, 4361.83691406, 164.32195312), 'rotation':(0.976997, 0.062107, 0.944096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6040.9134375, 4361.84570312, 164.50945312), 'rotation':(0.989168, 0.060855, 0.955434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.86757812, 4361.85398438, 164.69832031), 'rotation':(0.989039, 0.060851, 0.955319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6057.34414062, 4361.85839844, 164.79289062), 'rotation':(0.992242, 0.063003, 0.958313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6068.29484375, 4361.99070312, 164.9825), 'rotation':(0.998505, 0.063222, 0.964138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6111.89296875, 4353.52, 165.74869141), 'rotation':(-1.011139, -179.938263, -1.047302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6123.23914062, 4353.52929688, 165.94912109), 'rotation':(-1.012024, -179.938232, -1.048279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6134.5853125, 4353.53808594, 166.14980469), 'rotation':(-1.012817, -179.93483, -1.049103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6140.25867188, 4353.5425, 166.25019531), 'rotation':(-1.013641, -179.938171, -1.050018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6145.93203125, 4353.546875, 166.35066406), 'rotation':(-1.014069, -179.939301, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6157.27820312, 4353.55617188, 166.5515625), 'rotation':(-1.014069, -179.935425, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6162.95109375, 4353.56054688, 166.65199219), 'rotation':(-1.014069, -179.935425, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6168.624375, 4353.56492188, 166.75244141), 'rotation':(-1.014069, -179.939301, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6191.31679688, 4353.5825, 167.15396484000001), 'rotation':(-1.013214, -179.934555, -1.049561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6196.98960938, 4353.58691406, 167.25431641), 'rotation':(-1.013245, -179.938522, -1.049561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6202.66296875, 4353.59132812, 167.3546875), 'rotation':(-1.013245, -179.938522, -1.049561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6208.33046875, 4353.59523438, 167.45486327999998), 'rotation':(-1.011902, -179.936127, -1.048157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6219.6815625, 4353.60449219, 167.65505859), 'rotation':(-1.009033, -179.936234, -1.045074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6231.0271875, 4353.61328125, 167.854375), 'rotation':(-1.006317, -179.939606, -1.042175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6236.70054688, 4353.61765625, 167.95378906000002), 'rotation':(-1.003601, -179.936417, -1.039246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6248.04671875, 4353.62011719, 168.15236328), 'rotation':(-1.002167, -179.938736, -1.037689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6253.72007812, 4353.64304688, 168.25166016), 'rotation':(-1.002258, -179.933273, -1.037811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.73914062, 4353.67773438, 168.54871093999998), 'rotation':(-0.997864, -179.941818, -1.033112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.75867188, 4353.6909375, 168.84345703), 'rotation':(-0.990326, -179.937561, -1.025024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.1053125, 4353.6996875, 169.03951172), 'rotation':(-0.988861, -179.938705, -1.023438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.77820312, 4353.70410156, 169.13724609000002), 'rotation':(-0.986328, -179.938766, -1.020752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6310.45109375, 4353.70851562, 169.2346875), 'rotation':(-0.98349, -179.938873, -1.0177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6310.48328125, 4362.05664062, 169.23533203), 'rotation':(0.98087, 0.061027, 0.947703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.13710938, 4362.04785156, 169.04019531000003), 'rotation':(0.986238, 0.06121, 0.952713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6293.46375, 4362.04296875, 168.94220703), 'rotation':(0.988847, 0.0613, 0.955144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.7909375, 4362.03859375, 168.84412109000002), 'rotation':(0.990336, 0.062446, 0.956524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6282.11757812, 4362.03417969, 168.74603516), 'rotation':(0.990398, 0.062452, 0.956591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.771875, 4362.02539062, 168.54939453), 'rotation':(0.994851, 0.063177, 0.960731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6265.09851562, 4362.02101562, 168.45064452999998), 'rotation':(0.997788, 0.058171, 0.963476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6248.07945312, 4362.0078125, 168.15306640999998), 'rotation':(1.002153, 0.066716, 0.967544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6242.40609375, 4362.00292969, 168.05376952999998), 'rotation':(1.002262, 0.061258, 0.967635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6236.73328125, 4361.99851562, 167.95449219), 'rotation':(1.002337, 0.061255, 0.967707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6208.36804688, 4361.9765625, 167.45564453), 'rotation':(1.009058, 0.063771, 0.973962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6202.69515625, 4361.9721875, 167.35537109), 'rotation':(1.011927, 0.063873, 0.976634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6197.021875, 4361.96777344, 167.255), 'rotation':(1.013218, 0.061472, 0.977847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6191.34898438, 4361.96335938, 167.15464844), 'rotation':(1.013218, 0.061472, 0.977847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6162.98328125, 4361.9409375, 166.65267577999998), 'rotation':(1.014051, 0.06458, 0.978617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6151.63710938, 4361.93210938, 166.45179688), 'rotation':(1.013983, 0.060691, 0.978551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6140.2909375, 4361.92335938, 166.25089844), 'rotation':(1.014058, 0.060692, 0.978624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6117.59804688, 4361.90578125, 165.84957031000002), 'rotation':(1.011968, 0.061762, 0.97668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.251875, 4361.89648438, 165.64919922), 'rotation':(1.011189, 0.061734, 0.975956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6348.42320312, 4353.70554688, 169.88019531), 'rotation':(-0.967682, -179.938965, -1.000793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6353.94910156, 4353.70996094, 169.97345703), 'rotation':(-0.967682, -179.938965, -1.000793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6359.475, 4353.714375, 170.06658202999998), 'rotation':(-0.96582, -179.940201, -0.99881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6370.52773438, 4353.72265625, 170.25201172), 'rotation':(-0.95874, -179.94043, -0.991241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6376.0540625, 4353.72703125, 170.34439453), 'rotation':(-0.95874, -179.94043, -0.991241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6387.10632812, 4353.73585938, 170.52853516), 'rotation':(-0.953339, -179.938736, -0.985474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6398.1590625, 4353.74414062, 170.7125), 'rotation':(-0.953339, -179.938736, -0.985474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6409.21132812, 4353.75292969, 170.89626952999998), 'rotation':(-0.953339, -179.938736, -0.985474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6442.36851562, 4353.77882812, 171.44076172), 'rotation':(-0.936737, -179.941376, -0.967743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6458.948125, 4353.785625, 171.71089844), 'rotation':(-0.93219, -179.93721, -0.962921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6464.47449219, 4353.78613281, 171.80056641), 'rotation':(-0.930115, -179.941605, -0.960663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6481.05359375, 4353.84226562, 172.06849609), 'rotation':(-0.92334, -179.941818, -0.953461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6486.57996094, 4353.84667969, 172.15742188000002), 'rotation':(-0.921112, -179.941895, -0.95108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.10632812, 4353.85109375, 172.24623047), 'rotation':(-0.921112, -179.941895, -0.95108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6342.89046875, 4362.0815625, 169.78683593999997), 'rotation':(0.967633, 0.061036, 0.935352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6348.416875, 4362.0859375, 169.88019531), 'rotation':(0.965864, 0.059798, 0.933705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6353.94324219, 4362.0903125, 169.97345703), 'rotation':(0.965864, 0.059798, 0.933705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6359.46914062, 4362.09472656, 170.06658202999998), 'rotation':(0.962353, 0.063307, 0.930425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6387.1009375, 4362.11671875, 170.52855469), 'rotation':(0.953474, 0.061266, 0.922122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6392.62734375, 4362.120625, 170.62054688), 'rotation':(0.953337, 0.061259, 0.921992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6431.31042969, 4362.15085938, 171.25990234), 'rotation':(0.937874, 0.058682, 0.90753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6442.36316406, 4362.1596875, 171.44078125), 'rotation':(0.934479, 0.05853, 0.90437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6453.41589844, 4362.1684375, 171.62103516), 'rotation':(0.930094, 0.058392, 0.900258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6458.94273438, 4362.1753125, 171.71089844), 'rotation':(0.930094, 0.058392, 0.900258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6464.46914062, 4362.18359375, 171.80058594), 'rotation':(0.927792, 0.058319, 0.898103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6469.995, 4362.19140625, 171.89007812), 'rotation':(0.925641, 0.062578, 0.896079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6475.521875, 4362.16601562, 171.97939452999998), 'rotation':(0.923257, 0.058167, 0.893866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6481.04820312, 4362.15671875, 172.06851562), 'rotation':(0.921174, 0.058107, 0.891898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.1009375, 4362.16554688, 172.24626952999998), 'rotation':(0.920129, 0.062201, 0.890918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6547.13609375, 4362.24171875, 173.12669922), 'rotation':(0.91071, 0.06032, 0.882082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6569.73328125, 4362.25929688, 173.48521484), 'rotation':(0.904474, 0.060129, 0.876239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6575.38269531, 4362.26414062, 173.57449218999997), 'rotation':(0.902685, 0.055482, 0.874564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6592.33046875, 4362.27734375, 173.84158202999998), 'rotation':(0.901892, 0.057749, 0.873825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.62929688, 4362.28613281, 174.01949219), 'rotation':(0.901284, 0.059203, 0.873243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6631.87488281, 4362.308125, 174.46314453), 'rotation':(0.899065, 0.056447, 0.871168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6637.52476562, 4362.3125, 174.55185547000002), 'rotation':(0.898559, 0.059567, 0.870685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6648.82265625, 4362.32128906, 174.72908203), 'rotation':(0.897412, 0.059529, 0.869623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6654.47253906, 4362.32570312, 174.81759766), 'rotation':(0.896189, 0.059492, 0.868465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.77085938, 4362.33445312, 174.99443359), 'rotation':(0.895042, 0.056426, 0.867399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6682.71863281, 4362.35890625, 175.25921875), 'rotation':(0.894557, 0.060079, 0.866946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6705.31628906, 4362.3325, 175.611875), 'rotation':(0.892282, 0.057494, 0.864805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.61511719, 4362.34132812, 175.78789061999998), 'rotation':(0.891558, 0.057473, 0.864114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6722.26453125, 4362.34570312, 175.87580078), 'rotation':(0.890984, 0.060491, 0.863589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6727.91394531, 4362.35007812, 175.96369141), 'rotation':(0.891107, 0.056253, 0.863718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.56335938, 4362.35449219, 176.05158203), 'rotation':(0.891046, 0.060498, 0.863648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6739.21228516, 4362.35890625, 176.13945311999998), 'rotation':(0.890984, 0.060491, 0.863589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6744.8621875, 4362.36328125, 176.22734375), 'rotation':(0.890984, 0.060491, 0.863589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6750.51111328, 4362.36765625, 176.31521484), 'rotation':(0.890513, 0.055125, 0.863154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6524.54382812, 4353.84328125, 172.76609375), 'rotation':(-0.914703, -179.940552, -0.944275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6535.8421875, 4353.85203125, 172.94652344), 'rotation':(-0.914764, -179.940552, -0.944336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6547.14, 4353.86085938, 173.12666016), 'rotation':(-0.912354, -179.939621, -0.941772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.78945312, 4353.86523438, 173.21650391), 'rotation':(-0.910706, -179.939667, -0.940002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.43882812, 4353.86960938, 173.30621093999997), 'rotation':(-0.90921, -179.944305, -0.938416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6575.38609375, 4353.88328125, 173.57445312), 'rotation':(-0.904388, -179.93988, -0.933319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6581.03601562, 4353.88769531, 173.66357422000002), 'rotation':(-0.904388, -179.93988, -0.933319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6592.334375, 4353.89648438, 173.84154297), 'rotation':(-0.902008, -179.942245, -0.930756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6597.98328125, 4353.90085938, 173.93048828), 'rotation':(-0.901886, -179.942245, -0.930634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6609.28113281, 4353.9096875, 174.10830077999998), 'rotation':(-0.901337, -179.940781, -0.930054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6626.229375, 4353.92285156, 174.37443359), 'rotation':(-0.899078, -179.943558, -0.927643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6631.87828125, 4353.92726562, 174.463125), 'rotation':(-0.8992, -179.938843, -0.927795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6648.82605469, 4353.94042969, 174.72902344), 'rotation':(-0.89856, -179.94043, -0.927094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6654.4759375, 4353.94484375, 174.81755859), 'rotation':(-0.8974, -179.94046, -0.925873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.77429688, 4353.94382812, 174.994375), 'rotation':(-0.896149, -179.940506, -0.9245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6671.42371094, 4353.97753906, 175.08269531000002), 'rotation':(-0.89505, -179.940552, -0.92334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6699.67029297, 4354.01320312, 175.52373047), 'rotation':(-0.894043, -179.942444, -0.922302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6710.96863281, 4354.02246094, 175.69984375), 'rotation':(-0.892273, -179.942505, -0.92041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.21521484, 4354.04445312, 176.13939453), 'rotation':(-0.890991, -179.943741, -0.919006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6744.86462891, 4354.04882812, 176.22728515999998), 'rotation':(-0.890991, -179.943741, -0.919006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6756.16345703, 4354.05761719, 176.40294922), 'rotation':(-0.890533, -179.944855, -0.918549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6794.26257812, 4354.05421875, 176.99410156000002), 'rotation':(-0.888733, -179.937698, -0.916626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6805.57507812, 4354.06296875, 177.16933594), 'rotation':(-0.887634, -179.942413, -0.915466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6811.23181641, 4354.06789062, 177.25677734), 'rotation':(-0.885651, -179.94249, -0.913361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6816.88806641, 4354.07226562, 177.34414062), 'rotation':(-0.884583, -179.941406, -0.912231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6822.54529297, 4354.07664062, 177.43148438), 'rotation':(-0.884583, -179.941406, -0.912231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.85828125, 4354.08546875, 177.60621093999998), 'rotation':(-0.884491, -179.941406, -0.91214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6845.17175781, 4354.09421875, 177.7809375), 'rotation':(-0.884644, -179.941406, -0.912292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6856.48474609, 4354.10304688, 177.95539062), 'rotation':(-0.882538, -179.944473, -0.910034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6862.14099609, 4354.10742188, 178.04248047000002), 'rotation':(-0.881897, -179.940582, -0.909363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6867.79822266, 4354.11179688, 178.12957031000002), 'rotation':(-0.881897, -179.940582, -0.909363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6884.76794922, 4354.125, 178.39087891), 'rotation':(-0.881927, -179.943436, -0.909424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6930.02136719, 4354.1528125, 179.08570312), 'rotation':(-0.878174, -179.940643, -0.905426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.33484375, 4354.19726562, 179.25916016), 'rotation':(-0.878326, -179.940643, -0.905579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.27478516, 4354.22898438, 179.77835938), 'rotation':(-0.875732, -179.940552, -0.902832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.58777344, 4354.2378125, 179.95130859), 'rotation':(-0.87558, -179.943832, -0.902679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6997.90125, 4354.2465625, 180.12419922), 'rotation':(-0.875397, -179.940216, -0.902466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(7003.15027344, 4354.25097656, 180.20431641), 'rotation':(-0.87442, -179.944473, -0.901428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7009.21472656, 4354.08546875, 180.29683594), 'rotation':(-0.873932, -179.940063, -0.900909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6805.57458984, 4362.44382812, 177.16941406), 'rotation':(0.885643, 0.057511, 0.858571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6828.20154297, 4362.46191406, 177.51894531000002), 'rotation':(0.884482, 0.058582, 0.857479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.85828125, 4362.46632812, 177.60630859), 'rotation':(0.884585, 0.058585, 0.857573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6845.17175781, 4362.47507812, 177.78103516), 'rotation':(0.883997, 0.060811, 0.857016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6850.82800781, 4362.47949219, 177.86833984), 'rotation':(0.882501, 0.055521, 0.85564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.48474609, 4362.48390625, 177.95548828), 'rotation':(0.881948, 0.059422, 0.855086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6884.76794922, 4362.50585938, 178.39097656), 'rotation':(0.881948, 0.059422, 0.855086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6907.39441406, 4362.5234375, 178.73886718999998), 'rotation':(0.878294, 0.059349, 0.851666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6918.70837891, 4362.53222656, 178.91234375), 'rotation':(0.878192, 0.059346, 0.851576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.33533203, 4362.5503125, 179.25925781), 'rotation':(0.877618, 0.056289, 0.851035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6952.64832031, 4362.56054688, 179.43248047), 'rotation':(0.875644, 0.056155, 0.849176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6958.30505859, 4362.56984375, 179.51900390999998), 'rotation':(0.875644, 0.056155, 0.849176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6963.96179688, 4362.55761719, 179.60550781), 'rotation':(0.875746, 0.059447, 0.849275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6980.93152344, 4362.54835938, 179.86492188), 'rotation':(0.875644, 0.056155, 0.849176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6992.245, 4362.55710938, 180.03787109), 'rotation':(0.875337, 0.059766, 0.848893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6997.90222656, 4362.56152344, 180.12429688), 'rotation':(0.874414, 0.055523, 0.84802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7003.55798828, 4362.73632812, 180.210625), 'rotation':(0.873991, 0.05993, 0.847626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(7009.21521484, 4362.74023438, 180.29697266), 'rotation':(0.87393, 0.059928, 0.847559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6067.47203125, 4504.37890625, 166.31103516), 'rotation':(-1.068604, -179.913712, -1.109039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6056.66, 4504.3671875, 166.10931641), 'rotation':(-1.068512, -179.916733, -1.108948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6045.84703125, 4504.355, 165.90753906), 'rotation':(-1.068604, -179.916718, -1.109039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6035.0340625, 4504.34328125, 165.70587891), 'rotation':(-1.066284, -179.916092, -1.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6029.6278125, 4504.33691406, 165.6053125), 'rotation':(-1.062286, -179.916245, -1.102264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.2215625, 4504.33105469, 165.50509766), 'rotation':(-1.060059, -179.916382, -1.099854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6003.09507812, 4504.30710938, 165.10505859), 'rotation':(-1.05368, -179.921432, -1.092957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6007.98625, 4512.69382812, 165.20480468999997), 'rotation':(1.060148, 0.083626, 1.02146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.20546875, 4512.71191406, 165.50498047000002), 'rotation':(1.062292, 0.083761, 1.023418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6035.0175, 4512.72414062, 165.70574219), 'rotation':(1.06859, 0.083274, 1.029271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6045.83, 4512.73585938, 165.90740234), 'rotation':(1.068487, 0.08327, 1.029184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.23625, 4512.74171875, 166.00828125), 'rotation':(1.06859, 0.08629, 1.029271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6056.6425, 4512.74804688, 166.10914062), 'rotation':(1.06859, 0.08629, 1.029271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.46375, 4513.07078125, 170.65865234), 'rotation':(1.000438, 0.078703, 0.965943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.40953125, 4513.00488281, 170.35941406), 'rotation':(1.009878, 0.08053, 0.974739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6276.03796875, 4512.9921875, 170.15810547), 'rotation':(1.017555, 0.080804, 0.981883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.35242188, 4512.98585938, 170.05689453), 'rotation':(1.021407, 0.085771, 0.985467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6264.66640625, 4512.97949219, 169.95529297000002), 'rotation':(1.021407, 0.085771, 0.985467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6258.9803125, 4512.973125, 169.85333984000002), 'rotation':(1.02517, 0.081081, 0.988966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6236.23867188, 4512.94824219, 169.443125), 'rotation':(1.037444, 0.082082, 1.000369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6230.55265625, 4512.941875, 169.33990234), 'rotation':(1.040081, 0.08218, 1.002812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.8665625, 4512.93554688, 169.23642578), 'rotation':(1.042813, 0.082286, 1.005345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6207.80992188, 4512.91648438, 168.92435547000002), 'rotation':(1.050708, 0.082572, 1.012687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6196.43835938, 4512.90382812, 168.71550781000002), 'rotation':(1.051713, 0.08542, 1.013617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6179.38171875, 4512.88429688, 168.40125), 'rotation':(1.056938, 0.083804, 1.01846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6116.83921875, 4512.81492188, 167.23599609000001), 'rotation':(1.072852, 0.087061, 1.033222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6105.42125, 4504.34472656, 167.02169922000002), 'rotation':(-1.074677, -179.914917, -1.11557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6111.10195312, 4504.42726562, 167.12826172), 'rotation':(-1.074493, -179.914917, -1.115417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6116.78796875, 4504.4340625, 167.23484375), 'rotation':(-1.074158, -179.918045, -1.11499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6145.21617188, 4504.46582031, 167.76603516), 'rotation':(-1.067566, -179.913147, -1.10791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6173.644375, 4504.49707031, 168.29484375), 'rotation':(-1.063904, -179.915939, -1.103973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.01648438, 4504.50976562, 168.50511719), 'rotation':(-1.056946, -179.916199, -1.096497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6190.7015625, 4504.51609375, 168.60984375), 'rotation':(-1.056946, -179.916199, -1.096497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6196.38757812, 4504.52296875, 168.71439453), 'rotation':(-1.053711, -179.92009, -1.093018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6202.073125, 4504.52929688, 168.81880859), 'rotation':(-1.051727, -179.914581, -1.090881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6213.4446875, 4504.53417969, 169.02757812), 'rotation':(-1.05072, -179.917435, -1.089813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6219.13078125, 4504.56152344, 169.13160156), 'rotation':(-1.047821, -179.912262, -1.0867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.81625, 4504.58398438, 169.23535156000003), 'rotation':(-1.045197, -179.917633, -1.083862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6258.9315625, 4504.62546875, 169.85228515999998), 'rotation':(-1.029022, -179.918777, -1.066498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.30265625, 4504.63820312, 170.05583984), 'rotation':(-1.025177, -179.918915, -1.062378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6275.98914062, 4504.64453125, 170.15707031000002), 'rotation':(-1.021393, -179.91423, -1.058319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6281.67421875, 4504.65085938, 170.25791016), 'rotation':(-1.017548, -179.919189, -1.054199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6293.04578125, 4504.66359375, 170.45849609), 'rotation':(-1.009888, -179.919464, -1.045959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.73234375, 4504.66992188, 170.55824219), 'rotation':(-1.006195, -179.914764, -1.042023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6304.41835938, 4504.50585938, 170.65767577999998), 'rotation':(-1.002289, -179.919724, -1.037811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6041.178125, 4758.28125, 167.32857422), 'rotation':(-1.129364, -179.625763, -1.174591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6035.66835938, 4758.24707031, 167.21992188000002), 'rotation':(-1.129364, -179.625763, -1.174591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.64882812, 4758.1796875, 167.00261719), 'rotation':(-1.129333, -179.628769, -1.17453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6019.1390625, 4758.14599609, 166.89392578), 'rotation':(-1.129333, -179.628769, -1.17453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.62828125, 4758.11230469, 166.78523438), 'rotation':(-1.130219, -179.627686, -1.175476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6057.66296875, 4766.76269531, 167.65451172000002), 'rotation':(1.125772, 0.373616, 1.08216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6046.64882812, 4766.6953125, 167.43746094), 'rotation':(1.128115, 0.370702, 1.084327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6030.12828125, 4766.59423828, 167.11166015999999), 'rotation':(1.129372, 0.371208, 1.08547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.62195312, 4766.56054688, 167.00306641), 'rotation':(1.129426, 0.37426, 1.08553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.60828125, 4766.49316406, 166.78585938), 'rotation':(1.129276, 0.374237, 1.085384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6008.10140625, 4766.45947266, 166.67720702999998), 'rotation':(1.129276, 0.374237, 1.085384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6002.59460938, 4766.42578125, 166.56849609), 'rotation':(1.130212, 0.372307, 1.086253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6101.17375, 4758.6484375, 168.50742188), 'rotation':(-1.12027, -179.627975, -1.164764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.85679688, 4758.68310547, 168.61839844), 'rotation':(-1.12027, -179.627975, -1.164764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6112.54039062, 4758.71777344, 168.72927734), 'rotation':(-1.117462, -179.628067, -1.161713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6123.90710938, 4758.78710938, 168.95037109), 'rotation':(-1.114746, -179.624924, -1.158783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6135.27429688, 4758.85693359, 169.1709375), 'rotation':(-1.110443, -179.628799, -1.154144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6163.69179688, 4759.03027344, 169.71953125), 'rotation':(-1.099915, -179.629242, -1.142761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6169.37484375, 4759.06542969, 169.8284375), 'rotation':(-1.099915, -179.629242, -1.142761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6186.4246875, 4759.16992188, 170.15419922), 'rotation':(-1.093475, -179.626938, -1.135834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6192.1078125, 4759.20458984, 170.26257812), 'rotation':(-1.093475, -179.626938, -1.135834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6203.4759375, 4759.26806641, 170.47857422), 'rotation':(-1.085205, -179.631012, -1.126923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6209.15953125, 4759.31884766, 170.58609375), 'rotation':(-1.085205, -179.631012, -1.126923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6226.209375, 4759.44628906, 170.9065625), 'rotation':(-1.074341, -179.628342, -1.115204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6231.89296875, 4759.48095703, 171.01292969), 'rotation':(-1.071472, -179.631729, -1.112152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6243.2596875, 4759.55078125, 171.22539061999998), 'rotation':(-1.071564, -179.627563, -1.112244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6248.94328125, 4759.58544922, 171.33136718999998), 'rotation':(-1.068817, -179.628174, -1.109253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6254.62734375, 4759.62060547, 171.43689453), 'rotation':(-1.063171, -179.631439, -1.10321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6260.3109375, 4759.65478516, 171.54208984000002), 'rotation':(-1.063171, -179.631439, -1.10321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6265.9940625, 4759.68994141, 171.64705078), 'rotation':(-1.057678, -179.628571, -1.097321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6271.67765625, 4759.72460938, 171.75148438), 'rotation':(-1.052002, -179.631851, -1.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6277.3621875, 4759.75927734, 171.85582031), 'rotation':(-1.052002, -179.631851, -1.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6288.72890625, 4759.82910156, 172.06400391), 'rotation':(-1.049286, -179.627747, -1.088257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6294.41296875, 4759.86376953, 172.16777344), 'rotation':(-1.046967, -179.632141, -1.085754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.78945312, 4768.28125, 172.37519531), 'rotation':(1.034446, 0.372096, 0.997576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6260.3196875, 4768.00244141, 171.54320312), 'rotation':(1.057627, 0.368345, 1.019114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6243.26890625, 4767.89892578, 171.22652344), 'rotation':(1.068802, 0.371824, 1.029465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6237.58632812, 4767.86376953, 171.12041016), 'rotation':(1.068802, 0.371824, 1.029465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6226.21859375, 4767.79443359, 170.90769531), 'rotation':(1.071493, 0.372413, 1.031957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6220.535, 4767.75976562, 170.80113281), 'rotation':(1.074327, 0.368568, 1.034592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6203.48476562, 4767.65527344, 170.47970703), 'rotation':(1.079805, 0.371861, 1.039665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6192.11757812, 4767.5859375, 170.26373047), 'rotation':(1.090774, 0.372277, 1.04982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6180.75039062, 4767.51611328, 170.04683594), 'rotation':(1.093547, 0.369131, 1.052382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6175.06679688, 4767.48144531, 169.93830078), 'rotation':(1.093431, 0.373083, 1.052268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6152.33289062, 4767.34228516, 169.50197265999998), 'rotation':(1.104168, 0.370916, 1.062198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6123.916875, 4767.16845703, 168.9515625), 'rotation':(1.111886, 0.371684, 1.069342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6112.5496875, 4767.09863281, 168.73044922), 'rotation':(1.114817, 0.371817, 1.072043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6449.0140625, 4769.15771484, 174.86367188), 'rotation':(0.949478, 0.365604, 0.918399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6443.47695312, 4769.12402344, 174.77144531000002), 'rotation':(0.953952, 0.365754, 0.92257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6426.86707031, 4769.02246094, 174.49273438), 'rotation':(0.963139, 0.366061, 0.931153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6399.18152344, 4768.85302734, 174.02111327999998), 'rotation':(0.981614, 0.368103, 0.948394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6388.1078125, 4768.78515625, 173.82998047), 'rotation':(0.988875, 0.368354, 0.955159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6382.57117188, 4768.75146484, 173.73396484), 'rotation':(0.99242, 0.368475, 0.958468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6371.49792969, 4768.68359375, 173.54164062), 'rotation':(0.994079, 0.367751, 0.960025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6365.96082031, 4768.64941406, 173.44521484), 'rotation':(0.997467, 0.369538, 0.963175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6360.42273438, 4768.61572266, 173.34824218999998), 'rotation':(1.003812, 0.366372, 0.969086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6343.81234375, 4768.51367188, 173.05507812), 'rotation':(1.016701, 0.366832, 0.981077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.31335938, 4760.98095703, 175.40998047000002), 'rotation':(-0.931, -179.634995, -0.961639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6476.77527344, 4760.94677734, 175.31986328), 'rotation':(-0.935669, -179.634872, -0.966583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6438.00964844, 4760.70947266, 174.67916015999998), 'rotation':(-0.963074, -179.633972, -0.99588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6426.93542969, 4760.64160156, 174.49302734), 'rotation':(-0.967285, -179.632385, -1.000336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6415.85925781, 4760.57373047, 174.30541015999998), 'rotation':(-0.974365, -179.632141, -1.007935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6410.32164062, 4760.54003906, 174.21107422), 'rotation':(-0.978058, -179.632019, -1.011902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6404.7840625, 4760.50585938, 174.11638672), 'rotation':(-0.981628, -179.631897, -1.015686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6399.24597656, 4760.47216797, 174.02132812), 'rotation':(-0.985168, -179.631775, -1.019501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6382.63320312, 4760.37060547, 173.73414062), 'rotation':(-0.994232, -179.632248, -1.029205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6377.09558594, 4760.33642578, 173.63802734), 'rotation':(-0.99408, -179.632248, -1.029053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6366.02039062, 4760.26904297, 173.44535156), 'rotation':(-1.003815, -179.630234, -1.039459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6360.4828125, 4760.23535156, 173.34839843999998), 'rotation':(-1.010284, -179.633392, -1.046387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6354.94519531, 4760.20117188, 173.25109375), 'rotation':(-1.010284, -179.633392, -1.046387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6349.40710938, 4760.16748047, 173.15341797000002), 'rotation':(-1.016632, -179.629807, -1.053223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6343.86953125, 4760.13330078, 173.05519531000002), 'rotation':(-1.019897, -179.631912, -1.056732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6338.33289062, 4760.09960938, 172.95679688), 'rotation':(-1.019897, -179.631912, -1.056732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.280625, 4378.453125, 172.71128906), 'rotation':(0.595797, 90.888573, 0.583506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.11070312, 4389.50683594, 172.82619140999998), 'rotation':(0.593373, 90.887482, 0.581179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.9403125, 4400.56007812, 172.94027343999997), 'rotation':(0.584084, 90.887283, 0.572257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.85535156, 4406.08742188, 172.99679688), 'rotation':(0.584084, 90.887283, 0.572257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.77039062, 4411.61476562, 173.05300781000003), 'rotation':(0.579405, 90.88726, 0.567773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.68542969, 4417.14109375, 173.10890625), 'rotation':(0.577151, 90.886726, 0.565611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6502.60046875, 4422.6684375, 173.16458984000002), 'rotation':(0.577151, 90.886726, 0.565611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.34507812, 4439.24851562, 173.33154297000002), 'rotation':(0.57377, 90.889389, 0.562372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.08972656, 4455.82960938, 173.49585938), 'rotation':(0.554686, 90.889023, 0.544016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.00429688, 4461.35644531, 173.54960938), 'rotation':(0.551422, 90.887291, 0.540879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.91929688, 4466.88328125, 173.60298827999998), 'rotation':(0.551422, 90.887291, 0.540879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.834375, 4472.410625, 173.65621094), 'rotation':(0.551422, 90.887291, 0.540879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.57898438, 4488.99070312, 173.81478515999999), 'rotation':(0.539284, 90.890831, 0.529199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.40859375, 4500.04492188, 173.91832031), 'rotation':(0.529524, 90.885674, 0.519807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.23816406, 4511.09863281, 174.01998047), 'rotation':(0.519825, 90.890488, 0.51046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.15320312, 4516.62597656, 174.07007812), 'rotation':(0.514921, 90.885323, 0.505739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6500.98328125, 4527.68015625, 174.16919922), 'rotation':(0.508193, 90.88504, 0.499239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6500.89832031, 4533.2065625, 174.21853516), 'rotation':(0.508193, 90.88504, 0.499239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6509.36265625, 4527.81398438, 174.16925781), 'rotation':(-0.512421, -89.112976, -0.521637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6509.61804688, 4511.23339844, 174.02001952999998), 'rotation':(-0.524567, -89.114502, -0.534241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6509.78796875, 4500.1796875, 173.91835938), 'rotation':(-0.534393, -89.114319, -0.544403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.04335938, 4483.598125, 173.76236328), 'rotation':(-0.54892, -89.114044, -0.559509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6510.29871094, 4467.01804688, 173.60304688), 'rotation':(-0.554688, -89.110962, -0.565491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.38367188, 4461.49121094, 173.54964843999997), 'rotation':(-0.554688, -89.110962, -0.565491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.46863281, 4455.964375, 173.49591797000002), 'rotation':(-0.561066, -89.110901, -0.572113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.72449219, 4439.38429688, 173.33160156000002), 'rotation':(-0.577148, -89.113281, -0.588867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.80945312, 4433.85789062, 173.27601562), 'rotation':(-0.576996, -89.10791, -0.588684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6510.89441406, 4428.33105469, 173.22033202999998), 'rotation':(-0.577209, -89.11322, -0.588928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.97984375, 4422.80371094, 173.16464843999998), 'rotation':(-0.577148, -89.113281, -0.588867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6511.3196875, 4400.69578125, 172.94033202999998), 'rotation':(-0.588837, -89.108673, -0.601013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6511.4046875, 4395.16945312, 172.88353515999998), 'rotation':(-0.593384, -89.112518, -0.605774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6511.49011719, 4389.64210938, 172.82626953), 'rotation':(-0.595795, -89.11142, -0.608307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6511.745, 4373.08984375, 172.65416016), 'rotation':(-0.537079, -89.994965, -0.547211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6500.22839844, 4576.67578125, 174.58570312), 'rotation':(0.461325, 90.888329, 0.453948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.803125, 4604.30371094, 174.80226562), 'rotation':(0.419872, 90.884918, 0.413752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.63320312, 4615.35546875, 174.88388672000002), 'rotation':(0.412871, 90.885071, 0.406957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.54820312, 4620.88085938, 174.92392578), 'rotation':(0.412871, 90.885071, 0.406957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.46277344, 4626.40578125, 174.96369141), 'rotation':(0.405139, 90.884216, 0.39945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.3778125, 4631.93210938, 175.00279297), 'rotation':(0.389512, 90.886841, 0.384237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.29285156, 4637.45800781, 175.04140625), 'rotation':(0.389512, 90.886841, 0.384237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.20789062, 4642.984375, 175.07896484), 'rotation':(0.373809, 90.883774, 0.368968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.12292969, 4648.50878906, 175.11568359), 'rotation':(0.373809, 90.883774, 0.368968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.03796875, 4654.03515625, 175.15175781000002), 'rotation':(0.358196, 90.883606, 0.35374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.9525, 4659.56101562, 175.18660156), 'rotation':(0.358196, 90.883606, 0.35374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.86757812, 4665.0859375, 175.22111328), 'rotation':(0.350259, 90.8871, 0.345995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.69714844, 4676.13818359, 175.28871094), 'rotation':(0.342029, 90.88459, 0.337964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.44226562, 4692.71630859, 175.38546875), 'rotation':(0.308677, 90.88427, 0.305357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.35730469, 4698.24121094, 175.415625), 'rotation':(0.308677, 90.88427, 0.305357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.186875, 4709.29296875, 175.47332031000002), 'rotation':(0.283753, 90.883087, 0.280941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.10195312, 4714.81835938, 175.50105469), 'rotation':(0.283753, 90.883087, 0.280941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.01695312, 4720.34472656, 175.52841797000002), 'rotation':(0.283753, 90.883087, 0.280941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.93152344, 4725.87158203, 175.55578125), 'rotation':(0.275489, 90.881744, 0.272849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6497.8465625, 4731.39648438, 175.58244141), 'rotation':(0.259076, 90.885544, 0.25674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6497.59167969, 4747.97363281, 175.65587890999998), 'rotation':(0.226387, 90.885262, 0.2246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6508.6078125, 4576.80515625, 174.58570312), 'rotation':(-0.468262, -89.115265, -0.475952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6508.43789062, 4587.855, 174.67453125), 'rotation':(-0.461334, -89.111633, -0.468811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6507.92761719, 4621.01023438, 174.92392578), 'rotation':(-0.419861, -89.115082, -0.426056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.8421875, 4626.53515625, 174.96369141), 'rotation':(-0.412872, -89.114929, -0.418854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.7571875, 4632.06152344, 175.00279297), 'rotation':(-0.405151, -89.115784, -0.410919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.67226562, 4637.58691406, 175.04140625), 'rotation':(-0.405151, -89.115784, -0.410919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.58726562, 4643.11375, 175.07898438), 'rotation':(-0.389496, -89.113159, -0.394836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.50234375, 4648.63867188, 175.11568359), 'rotation':(-0.389496, -89.113159, -0.394836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.33191406, 4659.69042969, 175.18660156), 'rotation':(-0.37381, -89.116211, -0.378723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.24695312, 4665.2153125, 175.22111328), 'rotation':(-0.358215, -89.116394, -0.362701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.16148438, 4670.74171875, 175.25492188), 'rotation':(-0.350281, -89.112915, -0.354584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.0765625, 4676.26806641, 175.28871094), 'rotation':(-0.350403, -89.117828, -0.354736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.82164062, 4692.84570312, 175.38548828), 'rotation':(-0.325348, -89.115601, -0.329041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.73671875, 4698.37060547, 175.415625), 'rotation':(-0.325348, -89.115601, -0.329041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.48132812, 4714.94775391, 175.50105469), 'rotation':(-0.291992, -89.115906, -0.294983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6506.3109375, 4726.00048828, 175.55578125), 'rotation':(-0.283752, -89.116821, -0.286591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.05554688, 4742.57763672, 175.63253906000003), 'rotation':(-0.259094, -89.114441, -0.261444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6505.97058594, 4748.10253906, 175.65587890999998), 'rotation':(-0.242798, -89.11853, -0.244843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.93007812, 5050.69238281, 175.70142578), 'rotation':(-0.211151, 90.882355, -0.212708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.10339844, 5039.42871094, 175.74013672), 'rotation':(-0.190063, 90.882202, -0.191315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.27722656, 5028.16503906, 175.77576172000002), 'rotation':(-0.175751, 90.882111, -0.176819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.45054688, 5016.90332031, 175.80826172000002), 'rotation':(-0.161652, 90.882095, -0.162567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.53699219, 5011.27148438, 175.82380859), 'rotation':(-0.158173, 90.881248, -0.159058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.7103125, 5000.00830078, 175.85386719), 'rotation':(-0.150238, 90.88121, -0.151031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.88367188, 4988.74560547, 175.88027344), 'rotation':(-0.134338, 90.881165, -0.134979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6494.0575, 4977.48193359, 175.90251952999998), 'rotation':(-0.118439, 90.884232, -0.118927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.49109375, 4949.32470703, 175.94890625), 'rotation':(-0.084656, 90.881088, -0.0849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.66445312, 4938.06298828, 175.95941406000003), 'rotation':(-0.044556, 90.88102, -0.044647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.75085938, 4932.43261719, 175.96162109), 'rotation':(-0.02478, 90.880898, -0.02478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.83777344, 4926.80029297, 175.96306640999998), 'rotation':(-0.014862, 90.884415, -0.014862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.01109375, 4915.53613281, 175.96597656000003), 'rotation':(-0.014862, 90.884346, -0.014893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.18445312, 4904.27197266, 175.96886718999997), 'rotation':(-0.014862, 90.884346, -0.014893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.4446875, 4887.37792969, 175.97220703), 'rotation':(-0.014709, 90.884346, -0.014709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.53164062, 4881.74755859, 175.97064453), 'rotation':(0.003907, 90.881714, 0.003894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.70496094, 4870.48535156, 175.96048828), 'rotation':(0.060215, 90.880844, 0.060091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.87878906, 4859.22119141, 175.94867188), 'rotation':(0.060208, 90.885719, 0.060089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.96523438, 4853.59033203, 175.94275391), 'rotation':(0.060215, 90.880844, 0.060091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6496.13855469, 4842.32714844, 175.92818359), 'rotation':(0.068739, 90.883568, 0.068579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6496.22546875, 4836.69580078, 175.91933594), 'rotation':(0.086067, 90.879982, 0.085806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.74546875, 4802.91015625, 175.84357422000002), 'rotation':(0.150961, 90.881088, 0.150164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6505.47203125, 4780.51074219, 175.77521484000002), 'rotation':(-0.194916, -89.113403, -0.196228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6505.29820312, 4791.77441406, 175.81117188), 'rotation':(-0.177338, -89.118774, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.69128906, 4831.19287109, 175.90919922), 'rotation':(-0.120483, -89.116272, -0.121002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.43152344, 4848.08740234, 175.93599609), 'rotation':(-0.08606, -89.119995, -0.086304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.34507812, 4853.71972656, 175.94275391), 'rotation':(-0.068756, -89.116425, -0.068909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.17125, 4864.98242188, 175.95457031), 'rotation':(-0.060242, -89.114258, -0.060333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6504.084375, 4870.61474609, 175.96048828), 'rotation':(-0.060211, -89.119141, -0.060333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.99742188, 4876.24609375, 175.96640625), 'rotation':(-0.060211, -89.119141, -0.060333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6503.91101562, 4881.87646484, 175.97064453), 'rotation':(-0.041534, -89.118317, -0.041565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.82410156, 4887.50683594, 175.97220703), 'rotation':(-0.003906, -89.118286, -0.003906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.47742188, 4910.03369141, 175.96742188), 'rotation':(0.014869, -89.115662, 0.014858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.30359375, 4921.29785156, 175.96453125), 'rotation':(0.014869, -89.115662, 0.014858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.2171875, 4926.9296875, 175.96306640999998), 'rotation':(0.014712, -89.120758, 0.014697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.04382812, 4938.19189453, 175.95941406000003), 'rotation':(0.024766, -89.118988, 0.024755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6502.95691406, 4943.82324219, 175.95529297000002), 'rotation':(0.044546, -89.113556, 0.044488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.87046875, 4949.45361328, 175.94890625), 'rotation':(0.064696, -89.118958, 0.064547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.69714844, 4960.71679688, 175.93113281), 'rotation':(0.094632, -89.118835, 0.094328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.52332031, 4971.98046875, 175.91253906000003), 'rotation':(0.094537, -89.115753, 0.094237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.35, 4983.2421875, 175.89191406), 'rotation':(0.102555, -89.118958, 0.102185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.17664062, 4994.50585938, 175.86742188), 'rotation':(0.13435, -89.118805, 0.133719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.08972656, 5000.13720703, 175.85386719), 'rotation':(0.13435, -89.118805, 0.133719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.00328125, 5005.76904297, 175.83910156000002), 'rotation':(0.15023, -89.118774, 0.149456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.91640625, 5011.40039062, 175.82380859), 'rotation':(0.158194, -89.113098, 0.157321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.82996094, 5017.03222656, 175.80826172000002), 'rotation':(0.158194, -89.118652, 0.15732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.74304688, 5022.66308594, 175.79238281000002), 'rotation':(0.161623, -89.11795, 0.160718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.65664062, 5028.29394531, 175.77576172000002), 'rotation':(0.168774, -89.11792, 0.167779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.39636719, 5045.18945312, 175.72117188), 'rotation':(0.190036, -89.117798, 0.188785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.30945312, 5050.82128906, 175.70142578), 'rotation':(0.20399, -89.117676, 0.202541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.22253906, 5056.453125, 175.68091797), 'rotation':(0.211142, -89.117645, 0.209584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.5540625, 5204.99560547, 174.96708984), 'rotation':(-0.326263, 90.882492, -0.329987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.89539062, 5182.84375, 175.09113281), 'rotation':(-0.316528, 90.882408, -0.320038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.06578125, 5171.76806641, 175.1509375), 'rotation':(-0.31012, 90.885262, -0.313477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.40664062, 5149.61621094, 175.26728516), 'rotation':(-0.298309, 90.883759, -0.301422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.49207031, 5144.07861328, 175.29558594), 'rotation':(-0.293396, 90.883705, -0.296417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.6625, 5133.00244141, 175.35078125), 'rotation':(-0.28421, 90.883606, -0.287018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.74792969, 5127.46484375, 175.37769531), 'rotation':(-0.279449, 90.883575, -0.282196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.83335938, 5121.92675781, 175.40412109000002), 'rotation':(-0.274841, 90.883522, -0.277496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.91835938, 5116.38916016, 175.43007812), 'rotation':(-0.270111, 90.883484, -0.272644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.00378906, 5110.85107422, 175.45566406), 'rotation':(-0.265503, 90.883438, -0.267975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.0965625, 5099.77539062, 175.50605468999998), 'rotation':(-0.260071, 90.881821, -0.262451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6492.13074219, 5094.23535156, 175.53042968999998), 'rotation':(-0.253723, 90.881851, -0.255981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6500.38320312, 5110.97753906, 175.45566406), 'rotation':(0.263072, -89.115845, 0.260663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.87148438, 5144.20507812, 175.29558594), 'rotation':(0.288828, -89.116272, 0.285926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.36023438, 5177.43212891, 175.12113281), 'rotation':(0.303732, -89.117706, 0.300517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.27476562, 5182.97021484, 175.09113281), 'rotation':(0.310097, -89.114746, 0.306763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.01890625, 5199.58447266, 174.99849609), 'rotation':(0.323, -89.114563, 0.319379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.05507812, 5237.40429688, 174.78121094), 'rotation':(-0.33548, 90.885345, -0.339417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.88171875, 5248.67822266, 174.71509766), 'rotation':(-0.336639, 90.885712, -0.340607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.70789062, 5259.953125, 174.64882812), 'rotation':(-0.336639, 90.880463, -0.340607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.62097656, 5265.58984375, 174.61572266), 'rotation':(-0.33667, 90.886238, -0.340637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.53453125, 5271.22705078, 174.58259766), 'rotation':(-0.33667, 90.882431, -0.340637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.01355469, 5305.05029297, 174.38375), 'rotation':(-0.336823, 90.882576, -0.34082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.57945312, 5333.23632812, 174.21988281000003), 'rotation':(-0.324646, 90.883369, -0.328339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.405625, 5344.51074219, 174.15574218999998), 'rotation':(-0.322906, 90.884964, -0.326569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.31921875, 5350.14796875, 174.12392577999998), 'rotation':(-0.322906, 90.884964, -0.326569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.23230469, 5355.7846875, 174.09216797000002), 'rotation':(-0.321289, 90.884514, -0.324921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.14539062, 5361.42285156, 174.06056640999998), 'rotation':(-0.317963, 90.884476, -0.321503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.05898438, 5367.06054688, 174.02931640999998), 'rotation':(-0.314972, 90.884521, -0.318451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.79820312, 5383.9721875, 173.93759766), 'rotation':(-0.305084, 90.884331, -0.30835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.71132812, 5389.60984375, 173.90771484), 'rotation':(-0.30191, 90.8843, -0.305084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6487.624375, 5395.2465625, 173.87816406000002), 'rotation':(-0.297028, 90.881531, -0.30011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.45105469, 5406.52246094, 173.81986328), 'rotation':(-0.289581, 90.884308, -0.292542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6487.10390625, 5429.07179688, 173.7084375), 'rotation':(-0.269684, 90.879395, -0.272217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.01695312, 5434.70898438, 173.68171875), 'rotation':(-0.264801, 90.884087, -0.267273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6486.843125, 5445.984375, 173.62970703), 'rotation':(-0.257263, 90.889008, -0.259613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6486.66980469, 5457.26074219, 173.57919922000002), 'rotation':(-0.248413, 90.882072, -0.25058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6486.58289062, 5462.89890625, 173.55472656), 'rotation':(-0.242737, 90.882095, -0.244812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6486.4090625, 5474.17335938, 173.50763672000002), 'rotation':(-0.230865, 90.887222, -0.232727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6486.23523438, 5485.44773438, 173.46298828), 'rotation':(-0.219116, 90.881912, -0.220795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6485.97449219, 5502.36425781, 173.39998047), 'rotation':(-0.207031, 90.883331, -0.208527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.61460938, 5485.58007812, 173.46298828), 'rotation':(0.224966, -89.118103, 0.223198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.78796875, 5474.30566406, 173.50763672000002), 'rotation':(0.2367, -89.11795, 0.234767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.04921875, 5457.39304688, 173.57917969), 'rotation':(0.254459, -89.117798, 0.252213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.13609375, 5451.75539062, 173.60423828), 'rotation':(0.257286, -89.110992, 0.254977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.39636719, 5434.84277344, 173.68167968999998), 'rotation':(0.26967, -89.120575, 0.267146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.48328125, 5429.20507812, 173.70839844), 'rotation':(0.274697, -89.115845, 0.272071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.74351562, 5412.2934375, 173.79128906000003), 'rotation':(0.289593, -89.115662, 0.286674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.916875, 5401.01757812, 173.84886719), 'rotation':(0.297024, -89.118469, 0.293963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.26453125, 5378.46875, 173.9678125), 'rotation':(0.311429, -89.120941, 0.308067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.52476562, 5361.55664062, 174.06052734000002), 'rotation':(0.321292, -89.115479, 0.317708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.78503906, 5344.64453125, 174.15572265999998), 'rotation':(0.324632, -89.116608, 0.320959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.1321875, 5322.09521484, 174.28482422000002), 'rotation':(0.335089, -89.113342, 0.331191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.21914062, 5316.45849609, 174.31761719), 'rotation':(0.335089, -89.113342, 0.331191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.30601562, 5310.82128906, 174.35060547), 'rotation':(0.336824, -89.117432, 0.332885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.65320312, 5288.27246094, 174.48316406), 'rotation':(0.336762, -89.113831, 0.332832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.74011719, 5282.63574219, 174.51628906000002), 'rotation':(0.336667, -89.117554, 0.332732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.82703125, 5276.99804688, 174.54943359), 'rotation':(0.336667, -89.117554, 0.332732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.91394531, 5271.36132812, 174.58255859000002), 'rotation':(0.336667, -89.117554, 0.332732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.00039062, 5265.72412109, 174.61568359), 'rotation':(0.33664, -89.114288, 0.332702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.08726562, 5260.08691406, 174.64882812), 'rotation':(0.33664, -89.114288, 0.332702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.26109375, 5248.8125, 174.71507812), 'rotation':(0.33664, -89.119537, 0.332705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.43445312, 5237.53857422, 174.78117188), 'rotation':(0.333327, -89.114746, 0.329472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6485.30554688, 5545.82859375, 173.26324218999997), 'rotation':(-0.148529, 90.881561, -0.149292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.96523438, 5567.93601562, 173.20773438), 'rotation':(-0.118195, 90.881416, -0.118652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.88023438, 5573.46386719, 173.19597656000002), 'rotation':(-0.118195, 90.881416, -0.118652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.70984375, 5584.51757812, 173.17457031), 'rotation':(-0.095551, 90.882072, -0.095856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.624375, 5590.04492188, 173.16472656000002), 'rotation':(-0.095551, 90.882072, -0.095856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.45445312, 5601.098125, 173.14628906000002), 'rotation':(-0.095551, 90.882133, -0.095856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.36953125, 5606.62597656, 173.13726562), 'rotation':(-0.086853, 90.88607, -0.087097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.2840625, 5612.15382812, 173.129375), 'rotation':(-0.069214, 90.880829, -0.069397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.19910156, 5617.68066406, 173.12324218999998), 'rotation':(-0.051575, 90.880791, -0.051666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.94375, 5634.2621875, 173.11351562), 'rotation':(-0.025238, 90.882011, -0.025269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.68882812, 5650.84179688, 173.10623047), 'rotation':(-0.025146, 90.882004, -0.025177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6483.5184375, 5661.895, 173.10138672000002), 'rotation':(-0.011139, 90.881401, -0.011169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.43347656, 5667.42335938, 173.10007812), 'rotation':(0.017069, 90.881386, 0.017079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6483.34804688, 5672.95117188, 173.1003125), 'rotation':(0.017069, 90.881386, 0.017079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.26304688, 5678.47898438, 173.10212891), 'rotation':(0.031323, 90.881859, 0.031274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.17761719, 5684.00539062, 173.10513672000002), 'rotation':(0.03118, 90.881805, 0.031139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.92273438, 5700.585, 173.11416015999998), 'rotation':(0.03118, 90.881805, 0.031139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.83777344, 5706.1128125, 173.11728516), 'rotation':(0.036719, 90.882607, 0.036679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.2171875, 5706.24171875, 173.11728516), 'rotation':(-0.031158, -89.118195, -0.031219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.30210938, 5700.71390625, 173.11416015999998), 'rotation':(-0.031189, -89.114014, -0.031219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6491.47203125, 5689.66109375, 173.10814453), 'rotation':(-0.031158, -89.118195, -0.031219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6491.64246094, 5678.60789062, 173.10212891), 'rotation':(-0.01709, -89.118591, -0.01709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.72742188, 5673.08007812, 173.1003125), 'rotation':(0.011154, -89.118591, 0.011155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.49351562, 5623.33640625, 173.11890625), 'rotation':(0.051588, -89.119202, 0.05149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.57851562, 5617.80957031, 173.12324218999998), 'rotation':(0.069217, -89.119171, 0.069053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.74890625, 5606.75488281, 173.13726562), 'rotation':(0.095541, -89.117889, 0.095224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6492.91882812, 5595.70117188, 173.15550781000002), 'rotation':(0.095541, -89.117859, 0.095229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.08921875, 5584.64695312, 173.17457031), 'rotation':(0.103163, -89.118652, 0.102803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.25964844, 5573.59328125, 173.19597656000002), 'rotation':(0.133359, -89.115631, 0.132735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.34460938, 5568.06542969, 173.20773438), 'rotation':(0.133359, -89.115631, 0.132735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.6, 5551.48535156, 173.2484375), 'rotation':(0.155967, -89.117554, 0.155131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.68492188, 5545.95800781, 173.26324218999997), 'rotation':(0.155967, -89.117554, 0.155131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.16589844, 5749.73921875, 173.17222656), 'rotation':(0.103327, 90.879044, 0.102962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.990625, 5761.11421875, 173.19373047000002), 'rotation':(0.114809, 90.879005, 0.114358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.90320312, 5766.80125, 173.20542969), 'rotation':(0.126502, 90.884636, 0.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.72789062, 5778.17671875, 173.23070312), 'rotation':(0.138011, 90.884689, 0.137345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.46523438, 5795.23921875, 173.27310547000002), 'rotation':(0.14924, 90.88018, 0.148471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.02722656, 5823.67773438, 173.35279297), 'rotation':(0.176233, 90.885475, 0.175149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.93984375, 5829.36523438, 173.37042968999998), 'rotation':(0.181471, 90.880356, 0.180334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.76453125, 5840.74070312, 173.40728516), 'rotation':(0.189654, 90.882088, 0.188395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6480.58921875, 5852.11570312, 173.44529297), 'rotation':(0.195118, 90.882339, 0.19379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.50183594, 5857.80320312, 173.46484375), 'rotation':(0.202413, 90.882271, 0.200996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.3265625, 5869.17773438, 173.50513672), 'rotation':(0.209769, 90.882423, 0.208229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.15125, 5880.55273438, 173.54708984), 'rotation':(0.217091, 90.888062, 0.215445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.06382812, 5886.24070312, 173.56867188), 'rotation':(0.218873, 90.882812, 0.217216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.88855469, 5897.61523438, 173.61228516), 'rotation':(0.221004, 90.880959, 0.219305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.80117188, 5903.30226562, 173.63423827999998), 'rotation':(0.225205, 90.883919, 0.223441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.71375, 5908.98921875, 173.6565625), 'rotation':(0.229214, 90.883896, 0.227384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.5384375, 5920.36375, 173.70175781), 'rotation':(0.233415, 90.881073, 0.231517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.45105469, 5926.05125, 173.72470703), 'rotation':(0.233415, 90.881073, 0.231517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.74257812, 5931.86960938, 173.74787109000002), 'rotation':(-0.233429, -89.116058, -0.235321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.82996094, 5926.183125, 173.72470703), 'rotation':(-0.229218, -89.116089, -0.231049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.093125, 5909.12109375, 173.6565625), 'rotation':(-0.22522, -89.116089, -0.22699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.26796875, 5897.7465625, 173.61228516), 'rotation':(-0.218872, -89.117157, -0.220551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.7059375, 5869.3090625, 173.50515625), 'rotation':(-0.206116, -89.117615, -0.207611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.79382812, 5863.6215625, 173.48478516), 'rotation':(-0.202423, -89.117706, -0.203857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.88125, 5857.9340625, 173.46484375), 'rotation':(-0.198792, -89.117645, -0.200165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.96863281, 5852.2465625, 173.44529297), 'rotation':(-0.191467, -89.117676, -0.192749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.05652344, 5846.55953125, 173.42617188), 'rotation':(-0.189636, -89.117889, -0.190918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.40664062, 5823.80859375, 173.35279297), 'rotation':(-0.170685, -89.119781, -0.171661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.49402344, 5818.12109375, 173.33572266), 'rotation':(-0.165436, -89.114502, -0.166412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.58191406, 5812.43359375, 173.31921875), 'rotation':(-0.160034, -89.119843, -0.160919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6489.66929688, 5806.745625, 173.30328125), 'rotation':(-0.154785, -89.114563, -0.15564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6489.84460938, 5795.36960938, 173.273125), 'rotation':(-0.146637, -89.114502, -0.1474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6490.01941406, 5783.99460938, 173.24431640999998), 'rotation':(-0.138, -89.115295, -0.138672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.1946875, 5772.61960938, 173.21775391), 'rotation':(-0.126495, -89.115356, -0.127075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6490.28257812, 5766.93164062, 173.20544922000002), 'rotation':(-0.120667, -89.115387, -0.121185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.37, 5761.24460938, 173.19373047000002), 'rotation':(-0.109161, -89.115417, -0.109589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.63269531, 5744.18164062, 173.16220703), 'rotation':(-0.0961, -89.121887, -0.096436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6529.83335938, 5071.00976562, 176.17414062), 'rotation':(-0.974121, -179.404373, -1.00769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6541.12878906, 5071.12451172, 176.36523438), 'rotation':(-0.96698, -179.404602, -1.000061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.42421875, 5071.23876953, 176.555), 'rotation':(-0.960083, -179.404816, -0.992676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6580.6625, 5071.52539062, 177.02416015999998), 'rotation':(-0.947449, -179.40419, -0.979187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.31042969, 5071.58300781, 177.11757812), 'rotation':(-0.947571, -179.40419, -0.979309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6591.95835938, 5071.64013672, 177.210625), 'rotation':(-0.942749, -179.40361, -0.974152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.25328125, 5071.75488281, 177.39541015999998), 'rotation':(-0.933411, -179.400955, -0.964203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6614.5496875, 5071.86914062, 177.57878906000002), 'rotation':(-0.928558, -179.405594, -0.959015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.84507812, 5071.98046875, 177.76189452999998), 'rotation':(-0.928619, -179.402634, -0.959106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6665.37929688, 5072.41845703, 178.39277343999998), 'rotation':(-0.903778, -179.404205, -0.932617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6671.02722656, 5072.47558594, 178.4815625), 'rotation':(-0.900238, -179.404068, -0.928894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6682.32361328, 5072.59033203, 178.65886719), 'rotation':(-0.897308, -179.406021, -0.925751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6687.9715625, 5072.64746094, 178.74707031000003), 'rotation':(-0.897308, -179.406021, -0.925751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6693.61902344, 5072.70507812, 178.83496093999997), 'rotation':(-0.891388, -179.406174, -0.919434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6710.56335938, 5072.87646484, 179.0959375), 'rotation':(-0.879425, -179.406601, -0.906738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6721.85974609, 5072.99121094, 179.26878906000002), 'rotation':(-0.876587, -179.405045, -0.903717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6744.45203125, 5073.22070312, 179.61306641), 'rotation':(-0.869202, -179.404022, -0.895905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6750.07214844, 5081.62548828, 179.69898438), 'rotation':(0.859661, 0.595693, 0.834144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6744.42419922, 5081.56835938, 179.61394531000002), 'rotation':(0.864422, 0.595788, 0.838639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.1278125, 5081.45361328, 179.44242188), 'rotation':(0.874059, 0.59613, 0.847691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6727.48083984, 5081.39648438, 179.35613281000002), 'rotation':(0.87658, 0.594962, 0.850066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.18445312, 5081.28222656, 179.18326172000002), 'rotation':(0.87658, 0.594962, 0.850066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6699.24060547, 5081.11035156, 178.92316406), 'rotation':(0.879421, 0.593403, 0.852731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6693.59363281, 5081.05273438, 178.83587891), 'rotation':(0.885418, 0.59702, 0.858365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6687.94568359, 5080.99560547, 178.74798828), 'rotation':(0.891374, 0.593809, 0.863947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6676.65125, 5080.88085938, 178.57130859), 'rotation':(0.897316, 0.597391, 0.869528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6648.41148438, 5080.59423828, 178.12560547), 'rotation':(0.910908, 0.593239, 0.882282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6637.115625, 5080.47949219, 177.945), 'rotation':(0.918018, 0.596275, 0.888941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6608.87734375, 5080.19287109, 177.48822266), 'rotation':(0.928537, 0.597357, 0.898802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.22984375, 5080.13574219, 177.39642578), 'rotation':(0.928537, 0.597357, 0.898802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6591.93445312, 5080.02099609, 177.21160156000002), 'rotation':(0.933407, 0.596115, 0.903356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.2875, 5079.96337891, 177.11861327999998), 'rotation':(0.94275, 0.596389, 0.912099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.05066406, 5079.67724609, 176.65046875), 'rotation':(0.952846, 0.599572, 0.921546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.40222656, 5079.62011719, 176.55605469), 'rotation':(0.956343, 0.59502, 0.924815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6535.45984375, 5079.44824219, 176.27091797), 'rotation':(0.966991, 0.600049, 0.93475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6529.81140625, 5079.390625, 176.17519531000002), 'rotation':(0.970577, 0.595546, 0.938094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6512.86953125, 5079.21875, 175.88667969), 'rotation':(0.975986, 0.598756, 0.943154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(7008.76453125, 5075.87011719, 183.34714843999998), 'rotation':(-0.755768, -179.411163, -0.775909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(7003.44373047, 5075.81591797, 183.27695312), 'rotation':(-0.758698, -179.406418, -0.778992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6992.11804688, 5075.70117188, 183.12671875), 'rotation':(-0.764679, -179.410934, -0.785309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6980.79138672, 5075.5859375, 182.97535156), 'rotation':(-0.770782, -179.410767, -0.791748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6969.46570312, 5075.47119141, 182.82287109), 'rotation':(-0.776764, -179.410599, -0.798065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6958.13904297, 5075.35595703, 182.66933594), 'rotation':(-0.778351, -179.405563, -0.799744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6952.47693359, 5075.29882812, 182.59238281), 'rotation':(-0.780304, -179.410645, -0.801758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6929.82458984, 5075.06884766, 182.28234375), 'rotation':(-0.792053, -179.406937, -0.814209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6912.83582031, 5074.89648438, 182.04732422), 'rotation':(-0.793915, -179.41011, -0.816132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6907.17224609, 5074.83886719, 181.96882812), 'rotation':(-0.793915, -179.41011, -0.816132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6890.18396484, 5074.66650391, 181.7325), 'rotation':(-0.806946, -179.409592, -0.829956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6878.85779297, 5074.55175781, 181.57292969), 'rotation':(-0.812195, -179.405045, -0.83548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6873.19568359, 5074.49414062, 181.49257812), 'rotation':(-0.814758, -179.41124, -0.838196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6861.86951172, 5074.37939453, 181.33144531000002), 'rotation':(-0.814789, -179.406128, -0.838196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.20642578, 5074.32177734, 181.25087890999998), 'rotation':(-0.81485, -179.406067, -0.838287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.88025391, 5074.20703125, 181.08941406000002), 'rotation':(-0.820679, -179.405029, -0.844452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6839.21716797, 5074.14941406, 181.00826172), 'rotation':(-0.824554, -179.404953, -0.848572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6799.57898438, 5073.74707031, 180.43337891), 'rotation':(-0.841431, -179.405991, -0.866425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6788.13269531, 5082.01220703, 180.26634765999998), 'rotation':(0.841411, 0.59052, 0.816958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6793.79578125, 5082.06933594, 180.34972656000002), 'rotation':(0.841411, 0.59052, 0.816958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.12195312, 5082.18457031, 180.51560547), 'rotation':(0.8326, 0.593745, 0.808656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6810.78455078, 5082.2421875, 180.59806641), 'rotation':(0.8326, 0.593745, 0.808656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6827.77332031, 5082.4140625, 180.84445312), 'rotation':(0.828434, 0.591117, 0.804733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.76257812, 5082.58642578, 181.08894531), 'rotation':(0.816665, 0.594814, 0.793627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6850.42517578, 5082.64404297, 181.16976562), 'rotation':(0.814842, 0.593928, 0.791901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.08826172, 5082.70166016, 181.25041016), 'rotation':(0.814773, 0.58876, 0.791847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6867.41394531, 5082.81689453, 181.41152344), 'rotation':(0.814773, 0.593871, 0.791838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6901.39148438, 5083.16162109, 181.88986328), 'rotation':(0.7939, 0.592794, 0.77213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6907.05457031, 5083.21875, 181.96835938), 'rotation':(0.794037, 0.592825, 0.77226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6912.71814453, 5083.27636719, 182.04689453), 'rotation':(0.794037, 0.592825, 0.77226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6929.70789062, 5083.44873047, 182.28191406000002), 'rotation':(0.788019, 0.59289, 0.766568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6935.37097656, 5083.50634766, 182.35982422), 'rotation':(0.784188, 0.589457, 0.76293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.03357422, 5083.56347656, 182.43740234), 'rotation':(0.780294, 0.592713, 0.759255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6946.69666016, 5083.62109375, 182.51480468999998), 'rotation':(0.780294, 0.592713, 0.759255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6963.68689453, 5083.80371094, 182.74580078), 'rotation':(0.776777, 0.594065, 0.755917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6969.34949219, 5083.83300781, 182.82244140999998), 'rotation':(0.77386, 0.589317, 0.75316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.01355469, 5083.87890625, 182.89884766), 'rotation':(0.770794, 0.593903, 0.75026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6980.67615234, 5083.93310547, 182.97494140999999), 'rotation':(0.767795, 0.593871, 0.747417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.33923828, 5083.99023438, 183.05076172), 'rotation':(0.764674, 0.589072, 0.744458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7008.67761719, 5084.21728516, 183.34712890999998), 'rotation':(0.754121, 0.590965, 0.734457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6755.85583984, 4560.20117188, 178.18984375), 'rotation':(0.829315, 0.080985, 0.805552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6750.28650391, 4560.19484375, 178.10894531000002), 'rotation':(0.831869, 0.078178, 0.807974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6731.39734375, 4560.0703125, 177.83365234000001), 'rotation':(0.837122, 0.08121, 0.812916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.85730469, 4560.13671875, 177.95716797), 'rotation':(0.834594, 0.081135, 0.810552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6700.16394531, 4560.00585938, 177.37638672), 'rotation':(0.838385, 0.076977, 0.814111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6689.02527344, 4559.99265625, 177.21232422), 'rotation':(0.845612, 0.080215, 0.820918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6677.88708984, 4559.97949219, 177.04791016), 'rotation':(0.845612, 0.080215, 0.820918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6672.31773438, 4559.97265625, 176.96570312), 'rotation':(0.845468, 0.080209, 0.820788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6666.74890625, 4559.96582031, 176.88339843999998), 'rotation':(0.845468, 0.080209, 0.820788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6650.04234375, 4559.94628906, 176.63542969), 'rotation':(0.851977, 0.082904, 0.826911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6638.90320312, 4559.933125, 176.46892577999998), 'rotation':(0.856232, 0.08022, 0.830914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6633.334375, 4559.92675781, 176.38525391), 'rotation':(0.860488, 0.080346, 0.834926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6622.19714844, 4559.91359375, 176.21765625), 'rotation':(0.862742, 0.080324, 0.837049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6605.49011719, 4559.89355469, 175.96599609), 'rotation':(0.862742, 0.085136, 0.837043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.35144531, 4559.87988281, 175.79722656), 'rotation':(0.869667, 0.08234, 0.843555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6583.21328125, 4559.8671875, 175.62761719), 'rotation':(0.872249, 0.080269, 0.845996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6577.64539062, 4559.86035156, 175.5428125), 'rotation':(0.872099, 0.08361, 0.84585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6560.93835938, 4559.8403125, 175.28710938), 'rotation':(0.880364, 0.08446, 0.853608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6549.7996875, 4559.82714844, 175.11533203), 'rotation':(0.883676, 0.080394, 0.856731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6538.66199219, 4559.81398438, 174.94251953), 'rotation':(0.890192, 0.08477, 0.862845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6533.09265625, 4559.80710938, 174.85566406), 'rotation':(0.893382, 0.08069, 0.865844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6521.9559375, 4559.79394531, 174.68132812), 'rotation':(0.896715, 0.0808, 0.868961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6748.06189453, 4551.55226562, 178.07648438), 'rotation':(-0.834625, -179.918869, -0.859192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.15808594, 4551.59226562, 177.94683593999997), 'rotation':(-0.837067, -179.918777, -0.861816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6728.02039062, 4551.65332031, 177.78414062), 'rotation':(-0.83844, -179.923004, -0.863281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.88269531, 4551.645, 177.62113281), 'rotation':(-0.838379, -179.918396, -0.86319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6700.17517578, 4551.625, 177.37640625), 'rotation':(-0.84198, -179.917725, -0.867004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6694.60583984, 4551.61867188, 177.29453125), 'rotation':(-0.845612, -179.919785, -0.87085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6689.03699219, 4551.61179688, 177.21236327999998), 'rotation':(-0.845459, -179.919785, -0.870697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6677.89832031, 4551.59863281, 177.04792969), 'rotation':(-0.845459, -179.919785, -0.870697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6666.76015625, 4551.58496094, 176.88339843999998), 'rotation':(-0.847687, -179.920029, -0.873047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6650.053125, 4551.56542969, 176.63544922), 'rotation':(-0.856232, -179.919785, -0.882111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6638.91492188, 4551.55226562, 176.46894531), 'rotation':(-0.860474, -179.919647, -0.886627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6633.34507812, 4551.54589844, 176.38527344), 'rotation':(-0.862671, -179.919693, -0.888947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6622.20789062, 4551.53273438, 176.21767577999998), 'rotation':(-0.862762, -179.919678, -0.889038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.6390625, 4551.52585938, 176.13380859), 'rotation':(-0.862518, -179.919693, -0.888794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6611.06921875, 4551.5190625, 176.04990234000002), 'rotation':(-0.862671, -179.914871, -0.888947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6605.50039062, 4551.51269531, 175.96599609), 'rotation':(-0.865112, -179.922729, -0.891541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.36265625, 4551.49902344, 175.79724609000002), 'rotation':(-0.872284, -179.919724, -0.899139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6588.79285156, 4551.49265625, 175.71244141), 'rotation':(-0.872101, -179.916382, -0.898956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6572.08726562, 4551.473125, 175.45789062), 'rotation':(-0.877045, -179.919815, -0.904205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6566.51746094, 4551.46632812, 175.37261718999997), 'rotation':(-0.880371, -179.915527, -0.907745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6560.94910156, 4551.45945312, 175.28710938), 'rotation':(-0.883698, -179.919601, -0.911285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6549.8109375, 4551.44628906, 175.11533203), 'rotation':(-0.886871, -179.91951, -0.914673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6544.24207031, 4551.43992188, 175.02908202999998), 'rotation':(-0.890198, -179.919403, -0.918182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6521.96667969, 4551.41308594, 174.68134766), 'rotation':(-0.898346, -179.916718, -0.926849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7006.17859375, 4551.89992188, 181.7596875), 'rotation':(-0.808105, -179.919235, -0.831146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6989.06384766, 4551.96777344, 181.51818359), 'rotation':(-0.809204, -179.921082, -0.832306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6983.49353516, 4551.96140625, 181.43951172), 'rotation':(-0.809052, -179.921082, -0.832153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6972.35144531, 4551.94824219, 181.28212890999998), 'rotation':(-0.809052, -179.915894, -0.832123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6966.78162109, 4551.94140625, 181.2034375), 'rotation':(-0.809357, -179.924164, -0.832458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6955.64050781, 4551.92820312, 181.04597656), 'rotation':(-0.810211, -179.91954, -0.833374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6950.07019531, 4551.921875, 180.96716797000002), 'rotation':(-0.810791, -179.919525, -0.833984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6927.78796875, 4551.89550781, 180.65152343999998), 'rotation':(-0.812653, -179.919464, -0.835968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6922.21716797, 4551.88867188, 180.5725), 'rotation':(-0.812988, -179.920776, -0.836304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6916.64636719, 4551.88234375, 180.49345703), 'rotation':(-0.812988, -179.920776, -0.836304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6911.07605469, 4551.87546875, 180.41439452999998), 'rotation':(-0.812988, -179.920776, -0.836304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6866.51111328, 4551.82226562, 179.780625), 'rotation':(-0.816528, -179.920288, -0.840057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6860.94080078, 4551.8159375, 179.70123047), 'rotation':(-0.816528, -179.920288, -0.840057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6855.37048828, 4551.8090625, 179.62183593999998), 'rotation':(-0.81839, -179.920227, -0.842041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6833.08777344, 4551.78273438, 179.30294922000002), 'rotation':(-0.822205, -179.92012, -0.846069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6821.94714844, 4551.77, 179.14296875), 'rotation':(-0.823181, -179.91745, -0.847107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6799.66541016, 4551.74316406, 178.82265625), 'rotation':(-0.826477, -179.919861, -0.850555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6794.09460938, 4551.73679688, 178.74240234), 'rotation':(-0.826477, -179.919861, -0.850555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6794.04480469, 4560.1171875, 178.74181640999998), 'rotation':(0.824178, 0.080056, 0.800715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6799.61560547, 4560.12402344, 178.82208984000002), 'rotation':(0.824178, 0.080056, 0.800715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6821.89832031, 4560.14992188, 179.14240234000002), 'rotation':(0.823188, 0.082555, 0.799778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.03796875, 4560.16359375, 179.30238281), 'rotation':(0.820347, 0.079816, 0.797099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6849.74988281, 4560.183125, 179.54166016), 'rotation':(0.818393, 0.07976, 0.795261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6855.32019531, 4560.18992188, 179.62125), 'rotation':(0.816535, 0.079707, 0.793505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6866.46130859, 4560.203125, 179.78003906), 'rotation':(0.815545, 0.080039, 0.792568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6872.03210938, 4560.20996094, 179.859375), 'rotation':(0.81562, 0.080033, 0.792648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6877.60291016, 4560.21632812, 179.93869141), 'rotation':(0.815545, 0.080039, 0.792568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6883.17322266, 4560.223125, 180.01800781000003), 'rotation':(0.81562, 0.080033, 0.792648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6888.74353516, 4560.22949219, 180.09732422000002), 'rotation':(0.81422, 0.078845, 0.79132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6899.88513672, 4560.24265625, 180.25570312), 'rotation':(0.81297, 0.07922, 0.790143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6905.4559375, 4560.24953125, 180.33476561999998), 'rotation':(0.81297, 0.07922, 0.790143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6922.16736328, 4560.26953125, 180.57195312), 'rotation':(0.812656, 0.080524, 0.789844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6944.45007812, 4560.29882812, 180.88775391), 'rotation':(0.810791, 0.080471, 0.788081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6950.02039062, 4560.30957031, 180.96660156000002), 'rotation':(0.810211, 0.080455, 0.787539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6961.16150391, 4560.29492188, 181.12416016), 'rotation':(0.809357, 0.075828, 0.78673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6972.30310547, 4560.29589844, 181.28158202999998), 'rotation':(0.809207, 0.08411, 0.786586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6977.87341797, 4560.30273438, 181.36025390999998), 'rotation':(0.809043, 0.078915, 0.786429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6989.01404297, 4560.3159375, 181.51761718999998), 'rotation':(0.808578, 0.078504, 0.785991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7005.72644531, 4560.50585938, 181.75345703), 'rotation':(0.807984, 0.077109, 0.785424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7011.29626953, 4560.51269531, 181.83201172), 'rotation':(0.80808, 0.080762, 0.785535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6766.65710938, 5242.40332031, 179.50457031000002), 'rotation':(-0.228088, 90.486, -0.229889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.67371094, 5253.67236328, 179.45955078), 'rotation':(-0.229828, 90.488319, -0.231689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.57800781, 5264.94482422, 179.41429688), 'rotation':(-0.230774, 90.489281, -0.232635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.43494141, 5281.85302734, 179.34570312), 'rotation':(-0.236328, 90.485031, -0.238281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6766.38708984, 5287.48925781, 179.3225), 'rotation':(-0.237366, 90.489288, -0.239349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6766.24402344, 5304.39697266, 179.25251953), 'rotation':(-0.237579, 90.485962, -0.239532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.14832031, 5315.66943359, 179.20582031), 'rotation':(-0.237732, 90.488876, -0.239716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.05261719, 5326.94091797, 179.15904297), 'rotation':(-0.237915, 90.485954, -0.239899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.95691406, 5338.21335938, 179.11220702999998), 'rotation':(-0.238281, 90.488899, -0.240265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.86072266, 5349.48484375, 179.0653125), 'rotation':(-0.237976, 90.485779, -0.23996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.81287109, 5355.1215625, 179.041875), 'rotation':(-0.237976, 90.485779, -0.23996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.47791016, 5394.57273438, 178.88095703), 'rotation':(-0.229156, 90.488434, -0.230988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.43005859, 5400.20945312, 178.85839843999997), 'rotation':(-0.229126, 90.488388, -0.230957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.38220703, 5405.84472656, 178.83585938), 'rotation':(-0.227692, 90.487076, -0.229492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.19080078, 5428.38964844, 178.74724609), 'rotation':(-0.219025, 90.487022, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.14294922, 5434.02585938, 178.72554688), 'rotation':(-0.219025, 90.487022, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.09509766, 5439.66210938, 178.70400390999998), 'rotation':(-0.217438, 90.484566, -0.219116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6764.95203125, 5456.57128906, 178.64003906000002), 'rotation':(-0.212311, 90.485252, -0.213867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6764.85632812, 5467.84421875, 178.59876953), 'rotation':(-0.205688, 90.490723, -0.207153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6764.61707031, 5496.02492188, 178.50185547), 'rotation':(-0.190369, 90.484612, -0.19162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6764.56921875, 5501.66113281, 178.483125), 'rotation':(-0.190369, 90.484612, -0.19162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.94958984, 5501.73535156, 178.48310547), 'rotation':(0.190344, -89.512024, 0.189099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.04529297, 5490.46335938, 178.52060547000002), 'rotation':(0.192058, -89.514862, 0.190771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.09314453, 5484.82664062, 178.53958984000002), 'rotation':(0.195473, -89.509338, 0.194146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.14099609, 5479.1909375, 178.55896484000002), 'rotation':(0.198861, -89.514832, 0.197488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.18884766, 5473.55371094, 178.57869141), 'rotation':(0.205684, -89.509277, 0.204205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.23669922, 5467.9184375, 178.59876953), 'rotation':(0.209058, -89.514771, 0.207546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.33240234, 5456.64550781, 178.64003906000002), 'rotation':(0.215889, -89.509216, 0.214262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.76257812, 5405.91992188, 178.83583984), 'rotation':(0.229153, -89.516541, 0.227313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.85828125, 5394.64796875, 178.88095703), 'rotation':(0.229795, -89.514282, 0.227958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.0496875, 5372.10449219, 178.97214843999998), 'rotation':(0.234228, -89.514252, 0.232309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.24158203, 5349.56054688, 179.06529297), 'rotation':(0.23838, -89.514191, 0.236403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.28943359, 5343.92429688, 179.08875), 'rotation':(0.238278, -89.511108, 0.236302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.38513672, 5332.65234375, 179.13560547), 'rotation':(0.237909, -89.514038, 0.235948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.52869141, 5315.74462891, 179.20580078), 'rotation':(0.23754, -89.514038, 0.235585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.62390625, 5304.47216797, 179.2525), 'rotation':(0.237274, -89.510712, 0.235309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.71960938, 5293.20068359, 179.29919922000002), 'rotation':(0.236338, -89.514923, 0.234393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.76746094, 5287.56445312, 179.3225), 'rotation':(0.236338, -89.514923, 0.234393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.81482422, 5281.92822266, 179.34568359000002), 'rotation':(0.23459, -89.510742, 0.232686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.91003906, 5270.65576172, 179.39160156000003), 'rotation':(0.230744, -89.510742, 0.22889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6775.05408203, 5253.74755859, 179.45953125), 'rotation':(0.229843, -89.51532, 0.228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.18445312, 5193.44189453, 179.68974609), 'rotation':(-0.211578, 90.486282, -0.213135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.23181641, 5187.90771484, 179.70986327999998), 'rotation':(-0.208191, 90.48613, -0.209686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.27869141, 5182.37304688, 179.72939452999998), 'rotation':(-0.201874, 90.486107, -0.203308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.41931641, 5165.77246094, 179.78523438), 'rotation':(-0.188721, 90.490028, -0.189941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.65417969, 5138.10205078, 179.87324218999998), 'rotation':(-0.181152, 90.487091, -0.182312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.70154297, 5132.56787109, 179.88992188), 'rotation':(-0.172577, 90.484116, -0.173584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.74841797, 5127.03369141, 179.90580078), 'rotation':(-0.16394, 90.487, -0.164886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.84216797, 5115.96582031, 179.93648438), 'rotation':(-0.155334, 90.486969, -0.156189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.93591797, 5104.89794922, 179.96587891), 'rotation':(-0.151093, 90.487633, -0.151886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.03015625, 5093.83007812, 179.99414062), 'rotation':(-0.147125, 90.485794, -0.147888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.47107422, 5204.58154297, 179.64892577999998), 'rotation':(0.211572, -89.513702, 0.210021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.51794922, 5199.04785156, 179.669375), 'rotation':(0.211572, -89.513702, 0.210021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6775.6590625, 5182.4453125, 179.72939452999998), 'rotation':(0.195152, -89.513977, 0.193824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.7059375, 5176.91162109, 179.74845703), 'rotation':(0.188698, -89.509949, 0.187473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.7528125, 5171.37744141, 179.76705077999998), 'rotation':(0.188698, -89.509949, 0.187473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.84705078, 5160.31005859, 179.80314453), 'rotation':(0.185433, -89.513367, 0.184235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.98767578, 5143.70800781, 179.85628906000002), 'rotation':(0.172558, -89.515869, 0.171518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6776.08191406, 5132.64013672, 179.88992188), 'rotation':(0.163945, -89.513, 0.163012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.12878906, 5127.10595703, 179.90580078), 'rotation':(0.155339, -89.513031, 0.154495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.26941406, 5110.50390625, 179.95128906000002), 'rotation':(0.151084, -89.51236, 0.150288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.31628906, 5104.96972656, 179.96585938), 'rotation':(0.147129, -89.514191, 0.146373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.36316406, 5099.43652344, 179.98019531000003), 'rotation':(0.139363, -89.514221, 0.138695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.30457031, 5061.44287109, 180.06484375), 'rotation':(-0.11145, 90.485931, -0.111877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.53943359, 5033.78222656, 180.11179688), 'rotation':(-0.083069, 90.484306, -0.083313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.63367188, 5022.71679688, 180.12654297), 'rotation':(-0.070526, 90.489105, -0.070679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.72742188, 5011.65185547, 180.13910156000003), 'rotation':(-0.064148, 90.484245, -0.064301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6768.77429688, 5006.11914062, 180.14498047), 'rotation':(-0.060944, 90.487587, -0.061066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.82117188, 5000.58789062, 180.15039062), 'rotation':(-0.055145, 90.486389, -0.055267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6768.86804688, 4995.05566406, 180.15509766), 'rotation':(-0.055145, 90.486389, -0.055267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6768.96228516, 4983.99072266, 180.16207031000002), 'rotation':(-0.03186, 90.486366, -0.031921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.05603516, 4972.92578125, 180.165625), 'rotation':(-0.014374, 90.484917, -0.014374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.19714844, 4956.32861328, 180.1690625), 'rotation':(-0.01001, 90.487, -0.009979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.29089844, 4945.26367188, 180.16814452999998), 'rotation':(0.007377, 90.487, 0.00738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6776.68542969, 5061.51464844, 180.06484375), 'rotation':(0.108327, -89.515594, 0.107927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.10779297, 5011.72363281, 180.13910156000003), 'rotation':(0.060932, -89.512421, 0.060814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6777.15466797, 5006.19091797, 180.14498047), 'rotation':(0.055154, -89.51355, 0.055048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6777.29529297, 4989.59472656, 180.15900391), 'rotation':(0.03187, -89.513641, 0.031826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.38953125, 4978.52929688, 180.1640625), 'rotation':(0.014364, -89.515076, 0.014359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.43640625, 4972.99755859, 180.165625), 'rotation':(0.014494, -89.515076, 0.014489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.48328125, 4967.46484375, 180.16703125), 'rotation':(0.014494, -89.515076, 0.014489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.57751953, 4956.40039062, 180.1690625), 'rotation':(0.00138, -89.513, 0.001386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6777.67126953, 4945.33544922, 180.16814452999998), 'rotation':(-0.015991, -89.513, -0.015991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6769.56580078, 4912.87744141, 180.146875), 'rotation':(0.055277, 90.481056, 0.055176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.61267578, 4907.35449219, 180.14128906000002), 'rotation':(0.058057, 90.488518, 0.057937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.84705078, 4879.74169922, 180.10595702999998), 'rotation':(0.095418, 90.488022, 0.095114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.89392578, 4874.21972656, 180.09623047000002), 'rotation':(0.095418, 90.488022, 0.095114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.94080078, 4868.69628906, 180.08560547000002), 'rotation':(0.110335, 90.484665, 0.109925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.03455078, 4857.65136719, 180.06294922), 'rotation':(0.117834, 90.488693, 0.117358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.08142578, 4852.12939453, 180.05136718999998), 'rotation':(0.117821, 90.484779, 0.117355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.12830078, 4846.60644531, 180.03929688), 'rotation':(0.125416, 90.487236, 0.124865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.17517578, 4841.08398438, 180.02605469), 'rotation':(0.140517, 90.487274, 0.139831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.26892578, 4830.03808594, 179.99710938), 'rotation':(0.155646, 90.484024, 0.154791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.36267578, 4818.99462891, 179.96433593999998), 'rotation':(0.17085, 90.487465, 0.169836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.40955078, 4813.47119141, 179.94714843999998), 'rotation':(0.17837, 90.485916, 0.177274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.4559375, 4807.94824219, 179.92994141), 'rotation':(0.17837, 90.48941, 0.177263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.5496875, 4796.90332031, 179.89460938), 'rotation':(0.185446, 90.485397, 0.184241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.83142578, 4763.76757812, 179.76726562), 'rotation':(0.235075, 90.486801, 0.233167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.92419922, 4752.72314453, 179.720625), 'rotation':(0.248988, 90.487854, 0.246834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.97107422, 4747.20019531, 179.69625), 'rotation':(0.248988, 90.487854, 0.246834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.01794922, 4741.67773438, 179.67113281000002), 'rotation':(0.258188, 90.48793, 0.255876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.13367188, 4890.85888672, 180.12269531), 'rotation':(-0.080505, -89.515411, -0.080719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.18054688, 4885.3359375, 180.11494141), 'rotation':(-0.095428, -89.511963, -0.095734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.22742188, 4879.81298828, 180.10595702999998), 'rotation':(-0.110352, -89.515289, -0.110779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.55554688, 4841.15576172, 180.02605469), 'rotation':(-0.15564, -89.515991, -0.156464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6778.64929688, 4830.11035156, 179.99710938), 'rotation':(-0.170868, -89.512512, -0.171875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.74304688, 4819.06591797, 179.96431640999998), 'rotation':(-0.178406, -89.514069, -0.179504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6778.78992188, 4813.54345703, 179.94714843999998), 'rotation':(-0.178375, -89.51059, -0.179474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.02429688, 4785.9296875, 179.85533203), 'rotation':(-0.213806, -89.510742, -0.215393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.07117188, 4780.40820312, 179.83445312), 'rotation':(-0.228058, -89.514252, -0.229889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.11755859, 4774.88476562, 179.81246094), 'rotation':(-0.234924, -89.513245, -0.236847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.21130859, 4763.83935547, 179.76726562), 'rotation':(-0.239624, -89.512207, -0.241669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6779.35144531, 4747.27246094, 179.69625), 'rotation':(-0.258209, -89.512024, -0.260559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.29285156, 4709.28955078, 179.50966797), 'rotation':(0.297919, 90.488083, 0.294839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.38660156, 4698.23535156, 179.45126953), 'rotation':(0.303383, 90.48555, 0.300184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.43347656, 4692.70751953, 179.42087891), 'rotation':(0.31479, 90.489914, 0.311357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.48035156, 4687.18017578, 179.38945311999998), 'rotation':(0.326046, 90.485779, 0.322355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.57410156, 4676.12646484, 179.32427734), 'rotation':(0.342992, 90.48616, 0.338908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.66833984, 4665.07128906, 179.25800781), 'rotation':(0.342875, 90.490608, 0.338803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.71521484, 4659.54394531, 179.22443359000002), 'rotation':(0.3464, 90.484276, 0.342234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.85583984, 4642.96289062, 179.11978516), 'rotation':(0.367505, 90.489357, 0.362809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.90271484, 4637.43554688, 179.08359375), 'rotation':(0.374759, 90.489494, 0.369885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.94958984, 4631.90773438, 179.04677734), 'rotation':(0.381541, 90.489586, 0.376477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.99646484, 4626.38085938, 179.00927734), 'rotation':(0.388727, 90.484833, 0.383491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.04333984, 4620.85351562, 178.97113281000003), 'rotation':(0.395707, 90.489792, 0.390268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.09021484, 4615.32664062, 178.93265625), 'rotation':(0.399368, 90.487785, 0.393829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.13708984, 4609.79929688, 178.89412109), 'rotation':(0.399225, 90.492393, 0.393695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.23083984, 4598.74460938, 178.81587890999998), 'rotation':(0.403657, 90.486336, 0.398003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.37195312, 4582.16359375, 178.69345703), 'rotation':(0.429755, 90.486725, 0.423338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.46570312, 4571.10839844, 178.6096875), 'rotation':(0.434079, 90.492729, 0.427538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.67322266, 4709.36132812, 179.50966797), 'rotation':(-0.303375, -89.514435, -0.30661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6779.72009766, 4703.83447266, 179.48072266), 'rotation':(-0.303375, -89.514435, -0.30661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6779.76697266, 4698.30712891, 179.45126953), 'rotation':(-0.314789, -89.510071, -0.318268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.90759766, 4681.72509766, 179.35714843999997), 'rotation':(-0.343018, -89.513763, -0.347137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.04871094, 4665.14355469, 179.25802734), 'rotation':(-0.346436, -89.515656, -0.350647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.09558594, 4659.61570312, 179.22443359000002), 'rotation':(-0.353485, -89.510803, -0.35788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6780.14246094, 4654.08886719, 179.19019531), 'rotation':(-0.360596, -89.510681, -0.365173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6780.18884766, 4648.56101562, 179.1553125), 'rotation':(-0.367523, -89.510559, -0.372284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.28308594, 4637.50734375, 179.08361327999998), 'rotation':(-0.381531, -89.510406, -0.386658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.42371094, 4620.9253125, 178.97115234), 'rotation':(-0.399384, -89.507599, -0.404968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.75232422, 4582.23585938, 178.69345703), 'rotation':(-0.434082, -89.511536, -0.440674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6780.79919922, 4576.70800781, 178.65158203), 'rotation':(-0.434082, -89.507263, -0.440674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.84607422, 4571.18066406, 178.60970702999998), 'rotation':(-0.435547, -89.512939, -0.4422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.09998047, 4378.53710938, 176.94125), 'rotation':(0.537809, 90.487335, 0.527778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.05310547, 4384.06054688, 176.99320312), 'rotation':(0.537809, 90.487335, 0.527778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.95935547, 4395.10644531, 177.09660156), 'rotation':(0.533458, 90.491524, 0.523591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.77136719, 4417.19921875, 177.30125), 'rotation':(0.525023, 90.491409, 0.515462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.67761719, 4428.24414062, 177.40255859), 'rotation':(0.522557, 90.493477, 0.513101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.53699219, 4444.81347656, 177.55283203), 'rotation':(0.513671, 90.487946, 0.504535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.49011719, 4450.33640625, 177.60230468999998), 'rotation':(0.510994, 90.493263, 0.501942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.44324219, 4455.859375, 177.65150391), 'rotation':(0.507982, 90.487854, 0.499029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.39685547, 4461.3828125, 177.70041016), 'rotation':(0.505079, 90.493141, 0.496226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.34998047, 4466.90625, 177.74902343999997), 'rotation':(0.502258, 90.487762, 0.493512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.20886719, 4483.47460938, 177.89375), 'rotation':(0.497586, 90.490837, 0.489003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.06873047, 4500.04394531, 178.03625), 'rotation':(0.484766, 90.490601, 0.476626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.97498047, 4511.08984375, 178.12925781), 'rotation':(0.478441, 90.490532, 0.470497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.83435547, 4527.65917969, 178.26677734), 'rotation':(0.467943, 90.490524, 0.460341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.74060547, 4538.70554688, 178.35673828), 'rotation':(0.458128, 90.490326, 0.450853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.12097656, 4538.78859375, 178.35683594), 'rotation':(-0.462982, -89.509552, -0.47049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.16785156, 4533.265625, 178.31208984), 'rotation':(-0.467957, -89.514587, -0.475616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.26160156, 4522.21972656, 178.22125), 'rotation':(-0.475159, -89.509827, -0.483093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6781.30847656, 4516.69679688, 178.17544922000002), 'rotation':(-0.478394, -89.509491, -0.48645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.35535156, 4511.17335938, 178.12935547), 'rotation':(-0.484772, -89.509369, -0.493042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.49548828, 4494.605, 177.98921875), 'rotation':(-0.491119, -89.509277, -0.499603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.58923828, 4483.558125, 177.89386718999998), 'rotation':(-0.500702, -89.511505, -0.509521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.77673828, 4461.46726562, 177.70052734), 'rotation':(-0.507935, -89.512177, -0.516998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6781.82361328, 4455.94433594, 177.65162109000002), 'rotation':(-0.510986, -89.506714, -0.520172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6781.96423828, 4439.375, 177.50316406000002), 'rotation':(-0.519501, -89.511963, -0.528992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.01111328, 4433.8515625, 177.45306641), 'rotation':(-0.522583, -89.5065, -0.532166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.15222656, 4417.28367188, 177.30136718999998), 'rotation':(-0.52713, -89.508575, -0.536896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.19910156, 4411.76074219, 177.25046875), 'rotation':(-0.529327, -89.508514, -0.539185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.24597656, 4406.2378125, 177.19941406), 'rotation':(-0.531342, -89.508484, -0.54126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.43347656, 4384.14550781, 176.99333984), 'rotation':(-0.539948, -89.508301, -0.550201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.52673828, 4373.09960938, 176.88931641), 'rotation':(-0.540985, -89.508667, -0.55127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.9403125, 4279.47359375, 175.99423828), 'rotation':(0.553341, 90.489311, 0.542727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.84607422, 4290.59179688, 176.1015625), 'rotation':(0.552023, 90.489288, 0.541466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.75183594, 4301.71, 176.20865234000001), 'rotation':(0.550582, 90.489258, 0.540078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.70447266, 4307.26859375, 176.26210938), 'rotation':(0.550049, 90.493446, 0.539574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.61023438, 4318.38625, 176.36884766), 'rotation':(0.549263, 90.489227, 0.538809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.56335938, 4323.9453125, 176.42214843999997), 'rotation':(0.548635, 90.493469, 0.538216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.51599609, 4329.50484375, 176.47539061999998), 'rotation':(0.548246, 90.490685, 0.537843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6783.27380859, 4285.10351562, 176.04792969), 'rotation':(-0.553375, -89.510681, -0.564148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6783.17957031, 4296.2221875, 176.15511718999997), 'rotation':(-0.552032, -89.510712, -0.562744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.94373047, 4324.01804688, 176.42216797), 'rotation':(-0.549255, -89.510773, -0.559875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.89636719, 4329.5771875, 176.47541016), 'rotation':(-0.548645, -89.506531, -0.559235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6790.54919922, 4730.26123047, 179.80535156000002), 'rotation':(0.787678, 0.150199, 0.766245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6796.15076172, 4730.27490234, 179.88240234), 'rotation':(0.785943, 0.154796, 0.7646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6801.75232422, 4730.28857422, 179.95929688), 'rotation':(0.783914, 0.150097, 0.762674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6807.35291016, 4730.30224609, 180.03601562), 'rotation':(0.782166, 0.150047, 0.76103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6818.55603516, 4730.32958984, 180.18898438), 'rotation':(0.780137, 0.149995, 0.759102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6824.15759766, 4730.34375, 180.26521484), 'rotation':(0.778484, 0.154581, 0.757537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6829.75916016, 4730.35742188, 180.34126952999998), 'rotation':(0.776517, 0.149897, 0.755669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6857.76599609, 4730.42578125, 180.71927734000002), 'rotation':(0.769755, 0.151218, 0.749281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6863.36755859, 4730.43945312, 180.79447266), 'rotation':(0.767385, 0.151156, 0.747034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6868.96912109, 4730.453125, 180.86958984), 'rotation':(0.766375, 0.151127, 0.746076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6896.97693359, 4730.52197266, 181.24375), 'rotation':(0.764756, 0.152703, 0.744555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6908.17957031, 4730.54931641, 181.39302734), 'rotation':(0.759046, 0.148833, 0.739132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6919.38269531, 4730.57666016, 181.54148438), 'rotation':(0.759046, 0.148833, 0.739132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6930.58582031, 4730.60449219, 181.68996094), 'rotation':(0.75837, 0.150065, 0.738483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6936.18738281, 4730.61816406, 181.76414062), 'rotation':(0.75837, 0.150065, 0.738483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6952.99158203, 4730.66650391, 181.98626953), 'rotation':(0.75561, 0.149992, 0.73587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6958.59363281, 4730.66308594, 182.06015625), 'rotation':(0.754319, 0.149962, 0.734654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6969.79675781, 4730.66748047, 182.20765625), 'rotation':(0.753288, 0.151755, 0.733666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.39832031, 4730.68115234, 182.28130859), 'rotation':(0.752605, 0.151737, 0.73303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6980.99988281, 4730.69482422, 182.35492188), 'rotation':(0.751997, 0.147433, 0.732447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.60144531, 4730.70849609, 182.42847656), 'rotation':(0.751532, 0.151709, 0.732011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7014.60974609, 4730.77685547, 182.79550781), 'rotation':(0.749121, 0.151649, 0.729713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7014.6590625, 4722.4296875, 182.79587891), 'rotation':(-0.749664, -179.848343, -0.76947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7009.0575, 4722.41552734, 182.72255859), 'rotation':(-0.750244, -179.852615, -0.770111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.65076172, 4722.36083984, 182.42884766), 'rotation':(-0.751923, -179.85257, -0.771881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.44763672, 4722.33349609, 182.28169922), 'rotation':(-0.753296, -179.848236, -0.773285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6964.24451172, 4722.30615234, 182.13431641), 'rotation':(-0.754272, -179.850052, -0.774353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6953.04138672, 4722.27880859, 181.98664062), 'rotation':(-0.75708, -179.84996, -0.777283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.83826172, 4722.25097656, 181.83867188), 'rotation':(-0.758362, -179.846893, -0.778656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6913.83044922, 4722.18261719, 181.46763672), 'rotation':(-0.759064, -179.851166, -0.779388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6908.229375, 4722.16894531, 181.39341797), 'rotation':(-0.761902, -179.849213, -0.782379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6902.62732422, 4722.15527344, 181.31890625), 'rotation':(-0.764709, -179.847321, -0.785309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6880.2215625, 4722.10009766, 181.01980468999997), 'rotation':(-0.765198, -179.848892, -0.785828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6874.61951172, 4722.08642578, 180.94494140999998), 'rotation':(-0.766449, -179.848862, -0.78717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6869.01794922, 4722.07226562, 180.86998047), 'rotation':(-0.767395, -179.848846, -0.788147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6857.81482422, 4722.04492188, 180.71964844), 'rotation':(-0.771027, -179.84874, -0.791992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6846.6121875, 4722.01757812, 180.56884766), 'rotation':(-0.773132, -179.848694, -0.79422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6841.01111328, 4722.00390625, 180.49326172000002), 'rotation':(-0.77478, -179.850159, -0.795959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6835.41003906, 4721.99023438, 180.41753906000002), 'rotation':(-0.77652, -179.850098, -0.797791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6829.80847656, 4721.9765625, 180.34166016), 'rotation':(-0.778534, -179.845398, -0.799927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6818.60535156, 4721.94921875, 180.189375), 'rotation':(-0.782166, -179.849945, -0.803741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6813.00378906, 4721.93505859, 180.11296875), 'rotation':(-0.782166, -179.849945, -0.803741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6796.19958984, 4721.89404297, 179.88279297), 'rotation':(-0.787689, -179.845154, -0.80957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6790.59851562, 4721.88037109, 179.80576172000002), 'rotation':(-0.788483, -179.850739, -0.810425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7011.27917969, 4925.51171875, 183.30513672), 'rotation':(-0.723572, 179.915451, -0.742035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7005.71179688, 4925.52099609, 183.23480468999998), 'rotation':(-0.725494, 179.911606, -0.744049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(7000.1434375, 4925.53027344, 183.16427734), 'rotation':(-0.727722, 179.915543, -0.746399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6994.57605469, 4925.53955078, 183.09363281000003), 'rotation':(-0.729614, 179.915604, -0.748383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6966.73816406, 4925.69677734, 182.73804688), 'rotation':(-0.735779, 179.915771, -0.754852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6938.90076172, 4925.76171875, 182.37919922), 'rotation':(-0.74295, 179.913315, -0.76239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6916.63171875, 4925.79833984, 182.09005859), 'rotation':(-0.748718, 179.913849, -0.768463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6905.49597656, 4925.81689453, 181.94447266), 'rotation':(-0.75116, 179.91391, -0.771057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6872.09167969, 4925.87207031, 181.50269531), 'rotation':(-0.763031, 179.915253, -0.783569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6860.95691406, 4925.890625, 181.35431641), 'rotation':(-0.7677, 179.91539, -0.788483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.25525391, 4925.91845703, 181.13017578), 'rotation':(-0.771301, 179.914688, -0.792297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6827.55310547, 4925.94580078, 180.90460938), 'rotation':(-0.779388, 179.916306, -0.800812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6821.98572266, 4925.95507812, 180.82892578), 'rotation':(-0.782471, 179.916382, -0.804077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6810.85095703, 4925.97363281, 180.67675781000003), 'rotation':(-0.78595, 179.912186, -0.807739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.28357422, 4925.98291016, 180.60027344), 'rotation':(-0.789032, 179.916565, -0.811005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6794.14832031, 4926.00146484, 180.44652344), 'rotation':(-0.795593, 179.916748, -0.817932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6788.5809375, 4926.01074219, 180.36921875), 'rotation':(-0.796875, 179.916687, -0.819275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6799.69666016, 4934.37304688, 180.52308594), 'rotation':(0.789017, -0.083435, 0.767508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.26404297, 4934.36376953, 180.59982422000002), 'rotation':(0.78595, -0.087799, 0.764599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6810.83142578, 4934.35498047, 180.67630859000002), 'rotation':(0.782466, -0.083618, 0.761304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6816.39832031, 4934.34570312, 180.7525), 'rotation':(0.782466, -0.083618, 0.761304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.10046875, 4934.31787109, 180.97958984000002), 'rotation':(0.772829, -0.083862, 0.752181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.23523438, 4934.29931641, 181.12970703), 'rotation':(0.770186, -0.084534, 0.749692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6849.80212891, 4934.29003906, 181.20460938), 'rotation':(0.770186, -0.084534, 0.749692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6855.36951172, 4934.28076172, 181.27933593999998), 'rotation':(0.767706, -0.084595, 0.747329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6860.93738281, 4934.27148438, 181.35384765999999), 'rotation':(0.765357, -0.084686, 0.745116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6866.50476562, 4934.26220703, 181.428125), 'rotation':(0.763014, -0.084747, 0.742896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6888.77478516, 4934.22509766, 181.72404297), 'rotation':(0.755897, -0.085968, 0.736138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6905.47693359, 4934.19775391, 181.94404297), 'rotation':(0.748759, -0.086151, 0.729383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6916.61169922, 4934.17919922, 182.08962891), 'rotation':(0.746464, -0.086212, 0.727188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6933.31433594, 4934.15185547, 182.3065625), 'rotation':(0.742892, -0.08667, 0.723817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6950.01697266, 4934.125, 182.52283203), 'rotation':(0.736745, -0.085754, 0.71798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6961.15173828, 4934.11425781, 182.66609375), 'rotation':(0.735727, -0.084229, 0.717008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6978.49597656, 4934.1484375, 182.88853516), 'rotation':(0.731698, -0.088226, 0.713187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6988.99011719, 4934.19628906, 183.02240234), 'rotation':(0.727675, -0.084442, 0.709365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(7000.12537109, 4934.17822266, 183.16386719), 'rotation':(0.725482, -0.088409, 0.707278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7011.26013672, 4934.15966797, 183.30470703), 'rotation':(0.721575, -0.088501, 0.703575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6002.5809375, 5511.42285156, 165.11753906), 'rotation':(-0.988922, -179.74205, -1.023529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6039.75820312, 5511.58546875, 165.75560547), 'rotation':(-0.978943, -179.732925, -1.012848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6045.06875, 5511.60890625, 165.84619141), 'rotation':(-0.976166, -179.733002, -1.009857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6055.69125, 5511.65527344, 166.02681640999998), 'rotation':(-0.972961, -179.733124, -1.006439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6002.56578125, 5519.80371094, 165.11791015999998), 'rotation':(0.985432, 0.270056, 0.951957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6007.87484375, 5519.82664062, 165.20925781000003), 'rotation':(0.983322, 0.268149, 0.949993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6018.4940625, 5519.87304688, 165.39164062), 'rotation':(0.983452, 0.265243, 0.950127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6034.42273438, 5519.94289062, 165.665), 'rotation':(0.978957, 0.267076, 0.945911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6039.73234375, 5519.96632812, 165.75578125), 'rotation':(0.976164, 0.266999, 0.943303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6292.71421875, 5512.69238281, 169.99410156000002), 'rotation':(-0.958405, -179.732254, -0.990906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6281.33140625, 5512.64257812, 169.80375), 'rotation':(-0.955811, -179.737915, -0.988098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6241.49109375, 5512.46875, 169.13929688), 'rotation':(-0.954407, -179.732773, -0.986603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6235.7996875, 5512.44382812, 169.04443359), 'rotation':(-0.954407, -179.732773, -0.986603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6230.10828125, 5512.41894531, 168.94958984000002), 'rotation':(-0.953979, -179.734146, -0.986176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.416875, 5512.3940625, 168.85476562), 'rotation':(-0.954102, -179.734131, -0.986298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6218.72546875, 5512.36914062, 168.75994140999998), 'rotation':(-0.954102, -179.734131, -0.986298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6213.0340625, 5512.34375, 168.66513672000002), 'rotation':(-0.954163, -179.734116, -0.986359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6207.34265625, 5512.31882812, 168.57033203), 'rotation':(-0.954102, -179.730759, -0.986298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6184.57703125, 5512.21972656, 168.19103515999998), 'rotation':(-0.954529, -179.735168, -0.986725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6178.885625, 5512.19484375, 168.09621094), 'rotation':(-0.95462, -179.729614, -0.986847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6173.19421875, 5512.16945312, 168.00134766), 'rotation':(-0.954529, -179.735168, -0.986725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6156.12, 5512.09472656, 167.71673828), 'rotation':(-0.955841, -179.734589, -0.988159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6144.7371875, 5512.04492188, 167.52667968999998), 'rotation':(-0.95755, -179.734528, -0.98999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6292.68054688, 5521.07324219, 169.99416015999998), 'rotation':(0.959812, 0.267791, 0.928054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6286.98914062, 5521.04835938, 169.89888672), 'rotation':(0.958412, 0.267744, 0.926749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6275.60632812, 5520.99851562, 169.70882812), 'rotation':(0.955796, 0.267662, 0.924292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6264.22398438, 5520.94875, 169.51900390999998), 'rotation':(0.955236, 0.265156, 0.923769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6252.84070312, 5520.89890625, 169.32916016), 'rotation':(0.95512, 0.268925, 0.923666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6213.00085938, 5520.72507812, 168.66519531000003), 'rotation':(0.954109, 0.265853, 0.92271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6201.61804688, 5520.67480469, 168.47556641), 'rotation':(0.95415, 0.269248, 0.92276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6184.54382812, 5520.60007812, 168.19109375), 'rotation':(0.95443, 0.265949, 0.923017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6161.77867188, 5520.50046875, 167.81169922), 'rotation':(0.954608, 0.27038, 0.923189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6156.08726562, 5520.47558594, 167.71679688), 'rotation':(0.954826, 0.265351, 0.923385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6150.39585938, 5520.45070312, 167.62181640999998), 'rotation':(0.955844, 0.265407, 0.924334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6139.01304688, 5520.40085938, 167.43158203), 'rotation':(0.957551, 0.270449, 0.925943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6127.62976562, 5520.35109375, 167.24101561999998), 'rotation':(0.959266, 0.265522, 0.927535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6099.17375, 5520.2265625, 166.76328125), 'rotation':(0.963562, 0.267145, 0.931544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.4828125, 5520.20164062, 166.66738281000002), 'rotation':(0.965065, 0.267195, 0.932955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.15125, 5521.2153125, 170.53853515999998), 'rotation':(0.961492, 0.266157, 0.929624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6341.77234375, 5521.28859375, 170.81777344), 'rotation':(0.96516, 0.266194, 0.933046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6347.31289062, 5521.31296875, 170.91109375), 'rotation':(0.96516, 0.266194, 0.933046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6352.85289062, 5521.33691406, 171.00445312), 'rotation':(0.965215, 0.269558, 0.93309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6363.93296875, 5521.38574219, 171.19119141), 'rotation':(0.96527, 0.266197, 0.933144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6380.5540625, 5521.45800781, 171.47144531), 'rotation':(0.968172, 0.265582, 0.935862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6391.63414062, 5521.50632812, 171.659375), 'rotation':(0.976539, 0.266773, 0.943669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6402.71472656, 5521.5546875, 171.84824218999998), 'rotation':(0.976676, 0.266778, 0.943789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6413.79480469, 5521.60351562, 172.03714843999998), 'rotation':(0.976539, 0.270877, 0.943662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6424.87539062, 5521.651875, 172.22619140999998), 'rotation':(0.980016, 0.268325, 0.946904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6435.9559375, 5521.70070312, 172.41578125), 'rotation':(0.982454, 0.268426, 0.949177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6452.5765625, 5521.77296875, 172.70140625), 'rotation':(0.985924, 0.26999, 0.952415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6458.1165625, 5521.80078125, 172.79677734), 'rotation':(0.987584, 0.267522, 0.953959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6463.65613281, 5521.8671875, 172.89224609000001), 'rotation':(0.987584, 0.267522, 0.953959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6461.60195312, 5513.41503906, 172.85619140999998), 'rotation':(-0.985931, -179.734695, -1.020294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6452.6434375, 5513.39304688, 172.70193359), 'rotation':(-0.985931, -179.730011, -1.020325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6436.02332031, 5513.31984375, 172.41628906000003), 'rotation':(-0.980011, -179.735672, -1.013977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6430.4828125, 5513.29589844, 172.32140625), 'rotation':(-0.977844, -179.731735, -1.011658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6424.94273438, 5513.27148438, 172.22671875), 'rotation':(-0.977844, -179.731735, -1.011658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6419.40171875, 5513.24707031, 172.13214843999998), 'rotation':(-0.976532, -179.733215, -1.010284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6413.86171875, 5513.22265625, 172.03767578), 'rotation':(-0.976471, -179.733246, -1.010193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6402.78113281, 5513.17429688, 171.84873047000002), 'rotation':(-0.976532, -179.733215, -1.010284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6391.70054688, 5513.12597656, 171.65988281000003), 'rotation':(-0.973633, -179.734253, -1.007172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6386.16054688, 5513.10203125, 171.56568359000002), 'rotation':(-0.96817, -179.730804, -1.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6380.62, 5513.07765625, 171.47193359000002), 'rotation':(-0.96521, -179.73381, -0.998169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6369.53945312, 5513.02882812, 171.28505859), 'rotation':(-0.965271, -179.733795, -0.99823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6358.45886719, 5512.98046875, 171.09832031000002), 'rotation':(-0.96521, -179.73381, -0.998169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6341.8378125, 5512.90773438, 170.81826172), 'rotation':(-0.964081, -179.733734, -0.996948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6336.29726562, 5512.88328125, 170.725), 'rotation':(-0.961517, -179.733841, -0.994202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.7571875, 5512.85890625, 170.63199218999998), 'rotation':(-0.960297, -179.733856, -0.992889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.2171875, 5512.83496094, 170.53902344), 'rotation':(-0.960297, -179.733856, -0.992889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.30554688, 5514.64746094, 177.86796875), 'rotation':(-1.083435, -179.72644, -1.125031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.64734375, 5514.62257812, 177.76074218999997), 'rotation':(-1.083435, -179.72644, -1.125031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.67224609, 5514.54835938, 177.44068359000002), 'rotation':(-1.07428, -179.726425, -1.115173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6705.35535156, 5514.49902344, 177.22833984000002), 'rotation':(-1.072662, -179.731934, -1.113434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6688.38025391, 5514.42429688, 176.91103515999998), 'rotation':(-1.063782, -179.727585, -1.103851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6671.405625, 5514.35007812, 176.59615234), 'rotation':(-1.057922, -179.732483, -1.097565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.74792969, 5514.32519531, 176.49173828), 'rotation':(-1.054993, -179.727905, -1.094421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6660.08875, 5514.30078125, 176.38759765999998), 'rotation':(-1.052002, -179.732712, -1.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6654.43007812, 5514.27585938, 176.28367188), 'rotation':(-1.05069, -179.729889, -1.089783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6648.77136719, 5514.25097656, 176.17988281), 'rotation':(-1.048706, -179.730286, -1.087646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6631.79625, 5514.17675781, 175.86949219), 'rotation':(-1.041077, -179.730576, -1.079468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6626.13804688, 5514.15234375, 175.7665625), 'rotation':(-1.03714, -179.730728, -1.075195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6614.82117188, 5514.10253906, 175.56134766), 'rotation':(-1.035461, -179.731003, -1.073395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.50429688, 5514.05273438, 175.35669922), 'rotation':(-1.035278, -179.731033, -1.073212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6592.186875, 5514.0034375, 175.15234375), 'rotation':(-1.027802, -179.728821, -1.065216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.52820312, 5513.97851562, 175.05054688), 'rotation':(-1.027802, -179.728821, -1.065216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6580.87, 5513.95410156, 174.9490625), 'rotation':(-1.022827, -179.732605, -1.059845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6575.21132812, 5513.92921875, 174.84800781), 'rotation':(-1.017883, -179.729187, -1.054565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6563.8934375, 5513.87988281, 174.646875), 'rotation':(-1.015259, -179.730225, -1.051758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.23523438, 5513.855, 174.54654297000002), 'rotation':(-1.015289, -179.734039, -1.051758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.57703125, 5513.83007812, 174.44623047000002), 'rotation':(-1.013672, -179.731415, -1.050049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6518.62585938, 5513.68164062, 173.84775391), 'rotation':(-1.003662, -179.728821, -1.039307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6512.96667969, 5513.65671875, 173.74859375), 'rotation':(-1.001831, -179.733673, -1.037354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.30847656, 5513.63183594, 173.64960938000002), 'rotation':(-1.000885, -179.732956, -1.036346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.21523438, 5522.0121875, 173.64861327999998), 'rotation':(1.001825, 0.266329, 0.967244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6512.87390625, 5522.03710938, 173.74761718999997), 'rotation':(1.003655, 0.268236, 0.968934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6524.19078125, 5522.08691406, 173.94597656000002), 'rotation':(1.006906, 0.268337, 0.971972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6529.84949219, 5522.11179688, 174.04544922000002), 'rotation':(1.01028, 0.268466, 0.975109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6535.5071875, 5522.13625, 174.14511718999998), 'rotation':(1.01028, 0.268466, 0.975109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6541.16589844, 5522.16113281, 174.24494141), 'rotation':(1.013689, 0.268585, 0.978282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.4828125, 5522.21046875, 174.44521484), 'rotation':(1.01528, 0.269776, 0.979757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.14050781, 5522.23535156, 174.54550781), 'rotation':(1.01528, 0.269776, 0.979757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6563.79921875, 5522.25976562, 174.64583984), 'rotation':(1.017896, 0.267201, 0.982188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6575.11609375, 5522.30957031, 174.84695312), 'rotation':(1.022807, 0.270997, 0.986764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6580.77429688, 5522.33445312, 174.94802734), 'rotation':(1.027814, 0.267555, 0.991411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.43296875, 5522.35890625, 175.04949219), 'rotation':(1.032888, 0.271348, 0.996122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6592.09117188, 5522.38378906, 175.15126952999998), 'rotation':(1.032888, 0.271348, 0.996122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.40808594, 5522.43359375, 175.355625), 'rotation':(1.035443, 0.268975, 0.998513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6609.06628906, 5522.45851562, 175.45792969), 'rotation':(1.035443, 0.268975, 0.998513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6626.04089844, 5522.53273438, 175.76546875), 'rotation':(1.041098, 0.269423, 1.003755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6643.01550781, 5522.61570312, 176.07511719), 'rotation':(1.0487, 0.269703, 1.010818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6648.67371094, 5522.61085938, 176.17875), 'rotation':(1.050695, 0.270104, 1.012661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6659.99011719, 5522.64796875, 176.38646484), 'rotation':(1.055005, 0.272084, 1.016666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.64832031, 5522.67285156, 176.49058594), 'rotation':(1.057921, 0.26751, 1.019379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6676.96472656, 5522.7221875, 176.69966797), 'rotation':(1.060988, 0.272304, 1.022221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6688.28064453, 5522.77195312, 176.90984375), 'rotation':(1.066834, 0.272523, 1.027631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6693.93982422, 5522.796875, 177.01537109), 'rotation':(1.069744, 0.27263, 1.030341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6705.25525391, 5522.84617188, 177.22714843999998), 'rotation':(1.074122, 0.273563, 1.0344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.57166016, 5522.89601562, 177.43949218999998), 'rotation':(1.075946, 0.273246, 1.036088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6722.229375, 5522.92039062, 177.54583984), 'rotation':(1.0796, 0.269604, 1.039477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6727.88757812, 5522.9453125, 177.65251952999998), 'rotation':(1.083446, 0.269772, 1.043023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.54578125, 5522.97023438, 177.75951172), 'rotation':(1.087018, 0.273666, 1.046345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6744.86072266, 5523.18945312, 177.97416016), 'rotation':(1.089012, 0.271815, 1.048189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6750.51892578, 5523.214375, 178.08175781000003), 'rotation':(1.088978, 0.27183, 1.048145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6993.19861328, 5515.75878906, 182.73949219), 'rotation':(-1.058228, -179.732269, -1.09787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6987.51746094, 5515.73390625, 182.634375), 'rotation':(-1.063385, -179.726562, -1.103424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6981.83630859, 5515.70898438, 182.52865234), 'rotation':(-1.068726, -179.731888, -1.109161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6976.15564453, 5515.6840625, 182.42238281000002), 'rotation':(-1.079376, -179.731476, -1.120667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6964.79382812, 5515.63429688, 182.20804688), 'rotation':(-1.090057, -179.731079, -1.132141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6942.06970703, 5515.53515625, 181.77351562), 'rotation':(-1.098022, -179.728714, -1.140747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6930.70789062, 5515.48535156, 181.55548828), 'rotation':(-1.100494, -179.729385, -1.143402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6925.02673828, 5515.46046875, 181.44632812), 'rotation':(-1.105316, -179.726288, -1.14859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6919.34558594, 5515.43554688, 181.33666015999998), 'rotation':(-1.107788, -179.728973, -1.151276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6896.62195312, 5515.3359375, 180.89726561999998), 'rotation':(-1.107788, -179.728973, -1.151276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6885.25916016, 5515.28613281, 180.67744141), 'rotation':(-1.107788, -179.728973, -1.151276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6879.57800781, 5515.26125, 180.56753906000003), 'rotation':(-1.109497, -179.727371, -1.153107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6873.89685547, 5515.23632812, 180.45748047), 'rotation':(-1.111023, -179.726242, -1.154755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6868.21619141, 5515.21140625, 180.34730469), 'rotation':(-1.111176, -179.726242, -1.154938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6862.53503906, 5515.18652344, 180.23707031), 'rotation':(-1.111053, -179.731308, -1.154816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.85388672, 5515.16164062, 180.12685547), 'rotation':(-1.111023, -179.726242, -1.154755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6851.17273438, 5515.13671875, 180.01664062), 'rotation':(-1.110596, -179.727386, -1.154297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6839.80994141, 5515.08742188, 179.79634765999998), 'rotation':(-1.108765, -179.727448, -1.152313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6834.12878906, 5515.0625, 179.68634766), 'rotation':(-1.107635, -179.727509, -1.151093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6822.76599609, 5515.01269531, 179.46660156000002), 'rotation':(-1.105713, -179.727585, -1.149017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6817.08435547, 5514.9878125, 179.356875), 'rotation':(-1.104919, -179.7276, -1.148193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.72253906, 5514.93796875, 179.13773438), 'rotation':(-1.103271, -179.72995, -1.146393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6794.36511719, 5514.88328125, 178.91888672000002), 'rotation':(-1.101654, -179.725388, -1.144653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6788.68591797, 5514.76320312, 178.80962891), 'rotation':(-1.098267, -179.729156, -1.141022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.62097656, 5523.31882812, 179.13646484), 'rotation':(1.103786, 0.272339, 1.06185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6811.30212891, 5523.34375, 179.24599609), 'rotation':(1.104913, 0.272407, 1.062885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6816.98328125, 5523.36867188, 179.35564452999998), 'rotation':(1.105705, 0.272412, 1.063629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6834.02722656, 5523.44289062, 179.68507812), 'rotation':(1.108745, 0.272554, 1.06644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6862.43347656, 5523.56738281, 180.23580077999998), 'rotation':(1.111169, 0.27376, 1.068682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6885.15808594, 5523.66648438, 180.67621093999998), 'rotation':(1.107788, 0.271019, 1.065542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6913.56384766, 5523.79296875, 181.22568359000002), 'rotation':(1.105302, 0.270786, 1.063249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6930.60681641, 5523.83300781, 181.55425781000002), 'rotation':(1.098021, 0.271287, 1.056512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.96912109, 5523.88234375, 181.77228516), 'rotation':(1.098042, 0.271276, 1.056543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6947.65076172, 5523.90722656, 181.88123047000002), 'rotation':(1.098042, 0.271276, 1.056543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6964.69373047, 5523.98195312, 182.20685547000002), 'rotation':(1.084736, 0.274236, 1.044211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6976.05603516, 5524.03171875, 182.42119141), 'rotation':(1.074163, 0.273858, 1.03443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6981.73669922, 5524.05515625, 182.52748047), 'rotation':(1.063372, 0.273429, 1.024449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6987.41833984, 5524.0815625, 182.63320312), 'rotation':(1.058208, 0.267726, 1.019654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6993.09949219, 5524.10644531, 182.73832031), 'rotation':(1.05536, 0.268795, 1.017005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6998.78015625, 5524.30125, 182.84308593999998), 'rotation':(1.055496, 0.273419, 1.017138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6325.41882812, 5730.27390625, 170.59378906), 'rotation':(0.915307, 0.550166, 0.886414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.95640625, 5730.32570312, 170.68230469), 'rotation':(0.91239, 0.553102, 0.883662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6342.030625, 5730.4296875, 170.85871093999998), 'rotation':(0.909324, 0.550002, 0.880796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6358.64441406, 5730.58546875, 171.12203125), 'rotation':(0.904816, 0.552877, 0.876572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6380.79382812, 5730.79296875, 171.47185547), 'rotation':(0.902275, 0.549953, 0.874181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6386.3309375, 5730.84523438, 171.55914062), 'rotation':(0.900676, 0.549901, 0.872695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6391.86902344, 5730.89695312, 171.64632812), 'rotation':(0.900676, 0.549901, 0.872695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6397.40664062, 5730.94875, 171.73339843999997), 'rotation':(0.898826, 0.553206, 0.870949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6408.48132812, 5731.05273438, 171.90720703), 'rotation':(0.898115, 0.551706, 0.870291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6430.6321875, 5731.26023438, 172.25482422000002), 'rotation':(0.900069, 0.551999, 0.872101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6436.16980469, 5731.31203125, 172.341875), 'rotation':(0.900731, 0.551978, 0.872734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6441.70742188, 5731.36421875, 172.42902343999998), 'rotation':(0.901722, 0.552052, 0.873662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6452.78257812, 5731.4678125, 172.60349609000002), 'rotation':(0.903374, 0.552105, 0.875223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6463.8578125, 5731.57179688, 172.77828125), 'rotation':(0.90446, 0.552272, 0.876235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6469.499375, 5723.24367188, 172.86613281), 'rotation':(-0.904449, -179.451828, -0.93338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6458.42371094, 5723.1396875, 172.69125), 'rotation':(-0.90332, -179.447937, -0.932159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6452.88660156, 5723.08789062, 172.60390625), 'rotation':(-0.902466, -179.447922, -0.931244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6441.81140625, 5722.98390625, 172.42941406000003), 'rotation':(-0.900818, -179.447983, -0.929474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6430.7371875, 5722.88039062, 172.25523438), 'rotation':(-0.899292, -179.452866, -0.927887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6408.58582031, 5722.67234375, 171.90761719), 'rotation':(-0.898895, -179.446762, -0.927429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6403.04871094, 5722.620625, 171.82076172), 'rotation':(-0.898895, -179.446762, -0.927429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6397.51257812, 5722.56882812, 171.73382812), 'rotation':(-0.900696, -179.450104, -0.929352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6386.43738281, 5722.46484375, 171.55957031000003), 'rotation':(-0.902222, -179.450089, -0.931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6375.36265625, 5722.36132812, 171.38492188), 'rotation':(-0.904694, -179.451111, -0.933624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6358.75085938, 5722.20554688, 171.12248047), 'rotation':(-0.90625, -179.450119, -0.935272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6353.21277344, 5722.15382812, 171.03484375), 'rotation':(-0.909271, -179.446991, -0.938477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6336.6009375, 5721.99757812, 170.77103516), 'rotation':(-0.915375, -179.449799, -0.944977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6111.00523438, 5719.8828125, 167.00169922), 'rotation':(-1.016052, -179.444199, -1.052582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6116.698125, 5719.93601562, 167.10244140999998), 'rotation':(-1.013397, -179.443207, -1.049744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6128.08390625, 5720.04296875, 167.30353516), 'rotation':(-1.011261, -179.445419, -1.047424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6133.77671875, 5720.09617188, 167.40353516), 'rotation':(-1.006561, -179.445648, -1.042389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6150.85585938, 5720.25632812, 167.70101562), 'rotation':(-0.993103, -179.441483, -1.028015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6167.93445312, 5720.41648438, 167.99460938), 'rotation':(-0.979553, -179.446579, -1.013489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6179.32015625, 5720.5234375, 168.18900391), 'rotation':(-0.977417, -179.445511, -1.0112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.01359375, 5720.57664062, 168.28617188), 'rotation':(-0.977325, -179.448822, -1.011078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6196.39929688, 5720.683125, 168.47925781), 'rotation':(-0.972595, -179.443649, -1.006073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6207.78601562, 5720.78859375, 168.67029297000002), 'rotation':(-0.958313, -179.449188, -0.990814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.86460938, 5720.97507812, 168.95601562), 'rotation':(-0.958313, -179.444031, -0.990814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6241.94421875, 5721.14359375, 169.23994141), 'rotation':(-0.948669, -179.447144, -0.980499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6247.63710938, 5721.19679688, 169.33375), 'rotation':(-0.948669, -179.447144, -0.980499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6253.33046875, 5721.25046875, 169.42734375), 'rotation':(-0.942261, -179.447372, -0.973663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6259.02328125, 5721.30375, 169.52035156000002), 'rotation':(-0.935822, -179.447586, -0.966797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6264.7171875, 5721.35695312, 169.61324219), 'rotation':(-0.935822, -179.447586, -0.966797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.41054688, 5721.41015625, 169.70595702999998), 'rotation':(-0.932617, -179.448074, -0.963348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6281.79820312, 5721.34671875, 169.89128906000002), 'rotation':(-0.932556, -179.44812, -0.963318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.49203125, 5721.40039062, 169.98376953), 'rotation':(-0.930206, -179.449814, -0.960785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6099.54484375, 5728.24851562, 166.79966797), 'rotation':(1.016038, 0.555792, 0.98047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6116.62148438, 5728.31640625, 167.10246094), 'rotation':(1.013457, 0.556828, 0.97807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6128.0071875, 5728.4228125, 167.30355468999997), 'rotation':(1.006633, 0.554401, 0.971711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6139.39296875, 5728.52976562, 167.50316406000002), 'rotation':(0.997597, 0.554044, 0.963292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6156.47203125, 5728.68992188, 167.79933594), 'rotation':(0.9841, 0.553621, 0.950712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6162.16445312, 5728.743125, 167.89720703), 'rotation':(0.97962, 0.553464, 0.946542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6184.93640625, 5728.95703125, 168.28617188), 'rotation':(0.972612, 0.552927, 0.940005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6196.32265625, 5729.0634375, 168.47927734), 'rotation':(0.963063, 0.555989, 0.931087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6202.015, 5729.1171875, 168.575), 'rotation':(0.958405, 0.550869, 0.926731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6207.70890625, 5729.17039062, 168.6703125), 'rotation':(0.958166, 0.555956, 0.926498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6219.09507812, 5729.28273438, 168.86082031), 'rotation':(0.958405, 0.550869, 0.926731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6224.78796875, 5729.34132812, 168.95607422), 'rotation':(0.955072, 0.553034, 0.923623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6230.48132812, 5729.36132812, 169.05101562), 'rotation':(0.948624, 0.55282, 0.917593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6236.17515625, 5729.40429688, 169.14568359), 'rotation':(0.948624, 0.55282, 0.917593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6241.86804688, 5729.4575, 169.23998047), 'rotation':(0.942313, 0.552641, 0.91169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6247.5609375, 5729.51078125, 169.33376952999998), 'rotation':(0.942313, 0.552641, 0.91169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6253.25429688, 5729.56445312, 169.42734375), 'rotation':(0.935811, 0.552402, 0.905609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6258.9471875, 5729.61765625, 169.52039062), 'rotation':(0.93256, 0.555033, 0.902569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.334375, 5729.72460938, 169.70597656), 'rotation':(0.932621, 0.551911, 0.90261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6281.718125, 5730.00148438, 169.89130859), 'rotation':(0.93021, 0.550186, 0.900363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6002.56679688, 5727.24703125, 165.01949219), 'rotation':(1.07445, 0.554385, 1.034703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.229375, 5727.3471875, 165.21960938), 'rotation':(1.071527, 0.558789, 1.031986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6018.55992188, 5727.3975, 165.31933593999997), 'rotation':(1.07154, 0.555308, 1.031997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6029.2215625, 5727.51515625, 165.51865234000002), 'rotation':(1.067422, 0.556937, 1.028186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6039.88320312, 5727.68992188, 165.71683593999998), 'rotation':(1.059267, 0.556636, 1.020632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6045.21421875, 5727.77640625, 165.81541016), 'rotation':(1.051228, 0.55634, 1.013164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6050.5453125, 5727.82664062, 165.91326172), 'rotation':(1.042984, 0.556035, 1.005523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6054.39539062, 5719.22265625, 165.98244140999998), 'rotation':(-1.051239, -179.443665, -1.090363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6023.94570312, 5719.06640625, 165.41863281000002), 'rotation':(-1.071533, -179.441208, -1.112213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6018.60875, 5719.0165625, 165.31878906000003), 'rotation':(-1.071533, -179.441208, -1.112213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6013.27234375, 5718.96679688, 165.21892577999998), 'rotation':(-1.074371, -179.445648, -1.115265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6508.86375, 2478.89527344, 161.68060547), 'rotation':(0.964177, 28.7421, 0.932129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6489.13375, 2468.08277344, 161.29760742), 'rotation':(0.988759, 28.740435, 0.955064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6474.33785156, 2459.97460938, 161.00075195), 'rotation':(1.018456, 28.741476, 0.982704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6469.40570312, 2457.27148438, 160.89990234), 'rotation':(1.028367, 28.739697, 0.991928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6464.47359375, 2454.56859375, 160.79807617), 'rotation':(1.038243, 28.742193, 1.00111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6459.54242188, 2451.86597656, 160.69574219), 'rotation':(1.043202, 28.746025, 1.005716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6449.67820312, 2446.46046875, 160.48986328), 'rotation':(1.048796, 28.740164, 1.010907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6439.8134375, 2441.0544531200003, 160.28102539), 'rotation':(1.059895, 28.74358, 1.021204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6434.8817968799995, 2438.35203125, 160.17576172), 'rotation':(1.071151, 28.744005, 1.031644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6415.15476562, 2427.54101562, 159.74820312), 'rotation':(1.097222, 28.74584, 1.055778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6395.42769531, 2416.73023438, 159.31291016), 'rotation':(1.115554, 28.744545, 1.072723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6380.6317968799995, 2408.6215625, 158.9809375), 'rotation':(1.13429, 28.747284, 1.090031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6370.76898438, 2403.2165625, 158.75743164), 'rotation':(1.140573, 28.747879, 1.095816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6360.9052343799995, 2397.81078125, 158.53251953), 'rotation':(1.147151, 28.745146, 1.101883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6331.3139062499995, 2381.59421875, 157.84904297), 'rotation':(1.163687, 28.748636, 1.117108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6326.38226562, 2378.89160156, 157.73464844), 'rotation':(1.165435, 28.747595, 1.118721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6316.51804688, 2373.48609375, 157.50503906), 'rotation':(1.168632, 28.747719, 1.121657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6311.58640625, 2370.78320312, 157.38980469), 'rotation':(1.172122, 28.745913, 1.124874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6306.65523438, 2368.08082031, 157.27435547), 'rotation':(1.175428, 28.747999, 1.127916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6296.79148438, 2362.6753125, 157.04313477), 'rotation':(1.177149, 28.749214, 1.129496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6286.9271874999995, 2357.26953125, 156.81192382999998), 'rotation':(1.177204, 28.747414, 1.129534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6281.9950781200005, 2354.56664062, 156.69630859), 'rotation':(1.177169, 28.747561, 1.129516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6267.19867188, 2346.45777344, 156.35025391), 'rotation':(1.173324, 28.748777, 1.125976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6262.2665625, 2343.75484375, 156.23501953000002), 'rotation':(1.173256, 28.746964, 1.125914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6252.40234375, 2338.34914062, 156.00455078000002), 'rotation':(1.173256, 28.746964, 1.125914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6247.4701562499995, 2335.64625, 155.88931641), 'rotation':(1.173324, 28.748777, 1.125976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6242.53703125, 2332.94289062, 155.77427734), 'rotation':(1.170961, 28.747408, 1.123793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6237.60492188, 2330.24, 155.65966797), 'rotation':(1.166712, 28.747236, 1.119897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6512.89058594, 2471.54539062, 161.68058594000001), 'rotation':(-0.96405, -151.259796, -0.996948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6503.0263281200005, 2466.13914062, 161.49077148), 'rotation':(-0.979004, -151.259888, -1.012909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6498.09371094, 2463.43628906, 161.39466797), 'rotation':(-0.98877, -151.259552, -1.023346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6468.5009375, 2447.21875, 160.79806641), 'rotation':(-1.043152, -151.257721, -1.081696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6438.90960938, 2431.00171875, 160.17576172), 'rotation':(-1.082214, -151.255585, -1.123718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6429.04632812, 2425.59644531, 159.96291015999998), 'rotation':(-1.090973, -151.254395, -1.133118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6409.31832031, 2414.78492188, 159.53154297), 'rotation':(-1.109558, -151.255676, -1.153168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6399.45554688, 2409.37988281, 159.31291016), 'rotation':(-1.121887, -151.253189, -1.166504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6374.79683594, 2395.86671875, 158.75743164), 'rotation':(-1.147186, -151.251846, -1.193848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.0692968799995, 2385.05515625, 158.30578125), 'rotation':(-1.160431, -151.251328, -1.208191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6340.27390625, 2376.94703125, 157.96332031), 'rotation':(-1.163635, -151.254333, -1.21167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6330.41015625, 2371.54148438, 157.73463867), 'rotation':(-1.168732, -151.250137, -1.217163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6325.4784375, 2368.83886719, 157.61998047), 'rotation':(-1.172119, -151.252121, -1.220825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6310.68304688, 2360.73046875, 157.27432617), 'rotation':(-1.177094, -151.252594, -1.226227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6305.7514062499995, 2358.0278125, 157.1587207), 'rotation':(-1.177185, -151.252426, -1.226318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6295.8871875, 2352.62207031, 156.92749023), 'rotation':(-1.177216, -151.252579, -1.226349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6290.955, 2349.91917969, 156.8119043), 'rotation':(-1.177155, -151.250778, -1.226288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6286.02289062, 2347.21632812, 156.69626953), 'rotation':(-1.175171, -151.25296, -1.224152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6281.0912499999995, 2344.51367188, 156.58083984), 'rotation':(-1.173248, -151.253021, -1.222076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6276.15867188, 2341.81054688, 156.46546875), 'rotation':(-1.173248, -151.253021, -1.222076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6271.2265625, 2339.10765625, 156.35023438), 'rotation':(-1.173309, -151.251221, -1.222168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6266.2943749999995, 2336.40476562, 156.23498046999998), 'rotation':(-1.173248, -151.253021, -1.222076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6251.49796875, 2328.29617188, 155.88929688), 'rotation':(-1.171021, -151.250244, -1.219666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6246.5653906200005, 2325.5928125, 155.77425781), 'rotation':(-1.166718, -151.252762, -1.214996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6241.63328125, 2322.88992188, 155.6596875), 'rotation':(-1.162018, -151.252945, -1.2099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6236.70109375, 2320.18679688, 155.54549805), 'rotation':(-1.157776, -151.253128, -1.205322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6202.2465625, 2301.1575000000003, 154.75417969), 'rotation':(-1.133087, -151.253189, -1.178589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6188.83148438, 2293.90820312, 154.45494141), 'rotation':(-1.111481, -151.253891, -1.155273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6173.45992188, 2285.52929688, 154.11637695), 'rotation':(-1.106171, -151.254745, -1.149536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6168.4853125, 2282.80273438, 154.00680664), 'rotation':(-1.093872, -151.255127, -1.136261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6158.5341406200005, 2277.34960938, 153.78957031), 'rotation':(-1.069397, -151.257446, -1.109863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6143.60789062, 2269.1696875, 153.47279297), 'rotation':(-1.057159, -151.257889, -1.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6123.70648438, 2258.2629687500003, 153.05582031), 'rotation':(-1.026825, -151.256683, -1.064148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.82609375, 2244.62867188, 152.55923828000002), 'rotation':(-0.976379, -151.26236, -1.010101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6093.85101562, 2241.90210938, 152.46249023000001), 'rotation':(-0.966095, -151.260208, -0.999115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6083.8984375, 2236.4479687499997, 152.27104492), 'rotation':(-0.945496, -151.26088, -0.977112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6078.9232812499995, 2233.7214062499997, 152.17738281), 'rotation':(-0.924835, -151.260208, -0.955078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6073.9453125, 2230.993125, 152.08431640999999), 'rotation':(-0.924835, -151.260208, -0.955078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6063.9935937499995, 2225.53953125, 151.90222656), 'rotation':(-0.904266, -151.262222, -0.933167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6039.11179688, 2211.9035937500003, 151.46378906), 'rotation':(-0.843872, -151.262787, -0.869019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6009.5497656200005, 2195.55492188, 150.98782227), 'rotation':(-0.779572, -151.265076, -0.800995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6005.1849999999995, 2202.8671875, 150.98356445), 'rotation':(0.779557, 28.734911, 0.758564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6015.13671875, 2208.32125, 151.13837891), 'rotation':(0.801024, 28.733589, 0.778861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6030.064375, 2216.50242188, 151.37951171999998), 'rotation':(0.84389, 28.734819, 0.819298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6049.9701562499995, 2227.41085938, 151.7230957), 'rotation':(0.894031, 28.737883, 0.866448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6059.92132812, 2232.86476562, 151.90141602), 'rotation':(0.924794, 28.738426, 0.895287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6079.82421875, 2243.77195312, 152.27015625), 'rotation':(0.966158, 28.74114, 0.933969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.77585938, 2249.225625, 152.46158203000002), 'rotation':(0.976348, 28.740055, 0.943489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.7265625, 2254.67898438, 152.65541016), 'rotation':(0.986511, 28.740448, 0.952959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6104.70164062, 2257.40554688, 152.75314453000001), 'rotation':(1.006824, 28.742718, 0.971886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.62835938, 2265.58570312, 153.05479492), 'rotation':(1.046986, 28.742596, 1.00923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6129.578125, 2271.04, 153.26229492000002), 'rotation':(1.057149, 28.74333, 1.018657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6139.535625, 2276.4778125000003, 153.47170898000002), 'rotation':(1.05706, 28.74209, 1.018586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.4701562499995, 2284.6418750000003, 153.7884375), 'rotation':(1.0938, 28.744751, 1.052611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6159.44429688, 2287.36789062, 153.89677734), 'rotation':(1.106156, 28.745235, 1.064039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.34320312, 2298.2734375, 154.33433594), 'rotation':(1.111408, 28.745945, 1.068897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6184.23625, 2301.14890625, 154.44427734), 'rotation':(1.122323, 28.74473, 1.078976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6999.32710938, 2768.45898438, 167.06550781), 'rotation':(-0.344299, 179.840866, -0.34848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6988.03658203, 2768.49097656, 166.9975), 'rotation':(-0.348724, 179.840927, -0.352966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.39058594, 2768.50707031, 166.96320312), 'rotation':(-0.3508, 179.840942, -0.355133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6976.74605469, 2768.52294922, 166.92867188), 'rotation':(-0.352997, 179.838608, -0.357391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6971.09957031, 2768.53882812, 166.89396484), 'rotation':(-0.355286, 179.841003, -0.35968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6965.4540625, 2768.5546875, 166.8590625), 'rotation':(-0.3573, 179.841034, -0.361786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6942.87349609, 2768.61839844, 166.71746094), 'rotation':(-0.366669, 179.838913, -0.371399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6931.58296875, 2768.65039062, 166.64492188), 'rotation':(-0.375061, 179.83902, -0.379974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6920.29146484, 2768.68212891, 166.57064452999998), 'rotation':(-0.383118, 179.841782, -0.388275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6892.06587891, 2768.76171875, 166.37824218999998), 'rotation':(-0.39856, 179.839569, -0.404144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6886.42085938, 2768.77783203, 166.33896484000002), 'rotation':(-0.408997, 179.841324, -0.414856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6869.48482422, 2768.82568359, 166.21675781000002), 'rotation':(-0.429962, 179.841644, -0.436462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.83931641, 2768.8415625, 166.17455078), 'rotation':(-0.435242, 179.841431, -0.441895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6841.26021484, 2768.90527344, 166.00205078), 'rotation':(-0.453369, 179.840454, -0.460602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6835.61470703, 2768.92113281, 165.95753906000002), 'rotation':(-0.46048, 179.842896, -0.467926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.9696875, 2768.93701172, 165.91234375), 'rotation':(-0.46759, 179.840683, -0.475281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6813.03560547, 2768.98486328, 165.77275391), 'rotation':(-0.489288, 179.843384, -0.497711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6807.38960938, 2769.00244141, 165.72488281000003), 'rotation':(-0.489288, 179.843384, -0.497711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.74605469, 2769.01660156, 165.67652343999998), 'rotation':(-0.492859, 179.842957, -0.501404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.16792969, 2769.0803125, 165.47763672000002), 'rotation':(-0.529694, 179.843246, -0.539551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6767.87789062, 2769.11207031, 165.37232422), 'rotation':(-0.544281, 179.843536, -0.554718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6762.24019531, 2769.10546875, 165.31867188), 'rotation':(-0.551697, 179.842117, -0.562408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6761.33296875, 2777.55761719, 165.3096875), 'rotation':(0.544284, -0.156464, 0.53402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6767.88765625, 2777.49292969, 165.37220703), 'rotation':(0.529702, -0.156738, 0.519972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6773.5321875, 2777.47705078, 165.4253125), 'rotation':(0.529702, -0.156738, 0.519972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.17769531, 2777.46117188, 165.4775), 'rotation':(0.514955, -0.157013, 0.505771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6784.82271484, 2777.4453125, 165.52839844), 'rotation':(0.500223, -0.157257, 0.491529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6807.40181641, 2777.38134766, 165.72478515999998), 'rotation':(0.482164, -0.156738, 0.474099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6813.04683594, 2777.36546875, 165.77263672), 'rotation':(0.482164, -0.156738, 0.474099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6824.33736328, 2777.33349609, 165.86638672), 'rotation':(0.467602, -0.156982, 0.460013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6841.27193359, 2777.28564453, 166.00197265999998), 'rotation':(0.446045, -0.157318, 0.439152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6852.56246094, 2777.25367188, 166.0890625), 'rotation':(0.435226, -0.158569, 0.428648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.85298828, 2777.22167969, 166.17447266), 'rotation':(0.429988, -0.158356, 0.423568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6875.14351562, 2777.18994141, 166.25800781), 'rotation':(0.408978, -0.158661, 0.403176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6886.43404297, 2777.15820312, 166.33890625), 'rotation':(0.398589, -0.158813, 0.393073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.36910156, 2777.11035156, 166.45591797), 'rotation':(0.391295, -0.160767, 0.385974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6914.66060547, 2777.07861328, 166.53277343999997), 'rotation':(0.383119, -0.158203, 0.378032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6931.59664062, 2777.03076172, 166.64486327999998), 'rotation':(0.370893, -0.158356, 0.366129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6937.24166016, 2777.01488281, 166.68134766), 'rotation':(0.366686, -0.161072, 0.362009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6942.88814453, 2776.99878906, 166.71740234), 'rotation':(0.362663, -0.158447, 0.358102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6954.17867188, 2776.96679688, 166.78855468999998), 'rotation':(0.357308, -0.158966, 0.352875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6959.82417969, 2776.9509375, 166.82390625), 'rotation':(0.357308, -0.158966, 0.352875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6971.11519531, 2776.91917969, 166.89392578), 'rotation':(0.353011, -0.159027, 0.348689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6982.40621094, 2776.88695312, 166.96314453), 'rotation':(0.348715, -0.159058, 0.344494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6993.69722656, 2776.85498047, 167.03154297), 'rotation':(0.344276, -0.159119, 0.340157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6718.5321875, 2769.25171875, 164.88146484), 'rotation':(-0.615082, 179.846008, -0.628418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6707.22115234, 2769.28369141, 164.76035156), 'rotation':(-0.620361, 179.843658, -0.633881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6701.56490234, 2769.29980469, 164.69910156000003), 'rotation':(-0.6203, 179.843674, -0.63382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6667.63226562, 2769.39527344, 164.31410156), 'rotation':(-0.687347, 179.847015, -0.70401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6650.6684375, 2769.44335938, 164.11074219), 'rotation':(-0.695709, 179.84671, -0.712769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6645.01167969, 2769.45921875, 164.04205077999998), 'rotation':(-0.712311, 179.847122, -0.730194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.70113281, 2769.49121094, 163.90212891), 'rotation':(-0.728943, 179.847504, -0.747681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.38960938, 2769.52320312, 163.75729492), 'rotation':(-0.745605, 179.847961, -0.765198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6611.08003906, 2769.55517578, 163.60921875), 'rotation':(-0.753998, 179.848099, -0.774048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6599.77, 2769.58691406, 163.45985352), 'rotation':(-0.761963, 179.848923, -0.78244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6582.805625, 2769.63476562, 163.23027344), 'rotation':(-0.794281, 179.848251, -0.816559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6571.4950781200005, 2769.66699219, 163.07214844), 'rotation':(-0.81842, 179.850815, -0.842041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6560.18550781, 2769.69898438, 162.91118164), 'rotation':(-0.81842, 179.848694, -0.842072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6548.87640625, 2769.73095703, 162.74896484), 'rotation':(-0.841156, 179.849792, -0.86615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.91109375, 2769.77880859, 162.49956055), 'rotation':(-0.871613, 179.850708, -0.898438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6526.25582031, 2769.7946875, 162.41455078), 'rotation':(-0.871613, 179.850708, -0.898438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6514.94773438, 2769.82666016, 162.24186523), 'rotation':(-0.879211, 179.852264, -0.906525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6729.86763672, 2777.60035156, 164.99941406000002), 'rotation':(0.583066, -0.156708, 0.571286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6724.211875, 2777.61644531, 164.94087890999998), 'rotation':(0.593612, -0.154449, 0.58141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6712.89986328, 2777.6484375, 164.82125), 'rotation':(0.60428, -0.156281, 0.591636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6701.5888281200005, 2777.68042969, 164.69910156000003), 'rotation':(0.620331, -0.156342, 0.607011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6695.93453125, 2777.69628906, 164.63746093999998), 'rotation':(0.620277, -0.153656, 0.606963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6684.62300781, 2777.72828125, 164.51158203), 'rotation':(0.645453, -0.155029, 0.631033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6667.65621094, 2777.77613281, 164.31410156), 'rotation':(0.678996, -0.154236, 0.663033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6662.00191406, 2777.79222656, 164.24646484000002), 'rotation':(0.687301, -0.152985, 0.670958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6656.34617188, 2777.80810547, 164.17859375), 'rotation':(0.687301, -0.152985, 0.670958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6650.69234375, 2777.82398438, 164.11074219), 'rotation':(0.687349, -0.152985, 0.671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6645.03609375, 2777.83984375, 164.04205077999998), 'rotation':(0.695716, -0.15329, 0.678968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.06882812, 2777.88792969, 163.83013671999998), 'rotation':(0.728952, -0.152466, 0.710578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6616.75972656, 2777.9196875, 163.68370117), 'rotation':(0.745604, -0.152039, 0.726389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6605.4482031200005, 2777.95166016, 163.53480469), 'rotation':(0.753998, -0.151886, 0.734352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6599.79390625, 2777.96777344, 163.45985352), 'rotation':(0.753998, -0.151886, 0.734352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6582.82953125, 2778.015625, 163.23027344), 'rotation':(0.778081, -0.150635, 0.757159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6577.17378906, 2778.03173828, 163.15183594), 'rotation':(0.794283, -0.150177, 0.772485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6565.86421875, 2778.06371094, 162.99199219), 'rotation':(0.810334, -0.151276, 0.787658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6560.20945312, 2778.07958984, 162.91119141), 'rotation':(0.818421, -0.14917, 0.795289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6554.55367188, 2778.09546875, 162.83038086), 'rotation':(0.818421, -0.151306, 0.795284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.935, 2778.15941406, 162.49956055), 'rotation':(0.856485, -0.148132, 0.831157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6509.31585938, 2778.22339844, 162.15504883), 'rotation':(0.879209, -0.147705, 0.852518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6173.90671875, 2770.78929688, 156.58808594), 'rotation':(-0.870667, 179.852051, -0.897461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6190.73625, 2770.74195312, 156.84703125), 'rotation':(-0.878998, 179.851089, -0.906281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6201.95648438, 2770.71019531, 157.02404296999998), 'rotation':(-0.912262, 179.853577, -0.941681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6207.566875, 2770.69433594, 157.11376953), 'rotation':(-0.912262, 179.853577, -0.941681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6218.78609375, 2770.66259766, 157.29611328000001), 'rotation':(-0.928925, 179.852661, -0.959412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6224.395, 2770.64671875, 157.38789062), 'rotation':(-0.937195, 179.853439, -0.968231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6241.22359375, 2770.599375, 157.66460938), 'rotation':(-0.941315, 179.852493, -0.972656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6246.83296875, 2770.58349609, 157.75787109), 'rotation':(-0.949615, 179.85463, -0.981506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6258.0521874999995, 2770.55175781, 157.94631836), 'rotation':(-0.966125, 179.853317, -0.999146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6263.6615624999995, 2770.53589844, 158.04120117), 'rotation':(-0.970123, 179.855728, -1.003418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6269.27046875, 2770.52001953, 158.13620117), 'rotation':(-0.970123, 179.855728, -1.003418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6274.87984375, 2770.50414062, 158.23123046999999), 'rotation':(-0.970184, 179.8535, -1.003479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6297.316875, 2770.43652344, 158.61311523), 'rotation':(-0.975433, 179.855392, -1.009064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6319.75390625, 2770.41064453, 159.00099609), 'rotation':(-0.991241, 179.856049, -1.026001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6325.36273438, 2770.39476562, 159.09803711), 'rotation':(-0.990753, 179.856308, -1.025452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6330.97265625, 2770.37890625, 159.19499023), 'rotation':(-0.990021, 179.853683, -1.024689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6347.79929688, 2770.33128906, 159.48530273), 'rotation':(-0.987274, 179.853577, -1.021729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6359.0165625, 2770.29980469, 159.67835938), 'rotation':(-0.985474, 179.856125, -1.019836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.6264062499995, 2770.28394531, 159.77478516), 'rotation':(-0.984497, 179.8535, -1.018799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6370.2353125, 2770.26806641, 159.87115234), 'rotation':(-0.983887, 179.855103, -1.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6381.45359375, 2770.2365625, 160.06376953), 'rotation':(-0.981842, 179.856644, -1.01593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6392.67183594, 2770.20484375, 160.25535156), 'rotation':(-0.977661, 179.854279, -1.011475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6403.8896093799995, 2770.17308594, 160.44547852), 'rotation':(-0.969177, 179.856216, -1.002411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6415.1083593799995, 2770.14160156, 160.63490234), 'rotation':(-0.967133, 179.854568, -1.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6420.71820312, 2770.12574219, 160.72946289), 'rotation':(-0.964233, 179.853668, -0.997101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6431.93601562, 2770.09398438, 160.91714844), 'rotation':(-0.953278, 179.855881, -0.985413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6443.15425781, 2770.06226562, 161.10258789), 'rotation':(-0.942322, 179.852921, -0.973694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6454.3724999999995, 2770.03050781, 161.28581055), 'rotation':(-0.931366, 179.85257, -0.962036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6459.98140625, 2770.01464844, 161.37657227), 'rotation':(-0.925812, 179.852371, -0.956085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6465.5912499999995, 2769.99902344, 161.46704102), 'rotation':(-0.923035, 179.853439, -0.953156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6476.90671875, 2778.31494141, 161.64868164), 'rotation':(0.915799, -0.147369, 0.886861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6471.2978125, 2778.33082031, 161.55862305), 'rotation':(0.915799, -0.147369, 0.886861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6465.68796875, 2778.34667969, 161.46821289), 'rotation':(0.923018, -0.146545, 0.893634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6454.47117188, 2778.37816406, 161.28703125), 'rotation':(0.925805, -0.147614, 0.896243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6448.86179688, 2778.39404297, 161.19569336), 'rotation':(0.931365, -0.144836, 0.90144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6437.64398438, 2778.42578125, 161.01139648), 'rotation':(0.942313, -0.147064, 0.911692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6432.03460938, 2778.44140625, 160.91837891), 'rotation':(0.947723, -0.144318, 0.916743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6420.81636719, 2778.47314453, 160.73073242), 'rotation':(0.958829, -0.146545, 0.92713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6392.7724218799995, 2778.55224609, 160.25666992), 'rotation':(0.973425, -0.145874, 0.940762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6387.1630468799995, 2778.568125, 160.16105469000001), 'rotation':(0.97766, -0.143494, 0.944709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6381.55414062, 2778.58398438, 160.06509766), 'rotation':(0.97766, -0.143494, 0.944709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6375.94578125, 2778.59984375, 159.96885742), 'rotation':(0.981826, -0.145569, 0.948604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6308.6371875, 2778.78980469, 158.80818359), 'rotation':(0.991224, -0.143951, 0.957352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6303.02734375, 2778.80566406, 158.71109375), 'rotation':(0.991327, -0.145508, 0.957449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6291.80804688, 2778.83740234, 158.51820312), 'rotation':(0.985992, -0.144257, 0.952477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6286.19867188, 2778.85328125, 158.42266602), 'rotation':(0.975419, -0.144623, 0.942625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6280.58835938, 2778.86890625, 158.32751953000002), 'rotation':(0.970276, -0.146515, 0.937813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6269.37054688, 2778.900625, 158.1375), 'rotation':(0.970126, -0.144287, 0.937683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6258.1503125, 2778.93238281, 157.94756836), 'rotation':(0.970126, -0.144287, 0.937683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6246.9315625, 2778.96410156, 157.75912109), 'rotation':(0.957797, -0.146973, 0.92618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6235.7123437499995, 2778.99560547, 157.57310547), 'rotation':(0.949628, -0.145355, 0.918527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6230.1015625, 2779.01148438, 157.48087891), 'rotation':(0.94133, -0.14563, 0.910765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6218.8828125, 2779.04320312, 157.29731445), 'rotation':(0.937191, -0.146576, 0.906897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6207.66203125, 2779.07496094, 157.11491211), 'rotation':(0.928906, -0.147308, 0.899137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6196.4384375, 2779.10644531, 156.93582031), 'rotation':(0.912267, -0.146423, 0.883546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6190.8290625, 2779.12207031, 156.8480957), 'rotation':(0.895622, -0.148376, 0.867947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6185.21875, 2779.13818359, 156.76084961), 'rotation':(0.895622, -0.148376, 0.867947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.60984375, 2779.1540625, 156.67477539), 'rotation':(0.878977, -0.147461, 0.852313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6173.99796875, 2779.1696875, 156.58911133), 'rotation':(0.878977, -0.147461, 0.852313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6041.78609375, 2771.161875, 154.83030273), 'rotation':(-0.620789, 179.844574, -0.634338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6052.86375, 2771.130625, 154.95363281), 'rotation':(-0.643616, 179.845078, -0.658203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.4037499999995, 2771.115, 155.01787109), 'rotation':(-0.666687, 179.847183, -0.682343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6063.94234375, 2771.099375, 155.08300781), 'rotation':(-0.666687, 179.847183, -0.682343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.4809375, 2771.08375, 155.14967773), 'rotation':(-0.689484, 179.846146, -0.706238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6075.01953125, 2771.068125, 155.21712890999999), 'rotation':(-0.700989, 179.846802, -0.718292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6080.5590625, 2771.0525, 155.28521484), 'rotation':(-0.700989, 179.846802, -0.718292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.1732812499995, 2771.005625, 155.49579101999998), 'rotation':(-0.74411, 179.848724, -0.763641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6108.2514062499995, 2770.974375, 155.64235352), 'rotation':(-0.769165, 179.84938, -0.790039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6124.86664062, 2770.9275, 155.87095703), 'rotation':(-0.799866, 179.848007, -0.822449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6130.40421875, 2770.911875, 155.94830078), 'rotation':(-0.799927, 179.850723, -0.82254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6124.90085938, 2779.30810547, 155.87111328), 'rotation':(0.799938, -0.151978, 0.777832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.36125, 2779.32373047, 155.79392578), 'rotation':(0.799863, -0.149261, 0.777762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6113.82273438, 2779.33935547, 155.71758789), 'rotation':(0.793805, -0.152557, 0.772032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6108.28460938, 2779.35498047, 155.6424707), 'rotation':(0.781326, -0.150299, 0.760225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6086.129375, 2779.41773438, 155.35429688), 'rotation':(0.732032, -0.151581, 0.713504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6063.9740624999995, 2779.48023438, 155.08311523), 'rotation':(0.68948, -0.152252, 0.673048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.4349999999995, 2779.49585938, 155.01795898), 'rotation':(0.68948, -0.152252, 0.673048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.3559375, 2779.52710938, 154.89148438), 'rotation':(0.643622, -0.154907, 0.629273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6144.92375, 3041.48876953, 157.96986328), 'rotation':(0.37495, 90.252213, 0.370064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6144.94773438, 3035.90185547, 157.9331543), 'rotation':(0.376043, 90.252228, 0.371125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.0209374999995, 3019.14111328, 157.82237305), 'rotation':(0.379315, 90.252281, 0.374325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.04484375, 3013.55419922, 157.78526367), 'rotation':(0.380421, 90.252281, 0.375382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.06976562, 3007.96728516, 157.748125), 'rotation':(0.38081, 90.251984, 0.375771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.14304688, 2991.20629883, 157.63660156), 'rotation':(0.381582, 90.252563, 0.376518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.16742188, 2985.61938477, 157.5993457), 'rotation':(0.382135, 90.250389, 0.377058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.19140625, 2980.03271484, 157.56208984), 'rotation':(0.382135, 90.255669, 0.377049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.24015625, 2968.85864258, 157.48756836), 'rotation':(0.382293, 90.255669, 0.377214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.26460938, 2963.27148438, 157.4503125), 'rotation':(0.381849, 90.249702, 0.376794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.3134375, 2952.09765625, 157.37588867), 'rotation':(0.381316, 90.252571, 0.376271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.3378125, 2946.51049805, 157.33875), 'rotation':(0.381316, 90.252571, 0.376271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.36179688, 2940.92358398, 157.30160156), 'rotation':(0.380776, 90.252563, 0.375751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.38617188, 2935.33666992, 157.26451172), 'rotation':(0.380776, 90.252563, 0.375751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.410625, 2929.74951172, 157.22743164), 'rotation':(0.380332, 90.252548, 0.375303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.50828125, 2907.40136719, 157.07926758), 'rotation':(0.380114, 90.247978, 0.375097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.5321875, 2901.81445312, 157.04239257999998), 'rotation':(0.378065, 90.253403, 0.373104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.5810156200005, 2890.64013672, 156.96893555), 'rotation':(0.376302, 90.250534, 0.371393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.62984375, 2879.46606445, 156.89556641), 'rotation':(0.376302, 90.253609, 0.371393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.65421875, 2873.87890625, 156.85897461000002), 'rotation':(0.375606, 90.251907, 0.370719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.703125, 2862.70483398, 156.78618164), 'rotation':(0.37204, 90.251862, 0.367229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.7275, 2857.11791992, 156.74995117), 'rotation':(0.370886, 90.251831, 0.366101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.77585938, 2845.94384766, 156.67789062), 'rotation':(0.368468, 90.251801, 0.363751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.80023438, 2840.35668945, 156.64203125), 'rotation':(0.367314, 90.251785, 0.362625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.8246875, 2834.76976562, 156.60625), 'rotation':(0.366706, 90.257095, 0.362042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.89742188, 2818.0078125, 156.49946289), 'rotation':(0.362055, 90.25341, 0.357504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.970625, 2801.24609375, 156.39485352), 'rotation':(0.355552, 90.248993, 0.351164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.4003125, 2790.099375, 156.32573242), 'rotation':(-0.354065, -89.749359, -0.358459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6154.3515625, 2801.27320312, 156.39479492), 'rotation':(-0.354065, -89.746063, -0.35849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.254375, 2823.62183594, 156.53478515999998), 'rotation':(-0.362061, -89.746582, -0.366638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.20554688, 2834.79638672, 156.60618164), 'rotation':(-0.366699, -89.748413, -0.371429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.1810937499995, 2840.38330078, 156.64197266), 'rotation':(-0.366699, -89.748413, -0.371429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.10789062, 2857.14453125, 156.74989258), 'rotation':(-0.369751, -89.748138, -0.374573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.01023438, 2879.49243164, 156.89550781), 'rotation':(-0.37561, -89.748108, -0.380554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.8646874999995, 2913.01489258, 157.11618164), 'rotation':(-0.380127, -89.746552, -0.385193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.7909375, 2929.77563477, 157.22735352), 'rotation':(-0.379944, -89.746552, -0.38501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.74265625, 2940.94995117, 157.3015332), 'rotation':(-0.380341, -89.747437, -0.385406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.71820312, 2946.53686523, 157.33867188), 'rotation':(-0.380798, -89.747437, -0.385864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.6693749999995, 2957.71069336, 157.41300781), 'rotation':(-0.381317, -89.747406, -0.386414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.62109375, 2968.88476562, 157.48749023), 'rotation':(-0.381866, -89.747406, -0.386993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.5721875, 2980.05859375, 157.56203125), 'rotation':(-0.382111, -89.749634, -0.387238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.5478125, 2985.64526367, 157.59928711), 'rotation':(-0.382141, -89.744324, -0.387268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.49898438, 2996.81958008, 157.67375), 'rotation':(-0.381592, -89.747437, -0.386688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.47453125, 3002.40649414, 157.7109082), 'rotation':(-0.38092, -89.747986, -0.385986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.42578125, 3013.58032227, 157.78518555), 'rotation':(-0.380798, -89.747986, -0.385895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.3529687499995, 3030.34106445, 157.89625977), 'rotation':(-0.378204, -89.747742, -0.38324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.30414062, 3041.51489258, 157.96978516), 'rotation':(-0.376038, -89.747772, -0.381012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.27976562, 3047.10180664, 158.00639648), 'rotation':(-0.374939, -89.747772, -0.379883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.2309375, 3058.27587891, 158.07928711), 'rotation':(-0.372742, -89.747803, -0.377625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6309.71578125, 2095.54054688, 156.04670898), 'rotation':(-0.159515, 113.439232, -0.1604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6305.21671875, 2105.91726562, 156.01454102), 'rotation':(-0.167969, 113.439285, -0.168945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6302.96726562, 2111.10570312, 155.99782227), 'rotation':(-0.172241, 113.439301, -0.173309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6298.46921875, 2121.4821875, 155.96299805), 'rotation':(-0.184845, 113.439384, -0.186035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6296.2196875, 2126.6706249999997, 155.94491211000002), 'rotation':(-0.187012, 113.438866, -0.188232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6293.970625, 2131.8584375, 155.92654296999999), 'rotation':(-0.187012, 113.438866, -0.188232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6291.72117188, 2137.046875, 155.90808594), 'rotation':(-0.189209, 113.43972, -0.19046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6289.4716406200005, 2142.23484375, 155.88945311999998), 'rotation':(-0.189209, 113.43972, -0.19046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6287.22265625, 2147.42335938, 155.87068359), 'rotation':(-0.193756, 113.440384, -0.195068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6284.973125, 2152.6115625, 155.8515625), 'rotation':(-0.198181, 113.436874, -0.199554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6282.72359375, 2157.79984375, 155.83216797), 'rotation':(-0.198181, 113.436874, -0.199554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6278.22507812, 2168.17648438, 155.79255859), 'rotation':(-0.204956, 113.439728, -0.206421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6271.47703125, 2183.74148438, 155.73188477), 'rotation':(-0.208069, 113.443466, -0.209564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6269.2275, 2188.9296875, 155.71136719), 'rotation':(-0.210022, 113.438141, -0.211548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6262.47992188, 2204.4948437499997, 155.64862305), 'rotation':(-0.2164, 113.442574, -0.218048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6257.9809375, 2214.87132812, 155.60580078), 'rotation':(-0.220459, 113.438217, -0.222168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6253.48234375, 2225.24804688, 155.56228516), 'rotation':(-0.221436, 113.440475, -0.223145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6246.73382812, 2240.81273438, 155.49666016), 'rotation':(-0.222595, 113.439415, -0.224335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6244.484375, 2246.00148438, 155.47466796999998), 'rotation':(-0.224854, 113.440224, -0.226624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6239.9857812499995, 2256.37820312, 155.43020508), 'rotation':(-0.22583, 113.440933, -0.227631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6235.48679688, 2266.75484375, 155.385625), 'rotation':(-0.225922, 113.440933, -0.227722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6233.23773438, 2271.94335938, 155.36333008), 'rotation':(-0.225922, 113.440933, -0.227722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6230.98828125, 2277.1315624999997, 155.34101562), 'rotation':(-0.225861, 113.437576, -0.227631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6226.48921875, 2287.50875, 155.29644531), 'rotation':(-0.225464, 113.442719, -0.227234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6229.7509375, 2301.05421875, 155.2528125), 'rotation':(0.224324, -66.557312, 0.22258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6234.2465625, 2290.6848437500003, 155.29713867), 'rotation':(0.22584, -66.559662, 0.224064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6240.99015625, 2275.130625, 155.36395507999998), 'rotation':(0.225847, -66.559052, 0.22407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6245.4857812499995, 2264.76125, 155.40850586), 'rotation':(0.22584, -66.559662, 0.224064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6247.73335938, 2259.5768749999997, 155.43078125), 'rotation':(0.22584, -66.559662, 0.224064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6252.22898438, 2249.2075, 155.47521484), 'rotation':(0.222589, -66.560577, 0.220869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6254.47703125, 2244.02296875, 155.4971875), 'rotation':(0.221428, -66.562225, 0.219731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6263.46773438, 2223.2846875, 155.58456055), 'rotation':(0.220465, -66.561798, 0.218767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6270.2109375, 2207.73070312, 155.64901367000002), 'rotation':(0.214188, -66.561829, 0.212586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6274.7060156200005, 2197.3615625, 155.69099609), 'rotation':(0.209994, -66.561859, 0.208464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6279.20164062, 2186.9921875, 155.73220703), 'rotation':(0.205964, -66.56189, 0.204491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6281.44921875, 2181.8073437499997, 155.75251953), 'rotation':(0.20496, -66.560242, 0.203495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6283.6971875, 2176.6228125, 155.77273438), 'rotation':(0.202727, -66.55954, 0.201298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6292.6884375, 2155.88476562, 155.85178711), 'rotation':(0.193745, -66.559631, 0.192436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6297.18359375, 2145.51539062, 155.88962891), 'rotation':(0.18699, -66.557343, 0.185788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6301.6796875, 2135.14648438, 155.92669922), 'rotation':(0.187017, -66.561157, 0.185798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6312.91796875, 2109.22359375, 156.01462891), 'rotation':(0.163808, -66.56073, 0.162883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6321.8046875, 2088.9296875, 156.07609375), 'rotation':(0.153256, -66.561188, 0.152441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6212.32757812, 2341.2434375000003, 155.08214844), 'rotation':(0.221558, -66.560699, 0.219847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6210.0834374999995, 2346.41945312, 155.06079102), 'rotation':(0.217111, -66.56073, 0.215464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6198.86273438, 2372.29957031, 154.95529297), 'rotation':(0.213382, -66.55954, 0.211792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6192.13078125, 2387.82738281, 154.89439453), 'rotation':(0.201846, -66.558624, 0.200426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6189.88671875, 2393.00390625, 154.87464844), 'rotation':(0.199018, -66.563293, 0.197634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6185.39890625, 2403.35546875, 154.83609375), 'rotation':(0.193315, -66.558685, 0.192015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6180.910625, 2413.70800781, 154.79826172), 'rotation':(0.19171, -66.563263, 0.190425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6178.6669531200005, 2418.88402344, 154.77943359), 'rotation':(0.191833, -66.558594, 0.190552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6174.17867188, 2429.23609375, 154.74286132999998), 'rotation':(0.182578, -66.560333, 0.181406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6169.6903906200005, 2439.58835938, 154.70819336), 'rotation':(0.176253, -66.561157, 0.175176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6160.7138281200005, 2460.29371094, 154.64238281), 'rotation':(0.164587, -66.558197, 0.163648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.4701562499995, 2465.46996094, 154.62666016), 'rotation':(0.159772, -66.562805, 0.158889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6156.22601562, 2470.64601562, 154.61141602), 'rotation':(0.15495, -66.561829, 0.154112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6149.4935937499995, 2486.1740625, 154.56855469), 'rotation':(0.140463, -66.55835, 0.139769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.24945312, 2491.35007812, 154.55522461), 'rotation':(0.13549, -66.561951, 0.134852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.0053124999995, 2496.52734375, 154.54234375), 'rotation':(0.130805, -66.562958, 0.130212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6140.5165625, 2506.87964844, 154.51735352), 'rotation':(0.12838, -66.561493, 0.127808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6136.02828125, 2517.23195312, 154.49395508), 'rotation':(0.113484, -66.562012, 0.113041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6131.5404687499995, 2527.58398438, 154.47282227), 'rotation':(0.103628, -66.562012, 0.103253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6129.29632812, 2532.76050781, 154.46318359), 'rotation':(0.103628, -66.562012, 0.103253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6120.31976562, 2553.4665625, 154.42803711), 'rotation':(0.08882, -66.563873, 0.088542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6118.07515625, 2558.6428125, 154.42008789), 'rotation':(0.082782, -66.559631, 0.082541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6106.8544531200005, 2584.52441406, 154.39303711), 'rotation':(0.040681, -66.560089, 0.04063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6104.6103125, 2589.70042969, 154.38902344), 'rotation':(0.040687, -66.561005, 0.040622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.1224999999995, 2600.05273438, 154.38099609), 'rotation':(0.040687, -66.565308, 0.040632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.8778906200005, 2605.22972656, 154.37785156), 'rotation':(0.028618, -66.560333, 0.028599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6077.6810937499995, 2651.81566406, 154.38081055), 'rotation':(-0.007996, -66.561188, -0.007996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6073.191875, 2662.16945312, 154.38375976999998), 'rotation':(-0.014801, -66.558746, -0.014832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6061.970625, 2688.0525, 154.41), 'rotation':(-0.062897, -66.563049, -0.063049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6057.48289062, 2698.40478516, 154.42366211), 'rotation':(-0.070221, -66.564148, -0.070374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6055.23875, 2703.58082031, 154.43128906), 'rotation':(-0.080017, -66.564148, -0.080261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6052.9940625, 2708.75660156, 154.43943359000002), 'rotation':(-0.084991, -66.559082, -0.085266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6037.28515625, 2744.99046875, 154.50851562), 'rotation':(-0.108795, -66.561493, -0.109222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6206.90085938, 2332.66234375, 155.10416016), 'rotation':(-0.217102, 113.439255, -0.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6204.65570312, 2337.84695312, 155.08240234000002), 'rotation':(-0.217102, 113.439255, -0.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6202.4115624999995, 2343.03125, 155.06100586), 'rotation':(-0.214783, 113.437813, -0.2164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6197.91648438, 2353.39917969, 155.01855469), 'rotation':(-0.214783, 113.441284, -0.2164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6182.1903906200005, 2389.6875, 154.87458984), 'rotation':(-0.195984, 113.435677, -0.197327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.9428124999995, 2394.87109375, 154.85513672), 'rotation':(-0.193329, 113.441307, -0.194611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6177.69578125, 2400.0549218799997, 154.8359668), 'rotation':(-0.191711, 113.440575, -0.192993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6175.4482031200005, 2405.23875, 154.81698242000002), 'rotation':(-0.191833, 113.437569, -0.193115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6168.7060156200005, 2420.79027344, 154.76063477), 'rotation':(-0.182587, 113.439629, -0.183746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6164.2109375, 2431.15796875, 154.72503906), 'rotation':(-0.170074, 113.442345, -0.171082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6161.9638281200005, 2436.34179688, 154.70790039), 'rotation':(-0.170074, 113.442345, -0.171082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6157.46875, 2446.70945312, 154.6747168), 'rotation':(-0.166931, 113.438614, -0.167908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6143.98382812, 2477.8127343799997, 154.58197266), 'rotation':(-0.140472, 113.437088, -0.141144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6137.24164062, 2493.365, 154.54193359), 'rotation':(-0.128387, 113.438499, -0.128937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6134.9940625, 2498.54882812, 154.52926758), 'rotation':(-0.123444, 113.438622, -0.123962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6132.7465625, 2503.73339844, 154.51692383), 'rotation':(-0.123444, 113.438622, -0.123962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6126.004375, 2519.2846875, 154.48260742), 'rotation':(-0.103607, 113.43795, -0.104004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6117.01460938, 2540.02074219, 154.44477539), 'rotation':(-0.088806, 113.439995, -0.089081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6108.024375, 2560.75683594, 154.41275391), 'rotation':(-0.058777, 113.437782, -0.058929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6101.28171875, 2576.30859375, 154.39681640999999), 'rotation':(-0.04068, 113.438988, -0.040741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6099.0341406200005, 2581.49316406, 154.39280273), 'rotation':(-0.04068, 113.438988, -0.040741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.7865624999995, 2586.67699219, 154.38878906), 'rotation':(-0.040833, 113.439911, -0.040894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.2919531200005, 2597.04417969, 154.38075195), 'rotation':(-0.028656, 113.439659, -0.028656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.0443749999995, 2602.22925781, 154.37768555), 'rotation':(-0.004242, 113.436386, -0.004211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6085.54929688, 2612.59742188, 154.37540038999998), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6083.30171875, 2617.78246094, 154.37617188000002), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6081.05414062, 2622.96605469, 154.37695312), 'rotation':(0.007827, 113.438805, 0.007829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6072.064375, 2643.70070312, 154.38007812), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.81734375, 2648.88453125, 154.38087890999998), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6067.56929688, 2654.06910156, 154.38192383), 'rotation':(0.014808, 113.436623, 0.014809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6060.82609375, 2669.62207031, 154.39220703), 'rotation':(0.056096, 113.440292, 0.055987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6056.33148438, 2679.99046875, 154.40427734000002), 'rotation':(0.062892, 113.436966, 0.062756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6054.08390625, 2685.17529297, 154.41056641), 'rotation':(0.065563, 113.440857, 0.065416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.34171875, 2700.72632812, 154.43201172), 'rotation':(0.085009, 113.435867, 0.084763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6042.8466406200005, 2711.09351562, 154.44897461), 'rotation':(0.094653, 113.435898, 0.094337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6038.3515625, 2721.46240234, 154.46806641), 'rotation':(0.101968, 113.438454, 0.101607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6033.8568749999995, 2731.82958984, 154.48819336), 'rotation':(0.108805, 113.438484, 0.108396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6031.609375, 2737.01416016, 154.49847656), 'rotation':(0.108805, 113.438484, 0.108396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.7665625, 2797.76683594, 154.69857421999998), 'rotation':(0.22806, 106.946373, 0.226252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6007.27195312, 2802.70703125, 154.71981445), 'rotation':(0.240354, 106.768562, 0.238347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6016.41203125, 2801.31542969, 154.70328125), 'rotation':(-0.233704, -73.054077, -0.235626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6014.7841406200005, 2806.70777344, 154.72678711), 'rotation':(-0.240356, -73.227356, -0.242371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6011.53703125, 2817.4821875, 154.77604492), 'rotation':(-0.253601, -73.230774, -0.255859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6009.9140625, 2822.86914062, 154.80160156), 'rotation':(-0.260345, -73.232452, -0.262726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6003.42132812, 2844.41674805, 154.90424805), 'rotation':(-0.263153, -73.230469, -0.265594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.8525, 3310.14964844, 169.14882812), 'rotation':(-0.465179, -89.549408, -0.472778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.98677734, 3293.05761719, 169.01007812), 'rotation':(-0.463409, -89.545441, -0.470947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6912.07613281, 3281.66308594, 168.91824218999997), 'rotation':(-0.456116, -89.545563, -0.46344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.16548828, 3270.26832031, 168.8275), 'rotation':(-0.452576, -89.549438, -0.459778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.20992188, 3264.57080078, 168.7825), 'rotation':(-0.450775, -89.542847, -0.457886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6912.25484375, 3258.87353516, 168.73767578), 'rotation':(-0.450623, -89.547333, -0.457764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.65669922, 3207.59644531, 168.3440625), 'rotation':(-0.425629, -89.547424, -0.431976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.70162109, 3201.89892578, 168.30173828), 'rotation':(-0.425781, -89.547424, -0.432159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6912.79097656, 3190.50367188, 168.21742188), 'rotation':(-0.416962, -89.545166, -0.423065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.88033203, 3179.10888672, 168.13445312), 'rotation':(-0.411102, -89.548523, -0.417053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.92476562, 3173.41162109, 168.09355469), 'rotation':(-0.405365, -89.548584, -0.411133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6913.14839844, 3144.92260742, 167.89367188), 'rotation':(-0.388153, -89.547974, -0.393463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6913.19283203, 3139.22485352, 167.85488281000002), 'rotation':(-0.382446, -89.548065, -0.387573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6913.2821875, 3127.82983398, 167.77892577999998), 'rotation':(-0.370972, -89.548218, -0.375793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6905.03609375, 3110.66333008, 167.66890625), 'rotation':(0.365238, 90.451714, 0.360612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6904.94673828, 3122.05834961, 167.74169922000002), 'rotation':(0.376712, 90.451866, 0.371792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.85738281, 3133.45336914, 167.81658202999998), 'rotation':(0.382436, 90.451927, 0.377363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6904.76802734, 3144.84863281, 167.89361327999998), 'rotation':(0.393774, 90.45211, 0.388386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.72310547, 3150.54614258, 167.93292968999998), 'rotation':(0.399628, 90.452164, 0.394085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.67867188, 3156.24438477, 167.97269531), 'rotation':(0.402325, 90.451073, 0.396696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.49947266, 3179.03466797, 168.134375), 'rotation':(0.416956, 90.451576, 0.410927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6904.32076172, 3201.82445312, 168.30166015999998), 'rotation':(0.425644, 90.452583, 0.419358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.23189453, 3213.21923828, 168.38648438), 'rotation':(0.430432, 90.452721, 0.423994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.09761719, 3230.31152344, 168.51585938), 'rotation':(0.439789, 90.452881, 0.43308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.05318359, 3236.00878906, 168.55960938), 'rotation':(0.442904, 90.452927, 0.436099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6903.96382812, 3247.40380859, 168.64808594), 'rotation':(0.449146, 90.453026, 0.442148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.78511719, 3270.19335938, 168.82742188), 'rotation':(0.45614, 90.454414, 0.448926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6903.74019531, 3275.89039062, 168.87265625), 'rotation':(0.459726, 90.454506, 0.452404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.65083984, 3287.28564453, 168.96392577999998), 'rotation':(0.463408, 90.450722, 0.45597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6903.60591797, 3292.98265625, 169.01), 'rotation':(0.465156, 90.454018, 0.457645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.5165625, 3304.37744141, 169.1025), 'rotation':(0.46517, 90.454063, 0.457659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.086875, 3359.20824219, 169.55470703), 'rotation':(0.478496, 90.45343, 0.470552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.82613281, 3392.4841406200003, 169.83447266), 'rotation':(0.48605, 90.453873, 0.477855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.78267578, 3398.03003906, 169.88152344), 'rotation':(0.48605, 90.453873, 0.477855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.73873047, 3403.5759375, 169.92859375), 'rotation':(0.486159, 90.449623, 0.477975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.69527344, 3409.12183594, 169.97564452999998), 'rotation':(0.48605, 90.453873, 0.477855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.56490234, 3425.75976562, 170.11707031000003), 'rotation':(0.489977, 90.452217, 0.48165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6902.26021484, 3464.58128906, 170.45023438), 'rotation':(0.492463, 90.45295, 0.48404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.21675781, 3470.12695312, 170.49789062), 'rotation':(0.493495, 90.453026, 0.485051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6902.17330078, 3475.67308594, 170.54566406), 'rotation':(0.495414, 90.453049, 0.486906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.04292969, 3492.31101562, 170.68955078), 'rotation':(0.496425, 90.453117, 0.487891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.99947266, 3497.85695312, 170.73761718999998), 'rotation':(0.496425, 90.453117, 0.487891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.91255859, 3508.94824219, 170.83375), 'rotation':(0.496828, 90.450562, 0.488278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.86910156, 3514.49460938, 170.881875), 'rotation':(0.497258, 90.455032, 0.488688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.7821875, 3525.5861718799997, 170.97822266), 'rotation':(0.498358, 90.450577, 0.48974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.51070312, 3353.72804688, 169.50837891), 'rotation':(-0.478516, -89.54657, -0.486542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6911.46724609, 3359.2736718799997, 169.55470703), 'rotation':(-0.478668, -89.54657, -0.486725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.38033203, 3370.36570312, 169.64738281), 'rotation':(-0.478516, -89.54657, -0.486542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.336875, 3375.91164062, 169.69388672000002), 'rotation':(-0.479523, -89.542999, -0.48761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.29341797, 3381.45777344, 169.74054688), 'rotation':(-0.481384, -89.548462, -0.489502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.20650391, 3392.55003906, 169.83447266), 'rotation':(-0.486176, -89.550354, -0.494476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.11910156, 3403.64160156, 169.92859375), 'rotation':(-0.486023, -89.546143, -0.494324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.0321875, 3414.73339844, 170.02269531000002), 'rotation':(-0.486053, -89.546112, -0.494354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.98873047, 3420.27929688, 170.06982422000002), 'rotation':(-0.486908, -89.547821, -0.495239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.94527344, 3425.82519531, 170.11707031000003), 'rotation':(-0.488525, -89.543518, -0.496918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.72798828, 3453.5549218799997, 170.35488281000002), 'rotation':(-0.49234, -89.543121, -0.500854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.68453125, 3459.10082031, 170.40253906), 'rotation':(-0.49234, -89.543121, -0.500854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.64107422, 3464.64671875, 170.45021484), 'rotation':(-0.492462, -89.547058, -0.500977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.59761719, 3470.19261719, 170.49789062), 'rotation':(-0.492462, -89.547058, -0.500977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.55416016, 3475.73851562, 170.54566406), 'rotation':(-0.493469, -89.546967, -0.502045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.51070312, 3481.2846875, 170.59351562), 'rotation':(-0.493469, -89.546967, -0.502045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.37984375, 3497.92234375, 170.73761718999998), 'rotation':(-0.49646, -89.546875, -0.505096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.16255859, 3525.651875, 170.97822266), 'rotation':(-0.497833, -89.544922, -0.506531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.86421875, 3563.71242188, 171.31023438), 'rotation':(-0.500458, -89.547058, -0.509277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.77730469, 3574.79980469, 171.4071875), 'rotation':(-0.501495, -89.545807, -0.510315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.64693359, 3591.43066406, 171.55332031), 'rotation':(-0.504364, -89.548035, -0.513306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6909.60347656, 3596.97460938, 171.60212891), 'rotation':(-0.504364, -89.548035, -0.513306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.38619141, 3624.69261719, 171.84623047000002), 'rotation':(-0.505188, -89.546631, -0.51416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6909.21236328, 3646.8669531200003, 172.04244140999998), 'rotation':(-0.507507, -89.5466, -0.516571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.99458984, 3674.585, 172.28798827999998), 'rotation':(-0.507507, -89.5466, -0.516571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6908.90767578, 3685.67257812, 172.38679688), 'rotation':(-0.511292, -89.54599, -0.520477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6908.77730469, 3702.3034374999997, 172.53523438), 'rotation':(-0.511292, -89.54599, -0.520477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.69039062, 3713.390625, 172.63417969), 'rotation':(-0.511292, -89.54599, -0.520447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.64693359, 3718.93429688, 172.68371093999997), 'rotation':(-0.511902, -89.548676, -0.521088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.5165625, 3735.56546875, 172.8328125), 'rotation':(-0.514038, -89.548676, -0.523315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6908.42964844, 3746.65257812, 172.93257812), 'rotation':(-0.51593, -89.54541, -0.525269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.38619141, 3752.19601562, 172.9825), 'rotation':(-0.515717, -89.54541, -0.525085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.52730469, 3558.10328125, 171.26179688), 'rotation':(0.50038, 90.452965, 0.491702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.48335938, 3563.64671875, 171.31023438), 'rotation':(0.50038, 90.452965, 0.491702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.43990234, 3569.19042969, 171.35867188), 'rotation':(0.501493, 90.454193, 0.492772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.39644531, 3574.7341406200003, 171.4071875), 'rotation':(0.503364, 90.454231, 0.494594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.35347656, 3580.27808594, 171.45582031), 'rotation':(0.503364, 90.454231, 0.494594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.09273438, 3613.53980469, 171.74853516), 'rotation':(0.504368, 90.45536, 0.495544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.04927734, 3619.08351562, 171.79734375), 'rotation':(0.505181, 90.453354, 0.496345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.961875, 3630.17066406, 171.89519531000002), 'rotation':(0.506684, 90.453377, 0.497783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.70113281, 3663.4323437499997, 172.18978515999999), 'rotation':(0.50751, 90.4534, 0.498581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.57076172, 3680.0634375, 172.33730469), 'rotation':(0.511274, 90.454002, 0.502216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6900.52730469, 3685.6071875, 172.38679688), 'rotation':(0.511376, 90.454018, 0.502321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.39693359, 3702.2378125, 172.53523438), 'rotation':(0.511274, 90.454002, 0.502216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.2665625, 3718.86867188, 172.68371093999997), 'rotation':(0.513104, 90.455666, 0.503987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6900.22310547, 3724.41234375, 172.73332031), 'rotation':(0.514026, 90.455658, 0.504867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.17964844, 3729.9557812499997, 172.78302734000002), 'rotation':(0.514026, 90.455658, 0.504867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.13570312, 3735.49953125, 172.8328125), 'rotation':(0.515133, 90.451363, 0.505941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.04878906, 3746.58664062, 172.93257812), 'rotation':(0.515748, 90.454597, 0.506531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.00533203, 3752.130625, 172.9825), 'rotation':(0.51572, 90.454575, 0.506509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.96236328, 3757.6740625, 173.03240234), 'rotation':(0.515748, 90.454597, 0.506531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.48970703, 3817.91085938, 173.57841797), 'rotation':(0.521451, 90.45562, 0.51202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.35933594, 3834.55445312, 173.73041016), 'rotation':(0.525535, 90.454239, 0.515972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.31587891, 3840.1028125000003, 173.78128906), 'rotation':(0.525515, 90.454224, 0.515938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.27242188, 3845.650625, 173.83216797), 'rotation':(0.525515, 90.454224, 0.515938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.18550781, 3856.74632812, 173.93394531), 'rotation':(0.525535, 90.454239, 0.515972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.14205078, 3862.29445312, 173.98488281000002), 'rotation':(0.526136, 90.454971, 0.51655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.05464844, 3873.39015625, 174.08691406000003), 'rotation':(0.528766, 90.455025, 0.519067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.01119141, 3878.93820312, 174.13806641), 'rotation':(0.528766, 90.455025, 0.519067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.96773438, 3884.48632812, 174.18927734000002), 'rotation':(0.530146, 90.455032, 0.520411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.92427734, 3890.03421875, 174.240625), 'rotation':(0.530938, 90.453087, 0.521185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.83736328, 3901.12984375, 174.34341797000002), 'rotation':(0.530808, 90.453087, 0.521051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6898.57613281, 3934.41796875, 174.65244141), 'rotation':(0.534763, 90.4524, 0.524846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.40230469, 3956.609375, 174.85960938), 'rotation':(0.53477, 90.456047, 0.524846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.0009375, 3801.3303125, 173.42703125), 'rotation':(-0.520905, -89.544312, -0.530426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.91402344, 3812.42625, 173.52792968999998), 'rotation':(-0.520874, -89.549133, -0.530426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.87056641, 3817.974375, 173.57837891), 'rotation':(-0.520874, -89.544312, -0.530426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.82710938, 3823.5221874999997, 173.62894531), 'rotation':(-0.521454, -89.544373, -0.531006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.73970703, 3834.61789062, 173.73039062), 'rotation':(-0.524872, -89.544312, -0.534546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.69771484, 3840.16726562, 173.78126953), 'rotation':(-0.525543, -89.545746, -0.535248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.65279297, 3845.71414062, 173.83214843999997), 'rotation':(-0.525543, -89.545746, -0.535248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.47896484, 3867.90601562, 174.03582031000002), 'rotation':(-0.526154, -89.548462, -0.535889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.43550781, 3873.45382812, 174.08689453), 'rotation':(-0.527557, -89.545013, -0.537354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.3915625, 3879.00195312, 174.13804688), 'rotation':(-0.527557, -89.545013, -0.537354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.34810547, 3884.54984375, 174.18927734000002), 'rotation':(-0.528748, -89.544952, -0.538574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.26119141, 3895.6457812500003, 174.29199218999997), 'rotation':(-0.530151, -89.544922, -0.540039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.21773438, 3901.19359375, 174.34339844), 'rotation':(-0.530945, -89.546906, -0.540863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.17427734, 3906.74148438, 174.39480468999997), 'rotation':(-0.530823, -89.546906, -0.54071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6907.13082031, 3912.28929688, 174.44621094), 'rotation':(-0.530792, -89.546906, -0.54071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.08736328, 3917.83742188, 174.49763672), 'rotation':(-0.530823, -89.542664, -0.54071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.04390625, 3923.3854687499997, 174.54912109), 'rotation':(-0.531799, -89.547485, -0.541748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.95650391, 3934.48140625, 174.65244141), 'rotation':(-0.533844, -89.54361, -0.543854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.86958984, 3945.5771875, 174.75603515999998), 'rotation':(-0.534882, -89.543945, -0.544922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.82613281, 3951.12523438, 174.8078125), 'rotation':(-0.534882, -89.543945, -0.544922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.78267578, 3956.6731250000003, 174.85960938), 'rotation':(-0.53476, -89.547607, -0.54483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.45554688, 3285.25292969, 166.14322266), 'rotation':(-0.340271, -89.480957, -0.34433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.48140625, 3279.57177734, 166.10945312), 'rotation':(-0.340271, -89.480957, -0.34433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.53265625, 3273.88964844, 166.07572266), 'rotation':(-0.339539, -89.480988, -0.343597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.58394531, 3268.20777344, 166.04203125), 'rotation':(-0.339111, -89.481476, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.63523438, 3262.52587891, 166.00839843999998), 'rotation':(-0.339111, -89.481476, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6632.73773438, 3251.16162109, 165.94117188), 'rotation':(-0.33902, -89.481506, -0.343079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6632.78902344, 3245.47949219, 165.90751953), 'rotation':(-0.339142, -89.478363, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6632.8403125, 3239.79761719, 165.87388672), 'rotation':(-0.339142, -89.478363, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.9428125, 3228.43359375, 165.80667968999998), 'rotation':(-0.336456, -89.47879, -0.340424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6633.04585938, 3217.06957031, 165.73992188), 'rotation':(-0.335663, -89.480743, -0.33963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.2509375, 3194.3415625, 165.60693359), 'rotation':(-0.333282, -89.4841, -0.337158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.3021875, 3188.65941406, 165.57390625), 'rotation':(-0.331818, -89.479553, -0.335663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.40476562, 3177.29541016, 165.50828125), 'rotation':(-0.328674, -89.479584, -0.332428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6633.4560156200005, 3171.61376953, 165.47568359000002), 'rotation':(-0.32724, -89.484161, -0.330994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.60984375, 3154.56762695, 165.37876953), 'rotation':(-0.323212, -89.481903, -0.326904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.76414062, 3137.52026367, 165.28292968999997), 'rotation':(-0.316956, -89.481262, -0.320435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.8153906200005, 3131.83837891, 165.25150391), 'rotation':(-0.312561, -89.481323, -0.315979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.91792969, 3120.47412109, 165.18921875), 'rotation':(-0.30835, -89.478394, -0.311676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.96921875, 3114.79223633, 165.15853515999999), 'rotation':(-0.30835, -89.478394, -0.311676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6634.138125, 3104.90405273, 165.10548828), 'rotation':(-0.306274, -89.479248, -0.30954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.586875, 3103.34912109, 165.09757812), 'rotation':(0.306252, 90.517075, 0.302993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6625.48628906, 3126.07495117, 165.22019531), 'rotation':(0.316921, 90.518723, 0.313429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.435, 3131.75732422, 165.25146484), 'rotation':(0.316921, 90.518723, 0.313429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.3325, 3143.12133789, 165.31472656000003), 'rotation':(0.323225, 90.518082, 0.319593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6625.22992188, 3154.48608398, 165.37873047000002), 'rotation':(0.324072, 90.52037, 0.320413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.075625, 3171.53222656, 165.47564452999998), 'rotation':(0.328662, 90.520447, 0.324913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.92183594, 3188.57789062, 165.57386719), 'rotation':(0.333252, 90.5159, 0.329402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.71675781, 3211.30640625, 165.70662109), 'rotation':(0.335663, 90.519249, 0.331736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.35738281, 3251.07984375, 165.94111328), 'rotation':(0.339133, 90.518494, 0.335125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.30609375, 3256.76195312, 165.97474609), 'rotation':(0.339133, 90.518494, 0.335125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.25484375, 3262.44384766, 166.00837891), 'rotation':(0.339133, 90.518494, 0.335125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6624.20359375, 3268.12597656, 166.04201172), 'rotation':(0.339536, 90.51899, 0.335528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6623.9325781200005, 3290.85277344, 166.17699219), 'rotation':(0.340731, 90.518173, 0.336707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6623.84078125, 3296.53394531, 166.21076172000002), 'rotation':(0.340724, 90.521248, 0.336704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6623.7153125, 3307.8984375, 166.27837891), 'rotation':(0.340826, 90.518166, 0.336804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6623.50191406, 3345.849375, 166.50373047000002), 'rotation':(0.339795, 90.518005, 0.335786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6623.20210938, 3379.03222656, 166.7003125), 'rotation':(0.337807, 90.518906, 0.333832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.95257812, 3406.68457031, 166.86339843999997), 'rotation':(0.337787, 90.518898, 0.33382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.9028125, 3412.21507812, 166.89601562), 'rotation':(0.337138, 90.519547, 0.333183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.7528906200005, 3428.80640625, 166.99353516), 'rotation':(0.334877, 90.521225, 0.330988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.35347656, 3473.0503125, 167.25220703), 'rotation':(0.334208, 90.522903, 0.330337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.25335938, 3484.11085938, 167.31671875), 'rotation':(0.333948, 90.515106, 0.330077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6622.10347656, 3500.70238281, 167.41341797), 'rotation':(0.334078, 90.519211, 0.330206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6622.00335938, 3511.76320312, 167.47794922), 'rotation':(0.33442, 90.519234, 0.330515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.95359375, 3517.29394531, 167.51023438), 'rotation':(0.334816, 90.519234, 0.330919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.23382812, 3528.43554688, 167.57492188), 'rotation':(-0.334808, -89.480743, -0.338745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.33394531, 3517.37453125, 167.51027344), 'rotation':(-0.334412, -89.480743, -0.338318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.43355469, 3506.31371094, 167.44570312), 'rotation':(-0.334076, -89.480774, -0.338013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6630.48382812, 3500.78296875, 167.41345703), 'rotation':(-0.333954, -89.479919, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.58394531, 3489.72242188, 167.34896484), 'rotation':(-0.333923, -89.484894, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6630.68355469, 3478.66113281, 167.28449218999998), 'rotation':(-0.334229, -89.477081, -0.338135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6630.78316406, 3467.60058594, 167.21994141), 'rotation':(-0.334991, -89.481934, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.8334375, 3462.06984375, 167.18759766), 'rotation':(-0.334991, -89.47876, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.93304688, 3451.00902344, 167.12294922), 'rotation':(-0.334991, -89.481934, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.98335938, 3445.47851562, 167.09058593999998), 'rotation':(-0.334991, -89.481934, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.4325781200005, 3395.70410156, 166.79822266), 'rotation':(-0.337891, -89.481079, -0.341919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.48238281, 3390.17382812, 166.76560547), 'rotation':(-0.337799, -89.481079, -0.341797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.5825, 3379.1128125, 166.70035156000003), 'rotation':(-0.338257, -89.482513, -0.342285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.68210938, 3368.05199219, 166.63494140999998), 'rotation':(-0.339813, -89.481964, -0.343842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.7821875, 3356.99097656, 166.56935547), 'rotation':(-0.339813, -89.477722, -0.343842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6621.50972656, 3566.47898438, 167.79816406), 'rotation':(0.336318, 90.519974, 0.332389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.3559375, 3583.53953125, 167.89867188), 'rotation':(0.33821, 90.519051, 0.334235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6621.30414062, 3589.2263281200003, 167.93222656), 'rotation':(0.338047, 90.519028, 0.33407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.20113281, 3600.60007812, 167.99939453), 'rotation':(0.339262, 90.520218, 0.335278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.14984375, 3606.28664062, 168.03306641), 'rotation':(0.341366, 90.517426, 0.337318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6621.09859375, 3611.97363281, 168.06683593999998), 'rotation':(0.341366, 90.517426, 0.337318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.04734375, 3617.66089844, 168.10072266), 'rotation':(0.343565, 90.520271, 0.33946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.94476562, 3629.03441406, 168.16886719), 'rotation':(0.345744, 90.520294, 0.341594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6620.84226562, 3640.40820312, 168.2375), 'rotation':(0.346837, 90.520317, 0.342664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.79097656, 3646.09472656, 168.27193359), 'rotation':(0.346844, 90.517303, 0.342668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.63667969, 3663.1553125, 168.37529297), 'rotation':(0.350245, 90.517883, 0.345973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.48289062, 3680.21632812, 168.48035156000003), 'rotation':(0.35603, 90.521004, 0.351618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.43109375, 3685.90304688, 168.51568359), 'rotation':(0.356106, 90.518105, 0.351694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.32859375, 3697.276875, 168.58636718999998), 'rotation':(0.357881, 90.520317, 0.353417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.27730469, 3702.96390625, 168.62185547), 'rotation':(0.357881, 90.520317, 0.353417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.1747656200005, 3714.33765625, 168.69328125), 'rotation':(0.36519, 90.520393, 0.360566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.07171875, 3725.7109375, 168.76556641), 'rotation':(0.368905, 90.517555, 0.364183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.81492188, 3754.14601562, 168.94925781), 'rotation':(0.377484, 90.520164, 0.372539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.2978125, 3742.85304688, 168.87550781000002), 'rotation':(-0.370697, -89.484009, -0.375519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.34957031, 3737.16554688, 168.83869141), 'rotation':(-0.368896, -89.479553, -0.373688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.50335938, 3720.105, 168.72933593999997), 'rotation':(-0.361481, -89.479675, -0.366058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.55464844, 3714.41820312, 168.69332031000002), 'rotation':(-0.361481, -89.479675, -0.366058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.60640625, 3708.7317187500003, 168.65742188000002), 'rotation':(-0.35788, -89.482574, -0.362366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.70894531, 3697.35742188, 168.58638672), 'rotation':(-0.35611, -89.479004, -0.360565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.76023438, 3691.6706249999997, 168.55105468999997), 'rotation':(-0.356018, -89.481873, -0.360443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.96578125, 3668.9231250000003, 168.41011719), 'rotation':(-0.35022, -89.482117, -0.354553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.01703125, 3663.23609375, 168.3753125), 'rotation':(-0.3479, -89.476837, -0.352142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.06832031, 3657.5490625, 168.34080078), 'rotation':(-0.346832, -89.482697, -0.351074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.37640625, 3623.42796875, 168.13480468999998), 'rotation':(-0.34137, -89.479767, -0.345459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6629.42769531, 3617.74121094, 168.10076172), 'rotation':(-0.34137, -89.479767, -0.345459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.53023438, 3606.3671875, 168.03310547), 'rotation':(-0.339264, -89.479797, -0.343292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.63328125, 3594.99339844, 167.96583984), 'rotation':(-0.338043, -89.480988, -0.342041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6629.73578125, 3583.61988281, 167.89869141), 'rotation':(-0.338196, -89.480957, -0.342224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.78757812, 3577.93285156, 167.86513672), 'rotation':(-0.337463, -89.480042, -0.341461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.94136719, 3560.87257812, 167.76484375), 'rotation':(-0.335602, -89.481323, -0.339539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.35007812, 3797.78664062, 169.24115234), 'rotation':(0.388651, 90.519432, 0.383418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.37105469, 3803.316875, 169.27875), 'rotation':(0.391192, 90.521172, 0.385885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.2709375, 3814.38304688, 169.35476562), 'rotation':(0.400577, 90.517525, 0.395012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.22117188, 3819.91625, 169.39332031), 'rotation':(0.400577, 90.517525, 0.395012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.12105469, 3830.98265625, 169.47128906), 'rotation':(0.407619, 90.520439, 0.40184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.0209375, 3842.0490625, 169.55003906000002), 'rotation':(0.409162, 90.522972, 0.403357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.97117188, 3847.58226562, 169.58953125), 'rotation':(0.412093, 90.51812, 0.406193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6618.92132812, 3853.11546875, 169.62929688), 'rotation':(0.414975, 90.518112, 0.408998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6618.77144531, 3869.71484375, 169.75023438), 'rotation':(0.423711, 90.523155, 0.417483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.7216406200005, 3875.24757812, 169.79107422), 'rotation':(0.426798, 90.518326, 0.420465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.67183594, 3880.78125, 169.83220702999998), 'rotation':(0.429694, 90.523247, 0.423276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.6215625, 3886.31421875, 169.87363281), 'rotation':(0.431203, 90.521439, 0.424755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.57171875, 3891.84742188, 169.91521484), 'rotation':(0.432713, 90.517624, 0.42621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.32171875, 3919.5129687500003, 170.12716797000002), 'rotation':(0.448771, 90.517876, 0.441792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.22210938, 3930.5793750000003, 170.21408203), 'rotation':(0.455191, 90.51799, 0.448005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.17183594, 3936.11234375, 170.25798827999998), 'rotation':(0.456735, 90.522446, 0.449493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.07222656, 3947.17875, 170.34625), 'rotation':(0.459726, 90.519302, 0.4524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6617.97210938, 3958.24515625, 170.4353125), 'rotation':(0.465593, 90.522285, 0.458075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6626.40230469, 3952.7946875, 170.39072266), 'rotation':(-0.459747, -89.477783, -0.467163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.45257812, 3947.26171875, 170.34630859), 'rotation':(-0.456726, -89.477539, -0.46405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.5521875, 3936.19507812, 170.25804688), 'rotation':(-0.45517, -89.482025, -0.462433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.75191406, 3914.0625, 170.08421875), 'rotation':(-0.442383, -89.477234, -0.449249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.8021875, 3908.5299999999997, 170.04154297000002), 'rotation':(-0.439117, -89.482239, -0.445892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.85203125, 3902.9965625, 169.99914062), 'rotation':(-0.435974, -89.477325, -0.442657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.90230469, 3897.46390625, 169.95707031), 'rotation':(-0.432709, -89.482361, -0.43927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6626.95210938, 3891.92992188, 169.91527344), 'rotation':(-0.431183, -89.478577, -0.437714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.0521875, 3880.86351562, 169.83226562), 'rotation':(-0.426788, -89.481659, -0.433197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.10203125, 3875.3303125, 169.79113281000002), 'rotation':(-0.423706, -89.476837, -0.430023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.15179688, 3869.79757812, 169.75029297), 'rotation':(-0.420959, -89.48175, -0.427185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.20164062, 3864.26414062, 169.70970703), 'rotation':(-0.417908, -89.476898, -0.424042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.25191406, 3858.73117188, 169.66939452999998), 'rotation':(-0.414978, -89.481873, -0.421021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.30171875, 3853.19828125, 169.62935547), 'rotation':(-0.412079, -89.481903, -0.41803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.35152344, 3847.66476562, 169.58960938), 'rotation':(-0.40918, -89.47702, -0.415039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.4013281200005, 3842.13132812, 169.55009766), 'rotation':(-0.407776, -89.479553, -0.413605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.45164062, 3836.598125, 169.51070312), 'rotation':(-0.407654, -89.479553, -0.413483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.55125, 3825.53171875, 169.4321875), 'rotation':(-0.400604, -89.478699, -0.406219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.60152344, 3819.99851562, 169.39335938), 'rotation':(-0.395905, -89.47876, -0.401398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.70113281, 3808.93210938, 169.31658202999998), 'rotation':(-0.391205, -89.478851, -0.396576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.7865625, 3800.7925, 169.26103516), 'rotation':(-0.388672, -89.48053, -0.393982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.99019531, 3994.79984375, 170.73710938), 'rotation':(-0.480164, -89.478271, -0.488281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6617.66402344, 3996.0525, 170.74828125), 'rotation':(0.484015, 90.51915, 0.475894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.76023438, 3311.86890625, 162.62011719), 'rotation':(-0.303131, -89.872101, -0.306366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.78460938, 3300.52783203, 162.5602832), 'rotation':(-0.304901, -89.87323, -0.308136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.79734375, 3294.8571875, 162.53011719), 'rotation':(-0.305084, -89.87323, -0.308319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.80953125, 3289.18652344, 162.49994141), 'rotation':(-0.305786, -89.872925, -0.309052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.85933594, 3266.50414062, 162.37770508), 'rotation':(-0.312988, -89.872833, -0.316437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.89695312, 3249.4921875, 162.28415039), 'rotation':(-0.318329, -89.872803, -0.321899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.90960938, 3243.82177734, 162.25262695), 'rotation':(-0.319153, -89.871704, -0.322754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.92183594, 3238.15087891, 162.22100586), 'rotation':(-0.319153, -89.871704, -0.322754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.9340625, 3232.48095703, 162.1894043), 'rotation':(-0.320496, -89.874817, -0.324066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.94625, 3226.80980469, 162.15769531), 'rotation':(-0.322662, -89.870667, -0.326324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.95894531, 3221.13941406, 162.12575195), 'rotation':(-0.325104, -89.874756, -0.328827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.98382812, 3209.79833984, 162.06129883), 'rotation':(-0.327545, -89.870605, -0.331299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6364.00875, 3198.45703125, 161.99631836), 'rotation':(-0.328583, -89.871979, -0.332367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.03367188, 3187.11572266, 161.93121094), 'rotation':(-0.329773, -89.873596, -0.333588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.05855469, 3175.77441406, 161.86574219), 'rotation':(-0.333954, -89.870361, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.07078125, 3170.10400391, 161.8328125), 'rotation':(-0.333954, -89.870361, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6364.0834374999995, 3164.43335938, 161.79975586), 'rotation':(-0.33606, -89.873535, -0.339996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.09617188, 3158.76269531, 161.76654297), 'rotation':(-0.337006, -89.871582, -0.341003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6364.17039062, 3124.73876953, 161.56638672), 'rotation':(-0.338104, -89.874237, -0.342102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.20015625, 3119.06982422, 161.53295898), 'rotation':(-0.338104, -89.874237, -0.342102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.33003906, 3107.72973633, 161.46601562), 'rotation':(-0.338226, -89.874237, -0.342224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.7045312499995, 3107.70458984, 161.46598633), 'rotation':(0.33821, 90.129745, 0.334239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.74460938, 3113.37475586, 161.49945312), 'rotation':(0.338094, 90.125763, 0.334116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.78460938, 3119.04516602, 161.53292969), 'rotation':(0.337685, 90.127274, 0.333714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.7153125, 3158.73876953, 161.76649414), 'rotation':(0.336032, 90.12645, 0.332118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.70257812, 3164.40941406, 161.79972656), 'rotation':(0.333948, 90.126434, 0.33008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.6903906200005, 3170.08007812, 161.83276367), 'rotation':(0.33177, 90.129593, 0.32794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.665, 3181.42138672, 161.89854492), 'rotation':(0.329755, 90.126381, 0.325982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.6528125, 3187.09179688, 161.93117188), 'rotation':(0.328594, 90.128029, 0.324839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.64007812, 3192.76246094, 161.96375), 'rotation':(0.328594, 90.128029, 0.324839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.61570312, 3204.10375, 162.02880859), 'rotation':(0.327542, 90.125282, 0.323827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.60347656, 3209.77441406, 162.06125977), 'rotation':(0.325103, 90.129356, 0.321438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.59078125, 3215.44507812, 162.09359375), 'rotation':(0.325103, 90.129356, 0.321438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.56585938, 3226.78613281, 162.15766602), 'rotation':(0.320479, 90.125198, 0.316915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.55320312, 3232.45679688, 162.189375), 'rotation':(0.319182, 90.128288, 0.315623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.54097656, 3238.1271875, 162.22097656), 'rotation':(0.319182, 90.128288, 0.315623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.5287499999995, 3243.79808594, 162.25259766), 'rotation':(0.318335, 90.127213, 0.314806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.51609375, 3249.46851562, 162.28412109), 'rotation':(0.3166, 90.127182, 0.313106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.50386719, 3255.13941406, 162.31547852), 'rotation':(0.314728, 90.127174, 0.311278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.4911718799995, 3260.81005859, 162.34666016), 'rotation':(0.312993, 90.127151, 0.309569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.45359375, 3277.82203125, 162.43913086), 'rotation':(0.307659, 90.12709, 0.304364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.44136719, 3283.49292969, 162.46960938), 'rotation':(0.305774, 90.127083, 0.302524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.41648438, 3294.83375, 162.53008789), 'rotation':(0.304906, 90.126778, 0.301679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.2958593799995, 3349.94214844, 162.81603515999998), 'rotation':(0.287674, 90.126221, 0.284798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.28316406, 3355.6384375, 162.84481445), 'rotation':(0.287674, 90.126221, 0.284798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.27046875, 3361.33496094, 162.87341797), 'rotation':(0.28404, 90.129082, 0.281239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.24554688, 3372.72777344, 162.92988281), 'rotation':(0.280325, 90.126167, 0.277598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.23289062, 3378.42429688, 162.9577832), 'rotation':(0.27833, 90.12606, 0.27564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.17039062, 3406.9064843799997, 163.09533203), 'rotation':(0.273153, 90.125771, 0.270557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.12054688, 3429.69238281, 163.20280273), 'rotation':(0.267183, 90.125717, 0.264695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.09566406, 3441.08546875, 163.25583008), 'rotation':(0.266357, 90.12574, 0.263887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.07078125, 3452.47851562, 163.30868164), 'rotation':(0.264697, 90.127686, 0.262272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.03316406, 3469.56789062, 163.38685547), 'rotation':(0.25982, 90.127251, 0.257477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.02046875, 3475.26441406, 163.41268555), 'rotation':(0.259718, 90.127258, 0.257366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.99554688, 3486.65773438, 163.46432617), 'rotation':(0.258775, 90.12365, 0.256436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.9833593799995, 3492.35398438, 163.49006836), 'rotation':(0.258004, 90.128548, 0.255691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.95796875, 3503.74707031, 163.54136719), 'rotation':(0.256795, 90.123642, 0.254502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.94578125, 3509.44382812, 163.56689453), 'rotation':(0.256009, 90.128525, 0.253732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.93304688, 3515.140625, 163.59236328), 'rotation':(0.255394, 90.128532, 0.253145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.3139062499995, 3515.16257812, 163.59237305), 'rotation':(-0.256012, -89.87146, -0.258331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.3388281200005, 3503.76929688, 163.54138672), 'rotation':(-0.257385, -89.87146, -0.259705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.35152344, 3498.07273438, 163.51578125), 'rotation':(-0.257996, -89.871429, -0.260345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.41402344, 3469.59007812, 163.386875), 'rotation':(-0.261475, -89.875549, -0.263855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.42671875, 3463.89332031, 163.36097656), 'rotation':(-0.261475, -89.875549, -0.263855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.47652344, 3441.10765625, 163.25583984000002), 'rotation':(-0.266235, -89.870697, -0.268738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.5014062499995, 3429.71460938, 163.20282226999998), 'rotation':(-0.268677, -89.874268, -0.27121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.5263281200005, 3418.32152344, 163.14938476999998), 'rotation':(-0.271637, -89.869446, -0.274261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.53902344, 3412.6252343799997, 163.12244141), 'rotation':(-0.273163, -89.874237, -0.275787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.5639062499995, 3401.23195312, 163.06811523), 'rotation':(-0.274658, -89.874207, -0.277313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.57664062, 3395.53589844, 163.04074219), 'rotation':(-0.276154, -89.874207, -0.278809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.60152344, 3384.1428125, 162.98556641), 'rotation':(-0.27832, -89.873901, -0.281036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.6513281200005, 3361.3571875, 162.87344726999999), 'rotation':(-0.287689, -89.87085, -0.290558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.67671875, 3349.964375, 162.81605469), 'rotation':(-0.291382, -89.873718, -0.294342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.81246094, 3570.12207031, 163.83738281), 'rotation':(0.25689, 90.129089, 0.254609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.80023438, 3575.8025, 163.86285156000002), 'rotation':(0.25689, 90.129089, 0.254609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.77535156, 3587.16257812, 163.91376953), 'rotation':(0.25689, 90.129089, 0.254609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.71285156, 3615.56347656, 164.04234375), 'rotation':(0.261419, 90.126038, 0.259041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.67574219, 3632.60449219, 164.12025391), 'rotation':(0.263372, 90.127083, 0.260958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.6259375, 3655.32519531, 164.22626953), 'rotation':(0.274649, 90.12719, 0.272026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.61375, 3661.0051562500003, 164.25335938), 'rotation':(0.274649, 90.12719, 0.272026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.60101562, 3666.68554688, 164.28056641), 'rotation':(0.27652, 90.125717, 0.27386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.55125, 3689.40648438, 164.39033203), 'rotation':(0.280318, 90.126915, 0.2776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.41453125, 3751.8893749999997, 164.711875), 'rotation':(0.313588, 90.128212, 0.310171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6362.80710938, 3746.2321875, 164.68130859000001), 'rotation':(-0.306793, -89.871826, -0.310089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.81976562, 3740.55226562, 164.65103516), 'rotation':(-0.30014, -89.871887, -0.303314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.8325, 3734.87179688, 164.62111328), 'rotation':(-0.296997, -89.871948, -0.300079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.8446875, 3729.19164062, 164.59152343999997), 'rotation':(-0.293488, -89.871979, -0.296539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.85738281, 3723.51148438, 164.56228516), 'rotation':(-0.291779, -89.875397, -0.294769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.88226562, 3712.150625, 164.50435547), 'rotation':(-0.29187, -89.872253, -0.294861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6362.9071875, 3700.79, 164.44666016), 'rotation':(-0.287964, -89.872986, -0.290863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.91988281, 3695.109375, 164.41814452999998), 'rotation':(-0.280304, -89.873047, -0.283081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.94476562, 3683.7490625, 164.3628125), 'rotation':(-0.27652, -89.871429, -0.279205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.99460938, 3661.0278125, 164.25335938), 'rotation':(-0.270905, -89.872833, -0.273468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.01898438, 3649.66773438, 164.19945312), 'rotation':(-0.26712, -89.872864, -0.269623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.03171875, 3643.98707031, 164.17285156000003), 'rotation':(-0.26712, -89.872864, -0.269623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.04390625, 3638.30710938, 164.14638672), 'rotation':(-0.263397, -89.872894, -0.265808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.06882812, 3626.94605469, 164.09419922), 'rotation':(-0.261414, -89.873932, -0.263794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.08148438, 3621.26609375, 164.06828125), 'rotation':(-0.261414, -89.873932, -0.263794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.09371094, 3615.5859375, 164.04238281000002), 'rotation':(-0.261566, -89.873962, -0.263977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.14398438, 3592.86523438, 163.93925781000002), 'rotation':(-0.256897, -89.870911, -0.259216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.15621094, 3587.18507812, 163.91380859), 'rotation':(-0.256897, -89.874878, -0.259216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.16890625, 3581.50488281, 163.88833984000001), 'rotation':(-0.256897, -89.874878, -0.259216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.1810937499995, 3575.8246875, 163.86287109), 'rotation':(-0.256775, -89.870911, -0.259064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.2060156200005, 3564.464375, 163.81193359), 'rotation':(-0.256531, -89.874481, -0.25885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.3060937499995, 3801.18265625, 164.99027343999998), 'rotation':(0.341591, 90.126114, 0.33754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.29390625, 3806.70851562, 165.02320312), 'rotation':(0.345088, 90.128235, 0.340958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.26949219, 3817.75976562, 165.08978516), 'rotation':(0.34931, 90.129044, 0.345075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.25726562, 3823.2864062500003, 165.12335938), 'rotation':(0.34931, 90.129044, 0.345075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.22117188, 3839.86421875, 165.22625), 'rotation':(0.365722, 90.129265, 0.361086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.1849999999995, 3856.44164062, 165.33332031), 'rotation':(0.378065, 90.130516, 0.373101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.160625, 3867.49414062, 165.40628906), 'rotation':(0.382327, 90.126305, 0.377255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.14839844, 3873.01976562, 165.44318359000002), 'rotation':(0.391083, 90.129379, 0.385768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.13617188, 3878.5456249999997, 165.48044922), 'rotation':(0.391083, 90.129379, 0.385768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.1239843799995, 3884.07125, 165.51816406), 'rotation':(0.399648, 90.126556, 0.394099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.10007812, 3895.12328125, 165.59511719), 'rotation':(0.408281, 90.129608, 0.402512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.08785156, 3900.64890625, 165.63451172), 'rotation':(0.412646, 90.130119, 0.406732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.0756249999995, 3906.1753125, 165.67400390999998), 'rotation':(0.412646, 90.130119, 0.406732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.0634375, 3911.7009375, 165.71382812), 'rotation':(0.412625, 90.12558, 0.406723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.03953125, 3922.75320312, 165.79396484), 'rotation':(0.427898, 90.127899, 0.421542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.02730469, 3928.2790625, 165.83482422), 'rotation':(0.427898, 90.127899, 0.421542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6353.9911718799995, 3944.85640625, 165.96128906), 'rotation':(0.44834, 90.131569, 0.441355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6353.97898438, 3950.38257812, 166.00457031000002), 'rotation':(0.453361, 90.129395, 0.44624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6353.96675781, 3955.90820312, 166.04830077999998), 'rotation':(0.453443, 90.126083, 0.446321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6362.37203125, 3944.88109375, 165.96132812), 'rotation':(-0.43811, -89.871948, -0.444855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.38375, 3939.35523438, 165.91849609000002), 'rotation':(-0.43811, -89.871948, -0.444855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.3959374999995, 3933.82960938, 165.87623047), 'rotation':(-0.427887, -89.872101, -0.434326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.40816406, 3928.3034374999997, 165.83486327999998), 'rotation':(-0.417786, -89.872253, -0.42392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.46871094, 3900.6731250000003, 165.63453125), 'rotation':(-0.408295, -89.873322, -0.414154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.493125, 3889.6215625, 165.5565625), 'rotation':(-0.391083, -89.870605, -0.396454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.5170312499995, 3878.56984375, 165.48050781), 'rotation':(-0.382324, -89.873688, -0.387451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.56585938, 3856.46507812, 165.33335938), 'rotation':(-0.373932, -89.873596, -0.378845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.58980469, 3845.41359375, 165.2615625), 'rotation':(-0.365753, -89.870728, -0.370422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.61421875, 3834.36132812, 165.19158202999998), 'rotation':(-0.357513, -89.873779, -0.362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.6259375, 3828.83570312, 165.15708984), 'rotation':(-0.349335, -89.870911, -0.353607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.6381249999995, 3823.31007812, 165.12339844), 'rotation':(-0.345245, -89.871765, -0.349426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.66257812, 3812.25757812, 165.05654297), 'rotation':(-0.345093, -89.871765, -0.349274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.6747656200005, 3806.73140625, 165.02324219), 'rotation':(-0.341614, -89.873871, -0.345703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.69867188, 3795.67992188, 164.95765625), 'rotation':(-0.334442, -89.870789, -0.338348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6602.46089844, 3540.56542969, 167.34994140999999), 'rotation':(-0.793182, 179.43364, -0.815399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6591.14203125, 3540.6796875, 167.19269531), 'rotation':(-0.800781, 179.433746, -0.823425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6557.1840625, 3541.02171875, 166.71486328), 'rotation':(-0.817993, 179.435104, -0.841614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6540.20554688, 3541.19289062, 166.47064453), 'rotation':(-0.828369, 179.43602, -0.8526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6534.54539062, 3541.2497656200003, 166.38876953), 'rotation':(-0.828369, 179.43602, -0.8526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6517.566875, 3541.42089844, 166.14296875), 'rotation':(-0.838409, 179.434891, -0.863251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6511.90765625, 3541.47777344, 166.06021484000001), 'rotation':(-0.845245, 179.435104, -0.870483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6506.2475, 3541.5346875, 165.97677734), 'rotation':(-0.852112, 179.43779, -0.877747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6500.58835938, 3541.59179688, 165.89267578), 'rotation':(-0.855408, 179.434219, -0.881226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6494.92964844, 3541.6486718799997, 165.80820312), 'rotation':(-0.855316, 179.436798, -0.881165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6489.26949219, 3541.70582031, 165.72367188), 'rotation':(-0.855499, 179.43428, -0.881317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6483.60984375, 3541.76269531, 165.63912109), 'rotation':(-0.855316, 179.436798, -0.881165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6455.31246094, 3542.04785156, 165.21384766), 'rotation':(-0.872223, 179.435654, -0.899078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6449.65230469, 3542.105, 165.1278125), 'rotation':(-0.872223, 179.435654, -0.899078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6410.03609375, 3542.50390625, 164.52253906), 'rotation':(-0.881561, 179.436539, -0.909027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6398.71675781, 3542.61792969, 164.34796875), 'rotation':(-0.883911, 179.43692, -0.91153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6387.3974218799995, 3542.73195312, 164.17330077999998), 'rotation':(-0.883881, 179.436935, -0.911469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6381.73824219, 3542.7888281200003, 164.08595703), 'rotation':(-0.883881, 179.43544, -0.911499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6376.07859375, 3542.8459375, 163.99863281), 'rotation':(-0.883881, 179.43544, -0.911499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6376.11960938, 3551.2265625, 163.99794922), 'rotation':(0.883881, -0.564545, 0.85691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6381.77925781, 3551.16945312, 164.08529297), 'rotation':(0.883881, -0.564545, 0.85691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6387.4389062499995, 3551.11253906, 164.17261718999998), 'rotation':(0.883929, -0.56308, 0.856961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6398.75777344, 3550.99851562, 164.34730469), 'rotation':(0.883867, -0.563049, 0.856917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6427.0560937499995, 3550.71335938, 164.78164062), 'rotation':(0.874667, -0.564697, 0.848266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6449.6942968799995, 3550.48535156, 165.12714843999998), 'rotation':(0.8674, -0.562714, 0.841429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6455.35398438, 3550.42847656, 165.21320312), 'rotation':(0.8674, -0.562714, 0.841429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6472.3325, 3550.2575781200003, 165.46921875), 'rotation':(0.85781, -0.564789, 0.832407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6483.65230469, 3550.14355469, 165.63851562), 'rotation':(0.855474, -0.563202, 0.830203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6511.95015625, 3549.86449219, 166.05958984), 'rotation':(0.838426, -0.565094, 0.814142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6517.60933594, 3549.81128906, 166.14234375), 'rotation':(0.831739, -0.565308, 0.807844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6528.92867188, 3549.6560156200003, 166.30632812), 'rotation':(0.828386, -0.565796, 0.80468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6534.58835938, 3549.59742188, 166.38818359), 'rotation':(0.828379, -0.563995, 0.804685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6545.90765625, 3549.48339844, 166.55179688), 'rotation':(0.824902, -0.566345, 0.801417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6562.8871875, 3549.31203125, 166.79486328), 'rotation':(0.811194, -0.565033, 0.788456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6585.5263281200005, 3549.08421875, 167.11300781000003), 'rotation':(0.800799, -0.566254, 0.778634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6596.84617188, 3548.97023438, 167.27099609), 'rotation':(0.793258, -0.566406, 0.771516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6602.50582031, 3548.91332031, 167.34941406000002), 'rotation':(0.788375, -0.566528, 0.766914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6608.16546875, 3548.85621094, 167.42734375), 'rotation':(0.783184, -0.56662, 0.761974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6889.18501953, 3537.6753125, 170.92267578), 'rotation':(-0.672485, 179.426941, -0.688385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6883.53121094, 3537.73289062, 170.85628906000002), 'rotation':(-0.672577, 179.425034, -0.688538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6877.87837891, 3537.79027344, 170.78994140999998), 'rotation':(-0.672577, 179.425034, -0.688538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6872.22457031, 3537.84765625, 170.72355469), 'rotation':(-0.672485, 179.425018, -0.688385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6855.26460938, 3538.01953125, 170.52429688), 'rotation':(-0.674377, 179.429916, -0.690399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6843.95748047, 3538.13355469, 170.39115234000002), 'rotation':(-0.674561, 179.429886, -0.690582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6832.65083984, 3538.24730469, 170.25798827999998), 'rotation':(-0.674713, 179.429886, -0.690735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6826.99751953, 3538.30421875, 170.19142578), 'rotation':(-0.6763, 179.430923, -0.692413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6821.34419922, 3538.36109375, 170.12470703), 'rotation':(-0.6763, 179.430923, -0.692413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6804.38472656, 3538.53199219, 169.92345702999998), 'rotation':(-0.686584, 179.431168, -0.703186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6798.73140625, 3538.58886719, 169.85591797), 'rotation':(-0.686584, 179.431168, -0.703186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6787.42476562, 3538.7028906200003, 169.72025391), 'rotation':(-0.688354, 179.429932, -0.705048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6781.77144531, 3538.75976562, 169.65230469), 'rotation':(-0.689758, 179.432251, -0.706512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.46578125, 3538.87351562, 169.5159375), 'rotation':(-0.695312, 179.432388, -0.712341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6753.50630859, 3539.04445312, 169.30923828), 'rotation':(-0.703857, 179.432602, -0.721313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6747.8525, 3539.1013281200003, 169.23974609), 'rotation':(-0.706787, 179.432632, -0.724396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6730.89400391, 3539.27195312, 169.02974609), 'rotation':(-0.713654, 179.431686, -0.731598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6725.24068359, 3539.32886719, 168.95931640999999), 'rotation':(-0.718872, 179.431824, -0.737061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6713.93404297, 3539.44289062, 168.81763672), 'rotation':(-0.724243, 179.431976, -0.742706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6708.28121094, 3539.4997656200003, 168.74619141), 'rotation':(-0.729584, 179.432098, -0.748322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6680.0165625, 3539.78441406, 168.38494140999998), 'rotation':(-0.737, 179.432404, -0.756165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6668.71140625, 3539.8982031200003, 168.23912109), 'rotation':(-0.74884, 179.431046, -0.768616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6646.15035156, 3548.50660156, 167.94046875), 'rotation':(0.76464, -0.566559, 0.744425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6651.80367188, 3548.4496875, 168.0159375), 'rotation':(0.756723, -0.566803, 0.736931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6663.10933594, 3548.3359375, 168.16503906000003), 'rotation':(0.748855, -0.566956, 0.729464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6674.415, 3548.2221875, 168.31179688), 'rotation':(0.736984, -0.567596, 0.718211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6685.72115234, 3548.10816406, 168.45726562), 'rotation':(0.734553, -0.568634, 0.715893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6691.37447266, 3548.05125, 168.52982422000002), 'rotation':(0.729573, -0.567902, 0.711176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6697.02730469, 3547.99414062, 168.60214843999998), 'rotation':(0.729573, -0.567902, 0.711176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6702.68013672, 3547.9372656200003, 168.67414062), 'rotation':(0.724232, -0.566498, 0.706085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6713.98628906, 3547.82347656, 168.81724609), 'rotation':(0.71885, -0.568176, 0.70098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6725.29292969, 3547.70972656, 168.95892578), 'rotation':(0.713604, -0.568268, 0.695989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6736.59957031, 3547.59570312, 169.09957031000002), 'rotation':(0.709418, -0.567261, 0.692011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6742.25240234, 3547.5388281200003, 169.16960938), 'rotation':(0.706774, -0.569916, 0.689507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6747.90621094, 3547.48167969, 169.23935547000002), 'rotation':(0.703865, -0.567383, 0.686736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6764.86617188, 3547.31101562, 169.44695312), 'rotation':(0.6953, -0.567596, 0.678583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.51851562, 3547.25414062, 169.51554688), 'rotation':(0.69252, -0.567719, 0.675928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6810.09175781, 3546.85863281, 169.99042968999998), 'rotation':(0.679795, -0.56897, 0.663808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6821.39839844, 3546.75148438, 170.12433593999998), 'rotation':(0.674693, -0.567932, 0.658952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6855.31880859, 3546.3669531200003, 170.52392577999998), 'rotation':(0.673539, -0.570099, 0.65785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6866.62496094, 3546.25269531, 170.65679688), 'rotation':(0.672466, -0.573029, 0.656822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6877.93208984, 3546.13769531, 170.78957031000002), 'rotation':(0.672473, -0.574982, 0.656815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6883.58541016, 3546.0803125, 170.8559375), 'rotation':(0.672473, -0.574982, 0.656815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6889.23873047, 3546.02296875, 170.92230468999998), 'rotation':(0.672473, -0.574982, 0.656815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6943.79048828, 3537.12035156, 171.56972656000002), 'rotation':(-0.686188, 179.42392, -0.702759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6965.96041016, 3536.895, 171.83775391), 'rotation':(-0.695709, 179.426498, -0.712769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6971.50240234, 3536.83863281, 171.90548828), 'rotation':(-0.698944, 179.42662, -0.716156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.58833984, 3536.72582031, 172.04183593999997), 'rotation':(-0.705261, 179.424393, -0.722778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6988.12935547, 3536.6696875, 172.11023438), 'rotation':(-0.707092, 179.42688, -0.724701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6993.67232422, 3536.61328125, 172.17908203), 'rotation':(-0.707092, 179.42688, -0.724701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(7021.38570312, 3536.33179688, 172.53177734000002), 'rotation':(-0.734558, 179.426453, -0.753601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7026.92671875, 3536.26246094, 172.60396484), 'rotation':(-0.745605, 179.428238, -0.765198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7027.024375, 3544.66871094, 172.60414062), 'rotation':(0.751287, -0.572205, 0.731777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7015.94039062, 3544.76804688, 172.45998047), 'rotation':(0.745611, -0.573273, 0.726394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6993.77095703, 3544.99339844, 172.17923828), 'rotation':(0.712498, -0.572601, 0.694942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.68501953, 3545.10621094, 172.04199218999997), 'rotation':(0.707034, -0.57486, 0.689745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6977.14253906, 3545.16257812, 171.97367188), 'rotation':(0.705306, -0.573242, 0.688108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6971.60005859, 3545.21875, 171.90564453), 'rotation':(0.702253, -0.573273, 0.685195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6954.97310547, 3545.38769531, 171.70330077999998), 'rotation':(0.692697, -0.575958, 0.676102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6943.88863281, 3545.50046875, 171.56988281000002), 'rotation':(0.689337, -0.573578, 0.672895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6938.34566406, 3545.55664062, 171.50359375), 'rotation':(0.686236, -0.5737, 0.669942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6932.80269531, 3545.61304688, 171.43757812), 'rotation':(0.683026, -0.57373, 0.666887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6927.26021484, 3545.66945312, 171.37164062), 'rotation':(0.681305, -0.574982, 0.66525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.00578125, 3546.55199219, 158.98149414), 'rotation':(-0.543854, 179.428543, -0.55423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6018.95359375, 3546.441875, 159.08923828000002), 'rotation':(-0.567749, 179.427811, -0.579071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6029.9013281200005, 3546.33179688, 159.19962891), 'rotation':(-0.584045, 179.429428, -0.596039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6040.84859375, 3546.22144531, 159.31401367), 'rotation':(-0.605774, 179.429886, -0.618683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6046.32367188, 3546.16625, 159.37272461), 'rotation':(-0.616486, 179.430115, -0.629852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6051.79734375, 3546.11132812, 159.43243164), 'rotation':(-0.627411, 179.430283, -0.641266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6073.691875, 3545.8908593799997, 159.67987305), 'rotation':(-0.654541, 179.431183, -0.669617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6002.555625, 3554.98804688, 158.92862305), 'rotation':(0.543034, -0.572083, 0.532817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6018.99015625, 3554.8225, 159.08875977), 'rotation':(0.57321, -0.570831, 0.561829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6029.9467187499995, 3554.71242188, 159.19923828), 'rotation':(0.594793, -0.570404, 0.582551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6040.9028125, 3554.60230469, 159.31369141), 'rotation':(0.616479, -0.572357, 0.603318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6046.38226562, 3554.5471093799997, 159.37245117), 'rotation':(0.627407, -0.569702, 0.613776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6051.859375, 3554.4919531200003, 159.4321875), 'rotation':(0.638363, -0.569397, 0.624257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6068.2943749999995, 3554.32617188, 159.61716797), 'rotation':(0.654544, -0.570465, 0.639704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6338.1044531200005, 3543.22804688, 163.41259766), 'rotation':(-0.883423, 179.434692, -0.91098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6326.7821875, 3543.34226562, 163.23805664), 'rotation':(-0.881897, 179.437088, -0.909363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6321.12109375, 3543.39917969, 163.1509082), 'rotation':(-0.881042, 179.437027, -0.908478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6315.45945312, 3543.45628906, 163.06382812), 'rotation':(-0.88028, 179.437012, -0.907654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6309.7982812499995, 3543.51320312, 162.97683594), 'rotation':(-0.879456, 179.43457, -0.906769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6287.15328125, 3543.74144531, 162.62958984), 'rotation':(-0.877502, 179.43576, -0.904724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6281.4921875, 3543.79859375, 162.54291992), 'rotation':(-0.875183, 179.436661, -0.902252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6275.83, 3543.85546875, 162.45648438), 'rotation':(-0.870789, 179.436523, -0.897583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6258.8466406200005, 3544.02636719, 162.19962891), 'rotation':(-0.859619, 179.435608, -0.885712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6247.52140625, 3544.140625, 162.02972656), 'rotation':(-0.857269, 179.434982, -0.883209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6230.53757812, 3544.31152344, 161.77737305), 'rotation':(-0.842133, 179.436798, -0.867157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6168.2578125, 3544.93871094, 160.88739257999998), 'rotation':(-0.780365, 179.434814, -0.801849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6151.27, 3545.1096093799997, 160.65598633), 'rotation':(-0.768555, 179.43399, -0.789368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.60789062, 3545.16675781, 160.57977539), 'rotation':(-0.760498, 179.433792, -0.780884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6139.9467187499995, 3545.22363281, 160.50436523), 'rotation':(-0.752838, 179.430893, -0.772827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6111.6328125, 3545.50878906, 160.13978516), 'rotation':(-0.717224, 179.43158, -0.735352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6134.3403125, 3553.66113281, 160.42941406), 'rotation':(0.752748, -0.566406, 0.733173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.6640625, 3553.5471093799997, 160.57939453), 'rotation':(0.76854, -0.56601, 0.748132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6151.32609375, 3553.49, 160.65560546999998), 'rotation':(0.776429, -0.565796, 0.755594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6156.98828125, 3553.433125, 160.73250977), 'rotation':(0.780452, -0.567627, 0.75941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6162.649375, 3553.37597656, 160.80962891), 'rotation':(0.780294, -0.565155, 0.759264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6173.9740624999995, 3553.26195312, 160.96484375), 'rotation':(0.795007, -0.564514, 0.773173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.6357031200005, 3553.20507812, 161.04350586), 'rotation':(0.804863, -0.566376, 0.782484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6185.296875, 3553.14796875, 161.12304688), 'rotation':(0.814582, -0.566101, 0.791663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6219.26804688, 3552.80589844, 161.61095703), 'rotation':(0.837183, -0.563324, 0.812969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6230.59078125, 3552.691875, 161.77691406), 'rotation':(0.84708, -0.563049, 0.822304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6236.25242188, 3552.635, 161.86057617), 'rotation':(0.852175, -0.565155, 0.827103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6241.91351562, 3552.5778906200003, 161.94470703000002), 'rotation':(0.857264, -0.565002, 0.831899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6253.23625, 3552.46386719, 162.11414062), 'rotation':(0.859613, -0.564392, 0.834106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6258.8984375, 3552.40699219, 162.19913086), 'rotation':(0.861949, -0.563751, 0.836314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6264.5599999999995, 3552.34984375, 162.2843457), 'rotation':(0.86643, -0.56366, 0.840521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6298.5278125, 3552.0078125, 162.80257812), 'rotation':(0.878738, -0.563049, 0.852087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6304.1889062499995, 3551.95070312, 162.88942383), 'rotation':(0.879435, -0.562958, 0.852739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6315.51117188, 3551.83691406, 163.06332031), 'rotation':(0.880958, -0.565369, 0.854181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6321.1728125, 3551.77976562, 163.15041015999998), 'rotation':(0.881969, -0.562958, 0.855117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6326.83390625, 3551.7263281200003, 163.23754883), 'rotation':(0.882727, -0.562927, 0.85583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6875.23335938, 3772.80101562, 172.79945312), 'rotation':(-0.808899, 179.821945, -0.832001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.915, 3772.8385937499997, 172.63955077999998), 'rotation':(-0.810364, 179.820404, -0.833527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6846.93648438, 3772.89476562, 172.39884766), 'rotation':(-0.814117, 179.819534, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6841.27730469, 3772.91382812, 172.31839843999998), 'rotation':(-0.814148, 179.822327, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.95796875, 3772.95140625, 172.15751953), 'rotation':(-0.81601, 179.821442, -0.839478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6824.29878906, 3772.97023438, 172.07695311999998), 'rotation':(-0.81601, 179.821442, -0.839478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6818.63912109, 3772.98898438, 171.99632812), 'rotation':(-0.819489, 179.821548, -0.843201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6812.97994141, 3773.0078125, 171.91535156), 'rotation':(-0.823212, 179.821655, -0.847137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6807.32076172, 3773.02664062, 171.83429688), 'rotation':(-0.823212, 179.821655, -0.847137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.66109375, 3773.04539062, 171.75294922), 'rotation':(-0.826782, 179.821762, -0.850891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6790.34224609, 3773.08296875, 171.58972656000003), 'rotation':(-0.828369, 179.822342, -0.8526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.02339844, 3773.120625, 171.42601562), 'rotation':(-0.828461, 179.819611, -0.852692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6750.7275, 3773.214375, 171.01435547), 'rotation':(-0.84201, 179.822311, -0.867035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6745.06783203, 3773.2331249999997, 170.93117188), 'rotation':(-0.841949, 179.822342, -0.866974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6728.09029297, 3773.28953125, 170.68150391), 'rotation':(-0.844574, 179.822449, -0.869751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6722.430625, 3773.30835938, 170.59806641), 'rotation':(-0.849945, 179.822601, -0.875458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6711.1122656200005, 3773.3459375, 170.43013672), 'rotation':(-0.855164, 179.821121, -0.880981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6705.45259766, 3773.36476562, 170.34564453), 'rotation':(-0.860229, 179.822922, -0.886353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6688.47554688, 3773.42117188, 170.09042968999998), 'rotation':(-0.863007, 179.822083, -0.889313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6682.81734375, 3773.43992188, 170.00519531), 'rotation':(-0.862854, 179.822083, -0.88916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6671.49800781, 3773.4775, 169.83464844), 'rotation':(-0.866577, 179.822739, -0.893097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6665.83929688, 3773.49632812, 169.74912109000002), 'rotation':(-0.873901, 179.822952, -0.900848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6660.17964844, 3773.51492188, 169.66294922), 'rotation':(-0.877625, 179.821487, -0.904846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6654.52484375, 3773.48976562, 169.57640625), 'rotation':(-0.877472, 179.823807, -0.904663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6648.86570312, 3773.44773438, 169.48970702999998), 'rotation':(-0.877472, 179.823807, -0.904663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6643.20210938, 3773.441875, 169.40292968999998), 'rotation':(-0.877686, 179.823807, -0.904907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6641.22359375, 3782.08835938, 169.3721875), 'rotation':(0.877474, -0.176208, 0.850907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6654.513125, 3781.95921875, 169.57580077999998), 'rotation':(0.877625, -0.176178, 0.851042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6660.16988281, 3781.89601562, 169.66238281000003), 'rotation':(0.8738, -0.177032, 0.847454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6677.14693359, 3781.839375, 169.91933594), 'rotation':(0.862933, -0.17572, 0.837222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6722.41890625, 3781.68921875, 170.59748047000002), 'rotation':(0.844621, -0.177551, 0.819994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6739.39644531, 3781.6328125, 170.84738281000003), 'rotation':(0.84193, -0.177673, 0.817457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6745.055625, 3781.61421875, 170.93056640999998), 'rotation':(0.84193, -0.177673, 0.817457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6756.37398438, 3781.57664062, 171.09671875), 'rotation':(0.838686, -0.179413, 0.814396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6762.03267578, 3781.55765625, 171.17943359), 'rotation':(0.831931, -0.177979, 0.808025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.01021484, 3781.48609375, 171.42542969), 'rotation':(0.828536, -0.177643, 0.804827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6790.32857422, 3781.430625, 171.58912109000002), 'rotation':(0.82674, -0.179688, 0.803131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.64693359, 3781.3928125, 171.75234375), 'rotation':(0.823249, -0.178345, 0.79984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6807.30660156, 3781.3740625, 171.83367188), 'rotation':(0.819479, -0.178436, 0.796289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.94332031, 3781.2990625, 172.15691406000002), 'rotation':(0.814391, -0.177673, 0.791484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6858.23921875, 3781.20507812, 172.55884766), 'rotation':(0.810416, -0.179596, 0.787716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6869.55806641, 3781.16726562, 172.71890625), 'rotation':(0.808913, -0.17804, 0.786303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6576.82222656, 3773.7917187499997, 168.37453125), 'rotation':(-0.900574, 179.823273, -0.92923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6571.1528125, 3773.81054688, 168.28548827999998), 'rotation':(-0.905212, 179.825241, -0.934174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6554.14304688, 3773.86695312, 168.01644531000002), 'rotation':(-0.91214, 179.824203, -0.941559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6525.79390625, 3773.96117188, 167.56507812), 'rotation':(-0.916107, 179.824493, -0.94577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6514.45554688, 3773.9987499999997, 167.38375), 'rotation':(-0.920135, 179.824982, -0.950073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6508.78511719, 3774.01757812, 167.29267578), 'rotation':(-0.920227, 179.824982, -0.950165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6497.44578125, 3774.05515625, 167.11048828), 'rotation':(-0.920837, 179.825027, -0.950806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6491.77585938, 3774.07398438, 167.01935547000002), 'rotation':(-0.921936, 179.822754, -0.951996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6486.1059375, 3774.0928125, 166.92816406000003), 'rotation':(-0.923187, 179.825104, -0.953308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6469.0966406200005, 3774.14914062, 166.65382812), 'rotation':(-0.925507, 179.82518, -0.95578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6457.75726562, 3774.18703125, 166.47039062), 'rotation':(-0.927887, 179.822922, -0.958282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6452.0873437499995, 3774.2057812499997, 166.37851562), 'rotation':(-0.929108, 179.825317, -0.959625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6412.399375, 3774.33765625, 165.73427734), 'rotation':(-0.930267, 179.823837, -0.960846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6401.0599999999995, 3774.37523438, 165.55011718999998), 'rotation':(-0.930176, 179.82547, -0.960754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6389.7196875, 3774.4128124999997, 165.3659375), 'rotation':(-0.930267, 179.823837, -0.960846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6384.05023438, 3774.431875, 165.27386718999998), 'rotation':(-0.929474, 179.826584, -0.959991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6378.3871875, 3774.37523438, 165.18195312), 'rotation':(-0.927704, 179.824371, -0.95813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6376.80953125, 3782.94382812, 165.15585938), 'rotation':(0.92952, -0.175568, 0.899721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6395.3935156200005, 3782.77492188, 165.45763672), 'rotation':(0.930265, -0.176178, 0.900418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6401.06296875, 3782.75609375, 165.54970702999998), 'rotation':(0.930265, -0.176178, 0.900418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6412.40179688, 3782.71851562, 165.73386718999998), 'rotation':(0.930046, -0.176331, 0.900209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6418.0717187499995, 3782.6996875, 165.82595702999998), 'rotation':(0.930046, -0.176331, 0.900209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6423.7411718799995, 3782.6809375000003, 165.91800781), 'rotation':(0.929794, -0.174316, 0.899979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6429.410625, 3782.661875, 166.01003906000003), 'rotation':(0.929636, -0.175476, 0.899827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6435.08054688, 3782.64304688, 166.10208984000002), 'rotation':(0.929582, -0.175476, 0.899777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6440.75046875, 3782.62429688, 166.19410156), 'rotation':(0.929582, -0.175476, 0.899777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6452.08929688, 3782.58664062, 166.37810547), 'rotation':(0.927786, -0.174713, 0.89809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6463.4286718799995, 3782.5490625, 166.56175781000002), 'rotation':(0.92545, -0.174805, 0.895898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6474.7670312499995, 3782.51148438, 166.74496093999997), 'rotation':(0.923093, -0.174866, 0.89371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6480.43746094, 3782.49242188, 166.83638672), 'rotation':(0.923093, -0.174866, 0.89371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6486.1068749999995, 3782.4739062500003, 166.92771484000002), 'rotation':(0.922007, -0.174927, 0.892684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6491.7763281200005, 3782.45460938, 167.01894531000002), 'rotation':(0.92075, -0.174957, 0.891521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6497.44578125, 3782.43601562, 167.11005859), 'rotation':(0.920231, -0.175018, 0.89101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6514.45503906, 3782.37960938, 167.38332031000002), 'rotation':(0.916161, -0.175507, 0.887208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.4638281200005, 3782.30445312, 167.65494141), 'rotation':(0.911967, -0.175781, 0.883274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6537.13277344, 3782.27195312, 167.74521484000002), 'rotation':(0.912035, -0.175812, 0.88333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6542.80269531, 3782.25242188, 167.83548828), 'rotation':(0.912158, -0.173828, 0.883446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6548.47210938, 3782.23367188, 167.92576172), 'rotation':(0.912158, -0.173828, 0.883446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6565.48140625, 3782.17726562, 168.19568359000002), 'rotation':(0.900574, -0.174896, 0.87258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6576.82078125, 3782.1396875, 168.3740625), 'rotation':(0.896025, -0.176849, 0.868324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6588.16011719, 3782.10203125, 168.55128906000002), 'rotation':(0.893717, -0.176605, 0.866142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6593.82953125, 3782.08296875, 168.63974609000002), 'rotation':(0.893792, -0.176636, 0.86622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6605.169375, 3782.04539062, 168.81671875), 'rotation':(0.890991, -0.177551, 0.86361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6340.3466406200005, 3774.56320312, 164.56697266), 'rotation':(-0.920959, 179.48996, -0.950958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6317.6732812499995, 3774.87476562, 164.2034375), 'rotation':(-0.913208, 179.454971, -0.942688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6300.66351562, 3775.04101562, 163.9328125), 'rotation':(-0.908569, 179.4561, -0.937744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6289.32367188, 3775.151875, 163.75292969), 'rotation':(-0.90506, 179.454956, -0.93399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6272.3134375, 3775.318125, 163.48467773000002), 'rotation':(-0.894958, 179.455322, -0.923279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6255.30320312, 3775.48414062, 163.21879883), 'rotation':(-0.892548, 179.454666, -0.920715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6249.6328125, 3775.53953125, 163.13042969), 'rotation':(-0.887878, 179.454514, -0.915741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6243.9628125, 3775.5950000000003, 163.04248047), 'rotation':(-0.883148, 179.454315, -0.910675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6226.953125, 3775.76101562, 162.78130859), 'rotation':(-0.868713, 179.451645, -0.895386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6221.2826562499995, 3775.81640625, 162.69509766), 'rotation':(-0.863892, 179.453766, -0.890259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6215.61273438, 3775.87179688, 162.60932617), 'rotation':(-0.863892, 179.453766, -0.890259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.94234375, 3775.92726562, 162.52398438), 'rotation':(-0.859192, 179.453629, -0.885284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6187.2596875, 3776.14867188, 162.18576172), 'rotation':(-0.842255, 179.452194, -0.86731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6181.5888281200005, 3776.2040625, 162.10250976999998), 'rotation':(-0.832733, 179.45195, -0.857208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6175.9184375, 3776.25929688, 162.02006836), 'rotation':(-0.823059, 179.453537, -0.846954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.90671875, 3776.42554688, 161.77620117), 'rotation':(-0.818237, 179.451721, -0.841858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.564375, 3776.5364062500003, 161.6146875), 'rotation':(-0.798462, 179.452164, -0.820923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.2128125, 3776.81320312, 161.22335938), 'rotation':(-0.765533, 179.4505, -0.786194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6113.56734375, 3785.24929688, 161.14651367), 'rotation':(0.772105, -0.548553, 0.751498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.23875, 3785.19382812, 161.22260742), 'rotation':(0.772105, -0.548553, 0.751498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6124.90867188, 3785.1384375, 161.29904297), 'rotation':(0.785274, -0.549805, 0.763956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6130.57859375, 3785.08296875, 161.37663086), 'rotation':(0.798442, -0.547821, 0.776408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6136.24898438, 3785.0278125, 161.45480469), 'rotation':(0.798442, -0.547821, 0.776408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6141.91890625, 3784.97242188, 161.53384766), 'rotation':(0.811645, -0.547455, 0.78889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6147.58929688, 3784.91703125, 161.61387695), 'rotation':(0.811645, -0.547455, 0.78889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.2592187499995, 3784.8615625, 161.69436523000002), 'rotation':(0.818222, -0.548279, 0.795094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.92914062, 3784.80617188, 161.7753418), 'rotation':(0.818263, -0.548309, 0.795137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6164.5990624999995, 3784.7509375, 161.85633789), 'rotation':(0.822997, -0.548309, 0.799603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6175.939375, 3784.64039062, 162.01917969), 'rotation':(0.832778, -0.546173, 0.808828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6192.9496875, 3784.47414062, 162.26875), 'rotation':(0.852052, -0.547485, 0.82699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6198.62109375, 3784.42039062, 162.35324219), 'rotation':(0.856806, -0.547394, 0.831468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.95890625, 3784.30789062, 162.52300781), 'rotation':(0.863889, -0.546234, 0.838129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6215.629375, 3784.25242188, 162.60833984), 'rotation':(0.868718, -0.546082, 0.84267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6221.29875, 3784.19726562, 162.6940918), 'rotation':(0.868718, -0.546082, 0.84267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6226.96875, 3784.1418750000003, 162.78030273000002), 'rotation':(0.87354, -0.545929, 0.847205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6232.6381249999995, 3784.08640625, 162.86691406), 'rotation':(0.878226, -0.545807, 0.851609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6249.64742188, 3783.92039062, 163.129375), 'rotation':(0.892569, -0.545349, 0.865069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6260.98625, 3783.79835938, 163.30631836), 'rotation':(0.894973, -0.546448, 0.867322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6272.3256249999995, 3783.66578125, 163.48359375), 'rotation':(0.898368, -0.545227, 0.870522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6306.34273438, 3783.33351562, 164.02171875), 'rotation':(0.910116, -0.545105, 0.881541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6312.0121875, 3783.27804688, 164.11189453), 'rotation':(0.913142, -0.544983, 0.884379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6317.6815625, 3783.22289062, 164.20228516), 'rotation':(0.91629, -0.544922, 0.887314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6323.3515625, 3783.1675, 164.29292969), 'rotation':(0.91629, -0.544922, 0.887314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6329.0209374999995, 3783.11234375, 164.38369140999998), 'rotation':(0.919473, -0.54483, 0.890304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6334.69140625, 3783.05664062, 164.47472656000002), 'rotation':(0.923175, -0.51123, 0.893777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6075.51414062, 3777.24, 160.65414062), 'rotation':(-0.703156, 179.448273, -0.720581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.90085938, 3777.2946875, 160.5847168), 'rotation':(-0.703156, 179.448273, -0.720581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6064.28757812, 3777.34960938, 160.51583984), 'rotation':(-0.69574, 179.448685, -0.712799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.67523438, 3777.40429688, 160.44764648), 'rotation':(-0.695892, 179.448685, -0.712952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6041.83492188, 3777.56882812, 160.24597656), 'rotation':(-0.66861, 179.448624, -0.684387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6036.22117188, 3777.6237499999997, 160.18104492), 'rotation':(-0.650482, 179.446335, -0.665375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6019.3803124999995, 3777.788125, 159.99402344), 'rotation':(-0.623138, 179.446838, -0.63681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.1537499999995, 3777.89796875, 159.87217773), 'rotation':(-0.606506, 179.446274, -0.619446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.17671875, 3786.2785937500003, 159.87155273), 'rotation':(0.617722, -0.553436, 0.604502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6013.79390625, 3786.22359375, 159.93235352), 'rotation':(0.623125, -0.553162, 0.609681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6025.02828125, 3786.11398438, 160.05484375), 'rotation':(0.632387, -0.552216, 0.61855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6036.2621875, 3786.00414062, 160.18057617), 'rotation':(0.668634, -0.551392, 0.653155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.49609375, 3785.89453125, 160.31170898), 'rotation':(0.686823, -0.552795, 0.670494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6058.73046875, 3785.78492188, 160.44732421999998), 'rotation':(0.695723, -0.548859, 0.678988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6064.3466406200005, 3785.73023438, 160.51556641), 'rotation':(0.703168, -0.551727, 0.686048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6075.5795312499995, 3785.62039062, 160.65394531), 'rotation':(0.717655, -0.551361, 0.699839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.44382812, 3974.6535937500003, 161.72480469), 'rotation':(-0.785889, 179.719742, -0.807678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.29632812, 3974.71023438, 161.57302734), 'rotation':(-0.770569, 179.719345, -0.791504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6030.42523438, 3974.85203125, 161.20800781), 'rotation':(-0.73233, 179.718063, -0.751221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6019.27679688, 3974.90867188, 161.06619141), 'rotation':(-0.721954, 179.718323, -0.740326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6013.7040625, 3974.93703125, 160.9959375), 'rotation':(-0.701324, 179.716385, -0.718628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6002.56101562, 3983.37453125, 160.85915039), 'rotation':(0.70131, -0.2836, 0.684302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6013.71578125, 3983.31789062, 160.99555664), 'rotation':(0.721985, -0.281708, 0.703953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6030.4453125, 3983.23265625, 161.20770507999998), 'rotation':(0.732073, -0.281921, 0.71354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6036.02195312, 3983.2043750000003, 161.27931640999998), 'rotation':(0.739921, -0.281464, 0.72099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.17375, 3983.1475, 161.42439453), 'rotation':(0.75531, -0.282501, 0.735582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.328125, 3983.09078125, 161.57289062), 'rotation':(0.785861, -0.280243, 0.764528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6063.90421875, 3983.0625, 161.64821289), 'rotation':(0.785861, -0.280243, 0.764528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6075.05710938, 3983.00585938, 161.80160156), 'rotation':(0.793682, -0.280396, 0.771926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6339.16109375, 3973.1953125, 165.90478516), 'rotation':(-0.942474, 179.723557, -0.973877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6305.22992188, 3973.45460938, 165.34689453), 'rotation':(-0.937775, 179.724075, -0.968872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6276.9775, 3973.598125, 164.88582031), 'rotation':(-0.93396, 179.725372, -0.964783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6265.67671875, 3973.65578125, 164.70183594), 'rotation':(-0.925934, 179.723694, -0.956268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6226.12296875, 3973.85695312, 164.06644531), 'rotation':(-0.912445, 179.724854, -0.941895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.17085938, 3973.943125, 163.79733398), 'rotation':(-0.900818, 179.722107, -0.929474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6203.5209374999995, 3973.97195312, 163.7084668), 'rotation':(-0.893158, 179.723541, -0.921326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6192.21875, 3974.02929688, 163.53234375), 'rotation':(-0.885376, 179.721619, -0.913055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6186.56882812, 3974.058125, 163.44500976999998), 'rotation':(-0.881653, 179.721649, -0.909119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6180.9169531200005, 3974.086875, 163.35796875), 'rotation':(-0.881409, 179.72435, -0.908844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6175.2670312499995, 3974.11546875, 163.27101562), 'rotation':(-0.881653, 179.721649, -0.909119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6169.61617188, 3974.14429688, 163.18405273), 'rotation':(-0.881409, 179.72168, -0.908844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.0121875, 3974.25929688, 162.84019531), 'rotation':(-0.850555, 179.720428, -0.876099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6135.70945312, 3974.316875, 162.67265625), 'rotation':(-0.846069, 179.72049, -0.871338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6130.05859375, 3974.34546875, 162.58918945), 'rotation':(-0.846008, 179.72052, -0.871277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6118.7578125, 3974.40304688, 162.42228516), 'rotation':(-0.846008, 179.72052, -0.871277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6113.10734375, 3974.431875, 162.33881836), 'rotation':(-0.839355, 179.720917, -0.864197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6107.455, 3974.46046875, 162.25601562), 'rotation':(-0.825836, 179.720551, -0.849884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6333.52140625, 3981.69164062, 165.81130859), 'rotation':(0.942409, -0.276428, 0.911779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6322.22117188, 3981.7490625, 165.62554688), 'rotation':(0.941596, -0.277069, 0.911011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6310.92039062, 3981.80664062, 165.43976562), 'rotation':(0.94148, -0.275208, 0.910903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6299.61960938, 3981.86398438, 165.25433593999998), 'rotation':(0.937764, -0.275909, 0.907443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6293.96921875, 3981.8928125, 165.16220703), 'rotation':(0.93394, -0.274628, 0.903852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6288.31882812, 3981.92164062, 165.07005859), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6282.6684375, 3981.95015625, 164.97792969), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6277.0185156200005, 3981.97898438, 164.88578125), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6271.36765625, 3982.0078125, 164.79365234), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6265.71773438, 3982.03664062, 164.70179688), 'rotation':(0.93118, -0.276123, 0.901269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6248.76609375, 3982.12257812, 164.42777343999998), 'rotation':(0.925907, -0.276306, 0.896331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6243.11570312, 3982.15140625, 164.33695312), 'rotation':(0.920532, -0.276489, 0.891308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6237.46578125, 3982.18015625, 164.24666016), 'rotation':(0.915225, -0.276672, 0.886322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6231.8139062499995, 3982.20875, 164.15642577999998), 'rotation':(0.915225, -0.276672, 0.886322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.211875, 3982.32375, 163.79728516), 'rotation':(0.908641, -0.276001, 0.880152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6197.910625, 3982.38132812, 163.62017578), 'rotation':(0.893184, -0.278137, 0.865657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6175.30804688, 3982.49609375, 163.27097656), 'rotation':(0.881402, -0.27832, 0.854579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6169.6571875, 3982.52492188, 163.18402344), 'rotation':(0.881572, -0.27832, 0.854736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.3544531200005, 3982.58226562, 163.01060547), 'rotation':(0.877058, -0.278717, 0.850505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6152.7040625, 3982.61109375, 162.92496094), 'rotation':(0.868219, -0.279022, 0.842201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.05320312, 3982.63992188, 162.84016602), 'rotation':(0.859313, -0.277008, 0.833825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6141.4028125, 3982.66867188, 162.75619140999999), 'rotation':(0.85055, -0.279541, 0.825571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6135.75046875, 3982.6975, 162.67263671999999), 'rotation':(0.846014, -0.27948, 0.821297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6124.4496875, 3982.75484375, 162.50572266), 'rotation':(0.846001, -0.277466, 0.821298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6118.79875, 3982.78367188, 162.42225586), 'rotation':(0.846069, -0.27951, 0.82135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6597.57222656, 3971.96804688, 170.18123047), 'rotation':(-0.941284, 179.725067, -0.972626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6563.649375, 3972.14039062, 169.62371094), 'rotation':(-0.941895, 179.724869, -0.973267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6529.72601562, 3972.31273438, 169.06388672), 'rotation':(-0.947327, 179.725128, -0.979034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6524.07222656, 3972.3415625, 168.97039062), 'rotation':(-0.947266, 179.723373, -0.978973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6507.11078125, 3972.42796875, 168.68984375), 'rotation':(-0.947906, 179.723663, -0.979675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6495.80320312, 3972.4856250000003, 168.50253906), 'rotation':(-0.950226, 179.726059, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6484.49605469, 3972.54296875, 168.31492188), 'rotation':(-0.950226, 179.726059, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6473.18796875, 3972.600625, 168.12732422000002), 'rotation':(-0.950226, 179.723328, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6467.5341406200005, 3972.62914062, 168.03351562), 'rotation':(-0.950226, 179.723328, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6461.8803124999995, 3972.65796875, 167.93972656000003), 'rotation':(-0.950226, 179.723328, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6427.95699219, 3972.83054688, 167.37642577999998), 'rotation':(-0.951416, 179.724731, -0.983429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6399.68746094, 3972.974375, 166.90691406000002), 'rotation':(-0.950378, 179.723236, -0.98233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6388.37984375, 3973.03171875, 166.71929688), 'rotation':(-0.950195, 179.723328, -0.982086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6382.72601562, 3973.06054688, 166.62550781000002), 'rotation':(-0.950256, 179.725418, -0.982178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6377.07222656, 3973.089375, 166.53169922), 'rotation':(-0.950195, 179.723328, -0.982086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6603.26898438, 3980.31984375, 170.27396484000002), 'rotation':(0.937546, -0.275787, 0.907226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6597.61570312, 3980.34859375, 170.18125), 'rotation':(0.940135, -0.275696, 0.90966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6580.65425781, 3980.4348437500003, 169.90251952999998), 'rotation':(0.941296, -0.276672, 0.910735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6575.00046875, 3980.46335938, 169.80958984), 'rotation':(0.941296, -0.276672, 0.910735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6569.34710938, 3980.4921875, 169.71667968999998), 'rotation':(0.941296, -0.276672, 0.910735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6558.03902344, 3980.54984375, 169.53074218999998), 'rotation':(0.94189, -0.275146, 0.911294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6535.42378906, 3980.66476562, 169.15742188000002), 'rotation':(0.947245, -0.276611, 0.916305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6529.77, 3980.69335938, 169.06390625), 'rotation':(0.947245, -0.276611, 0.916305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6518.46234375, 3980.7509375, 168.87689453), 'rotation':(0.94732, -0.276642, 0.916365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6507.15523438, 3980.80835938, 168.68990234), 'rotation':(0.947258, -0.274841, 0.916317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6501.50140625, 3980.83742188, 168.59628906), 'rotation':(0.947907, -0.276337, 0.916915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6490.19332031, 3980.89476562, 168.40873047000002), 'rotation':(0.950141, -0.273926, 0.918998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6478.8857031200005, 3980.95242188, 168.22115234), 'rotation':(0.950223, -0.276672, 0.919091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6461.92429688, 3981.03859375, 167.93974609), 'rotation':(0.950216, -0.273926, 0.919089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6439.30953125, 3981.1535937500003, 167.56429688), 'rotation':(0.951418, -0.275269, 0.920199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6428.00191406, 3981.21117188, 167.37646484), 'rotation':(0.951411, -0.277985, 0.920192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6411.04, 3981.29734375, 167.09470703), 'rotation':(0.951329, -0.275238, 0.920108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6405.38617188, 3981.32617188, 167.00080078), 'rotation':(0.951418, -0.275269, 0.920199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6388.4247656200005, 3981.41234375, 166.71933593999998), 'rotation':(0.950243, -0.276703, 0.919111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6382.7709374999995, 3981.44117188, 166.62552734000002), 'rotation':(0.950175, -0.274567, 0.919051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6646.80515625, 3980.2278125000003, 170.98496093999998), 'rotation':(0.930128, -0.276611, 0.900277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6658.09226562, 3980.1440625, 171.16816406), 'rotation':(0.927061, -0.276672, 0.897415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6680.66353516, 3979.92601562, 171.5328125), 'rotation':(0.923482, -0.276886, 0.894072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6697.59322266, 3979.84007812, 171.80558594), 'rotation':(0.918066, -0.275818, 0.888994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6714.52339844, 3979.75390625, 172.07714843999997), 'rotation':(0.916359, -0.278473, 0.887389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6737.0966406200005, 3979.63914062, 172.43830078), 'rotation':(0.914979, -0.276764, 0.886093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6742.73970703, 3979.6103125, 172.52845703), 'rotation':(0.912076, -0.276855, 0.883374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6748.38228516, 3979.58179688, 172.61841797), 'rotation':(0.909303, -0.276947, 0.880782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.95552734, 3979.46703125, 172.97621094), 'rotation':(0.905137, -0.277405, 0.876871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6776.59908203, 3979.441875, 173.06539062), 'rotation':(0.905137, -0.277405, 0.876871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6782.24263672, 3979.41820312, 173.15455078), 'rotation':(0.905143, -0.27536, 0.876864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6787.88570312, 3979.36476562, 173.24375), 'rotation':(0.905143, -0.27536, 0.876864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6793.52876953, 3979.3225, 173.33283203), 'rotation':(0.902206, -0.277924, 0.874121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6799.17183594, 3979.2903125000003, 173.42175781000003), 'rotation':(0.896503, -0.276642, 0.868783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6810.45845703, 3979.23289062, 173.59865234), 'rotation':(0.893628, -0.278748, 0.866063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6821.74556641, 3979.17554688, 173.77478516), 'rotation':(0.893525, -0.277069, 0.865968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6838.67574219, 3979.089375, 174.03890625), 'rotation':(0.893682, -0.277069, 0.866122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6861.24898438, 3978.97484375, 174.38994141), 'rotation':(0.886702, -0.277008, 0.859572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6866.89205078, 3978.94601562, 174.47730468999998), 'rotation':(0.886859, -0.27948, 0.859721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6878.17916016, 3978.8884375, 174.65205078), 'rotation':(0.886859, -0.277008, 0.859717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6883.82320312, 3979.0303125, 174.73941406000003), 'rotation':(0.886319, -0.278168, 0.859208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6878.19136719, 3970.54054688, 174.65291016), 'rotation':(-0.886719, 179.722977, -0.91449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6872.54732422, 3970.569375, 174.56552734000002), 'rotation':(-0.886871, 179.722992, -0.914642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6866.90425781, 3970.598125, 174.47814452999998), 'rotation':(-0.886719, 179.72052, -0.91449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6861.26119141, 3970.62695312, 174.39080077999998), 'rotation':(-0.888489, 179.724152, -0.916351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6844.33150391, 3970.71289062, 174.1278125), 'rotation':(-0.893646, 179.721252, -0.921844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6827.40132812, 3970.79882812, 173.86369141), 'rotation':(-0.893524, 179.722931, -0.921722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6816.11421875, 3970.85617188, 173.68757812), 'rotation':(-0.893646, 179.722931, -0.921844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6810.47115234, 3970.885, 173.59951172), 'rotation':(-0.896515, 179.721878, -0.924927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6804.82808594, 3970.91382812, 173.51119140999998), 'rotation':(-0.902222, 179.723557, -0.930969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6799.18501953, 3970.94234375, 173.42261718999998), 'rotation':(-0.902222, 179.723557, -0.930969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6793.54195312, 3970.97117188, 173.33375), 'rotation':(-0.905151, 179.72258, -0.934082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6776.61177734, 3971.0573437499997, 173.06625), 'rotation':(-0.905151, 179.72258, -0.934082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.96871094, 3971.0859375, 172.97708984000002), 'rotation':(-0.905151, 179.72258, -0.934082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6754.03902344, 3971.17210938, 172.70908203), 'rotation':(-0.912079, 179.723145, -0.941498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6748.39595703, 3971.2009375, 172.61931640999998), 'rotation':(-0.912079, 179.723145, -0.941498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6737.10982422, 3971.25828125, 172.43917968999997), 'rotation':(-0.916229, 179.723602, -0.945892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6725.82369141, 3971.31570312, 172.25861328), 'rotation':(-0.916229, 179.723602, -0.945892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6720.17964844, 3971.34421875, 172.16832031), 'rotation':(-0.916351, 179.723602, -0.946045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6669.39253906, 3971.56882812, 171.35167968999997), 'rotation':(-0.925659, 179.723267, -0.955933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6663.74945312, 3971.56296875, 171.26046875), 'rotation':(-0.927155, 179.723297, -0.95755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6652.461875, 3971.5590625, 171.07755859), 'rotation':(-0.930115, 179.726044, -0.960724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6641.17523438, 3971.61671875, 170.89404297000002), 'rotation':(-0.932861, 179.723511, -0.963623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(7021.34371094, 3969.683125, 176.85523438), 'rotation':(-0.883636, 179.722992, -0.911194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(7005.47847656, 3969.8815624999997, 176.61046875), 'rotation':(-0.881439, 179.724228, -0.908875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6988.1415625, 3969.98140625, 176.34402343999997), 'rotation':(-0.879272, 179.722763, -0.906586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.60787109, 3970.00953125, 176.25908203), 'rotation':(-0.879272, 179.722763, -0.906586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6960.47261719, 3970.12203125, 175.91925781), 'rotation':(-0.879364, 179.720993, -0.906677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6949.40572266, 3970.1784374999997, 175.749375), 'rotation':(-0.879303, 179.723175, -0.906616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6943.87203125, 3970.2065625, 175.66439452999998), 'rotation':(-0.879547, 179.721863, -0.90686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6932.80416016, 3970.2629687500003, 175.49445312), 'rotation':(-0.879547, 179.721863, -0.90686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6921.76509766, 3978.69992188, 175.32429688), 'rotation':(0.879544, -0.278137, 0.852843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6949.43599609, 3978.55929688, 175.74917968999998), 'rotation':(0.879298, -0.276825, 0.852614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6954.9696875, 3978.53125, 175.83414062), 'rotation':(0.879353, -0.279999, 0.852662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6966.03804688, 3978.47484375, 176.00404297), 'rotation':(0.879271, -0.277222, 0.852589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6977.10640625, 3978.4184375, 176.17396484), 'rotation':(0.879271, -0.279968, 0.852595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.64058594, 3978.39039062, 176.25892578), 'rotation':(0.879271, -0.277222, 0.852589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6993.70845703, 3978.33421875, 176.42880859000002), 'rotation':(0.879271, -0.277222, 0.852589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7005.50435547, 3978.28585938, 176.61019531000002), 'rotation':(0.883676, -0.277008, 0.856714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7016.57320312, 3978.32007812, 176.78095703), 'rotation':(0.883676, -0.277008, 0.856714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7026.91402344, 3978.2946875, 176.94048827999998), 'rotation':(0.883663, -0.278778, 0.85672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.07757812, 3529.30710938, 159.85644531), 'rotation':(0.216264, 90.428017, 0.21464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.17625, 3518.21726562, 159.8143457), 'rotation':(0.218429, 90.42717, 0.216758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.21773438, 3512.67066406, 159.793125), 'rotation':(0.218429, 90.42717, 0.216758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.38375, 3490.4846093799997, 159.70740234000002), 'rotation':(0.22181, 90.431915, 0.220109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.4247656200005, 3484.93824219, 159.68587890999999), 'rotation':(0.22181, 90.431915, 0.220109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.54929688, 3468.30054688, 159.62057617), 'rotation':(0.226086, 90.429153, 0.224309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6091.63226562, 3457.20628906, 159.57614258), 'rotation':(0.228934, 90.429176, 0.227109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.83929688, 3429.47386719, 159.46337891), 'rotation':(0.234542, 90.426888, 0.232634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.8803124999995, 3423.92773438, 159.44050780999999), 'rotation':(0.237499, 90.431641, 0.235542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.921875, 3418.38109375, 159.41736328000002), 'rotation':(0.240457, 90.426933, 0.238452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.96335938, 3412.83472656, 159.39395507999998), 'rotation':(0.240457, 90.426933, 0.238452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.00484375, 3407.28859375, 159.3703418), 'rotation':(0.243264, 90.431664, 0.241203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.17085938, 3385.10304688, 159.27501953), 'rotation':(0.249001, 90.429314, 0.246833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.2123437499995, 3379.556875, 159.2506543), 'rotation':(0.252034, 90.429367, 0.249825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.25390625, 3374.01023438, 159.22598632999998), 'rotation':(0.254909, 90.429382, 0.252651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.29539062, 3368.46410156, 159.20105469), 'rotation':(0.257915, 90.429382, 0.255615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6092.3778906200005, 3357.37109375, 159.15030273), 'rotation':(0.263652, 90.429436, 0.26124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6092.4609375, 3346.27855469, 159.09855469000001), 'rotation':(0.26803, 90.429878, 0.265532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6099.51507812, 3523.82640625, 159.83544922), 'rotation':(-0.218414, -89.572815, -0.220093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.5565625, 3518.27976562, 159.8143457), 'rotation':(-0.21991, -89.568481, -0.221588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6099.598125, 3512.73339844, 159.793125), 'rotation':(-0.21991, -89.568481, -0.221588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.72265625, 3496.09375, 159.72888672), 'rotation':(-0.221832, -89.571594, -0.223541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.8881249999995, 3473.90820312, 159.64246094), 'rotation':(-0.226074, -89.570862, -0.227875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.97117188, 3462.81519531, 159.5984082), 'rotation':(-0.231689, -89.570801, -0.233551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.05414062, 3451.7221875, 159.55371094), 'rotation':(-0.233124, -89.57312, -0.235046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.26117188, 3423.99023438, 159.44050780999999), 'rotation':(-0.240448, -89.568359, -0.242493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6100.30265625, 3418.44359375, 159.41736328000002), 'rotation':(-0.243256, -89.573029, -0.245361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.34421875, 3412.89746094, 159.39395507999998), 'rotation':(-0.243256, -89.573029, -0.245361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.42671875, 3401.8044531200003, 159.34665039), 'rotation':(-0.244812, -89.569366, -0.246887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.5096875, 3390.71191406, 159.29913086), 'rotation':(-0.249023, -89.570679, -0.25119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.55125, 3385.16578125, 159.27501953), 'rotation':(-0.252014, -89.570648, -0.254272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6100.59273438, 3379.619375, 159.25064453000002), 'rotation':(-0.254883, -89.570618, -0.257172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6100.8412499999995, 3346.34132812, 159.09857422), 'rotation':(-0.267853, -89.570129, -0.270386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.8090625, 3567.34667969, 160.00011719), 'rotation':(0.216722, 90.429024, 0.215077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.7675, 3572.89183594, 160.02110352), 'rotation':(0.216811, 90.429008, 0.215164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.6849999999995, 3583.98289062, 160.06306641), 'rotation':(0.216722, 90.429024, 0.215077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.6435156200005, 3589.52832031, 160.08404296999998), 'rotation':(0.216722, 90.429024, 0.215077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.60203125, 3595.07375, 160.1050293), 'rotation':(0.216811, 90.429008, 0.215164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.47703125, 3611.71019531, 160.16808594), 'rotation':(0.220212, 90.431297, 0.218534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.39453125, 3622.80101562, 160.21071289), 'rotation':(0.220212, 90.431297, 0.218534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.2284375, 3644.98316406, 160.29635742), 'rotation':(0.224754, 90.429596, 0.223012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.06296875, 3667.165, 160.38427734), 'rotation':(0.232028, 90.429649, 0.23016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.02140625, 3672.71070312, 160.40666016), 'rotation':(0.232028, 90.429649, 0.23016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.9384375, 3683.80148438, 160.4518457), 'rotation':(0.234733, 90.428993, 0.23282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.89695312, 3689.3471875, 160.47458008), 'rotation':(0.234863, 90.428993, 0.232943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.8139062499995, 3700.43796875, 160.52029296999999), 'rotation':(0.244043, 90.430931, 0.241976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.689375, 3717.0746875, 160.59092773), 'rotation':(0.247273, 90.428238, 0.245144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.64789062, 3722.62039062, 160.61483398000001), 'rotation':(0.247273, 90.428238, 0.245144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.5990624999995, 3728.16554688, 160.63878906), 'rotation':(0.248441, 90.432495, 0.246301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6089.45015625, 3739.25539062, 160.68731445), 'rotation':(0.25439, 90.427414, 0.252134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.8544531200005, 3763.2959375, 160.79608398), 'rotation':(-0.265778, -89.567322, -0.26825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.9389062499995, 3752.0078125, 160.74422852), 'rotation':(-0.259979, -89.57254, -0.26236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.97507812, 3740.52023438, 160.69264648), 'rotation':(-0.251495, -89.567474, -0.253723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.02828125, 3722.68578125, 160.61485352), 'rotation':(-0.247131, -89.567627, -0.249268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.06976562, 3717.14015625, 160.5909375), 'rotation':(-0.247131, -89.567627, -0.249268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.1528125, 3706.04929688, 160.54348633), 'rotation':(-0.237823, -89.569122, -0.239807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.19429688, 3700.50367188, 160.5203125), 'rotation':(-0.237823, -89.569122, -0.239807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.40179688, 3672.775625, 160.40666016), 'rotation':(-0.230316, -89.570374, -0.232178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.44328125, 3667.23023438, 160.38429688), 'rotation':(-0.230316, -89.570374, -0.232178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.56734375, 3650.59375, 160.31811523), 'rotation':(-0.224762, -89.570374, -0.226532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.60882812, 3645.04835938, 160.29636719), 'rotation':(-0.222931, -89.570404, -0.22464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6098.73335938, 3628.41164062, 160.23202148000001), 'rotation':(-0.220215, -89.568726, -0.221893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.7748437499995, 3622.86621094, 160.21071289), 'rotation':(-0.220398, -89.568695, -0.222107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.81640625, 3617.32078125, 160.18939453000002), 'rotation':(-0.220215, -89.574219, -0.221924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.899375, 3606.22949219, 160.14699219), 'rotation':(-0.216797, -89.570984, -0.218445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.98234375, 3595.13890625, 160.1050293), 'rotation':(-0.216705, -89.570984, -0.218353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.0653906200005, 3584.04785156, 160.06306641), 'rotation':(-0.216797, -89.570984, -0.218445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.14789062, 3572.95703125, 160.02110352), 'rotation':(-0.216705, -89.570984, -0.218353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.189375, 3567.41164062, 160.00013672), 'rotation':(-0.216614, -89.569, -0.218262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.94867188, 3816.1284375, 161.05419922), 'rotation':(0.295064, 90.430962, 0.292047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.8246875, 3832.77640625, 161.14051758), 'rotation':(0.305542, 90.429138, 0.302284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.783125, 3838.32570312, 161.16994140999998), 'rotation':(0.309763, 90.429169, 0.306427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.65867188, 3854.9739062500003, 161.26052734), 'rotation':(0.322016, 90.434326, 0.318413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.5756249999995, 3866.07226562, 161.32294922), 'rotation':(0.328218, 90.427589, 0.324476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.5341406200005, 3871.62203125, 161.3546582), 'rotation':(0.328218, 90.427589, 0.324476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.45109375, 3882.72046875, 161.41868164), 'rotation':(0.339522, 90.430023, 0.335524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.40960938, 3888.27, 161.45135742), 'rotation':(0.339522, 90.430023, 0.335524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.32664062, 3899.3684375000003, 161.51792969), 'rotation':(0.354774, 90.430214, 0.350407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.28515625, 3904.91773438, 161.55192383), 'rotation':(0.354774, 90.430214, 0.350407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6087.99460938, 3943.76320312, 161.79844727), 'rotation':(0.378741, 90.432289, 0.373767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6087.8700781200005, 3960.41085938, 161.91009766), 'rotation':(0.39096, 90.431343, 0.385648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6096.2509375, 3960.4778125000003, 161.91012695), 'rotation':(-0.386932, -89.567596, -0.392212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.33390625, 3949.37867188, 161.83515625), 'rotation':(-0.378754, -89.570679, -0.383789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.37546875, 3943.82960938, 161.79847656), 'rotation':(-0.370728, -89.567841, -0.375549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.5, 3927.181875, 161.69083984), 'rotation':(-0.36261, -89.570923, -0.367218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.62398438, 3910.53320312, 161.58630859000002), 'rotation':(-0.354797, -89.569794, -0.359192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.6654687499995, 3904.98390625, 161.55194336), 'rotation':(-0.347229, -89.569885, -0.351471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.70703125, 3899.43453125, 161.51794922), 'rotation':(-0.347229, -89.569885, -0.351471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.79, 3888.33617188, 161.45136719), 'rotation':(-0.332001, -89.570038, -0.335876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.0390625, 3855.03953125, 161.26055664), 'rotation':(-0.317932, -89.57074, -0.321472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.08054688, 3849.49, 161.22995117), 'rotation':(-0.313721, -89.57077, -0.317169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.12203125, 3843.9409375, 161.19975586), 'rotation':(-0.309753, -89.570831, -0.313141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.2465625, 3827.29296875, 161.11152344), 'rotation':(-0.297363, -89.570953, -0.300446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.28804688, 3821.743125, 161.08282227), 'rotation':(-0.295258, -89.574463, -0.298279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6097.3295312499995, 3816.1940624999997, 161.05421875), 'rotation':(-0.293304, -89.570953, -0.296295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.41015625, 3810.64648438, 161.02574219), 'rotation':(-0.289154, -89.565918, -0.292084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6076.921875, 3325.39183594, 158.7937207), 'rotation':(-0.634216, 179.882874, -0.648346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6055.67429688, 3325.54882812, 158.56507812), 'rotation':(-0.587982, 179.882645, -0.600159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6050.3603125, 3325.5603125, 158.51022461), 'rotation':(-0.587952, 179.882645, -0.600128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6045.0482812499995, 3325.57177734, 158.45570312), 'rotation':(-0.587952, 179.882645, -0.600128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6039.734375, 3325.58277344, 158.40128906), 'rotation':(-0.575714, 179.883347, -0.587372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6029.109375, 3325.60570312, 158.29541016), 'rotation':(-0.551239, 179.881348, -0.56192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6023.796875, 3325.6171875, 158.24429688), 'rotation':(-0.526672, 179.882401, -0.536407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6076.94085938, 3333.99511719, 158.79373046999999), 'rotation':(0.652713, -0.11499, 0.637976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6066.31640625, 3333.90671875, 158.67727539), 'rotation':(0.634176, -0.117126, 0.620269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6055.6889062499995, 3333.9296875, 158.5650293), 'rotation':(0.597177, -0.11792, 0.584817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6050.375, 3333.94117188, 158.51019531), 'rotation':(0.587936, -0.11734, 0.575965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6045.06148438, 3333.95265625, 158.4556543), 'rotation':(0.587936, -0.11734, 0.575965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6029.1200781200005, 3333.9865625, 158.29535156), 'rotation':(0.57571, -0.116638, 0.56423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6018.4896874999995, 3334.00953125, 158.19460938), 'rotation':(0.551237, -0.118652, 0.540708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6013.17671875, 3334.02074219, 158.14577148), 'rotation':(0.526662, -0.117584, 0.517047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6002.5478125, 3334.04371094, 158.05275390999998), 'rotation':(0.502087, -0.119568, 0.493347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6329.7943749999995, 3324.95947266, 162.26286133), 'rotation':(-0.860565, 179.890778, -0.886719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6318.48289062, 3324.98363281, 162.093125), 'rotation':(-0.857086, 179.890686, -0.883026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6307.171875, 3325.00804688, 161.92396484), 'rotation':(-0.85437, 179.889877, -0.880157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6301.515625, 3325.02027344, 161.83955078), 'rotation':(-0.85437, 179.889877, -0.880157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6284.54875, 3325.05664062, 161.58645508), 'rotation':(-0.854553, 179.888138, -0.880341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6273.2372656200005, 3325.08105469, 161.41770508), 'rotation':(-0.846313, 179.889633, -0.871613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6261.9247656200005, 3325.10523438, 161.25076171999999), 'rotation':(-0.838074, 179.889389, -0.862885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6256.26953125, 3325.11742188, 161.16801758), 'rotation':(-0.837952, 179.889374, -0.862732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6244.9575, 3325.14183594, 161.0025), 'rotation':(-0.838074, 179.889389, -0.862885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6239.30171875, 3325.1540625, 160.91973633), 'rotation':(-0.835327, 179.889481, -0.859955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6227.98828125, 3325.17822266, 160.75544922), 'rotation':(-0.824341, 179.88916, -0.848328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6222.3325, 3325.19042969, 160.67420898), 'rotation':(-0.818939, 179.886215, -0.842621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6211.02046875, 3325.21460938, 160.51351562), 'rotation':(-0.802582, 179.888535, -0.825317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6199.7084374999995, 3325.23876953, 160.35522461), 'rotation':(-0.794464, 179.88736, -0.816711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6182.73828125, 3325.27539062, 160.12003906), 'rotation':(-0.78833, 179.88707, -0.810272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6177.08148438, 3325.28759766, 160.0422168), 'rotation':(-0.776306, 179.888565, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6171.42523438, 3325.29980469, 159.96555664), 'rotation':(-0.76413, 179.886398, -0.784698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6160.11273438, 3325.32421875, 159.81469727), 'rotation':(-0.751892, 179.886078, -0.77182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6148.79929688, 3325.34839844, 159.66679688), 'rotation':(-0.74588, 179.886581, -0.765503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6131.83148438, 3325.318125, 159.4471875), 'rotation':(-0.721039, 179.886124, -0.739349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6120.51359375, 3325.27978516, 159.30566406), 'rotation':(-0.704651, 179.884018, -0.722168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6115.501875, 3325.29052734, 159.24400391), 'rotation':(-0.68808, 179.8853, -0.704773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6120.501875, 3333.9196875, 159.30529296999998), 'rotation':(0.721029, -0.113892, 0.703054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6126.1615624999995, 3333.88941406, 159.37557617000002), 'rotation':(0.721029, -0.113892, 0.703054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6131.81734375, 3333.83300781, 159.44677734), 'rotation':(0.737592, -0.113464, 0.718782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6137.473125, 3333.776875, 159.51953125), 'rotation':(0.745891, -0.113403, 0.726657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6148.78460938, 3333.72949219, 159.66638672), 'rotation':(0.745768, -0.113434, 0.726539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.44140625, 3333.71726562, 159.74001953), 'rotation':(0.751881, -0.113922, 0.732348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6171.41015625, 3333.68066406, 159.96511719), 'rotation':(0.776292, -0.11142, 0.755458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6177.06585938, 3333.6684375, 160.04174805), 'rotation':(0.788347, -0.112946, 0.766874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6182.72265625, 3333.65625, 160.11958008), 'rotation':(0.794447, -0.11264, 0.772644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6194.03460938, 3333.63183594, 160.27625977), 'rotation':(0.794447, -0.11264, 0.772644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6199.69140625, 3333.61960938, 160.35473633), 'rotation':(0.797165, -0.111603, 0.775217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6222.31492188, 3333.57105469, 160.67371094), 'rotation':(0.824342, -0.11084, 0.800871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6239.28367188, 3333.53492188, 160.91921875), 'rotation':(0.838091, -0.112823, 0.813841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6244.939375, 3333.52269531, 161.00197265999998), 'rotation':(0.838153, -0.110626, 0.813893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6256.2509375, 3333.49828125, 161.16748047), 'rotation':(0.838091, -0.110626, 0.813833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6261.90671875, 3333.48632812, 161.25022461), 'rotation':(0.846308, -0.110352, 0.82157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6273.21820312, 3333.46828125, 161.4171582), 'rotation':(0.854375, -0.111847, 0.829178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6278.87398438, 3333.4607031200003, 161.50152344), 'rotation':(0.854532, -0.110107, 0.829331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6290.1849999999995, 3333.39234375, 161.67025390999999), 'rotation':(0.854395, -0.110107, 0.829178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6295.84078125, 3333.38011719, 161.75461914), 'rotation':(0.854395, -0.110107, 0.829178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6318.46335938, 3333.33128906, 162.09255859), 'rotation':(0.858575, -0.111328, 0.833117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6324.1190625, 3333.31933594, 162.17735352), 'rotation':(0.860583, -0.111267, 0.835002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6329.7753125, 3333.30710938, 162.26231445), 'rotation':(0.861266, -0.109711, 0.83566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6335.4310937499995, 3333.46507812, 162.34732422), 'rotation':(0.861266, -0.109711, 0.83566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6576.856875, 3324.4275, 165.77150390999998), 'rotation':(-0.732727, 179.884598, -0.751648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6571.20453125, 3324.4396875, 165.699375), 'rotation':(-0.737854, 179.887375, -0.75705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6565.55320312, 3324.45166016, 165.62671875), 'rotation':(-0.743011, 179.884857, -0.762482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6542.94578125, 3324.50048828, 165.33052734), 'rotation':(-0.761383, 179.886826, -0.78183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6531.6415625, 3324.52490234, 165.18025391), 'rotation':(-0.766174, 179.888046, -0.786865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6509.035625, 3324.57347656, 164.87490234), 'rotation':(-0.79483, 179.886826, -0.817108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6503.38328125, 3324.58544922, 164.79664062), 'rotation':(-0.799591, 179.887115, -0.822144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6497.73289062, 3324.59765625, 164.71794922), 'rotation':(-0.799591, 179.889694, -0.822144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6492.08054688, 3324.60986328, 164.63902344), 'rotation':(-0.799591, 179.887115, -0.822144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6469.4740624999995, 3324.65869141, 164.32244140999998), 'rotation':(-0.810547, 179.887009, -0.83374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6458.1708593799995, 3324.68310547, 164.16140625), 'rotation':(-0.825195, 179.889465, -0.849243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6441.21578125, 3324.71949219, 163.91646484), 'rotation':(-0.828766, 179.888321, -0.852997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6435.5639062499995, 3324.73167969, 163.8346875), 'rotation':(-0.831757, 179.888306, -0.856201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6424.26117188, 3324.75609375, 163.67063477), 'rotation':(-0.837677, 179.890152, -0.862427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6418.60933594, 3324.76832031, 163.58799805), 'rotation':(-0.843567, 179.888641, -0.868683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6412.9575, 3324.78050781, 163.50499023), 'rotation':(-0.843567, 179.888641, -0.868683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6407.3060937499995, 3324.79248047, 163.42170898), 'rotation':(-0.849426, 179.888809, -0.874908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6401.65425781, 3324.8046875, 163.33789062), 'rotation':(-0.852234, 179.890091, -0.877899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6390.35152344, 3324.82910156, 163.16980469), 'rotation':(-0.852417, 179.890091, -0.878052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6384.6996875, 3324.84130859, 163.08569336), 'rotation':(-0.85318, 179.888916, -0.878906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6384.6786718799995, 3333.22191406, 163.08511719), 'rotation':(0.852401, -0.109894, 0.827314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6407.28609375, 3333.17359375, 163.42114258), 'rotation':(0.843508, -0.111359, 0.818951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6412.93695312, 3333.16136719, 163.50442383), 'rotation':(0.837716, -0.111511, 0.813478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6424.2411718799995, 3333.13695312, 163.67008789), 'rotation':(0.83176, -0.110016, 0.807867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6435.54390625, 3333.11253906, 163.83414062), 'rotation':(0.828755, -0.111694, 0.805036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6441.19625, 3333.10035156, 163.91591797), 'rotation':(0.828802, -0.111694, 0.805073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6452.49996094, 3333.0759375, 164.07947266), 'rotation':(0.825203, -0.110535, 0.801676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6469.45554688, 3333.03953125, 164.32191406), 'rotation':(0.803278, -0.111176, 0.780996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6475.1068749999995, 3333.02734375, 164.4015625), 'rotation':(0.803278, -0.111176, 0.780996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6486.41109375, 3333.00292969, 164.55962891), 'rotation':(0.799576, -0.112885, 0.777496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6497.71480469, 3332.97875, 164.71742188), 'rotation':(0.799583, -0.110291, 0.777493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6509.0185156200005, 3332.95433594, 164.87441406000002), 'rotation':(0.785301, -0.11145, 0.764003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6525.9740625, 3332.91796875, 165.10441406), 'rotation':(0.761457, -0.113159, 0.741415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.6259375, 3332.90578125, 165.17978516), 'rotation':(0.761457, -0.113159, 0.741415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6548.5825, 3332.85863281, 165.40496094), 'rotation':(0.753452, -0.112213, 0.733825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6559.88617188, 3332.8122656200003, 165.55308594), 'rotation':(0.743002, -0.112488, 0.72392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6571.18992188, 3332.78734375, 165.69898438), 'rotation':(0.732729, -0.112762, 0.714161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6582.49460938, 3332.76320312, 165.84267577999998), 'rotation':(0.722115, -0.115692, 0.704084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6593.79828125, 3332.73902344, 165.98478516), 'rotation':(0.716132, -0.113708, 0.698401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6599.45113281, 3332.7267968799997, 166.05546875), 'rotation':(0.709308, -0.116272, 0.691917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6868.87984375, 3323.79882812, 168.92226562), 'rotation':(-0.55014, 179.881714, -0.56076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.23726562, 3323.81103516, 168.86808594), 'rotation':(-0.550903, 179.881729, -0.561584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6857.59517578, 3323.82324219, 168.81386719), 'rotation':(-0.550903, 179.881729, -0.561584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6835.024375, 3323.87183594, 168.59671875), 'rotation':(-0.551147, 179.881744, -0.561829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.38228516, 3323.88402344, 168.54236328), 'rotation':(-0.553711, 179.883408, -0.564484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6823.73970703, 3323.89625, 168.48783203), 'rotation':(-0.558258, 179.882019, -0.569214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6795.52681641, 3323.95679688, 168.21125), 'rotation':(-0.570007, 179.882172, -0.581421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6767.31539062, 3324.01757812, 167.93), 'rotation':(-0.578857, 179.882263, -0.590637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6761.6728125, 3324.02978516, 167.87291016), 'rotation':(-0.584717, 179.884384, -0.596741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6756.03023438, 3324.04199219, 167.81533202999998), 'rotation':(-0.590759, 179.882492, -0.603027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6744.74605469, 3324.06617188, 167.69884765999998), 'rotation':(-0.593567, 179.882904, -0.605988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6739.10347656, 3324.07835938, 167.64039062), 'rotation':(-0.596344, 179.882248, -0.608856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6733.46236328, 3324.09058594, 167.58167969), 'rotation':(-0.601624, 179.88237, -0.61438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6727.81978516, 3324.10253906, 167.52253906), 'rotation':(-0.607117, 179.884613, -0.620087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6722.17769531, 3324.11474609, 167.46294922), 'rotation':(-0.61264, 179.882584, -0.625854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6710.89302734, 3324.13916016, 167.34242188), 'rotation':(-0.61792, 179.882706, -0.631378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6660.1146875, 3324.24828125, 166.77837891), 'rotation':(-0.659454, 179.884308, -0.674774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6648.83003906, 3324.27246094, 166.64753906), 'rotation':(-0.672882, 179.883484, -0.688812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6654.46773438, 3332.64136719, 166.71310547000002), 'rotation':(0.659455, -0.115692, 0.644416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6677.03707031, 3332.59277344, 166.96998047), 'rotation':(0.636929, -0.114655, 0.62289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6682.67818359, 3332.58054688, 167.03296875), 'rotation':(0.636929, -0.114655, 0.62289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6693.961875, 3332.55640625, 167.15792968999997), 'rotation':(0.62878, -0.117065, 0.615098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6705.24751953, 3332.53222656, 167.28126953), 'rotation':(0.61792, -0.117279, 0.604699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6710.88960938, 3332.52, 167.3421875), 'rotation':(0.612627, -0.117401, 0.599631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6722.17427734, 3332.495625, 167.46271484000002), 'rotation':(0.607108, -0.115387, 0.594353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6733.45894531, 3332.47144531, 167.58146484), 'rotation':(0.596344, -0.117767, 0.584024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6739.10103516, 3332.45921875, 167.64017578), 'rotation':(0.593578, -0.117096, 0.581367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6744.74361328, 3332.44703125, 167.69863281000002), 'rotation':(0.59075, -0.117493, 0.578666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6756.02779297, 3332.42261719, 167.81511719), 'rotation':(0.584719, -0.117645, 0.572879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6772.95552734, 3332.38625, 167.98642578), 'rotation':(0.569993, -0.117828, 0.558747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.16792969, 3332.32542969, 168.26695312), 'rotation':(0.562931, -0.117859, 0.551954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6812.45308594, 3332.30101562, 168.37787109), 'rotation':(0.558252, -0.11795, 0.547458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6829.38082031, 3332.26464844, 168.54216797), 'rotation':(0.551148, -0.118256, 0.540628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6857.59419922, 3332.20582031, 168.81369141), 'rotation':(0.550131, -0.118286, 0.539644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.23628906, 3332.19679688, 168.86792968999998), 'rotation':(0.550131, -0.118286, 0.539644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6868.87886719, 3332.1875, 168.92208984), 'rotation':(0.549721, -0.117798, 0.539245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6880.16451172, 3332.14015625, 169.03039062), 'rotation':(0.549721, -0.117798, 0.539245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6891.45015625, 3332.09960938, 169.13876953), 'rotation':(0.551265, -0.118164, 0.540734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7029.02291016, 3323.45458984, 170.54998047), 'rotation':(-0.648346, 179.885483, -0.663147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(7023.48775391, 3323.4665625, 170.48697266), 'rotation':(-0.640259, 179.882706, -0.654694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7017.95308594, 3323.47828125, 170.42474609), 'rotation':(-0.632385, 179.885117, -0.646454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7001.34712891, 3323.51416016, 170.24283203), 'rotation':(-0.608337, 179.882004, -0.621368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6995.81197266, 3323.52613281, 170.18376952999998), 'rotation':(-0.60025, 179.881851, -0.612946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6990.27681641, 3323.53808594, 170.12550781000002), 'rotation':(-0.596283, 179.884003, -0.608795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6979.20601562, 3323.56175781, 170.01019531000003), 'rotation':(-0.592407, 179.881851, -0.604767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6962.60152344, 3323.59765625, 169.83943359), 'rotation':(-0.577271, 179.882996, -0.58902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6951.53169922, 3323.62109375, 169.72759766), 'rotation':(-0.56958, 179.881378, -0.580994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6929.3915625, 3323.66871094, 169.50824218999998), 'rotation':(-0.561646, 179.883163, -0.572723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6923.85640625, 3323.68066406, 169.45380859), 'rotation':(-0.561646, 179.883163, -0.572723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7037.38375, 3331.93921875, 170.64595702999998), 'rotation':(0.660315, -0.114136, 0.645224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(7023.50679688, 3331.84742188, 170.48697266), 'rotation':(0.648363, -0.114532, 0.633804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6995.83101562, 3331.90671875, 170.18376952999998), 'rotation':(0.608351, -0.117981, 0.595532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6984.76021484, 3331.93066406, 170.06777344), 'rotation':(0.600244, -0.11557, 0.587769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6973.69039062, 3331.95460938, 169.95294922000002), 'rotation':(0.592423, -0.116699, 0.580267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6968.15523438, 3331.96632812, 169.89595702999998), 'rotation':(0.592423, -0.116699, 0.580267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6962.62056641, 3331.97804688, 169.83945312), 'rotation':(0.584835, -0.118317, 0.572986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6957.08589844, 3331.99, 169.78337890999998), 'rotation':(0.584835, -0.118317, 0.572986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6934.94527344, 3332.03757812, 169.5628125), 'rotation':(0.565833, -0.118103, 0.554753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n ]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/result_writer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module contains the result gatherer and write for CARLA scenarios.\nIt shall be used from the ScenarioManager only.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport time\nfrom collections import OrderedDict\nfrom tabulate import tabulate\n\n\nCOLORED_STATUS = {\n    \"FAILURE\": '\\033[91mFAILURE\\033[0m',\n    \"SUCCESS\": '\\033[92mSUCCESS\\033[0m',\n    \"ACCEPTABLE\": '\\033[93mACCEPTABLE\\033[0m',\n}\n\nSTATUS_PRIORITY = {\n    \"FAILURE\": 0,\n    \"ACCEPTABLE\": 1,\n    \"SUCCESS\": 2,\n}  # Lower number is higher priority\n\n\nclass ResultOutputProvider(object):\n\n    \"\"\"\n    This module contains the _result gatherer and write for CARLA scenarios.\n    It shall be used from the ScenarioManager only.\n    \"\"\"\n\n    def __init__(self, data):\n        \"\"\"\n        - data contains all scenario-related information\n        - global_result is overall pass/fail info\n        \"\"\"\n        self._data = data\n        self._start_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.start_system_time))\n        self._end_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.end_system_time))\n\n        self._global_result = '\\033[92m'+'SUCCESS'+'\\033[0m'\n        for criterion in self._data.scenario.get_criteria():\n            if criterion.test_status != \"SUCCESS\":\n                self._global_result = '\\033[91m'+'FAILURE'+'\\033[0m'\n        if self._data.scenario.timeout_node.timeout:\n            self._global_result = '\\033[91m'+'FAILURE'+'\\033[0m'\n\n        print(self.create_output_text())\n\n    def create_output_text(self):\n        \"\"\"\n        Creates the output message\n        \"\"\"\n\n        # Create the title\n        output = \"\\n\"\n        output += \"\\033[1m========= Results of {} (repetition {}) ------ {} \\033[1m=========\\033[0m\\n\".format(\n            self._data.scenario_tree.name, self._data.repetition_number, self._global_result)\n        output += \"\\n\"\n\n        # Simulation part\n        system_time = round(self._data.scenario_duration_system, 2)\n        game_time = round(self._data.scenario_duration_game, 2)\n        ratio = round(self._data.scenario_duration_game / self._data.scenario_duration_system, 3)\n\n        list_statistics = [[\"Start Time\", \"{}\".format(self._start_time)]]\n        list_statistics.extend([[\"End Time\", \"{}\".format(self._end_time)]])\n        list_statistics.extend([[\"System Time\", \"{}s\".format(system_time)]])\n        list_statistics.extend([[\"Game Time\", \"{}s\".format(game_time)]])\n        list_statistics.extend([[\"Ratio (Game / System)\", \"{}\".format(ratio)]])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\\n\"\n\n        # Criteria part\n        header = ['Criterion', 'Result', 'Value']\n        list_statistics = [header]\n        criteria_data = OrderedDict()\n\n        for criterion in self._data.scenario.get_criteria():\n\n            name = criterion.name\n\n            if name in criteria_data:\n                result = criterion.test_status\n                if STATUS_PRIORITY[result] < STATUS_PRIORITY[criteria_data[name]['result']]:\n                    criteria_data[name]['result'] = result\n                criteria_data[name]['actual_value'] += criterion.actual_value\n\n            else:\n                criteria_data[name] = {\n                    'result': criterion.test_status,\n                    'actual_value': criterion.actual_value,\n                    'units': criterion.units\n                }\n\n        for criterion_name in criteria_data:\n            criterion = criteria_data[criterion_name]\n\n            result = criterion['result']\n            if result in COLORED_STATUS:\n                result = COLORED_STATUS[result]\n\n            if criterion['units'] is None:\n                actual_value = \"\"\n            else:\n                actual_value = str(criterion['actual_value']) + \" \" + criterion['units']\n\n            list_statistics.extend([[criterion_name, result, actual_value]])\n\n        # Timeout\n        name = \"Timeout\"\n\n        actual_value = self._data.scenario_duration_game\n\n        if self._data.scenario_duration_game < self._data.scenario.timeout:\n            result = '\\033[92m'+'SUCCESS'+'\\033[0m'\n        else:\n            result = '\\033[91m'+'FAILURE'+'\\033[0m'\n\n        list_statistics.extend([[name, result, '']])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\"\n\n        return output\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/route_indexer.py",
    "content": "from collections import OrderedDict\nfrom dictor import dictor\n\nimport copy\n\nfrom leaderboard.utils.route_parser import RouteParser\nfrom leaderboard.utils.checkpoint_tools import fetch_dict\n\n\nclass RouteIndexer():\n    def __init__(self, routes_file, repetitions, routes_subset):\n        self._configs_dict = OrderedDict()\n        self._configs_list = []\n        self.index = 0\n\n        route_configurations = RouteParser.parse_routes_file(routes_file, routes_subset)\n        self.total = len(route_configurations) * repetitions\n\n        for i, config in enumerate(route_configurations):\n            for repetition in range(repetitions):\n                config.index = i * repetitions + repetition\n                config.repetition_index = repetition\n                self._configs_dict['{}.{}'.format(config.name, repetition)] = copy.copy(config)\n\n        self._configs_list = list(self._configs_dict.values())\n\n\n    def peek(self):\n        return self.index < self.total\n\n    def get_next_config(self):\n        if self.index >= self.total:\n            return None\n\n        config = self._configs_list[self.index]\n        self.index += 1\n\n        return config\n\n    def validate_and_resume(self, endpoint):\n        \"\"\"\n        Validates the endpoint by comparing several of its values with the current running routes.\n        If all checks pass, the simulation starts from the last route.\n        Otherwise, the resume is canceled, and the leaderboard goes back to normal behavior\n        \"\"\"\n        data = fetch_dict(endpoint)\n        if not data:\n            print('Problem reading checkpoint. Found no data')\n            return False\n\n        entry_status = dictor(data, 'entry_status')\n        if not entry_status:\n            print(\"Problem reading checkpoint. Given checkpoint is malformed\")\n            return False\n        if entry_status == \"Invalid\":\n            print(\"Problem reading checkpoint. The 'entry_status' is 'Invalid'\")\n            return False\n\n        checkpoint_dict = dictor(data, '_checkpoint')\n        if not checkpoint_dict or 'progress' not in checkpoint_dict:\n            print(\"Problem reading checkpoint. Given endpoint is malformed\")\n            return False\n\n        progress = checkpoint_dict['progress']\n        if progress[1] != self.total:\n            print(\"Problem reading checkpoint. Endpoint's amount of routes does not match the given one\")\n            return False\n\n        route_data = dictor(checkpoint_dict, 'records')\n\n        check_index = 0\n        resume_index = progress[0]\n        while check_index < resume_index:\n            try:\n                route_id = self._configs_list[check_index].name\n                route_id += \"_rep\" + str(self._configs_list[check_index].repetition_index)\n                checkpoint_route_id = route_data[check_index]['route_id']\n\n                if route_id != checkpoint_route_id:\n                    print(\"Problem reading checkpoint. Checkpoint routes don't match the current ones\")\n                    return False\n\n                if route_data[check_index]['status'] not in ['Failed', 'Failed - Simulation crashed', 'Failed - Agent crashed', 'Failed - Simulation crashed']:\n                    check_index += 1\n                else:\n                    resume_index = check_index\n                    break\n            except IndexError:\n                # Patch to fix some cases where the progress might be higher than the actual results\n                resume_index = max(check_index - 1, 0)\n\n        if entry_status == \"Crashed\":\n            self.index = max(0, resume_index - 1)  # Something went wrong, repeat the last route\n        else: \n            self.index = max(0, resume_index)\n        return True\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/route_manipulation.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Labs.\n# authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule to manipulate the routes, by making then more or less dense (Up to a certain parameter).\nIt also contains functions to convert the CARLA world location do GPS coordinates.\n\"\"\"\n\nimport math\nimport xml.etree.ElementTree as ET\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\n\n\ndef _location_to_gps(lat_ref, lon_ref, location):\n    \"\"\"\n    Convert from world coordinates to GPS coordinates\n    :param lat_ref: latitude reference for the current map\n    :param lon_ref: longitude reference for the current map\n    :param location: location to translate\n    :return: dictionary with lat, lon and height\n    \"\"\"\n\n    EARTH_RADIUS_EQUA = 6378137.0   # pylint: disable=invalid-name\n    scale = math.cos(lat_ref * math.pi / 180.0)\n    mx = scale * lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n    my = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + lat_ref) * math.pi / 360.0))\n    mx += location.x\n    my -= location.y\n\n    lon = mx * 180.0 / (math.pi * EARTH_RADIUS_EQUA * scale)\n    lat = 360.0 * math.atan(math.exp(my / (EARTH_RADIUS_EQUA * scale))) / math.pi - 90.0\n    z = location.z\n\n    return {'lat': lat, 'lon': lon, 'z': z}\n\n\ndef location_route_to_gps(route, lat_ref, lon_ref):\n    \"\"\"\n        Locate each waypoint of the route into gps, (lat long ) representations.\n    :param route:\n    :param lat_ref:\n    :param lon_ref:\n    :return:\n    \"\"\"\n    gps_route = []\n\n    for transform, connection in route:\n        gps_point = _location_to_gps(lat_ref, lon_ref, transform.location)\n        gps_route.append((gps_point, connection))\n\n    return gps_route\n\n\ndef _get_latlon_ref(world):\n    \"\"\"\n    Convert from waypoints world coordinates to CARLA GPS coordinates\n    :return: tuple with lat and lon coordinates\n    \"\"\"\n    xodr = world.get_map().to_opendrive()\n    tree = ET.ElementTree(ET.fromstring(xodr))\n\n    # default reference\n    lat_ref = 42.0\n    lon_ref = 2.0\n\n    for opendrive in tree.iter(\"OpenDRIVE\"):\n        for header in opendrive.iter(\"header\"):\n            for georef in header.iter(\"geoReference\"):\n                if georef.text:\n                    str_list = georef.text.split(' ')\n                    for item in str_list:\n                        if '+lat_0' in item:\n                            lat_ref = float(item.split('=')[1])\n                        if '+lon_0' in item:\n                            lon_ref = float(item.split('=')[1])\n    return lat_ref, lon_ref\n\n\ndef downsample_route(route, sample_factor):\n    \"\"\"\n    Downsample the route by some factor.\n    :param route: the trajectory , has to contain the waypoints and the road options\n    :param sample_factor: Maximum distance between samples\n    :return: returns the ids of the final route that can\n    \"\"\"\n\n    ids_to_sample = []\n    prev_option = None\n    dist = 0\n\n    for i, point in enumerate(route):\n        curr_option = point[1]\n\n        # At the beginning\n        if prev_option is None:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # Lane changing\n        elif curr_option in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # When entering or exitting intersections\n        elif prev_option != curr_option and prev_option not in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # After a certain max distance\n        elif dist > sample_factor:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # At the end\n        elif i == len(route) - 1:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # Compute the distance traveled\n        else:\n            curr_location = point[0].location\n            prev_location = route[i-1][0].location\n            dist += curr_location.distance(prev_location)\n\n        prev_option = curr_option\n\n    return ids_to_sample\n\n\ndef interpolate_trajectory(waypoints_trajectory, hop_resolution=1.0):\n    \"\"\"\n    Given some raw keypoints interpolate a full dense trajectory to be used by the user.\n    returns the full interpolated route both in GPS coordinates and also in its original form.\n    \n    Args:\n        - waypoints_trajectory: the current coarse trajectory\n        - hop_resolution: distance between the trajectory's waypoints\n    \"\"\"\n\n    grp = GlobalRoutePlanner(CarlaDataProvider.get_map(), hop_resolution)\n    # Obtain route plan\n    lat_ref, lon_ref = _get_latlon_ref(CarlaDataProvider.get_world())\n\n    route = []\n    gps_route = []\n\n    for i in range(len(waypoints_trajectory) - 1):\n\n        waypoint = waypoints_trajectory[i]\n        waypoint_next = waypoints_trajectory[i + 1]\n        interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n        for wp, connection in interpolated_trace:\n            route.append((wp.transform, connection))\n            gps_coord = _location_to_gps(lat_ref, lon_ref, wp.transform.location)\n            gps_route.append((gps_coord, connection))\n\n    return gps_route, route\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/route_parser.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule used to parse all the route and scenario configuration parameters.\n\"\"\"\nimport math\nimport xml.etree.ElementTree as ET\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\nfrom srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData\n\n# Threshold to say if a scenarios trigger position is part of the route\nDIST_THRESHOLD = 2.0\nANGLE_THRESHOLD = 10\n\n\ndef convert_elem_to_transform(elem):\n    \"\"\"Convert an ElementTree.Element to a CARLA transform\"\"\"\n    return carla.Transform(\n        carla.Location(\n            float(elem.attrib.get('x')),\n            float(elem.attrib.get('y')),\n            float(elem.attrib.get('z'))\n        ),\n        carla.Rotation(\n            roll=0.0,\n            pitch=0.0,\n            yaw=float(elem.attrib.get('yaw'))\n        )\n    )\n\n\nclass RouteParser(object):\n\n    \"\"\"\n    Pure static class used to parse all the route and scenario configuration parameters.\n    \"\"\"\n\n    @staticmethod\n    def parse_routes_file(route_filename, routes_subset=''):\n        \"\"\"\n        Returns a list of route configuration elements.\n        :param route_filename: the path to a set of routes.\n        :param single_route: If set, only this route shall be returned\n        :return: List of dicts containing the waypoints, id and town of the routes\n        \"\"\"\n        def get_routes_subset():\n            \"\"\"\n            The route subset can be indicated by single routes separated by commas,\n            or group of routes separated by dashes (or a combination of the two)\"\"\"\n            subset_ids = []\n            subset_groups = routes_subset.replace(\" \",\"\").split(',')\n            for group in subset_groups:\n                if \"-\" in group:\n                    # Group of route, iterate from start to end, making sure both ids exist\n                    start, end = group.split('-')\n                    found_start, found_end = (False, False)\n\n                    for route in tree.iter(\"route\"):\n                        route_id = route.attrib['id']\n                        if not found_start and route_id == start:\n                            found_start = True\n                        if not found_start and route_id == end:\n                            raise ValueError(f\"Malformed route subset '{group}', found the end id before the starting one\")\n                        if not found_end and found_start:\n                            if route_id in subset_ids:\n                                raise ValueError(f\"Found a repeated route with id '{route_id}'\")\n                            else:\n                                subset_ids.append(route_id)\n                            if route_id == end:\n                                found_end = True\n\n                    if not found_start:\n                        raise ValueError(f\"Couldn\\'t find the route with id '{start}' inside the given routes file\")\n                    if not found_end:\n                        raise ValueError(f\"Couldn\\'t find the route with id '{end}' inside the given routes file\")\n\n                else:\n                    # Just one route, get its id while making sure it exists\n\n                    found = False\n                    for route in tree.iter(\"route\"):\n                        route_id = route.attrib['id']\n                        if route_id == group:\n                            if route_id in subset_ids:\n                                raise ValueError(f\"Found a repeated route with id '{route_id}'\")\n                            else:\n                                subset_ids.append(route_id)\n                            found = True\n\n                    if not found:\n                        raise ValueError(f\"Couldn't find the route with id '{group}' inside the given routes file\")\n\n            subset_ids.sort(key=lambda k: int(k))\n            return subset_ids\n\n        route_configs = []\n        tree = ET.parse(route_filename)\n        if routes_subset:\n            subset_list = get_routes_subset()\n        for route in tree.iter(\"route\"):\n\n            route_id = route.attrib['id']\n            if routes_subset and route_id not in subset_list:\n                continue\n\n            route_config = RouteScenarioConfiguration()\n            route_config.town = route.attrib['town']\n            route_config.name = \"RouteScenario_{}\".format(route_id)\n            route_config.weather = RouteParser.parse_weather(route)\n\n            # The list of carla.Location that serve as keypoints on this route\n            positions = []\n            for position in route.find('waypoints').iter('position'):\n                positions.append(carla.Location(x=float(position.attrib['x']),\n                                                y=float(position.attrib['y']),\n                                                z=float(position.attrib['z'])))\n            route_config.keypoints = positions\n\n            # The list of ScenarioConfigurations that store the scenario's data\n            scenario_configs = []\n            for scenario in route.find('scenarios').iter('scenario'):\n                scenario_config = ScenarioConfiguration()\n                scenario_config.name = scenario.attrib.get('name')\n                scenario_config.type = scenario.attrib.get('type')\n\n                for elem in scenario.getchildren():\n                    if elem.tag == 'trigger_point':\n                        scenario_config.trigger_points.append(convert_elem_to_transform(elem))\n                    elif elem.tag == 'other_actor':\n                        scenario_config.other_actors.append(ActorConfigurationData.parse_from_node(elem, 'scenario'))\n                    else:\n                        scenario_config.other_parameters[elem.tag] = elem.attrib\n\n                scenario_configs.append(scenario_config)\n            route_config.scenario_configs = scenario_configs\n\n            route_configs.append(route_config)\n\n        return route_configs\n\n    @staticmethod\n    def parse_weather(route):\n        \"\"\"\n        Parses all the weather information as a list of [position, carla.WeatherParameters],\n        where the position represents a % of the route.\n        \"\"\"\n        weathers = []\n\n        weathers_elem = route.find(\"weathers\")\n        if weathers_elem is None:\n            return [[0, carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)]]\n\n        for weather_elem in weathers_elem.iter('weather'):\n            route_percentage = float(weather_elem.attrib['route_percentage'])\n\n            weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)  # Base weather\n            for weather_attrib in weather_elem.attrib:\n                if hasattr(weather, weather_attrib):\n                    setattr(weather, weather_attrib, float(weather_elem.attrib[weather_attrib]))\n                elif weather_attrib != 'route_percentage':\n                    print(f\"WARNING: Ignoring '{weather_attrib}', as it isn't a weather parameter\")\n\n            weathers.append([route_percentage, weather])\n\n        weathers.sort(key=lambda x: x[0])\n        return weathers\n\n    @staticmethod\n    def is_scenario_at_route(trigger_transform, route):\n        \"\"\"\n        Check if the scenario is affecting the route.\n        This is true if the trigger position is very close to any route point\n        \"\"\"\n        def is_trigger_close(trigger_transform, route_transform):\n            \"\"\"Check if the two transforms are similar\"\"\"\n            dx = trigger_transform.location.x - route_transform.location.x\n            dy = trigger_transform.location.y - route_transform.location.y\n            dz = trigger_transform.location.z - route_transform.location.z\n            dpos = math.sqrt(dx * dx + dy * dy)\n\n            dyaw = (float(trigger_transform.rotation.yaw) - route_transform.rotation.yaw) % 360\n\n            return dz < DIST_THRESHOLD and dpos < DIST_THRESHOLD \\\n                and (dyaw < ANGLE_THRESHOLD or dyaw > (360 - ANGLE_THRESHOLD))\n\n        for route_transform, _ in route:\n            if is_trigger_close(trigger_transform, route_transform):\n                return True\n\n        return False\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/leaderboard/utils/statistics_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module contains a statistics manager for the CARLA AD leaderboard\n\"\"\"\n\nfrom __future__ import print_function\n\nfrom dictor import dictor\nimport math\n\nfrom srunner.scenariomanager.traffic_events import TrafficEventType\n\nfrom leaderboard.utils.checkpoint_tools import fetch_dict, save_dict\n\nPENALTY_VALUE_DICT = {\n    # Traffic events that substract a set amount of points.\n    TrafficEventType.COLLISION_PEDESTRIAN: 0.5,\n    TrafficEventType.COLLISION_VEHICLE: 0.6,\n    TrafficEventType.COLLISION_STATIC: 0.65,\n    TrafficEventType.TRAFFIC_LIGHT_INFRACTION: 0.7,\n    TrafficEventType.STOP_INFRACTION: 0.8,\n    TrafficEventType.SCENARIO_TIMEOUT: 0.7,\n    TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE: 0.7\n}\nPENALTY_PERC_DICT = {\n    # Traffic events that substract a varying amount of points. This is the per unit value.\n    # 'increases' means that the higher the value, the higher the penalty.\n    # 'decreases' means that the ideal value is 100 and the lower the value, the higher the penalty.\n    TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION: [0, 'increases'],  # All route traversed through outside lanes is ignored\n    # TrafficEventType.MIN_SPEED_INFRACTION: [0.7, 'decreases'],\n    TrafficEventType.MIN_SPEED_INFRACTION: [0.7, 'unused'],\n}\n\nPENALTY_NAME_DICT = {\n    TrafficEventType.COLLISION_STATIC: 'collisions_layout',\n    TrafficEventType.COLLISION_PEDESTRIAN: 'collisions_pedestrian',\n    TrafficEventType.COLLISION_VEHICLE: 'collisions_vehicle',\n    TrafficEventType.TRAFFIC_LIGHT_INFRACTION: 'red_light',\n    TrafficEventType.STOP_INFRACTION: 'stop_infraction',\n    TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION: 'outside_route_lanes',\n    TrafficEventType.MIN_SPEED_INFRACTION: 'min_speed_infractions',\n    TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE: 'yield_emergency_vehicle_infractions',\n    TrafficEventType.SCENARIO_TIMEOUT: 'scenario_timeouts',\n    TrafficEventType.ROUTE_DEVIATION: 'route_dev',\n    TrafficEventType.VEHICLE_BLOCKED: 'vehicle_blocked',\n}\n\n# Limit the entry status to some values. Eligible should always be gotten from this table\nENTRY_STATUS_VALUES = ['Started', 'Finished', 'Rejected', 'Crashed', 'Invalid']\nELIGIBLE_VALUES = {'Started': False, 'Finished': True, 'Rejected': False, 'Crashed': False, 'Invalid': False}\n\n# Dictionary mapping a route failure with the 'entry status' and 'status'\nFAILURE_MESSAGES = {\n    \"Simulation\" : [\"Crashed\", \"Simulation crashed\"],\n    \"Sensors\": [\"Rejected\", \"Agent's sensors were invalid\"],\n    \"Agent_init\": [\"Started\", \"Agent couldn't be set up\"],\n    \"Agent_runtime\": [\"Started\", \"Agent crashed\"]\n}\n\nROUND_DIGITS = 3\nROUND_DIGITS_SCORE = 6\n\n\nclass RouteRecord():\n    def __init__(self):\n        self.index = -1\n        self.route_id = None\n        self.scenario_name = None\n        self.weather_id = None\n        self.save_name = None\n        self.status = 'Started'\n        self.num_infractions = 0\n        self.infractions = {}\n        for event_name in PENALTY_NAME_DICT.values():\n            self.infractions[event_name] = []\n        self.infractions['route_timeout'] = []\n\n        self.scores = {\n            'score_route': 0,\n            'score_penalty': 0,\n            'score_composed': 0\n        }\n\n        self.meta = {\n            'route_length': 0,\n            'duration_game': 0,\n            'duration_system': 0,\n        }\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        return vars(self)\n\n\nclass GlobalRecord():\n    def __init__(self):\n        self.index = -1\n        self.route_id = -1\n        self.status = 'Perfect'\n        self.infractions = {}\n        for event_name in PENALTY_NAME_DICT.values():\n            self.infractions[event_name] = 0\n        self.infractions['route_timeout'] = 0\n\n        self.scores_mean = {\n            'score_composed': 0,\n            'score_route': 0,\n            'score_penalty': 0\n        }\n        self.scores_std_dev = self.scores_mean.copy()\n\n        self.meta = {\n            \"total_length\": 0,\n            \"duration_game\": 0,\n            \"duration_system\": 0,\n            'exceptions': []\n        }\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        return vars(self)\n\nclass Checkpoint():\n\n    def __init__(self):\n        self.global_record = {}\n        self.progress = []\n        self.records = []\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        d = {}\n        d['global_record'] = self.global_record.to_json() if self.global_record else {}\n        d['progress'] = self.progress\n        d['records'] = []\n        d['records'] = [x.to_json() for x in self.records if x.index != -1]  # Index -1 = Route in progress\n\n        return d\n\n\nclass Results():\n\n    def __init__(self):\n        self.checkpoint = Checkpoint()\n        self.entry_status = \"Started\"\n        self.eligible = ELIGIBLE_VALUES[self.entry_status]\n        self.sensors = []\n        self.values = []\n        self.labels = []\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        d = {}\n        d['_checkpoint'] = self.checkpoint.to_json()\n        d['entry_status'] = self.entry_status\n        d['eligible'] = self.eligible\n        d['sensors'] = self.sensors\n        d['values'] = self.values\n        d['labels'] = self.labels\n\n        return d\n\n\ndef to_route_record(record_dict):\n    record = RouteRecord()\n    for key, value in record_dict.items():\n        setattr(record, key, value)\n\n    return record\n\n\ndef compute_route_length(route):\n    route_length = 0.0\n    previous_location = None\n\n    for transform, _ in route:\n        location = transform.location\n        if previous_location:\n            dist_vec = location - previous_location\n            route_length += dist_vec.length()\n        previous_location = location\n\n    return route_length\n\n\n\nclass StatisticsManager(object):\n\n    \"\"\"\n    This is the statistics manager for the CARLA leaderboard.\n    It gathers data at runtime via the scenario evaluation criteria.\n    \"\"\"\n\n    def __init__(self, endpoint, debug_endpoint):\n        self._scenario = None\n        self._route_length = 0\n        self._total_routes = 0\n        self._results = Results()\n        self._endpoint = endpoint\n        self._debug_endpoint = debug_endpoint\n\n    def add_file_records(self, endpoint):\n        \"\"\"Reads a file and saves its records onto the statistics manager\"\"\"\n        data = fetch_dict(endpoint)\n\n        if data:\n            route_records = dictor(data, '_checkpoint.records')\n            if route_records:\n                for record in route_records:\n                    self._results.checkpoint.records.append(to_route_record(record))\n\n    def clear_records(self):\n        \"\"\"Cleanes up the file\"\"\"\n        if not self._endpoint.startswith(('http:', 'https:', 'ftp:')):\n            with open(self._endpoint, 'w') as fd:\n                fd.truncate(0)\n\n    def sort_records(self):\n        \"\"\"Sorts the route records according to their route id (This being i.e RouteScenario0_rep0)\"\"\"\n        self._results.checkpoint.records.sort(key=lambda x: (\n            int(x.route_id.split('_')[1]),\n            int(x.route_id.split('_rep')[-1])\n        ))\n\n        for i, record in enumerate(self._results.checkpoint.records):\n            record.index = i\n\n    def write_live_results(self, index, ego_speed, ego_control, ego_location):\n        \"\"\"Writes live results\"\"\"\n        route_record = self._results.checkpoint.records[index]\n\n        all_events = []\n        if self._scenario:\n            for node in self._scenario.get_criteria():\n                all_events.extend(node.events)\n\n        all_events.sort(key=lambda e: e.get_frame(), reverse=True)\n\n        with open(self._debug_endpoint, 'w') as f:\n            f.write(\"Route id: {}\\n\\n\"\n                    \"Scenario: {}\\n\\n\"\n                    \"Town name: {}\\n\\n\"\n                    \"Weather id: {}\\n\\n\"\n                    \"Save name: {}\\n\\n\"\n                    \"Scores:\\n\"\n                    \"    Driving score:      {:.3f}\\n\"\n                    \"    Route completion:   {:.3f}\\n\"\n                    \"    Infraction penalty: {:.3f}\\n\\n\"\n                    \"    Route length:    {:.3f}\\n\"\n                    \"    Game duration:   {:.3f}\\n\"\n                    \"    System duration: {:.3f}\\n\\n\"\n                    \"Ego:\\n\"\n                    \"    Throttle:           {:.3f}\\n\"\n                    \"    Brake:              {:.3f}\\n\"\n                    \"    Steer:              {:.3f}\\n\\n\"\n                    \"    Speed:           {:.3f} km/h\\n\\n\"\n                    \"    Location:           ({:.3f} {:.3f} {:.3f})\\n\\n\"\n                    \"Total infractions: {}\\n\"\n                    \"Last 5 infractions:\\n\".format(\n                        route_record.route_id,\n                        route_record.scenario_name,\n                        route_record.town_name,\n                        route_record.weather_id,\n                        route_record.save_name,\n                        route_record.scores[\"score_composed\"],\n                        route_record.scores[\"score_route\"],\n                        route_record.scores[\"score_penalty\"],\n                        route_record.meta[\"route_length\"],\n                        route_record.meta[\"duration_game\"],\n                        route_record.meta[\"duration_system\"],\n                        ego_control.throttle,\n                        ego_control.brake,\n                        ego_control.steer,\n                        ego_speed * 3.6,\n                        ego_location.x,\n                        ego_location.y,\n                        ego_location.z,\n                        route_record.num_infractions\n                    )\n                )\n            for e in all_events[:5]:\n                # Prevent showing the ROUTE_COMPLETION event.\n                event_type = e.get_type()\n                if event_type == TrafficEventType.ROUTE_COMPLETION:\n                    continue\n                string = \"    \" + str(e.get_type()).replace(\"TrafficEventType.\", \"\")\n                if event_type in PENALTY_VALUE_DICT:\n                    string += \" (penalty: \" + str(PENALTY_VALUE_DICT[event_type]) + \")\\n\"\n                elif event_type in PENALTY_PERC_DICT:\n                    string += \" (value: \" + str(round(e.get_dict()['percentage'], 3)) + \"%)\\n\"\n\n                f.write(string)\n\n    def save_sensors(self, sensors):\n        self._results.sensors = sensors\n\n    def save_entry_status(self, entry_status):\n        if entry_status not in ENTRY_STATUS_VALUES:\n            raise ValueError(\"Found an invalid value for 'entry_status'\")\n        self._results.entry_status = entry_status\n        self._results.eligible = ELIGIBLE_VALUES[entry_status]\n\n    def save_progress(self, route_index, total_routes):\n        self._results.checkpoint.progress = [route_index, total_routes]\n        self._total_routes = total_routes\n\n    def create_route_data(self, route_id, scenario_name, weather_id, save_name, town_name, index):\n        \"\"\"\n        Creates the basic route data.\n        This is done at the beginning to ensure the data is saved, even if a crash occurs\n        \"\"\"\n        route_record = RouteRecord()\n        route_record.route_id = route_id\n        route_record.scenario_name = scenario_name\n        route_record.weather_id = weather_id\n        route_record.save_name = save_name\n        route_record.town_name = town_name\n\n        # Check if we have to overwrite an element (when resuming), or create a new one\n        route_records = self._results.checkpoint.records\n        if index < len(route_records):\n            self._results.checkpoint.records[index] = route_record\n        else:\n            self._results.checkpoint.records.append(route_record)\n\n    def set_scenario(self, scenario):\n        \"\"\"Sets the scenario from which the statistics will be taken\"\"\"\n        self._scenario = scenario\n        self._route_length = round(compute_route_length(scenario.route), ROUND_DIGITS)\n\n    def remove_scenario(self):\n        \"\"\"Removes the scenario\"\"\"\n        self._scenario = None\n        self._route_length = 0\n\n    def compute_route_statistics(self, route_index, duration_time_system=-1, duration_time_game=-1, failure_message=\"\"):\n        \"\"\"\n        Compute the current statistics by evaluating all relevant scenario criteria.\n        Failure message will not be empty if an external source has stopped the simulations (i.e simulation crash).\n        For the rest of the cases, it will be filled by this function depending on the criteria.\n        \"\"\"\n        def set_infraction_message():\n            infraction_name = PENALTY_NAME_DICT[event.get_type()]\n            route_record.infractions[infraction_name].append(event.get_message())\n\n        def set_score_penalty(score_penalty):\n            event_value = event.get_dict()['percentage']\n            penalty_value, penalty_type = PENALTY_PERC_DICT[event.get_type()]\n            if penalty_type == \"decreases\":\n                score_penalty *= (1 - (1 - penalty_value) * (1 - event_value / 100))\n            elif penalty_type == \"increases\":\n                score_penalty *= (1 - (1 - penalty_value) * event_value / 100)\n            elif penalty_type == \"unused\":\n                pass\n            else:\n                raise ValueError(\"Found a criteria with an unknown penalty type\")\n            return score_penalty\n\n        route_record = self._results.checkpoint.records[route_index]\n        route_record.index = route_index\n\n        target_reached = False\n        score_penalty = 1.0\n        score_route = 0.0\n        for event_name in PENALTY_NAME_DICT.values():\n            route_record.infractions[event_name] = []\n\n        # Update the route meta\n        route_record.meta['route_length'] = self._route_length\n        route_record.meta['duration_game'] = round(duration_time_game, ROUND_DIGITS)\n        route_record.meta['duration_system'] = round(duration_time_system, ROUND_DIGITS)\n\n        # Update the route infractions\n        if self._scenario:\n            if self._scenario.timeout_node.timeout:\n                route_record.infractions['route_timeout'].append('Route timeout.')\n                failure_message = \"Agent timed out\"\n\n            for node in self._scenario.get_criteria():\n                for event in node.events:\n                    # Traffic events that substract a set amount of points\n                    if event.get_type() in PENALTY_VALUE_DICT:\n                        score_penalty *= PENALTY_VALUE_DICT[event.get_type()]\n                        set_infraction_message()\n\n                    # Traffic events that substract a varying amount of points\n                    elif event.get_type() in PENALTY_PERC_DICT:\n                        score_penalty = set_score_penalty(score_penalty)\n                        set_infraction_message()\n\n                    # Traffic events that stop the simulation\n                    elif event.get_type() == TrafficEventType.ROUTE_DEVIATION:\n                        failure_message = \"Agent deviated from the route\"\n                        set_infraction_message()\n\n                    elif event.get_type() == TrafficEventType.VEHICLE_BLOCKED:\n                        failure_message = \"Agent got blocked\"\n                        set_infraction_message()\n\n                    elif event.get_type() == TrafficEventType.ROUTE_COMPLETION:\n                        score_route = event.get_dict()['route_completed']\n                        target_reached = score_route >= 100\n\n        # Update route scores\n        route_record.scores['score_route'] = round(score_route, ROUND_DIGITS_SCORE)\n        route_record.scores['score_penalty'] = round(score_penalty, ROUND_DIGITS_SCORE)\n        route_record.scores['score_composed'] = round(max(score_route * score_penalty, 0.0), ROUND_DIGITS_SCORE)\n\n        # Update result\n        route_record.num_infractions = sum([len(route_record.infractions[key]) for key in route_record.infractions])\n\n        if target_reached:\n            route_record.status = 'Completed' if route_record.num_infractions > 0 else 'Perfect'\n        else:\n            route_record.status = 'Failed'\n            if failure_message:\n                route_record.status += ' - ' + failure_message\n\n        # Add the new data, or overwrite a previous result (happens when resuming the simulation)\n        record_len = len(self._results.checkpoint.records)\n        if route_index == record_len:\n            self._results.checkpoint.records.append(route_record)\n        elif route_index < record_len:\n            self._results.checkpoint.records[route_index] = route_record\n        else:\n            raise ValueError(\"Not enough entries in the route record\")\n\n    def compute_global_statistics(self):\n        \"\"\"Computes and saves the global statistics of the routes\"\"\"\n        def get_infractions_value(route_record, key):\n            # Special case for the % based criteria. Extract the meters from the message. Very ugly, but it works\n            if key == PENALTY_NAME_DICT[TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION]:\n                if not route_record.infractions[key]:\n                    return 0.0\n                return float(route_record.infractions[key][0].split(\" \")[8])/1000\n\n            return len(route_record.infractions[key])\n\n        global_record = GlobalRecord()\n        global_result = global_record.status\n\n        route_records = self._results.checkpoint.records\n\n        # Calculate the score's means and result\n        for route_record in route_records:\n\n            global_record.scores_mean['score_route'] += route_record.scores['score_route'] / self._total_routes\n            global_record.scores_mean['score_penalty'] += route_record.scores['score_penalty'] / self._total_routes\n            global_record.scores_mean['score_composed'] += route_record.scores['score_composed'] / self._total_routes\n\n            global_record.meta['total_length'] += route_record.meta['route_length']\n            global_record.meta['duration_game'] += route_record.meta['duration_game']\n            global_record.meta['duration_system'] += route_record.meta['duration_system']\n\n            # Downgrade the global result if need be ('Perfect' -> 'Completed' -> 'Failed'), and record the failed routes\n            route_result = 'Failed' if 'Failed' in route_record.status else route_record.status\n            if route_result == 'Failed':\n                global_record.meta['exceptions'].append((route_record.route_id,\n                                                         route_record.index,\n                                                         route_record.status))\n                global_result = route_result\n            elif global_result == 'Perfect' and route_result != 'Perfect':\n                global_result = route_result\n\n        for item in global_record.scores_mean:\n            global_record.scores_mean[item] = round(global_record.scores_mean[item], ROUND_DIGITS_SCORE)\n        global_record.status = global_result\n\n        # Calculate the score's standard deviation\n        if self._total_routes == 1:\n            for key in global_record.scores_std_dev:\n                global_record.scores_std_dev[key] = 0\n        else:\n            for route_record in route_records:\n                for key in global_record.scores_std_dev:\n                    diff = route_record.scores[key] - global_record.scores_mean[key]\n                    global_record.scores_std_dev[key] += math.pow(diff, 2)\n\n            for key in global_record.scores_std_dev:\n                value = round(math.sqrt(global_record.scores_std_dev[key] / float(self._total_routes - 1)), ROUND_DIGITS)\n                global_record.scores_std_dev[key] = value\n\n        # Calculate the number of infractions per km\n        km_driven = 0\n        for route_record in route_records:\n            km_driven += route_record.meta['route_length'] / 1000 * route_record.scores['score_route'] / 100\n            for key in global_record.infractions:\n                global_record.infractions[key] += get_infractions_value(route_record, key)\n        km_driven = max(km_driven, 0.001)\n\n        for key in global_record.infractions:\n            # Special case for the % based criteria.\n            if key != PENALTY_NAME_DICT[TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION]:\n                global_record.infractions[key] /= km_driven\n            global_record.infractions[key] = round(global_record.infractions[key], ROUND_DIGITS)\n\n        # Save the global records\n        self._results.checkpoint.global_record = global_record\n\n        # Change the values and labels. These MUST HAVE A MATCHING ORDER\n        self._results.values = [\n            str(global_record.scores_mean['score_composed']),\n            str(global_record.scores_mean['score_route']),\n            str(global_record.scores_mean['score_penalty']),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.COLLISION_PEDESTRIAN]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.COLLISION_VEHICLE]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.COLLISION_STATIC]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.TRAFFIC_LIGHT_INFRACTION]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.STOP_INFRACTION]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.ROUTE_DEVIATION]]),\n            str(global_record.infractions['route_timeout']),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.VEHICLE_BLOCKED]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.SCENARIO_TIMEOUT]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.MIN_SPEED_INFRACTION]]),\n        ]\n\n        self._results.labels = [\n            \"Avg. driving score\",\n            \"Avg. route completion\",\n            \"Avg. infraction penalty\",\n            \"Collisions with pedestrians\",\n            \"Collisions with vehicles\",\n            \"Collisions with layout\",\n            \"Red lights infractions\",\n            \"Stop sign infractions\",\n            \"Off-road infractions\",\n            \"Route deviations\",\n            \"Route timeouts\",\n            \"Agent blocked\",\n            \"Yield emergency vehicles infractions\",\n            \"Scenario timeouts\",\n            \"Min speed infractions\"\n        ]\n\n        # Change the entry status and eligible\n        entry_status = 'Finished'\n        for route_record in route_records:\n            route_status = route_record.status\n            if 'Simulation crashed' in route_status:\n                entry_status = 'Crashed'\n            elif \"Agent's sensors were invalid\" in route_status:\n                entry_status = 'Rejected'\n\n        self.save_entry_status(entry_status)\n\n    def validate_and_write_statistics(self, sensors_initialized, crashed):\n        \"\"\"\n        Makes sure that all the relevant data is there.\n        Changes the 'entry status' to 'Invalid' if this isn't the case\n        \"\"\"\n        error_message = \"\"\n        if sensors_initialized and not self._results.sensors:\n            error_message = \"Missing 'sensors' data\"\n\n        elif not self._results.values:\n            error_message = \"Missing 'values' data\"\n\n        elif self._results.entry_status == 'Started':\n            error_message = \"'entry_status' has the 'Started' value\"\n\n        else:\n            global_records = self._results.checkpoint.global_record\n            progress = self._results.checkpoint.progress\n            route_records = self._results.checkpoint.records\n\n            if not global_records:\n                error_message = \"Missing 'global_records' data\"\n\n            elif not progress:\n                error_message = \"Missing 'progress' data\"\n\n            elif not crashed and (progress[0] != progress[1] or progress[0] != len(route_records)):\n                error_message = \"'progress' data doesn't match its expected value\"\n\n            else:\n                for record in route_records:\n                    if record.status == 'Started':\n                        error_message = \"Found a route record with missing data\"\n                        break\n\n        if error_message:\n            print(\"\\n\\033[91mThe statistics are badly formed. Setting their status to 'Invalid':\")\n            print(\"> {}\\033[0m\\n\".format(error_message))\n\n            self.save_entry_status('Invalid')\n\n        self.write_statistics()\n\n    def write_statistics(self):\n        \"\"\"\n        Writes the results into the endpoint. Meant to be used only for partial evaluations,\n        use 'validate_and_write_statistics' for the final one as it only validates the data.\n        \"\"\"\n        save_dict(self._endpoint, self._results.to_json())\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/requirements.txt",
    "content": "dictor\nrequests\nopencv-python==4.2.0.32\npygame\ntabulate\npexpect\ntransforms3d\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/run_leaderboard.sh",
    "content": " #!/bin/bash\n\nexport TEAM_AGENT=$LEADERBOARD_ROOT/leaderboard/autoagents/human_agent.py\n\nexport ROUTES=$LEADERBOARD_ROOT/data/routes_devtest.xml\nexport ROUTES_SUBSET=0\nexport REPETITIONS=1\n\nexport DEBUG_CHALLENGE=1\nexport CHALLENGE_TRACK_CODENAME=SENSORS\nexport CHECKPOINT_ENDPOINT=\"${LEADERBOARD_ROOT}/results.json\"\nexport RECORD_PATH=\nexport RESUME=\n\n#!/bin/bash\n\npython3 ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \\\n--routes=${ROUTES} \\\n--routes-subset=${ROUTES_SUBSET} \\\n--repetitions=${REPETITIONS} \\\n--track=${CHALLENGE_TRACK_CODENAME} \\\n--checkpoint=${CHECKPOINT_ENDPOINT} \\\n--debug-checkpoint=${DEBUG_CHECKPOINT_ENDPOINT} \\\n--agent=${TEAM_AGENT} \\\n--agent-config=${TEAM_CONFIG} \\\n--debug=${DEBUG_CHALLENGE} \\\n--record=${RECORD_PATH} \\\n--resume=${RESUME}"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/Dockerfile.master",
    "content": "FROM nvidia/cuda:11.7.1-cudnn8-devel-ubuntu20.04\n\nARG HTTP_PROXY\nARG HTTPS_PROXY\nARG http_proxy\n\nRUN apt-get update && apt-get install --reinstall -y locales && locale-gen en_US.UTF-8 && rm -rf /var/lib/apt/lists/*\nENV LANG en_US.UTF-8\nENV LANGUAGE en_US\nENV LC_ALL en_US.UTF-8\nENV DEBIAN_FRONTEND=noninteractive\n\n# Install dependencies\nRUN apt-get update && apt-get install -y --no-install-recommends \\\n    build-essential \\\n    cmake \\\n    git \\\n    curl \\\n    vim \\\n    ca-certificates \\\n    libjpeg-dev \\\n    libpng16-16 \\\n    libtiff5 \\\n    libpng-dev \\\n    python3-dev \\\n    python3-pip \\\n    python3-setuptools && \\\n    python3 -m pip install --upgrade pip && \\\n    rm -rf /var/lib/apt/lists/*\n\n# Installing conda\nRUN curl -o ~/miniconda.sh -LO https://repo.continuum.io/miniconda/Miniconda3-latest-Linux-x86_64.sh  && \\\n    chmod +x ~/miniconda.sh && \\\n    ~/miniconda.sh -b -p /opt/conda && \\\n    rm ~/miniconda.sh && \\\n    /opt/conda/bin/conda clean -ya && \\\n    /opt/conda/bin/conda create -n python37 python=3.7 numpy networkx scipy six requests\n\nENV PATH \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\":\"/opt/conda/envs/python37/bin\":\"/opt/conda/envs/bin\":$PATH\n\n# Copy the files into the docker\nWORKDIR /workspace\n\nENV CARLA_ROOT \"/workspace/CARLA\"\nENV SCENARIO_RUNNER_ROOT \"/workspace/scenario_runner\"\nENV LEADERBOARD_ROOT \"/workspace/leaderboard\"\nENV TEAM_CODE_ROOT \"/workspace/team_code\"\n\nCOPY PythonAPI ${CARLA_ROOT}/PythonAPI\nCOPY scenario_runner ${SCENARIO_RUNNER_ROOT}\nCOPY leaderboard ${LEADERBOARD_ROOT}\nCOPY team_code ${TEAM_CODE_ROOT}\n\nRUN pip3 install -r ${SCENARIO_RUNNER_ROOT}/requirements.txt\nRUN pip3 install -r ${LEADERBOARD_ROOT}/requirements.txt\n\nRUN mkdir -p /workspace/results\nRUN chmod +x /workspace/leaderboard/run_leaderboard.sh\n\nENV PYTHONPATH \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\":\"${SCENARIO_RUNNER_ROOT}\":\"${CARLA_ROOT}/PythonAPI/carla\":\"${LEADERBOARD_ROOT}\":\"${TEAM_CODE_ROOT}\":${PYTHONPATH}\n\n############################################################################################\n####                     BEGINNING OF AGENT SPECIFIC COMMANDS                           ####\n############################################################################################\n\nENV TEAM_AGENT ${TEAM_CODE_ROOT}/npc_agent.py\n# ENV TEAM_CONFIG ${TEAM_CODE_ROOT}/YOUR_CONFIG_FILE\nENV CHALLENGE_TRACK_CODENAME SENSORS\n\n############################################################################################\n####                        END OF AGENT SPECIFIC COMMANDS                              ####\n############################################################################################\n\nENV ROUTES ${LEADERBOARD_ROOT}/data/routes_training.xml\nENV REPETITIONS 1\nENV CHECKPOINT_ENDPOINT /workspace/results/results.json\nENV DEBUG_CHALLENGE 0\n\nENV HTTP_PROXY \"\"\nENV HTTPS_PROXY \"\"\nENV http_proxy \"\"\nENV https_proxy \"\"\n\nCMD [\"/bin/bash\"]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/Dockerfile.ros",
    "content": "ARG ROS_DISTRO\n\nFROM ros:$ROS_DISTRO-ros-base\n\nWORKDIR /workspace\n\nENV DEBIAN_FRONTEND \"noninteractive\"\n\nRUN apt-get update; \\\n  if [ \"$ROS_DISTRO\" = \"melodic\" ]; then \\\n    apt-get install -y --no-install-recommends \\\n      ros-${ROS_DISTRO}-rosbridge-suite \\\n      python-setuptools \\\n      python3-setuptools \\\n      python-wheel \\\n      python3-wheel \\\n      python-pip \\\n      python3-pip \\\n      && python2 -m pip install --upgrade pip \\\n      && python3 -m pip install --upgrade pip; \\\n  elif [ \"$ROS_DISTRO\" = \"noetic\" ]; then \\\n    apt-get install -y --no-install-recommends \\\n      ros-${ROS_DISTRO}-rosbridge-suite \\\n      python-is-python3 \\\n      python3-setuptools \\\n      python3-wheel \\\n      python3-pip \\\n      && python3 -m pip install --upgrade pip; \\\n  elif [ \"$ROS_DISTRO\" = \"foxy\" ]; then \\\n    apt-get install -y --no-install-recommends \\\n      # TODO: This should be installed by rosdep\n      python3-opencv \\\n      python3-setuptools \\\n      python3-wheel \\\n      python3-pip \\\n      && python3 -m pip install --upgrade pip; \\\n  fi; \\\n  rm -rf /var/lib/apt/lists/*\n\nENV CARLA_ROOT \"/workspace/CARLA\"\nENV SCENARIO_RUNNER_ROOT \"/workspace/scenario_runner\"\nENV LEADERBOARD_ROOT \"/workspace/leaderboard\"\nENV CARLA_ROS_BRIDGE_ROOT \"/workspace/carla_ros_bridge\"\nENV TEAM_CODE_ROOT \"/workspace/team_code\"\n\nCOPY PythonAPI ${CARLA_ROOT}/PythonAPI\nCOPY scenario_runner ${SCENARIO_RUNNER_ROOT}\nCOPY leaderboard ${LEADERBOARD_ROOT}\n\nCOPY carla_ros_bridge/carla_ros_bridge ${CARLA_ROS_BRIDGE_ROOT}/src/carla_ros_bridge\nCOPY carla_ros_bridge/carla_common ${CARLA_ROS_BRIDGE_ROOT}/src/carla_common\nCOPY carla_ros_bridge/carla_msgs ${CARLA_ROS_BRIDGE_ROOT}/src/carla_msgs\nCOPY carla_ros_bridge/ros_compatibility ${CARLA_ROS_BRIDGE_ROOT}/src/ros_compatibility\n\nCOPY team_code ${TEAM_CODE_ROOT}\n\n# Install carla ros bridge\nRUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \\\n  apt-get update && rosdep update; \\\n  cd /workspace/carla_ros_bridge; \\\n  rm -rf build devel install log; \\\n  rosdep install --from-paths src --ignore-src -r -y; \\\n  if [ \"$ROS_VERSION\" = \"1\" ]; then \\\n    catkin_make install -DCMAKE_INSTALL_PREFIX=/opt/ros/$ROS_DISTRO; \\\n  else \\\n    colcon build; \\\n  fi; \\\n  rm -rf build devel log; \\\n  rm -rf /var/lib/apt/lists/*'\n  #colcon build --merge-install --install-base /opt/ros/$ROS_DISTRO; \\\n  #catkin_make install --only-pkg-with-deps carla_ros_bridge -DCMAKE_INSTALL_PREFIX=/opt/ros/melodic'\n\n# Install agent\nRUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \\\n  apt-get update && rosdep update; \\\n  cd /workspace/team_code; \\\n  rm -rf build devel install log; \\\n  rosdep install --from-paths src --ignore-src -r -y; \\\n  if [ \"$ROS_VERSION\" = \"1\" ]; then \\\n    catkin_make install; \\\n  else \\\n    colcon build; \\\n  fi; \\\n  rm -rf build devel log; \\\n  rm -rf /var/lib/apt/lists/*'\n\nRUN mkdir -p /workspace/results\nRUN chmod +x /workspace/leaderboard/run_leaderboard.sh\n\nENV PYTHONPATH \"${CARLA_ROOT}/PythonAPI/carla\":\"${SCENARIO_RUNNER_ROOT}\":\"${LEADERBOARD_ROOT}\":${PYTHONPATH}\n\nRUN if [ \"$ROS_DISTRO\" = \"melodic\" ]; then \\\n    echo \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py2.7.egg\" > /usr/local/lib/python2.7/dist-packages/carla.pth; \\\n    echo \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\" > /usr/local/lib/python3.6/dist-packages/carla.pth; \\\n  else \\\n    echo \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\" > /usr/local/lib/python3.8/dist-packages/carla.pth; \\\n  fi\n\nRUN pip3 install \\\n     transforms3d \\\n     roslibpy \\\n     pexpect \\\n     networkx \\\n     numpy \\\n     py_trees==0.8.3 \\\n     psutil \\\n     shapely \\\n     six \\\n     dictor \\\n     requests \\\n     ephem \\\n     tabulate \\\n     simple-watchdog-timer\n\n############################################################################################\n####                     BEGINNING OF AGENT SPECIFIC COMMANDS                           ####\n############################################################################################\n\nENV TEAM_AGENT ${TEAM_CODE_ROOT}/my_ros_agent.py\nENV CHALLENGE_TRACK_CODENAME MAP\n\n############################################################################################\n####                        END OF AGENT SPECIFIC COMMANDS                              ####\n############################################################################################\n\nENV ROUTES ${LEADERBOARD_ROOT}/data/routes_training.xml\nENV REPETITIONS 1\nENV CHECKPOINT_ENDPOINT /workspace/results/results.json\nENV DEBUG_CHALLENGE 0\n\n# Agent sources\nRUN /bin/echo \\\n  'source /opt/ros/$ROS_DISTRO/setup.bash; \\\n  if [ \"$ROS_VERSION\" = \"2\" ]; then \\\n    source $CARLA_ROS_BRIDGE_ROOT/install/setup.bash; \\\n  fi; \\\n  source $TEAM_CODE_ROOT/install/setup.bash;' >> ${HOME}/agent_sources.sh\n\nCOPY agent_entrypoint.sh /\nENTRYPOINT [\"/agent_entrypoint.sh\"]\n\nCMD [\"/bin/bash\"]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/agent_entrypoint.sh",
    "content": "#!/bin/bash\nset -e\n\nsource \"${HOME}/agent_sources.sh\"\n\nexec \"$@\""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/code_check_and_formatting.sh",
    "content": "#!/bin/bash\n\nautopep8_params=\"--in-place --max-line-length=120\"\npylint_params=\"--rcfile=.pylintrc\"\n\nfiles=`find leaderboard/ -type f -name \"*.py\"`\nfor file in ${files[@]}\ndo\n  autopep8 $file ${autopep8_params}\n  pylint --rcfile=.pylintrc ${pylint_params} $file\ndone\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/make_docker.sh",
    "content": "#!/bin/bash\n\nDOC_STRING=\"Build agent leadearboard image.\"\n\nUSAGE_STRING=$(cat <<- END\nUsage: $0 [-h|--help] [-r|--ros-distro ROS_DISTRO]\n\nThe following ROS distributions are supported:\n    * melodic\n    * noetic\n    * foxy\nEND\n)\n\nusage() { echo \"$DOC_STRING\"; echo \"$USAGE_STRING\"; exit 1; }\n\nROS_DISTRO=\"\"\n\nwhile [[ $# -gt 0 ]]; do\n  case \"$1\" in\n    -r |--ros-distro )\n      ROS_DISTRO=$2\n      if [ \"$ROS_DISTRO\" != \"melodic\" ] && [ \"$ROS_DISTRO\" != \"noetic\" ] && [ \"$ROS_DISTRO\" != \"foxy\" ]; then\n        usage\n      fi\n      shift 2 ;;\n    -h | --help )\n      usage\n      ;;\n    * )\n      shift ;;\n  esac\ndone\n\nif [ -z \"$CARLA_ROOT\" ]; then\n  echo \"Error $CARLA_ROOT is empty. Set \\$CARLA_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ -z \"$SCENARIO_RUNNER_ROOT\" ]; then\n  echo \"Error $SCENARIO_RUNNER_ROOT is empty. Set \\$SCENARIO_RUNNER_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ ! -z \"$ROS_DISTRO\" ] && [ -z $CARLA_ROS_BRIDGE_ROOT ]; then\n  echo \"Error $CARLA_ROS_BRIDGE_ROOT is empty. Set \\$CARLA_ROS_BRIDGE_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ -z \"$LEADERBOARD_ROOT\" ]; then\n  echo \"Error $LEADERBOARD_ROOT is empty. Set \\$LEADERBOARD_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ -z \"$TEAM_CODE_ROOT\" ]; then\n  echo \"Error $TEAM_CODE_ROOT is empty. Set \\$TEAM_CODE_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nrm -fr .lbtmp\nmkdir -p .lbtmp\n\necho \"Copying CARLA Python API\"\ncp -fr ${CARLA_ROOT}/PythonAPI  .lbtmp\nmv .lbtmp/PythonAPI/carla/dist/carla*-py2*.egg .lbtmp/PythonAPI/carla/dist/carla-leaderboard-py2.7.egg\nmv .lbtmp/PythonAPI/carla/dist/carla*-py3*.egg .lbtmp/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\n\necho \"Copying Scenario Runner\"\ncp -fr ${SCENARIO_RUNNER_ROOT}/ .lbtmp\nrm -fr .lbtmp/scenario_runner/.git\n\necho \"Copying Leaderboard\"\ncp -fr ${LEADERBOARD_ROOT}/ .lbtmp\nrm -fr .lbtmp/leaderboard/.git\n\nif [ ! -z \"$ROS_DISTRO\" ]; then\n  echo \"Copying ROS Bridge\"\n  cp -fr ${CARLA_ROS_BRIDGE_ROOT}/ .lbtmp/carla_ros_bridge\nfi\n\necho \"Copying team code folder\"\ncp -fr ${TEAM_CODE_ROOT}/ .lbtmp/team_code\n\ncp ${LEADERBOARD_ROOT}/scripts/agent_entrypoint.sh .lbtmp/agent_entrypoint.sh\n\necho \"Building docker\"\n# build docker image\nif [ -z \"$ROS_DISTRO\" ]; then\n  docker build \\\n    --force-rm  \\\n    -t leaderboard-user \\\n    -f ${LEADERBOARD_ROOT}/scripts/Dockerfile.master .lbtmp\nelse\n  docker build \\\n    --force-rm  \\\n    -t leaderboard-user:ros-$ROS_DISTRO \\\n    -f ${LEADERBOARD_ROOT}/scripts/Dockerfile.ros .lbtmp \\\n    --build-arg ROS_DISTRO=$ROS_DISTRO\nfi\n\nrm -fr .lbtmp\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/manage_scenarios.py",
    "content": "import argparse\nfrom argparse import RawTextHelpFormatter\nimport math\n\nimport carla\n\nfrom leaderboard.utils.checkpoint_tools import fetch_dict\nfrom leaderboard.utils.route_parser import DIST_THRESHOLD\n\nSCENARIO_COLOR = {\n    \"Scenario1\": [carla.Color(255, 0, 0), \"Red\"],\n    \"Scenario2\": [carla.Color(0, 255, 0), \"Green\"],\n    \"Scenario3\": [carla.Color(0, 0, 255), \"Blue\"],\n    \"Scenario4\": [carla.Color(255, 100, 0), \"Orange\"],\n    \"Scenario5\": [carla.Color(0, 255, 100), \"Blueish green\"],\n    \"Scenario6\": [carla.Color(100, 0, 255), \"Purple\"],\n    \"Scenario7\": [carla.Color(255, 100, 255), \"Pink\"],\n    \"Scenario8\": [carla.Color(255, 255, 100), \"Yellow\"],\n    \"Scenario9\": [carla.Color(100, 255, 255), \"Light Blue\"], \n    \"Scenario10\": [carla.Color(100, 100, 100), \"Gray\"]\n}\n\nDEBUG_HEIGHT_INTERVAL = 0.3\n\ndef get_scenario_transform(scenario_dict):\n    return carla.Transform(\n        carla.Location(\n            float(scenario_dict['transform']['x']),\n            float(scenario_dict['transform']['y']),\n            float(scenario_dict['transform']['z'])\n        ),\n        carla.Rotation(\n            float(scenario_dict['transform']['pitch']),\n            float(scenario_dict['transform']['yaw']),\n            0\n        )\n    )\n\ndef get_color_validity(waypoint_transform, scenario_transform, scenario_type, scenario_index, debug):\n    \"\"\"\n    Uses the same condition as in route_scenario to see if they will\n    be differentiated\n    \"\"\"\n    ANGLE_THRESHOLD = 10\n\n    dx = float(waypoint_transform.location.x) - scenario_transform.location.x\n    dy = float(waypoint_transform.location.y) - scenario_transform.location.y\n    dz = float(waypoint_transform.location.z) - scenario_transform.location.z\n    dpos = math.sqrt(dx * dx + dy * dy + dz * dz)\n    dyaw = (float(waypoint_transform.rotation.yaw) - scenario_transform.rotation.yaw) % 360\n\n    if dpos > DIST_THRESHOLD:\n        if not debug:\n            print(\"WARNING: Found a scenario with the wrong position \"\n                  \"(Type: {}, Index: {})\".format(scenario_type, scenario_index))\n        return carla.Color(255, 0, 0)\n    if dyaw > ANGLE_THRESHOLD and dyaw < (360 - ANGLE_THRESHOLD):\n        if not debug:\n            print(\"WARNING: Found a scenario with the wrong orientation \"\n                  \"(Type: {}, Index: {})\".format(scenario_type, scenario_index))\n        return carla.Color(0, 0, 255)\n    return carla.Color(0, 255, 0)\n\n\ndef create_scenarios(world, town_data, tmap, scenarios, debug):\n    \"\"\"\n    Creates new S7 to S10 by moving 5 meters backwards from an already existing S4.\n    They have to be manually added to the json file but information is given to simplify that process\n    \"\"\"\n    for scenario_data in town_data:\n        # Get the desired scenario data\n        scenario_type = scenario_data[\"scenario_type\"]\n        if scenario_type not in scenarios:\n            continue\n\n        number = float(scenario_type[8:])\n        debug_loc_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number)\n        debug_str_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number + 0.1)\n        color = SCENARIO_COLOR[scenario_type][0]\n\n        scenario_list = scenario_data[\"available_event_configurations\"]\n        for i in range(len(scenario_list)):\n            # Get the individual scenario data\n            scenario_dict = scenario_list[i]\n            scenario_transform = get_scenario_transform(scenario_dict)\n            scenario_location = scenario_transform.location\n            world.debug.draw_point(\n                scenario_location + debug_loc_height, float(0.15), color)\n            world.debug.draw_string(\n                scenario_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            # Get the new scenario data\n            scenario_wp = tmap.get_waypoint(scenario_location)\n            new_transform = scenario_wp.previous(5)[0].transform\n            new_location = new_transform.location\n            world.debug.draw_point(\n                new_location + debug_loc_height, float(0.15), carla.Color(0,0,0))\n            world.debug.draw_string(\n                new_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            if debug:\n                spectator = world.get_spectator()\n                spectator.set_transform(carla.Transform(new_location + carla.Location(z=50),\n                                                        carla.Rotation(pitch=-90)))\n                input(\" New Scenario [{}/{}] at (x={}, y={}, z={}, yaw={}). Press Enter to continue\".format(\n                    i, len(scenario_list) -1,\n                    round(new_location.x, 1),\n                    round(new_location.y, 1),\n                    round(new_location.z, 1),\n                    round(new_transform.rotation.yaw, 1))\n                )\n\n        world.wait_for_tick()\n\n\ndef validate_scenarios(world, town_data, tmap, scenarios, debug):\n    \"\"\"\n    Validates that all the scenarios can be triggered (by having a waypoint closeby). Color code\n    - Can be triggered: Green\n    - Didn't pass the position check: Red\n    - Didn't pass the yaw check: Blue\n    \"\"\"\n    for scenario_data in town_data:\n        # Get the desired scenario data\n        scenario_type = scenario_data[\"scenario_type\"]\n        if scenario_type not in scenarios:\n            continue\n\n        number = float(scenario_type[8:])\n        debug_loc_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number)\n        debug_str_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number + 0.1)\n\n        scenario_list = scenario_data[\"available_event_configurations\"]\n        for i in range(len(scenario_list)):\n            # Get the individual scenario data\n            scenario_dict = scenario_list[i]\n            scenario_transform = get_scenario_transform(scenario_dict)\n            scenario_location = scenario_transform.location\n\n            # Check if the scenario is close enough to the wp\n            scenario_wp = tmap.get_waypoint(scenario_location)\n            color = get_color_validity(scenario_wp.transform, scenario_transform, scenario_type, i, debug)\n\n            world.debug.draw_point(\n                scenario_location + debug_loc_height, float(0.15), color)\n            world.debug.draw_string(\n                scenario_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            if debug:\n                spectator = world.get_spectator()\n                spectator.set_transform(carla.Transform(scenario_location + carla.Location(z=50),\n                                                        carla.Rotation(pitch=-90)))\n                input(\" Scenario [{}/{}] at (x={}, y={}, z={}, yaw={}). Press Enter to continue\".format(\n                    i, len(scenario_list) - 1,\n                    round(scenario_location.x, 1),\n                    round(scenario_location.y, 1),\n                    round(scenario_location.z, 1),\n                    round(scenario_transform.rotation.yaw, 1))\n                )\n\n        world.wait_for_tick()\n\ndef draw_scenarios(world, town_data, scenarios, debug):\n    \"\"\"\n    Draws all the scenario trigger positions. Each scenario is of a specific color\n    \"\"\"\n    final_message = \"\\n------------------------------\\n\"\n    for scenario_data in town_data:\n        # Get the desired scenario data\n        scenario_type = scenario_data[\"scenario_type\"]\n        if scenario_type not in scenarios:\n            continue\n\n        number = float(scenario_type[8:])\n        debug_loc_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number)\n        debug_str_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number + 0.1)\n        color = SCENARIO_COLOR[scenario_type][0]\n        end_color= \"\\x1b[0m\"\n        true_color = \"\\x1b[38;2;\" + str(color.r) +\";\" + str(color.g) + \";\" + str(color.b) + \"m\"\n        final_message += \"{}{} is colored as {}{}\\n\".format(true_color, scenario_type, SCENARIO_COLOR[scenario_type][1], end_color)\n\n        scenario_list = scenario_data[\"available_event_configurations\"]\n        for i in range(len(scenario_list)):\n            # Get the individual scenario data\n            scenario_dict = scenario_list[i]\n            scenario_transform = get_scenario_transform(scenario_dict)\n            scenario_location = scenario_transform.location\n            world.debug.draw_point(\n                scenario_location + debug_loc_height, float(0.15), color)\n            world.debug.draw_string(\n                scenario_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            if debug:\n                spectator = world.get_spectator()\n                spectator.set_transform(carla.Transform(scenario_location + carla.Location(z=50),\n                                                        carla.Rotation(pitch=-90)))\n                input(\" Scenario [{}/{}] at (x={}, y={}, z={}, yaw={}). Press Enter to continue\".format(\n                    i, len(scenario_list) - 1,\n                    round(scenario_location.x, 1),\n                    round(scenario_location.y, 1),\n                    round(scenario_location.z, 1),\n                    round(scenario_transform.rotation.yaw, 1))\n                )\n\n        world.wait_for_tick()\n    final_message += \"------------------------------\\n\"\n\ndef main():\n    \"\"\"Used to help with the visualization of the scenario trigger points\"\"\"\n    # general parameters\n    parser = argparse.ArgumentParser(formatter_class=RawTextHelpFormatter,\n                                     description=\"Draw, validate or create Leaderboard scenarios. \"\n                                                 \"For multiple scenarios, separate them by spaces (example '1 3 6 9')\")\n    parser.add_argument('--host', default='localhost',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', default='2000',\n                        help='TCP port to listen to (default: 2000)')\n\n    # Path from which all scenarios will be taken\n    parser.add_argument('-f', '--file-path', default=\"../data/all_towns_traffic_scenarios_public.json\",\n                        help='path to the .json file containing the scenarios')\n\n    # Different tests. CHOOSE ONLY ONE.\n    parser.add_argument('--draw-scenarios', nargs='+',\n                        help='Draw the scenarios.')\n    parser.add_argument('--validate-scenarios', nargs='+',\n                        help='Checks whether or not a scenario is well positioned in lane')\n    parser.add_argument('--create-junction-scenarios', action='store_true',\n                        help='Creates scenarios 7 to 10 using scenario 4 as reference')\n\n    # Debug tool, to easily differentiate between scenarios\n    parser.add_argument('--debug', action='store_true',\n                        help='Scenarios are printed one by one, and additional information is given')\n\n    # Town loading arguments\n    parser.add_argument('--load-town',\n                        help='Loads a specific town (example \"Town01\")')\n    parser.add_argument('--reload-town', action='store_true',\n                        help='Reloads the town')\n    args = parser.parse_args()\n\n    if args.load_town and args.reload_town:\n        raise ValueError(\"'load_town' and 'reload' can't be active at the same time\")\n\n    try:\n        client = carla.Client(args.host, int(args.port))\n        client.set_timeout(20)\n        if args.load_town:\n            world = client.load_world(args.load_town)\n        elif args.reload_town:\n            world = client.reload_world()\n        else:\n            world = client.get_world()\n        tmap = world.get_map()\n\n        settings = world.get_settings()\n        settings.fixed_delta_seconds = None\n        settings.synchronous_mode = False\n        world.apply_settings(settings)\n\n        # Read the json file\n        data = fetch_dict(args.file_path)\n        town_name = world.get_map().name.split(\"/\")[-1]\n        town_data = data[\"available_scenarios\"][0][town_name]\n\n        if args.draw_scenarios:\n            scenarios = [\"Scenario\" + ar_sc for ar_sc in args.draw_scenarios]\n            draw_scenarios(world, town_data, scenarios, args.debug)\n        elif args.validate_scenarios:\n            scenarios = [\"Scenario\" + ar_sc for ar_sc in args.validate_scenarios]\n            validate_scenarios(world, town_data, tmap, scenarios, args.debug)\n        elif args.create_junction_scenarios:\n            scenarios = [\"Scenario4\"]\n            create_scenarios(world, town_data, tmap, scenarios, args.debug)\n\n    except KeyboardInterrupt:\n        pass\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/merge_statistics.py",
    "content": "import argparse\n\nfrom leaderboard.utils.checkpoint_tools import fetch_dict\nfrom leaderboard.utils.statistics_manager import StatisticsManager\n\n\ndef check_duplicates(route_ids):\n    \"\"\"Checks that all route ids are present only once in the files\"\"\"\n    for id in route_ids:\n        if route_ids.count(id) > 1:\n            raise ValueError(f\"Stopping. Found that the route {id} has more than one record\")\n\n\ndef check_missing_data(route_ids):\n    \"\"\"Checks that there is no missing data, by changing their route id to an integer\"\"\"\n    rep_num = 1\n    prev_rep_int = 0\n    prev_total_int = 0\n    prev_id = \"\"\n\n    for id in route_ids:\n        route_int = int(id.split('_')[1])\n        rep_int = int(id.split('_rep')[-1])\n\n        # Get the amount of repetitions. Done when a reset of the repetition number is found\n        if rep_int < prev_rep_int:\n            rep_num = prev_rep_int + 1\n\n        # Missing data will create a jump of 2 units\n        # (i.e if 'Route0_rep1' is missing, 'Route0_rep0' will be followed by 'Route0_rep2', which are two units)\n        total_int = route_int * rep_num + rep_int\n        if total_int - prev_total_int > 1: \n            raise ValueError(f\"Stopping. Missing some data as the ids jumped from {prev_id} to {id}\")\n\n        prev_rep_int = rep_int\n        prev_total_int = total_int\n        prev_id = id\n\n\ndef main():\n    \"\"\"\n    Utility script to merge two or more statistics into one.\n    While some checks are done, it is best to ensure that merging all files makes sense\n    \"\"\"\n    argparser = argparse.ArgumentParser()\n    argparser.add_argument('-f', '--file-paths', nargs=\"+\", required=True, help='path to all the files containing the partial results')\n    argparser.add_argument('-e', '--endpoint', required=True, help='path to the endpoint containing the joined results')\n    args = argparser.parse_args()\n\n    # Initialize the statistics manager\n    statistics_manager = StatisticsManager(args.endpoint, 0)\n\n    # Make sure that the data is correctly formed\n    sensors = []\n    route_ids = []\n    total_routes = 0\n    total_progress = 0\n\n    for file in args.file_paths:\n        data = fetch_dict(file)\n        if not data:\n            continue\n\n        route_ids.extend([x['route_id'] for x in data['_checkpoint']['records']])\n        total_routes += len(data['_checkpoint']['records'])\n        total_progress += data['_checkpoint']['progress'][1]\n\n        if data['sensors']:\n            if not sensors:\n                sensors = data['sensors']\n            elif data['sensors'] != sensors:\n                raise ValueError(\"Stopping. Found two files with different sensor configurations\")\n\n    route_ids.sort(key=lambda x: (\n        int(x.split('_')[1]),\n        int(x.split('_rep')[-1])\n    ))\n\n    global_statistics = total_progress != 0 and total_routes == total_progress\n\n    if global_statistics:\n        check_duplicates(route_ids)\n        check_missing_data(route_ids)\n\n    # All good, join the data and get the global results\n    for file in args.file_paths:\n        statistics_manager.add_file_records(file)\n\n    statistics_manager.sort_records()\n    statistics_manager.save_sensors(sensors)\n    statistics_manager.save_progress(total_routes, total_progress)\n    statistics_manager.save_entry_status('Started')\n    if global_statistics:\n        statistics_manager.compute_global_statistics()\n        statistics_manager.validate_and_write_statistics(True, False)\n    else:\n        statistics_manager.write_statistics()\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/pretty_print_json.py",
    "content": "# !/usr/bin/env python\n# Copyright (c) 2020 Intel Corporation.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCreate a human readable version of the scores provided by the leaderboard.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport argparse\nfrom argparse import RawTextHelpFormatter\nfrom dictor import dictor\nimport json\nfrom tabulate import tabulate\n\n\ndef prettify_json(args):\n    with open(args.file) as fd:\n        json_dict = json.load(fd)\n\n    if not json_dict:\n        print('[Error] The file [{}] could not be parsed.'.format(args.file))\n        return -1\n\n    progress = dictor(json_dict, '_checkpoint.progress')\n    records_table = dictor(json_dict, '_checkpoint.records')\n    sensors = dictor(json_dict, 'sensors')\n    labels_scores = dictor(json_dict, 'labels')\n    scores = dictor(json_dict, 'values')\n\n    # compose output\n    output = \"\"\n\n    if progress:\n        output += '* {}% ({}/{}) routes completed\\n'.format(100.0*progress[0]/float(progress[1]),\n                                                            progress[0],\n                                                            progress[1])\n    if sensors:\n        output += '* The agent used the following sensors: {}\\n\\n'.format(', '.join(sensors))\n\n    if scores and labels_scores:\n        metrics = list(zip(*[labels_scores[0:3], scores[0:3]]))\n        infractions = list(zip(*[labels_scores[3:], scores[3:]]))\n\n        output += '=== Global average metrics: ===\\n'\n        output += tabulate(metrics, tablefmt=args.format)\n        output += '\\n\\n'\n        output += '=== Total infractions: ===\\n'\n        output += tabulate(infractions, tablefmt=args.format)\n        output += '\\n\\n'\n\n    if records_table:\n        header = ['Metric', 'Value', 'Additional information']\n        list_statistics = [header]\n        total_duration_game = 0\n        total_duration_system = 0\n        total_route_length = 0\n        for route in records_table:\n            route_completed_kms = 0.01 * route['scores']['Route completion'] * route['meta']['Route length'] / 1000.0\n            metrics_route = [[key, '{:.3f}'.format(values), ''] for key, values in route['scores'].items()]\n            infractions_route = [[key, '{:.3f} ({} occurrences)'.format(len(values)/route_completed_kms, len(values)),\n                                 '\\n'.join(values)] for key, values in route['infractions'].items()]\n\n            times = [['Game duration', '{:.3f}'.format(route['meta']['Game duration']), 'seconds'],\n                     ['System duration', '{:.3f}'.format(route['meta']['System duration']), 'seconds']]\n\n            route_completed_length = [ ['distance driven', '{:.3f}'.format(route_completed_kms), 'Km']]\n\n            total_duration_game += route['meta']['Game duration']\n            total_duration_system += route['meta']['System duration']\n            total_route_length += route_completed_kms\n\n            list_statistics.extend([['{}'.format(route['route_id']), '', '']])\n            list_statistics.extend([*metrics_route, *infractions_route, *times, *route_completed_length])\n            list_statistics.extend([['', '', '']])\n\n        list_statistics.extend([['Total game duration', '{:.3f}'.format(total_duration_game), 'seconds']])\n        list_statistics.extend([['Total system duration', '{:.3f}'.format(total_duration_system), 'seconds']])\n        list_statistics.extend([['Total distance driven', '{:.3f}'.format(total_route_length), 'Km']])\n\n        output += '==== Per-route analysis: ===\\n'.format()\n        output += tabulate(list_statistics, tablefmt=args.format)\n\n    if args.output:\n        with open(args.output, 'w') as fd:\n            fd.write(output)\n    else:\n        print(output)\n\n    return 0\n\n\ndef main():\n    description = 'Create a human readable version of the scores provided by the leaderboard.\\n'\n    # general parameters\n    parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter)\n    parser.add_argument('-f', '--file', help='JSON file containing the results of the leaderboard', required=True)\n    parser.add_argument('--format', default='fancy_grid',\n                        help='Format in which the table will be printed, e.g.: fancy_grid, latex, github, html, jira')\n    parser.add_argument('-o', '--output', help='Output file to print the results into')\n    arguments = parser.parse_args()\n\n    return prettify_json(arguments)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/route_creator.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport sys\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\n\nLIFE_TIME = 10000\n\ndef draw_point(world, wp, option):\n    if option == RoadOption.LEFT:  # Yellow\n        color = carla.Color(128, 128, 0)\n    elif option == RoadOption.RIGHT:  # Cyan\n        color = carla.Color(0, 128, 128)\n    elif option == RoadOption.CHANGELANELEFT:  # Orange\n        color = carla.Color(128, 32, 0)\n    elif option == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n        color = carla.Color(0, 32, 128)\n    elif option == RoadOption.STRAIGHT:  # Gray\n        color = carla.Color(64, 64, 64)\n    else:  # LANEFOLLOW\n        color = carla.Color(0, 128, 0)  # Green\n\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.05, color=color, life_time=LIFE_TIME)\n\ndef draw_keypoint(world, location):\n    world.debug.draw_point(location + carla.Location(z=0.2), size=0.1, color=carla.Color(128, 0, 128), life_time=LIFE_TIME)\n    string = \"(\" + str(round(location.x, 1)) + \", \" + str(round(location.y, 1)) + \", \" + str(round(location.z, 1)) + \")\"\n    world.debug.draw_string(location + carla.Location(z=0.5), string, True, color=carla.Color(0, 0 , 128), life_time=LIFE_TIME)\n\ndef get_saved_data(filename, route_id, world, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    distance = 0\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    found_id = False\n\n    points = []\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        found_id = True\n\n        for position in route.find('waypoints').iter('position'):\n            points.append(convert_elem_to_location(position))\n\n        if points:\n            for i in range(len(points) - 1):\n                waypoint = points[i]\n                waypoint_next = points[i + 1]\n                interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n                for j in range(len(interpolated_trace) - 1):\n                    wp, option = interpolated_trace[j]\n                    wp_next = interpolated_trace[j + 1][0]\n                    draw_point(world, wp, option)\n                    distance += wp.transform.location.distance(wp_next.transform.location)\n\n                draw_keypoint(world, waypoint)\n            draw_keypoint(world, points[-1])\n\n    if not found_id:\n        print(f\"\\033[91mCouldn't find the id '{route_id}' in the given routes file\\033[0m\")\n\n\n    return points, distance\n\ndef add_data(points, tmap, world, spectator, grp):\n    waypoint = tmap.get_waypoint(spectator.get_location())\n    draw_keypoint(world, waypoint.transform.location)\n    added_distance = 0\n    if points:\n        interpolated_trace = grp.trace_route(points[-1], waypoint.transform.location)\n        for j in range(len(interpolated_trace) - 1):\n            wp, option = interpolated_trace[j]\n            wp_next = interpolated_trace[j + 1][0]\n            draw_point(world, wp, option)\n            added_distance += wp.transform.location.distance(wp_next.transform.location)\n    points.append(waypoint.transform.location)\n    return added_distance\n\ndef save_data(filename, route_id, points):\n    def indent(elem, spaces=3, level=0):\n        i = \"\\n\" + level * spaces * \" \"\n        j = \"\\n\" + (level + 1) * spaces * \" \"\n        if len(elem):\n            if not elem.text or not elem.text.strip():\n                elem.text = j\n            if not elem.tail or not elem.tail.strip():\n                elem.tail = i\n            for subelem in elem:\n                indent(subelem, spaces, level+1)\n        else:\n            if level and (not elem.tail or not elem.tail.strip()):\n                elem.tail = i\n        return elem\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    found_id = False\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n        \n        found_id = True\n\n        waypoints = route.find('waypoints')\n        for position in waypoints.iter('position'):\n            waypoints.remove(position)\n\n        for point in points:\n            new_point = etree.SubElement(waypoints, \"position\")\n            new_point.set(\"x\", str(round(point.x, 1)))\n            new_point.set(\"y\", str(round(point.y, 1)))\n            new_point.set(\"z\", str(round(point.z, 1)))\n        break\n\n    if not found_id:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\n    # Prettify the xml. A bit of automatic indentation, a bit of manual one\n    spaces = 3\n    indent(root, spaces)\n    tree.write(filename)\n\n    with open(filename, 'r') as f:\n        data = f.read()\n    temp = data.replace(\"   </\", \"</\")  # The 'indent' function fails for these cases\n\n    weather_spaces = spaces*4*\" \"\n    temp = temp.replace(\" cloudiness\", \"\\n\" + weather_spaces + \"cloudiness\")\n    temp = temp.replace(\" wind_intensity\", \"\\n\" + weather_spaces + \"wind_intensity\")\n    temp = temp.replace(\" fog_density\", \"\\n\" + weather_spaces + \"fog_density\")\n    new_data = temp.replace(\" mie_scattering_scale\", \"\\n\" + weather_spaces + \"mie_scattering_scale\")\n\n    with open(filename, 'w') as f:\n        f.write(new_data)\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, nargs=\"+\", help='File at which to place the scenarios')\n    args = argparser.parse_args()\n\n    # Get the client\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n\n    # # Get the rest\n    world = client.get_world()\n    spectator = world.get_spectator()\n    tmap = world.get_map()\n    grp = GlobalRoutePlanner(tmap, 2.0)\n    points = []\n\n    file_path = args.file[0]\n    route_id = args.file[1] if len(args.file) > 1 else 0\n\n    # Get the data already at the file\n    points, distance = get_saved_data(file_path, route_id, world, grp)\n\n    print(\" ------------------------------------------------------------ \")\n    print(\" |               Use Ctrl+C to stop the script              | \")\n    print(\" |          Any unsaved route points will be lost           | \")\n    print(\" ------------------------------------------------------------ \")\n\n    print(f\"Total accumulated distance is {round(distance, 1)}\")\n\n    try:\n        while True:\n            # Get the scenario type\n            action = input(f\"\\033[1m> Specify the next action ('Add' / 'Save') \\033[0m\")\n            if action == \"Add\":\n                print(\"Adding a new point\")\n                added_distance = add_data(points, tmap, world, spectator, grp)\n                distance += added_distance\n                print(f\"Total accumulated distance is {round(distance, 1)}\")\n            elif action == \"Save\":\n                print(\"Saving data to the xml file\")\n                save_data(file_path, route_id, points)\n            else:\n                print(f\"\\033[1m\\033[93mUnknown action '{action}'. Try again\\033[0m\")\n\n    except KeyboardInterrupt as e:\n        print(\"\\n Detected a keyboard interruption, stopping the script. \")\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/route_displayer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport sys\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\nfrom numpy import random\n\nLIFE_TIME = 10000\n\nCOLORS = [\n    carla.Color(255, 255, 255),\n    carla.Color(255, 0, 0),\n    carla.Color(0, 255, 0),\n    carla.Color(0, 0, 255),\n    carla.Color(255, 255, 0),\n    carla.Color(255, 0, 255),\n    carla.Color(0, 255, 255),\n\n    carla.Color(192, 192, 192),\n    carla.Color(192, 0, 0),\n    carla.Color(0, 192, 0),\n    carla.Color(0, 0, 192),\n    carla.Color(192, 192, 0),\n    carla.Color(192, 0, 192),\n    carla.Color(0, 192, 192),\n\n    carla.Color(128, 128, 128),\n    carla.Color(128, 0, 0),\n    carla.Color(0, 128, 0),\n    carla.Color(0, 0, 128),\n    carla.Color(128, 128, 0),\n    carla.Color(128, 0, 128),\n    carla.Color(0, 128, 128),\n\n    carla.Color(64, 64, 64),\n    carla.Color(64, 0, 0),\n    carla.Color(0, 64, 0),\n    carla.Color(0, 0, 64),\n    carla.Color(64, 64, 0),\n    carla.Color(64, 0, 64),\n    carla.Color(0, 64, 64),\n\n    carla.Color(0, 0, 0),\n]\n\n\ndef draw_point(world, wp, color):\n    world.debug.draw_point( wp.transform.location + carla.Location(z=0.2), size=0.05, color=color, life_time=LIFE_TIME)\n\n\ndef draw_keypoint(world, location):\n    world.debug.draw_point(location + carla.Location(z=0.2), size=0.1, color=carla.Color(128, 0, 128), life_time=LIFE_TIME)\n    string = \"(\" + str(round(location.x, 1)) + \", \" + str(round(location.y, 1)) + \", \" + str(round(location.z, 1)) + \")\"\n    world.debug.draw_string(location + carla.Location(z=0.5), string, True, color=carla.Color(0, 0 , 128), life_time=LIFE_TIME)\n\n\ndef show_all_routes(filename, show_scenarios, world, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    def get_random_color(rng):\n        \"\"\"Gets a random CARLA RGB color\"\"\"\n        r = rng.randint(0, 256)\n        g = rng.randint(0, 256)\n        b = rng.randint(0, 256)\n        return carla.Color(r, g, b)\n\n    rng = random.RandomState(2002)\n    colors = list(COLORS)\n    rng.shuffle(colors)\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n    for i, route in enumerate(root.iter(\"route\")):\n        prev_point = None\n        color = get_random_color(rng)\n        # color = colors[i]\n\n        for position in route.find('waypoints').iter('position'):\n            point = convert_elem_to_location(position)\n            # draw_keypoint(world, point)\n\n            if prev_point:\n                interpolated_trace = grp.trace_route(prev_point, point)\n                for wp, _ in interpolated_trace:\n                    draw_point(world, wp, color)\n            else:\n                world.debug.draw_string(point + carla.Location(z=1), route.attrib['id'], color=color, life_time=10000)\n            prev_point = point\n\n        if show_scenarios:\n            show_saved_scenarios(route, world)\n\n\ndef show_route(filename, route_id, show_keypoints, show_scenarios, world, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n    def get_color(option):\n        if option == RoadOption.LEFT:  # Yellow\n            return carla.Color(128, 128, 0)\n        elif option == RoadOption.RIGHT:  # Cyan\n            return carla.Color(0, 128, 128)\n        elif option == RoadOption.CHANGELANELEFT:  # Orange\n            return carla.Color(128, 32, 0)\n        elif option == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n            return carla.Color(0, 32, 128)\n        elif option == RoadOption.STRAIGHT:  # Gray\n            return carla.Color(64, 64, 64)\n        else:  # LANEFOLLOW\n            return carla.Color(0, 128, 0)  # Green\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        points = []\n        for position in route.find('waypoints').iter('position'):\n            points.append(convert_elem_to_location(position))\n\n        if points:\n            for i in range(len(points) - 1):\n                waypoint = points[i]\n                waypoint_next = points[i + 1]\n                interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n                for j in range(len(interpolated_trace) - 1):\n                    wp, option = interpolated_trace[j]\n                    draw_point(world, wp, get_color(option))\n\n                if show_keypoints:\n                    draw_keypoint(world, waypoint)\n            if show_keypoints:\n                draw_keypoint(world, points[-1])\n\n        if show_scenarios:\n            show_saved_scenarios(route, world)\n\n        # spec_transform = carla.Transform(points[0] + carla.Location(z=100), carla.Rotation(pitch=-90))\n        # world.get_spectator().set_transform(spec_transform)\n\ndef show_saved_scenarios(route, world):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    for scenario in route.find('scenarios').iter('scenario'):\n        name = scenario.attrib.get('name')\n        trigger_location = convert_elem_to_location(scenario.find('trigger_point'))\n        world.debug.draw_point(trigger_location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n        world.debug.draw_string(trigger_location + carla.Location(z=0.5), name, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, help='File at which to place the scenarios')\n    argparser.add_argument('-sr', '--show-route', help='Shows the given route')\n    argparser.add_argument('-sa', '--show-all', action='store_true', help='Shows all the routes')\n    argparser.add_argument('-sk', '--show-keypoints', action='store_true', help='Shows the keypoints that define the route')\n    argparser.add_argument('-ss', '--show-scenarios', action='store_true', help='Shows the scemarios part of the route')\n    args = argparser.parse_args()\n\n    # Get the client\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n\n    # Get the rest\n    world = client.get_world()\n    tmap = world.get_map()\n    grp = GlobalRoutePlanner(tmap, 2.0)\n\n    if not args.show_route and not args.show_all:\n        print(\"No instructions to show were given, stopping the script\")\n\n    # Show all routes\n    if args.show_all:\n        show_all_routes(args.file, args.show_scenarios, world, grp)\n\n    # Show one route\n    if args.show_route:\n        show_route(args.file, args.show_route, args.show_keypoints, args.show_scenarios, world, grp)\n\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/route_summarizer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nimport os\nimport sys\nfrom lxml import etree\nfrom tabulate import tabulate\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nMAPS_LOCATIONS = {\n    \"Town01\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01.xodr\",\n    \"Town01_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01_Opt.xodr\",\n    \"Town02\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02.xodr\",\n    \"Town02_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02_Opt.xodr\",\n    \"Town03\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town03.xodr\",\n    \"Town03_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town04\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04.xodr\",\n    \"Town04_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town05\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05.xodr\",\n    \"Town05_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05_Opt.xodr\",\n    \"Town06\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06.xodr\",\n    \"Town06_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06_Opt.xodr\",\n    \"Town07\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07.xodr\",\n    \"Town07_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07_Opt.xodr\",\n    \"Town10HD\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD.xodr\",\n    \"Town10HD_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD_Opt.xodr\",\n    \"Town11\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town11/OpenDrive/Town11.xodr\",\n    \"Town12\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town12/OpenDrive/Town12.xodr\",\n    \"Town13\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town13/OpenDrive/Town13.xodr\",\n}\n\ndef convert_elem_to_location(elem):\n    \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n    return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, help=\"Route's file path\")\n    argparser.add_argument('--endpoint', default=\"\", help='Output file')\n    argparser.add_argument('--show', action=\"store_true\", help='Print the results on stdout')\n    args = argparser.parse_args()\n\n    if not args.endpoint and not args.show:\n        print(\"No output method was selected. Use either '--endpoint', or '--show' to get the route results\")\n        sys.exit(0)\n\n    root = etree.parse(args.file).getroot()\n    total_distance = 0\n    total_num_scenarios = 0\n    total_scenarios = {}\n\n    statistics = [['Route id', 'Distance (m)', 'Scenarios (type)', 'Scenarios (nº)', 'Avg dist between scenarios']]\n\n    prev_town = None\n\n    for route in root.iter(\"route\"):\n\n        route_id = route.attrib['id']\n        route_town = route.attrib['town']\n\n        if route_town not in MAPS_LOCATIONS:\n            print(f\"Ignoring route '{route_id}' as it uses an unknown map '{route_town}\")\n            continue\n        elif route_town != prev_town:\n            full_name = os.environ[\"CARLA_ROOT\"] + \"/\" + MAPS_LOCATIONS[route_town]\n            with open(full_name, 'r') as f:\n                map_contents = f.read()\n            tmap = carla.Map(route_town, map_contents)\n            grp = GlobalRoutePlanner(tmap, 2.0)\n\n        print(f\"Parsing route '{route_id}'\")\n\n        # Get the route distance\n        route_distance = 0\n\n        route_points = []\n        for position in route.find('waypoints').iter('position'):\n            route_points.append(convert_elem_to_location(position))\n\n        for i in range(len(route_points) - 1):\n            waypoint = route_points[i]\n            waypoint_next = route_points[i + 1]\n            interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n            for j in range(len(interpolated_trace) - 1):\n                wp = interpolated_trace[j][0]\n                wp_next = interpolated_trace[j + 1][0]\n                route_distance += wp.transform.location.distance(wp_next.transform.location)\n\n        # Get the route scenarios\n        route_scenarios = {}\n\n        for scenario in route.find('scenarios').iter('scenario'):\n            scenario_type = scenario.attrib.get('type')\n            if not scenario_type in route_scenarios:\n                route_scenarios[scenario_type] = 0\n\n            route_scenarios[scenario_type] += 1\n\n        num_scenarios = sum([x for x in route_scenarios.values()])\n        dist_scenarios = route_distance / num_scenarios\n\n        print_scenarios = \"\"\n        route_scenario_items = sorted(list(route_scenarios.items()), key=lambda x: x[0])\n        for s_type, s_num in route_scenario_items:\n            print_scenarios += f\"{s_type}: {s_num}\\n\"\n\n        statistics += [[\n            route_id,\n            round(route_distance, 1),\n            print_scenarios,\n            sum([x for x in route_scenarios.values()]),\n            round(dist_scenarios, 1)\n        ]]\n\n        # Get the total amounts\n        total_distance += route_distance\n        total_num_scenarios += num_scenarios\n\n        for s_type, s_num in route_scenario_items:\n            if s_type not in total_scenarios:\n                total_scenarios[s_type] = 0\n            total_scenarios[s_type] += s_num\n\n        prev_town = route_town\n\n    print_total_scenarios = \"\"\n    total_scenario_items = sorted(list(total_scenarios.items()), key=lambda x: x[0])\n    for s_type, s_num in total_scenario_items:\n        print_total_scenarios += f\"{s_type}: {s_num}\\n\"\n\n    statistics += [[\n        \"Total\",\n        round(total_distance, 1),\n        print_total_scenarios,\n        total_num_scenarios,\n        round(total_distance / total_num_scenarios, 1)\n    ]]\n\n    output = tabulate(statistics, tablefmt='fancy_grid')\n    if args.show:\n        print(output)\n\n    if args.endpoint:\n        with open(args.endpoint, 'w', encoding='utf-8') as fd:\n            fd.write(output)\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation.sh",
    "content": "#!/bin/bash\n# Must set CARLA_ROOT\nexport CARLA_ROOT=/data/songziying/workspace/carla\nexport CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla\nexport PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-0.9.15-py3.7-linux-x86_64.egg\nexport PYTHONPATH=$PYTHONPATH:leaderboard\nexport PYTHONPATH=$PYTHONPATH:leaderboard/team_code\nexport PYTHONPATH=$PYTHONPATH:scenario_runner\nexport SCENARIO_RUNNER_ROOT=scenario_runner\n\nexport LEADERBOARD_ROOT=leaderboard\nexport CHALLENGE_TRACK_CODENAME=SENSORS\nexport PORT=$1\nexport TM_PORT=$2\nexport DEBUG_CHALLENGE=0\nexport REPETITIONS=1 # multiple evaluation runs\nexport RESUME=True\nexport IS_BENCH2DRIVE==$3\nexport PLANNER_TYPE=$9\nexport GPU_RANK=${10}\n\n# TCP evaluation\nexport ROUTES=$4\nexport TEAM_AGENT=$5\nexport TEAM_CONFIG=$6\nexport CHECKPOINT_ENDPOINT=$7\nexport SAVE_PATH=$8\n\nCUDA_VISIBLE_DEVICES=${GPU_RANK} python ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \\\n--routes=${ROUTES} \\\n--repetitions=${REPETITIONS} \\\n--track=${CHALLENGE_TRACK_CODENAME} \\\n--checkpoint=${CHECKPOINT_ENDPOINT} \\\n--agent=${TEAM_AGENT} \\\n--agent-config=${TEAM_CONFIG} \\\n--debug=${DEBUG_CHALLENGE} \\\n--record=${RECORD_PATH} \\\n--resume=${RESUME} \\\n--port=${PORT} \\\n--traffic-manager-port=${TM_PORT} \\\n--gpu-rank=${GPU_RANK} \\"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation_debug.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\n#TEAM_AGENT=./team_agent/vad_b2d_agent.py\nTEAM_AGENT=leaderboard/team_agent/sparsedrive_b2d_agent.py\n#TEAM_CONFIG=/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py+/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/work_dirs/MomAD_base_e2e_b2d/epoch_5.pth\nTEAM_CONFIG=/data/songziying/workspace/SparseDriveb2d/adzoo/sparsedrive/configs/momad_small_b2d_stage2_multiplan.py+/data/songziying/workspace/SparseDriveb2d/ckpt/iter_9782.pth\n# /data/songziying/workspace/Bench2Drive/Bench2DriveZoo/ckpts/vad_b2d_base.pth\nBASE_CHECKPOINT_ENDPOINT=eval\nSAVE_PATH=./eval_v1/\nPLANNER_TYPE=only_traj\n\nGPU_RANK=3\nPORT=$BASE_PORT\nTM_PORT=$BASE_TM_PORT\nROUTES=\"${BASE_ROUTES}.xml\"\nCHECKPOINT_ENDPOINT=\"${BASE_CHECKPOINT_ENDPOINT}.json\"\nbash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation_multi_admlp.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/admlp_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=YOUR_CKPT_PATH/admlp_b2d.ckpt\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=traj\nALGO=admlp\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=12\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 4*A6000, 3 task per gpu\nGPU_RANK_LIST=(0 0 0 1 1 1 2 2 2 3 3 3)\nTASK_LIST=(0 1 2 3 4 5 6 7 8 9 10 11)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation_multi_tcp.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/tcp_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=YOUR_CKPT_PATH/tcp_b2d.ckpt\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=merge_ctrl_traj # You can choose from only_ctrl, only_traj and merge_ctrl_traj\nALGO=tcp\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=12\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 4*A6000, 3 task per gpu\nGPU_RANK_LIST=(0 0 0 1 1 1 2 2 2 3 3 3)\nTASK_LIST=(0 1 2 3 4 5 6 7 8 9 10 11)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation_multi_uniad.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/uniad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/base_e2e_b2d.py+YOUR_CKPT_PATH/uniad_base_b2d.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=traj\nALGO=uniad\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation_multi_uniad_tiny.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/uniad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/tiny_e2e_b2d.py+YOUR_CKPT_PATH/uniad_tiny_b2d.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=traj\nALGO=uniad_tiny\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evaluation_multi_vad.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/vad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py+/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/work_dirs/MomAD_base_e2e_b2d/epoch_5.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220_momad\nPLANNER_TYPE=traj\nALGO=vad\nSAVE_PATH=./eval_bench2drive220_momad_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/run_evalutaion_multi_sparsedrive.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=leaderboard/team_code/sparsedrive_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=/data/songziying/workspace/SparseDriveb2d/adzoo/sparsedrive/configs/momad_small_b2d_stage2_multiplan.py+/data/songziying/workspace/SparseDriveb2d/ckpt/iter_9782.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220_momad\nPLANNER_TYPE=traj\nALGO=vad\nSAVE_PATH=./eval_bench2drive220_momad_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/scenario_creator.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport sys\n\nimport carla\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nLIFE_TIME = 10000\n\nSCENARIO_TYPES ={\n\n    # Junction scenarios\n    \"SignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"SignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleRunningRedLight\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"NonSignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"NonSignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleTakingPriority\": [\n        [\"direction\", \"choice\"],\n    ],\n\n    # Crossing actors\n    \"DynamicObjectCrossing\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"blocker_model\", \"value\"],\n        [\"crossing_angle\", \"value\"]\n    ],\n    \"ParkingCrossingPedestrian\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n        [\"crossing_angle\", \"value\"],\n    ],\n    \"PedestrianCrossing\": [\n    ],\n    \"VehicleTurningRoute\": [\n    ],\n    \"VehicleTurningRoutePedestrian\": [\n    ],\n    \"BlockedIntersection\": [\n    ],\n\n    # Actor flows\n    \"EnterActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"EnterActorFlowV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanAdvancedActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"HighwayExit\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTraffic\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTrafficV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"CrossingBicycleFlow\": [\n        [\"start_actor_flow\", \"location bicycle\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n\n    # Route obstacles\n    \"ConstructionObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ConstructionObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"Accident\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"AccidentTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"ParkedObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ParkedObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"VehicleOpensDoorTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"HazardAtSideLane\": [\n        [\"distance\", \"value\"],\n        [\"speed\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"HazardAtSideLaneTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"InvadingTurn\": [\n        [\"distance\", \"value\"],\n        [\"offset\", \"value\"],\n    ],\n\n    # Cut ins\n    \"HighwayCutIn\": [\n        [\"other_actor_location\", \"location driving\"],\n    ],\n    \"ParkingCutIn\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"StaticCutIn\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n    ],\n\n    # Others\n    \"ControlLoss\": [\n    ],\n    \"HardBreakRoute\": [\n    ],\n    \"ParkingExit\": [\n        [\"direction\", \"choice\"],\n        [\"front_vehicle_distance\", \"value\"],\n        [\"behind_vehicle_distance\", \"value\"],\n    ],\n    \"YieldToEmergencyVehicle\": [\n        [\"distance\", \"value\"],\n    ],\n\n    # Special ones\n    \"BackgroundActivityParametrizer\": [\n        [\"num_front_vehicles\", \"value\"],\n        [\"num_back_vehicles\", \"value\"],\n        [\"road_spawn_dist\", \"value\"],\n        [\"opposite_source_dist\", \"value\"],\n        [\"opposite_max_actors\", \"value\"],\n        [\"opposite_spawn_dist\", \"value\"],\n        [\"opposite_active\", \"bool\"],\n        [\"junction_source_dist\", \"value\"],\n        [\"junction_max_actors\", \"value\"],\n        [\"junction_spawn_dist\", \"value\"],\n        [\"junction_source_perc\", \"value\"],\n    ],\n    \"PriorityAtJunction\": [\n    ],\n}\n\ndef show_saved_scenarios(filename, route_id, world):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    found_id = False\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        found_id = True\n\n        for scenario in route.find('scenarios').iter('scenario'):\n            name = scenario.attrib.get('name')\n            trigger_location = convert_elem_to_location(scenario.find('trigger_point'))\n            world.debug.draw_point(trigger_location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n            world.debug.draw_string(trigger_location + carla.Location(z=0.5), name, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n\n    if not found_id:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\ndef get_scenario_type(tmap, world, spectator):\n    while True:\n        scen_type = input(\"\\033[1m> Specify the scenario type \\033[0m\")\n        if scen_type not in list(SCENARIO_TYPES):\n            print(f\"\\033[1m\\033[93mScenario type '{scen_type}' doesn't match any of the know scenarios\\033[0m\")\n        else:\n            break\n\n    wp = tmap.get_waypoint(spectator.get_location())\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n    world.debug.draw_string(wp.transform.location + carla.Location(z=0.5), scen_type, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n    trigger_point = (\n        str(round(wp.transform.location.x, 1)),\n        str(round(wp.transform.location.y, 1)),\n        str(round(wp.transform.location.z, 1)),\n        str(round(wp.transform.rotation.yaw, 1))\n    )\n    return scen_type, trigger_point\n\ndef get_attributes_data(scen_type, trigger_point, tmap, world, spectator):\n    attribute_list = SCENARIO_TYPES[scen_type]\n    scenario_attributes = [['trigger_point', 'transform', trigger_point]]\n    for attribute in attribute_list:\n        a_name, a_type = attribute\n        if a_type == 'transform':\n            a_data = get_transform_data(a_name, scen_type, tmap, world, spectator)\n        elif 'location' in a_type:\n            a_data = get_location_data(a_name, scen_type, tmap, world, spectator, a_type)\n        elif a_type in ('value', 'choice', 'bool'):\n            a_data = get_value_data(a_name)\n        elif a_type == 'interval':\n            a_data = get_interval_data(a_name)\n        else:\n            raise ValueError(\"Unknown attribute type\")\n\n        if a_data:  # Ignore the attributes that use default values\n            scenario_attributes.append([a_name, a_type, a_data])\n    return scenario_attributes\n\ndef get_transform_data(a_name, scen_type, tmap, world, spectator):\n    input(f\"\\033[1m> Enter the '{a_name}' transform \\033[0m\")\n    wp = tmap.get_waypoint(spectator.get_location())\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n    world.debug.draw_string(wp.transform.location + carla.Location(z=0.5), scen_type, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n    return (\n        str(round(wp.transform.location.x, 1)),\n        str(round(wp.transform.location.y, 1)),\n        str(round(wp.transform.location.z, 1)),\n        str(round(wp.transform.rotation.yaw, 1))\n    )\n\ndef get_location_data(a_name, scen_type, tmap, world, spectator, a_type):\n    input(f\"\\033[1m> Enter the '{a_name}' location \\033[0m\")\n    if \"sidewalk\" in a_type:\n        lane_type = carla.LaneType.Sidewalk\n    elif \"bicycle\" in a_type:\n        lane_type = carla.LaneType.Biking\n    elif \"driving\" in a_type:\n        lane_type = carla.LaneType.Driving\n    else:\n        lane_type = carla.LaneType.Driving\n\n    wp = tmap.get_waypoint(spectator.get_location(), lane_type=lane_type)\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n    world.debug.draw_string(wp.transform.location + carla.Location(z=0.5), scen_type, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n\n    loc =  (\n            str(round(wp.transform.location.x, 1)),\n            str(round(wp.transform.location.y, 1)),\n            str(round(wp.transform.location.z, 1))\n        )\n\n    if \"probability\" in a_type:\n        p = input(f\"\\033[1m> Enter the '{a_name}' probability \\033[0m\")\n        loc += (p,)\n    return loc\n\n\ndef get_value_data(a_name):\n    value = input(f\"\\033[1m> Specify the '{a_name}' value \\033[0m\")\n    return value\n\ndef get_interval_data(a_name):\n    lower_value = input(f\"\\033[1m> Specify the '{a_name}' from \\033[0m\")\n    upper_value = input(f\"\\033[1m> Specify the '{a_name}' from \\033[0m{lower_value}\\033[1m to \\033[0m\")\n    return (lower_value, upper_value)\n\ndef print_scenario_data(scen_type, scen_attributes):\n    print_dict = f\"\\n   scenario_type: {scen_type}\\n\"\n    for print_attribute in scen_attributes:\n        print_dict += f\"   {print_attribute[0]}: {print_attribute[2]}\\n\"\n    print(print_dict)\n\ndef save_scenario(filename, route_id, scenario_type, scenario_attributes):\n\n    while True:\n        save = input(\"\\033[1m> Save the scenario? ('Yes' / 'No'): \\033[0m\")\n        if save == \"Yes\":\n            break\n        elif save == \"No\":\n            return\n        else:\n            print(f\"\\033[1m\\033[93mThis is a 'Yes' or 'No' question, try again.\\033[0m\")\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    scenario_names = {}\n    for scen_type in list(SCENARIO_TYPES):\n        scenario_names[scen_type] = 1\n\n    found_id = False\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        found_id = True\n\n        scenarios = route.find('scenarios')\n        for scenario in scenarios.iter('scenario'):\n            scen_type = scenario.attrib['type']\n            scenario_names[scen_type] += 1\n\n        number = scenario_names[scenario_type]\n        new_scenario = etree.SubElement(scenarios, \"scenario\")\n\n        new_scenario.set(\"name\", scenario_type + \"_\" + str(number))\n        new_scenario.set(\"type\", scenario_type)\n\n        for a_name, a_type, a_value in scenario_attributes:\n            data = etree.SubElement(new_scenario, a_name)\n            if a_type == 'transform':\n                data.set(\"x\", a_value[0])\n                data.set(\"y\", a_value[1])\n                data.set(\"z\", a_value[2])\n                data.set(\"yaw\", a_value[3])\n            elif 'location' in a_type:\n                data.set(\"x\", a_value[0])\n                data.set(\"y\", a_value[1])\n                data.set(\"z\", a_value[2])\n                if 'probability' in a_type:\n                    data.set(\"p\", a_value[3])\n            elif a_type in ('value', 'choice', 'bool'):\n                data.set(\"value\", a_value)\n            elif a_type == 'interval':\n                data.set(\"from\", a_value[0])\n                data.set(\"to\", a_value[1])\n        break\n\n    if not found_id:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\n    prettify_and_save_tree(filename, tree)\n\ndef prettify_and_save_tree(filename, tree):\n    def indent(elem, spaces=3, level=0):\n        i = \"\\n\" + level * spaces * \" \"\n        j = \"\\n\" + (level + 1) * spaces * \" \"\n        if len(elem):\n            if not elem.text or not elem.text.strip():\n                elem.text = j\n            if not elem.tail or not elem.tail.strip():\n                elem.tail = i\n            for subelem in elem:\n                indent(subelem, spaces, level+1)\n        else:\n            if level and (not elem.tail or not elem.tail.strip()):\n                elem.tail = i\n        return elem\n\n    # Prettify the xml. A bit of automatic indentation, a bit of manual one\n    spaces = 3\n    indent(tree.getroot(), spaces)\n    tree.write(filename)\n\n    with open(filename, 'r') as f:\n        data = f.read()\n    temp = data.replace(\"   </\", \"</\")  # The 'indent' function fails for these cases\n\n    weather_spaces = spaces*4*\" \"\n    temp = temp.replace(\" cloudiness\", \"\\n\" + weather_spaces + \"cloudiness\")\n    temp = temp.replace(\" wind_intensity\", \"\\n\" + weather_spaces + \"wind_intensity\")\n    new_data = temp.replace(\" mie_scattering_scale\", \"\\n\" + weather_spaces + \"mie_scattering_scale\")\n\n    with open(filename, 'w') as f:\n        f.write(new_data)\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, nargs=\"+\", help='File at which to place the scenarios')\n    argparser.add_argument('-s', '--show-only', action='store_true', help='Only shows the route')\n    args = argparser.parse_args()\n\n    # Get the client\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n\n    # # Get the rest\n    world = client.get_world()\n    spectator = world.get_spectator()\n    tmap = world.get_map()\n\n    file_path = args.file[0]\n    route_id = args.file[1] if len(args.file) > 1 else 0\n\n    # Get the data already at the file\n    show_saved_scenarios(file_path, route_id, world)\n    if args.show_only:\n        sys.exit(0)\n\n    print(\" ------------------------------------------------------------ \")\n    print(\" |               Use Ctrl+C to stop the script              | \")\n    print(\" |            Any ongoing scenario will be ignored          | \")\n    print(\" |                                                          | \")\n    print(\" |   Transform and location parameters will automatically   | \")\n    print(\" |     get the closest waypoint to the spectator camera     | \")\n    try:\n        while True:\n            print(\" ------------------------------------------------------------ \")\n\n            # Get the scenario type\n            scen_type, trigger_point = get_scenario_type(tmap, world, spectator)\n\n            # Get the attributes\n            scen_attributes = get_attributes_data(scen_type, trigger_point, tmap, world, spectator)\n\n            # Give feedback to the user\n            print_scenario_data(scen_type, scen_attributes)\n\n            # Save the data\n            save_scenario(file_path, route_id, scen_type, scen_attributes)\n\n    except KeyboardInterrupt as e:\n        print(\"\\n Detected a keyboard interruption, stopping the script \")\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/scenario_orderer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport os\n\nimport carla\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nSCENARIO_TYPES = {\n\n    # Junction scenarios\n    \"SignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"SignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleRunningRedLight\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"NonSignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"NonSignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleTakingPriority\": [\n        [\"direction\", \"choice\"],\n    ],\n\n    # Crossing actors\n    \"DynamicObjectCrossing\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"blocker_model\", \"value\"],\n        [\"crossing_angle\", \"value\"]\n    ],\n    \"ParkingCrossingPedestrian\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n        [\"crossing_angle\", \"value\"],\n    ],\n    \"PedestrianCrossing\": [\n    ],\n    \"VehicleTurningRoute\": [\n    ],\n    \"VehicleTurningRoutePedestrian\": [\n    ],\n    \"BlockedIntersection\": [\n    ],\n\n    # Actor flows\n    \"EnterActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"EnterActorFlowV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanAdvancedActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"HighwayExit\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTraffic\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTrafficV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"CrossingBicycleFlow\": [\n        [\"start_actor_flow\", \"location bicycle\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n\n    # Route obstacles\n    \"ConstructionObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ConstructionObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"Accident\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"AccidentTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"ParkedObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ParkedObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"VehicleOpensDoorTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"HazardAtSideLane\": [\n        [\"distance\", \"value\"],\n        [\"speed\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"HazardAtSideLaneTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"InvadingTurn\": [\n        [\"distance\", \"value\"],\n        [\"offset\", \"value\"],\n    ],\n\n    # Cut ins\n    \"HighwayCutIn\": [\n        [\"other_actor_location\", \"location driving\"],\n    ],\n    \"ParkingCutIn\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"StaticCutIn\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n    ],\n\n    # Others\n    \"ControlLoss\": [\n    ],\n    \"HardBreakRoute\": [\n    ],\n    \"ParkingExit\": [\n        [\"direction\", \"choice\"],\n        [\"front_vehicle_distance\", \"value\"],\n        [\"behind_vehicle_distance\", \"value\"],\n    ],\n    \"YieldToEmergencyVehicle\": [\n        [\"distance\", \"value\"],\n    ],\n\n    # Special ones\n    \"BackgroundActivityParametrizer\": [\n        [\"num_front_vehicles\", \"value\"],\n        [\"num_back_vehicles\", \"value\"],\n        [\"road_spawn_dist\", \"value\"],\n        [\"opposite_source_dist\", \"value\"],\n        [\"opposite_max_actors\", \"value\"],\n        [\"opposite_spawn_dist\", \"value\"],\n        [\"opposite_active\", \"bool\"],\n        [\"junction_source_dist\", \"value\"],\n        [\"junction_max_actors\", \"value\"],\n        [\"junction_spawn_dist\", \"value\"],\n        [\"junction_source_perc\", \"value\"],\n    ],\n    \"PriorityAtJunction\": [\n    ],\n\n}\n\nMAPS_LOCATIONS = {\n    \"Town01\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01.xodr\",\n    \"Town01_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01_Opt.xodr\",\n    \"Town02\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02.xodr\",\n    \"Town02_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02_Opt.xodr\",\n    \"Town03\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town03.xodr\",\n    \"Town03_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town04\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04.xodr\",\n    \"Town04_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town05\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05.xodr\",\n    \"Town05_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05_Opt.xodr\",\n    \"Town06\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06.xodr\",\n    \"Town06_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06_Opt.xodr\",\n    \"Town07\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07.xodr\",\n    \"Town07_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07_Opt.xodr\",\n    \"Town10HD\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD.xodr\",\n    \"Town10HD_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD_Opt.xodr\",\n    \"Town11\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town11/OpenDrive/Town11.xodr\",\n    \"Town12\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town12/OpenDrive/Town12.xodr\",\n    \"Town13\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town13/OpenDrive/Town13.xodr\",\n}\n\ndef order_saved_scenarios(filename, route_id, tmap, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    def get_scenario_route_position(trigger_location):\n        position = 0\n        distance = float('inf')\n        for i, (wp, _) in enumerate(route_wps):\n            route_distance = wp.transform.location.distance(trigger_location)\n            if route_distance < distance:\n                distance = route_distance\n                position = i\n        return position\n\n    def indent(elem, spaces=3, level=0):\n        i = \"\\n\" + level * spaces * \" \"\n        j = \"\\n\" + (level + 1) * spaces * \" \"\n        if len(elem):\n            if not elem.text or not elem.text.strip():\n                elem.text = j\n            if not elem.tail or not elem.tail.strip():\n                elem.tail = i\n            for subelem in elem:\n                indent(subelem, spaces, level+1)\n        else:\n            if level and (not elem.tail or not elem.tail.strip()):\n                elem.tail = i\n        return elem\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    scenarios = None\n    route_wps = []\n    prev_route_keypoint = None\n    scenarios = []\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        # Scenarios data\n        for scenario in route.find('scenarios').iter('scenario'):\n            scenarios.append(scenario)\n\n        # Route data\n        for position in route.find('waypoints').iter('position'):\n            route_keypoint = convert_elem_to_location(position)\n            if prev_route_keypoint:\n                route_wps.extend(grp.trace_route(prev_route_keypoint, route_keypoint))\n            prev_route_keypoint = route_keypoint\n\n    if scenarios is None:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\n    # Order the scenarios according to route position\n    scenario_and_pos = []\n    for scenario in scenarios:\n        trigger_location = convert_elem_to_location(scenario.find('trigger_point'))\n        route_position = get_scenario_route_position(trigger_location)\n        scenario_and_pos.append([scenario, route_position])\n    scenario_and_pos = sorted(scenario_and_pos, key=lambda x: x[1])\n\n    # Update the scenarios. TODO: reorder them\n    scenario_names = {}\n    for scen_type in list(SCENARIO_TYPES):\n        scenario_names[scen_type] = 1\n\n    for scenario, _ in scenario_and_pos:\n        scen_type = scenario.attrib['type']\n        scen_name = f\"{scen_type}_{scenario_names[scen_type]}\"\n        scenario.set(\"name\", scen_name)\n        scenario_names[scen_type] += 1\n\n    # Prettify the xml. A bit of automatic indentation, a bit of manual one\n    spaces = 3\n    indent(tree.getroot(), spaces)\n    tree.write(filename)\n\n    with open(filename, 'r') as f:\n        data = f.read()\n    temp = data.replace(\"   </\", \"</\")  # The 'indent' function fails for these cases\n\n    weather_spaces = spaces*4*\" \"\n    temp = temp.replace(\" cloudiness\", \"\\n\" + weather_spaces + \"cloudiness\")\n    temp = temp.replace(\" wind_intensity\", \"\\n\" + weather_spaces + \"wind_intensity\")\n    temp = temp.replace(\" fog_density\", \"\\n\" + weather_spaces + \"fog_density\")\n    new_data = temp.replace(\" mie_scattering_scale\", \"\\n\" + weather_spaces + \"mie_scattering_scale\")\n\n    with open(filename, 'w') as f:\n        f.write(new_data)\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, help='File at which to place the scenarios')\n    args = argparser.parse_args()\n\n    root = etree.parse(args.file).getroot()\n    prev_town = None\n    for route in root.iter(\"route\"):\n\n        route_id = route.attrib['id']\n        route_town = route.attrib['town']\n\n        if route_town not in MAPS_LOCATIONS:\n            print(f\"Ignoring route '{route_id}' as it uses an unknown map '{route_town}\")\n            continue\n        elif route_town != prev_town:\n            full_name = os.environ[\"CARLA_ROOT\"] + \"/\" + MAPS_LOCATIONS[route_town]\n            with open(full_name, 'r') as f:\n                map_contents = f.read()\n            tmap = carla.Map(route_town, map_contents)\n            grp = GlobalRoutePlanner(tmap, 1.0)\n\n        print(f\"Parsing route '{route_id}'\")\n\n    file_path = args.file[0]\n    route_id = args.file[1] if len(args.file) > 1 else 0\n\n    order_saved_scenarios(file_path, route_id, tmap)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/scripts/weather_creator.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\nimport argparse\nimport carla\n\n\n\ndef main():\n    argparser = argparse.ArgumentParser(\n        description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', action=\"store_true\", help='File to start')\n    argparser.add_argument('-r', '--route', default=\"\", help='Route')\n    # argparser.add_argument('-t', '--time', default=60, help='Time')\n    args = argparser.parse_args()\n\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n    world = client.get_world()\n    weather = world.get_weather()\n\n    weather_string = f\"         <weather\\n\"\n    weather_string += f\"            route_percentage=\\\"0\\\"\\n\"\n    weather_string += f\"            cloudiness=\\\"{weather.cloudiness}\\\" \"\n    weather_string += f\"precipitation=\\\"{weather.precipitation}\\\" \"\n    weather_string += f\"precipitation_deposits=\\\"{weather.precipitation_deposits}\\\" \"\n    weather_string += f\"wetness=\\\"{weather.wetness}\\\"\\n\"\n    weather_string += f\"            wind_intensity=\\\"{weather.wind_intensity}\\\" \"\n    weather_string += f\"sun_azimuth_angle=\\\"{weather.sun_azimuth_angle}\\\" \"\n    weather_string += f\"sun_altitude_angle=\\\"{weather.sun_altitude_angle}\\\"\\n\"\n    weather_string += f\"            fog_density=\\\"{weather.fog_density}\\\" \"\n    weather_string += f\"fog_distance=\\\"{weather.fog_distance}\\\" \"\n    weather_string += f\"fog_falloff=\\\"{round(weather.fog_falloff, 2)}\\\" \"\n    weather_string += f\"scattering_intensity=\\\"{weather.scattering_intensity}\\\"\\n\"\n    weather_string += f\"            mie_scattering_scale=\\\"{round(weather.mie_scattering_scale, 2)}\\\"/>\"\n\n    print(weather_string)\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/team_code/pid_controller.py",
    "content": "from collections import deque\nimport numpy as np\n\nclass PID(object):\n\tdef __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20):\n\t\tself._K_P = K_P\n\t\tself._K_I = K_I\n\t\tself._K_D = K_D\n\n\t\tself._window = deque([0 for _ in range(n)], maxlen=n)\n\t\tself._max = 0.0\n\t\tself._min = 0.0\n\n\tdef step(self, error):\n\t\tself._window.append(error)\n\t\tself._max = max(self._max, abs(error))\n\t\tself._min = -abs(self._max)\n\n\t\tif len(self._window) >= 2:\n\t\t\tintegral = np.mean(self._window)\n\t\t\tderivative = (self._window[-1] - self._window[-2])\n\t\telse:\n\t\t\tintegral = 0.0\n\t\t\tderivative = 0.0\n\n\t\treturn self._K_P * error + self._K_I * integral + self._K_D * derivative\n\n\n\nclass PIDController(object):\n    \n    def __init__(self, turn_KP=0.75, turn_KI=0.75, turn_KD=0.3, turn_n=40, speed_KP=5.0, speed_KI=0.5,speed_KD=1.0, speed_n = 40,max_throttle=0.75, brake_speed=0.4,brake_ratio=1.1, clip_delta=0.25, aim_dist=4.0, angle_thresh=0.3, dist_thresh=10):\n        \n        self.turn_controller = PID(K_P=turn_KP, K_I=turn_KI, K_D=turn_KD, n=turn_n)\n        self.speed_controller = PID(K_P=speed_KP, K_I=speed_KI, K_D=speed_KD, n=speed_n)\n        self.max_throttle = max_throttle\n        self.brake_speed = brake_speed\n        self.brake_ratio = brake_ratio\n        self.clip_delta = clip_delta\n        self.aim_dist = aim_dist\n        self.angle_thresh = angle_thresh\n        self.dist_thresh = dist_thresh\n\n    def control_pid(self, waypoints, speed, target):\n        ''' Predicts vehicle control with a PID controller.\n        Args:\n            waypoints (tensor): output of self.plan()\n            speed (tensor): speedometer input\n        '''\n\n        # iterate over vectors between predicted waypoints\n        num_pairs = len(waypoints) - 1\n        best_norm = 1e5\n        desired_speed = 0\n        aim = waypoints[0]\n        for i in range(num_pairs):\n            # magnitude of vectors, used for speed\n            desired_speed += np.linalg.norm(\n                    waypoints[i+1] - waypoints[i]) * 2.0 / num_pairs\n\n            # norm of vector midpoints, used for steering\n            norm = np.linalg.norm((waypoints[i+1] + waypoints[i]) / 2.0)\n            if abs(self.aim_dist-best_norm) > abs(self.aim_dist-norm):\n                aim = waypoints[i]\n                best_norm = norm\n\n        aim_last = waypoints[-1] - waypoints[-2]\n\n        angle = np.degrees(np.pi / 2 - np.arctan2(aim[1], aim[0])) / 90\n        angle_last = np.degrees(np.pi / 2 - np.arctan2(aim_last[1], aim_last[0])) / 90\n        angle_target = np.degrees(np.pi / 2 - np.arctan2(target[1], target[0])) / 90\n\n        # choice of point to aim for steering, removing outlier predictions\n        # use target point if it has a smaller angle or if error is large\n        # predicted point otherwise\n        # (reduces noise in eg. straight roads, helps with sudden turn commands)\n        use_target_to_aim = np.abs(angle_target) < np.abs(angle)\n        use_target_to_aim = use_target_to_aim or (np.abs(angle_target-angle_last) > self.angle_thresh and target[1] < self.dist_thresh)\n        if use_target_to_aim:\n            angle_final = angle_target\n        else:\n            angle_final = angle\n\n        steer = self.turn_controller.step(angle_final)\n        steer = np.clip(steer, -1.0, 1.0)\n\n        brake = desired_speed < self.brake_speed or (speed / desired_speed) > self.brake_ratio\n\n        delta = np.clip(desired_speed - speed, 0.0, self.clip_delta)\n        throttle = self.speed_controller.step(delta)\n        throttle = np.clip(throttle, 0.0, self.max_throttle)\n        throttle = throttle if not brake else 0.0\n\n        metadata = {\n            'speed': float(speed.astype(np.float64)),\n            'steer': float(steer),\n            'throttle': float(throttle),\n            'brake': float(brake),\n            'wp_4': tuple(waypoints[3].astype(np.float64)),\n            'wp_3': tuple(waypoints[2].astype(np.float64)),\n            'wp_2': tuple(waypoints[1].astype(np.float64)),\n            'wp_1': tuple(waypoints[0].astype(np.float64)),\n            'aim': tuple(aim.astype(np.float64)),\n            'target': tuple(target.astype(np.float64)),\n            'desired_speed': float(desired_speed.astype(np.float64)),\n            'angle': float(angle.astype(np.float64)),\n            'angle_last': float(angle_last.astype(np.float64)),\n            'angle_target': float(angle_target.astype(np.float64)),\n            'angle_final': float(angle_final.astype(np.float64)),\n            'delta': float(delta.astype(np.float64)),\n        }\n\n        return steer, throttle, brake, metadata"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/team_code/planner.py",
    "content": "import os\nfrom collections import deque\n\nimport numpy as np\nimport math\nEARTH_RADIUS_EQUA = 6378137.0\n\n\nDEBUG = int(os.environ.get('HAS_DISPLAY', 0))\n\n\nclass Plotter(object):\n    def __init__(self, size):\n        self.size = size\n        self.clear()\n        self.title = str(self.size)\n\n    def clear(self):\n        from PIL import Image, ImageDraw\n\n        self.img = Image.fromarray(np.zeros((self.size, self.size, 3), dtype=np.uint8))\n        self.draw = ImageDraw.Draw(self.img)\n\n    def dot(self, pos, node, color=(255, 255, 255), r=2):\n        x, y = 5.5 * (pos - node)\n        x += self.size / 2\n        y += self.size / 2\n\n        self.draw.ellipse((x-r, y-r, x+r, y+r), color)\n\n    def show(self):\n        if not DEBUG:\n            return\n\n        import cv2\n\n        cv2.imshow(self.title, cv2.cvtColor(np.array(self.img), cv2.COLOR_BGR2RGB))\n        cv2.waitKey(1)\n\n\nclass RoutePlanner(object):\n    def __init__(self, min_distance, max_distance, debug_size=256, lat_ref=42.0, lon_ref=2.0):\n        self.route = deque()\n        self.min_distance = min_distance\n        self.max_distance = max_distance\n\n        # self.mean = np.array([49.0, 8.0]) # for carla 9.9\n        # self.scale = np.array([111324.60662786, 73032.1570362]) # for carla 9.9\n        self.mean = np.array([0.0, 0.0]) # for carla 9.10\n        self.scale = np.array([111324.60662786, 111319.490945]) # for carla 9.10\n\n        self.debug = Plotter(debug_size)\n        # self.lat_ref, self.lon_ref = self._get_latlon_ref()\n        self.lat_ref = lat_ref\n        self.lon_ref = lon_ref\n\n    def set_route(self, global_plan, gps=False, global_plan_world = None):\n        self.route.clear()\n\n        if global_plan_world:\n            for (pos, cmd), (pos_word, _ )in zip(global_plan, global_plan_world):\n                if gps:\n                    pos = self.gps_to_location(np.array([pos['lat'], pos['lon']]))\n                    # pos -= self.mean\n                    # pos *= self.scale\n                else:\n                    pos = np.array([pos.location.x, pos.location.y])\n                    # pos -= self.mean\n                \n                self.route.append((pos, cmd, pos_word))\n        else:\n            for pos, cmd in global_plan:\n                if gps:\n                    pos = self.gps_to_location(np.array([pos['lat'], pos['lon']]))\n                    # pos -= self.mean\n                    # pos *= self.scale\n                else:\n                    pos = np.array([pos.location.x, pos.location.y])\n                    # pos -= self.mean\n\n                self.route.append((pos, cmd))\n\n    def run_step(self, gps):\n        self.debug.clear()\n\n        if len(self.route) == 1:\n            return self.route[0]\n\n        to_pop = 0\n        farthest_in_range = -np.inf\n        cumulative_distance = 0.0\n\n        for i in range(1, len(self.route)):\n            if cumulative_distance > self.max_distance:\n                break\n\n            cumulative_distance += np.linalg.norm(self.route[i][0] - self.route[i-1][0])\n            distance = np.linalg.norm(self.route[i][0] - gps)\n\n            if distance <= self.min_distance and distance > farthest_in_range:\n                farthest_in_range = distance\n                to_pop = i\n\n            r = 255 * int(distance > self.min_distance)\n            g = 255 * int(self.route[i][1].value == 4)\n            b = 255\n            self.debug.dot(gps, self.route[i][0], (r, g, b))\n\n        for _ in range(to_pop):\n            if len(self.route) > 2:\n                self.route.popleft()\n\n        self.debug.dot(gps, self.route[0][0], (0, 255, 0))\n        self.debug.dot(gps, self.route[1][0], (255, 0, 0))\n        self.debug.dot(gps, gps, (0, 0, 255))\n        self.debug.show()\n\n        return self.route[1]\n    \n    def gps_to_location(self, gps):\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/team_code/sparsedrive_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\n\nimport math\nfrom scipy.optimize import fsolve\nfrom pyquaternion import Quaternion\n\nfrom PIL import Image\nimport cv2\nimport numpy as np\nimport torch\nimport pickle\n\nimport carla\nfrom team_code.pid_controller import PIDController\nfrom team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom mmcv import Config\nfrom mmcv.runner import load_checkpoint\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmdet.models import build_detector\nfrom mmdet.datasets.pipelines import Compose\n\n\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\nCAMERAS = ['CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_FRONT_LEFT', 'CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']\nframe_rate = 10\nresize_scale = 1\nsave_interval = 1\n\n\nlefthand_ego_to_lidar = np.array([[ 0, 1, 0, 0],\n                                  [ 1, 0, 0, 0],\n                                  [ 0, 0, 1, 0],\n                                  [ 0, 0, 0, 1]])\n\nleft2right = np.eye(4)\nleft2right[1,1] = -1\n\n\ndef get_entry_point():\n    return 'SparseDriveAgent'\n\nclass Clock():\n    def __init__(self):\n        self.time =  time.time()\n        self.verbose = False\n\n    def count(self, tag):\n        if self.verbose:\n            prev_time = self.time\n            self.time = time.time()\n            print(tag, self.time - prev_time)\n        else:\n            pass\n    \n\nclass SparseDriveAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file, gpu_rank, save_name):\n        self.save_name = save_name\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        self.cfg = cfg\n        if hasattr(cfg, \"plugin\"):\n            if cfg.plugin:\n                import importlib\n\n                if hasattr(cfg, \"plugin_dir\"):\n                    plugin_dir = cfg.plugin_dir\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split(\"/\")\n                    _module_path = _module_dir[0]\n\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + \".\" + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)\n                else:\n                    # import dir is the dirpath for the config file\n                    _module_dir = os.path.dirname(args.config)\n                    _module_dir = _module_dir.split(\"/\")\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + \".\" + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)\n  \n        self.gpu_rank = gpu_rank\n        model = build_detector(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model = MMDataParallel(model, device_ids=[gpu_rank])\n        self.device = next(self.model.module.parameters()).device\n        self.model.eval()\n        self.test_pipeline = []\n        for test_pipeline in cfg.test_pipeline:\n            if test_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.test_pipeline.append(test_pipeline)\n        self.test_pipeline = Compose(self.test_pipeline)\n        self.data_aug_conf = cfg.data_aug_conf\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n\n        self.save_path = pathlib.Path(f'close_loop_log/save/{save_name}')\n        self.save_path.mkdir(parents=True, exist_ok=True)\n        (self.save_path / 'rgb_front' ).mkdir(exist_ok=True)\n        (self.save_path / 'rgb_front_right').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_front_left').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_back').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_back_right').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_back_left').mkdir(exist_ok=True)\n        (self.save_path / 'meta').mkdir(exist_ok=True)\n        (self.save_path / 'bev').mkdir(exist_ok=True)\n   \n        # self.lidar2img = {\n        # 'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n        #                       [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n        #                       [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n        #                       [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        # 'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n        #                             [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n        #                             [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n        #                             [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        # 'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n        #                            [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n        #                            [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n        #                            [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        # 'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n        #                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n        #                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, 1.61000000e+00],\n        #                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,1.00000000e+00]]),\n        # 'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n        #                           [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n        #                           [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n        #                           [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        # 'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n        #                             [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n        #                             [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n        #                             [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        # }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                                [ 0.  ,  0.  ,  1.  ,  0.  ],\n                                [ 0.  , -1.  ,  0.  ,  0.  ],\n                                [ 0.  , -0.24, -1.19,  1.  ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644,  0.        ,  0.81915204,  0.        ],\n                                    [-0.81915204,  0.        ,  0.57357644,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [ 0.22517331, -0.24      , -0.82909407,  1.        ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.        , -0.81915204,  0.        ],\n                                    [ 0.81915204,  0.        ,  0.57357644,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [-0.22517331, -0.24      , -0.82909407,  1.        ]]),\n        'CAM_BACK':np.array([[-1.00000000e+00,  0.00000000e+00,  1.22464680e-16, 0.00000000e+00],\n                            [-1.22464680e-16,  0.00000000e+00, -1.00000000e+00, 0.00000000e+00],\n                            [ 0.00000000e+00, -1.00000000e+00,  0.00000000e+00, 0.00000000e+00],\n                            [-1.97168135e-16, -2.40000000e-01, -1.61000000e+00, 1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.        , -0.93969262,  0.        ],\n                                    [ 0.93969262,  0.        , -0.34202014,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [-0.25388956, -0.24      , -0.49288953,  1.        ]]),\n        'CAM_BACK_RIGHT':np.array([[-0.34202014,  0.        ,  0.93969262,  0.        ],\n                                    [-0.93969262,  0.        , -0.34202014,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [ 0.25388956, -0.24      , -0.49288953,  1.        ]])\n        }\n        self.cam_intrinsic = {\n        'CAM_FRONT': np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                            [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                            [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_FRONT_RIGHT': np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_FRONT_LEFT': np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[560.16603057,   0.        , 800.        ],\n                            [  0.        , 560.16603057, 450.        ],\n                            [  0.        ,   0.        ,   1.        ]]),\n        'CAM_BACK_LEFT':np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK_RIGHT':np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        }\n\n        self.lidar2img = {}\n        for key, value in self.cam_intrinsic.items():\n            intrinsic = value * resize_scale\n            self.cam_intrinsic[key] = intrinsic\n\n            viewpad = np.eye(4)\n            viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n            lidar2cam = self.lidar2cam[key]\n            self.lidar2img[key] = viewpad @ lidar2cam.T\n\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n        self.clock = Clock() \n\n        self.stuck_detector = 0\n        self.forced_move = 0\n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n\n    def sensors(self):\n        W = 1600 * resize_scale\n        H = 900 * resize_scale\n\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': W, 'height': H, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n                # lidar\n                {   'type': 'sensor.lidar.ray_cast',\n                    'x': -0.39, 'y': 0.0, 'z': 1.84,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 85,\n                    'rotation_frequency': 10,\n                    'channels': 64,\n                    'points_per_second': 600000,\n                    'dropoff_general_rate': 0.0,\n                    'dropoff_intensity_limit': 0.0,\n                    'dropoff_zero_intensity': 0.0,\n                    'id': 'LIDAR_TOP'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in CAMERAS:\n            img = input_data[cam][1][:, :, :3]\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n\n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        self.clock.count(\"start\")\n        tick_data = self.tick(input_data)\n        self.clock.count(\"tick\")\n        #import pdb;pdb.set_trace()\n        results = {}\n        results['timestamp'] = self.step / frame_rate\n        results['img'] = []\n        results['lidar2img'] = []\n  \n        for cam in CAMERAS:\n            results['img'].append(tick_data['imgs'][cam])\n            results['lidar2img'].append(self.lidar2img[cam])\n        \n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        \n        lidar = CarlaDataProvider.get_world().get_actors().filter('*sensor.lidar.ray_cast*')[0]\n        world2lidar = lidar.get_transform().get_inverse_matrix()\n        world2lidar = lefthand_ego_to_lidar @ world2lidar @ left2right\n        lidar2global =  self.invert_pose(world2lidar)\n        results['lidar2global'] = lidar2global\n\n        ego_status = np.zeros(10, dtype=np.float32)\n        ego_status[:3] = np.array([tick_data['acceleration'][0],-tick_data['acceleration'][1],tick_data['acceleration'][2]])\n        ego_status[3:6] = -np.array(tick_data['angular_velocity'])\n        ego_status[6:9] = np.array([tick_data['speed'],0,0])\n        results[\"ego_status\"] = ego_status\n        \n        if self.cfg.num_cmd > 1:\n            command = tick_data['command_near']\n            if command < 0:\n                command = 4\n            command -= 1\n            command_onehot = np.zeros(6)\n            command_onehot[command] = 1\n        else:\n            command = 0\n            command_onehot = np.array([0, ])\n        # import ipdb; ipdb.set_trace()\n        results['gt_ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n        results['tp_near'] = local_command_xy\n        results['tp_far'] = local_command_xy\n\n        # ego2world = np.eye(4)\n        # ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        # ego2world[0:2,3] = can_bus[0:2]\n        # lidar2global = ego2world @ self.lidar2ego\n        # results['lidar2global'] = lidar2global\n\n        stacked_img = np.stack(results['img'], axis=-1)\n        results['img_shape'] = stacked_img.shape\n        results['ori_shape'] = stacked_img.shape\n        results['pad_shape'] = stacked_img.shape\n\n        aug_config = self.get_augmentation()\n        results[\"aug_config\"] = aug_config\n        #import pdb;pdb.set_trace()\n        results = self.test_pipeline(results)\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data):\n                    data = data.to(self.device)\n        self.clock.count(\"data\")\n        output_data_batch = self.model(**input_data_batch)\n        self.clock.count(\"model\")\n        out_truck = output_data_batch[0]['img_bbox']['final_planning'].numpy()\n        #all_out_truck =  np.cumsum(out_truck,axis=0)\n        \n        ## creep\n        is_stuck = False\n        if(self.stuck_detector > 150 and self.forced_move < 15):\n            print(\"Detected agent being stuck. Move for frame: \", self.forced_move)\n            is_stuck = True\n            self.forced_move += 1\n\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)#, is_stuck)\n        #import pdb;pdb.set_trace()\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        if is_stuck:\n            steer_traj *= 0.5\n\n        if(tick_data['speed'] < 0.1): # 0.1 is just an arbitrary low number to threshhold when the car is stopped\n            self.stuck_detector += 1\n\n        elif(tick_data['speed'] > 0.1 and is_stuck == False):\n            self.stuck_detector = 0\n            self.forced_move    = 0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['local_command_xy'] = local_command_xy\n        self.pid_metadata['result'] = output_data_batch[0]['img_bbox']\n\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n\n        if self.step % save_interval == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n\n        return control\n\n    def save(self, tick_data):\n        frame = self.step // save_interval\n\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n\n        data = {}\n\n        cmd = np.zeros(6)\n        cmd[self.pid_metadata[\"command\"]] = 1\n        data[\"gt_ego_fut_cmd\"] = cmd\n        data[\"tp_near\"] = self.pid_metadata[\"local_command_xy\"]\n\n        data[\"img_filename\"] = [\n            self.save_path / 'rgb_front' / ('%04d.png' % frame),\n            self.save_path / 'rgb_front_right' / ('%04d.png' % frame),\n            self.save_path / 'rgb_front_left' / ('%04d.png' % frame),\n            self.save_path / 'rgb_back' / ('%04d.png' % frame),\n            self.save_path / 'rgb_back_left' / ('%04d.png' % frame),\n            self.save_path / 'rgb_back_right' / ('%04d.png' % frame),\n        ]\n\n        data['lidar2cam'] = []\n        data['cam_intrinsic'] = []\n        for cam in CAMERAS:\n            data['lidar2cam'].append(self.lidar2cam[cam])\n            data['cam_intrinsic'].append(self.cam_intrinsic[cam])\n        \n        self.pid_metadata[\"data\"] = data\n            \n        outfile = open(self.save_path / 'meta' / ('%04d.pkl' % frame), 'wb')\n        pickle.dump(self.pid_metadata, outfile)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n\n    def get_augmentation(self):\n        H = 900 * resize_scale\n        W = 1600 * resize_scale\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        resize = max(fH / H, fW / W)\n        resize_dims = (int(W * resize), int(H * resize))\n        newW, newH = resize_dims\n        crop_h = (\n            int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n            - fH\n        )\n        crop_w = int(max(0, newW - fW) / 2)\n        crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n        flip = False\n        rotate = 0\n        rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\ndef draw(input, step, cfg):\n    img = input['img'].data[0][0, 0]\n    projection_mat = input['projection_mat'].data[0, 0]\n    key_points = torch.tensor([0, 10, -1.8])\n    pts_extend = torch.cat(\n        [key_points, torch.ones_like(key_points[..., :1])], dim=-1\n    )\n    points_2d = torch.matmul(\n        projection_mat, pts_extend[..., None]\n    ).squeeze(-1)\n    points_2d = points_2d[..., :2] / torch.clamp(\n        points_2d[..., 2:3], min=1e-5\n    )\n    print(points_2d[0]/img.shape[2], points_2d[1]/img.shape[1])\n    points_2d = points_2d.numpy()\n    img = img.numpy().transpose(1, 2, 0).astype(np.uint8)\n    img = img.copy()\n    cv2.circle(img, (int(points_2d[0]), int(points_2d[1])), 5, (0, 0, 255))\n    cv2.imwrite(f'vis3/{resize_scale}_{cfg.data_aug_conf[\"final_dim\"]}{step}.jpg', img)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/team_code/uniad_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom Bench2DriveZoo.team_code.pid_controller import PIDController\nfrom Bench2DriveZoo.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\nfrom scipy.optimize import fsolve\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\ndef get_entry_point():\n    return 'UniadAgent'\n\nclass UniadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steers = deque()\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        cfg.model['motion_head']['anchor_info_path'] = os.path.join('Bench2DriveZoo',cfg.model['motion_head']['anchor_info_path'])\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.last_steers = deque()\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            # string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string = self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        # write extrinsics directly\n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                                  [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                                  [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                                 [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n          'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n          'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                       [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n         'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                                 [ 0.  ,  0.  , -1.  , -0.24],\n                                 [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                      [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n          'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n    def _init(self):\n        \n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0        \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n                \n            ]\n        \n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n    \n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n  \n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n  \n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n  \n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        out_truck =  output_data_batch[0]['planning']['result_planning']['sdc_traj'][0].cpu().numpy()\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n        if tick_data['speed']>5:\n            throttle_traj = 0\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)\n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n        if SAVE_PATH is not None and self.step % 1 == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        return control\n\n    def save(self, tick_data):\n        frame = self.step // 10\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/team_code/vad_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nfrom scipy.optimize import fsolve\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom team_code.pid_controller import PIDController\nfrom team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,\n                        wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\n\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\n\ndef get_entry_point():\n    return 'VadAgent'\n\n\nclass VadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string += self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                              [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                              [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                              [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                    [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                              [ 0.  ,  0.  , -1.  , -0.24],\n                              [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n  \n  \n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n  \n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        \n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = can_bus[0:2].copy()\n        ego_lcf_feat[2:4] = can_bus[10:12].copy()\n        ego_lcf_feat[4] = rotation[-1]\n        ego_lcf_feat[5] = 4.89238167\n        ego_lcf_feat[6] = 1.83671331\n        ego_lcf_feat[7] = np.sqrt(can_bus[0]**2+can_bus[1]**2)\n\n        if len(self.prev_control_cache)<10:\n            ego_lcf_feat[8] = 0\n        else:\n            ego_lcf_feat[8] = self.prev_control_cache[0].steer\n\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n        command_onehot = np.zeros(6)\n        command_onehot[command] = 1\n        results['ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        #import pdb;pdb.set_trace()\n        #all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds_refine'].cpu().numpy()\n        all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds_refine'].cpu().numpy() # [6,6,2]\n        all_cls = output_data_batch[0]['pts_bbox']['ego_fut_classification_refine'].reshape(6,6,-1).sum(dim=-1)\n        all_cls = all_cls.cpu().numpy()\n        nnums = np.arange(all_out_truck_d1.shape[0])\n        all_out_truck_d1 = all_out_truck_d1[nnums,all_cls.argmax(-1), :, :]\n        #all_cls = all_cls.reshape(6,6,-1).sum(dim=-1)\n        #import pdb;pdb.set_trace()\n        all_out_truck =  np.cumsum(all_out_truck_d1,axis=1)\n        out_truck = all_out_truck[command]\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['all_plan'] = all_out_truck.tolist()\n\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n        if SAVE_PATH is not None and self.step % 1 == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n        return control\n\n\n    def save(self, tick_data):\n        frame = self.step // 10\n\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n\n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/leaderboard/team_code/vad_b2d_agent_visualize.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nfrom scipy.optimize import fsolve\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom Bench2DriveZoo.team_code.pid_controller import PIDController\nfrom Bench2DriveZoo.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,\n                        wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\nfrom scipy.interpolate import splprep, splev\nimport copy\nimport seaborn as sns\n\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\ndef float_to_uint8_color(float_clr):\n    assert all([c >= 0. for c in float_clr])\n    assert all([c <= 1. for c in float_clr])\n    return [int(c * 255.) for c in float_clr]\n\n\nCOLORS = [float_to_uint8_color(clr) for clr in sns.color_palette(\"bright\", n_colors=10)]\nCOLORMAP = OrderedDict({\n    6: COLORS[8],  # yellow\n    4: COLORS[8],\n    3: COLORS[0],  # blue\n    1: COLORS[6],  # pink\n    0: COLORS[2],  # green\n    8: COLORS[7],  # gray\n    7: COLORS[1],  # orange\n    5: COLORS[3],  # red\n    2: COLORS[5],  # brown\n})\n\ndef get_entry_point():\n    return 'VadAgent'\n\n\nclass VadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string += self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                              [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                              [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                              [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                    [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                              [ 0.  ,  0.  , -1.  , -0.24],\n                              [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        # topdown_extrinsics =  np.array([[0.0, -0.0, -1.0, 50.0], \n        #                                 [0.0,  1.0, -0.0,  0.0], \n        #                                 [1.0, -0.0,  0.0, -0.0], \n        #                                 [0.0,  0.0,  0.0,  1.0]])\n        # unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        #unreal2cam @ topdown_extrinsics\n        self.coor2topdown = np.array([[1.0,  0.0,  0.0,  0.0], \n                                      [0.0, -1.0,  0.0,  0.0], \n                                      [0.0,  0.0, -1.0, 50.0], \n                                      [0.0,  0.0,  0.0,  1.0]])\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown         \n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n  \n  \n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n  \n        if math.isnan(compass): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = can_bus[0:2].copy()\n        ego_lcf_feat[2:4] = can_bus[10:12].copy()\n        ego_lcf_feat[4] = rotation[-1]\n        ego_lcf_feat[5] = 4.89238167\n        ego_lcf_feat[6] = 1.83671331\n        ego_lcf_feat[7] = np.sqrt(can_bus[0]**2+can_bus[1]**2)\n\n        if len(self.prev_control_cache)<10:\n            ego_lcf_feat[8] = 0\n        else:\n            ego_lcf_feat[8] = self.prev_control_cache[0].steer\n\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n        command_onehot = np.zeros(6)\n        command_onehot[command] = 1\n        results['ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds'].cpu().numpy()\n        all_out_truck =  np.cumsum(all_out_truck_d1,axis=1)\n        out_truck = all_out_truck[command]\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['all_plan'] = all_out_truck.tolist()\n\n        #if SAVE_PATH is not None and self.step % 10 == 0:\n        self.save(tick_data,out_truck,output_data_batch)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n        return control\n\n\n    def save(self, tick_data,ego_traj,result=None):\n        frame = self.step\n        imgs_with_box = {}\n        for cam, img in tick_data['imgs'].items():\n            imgs_with_box[cam] = self.draw_lidar_bbox3d_on_img(result[0]['pts_bbox']['boxes_3d'], tick_data['imgs'][cam], self.lidar2img[cam], scores=result[0]['pts_bbox']['scores_3d'],labels=result[0]['pts_bbox']['labels_3d'],canvas_size=(900,1600))\n        imgs_with_box['bev'] = self.draw_lidar_bbox3d_on_img(result[0]['pts_bbox']['boxes_3d'], tick_data['bev'], self.coor2topdown, scores=result[0]['pts_bbox']['scores_3d'],labels=result[0]['pts_bbox']['labels_3d'],trajs=result[0]['pts_bbox']['trajs_3d'],canvas_size=(512,512))\n        imgs_with_box['bev'] = self.draw_traj_bev(ego_traj, imgs_with_box['bev'],is_ego=True)\n        imgs_with_box['CAM_FRONT'] = self.draw_traj(ego_traj, imgs_with_box['CAM_FRONT'])\n        for cam, img in imgs_with_box.items():\n            Image.fromarray(img).save(self.save_path / str.lower(cam).replace('cam','rgb') / ('%04d.png' % frame))   \n                \n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n        \n    def draw_traj(self, traj, raw_img,canvas_size=(900,1600),thickness=3,is_ego=True,hue_start=120,hue_end=80):\n        line = traj\n        lidar2img_rt = self.lidar2img['CAM_FRONT']\n        img = raw_img.copy()\n        pts_4d = np.stack([line[:,0],line[:,1],np.ones((line.shape[0]))*(-1.84),np.ones((line.shape[0]))])\n        pts_2d = ((lidar2img_rt @ pts_4d).T)\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        mask = (pts_2d[:, 0]>0) & (pts_2d[:, 0]<canvas_size[1]) & (pts_2d[:, 1]>0) & (pts_2d[:, 1]<canvas_size[0])\n        if not mask.any():\n            return img\n        pts_2d = pts_2d[mask,0:2]\n        if is_ego:\n            pts_2d = np.concatenate([np.array([[800,900]]),pts_2d],axis=0)\n        try:\n            tck, u = splprep([pts_2d[:, 0], pts_2d[:, 1]], s=0)\n        except:\n            return img\n        unew = np.linspace(0, 1, 100)\n        smoothed_pts = np.stack(splev(unew, tck)).astype(int).T\n        \n        num_points = len(smoothed_pts)\n        for i in range(num_points-1):\n            hue = hue_start + (hue_end - hue_start) * (i / num_points)\n            hsv_color = np.array([hue, 255, 255], dtype=np.uint8)\n            rgb_color = cv2.cvtColor(hsv_color[np.newaxis, np.newaxis, :], cv2.COLOR_HSV2RGB).reshape(-1)\n            rgb_color_tuple = (float(rgb_color[0]),float(rgb_color[1]),float(rgb_color[2]))\n            cv2.line(img,(smoothed_pts[i,0],smoothed_pts[i,1]),(smoothed_pts[i+1,0],smoothed_pts[i+1,1]),color=rgb_color_tuple, thickness=thickness)  \n      \n        return img\n\n\n\n    def draw_traj_bev(self, traj, raw_img,canvas_size=(512,512),thickness=3,is_ego=False,hue_start=120,hue_end=80):\n        if is_ego:\n            line = np.concatenate([np.zeros((1,2)),traj],axis=0)\n        else:\n            line = traj\n        img = raw_img.copy()        \n        pts_4d = np.stack([line[:,0],line[:,1],np.zeros((line.shape[0])),np.ones((line.shape[0]))])\n        pts_2d = (self.coor2topdown @ pts_4d).T\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        mask = (pts_2d[:, 0]>0) & (pts_2d[:, 0]<canvas_size[1]) & (pts_2d[:, 1]>0) & (pts_2d[:, 1]<canvas_size[0])\n        if not mask.any():\n            return img\n        pts_2d = pts_2d[mask,0:2]\n        try:\n            tck, u = splprep([pts_2d[:, 0], pts_2d[:, 1]], s=0)\n        except:\n            return img\n        unew = np.linspace(0, 1, 100)\n        smoothed_pts = np.stack(splev(unew, tck)).astype(int).T\n\n        num_points = len(smoothed_pts)\n        for i in range(num_points-1):\n            hue = hue_start + (hue_end - hue_start) * (i / num_points)\n            hsv_color = np.array([hue, 255, 255], dtype=np.uint8)\n            rgb_color = cv2.cvtColor(hsv_color[np.newaxis, np.newaxis, :], cv2.COLOR_HSV2RGB).reshape(-1)\n            rgb_color_tuple = (float(rgb_color[0]),float(rgb_color[1]),float(rgb_color[2]))\n            if smoothed_pts[i,0]>0 and smoothed_pts[i,0]<canvas_size[1] and smoothed_pts[i,1]>0 and smoothed_pts[i,1]<canvas_size[0]:\n                cv2.line(img,(smoothed_pts[i,0],smoothed_pts[i,1]),(smoothed_pts[i+1,0],smoothed_pts[i+1,1]),color=rgb_color_tuple, thickness=thickness)   \n            elif i==0:\n                break\n        return img\n    \n    def draw_lidar_bbox3d_on_img(self,bboxes3d,raw_img,lidar2img_rt,canvas_size=(900,1600),img_metas=None,scores=None,labels=None,trajs=None,color=(0, 255, 0),thickness=1):\n        img = raw_img.copy()\n        bboxes3d_numpy = bboxes3d.tensor.cpu().numpy()\n        if len(bboxes3d_numpy) == 0:\n            return img\n        corners_3d = bboxes3d.corners\n        num_bbox = corners_3d.shape[0]\n        pts_4d = np.concatenate(\n            [corners_3d.reshape(-1, 3),\n            np.ones((num_bbox * 8, 1))], axis=-1)\n        lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n        if isinstance(lidar2img_rt, torch.Tensor):\n            lidar2img_rt = lidar2img_rt.cpu().numpy()\n        if isinstance(scores, torch.Tensor):\n            scores = scores.cpu().numpy()            \n        if isinstance(labels, torch.Tensor):\n            labels = labels.cpu().numpy()            \n            \n        pts_2d = (lidar2img_rt @ pts_4d.T).T\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)\n        depth = pts_2d[..., 2].reshape(num_bbox, 8)\n        mask1 = ((imgfov_pts_2d[:,:,0]>-1e5) & (imgfov_pts_2d[:,:,0]<1e5)&(imgfov_pts_2d[:,:,1]>-1e5) & (imgfov_pts_2d[:,:,1]<1e5) & (depth > -1) ).all(-1)\n        mask2 = (imgfov_pts_2d.reshape(num_bbox,16).max(axis=-1) - imgfov_pts_2d.reshape(num_bbox,16).min(axis=-1))< 2000\n        mask = mask1 & mask2\n        if scores is not None:\n            mask3 = (scores>=0.3)\n            mask = mask & mask3\n            \n        if not mask.any():\n            return img\n\n        scores = scores[mask] if scores is not None else None\n        labels = labels[mask] if labels is not None else None\n        \n        imgfov_pts_2d = imgfov_pts_2d[mask]\n        num_bbox = mask.sum()\n        if trajs is not None:\n            \n            trajs = trajs[mask]\n            agent_boxes = bboxes3d_numpy[mask]\n            for traj,agent_box,label in zip(trajs,agent_boxes,labels):\n                if label in [0,1,2,3,7]:\n                    for i in range(6):\n                        traj1 = np.concatenate([np.zeros((1,2)),traj[i].reshape(6,2)],axis=0)\n                        traj1 = np.cumsum(traj1,axis=0) + agent_box[None,0:2]\n                        #traj1 = (r_m @ traj1.T).T + agent_box[None,0:2]\n                        if canvas_size==(900,1600):\n                            img = self.draw_traj(traj1,img,hue_start=0,hue_end=20)\n                        else:\n                            img = self.draw_traj_bev(traj1,img,hue_start=0,hue_end=20)\n\n        return self.plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, scores, labels, color, thickness,bev=(canvas_size!=(900,1600))) \n    \n    \n\n    \n    def plot_rect3d_on_img(self,img,num_rects,rect_corners,scores=None,labels=None,color=(0, 255, 0),thickness=1,bev=False):\n        line_indices = ((0, 1), (0, 3), (0, 4), (1, 2), (1, 5), (3, 2), (3, 7),\n                        (4, 5), (4, 7), (2, 6), (5, 6), (6, 7))\n        if bev:\n            line_indices = ((0, 3), (3, 7),(4, 7), (0, 4))\n        for i in range(num_rects):\n            c = COLORMAP[labels[i]]\n            thinck = 2\n            corners = rect_corners[i].astype(np.int)\n            # if scores is not None:\n            #     cv2.putText(img, \"{:.2f}\".format(scores[i]), corners[0], cv2.FONT_HERSHEY_SIMPLEX, 0.3, (0,0,0), 1)\n            if scores[i] < 0.3:\n                continue\n                #     c=(255,255,255)\n                #     thinck=1\n            for start, end in line_indices:\n                cv2.line(img, (corners[start, 0], corners[start, 1]),\n                        (corners[end, 0], corners[end, 1]), c, thinck,\n                        cv2.LINE_AA)\n        return img.astype(np.uint8)\n    \n\n        \n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/__init__.py",
    "content": "from .datasets import *\nfrom .models import *\nfrom .apis import *\nfrom .core.evaluation import *\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/apis/__init__.py",
    "content": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector\n\n# from .test import custom_multi_gpu_test\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/apis/mmdet_train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport random\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.runner import (\n    HOOKS,\n    DistSamplerSeedHook,\n    EpochBasedRunner,\n    Fp16OptimizerHook,\n    OptimizerHook,\n    build_optimizer,\n    build_runner,\n    get_dist_info,\n)\nfrom mmcv.utils import build_from_cfg\n\nfrom mmdet.core import EvalHook\n\nfrom mmdet.datasets import build_dataset, replace_ImageToTensor\nfrom mmdet.utils import get_root_logger\nimport time\nimport os.path as osp\nfrom mmdet3d_plugin.datasets.builder import build_dataloader\nfrom mmdet3d_plugin.core.evaluation.eval_hooks import (\n    CustomDistEvalHook,\n)\nfrom mmdet3d_plugin.datasets import custom_build_dataset\n\n\ndef custom_train_detector(\n    model,\n    dataset,\n    cfg,\n    distributed=False,\n    validate=False,\n    timestamp=None,\n    meta=None,\n):\n    logger = get_root_logger(cfg.log_level)\n\n    # prepare data loaders\n\n    dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]\n    # assert len(dataset)==1s\n    if \"imgs_per_gpu\" in cfg.data:\n        logger.warning(\n            '\"imgs_per_gpu\" is deprecated in MMDet V2.0. '\n            'Please use \"samples_per_gpu\" instead'\n        )\n        if \"samples_per_gpu\" in cfg.data:\n            logger.warning(\n                f'Got \"imgs_per_gpu\"={cfg.data.imgs_per_gpu} and '\n                f'\"samples_per_gpu\"={cfg.data.samples_per_gpu}, \"imgs_per_gpu\"'\n                f\"={cfg.data.imgs_per_gpu} is used in this experiments\"\n            )\n        else:\n            logger.warning(\n                'Automatically set \"samples_per_gpu\"=\"imgs_per_gpu\"='\n                f\"{cfg.data.imgs_per_gpu} in this experiments\"\n            )\n        cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu\n\n    if \"runner\" in cfg:\n        runner_type = cfg.runner[\"type\"]\n    else:\n        runner_type = \"EpochBasedRunner\"\n    data_loaders = [\n        build_dataloader(\n            ds,\n            cfg.data.samples_per_gpu,\n            cfg.data.workers_per_gpu,\n            # cfg.gpus will be ignored if distributed\n            len(cfg.gpu_ids),\n            dist=distributed,\n            seed=cfg.seed,\n            nonshuffler_sampler=dict(\n                type=\"DistributedSampler\"\n            ),  # dict(type='DistributedSampler'),\n            runner_type=runner_type,\n        )\n        for ds in dataset\n    ]\n\n    # put model on gpus\n    if distributed:\n        find_unused_parameters = cfg.get(\"find_unused_parameters\", False)\n        # Sets the `find_unused_parameters` parameter in\n        # torch.nn.parallel.DistributedDataParallel\n        model = MMDistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n            find_unused_parameters=find_unused_parameters,\n        )\n\n    else:\n        model = MMDataParallel(\n            model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids\n        )\n\n    # build runner\n    optimizer = build_optimizer(model, cfg.optimizer)\n\n    if \"runner\" not in cfg:\n        cfg.runner = {\n            \"type\": \"EpochBasedRunner\",\n            \"max_epochs\": cfg.total_epochs,\n        }\n        warnings.warn(\n            \"config is now expected to have a `runner` section, \"\n            \"please set `runner` in your config.\",\n            UserWarning,\n        )\n    else:\n        if \"total_epochs\" in cfg:\n            assert cfg.total_epochs == cfg.runner.max_epochs\n\n    runner = build_runner(\n        cfg.runner,\n        default_args=dict(\n            model=model,\n            optimizer=optimizer,\n            work_dir=cfg.work_dir,\n            logger=logger,\n            meta=meta,\n        ),\n    )\n\n    # an ugly workaround to make .log and .log.json filenames the same\n    runner.timestamp = timestamp\n\n    # fp16 setting\n    fp16_cfg = cfg.get(\"fp16\", None)\n    if fp16_cfg is not None:\n        optimizer_config = Fp16OptimizerHook(\n            **cfg.optimizer_config, **fp16_cfg, distributed=distributed\n        )\n    elif distributed and \"type\" not in cfg.optimizer_config:\n        optimizer_config = OptimizerHook(**cfg.optimizer_config)\n    else:\n        optimizer_config = cfg.optimizer_config\n\n    # register hooks\n    runner.register_training_hooks(\n        cfg.lr_config,\n        optimizer_config,\n        cfg.checkpoint_config,\n        cfg.log_config,\n        cfg.get(\"momentum_config\", None),\n    )\n\n    # register profiler hook\n    # trace_config = dict(type='tb_trace', dir_name='work_dir')\n    # profiler_config = dict(on_trace_ready=trace_config)\n    # runner.register_profiler_hook(profiler_config)\n\n    if distributed:\n        if isinstance(runner, EpochBasedRunner):\n            runner.register_hook(DistSamplerSeedHook())\n\n    # register eval hooks\n    if validate:\n        # Support batch_size > 1 in validation\n        val_samples_per_gpu = cfg.data.val.pop(\"samples_per_gpu\", 1)\n        if val_samples_per_gpu > 1:\n            assert False\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.val.pipeline = replace_ImageToTensor(\n                cfg.data.val.pipeline\n            )\n        val_dataset = custom_build_dataset(cfg.data.val, dict(test_mode=True))\n\n        val_dataloader = build_dataloader(\n            val_dataset,\n            samples_per_gpu=val_samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n        )\n        eval_cfg = cfg.get(\"evaluation\", {})\n        eval_cfg[\"by_epoch\"] = cfg.runner[\"type\"] != \"IterBasedRunner\"\n        eval_cfg[\"jsonfile_prefix\"] = osp.join(\n            \"val\",\n            cfg.work_dir,\n            time.ctime().replace(\" \", \"_\").replace(\":\", \"_\"),\n        )\n        eval_hook = CustomDistEvalHook if distributed else EvalHook\n        runner.register_hook(eval_hook(val_dataloader, **eval_cfg))\n\n    # user-defined hooks\n    if cfg.get(\"custom_hooks\", None):\n        custom_hooks = cfg.custom_hooks\n        assert isinstance(\n            custom_hooks, list\n        ), f\"custom_hooks expect list type, but got {type(custom_hooks)}\"\n        for hook_cfg in cfg.custom_hooks:\n            assert isinstance(hook_cfg, dict), (\n                \"Each item in custom_hooks expects dict type, but got \"\n                f\"{type(hook_cfg)}\"\n            )\n            hook_cfg = hook_cfg.copy()\n            priority = hook_cfg.pop(\"priority\", \"NORMAL\")\n            hook = build_from_cfg(hook_cfg, HOOKS)\n            runner.register_hook(hook, priority=priority)\n\n    if cfg.resume_from:\n        runner.resume(cfg.resume_from)\n    elif cfg.load_from:\n        runner.load_checkpoint(cfg.load_from)\n    runner.run(data_loaders, cfg.workflow)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/apis/test.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport os.path as osp\nimport pickle\nimport shutil\nimport tempfile\nimport time\n\nimport mmcv\nimport torch\nimport torch.distributed as dist\nfrom mmcv.image import tensor2imgs\nfrom mmcv.runner import get_dist_info\n\nfrom mmdet.core import encode_mask_results\n\n\nimport mmcv\nimport numpy as np\nimport pycocotools.mask as mask_util\n\n\ndef custom_encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code. Semantic Masks only\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = []\n    for i in range(len(cls_segms)):\n        encoded_mask_results.append(\n            mask_util.encode(\n                np.array(\n                    cls_segms[i][:, :, np.newaxis], order=\"F\", dtype=\"uint8\"\n                )\n            )[0]\n        )  # encoded with RLE\n    return [encoded_mask_results]\n\n\ndef custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):\n    \"\"\"Test model with multiple gpus.\n    This method tests model with multiple gpus and collects the results\n    under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'\n    it encodes results to gpu tensors and use gpu communication for results\n    collection. On cpu mode it saves the results on different gpus to 'tmpdir'\n    and collects them by the rank 0 worker.\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        tmpdir (str): Path of directory to save the temporary results from\n            different gpus under cpu mode.\n        gpu_collect (bool): Option to use either gpu or cpu to collect results.\n    Returns:\n        list: The prediction results.\n    \"\"\"\n    model.eval()\n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    rank, world_size = get_dist_info()\n    if rank == 0:\n        prog_bar = mmcv.ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(return_loss=False, rescale=True, **data)\n            # encode mask results\n            if isinstance(result, dict):\n                if \"bbox_results\" in result.keys():\n                    bbox_result = result[\"bbox_results\"]\n                    batch_size = len(result[\"bbox_results\"])\n                    bbox_results.extend(bbox_result)\n                if (\n                    \"mask_results\" in result.keys()\n                    and result[\"mask_results\"] is not None\n                ):\n                    mask_result = custom_encode_mask_results(\n                        result[\"mask_results\"]\n                    )\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n\n        if rank == 0:\n            for _ in range(batch_size * world_size):\n                prog_bar.update()\n\n    # collect results from all ranks\n    if gpu_collect:\n        bbox_results = collect_results_gpu(bbox_results, len(dataset))\n        if have_mask:\n            mask_results = collect_results_gpu(mask_results, len(dataset))\n        else:\n            mask_results = None\n    else:\n        bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)\n        tmpdir = tmpdir + \"_mask\" if tmpdir is not None else None\n        if have_mask:\n            mask_results = collect_results_cpu(\n                mask_results, len(dataset), tmpdir\n            )\n        else:\n            mask_results = None\n\n    if mask_results is None:\n        return bbox_results\n    return {\"bbox_results\": bbox_results, \"mask_results\": mask_results}\n\n\ndef collect_results_cpu(result_part, size, tmpdir=None):\n    rank, world_size = get_dist_info()\n    # create a tmp dir if it is not specified\n    if tmpdir is None:\n        MAX_LEN = 512\n        # 32 is whitespace\n        dir_tensor = torch.full(\n            (MAX_LEN,), 32, dtype=torch.uint8, device=\"cuda\"\n        )\n        if rank == 0:\n            mmcv.mkdir_or_exist(\".dist_test\")\n            tmpdir = tempfile.mkdtemp(dir=\".dist_test\")\n            tmpdir = torch.tensor(\n                bytearray(tmpdir.encode()), dtype=torch.uint8, device=\"cuda\"\n            )\n            dir_tensor[: len(tmpdir)] = tmpdir\n        dist.broadcast(dir_tensor, 0)\n        tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()\n    else:\n        mmcv.mkdir_or_exist(tmpdir)\n    # dump the part result to the dir\n    mmcv.dump(result_part, osp.join(tmpdir, f\"part_{rank}.pkl\"))\n    dist.barrier()\n    # collect all parts\n    if rank != 0:\n        return None\n    else:\n        # load results of all parts from tmp dir\n        part_list = []\n        for i in range(world_size):\n            part_file = osp.join(tmpdir, f\"part_{i}.pkl\")\n            part_list.append(mmcv.load(part_file))\n        # sort the results\n        ordered_results = []\n        \"\"\"\n        bacause we change the sample of the evaluation stage to make sure that\n        each gpu will handle continuous sample,\n        \"\"\"\n        # for res in zip(*part_list):\n        for res in part_list:\n            ordered_results.extend(list(res))\n        # the dataloader may pad some samples\n        ordered_results = ordered_results[:size]\n        # remove tmp dir\n        shutil.rmtree(tmpdir)\n        return ordered_results\n\n\ndef collect_results_gpu(result_part, size):\n    collect_results_cpu(result_part, size)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/apis/train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom .mmdet_train import custom_train_detector\n# from mmseg.apis import train_segmentor\nfrom mmdet.apis import train_detector\n\n\ndef custom_train_model(\n    model,\n    dataset,\n    cfg,\n    distributed=False,\n    validate=False,\n    timestamp=None,\n    meta=None,\n):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in [\"EncoderDecoder3D\"]:\n        assert False\n    else:\n        custom_train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\ndef train_model(\n    model,\n    dataset,\n    cfg,\n    distributed=False,\n    validate=False,\n    timestamp=None,\n    meta=None,\n):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    train_detector(\n        model,\n        dataset,\n        cfg,\n        distributed=distributed,\n        validate=validate,\n        timestamp=timestamp,\n        meta=meta,\n    )\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/core/box3d.py",
    "content": "X, Y, Z, W, L, H, SIN_YAW, COS_YAW, VX, VY, VZ = list(range(11))  # undecoded\nCNS, YNS = 0, 1  # centerness and yawness indices in quality\nYAW = 6  # decoded\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/core/evaluation/__init__.py",
    "content": "from .eval_hooks import CustomDistEvalHook"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/core/evaluation/eval_hooks.py",
    "content": "# Note: Considering that MMCV's EvalHook updated its interface in V1.3.16,\n# in order to avoid strong version dependency, we did not directly\n# inherit EvalHook but BaseDistEvalHook.\n\nimport bisect\nimport os.path as osp\n\nimport mmcv\nimport torch.distributed as dist\nfrom mmcv.runner import DistEvalHook as BaseDistEvalHook\nfrom mmcv.runner import EvalHook as BaseEvalHook\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom mmdet.core.evaluation.eval_hooks import DistEvalHook\n\n\ndef _calc_dynamic_intervals(start_interval, dynamic_interval_list):\n    assert mmcv.is_list_of(dynamic_interval_list, tuple)\n\n    dynamic_milestones = [0]\n    dynamic_milestones.extend(\n        [dynamic_interval[0] for dynamic_interval in dynamic_interval_list]\n    )\n    dynamic_intervals = [start_interval]\n    dynamic_intervals.extend(\n        [dynamic_interval[1] for dynamic_interval in dynamic_interval_list]\n    )\n    return dynamic_milestones, dynamic_intervals\n\n\nclass CustomDistEvalHook(BaseDistEvalHook):\n    def __init__(self, *args, dynamic_intervals=None, **kwargs):\n        super(CustomDistEvalHook, self).__init__(*args, **kwargs)\n        self.use_dynamic_intervals = dynamic_intervals is not None\n        if self.use_dynamic_intervals:\n            (\n                self.dynamic_milestones,\n                self.dynamic_intervals,\n            ) = _calc_dynamic_intervals(self.interval, dynamic_intervals)\n\n    def _decide_interval(self, runner):\n        if self.use_dynamic_intervals:\n            progress = runner.epoch if self.by_epoch else runner.iter\n            step = bisect.bisect(self.dynamic_milestones, (progress + 1))\n            # Dynamically modify the evaluation interval\n            self.interval = self.dynamic_intervals[step - 1]\n\n    def before_train_epoch(self, runner):\n        \"\"\"Evaluate the model only at the start of training by epoch.\"\"\"\n        self._decide_interval(runner)\n        super().before_train_epoch(runner)\n\n    def before_train_iter(self, runner):\n        self._decide_interval(runner)\n        super().before_train_iter(runner)\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        # Synchronization of BatchNorm's buffer (running_mean\n        # and running_var) is not supported in the DDP of pytorch,\n        # which may cause the inconsistent performance of models in\n        # different ranks, so we broadcast BatchNorm's buffers\n        # of rank 0 to other ranks to avoid this.\n        if self.broadcast_bn_buffer:\n            model = runner.model\n            for name, module in model.named_modules():\n                if (\n                    isinstance(module, _BatchNorm)\n                    and module.track_running_stats\n                ):\n                    dist.broadcast(module.running_var, 0)\n                    dist.broadcast(module.running_mean, 0)\n\n        if not self._should_evaluate(runner):\n            return\n\n        tmpdir = self.tmpdir\n        if tmpdir is None:\n            tmpdir = osp.join(runner.work_dir, \".eval_hook\")\n\n        from mmdet3d_plugin.apis.test import (\n            custom_multi_gpu_test,\n        )  # to solve circlur  import\n\n        results = custom_multi_gpu_test(\n            runner.model,\n            self.dataloader,\n            tmpdir=tmpdir,\n            gpu_collect=self.gpu_collect,\n        )\n        if runner.rank == 0:\n            print(\"\\n\")\n            runner.log_buffer.output[\"eval_iter_num\"] = len(self.dataloader)\n\n            key_score = self.evaluate(runner, results)\n\n            if self.save_best:\n                self._save_ckpt(runner, key_score)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/__init__.py",
    "content": "from .nuscenes_3d_dataset import NuScenes3DDataset\nfrom .b2d_3d_dataset import B2D3DDataset\nfrom .builder import *\nfrom .pipelines import *\nfrom .samplers import *\n\n__all__ = [\n    'NuScenes3DDataset',\n    \"B2D3DDataset\",\n    \"custom_build_dataset\",\n]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/b2d_3d_dataset.py",
    "content": "import random\nimport math\nimport os\nfrom os import path as osp\nimport cv2\nimport tempfile\nimport copy\nimport prettytable\nimport pickle\nimport json\n\nimport numpy as np\n# np.set_printoptions(suppress=True)\nimport torch\nfrom torch.utils.data import Dataset\nimport pyquaternion\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import LineString\nfrom .evaluation.detection.nuscenes_styled_eval_utils import (\n    DetectionMetrics, \n    EvalBoxes, \n    DetectionBox,\n    center_distance,\n    accumulate,\n    DetectionMetricDataList,\n    calc_ap, \n    calc_tp, \n    quaternion_yaw,\n)\n\n\nimport mmcv\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.pipelines import Compose\nfrom .utils import (\n    draw_lidar_bbox3d_on_img,\n    draw_lidar_bbox3d_on_bev,\n)\n\n\n@DATASETS.register_module()\nclass B2D3DDataset(Dataset):\n    CLASSES = [\n        'car',\n        'van',\n        'truck',\n        'bicycle',\n        'traffic_sign',\n        'traffic_cone',\n        'traffic_light',\n        'pedestrian',\n        'others',\n    ]\n    MAP_CLASSES = [\n        'Broken',\n        'Solid',\n        'SolidSolid',\n        # 'Center',\n        # 'TrafficLight',\n        # 'StopSign',\n    ]\n    ID_COLOR_MAP = [\n        (59, 59, 238),\n        (0, 255, 0),\n        (0, 0, 255),\n        (255, 255, 0),\n        (0, 255, 255),\n        (255, 0, 255),\n        (255, 255, 255),\n        (0, 127, 255),\n        (71, 130, 255),\n        (127, 127, 0),\n    ]\n\n    def __init__(\n        self,\n        ann_file,\n        pipeline=None,\n        data_root=None,\n        classes=None,\n        map_classes=None,\n        name_mapping=None,\n        load_interval=1,\n        modality=None,\n        sample_interval=5,\n        past_frames=2,\n        future_frames=6,\n        test_mode=False,\n        vis_score_threshold=0.25,\n        data_aug_conf=None,\n        sequences_split_num=1,\n        with_seq_flag=False,\n        keep_consistent_seq_aug=True,\n        work_dir=None,\n        eval_config=None,\n        use_cmd=True,\n        use_generated_img=False,\n        generated_img_root=None,\n    ):\n        self.load_interval = load_interval\n        super().__init__()\n        self.data_root = data_root\n        self.ann_file = ann_file\n        self.test_mode = test_mode\n        self.modality = modality\n        self.box_mode_3d = 0\n        self.sample_interval = sample_interval\n        self.past_frames = past_frames\n        self.future_frames = future_frames\n\n        if classes is not None:\n            self.CLASSES = classes\n        if map_classes is not None: \n            self.MAP_CLASSES = map_classes\n        self.NameMapping = name_mapping\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if pipeline is not None:\n            self.pipeline = Compose(pipeline)\n\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n        self.vis_score_threshold = vis_score_threshold\n\n        self.data_aug_conf = data_aug_conf\n        self.sequences_split_num = sequences_split_num\n        self.keep_consistent_seq_aug = keep_consistent_seq_aug\n        if with_seq_flag:\n            self._set_sequence_group_flag()\n        \n        self.work_dir = work_dir\n        self.eval_config = eval_config\n        self.use_cmd = use_cmd\n\n        self.use_generated_img = use_generated_img\n        self.generated_img_root = generated_img_root\n\n        self.eval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n        }\n\n    def __len__(self):\n        return len(self.data_infos)\n\n    def _set_sequence_group_flag(self):\n        \"\"\"\n        Set each sequence to be a different group\n        \"\"\"\n        if self.sequences_split_num == -1:\n            self.flag = np.arange(len(self.data_infos))\n            return\n        \n        res = []\n\n        curr_folder = self.data_infos[0][\"folder\"]\n        curr_sequence = 0\n        for idx in range(len(self.data_infos)):\n            if idx != 0 and self.data_infos[idx][\"folder\"] != curr_folder:\n                # Not first frame and # of sweeps is 0 -> new sequence\n                curr_sequence += 1\n                curr_folder = self.data_infos[idx][\"folder\"]\n            res.append(curr_sequence)\n\n        self.flag = np.array(res, dtype=np.int64)\n\n        if self.sequences_split_num != 1:\n            if self.sequences_split_num == \"all\":\n                self.flag = np.array(\n                    range(len(self.data_infos)), dtype=np.int64\n                )\n            else:\n                bin_counts = np.bincount(self.flag)\n                new_flags = []\n                curr_new_flag = 0\n                for curr_flag in range(len(bin_counts)):\n                    curr_sequence_length = np.array(\n                        list(\n                            range(\n                                0,\n                                bin_counts[curr_flag],\n                                math.ceil(\n                                    bin_counts[curr_flag]\n                                    / self.sequences_split_num\n                                ),\n                            )\n                        )\n                        + [bin_counts[curr_flag]]\n                    )\n\n                    for sub_seq_idx in (\n                        curr_sequence_length[1:] - curr_sequence_length[:-1]\n                    ):\n                        for _ in range(sub_seq_idx):\n                            new_flags.append(curr_new_flag)\n                        curr_new_flag += 1\n\n                assert len(new_flags) == len(self.flag)\n                assert (\n                    len(np.bincount(new_flags))\n                    == len(np.bincount(self.flag)) * self.sequences_split_num\n                )\n                self.flag = np.array(new_flags, dtype=np.int64)\n\n    def get_augmentation(self):\n        if self.data_aug_conf is None:\n            return None\n        H, W = self.data_aug_conf[\"H\"], self.data_aug_conf[\"W\"]\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        if not self.test_mode:\n            resize = np.random.uniform(*self.data_aug_conf[\"resize_lim\"])\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int(\n                    (1 - np.random.uniform(*self.data_aug_conf[\"bot_pct_lim\"]))\n                    * newH\n                )\n                - fH\n            )\n            crop_w = int(np.random.uniform(0, max(0, newW - fW)))\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            if self.data_aug_conf[\"rand_flip\"] and np.random.choice([0, 1]):\n                flip = True\n            rotate = np.random.uniform(*self.data_aug_conf[\"rot_lim\"])\n            rotate_3d = np.random.uniform(*self.data_aug_conf[\"rot3d_range\"])\n        else:\n            resize = max(fH / H, fW / W)\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n                - fH\n            )\n            crop_w = int(max(0, newW - fW) / 2)\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            rotate = 0\n            rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def __getitem__(self, idx):\n        if isinstance(idx, dict):\n            aug_config = idx[\"aug_config\"]\n            idx = idx[\"idx\"]\n        else:\n            aug_config = self.get_augmentation()\n        data = self.get_data_info(idx)\n        data[\"aug_config\"] = aug_config\n        data = self.pipeline(data)\n        return data\n\n    def load_annotations(self, ann_file):\n        data = mmcv.load(ann_file, file_format=\"pkl\")\n        data_infos = data[:: self.load_interval]\n        return data_infos\n    \n    def anno2geom(self, annos):\n        map_geoms = {}\n        for label, anno_list in annos.items():\n            map_geoms[label] = []\n            for anno in anno_list:\n                geom = LineString(anno)\n                map_geoms[label].append(geom)\n        return map_geoms\n    \n    def get_data_info(self, index):\n        info = self.data_infos[index]\n        input_dict = dict(\n            token=info['token'],\n            timestamp=info['timestamp'] / 1e6,\n        )\n        ## only use 3 classes\n        map_annos = {\n            0: info[\"map_annos\"][0],\n            1: info[\"map_annos\"][1],\n            2: info[\"map_annos\"][2],\n        }\n        map_geoms = self.anno2geom(map_annos)\n        input_dict[\"map_infos\"] = map_annos\n        input_dict[\"map_geoms\"] = map_geoms\n\n        if self.modality['use_camera']:\n            image_paths = []\n            depth_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsic = []\n            lidar2ego = info['sensors']['LIDAR_TOP']['lidar2ego']\n            lidar2global =  self.invert_pose(info['sensors']['LIDAR_TOP']['world2lidar'])\n            for sensor_type, cam_info in info['sensors'].items():\n                if not 'CAM' in sensor_type:\n                    continue\n                img_path = osp.join(self.data_root,cam_info['data_path'])\n                image_paths.append(img_path)\n                depth_path = img_path.replace('rgb_','depth_').replace('.jpg','.png')\n                depth_paths.append(depth_path)\n                # obtain lidar to image transformation matrix\n                cam2ego = cam_info['cam2ego']\n                intrinsic = copy.deepcopy(cam_info[\"intrinsic\"])\n                cam_intrinsic.append(intrinsic)\n                viewpad = np.eye(4)\n                viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n                lidar2cam = (self.invert_pose(cam2ego) @ lidar2ego).T\n                lidar2img = viewpad @ lidar2cam.T\n                lidar2img_rts.append(lidar2img)\n                lidar2cam_rts.append(lidar2cam)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    depth_filename=depth_paths,\n                    lidar2img=lidar2img_rts,\n                    lidar2cam=lidar2cam_rts,\n                    cam_intrinsic=cam_intrinsic,\n                    lidar2global=lidar2global,\n                )\n            )\n\n        annos = self.get_ann_info(index)\n        input_dict.update(annos)\n\n        return input_dict\n\n    def get_ann_info(self, index):\n        info = self.data_infos[index]\n        mask = (info['num_points'] != 0)\n        gt_bboxes_3d = info[\"gt_boxes\"][mask]\n        gt_names_3d = info[\"gt_names\"][mask]\n        for i in range(len(gt_names_3d)):\n            if gt_names_3d[i] in self.NameMapping.keys():\n                gt_names_3d[i] = self.NameMapping[gt_names_3d[i]]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)        \n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n        )\n\n        if \"gt_ids\" in info:\n            instance_inds = np.array(info[\"gt_ids\"], dtype=np.int)[mask]\n            anns_results[\"instance_inds\"] = instance_inds\n\n        gt_agent_fut_trajs, gt_agent_fut_masks = self.get_fut_agent(index, self.sample_interval, self.future_frames)\n        anns_results['gt_agent_fut_trajs'] = gt_agent_fut_trajs[mask]\n        anns_results['gt_agent_fut_masks'] = gt_agent_fut_masks[mask]\n\n        (\n            ego_his_trajs, \n            ego_fut_trajs, \n            ego_fut_masks, \n            command\n        ) = self.get_ego_trajs(index,self.sample_interval,self.past_frames,self.future_frames)\n        anns_results['gt_ego_fut_trajs'] = ego_fut_trajs\n        anns_results['gt_ego_fut_masks'] = ego_fut_masks\n        anns_results['gt_ego_fut_cmd'] = command\n        anns_results['ego_his_trajs'] = ego_his_trajs\n\n        global2lidar = info['sensors']['LIDAR_TOP']['world2lidar']\n        tp_near_global = info[\"command_near_xy\"]\n        tp_near_global = np.concatenate([info[\"command_near_xy\"], np.array([0, 1])])\n        tp_near_local = global2lidar @ tp_near_global\n        anns_results[\"tp_near\"] = tp_near_local[:2]\n\n        tp_far_global = info[\"command_far_xy\"]\n        tp_far_global = np.concatenate([info[\"command_far_xy\"], np.array([0, 1])])\n        tp_far_local = global2lidar @ tp_far_global\n        anns_results[\"tp_far\"] = tp_far_local[:2]\n\n        ego_status = np.zeros(10)\n        ego_status[:3] = info[\"ego_accel\"]\n        ego_status[3:6] = info[\"ego_rotation_rate\"]\n        ego_status[6:9] = info[\"ego_vel\"]\n        anns_results[\"ego_status\"] = ego_status.astype(np.float32)\n        # def dis(a,b):\n        #     a1 = a[:2]\n        #     a2 = b[:2]\n        #     d = a1-a2\n        #     dis = np.sqrt(d[0]*d[0]+d[1]*d[1])\n        #     return dis\n\n        # if index != 0:\n        #     print(\"near: \", dis(tp_near_global, self.tp_near_global), \"far: \", dis(tp_far_global, self.tp_far_global))\n\n        # self.tp_near_global = tp_near_global\n        # self.tp_far_global = tp_far_global\n        return anns_results\n\n        ## get future box for planning eval\n        fut_ts = int(ego_fut_masks.sum())\n        fut_boxes = []\n        cur_scene_token = info[\"folder\"]\n        cur_T_global = get_T_global(info)\n        for i in range(1, fut_ts + 1):\n            fut_info = self.data_infos[index + i]\n            fut_scene_token = fut_info[\"scene_token\"]\n            if cur_scene_token != fut_scene_token:\n                break\n            if self.use_valid_flag:\n                mask = fut_info[\"valid_flag\"]\n            else:\n                mask = fut_info[\"num_lidar_pts\"] > 0\n\n            fut_gt_bboxes_3d = fut_info[\"gt_boxes\"][mask]\n            \n            fut_T_global = get_T_global(fut_info)\n            T_fut2cur = np.linalg.inv(cur_T_global) @ fut_T_global\n\n            center = fut_gt_bboxes_3d[:, :3] @ T_fut2cur[:3, :3].T + T_fut2cur[:3, 3]\n            yaw = np.stack([np.cos(fut_gt_bboxes_3d[:, 6]), np.sin(fut_gt_bboxes_3d[:, 6])], axis=-1)\n            yaw = yaw @ T_fut2cur[:2, :2].T\n            yaw = np.arctan2(yaw[..., 1], yaw[..., 0])\n\n            fut_gt_bboxes_3d[:, :3] = center\n            fut_gt_bboxes_3d[:, 6] = yaw\n            fut_boxes.append(fut_gt_bboxes_3d)\n\n        anns_results['fut_boxes'] = fut_boxes\n        \n        return anns_results\n\n    def get_fut_agent(self, idx, sample_rate, frames):\n        adj_idx_list = range(idx,idx+(frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        cur_boxes = cur_frame['gt_boxes'].copy()\n        box_ids = cur_frame['gt_ids']\n\n        future_track = np.zeros((len(box_ids),frames+1,2))\n        future_mask = np.zeros((len(box_ids),frames+1))\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for i in range(len(box_ids)):\n            box_id = box_ids[i]\n            cur_box2lidar = world2lidar_lidar_cur @ cur_frame['npc2world'][i]\n            cur_xy = cur_box2lidar[0:2,3]\n            for j in range(len(adj_idx_list)):\n                adj_idx = adj_idx_list[j]\n                if adj_idx < 0 or adj_idx >= len(self.data_infos):\n                    break\n                adj_frame = self.data_infos[adj_idx]\n                if adj_frame['folder'] != cur_frame ['folder']:\n                    break\n                if len(np.where(adj_frame['gt_ids']==box_id)[0])==0:\n                    break\n                assert len(np.where(adj_frame['gt_ids']==box_id)[0]) == 1 , np.where(adj_frame['gt_ids']==box_id)[0]\n                adj_idx = np.where(adj_frame['gt_ids']==box_id)[0][0]\n                adj_box2lidar = world2lidar_lidar_cur @ adj_frame['npc2world'][adj_idx]\n                adj_xy = adj_box2lidar[0:2,3]\n                if j > 0:\n                    last_xy = future_track[i,j-1,:]\n                    distance = np.linalg.norm(last_xy - adj_xy)\n                    if distance > 10:\n                        break\n                future_track[i,j,:] = adj_xy\n                future_mask[i,j] = 1\n\n        future_track_offset = future_track[:,1:,:] - future_track[:,:-1,:]\n        future_mask_offset = future_mask[:,1:]\n        future_track_offset[future_mask_offset==0] = 0\n\n        return future_track_offset.astype(np.float32), future_mask_offset.astype(np.float32)\n\n    def get_ego_trajs(self,idx,sample_rate,past_frames,future_frames):\n        adj_idx_list = range(idx-past_frames*sample_rate,idx+(future_frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        full_adj_track = np.zeros((past_frames+future_frames+1,2))\n        full_adj_adj_mask = np.zeros(past_frames+future_frames+1)\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for j in range(len(adj_idx_list)):\n            adj_idx = adj_idx_list[j]\n            if adj_idx <0 or adj_idx>=len(self.data_infos):\n                break\n            adj_frame = self.data_infos[adj_idx]\n            if adj_frame['folder'] != cur_frame ['folder']:\n                break\n            world2lidar_ego_adj = adj_frame['sensors']['LIDAR_TOP']['world2lidar']\n            adj2cur_lidar = world2lidar_lidar_cur @ np.linalg.inv(world2lidar_ego_adj)\n            xy = adj2cur_lidar[0:2,3]\n            full_adj_track[j,0:2] = xy\n            full_adj_adj_mask[j] = 1\n        offset_track = full_adj_track[1:] - full_adj_track[:-1]\n        for j in range(past_frames-1,-1,-1):\n            if full_adj_adj_mask[j] == 0:\n                offset_track[j] = offset_track[j+1]\n        for j in range(past_frames,past_frames+future_frames,1):\n\n            if full_adj_adj_mask[j+1] == 0 :\n                offset_track[j] = 0\n        if self.use_cmd:\n            command = self.command2hot(cur_frame['command_near'])\n        else:\n            command = np.array([0, ])\n        offset_track = offset_track.astype(np.float32)\n        return offset_track[:past_frames].copy(), offset_track[past_frames:].copy(), full_adj_adj_mask[-future_frames:].copy(), command\n    \n    def command2hot(self,command,max_dim=6):\n        if command < 0:\n            command = 4\n        command -= 1\n        cmd_one_hot = np.zeros(max_dim)\n        cmd_one_hot[command] = 1\n        return cmd_one_hot\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\n    def _format_bbox(self, results, jsonfile_prefix=None, tracking=False):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            box3d = det['boxes_3d']\n            scores = det['scores_3d']\n            labels = det['labels_3d']\n            box_gravity_center = box3d[:, :3]\n            box_dims = box3d[:, 3:6]\n            box_yaw = box3d[:, 6]\n            sample_token = self.data_infos[sample_id]['token']\n\n            for i in range(len(box3d)):\n                quat = list(Quaternion(axis=[0, 0, 1], radians=box_yaw[i]))\n                velocity = [box3d[i, 7].item(),box3d[i, 8].item()]\n                name = mapped_class_names[labels[i]]\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box_gravity_center[i].tolist(),\n                    size=box_dims[i].tolist(),\n                    rotation=quat,\n                    velocity=velocity,\n                    detection_name=name,\n                    detection_score=scores[i].item(),\n                    attribute_name=name)\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, \"results_nusc.json\")\n        print(\"Results writes to\", res_path)\n        mmcv.dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(\n        self, result_path, logger=None, result_name=\"img_bbox\", tracking=False\n    ):\n\n        with open(result_path) as f:\n            result_data = json.load(f)\n        pred_boxes = EvalBoxes.deserialize(result_data['results'], DetectionBox)\n        meta = result_data['meta']\n\n        gt_boxes = self.load_gt()\n\n        metric_data_list = DetectionMetricDataList()\n        for class_name in self.eval_cfg['class_names']:\n            for dist_th in self.eval_cfg['dist_ths']:\n                md = accumulate(gt_boxes, pred_boxes, class_name, center_distance, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics = DetectionMetrics(self.eval_cfg)\n\n        for class_name in self.eval_cfg['class_names']:\n            # Compute APs.\n            for dist_th in self.eval_cfg['dist_ths']:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.eval_cfg['min_recall'], self.eval_cfg['min_precision'])\n                metrics.add_label_ap(class_name, dist_th, ap)\n\n            # Compute TP metrics.\n            for metric_name in self.eval_cfg['tp_metrics']:\n                metric_data = metric_data_list[(class_name, self.eval_cfg['dist_th_tp'])]\n                tp = calc_tp(metric_data, self.eval_cfg['min_recall'], metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        metrics_summary = metrics.serialize()\n        metrics_summary['meta'] = meta.copy()\n        print('mAP: %.4f' % (metrics_summary['mean_ap']))\n        err_name_mapping = {\n            'trans_err': 'mATE',\n            'scale_err': 'mASE',\n            'orient_err': 'mAOE',\n            'vel_err': 'mAVE',\n        }\n        for tp_name, tp_val in metrics_summary['tp_errors'].items():\n            print('%s: %.4f' % (err_name_mapping[tp_name], tp_val))\n        print('NDS: %.4f' % (metrics_summary['nd_score']))\n        #print('Eval time: %.1fs' % metrics_summary['eval_time'])\n\n        # Print per-class metrics.\n        print()\n        print('Per-class results:')\n        print('Object Class\\tAP\\tATE\\tASE\\tAOE\\tAVE')\n        class_aps = metrics_summary['mean_dist_aps']\n        class_tps = metrics_summary['label_tp_errors']\n        for class_name in class_aps.keys():\n            print('%s\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f'\n                  % (class_name, class_aps[class_name],\n                     class_tps[class_name]['trans_err'],\n                     class_tps[class_name]['scale_err'],\n                     class_tps[class_name]['orient_err'],\n                     class_tps[class_name]['vel_err']))        \n\n        detail = dict()\n        metric_prefix = 'bbox_NuScenes'\n        for name in self.eval_cfg['class_names']:\n            for k, v in metrics_summary['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,self.eval_cfg['err_name_maping'][k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics_summary['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics_summary['mean_ap']\n\n\n        return detail\n\n    def load_gt(self):\n        all_annotations = EvalBoxes()\n        for i in range(len(self.data_infos)):\n            sample_boxes = []\n            sample_data = self.data_infos[i]\n\n            gt_boxes = sample_data['gt_boxes']\n            \n            for j in range(gt_boxes.shape[0]):\n                class_name = self.NameMapping[sample_data['gt_names'][j]]\n                if not class_name in self.eval_cfg['class_range'].keys():\n                    continue\n                range_x, range_y = self.eval_cfg['class_range'][class_name]\n                if abs(gt_boxes[j,0]) > range_x or abs(gt_boxes[j,1]) > range_y:\n                    continue\n                sample_boxes.append(DetectionBox(\n                    sample_token=sample_data['token'],\n                    translation=gt_boxes[j,0:3],\n                    size=gt_boxes[j,3:6],\n                    rotation=list(Quaternion(axis=[0, 0, 1], radians=gt_boxes[j,6])),\n                    velocity=gt_boxes[j,7:9],\n                    num_pts=int(sample_data['num_points'][j]),\n                    detection_name=self.NameMapping[sample_data['gt_names'][j]],\n                    detection_score=-1.0,  \n                    attribute_name=self.NameMapping[sample_data['gt_names'][j]]\n                ))\n            all_annotations.add_boxes(sample_data['token'], sample_boxes)\n        return all_annotations\n\n    def format_results(self, results, jsonfile_prefix=None, tracking=False):\n        assert isinstance(results, list), \"results must be a list\"\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, \"results\")\n        else:\n            tmp_dir = None\n\n        if not (\"pts_bbox\" in results[0] or \"img_bbox\" in results[0]):\n            result_files = self._format_bbox(\n                results, jsonfile_prefix, tracking=tracking\n            )\n        else:\n            result_files = dict()\n            for name in results[0]:\n                print(f\"\\nFormating bboxes of {name}\")\n                results_ = [out[name] for out in results]\n                tmp_file_ = jsonfile_prefix\n                result_files.update(\n                    {\n                        name: self._format_bbox(\n                            results_, tmp_file_, tracking=tracking\n                        )\n                    }\n                )\n        return result_files, tmp_dir\n\n    def format_map_results(self, results, prefix=None):\n        submissions = {'results': {},}\n        \n        for j, pred in enumerate(results):\n            '''\n            For each case, the result should be formatted as Dict{'vectors': [], 'scores': [], 'labels': []}\n            'vectors': List of vector, each vector is a array([[x1, y1], [x2, y2] ...]),\n                contain all vectors predicted in this sample.\n            'scores: List of score(float), \n                contain scores of all instances in this sample.\n            'labels': List of label(int), \n                contain labels of all instances in this sample.\n            '''\n            if pred is None: # empty prediction\n                continue\n            pred = pred['img_bbox']\n\n            single_case = {'vectors': [], 'scores': [], 'labels': []}\n            token = self.data_infos[j]['token']\n            for i in range(len(pred['scores'])):\n                score = pred['scores'][i]\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n\n                # A line should have >=2 points\n                if len(vector) < 2:\n                    continue\n                \n                single_case['vectors'].append(vector)\n                single_case['scores'].append(score)\n                single_case['labels'].append(label)\n            \n            submissions['results'][token] = single_case\n        \n        out_path = osp.join(prefix, 'submission_vector.json')\n        print(f'saving submissions results to {out_path}')\n        os.makedirs(os.path.dirname(out_path), exist_ok=True)\n        mmcv.dump(submissions, out_path)\n        return out_path\n\n    def format_motion_results(self, results, jsonfile_prefix=None, tracking=False, thresh=None):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det['img_bbox'], threshold=None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n                filter_with_cls_range=False,\n            )\n            for i, box in enumerate(boxes):\n                if thresh is not None and box.score < thresh:\n                    continue\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = B2D3DDataset.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = B2D3DDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n                nusc_anno.update(\n                    dict(\n                        trajs=det['img_bbox']['trajs_3d'][i].numpy(),\n                    )\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        return nusc_submissions \n\n    def _evaluate_single_motion(self,\n                         results,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        from .evaluation.motion.motion_eval_uniad import NuScenesEval as NuScenesEvalMotion\n\n        output_dir = result_path\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        nusc_eval = NuScenesEvalMotion(\n            nusc,\n            config=copy.deepcopy(self.det3d_eval_configs),\n            result_path=results,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False,\n            seconds=6)\n        metrics = nusc_eval.main(render_curves=False)\n        \n        MOTION_METRICS = ['EPA', 'min_ade_err', 'min_fde_err', 'miss_rate_err']\n        class_names = ['car', 'pedestrian']\n\n        table = prettytable.PrettyTable()\n        table.field_names = [\"class names\"] + MOTION_METRICS\n        for class_name in class_names:\n            row_data = [class_name]\n            for m in MOTION_METRICS:\n                row_data.append('%.4f' % metrics[f'{class_name}_{m}'])\n            table.add_row(row_data)\n        print_log('\\n'+str(table), logger=logger)\n        return metrics\n\n    def evaluate(\n        self,\n        results,\n        eval_mode,\n        metric=None,\n        logger=None,\n        jsonfile_prefix=None,\n        result_names=[\"img_bbox\"],\n        show=False,\n        out_dir=None,\n        pipeline=None,\n    ):\n        res_path = \"results.pkl\"\n        res_path = osp.join(self.work_dir, res_path)\n        print('All Results write to', res_path)\n        mmcv.dump(results, res_path)\n\n        results_dict = dict()\n        if eval_mode['with_det']:\n            self.tracking = eval_mode[\"with_tracking\"]\n            self.tracking_threshold = eval_mode[\"tracking_threshold\"]\n            for metric in [\"detection\", \"tracking\"]:\n                tracking = metric == \"tracking\"\n                if tracking and not self.tracking:\n                    continue\n                result_files, tmp_dir = self.format_results(\n                    results, jsonfile_prefix=self.work_dir, tracking=tracking\n                )\n\n                if isinstance(result_files, dict):\n                    for name in result_names:\n                        ret_dict = self._evaluate_single(\n                            result_files[name], tracking=tracking\n                        )\n                    results_dict.update(ret_dict)\n                elif isinstance(result_files, str):\n                    ret_dict = self._evaluate_single(\n                        result_files, tracking=tracking\n                    )\n                    results_dict.update(ret_dict)\n\n                if tmp_dir is not None:\n                    tmp_dir.cleanup()\n\n        if eval_mode['with_map']:\n            from .evaluation.map.vector_eval import VectorEvaluate\n            self.map_evaluator = VectorEvaluate(self.eval_config)\n            result_path = self.format_map_results(results, prefix=self.work_dir)\n            map_results_dict = self.map_evaluator.evaluate(result_path, logger=logger)\n            results_dict.update(map_results_dict)\n\n        if eval_mode['with_motion']:\n            thresh = eval_mode[\"motion_threshhold\"]\n            result_files = self.format_motion_results(results, jsonfile_prefix=self.work_dir, thresh=thresh)\n            motion_results_dict = self._evaluate_single_motion(result_files, self.work_dir, logger=logger)\n            results_dict.update(motion_results_dict)\n        \n        if eval_mode['with_planning']:\n            from .evaluation.planning.planning_eval import planning_eval\n            planning_results_dict = planning_eval(results, self.eval_config, logger=logger)\n            results_dict.update(planning_results_dict)\n\n        if show or out_dir:\n            self.show(results, save_dir=out_dir, show=show, pipeline=pipeline)\n        \n        # print main metrics for recording\n        metric_str = '\\n'\n        if \"img_bbox_NuScenes/NDS\" in results_dict:\n            metric_str += f'mAP: {results_dict.get(\"img_bbox_NuScenes/mAP\"):.4f}\\n'\n            metric_str += f'mATE: {results_dict.get(\"img_bbox_NuScenes/mATE\"):.4f}\\n'\n            metric_str += f'mASE: {results_dict.get(\"img_bbox_NuScenes/mASE\"):.4f}\\n'\n            metric_str += f'mAOE: {results_dict.get(\"img_bbox_NuScenes/mAOE\"):.4f}\\n' \n            metric_str += f'mAVE: {results_dict.get(\"img_bbox_NuScenes/mAVE\"):.4f}\\n' \n            metric_str += f'mAAE: {results_dict.get(\"img_bbox_NuScenes/mAAE\"):.4f}\\n' \n            metric_str += f'NDS: {results_dict.get(\"img_bbox_NuScenes/NDS\"):.4f}\\n\\n'\n        \n        if \"img_bbox_NuScenes/amota\" in results_dict:\n            metric_str += f'AMOTA: {results_dict[\"img_bbox_NuScenes/amota\"]:.4f}\\n' \n            metric_str += f'AMOTP: {results_dict[\"img_bbox_NuScenes/amotp\"]:.4f}\\n' \n            metric_str += f'RECALL: {results_dict[\"img_bbox_NuScenes/recall\"]:.4f}\\n' \n            metric_str += f'MOTAR: {results_dict[\"img_bbox_NuScenes/motar\"]:.4f}\\n' \n            metric_str += f'MOTA: {results_dict[\"img_bbox_NuScenes/mota\"]:.4f}\\n' \n            metric_str += f'MOTP: {results_dict[\"img_bbox_NuScenes/motp\"]:.4f}\\n' \n            metric_str += f'IDS: {results_dict[\"img_bbox_NuScenes/ids\"]}\\n\\n' \n\n        if \"mAP_normal\" in results_dict:\n            # metric_str += f'ped_crossing= {results_dict[\"ped_crossing\"]:.4f}\\n' \n            # metric_str += f'divider= {results_dict[\"divider\"]:.4f}\\n' \n            # metric_str += f'boundary= {results_dict[\"boundary\"]:.4f}\\n' \n            metric_str += f'mAP_normal= {results_dict[\"mAP_normal\"]:.4f}\\n\\n' \n\n        if \"car_EPA\" in results_dict:\n            metric_str += f'Car / Ped\\n' \n            metric_str += f'epa= {results_dict[\"car_EPA\"]:.4f} / {results_dict[\"pedestrian_EPA\"]:.4f}\\n'\n            metric_str += f'ade= {results_dict[\"car_min_ade_err\"]:.4f} / {results_dict[\"pedestrian_min_ade_err\"]:.4f}\\n'\n            metric_str += f'fde= {results_dict[\"car_min_fde_err\"]:.4f} / {results_dict[\"pedestrian_min_fde_err\"]:.4f}\\n'\n            metric_str += f'mr= {results_dict[\"car_miss_rate_err\"]:.4f} / {results_dict[\"pedestrian_miss_rate_err\"]:.4f}\\n\\n' \n\n        if \"L2\" in results_dict:\n            metric_str += f'obj_box_col: {(results_dict[\"obj_box_col\"]*100):.3f}%\\n'\n            metric_str += f'L2: {results_dict[\"L2\"]:.4f}\\n\\n'\n        \n        print_log(metric_str, logger=logger)\n        return results_dict\n\n    def show(self, results, save_dir=None, show=False, pipeline=None):\n        save_dir = \"./\" if save_dir is None else save_dir\n        save_dir = os.path.join(save_dir, \"visual\")\n        print_log(os.path.abspath(save_dir))\n        pipeline = Compose(pipeline)\n        if not os.path.exists(save_dir):\n            os.makedirs(save_dir)\n\n        fourcc = cv2.VideoWriter_fourcc(*\"MJPG\")\n        videoWriter = None\n\n        for i, result in enumerate(results):\n            if \"img_bbox\" in result.keys():\n                result = result[\"img_bbox\"]\n            data_info = pipeline(self.get_data_info(i))\n            imgs = []\n\n            raw_imgs = data_info[\"img\"]\n            lidar2img = data_info[\"img_metas\"].data[\"lidar2img\"]\n            pred_bboxes_3d = result[\"boxes_3d\"][\n                result[\"scores_3d\"] > self.vis_score_threshold\n            ]\n            if \"instance_ids\" in result and self.tracking:\n                color = []\n                for id in result[\"instance_ids\"].cpu().numpy().tolist():\n                    color.append(\n                        self.ID_COLOR_MAP[int(id % len(self.ID_COLOR_MAP))]\n                    )\n            elif \"labels_3d\" in result:\n                color = []\n                for id in result[\"labels_3d\"].cpu().numpy().tolist():\n                    color.append(self.ID_COLOR_MAP[id])\n            else:\n                color = (255, 0, 0)\n\n            # ===== draw boxes_3d to images =====\n            for j, img_origin in enumerate(raw_imgs):\n                img = img_origin.copy()\n                if len(pred_bboxes_3d) != 0:\n                    img = draw_lidar_bbox3d_on_img(\n                        pred_bboxes_3d,\n                        img,\n                        lidar2img[j],\n                        img_metas=None,\n                        color=color,\n                        thickness=3,\n                    )\n                imgs.append(img)\n\n            # ===== draw boxes_3d to BEV =====\n            bev = draw_lidar_bbox3d_on_bev(\n                pred_bboxes_3d,\n                bev_size=img.shape[0] * 2,\n                color=color,\n            )\n\n            # ===== put text and concat =====\n            for j, name in enumerate(\n                [\n                    \"front\",\n                    \"front right\",\n                    \"front left\",\n                    \"rear\",\n                    \"rear left\",\n                    \"rear right\",\n                ]\n            ):\n                imgs[j] = cv2.rectangle(\n                    imgs[j],\n                    (0, 0),\n                    (440, 80),\n                    color=(255, 255, 255),\n                    thickness=-1,\n                )\n                w, h = cv2.getTextSize(name, cv2.FONT_HERSHEY_SIMPLEX, 2, 2)[0]\n                text_x = int(220 - w / 2)\n                text_y = int(40 + h / 2)\n\n                imgs[j] = cv2.putText(\n                    imgs[j],\n                    name,\n                    (text_x, text_y),\n                    cv2.FONT_HERSHEY_SIMPLEX,\n                    2,\n                    (0, 0, 0),\n                    2,\n                    cv2.LINE_AA,\n                )\n            image = np.concatenate(\n                [\n                    np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n                    np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n                ],\n                axis=0,\n            )\n            image = np.concatenate([image, bev], axis=1)\n\n            # ===== save video =====\n            if videoWriter is None:\n                videoWriter = cv2.VideoWriter(\n                    os.path.join(save_dir, \"video.avi\"),\n                    fourcc,\n                    7,\n                    image.shape[:2][::-1],\n                )\n            cv2.imwrite(os.path.join(save_dir, f\"{i}.jpg\"), image)\n            videoWriter.write(image)\n        videoWriter.release()\n\n\ndef get_T_global(info):\n    lidar2ego = np.eye(4)\n    lidar2ego[:3, :3] = pyquaternion.Quaternion(\n        info[\"lidar2ego_rotation\"]\n    ).rotation_matrix\n    lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n    ego2global = np.eye(4)\n    ego2global[:3, :3] = pyquaternion.Quaternion(\n        info[\"ego2global_rotation\"]\n    ).rotation_matrix\n    ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n    return ego2global @ lidar2ego"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/builder.py",
    "content": "import copy\nimport platform\nimport random\nfrom functools import partial\n\nimport numpy as np\nfrom mmcv.parallel import collate\nfrom mmcv.runner import get_dist_info\nfrom mmcv.utils import Registry, build_from_cfg\nfrom torch.utils.data import DataLoader\n\nfrom mmdet.datasets.samplers import GroupSampler\nfrom mmdet3d_plugin.datasets.samplers import (\n    GroupInBatchSampler,\n    DistributedGroupSampler,\n    DistributedSampler,\n    build_sampler\n)\n\n\ndef build_dataloader(\n    dataset,\n    samples_per_gpu,\n    workers_per_gpu,\n    num_gpus=1,\n    dist=True,\n    shuffle=True,\n    seed=None,\n    shuffler_sampler=None,\n    nonshuffler_sampler=None,\n    runner_type=\"EpochBasedRunner\",\n    **kwargs\n):\n    \"\"\"Build PyTorch DataLoader.\n    In distributed training, each GPU/process has a dataloader.\n    In non-distributed training, there is only one dataloader for all GPUs.\n    Args:\n        dataset (Dataset): A PyTorch dataset.\n        samples_per_gpu (int): Number of training samples on each GPU, i.e.,\n            batch size of each GPU.\n        workers_per_gpu (int): How many subprocesses to use for data loading\n            for each GPU.\n        num_gpus (int): Number of GPUs. Only used in non-distributed training.\n        dist (bool): Distributed training/test or not. Default: True.\n        shuffle (bool): Whether to shuffle the data at every epoch.\n            Default: True.\n        kwargs: any keyword argument to be used to initialize DataLoader\n    Returns:\n        DataLoader: A PyTorch dataloader.\n    \"\"\"\n    rank, world_size = get_dist_info()\n    batch_sampler = None\n    if runner_type == 'IterBasedRunner':\n        print(\"Use GroupInBatchSampler !!!\")\n        batch_sampler = GroupInBatchSampler(\n            dataset,\n            samples_per_gpu,\n            world_size,\n            rank,\n            seed=seed,\n        )\n        batch_size = 1\n        sampler = None\n        num_workers = workers_per_gpu\n    elif dist:\n        # DistributedGroupSampler will definitely shuffle the data to satisfy\n        # that images on each GPU are in the same group\n        if shuffle:\n            print(\"Use DistributedGroupSampler !!!\")\n            sampler = build_sampler(\n                shuffler_sampler\n                if shuffler_sampler is not None\n                else dict(type=\"DistributedGroupSampler\"),\n                dict(\n                    dataset=dataset,\n                    samples_per_gpu=samples_per_gpu,\n                    num_replicas=world_size,\n                    rank=rank,\n                    seed=seed,\n                ),\n            )\n        else:\n            sampler = build_sampler(\n                nonshuffler_sampler\n                if nonshuffler_sampler is not None\n                else dict(type=\"DistributedSampler\"),\n                dict(\n                    dataset=dataset,\n                    num_replicas=world_size,\n                    rank=rank,\n                    shuffle=shuffle,\n                    seed=seed,\n                ),\n            )\n\n        batch_size = samples_per_gpu\n        num_workers = workers_per_gpu\n    else:\n        # assert False, 'not support in bevformer'\n        print(\"WARNING!!!!, Only can be used for obtain inference speed!!!!\")\n        sampler = GroupSampler(dataset, samples_per_gpu) if shuffle else None\n        batch_size = num_gpus * samples_per_gpu\n        num_workers = num_gpus * workers_per_gpu\n\n    init_fn = (\n        partial(worker_init_fn, num_workers=num_workers, rank=rank, seed=seed)\n        if seed is not None\n        else None\n    )\n\n    data_loader = DataLoader(\n        dataset,\n        batch_size=batch_size,\n        sampler=sampler,\n        batch_sampler=batch_sampler,\n        num_workers=num_workers,\n        collate_fn=partial(collate, samples_per_gpu=samples_per_gpu),\n        pin_memory=False,\n        worker_init_fn=init_fn,\n        **kwargs\n    )\n\n    return data_loader\n\n\ndef worker_init_fn(worker_id, num_workers, rank, seed):\n    # The seed of each worker equals to\n    # num_worker * rank + worker_id + user_seed\n    worker_seed = num_workers * rank + worker_id + seed\n    np.random.seed(worker_seed)\n    random.seed(worker_seed)\n\n\n# Copyright (c) OpenMMLab. All rights reserved.\nimport platform\nfrom mmcv.utils import Registry, build_from_cfg\n\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.builder import _concat_dataset\n\nif platform.system() != \"Windows\":\n    # https://github.com/pytorch/pytorch/issues/973\n    import resource\n\n    rlimit = resource.getrlimit(resource.RLIMIT_NOFILE)\n    base_soft_limit = rlimit[0]\n    hard_limit = rlimit[1]\n    soft_limit = min(max(4096, base_soft_limit), hard_limit)\n    resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit))\n\nOBJECTSAMPLERS = Registry(\"Object sampler\")\n\n\ndef custom_build_dataset(cfg, default_args=None):\n    try:\n        from mmdet3d.datasets.dataset_wrappers import CBGSDataset\n    except:\n        CBGSDataset = None\n    from mmdet.datasets.dataset_wrappers import (\n        ClassBalancedDataset,\n        ConcatDataset,\n        RepeatDataset,\n    )\n\n    if isinstance(cfg, (list, tuple)):\n        dataset = ConcatDataset(\n            [custom_build_dataset(c, default_args) for c in cfg]\n        )\n    elif cfg[\"type\"] == \"ConcatDataset\":\n        dataset = ConcatDataset(\n            [custom_build_dataset(c, default_args) for c in cfg[\"datasets\"]],\n            cfg.get(\"separate_eval\", True),\n        )\n    elif cfg[\"type\"] == \"RepeatDataset\":\n        dataset = RepeatDataset(\n            custom_build_dataset(cfg[\"dataset\"], default_args), cfg[\"times\"]\n        )\n    elif cfg[\"type\"] == \"ClassBalancedDataset\":\n        dataset = ClassBalancedDataset(\n            custom_build_dataset(cfg[\"dataset\"], default_args),\n            cfg[\"oversample_thr\"],\n        )\n    elif cfg[\"type\"] == \"CBGSDataset\":\n        dataset = CBGSDataset(\n            custom_build_dataset(cfg[\"dataset\"], default_args)\n        )\n    elif isinstance(cfg.get(\"ann_file\"), (list, tuple)):\n        dataset = _concat_dataset(cfg, default_args)\n    else:\n        dataset = build_from_cfg(cfg, DATASETS, default_args)\n\n    return dataset\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/detection/nuscenes_styled_eval_utils.py",
    "content": "from collections import defaultdict\nfrom typing import List, Dict, Tuple, Union, Callable\nimport abc\nimport numpy as np\nfrom pyquaternion import Quaternion\n\n\ndef center_distance(gt_box, pred_box) -> float:\n    \"\"\"\n    L2 distance between the box centers (xy only).\n    :param gt_box: GT annotation sample.\n    :param pred_box: Predicted sample.\n    :return: L2 distance.\n    \"\"\"\n    return np.linalg.norm(np.array(pred_box.translation[:2]) - np.array(gt_box.translation[:2]))\n\n\ndef velocity_l2(gt_box, pred_box) -> float:\n    \"\"\"\n    L2 distance between the velocity vectors (xy only).\n    If the predicted velocities are nan, we return inf, which is subsequently clipped to 1.\n    :param gt_box: GT annotation sample.\n    :param pred_box: Predicted sample.\n    :return: L2 distance.\n    \"\"\"\n    return np.linalg.norm(np.array(pred_box.velocity) - np.array(gt_box.velocity))\n\n\ndef yaw_diff(gt_box, eval_box, period: float = 2*np.pi) -> float:\n    \"\"\"\n    Returns the yaw angle difference between the orientation of two boxes.\n    :param gt_box: Ground truth box.\n    :param eval_box: Predicted box.\n    :param period: Periodicity in radians for assessing angle difference.\n    :return: Yaw angle difference in radians in [0, pi].\n    \"\"\"\n    yaw_gt = quaternion_yaw(Quaternion(gt_box.rotation))\n    yaw_est = quaternion_yaw(Quaternion(eval_box.rotation))\n\n    return abs(angle_diff(yaw_gt, yaw_est, period))\n\n\ndef angle_diff(x: float, y: float, period: float) -> float:\n    \"\"\"\n    Get the smallest angle difference between 2 angles: the angle from y to x.\n    :param x: To angle.\n    :param y: From angle.\n    :param period: Periodicity in radians for assessing angle difference.\n    :return: <float>. Signed smallest between-angle difference in range (-pi, pi).\n    \"\"\"\n\n    # calculate angle difference, modulo to [0, 2*pi]\n    diff = (x - y + period / 2) % period - period / 2\n    if diff > np.pi:\n        diff = diff - (2 * np.pi)  # shift (pi, 2*pi] to (-pi, 0]\n\n    return diff\n\n\ndef attr_acc(gt_box, pred_box) -> float:\n    \"\"\"\n    Computes the classification accuracy for the attribute of this class (if any).\n    If the GT class has no attributes or the annotation is missing attributes, we assign an accuracy of nan, which is\n    ignored later on.\n    :param gt_box: GT annotation sample.\n    :param pred_box: Predicted sample.\n    :return: Attribute classification accuracy (0 or 1) or nan if GT annotation does not have any attributes.\n    \"\"\"\n    if gt_box.attribute_name == '':\n        # If the class does not have attributes or this particular sample is missing attributes, return nan, which is\n        # ignored later. Note that about 0.4% of the sample_annotations have no attributes, although they should.\n        acc = np.nan\n    else:\n        # Check that label is correct.\n        acc = float(gt_box.attribute_name == pred_box.attribute_name)\n    return acc\n\n\ndef scale_iou(sample_annotation, sample_result) -> float:\n    \"\"\"\n    This method compares predictions to the ground truth in terms of scale.\n    It is equivalent to intersection over union (IOU) between the two boxes in 3D,\n    if we assume that the boxes are aligned, i.e. translation and rotation are considered identical.\n    :param sample_annotation: GT annotation sample.\n    :param sample_result: Predicted sample.\n    :return: Scale IOU.\n    \"\"\"\n    # Validate inputs.\n    sa_size = np.array(sample_annotation.size)\n    sr_size = np.array(sample_result.size)\n    assert all(sa_size > 0), 'Error: sample_annotation sizes must be >0.'\n    assert all(sr_size > 0), 'Error: sample_result sizes must be >0.'\n\n    # Compute IOU.\n    min_wlh = np.minimum(sa_size, sr_size)\n    volume_annotation = np.prod(sa_size)\n    volume_result = np.prod(sr_size)\n    intersection = np.prod(min_wlh)  # type: float\n    union = volume_annotation + volume_result - intersection  # type: float\n    iou = intersection / union\n\n    return iou\n\n\ndef quaternion_yaw(q: Quaternion) -> float:\n    \"\"\"\n    Calculate the yaw angle from a quaternion.\n    Note that this only works for a quaternion that represents a box in lidar or global coordinate frame.\n    It does not work for a box in the camera frame.\n    :param q: Quaternion of interest.\n    :return: Yaw angle in radians.\n    \"\"\"\n\n    # Project into xy plane.\n    v = np.dot(q.rotation_matrix, np.array([1, 0, 0]))\n\n    # Measure yaw using arctan.\n    yaw = np.arctan2(v[1], v[0])\n\n    return yaw\n\n\n\ndef cummean(x: np.array) -> np.array:\n    \"\"\"\n    Computes the cumulative mean up to each position in a NaN sensitive way\n    - If all values are NaN return an array of ones.\n    - If some values are NaN, accumulate arrays discording those entries.\n    \"\"\"\n    if sum(np.isnan(x)) == len(x):\n        # Is all numbers in array are NaN's.\n        return np.ones(len(x))  # If all errors are NaN set to error to 1 for all operating points.\n    else:\n        # Accumulate in a nan-aware manner.\n        sum_vals = np.nancumsum(x.astype(float))  # Cumulative sum ignoring nans.\n        count_vals = np.cumsum(~np.isnan(x))  # Number of non-nans up to each position.\n        return np.divide(sum_vals, count_vals, out=np.zeros_like(sum_vals), where=count_vals != 0)\n    \n\nclass DetectionMetricData(abc.ABC):\n    \"\"\" This class holds accumulated and interpolated data required to calculate the detection metrics. \"\"\"\n\n    nelem = 101\n\n    def __init__(self,\n                 recall: np.array,\n                 precision: np.array,\n                 confidence: np.array,\n                 trans_err: np.array,\n                 vel_err: np.array,\n                 scale_err: np.array,\n                 orient_err: np.array,\n                 attr_err: np.array):\n\n        # Assert lengths.\n        assert len(recall) == self.nelem\n        assert len(precision) == self.nelem\n        assert len(confidence) == self.nelem\n        assert len(trans_err) == self.nelem\n        assert len(vel_err) == self.nelem\n        assert len(scale_err) == self.nelem\n        assert len(orient_err) == self.nelem\n        assert len(attr_err) == self.nelem\n\n        # Assert ordering.\n        assert all(confidence == sorted(confidence, reverse=True))  # Confidences should be descending.\n        assert all(recall == sorted(recall))  # Recalls should be ascending.\n\n        # Set attributes explicitly to help IDEs figure out what is going on.\n        self.recall = recall\n        self.precision = precision\n        self.confidence = confidence\n        self.trans_err = trans_err\n        self.vel_err = vel_err\n        self.scale_err = scale_err\n        self.orient_err = orient_err\n        self.attr_err = attr_err\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.serialize().keys():\n            eq = eq and np.array_equal(getattr(self, key), getattr(other, key))\n        return eq\n\n    @property\n    def max_recall_ind(self):\n        \"\"\" Returns index of max recall achieved. \"\"\"\n\n        # Last instance of confidence > 0 is index of max achieved recall.\n        non_zero = np.nonzero(self.confidence)[0]\n        if len(non_zero) == 0:  # If there are no matches, all the confidence values will be zero.\n            max_recall_ind = 0\n        else:\n            max_recall_ind = non_zero[-1]\n\n        return max_recall_ind\n\n    @property\n    def max_recall(self):\n        \"\"\" Returns max recall achieved. \"\"\"\n\n        return self.recall[self.max_recall_ind]\n\n    def serialize(self):\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'recall': self.recall.tolist(),\n            'precision': self.precision.tolist(),\n            'confidence': self.confidence.tolist(),\n            'trans_err': self.trans_err.tolist(),\n            'vel_err': self.vel_err.tolist(),\n            'scale_err': self.scale_err.tolist(),\n            'orient_err': self.orient_err.tolist(),\n            'attr_err': self.attr_err.tolist(),\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(recall=np.array(content['recall']),\n                   precision=np.array(content['precision']),\n                   confidence=np.array(content['confidence']),\n                   trans_err=np.array(content['trans_err']),\n                   vel_err=np.array(content['vel_err']),\n                   scale_err=np.array(content['scale_err']),\n                   orient_err=np.array(content['orient_err']),\n                   attr_err=np.array(content['attr_err']))\n\n    @classmethod\n    def no_predictions(cls):\n        \"\"\" Returns a md instance corresponding to having no predictions. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.zeros(cls.nelem),\n                   confidence=np.zeros(cls.nelem),\n                   trans_err=np.ones(cls.nelem),\n                   vel_err=np.ones(cls.nelem),\n                   scale_err=np.ones(cls.nelem),\n                   orient_err=np.ones(cls.nelem),\n                   attr_err=np.ones(cls.nelem))\n\n    @classmethod\n    def random_md(cls):\n        \"\"\" Returns an md instance corresponding to a random results. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.random.random(cls.nelem),\n                   confidence=np.linspace(0, 1, cls.nelem)[::-1],\n                   trans_err=np.random.random(cls.nelem),\n                   vel_err=np.random.random(cls.nelem),\n                   scale_err=np.random.random(cls.nelem),\n                   orient_err=np.random.random(cls.nelem),\n                   attr_err=np.random.random(cls.nelem))\n    \n\nclass DetectionMetricDataList:\n    \"\"\" This stores a set of MetricData in a dict indexed by (name, match-distance). \"\"\"\n\n    def __init__(self):\n        self.md = {}\n\n    def __getitem__(self, key):\n        return self.md[key]\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.md.keys():\n            eq = eq and self[key] == other[key]\n        return eq\n\n    def get_class_data(self, detection_name: str) -> List[Tuple[DetectionMetricData, float]]:\n        \"\"\" Get all the MetricData entries for a certain detection_name. \"\"\"\n        return [(md, dist_th) for (name, dist_th), md in self.md.items() if name == detection_name]\n\n    def get_dist_data(self, dist_th: float) -> List[Tuple[DetectionMetricData, str]]:\n        \"\"\" Get all the MetricData entries for a certain match_distance. \"\"\"\n        return [(md, detection_name) for (detection_name, dist), md in self.md.items() if dist == dist_th]\n\n    def set(self, detection_name: str, match_distance: float, data: DetectionMetricData):\n        \"\"\" Sets the MetricData entry for a certain detection_name and match_distance. \"\"\"\n        self.md[(detection_name, match_distance)] = data\n\n    def serialize(self) -> dict:\n        return {key[0] + ':' + str(key[1]): value.serialize() for key, value in self.md.items()}\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        mdl = cls()\n        for key, md in content.items():\n            name, distance = key.split(':')\n            mdl.set(name, float(distance), DetectionMetricData.deserialize(md))\n        return mdl\n\nclass DetectionMetrics:\n    \"\"\" Stores average precision and true positive metric results. Provides properties to summarize. \"\"\"\n\n    def __init__(self, cfg: dict):\n\n        self.cfg = cfg\n        self._label_aps = defaultdict(lambda: defaultdict(float))\n        self._label_tp_errors = defaultdict(lambda: defaultdict(float))\n        self.eval_time = None\n\n    def add_label_ap(self, detection_name: str, dist_th: float, ap: float) -> None:\n        self._label_aps[detection_name][dist_th] = ap\n\n    def get_label_ap(self, detection_name: str, dist_th: float) -> float:\n        return self._label_aps[detection_name][dist_th]\n\n    def add_label_tp(self, detection_name: str, metric_name: str, tp: float):\n        self._label_tp_errors[detection_name][metric_name] = tp\n\n    def get_label_tp(self, detection_name: str, metric_name: str) -> float:\n        return self._label_tp_errors[detection_name][metric_name]\n\n    def add_runtime(self, eval_time: float) -> None:\n        self.eval_time = eval_time\n\n    @property\n    def mean_dist_aps(self) -> Dict[str, float]:\n        \"\"\" Calculates the mean over distance thresholds for each label. \"\"\"\n        return {class_name: np.mean(list(d.values())) for class_name, d in self._label_aps.items()}\n\n    @property\n    def mean_ap(self) -> float:\n        \"\"\" Calculates the mean AP by averaging over distance thresholds and classes. \"\"\"\n        return float(np.mean(list(self.mean_dist_aps.values())))\n\n    @property\n    def tp_errors(self) -> Dict[str, float]:\n        \"\"\" Calculates the mean true positive error across all classes for each metric. \"\"\"\n        errors = {}\n        for metric_name in self.cfg['tp_metrics']:\n            class_errors = []\n            for detection_name in self.cfg['class_names']:\n                class_errors.append(self.get_label_tp(detection_name, metric_name))\n\n            errors[metric_name] = float(np.nanmean(class_errors))\n\n        return errors\n\n    @property\n    def tp_scores(self) -> Dict[str, float]:\n        scores = {}\n        tp_errors = self.tp_errors\n        for metric_name in self.cfg['tp_metrics']:\n\n            # We convert the true positive errors to \"scores\" by 1-error.\n            score = 1.0 - tp_errors[metric_name]\n\n            # Some of the true positive errors are unbounded, so we bound the scores to min 0.\n            score = max(0.0, score)\n\n            scores[metric_name] = score\n\n        return scores\n\n    @property\n    def nd_score(self) -> float:\n        \"\"\"\n        Compute the nuScenes detection score (NDS, weighted sum of the individual scores).\n        :return: The NDS.\n        \"\"\"\n        # Summarize.\n        total = float(self.cfg['mean_ap_weight'] * self.mean_ap + np.sum(list(self.tp_scores.values())))\n\n        # Normalize.\n        total = total / float(self.cfg['mean_ap_weight'] + len(self.tp_scores.keys()))\n\n        return total\n    \n\n    def serialize(self):\n        return {\n            'label_aps': self._label_aps,\n            'mean_dist_aps': self.mean_dist_aps,\n            'mean_ap': self.mean_ap,\n            'label_tp_errors': self._label_tp_errors,\n            'tp_errors': self.tp_errors,\n            'tp_scores': self.tp_scores,\n            'nd_score': self.nd_score,\n            'eval_time': self.eval_time,\n            'cfg': self.cfg\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized dictionary. \"\"\"\n\n        cfg = content['cfg']\n        metrics = cls(cfg=cfg)\n        metrics.add_runtime(content['eval_time'])\n\n        for detection_name, label_aps in content['label_aps'].items():\n            for dist_th, ap in label_aps.items():\n                metrics.add_label_ap(detection_name=detection_name, dist_th=float(dist_th), ap=float(ap))\n\n        for detection_name, label_tps in content['label_tp_errors'].items():\n            for metric_name, tp in label_tps.items():\n                metrics.add_label_tp(detection_name=detection_name, metric_name=metric_name, tp=float(tp))\n\n        return metrics\n\n    def __eq__(self, other):\n        eq = True\n        eq = eq and self._label_aps == other._label_aps\n        eq = eq and self._label_tp_errors == other._label_tp_errors\n        eq = eq and self.eval_time == other.eval_time\n        eq = eq and self.cfg == other.cfg\n\n        return eq\n    \n\nclass DetectionBox(abc.ABC):\n    \"\"\" Data class used during detection evaluation. Can be a prediction or ground truth.\"\"\"\n\n    def __init__(self,\n                 sample_token: str = \"\",\n                 translation: Tuple[float, float, float] = (0, 0, 0),\n                 size: Tuple[float, float, float] = (0, 0, 0),\n                 rotation: Tuple[float, float, float, float] = (0, 0, 0, 0),\n                 velocity: Tuple[float, float] = (0, 0),\n                 ego_translation: Tuple[float, float, float] = (0, 0, 0),  # Translation to ego vehicle in meters.\n                 num_pts: int = -1,  # Nbr. LIDAR or RADAR inside the box. Only for gt boxes.\n                 detection_name: str = 'car',  # The class name used in the detection challenge.\n                 detection_score: float = -1.0,  # GT samples do not have a score.\n                 attribute_name: str = ''):  # Box attribute. Each box can have at most 1 attribute.\n\n\n        assert detection_name is not None, 'Error: detection_name cannot be empty!'\n        # assert detection_name in DETECTION_NAMES, 'Error: Unknown detection_name %s' % detection_name\n\n        # assert attribute_name in ATTRIBUTE_NAMES or attribute_name == '', \\\n        #     'Error: Unknown attribute_name %s' % attribute_name\n\n        assert type(detection_score) == float, 'Error: detection_score must be a float!'\n        assert not np.any(np.isnan(detection_score)), 'Error: detection_score may not be NaN!'\n        self.sample_token = sample_token\n        self.translation = translation\n        self.size = size\n        self.rotation = rotation\n        self.velocity = velocity\n        self.ego_translation = ego_translation\n        self.num_pts = num_pts\n        self.detection_name = detection_name\n        self.detection_score = detection_score\n        self.attribute_name = attribute_name\n\n    def __eq__(self, other):\n        return (self.sample_token == other.sample_token and\n                self.translation == other.translation and\n                self.size == other.size and\n                self.rotation == other.rotation and\n                self.velocity == other.velocity and\n                self.ego_translation == other.ego_translation and\n                self.num_pts == other.num_pts and\n                self.detection_name == other.detection_name and\n                self.detection_score == other.detection_score and\n                self.attribute_name == other.attribute_name)\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(sample_token=content['sample_token'],\n                   translation=tuple(content['translation']),\n                   size=tuple(content['size']),\n                   rotation=tuple(content['rotation']),\n                   velocity=tuple(content['velocity']),\n                   ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                   else tuple(content['ego_translation']),\n                   num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                   detection_name=content['detection_name'],\n                   detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                   attribute_name=content['attribute_name'])\n    @property\n    def ego_dist(self) -> float:\n        \"\"\" Compute the distance from this box to the ego vehicle in 2D. \"\"\"\n        return np.sqrt(np.sum(np.array(self.ego_translation[:2]) ** 2))    \n\n\n\n\n\nclass EvalBoxes:\n    \"\"\" Data class that groups EvalBox instances by sample. \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the EvalBoxes for GT or predictions.\n        \"\"\"\n        self.boxes = defaultdict(list)\n\n    def __repr__(self):\n        return \"EvalBoxes with {} boxes across {} samples\".format(len(self.all), len(self.sample_tokens))\n\n    def __getitem__(self, item) -> List[DetectionBox]:\n        return self.boxes[item]\n\n    def __eq__(self, other):\n        if not set(self.sample_tokens) == set(other.sample_tokens):\n            return False\n        for token in self.sample_tokens:\n            if not len(self[token]) == len(other[token]):\n                return False\n            for box1, box2 in zip(self[token], other[token]):\n                if box1 != box2:\n                    return False\n        return True\n\n    def __len__(self):\n        return len(self.boxes)\n\n    @property\n    def all(self) -> List[DetectionBox]:\n        \"\"\" Returns all EvalBoxes in a list. \"\"\"\n        ab = []\n        for sample_token in self.sample_tokens:\n            ab.extend(self[sample_token])\n        return ab\n\n    @property\n    def sample_tokens(self) -> List[str]:\n        \"\"\" Returns a list of all keys. \"\"\"\n        return list(self.boxes.keys())\n\n    def add_boxes(self, sample_token: str, boxes: List[DetectionBox]) -> None:\n        \"\"\" Adds a list of boxes. \"\"\"\n        self.boxes[sample_token].extend(boxes)\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {key: [box.serialize() for box in boxes] for key, boxes in self.boxes.items()}\n\n    @classmethod\n    def deserialize(cls, content: dict, box_cls):\n        \"\"\"\n        Initialize from serialized content.\n        :param content: A dictionary with the serialized content of the box.\n        :param box_cls: The class of the boxes, DetectionBox or TrackingBox.\n        \"\"\"\n        eb = cls()\n        for sample_token, boxes in content.items():\n            eb.add_boxes(sample_token, [box_cls.deserialize(box) for box in boxes])\n        return eb\n    \n\ndef accumulate(gt_boxes,\n               pred_boxes,\n               class_name: str,\n               dist_fcn: Callable,\n               dist_th: float,\n               verbose: bool = False) -> DetectionMetricData:\n    \"\"\"\n    Average Precision over predefined different recall thresholds for a single distance threshold.\n    The recall/conf thresholds and other raw metrics will be used in secondary metrics.\n    :param gt_boxes: Maps every sample_token to a list of its sample_annotations.\n    :param pred_boxes: Maps every sample_token to a list of its sample_results.\n    :param class_name: Class to compute AP on.\n    :param dist_fcn: Distance function used to match detections and ground truths.\n    :param dist_th: Distance threshold for a match.\n    :param verbose: If true, print debug messages.\n    :return: (average_prec, metrics). The average precision value and raw data for a number of metrics.\n    \"\"\"\n    # ---------------------------------------------\n    # Organize input and initialize accumulators.\n    # ---------------------------------------------\n\n    # Count the positives.\n    npos = len([1 for gt_box in gt_boxes.all if gt_box.detection_name == class_name])\n    if verbose:\n        print(\"Found {} GT of class {} out of {} total across {} samples.\".\n              format(npos, class_name, len(gt_boxes.all), len(gt_boxes.sample_tokens)))\n\n    # For missing classes in the GT, return a data structure corresponding to no predictions.\n    if npos == 0:\n        return DetectionMetricData.no_predictions()\n\n    # Organize the predictions in a single list.\n    pred_boxes_list = [box for box in pred_boxes.all if box.detection_name == class_name]\n    pred_confs = [box.detection_score for box in pred_boxes_list]\n\n    if verbose:\n        print(\"Found {} PRED of class {} out of {} total across {} samples.\".\n              format(len(pred_confs), class_name, len(pred_boxes.all), len(pred_boxes.sample_tokens)))\n\n    # Sort by confidence.\n    sortind = [i for (v, i) in sorted((v, i) for (i, v) in enumerate(pred_confs))][::-1]\n\n    # Do the actual matching.\n    tp = []  # Accumulator of true positives.\n    fp = []  # Accumulator of false positives.\n    conf = []  # Accumulator of confidences.\n\n    # match_data holds the extra metrics we calculate for each match.\n    match_data = {'trans_err': [],\n                  'vel_err': [],\n                  'scale_err': [],\n                  'orient_err': [],\n                  'attr_err': [],\n                  'conf': []}\n\n    # ---------------------------------------------\n    # Match and accumulate match data.\n    # ---------------------------------------------\n\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th\n\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n\n            #  Update tp, fp and confs.\n            tp.append(1)\n            fp.append(0)\n            conf.append(pred_box.detection_score)\n\n            # Since it is a match, update match data also.\n            gt_box_match = gt_boxes[pred_box.sample_token][match_gt_idx]\n\n            match_data['trans_err'].append(center_distance(gt_box_match, pred_box))\n            match_data['vel_err'].append(velocity_l2(gt_box_match, pred_box))\n            match_data['scale_err'].append(1 - scale_iou(gt_box_match, pred_box))\n\n            # Barrier orientation is only determined up to 180 degree. (For cones orientation is discarded later)\n            period = np.pi if class_name == 'barrier' else 2 * np.pi\n            match_data['orient_err'].append(yaw_diff(gt_box_match, pred_box, period=period))\n\n            match_data['attr_err'].append(1 - attr_acc(gt_box_match, pred_box))\n            match_data['conf'].append(pred_box.detection_score)\n\n        else:\n            # No match. Mark this as a false positive.\n            tp.append(0)\n            fp.append(1)\n            conf.append(pred_box.detection_score)\n\n    # Check if we have any matches. If not, just return a \"no predictions\" array.\n    if len(match_data['trans_err']) == 0:\n        return DetectionMetricData.no_predictions()\n\n    # ---------------------------------------------\n    # Calculate and interpolate precision and recall\n    # ---------------------------------------------\n\n    # Accumulate.\n    tp = np.cumsum(tp).astype(float)\n    fp = np.cumsum(fp).astype(float)\n    conf = np.array(conf)\n\n    # Calculate precision and recall.\n    prec = tp / (fp + tp)\n    rec = tp / float(npos)\n\n    rec_interp = np.linspace(0, 1, DetectionMetricData.nelem)  # 101 steps, from 0% to 100% recall.\n    prec = np.interp(rec_interp, rec, prec, right=0)\n    conf = np.interp(rec_interp, rec, conf, right=0)\n    rec = rec_interp\n\n    # ---------------------------------------------\n    # Re-sample the match-data to match, prec, recall and conf.\n    # ---------------------------------------------\n\n    for key in match_data.keys():\n        if key == \"conf\":\n            continue  # Confidence is used as reference to align with fp and tp. So skip in this step.\n\n        else:\n            # For each match_data, we first calculate the accumulated mean.\n            tmp = cummean(np.array(match_data[key]))\n\n            # Then interpolate based on the confidences. (Note reversing since np.interp needs increasing arrays)\n            match_data[key] = np.interp(conf[::-1], match_data['conf'][::-1], tmp[::-1])[::-1]\n\n    # ---------------------------------------------\n    # Done. Instantiate MetricData and return\n    # ---------------------------------------------\n    return DetectionMetricData(recall=rec,\n                               precision=prec,\n                               confidence=conf,\n                               trans_err=match_data['trans_err'],\n                               vel_err=match_data['vel_err'],\n                               scale_err=match_data['scale_err'],\n                               orient_err=match_data['orient_err'],\n                               attr_err=match_data['attr_err'])\n\n\n\ndef calc_ap(md: DetectionMetricData, min_recall: float, min_precision: float) -> float:\n    \"\"\" Calculated average precision. \"\"\"\n\n    assert 0 <= min_precision < 1\n    assert 0 <= min_recall <= 1\n\n    prec = np.copy(md.precision)\n    prec = prec[round(100 * min_recall) + 1:]  # Clip low recalls. +1 to exclude the min recall bin.\n    prec -= min_precision  # Clip low precision\n    prec[prec < 0] = 0\n    return float(np.mean(prec)) / (1.0 - min_precision)\n\n\ndef calc_tp(md: DetectionMetricData, min_recall: float, metric_name: str) -> float:\n    \"\"\" Calculates true positive errors. \"\"\"\n\n    first_ind = round(100 * min_recall) + 1  # +1 to exclude the error at min recall.\n    last_ind = md.max_recall_ind  # First instance of confidence = 0 is index of max achieved recall.\n    if last_ind < first_ind:\n        return 1.0  # Assign 1 here. If this happens for all classes, the score for that TP metric will be 0.\n    else:\n        return float(np.mean(getattr(md, metric_name)[first_ind: last_ind + 1]))  # +1 to include error at max recall.\n    \n    \ndef quaternion_yaw(q: Quaternion) -> float:\n    \"\"\"\n    Calculate the yaw angle from a quaternion.\n    Note that this only works for a quaternion that represents a box in lidar or global coordinate frame.\n    It does not work for a box in the camera frame.\n    :param q: Quaternion of interest.\n    :return: Yaw angle in radians.\n    \"\"\"\n\n    # Project into xy plane.\n    v = np.dot(q.rotation_matrix, np.array([1, 0, 0]))\n\n    # Measure yaw using arctan.\n    yaw = np.arctan2(v[1], v[0])\n\n    return yaw"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/map/AP.py",
    "content": "import numpy as np\nfrom .distance import chamfer_distance, frechet_distance, chamfer_distance_batch\nfrom typing import List, Tuple, Union\nfrom numpy.typing import NDArray\n\ndef average_precision(recalls, precisions, mode='area'):\n    \"\"\"Calculate average precision. \n\n    Args:\n        recalls (ndarray): shape (num_dets, )\n        precisions (ndarray): shape (num_dets, )\n        mode (str): 'area' or '11points', 'area' means calculating the area\n            under precision-recall curve, '11points' means calculating\n            the average precision of recalls at [0, 0.1, ..., 1]\n\n    Returns:\n        float: calculated average precision\n    \"\"\"\n\n    recalls = recalls[np.newaxis, :]\n    precisions = precisions[np.newaxis, :]\n\n    assert recalls.shape == precisions.shape and recalls.ndim == 2\n    num_scales = recalls.shape[0]\n    ap = 0.\n\n    if mode == 'area':\n        zeros = np.zeros((num_scales, 1), dtype=recalls.dtype)\n        ones = np.ones((num_scales, 1), dtype=recalls.dtype)\n        mrec = np.hstack((zeros, recalls, ones))\n        mpre = np.hstack((zeros, precisions, zeros))\n        for i in range(mpre.shape[1] - 1, 0, -1):\n            mpre[:, i - 1] = np.maximum(mpre[:, i - 1], mpre[:, i])\n        \n        ind = np.where(mrec[0, 1:] != mrec[0, :-1])[0]\n        ap = np.sum(\n            (mrec[0, ind + 1] - mrec[0, ind]) * mpre[0, ind + 1])\n    \n    elif mode == '11points':\n        for thr in np.arange(0, 1 + 1e-3, 0.1):\n            precs = precisions[0, recalls[i, :] >= thr]\n            prec = precs.max() if precs.size > 0 else 0\n            ap += prec\n        ap /= 11\n    else:\n        raise ValueError(\n            'Unrecognized mode, only \"area\" and \"11points\" are supported')\n    \n    return ap\n\ndef instance_match(pred_lines: NDArray, \n                   scores: NDArray, \n                   gt_lines: NDArray, \n                   thresholds: Union[Tuple, List], \n                   metric: str='chamfer') -> List:\n    \"\"\"Compute whether detected lines are true positive or false positive.\n\n    Args:\n        pred_lines (array): Detected lines of a sample, of shape (M, INTERP_NUM, 2 or 3).\n        scores (array): Confidence score of each line, of shape (M, ).\n        gt_lines (array): GT lines of a sample, of shape (N, INTERP_NUM, 2 or 3).\n        thresholds (list of tuple): List of thresholds.\n        metric (str): Distance function for lines matching. Default: 'chamfer'.\n\n    Returns:\n        list_of_tp_fp (list): tp-fp matching result at all thresholds\n    \"\"\"\n\n    if metric == 'chamfer':\n        distance_fn = chamfer_distance\n\n    elif metric == 'frechet':\n        distance_fn = frechet_distance\n    \n    else:\n        raise ValueError(f'unknown distance function {metric}')\n\n    num_preds = pred_lines.shape[0]\n    num_gts = gt_lines.shape[0]\n\n    # tp and fp\n    tp_fp_list = []\n    tp = np.zeros((num_preds), dtype=np.float32)\n    fp = np.zeros((num_preds), dtype=np.float32)\n\n    # if there is no gt lines in this sample, then all pred lines are false positives\n    if num_gts == 0:\n        fp[...] = 1\n        for thr in thresholds:\n            tp_fp_list.append((tp.copy(), fp.copy()))\n        return tp_fp_list\n    \n    if num_preds == 0:\n        for thr in thresholds:\n            tp_fp_list.append((tp.copy(), fp.copy()))\n        return tp_fp_list\n\n    assert pred_lines.shape[1] == gt_lines.shape[1], \\\n        \"sample points num should be the same\"\n\n    # distance matrix: M x N\n    matrix = np.zeros((num_preds, num_gts))\n\n    # for i in range(num_preds):\n    #     for j in range(num_gts):\n    #         matrix[i, j] = distance_fn(pred_lines[i], gt_lines[j])\n    \n    matrix = chamfer_distance_batch(pred_lines, gt_lines)\n    # for each det, the min distance with all gts\n    matrix_min = matrix.min(axis=1)\n\n    # for each det, which gt is the closest to it\n    matrix_argmin = matrix.argmin(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-scores)\n\n    # match under different thresholds\n    for thr in thresholds:\n        tp = np.zeros((num_preds), dtype=np.float32)\n        fp = np.zeros((num_preds), dtype=np.float32)\n\n        gt_covered = np.zeros(num_gts, dtype=bool)\n        for i in sort_inds:\n            if matrix_min[i] <= thr:\n                matched_gt = matrix_argmin[i]\n                if not gt_covered[matched_gt]:\n                    gt_covered[matched_gt] = True\n                    tp[i] = 1\n                else:\n                    fp[i] = 1\n            else:\n                fp[i] = 1\n        \n        tp_fp_list.append((tp, fp))\n\n    return tp_fp_list"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/map/distance.py",
    "content": "from scipy.spatial import distance\nfrom numpy.typing import NDArray\nimport torch\n\ndef chamfer_distance(line1: NDArray, line2: NDArray) -> float:\n    ''' Calculate chamfer distance between two lines. Make sure the \n    lines are interpolated.\n\n    Args:\n        line1 (array): coordinates of line1\n        line2 (array): coordinates of line2\n    \n    Returns:\n        distance (float): chamfer distance\n    '''\n    \n    dist_matrix = distance.cdist(line1, line2, 'euclidean')\n    dist12 = dist_matrix.min(-1).sum() / len(line1)\n    dist21 = dist_matrix.min(-2).sum() / len(line2)\n\n    return (dist12 + dist21) / 2\n\ndef frechet_distance(line1: NDArray, line2: NDArray) -> float:\n    ''' Calculate frechet distance between two lines. Make sure the \n    lines are interpolated.\n\n    Args:\n        line1 (array): coordinates of line1\n        line2 (array): coordinates of line2\n    \n    Returns:\n        distance (float): frechet distance\n    '''\n    \n    raise NotImplementedError\n\ndef chamfer_distance_batch(pred_lines, gt_lines):\n    ''' Calculate chamfer distance between two group of lines. Make sure the \n    lines are interpolated.\n\n    Args:\n        pred_lines (array or tensor): shape (m, num_pts, 2 or 3)\n        gt_lines (array or tensor): shape (n, num_pts, 2 or 3)\n    \n    Returns:\n        distance (array): chamfer distance\n    '''\n    _, num_pts, coord_dims = pred_lines.shape\n    \n    if not isinstance(pred_lines, torch.Tensor):\n        pred_lines = torch.tensor(pred_lines)\n    if not isinstance(gt_lines, torch.Tensor):\n        gt_lines = torch.tensor(gt_lines)\n    dist_mat = torch.cdist(pred_lines.view(-1, coord_dims), \n                    gt_lines.view(-1, coord_dims), p=2) \n    # (num_query*num_points, num_gt*num_points)\n    dist_mat = torch.stack(torch.split(dist_mat, num_pts)) \n    # (num_query, num_points, num_gt*num_points)\n    dist_mat = torch.stack(torch.split(dist_mat, num_pts, dim=-1)) \n    # (num_gt, num_q, num_pts, num_pts)\n\n    dist1 = dist_mat.min(-1)[0].sum(-1)\n    dist2 = dist_mat.min(-2)[0].sum(-1)\n\n    dist_matrix = (dist1 + dist2).transpose(0, 1) / (2 * num_pts)\n    \n    return dist_matrix.numpy()"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/map/vector_eval.py",
    "content": "import prettytable\nfrom typing import Dict, List, Optional\nfrom time import time\nfrom copy import deepcopy\nfrom multiprocessing import Pool\nfrom logging import Logger\nfrom functools import partial, cached_property\n\nimport numpy as np\nfrom numpy.typing import NDArray\nfrom shapely.geometry import LineString\n\nimport mmcv\nfrom mmcv import Config\nfrom mmdet.datasets import build_dataset, build_dataloader\n\nfrom .AP import instance_match, average_precision\n\nINTERP_NUM = 50 # number of points to interpolate during evaluation\nTHRESHOLDS = [0.5, 1.0, 1.5] # AP thresholds\nN_WORKERS = 0 # num workers to parallel\n\nclass VectorEvaluate(object):\n    \"\"\"Evaluator for vectorized map.\n\n    Args:\n        dataset_cfg (Config): dataset cfg for gt\n        n_workers (int): num workers to parallel\n    \"\"\"\n\n    def __init__(self, dataset_cfg: Config, n_workers: int=N_WORKERS) -> None:\n        self.dataset = build_dataset(dataset_cfg)\n        self.dataloader = build_dataloader(\n            self.dataset, samples_per_gpu=1, workers_per_gpu=n_workers, shuffle=False, dist=False)\n        classes = self.dataset.MAP_CLASSES\n        self.cat2id = {cls: i for i, cls in enumerate(classes)}\n        self.id2cat = {v: k for k, v in self.cat2id.items()}\n        self.n_workers = n_workers\n        self.thresholds = [0.5, 1.0, 1.5]\n        \n    @cached_property\n    def gts(self) -> Dict[str, Dict[int, List[NDArray]]]:\n        print('collecting gts...')\n        gts = {}\n        pbar = mmcv.ProgressBar(len(self.dataloader))\n        for data in self.dataloader:\n            token = deepcopy(data['img_metas'].data[0][0]['token'])\n            gt = deepcopy(data['vectors'].data[0][0])\n            gts[token] = gt\n            pbar.update()\n            del data # avoid dataloader memory crash\n        \n        return gts\n    \n    def interp_fixed_num(self, \n                         vector: NDArray, \n                         num_pts: int) -> NDArray:\n        ''' Interpolate a polyline.\n        \n        Args:\n            vector (array): line coordinates, shape (M, 2)\n            num_pts (int): \n        \n        Returns:\n            sampled_points (array): interpolated coordinates\n        '''\n        line = LineString(vector)\n        distances = np.linspace(0, line.length, num_pts)\n        sampled_points = np.array([list(line.interpolate(distance).coords) \n            for distance in distances]).squeeze()\n        \n        return sampled_points\n    \n    def interp_fixed_dist(self, \n                          vector: NDArray,\n                          sample_dist: float) -> NDArray:\n        ''' Interpolate a line at fixed interval.\n        \n        Args:\n            vector (LineString): vector\n            sample_dist (float): sample interval\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n        line = LineString(vector)\n        distances = list(np.arange(sample_dist, line.length, sample_dist))\n        # make sure to sample at least two points when sample_dist > line.length\n        distances = [0,] + distances + [line.length,] \n        \n        sampled_points = np.array([list(line.interpolate(distance).coords)\n                                for distance in distances]).squeeze()\n        \n        return sampled_points\n\n    def _evaluate_single(self, \n                         pred_vectors: List, \n                         scores: List, \n                         groundtruth: List, \n                         thresholds: List, \n                         metric: str='metric') -> Dict[int, NDArray]:\n        ''' Do single-frame matching for one class.\n        \n        Args:\n            pred_vectors (List): List[vector(ndarray) (different length)], \n            scores (List): List[score(float)]\n            groundtruth (List): List of vectors\n            thresholds (List): List of thresholds\n        \n        Returns:\n            tp_fp_score_by_thr (Dict): matching results at different thresholds\n                e.g. {0.5: (M, 2), 1.0: (M, 2), 1.5: (M, 2)}\n        '''\n        pred_lines = []\n\n        # interpolate predictions\n        for vector in pred_vectors:\n            vector = np.array(vector)\n            vector_interp = self.interp_fixed_num(vector, INTERP_NUM)\n            pred_lines.append(vector_interp)\n        if pred_lines:\n            pred_lines = np.stack(pred_lines)\n        else:\n            pred_lines = np.zeros((0, INTERP_NUM, 2))\n\n        # interpolate groundtruth\n        gt_lines = []\n        for vector in groundtruth:\n            vector_interp = self.interp_fixed_num(vector, INTERP_NUM)\n            gt_lines.append(vector_interp)\n        if gt_lines:\n            gt_lines = np.stack(gt_lines)\n        else:\n            gt_lines = np.zeros((0, INTERP_NUM, 2))\n        \n        scores = np.array(scores)\n        tp_fp_list = instance_match(pred_lines, scores, gt_lines, thresholds, metric) # (M, 2)\n        tp_fp_score_by_thr = {}\n        for i, thr in enumerate(thresholds):\n            tp, fp = tp_fp_list[i]\n            tp_fp_score = np.hstack([tp[:, None], fp[:, None], scores[:, None]])\n            tp_fp_score_by_thr[thr] = tp_fp_score\n        \n        return tp_fp_score_by_thr # {0.5: (M, 2), 1.0: (M, 2), 1.5: (M, 2)}\n        \n    def evaluate(self, \n                 result_path: str, \n                 metric: str='chamfer', \n                 logger: Optional[Logger]=None) -> Dict[str, float]:\n        ''' Do evaluation for a submission file and print evalution results to `logger` if specified.\n        The submission will be aligned by tokens before evaluation. We use multi-worker to speed up.\n        \n        Args:\n            result_path (str): path to submission file\n            metric (str): distance metric. Default: 'chamfer'\n            logger (Logger): logger to print evaluation result, Default: None\n        \n        Returns:\n            new_result_dict (Dict): evaluation results. AP by categories.\n        '''\n        results = mmcv.load(result_path)\n        results = results['results']\n        \n        # re-group samples and gt by label\n        samples_by_cls = {label: [] for label in self.id2cat.keys()}\n        num_gts = {label: 0 for label in self.id2cat.keys()}\n        num_preds = {label: 0 for label in self.id2cat.keys()}\n\n        # align by token\n        for token, gt in self.gts.items():\n            if token in results.keys():\n                pred = results[token]\n            else:\n                pred = {'vectors': [], 'scores': [], 'labels': []}\n            \n            # for every sample\n            vectors_by_cls = {label: [] for label in self.id2cat.keys()}\n            scores_by_cls = {label: [] for label in self.id2cat.keys()}\n\n            for i in range(len(pred['labels'])):\n                # i-th pred line in sample\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n                score = pred['scores'][i]\n\n                vectors_by_cls[label].append(vector)\n                scores_by_cls[label].append(score)\n\n            for label in self.id2cat.keys():\n                new_sample = (vectors_by_cls[label], scores_by_cls[label], gt[label])\n                num_gts[label] += len(gt[label])\n                num_preds[label] += len(scores_by_cls[label])\n                samples_by_cls[label].append(new_sample)\n\n        result_dict = {}\n\n        print(f'\\nevaluating {len(self.id2cat)} categories...')\n        start = time()\n        if self.n_workers > 0:\n            pool = Pool(self.n_workers)\n        \n        sum_mAP = 0\n        pbar = mmcv.ProgressBar(len(self.id2cat))\n        for label in self.id2cat.keys():\n            samples = samples_by_cls[label] # List[(pred_lines, scores, gts)]\n            result_dict[self.id2cat[label]] = {\n                'num_gts': num_gts[label],\n                'num_preds': num_preds[label]\n            }\n            sum_AP = 0\n\n            fn = partial(self._evaluate_single, thresholds=self.thresholds, metric=metric)\n            if self.n_workers > 0 and len(samples) > 81:\n                tpfp_score_list = pool.starmap(fn, samples)\n            else:\n                tpfp_score_list = []\n                for sample in samples:\n                    tpfp_score_list.append(fn(*sample))\n            \n            for thr in self.thresholds:\n                tp_fp_score = [i[thr] for i in tpfp_score_list]\n                tp_fp_score = np.vstack(tp_fp_score) # (num_dets, 3)\n                sort_inds = np.argsort(-tp_fp_score[:, -1])\n\n                tp = tp_fp_score[sort_inds, 0] # (num_dets,)\n                fp = tp_fp_score[sort_inds, 1] # (num_dets,)\n                tp = np.cumsum(tp, axis=0)\n                fp = np.cumsum(fp, axis=0)\n                eps = np.finfo(np.float32).eps\n                recalls = tp / np.maximum(num_gts[label], eps)\n                precisions = tp / np.maximum((tp + fp), eps)\n\n                AP = average_precision(recalls, precisions, 'area')\n                sum_AP += AP\n                result_dict[self.id2cat[label]].update({f'AP@{thr}': AP})\n\n            pbar.update()\n            \n            AP = sum_AP / len(self.thresholds)\n            sum_mAP += AP\n\n            result_dict[self.id2cat[label]].update({f'AP': AP})\n        \n        if self.n_workers > 0:\n            pool.close()\n        \n        mAP = sum_mAP / len(self.id2cat.keys())\n        result_dict.update({'mAP': mAP})\n        \n        print(f\"finished in {time() - start:.2f}s\")\n\n        # print results\n        table = prettytable.PrettyTable(['category', 'num_preds', 'num_gts'] + \n                [f'AP@{thr}' for thr in self.thresholds] + ['AP'])\n        for label in self.id2cat.keys():\n            table.add_row([\n                self.id2cat[label], \n                result_dict[self.id2cat[label]]['num_preds'],\n                result_dict[self.id2cat[label]]['num_gts'],\n                *[round(result_dict[self.id2cat[label]][f'AP@{thr}'], 4) for thr in self.thresholds],\n                round(result_dict[self.id2cat[label]]['AP'], 4),\n            ])\n        \n        from mmcv.utils import print_log\n        print_log('\\n'+str(table), logger=logger)\n        mAP_normal = 0\n        for label in self.id2cat.keys():\n            for thr in self.thresholds:\n                mAP_normal += result_dict[self.id2cat[label]][f'AP@{thr}']\n        mAP_normal = mAP_normal / 9\n\n        print_log(f'mAP_normal = {mAP_normal:.4f}\\n', logger=logger)\n        # print_log(f'mAP_hard = {mAP_easy:.4f}\\n', logger=logger)\n\n        new_result_dict = {}\n        for name in self.cat2id:\n            new_result_dict[name] = result_dict[name]['AP']\n        new_result_dict['mAP_normal'] = mAP_normal\n        return new_result_dict"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/motion/motion_eval_uniad.py",
    "content": "# nuScenes dev-kit.\n# Code written by Holger Caesar & Oscar Beijbom, 2018.\n\nimport argparse\nimport json\nimport os\nimport random\nimport time\nimport tqdm\nfrom typing import Tuple, Dict, Any\n\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import accumulate, calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES, ATTRIBUTE_NAMES, TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList, DetectionMetricData\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, class_tp_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom nuscenes.eval.common.utils import center_distance, scale_iou, yaw_diff, velocity_l2, attr_acc, cummean\n\nfrom .motion_utils import MotionBox, load_prediction, load_gt, accumulate\nMOTION_TP_METRICS = ['min_ade_err', 'min_fde_err', 'miss_rate_err']\n\n\nclass MotionEval:\n    \"\"\"\n    This is the official nuScenes detection evaluation code.\n    Results are written to the provided output_dir.\n\n    nuScenes uses the following detection metrics:\n    - Mean Average Precision (mAP): Uses center-distance as matching criterion; averaged over distance thresholds.\n    - True Positive (TP) metrics: Average of translation, velocity, scale, orientation and attribute errors.\n    - nuScenes Detection Score (NDS): The weighted sum of the above.\n\n    Here is an overview of the functions in this method:\n    - init: Loads GT annotations and predictions stored in JSON format and filters the boxes.\n    - run: Performs evaluation and dumps the metric data to disk.\n    - render: Renders various plots and dumps to disk.\n\n    We assume that:\n    - Every sample_token is given in the results, although there may be not predictions for that sample.\n\n    Please see https://www.nuscenes.org/object-detection for more details.\n    \"\"\"\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 seconds: int = 12):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n\n        # Check result file exists.\n        # assert os.path.exists(result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, MotionBox,\n                                                     verbose=verbose)\n        self.gt_boxes = load_gt(self.nusc, self.eval_set, MotionBox, verbose=verbose, seconds=seconds)\n\n        assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n            \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        # Filter boxes (distance, points per box, etc.).\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(nusc, self.pred_boxes, self.cfg.class_range, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(nusc, self.gt_boxes, self.cfg.class_range, verbose=verbose)\n\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n    def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n        self.cfg.class_names = ['car', 'pedestrian']\n        self.cfg.dist_ths = [2.0]\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMetricDataList()\n        metrics = {}\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md, EPA, EPA_ = accumulate(self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics[f'{class_name}_EPA'] = EPA_\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        for class_name in self.cfg.class_names:\n            # Compute TP metrics.\n            for metric_name in MOTION_TP_METRICS:\n                metric_data = metric_data_list[(class_name, self.cfg.dist_th_tp)]\n                tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                metrics[f'{class_name}_{metric_name}']  = tp\n\n        return metrics, metric_data_list\n\n    def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(md_list, metrics, min_precision=self.cfg.min_precision, min_recall=self.cfg.min_recall,\n                     dist_th_tp=self.cfg.dist_th_tp, savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(md_list, metrics, detection_name, self.cfg.min_precision, self.cfg.min_recall,\n                           savepath=savepath(detection_name + '_pr'))\n\n            class_tp_curve(md_list, metrics, detection_name, self.cfg.min_recall, self.cfg.dist_th_tp,\n                           savepath=savepath(detection_name + '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(md_list, metrics, dist_th, self.cfg.min_precision, self.cfg.min_recall,\n                          savepath=savepath('dist_pr_' + str(dist_th)))\n\n    def main(self,\n             plot_examples: int = 0,\n             render_curves: bool = True) -> Dict[str, Any]:\n        \"\"\"\n        Main function that loads the evaluation code, visualizes samples, runs the evaluation and renders stat plots.\n        :param plot_examples: How many example visualizations to write to disk.\n        :param render_curves: Whether to render PR and TP curves to disk.\n        :return: A dict that stores the high-level metrics and meta data.\n        \"\"\"\n        if plot_examples > 0:\n            # Select a random but fixed subset to plot.\n            random.seed(42)\n            sample_tokens = list(self.sample_tokens)\n            random.shuffle(sample_tokens)\n            sample_tokens = sample_tokens[:plot_examples]\n\n            # Visualize samples.\n            example_dir = os.path.join(self.output_dir, 'examples')\n            if not os.path.isdir(example_dir):\n                os.mkdir(example_dir)\n            for sample_token in sample_tokens:\n                visualize_sample(self.nusc,\n                                 sample_token,\n                                 self.gt_boxes if self.eval_set != 'test' else EvalBoxes(),\n                                 # Don't render test GT.\n                                 self.pred_boxes,\n                                 eval_range=max(self.cfg.class_range.values()),\n                                 savepath=os.path.join(example_dir, '{}.png'.format(sample_token)))\n\n        # Run evaluation.\n        metrics, metric_data_list = self.evaluate()\n\n        return metrics\n\nclass NuScenesEval(MotionEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as MotionEval.\n    \"\"\"\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(description='Evaluate nuScenes detection results.',\n                                     formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument('result_path', type=str, help='The submission as a JSON file.')\n    parser.add_argument('--output_dir', type=str, default='~/nuscenes-metrics',\n                        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument('--eval_set', type=str, default='val',\n                        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='/data/sets/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument('--version', type=str, default='v1.0-trainval',\n                        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument('--config_path', type=str, default='',\n                        help='Path to the configuration file.'\n                             'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument('--plot_examples', type=int, default=10,\n                        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = DetectionEval(nusc_, config=cfg_, result_path=result_path_, eval_set=eval_set_,\n                              output_dir=output_dir_, verbose=verbose_)\n    nusc_eval.main(plot_examples=plot_examples_, render_curves=render_curves_)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/motion/motion_utils.py",
    "content": "# nuScenes dev-kit.\n# Code written by Holger Caesar & Oscar Beijbom, 2018.\n\nimport argparse\nimport json\nimport os\nimport random\nimport time\nimport tqdm\nfrom typing import Tuple, Dict, Any, Callable\n\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES, ATTRIBUTE_NAMES, TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList, DetectionMetricData\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, class_tp_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom nuscenes.eval.common.utils import center_distance, scale_iou, yaw_diff, velocity_l2, attr_acc, cummean\n\n\nmotion_name_mapping = {\n    'car': 'car',\n    'truck': 'car',\n    'construction_vehicle': 'car',\n    'bus': 'car',\n    'trailer': 'car',\n    'motorcycle': 'car',\n    'bicycle': 'car',\n    'pedestrian': 'pedestrian',\n    'traffic_cone': 'barrier',\n    'barrier': 'barrier',\n}\n\n\nclass MotionBox(DetectionBox):\n    \"\"\" Data class used during detection evaluation. Can be a prediction or ground truth.\"\"\"\n\n    def __init__(self,\n                 sample_token: str = \"\",\n                 translation: Tuple[float, float, float] = (0, 0, 0),\n                 size: Tuple[float, float, float] = (0, 0, 0),\n                 rotation: Tuple[float, float, float, float] = (0, 0, 0, 0),\n                 velocity: Tuple[float, float] = (0, 0),\n                 ego_translation: [float, float, float] = (0, 0, 0),  # Translation to ego vehicle in meters.\n                 num_pts: int = -1,  # Nbr. LIDAR or RADAR inside the box. Only for gt boxes.\n                 detection_name: str = 'car',  # The class name used in the detection challenge.\n                 detection_score: float = -1.0,  # GT samples do not have a score.\n                 attribute_name: str = '',  # Box attribute. Each box can have at most 1 attribute.\n                 traj=None):  \n\n        super().__init__(sample_token, translation, size, rotation, velocity, ego_translation, num_pts)\n\n        assert detection_name is not None, 'Error: detection_name cannot be empty!'\n        assert detection_name in DETECTION_NAMES, 'Error: Unknown detection_name %s' % detection_name\n\n        assert attribute_name in ATTRIBUTE_NAMES or attribute_name == '', \\\n            'Error: Unknown attribute_name %s' % attribute_name\n\n        assert type(detection_score) == float, 'Error: detection_score must be a float!'\n        assert not np.any(np.isnan(detection_score)), 'Error: detection_score may not be NaN!'\n\n        # Assign.\n        self.detection_name = detection_name\n        self.detection_score = detection_score\n        self.attribute_name = attribute_name\n        self.traj = traj\n\n    def __eq__(self, other):\n        return (self.sample_token == other.sample_token and\n                self.translation == other.translation and\n                self.size == other.size and\n                self.rotation == other.rotation and\n                self.velocity == other.velocity and\n                self.ego_translation == other.ego_translation and\n                self.num_pts == other.num_pts and\n                self.detection_name == other.detection_name and\n                self.detection_score == other.detection_score and\n                self.attribute_name == other.attribute_name and\n                np.all(self.traj == other.traj))\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'traj': self.traj,\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(sample_token=content['sample_token'],\n                   translation=tuple(content['translation']),\n                   size=tuple(content['size']),\n                   rotation=tuple(content['rotation']),\n                   velocity=tuple(content['velocity']),\n                   ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                   else tuple(content['ego_translation']),\n                   num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                   detection_name=content['detection_name'],\n                   detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                   attribute_name=content['attribute_name'],\n                   traj=content['trajs'],)\n\n\ndef load_prediction(result_path: str, max_boxes_per_sample: int, box_cls, verbose: bool = False) \\\n        -> Tuple[EvalBoxes, Dict]:\n    \"\"\"\n    Loads object predictions from file.\n    :param result_path: Path to the .json result file provided by the user.\n    :param max_boxes_per_sample: Maximim number of boxes allowed per sample.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The deserialized results and meta data.\n    \"\"\"\n\n    # Load from file and check that the format is correct.\n    # with open(result_path) as f:\n    #     data = json.load(f)\n    data = result_path\n    assert 'results' in data, 'Error: No field `results` in result file. Please note that the result format changed.' \\\n                              'See https://www.nuscenes.org/object-detection for more information.'\n\n    # motion name mapping\n    for key in data['results'].keys():\n        for i in range(len(data['results'][key])):\n            cls_name = data['results'][key][i]['detection_name']\n            if cls_name in motion_name_mapping:\n                cls_name = motion_name_mapping[cls_name]\n            data['results'][key][i]['detection_name'] = cls_name\n    \n    # Deserialize results and get meta data.\n    all_results = EvalBoxes.deserialize(data['results'], box_cls)\n    meta = data['meta']\n    if verbose:\n        print(\"Loaded results from {}. Found detections for {} samples.\"\n              .format(result_path, len(all_results.sample_tokens)))\n\n    # Check that each sample has no more than x predicted boxes.\n    for sample_token in all_results.sample_tokens:\n        assert len(all_results.boxes[sample_token]) <= max_boxes_per_sample, \\\n            \"Error: Only <= %d boxes per sample allowed!\" % max_boxes_per_sample\n\n    return all_results, meta\n\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False, seconds: int = 12) -> EvalBoxes:\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n    predict_helper = PredictHelper(nusc)\n    # Init.\n    if box_cls == MotionBox:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n\n    sample_tokens = []\n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n\n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == MotionBox:\n                # Get label name in detection task and filter unused labels.\n                detection_name = category_to_detection_name(sample_annotation['category_name'])\n                # motion name mapping\n                if detection_name in motion_name_mapping:\n                    detection_name = motion_name_mapping[detection_name]\n\n                if detection_name is None:\n                    continue\n\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n\n                # get future trajs\n                instance_token = nusc.get('sample_annotation', sample_annotation['token'])['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample_token, \n                    seconds=seconds, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    _, boxes, _ = nusc.get_sample_data(sample['data']['LIDAR_TOP'], selected_anntokens=[sample_annotation['token']])\n                    box = boxes[0]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scence_centric = convert_local_coords_to_global(fut_traj_local, trans, rot) \n                else:\n                    fut_traj_scence_centric = np.zeros((0,))\n\n                sample_boxes.append(\n                    box_cls(\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        traj=fut_traj_scence_centric\n                    )\n                )\n            elif box_cls == TrackingBox:\n                # Use nuScenes token as tracking id.\n                tracking_id = sample_annotation['instance_token']\n                tracking_id_set.add(tracking_id)\n\n                # Get label name in detection task and filter unused labels.\n                # Import locally to avoid errors when motmetrics package is not installed.\n                from nuscenes.eval.tracking.utils import category_to_tracking_name\n                tracking_name = category_to_tracking_name(sample_annotation['category_name'])\n                if tracking_name is None:\n                    continue\n\n                sample_boxes.append(\n                    box_cls(\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        tracking_id=tracking_id,\n                        tracking_name=tracking_name,\n                        tracking_score=-1.0  # GT samples do not have a score.\n                    )\n                )\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\n\ndef accumulate(gt_boxes: EvalBoxes,\n               pred_boxes: EvalBoxes,\n               class_name: str,\n               dist_fcn: Callable,\n               dist_th: float,\n               verbose: bool = False) -> DetectionMetricData:\n    \"\"\"\n    Average Precision over predefined different recall thresholds for a single distance threshold.\n    The recall/conf thresholds and other raw metrics will be used in secondary metrics.\n    :param gt_boxes: Maps every sample_token to a list of its sample_annotations.\n    :param pred_boxes: Maps every sample_token to a list of its sample_results.\n    :param class_name: Class to compute AP on.\n    :param dist_fcn: Distance function used to match detections and ground truths.\n    :param dist_th: Distance threshold for a match.\n    :param verbose: If true, print debug messages.\n    :return: (average_prec, metrics). The average precision value and raw data for a number of metrics.\n    \"\"\"\n    # ---------------------------------------------\n    # Organize input and initialize accumulators.\n    # ---------------------------------------------\n\n    # Count the positives.\n    npos = len([1 for gt_box in gt_boxes.all if gt_box.detection_name == class_name])\n    if verbose:\n        print(\"Found {} GT of class {} out of {} total across {} samples.\".\n              format(npos, class_name, len(gt_boxes.all), len(gt_boxes.sample_tokens)))\n\n    # For missing classes in the GT, return a data structure corresponding to no predictions.\n    if npos == 0:\n        return DetectionMetricData.no_predictions(), 0\n\n    # Organize the predictions in a single list.\n    pred_boxes_list = [box for box in pred_boxes.all if box.detection_name == class_name]\n    pred_confs = [box.detection_score for box in pred_boxes_list]\n\n    if verbose:\n        print(\"Found {} PRED of class {} out of {} total across {} samples.\".\n              format(len(pred_confs), class_name, len(pred_boxes.all), len(pred_boxes.sample_tokens)))\n\n    # Sort by confidence.\n    sortind = [i for (v, i) in sorted((v, i) for (i, v) in enumerate(pred_confs))][::-1]\n\n    # Do the actual matching.\n    tp = []  # Accumulator of true positives.\n    fp = []  # Accumulator of false positives.\n    conf = []  # Accumulator of confidences.\n    hit = 0 # Accumulator of matched and hit\n\n    # match_data holds the extra metrics we calculate for each match.\n    match_data = {'conf': [],\n                  'min_ade': [],\n                  'min_fde': [],\n                  'miss_rate': []}\n\n    # ---------------------------------------------\n    # Match and accumulate match data.\n    # ---------------------------------------------\n\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th\n\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n\n            #  Update tp, fp and confs.\n            tp.append(1)\n            fp.append(0)\n            conf.append(pred_box.detection_score)\n\n            # Since it is a match, update match data also.\n            gt_box_match = gt_boxes[pred_box.sample_token][match_gt_idx]\n\n            match_data['conf'].append(pred_box.detection_score)\n\n            minade, minfde, mr = prediction_metrics(gt_box_match, pred_box)\n            match_data['min_ade'].append(minade)\n            match_data['min_fde'].append(minfde)\n            match_data['miss_rate'].append(mr)\n\n            if minfde < 2.0:\n                hit += 1\n\n        else:\n            # No match. Mark this as a false positive.\n            tp.append(0)\n            fp.append(1)\n            conf.append(pred_box.detection_score)\n\n    # Check if we have any matches. If not, just return a \"no predictions\" array.\n    if len(match_data['min_ade']) == 0:\n        return MotionMetricData.no_predictions()\n\n    # Accumulate.\n    N_tp = np.sum(tp)\n    N_fp = np.sum(fp)\n    tp = np.cumsum(tp).astype(float)\n    fp = np.cumsum(fp).astype(float)\n    conf = np.array(conf)\n\n    # Calculate precision and recall.\n    prec = tp / (fp + tp)\n    rec = tp / float(npos)\n\n    rec_interp = np.linspace(0, 1, DetectionMetricData.nelem)  # 101 steps, from 0% to 100% recall.\n    prec = np.interp(rec_interp, rec, prec, right=0)\n    conf = np.interp(rec_interp, rec, conf, right=0)\n    rec = rec_interp\n\n    # ---------------------------------------------\n    # Re-sample the match-data to match, prec, recall and conf.\n    # ---------------------------------------------\n\n    for key in match_data.keys():\n        if key == \"conf\":\n            continue  # Confidence is used as reference to align with fp and tp. So skip in this step.\n\n        else:\n            # For each match_data, we first calculate the accumulated mean.\n            tmp = cummean(np.array(match_data[key]))\n\n            # Then interpolate based on the confidences. (Note reversing since np.interp needs increasing arrays)\n            match_data[key] = np.interp(conf[::-1], match_data['conf'][::-1], tmp[::-1])[::-1]\n\n    EPA = (hit - 0.5 * N_fp) / npos\n\n    ## match based on traj\n    traj_matched = 0\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n                    fde_distance = traj_fde(gt_box, pred_box, final_step=12)\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th and fde_distance < 2.0\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n            traj_matched += 1\n    EPA_ = (traj_matched - 0.5 * N_fp) / npos  ## same as UniAD\n\n    # ---------------------------------------------\n    # Done. Instantiate MetricData and return\n    # ---------------------------------------------\n    return MotionMetricData(recall=rec,\n                               precision=prec,\n                               confidence=conf,\n                               min_ade_err=match_data['min_ade'],\n                               min_fde_err=match_data['min_fde'],\n                               miss_rate_err=match_data['miss_rate']), EPA, EPA_\n\n\ndef prediction_metrics(gt_box_match, pred_box, miss_thresh=2):\n    gt_traj = np.array(gt_box_match.traj)\n    pred_traj = np.array(pred_box.traj)\n\n    valid_step = gt_traj.shape[0]\n    if valid_step <= 0:\n        return 0, 0, 0\n\n    pred_traj_valid = pred_traj[:, :valid_step, :]\n    dist = np.linalg.norm(pred_traj_valid - gt_traj[np.newaxis], axis=2)\n\n    minade = dist.mean(axis=1).min()\n    minfde = dist[:, -1].min()\n    mr = dist.max(axis=1).min() > miss_thresh\n\n    return minade, minfde, mr\n\ndef traj_fde(gt_box, pred_box, final_step):\n    if gt_box.traj.shape[0] <= 0:\n        return np.inf\n    final_step = min(gt_box.traj.shape[0], final_step)\n    gt_final = gt_box.traj[None, final_step-1]\n    pred_final = np.array(pred_box.traj)[:,final_step-1,:]\n    err = gt_final - pred_final\n    err = np.sqrt(np.sum(np.square(gt_final - pred_final), axis=-1))\n    return np.min(err)\n\n\nclass MotionMetricDataList(DetectionMetricDataList):\n    \"\"\" This stores a set of MetricData in a dict indexed by (name, match-distance). \"\"\"\n    @classmethod\n    def deserialize(cls, content: dict):\n        mdl = cls()\n        for key, md in content.items():\n            name, distance = key.split(':')\n            mdl.set(name, float(distance), MotionMetricData.deserialize(md))\n        return mdl\n\nclass MotionMetricData(DetectionMetricData):\n    \"\"\" This class holds accumulated and interpolated data required to calculate the detection metrics. \"\"\"\n\n    nelem = 101\n\n    def __init__(self,\n                 recall: np.array,\n                 precision: np.array,\n                 confidence: np.array,\n                 min_ade_err: np.array,\n                 min_fde_err: np.array,\n                 miss_rate_err: np.array):\n\n        # Assert lengths.\n        assert len(recall) == self.nelem\n        assert len(precision) == self.nelem\n        assert len(confidence) == self.nelem\n        assert len(min_ade_err) == self.nelem\n        assert len(min_fde_err) == self.nelem\n        assert len(miss_rate_err) == self.nelem\n\n        # Assert ordering.\n        assert all(confidence == sorted(confidence, reverse=True))  # Confidences should be descending.\n        assert all(recall == sorted(recall))  # Recalls should be ascending.\n\n        # Set attributes explicitly to help IDEs figure out what is going on.\n        self.recall = recall\n        self.precision = precision\n        self.confidence = confidence\n        self.min_ade_err = min_ade_err\n        self.min_fde_err = min_fde_err\n        self.miss_rate_err = miss_rate_err\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.serialize().keys():\n            eq = eq and np.array_equal(getattr(self, key), getattr(other, key))\n        return eq\n\n    @property\n    def max_recall_ind(self):\n        \"\"\" Returns index of max recall achieved. \"\"\"\n\n        # Last instance of confidence > 0 is index of max achieved recall.\n        non_zero = np.nonzero(self.confidence)[0]\n        if len(non_zero) == 0:  # If there are no matches, all the confidence values will be zero.\n            max_recall_ind = 0\n        else:\n            max_recall_ind = non_zero[-1]\n\n        return max_recall_ind\n\n    @property\n    def max_recall(self):\n        \"\"\" Returns max recall achieved. \"\"\"\n\n        return self.recall[self.max_recall_ind]\n\n    def serialize(self):\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'recall': self.recall.tolist(),\n            'precision': self.precision.tolist(),\n            'confidence': self.confidence.tolist(),\n            'min_ade_err': self.min_ade_err.tolist(),\n            'min_fde_err': self.min_fde_err.tolist(),\n            'miss_rate_err': self.miss_rate_err.tolist(),\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(recall=np.array(content['recall']),\n                   precision=np.array(content['precision']),\n                   confidence=np.array(content['confidence']),\n                   min_ade_err=np.array(content['min_ade_err']),\n                   min_fde_err=np.array(content['min_fde_err']),\n                   miss_rate_err=np.array(content['miss_rate_err']))\n\n    @classmethod\n    def no_predictions(cls):\n        \"\"\" Returns a md instance corresponding to having no predictions. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.zeros(cls.nelem),\n                   confidence=np.zeros(cls.nelem),\n                   min_ade_err=np.ones(cls.nelem),\n                   min_fde_err=np.ones(cls.nelem),\n                   miss_rate_err=np.ones(cls.nelem))\n\n    @classmethod\n    def random_md(cls):\n        \"\"\" Returns an md instance corresponding to a random results. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.random.random(cls.nelem),\n                   confidence=np.linspace(0, 1, cls.nelem)[::-1],\n                   min_ade_err=np.random.random(cls.nelem),\n                   min_fde_err=np.random.random(cls.nelem),\n                   miss_rate_err=np.random.random(cls.nelem))\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/evaluation/planning/planning_eval.py",
    "content": "from tqdm import tqdm\nimport torch\nimport torch.nn as nn\nimport numpy as np\nfrom shapely.geometry import Polygon\n\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import build_dataset, build_dataloader\n\nfrom mmdet3d_plugin.datasets.utils import box3d_to_corners\n\n\ndef check_collision(ego_box, boxes):\n    '''\n        ego_box: tensor with shape [7], [x, y, z, w, l, h, yaw]\n        boxes: tensor with shape [N, 7]\n    '''\n    if  boxes.shape[0] == 0:\n        return False\n\n    # follow uniad, add a 0.5m offset\n    ego_box[0] += 0.5 * torch.cos(ego_box[6])\n    ego_box[1] += 0.5 * torch.sin(ego_box[6])\n    ego_corners_box = box3d_to_corners(ego_box.unsqueeze(0))[0, [0, 3, 7, 4], :2]\n    corners_box = box3d_to_corners(boxes)[:, [0, 3, 7, 4], :2]\n    ego_poly = Polygon([(point[0], point[1]) for point in ego_corners_box])\n    for i in range(len(corners_box)):\n        box_poly =  Polygon([(point[0], point[1]) for point in corners_box[i]])\n        collision = ego_poly.intersects(box_poly)\n        if collision:\n            return True\n\n    return False\n\ndef get_yaw(traj):\n    start = traj[0]\n    end = traj[-1]\n    dist = torch.linalg.norm(end - start, dim=-1)\n    if dist < 0.5:\n        return traj.new_ones(traj.shape[0]) * np.pi / 2\n\n    zeros = traj.new_zeros((1, 2))\n    traj_cat = torch.cat([zeros, traj], dim=0)\n    yaw = traj.new_zeros(traj.shape[0]+1)\n    yaw[..., 1:-1] = torch.atan2(\n        traj_cat[..., 2:, 1] - traj_cat[..., :-2, 1],\n        traj_cat[..., 2:, 0] - traj_cat[..., :-2, 0],\n    )\n    yaw[..., -1] = torch.atan2(\n        traj_cat[..., -1, 1] - traj_cat[..., -2, 1],\n        traj_cat[..., -1, 0] - traj_cat[..., -2, 0],\n    )\n    return yaw[1:]\n\nclass PlanningMetric():\n    def __init__(\n        self,\n        n_future=6,\n        compute_on_step: bool = False,\n    ):\n        self.W = 1.85\n        self.H = 4.084\n\n        self.n_future = n_future\n        self.reset()\n\n    def reset(self):\n        self.obj_col = torch.zeros(self.n_future)\n        self.obj_box_col = torch.zeros(self.n_future)\n        self.L2 = torch.zeros(self.n_future)\n        self.total = torch.tensor(0)\n\n    def evaluate_single_coll(self, traj, fut_boxes):\n        n_future = traj.shape[0]\n        yaw = get_yaw(traj)\n        ego_box = traj.new_zeros((n_future, 7))\n        ego_box[:, :2] = traj\n        ego_box[:, 3:6] = ego_box.new_tensor([self.H, self.W, 1.56])\n        ego_box[:, 6] = yaw\n        collision = torch.zeros(n_future, dtype=torch.bool)\n\n        for t in range(n_future):\n            ego_box_t = ego_box[t].clone()\n            boxes = fut_boxes[t][0].clone()\n            collision[t] = check_collision(ego_box_t, boxes)\n        return collision\n\n    def evaluate_coll(self, trajs, gt_trajs, fut_boxes):\n        B, n_future, _ = trajs.shape\n        trajs = trajs * torch.tensor([-1, 1], device=trajs.device)\n        gt_trajs = gt_trajs * torch.tensor([-1, 1], device=gt_trajs.device)\n\n        obj_coll_sum = torch.zeros(n_future, device=trajs.device)\n        obj_box_coll_sum = torch.zeros(n_future, device=trajs.device)\n\n        assert B == 1, 'only supprt bs=1'\n        for i in range(B):\n            gt_box_coll = self.evaluate_single_coll(gt_trajs[i], fut_boxes)\n            box_coll = self.evaluate_single_coll(trajs[i], fut_boxes)\n            box_coll = torch.logical_and(box_coll, torch.logical_not(gt_box_coll))\n            \n            obj_coll_sum += gt_box_coll.long()\n            obj_box_coll_sum += box_coll.long()\n\n        return obj_coll_sum, obj_box_coll_sum\n\n    def compute_L2(self, trajs, gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n        return torch.sqrt((((trajs[:, :, :2] - gt_trajs[:, :, :2]) ** 2) * gt_trajs_mask).sum(dim=-1)) \n\n    def update(self, trajs, gt_trajs, gt_trajs_mask, fut_boxes):\n        assert trajs.shape == gt_trajs.shape\n        trajs[..., 0] = - trajs[..., 0]\n        gt_trajs[..., 0] = - gt_trajs[..., 0]\n        L2 = self.compute_L2(trajs, gt_trajs, gt_trajs_mask)\n        # obj_coll_sum, obj_box_coll_sum = self.evaluate_coll(trajs[:,:,:2], gt_trajs[:,:,:2], fut_boxes)\n\n        # self.obj_col += obj_coll_sum\n        # self.obj_box_col += obj_box_coll_sum\n        self.L2 += L2.sum(dim=0)\n        self.total +=len(trajs)\n\n    def compute(self):\n        return {\n            'obj_col': self.obj_col / self.total,\n            'obj_box_col': self.obj_box_col / self.total,\n            'L2' : self.L2 / self.total\n        }\n\n\ndef planning_eval(results, eval_config, logger):\n    dataset = build_dataset(eval_config)\n    dataloader = build_dataloader(\n            dataset, samples_per_gpu=1, workers_per_gpu=1, shuffle=False, dist=False)\n    planning_metrics = PlanningMetric()\n    for i, data in enumerate(tqdm(dataloader)):\n        sdc_planning = data['gt_ego_fut_trajs'].cumsum(dim=-2).unsqueeze(1)\n        sdc_planning_mask = data['gt_ego_fut_masks'].unsqueeze(-1).repeat(1, 1, 2).unsqueeze(1)\n        command = data['gt_ego_fut_cmd'].argmax(dim=-1).item()\n        # fut_boxes = data['fut_boxes']\n        fut_boxes = None\n        if not sdc_planning_mask.all(): ## for incomplete gt, we do not count this sample\n            continue\n        res = results[i]\n        pred_sdc_traj = res['img_bbox']['final_planning'].unsqueeze(0)\n        planning_metrics.update(pred_sdc_traj[:, :6, :2], sdc_planning[0,:, :6, :2], sdc_planning_mask[0,:, :6, :2], fut_boxes)\n       \n    planning_results = planning_metrics.compute()\n    planning_metrics.reset()\n    from prettytable import PrettyTable\n    planning_tab = PrettyTable()\n    metric_dict = {}\n\n    planning_tab.field_names = [\n    \"metrics\", \"0.5s\", \"1.0s\", \"1.5s\", \"2.0s\", \"2.5s\", \"3.0s\", \"avg\"]\n    for key in planning_results.keys():\n        value = planning_results[key].tolist()\n        new_values = []\n        for i in range(len(value)):\n            new_values.append(np.array(value[:i+1]).mean())\n        value = new_values\n        avg = [value[1], value[3], value[5]]\n        avg = sum(avg) / len(avg)\n        value.append(avg)\n        metric_dict[key] = avg\n        row_value = []\n        row_value.append(key)\n        for i in range(len(value)):\n            if 'col' in key:\n                row_value.append('%.3f' % float(value[i]*100) + '%')\n            else:\n                row_value.append('%.4f' % float(value[i]))\n        planning_tab.add_row(row_value)\n\n    print_log('\\n'+str(planning_tab), logger=logger)\n    return metric_dict\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/map_utils/nuscmap_extractor.py",
    "content": "from shapely.geometry import LineString, box, Polygon\nfrom shapely import ops, strtree\n\nimport numpy as np\nfrom nuscenes.map_expansion.map_api import NuScenesMap, NuScenesMapExplorer\nfrom nuscenes.eval.common.utils import quaternion_yaw\nfrom pyquaternion import Quaternion\nfrom .utils import split_collections, get_drivable_area_contour, \\\n        get_ped_crossing_contour\nfrom numpy.typing import NDArray\nfrom typing import Dict, List, Tuple, Union\n\nclass NuscMapExtractor(object):\n    \"\"\"NuScenes map ground-truth extractor.\n\n    Args:\n        data_root (str): path to nuScenes dataset\n        roi_size (tuple or list): bev range\n    \"\"\"\n    def __init__(self, data_root: str, roi_size: Union[List, Tuple]) -> None:\n        self.roi_size = roi_size\n        self.MAPS = ['boston-seaport', 'singapore-hollandvillage',\n                     'singapore-onenorth', 'singapore-queenstown']\n        \n        self.nusc_maps = {}\n        self.map_explorer = {}\n        for loc in self.MAPS:\n            self.nusc_maps[loc] = NuScenesMap(\n                dataroot=data_root, map_name=loc)\n            self.map_explorer[loc] = NuScenesMapExplorer(self.nusc_maps[loc])\n        \n        # local patch in nuScenes format\n        self.local_patch = box(-roi_size[0] / 2, -roi_size[1] / 2, \n                roi_size[0] / 2, roi_size[1] / 2)\n    \n    def _union_ped(self, ped_geoms: List[Polygon]) -> List[Polygon]:\n        ''' merge close ped crossings.\n        \n        Args:\n            ped_geoms (list): list of Polygon\n        \n        Returns:\n            union_ped_geoms (Dict): merged ped crossings \n        '''\n\n        def get_rec_direction(geom):\n            rect = geom.minimum_rotated_rectangle\n            rect_v_p = np.array(rect.exterior.coords)[:3]\n            rect_v = rect_v_p[1:]-rect_v_p[:-1]\n            v_len = np.linalg.norm(rect_v, axis=-1)\n            longest_v_i = v_len.argmax()\n\n            return rect_v[longest_v_i], v_len[longest_v_i]\n\n        tree = strtree.STRtree(ped_geoms)\n        index_by_id = dict((id(pt), i) for i, pt in enumerate(ped_geoms))\n\n        final_pgeom = []\n        remain_idx = [i for i in range(len(ped_geoms))]\n        for i, pgeom in enumerate(ped_geoms):\n\n            if i not in remain_idx:\n                continue\n            # update\n            remain_idx.pop(remain_idx.index(i))\n            pgeom_v, pgeom_v_norm = get_rec_direction(pgeom)\n            final_pgeom.append(pgeom)\n\n            for o in tree.query(pgeom):\n                o_idx = index_by_id[id(o)]\n                if o_idx not in remain_idx:\n                    continue\n\n                o_v, o_v_norm = get_rec_direction(o)\n                cos = pgeom_v.dot(o_v)/(pgeom_v_norm*o_v_norm)\n                if 1 - np.abs(cos) < 0.01:  # theta < 8 degrees.\n                    final_pgeom[-1] =\\\n                        final_pgeom[-1].union(o)\n                    # update\n                    remain_idx.pop(remain_idx.index(o_idx))\n\n        results = []\n        for p in final_pgeom:\n            results.extend(split_collections(p))\n        return results\n        \n    def get_map_geom(self, \n                     location: str, \n                     translation: Union[List, NDArray],\n                     rotation: Union[List, NDArray]) -> Dict[str, List[Union[LineString, Polygon]]]:\n        ''' Extract geometries given `location` and self pose, self may be lidar or ego.\n        \n        Args:\n            location (str): city name\n            translation (array): self2global translation, shape (3,)\n            rotation (array): self2global quaternion, shape (4, )\n            \n        Returns:\n            geometries (Dict): extracted geometries by category.\n        '''\n\n        # (center_x, center_y, len_y, len_x) in nuscenes format\n        patch_box = (translation[0], translation[1], \n                self.roi_size[1], self.roi_size[0])\n        rotation = Quaternion(rotation)\n        yaw = quaternion_yaw(rotation) / np.pi * 180\n\n        # get dividers\n        lane_dividers = self.map_explorer[location]._get_layer_line(\n                    patch_box, yaw, 'lane_divider')\n        \n        road_dividers = self.map_explorer[location]._get_layer_line(\n                    patch_box, yaw, 'road_divider')\n        \n        all_dividers = []\n        for line in lane_dividers + road_dividers:\n            all_dividers += split_collections(line)\n\n        # get ped crossings\n        ped_crossings = []\n        ped = self.map_explorer[location]._get_layer_polygon(\n                    patch_box, yaw, 'ped_crossing')\n        \n        for p in ped:\n            ped_crossings += split_collections(p)\n        # some ped crossings are split into several small parts\n        # we need to merge them\n        ped_crossings = self._union_ped(ped_crossings)\n        \n        ped_crossing_lines = []\n        for p in ped_crossings:\n            # extract exteriors to get a closed polyline\n            line = get_ped_crossing_contour(p, self.local_patch)\n            if line is not None:\n                ped_crossing_lines.append(line)\n\n        # get boundaries\n        # we take the union of road segments and lanes as drivable areas\n        # we don't take drivable area layer in nuScenes since its definition may be ambiguous\n        road_segments = self.map_explorer[location]._get_layer_polygon(\n                    patch_box, yaw, 'road_segment')\n        lanes = self.map_explorer[location]._get_layer_polygon(\n                    patch_box, yaw, 'lane')\n        union_roads = ops.unary_union(road_segments)\n        union_lanes = ops.unary_union(lanes)\n        drivable_areas = ops.unary_union([union_roads, union_lanes])\n        \n        drivable_areas = split_collections(drivable_areas)\n        \n        # boundaries are defined as the contour of drivable areas\n        boundaries = get_drivable_area_contour(drivable_areas, self.roi_size)\n\n        return dict(\n            divider=all_dividers, # List[LineString]\n            ped_crossing=ped_crossing_lines, # List[LineString]\n            boundary=boundaries, # List[LineString]\n            drivable_area=drivable_areas, # List[Polygon],\n        )\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/map_utils/utils.py",
    "content": "from shapely.geometry import LineString, box, Polygon, LinearRing\nfrom shapely.geometry.base import BaseGeometry\nfrom shapely import ops\nimport numpy as np\nfrom scipy.spatial import distance\nfrom typing import List, Optional, Tuple\nfrom numpy.typing import NDArray\n\ndef split_collections(geom: BaseGeometry) -> List[Optional[BaseGeometry]]:\n    ''' Split Multi-geoms to list and check is valid or is empty.\n        \n    Args:\n        geom (BaseGeometry): geoms to be split or validate.\n    \n    Returns:\n        geometries (List): list of geometries.\n    '''\n    assert geom.geom_type in ['MultiLineString', 'LineString', 'MultiPolygon', \n        'Polygon', 'GeometryCollection'], f\"got geom type {geom.geom_type}\"\n    if 'Multi' in geom.geom_type:\n        outs = []\n        for g in geom.geoms:\n            if g.is_valid and not g.is_empty:\n                outs.append(g)\n        return outs\n    else:\n        if geom.is_valid and not geom.is_empty:\n            return [geom,]\n        else:\n            return []\n\ndef get_drivable_area_contour(drivable_areas: List[Polygon], \n                              roi_size: Tuple) -> List[LineString]:\n    ''' Extract drivable area contours to get list of boundaries.\n\n    Args:\n        drivable_areas (list): list of drivable areas.\n        roi_size (tuple): bev range size\n    \n    Returns:\n        boundaries (List): list of boundaries.\n    '''\n    max_x = roi_size[0] / 2\n    max_y = roi_size[1] / 2\n\n    # a bit smaller than roi to avoid unexpected boundaries on edges\n    local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n    \n    exteriors = []\n    interiors = []\n    \n    for poly in drivable_areas:\n        exteriors.append(poly.exterior)\n        for inter in poly.interiors:\n            interiors.append(inter)\n    \n    results = []\n    for ext in exteriors:\n        # NOTE: we make sure all exteriors are clock-wise\n        # such that each boundary's right-hand-side is drivable area\n        # and left-hand-side is walk way\n        \n        if ext.is_ccw:\n            ext = LinearRing(list(ext.coords)[::-1])\n        lines = ext.intersection(local_patch)\n        if lines.geom_type == 'MultiLineString':\n            lines = ops.linemerge(lines)\n        assert lines.geom_type in ['MultiLineString', 'LineString']\n        \n        results.extend(split_collections(lines))\n\n    for inter in interiors:\n        # NOTE: we make sure all interiors are counter-clock-wise\n        if not inter.is_ccw:\n            inter = LinearRing(list(inter.coords)[::-1])\n        lines = inter.intersection(local_patch)\n        if lines.geom_type == 'MultiLineString':\n            lines = ops.linemerge(lines)\n        assert lines.geom_type in ['MultiLineString', 'LineString']\n        \n        results.extend(split_collections(lines))\n\n    return results\n\ndef get_ped_crossing_contour(polygon: Polygon, \n                             local_patch: box) -> Optional[LineString]:\n    ''' Extract ped crossing contours to get a closed polyline.\n    Different from `get_drivable_area_contour`, this function ensures a closed polyline.\n\n    Args:\n        polygon (Polygon): ped crossing polygon to be extracted.\n        local_patch (tuple): local patch params\n    \n    Returns:\n        line (LineString): a closed line\n    '''\n\n    ext = polygon.exterior\n    if not ext.is_ccw:\n        ext = LinearRing(list(ext.coords)[::-1])\n    lines = ext.intersection(local_patch)\n    if lines.type != 'LineString':\n        # remove points in intersection results\n        lines = [l for l in lines.geoms if l.geom_type != 'Point']\n        lines = ops.linemerge(lines)\n        \n        # same instance but not connected.\n        if lines.type != 'LineString':\n            ls = []\n            for l in lines.geoms:\n                ls.append(np.array(l.coords))\n            \n            lines = np.concatenate(ls, axis=0)\n            lines = LineString(lines)\n    if not lines.is_empty:\n        return lines\n    \n    return None\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/nuscenes_3d_dataset.py",
    "content": "import random\nimport math\nimport os\nfrom os import path as osp\nimport cv2\nimport tempfile\nimport copy\nimport prettytable\n\nimport numpy as np\nimport torch\nfrom torch.utils.data import Dataset\nimport pyquaternion\nfrom shapely.geometry import LineString\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.eval.detection.config import config_factory as det_configs\nfrom nuscenes.eval.common.config import config_factory as track_configs\n\nimport mmcv\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.pipelines import Compose\nfrom .utils import (\n    draw_lidar_bbox3d_on_img,\n    draw_lidar_bbox3d_on_bev,\n)\n\n\n@DATASETS.register_module()\nclass NuScenes3DDataset(Dataset):\n    DefaultAttribute = {\n        \"car\": \"vehicle.parked\",\n        \"pedestrian\": \"pedestrian.moving\",\n        \"trailer\": \"vehicle.parked\",\n        \"truck\": \"vehicle.parked\",\n        \"bus\": \"vehicle.moving\",\n        \"motorcycle\": \"cycle.without_rider\",\n        \"construction_vehicle\": \"vehicle.parked\",\n        \"bicycle\": \"cycle.without_rider\",\n        \"barrier\": \"\",\n        \"traffic_cone\": \"\",\n    }\n    ErrNameMapping = {\n        \"trans_err\": \"mATE\",\n        \"scale_err\": \"mASE\",\n        \"orient_err\": \"mAOE\",\n        \"vel_err\": \"mAVE\",\n        \"attr_err\": \"mAAE\",\n    }\n    CLASSES = (\n        \"car\",\n        \"truck\",\n        \"trailer\",\n        \"bus\",\n        \"construction_vehicle\",\n        \"bicycle\",\n        \"motorcycle\",\n        \"pedestrian\",\n        \"traffic_cone\",\n        \"barrier\",\n    )\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    ID_COLOR_MAP = [\n        (59, 59, 238),\n        (0, 255, 0),\n        (0, 0, 255),\n        (255, 255, 0),\n        (0, 255, 255),\n        (255, 0, 255),\n        (255, 255, 255),\n        (0, 127, 255),\n        (71, 130, 255),\n        (127, 127, 0),\n    ]\n\n    def __init__(\n        self,\n        ann_file,\n        pipeline=None,\n        data_root=None,\n        classes=None,\n        map_classes=None,\n        load_interval=1,\n        with_velocity=True,\n        modality=None,\n        test_mode=False,\n        det3d_eval_version=\"detection_cvpr_2019\",\n        track3d_eval_version=\"tracking_nips_2019\",\n        version=\"v1.0-trainval\",\n        use_valid_flag=False,\n        vis_score_threshold=0.25,\n        data_aug_conf=None,\n        sequences_split_num=1,\n        with_seq_flag=False,\n        keep_consistent_seq_aug=True,\n        work_dir=None,\n        eval_config=None,\n        use_generated_img=False,\n        generated_img_root=None,\n    ):\n        self.version = version\n        self.load_interval = load_interval\n        self.use_valid_flag = use_valid_flag\n        super().__init__()\n        self.data_root = data_root\n        self.ann_file = ann_file\n        self.test_mode = test_mode\n        self.modality = modality\n        self.box_mode_3d = 0\n\n        if classes is not None:\n            self.CLASSES = classes\n        if map_classes is not None: \n            self.MAP_CLASSES = map_classes\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if pipeline is not None:\n            self.pipeline = Compose(pipeline)\n\n        self.with_velocity = with_velocity\n        self.det3d_eval_version = det3d_eval_version\n        self.det3d_eval_configs = det_configs(self.det3d_eval_version)\n        self.det3d_eval_configs.class_names = list(self.det3d_eval_configs.class_range.keys())\n        self.track3d_eval_version = track3d_eval_version\n        self.track3d_eval_configs = track_configs(self.track3d_eval_version)\n        self.track3d_eval_configs.class_names = list(self.track3d_eval_configs.class_range.keys())\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n        self.vis_score_threshold = vis_score_threshold\n\n        self.data_aug_conf = data_aug_conf\n        self.sequences_split_num = sequences_split_num\n        self.keep_consistent_seq_aug = keep_consistent_seq_aug\n        if with_seq_flag:\n            self._set_sequence_group_flag()\n        \n        self.work_dir = work_dir\n        self.eval_config = eval_config\n\n        self.use_generated_img = use_generated_img\n        self.generated_img_root = generated_img_root\n\n    def __len__(self):\n        return len(self.data_infos)\n\n    def _set_sequence_group_flag(self):\n        \"\"\"\n        Set each sequence to be a different group\n        \"\"\"\n        if self.sequences_split_num == -1:\n            self.flag = np.arange(len(self.data_infos))\n            return\n        \n        res = []\n\n        curr_sequence = 0\n        for idx in range(len(self.data_infos)):\n            if idx != 0 and len(self.data_infos[idx][\"sweeps\"]) == 0:\n                # Not first frame and # of sweeps is 0 -> new sequence\n                curr_sequence += 1\n            res.append(curr_sequence)\n\n        self.flag = np.array(res, dtype=np.int64)\n\n        if self.sequences_split_num != 1:\n            if self.sequences_split_num == \"all\":\n                self.flag = np.array(\n                    range(len(self.data_infos)), dtype=np.int64\n                )\n            else:\n                bin_counts = np.bincount(self.flag)\n                new_flags = []\n                curr_new_flag = 0\n                for curr_flag in range(len(bin_counts)):\n                    curr_sequence_length = np.array(\n                        list(\n                            range(\n                                0,\n                                bin_counts[curr_flag],\n                                math.ceil(\n                                    bin_counts[curr_flag]\n                                    / self.sequences_split_num\n                                ),\n                            )\n                        )\n                        + [bin_counts[curr_flag]]\n                    )\n\n                    for sub_seq_idx in (\n                        curr_sequence_length[1:] - curr_sequence_length[:-1]\n                    ):\n                        for _ in range(sub_seq_idx):\n                            new_flags.append(curr_new_flag)\n                        curr_new_flag += 1\n\n                assert len(new_flags) == len(self.flag)\n                assert (\n                    len(np.bincount(new_flags))\n                    == len(np.bincount(self.flag)) * self.sequences_split_num\n                )\n                self.flag = np.array(new_flags, dtype=np.int64)\n\n    def get_augmentation(self):\n        if self.data_aug_conf is None:\n            return None\n        H, W = self.data_aug_conf[\"H\"], self.data_aug_conf[\"W\"]\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        if not self.test_mode:\n            resize = np.random.uniform(*self.data_aug_conf[\"resize_lim\"])\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int(\n                    (1 - np.random.uniform(*self.data_aug_conf[\"bot_pct_lim\"]))\n                    * newH\n                )\n                - fH\n            )\n            crop_w = int(np.random.uniform(0, max(0, newW - fW)))\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            if self.data_aug_conf[\"rand_flip\"] and np.random.choice([0, 1]):\n                flip = True\n            rotate = np.random.uniform(*self.data_aug_conf[\"rot_lim\"])\n            rotate_3d = np.random.uniform(*self.data_aug_conf[\"rot3d_range\"])\n        else:\n            resize = max(fH / H, fW / W)\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n                - fH\n            )\n            crop_w = int(max(0, newW - fW) / 2)\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            rotate = 0\n            rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def __getitem__(self, idx):\n        if isinstance(idx, dict):\n            aug_config = idx[\"aug_config\"]\n            idx = idx[\"idx\"]\n        else:\n            aug_config = self.get_augmentation()\n        data = self.get_data_info(idx)\n        data[\"aug_config\"] = aug_config\n        data = self.pipeline(data)\n        return data\n\n    def get_cat_ids(self, idx):\n        info = self.data_infos[idx]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n            gt_names = set(info[\"gt_names\"][mask])\n        else:\n            gt_names = set(info[\"gt_names\"])\n\n        cat_ids = []\n        for name in gt_names:\n            if name in self.CLASSES:\n                cat_ids.append(self.cat2id[name])\n        return cat_ids\n\n    def load_annotations(self, ann_file):\n        data = mmcv.load(ann_file, file_format=\"pkl\")\n        data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\n        data_infos = data_infos[:: self.load_interval]\n        self.metadata = data[\"metadata\"]\n        self.version = self.metadata[\"version\"]\n        print(self.metadata)\n        return data_infos\n    \n    def anno2geom(self, annos):\n        map_geoms = {}\n        for label, anno_list in annos.items():\n            map_geoms[label] = []\n            for anno in anno_list:\n                geom = LineString(anno)\n                map_geoms[label].append(geom)\n        return map_geoms\n    \n    def get_data_info(self, index):\n        info = self.data_infos[index]\n        input_dict = dict(\n            token=info[\"token\"],\n            map_location=info[\"map_location\"],\n            pts_filename=info[\"lidar_path\"],\n            sweeps=info[\"sweeps\"],\n            timestamp=info[\"timestamp\"] / 1e6,\n            lidar2ego_translation=info[\"lidar2ego_translation\"],\n            lidar2ego_rotation=info[\"lidar2ego_rotation\"],\n            ego2global_translation=info[\"ego2global_translation\"],\n            ego2global_rotation=info[\"ego2global_rotation\"],\n            ego_status=info['ego_status'].astype(np.float32),\n            map_infos=info[\"map_annos\"],\n        )\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = pyquaternion.Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = pyquaternion.Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        input_dict[\"lidar2global\"] = ego2global @ lidar2ego\n\n        map_geoms = self.anno2geom(info[\"map_annos\"])\n        input_dict[\"map_geoms\"] = map_geoms\n\n        if self.modality[\"use_camera\"]:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsic = []\n            for cam_type, cam_info in info[\"cams\"].items():\n                image_paths.append(cam_info[\"data_path\"])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info[\"sensor2lidar_rotation\"])\n                lidar2cam_t = (\n                    cam_info[\"sensor2lidar_translation\"] @ lidar2cam_r.T\n                )\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = copy.deepcopy(cam_info[\"cam_intrinsic\"])\n                cam_intrinsic.append(intrinsic)\n                viewpad = np.eye(4)\n                viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = viewpad @ lidar2cam_rt.T\n                lidar2img_rts.append(lidar2img_rt)\n                lidar2cam_rts.append(lidar2cam_rt)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    lidar2cam=lidar2cam_rts,\n                    cam_intrinsic=cam_intrinsic,\n                )\n            )\n\n        annos = self.get_ann_info(index)\n        input_dict.update(annos)\n\n        ## load generated image\n        if self.use_generated_img and self.generated_img_root != None:\n            input_dict[\"img_filename\"] = [\n                osp.join(self.generated_img_root, f\"img_{str(index).zfill(4)}_{cam}.jpg\")\n                    for cam in range(len(input_dict['cam_intrinsic']))\n            ]\n        return input_dict\n\n    def get_ann_info(self, index):\n        info = self.data_infos[index]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n        else:\n            mask = info[\"num_lidar_pts\"] > 0\n        gt_bboxes_3d = info[\"gt_boxes\"][mask]\n        gt_names_3d = info[\"gt_names\"][mask]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info[\"gt_velocity\"][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n        )\n        if \"instance_inds\" in info:\n            instance_inds = np.array(info[\"instance_inds\"], dtype=np.int)[mask]\n            anns_results[\"instance_inds\"] = instance_inds\n            \n        if 'gt_agent_fut_trajs' in info:\n            anns_results['gt_agent_fut_trajs'] = info['gt_agent_fut_trajs'][mask]\n            anns_results['gt_agent_fut_masks'] = info['gt_agent_fut_masks'][mask]\n\n        if 'gt_ego_fut_trajs' in info:\n            anns_results['gt_ego_fut_trajs'] = info['gt_ego_fut_trajs']\n            anns_results['gt_ego_fut_masks'] = info['gt_ego_fut_masks']\n            anns_results['gt_ego_fut_cmd'] = info['gt_ego_fut_cmd']\n        \n            ## get future box for planning eval\n            fut_ts = int(info['gt_ego_fut_masks'].sum())\n            fut_boxes = []\n            cur_scene_token = info[\"scene_token\"]\n            cur_T_global = get_T_global(info)\n            for i in range(1, fut_ts + 1):\n                fut_info = self.data_infos[index + i]\n                fut_scene_token = fut_info[\"scene_token\"]\n                if cur_scene_token != fut_scene_token:\n                    break\n                if self.use_valid_flag:\n                    mask = fut_info[\"valid_flag\"]\n                else:\n                    mask = fut_info[\"num_lidar_pts\"] > 0\n\n                fut_gt_bboxes_3d = fut_info[\"gt_boxes\"][mask]\n                \n                fut_T_global = get_T_global(fut_info)\n                T_fut2cur = np.linalg.inv(cur_T_global) @ fut_T_global\n\n                center = fut_gt_bboxes_3d[:, :3] @ T_fut2cur[:3, :3].T + T_fut2cur[:3, 3]\n                yaw = np.stack([np.cos(fut_gt_bboxes_3d[:, 6]), np.sin(fut_gt_bboxes_3d[:, 6])], axis=-1)\n                yaw = yaw @ T_fut2cur[:2, :2].T\n                yaw = np.arctan2(yaw[..., 1], yaw[..., 0])\n\n                fut_gt_bboxes_3d[:, :3] = center\n                fut_gt_bboxes_3d[:, 6] = yaw\n                fut_boxes.append(fut_gt_bboxes_3d)\n\n            anns_results['fut_boxes'] = fut_boxes\n        \n        return anns_results\n\n    def _format_bbox(self, results, jsonfile_prefix=None, tracking=False):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det, threshold=self.tracking_threshold if tracking else None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n            )\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, \"results_nusc.json\")\n        print(\"Results writes to\", res_path)\n        mmcv.dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(\n        self, result_path, logger=None, result_name=\"img_bbox\", tracking=False\n    ):\n        from nuscenes import NuScenes\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False\n        )\n        eval_set_map = {\n            \"v1.0-mini\": \"mini_val\",\n            \"v1.0-trainval\": \"val\",\n        }\n        if not tracking:\n            from nuscenes.eval.detection.evaluate import NuScenesEval\n\n            nusc_eval = NuScenesEval(\n                nusc,\n                config=self.det3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n            )\n            nusc_eval.main(render_curves=False)\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            for name in self.CLASSES:\n                for k, v in metrics[\"label_aps\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}_AP_dist_{}\".format(metric_prefix, name, k)\n                    ] = val\n                for k, v in metrics[\"label_tp_errors\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\"{}/{}_{}\".format(metric_prefix, name, k)] = val\n                for k, v in metrics[\"tp_errors\"].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}\".format(metric_prefix, self.ErrNameMapping[k])\n                    ] = val\n\n            detail[\"{}/NDS\".format(metric_prefix)] = metrics[\"nd_score\"]\n            detail[\"{}/mAP\".format(metric_prefix)] = metrics[\"mean_ap\"]\n        else:\n            from nuscenes.eval.tracking.evaluate import TrackingEval\n\n            nusc_eval = TrackingEval(\n                config=self.track3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n                nusc_version=self.version,\n                nusc_dataroot=self.data_root,\n            )\n            metrics = nusc_eval.main()\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            print(metrics)\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            keys = [\n                \"amota\",\n                \"amotp\",\n                \"recall\",\n                \"motar\",\n                \"gt\",\n                \"mota\",\n                \"motp\",\n                \"mt\",\n                \"ml\",\n                \"faf\",\n                \"tp\",\n                \"fp\",\n                \"fn\",\n                \"ids\",\n                \"frag\",\n                \"tid\",\n                \"lgd\",\n            ]\n            for key in keys:\n                detail[\"{}/{}\".format(metric_prefix, key)] = metrics[key]\n\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None, tracking=False):\n        assert isinstance(results, list), \"results must be a list\"\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, \"results\")\n        else:\n            tmp_dir = None\n\n        if not (\"pts_bbox\" in results[0] or \"img_bbox\" in results[0]):\n            result_files = self._format_bbox(\n                results, jsonfile_prefix, tracking=tracking\n            )\n        else:\n            result_files = dict()\n            for name in results[0]:\n                print(f\"\\nFormating bboxes of {name}\")\n                results_ = [out[name] for out in results]\n                tmp_file_ = jsonfile_prefix\n                result_files.update(\n                    {\n                        name: self._format_bbox(\n                            results_, tmp_file_, tracking=tracking\n                        )\n                    }\n                )\n        return result_files, tmp_dir\n\n    def format_map_results(self, results, prefix=None):\n        submissions = {'results': {},}\n        \n        for j, pred in enumerate(results):\n            '''\n            For each case, the result should be formatted as Dict{'vectors': [], 'scores': [], 'labels': []}\n            'vectors': List of vector, each vector is a array([[x1, y1], [x2, y2] ...]),\n                contain all vectors predicted in this sample.\n            'scores: List of score(float), \n                contain scores of all instances in this sample.\n            'labels': List of label(int), \n                contain labels of all instances in this sample.\n            '''\n            if pred is None: # empty prediction\n                continue\n            pred = pred['img_bbox']\n\n            single_case = {'vectors': [], 'scores': [], 'labels': []}\n            token = self.data_infos[j]['token']\n            for i in range(len(pred['scores'])):\n                score = pred['scores'][i]\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n\n                # A line should have >=2 points\n                if len(vector) < 2:\n                    continue\n                \n                single_case['vectors'].append(vector)\n                single_case['scores'].append(score)\n                single_case['labels'].append(label)\n            \n            submissions['results'][token] = single_case\n        \n        out_path = osp.join(prefix, 'submission_vector.json')\n        print(f'saving submissions results to {out_path}')\n        os.makedirs(os.path.dirname(out_path), exist_ok=True)\n        mmcv.dump(submissions, out_path)\n        return out_path\n\n    def format_motion_results(self, results, jsonfile_prefix=None, tracking=False, thresh=None):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det['img_bbox'], threshold=None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n                filter_with_cls_range=False,\n            )\n            for i, box in enumerate(boxes):\n                if thresh is not None and box.score < thresh:\n                    continue\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n                nusc_anno.update(\n                    dict(\n                        trajs=det['img_bbox']['trajs_3d'][i].numpy(),\n                    )\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        return nusc_submissions \n\n    def _evaluate_single_motion(self,\n                         results,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        from .evaluation.motion.motion_eval_uniad import NuScenesEval as NuScenesEvalMotion\n\n        output_dir = result_path\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        nusc_eval = NuScenesEvalMotion(\n            nusc,\n            config=copy.deepcopy(self.det3d_eval_configs),\n            result_path=results,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False,\n            seconds=6)\n        metrics = nusc_eval.main(render_curves=False)\n        \n        MOTION_METRICS = ['EPA', 'min_ade_err', 'min_fde_err', 'miss_rate_err']\n        class_names = ['car', 'pedestrian']\n\n        table = prettytable.PrettyTable()\n        table.field_names = [\"class names\"] + MOTION_METRICS\n        for class_name in class_names:\n            row_data = [class_name]\n            for m in MOTION_METRICS:\n                row_data.append('%.4f' % metrics[f'{class_name}_{m}'])\n            table.add_row(row_data)\n        print_log('\\n'+str(table), logger=logger)\n        return metrics\n\n    def evaluate(\n        self,\n        results,\n        eval_mode,\n        metric=None,\n        logger=None,\n        jsonfile_prefix=None,\n        result_names=[\"img_bbox\"],\n        show=False,\n        out_dir=None,\n        pipeline=None,\n    ):\n        res_path = \"results.pkl\" if \"trainval\" in self.version else \"results_mini.pkl\"\n        res_path = osp.join(self.work_dir, res_path)\n        print('All Results write to', res_path)\n        mmcv.dump(results, res_path)\n\n        results_dict = dict()\n        if eval_mode['with_det']:\n            self.tracking = eval_mode[\"with_tracking\"]\n            self.tracking_threshold = eval_mode[\"tracking_threshold\"]\n            for metric in [\"detection\", \"tracking\"]:\n                tracking = metric == \"tracking\"\n                if tracking and not self.tracking:\n                    continue\n                result_files, tmp_dir = self.format_results(\n                    results, jsonfile_prefix=self.work_dir, tracking=tracking\n                )\n\n                if isinstance(result_files, dict):\n                    for name in result_names:\n                        ret_dict = self._evaluate_single(\n                            result_files[name], tracking=tracking\n                        )\n                    results_dict.update(ret_dict)\n                elif isinstance(result_files, str):\n                    ret_dict = self._evaluate_single(\n                        result_files, tracking=tracking\n                    )\n                    results_dict.update(ret_dict)\n\n                if tmp_dir is not None:\n                    tmp_dir.cleanup()\n\n        if eval_mode['with_map']:\n            from .evaluation.map.vector_eval import VectorEvaluate\n            self.map_evaluator = VectorEvaluate(self.eval_config)\n            result_path = self.format_map_results(results, prefix=self.work_dir)\n            map_results_dict = self.map_evaluator.evaluate(result_path, logger=logger)\n            results_dict.update(map_results_dict)\n\n        if eval_mode['with_motion']:\n            thresh = eval_mode[\"motion_threshhold\"]\n            result_files = self.format_motion_results(results, jsonfile_prefix=self.work_dir, thresh=thresh)\n            motion_results_dict = self._evaluate_single_motion(result_files, self.work_dir, logger=logger)\n            results_dict.update(motion_results_dict)\n        \n        if eval_mode['with_planning']:\n            from .evaluation.planning.planning_eval import planning_eval\n            planning_results_dict = planning_eval(results, self.eval_config, logger=logger)\n            results_dict.update(planning_results_dict)\n\n        if show or out_dir:\n            self.show(results, save_dir=out_dir, show=show, pipeline=pipeline)\n        \n        # print main metrics for recording\n        metric_str = '\\n'\n        if \"img_bbox_NuScenes/NDS\" in results_dict:\n            metric_str += f'mAP: {results_dict.get(\"img_bbox_NuScenes/mAP\"):.4f}\\n'\n            metric_str += f'mATE: {results_dict.get(\"img_bbox_NuScenes/mATE\"):.4f}\\n'\n            metric_str += f'mASE: {results_dict.get(\"img_bbox_NuScenes/mASE\"):.4f}\\n'\n            metric_str += f'mAOE: {results_dict.get(\"img_bbox_NuScenes/mAOE\"):.4f}\\n' \n            metric_str += f'mAVE: {results_dict.get(\"img_bbox_NuScenes/mAVE\"):.4f}\\n' \n            metric_str += f'mAAE: {results_dict.get(\"img_bbox_NuScenes/mAAE\"):.4f}\\n' \n            metric_str += f'NDS: {results_dict.get(\"img_bbox_NuScenes/NDS\"):.4f}\\n\\n'\n        \n        if \"img_bbox_NuScenes/amota\" in results_dict:\n            metric_str += f'AMOTA: {results_dict[\"img_bbox_NuScenes/amota\"]:.4f}\\n' \n            metric_str += f'AMOTP: {results_dict[\"img_bbox_NuScenes/amotp\"]:.4f}\\n' \n            metric_str += f'RECALL: {results_dict[\"img_bbox_NuScenes/recall\"]:.4f}\\n' \n            metric_str += f'MOTAR: {results_dict[\"img_bbox_NuScenes/motar\"]:.4f}\\n' \n            metric_str += f'MOTA: {results_dict[\"img_bbox_NuScenes/mota\"]:.4f}\\n' \n            metric_str += f'MOTP: {results_dict[\"img_bbox_NuScenes/motp\"]:.4f}\\n' \n            metric_str += f'IDS: {results_dict[\"img_bbox_NuScenes/ids\"]}\\n\\n' \n        \n        if \"mAP_normal\" in results_dict:\n            metric_str += f'ped_crossing= {results_dict[\"ped_crossing\"]:.4f}\\n' \n            metric_str += f'divider= {results_dict[\"divider\"]:.4f}\\n' \n            metric_str += f'boundary= {results_dict[\"boundary\"]:.4f}\\n' \n            metric_str += f'mAP_normal= {results_dict[\"mAP_normal\"]:.4f}\\n\\n' \n\n        if \"car_EPA\" in results_dict:\n            metric_str += f'Car / Ped\\n' \n            metric_str += f'epa= {results_dict[\"car_EPA\"]:.4f} / {results_dict[\"pedestrian_EPA\"]:.4f}\\n'\n            metric_str += f'ade= {results_dict[\"car_min_ade_err\"]:.4f} / {results_dict[\"pedestrian_min_ade_err\"]:.4f}\\n'\n            metric_str += f'fde= {results_dict[\"car_min_fde_err\"]:.4f} / {results_dict[\"pedestrian_min_fde_err\"]:.4f}\\n'\n            metric_str += f'mr= {results_dict[\"car_miss_rate_err\"]:.4f} / {results_dict[\"pedestrian_miss_rate_err\"]:.4f}\\n\\n' \n\n        if \"L2\" in results_dict:\n            metric_str += f'obj_box_col: {(results_dict[\"obj_box_col\"]*100):.3f}%\\n'\n            metric_str += f'L2: {results_dict[\"L2\"]:.4f}\\n\\n'\n        \n        print_log(metric_str, logger=logger)\n        return results_dict\n\n    def show(self, results, save_dir=None, show=False, pipeline=None):\n        save_dir = \"./\" if save_dir is None else save_dir\n        save_dir = os.path.join(save_dir, \"visual\")\n        print_log(os.path.abspath(save_dir))\n        pipeline = Compose(pipeline)\n        if not os.path.exists(save_dir):\n            os.makedirs(save_dir)\n\n        fourcc = cv2.VideoWriter_fourcc(*\"MJPG\")\n        videoWriter = None\n\n        for i, result in enumerate(results):\n            if \"img_bbox\" in result.keys():\n                result = result[\"img_bbox\"]\n            data_info = pipeline(self.get_data_info(i))\n            imgs = []\n\n            raw_imgs = data_info[\"img\"]\n            lidar2img = data_info[\"img_metas\"].data[\"lidar2img\"]\n            pred_bboxes_3d = result[\"boxes_3d\"][\n                result[\"scores_3d\"] > self.vis_score_threshold\n            ]\n            if \"instance_ids\" in result and self.tracking:\n                color = []\n                for id in result[\"instance_ids\"].cpu().numpy().tolist():\n                    color.append(\n                        self.ID_COLOR_MAP[int(id % len(self.ID_COLOR_MAP))]\n                    )\n            elif \"labels_3d\" in result:\n                color = []\n                for id in result[\"labels_3d\"].cpu().numpy().tolist():\n                    color.append(self.ID_COLOR_MAP[id])\n            else:\n                color = (255, 0, 0)\n\n            # ===== draw boxes_3d to images =====\n            for j, img_origin in enumerate(raw_imgs):\n                img = img_origin.copy()\n                if len(pred_bboxes_3d) != 0:\n                    img = draw_lidar_bbox3d_on_img(\n                        pred_bboxes_3d,\n                        img,\n                        lidar2img[j],\n                        img_metas=None,\n                        color=color,\n                        thickness=3,\n                    )\n                imgs.append(img)\n\n            # ===== draw boxes_3d to BEV =====\n            bev = draw_lidar_bbox3d_on_bev(\n                pred_bboxes_3d,\n                bev_size=img.shape[0] * 2,\n                color=color,\n            )\n\n            # ===== put text and concat =====\n            for j, name in enumerate(\n                [\n                    \"front\",\n                    \"front right\",\n                    \"front left\",\n                    \"rear\",\n                    \"rear left\",\n                    \"rear right\",\n                ]\n            ):\n                imgs[j] = cv2.rectangle(\n                    imgs[j],\n                    (0, 0),\n                    (440, 80),\n                    color=(255, 255, 255),\n                    thickness=-1,\n                )\n                w, h = cv2.getTextSize(name, cv2.FONT_HERSHEY_SIMPLEX, 2, 2)[0]\n                text_x = int(220 - w / 2)\n                text_y = int(40 + h / 2)\n\n                imgs[j] = cv2.putText(\n                    imgs[j],\n                    name,\n                    (text_x, text_y),\n                    cv2.FONT_HERSHEY_SIMPLEX,\n                    2,\n                    (0, 0, 0),\n                    2,\n                    cv2.LINE_AA,\n                )\n            image = np.concatenate(\n                [\n                    np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n                    np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n                ],\n                axis=0,\n            )\n            image = np.concatenate([image, bev], axis=1)\n\n            # ===== save video =====\n            if videoWriter is None:\n                videoWriter = cv2.VideoWriter(\n                    os.path.join(save_dir, \"video.avi\"),\n                    fourcc,\n                    7,\n                    image.shape[:2][::-1],\n                )\n            cv2.imwrite(os.path.join(save_dir, f\"{i}.jpg\"), image)\n            videoWriter.write(image)\n        videoWriter.release()\n\n\ndef output_to_nusc_box(detection, threshold=None):\n    box3d = detection[\"boxes_3d\"]\n    scores = detection[\"scores_3d\"].numpy()\n    labels = detection[\"labels_3d\"].numpy()\n    if \"instance_ids\" in detection:\n        ids = detection[\"instance_ids\"]  # .numpy()\n    if threshold is not None:\n        if \"cls_scores\" in detection:\n            mask = detection[\"cls_scores\"].numpy() >= threshold\n        else:\n            mask = scores >= threshold\n        box3d = box3d[mask]\n        scores = scores[mask]\n        labels = labels[mask]\n        ids = ids[mask]\n\n    if hasattr(box3d, \"gravity_center\"):\n        box_gravity_center = box3d.gravity_center.numpy()\n        box_dims = box3d.dims.numpy()\n        nus_box_dims = box_dims[:, [1, 0, 2]]\n        box_yaw = box3d.yaw.numpy()\n    else:\n        box3d = box3d.numpy()\n        box_gravity_center = box3d[..., :3].copy()\n        box_dims = box3d[..., 3:6].copy()\n        nus_box_dims = box_dims[..., [1, 0, 2]]\n        box_yaw = box3d[..., 6].copy()\n\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    # box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        if hasattr(box3d, \"gravity_center\"):\n            velocity = (*box3d.tensor[i, 7:9], 0.0)\n        else:\n            velocity = (*box3d[i, 7:9], 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            nus_box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity,\n        )\n        if \"instance_ids\" in detection:\n            box.token = ids[i]\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(\n    info,\n    boxes,\n    classes,\n    eval_configs,\n    eval_version=\"detection_cvpr_2019\",\n    filter_with_cls_range=True,\n):\n    box_list = []\n    for i, box in enumerate(boxes):\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info[\"lidar2ego_rotation\"]))\n        box.translate(np.array(info[\"lidar2ego_translation\"]))\n        # filter det in ego.\n        if filter_with_cls_range:\n            cls_range_map = eval_configs.class_range\n            radius = np.linalg.norm(box.center[:2], 2)\n            det_range = cls_range_map[classes[box.label]]\n            if radius > det_range:\n                continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info[\"ego2global_rotation\"]))\n        box.translate(np.array(info[\"ego2global_translation\"]))\n        box_list.append(box)\n    return box_list\n\n\ndef get_T_global(info):\n    lidar2ego = np.eye(4)\n    lidar2ego[:3, :3] = pyquaternion.Quaternion(\n        info[\"lidar2ego_rotation\"]\n    ).rotation_matrix\n    lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n    ego2global = np.eye(4)\n    ego2global[:3, :3] = pyquaternion.Quaternion(\n        info[\"ego2global_rotation\"]\n    ).rotation_matrix\n    ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n    return ego2global @ lidar2ego"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/pipelines/__init__.py",
    "content": "from .transform import (\n    InstanceNameFilter,\n    CircleObjectRangeFilter,\n    NormalizeMultiviewImage,\n    NuScenesSparse4DAdaptor,\n    MultiScaleDepthMapGenerator,\n    DenseDepthMapGenerator,\n)\nfrom .augment import (\n    ResizeCropFlipImage,\n    BBoxRotation,\n    PhotoMetricDistortionMultiViewImage,\n)\nfrom .loading import LoadMultiViewImageFromFiles, LoadPointsFromFile\nfrom .vectorize import VectorizeMap\n\n__all__ = [\n    \"InstanceNameFilter\",\n    \"ResizeCropFlipImage\",\n    \"BBoxRotation\",\n    \"CircleObjectRangeFilter\",\n    \"MultiScaleDepthMapGenerator\",\n    \"NormalizeMultiviewImage\",\n    \"PhotoMetricDistortionMultiViewImage\",\n    \"NuScenesSparse4DAdaptor\",\n    \"LoadMultiViewImageFromFiles\",\n    \"LoadPointsFromFile\",\n    \"VectorizeMap\",\n]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/pipelines/augment.py",
    "content": "import torch\n\nimport numpy as np\nfrom numpy import random\nimport mmcv\nfrom mmdet.datasets.builder import PIPELINES\nfrom PIL import Image\n\n\n@PIPELINES.register_module()\nclass ResizeCropFlipImage(object):\n    def __init__(self, use_generated_img=False):\n        self.transform_img = not use_generated_img\n\n    def __call__(self, results):\n        aug_config = results.get(\"aug_config\")\n        if aug_config is None:\n            return results\n        imgs = results[\"img\"]\n        N = len(imgs)\n        new_imgs = []\n        for i in range(N):\n            img, mat = self._img_transform(\n                np.uint8(imgs[i]), aug_config,\n            )\n            new_imgs.append(np.array(img).astype(np.float32))\n            results[\"lidar2img\"][i] = mat @ results[\"lidar2img\"][i]\n            if \"cam_intrinsic\" in results:\n                # results[\"cam_intrinsic\"][i][:3, :3] *= aug_config[\"resize\"]\n                results[\"cam_intrinsic\"][i][:3, :3] = (\n                    mat[:3, :3] @ results[\"cam_intrinsic\"][i][:3, :3]\n                )\n\n        results[\"img\"] = new_imgs\n        results[\"img_shape\"] = [x.shape[:2] for x in new_imgs]\n        return results\n\n    def _img_transform(self, img, aug_configs):\n        H, W = img.shape[:2]\n        resize = aug_configs.get(\"resize\", 1)\n        resize_dims = (int(W * resize), int(H * resize))\n        crop = aug_configs.get(\"crop\", [0, 0, *resize_dims])\n        flip = aug_configs.get(\"flip\", False)\n        rotate = aug_configs.get(\"rotate\", 0)\n\n        if self.transform_img:\n            origin_dtype = img.dtype\n            if origin_dtype != np.uint8:\n                min_value = img.min()\n                max_vaule = img.max()\n                scale = 255 / (max_vaule - min_value)\n                img = (img - min_value) * scale\n                img = np.uint8(img)\n            img = Image.fromarray(img)\n            img = img.resize(resize_dims).crop(crop)\n            if flip:\n                img = img.transpose(method=Image.FLIP_LEFT_RIGHT)\n            img = img.rotate(rotate)\n            img = np.array(img).astype(np.float32)\n            if origin_dtype != np.uint8:\n                img = img.astype(np.float32)\n                img = img / scale + min_value\n\n        transform_matrix = np.eye(3)\n        transform_matrix[:2, :2] *= resize\n        transform_matrix[:2, 2] -= np.array(crop[:2])\n        if flip:\n            flip_matrix = np.array(\n                [[-1, 0, crop[2] - crop[0]], [0, 1, 0], [0, 0, 1]]\n            )\n            transform_matrix = flip_matrix @ transform_matrix\n        rotate = rotate / 180 * np.pi\n        rot_matrix = np.array(\n            [\n                [np.cos(rotate), np.sin(rotate), 0],\n                [-np.sin(rotate), np.cos(rotate), 0],\n                [0, 0, 1],\n            ]\n        )\n        rot_center = np.array([crop[2] - crop[0], crop[3] - crop[1]]) / 2\n        rot_matrix[:2, 2] = -rot_matrix[:2, :2] @ rot_center + rot_center\n        transform_matrix = rot_matrix @ transform_matrix\n        extend_matrix = np.eye(4)\n        extend_matrix[:3, :3] = transform_matrix\n        return img, extend_matrix\n\n\n@PIPELINES.register_module()\nclass BBoxRotation(object):\n    def __call__(self, results):\n        angle = results[\"aug_config\"][\"rotate_3d\"]\n        rot_cos = np.cos(angle)\n        rot_sin = np.sin(angle)\n\n        rot_mat = np.array(\n            [\n                [rot_cos, -rot_sin, 0, 0],\n                [rot_sin, rot_cos, 0, 0],\n                [0, 0, 1, 0],\n                [0, 0, 0, 1],\n            ]\n        )\n        rot_mat_inv = np.linalg.inv(rot_mat)\n\n        num_view = len(results[\"lidar2img\"])\n        for view in range(num_view):\n            results[\"lidar2img\"][view] = (\n                results[\"lidar2img\"][view] @ rot_mat_inv\n            )\n        if \"lidar2global\" in results:\n            results[\"lidar2global\"] = results[\"lidar2global\"] @ rot_mat_inv\n        if \"gt_bboxes_3d\" in results:\n            results[\"gt_bboxes_3d\"] = self.box_rotate(\n                results[\"gt_bboxes_3d\"], angle\n            )\n        return results\n\n    @staticmethod\n    def box_rotate(bbox_3d, angle):\n        rot_cos = np.cos(angle)\n        rot_sin = np.sin(angle)\n        rot_mat_T = np.array(\n            [[rot_cos, rot_sin, 0], [-rot_sin, rot_cos, 0], [0, 0, 1]]\n        )\n        bbox_3d[:, :3] = bbox_3d[:, :3] @ rot_mat_T\n        bbox_3d[:, 6] += angle\n        if bbox_3d.shape[-1] > 7:\n            vel_dims = bbox_3d[:, 7:].shape[-1]\n            bbox_3d[:, 7:] = bbox_3d[:, 7:] @ rot_mat_T[:vel_dims, :vel_dims]\n        return bbox_3d\n\n\n@PIPELINES.register_module()\nclass PhotoMetricDistortionMultiViewImage:\n    \"\"\"Apply photometric distortion to image sequentially, every transformation\n    is applied with a probability of 0.5. The position of random contrast is in\n    second or second to last.\n    1. random brightness\n    2. random contrast (mode 0)\n    3. convert color from BGR to HSV\n    4. random saturation\n    5. random hue\n    6. convert color from HSV to BGR\n    7. random contrast (mode 1)\n    8. randomly swap channels\n    Args:\n        brightness_delta (int): delta of brightness.\n        contrast_range (tuple): range of contrast.\n        saturation_range (tuple): range of saturation.\n        hue_delta (int): delta of hue.\n    \"\"\"\n\n    def __init__(\n        self,\n        brightness_delta=32,\n        contrast_range=(0.5, 1.5),\n        saturation_range=(0.5, 1.5),\n        hue_delta=18,\n    ):\n        self.brightness_delta = brightness_delta\n        self.contrast_lower, self.contrast_upper = contrast_range\n        self.saturation_lower, self.saturation_upper = saturation_range\n        self.hue_delta = hue_delta\n\n    def __call__(self, results):\n        \"\"\"Call function to perform photometric distortion on images.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Result dict with images distorted.\n        \"\"\"\n        imgs = results[\"img\"]\n        new_imgs = []\n        for img in imgs:\n            assert img.dtype == np.float32, (\n                \"PhotoMetricDistortion needs the input image of dtype np.float32,\"\n                ' please set \"to_float32=True\" in \"LoadImageFromFile\" pipeline'\n            )\n            # random brightness\n            if random.randint(2):\n                delta = random.uniform(\n                    -self.brightness_delta, self.brightness_delta\n                )\n                img += delta\n\n            # mode == 0 --> do random contrast first\n            # mode == 1 --> do random contrast last\n            mode = random.randint(2)\n            if mode == 1:\n                if random.randint(2):\n                    alpha = random.uniform(\n                        self.contrast_lower, self.contrast_upper\n                    )\n                    img *= alpha\n\n            # convert color from BGR to HSV\n            img = mmcv.bgr2hsv(img)\n\n            # random saturation\n            if random.randint(2):\n                img[..., 1] *= random.uniform(\n                    self.saturation_lower, self.saturation_upper\n                )\n\n            # random hue\n            if random.randint(2):\n                img[..., 0] += random.uniform(-self.hue_delta, self.hue_delta)\n                img[..., 0][img[..., 0] > 360] -= 360\n                img[..., 0][img[..., 0] < 0] += 360\n\n            # convert color from HSV to BGR\n            img = mmcv.hsv2bgr(img)\n\n            # random contrast\n            if mode == 0:\n                if random.randint(2):\n                    alpha = random.uniform(\n                        self.contrast_lower, self.contrast_upper\n                    )\n                    img *= alpha\n\n            # randomly swap channels\n            if random.randint(2):\n                img = img[..., random.permutation(3)]\n            new_imgs.append(img)\n        results[\"img\"] = new_imgs\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f\"(\\nbrightness_delta={self.brightness_delta},\\n\"\n        repr_str += \"contrast_range=\"\n        repr_str += f\"{(self.contrast_lower, self.contrast_upper)},\\n\"\n        repr_str += \"saturation_range=\"\n        repr_str += f\"{(self.saturation_lower, self.saturation_upper)},\\n\"\n        repr_str += f\"hue_delta={self.hue_delta})\"\n        return repr_str\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/pipelines/loading.py",
    "content": "import numpy as np\nimport mmcv\nfrom mmdet.datasets.builder import PIPELINES\n\n\n@PIPELINES.register_module()\nclass LoadMultiViewImageFromFiles(object):\n    \"\"\"Load multi channel images from a list of separate channel files.\n\n    Expects results['img_filename'] to be a list of filenames.\n\n    Args:\n        to_float32 (bool, optional): Whether to convert the img to float32.\n            Defaults to False.\n        color_type (str, optional): Color type of the file.\n            Defaults to 'unchanged'.\n    \"\"\"\n\n    def __init__(self, to_float32=False, color_type=\"unchanged\"):\n        self.to_float32 = to_float32\n        self.color_type = color_type\n\n    def __call__(self, results):\n        \"\"\"Call function to load multi-view image from files.\n\n        Args:\n            results (dict): Result dict containing multi-view image filenames.\n\n        Returns:\n            dict: The result dict containing the multi-view image data.\n                Added keys and values are described below.\n\n                - filename (str): Multi-view image filenames.\n                - img (np.ndarray): Multi-view image arrays.\n                - img_shape (tuple[int]): Shape of multi-view image arrays.\n                - ori_shape (tuple[int]): Shape of original image arrays.\n                - pad_shape (tuple[int]): Shape of padded image arrays.\n                - scale_factor (float): Scale factor.\n                - img_norm_cfg (dict): Normalization configuration of images.\n        \"\"\"\n        filename = results[\"img_filename\"]\n        # img is of shape (h, w, c, num_views)\n        img = np.stack(\n            [mmcv.imread(name, self.color_type) for name in filename], axis=-1\n        )\n        if self.to_float32:\n            img = img.astype(np.float32)\n        results[\"filename\"] = filename\n        # unravel to list, see `DefaultFormatBundle` in formatting.py\n        # which will transpose each image separately and then stack into array\n        results[\"img\"] = [img[..., i] for i in range(img.shape[-1])]\n        results[\"img_shape\"] = img.shape\n        results[\"ori_shape\"] = img.shape\n        # Set initial values for default meta_keys\n        results[\"pad_shape\"] = img.shape\n        results[\"scale_factor\"] = 1.0\n        num_channels = 1 if len(img.shape) < 3 else img.shape[2]\n        results[\"img_norm_cfg\"] = dict(\n            mean=np.zeros(num_channels, dtype=np.float32),\n            std=np.ones(num_channels, dtype=np.float32),\n            to_rgb=False,\n        )\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f\"(to_float32={self.to_float32}, \"\n        repr_str += f\"color_type='{self.color_type}')\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadPointsFromFile(object):\n    \"\"\"Load Points From File.\n\n    Load points from file.\n\n    Args:\n        coord_type (str): The type of coordinates of points cloud.\n            Available options includes:\n            - 'LIDAR': Points in LiDAR coordinates.\n            - 'DEPTH': Points in depth coordinates, usually for indoor dataset.\n            - 'CAMERA': Points in camera coordinates.\n        load_dim (int, optional): The dimension of the loaded points.\n            Defaults to 6.\n        use_dim (list[int], optional): Which dimensions of the points to use.\n            Defaults to [0, 1, 2]. For KITTI dataset, set use_dim=4\n            or use_dim=[0, 1, 2, 3] to use the intensity dimension.\n        shift_height (bool, optional): Whether to use shifted height.\n            Defaults to False.\n        use_color (bool, optional): Whether to use color features.\n            Defaults to False.\n        file_client_args (dict, optional): Config dict of file clients,\n            refer to\n            https://github.com/open-mmlab/mmcv/blob/master/mmcv/fileio/file_client.py\n            for more details. Defaults to dict(backend='disk').\n    \"\"\"\n\n    def __init__(\n        self,\n        coord_type,\n        load_dim=6,\n        use_dim=[0, 1, 2],\n        shift_height=False,\n        use_color=False,\n        file_client_args=dict(backend=\"disk\"),\n    ):\n        self.shift_height = shift_height\n        self.use_color = use_color\n        if isinstance(use_dim, int):\n            use_dim = list(range(use_dim))\n        assert (\n            max(use_dim) < load_dim\n        ), f\"Expect all used dimensions < {load_dim}, got {use_dim}\"\n        assert coord_type in [\"CAMERA\", \"LIDAR\", \"DEPTH\"]\n\n        self.coord_type = coord_type\n        self.load_dim = load_dim\n        self.use_dim = use_dim\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n\n    def _load_points(self, pts_filename):\n        \"\"\"Private function to load point clouds data.\n\n        Args:\n            pts_filename (str): Filename of point clouds data.\n\n        Returns:\n            np.ndarray: An array containing point clouds data.\n        \"\"\"\n        if self.file_client is None:\n            self.file_client = mmcv.FileClient(**self.file_client_args)\n        try:\n            pts_bytes = self.file_client.get(pts_filename)\n            points = np.frombuffer(pts_bytes, dtype=np.float32)\n        except ConnectionError:\n            mmcv.check_file_exist(pts_filename)\n            if pts_filename.endswith(\".npy\"):\n                points = np.load(pts_filename)\n            else:\n                points = np.fromfile(pts_filename, dtype=np.float32)\n\n        return points\n\n    def __call__(self, results):\n        \"\"\"Call function to load points data from file.\n\n        Args:\n            results (dict): Result dict containing point clouds data.\n\n        Returns:\n            dict: The result dict containing the point clouds data.\n                Added key and value are described below.\n\n                - points (:obj:`BasePoints`): Point clouds data.\n        \"\"\"\n        pts_filename = results[\"pts_filename\"]\n        points = self._load_points(pts_filename)\n        points = points.reshape(-1, self.load_dim)\n        points = points[:, self.use_dim]\n        attribute_dims = None\n\n        if self.shift_height:\n            floor_height = np.percentile(points[:, 2], 0.99)\n            height = points[:, 2] - floor_height\n            points = np.concatenate(\n                [points[:, :3], np.expand_dims(height, 1), points[:, 3:]], 1\n            )\n            attribute_dims = dict(height=3)\n\n        if self.use_color:\n            assert len(self.use_dim) >= 6\n            if attribute_dims is None:\n                attribute_dims = dict()\n            attribute_dims.update(\n                dict(\n                    color=[\n                        points.shape[1] - 3,\n                        points.shape[1] - 2,\n                        points.shape[1] - 1,\n                    ]\n                )\n            )\n\n        results[\"points\"] = points\n        return results\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/pipelines/transform.py",
    "content": "import cv2\nimport numpy as np\nfrom PIL import Image\n\nimport mmcv\nfrom mmcv.parallel import DataContainer as DC\nfrom mmdet.datasets.builder import PIPELINES\nfrom mmdet.datasets.pipelines import to_tensor\n\n\n@PIPELINES.register_module()\nclass DenseDepthMapGenerator(object):\n    def __init__(self, downsample=1, max_depth=60):\n        if not isinstance(downsample, (list, tuple)):\n            downsample = [downsample]\n        self.downsample = downsample\n        self.max_depth = max_depth\n\n    def __call__(self, input_dict):\n        aug_config = input_dict.get(\"aug_config\")\n        filename = input_dict[\"depth_filename\"]\n        depths = [cv2.imread(name) for name in filename]\n        depths = [self.decode(x) for x in depths]\n        N = len(depths)\n        new_depths = []\n        for i in range(N):\n            depth = self._img_transform(\n                np.uint8(depths[i] * 255) , aug_config,\n            )\n            depth = np.array(depth).astype(np.float32) / 255 * 1000\n            new_depths.append(depth)\n        \n        gt_depth = []\n        for i, depth in enumerate(new_depths):\n            for j, downsample in enumerate(self.downsample):\n                if len(gt_depth) < j + 1:\n                    gt_depth.append([])\n                depth_map = cv2.resize(depth, dsize=None, fx=1/downsample, fy=1/downsample)\n                mask = (depth_map == 0)\n                depth_map = np.clip(depth_map, 0.1, self.max_depth)\n                depth_map[mask] = -1\n                gt_depth[j].append(depth_map)\n        \n        input_dict[\"gt_depth\"] = [np.stack(x) for x in gt_depth]\n\n        # import matplotlib.pyplot as plt\n        # for i, depth in enumerate(input_dict[\"gt_depth\"][0]):\n        #     plt.imshow(depth)\n        #     plt.colorbar()\n        #     plt.savefig(f\"vis/depth_hm_{i}.jpg\")\n        #     plt.close()\n        # imgs = input_dict[\"img\"]\n        # image = np.concatenate(\n        #     [\n        #         np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n        #         np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n        #     ],\n        #     axis=0,\n        # )\n        # cv2.imwrite(f\"vis/img.jpg\", image)\n\n        # for i in range(3):\n        #     imgs = gt_depth[i]\n        #     image = np.concatenate(\n        #         [\n        #             np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n        #             np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n        #         ],\n        #         axis=0,\n        #     )\n        #     cv2.imwrite(f\"vis/depth_{i}.jpg\", image*255)\n        return input_dict\n\n    def decode(self, depth):\n        depth = cv2.cvtColor(depth, cv2.COLOR_BGR2RGB)\n        normalized_depth = np.dot(depth[:, :, :3], [65536.0, 256.0, 1.0]) / (256.0 * 256.0 * 256.0 - 1.0)\n        return normalized_depth\n\n    def _img_transform(self, img, aug_configs):\n        H, W = img.shape[:2]\n        resize = aug_configs.get(\"resize\", 1)\n        resize_dims = (int(W * resize), int(H * resize))\n        crop = aug_configs.get(\"crop\", [0, 0, *resize_dims])\n        flip = aug_configs.get(\"flip\", False)\n        rotate = aug_configs.get(\"rotate\", 0)\n\n        origin_dtype = img.dtype\n        if origin_dtype != np.uint8:\n            min_value = img.min()\n            max_vaule = img.max()\n            scale = 255 / (max_vaule - min_value)\n            img = (img - min_value) * scale\n            img = np.uint8(img)\n        img = Image.fromarray(img)\n        img = img.resize(resize_dims).crop(crop)\n        if flip:\n            img = img.transpose(method=Image.FLIP_LEFT_RIGHT)\n        img = img.rotate(rotate)\n        img = np.array(img).astype(np.float32)\n        if origin_dtype != np.uint8:\n            img = img.astype(np.float32)\n            img = img / scale + min_value\n\n        return img\n\n    \n\n\n@PIPELINES.register_module()\nclass MultiScaleDepthMapGenerator(object):\n    def __init__(self, downsample=1, max_depth=60):\n        if not isinstance(downsample, (list, tuple)):\n            downsample = [downsample]\n        self.downsample = downsample\n        self.max_depth = max_depth\n\n    def __call__(self, input_dict):\n        points = input_dict[\"points\"][..., :3, None]\n        gt_depth = []\n        for i, lidar2img in enumerate(input_dict[\"lidar2img\"]):\n            H, W = input_dict[\"img_shape\"][i][:2]\n\n            pts_2d = (\n                np.squeeze(lidar2img[:3, :3] @ points, axis=-1)\n                + lidar2img[:3, 3]\n            )\n            pts_2d[:, :2] /= pts_2d[:, 2:3]\n            U = np.round(pts_2d[:, 0]).astype(np.int32)\n            V = np.round(pts_2d[:, 1]).astype(np.int32)\n            depths = pts_2d[:, 2]\n            mask = np.logical_and.reduce(\n                [\n                    V >= 0,\n                    V < H,\n                    U >= 0,\n                    U < W,\n                    depths >= 0.1,\n                    # depths <= self.max_depth,\n                ]\n            )\n            V, U, depths = V[mask], U[mask], depths[mask]\n            sort_idx = np.argsort(depths)[::-1]\n            V, U, depths = V[sort_idx], U[sort_idx], depths[sort_idx]\n            depths = np.clip(depths, 0.1, self.max_depth)\n            for j, downsample in enumerate(self.downsample):\n                if len(gt_depth) < j + 1:\n                    gt_depth.append([])\n                h, w = (int(H / downsample), int(W / downsample))\n                u = np.floor(U / downsample).astype(np.int32)\n                v = np.floor(V / downsample).astype(np.int32)\n                depth_map = np.ones([h, w], dtype=np.float32) * -1\n                depth_map[v, u] = depths\n                gt_depth[j].append(depth_map)\n\n        input_dict[\"gt_depth\"] = [np.stack(x) for x in gt_depth]\n        return input_dict\n\n\n@PIPELINES.register_module()\nclass NuScenesSparse4DAdaptor(object):\n    def __init(self):\n        pass\n\n    def __call__(self, input_dict):\n        input_dict[\"projection_mat\"] = np.float32(\n            np.stack(input_dict[\"lidar2img\"])\n        )\n        input_dict[\"image_wh\"] = np.ascontiguousarray(\n            np.array(input_dict[\"img_shape\"], dtype=np.float32)[:, :2][:, ::-1]\n        )\n        input_dict[\"T_global_inv\"] = np.linalg.inv(input_dict[\"lidar2global\"])\n        input_dict[\"T_global\"] = input_dict[\"lidar2global\"]\n        if \"cam_intrinsic\" in input_dict:\n            input_dict[\"cam_intrinsic\"] = np.float32(\n                np.stack(input_dict[\"cam_intrinsic\"])\n            )\n            input_dict[\"focal\"] = input_dict[\"cam_intrinsic\"][..., 0, 0]\n        if \"instance_inds\" in input_dict:\n            input_dict[\"instance_id\"] = input_dict[\"instance_inds\"]\n\n        if \"gt_bboxes_3d\" in input_dict:\n            input_dict[\"gt_bboxes_3d\"][:, 6] = self.limit_period(\n                input_dict[\"gt_bboxes_3d\"][:, 6], offset=0.5, period=2 * np.pi\n            )\n            input_dict[\"gt_bboxes_3d\"] = DC(\n                to_tensor(input_dict[\"gt_bboxes_3d\"]).float()\n            )\n        if \"gt_labels_3d\" in input_dict:\n            input_dict[\"gt_labels_3d\"] = DC(\n                to_tensor(input_dict[\"gt_labels_3d\"]).long()\n            )\n\n        imgs = [img.transpose(2, 0, 1) for img in input_dict[\"img\"]]\n        imgs = np.ascontiguousarray(np.stack(imgs, axis=0))\n        input_dict[\"img\"] = DC(to_tensor(imgs), stack=True)\n\n        for key in [\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n        ]:\n            if key not in input_dict:\n                continue\n            input_dict[key] = DC(to_tensor(input_dict[key]), stack=False, cpu_only=False) \n\n        for key in [\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            'tp_near',\n            'tp_far',\n        ]:\n            if key not in input_dict:\n                continue\n            input_dict[key] = DC(to_tensor(input_dict[key]), stack=True, cpu_only=False, pad_dims=None)\n        \n        return input_dict\n\n    def limit_period(\n        self, val: np.ndarray, offset: float = 0.5, period: float = np.pi\n    ) -> np.ndarray:\n        limited_val = val - np.floor(val / period + offset) * period\n        return limited_val\n\n\n@PIPELINES.register_module()\nclass InstanceNameFilter(object):\n    \"\"\"Filter GT objects by their names.\n\n    Args:\n        classes (list[str]): List of class names to be kept for training.\n    \"\"\"\n\n    def __init__(self, classes):\n        self.classes = classes\n        self.labels = list(range(len(self.classes)))\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by their names.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        gt_labels_3d = input_dict[\"gt_labels_3d\"]\n        gt_bboxes_mask = np.array(\n            [n in self.labels for n in gt_labels_3d], dtype=np.bool_\n        )\n        input_dict[\"gt_bboxes_3d\"] = input_dict[\"gt_bboxes_3d\"][gt_bboxes_mask]\n        input_dict[\"gt_labels_3d\"] = input_dict[\"gt_labels_3d\"][gt_bboxes_mask]\n        if \"instance_inds\" in input_dict:\n            input_dict[\"instance_inds\"] = input_dict[\"instance_inds\"][gt_bboxes_mask]\n        if \"gt_agent_fut_trajs\" in input_dict:\n            input_dict[\"gt_agent_fut_trajs\"] = input_dict[\"gt_agent_fut_trajs\"][gt_bboxes_mask]\n            input_dict[\"gt_agent_fut_masks\"] = input_dict[\"gt_agent_fut_masks\"][gt_bboxes_mask]\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f\"(classes={self.classes})\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass CircleObjectRangeFilter(object):\n    def __init__(\n        self, class_dist_thred=[52.5] * 5 + [31.5] + [42] * 3 + [31.5]\n    ):\n        self.class_dist_thred = class_dist_thred\n\n    def __call__(self, input_dict):\n        gt_bboxes_3d = input_dict[\"gt_bboxes_3d\"]\n        gt_labels_3d = input_dict[\"gt_labels_3d\"]\n        dist = np.sqrt(\n            np.sum(gt_bboxes_3d[:, :2] ** 2, axis=-1)\n        )\n        mask = np.array([False] * len(dist))\n        for label_idx, dist_thred in enumerate(self.class_dist_thred):\n            mask = np.logical_or(\n                mask,\n                np.logical_and(gt_labels_3d == label_idx, dist <= dist_thred),\n            )\n\n        gt_bboxes_3d = gt_bboxes_3d[mask]\n        gt_labels_3d = gt_labels_3d[mask]\n\n        input_dict[\"gt_bboxes_3d\"] = gt_bboxes_3d\n        input_dict[\"gt_labels_3d\"] = gt_labels_3d\n        if \"instance_inds\" in input_dict:\n            input_dict[\"instance_inds\"] = input_dict[\"instance_inds\"][mask]\n        if \"gt_agent_fut_trajs\" in input_dict:\n            input_dict[\"gt_agent_fut_trajs\"] = input_dict[\"gt_agent_fut_trajs\"][mask]\n            input_dict[\"gt_agent_fut_masks\"] = input_dict[\"gt_agent_fut_masks\"][mask]\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f\"(class_dist_thred={self.class_dist_thred})\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass NormalizeMultiviewImage(object):\n    \"\"\"Normalize the image.\n    Added key is \"img_norm_cfg\".\n    Args:\n        mean (sequence): Mean values of 3 channels.\n        std (sequence): Std values of 3 channels.\n        to_rgb (bool): Whether to convert the image from BGR to RGB,\n            default is true.\n    \"\"\"\n\n    def __init__(self, mean, std, to_rgb=True):\n        self.mean = np.array(mean, dtype=np.float32)\n        self.std = np.array(std, dtype=np.float32)\n        self.to_rgb = to_rgb\n\n    def __call__(self, results):\n        \"\"\"Call function to normalize images.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Normalized results, 'img_norm_cfg' key is added into\n                result dict.\n        \"\"\"\n        results[\"img\"] = [\n            mmcv.imnormalize(img, self.mean, self.std, self.to_rgb)\n            for img in results[\"img\"]\n        ]\n        results[\"img_norm_cfg\"] = dict(\n            mean=self.mean, std=self.std, to_rgb=self.to_rgb\n        )\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f\"(mean={self.mean}, std={self.std}, to_rgb={self.to_rgb})\"\n        return repr_str\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/pipelines/vectorize.py",
    "content": "from typing import List, Tuple, Union, Dict\n\nimport numpy as np\nfrom shapely.geometry import LineString\nfrom numpy.typing import NDArray\n\nfrom mmcv.parallel import DataContainer as DC\nfrom mmdet.datasets.builder import PIPELINES\n\n\n@PIPELINES.register_module(force=True)\nclass VectorizeMap(object):\n    \"\"\"Generate vectoized map and put into `semantic_mask` key.\n    Concretely, shapely geometry objects are converted into sample points (ndarray).\n    We use args `sample_num`, `sample_dist`, `simplify` to specify sampling method.\n\n    Args:\n        roi_size (tuple or list): bev range .\n        normalize (bool): whether to normalize points to range (0, 1).\n        coords_dim (int): dimension of point coordinates.\n        simplify (bool): whether to use simpily function. If true, `sample_num` \\\n            and `sample_dist` will be ignored.\n        sample_num (int): number of points to interpolate from a polyline. Set to -1 to ignore.\n        sample_dist (float): interpolate distance. Set to -1 to ignore.\n    \"\"\"\n\n    def __init__(self, \n                 roi_size: Union[Tuple, List], \n                 normalize: bool,\n                 coords_dim: int=2,\n                 simplify: bool=False, \n                 sample_num: int=-1, \n                 sample_dist: float=-1, \n                 permute: bool=False\n        ):\n        self.coords_dim = coords_dim\n        self.sample_num = sample_num\n        self.sample_dist = sample_dist\n        self.roi_size = np.array(roi_size)\n        self.normalize = normalize\n        self.simplify = simplify\n        self.permute = permute\n\n        if sample_dist > 0:\n            assert sample_num < 0 and not simplify\n            self.sample_fn = self.interp_fixed_dist\n        elif sample_num > 0:\n            assert sample_dist < 0 and not simplify\n            self.sample_fn = self.interp_fixed_num\n        else:\n            assert simplify\n\n    def interp_fixed_num(self, line: LineString) -> NDArray:\n        ''' Interpolate a line to fixed number of points.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n\n        distances = np.linspace(0, line.length, self.sample_num)\n        sampled_points = np.array([list(line.interpolate(distance).coords) \n            for distance in distances]).squeeze()\n\n        return sampled_points\n\n    def interp_fixed_dist(self, line: LineString) -> NDArray:\n        ''' Interpolate a line at fixed interval.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n\n        distances = list(np.arange(self.sample_dist, line.length, self.sample_dist))\n        # make sure to sample at least two points when sample_dist > line.length\n        distances = [0,] + distances + [line.length,] \n        \n        sampled_points = np.array([list(line.interpolate(distance).coords)\n                                for distance in distances]).squeeze()\n        \n        return sampled_points\n    \n    def get_vectorized_lines(self, map_geoms: Dict) -> Dict:\n        ''' Vectorize map elements. Iterate over the input dict and apply the \n        specified sample funcion.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            vectors (array): dict of vectorized map elements.\n        '''\n\n        vectors = {}\n        for label, geom_list in map_geoms.items():\n            vectors[label] = []\n            for geom in geom_list:\n                if geom.geom_type == 'LineString':\n                    if self.simplify:\n                        line = geom.simplify(0.2, preserve_topology=True)\n                        line = np.array(line.coords)\n                    else:\n                        line = self.sample_fn(geom)\n                    line = line[:, :self.coords_dim]\n\n                    if self.normalize:\n                        line = self.normalize_line(line)\n                    if self.permute:\n                        line = self.permute_line(line)\n                    vectors[label].append(line)\n\n                elif geom.geom_type == 'Polygon':\n                    # polygon objects will not be vectorized\n                    continue\n                \n                else:\n                    raise ValueError('map geoms must be either LineString or Polygon!')\n        return vectors\n    \n    def normalize_line(self, line: NDArray) -> NDArray:\n        ''' Convert points to range (0, 1).\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            normalized (array): normalized points.\n        '''\n\n        origin = -np.array([self.roi_size[0]/2, self.roi_size[1]/2])\n\n        line[:, :2] = line[:, :2] - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        line[:, :2] = line[:, :2] / (self.roi_size + eps)\n\n        return line\n    \n    def permute_line(self, line: np.ndarray, padding=1e5):\n        '''\n        (num_pts, 2) -> (num_permute, num_pts, 2)\n        where num_permute = 2 * (num_pts - 1)\n        '''\n        is_closed = np.allclose(line[0], line[-1], atol=1e-3)\n        num_points = len(line)\n        permute_num = num_points - 1\n        permute_lines_list = []\n        if is_closed:\n            pts_to_permute = line[:-1, :] # throw away replicate start end pts\n            for shift_i in range(permute_num):\n                permute_lines_list.append(np.roll(pts_to_permute, shift_i, axis=0))\n            flip_pts_to_permute = np.flip(pts_to_permute, axis=0)\n            for shift_i in range(permute_num):\n                permute_lines_list.append(np.roll(flip_pts_to_permute, shift_i, axis=0))\n        else:\n            permute_lines_list.append(line)\n            permute_lines_list.append(np.flip(line, axis=0))\n\n        permute_lines_array = np.stack(permute_lines_list, axis=0)\n\n        if is_closed:\n            tmp = np.zeros((permute_num * 2, num_points, self.coords_dim))\n            tmp[:, :-1, :] = permute_lines_array\n            tmp[:, -1, :] = permute_lines_array[:, 0, :] # add replicate start end pts\n            permute_lines_array = tmp\n\n        else:\n            # padding\n            padding = np.full([permute_num * 2 - 2, num_points, self.coords_dim], padding)\n            permute_lines_array = np.concatenate((permute_lines_array, padding), axis=0)\n        \n        return permute_lines_array\n    \n    def __call__(self, input_dict):\n        if \"map_geoms\" not in input_dict:\n            return input_dict\n        map_geoms = input_dict['map_geoms']\n        vectors = self.get_vectorized_lines(map_geoms)\n\n        if self.permute:\n            gt_map_labels, gt_map_pts = [], []\n            for label, vecs in vectors.items():\n                for vec in vecs:\n                    gt_map_labels.append(label)\n                    gt_map_pts.append(vec)\n            input_dict['gt_map_labels'] = np.array(gt_map_labels, dtype=np.int64)\n            input_dict['gt_map_pts'] = np.array(gt_map_pts, dtype=np.float32).reshape(-1, 2 * (self.sample_num - 1), self.sample_num, self.coords_dim)\n        else:\n            input_dict['vectors'] = DC(vectors, stack=False, cpu_only=True)\n        \n        return input_dict\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(simplify={self.simplify}, '\n        repr_str += f'sample_num={self.sample_num}), '\n        repr_str += f'sample_dist={self.sample_dist}), ' \n        repr_str += f'roi_size={self.roi_size})'\n        repr_str += f'normalize={self.normalize})'\n        repr_str += f'coords_dim={self.coords_dim})'\n\n        return repr_str"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/samplers/__init__.py",
    "content": "from .group_sampler import DistributedGroupSampler\nfrom .distributed_sampler import DistributedSampler\nfrom .sampler import SAMPLER, build_sampler\nfrom .group_in_batch_sampler import (\n    GroupInBatchSampler,\n)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/samplers/distributed_sampler.py",
    "content": "import math\n\nimport torch\nfrom torch.utils.data import DistributedSampler as _DistributedSampler\nfrom .sampler import SAMPLER\n\nimport pdb\nimport sys\n\n\nclass ForkedPdb(pdb.Pdb):\n    def interaction(self, *args, **kwargs):\n        _stdin = sys.stdin\n        try:\n            sys.stdin = open(\"/dev/stdin\")\n            pdb.Pdb.interaction(self, *args, **kwargs)\n        finally:\n            sys.stdin = _stdin\n\n\ndef set_trace():\n    ForkedPdb().set_trace(sys._getframe().f_back)\n\n\n@SAMPLER.register_module()\nclass DistributedSampler(_DistributedSampler):\n    def __init__(\n        self, dataset=None, num_replicas=None, rank=None, shuffle=True, seed=0\n    ):\n        super().__init__(\n            dataset, num_replicas=num_replicas, rank=rank, shuffle=shuffle\n        )\n        # for the compatibility from PyTorch 1.3+\n        self.seed = seed if seed is not None else 0\n\n    def __iter__(self):\n        # deterministically shuffle based on epoch\n        assert not self.shuffle\n        if \"data_infos\" in dir(self.dataset):\n            timestamps = [\n                x[\"timestamp\"] / 1e6 for x in self.dataset.data_infos\n            ]\n            vehicle_idx = [\n                x[\"lidar_path\"].split(\"/\")[-1][:4]\n                if \"lidar_path\" in x\n                else None\n                for x in self.dataset.data_infos\n            ]\n        else:\n            timestamps = [\n                x[\"timestamp\"] / 1e6\n                for x in self.dataset.datasets[0].data_infos\n            ] * len(self.dataset.datasets)\n            vehicle_idx = [\n                x[\"lidar_path\"].split(\"/\")[-1][:4]\n                if \"lidar_path\" in x\n                else None\n                for x in self.dataset.datasets[0].data_infos\n            ] * len(self.dataset.datasets)\n\n        sequence_splits = []\n        for i in range(len(timestamps)):\n            if i == 0 or (\n                abs(timestamps[i] - timestamps[i - 1]) > 4\n                or vehicle_idx[i] != vehicle_idx[i - 1]\n            ):\n                sequence_splits.append([i])\n            else:\n                sequence_splits[-1].append(i)\n\n        indices = []\n        perfix_sum = 0\n        split_length = len(self.dataset) // self.num_replicas\n        for i in range(len(sequence_splits)):\n            if perfix_sum >= (self.rank + 1) * split_length:\n                break\n            elif perfix_sum >= self.rank * split_length:\n                indices.extend(sequence_splits[i])\n            perfix_sum += len(sequence_splits[i])\n\n        self.num_samples = len(indices)\n        return iter(indices)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/samplers/group_in_batch_sampler.py",
    "content": "# https://github.com/Divadi/SOLOFusion/blob/main/mmdet3d/datasets/samplers/infinite_group_each_sample_in_batch_sampler.py\nimport itertools\nimport copy\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.runner import get_dist_info\nfrom torch.utils.data.sampler import Sampler\n\n\n# https://github.com/open-mmlab/mmdetection/blob/3b72b12fe9b14de906d1363982b9fba05e7d47c1/mmdet/core/utils/dist_utils.py#L157\ndef sync_random_seed(seed=None, device=\"cuda\"):\n    \"\"\"Make sure different ranks share the same seed.\n    All workers must call this function, otherwise it will deadlock.\n    This method is generally used in `DistributedSampler`,\n    because the seed should be identical across all processes\n    in the distributed group.\n    In distributed sampling, different ranks should sample non-overlapped\n    data in the dataset. Therefore, this function is used to make sure that\n    each rank shuffles the data indices in the same order based\n    on the same seed. Then different ranks could use different indices\n    to select non-overlapped data from the same data list.\n    Args:\n        seed (int, Optional): The seed. Default to None.\n        device (str): The device where the seed will be put on.\n            Default to 'cuda'.\n    Returns:\n        int: Seed to be used.\n    \"\"\"\n    if seed is None:\n        seed = np.random.randint(2**31)\n    assert isinstance(seed, int)\n\n    rank, world_size = get_dist_info()\n\n    if world_size == 1:\n        return seed\n\n    if rank == 0:\n        random_num = torch.tensor(seed, dtype=torch.int32, device=device)\n    else:\n        random_num = torch.tensor(0, dtype=torch.int32, device=device)\n    dist.broadcast(random_num, src=0)\n    return random_num.item()\n\n\nclass GroupInBatchSampler(Sampler):\n    \"\"\"\n    Pardon this horrendous name. Basically, we want every sample to be from its own group.\n    If batch size is 4 and # of GPUs is 8, each sample of these 32 should be operating on\n    its own group.\n\n    Shuffling is only done for group order, not done within groups.\n    \"\"\"\n\n    def __init__(\n        self,\n        dataset,\n        batch_size=1,\n        world_size=None,\n        rank=None,\n        seed=0,\n        skip_prob=0.,\n        sequence_flip_prob=0.,\n    ):\n        _rank, _world_size = get_dist_info()\n        if world_size is None:\n            world_size = _world_size\n        if rank is None:\n            rank = _rank\n\n        self.dataset = dataset\n        self.batch_size = batch_size\n        self.world_size = world_size\n        self.rank = rank\n        self.seed = sync_random_seed(seed)\n\n        self.size = len(self.dataset)\n\n        assert hasattr(self.dataset, \"flag\")\n        self.flag = self.dataset.flag\n        self.group_sizes = np.bincount(self.flag)\n        self.groups_num = len(self.group_sizes)\n        self.global_batch_size = batch_size * world_size\n        assert self.groups_num >= self.global_batch_size\n\n        # Now, for efficiency, make a dict group_idx: List[dataset sample_idxs]\n        self.group_idx_to_sample_idxs = {\n            group_idx: np.where(self.flag == group_idx)[0].tolist()\n            for group_idx in range(self.groups_num)\n        }\n\n        # Get a generator per sample idx. Considering samples over all\n        # GPUs, each sample position has its own generator\n        self.group_indices_per_global_sample_idx = [\n            self._group_indices_per_global_sample_idx(\n                self.rank * self.batch_size + local_sample_idx\n            )\n            for local_sample_idx in range(self.batch_size)\n        ]\n\n        # Keep track of a buffer of dataset sample idxs for each local sample idx\n        self.buffer_per_local_sample = [[] for _ in range(self.batch_size)]\n        self.aug_per_local_sample = [None for _ in range(self.batch_size)]\n        self.skip_prob = skip_prob\n        self.sequence_flip_prob = sequence_flip_prob\n\n    def _infinite_group_indices(self):\n        g = torch.Generator()\n        g.manual_seed(self.seed)\n        while True:\n            yield from torch.randperm(self.groups_num, generator=g).tolist()\n\n    def _group_indices_per_global_sample_idx(self, global_sample_idx):\n        yield from itertools.islice(\n            self._infinite_group_indices(),\n            global_sample_idx,\n            None,\n            self.global_batch_size,\n        )\n\n    def __iter__(self):\n        while True:\n            curr_batch = []\n            for local_sample_idx in range(self.batch_size):\n                skip = (\n                    np.random.uniform() < self.skip_prob\n                    and len(self.buffer_per_local_sample[local_sample_idx]) > 1\n                )\n                if len(self.buffer_per_local_sample[local_sample_idx]) == 0:\n                    # Finished current group, refill with next group\n                    # skip = False\n                    new_group_idx = next(\n                        self.group_indices_per_global_sample_idx[\n                            local_sample_idx\n                        ]\n                    )\n                    self.buffer_per_local_sample[\n                        local_sample_idx\n                    ] = copy.deepcopy(\n                        self.group_idx_to_sample_idxs[new_group_idx]\n                    )\n                    if np.random.uniform() < self.sequence_flip_prob:\n                        self.buffer_per_local_sample[\n                            local_sample_idx\n                        ] = self.buffer_per_local_sample[local_sample_idx][\n                            ::-1\n                        ]\n                    if self.dataset.keep_consistent_seq_aug:\n                        self.aug_per_local_sample[\n                            local_sample_idx\n                        ] = self.dataset.get_augmentation()\n\n                if not self.dataset.keep_consistent_seq_aug:\n                    self.aug_per_local_sample[\n                        local_sample_idx\n                    ] = self.dataset.get_augmentation()\n\n                if skip:\n                    self.buffer_per_local_sample[local_sample_idx].pop(0)\n                curr_batch.append(\n                    dict(\n                        idx=self.buffer_per_local_sample[local_sample_idx].pop(\n                            0\n                        ),\n                        aug_config=self.aug_per_local_sample[local_sample_idx],\n                    )\n                )\n\n            yield curr_batch\n\n    def __len__(self):\n        \"\"\"Length of base dataset.\"\"\"\n        return self.size\n\n    def set_epoch(self, epoch):\n        self.epoch = epoch\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/samplers/group_sampler.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport math\n\nimport numpy as np\nimport torch\nfrom mmcv.runner import get_dist_info\nfrom torch.utils.data import Sampler\nfrom .sampler import SAMPLER\nimport random\nfrom IPython import embed\n\n\n@SAMPLER.register_module()\nclass DistributedGroupSampler(Sampler):\n    \"\"\"Sampler that restricts data loading to a subset of the dataset.\n    It is especially useful in conjunction with\n    :class:`torch.nn.parallel.DistributedDataParallel`. In such case, each\n    process can pass a DistributedSampler instance as a DataLoader sampler,\n    and load a subset of the original dataset that is exclusive to it.\n    .. note::\n        Dataset is assumed to be of constant size.\n    Arguments:\n        dataset: Dataset used for sampling.\n        num_replicas (optional): Number of processes participating in\n            distributed training.\n        rank (optional): Rank of the current process within num_replicas.\n        seed (int, optional): random seed used to shuffle the sampler if\n            ``shuffle=True``. This number should be identical across all\n            processes in the distributed group. Default: 0.\n    \"\"\"\n\n    def __init__(\n        self, dataset, samples_per_gpu=1, num_replicas=None, rank=None, seed=0\n    ):\n        _rank, _num_replicas = get_dist_info()\n        if num_replicas is None:\n            num_replicas = _num_replicas\n        if rank is None:\n            rank = _rank\n        self.dataset = dataset\n        self.samples_per_gpu = samples_per_gpu\n        self.num_replicas = num_replicas\n        self.rank = rank\n        self.epoch = 0\n        self.seed = seed if seed is not None else 0\n\n        assert hasattr(self.dataset, \"flag\")\n        self.flag = self.dataset.flag\n        self.group_sizes = np.bincount(self.flag)\n\n        self.num_samples = 0\n        for i, j in enumerate(self.group_sizes):\n            self.num_samples += (\n                int(\n                    math.ceil(\n                        self.group_sizes[i]\n                        * 1.0\n                        / self.samples_per_gpu\n                        / self.num_replicas\n                    )\n                )\n                * self.samples_per_gpu\n            )\n        self.total_size = self.num_samples * self.num_replicas\n\n    def __iter__(self):\n        # deterministically shuffle based on epoch\n        g = torch.Generator()\n        g.manual_seed(self.epoch + self.seed)\n\n        indices = []\n        for i, size in enumerate(self.group_sizes):\n            if size > 0:\n                indice = np.where(self.flag == i)[0]\n                assert len(indice) == size\n                # add .numpy() to avoid bug when selecting indice in parrots.\n                # TODO: check whether torch.randperm() can be replaced by\n                # numpy.random.permutation().\n                indice = indice[\n                    list(torch.randperm(int(size), generator=g).numpy())\n                ].tolist()\n                extra = int(\n                    math.ceil(\n                        size * 1.0 / self.samples_per_gpu / self.num_replicas\n                    )\n                ) * self.samples_per_gpu * self.num_replicas - len(indice)\n                # pad indice\n                tmp = indice.copy()\n                for _ in range(extra // size):\n                    indice.extend(tmp)\n                indice.extend(tmp[: extra % size])\n                indices.extend(indice)\n\n        assert len(indices) == self.total_size\n\n        indices = [\n            indices[j]\n            for i in list(\n                torch.randperm(\n                    len(indices) // self.samples_per_gpu, generator=g\n                )\n            )\n            for j in range(\n                i * self.samples_per_gpu, (i + 1) * self.samples_per_gpu\n            )\n        ]\n\n        # subsample\n        offset = self.num_samples * self.rank\n        indices = indices[offset : offset + self.num_samples]\n        assert len(indices) == self.num_samples\n\n        return iter(indices)\n\n    def __len__(self):\n        return self.num_samples\n\n    def set_epoch(self, epoch):\n        self.epoch = epoch\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/samplers/sampler.py",
    "content": "from mmcv.utils.registry import Registry, build_from_cfg\n\nSAMPLER = Registry(\"sampler\")\n\n\ndef build_sampler(cfg, default_args):\n    return build_from_cfg(cfg, SAMPLER, default_args)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/datasets/utils.py",
    "content": "import copy\n\nimport cv2\nimport numpy as np\nimport torch\n\nfrom mmdet3d_plugin.core.box3d import *\n\n\ndef box3d_to_corners(box3d):\n    if isinstance(box3d, torch.Tensor):\n        box3d = box3d.detach().cpu().numpy()\n    corners_norm = np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)\n    corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n    # use relative origin [0.5, 0.5, 0]\n    corners_norm = corners_norm - np.array([0.5, 0.5, 0.5])\n    corners = box3d[:, None, [W, L, H]] * corners_norm.reshape([1, 8, 3])\n\n    # rotate around z axis\n    rot_cos = np.cos(box3d[:, YAW])\n    rot_sin = np.sin(box3d[:, YAW])\n    rot_mat = np.tile(np.eye(3)[None], (box3d.shape[0], 1, 1))\n    rot_mat[:, 0, 0] = rot_cos\n    rot_mat[:, 0, 1] = -rot_sin\n    rot_mat[:, 1, 0] = rot_sin\n    rot_mat[:, 1, 1] = rot_cos\n    corners = (rot_mat[:, None] @ corners[..., None]).squeeze(axis=-1)\n    corners += box3d[:, None, :3]\n    return corners\n\n\ndef plot_rect3d_on_img(\n    img, num_rects, rect_corners, color=(0, 255, 0), thickness=1\n):\n    \"\"\"Plot the boundary lines of 3D rectangular on 2D images.\n\n    Args:\n        img (numpy.array): The numpy array of image.\n        num_rects (int): Number of 3D rectangulars.\n        rect_corners (numpy.array): Coordinates of the corners of 3D\n            rectangulars. Should be in the shape of [num_rect, 8, 2].\n        color (tuple[int], optional): The color to draw bboxes.\n            Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    line_indices = (\n        (0, 1),\n        (0, 3),\n        (0, 4),\n        (1, 2),\n        (1, 5),\n        (3, 2),\n        (3, 7),\n        (4, 5),\n        (4, 7),\n        (2, 6),\n        (5, 6),\n        (6, 7),\n    )\n    h, w = img.shape[:2]\n    for i in range(num_rects):\n        corners = np.clip(rect_corners[i], -1e4, 1e5).astype(np.int32)\n        for start, end in line_indices:\n            if (\n                (corners[start, 1] >= h or corners[start, 1] < 0)\n                or (corners[start, 0] >= w or corners[start, 0] < 0)\n            ) and (\n                (corners[end, 1] >= h or corners[end, 1] < 0)\n                or (corners[end, 0] >= w or corners[end, 0] < 0)\n            ):\n                continue\n            if isinstance(color[0], int):\n                cv2.line(\n                    img,\n                    (corners[start, 0], corners[start, 1]),\n                    (corners[end, 0], corners[end, 1]),\n                    color,\n                    thickness,\n                    cv2.LINE_AA,\n                )\n            else:\n                cv2.line(\n                    img,\n                    (corners[start, 0], corners[start, 1]),\n                    (corners[end, 0], corners[end, 1]),\n                    color[i],\n                    thickness,\n                    cv2.LINE_AA,\n                )\n\n    return img.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d_on_img(\n    bboxes3d, raw_img, lidar2img_rt, img_metas=None, color=(0, 255, 0), thickness=1\n):\n    \"\"\"Project the 3D bbox on 2D plane and draw on input image.\n\n    Args:\n        bboxes3d (:obj:`LiDARInstance3DBoxes`):\n            3d bbox in lidar coordinate system to visualize.\n        raw_img (numpy.array): The numpy array of image.\n        lidar2img_rt (numpy.array, shape=[4, 4]): The projection matrix\n            according to the camera intrinsic parameters.\n        img_metas (dict): Useless here.\n        color (tuple[int], optional): The color to draw bboxes.\n            Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    img = raw_img.copy()\n    # corners_3d = bboxes3d.corners\n    corners_3d = box3d_to_corners(bboxes3d)\n    num_bbox = corners_3d.shape[0]\n    pts_4d = np.concatenate(\n        [corners_3d.reshape(-1, 3), np.ones((num_bbox * 8, 1))], axis=-1\n    )\n    lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n    if isinstance(lidar2img_rt, torch.Tensor):\n        lidar2img_rt = lidar2img_rt.cpu().numpy()\n    pts_2d = pts_4d @ lidar2img_rt.T\n\n    pts_2d[:, 2] = np.clip(pts_2d[:, 2], a_min=1e-5, a_max=1e5)\n    pts_2d[:, 0] /= pts_2d[:, 2]\n    pts_2d[:, 1] /= pts_2d[:, 2]\n    imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)\n\n    return plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, color, thickness)\n\n\ndef draw_points_on_img(points, img, lidar2img_rt, color=(0, 255, 0), circle=4):\n    img = img.copy()\n    N = points.shape[0]\n    points = points.cpu().numpy()\n    lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n    if isinstance(lidar2img_rt, torch.Tensor):\n        lidar2img_rt = lidar2img_rt.cpu().numpy()\n    pts_2d = (\n        np.sum(points[:, :, None] * lidar2img_rt[:3, :3], axis=-1)\n        + lidar2img_rt[:3, 3]\n    )\n    pts_2d[..., 2] = np.clip(pts_2d[..., 2], a_min=1e-5, a_max=1e5)\n    pts_2d = pts_2d[..., :2] / pts_2d[..., 2:3]\n    pts_2d = np.clip(pts_2d, -1e4, 1e4).astype(np.int32)\n\n    for i in range(N):\n        for point in pts_2d[i]:\n            if isinstance(color[0], int):\n                color_tmp = color\n            else:\n                color_tmp = color[i]\n            cv2.circle(img, point.tolist(), circle, color_tmp, thickness=-1)\n    return img.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d_on_bev(\n    bboxes_3d, bev_size, bev_range=115, color=(255, 0, 0), thickness=3):\n    if isinstance(bev_size, (list, tuple)):\n        bev_h, bev_w = bev_size\n    else:\n        bev_h, bev_w = bev_size, bev_size\n    bev = np.zeros([bev_h, bev_w, 3])\n\n    marking_color = (127, 127, 127)\n    bev_resolution = bev_range / bev_h\n    for cir in range(int(bev_range / 2 / 10)):\n        cv2.circle(\n            bev,\n            (int(bev_h / 2), int(bev_w / 2)),\n            int((cir + 1) * 10 / bev_resolution),\n            marking_color,\n            thickness=thickness,\n        )\n    cv2.line(\n        bev,\n        (0, int(bev_h / 2)),\n        (bev_w, int(bev_h / 2)),\n        marking_color,\n    )\n    cv2.line(\n        bev,\n        (int(bev_w / 2), 0),\n        (int(bev_w / 2), bev_h),\n        marking_color,\n    )\n    if len(bboxes_3d) != 0:\n        bev_corners = box3d_to_corners(bboxes_3d)[:, [0, 3, 4, 7]][\n            ..., [0, 1]\n        ]\n        xs = bev_corners[..., 0] / bev_resolution + bev_w / 2\n        ys = -bev_corners[..., 1] / bev_resolution + bev_h / 2\n        for obj_idx, (x, y) in enumerate(zip(xs, ys)):\n            for p1, p2 in ((0, 1), (0, 2), (1, 3), (2, 3)):\n                if isinstance(color[0], (list, tuple)):\n                    tmp = color[obj_idx]\n                else:\n                    tmp = color\n                cv2.line(\n                    bev,\n                    (int(x[p1]), int(y[p1])),\n                    (int(x[p2]), int(y[p2])),\n                    tmp,\n                    thickness=thickness,\n                )\n    return bev.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d(bboxes_3d, imgs, lidar2imgs, color=(255, 0, 0)):\n    vis_imgs = []\n    for i, (img, lidar2img) in enumerate(zip(imgs, lidar2imgs)):\n        vis_imgs.append(\n            draw_lidar_bbox3d_on_img(bboxes_3d, img, lidar2img, color=color)\n        )\n\n    num_imgs = len(vis_imgs)\n    if num_imgs < 4 or num_imgs % 2 != 0:\n        vis_imgs = np.concatenate(vis_imgs, axis=1)\n    else:\n        vis_imgs = np.concatenate([\n            np.concatenate(vis_imgs[:num_imgs//2], axis=1),\n            np.concatenate(vis_imgs[num_imgs//2:], axis=1)\n        ], axis=0)\n\n    bev = draw_lidar_bbox3d_on_bev(bboxes_3d, vis_imgs.shape[0], color=color)\n    vis_imgs = np.concatenate([bev, vis_imgs], axis=1)\n    return vis_imgs\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/MomAD.py",
    "content": "from inspect import signature\n\nimport torch\n\nfrom mmcv.runner import force_fp32, auto_fp16\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\nfrom mmdet.models import (\n    DETECTORS,\n    BaseDetector,\n    build_backbone,\n    build_head,\n    build_neck,\n)\nfrom .grid_mask import GridMask\n\ntry:\n    from ..ops import feature_maps_format\n    DAF_VALID = True\nexcept:\n    DAF_VALID = False\n\n__all__ = [\"MomAD\"]\n\n\n@DETECTORS.register_module()\nclass MomAD(BaseDetector):\n    def __init__(\n        self,\n        img_backbone,\n        head,\n        img_neck=None,\n        init_cfg=None,\n        train_cfg=None,\n        test_cfg=None,\n        pretrained=None,\n        use_grid_mask=True,\n        use_deformable_func=False,\n        depth_branch=None,\n        freeze_backbone=False,\n        freeze_neck=False,\n        freeze_perception=False,\n    ):\n        super(MomAD, self).__init__(init_cfg=init_cfg)\n        if pretrained is not None:\n            backbone.pretrained = pretrained\n        self.img_backbone = build_backbone(img_backbone)\n        if img_neck is not None:\n            self.img_neck = build_neck(img_neck)\n        self.head = build_head(head)\n        self.use_grid_mask = use_grid_mask\n        if use_deformable_func:\n            assert DAF_VALID, \"deformable_aggregation needs to be set up.\"\n        self.use_deformable_func = use_deformable_func\n        if depth_branch is not None:\n            self.depth_branch = build_from_cfg(depth_branch, PLUGIN_LAYERS)\n        else:\n            self.depth_branch = None\n        if use_grid_mask:\n            self.grid_mask = GridMask(\n                True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7\n            )\n        if freeze_backbone:\n            self.img_backbone.eval()\n            for param in self.img_backbone.parameters():\n                param.requires_grad = False\n        if freeze_neck:\n            self.img_neck.eval()\n            for param in self.img_neck.parameters():\n                param.requires_grad = False\n        if freeze_perception:\n            self.head.det_head.eval()\n            for param in self.head.det_head.parameters():\n                param.requires_grad = False\n            self.head.map_head.eval()\n            for param in self.head.map_head.parameters():\n                param.requires_grad = False\n         \n\n    @auto_fp16(apply_to=(\"img\",), out_fp32=True)\n    def extract_feat(self, img, return_depth=False, metas=None):\n        bs = img.shape[0]\n        if img.dim() == 5:  # multi-view\n            num_cams = img.shape[1]\n            img = img.flatten(end_dim=1)\n        else:\n            num_cams = 1\n        if self.use_grid_mask:\n            img = self.grid_mask(img)\n        if \"metas\" in signature(self.img_backbone.forward).parameters:\n            feature_maps = self.img_backbone(img, num_cams, metas=metas)\n        else:\n            feature_maps = self.img_backbone(img)\n        if self.img_neck is not None:\n            feature_maps = list(self.img_neck(feature_maps))\n        for i, feat in enumerate(feature_maps):\n            feature_maps[i] = torch.reshape(\n                feat, (bs, num_cams) + feat.shape[1:]\n            )\n        if return_depth and self.depth_branch is not None:\n            depths = self.depth_branch(feature_maps, metas.get(\"focal\"))\n        else:\n            depths = None\n        if self.use_deformable_func:\n            feature_maps = feature_maps_format(feature_maps)\n        if return_depth:\n            return feature_maps, depths\n        return feature_maps\n\n    @force_fp32(apply_to=(\"img\",))\n    def forward(self, img, **data):\n        if self.training:\n            return self.forward_train(img, **data)\n        else:\n            return self.forward_test(img, **data)\n\n    def forward_train(self, img, **data):\n        #import pdb;pdb.set_trace()\n        feature_maps, depths = self.extract_feat(img, True, data)\n        model_outs = self.head(feature_maps, data)\n        output = self.head.loss(model_outs, data)\n        if depths is not None and \"gt_depth\" in data:\n            output[\"loss_dense_depth\"] = self.depth_branch.loss(\n                depths, data[\"gt_depth\"]\n            )\n        return output\n\n    def forward_test(self, img, **data):\n        if isinstance(img, list):\n            return self.aug_test(img, **data)\n        else:\n            return self.simple_test(img, **data)\n\n    def simple_test(self, img, **data):\n        feature_maps = self.extract_feat(img)\n\n        model_outs = self.head(feature_maps, data)\n        results = self.head.post_process(model_outs, data)\n        output = [{\"img_bbox\": result} for result in results]\n        #import pdb;pdb.set_trace()\n        return output\n\n    def aug_test(self, img, **data):\n        # fake test time augmentation\n        for key in data.keys():\n            if isinstance(data[key], list):\n                data[key] = data[key][0]\n        return self.simple_test(img[0], **data)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/MomAD_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.runner import BaseModule\nfrom mmdet.models import HEADS\nfrom mmdet.models import build_head\n\n\n@HEADS.register_module()\nclass MomADHead(BaseModule):\n    def __init__(\n        self,\n        task_config: dict,\n        det_head = dict,\n        map_head = dict,\n        motion_plan_head = dict,\n        init_cfg=None,\n        **kwargs,\n    ):\n        super(MomADHead, self).__init__(init_cfg)\n        self.task_config = task_config\n        if self.task_config['with_det']:\n            self.det_head = build_head(det_head)\n        if self.task_config['with_map']:\n            self.map_head = build_head(map_head)\n        if self.task_config['with_motion_plan']:\n            self.motion_plan_head = build_head(motion_plan_head)\n\n    def init_weights(self):\n        if self.task_config['with_det']:\n            self.det_head.init_weights()\n        if self.task_config['with_map']:\n            self.map_head.init_weights()\n        if self.task_config['with_motion_plan']:\n            self.motion_plan_head.init_weights()\n\n    def forward(\n        self,\n        feature_maps: Union[torch.Tensor, List],\n        metas: dict,\n    ):\n        if self.task_config['with_det']:\n            det_output = self.det_head(feature_maps, metas)\n        else:\n            det_output = None\n\n        if self.task_config['with_map']:\n            map_output = self.map_head(feature_maps, metas)\n        else:\n            map_output = None\n        \n        if self.task_config['with_motion_plan']:\n            motion_output, planning_output = self.motion_plan_head(\n                det_output, \n                map_output, \n                feature_maps,\n                metas,\n                self.det_head.anchor_encoder,\n                self.det_head.instance_bank.mask,\n                self.det_head.instance_bank.anchor_handler,\n            )\n        else:\n            motion_output, planning_output = None, None\n\n        return det_output, map_output, motion_output, planning_output\n\n    def loss(self, model_outs, data):\n        det_output, map_output, motion_output, planning_output = model_outs\n        losses = dict()\n        if self.task_config['with_det']:\n            loss_det = self.det_head.loss(det_output, data)\n            losses.update(loss_det)\n        \n        if self.task_config['with_map']:\n            loss_map = self.map_head.loss(map_output, data)\n            losses.update(loss_map)\n\n        if self.task_config['with_motion_plan']:\n            motion_loss_cache = dict(\n                indices=self.det_head.sampler.indices, \n            )\n            loss_motion = self.motion_plan_head.loss(\n                motion_output, \n                planning_output, \n                data, \n                motion_loss_cache\n            )\n            losses.update(loss_motion)\n        \n        return losses\n\n    def post_process(self, model_outs, data):\n        det_output, map_output, motion_output, planning_output = model_outs\n        if self.task_config['with_det']:\n            det_result = self.det_head.post_process(det_output)\n            batch_size = len(det_result)\n        \n        if self.task_config['with_map']:\n            map_result= self.map_head.post_process(map_output)\n            batch_size = len(map_result)\n\n        if self.task_config['with_motion_plan']:\n            motion_result, planning_result = self.motion_plan_head.post_process(\n                det_output,\n                motion_output, \n                planning_output,\n                data,\n            )\n\n        results = [dict()] * batch_size\n        for i in range(batch_size):\n            if self.task_config['with_det']:\n                results[i].update(det_result[i])\n            if self.task_config['with_map']:\n                results[i].update(map_result[i])\n            if self.task_config['with_motion_plan']:\n                results[i].update(motion_result[i])\n                results[i].update(planning_result[i])\n\n        return results\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/__init__.py",
    "content": "from .sparsedrive import SparseDrive\nfrom .MomAD import MomAD\nfrom .sparsedrive_head import SparseDriveHead\nfrom .MomAD_head import MomADHead\nfrom .blocks import (\n    DeformableFeatureAggregation,\n    DenseDepthNet,\n    AsymmetricFFN,\n)\nfrom .instance_bank import InstanceBank\nfrom .detection3d import (\n    SparseBox3DDecoder,\n    SparseBox3DTarget,\n    SparseBox3DRefinementModule,\n    SparseBox3DKeyPointsGenerator,\n    SparseBox3DEncoder,\n)\nfrom .map import *\nfrom .motion import *\n\n\n__all__ = [\n    \"SparseDrive\",\n    \"SparseDriveHead\",\n    \"DeformableFeatureAggregation\",\n    \"DenseDepthNet\",\n    \"AsymmetricFFN\",\n    \"InstanceBank\",\n    \"SparseBox3DDecoder\",\n    \"SparseBox3DTarget\",\n    \"SparseBox3DRefinementModule\",\n    \"SparseBox3DKeyPointsGenerator\",\n    \"SparseBox3DEncoder\",\n]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/attention.py",
    "content": "import warnings\nimport math\n\nimport torch\nimport torch.nn as nn\nfrom torch.nn.functional import linear\nfrom torch.nn.init import xavier_uniform_, constant_\n\nfrom mmcv.utils import deprecated_api_warning\nfrom mmcv.runner import auto_fp16\nfrom mmcv.runner.base_module import BaseModule\nfrom mmcv.cnn.bricks.drop import build_dropout\nfrom mmcv.cnn.bricks.registry import ATTENTION\nimport torch.utils.checkpoint as cp\n\n\nfrom einops import rearrange\ntry:\n    from flash_attn.flash_attn_interface import flash_attn_unpadded_kvpacked_func\n    print('Use flash_attn_unpadded_kvpacked_func')\nexcept:\n    from flash_attn.flash_attn_interface import  flash_attn_varlen_kvpacked_func as flash_attn_unpadded_kvpacked_func\n    print('Use flash_attn_varlen_kvpacked_func')\nfrom flash_attn.bert_padding import unpad_input, pad_input, index_first_axis\n\n\ndef _in_projection_packed(q, k, v, w, b = None):\n    w_q, w_k, w_v = w.chunk(3)\n    if b is None:\n        b_q = b_k = b_v = None\n    else:\n        b_q, b_k, b_v = b.chunk(3)\n    return linear(q, w_q, b_q), linear(k, w_k, b_k), linear(v, w_v, b_v)\n\n\nclass FlashAttention(nn.Module):\n    \"\"\"Implement the scaled dot product attention with softmax.\n    Arguments\n    ---------\n        softmax_scale: The temperature to use for the softmax attention.\n                      (default: 1/sqrt(d_keys) where d_keys is computed at\n                      runtime)\n        attention_dropout: The dropout rate to apply to the attention\n                           (default: 0.1)\n    \"\"\"\n    def __init__(self, softmax_scale=None, attention_dropout=0.0, device=None, dtype=None):\n        super().__init__()\n        self.softmax_scale = softmax_scale\n        self.dropout_p = attention_dropout\n        self.fp16_enabled = True\n\n    @auto_fp16(apply_to=('q', 'kv'), out_fp32=True)\n    def forward(self, q, kv, \n                causal=False, \n                key_padding_mask=None):\n        \"\"\"Implements the multihead softmax attention.\n        Arguments\n        ---------\n            q: The tensor containing the query. (B, T, H, D) \n            kv: The tensor containing the key, and value. (B, S, 2, H, D) \n            key_padding_mask: a bool tensor of shape (B, S)\n        \"\"\"\n        assert q.dtype in [torch.float16, torch.bfloat16] and kv.dtype in [torch.float16, torch.bfloat16]\n        assert q.is_cuda and kv.is_cuda\n        assert q.shape[0] == kv.shape[0] and q.shape[-2] == kv.shape[-2] and q.shape[-1] == kv.shape[-1]\n\n        batch_size = q.shape[0]\n        seqlen_q, seqlen_k = q.shape[1], kv.shape[1]\n        if key_padding_mask is None:\n            q, kv = rearrange(q, 'b s ... -> (b s) ...'), rearrange(kv, 'b s ... -> (b s) ...')\n            max_sq, max_sk = seqlen_q, seqlen_k \n            cu_seqlens_q = torch.arange(0, (batch_size + 1) * seqlen_q, step=seqlen_q, dtype=torch.int32,\n                                    device=q.device)\n            cu_seqlens_k = torch.arange(0, (batch_size + 1) * seqlen_k, step=seqlen_k, dtype=torch.int32,\n                                    device=kv.device)                    \n            output = flash_attn_unpadded_kvpacked_func(\n                q, kv, cu_seqlens_q, cu_seqlens_k, max_sq, max_sk,\n                self.dropout_p if self.training else 0.0,\n                softmax_scale=self.softmax_scale, causal=causal\n            )\n            output = rearrange(output, '(b s) ... -> b s ...', b=batch_size)\n        else:\n            nheads = kv.shape[-2]\n            q = rearrange(q, 'b s ... -> (b s) ...')\n            max_sq = seqlen_q\n            cu_seqlens_q = torch.arange(0, (batch_size + 1) * seqlen_q, step=seqlen_q, dtype=torch.int32,\n                                    device=q.device)\n            x = rearrange(kv, 'b s two h d -> b s (two h d)')\n            x_unpad, indices, cu_seqlens_k, max_sk = unpad_input(x, key_padding_mask)\n            x_unpad = rearrange(x_unpad, 'nnz (two h d) -> nnz two h d', two=2, h=nheads)\n            output_unpad = flash_attn_unpadded_kvpacked_func(\n                q, x_unpad, cu_seqlens_q, cu_seqlens_k, max_sq, max_sk,\n                self.dropout_p if self.training else 0.0,\n                softmax_scale=self.softmax_scale, causal=causal\n            )\n            output = rearrange(output_unpad, '(b s) ... -> b s ...', b=batch_size)\n\n        return output, None\n\n\nclass FlashMHA(nn.Module):\n\n    def __init__(self, embed_dim, num_heads, bias=True, batch_first=True, attention_dropout=0.0,\n                 causal=False, device=None, dtype=None, **kwargs) -> None:\n        assert batch_first\n        factory_kwargs = {'device': device, 'dtype': dtype}\n        super().__init__()\n        self.embed_dim = embed_dim\n        self.causal = causal\n        self.bias = bias\n\n        self.num_heads = num_heads\n        assert self.embed_dim % num_heads == 0, \"self.kdim must be divisible by num_heads\"\n        self.head_dim = self.embed_dim // num_heads\n        assert self.head_dim % 8 == 0 and self.head_dim <= 128, \"Only support head_dim <= 128 and divisible by 8\"\n\n        self.in_proj_weight = nn.Parameter(torch.empty((3 * embed_dim, embed_dim)))\n        if bias:\n            self.in_proj_bias = nn.Parameter(torch.empty(3 * embed_dim))\n        else:\n            self.register_parameter('in_proj_bias', None)\n        self.inner_attn = FlashAttention(attention_dropout=attention_dropout, **factory_kwargs)\n        self.out_proj = nn.Linear(embed_dim, embed_dim, bias=bias)\n        self._reset_parameters()\n\n    def _reset_parameters(self) -> None:\n        xavier_uniform_(self.in_proj_weight)\n        if self.in_proj_bias is not None:\n            constant_(self.in_proj_bias, 0.)\n            constant_(self.out_proj.bias, 0.)\n        \n    def forward(self, q, k, v, key_padding_mask=None):\n        \"\"\"x: (batch, seqlen, hidden_dim) (where hidden_dim = num heads * head dim)\n        key_padding_mask: bool tensor of shape (batch, seqlen)\n        \"\"\"\n        q, k, v = _in_projection_packed(q, k, v, self.in_proj_weight, self.in_proj_bias)\n        q = rearrange(q, 'b s (h d) -> b s h d', h=self.num_heads)\n        k = rearrange(k, 'b s (h d) -> b s h d', h=self.num_heads)\n        v = rearrange(v, 'b s (h d) -> b s h d', h=self.num_heads)\n        kv = torch.stack([k, v], dim=2)\n        \n        context, attn_weights = self.inner_attn(q, kv, key_padding_mask=key_padding_mask, causal=self.causal)\n        return self.out_proj(rearrange(context, 'b s h d -> b s (h d)')), attn_weights\n\n\n@ATTENTION.register_module()\nclass MultiheadFlashAttention(BaseModule):\n    \"\"\"A wrapper for ``torch.nn.MultiheadAttention``.\n    This module implements MultiheadAttention with identity connection,\n    and positional encoding  is also passed as input.\n    Args:\n        embed_dims (int): The embedding dimension.\n        num_heads (int): Parallel attention heads.\n        attn_drop (float): A Dropout layer on attn_output_weights.\n            Default: 0.0.\n        proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.\n            Default: 0.0.\n        dropout_layer (agent:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (agent:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): When it is True,  Key, Query and Value are shape of\n            (batch, n, embed_dim), otherwise (n, batch, embed_dim).\n             Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims,\n                 num_heads,\n                 attn_drop=0.,\n                 proj_drop=0.,\n                 dropout_layer=dict(type='Dropout', drop_prob=0.),\n                 init_cfg=None,\n                 batch_first=True,\n                 **kwargs):\n        super(MultiheadFlashAttention, self).__init__(init_cfg)\n        if 'dropout' in kwargs:\n            warnings.warn(\n                'The arguments `dropout` in MultiheadAttention '\n                'has been deprecated, now you can separately '\n                'set `attn_drop`(float), proj_drop(float), '\n                'and `dropout_layer`(dict) ', DeprecationWarning)\n            attn_drop = kwargs['dropout']\n            dropout_layer['drop_prob'] = kwargs.pop('dropout')\n\n        self.embed_dims = embed_dims\n        self.num_heads = num_heads\n        self.batch_first = True\n        self.attn = FlashMHA(\n            embed_dim=embed_dims, \n            num_heads=num_heads, \n            attention_dropout=attn_drop, \n            dtype=torch.float16, \n            device='cuda',\n            **kwargs\n        )\n\n        self.proj_drop = nn.Dropout(proj_drop)\n        self.dropout_layer = build_dropout(\n            dropout_layer) if dropout_layer else nn.Identity()\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiheadAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_pos=None,\n                attn_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `MultiheadAttention`.\n        **kwargs allow passing a more general data flow when combining\n        with other operations in `transformerlayer`.\n        Args:\n            query (Tensor): The input query with shape [num_queries, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n                If None, the ``query`` will be used. Defaults to None.\n            value (Tensor): The value tensor with same shape as `key`.\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n                If None, the `key` will be used.\n            identity (Tensor): This tensor, with the same shape as x,\n                will be used for the identity link.\n                If None, `x` will be used. Defaults to None.\n            query_pos (Tensor): The positional encoding for query, with\n                the same shape as `x`. If not None, it will\n                be added to `x` before forward function. Defaults to None.\n            key_pos (Tensor): The positional encoding for `key`, with the\n                same shape as `key`. Defaults to None. If not None, it will\n                be added to `key` before forward function. If None, and\n                `query_pos` has the same shape as `key`, then `query_pos`\n                will be used for `key_pos`. Defaults to None.\n            attn_mask (Tensor): ByteTensor mask with shape [num_queries,\n                num_keys]. Same in `nn.MultiheadAttention.forward`.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].\n                Defaults to None.\n        Returns:\n            Tensor: forwarded results with shape\n            [num_queries, bs, embed_dims]\n            if self.batch_first is False, else\n            [bs, num_queries embed_dims].\n        \"\"\"\n        assert attn_mask is None, 'attn mask not supported now.'\n        if key is None:\n            key = query\n        if value is None:\n            value = key\n        if identity is None:\n            identity = query\n        if key_pos is None:\n            if query_pos is not None:\n                # use query_pos if key_pos is not available\n                if query_pos.shape == key.shape:\n                    key_pos = query_pos\n                else:\n                    warnings.warn(f'position encoding of key is'\n                                  f'missing in {self.__class__.__name__}.')\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n\n        # The dataflow('key', 'query', 'value') of ``FlashAttention`` is (batch, num_query, embed_dims).\n        if not self.batch_first:\n            query = query.transpose(0, 1)\n            key = key.transpose(0, 1)\n            value = value.transpose(0, 1)\n        \n        out = self.attn(\n            q=query,\n            k=key,\n            v=value,\n            key_padding_mask=key_padding_mask)[0]\n\n        if not self.batch_first:\n            out = out.transpose(0, 1)\n\n        return identity + self.dropout_layer(self.proj_drop(out))\n\n\ndef gen_sineembed_for_position(pos_tensor, hidden_dim=256):\n    \"\"\"Mostly copy-paste from https://github.com/IDEA-opensource/DAB-DETR/\n    \"\"\"\n    half_hidden_dim = hidden_dim // 2\n    scale = 2 * math.pi\n    dim_t = torch.arange(half_hidden_dim, dtype=torch.float32, device=pos_tensor.device)\n    dim_t = 10000 ** (2 * (dim_t // 2) / half_hidden_dim)\n    x_embed = pos_tensor[..., 0] * scale\n    y_embed = pos_tensor[..., 1] * scale\n    pos_x = x_embed[..., None] / dim_t\n    pos_y = y_embed[..., None] / dim_t\n    pos_x = torch.stack((pos_x[..., 0::2].sin(), pos_x[..., 1::2].cos()), dim=-1).flatten(-2)\n    pos_y = torch.stack((pos_y[..., 0::2].sin(), pos_y[..., 1::2].cos()), dim=-1).flatten(-2)\n    pos = torch.cat((pos_y, pos_x), dim=-1)\n    return pos\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/base_target.py",
    "content": "from abc import ABC, abstractmethod\n\n\n__all__ = [\"BaseTargetWithDenoising\"]\n\n\nclass BaseTargetWithDenoising(ABC):\n    def __init__(self, num_dn_groups=0, num_temp_dn_groups=0):\n        super(BaseTargetWithDenoising, self).__init__()\n        self.num_dn_groups = num_dn_groups\n        self.num_temp_dn_groups = num_temp_dn_groups\n        self.dn_metas = None\n\n    @abstractmethod\n    def sample(self, cls_pred, box_pred, cls_target, box_target):\n        \"\"\"\n        Perform Hungarian matching between predictions and ground truth,\n        returning the matched ground truth corresponding to the predictions\n        along with the corresponding regression weights.\n        \"\"\"\n\n    def get_dn_anchors(self, cls_target, box_target, *args, **kwargs):\n        \"\"\"\n        Generate noisy instances for the current frame, with a total of\n        'self.num_dn_groups' groups.\n        \"\"\"\n        return None\n\n    def update_dn(self, instance_feature, anchor, *args, **kwargs):\n        \"\"\"\n        Insert the previously saved 'self.dn_metas' into the noisy instances\n        of the current frame.\n        \"\"\"\n\n    def cache_dn(\n        self,\n        dn_instance_feature,\n        dn_anchor,\n        dn_cls_target,\n        valid_mask,\n        dn_id_target,\n    ):\n        \"\"\"\n        Randomly save information for 'self.num_temp_dn_groups' groups of\n        temporal noisy instances to 'self.dn_metas'.\n        \"\"\"\n        if self.num_temp_dn_groups < 0:\n            return\n        self.dn_metas = dict(dn_anchor=dn_anchor[:, : self.num_temp_dn_groups])\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/blocks.py",
    "content": "from typing import List, Optional, Tuple\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nfrom torch.cuda.amp.autocast_mode import autocast\n\nfrom mmcv.cnn import Linear, build_activation_layer, build_norm_layer\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn.bricks.transformer import FFN\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.drop import build_dropout\nfrom mmcv.cnn import xavier_init, constant_init\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    FEEDFORWARD_NETWORK,\n)\n\ntry:\n    from ..ops import deformable_aggregation_function as DAF\nexcept:\n    DAF = None\n\n__all__ = [\n    \"DeformableFeatureAggregation\",\n    \"DenseDepthNet\",\n    \"AsymmetricFFN\",\n]\n\n\ndef linear_relu_ln(embed_dims, in_loops, out_loops, input_dims=None):\n    if input_dims is None:\n        input_dims = embed_dims\n    layers = []\n    for _ in range(out_loops):\n        for _ in range(in_loops):\n            layers.append(Linear(input_dims, embed_dims))\n            layers.append(nn.ReLU(inplace=True))\n            input_dims = embed_dims\n        layers.append(nn.LayerNorm(embed_dims))\n    return layers\n\n\n@ATTENTION.register_module()\nclass DeformableFeatureAggregation(BaseModule):\n    def __init__(\n        self,\n        embed_dims: int = 256,\n        num_groups: int = 8,\n        num_levels: int = 4,\n        num_cams: int = 6,\n        proj_drop: float = 0.0,\n        attn_drop: float = 0.0,\n        kps_generator: dict = None,\n        temporal_fusion_module=None,\n        use_temporal_anchor_embed=True,\n        use_deformable_func=False,\n        use_camera_embed=False,\n        residual_mode=\"add\",\n    ):\n        super(DeformableFeatureAggregation, self).__init__()\n        if embed_dims % num_groups != 0:\n            raise ValueError(\n                f\"embed_dims must be divisible by num_groups, \"\n                f\"but got {embed_dims} and {num_groups}\"\n            )\n        self.group_dims = int(embed_dims / num_groups)\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_groups = num_groups\n        self.num_cams = num_cams\n        self.use_temporal_anchor_embed = use_temporal_anchor_embed\n        if use_deformable_func:\n            assert DAF is not None, \"deformable_aggregation needs to be set up.\"\n        self.use_deformable_func = use_deformable_func\n        self.attn_drop = attn_drop\n        self.residual_mode = residual_mode\n        self.proj_drop = nn.Dropout(proj_drop)\n        kps_generator[\"embed_dims\"] = embed_dims\n        self.kps_generator = build_from_cfg(kps_generator, PLUGIN_LAYERS)\n        self.num_pts = self.kps_generator.num_pts\n        if temporal_fusion_module is not None:\n            if \"embed_dims\" not in temporal_fusion_module:\n                temporal_fusion_module[\"embed_dims\"] = embed_dims\n            self.temp_module = build_from_cfg(\n                temporal_fusion_module, PLUGIN_LAYERS\n            )\n        else:\n            self.temp_module = None\n        self.output_proj = Linear(embed_dims, embed_dims)\n\n        if use_camera_embed:\n            self.camera_encoder = Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 12)\n            )\n            self.weights_fc = Linear(\n                embed_dims, num_groups * num_levels * self.num_pts\n            )\n        else:\n            self.camera_encoder = None\n            self.weights_fc = Linear(\n                embed_dims, num_groups * num_cams * num_levels * self.num_pts\n            )\n\n    def init_weight(self):\n        constant_init(self.weights_fc, val=0.0, bias=0.0)\n        xavier_init(self.output_proj, distribution=\"uniform\", bias=0.0)\n\n    def forward(\n        self,\n        instance_feature: torch.Tensor,\n        anchor: torch.Tensor,\n        anchor_embed: torch.Tensor,\n        feature_maps: List[torch.Tensor],\n        metas: dict,\n        **kwargs: dict,\n    ):\n        bs, num_anchor = instance_feature.shape[:2]\n        key_points = self.kps_generator(anchor, instance_feature)\n        weights = self._get_weights(instance_feature, anchor_embed, metas)\n\n        if self.use_deformable_func:\n            points_2d = (\n                self.project_points(\n                    key_points,\n                    metas[\"projection_mat\"],\n                    metas.get(\"image_wh\"),\n                )\n                .permute(0, 2, 3, 1, 4)\n                .reshape(bs, num_anchor, self.num_pts, self.num_cams, 2)\n            )\n            weights = (\n                weights.permute(0, 1, 4, 2, 3, 5)\n                .contiguous()\n                .reshape(\n                    bs,\n                    num_anchor,\n                    self.num_pts,\n                    self.num_cams,\n                    self.num_levels,\n                    self.num_groups,\n                )\n            )\n            features = DAF(*feature_maps, points_2d, weights).reshape(\n                bs, num_anchor, self.embed_dims\n            )\n        else:\n            features = self.feature_sampling(\n                feature_maps,\n                key_points,\n                metas[\"projection_mat\"],\n                metas.get(\"image_wh\"),\n            )\n            features = self.multi_view_level_fusion(features, weights)\n            features = features.sum(dim=2)  # fuse multi-point features\n        output = self.proj_drop(self.output_proj(features))\n        if self.residual_mode == \"add\":\n            output = output + instance_feature\n        elif self.residual_mode == \"cat\":\n            output = torch.cat([output, instance_feature], dim=-1)\n        return output\n\n    def _get_weights(self, instance_feature, anchor_embed, metas=None):\n        bs, num_anchor = instance_feature.shape[:2]\n        feature = instance_feature + anchor_embed\n        if self.camera_encoder is not None:\n            camera_embed = self.camera_encoder(\n                metas[\"projection_mat\"][:, :, :3].reshape(\n                    bs, self.num_cams, -1\n                )\n            )\n            feature = feature[:, :, None] + camera_embed[:, None]\n\n        weights = (\n            self.weights_fc(feature)\n            .reshape(bs, num_anchor, -1, self.num_groups)\n            .softmax(dim=-2)\n            .reshape(\n                bs,\n                num_anchor,\n                self.num_cams,\n                self.num_levels,\n                self.num_pts,\n                self.num_groups,\n            )\n        )\n        if self.training and self.attn_drop > 0:\n            mask = torch.rand(\n                bs, num_anchor, self.num_cams, 1, self.num_pts, 1\n            )\n            mask = mask.to(device=weights.device, dtype=weights.dtype)\n            weights = ((mask > self.attn_drop) * weights) / (\n                1 - self.attn_drop\n            )\n        return weights\n\n    @staticmethod\n    def project_points(key_points, projection_mat, image_wh=None):\n        bs, num_anchor, num_pts = key_points.shape[:3]\n\n        pts_extend = torch.cat(\n            [key_points, torch.ones_like(key_points[..., :1])], dim=-1\n        )\n        points_2d = torch.matmul(\n            projection_mat[:, :, None, None], pts_extend[:, None, ..., None]\n        ).squeeze(-1)\n        points_2d = points_2d[..., :2] / torch.clamp(\n            points_2d[..., 2:3], min=1e-5\n        )\n        if image_wh is not None:\n            points_2d = points_2d / image_wh[:, :, None, None]\n        return points_2d\n\n    @staticmethod\n    def feature_sampling(\n        feature_maps: List[torch.Tensor],\n        key_points: torch.Tensor,\n        projection_mat: torch.Tensor,\n        image_wh: Optional[torch.Tensor] = None,\n    ) -> torch.Tensor:\n        num_levels = len(feature_maps)\n        num_cams = feature_maps[0].shape[1]\n        bs, num_anchor, num_pts = key_points.shape[:3]\n\n        points_2d = DeformableFeatureAggregation.project_points(\n            key_points, projection_mat, image_wh\n        )\n        points_2d = points_2d * 2 - 1\n        points_2d = points_2d.flatten(end_dim=1)\n\n        features = []\n        for fm in feature_maps:\n            features.append(\n                torch.nn.functional.grid_sample(\n                    fm.flatten(end_dim=1), points_2d\n                )\n            )\n        features = torch.stack(features, dim=1)\n        features = features.reshape(\n            bs, num_cams, num_levels, -1, num_anchor, num_pts\n        ).permute(\n            0, 4, 1, 2, 5, 3\n        )  # bs, num_anchor, num_cams, num_levels, num_pts, embed_dims\n\n        return features\n\n    def multi_view_level_fusion(\n        self,\n        features: torch.Tensor,\n        weights: torch.Tensor,\n    ):\n        bs, num_anchor = weights.shape[:2]\n        features = weights[..., None] * features.reshape(\n            features.shape[:-1] + (self.num_groups, self.group_dims)\n        )\n        features = features.sum(dim=2).sum(dim=2)\n        features = features.reshape(\n            bs, num_anchor, self.num_pts, self.embed_dims\n        )\n        return features\n\n\n@PLUGIN_LAYERS.register_module()\nclass DenseDepthNet(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        num_depth_layers=1,\n        equal_focal=100,\n        max_depth=60,\n        loss_weight=1.0,\n    ):\n        super().__init__()\n        self.embed_dims = embed_dims\n        self.equal_focal = equal_focal\n        self.num_depth_layers = num_depth_layers\n        self.max_depth = max_depth\n        self.loss_weight = loss_weight\n\n        self.depth_layers = nn.ModuleList()\n        for i in range(num_depth_layers):\n            self.depth_layers.append(\n                nn.Conv2d(embed_dims, 1, kernel_size=1, stride=1, padding=0)\n            )\n\n    def forward(self, feature_maps, focal=None, gt_depths=None):\n        if focal is None:\n            focal = self.equal_focal\n        else:\n            focal = focal.reshape(-1)\n        depths = []\n        for i, feat in enumerate(feature_maps[: self.num_depth_layers]):\n            depth = self.depth_layers[i](feat.flatten(end_dim=1).float()).exp()\n            depth = depth.transpose(0, -1) * focal / self.equal_focal\n            depth = depth.transpose(0, -1)\n            depths.append(depth)\n        if gt_depths is not None and self.training:\n            loss = self.loss(depths, gt_depths)\n            return loss\n        return depths\n\n    def loss(self, depth_preds, gt_depths):\n        loss = 0.0\n        for pred, gt in zip(depth_preds, gt_depths):\n            pred = pred.permute(0, 2, 3, 1).contiguous().reshape(-1)\n            gt = gt.reshape(-1)\n            fg_mask = torch.logical_and(\n                gt > 0.0, torch.logical_not(torch.isnan(pred))\n            )\n            gt = gt[fg_mask]\n            pred = pred[fg_mask]\n            pred = torch.clip(pred, 0.0, self.max_depth)\n            with autocast(enabled=False):\n                error = torch.abs(pred - gt).sum()\n                _loss = (\n                    error\n                    / max(1.0, len(gt) * len(depth_preds))\n                    * self.loss_weight\n                )\n            loss = loss + _loss\n        return loss\n\n\n@FEEDFORWARD_NETWORK.register_module()\nclass AsymmetricFFN(BaseModule):\n    def __init__(\n        self,\n        in_channels=None,\n        pre_norm=None,\n        embed_dims=256,\n        feedforward_channels=1024,\n        num_fcs=2,\n        act_cfg=dict(type=\"ReLU\", inplace=True),\n        ffn_drop=0.0,\n        dropout_layer=None,\n        add_identity=True,\n        init_cfg=None,\n        **kwargs,\n    ):\n        super(AsymmetricFFN, self).__init__(init_cfg)\n        assert num_fcs >= 2, (\n            \"num_fcs should be no less \" f\"than 2. got {num_fcs}.\"\n        )\n        self.in_channels = in_channels\n        self.pre_norm = pre_norm\n        self.embed_dims = embed_dims\n        self.feedforward_channels = feedforward_channels\n        self.num_fcs = num_fcs\n        self.act_cfg = act_cfg\n        self.activate = build_activation_layer(act_cfg)\n\n        layers = []\n        if in_channels is None:\n            in_channels = embed_dims\n        if pre_norm is not None:\n            self.pre_norm = build_norm_layer(pre_norm, in_channels)[1]\n\n        for _ in range(num_fcs - 1):\n            layers.append(\n                Sequential(\n                    Linear(in_channels, feedforward_channels),\n                    self.activate,\n                    nn.Dropout(ffn_drop),\n                )\n            )\n            in_channels = feedforward_channels\n        layers.append(Linear(feedforward_channels, embed_dims))\n        layers.append(nn.Dropout(ffn_drop))\n        self.layers = Sequential(*layers)\n        self.dropout_layer = (\n            build_dropout(dropout_layer)\n            if dropout_layer\n            else torch.nn.Identity()\n        )\n        self.add_identity = add_identity\n        if self.add_identity:\n            self.identity_fc = (\n                torch.nn.Identity()\n                if in_channels == embed_dims\n                else Linear(self.in_channels, embed_dims)\n            )\n\n    def forward(self, x, identity=None):\n        if self.pre_norm is not None:\n            x = self.pre_norm(x)\n        out = self.layers(x)\n        if not self.add_identity:\n            return self.dropout_layer(out)\n        if identity is None:\n            identity = x\n        identity = self.identity_fc(identity)\n        return identity + self.dropout_layer(out)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/detection3d/__init__.py",
    "content": "from .decoder import SparseBox3DDecoder\nfrom .target import SparseBox3DTarget\nfrom .detection3d_blocks import (\n    SparseBox3DRefinementModule,\n    SparseBox3DKeyPointsGenerator,\n    SparseBox3DEncoder,\n)\nfrom .losses import SparseBox3DLoss\nfrom .detection3d_head import Sparse4DHead\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/detection3d/decoder.py",
    "content": "from typing import Optional\n\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\nfrom mmdet3d_plugin.core.box3d import *\n\ndef decode_box(box):\n    yaw = torch.atan2(box[..., SIN_YAW], box[..., COS_YAW])\n    box = torch.cat(\n        [\n            box[..., [X, Y, Z]],\n            box[..., [W, L, H]].exp(),\n            yaw[..., None],\n            box[..., VX:],\n        ],\n        dim=-1,\n    )\n    return box\n\n\n@BBOX_CODERS.register_module()\nclass SparseBox3DDecoder(object):\n    def __init__(\n        self,\n        num_output: int = 300,\n        score_threshold: Optional[float] = None,\n        sorted: bool = True,\n    ):\n        super(SparseBox3DDecoder, self).__init__()\n        self.num_output = num_output\n        self.score_threshold = score_threshold\n        self.sorted = sorted\n\n    def decode(\n        self,\n        cls_scores,\n        box_preds,\n        instance_id=None,\n        quality=None,\n        output_idx=-1,\n    ):\n        squeeze_cls = instance_id is not None\n\n        cls_scores = cls_scores[output_idx].sigmoid()\n\n        if squeeze_cls:\n            cls_scores, cls_ids = cls_scores.max(dim=-1)\n            cls_scores = cls_scores.unsqueeze(dim=-1)\n\n        box_preds = box_preds[output_idx]\n        bs, num_pred, num_cls = cls_scores.shape\n        cls_scores, indices = cls_scores.flatten(start_dim=1).topk(\n            self.num_output, dim=1, sorted=self.sorted\n        )\n        if not squeeze_cls:\n            cls_ids = indices % num_cls\n        if self.score_threshold is not None:\n            mask = cls_scores >= self.score_threshold\n\n        if quality[output_idx] is None:\n            quality = None\n        if quality is not None:\n            centerness = quality[output_idx][..., CNS]\n            centerness = torch.gather(centerness, 1, indices // num_cls)\n            cls_scores_origin = cls_scores.clone()\n            cls_scores *= centerness.sigmoid()\n            cls_scores, idx = torch.sort(cls_scores, dim=1, descending=True)\n            if not squeeze_cls:\n                cls_ids = torch.gather(cls_ids, 1, idx)\n            if self.score_threshold is not None:\n                mask = torch.gather(mask, 1, idx)\n            indices = torch.gather(indices, 1, idx)\n\n        output = []\n        for i in range(bs):\n            category_ids = cls_ids[i]\n            if squeeze_cls:\n                category_ids = category_ids[indices[i]]\n            scores = cls_scores[i]\n            box = box_preds[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                category_ids = category_ids[mask[i]]\n                scores = scores[mask[i]]\n                box = box[mask[i]]\n            if quality is not None:\n                scores_origin = cls_scores_origin[i]\n                if self.score_threshold is not None:\n                    scores_origin = scores_origin[mask[i]]\n\n            box = decode_box(box)\n            output.append(\n                {\n                    \"boxes_3d\": box.cpu(),\n                    \"scores_3d\": scores.cpu(),\n                    \"labels_3d\": category_ids.cpu(),\n                }\n            )\n            if quality is not None:\n                output[-1][\"cls_scores\"] = scores_origin.cpu()\n            if instance_id is not None:\n                ids = instance_id[i, indices[i]]\n                if self.score_threshold is not None:\n                    ids = ids[mask[i]]\n                output[-1][\"instance_ids\"] = ids.cpu()\n        return output\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/detection3d/detection3d_blocks.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\n\nfrom mmcv.cnn import Linear, Scale, bias_init_with_prob\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.registry import (\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n)\n\nfrom mmdet3d_plugin.core.box3d import *\nfrom ..blocks import linear_relu_ln\n\n__all__ = [\n    \"SparseBox3DRefinementModule\",\n    \"SparseBox3DKeyPointsGenerator\",\n    \"SparseBox3DEncoder\",\n]\n\n\n@POSITIONAL_ENCODING.register_module()\nclass SparseBox3DEncoder(BaseModule):\n    def __init__(\n        self,\n        embed_dims,\n        vel_dims=3,\n        mode=\"add\",\n        output_fc=True,\n        in_loops=1,\n        out_loops=2,\n    ):\n        super().__init__()\n        assert mode in [\"add\", \"cat\"]\n        self.embed_dims = embed_dims\n        self.vel_dims = vel_dims\n        self.mode = mode\n\n        def embedding_layer(input_dims, output_dims):\n            return nn.Sequential(\n                *linear_relu_ln(output_dims, in_loops, out_loops, input_dims)\n            )\n\n        if not isinstance(embed_dims, (list, tuple)):\n            embed_dims = [embed_dims] * 5\n        self.pos_fc = embedding_layer(3, embed_dims[0])\n        self.size_fc = embedding_layer(3, embed_dims[1])\n        self.yaw_fc = embedding_layer(2, embed_dims[2])\n        if vel_dims > 0:\n            self.vel_fc = embedding_layer(self.vel_dims, embed_dims[3])\n        if output_fc:\n            self.output_fc = embedding_layer(embed_dims[-1], embed_dims[-1])\n        else:\n            self.output_fc = None\n\n    def forward(self, box_3d: torch.Tensor):\n        pos_feat = self.pos_fc(box_3d[..., [X, Y, Z]])\n        size_feat = self.size_fc(box_3d[..., [W, L, H]])\n        yaw_feat = self.yaw_fc(box_3d[..., [SIN_YAW, COS_YAW]])\n        if self.mode == \"add\":\n            output = pos_feat + size_feat + yaw_feat\n        elif self.mode == \"cat\":\n            output = torch.cat([pos_feat, size_feat, yaw_feat], dim=-1)\n\n        if self.vel_dims > 0:\n            vel_feat = self.vel_fc(box_3d[..., VX : VX + self.vel_dims])\n            if self.mode == \"add\":\n                output = output + vel_feat\n            elif self.mode == \"cat\":\n                output = torch.cat([output, vel_feat], dim=-1)\n        if self.output_fc is not None:\n            output = self.output_fc(output)\n        return output\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparseBox3DRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        output_dim=11,\n        num_cls=10,\n        normalize_yaw=False,\n        refine_yaw=False,\n        with_cls_branch=True,\n        with_quality_estimation=False,\n    ):\n        super(SparseBox3DRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.output_dim = output_dim\n        self.num_cls = num_cls\n        self.normalize_yaw = normalize_yaw\n        self.refine_yaw = refine_yaw\n\n        self.refine_state = [X, Y, Z, W, L, H]\n        if self.refine_yaw:\n            self.refine_state += [SIN_YAW, COS_YAW]\n\n        self.layers = nn.Sequential(\n            *linear_relu_ln(embed_dims, 2, 2),\n            Linear(self.embed_dims, self.output_dim),\n            Scale([1.0] * self.output_dim),\n        )\n        self.with_cls_branch = with_cls_branch\n        if with_cls_branch:\n            self.cls_layers = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2),\n                Linear(self.embed_dims, self.num_cls),\n            )\n        self.with_quality_estimation = with_quality_estimation\n        if with_quality_estimation:\n            self.quality_layers = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2),\n                Linear(self.embed_dims, 2),\n            )\n\n    def init_weight(self):\n        if self.with_cls_branch:\n            bias_init = bias_init_with_prob(0.01)\n            nn.init.constant_(self.cls_layers[-1].bias, bias_init)\n\n    def forward(\n        self,\n        instance_feature: torch.Tensor,\n        anchor: torch.Tensor,\n        anchor_embed: torch.Tensor,\n        time_interval: torch.Tensor = 1.0,\n        return_cls=True,\n    ):\n        feature = instance_feature + anchor_embed\n        output = self.layers(feature)\n        output[..., self.refine_state] = (\n            output[..., self.refine_state] + anchor[..., self.refine_state]\n        )\n        if self.normalize_yaw:\n            output[..., [SIN_YAW, COS_YAW]] = torch.nn.functional.normalize(\n                output[..., [SIN_YAW, COS_YAW]], dim=-1\n            )\n        if self.output_dim > 8:\n            if not isinstance(time_interval, torch.Tensor):\n                time_interval = instance_feature.new_tensor(time_interval)\n            translation = torch.transpose(output[..., VX:], 0, -1)\n            velocity = torch.transpose(translation / time_interval, 0, -1)\n            output[..., VX:] = velocity + anchor[..., VX:]\n\n        if return_cls:\n            assert self.with_cls_branch, \"Without classification layers !!!\"\n            cls = self.cls_layers(instance_feature)\n        else:\n            cls = None\n        if return_cls and self.with_quality_estimation:\n            quality = self.quality_layers(feature)\n        else:\n            quality = None\n        return output, cls, quality\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparseBox3DKeyPointsGenerator(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        num_learnable_pts=0,\n        fix_scale=None,\n    ):\n        super(SparseBox3DKeyPointsGenerator, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_learnable_pts = num_learnable_pts\n        if fix_scale is None:\n            fix_scale = ((0.0, 0.0, 0.0),)\n        self.fix_scale = nn.Parameter(\n            torch.tensor(fix_scale), requires_grad=False\n        )\n        self.num_pts = len(self.fix_scale) + num_learnable_pts\n        if num_learnable_pts > 0:\n            self.learnable_fc = Linear(self.embed_dims, num_learnable_pts * 3)\n\n    def init_weight(self):\n        if self.num_learnable_pts > 0:\n            xavier_init(self.learnable_fc, distribution=\"uniform\", bias=0.0)\n\n    def forward(\n        self,\n        anchor,\n        instance_feature=None,\n        T_cur2temp_list=None,\n        cur_timestamp=None,\n        temp_timestamps=None,\n    ):\n        bs, num_anchor = anchor.shape[:2]\n        size = anchor[..., None, [W, L, H]].exp()\n        key_points = self.fix_scale * size\n        if self.num_learnable_pts > 0 and instance_feature is not None:\n            learnable_scale = (\n                self.learnable_fc(instance_feature)\n                .reshape(bs, num_anchor, self.num_learnable_pts, 3)\n                .sigmoid()\n                - 0.5\n            )\n            key_points = torch.cat(\n                [key_points, learnable_scale * size], dim=-2\n            )\n\n        rotation_mat = anchor.new_zeros([bs, num_anchor, 3, 3])\n\n        rotation_mat[:, :, 0, 0] = anchor[:, :, COS_YAW]\n        rotation_mat[:, :, 0, 1] = -anchor[:, :, SIN_YAW]\n        rotation_mat[:, :, 1, 0] = anchor[:, :, SIN_YAW]\n        rotation_mat[:, :, 1, 1] = anchor[:, :, COS_YAW]\n        rotation_mat[:, :, 2, 2] = 1\n\n        key_points = torch.matmul(\n            rotation_mat[:, :, None], key_points[..., None]\n        ).squeeze(-1)\n        key_points = key_points + anchor[..., None, [X, Y, Z]]\n\n        if (\n            cur_timestamp is None\n            or temp_timestamps is None\n            or T_cur2temp_list is None\n            or len(temp_timestamps) == 0\n        ):\n            return key_points\n\n        temp_key_points_list = []\n        velocity = anchor[..., VX:]\n        for i, t_time in enumerate(temp_timestamps):\n            time_interval = cur_timestamp - t_time\n            translation = (\n                velocity\n                * time_interval.to(dtype=velocity.dtype)[:, None, None]\n            )\n            temp_key_points = key_points - translation[:, :, None]\n            T_cur2temp = T_cur2temp_list[i].to(dtype=key_points.dtype)\n            temp_key_points = (\n                T_cur2temp[:, None, None, :3]\n                @ torch.cat(\n                    [\n                        temp_key_points,\n                        torch.ones_like(temp_key_points[..., :1]),\n                    ],\n                    dim=-1,\n                ).unsqueeze(-1)\n            )\n            temp_key_points = temp_key_points.squeeze(-1)\n            temp_key_points_list.append(temp_key_points)\n        return key_points, temp_key_points_list\n\n    @staticmethod\n    def anchor_projection(\n        anchor,\n        T_src2dst_list,\n        src_timestamp=None,\n        dst_timestamps=None,\n        time_intervals=None,\n    ):\n        dst_anchors = []\n        for i in range(len(T_src2dst_list)):\n            vel = anchor[..., VX:]\n            vel_dim = vel.shape[-1]\n            T_src2dst = torch.unsqueeze(\n                T_src2dst_list[i].to(dtype=anchor.dtype), dim=1\n            )\n\n            center = anchor[..., [X, Y, Z]]\n            if time_intervals is not None:\n                time_interval = time_intervals[i]\n            elif src_timestamp is not None and dst_timestamps is not None:\n                time_interval = (src_timestamp - dst_timestamps[i]).to(\n                    dtype=vel.dtype\n                )\n            else:\n                time_interval = None\n            if time_interval is not None:\n                translation = vel.transpose(0, -1) * time_interval\n                translation = translation.transpose(0, -1)\n                center = center - translation\n            center = (\n                torch.matmul(\n                    T_src2dst[..., :3, :3], center[..., None]\n                ).squeeze(dim=-1)\n                + T_src2dst[..., :3, 3]\n            )\n            size = anchor[..., [W, L, H]]\n            yaw = torch.matmul(\n                T_src2dst[..., :2, :2],\n                anchor[..., [COS_YAW, SIN_YAW], None],\n            ).squeeze(-1)\n            yaw = yaw[..., [1,0]]\n            vel = torch.matmul(\n                T_src2dst[..., :vel_dim, :vel_dim], vel[..., None]\n            ).squeeze(-1)\n            dst_anchor = torch.cat([center, size, yaw, vel], dim=-1)\n            dst_anchors.append(dst_anchor)\n        return dst_anchors\n\n    @staticmethod\n    def distance(anchor):\n        return torch.norm(anchor[..., :2], p=2, dim=-1)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/detection3d/detection3d_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\nfrom mmdet.core.bbox.builder import BBOX_CODERS\nfrom mmdet.models import HEADS, LOSSES\nfrom mmdet.core import reduce_mean\n\nfrom ..blocks import DeformableFeatureAggregation as DFG\n\n__all__ = [\"Sparse4DHead\"]\n\n\n@HEADS.register_module()\nclass Sparse4DHead(BaseModule):\n    def __init__(\n        self,\n        instance_bank: dict,\n        anchor_encoder: dict,\n        graph_model: dict,\n        norm_layer: dict,\n        ffn: dict,\n        deformable_model: dict,\n        refine_layer: dict,\n        num_decoder: int = 6,\n        num_single_frame_decoder: int = -1,\n        temp_graph_model: dict = None,\n        loss_cls: dict = None,\n        loss_reg: dict = None,\n        decoder: dict = None,\n        sampler: dict = None,\n        gt_cls_key: str = \"gt_labels_3d\",\n        gt_reg_key: str = \"gt_bboxes_3d\",\n        gt_id_key: str = \"instance_id\",\n        with_instance_id: bool = True,\n        task_prefix: str = 'det',\n        reg_weights: List = None,\n        operation_order: Optional[List[str]] = None,\n        cls_threshold_to_reg: float = -1,\n        dn_loss_weight: float = 5.0,\n        decouple_attn: bool = True,\n        init_cfg: dict = None,\n        **kwargs,\n    ):\n        super(Sparse4DHead, self).__init__(init_cfg)\n        self.num_decoder = num_decoder\n        self.num_single_frame_decoder = num_single_frame_decoder\n        self.gt_cls_key = gt_cls_key\n        self.gt_reg_key = gt_reg_key\n        self.gt_id_key = gt_id_key\n        self.with_instance_id = with_instance_id\n        self.task_prefix = task_prefix\n        self.cls_threshold_to_reg = cls_threshold_to_reg\n        self.dn_loss_weight = dn_loss_weight\n        self.decouple_attn = decouple_attn\n\n        if reg_weights is None:\n            self.reg_weights = [1.0] * 10\n        else:\n            self.reg_weights = reg_weights\n\n        if operation_order is None:\n            operation_order = [\n                \"temp_gnn\",\n                \"gnn\",\n                \"norm\",\n                \"deformable\",\n                \"norm\",\n                \"ffn\",\n                \"norm\",\n                \"refine\",\n            ] * num_decoder\n            # delete the 'gnn' and 'norm' layers in the first transformer blocks\n            operation_order = operation_order[3:]\n        self.operation_order = operation_order\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.instance_bank = build(instance_bank, PLUGIN_LAYERS)\n        self.anchor_encoder = build(anchor_encoder, POSITIONAL_ENCODING)\n        self.sampler = build(sampler, BBOX_SAMPLERS)\n        self.decoder = build(decoder, BBOX_CODERS)\n        self.loss_cls = build(loss_cls, LOSSES)\n        self.loss_reg = build(loss_reg, LOSSES)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"deformable\": [deformable_model, ATTENTION],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = self.instance_bank.embed_dims\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self,\n        feature_maps: Union[torch.Tensor, List],\n        metas: dict,\n    ):\n        if isinstance(feature_maps, torch.Tensor):\n            feature_maps = [feature_maps]\n        batch_size = feature_maps[0].shape[0]\n\n        # ========= get instance info ============\n        if (\n            self.sampler.dn_metas is not None\n            and self.sampler.dn_metas[\"dn_anchor\"].shape[0] != batch_size\n        ):\n            self.sampler.dn_metas = None\n        (\n            instance_feature,\n            anchor,\n            temp_instance_feature,\n            temp_anchor,\n            time_interval,\n        ) = self.instance_bank.get(\n            batch_size, metas, dn_metas=self.sampler.dn_metas\n        )\n\n        # ========= prepare for denosing training ============\n        # 1. get dn metas: noisy-anchors and corresponding GT\n        # 2. concat learnable instances and noisy instances\n        # 3. get attention mask\n        attn_mask = None\n        dn_metas = None\n        temp_dn_reg_target = None\n        if self.training and hasattr(self.sampler, \"get_dn_anchors\"):\n            if self.gt_id_key in metas[\"img_metas\"][0]:\n                gt_instance_id = [\n                    torch.from_numpy(x[self.gt_id_key]).cuda()\n                    for x in metas[\"img_metas\"]\n                ]\n            else:\n                gt_instance_id = None\n            dn_metas = self.sampler.get_dn_anchors(\n                metas[self.gt_cls_key],\n                metas[self.gt_reg_key],\n                gt_instance_id,\n            )\n        if dn_metas is not None:\n            (\n                dn_anchor,\n                dn_reg_target,\n                dn_cls_target,\n                dn_attn_mask,\n                valid_mask,\n                dn_id_target,\n            ) = dn_metas\n            num_dn_anchor = dn_anchor.shape[1]\n            if dn_anchor.shape[-1] != anchor.shape[-1]:\n                remain_state_dims = anchor.shape[-1] - dn_anchor.shape[-1]\n                dn_anchor = torch.cat(\n                    [\n                        dn_anchor,\n                        dn_anchor.new_zeros(\n                            batch_size, num_dn_anchor, remain_state_dims\n                        ),\n                    ],\n                    dim=-1,\n                )\n            anchor = torch.cat([anchor, dn_anchor], dim=1)\n            instance_feature = torch.cat(\n                [\n                    instance_feature,\n                    instance_feature.new_zeros(\n                        batch_size, num_dn_anchor, instance_feature.shape[-1]\n                    ),\n                ],\n                dim=1,\n            )\n            num_instance = instance_feature.shape[1]\n            num_free_instance = num_instance - num_dn_anchor\n            attn_mask = anchor.new_ones(\n                (num_instance, num_instance), dtype=torch.bool\n            )\n            attn_mask[:num_free_instance, :num_free_instance] = False\n            attn_mask[num_free_instance:, num_free_instance:] = dn_attn_mask\n\n        anchor_embed = self.anchor_encoder(anchor)\n        if temp_anchor is not None:\n            temp_anchor_embed = self.anchor_encoder(temp_anchor)\n        else:\n            temp_anchor_embed = None\n\n        # =================== forward the layers ====================\n        prediction = []\n        classification = []\n        quality = []\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed,\n                    key_pos=temp_anchor_embed,\n                    attn_mask=attn_mask\n                    if temp_instance_feature is None\n                    else None,\n                )\n            elif op == \"gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    value=instance_feature,\n                    query_pos=anchor_embed,\n                    attn_mask=attn_mask,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"deformable\":\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    anchor,\n                    anchor_embed,\n                    feature_maps,\n                    metas,\n                )\n            elif op == \"refine\":\n                anchor, cls, qt = self.layers[i](\n                    instance_feature,\n                    anchor,\n                    anchor_embed,\n                    time_interval=time_interval,\n                    return_cls=True,\n                )\n                prediction.append(anchor)\n                classification.append(cls)\n                quality.append(qt)\n                if len(prediction) == self.num_single_frame_decoder:\n                    instance_feature, anchor = self.instance_bank.update(\n                        instance_feature, anchor, cls\n                    )\n                    if (\n                        dn_metas is not None\n                        and self.sampler.num_temp_dn_groups > 0\n                        and dn_id_target is not None\n                    ):\n                        (\n                            instance_feature,\n                            anchor,\n                            temp_dn_reg_target,\n                            temp_dn_cls_target,\n                            temp_valid_mask,\n                            dn_id_target,\n                        ) = self.sampler.update_dn(\n                            instance_feature,\n                            anchor,\n                            dn_reg_target,\n                            dn_cls_target,\n                            valid_mask,\n                            dn_id_target,\n                            self.instance_bank.num_anchor,\n                            self.instance_bank.mask,\n                        )\n                anchor_embed = self.anchor_encoder(anchor)\n                if (\n                    len(prediction) > self.num_single_frame_decoder\n                    and temp_anchor_embed is not None\n                ):\n                    temp_anchor_embed = anchor_embed[\n                        :, : self.instance_bank.num_temp_instances\n                    ]\n            else:\n                raise NotImplementedError(f\"{op} is not supported.\")\n\n        output = {}\n\n        # split predictions of learnable instances and noisy instances\n        if dn_metas is not None:\n            dn_classification = [\n                x[:, num_free_instance:] for x in classification\n            ]\n            classification = [x[:, :num_free_instance] for x in classification]\n            dn_prediction = [x[:, num_free_instance:] for x in prediction]\n            prediction = [x[:, :num_free_instance] for x in prediction]\n            quality = [\n                x[:, :num_free_instance] if x is not None else None\n                for x in quality\n            ]\n            output.update(\n                {\n                    \"dn_prediction\": dn_prediction,\n                    \"dn_classification\": dn_classification,\n                    \"dn_reg_target\": dn_reg_target,\n                    \"dn_cls_target\": dn_cls_target,\n                    \"dn_valid_mask\": valid_mask,\n                }\n            )\n            if temp_dn_reg_target is not None:\n                output.update(\n                    {\n                        \"temp_dn_reg_target\": temp_dn_reg_target,\n                        \"temp_dn_cls_target\": temp_dn_cls_target,\n                        \"temp_dn_valid_mask\": temp_valid_mask,\n                        \"dn_id_target\": dn_id_target,\n                    }\n                )\n                dn_cls_target = temp_dn_cls_target\n                valid_mask = temp_valid_mask\n            dn_instance_feature = instance_feature[:, num_free_instance:]\n            dn_anchor = anchor[:, num_free_instance:]\n            instance_feature = instance_feature[:, :num_free_instance]\n            anchor_embed = anchor_embed[:, :num_free_instance]\n            anchor = anchor[:, :num_free_instance]\n            cls = cls[:, :num_free_instance]\n\n            # cache dn_metas for temporal denoising\n            self.sampler.cache_dn(\n                dn_instance_feature,\n                dn_anchor,\n                dn_cls_target,\n                valid_mask,\n                dn_id_target,\n            )\n        output.update(\n            {\n                \"classification\": classification,\n                \"prediction\": prediction,\n                \"quality\": quality,\n                \"instance_feature\": instance_feature,\n                \"anchor_embed\": anchor_embed,\n            }\n        )\n\n        # cache current instances for temporal modeling\n        self.instance_bank.cache(\n            instance_feature, anchor, cls, metas, feature_maps\n        )\n        if self.with_instance_id:\n            instance_id = self.instance_bank.get_instance_id(\n                cls, anchor, self.decoder.score_threshold\n            )\n            output[\"instance_id\"] = instance_id\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss(self, model_outs, data, feature_maps=None):\n        # ===================== prediction losses ======================\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        quality = model_outs[\"quality\"]\n        output = {}\n        for decoder_idx, (cls, reg, qt) in enumerate(\n            zip(cls_scores, reg_preds, quality)\n        ):\n            reg = reg[..., : len(self.reg_weights)]\n            cls_target, reg_target, reg_weights = self.sampler.sample(\n                cls,\n                reg,\n                data[self.gt_cls_key],\n                data[self.gt_reg_key],\n            )\n            reg_target = reg_target[..., : len(self.reg_weights)]\n            reg_target_full = reg_target.clone()\n            mask = torch.logical_not(torch.all(reg_target == 0, dim=-1))\n            mask_valid = mask.clone()\n\n            num_pos = max(\n                reduce_mean(torch.sum(mask).to(dtype=reg.dtype)), 1.0\n            )\n            if self.cls_threshold_to_reg > 0:\n                threshold = self.cls_threshold_to_reg\n                mask = torch.logical_and(\n                    mask, cls.max(dim=-1).values.sigmoid() > threshold\n                )\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_loss = self.loss_cls(cls, cls_target, avg_factor=num_pos)\n\n            mask = mask.reshape(-1)\n            reg_weights = reg_weights * reg.new_tensor(self.reg_weights)\n            reg_target = reg_target.flatten(end_dim=1)[mask]\n            reg = reg.flatten(end_dim=1)[mask]\n            reg_weights = reg_weights.flatten(end_dim=1)[mask]\n            reg_target = torch.where(\n                reg_target.isnan(), reg.new_tensor(0.0), reg_target\n            )\n            cls_target = cls_target[mask]\n            if qt is not None:\n                qt = qt.flatten(end_dim=1)[mask]\n\n            reg_loss = self.loss_reg(\n                reg,\n                reg_target,\n                weight=reg_weights,\n                avg_factor=num_pos,\n                prefix=f\"{self.task_prefix}_\",\n                suffix=f\"_{decoder_idx}\",\n                quality=qt,\n                cls_target=cls_target,\n            )\n\n            output[f\"{self.task_prefix}_loss_cls_{decoder_idx}\"] = cls_loss\n            output.update(reg_loss)\n\n        if \"dn_prediction\" not in model_outs:\n            return output\n\n        # ===================== denoising losses ======================\n        dn_cls_scores = model_outs[\"dn_classification\"]\n        dn_reg_preds = model_outs[\"dn_prediction\"]\n\n        (\n            dn_valid_mask,\n            dn_cls_target,\n            dn_reg_target,\n            dn_pos_mask,\n            reg_weights,\n            num_dn_pos,\n        ) = self.prepare_for_dn_loss(model_outs)\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(dn_cls_scores, dn_reg_preds)\n        ):\n            if (\n                \"temp_dn_valid_mask\" in model_outs\n                and decoder_idx == self.num_single_frame_decoder\n            ):\n                (\n                    dn_valid_mask,\n                    dn_cls_target,\n                    dn_reg_target,\n                    dn_pos_mask,\n                    reg_weights,\n                    num_dn_pos,\n                ) = self.prepare_for_dn_loss(model_outs, prefix=\"temp_\")\n\n            cls_loss = self.loss_cls(\n                cls.flatten(end_dim=1)[dn_valid_mask],\n                dn_cls_target,\n                avg_factor=num_dn_pos,\n            )\n            reg_loss = self.loss_reg(\n                reg.flatten(end_dim=1)[dn_valid_mask][dn_pos_mask][\n                    ..., : len(self.reg_weights)\n                ],\n                dn_reg_target,\n                avg_factor=num_dn_pos,\n                weight=reg_weights,\n                prefix=f\"{self.task_prefix}_\",\n                suffix=f\"_dn_{decoder_idx}\",\n            )\n            output[f\"{self.task_prefix}_loss_cls_dn_{decoder_idx}\"] = cls_loss\n            output.update(reg_loss)\n        return output\n\n    def prepare_for_dn_loss(self, model_outs, prefix=\"\"):\n        dn_valid_mask = model_outs[f\"{prefix}dn_valid_mask\"].flatten(end_dim=1)\n        dn_cls_target = model_outs[f\"{prefix}dn_cls_target\"].flatten(\n            end_dim=1\n        )[dn_valid_mask]\n        dn_reg_target = model_outs[f\"{prefix}dn_reg_target\"].flatten(\n            end_dim=1\n        )[dn_valid_mask][..., : len(self.reg_weights)]\n        dn_pos_mask = dn_cls_target >= 0\n        dn_reg_target = dn_reg_target[dn_pos_mask]\n        reg_weights = dn_reg_target.new_tensor(self.reg_weights)[None].tile(\n            dn_reg_target.shape[0], 1\n        )\n        num_dn_pos = max(\n            reduce_mean(torch.sum(dn_valid_mask).to(dtype=reg_weights.dtype)),\n            1.0,\n        )\n        return (\n            dn_valid_mask,\n            dn_cls_target,\n            dn_reg_target,\n            dn_pos_mask,\n            reg_weights,\n            num_dn_pos,\n        )\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(self, model_outs, output_idx=-1):\n        return self.decoder.decode(\n            model_outs[\"classification\"],\n            model_outs[\"prediction\"],\n            model_outs.get(\"instance_id\"),\n            model_outs.get(\"quality\"),\n            output_idx=output_idx,\n        )\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/detection3d/losses.py",
    "content": "import torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.models.builder import LOSSES\n\nfrom mmdet3d_plugin.core.box3d import *\n\n\n@LOSSES.register_module()\nclass SparseBox3DLoss(nn.Module):\n    def __init__(\n        self,\n        loss_box,\n        loss_centerness=None,\n        loss_yawness=None,\n        cls_allow_reverse=None,\n    ):\n        super().__init__()\n\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.loss_box = build(loss_box, LOSSES)\n        self.loss_cns = build(loss_centerness, LOSSES)\n        self.loss_yns = build(loss_yawness, LOSSES)\n        self.cls_allow_reverse = cls_allow_reverse\n\n    def forward(\n        self,\n        box,\n        box_target,\n        weight=None,\n        avg_factor=None,\n        prefix=\"\",\n        suffix=\"\",\n        quality=None,\n        cls_target=None,\n        **kwargs,\n    ):\n        # Some categories do not distinguish between positive and negative\n        # directions. For example, barrier in nuScenes dataset.\n        if self.cls_allow_reverse is not None and cls_target is not None:\n            if_reverse = (\n                torch.nn.functional.cosine_similarity(\n                    box_target[..., [SIN_YAW, COS_YAW]],\n                    box[..., [SIN_YAW, COS_YAW]],\n                    dim=-1,\n                )\n                < 0\n            )\n            if_reverse = (\n                torch.isin(\n                    cls_target, cls_target.new_tensor(self.cls_allow_reverse)\n                )\n                & if_reverse\n            )\n            box_target[..., [SIN_YAW, COS_YAW]] = torch.where(\n                if_reverse[..., None],\n                -box_target[..., [SIN_YAW, COS_YAW]],\n                box_target[..., [SIN_YAW, COS_YAW]],\n            )\n\n        output = {}\n        box_loss = self.loss_box(\n            box, box_target, weight=weight, avg_factor=avg_factor\n        )\n        output[f\"{prefix}loss_box{suffix}\"] = box_loss\n\n        if quality is not None:\n            cns = quality[..., CNS]\n            yns = quality[..., YNS].sigmoid()\n            cns_target = torch.norm(\n                box_target[..., [X, Y, Z]] - box[..., [X, Y, Z]], p=2, dim=-1\n            )\n            cns_target = torch.exp(-cns_target)\n            cns_loss = self.loss_cns(cns, cns_target, avg_factor=avg_factor)\n            output[f\"{prefix}loss_cns{suffix}\"] = cns_loss\n\n            yns_target = (\n                torch.nn.functional.cosine_similarity(\n                    box_target[..., [SIN_YAW, COS_YAW]],\n                    box[..., [SIN_YAW, COS_YAW]],\n                    dim=-1,\n                )\n                > 0\n            )\n            yns_target = yns_target.float()\n            yns_loss = self.loss_yns(yns, yns_target, avg_factor=avg_factor)\n            output[f\"{prefix}loss_yns{suffix}\"] = yns_loss\n        return output\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/detection3d/target.py",
    "content": "import torch\nimport numpy as np\nimport torch.nn.functional as F\nfrom scipy.optimize import linear_sum_assignment\n\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\n\nfrom mmdet3d_plugin.core.box3d import *\nfrom ..base_target import BaseTargetWithDenoising\n\n\n__all__ = [\"SparseBox3DTarget\"]\n\n\n@BBOX_SAMPLERS.register_module()\nclass SparseBox3DTarget(BaseTargetWithDenoising):\n    def __init__(\n        self,\n        cls_weight=2.0,\n        alpha=0.25,\n        gamma=2,\n        eps=1e-12,\n        box_weight=0.25,\n        reg_weights=None,\n        cls_wise_reg_weights=None,\n        num_dn_groups=0,\n        dn_noise_scale=0.5,\n        max_dn_gt=32,\n        add_neg_dn=True,\n        num_temp_dn_groups=0,\n    ):\n        super(SparseBox3DTarget, self).__init__(\n            num_dn_groups, num_temp_dn_groups\n        )\n        self.cls_weight = cls_weight\n        self.box_weight = box_weight\n        self.alpha = alpha\n        self.gamma = gamma\n        self.eps = eps\n        self.reg_weights = reg_weights\n        if self.reg_weights is None:\n            self.reg_weights = [1.0] * 8 + [0.0] * 2\n        self.cls_wise_reg_weights = cls_wise_reg_weights\n        self.dn_noise_scale = dn_noise_scale\n        self.max_dn_gt = max_dn_gt\n        self.add_neg_dn = add_neg_dn\n\n    def encode_reg_target(self, box_target, device=None):\n        outputs = []\n        for box in box_target:\n            output = torch.cat(\n                [\n                    box[..., [X, Y, Z]],\n                    box[..., [W, L, H]].log(),\n                    torch.sin(box[..., YAW]).unsqueeze(-1),\n                    torch.cos(box[..., YAW]).unsqueeze(-1),\n                    box[..., YAW + 1 :],\n                ],\n                dim=-1,\n            )\n            if device is not None:\n                output = output.to(device=device)\n            outputs.append(output)\n        return outputs\n\n    def sample(\n        self,\n        cls_pred,\n        box_pred,\n        cls_target,\n        box_target,\n    ):\n        bs, num_pred, num_cls = cls_pred.shape\n\n        cls_cost = self._cls_cost(cls_pred, cls_target)\n\n        box_target = self.encode_reg_target(box_target, box_pred.device)\n\n        instance_reg_weights = []\n        for i in range(len(box_target)):\n            weights = torch.logical_not(box_target[i].isnan()).to(\n                dtype=box_target[i].dtype\n            )\n            if self.cls_wise_reg_weights is not None:\n                for cls, weight in self.cls_wise_reg_weights.items():\n                    weights = torch.where(\n                        (cls_target[i] == cls)[:, None],\n                        weights.new_tensor(weight),\n                        weights,\n                    )\n            instance_reg_weights.append(weights)\n        box_cost = self._box_cost(box_pred, box_target, instance_reg_weights)\n\n        indices = []\n        for i in range(bs):\n            if cls_cost[i] is not None and box_cost[i] is not None:\n                cost = (cls_cost[i] + box_cost[i]).detach().cpu().numpy()\n                cost = np.where(np.isneginf(cost) | np.isnan(cost), 1e8, cost)\n                assign = linear_sum_assignment(cost)\n                indices.append(\n                    [cls_pred.new_tensor(x, dtype=torch.int64) for x in assign]\n                )\n            else:\n                indices.append([None, None])\n\n        output_cls_target = (\n            cls_target[0].new_ones([bs, num_pred], dtype=torch.long) * num_cls\n        )\n        output_box_target = box_pred.new_zeros(box_pred.shape)\n        output_reg_weights = box_pred.new_zeros(box_pred.shape)\n        for i, (pred_idx, target_idx) in enumerate(indices):\n            if len(cls_target[i]) == 0:\n                continue\n            output_cls_target[i, pred_idx] = cls_target[i][target_idx]\n            output_box_target[i, pred_idx] = box_target[i][target_idx]\n            output_reg_weights[i, pred_idx] = instance_reg_weights[i][\n                target_idx\n            ]\n        self.indices = indices\n        return output_cls_target, output_box_target, output_reg_weights\n\n    def _cls_cost(self, cls_pred, cls_target):\n        bs = cls_pred.shape[0]\n        cls_pred = cls_pred.sigmoid()\n        cost = []\n        for i in range(bs):\n            if len(cls_target[i]) > 0:\n                neg_cost = (\n                    -(1 - cls_pred[i] + self.eps).log()\n                    * (1 - self.alpha)\n                    * cls_pred[i].pow(self.gamma)\n                )\n                pos_cost = (\n                    -(cls_pred[i] + self.eps).log()\n                    * self.alpha\n                    * (1 - cls_pred[i]).pow(self.gamma)\n                )\n                cost.append(\n                    (pos_cost[:, cls_target[i]] - neg_cost[:, cls_target[i]])\n                    * self.cls_weight\n                )\n            else:\n                cost.append(None)\n        return cost\n\n    def _box_cost(self, box_pred, box_target, instance_reg_weights):\n        bs = box_pred.shape[0]\n        cost = []\n        for i in range(bs):\n            if len(box_target[i]) > 0:\n                cost.append(\n                    torch.sum(\n                        torch.abs(box_pred[i, :, None] - box_target[i][None])\n                        * instance_reg_weights[i][None]\n                        * box_pred.new_tensor(self.reg_weights),\n                        dim=-1,\n                    )\n                    * self.box_weight\n                )\n            else:\n                cost.append(None)\n        return cost\n\n    def get_dn_anchors(self, cls_target, box_target, gt_instance_id=None):\n        if self.num_dn_groups <= 0:\n            return None\n        if self.num_temp_dn_groups <= 0:\n            gt_instance_id = None\n\n        if self.max_dn_gt > 0:\n            cls_target = [x[: self.max_dn_gt] for x in cls_target]\n            box_target = [x[: self.max_dn_gt] for x in box_target]\n            if gt_instance_id is not None:\n                gt_instance_id = [x[: self.max_dn_gt] for x in gt_instance_id]\n\n        max_dn_gt = max([len(x) for x in cls_target])\n        if max_dn_gt == 0:\n            return None\n        cls_target = torch.stack(\n            [\n                F.pad(x, (0, max_dn_gt - x.shape[0]), value=-1)\n                for x in cls_target\n            ]\n        )\n        box_target = self.encode_reg_target(box_target, cls_target.device)\n        box_target = torch.stack(\n            [F.pad(x, (0, 0, 0, max_dn_gt - x.shape[0])) for x in box_target]\n        )\n        box_target = torch.where(\n            cls_target[..., None] == -1, box_target.new_tensor(0), box_target\n        )\n        if gt_instance_id is not None:\n            gt_instance_id = torch.stack(\n                [\n                    F.pad(x, (0, max_dn_gt - x.shape[0]), value=-1)\n                    for x in gt_instance_id\n                ]\n            )\n\n        bs, num_gt, state_dims = box_target.shape\n        if self.num_dn_groups > 1:\n            cls_target = cls_target.tile(self.num_dn_groups, 1)\n            box_target = box_target.tile(self.num_dn_groups, 1, 1)\n            if gt_instance_id is not None:\n                gt_instance_id = gt_instance_id.tile(self.num_dn_groups, 1)\n\n        noise = torch.rand_like(box_target) * 2 - 1\n        noise *= box_target.new_tensor(self.dn_noise_scale)\n        dn_anchor = box_target + noise\n        if self.add_neg_dn:\n            noise_neg = torch.rand_like(box_target) + 1\n            flag = torch.where(\n                torch.rand_like(box_target) > 0.5,\n                noise_neg.new_tensor(1),\n                noise_neg.new_tensor(-1),\n            )\n            noise_neg *= flag\n            noise_neg *= box_target.new_tensor(self.dn_noise_scale)\n            dn_anchor = torch.cat([dn_anchor, box_target + noise_neg], dim=1)\n            num_gt *= 2\n\n        box_cost = self._box_cost(\n            dn_anchor, box_target, torch.ones_like(box_target)\n        )\n        dn_box_target = torch.zeros_like(dn_anchor)\n        dn_cls_target = -torch.ones_like(cls_target) * 3\n        if gt_instance_id is not None:\n            dn_id_target = -torch.ones_like(gt_instance_id)\n        if self.add_neg_dn:\n            dn_cls_target = torch.cat([dn_cls_target, dn_cls_target], dim=1)\n            if gt_instance_id is not None:\n                dn_id_target = torch.cat([dn_id_target, dn_id_target], dim=1)\n\n        for i in range(dn_anchor.shape[0]):\n            cost = box_cost[i].cpu().numpy()\n            anchor_idx, gt_idx = linear_sum_assignment(cost)\n            anchor_idx = dn_anchor.new_tensor(anchor_idx, dtype=torch.int64)\n            gt_idx = dn_anchor.new_tensor(gt_idx, dtype=torch.int64)\n            dn_box_target[i, anchor_idx] = box_target[i, gt_idx]\n            dn_cls_target[i, anchor_idx] = cls_target[i, gt_idx]\n            if gt_instance_id is not None:\n                dn_id_target[i, anchor_idx] = gt_instance_id[i, gt_idx]\n        dn_anchor = (\n            dn_anchor.reshape(self.num_dn_groups, bs, num_gt, state_dims)\n            .permute(1, 0, 2, 3)\n            .flatten(1, 2)\n        )\n        dn_box_target = (\n            dn_box_target.reshape(self.num_dn_groups, bs, num_gt, state_dims)\n            .permute(1, 0, 2, 3)\n            .flatten(1, 2)\n        )\n        dn_cls_target = (\n            dn_cls_target.reshape(self.num_dn_groups, bs, num_gt)\n            .permute(1, 0, 2)\n            .flatten(1)\n        )\n        if gt_instance_id is not None:\n            dn_id_target = (\n                dn_id_target.reshape(self.num_dn_groups, bs, num_gt)\n                .permute(1, 0, 2)\n                .flatten(1)\n            )\n        else:\n            dn_id_target = None\n        valid_mask = dn_cls_target >= 0\n        if self.add_neg_dn:\n            cls_target = (\n                torch.cat([cls_target, cls_target], dim=1)\n                .reshape(self.num_dn_groups, bs, num_gt)\n                .permute(1, 0, 2)\n                .flatten(1)\n            )\n            valid_mask = torch.logical_or(\n                valid_mask, ((cls_target >= 0) & (dn_cls_target == -3))\n            )  # valid denotes the items is not from pad.\n        attn_mask = dn_box_target.new_ones(\n            num_gt * self.num_dn_groups, num_gt * self.num_dn_groups\n        )\n        for i in range(self.num_dn_groups):\n            start = num_gt * i\n            end = start + num_gt\n            attn_mask[start:end, start:end] = 0\n        attn_mask = attn_mask == 1\n        dn_cls_target = dn_cls_target.long()\n        return (\n            dn_anchor,\n            dn_box_target,\n            dn_cls_target,\n            attn_mask,\n            valid_mask,\n            dn_id_target,\n        )\n\n    def update_dn(\n        self,\n        instance_feature,\n        anchor,\n        dn_reg_target,\n        dn_cls_target,\n        valid_mask,\n        dn_id_target,\n        num_noraml_anchor,\n        temporal_valid_mask,\n    ):\n        bs, num_anchor = instance_feature.shape[:2]\n        if temporal_valid_mask is None:\n            self.dn_metas = None\n        if self.dn_metas is None or num_noraml_anchor >= num_anchor:\n            return (\n                instance_feature,\n                anchor,\n                dn_reg_target,\n                dn_cls_target,\n                valid_mask,\n                dn_id_target,\n            )\n\n        # split instance_feature and anchor into non-dn and dn\n        num_dn = num_anchor - num_noraml_anchor\n        dn_instance_feature = instance_feature[:, -num_dn:]\n        dn_anchor = anchor[:, -num_dn:]\n        instance_feature = instance_feature[:, :num_noraml_anchor]\n        anchor = anchor[:, :num_noraml_anchor]\n\n        # reshape all dn metas from (bs,num_all_dn,xxx)\n        # to (bs, dn_group, num_dn_per_group, xxx)\n        num_dn_groups = self.num_dn_groups\n        num_dn = num_dn // num_dn_groups\n        dn_feat = dn_instance_feature.reshape(bs, num_dn_groups, num_dn, -1)\n        dn_anchor = dn_anchor.reshape(bs, num_dn_groups, num_dn, -1)\n        dn_reg_target = dn_reg_target.reshape(bs, num_dn_groups, num_dn, -1)\n        dn_cls_target = dn_cls_target.reshape(bs, num_dn_groups, num_dn)\n        valid_mask = valid_mask.reshape(bs, num_dn_groups, num_dn)\n        if dn_id_target is not None:\n            dn_id = dn_id_target.reshape(bs, num_dn_groups, num_dn)\n\n        # update temp_dn_metas by instance_id\n        temp_dn_feat = self.dn_metas[\"dn_instance_feature\"]\n        _, num_temp_dn_groups, num_temp_dn = temp_dn_feat.shape[:3]\n        temp_dn_id = self.dn_metas[\"dn_id_target\"]\n\n        # bs, num_temp_dn_groups, num_temp_dn, num_dn\n        match = temp_dn_id[..., None] == dn_id[:, :num_temp_dn_groups, None]\n        temp_reg_target = (\n            match[..., None] * dn_reg_target[:, :num_temp_dn_groups, None]\n        ).sum(dim=3)\n        temp_cls_target = torch.where(\n            torch.all(torch.logical_not(match), dim=-1),\n            self.dn_metas[\"dn_cls_target\"].new_tensor(-1),\n            self.dn_metas[\"dn_cls_target\"],\n        )\n        temp_valid_mask = self.dn_metas[\"valid_mask\"]\n        temp_dn_anchor = self.dn_metas[\"dn_anchor\"]\n\n        # handle the misalignment the length of temp_dn to dn caused by the\n        # change of num_gt, then concat the temp_dn and dn\n        temp_dn_metas = [\n            temp_dn_feat,\n            temp_dn_anchor,\n            temp_reg_target,\n            temp_cls_target,\n            temp_valid_mask,\n            temp_dn_id,\n        ]\n        dn_metas = [\n            dn_feat,\n            dn_anchor,\n            dn_reg_target,\n            dn_cls_target,\n            valid_mask,\n            dn_id,\n        ]\n        output = []\n        for i, (temp_meta, meta) in enumerate(zip(temp_dn_metas, dn_metas)):\n            if num_temp_dn < num_dn:\n                pad = (0, num_dn - num_temp_dn)\n                if temp_meta.dim() == 4:\n                    pad = (0, 0) + pad\n                else:\n                    assert temp_meta.dim() == 3\n                temp_meta = F.pad(temp_meta, pad, value=0)\n            else:\n                temp_meta = temp_meta[:, :, :num_dn]\n            mask = temporal_valid_mask[:, None, None]\n            if meta.dim() == 4:\n                mask = mask.unsqueeze(dim=-1)\n            temp_meta = torch.where(\n                mask, temp_meta, meta[:, :num_temp_dn_groups]\n            )\n            meta = torch.cat([temp_meta, meta[:, num_temp_dn_groups:]], dim=1)\n            meta = meta.flatten(1, 2)\n            output.append(meta)\n        output[0] = torch.cat([instance_feature, output[0]], dim=1)\n        output[1] = torch.cat([anchor, output[1]], dim=1)\n        return output\n\n    def cache_dn(\n        self,\n        dn_instance_feature,\n        dn_anchor,\n        dn_cls_target,\n        valid_mask,\n        dn_id_target,\n    ):\n        if self.num_temp_dn_groups <= 0:\n            return\n        num_dn_groups = self.num_dn_groups\n        bs, num_dn = dn_instance_feature.shape[:2]\n        num_temp_dn = num_dn // num_dn_groups\n        temp_group_mask = (\n            torch.randperm(num_dn_groups) < self.num_temp_dn_groups\n        )\n        temp_group_mask = temp_group_mask.to(device=dn_anchor.device)\n        dn_instance_feature = dn_instance_feature.detach().reshape(\n            bs, num_dn_groups, num_temp_dn, -1\n        )[:, temp_group_mask]\n        dn_anchor = dn_anchor.detach().reshape(\n            bs, num_dn_groups, num_temp_dn, -1\n        )[:, temp_group_mask]\n        dn_cls_target = dn_cls_target.reshape(bs, num_dn_groups, num_temp_dn)[\n            :, temp_group_mask\n        ]\n        valid_mask = valid_mask.reshape(bs, num_dn_groups, num_temp_dn)[\n            :, temp_group_mask\n        ]\n        if dn_id_target is not None:\n            dn_id_target = dn_id_target.reshape(\n                bs, num_dn_groups, num_temp_dn\n            )[:, temp_group_mask]\n        self.dn_metas = dict(\n            dn_instance_feature=dn_instance_feature,\n            dn_anchor=dn_anchor,\n            dn_cls_target=dn_cls_target,\n            valid_mask=valid_mask,\n            dn_id_target=dn_id_target,\n        )\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/grid_mask.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\nfrom PIL import Image\n\n\nclass Grid(object):\n    def __init__(\n        self, use_h, use_w, rotate=1, offset=False, ratio=0.5, mode=0, prob=1.0\n    ):\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode = mode\n        self.st_prob = prob\n        self.prob = prob\n\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch\n\n    def __call__(self, img, label):\n        if np.random.rand() > self.prob:\n            return img, label\n        h = img.size(1)\n        w = img.size(2)\n        self.d1 = 2\n        self.d2 = min(h, w)\n        hh = int(1.5 * h)\n        ww = int(1.5 * w)\n        d = np.random.randint(self.d1, self.d2)\n        if self.ratio == 1:\n            self.l = np.random.randint(1, d)\n        else:\n            self.l = min(max(int(d * self.ratio + 0.5), 1), d - 1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh // d):\n                s = d * i + st_h\n                t = min(s + self.l, hh)\n                mask[s:t, :] *= 0\n        if self.use_w:\n            for i in range(ww // d):\n                s = d * i + st_w\n                t = min(s + self.l, ww)\n                mask[:, s:t] *= 0\n\n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[\n            (hh - h) // 2 : (hh - h) // 2 + h,\n            (ww - w) // 2 : (ww - w) // 2 + w,\n        ]\n\n        mask = torch.from_numpy(mask).float()\n        if self.mode == 1:\n            mask = 1 - mask\n\n        mask = mask.expand_as(img)\n        if self.offset:\n            offset = torch.from_numpy(2 * (np.random.rand(h, w) - 0.5)).float()\n            offset = (1 - mask) * offset\n            img = img * mask + offset\n        else:\n            img = img * mask\n\n        return img, label\n\n\nclass GridMask(nn.Module):\n    def __init__(\n        self, use_h, use_w, rotate=1, offset=False, ratio=0.5, mode=0, prob=1.0\n    ):\n        super(GridMask, self).__init__()\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode = mode\n        self.st_prob = prob\n        self.prob = prob\n\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch  # + 1.#0.5\n\n    def forward(self, x):\n        if np.random.rand() > self.prob or not self.training:\n            return x\n        n, c, h, w = x.size()\n        x = x.view(-1, h, w)\n        hh = int(1.5 * h)\n        ww = int(1.5 * w)\n        d = np.random.randint(2, h)\n        self.l = min(max(int(d * self.ratio + 0.5), 1), d - 1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh // d):\n                s = d * i + st_h\n                t = min(s + self.l, hh)\n                mask[s:t, :] *= 0\n        if self.use_w:\n            for i in range(ww // d):\n                s = d * i + st_w\n                t = min(s + self.l, ww)\n                mask[:, s:t] *= 0\n\n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[\n            (hh - h) // 2 : (hh - h) // 2 + h,\n            (ww - w) // 2 : (ww - w) // 2 + w,\n        ]\n\n        mask = torch.from_numpy(mask.copy()).float().cuda()\n        if self.mode == 1:\n            mask = 1 - mask\n        mask = mask.expand_as(x)\n        if self.offset:\n            offset = (\n                torch.from_numpy(2 * (np.random.rand(h, w) - 0.5))\n                .float()\n                .cuda()\n            )\n            x = x * mask + offset * (1 - mask)\n        else:\n            x = x * mask\n\n        return x.view(n, c, h, w)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/instance_bank.py",
    "content": "import torch\nfrom torch import nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\n\n__all__ = [\"InstanceBank\"]\n\n\ndef topk(confidence, k, *inputs):\n    bs, N = confidence.shape[:2]\n    confidence, indices = torch.topk(confidence, k, dim=1)\n    indices = (\n        indices + torch.arange(bs, device=indices.device)[:, None] * N\n    ).reshape(-1)\n    outputs = []\n    for input in inputs:\n        outputs.append(input.flatten(end_dim=1)[indices].reshape(bs, k, -1))\n    return confidence, outputs\n\n\n@PLUGIN_LAYERS.register_module()\nclass InstanceBank(nn.Module):\n    def __init__(\n        self,\n        num_anchor,\n        embed_dims,\n        anchor,\n        anchor_handler=None,\n        num_temp_instances=0,\n        default_time_interval=0.5,\n        confidence_decay=0.6,\n        anchor_grad=True,\n        feat_grad=True,\n        max_time_interval=2,\n    ):\n        super(InstanceBank, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_temp_instances = num_temp_instances\n        self.default_time_interval = default_time_interval\n        self.confidence_decay = confidence_decay\n        self.max_time_interval = max_time_interval\n\n        if anchor_handler is not None:\n            anchor_handler = build_from_cfg(anchor_handler, PLUGIN_LAYERS)\n            assert hasattr(anchor_handler, \"anchor_projection\")\n        self.anchor_handler = anchor_handler\n        if isinstance(anchor, str):\n            anchor = np.load(anchor)\n        elif isinstance(anchor, (list, tuple)):\n            anchor = np.array(anchor)\n        if len(anchor.shape) == 3: # for map\n            anchor = anchor.reshape(anchor.shape[0], -1)\n        self.num_anchor = min(len(anchor), num_anchor)\n        anchor = anchor[:num_anchor]\n        self.anchor = nn.Parameter(\n            torch.tensor(anchor, dtype=torch.float32),\n            requires_grad=anchor_grad,\n        )\n        self.anchor_init = anchor\n        self.instance_feature = nn.Parameter(\n            torch.zeros([self.anchor.shape[0], self.embed_dims]),\n            requires_grad=feat_grad,\n        )\n        self.reset()\n\n    def init_weight(self):\n        self.anchor.data = self.anchor.data.new_tensor(self.anchor_init)\n        if self.instance_feature.requires_grad:\n            torch.nn.init.xavier_uniform_(self.instance_feature.data, gain=1)\n\n    def reset(self):\n        self.cached_feature = None\n        self.cached_anchor = None\n        self.metas = None\n        self.mask = None\n        self.confidence = None\n        self.temp_confidence = None\n        self.instance_id = None\n        self.prev_id = 0\n\n    def get(self, batch_size, metas=None, dn_metas=None):\n        instance_feature = torch.tile(\n            self.instance_feature[None], (batch_size, 1, 1)\n        )\n        anchor = torch.tile(self.anchor[None], (batch_size, 1, 1))\n\n        if (\n            self.cached_anchor is not None\n            and batch_size == self.cached_anchor.shape[0]\n        ):\n            history_time = self.metas[\"timestamp\"]\n            time_interval = metas[\"timestamp\"] - history_time\n            time_interval = time_interval.to(dtype=instance_feature.dtype)\n            self.mask = torch.abs(time_interval) <= self.max_time_interval\n\n            if self.anchor_handler is not None:\n                T_temp2cur = self.cached_anchor.new_tensor(\n                    np.stack(\n                        [\n                            x[\"T_global_inv\"]\n                            @ self.metas[\"img_metas\"][i][\"T_global\"]\n                            for i, x in enumerate(metas[\"img_metas\"])\n                        ]\n                    )\n                )\n                self.cached_anchor = self.anchor_handler.anchor_projection(\n                    self.cached_anchor,\n                    [T_temp2cur],\n                    time_intervals=[-time_interval],\n                )[0]\n\n            if (\n                self.anchor_handler is not None\n                and dn_metas is not None\n                and batch_size == dn_metas[\"dn_anchor\"].shape[0]\n            ):\n                num_dn_group, num_dn = dn_metas[\"dn_anchor\"].shape[1:3]\n                dn_anchor = self.anchor_handler.anchor_projection(\n                    dn_metas[\"dn_anchor\"].flatten(1, 2),\n                    [T_temp2cur],\n                    time_intervals=[-time_interval],\n                )[0]\n                dn_metas[\"dn_anchor\"] = dn_anchor.reshape(\n                    batch_size, num_dn_group, num_dn, -1\n                )\n            time_interval = torch.where(\n                torch.logical_and(time_interval != 0, self.mask),\n                time_interval,\n                time_interval.new_tensor(self.default_time_interval),\n            )\n        else:\n            self.reset()\n            time_interval = instance_feature.new_tensor(\n                [self.default_time_interval] * batch_size\n            )\n\n        return (\n            instance_feature,\n            anchor,\n            self.cached_feature,\n            self.cached_anchor,\n            time_interval,\n        )\n\n    def update(self, instance_feature, anchor, confidence):\n        if self.cached_feature is None:\n            return instance_feature, anchor\n\n        num_dn = 0\n        if instance_feature.shape[1] > self.num_anchor:\n            num_dn = instance_feature.shape[1] - self.num_anchor\n            dn_instance_feature = instance_feature[:, -num_dn:]\n            dn_anchor = anchor[:, -num_dn:]\n            instance_feature = instance_feature[:, : self.num_anchor]\n            anchor = anchor[:, : self.num_anchor]\n            confidence = confidence[:, : self.num_anchor]\n\n        N = self.num_anchor - self.num_temp_instances\n        confidence = confidence.max(dim=-1).values\n        _, (selected_feature, selected_anchor) = topk(\n            confidence, N, instance_feature, anchor\n        )\n        selected_feature = torch.cat(\n            [self.cached_feature, selected_feature], dim=1\n        )\n        selected_anchor = torch.cat(\n            [self.cached_anchor, selected_anchor], dim=1\n        )\n        instance_feature = torch.where(\n            self.mask[:, None, None], selected_feature, instance_feature\n        )\n        anchor = torch.where(self.mask[:, None, None], selected_anchor, anchor)\n        self.confidence = torch.where(\n            self.mask[:, None],\n            self.confidence,\n            self.confidence.new_tensor(0)\n        )\n        if self.instance_id is not None:\n            self.instance_id = torch.where(\n                self.mask[:, None],\n                self.instance_id,\n                self.instance_id.new_tensor(-1),\n            )\n\n        if num_dn > 0:\n            instance_feature = torch.cat(\n                [instance_feature, dn_instance_feature], dim=1\n            )\n            anchor = torch.cat([anchor, dn_anchor], dim=1)\n        return instance_feature, anchor\n\n    def cache(\n        self,\n        instance_feature,\n        anchor,\n        confidence,\n        metas=None,\n        feature_maps=None,\n    ):\n        if self.num_temp_instances <= 0:\n            return\n        instance_feature = instance_feature.detach()\n        anchor = anchor.detach()\n        confidence = confidence.detach()\n\n        self.metas = metas\n        confidence = confidence.max(dim=-1).values.sigmoid()\n        if self.confidence is not None:\n            confidence[:, : self.num_temp_instances] = torch.maximum(\n                self.confidence * self.confidence_decay,\n                confidence[:, : self.num_temp_instances],\n            )\n        self.temp_confidence = confidence\n\n        (\n            self.confidence,\n            (self.cached_feature, self.cached_anchor),\n        ) = topk(confidence, self.num_temp_instances, instance_feature, anchor)\n\n    def get_instance_id(self, confidence, anchor=None, threshold=None):\n        confidence = confidence.max(dim=-1).values.sigmoid()\n        instance_id = confidence.new_full(confidence.shape, -1).long()\n\n        if (\n            self.instance_id is not None\n            and self.instance_id.shape[0] == instance_id.shape[0]\n        ):\n            instance_id[:, : self.instance_id.shape[1]] = self.instance_id\n\n        mask = instance_id < 0\n        if threshold is not None:\n            mask = mask & (confidence >= threshold)\n        num_new_instance = mask.sum()\n        new_ids = torch.arange(num_new_instance).to(instance_id) + self.prev_id\n        instance_id[torch.where(mask)] = new_ids\n        self.prev_id += num_new_instance\n        self.update_instance_id(instance_id, confidence)\n        return instance_id\n\n    def update_instance_id(self, instance_id=None, confidence=None):\n        if self.temp_confidence is None:\n            if confidence.dim() == 3:  # bs, num_anchor, num_cls\n                temp_conf = confidence.max(dim=-1).values\n            else:  # bs, num_anchor\n                temp_conf = confidence\n        else:\n            temp_conf = self.temp_confidence\n        instance_id = topk(temp_conf, self.num_temp_instances, instance_id)[1][\n            0\n        ]\n        instance_id = instance_id.squeeze(dim=-1)\n        self.instance_id = F.pad(\n            instance_id,\n            (0, self.num_anchor - self.num_temp_instances),\n            value=-1,\n        )"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/map/__init__.py",
    "content": "from .decoder import SparsePoint3DDecoder\nfrom .target import SparsePoint3DTarget, HungarianLinesAssigner\nfrom .match_cost import LinesL1Cost, MapQueriesCost\nfrom .loss import LinesL1Loss, SparseLineLoss\nfrom .map_blocks import (\n    SparsePoint3DRefinementModule,\n    SparsePoint3DKeyPointsGenerator,\n    SparsePoint3DEncoder,\n)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/map/decoder.py",
    "content": "from typing import Optional, List\n\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\n\n@BBOX_CODERS.register_module()\nclass SparsePoint3DDecoder(object):\n    def __init__(\n        self,\n        coords_dim: int = 2,\n        score_threshold: Optional[float] = None,\n    ):\n        super(SparsePoint3DDecoder, self).__init__()\n        self.score_threshold = score_threshold\n        self.coords_dim = coords_dim\n\n    def decode(\n        self,\n        cls_scores,\n        pts_preds,\n        instance_id=None,\n        quality=None,\n        output_idx=-1,\n    ):\n        bs, num_pred, num_cls = cls_scores[-1].shape\n        cls_scores = cls_scores[-1].sigmoid()\n        pts_preds = pts_preds[-1].reshape(bs, num_pred, -1, self.coords_dim)\n        cls_scores, indices = cls_scores.flatten(start_dim=1).topk(\n            num_pred, dim=1\n        )\n        cls_ids = indices % num_cls\n        if self.score_threshold is not None:\n            mask = cls_scores >= self.score_threshold\n        output = []\n        for i in range(bs):\n            category_ids = cls_ids[i]\n            scores = cls_scores[i]\n            pts = pts_preds[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                category_ids = category_ids[mask[i]]\n                scores = scores[mask[i]]\n                pts = pts[mask[i]]\n\n            output.append(\n                {\n                    \"vectors\": [vec.detach().cpu().numpy() for vec in pts],\n                    \"scores\": scores.detach().cpu().numpy(),\n                    \"labels\": category_ids.detach().cpu().numpy(),\n                }\n            )\n        return output"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/map/loss.py",
    "content": "import torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.models.builder import LOSSES\nfrom mmdet.models.losses import l1_loss, smooth_l1_loss\n\n\n@LOSSES.register_module()\nclass LinesL1Loss(nn.Module):\n\n    def __init__(self, reduction='mean', loss_weight=1.0, beta=0.5):\n        \"\"\"\n            L1 loss. The same as the smooth L1 loss\n            Args:\n                reduction (str, optional): The method to reduce the loss.\n                    Options are \"none\", \"mean\" and \"sum\".\n                loss_weight (float, optional): The weight of loss.\n        \"\"\"\n\n        super().__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n        self.beta = beta\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n        Args:\n            pred (torch.Tensor): The prediction.\n                shape: [bs, ...]\n            target (torch.Tensor): The learning target of the prediction.\n                shape: [bs, ...]\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None. \n                it's useful when the predictions are not all valid.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        if self.beta > 0:\n            loss = smooth_l1_loss(\n                pred, target, weight, reduction=reduction, avg_factor=avg_factor, beta=self.beta)\n        \n        else:\n            loss = l1_loss(\n                pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        \n        num_points = pred.shape[-1] // 2\n        loss = loss / num_points\n\n        return loss*self.loss_weight\n\n\n@LOSSES.register_module()\nclass SparseLineLoss(nn.Module):\n    def __init__(\n        self,\n        loss_line,\n        num_sample=20,\n        roi_size=(30, 60),\n    ):\n        super().__init__()\n\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.loss_line = build(loss_line, LOSSES)\n        self.num_sample = num_sample\n        self.roi_size = roi_size\n\n    def forward(\n        self,\n        line,\n        line_target,\n        weight=None,\n        avg_factor=None,\n        prefix=\"\",\n        suffix=\"\",\n        **kwargs,\n    ):\n\n        output = {}\n        line = self.normalize_line(line)\n        line_target = self.normalize_line(line_target)\n        line_loss = self.loss_line(\n            line, line_target, weight=weight, avg_factor=avg_factor\n        )\n        output[f\"{prefix}loss_line{suffix}\"] = line_loss\n\n        return output\n\n    def normalize_line(self, line):\n        if line.shape[0] == 0:\n            return line\n\n        line = line.view(line.shape[:-1] + (self.num_sample, -1))\n        \n        origin = -line.new_tensor([self.roi_size[0]/2, self.roi_size[1]/2])\n        line = line - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        norm = line.new_tensor([self.roi_size[0], self.roi_size[1]]) + eps\n        line = line / norm\n        line = line.flatten(-2, -1)\n\n        return line\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/map/map_blocks.py",
    "content": "from typing import Optional, List, Tuple\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom mmcv.cnn import Linear, Scale, bias_init_with_prob\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.registry import (\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n)\n\nfrom ..blocks import linear_relu_ln\n\n\n@POSITIONAL_ENCODING.register_module()\nclass SparsePoint3DEncoder(BaseModule):\n    def __init__(\n        self, \n        embed_dims: int = 256,\n        num_sample: int = 20,\n        coords_dim: int = 2,\n    ):\n        super(SparsePoint3DEncoder, self).__init__()\n        self.embed_dims = embed_dims\n        self.input_dims = num_sample * coords_dim\n        def embedding_layer(input_dims):\n            return nn.Sequential(*linear_relu_ln(embed_dims, 1, 2, input_dims))\n\n        self.pos_fc = embedding_layer(self.input_dims)\n\n    def forward(self, anchor: torch.Tensor):\n        pos_feat = self.pos_fc(anchor)  \n        return pos_feat\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparsePoint3DRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims: int = 256,\n        num_sample: int = 20,\n        coords_dim: int = 2,\n        num_cls: int = 3,\n        with_cls_branch: bool = True,\n    ):\n        super(SparsePoint3DRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_sample = num_sample\n        self.output_dim = num_sample * coords_dim\n        self.num_cls = num_cls\n\n        self.layers = nn.Sequential(\n            *linear_relu_ln(embed_dims, 2, 2),\n            Linear(self.embed_dims, self.output_dim),\n            Scale([1.0] * self.output_dim),\n        )\n\n        self.with_cls_branch = with_cls_branch\n        if with_cls_branch:\n            self.cls_layers = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2),\n                Linear(self.embed_dims, self.num_cls),\n            )\n\n    def init_weight(self):\n        if self.with_cls_branch:\n            bias_init = bias_init_with_prob(0.01)\n            nn.init.constant_(self.cls_layers[-1].bias, bias_init)\n\n    def forward(\n        self,\n        instance_feature: torch.Tensor,\n        anchor: torch.Tensor,\n        anchor_embed: torch.Tensor,\n        time_interval: torch.Tensor = 1.0,\n        return_cls=True,\n    ):\n        output = self.layers(instance_feature + anchor_embed)\n        output = output + anchor\n        if return_cls:\n            assert self.with_cls_branch, \"Without classification layers !!!\"\n            cls = self.cls_layers(instance_feature)  ## NOTE anchor embed?\n        else:\n            cls = None\n        qt = None\n        return output, cls, qt\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparsePoint3DKeyPointsGenerator(BaseModule): \n    def __init__(\n        self,\n        embed_dims: int = 256,\n        num_sample: int = 20,\n        num_learnable_pts: int = 0,\n        fix_height: Tuple = (0,),\n        ground_height: int = 0,\n    ):\n        super(SparsePoint3DKeyPointsGenerator, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_sample = num_sample\n        self.num_learnable_pts = num_learnable_pts\n        self.num_pts = num_sample * len(fix_height) * num_learnable_pts\n        if self.num_learnable_pts > 0:\n            self.learnable_fc = Linear(self.embed_dims, self.num_pts * 2)\n\n        self.fix_height = np.array(fix_height)\n        self.ground_height = ground_height\n\n    def init_weight(self):\n        if self.num_learnable_pts > 0:\n            xavier_init(self.learnable_fc, distribution=\"uniform\", bias=0.0)\n\n    def forward(\n        self,\n        anchor,\n        instance_feature=None,\n        T_cur2temp_list=None,\n        cur_timestamp=None,\n        temp_timestamps=None,\n    ):\n        assert self.num_learnable_pts > 0, 'No learnable pts'\n        bs, num_anchor, _ = anchor.shape\n        key_points = anchor.view(bs, num_anchor, self.num_sample, -1)\n        offset = (\n            self.learnable_fc(instance_feature)\n            .reshape(bs, num_anchor, self.num_sample, len(self.fix_height), self.num_learnable_pts, 2)\n        )        \n        key_points = offset + key_points[..., None, None, :]\n        key_points = torch.cat(\n            [\n                key_points,\n                key_points.new_full(key_points.shape[:-1]+(1,), fill_value=self.ground_height),\n            ],\n            dim=-1,\n        )\n        fix_height = key_points.new_tensor(self.fix_height)\n        height_offset = key_points.new_zeros([len(fix_height), 2])\n        height_offset = torch.cat([height_offset, fix_height[:,None]], dim=-1)\n        key_points = key_points + height_offset[None, None, None, :, None]\n        key_points = key_points.flatten(2, 4)\n        if (\n            cur_timestamp is None\n            or temp_timestamps is None\n            or T_cur2temp_list is None\n            or len(temp_timestamps) == 0\n        ):\n            return key_points\n\n        temp_key_points_list = []\n        for i, t_time in enumerate(temp_timestamps):\n            temp_key_points = key_points\n            T_cur2temp = T_cur2temp_list[i].to(dtype=key_points.dtype)\n            temp_key_points = (\n                T_cur2temp[:, None, None, :3]\n                @ torch.cat(\n                    [\n                        temp_key_points,\n                        torch.ones_like(temp_key_points[..., :1]),\n                    ],\n                    dim=-1,\n                ).unsqueeze(-1)\n            )\n            temp_key_points = temp_key_points.squeeze(-1)\n            temp_key_points_list.append(temp_key_points)\n        return key_points, temp_key_points_list\n\n    # @staticmethod\n    def anchor_projection(\n        self,\n        anchor,\n        T_src2dst_list,\n        src_timestamp=None,\n        dst_timestamps=None,\n        time_intervals=None,\n    ):\n        dst_anchors = []\n        for i in range(len(T_src2dst_list)):\n            dst_anchor = anchor.clone()\n            bs, num_anchor, _ = anchor.shape\n            dst_anchor = dst_anchor.reshape(bs, num_anchor, self.num_sample, -1).flatten(1, 2)\n            T_src2dst = torch.unsqueeze(\n                T_src2dst_list[i].to(dtype=anchor.dtype), dim=1\n            )\n\n            dst_anchor = (\n                torch.matmul(\n                    T_src2dst[..., :2, :2], dst_anchor[..., None]\n                ).squeeze(dim=-1)\n                + T_src2dst[..., :2, 3]\n            )\n\n            dst_anchor = dst_anchor.reshape(bs, num_anchor, self.num_sample, -1).flatten(2, 3)\n            dst_anchors.append(dst_anchor)\n        return dst_anchors"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/map/match_cost.py",
    "content": "import torch\nfrom mmdet.core.bbox.match_costs.builder import MATCH_COST\nfrom mmdet.core.bbox.match_costs import build_match_cost\nfrom torch.nn.functional import smooth_l1_loss\n\n\n@MATCH_COST.register_module()\nclass LinesL1Cost(object):\n    \"\"\"LinesL1Cost.\n     Args:\n         weight (int | float, optional): loss_weight\n    \"\"\"\n\n    def __init__(self, weight=1.0, beta=0.0, permute=False):\n        self.weight = weight\n        self.permute = permute\n        self.beta = beta\n\n    def __call__(self, lines_pred, gt_lines, **kwargs):\n        \"\"\"\n        Args:\n            lines_pred (Tensor): predicted normalized lines:\n                [num_query, 2*num_points]\n            gt_lines (Tensor): Ground truth lines\n                [num_gt, 2*num_points] or [num_gt, num_permute, 2*num_points]\n        Returns:\n            torch.Tensor: reg_cost value with weight\n                shape [num_pred, num_gt]\n        \"\"\"        \n        if self.permute:\n            assert len(gt_lines.shape) == 3\n        else:\n            assert len(gt_lines.shape) == 2\n\n        num_pred, num_gt = len(lines_pred), len(gt_lines)\n        if self.permute:\n            # permute-invarint labels\n            gt_lines = gt_lines.flatten(0, 1) # (num_gt*num_permute, 2*num_pts)\n\n        num_pts = lines_pred.shape[-1]//2\n\n        if self.beta > 0:\n            lines_pred = lines_pred.unsqueeze(1).repeat(1, len(gt_lines), 1)\n            gt_lines = gt_lines.unsqueeze(0).repeat(num_pred, 1, 1)\n            dist_mat = smooth_l1_loss(lines_pred, gt_lines, reduction='none', beta=self.beta).sum(-1)\n        \n        else:\n            dist_mat = torch.cdist(lines_pred, gt_lines, p=1)\n\n        dist_mat = dist_mat / num_pts\n\n        if self.permute:\n            # dist_mat: (num_pred, num_gt*num_permute)\n            dist_mat = dist_mat.view(num_pred, num_gt, -1) # (num_pred, num_gt, num_permute)\n            dist_mat, gt_permute_index = torch.min(dist_mat, 2)\n            return dist_mat * self.weight, gt_permute_index\n        \n        return dist_mat * self.weight\n\n\n@MATCH_COST.register_module()\nclass MapQueriesCost(object):\n\n    def __init__(self, cls_cost, reg_cost, iou_cost=None):\n\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n\n        self.iou_cost = None\n        if iou_cost is not None:\n            self.iou_cost = build_match_cost(iou_cost)\n\n    def __call__(self, preds: dict, gts: dict, ignore_cls_cost: bool):\n\n        # classification and bboxcost.\n        cls_cost = self.cls_cost(preds['scores'], gts['labels'])\n\n        # regression cost\n        regkwargs = {}\n        if 'masks' in preds and 'masks' in gts:\n            assert isinstance(self.reg_cost, DynamicLinesCost), ' Issues!!'\n            regkwargs = {\n                'masks_pred': preds['masks'],\n                'masks_gt': gts['masks'],\n            }\n\n        reg_cost = self.reg_cost(preds['lines'], gts['lines'], **regkwargs)\n        if self.reg_cost.permute:\n            reg_cost, gt_permute_idx = reg_cost\n\n        # weighted sum of above three costs\n        if ignore_cls_cost:\n            cost = reg_cost\n        else:\n            cost = cls_cost + reg_cost\n\n        # Iou\n        if self.iou_cost is not None:\n            iou_cost = self.iou_cost(preds['lines'],gts['lines'])\n            cost += iou_cost\n        \n        if self.reg_cost.permute:\n            return cost, gt_permute_idx\n        return cost\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/map/target.py",
    "content": "import torch\nimport numpy as np\nimport torch.nn.functional as F\nfrom scipy.optimize import linear_sum_assignment\n\nfrom mmdet.core.bbox.builder import (BBOX_SAMPLERS, BBOX_ASSIGNERS)\nfrom mmdet.core.bbox.match_costs import build_match_cost\nfrom mmdet.core import (build_assigner, build_sampler)\nfrom mmdet.core.bbox.assigners import (AssignResult, BaseAssigner)\n\nfrom ..base_target import BaseTargetWithDenoising\n\n\n@BBOX_SAMPLERS.register_module()\nclass SparsePoint3DTarget(BaseTargetWithDenoising):\n    def __init__(\n        self,\n        assigner=None,\n        num_dn_groups=0,\n        dn_noise_scale=0.5,\n        max_dn_gt=32,\n        add_neg_dn=True,\n        num_temp_dn_groups=0,\n        num_cls=3,\n        num_sample=20,\n        roi_size=(30, 60),\n    ):\n        super(SparsePoint3DTarget, self).__init__(\n            num_dn_groups, num_temp_dn_groups\n        )\n        self.assigner = build_assigner(assigner)\n        self.dn_noise_scale = dn_noise_scale\n        self.max_dn_gt = max_dn_gt\n        self.add_neg_dn = add_neg_dn\n\n        self.num_cls = num_cls\n        self.num_sample = num_sample\n        self.roi_size = roi_size\n\n    def sample(\n        self,\n        cls_preds,\n        pts_preds,\n        cls_targets,\n        pts_targets,\n    ):\n        pts_targets  = [x.flatten(2, 3) if len(x.shape)==4 else x for x in pts_targets]\n        indices = []\n        for(cls_pred, pts_pred, cls_target, pts_target) in zip(\n            cls_preds, pts_preds, cls_targets, pts_targets\n        ):\n            # normalize to (0, 1)\n            pts_pred = self.normalize_line(pts_pred)\n            pts_target = self.normalize_line(pts_target)\n            preds=dict(lines=pts_pred, scores=cls_pred)\n            gts=dict(lines=pts_target, labels=cls_target)\n            indice = self.assigner.assign(preds, gts)\n            indices.append(indice)\n        \n        bs, num_pred, num_cls = cls_preds.shape\n        output_cls_target = cls_targets[0].new_ones([bs, num_pred], dtype=torch.long) * num_cls\n        output_box_target = pts_preds.new_zeros(pts_preds.shape)\n        output_reg_weights = pts_preds.new_zeros(pts_preds.shape)\n        for i, (pred_idx, target_idx, gt_permute_index) in enumerate(indices):\n            if len(cls_targets[i]) == 0:\n                continue\n            permute_idx = gt_permute_index[pred_idx, target_idx]\n            output_cls_target[i, pred_idx] = cls_targets[i][target_idx]\n            output_box_target[i, pred_idx] = pts_targets[i][target_idx, permute_idx]\n            output_reg_weights[i, pred_idx] = 1\n\n        return output_cls_target, output_box_target, output_reg_weights\n\n    def normalize_line(self, line):\n        if line.shape[0] == 0:\n            return line\n        \n        line = line.view(line.shape[:-1] + (self.num_sample, -1))\n        \n        origin = -line.new_tensor([self.roi_size[0]/2, self.roi_size[1]/2])\n        line = line - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        norm = line.new_tensor([self.roi_size[0], self.roi_size[1]]) + eps\n        line = line / norm\n        line = line.flatten(-2, -1)\n\n        return line\n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianLinesAssigner(BaseAssigner):\n    \"\"\"\n        Computes one-to-one matching between predictions and ground truth.\n        This class computes an assignment between the targets and the predictions\n        based on the costs. The costs are weighted sum of three components:\n        classification cost and regression L1 cost. The\n        targets don't include the no_object, so generally there are more\n        predictions than targets. After the one-to-one matching, the un-matched\n        are treated as backgrounds. Thus each query prediction will be assigned\n        with `0` or a positive integer indicating the ground truth index:\n        - 0: negative sample, no assigned gt\n        - positive integer: positive sample, index (1-based) of assigned gt\n        Args:\n            cls_weight (int | float, optional): The scale factor for classification\n                cost. Default 1.0.\n            bbox_weight (int | float, optional): The scale factor for regression\n                L1 cost. Default 1.0.\n    \"\"\"\n\n    def __init__(self, cost=dict, **kwargs):\n        self.cost = build_match_cost(cost)\n\n    def assign(self,\n               preds: dict,\n               gts: dict,\n               ignore_cls_cost=False,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"\n            Computes one-to-one matching based on the weighted costs.\n            This method assign each query prediction to a ground truth or\n            background. The `assigned_gt_inds` with -1 means don't care,\n            0 means negative sample, and positive number is the index (1-based)\n            of assigned gt.\n            The assignment is done in the following steps, the order matters.\n            1. assign every prediction to -1\n            2. compute the weighted costs\n            3. do Hungarian matching on CPU based on the costs\n            4. assign all to 0 (background) first, then for each matched pair\n            between predictions and gts, treat this prediction as foreground\n            and assign the corresponding gt index (plus 1) to it.\n            Args:\n                lines_pred (Tensor): predicted normalized lines:\n                    [num_query, num_points, 2]\n                cls_pred (Tensor): Predicted classification logits, shape\n                    [num_query, num_class].\n\n                lines_gt (Tensor): Ground truth lines\n                    [num_gt, num_points, 2].\n                labels_gt (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n                gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                    labelled as `ignored`. Default None.\n                eps (int | float, optional): A value added to the denominator for\n                    numerical stability. Default 1e-7.\n            Returns:\n                :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        \n        num_gts, num_lines = gts['lines'].size(0), preds['lines'].size(0)\n        if num_gts == 0 or num_lines == 0:\n            return None, None, None\n\n        # compute the weighted costs\n        gt_permute_idx = None # (num_preds, num_gts)\n        if self.cost.reg_cost.permute:\n            cost, gt_permute_idx = self.cost(preds, gts, ignore_cls_cost)\n        else:\n            cost = self.cost(preds, gts, ignore_cls_cost)\n\n        # do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu().numpy()\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        return matched_row_inds, matched_col_inds, gt_permute_idx"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/__init__.py",
    "content": "from .motion_planning_head import MotionPlanningHead\nfrom .motion_planning_head_MomAD import MomADMotionPlanningHead\nfrom .motion_planning_cls_head import MotionPlanningClsHead\nfrom .motion_blocks import MotionPlanningRefinementModule, MotionPlanningClsRefinementModule\nfrom .instance_queue import InstanceQueue\nfrom .target import MotionTarget, PlanningTarget, ClsPlanningTarget\nfrom .decoder import SparseBox3DMotionDecoder, HierarchicalPlanningDecoder\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/decoder.py",
    "content": "from typing import Optional\n\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\nfrom mmdet3d_plugin.core.box3d import *\nfrom mmdet3d_plugin.models.detection3d.decoder import *\nfrom mmdet3d_plugin.datasets.utils import box3d_to_corners\n\n\n@BBOX_CODERS.register_module()\nclass SparseBox3DMotionDecoder(SparseBox3DDecoder):\n    def __init__(self):\n        super(SparseBox3DMotionDecoder, self).__init__()\n\n    def decode(\n        self,\n        cls_scores,\n        box_preds,\n        instance_id=None,\n        quality=None,\n        motion_output=None,\n        output_idx=-1,\n    ):\n        squeeze_cls = instance_id is not None\n\n        cls_scores = cls_scores[output_idx].sigmoid()\n\n        if squeeze_cls:\n            cls_scores, cls_ids = cls_scores.max(dim=-1)\n            cls_scores = cls_scores.unsqueeze(dim=-1)\n\n        box_preds = box_preds[output_idx]\n        bs, num_pred, num_cls = cls_scores.shape\n        cls_scores, indices = cls_scores.flatten(start_dim=1).topk(\n            self.num_output, dim=1, sorted=self.sorted\n        )\n        if not squeeze_cls:\n            cls_ids = indices % num_cls\n        if self.score_threshold is not None:\n            mask = cls_scores >= self.score_threshold\n\n        if quality[output_idx] is None:\n            quality = None\n        if quality is not None:\n            centerness = quality[output_idx][..., CNS]\n            centerness = torch.gather(centerness, 1, indices // num_cls)\n            cls_scores_origin = cls_scores.clone()\n            cls_scores *= centerness.sigmoid()\n            cls_scores, idx = torch.sort(cls_scores, dim=1, descending=True)\n            if not squeeze_cls:\n                cls_ids = torch.gather(cls_ids, 1, idx)\n            if self.score_threshold is not None:\n                mask = torch.gather(mask, 1, idx)\n            indices = torch.gather(indices, 1, idx)\n\n        output = []\n        anchor_queue = motion_output[\"anchor_queue\"]\n        anchor_queue = torch.stack(anchor_queue, dim=2)\n        period = motion_output[\"period\"]\n\n        for i in range(bs):\n            category_ids = cls_ids[i]\n            if squeeze_cls:\n                category_ids = category_ids[indices[i]]\n            scores = cls_scores[i]\n            box = box_preds[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                category_ids = category_ids[mask[i]]\n                scores = scores[mask[i]]\n                box = box[mask[i]]\n            if quality is not None:\n                scores_origin = cls_scores_origin[i]\n                if self.score_threshold is not None:\n                    scores_origin = scores_origin[mask[i]]\n\n            box = decode_box(box)\n            trajs = motion_output[\"prediction\"][-1]\n            traj_cls = motion_output[\"classification\"][-1].sigmoid()\n            traj = trajs[i, indices[i] // num_cls]\n            traj_cls = traj_cls[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                traj = traj[mask[i]]\n                traj_cls = traj_cls[mask[i]]\n            traj = traj.cumsum(dim=-2) + box[:, None, None, :2]\n            output.append(\n                {\n                    \"trajs_3d\": traj.cpu(),\n                    \"trajs_score\": traj_cls.cpu()\n                }\n            )\n\n            temp_anchor = anchor_queue[i, indices[i] // num_cls]\n            temp_period = period[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                temp_anchor = temp_anchor[mask[i]]\n                temp_period = temp_period[mask[i]]\n            num_pred, queue_len = temp_anchor.shape[:2]\n            temp_anchor = temp_anchor.flatten(0, 1)\n            temp_anchor = decode_box(temp_anchor)\n            temp_anchor = temp_anchor.reshape([num_pred, queue_len, box.shape[-1]])\n            output[-1]['anchor_queue'] = temp_anchor.cpu()\n            output[-1]['period'] = temp_period.cpu()\n        \n        return output\n\n\n@BBOX_CODERS.register_module()\nclass HierarchicalPlanningDecoder(object):\n    def __init__(\n        self,\n        ego_fut_ts,\n        ego_fut_mode,\n        num_cmd=3,\n        use_rescore=False,\n    ):\n        super(HierarchicalPlanningDecoder, self).__init__()\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.num_cmd = num_cmd\n        self.use_rescore = use_rescore\n    \n    def decode(\n        self, \n        det_output,\n        motion_output,\n        planning_output, \n        data,\n    ):\n        classification = planning_output['classification_refined'][-1]\n        prediction = planning_output['prediction_refined'][-1]\n        bs = classification.shape[0]\n        classification = classification.reshape(bs, self.num_cmd, self.ego_fut_mode)\n        prediction = prediction.reshape(bs, self.num_cmd, self.ego_fut_mode, self.ego_fut_ts, 2).cumsum(dim=-2)\n        classification, final_planning = self.select(det_output, motion_output, classification, prediction, data)\n        anchor_queue = planning_output[\"anchor_queue\"]\n        anchor_queue = torch.stack(anchor_queue, dim=2)\n        period = planning_output[\"period\"]\n        output = []\n        for i, (cls, pred) in enumerate(zip(classification, prediction)):\n            output.append(\n                {\n                    \"planning_score\": cls.sigmoid().cpu(),\n                    \"planning\": pred.cpu(),\n                    \"final_planning\": final_planning[i].cpu(),\n                    \"ego_period\": period[i].cpu(),\n                    \"ego_anchor_queue\": decode_box(anchor_queue[i]).cpu(),\n                }\n            )\n\n        return output\n\n    def select(\n        self,\n        det_output,\n        motion_output,\n        plan_cls,\n        plan_reg,\n        data,\n    ):\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        motion_cls = motion_output[\"classification\"][-1].sigmoid()\n        motion_reg = motion_output[\"prediction\"][-1]\n        \n        # cmd select\n        bs = motion_cls.shape[0]\n        bs_indices = torch.arange(bs, device=motion_cls.device)\n        cmd = data['gt_ego_fut_cmd'].argmax(dim=-1)\n        plan_cls_full = plan_cls.detach().clone()\n        plan_cls = plan_cls[bs_indices, cmd]\n        plan_reg = plan_reg[bs_indices, cmd]\n\n        # rescore\n        if self.use_rescore:\n            plan_cls = self.rescore(\n                plan_cls,\n                plan_reg, \n                motion_cls,\n                motion_reg, \n                det_anchors,\n                det_confidence,\n            )\n        plan_cls_full[bs_indices, cmd] = plan_cls\n        mode_idx = plan_cls.argmax(dim=-1)\n        final_planning = plan_reg[bs_indices, mode_idx]\n        return plan_cls_full, final_planning\n\n    def rescore(\n        self, \n        plan_cls,\n        plan_reg, \n        motion_cls,\n        motion_reg, \n        det_anchors,\n        det_confidence,\n        score_thresh=0.5,\n        static_dis_thresh=0.5,\n        dim_scale=1.1,\n        num_motion_mode=1,\n        offset=0.5,\n    ):\n        \n        def cat_with_zero(traj):\n            zeros = traj.new_zeros(traj.shape[:-2] + (1, 2))\n            traj_cat = torch.cat([zeros, traj], dim=-2)\n            return traj_cat\n        \n        def get_yaw(traj, start_yaw=np.pi/2):\n            yaw = traj.new_zeros(traj.shape[:-1])\n            yaw[..., 1:-1] = torch.atan2(\n                traj[..., 2:, 1] - traj[..., :-2, 1],\n                traj[..., 2:, 0] - traj[..., :-2, 0],\n            )\n            yaw[..., -1] = torch.atan2(\n                traj[..., -1, 1] - traj[..., -2, 1],\n                traj[..., -1, 0] - traj[..., -2, 0],\n            )\n            yaw[..., 0] = start_yaw\n            # for static object, estimated future yaw would be unstable\n            start = traj[..., 0, :]\n            end = traj[..., -1, :]\n            dist = torch.linalg.norm(end - start, dim=-1)\n            mask = dist < static_dis_thresh\n            start_yaw = yaw[..., 0].unsqueeze(-1)\n            yaw = torch.where(\n                mask.unsqueeze(-1),\n                start_yaw,\n                yaw,\n            )\n            return yaw.unsqueeze(-1)\n        \n        ## ego\n        bs = plan_reg.shape[0]\n        plan_reg_cat = cat_with_zero(plan_reg)\n        ego_box = det_anchors.new_zeros(bs, self.ego_fut_mode, self.ego_fut_ts + 1, 7)\n        ego_box[..., [X, Y]] = plan_reg_cat\n        ego_box[..., [W, L, H]] = ego_box.new_tensor([4.08, 1.73, 1.56]) * dim_scale\n        ego_box[..., [YAW]] = get_yaw(plan_reg_cat)\n\n        ## motion\n        motion_reg = motion_reg[..., :self.ego_fut_ts, :].cumsum(-2)\n        motion_reg = cat_with_zero(motion_reg) + det_anchors[:, :, None, None, :2]\n        _, motion_mode_idx = torch.topk(motion_cls, num_motion_mode, dim=-1)\n        motion_mode_idx = motion_mode_idx[..., None, None].repeat(1, 1, 1, self.ego_fut_ts + 1, 2)\n        motion_reg = torch.gather(motion_reg, 2, motion_mode_idx)\n\n        motion_box = motion_reg.new_zeros(motion_reg.shape[:-1] + (7,))\n        motion_box[..., [X, Y]] = motion_reg\n        motion_box[..., [W, L, H]] = det_anchors[..., None, None, [W, L, H]].exp()\n        box_yaw = torch.atan2(\n            det_anchors[..., SIN_YAW],\n            det_anchors[..., COS_YAW],\n        )\n        motion_box[..., [YAW]] = get_yaw(motion_reg, box_yaw.unsqueeze(-1))\n\n        filter_mask = det_confidence < score_thresh\n        motion_box[filter_mask] = 1e6\n\n        ego_box = ego_box[..., 1:, :]\n        motion_box = motion_box[..., 1:, :]\n\n        bs, num_ego_mode, ts, _ = ego_box.shape\n        bs, num_anchor, num_motion_mode, ts, _ = motion_box.shape\n        ego_box = ego_box[:, None, None].repeat(1, num_anchor, num_motion_mode, 1, 1, 1).flatten(0, -2)\n        motion_box = motion_box.unsqueeze(3).repeat(1, 1, 1, num_ego_mode, 1, 1).flatten(0, -2)\n\n        ego_box[0] += offset * torch.cos(ego_box[6])\n        ego_box[1] += offset * torch.sin(ego_box[6])\n        col = check_collision(ego_box, motion_box)\n        col = col.reshape(bs, num_anchor, num_motion_mode, num_ego_mode, ts).permute(0, 3, 1, 2, 4)\n        col = col.flatten(2, -1).any(dim=-1)\n        all_col = col.all(dim=-1)\n        col[all_col] = False # for case that all modes collide, no need to rescore\n        score_offset = col.float() * -999\n        plan_cls = plan_cls + score_offset\n        return plan_cls\n\n\ndef check_collision(boxes1, boxes2):\n    '''\n        A rough check for collision detection: \n            check if any corner point of boxes1 is inside boxes2 and vice versa.\n        \n        boxes1: tensor with shape [N, 7], [x, y, z, w, l, h, yaw]\n        boxes2: tensor with shape [N, 7]\n    '''\n    col_1 = corners_in_box(boxes1.clone(), boxes2.clone())\n    col_2 = corners_in_box(boxes2.clone(), boxes1.clone())\n    collision = torch.logical_or(col_1, col_2)\n\n    return collision\n\ndef corners_in_box(boxes1, boxes2):\n    if  boxes1.shape[0] == 0 or boxes2.shape[0] == 0:\n        return False\n\n    boxes1_yaw = boxes1[:, 6].clone()\n    boxes1_loc = boxes1[:, :3].clone()\n    cos_yaw = torch.cos(-boxes1_yaw)\n    sin_yaw = torch.sin(-boxes1_yaw)\n    rot_mat_T = torch.stack(\n        [\n            torch.stack([cos_yaw, sin_yaw]),\n            torch.stack([-sin_yaw, cos_yaw]),\n        ]\n    )\n    # translate and rotate boxes\n    boxes1[:, :3] = boxes1[:, :3] - boxes1_loc\n    boxes1[:, :2] = torch.einsum('ij,jki->ik', boxes1[:, :2], rot_mat_T)\n    boxes1[:, 6] = boxes1[:, 6] - boxes1_yaw\n\n    boxes2[:, :3] = boxes2[:, :3] - boxes1_loc\n    boxes2[:, :2] = torch.einsum('ij,jki->ik', boxes2[:, :2], rot_mat_T)\n    boxes2[:, 6] = boxes2[:, 6] - boxes1_yaw\n\n    corners_box2 = box3d_to_corners(boxes2)[:, [0, 3, 7, 4], :2]\n    corners_box2 = torch.from_numpy(corners_box2).to(boxes2.device)\n    H = boxes1[:, [3]]\n    W = boxes1[:, [4]]\n\n    collision = torch.logical_and(\n        torch.logical_and(corners_box2[..., 0] <= H / 2, corners_box2[..., 0] >= -H / 2),\n        torch.logical_and(corners_box2[..., 1] <= W / 2, corners_box2[..., 1] >= -W / 2),\n    )\n    collision = collision.any(dim=-1)\n\n    return collision"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/instance_queue.py",
    "content": "import copy\nimport torch\nfrom torch import nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\n\nfrom mmdet3d_plugin.ops import feature_maps_format\nfrom mmdet3d_plugin.core.box3d import *\n\nfrom ..blocks import linear_relu_ln\n\n@PLUGIN_LAYERS.register_module()\nclass InstanceQueue(nn.Module):\n    def __init__(\n        self,\n        embed_dims,\n        queue_length=0,\n        frame_rate=1,\n        tracking_threshold=0,\n        feature_map_scale=None,\n        use_ego_status=False,\n        use_tp=None,\n    ):\n        super(InstanceQueue, self).__init__()\n        self.embed_dims = embed_dims\n        self.queue_length = queue_length\n        self.frame_rate = frame_rate\n        self.tracking_threshold = tracking_threshold\n        self.use_ego_status = use_ego_status\n        self.use_tp = use_tp\n\n        kernel_size = tuple([int(x / 2) for x in feature_map_scale])\n        self.ego_feature_encoder = nn.Sequential(\n            nn.Conv2d(embed_dims, embed_dims, 3, stride=1, padding=1, bias=False),\n            nn.BatchNorm2d(embed_dims),\n            nn.Conv2d(embed_dims, embed_dims, 3, stride=2, padding=1, bias=False),\n            nn.BatchNorm2d(embed_dims),\n            nn.ReLU(),\n            nn.AvgPool2d(kernel_size),\n        )\n        self.ego_anchor = nn.Parameter(\n            torch.tensor([[0, 0.5, -1.84 + 1.56/2, np.log(4.08), np.log(1.73), np.log(1.56), 1, 0, 0, 0, 0],], dtype=torch.float32),\n            requires_grad=False,\n        )\n        if use_ego_status:\n            self.ego_status_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 10)\n            )\n        if self.use_tp is not None:\n            self.tp_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 2 * len(use_tp))\n            )\n\n        self.reset()\n\n    def reset(self):\n        self.metas = None\n        self.prev_instance_id = None\n        self.prev_confidence = None\n        self.period = None\n        self.instance_feature_queue = []\n        self.anchor_queue = []\n        self.prev_ego_status = None\n        self.ego_period = None\n        self.ego_feature_queue = []\n        self.ego_anchor_queue = []\n        self.cache_step = -1\n\n    def get(\n        self,\n        det_output,\n        feature_maps,\n        metas,\n        batch_size,\n        mask,\n        anchor_handler,\n    ):\n        if (\n            self.period is not None\n            and batch_size == self.period.shape[0]\n        ):\n            if anchor_handler is not None:\n                T_temp2cur = feature_maps[0].new_tensor(\n                    np.stack(\n                        [\n                            x[\"T_global_inv\"]\n                            @ self.metas[\"img_metas\"][i][\"T_global\"]\n                            for i, x in enumerate(metas[\"img_metas\"])\n                        ]\n                    )\n                )\n                for i in range(len(self.anchor_queue)):\n                    temp_anchor = self.anchor_queue[i]\n                    temp_anchor = anchor_handler.anchor_projection(\n                        temp_anchor,\n                        [T_temp2cur],\n                    )[0]\n                    self.anchor_queue[i] = temp_anchor\n                for i in range(len(self.ego_anchor_queue)):\n                    temp_anchor = self.ego_anchor_queue[i]\n                    temp_anchor = anchor_handler.anchor_projection(\n                        temp_anchor,\n                        [T_temp2cur],\n                    )[0]\n                    self.ego_anchor_queue[i] = temp_anchor\n        else:\n            self.reset()\n\n        self.cache_step += 1\n        self.prepare_motion(det_output, mask)\n        ego_feature, ego_anchor = self.prepare_planning(feature_maps, mask, batch_size, metas)\n\n        # temporal \n        temp_instance_feature = torch.stack(self.instance_feature_queue, dim=2)\n        temp_anchor = torch.stack(self.anchor_queue, dim=2)\n        temp_ego_feature = torch.stack(self.ego_feature_queue, dim=2)\n        temp_ego_anchor = torch.stack(self.ego_anchor_queue, dim=2)\n\n        period = torch.cat([self.period, self.ego_period], dim=1)\n        temp_instance_feature = torch.cat([temp_instance_feature, temp_ego_feature], dim=1)\n        temp_anchor = torch.cat([temp_anchor, temp_ego_anchor], dim=1)\n        num_agent = temp_anchor.shape[1]\n        \n        temp_mask = torch.arange(len(self.anchor_queue), 0, -1, device=temp_anchor.device)\n        temp_mask = temp_mask[None, None].repeat((batch_size, num_agent, 1))\n        temp_mask = torch.gt(temp_mask, period[..., None])\n\n        return ego_feature, ego_anchor, temp_instance_feature, temp_anchor, temp_mask\n\n    def prepare_motion(\n        self,\n        det_output,\n        mask,\n    ):\n        if self.cache_step % self.frame_rate != 0:\n            return\n        \n        instance_feature = det_output[\"instance_feature\"]\n        det_anchors = det_output[\"prediction\"][-1]\n\n        if self.period == None:\n            self.period = instance_feature.new_zeros(instance_feature.shape[:2]).long()\n        else:\n            instance_id = det_output['instance_id']\n            prev_instance_id = self.prev_instance_id\n            match = instance_id[..., None] == prev_instance_id[:, None]\n            if self.tracking_threshold > 0:\n                temp_mask = self.prev_confidence > self.tracking_threshold\n                match = match * temp_mask.unsqueeze(1)\n\n            for i in range(len(self.instance_feature_queue)):\n                temp_feature = self.instance_feature_queue[i]\n                temp_feature = (\n                    match[..., None] * temp_feature[:, None]\n                ).sum(dim=2)\n                self.instance_feature_queue[i] = temp_feature\n\n                temp_anchor = self.anchor_queue[i]\n                temp_anchor = (\n                    match[..., None] * temp_anchor[:, None]\n                ).sum(dim=2)\n                self.anchor_queue[i] = temp_anchor\n\n            self.period = (\n                match * self.period[:, None]\n            ).sum(dim=2)\n\n        self.instance_feature_queue.append(instance_feature.detach())\n        self.anchor_queue.append(det_anchors.detach())\n        self.period += 1\n\n        if len(self.instance_feature_queue) > self.queue_length:\n            self.instance_feature_queue.pop(0)\n            self.anchor_queue.pop(0)\n        self.period = torch.clip(self.period, 0, self.queue_length)\n\n    def prepare_planning(\n        self,\n        feature_maps,\n        mask,\n        batch_size,\n        metas,\n    ):\n        ## ego instance init\n        feature_maps_inv = feature_maps_format(feature_maps, inverse=True)\n        feature_map = feature_maps_inv[0][-1][:, 0]\n        ego_feature = self.ego_feature_encoder(feature_map)\n        ego_feature = ego_feature.unsqueeze(1).squeeze(-1).squeeze(-1)\n\n        ego_anchor = torch.tile(\n            self.ego_anchor[None], (batch_size, 1, 1)\n        )\n        if self.prev_ego_status is not None:\n            prev_ego_status = torch.where(\n                mask[:, None, None],\n                self.prev_ego_status,\n                self.prev_ego_status.new_tensor(0),\n            )\n            ego_anchor[..., VY] = prev_ego_status[..., 6]\n\n        if self.use_ego_status:\n            ego_status = metas[\"ego_status\"]\n            ego_status_embed = self.ego_status_encoder(ego_status)\n            ego_feature = ego_feature + ego_status_embed[:, None]\n            ego_anchor[..., VY] = ego_status[:, [6]]\n        \n        try:\n            if self.use_tp is not None:\n                if len(self.use_tp) == 2:\n                    tp = torch.cat([metas['tp_near'], metas['tp_far']], dim=1)\n                elif self.use_tp[0] == 'near':\n                    tp = metas['tp_near']\n                else:\n                    tp = metas['tp_far']\n                tp_embedding = self.tp_encoder(tp.float())\n                ego_feature = ego_feature + tp_embedding[:, None]\n        except:\n            import ipdb; ipdb.set_trace()\n\n        if self.cache_step % self.frame_rate != 0:\n            return ego_feature, ego_anchor\n\n        if self.ego_period == None:\n            self.ego_period = ego_feature.new_zeros((batch_size, 1)).long()\n        else:\n            self.ego_period = torch.where(\n                mask[:, None],\n                self.ego_period,\n                self.ego_period.new_tensor(0),\n            )\n\n        self.ego_feature_queue.append(ego_feature.detach())\n        self.ego_anchor_queue.append(ego_anchor.detach())\n        self.ego_period += 1\n        \n        if len(self.ego_feature_queue) > self.queue_length:\n            self.ego_feature_queue.pop(0)\n            self.ego_anchor_queue.pop(0)\n        self.ego_period = torch.clip(self.ego_period, 0, self.queue_length)\n\n        return ego_feature, ego_anchor\n\n    def cache_motion(self, instance_feature, det_output, metas):\n        if self.cache_step % self.frame_rate != 0:\n            return\n        \n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_confidence = det_classification.max(dim=-1).values\n        instance_id = det_output['instance_id']\n        self.metas = metas\n        self.prev_confidence = det_confidence.detach()\n        self.prev_instance_id = instance_id\n\n    def cache_planning(self, ego_feature, ego_status):\n        if self.cache_step % self.frame_rate != 0:\n            return\n        \n        self.prev_ego_status = ego_status.detach()\n        self.ego_feature_queue[-1] = ego_feature.detach()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/motion_blocks.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\n\nfrom mmcv.cnn import Linear, Scale, bias_init_with_prob\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.registry import (\n    PLUGIN_LAYERS,\n)\n\nfrom mmdet3d_plugin.core.box3d import *\nfrom ..blocks import linear_relu_ln\n\n\n@PLUGIN_LAYERS.register_module()\nclass MotionPlanningRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        num_cmd=3,\n        use_gru=False,\n        gru_cat_tp=False,\n    ):\n        super(MotionPlanningRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.num_cmd = num_cmd\n        self.use_gru = use_gru\n        self.gru_cat_tp = gru_cat_tp\n\n        self.motion_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        self.motion_reg_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, fut_ts * 2),\n        )\n        self.plan_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        if self.use_gru:\n            if self.gru_cat_tp:\n                input_size = 4\n            else:\n                input_size = 2\n            self.plan_reg_branch = nn.GRUCell(\n                input_size=input_size,\n                hidden_size=self.embed_dims,\n            )\n            self.output = nn.Linear(embed_dims, 2)\n        else:\n            self.plan_reg_branch = nn.Sequential(\n                nn.Linear(embed_dims, embed_dims),\n                nn.ReLU(),\n                nn.Linear(embed_dims, embed_dims),\n                nn.ReLU(),\n                nn.Linear(embed_dims, ego_fut_ts * 2),\n            )\n        self.plan_status_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, 10),\n        )\n\n    def init_weight(self):\n        bias_init = bias_init_with_prob(0.01)\n        nn.init.constant_(self.motion_cls_branch[-1].bias, bias_init)\n        nn.init.constant_(self.plan_cls_branch[-1].bias, bias_init)\n\n    def forward(\n        self,\n        motion_query,\n        plan_query,\n        ego_feature,\n        ego_anchor_embed,\n        metas,\n    ):\n        bs, num_anchor = motion_query.shape[:2]\n        motion_cls = self.motion_cls_branch(motion_query).squeeze(-1)\n        motion_reg = self.motion_reg_branch(motion_query).reshape(bs, num_anchor, self.fut_mode, self.fut_ts, 2)\n        plan_cls = self.plan_cls_branch(plan_query).squeeze(-1)\n        if self.use_gru:\n            z = plan_query.flatten(0, 2)\n            tp = metas[\"tp_near\"][:, None, None].repeat(1, self.num_cmd, self.ego_fut_mode, 1).flatten(0, 2)\n            x = torch.zeros(size=(z.shape[0], 2), dtype=z.dtype).to(z.device)\n            output_wp = []\n            for _ in range(self.ego_fut_ts):\n                if self.gru_cat_tp:\n                    x_in = torch.cat([x, tp.float()], dim=-1)\n                else:\n                    x_in = x\n            \n                z = self.plan_reg_branch(x_in, z)\n                dx = self.output(z)\n                x = dx[:, :2] + x\n                output_wp.append(x[:, :2])\n            plan_reg = torch.stack(output_wp, dim=1)\n            plan_reg = plan_reg.reshape(bs, 1, self.ego_fut_mode, self.ego_fut_ts, 2)\n        else:\n            plan_reg = self.plan_reg_branch(plan_query).reshape(bs, 1, self.num_cmd * self.ego_fut_mode, self.ego_fut_ts, 2)\n        planning_status = self.plan_status_branch(ego_feature + ego_anchor_embed)\n        return motion_cls, motion_reg, plan_cls, plan_reg, planning_status\n\n\n@PLUGIN_LAYERS.register_module()\nclass MotionPlanningClsRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        num_cmd=3,\n        use_gru=False,\n        gru_cat_tp=False,\n    ):\n        super(MotionPlanningClsRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.num_cmd = num_cmd\n        self.use_gru = use_gru\n        self.gru_cat_tp = gru_cat_tp\n\n        self.motion_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        self.motion_reg_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, fut_ts * 2),\n        )\n        self.plan_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        # if self.use_gru:\n        #     if self.gru_cat_tp:\n        #         input_size = 4\n        #     else:\n        #         input_size = 2\n        #     self.plan_reg_branch = nn.GRUCell(\n        #         input_size=input_size,\n        #         hidden_size=self.embed_dims,\n        #     )\n        #     self.output = nn.Linear(embed_dims, 2)\n        # else:\n        #     self.plan_reg_branch = nn.Sequential(\n        #         nn.Linear(embed_dims, embed_dims),\n        #         nn.ReLU(),\n        #         nn.Linear(embed_dims, embed_dims),\n        #         nn.ReLU(),\n        #         nn.Linear(embed_dims, ego_fut_ts * 2),\n        #     )\n        self.plan_status_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, 10),\n        )\n\n    def init_weight(self):\n        bias_init = bias_init_with_prob(0.01)\n        nn.init.constant_(self.motion_cls_branch[-1].bias, bias_init)\n        nn.init.constant_(self.plan_cls_branch[-1].bias, bias_init)\n\n    def forward(\n        self,\n        motion_query,\n        plan_query,\n        ego_feature,\n        ego_anchor_embed,\n        metas,\n    ):\n        bs, num_anchor = motion_query.shape[:2]\n        motion_cls = self.motion_cls_branch(motion_query).squeeze(-1)\n        motion_reg = self.motion_reg_branch(motion_query).reshape(bs, num_anchor, self.fut_mode, self.fut_ts, 2)\n        plan_cls = self.plan_cls_branch(plan_query).squeeze(-1)\n        planning_status = self.plan_status_branch(ego_feature + ego_anchor_embed)\n        return motion_cls, motion_reg, plan_cls, planning_status\n\n\n@PLUGIN_LAYERS.register_module()\nclass MotionPlanning2thRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        num_cmd=3,\n        use_gru=False,\n        gru_cat_tp=False,\n    ):\n        super(MotionPlanning2thRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.num_cmd = num_cmd\n        self.use_gru = use_gru\n        self.gru_cat_tp = gru_cat_tp\n\n        self.plan_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        if self.use_gru:\n            if self.gru_cat_tp:\n                input_size = 4\n            else:\n                input_size = 2\n            self.plan_reg_branch = nn.GRUCell(\n                input_size=input_size,\n                hidden_size=self.embed_dims,\n            )\n            self.output = nn.Linear(embed_dims, 2)\n        else:\n            self.plan_reg_branch = nn.Sequential(\n                nn.Linear(embed_dims, embed_dims),\n                nn.ReLU(),\n                nn.Linear(embed_dims, embed_dims),\n                nn.ReLU(),\n                nn.Linear(embed_dims, ego_fut_ts * 2),\n            )\n        self.plan_status_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, 10),\n        )\n\n    def init_weight(self):\n        bias_init = bias_init_with_prob(0.01)\n        #nn.init.constant_(self.motion_cls_branch[-1].bias, bias_init)\n        nn.init.constant_(self.plan_cls_branch[-1].bias, bias_init)\n\n    def forward(\n        self,\n        plan_query,\n        ego_feature,\n        ego_anchor_embed,\n        metas,\n    ):\n        bs = plan_query.shape[0]\n        plan_cls = self.plan_cls_branch(plan_query).squeeze(-1)\n        if self.use_gru:\n            z = plan_query.flatten(0, 2)\n            tp = metas[\"tp_near\"][:, None, None].repeat(1, self.num_cmd, self.ego_fut_mode, 1).flatten(0, 2)\n            x = torch.zeros(size=(z.shape[0], 2), dtype=z.dtype).to(z.device)\n            output_wp = []\n            for _ in range(self.ego_fut_ts):\n                if self.gru_cat_tp:\n                    x_in = torch.cat([x, tp.float()], dim=-1)\n                else:\n                    x_in = x\n            \n                z = self.plan_reg_branch(x_in, z)\n                dx = self.output(z)\n                x = dx[:, :2] + x\n                output_wp.append(x[:, :2])\n            plan_reg = torch.stack(output_wp, dim=1)\n            plan_reg = plan_reg.reshape(bs, 1, self.ego_fut_mode, self.ego_fut_ts, 2)\n        else:\n            plan_reg = self.plan_reg_branch(plan_query).reshape(bs, 1, self.num_cmd * self.ego_fut_mode, self.ego_fut_ts, 2)\n        planning_status = self.plan_status_branch(ego_feature + ego_anchor_embed)\n        return plan_cls, plan_reg, planning_status"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/motion_planning_cls_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\nimport copy\n\nimport numpy as np\nimport cv2\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn import Linear, bias_init_with_prob\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmdet.core import reduce_mean\nfrom mmdet.models import HEADS\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS, BBOX_CODERS\nfrom mmdet.models import build_loss\n\nfrom mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom mmdet3d_plugin.core.box3d import *\n\nfrom ..attention import gen_sineembed_for_position\nfrom ..blocks import linear_relu_ln\nfrom ..instance_bank import topk\n\n\n@HEADS.register_module()\nclass MotionPlanningClsHead(BaseModule):\n    def __init__(\n        self,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        motion_anchor=None,\n        plan_anchor=None,\n        embed_dims=256,\n        decouple_attn=False,\n        instance_queue=None,\n        operation_order=None,\n        temp_graph_model=None,\n        graph_model=None,\n        cross_graph_model=None,\n        norm_layer=None,\n        ffn=None,\n        refine_layer=None,\n        motion_sampler=None,\n        motion_loss_cls=None,\n        motion_loss_reg=None,\n        planning_sampler=None,\n        plan_loss_cls=None,\n        plan_loss_reg=None,\n        plan_loss_status=None,\n        motion_decoder=None,\n        planning_decoder=None,\n        num_det=50,\n        num_map=10,\n        use_tp=None,\n    ):\n        super(MotionPlanningClsHead, self).__init__()\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.decouple_attn = decouple_attn\n        self.operation_order = operation_order\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n        \n        self.instance_queue = build(instance_queue, PLUGIN_LAYERS)\n        self.motion_sampler = build(motion_sampler, BBOX_SAMPLERS)\n        self.planning_sampler = build(planning_sampler, BBOX_SAMPLERS)\n        self.motion_decoder = build(motion_decoder, BBOX_CODERS)\n        self.planning_decoder = build(planning_decoder, BBOX_CODERS)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"cross_gnn\": [cross_graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = embed_dims\n\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n        self.motion_loss_cls = build_loss(motion_loss_cls)\n        self.motion_loss_reg = build_loss(motion_loss_reg)\n        self.plan_loss_cls = build_loss(plan_loss_cls)\n        self.plan_loss_reg = build_loss(plan_loss_reg)\n        self.plan_loss_status = build_loss(plan_loss_status)\n\n        # motion init\n        motion_anchor = np.load(motion_anchor)\n        self.motion_anchor = nn.Parameter(\n            torch.tensor(motion_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.motion_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        # plan anchor init\n        if plan_anchor is not None:\n            plan_anchor = np.load(plan_anchor)\n            self.plan_anchor = nn.Parameter(\n                torch.tensor(plan_anchor, dtype=torch.float32),\n                requires_grad=False,\n            )\n            self.plan_anchor_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 1, embed_dims * fut_ts),\n                Linear(embed_dims, embed_dims),\n            )\n        else:\n            self.plan_mode_embedding = nn.Embedding(self.ego_fut_mode, embed_dims)\n\n        self.num_det = num_det\n        self.num_map = num_map\n        self.use_tp = use_tp\n        if self.use_tp is not None:\n            self.tp_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 2)\n            )\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def get_motion_anchor(\n        self, \n        classification, \n        prediction,\n    ):\n        cls_ids = classification.argmax(dim=-1)\n        motion_anchor = self.motion_anchor[cls_ids]\n        prediction = prediction.detach()\n        return self._agent2lidar(motion_anchor, prediction)\n\n    def _agent2lidar(self, trajs, boxes):\n        yaw = torch.atan2(boxes[..., SIN_YAW], boxes[..., COS_YAW])\n        cos_yaw = torch.cos(yaw)\n        sin_yaw = torch.sin(yaw)\n        rot_mat_T = torch.stack(\n            [\n                torch.stack([cos_yaw, sin_yaw]),\n                torch.stack([-sin_yaw, cos_yaw]),\n            ]\n        )\n\n        trajs_lidar = torch.einsum('abcij,jkab->abcik', trajs, rot_mat_T)\n        return trajs_lidar\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self, \n        det_output,\n        map_output,\n        feature_maps,\n        metas,\n        anchor_encoder,\n        mask,\n        anchor_handler,\n    ):   \n        # =========== det/map feature/anchor ===========\n        instance_feature = det_output[\"instance_feature\"]\n        anchor_embed = det_output[\"anchor_embed\"]\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        _, (instance_feature_selected, anchor_embed_selected) = topk(\n            det_confidence, self.num_det, instance_feature, anchor_embed\n        )\n\n        map_instance_feature = map_output[\"instance_feature\"]\n        map_anchor_embed = map_output[\"anchor_embed\"]\n        map_classification = map_output[\"classification\"][-1].sigmoid()\n        map_anchors = map_output[\"prediction\"][-1]\n        map_confidence = map_classification.max(dim=-1).values\n        _, (map_instance_feature_selected, map_anchor_embed_selected) = topk(\n            map_confidence, self.num_map, map_instance_feature, map_anchor_embed\n        )\n\n        # =========== get ego/temporal feature/anchor ===========\n        bs, num_anchor, dim = instance_feature.shape\n        (\n            ego_feature,\n            ego_anchor,\n            temp_instance_feature,\n            temp_anchor,\n            temp_mask,\n        ) = self.instance_queue.get(\n            det_output,\n            feature_maps,\n            metas,\n            bs,\n            mask,\n            anchor_handler,\n        )\n        ego_anchor_embed = anchor_encoder(ego_anchor)\n        temp_anchor_embed = anchor_encoder(temp_anchor)\n        temp_instance_feature = temp_instance_feature.flatten(0, 1)\n        temp_anchor_embed = temp_anchor_embed.flatten(0, 1)\n        temp_mask = temp_mask.flatten(0, 1)\n\n        # =========== motion init ===========\n        motion_anchor = self.get_motion_anchor(det_classification, det_anchors)\n        motion_mode_query = self.motion_anchor_encoder(gen_sineembed_for_position(motion_anchor[..., -1, :]))\n\n        # =========== plan init ===========\n        # anchor_idx = torch.randint(0, self.plan_anchor.shape[0], (bs, self.ego_fut_mode)).to(self.plan_anchor.device)\n        # if self.training:\n        #     gt_traj = metas['gt_ego_fut_trajs'].cumsum(-2)\n        #     gt_mask = metas['gt_ego_fut_masks']\n        #     dist = torch.linalg.norm(self.plan_anchor[None] - gt_traj[:, None], dim=-1)\n        #     dist = (dist * gt_mask[:, None]).mean(dim=-1)\n        #     best_match_index = dist.argmin(dim=1)\n        #     anchor_idx[:, -1] = best_match_index\n        #     for i in range(bs):\n        #         if best_match_index[i] not in anchor_idx[i]:\n        #             anchor_idx[i][-1] = best_match_index[i]\n        # plan_anchor = self.plan_anchor[anchor_idx]\n        #import pdb;pdb.set_trace()\n        #plan_anchor = self.plan_anchor[None].reshape(self.plan_anchor.shape[0]*self.plan_anchor.shape[1], self.plan_anchor.shape[2], self.plan_anchor.shape[3])\n        #[6,6,2]\n        plan_anchor = plan_anchor[None].repeat(bs, 1, 1, 1)\n        plan_pos = gen_sineembed_for_position(plan_anchor)\n        plan_mode_query = self.plan_anchor_encoder(plan_pos.flatten(2, 3)).unsqueeze(1)\n\n        # =========== cat instance and ego ===========\n        instance_feature_selected = torch.cat([instance_feature_selected, ego_feature], dim=1)\n        anchor_embed_selected = torch.cat([anchor_embed_selected, ego_anchor_embed], dim=1)\n\n        instance_feature = torch.cat([instance_feature, ego_feature], dim=1)\n        anchor_embed = torch.cat([anchor_embed, ego_anchor_embed], dim=1)\n\n        # =================== forward the layers ====================\n        motion_classification = []\n        motion_prediction = []\n        planning_classification = []\n        planning_prediction = []\n        planning_status = []\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature.flatten(0, 1).unsqueeze(1),\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed.flatten(0, 1).unsqueeze(1),\n                    key_pos=temp_anchor_embed,\n                    key_padding_mask=temp_mask,\n                )\n                instance_feature = instance_feature.reshape(bs, num_anchor + 1, dim)\n            elif op == \"gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    instance_feature_selected,\n                    instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=anchor_embed_selected,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"cross_gnn\":\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    key=map_instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=map_anchor_embed_selected,\n                )\n            elif op == \"refine\":\n                if self.use_tp:\n                    tp_embedding = self.tp_encoder(metas[\"tp_near\"].float())\n                    instance_feature[:, num_anchor:] = instance_feature[:, num_anchor:] + tp_embedding[:, None]\n                motion_query = motion_mode_query + (instance_feature + anchor_embed)[:, :num_anchor].unsqueeze(2)\n                plan_query = plan_mode_query + (instance_feature + anchor_embed)[:, num_anchor:].unsqueeze(2)\n                (\n                    motion_cls,\n                    motion_reg,\n                    plan_cls,\n                    plan_status,\n                ) = self.layers[i](\n                    motion_query,\n                    plan_query,\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                    metas,\n                )\n                plan_reg = torch.cat([plan_anchor.new_zeros([bs, self.ego_fut_mode, 1, 2]), plan_anchor], dim=-2)\n                plan_reg = plan_reg[..., 1:, :] - plan_reg[..., :-1, :]\n                plan_reg = plan_reg.unsqueeze(1)\n                motion_classification.append(motion_cls)\n                motion_prediction.append(motion_reg)\n                planning_classification.append(plan_cls)\n                planning_prediction.append(plan_reg)\n                planning_status.append(plan_status)\n        \n        self.instance_queue.cache_motion(instance_feature[:, :num_anchor], det_output, metas)\n        self.instance_queue.cache_planning(instance_feature[:, num_anchor:], plan_status)\n\n        motion_output = {\n            \"classification\": motion_classification,\n            \"prediction\": motion_prediction,\n            \"period\": self.instance_queue.period,\n            \"anchor_queue\": self.instance_queue.anchor_queue,\n        }\n        planning_output = {\n            \"classification\": planning_classification,\n            \"prediction\": planning_prediction,\n            \"status\": planning_status,\n            \"period\": self.instance_queue.ego_period,\n            \"anchor_queue\": self.instance_queue.ego_anchor_queue,\n        }\n        return motion_output, planning_output\n    \n    def loss(self,\n        motion_model_outs, \n        planning_model_outs,\n        data, \n        motion_loss_cache\n    ):\n        loss = {}\n        motion_loss = self.loss_motion(motion_model_outs, data, motion_loss_cache)\n        loss.update(motion_loss)\n        planning_loss = self.loss_planning(planning_model_outs, data)\n        loss.update(planning_loss)\n        return loss\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_motion(self, model_outs, data, motion_loss_cache):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        output = {}\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(cls_scores, reg_preds)\n        ):\n            (\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n                num_pos\n            ) = self.motion_sampler.sample(\n                reg,\n                data[\"gt_agent_fut_trajs\"],\n                data[\"gt_agent_fut_masks\"],\n                motion_loss_cache,\n            )\n            num_pos = max(reduce_mean(num_pos), 1.0)\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.motion_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=num_pos)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n            reg_pred = reg_pred.cumsum(dim=-2)\n            reg_target = reg_target.cumsum(dim=-2)\n            reg_loss = self.motion_loss_reg(\n                reg_pred, reg_target, weight=reg_weight, avg_factor=num_pos\n            )\n\n            output.update(\n                {\n                    f\"motion_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"motion_loss_reg_{decoder_idx}\": reg_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning(self, model_outs, data):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        status_preds = model_outs[\"status\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            bs = cls.shape[0]\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=bs*self.ego_fut_mode)\n\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_status_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(\n        self, \n        det_output,\n        motion_output,\n        planning_output,\n        data,\n    ):\n        motion_result = self.motion_decoder.decode(\n            det_output[\"classification\"],\n            det_output[\"prediction\"],\n            det_output.get(\"instance_id\"),\n            det_output.get(\"quality\"),\n            motion_output,\n        )\n        planning_result = self.planning_decoder.decode(\n            det_output,\n            motion_output,\n            planning_output, \n            data,\n        )\n\n        return motion_result, planning_result"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/motion_planning_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\nimport copy\n\nimport numpy as np\nimport cv2\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn import Linear, bias_init_with_prob\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmdet.core import reduce_mean\nfrom mmdet.models import HEADS\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS, BBOX_CODERS\nfrom mmdet.models import build_loss\n\nfrom mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom mmdet3d_plugin.core.box3d import *\n\nfrom ..attention import gen_sineembed_for_position\nfrom ..blocks import linear_relu_ln\nfrom ..instance_bank import topk\n\n\n@HEADS.register_module()\nclass MotionPlanningHead(BaseModule):\n    def __init__(\n        self,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        motion_anchor=None,\n        plan_anchor=None,\n        embed_dims=256,\n        decouple_attn=False,\n        instance_queue=None,\n        operation_order=None,\n        temp_graph_model=None,\n        graph_model=None,\n        cross_graph_model=None,\n        norm_layer=None,\n        ffn=None,\n        refine_layer=None,\n        motion_sampler=None,\n        motion_loss_cls=None,\n        motion_loss_reg=None,\n        planning_sampler=None,\n        plan_loss_cls=None,\n        plan_loss_reg=None,\n        plan_loss_status=None,\n        motion_decoder=None,\n        planning_decoder=None,\n        num_det=50,\n        num_map=10,\n        use_tp=None,\n    ):\n        super(MotionPlanningHead, self).__init__()\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.decouple_attn = decouple_attn\n        self.operation_order = operation_order\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n        \n        self.instance_queue = build(instance_queue, PLUGIN_LAYERS)\n        self.motion_sampler = build(motion_sampler, BBOX_SAMPLERS)\n        self.planning_sampler = build(planning_sampler, BBOX_SAMPLERS)\n        self.motion_decoder = build(motion_decoder, BBOX_CODERS)\n        self.planning_decoder = build(planning_decoder, BBOX_CODERS)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"cross_gnn\": [cross_graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = embed_dims\n\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n        self.motion_loss_cls = build_loss(motion_loss_cls)\n        self.motion_loss_reg = build_loss(motion_loss_reg)\n        self.plan_loss_cls = build_loss(plan_loss_cls)\n        self.plan_loss_reg = build_loss(plan_loss_reg)\n        self.plan_loss_status = build_loss(plan_loss_status)\n\n        # motion init\n        motion_anchor = np.load(motion_anchor)\n        self.motion_anchor = nn.Parameter(\n            torch.tensor(motion_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.motion_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        # plan anchor init\n        if plan_anchor is not None:\n            plan_anchor = np.load(plan_anchor)\n            self.plan_anchor = nn.Parameter(\n                torch.tensor(plan_anchor, dtype=torch.float32),\n                requires_grad=False,\n            )\n            self.plan_anchor_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 1),\n                Linear(embed_dims, embed_dims),\n            )\n        else:\n            self.plan_mode_embedding = nn.Embedding(self.ego_fut_mode, embed_dims)\n\n        self.num_det = num_det\n        self.num_map = num_map\n        self.use_tp = use_tp\n        if self.use_tp is not None:\n            self.tp_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 2)\n            )\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def get_motion_anchor(\n        self, \n        classification, \n        prediction,\n    ):\n        cls_ids = classification.argmax(dim=-1)\n        motion_anchor = self.motion_anchor[cls_ids]\n        prediction = prediction.detach()\n        return self._agent2lidar(motion_anchor, prediction)\n\n    def _agent2lidar(self, trajs, boxes):\n        yaw = torch.atan2(boxes[..., SIN_YAW], boxes[..., COS_YAW])\n        cos_yaw = torch.cos(yaw)\n        sin_yaw = torch.sin(yaw)\n        rot_mat_T = torch.stack(\n            [\n                torch.stack([cos_yaw, sin_yaw]),\n                torch.stack([-sin_yaw, cos_yaw]),\n            ]\n        )\n\n        trajs_lidar = torch.einsum('abcij,jkab->abcik', trajs, rot_mat_T)\n        return trajs_lidar\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self, \n        det_output,\n        map_output,\n        feature_maps,\n        metas,\n        anchor_encoder,\n        mask,\n        anchor_handler,\n    ):   \n        # =========== det/map feature/anchor ===========\n        instance_feature = det_output[\"instance_feature\"]\n        anchor_embed = det_output[\"anchor_embed\"]\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        _, (instance_feature_selected, anchor_embed_selected) = topk(\n            det_confidence, self.num_det, instance_feature, anchor_embed\n        )\n\n        map_instance_feature = map_output[\"instance_feature\"]\n        map_anchor_embed = map_output[\"anchor_embed\"]\n        map_classification = map_output[\"classification\"][-1].sigmoid()\n        map_anchors = map_output[\"prediction\"][-1]\n        map_confidence = map_classification.max(dim=-1).values\n        _, (map_instance_feature_selected, map_anchor_embed_selected) = topk(\n            map_confidence, self.num_map, map_instance_feature, map_anchor_embed\n        )\n\n        # =========== get ego/temporal feature/anchor ===========\n        bs, num_anchor, dim = instance_feature.shape\n        (\n            ego_feature,\n            ego_anchor,\n            temp_instance_feature,\n            temp_anchor,\n            temp_mask,\n        ) = self.instance_queue.get(\n            det_output,\n            feature_maps,\n            metas,\n            bs,\n            mask,\n            anchor_handler,\n        )\n        ego_anchor_embed = anchor_encoder(ego_anchor)\n        temp_anchor_embed = anchor_encoder(temp_anchor)\n        temp_instance_feature = temp_instance_feature.flatten(0, 1)\n        temp_anchor_embed = temp_anchor_embed.flatten(0, 1)\n        temp_mask = temp_mask.flatten(0, 1)\n\n        # =========== motion init ===========\n        motion_anchor = self.get_motion_anchor(det_classification, det_anchors)\n        motion_mode_query = self.motion_anchor_encoder(gen_sineembed_for_position(motion_anchor[..., -1, :]))\n\n        # =========== plan init ===========\n        if hasattr(self, \"plan_anchor\"):\n            plan_anchor = torch.tile(\n                self.plan_anchor[None], (bs, 1, 1, 1, 1)\n            )\n            plan_pos = gen_sineembed_for_position(plan_anchor[..., -1, :])\n            plan_mode_query = self.plan_anchor_encoder(plan_pos).flatten(1, 2).unsqueeze(1)\n        else:\n            plan_mode_query = torch.tile(\n                self.plan_mode_embedding.weight[None, None], (bs, 1, 1, 1)\n            )\n\n        # =========== cat instance and ego ===========\n        instance_feature_selected = torch.cat([instance_feature_selected, ego_feature], dim=1)\n        anchor_embed_selected = torch.cat([anchor_embed_selected, ego_anchor_embed], dim=1)\n\n        instance_feature = torch.cat([instance_feature, ego_feature], dim=1)\n        anchor_embed = torch.cat([anchor_embed, ego_anchor_embed], dim=1)\n\n        # =================== forward the layers ====================\n        motion_classification = []\n        motion_prediction = []\n        planning_classification = []\n        planning_prediction = []\n        planning_status = []\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature.flatten(0, 1).unsqueeze(1),\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed.flatten(0, 1).unsqueeze(1),\n                    key_pos=temp_anchor_embed,\n                    key_padding_mask=temp_mask,\n                )\n                instance_feature = instance_feature.reshape(bs, num_anchor + 1, dim)\n            elif op == \"gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    instance_feature_selected,\n                    instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=anchor_embed_selected,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"cross_gnn\":\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    key=map_instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=map_anchor_embed_selected,\n                )\n            elif op == \"refine\":\n                if self.use_tp:\n                    tp_embedding = self.tp_encoder(metas[\"tp_near\"].float())\n                    instance_feature[:, num_anchor:] = instance_feature[:, num_anchor:] + tp_embedding[:, None]\n                motion_query = motion_mode_query + (instance_feature + anchor_embed)[:, :num_anchor].unsqueeze(2)\n                plan_query = plan_mode_query + (instance_feature + anchor_embed)[:, num_anchor:].unsqueeze(2)\n                (\n                    motion_cls,\n                    motion_reg,\n                    plan_cls,\n                    plan_reg,\n                    plan_status,\n                ) = self.layers[i](\n                    motion_query,\n                    plan_query,\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                    metas,\n                )\n                motion_classification.append(motion_cls)\n                motion_prediction.append(motion_reg)\n                planning_classification.append(plan_cls)\n                planning_prediction.append(plan_reg)\n                planning_status.append(plan_status)\n        \n        self.instance_queue.cache_motion(instance_feature[:, :num_anchor], det_output, metas)\n        self.instance_queue.cache_planning(instance_feature[:, num_anchor:], plan_status)\n\n        motion_output = {\n            \"classification\": motion_classification,\n            \"prediction\": motion_prediction,\n            \"period\": self.instance_queue.period,\n            \"anchor_queue\": self.instance_queue.anchor_queue,\n        }\n        \n        planning_output = {\n            \"classification\": planning_classification,\n            \"prediction\": planning_prediction,\n            \"status\": planning_status,\n            \"period\": self.instance_queue.ego_period,\n            \"anchor_queue\": self.instance_queue.ego_anchor_queue,\n        }\n        return motion_output, planning_output\n    \n    def loss(self,\n        motion_model_outs, \n        planning_model_outs,\n        data, \n        motion_loss_cache\n    ):\n        loss = {}\n        motion_loss = self.loss_motion(motion_model_outs, data, motion_loss_cache)\n        loss.update(motion_loss)\n        planning_loss = self.loss_planning(planning_model_outs, data)\n        loss.update(planning_loss)\n        return loss\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_motion(self, model_outs, data, motion_loss_cache):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        output = {}\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(cls_scores, reg_preds)\n        ):\n            (\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n                num_pos\n            ) = self.motion_sampler.sample(\n                reg,\n                data[\"gt_agent_fut_trajs\"],\n                data[\"gt_agent_fut_masks\"],\n                motion_loss_cache,\n            )\n            num_pos = max(reduce_mean(num_pos), 1.0)\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.motion_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=num_pos)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n            reg_pred = reg_pred.cumsum(dim=-2)\n            reg_target = reg_target.cumsum(dim=-2)\n            reg_loss = self.motion_loss_reg(\n                reg_pred, reg_target, weight=reg_weight, avg_factor=num_pos\n            )\n\n            output.update(\n                {\n                    f\"motion_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"motion_loss_reg_{decoder_idx}\": reg_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning(self, model_outs, data):\n        cls_scores = model_outs[\"classification\"]#[1,2,1,6]\n        reg_preds = model_outs[\"prediction\"]     #[1,2,1,6,6,2]\n        status_preds = model_outs[\"status\"]      #[1,2,1,10]\n        output = {}\n        import pdb; pdb.set_trace() \n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,#torch.Size([2, 1, 6])\n                reg,#torch.Size([2, 1, 6, 6, 2])\n                data['gt_ego_fut_trajs'],#torch.Size([2, 6, 2])\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(\n        self, \n        det_output,\n        motion_output,\n        planning_output,\n        data,\n    ):\n        motion_result = self.motion_decoder.decode(\n            det_output[\"classification\"],\n            det_output[\"prediction\"],\n            det_output.get(\"instance_id\"),\n            det_output.get(\"quality\"),\n            motion_output,\n        )\n        planning_result = self.planning_decoder.decode(\n            det_output,\n            motion_output,\n            planning_output, \n            data,\n        )\n\n        return motion_result, planning_result"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/motion_planning_head_MomAD.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\nimport copy\n\nimport numpy as np\nimport cv2\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn import Linear, bias_init_with_prob\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmdet.core import reduce_mean\nfrom mmdet.models import HEADS\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS, BBOX_CODERS\nfrom mmdet.models import build_loss\n\nfrom mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom mmdet3d_plugin.core.box3d import *\nfrom mmdet3d_plugin.models.motion.motion_blocks import *\n\nfrom ..attention import gen_sineembed_for_position\nfrom ..blocks import linear_relu_ln\nfrom ..instance_bank import topk\n\n\n\n\nclass MLP(nn.Module):\n    def __init__(self, in_channels, hidden_unit, verbose=False):\n        super(MLP, self).__init__()\n        self.mlp = nn.Sequential(\n            nn.Linear(in_channels, hidden_unit),\n            nn.LayerNorm(hidden_unit),\n            nn.ReLU()\n        )\n\n    def forward(self, x):\n        x = self.mlp(x)\n        return x\n\nclass LaneNet(nn.Module):\n    def __init__(self, in_channels, hidden_unit, num_subgraph_layers):\n        super(LaneNet, self).__init__()\n        self.num_subgraph_layers = num_subgraph_layers\n        self.layer_seq = nn.Sequential()\n        for i in range(num_subgraph_layers):\n            self.layer_seq.add_module(\n                f'lmlp_{i}', MLP(in_channels, hidden_unit))\n            in_channels = hidden_unit*2\n\n    def forward(self, pts_lane_feats):\n        '''\n            Extract lane_feature from vectorized lane representation\n\n        Args:\n            pts_lane_feats: [batch size, max_pnum, pts, D]\n\n        Returns:\n            inst_lane_feats: [batch size, max_pnum, D]\n        '''\n        x = pts_lane_feats\n        for name, layer in self.layer_seq.named_modules():\n            if isinstance(layer, MLP):\n                # x [bs,max_lane_num,9,dim]\n                x = layer(x)\n                x_max = torch.max(x, -2)[0]\n                x_max = x_max.unsqueeze(2).repeat(1, 1, x.shape[2], 1)\n                x = torch.cat([x, x_max], dim=-1)\n        x_max = torch.max(x, -2)[0]\n        return x_max\n\n\n\n@HEADS.register_module()\nclass MomADMotionPlanningHead(BaseModule):\n    def __init__(\n        self,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        motion_anchor=None,\n        plan_anchor=None,\n        embed_dims=256,\n        decouple_attn=False,\n        instance_queue=None,\n        operation_order=None,\n        temp_graph_model=None,\n        graph_model=None,\n        cross_graph_model=None,\n        norm_layer=None,\n        ffn=None,\n        refine_layer=None,\n        motion_sampler=None,\n        motion_loss_cls=None,\n        motion_loss_reg=None,\n        planning_sampler=None,\n        plan_loss_cls=None,\n        plan_loss_reg=None,\n        plan_loss_status=None,\n        motion_decoder=None,\n        planning_decoder=None,\n        num_det=50,\n        num_map=10,\n        use_tp=None,\n    ):\n        super(MomADMotionPlanningHead, self).__init__()\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.decouple_attn = decouple_attn\n        self.operation_order = operation_order\n        #import pdb;pdb.set_trace()\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n        \n        self.instance_queue = build(instance_queue, PLUGIN_LAYERS)\n        self.motion_sampler = build(motion_sampler, BBOX_SAMPLERS)\n        self.planning_sampler = build(planning_sampler, BBOX_SAMPLERS)\n        self.motion_decoder = build(motion_decoder, BBOX_CODERS)\n        self.planning_decoder = build(planning_decoder, BBOX_CODERS)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"cross_gnn\": [cross_graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = embed_dims\n\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n        self.motion_loss_cls = build_loss(motion_loss_cls)\n        self.motion_loss_reg = build_loss(motion_loss_reg)\n        self.plan_loss_cls = build_loss(plan_loss_cls)\n        self.plan_loss_reg = build_loss(plan_loss_reg)\n        self.plan_loss_status = build_loss(plan_loss_status)\n\n        # motion init\n        motion_anchor = np.load(motion_anchor)\n        self.motion_anchor = nn.Parameter(\n            torch.tensor(motion_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.motion_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        # plan anchor init\n        if plan_anchor is not None:\n            plan_anchor = np.load(plan_anchor)\n            self.plan_anchor = nn.Parameter(\n                torch.tensor(plan_anchor, dtype=torch.float32),\n                requires_grad=False,\n            )\n            self.plan_anchor_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 1),\n                Linear(embed_dims, embed_dims),\n            )\n        else:\n            self.plan_mode_embedding = nn.Embedding(self.ego_fut_mode, embed_dims)\n\n        self.num_det = num_det\n        self.num_map = num_map\n        self.use_tp = use_tp\n        if self.use_tp is not None:\n            self.tp_encoder = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 2)\n            )\n        self.ego_his_encoder = LaneNet(2,128,3)\n        \n        self.refine_2th_layer = MotionPlanning2thRefinementModule(embed_dims=256,\n                ego_fut_ts=6,\n                ego_fut_mode=6,\n                num_cmd=1,\n                use_gru=False)\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def get_motion_anchor(\n        self, \n        classification, \n        prediction,\n    ):\n        cls_ids = classification.argmax(dim=-1)\n        motion_anchor = self.motion_anchor[cls_ids]\n        prediction = prediction.detach()\n        return self._agent2lidar(motion_anchor, prediction)\n\n    def _agent2lidar(self, trajs, boxes):\n        yaw = torch.atan2(boxes[..., SIN_YAW], boxes[..., COS_YAW])\n        cos_yaw = torch.cos(yaw)\n        sin_yaw = torch.sin(yaw)\n        rot_mat_T = torch.stack(\n            [\n                torch.stack([cos_yaw, sin_yaw]),\n                torch.stack([-sin_yaw, cos_yaw]),\n            ]\n        )\n\n        trajs_lidar = torch.einsum('abcij,jkab->abcik', trajs, rot_mat_T)\n        return trajs_lidar\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self, \n        det_output,\n        map_output,\n        feature_maps,\n        metas,\n        anchor_encoder,\n        mask,\n        anchor_handler,\n    ):   \n        # =========== det/map feature/anchor ===========\n        #import pdb;pdb.set_trace()\n        instance_feature = det_output[\"instance_feature\"]\n        anchor_embed = det_output[\"anchor_embed\"]\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        _, (instance_feature_selected, anchor_embed_selected) = topk(\n            det_confidence, self.num_det, instance_feature, anchor_embed\n        )\n        if 'ego_his_trajs' not in metas.keys():\n            ego_his_trajs = None\n            #ego_his_traj = metas['ego_his_trajs'] # [bs,6,2]\n            #ego_his_feats = self.ego_his_encoder(ego_his_traj.unsqueeze(1)) # [6,1,512]\n        else:\n            ego_his_trajs = None\n        #import pdb;pdb.set_trace()\n        map_instance_feature = map_output[\"instance_feature\"]\n        map_anchor_embed = map_output[\"anchor_embed\"]\n        map_classification = map_output[\"classification\"][-1].sigmoid()\n        map_anchors = map_output[\"prediction\"][-1]\n        map_confidence = map_classification.max(dim=-1).values\n        _, (map_instance_feature_selected, map_anchor_embed_selected) = topk(\n            map_confidence, self.num_map, map_instance_feature, map_anchor_embed\n        )\n\n        # =========== get ego/temporal feature/anchor ===========\n        bs, num_anchor, dim = instance_feature.shape\n        (\n            ego_feature,\n            ego_anchor,\n            temp_instance_feature,\n            temp_anchor,\n            temp_mask,\n        ) = self.instance_queue.get(\n            det_output,\n            feature_maps,\n            metas,\n            bs,\n            mask,\n            anchor_handler,\n        )\n        ego_anchor_embed = anchor_encoder(ego_anchor)\n        temp_anchor_embed = anchor_encoder(temp_anchor)\n        temp_instance_feature = temp_instance_feature.flatten(0, 1)\n        temp_anchor_embed = temp_anchor_embed.flatten(0, 1)\n        temp_mask = temp_mask.flatten(0, 1)\n\n        # =========== motion init ===========\n        motion_anchor = self.get_motion_anchor(det_classification, det_anchors)\n        motion_mode_query = self.motion_anchor_encoder(gen_sineembed_for_position(motion_anchor[..., -1, :]))\n\n        # =========== plan init ===========\n        if hasattr(self, \"plan_anchor\"):\n            plan_anchor = torch.tile(\n                self.plan_anchor[None], (bs, 1, 1, 1, 1)\n            )\n            plan_pos = gen_sineembed_for_position(plan_anchor[..., -1, :])\n            plan_mode_query = self.plan_anchor_encoder(plan_pos).flatten(1, 2).unsqueeze(1)\n        else:\n            plan_mode_query = torch.tile(\n                self.plan_mode_embedding.weight[None, None], (bs, 1, 1, 1)\n            )\n\n        # =========== cat instance and ego ===========\n        instance_feature_selected = torch.cat([instance_feature_selected, ego_feature], dim=1)\n        anchor_embed_selected = torch.cat([anchor_embed_selected, ego_anchor_embed], dim=1)\n\n        instance_feature = torch.cat([instance_feature, ego_feature], dim=1)\n        anchor_embed = torch.cat([anchor_embed, ego_anchor_embed], dim=1)\n\n        # =================== forward the layers ====================\n        motion_classification = []\n        motion_prediction = []\n        planning_classification = []\n        planning_prediction = []\n        planning_status = []\n        planning_classification_refined = []\n        planning_prediction_refined = []\n        planning_status_refined = []\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature.flatten(0, 1).unsqueeze(1),\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed.flatten(0, 1).unsqueeze(1),\n                    key_pos=temp_anchor_embed,\n                    key_padding_mask=temp_mask,\n                )\n                instance_feature = instance_feature.reshape(bs, num_anchor + 1, dim)\n            elif op == \"gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    instance_feature_selected,\n                    instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=anchor_embed_selected,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"cross_gnn\":\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    key=map_instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=map_anchor_embed_selected,\n                )\n            elif op == \"refine\":\n                if self.use_tp:\n                    tp_embedding = self.tp_encoder(metas[\"tp_near\"].float())\n                    instance_feature[:, num_anchor:] = instance_feature[:, num_anchor:] + tp_embedding[:, None]\n                motion_query = motion_mode_query + (instance_feature + anchor_embed)[:, :num_anchor].unsqueeze(2)\n                plan_query = plan_mode_query + (instance_feature + anchor_embed)[:, num_anchor:].unsqueeze(2)\n                (\n                    motion_cls,\n                    motion_reg,\n                    plan_cls,\n                    plan_reg,\n                    plan_status,\n                ) = self.layers[i](\n                    motion_query,\n                    plan_query,\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                    metas,\n                ) # [6.1.6.256]\n                motion_classification.append(motion_cls)\n                motion_prediction.append(motion_reg)\n                planning_classification.append(plan_cls)\n                planning_prediction.append(plan_reg)\n                planning_status.append(plan_status)\n        \n        self.instance_queue.cache_motion(instance_feature[:, :num_anchor], det_output, metas)\n        self.instance_queue.cache_planning(instance_feature[:, num_anchor:], plan_status)\n\n        motion_output = {\n            \"classification\": motion_classification,\n            \"prediction\": motion_prediction,\n            \"period\": self.instance_queue.period,\n            \"anchor_queue\": self.instance_queue.anchor_queue,\n        }\n        #import pdb;pdb.set_trace()\n        \n        # [6.1.6.256] [6, 1, 256]\n        if ego_his_trajs != None:\n            selected_idx = self.select_best_reg(planning_prediction[0],ego_his_traj.unsqueeze(1))\n            ego_his_feats = ego_his_feats.unsqueeze(2).repeat(1,1,planning_prediction[0].shape[2],1)\n            # [6,1,6,256]\n            his_mask = torch.zeros_like(ego_his_feats).to(ego_his_feats.device)\n            his_mask[torch.arange(ego_his_feats.shape[0]).unsqueeze(1), :, selected_idx, :] = 1\n            plan_query = plan_query + ego_his_feats*his_mask\n        #ego_his_feats = ego_his_feats.repeat(1, ego_feats.shape[1], 1)\n        plan_cls_2th, plan_reg_2th, plan_status_2th = self.refine_2th_layer(\n                    plan_query,\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                    metas)\n        \n        planning_classification_refined.append(plan_cls_2th)\n        planning_prediction_refined.append(plan_reg_2th)\n        planning_status_refined.append(plan_status_2th)\n        \n        #import pdb;pdb.set_trace()\n        planning_output = {\n            \"classification\": planning_classification,\n            \"prediction\": planning_prediction, # [[6,1,6,6,2]]\n            \"status\": planning_status, # [[6, 1, 10]]\n            \"classification_refined\": planning_classification_refined,#[6, 1, 18] #3是command\n            \"prediction_refined\": planning_prediction_refined,#[6, 1, 18, 6, 2]\n            \"status_refined\": planning_status_refined,#[6, 1, 10]\n            \"period\": self.instance_queue.ego_period,\n            \"anchor_queue\": self.instance_queue.ego_anchor_queue,\n        }\n        return motion_output, planning_output\n    \n    def select_best_reg(self, reg_preds, reg_target):\n        bs, num_pred, mode, ts, d = reg_preds.shape # plan [6,1,6,2] [1,6,6,6,2]\n        reg_preds_cum = reg_preds.cumsum(dim=-2)\n        reg_preds_cum = reg_preds_cum.reshape(bs, num_pred*mode, ts, d) # [1,36,6,2]\n        reg_target_cum = reg_target.cumsum(dim=-2) # [1,1,6,2]\n        reg_preds_cum = reg_preds_cum.unsqueeze(1) # [1,1,36,6,2]\n        #import pdb;pdb.set_trace()\n        dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1) # [6,1,6,6]\n        #dist = dist * reg_weight.unsqueeze(2) # reg_weight.unsqueeze(2) = [6,1,6,6]\n        dist = dist.mean(dim=-1)\n        mode_idx = torch.argmin(dist, dim=-1) # [6,1] 0,4,1,0,0,1\n        return mode_idx\n    \n    def loss(self,\n        motion_model_outs, \n        planning_model_outs,\n        data, \n        motion_loss_cache\n    ):\n        loss = {}\n        motion_loss = self.loss_motion(motion_model_outs, data, motion_loss_cache)\n        loss.update(motion_loss)\n        planning_loss = self.loss_planning(planning_model_outs, data)\n        loss.update(planning_loss)\n        planning_loss_refined = self.loss_planning_refined(planning_model_outs, data)\n        loss.update(planning_loss_refined)\n        return loss\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_motion(self, model_outs, data, motion_loss_cache):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        output = {}\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(cls_scores, reg_preds)\n        ):\n            (\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n                num_pos\n            ) = self.motion_sampler.sample(\n                reg,\n                data[\"gt_agent_fut_trajs\"],\n                data[\"gt_agent_fut_masks\"],\n                motion_loss_cache,\n            )\n            num_pos = max(reduce_mean(num_pos), 1.0)\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.motion_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=num_pos)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n            reg_pred = reg_pred.cumsum(dim=-2)\n            reg_target = reg_target.cumsum(dim=-2)\n            reg_loss = self.motion_loss_reg(\n                reg_pred, reg_target, weight=reg_weight, avg_factor=num_pos\n            )\n\n            output.update(\n                {\n                    f\"motion_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"motion_loss_reg_{decoder_idx}\": reg_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning(self, model_outs, data):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        status_preds = model_outs[\"status\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n    \n    \n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning_refined(self, model_outs, data):\n        cls_scores = model_outs[\"classification_refined\"]\n        reg_preds = model_outs[\"prediction_refined\"]\n        status_preds = model_outs[\"status_refined\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_refined_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_refined_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_refined_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n    \n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(\n        self, \n        det_output,\n        motion_output,\n        planning_output,\n        data,\n    ):\n        motion_result = self.motion_decoder.decode(\n            det_output[\"classification\"],\n            det_output[\"prediction\"],\n            det_output.get(\"instance_id\"),\n            det_output.get(\"quality\"),\n            motion_output,\n        )\n        planning_result = self.planning_decoder.decode(\n            det_output,\n            motion_output,\n            planning_output, \n            data,\n        )\n\n        return motion_result, planning_result"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/motion/target.py",
    "content": "import torch\n\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\n\n__all__ = [\"MotionTarget\", \"PlanningTarget\"]\n\n\ndef get_cls_target(\n    reg_preds, \n    reg_target,\n    reg_weight,\n):\n    bs, num_pred, mode, ts, d = reg_preds.shape\n    reg_preds_cum = reg_preds.cumsum(dim=-2)\n    reg_target_cum = reg_target.cumsum(dim=-2)\n    dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1)\n    dist = dist * reg_weight.unsqueeze(2)\n    dist = dist.mean(dim=-1)\n    mode_idx = torch.argmin(dist, dim=-1)\n    return mode_idx\n\ndef get_best_reg(\n    reg_preds, \n    reg_target,\n    reg_weight,\n):\n    bs, num_pred, mode, ts, d = reg_preds.shape\n    reg_preds_cum = reg_preds.cumsum(dim=-2)\n    reg_target_cum = reg_target.cumsum(dim=-2)\n    dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1)\n    dist = dist * reg_weight.unsqueeze(2)\n    dist = dist.mean(dim=-1)\n    mode_idx = torch.argmin(dist, dim=-1)\n    mode_idx = mode_idx[..., None, None, None].repeat(1, 1, 1, ts, d)\n    best_reg = torch.gather(reg_preds, 2, mode_idx).squeeze(2)\n    return best_reg\n\n\n@BBOX_SAMPLERS.register_module()\nclass MotionTarget():\n    def __init__(\n        self,\n    ):\n        super(MotionTarget, self).__init__()\n\n    def sample(\n        self,\n        reg_pred,\n        gt_reg_target,\n        gt_reg_mask,\n        motion_loss_cache,\n    ):\n        bs, num_anchor, mode, ts, d = reg_pred.shape\n        reg_target = reg_pred.new_zeros((bs, num_anchor, ts, d))\n        reg_weight = reg_pred.new_zeros((bs, num_anchor, ts))\n        indices = motion_loss_cache['indices']\n        num_pos = reg_pred.new_tensor([0])\n        for i, (pred_idx, target_idx) in enumerate(indices):\n            if len(gt_reg_target[i]) == 0:\n                continue\n            reg_target[i, pred_idx] = gt_reg_target[i][target_idx]\n            reg_weight[i, pred_idx] = gt_reg_mask[i][target_idx]\n            num_pos += len(pred_idx)\n        \n        cls_target = get_cls_target(reg_pred, reg_target, reg_weight)\n        cls_weight = reg_weight.any(dim=-1)\n        best_reg = get_best_reg(reg_pred, reg_target, reg_weight)\n\n        return cls_target, cls_weight, best_reg, reg_target, reg_weight, num_pos\n\n\n@BBOX_SAMPLERS.register_module()\nclass PlanningTarget():\n    def __init__(\n        self,\n        ego_fut_ts,\n        ego_fut_mode,\n        num_cmd=3,\n    ):\n        super(PlanningTarget, self).__init__()\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.num_cmd = num_cmd\n\n    def sample(\n        self,\n        cls_pred,\n        reg_pred,\n        gt_reg_target,\n        gt_reg_mask,\n        data,\n    ):\n        gt_reg_target = gt_reg_target.unsqueeze(1)\n        gt_reg_mask = gt_reg_mask.unsqueeze(1)\n\n        bs = reg_pred.shape[0]\n        bs_indices = torch.arange(bs, device=reg_pred.device)\n        cmd = data['gt_ego_fut_cmd'].argmax(dim=-1)\n\n        cls_pred = cls_pred.reshape(bs, self.num_cmd, 1, self.ego_fut_mode)\n        reg_pred = reg_pred.reshape(bs, self.num_cmd, 1, self.ego_fut_mode, self.ego_fut_ts, 2)\n        cls_pred = cls_pred[bs_indices, cmd]\n        reg_pred = reg_pred[bs_indices, cmd]\n        cls_target = get_cls_target(reg_pred, gt_reg_target, gt_reg_mask)\n        cls_weight = gt_reg_mask.any(dim=-1)\n        best_reg = get_best_reg(reg_pred, gt_reg_target, gt_reg_mask)\n\n        return cls_pred, cls_target, cls_weight, best_reg, gt_reg_target, gt_reg_mask\n\n\n@BBOX_SAMPLERS.register_module()\nclass ClsPlanningTarget():\n    def __init__(\n        self,\n        ego_fut_ts,\n        ego_fut_mode,\n        num_cmd=3,\n    ):\n        super(ClsPlanningTarget, self).__init__()\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.num_cmd = num_cmd\n\n    def sample(\n        self,\n        cls_pred,\n        reg_pred,\n        gt_reg_target,\n        gt_reg_mask,\n        data,\n    ):\n        cls_pred = cls_pred[:, 0] # bs, num_mode\n        reg_pred = reg_pred[:, 0].cumsum(dim=-2) # bs, num_mode, fut_ts, 2\n        gt_reg_target = gt_reg_target.cumsum(dim=-2)\n        dist = torch.linalg.norm(gt_reg_target.unsqueeze(1) - reg_pred, dim=-1)\n        dist = dist * gt_reg_mask.unsqueeze(1)\n        dist = dist.mean(dim=-1)\n        mode_idx = torch.argmin(dist, dim=-1)\n\n        bs = reg_pred.shape[0]\n        bs_indices = torch.arange(bs, device=reg_pred.device)\n        cls_target = torch.ones([bs, self.ego_fut_mode], dtype=torch.long, device=cls_pred.device)\n        cls_target[bs_indices, mode_idx] = 0\n        cls_weight = gt_reg_mask.any(dim=-1, keepdim=True) * dist * 100\n        cls_weight[bs_indices, mode_idx] = 100\n\n        return cls_pred[..., None], cls_target, cls_weight"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/sparsedrive.py",
    "content": "from inspect import signature\n\nimport torch\n\nfrom mmcv.runner import force_fp32, auto_fp16\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\nfrom mmdet.models import (\n    DETECTORS,\n    BaseDetector,\n    build_backbone,\n    build_head,\n    build_neck,\n)\nfrom .grid_mask import GridMask\n\ntry:\n    from ..ops import feature_maps_format\n    DAF_VALID = True\nexcept:\n    DAF_VALID = False\n\n__all__ = [\"SparseDrive\"]\n\n\n@DETECTORS.register_module()\nclass SparseDrive(BaseDetector):\n    def __init__(\n        self,\n        img_backbone,\n        head,\n        img_neck=None,\n        init_cfg=None,\n        train_cfg=None,\n        test_cfg=None,\n        pretrained=None,\n        use_grid_mask=True,\n        use_deformable_func=False,\n        depth_branch=None,\n        freeze_backbone=False,\n        freeze_neck=False,\n        freeze_perception=False,\n    ):\n        super(SparseDrive, self).__init__(init_cfg=init_cfg)\n        if pretrained is not None:\n            backbone.pretrained = pretrained\n        self.img_backbone = build_backbone(img_backbone)\n        if img_neck is not None:\n            self.img_neck = build_neck(img_neck)\n        self.head = build_head(head)\n        self.use_grid_mask = use_grid_mask\n        if use_deformable_func:\n            assert DAF_VALID, \"deformable_aggregation needs to be set up.\"\n        self.use_deformable_func = use_deformable_func\n        if depth_branch is not None:\n            self.depth_branch = build_from_cfg(depth_branch, PLUGIN_LAYERS)\n        else:\n            self.depth_branch = None\n        if use_grid_mask:\n            self.grid_mask = GridMask(\n                True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7\n            )\n        if freeze_backbone:\n            self.img_backbone.eval()\n            for param in self.img_backbone.parameters():\n                param.requires_grad = False\n        if freeze_neck:\n            self.img_neck.eval()\n            for param in self.img_neck.parameters():\n                param.requires_grad = False\n        if freeze_perception:\n            self.head.det_head.eval()\n            for param in self.head.det_head.parameters():\n                param.requires_grad = False\n            self.head.map_head.eval()\n            for param in self.head.map_head.parameters():\n                param.requires_grad = False\n         \n\n    @auto_fp16(apply_to=(\"img\",), out_fp32=True)\n    def extract_feat(self, img, return_depth=False, metas=None):\n        bs = img.shape[0]\n        if img.dim() == 5:  # multi-view\n            num_cams = img.shape[1]\n            img = img.flatten(end_dim=1)\n        else:\n            num_cams = 1\n        if self.use_grid_mask:\n            img = self.grid_mask(img)\n        if \"metas\" in signature(self.img_backbone.forward).parameters:\n            feature_maps = self.img_backbone(img, num_cams, metas=metas)\n        else:\n            feature_maps = self.img_backbone(img)\n        if self.img_neck is not None:\n            feature_maps = list(self.img_neck(feature_maps))\n        for i, feat in enumerate(feature_maps):\n            feature_maps[i] = torch.reshape(\n                feat, (bs, num_cams) + feat.shape[1:]\n            )\n        if return_depth and self.depth_branch is not None:\n            depths = self.depth_branch(feature_maps, metas.get(\"focal\"))\n        else:\n            depths = None\n        if self.use_deformable_func:\n            feature_maps = feature_maps_format(feature_maps)\n        if return_depth:\n            return feature_maps, depths\n        return feature_maps\n\n    @force_fp32(apply_to=(\"img\",))\n    def forward(self, img, **data):\n        if self.training:\n            return self.forward_train(img, **data)\n        else:\n            return self.forward_test(img, **data)\n\n    def forward_train(self, img, **data):\n        feature_maps, depths = self.extract_feat(img, True, data)\n        model_outs = self.head(feature_maps, data)\n        output = self.head.loss(model_outs, data)\n        if depths is not None and \"gt_depth\" in data:\n            output[\"loss_dense_depth\"] = self.depth_branch.loss(\n                depths, data[\"gt_depth\"]\n            )\n        return output\n\n    def forward_test(self, img, **data):\n        if isinstance(img, list):\n            return self.aug_test(img, **data)\n        else:\n            return self.simple_test(img, **data)\n\n    def simple_test(self, img, **data):\n        feature_maps = self.extract_feat(img)\n\n        model_outs = self.head(feature_maps, data)\n        results = self.head.post_process(model_outs, data)\n        output = [{\"img_bbox\": result} for result in results]\n        return output\n\n    def aug_test(self, img, **data):\n        # fake test time augmentation\n        for key in data.keys():\n            if isinstance(data[key], list):\n                data[key] = data[key][0]\n        return self.simple_test(img[0], **data)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/models/sparsedrive_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.runner import BaseModule\nfrom mmdet.models import HEADS\nfrom mmdet.models import build_head\n\n\n@HEADS.register_module()\nclass SparseDriveHead(BaseModule):\n    def __init__(\n        self,\n        task_config: dict,\n        det_head = dict,\n        map_head = dict,\n        motion_plan_head = dict,\n        init_cfg=None,\n        **kwargs,\n    ):\n        super(SparseDriveHead, self).__init__(init_cfg)\n        self.task_config = task_config\n        if self.task_config['with_det']:\n            self.det_head = build_head(det_head)\n        if self.task_config['with_map']:\n            self.map_head = build_head(map_head)\n        if self.task_config['with_motion_plan']:\n            self.motion_plan_head = build_head(motion_plan_head)\n\n    def init_weights(self):\n        if self.task_config['with_det']:\n            self.det_head.init_weights()\n        if self.task_config['with_map']:\n            self.map_head.init_weights()\n        if self.task_config['with_motion_plan']:\n            self.motion_plan_head.init_weights()\n\n    def forward(\n        self,\n        feature_maps: Union[torch.Tensor, List],\n        metas: dict,\n    ):\n        if self.task_config['with_det']:\n            det_output = self.det_head(feature_maps, metas)\n        else:\n            det_output = None\n\n        if self.task_config['with_map']:\n            map_output = self.map_head(feature_maps, metas)\n        else:\n            map_output = None\n        \n        if self.task_config['with_motion_plan']:\n            motion_output, planning_output = self.motion_plan_head(\n                det_output, \n                map_output, \n                feature_maps,\n                metas,\n                self.det_head.anchor_encoder,\n                self.det_head.instance_bank.mask,\n                self.det_head.instance_bank.anchor_handler,\n            )\n        else:\n            motion_output, planning_output = None, None\n\n        return det_output, map_output, motion_output, planning_output\n\n    def loss(self, model_outs, data):\n        det_output, map_output, motion_output, planning_output = model_outs\n        losses = dict()\n        if self.task_config['with_det']:\n            loss_det = self.det_head.loss(det_output, data)\n            losses.update(loss_det)\n        \n        if self.task_config['with_map']:\n            loss_map = self.map_head.loss(map_output, data)\n            losses.update(loss_map)\n\n        if self.task_config['with_motion_plan']:\n            motion_loss_cache = dict(\n                indices=self.det_head.sampler.indices, \n            )\n            loss_motion = self.motion_plan_head.loss(\n                motion_output, \n                planning_output, \n                data, \n                motion_loss_cache\n            )\n            losses.update(loss_motion)\n        \n        return losses\n\n    def post_process(self, model_outs, data):\n        det_output, map_output, motion_output, planning_output = model_outs\n        if self.task_config['with_det']:\n            det_result = self.det_head.post_process(det_output)\n            batch_size = len(det_result)\n        \n        if self.task_config['with_map']:\n            map_result= self.map_head.post_process(map_output)\n            batch_size = len(map_result)\n\n        if self.task_config['with_motion_plan']:\n            motion_result, planning_result = self.motion_plan_head.post_process(\n                det_output,\n                motion_output, \n                planning_output,\n                data,\n            )\n\n        results = [dict()] * batch_size\n        for i in range(batch_size):\n            if self.task_config['with_det']:\n                results[i].update(det_result[i])\n            if self.task_config['with_map']:\n                results[i].update(map_result[i])\n            if self.task_config['with_motion_plan']:\n                results[i].update(motion_result[i])\n                results[i].update(planning_result[i])\n\n        return results\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/ops/__init__.py",
    "content": "import torch\n\nfrom .deformable_aggregation import DeformableAggregationFunction\n\n\ndef deformable_aggregation_function(\n    feature_maps,\n    spatial_shape,\n    scale_start_index,\n    sampling_location,\n    weights,\n):\n    return DeformableAggregationFunction.apply(\n        feature_maps,\n        spatial_shape,\n        scale_start_index,\n        sampling_location,\n        weights,\n    )\n\n\ndef feature_maps_format(feature_maps, inverse=False):\n    if inverse:\n        col_feats, spatial_shape, scale_start_index = feature_maps\n        num_cams, num_levels = spatial_shape.shape[:2]\n\n        split_size = spatial_shape[..., 0] * spatial_shape[..., 1]\n        split_size = split_size.cpu().numpy().tolist()\n\n        idx = 0\n        cam_split = [1]\n        cam_split_size = [sum(split_size[0])]\n        for i in range(num_cams - 1):\n            if not torch.all(spatial_shape[i] == spatial_shape[i + 1]):\n                cam_split.append(0)\n                cam_split_size.append(0)\n            cam_split[-1] += 1\n            cam_split_size[-1] += sum(split_size[i + 1])\n        mc_feat = [\n            x.unflatten(1, (cam_split[i], -1))\n            for i, x in enumerate(col_feats.split(cam_split_size, dim=1))\n        ]\n\n        spatial_shape = spatial_shape.cpu().numpy().tolist()\n        mc_ms_feat = []\n        shape_index = 0\n        for i, feat in enumerate(mc_feat):\n            feat = list(feat.split(split_size[shape_index], dim=2))\n            for j, f in enumerate(feat):\n                feat[j] = f.unflatten(2, spatial_shape[shape_index][j])\n                feat[j] = feat[j].permute(0, 1, 4, 2, 3)\n            mc_ms_feat.append(feat)\n            shape_index += cam_split[i]\n        return mc_ms_feat\n\n    if isinstance(feature_maps[0], (list, tuple)):\n        formated = [feature_maps_format(x) for x in feature_maps]\n        col_feats = torch.cat([x[0] for x in formated], dim=1)\n        spatial_shape = torch.cat([x[1] for x in formated], dim=0)\n        scale_start_index = torch.cat([x[2] for x in formated], dim=0)\n        return [col_feats, spatial_shape, scale_start_index]\n\n    bs, num_cams = feature_maps[0].shape[:2]\n    spatial_shape = []\n\n    col_feats = []\n    for i, feat in enumerate(feature_maps):\n        spatial_shape.append(feat.shape[-2:])\n        col_feats.append(\n            torch.reshape(feat, (bs, num_cams, feat.shape[2], -1))\n        )\n\n    col_feats = torch.cat(col_feats, dim=-1).permute(0, 1, 3, 2).flatten(1, 2)\n    spatial_shape = [spatial_shape] * num_cams\n    spatial_shape = torch.tensor(\n        spatial_shape,\n        dtype=torch.int64,\n        device=col_feats.device,\n    )\n    scale_start_index = spatial_shape[..., 0] * spatial_shape[..., 1]\n    scale_start_index = scale_start_index.flatten().cumsum(dim=0)\n    scale_start_index = torch.cat(\n        [torch.tensor([0]).to(scale_start_index), scale_start_index[:-1]]\n    )\n    scale_start_index = scale_start_index.reshape(num_cams, -1)\n\n    feature_maps = [\n        col_feats,\n        spatial_shape,\n        scale_start_index,\n    ]\n    return feature_maps\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/ops/deformable_aggregation.py",
    "content": "import torch\nfrom torch.autograd.function import Function, once_differentiable\n\nfrom . import deformable_aggregation_ext\n\n\nclass DeformableAggregationFunction(Function):\n    @staticmethod\n    def forward(\n        ctx,\n        mc_ms_feat,\n        spatial_shape,\n        scale_start_index,\n        sampling_location,\n        weights,\n    ):\n        # output: [bs, num_pts, num_embeds]\n        mc_ms_feat = mc_ms_feat.contiguous().float()\n        spatial_shape = spatial_shape.contiguous().int()\n        scale_start_index = scale_start_index.contiguous().int()\n        sampling_location = sampling_location.contiguous().float()\n        weights = weights.contiguous().float()\n        output = deformable_aggregation_ext.deformable_aggregation_forward(\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n        )\n        ctx.save_for_backward(\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n        )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        (\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n        ) = ctx.saved_tensors\n        mc_ms_feat = mc_ms_feat.contiguous().float()\n        spatial_shape = spatial_shape.contiguous().int()\n        scale_start_index = scale_start_index.contiguous().int()\n        sampling_location = sampling_location.contiguous().float()\n        weights = weights.contiguous().float()\n\n        grad_mc_ms_feat = torch.zeros_like(mc_ms_feat)\n        grad_sampling_location = torch.zeros_like(sampling_location)\n        grad_weights = torch.zeros_like(weights)\n        deformable_aggregation_ext.deformable_aggregation_backward(\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n            grad_output.contiguous(),\n            grad_mc_ms_feat,\n            grad_sampling_location,\n            grad_weights,\n        )\n        return (\n            grad_mc_ms_feat,\n            None,\n            None,\n            grad_sampling_location,\n            grad_weights,\n        )\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/ops/setup.py",
    "content": "import os\n\nimport torch\nfrom setuptools import setup\nfrom torch.utils.cpp_extension import (\n    BuildExtension,\n    CppExtension,\n    CUDAExtension,\n)\n\n\ndef make_cuda_ext(\n    name,\n    module,\n    sources,\n    sources_cuda=[],\n    extra_args=[],\n    extra_include_path=[],\n):\n\n    define_macros = []\n    extra_compile_args = {\"cxx\": [] + extra_args}\n\n    if torch.cuda.is_available() or os.getenv(\"FORCE_CUDA\", \"0\") == \"1\":\n        define_macros += [(\"WITH_CUDA\", None)]\n        extension = CUDAExtension\n        extra_compile_args[\"nvcc\"] = extra_args + [\n            \"-D__CUDA_NO_HALF_OPERATORS__\",\n            \"-D__CUDA_NO_HALF_CONVERSIONS__\",\n            \"-D__CUDA_NO_HALF2_OPERATORS__\",\n        ]\n        sources += sources_cuda\n    else:\n        print(\"Compiling {} without CUDA\".format(name))\n        extension = CppExtension\n\n    return extension(\n        name=\"{}.{}\".format(module, name),\n        sources=[os.path.join(*module.split(\".\"), p) for p in sources],\n        include_dirs=extra_include_path,\n        define_macros=define_macros,\n        extra_compile_args=extra_compile_args,\n    )\n\n\nif __name__ == \"__main__\":\n    setup(\n        name=\"deformable_aggregation_ext\",\n        ext_modules=[\n            make_cuda_ext(\n                \"deformable_aggregation_ext\",\n                module=\".\",\n                sources=[\n                    f\"src/deformable_aggregation.cpp\",\n                    f\"src/deformable_aggregation_cuda.cu\",\n                ],\n            ),\n        ],\n        cmdclass={\"build_ext\": BuildExtension},\n    )\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/ops/src/deformable_aggregation.cpp",
    "content": "#include <torch/extension.h>\n#include <c10/cuda/CUDAGuard.h>\n\nvoid deformable_aggregation(\n  float* output,\n  const float* mc_ms_feat,\n  const int* spatial_shape,\n  const int* scale_start_index,\n  const float* sample_location,\n  const float* weights,\n  int batch_size,\n  int num_cams,\n  int num_feat,\n  int num_embeds,\n  int num_scale,\n  int num_anchors,\n  int num_pts,\n  int num_groups\n);\n  \n\n/* feat: bs, num_feat, c */\n/* _spatial_shape: cam, scale, 2 */\n/* _scale_start_index: cam, scale */\n/* _sampling_location: bs, anchor, pts, cam, 2 */\n/* _weights: bs, anchor, pts, cam, scale, group */\n/* output: bs, anchor, c */\n/* kernel: bs, anchor, pts, c */\n\n\nat::Tensor deformable_aggregation_forward(\n  const at::Tensor &_mc_ms_feat,\n  const at::Tensor &_spatial_shape,\n  const at::Tensor &_scale_start_index,\n  const at::Tensor &_sampling_location,\n  const at::Tensor &_weights\n) {\n  at::DeviceGuard guard(_mc_ms_feat.device());\n  const at::cuda::OptionalCUDAGuard device_guard(device_of(_mc_ms_feat));\n  int batch_size = _mc_ms_feat.size(0);\n  int num_feat = _mc_ms_feat.size(1);\n  int num_embeds = _mc_ms_feat.size(2);\n  int num_cams = _spatial_shape.size(0);\n  int num_scale = _spatial_shape.size(1);\n  int num_anchors = _sampling_location.size(1);\n  int num_pts = _sampling_location.size(2);\n  int num_groups = _weights.size(5);\n\n  const float* mc_ms_feat = _mc_ms_feat.data_ptr<float>();\n  const int* spatial_shape = _spatial_shape.data_ptr<int>();\n  const int* scale_start_index = _scale_start_index.data_ptr<int>();\n  const float* sampling_location = _sampling_location.data_ptr<float>();\n  const float* weights = _weights.data_ptr<float>();\n\n  auto output = at::zeros({batch_size, num_anchors, num_embeds}, _mc_ms_feat.options());\n  deformable_aggregation(\n    output.data_ptr<float>(),\n    mc_ms_feat, spatial_shape, scale_start_index, sampling_location, weights,\n    batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n  );\n  return output;\n}\n\n\nvoid deformable_aggregation_grad(\n  const float* mc_ms_feat,\n  const int* spatial_shape,\n  const int* scale_start_index,\n  const float* sample_location,\n  const float* weights,\n  const float* grad_output,\n  float* grad_mc_ms_feat,\n  float* grad_sampling_location,\n  float* grad_weights,\n  int batch_size,\n  int num_cams,\n  int num_feat,\n  int num_embeds,\n  int num_scale,\n  int num_anchors,\n  int num_pts,\n  int num_groups\n);\n\n\nvoid deformable_aggregation_backward(\n  const at::Tensor &_mc_ms_feat,\n  const at::Tensor &_spatial_shape,\n  const at::Tensor &_scale_start_index,\n  const at::Tensor &_sampling_location,\n  const at::Tensor &_weights,\n  const at::Tensor &_grad_output,\n  at::Tensor &_grad_mc_ms_feat,\n  at::Tensor &_grad_sampling_location,\n  at::Tensor &_grad_weights\n) {\n  at::DeviceGuard guard(_mc_ms_feat.device());\n  const at::cuda::OptionalCUDAGuard device_guard(device_of(_mc_ms_feat));\n  int batch_size = _mc_ms_feat.size(0);\n  int num_feat = _mc_ms_feat.size(1);\n  int num_embeds = _mc_ms_feat.size(2);\n  int num_cams = _spatial_shape.size(0);\n  int num_scale = _spatial_shape.size(1);\n  int num_anchors = _sampling_location.size(1);\n  int num_pts = _sampling_location.size(2);\n  int num_groups = _weights.size(5);\n\n  const float* mc_ms_feat = _mc_ms_feat.data_ptr<float>();\n  const int* spatial_shape = _spatial_shape.data_ptr<int>();\n  const int* scale_start_index = _scale_start_index.data_ptr<int>();\n  const float* sampling_location = _sampling_location.data_ptr<float>();\n  const float* weights = _weights.data_ptr<float>();\n  const float* grad_output = _grad_output.data_ptr<float>();\n\n  float* grad_mc_ms_feat = _grad_mc_ms_feat.data_ptr<float>();\n  float* grad_sampling_location = _grad_sampling_location.data_ptr<float>();\n  float* grad_weights = _grad_weights.data_ptr<float>();\n\n  deformable_aggregation_grad(\n    mc_ms_feat, spatial_shape, scale_start_index, sampling_location, weights,\n    grad_output, grad_mc_ms_feat, grad_sampling_location, grad_weights,\n    batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n  );\n}\n\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\n    \"deformable_aggregation_forward\",\n    &deformable_aggregation_forward,\n    \"deformable_aggregation_forward\"\n  );\n  m.def(\n    \"deformable_aggregation_backward\",\n    &deformable_aggregation_backward,\n    \"deformable_aggregation_backward\"\n  );\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/mmdet3d_plugin/ops/src/deformable_aggregation_cuda.cu",
    "content": "\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n\n#include <THC/THCAtomics.cuh>\n\n#include <iostream>\n#include <stdlib.h>\n\n\n__device__ float bilinear_sampling(\n    const float *&bottom_data, const int &height, const int &width,\n    const int &num_embeds, const float &h_im, const float &w_im,\n    const int &base_ptr\n) {\n  const int h_low = floorf(h_im);\n  const int w_low = floorf(w_im);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const float lh = h_im - h_low;\n  const float lw = w_im - w_low;\n  const float hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = num_embeds;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n\n  float v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n  }\n  float v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n  }\n  float v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n  }\n  float v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n  }\n\n  const float w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  const float val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\n\n__device__ void bilinear_sampling_grad(\n    const float *&bottom_data, const float &weight,\n    const int &height, const int &width,\n    const int &num_embeds, const float &h_im, const float &w_im,\n    const int &base_ptr,\n    const float &grad_output,\n    float *&grad_mc_ms_feat, float *grad_sampling_location, float *grad_weights) {\n  const int h_low = floorf(h_im);\n  const int w_low = floorf(w_im);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const float lh = h_im - h_low;\n  const float lw = w_im - w_low;\n  const float hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = num_embeds;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n\n  const float w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n  const float top_grad_mc_ms_feat = grad_output * weight;\n  float grad_h_weight = 0, grad_w_weight = 0;\n\n  float v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n    grad_h_weight -= hw * v1;\n    grad_w_weight -= hh * v1;\n    atomicAdd(grad_mc_ms_feat + ptr1, w1 * top_grad_mc_ms_feat);\n  }\n  float v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n    grad_h_weight -= lw * v2;\n    grad_w_weight += hh * v2;\n    atomicAdd(grad_mc_ms_feat + ptr2, w2 * top_grad_mc_ms_feat);\n  }\n  float v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n    grad_h_weight += hw * v3;\n    grad_w_weight -= lh * v3;\n    atomicAdd(grad_mc_ms_feat + ptr3, w3 * top_grad_mc_ms_feat);\n  }\n  float v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n    grad_h_weight += lw * v4;\n    grad_w_weight += lh * v4;\n    atomicAdd(grad_mc_ms_feat + ptr4, w4 * top_grad_mc_ms_feat);\n  }\n\n  const float val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  atomicAdd(grad_weights, grad_output * val);\n  atomicAdd(grad_sampling_location, width * grad_w_weight * top_grad_mc_ms_feat);\n  atomicAdd(grad_sampling_location + 1, height * grad_h_weight * top_grad_mc_ms_feat);\n}\n\n\n__global__ void deformable_aggregation_kernel(\n    const int num_kernels,\n    float* output,\n    const float* mc_ms_feat,\n    const int* spatial_shape,\n    const int* scale_start_index,\n    const float* sample_location,\n    const float* weights,\n    int batch_size,\n    int num_cams,\n    int num_feat,\n    int num_embeds,\n    int num_scale,\n    int num_anchors,\n    int num_pts,\n    int num_groups\n) {\n    int idx = blockIdx.x * blockDim.x + threadIdx.x;\n    if (idx >= num_kernels) return;\n\n    const float weight = *(weights + idx / (num_embeds / num_groups));\n    const int channel_index = idx % num_embeds;\n    idx /= num_embeds;\n    const int scale_index = idx % num_scale;\n    idx /= num_scale;\n\n    const int cam_index = idx % num_cams;\n    idx /= num_cams;\n    const int pts_index = idx % num_pts;\n    idx /= num_pts;\n\n    int anchor_index = idx % num_anchors;\n    idx /= num_anchors;\n    const int batch_index = idx % batch_size;\n    idx /= batch_size;\n\n    anchor_index = batch_index * num_anchors + anchor_index;\n    const int loc_offset = ((anchor_index * num_pts + pts_index) * num_cams + cam_index) << 1;\n\n    const float loc_w = sample_location[loc_offset];\n    if (loc_w <= 0 || loc_w >= 1) return;\n    const float loc_h = sample_location[loc_offset + 1];\n    if (loc_h <= 0 || loc_h >= 1) return;\n    \n    int cam_scale_index = cam_index * num_scale + scale_index;\n    const int value_offset = (batch_index * num_feat + scale_start_index[cam_scale_index]) * num_embeds + channel_index;\n\n    cam_scale_index = cam_scale_index << 1;\n    const int h = spatial_shape[cam_scale_index];\n    const int w = spatial_shape[cam_scale_index + 1];\n\n    const float h_im = loc_h * h - 0.5;\n    const float w_im = loc_w * w - 0.5;\n\n    atomicAdd(\n        output + anchor_index * num_embeds + channel_index,\n        bilinear_sampling(mc_ms_feat, h, w, num_embeds, h_im, w_im, value_offset) * weight\n    );\n}\n\n\n__global__ void deformable_aggregation_grad_kernel(\n    const int num_kernels,\n    const float* mc_ms_feat,\n    const int* spatial_shape,\n    const int* scale_start_index,\n    const float* sample_location,\n    const float* weights,\n    const float* grad_output,\n    float* grad_mc_ms_feat,\n    float* grad_sampling_location,\n    float* grad_weights,\n    int batch_size,\n    int num_cams,\n    int num_feat,\n    int num_embeds,\n    int num_scale,\n    int num_anchors,\n    int num_pts,\n    int num_groups\n) {\n    int idx = blockIdx.x * blockDim.x + threadIdx.x;\n    if (idx >= num_kernels) return;\n\n    const int weights_ptr = idx / (num_embeds / num_groups);\n    const int channel_index = idx % num_embeds;\n    idx /= num_embeds;\n    const int scale_index = idx % num_scale;\n    idx /= num_scale;\n\n    const int cam_index = idx % num_cams;\n    idx /= num_cams;\n    const int pts_index = idx % num_pts;\n    idx /= num_pts;\n\n    int anchor_index = idx % num_anchors;\n    idx /= num_anchors;\n    const int batch_index = idx % batch_size;\n    idx /= batch_size;\n\n    anchor_index = batch_index * num_anchors + anchor_index;\n    const int loc_offset = ((anchor_index * num_pts + pts_index) * num_cams + cam_index) << 1;\n\n    const float loc_w = sample_location[loc_offset];\n    if (loc_w <= 0 || loc_w >= 1) return;\n    const float loc_h = sample_location[loc_offset + 1];\n    if (loc_h <= 0 || loc_h >= 1) return;\n    \n    const float grad = grad_output[anchor_index*num_embeds + channel_index];\n\n    int cam_scale_index = cam_index * num_scale + scale_index;\n    const int value_offset = (batch_index * num_feat + scale_start_index[cam_scale_index]) * num_embeds + channel_index;\n\n    cam_scale_index = cam_scale_index << 1;\n    const int h = spatial_shape[cam_scale_index];\n    const int w = spatial_shape[cam_scale_index + 1];\n\n    const float h_im = loc_h * h - 0.5;\n    const float w_im = loc_w * w - 0.5;\n\n    /* atomicAdd( */\n    /*     output + anchor_index * num_embeds + channel_index, */\n    /*     bilinear_sampling(mc_ms_feat, h, w, num_embeds, h_im, w_im, value_offset) * weight */\n    /* ); */\n    const float weight = weights[weights_ptr];\n    float *grad_weights_ptr = grad_weights + weights_ptr;\n    float *grad_location_ptr = grad_sampling_location + loc_offset;\n    bilinear_sampling_grad(\n        mc_ms_feat, weight, h, w, num_embeds, h_im, w_im,\n        value_offset,\n        grad,\n        grad_mc_ms_feat, grad_location_ptr, grad_weights_ptr\n    );\n}\n\n\nvoid deformable_aggregation(\n    float* output,\n    const float* mc_ms_feat,\n    const int* spatial_shape,\n    const int* scale_start_index,\n    const float* sample_location,\n    const float* weights,\n    int batch_size,\n    int num_cams,\n    int num_feat,\n    int num_embeds,\n    int num_scale,\n    int num_anchors,\n    int num_pts,\n    int num_groups\n) {\n    const int num_kernels = batch_size * num_pts * num_embeds * num_anchors * num_cams * num_scale;\n    deformable_aggregation_kernel\n        <<<(int)ceil(((double)num_kernels/128)), 128>>>(\n        num_kernels, output,\n        mc_ms_feat, spatial_shape, scale_start_index, sample_location, weights,\n        batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n    );\n}\n\n\nvoid deformable_aggregation_grad(\n  const float* mc_ms_feat,\n  const int* spatial_shape,\n  const int* scale_start_index,\n  const float* sample_location,\n  const float* weights,\n  const float* grad_output,\n  float* grad_mc_ms_feat,\n  float* grad_sampling_location,\n  float* grad_weights,\n  int batch_size,\n  int num_cams,\n  int num_feat,\n  int num_embeds,\n  int num_scale,\n  int num_anchors,\n  int num_pts,\n  int num_groups\n) {\n    const int num_kernels = batch_size * num_pts * num_embeds * num_anchors * num_cams * num_scale;\n    deformable_aggregation_grad_kernel\n        <<<(int)ceil(((double)num_kernels/128)), 128>>>(\n        num_kernels,\n        mc_ms_feat, spatial_shape, scale_start_index, sample_location, weights,\n        grad_output, grad_mc_ms_feat, grad_sampling_location, grad_weights,\n        batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n    );\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/requirement.txt",
    "content": "numpy==1.23.5\nmmdet==2.28.2\nurllib3==1.26.16\npyquaternion==0.9.9\nnuscenes-devkit==1.1.10\nyapf==0.33.0\ntensorboard==2.14.0\nmotmetrics==1.1.3\npandas==1.1.5\nopencv-python==4.8.1.78\nprettytable==3.7.0\nscikit-learn==1.3.0\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/.pylintrc",
    "content": "[MESSAGES CONTROL]\nmax-line-length=120\ndisable=no-self-use,anomalous-backslash-in-string,too-many-arguments,too-few-public-methods,too-many-instance-attributes,redefined-variable-type,unused-argument,bad-continuation,too-many-lines,too-many-branches,locally-disabled,too-many-locals,too-many-statements,duplicate-code,too-many-nested-blocks,fixme,useless-object-inheritance,no-else-raise,no-else-break,unnecessary-pass,no-else-return,super-with-arguments,no-else-continue,bad-option-value,consider-using-dict-items,consider-using-f-string\nignored-modules=carla,carla.command,agents.navigation.basic_agent,agents.navigation.roaming_agent,agents.tools.misc,agents.navigation.local_planner,agents.navigation.global_route_planner,agents.navigation.global_route_planner_dao,shutil,carla_msgs,nav_msgs,sensor_msgs,std_msgs,tf,cv_bridge,geometry_msgs,rosgraph_msgs,rospy\nvariable-rgx=[a-z0-9_]{1,40}$\nfunction-rgx=[a-z0-9_]{1,40}$\nextension-pkg-whitelist=cv2,pygame,numpy\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/.readthedocs.yml",
    "content": "# Read the Docs configuration file\n# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details\n\nversion: 2\n\nmkdocs:\n  configuration: mkdocs.yml\n\nformats: all\n\npython:\n  version: 3.7\n  install:\n  - requirements: Docs/requirements.txt\n\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/CARLA_VER",
    "content": "HOST = https://carla-releases.s3.eu-west-3.amazonaws.com/Linux\nRELEASE=CARLA_0.9.13\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Dockerfile",
    "content": "from ubuntu:18.04\n\n# Install base libs\nrun apt-get update && apt-get install --no-install-recommends -y libpng16-16=1.6.34-1ubuntu0.18.04.2 \\\nlibtiff5=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 \\\n python3.6 python3.6-dev python3-pip libxerces-c-dev \\\n && rm -rf /var/lib/apt/lists/* \n\n# Install python requirements\nrun 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 \\\n    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\\\n&& mkdir -p /app/scenario_runner \n\n# Install scenario_runner \ncopy . /app/scenario_runner\n\n# setup environment :\n# \n#   CARLA_HOST :    uri for carla package without trailing slash. \n#                   For example, \"https://carla-releases.s3.eu-west-3.amazonaws.com/Linux\".\n#                   If this environment is not passed to docker build, the value\n#                   is taken from CARLA_VER file inside the repository.\n#\n#   CARLA_RELEASE : Name of the package to be used. For example, \"CARLA_0.9.9\".\n#                   If this environment is not passed to docker build, the value\n#                   is taken from CARLA_VER file inside the repository.\n# \n#\n#  It's expected that $(CARLA_HOST)/$(CARLA_RELEASE).tar.gz is a downloadable resource.\n#\n\nenv CARLA_HOST \"\"\nenv CARLA_RELEASE \"\"\n\n# Extract and install python API and resources from CARLA\nrun export DEFAULT_CARLA_HOST=\"$(sed -e 's/^\\s*HOST\\s*=\\s*//;t;d' /app/scenario_runner/CARLA_VER)\" && \\\n    echo \"$DEFAULT_CARLA_HOST\" && \\\n    export CARLA_HOST=\"${CARLA_HOST:-$DEFAULT_CARLA_HOST}\" && \\\n    export DEFAULT_CARLA_RELEASE=\"$(sed -e 's/^\\s*RELEASE\\s*=\\s*//;t;d' /app/scenario_runner/CARLA_VER)\" && \\\n    export CARLA_RELEASE=\"${CARLA_RELEASE:-$DEFAULT_CARLA_RELEASE}\" && \\\n    echo \"$CARLA_HOST/$CARLA_RELEASE.tar.gz\" && \\\n    wget -qO- \"$CARLA_HOST/$CARLA_RELEASE.tar.gz\" | tar -xzv PythonAPI/carla -C / && \\\n    mv /PythonAPI/carla /app/ && \\\n    python3 -m easy_install --no-find-links --no-deps \"$(find /app/carla/ -iname '*py3.*.egg' )\"\n\n\n# Setup working environment\nworkdir /app/scenario_runner\nenv PYTHONPATH \"${PYTHONPATH}:/app/carla/agents:/app/carla\"\nentrypoint [\"/bin/sh\" ]\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/CHANGELOG.md",
    "content": "## Table of Contents\n* [Latest Changes](#latest-changes)\n* [CARLA ScenarioRunner 0.9.13](#carla-scenariorunner-0913)\n* [CARLA ScenarioRunner 0.9.12](#carla-scenariorunner-0912)\n* [CARLA ScenarioRunner 0.9.11](#carla-scenariorunner-0911)\n* [CARLA ScenarioRunner 0.9.10](#carla-scenariorunner-0910)\n* [CARLA ScenarioRunner 0.9.9](#carla-scenariorunner-099)\n* [CARLA ScenarioRunner 0.9.8](#carla-scenariorunner-098)\n* [CARLA ScenarioRunner 0.9.7](#carla-scenariorunner-097)\n* [CARLA ScenarioRunner 0.9.6](#carla-scenariorunner-096)\n* [CARLA ScenarioRunner 0.9.5.1](#carla-scenariorunner-0951)\n* [CARLA ScenarioRunner 0.9.5](#carla-scenariorunner-095)\n* [CARLA ScenarioRunner 0.9.2](#carla-scenariorunner-092)\n\n## Latest changes\n### :rocket: New Features\n\n* New scenarios:\n    - InvadingTurn: vehicles at the opposite direction lane partially invade the ego's one, forcing it to leave space for them,moving slightly off-center.\n    - EnterActorFlow: the ego has to enter a highway lane filled with incoming traffic\n    - MergerIntoslowtraffic. variation of `EnterActorFlow` but with slow traffic.\n    - InterurbanActorFlow and InterurbanAdvancedActorFlow: actor flow scenarios for the new interurban intersections with dedicated lanes present at Town12 and Town13.\n    - Accident: the ego is met with an accident, forcing it to lane change to avoid it.\n    - AccidentTwoWays:  same as `Accident` but having to invade an opposite direction lane.\n    - ParkedObstacle: similar to `Accident` but with a parked obstacle instead.\n    - ParkedObstacleTwoWays:  same as `ParkedObstacle` but having to invade an opposite direction lane.\n    - HazardAtSideLane: similar to `Accident` but with a moving group of bicycles in the rightmost park of the lane\n    - HazardAtSideLaneTwoWays:  same as `HazardAtSideLane` but having to invade an opposite direction lane.\n    - ConstructionObstacleTwoWays: same as `ConstructionObstacle` but having to invade an opposite direction lane.\n    - VehicleOpensDoorTwoWays: similar to `Accident` but this time the blockage is cause by a vehicle opening its door.\n    - StaticCutIn: the ego is meant with an adversary that exits a stopped lane, cutting in front of the ego.\n    - ParkingCutIn: similar to `StaticCutIn` but the adversary starts at a parking lane.\n    - HighwayCutIn: the ego is met with a vehicle that tries to enter the highway by cutting in front of it.\n    - ParkingExit: Only usable at the beginning of the routes, makes the ego start at a parking lane.\n    - HardBreakRoute: uses the BackgroundActivity to make all vehicles in front of the ego hard break.\n    - YieldToEmergencyVehicle: the ego finds an emergency vehicle behind, having to lane chane to give way.\n    - VehicleTurningRoutePedestrian: variation of `VehicleTurningRoute` but with a pedestrian crossing instead of a bycicle.\n    - BlockedIntersection: with low visibility, the ego performs a turn only to find out that the end is blocked by another vehicle.\n    - CrossingBicycleFlow: the ego has to do a turn at an intersection but it has to cross a bycicle lane full of traffic.\n    - PedestrianCrossing: a group of pedestrians crossing a crosswalk. Easier version of `DynamicObjectCrossing` with no occluder.\n    - ParkingCrossingPedestrian: variation of `DynamicObjectCrossing`, but using a parked vehicle as the occluder.\n    - OppositeVehicleTakingPriority: variation of `OppositeVehicleRunningRedLight` but without traffic lights.\n    - NonSignalizedJunctionLeftTurn: variation of `SignalizedJunctionLeftTurn` but without traffic lights.\n    - NonSignalizedJunctionRightTurn: variation of `SignalizedJunctionRightTurn` but without traffic lights.\n    - PriorityAtJunction: utility scenario during routes to add a green traffic light at the next intersection.\n    - NoSignalJunctionCrossingRoute: Does nothing but wait for the ego to exit an intersection.\n* Improvements to old scenarios:\n    - ControlLoss: Added actual noise to the ego's control (currently only during routes).\n    - All VehicleTurning variations: more robustness and better synchronization.\n    - OppositeVehicleRunningRedLight: Improvement synchronization and the opposite vehicle's behavior.\n    - SignalizedJunctionLeftTurn: it is now an actor flow that ego has to cross.\n    - SignalizedJunctionRightTurn. it is now an actor flow that the ego has to merge into.\n    - Renamed `ConstructionSetupCrossing` to `ConstructionObstacle`, and prepared it for routes.\n* Improvements to the CarlaDataProvider:\n    - Added a lock when checking the dictionaries to avoid issues in multithreading\n    - Added the `transform` argument to all register function to avoid returning None during the first frame\n    - Added the `get_global_route_planner` and `get_all_actors` to avoid repeating these costly calls more than necessary\n    - Added `set_runtime_init_mode` and `is_runtime_init_mode`, used by the Leaderboard to initialize scenarios during the simulation\n    - At the `create_blueprint` function, replaced the `safe` argument with the `attribute_filter`, for a more generic parsing of any of the blueprint attributes.\n    - Removed the `CarlaDataProvider.get_ego_vehicle_route()` and `CarlaDataProvider.set_ego_vehicle_route()` functions as this is now information available to all scenarios.\n* Improvements to the routes:\n    - Scenarios are no longer position based, but instead part of a route's xml.\n    - Routes now also include the criteria of its scenarios.\n    - `waypoint` have been renamed to `position` and are part of the `waypoints` category.\n    - More than one `weather` are allowed, creating a dynamic one based on the ego vehicle's completed percentage of the route.\n    - Changed the timeout to also be dependent on the distance driven by the ego vehicle.\n    - Added the `RouteLightsBehavior` to control of all scene and vehicle lights during runtime\n    - Added a new criteria for routes, `CheckMinSpeed`, that checks the ego's speed and compares it with the rest of the traffic\n    - Separated the route argument into two, `route` for the file path, and `route-id`, for the name of route. the functionality remains unchanged.\n    - Simplified the overall parsing.\n* The BackgroundActivity part of the routes has been completely remade, with the objective of creating the sensation of traffic around the ego will increasing the performance\n* Added a Backgroundmanager to interact with the new BackgroundActivity, to allow it to adapt to incoming scenarios\n* Added new atomic behaviors:\n    - SyncArrivalWithAgent\n    - CutIn\n    - AddNoiseToRouteEgo\n    - ConstantVelocityAgentBehavior\n    - AdaptiveConstantVelocityAgentBehavior\n    - WaitForever\n    - BatchActorTransformSetter\n    - OppositeActorFlow\n    - InvadingActorFlow\n    - BicycleFlow\n    - OpenVehicleDoor\n    - SwitchWrongDirectionTest\n    - SwitchMinSpeedCriteria\n    - WalkerFlow\n    - AIWalkerBehavior\n    - ScenarioTimeout\n    - MovePedestrianWithEgo\n* Improved the Criterion class for a more comprehensive base criteria and easier use in the `results_writer` class.\n* Added new atomic criteria:\n    - MinimumSpeedRouteTest\n    - YieldToEmergencyVehicleTest\n    - ScenarioTimeoutTest\n* Added new atomic trigger conditions\n    - WaitUntilInFrontPosition\n* Merged the `Scenario` class into the `BasicScenario` one.\n* Scenarios can now have parameters as part of the their xml definition, which is saved as a dictionary at `config.other_parameters`\n* Simplified and improved how routes are parsed.\n* Added the `wait-for-repetitions` argument at the manual control for a smoother transition between scenarios / repetitions\n* Updated numpy's version to avoid issues with newer version of Python 3\n\n### :bug: Bug Fixes\n* Fixed bug at OtherLeadingVehicle scenario causing the vehicles to move faster than intended\n* Fixed bug causing some debris at ControlLoss scenario to be floating, instead of at ground level\n\n## CARLA ScenarioRunner 0.9.13\n### :rocket: New Features\n* OpenSCENARIO support:\n    - Added support for `ParameterAction`\n    - Extended `ParameterCondition` support to use as an event trigger condition\n\n### :bug: Bug Fixes\n* Fixed metrics parsing and remade the example recordings\n* Fixed a bug with repetitions / scenario groups causing the simulation to crash after the second one.\n* Fixed use of OSC Parameters as entry names for catalogs\n\n### :ghost: Maintenance\n* Removed CARLA example dependencies\n\n## CARLA ScenarioRunner 0.9.12\n### :rocket: New Features\n* OpenSCENARIO support:\n    - Added support for LongitudinalDistanceAction\n    - Extended RelativeDistanceCondition with support for 'longitudinal' and 'lateral' distance along with freespace.\n    - Added support for RelativeRoadPosition\n    - Added support for RoadPosition\n    - Added `--openscenarioparams` argument to overwrite global `ParameterDeclaration`\n    - Added controller using CARLA's autopilot (in replacement for ActivateControllerAction)\n    - Added support for storyboards with multiple stories\n    - Eliminated unnecessary reloads of OpenDRIVE maps\n* Additional Scenarios:\n    - Added Construction setup scenario.\n### :bug: Bug Fixes\n* Fixed LaneOffset (+ vs. -) for OpenSCENARIO\n* Fixed RelativeLanePosition for OpenSCENARIO causing exception when using ds != 0\n* Fixed bug at the Getting Started docs which caused an import error\n* Fixed neverending lane change maneuver in OpenSCENARIO\n* Fixed bug causing the spawning of an actor with `request_new_actor` to never activate the autopilot.\n* Fixed handling of evaluation criteria in OpenSCENARIO (using a delay value of .0 caused an exception)\n### :ghost: Maintenance\n* Extended SimpleVehicleController (OSC) to handle traffic lights\n* Generalized visualizer attached to OSC controllers\n* Fixed bug at the Getting Started docs which caused an import error\n* Improved the watchdog. It can now be paused, resumed and uses the same thread, instead of opening and closing new ones each frame.\n* Added `simple-watchdog-timer` library to the requirements, as it is used by the new watchdog. This requires Python 3.x from now on!\n* Extended CarlaDataProvider's spawning functions to allow filtering the safer blueprint, and optionally tick the server\n* Improved cleanup handling to resolve memory leak issues and resolve timeouts\n\n## CARLA ScenarioRunner 0.9.11\n### :rocket: New Features\n* Added a sensor barrier for the agents to ensure that the simulation waits for them to render their data.\n* Added an option to produce a machine-readable JSON version of the scenario report.\n* Added a static obstacle evasion OpenSCENARIO scenario\n* Added support for OSC Routing options\n* Added support for OSC SynchronizeAction\n* Added support for OSC LaneOffsetAction\n* Added support to place OSC controller implementation alongside the OSC scenario\n* Updated *GameTime.restart()* at *srunner/scenariomanager/timer.py* to also reset the frame number\n### :bug: Bug Fixes\n* Fixed metrics-manager.py failing to run with port argument\n* Fixed exception when using OSC scenarios without EnvironmentAction inside Storyboard-Init\n* Fixed bug causing the TrafficManager to not be correctly updated at asynchronous simualtions\n* Fixed shutdown issue in ScenarioRunner causing to not switch to asynchronous mode\n* Fixed OSC TeleportAction within Story\n* Fixed runtime exception on RouteScenario without an agent parameter \n* Fixed bug causing the InTimeToArrivalToVehicle atomic to crash if one of the actors was a a static object\n* Fixed writing result files when using OpenSCENARIO under Windows (CARLA: prefix is removed from the filename)\n### :ghost: Maintenance\n* Added check to ensure OSC names (for story/act/maneuver) are unique\n\n\n## CARLA ScenarioRunner 0.9.10\n### :rocket: New Features\n* Renamed some agent labels inside Jenkins CI pipelines for new standard proposals.\n* Added support for Jenkins CI pipelines doing automated testing and docker images creation.\n* **Very important:** CarlaActorPool has been removed and all its functions moved to the CarlaDataProvider:\n    - 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.\n    - Changed *ActorConfiguration* to *ActorConfigurationData.parse_from_node*\n    - Renamed the _map_ element at routes to _town_, matching the scenario configuration files\n\n* Added new environment variables needed. They can be seen at (Docs/getting_scenariorunner.md).\n* Improved the visual display of the information from the *output* and *file* arguments.\n* Routes are now deterministic in regards to the spawning scenarios when more than one are at the same location\n* 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.\n* 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.\n* The new weather parameters (related to fog) are now correctly read when running scenarios outside routes.\n* Enable weather animation during scenario execution (requires ephem pip package)\n* Changed manual control to be in par with the CARLA version. Among others, added vehicle lights, recording and some new sensors\n* Removed unsupported scenarios (ChallengeBasic and BackgroundActivity, VehicleTurnLeftAtJunction)\n* 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)\n* Removed the default randomness at the ControlLoss scenario\n* OpenSCENARIO support:\n    - 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:\n        - Pedestrian controller\n        - NPC vehicle controller (based on CARLA LocalPlanner)\n        - Simple vehicle controller to set velocities not brake/throttle, and consider obstacles in the forward-facing region.\n        - External controller (to forward control to external entities)\n    - Added initial speed support for pedestrians for OpenSCENARIO\n    - Support for EnvironmentActions within Story (before only within Init). This allows changing weather conditions during scenario execution\n    - Added support for RelativeSpeedCondition\n    - Added support for AccelerationCondition\n    - Added support for TimeOfDayCondition\n    - Added support for OffroadCondition\n    - Added support for CollisionCondition\n    - Added support for EndOfRoadCondition\n    - Added support for TimeHeadwayCondition\n    - Added support for TrafficSignalCondition\n    - Added support for AcquirePositionAction\n    - Extended FollowLeadingVehicle example to illustrate weather changes\n    - Created example scenarios to illustrate usage of controllers and weather changes\n    - Extended LaneChangeAction to allow lane changes of multiple lanes\n    - Reworked the handling of Catalogs to make it compliant to the 1.0 version (relative paths have to be relative to the scenario file)\n    - The RoadNetwork can be defined as global Parameter\n    - Fixed handling of relative positions with negative offset\n    - Added support for local ParamaterDeclarations\n    - Added support for Parameters within Catalogs\n    - Added support for ParameterAssignments for CatalogReferences\n    - Fixed name handling of Parameters: Parameter declerations must not start with a leading '$', but when the parameter is used a leading '$' is required.\n    - Fixed use of Parameters for multiple instances of the same Catalog element\n    - Fixed use of relative initial positions for any actor\n    - Added possibility to use synchronous execution mode with OpenSCENARIO\n    - Fixed use of relative paths in CustomCommandAction\n    - Fixed use of ControllerCatalogs\n* Atomics:\n    - Several new atomics to enable usage of OSC controllers\n    - WeatherBehavior to simulate weather over time\n    - UpdateWeather to update weather to a new setting, e.g. sun to rain\n    - UpdateRoadFriction to update the road friction while running\n    - new RelativeVelocityToOtherActor trigger condition, used to compare velocities of two actors\n    - new TriggerAcceleration trigger condition which compares a reference acceleration with the actor's one.\n    - new TimeOfDayComparison trigger condition, comparing the simulation time (set up by the new weather system) with a given *datetime*.\n    - Added new *OffRoadTest* criteria.\n    - Added new *EndofRoadTest* criteria, to detect when a vehicle changes between OpenDRIVE roads.\n    - CollisionTest criterion can now filter the collisions for a specific actor, or actor type_id.\n    - 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.\n    - InTimeToArrivalToVehicle has had its two actor arguments swapped, to match all the other behaviors.\n    - Added *along_route* flag to InTimeToArrivalToVehicle, to take into account the topology of the road\n    - Changed the inputs to TrafficLightStateSetter to match the other atomics, but the functionality remains unchanged\n    - Improved LaneChange atomic to allow lane changes of multiple lanes\n\n### :bug: Bug Fixes\n* Fixed bug causing parsing RelativeTargetSpeed tag to fail. \n* Fixed missing 'six' in requirements.txt\n* Support OpenSCENARIO parameters also if they're only part of a string value\n* Support Routes in Catalogs\n* Fix parsing of properties within ControllerCatalogs\n* Add cleanup of instantiated OpenSCENARIO controllers\n* Do not register SIGHUP signal in windows\n* Fixed initial speed of vehicles using OpenSCENARIO\n* Fixed bug causing an exception when calling BasicScenario's *_initialize_actors* with no other_actors.\n* Fixed bug causing the route to be downsampled (introduced by mistake at 0.9.9)\n* Fixed bug causing _output_ argument to not display the correct number with _InRouteTest_ and _RouteCompletionTest_ criterias (the succces and failure was correctly displayed)\n* Fixed bug causing OpenSCENARIO's SpeedCondition to not work as intended\n* Fixed bug causing CollisionConditions not to work properly in OpenSCENARIO\n* Fixed bug causing the *group:* functionality to behave incorrectly when moving scenarios around.\n* Fixed bug causing FollowLeadingVehicle and FollowLeadingVehicleWithObstacle scenarios to not properly end\n* Fixed bug causing CollisionTest to ignore multiple collisions with scene objects\n* Fixed bug causing NoSignalJunctionCrossing to not output the results of the scenario\n* Fixed bug causing SyncArrival to fail when the actor was destroyed after the behavior ended\n* Fixed bug with ending roads near stop signals to break the simulation\n* Fixed exception bug in spawn function of CarlaDataProvider\n* Fixed access to private member of CARLA LocalPlanner inside OSC NpcVehicleControl\n* Fixed bug causing LaneChange to break the simulation if the asked lane change was impossible, instead of correctly stopping it\n* Fixed bug causing ChangeLane scenarios to never end\n* Fixed handling of OSC LanePosition (#625)\n* Fixed bug causing the route repetitions to spawn different background activity\n* Fixed bug causing the rotate_point function inside RunningRedLightTest to not function properly.\n### :ghost: Maintenance\n* Exposed traffic manager port flag to enable the execution of multiple scenarios on a single machine.\n\n## CARLA ScenarioRunner 0.9.9\n### :rocket: New Features\n* OpenSCENARIO support:\n    - Support for OpenSCENARIO 1.0 (a converter for old scenarios is available)\n    - Added support for position with Lane information (roadId and laneId)\n    - Added support to use a non-CARLA OpenDRIVE map (instead of CARLA towns)\n    - Added support for TimeOfDay tag\n    - Added support for scenarios with no actors\n    - Added support for TimeToCollisionCondition with freespace.\n    - Added support for TimeHeadwayCondition with freespace.\n* Scenario updates:\n    - 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.\n* Atomics:\n    - ChangeAutopilot now calls a TM instance, and allows to change its parameters\n    - Added WaitUntilInFront behavior and InTimeToArrivalToVehicleSideLane trigger condition, useful for cut ins\n    - Added new trigger condition, AtRightestLane, which checks if the actor is at the rightmost driving lane\n    - Added new criteria, ActorSpeedAboveThresholdTest, useful to check if the ego vehicle has been standing still for long periods of time.\n* Setting up actors in batch now also randomizes their colors\n* 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.\n* **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:\n    - The path to the autoagents has changed from .../challenge/autoagents to .../autoagents\n    - The path to the route and scenario descriptions has changed from .../challenge to .../data\n### :bug: Bug Fixes\n* Fixed spawning bugs for scenario DynamicObjectCrossing when it is part of a route\n* Fixed spawning bugs for scenarios VehicleTurningRight, VehicleTurningLeft when they are part of a route\n* Fixed bug causing the GPS coordinates given to the agents to be wrongly calculated\n* Fixed bug when setting up actors in batch causing to ignore the spawn points given.\n* Fixed bug where CollisionTest was counting as multiple hits collisions that displaced the actor for a long distance.\n* Fixed bug causing the simulation to end after running in synchronous mode\n* Fixed bug when using the WaypointFollower atomic to create new LocalPlanners for on-the-fly created actors (#502)\n* Fixed bug causing the scenarios to run faster than real time.\n### :ghost: Maintenance\n* Removed perform_carla_tick() function at CarlaDataProvider, which was a workaround for world.tick()\n\n\n## CARLA ScenarioRunner 0.9.8\n### :rocket: New Features\n* Added \"--timeout\" command line parameter to set a user-defined timeout value\n* Scenario updates:\n    - 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.\n* OpenSCENARIO support:\n    - Added initial support for Catalogs (Vehicle, Pedestrian, Environment, Maneuver, and and MiscObject types only)\n### :bug: Bug Fixes\n* Fixed #471: Handling of weather parameter (cloudyness -> cloudiness adaption)\n* Fixed #472: Spawning issue of pedestrians in OpenSCENARIO\n* Fixed #374: Usage of evaluation critieria with multiple ego vehicles in OpenSCENARIO\n* Fixed #459: Add initial support for Catalogs (Vehicle, Pedestrian, Environment, Maneuver, and and MiscObject types only)\n* Fixed wrong StandStill behavior which return SUCCESS immediatly on a standing actor\n* Fixed scenario bug causing junction related scenarios (4, 7, 8 and 9) to not spawn due to lane changes.\n### :ghost: Maintenance\n* Added watchdog to ScenarioManager to handle timeouts and CARLA crashes\n* Added timeout for CARLA tick() calls to avoid blocking CARLA server calls\n\n\n## CARLA ScenarioRunner 0.9.7\n**This is the _first_ release to work with CARLA 0.9.7 (not the patch versions 0.9.7.x)**\n### :rocket: New Features\n* Challenge routes can be directly executed with the ScenarioRunner using the --route option\n* Agents can be used with the ScenarioRunner (currently only for route-based scenarios)\n* New scenarios:\n    - Added example scenario for lane change\n    - Added cut-in example scenario\n* Scenario updates:\n    - Scenarios 7 to 10 are now visible when running routes (instead of being triggered in the background). Their\n      methodology has remained unchanged\n* Scenario atomics:\n    - Added new OutsideRouteLanesTest atomic criter that encompasses both SidewalkTest and WrongLaneTest, returning\n      the percentage of route that has been traveled outside the lane.\n    - InRouteTest is now more forgiving. The max distance has been increased, but staying above the previous one will eventually \n      also cause failure\n    - Changed SidewalkTest atomic criteria to also track other type of out of lane conditions\n    - SidewalkTest and WrongLaneTest atomic criterias now track the amount of meters traversed\n    - CollisionTest atomic criteria now correctly ignores multiple micro-collisions with the same object\n    - Added LaneChange and TrafficLightSateSetter behavior atomics\n    - Added AccelerateToCatchUp behavior atomic\n    - Added get_transform() method for CarlaDataProvider\n    - Added support for weather conditions\n    - Added basic version check to ensure usage of correct CARLA version\n    - WaypointFollower atomic can handle pedestrians\n    - Extensions in WaypointFollower atomic for consecutive WaypointFollowers (one WF cancels the previous one)\n* Extended OpenScenario support:\n    - Added support for UserDefinedActions (e.g. to run additional scripts)\n    - Added init speed behavior for vehicles\n    - Added support for relative velocities\n    - Extended convert_position_to_transform with RelativeWorld, RelativeObject and RelativeLane osc_positions\n    - Added new trigger atomics InTriggerDistanceToOSCPosition and InTimeToArrivalToOSCPosition to support relative osc_positions\n    - Added new atomic behaviour ActorTransformSetterToOSCPosition\n    - Workaround for relative osc_positions: World is started earlier to support relative osc_positions in story init\n    - Added delay condition support in convert_condition_to_atomic\n    - Added support for pedestrians\n    - Full support for SimulationTime condition\n    - Added weather support\n    - Updated implementation to be closer to upcoming OpenSCENARIO standard\n    - AfterTermination, AtStart conditions are supported\n    - Added initial support for lateral action: LaneChange\n    - Added initial support for OSCGlobalAction to set state of traffic signal\n    - FollowRoute action is supported for vehicles and pedestrians, for global world positions.\n    - Added support for RoadCondition: Friction\n    - Redundant rolename object property is no longer required\n    - Added support for global parameters\n    - 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.\n    - Added support to change actor color\n    - Added support for a default actor model, in case the stated model is not available\n    - Added support for MiscObjects (besides vehicles and pedestrians)\n    - 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\n    - Actor physics can now be set via Object Properties (<Property name=\"physics\" value=\"off\" />)\n### :bug: Bug Fixes\n* Fixed wrong handling of OpenSCENARIO ConditionGroups, which should be handled as parallel composites, not sequences\n* Fixed #443: Repetitions in OpenSCENARIO were not properly working\n* Fixed bug causing RunningStopTest atomic criteria to trigger when lane changing near a STOP signal\n* Fixed bug causing RunningRedLightTest atomic criteria to occasionally not trigger\n* Fixed bug causing occasional frame_errors\n* Fixed #426: Avoid underground vehicles fall forever by disabling physics when spawning underground.\n* Fixed #427: Removed unnecessary warnings when using get_next_traffic_light() with non-cached locations\n* Fixed missing ego_vehicle: compare actor IDs instead of object in CarlaDataProvider in get_velocity, get_transform and get_location\n* Avoided use of 'controller.ai.walker' as walker type in DynamicObjectCrossing scenario\n* Fixed WaypointFollower behavior to use m/s instead of km/h\n* Fixed starting position of VehicleTurnLeft/Right scenarios\n* Fixed spawn_point modification inside CarlaActorPool.setup_actor()\n* Fixed result of DrivenDistanceTest\n* Fixed exception in manual_control on fps visualization\n* Cleanup of pylint errors for all autonomous agents\n* Fixed randomness of route-based scenarios\n* Fixed usage of radians instead of degrees for OpenSCENARIO\n* Fixed ActorTransformSetter behavior to avoid vehicles not reaching the desired transform\n* Fixed spawning of debris for ControlLoss scenario (Scenario01)\n* Fixed CTRL+C termination of ScenarioRunner\n### :ghost: Maintenance\n* Increased speed of actor initialization by using CARLA batch mode and buffering CARLA blueprint library\n* Split of behaviors into behaviors and conditions\n* Moved atomics into new submodule scenarioatomics\n* Updated documentation for all behaviors, conditions and test criteria\n* Refactoring of scenario configurations and parsers\n* Extended WaypointFollower atomic behavior to be able to use the current actor speed\n* Removed usage of 'import *' to have cleaner Python imports\n* Removed broad-except and bare-except where possible\n* Python-Scenarios: Removed obsolete categories\n* ScenarioRunner: Removed scenario dictonary, use imports directly\n* CarlaDataProvider: Simplified update_light_states() to remove code duplication\n* Timer: class TimeOut() is derived from SimulationTimeCondition() to  avoid code duplication\n* Moved backported py_trees classes and methods to tools/py_trees_port.py to avoid code duplication\n* Removed setup_environment.sh\n* Adaptions to CARLA API Changes\n     - Renamed GnssEvent to GnssMeasurement\n\n## CARLA ScenarioRunner 0.9.6\n**This is the _first_ release to work with CARLA 0.9.6**\n### :ghost: Maintenance\n* Adapted to CARLA API changes\n    - Frame rate is set now via Python\n    - Renamed frame_count and frame_number to frame\n    - Removed wait_for_tick() calls\n\n\n## CARLA ScenarioRunner 0.9.5.1\n**This is the _last_ release that works with CARLA 0.9.5**\n### :rocket: New Features\n* Added initial support for OpenScenario v0.9.1\n* Added support for multiple ego vehicles plus an example\n* Added commandline option for output directory\n* Added option to load external scenario implementations (in python)\n* Added option to scenario_runner to load external scenario XMLs\n* Atomic behaviors:\n    - Extended KeepVelocity atomic behavior to support duration/distance\n      based termination\n    - Extended StandStill atomic behavior to support duration based\n      termination\n    - Added behavior to activate/deactivate autopilot\n### :bug: Bug Fixes\n* Fixed WaypointFollower initialization\n\n\n## CARLA ScenarioRunner 0.9.5\n**This is the _first_ release to work with CARLA 0.9.5**\n### :rocket: New Features\n* Added support for CARLA challenge\n    - Added logging functionalities to challenge_evaluator_routes.py\n    - Added wall clock timeout for the CARLA challenge\n    - Added background scenario to generate dynamic traffic using autopilot\n    - Updated compatibility with Python 2.7 for the challenge evaluator\n    - Updated WaypointFollower behavior\n    - Added detect_lane_obstacle() helper function which identifies if an obstacle is present in front of the reference actor\n    - Added test to detect vehicles running a stop\n    - Updated the reference position for a scenario is now called trigger_point\n    - Added universal access to the map without re-calling get_map()\n    - Added criteria_enable flag to enable/disable criteria tree\n    - Added multiple helper methods for generic scenario execution.\n    - Added pseudo-sensors for SceneLayoutMeasurements and ObjectMeasurements for Track4 of the CARLA AD challenge\n    - Added track identification for autonomous_agent.py\n    - Added HDMap pseudo-sensor\n    - Added new traffic event logger\n    - Added various helper methods to allow generic scenario execution\n    - Added method to calculate distance along a route\n    - In challenge mode spawn exception are caught and the corresponding scenario is removed\n* Added new atomic behaviors using py_trees behavior tree library\n    - BasicAgentBehavior: drive to target location using CARLA's BasicAgent\n    - StandStill: check if a vehicle stands still\n    - InTriggerDistanceToNextIntersection: check if a vehicle is within certain distance with respect to the next intersection\n    - WaypointFollower: follows auto-generated waypoints indefinitely or follows a given waypoint list\n    - HandBrakeVehicle: sets the handbrake value for a given actor\n    - ActorDestroy: destroys a given actor\n    - ActorTransformSetter: sets transform of given actor\n    - ActorSource: creates actors indefinitely around a location if no other vehicles are present within a threshold\n    - ActorSink: indefinitely destroys vehicles that wander close to a location within a threshold\n    - InTriggerDistanceToLocationAlongRoute: check if an actor is within a certain distance to a given location along a given route\n* Added new atomic evaluation criteria\n    - Added running red light test\n    - Added running stop test\n    - Added wrong way test\n* Added NHTSA Traffic Scenarios\n    - Updated all traffic scenarios to let the other actors appear upon scenario triggering and removal on scenario end\n    - ManeuverOppositeDirection: hero vehicle must maneuver in the opposite lane to pass a leading vehicle.\n    - OtherLeadingVehicle: hero vehicle must react to the deceleration of leading vehicle and change lane to avoid collision and follow the vehicle in changed lane\n    - 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.\n    - SignalizedJunctionLeftTurn : hero vehicle is turning left at signalized intersection, cuts across the path of another vehicle coming straight crossing from an opposite direction.\n### :bug: Bug Fixes\n* Fixed SteerVehicle atomic behavior to keep vehicle velocity    \n### :ghost: Maintenance\n* Reworked scenario execution\n    - Updated folder structure and naming convention in lowercase\n    - Extended CarlaDataProvider with method to get next relevant traffic light\n    - Every scenario has to have a configuration provided as XML file.\n      Currently there is one XML file for each scenario class\n    - The scenario runner is now responsible for spawning/destroying the ego vehicle\n    - Added a CarlaActorPool to share scenario-related actors between scenarios and the scenario_runner\n    - Renamed vehicle -> actor\n    - If all scenarios in one configurations file should be executed, the scenario_runner can be started with --scenario group:<CONFIG_FILE>\n    - Generalized ControlLoss and FollowLeadingVehicle scenarios\n    - Added randomization option to scenario_runner and scenarios\n    - The scenario behavior always starts with a wait behavior until the ego vehicle reached the scenario starting position\n    - Created method _initialize_actors in basic scenario that can be overridden for scenario specific actor initialization\n* Updated NHTSA Traffic Scenarios\n    - OppositeVehicleRunningRedLight: Updated to allow execution at different locations    \n\n\n## CARLA ScenarioRunner 0.9.2\n**This release is designed to work with CARLA 0.9.2**\n### :rocket: New Features\n* Added Traffic Scenarios engine to reproduce complex traffic situations for training and evaluating driving agents\n* Added NHTSA Traffic Scenarios\n    - FollowLeadingVehicle: hero vehicle must react to the deceleration of a leading vehicle\n    - FollowLeadingVehicleWithObstacle: hero vehicle must react to a leading vehicle due to an obstacle blocking the road\n    - StationaryObjectCrossing: hero vehicle must react to a cyclist or pedestrian blocking the road\n    - DynamicObjectCrossing: hero vehicle must react to a cyclist or pedestrian suddenly crossing in front of it\n    - OppositeVehicleRunningRedLight: hero vehicle must avoid a collision at an intersection regulated by traffic lights when the crossing traffic runs a red light\n    - NoSignalJunctionCrossing: hero vehicle must cross a non-signalized intersection\n    - VehicleTurningRight: hero vehicle must react to a cyclist or pedestrian crossing ahead after a right turn\n    - VehicleTurningLeft: hero vehicle must react to a cyclist or pedestrian crossing ahead after a left turn\n    - ControlLoss: Hero vehicle must react to a control loss and regain its control\n* Added atomic behaviors using py_trees behavior trees library\n    - InTriggerRegion: new behavior to check if an object is within a trigger region\n    - InTriggerDistanceToVehicle: check if a vehicle is within certain distance with respect to a reference vehicle\n    - InTriggerDistanceToLocation: check if a vehicle is within certain distance with respect to a reference location\n    - TriggerVelocity: triggers if a velocity is met\n    - InTimeToArrivalToLocation:  check if a vehicle arrives within a given time budget to a reference location\n    - InTimeToArrivalToVehicle: check if a vehicle arrives within a given time budget to a reference vehicle\n    - AccelerateToVelocity: accelerate until reaching requested velocity\n    - KeepVelocity: keep constant velocity\n    - DriveDistance: drive certain distance\n    - UseAutoPilot: enable autopilot\n    - StopVehicle: stop vehicle\n    - WaitForTrafficLightState: wait for the traffic light to have a given state\n    - SyncArrival: sync the arrival of two vehicles to a given target\n    - AddNoiseToVehicle: Add noise to steer as well as throttle of the vehicle\n    - CutInWithStaticVehicle:Based on the code of ParkingCutIn,realized the cutin function of a static vehicle on the highway\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/CODE_OF_CONDUCT.md",
    "content": "# Contributor Covenant Code of Conduct\n\n## Our Pledge\n\nIn the interest of fostering an open and welcoming environment, we as\ncontributors and maintainers pledge to making participation in our project and\nour community a harassment-free experience for everyone, regardless of age, body\nsize, disability, ethnicity, gender identity and expression, level of experience,\neducation, socio-economic status, nationality, personal appearance, race,\nreligion, or sexual identity and orientation.\n\n## Our Standards\n\nExamples of behavior that contributes to creating a positive environment\ninclude:\n\n* Using welcoming and inclusive language\n* Being respectful of differing viewpoints and experiences\n* Gracefully accepting constructive criticism\n* Focusing on what is best for the community\n* Showing empathy towards other community members\n\nExamples of unacceptable behavior by participants include:\n\n* The use of sexualized language or imagery and unwelcome sexual attention or\n  advances\n* Trolling, insulting/derogatory comments, and personal or political attacks\n* Public or private harassment\n* Publishing others' private information, such as a physical or electronic\n  address, without explicit permission\n* Other conduct which could reasonably be considered inappropriate in a\n  professional setting\n\n## Our Responsibilities\n\nProject maintainers are responsible for clarifying the standards of acceptable\nbehavior and are expected to take appropriate and fair corrective action in\nresponse to any instances of unacceptable behavior.\n\nProject maintainers have the right and responsibility to remove, edit, or\nreject comments, commits, code, wiki edits, issues, and other contributions\nthat are not aligned to this Code of Conduct, or to ban temporarily or\npermanently any contributor for other behaviors that they deem inappropriate,\nthreatening, offensive, or harmful.\n\n## Scope\n\nThis Code of Conduct applies both within project spaces and in public spaces\nwhen an individual is representing the project or its community. Examples of\nrepresenting a project or community include using an official project e-mail\naddress, posting via an official social media account, or acting as an appointed\nrepresentative at an online or offline event. Representation of a project may be\nfurther defined and clarified by project maintainers.\n\n## Enforcement\n\nInstances of abusive, harassing, or otherwise unacceptable behavior may be\nreported by contacting the project team at [INSERT EMAIL ADDRESS]. All\ncomplaints will be reviewed and investigated and will result in a response that\nis deemed necessary and appropriate to the circumstances. The project team is\nobligated to maintain confidentiality with regard to the reporter of an incident.\nFurther details of specific enforcement policies may be posted separately.\n\nProject maintainers who do not follow or enforce the Code of Conduct in good\nfaith may face temporary or permanent repercussions as determined by other\nmembers of the project's leadership.\n\n## Attribution\n\nThis Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4,\navailable at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html\n\n[homepage]: https://www.contributor-covenant.org\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/CONTRIBUTING.md",
    "content": "Contributing to CARLA\n=====================\n\nWe are more than happy to accept contributions!\n\nHow can I contribute?\n\n  * Reporting bugs\n  * Feature requests\n  * Improving documentation\n  * Code contributions\n\nReporting bugs\n--------------\n\nUse our [issue section][issueslink] on GitHub. Please check before that the\nissue is not already reported, and make sure you have read our CARLA\n[Documentation][docslink] and [FAQ][faqlink].\n\n[issueslink]: https://github.com/carla-simulator/scenario_runner/issues\n[docslink]: http://carla.readthedocs.io\n[faqlink]: http://carla.readthedocs.io/en/latest/faq/\n\nFeature requests\n----------------\n\nPlease check first the list of [feature requests][frlink]. If it is not there\nand you think is a feature that might be interesting for users, please submit\nyour request as a new issue.\n\n[frlink]: https://github.com/carla-simulator/scenario_runner/issues?q=is%3Aissue+is%3Aopen+label%3A%22feature+request%22+sort%3Acomments-desc\n\nImproving documentation\n-----------------------\n\nIf you feel something is missing in the documentation, please don't hesitate to\nopen an issue to let us know. Even better, if you think you can improve it\nyourself, it would be a great contribution to the community!\n\nWe build our documentation with [MkDocs](http://www.mkdocs.org/) based on the\nMarkdown files inside the \"Docs\" folder. You can either directly modify them on\nGitHub or locally in your machine.\n\nOnce you are done with your changes, please submit a pull-request.\n\n**TIP:** You can build and serve it locally by running `mkdocs` in the project's\nmain folder\n\n    $ sudo pip install mkdocs\n    $ mkdocs serve\n\nCode contributions\n------------------\n\nSo you are considering making a code contribution, great! we love to have\ncontributions from the community.\n\nBefore starting hands-on on coding, please check out our\n[issue board][wafflelink] to see if we are already working on that, it would\nbe a pity putting an effort into something just to discover that someone else\nwas already working on that. In case of doubt or to discuss how to proceed,\nplease contact one of us (or send an email to carla.simulator@gmail.com).\n\n[wafflelink]: https://waffle.io/carla-simulator/scenario_runner\n\n#### What should I know before I get started?\n\nCheck out the [\"CARLA Documentation\"][docslink] to get an idea on CARLA. In\naddition you may want to check the [Getting started](getting_started.md) document.\n\n[docslink]: http://carla.readthedocs.io\n\n#### Coding standard\n\nPlease follow the current [coding standard](coding_standard.md) when submitting\nnew code.\n\n#### Pull-requests\n\nOnce you think your contribution is ready to be added to CARLA, please submit a\npull-request.\n\nTry to be as descriptive as possible when filling the pull-request description.\nAdding images and gifs may help people to understand your changes or new\nfeatures.\n\nPlease note that there are some checks that the new code is required to pass\nbefore we can do the merge. The checks are automatically run by the continuous\nintegration system, you will see a green tick mark if all the checks succeeded.\nIf you see a red mark, please correct your code accordingly.\n\n###### Checklist\n\n  - [ ] Your branch is up-to-date with the `master` branch and tested with latest changes\n  - [ ] Extended the README / documentation, if necessary\n  - [ ] Code compiles correctly\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/FAQ.md",
    "content": "# Frequently Asked Questions\n\n## I receive the error \"TypeError: 'instancemethod' object has no attribute '__getitem__'\" in the agent navigation\n\nThis issue is most likely caused by an outdated version of the Python Networkx package. Please remove the current installation\n(e.g. sudo apt-get remove python-networkx) and install it using \"pip install --user networkx==2.2\".\n\n## No scenario visible and I receive the message \"No more scenarios .... Exiting\"\n\nIn case you receive the following output\n```\nPreparing scenario: FollowLeadingVehicle_1\nScenarioManager: Running scenario FollowVehicle\nResetting ego-vehicle!\nFailure!\nResetting ego-vehicle!\nERROR: failed to destroy actor 527 : unable to destroy actor: not found\nNo more scenarios .... Exiting\n```\nand you see nothing happening, it is most likely due to the fact, that you did not launch a program to control\nthe ego vehicle. Run for example manual_control.py, and you should now see something happening.\n\n\n## Scenario Runner exits with error when using --debug commandline parameter\n\nIn case you receive the following output\n```\nUnicodeEncodeError: 'ascii' codec can't encode character '\\u2713' in position 58: ordinal not in range(128)\n```\nPlease set environment variable\n```\nPYTHONIOENCODING=utf-8\n```\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/agent_evaluation.md",
    "content": "#### Setting up your agent for evaluation\n\n## 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\n\nTo have your agent evaluated by the challenge evaluation system\nyou must define an Agent class that inherits the\n[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.\n\nOn your agent class there are three main functions to be overwritten\nthat need to be defined in order to set your agent to run.\nFurther you also should consider the route to the goal that is\ninitially set as a variable.\n\n\n##### The \"setup\" function:\nThis is the function where you should make all the necessary setup\nfor the your agent.\n\nThis function receives as a parameter the path to a configuration\nfile to be parsed by the user.\n\nWhen executing the \"challenge_evaluator.py\" you should pass the\nconfiguration file path as a parameter. For example:\n\n```\npython srunner/challenge/challenge_evaluator_routes.py  --agent=<path_to_my_agent> --config=myconfigfilename.format\n```\n\n\n##### The \"sensors\" function:\n\nThis function is where you set all the sensors required by your agent.\nFor instance, on the dummy agent sample class the following sensors are defined:\n\n```Python\ndef sensors(self):\n    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'},\n               {'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'},\n               {'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'},\n               {'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'},\n               {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'},\n               {'type': 'sensor.speedometer','reading_frequency': 25, 'id': 'speed'}\n              ]\n    return sensors\n```\n\n\nEvery sensor is a dictionary where you should\nspecify:\n\n* 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.\n* id: the label that will be given to the sensor in order for it to be accessed later.\n* other parameters: these are sensor dependent, such as position, 'x' and 'y', or the field of view for a camera, 'fov'\n\n\n\n\n##### The \"run_step\" function:\n\nThis function is called on every step of the simulation from the challenge evaluation\nan receives some input data as parameter.\n\nThis input data is a dictionary with all the sensors specified on the \"sensors\" function.\n\nThis function should return a [vehicle control](https://carla.readthedocs.io/en/latest/python_api_tutorial/#vehicles)\n to be applied into the ego vehicle.\n\n\n\n\n##### The initial route:\n\nOn the beginning of the execution, the entire route that the hero agent\nshould travel is set on  the \"self.global_plan\" variable:\n\n```\n[({'z': 0.0, 'lat': 48.99822669411668, 'lon': 8.002271601998707}, <RoadOption.LANEFOLLOW: 4>),\n ({'z': 0.0, 'lat': 48.99822669411668, 'lon': 8.002709765148996}, <RoadOption.LANEFOLLOW: 4>),\n ...\n ({'z': 0.0, 'lat': 48.99822679980298, 'lon': 8.002735250105061}, <RoadOption.LANEFOLLOW: 4>)]`\n ```\n\n It is represented as a list of tuples, containing the route waypoints, expressed in latitude\n and longitude and the current road option recommended. For an intersection, the option can\n be go straight, turn left or turn right. For the rest of the route the recommended option\n is lane follow.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/coding_standard.md",
    "content": "<h1>Coding standard</h1>\n\n> _This document is a work in progress and might be incomplete._\n\nGeneral\n-------\n\n  * Use spaces, not tabs.\n  * Avoid adding trailing whitespace as it creates noise in the diffs.\n  * Comments should not exceed 120 columns, code may exceed this limit a bit in\n    rare occasions if it results in clearer code.\n\nPython\n------\n\n  * All code must be compatible with Python 2.7, 3.5, and 3.6.\n  * [Pylint][pylintlink] should not give any error or warning (few exceptions\n    apply with external classes like `numpy`, see our `.pylintrc`).\n  * Python code follows [PEP8 style guide][pep8link] (use `autopep8` whenever\n    possible).\n\n[pylintlink]: https://www.pylint.org/\n[pep8link]: https://www.python.org/dev/peps/pep-0008/\n\nC++\n---\n\n  * Compilation should not give any error or warning\n    (`clang++ -Wall -Wextra -std=C++14 -Wno-missing-braces`).\n  * Unreal C++ code (CarlaUE4 and Carla plugin) follow the\n    [Unreal Engine's Coding Standard][ue4link] with the exception of using\n    spaces instead of tabs.\n  * LibCarla uses a variation of [Google's style guide][googlelink].\n\n[ue4link]: https://docs.unrealengine.com/latest/INT/Programming/Development/CodingStandard/\n[googlelink]: https://google.github.io/styleguide/cppguide.html\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/creating_new_scenario.md",
    "content": "# Create a new scenario tutorial\n\nThis tutorial describes how you can create and run a new scenario using the\nScenarioRunner and the ScenarioManager suite.\n\nLet us call the new scenario _NewScenario_. To create it, there are only few\nsteps required.\n\n## Creating an empty Python class\nGo to the Scenarios folder and create a new Python class with the name\n_NewScenario_ in a new Python file (_new_scenario.py_). The class should be\nderived from the _BasicScenario_ class. As a result, the class should look as\nfollows:\n\n   ```\n   class NewScenario(BasicScenario):\n       \"\"\"\n       Some documentation on NewScenario\n       :param world is the CARLA world\n       :param ego_vehicles is a list of ego vehicles for this scenario\n       :param config is the scenario configuration (ScenarioConfiguration)\n       :param randomize can be used to select parameters randomly (optional, default=False)\n       :param debug_mode can be used to provide more comprehensive console output (optional, default=False)\n       :param criteria_enable can be used to disable/enable scenario evaluation based on test criteria (optional, default=True)\n       :param timeout is the overall scenario timeout (optional, default=60 seconds)\n       \"\"\"\n\n       # some ego vehicle parameters\n       # some parameters for the other vehicles\n\n       def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                    timeout=60):\n           \"\"\"\n           Initialize all parameters required for NewScenario\n           \"\"\"\n\n           # Call constructor of BasicScenario\n           super(NewScenario, self).__init__(\n             \"NewScenario\",\n             ego_vehicles,\n             config,\n             world,\n             debug_mode,\n             criteria_enable=criteria_enable)\n\n\n       def _create_behavior(self):\n           \"\"\"\n           Setup the behavior for NewScenario\n           \"\"\"\n\n       def _create_test_criteria(self):\n           \"\"\"\n           Setup the evaluation criteria for NewScenario\n           \"\"\"\n   ```\n\n## Filling the Python class\n\nIn the NewScenario class, you have to define the following methods mentioned\nin the code example.\n\n### Initialize Method\nThe initialize method is intended to setup all parameters required\nfor the scenario and all vehicles. This includes selecting the correct vehicles,\nspawning them at the correct location, etc. To simplify this, you may want to\nuse the _setup_vehicle()_ function defined in basic_scenario.py\n\n### CreateBehavior method\nThis method should setup the behavior tree that contains the behavior of all\nnon-ego vehicles during the scenario. The behavior tree should use py_trees and\nthe atomic behaviors defined in _atomic_scenario_behavior.py_\n\n### CreateTestCriteria method\nThis method should setup a list with all evaluation criteria for the scenario.\nThe criteria should be based on the atomic criteria defined in\n_atomic_scenario_criteria.py_.\n\nNote: From this list a parallel py_tree will be created automatically!\n\n## Adding the scenario configuration\nFinally the scenario configuration should be added to the examples/ folder. If you\nextend an already existing scenario module, you can simply extend the corresponding\nXML, otherwise add a new XML file. In this case you can use any of the existing\nXML files as blueprint.\n\nIf you want to add multiple ego vehicles for a scenario, make sure that they use different\nrole names, e.g.\n```\n    <scenario name=\"MultiEgoTown03\" type=\"FreeRide\" town=\"Town03\">\n        <ego_vehicle x=\"207\" y=\"59\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" rolename=\"hero\"/>\n        <ego_vehicle x=\"237\" y=\"-95.0754252474\" z=\"0\" yaw=\"90\" model=\"vehicle.tesla.model3\" rolename=\"hero2\"/>\n    </scenario>\n```\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/extra.css",
    "content": ".build-buttons{\n    text-align: center;\n}\n\n.build-buttons > p {\n    display: inline-block;\n    vertical-align: top;\n    padding: 5px;\n}\n\n.vector-zero {\n    text-align: center;\n}\n\n\n/************************* DEFAULT TABLES **************************/\n\ntable {\n  border: 1px solid #242424;\n  background-color: #f3f6f6;\n  text-align: left;\n  border-collapse: collapse;\n}\n\ntable thead {\n  background: #ffffff; \n  border-bottom: 1px solid #444444;\n}\n\ntable tr:nth-child(even) {\n  background: #ffffff;\n}\n\ntable thead th {\n  padding: 7px 13px;\n}\n\ntable tbody td{\n  padding: 7px 13px;\n}\n\n/************************* TOWN SLIDER **************************/\n\n * {box-sizing:border-box}\n\n/* Container */\n.townslider-container {\n  max-width: 1000px;\n  position: relative;\n  margin: auto;\n}\n\n/* Hide the images by default */\n.townslide {\n  display: none;\n  text-align: center; \n\n}\n\n/* Fading animation for slides */\n.fade {\n  -webkit-animation-name: fade;\n  -webkit-animation-duration: 1.5s;\n  animation-name: fade;\n  animation-duration: 1.5s;\n}\n\n@-webkit-keyframes fade {\n  from {opacity: .4}\n  to {opacity: 1}\n}\n\n@keyframes fade {\n  from {opacity: .4}\n  to {opacity: 1}\n}\n\n/* \"next\" and \"previous\" buttons */\n.prev, .next {\n  cursor: pointer;\n  position: absolute;\n  top: 50%;\n  width: auto;\n  margin-top: -22px;\n  padding: 16px;\n  color: white;\n  font-weight: bold;\n  font-size: 18px;\n  transition: 0.6s ease;\n  border-radius: 0 3px 3px 0;\n  user-select: none;\n}\n\n/* Position the \"next\" button*/\n.next {\n  right: 0;\n  border-radius: 3px 0 0 3px;\n}\n\n/* Black background color to buttons when hovering*/\n.prev:hover, .next:hover {\n  background-color: rgba(0,0,0,0.8);\n}\n\n/* Caption text for towns */\n.text {\n  color: #f2f2f2;\n  font-size: 15px;\n  padding: 8px 12px;\n  position: absolute;\n  bottom: 8px;\n  width: 100%;\n  text-align: center;\n  /*background-color:rgba(0,0,0,0.5);*/\n}\n\n/* The dot indicators for slides */\n.dot {\n  cursor: pointer;\n  height: 15px;\n  width: 15px;\n  margin: 0 2px;\n  background-color: #bbb;\n  border-radius: 50%;\n  display: inline-block;\n  transition: background-color 0.6s ease;\n}\n\n.active, .dot:hover {\n  background-color: #717171;\n}\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/getting_scenariorunner.md",
    "content": "# Get ScenarioRunner\n\nThis 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.  \n\n*   __[Installation summary](#installation-summary)__  \n*   __[A. Download a ScenarioRunner release](#a.-download-a-scenariorunner-release)__  \n\t*   [Update the release](#update-the-release)  \n*   __[B. Download ScenarioRunner from source](#b.-build-scenariorunner-from-source)__  \n\t*   [Update the build from source](#update-the-build-from-source)  \n*   __[Run a test](#run-a-test)__  \n\n---\n## Installation summary\n\n<details>\n   <summary>\n    Show command line summary for the quick start installation\n   </summary>\n\n```sh\n# Decide whether to use a package or make the build from source\n\n\n# Option A) Use a ScenarioRunner package\n   # 1. Install a CARLA package: \n      https://carla.readthedocs.io/en/latest/start_quickstart/\n   # 2. Download the matching ScenarioRunner package: \n      https://github.com/carla-simulator/scenario_runner/releases\n   # 3. Extract the content wherever needed. \n\n   # Update the release: \n   # 1. Delete previous CARLA and ScenarioRunner versions.\n   # 2. Download the latest CARLA release. \n   # 3. Download the matching ScenarioRunner release.\n\n\n# Option B) Download ScenarioRunner from source\n   # 1. Build CARLA from source:\n      https://carla.readthedocs.io/en/latest/build_linux/\n   # 2. Clone the ScenarioRunner repository: \ngit clone https://github.com/carla-simulator/scenario_runner.git\n   # 3. Install requirements according to the Python version to be used: \n   # For Python 2.x:\nsudo apt remove python-networkx #if installed, remove old version of networkx\npip2 install --user -r requirements.txt\n   # For Python 3.x: \nsudo apt remove python3-networkx #if installed, remove old version of networkx\npip3 install --user -r requirements.txt\n\n   # To update ScenarioRunner from source:\n   # 1. Update CARLA: \n      https://carla.readthedocs.io/en/latest/build_update/\n   # 2. Go to the ScenarioRunner repository, master branch\ncd ~/scenario_runner\ngit branch master\n   # 3. Pull the latest changes from the repository\ngit pull \n\n```\n</details>\n\n\n---\n## A. Download a ScenarioRunner release\n\nThe releases of ScenarioRunner are packages containing:  \n*   A ScenarioRunner version tied to a specific CARLA release.  \n*   A few example scenarios written in Python.  \n\nThe process to run a ScenarioRunner release is quite straightforward.  \n\n__1. Download a CARLA release.__ Follow the process in the [CARLA quick start](https://github.com/carla-simulator/carla/releases).  \n__2. Download the matching ScenarioRunner release.__ All of the releases are listed [here](https://github.com/carla-simulator/scenario_runner/releases).\n\n!!! Important\n    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.  \n\n__3. Extract the content.__ The directory does not matter.  \n\n\n### Update the release\n\nThe 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:  \n\n*   [CARLA releases](https://github.com/carla-simulator/carla/releases)  \n*   [Scenario Runner releases](https://github.com/carla-simulator/scenario_runner/releases)  \n\nTo run the latest or any other release, delete the previous and install the one desired.  \n\n---\n## B. Download ScenarioRunner from source\n\nThe 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.  \n\n__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/).  \n\n!!! Important\n    ScenarioRunner needs CARLA to run, so the minimum requirements for CARLA stated in the docs are also necessary to run ScenarioRunner.  \n\n__2. Clone the ScenarioRunner repository.__\n\n```sh\ngit clone https://github.com/carla-simulator/scenario_runner.git\n```\n\n__3. Install the requirements according to the Python version to be used.__  First go to the main ScenarioRunner directory\n\n```sh\ncd ~/scenario_runner/\n```\n\n*   __For Python 2.x.__  \n\n```sh\nsudo apt remove python-networkx #if installed, remove old version of networkx\npip2 install --user -r requirements.txt\n```\n\n*   __For Python 3.x__  \n```sh\nsudo apt remove python3-networkx #if installed, remove old version of networkx\npip3 install --user -r requirements.txt\n```\n\n!!! Warning\n    py-trees newer than v0.8 are __not__ supported.\n\n\n### Update from source  \n\n__1. Update the CARLA build__ Follow the [docs](https://carla.readthedocs.io/en/latest/build_update/) to update CARLA.  \n\n__2. Go to the main ScenarioRunner directory.__ Make sure to be in the local master branch.  \n\n```sh\ncd ~/scenario_runner\ngit branch master\n```\n__3. Pull the latest changes from the repository.__  \n\n```sh\ngit pull\n```\n\n__4. Add environment variables and Python paths__ These are necessary for the system to find CARLA, and add the PythonAPI to the Python path.\n\n*   __For Linux__\n\n```sh\n# ${CARLA_ROOT} is the CARLA installation directory\n# ${SCENARIO_RUNNER} is the ScenarioRunner installation directory\n# <VERSION> is the correct string for the Python version being used\n# In a build from source, the .egg files may be in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI\nexport CARLA_ROOT=/path/to/your/carla/installation\nexport SCENARIO_RUNNER_ROOT=/path/to/your/scenario/runner/installation\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-<VERSION>.egg\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla\n```\n\n!!! Note\n    Change the command lines with the proper paths, according to the comments. \n\n*   __For Windows__\n\n\n```sh\n# %CARLA_ROOT% is the CARLA installation directory\n# %SCENARIO_RUNNER% is the ScenarioRunner installation directory\n# <VERSION> is the correct string for the Python version being used\n# In a build from source, the .egg files may be in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI\nset CARLA_ROOT=\\path\\to\\your\\carla\\installation\nset SCENARIO_RUNNER_ROOT=\\path\\to\\your\\scenario\\runner\\installation\nset PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\\PythonAPI\\carla\\dist\\carla-<VERSION>.egg\nset PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\\PythonAPI\\carla\n```\n\n!!! Note\n    Change the command lines with the proper paths, according to the comments. \n\nTo 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.\n\n---\n## Run a test \n\nRunning the follow vehicle example\nFirst of all, you need to get latest master branch from CARLA. Then you have to\ninclude CARLA Python API to the Python path:\n\n!!! Important\n    If working with builds from source, make sure to upload these. Download the latest content in the master branches.  \n\n\n__1. Run the CARLA server.__\n\n*   __A) In a build from source__ go to the CARLA directory and launch the server in the editor. \n\n```sh\ncd ~/carla # Change the path accordingly\nmake launch\n# Press Play in the UE Editor\n```\n\n*   __B) In a CARLA package__ run the server directly. \n\n```sh\n./CarlaUE4.sh\n```\n\n__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. \n\n```sh\n# Inside the ScenarioRunner root directory\npython scenario_runner.py --scenario FollowLeadingVehicle_1 --reloadWorld\n```\n\n!!! Note\n    If using a Python 3.x version, run the command with `python3`. \n\n__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. \n\n```sh\n# Inside the ScenarioRunner root directory\npython manual_control.py\n```\n\nThe 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.  \n\n!!! Warning\n    Run the `manual_control.py` found in the ScenarioRunner package/repository, __not CARLA__. \n\n__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`.\n\n```sh\npython scenario_runner.py --help\n```\n\n---\n\nThus 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. \n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/getting_started.md",
    "content": "# Getting Started Tutorial\n\n!!! important\n    This tutorial refers to the latest versions of CARLA (at least 0.9.5)\n\nWelcome to the ScenarioRunner for CARLA! This tutorial provides the basic steps\nfor getting started using the ScenarioRunner for CARLA.\n\nDownload the latest release from our GitHub page and extract all the contents of\nthe package in a folder of your choice.\n\nThe release package contains the following\n\n  * The ScenarioRunner for CARLA\n  * A few example scenarios written in Python.\n\n## Installing prerequisites\nThe current version is designed to be used with Ubuntu 16.04, Python 2.7 or\nPython 3.5. Depending on your Python version, execute:\n```\n\n\n#Python 2.x\nsudo apt remove python-networkx #if installed, remove old version of networkx\npip2 install --user -r requirements.txt\n#Python 3.x\nsudo apt remove python3-networkx #if installed, remove old version of networkx\npip3 install --user -r requirements.txt\n```\nNote: py-trees newer than v0.8 is *NOT* supported.\n\n\n\n## Running the follow vehicle example\nFirst of all, you need to get latest master branch from CARLA. Then you have to\ninclude CARLA Python API to the Python path:\n```Bash\nexport CARLA_ROOT=/path/to/your/carla/installation\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-<VERSION>.egg:${CARLA_ROOT}/PythonAPI/carla/agents:${CARLA_ROOT}/PythonAPI/carla\n```\nNOTE: ${CARLA_ROOT} needs to be replaced with your CARLA installation directory,\n      and <VERSION> needs to be replaced with the correct string.\n      If you build CARLA from source, the egg files maybe located in:\n      ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI.\n\nNow, you can start the CARLA server from ${CARLA_ROOT}\n```\n./CarlaUE4.sh\n```\n\nStart the example scenario (follow a leading vehicle) in an extra terminal:\n```\npython scenario_runner.py --scenario FollowLeadingVehicle_1 --reloadWorld\n```\n\nIf you require help or want to explore other command line parameters, start the scenario\nrunner as follows:\n```\npython scenario_runner.py --help\n```\n\nTo control the ego vehicle within the scenario, open another terminal and run:\n```\npython manual_control.py\n```\n\nNote: If you do not wish to automatically (re-)load the CARLA world, you can\nskip the command line option _--reloadWorld_\n\n## Running all scenarios of one scenario class\nSimilar to the previous example, it is also possible to execute a sequence of scenarios,\nthat belong to the same class, e.g. the \"FollowLeadingVehicle\" class.\n\nThe only difference is, that you start the scenario_runner as follows:\n```\npython scenario_runner.py --scenario group:FollowLeadingVehicle\n```\n\n## Running other scenarios\nA list of supported scenarios is provided in\n[List of Supported Scenarios](list_of_scenarios.md). Please note that\ndifferent scenarios may take place in different CARLA towns. This has to be\nrespected when launching the CARLA server.\n\n## Running scenarios using the OpenSCENARIO format\nTo run a scenario, which is based on the OpenSCENARIO format, please run the ScenarioRunner as follows:\n```\npython scenario_runner.py --openscenario <path/to/xosc-file>\n```\nPlease note that the OpenSCENARIO support and the OpenSCENARIO format itself are still work in progress.\nMore information you can find in [OpenSCENARIO support](openscenario_support.md)\n\n### Running scenarios using the OpenSCENARIO format with Global ParameterDeclaration overwrite\n```\npython scenario_runner.py --openscenario <path/to/xosc-file> --openscenarioparams 'param1: value1, param2: value2'\n```\n\n## Running route-based scenario (similar to the CARLA AD Challenge)\nTo run a route-based scenario, please run the ScenarioRunner as follows:\n```\npython scenario_runner.py --route <path/to/route-file> <path/to/scenario_sample_file> [route id] --agent <path/to/agent_file>\n```\nExample:\n```\npython 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\n```\n\nIf no route id is provided, all routes within the given file will be executed.\n\n\nBy 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)\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/index.md",
    "content": "[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT)\n![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/carla-simulator/scenario_runner.svg)\n[![Build Status](https://travis-ci.com/carla-simulator/scenario_runner.svg?branch=master)](https://travis-ci.com/carla/scenario_runner)\n\n# ScenarioRunner\n\nScenarioRunner 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.  \n  \nScenarioRunner 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.\n\n\nThe 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.  \n<div class=\"build-buttons\">\n<a href=\"https://forum.carla.org/\" target=\"_blank\" class=\"btn btn-neutral\" title=\"Go to the latest CARLA release\">\nCARLA forum</a>\n</div>\n\n---\n\n## Quick start\n\n[**Get ScenarioRunner**](<getting_scenariorunner>) — Tutorial on how to download and launch ScenarioRunner.<br>\n\n[**First steps**](<getting_started>) — Brief tutorials on how to run different types of scenarios.<br>\n\n[**Create a new scenario**](<creating_new_scenario>) — Tutorial on how to create a new scenario using ScenarioRunner.<br>\n\n[**Metrics module**](<metrics_module>) — Explanation of the metrics module.<br>\n\n[**F.A.Q.**](<FAQ>) — Some of the most frequent installation issues.<br>\n\n[**Release notes**](<CHANGELOG>) — Features, fixes and other changes listed per release.<br>\n\n\n## References\n\n[**List of scenarios**](<list_of_scenarios>) — Example scenarios available in ScenarioRunner.<br>\n\n[**OpenScenario support**](<openscenario_support>) — Support status of OpenSCENARIO features.<br>\n\n\n## Contributing\n[**Code of conduct**](<CODE_OF_CONDUCT>) — Standard rights and duties for contributors.<br>\n\n[**Coding standard**](<coding_standard>) — Guidelines to write proper code.<br>\n\n[**Contribution guidelines**](<CONTRIBUTING>) — The different ways to contribute to ScenarioRunner.<br>\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/list_of_scenarios.md",
    "content": "# List of Supported Scenarios\n\nWelcome to the ScenarioRunner for CARLA! This document provides a list of all\ncurrently supported scenarios, and a short description for each one.\n\n### FollowLeadingVehicle\nThe scenario realizes a common driving behavior, in which the user-controlled\nego vehicle follows a leading car driving down a given road in Town01. At some\npoint the leading car slows down and finally stops. The ego vehicle has to react\naccordingly to avoid a collision. The scenario ends either via a timeout, or if\nthe ego vehicle stopped close enough to the leading vehicle\n\n### FollowLeadingVehicleWithObstacle\nThis scenario is very similar to 'FollowLeadingVehicle'. The only difference is,\nthat in front of the leading vehicle is a (hidden) obstacle that blocks the way.\n\n### VehicleTurningRight\nIn this scenario the ego vehicle takes a right turn from an intersection where\na cyclist suddenly drives into the way of the ego vehicle,which has to stop\naccordingly. After some time, the cyclist clears the road, such that ego vehicle\ncan continue driving.\n\n### VehicleTurningLeft\nThis scenario is similar to 'VehicleTurningRight'. The difference is that the ego\nvehicle takes a left turn from an intersection.\n\n### OppositeVehicleRunningRedLight\nIn this scenario an illegal behavior at an intersection is tested. An other\nvehicle waits at an intersection, but illegally runs a red traffic light. The\napproaching ego vehicle has to handle this situation correctly, i.e. despite of\na green traffic light, it has to stop and wait until the intersection is clear\nagain. Afterwards, it should continue driving.\n\n### StationaryObjectCrossing\nIn this scenario a cyclist is stationary waiting in the middle of the road and\nblocking the way for the ego vehicle. Hence, the ego vehicle has to stop in\nfront of the cyclist.\n\n### DynamicObjectCrossing\nThis is similar to 'StationaryObjectCrossing', but with the difference that the\ncyclist is dynamic. It suddenly drives into the way of the ego vehicle, which\nhas to stop accordingly. After some time, the cyclist will clear the road, such\nthat the ego vehicle can continue driving.\n\n### NoSignalJunctionCrossing\nThis scenario tests negotiation between two vehicles crossing cross each other\nthrough a junction without signal.\nThe ego vehicle is passing through a junction without traffic lights\nAnd encounters another vehicle passing across the junction. The ego vehicle has\nto avoid collision and navigate across the junction to succeed.\n\n### ControlLoss\nIn this scenario control loss of a vehicle is tested due to bad road conditions, etc\nand it checks whether the vehicle is regained its control and corrected its course.\n\n### ManeuverOppositeDirection\nIn this scenario vehicle is passing another vehicle in a rural area, in daylight, under clear\nweather conditions, at a non-junction and encroaches into another\nvehicle traveling in the opposite direction.\n\n### OtherLeadingVehicle\nThe scenario realizes a common driving behavior, in which the user-controlled ego\nvehicle follows a leading car driving down a given road.\nAt some point the leading car has to decelerate. The ego vehicle has to react\naccordingly by changing lane to avoid a collision and follow the leading car in\nother lane. The scenario ends via timeout, or if the ego vehicle drives certain\ndistance.\n\n### SignalizedJunctionRightTurn\nIn this scenario right turn of hero actor without collision at signalized intersection\nis tested. Hero Vehicle is turning right in an urban area, at a signalized intersection and\nturns into the same direction of another vehicle crossing straight initially from\na lateral direction.\n\n### SignalizedJunctionLeftTurn\nIn this scenario hero vehicle is turning left in an urban area,\nat a signalized intersection and cuts across the path of another vehicle\ncoming straight crossing from an opposite direction.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/metrics_module.md",
    "content": "# Metrics module\n\n\nThe 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. \n\nThis 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.  \n\n* [__Structure of the module__](#structure-of-the-module)  \n* [__How to use the metrics module__](#how-to-use-the-metrics-module)  \n\t* [1. Record a scenario](#1.-record-a-scenario)  \n\t* [2. Define the metrics](#2.-run-the-metrics-manager)  \n\t* [3. Run the metrics manager](#3.-run-the-metrics-manager)  \n* [__Recording queries reference__](#recording-queries-reference)  \n\t* [Generic actor data](#generic-actor-data)  \n\t* [Generic simulation data](#generic-simulation-data)  \n\t* [Actor accelerations](#actor-accelerations)  \n\t* [Actor angular velocities](#actor-angular-velocities)  \n\t* [Actor controls](#actor-controls)  \n\t* [Actor transforms](#actor-transforms)  \n\t* [Actor velocities](#actor-velocities)  \n\t* [Scene lights](#scene-lights)  \n\t* [Traffic lights](#traffic-lights)  \n\t* [Vehicle lights](#vehicle-lights)  \n\n---\n## Structure of the module\n\nSimilarly 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.  \n\n*   __`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.  \n\t*   `host` *(string)* – IP address where a CARLA simulation is running. Default is `(127.0.0.1)`.  \n\t*   `port` *(int)* – TCP port where the CARLA simulation is running. Default are `2000` and `2001`.  \n\t*   `metrics` — Path to the metrics to be used.  \n\t*   `log` — Path to the `.log` file containing the recording (relative to the environment variable `SCENARIO_RUNNER_ROOT`).  \n\t*   `criteria` *(optional)* — Path to a JSON file with the criteria of the scenario.  \n\nThe rest of the elements that shape the module can be found in the `srunner/metrics` folder. These folder has been divided in three subfolders.\n\n* __`srunner/metrics/data`__ — Stores information about the scenarios. By default, it has six files, which are part of the examples metric.  \n\n* __`srunner/metrics/examples`__ — Contains some example metrics, and the metric containing the base class `BaseMetric` to create new metrics.  \n\t*   `basic_metric.py` – Contains the base class `BaseMetric`. All the metrics are inherited from it.  \n\t*   `criteria_filter.py` – Returns a JSON with the most important attributes of the criteria. \n\t*   `distance_between_vehicles.py` – Returns the distance betwen two vehicles. Useful to show how to query the recording.  \n\t*   `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..  \n\n* __`srunner/metrics/tools`__ — Contains two key scripts that allow to query the recording.  \n\t*   `metrics_parser.py` – Transforms the string provided by the recording to a dictionary.  \n\t*   `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.  \n\n---\n## How to use the metrics module\n\n### 1. Record a scenario\n\nThe 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.  \n\nUse 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`.  \n\n```sh\npython scenario_runner.py --scenario <scenario_name> --record <path/to/save/the/recorder/file>\n```\n\nBy 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`.  \n__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/).  \n__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.\n\n!!! Note\n    Only the JSON serializable attributes will be parsed, the rest will be ignored.\n\n 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`.  \n\n\n### 2. Define the metrics\n\nIt 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.  \n\n    class DistanceBetweenVehicles(BasicMetric):\n    \"\"\"\n    Metric class DistanceBetweenVehicles\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric. This is an example to show how to use the recorder,\n        accessed via the log.\n        \"\"\"\n\n        # Get the ID of the two vehicles\n        ego_id = log.get_ego_vehicle_id()\n        adv_id = log.get_actor_ids_with_role_name(\"scenario\")[0]  # Could have also used its type_id\n\n        dist_list = []\n        frames_list = []\n\n        # Get the frames both actors were alive\n        start_ego, end_ego = log.get_actor_alive_frames(ego_id)\n        start_adv, end_adv = log.get_actor_alive_frames(adv_id)\n        start = max(start_ego, start_adv)\n        end = min(end_ego, end_adv)\n\n        # Get the distance between the two\n        for i in range(start, end):\n\n            # Get the transforms\n            ego_location = log.get_actor_transform(ego_id, i).location\n            adv_location = log.get_actor_transform(adv_id, i).location\n\n            # Filter some points for a better graph\n            if adv_location.z < -10:\n                continue\n\n            dist_v = ego_location - adv_location\n            dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n            dist_list.append(dist)\n            frames_list.append(i)\n\n        # Use matplotlib to show the results\n        plt.plot(frames_list, dist_list)\n        plt.ylabel('Distance [m]')\n        plt.xlabel('Frame number')\n        plt.title('Distance between the ego vehicle and the adversary over time')\n        plt.show()\n\n__2.1. Name the metric__. First of all, as it was previously mentioned, all metrics are childs of the `BasicMetric` class.\n\n```py\n    class DistanceBetweenVehicles(BasicMetric):\n```\n\n__2.2. Name the main method__. A metric only requires one method in order to run, `_create_metric()`, which has three arguments.  \n\n*   __`town_map`__ — Instance of the [carla.Map()](https://carla.readthedocs.io/en/latest/python_api/#carlamap) where the scenario took place in.  \n*   __`log`__ — Instance to the `MetricsLog` class, with all the functions needed to access the recorder dictionary.  \n*   __`criteria`__ — A JSOn with the criteria dictionary. The file provided when recording a scenario that is later provided to the `metrics_manager.py`.  \n\n```py\n    def _create_metric(self, town_map, log, criteria):\n```\n\n__2.3. Implement the metric__. The code will vary depending on the metric itself.  \n\nThe 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. \n\n```py\n    # Get the ID of the two vehicles\n    ego_id = log.get_ego_vehicle_id()\n    adv_id = log.get_actor_ids_with_role_name(\"scenario\")[0]  # Could have also used its type_id\n```\n\nThe `id` are used to retrieve the frames where the vehicles were alive using `get_actor_alive_frames(actor_id)`. \n```py\n    # Get the frames both actors were alive\n    start_ego, end_ego = log.get_actor_alive_frames(ego_id)\n    start_adv, end_adv = log.get_actor_alive_frames(adv_id)\n    start = max(start_ego, start_adv)\n    end = min(end_ego, end_adv)\n```\n\nNow 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. \n\n```py\n    dist_list = []\n    frames_list = []\n\n...\n\n    # Get the distance between the two\n    for i in range(start, end):\n\n        # Get the transforms\n        ego_location = log.get_actor_transform(ego_id, i).location\n        adv_location = log.get_actor_transform(adv_id, i).location\n\n        # Filter some points for a better graph\n        if adv_location.z < -10:\n            continue\n\n        dist_v = ego_location - adv_location\n        dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n        dist_list.append(dist)\n```\n!!! Note\n    The vertical condition of the adversary is to only take into account the adversary when it is driving normally.\n\nLastly, use [matplotlib](https://matplotlib.org/) to define which should be the output of the metric when running `metrics_manager.py`.  \n\n```py\n        # Use matplotlib to show the results\n        plt.plot(frames_list, dist_list)\n        plt.ylabel('Distance [m]')\n        plt.xlabel('Frame number')\n        plt.title('Distance between the ego vehicle and the adversary over time')\n        plt.show()\n```\n\n### 3. Run the metrics manager\n\nFinally 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.  \n\n```sh\npython metrics_manager.py --metric srunner/metrics/examples/distance_between_vehicles.py --log srunner/metrics/data/DistanceBetweenVehicles.log\n```\n\n!!! Warning\n    A simulation must be running. Otherwise, the module will not be able to acces the map API.\n\n\nThis will create a new window with the results plotted. The script will not finish until the ouput window is closed.\n\n![metrics_plot](img/metrics_example.jpg)\n\n---\n## Recording queries reference\n\nWhen 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.  \n\n### Generic actor data\n\n- <a name=\"get_ego_vehicle_id\"></a>__<font color=\"#7fb800\">get_ego_vehicle_id</font>__(<font color=\"#00a6ed\">__self__</font>)  \nReturns the `id` of the ego vehicle.\n    - __Return —__ int\n\n- <a name=\"get_actor_ids_with_role_name\"></a>__<font color=\"#7fb800\">get_actor_ids_with_role_name</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__role_name__</font>)  \nReturns a list of actor `id` that match the given `role_name`.\n    - __Return —__ list\n    - __Parameters__\n        - `role_name` (_str_) — `role_name` of the actor.\n\n- <a name=\"get_actor_ids_with_type_id\"></a>__<font color=\"#7fb800\">get_actor_ids_with_type_id</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__type_id__</font>)  \nReturns a list of actor `id` that match the given `type_id`, according to fnmatch standard.\n    - __Return —__ list\n    - __Parameters__\n        - `type_id` (_str_) — `type_id` of the actor.\n\n- <a name=\"get_actor_attributes\"></a>__<font color=\"#7fb800\">get_actor_attributes</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>)  \nReturns a dictionary with all the attributes of an actor.\n    - __Return —__ dict\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n- <a name=\"get_actor_bounding_box\"></a>__<font color=\"#7fb800\">get_actor_bounding_box</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>)  \nReturns the bounding box of the specified actor.\n    - __Return —__ [carla.BoundingBox](https://carla.readthedocs.io/en/latest/python_api/#carlaboundingbox)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n- <a name=\"get_traffic_light_trigger_volume\"></a>__<font color=\"#7fb800\">get_traffic_light_trigger_volume</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>)  \nReturns the trigger volume of the specified traffic light.\n    - __Return —__ [carla.BoundingBox](https://carla.readthedocs.io/en/latest/python_api/#carlaboundingbox)\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n\n- <a name=\"get_actor_alive_frames\"></a>__<font color=\"#7fb800\">get_actor_alive_frames</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>)  \nReturns a tuple with the first and last frame an actor was alive. Note that frames start at 1, not 0.\n    - __Return —__ tuple\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n\n### Generic simulation data\n\n- <a name=\"get_collisions\"></a>__<font color=\"#7fb800\">get_collisions</font>__(<font color=\"#00a6ed\">__self__</font>,<font color=\"#00a6ed\">__actor_id__</font>)  \nReturns 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.\n    - __Return —__ list\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n- <a name=\"get_total_frame_count\"></a>__<font color=\"#7fb800\">get_total_frame_count</font>__(<font color=\"#00a6ed\">__self__</font>)  \nReturns an int with the total amount of frames the simulation lasted.\n    - __Return —__ int\n\n- <a name=\"get_elapsed_time\"></a>__<font color=\"#7fb800\">get_elapsed_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns a float with the elapsed time of a specific frame.\n    - __Return —__ float\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_delta_time\"></a>__<font color=\"#7fb800\">get_delta_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns an float with the delta time of a specific frame.\n    - __Return —__ float\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_platform_time\"></a>__<font color=\"#7fb800\">get_platform_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns a float with the platform time of a specific frame.\n    - __Return —__ float\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n\n### Actor accelerations\n\n- <a name=\"get_actor_acceleration\"></a>__<font color=\"#7fb800\">get_actor_acceleration</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the acceleration of the actor at a given frame. Returns <b>None</b> if the actor `id` doesn't exist, the actor has no acceleration, or the actor wasn't alive at that frame.\n    - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_accelerations\"></a>__<font color=\"#7fb800\">get_all_actor_accelerations</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the accelerations of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list(carla.Vector3D)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_accelerations_at_frame\"></a>__<font color=\"#7fb800\">get_actor_accelerations_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list(carla.Vector3D)\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n        - `actor_list` (_int_) — List of actor `id`.\n\n### Actor angular velocities\n\n- <a name=\"get_actor_angular_velocity\"></a>__<font color=\"#7fb800\">get_actor_angular_velocity</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the angular velocity of the actor at a given frame. Returns <b>None</b> if the actor id doesn't exist, the actor has no angular velocity, or the actor wasn't alive at that frame.\n    - __Return —__ carla.Vector3D\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_angular_velocities\"></a>__<font color=\"#7fb800\">get_all_actor_angular_velocities</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the angular velocities of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list(carla.Vector3D)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_angular_velocities_at_frame\"></a>__<font color=\"#7fb800\">get_actor_angular_velocities_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d))\n    - __Parameters__\n        - `frame` (_int_) — frame number.\n        - `actor_list` (_int_) — List of actor ids.\n\n### Actor controls\n\n- <a name=\"get_vehicle_control\"></a>__<font color=\"#7fb800\">get_vehicle_control</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the control of a vehicle at a given frame. The `manual_gear_shift` attribute will always be False.\n    - __Return —__ [carla.VehicleCotnrol](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclecontrol)\n    - __Parameters__\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_vehicle_physics_control\"></a>__<font color=\"#7fb800\">get_vehicle_physics_control</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the physics control of a vehicle at a given frame.\n    - __Return —__ [carla.VehiclePhysicsControl](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclephysicscontrol)\n    - __Parameters__\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_walker_speed\"></a>__<font color=\"#7fb800\">get_walker_speed</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__walker_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the speed of a walker at a given frame.\n    - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `walker_id` (_int_) — `id` of the walker.\n        - `frame` (_int_) — Frame number.\n\n\n### Actor transforms\n\n- <a name=\"get_actor_transform\"></a>__<font color=\"#7fb800\">get_actor_transform</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the transform of the actor at a given frame. Returns <b>None</b> if the actor id doesn't exist, the actor has no transform, or the actor wasn't alive at that frame.\n    - __Return —__ [carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_transforms\"></a>__<font color=\"#7fb800\">get_all_actor_transforms</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the transforms of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list([carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform))\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_transforms_at_frame\"></a>__<font color=\"#7fb800\">get_actor_transforms_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list([carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform))\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n        - `actor_list` (_int_) — List of actor `id`. \n\n### Actor velocities\n\n- <a name=\"get_actor_velocity\"></a>__<font color=\"#7fb800\">get_actor_velocity</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the velocity of the actor at a given frame. Returns <b>None</b> if the actor id doesn't exist, the actor has no velocity, or the actor wasn't alive at that frame.\n    - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_velocities\"></a>__<font color=\"#7fb800\">get_all_actor_velocities</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the velocities of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d))\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_velocities_at_frame\"></a>__<font color=\"#7fb800\">get_actor_velocities_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n        - `actor_list` (_int_) — List of actor `id`. \n\n### Scene lights\n\n- <a name=\"get_scene_light_state\"></a>__<font color=\"#7fb800\">get_scene_light_state</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__light__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns 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).\n    - __Return —__ carla.LightState\n    - __Parameters__\n        - `light_id` (_int_) — `id` of the scene light.\n        - `frame` (_int_) — Frame number.\n\n\n### Traffic lights\n\n- <a name=\"get_traffic_light_state\"></a>__<font color=\"#7fb800\">get_traffic_light_state</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the state of a traffic light at a given frame.\n    - __Return —__ [carla.TrafficLightState](https://carla.readthedocs.io/en/latest/python_api/#carlatrafficlightstate).\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"is_traffic_light_frozen\"></a>__<font color=\"#7fb800\">is_traffic_light_frozen</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns whether or not a traffic light is frozen at a given frame.\n    - __Return —__ bool\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_traffic_light_elapsed_time\"></a>__<font color=\"#7fb800\">get_traffic_light_elapsed_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the elapsed time of a traffic light at a given frame.\n    - __Return —__ float\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_traffic_light_state_time\"></a>__<font color=\"#7fb800\">get_traffic_light_state_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__state__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the maximum time of a specific state of a traffic light at a given frame.\n    - __Return —__ float\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `state` ([carla.TrafficLightState](https://carla.readthedocs.io/en/latest/python_api/#carlatrafficlightstate)) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n### Vehicle lights\n\n- <a name=\"get_vehicle_lights\"></a>__<font color=\"#7fb800\">get_vehicle_lights</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns a list with the active lights of a specific vehicle at a given frame.\n    - __Return —__ list([carla.VehicleLightState](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclelightstate))\n    - __Parameters__\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"is_vehicle_light_active\"></a>__<font color=\"#7fb800\">is_vehicle_light_active</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__light__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nChecks whether or not a given vehicle light is active for a vehicle at a specific frame.\n    - __Return —__ bool\n    - __Parameters__\n        - `light` ([carla.VehicleLightState](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclelightstate)) — The light state to be compared with the vehicle.\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/openscenario_support.md",
    "content": "## OpenSCENARIO Support\n\nThe scenario_runner provides support for the [OpenSCENARIO](http://www.openscenario.org/) 1.0 standard.\nThe current implementation covers initial support for maneuver Actions, Conditions, Stories and the Storyboard.\nIf you would like to use evaluation criteria for a scenario to evaluate pass/fail results, these can be implemented\nas StopTriggers (see below). However, not all features for these elements are yet available. If in doubt, please see the\nmodule documentation in srunner/tools/openscenario_parser.py\n\nAn example for a supported scenario based on OpenSCENARIO is available [here](https://github.com/carla-simulator/scenario_runner/blob/master/srunner/examples/FollowLeadingVehicle.xosc)\n\nIn 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).\n\n### Migrating OpenSCENARIO 0.9.x to 1.0\nThe 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.\nExample:\n\n```bash\nxsltproc -o newScenario.xosc migration0_9_1to1_0.xslt oldScenario.xosc\n```\n\n\n### Level of support\nIn the following the OpenSCENARIO attributes are listed with their current support status.\n\n#### General OpenSCENARIO setup\n\nThis covers all part that are defined outside the OpenSCENARIO Storyboard\n\n| Attribute                          | Support                            | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `FileHeader`                       | &#9989;                              | Use \"CARLA:\" at the beginning of the description to use the CARLA coordinate system.                                |\n| `CatalogLocations`<br>`ControllerCatalog`                                      | &#9989;                              | While the catalog is supported, the reference/usage may not work.                |\n| `CatalogLocations`<br>`EnvironmentCatalog`                                     | &#9989;                              |                                    |\n| `CatalogLocations`<br>`ManeuverCatalog`                                        | &#9989;                              |                                    |\n| `CatalogLocations`<br>`MiscObjectCatalog`                                      | &#9989;                              |                                    |\n| `CatalogLocations`<br>`PedestrianCatalog`                                      | &#9989;                              |                                    |\n| `CatalogLocations`<br>`RouteCatalog`                                           | &#9989;                              | While the catalog is supported, the reference/usage may not work.                |\n| `CatalogLocations`<br>`TrajectoryCatalog`                                      | &#9989;                              | While the catalog is supported, the reference/usage may not work.                |\n| `CatalogLocations`<br>`VehicleCatalog`                                         | &#9989;                              |                                    |\n| `ParameterDeclarations`            | &#9989;                              |                                    |\n| `RoadNetwork`<br>`LogicFile`                                                   | &#9989;                              | The CARLA level can be used directly (e.g. LogicFile=Town01). Also any OpenDRIVE path can be provided.              |\n| `RoadNetwork`<br>`SceneGraphFile`                                              | &#10060;                               | The provided information is not used.                                            |\n| `RoadNetwork`<br>`TafficSignals`                                               | &#10060;                               | The provided information is not used.                                            |\n| `Entities`<br>`EntitySelection`                                                | &#10060;                               | The provided information is not used.                                            |\n| `Entities` `ScenarioObject`<br>`CatalogReference`                               | &#9989;                              | The provided information is not used.                                            |\n| `Entities` `ScenarioObject`<br>`MiscObject`                                     | &#9989;                              | The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. BoundingBox entries are ignored.                   |\n| `Entities` `ScenarioObject`<br>`ObjectController`                               | &#10060;                               | The provided information is not used.                                            |\n| `Entities` `ScenarioObject`<br>`Pedestrian`                                     | &#9989;                              | The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. BoundingBox entries are ignored.                   |\n| `Entities` `ScenarioObject`<br>`Vehicle`                                        | &#9989;                              | 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. |\n\n<br>\n\n\n#### OpenSCENARIO Storyboard\n\n##### OpenSCENARIO Actions\n\nThe OpenSCENARIO Actions can be used for two different purposes. First, Actions can be used to\ndefine the initial behavior of something, e.g. a traffic participant. Therefore, Actions can be\nused within the OpenSCENARIO Init. In addition, Actions are also used within the OpenSCENARIO\nstory. In the following, the support status for both application areas is listed. If an action\ncontains of submodules, which are not listed, the support status applies to all submodules.\n\n###### GlobalAction\n\n\n\n| GlobalAction                          | Init  support                            | Story support                              | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `EntityAction`                | &#10060;                          | &#10060;                          |                               |\n| `EnvironmentAction`           | &#9989;                         | &#10060;                          |                               |\n| `ParameterAction`             | &#9989;                          | &#9989;                          |                               |\n| `InfrastructureAction` `TrafficSignalAction`<br>`TrafficAction`                                               | &#10060;                          | &#10060;                          |                               |\n| `InfrastructureAction` `TrafficSignalAction`<br>`TrafficSignalControllerAction`                               | &#10060;                          | &#10060;                          |                               |\n| `InfrastructureAction` `TrafficSignalAction`<br>`TrafficSignalStateAction`                                    | &#10060;                          | &#9989;                         | 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\") |\n\n<br>\n\n\n\n###### UserDefinedAction\n\n\n\n| UserDefinedAction                          | Init  support                            | Story support                              | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `CustomCommandAction`                       | &#10060;                                        | &#9989;                                       | This action is currently used to trigger the execution of an additional script. Example: type=\"python /path/to/script args\". |\n\n<br>\n\n\n###### PrivateAction\n\n\n| PrivateAction                          | Init  support                            | Story support                              | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `ActivateControllerAction`                          | &#10060;             | &#9989;            | Can be used to activate/deactive the CARLA autopilot.                                             |\n| `ControllerAction`                                  | &#9989;            | &#9989;            | AssignControllerAction is supported, but a Python module has to be provided for the controller implementation, and in OverrideControllerValueAction all values need to be `False`. |\n| `LateralAction`<br> `LaneChangeAction`             | &#10060;             | &#9989;            | Currently all lane changes have a linear dynamicShape, the dynamicDimension is defined as the distance and are relative to the actor itself (RelativeTargetLane).                  |\n| `LateralAction`<br>`LaneOffsetAction`             | &#10060;             | &#9989;             |  Currently all type of dynamicShapes are ignored and depend on the controller. This action might not work as intended if the offset is high enough to make the vehicle exit its lane  |\n| `LateralAction`<br> `LateralDistanceAction`        | &#10060;             | &#10060;             |                  |\n| `LongitudinalAction`<br> `LongitudinalDistanceAction`| &#10060;             | &#9989;              |`timeGap` attribute is not supported              |\n| `LongitudinalAction`<br> `SpeedAction`             | &#9989;            | &#9989;            |                  |\n| `SynchronizeAction`                                 | &#10060;             | &#10060;             |                  |\n| `TeleportAction`                                    | &#9989;            | &#9989;            |                  |\n| `VisibilityAction`                                  | &#10060;             | &#10060;             |                  |\n| `RoutingAction`<br> `AcquirePositionAction`        | &#10060;             | &#9989;            |                  |\n| `RoutingAction`<br> `AssignRouteAction`            | &#10060;             | &#9989;            | Route Options (shortest/fastest/etc) are supported. Shortests means direct path between A and B, all other will use the shortest path along the road network between A and B       |\n| `RoutingAction`<br> `FollowTrajectoryAction`       | &#10060;             | &#10060;             |                  |\n\n<br>\n\n\n\n##### OpenSCENARIO Conditions\n\nConditions in OpenSCENARIO can be defined either as ByEntityCondition or as ByValueCondition.\nBoth can be used for StartTrigger and StopTrigger conditions.\nThe following two tables list the support status for each.\n\n###### ByEntityCondition\n\n\n| EntityCondition                                | Support                                        | Notes                                          |\n| ---------------------------------------------- | ---------------------------------------------- | ---------------------------------------------- |\n| `AccelerationCondition`                        | &#9989;                                          |                                                |\n| `CollisionCondition`                           | &#9989;                                          |                                                |\n| `DistanceCondition`                            | &#9989;                                          | \\*freespace\\* attribute is still not supported |\n| `EndOfRoadCondition`                           | &#9989;                                          |                                                |\n| `OffroadCondition`                             | &#9989;                                          |                                                |\n| `ReachPositionCondition`                       | &#9989;                                          |                                                |\n| `RelativeDistanceCondition`                    | &#9989;                                          |                                                |\n| `RelativeSpeedCondition`                       | &#9989;                                          |                                                |\n| `SpeedCondition`                               | &#9989;                                          |                                                |\n| `StandStillCondition`                          | &#9989;                                          |                                                |\n| `TimeHeadwayCondition`                         | &#9989;                                          |                                                |\n| `TimeToCollisionCondition`                     | &#9989;                                          |                                                |\n| `TraveledDistanceCondition`                    | &#9989;                                          |                                                |\n\n<br>\n\n###### ByValueCondition\n\n\n| ValueCondition            | Support                   | Notes                     |\n| -------------------------------------------------------- | -------------------------------------------------------- | -------------------------------------------------------- |\n| `ParameterCondition`         | &#9989;                     | The level of support depends on the parameter. It is recommended to use other conditions if possible. Please also consider the note below.                                                  |\n| `SimulationTimeCondition`                                    | &#9989;                     |                           |\n| `StoryboardElementStateCondition`                            | &#9989;                     | startTransition, stopTransition, endTransition and completeState are currently supported.                  |\n| `TimeOfDayCondition`         | &#9989;                     |                           |\n| `TrafficSignalCondition`                                     | &#9989;                     | 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\") |\n| `TrafficSignalControllerCondition`                           | &#10060;                      |                           |\n| `UserDefinedValueCondition`                                  | &#10060;                      |                           |\n\n<br>\n\n!!! Note\n     In the OpenSCENARIO 1.0 standard, a definition of test / evaluation criteria is not\n     defined. For this purpose, you can re-use StopTrigger conditions with CARLA. The following\n     StopTrigger conditions for evaluation criteria are supported through ParameterConditions by\n     providing the criteria name for the condition:\n\n     * criteria_RunningStopTest\n     * criteria_RunningRedLightTest\n     * criteria_WrongLaneTest\n     * criteria_OnSideWalkTest\n     * criteria_KeepLaneTest\n     * criteria_CollisionTest\n     * criteria_DrivenDistanceTest\n\n\n##### OpenSCENARIO Positions\n\nThere are several ways of defining positions in OpenSCENARIO. In the following we list the\ncurrent support status for each definition format.\n\n| Position                          | Support                            | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `LanePosition`           | &#9989;                    |                          |\n| `RelativeLanePosition`   | &#9989;                    |                          |\n| `RelativeObjectPosition` | &#9989;                    |                          |\n| `RelativeRoadPosition`   | &#9989;                     |                          |\n| `RelativeWorldPosition`  | &#9989;                    |                          |\n| `RoadPosition`           | &#9989;                     |                          |\n| `RoutePosition`          | &#10060;                     |                          |\n| `WorldPosition`          | &#9989;                    |                          |\n\n<br>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/requirements.txt",
    "content": "mkdocs >= 1.0\nmarkdown-include\nmkdocs-redirects\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Docs/ros_agent.md",
    "content": "# ROS-based Challenge Agent\n\nInterfacing CARLA from ROS is normally done via [CARLA ROS Bridge](https://github.com/carla-simulator/ros-bridge).\nIn 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.\n \n# Requirements\n\n* `roscore` is expected to be running in the docker container. Please adapt your entrypoint.\n\n## Setup\n\nTo enable your stack within challenge mode, the following steps need to be taken:\n\n1. Define Sensor Setup\n2. Define Startup\n\n### Define Sensor Setup\n\nDerive from RosAgent and implement the sensors() method.\n\n    from srunner.autoagents.ros_agent import RosAgent\n\n    class MyRosAgent(RosAgent):\n\n        def sensors(self):\n            return [ <sensor-definition> ]\n\nAs an example for the sensor definition, see [HumanAgent.py](../srunner/autoagents/human_agent.py).\n\n\n### Define Startup\n\nThe startup of the stack is done within the shell script `$TEAM_CODE_ROOT/start.sh`.\nTherefore the environment variable `TEAM_CODE_ROOT` must be set.\n\nRosAgent takes care of executing and monitoring. The script shall remain running as long as the stack is active.\n\nExample for start.sh\n\n    #!/bin/bash -e\n    roslaunch $TEAM_CODE_ROOT/challenge.launch\n\n\n## Testing\n\nIn general, the challenge execution is headless. For diagnosis you're still able to use ros-tools like rviz or rqt. Additionally you\ncan 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).\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/Jenkinsfile",
    "content": "#!/usr/bin/env groovy\n\n\nString CARLA_HOST \nString CARLA_RELEASE\nString TEST_HOST\nString COMMIT\nString ECR_REPOSITORY = \"456841689987.dkr.ecr.eu-west-3.amazonaws.com/scenario_runner\"\nboolean CARLA_RUNNING = false\nboolean CONCURRENCY = true\n\n// V3 - include detection of concurrent builds\n\npipeline\n{\n    agent none\n\n    options\n    {\n        buildDiscarder(logRotator(numToKeepStr: '3', artifactNumToKeepStr: '3'))\n        skipDefaultCheckout()\n    }\n\n    stages\n    {\n        stage('setup')\n        {\n            agent { label \"master\" }\n            steps\n            {\n                checkout scm\n                script\n                {\n                    jenkinsLib = load(\"/home/jenkins/scenario_runner.groovy\")\n                    TEST_HOST = jenkinsLib.getUbuntuTestNodeHost()\n                    CARLA_HOST= sh(\n                        script: \"cat ./CARLA_VER | grep HOST | sed 's/HOST\\\\s*=\\\\s*//g'\",\n                        returnStdout: true).trim()\n                    CARLA_RELEASE = sh(\n                        script: \"cat ./CARLA_VER | grep RELEASE | sed 's/RELEASE\\\\s*=\\\\s*//g'\",\n                        returnStdout: true).trim()\n                    COMMIT = sh(returnStdout: true, script: \"git log -n 1 --pretty=format:'%h'\").trim()\n                }\n                println \"using CARLA version ${CARLA_RELEASE} from ${TEST_HOST}\"\n            }\n        }\n        stage('get concurrency status')\n        {\n            options\n            {\n                lock resource: 'ubuntu_gpu', skipIfLocked: true\n            }\n            agent { label \"master\" }\n            steps\n            {\n                script\n                {\n                    CONCURRENCY = false\n                    println \"no concurrent builds detected.\"\n                }\n            }\n        }\n        stage('act on concurrency')\n        {\n            agent { label \"master\" }\n            steps\n            {\n                script\n                {\n                    if ( CONCURRENCY == true )\n                    {\n                        println \"concurrent builds detected, prebuilding SR image.\"\n                        stage('prebuild SR docker image')\n                        {\n                            //checkout scm\n                            sh \"docker build -t jenkins/scenario_runner:${COMMIT} .\"\n                            sh \"docker tag jenkins/scenario_runner:${COMMIT} ${ECR_REPOSITORY}:${COMMIT}\"\n                            sh '$(aws ecr get-login | sed \\'s/ -e none//g\\' )' \n                            sh \"docker push ${ECR_REPOSITORY}\"\n\t\t\t    sh \"docker image rmi -f \\\"\\$(docker images -q ${ECR_REPOSITORY}:${COMMIT})\\\"\"\n                        }\n                    }\n                }\n            }\n        }\n        stage('lock ubuntu_gpu instance')\n        {\n            options\n            {\n                lock resource: \"ubuntu_gpu\"\n            }\n            stages\n            {\n                stage('start server')\n                {\n                        agent { label \"master\" }\n                        steps\n                        {\n                            script\n                            {\n                                jenkinsLib = load(\"/home/jenkins/scenario_runner.groovy\")\n                                jenkinsLib.StartUbuntuTestNode()\n                            }\n                        }\n                }\n                stage('deploy')\n                {\n                        parallel\n                        {\n                            stage('build SR docker image')\n                            {\n                                    agent { label \"master\" }\n                                    steps\n                                    {\n                                        script\n                                        {\n                                            if ( CONCURRENCY == false )\n                                            {\n                                                //checkout scm\n                                                sh \"docker build -t jenkins/scenario_runner:${COMMIT} .\"\n                                                sh \"docker tag jenkins/scenario_runner:${COMMIT} ${ECR_REPOSITORY}:${COMMIT}\"\n                                                sh '$(aws ecr get-login | sed \\'s/ -e none//g\\' )'\n                                                sh \"docker push ${ECR_REPOSITORY}\"\n\t\t\t\t\t\tsh \"docker image rmi -f \\\"\\$(docker images -q ${ECR_REPOSITORY}:${COMMIT})\\\"\"\n                                            }\n                                            else\n                                            {\n                                                println \"SR docker image already built due concurrency\"\n                                            }\n                                        }\n                                    }\n                            }\n                            stage('deploy CARLA')\n                            {\n                                    stages\n                                    {\n                                        stage('install CARLA')\n                                        {\n                                                agent { label \"secondary && ubuntu && gpu && sr\" }\n                                                steps\n                                                {\n                                                    println \"using CARLA version ${CARLA_RELEASE}\"\n                                                    sh \"wget -qO- ${CARLA_HOST}/${CARLA_RELEASE}.tar.gz | tar -xzv -C .\"\n                                                }\n                                        }\n                                    }\n                            }\n                        }\n                }\n                stage('run test')\n                {\n                    agent { label \"secondary && ubuntu && gpu && sr\" }\n                        steps\n                        {\n                            sh 'DISPLAY= ./CarlaUE4.sh -opengl -nosound > CarlaUE4.log&'\n                        sleep 10\n                            script\n                            {\n                                    sh '$(aws ecr get-login | sed \\'s/ -e none//g\\' )' \n                                    sh \"docker pull ${ECR_REPOSITORY}:${COMMIT}\"\n                                    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 \\\"\"\n                                    deleteDir()\n                            }\n                        }\n                }\n            }\n            post\n            {\n                always\n                {\n                        node('master')\n                        {\n                            script  \n                            {\n                                    jenkinsLib = load(\"/home/jenkins/scenario_runner.groovy\")\n                                    jenkinsLib.StopUbuntuTestNode()\n                                    echo 'test node stopped'\n                                    sh 'docker system prune --volumes -f'\n                            }\n                            deleteDir()\n                        }\n                }\n            }\n        }\n    }\n}\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/LICENSE",
    "content": "MIT License\n\nCopyright (c) 2018 CARLA\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/README.md",
    "content": "[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT)\n![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/carla-simulator/scenario_runner.svg)\n[![Build Status](https://travis-ci.com/carla-simulator/scenario_runner.svg?branch=master)](https://travis-ci.com/carla/scenario_runner)\n\nScenarioRunner for CARLA\n========================\nThis repository contains traffic scenario definition and an execution engine\nfor CARLA. It also allows the execution of a simulation of the CARLA Challenge.\nYou can use this system to prepare your agent for the CARLA Challenge.\n\nScenarios can be defined through a Python interface, and with the newest version\nthe scenario_runner also the upcoming [OpenSCENARIO](http://www.openscenario.org/) standard is supported.\n\n[![Scenario_Runner for CARLA](Docs/img/scenario_runner_video.png)](https://youtu.be/ChmF8IFagpo?t=68)\n\nGetting the ScenarioRunner\n---------------------------\n\nUse `git clone` or download the project from this page. Note that the master\nbranch contains the latest fixes and features, and may be required to use the latest features from CARLA.\n\nIt is important to also consider the release version that has to match the CARLA version.\n\n* [Version 0.9.13](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.13) and the 0.9.13 Branch: Compatible with [CARLA 0.9.13](https://github.com/carla-simulator/carla/releases/tag/0.9.13)\n* [Version 0.9.12](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.12) and the 0.9.12 Branch: Compatible with [CARLA 0.9.12](https://github.com/carla-simulator/carla/releases/tag/0.9.12)\n* [Version 0.9.11](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.11) and the 0.9.11 Branch: Compatible with [CARLA 0.9.11](https://github.com/carla-simulator/carla/releases/tag/0.9.11)\n* [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)\n* [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.\n* [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)\n* [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.\n* [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)\n* [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)\n* [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)\n\nTo 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)\n\nCurrently no build is required, as all code is in Python.\n\nUsing the ScenarioRunner\n------------------------\n\nPlease take a look at our [Getting started](Docs/getting_scenariorunner.md)\ndocumentation.\n\nChallenge Evaluation\n---------------------\n\nThe CARLA Challenge has moved to the [CARLA Autonomous Driving Leaderboard](https://leaderboard.carla.org/). Please see the [leaderboard repository](https://github.com/carla-simulator/leaderboard) and the [getting started guide](https://leaderboard.carla.org/get_started/) for more information.\n\nContributing\n------------\n\nPlease take a look at our [Contribution guidelines](https://carla.readthedocs.io/en/latest/#contributing).\n\nFAQ\n------\n\nIf you run into problems, check our\n[FAQ](http://carla.readthedocs.io/en/latest/faq/).\n\nLicense\n-------\n\nScenarioRunner specific code is distributed under MIT License.\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/manual_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n# Allows controlling a vehicle with a keyboard. For a simpler and more\n# documented example, please take a look at tutorial.py.\n\n\"\"\"\nWelcome to CARLA manual control.\n\nUse ARROWS or WASD keys for control.\n\n    W            : throttle\n    S            : brake\n    A/D          : steer left/right\n    Q            : toggle reverse\n    Space        : hand-brake\n    P            : toggle autopilot\n    M            : toggle manual transmission\n    ,/.          : gear up/down\n\n    L            : toggle next light type\n    SHIFT + L    : toggle high beam\n    Z/X          : toggle right/left blinker\n    I            : toggle interior light\n\n    TAB          : change camera position\n\n    R            : toggle recording images to disk\n\n    CTRL + R     : toggle recording of simulation (replacing any previous)\n    CTRL + P     : start replaying last recorded simulation\n    CTRL + +     : increments the start time of the replay by 1 second (+SHIFT = 10 seconds)\n    CTRL + -     : decrements the start time of the replay by 1 second (+SHIFT = 10 seconds)\n\n    F1           : toggle HUD\n    H/?          : toggle help\n    ESC          : quit\n\"\"\"\n\nfrom __future__ import print_function\n\n# ==============================================================================\n# -- imports -------------------------------------------------------------------\n# ==============================================================================\n\nimport carla\nfrom carla import ColorConverter as cc\n\nimport argparse\nimport os\nimport sys\nimport time\nimport collections\nimport datetime\nimport logging\nimport math\nimport weakref\n\ntry:\n    import pygame\n    from pygame.locals import K_ESCAPE\n    from pygame.locals import K_F1\n    from pygame.locals import KMOD_CTRL\n    from pygame.locals import KMOD_SHIFT\n    from pygame.locals import K_TAB\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_UP\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_w\n    from pygame.locals import K_a\n    from pygame.locals import K_s\n    from pygame.locals import K_d\n    from pygame.locals import K_q\n    from pygame.locals import K_m\n    from pygame.locals import K_COMMA\n    from pygame.locals import K_PERIOD\n    from pygame.locals import K_p\n    from pygame.locals import K_i\n    from pygame.locals import K_l\n    from pygame.locals import K_z\n    from pygame.locals import K_x\n    from pygame.locals import K_r\n    from pygame.locals import K_MINUS\n    from pygame.locals import K_EQUALS\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\ntry:\n    import numpy as np\nexcept ImportError:\n    raise RuntimeError('cannot import numpy, make sure numpy package is installed')\n\n\n# ==============================================================================\n# -- Global functions ----------------------------------------------------------\n# ==============================================================================\n\ndef get_actor_display_name(actor, truncate=250):\n    name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])\n    return (name[:truncate - 1] + u'\\u2026') if len(name) > truncate else name\n\n\n# ==============================================================================\n# -- World ---------------------------------------------------------------------\n# ==============================================================================\n\nclass World(object):\n\n    def __init__(self, carla_world, hud, args):\n        self.world = carla_world\n        try:\n            self.map = self.world.get_map()\n        except RuntimeError as error:\n            print('RuntimeError: {}'.format(error))\n            print('  The server could not send the OpenDRIVE (.xodr) file:')\n            print('  Make sure it exists, has the same name of your town, and is correct.')\n            sys.exit(1)\n        self.hud = hud\n        self.player = None\n        self.collision_sensor = None\n        self.lane_invasion_sensor = None\n        self.gnss_sensor = None\n        self.imu_sensor = None\n        self.radar_sensor = None\n        self.camera_manager = None\n        self.restart()\n        self.world.on_tick(hud.on_world_tick)\n        self.recording_enabled = False\n        self.recording_start = 0\n\n    def restart(self):\n\n        self.player_max_speed = 1.589\n        self.player_max_speed_fast = 3.713\n\n        # Keep same camera config if the camera manager exists.\n        cam_index = self.camera_manager.index if self.camera_manager is not None else 0\n        cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0\n\n        # Get the ego vehicle\n        while self.player is None:\n            print(\"Waiting for the ego vehicle...\")\n            time.sleep(1)\n            possible_vehicles = self.world.get_actors().filter('vehicle.*')\n            for vehicle in possible_vehicles:\n                if vehicle.attributes['role_name'] == 'hero':\n                    print(\"Ego vehicle found\")\n                    self.player = vehicle\n                    break\n\n        self.player_name = self.player.type_id\n\n        # Set up the sensors.\n        self.collision_sensor = CollisionSensor(self.player, self.hud)\n        self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)\n        self.gnss_sensor = GnssSensor(self.player)\n        self.imu_sensor = IMUSensor(self.player)\n        self.camera_manager = CameraManager(self.player, self.hud)\n        self.camera_manager.transform_index = cam_pos_index\n        self.camera_manager.set_sensor(cam_index, notify=False)\n        actor_type = get_actor_display_name(self.player)\n        self.hud.notification(actor_type)\n\n        self.world.wait_for_tick()\n\n    def tick(self, clock, wait_for_repetitions):\n        if len(self.world.get_actors().filter(self.player_name)) < 1:\n            if not wait_for_repetitions:\n                return False\n            else:\n                self.player = None\n                self.destroy()\n                self.restart()\n\n        self.hud.tick(self, clock)\n        return True\n\n    def render(self, display):\n        self.camera_manager.render(display)\n        self.hud.render(display)\n\n    def destroy_sensors(self):\n        self.camera_manager.sensor.destroy()\n        self.camera_manager.sensor = None\n        self.camera_manager.index = None\n\n    def destroy(self):\n        sensors = [\n            self.camera_manager.sensor,\n            self.collision_sensor.sensor,\n            self.lane_invasion_sensor.sensor,\n            self.gnss_sensor.sensor,\n            self.imu_sensor.sensor]\n        for sensor in sensors:\n            if sensor is not None:\n                sensor.stop()\n                sensor.destroy()\n        if self.player is not None:\n            self.player.destroy()\n\n\n# ==============================================================================\n# -- KeyboardControl -----------------------------------------------------------\n# ==============================================================================\n\n\nclass KeyboardControl(object):\n    \"\"\"Class that handles keyboard input.\"\"\"\n    def __init__(self, world, start_in_autopilot):\n        self._autopilot_enabled = start_in_autopilot\n        self._control = carla.VehicleControl()\n        self._lights = carla.VehicleLightState.NONE\n        self._steer_cache = 0.0\n        world.player.set_autopilot(self._autopilot_enabled)\n        world.player.set_light_state(self._lights)\n        world.hud.notification(\"Press 'H' or '?' for help.\", seconds=4.0)\n\n    def parse_events(self, client, world, clock):\n        current_lights = self._lights\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                return True\n            elif event.type == pygame.KEYUP:\n                if self._is_quit_shortcut(event.key):\n                    return True\n                elif event.key == K_F1:\n                    world.hud.toggle_info()\n                elif event.key == K_TAB:\n                    world.camera_manager.toggle_camera()\n                elif event.key == K_r and not (pygame.key.get_mods() & KMOD_CTRL):\n                    world.camera_manager.toggle_recording()\n                elif event.key == K_r and (pygame.key.get_mods() & KMOD_CTRL):\n                    if (world.recording_enabled):\n                        client.stop_recorder()\n                        world.recording_enabled = False\n                        world.hud.notification(\"Recorder is OFF\")\n                    else:\n                        client.start_recorder(\"manual_recording.rec\")\n                        world.recording_enabled = True\n                        world.hud.notification(\"Recorder is ON\")\n                elif event.key == K_p and (pygame.key.get_mods() & KMOD_CTRL):\n                    # stop recorder\n                    client.stop_recorder()\n                    world.recording_enabled = False\n                    # work around to fix camera at start of replaying\n                    current_index = world.camera_manager.index\n                    world.destroy_sensors()\n                    # disable autopilot\n                    self._autopilot_enabled = False\n                    world.player.set_autopilot(self._autopilot_enabled)\n                    world.hud.notification(\"Replaying file 'manual_recording.rec'\")\n                    # replayer\n                    client.replay_file(\"manual_recording.rec\", world.recording_start, 0, 0)\n                    world.camera_manager.set_sensor(current_index)\n                elif event.key == K_MINUS and (pygame.key.get_mods() & KMOD_CTRL):\n                    if pygame.key.get_mods() & KMOD_SHIFT:\n                        world.recording_start -= 10\n                    else:\n                        world.recording_start -= 1\n                    world.hud.notification(\"Recording start time is %d\" % (world.recording_start))\n                elif event.key == K_EQUALS and (pygame.key.get_mods() & KMOD_CTRL):\n                    if pygame.key.get_mods() & KMOD_SHIFT:\n                        world.recording_start += 10\n                    else:\n                        world.recording_start += 1\n                    world.hud.notification(\"Recording start time is %d\" % (world.recording_start))\n                elif event.key == K_q:\n                    self._control.gear = 1 if self._control.reverse else -1\n                elif event.key == K_m:\n                    self._control.manual_gear_shift = not self._control.manual_gear_shift\n                    self._control.gear = world.player.get_control().gear\n                    world.hud.notification('%s Transmission' %\n                                            ('Manual' if self._control.manual_gear_shift else 'Automatic'))\n                elif self._control.manual_gear_shift and event.key == K_COMMA:\n                    self._control.gear = max(-1, self._control.gear - 1)\n                elif self._control.manual_gear_shift and event.key == K_PERIOD:\n                    self._control.gear = self._control.gear + 1\n                elif event.key == K_p and not pygame.key.get_mods() & KMOD_CTRL:\n                    self._autopilot_enabled = not self._autopilot_enabled\n                    world.player.set_autopilot(self._autopilot_enabled)\n                    world.hud.notification(\n                        'Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))\n                elif event.key == K_l and pygame.key.get_mods() & KMOD_CTRL:\n                    current_lights ^= carla.VehicleLightState.Special1\n                elif event.key == K_l and pygame.key.get_mods() & KMOD_SHIFT:\n                    current_lights ^= carla.VehicleLightState.HighBeam\n                elif event.key == K_l:\n                    # Use 'L' key to switch between lights:\n                    # closed -> position -> low beam -> fog\n                    if not self._lights & carla.VehicleLightState.Position:\n                        world.hud.notification(\"Position lights\")\n                        current_lights |= carla.VehicleLightState.Position\n                    else:\n                        world.hud.notification(\"Low beam lights\")\n                        current_lights |= carla.VehicleLightState.LowBeam\n                    if self._lights & carla.VehicleLightState.LowBeam:\n                        world.hud.notification(\"Fog lights\")\n                        current_lights |= carla.VehicleLightState.Fog\n                    if self._lights & carla.VehicleLightState.Fog:\n                        world.hud.notification(\"Lights off\")\n                        current_lights ^= carla.VehicleLightState.Position\n                        current_lights ^= carla.VehicleLightState.LowBeam\n                        current_lights ^= carla.VehicleLightState.Fog\n                elif event.key == K_i:\n                    current_lights ^= carla.VehicleLightState.Interior\n                elif event.key == K_z:\n                    current_lights ^= carla.VehicleLightState.LeftBlinker\n                elif event.key == K_x:\n                    current_lights ^= carla.VehicleLightState.RightBlinker\n\n        if not self._autopilot_enabled:\n            self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time())\n            self._control.reverse = self._control.gear < 0\n            # Set automatic control-related vehicle lights\n            if self._control.brake:\n                current_lights |= carla.VehicleLightState.Brake\n            else: # Remove the Brake flag\n                current_lights &= ~carla.VehicleLightState.Brake\n            if self._control.reverse:\n                current_lights |= carla.VehicleLightState.Reverse\n            else: # Remove the Reverse flag\n                current_lights &= ~carla.VehicleLightState.Reverse\n            if current_lights != self._lights: # Change the light state only if necessary\n                self._lights = current_lights\n                world.player.set_light_state(carla.VehicleLightState(self._lights))\n            world.player.apply_control(self._control)\n\n    def _parse_vehicle_keys(self, keys, milliseconds):\n        if keys[K_UP] or keys[K_w]:\n            self._control.throttle = min(self._control.throttle + 0.1, 1.00)\n        else:\n            self._control.throttle = 0.0\n\n        if keys[K_DOWN] or keys[K_s]:\n            self._control.brake = min(self._control.brake + 0.2, 1)\n        else:\n            self._control.brake = 0\n\n        steer_increment = 5e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            if self._steer_cache > 0:\n                self._steer_cache = 0\n            else:\n                self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            if self._steer_cache < 0:\n                self._steer_cache = 0\n            else:\n                self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n        self._steer_cache = min(0.7, max(-0.7, self._steer_cache))\n        self._control.steer = round(self._steer_cache, 1)\n        self._control.hand_brake = keys[K_SPACE]\n\n    @staticmethod\n    def _is_quit_shortcut(key):\n        return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)\n\n\n# ==============================================================================\n# -- HUD -----------------------------------------------------------------------\n# ==============================================================================\n\n\nclass HUD(object):\n    def __init__(self, width, height):\n        self.dim = (width, height)\n        font = pygame.font.Font(pygame.font.get_default_font(), 20)\n        font_name = 'courier' if os.name == 'nt' else 'mono'\n        fonts = [x for x in pygame.font.get_fonts() if font_name in x]\n        default_font = 'ubuntumono'\n        mono = default_font if default_font in fonts else fonts[0]\n        mono = pygame.font.match_font(mono)\n        self._font_mono = pygame.font.Font(mono, 12 if os.name == 'nt' else 14)\n        self._notifications = FadingText(font, (width, 40), (0, height - 40))\n        self.help = HelpText(pygame.font.Font(mono, 16), width, height)\n        self.server_fps = 0\n        self.frame = 0\n        self.simulation_time = 0\n        self._show_info = True\n        self._info_text = []\n        self._server_clock = pygame.time.Clock()\n\n    def on_world_tick(self, timestamp):\n        self._server_clock.tick()\n        self.server_fps = self._server_clock.get_fps()\n        self.frame = timestamp.frame\n        self.simulation_time = timestamp.elapsed_seconds\n\n    def tick(self, world, clock):\n        self._notifications.tick(world, clock)\n        if not self._show_info:\n            return\n        t = world.player.get_transform()\n        v = world.player.get_velocity()\n        c = world.player.get_control()\n        compass = world.imu_sensor.compass\n        heading = 'N' if compass > 270.5 or compass < 89.5 else ''\n        heading += 'S' if 90.5 < compass < 269.5 else ''\n        heading += 'E' if 0.5 < compass < 179.5 else ''\n        heading += 'W' if 180.5 < compass < 359.5 else ''\n        colhist = world.collision_sensor.get_collision_history()\n        collision = [colhist[x + self.frame - 200] for x in range(0, 200)]\n        max_col = max(1.0, max(collision))\n        collision = [x / max_col for x in collision]\n        vehicles = world.world.get_actors().filter('vehicle.*')\n        self._info_text = [\n            'Server:  % 16.0f FPS' % self.server_fps,\n            'Client:  % 16.0f FPS' % clock.get_fps(),\n            '',\n            'Vehicle: % 20s' % get_actor_display_name(world.player, truncate=20),\n            'Map:     % 20s' % world.map.name.split('/')[-1],\n            'Simulation time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),\n            '',\n            'Speed:   % 15.0f km/h' % (3.6 * math.sqrt(v.x**2 + v.y**2 + v.z**2)),\n            u'Compass:% 17.0f\\N{DEGREE SIGN} % 2s' % (compass, heading),\n            'Accelero: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.accelerometer),\n            'Gyroscop: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.gyroscope),\n            'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (t.location.x, t.location.y)),\n            'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (world.gnss_sensor.lat, world.gnss_sensor.lon)),\n            'Height:  % 18.0f m' % t.location.z,\n            '']\n        self._info_text += [\n            ('Throttle:', c.throttle, 0.0, 1.0),\n            ('Steer:', c.steer, -1.0, 1.0),\n            ('Brake:', c.brake, 0.0, 1.0),\n            ('Reverse:', c.reverse),\n            ('Hand brake:', c.hand_brake),\n            ('Manual:', c.manual_gear_shift),\n            'Gear:        %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear)]\n        self._info_text += [\n            '',\n            'Collision:',\n            collision,\n            '',\n            'Number of vehicles: % 8d' % len(vehicles)]\n        if len(vehicles) > 1:\n            self._info_text += ['Nearby vehicles:']\n            distance = lambda l: math.sqrt((l.x - t.location.x)**2 + (l.y - t.location.y)**2 + (l.z - t.location.z)**2)\n            vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.player.id]\n            for d, vehicle in sorted(vehicles, key=lambda vehicles: vehicles[0]):\n                if d > 200.0:\n                    break\n                vehicle_type = get_actor_display_name(vehicle, truncate=22)\n                self._info_text.append('% 4dm %s' % (d, vehicle_type))\n\n    def toggle_info(self):\n        self._show_info = not self._show_info\n\n    def notification(self, text, seconds=2.0):\n        self._notifications.set_text(text, seconds=seconds)\n\n    def error(self, text):\n        self._notifications.set_text('Error: %s' % text, (255, 0, 0))\n\n    def render(self, display):\n        if self._show_info:\n            info_surface = pygame.Surface((220, self.dim[1]))\n            info_surface.set_alpha(100)\n            display.blit(info_surface, (0, 0))\n            v_offset = 4\n            bar_h_offset = 100\n            bar_width = 106\n            for item in self._info_text:\n                if v_offset + 18 > self.dim[1]:\n                    break\n                if isinstance(item, list):\n                    if len(item) > 1:\n                        points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)]\n                        pygame.draw.lines(display, (255, 136, 0), False, points, 2)\n                    item = None\n                    v_offset += 18\n                elif isinstance(item, tuple):\n                    if isinstance(item[1], bool):\n                        rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6))\n                        pygame.draw.rect(display, (255, 255, 255), rect, 0 if item[1] else 1)\n                    else:\n                        rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6))\n                        pygame.draw.rect(display, (255, 255, 255), rect_border, 1)\n                        f = (item[1] - item[2]) / (item[3] - item[2])\n                        if item[2] < 0.0:\n                            rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6))\n                        else:\n                            rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))\n                        pygame.draw.rect(display, (255, 255, 255), rect)\n                    item = item[0]\n                if item:  # At this point has to be a str.\n                    surface = self._font_mono.render(item, True, (255, 255, 255))\n                    display.blit(surface, (8, v_offset))\n                v_offset += 18\n        self._notifications.render(display)\n        self.help.render(display)\n\n\n# ==============================================================================\n# -- FadingText ----------------------------------------------------------------\n# ==============================================================================\n\n\nclass FadingText(object):\n    def __init__(self, font, dim, pos):\n        self.font = font\n        self.dim = dim\n        self.pos = pos\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n\n    def set_text(self, text, color=(255, 255, 255), seconds=2.0):\n        text_texture = self.font.render(text, True, color)\n        self.surface = pygame.Surface(self.dim)\n        self.seconds_left = seconds\n        self.surface.fill((0, 0, 0, 0))\n        self.surface.blit(text_texture, (10, 11))\n\n    def tick(self, _, clock):\n        delta_seconds = 1e-3 * clock.get_time()\n        self.seconds_left = max(0.0, self.seconds_left - delta_seconds)\n        self.surface.set_alpha(500.0 * self.seconds_left)\n\n    def render(self, display):\n        display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- HelpText ------------------------------------------------------------------\n# ==============================================================================\n\n\nclass HelpText(object):\n    \"\"\"Helper class to handle text output using pygame\"\"\"\n    def __init__(self, font, width, height):\n        lines = __doc__.split('\\n')\n        self.font = font\n        self.line_space = 18\n        self.dim = (780, len(lines) * self.line_space + 12)\n        self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n        self.surface.fill((0, 0, 0, 0))\n        for n, line in enumerate(lines):\n            text_texture = self.font.render(line, True, (255, 255, 255))\n            self.surface.blit(text_texture, (22, n * self.line_space))\n            self._render = False\n        self.surface.set_alpha(220)\n\n    def toggle(self):\n        self._render = not self._render\n\n    def render(self, display):\n        if self._render:\n            display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- CollisionSensor -----------------------------------------------------------\n# ==============================================================================\n\n\nclass CollisionSensor(object):\n    def __init__(self, parent_actor, hud):\n        self.sensor = None\n        self.history = []\n        self._parent = parent_actor\n        self.hud = hud\n        world = self._parent.get_world()\n        bp = world.get_blueprint_library().find('sensor.other.collision')\n        self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)\n        # We need to pass the lambda a weak reference to self to avoid circular\n        # reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(lambda event: CollisionSensor._on_collision(weak_self, event))\n\n    def get_collision_history(self):\n        history = collections.defaultdict(int)\n        for frame, intensity in self.history:\n            history[frame] += intensity\n        return history\n\n    @staticmethod\n    def _on_collision(weak_self, event):\n        self = weak_self()\n        if not self:\n            return\n        actor_type = get_actor_display_name(event.other_actor)\n        self.hud.notification('Collision with %r' % actor_type)\n        impulse = event.normal_impulse\n        intensity = math.sqrt(impulse.x**2 + impulse.y**2 + impulse.z**2)\n        self.history.append((event.frame, intensity))\n        if len(self.history) > 4000:\n            self.history.pop(0)\n\n\n# ==============================================================================\n# -- LaneInvasionSensor --------------------------------------------------------\n# ==============================================================================\n\n\nclass LaneInvasionSensor(object):\n    def __init__(self, parent_actor, hud):\n        self.sensor = None\n\n        # If the spawn object is not a vehicle, we cannot use the Lane Invasion Sensor\n        if parent_actor.type_id.startswith(\"vehicle.\"):\n            self._parent = parent_actor\n            self.hud = hud\n            world = self._parent.get_world()\n            bp = world.get_blueprint_library().find('sensor.other.lane_invasion')\n            self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)\n            # We need to pass the lambda a weak reference to self to avoid circular\n            # reference.\n            weak_self = weakref.ref(self)\n            self.sensor.listen(lambda event: LaneInvasionSensor._on_invasion(weak_self, event))\n\n    @staticmethod\n    def _on_invasion(weak_self, event):\n        self = weak_self()\n        if not self:\n            return\n        lane_types = set(x.type for x in event.crossed_lane_markings)\n        text = ['%r' % str(x).split()[-1] for x in lane_types]\n        self.hud.notification('Crossed line %s' % ' and '.join(text))\n\n\n# ==============================================================================\n# -- GnssSensor ----------------------------------------------------------------\n# ==============================================================================\n\n\nclass GnssSensor(object):\n    def __init__(self, parent_actor):\n        self.sensor = None\n        self._parent = parent_actor\n        self.lat = 0.0\n        self.lon = 0.0\n        world = self._parent.get_world()\n        bp = world.get_blueprint_library().find('sensor.other.gnss')\n        self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)), attach_to=self._parent)\n        # We need to pass the lambda a weak reference to self to avoid circular\n        # reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(lambda event: GnssSensor._on_gnss_event(weak_self, event))\n\n    @staticmethod\n    def _on_gnss_event(weak_self, event):\n        self = weak_self()\n        if not self:\n            return\n        self.lat = event.latitude\n        self.lon = event.longitude\n\n\n# ==============================================================================\n# -- IMUSensor -----------------------------------------------------------------\n# ==============================================================================\n\n\nclass IMUSensor(object):\n    def __init__(self, parent_actor):\n        self.sensor = None\n        self._parent = parent_actor\n        self.accelerometer = (0.0, 0.0, 0.0)\n        self.gyroscope = (0.0, 0.0, 0.0)\n        self.compass = 0.0\n        world = self._parent.get_world()\n        bp = world.get_blueprint_library().find('sensor.other.imu')\n        self.sensor = world.spawn_actor(\n            bp, carla.Transform(), attach_to=self._parent)\n        # We need to pass the lambda a weak reference to self to avoid circular\n        # reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(\n            lambda sensor_data: IMUSensor._IMU_callback(weak_self, sensor_data))\n\n    @staticmethod\n    def _IMU_callback(weak_self, sensor_data):\n        self = weak_self()\n        if not self:\n            return\n        limits = (-99.9, 99.9)\n        self.accelerometer = (\n            max(limits[0], min(limits[1], sensor_data.accelerometer.x)),\n            max(limits[0], min(limits[1], sensor_data.accelerometer.y)),\n            max(limits[0], min(limits[1], sensor_data.accelerometer.z)))\n        self.gyroscope = (\n            max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.x))),\n            max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.y))),\n            max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.z))))\n        self.compass = math.degrees(sensor_data.compass)\n\n\n# ==============================================================================\n# -- RadarSensor ---------------------------------------------------------------\n# ==============================================================================\n\n\nclass RadarSensor(object):\n    def __init__(self, parent_actor):\n        self.sensor = None\n        self._parent = parent_actor\n        bound_x = 0.5 + self._parent.bounding_box.extent.x\n        bound_y = 0.5 + self._parent.bounding_box.extent.y\n        bound_z = 0.5 + self._parent.bounding_box.extent.z\n\n        self.velocity_range = 7.5 # m/s\n        world = self._parent.get_world()\n        self.debug = world.debug\n        bp = world.get_blueprint_library().find('sensor.other.radar')\n        bp.set_attribute('horizontal_fov', str(35))\n        bp.set_attribute('vertical_fov', str(20))\n        self.sensor = world.spawn_actor(\n            bp,\n            carla.Transform(\n                carla.Location(x=bound_x + 0.05, z=bound_z+0.05),\n                carla.Rotation(pitch=5)),\n            attach_to=self._parent)\n        # We need a weak reference to self to avoid circular reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(\n            lambda radar_data: RadarSensor._Radar_callback(weak_self, radar_data))\n\n    @staticmethod\n    def _Radar_callback(weak_self, radar_data):\n        self = weak_self()\n        if not self:\n            return\n        # To get a numpy [[vel, altitude, azimuth, depth],...[,,,]]:\n        # points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))\n        # points = np.reshape(points, (len(radar_data), 4))\n\n        current_rot = radar_data.transform.rotation\n        for detect in radar_data:\n            azi = math.degrees(detect.azimuth)\n            alt = math.degrees(detect.altitude)\n            # The 0.25 adjusts a bit the distance so the dots can\n            # be properly seen\n            fw_vec = carla.Vector3D(x=detect.depth - 0.25)\n            carla.Transform(\n                carla.Location(),\n                carla.Rotation(\n                    pitch=current_rot.pitch + alt,\n                    yaw=current_rot.yaw + azi,\n                    roll=current_rot.roll)).transform(fw_vec)\n\n            def clamp(min_v, max_v, value):\n                return max(min_v, min(value, max_v))\n\n            norm_velocity = detect.velocity / self.velocity_range # range [-1, 1]\n            r = int(clamp(0.0, 1.0, 1.0 - norm_velocity) * 255.0)\n            g = int(clamp(0.0, 1.0, 1.0 - abs(norm_velocity)) * 255.0)\n            b = int(abs(clamp(- 1.0, 0.0, - 1.0 - norm_velocity)) * 255.0)\n            self.debug.draw_point(\n                radar_data.transform.location + fw_vec,\n                size=0.075,\n                life_time=0.06,\n                persistent_lines=False,\n                color=carla.Color(r, g, b))\n\n# ==============================================================================\n# -- CameraManager -------------------------------------------------------------\n# ==============================================================================\n\n\nclass CameraManager(object):\n    def __init__(self, parent_actor, hud):\n        self.sensor = None\n        self.surface = None\n        self._parent = parent_actor\n        self.hud = hud\n        self.recording = False\n        bound_x = 0.5 + self._parent.bounding_box.extent.x\n        bound_y = 0.5 + self._parent.bounding_box.extent.y\n        bound_z = 0.5 + self._parent.bounding_box.extent.z\n        Attachment = carla.AttachmentType\n\n        self._camera_transforms = [\n            (carla.Transform(carla.Location(x=-2.0*bound_x, y=+0.0*bound_y, z=2.0*bound_z), carla.Rotation(pitch=8.0)), Attachment.SpringArm),\n            (carla.Transform(carla.Location(x=+0.8*bound_x, y=+0.0*bound_y, z=1.3*bound_z)), Attachment.Rigid),\n            (carla.Transform(carla.Location(x=+1.9*bound_x, y=+1.0*bound_y, z=1.2*bound_z)), Attachment.SpringArm),\n            (carla.Transform(carla.Location(x=-2.8*bound_x, y=+0.0*bound_y, z=4.6*bound_z), carla.Rotation(pitch=6.0)), Attachment.SpringArm),\n            (carla.Transform(carla.Location(x=-1.0, y=-1.0*bound_y, z=0.4*bound_z)), Attachment.Rigid)]\n\n        self.transform_index = 1\n        self.sensors = [['sensor.camera.rgb', cc.Raw, 'Camera RGB']]\n        world = self._parent.get_world()\n        bp_library = world.get_blueprint_library()\n        for item in self.sensors:\n            bp = bp_library.find(item[0])\n            bp.set_attribute('image_size_x', str(hud.dim[0]))\n            bp.set_attribute('image_size_y', str(hud.dim[1]))\n            bp.set_attribute('gamma', '2.2')\n            item.append(bp)\n        self.index = None\n\n    def toggle_camera(self):\n        self.transform_index = (self.transform_index + 1) % len(self._camera_transforms)\n        self.set_sensor(self.index, notify=False, force_respawn=True)\n\n    def set_sensor(self, index, notify=True, force_respawn=False):\n        index = index % len(self.sensors)\n        needs_respawn = True if self.index is None else \\\n            (force_respawn or (self.sensors[index][2] != self.sensors[self.index][2]))\n        if needs_respawn:\n            if self.sensor is not None:\n                self.sensor.destroy()\n                self.surface = None\n            self.sensor = self._parent.get_world().spawn_actor(\n                self.sensors[index][-1],\n                self._camera_transforms[self.transform_index][0],\n                attach_to=self._parent,\n                attachment_type=self._camera_transforms[self.transform_index][1])\n            # We need to pass the lambda a weak reference to self to avoid\n            # circular reference.\n            weak_self = weakref.ref(self)\n            self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image))\n        if notify:\n            self.hud.notification(self.sensors[index][2])\n        self.index = index\n\n    def toggle_recording(self):\n        self.recording = not self.recording\n        self.hud.notification('Recording %s' % ('On' if self.recording else 'Off'))\n\n    def render(self, display):\n        if self.surface is not None:\n            display.blit(self.surface, (0, 0))\n\n    @staticmethod\n    def _parse_image(weak_self, image):\n        self = weak_self()\n        if not self:\n            return\n        if self.sensors[self.index][0].startswith('sensor.lidar'):\n            points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))\n            points = np.reshape(points, (int(points.shape[0] / 4), 4))\n            lidar_data = np.array(points[:, :2])\n            lidar_data *= min(self.hud.dim) / (2.0 * self.lidar_range)\n            lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1])\n            lidar_data = np.fabs(lidar_data)  # pylint: disable=E1111\n            lidar_data = lidar_data.astype(np.int32)\n            lidar_data = np.reshape(lidar_data, (-1, 2))\n            lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3)\n            lidar_img = np.zeros((lidar_img_size), dtype=np.uint8)\n            lidar_img[tuple(lidar_data.T)] = (255, 255, 255)\n            self.surface = pygame.surfarray.make_surface(lidar_img)\n        elif self.sensors[self.index][0].startswith('sensor.camera.dvs'):\n            # Example of converting the raw_data from a carla.DVSEventArray\n            # sensor into a NumPy array and using it as an image\n            dvs_events = np.frombuffer(image.raw_data, dtype=np.dtype([\n                ('x', np.uint16), ('y', np.uint16), ('t', np.int64), ('pol', np.bool)]))\n            dvs_img = np.zeros((image.height, image.width, 3), dtype=np.uint8)\n            # Blue is positive, red is negative\n            dvs_img[dvs_events[:]['y'], dvs_events[:]['x'], dvs_events[:]['pol'] * 2] = 255\n            self.surface = pygame.surfarray.make_surface(dvs_img.swapaxes(0, 1))\n        elif self.sensors[self.index][0].startswith('sensor.camera.optical_flow'):\n            image = image.get_color_coded_flow()\n            array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n            array = np.reshape(array, (image.height, image.width, 4))\n            array = array[:, :, :3]\n            array = array[:, :, ::-1]\n            self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))\n        else:\n            image.convert(self.sensors[self.index][1])\n            array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n            array = np.reshape(array, (image.height, image.width, 4))\n            array = array[:, :, :3]\n            array = array[:, :, ::-1]\n            self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))\n        if self.recording:\n            image.save_to_disk('_out/%08d' % image.frame)\n\n\n# ==============================================================================\n# -- game_loop() ---------------------------------------------------------------\n# ==============================================================================\n\ndef game_loop(args):\n    pygame.init()\n    pygame.font.init()\n    world = None\n\n    try:\n        client = carla.Client(args.host, args.port)\n        client.set_timeout(20.0)\n        sim_world = client.get_world()\n\n        display = pygame.display.set_mode(\n            (args.width, args.height),\n            pygame.HWSURFACE | pygame.DOUBLEBUF)\n        display.fill((0,0,0))\n        pygame.display.flip()\n\n        hud = HUD(args.width, args.height)\n        world = World(sim_world, hud, args)\n        controller = KeyboardControl(world, args.autopilot)\n\n        sim_world.wait_for_tick()\n\n        clock = pygame.time.Clock()\n        while True:\n            clock.tick_busy_loop(60)\n            if controller.parse_events(client, world, clock):\n                return\n            if not world.tick(clock, args.wait_for_repetitions):\n                return\n            world.render(display)\n            pygame.display.flip()\n\n    finally:\n\n        if (world and world.recording_enabled):\n            client.stop_recorder()\n\n        if world is not None:\n            # prevent destruction of ego vehicle\n            if args.keep_ego_vehicle:\n                world.player = None\n            world.destroy()\n\n        pygame.quit()\n\n\n# ==============================================================================\n# -- main() --------------------------------------------------------------------\n# ==============================================================================\n\n\ndef main():\n    argparser = argparse.ArgumentParser(\n        description='CARLA Manual Control Client')\n    argparser.add_argument(\n        '-v', '--verbose',\n        action='store_true',\n        dest='debug',\n        help='print debug information')\n    argparser.add_argument(\n        '--host',\n        metavar='H',\n        default='127.0.0.1',\n        help='IP of the host server (default: 127.0.0.1)')\n    argparser.add_argument(\n        '-p', '--port',\n        metavar='P',\n        default=2000,\n        type=int,\n        help='TCP port to listen to (default: 2000)')\n    argparser.add_argument(\n        '-a', '--autopilot',\n        action='store_true',\n        help='enable autopilot. This does not autocomplete the scenario')\n    argparser.add_argument(\n        '--rolename',\n        metavar='NAME',\n        default='hero',\n        help='role name of ego vehicle to control (default: \"hero\")')\n    argparser.add_argument(\n        '--res',\n        metavar='WIDTHxHEIGHT',\n        default='1280x720',\n        help='window resolution (default: 1280x720)')\n    argparser.add_argument(\n        '--keep_ego_vehicle',\n        action='store_true',\n        help='do not destroy ego vehicle on exit')\n    argparser.add_argument(\n        '--wait-for-repetitions',\n        action='store_true',\n        help='Avoids stopping the manual control when the scenario ends.')\n    args = argparser.parse_args()\n\n    args.width, args.height = [int(x) for x in args.res.split('x')]\n\n    log_level = logging.DEBUG if args.debug else logging.INFO\n    logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)\n\n    logging.info('listening to server %s:%s', args.host, args.port)\n\n    print(__doc__)\n\n    try:\n\n        game_loop(args)\n\n    except KeyboardInterrupt:\n        print('\\nCancelled by user. Bye!')\n    except Exception as error:\n        logging.exception(error)\n\n\nif __name__ == '__main__':\n\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/metrics_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n# Allows the execution of user-implemented metrics\n\n\"\"\"\nWelcome to the ScenarioRunner's metric module\n\nThis is the main script to be executed when running a metric.\nIt is responsible of parsing all the information and executing\nthe metric specified by the user.\n\"\"\"\n\nimport os\nimport sys\nimport importlib\nimport inspect\nimport json\nimport argparse\nfrom argparse import RawTextHelpFormatter\n\nimport carla\nfrom srunner.metrics.tools.metrics_log import MetricsLog\n\n\nclass MetricsManager(object):\n    \"\"\"\n    Main class of the metrics module. Handles the parsing and execution of\n    the metrics.\n    \"\"\"\n\n    def __init__(self, args):\n        \"\"\"\n        Initialization of the metrics manager. This creates the client, needed to parse\n        the information from the recorder, extract the metrics class, and runs it\n        \"\"\"\n        self._args = args\n\n        # Parse the arguments\n        recorder_str = self._get_recorder(self._args.log)\n        criteria_dict = self._get_criteria(self._args.criteria)\n\n        # Get the correct world and load it\n        map_name = self._get_recorder_map(recorder_str)\n        world = self._client.load_world(map_name)\n        town_map = world.get_map()\n\n        # Instanciate the MetricsLog, used to querry the needed information\n        log = MetricsLog(recorder_str)\n\n        # Read and run the metric class\n        metric_class = self._get_metric_class(self._args.metric)\n        metric_class(town_map, log, criteria_dict)\n\n    def _get_recorder(self, log):\n        \"\"\"\n        Parses the log argument into readable information\n        \"\"\"\n\n        # Get the log information.\n        self._client = carla.Client(self._args.host, int(self._args.port))\n        recorder_file = \"{}/{}\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\"), log)\n\n        # Check that the file is correct\n        if recorder_file[-4:] != '.log':\n            print(\"ERROR: The log argument has to point to a .log file\")\n            sys.exit(-1)\n        if not os.path.exists(recorder_file):\n            print(\"ERROR: The specified log file does not exist\")\n            sys.exit(-1)\n\n        recorder_str = self._client.show_recorder_file_info(recorder_file, True)\n\n        return recorder_str\n\n    def _get_criteria(self, criteria_file):\n        \"\"\"\n        Parses the criteria argument into a dictionary\n        \"\"\"\n        if criteria_file:\n            with open(criteria_file) as fd:\n                criteria_dict = json.load(fd)\n        else:\n            criteria_dict = None\n\n        return criteria_dict\n\n    def _get_metric_class(self, metric_file):\n        \"\"\"\n        Function to extract the metrics class from the path given by the metrics\n        argument. Returns the first class found that is a child of BasicMetric\n\n        Args:\n            metric_file (str): path to the metric's file.\n        \"\"\"\n        # Get their module\n        module_name = os.path.basename(metric_file).split('.')[0]\n        sys.path.insert(0, os.path.dirname(metric_file))\n        metric_module = importlib.import_module(module_name)\n\n        # And their members of type class\n        for member in inspect.getmembers(metric_module, inspect.isclass):\n            # Get the first one with parent BasicMetrics\n            member_parent = member[1].__bases__[0]\n            if 'BasicMetric' in str(member_parent):\n                return member[1]\n\n        print(\"No child class of BasicMetric was found ... Exiting\")\n        sys.exit(-1)\n\n    def _get_recorder_map(self, recorder_str):\n        \"\"\"\n        Returns the name of the map the simulation took place in\n        \"\"\"\n\n        header = recorder_str.split(\"\\n\")\n        sim_map = header[1][5:]\n\n        return sim_map\n\n\ndef main():\n    \"\"\"\n    main function\n    \"\"\"\n\n    # pylint: disable=line-too-long\n    description = (\"Scenario Runner's metrics module. Evaluate the execution of a specific scenario by developing your own metric.\\n\")\n\n    parser = argparse.ArgumentParser(description=description,\n                                    formatter_class=RawTextHelpFormatter)\n    parser.add_argument('--host', default='127.0.0.1',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', '-p', default=2000,\n                        help='TCP port to listen to (default: 2000)')\n    parser.add_argument('--log', required=True,\n                        help='Path to the CARLA recorder .log file (relative to SCENARIO_RUNNER_ROOT).\\nThis file is created by the record functionality at ScenarioRunner')\n    parser.add_argument('--metric', required=True,\n                        help='Path to the .py file defining the used metric.\\nSome examples at srunner/metrics')\n    parser.add_argument('--criteria', default=\"\",\n                        help='Path to the .json file with the criteria information.\\nThis file is created by the record functionality at ScenarioRunner')\n    # pylint: enable=line-too-long\n\n    args = parser.parse_args()\n\n    MetricsManager(args)\n\nif __name__ == \"__main__\":\n    sys.exit(main())\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/mkdocs.yml",
    "content": "site_name: CARLA ScenarioRunner\nrepo_url: https://github.com/carla-simulator/scenario_runner\ndocs_dir: Docs\nedit_uri: 'edit/master/Docs/'\ntheme: readthedocs\nextra_css: [extra.css]\n\nnav:\n- Home: index.md\n- Quick start:\n  - Get ScenarioRunner: getting_scenariorunner.md\n  - First steps: getting_started.md\n  - Create a new scenario: creating_new_scenario.md\n  - Metrics module: metrics_module.md\n  - FAQ: FAQ.md\n  - Release Notes: CHANGELOG.md\n- References:\n  - List of scenarios: list_of_scenarios.md\n  - OpenSCENARIO support: openscenario_support.md\n- Contributing:\n  - Code of conduct: CODE_OF_CONDUCT.md\n  - Coding standard: coding_standard.md\n  - Contribution guidelines: CONTRIBUTING.md\n\nmarkdown_extensions:\n  - admonition\n  - markdown_include.include:\n      base_path: '.'\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/no_rendering_mode.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n# Allows visualising a 2D map generated by vehicles.\n\n\"\"\"\nWelcome to CARLA No-Rendering Mode Visualizer\n\n    TAB          : toggle hero mode\n    Mouse Wheel  : zoom in / zoom out\n    Mouse Drag   : move map (map mode only)\n\n    W            : throttle\n    S            : brake\n    AD           : steer\n    Q            : toggle reverse\n    Space        : hand-brake\n    P            : toggle autopilot\n    M            : toggle manual transmission\n    ,/.          : gear up/down\n\n    F1           : toggle HUD\n    I            : toggle actor ids\n    H/?          : toggle help\n    ESC          : quit\n\"\"\"\n\n# ==============================================================================\n# -- find carla module ---------------------------------------------------------\n# ==============================================================================\n\nimport glob\nimport os\nimport sys\n\ntry:\n    sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % (\n        sys.version_info.major,\n        sys.version_info.minor,\n        'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])\nexcept IndexError:\n    pass\n\n# ==============================================================================\n# -- imports -------------------------------------------------------------------\n# ==============================================================================\n\nimport carla\nfrom carla import TrafficLightState as tls\n\nimport argparse\nimport logging\nimport datetime\nimport weakref\nimport math\nimport random\n\ntry:\n    import pygame\n    from pygame.locals import KMOD_CTRL\n    from pygame.locals import KMOD_SHIFT\n    from pygame.locals import K_COMMA\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_ESCAPE\n    from pygame.locals import K_F1\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_PERIOD\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_SLASH\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_TAB\n    from pygame.locals import K_UP\n    from pygame.locals import K_a\n    from pygame.locals import K_d\n    from pygame.locals import K_h\n    from pygame.locals import K_i\n    from pygame.locals import K_m\n    from pygame.locals import K_p\n    from pygame.locals import K_q\n    from pygame.locals import K_s\n    from pygame.locals import K_w\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\n# ==============================================================================\n# -- Constants -----------------------------------------------------------------\n# ==============================================================================\n\n# Colors\n\n# We will use the color palette used in Tango Desktop Project (Each color is indexed depending on brightness level)\n# See: https://en.wikipedia.org/wiki/Tango_Desktop_Project\n\nCOLOR_BUTTER_0 = pygame.Color(252, 233, 79)\nCOLOR_BUTTER_1 = pygame.Color(237, 212, 0)\nCOLOR_BUTTER_2 = pygame.Color(196, 160, 0)\n\nCOLOR_ORANGE_0 = pygame.Color(252, 175, 62)\nCOLOR_ORANGE_1 = pygame.Color(245, 121, 0)\nCOLOR_ORANGE_2 = pygame.Color(209, 92, 0)\n\nCOLOR_CHOCOLATE_0 = pygame.Color(233, 185, 110)\nCOLOR_CHOCOLATE_1 = pygame.Color(193, 125, 17)\nCOLOR_CHOCOLATE_2 = pygame.Color(143, 89, 2)\n\nCOLOR_CHAMELEON_0 = pygame.Color(138, 226, 52)\nCOLOR_CHAMELEON_1 = pygame.Color(115, 210, 22)\nCOLOR_CHAMELEON_2 = pygame.Color(78, 154, 6)\n\nCOLOR_SKY_BLUE_0 = pygame.Color(114, 159, 207)\nCOLOR_SKY_BLUE_1 = pygame.Color(52, 101, 164)\nCOLOR_SKY_BLUE_2 = pygame.Color(32, 74, 135)\n\nCOLOR_PLUM_0 = pygame.Color(173, 127, 168)\nCOLOR_PLUM_1 = pygame.Color(117, 80, 123)\nCOLOR_PLUM_2 = pygame.Color(92, 53, 102)\n\nCOLOR_SCARLET_RED_0 = pygame.Color(239, 41, 41)\nCOLOR_SCARLET_RED_1 = pygame.Color(204, 0, 0)\nCOLOR_SCARLET_RED_2 = pygame.Color(164, 0, 0)\n\nCOLOR_ALUMINIUM_0 = pygame.Color(238, 238, 236)\nCOLOR_ALUMINIUM_1 = pygame.Color(211, 215, 207)\nCOLOR_ALUMINIUM_2 = pygame.Color(186, 189, 182)\nCOLOR_ALUMINIUM_3 = pygame.Color(136, 138, 133)\nCOLOR_ALUMINIUM_4 = pygame.Color(85, 87, 83)\nCOLOR_ALUMINIUM_4_5 = pygame.Color(66, 62, 64)\nCOLOR_ALUMINIUM_5 = pygame.Color(46, 52, 54)\n\n\nCOLOR_WHITE = pygame.Color(255, 255, 255)\nCOLOR_BLACK = pygame.Color(0, 0, 0)\n\n\n# Module Defines\nMODULE_WORLD = 'WORLD'\nMODULE_HUD = 'HUD'\nMODULE_INPUT = 'INPUT'\n\nPIXELS_PER_METER = 12\n\nMAP_DEFAULT_SCALE = 0.1\nHERO_DEFAULT_SCALE = 1.0\n\nPIXELS_AHEAD_VEHICLE = 150\n\n# ==============================================================================\n# -- Util -----------------------------------------------------------\n# ==============================================================================\n\n\ndef get_actor_display_name(actor, truncate=250):\n    name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])\n    return (name[:truncate - 1] + u'\\u2026') if len(name) > truncate else name\n\n\nclass Util(object):\n\n    @staticmethod\n    def blits(destination_surface, source_surfaces, rect=None, blend_mode=0):\n        for surface in source_surfaces:\n            destination_surface.blit(surface[0], surface[1], rect, blend_mode)\n\n    @staticmethod\n    def length(v):\n        return math.sqrt(v.x**2 + v.y**2 + v.z**2)\n\n    @staticmethod\n    def get_bounding_box(actor):\n        bb = actor.trigger_volume.extent\n        corners = [carla.Location(x=-bb.x, y=-bb.y),\n                   carla.Location(x=bb.x, y=-bb.y),\n                   carla.Location(x=bb.x, y=bb.y),\n                   carla.Location(x=-bb.x, y=bb.y),\n                   carla.Location(x=-bb.x, y=-bb.y)]\n        corners = [x + actor.trigger_volume.location for x in corners]\n        t = actor.get_transform()\n        t.transform(corners)\n        return corners\n\n# ==============================================================================\n# -- ModuleManager -------------------------------------------------------------\n# ==============================================================================\n\n\nclass ModuleManager(object):\n    def __init__(self):\n        self.modules = []\n\n    def register_module(self, module):\n        self.modules.append(module)\n\n    def clear_modules(self):\n        del self.modules[:]\n\n    def tick(self, clock):\n        # Update all the modules\n        for module in self.modules:\n            module.tick(clock)\n\n    def render(self, display):\n        display.fill(COLOR_ALUMINIUM_4)\n        for module in self.modules:\n            module.render(display)\n\n    def get_module(self, name):\n        for module in self.modules:\n            if module.name == name:\n                return module\n\n    def start_modules(self):\n        for module in self.modules:\n            module.start()\n\n\n# ==============================================================================\n# -- FadingText ----------------------------------------------------------------\n# ==============================================================================\n\n\nclass FadingText(object):\n    def __init__(self, font, dim, pos):\n        self.font = font\n        self.dim = dim\n        self.pos = pos\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n\n    def set_text(self, text, color=COLOR_WHITE, seconds=2.0):\n        text_texture = self.font.render(text, True, color)\n        self.surface = pygame.Surface(self.dim)\n        self.seconds_left = seconds\n        self.surface.fill(COLOR_BLACK)\n        self.surface.blit(text_texture, (10, 11))\n\n    def tick(self, clock):\n        delta_seconds = 1e-3 * clock.get_time()\n        self.seconds_left = max(0.0, self.seconds_left - delta_seconds)\n        self.surface.set_alpha(500.0 * self.seconds_left)\n\n    def render(self, display):\n        display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- HelpText ------------------------------------------------------------------\n# ==============================================================================\n\n\nclass HelpText(object):\n    def __init__(self, font, width, height):\n        lines = __doc__.split('\\n')\n        self.font = font\n        self.dim = (680, len(lines) * 22 + 12)\n        self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n        self.surface.fill(COLOR_BLACK)\n        for n, line in enumerate(lines):\n            text_texture = self.font.render(line, True, COLOR_WHITE)\n            self.surface.blit(text_texture, (22, n * 22))\n            self._render = False\n        self.surface.set_alpha(220)\n\n    def toggle(self):\n        self._render = not self._render\n\n    def render(self, display):\n        if self._render:\n            display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- ModuleHUD -----------------------------------------------------------------\n# ==============================================================================\n\n\nclass ModuleHUD (object):\n\n    def __init__(self, name, width, height):\n        self.name = name\n        self.dim = (width, height)\n        self._init_hud_params()\n        self._init_data_params()\n\n    def start(self):\n        pass\n\n    def _init_hud_params(self):\n        fonts = [x for x in pygame.font.get_fonts() if 'mono' in x]\n        default_font = 'ubuntumono'\n        mono = default_font if default_font in fonts else fonts[0]\n        mono = pygame.font.match_font(mono)\n        self._font_mono = pygame.font.Font(mono, 14)\n        self._header_font = pygame.font.SysFont('Arial', 14, True)\n        self.help = HelpText(pygame.font.Font(mono, 24), *self.dim)\n        self._notifications = FadingText(\n            pygame.font.Font(pygame.font.get_default_font(), 20),\n            (self.dim[0], 40), (0, self.dim[1] - 40))\n\n    def _init_data_params(self):\n        self.show_info = True\n        self.show_actor_ids = False\n        self._info_text = {}\n\n    def notification(self, text, seconds=2.0):\n        self._notifications.set_text(text, seconds=seconds)\n\n    def tick(self, clock):\n        self._notifications.tick(clock)\n\n    def add_info(self, module_name, info):\n        self._info_text[module_name] = info\n\n    def render_vehicles_ids(self, vehicle_id_surface, list_actors, world_to_pixel, hero_actor, hero_transform):\n        vehicle_id_surface.fill(COLOR_BLACK)\n        if self.show_actor_ids:\n            vehicle_id_surface.set_alpha(150)\n            for actor in list_actors:\n                x, y = world_to_pixel(actor[1].location)\n\n                angle = 0\n                if hero_actor is not None:\n                    angle = -hero_transform.rotation.yaw - 90\n\n                color = COLOR_SKY_BLUE_0\n                if int(actor[0].attributes['number_of_wheels']) == 2:\n                    color = COLOR_CHOCOLATE_0\n                if actor[0].attributes['role_name'] == 'hero':\n                    color = COLOR_CHAMELEON_0\n\n                font_surface = self._header_font.render(str(actor[0].id), True, color)\n                rotated_font_surface = pygame.transform.rotate(font_surface, angle)\n                rect = rotated_font_surface.get_rect(center=(x, y))\n                vehicle_id_surface.blit(rotated_font_surface, rect)\n\n        return vehicle_id_surface\n\n    def render(self, display):\n        if self.show_info:\n            info_surface = pygame.Surface((240, self.dim[1]))\n            info_surface.set_alpha(100)\n            display.blit(info_surface, (0, 0))\n            v_offset = 4\n            bar_h_offset = 100\n            bar_width = 106\n            i = 0\n            for module_name, module_info in self._info_text.items():\n                if not module_info:\n                    continue\n                surface = self._header_font.render(module_name, True, COLOR_ALUMINIUM_0).convert_alpha()\n                display.blit(surface, (8 + bar_width / 2, 18 * i + v_offset))\n                v_offset += 12\n                i += 1\n                for item in module_info:\n                    if v_offset + 18 > self.dim[1]:\n                        break\n                    if isinstance(item, list):\n                        if len(item) > 1:\n                            points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)]\n                            pygame.draw.lines(display, (255, 136, 0), False, points, 2)\n                        item = None\n                    elif isinstance(item, tuple):\n                        if isinstance(item[1], bool):\n                            rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6))\n                            pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect, 0 if item[1] else 1)\n                        else:\n                            rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6))\n                            pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect_border, 1)\n                            f = (item[1] - item[2]) / (item[3] - item[2])\n                            if item[2] < 0.0:\n                                rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6))\n                            else:\n                                rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))\n                            pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect)\n                        item = item[0]\n                    if item:  # At this point has to be a str.\n                        surface = self._font_mono.render(item, True, COLOR_ALUMINIUM_0).convert_alpha()\n                        display.blit(surface, (8, 18 * i + v_offset))\n                    v_offset += 18\n                v_offset += 24\n        self._notifications.render(display)\n        self.help.render(display)\n\n\n# ==============================================================================\n# -- TrafficLightSurfaces ------------------------------------------------------\n# ==============================================================================\n\n\nclass TrafficLightSurfaces(object):\n    \"\"\"Holds the surfaces (scaled and rotated) for painting traffic lights\"\"\"\n\n    def __init__(self):\n        def make_surface(tl):\n            w = 40\n            surface = pygame.Surface((w, 3 * w), pygame.SRCALPHA)\n            surface.fill(COLOR_ALUMINIUM_5 if tl != 'h' else COLOR_ORANGE_2)\n            if tl != 'h':\n                hw = int(w / 2)\n                off = COLOR_ALUMINIUM_4\n                red = COLOR_SCARLET_RED_0\n                yellow = COLOR_BUTTER_0\n                green = COLOR_CHAMELEON_0\n                pygame.draw.circle(surface, red if tl == tls.Red else off, (hw, hw), int(0.4 * w))\n                pygame.draw.circle(surface, yellow if tl == tls.Yellow else off, (hw, w + hw), int(0.4 * w))\n                pygame.draw.circle(surface, green if tl == tls.Green else off, (hw, 2 * w + hw), int(0.4 * w))\n            return pygame.transform.smoothscale(surface, (15, 45) if tl != 'h' else (19, 49))\n        self._original_surfaces = {\n            'h': make_surface('h'),\n            tls.Red: make_surface(tls.Red),\n            tls.Yellow: make_surface(tls.Yellow),\n            tls.Green: make_surface(tls.Green),\n            tls.Off: make_surface(tls.Off),\n            tls.Unknown: make_surface(tls.Unknown)\n        }\n        self.surfaces = dict(self._original_surfaces)\n\n    def rotozoom(self, angle, scale):\n        for key, surface in self._original_surfaces.items():\n            self.surfaces[key] = pygame.transform.rotozoom(surface, angle, scale)\n\n\n# ==============================================================================\n# -- World ---------------------------------------------------------------------\n# ==============================================================================\n\n\nclass MapImage(object):\n    def __init__(self, carla_world, carla_map, pixels_per_meter, show_triggers, show_connections, show_spawn_points):\n        self._pixels_per_meter = pixels_per_meter\n        self.scale = 1.0\n        self.show_triggers = show_triggers\n        self.show_connections = show_connections\n        self.show_spawn_points = show_spawn_points\n\n        waypoints = carla_map.generate_waypoints(2)\n        margin = 50\n        max_x = max(waypoints, key=lambda x: x.transform.location.x).transform.location.x + margin\n        max_y = max(waypoints, key=lambda x: x.transform.location.y).transform.location.y + margin\n        min_x = min(waypoints, key=lambda x: x.transform.location.x).transform.location.x - margin\n        min_y = min(waypoints, key=lambda x: x.transform.location.y).transform.location.y - margin\n\n        self.width = max(max_x - min_x, max_y - min_y)\n        self._world_offset = (min_x, min_y)\n\n        width_in_pixels = int(self._pixels_per_meter * self.width)\n\n        self.big_map_surface = pygame.Surface((width_in_pixels, width_in_pixels)).convert()\n        self.draw_road_map(self.big_map_surface, carla_world, carla_map, self.world_to_pixel, self.world_to_pixel_width)\n        self.surface = self.big_map_surface\n\n    def draw_road_map(self, map_surface, carla_world, carla_map, world_to_pixel, world_to_pixel_width):\n        map_surface.fill(COLOR_ALUMINIUM_4)\n        precision = 0.05\n\n        def lane_marking_color_to_tango(lane_marking_color):\n            tango_color = COLOR_BLACK\n\n            if lane_marking_color == carla.LaneMarkingColor.White:\n                tango_color = COLOR_ALUMINIUM_2\n\n            elif lane_marking_color == carla.LaneMarkingColor.Blue:\n                tango_color = COLOR_SKY_BLUE_0\n\n            elif lane_marking_color == carla.LaneMarkingColor.Green:\n                tango_color = COLOR_CHAMELEON_0\n\n            elif lane_marking_color == carla.LaneMarkingColor.Red:\n                tango_color = COLOR_SCARLET_RED_0\n\n            elif lane_marking_color == carla.LaneMarkingColor.Yellow:\n                tango_color = COLOR_ORANGE_0\n\n            return tango_color\n\n        def draw_solid_line(surface, color, closed, points, width):\n            if len(points) >= 2:\n                pygame.draw.lines(surface, color, closed, points, width)\n\n        def draw_broken_line(surface, color, closed, points, width):\n            broken_lines = [x for n, x in enumerate(zip(*(iter(points),) * 20)) if n % 3 == 0]\n            for line in broken_lines:\n                pygame.draw.lines(surface, color, closed, line, width)\n\n        def get_lane_markings(lane_marking_type, lane_marking_color, waypoints, sign):\n            margin = 0.20\n            if lane_marking_type == carla.LaneMarkingType.Broken or (lane_marking_type == carla.LaneMarkingType.Solid):\n                marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints]\n                return [(lane_marking_type, lane_marking_color, marking_1)]\n            elif lane_marking_type == carla.LaneMarkingType.SolidBroken or lane_marking_type == carla.LaneMarkingType.BrokenSolid:\n                marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints]\n                marking_2 = [world_to_pixel(lateral_shift(w.transform,\n                                                          sign * (w.lane_width * 0.5 + margin * 2))) for w in waypoints]\n                return [(carla.LaneMarkingType.Solid, lane_marking_color, marking_1),\n                        (carla.LaneMarkingType.Broken, lane_marking_color, marking_2)]\n            elif lane_marking_type == carla.LaneMarkingType.BrokenBroken:\n                marking = [world_to_pixel(lateral_shift(w.transform,\n                                                        sign * (w.lane_width * 0.5 - margin))) for w in waypoints]\n                return [(carla.LaneMarkingType.Broken, lane_marking_color, marking)]\n            elif lane_marking_type == carla.LaneMarkingType.SolidSolid:\n                marking = [world_to_pixel(lateral_shift(w.transform,\n                                                        sign * ((w.lane_width * 0.5) - margin))) for w in waypoints]\n                return [(carla.LaneMarkingType.Solid, lane_marking_color, marking)]\n\n            return [(carla.LaneMarkingType.NONE, carla.LaneMarkingColor.Other, [])]\n\n        def draw_lane_marking(surface, waypoints, is_left):\n            sign = -1 if is_left else 1\n            lane_marking = None\n\n            marking_type = carla.LaneMarkingType.NONE\n            previous_marking_type = carla.LaneMarkingType.NONE\n\n            marking_color = carla.LaneMarkingColor.Other\n            previous_marking_color = carla.LaneMarkingColor.Other\n\n            waypoints_list = []\n            temp_waypoints = []\n            current_lane_marking = carla.LaneMarkingType.NONE\n            for sample in waypoints:\n                lane_marking = sample.left_lane_marking if sign < 0 else sample.right_lane_marking\n\n                if lane_marking is None:\n                    continue\n\n                marking_type = lane_marking.type\n                marking_color = lane_marking.color\n\n                if current_lane_marking != marking_type:\n                    markings = get_lane_markings(\n                        previous_marking_type,\n                        lane_marking_color_to_tango(previous_marking_color),\n                        temp_waypoints,\n                        sign)\n                    current_lane_marking = marking_type\n\n                    for marking in markings:\n                        waypoints_list.append(marking)\n\n                    temp_waypoints = temp_waypoints[-1:]\n\n                else:\n                    temp_waypoints.append((sample))\n                    previous_marking_type = marking_type\n                    previous_marking_color = marking_color\n\n            # Add last marking\n            last_markings = get_lane_markings(\n                previous_marking_type,\n                lane_marking_color_to_tango(previous_marking_color),\n                temp_waypoints,\n                sign)\n            for marking in last_markings:\n                waypoints_list.append(marking)\n\n            for markings in waypoints_list:\n                if markings[0] == carla.LaneMarkingType.Solid:\n                    draw_solid_line(surface, markings[1], False, markings[2], 2)\n                elif markings[0] == carla.LaneMarkingType.Broken:\n                    draw_broken_line(surface, markings[1], False, markings[2], 2)\n\n        def draw_arrow(surface, transform, color=COLOR_ALUMINIUM_2):\n            transform.rotation.yaw += 180\n            forward = transform.get_forward_vector()\n            transform.rotation.yaw += 90\n            right_dir = transform.get_forward_vector()\n            end = transform.location\n            start = end - 2.0 * forward\n            right = start + 0.8 * forward + 0.4 * right_dir\n            left = start + 0.8 * forward - 0.4 * right_dir\n            pygame.draw.lines(\n                surface, color, False, [\n                    world_to_pixel(x) for x in [\n                        start, end]], 4)\n            pygame.draw.lines(\n                surface, color, False, [\n                    world_to_pixel(x) for x in [\n                        left, start, right]], 4)\n\n        def draw_traffic_signs(surface, font_surface, actor, color=COLOR_ALUMINIUM_2, trigger_color=COLOR_PLUM_0):\n            transform = actor.get_transform()\n            waypoint = carla_map.get_waypoint(transform.location)\n\n            angle = -waypoint.transform.rotation.yaw - 90.0\n            font_surface = pygame.transform.rotate(font_surface, angle)\n            pixel_pos = world_to_pixel(waypoint.transform.location)\n            offset = font_surface.get_rect(center=(pixel_pos[0], pixel_pos[1]))\n            surface.blit(font_surface, offset)\n\n            # Draw line in front of stop\n            forward_vector = carla.Location(waypoint.transform.get_forward_vector())\n            left_vector = carla.Location(-forward_vector.y, forward_vector.x,\n                                         forward_vector.z) * waypoint.lane_width / 2 * 0.7\n\n            line = [(waypoint.transform.location + (forward_vector * 1.5) + (left_vector)),\n                    (waypoint.transform.location + (forward_vector * 1.5) - (left_vector))]\n\n            line_pixel = [world_to_pixel(p) for p in line]\n            pygame.draw.lines(surface, color, True, line_pixel, 2)\n\n            # draw bounding box\n            if self.show_triggers:\n                corners = Util.get_bounding_box(actor)\n                corners = [world_to_pixel(p) for p in corners]\n                pygame.draw.lines(surface, trigger_color, True, corners, 2)\n\n        def lateral_shift(transform, shift):\n            transform.rotation.yaw += 90\n            return transform.location + shift * transform.get_forward_vector()\n\n        def draw_topology(carla_topology, index):\n            topology = [x[index] for x in carla_topology]\n            topology = sorted(topology, key=lambda w: w.transform.location.z)\n            for waypoint in topology:\n                # if waypoint.road_id == 150 or waypoint.road_id == 16:\n                waypoints = [waypoint]\n\n                nxt = waypoint.next(precision)\n                if len(nxt) > 0:\n                    nxt = nxt[0]\n                    while nxt.road_id == waypoint.road_id:\n                        waypoints.append(nxt)\n                        nxt = nxt.next(precision)\n                        if len(nxt) > 0:\n                            nxt = nxt[0]\n                        else:\n                            break\n\n                # Draw Road\n                road_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in waypoints]\n                road_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in waypoints]\n\n                polygon = road_left_side + [x for x in reversed(road_right_side)]\n                polygon = [world_to_pixel(x) for x in polygon]\n\n                if len(polygon) > 2:\n                    pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon, 5)\n                    pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon)\n\n                # Draw Shoulders and Parkings\n                PARKING_COLOR = COLOR_ALUMINIUM_4_5\n                SHOULDER_COLOR = COLOR_ALUMINIUM_5\n\n                final_color = SHOULDER_COLOR\n\n                # Draw Right\n                shoulder = []\n                for w in waypoints:\n                    r = w.get_right_lane()\n                    if r is not None and (\n                            r.lane_type == carla.LaneType.Shoulder or r.lane_type == carla.LaneType.Parking):\n                        if r.lane_type == carla.LaneType.Parking:\n                            final_color = PARKING_COLOR\n                        shoulder.append(r)\n\n                shoulder_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in shoulder]\n                shoulder_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in shoulder]\n\n                polygon = shoulder_left_side + [x for x in reversed(shoulder_right_side)]\n                polygon = [world_to_pixel(x) for x in polygon]\n\n                if len(polygon) > 2:\n                    pygame.draw.polygon(map_surface, final_color, polygon, 5)\n                    pygame.draw.polygon(map_surface, final_color, polygon)\n\n                draw_lane_marking(\n                    map_surface,\n                    shoulder,\n                    False)\n\n                # Draw Left\n                shoulder = []\n                for w in waypoints:\n                    r = w.get_left_lane()\n                    if r is not None and (\n                            r.lane_type == carla.LaneType.Shoulder or r.lane_type == carla.LaneType.Parking):\n                        if r.lane_type == carla.LaneType.Parking:\n                            final_color = PARKING_COLOR\n                        shoulder.append(r)\n\n                shoulder_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in shoulder]\n                shoulder_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in shoulder]\n\n                polygon = shoulder_left_side + [x for x in reversed(shoulder_right_side)]\n                polygon = [world_to_pixel(x) for x in polygon]\n\n                if len(polygon) > 2:\n                    pygame.draw.polygon(map_surface, final_color, polygon, 5)\n                    pygame.draw.polygon(map_surface, final_color, polygon)\n\n                draw_lane_marking(\n                    map_surface,\n                    shoulder,\n                    True)\n\n                # Draw Lane Markings and Arrows\n                if not waypoint.is_intersection:\n                    draw_lane_marking(\n                        map_surface,\n                        waypoints,\n                        True)\n                    draw_lane_marking(\n                        map_surface,\n                        waypoints,\n                        False)\n                    for n, wp in enumerate(waypoints):\n                        if ((n + 1) % 400) == 0:\n                            draw_arrow(map_surface, wp.transform)\n\n        topology = carla_map.get_topology()\n        draw_topology(topology, 0)\n        draw_topology(topology, 1)\n\n        if self.show_spawn_points:\n            for sp in carla_map.get_spawn_points():\n                draw_arrow(map_surface, sp, color=COLOR_CHOCOLATE_0)\n\n        if self.show_connections:\n            dist = 1.5\n            to_pixel = lambda wp: world_to_pixel(wp.transform.location)\n            for wp in carla_map.generate_waypoints(dist):\n                col = (0, 255, 255) if wp.is_intersection else (0, 255, 0)\n                for nxt in wp.next(dist):\n                    pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(nxt), 2)\n                if wp.lane_change & carla.LaneChange.Right:\n                    r = wp.get_right_lane()\n                    if r and r.lane_type == carla.LaneType.Driving:\n                        pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(r), 2)\n                if wp.lane_change & carla.LaneChange.Left:\n                    l = wp.get_left_lane()\n                    if l and l.lane_type == carla.LaneType.Driving:\n                        pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(l), 2)\n\n        actors = carla_world.get_actors()\n\n        # Draw Traffic Signs\n        font_size = world_to_pixel_width(1)\n        font = pygame.font.SysFont('Arial', font_size, True)\n\n        stops = [actor for actor in actors if 'stop' in actor.type_id]\n        yields = [actor for actor in actors if 'yield' in actor.type_id]\n\n        stop_font_surface = font.render(\"STOP\", False, COLOR_ALUMINIUM_2)\n        stop_font_surface = pygame.transform.scale(\n            stop_font_surface, (stop_font_surface.get_width(), stop_font_surface.get_height() * 2))\n\n        yield_font_surface = font.render(\"YIELD\", False, COLOR_ALUMINIUM_2)\n        yield_font_surface = pygame.transform.scale(\n            yield_font_surface, (yield_font_surface.get_width(), yield_font_surface.get_height() * 2))\n\n        for ts_stop in stops:\n            draw_traffic_signs(map_surface, stop_font_surface, ts_stop, trigger_color=COLOR_SCARLET_RED_1)\n\n        for ts_yield in yields:\n            draw_traffic_signs(map_surface, yield_font_surface, ts_yield, trigger_color=COLOR_ORANGE_1)\n\n    def world_to_pixel(self, location, offset=(0, 0)):\n        x = self.scale * self._pixels_per_meter * (location.x - self._world_offset[0])\n        y = self.scale * self._pixels_per_meter * (location.y - self._world_offset[1])\n        return [int(x - offset[0]), int(y - offset[1])]\n\n    def world_to_pixel_width(self, width):\n        return int(self.scale * self._pixels_per_meter * width)\n\n    def scale_map(self, scale):\n        if scale != self.scale:\n            self.scale = scale\n            width = int(self.big_map_surface.get_width() * self.scale)\n            self.surface = pygame.transform.smoothscale(self.big_map_surface, (width, width))\n\n\nclass ModuleWorld(object):\n    def __init__(self, name, args, timeout):\n        self.client = None\n        self.name = name\n        self.args = args\n        self.timeout = timeout\n        self.server_fps = 0.0\n        self.simulation_time = 0\n        self.server_clock = pygame.time.Clock()\n\n        # World data\n        self.world = None\n        self.town_map = None\n        self.actors_with_transforms = []\n        # Store necessary modules\n        self.module_hud = None\n        self.module_input = None\n\n        self.surface_size = [0, 0]\n        self.prev_scaled_size = 0\n        self.scaled_size = 0\n        # Hero actor\n        self.hero_actor = None\n        self.spawned_hero = None\n        self.hero_transform = None\n\n        self.scale_offset = [0, 0]\n\n        self.vehicle_id_surface = None\n        self.result_surface = None\n\n        self.traffic_light_surfaces = TrafficLightSurfaces()\n        self.affected_traffic_light = None\n\n        # Map info\n        self.map_image = None\n        self.border_round_surface = None\n        self.original_surface_size = None\n        self.hero_surface = None\n        self.actors_surface = None\n\n    def _get_data_from_carla(self):\n        try:\n            self.client = carla.Client(self.args.host, self.args.port)\n            self.client.set_timeout(self.timeout)\n\n            if self.args.map is None:\n                world = self.client.get_world()\n            else:\n                world = self.client.load_world(self.args.map)\n\n            town_map = world.get_map()\n            return (world, town_map)\n\n        except RuntimeError as ex:\n            logging.error(ex)\n            exit_game()\n\n    def start(self):\n        self.world, self.town_map = self._get_data_from_carla()\n\n        # Create Surfaces\n        self.map_image = MapImage(\n            carla_world=self.world,\n            carla_map=self.town_map,\n            pixels_per_meter=PIXELS_PER_METER,\n            show_triggers=self.args.show_triggers,\n            show_connections=self.args.show_connections,\n            show_spawn_points=self.args.show_spawn_points)\n\n        # Store necessary modules\n        self.module_hud = module_manager.get_module(MODULE_HUD)\n        self.module_input = module_manager.get_module(MODULE_INPUT)\n\n        self.original_surface_size = min(self.module_hud.dim[0], self.module_hud.dim[1])\n        self.surface_size = self.map_image.big_map_surface.get_width()\n\n        self.scaled_size = int(self.surface_size)\n        self.prev_scaled_size = int(self.surface_size)\n\n        # Render Actors\n        self.actors_surface = pygame.Surface((self.map_image.surface.get_width(), self.map_image.surface.get_height()))\n        self.actors_surface.set_colorkey(COLOR_BLACK)\n\n        self.vehicle_id_surface = pygame.Surface((self.surface_size, self.surface_size)).convert()\n        self.vehicle_id_surface.set_colorkey(COLOR_BLACK)\n\n        self.border_round_surface = pygame.Surface(self.module_hud.dim, pygame.SRCALPHA).convert()\n        self.border_round_surface.set_colorkey(COLOR_WHITE)\n        self.border_round_surface.fill(COLOR_BLACK)\n\n        center_offset = (int(self.module_hud.dim[0] / 2), int(self.module_hud.dim[1] / 2))\n        pygame.draw.circle(self.border_round_surface, COLOR_ALUMINIUM_1, center_offset, int(self.module_hud.dim[1] / 2))\n        pygame.draw.circle(self.border_round_surface, COLOR_WHITE, center_offset, int((self.module_hud.dim[1] - 8) / 2))\n\n        scaled_original_size = self.original_surface_size * (1.0 / 0.9)\n        self.hero_surface = pygame.Surface((scaled_original_size, scaled_original_size)).convert()\n\n        self.result_surface = pygame.Surface((self.surface_size, self.surface_size)).convert()\n        self.result_surface.set_colorkey(COLOR_BLACK)\n\n        # Start hero mode by default\n        self.select_hero_actor()\n        self.hero_actor.set_autopilot(False)\n        self.module_input.wheel_offset = HERO_DEFAULT_SCALE\n        self.module_input.control = carla.VehicleControl()\n\n        weak_self = weakref.ref(self)\n        self.world.on_tick(lambda timestamp: ModuleWorld.on_world_tick(weak_self, timestamp))\n\n    def select_hero_actor(self):\n        hero_vehicles = [actor for actor in self.world.get_actors(\n        ) if 'vehicle' in actor.type_id and actor.attributes['role_name'] == 'hero']\n        if len(hero_vehicles) > 0:\n            self.hero_actor = random.choice(hero_vehicles)\n            self.hero_transform = self.hero_actor.get_transform()\n        else:\n            self._spawn_hero()\n\n    def _spawn_hero(self):\n        # Get a random blueprint.\n        blueprint = random.choice(self.world.get_blueprint_library().filter(self.args.filter))\n        blueprint.set_attribute('role_name', 'hero')\n        if blueprint.has_attribute('color'):\n            color = random.choice(blueprint.get_attribute('color').recommended_values)\n            blueprint.set_attribute('color', color)\n        # Spawn the player.\n        while self.hero_actor is None:\n            spawn_points = self.world.get_map().get_spawn_points()\n            spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()\n            self.hero_actor = self.world.try_spawn_actor(blueprint, spawn_point)\n        self.hero_transform = self.hero_actor.get_transform()\n\n        # Save it in order to destroy it when closing program\n        self.spawned_hero = self.hero_actor\n\n    def tick(self, clock):\n        actors = self.world.get_actors()\n        self.actors_with_transforms = [(actor, actor.get_transform()) for actor in actors]\n        if self.hero_actor is not None:\n            self.hero_transform = self.hero_actor.get_transform()\n        self.update_hud_info(clock)\n\n    def update_hud_info(self, clock):\n        hero_mode_text = []\n        if self.hero_actor is not None:\n            hero_speed = self.hero_actor.get_velocity()\n            hero_speed_text = 3.6 * math.sqrt(hero_speed.x ** 2 + hero_speed.y ** 2 + hero_speed.z ** 2)\n\n            affected_traffic_light_text = 'None'\n            if self.affected_traffic_light is not None:\n                state = self.affected_traffic_light.state\n                if state == carla.TrafficLightState.Green:\n                    affected_traffic_light_text = 'GREEN'\n                elif state == carla.TrafficLightState.Yellow:\n                    affected_traffic_light_text = 'YELLOW'\n                else:\n                    affected_traffic_light_text = 'RED'\n\n            affected_speed_limit_text = self.hero_actor.get_speed_limit()\n\n            hero_mode_text = [\n                'Hero Mode:                 ON',\n                'Hero ID:              %7d' % self.hero_actor.id,\n                'Hero Vehicle:  %14s' % get_actor_display_name(self.hero_actor, truncate=14),\n                'Hero Speed:          %3d km/h' % hero_speed_text,\n                'Hero Affected by:',\n                '  Traffic Light: %12s' % affected_traffic_light_text,\n                '  Speed Limit:       %3d km/h' % affected_speed_limit_text\n            ]\n        else:\n            hero_mode_text = ['Hero Mode:                OFF']\n\n        self.server_fps = self.server_clock.get_fps()\n        self.server_fps = 'inf' if self.server_fps == float('inf') else round(self.server_fps)\n        module_info_text = [\n            'Server:  % 16s FPS' % self.server_fps,\n            'Client:  % 16s FPS' % round(clock.get_fps()),\n            'Simulation Time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),\n            'Map Name:          %10s' % self.town_map.name.split('/')[-1],\n        ]\n\n        module_info_text = module_info_text\n        module_hud = module_manager.get_module(MODULE_HUD)\n        module_hud.add_info(self.name, module_info_text)\n        module_hud.add_info('HERO', hero_mode_text)\n\n    @staticmethod\n    def on_world_tick(weak_self, timestamp):\n        self = weak_self()\n        if not self:\n            return\n\n        self.server_clock.tick()\n        self.server_fps = self.server_clock.get_fps()\n        self.simulation_time = timestamp.elapsed_seconds\n\n    def _split_actors(self):\n        vehicles = []\n        traffic_lights = []\n        speed_limits = []\n        walkers = []\n\n        for actor_with_transform in self.actors_with_transforms:\n            actor = actor_with_transform[0]\n            if 'vehicle' in actor.type_id:\n                vehicles.append(actor_with_transform)\n            elif 'traffic_light' in actor.type_id:\n                traffic_lights.append(actor_with_transform)\n            elif 'speed_limit' in actor.type_id:\n                speed_limits.append(actor_with_transform)\n            elif 'walker' in actor.type_id:\n                walkers.append(actor_with_transform)\n\n        info_text = []\n        if self.hero_actor is not None and len(vehicles) > 1:\n            location = self.hero_transform.location\n            vehicle_list = [x[0] for x in vehicles if x[0].id != self.hero_actor.id]\n\n            def distance(v): return location.distance(v.get_location())\n            for n, vehicle in enumerate(sorted(vehicle_list, key=distance)):\n                if n > 15:\n                    break\n                vehicle_type = get_actor_display_name(vehicle, truncate=22)\n                info_text.append('% 5d %s' % (vehicle.id, vehicle_type))\n        module_manager.get_module(MODULE_HUD).add_info(\n            'NEARBY VEHICLES',\n            info_text)\n\n        return (vehicles, traffic_lights, speed_limits, walkers)\n\n    def _render_traffic_lights(self, surface, list_tl, world_to_pixel):\n        self.affected_traffic_light = None\n\n        for tl in list_tl:\n            world_pos = tl.get_location()\n            pos = world_to_pixel(world_pos)\n\n            if self.args.show_triggers:\n                corners = Util.get_bounding_box(tl)\n                corners = [world_to_pixel(p) for p in corners]\n                pygame.draw.lines(surface, COLOR_BUTTER_1, True, corners, 2)\n\n            if self.hero_actor is not None:\n                corners = Util.get_bounding_box(tl)\n                corners = [world_to_pixel(p) for p in corners]\n                tl_t = tl.get_transform()\n\n                transformed_tv = tl_t.transform(tl.trigger_volume.location)\n                hero_location = self.hero_actor.get_location()\n                d = hero_location.distance(transformed_tv)\n                s = Util.length(tl.trigger_volume.extent) + Util.length(self.hero_actor.bounding_box.extent)\n                if (d <= s):\n                    # Highlight traffic light\n                    self.affected_traffic_light = tl\n                    srf = self.traffic_light_surfaces.surfaces['h']\n                    surface.blit(srf, srf.get_rect(center=pos))\n\n            srf = self.traffic_light_surfaces.surfaces[tl.state]\n            surface.blit(srf, srf.get_rect(center=pos))\n\n    def _render_speed_limits(self, surface, list_sl, world_to_pixel, world_to_pixel_width):\n\n        font_size = world_to_pixel_width(2)\n        radius = world_to_pixel_width(2)\n        font = pygame.font.SysFont('Arial', font_size)\n\n        for sl in list_sl:\n\n            x, y = world_to_pixel(sl.get_location())\n\n            # Render speed limit\n            white_circle_radius = int(radius * 0.75)\n\n            pygame.draw.circle(surface, COLOR_SCARLET_RED_1, (x, y), radius)\n            pygame.draw.circle(surface, COLOR_ALUMINIUM_0, (x, y), white_circle_radius)\n\n            limit = sl.type_id.split('.')[2]\n            font_surface = font.render(limit, True, COLOR_ALUMINIUM_5)\n\n            if self.args.show_triggers:\n                corners = Util.get_bounding_box(sl)\n                corners = [world_to_pixel(p) for p in corners]\n                pygame.draw.lines(surface, COLOR_PLUM_2, True, corners, 2)\n\n            # Blit\n            if self.hero_actor is not None:\n                # Rotate font surface with respect to hero vehicle front\n                angle = -self.hero_transform.rotation.yaw - 90.0\n                font_surface = pygame.transform.rotate(font_surface, angle)\n                offset = font_surface.get_rect(center=(x, y))\n                surface.blit(font_surface, offset)\n\n            else:\n                surface.blit(font_surface, (x - radius / 2, y - radius / 2))\n\n    def _render_walkers(self, surface, list_w, world_to_pixel):\n        for w in list_w:\n            color = COLOR_PLUM_0\n\n            # Compute bounding box points\n            bb = w[0].bounding_box.extent\n            corners = [\n                carla.Location(x=-bb.x, y=-bb.y),\n                carla.Location(x=bb.x, y=-bb.y),\n                carla.Location(x=bb.x, y=bb.y),\n                carla.Location(x=-bb.x, y=bb.y)]\n\n            w[1].transform(corners)\n            corners = [world_to_pixel(p) for p in corners]\n            pygame.draw.polygon(surface, color, corners)\n\n    def _render_vehicles(self, surface, list_v, world_to_pixel):\n\n        for v in list_v:\n            color = COLOR_SKY_BLUE_0\n            if int(v[0].attributes['number_of_wheels']) == 2:\n                color = COLOR_CHOCOLATE_1\n            if v[0].attributes['role_name'] == 'hero':\n                color = COLOR_CHAMELEON_0\n            # Compute bounding box points\n            bb = v[0].bounding_box.extent\n            corners = [carla.Location(x=-bb.x, y=-bb.y),\n                       carla.Location(x=bb.x - 0.8, y=-bb.y),\n                       carla.Location(x=bb.x, y=0),\n                       carla.Location(x=bb.x - 0.8, y=bb.y),\n                       carla.Location(x=-bb.x, y=bb.y),\n                       carla.Location(x=-bb.x, y=-bb.y)\n                       ]\n            v[1].transform(corners)\n            corners = [world_to_pixel(p) for p in corners]\n            pygame.draw.lines(surface, color, False, corners, int(math.ceil(4.0 * self.map_image.scale)))\n\n    def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers):\n        # Static actors\n        self._render_traffic_lights(surface, [tl[0] for tl in traffic_lights], self.map_image.world_to_pixel)\n        self._render_speed_limits(surface, [sl[0] for sl in speed_limits], self.map_image.world_to_pixel,\n                                  self.map_image.world_to_pixel_width)\n\n        # Dynamic actors\n        self._render_vehicles(surface, vehicles, self.map_image.world_to_pixel)\n        self._render_walkers(surface, walkers, self.map_image.world_to_pixel)\n\n    def clip_surfaces(self, clipping_rect):\n        self.actors_surface.set_clip(clipping_rect)\n        self.vehicle_id_surface.set_clip(clipping_rect)\n        self.result_surface.set_clip(clipping_rect)\n\n    def _compute_scale(self, scale_factor):\n        m = self.module_input.mouse_pos\n\n        # Percentage of surface where mouse position is actually\n        px = (m[0] - self.scale_offset[0]) / float(self.prev_scaled_size)\n        py = (m[1] - self.scale_offset[1]) / float(self.prev_scaled_size)\n\n        # Offset will be the previously accumulated offset added with the\n        # difference of mouse positions in the old and new scales\n        diff_between_scales = ((float(self.prev_scaled_size) * px) - (float(self.scaled_size) * px),\n                               (float(self.prev_scaled_size) * py) - (float(self.scaled_size) * py))\n\n        self.scale_offset = (self.scale_offset[0] + diff_between_scales[0],\n                             self.scale_offset[1] + diff_between_scales[1])\n\n        # Update previous scale\n        self.prev_scaled_size = self.scaled_size\n\n        # Scale performed\n        self.map_image.scale_map(scale_factor)\n\n    def render(self, display):\n        if self.actors_with_transforms is None:\n            return\n        self.result_surface.fill(COLOR_BLACK)\n        vehicles, traffic_lights, speed_limits, walkers = self._split_actors()\n\n        scale_factor = self.module_input.wheel_offset\n        self.scaled_size = int(self.map_image.width * scale_factor)\n        if self.scaled_size != self.prev_scaled_size:\n            self._compute_scale(scale_factor)\n\n        # Render Actors\n\n        self.actors_surface.fill(COLOR_BLACK)\n        self.render_actors(\n            self.actors_surface,\n            vehicles,\n            traffic_lights,\n            speed_limits,\n            walkers)\n\n        # Render Ids\n        self.module_hud.render_vehicles_ids(self.vehicle_id_surface, vehicles,\n                                            self.map_image.world_to_pixel, self.hero_actor, self.hero_transform)\n\n        # Blit surfaces\n        surfaces = ((self.map_image.surface, (0, 0)),\n                    (self.actors_surface, (0, 0)),\n                    (self.vehicle_id_surface, (0, 0)),\n                    )\n\n        angle = 0.0 if self.hero_actor is None else self.hero_transform.rotation.yaw + 90.0\n        self.traffic_light_surfaces.rotozoom(-angle, self.map_image.scale)\n\n        center_offset = (0, 0)\n        if self.hero_actor is not None:\n\n            hero_location_screen = self.map_image.world_to_pixel(self.hero_transform.location)\n            hero_front = self.hero_transform.get_forward_vector()\n            translation_offset = (\n                hero_location_screen[0] -\n                self.hero_surface.get_width() /\n                2 +\n                hero_front.x *\n                PIXELS_AHEAD_VEHICLE,\n                (hero_location_screen[1] -\n                 self.hero_surface.get_height() /\n                 2 +\n                 hero_front.y *\n                 PIXELS_AHEAD_VEHICLE))\n\n            # Apply clipping rect\n            clipping_rect = pygame.Rect(translation_offset[0],\n                                        translation_offset[1],\n                                        self.hero_surface.get_width(),\n                                        self.hero_surface.get_height())\n            self.clip_surfaces(clipping_rect)\n\n            Util.blits(self.result_surface, surfaces)\n\n            self.border_round_surface.set_clip(clipping_rect)\n\n            self.hero_surface.fill(COLOR_ALUMINIUM_4)\n            self.hero_surface.blit(self.result_surface, (-translation_offset[0],\n                                                         -translation_offset[1]))\n\n            rotated_result_surface = pygame.transform.rotozoom(self.hero_surface, angle, 0.9).convert()\n\n            center = (display.get_width() / 2, display.get_height() / 2)\n            rotation_pivot = rotated_result_surface.get_rect(center=center)\n            display.blit(rotated_result_surface, rotation_pivot)\n\n            display.blit(self.border_round_surface, (0, 0))\n        else:\n            # Translation offset\n            translation_offset = (self.module_input.mouse_offset[0] * scale_factor + self.scale_offset[0],\n                                  self.module_input.mouse_offset[1] * scale_factor + self.scale_offset[1])\n            center_offset = (abs(display.get_width() - self.surface_size) / 2 * scale_factor, 0)\n\n            # Apply clipping rect\n            clipping_rect = pygame.Rect(-translation_offset[0] - center_offset[0], -translation_offset[1],\n                                        self.module_hud.dim[0], self.module_hud.dim[1])\n            self.clip_surfaces(clipping_rect)\n            Util.blits(self.result_surface, surfaces)\n\n            display.blit(self.result_surface, (translation_offset[0] + center_offset[0],\n                                               translation_offset[1]))\n\n    def destroy(self):\n        if self.spawned_hero is not None:\n            self.spawned_hero.destroy()\n# ==============================================================================\n# -- Input -----------------------------------------------------------\n# ==============================================================================\n\n\nclass ModuleInput(object):\n    def __init__(self, name):\n        self.name = name\n        self.mouse_pos = (0, 0)\n        self.mouse_offset = [0.0, 0.0]\n        self.wheel_offset = 0.1\n        self.wheel_amount = 0.025\n        self._steer_cache = 0.0\n        self.control = None\n        self._autopilot_enabled = False\n\n    def start(self):\n        hud = module_manager.get_module(MODULE_HUD)\n        hud.notification(\"Press 'H' or '?' for help.\", seconds=4.0)\n\n    def render(self, display):\n        pass\n\n    def tick(self, clock):\n        self.parse_input(clock)\n\n    def _parse_events(self):\n        self.mouse_pos = pygame.mouse.get_pos()\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                exit_game()\n            elif event.type == pygame.KEYUP:\n                if self._is_quit_shortcut(event.key):\n                    exit_game()\n                elif event.key == K_h or (event.key == K_SLASH and pygame.key.get_mods() & KMOD_SHIFT):\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    module_hud.help.toggle()\n                elif event.key == K_TAB:\n                    module_world = module_manager.get_module(MODULE_WORLD)\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    if module_world.hero_actor is None:\n                        module_world.select_hero_actor()\n                        self.wheel_offset = HERO_DEFAULT_SCALE\n                        self.control = carla.VehicleControl()\n                        module_hud.notification('Hero Mode')\n                    else:\n                        self.wheel_offset = MAP_DEFAULT_SCALE\n                        self.mouse_offset = [0, 0]\n                        self.mouse_pos = [0, 0]\n                        module_world.scale_offset = [0, 0]\n                        module_world.hero_actor = None\n                        module_hud.notification('Map Mode')\n                elif event.key == K_F1:\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    module_hud.show_info = not module_hud.show_info\n                elif event.key == K_i:\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    module_hud.show_actor_ids = not module_hud.show_actor_ids\n                elif isinstance(self.control, carla.VehicleControl):\n                    if event.key == K_q:\n                        self.control.gear = 1 if self.control.reverse else -1\n                    elif event.key == K_m:\n                        self.control.manual_gear_shift = not self.control.manual_gear_shift\n                        world = module_manager.get_module(MODULE_WORLD)\n                        self.control.gear = world.hero_actor.get_control().gear\n                        module_hud = module_manager.get_module(MODULE_HUD)\n                        module_hud.notification('%s Transmission' % (\n                            'Manual' if self.control.manual_gear_shift else 'Automatic'))\n                    elif self.control.manual_gear_shift and event.key == K_COMMA:\n                        self.control.gear = max(-1, self.control.gear - 1)\n                    elif self.control.manual_gear_shift and event.key == K_PERIOD:\n                        self.control.gear = self.control.gear + 1\n                    elif event.key == K_p:\n                        world = module_manager.get_module(MODULE_WORLD)\n                        if world.hero_actor is not None:\n                            self._autopilot_enabled = not self._autopilot_enabled\n                            world.hero_actor.set_autopilot(self._autopilot_enabled)\n                            module_hud = module_manager.get_module(MODULE_HUD)\n                            module_hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))\n            elif event.type == pygame.MOUSEBUTTONDOWN:\n                if event.button == 4:\n                    self.wheel_offset += self.wheel_amount\n                    if self.wheel_offset >= 1.0:\n                        self.wheel_offset = 1.0\n                elif event.button == 5:\n                    self.wheel_offset -= self.wheel_amount\n                    if self.wheel_offset <= 0.1:\n                        self.wheel_offset = 0.1\n\n    def _parse_keys(self, milliseconds):\n        keys = pygame.key.get_pressed()\n        self.control.throttle = 1.0 if keys[K_UP] or keys[K_w] else 0.0\n        steer_increment = 5e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n        self._steer_cache = min(0.7, max(-0.7, self._steer_cache))\n        self.control.steer = round(self._steer_cache, 1)\n        self.control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0\n        self.control.hand_brake = keys[K_SPACE]\n\n    def _parse_mouse(self):\n        if pygame.mouse.get_pressed()[0]:\n            x, y = pygame.mouse.get_pos()\n            self.mouse_offset[0] += (1.0 / self.wheel_offset) * (x - self.mouse_pos[0])\n            self.mouse_offset[1] += (1.0 / self.wheel_offset) * (y - self.mouse_pos[1])\n            self.mouse_pos = (x, y)\n\n    def parse_input(self, clock):\n        self._parse_events()\n        self._parse_mouse()\n        if not self._autopilot_enabled:\n            if isinstance(self.control, carla.VehicleControl):\n                self._parse_keys(clock.get_time())\n                self.control.reverse = self.control.gear < 0\n            world = module_manager.get_module(MODULE_WORLD)\n            if (world.hero_actor is not None):\n                world.hero_actor.apply_control(self.control)\n\n    @staticmethod\n    def _is_quit_shortcut(key):\n        return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)\n\n\n# ==============================================================================\n# -- Global Objects ------------------------------------------------------------\n# ==============================================================================\nmodule_manager = ModuleManager()\n\n\n# ==============================================================================\n# -- Game Loop ---------------------------------------------------------------\n# ==============================================================================\n\n\ndef game_loop(args):\n    try:\n        # Init Pygame\n        pygame.init()\n        display = pygame.display.set_mode(\n            (args.width, args.height),\n            pygame.HWSURFACE | pygame.DOUBLEBUF)\n        pygame.display.set_caption(args.description)\n\n        font = pygame.font.Font(pygame.font.get_default_font(), 20)\n        text_surface = font.render('Rendering map...', True, COLOR_WHITE)\n        display.blit(text_surface, text_surface.get_rect(center=(args.width / 2, args.height / 2)))\n        pygame.display.flip()\n\n        # Init modules\n        input_module = ModuleInput(MODULE_INPUT)\n        hud_module = ModuleHUD(MODULE_HUD, args.width, args.height)\n        world_module = ModuleWorld(MODULE_WORLD, args, timeout=2.0)\n\n        # Register Modules\n        module_manager.register_module(world_module)\n        module_manager.register_module(hud_module)\n        module_manager.register_module(input_module)\n\n        module_manager.start_modules()\n\n        clock = pygame.time.Clock()\n        while True:\n            clock.tick_busy_loop(60)\n\n            module_manager.tick(clock)\n            module_manager.render(display)\n\n            pygame.display.flip()\n\n    except KeyboardInterrupt:\n        print('\\nCancelled by user. Bye!')\n\n    finally:\n        if world_module is not None:\n            world_module.destroy()\n\ndef exit_game():\n    module_manager.clear_modules()\n    pygame.quit()\n    sys.exit()\n\n# ==============================================================================\n# -- Main --------------------------------------------------------------------\n# ==============================================================================\n\n\ndef main():\n    # Parse arguments\n    argparser = argparse.ArgumentParser(\n        description='CARLA No Rendering Mode Visualizer')\n    argparser.add_argument(\n        '-v', '--verbose',\n        action='store_true',\n        dest='debug',\n        help='print debug information')\n    argparser.add_argument(\n        '--host',\n        metavar='H',\n        default='127.0.0.1',\n        help='IP of the host server (default: 127.0.0.1)')\n    argparser.add_argument(\n        '-p', '--port',\n        metavar='P',\n        default=2000,\n        type=int,\n        help='TCP port to listen to (default: 2000)')\n    argparser.add_argument(\n        '--res',\n        metavar='WIDTHxHEIGHT',\n        default='1280x720',\n        help='window resolution (default: 1280x720)')\n    argparser.add_argument(\n        '--filter',\n        metavar='PATTERN',\n        default='vehicle.*',\n        help='actor filter (default: \"vehicle.*\")')\n    argparser.add_argument(\n        '--map',\n        metavar='TOWN',\n        default=None,\n        help='start a new episode at the given TOWN')\n    argparser.add_argument(\n        '--no-rendering',\n        action='store_true',\n        default=True,\n        help='switch off server rendering')\n    argparser.add_argument(\n        '--show-triggers',\n        action='store_true',\n        help='show trigger boxes of traffic signs')\n    argparser.add_argument(\n        '--show-connections',\n        action='store_true',\n        help='show waypoint connections')\n    argparser.add_argument(\n        '--show-spawn-points',\n        action='store_true',\n        help='show recommended spawn points')\n\n    args = argparser.parse_args()\n    args.description = argparser.description\n    args.width, args.height = [int(x) for x in args.res.split('x')]\n\n    log_level = logging.DEBUG if args.debug else logging.INFO\n    logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)\n\n    logging.info('listening to server %s:%s', args.host, args.port)\n    print(__doc__)\n\n    game_loop(args)\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/requirements.txt",
    "content": "py-trees==0.8.3\nnumpy==1.18.4; python_version >= '3.0'\nnetworkx==2.2\nShapely==1.7.1\npsutil\nxmlschema==1.0.18\nephem\ntabulate\nopencv-python==4.2.0.32\nmatplotlib\nsix\nsimple-watchdog-timer\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/scenario_runner.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nWelcome to CARLA scenario_runner\n\nThis is the main script to be executed when running a scenario.\nIt loads the scenario configuration, loads the scenario and manager,\nand finally triggers the scenario execution.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport glob\nimport traceback\nimport argparse\nfrom argparse import RawTextHelpFormatter\nfrom datetime import datetime\ntry:\n    from packaging.version import Version\nexcept ImportError:\n    from distutils.version import LooseVersion as Version # Python 2 fallback\nimport importlib\nimport inspect\nimport os\nimport signal\nimport sys\nimport time\nimport json\n\ntry:\n    # requires Python 3.8+\n    from importlib.metadata import metadata\n    def get_carla_version():\n        return Version(metadata(\"carla\")[\"Version\"])\nexcept ModuleNotFoundError:\n    # backport checking for older Python versions; module is deprecated\n    import pkg_resources\n    def get_carla_version():\n        return Version(pkg_resources.get_distribution(\"carla\").version)\n\nimport carla\n\nfrom srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenario_manager import ScenarioManager\nfrom srunner.scenarios.open_scenario import OpenScenario\nfrom srunner.scenarios.route_scenario import RouteScenario\nfrom srunner.tools.scenario_parser import ScenarioConfigurationParser\nfrom srunner.tools.route_parser import RouteParser\n\n# Version of scenario_runner\nVERSION = '0.9.13'\n\n# Minimum version of CARLA that is required\nMIN_CARLA_VERSION = '0.9.12'\n\n\nclass ScenarioRunner(object):\n\n    \"\"\"\n    This is the core scenario runner module. It is responsible for\n    running (and repeating) a single scenario or a list of scenarios.\n\n    Usage:\n    scenario_runner = ScenarioRunner(args)\n    scenario_runner.run()\n    del scenario_runner\n    \"\"\"\n\n    ego_vehicles = []\n\n    # Tunable parameters\n    client_timeout = 30.0  # in seconds\n    wait_for_world = 30.0  # in seconds\n    frame_rate = 20.0      # in Hz\n\n    # CARLA world and scenario handlers\n    world = None\n    manager = None\n\n    finished = False\n\n    additional_scenario_module = None\n\n    agent_instance = None\n    module_agent = None\n\n    def __init__(self, args):\n        \"\"\"\n        Setup CARLA client and world\n        Setup ScenarioManager\n        \"\"\"\n        self._args = args\n\n        if args.timeout:\n            self.client_timeout = float(args.timeout)\n\n        # First of all, we need to create the client that will send the requests\n        # to the simulator. Here we'll assume the simulator is accepting\n        # requests in the localhost at port 2000.\n        self.client = carla.Client(args.host, int(args.port))\n        self.client.set_timeout(self.client_timeout)\n        carla_version = get_carla_version()\n        if carla_version < Version(MIN_CARLA_VERSION):\n            raise ImportError(\"CARLA version {} or newer required. CARLA version found: {}\".format(MIN_CARLA_VERSION, carla_version))\n\n        # Load agent if requested via command line args\n        # If something goes wrong an exception will be thrown by importlib (ok here)\n        if self._args.agent is not None:\n            module_name = os.path.basename(args.agent).split('.')[0]\n            sys.path.insert(0, os.path.dirname(args.agent))\n            self.module_agent = importlib.import_module(module_name)\n\n        # Create the ScenarioManager\n        self.manager = ScenarioManager(self._args.debug, self._args.sync, self._args.timeout)\n\n        # Create signal handler for SIGINT\n        self._shutdown_requested = False\n        if sys.platform != 'win32':\n            signal.signal(signal.SIGHUP, self._signal_handler)\n        signal.signal(signal.SIGINT, self._signal_handler)\n        signal.signal(signal.SIGTERM, self._signal_handler)\n\n        self._start_wall_time = datetime.now()\n\n    def destroy(self):\n        \"\"\"\n        Cleanup and delete actors, ScenarioManager and CARLA world\n        \"\"\"\n\n        self._cleanup()\n        if self.manager is not None:\n            del self.manager\n        if self.world is not None:\n            del self.world\n        if self.client is not None:\n            del self.client\n\n    def _signal_handler(self, signum, frame):\n        \"\"\"\n        Terminate scenario ticking when receiving a signal interrupt\n        \"\"\"\n        self._shutdown_requested = True\n        if self.manager:\n            self.manager.stop_scenario()\n\n    def _get_scenario_class_or_fail(self, scenario):\n        \"\"\"\n        Get scenario class by scenario name\n        If scenario is not supported or not found, exit script\n        \"\"\"\n\n        # Path of all scenario at \"srunner/scenarios\" folder + the path of the additional scenario argument\n        scenarios_list = glob.glob(\"{}/srunner/scenarios/*.py\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        scenarios_list.append(self._args.additionalScenario)\n\n        for scenario_file in scenarios_list:\n\n            # Get their module\n            module_name = os.path.basename(scenario_file).split('.')[0]\n            sys.path.insert(0, os.path.dirname(scenario_file))\n            scenario_module = importlib.import_module(module_name)\n\n            # And their members of type class\n            for member in inspect.getmembers(scenario_module, inspect.isclass):\n                if scenario in member:\n                    return member[1]\n\n            # Remove unused Python paths\n            sys.path.pop(0)\n\n        print(\"Scenario '{}' not supported ... Exiting\".format(scenario))\n        sys.exit(-1)\n\n    def _cleanup(self):\n        \"\"\"\n        Remove and destroy all actors\n        \"\"\"\n        if self.finished:\n            return\n\n        self.finished = True\n\n        # Simulation still running and in synchronous mode?\n        if self.world is not None and self._args.sync:\n            try:\n                # Reset to asynchronous mode\n                settings = self.world.get_settings()\n                settings.synchronous_mode = False\n                settings.fixed_delta_seconds = None\n                self.world.apply_settings(settings)\n                self.client.get_trafficmanager(int(self._args.trafficManagerPort)).set_synchronous_mode(False)\n            except RuntimeError:\n                sys.exit(-1)\n\n        self.manager.cleanup()\n\n        CarlaDataProvider.cleanup()\n\n        for i, _ in enumerate(self.ego_vehicles):\n            if self.ego_vehicles[i]:\n                if not self._args.waitForEgo and self.ego_vehicles[i] is not None and self.ego_vehicles[i].is_alive:\n                    print(\"Destroying ego vehicle {}\".format(self.ego_vehicles[i].id))\n                    self.ego_vehicles[i].destroy()\n                self.ego_vehicles[i] = None\n        self.ego_vehicles = []\n\n        if self.agent_instance:\n            self.agent_instance.destroy()\n            self.agent_instance = None\n\n    def _prepare_ego_vehicles(self, ego_vehicles):\n        \"\"\"\n        Spawn or update the ego vehicles\n        \"\"\"\n\n        if not self._args.waitForEgo:\n            for vehicle in ego_vehicles:\n                self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model,\n                                                                             vehicle.transform,\n                                                                             vehicle.rolename,\n                                                                             color=vehicle.color,\n                                                                             actor_category=vehicle.category))\n        else:\n            ego_vehicle_missing = True\n            while ego_vehicle_missing:\n                self.ego_vehicles = []\n                ego_vehicle_missing = False\n                for ego_vehicle in ego_vehicles:\n                    ego_vehicle_found = False\n                    carla_vehicles = CarlaDataProvider.get_world().get_actors().filter('vehicle.*')\n                    for carla_vehicle in carla_vehicles:\n                        if carla_vehicle.attributes['role_name'] == ego_vehicle.rolename:\n                            ego_vehicle_found = True\n                            self.ego_vehicles.append(carla_vehicle)\n                            break\n                    if not ego_vehicle_found:\n                        ego_vehicle_missing = True\n                        break\n\n            for i, _ in enumerate(self.ego_vehicles):\n                self.ego_vehicles[i].set_transform(ego_vehicles[i].transform)\n                self.ego_vehicles[i].set_target_velocity(carla.Vector3D())\n                self.ego_vehicles[i].set_target_angular_velocity(carla.Vector3D())\n                self.ego_vehicles[i].apply_control(carla.VehicleControl())\n                CarlaDataProvider.register_actor(self.ego_vehicles[i], ego_vehicles[i].transform)\n\n        # sync state\n        if CarlaDataProvider.is_sync_mode():\n            self.world.tick()\n        else:\n            self.world.wait_for_tick()\n\n    def _analyze_scenario(self, config):\n        \"\"\"\n        Provide feedback about success/failure of a scenario\n        \"\"\"\n\n        # Create the filename\n        current_time = str(datetime.now().strftime('%Y-%m-%d-%H-%M-%S'))\n        junit_filename = None\n        json_filename = None\n        config_name = config.name\n        if self._args.outputDir != '':\n            config_name = os.path.join(self._args.outputDir, config_name)\n\n        if self._args.junit:\n            junit_filename = config_name + current_time + \".xml\"\n        if self._args.json:\n            json_filename = config_name + current_time + \".json\"\n        filename = None\n        if self._args.file:\n            filename = config_name + current_time + \".txt\"\n\n        if not self.manager.analyze_scenario(self._args.output, filename, junit_filename, json_filename):\n            print(\"All scenario tests were passed successfully!\")\n        else:\n            print(\"Not all scenario tests were successful\")\n            if not (self._args.output or filename or junit_filename):\n                print(\"Please run with --output for further information\")\n\n    def _record_criteria(self, criteria, name):\n        \"\"\"\n        Filter the JSON serializable attributes of the criterias and\n        dumps them into a file. This will be used by the metrics manager,\n        in case the user wants specific information about the criterias.\n        \"\"\"\n        file_name = name[:-4] + \".json\"\n\n        # Filter the attributes that aren't JSON serializable\n        with open('temp.json', 'w', encoding='utf-8') as fp:\n\n            criteria_dict = {}\n            for criterion in criteria:\n\n                criterion_dict = criterion.__dict__\n                criteria_dict[criterion.name] = {}\n\n                for key in criterion_dict:\n                    if key != \"name\":\n                        try:\n                            key_dict = {key: criterion_dict[key]}\n                            json.dump(key_dict, fp, sort_keys=False, indent=4)\n                            criteria_dict[criterion.name].update(key_dict)\n                        except TypeError:\n                            pass\n\n        os.remove('temp.json')\n\n        # Save the criteria dictionary into a .json file\n        with open(file_name, 'w', encoding='utf-8') as fp:\n            json.dump(criteria_dict, fp, sort_keys=False, indent=4)\n\n    def _load_and_wait_for_world(self, town, ego_vehicles=None):\n        \"\"\"\n        Load a new CARLA world and provide data to CarlaDataProvider\n        \"\"\"\n\n        if self._args.reloadWorld:\n            self.world = self.client.load_world(town)\n        else:\n            # if the world should not be reloaded, wait at least until all ego vehicles are ready\n            ego_vehicle_found = False\n            if self._args.waitForEgo:\n                while not ego_vehicle_found and not self._shutdown_requested:\n                    vehicles = self.client.get_world().get_actors().filter('vehicle.*')\n                    for ego_vehicle in ego_vehicles:\n                        ego_vehicle_found = False\n                        for vehicle in vehicles:\n                            if vehicle.attributes['role_name'] == ego_vehicle.rolename:\n                                ego_vehicle_found = True\n                                break\n                        if not ego_vehicle_found:\n                            print(\"Not all ego vehicles ready. Waiting ... \")\n                            time.sleep(1)\n                            break\n\n        self.world = self.client.get_world()\n\n        if self._args.sync:\n            settings = self.world.get_settings()\n            settings.synchronous_mode = True\n            settings.fixed_delta_seconds = 1.0 / self.frame_rate\n            self.world.apply_settings(settings)\n\n        CarlaDataProvider.set_client(self.client)\n        CarlaDataProvider.set_world(self.world)\n\n        # Wait for the world to be ready\n        if CarlaDataProvider.is_sync_mode():\n            self.world.tick()\n        else:\n            self.world.wait_for_tick()\n\n        map_name = CarlaDataProvider.get_map().name.split('/')[-1]\n        if map_name not in (town, \"OpenDriveMap\"):\n            print(\"The CARLA server uses the wrong map: {}\".format(map_name))\n            print(\"This scenario requires to use map: {}\".format(town))\n            return False\n\n        return True\n\n    def _load_and_run_scenario(self, config):\n        \"\"\"\n        Load and run the scenario given by config\n        \"\"\"\n        result = False\n        if not self._load_and_wait_for_world(config.town, config.ego_vehicles):\n            self._cleanup()\n            return False\n\n        if self._args.agent:\n            agent_class_name = self.module_agent.__name__.title().replace('_', '')\n            try:\n                self.agent_instance = getattr(self.module_agent, agent_class_name)(self._args.agentConfig)\n                config.agent = self.agent_instance\n            except Exception as e:          # pylint: disable=broad-except\n                traceback.print_exc()\n                print(\"Could not setup required agent due to {}\".format(e))\n                self._cleanup()\n                return False\n\n        CarlaDataProvider.set_traffic_manager_port(int(self._args.trafficManagerPort))\n        tm = self.client.get_trafficmanager(int(self._args.trafficManagerPort))\n        tm.set_random_device_seed(int(self._args.trafficManagerSeed))\n        if self._args.sync:\n            tm.set_synchronous_mode(True)\n\n        # Prepare scenario\n        print(\"Preparing scenario: \" + config.name)\n        try:\n            self._prepare_ego_vehicles(config.ego_vehicles)\n            if self._args.openscenario:\n                scenario = OpenScenario(world=self.world,\n                                        ego_vehicles=self.ego_vehicles,\n                                        config=config,\n                                        config_file=self._args.openscenario,\n                                        timeout=100000)\n            elif self._args.route:\n                scenario = RouteScenario(world=self.world,\n                                         config=config,\n                                         debug_mode=self._args.debug)\n            else:\n                scenario_class = self._get_scenario_class_or_fail(config.type)\n                scenario = scenario_class(world=self.world,\n                                          ego_vehicles=self.ego_vehicles,\n                                          config=config,\n                                          randomize=self._args.randomize,\n                                          debug_mode=self._args.debug)\n        except Exception as exception:                  # pylint: disable=broad-except\n            print(\"The scenario cannot be loaded\")\n            traceback.print_exc()\n            print(exception)\n            self._cleanup()\n            return False\n\n        try:\n            if self._args.record:\n                recorder_name = \"{}/{}/{}.log\".format(\n                    os.getenv('SCENARIO_RUNNER_ROOT', \"./\"), self._args.record, config.name)\n                self.client.start_recorder(recorder_name, True)\n\n            # Load scenario and run it\n            self.manager.load_scenario(scenario, self.agent_instance)\n            self.manager.run_scenario()\n\n            # Provide outputs if required\n            self._analyze_scenario(config)\n\n            # Remove all actors, stop the recorder and save all criterias (if needed)\n            scenario.remove_all_actors()\n            if self._args.record:\n                self.client.stop_recorder()\n                self._record_criteria(self.manager.scenario.get_criteria(), recorder_name)\n\n            result = True\n\n        except Exception as e:              # pylint: disable=broad-except\n            traceback.print_exc()\n            print(e)\n            result = False\n\n        self._cleanup()\n        return result\n\n    def _run_scenarios(self):\n        \"\"\"\n        Run conventional scenarios (e.g. implemented using the Python API of ScenarioRunner)\n        \"\"\"\n        result = False\n\n        # Load the scenario configurations provided in the config file\n        scenario_configurations = ScenarioConfigurationParser.parse_scenario_configuration(\n            self._args.scenario,\n            self._args.configFile)\n        if not scenario_configurations:\n            print(\"Configuration for scenario {} cannot be found!\".format(self._args.scenario))\n            return result\n\n        # Execute each configuration\n        for config in scenario_configurations:\n            for _ in range(self._args.repetitions):\n                self.finished = False\n                result = self._load_and_run_scenario(config)\n\n            self._cleanup()\n        return result\n\n    def _run_route(self):\n        \"\"\"\n        Run the route scenario\n        \"\"\"\n        result = False\n\n        # retrieve routes\n        route_configurations = RouteParser.parse_routes_file(self._args.route, self._args.route_id)\n\n        for config in route_configurations:\n            for _ in range(self._args.repetitions):\n                result = self._load_and_run_scenario(config)\n\n                self._cleanup()\n        return result\n\n    def _run_openscenario(self):\n        \"\"\"\n        Run a scenario based on OpenSCENARIO\n        \"\"\"\n\n        # Load the scenario configurations provided in the config file\n        if not os.path.isfile(self._args.openscenario):\n            print(\"File does not exist\")\n            self._cleanup()\n            return False\n\n        openscenario_params = {}\n        if self._args.openscenarioparams is not None:\n            for entry in self._args.openscenarioparams.split(','):\n                [key, val] = [m.strip() for m in entry.split(':')]\n                openscenario_params[key] = val\n        config = OpenScenarioConfiguration(self._args.openscenario, self.client, openscenario_params)\n\n        result = self._load_and_run_scenario(config)\n        self._cleanup()\n        return result\n\n    def run(self):\n        \"\"\"\n        Run all scenarios according to provided commandline args\n        \"\"\"\n        result = True\n        if self._args.openscenario:\n            result = self._run_openscenario()\n        elif self._args.route:\n            result = self._run_route()\n        else:\n            result = self._run_scenarios()\n\n        print(\"No more scenarios .... Exiting\")\n        return result\n\n\ndef main():\n    \"\"\"\n    main function\n    \"\"\"\n    description = (\"CARLA Scenario Runner: Setup, Run and Evaluate scenarios using CARLA\\n\"\n                   \"Current version: \" + VERSION)\n\n    # pylint: disable=line-too-long\n    parser = argparse.ArgumentParser(description=description,\n                                     formatter_class=RawTextHelpFormatter)\n    parser.add_argument('-v', '--version', action='version', version='%(prog)s ' + VERSION)\n    parser.add_argument('--host', default='127.0.0.1',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', default='2000',\n                        help='TCP port to listen to (default: 2000)')\n    parser.add_argument('--timeout', default=\"10.0\",\n                        help='Set the CARLA client timeout value in seconds')\n    parser.add_argument('--trafficManagerPort', default='8000',\n                        help='Port to use for the TrafficManager (default: 8000)')\n    parser.add_argument('--trafficManagerSeed', default='0',\n                        help='Seed used by the TrafficManager (default: 0)')\n    parser.add_argument('--sync', action='store_true',\n                        help='Forces the simulation to run synchronously')\n    parser.add_argument('--list', action=\"store_true\", help='List all supported scenarios and exit')\n\n    parser.add_argument(\n        '--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')\n    parser.add_argument('--openscenario', help='Provide an OpenSCENARIO definition')\n    parser.add_argument('--openscenarioparams', help='Overwrited for OpenSCENARIO ParameterDeclaration')\n    parser.add_argument('--route', help='Run a route as a scenario', type=str)\n    parser.add_argument('--route-id', help='Run a specific route inside that \\'route\\' file', default='', type=str)\n    parser.add_argument(\n        '--agent', help=\"Agent used to execute the route. Not compatible with non-route-based scenarios.\")\n    parser.add_argument('--agentConfig', type=str, help=\"Path to Agent's configuration file\", default=\"\")\n\n    parser.add_argument('--output', action=\"store_true\", help='Provide results on stdout')\n    parser.add_argument('--file', action=\"store_true\", help='Write results into a txt file')\n    parser.add_argument('--junit', action=\"store_true\", help='Write results into a junit file')\n    parser.add_argument('--json', action=\"store_true\", help='Write results into a JSON file')\n    parser.add_argument('--outputDir', default='', help='Directory for output files (default: this directory)')\n\n    parser.add_argument('--configFile', default='', help='Provide an additional scenario configuration file (*.xml)')\n    parser.add_argument('--additionalScenario', default='', help='Provide additional scenario implementations (*.py)')\n\n    parser.add_argument('--debug', action=\"store_true\", help='Run with debug output')\n    parser.add_argument('--reloadWorld', action=\"store_true\",\n                        help='Reload the CARLA world before starting a scenario (default=True)')\n    parser.add_argument('--record', type=str, default='',\n                        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.')\n    parser.add_argument('--randomize', action=\"store_true\", help='Scenario parameters are randomized')\n    parser.add_argument('--repetitions', default=1, type=int, help='Number of scenario executions')\n    parser.add_argument('--waitForEgo', action=\"store_true\", help='Connect the scenario to an existing ego vehicle')\n\n    arguments = parser.parse_args()\n    # pylint: enable=line-too-long\n\n    if arguments.list:\n        print(\"Currently the following scenarios are supported:\")\n        print(*ScenarioConfigurationParser.get_list_of_scenarios(arguments.configFile), sep='\\n')\n        return 1\n\n    if not arguments.scenario and not arguments.openscenario and not arguments.route:\n        print(\"Please specify either a scenario or use the route mode\\n\\n\")\n        parser.print_help(sys.stdout)\n        return 1\n\n    if arguments.route and (arguments.openscenario or arguments.scenario):\n        print(\"The route mode cannot be used together with a scenario (incl. OpenSCENARIO)'\\n\\n\")\n        parser.print_help(sys.stdout)\n        return 1\n\n    if arguments.agent and (arguments.openscenario or arguments.scenario):\n        print(\"Agents are currently only compatible with route scenarios'\\n\\n\")\n        parser.print_help(sys.stdout)\n        return 1\n\n    if arguments.openscenarioparams and not arguments.openscenario:\n        print(\"WARN: Ignoring --openscenarioparams when --openscenario is not specified\")\n\n    if arguments.route:\n        arguments.reloadWorld = True\n\n    if arguments.agent:\n        arguments.sync = True\n\n    scenario_runner = None\n    result = True\n    try:\n        scenario_runner = ScenarioRunner(arguments)\n        result = scenario_runner.run()\n    except Exception:   # pylint: disable=broad-except\n        traceback.print_exc()\n\n    finally:\n        if scenario_runner is not None:\n            scenario_runner.destroy()\n            del scenario_runner\n    return not result\n\n\nif __name__ == \"__main__\":\n    sys.exit(main())\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/agent_wrapper.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nWrapper for autonomous agents required for tracking and checking of used sensors\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom srunner.autoagents.sensor_interface import CallBack\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass AgentWrapper(object):\n\n    \"\"\"\n    Wrapper for autonomous agents required for tracking and checking of used sensors\n    \"\"\"\n\n    _agent = None\n    _sensors_list = []\n\n    def __init__(self, agent):\n        \"\"\"\n        Set the autonomous agent\n        \"\"\"\n        self._agent = agent\n\n    def __call__(self):\n        \"\"\"\n        Pass the call directly to the agent\n        \"\"\"\n        return self._agent()\n\n    def setup_sensors(self, vehicle, debug_mode=False):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        bp_library = CarlaDataProvider.get_world().get_blueprint_library()\n        for sensor_spec in self._agent.sensors():\n            # These are the sensors spawned on the carla world\n            bp = bp_library.find(str(sensor_spec['type']))\n            if sensor_spec['type'].startswith('sensor.camera'):\n                bp.set_attribute('image_size_x', str(sensor_spec['width']))\n                bp.set_attribute('image_size_y', str(sensor_spec['height']))\n                bp.set_attribute('fov', str(sensor_spec['fov']))\n                sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                 z=sensor_spec['z'])\n                sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                 roll=sensor_spec['roll'],\n                                                 yaw=sensor_spec['yaw'])\n            elif sensor_spec['type'].startswith('sensor.lidar'):\n                bp.set_attribute('range', str(sensor_spec['range']))\n                bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency']))\n                bp.set_attribute('channels', str(sensor_spec['channels']))\n                bp.set_attribute('upper_fov', str(sensor_spec['upper_fov']))\n                bp.set_attribute('lower_fov', str(sensor_spec['lower_fov']))\n                bp.set_attribute('points_per_second', str(sensor_spec['points_per_second']))\n                sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                 z=sensor_spec['z'])\n                sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                 roll=sensor_spec['roll'],\n                                                 yaw=sensor_spec['yaw'])\n            elif sensor_spec['type'].startswith('sensor.other.gnss'):\n                sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                 z=sensor_spec['z'])\n                sensor_rotation = carla.Rotation()\n\n            # create sensor\n            sensor_transform = carla.Transform(sensor_location, sensor_rotation)\n            sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)\n            # setup callback\n            sensor.listen(CallBack(sensor_spec['id'], sensor, self._agent.sensor_interface))\n            self._sensors_list.append(sensor)\n\n        # Tick once to spawn the sensors\n        CarlaDataProvider.get_world().tick()\n\n    def cleanup(self):\n        \"\"\"\n        Remove and destroy all sensors\n        \"\"\"\n        for i, _ in enumerate(self._sensors_list):\n            if self._sensors_list[i] is not None:\n                self._sensors_list[i].stop()\n                self._sensors_list[i].destroy()\n                self._sensors_list[i] = None\n        self._sensors_list = []\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/autonomous_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the base class for all autonomous agents\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom srunner.autoagents.sensor_interface import SensorInterface\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.tools.route_manipulation import downsample_route\n\n\nclass AutonomousAgent(object):\n\n    \"\"\"\n    Autonomous agent base class. All user agents have to be derived from this class\n    \"\"\"\n\n    def __init__(self, path_to_conf_file):\n        #  current global plans to reach a destination\n        self._global_plan = None\n        self._global_plan_world_coord = None\n\n        # this data structure will contain all sensor data\n        self.sensor_interface = SensorInterface()\n\n        # agent's initialization\n        self.setup(path_to_conf_file)\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Initialize everything needed by your agent and set the track attribute to the right type:\n        \"\"\"\n        pass\n\n    def sensors(self):  # pylint: disable=no-self-use\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n\n        \"\"\"\n        sensors = []\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        :return: control\n        \"\"\"\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        pass\n\n    def __call__(self):\n        \"\"\"\n        Execute the agent call, e.g. agent()\n        Returns the next vehicle controls\n        \"\"\"\n        input_data = self.sensor_interface.get_data()\n\n        timestamp = GameTime.get_time()\n        wallclock = GameTime.get_wallclocktime()\n        print('======[Agent] Wallclock_time = {} / Sim_time = {}'.format(wallclock, timestamp), flush=True)\n\n        control = self.run_step(input_data, timestamp)\n        control.manual_gear_shift = False\n\n        return control\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        \"\"\"\n        Set the plan (route) for the agent\n        \"\"\"\n\n        ds_ids = downsample_route(global_plan_world_coord, 1)\n        self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1])\n                                         for x in ds_ids]\n        self._global_plan = [global_plan_gps[x] for x in ds_ids]\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/dummy_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a dummy agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\n\n\nclass DummyAgent(AutonomousAgent):\n\n    \"\"\"\n    Dummy autonomous agent to control the ego vehicle\n    \"\"\"\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n\n\n        \"\"\"\n        sensors = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'},\n                   {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n                    'yaw': -45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'},\n                   {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0,\n                    'width': 800, 'height': 600, 'fov': 100, 'id': 'Right'},\n                   {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n                    'yaw': -45.0, 'id': 'LIDAR'},\n                   {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'},\n                   {'type': 'sensor.can_bus', 'reading_frequency': 25, 'id': 'can_bus'},\n                   {'type': 'sensor.hd_map', 'reading_frequency': 1, 'id': 'hdmap'},\n                   ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        print(\"=====================>\")\n        for key, val in input_data.items():\n            if hasattr(val[1], 'shape'):\n                shape = val[1].shape\n                print(\"[{} -- {:06d}] with shape {}\".format(key, val[0], shape))\n            else:\n                print(\"[{} -- {:06d}] \".format(key, val[0]))\n        print(\"<=====================\")\n\n        # DO SOMETHING SMART\n\n        # RETURN CONTROL\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/human_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a human agent to control the ego vehicle via keyboard\n\"\"\"\n\nfrom __future__ import print_function\n\nimport json\n\ntry:\n    import pygame\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_UP\n    from pygame.locals import K_a\n    from pygame.locals import K_d\n    from pygame.locals import K_s\n    from pygame.locals import K_w\n    from pygame.locals import K_q\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\nimport carla\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\n\n\nclass HumanInterface(object):\n\n    \"\"\"\n    Class to control a vehicle manually for debugging purposes\n    \"\"\"\n\n    def __init__(self, width, height):\n        self._width = width\n        self._height = height\n        self._surface = None\n\n        pygame.init()\n        pygame.font.init()\n        self._clock = pygame.time.Clock()\n        self._display = pygame.display.set_mode((self._width, self._height), pygame.HWSURFACE | pygame.DOUBLEBUF)\n        pygame.display.set_caption(\"Human Agent\")\n\n    def run_interface(self, input_data):\n        \"\"\"\n        Run the GUI\n        \"\"\"\n        # process sensor data\n        image_center = input_data['Center'][1][:, :, -2::-1]\n\n        # display image\n        self._surface = pygame.surfarray.make_surface(image_center.swapaxes(0, 1))\n        if self._surface is not None:\n            self._display.blit(self._surface, (0, 0))\n        pygame.display.flip()\n\n    def quit_interface(self):\n        \"\"\"\n        Stops the pygame window\n        \"\"\"\n        pygame.quit()\n\n\nclass HumanAgent(AutonomousAgent):\n\n    \"\"\"\n    Human agent to control the ego vehicle via keyboard\n    \"\"\"\n\n    current_control = None\n    agent_engaged = False\n    prev_timestamp = 0\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n\n        self.agent_engaged = False\n        self.camera_width = 800\n        self.camera_height = 500\n\n        self._hic = HumanInterface(self.camera_width, self.camera_height)\n        self._controller = KeyboardControl(path_to_conf_file)\n        self.prev_timestamp = 0\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            ['sensor.camera.rgb', {'x':x_rel, 'y': y_rel, 'z': z_rel,\n                                   'yaw': yaw, 'pitch': pitch, 'roll': roll,\n                                   'width': width, 'height': height, 'fov': fov}, 'Sensor01'],\n            ['sensor.camera.rgb', {'x':x_rel, 'y': y_rel, 'z': z_rel,\n                                   'yaw': yaw, 'pitch': pitch, 'roll': roll,\n                                   'width': width, 'height': height, 'fov': fov}, 'Sensor02'],\n\n            ['sensor.lidar.ray_cast', {'x':x_rel, 'y': y_rel, 'z': z_rel,\n                                       'yaw': yaw, 'pitch': pitch, 'roll': roll}, 'Sensor03']\n        ]\n\n        \"\"\"\n        sensors = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': self.camera_width, 'height': self.camera_height, 'fov': 100, 'id': 'Center'},\n                   {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'}\n                   ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        self.agent_engaged = True\n        self._hic.run_interface(input_data)\n\n        control = self._controller.parse_events(timestamp - self.prev_timestamp)\n        self.prev_timestamp = timestamp\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Cleanup\n        \"\"\"\n        self._hic.quit_interface = True\n\n\nclass KeyboardControl(object):\n\n    \"\"\"\n    Keyboard control for the human agent\n    \"\"\"\n\n    def __init__(self, path_to_conf_file):\n        \"\"\"\n        Init\n        \"\"\"\n        self._control = carla.VehicleControl()\n        self._steer_cache = 0.0\n        self._clock = pygame.time.Clock()\n\n        # Get the mode\n        if path_to_conf_file:\n\n            with (open(path_to_conf_file, \"r\")) as f:\n                lines = f.read().split(\"\\n\")\n                self._mode = lines[0].split(\" \")[1]\n                self._endpoint = lines[1].split(\" \")[1]\n\n            # Get the needed vars\n            if self._mode == \"log\":\n                self._log_data = {'records': []}\n\n            elif self._mode == \"playback\":\n                self._index = 0\n                self._control_list = []\n\n                with open(self._endpoint) as fd:\n                    try:\n                        self._records = json.load(fd)\n                        self._json_to_control()\n                    except ValueError:\n                        # Moving to Python 3.5+ this can be replaced with json.JSONDecodeError\n                        pass\n        else:\n            self._mode = \"normal\"\n            self._endpoint = None\n\n    def _json_to_control(self):\n        \"\"\"\n        Parses the json file into a list of carla.VehicleControl\n        \"\"\"\n\n        # transform strs into VehicleControl commands\n        for entry in self._records['records']:\n            control = carla.VehicleControl(throttle=entry['control']['throttle'],\n                                           steer=entry['control']['steer'],\n                                           brake=entry['control']['brake'],\n                                           hand_brake=entry['control']['hand_brake'],\n                                           reverse=entry['control']['reverse'],\n                                           manual_gear_shift=entry['control']['manual_gear_shift'],\n                                           gear=entry['control']['gear'])\n            self._control_list.append(control)\n\n    def parse_events(self, timestamp):\n        \"\"\"\n        Parse the keyboard events and set the vehicle controls accordingly\n        \"\"\"\n        # Move the vehicle\n        if self._mode == \"playback\":\n            self._parse_json_control()\n        else:\n            self._parse_vehicle_keys(pygame.key.get_pressed(), timestamp * 1000)\n\n        # Record the control\n        if self._mode == \"log\":\n            self._record_control()\n\n        return self._control\n\n    def _parse_vehicle_keys(self, keys, milliseconds):\n        \"\"\"\n        Calculate new vehicle controls based on input keys\n        \"\"\"\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                return\n            elif event.type == pygame.KEYUP:\n                if event.key == K_q:\n                    self._control.gear = 1 if self._control.reverse else -1\n                    self._control.reverse = self._control.gear < 0\n\n        if keys[K_UP] or keys[K_w]:\n            self._control.throttle = 0.6\n        else:\n            self._control.throttle = 0.0\n\n        steer_increment = 3e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n\n        self._steer_cache = min(0.95, max(-0.95, self._steer_cache))\n        self._control.steer = round(self._steer_cache, 1)\n        self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0\n        self._control.hand_brake = keys[K_SPACE]\n\n    def _parse_json_control(self):\n        \"\"\"\n        Gets the control corresponding to the current frame\n        \"\"\"\n\n        if self._index < len(self._control_list):\n            self._control = self._control_list[self._index]\n            self._index += 1\n        else:\n            print(\"JSON file has no more entries\")\n\n    def _record_control(self):\n        \"\"\"\n        Saves the list of control into a json file\n        \"\"\"\n\n        new_record = {\n            'control': {\n                'throttle': self._control.throttle,\n                'steer': self._control.steer,\n                'brake': self._control.brake,\n                'hand_brake': self._control.hand_brake,\n                'reverse': self._control.reverse,\n                'manual_gear_shift': self._control.manual_gear_shift,\n                'gear': self._control.gear\n            }\n        }\n\n        self._log_data['records'].append(new_record)\n\n    def __del__(self):\n        \"\"\"\n        Delete method\n        \"\"\"\n        # Get ready to log user commands\n        if self._mode == \"log\" and self._log_data:\n            with open(self._endpoint, 'w') as fd:\n                json.dump(self._log_data, fd, indent=4, sort_keys=True)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/human_agent_config.txt",
    "content": "mode: log                      # Either 'log' or 'playback'\nfile: test.json                     # path to the file with the controls\n\n\nThis is the configuration file of the human agent. This agent incorporates two modes.\nThe log mode parses the controls given to the vehicle into a dictionary and records them into a .json file.\nThis file can be read by the playback mode to control the vehicle in the same way, resulting in a deterministic agent.\nThe file name can be chosen, and is the second argument of this config file.\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/npc_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an NPC agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass NpcAgent(AutonomousAgent):\n\n    \"\"\"\n    NPC autonomous agent to control the ego vehicle\n    \"\"\"\n\n    _agent = None\n    _route_assigned = False\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self._agent = None\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n        ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        if not self._agent:\n\n            # Search for the ego actor\n            hero_actor = None\n            for actor in CarlaDataProvider.get_world().get_actors():\n                if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero':\n                    hero_actor = actor\n                    break\n\n            if not hero_actor:\n                return carla.VehicleControl()\n\n            # Add an agent that follows the route to the ego\n            self._agent = BasicAgent(hero_actor, 30)\n\n            plan = []\n            prev_wp = None\n            for transform, _ in self._global_plan_world_coord:\n                wp = CarlaDataProvider.get_map().get_waypoint(transform.location)\n                if prev_wp:\n                    plan.extend(self._agent.trace_route(prev_wp, wp))\n                prev_wp = wp\n\n            self._agent.set_global_plan(plan)\n\n            return carla.VehicleControl()\n\n        else:\n            return self._agent.run_step()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/ros_agent.py",
    "content": "#!/usr/bin/env python\n#\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n#\n\n\"\"\"\nThis module provides a ROS autonomous agent interface to control the ego vehicle via a ROS stack\n\"\"\"\n\nimport math\nimport os\nimport subprocess\nimport signal\nimport threading\nimport time\n\nimport numpy\n\nimport carla\n\nimport rospy\nfrom cv_bridge import CvBridge\nfrom geometry_msgs.msg import PoseStamped\nfrom nav_msgs.msg import Odometry, Path\nfrom rosgraph_msgs.msg import Clock\nfrom sensor_msgs.msg import Image, PointCloud2, NavSatFix, NavSatStatus, CameraInfo\nfrom sensor_msgs.point_cloud2 import create_cloud_xyz32\nfrom std_msgs.msg import Header, String\nimport tf\n# pylint: disable=line-too-long\nfrom carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, CarlaEgoVehicleControl, CarlaWorldInfo\n# pylint: enable=line-too-long\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\n\n\nclass RosAgent(AutonomousAgent):\n\n    \"\"\"\n    Base class for ROS-based stacks.\n\n    Derive from it and implement the sensors() method.\n\n    Please define TEAM_CODE_ROOT in your environment.\n    The stack is started by executing $TEAM_CODE_ROOT/start.sh\n\n    The sensor data is published on similar topics as with the carla-ros-bridge. You can find details about\n    the utilized datatypes there.\n\n    This agent expects a roscore to be running.\n    \"\"\"\n\n    speed = None\n    current_control = None\n    stack_process = None\n    timestamp = None\n    current_map_name = None\n    step_mode_possible = None\n    vehicle_info_publisher = None\n    global_plan_published = None\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        setup agent\n        \"\"\"\n        self.stack_thread = None\n\n        # get start_script from environment\n        team_code_path = os.environ['TEAM_CODE_ROOT']\n        if not team_code_path or not os.path.exists(team_code_path):\n            raise IOError(\"Path '{}' defined by TEAM_CODE_ROOT invalid\".format(team_code_path))\n        start_script = \"{}/start.sh\".format(team_code_path)\n        if not os.path.exists(start_script):\n            raise IOError(\"File '{}' defined by TEAM_CODE_ROOT invalid\".format(start_script))\n\n        # set use_sim_time via commandline before init-node\n        process = subprocess.Popen(\n            \"rosparam set use_sim_time true\", shell=True, stderr=subprocess.STDOUT, stdout=subprocess.PIPE)\n        process.wait()\n        if process.returncode:\n            raise RuntimeError(\"Could not set use_sim_time\")\n\n        # initialize ros node\n        rospy.init_node('ros_agent', anonymous=True)\n\n        # publish first clock value '0'\n        self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10, latch=True)\n        self.clock_publisher.publish(Clock(rospy.Time.from_sec(0)))\n\n        # execute script that starts the ad stack (remains running)\n        rospy.loginfo(\"Executing stack...\")\n        self.stack_process = subprocess.Popen(start_script, shell=True, preexec_fn=os.setpgrp)\n\n        self.vehicle_control_event = threading.Event()\n        self.timestamp = None\n        self.speed = 0\n        self.global_plan_published = False\n\n        self.vehicle_info_publisher = None\n        self.vehicle_status_publisher = None\n        self.odometry_publisher = None\n        self.world_info_publisher = None\n        self.map_file_publisher = None\n        self.current_map_name = None\n        self.tf_broadcaster = None\n        self.step_mode_possible = False\n\n        self.vehicle_control_subscriber = rospy.Subscriber(\n            '/carla/ego_vehicle/vehicle_control_cmd', CarlaEgoVehicleControl, self.on_vehicle_control)\n\n        self.current_control = carla.VehicleControl()\n\n        self.waypoint_publisher = rospy.Publisher(\n            '/carla/ego_vehicle/waypoints', Path, queue_size=1, latch=True)\n\n        self.publisher_map = {}\n        self.id_to_sensor_type_map = {}\n        self.id_to_camera_info_map = {}\n        self.cv_bridge = CvBridge()\n\n        # setup ros publishers for sensors\n        # pylint: disable=line-too-long\n        for sensor in self.sensors():\n            self.id_to_sensor_type_map[sensor['id']] = sensor['type']\n            if sensor['type'] == 'sensor.camera.rgb':\n                self.publisher_map[sensor['id']] = rospy.Publisher(\n                    '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + \"/image_color\", Image, queue_size=1, latch=True)\n                self.id_to_camera_info_map[sensor['id']] = self.build_camera_info(sensor)\n                self.publisher_map[sensor['id'] + '_info'] = rospy.Publisher(\n                    '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + \"/camera_info\", CameraInfo, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.lidar.ray_cast':\n                self.publisher_map[sensor['id']] = rospy.Publisher(\n                    '/carla/ego_vehicle/lidar/' + sensor['id'] + \"/point_cloud\", PointCloud2, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.other.gnss':\n                self.publisher_map[sensor['id']] = rospy.Publisher(\n                    '/carla/ego_vehicle/gnss/' + sensor['id'] + \"/fix\", NavSatFix, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.can_bus':\n                if not self.vehicle_info_publisher:\n                    self.vehicle_info_publisher = rospy.Publisher(\n                        '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True)\n                if not self.vehicle_status_publisher:\n                    self.vehicle_status_publisher = rospy.Publisher(\n                        '/carla/ego_vehicle/vehicle_status', CarlaEgoVehicleStatus, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.hd_map':\n                if not self.odometry_publisher:\n                    self.odometry_publisher = rospy.Publisher(\n                        '/carla/ego_vehicle/odometry', Odometry, queue_size=1, latch=True)\n                if not self.world_info_publisher:\n                    self.world_info_publisher = rospy.Publisher(\n                        '/carla/world_info', CarlaWorldInfo, queue_size=1, latch=True)\n                if not self.map_file_publisher:\n                    self.map_file_publisher = rospy.Publisher('/carla/map_file', String, queue_size=1, latch=True)\n                if not self.tf_broadcaster:\n                    self.tf_broadcaster = tf.TransformBroadcaster()\n            else:\n                raise TypeError(\"Invalid sensor type: {}\".format(sensor['type']))\n        # pylint: enable=line-too-long\n\n    def destroy(self):\n        \"\"\"\n        Cleanup of all ROS publishers\n        \"\"\"\n        if self.stack_process and self.stack_process.poll() is None:\n            rospy.loginfo(\"Sending SIGTERM to stack...\")\n            os.killpg(os.getpgid(self.stack_process.pid), signal.SIGTERM)\n            rospy.loginfo(\"Waiting for termination of stack...\")\n            self.stack_process.wait()\n            time.sleep(5)\n            rospy.loginfo(\"Terminated stack.\")\n\n        rospy.loginfo(\"Stack is no longer running\")\n        self.world_info_publisher.unregister()\n        self.map_file_publisher.unregister()\n        self.vehicle_status_publisher.unregister()\n        self.vehicle_info_publisher.unregister()\n        self.waypoint_publisher.unregister()\n        self.stack_process = None\n        rospy.loginfo(\"Cleanup finished\")\n\n    def on_vehicle_control(self, data):\n        \"\"\"\n        callback if a new vehicle control command is received\n        \"\"\"\n        cmd = carla.VehicleControl()\n        cmd.throttle = data.throttle\n        cmd.steer = data.steer\n        cmd.brake = data.brake\n        cmd.hand_brake = data.hand_brake\n        cmd.reverse = data.reverse\n        cmd.gear = data.gear\n        cmd.manual_gear_shift = data.manual_gear_shift\n        self.current_control = cmd\n        if not self.vehicle_control_event.is_set():\n            self.vehicle_control_event.set()\n        # After the first vehicle control is sent out, it is possible to use the stepping mode\n        self.step_mode_possible = True\n\n    def build_camera_info(self, attributes):  # pylint: disable=no-self-use\n        \"\"\"\n        Private function to compute camera info\n\n        camera info doesn't change over time\n        \"\"\"\n        camera_info = CameraInfo()\n        # store info without header\n        camera_info.header = None\n        camera_info.width = int(attributes['width'])\n        camera_info.height = int(attributes['height'])\n        camera_info.distortion_model = 'plumb_bob'\n        cx = camera_info.width / 2.0\n        cy = camera_info.height / 2.0\n        fx = camera_info.width / (\n            2.0 * math.tan(float(attributes['fov']) * math.pi / 360.0))\n        fy = fx\n        camera_info.K = [fx, 0, cx, 0, fy, cy, 0, 0, 1]\n        camera_info.D = [0, 0, 0, 0, 0]\n        camera_info.R = [1.0, 0, 0, 0, 1.0, 0, 0, 0, 1.0]\n        camera_info.P = [fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1.0, 0]\n        return camera_info\n\n    def publish_plan(self):\n        \"\"\"\n        publish the global plan\n        \"\"\"\n        msg = Path()\n        msg.header.frame_id = \"/map\"\n        msg.header.stamp = rospy.Time.now()\n        for wp in self._global_plan_world_coord:\n            pose = PoseStamped()\n            pose.pose.position.x = wp[0].location.x\n            pose.pose.position.y = -wp[0].location.y\n            pose.pose.position.z = wp[0].location.z\n            quaternion = tf.transformations.quaternion_from_euler(\n                0, 0, -math.radians(wp[0].rotation.yaw))\n            pose.pose.orientation.x = quaternion[0]\n            pose.pose.orientation.y = quaternion[1]\n            pose.pose.orientation.z = quaternion[2]\n            pose.pose.orientation.w = quaternion[3]\n            msg.poses.append(pose)\n\n        rospy.loginfo(\"Publishing Plan...\")\n        self.waypoint_publisher.publish(msg)\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors\n        \"\"\"\n        raise NotImplementedError(\n            \"This function has to be implemented by the derived classes\")\n\n    def get_header(self):\n        \"\"\"\n        Returns ROS message header\n        \"\"\"\n        header = Header()\n        header.stamp = rospy.Time.from_sec(self.timestamp)\n        return header\n\n    def publish_lidar(self, sensor_id, data):\n        \"\"\"\n        Function to publish lidar data\n        \"\"\"\n        header = self.get_header()\n        header.frame_id = 'ego_vehicle/lidar/{}'.format(sensor_id)\n\n        lidar_data = numpy.frombuffer(\n            data, dtype=numpy.float32)\n        lidar_data = numpy.reshape(\n            lidar_data, (int(lidar_data.shape[0] / 3), 3))\n        # we take the oposite of y axis\n        # (as lidar point are express in left handed coordinate system, and ros need right handed)\n        # we need a copy here, because the data are read only in carla numpy\n        # array\n        lidar_data = -1.0 * lidar_data\n        # we also need to permute x and y\n        lidar_data = lidar_data[..., [1, 0, 2]]\n        msg = create_cloud_xyz32(header, lidar_data)\n        self.publisher_map[sensor_id].publish(msg)\n\n    def publish_gnss(self, sensor_id, data):\n        \"\"\"\n        Function to publish gnss data\n        \"\"\"\n        msg = NavSatFix()\n        msg.header = self.get_header()\n        msg.header.frame_id = 'gps'\n        msg.latitude = data[0]\n        msg.longitude = data[1]\n        msg.altitude = data[2]\n        msg.status.status = NavSatStatus.STATUS_SBAS_FIX\n        # pylint: disable=line-too-long\n        msg.status.service = NavSatStatus.SERVICE_GPS | NavSatStatus.SERVICE_GLONASS | NavSatStatus.SERVICE_COMPASS | NavSatStatus.SERVICE_GALILEO\n        # pylint: enable=line-too-long\n        self.publisher_map[sensor_id].publish(msg)\n\n    def publish_camera(self, sensor_id, data):\n        \"\"\"\n        Function to publish camera data\n        \"\"\"\n        msg = self.cv_bridge.cv2_to_imgmsg(data, encoding='bgra8')\n        # the camera data is in respect to the camera's own frame\n        msg.header = self.get_header()\n        msg.header.frame_id = 'ego_vehicle/camera/rgb/{}'.format(sensor_id)\n\n        cam_info = self.id_to_camera_info_map[sensor_id]\n        cam_info.header = msg.header\n        self.publisher_map[sensor_id + '_info'].publish(cam_info)\n        self.publisher_map[sensor_id].publish(msg)\n\n    def publish_can(self, sensor_id, data):\n        \"\"\"\n        publish can data\n        \"\"\"\n        if not self.vehicle_info_publisher:\n            self.vehicle_info_publisher = rospy.Publisher(\n                '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True)\n            info_msg = CarlaEgoVehicleInfo()\n            for wheel in data['wheels']:\n                wheel_info = CarlaEgoVehicleInfoWheel()\n                wheel_info.tire_friction = wheel['tire_friction']\n                wheel_info.damping_rate = wheel['damping_rate']\n                wheel_info.steer_angle = wheel['steer_angle']\n                wheel_info.disable_steering = wheel['disable_steering']\n                info_msg.wheels.append(wheel_info)\n            info_msg.max_rpm = data['max_rpm']\n            info_msg.moi = data['moi']\n            info_msg.damping_rate_full_throttle = data['damping_rate_full_throttle']\n            info_msg.damping_rate_zero_throttle_clutch_disengaged = data['damping_rate_zero_throttle_clutch_disengaged']\n            info_msg.use_gear_autobox = data['use_gear_autobox']\n            info_msg.clutch_strength = data['clutch_strength']\n            info_msg.mass = data['mass']\n            info_msg.drag_coefficient = data['drag_coefficient']\n            info_msg.center_of_mass.x = data['center_of_mass']['x']\n            info_msg.center_of_mass.y = data['center_of_mass']['y']\n            info_msg.center_of_mass.z = data['center_of_mass']['z']\n            self.vehicle_info_publisher.publish(info_msg)\n        msg = CarlaEgoVehicleStatus()\n        msg.header = self.get_header()\n        msg.velocity = data['speed']\n        self.speed = data['speed']\n        # todo msg.acceleration\n        msg.control.throttle = self.current_control.throttle\n        msg.control.steer = self.current_control.steer\n        msg.control.brake = self.current_control.brake\n        msg.control.hand_brake = self.current_control.hand_brake\n        msg.control.reverse = self.current_control.reverse\n        msg.control.gear = self.current_control.gear\n        msg.control.manual_gear_shift = self.current_control.manual_gear_shift\n\n        self.vehicle_status_publisher.publish(msg)\n\n    def publish_hd_map(self, sensor_id, data):\n        \"\"\"\n        publish hd map data\n        \"\"\"\n        roll = -math.radians(data['transform']['roll'])\n        pitch = -math.radians(data['transform']['pitch'])\n        yaw = -math.radians(data['transform']['yaw'])\n        quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw)\n        x = data['transform']['x']\n        y = -data['transform']['y']\n        z = data['transform']['z']\n\n        if self.odometry_publisher:\n\n            odometry = Odometry()\n            odometry.header.frame_id = 'map'\n            odometry.header.stamp = rospy.Time.from_sec(self.timestamp)\n            odometry.child_frame_id = 'base_link'\n            odometry.pose.pose.position.x = x\n            odometry.pose.pose.position.y = y\n            odometry.pose.pose.position.z = z\n\n            odometry.pose.pose.orientation.x = quat[0]\n            odometry.pose.pose.orientation.y = quat[1]\n            odometry.pose.pose.orientation.z = quat[2]\n            odometry.pose.pose.orientation.w = quat[3]\n\n            odometry.twist.twist.linear.x = self.speed\n            odometry.twist.twist.linear.y = 0\n            odometry.twist.twist.linear.z = 0\n\n            self.odometry_publisher.publish(odometry)\n\n        if self.world_info_publisher:\n            # extract map name\n            map_name = os.path.basename(data['map_file'])[:-4]\n            if self.current_map_name != map_name:\n                self.current_map_name = map_name\n                world_info = CarlaWorldInfo()\n                world_info.map_name = self.current_map_name\n                world_info.opendrive = data['opendrive']\n                self.world_info_publisher.publish(world_info)\n        if self.map_file_publisher:\n            self.map_file_publisher.publish(data['map_file'])\n\n    def use_stepping_mode(self):  # pylint: disable=no-self-use\n        \"\"\"\n        Overload this function to use stepping mode!\n        \"\"\"\n        return False\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        self.vehicle_control_event.clear()\n        self.timestamp = timestamp\n        self.clock_publisher.publish(Clock(rospy.Time.from_sec(timestamp)))\n\n        # check if stack is still running\n        if self.stack_process and self.stack_process.poll() is not None:\n            raise RuntimeError(\"Stack exited with: {} {}\".format(\n                self.stack_process.returncode, self.stack_process.communicate()[0]))\n\n        # publish global plan to ROS once\n        if self._global_plan_world_coord and not self.global_plan_published:\n            self.global_plan_published = True\n            self.publish_plan()\n\n        new_data_available = False\n\n        # publish data of all sensors\n        for key, val in input_data.items():\n            new_data_available = True\n            sensor_type = self.id_to_sensor_type_map[key]\n            if sensor_type == 'sensor.camera.rgb':\n                self.publish_camera(key, val[1])\n            elif sensor_type == 'sensor.lidar.ray_cast':\n                self.publish_lidar(key, val[1])\n            elif sensor_type == 'sensor.other.gnss':\n                self.publish_gnss(key, val[1])\n            elif sensor_type == 'sensor.can_bus':\n                self.publish_can(key, val[1])\n            elif sensor_type == 'sensor.hd_map':\n                self.publish_hd_map(key, val[1])\n            else:\n                raise TypeError(\"Invalid sensor type: {}\".format(sensor_type))\n\n        if self.use_stepping_mode():\n            if self.step_mode_possible and new_data_available:\n                self.vehicle_control_event.wait()\n        # if the stepping mode is not used or active, there is no need to wait here\n\n        return self.current_control\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/autoagents/sensor_interface.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis file containts CallBack class and SensorInterface, responsible of\nhandling the use of sensors for the agents\n\"\"\"\n\nimport copy\nimport logging\n\ntry:\n    from queue import Queue\n    from queue import Empty\nexcept ImportError:\n    from Queue import Queue\n    from Queue import Empty\n\nimport numpy as np\n\nimport carla\n\n\nclass SensorReceivedNoData(Exception):\n\n    \"\"\"\n    Exceptions thrown when the sensors used by the agent take too long to receive data\n    \"\"\"\n\n\nclass CallBack(object):\n\n    \"\"\"\n    Class the sensors listen to in order to receive their data each frame\n    \"\"\"\n\n    def __init__(self, tag, sensor, data_provider):\n        \"\"\"\n        Initializes the call back\n        \"\"\"\n        self._tag = tag\n        self._data_provider = data_provider\n\n        self._data_provider.register_sensor(tag, sensor)\n\n    def __call__(self, data):\n        \"\"\"\n        call function\n        \"\"\"\n        if isinstance(data, carla.Image):\n            self._parse_image_cb(data, self._tag)\n        elif isinstance(data, carla.LidarMeasurement):\n            self._parse_lidar_cb(data, self._tag)\n        elif isinstance(data, carla.RadarMeasurement):\n            self._parse_radar_cb(data, self._tag)\n        elif isinstance(data, carla.GnssMeasurement):\n            self._parse_gnss_cb(data, self._tag)\n        elif isinstance(data, carla.IMUMeasurement):\n            self._parse_imu_cb(data, self._tag)\n        else:\n            logging.error('No callback method for this sensor.')\n\n    # Parsing CARLA physical Sensors\n    def _parse_image_cb(self, image, tag):\n        \"\"\"\n        parses cameras\n        \"\"\"\n        array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n        array = copy.deepcopy(array)\n        array = np.reshape(array, (image.height, image.width, 4))\n        self._data_provider.update_sensor(tag, array, image.frame)\n\n    def _parse_lidar_cb(self, lidar_data, tag):\n        \"\"\"\n        parses lidar sensors\n        \"\"\"\n        points = np.frombuffer(lidar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        self._data_provider.update_sensor(tag, points, lidar_data.frame)\n\n    def _parse_radar_cb(self, radar_data, tag):\n        \"\"\"\n        parses radar sensors\n        \"\"\"\n        # [depth, azimuth, altitute, velocity]\n        points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        points = np.flip(points, 1)\n        self._data_provider.update_sensor(tag, points, radar_data.frame)\n\n    def _parse_gnss_cb(self, gnss_data, tag):\n        \"\"\"\n        parses gnss sensors\n        \"\"\"\n        array = np.array([gnss_data.latitude,\n                          gnss_data.longitude,\n                          gnss_data.altitude], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, gnss_data.frame)\n\n    def _parse_imu_cb(self, imu_data, tag):\n        \"\"\"\n        parses IMU sensors\n        \"\"\"\n        array = np.array([imu_data.accelerometer.x,\n                          imu_data.accelerometer.y,\n                          imu_data.accelerometer.z,\n                          imu_data.gyroscope.x,\n                          imu_data.gyroscope.y,\n                          imu_data.gyroscope.z,\n                          imu_data.compass,\n                          ], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, imu_data.frame)\n\n\nclass SensorInterface(object):\n\n    \"\"\"\n    Class that contains all sensor data\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the class\n        \"\"\"\n        self._sensors_objects = {}\n        self._new_data_buffers = Queue()\n        self._queue_timeout = 30\n\n    def register_sensor(self, tag, sensor):\n        \"\"\"\n        Registers the sensors\n        \"\"\"\n        if tag in self._sensors_objects:\n            raise ValueError(\"Duplicated sensor tag [{}]\".format(tag))\n\n        self._sensors_objects[tag] = sensor\n\n    def update_sensor(self, tag, data, timestamp):\n        \"\"\"\n        Updates the sensor\n        \"\"\"\n        if tag not in self._sensors_objects:\n            raise ValueError(\"The sensor with tag [{}] has not been created!\".format(tag))\n\n        self._new_data_buffers.put((tag, timestamp, data))\n\n    def get_data(self):\n        \"\"\"\n        Returns the data of a sensor\n        \"\"\"\n        try:\n            data_dict = {}\n            while len(data_dict.keys()) < len(self._sensors_objects.keys()):\n\n                sensor_data = self._new_data_buffers.get(True, self._queue_timeout)\n                data_dict[sensor_data[0]] = ((sensor_data[1], sensor_data[2]))\n\n        except Empty:\n            raise SensorReceivedNoData(\"A sensor took too long to send its data\")\n\n        return data_dict\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/ActorFlow.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"EnterActorFlow_1\" type=\"EnterActorFlow\" town=\"Town04\">\n        <ego_vehicle x=\"86.9\" y=\"144.0\" z=\"1.9\" yaw=\"170\" model=\"vehicle.lincoln.mkz_2017\" />\n        <start_actor_flow x=\"16.2\" y=\"220.6\" z=\"0.2\"/>\n        <end_actor_flow x=\"15.50\" y=\"35.0\" z=\"0.2\"/>\n        <flow_speed value=\"30\"/>\n        <source_dist_interval from=\"35\" to=\"50\"/>\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/CatalogExample.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:PedestrianCrossing\" author=\"\"/>\n  <ParameterDeclarations>\n    <ParameterDeclaration name=\"weather\" parameterType=\"string\" value=\"ClearNoon\" />\n    <ParameterDeclaration name=\"carcolor\" parameterType=\"string\" value=\"122,122,122\" />\n  </ParameterDeclarations>\n  <CatalogLocations>\n    <VehicleCatalog>\n      <Directory path=\"catalogs\"/>\n    </VehicleCatalog>\n    <PedestrianCatalog>\n      <Directory path=\"catalogs\"/>\n    </PedestrianCatalog>\n    <MiscObjectCatalog>\n      <Directory path=\"catalogs\"/>\n    </MiscObjectCatalog>\n    <EnvironmentCatalog>\n      <Directory path=\"catalogs\"/>\n    </EnvironmentCatalog>\n    <ManeuverCatalog>\n      <Directory path=\"catalogs\"/>\n    </ManeuverCatalog>\n    <ControllerCatalog>\n      <Directory path=\"catalogs\"/>\n    </ControllerCatalog>\n  </CatalogLocations>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <CatalogReference catalogName=\"VehicleCatalog\" entryName=\"vehicle.volkswagen.t2\"/> \n    </ScenarioObject>\n    <ScenarioObject name=\"vehicle\">\n      <CatalogReference catalogName=\"VehicleCatalog\" entryName=\"vehicle.tesla.model3\">\n        <ParameterAssignments>\n          <ParameterAssignment parameterRef=\"carcolor\" value=\"255,255,0\" />\n        </ParameterAssignments>\n      </CatalogReference>\n    </ScenarioObject>\n    <ScenarioObject name=\"vehicle2\">\n      <CatalogReference catalogName=\"VehicleCatalog\" entryName=\"vehicle.tesla.model3\">\n        <ParameterAssignments>\n          <ParameterAssignment parameterRef=\"carcolor\" value=\"122,122,122\" />\n        </ParameterAssignments>\n      </CatalogReference>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <CatalogReference catalogName=\"PedestrianCatalog\" entryName=\"Pedestrian1\"/>\n    </ScenarioObject>\n    <ScenarioObject name=\"barrier1\">\n      <CatalogReference catalogName=\"MiscObjectCatalog\" entryName=\"Barrier1\"/>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <CatalogReference catalogName=\"EnvironmentCatalog\" entryName=\"$weather\"/>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"170\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <CatalogReference catalogName=\"ControllerCatalog\" entryName=\"ExternalControl\"/>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"vehicle\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"150\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"vehicle2\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"150\" y=\"60\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"110\" y=\"52\" z=\"0.3\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"barrier1\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"100\" y=\"58\" z=\"0\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"AutopilotSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"vehicle\"/>\n          </Actors>\n          <CatalogReference catalogName=\"ManeuverCatalog\" entryName=\"Autopilot\"/>\n        </ManeuverGroup>\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"PedestrianCrossingSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"PedestrianCrossingManeuver\">\n            <Event name=\"PedestrianStartsWalking\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalking\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"3\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"10.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"vehicle\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <ReachPositionCondition tolerance=\"1.0\">\n                          <Position>\n                            <WorldPosition x=\"140\" y=\"55\" z=\"0\"/>\n                          </Position>\n                        </ReachPositionCondition>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianStopsAndWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianStopsAndWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"5\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianWalks\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalking\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWalksAway\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalkingAway\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"6.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"vehicle\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStopsAndWaits\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStopsAndWaits\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalkingAway\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"20.0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/ChangeLane.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"ChangeLane_1\" type=\"ChangeLane\" town=\"Town04\">\n        <ego_vehicle x=\"284.4\" y=\"16.4\" z=\"2.5\" yaw=\"-173\" model=\"vehicle.lincoln.mkz_2017\" />\n\t<!-- spawn actors-->\n\t<other_actor x=\"264.4\" y=\"16.3\" z=\"-500\" yaw=\"-179\" model=\"vehicle.tesla.model3\" />\n\t<other_actor x=\"184.4\" y=\"14.9\" z=\"-500\" yaw=\"-176\" model=\"vehicle.volkswagen.t2\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n    <scenario name=\"ChangeLane_2\" type=\"ChangeLane\" town=\"Town01\">\n        <ego_vehicle x=\"107\" y=\"133.5\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/ChangingWeather.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T12:00:00\" description=\"CARLA:ChangingWeatherExample\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n          <Property name=\"color\" value=\"0,0,255\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"true\" dateTime=\"2020-01-01T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <LanePosition roadId=\"4\" laneId=\"-1\" offset=\"1.0\" s=\"48.58\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"ManeuverSequence\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\"/>\n          <Maneuver name=\"WeatherChange\">\n            <Event name=\"WeatherChangeEvent\" priority=\"overwrite\">\n              <Action name=\"WeatherChangeAction\">\n                <GlobalAction>\n                  <EnvironmentAction>\n                    <Environment name=\"Environment1\">\n                      <TimeOfDay animation=\"true\" dateTime=\"2020-01-01T22:00:00\"/>\n                      <Weather cloudState=\"free\">\n                        <Sun intensity=\"0.05\" azimuth=\"0\" elevation=\"1.31\"/>\n                        <Fog visualRange=\"100000.0\"/>\n                        <Precipitation precipitationType=\"rain\" intensity=\"0.9\"/>\n                      </Weather>\n                      <RoadCondition frictionScaleFactor=\"1.0\"/>\n                    </Environment>\n                  </EnvironmentAction>\n                </GlobalAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"WeatherChangeStartTime\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"20\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n          <Maneuver name=\"DummyManeuver\">\n            <Event name=\"DummyManeuver\" priority=\"overwrite\">\n              <Action name=\"DummyManeuver\"/>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"DummyManeuverStartTime\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"10000000\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"5\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger/>\n      </Act>\n    </Story>\n    <StopTrigger/>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/ControlLoss.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"ControlLoss_1\" type=\"ControlLoss\" town=\"Town01\">\n        <ego_vehicle x=\"392.5\" y=\"195\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_2\" type=\"ControlLoss\" town=\"Town01\">\n        <ego_vehicle x=\"-2.0\" y=\"160\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_3\" type=\"ControlLoss\" town=\"Town01\">\n        <ego_vehicle x=\"168.9\" y=\"59.8\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_4\" type=\"ControlLoss\" town=\"Town02\">\n        <ego_vehicle x=\"27\" y=\"110\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_5\" type=\"ControlLoss\" town=\"Town02\">\n        <ego_vehicle x=\"54.8\" y=\"307.2\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_6\" type=\"ControlLoss\" town=\"Town02\">\n        <ego_vehicle x=\"57.4\" y=\"191.7\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_7\" type=\"ControlLoss\" town=\"Town03\">\n        <ego_vehicle x=\"15\" y=\"207.5\" z=\"2\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_8\" type=\"ControlLoss\" town=\"Town03\">\n        <ego_vehicle x=\"-74\" y=\"-12\" z=\"0.1\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_9\" type=\"ControlLoss\" town=\"Town03\">\n        <ego_vehicle x=\"-85.1\" y=\"-87.4\" z=\"0.3\" yaw=\"89\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_10\" type=\"ControlLoss\" town=\"Town04\">\n        <ego_vehicle x=\"218.4\" y=\"193\" z=\"0\" yaw=\"338\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_11\" type=\"ControlLoss\" town=\"Town04\">\n        <ego_vehicle x=\"-40.4\" y=\"-229.5\" z=\"0\" yaw=\"131\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_12\" type=\"ControlLoss\" town=\"Town04\">\n        <ego_vehicle x=\"-45\" y=\"37.2\" z=\"11\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_13\" type=\"ControlLoss\" town=\"Town05\">\n        <ego_vehicle x=\"90.9\" y=\"-66\" z=\"0\" yaw=\"67\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_14\" type=\"ControlLoss\" town=\"Town05\">\n        <ego_vehicle x=\"-54.7\" y=\"110.9\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_15\" type=\"ControlLoss\" town=\"Town05\">\n        <ego_vehicle x=\"119.1\" y=\"-142.7\" z=\"0.1\" yaw=\"-170\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/CutIn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <!-- scenario name MUST contain 'left' or 'right', defines whether car comes from left or right lane-->\n    <scenario name=\"CutInFrom_left_Lane\" type=\"CutIn\" town=\"Town04\">\n        <ego_vehicle x=\"284.4\" y=\"16.4\" z=\"2.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n\t    <other_actor x=\"324.2\" y=\"20.7\" z=\"-100\" yaw=\"180\" model=\"vehicle.tesla.model3\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n    <scenario name=\"CutInFrom_right_Lane\" type=\"CutIn\" town=\"Town04\">\n        <ego_vehicle x=\"284.4\" y=\"16.4\" z=\"2.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n\t    <other_actor x=\"336.6\" y=\"14.4\" z=\"-100\" yaw=\"180\" model=\"vehicle.tesla.model3\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/CyclistCrossing.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:CyclistCrossing\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.diamondback.century\" vehicleCategory=\"bicycle\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"130\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"95.5\" y=\"41\" z=\"0.2\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"AdversaryAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"vehicle_longitudinal_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"CyclistCrossingManeuver\">\n            <Event name=\"CyclistStartsWalking\" priority=\"overwrite\">\n              <Action name=\"CyclistStartsWalking\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"1.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"14.0\" freespace=\"false\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"CyclistStopsAndWaits\" priority=\"overwrite\">\n              <Action name=\"CyclistStopsAndWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterCyclistStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"CyclistStartsWalking\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"CyclistWalksAway\" priority=\"overwrite\">\n              <Action name=\"CyclistStartsWalkingAway\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"6.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterCyclistStopsAndWaits\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"CyclistStopsAndWaits\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"CyclistWaits\" priority=\"overwrite\">\n              <Action name=\"CyclistWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterCyclistStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"CyclistStartsWalkingAway\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"10.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/FollowLeadingVehicle.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"FollowLeadingVehicle_1\" type=\"FollowLeadingVehicle\" town=\"Town01\">\n        <ego_vehicle x=\"107\" y=\"133\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_1\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town01\">\n        <ego_vehicle x=\"107\" y=\"133.5\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_2\" type=\"FollowLeadingVehicle\" town=\"Town01\">\n        <ego_vehicle x=\"105\" y=\"199.1\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_2\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town01\">\n        <ego_vehicle x=\"105\" y=\"199.1\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_3\" type=\"FollowLeadingVehicle\" town=\"Town02\">\n        <ego_vehicle x=\"28.7\" y=\"302.5\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_3\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town02\">\n        <ego_vehicle x=\"28.7\" y=\"302.5\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_4\" type=\"FollowLeadingVehicle\" town=\"Town03\">\n        <ego_vehicle x=\"120\" y=\"193\" z=\"3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_4\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town03\">\n        <ego_vehicle x=\"150\" y=\"193.2\" z=\"3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_5\" type=\"FollowLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-326.2  \" y=\"435.8\" z=\"0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_5\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"-337  \" y=\"435.8\" z=\"5.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_6\" type=\"FollowLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"44.8\" y=\"-98.3\" z=\"0\" yaw=\"-18\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_6\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"44.8\" y=\"-98.3\" z=\"0\" yaw=\"-18\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_7\" type=\"FollowLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"178\" y=\"-395.8\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_7\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"178\" y=\"-395.8\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_8\" type=\"FollowLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"170.6\" y=\"-182\" z=\"0\" yaw=\"-136\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_8\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town05\">\n         <ego_vehicle x=\"170.6\" y=\"-182.0\" z=\"0\" yaw=\"-137\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_9\" type=\"FollowLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-150\" y=\"-190\" z=\"11\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_9\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town05\">\n        <ego_vehicle x=\"-150\" y=\"-190\" z=\"11\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_10\" type=\"FollowLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-141\" y=\"208.5\" z=\"9\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_10\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town05\">\n        <ego_vehicle x=\"-141\" y=\"208.5\" z=\"9\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_11\" type=\"FollowLeadingVehicle\" town=\"Town02\">\n        <ego_vehicle x=\"137\" y=\"105.3\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_11\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town02\">\n        <ego_vehicle x=\"137\" y=\"105.3\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/FollowLeadingVehicle.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T12:00:00\" description=\"CARLA:FollowLeadingVehicle\" author=\"\"/>\n  <ParameterDeclarations>\n    <ParameterDeclaration name=\"leadingSpeed\" parameterType=\"double\" value=\"2.0\"/>\n  </ParameterDeclarations>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n          <Property name=\"color\" value=\"0,0,255\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n          <Property name=\"color\" value=\"255,0,0\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2020-03-20T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <RoadPosition roadId=\"4\" s=\"48.58\" t=\"2.75\"/>\n<!--                <LanePosition roadId=\"4\" laneId=\"-1\" offset=\"1.0\" s=\"48.58\"/>-->\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <RelativeRoadPosition entityRef=\"hero\" ds=\"50\" dt=\"-1.0\"/>\n<!--                <WorldPosition x=\"190\" y=\"133\" z=\"0\" h=\"0\"/>-->\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"ManeuverSequence\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"FollowLeadingVehicleManeuver\">\n            <Event name=\"LeadingVehicleKeepsVelocity\" priority=\"overwrite\">\n              <Action name=\"LeadingVehicleKeepsVelocity\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"20\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"$leadingSpeed\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartConditionLeadingVehicleKeepsVelocity\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n<!--                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"40.0\" freespace=\"false\" rule=\"lessThan\"/>-->\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"longitudinal\" value=\"40.0\" freespace=\"true\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"LeadingVehicleWaits\" priority=\"overwrite\">\n              <Action name=\"LeadingVehicleWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"AfterLeadingVehicleKeepsVelocity\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"LeadingVehicleKeepsVelocity\" state=\"endTransition\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"1.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"equalTo\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/FreeRide.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"FreeRide_1\" type=\"FreeRide\" town=\"Town01\">\n        <ego_vehicle x=\"312\" y=\"129\" z=\"0\" yaw=\"180\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"FreeRide_2\" type=\"FreeRide\" town=\"Town02\">\n        <ego_vehicle x=\"132\" y=\"215\" z=\"0\" yaw=\"90\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"FreeRide_3\" type=\"FreeRide\" town=\"Town03\">\n        <ego_vehicle x=\"207\" y=\"59\" z=\"0\" yaw=\"180\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"FreeRide_4\" type=\"FreeRide\" town=\"Town04\">\n        <ego_vehicle x=\"269\" y=\"-246\" z=\"0\" yaw=\"0\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"MultiEgo_1\" type=\"FreeRide\" town=\"Town01\">\n        <ego_vehicle x=\"270\" y=\"129\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" rolename=\"hero\"/>\n        <ego_vehicle x=\"100\" y=\"133\" z=\"0\" yaw=\"0\" model=\"vehicle.tesla.model3\" rolename=\"hero2\"/>\n    </scenario>\n    <scenario name=\"MultiEgo_2\" type=\"FreeRide\" town=\"Town03\">\n        <ego_vehicle x=\"207\" y=\"59\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" rolename=\"hero\"/>\n        <ego_vehicle x=\"237\" y=\"-95.0754252474\" z=\"0\" yaw=\"90\" model=\"vehicle.tesla.model3\" rolename=\"hero2\"/>\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/HighwayCutIn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"HighwayCutIn_1\" type=\"HighwayCutIn\" town=\"Highway\">\n        <ego_vehicle x=\"-619.20\" y=\"1055.3\" z=\"0\" yaw=\"-120\" model=\"vehicle.lincoln.mkz_2017\" />\n        <other_actor x=\"-515.70\" y=\"1048.5\" z=\"0\" yaw=\"150\" model=\"vehicle.tesla.model3\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/IntersectionCollisionAvoidance.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:SynchronizeIntersectionEntry\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.audi.tt\" vehicleCategory=\"bicycle\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"140\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"92.5\" y=\"91\" z=\"0.2\" h=\"-1.56\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"AdversaryAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"npc_vehicle_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"SynchronizeManeuver\">\n            <Event name=\"RouteCreation\" priority=\"overwrite\">\n              <Action name=\"RouteCreation\">\n                <PrivateAction>\n                  <RoutingAction>\n                    <AcquirePositionAction>\n                      <Position>\n                        <WorldPosition x=\"92\" y=\"13.5\" z=\"0\" h=\"0\"/>\n                      </Position>\n                    </AcquirePositionAction>\n                  </RoutingAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"0.1\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"ActorSynchronization\" priority=\"overwrite\">\n              <Action name=\"ActorSynchronization\">\n                <PrivateAction>\n                  <SynchronizeAction masterEntityRef=\"hero\">\n                    <TargetPositionMaster>\n                      <WorldPosition x=\"103\" y=\"55\" z=\"0\" h=\"3.14159\"/>\n                    </TargetPositionMaster>\n                    <TargetPosition>\n                      <WorldPosition x=\"92\" y=\"63.8\" z=\"0\" h=\"-1.56\"/>\n                    </TargetPosition>\n                    <FinalSpeed>\n                      <RelativeSpeedToMaster value='3' speedTargetValueType='delta'/>\n                    </FinalSpeed>\n                  </SynchronizeAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"0.1\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"0.1\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/LaneChangeSimple.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:LaneChangeSimple\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town04\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"standing\">\n      <Vehicle name=\"vehicle.volkswagen.t2\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"-9.4\" y=\"-152.8\" z=\"0.5\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"-9.4\" y=\"-71.0\" z=\"0.5\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"standing\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"-8.2\" y=\"29.2\" z=\"0.5\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"LaneChangeSimpleManeuver\">\n            <Event name=\"AdversaryAccelerates\" priority=\"overwrite\">\n              <Action name=\"AdversaryAccelerates\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"50\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"5.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"40.0\" freespace=\"false\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"AdversaryChangesLane\" priority=\"overwrite\">\n              <Action name=\"AdversaryChangesLane\">\n                <PrivateAction>\n                  <LateralAction>\n                    <LaneChangeAction>\n                      <LaneChangeActionDynamics dynamicsShape=\"linear\" value=\"25\" dynamicsDimension=\"distance\"/>\n                      <LaneChangeTarget>\n                        <RelativeTargetLane entityRef=\"adversary\" value=\"-1\"/>\n                      </LaneChangeTarget>\n                    </LaneChangeAction>\n                  </LateralAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"AfterAdversaryAccelerates\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"AdversaryAccelerates\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"1.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"equalTo\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/LeadingVehicle.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"OtherLeadingVehicle_1\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"388.9\" y=\"-140\" z=\"0\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_2\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-510\" y=\"88\" z=\"0\" yaw=\"91\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_3\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"82\" y=\"249.1\" z=\"0\" yaw=\"-33\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_4\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"138.9\" y=\"34.9\" z=\"10\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_5\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-110\" y=\"9.1\" z=\"9.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_6\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-12.5\" y=\"-17\" z=\"0\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_7\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"125.5\" y=\"225.1\" z=\"0\" yaw=\"-25\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_8\" type=\"OtherLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-226.9\" y=\"100\" z=\"11\" yaw=\"-88\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_9\" type=\"OtherLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-10\" y=\"191.1\" z=\"3\" yaw=\"-180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_10\" type=\"OtherLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"188.9\" y=\"-100\" z=\"0\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/NoSignalJunction.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"NoSignalJunctionCrossing\" type=\"NoSignalJunctionCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"-74.32\" y=\"-50\" z=\"0.5\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n        <other_actor x=\"-105\" y=\"-136\" z=\"0.5\" yaw=\"0\" model=\"vehicle.tesla.model3\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/ObjectCrossing.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"StationaryObjectCrossing_1\" type=\"StationaryObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"7.63\" y=\"109.91\" z=\"1.22\" yaw=\"359\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_1\" type=\"DynamicObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"7.63\" y=\"109.91\" z=\"1.22\" yaw=\"359\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_2\" type=\"StationaryObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"180.93\" y=\"105.31\" z=\"1.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_2\" type=\"DynamicObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"180.93\" y=\"105.31\" z=\"1.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_3\" type=\"StationaryObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"239.39\" y=\"113.42\" z=\"2.36\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_3\" type=\"DynamicObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"110\" y=\"129\" z=\"1\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_4\" type=\"StationaryObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"232.36\" y=\"113.29\" z=\"2.46\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_4\" type=\"DynamicObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"232.36\" y=\"113.29\" z=\"2.46\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_5\" type=\"StationaryObjectCrossing\" town=\"Town04\">\n        <ego_vehicle x=\"156.27\" y=\"18.7\" z=\"10.31\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_5\" type=\"DynamicObjectCrossing\" town=\"Town04\">\n        <ego_vehicle x=\"151.8\" y=\"17.7\" z=\"10.31\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_6\" type=\"StationaryObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"-150.70\" y=\"204.97\" z=\"9.65\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_6\" type=\"DynamicObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"-150.70\" y=\"204.97\" z=\"9.65\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_7\" type=\"StationaryObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"149.0\" y=\"-104.4\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_7\" type=\"DynamicObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"149.0\" y=\"-108.4\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_8\" type=\"StationaryObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"138.2\" y=\"116.4\" z=\"0.1\" yaw=\"130\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_8\" type=\"DynamicObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"138.2\" y=\"116.4\" z=\"0.1\" yaw=\"130\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_9\" type=\"DynamicObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"90\" y=\"129\" z=\"1\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ConstructionObstacle\" type=\"ConstructionObstacle\" town=\"Town02\">\n        <ego_vehicle x=\"7.63\" y=\"109.91\" z=\"1.22\" yaw=\"359\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/OppositeDirection.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"ManeuverOppositeDirection_1\" type=\"ManeuverOppositeDirection\" town=\"Town03\">\n        <ego_vehicle x=\"17\" y=\"136\" z=\"2\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ManeuverOppositeDirection_2\" type=\"ManeuverOppositeDirection\" town=\"Town04\">\n        <ego_vehicle x=\"63.3\" y=\"-190.3\" z=\"2\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ManeuverOppositeDirection_3\" type=\"ManeuverOppositeDirection\" town=\"Town04\">\n        <ego_vehicle x=\"192\" y=\"-311.5\" z=\"2\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ManeuverOppositeDirection_4\" type=\"ManeuverOppositeDirection\" town=\"Town05\">\n        <ego_vehicle x=\"94\" y=\"144.7\" z=\"2\" yaw=\"-19\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/OscControllerExample.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T12:00:00\" description=\"CARLA:ControllerExample\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n          <Property name=\"color\" value=\"0,0,255\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n          <Property name=\"color\" value=\"255,0,0\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2020-03-20T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <LanePosition roadId=\"4\" laneId=\"-1\" offset=\"1.0\" s=\"48.58\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"190\" y=\"133\" z=\"0\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"AdversaryAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"npc_vehicle_control\"/>\n                    <Property name=\"an_unused_property\" value=\"an_unused_value\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n          <PrivateAction>\n            <LongitudinalAction>\n              <SpeedAction>\n                <SpeedActionDynamics dynamicsShape=\"step\" value=\"20\" dynamicsDimension=\"distance\"/>\n                <SpeedActionTarget>\n                  <AbsoluteTargetSpeed value=\"1\"/>\n                </SpeedActionTarget>\n              </SpeedAction>\n            </LongitudinalAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"ManeuverSequence\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"FollowLeadingVehicleManeuver\">\n            <Event name=\"LeadingVehicleKeepsVelocity\" priority=\"overwrite\">\n              <Action name=\"LeadingVehicleKeepsVelocity\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10000\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"10\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartConditionLeadingVehicleKeepsVelocity\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"20.0\" freespace=\"false\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"1.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"equalTo\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"20000.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger/>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/PedestrianCrossingFront.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:PedestrianCrossing\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.volkswagen.t2\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Pedestrian model=\"walker.pedestrian.0001\" mass=\"90.0\" name=\"walker.pedestrian.0001\" pedestrianCategory=\"pedestrian\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Pedestrian>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.35\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"rain\" intensity=\"0.2\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"150\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"110\" y=\"52\" z=\"0.3\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"PedestrianCrossingManeuver\">\n            <Event name=\"PedestrianStartsWalking\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalking\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"1.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"10.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <ReachPositionCondition tolerance=\"2.0\">\n                          <Position>\n                            <WorldPosition x=\"140\" y=\"55\" z=\"0\" h=\"180\"/>\n                          </Position>\n                        </ReachPositionCondition>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianStopsAndWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianStopsAndWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"AfterPedestrianWalks\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalking\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWalksAway\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalkingAway\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"6.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStopsAndWaits\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStopsAndWaits\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalkingAway\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"10.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/RouteObstacles.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"Accident_1\" type=\"Accident\" town=\"Town04\">\n        <ego_vehicle x=\"30.39\" y=\"-285.92\" z=\"2.8\" yaw=\"-70\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"Construction_1\" type=\"ConstructionObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"30.39\" y=\"-285.92\" z=\"2.8\" yaw=\"-70\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/RunningRedLight.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"OppositeVehicleRunningRedLight_1\" type=\"OppositeVehicleRunningRedLight\" town=\"Town03\">\n        <ego_vehicle x=\"-2.8\" y=\"-184\" z=\"1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_2\" type=\"OppositeVehicleRunningRedLight\" town=\"Town03\">\n        <ego_vehicle x=\"69\" y=\"130\" z=\"1\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_3\" type=\"OppositeVehicleRunningRedLight\" town=\"Town03\">\n        <ego_vehicle x=\"-48\" y=\"134.7\" z=\"1\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_4\" type=\"OppositeVehicleRunningRedLight\" town=\"Town04\">\n        <ego_vehicle x=\"274.1\" y=\"-246.2\" z=\"0.3\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_5\" type=\"OppositeVehicleRunningRedLight\" town=\"Town04\">\n        <ego_vehicle x=\"255\" y=\"-224.4\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/SignalizedJunctionLeftTurn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"SignalizedJunctionLeftTurn_1\" type=\"SignalizedJunctionLeftTurn\" town=\"Town03\">\n        <ego_vehicle x=\"-133.7\" y=\"137.4\" z=\"0.2\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n     </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_2\" type=\"SignalizedJunctionLeftTurn\" town=\"Town04\">\n        <ego_vehicle x=\"202.8\" y=\"-209.8\" z=\"0.3\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_3\" type=\"SignalizedJunctionLeftTurn\" town=\"Town04\">\n        <ego_vehicle x=\"274.1\" y=\"-246.2\" z=\"0.3\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_4\" type=\"SignalizedJunctionLeftTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-145.5\" y=\"-1\" z=\"0.3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_5\" type=\"SignalizedJunctionLeftTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-76.5\" y=\"-0.8\" z=\"0.3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_6\" type=\"SignalizedJunctionLeftTurn\" town=\"Town05\">\n        <ego_vehicle x=\"76.4\" y=\"83\" z=\"0.3\" yaw=\"157\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/SignalizedJunctionRightTurn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"SignalizedJunctionRightTurn_1\" type=\"SignalizedJunctionRightTurn\" town=\"Town03\">\n        <ego_vehicle x=\"-2.8\" y=\"-182.8\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_2\" type=\"SignalizedJunctionRightTurn\" town=\"Town04\">\n        <ego_vehicle x=\"244.7\" y=\"-249.4\" z=\"0.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_3\" type=\"SignalizedJunctionRightTurn\" town=\"Town04\">\n        <ego_vehicle x=\"246\" y=\"-311\" z=\"0.1\" yaw=\"-179\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_4\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-54.9\" y=\"25.3\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_5\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-25.7\" y=\"95\" z=\"0.0\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_6\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"72.2\" y=\"-5.6\" z=\"0.0\" yaw=\"-180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_7\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-170.3\" y=\"94.9\" z=\"0.0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/Slalom.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-07-30T12:00:00\" description=\"CARLA:Slalom\" author=\"Dimitri Scheftelowitsch\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.nissan.micra\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"c1\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n     <ScenarioObject name=\"c2\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n     <ScenarioObject name=\"c3\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n     <ScenarioObject name=\"c4\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n    <ScenarioObject name=\"c5\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.35\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"rain\" intensity=\"0.2\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"92.44\" y=\"314\" z=\"0\" h=\"-1.5707963267948966\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c1\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"90\" y=\"308\" z=\"0.0\" h=\"-1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c2\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"95\" y=\"298\" z=\"0.3\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c3\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"91\" y=\"288\" z=\"0.3\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c4\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"93\" y=\"278\" z=\"0.0\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c5\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"91\" y=\"268\" z=\"0.0\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"NoManeuver\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"hero\"/>\n          </Actors>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"120.0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"1\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"120.0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"70\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/VehicleOpensDoor.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"VehicleOpensDoorTwoWays_1\" type=\"VehicleOpensDoorTwoWays\" town=\"Town10HD_Opt\">\n        <ego_vehicle x=\"-19.4\" y=\"69.5\" z=\"0.3\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n        <direction value=\"right\"/>\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/VehicleTurning.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"VehicleTurningRight_1\" type=\"VehicleTurningRight\" town=\"Town01\">\n        <ego_vehicle x=\"130\" y=\"55\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_1\" type=\"VehicleTurningLeft\" town=\"Town01\">\n        <ego_vehicle x=\"130\" y=\"55\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n     <scenario name=\"VehicleTurningRight_2\" type=\"VehicleTurningRight\" town=\"Town01\">\n        <ego_vehicle x=\"132\" y=\"195.5\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_2\" type=\"VehicleTurningLeft\" town=\"Town01\">\n        <ego_vehicle x=\"132\" y=\"195.5\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_3\" type=\"VehicleTurningRight\" town=\"Town01\">\n        <ego_vehicle x=\"282.5\" y=\"199.4\" z=\"0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_3\" type=\"VehicleTurningLeft\" town=\"Town01\">\n        <ego_vehicle x=\"282.5\" y=\"199.4\" z=\"0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_4\" type=\"VehicleTurningRight\" town=\"Town02\">\n        <ego_vehicle x=\"30.1\" y=\"187.4\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_4\" type=\"VehicleTurningLeft\" town=\"Town02\">\n        <ego_vehicle x=\"30.1\" y=\"187.4\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_5\" type=\"VehicleTurningRight\" town=\"Town02\">\n        <ego_vehicle x=\"90\" y=\"237.1\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_5\" type=\"VehicleTurningLeft\" town=\"Town02\">\n        <ego_vehicle x=\"87.5\" y=\"237.1\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_6\" type=\"VehicleTurningRight\" town=\"Town02\">\n        <ego_vehicle x=\"146.2\" y=\"191.7\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_6\" type=\"VehicleTurningLeft\" town=\"Town02\">\n        <ego_vehicle x=\"146.2\" y=\"191.7\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_7\" type=\"VehicleTurningRight\" town=\"Town03\">\n        <ego_vehicle x=\"-74.32\" y=\"-50\" z=\"0.5\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_7\" type=\"VehicleTurningLeft\" town=\"Town03\">\n        <ego_vehicle x=\"-74.32\" y=\"-50\" z=\"0.5\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_8\" type=\"VehicleTurningRight\" town=\"Town04\">\n        <ego_vehicle x=\"255.2\" y=\"-300.4\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_8\" type=\"VehicleTurningLeft\" town=\"Town04\">\n        <ego_vehicle x=\"255.2\" y=\"-300.4\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/catalogs/ControllerCatalog.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T00:00:00\" description=\"CARLA:ControllerCatalog\" author=\"\" />\n  <Catalog name=\"ControllerCatalog\">\n    <Controller name=\"ExternalControl\">\n      <Properties>\n        <Property name=\"module\" value=\"external_control\" />\n      </Properties>\n    </Controller>\n  </Catalog>\n</OpenSCENARIO>"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/catalogs/EnvironmentCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-20\" description=\"CARLA:EnvironmentCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"EnvironmentCatalog\">\n    <Environment name=\"ClearNoon\">\n      <TimeOfDay animation=\"false\" dateTime=\"2020-01-01T12:00:00\"/>\n      <Weather cloudState=\"free\">\n        <Sun intensity=\"1.0\" azimuth=\"0.0\" elevation=\"1.5\"/>\n        <Fog visualRange=\"10000.0\"/>\n        <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n      </Weather>\n      <RoadCondition frictionScaleFactor=\"1.0\"/>\n    </Environment>\n    <Environment name=\"ClearMidnight\">\n      <TimeOfDay animation=\"false\" dateTime=\"2020-01-01T00:00:00\"/>\n      <Weather cloudState=\"free\">\n        <Sun intensity=\"1.0\" azimuth=\"0.26\" elevation=\"-1.1\"/>\n        <Fog visualRange=\"10000.0\"/>\n        <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n      </Weather>\n      <RoadCondition frictionScaleFactor=\"1.0\"/>\n    </Environment>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/catalogs/ManeuverCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-21\" description=\"CARLA:ManeuverCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"ManeuverCatalog\">\n    <Maneuver name=\"Autopilot\">\n      <Event name=\"StartAutopilot\" priority=\"overwrite\">\n        <Action name=\"StartAutopilot\">\n          <PrivateAction>\n            <ActivateControllerAction longitudinal=\"true\"/>\n          </PrivateAction>\n        </Action>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n      </Event>\n      <Event name=\"StopAutopilot\" priority=\"overwrite\">\n        <Action name=\"StopAutopilot\">\n          <PrivateAction>\n            <ActivateControllerAction longitudinal=\"false\"/>\n          </PrivateAction>\n        </Action>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"20\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n      </Event>\n    </Maneuver>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/catalogs/MiscObjectCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-25\" description=\"CARLA:MiscObjectCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"MiscObjectCatalog\">\n    <MiscObject miscObjectCategory=\"barrier\" mass=\"0.0\" name=\"Barrier1\">\n      <ParameterDeclarations/>\n      <BoundingBox>\n        <Center x=\"0.0\" y=\"0.0\" z=\"0.0\"/>\n        <Dimensions width=\"0.0\" length=\"0.0\" height=\"0.0\"/>\n      </BoundingBox>\n      <Properties/>\n    </MiscObject>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/catalogs/PedestrianCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-20\" description=\"CARLA:PedestrianCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"PedestrianCatalog\">\n    <Pedestrian model=\"walker.pedestrian.0001\" mass=\"0.0\" name=\"Pedestrian1\" pedestrianCategory=\"pedestrian\">\n      <BoundingBox>\n        <Center x=\"0.0\" y=\"0.0\" z=\"0.0\"/>\n        <Dimensions width=\"0.0\" length=\"0.0\" height=\"0.0\"/>\n      </BoundingBox>\n      <Properties/>\n    </Pedestrian>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/examples/catalogs/VehicleCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-17\" description=\"CARLA:VehicleCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"VehicleCatalog\">\n    <Vehicle name=\"vehicle.volkswagen.t2\" vehicleCategory=\"car\">\n      <ParameterDeclarations/>\n      <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n      <BoundingBox>\n        <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n        <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n      </BoundingBox>\n      <Axles>\n        <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n        <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n      </Axles>\n      <Properties>\n        <Property name=\"type\" value=\"ego_vehicle\"/>\n      </Properties>\n    </Vehicle>\n    <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n      <ParameterDeclarations>\n        <ParameterDeclaration name=\"carcolor\" parameterType=\"string\" value=\"0,0,0\" />\n      </ParameterDeclarations>\n      <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n      <BoundingBox>\n        <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n        <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n      </BoundingBox>\n      <Axles>\n        <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n        <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n      </Axles>\n      <Properties>\n        <Property name=\"color\" value=\"$carcolor\"/>\n      </Properties>\n    </Vehicle>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/metrics/examples/basic_metric.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provide BasicMetric, the basic class of all the metrics.\n\"\"\"\n\nclass BasicMetric(object):\n    \"\"\"\n    Base class of all the metrics.\n    \"\"\"\n\n    def __init__(self, town_map, log, criteria=None):\n        \"\"\"\n        Initialization of the metric class. This calls the metrics log and creates the metrics\n\n        Args:\n            town_map (carla.Map): Map of the simulation. Used to access the Waypoint API.\n            log (srunner.metrics.tools.Metricslog): instance of a class used to access the recorder information\n            criteria (dict): list of dictionaries with all the criteria information\n        \"\"\"\n\n        # Create the metrics of the simulation. This part is left to the user\n        self._create_metric(town_map, log, criteria)\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Pure virtual function to setup the metrics by the user.\n\n        Args:\n            town_map (carla.Map): Map of the simulation. Used to access the Waypoint API.\n            log (srunner.metrics.tools.Metricslog): instance of a class used to access the recorder information\n            criteria (dict): dictionaries with all the criteria information\n        \"\"\"\n        raise NotImplementedError(\n            \"This function should be re-implemented by all metrics\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/metrics/examples/criteria_filter.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis metric filters the useful information of the criteria (sucess / fail ...),\nand dump it into a json file\n\nIt is meant to serve as an example of how to use the criteria\n\"\"\"\n\nimport json\n\nfrom srunner.metrics.examples.basic_metric import BasicMetric\n\n\nclass CriteriaFilter(BasicMetric):\n    \"\"\"\n    Metric class CriteriaFilter\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric. This is an example to show how to use the criteria\n        \"\"\"\n\n        ### Parse the criteria information, filtering only the useful information, and dump it into a json ###\n\n        results = {}\n        for criterion_name in criteria:\n            criterion = criteria[criterion_name]\n            results.update({criterion_name:\n                {\n                    \"test_status\": criterion[\"test_status\"],\n                    \"actual_value\": criterion[\"actual_value\"],\n                    \"success_value\": criterion[\"success_value\"]\n                }\n            }\n        )\n\n        with open('srunner/metrics/data/CriteriaFilter_results.json', 'w') as fw:\n            json.dump(results, fw, sort_keys=False, indent=4)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/metrics/examples/distance_between_vehicles.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis metric calculates the distance between the ego vehicle and\nanother actor, dumping it to a json file.\n\nIt is meant to serve as an example of how to use the information from\nthe recorder\n\"\"\"\n\nimport math\nimport matplotlib.pyplot as plt\n\nfrom srunner.metrics.examples.basic_metric import BasicMetric\n\n\nclass DistanceBetweenVehicles(BasicMetric):\n    \"\"\"\n    Metric class DistanceBetweenVehicles\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric. This is an example to show how to use the recorder,\n        accessed via the log.\n        \"\"\"\n\n        # Get the ID of the two vehicles\n        ego_id = log.get_ego_vehicle_id()\n        adv_id = log.get_actor_ids_with_role_name(\"scenario\")[0]  # Could have also used its type_id\n\n        dist_list = []\n        frames_list = []\n\n        # Get the frames both actors were alive\n        start_ego, end_ego = log.get_actor_alive_frames(ego_id)\n        start_adv, end_adv = log.get_actor_alive_frames(adv_id)\n        start = max(start_ego, start_adv)\n        end = min(end_ego, end_adv)\n\n        # Get the distance between the two\n        for i in range(start, end):\n\n            # Get the transforms\n            ego_location = log.get_actor_transform(ego_id, i).location\n            adv_location = log.get_actor_transform(adv_id, i).location\n\n            # Filter some points for a better graph\n            if adv_location.z < -10:\n                continue\n\n            dist_v = ego_location - adv_location\n            dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n            dist_list.append(dist)\n            frames_list.append(i)\n\n        # Use matplotlib to show the results\n        plt.plot(frames_list, dist_list)\n        plt.ylabel('Distance [m]')\n        plt.xlabel('Frame number')\n        plt.title('Distance between the ego vehicle and the adversary over time')\n        plt.show()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/metrics/examples/distance_to_lane_center.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis metric calculates the distance between the ego vehicle and\nthe center of the lane, dumping it to a json file.\n\nIt is meant to serve as an example of how to use the map API\n\"\"\"\n\nimport math\nimport json\n\nfrom srunner.metrics.examples.basic_metric import BasicMetric\n\n\nclass DistanceToLaneCenter(BasicMetric):\n    \"\"\"\n    Metric class DistanceToLaneCenter\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric.\n        \"\"\"\n\n        # Get ego vehicle id\n        ego_id = log.get_ego_vehicle_id()\n\n        dist_list = []\n        frames_list = []\n\n        # Get the frames the ego actor was alive and its transforms\n        start, end = log.get_actor_alive_frames(ego_id)\n\n        # Get the projected distance vector to the center of the lane\n        for i in range(start, end + 1):\n\n            ego_location = log.get_actor_transform(ego_id, i).location\n            ego_waypoint = town_map.get_waypoint(ego_location)\n\n            # Get the distance vector and project it\n            a = ego_location - ego_waypoint.transform.location      # Ego to waypoint vector\n            b = ego_waypoint.transform.get_right_vector()           # Waypoint perpendicular vector\n            b_norm = math.sqrt(b.x * b.x + b.y * b.y + b.z * b.z)\n\n            ab_dot = a.x * b.x + a.y * b.y + a.z * b.z\n            dist_v = ab_dot/(b_norm*b_norm)*b\n            dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n            # Get the sign of the distance (left side is positive)\n            c = ego_waypoint.transform.get_forward_vector()         # Waypoint forward vector\n            ac_cross = c.x * a.y - c.y * a.x\n            if ac_cross < 0:\n                dist *= -1\n\n            dist_list.append(dist)\n            frames_list.append(i)\n\n        # Save the results to a file\n        results = {'frames': frames_list, 'distance': dist_list}\n        with open('srunner/metrics/data/DistanceToLaneCenter_results.json', 'w') as fw:\n            json.dump(results, fw, sort_keys=False, indent=4)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/metrics/tools/metrics_log.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSupport class of the MetricsManager to query the information available\nto the metrics.\n\nIt also provides a series of functions to help the user querry\nspecific information\n\"\"\"\n\nimport fnmatch\nfrom srunner.metrics.tools.metrics_parser import MetricsParser\n\nclass MetricsLog(object):  # pylint: disable=too-many-public-methods\n    \"\"\"\n    Utility class to query the log.\n    \"\"\"\n\n    def __init__(self, recorder):\n        \"\"\"\n        Initializes the log class and parses it to extract the dictionaries.\n        \"\"\"\n        # Parse the information\n        parser = MetricsParser(recorder)\n        self._simulation, self._actors, self._frames = parser.parse_recorder_info()\n\n    ### Functions used to get general info of the simulation ###\n    def get_actor_collisions(self, actor_id):\n        \"\"\"\n        Returns a dict where the keys are the frame number and the values,\n        a list of actor ids the actor collided with.\n\n        Args:\n            actor_id (int): ID of the actor.\n        \"\"\"\n        actor_collisions = {}\n\n        for i, frame in enumerate(self._frames):\n            collisions = frame[\"events\"][\"collisions\"]\n\n            if actor_id in collisions:\n                actor_collisions.update({i: collisions[actor_id]})\n\n        return actor_collisions\n\n    def get_total_frame_count(self):\n        \"\"\"\n        Returns an int with the total amount of frames the simulation lasted.\n        \"\"\"\n\n        return self._simulation[\"total_frames\"]\n\n    def get_elapsed_time(self, frame):\n        \"\"\"\n        Returns a float with the elapsed time of a specific frame.\n        \"\"\"\n\n        return self._frames[frame][\"frame\"][\"elapsed_time\"]\n\n    def get_delta_time(self, frame):\n        \"\"\"\n        Returns a float with the delta time of a specific frame.\n        \"\"\"\n\n        return self._frames[frame][\"frame\"][\"delta_time\"]\n\n    def get_platform_time(self, frame):\n        \"\"\"\n        Returns a float with the platform time time of a specific frame.\n        \"\"\"\n\n        return self._frames[frame][\"frame\"][\"platform_time\"]\n\n    ### Functions used to get info about the actors ###\n    def get_ego_vehicle_id(self):\n        \"\"\"\n        Returns the id of the ego vehicle.\n        \"\"\"\n        return self.get_actor_ids_with_role_name(\"hero\")[0]\n\n    def get_actor_ids_with_role_name(self, role_name):\n        \"\"\"\n        Returns a list of actor ids that match the given role_name.\n\n        Args:\n            role_name (str): string with the desired role_name to filter the actors.\n        \"\"\"\n        actor_list = []\n\n        for actor_id in self._actors:\n            actor = self._actors[actor_id]\n            if \"role_name\" in actor and actor[\"role_name\"] == role_name:\n                actor_list.append(actor_id)\n\n        return actor_list\n\n    def get_actor_ids_with_type_id(self, type_id):\n        \"\"\"\n        Returns a list of actor ids that match the given type_id, matching fnmatch standard.\n\n        Args:\n            type_id (str): string with the desired type id to filter the actors.\n        \"\"\"\n        actor_list = []\n\n        for actor_id in self._actors:\n            actor = self._actors[actor_id]\n            if \"type_id\" in actor and fnmatch.fnmatch(actor[\"type_id\"], type_id):\n                actor_list.append(actor_id)\n\n        return actor_list\n\n    def get_actor_attributes(self, actor_id):\n        \"\"\"\n        Returns a dictionary with all the attributes of an actor.\n\n        Args:\n            actor_id (int): ID of the actor.\n        \"\"\"\n        if actor_id in self._actors:\n            return self._actors[actor_id]\n\n        return None\n\n    def get_actor_bounding_box(self, actor_id):\n        \"\"\"\n        Returns the bounding box of the specified actor\n\n        Args:\n            actor_id (int): Id of the actor\n        \"\"\"\n\n        if actor_id in self._actors:\n            if \"bounding_box\" in self._actors[actor_id]:\n                return self._actors[actor_id][\"bounding_box\"]\n            return None\n\n        return None\n\n    def get_traffic_light_trigger_volume(self, traffic_light_id):\n        \"\"\"\n        Returns the trigger volume of the specified traffic light\n\n        Args:\n            actor_id (int): Id of the traffic light\n        \"\"\"\n\n        if traffic_light_id in self._actors:\n            if \"trigger_volume\" in self._actors[traffic_light_id]:\n                return self._actors[traffic_light_id][\"trigger_volume\"]\n            return None\n\n        return None\n\n    def get_actor_alive_frames(self, actor_id):\n        \"\"\"\n        Returns a tuple with the first and last frame an actor was alive.\n        It is important to note that frames start at 1, not 0.\n\n        Args:\n            actor_id (int): Id of the actor\n        \"\"\"\n\n        if actor_id in self._actors:\n\n            actor_info = self._actors[actor_id]\n            first_frame = actor_info[\"created\"]\n            if \"destroyed\" in actor_info:\n                last_frame = actor_info[\"destroyed\"] - 1\n            else:\n                last_frame = self.get_total_frame_count()\n\n            return first_frame, last_frame\n\n        return None, None\n\n    ### Functions used to get the actor states ###\n    def _get_actor_state(self, actor_id, state, frame):\n        \"\"\"\n        Given an actor id, returns the specific variable of that actor at a given frame.\n        Returns None if the actor_id or the state are missing.\n\n        Args:\n            actor_id (int): Id of the actor to be checked.\n            frame: (int): frame number of the simulation.\n            attribute (str): name of the actor's attribute to be returned.\n        \"\"\"\n        frame_state = self._frames[frame - 1][\"actors\"]\n\n        # Check if the actor exists\n        if actor_id in frame_state:\n\n            # Check if the state exists\n            if state not in frame_state[actor_id]:\n                return None\n\n            state_info = frame_state[actor_id][state]\n            return state_info\n\n        return None\n\n    def _get_all_actor_states(self, actor_id, state, first_frame=None, last_frame=None):\n        \"\"\"\n        Given an actor id, returns a list of the specific variable of that actor during\n        a frame interval. Some elements might be None.\n\n        By default, first_frame and last_frame are the start and end of the simulation, respectively.\n\n        Args:\n            actor_id (int): ID of the actor.\n            attribute: name of the actor's attribute to be returned.\n            first_frame (int): First frame checked. By default, 0.\n            last_frame (int): Last frame checked. By default, max number of frames.\n        \"\"\"\n        if first_frame is None:\n            first_frame = 1\n        if last_frame is None:\n            last_frame = self.get_total_frame_count()\n\n        state_list = []\n\n        for frame_number in range(first_frame, last_frame + 1):\n            state_info = self._get_actor_state(actor_id, state, frame_number)\n            state_list.append(state_info)\n\n        return state_list\n\n    def _get_states_at_frame(self, frame, state, actor_list=None):\n        \"\"\"\n        Returns a dict where the keys are the frame number, and the values are the\n        carla.Transform of the actor at the given frame.\n\n        By default, all actors will be considered.\n        \"\"\"\n        states = {}\n        actor_info = self._frames[frame][\"actors\"]\n\n        for actor_id in actor_info:\n            if not actor_list:\n                _state = self._get_actor_state(actor_id, state, frame)\n                if _state:\n                    states.update({actor_id: _state})\n            elif actor_id in actor_list:\n                _state = self._get_actor_state(actor_id, state, frame)\n                states.update({actor_id: _state})\n\n        return states\n\n    # Transforms\n    def get_actor_transform(self, actor_id, frame):\n        \"\"\"\n        Returns the transform of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"transform\", frame)\n\n    def get_all_actor_transforms(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the transforms of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"transform\", first_frame, last_frame)\n\n    def get_actor_transforms_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Transform} with the actor ID and transform\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"transform\", actor_list)\n\n    # Velocities\n    def get_actor_velocity(self, actor_id, frame):\n        \"\"\"\n        Returns the velocity of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"velocity\", frame)\n\n    def get_all_actor_velocities(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the velocities of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"velocity\", first_frame, last_frame)\n\n    def get_actor_velocities_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Vector3D} with the actor ID and velocity\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"velocity\", actor_list)\n\n    # Angular velocities\n    def get_actor_angular_velocity(self, actor_id, frame):\n        \"\"\"\n        Returns the angular velocity of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"angular_velocity\", frame)\n\n    def get_all_actor_angular_velocities(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the angular velocities of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"angular_velocity\", first_frame, last_frame)\n\n    def get_actor_angular_velocities_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Vector3D} with the actor ID and angular velocity\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"angular_velocity\", actor_list)\n\n    # Acceleration\n    def get_actor_acceleration(self, actor_id, frame):\n        \"\"\"\n        Returns the acceleration of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"acceleration\", frame)\n\n    def get_all_actor_accelerations(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the accelerations of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"acceleration\", first_frame, last_frame)\n\n    def get_actor_accelerations_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Vector3D} with the actor ID and angular velocity\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"acceleration\", actor_list)\n\n    # Controls\n    def get_vehicle_control(self, vehicle_id, frame):\n        \"\"\"\n        Returns the control of the vehicle at a given frame.\n        \"\"\"\n        return self._get_actor_state(vehicle_id, \"control\", frame)\n\n    def get_vehicle_physics_control(self, vehicle_id, frame):\n        \"\"\"\n        Returns the carla.VehiclePhysicsControl of a vehicle at a given frame.\n        Returns None if the id can't be found.\n        \"\"\"\n\n        for i in range(frame - 1, -1, -1):  # Go backwards from the frame until 0\n            physics_info = self._frames[i][\"events\"][\"physics_control\"]\n\n            if vehicle_id in physics_info:\n                return physics_info[vehicle_id]\n\n        return None\n\n    def get_walker_speed(self, walker_id, frame):\n        \"\"\"\n        Returns the speed of the walker at a specific frame.\n        \"\"\"\n        return self._get_actor_state(walker_id, \"speed\", frame)\n\n    # Traffic lights\n    def get_traffic_light_state(self, traffic_light_id, frame):\n        \"\"\"\n        Returns the state of the traffic light at a specific frame.\n        \"\"\"\n        return self._get_actor_state(traffic_light_id, \"state\", frame)\n\n    def is_traffic_light_frozen(self, traffic_light_id, frame):\n        \"\"\"\n        Returns whether or not the traffic light is frozen at a specific frame.\n        \"\"\"\n        return self._get_actor_state(traffic_light_id, \"frozen\", frame)\n\n    def get_traffic_light_elapsed_time(self, traffic_light_id, frame):\n        \"\"\"\n        Returns the elapsed time of the traffic light at a specific frame.\n        \"\"\"\n        return self._get_actor_state(traffic_light_id, \"elapsed_time\", frame)\n\n    def get_traffic_light_state_time(self, traffic_light_id, state, frame):\n        \"\"\"\n        Returns the state time of the traffic light at a specific frame.\n        Returns None if the id can't be found.\n        \"\"\"\n\n        for i in range(frame - 1, -1, -1):  # Go backwards from the frame until 0\n            state_times_info = self._frames[i][\"events\"][\"traffic_light_state_time\"]\n\n            if traffic_light_id in state_times_info:\n                states = state_times_info[traffic_light_id]\n                if state in states:\n                    return state_times_info[traffic_light_id][state]\n\n        return None\n\n    # Vehicle lights\n    def get_vehicle_lights(self, vehicle_id, frame):\n        \"\"\"\n        Returns the vehicle lights of the vehicle at a specific frame.\n        \"\"\"\n        return self._get_actor_state(vehicle_id, \"lights\", frame)\n\n    def is_vehicle_light_active(self, light, vehicle_id, frame):\n        \"\"\"\n        Returns the elapsed time of the traffic light at a specific frame.\n        \"\"\"\n        lights = self.get_vehicle_lights(vehicle_id, frame)\n\n        if light in lights:\n            return True\n\n        return False\n\n    # Scene lights\n    def get_scene_light_state(self, light_id, frame):\n        \"\"\"\n        Returns the state of the scene light at a specific frame.\n        Returns None if the id can't be found.\n        \"\"\"\n\n        for i in range(frame - 1, -1, -1):  # Go backwards from the frame until 0\n            scene_lights_info = self._frames[i][\"events\"][\"scene_lights\"]\n\n            if light_id in scene_lights_info:\n                return scene_lights_info[light_id]\n\n        return None\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/metrics/tools/metrics_parser.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSupport class of the MetricsManager to parse the information of\nthe CARLA recorder into a readable dictionary\n\"\"\"\n\nimport carla\n\n\ndef parse_actor(info):\n    \"\"\"Returns a dictionary with the basic actor information\"\"\"\n    actor = {\n        \"type_id\": info[2],\n        \"location\": carla.Location(\n            x=float(info[5][1:-1]) / 100,\n            y=float(info[6][:-1]) / 100,\n            z=float(info[7][:-1]) / 100\n        )\n    }\n    return actor\n\ndef parse_transform(info):\n    \"\"\"Parses a list into a carla.Transform\"\"\"\n    transform = carla.Transform(\n        carla.Location(\n            x=float(info[3][1:-1]) / 100,\n            y=float(info[4][:-1]) / 100,\n            z=float(info[5][:-1]) / 100,\n        ),\n        carla.Rotation(\n            roll=float(info[7][1:-1]),\n            pitch=float(info[8][:-1]), \n            yaw=float(info[9][:-1])\n        )\n    )\n    return transform\n\ndef parse_control(info):\n    \"\"\"Parses a list into a carla.VehicleControl\"\"\"\n    control = carla.VehicleControl(\n        throttle=float(info[5]),\n        steer=float(info[3]),\n        brake=float(info[7]),\n        hand_brake=bool(int(info[9])),\n        reverse=int(info[11]) < 0,\n        manual_gear_shift=False,\n        gear=int(info[11]),\n    )\n    return control\n\ndef parse_vehicle_lights(info):\n    \"\"\"Parses a list into a carla.VehicleLightState\"\"\"\n    srt_to_vlight = {\n        \"None\": carla.VehicleLightState.NONE,\n        \"Position\": carla.VehicleLightState.Position,\n        \"LowBeam\": carla.VehicleLightState.LowBeam,\n        \"HighBeam\": carla.VehicleLightState.HighBeam,\n        \"Brake\": carla.VehicleLightState.Brake,\n        \"RightBlinker\": carla.VehicleLightState.RightBlinker,\n        \"LeftBlinker\": carla.VehicleLightState.LeftBlinker,\n        \"Reverse\": carla.VehicleLightState.Reverse,\n        \"Fog\": carla.VehicleLightState.Fog,\n        \"Interior\": carla.VehicleLightState.Interior,\n        \"Special1\": carla.VehicleLightState.Special1,\n        \"Special2\": carla.VehicleLightState.Special2,\n    }\n\n    lights = []\n    for i in range(2, len(info)):\n        lights.append(srt_to_vlight[info[i]])\n\n    return lights\n\ndef parse_traffic_light(info):\n    \"\"\"Parses a list into a dictionary with all the traffic light's information\"\"\"\n    number_to_state = {\n        \"0\": carla.TrafficLightState.Red,\n        \"1\": carla.TrafficLightState.Yellow,\n        \"2\": carla.TrafficLightState.Green,\n        \"3\": carla.TrafficLightState.Off,\n        \"4\": carla.TrafficLightState.Unknown,\n    }\n    traffic_light = {\n        \"state\": number_to_state[info[3]],\n        \"frozen\": bool(int(info[5])),\n        \"elapsed_time\": float(info[7]),\n    }\n    return traffic_light\n\ndef parse_velocity(info):\n    \"\"\"Parses a list into a carla.Vector3D with the velocity\"\"\"\n    velocity = carla.Vector3D(\n        x=float(info[3][1:-1]),\n        y=float(info[4][:-1]),\n        z=float(info[5][:-1])\n    )\n    return velocity\n\ndef parse_angular_velocity(info):\n    \"\"\"Parses a list into a carla.Vector3D with the angular velocity\"\"\"\n    velocity = carla.Vector3D(\n        x=float(info[7][1:-1]),\n        y=float(info[8][:-1]),\n        z=float(info[9][:-1])\n    )\n    return velocity\n\ndef parse_scene_lights(info):\n    \"\"\"Parses a list into a carla.VehicleLightState\"\"\"\n\n    red = int(float(info[7][1:-1]) * 255)\n    green = int(float(info[8][:-1]) * 255)\n    blue = int(float(info[9][:-1]) * 255)\n\n    scene_light = carla.LightState(\n        intensity=int(float(info[5])),\n        color=carla.Color(red, green, blue),\n        group=carla.LightGroup.NONE,\n        active=bool(info[3])\n    )\n    return scene_light\n\ndef parse_bounding_box(info):\n    \"\"\"\n    Parses a list into a carla.BoundingBox.\n    Some actors like sensors might have 'nan' location and 'inf' extent, so filter those.\n    \"\"\"\n    if 'nan' in info[3]:\n        location = carla.Location()\n    else:\n        location = carla.Location(\n            float(info[3][1:-1])/100,\n            float(info[4][:-1])/100,\n            float(info[5][:-1])/100,\n        )\n\n    if 'inf' in info[7]:\n        extent = carla.Vector3D()\n    else:\n        extent = carla.Vector3D(\n            float(info[7][1:-1])/100,\n            float(info[8][:-1])/100,\n            float(info[9][:-1])/100,\n        )\n\n    bbox = carla.BoundingBox(location, extent)\n\n    return bbox\n\ndef parse_state_times(info):\n    \"\"\"Parses a list into a dict containing the state times of the traffic lights\"\"\"\n    state_times = {\n        carla.TrafficLightState.Green: float(info[3]),\n        carla.TrafficLightState.Yellow: float(info[5]),\n        carla.TrafficLightState.Red: float(info[7]),\n    }\n    return state_times\n\ndef parse_vector_list(info):\n    \"\"\"Parses a list of string into a list of Vector2D\"\"\"\n    vector_list = []\n    for i in range(0, len(info), 2):\n        vector = carla.Vector2D(\n            x=float(info[i][1:-1]),\n            y=float(info[i+1][:-1]),\n        )\n        vector_list.append(vector)\n\n    return vector_list\n\ndef parse_gears_control(info):\n    \"\"\"Parses a list into a GearPhysicsControl\"\"\"\n    gears_control = carla.GearPhysicsControl(\n        ratio=float(info[3]),\n        down_ratio=float(info[5]),\n        up_ratio=float(info[7]),\n    )\n    return gears_control\n\ndef parse_wheels_control(info):\n    \"\"\"Parses a list into a WheelsPhysicsControl\"\"\"\n    wheels_control = carla.WheelPhysicsControl(\n        tire_friction=float(info[3]),\n        damping_rate=float(info[5]),\n        max_steer_angle=float(info[7]),\n        radius=float(info[9]),\n        max_brake_torque=float(info[11]),\n        max_handbrake_torque=float(info[13]),\n        position=carla.Vector3D(\n            x=float(info[17][1:-1]) / 100,\n            y=float(info[17][:-1]) / 100,\n            z=float(info[17][:-1]) / 100)\n    )\n    return wheels_control\n\n\nclass MetricsParser(object):\n    \"\"\"\n    Class used to parse the CARLA recorder into readable information\n    \"\"\"\n\n    def __init__(self, recorder_info):\n\n        self.recorder_info = recorder_info\n        self.frame_list = None\n        self.frame_row = None\n        self.i = 0\n\n    def get_row_elements(self, indent_num, split_string):\n        \"\"\"\n        returns a list with the elements of the row\n        \"\"\"\n        return self.frame_row[indent_num:].split(split_string)\n\n    def next_row(self):\n        \"\"\"\n        Gets the next row of the recorder\n        \"\"\"\n        self.i += 1\n        self.frame_row = self.frame_list[self.i]\n\n    def parse_recorder_info(self):\n        \"\"\"\n        Parses the recorder into readable information.\n\n        Args:\n            recorder_info (str): string given by the recorder\n        \"\"\"\n\n        # Divide it into frames\n        recorder_list = self.recorder_info.split(\"Frame\")\n\n        # Get general information\n        header = recorder_list[0].split(\"\\n\")\n        sim_map = header[1][5:]\n        sim_date = header[2][6:]\n\n        annex = recorder_list[-1].split(\"\\n\")\n        sim_frames = int(annex[0][3:])\n        sim_duration = float(annex[1][10:-8])\n\n        recorder_list = recorder_list[1:-1]\n\n        simulation_info = {\n            \"map\": sim_map,\n            \"date:\": sim_date,\n            \"total_frames\": sim_frames,\n            \"duration\": sim_duration\n        }\n\n        actors_info = {}\n        frames_info = []\n\n        for frame in recorder_list:\n\n            # Divide the frame in lines\n            self.frame_list = frame.split(\"\\n\")\n\n            # Get the general frame information\n            frame_info = self.frame_list[0].split(\" \")\n            frame_number = int(frame_info[1])\n            frame_time = float(frame_info[3])\n\n            try:\n                prev_frame = frames_info[frame_number - 2]\n                prev_time = prev_frame[\"frame\"][\"elapsed_time\"]\n                delta_time = round(frame_time - prev_time, 6)\n            except IndexError:\n                delta_time = 0\n\n            # Variable to store all the information about the frame\n            frame_state = {\n                \"frame\": {\n                    \"elapsed_time\": frame_time,\n                    \"delta_time\": delta_time,\n                    \"platform_time\": None\n                },\n                \"actors\": {},\n                \"events\":{\n                    \"scene_lights\": {},\n                    \"physics_control\": {},\n                    \"traffic_light_state_time\": {},\n                    \"collisions\": {}\n                }\n            }\n\n            # Loop through all the other rows.\n            self.i = 0\n            self.next_row()\n\n            while self.frame_row.startswith(' Create') or self.frame_row.startswith('  '):\n\n                if self.frame_row.startswith(' Create'):\n                    elements = self.get_row_elements(1, \" \")\n                    actor_id = int(elements[1][:-1])\n\n                    actor = parse_actor(elements)\n                    actors_info.update({actor_id: actor})\n                    actors_info[actor_id].update({\"created\": frame_number})\n                else:\n                    elements = self.get_row_elements(2, \" = \")\n                    actors_info[actor_id].update({elements[0]: elements[1]})\n\n                self.next_row()\n\n            while self.frame_row.startswith(' Destroy'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                actor_id = int(elements[1])\n                actors_info[actor_id].update({\"destroyed\": frame_number})\n\n                self.next_row()\n\n            while self.frame_row.startswith(' Collision'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                actor_id = int(elements[4])\n                other_id = int(elements[-1])\n\n                if actor_id not in frame_state[\"events\"][\"collisions\"]:\n                    frame_state[\"events\"][\"collisions\"][actor_id] = [other_id]\n                else:\n                    collisions = frame_state[\"events\"][\"collisions\"][actor_id]\n                    collisions.append(other_id)\n                    frame_state[\"events\"][\"collisions\"].update({actor_id: collisions})\n\n                self.next_row()\n\n            while self.frame_row.startswith(' Parenting'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                actor_id = int(elements[1])\n                parent_id = int(elements[3])\n                actors_info[actor_id].update({\"parent\": parent_id})\n\n                self.next_row()\n\n            if self.frame_row.startswith(' Positions'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    transform = parse_transform(elements)\n                    frame_state[\"actors\"].update({actor_id: {\"transform\": transform}})\n\n                    self.next_row()\n\n            if self.frame_row.startswith(' State traffic lights'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    traffic_light = parse_traffic_light(elements)\n                    frame_state[\"actors\"].update({actor_id: traffic_light})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Vehicle animations'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    control = parse_control(elements)\n                    frame_state[\"actors\"][actor_id].update({\"control\": control})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Walker animations'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    frame_state[\"actors\"][actor_id].update({\"speed\": elements[3]})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Vehicle light animations'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    lights = parse_vehicle_lights(elements)\n                    frame_state[\"actors\"][actor_id].update({\"lights\": lights})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Scene light changes'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    scene_light = parse_scene_lights(elements)\n                    frame_state[\"events\"][\"scene_lights\"].update({actor_id: scene_light})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Dynamic actors'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    velocity = parse_velocity(elements)\n                    frame_state[\"actors\"][actor_id].update({\"velocity\": velocity})\n\n                    angular_v = parse_angular_velocity(elements)\n                    frame_state[\"actors\"][actor_id].update({\"angular_velocity\": angular_v})\n\n                    if delta_time == 0:\n                        acceleration = carla.Vector3D(0, 0, 0)\n                    else:\n                        prev_velocity = frame_state[\"actors\"][actor_id][\"velocity\"]\n                        acceleration = (velocity - prev_velocity) / delta_time\n\n                    frame_state[\"actors\"][actor_id].update({\"acceleration\": acceleration})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Actor bounding boxes'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    bbox = parse_bounding_box(elements)\n                    actors_info[actor_id].update({\"bounding_box\": bbox})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Actor trigger volumes'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    trigvol = parse_bounding_box(elements)\n                    actors_info[actor_id].update({\"trigger_volume\": trigvol})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Current platform time'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                platform_time = float(elements[-1])\n                frame_state[\"frame\"][\"platform_time\"] = platform_time\n                self.next_row()\n\n            if self.frame_row.startswith(' Physics Control'):\n                self.next_row()\n\n                actor_id = None\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n                    physics_control = carla.VehiclePhysicsControl()\n                    self.next_row()\n\n                    forward_gears = []\n                    wheels = []\n                    while self.frame_row.startswith('   '):\n\n                        if self.frame_row.startswith('    '):\n                            elements = self.get_row_elements(4, \" \")\n                            if elements[0] == \"gear\":\n                                forward_gears.append(parse_gears_control(elements))\n                            elif elements[0] == \"wheel\":\n                                wheels.append(parse_wheels_control(elements))\n\n                        else:\n                            elements = self.get_row_elements(3, \" = \")\n                            name = elements[0]\n\n                            if name == \"center_of_mass\":\n                                values = elements[1].split(\" \")\n                                value = carla.Vector3D(\n                                    float(values[0][1:-1]),\n                                    float(values[1][:-1]),\n                                    float(values[2][:-1]),\n                                )\n                                setattr(physics_control, name, value)\n                            elif name == \"torque_curve\" or name == \"steering_curve\":\n                                values = elements[1].split(\" \")\n                                value = parse_vector_list(values)\n                                setattr(physics_control, name, value)\n\n                            elif name == \"use_gear_auto_box\":\n                                name = \"use_gear_autobox\"\n                                value = True if elements[1] == \"true\" else False\n                                setattr(physics_control, name, value)\n\n                            elif \"forward_gears\" in name or \"wheels\" in name:\n                                pass\n\n                            else:\n                                name = name.lower()\n                                value = float(elements[1])\n                                setattr(physics_control, name, value)\n\n                        self.next_row()\n\n                    setattr(physics_control, \"forward_gears\", forward_gears)\n                    setattr(physics_control, \"wheels\", wheels)\n                    frame_state[\"events\"][\"physics_control\"].update({actor_id: physics_control})\n\n            if self.frame_row.startswith(' Traffic Light time events'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    state_times = parse_state_times(elements)\n                    frame_state[\"events\"][\"traffic_light_state_time\"].update({actor_id: state_times})\n                    self.next_row()\n\n            frames_info.append(frame_state)\n\n        return simulation_info, actors_info, frames_info\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_Catalog.xsd",
    "content": "<?xml version=\"1.0\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n    \n    <xsd:include schemaLocation=\"OpenSCENARIO_TypeDefs.xsd\"/>\n    \n    <xsd:import namespace=\"http://www.w3.org/XML/1998/namespace\" schemaLocation=\"http://www.w3.org/2001/xml.xsd\"/>\n    \n    <xsd:annotation>\n        <xsd:documentation>\n            XML Schema Definition for OpenSCENARIO Catalog XML files - Version Draft 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany\n        </xsd:documentation>\n    </xsd:annotation>\n    \n    <xsd:element name=\"OpenSCENARIO\">\n        <xsd:complexType>\n            <xsd:sequence>\n                <xsd:element name=\"FileHeader\"  type=\"OSCFileHeader\"/>\n                \n                <xsd:element name=\"Catalog\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Vehicle\"                 type=\"OSCVehicle\"               minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Driver\"                  type=\"OSCDriver\"                minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Pedestrian\"              type=\"OSCPedestrian\"            minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"PedestrianController\"    type=\"OSCPedestrianController\"  minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"MiscObject\"              type=\"OSCMiscObject\"            minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Environment\"             type=\"OSCEnvironment\"           minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Maneuver\"                type=\"OSCManeuver\"              minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Trajectory\"              type=\"OSCTrajectory\"            minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Route\"                   type=\"OSCRoute\"                 minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                        </xsd:sequence>\n                        <xsd:attribute name=\"name\" type=\"xsd:string\"/>\n                    </xsd:complexType>\n                </xsd:element>\n            </xsd:sequence>\n        </xsd:complexType>\n    </xsd:element>\n    \n</xsd:schema>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_TypeDefs.xsd",
    "content": "<?xml version=\"1.0\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n    \n    <xsd:import namespace=\"http://www.w3.org/XML/1998/namespace\" schemaLocation=\"http://www.w3.org/2001/xml.xsd\"/>\n    \n    <xsd:annotation>\n        <xsd:documentation>\n            XML Schema Type Definitions for OpenSCENARIO XML files - Version Draft 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany\n        </xsd:documentation>\n    </xsd:annotation>\n\n    <xsd:complexType name=\"OSCParameterDeclaration\">\n        <xsd:sequence>\n            <xsd:element name=\"Parameter\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"name\"  type=\"xsd:string\"               use=\"required\"/>\n                    <xsd:attribute name=\"type\"  type=\"Enum_OSC_Parameter_type\"  use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\"               use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCFile\">\n        <xsd:attribute name=\"filepath\"  type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCDirectory\">\n        <xsd:attribute name=\"path\"  type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCCatalogs\">\n        <xsd:all>\n            <xsd:element name=\"VehicleCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"DriverCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"PedestrianCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"PedestrianControllerCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"MiscObjectCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"EnvironmentCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"ManeuverCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"TrajectoryCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RouteCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCConditionGroup\">\n        <xsd:sequence>\n            <xsd:element name=\"Condition\" type=\"OSCCondition\" maxOccurs=\"unbounded\"/>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCCatalogReference\">\n        <xsd:sequence>\n            <xsd:element name=\"OSCParameterAssignment\" minOccurs=\"0\"/>\n        </xsd:sequence>\n        <xsd:attribute name=\"catalogName\"   type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"entryName\"     type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCParameterAssignment\">\n        <xsd:sequence>\n            <xsd:element name=\"Parameter\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCUserDataList\">\n        <xsd:sequence>\n            <xsd:element name=\"UserData\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"code\"  type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCFileHeader\">\n        <xsd:attribute name=\"revMajor\"      type=\"xsd:unsignedShort\" use=\"required\"/>\n        <xsd:attribute name=\"revMinor\"      type=\"xsd:unsignedShort\" use=\"required\"/>\n        <xsd:attribute name=\"date\"          type=\"xsd:dateTime\" use=\"required\"/>\n        <xsd:attribute name=\"description\"   type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"author\"        type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPedestrian\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\"/>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:all>\n        <xsd:attribute name=\"model\"     type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"mass\"      type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"category\"  type=\"Enum_Pedestrian_category\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCVehicle\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\"/>\n            <xsd:element name=\"Performance\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"maxSpeed\"          type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"maxDeceleration\"   type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"mass\"              type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Axles\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Front\" type=\"OSCAxle\"/>\n                        <xsd:element name=\"Rear\" type=\"OSCAxle\"/>\n                        <xsd:element name=\"Additional\" type=\"OSCAxle\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                    </xsd:sequence>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:all>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"category\"  type=\"Enum_Vehicle_category\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCAxle\">\n        <xsd:attribute name=\"maxSteering\"   type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"wheelDiameter\" type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"trackWidth\"    type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"positionX\"     type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"positionZ\"     type=\"xsd:double\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCMiscObject\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\"/>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:all>\n        <xsd:attribute name=\"category\"  type=\"Enum_MiscObject_category\" use=\"required\"/>\n        <xsd:attribute name=\"mass\"      type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCCondition\">\n        <xsd:choice>\n            <xsd:element name=\"ByEntity\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"TriggeringEntities\">\n                            <xsd:complexType>\n                                <xsd:sequence>\n                                    <xsd:element name=\"Entity\" maxOccurs=\"unbounded\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:sequence>\n                                <xsd:attribute name=\"rule\" type=\"Enum_TriggeringEntities_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"EntityCondition\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"EndOfRoad\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"duration\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Collision\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"ByEntity\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"ByType \">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"type\" type=\"OSCObjectType\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Offroad\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"duration\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TimeHeadway\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"entity\"        type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\"     type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"alongRoute\"    type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"          type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TimeToCollision\">\n                                        <xsd:complexType>\n                                            <xsd:all>\n                                                <xsd:element name=\"Target\">\n                                                    <xsd:complexType>\n                                                        <xsd:choice>\n                                                            <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                                            <xsd:element name=\"Entity\">\n                                                                <xsd:complexType>\n                                                                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                                </xsd:complexType>\n                                                            </xsd:element>\n                                                        </xsd:choice>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:all>\n                                            <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\"     type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"alongRoute\"    type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"          type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Acceleration\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"StandStill\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"duration\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Speed\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"RelativeSpeed\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"entity\"    type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"      type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TraveledDistance\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"ReachPosition\">\n                                        <xsd:complexType>\n                                            <xsd:all>\n                                                <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                            </xsd:all>\n                                            <xsd:attribute name=\"tolerance\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Distance\">\n                                        <xsd:complexType>\n                                            <xsd:all>\n                                                <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                            </xsd:all>\n                                            <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\"     type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"alongRoute\"    type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"          type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"RelativeDistance\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"entity\"    type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"type\"      type=\"Enum_RelativeDistance_type\" use=\"required\"/>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\" type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"      type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"ByState\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"AtStart\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"type\"  type=\"Enum_Story_Element_type\" use=\"required\"/>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"AfterTermination\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"type\"  type=\"Enum_Story_Element_type\" use=\"required\"/>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_AfterTermination_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Command\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Signal\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Controller\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"ByValue\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Parameter\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"TimeOfDay\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Time\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"hour\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"min\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"sec\"   type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Date\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"day\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"month\" type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"year\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"SimulationTime\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n        <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"delay\" type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"edge\"  type=\"Enum_Condition_edge\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:simpleType name=\"OSCObjectType\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"pedestrian\" />\n            <xsd:enumeration value=\"vehicle\" />\n            <xsd:enumeration value=\"miscellaneous\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:complexType name=\"OSCPrivateAction\">\n        <xsd:choice>\n            <xsd:element name=\"Longitudinal\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Speed\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"shape\"     type=\"Enum_Dynamics_shape\" use=\"required\"/>\n                                            <xsd:attribute name=\"rate\"      type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"time\"      type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"distance\"  type=\"xsd:double\" use=\"optional\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Target\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Relative\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"object\"        type=\"xsd:string\" use=\"required\"/>\n                                                        <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"valueType\"     type=\"Enum_Speed_Target_valueType\" use=\"required\"/>\n                                                        <xsd:attribute name=\"continuous\"    type=\"xsd:boolean\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Absolute\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\"  type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Distance\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"None\"/>\n                                                <xsd:element name=\"Limited\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"maxAcceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxDeceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxSpeed\"          type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"object\"    type=\"xsd:string\"   use=\"required\"/>\n                                <xsd:attribute name=\"distance\"  type=\"xsd:double\"   use=\"optional\"/>\n                                <xsd:attribute name=\"timeGap\"   type=\"xsd:double\"   use=\"optional\"/>\n                                <xsd:attribute name=\"freespace\" type=\"xsd:boolean\"  use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Lateral\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"LaneChange\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"time\"      type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"distance\"  type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"shape\"     type=\"Enum_Dynamics_shape\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Target\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Relative\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                                                        <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Absolute\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\"  type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"targetLaneOffset\" type=\"xsd:double\" use=\"optional\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"LaneOffset\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"maxLateralAcc\" type=\"xsd:double\"/>\n                                            <xsd:attribute name=\"duration\"      type=\"xsd:double\"/>\n                                            <xsd:attribute name=\"shape\"         type=\"Enum_Dynamics_shape\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Target\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Relative\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                                                        <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Absolute\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\"  type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Distance\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"None\"/>\n                                                <xsd:element name=\"Limited\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"maxAcceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxDeceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxSpeed\"          type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"distance\"  type=\"xsd:double\"/>\n                                <xsd:attribute name=\"freespace\" type=\"xsd:boolean\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Visibility\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"graphics\"  type=\"xsd:boolean\" use=\"required\"/>\n                    <xsd:attribute name=\"traffic\"   type=\"xsd:boolean\" use=\"required\"/>\n                    <xsd:attribute name=\"sensors\"   type=\"xsd:boolean\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Meeting\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"mode\"          type=\"Enum_Meeting_Position_mode\" use=\"required\"/>\n                    <xsd:attribute name=\"timingOffset\"  type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Autonomous\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"activate\"  type=\"xsd:boolean\" use=\"required\"/>\n                    <xsd:attribute name=\"domain\"    type=\"Enum_Controller_domain\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Controller\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Assign\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Driver\"                  type=\"OSCDriver\"/>\n                                    <xsd:element name=\"PedestrianController\"    type=\"OSCPedestrianController\"/>\n                                    <xsd:element name=\"CatalogReference\"        type=\"OSCCatalogReference\"/>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Override\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Throttle\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Brake\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Clutch\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"ParkingBrake\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"SteeringWheel\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Gear\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"number\"    type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n            <xsd:element name=\"Routing\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"FollowRoute\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Route\"               type=\"OSCRoute\"/>\n                                    <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"FollowTrajectory\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Trajectory\"          type=\"OSCTrajectory\"        minOccurs=\"0\"/> <!--todo: only one of Trajectory or CatalogReference is allowed -->\n                                    <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"  minOccurs=\"0\"/> <!--todo: only one of Trajectory or CatalogReference is allowed -->\n                                    <xsd:element name=\"Longitudinal\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"None\"/>\n                                                <xsd:element name=\"Timing\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"domain\"    type=\"Enum_domain_absolute_relative\" use=\"required\"/>\n                                                        <xsd:attribute name=\"scale\"     type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"offset\"    type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Lateral\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"purpose\" type=\"Enum_Lateral_purpose\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"AcquirePosition\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCUserDefinedAction\">\n        <xsd:choice>\n            <xsd:element name=\"Command\" type=\"xsd:string\"/>\n            <xsd:element name=\"Script\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"OSCParameterAssignment\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"file\"      type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"execution\" type=\"Enum_Script_execution\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCGlobalAction\">\n        <xsd:choice>\n            <xsd:element name=\"SetEnvironment\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Environment\"         type=\"OSCEnvironment\"/>\n                        <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Entity\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Add\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Delete\"/>\n                    </xsd:choice>\n                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Parameter\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Set\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Modify\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Rule\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Add\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Multiply\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Infrastructure\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Signal\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"SetController\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"SetState\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Traffic\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Source\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\"            type=\"OSCPosition\"/>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"rate\"      type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"radius\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Sink\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\"            type=\"OSCPosition\"/>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"rate\"      type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"radius\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Swarm\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"CentralObject\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"semiMajorAxis\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"semiMinorAxis\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"innerRadius\"   type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"offset\"        type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Jam\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\"            type=\"OSCPosition\"/>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"direction\" type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"speed\"     type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"length\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCManeuver\">\n        <xsd:sequence>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Event\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Action\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Global\"      type=\"OSCGlobalAction\"/>\n                                    <xsd:element name=\"UserDefined\" type=\"OSCUserDefinedAction\"/>\n                                    <xsd:element name=\"Private\"     type=\"OSCPrivateAction\"/>\n                                </xsd:choice>\n                                <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"StartConditions\">\n                            <xsd:complexType>\n                                <xsd:sequence>\n                                    <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                </xsd:sequence>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"priority\"  type=\"Enum_event_priority\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCTrafficDefinition\">\n        <xsd:all>\n            <xsd:element name=\"VehicleDistribution\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Vehicle\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"category\"      type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"percentage\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"DriverDistribution\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Driver\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"percentage\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCEnvironment\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"TimeOfDay\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Time\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"hour\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"min\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"sec\"   type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Date\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"day\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"month\" type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"year\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                    <xsd:attribute name=\"animation\" type=\"xsd:boolean\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Weather\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Sun\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"intensity\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"azimuth\"   type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"elevation\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Fog\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\" minOccurs=\"0\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"visualRange\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Precipitation\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"type\"      type=\"Enum_Precipitation_type\" use=\"required\"/>\n                                <xsd:attribute name=\"intensity\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                    <xsd:attribute name=\"cloudState\" type=\"Enum_cloudState\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RoadCondition\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Effect\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"intensity\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"frictionScale\" type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n        <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPedestrianController\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Description\" type=\"OSCPersonDescription\"/>\n        </xsd:all>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCDriver\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Description\" type=\"OSCPersonDescription\"/>\n        </xsd:all>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPersonDescription\">\n        <xsd:sequence>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:sequence>\n        <xsd:attribute name=\"weight\"        type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"height\"        type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"eyeDistance\"   type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"age\"           type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"sex\"           type=\"Enum_sex\"   use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCRoute\">\n        <xsd:sequence>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Waypoint\" minOccurs=\"2\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"strategy\"  type=\"Enum_Route_strategy\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"closed\"    type=\"xsd:boolean\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCTrajectory\">\n        <xsd:sequence>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Vertex\" minOccurs=\"2\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                        <xsd:element name=\"Shape\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Polyline\"/>\n                                    <xsd:element name=\"Clothoid\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"curvature\"     type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"curvatureDot\"  type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"length\"        type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Spline\">\n                                        <xsd:complexType>\n                                            <xsd:sequence>\n                                                <xsd:element name=\"ControlPoint1\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"status\"    type=\"xsd:string\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"ControlPoint2\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"status\"    type=\"xsd:string\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:sequence>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"reference\" type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"closed\"    type=\"xsd:boolean\" use=\"required\"/>\n        <xsd:attribute name=\"domain\"    type=\"Enum_domain_time_distance\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPosition\">\n        <xsd:choice>\n            <xsd:element name=\"World\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"x\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"y\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"z\"  type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"h\"  type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"p\"  type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"r\"  type=\"xsd:double\" use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeWorld\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"dx\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dy\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dz\"        type=\"xsd:double\" use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeObject\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"dx\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dy\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dz\"        type=\"xsd:double\" use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Road\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"roadId\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"s\"         type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"t\"         type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeRoad\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"ds\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dt\"        type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Lane\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"roadId\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"laneId\"    type=\"xsd:int\" use=\"required\"/>\n                    <xsd:attribute name=\"offset\"    type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"s\"         type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeLane\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\"   use=\"required\"/>\n                    <xsd:attribute name=\"dLane\"     type=\"xsd:int\"      use=\"required\"/>\n                    <xsd:attribute name=\"ds\"        type=\"xsd:double\"   use=\"required\"/>\n                    <xsd:attribute name=\"offset\"    type=\"xsd:double\"   use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Route\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"RouteRef\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Route\"               type=\"OSCRoute\"/>\n                                    <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                        <xsd:element name=\"Position\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Current\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"object\"    type=\"xsd:string\"   use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"RoadCoord\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"pathS\" type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"t\"     type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"LaneCoord\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"pathS\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"laneId\"        type=\"xsd:int\" use=\"required\"/>\n                                            <xsd:attribute name=\"laneOffset\"    type=\"xsd:double\" use=\"optional\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCBoundingBox\">\n        <xsd:all>\n            <xsd:element name=\"Center\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"x\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"y\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"z\"  type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Dimension\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"width\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"length\" type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"height\" type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCProperties\">\n        <xsd:sequence>\n            <xsd:element name=\"Property\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"File\" type=\"OSCFile\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCOrientation\">\n        <xsd:attribute name=\"type\"  type=\"Enum_Orientation_type\" use=\"optional\"/>\n        <xsd:attribute name=\"h\"     type=\"xsd:double\" use=\"optional\"/>\n        <xsd:attribute name=\"p\"     type=\"xsd:double\" use=\"optional\"/>\n        <xsd:attribute name=\"r\"     type=\"xsd:double\" use=\"optional\"/>\n    </xsd:complexType>\n    \n    \n    <!-- **************************************************************\n    ************************ Enumerations ************************\n    ************************************************************** -->\n    \n    <xsd:simpleType name=\"Enum_Route_strategy\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"fastest\" />\n            <xsd:enumeration value=\"shortest\" />\n            <xsd:enumeration value=\"leastIntersections\" />\n            <xsd:enumeration value=\"random\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_sex\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"male\" />\n            <xsd:enumeration value=\"female\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Precipitation_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"dry\" />\n            <xsd:enumeration value=\"rain\" />\n            <xsd:enumeration value=\"snow\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_cloudState\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"skyOff\" />\n            <xsd:enumeration value=\"free\" />\n            <xsd:enumeration value=\"cloudy\" />\n            <xsd:enumeration value=\"overcast\" />\n            <xsd:enumeration value=\"rainy\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Orientation_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"relative\" />\n            <xsd:enumeration value=\"absolute\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_domain_time_distance\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"time\" />\n            <xsd:enumeration value=\"distance\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_domain_absolute_relative\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"absolute\" />\n            <xsd:enumeration value=\"relative\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_event_priority\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"overwrite\" />\n            <xsd:enumeration value=\"following\" />\n            <xsd:enumeration value=\"skip\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Script_execution\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"single\" />\n            <xsd:enumeration value=\"continuous\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Dynamics_shape\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"linear\" />\n            <xsd:enumeration value=\"cubic\" />\n            <xsd:enumeration value=\"sinusoidal\" />\n            <xsd:enumeration value=\"step\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Speed_Target_valueType\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"delta\" />\n            <xsd:enumeration value=\"factor\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Meeting_Position_mode\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"straight\" />\n            <xsd:enumeration value=\"route\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Controller_domain\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"longitudinal\" />\n            <xsd:enumeration value=\"lateral\" />\n            <xsd:enumeration value=\"both\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Lateral_purpose\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"position\" />\n            <xsd:enumeration value=\"steering\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Condition_edge\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"rising\" />\n            <xsd:enumeration value=\"falling\" />\n            <xsd:enumeration value=\"any\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_TriggeringEntities_rule\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"any\" />\n            <xsd:enumeration value=\"all\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_rule\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"greater_than\" />\n            <xsd:enumeration value=\"less_than\" />\n            <xsd:enumeration value=\"equal_to\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_RelativeDistance_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"longitudinal\" />\n            <xsd:enumeration value=\"lateral\" />\n            <xsd:enumeration value=\"inertial\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Story_Element_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"act\" />\n            <xsd:enumeration value=\"scene\" />\n            <xsd:enumeration value=\"maneuver\" />\n            <xsd:enumeration value=\"event\" />\n            <xsd:enumeration value=\"action\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_AfterTermination_rule\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"end\" />\n            <xsd:enumeration value=\"cancel\" />\n            <xsd:enumeration value=\"any\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_MiscObject_category\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"barrier\" />\n            <xsd:enumeration value=\"guardRail\" />\n            <xsd:enumeration value=\"other\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Vehicle_category\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"car\" />\n            <xsd:enumeration value=\"van\" />\n            <xsd:enumeration value=\"truck\" />\n            <xsd:enumeration value=\"trailer\" />\n            <xsd:enumeration value=\"semitrailer\" />\n            <xsd:enumeration value=\"bus\" />\n            <xsd:enumeration value=\"motorbike\" />\n            <xsd:enumeration value=\"bicycle\" />\n            <xsd:enumeration value=\"train\" />\n            <xsd:enumeration value=\"tram\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Pedestrian_category\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"pedestrian\" />\n            <xsd:enumeration value=\"wheelchair\" />\n            <xsd:enumeration value=\"animal\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_ByCondition_actor\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"triggeringEntity\" />\n            <xsd:enumeration value=\"anyEntity\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_OSC_Parameter_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"integer\" />\n            <xsd:enumeration value=\"double\" />\n            <xsd:enumeration value=\"string\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n</xsd:schema>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_v0.9.1.xsd",
    "content": "<?xml version=\"1.0\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n    \n    <xsd:include schemaLocation=\"OpenSCENARIO_TypeDefs.xsd\"/>\n    \n    <xsd:import namespace=\"http://www.w3.org/XML/1998/namespace\" schemaLocation=\"http://www.w3.org/2001/xml.xsd\"/>\n    \n    <xsd:annotation>\n        <xsd:documentation>\n            XML Schema Definition for OpenSCENARIO XML files - Version 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany\n        </xsd:documentation>\n    </xsd:annotation>\n    \n    <xsd:element name=\"OpenSCENARIO\">\n        <xsd:complexType>\n            <xsd:sequence>\n                <xsd:element name=\"FileHeader\"              type=\"OSCFileHeader\"/>\n                <xsd:element name=\"ParameterDeclaration\"    type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n                <xsd:element name=\"Catalogs\"                type=\"OSCCatalogs\"/>\n                <xsd:element name=\"RoadNetwork\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Logics\"      type=\"OSCFile\"/>\n                            <xsd:element name=\"SceneGraph\"  type=\"OSCFile\"/>\n                            <xsd:element name=\"Signals\"     minOccurs=\"0\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Controller\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:element name=\"Phase\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Signal\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                                                        <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                            </xsd:sequence>\n                                                            <xsd:attribute name=\"type\"      type=\"xsd:string\" use=\"required\"/>\n                                                            <xsd:attribute name=\"duration\"  type=\"xsd:double\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:sequence>\n                                                <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                                                <xsd:attribute name=\"delay\"     type=\"xsd:double\" use=\"optional\"/>\n                                                <xsd:attribute name=\"reference\" type=\"xsd:string\" use=\"optional\"/>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                        </xsd:sequence>\n                    </xsd:complexType>\n                </xsd:element>\n                <xsd:element name=\"Entities\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Object\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:choice>\n                                            <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                                            <xsd:element name=\"Vehicle\"             type=\"OSCVehicle\"/>\n                                            <xsd:element name=\"Pedestrian\"          type=\"OSCPedestrian\"/>\n                                            <xsd:element name=\"MiscObject\"          type=\"OSCMiscObject\"/>\n                                        </xsd:choice>\n                                        <xsd:element name=\"Controller\" minOccurs=\"0\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:choice>\n                                                        <xsd:element name=\"CatalogReference\"        type=\"OSCCatalogReference\"/>\n                                                        <xsd:element name=\"Driver\"                  type=\"OSCDriver\"/>\n                                                        <xsd:element name=\"PedestrianController\"    type=\"OSCPedestrianController\"/>\n                                                    </xsd:choice>\n                                                </xsd:sequence>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                            <xsd:element name=\"Selection\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Members\">\n                                            <xsd:complexType>\n                                                <xsd:choice>\n                                                    <xsd:element name=\"ByEntity\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                    <xsd:element name=\"ByType\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:attribute name=\"type\" type=\"OSCObjectType\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:choice>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                        </xsd:sequence>\n                    </xsd:complexType>\n                </xsd:element>\n                <xsd:element name=\"Storyboard\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Init\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Actions\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:element name=\"Global\" type=\"OSCGlobalAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                    <xsd:element name=\"UserDefined\" type=\"OSCUserDefinedAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                    <xsd:element name=\"Private\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Action\" type=\"OSCPrivateAction\" maxOccurs=\"unbounded\"/>\n                                                            </xsd:sequence>\n                                                            <xsd:attribute name=\"object\"  type=\"xsd:string\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:sequence>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                </xsd:complexType>\n                            </xsd:element>\n                            <xsd:element name=\"Story\" maxOccurs=\"unbounded\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Act\" maxOccurs=\"unbounded\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:element name=\"Sequence\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Actors\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"Entity\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                                                <xsd:complexType>\n                                                                                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                                                </xsd:complexType>\n                                                                            </xsd:element>\n                                                                            <xsd:element name=\"ByCondition\" minOccurs=\"0\">\n                                                                                <xsd:complexType>\n                                                                                    <xsd:attribute name=\"actor\" type=\"Enum_ByCondition_actor\" use=\"required\"/>\n                                                                                </xsd:complexType>\n                                                                            </xsd:element>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                                <xsd:element name=\"CatalogReference\" type=\"OSCCatalogReference\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                                <xsd:element name=\"Maneuver\" type=\"OSCManeuver\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                            </xsd:sequence>\n                                                            <xsd:attribute name=\"numberOfExecutions\"    type=\"xsd:int\" use=\"required\"/>\n                                                            <xsd:attribute name=\"name\"                  type=\"xsd:string\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                    <xsd:element name=\"Conditions\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Start\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                                <xsd:element name=\"End\" minOccurs=\"0\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                                <xsd:element name=\"Cancel\" minOccurs=\"0\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                            </xsd:sequence>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:sequence>\n                                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"owner\" type=\"xsd:string\" use=\"optional\"/>\n                                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                            <xsd:element name=\"EndConditions\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                    </xsd:sequence>\n                                </xsd:complexType>\n                            </xsd:element>\n                        </xsd:sequence>\n                    </xsd:complexType>\n                </xsd:element>\n            </xsd:sequence>\n        </xsd:complexType>\n    </xsd:element>\n    \n</xsd:schema>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/openscenario/0.9.x/migration0_9_1to1_0.xslt",
    "content": "<!--\nASAM OpenSCENARIO V1.0.0\n\nThis file allows transformation from version 0.9.1 to V 1.0.0\n\n© by ASAM e.V., 2020\n-->\n<xsl:stylesheet version='1.0' xmlns:xsl='http://www.w3.org/1999/XSL/Transform'>\n  <xsl:output method='xml' indent='yes' />\n  <xsl:strip-space elements='*' />\n  <xsl:template name='RelativeDistanceType'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"longitudinal\"'>longitudinal</xsl:when>\n      <xsl:when test='$oldValue=\"lateral\"'>lateral</xsl:when>\n      <xsl:otherwise>cartesianDistance</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='Rule'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"greater_than\"'>greaterThan</xsl:when>\n      <xsl:when test='$oldValue=\"less_than\"'>lessThan</xsl:when>\n      <xsl:otherwise>equalTo</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='MiscObjectCategory'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"other\"'>none</xsl:when>\n      <xsl:when test='$oldValue=\"guardRail\"'>railing</xsl:when>\n      <xsl:otherwise>barrier</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='StoryboardElementState'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"end\"'>endTransition</xsl:when>\n      <xsl:when test='$oldValue=\"cancel\"'>stopTransition</xsl:when>\n      <xsl:otherwise>completeState</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='ConditionEdge'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"any\"'>risingOrFalling</xsl:when>\n      <xsl:when test='$oldValue=\"falling\"'>falling</xsl:when>\n      <xsl:otherwise>rising</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='FollowingMode'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"position\"'>position</xsl:when>\n      <xsl:otherwise>follow</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template match='/'>\n    <xsl:call-template name='unsupportedMigration' />\n    <OpenSCENARIO>\n      <xsl:for-each select='*'>\n        <xsl:copy-of select='@*' />\n        <xsl:call-template name='OpenScenario' />\n      </xsl:for-each>\n    </OpenSCENARIO>\n  </xsl:template><xsl:template name=\"unsupportedMigration\"/>\n\n  <xsl:template name='OpenScenario'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"FileHeader\"'>\n        <FileHeader>\n          <xsl:call-template name='FileHeader' />\n        </FileHeader>\n      </xsl:if>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Catalogs\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"RoadNetwork\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Entities\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Storyboard\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Catalog\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='OpenScenarioCategory'>\n    <xsl:if test='name()=\"ParameterDeclaration\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Catalogs\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"RoadNetwork\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Entities\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Storyboard\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Catalog\"'>\n      <xsl:call-template name='CatalogDefinition' />\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='CatalogDefinition'>\n    <xsl:if test='name()=\"Catalog\"'>\n      <Catalog>\n        <xsl:call-template name='Catalog' />\n      </Catalog>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ScenarioDefinition'>\n    <xsl:if test='name()=\"ParameterDeclaration\"'>\n      <ParameterDeclarations>\n        <xsl:call-template name='ParameterDeclarations' />\n      </ParameterDeclarations>\n    </xsl:if>\n    <xsl:if test='name()=\"Catalogs\"'>\n      <CatalogLocations>\n        <xsl:call-template name='CatalogLocations' />\n      </CatalogLocations>\n    </xsl:if>\n    <xsl:if test='name()=\"RoadNetwork\"'>\n      <RoadNetwork>\n        <xsl:call-template name='RoadNetwork' />\n      </RoadNetwork>\n    </xsl:if>\n    <xsl:if test='name()=\"Entities\"'>\n      <Entities>\n        <xsl:call-template name='Entities' />\n      </Entities>\n    </xsl:if>\n    <xsl:if test='name()=\"Storyboard\"'>\n      <Storyboard>\n        <xsl:call-template name='Storyboard' />\n      </Storyboard>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='EntityObject'>\n    <xsl:if test='name()=\"CatalogReference\"'>\n      <CatalogReference>\n        <xsl:call-template name='CatalogReference' />\n      </CatalogReference>\n    </xsl:if>\n    <xsl:if test='name()=\"Vehicle\"'>\n      <Vehicle>\n        <xsl:call-template name='Vehicle' />\n      </Vehicle>\n    </xsl:if>\n    <xsl:if test='name()=\"Pedestrian\"'>\n      <Pedestrian>\n        <xsl:call-template name='Pedestrian' />\n      </Pedestrian>\n    </xsl:if>\n    <xsl:if test='name()=\"MiscObject\"'>\n      <MiscObject>\n        <xsl:call-template name='MiscObject' />\n      </MiscObject>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ParameterDeclarations'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterDeclaration>\n          <xsl:call-template name='ParameterDeclaration' />\n        </ParameterDeclaration>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='File'>\n    <xsl:if test='@filepath'>\n      <xsl:attribute name='filepath'>\n        <xsl:value-of select='@filepath' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Directory'>\n    <xsl:if test='@path'>\n      <xsl:attribute name='path'>\n        <xsl:value-of select='@path' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"CatalogLocations\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;VehicleCatalog&quot;\">\n      <VehicleCatalog>\n        <xsl:call-template name=\"VehicleCatalogLocation\"/>\n      </VehicleCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;DriverCatalog&quot;\">\n      <ControllerCatalog>\n        <xsl:call-template name=\"ControllerCatalogLocation\"/>\n      </ControllerCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianCatalog&quot;\">\n      <PedestrianCatalog>\n        <xsl:call-template name=\"PedestrianCatalogLocation\"/>\n      </PedestrianCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;MiscObjectCatalog&quot;\">\n      <MiscObjectCatalog>\n        <xsl:call-template name=\"MiscObjectCatalogLocation\"/>\n      </MiscObjectCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;EnvironmentCatalog&quot;\">\n      <EnvironmentCatalog>\n        <xsl:call-template name=\"EnvironmentCatalogLocation\"/>\n      </EnvironmentCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;ManeuverCatalog&quot;\">\n      <ManeuverCatalog>\n        <xsl:call-template name=\"ManeuverCatalogLocation\"/>\n      </ManeuverCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrajectoryCatalog&quot;\">\n      <TrajectoryCatalog>\n        <xsl:call-template name=\"TrajectoryCatalogLocation\"/>\n      </TrajectoryCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;RouteCatalog&quot;\">\n      <RouteCatalog>\n        <xsl:call-template name=\"RouteCatalogLocation\"/>\n      </RouteCatalog>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianControllerCatalog\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='ConditionGroup'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Condition\"'>\n        <Condition>\n          <xsl:call-template name='Condition' />\n        </Condition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='CatalogReference'>\n    <xsl:if test='@catalogName'>\n      <xsl:attribute name='catalogName'>\n        <xsl:value-of select='@catalogName' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@entryName'>\n      <xsl:attribute name='entryName'>\n        <xsl:value-of select='@entryName' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterAssignment\"'>\n        <ParameterAssignments>\n          <xsl:call-template name='ParameterAssignments' />\n        </ParameterAssignments>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterAssignments'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterAssignment>\n          <xsl:call-template name='ParameterAssignment' />\n        </ParameterAssignment>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='UserDataList'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"UserData\"'>\n        <UserData>\n          <xsl:call-template name='UserData' />\n        </UserData>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='FileHeader'>\n    <xsl:if test='@revMajor'>\n      <xsl:attribute name='revMajor'>\n        <xsl:value-of select='@revMajor' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@revMinor'>\n      <xsl:attribute name='revMinor'>\n        <xsl:value-of select='@revMinor' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@date'>\n      <xsl:attribute name='date'>\n        <xsl:value-of select='@date' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@description'>\n      <xsl:attribute name='description'>\n        <xsl:value-of select='@description' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@author'>\n      <xsl:attribute name='author'>\n        <xsl:value-of select='@author' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Pedestrian'>\n    <xsl:if test='@model'>\n      <xsl:attribute name='model'>\n        <xsl:value-of select='@model' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@mass'>\n      <xsl:attribute name='mass'>\n        <xsl:value-of select='@mass' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@category'>\n      <xsl:attribute name='pedestrianCategory'>\n        <xsl:value-of select='@category' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n      <xsl:if test='name()=\"Properties\"'>\n        <Properties>\n          <xsl:call-template name='Properties' />\n        </Properties>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Vehicle'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@category'>\n      <xsl:attribute name='vehicleCategory'>\n        <xsl:value-of select='@category' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n      <xsl:if test='name()=\"Performance\"'>\n        <Performance>\n          <xsl:call-template name='Performance' />\n        </Performance>\n      </xsl:if>\n      <xsl:if test='name()=\"Axles\"'>\n        <Axles>\n          <xsl:call-template name='Axles' />\n        </Axles>\n      </xsl:if>\n      <xsl:if test='name()=\"Properties\"'>\n        <Properties>\n          <xsl:call-template name='Properties' />\n        </Properties>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Axle'>\n    <xsl:if test='@maxSteering'>\n      <xsl:attribute name='maxSteering'>\n        <xsl:value-of select='@maxSteering' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@wheelDiameter'>\n      <xsl:attribute name='wheelDiameter'>\n        <xsl:value-of select='@wheelDiameter' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@trackWidth'>\n      <xsl:attribute name='trackWidth'>\n        <xsl:value-of select='@trackWidth' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@positionX'>\n      <xsl:attribute name='positionX'>\n        <xsl:value-of select='@positionX' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@positionZ'>\n      <xsl:attribute name='positionZ'>\n        <xsl:value-of select='@positionZ' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='MiscObject'>\n    <xsl:if test='@category'>\n      <xsl:attribute name='miscObjectCategory'>\n        <xsl:call-template name='MiscObjectCategory'>\n          <xsl:with-param name='oldValue' select='@category' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@mass'>\n      <xsl:attribute name='mass'>\n        <xsl:value-of select='@mass' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n      <xsl:if test='name()=\"Properties\"'>\n        <Properties>\n          <xsl:call-template name='Properties' />\n        </Properties>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Condition\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@delay\">\n    <xsl:attribute name=\"delay\">\n      <xsl:value-of select=\"@delay\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@edge\">\n    <xsl:attribute name=\"conditionEdge\">\n      <xsl:call-template name=\"ConditionEdge\">\n        <xsl:with-param name=\"oldValue\" select=\"@edge\"/>\n      </xsl:call-template>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;ByEntity&quot;\">\n      <ByEntityCondition>\n        <xsl:call-template name=\"ByEntityCondition\"/>\n      </ByEntityCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;ByState&quot;\">\n      <ByValueCondition>\n        <xsl:call-template name=\"ByStateCondition\"/>\n      </ByValueCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;ByValue&quot;\">\n      <ByValueCondition>\n        <xsl:call-template name=\"ByValueCondition\"/>\n      </ByValueCondition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"PrivateAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Longitudinal&quot;\">\n      <LongitudinalAction>\n        <xsl:call-template name=\"LongitudinalAction\"/>\n      </LongitudinalAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Lateral&quot;\">\n      <LateralAction>\n        <xsl:call-template name=\"LateralAction\"/>\n      </LateralAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Visibility&quot;\">\n      <VisibilityAction>\n        <xsl:call-template name=\"VisibilityAction\"/>\n      </VisibilityAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Meeting&quot;\">\n      <MeetingAction>\n        <xsl:call-template name=\"MeetingAction\"/>\n      </MeetingAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Autonomous&quot;\">\n      <ActivateControllerAction>\n        <xsl:call-template name=\"ActivateControllerAction\"/>\n      </ActivateControllerAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Controller&quot;\">\n      <ControllerAction>\n        <xsl:call-template name=\"ControllerAction\"/>\n      </ControllerAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <TeleportAction>\n        <Position>\n          <xsl:call-template name=\"Position\"/>\n        </Position>\n      </TeleportAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Routing&quot;\">\n      <RoutingAction>\n        <xsl:call-template name=\"RoutingAction\"/>\n      </RoutingAction>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='UserDefinedAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Command\"'>\n        <CommandAction>\n          <xsl:call-template name='CustomCommandAction' />\n        </CommandAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Script\"'>\n        <Script>\n          <xsl:call-template name='ScriptAction' />\n        </Script>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='GlobalAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"SetEnvironment\"'>\n        <EnvironmentAction>\n          <xsl:call-template name='EnvironmentAction' />\n        </EnvironmentAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Entity\"'>\n        <EntityAction>\n          <xsl:call-template name='EntityAction' />\n        </EntityAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterAction>\n          <xsl:call-template name='ParameterAction' />\n        </ParameterAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Infrastructure\"'>\n        <InfrastructureAction>\n          <xsl:call-template name='InfrastructureAction' />\n        </InfrastructureAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Traffic\"'>\n        <TrafficAction>\n          <xsl:call-template name='TrafficAction' />\n        </TrafficAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Maneuver'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"Event\"'>\n        <Event>\n          <xsl:call-template name='Event' />\n        </Event>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficDefinition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"VehicleDistribution\"'>\n        <VehicleCategoryDistribution>\n          <xsl:call-template name='VehicleCategoryDistribution' />\n        </VehicleCategoryDistribution>\n      </xsl:if>\n      <xsl:if test='name()=\"DriverDistribution\"'>\n        <ControllerDistribution>\n          <xsl:call-template name='ControllerDistribution' />\n        </ControllerDistribution>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Environment'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeOfDay\"'>\n        <TimeOfDay>\n          <xsl:call-template name='TimeOfDay' />\n        </TimeOfDay>\n      </xsl:if>\n      <xsl:if test='name()=\"Weather\"'>\n        <Weather>\n          <xsl:call-template name='Weather' />\n        </Weather>\n      </xsl:if>\n      <xsl:if test='name()=\"RoadCondition\"'>\n        <RoadCondition>\n          <xsl:call-template name='RoadCondition' />\n        </RoadCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Controller\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;ParameterDeclaration&quot;\">\n      <ParameterDeclarations>\n        <xsl:call-template name=\"ParameterDeclarations\"/>\n      </ParameterDeclarations>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Description&quot;\">\n      <Properties>\n        <xsl:call-template name=\"PersonDescription\"/>\n      </Properties>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"PersonDescription\">\n  <xsl:if test=\"@weight\">\n    <Property name=\"weight\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@weight\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@height\">\n    <Property name=\"height\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@height\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@eyeDistance\">\n    <Property name=\"eyeDistance\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@eyeDistance\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@age\">\n    <Property name=\"age\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@age\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@sex\">\n    <Property name=\"sex\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@sex\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Properties&quot;\">\n      <xsl:call-template name=\"Properties\"/>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='Route'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@closed'>\n      <xsl:attribute name='closed'>\n        <xsl:value-of select='@closed' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"Waypoint\"'>\n        <Waypoint>\n          <xsl:call-template name='Waypoint' />\n        </Waypoint>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Trajectory\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@closed\">\n    <xsl:attribute name=\"closed\">\n      <xsl:value-of select=\"@closed\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;ParameterDeclaration&quot;\">\n      <ParameterDeclarations>\n        <xsl:call-template name=\"ParameterDeclarations\"/>\n      </ParameterDeclarations>\n    </xsl:if>\n  </xsl:for-each>\n  <Shape>\n    <Polyline>\n      <xsl:for-each select=\"*\">\n        <xsl:if test=\"name()=&quot;Vertex&quot;\">\n          <Vertex>\n            <xsl:call-template name=\"Vertex\"/>\n          </Vertex>\n        </xsl:if>\n      </xsl:for-each>\n    </Polyline>\n  </Shape>\n  <xsl:message terminate=\"no\">\n    WARNING: OSCTrajectory is restructured and connot be automatically migrated. Review XML\n  </xsl:message>\n</xsl:template>\n\n  <xsl:template name='Position'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"World\"'>\n        <WorldPosition>\n          <xsl:call-template name='WorldPosition' />\n        </WorldPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeWorld\"'>\n        <RelativeWorldPosition>\n          <xsl:call-template name='RelativeWorldPosition' />\n        </RelativeWorldPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeObject\"'>\n        <RelativeObjectPosition>\n          <xsl:call-template name='RelativeObjectPosition' />\n        </RelativeObjectPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"Road\"'>\n        <RoadPosition>\n          <xsl:call-template name='RoadPosition' />\n        </RoadPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeRoad\"'>\n        <RelativeRoadPosition>\n          <xsl:call-template name='RelativeRoadPosition' />\n        </RelativeRoadPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"Lane\"'>\n        <LanePosition>\n          <xsl:call-template name='LanePosition' />\n        </LanePosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeLane\"'>\n        <RelativeLanePosition>\n          <xsl:call-template name='RelativeLanePosition' />\n        </RelativeLanePosition>\n      </xsl:if>\n      <xsl:if test='name()=\"Route\"'>\n        <RoutePosition>\n          <xsl:call-template name='RoutePosition' />\n        </RoutePosition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='BoundingBox'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Center\"'>\n        <Center>\n          <xsl:call-template name='Center' />\n        </Center>\n      </xsl:if>\n      <xsl:if test='name()=\"Dimension\"'>\n        <Dimensions>\n          <xsl:call-template name='Dimensions' />\n        </Dimensions>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Properties'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Property\"'>\n        <Property>\n          <xsl:call-template name='Property' />\n        </Property>\n      </xsl:if>\n      <xsl:if test='name()=\"File\"'>\n        <File>\n          <xsl:call-template name='File' />\n        </File>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Orientation'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@h'>\n      <xsl:attribute name='h'>\n        <xsl:value-of select='@h' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@p'>\n      <xsl:attribute name='p'>\n        <xsl:value-of select='@p' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@r'>\n      <xsl:attribute name='r'>\n        <xsl:value-of select='@r' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"Catalog\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Vehicle&quot;\">\n      <Vehicle>\n        <xsl:call-template name=\"Vehicle\"/>\n      </Vehicle>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Driver&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Pedestrian&quot;\">\n      <Pedestrian>\n        <xsl:call-template name=\"Pedestrian\"/>\n      </Pedestrian>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianController&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;MiscObject&quot;\">\n      <MiscObject>\n        <xsl:call-template name=\"MiscObject\"/>\n      </MiscObject>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Environment&quot;\">\n      <Environment>\n        <xsl:call-template name=\"Environment\"/>\n      </Environment>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Maneuver&quot;\">\n      <Maneuver>\n        <xsl:call-template name=\"Maneuver\"/>\n      </Maneuver>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Trajectory&quot;\">\n      <Trajectory>\n        <xsl:call-template name=\"Trajectory\"/>\n      </Trajectory>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Route&quot;\">\n      <Route>\n        <xsl:call-template name=\"Route\"/>\n      </Route>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianController\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='RoadNetwork'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Logics\"'>\n        <LogicFile>\n          <xsl:call-template name='File' />\n        </LogicFile>\n      </xsl:if>\n      <xsl:if test='name()=\"SceneGraph\"'>\n        <SceneGraphFile>\n          <xsl:call-template name='File' />\n        </SceneGraphFile>\n      </xsl:if>\n      <xsl:if test='name()=\"Signals\"'>\n        <TrafficSignals>\n          <xsl:call-template name='TrafficSignals' />\n        </TrafficSignals>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"TrafficSignals\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Controller&quot;\">\n      <TrafficSignalController>\n        <xsl:call-template name=\"TrafficSignalController\"/>\n      </TrafficSignalController>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='TrafficSignalController'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@delay'>\n      <xsl:attribute name='delay'>\n        <xsl:value-of select='@delay' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@reference'>\n      <xsl:attribute name='reference'>\n        <xsl:value-of select='@reference' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Phase\"'>\n        <Phase>\n          <xsl:call-template name='Phase' />\n        </Phase>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Phase'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Signal\"'>\n        <TrafficSignalState>\n          <xsl:call-template name='TrafficSignalState' />\n        </TrafficSignalState>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficSignalState'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='trafficSignalId'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='state'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Entities'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Object\"'>\n        <ScenarioObject>\n          <xsl:call-template name='ScenarioObject' />\n        </ScenarioObject>\n      </xsl:if>\n      <xsl:if test='name()=\"Selection\"'>\n        <EntitySelection>\n          <xsl:call-template name='EntitySelection' />\n        </EntitySelection>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ScenarioObject'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"Vehicle\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"Pedestrian\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"MiscObject\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"Controller\"'>\n        <ObjectController>\n          <xsl:call-template name='ObjectController' />\n        </ObjectController>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"ObjectController\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;CatalogReference&quot;\">\n      <CatalogReference>\n        <xsl:call-template name=\"CatalogReference\"/>\n      </CatalogReference>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Driver&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianController&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianController\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='EntitySelection'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Members\"'>\n        <Members>\n          <xsl:call-template name='SelectedEntities' />\n        </Members>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='SelectedEntities'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ByEntity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n      <xsl:if test='name()=\"ByType\"'>\n        <ByType>\n          <xsl:call-template name='ByType' />\n        </ByType>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EntityRef'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ByType'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='objectType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Storyboard'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Init\"'>\n        <Init>\n          <xsl:call-template name='Init' />\n        </Init>\n      </xsl:if>\n      <xsl:if test='name()=\"Story\"'>\n        <Story>\n          <xsl:call-template name='Story' />\n        </Story>\n      </xsl:if>\n      <xsl:if test='name()=\"EndConditions\"'>\n        <StopTrigger>\n          <xsl:call-template name='Trigger' />\n        </StopTrigger>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Init'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Actions\"'>\n        <Actions>\n          <xsl:call-template name='InitActions' />\n        </Actions>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"InitActions\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Global&quot;\">\n      <xsl:if test=\"not(Traffic/Jam)\">\n        <GlobalAction>\n          <xsl:call-template name=\"GlobalAction\"/>\n        </GlobalAction>\n      </xsl:if>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;UserDefined&quot;\">\n      <xsl:if test=\"not(Script)\">\n        <UserDefinedAction>\n          <xsl:call-template name=\"UserDefinedAction\"/>\n        </UserDefinedAction>\n      </xsl:if>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Private&quot;\">\n      <Private>\n        <xsl:call-template name=\"Private\"/>\n      </Private>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"Global/Traffic/Jam\">\n    <xsl:message terminate=\"no\">\n      WARNING: Jam is desupported: removed during migration\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"UserDefined/Script\">\n    <xsl:message terminate=\"no\">\n      WARNING: Script is desupported: removed during migration\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n<xsl:template name=\"Private\">\n  <xsl:if test=\"@object\">\n    <xsl:attribute name=\"entityRef\">\n      <xsl:value-of select=\"@object\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Action&quot;\">\n      <xsl:if test=\"not(Meeting)\">\n        <PrivateAction>\n          <xsl:call-template name=\"PrivateAction\"/>\n        </PrivateAction>\n      </xsl:if>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"Action/Meeting\">\n    <xsl:message terminate=\"no\">\n      WARNING: OSCPrivateAction.Meeting is desupported: removed during migration\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n<xsl:template name=\"Story\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@owner and @owner != &quot;&quot;\">\n    <ParameterDeclarations>\n      <ParameterDeclaration parameterType=\"string\" name=\"$owner\">\n        <xsl:attribute name=\"value\">\n          <xsl:value-of select=\"@owner\"/>\n        </xsl:attribute>\n      </ParameterDeclaration>\n    </ParameterDeclarations>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Act&quot;\">\n      <Act>\n        <xsl:call-template name=\"Act\"/>\n      </Act>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"Act\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Sequence&quot;\">\n      <ManeuverGroup>\n        <xsl:call-template name=\"ManeuverGroup\"/>\n      </ManeuverGroup>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Conditions&quot;\">\n      <xsl:for-each select=\"*\">\n        <xsl:if test=\"name()=&quot;Start&quot;\">\n          <StartTrigger>\n            <xsl:call-template name=\"Trigger\"/>\n          </StartTrigger>\n        </xsl:if>\n        <xsl:if test=\"name()=&quot;End&quot;\">\n          <StopTrigger>\n            <xsl:call-template name=\"Trigger\"/>\n          </StopTrigger>\n        </xsl:if>\n        <xsl:if test=\"name()=&quot;Cancel&quot;\">\n          <StopTrigger>\n            <xsl:call-template name=\"Trigger\"/>\n          </StopTrigger>\n        </xsl:if>\n      </xsl:for-each>\n    </xsl:if>\n    <xsl:if test=\"Cancel and End\">\n      <xsl:message terminate=\"no\">\n        ERROR: Act: Cancel and End are both defined: Version 1.0 only supports Stop Trigger. Invalid XML is produced and needs to be revisited.\n      </xsl:message>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='ManeuverGroup'>\n    <xsl:if test='@numberOfExecutions'>\n      <xsl:attribute name='maximumExecutionCount'>\n        <xsl:value-of select='@numberOfExecutions' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Actors\"'>\n        <Actors>\n          <xsl:call-template name='Actors' />\n        </Actors>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n      <xsl:if test='name()=\"Maneuver\"'>\n        <Maneuver>\n          <xsl:call-template name='Maneuver' />\n        </Maneuver>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Actors\">\n  <xsl:choose>\n    <xsl:when test=\"ByCondition\">\n      <xsl:if test=\"ByCondition[@actor = &quot;triggeringEntity&quot;]\">\n        <xsl:attribute name=\"selectTriggeringEntities\">\n          <xsl:value-of select=\"&quot;true&quot;\"/>\n        </xsl:attribute>\n      </xsl:if>\n      <xsl:if test=\"ByCondition[@actor = &quot;anyEntity&quot;]\">\n        <xsl:attribute name=\"selectTriggeringEntities\">\n          <xsl:value-of select=\"&quot;false&quot;\"/>\n        </xsl:attribute>\n        <xsl:message terminate=\"no\">\n          WARNING: Storyboard.Story.Act.Sequence.Actors.ByCondition: \"anyEntity\" is de-supported for version 1.0\n        </xsl:message>\n      </xsl:if>\n    </xsl:when>\n    <xsl:otherwise>\n      <xsl:attribute name=\"selectTriggeringEntities\">\n        <xsl:value-of select=\"&quot;false&quot;\"/>\n      </xsl:attribute>\n    </xsl:otherwise>\n  </xsl:choose>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Entity&quot;\">\n      <EntityRef>\n        <xsl:call-template name=\"EntityRef\"/>\n      </EntityRef>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='SelectActorByTrigger'>\n    <xsl:if test='@actor'>\n      <xsl:attribute name='selectionFilter'>\n        <xsl:value-of select='@actor' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ConditionSet'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Start\"'>\n        <StartConditions>\n          <xsl:call-template name='Trigger' />\n        </StartConditions>\n      </xsl:if>\n      <xsl:if test='name()=\"End\"'>\n        <EndConditions>\n          <xsl:call-template name='Trigger' />\n        </EndConditions>\n      </xsl:if>\n      <xsl:if test='name()=\"Cancel\"'>\n        <CancelConditions>\n          <xsl:call-template name='Trigger' />\n        </CancelConditions>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Trigger'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ConditionGroup\"'>\n        <ConditionGroup>\n          <xsl:call-template name='ConditionGroup' />\n        </ConditionGroup>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterDeclaration'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@type'>\n      <xsl:attribute name='parameterType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='VehicleCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ControllerCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='PedestrianCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='MiscObjectCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EnvironmentCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ManeuverCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrajectoryCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RouteCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterAssignment'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='parameterRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='UserData'>\n    <xsl:if test='@code'>\n      <xsl:attribute name='code'>\n        <xsl:value-of select='@code' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"Performance\">\n  <xsl:if test=\"@maxSpeed\">\n    <xsl:attribute name=\"maxSpeed\">\n      <xsl:value-of select=\"@maxSpeed\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@maxAcceleration\">\n    <xsl:attribute name=\"maxAcceleration\">\n      <xsl:value-of select=\"@maxAcceleration\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@maxDeceleration\">\n    <xsl:attribute name=\"maxDeceleration\">\n      <xsl:value-of select=\"@maxDeceleration\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='Axles'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Front\"'>\n        <FrontAxle>\n          <xsl:call-template name='Axle' />\n        </FrontAxle>\n      </xsl:if>\n      <xsl:if test='name()=\"Rear\"'>\n        <RearAxle>\n          <xsl:call-template name='Axle' />\n        </RearAxle>\n      </xsl:if>\n      <xsl:if test='name()=\"Additional\"'>\n        <AdditionalAxle>\n          <xsl:call-template name='Axle' />\n        </AdditionalAxle>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ByEntityCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"TriggeringEntities\"'>\n        <TriggeringEntities>\n          <xsl:call-template name='TriggeringEntities' />\n        </TriggeringEntities>\n      </xsl:if>\n      <xsl:if test='name()=\"EntityCondition\"'>\n        <EntityCondition>\n          <xsl:call-template name='EntityCondition' />\n        </EntityCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TriggeringEntities'>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='triggeringEntitiesRule'>\n        <xsl:value-of select='@rule' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Entity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EntityCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"EndOfRoad\"'>\n        <EndOfRoadCondition>\n          <xsl:call-template name='EndOfRoadCondition' />\n        </EndOfRoadCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Collision\"'>\n        <CollisionCondition>\n          <xsl:call-template name='CollisionCondition' />\n        </CollisionCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Offroad\"'>\n        <OffroadCondition>\n          <xsl:call-template name='OffroadCondition' />\n        </OffroadCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeHeadway\"'>\n        <TimeHeadwayCondition>\n          <xsl:call-template name='TimeHeadwayCondition' />\n        </TimeHeadwayCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeToCollision\"'>\n        <TimeToCollisionCondition>\n          <xsl:call-template name='TimeToCollisionCondition' />\n        </TimeToCollisionCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Acceleration\"'>\n        <AccelerationCondition>\n          <xsl:call-template name='AccelerationCondition' />\n        </AccelerationCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"StandStill\"'>\n        <StandStillCondition>\n          <xsl:call-template name='StandStillCondition' />\n        </StandStillCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Speed\"'>\n        <SpeedCondition>\n          <xsl:call-template name='SpeedCondition' />\n        </SpeedCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeSpeed\"'>\n        <RelativeSpeedCondition>\n          <xsl:call-template name='RelativeSpeedCondition' />\n        </RelativeSpeedCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TraveledDistance\"'>\n        <TraveledDistanceCondition>\n          <xsl:call-template name='TraveledDistanceCondition' />\n        </TraveledDistanceCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"ReachPosition\"'>\n        <ReachPositionCondition>\n          <xsl:call-template name='ReachPositionCondition' />\n        </ReachPositionCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Distance\"'>\n        <DistanceCondition>\n          <xsl:call-template name='DistanceCondition' />\n        </DistanceCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeDistance\"'>\n        <RelativeDistanceCondition>\n          <xsl:call-template name='RelativeDistanceCondition' />\n        </RelativeDistanceCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EndOfRoadCondition'>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='CollisionCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ByEntity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n      <xsl:if test='name()=\"ByType\"'>\n        <ByType>\n          <xsl:call-template name='ByObjectType' />\n        </ByType>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ByObjectType'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OffroadCondition'>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TimeHeadwayCondition'>\n    <xsl:if test='@entity'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@entity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@alongRoute'>\n      <xsl:attribute name='alongRoute'>\n        <xsl:value-of select='@alongRoute' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TimeToCollisionCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@alongRoute'>\n      <xsl:attribute name='alongRoute'>\n        <xsl:value-of select='@alongRoute' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Target\"'>\n        <TimeToCollisionConditionTarget>\n          <xsl:call-template name='TimeToCollisionConditionTarget' />\n        </TimeToCollisionConditionTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TimeToCollisionConditionTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n      <xsl:if test='name()=\"Entity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='AccelerationCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='StandStillCondition'>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='SpeedCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='RelativeSpeedCondition'>\n    <xsl:if test='@entity'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@entity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TraveledDistanceCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ReachPositionCondition'>\n    <xsl:if test='@tolerance'>\n      <xsl:attribute name='tolerance'>\n        <xsl:value-of select='@tolerance' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='DistanceCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@alongRoute'>\n      <xsl:attribute name='alongRoute'>\n        <xsl:value-of select='@alongRoute' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeDistanceCondition'>\n    <xsl:if test='@entity'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@entity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@type'>\n      <xsl:attribute name='relativeDistanceType'>\n        <xsl:call-template name='RelativeDistanceType'>\n          <xsl:with-param name='oldValue' select='@type' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"ByStateCondition\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;AtStart&quot;\">\n      <StoryboardElementStateCondition>\n        <xsl:if test=\"@type\">\n          <xsl:attribute name=\"storyboardElementType\">\n            <xsl:value-of select=\"@type\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:if test=\"@name\">\n          <xsl:attribute name=\"storyboardElementRef\">\n            <xsl:value-of select=\"@name\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:attribute name=\"state\">\n          <xsl:value-of select=\"'startTransition'\"/>\n        </xsl:attribute>\n      </StoryboardElementStateCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;AfterTermination&quot;\">\n      <StoryboardElementStateCondition>\n        <xsl:call-template name=\"StoryboardElementStateCondition\"/>\n      </StoryboardElementStateCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Command&quot;\">\n      <UserDefinedValueCondition>\n        <xsl:call-template name=\"UserDefinedValueCondition\"/>\n      </UserDefinedValueCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Signal&quot;\">\n      <TrafficSignalCondition>\n        <xsl:call-template name=\"TrafficSignalCondition\"/>\n      </TrafficSignalCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Controller&quot;\">\n      <TrafficSignalControllerCondition>\n        <xsl:call-template name=\"TrafficSignalControllerCondition\"/>\n      </TrafficSignalControllerCondition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='AtStartCondition'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='StoryboardElementStateCondition'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='storyboardElementType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='storyboardElementRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='state'>\n        <xsl:call-template name='StoryboardElementState'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"UserDefinedValueCondition\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:attribute name=\"rule\">\n    <xsl:value-of select=\"'equalTo'\"/>\n  </xsl:attribute>\n  <xsl:attribute name=\"value\">\n    <xsl:value-of select=\"'true'\"/>\n  </xsl:attribute>\n</xsl:template>\n\n  <xsl:template name='TrafficSignalCondition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='state'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficSignalControllerCondition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='trafficSignalControllerRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='phase'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ByValueCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterCondition>\n          <xsl:call-template name='ParameterCondition' />\n        </ParameterCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeOfDay\"'>\n        <TimeOfDayCondition>\n          <xsl:call-template name='TimeOfDayCondition' />\n        </TimeOfDayCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"SimulationTime\"'>\n        <SimulationTimeCondition>\n          <xsl:call-template name='SimulationTimeCondition' />\n        </SimulationTimeCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterCondition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='parameterRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"TimeOfDayCondition\">\n  <xsl:if test=\"@rule\">\n    <xsl:attribute name=\"rule\">\n      <xsl:call-template name=\"Rule\">\n        <xsl:with-param name=\"oldValue\" select=\"@rule\"/>\n      </xsl:call-template>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:variable name=\"hour\" select=\"Time/@hour\"/>\n  <xsl:variable name=\"min\" select=\"Time/@min\"/>\n  <xsl:variable name=\"sec\" select=\"Time/@sec\"/>\n  <xsl:variable name=\"day\" select=\"Date/@day\"/>\n  <xsl:variable name=\"month\" select=\"Date/@month\"/>\n  <xsl:variable name=\"year\" select=\"Date/@year\"/>\n  <xsl:attribute name=\"dateTime\">\n    <xsl:value-of select=\"format-number($year,'0000')\"/>\n    <xsl:value-of select=\"format-number($month,'-00')\"/>\n    <xsl:value-of select=\"format-number($day,'-00')\"/>\n    <xsl:value-of select=\"format-number($hour,'T00')\"/>\n    <xsl:value-of select=\"format-number($min,':00')\"/>\n    <xsl:value-of select=\"format-number($sec,':00')\"/>\n  </xsl:attribute>\n</xsl:template>\n\n  <xsl:template name='Time'>\n    <xsl:if test='@hour'>\n      <xsl:attribute name='hour'>\n        <xsl:value-of select='@hour' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@min'>\n      <xsl:attribute name='min'>\n        <xsl:value-of select='@min' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@sec'>\n      <xsl:attribute name='sec'>\n        <xsl:value-of select='@sec' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Date'>\n    <xsl:if test='@day'>\n      <xsl:attribute name='day'>\n        <xsl:value-of select='@day' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@month'>\n      <xsl:attribute name='month'>\n        <xsl:value-of select='@month' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@year'>\n      <xsl:attribute name='year'>\n        <xsl:value-of select='@year' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='SimulationTimeCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LongitudinalAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Speed&quot;\">\n      <SpeedAction>\n        <xsl:call-template name=\"SpeedAction\"/>\n      </SpeedAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Distance&quot;\">\n      <LongitudinalDistanceAction continuous=\"true\">\n        <xsl:call-template name=\"LongitudinalDistanceAction\"/>\n      </LongitudinalDistanceAction>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='SpeedAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Dynamics\"'>\n        <SpeedActionDynamics>\n          <xsl:call-template name='TransitionDynamics' />\n        </SpeedActionDynamics>\n      </xsl:if>\n      <xsl:if test='name()=\"Target\"'>\n        <SpeedActionTarget>\n          <xsl:call-template name='SpeedActionTarget' />\n        </SpeedActionTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"TransitionDynamics\">\n  <xsl:if test=\"@shape\">\n    <xsl:attribute name=\"dynamicsShape\">\n      <xsl:value-of select=\"@shape\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@rate\">\n    <xsl:attribute name=\"value\">\n      <xsl:value-of select=\"@rate\"/>\n    </xsl:attribute>\n    <xsl:attribute name=\"dynamicsDimension\">\n      <xsl:value-of select=\"&quot;rate&quot;\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@time\">\n    <xsl:attribute name=\"value\">\n      <xsl:value-of select=\"@time\"/>\n    </xsl:attribute>\n    <xsl:attribute name=\"dynamicsDimension\">\n      <xsl:value-of select=\"&quot;time&quot;\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@distance\">\n    <xsl:attribute name=\"value\">\n      <xsl:value-of select=\"@distance\"/>\n    </xsl:attribute>\n    <xsl:attribute name=\"dynamicsDimension\">\n      <xsl:value-of select=\"&quot;distance&quot;\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"(@distance and @time) or (@distance and @rate) or  (@time and @rate)\">\n    <xsl:message terminate=\"no\">\n      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.\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"not(@distance) and not(@time) and not(@rate)\">\n    <xsl:message terminate=\"no\">\n      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.\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='SpeedActionTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Relative\"'>\n        <RelativeTargetSpeed>\n          <xsl:call-template name='RelativeTargetSpeed' />\n        </RelativeTargetSpeed>\n      </xsl:if>\n      <xsl:if test='name()=\"Absolute\"'>\n        <AbsoluteTargetSpeed>\n          <xsl:call-template name='AbsoluteTargetSpeed' />\n        </AbsoluteTargetSpeed>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeTargetSpeed'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@valueType'>\n      <xsl:attribute name='speedTargetValueType'>\n        <xsl:value-of select='@valueType' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@continuous'>\n      <xsl:attribute name='continuous'>\n        <xsl:value-of select='@continuous' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AbsoluteTargetSpeed'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LongitudinalDistanceAction\">\n  <xsl:if test=\"@object\">\n    <xsl:attribute name=\"entityRef\">\n      <xsl:value-of select=\"@object\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@distance\">\n    <xsl:attribute name=\"distance\">\n      <xsl:value-of select=\"@distance\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@timeGap\">\n    <xsl:attribute name=\"timeGap\">\n      <xsl:value-of select=\"@timeGap\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@freespace\">\n    <xsl:attribute name=\"freespace\">\n      <xsl:value-of select=\"@freespace\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Dynamics&quot;\">\n      <xsl:call-template name=\"DynamicConstraints\"/>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"DynamicConstraints\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Limited&quot;\">\n      <DynamicConstraints>\n        <xsl:if test=\"@maxAcceleration\">\n          <xsl:attribute name=\"maxAcceleration\">\n            <xsl:value-of select=\"@maxAcceleration\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:if test=\"@maxDeceleration\">\n          <xsl:attribute name=\"maxDeceleration\">\n            <xsl:value-of select=\"@maxDeceleration\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:if test=\"@maxSpeed\">\n          <xsl:attribute name=\"maxSpeed\">\n            <xsl:value-of select=\"@maxSpeed\"/>\n          </xsl:attribute>\n        </xsl:if>\n      </DynamicConstraints>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='None' />\n  <xsl:template name='Limited'>\n    <xsl:if test='@maxAcceleration'>\n      <xsl:attribute name='maxAcceleration'>\n        <xsl:value-of select='@maxAcceleration' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@maxDeceleration'>\n      <xsl:attribute name='maxDeceleration'>\n        <xsl:value-of select='@maxDeceleration' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@maxSpeed'>\n      <xsl:attribute name='maxSpeed'>\n        <xsl:value-of select='@maxSpeed' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LateralAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;LaneChange&quot;\">\n      <LaneChangeAction>\n        <xsl:call-template name=\"LaneChangeAction\"/>\n      </LaneChangeAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;LaneOffset&quot;\">\n      <LaneOffsetAction continuous=\"true\">\n        <xsl:call-template name=\"LaneOffsetAction\"/>\n      </LaneOffsetAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Distance&quot;\">\n      <LateralDistanceAction continuous=\"true\">\n        <xsl:call-template name=\"LateralDistanceAction\"/>\n      </LateralDistanceAction>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='LaneChangeAction'>\n    <xsl:if test='@targetLaneOffset'>\n      <xsl:attribute name='targetLaneOffset'>\n        <xsl:value-of select='@targetLaneOffset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Dynamics\"'>\n        <LaneChangeActionDynamics>\n          <xsl:call-template name='TransitionDynamics' />\n        </LaneChangeActionDynamics>\n      </xsl:if>\n      <xsl:if test='name()=\"Target\"'>\n        <LaneChangeTarget>\n          <xsl:call-template name='LaneChangeTarget' />\n        </LaneChangeTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='LaneChangeTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Relative\"'>\n        <RelativeTargetLane>\n          <xsl:call-template name='RelativeTargetLane' />\n        </RelativeTargetLane>\n      </xsl:if>\n      <xsl:if test='name()=\"Absolute\"'>\n        <AbsoluteTargetLane>\n          <xsl:call-template name='AbsoluteTargetLane' />\n        </AbsoluteTargetLane>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeTargetLane'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AbsoluteTargetLane'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='LaneOffsetAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Dynamics\"'>\n        <LaneOffsetActionDynamics>\n          <xsl:call-template name='LaneOffsetActionDynamics' />\n        </LaneOffsetActionDynamics>\n      </xsl:if>\n      <xsl:if test='name()=\"Target\"'>\n        <LaneOffsetTarget>\n          <xsl:call-template name='LaneOffsetTarget' />\n        </LaneOffsetTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"LaneOffsetActionDynamics\">\n  <xsl:if test=\"@maxLateralAcc\">\n    <xsl:attribute name=\"maxLateralAcc\">\n      <xsl:value-of select=\"@maxLateralAcc\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@shape\">\n    <xsl:attribute name=\"dynamicsShape\">\n      <xsl:value-of select=\"@shape\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='LaneOffsetTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Relative\"'>\n        <RelativeTargetLaneOffset>\n          <xsl:call-template name='RelativeTargetLaneOffset' />\n        </RelativeTargetLaneOffset>\n      </xsl:if>\n      <xsl:if test='name()=\"Absolute\"'>\n        <AbsoluteTargetLaneOffset>\n          <xsl:call-template name='AbsoluteTargetLaneOffset' />\n        </AbsoluteTargetLaneOffset>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeTargetLaneOffset'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AbsoluteTargetLaneOffset'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LateralDistanceAction\">\n  <xsl:if test=\"@object\">\n    <xsl:attribute name=\"entityRef\">\n      <xsl:value-of select=\"@object\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@distance\">\n    <xsl:attribute name=\"distance\">\n      <xsl:value-of select=\"@distance\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@freespace\">\n    <xsl:attribute name=\"freespace\">\n      <xsl:value-of select=\"@freespace\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Dynamics&quot;\">\n      <xsl:call-template name=\"DynamicConstraints\"/>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='VisibilityAction'>\n    <xsl:if test='@graphics'>\n      <xsl:attribute name='graphics'>\n        <xsl:value-of select='@graphics' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@traffic'>\n      <xsl:attribute name='traffic'>\n        <xsl:value-of select='@traffic' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@sensors'>\n      <xsl:attribute name='sensors'>\n        <xsl:value-of select='@sensors' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='MeetingAction'>\n    <xsl:if test='@mode'>\n      <xsl:attribute name='meetingPositionMode'>\n        <xsl:value-of select='@mode' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@timingOffset'>\n      <xsl:attribute name='timingOffset'>\n        <xsl:value-of select='@timingOffset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"ActivateControllerAction\">\n  <xsl:if test=\"@activate and @domain = &quot;lateral&quot;\">\n    <xsl:attribute name=\"lateral\">\n      <xsl:value-of select=\"@activate\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@activate and @domain = &quot;longitudinal&quot;\">\n    <xsl:attribute name=\"longitudinal\">\n      <xsl:value-of select=\"@activate\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='ControllerAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Assign\"'>\n        <AssignControllerAction>\n          <xsl:call-template name='AssignControllerAction' />\n        </AssignControllerAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Override\"'>\n        <OverrideControllerValueAction>\n          <xsl:call-template name='OverrideControllerValueAction' />\n        </OverrideControllerValueAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"AssignControllerAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Driver&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianController&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;CatalogReference&quot;\">\n      <CatalogReference>\n        <xsl:call-template name=\"CatalogReference\"/>\n      </CatalogReference>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianController\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='OverrideControllerValueAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Throttle\"'>\n        <Throttle>\n          <xsl:call-template name='OverrideThrottleAction' />\n        </Throttle>\n      </xsl:if>\n      <xsl:if test='name()=\"Brake\"'>\n        <Brake>\n          <xsl:call-template name='OverrideBrakeAction' />\n        </Brake>\n      </xsl:if>\n      <xsl:if test='name()=\"Clutch\"'>\n        <Clutch>\n          <xsl:call-template name='OverrideClutchAction' />\n        </Clutch>\n      </xsl:if>\n      <xsl:if test='name()=\"ParkingBrake\"'>\n        <ParkingBrake>\n          <xsl:call-template name='OverrideParkingBrakeAction' />\n        </ParkingBrake>\n      </xsl:if>\n      <xsl:if test='name()=\"SteeringWheel\"'>\n        <SteeringWheel>\n          <xsl:call-template name='OverrideSteeringWheelAction' />\n        </SteeringWheel>\n      </xsl:if>\n      <xsl:if test='name()=\"Gear\"'>\n        <Gear>\n          <xsl:call-template name='OverrideGearAction' />\n        </Gear>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='OverrideThrottleAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideBrakeAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideClutchAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideParkingBrakeAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideSteeringWheelAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideGearAction'>\n    <xsl:if test='@number'>\n      <xsl:attribute name='number'>\n        <xsl:value-of select='@number' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='RoutingAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"FollowRoute\"'>\n        <AssignRouteAction>\n          <xsl:call-template name='AssignRouteAction' />\n        </AssignRouteAction>\n      </xsl:if>\n      <xsl:if test='name()=\"FollowTrajectory\"'>\n        <FollowTrajectoryAction>\n          <xsl:call-template name='FollowTrajectoryAction' />\n        </FollowTrajectoryAction>\n      </xsl:if>\n      <xsl:if test='name()=\"AcquirePosition\"'>\n        <AcquirePositionAction>\n          <xsl:call-template name='AcquirePositionAction' />\n        </AcquirePositionAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='AssignRouteAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Route\"'>\n        <Route>\n          <xsl:call-template name='Route' />\n        </Route>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='FollowTrajectoryAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Trajectory\"'>\n        <Trajectory>\n          <xsl:call-template name='Trajectory' />\n        </Trajectory>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n      <xsl:if test='name()=\"Longitudinal\"'>\n        <TimeReference>\n          <xsl:call-template name='TimeReference' />\n        </TimeReference>\n      </xsl:if>\n      <xsl:if test='name()=\"Lateral\"'>\n        <TrajectoryFollowingMode>\n          <xsl:call-template name='TrajectoryFollowingMode' />\n        </TrajectoryFollowingMode>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TimeReference'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"None\"'>\n        <None>\n          <xsl:call-template name='None' />\n        </None>\n      </xsl:if>\n      <xsl:if test='name()=\"Timing\"'>\n        <Timing>\n          <xsl:call-template name='Timing' />\n        </Timing>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Timing'>\n    <xsl:if test='@domain'>\n      <xsl:attribute name='domainAbsoluteRelative'>\n        <xsl:value-of select='@domain' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@scale'>\n      <xsl:attribute name='scale'>\n        <xsl:value-of select='@scale' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@offset'>\n      <xsl:attribute name='offset'>\n        <xsl:value-of select='@offset' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrajectoryFollowingMode'>\n    <xsl:if test='@purpose'>\n      <xsl:attribute name='followingMode'>\n        <xsl:call-template name='FollowingMode'>\n          <xsl:with-param name='oldValue' select='@purpose' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AcquirePositionAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='CustomCommandAction'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ScriptAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@file'>\n      <xsl:attribute name='file'>\n        <xsl:value-of select='@file' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@execution'>\n      <xsl:attribute name='execution'>\n        <xsl:value-of select='@execution' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterAssignment\"'>\n        <ParameterAssignment>\n          <xsl:call-template name='ParameterAssignments' />\n        </ParameterAssignment>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EnvironmentAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Environment\"'>\n        <Environment>\n          <xsl:call-template name='Environment' />\n        </Environment>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EntityAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Add\"'>\n        <AddEntityAction>\n          <xsl:call-template name='AddEntityAction' />\n        </AddEntityAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Delete\"'>\n        <DeleteEntityAction>\n          <xsl:call-template name='DeleteEntityAction' />\n        </DeleteEntityAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='AddEntityAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='DeleteEntityAction' />\n  <xsl:template name='ParameterAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='parameterRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Set\"'>\n        <SetAction>\n          <xsl:call-template name='ParameterSetAction' />\n        </SetAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Modify\"'>\n        <ModifyAction>\n          <xsl:call-template name='ParameterModifyAction' />\n        </ModifyAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterSetAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ParameterModifyAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Rule\"'>\n        <Rule>\n          <xsl:call-template name='ModifyRule' />\n        </Rule>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ModifyRule'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Add\"'>\n        <AddValue>\n          <xsl:call-template name='ParameterAddValueRule' />\n        </AddValue>\n      </xsl:if>\n      <xsl:if test='name()=\"Multiply\"'>\n        <MultiplyByValue>\n          <xsl:call-template name='ParameterMultiplyByValueRule' />\n        </MultiplyByValue>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterAddValueRule'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ParameterMultiplyByValueRule'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='InfrastructureAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Signal\"'>\n        <TrafficSignalAction>\n          <xsl:call-template name='TrafficSignalAction' />\n        </TrafficSignalAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficSignalAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"SetController\"'>\n        <TrafficSignalControllerAction>\n          <xsl:call-template name='TrafficSignalControllerAction' />\n        </TrafficSignalControllerAction>\n      </xsl:if>\n      <xsl:if test='name()=\"SetState\"'>\n        <TrafficSignalStateAction>\n          <xsl:call-template name='TrafficSignalStateAction' />\n        </TrafficSignalStateAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficSignalControllerAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='trafficSignalControllerRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='phase'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficSignalStateAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='state'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Source\"'>\n        <TrafficSourceAction>\n          <xsl:call-template name='TrafficSourceAction' />\n        </TrafficSourceAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Sink\"'>\n        <TrafficSinkAction>\n          <xsl:call-template name='TrafficSinkAction' />\n        </TrafficSinkAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Swarm\"'>\n        <TrafficSwarmAction>\n          <xsl:call-template name='TrafficSwarmAction' />\n        </TrafficSwarmAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Jam\"'>\n        <TrafficJamAction>\n          <xsl:call-template name='TrafficJamAction' />\n        </TrafficJamAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"TrafficSourceAction\">\n  <xsl:if test=\"@rate\">\n    <xsl:attribute name=\"rate\">\n      <xsl:value-of select=\"@rate\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@radius\">\n    <xsl:attribute name=\"radius\">\n      <xsl:value-of select=\"@radius\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <Position>\n        <xsl:call-template name=\"Position\"/>\n      </Position>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrafficDefinition&quot;\">\n      <TrafficDefinition>\n        <xsl:call-template name=\"TrafficDefinition\"/>\n      </TrafficDefinition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"TrafficSinkAction\">\n  <xsl:if test=\"@rate\">\n    <xsl:attribute name=\"rate\">\n      <xsl:value-of select=\"@rate\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@radius\">\n    <xsl:attribute name=\"radius\">\n      <xsl:value-of select=\"@radius\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <Position>\n        <xsl:call-template name=\"Position\"/>\n      </Position>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrafficDefinition&quot;\">\n      <TrafficDefinition>\n        <xsl:call-template name=\"TrafficDefinition\"/>\n      </TrafficDefinition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"TrafficSwarmAction\">\n  <xsl:if test=\"@semiMajorAxis\">\n    <xsl:attribute name=\"semiMajorAxis\">\n      <xsl:value-of select=\"@semiMajorAxis\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@semiMinorAxis\">\n    <xsl:attribute name=\"semiMinorAxis\">\n      <xsl:value-of select=\"@semiMinorAxis\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@innerRadius\">\n    <xsl:attribute name=\"innerRadius\">\n      <xsl:value-of select=\"@innerRadius\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@offset\">\n    <xsl:attribute name=\"offset\">\n      <xsl:value-of select=\"@offset\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@numberOfVehicles\">\n    <xsl:attribute name=\"numberOfVehicles\">\n      <xsl:value-of select=\"@numberOfVehicles\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;CentralObject&quot;\">\n      <CentralObject>\n        <xsl:call-template name=\"CentralSwarmObject\"/>\n      </CentralObject>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrafficDefinition&quot;\">\n      <TrafficDefinition>\n        <xsl:call-template name=\"TrafficDefinition\"/>\n      </TrafficDefinition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='CentralSwarmObject'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficJamAction'>\n    <xsl:if test='@direction'>\n      <xsl:attribute name='direction'>\n        <xsl:value-of select='@direction' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@speed'>\n      <xsl:attribute name='speed'>\n        <xsl:value-of select='@speed' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@length'>\n      <xsl:attribute name='length'>\n        <xsl:value-of select='@length' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n      <xsl:if test='name()=\"TrafficDefinition\"'>\n        <TrafficDefinition>\n          <xsl:call-template name='TrafficDefinition' />\n        </TrafficDefinition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Event\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@priority\">\n    <xsl:choose>\n      <xsl:when test=\"@priority =&quot;following&quot;\">\n        <xsl:attribute name=\"priority\">\n          <xsl:value-of select=\"&quot;&quot;\"/>\n        </xsl:attribute>\n        <xsl:message terminate=\"no\">\n          WARNING: Event.priority: 'following' is desupported: removed during migration. This results in unvalifd XML code.\n        </xsl:message>\n      </xsl:when>\n      <xsl:otherwise>\n        <xsl:attribute name=\"priority\">\n          <xsl:value-of select=\"@priority\"/>\n        </xsl:attribute>\n      </xsl:otherwise>\n    </xsl:choose>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Action&quot;\">\n      <xsl:if test=\"not(Global/Traffic/Jam) and not(UserDefined/Script) and not(Private/Meeting)\">\n        <Action>\n          <xsl:call-template name=\"Action\"/>\n        </Action>\n      </xsl:if>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;StartConditions&quot;\">\n      <StartTrigger>\n        <xsl:call-template name=\"Trigger\"/>\n      </StartTrigger>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"Action/Private/Meeting\">\n    <xsl:message terminate=\"no\">\n      WARNING: OSCPrivateAction.Meeting  is desupported: removed during migration: This may result in unvalid XML\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"Action/Global/Traffic/Jam\">\n    <xsl:message terminate=\"no\">\n      WARNING: Jam is desupported: removed during migration: This may result in unvalid XML\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"Action/UserDefined/Script\">\n    <xsl:message terminate=\"no\">\n      WARNING: Script is desupported: removed during migration: This may result in unvalid XML\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='Action'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Global\"'>\n        <GlobalAction>\n          <xsl:call-template name='GlobalAction' />\n        </GlobalAction>\n      </xsl:if>\n      <xsl:if test='name()=\"UserDefined\"'>\n        <UserDefinedAction>\n          <xsl:call-template name='UserDefinedAction' />\n        </UserDefinedAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Private\"'>\n        <PrivateAction>\n          <xsl:call-template name='PrivateAction' />\n        </PrivateAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='VehicleCategoryDistribution'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Vehicle\"'>\n        <VehicleCategoryDistributionEntry>\n          <xsl:call-template name='VehicleCategoryDistributionEntry' />\n        </VehicleCategoryDistributionEntry>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"VehicleCategoryDistributionEntry\">\n  <xsl:if test=\"@category\">\n    <xsl:attribute name=\"category\">\n      <xsl:choose>\n        <xsl:when test=\"@category='van' or @category='truck' or @category='trailer' or @category='semitrailer' or @category='bus' or @category='motorbike' or @category='bicycle' or @category='train' or @category='tram'\">\n          <xsl:value-of select=\"@category\"/>\n        </xsl:when>\n        <xsl:otherwise>\n          <xsl:value-of select=\"'car'\"/>\n        </xsl:otherwise>\n      </xsl:choose>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@percentage\">\n    <xsl:attribute name=\"weight\">\n      <xsl:value-of select=\"@percentage\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='ControllerDistribution'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Driver\"'>\n        <ControllerDistributionEntry>\n          <xsl:call-template name='ControllerDistributionEntry' />\n        </ControllerDistributionEntry>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"ControllerDistributionEntry\">\n  <xsl:if test=\"@percentage\">\n    <xsl:attribute name=\"weight\">\n      <xsl:value-of select=\"@percentage\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:comment>\n    Migration: Insert Controller here\n  </xsl:comment>\n  <Controller/>\n  <xsl:message terminate=\"no\">\n    ERROR: OSCTrafficDefinition.DriverDistribution.Driver cannot be migrated automatically and will result in unvalid XML output.\n  </xsl:message>\n</xsl:template>\n<xsl:template name=\"TimeOfDay\">\n  <xsl:if test=\"@animation\">\n    <xsl:attribute name=\"animation\">\n      <xsl:value-of select=\"@animation\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:variable name=\"hour\" select=\"Time/@hour\"/>\n  <xsl:variable name=\"min\" select=\"Time/@min\"/>\n  <xsl:variable name=\"sec\" select=\"Time/@sec\"/>\n  <xsl:variable name=\"day\" select=\"Date/@day\"/>\n  <xsl:variable name=\"month\" select=\"Date/@month\"/>\n  <xsl:variable name=\"year\" select=\"Date/@year\"/>\n  <xsl:attribute name=\"dateTime\">\n    <xsl:value-of select=\"format-number($year,'0000')\"/>\n    <xsl:value-of select=\"format-number($month,'-00')\"/>\n    <xsl:value-of select=\"format-number($day,'-00')\"/>\n    <xsl:value-of select=\"format-number($hour,'T00')\"/>\n    <xsl:value-of select=\"format-number($min,':00')\"/>\n    <xsl:value-of select=\"format-number($sec,':00')\"/>\n  </xsl:attribute>\n</xsl:template>\n\n  <xsl:template name='Weather'>\n    <xsl:if test='@cloudState'>\n      <xsl:attribute name='cloudState'>\n        <xsl:value-of select='@cloudState' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Sun\"'>\n        <Sun>\n          <xsl:call-template name='Sun' />\n        </Sun>\n      </xsl:if>\n      <xsl:if test='name()=\"Fog\"'>\n        <Fog>\n          <xsl:call-template name='Fog' />\n        </Fog>\n      </xsl:if>\n      <xsl:if test='name()=\"Precipitation\"'>\n        <Precipitation>\n          <xsl:call-template name='Precipitation' />\n        </Precipitation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Sun'>\n    <xsl:if test='@intensity'>\n      <xsl:attribute name='intensity'>\n        <xsl:value-of select='@intensity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@azimuth'>\n      <xsl:attribute name='azimuth'>\n        <xsl:value-of select='@azimuth' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@elevation'>\n      <xsl:attribute name='elevation'>\n        <xsl:value-of select='@elevation' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Fog'>\n    <xsl:if test='@visualRange'>\n      <xsl:attribute name='visualRange'>\n        <xsl:value-of select='@visualRange' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Precipitation'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='precipitationType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@intensity'>\n      <xsl:attribute name='intensity'>\n        <xsl:value-of select='@intensity' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"RoadCondition\">\n  <xsl:if test=\"@frictionScale\">\n    <xsl:attribute name=\"frictionScaleFactor\">\n      <xsl:value-of select=\"@frictionScale\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='SurfaceState'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@intensity'>\n      <xsl:attribute name='intensity'>\n        <xsl:value-of select='@intensity' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Waypoint'>\n    <xsl:if test='@strategy'>\n      <xsl:attribute name='routeStrategy'>\n        <xsl:value-of select='@strategy' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Vertex\">\n  <xsl:if test=\"@reference\">\n    <xsl:attribute name=\"time\">\n      <xsl:value-of select=\"@reference\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <Position>\n        <xsl:call-template name=\"Position\"/>\n      </Position>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:message terminate=\"no\">\n    WARNING: OSCTrajectory.Vertex: OSCTrajectory is restructured and connot be automatically migrated. Review XML.\n  </xsl:message>\n</xsl:template>\n\n  <xsl:template name='Shape'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Polyline\"'>\n        <Polyline>\n          <xsl:call-template name='Polyline' />\n        </Polyline>\n      </xsl:if>\n      <xsl:if test='name()=\"Clothoid\"'>\n        <Clothoid>\n          <xsl:call-template name='Clothoid' />\n        </Clothoid>\n      </xsl:if>\n      <xsl:if test='name()=\"Spline\"'>\n        <Spline>\n          <xsl:call-template name='Spline' />\n        </Spline>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Polyline' />\n  <xsl:template name='Clothoid'>\n    <xsl:if test='@curvature'>\n      <xsl:attribute name='curvature'>\n        <xsl:value-of select='@curvature' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@curvatureDot'>\n      <xsl:attribute name='curvatureDot'>\n        <xsl:value-of select='@curvatureDot' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@length'>\n      <xsl:attribute name='length'>\n        <xsl:value-of select='@length' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Spline'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ControlPoint1\"'>\n        <ControlPoint1>\n          <xsl:call-template name='ControlPoint1' />\n        </ControlPoint1>\n      </xsl:if>\n      <xsl:if test='name()=\"ControlPoint2\"'>\n        <ControlPoint2>\n          <xsl:call-template name='ControlPoint2' />\n        </ControlPoint2>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ControlPoint1'>\n    <xsl:if test='@status'>\n      <xsl:attribute name='status'>\n        <xsl:value-of select='@status' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ControlPoint2'>\n    <xsl:if test='@status'>\n      <xsl:attribute name='status'>\n        <xsl:value-of select='@status' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='WorldPosition'>\n    <xsl:if test='@x'>\n      <xsl:attribute name='x'>\n        <xsl:value-of select='@x' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@y'>\n      <xsl:attribute name='y'>\n        <xsl:value-of select='@y' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@z'>\n      <xsl:attribute name='z'>\n        <xsl:value-of select='@z' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@h'>\n      <xsl:attribute name='h'>\n        <xsl:value-of select='@h' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@p'>\n      <xsl:attribute name='p'>\n        <xsl:value-of select='@p' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@r'>\n      <xsl:attribute name='r'>\n        <xsl:value-of select='@r' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='RelativeWorldPosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dx'>\n      <xsl:attribute name='dx'>\n        <xsl:value-of select='@dx' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dy'>\n      <xsl:attribute name='dy'>\n        <xsl:value-of select='@dy' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dz'>\n      <xsl:attribute name='dz'>\n        <xsl:value-of select='@dz' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeObjectPosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dx'>\n      <xsl:attribute name='dx'>\n        <xsl:value-of select='@dx' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dy'>\n      <xsl:attribute name='dy'>\n        <xsl:value-of select='@dy' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dz'>\n      <xsl:attribute name='dz'>\n        <xsl:value-of select='@dz' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RoadPosition'>\n    <xsl:if test='@roadId'>\n      <xsl:attribute name='roadId'>\n        <xsl:value-of select='@roadId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@s'>\n      <xsl:attribute name='s'>\n        <xsl:value-of select='@s' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@t'>\n      <xsl:attribute name='t'>\n        <xsl:value-of select='@t' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeRoadPosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@ds'>\n      <xsl:attribute name='ds'>\n        <xsl:value-of select='@ds' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dt'>\n      <xsl:attribute name='dt'>\n        <xsl:value-of select='@dt' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='LanePosition'>\n    <xsl:if test='@roadId'>\n      <xsl:attribute name='roadId'>\n        <xsl:value-of select='@roadId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@laneId'>\n      <xsl:attribute name='laneId'>\n        <xsl:value-of select='@laneId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@offset'>\n      <xsl:attribute name='offset'>\n        <xsl:value-of select='@offset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@s'>\n      <xsl:attribute name='s'>\n        <xsl:value-of select='@s' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeLanePosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dLane'>\n      <xsl:attribute name='dLane'>\n        <xsl:value-of select='@dLane' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@ds'>\n      <xsl:attribute name='ds'>\n        <xsl:value-of select='@ds' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@offset'>\n      <xsl:attribute name='offset'>\n        <xsl:value-of select='@offset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RoutePosition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"RouteRef\"'>\n        <RouteRef>\n          <xsl:call-template name='RouteRef' />\n        </RouteRef>\n      </xsl:if>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n      <xsl:if test='name()=\"Position\"'>\n        <InRoutePosition>\n          <xsl:call-template name='InRoutePosition' />\n        </InRoutePosition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RouteRef'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Route\"'>\n        <Route>\n          <xsl:call-template name='Route' />\n        </Route>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='InRoutePosition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Current\"'>\n        <FromCurrentEntity>\n          <xsl:call-template name='PositionOfCurrentEntity' />\n        </FromCurrentEntity>\n      </xsl:if>\n      <xsl:if test='name()=\"RoadCoord\"'>\n        <FromRoadCoordinates>\n          <xsl:call-template name='PositionInRoadCoordinates' />\n        </FromRoadCoordinates>\n      </xsl:if>\n      <xsl:if test='name()=\"LaneCoord\"'>\n        <FromLaneCoordinates>\n          <xsl:call-template name='PositionInLaneCoordinates' />\n        </FromLaneCoordinates>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='PositionOfCurrentEntity'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='PositionInRoadCoordinates'>\n    <xsl:if test='@pathS'>\n      <xsl:attribute name='pathS'>\n        <xsl:value-of select='@pathS' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@t'>\n      <xsl:attribute name='t'>\n        <xsl:value-of select='@t' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='PositionInLaneCoordinates'>\n    <xsl:if test='@pathS'>\n      <xsl:attribute name='pathS'>\n        <xsl:value-of select='@pathS' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@laneId'>\n      <xsl:attribute name='laneId'>\n        <xsl:value-of select='@laneId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@laneOffset'>\n      <xsl:attribute name='laneOffset'>\n        <xsl:value-of select='@laneOffset' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Center'>\n    <xsl:if test='@x'>\n      <xsl:attribute name='x'>\n        <xsl:value-of select='@x' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@y'>\n      <xsl:attribute name='y'>\n        <xsl:value-of select='@y' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@z'>\n      <xsl:attribute name='z'>\n        <xsl:value-of select='@z' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Dimensions'>\n    <xsl:if test='@width'>\n      <xsl:attribute name='width'>\n        <xsl:value-of select='@width' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@length'>\n      <xsl:attribute name='length'>\n        <xsl:value-of select='@length' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@height'>\n      <xsl:attribute name='height'>\n        <xsl:value-of select='@height' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Property'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n</xsl:stylesheet>"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/openscenario/OpenSCENARIO.xsd",
    "content": "﻿<?xml version=\"1.0\" encoding=\"utf-8\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n<!--\nASAM OpenSCENARIO V1.0.0\n\n© by ASAM e.V., 2020\n\nDescription of dynamic content in driving simulations\n\n\nAny use is limited to the scope described in the ASAM license terms. \nThis file is distributable in accordance with the ASAM license terms. \nSee www.asam.net/license.html for further details.\n-->\n    <xsd:element name=\"OpenSCENARIO\" type=\"OpenScenario\"/>\n\t<xsd:simpleType name=\"parameter\">\n\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t<xsd:pattern value=\"[$][A-Za-z_][A-Za-z0-9_]*\"/>\n\t\t</xsd:restriction>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Boolean\">\n\t\t<xsd:union memberTypes=\"parameter xsd:boolean\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"DateTime\">\n\t\t<xsd:union memberTypes=\"parameter xsd:dateTime\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Double\">\n\t\t<xsd:union memberTypes=\"parameter xsd:double\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Int\">\n\t\t<xsd:union memberTypes=\"parameter xsd:int\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"String\">\n\t\t<xsd:union memberTypes=\"parameter xsd:string\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"UnsignedInt\">\n\t\t<xsd:union memberTypes=\"parameter xsd:unsignedInt\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"UnsignedShort\">\n\t\t<xsd:union memberTypes=\"parameter xsd:unsignedShort\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"CloudState\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"cloudy\"/>\n\t\t\t\t\t<xsd:enumeration value=\"free\"/>\n\t\t\t\t\t<xsd:enumeration value=\"overcast\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rainy\"/>\n\t\t\t\t\t<xsd:enumeration value=\"skyOff\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ConditionEdge\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"falling\"/>\n\t\t\t\t\t<xsd:enumeration value=\"none\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rising\"/>\n\t\t\t\t\t<xsd:enumeration value=\"risingOrFalling\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"DynamicsDimension\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"distance\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rate\"/>\n\t\t\t\t\t<xsd:enumeration value=\"time\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"DynamicsShape\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"cubic\"/>\n\t\t\t\t\t<xsd:enumeration value=\"linear\"/>\n\t\t\t\t\t<xsd:enumeration value=\"sinusoidal\"/>\n\t\t\t\t\t<xsd:enumeration value=\"step\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"FollowingMode\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"follow\"/>\n\t\t\t\t\t<xsd:enumeration value=\"position\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"MiscObjectCategory\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"barrier\"/>\n\t\t\t\t\t<xsd:enumeration value=\"building\"/>\n\t\t\t\t\t<xsd:enumeration value=\"crosswalk\"/>\n\t\t\t\t\t<xsd:enumeration value=\"gantry\"/>\n\t\t\t\t\t<xsd:enumeration value=\"none\"/>\n\t\t\t\t\t<xsd:enumeration value=\"obstacle\"/>\n\t\t\t\t\t<xsd:enumeration value=\"parkingSpace\"/>\n\t\t\t\t\t<xsd:enumeration value=\"patch\"/>\n\t\t\t\t\t<xsd:enumeration value=\"pole\"/>\n\t\t\t\t\t<xsd:enumeration value=\"railing\"/>\n\t\t\t\t\t<xsd:enumeration value=\"roadMark\"/>\n\t\t\t\t\t<xsd:enumeration value=\"soundBarrier\"/>\n\t\t\t\t\t<xsd:enumeration value=\"streetLamp\"/>\n\t\t\t\t\t<xsd:enumeration value=\"trafficIsland\"/>\n\t\t\t\t\t<xsd:enumeration value=\"tree\"/>\n\t\t\t\t\t<xsd:enumeration value=\"vegetation\"/>\n\t\t\t\t\t<xsd:enumeration value=\"wind\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ObjectType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"miscellaneous\"/>\n\t\t\t\t\t<xsd:enumeration value=\"pedestrian\"/>\n\t\t\t\t\t<xsd:enumeration value=\"vehicle\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ParameterType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"boolean\"/>\n\t\t\t\t\t<xsd:enumeration value=\"dateTime\"/>\n\t\t\t\t\t<xsd:enumeration value=\"double\"/>\n\t\t\t\t\t<xsd:enumeration value=\"integer\"/>\n\t\t\t\t\t<xsd:enumeration value=\"string\"/>\n\t\t\t\t\t<xsd:enumeration value=\"unsignedInt\"/>\n\t\t\t\t\t<xsd:enumeration value=\"unsignedShort\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"PedestrianCategory\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"animal\"/>\n\t\t\t\t\t<xsd:enumeration value=\"pedestrian\"/>\n\t\t\t\t\t<xsd:enumeration value=\"wheelchair\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"PrecipitationType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"dry\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rain\"/>\n\t\t\t\t\t<xsd:enumeration value=\"snow\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Priority\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"overwrite\"/>\n\t\t\t\t\t<xsd:enumeration value=\"parallel\"/>\n\t\t\t\t\t<xsd:enumeration value=\"skip\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ReferenceContext\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"absolute\"/>\n\t\t\t\t\t<xsd:enumeration value=\"relative\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"RelativeDistanceType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"cartesianDistance\"/>\n\t\t\t\t\t<xsd:enumeration value=\"lateral\"/>\n\t\t\t\t\t<xsd:enumeration value=\"longitudinal\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"RouteStrategy\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"fastest\"/>\n\t\t\t\t\t<xsd:enumeration value=\"leastIntersections\"/>\n\t\t\t\t\t<xsd:enumeration value=\"random\"/>\n\t\t\t\t\t<xsd:enumeration value=\"shortest\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Rule\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"equalTo\"/>\n\t\t\t\t\t<xsd:enumeration value=\"greaterThan\"/>\n\t\t\t\t\t<xsd:enumeration value=\"lessThan\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"SpeedTargetValueType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"delta\"/>\n\t\t\t\t\t<xsd:enumeration value=\"factor\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"StoryboardElementState\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"completeState\"/>\n\t\t\t\t\t<xsd:enumeration value=\"endTransition\"/>\n\t\t\t\t\t<xsd:enumeration value=\"runningState\"/>\n\t\t\t\t\t<xsd:enumeration value=\"skipTransition\"/>\n\t\t\t\t\t<xsd:enumeration value=\"standbyState\"/>\n\t\t\t\t\t<xsd:enumeration value=\"startTransition\"/>\n\t\t\t\t\t<xsd:enumeration value=\"stopTransition\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"StoryboardElementType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"act\"/>\n\t\t\t\t\t<xsd:enumeration value=\"action\"/>\n\t\t\t\t\t<xsd:enumeration value=\"event\"/>\n\t\t\t\t\t<xsd:enumeration value=\"maneuver\"/>\n\t\t\t\t\t<xsd:enumeration value=\"maneuverGroup\"/>\n\t\t\t\t\t<xsd:enumeration value=\"story\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"TriggeringEntitiesRule\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"all\"/>\n\t\t\t\t\t<xsd:enumeration value=\"any\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"VehicleCategory\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"bicycle\"/>\n\t\t\t\t\t<xsd:enumeration value=\"bus\"/>\n\t\t\t\t\t<xsd:enumeration value=\"car\"/>\n\t\t\t\t\t<xsd:enumeration value=\"motorbike\"/>\n\t\t\t\t\t<xsd:enumeration value=\"semitrailer\"/>\n\t\t\t\t\t<xsd:enumeration value=\"trailer\"/>\n\t\t\t\t\t<xsd:enumeration value=\"train\"/>\n\t\t\t\t\t<xsd:enumeration value=\"tram\"/>\n\t\t\t\t\t<xsd:enumeration value=\"truck\"/>\n\t\t\t\t\t<xsd:enumeration value=\"van\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:complexType name=\"AbsoluteSpeed\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AbsoluteTargetLane\">\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AbsoluteTargetLaneOffset\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AbsoluteTargetSpeed\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AccelerationCondition\">\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AcquirePositionAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Act\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ManeuverGroup\" type=\"ManeuverGroup\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"StartTrigger\" type=\"Trigger\"/>\n\t\t\t<xsd:element name=\"StopTrigger\" type=\"Trigger\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Action\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"GlobalAction\" type=\"GlobalAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"UserDefinedAction\" type=\"UserDefinedAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"PrivateAction\" type=\"PrivateAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ActivateControllerAction\">\n\t\t<xsd:attribute name=\"lateral\" type=\"Boolean\"/>\n\t\t<xsd:attribute name=\"longitudinal\" type=\"Boolean\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Actors\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"selectTriggeringEntities\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AddEntityAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AssignControllerAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AssignRouteAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Route\" type=\"Route\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Axle\">\n\t\t<xsd:attribute name=\"maxSteering\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"positionX\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"positionZ\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"trackWidth\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"wheelDiameter\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Axles\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"FrontAxle\" type=\"Axle\"/>\n\t\t\t<xsd:element name=\"RearAxle\" type=\"Axle\"/>\n\t\t\t<xsd:element name=\"AdditionalAxle\" type=\"Axle\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"BoundingBox\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Center\" type=\"Center\"/>\n\t\t\t<xsd:element name=\"Dimensions\" type=\"Dimensions\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByEntityCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TriggeringEntities\" type=\"TriggeringEntities\"/>\n\t\t\t<xsd:element name=\"EntityCondition\" type=\"EntityCondition\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByObjectType\">\n\t\t<xsd:attribute name=\"type\" type=\"ObjectType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByType\">\n\t\t<xsd:attribute name=\"objectType\" type=\"ObjectType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByValueCondition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"ParameterCondition\" type=\"ParameterCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeOfDayCondition\" type=\"TimeOfDayCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SimulationTimeCondition\" type=\"SimulationTimeCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"StoryboardElementStateCondition\" type=\"StoryboardElementStateCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"UserDefinedValueCondition\" type=\"UserDefinedValueCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignalCondition\" type=\"TrafficSignalCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignalControllerCondition\" type=\"TrafficSignalControllerCondition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Catalog\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Vehicle\" type=\"Vehicle\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Pedestrian\" type=\"Pedestrian\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"MiscObject\" type=\"MiscObject\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Environment\" type=\"Environment\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Maneuver\" type=\"Maneuver\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Trajectory\" type=\"Trajectory\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Route\" type=\"Route\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\"/>\n\t</xsd:complexType>\n\t<xsd:group name=\"CatalogDefinition\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Catalog\" type=\"Catalog\"/>\n\t\t</xsd:sequence>\n\t</xsd:group>\n\t<xsd:complexType name=\"CatalogLocations\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"VehicleCatalog\" type=\"VehicleCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ControllerCatalog\" type=\"ControllerCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"PedestrianCatalog\" type=\"PedestrianCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"MiscObjectCatalog\" type=\"MiscObjectCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"EnvironmentCatalog\" type=\"EnvironmentCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ManeuverCatalog\" type=\"ManeuverCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrajectoryCatalog\" type=\"TrajectoryCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RouteCatalog\" type=\"RouteCatalogLocation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CatalogReference\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterAssignments\" type=\"ParameterAssignments\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"catalogName\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"entryName\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Center\">\n\t\t<xsd:attribute name=\"x\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"y\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"z\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CentralSwarmObject\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Clothoid\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"curvature\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"curvatureDot\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"length\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"startTime\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"stopTime\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CollisionCondition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ByType\" type=\"ByObjectType\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Condition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"ByEntityCondition\" type=\"ByEntityCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ByValueCondition\" type=\"ByValueCondition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"conditionEdge\" type=\"ConditionEdge\" use=\"required\"/>\n\t\t<xsd:attribute name=\"delay\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ConditionGroup\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Condition\" type=\"Condition\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Controller\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"AssignControllerAction\" type=\"AssignControllerAction\"/>\n\t\t\t<xsd:element name=\"OverrideControllerValueAction\" type=\"OverrideControllerValueAction\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerDistribution\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ControllerDistributionEntry\" type=\"ControllerDistributionEntry\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerDistributionEntry\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"weight\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControlPoint\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"time\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"weight\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CustomCommandAction\">\n\t\t<xsd:simpleContent>\n\t\t\t<xsd:extension base=\"xsd:string\">\n\t\t\t\t<xsd:attribute name=\"type\" type=\"String\" use=\"required\"/>\n\t\t\t</xsd:extension>\n\t\t</xsd:simpleContent>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"DeleteEntityAction\"/>\n\t<xsd:complexType name=\"Dimensions\">\n\t\t<xsd:attribute name=\"height\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"length\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"width\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Directory\">\n\t\t<xsd:attribute name=\"path\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"DistanceCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"alongRoute\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"DynamicConstraints\">\n\t\t<xsd:attribute name=\"maxAcceleration\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"maxDeceleration\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"maxSpeed\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EndOfRoadCondition\">\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Entities\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ScenarioObject\" type=\"ScenarioObject\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"EntitySelection\" type=\"EntitySelection\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EntityAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AddEntityAction\" type=\"AddEntityAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"DeleteEntityAction\" type=\"DeleteEntityAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EntityCondition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EndOfRoadCondition\" type=\"EndOfRoadCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CollisionCondition\" type=\"CollisionCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"OffroadCondition\" type=\"OffroadCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeHeadwayCondition\" type=\"TimeHeadwayCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeToCollisionCondition\" type=\"TimeToCollisionCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AccelerationCondition\" type=\"AccelerationCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"StandStillCondition\" type=\"StandStillCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SpeedCondition\" type=\"SpeedCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeSpeedCondition\" type=\"RelativeSpeedCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TraveledDistanceCondition\" type=\"TraveledDistanceCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ReachPositionCondition\" type=\"ReachPositionCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"DistanceCondition\" type=\"DistanceCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeDistanceCondition\" type=\"RelativeDistanceCondition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:group name=\"EntityObject\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Vehicle\" type=\"Vehicle\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Pedestrian\" type=\"Pedestrian\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"MiscObject\" type=\"MiscObject\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:group>\n\t<xsd:complexType name=\"EntityRef\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EntitySelection\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Members\" type=\"SelectedEntities\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Environment\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeOfDay\" type=\"TimeOfDay\"/>\n\t\t\t<xsd:element name=\"Weather\" type=\"Weather\"/>\n\t\t\t<xsd:element name=\"RoadCondition\" type=\"RoadCondition\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EnvironmentAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Environment\" type=\"Environment\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EnvironmentCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Event\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Action\" type=\"Action\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"StartTrigger\" type=\"Trigger\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"maximumExecutionCount\" type=\"UnsignedInt\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"priority\" type=\"Priority\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"File\">\n\t\t<xsd:attribute name=\"filepath\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"FileHeader\">\n\t\t<xsd:attribute name=\"author\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"date\" type=\"DateTime\" use=\"required\"/>\n\t\t<xsd:attribute name=\"description\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"revMajor\" type=\"UnsignedShort\" use=\"required\"/>\n\t\t<xsd:attribute name=\"revMinor\" type=\"UnsignedShort\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"FinalSpeed\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AbsoluteSpeed\" type=\"AbsoluteSpeed\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeSpeedToMaster\" type=\"RelativeSpeedToMaster\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Fog\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"visualRange\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"FollowTrajectoryAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Trajectory\" type=\"Trajectory\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeReference\" type=\"TimeReference\"/>\n\t\t\t<xsd:element name=\"TrajectoryFollowingMode\" type=\"TrajectoryFollowingMode\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"GlobalAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EnvironmentAction\" type=\"EnvironmentAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"EntityAction\" type=\"EntityAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ParameterAction\" type=\"ParameterAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"InfrastructureAction\" type=\"InfrastructureAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficAction\" type=\"TrafficAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"InfrastructureAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TrafficSignalAction\" type=\"TrafficSignalAction\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Init\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Actions\" type=\"InitActions\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"InitActions\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"GlobalAction\" type=\"GlobalAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"UserDefinedAction\" type=\"UserDefinedAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Private\" type=\"Private\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"InRoutePosition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"FromCurrentEntity\" type=\"PositionOfCurrentEntity\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"FromRoadCoordinates\" type=\"PositionInRoadCoordinates\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"FromLaneCoordinates\" type=\"PositionInLaneCoordinates\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Knot\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneChangeAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"LaneChangeActionDynamics\" type=\"TransitionDynamics\"/>\n\t\t\t<xsd:element name=\"LaneChangeTarget\" type=\"LaneChangeTarget\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"targetLaneOffset\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneChangeTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"RelativeTargetLane\" type=\"RelativeTargetLane\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AbsoluteTargetLane\" type=\"AbsoluteTargetLane\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneOffsetAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"LaneOffsetActionDynamics\" type=\"LaneOffsetActionDynamics\"/>\n\t\t\t<xsd:element name=\"LaneOffsetTarget\" type=\"LaneOffsetTarget\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneOffsetActionDynamics\">\n\t\t<xsd:attribute name=\"dynamicsShape\" type=\"DynamicsShape\" use=\"required\"/>\n\t\t<xsd:attribute name=\"maxLateralAcc\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneOffsetTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"RelativeTargetLaneOffset\" type=\"RelativeTargetLaneOffset\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AbsoluteTargetLaneOffset\" type=\"AbsoluteTargetLaneOffset\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LanePosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"laneId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"roadId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"s\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LateralAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"LaneChangeAction\" type=\"LaneChangeAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LaneOffsetAction\" type=\"LaneOffsetAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LateralDistanceAction\" type=\"LateralDistanceAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LateralDistanceAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"DynamicConstraints\" type=\"DynamicConstraints\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"distance\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LongitudinalAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"SpeedAction\" type=\"SpeedAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LongitudinalDistanceAction\" type=\"LongitudinalDistanceAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LongitudinalDistanceAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"DynamicConstraints\" type=\"DynamicConstraints\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"distance\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"timeGap\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Maneuver\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Event\" type=\"Event\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ManeuverCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ManeuverGroup\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Actors\" type=\"Actors\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Maneuver\" type=\"Maneuver\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"maximumExecutionCount\" type=\"UnsignedInt\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"MiscObject\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"mass\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"miscObjectCategory\" type=\"MiscObjectCategory\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"MiscObjectCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ModifyRule\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AddValue\" type=\"ParameterAddValueRule\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"MultiplyByValue\" type=\"ParameterMultiplyByValueRule\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"None\"/>\n\t<xsd:complexType name=\"Nurbs\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ControlPoint\" type=\"ControlPoint\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Knot\" type=\"Knot\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"order\" type=\"UnsignedInt\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ObjectController\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OffroadCondition\">\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OpenScenario\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"FileHeader\" type=\"FileHeader\"/>\n\t\t\t<xsd:group ref=\"OpenScenarioCategory\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:element name=\"OpenScenario\" type=\"OpenScenario\"/>\n\t<xsd:group name=\"OpenScenarioCategory\">\n\t\t<xsd:choice>\n\t\t\t<xsd:group ref=\"ScenarioDefinition\"/>\n\t\t\t<xsd:group ref=\"CatalogDefinition\"/>\n\t\t</xsd:choice>\n\t</xsd:group>\n\t<xsd:complexType name=\"Orientation\">\n\t\t<xsd:attribute name=\"h\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"p\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"r\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"type\" type=\"ReferenceContext\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideBrakeAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideClutchAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideControllerValueAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Throttle\" type=\"OverrideThrottleAction\"/>\n\t\t\t<xsd:element name=\"Brake\" type=\"OverrideBrakeAction\"/>\n\t\t\t<xsd:element name=\"Clutch\" type=\"OverrideClutchAction\"/>\n\t\t\t<xsd:element name=\"ParkingBrake\" type=\"OverrideParkingBrakeAction\"/>\n\t\t\t<xsd:element name=\"SteeringWheel\" type=\"OverrideSteeringWheelAction\"/>\n\t\t\t<xsd:element name=\"Gear\" type=\"OverrideGearAction\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideGearAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"number\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideParkingBrakeAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideSteeringWheelAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideThrottleAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"SetAction\" type=\"ParameterSetAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ModifyAction\" type=\"ParameterModifyAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"parameterRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAddValueRule\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAssignment\">\n\t\t<xsd:attribute name=\"parameterRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAssignments\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterAssignment\" type=\"ParameterAssignment\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterCondition\">\n\t\t<xsd:attribute name=\"parameterRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterDeclaration\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"parameterType\" type=\"ParameterType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterDeclarations\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclaration\" type=\"ParameterDeclaration\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterModifyAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Rule\" type=\"ModifyRule\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterMultiplyByValueRule\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterSetAction\">\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Pedestrian\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"mass\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"model\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"pedestrianCategory\" type=\"PedestrianCategory\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PedestrianCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Performance\">\n\t\t<xsd:attribute name=\"maxAcceleration\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"maxDeceleration\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"maxSpeed\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Phase\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"TrafficSignalState\" type=\"TrafficSignalState\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Polyline\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Vertex\" type=\"Vertex\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Position\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"WorldPosition\" type=\"WorldPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeWorldPosition\" type=\"RelativeWorldPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeObjectPosition\" type=\"RelativeObjectPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RoadPosition\" type=\"RoadPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeRoadPosition\" type=\"RelativeRoadPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LanePosition\" type=\"LanePosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeLanePosition\" type=\"RelativeLanePosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RoutePosition\" type=\"RoutePosition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PositionInLaneCoordinates\">\n\t\t<xsd:attribute name=\"laneId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"laneOffset\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"pathS\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PositionInRoadCoordinates\">\n\t\t<xsd:attribute name=\"pathS\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"t\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PositionOfCurrentEntity\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Precipitation\">\n\t\t<xsd:attribute name=\"intensity\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"precipitationType\" type=\"PrecipitationType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Private\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"PrivateAction\" type=\"PrivateAction\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PrivateAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"LongitudinalAction\" type=\"LongitudinalAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LateralAction\" type=\"LateralAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"VisibilityAction\" type=\"VisibilityAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SynchronizeAction\" type=\"SynchronizeAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ActivateControllerAction\" type=\"ActivateControllerAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ControllerAction\" type=\"ControllerAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TeleportAction\" type=\"TeleportAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RoutingAction\" type=\"RoutingAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Properties\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Property\" type=\"Property\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"File\" type=\"File\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Property\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ReachPositionCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"tolerance\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeDistanceCondition\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"relativeDistanceType\" type=\"RelativeDistanceType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeLanePosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dLane\" type=\"Int\" use=\"required\"/>\n\t\t<xsd:attribute name=\"ds\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeObjectPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dx\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dy\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dz\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeRoadPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"ds\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dt\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeSpeedCondition\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeSpeedToMaster\">\n\t\t<xsd:attribute name=\"speedTargetValueType\" type=\"SpeedTargetValueType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeTargetLane\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Int\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeTargetLaneOffset\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeTargetSpeed\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"speedTargetValueType\" type=\"SpeedTargetValueType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeWorldPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dx\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dy\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dz\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoadCondition\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"frictionScaleFactor\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoadNetwork\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"LogicFile\" type=\"File\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SceneGraphFile\" type=\"File\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignals\" type=\"TrafficSignals\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoadPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"roadId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"s\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"t\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Route\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Waypoint\" type=\"Waypoint\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"closed\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RouteCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoutePosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"RouteRef\" type=\"RouteRef\"/>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"InRoutePosition\" type=\"InRoutePosition\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RouteRef\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Route\" type=\"Route\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoutingAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AssignRouteAction\" type=\"AssignRouteAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"FollowTrajectoryAction\" type=\"FollowTrajectoryAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AcquirePositionAction\" type=\"AcquirePositionAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:group name=\"ScenarioDefinition\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogLocations\" type=\"CatalogLocations\"/>\n\t\t\t<xsd:element name=\"RoadNetwork\" type=\"RoadNetwork\"/>\n\t\t\t<xsd:element name=\"Entities\" type=\"Entities\"/>\n\t\t\t<xsd:element name=\"Storyboard\" type=\"Storyboard\"/>\n\t\t</xsd:sequence>\n\t</xsd:group>\n\t<xsd:complexType name=\"ScenarioObject\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:group ref=\"EntityObject\"/>\n\t\t\t<xsd:element name=\"ObjectController\" type=\"ObjectController\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SelectedEntities\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"ByType\" type=\"ByType\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Shape\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Polyline\" type=\"Polyline\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Clothoid\" type=\"Clothoid\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Nurbs\" type=\"Nurbs\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SimulationTimeCondition\">\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SpeedAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"SpeedActionDynamics\" type=\"TransitionDynamics\"/>\n\t\t\t<xsd:element name=\"SpeedActionTarget\" type=\"SpeedActionTarget\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SpeedActionTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"RelativeTargetSpeed\" type=\"RelativeTargetSpeed\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AbsoluteTargetSpeed\" type=\"AbsoluteTargetSpeed\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SpeedCondition\">\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"StandStillCondition\">\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Story\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Act\" type=\"Act\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Storyboard\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Init\" type=\"Init\"/>\n\t\t\t<xsd:element name=\"Story\" type=\"Story\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"StopTrigger\" type=\"Trigger\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"StoryboardElementStateCondition\">\n\t\t<xsd:attribute name=\"storyboardElementRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"state\" type=\"StoryboardElementState\" use=\"required\"/>\n\t\t<xsd:attribute name=\"storyboardElementType\" type=\"StoryboardElementType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Sun\">\n\t\t<xsd:attribute name=\"azimuth\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"elevation\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"intensity\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SynchronizeAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TargetPositionMaster\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"TargetPosition\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"FinalSpeed\" type=\"FinalSpeed\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"masterEntityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TeleportAction\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeHeadwayCondition\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"alongRoute\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeOfDay\">\n\t\t<xsd:attribute name=\"animation\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dateTime\" type=\"DateTime\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeOfDayCondition\">\n\t\t<xsd:attribute name=\"dateTime\" type=\"DateTime\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeReference\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"None\" type=\"None\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Timing\" type=\"Timing\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeToCollisionCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TimeToCollisionConditionTarget\" type=\"TimeToCollisionConditionTarget\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"alongRoute\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeToCollisionConditionTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Timing\">\n\t\t<xsd:attribute name=\"domainAbsoluteRelative\" type=\"ReferenceContext\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"scale\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"TrafficSourceAction\" type=\"TrafficSourceAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSinkAction\" type=\"TrafficSinkAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSwarmAction\" type=\"TrafficSwarmAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficDefinition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"VehicleCategoryDistribution\" type=\"VehicleCategoryDistribution\"/>\n\t\t\t<xsd:element name=\"ControllerDistribution\" type=\"ControllerDistribution\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"TrafficSignalControllerAction\" type=\"TrafficSignalControllerAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignalStateAction\" type=\"TrafficSignalStateAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalCondition\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"state\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalController\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Phase\" type=\"Phase\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"delay\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"reference\" type=\"String\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignals\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"TrafficSignalController\" type=\"TrafficSignalController\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalControllerAction\">\n\t\t<xsd:attribute name=\"trafficSignalControllerRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"phase\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalControllerCondition\">\n\t\t<xsd:attribute name=\"trafficSignalControllerRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"phase\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalState\">\n\t\t<xsd:attribute name=\"state\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"trafficSignalId\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalStateAction\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"state\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSinkAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"TrafficDefinition\" type=\"TrafficDefinition\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"radius\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rate\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSourceAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"TrafficDefinition\" type=\"TrafficDefinition\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"radius\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rate\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"velocity\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSwarmAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"CentralObject\" type=\"CentralSwarmObject\"/>\n\t\t\t<xsd:element name=\"TrafficDefinition\" type=\"TrafficDefinition\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"innerRadius\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"numberOfVehicles\" type=\"UnsignedInt\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"semiMajorAxis\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"semiMinorAxis\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"velocity\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Trajectory\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Shape\" type=\"Shape\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"closed\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrajectoryCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrajectoryFollowingMode\">\n\t\t<xsd:attribute name=\"followingMode\" type=\"FollowingMode\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TransitionDynamics\">\n\t\t<xsd:attribute name=\"dynamicsDimension\" type=\"DynamicsDimension\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dynamicsShape\" type=\"DynamicsShape\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TraveledDistanceCondition\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Trigger\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ConditionGroup\" type=\"ConditionGroup\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TriggeringEntities\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"triggeringEntitiesRule\" type=\"TriggeringEntitiesRule\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"UserDefinedAction\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"CustomCommandAction\" type=\"CustomCommandAction\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"UserDefinedValueCondition\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Vehicle\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\"/>\n\t\t\t<xsd:element name=\"Performance\" type=\"Performance\"/>\n\t\t\t<xsd:element name=\"Axles\" type=\"Axles\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"vehicleCategory\" type=\"VehicleCategory\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VehicleCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VehicleCategoryDistribution\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"VehicleCategoryDistributionEntry\" type=\"VehicleCategoryDistributionEntry\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VehicleCategoryDistributionEntry\">\n\t\t<xsd:attribute name=\"category\" type=\"VehicleCategory\" use=\"required\"/>\n\t\t<xsd:attribute name=\"weight\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Vertex\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"time\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VisibilityAction\">\n\t\t<xsd:attribute name=\"graphics\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"sensors\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"traffic\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Waypoint\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"routeStrategy\" type=\"RouteStrategy\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Weather\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Sun\" type=\"Sun\"/>\n\t\t\t<xsd:element name=\"Fog\" type=\"Fog\"/>\n\t\t\t<xsd:element name=\"Precipitation\" type=\"Precipitation\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"cloudState\" type=\"CloudState\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"WorldPosition\">\n\t\t<xsd:attribute name=\"h\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"p\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"r\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"x\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"y\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"z\" type=\"Double\"/>\n\t</xsd:complexType>\n</xsd:schema>\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarioconfigs/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarioconfigs/openscenario_configuration.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the key configuration parameters for a scenario based on OpenSCENARIO\n\"\"\"\n\nimport logging\nimport os\nimport xml.etree.ElementTree as ET\n\nimport xmlschema\n\nimport carla\n\n# pylint: disable=line-too-long\nfrom srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData, ScenarioConfiguration\n# pylint: enable=line-too-long\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider  # workaround\nfrom srunner.tools.openscenario_parser import OpenScenarioParser, ParameterRef\n\n\nclass OpenScenarioConfiguration(ScenarioConfiguration):\n\n    \"\"\"\n    Limitations:\n    - Only one Story + Init is supported per Storyboard\n    \"\"\"\n\n    def __init__(self, filename, client, custom_params):\n\n        super(OpenScenarioConfiguration, self).__init__()\n\n        self.xml_tree = ET.parse(filename)\n        self.filename = filename\n        self._custom_params = custom_params if custom_params is not None else {}\n\n        self._validate_openscenario_configuration()\n        self.client = client\n\n        self.catalogs = {}\n\n        self.other_actors = []\n        self.ego_vehicles = []\n        self.trigger_points = []\n        self.weather = carla.WeatherParameters()\n\n        self.storyboard = self.xml_tree.find(\"Storyboard\")\n        self.stories = self.storyboard.findall(\"Story\")\n        self.init = self.storyboard.find(\"Init\")\n\n        logging.basicConfig()\n        self.logger = logging.getLogger(\"[SR:OpenScenarioConfiguration]\")\n\n        self._global_parameters = {}\n\n        self._set_parameters()\n        self._parse_openscenario_configuration()\n\n    def _validate_openscenario_configuration(self):\n        \"\"\"\n        Validate the given OpenSCENARIO config against the 1.0 XSD\n\n        Note: This will throw if the config is not valid. But this is fine here.\n        \"\"\"\n        xsd_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), \"../openscenario/OpenSCENARIO.xsd\")\n        xsd = xmlschema.XMLSchema(xsd_file)\n        xsd.validate(self.xml_tree)\n\n    def _validate_openscenario_catalog_configuration(self, catalog_xml_tree):\n        \"\"\"\n        Validate the given OpenSCENARIO catalog config against the 1.0 XSD\n\n        Note: This will throw if the catalog config is not valid. But this is fine here.\n        \"\"\"\n        xsd_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), \"../openscenario/OpenSCENARIO.xsd\")\n        xsd = xmlschema.XMLSchema(xsd_file)\n        xsd.validate(catalog_xml_tree)\n\n    def _parse_openscenario_configuration(self):\n        \"\"\"\n        Parse the given OpenSCENARIO config file, set and validate parameters\n        \"\"\"\n        OpenScenarioParser.set_osc_filepath(os.path.dirname(self.filename))\n\n        self._check_version()\n        self._load_catalogs()\n        self._set_scenario_name()\n        self._set_carla_town()\n        self._set_actor_information()\n\n        self._validate_result()\n\n    def _check_version(self):\n        \"\"\"\n        Ensure correct OpenSCENARIO version is used\n        \"\"\"\n        header = self.xml_tree.find(\"FileHeader\")\n        if not (header.attrib.get('revMajor') == \"1\" and header.attrib.get('revMinor') == \"0\"):\n            raise AttributeError(\"Only OpenSCENARIO 1.0 is supported\")\n\n    def _load_catalogs(self):\n        \"\"\"\n        Read Catalog xml files into dictionary for later use\n\n        NOTE: Catalogs must have distinct names, even across different types\n        \"\"\"\n        catalogs = self.xml_tree.find(\"CatalogLocations\")\n        if list(catalogs) is None:\n            return\n\n        catalog_types = [\"Vehicle\",\n                         \"Controller\",\n                         \"Pedestrian\",\n                         \"MiscObject\",\n                         \"Environment\",\n                         \"Maneuver\",\n                         \"Trajectory\",\n                         \"Route\"]\n        for catalog_type in catalog_types:\n            catalog = catalogs.find(catalog_type + \"Catalog\")\n            if catalog is None:\n                continue\n\n            catalog_path = catalog.find(\"Directory\").attrib.get('path') + \"/\" + catalog_type + \"Catalog.xosc\"\n            if not os.path.isabs(catalog_path) and \"xosc\" in self.filename:\n                catalog_path = os.path.dirname(os.path.abspath(self.filename)) + \"/\" + catalog_path\n\n            if not os.path.isfile(catalog_path):\n                self.logger.warning(\" The %s path for the %s Catalog is invalid\", catalog_path, catalog_type)\n            else:\n                xml_tree = ET.parse(catalog_path)\n                self._validate_openscenario_catalog_configuration(xml_tree)\n                catalog = xml_tree.find(\"Catalog\")\n                catalog_name = catalog.attrib.get(\"name\")\n                self.catalogs[catalog_name] = {}\n                for entry in catalog:\n                    self.catalogs[catalog_name][entry.attrib.get(\"name\")] = entry\n\n    def _set_scenario_name(self):\n        \"\"\"\n        Extract the scenario name from the OpenSCENARIO header information\n        \"\"\"\n        header = self.xml_tree.find(\"FileHeader\")\n        self.name = header.attrib.get('description', 'Unknown')\n\n        if self.name.startswith(\"CARLA:\"):\n            self.name = self.name[6:]\n            OpenScenarioParser.set_use_carla_coordinate_system()\n\n    def _set_carla_town(self):\n        \"\"\"\n        Extract the CARLA town (level) from the RoadNetwork information from OpenSCENARIO\n\n        Note: The specification allows multiple Logics elements within the RoadNetwork element.\n              Hence, there can be multiple towns specified. We just use the _last_ one.\n        \"\"\"\n        for logic in self.xml_tree.find(\"RoadNetwork\").findall(\"LogicFile\"):\n            self.town = logic.attrib.get('filepath', None)\n\n        if self.town is not None and \".xodr\" in self.town:\n            if not os.path.isabs(self.town):\n                self.town = os.path.dirname(os.path.abspath(self.filename)) + \"/\" + self.town\n            if not os.path.exists(self.town):\n                raise AttributeError(\"The provided RoadNetwork '{}' does not exist\".format(self.town))\n\n        # workaround for relative positions during init\n        world = self.client.get_world()\n        wmap = None\n        if world:\n            world.get_settings()\n            wmap = world.get_map()\n\n        if world is None or (wmap is not None and wmap.name.split('/')[-1] != self.town):\n            if \".xodr\" in self.town:\n                with open(self.town, 'r', encoding='utf-8') as od_file:\n                    data = od_file.read()\n                index = data.find('<OpenDRIVE>')\n                data = data[index:]\n\n                old_map = \"\"\n                if wmap is not None:\n                    old_map = wmap.to_opendrive()\n                    index = old_map.find('<OpenDRIVE>')\n                    old_map = old_map[index:]\n\n                if data != old_map:\n                    self.logger.warning(\" Wrong OpenDRIVE map in use. Forcing reload of CARLA world\")\n\n                    vertex_distance = 2.0  # in meters\n                    wall_height = 1.0      # in meters\n                    extra_width = 0.6      # in meters\n                    world = self.client.generate_opendrive_world(str(data),\n                                                                 carla.OpendriveGenerationParameters(\n                                                                 vertex_distance=vertex_distance,\n                                                                 wall_height=wall_height,\n                                                                 additional_width=extra_width,\n                                                                 smooth_junctions=True,\n                                                                 enable_mesh_visibility=True))\n            else:\n                self.logger.warning(\" Wrong map in use. Forcing reload of CARLA world\")\n                self.client.load_world(self.town)\n                world = self.client.get_world()\n\n            CarlaDataProvider.set_world(world)\n            if CarlaDataProvider.is_sync_mode():\n                world.tick()\n            else:\n                world.wait_for_tick()\n        else:\n            CarlaDataProvider.set_world(world)\n\n    def _set_parameters(self):\n        \"\"\"\n        Parse the complete scenario definition file, and replace all parameter references\n        with the actual values\n\n        Set _global_parameters.\n        \"\"\"\n        self.xml_tree, self._global_parameters = OpenScenarioParser.set_parameters(self.xml_tree, self._custom_params)\n\n        for elem in self.xml_tree.iter():\n            if elem.find('ParameterDeclarations') is not None:\n                elem, _ = OpenScenarioParser.set_parameters(elem)\n\n        OpenScenarioParser.set_global_parameters(self._global_parameters)\n\n    def _set_actor_information(self):\n        \"\"\"\n        Extract all actors and their corresponding specification\n\n        NOTE: The rolename property has to be unique!\n        \"\"\"\n        for entity in self.xml_tree.iter(\"Entities\"):\n            for obj in entity.iter(\"ScenarioObject\"):\n                rolename = obj.attrib.get('name', 'simulation')\n                args = {}\n                for prop in obj.iter(\"Property\"):\n                    key = prop.get('name')\n                    value = prop.get('value')\n                    args[key] = value\n\n                for catalog_reference in obj.iter(\"CatalogReference\"):\n                    entry = OpenScenarioParser.get_catalog_entry(self.catalogs, catalog_reference)\n                    if entry.tag == \"Vehicle\":\n                        self._extract_vehicle_information(entry, rolename, entry, args)\n                    elif entry.tag == \"Pedestrian\":\n                        self._extract_pedestrian_information(entry, rolename, entry, args)\n                    elif entry.tag == \"MiscObject\":\n                        self._extract_misc_information(entry, rolename, entry, args)\n                    else:\n                        self.logger.debug(\n                            \" A CatalogReference specifies a reference that is not an Entity. Skipping...\")\n\n                for vehicle in obj.iter(\"Vehicle\"):\n                    self._extract_vehicle_information(obj, rolename, vehicle, args)\n\n                for pedestrian in obj.iter(\"Pedestrian\"):\n                    self._extract_pedestrian_information(obj, rolename, pedestrian, args)\n\n                for misc in obj.iter(\"MiscObject\"):\n                    self._extract_misc_information(obj, rolename, misc, args)\n\n        # Set transform for all actors\n        # This has to be done in a multi-stage loop to resolve relative position settings\n        all_actor_transforms_set = False\n        while not all_actor_transforms_set:\n            all_actor_transforms_set = True\n            for actor in self.other_actors + self.ego_vehicles:\n                if actor.transform is None:\n                    try:\n                        actor.transform = self._get_actor_transform(actor.rolename)\n                    except AttributeError as e:\n                        if \"Object '\" in str(e):\n                            ref_actor_rolename = str(e).split('\\'')[1]\n                            for ref_actor in self.other_actors + self.ego_vehicles:\n                                if ref_actor.rolename == ref_actor_rolename:\n                                    if ref_actor.transform is not None:\n                                        raise e\n                                    break\n                        else:\n                            raise e\n                    if actor.transform is None:\n                        all_actor_transforms_set = False\n\n    def _extract_vehicle_information(self, obj, rolename, vehicle, args):\n        \"\"\"\n        Helper function to _set_actor_information for getting vehicle information from XML tree\n        \"\"\"\n        color = None\n        model = vehicle.attrib.get('name', \"vehicle.*\")\n        category = vehicle.attrib.get('vehicleCategory', \"car\")\n        ego_vehicle = False\n        for prop in obj.iter(\"Property\"):\n            if prop.get('name', '') == 'type':\n                ego_vehicle = prop.get('value') == 'ego_vehicle'\n            if prop.get('name', '') == 'color':\n                color = prop.get('value')\n\n        speed = self._get_actor_speed(rolename)\n        new_actor = ActorConfigurationData(\n            model, None, rolename, speed, color=color, category=category, args=args)\n\n        if ego_vehicle:\n            self.ego_vehicles.append(new_actor)\n        else:\n            self.other_actors.append(new_actor)\n\n    def _extract_pedestrian_information(self, obj, rolename, pedestrian, args):\n        \"\"\"\n        Helper function to _set_actor_information for getting pedestrian information from XML tree\n        \"\"\"\n        model = pedestrian.attrib.get('model', \"walker.*\")\n\n        speed = self._get_actor_speed(rolename)\n        new_actor = ActorConfigurationData(model, None, rolename, speed, category=\"pedestrian\", args=args)\n\n        self.other_actors.append(new_actor)\n\n    def _extract_misc_information(self, obj, rolename, misc, args):\n        \"\"\"\n        Helper function to _set_actor_information for getting vehicle information from XML tree\n        \"\"\"\n        category = misc.attrib.get('miscObjectCategory')\n        if category == \"barrier\":\n            model = \"static.prop.streetbarrier\"\n        elif category == \"guardRail\":\n            model = \"static.prop.chainbarrier\"\n        else:\n            model = misc.attrib.get('name')\n        new_actor = ActorConfigurationData(model, None, rolename, category=\"misc\", args=args)\n\n        self.other_actors.append(new_actor)\n\n    def _get_actor_transform(self, actor_name):\n        \"\"\"\n        Get the initial actor transform provided by the Init section\n\n        Note: - The OpenScenario specification allows multiple definitions. We use the _first_ one\n              - The OpenScenario specification allows different ways of specifying a position.\n                We currently support the specification with absolute world coordinates and the relative positions\n                RelativeWorld, RelativeObject and RelativeLane\n              - When using relative positions the relevant reference point (e.g. transform of another actor)\n                should be defined before!\n        \"\"\"\n\n        actor_transform = carla.Transform()\n\n        actor_found = False\n\n        for private_action in self.init.iter(\"Private\"):\n            if private_action.attrib.get('entityRef', None) == actor_name:\n                if actor_found:\n                    # pylint: disable=line-too-long\n                    self.logger.warning(\n                        \" Warning: The actor '%s' was already assigned an initial position. Overwriting pose!\", actor_name)\n                    # pylint: enable=line-too-long\n                actor_found = True\n                for position in private_action.iter('Position'):\n                    transform = OpenScenarioParser.convert_position_to_transform(\n                        position, actor_list=self.other_actors + self.ego_vehicles)\n                    if transform:\n                        actor_transform = transform\n\n        if not actor_found:\n            # pylint: disable=line-too-long\n            self.logger.warning(\n                \" Warning: The actor '%s' was not assigned an initial position. Using (0,0,0)\", actor_name)\n            # pylint: enable=line-too-long\n\n        return actor_transform\n\n    def _get_actor_speed(self, actor_name):\n        \"\"\"\n        Get the initial actor speed provided by the Init section\n        \"\"\"\n        actor_speed = 0\n        actor_found = False\n\n        for private_action in self.init.iter(\"Private\"):\n            if private_action.attrib.get('entityRef', None) == actor_name:\n                if actor_found:\n                    # pylint: disable=line-too-long\n                    self.logger.warning(\n                        \" Warning: The actor '%s' was already assigned an initial speed. Overwriting inital speed!\", actor_name)\n                    # pylint: enable=line-too-long\n                actor_found = True\n\n                for longitudinal_action in private_action.iter('LongitudinalAction'):\n                    for speed in longitudinal_action.iter('SpeedAction'):\n                        for target in speed.iter('SpeedActionTarget'):\n                            for absolute in target.iter('AbsoluteTargetSpeed'):\n                                speed = float(ParameterRef(absolute.attrib.get('value', 0)))\n                                if speed >= 0:\n                                    actor_speed = speed\n                                else:\n                                    raise AttributeError(\n                                        \"Warning: Speed value of actor {} must be positive. Speed set to 0.\".format(actor_name))  # pylint: disable=line-too-long\n        return actor_speed\n\n    def _validate_result(self):\n        \"\"\"\n        Check that the current scenario configuration is valid\n        \"\"\"\n        if not self.name:\n            raise AttributeError(\"No scenario name found\")\n\n        if not self.town:\n            raise AttributeError(\"CARLA level not defined\")\n\n        if not self.ego_vehicles:\n            self.logger.warning(\" No ego vehicles defined in scenario\")\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarioconfigs/route_scenario_configuration.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the key configuration parameters for a route-based scenario\n\"\"\"\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration\n\n\nclass RouteConfiguration(object):\n\n    \"\"\"\n    This class provides the basic  configuration for a route\n    \"\"\"\n\n    def __init__(self, route=None):\n        self.data = route\n\n    def parse_xml(self, node):\n        \"\"\"\n        Parse route config XML\n        \"\"\"\n        self.data = []\n\n        for waypoint in node.iter(\"waypoint\"):\n            x = float(waypoint.attrib.get('x', 0))\n            y = float(waypoint.attrib.get('y', 0))\n            z = float(waypoint.attrib.get('z', 0))\n            c = waypoint.attrib.get('connection', '')\n            connection = RoadOption[c.split('.')[1]]\n\n            self.data.append((carla.Location(x, y, z), connection))\n\n\nclass RouteScenarioConfiguration(ScenarioConfiguration):\n\n    \"\"\"\n    Basic configuration of a RouteScenario\n    \"\"\"\n\n    def __init__(self):\n        super(RouteScenarioConfiguration, self).__init__()\n        self.keypoints = None\n        self.scenario_configs = []\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarioconfigs/scenario_configuration.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the key configuration parameters for an XML-based scenario\n\"\"\"\n\nimport carla\n\n\nclass ActorConfigurationData(object):\n\n    \"\"\"\n    This is a configuration base class to hold model and transform attributes\n    \"\"\"\n\n    def __init__(self, model, transform, rolename='other', speed=0, autopilot=False,\n                 random=False, color=None, category=\"car\", args=None):\n        self.model = model\n        self.rolename = rolename\n        self.transform = transform\n        self.speed = speed\n        self.autopilot = autopilot\n        self.random_location = random\n        self.color = color\n        self.category = category\n        self.args = args\n\n    @staticmethod\n    def parse_from_node(node, rolename):\n        \"\"\"\n        static method to initialize an ActorConfigurationData from a given ET tree\n        \"\"\"\n\n        model = node.attrib.get('model', 'vehicle.*')\n\n        pos_x = float(node.attrib.get('x', 0))\n        pos_y = float(node.attrib.get('y', 0))\n        pos_z = float(node.attrib.get('z', 0))\n        yaw = float(node.attrib.get('yaw', 0))\n\n        transform = carla.Transform(carla.Location(x=pos_x, y=pos_y, z=pos_z), carla.Rotation(yaw=yaw))\n\n        rolename = node.attrib.get('rolename', rolename)\n\n        speed = node.attrib.get('speed', 0)\n\n        autopilot = False\n        if 'autopilot' in node.keys():\n            autopilot = True\n\n        random_location = False\n        if 'random_location' in node.keys():\n            random_location = True\n\n        color = node.attrib.get('color', None)\n\n        return ActorConfigurationData(model, transform, rolename, speed, autopilot, random_location, color)\n\n    @staticmethod\n    def parse_from_dict(actor_dict, rolename):\n        \"\"\"\n        static method to initialize an ActorConfigurationData from a given ET tree\n        \"\"\"\n\n        model = actor_dict['model'] if 'model' in actor_dict else 'vehicle.*'\n\n        pos_x = float(actor_dict['x']) if 'x' in actor_dict else 0\n        pos_y = float(actor_dict['y']) if 'y' in actor_dict else 0\n        pos_z = float(actor_dict['z']) if 'z' in actor_dict else 0\n        yaw = float(actor_dict['yaw']) if 'yaw' in actor_dict else 0\n        transform = carla.Transform(carla.Location(x=pos_x, y=pos_y, z=pos_z), carla.Rotation(yaw=yaw))\n\n        rolename = actor_dict['rolename'] if 'rolename' in actor_dict else rolename\n        speed = actor_dict['speed'] if 'speed' in actor_dict else 0\n        autopilot = actor_dict['autopilot'] if 'autopilot' in actor_dict else False\n        random_location = actor_dict['random_location'] if 'random_location' in actor_dict else False\n        color = actor_dict['color'] if 'color' in actor_dict else None\n\n        return ActorConfigurationData(model, transform, rolename, speed, autopilot, random_location, color)\n\n\nclass ScenarioConfiguration(object):\n\n    \"\"\"\n    This class provides a basic scenario configuration incl.:\n    - configurations for all actors\n    - town, where the scenario should be executed\n    - name of the scenario (e.g. ControlLoss_1)\n    - type is the class of scenario (e.g. ControlLoss)\n    \"\"\"\n\n    def __init__(self):\n        self.trigger_points = []\n        self.ego_vehicles = []\n        self.other_actors = []\n        self.other_parameters = {}\n        self.town = None\n        self.name = None\n        self.type = None\n        self.route = None\n        self.agent = None\n        self.weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)\n        self.friction = None\n        self.subtype = None\n        self.route_var_name = None\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/actor_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a wrapper to access/use user-defined actor\ncontrols for example to realize OpenSCENARIO controllers.\n\nAt the moment only controls implemented in Python are supported.\n\nA user must not modify this module.\n\"\"\"\n\nimport importlib\nimport os\nimport sys\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.external_control import ExternalControl\nfrom srunner.scenariomanager.actorcontrols.npc_vehicle_control import NpcVehicleControl\nfrom srunner.scenariomanager.actorcontrols.pedestrian_control import PedestrianControl\n\n\nclass ActorControl(object):\n\n    \"\"\"\n    This class provides a wrapper (access mechanism) for user-defined actor controls.\n    The controllers are loaded via importlib. Therefore, the module name of the controller\n    has to match the control class name (e.g. my_own_control.py and MyOwnControl()).\n\n    At the moment only controllers implemented in Python are supported, or controllers that\n    are completely implemented outside of ScenarioRunner (see ExternalControl).\n\n    This wrapper is for example used to realize the OpenSCENARIO controllers.\n\n    Note:\n       If no controllers are provided in OpenSCENARIO a default controller for vehicles and\n       pedestrians is instantiated. For vehicles the NpcVehicleControl is used, for pedestrians\n       it is the PedestrianControl.\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the controller.\n        control_py_module (string): Fully qualified path to the controller python module.\n        args (dict): A dictionary containing all parameters of the controller as (key, value) pairs.\n        scenario_file_path (string): Path to search for the controller implementation.\n\n    Attributes:\n        control_instance: Instance of the user-defined controller.\n        _last_longitudinal_command: Timestamp of the last issued longitudinal control command (e.g. target speed).\n            Defaults to None. Used to avoid that 2 longitudinal control commands are issued at the same time.\n        _last_waypoint_command: Timestamp of the last issued waypoint control command.\n            Defaults to None. Used to avoid that 2 waypoint control commands are issued at the same time.\n    \"\"\"\n\n    control_instance = None\n\n    _last_longitudinal_command = None\n    _last_waypoint_command = None\n    _last_lane_offset_command = None\n\n    def __init__(self, actor, control_py_module, args, scenario_file_path):\n\n        # use importlib to import the control module\n        if not control_py_module:\n            if isinstance(actor, carla.Walker):\n                self.control_instance = PedestrianControl(actor)\n            elif isinstance(actor, carla.Vehicle):\n                self.control_instance = NpcVehicleControl(actor)\n            else:\n                # use ExternalControl for all misc objects to handle all actors the same way\n                self.control_instance = ExternalControl(actor)\n        else:\n            if scenario_file_path:\n                sys.path.append(scenario_file_path)\n            if \".py\" in control_py_module:\n                module_name = os.path.basename(control_py_module).split('.')[0]\n                sys.path.append(os.path.dirname(control_py_module))\n                module_control = importlib.import_module(module_name)\n                control_class_name = module_control.__name__.title().replace('_', '')\n            else:\n                sys.path.append(os.path.dirname(__file__))\n                module_control = importlib.import_module(control_py_module)\n                control_class_name = control_py_module.split('.')[-1].title().replace('_', '')\n\n            self.control_instance = getattr(module_control, control_class_name)(actor, args)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        self.control_instance.reset()\n\n    def update_target_speed(self, target_speed, start_time=None):\n        \"\"\"\n        Update the actor's target speed.\n\n        Args:\n            target_speed (float): New target speed [m/s].\n            start_time (float): Start time of the new \"maneuver\" [s].\n        \"\"\"\n        self.control_instance.update_target_speed(target_speed)\n        if start_time:\n            self._last_longitudinal_command = start_time\n\n    def update_waypoints(self, waypoints, start_time=None):\n        \"\"\"\n        Update the actor's waypoints\n\n        Args:\n            waypoints (List of carla.Transform): List of new waypoints.\n            start_time (float): Start time of the new \"maneuver\" [s].\n        \"\"\"\n        self.control_instance.update_waypoints(waypoints)\n        if start_time:\n            self._last_waypoint_command = start_time\n\n    def update_offset(self, offset, start_time=None):\n        \"\"\"\n        Update the actor's offset\n\n        Args:\n            offset (float): Value of the new offset.\n            start_time (float): Start time of the new \"maneuver\" [s].\n        \"\"\"\n        self.control_instance.update_offset(offset)\n        if start_time:\n            self._last_waypoint_command = start_time\n            self._last_lane_offset_command = start_time\n\n    def check_reached_waypoint_goal(self):\n        \"\"\"\n        Check if the actor reached the end of the waypoint list\n\n        returns:\n            True if the end was reached, False otherwise.\n        \"\"\"\n        return self.control_instance.check_reached_waypoint_goal()\n\n    def get_last_longitudinal_command(self):\n        \"\"\"\n        Get timestamp of the last issued longitudinal control command (target_speed)\n\n        returns:\n            Timestamp of last longitudinal control command\n        \"\"\"\n        return self._last_longitudinal_command\n\n    def get_last_waypoint_command(self):\n        \"\"\"\n        Get timestamp of the last issued waypoint control command\n\n        returns:\n            Timestamp of last waypoint control command\n        \"\"\"\n        return self._last_waypoint_command\n\n    def get_last_lane_offset_command(self):\n        \"\"\"\n        Get timestamp of the last issued lane offset control command\n\n        returns:\n            Timestamp of last lane offset control command\n        \"\"\"\n        return self._last_lane_offset_command\n\n    def set_init_speed(self):\n        \"\"\"\n        Update the actor's initial speed setting\n        \"\"\"\n        self.control_instance.set_init_speed()\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n        \"\"\"\n        self.control_instance.run_step()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/basic_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the base class for user-defined actor\ncontrollers. All user-defined controls must be derived from\nthis class.\n\nA user must not modify the module.\n\"\"\"\n\n\nclass BasicControl(object):\n\n    \"\"\"\n    This class is the base class for user-defined actor controllers\n    All user-defined agents must be derived from this class.\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the controller.\n\n    Attributes:\n        _actor (carla.Actor): Controlled actor.\n            Defaults to None.\n        _target_speed (float): Logitudinal target speed of the controller.\n            Defaults to 0.\n        _init_speed (float): Initial longitudinal speed of the controller.\n            Defaults to 0.\n        _waypoints (list of carla.Transform): List of target waypoints the actor\n            should travel along. A waypoint here is of type carla.Transform!\n            Defaults to [].\n        _waypoints_updated (boolean):\n            Defaults to False.\n        _reached_goal (boolean):\n            Defaults to False.\n    \"\"\"\n\n    _actor = None\n    _waypoints = []\n    _waypoints_updated = False\n    _offset = 0\n    _offset_updated = False\n    _target_speed = 0\n    _reached_goal = False\n    _init_speed = False\n\n    def __init__(self, actor):\n        \"\"\"\n        Initialize the actor\n        \"\"\"\n        self._actor = actor\n\n    def update_target_speed(self, speed):\n        \"\"\"\n        Update the actor's target speed and set _init_speed to False.\n\n        Args:\n            speed (float): New target speed [m/s].\n        \"\"\"\n        self._target_speed = speed\n        self._init_speed = False\n\n    def update_waypoints(self, waypoints, start_time=None):\n        \"\"\"\n        Update the actor's waypoints\n\n        Args:\n            waypoints (List of carla.Transform): List of new waypoints.\n        \"\"\"\n        self._waypoints = waypoints\n        self._waypoints_updated = True\n\n    def update_offset(self, offset, start_time=None):\n        \"\"\"\n        Update the actor's waypoints\n\n        Args:\n            waypoints (List of carla.Transform): List of new waypoints.\n        \"\"\"\n        self._offset = offset\n        self._offset_updated = True\n\n    def set_init_speed(self):\n        \"\"\"\n        Set _init_speed to True\n        \"\"\"\n        self._init_speed = True\n\n    def check_reached_waypoint_goal(self):\n        \"\"\"\n        Check if the actor reached the end of the waypoint list\n\n        returns:\n            True if the end was reached, False otherwise.\n        \"\"\"\n        return self._reached_goal\n\n    def reset(self):\n        \"\"\"\n        Pure virtual function to reset the controller. This should be implemented\n        in the user-defined agent implementation.\n        \"\"\"\n        raise NotImplementedError(\n            \"This function must be re-implemented by the user-defined actor control.\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n\n    def run_step(self):\n        \"\"\"\n        Pure virtual function to run one step of the controllers's control loop.\n        This should be implemented in the user-defined agent implementation.\n        \"\"\"\n        raise NotImplementedError(\n            \"This function must be re-implemented by the user-defined actor control.\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/carla_autopilot.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for vehicles which\nuse CARLA's autopilot functionality\n\nLimitations:\n- No direct velocity control\n- No lateral maneuvers can be enforced\n\"\"\"\n\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass CarlaAutoPilotControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller uses CARLA's autopilot functionality. As a result,\n    the vehicle respects other traffic participants and traffic rules.\n    However, no longitudinal or lateral maneuvers can be enforced.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n        args (dictionary): Dictonary of (key, value) arguments to be used by the controller.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(CarlaAutoPilotControl, self).__init__(actor)\n        self._actor.set_autopilot(enabled=True)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        self._actor.set_autopilot(enabled=False)\n\n    def run_step(self):\n        \"\"\"\n        Everything is controlled through CARLA's autopilot functionality.\n        Nothing to do here\n        \"\"\"\n        pass\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/external_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example controller for actors, that use an external\nsoftware for longitudinal and lateral control command calculation.\nExamples for external controls are: Autoware, CARLA manual_control, etc.\n\nThis module is not intended for modification.\n\"\"\"\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass ExternalControl(BasicControl):\n\n    \"\"\"\n    Actor control class for actors, with externally implemented longitudinal and\n    lateral controlers (e.g. Autoware).\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the agent.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(ExternalControl, self).__init__(actor)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        The control loop and setting the actor controls is implemented externally.\n        \"\"\"\n        pass\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/npc_vehicle_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for vehicles\n\"\"\"\n\nimport math\n\nimport carla\nfrom agents.navigation.basic_agent import LocalPlanner\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass NpcVehicleControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller makes use of the LocalPlanner implemented in CARLA.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n    \"\"\"\n\n    _args = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05}\n\n    def __init__(self, actor, args=None):\n        super(NpcVehicleControl, self).__init__(actor)\n\n        self._local_planner = LocalPlanner(  # pylint: disable=undefined-variable\n            self._actor, opt_dict={\n                'target_speed': self._target_speed * 3.6,\n                'lateral_control_dict': self._args})\n\n        if self._waypoints:\n            self._update_plan()\n\n        self._brake_lights_active = False\n\n    def _update_plan(self):\n        \"\"\"\n        Update the plan (waypoint list) of the LocalPlanner\n        \"\"\"\n        plan = []\n        for transform in self._waypoints:\n            waypoint = CarlaDataProvider.get_map().get_waypoint(\n                transform.location, project_to_road=True, lane_type=carla.LaneType.Any)\n            plan.append((waypoint, RoadOption.LANEFOLLOW))\n        self._local_planner.set_global_plan(plan)\n\n    def _update_offset(self):\n        \"\"\"\n        Update the plan (waypoint list) of the LocalPlanner\n        \"\"\"\n        self._local_planner._vehicle_controller._lat_controller._offset = self._offset   # pylint: disable=protected-access\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            if self._local_planner:\n                self._local_planner.reset_vehicle()\n                self._local_planner = None\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        Note: Negative target speeds are not yet supported.\n              Try using simple_vehicle_control or vehicle_longitudinal_control.\n\n        If _waypoints are provided, the vehicle moves towards the next waypoint\n        with the given _target_speed, until reaching the final waypoint. Upon reaching\n        the final waypoint, _reached_goal is set to True.\n\n        If _waypoints is empty, the vehicle moves in its current direction with\n        the given _target_speed.\n\n        If _init_speed is True, the control command is post-processed to ensure that\n        the initial actor velocity is maintained independent of physics.\n        \"\"\"\n        self._reached_goal = False\n\n        if self._waypoints_updated:\n            self._waypoints_updated = False\n            self._update_plan()\n\n        if self._offset_updated:\n            self._offset_updated = False\n            self._update_offset()\n\n        target_speed = self._target_speed\n        # If target speed is negavite, raise an exception\n        if target_speed < 0:\n            raise NotImplementedError(\"Negative target speeds are not yet supported\")\n\n        self._local_planner.set_speed(target_speed * 3.6)\n        control = self._local_planner.run_step(debug=False)\n\n        # Check if the actor reached the end of the plan\n        if self._local_planner.done():\n            self._reached_goal = True\n\n        self._actor.apply_control(control)\n\n        current_speed = math.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2)\n\n        if self._init_speed:\n\n            # If _init_speed is set, and the PID controller is not yet up to the point to take over,\n            # we manually set the vehicle to drive with the correct velocity\n            if abs(target_speed - current_speed) > 3:\n                yaw = self._actor.get_transform().rotation.yaw * (math.pi / 180)\n                vx = math.cos(yaw) * target_speed\n                vy = math.sin(yaw) * target_speed\n                self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0))\n\n        # Change Brake light state\n        if (current_speed > target_speed or target_speed < 0.2) and not self._brake_lights_active:\n            light_state = self._actor.get_light_state()\n            light_state |= carla.VehicleLightState.Brake\n            self._actor.set_light_state(carla.VehicleLightState(light_state))\n            self._brake_lights_active = True\n\n        if self._brake_lights_active and current_speed < target_speed:\n            self._brake_lights_active = False\n            light_state = self._actor.get_light_state()\n            light_state &= ~carla.VehicleLightState.Brake\n            self._actor.set_light_state(carla.VehicleLightState(light_state))\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/pedestrian_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for pedestrians\n\"\"\"\n\nimport math\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass PedestrianControl(BasicControl):\n\n    \"\"\"\n    Controller class for pedestrians derived from BasicControl.\n\n    Args:\n        actor (carla.Actor): Pedestrian actor that should be controlled.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        if not isinstance(actor, carla.Walker):\n            raise RuntimeError(\"PedestrianControl: The to be controlled actor is not a pedestrian\")\n\n        super(PedestrianControl, self).__init__(actor)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        Note: Walkers / pedestrians are not able to walk backwards.\n\n        If _waypoints are provided, the pedestrian moves towards the next waypoint\n        with the given _target_speed, until reaching the final waypoint. Upon reaching\n        the final waypoint, _reached_goal is set to True.\n\n        If _waypoints is empty, the pedestrians moves in its current direction with\n        the given _target_speed.\n        \"\"\"\n        if not self._actor or not self._actor.is_alive:\n            return\n\n        control = self._actor.get_control()\n        control.speed = self._target_speed\n\n        # If target speed is negavite, raise an exception\n        if self._target_speed < 0:\n            raise NotImplementedError(\"Negative target speeds are not yet supported\")\n\n        if self._waypoints:\n            self._reached_goal = False\n            location = self._waypoints[0].location\n            direction = location - self._actor.get_location()\n            direction_norm = math.sqrt(direction.x**2 + direction.y**2)\n            control.direction = direction / direction_norm\n            self._actor.apply_control(control)\n            if direction_norm < 1.0:\n                self._waypoints = self._waypoints[1:]\n                if not self._waypoints:\n                    self._reached_goal = True\n        else:\n            control.direction = self._actor.get_transform().rotation.get_forward_vector()\n            self._actor.apply_control(control)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020-2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for vehicles which\ndoes not use CARLA's vehicle engine.\n\nLimitations:\n- Does not respect any traffic regulation: speed limit, priorities, etc.\n- Can only consider obstacles in forward facing reaching (i.e. in tight corners obstacles may be ignored).\n\"\"\"\n\nfrom distutils.util import strtobool\nimport math\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\nfrom srunner.scenariomanager.actorcontrols.visualizer import Visualizer\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\n\nclass SimpleVehicleControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller directly sets velocities in CARLA, therefore bypassing\n    CARLA's vehicle engine. This allows a very precise speed control, but comes\n    with limitations during cornering.\n\n    In addition, the controller can consider blocking obstacles, which are\n    classified as dynamic (i.e. vehicles, bikes, pedestrians). Activation of this\n    features is controlled by passing proper arguments to the class constructor.\n    The collision detection uses CARLA's obstacle sensor (sensor.other.obstacle),\n    which checks for obstacles in the direct forward channel of the vehicle, i.e.\n    there are limitation with sideways obstacles and while cornering.\n\n    The controller can also respect red traffic lights, and use a given deceleration\n    value for more realistic behavior. Both behaviors are activated via the corresponding\n    controller arguments.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n        args (dictionary): Dictonary of (key, value) arguments to be used by the controller.\n                           May include: (consider_obstacles, true/false)     - Enable consideration of obstacles\n                                        (proximity_threshold, distance)      - Distance in front of actor in which\n                                                                               obstacles are considered\n                                        (consider_trafficlights, true/false) - Enable consideration of traffic lights\n                                        (max_deceleration, float)            - Use a reasonable deceleration value for\n                                                                               this vehicle\n                                        (max_acceleration, float)            - Use a reasonable acceleration value for\n                                                                               this vehicle\n                                        (attach_camera, true/false)          - Attach OpenCV display to actor\n                                                                               (useful for debugging)\n\n    Attributes:\n\n        _generated_waypoint_list (list of carla.Transform): List of target waypoints the actor\n            should travel along. A waypoint here is of type carla.Transform!\n            Defaults to [].\n        _last_update (float): Last time step the update function (tick()) was called.\n            Defaults to None.\n        _consider_obstacles (boolean): Enable/Disable consideration of obstacles\n            Defaults to False.\n        _proximity_threshold (float): Distance in front of actor in which obstacles are considered\n            Defaults to infinity.\n        _cv_image (CV Image): Contains the OpenCV image, in case a debug camera is attached to the actor\n            Defaults to None.\n        _camera (sensor.camera.rgb): Debug camera attached to actor\n            Defaults to None.\n        _obstacle_sensor (sensor.other.obstacle): Obstacle sensor attached to actor\n            Defaults to None.\n        _obstacle_distance (float): Distance of the closest obstacle returned by the obstacle sensor\n            Defaults to infinity.\n        _obstacle_actor (carla.Actor): Closest obstacle returned by the obstacle sensor\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(SimpleVehicleControl, self).__init__(actor)\n        self._generated_waypoint_list = []\n        self._last_update = None\n        self._consider_traffic_lights = False\n        self._consider_obstacles = False\n        self._proximity_threshold = float('inf')\n        self._max_deceleration = None\n        self._max_acceleration = None\n\n        self._obstacle_sensor = None\n        self._obstacle_distance = float('inf')\n        self._obstacle_actor = None\n\n        self._visualizer = None\n\n        self._brake_lights_active = False\n\n        if args and 'consider_obstacles' in args and strtobool(args['consider_obstacles']):\n            self._consider_obstacles = strtobool(args['consider_obstacles'])\n            bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.other.obstacle')\n            bp.set_attribute('distance', '250')\n            if args and 'proximity_threshold' in args:\n                self._proximity_threshold = float(args['proximity_threshold'])\n                bp.set_attribute('distance', str(max(float(args['proximity_threshold']), 250)))\n            bp.set_attribute('hit_radius', '1')\n            bp.set_attribute('only_dynamics', 'True')\n            self._obstacle_sensor = CarlaDataProvider.get_world().spawn_actor(\n                bp, carla.Transform(carla.Location(x=self._actor.bounding_box.extent.x, z=1.0)), attach_to=self._actor)\n            self._obstacle_sensor.listen(lambda event: self._on_obstacle(event))  # pylint: disable=unnecessary-lambda\n\n        if args and 'consider_trafficlights' in args and strtobool(args['consider_trafficlights']):\n            self._consider_traffic_lights = strtobool(args['consider_trafficlights'])\n\n        if args and 'max_deceleration' in args:\n            self._max_deceleration = float(args['max_deceleration'])\n\n        if args and 'max_acceleration' in args:\n            self._max_acceleration = float(args['max_acceleration'])\n\n        if args and 'attach_camera' in args and strtobool(args['attach_camera']):\n            self._visualizer = Visualizer(self._actor)\n\n    def _on_obstacle(self, event):\n        \"\"\"\n        Callback for the obstacle sensor\n\n        Sets _obstacle_distance and _obstacle_actor according to the closest obstacle\n        found by the sensor.\n        \"\"\"\n        if not event:\n            return\n        self._obstacle_distance = event.distance\n        self._obstacle_actor = event.other_actor\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n\n        if self._visualizer:\n            self._visualizer.reset()\n        if self._obstacle_sensor:\n            self._obstacle_sensor.destroy()\n            self._obstacle_sensor = None\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        If _waypoints are provided, the vehicle moves towards the next waypoint\n        with the given _target_speed, until reaching the final waypoint. Upon reaching\n        the final waypoint, _reached_goal is set to True.\n\n        If _waypoints is empty, the vehicle moves in its current direction with\n        the given _target_speed.\n\n        For further details see :func:`_set_new_velocity`\n        \"\"\"\n\n        if self._reached_goal:\n            # Reached the goal, so stop\n            velocity = carla.Vector3D(0, 0, 0)\n            self._actor.set_target_velocity(velocity)\n            return\n\n        if self._visualizer:\n            self._visualizer.render()\n\n        self._reached_goal = False\n\n        if not self._waypoints:\n            # No waypoints are provided, so we have to create a list of waypoints internally\n            # get next waypoints from map, to avoid leaving the road\n            self._reached_goal = False\n\n            map_wp = None\n            if not self._generated_waypoint_list:\n                map_wp = CarlaDataProvider.get_map().get_waypoint(CarlaDataProvider.get_location(self._actor))\n            else:\n                map_wp = CarlaDataProvider.get_map().get_waypoint(self._generated_waypoint_list[-1].location)\n            while len(self._generated_waypoint_list) < 50:\n                map_wps = map_wp.next(2.0)\n                if map_wps:\n                    self._generated_waypoint_list.append(map_wps[0].transform)\n                    map_wp = map_wps[0]\n                else:\n                    break\n\n            # Remove all waypoints that are too close to the vehicle\n            while (self._generated_waypoint_list and\n                   self._generated_waypoint_list[0].location.distance(self._actor.get_location()) < 0.5):\n                self._generated_waypoint_list = self._generated_waypoint_list[1:]\n\n            direction_norm = self._set_new_velocity(self._offset_waypoint(self._generated_waypoint_list[0]))\n            if direction_norm < 2.0:\n                self._generated_waypoint_list = self._generated_waypoint_list[1:]\n        else:\n            # When changing from \"free\" driving without pre-defined waypoints to a defined route with waypoints\n            # it may happen that the first few waypoints are too close to the ego vehicle for obtaining a\n            # reasonable control command. Therefore, we drop these waypoints first.\n            while self._waypoints and self._waypoints[0].location.distance(self._actor.get_location()) < 0.5:\n                self._waypoints = self._waypoints[1:]\n\n            self._reached_goal = False\n            if not self._waypoints:\n                self._reached_goal = True\n            else:\n                direction_norm = self._set_new_velocity(self._offset_waypoint(self._waypoints[0]))\n                if direction_norm < 4.0:\n                    self._waypoints = self._waypoints[1:]\n                    if not self._waypoints:\n                        self._reached_goal = True\n\n    def _offset_waypoint(self, transform):\n        \"\"\"\n        Given a transform (which should be the position of a waypoint), displaces it to the side,\n        according to a given offset\n\n        Args:\n            transform (carla.Transform): Transform to be moved\n\n        returns:\n            offset_location (carla.Transform): Moved transform\n        \"\"\"\n        if self._offset == 0:\n            offset_location = transform.location\n        else:\n            right_vector = transform.get_right_vector()\n            offset_location = transform.location + carla.Location(x=self._offset*right_vector.x,\n                                                                  y=self._offset*right_vector.y)\n\n        return offset_location\n\n    def _set_new_velocity(self, next_location):\n        \"\"\"\n        Calculate and set the new actor veloctiy given the current actor\n        location and the _next_location_\n\n        If _consider_obstacles is true, the speed is adapted according to the closest\n        obstacle in front of the actor, if it is within the _proximity_threshold distance.\n        If _consider_trafficlights is true, the vehicle will enforce a stop at a red\n        traffic light.\n        If _max_deceleration is set, the vehicle will reduce its speed according to the\n        given deceleration value.\n        If the vehicle reduces its speed, braking lights will be activated.\n\n        Args:\n            next_location (carla.Location): Next target location of the actor\n\n        returns:\n            direction (carla.Vector3D): Length of direction vector of the actor\n        \"\"\"\n\n        current_time = GameTime.get_time()\n        target_speed = self._target_speed\n\n        if not self._last_update:\n            self._last_update = current_time\n\n        current_speed = math.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2)\n\n        if self._consider_obstacles:\n            # If distance is less than the proximity threshold, adapt velocity\n            if self._obstacle_distance < self._proximity_threshold:\n                distance = max(self._obstacle_distance, 0)\n                if distance > 0:\n                    current_speed_other = math.sqrt(\n                        self._obstacle_actor.get_velocity().x**2 + self._obstacle_actor.get_velocity().y**2)\n                    if current_speed_other < current_speed:\n                        acceleration = -0.5 * (current_speed - current_speed_other)**2 / distance\n                        target_speed = max(acceleration * (current_time - self._last_update) + current_speed, 0)\n                else:\n                    target_speed = 0\n\n        if self._consider_traffic_lights:\n            if (self._actor.is_at_traffic_light() and\n                    self._actor.get_traffic_light_state() == carla.TrafficLightState.Red):\n                target_speed = 0\n\n        if target_speed < current_speed:\n            if not self._brake_lights_active:\n                self._brake_lights_active = True\n                light_state = self._actor.get_light_state()\n                light_state |= carla.VehicleLightState.Brake\n                self._actor.set_light_state(carla.VehicleLightState(light_state))\n            if self._max_deceleration is not None:\n                target_speed = max(target_speed, current_speed - (current_time -\n                                                                  self._last_update) * self._max_deceleration)\n        else:\n            if self._brake_lights_active:\n                self._brake_lights_active = False\n                light_state = self._actor.get_light_state()\n                light_state &= ~carla.VehicleLightState.Brake\n                self._actor.set_light_state(carla.VehicleLightState(light_state))\n            if self._max_acceleration is not None:\n                tmp_speed = min(target_speed, current_speed + (current_time -\n                                                               self._last_update) * self._max_acceleration)\n                # If the tmp_speed is < 0.5 the vehicle may not properly accelerate.\n                # Therefore, we bump the speed to 0.5 m/s if target_speed allows.\n                target_speed = max(tmp_speed, min(0.5, target_speed))\n\n        # set new linear velocity\n        velocity = carla.Vector3D(0, 0, 0)\n        direction = next_location - CarlaDataProvider.get_location(self._actor)\n        direction_norm = math.sqrt(direction.x**2 + direction.y**2)\n        velocity.x = direction.x / direction_norm * target_speed\n        velocity.y = direction.y / direction_norm * target_speed\n\n        self._actor.set_target_velocity(velocity)\n\n        # set new angular velocity\n        current_yaw = CarlaDataProvider.get_transform(self._actor).rotation.yaw\n        # When we have a waypoint list, use the direction between the waypoints to calculate the heading (change)\n        # otherwise use the waypoint heading directly\n        if self._waypoints:\n            delta_yaw = math.degrees(math.atan2(direction.y, direction.x)) - current_yaw\n        else:\n            new_yaw = CarlaDataProvider.get_map().get_waypoint(next_location).transform.rotation.yaw\n            delta_yaw = new_yaw - current_yaw\n\n        if math.fabs(delta_yaw) > 360:\n            delta_yaw = delta_yaw % 360\n\n        if delta_yaw > 180:\n            delta_yaw = delta_yaw - 360\n        elif delta_yaw < -180:\n            delta_yaw = delta_yaw + 360\n\n        angular_velocity = carla.Vector3D(0, 0, 0)\n        if target_speed == 0:\n            angular_velocity.z = 0\n        else:\n            angular_velocity.z = delta_yaw / (direction_norm / target_speed)\n        self._actor.set_target_angular_velocity(angular_velocity)\n\n        self._last_update = current_time\n\n        return direction_norm\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/vehicle_longitudinal_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example longitudinal control for vehicles\n\"\"\"\n\nimport math\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass VehicleLongitudinalControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller only controls the throttle of a vehicle, but not the steering.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(VehicleLongitudinalControl, self).__init__(actor)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        The control loop is very simplistic:\n            If the actor speed is below the _target_speed, set throttle to 1.0,\n            otherwise, set throttle to 0.0\n        Note: This is a longitudinal controller only.\n\n        If _init_speed is True, the control command is post-processed to ensure that\n        the initial actor velocity is maintained independent of physics.\n        \"\"\"\n\n        control = self._actor.get_control()\n\n        velocity = self._actor.get_velocity()\n        current_speed = math.sqrt(velocity.x**2 + velocity.y**2)\n        if current_speed < self._target_speed and self._target_speed >= 0:\n            control.reverse = False\n            control.throttle = 1.0\n        elif current_speed > self._target_speed and self._target_speed < 0:\n            control.reverse = True\n            control.throttle = 1.0\n        else:\n            control.throttle = 0.0\n\n        self._actor.apply_control(control)\n\n        if self._init_speed:\n            if abs(self._target_speed - current_speed) > 3:\n                yaw = self._actor.get_transform().rotation.yaw * (math.pi / 180)\n                vx = math.cos(yaw) * self._target_speed\n                vy = math.sin(yaw) * self._target_speed\n                self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0))\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/visualizer.py",
    "content": "#!/usr/bin/python\n\n# Copyright (c) 2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an OpenCV based visualizer for camera sensors\nattached to an actor.\n\nThe modul can for example be used inside an OSC Actor controller,\nsuch as simple_vehicle_control.py\n\nIt can also be used as blueprint to implement custom visualizers.\n\"\"\"\n\nimport cv2\nimport numpy as np\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass Visualizer(object):\n\n    \"\"\"\n    Visualizer class for actor controllers.\n\n    The class provides a birdeye camera and a camera mounted in the front\n    bumper of the actor. The resolution is 1000x400 for both RGB cameras.\n\n    To use this class, it is only required to:\n    1. Add an instance inside the controller constructor\n        visualizer = Visualizer(actor)\n    2. Call the render method on a regular basis\n        visualizer.render()\n    3. Call the reset method during cleanup\n        visualizer.reset()\n\n    Args:\n        actor (carla.Actor): Vehicle actor the cameras should be attached to.\n\n    Attributes:\n        _actor (carla.Actor): The reference actor\n        _cv_image_bird (numpy array): OpenCV image for the birdeye camera\n        _cv_image_actor (numpy array): OpenCV image for the bumper camera\n        _camera_bird (carla.Camera): Birdeye camera\n        _camera_actor (carla.Camera): Bumper camera\n        _video_writer (boolean): Flag to disable/enable writing the image stream into a video\n    \"\"\"\n\n    _video_writer = False\n\n    def __init__(self, actor):\n        self._actor = actor\n        self._cv_image_bird = None\n        self._cv_image_actor = None\n        self._camera_bird = None\n        self._camera_actor = None\n\n        bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.camera.rgb')\n        bp.set_attribute('image_size_x', '1000')\n        bp.set_attribute('image_size_y', '400')\n        self._camera_bird = CarlaDataProvider.get_world().spawn_actor(bp, carla.Transform(\n            carla.Location(x=20.0, z=50.0), carla.Rotation(pitch=-90, yaw=-90)), attach_to=self._actor)\n        self._camera_bird.listen(lambda image: self._on_camera_update(\n            image, birdseye=True))  # pylint: disable=unnecessary-lambda\n\n        bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.camera.rgb')\n        bp.set_attribute('image_size_x', '1000')\n        bp.set_attribute('image_size_y', '400')\n        self._camera_actor = CarlaDataProvider.get_world().spawn_actor(bp, carla.Transform(\n            carla.Location(x=2.3, z=1.0)), attach_to=self._actor)\n        self._camera_actor.listen(lambda image: self._on_camera_update(\n            image, birdseye=False))  # pylint: disable=unnecessary-lambda\n\n        if self._video_writer:\n            fourcc = cv2.VideoWriter_fourcc(*'mp4v')\n            self._video = cv2.VideoWriter('recorded_video.avi', fourcc, 13, (1000, 800))\n\n    def reset(self):\n        \"\"\"\n        Reset cameras\n        \"\"\"\n        if self._camera_bird:\n            self._camera_bird.destroy()\n            self._camera_bird = None\n        if self._camera_actor:\n            self._camera_actor.destroy()\n            self._camera_actor = None\n\n    def _on_camera_update(self, image, birdseye):\n        \"\"\"\n        Callback for the camera sensor\n\n        Sets the OpenCV image (_cv_image). Requires conversion from BGRA to RGB.\n        \"\"\"\n        if not image:\n            return\n\n        image_data = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n        np_image = np.reshape(image_data, (image.height, image.width, 4))\n        np_image = np_image[:, :, :3]\n        np_image = np_image[:, :, ::-1]\n        if not birdseye:\n            self._cv_image_actor = cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB)\n        else:\n            self._cv_image_bird = cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB)\n\n    def render(self):\n        \"\"\"\n        Render images in an OpenCV window (has to be called on a regular basis)\n        \"\"\"\n        if self._cv_image_actor is not None and self._cv_image_bird is not None:\n            im_v = cv2.vconcat([self._cv_image_actor, self._cv_image_bird])\n            cv2.circle(im_v, (900, 300), 80, (170, 170, 170), -1)\n            text = str(int(round((self._actor.get_velocity().x * 3.6))))+\" kph\"\n\n            speed = np.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2)\n\n            text = str(int(round((speed * 3.6))))+\" kph\"\n            text = ' '*(7-len(text)) + text\n            im_v = cv2.putText(im_v, text, (830, 310), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 0), 2, cv2.LINE_AA)\n            cv2.imshow(\"\", im_v)\n            cv2.waitKey(1)\n\n            if self._video_writer:\n                self._video.write(im_v)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/carla_data_provider.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all frequently used data from CARLA via\nlocal buffers to avoid blocking calls to CARLA\n\"\"\"\n\nfrom __future__ import print_function\n\nimport math\nimport re\nimport threading\nfrom numpy import random\nfrom six import iteritems\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\n\ndef calculate_velocity(actor):\n    \"\"\"\n    Method to calculate the velocity of a actor\n    \"\"\"\n    velocity_squared = actor.get_velocity().x**2\n    velocity_squared += actor.get_velocity().y**2\n    return math.sqrt(velocity_squared)\n\n\nclass CarlaDataProvider(object):  # pylint: disable=too-many-public-methods\n\n    \"\"\"\n    This class provides access to various data of all registered actors\n    It buffers the data and updates it on every CARLA tick\n\n    Currently available data:\n    - Absolute velocity\n    - Location\n    - Transform\n\n    Potential additions:\n    - Acceleration\n\n    In addition it provides access to the map and the transform of all traffic lights\n    \"\"\"\n\n    _actor_velocity_map = {}\n    _actor_location_map = {}\n    _actor_transform_map = {}\n    _traffic_light_map = {}\n    _carla_actor_pool = {}\n    _global_osc_parameters = {}\n    _client = None\n    _world = None\n    _map = None\n    _sync_flag = False\n    _spawn_points = None\n    _spawn_index = 0\n    _blueprint_library = None\n    _all_actors = None\n    _ego_vehicle_route = None\n    _traffic_manager_port = 8000\n    _random_seed = 2000\n    _rng = random.RandomState(_random_seed)\n    _grp = None\n    _runtime_init_flag = False\n    _lock = threading.Lock()\n\n    @staticmethod\n    def register_actor(actor, transform=None):\n        \"\"\"\n        Add new actor to dictionaries\n        If actor already exists, throw an exception\n        \"\"\"\n        with CarlaDataProvider._lock:\n            if actor in CarlaDataProvider._actor_velocity_map:\n                raise KeyError(\n                    \"Vehicle '{}' already registered. Cannot register twice!\".format(actor.id))\n            else:\n                CarlaDataProvider._actor_velocity_map[actor] = 0.0\n            if actor in CarlaDataProvider._actor_location_map:\n                raise KeyError(\n                    \"Vehicle '{}' already registered. Cannot register twice!\".format(actor.id))\n            elif transform:\n                CarlaDataProvider._actor_location_map[actor] = transform.location\n            else:\n                CarlaDataProvider._actor_location_map[actor] = None\n\n            if actor in CarlaDataProvider._actor_transform_map:\n                raise KeyError(\n                    \"Vehicle '{}' already registered. Cannot register twice!\".format(actor.id))\n            else:\n                CarlaDataProvider._actor_transform_map[actor] = transform\n\n    @staticmethod\n    def update_osc_global_params(parameters):\n        \"\"\"\n        updates/initializes global osc parameters.\n        \"\"\"\n        CarlaDataProvider._global_osc_parameters.update(parameters)\n\n    @staticmethod\n    def get_osc_global_param_value(ref):\n        \"\"\"\n        returns updated global osc parameter value.\n        \"\"\"\n        return CarlaDataProvider._global_osc_parameters.get(ref.replace(\"$\", \"\"))\n\n    @staticmethod\n    def register_actors(actors, transforms=None):\n        \"\"\"\n        Add new set of actors to dictionaries\n        \"\"\"\n        if transforms is None:\n            transforms = [None] * len(actors)\n\n        for actor, transform in zip(actors, transforms):\n            CarlaDataProvider.register_actor(actor, transform)\n\n    @staticmethod\n    def on_carla_tick():\n        \"\"\"\n        Callback from CARLA\n        \"\"\"\n        with CarlaDataProvider._lock:\n            for actor in CarlaDataProvider._actor_velocity_map:\n                if actor is not None and actor.is_alive:\n                    CarlaDataProvider._actor_velocity_map[actor] = calculate_velocity(actor)\n\n            for actor in CarlaDataProvider._actor_location_map:\n                if actor is not None and actor.is_alive:\n                    CarlaDataProvider._actor_location_map[actor] = actor.get_location()\n\n            for actor in CarlaDataProvider._actor_transform_map:\n                if actor is not None and actor.is_alive:\n                    CarlaDataProvider._actor_transform_map[actor] = actor.get_transform()\n\n            world = CarlaDataProvider._world\n            if world is None:\n                print(\"WARNING: CarlaDataProvider couldn't find the world\")\n\n            CarlaDataProvider._all_actors = None\n\n    @staticmethod\n    def get_velocity(actor):\n        \"\"\"\n        returns the absolute velocity for the given actor\n        \"\"\"\n        for key in CarlaDataProvider._actor_velocity_map:\n            if key.id == actor.id:\n                return CarlaDataProvider._actor_velocity_map[key]\n\n        # We are intentionally not throwing here\n        # This may cause exception loops in py_trees\n        print('{}.get_velocity: {} not found!' .format(__name__, actor))\n        return 0.0\n\n    @staticmethod\n    def get_location(actor):\n        \"\"\"\n        returns the location for the given actor\n        \"\"\"\n        for key in CarlaDataProvider._actor_location_map:\n            if key.id == actor.id:\n                return CarlaDataProvider._actor_location_map[key]\n\n        # We are intentionally not throwing here\n        # This may cause exception loops in py_trees\n        print('{}.get_location: {} not found!' .format(__name__, actor))\n        return None\n\n    @staticmethod\n    def get_transform(actor):\n        \"\"\"\n        returns the transform for the given actor\n        \"\"\"\n        for key in CarlaDataProvider._actor_transform_map:\n            if key.id == actor.id:\n                return CarlaDataProvider._actor_transform_map[key]\n\n        # We are intentionally not throwing here\n        # This may cause exception loops in py_trees\n        print('{}.get_transform: {} not found!' .format(__name__, actor))\n        return None\n\n    @staticmethod\n    def set_client(client):\n        \"\"\"\n        Set the CARLA client\n        \"\"\"\n        CarlaDataProvider._client = client\n\n    @staticmethod\n    def get_client():\n        \"\"\"\n        Get the CARLA client\n        \"\"\"\n        return CarlaDataProvider._client\n\n    @staticmethod\n    def set_world(world):\n        \"\"\"\n        Set the world and world settings\n        \"\"\"\n        CarlaDataProvider._world = world\n        CarlaDataProvider._sync_flag = world.get_settings().synchronous_mode\n        CarlaDataProvider._map = world.get_map()\n        CarlaDataProvider._blueprint_library = world.get_blueprint_library()\n        CarlaDataProvider._grp = GlobalRoutePlanner(CarlaDataProvider._map, 2.0)\n        CarlaDataProvider.generate_spawn_points()\n        CarlaDataProvider.prepare_map()\n\n    @staticmethod\n    def get_world():\n        \"\"\"\n        Return world\n        \"\"\"\n        return CarlaDataProvider._world\n\n    @staticmethod\n    def get_map(world=None):\n        \"\"\"\n        Get the current map\n        \"\"\"\n        if CarlaDataProvider._map is None:\n            if world is None:\n                if CarlaDataProvider._world is None:\n                    raise ValueError(\"class member \\'world'\\' not initialized yet\")\n                else:\n                    CarlaDataProvider._map = CarlaDataProvider._world.get_map()\n            else:\n                CarlaDataProvider._map = world.get_map()\n\n        return CarlaDataProvider._map\n\n    @staticmethod\n    def get_random_seed():\n        \"\"\"\n        @return the random seed.\n        \"\"\"\n        return CarlaDataProvider._rng\n\n    @staticmethod\n    def get_global_route_planner():\n        \"\"\"\n        @return the global route planner\n        \"\"\"\n        return CarlaDataProvider._grp\n\n    @staticmethod\n    def get_all_actors():\n        \"\"\"\n        @return all the world actors. This is an expensive call, hence why it is part of the CDP,\n        but as this might not be used by everyone, only get the actors the first time someone\n        calls asks for them. 'CarlaDataProvider._all_actors' is reset each tick to None.\n        \"\"\"\n        if CarlaDataProvider._all_actors:\n            return CarlaDataProvider._all_actors\n\n        CarlaDataProvider._all_actors = CarlaDataProvider._world.get_actors()\n        return CarlaDataProvider._all_actors\n\n    @staticmethod\n    def is_sync_mode():\n        \"\"\"\n        @return true if syncronuous mode is used\n        \"\"\"\n        return CarlaDataProvider._sync_flag\n\n    @staticmethod\n    def set_runtime_init_mode(flag):\n        \"\"\"\n        Set the runtime init mode\n        \"\"\"\n        CarlaDataProvider._runtime_init_flag = flag\n\n    @staticmethod\n    def is_runtime_init_mode():\n        \"\"\"\n        @return true if runtime init mode is used\n        \"\"\"\n        return CarlaDataProvider._runtime_init_flag\n\n    @staticmethod\n    def find_weather_presets():\n        \"\"\"\n        Get weather presets from CARLA\n        \"\"\"\n        rgx = re.compile('.+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)')\n        name = lambda x: ' '.join(m.group(0) for m in rgx.finditer(x))\n        presets = [x for x in dir(carla.WeatherParameters) if re.match('[A-Z].+', x)]\n        return [(getattr(carla.WeatherParameters, x), name(x)) for x in presets]\n\n    @staticmethod\n    def prepare_map():\n        \"\"\"\n        This function set the current map and loads all traffic lights for this map to\n        _traffic_light_map\n        \"\"\"\n        if CarlaDataProvider._map is None:\n            CarlaDataProvider._map = CarlaDataProvider._world.get_map()\n\n        # Parse all traffic lights\n        CarlaDataProvider._traffic_light_map.clear()\n        for traffic_light in CarlaDataProvider._world.get_actors().filter('*traffic_light*'):\n            if traffic_light not in list(CarlaDataProvider._traffic_light_map):\n                CarlaDataProvider._traffic_light_map[traffic_light] = traffic_light.get_transform()\n            else:\n                raise KeyError(\n                    \"Traffic light '{}' already registered. Cannot register twice!\".format(traffic_light.id))\n\n    @staticmethod\n    def annotate_trafficlight_in_group(traffic_light):\n        \"\"\"\n        Get dictionary with traffic light group info for a given traffic light\n        \"\"\"\n        dict_annotations = {'ref': [], 'opposite': [], 'left': [], 'right': []}\n\n        # Get the waypoints\n        ref_location = CarlaDataProvider.get_trafficlight_trigger_location(traffic_light)\n        ref_waypoint = CarlaDataProvider.get_map().get_waypoint(ref_location)\n        ref_yaw = ref_waypoint.transform.rotation.yaw\n\n        group_tl = traffic_light.get_group_traffic_lights()\n\n        for target_tl in group_tl:\n            if traffic_light.id == target_tl.id:\n                dict_annotations['ref'].append(target_tl)\n            else:\n                # Get the angle between yaws\n                target_location = CarlaDataProvider.get_trafficlight_trigger_location(target_tl)\n                target_waypoint = CarlaDataProvider.get_map().get_waypoint(target_location)\n                target_yaw = target_waypoint.transform.rotation.yaw\n\n                diff = (target_yaw - ref_yaw) % 360\n\n                if diff > 330:\n                    continue\n                elif diff > 225:\n                    dict_annotations['right'].append(target_tl)\n                elif diff > 135.0:\n                    dict_annotations['opposite'].append(target_tl)\n                elif diff > 30:\n                    dict_annotations['left'].append(target_tl)\n\n        return dict_annotations\n\n    @staticmethod\n    def get_trafficlight_trigger_location(traffic_light):    # pylint: disable=invalid-name\n        \"\"\"\n        Calculates the yaw of the waypoint that represents the trigger volume of the traffic light\n        \"\"\"\n        def rotate_point(point, angle):\n            \"\"\"\n            rotate a given point by a given angle\n            \"\"\"\n            x_ = math.cos(math.radians(angle)) * point.x - math.sin(math.radians(angle)) * point.y\n            y_ = math.sin(math.radians(angle)) * point.x - math.cos(math.radians(angle)) * point.y\n\n            return carla.Vector3D(x_, y_, point.z)\n\n        base_transform = traffic_light.get_transform()\n        base_rot = base_transform.rotation.yaw\n        area_loc = base_transform.transform(traffic_light.trigger_volume.location)\n        area_ext = traffic_light.trigger_volume.extent\n\n        point = rotate_point(carla.Vector3D(0, 0, area_ext.z), base_rot)\n        point_location = area_loc + carla.Location(x=point.x, y=point.y)\n\n        return carla.Location(point_location.x, point_location.y, point_location.z)\n\n    @staticmethod\n    def update_light_states(ego_light, annotations, states, freeze=False, timeout=1000000000):\n        \"\"\"\n        Update traffic light states\n        \"\"\"\n        reset_params = []\n\n        for state in states:\n            relevant_lights = []\n            if state == 'ego':\n                relevant_lights = [ego_light]\n            else:\n                relevant_lights = annotations[state]\n            for light in relevant_lights:\n                prev_state = light.get_state()\n                prev_green_time = light.get_green_time()\n                prev_red_time = light.get_red_time()\n                prev_yellow_time = light.get_yellow_time()\n                reset_params.append({'light': light,\n                                     'state': prev_state,\n                                     'green_time': prev_green_time,\n                                     'red_time': prev_red_time,\n                                     'yellow_time': prev_yellow_time})\n\n                light.set_state(states[state])\n                if freeze:\n                    light.set_green_time(timeout)\n                    light.set_red_time(timeout)\n                    light.set_yellow_time(timeout)\n\n        return reset_params\n\n    @staticmethod\n    def reset_lights(reset_params):\n        \"\"\"\n        Reset traffic lights\n        \"\"\"\n        for param in reset_params:\n            param['light'].set_state(param['state'])\n            param['light'].set_green_time(param['green_time'])\n            param['light'].set_red_time(param['red_time'])\n            param['light'].set_yellow_time(param['yellow_time'])\n\n    @staticmethod\n    def get_next_traffic_light(actor, use_cached_location=True):\n        \"\"\"\n        returns the next relevant traffic light for the provided actor\n        \"\"\"\n\n        if not use_cached_location:\n            location = actor.get_transform().location\n        else:\n            location = CarlaDataProvider.get_location(actor)\n\n        waypoint = CarlaDataProvider.get_map().get_waypoint(location)\n        # Create list of all waypoints until next intersection\n        list_of_waypoints = []\n        while waypoint and not waypoint.is_intersection:\n            list_of_waypoints.append(waypoint)\n            waypoint = waypoint.next(2.0)[0]\n\n        # If the list is empty, the actor is in an intersection\n        if not list_of_waypoints:\n            return None\n\n        relevant_traffic_light = None\n        distance_to_relevant_traffic_light = float(\"inf\")\n\n        for traffic_light in CarlaDataProvider._traffic_light_map:\n            if hasattr(traffic_light, 'trigger_volume'):\n                tl_t = CarlaDataProvider._traffic_light_map[traffic_light]\n                transformed_tv = tl_t.transform(traffic_light.trigger_volume.location)\n                distance = carla.Location(transformed_tv).distance(list_of_waypoints[-1].transform.location)\n\n                if distance < distance_to_relevant_traffic_light:\n                    relevant_traffic_light = traffic_light\n                    distance_to_relevant_traffic_light = distance\n\n        return relevant_traffic_light\n\n    @staticmethod\n    def generate_spawn_points():\n        \"\"\"\n        Generate spawn points for the current map\n        \"\"\"\n        spawn_points = list(CarlaDataProvider.get_map(CarlaDataProvider._world).get_spawn_points())\n        CarlaDataProvider._rng.shuffle(spawn_points)\n        CarlaDataProvider._spawn_points = spawn_points\n        CarlaDataProvider._spawn_index = 0\n\n    @staticmethod\n    def create_blueprint(model, rolename='scenario', color=None, actor_category=\"car\", attribute_filter=None):\n        \"\"\"\n        Function to setup the blueprint of an actor given its model and other relevant parameters\n        \"\"\"\n        def check_attribute_value(blueprint, name, value):\n            \"\"\"\n            Checks if the blueprint has that attribute with that value\n            \"\"\"\n            if not blueprint.has_attribute(name):\n                return False\n\n            attribute_type = blueprint.get_attribute(key).type\n            if attribute_type == carla.ActorAttributeType.Bool:\n                return blueprint.get_attribute(name).as_bool() == value\n            elif attribute_type == carla.ActorAttributeType.Int:\n                return blueprint.get_attribute(name).as_int() == value\n            elif attribute_type == carla.ActorAttributeType.Float:\n                return blueprint.get_attribute(name).as_float() == value\n            elif attribute_type == carla.ActorAttributeType.String:\n                return blueprint.get_attribute(name).as_str() == value\n\n            return False\n\n        _actor_blueprint_categories = {\n            'car': 'vehicle.tesla.model3',\n            'van': 'vehicle.volkswagen.t2',\n            'truck': 'vehicle.carlamotors.carlacola',\n            'trailer': '',\n            'semitrailer': '',\n            'bus': 'vehicle.volkswagen.t2',\n            'motorbike': 'vehicle.kawasaki.ninja',\n            'bicycle': 'vehicle.diamondback.century',\n            'train': '',\n            'tram': '',\n            'pedestrian': 'walker.pedestrian.0001',\n        }\n\n        # Set the model\n        try:\n            blueprints = CarlaDataProvider._blueprint_library.filter(model)\n            if attribute_filter is not None:\n                for key, value in attribute_filter.items():\n                    blueprints = [x for x in blueprints if check_attribute_value(x, key, value)]\n\n            blueprint = CarlaDataProvider._rng.choice(blueprints)\n        except ValueError:\n            # The model is not part of the blueprint library. Let's take a default one for the given category\n            bp_filter = \"vehicle.*\"\n            new_model = _actor_blueprint_categories[actor_category]\n            if new_model != '':\n                bp_filter = new_model\n            print(\"WARNING: Actor model {} not available. Using instead {}\".format(model, new_model))\n            blueprint = CarlaDataProvider._rng.choice(CarlaDataProvider._blueprint_library.filter(bp_filter))\n\n        # Set the color\n        if color:\n            if not blueprint.has_attribute('color'):\n                print(\n                    \"WARNING: Cannot set Color ({}) for actor {} due to missing blueprint attribute\".format(\n                        color, blueprint.id))\n            else:\n                default_color_rgba = blueprint.get_attribute('color').as_color()\n                default_color = '({}, {}, {})'.format(default_color_rgba.r, default_color_rgba.g, default_color_rgba.b)\n                try:\n                    blueprint.set_attribute('color', color)\n                except ValueError:\n                    # Color can't be set for this vehicle\n                    print(\"WARNING: Color ({}) cannot be set for actor {}. Using instead: ({})\".format(\n                        color, blueprint.id, default_color))\n                    blueprint.set_attribute('color', default_color)\n        else:\n            if blueprint.has_attribute('color') and rolename != 'hero':\n                color = CarlaDataProvider._rng.choice(blueprint.get_attribute('color').recommended_values)\n                blueprint.set_attribute('color', color)\n\n        # Make pedestrians mortal\n        if blueprint.has_attribute('is_invincible'):\n            blueprint.set_attribute('is_invincible', 'false')\n\n        # Set the rolename\n        if blueprint.has_attribute('role_name'):\n            blueprint.set_attribute('role_name', rolename)\n\n        return blueprint\n\n    @staticmethod\n    def handle_actor_batch(batch, tick=True):\n        \"\"\"\n        Forward a CARLA command batch to spawn actors to CARLA, and gather the responses.\n        Returns list of actors on success, none otherwise\n        \"\"\"\n        sync_mode = CarlaDataProvider.is_sync_mode()\n        actors = []\n\n        if CarlaDataProvider._client:\n            responses = CarlaDataProvider._client.apply_batch_sync(batch, sync_mode and tick)\n        else:\n            raise ValueError(\"class member \\'client'\\' not initialized yet\")\n\n        # Wait (or not) for the actors to be spawned properly before we do anything\n        if not tick:\n            pass\n        elif CarlaDataProvider.is_runtime_init_mode():\n            CarlaDataProvider._world.wait_for_tick()\n        elif sync_mode:\n            CarlaDataProvider._world.tick()\n        else:\n            CarlaDataProvider._world.wait_for_tick()\n\n        actor_ids = [r.actor_id for r in responses if not r.error]\n        for r in responses:\n            if r.error:\n                print(\"WARNING: Not all actors were spawned\")\n                break\n        actors = list(CarlaDataProvider._world.get_actors(actor_ids))\n        return actors\n\n    @staticmethod\n    def request_new_actor(model, spawn_point, rolename='scenario', autopilot=False,\n                          random_location=False, color=None, actor_category=\"car\",\n                          attribute_filter=None, tick=True):\n        \"\"\"\n        This method tries to create a new actor, returning it if successful (None otherwise).\n        \"\"\"\n        blueprint = CarlaDataProvider.create_blueprint(model, rolename, color, actor_category, attribute_filter)\n\n        if random_location:\n            actor = None\n            while not actor:\n                spawn_point = CarlaDataProvider._rng.choice(CarlaDataProvider._spawn_points)\n                actor = CarlaDataProvider._world.try_spawn_actor(blueprint, spawn_point)\n\n        else:\n            # For non prop models, slightly lift the actor to avoid collisions with the ground\n            z_offset = 0.2 if 'prop' not in model else 0\n\n            # DO NOT USE spawn_point directly, as this will modify spawn_point permanently\n            _spawn_point = carla.Transform(carla.Location(), spawn_point.rotation)\n            _spawn_point.location.x = spawn_point.location.x\n            _spawn_point.location.y = spawn_point.location.y\n            _spawn_point.location.z = spawn_point.location.z + z_offset\n            actor = CarlaDataProvider._world.try_spawn_actor(blueprint, _spawn_point)\n\n        if actor is None:\n            print(\"WARNING: Cannot spawn actor {} at position {}\".format(model, spawn_point.location))\n            return None\n\n        # De/activate the autopilot of the actor if it belongs to vehicle\n        if autopilot:\n            if isinstance(actor, carla.Vehicle):\n                actor.set_autopilot(autopilot, CarlaDataProvider._traffic_manager_port)\n            else:\n                print(\"WARNING: Tried to set the autopilot of a non vehicle actor\")\n\n        # Wait for the actor to be spawned properly before we do anything\n        if not tick:\n            pass\n        elif CarlaDataProvider.is_runtime_init_mode():\n            CarlaDataProvider._world.wait_for_tick()\n        elif CarlaDataProvider.is_sync_mode():\n            CarlaDataProvider._world.tick()\n        else:\n            CarlaDataProvider._world.wait_for_tick()\n\n        CarlaDataProvider._carla_actor_pool[actor.id] = actor\n        CarlaDataProvider.register_actor(actor, spawn_point)\n        return actor\n\n    @staticmethod\n    def request_new_actors(actor_list, attribute_filter=None, tick=True):\n        \"\"\"\n        This method tries to series of actor in batch. If this was successful,\n        the new actors are returned, None otherwise.\n\n        param:\n        - actor_list: list of ActorConfigurationData\n        \"\"\"\n\n        SpawnActor = carla.command.SpawnActor                      # pylint: disable=invalid-name\n        PhysicsCommand = carla.command.SetSimulatePhysics          # pylint: disable=invalid-name\n        FutureActor = carla.command.FutureActor                    # pylint: disable=invalid-name\n        ApplyTransform = carla.command.ApplyTransform              # pylint: disable=invalid-name\n        SetAutopilot = carla.command.SetAutopilot                  # pylint: disable=invalid-name\n        SetVehicleLightState = carla.command.SetVehicleLightState  # pylint: disable=invalid-name\n\n        batch = []\n\n        CarlaDataProvider.generate_spawn_points()\n\n        for actor in actor_list:\n\n            # Get the blueprint\n            blueprint = CarlaDataProvider.create_blueprint(\n                actor.model, actor.rolename, actor.color, actor.category, attribute_filter)\n\n            # Get the spawn point\n            transform = actor.transform\n            if actor.random_location:\n                if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points):\n                    print(\"No more spawn points to use\")\n                    break\n                else:\n                    _spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index]  # pylint: disable=unsubscriptable-object\n                    CarlaDataProvider._spawn_index += 1\n\n            else:\n                _spawn_point = carla.Transform()\n                _spawn_point.rotation = transform.rotation\n                _spawn_point.location.x = transform.location.x\n                _spawn_point.location.y = transform.location.y\n                if blueprint.has_tag('walker'):\n                    # On imported OpenDRIVE maps, spawning of pedestrians can fail.\n                    # By increasing the z-value the chances of success are increased.\n                    map_name = CarlaDataProvider._map.name.split(\"/\")[-1]\n                    if not map_name.startswith('OpenDrive'):\n                        _spawn_point.location.z = transform.location.z + 0.2\n                    else:\n                        _spawn_point.location.z = transform.location.z + 0.8\n                else:\n                    _spawn_point.location.z = transform.location.z + 0.2\n\n            # Get the command\n            command = SpawnActor(blueprint, _spawn_point)\n            command.then(SetAutopilot(FutureActor, actor.autopilot, CarlaDataProvider._traffic_manager_port))\n\n            if actor.args is not None and 'physics' in actor.args and actor.args['physics'] == \"off\":\n                command.then(ApplyTransform(FutureActor, _spawn_point)).then(PhysicsCommand(FutureActor, False))\n            elif actor.category == 'misc':\n                command.then(PhysicsCommand(FutureActor, True))\n            if actor.args is not None and 'lights' in actor.args and actor.args['lights'] == \"on\":\n                command.then(SetVehicleLightState(FutureActor, carla.VehicleLightState.All))\n\n            batch.append(command)\n\n        actors = CarlaDataProvider.handle_actor_batch(batch, tick)\n        for actor in actors:\n            if actor is None:\n                continue\n            CarlaDataProvider._carla_actor_pool[actor.id] = actor\n            CarlaDataProvider.register_actor(actor, _spawn_point)\n\n        return actors\n\n    @staticmethod\n    def request_new_batch_actors(model, amount, spawn_points, autopilot=False,\n                                 random_location=False, rolename='scenario',\n                                 attribute_filter=None, tick=True):\n        \"\"\"\n        Simplified version of \"request_new_actors\". This method also create several actors in batch.\n\n        Instead of needing a list of ActorConfigurationData, an \"amount\" parameter is used.\n        This makes actor spawning easier but reduces the amount of configurability.\n\n        Some parameters are the same for all actors (rolename, autopilot and random location)\n        while others are randomized (color)\n        \"\"\"\n\n        SpawnActor = carla.command.SpawnActor      # pylint: disable=invalid-name\n        SetAutopilot = carla.command.SetAutopilot  # pylint: disable=invalid-name\n        FutureActor = carla.command.FutureActor    # pylint: disable=invalid-name\n\n        CarlaDataProvider.generate_spawn_points()\n\n        batch = []\n\n        for i in range(amount):\n            # Get vehicle by model\n            blueprint = CarlaDataProvider.create_blueprint(model, rolename, attribute_filter=attribute_filter)\n\n            if random_location:\n                if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points):\n                    print(\"No more spawn points to use. Spawned {} actors out of {}\".format(i + 1, amount))\n                    break\n                else:\n                    spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index]  # pylint: disable=unsubscriptable-object\n                    CarlaDataProvider._spawn_index += 1\n            else:\n                try:\n                    spawn_point = spawn_points[i]\n                except IndexError:\n                    print(\"The amount of spawn points is lower than the amount of vehicles spawned\")\n                    break\n\n            if spawn_point:\n                batch.append(SpawnActor(blueprint, spawn_point).then(\n                    SetAutopilot(FutureActor, autopilot, CarlaDataProvider._traffic_manager_port)))\n\n        actors = CarlaDataProvider.handle_actor_batch(batch, tick)\n        for actor, command in zip(actors, batch):\n            if actor is None:\n                continue\n            CarlaDataProvider._carla_actor_pool[actor.id] = actor\n            CarlaDataProvider.register_actor(actor, command.transform)\n\n        return actors\n\n    @staticmethod\n    def get_actors():\n        \"\"\"\n        Return list of actors and their ids\n\n        Note: iteritems from six is used to allow compatibility with Python 2 and 3\n        \"\"\"\n        return iteritems(CarlaDataProvider._carla_actor_pool)\n\n    @staticmethod\n    def actor_id_exists(actor_id):\n        \"\"\"\n        Check if a certain id is still at the simulation\n        \"\"\"\n        if actor_id in CarlaDataProvider._carla_actor_pool:\n            return True\n\n        return False\n\n    @staticmethod\n    def get_hero_actor():\n        \"\"\"\n        Get the actor object of the hero actor if it exists, returns none otherwise.\n        \"\"\"\n        for actor_id in CarlaDataProvider._carla_actor_pool:\n            if CarlaDataProvider._carla_actor_pool[actor_id].attributes['role_name'] == 'hero':\n                return CarlaDataProvider._carla_actor_pool[actor_id]\n        return None\n\n    @staticmethod\n    def get_actor_by_id(actor_id):\n        \"\"\"\n        Get an actor from the pool by using its ID. If the actor\n        does not exist, None is returned.\n        \"\"\"\n        if actor_id in CarlaDataProvider._carla_actor_pool:\n            return CarlaDataProvider._carla_actor_pool[actor_id]\n\n        print(\"Non-existing actor id {}\".format(actor_id))\n        return None\n\n    @staticmethod\n    def remove_actor_by_id(actor_id):\n        \"\"\"\n        Remove an actor from the pool using its ID\n        \"\"\"\n        if actor_id in CarlaDataProvider._carla_actor_pool:\n            CarlaDataProvider._carla_actor_pool[actor_id].destroy()\n            CarlaDataProvider._carla_actor_pool[actor_id] = None\n            CarlaDataProvider._carla_actor_pool.pop(actor_id)\n        else:\n            print(\"Trying to remove a non-existing actor id {}\".format(actor_id))\n\n    @staticmethod\n    def remove_actors_in_surrounding(location, distance):\n        \"\"\"\n        Remove all actors from the pool that are closer than distance to the\n        provided location\n        \"\"\"\n        for actor_id in CarlaDataProvider._carla_actor_pool.copy():\n            if CarlaDataProvider._carla_actor_pool[actor_id].get_location().distance(location) < distance:\n                CarlaDataProvider._carla_actor_pool[actor_id].destroy()\n                CarlaDataProvider._carla_actor_pool.pop(actor_id)\n\n        # Remove all keys with None values\n        CarlaDataProvider._carla_actor_pool = dict({k: v for k, v in CarlaDataProvider._carla_actor_pool.items() if v})\n\n    @staticmethod\n    def get_traffic_manager_port():\n        \"\"\"\n        Get the port of the traffic manager.\n        \"\"\"\n        return CarlaDataProvider._traffic_manager_port\n\n    @staticmethod\n    def set_traffic_manager_port(tm_port):\n        \"\"\"\n        Set the port to use for the traffic manager.\n        \"\"\"\n        CarlaDataProvider._traffic_manager_port = tm_port\n\n    @staticmethod\n    def cleanup():\n        \"\"\"\n        Cleanup and remove all entries from all dictionaries\n        \"\"\"\n        DestroyActor = carla.command.DestroyActor       # pylint: disable=invalid-name\n        batch = []\n\n        for actor_id in CarlaDataProvider._carla_actor_pool.copy():\n            actor = CarlaDataProvider._carla_actor_pool[actor_id]\n            if actor is not None and actor.is_alive:\n                batch.append(DestroyActor(actor))\n\n        if CarlaDataProvider._client:\n            try:\n                CarlaDataProvider._client.apply_batch_sync(batch)\n            except RuntimeError as e:\n                if \"time-out\" in str(e):\n                    pass\n                else:\n                    raise e\n\n        CarlaDataProvider._actor_velocity_map.clear()\n        CarlaDataProvider._actor_location_map.clear()\n        CarlaDataProvider._actor_transform_map.clear()\n        CarlaDataProvider._traffic_light_map.clear()\n        CarlaDataProvider._map = None\n        CarlaDataProvider._world = None\n        CarlaDataProvider._sync_flag = False\n        CarlaDataProvider._ego_vehicle_route = None\n        CarlaDataProvider._all_actors = None\n        CarlaDataProvider._carla_actor_pool = {}\n        CarlaDataProvider._client = None\n        CarlaDataProvider._spawn_points = None\n        CarlaDataProvider._spawn_index = 0\n        CarlaDataProvider._rng = random.RandomState(CarlaDataProvider._random_seed)\n        CarlaDataProvider._grp = None\n        CarlaDataProvider._runtime_init_flag = False\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/lights_sim.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a weather class and py_trees behavior\nto simulate weather in CARLA according to the astronomic\nbehavior of the sun.\n\"\"\"\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass RouteLightsBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Behavior responsible for turning the street lights on and off depending on the weather conditions.\n    Only those around the ego vehicle will be turned on, regardless of weather conditions\n    \"\"\"\n    SUN_ALTITUDE_THRESHOLD_1 = 15\n    SUN_ALTITUDE_THRESHOLD_2 = 165\n\n    # For higher fog and cloudness values, the amount of light in scene starts to rapidly decrease\n    CLOUDINESS_THRESHOLD = 80\n    FOG_THRESHOLD = 40\n\n    # In cases where more than one weather conditition is active, decrease the thresholds\n    COMBINED_THRESHOLD = 10\n\n    def __init__(self, ego_vehicle, radius=50, radius_increase=15, name=\"LightsBehavior\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super().__init__(name)\n        self._ego_vehicle = ego_vehicle\n        self._radius = radius\n        self._radius_increase = radius_increase\n        self._world = CarlaDataProvider.get_world()\n        self._light_manager = self._world.get_lightmanager()\n        self._light_manager.set_day_night_cycle(False)\n        self._vehicle_lights = carla.VehicleLightState.Position | carla.VehicleLightState.LowBeam\n\n        self._prev_night_mode = False\n\n    def update(self):\n        \"\"\"\n        Turns on / off all the lghts around a radius of the ego vehicle\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._ego_vehicle)\n        if not location:\n            return new_status\n\n        night_mode = self._get_night_mode(self._world.get_weather())\n        if night_mode:\n            self._turn_close_lights_on(location)\n        elif self._prev_night_mode:\n            self._turn_all_lights_off()\n\n        self._prev_night_mode = night_mode\n        return new_status\n\n    def _get_night_mode(self, weather):\n        \"\"\"Check wheather or not the street lights need to be turned on\"\"\"\n        altitude_dist = weather.sun_altitude_angle - self.SUN_ALTITUDE_THRESHOLD_1\n        altitude_dist = min(altitude_dist, self.SUN_ALTITUDE_THRESHOLD_2 - weather.sun_altitude_angle)\n        cloudiness_dist = self.CLOUDINESS_THRESHOLD - weather.cloudiness\n        fog_density_dist = self.FOG_THRESHOLD - weather.fog_density\n\n        # Check each parameter independetly\n        if altitude_dist < 0 or cloudiness_dist < 0 or fog_density_dist < 0:\n            return True\n\n        # Check if two or more values are close to their threshold\n        joined_threshold = int(altitude_dist < self.COMBINED_THRESHOLD)\n        joined_threshold += int(cloudiness_dist < self.COMBINED_THRESHOLD)\n        joined_threshold += int(fog_density_dist < self.COMBINED_THRESHOLD)\n\n        if joined_threshold >= 2:\n            return True\n\n        return False\n\n    def _turn_close_lights_on(self, location):\n        \"\"\"Turns on the lights of all the objects close to the ego vehicle\"\"\"\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_vehicle)\n        radius = max(self._radius, self._radius_increase * ego_speed)\n\n        # Street lights\n        on_lights = []\n        off_lights = []\n\n        all_lights = self._light_manager.get_all_lights()\n        for light in all_lights:\n            if light.location.distance(location) > radius:\n                if light.is_on:\n                    off_lights.append(light)\n            else:\n                if not light.is_on:\n                    on_lights.append(light)\n\n        self._light_manager.turn_on(on_lights)\n        self._light_manager.turn_off(off_lights)\n\n        # Vehicles\n        all_vehicles = CarlaDataProvider.get_all_actors().filter('*vehicle.*')\n        scenario_vehicles = [v for v in all_vehicles if v.attributes['role_name'] == 'scenario']\n\n        for vehicle in scenario_vehicles:\n            try:\n                if vehicle.get_location().distance(location) > radius:\n                        lights = vehicle.get_light_state()\n                        lights &= ~self._vehicle_lights  # Remove those lights\n                        vehicle.set_light_state(carla.VehicleLightState(lights))\n                else:\n                    lights = vehicle.get_light_state()\n                    lights |= self._vehicle_lights  # Add those lights\n                    vehicle.set_light_state(carla.VehicleLightState(lights))\n            except RuntimeError:\n                pass\n\n        # Ego vehicle\n        lights = self._ego_vehicle.get_light_state()\n        lights |= self._vehicle_lights\n        self._ego_vehicle.set_light_state(carla.VehicleLightState(lights))\n\n    def _turn_all_lights_off(self):\n        \"\"\"Turns off the lights of all object\"\"\"\n        all_lights = self._light_manager.get_all_lights()\n        off_lights = [l for l in all_lights if l.is_on]\n        self._light_manager.turn_off(off_lights)\n\n        # Vehicles\n        all_vehicles = CarlaDataProvider.get_all_actors().filter('*vehicle.*')\n        scenario_vehicles = [v for v in all_vehicles if v.attributes['role_name'] == 'scenario']\n\n        for vehicle in scenario_vehicles:\n            lights = vehicle.get_light_state()\n            lights &= ~self._vehicle_lights  # Remove those lights\n            vehicle.set_light_state(carla.VehicleLightState(lights))\n\n        # Ego vehicle\n        lights = self._ego_vehicle.get_light_state()\n        lights &= ~self._vehicle_lights  # Remove those lights\n        self._ego_vehicle.set_light_state(carla.VehicleLightState(lights))\n\n    def terminate(self, new_status):\n        self._light_manager.set_day_night_cycle(True)\n        return super().terminate(new_status)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/result_writer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module contains the result gatherer and write for CARLA scenarios.\nIt shall be used from the ScenarioManager only.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport time\nimport json\nfrom tabulate import tabulate\n\n\nclass ResultOutputProvider(object):\n\n    \"\"\"\n    This module contains the _result gatherer and write for CARLA scenarios.\n    It shall be used from the ScenarioManager only.\n    \"\"\"\n\n    def __init__(self, data, result, stdout=True, filename=None, junitfile=None, jsonfile=None):\n        \"\"\"\n        Setup all parameters\n        - _data contains all scenario-related information\n        - _result is overall pass/fail info\n        - _stdout (True/False) is used to (de)activate terminal output\n        - _filename is used to (de)activate file output in tabular form\n        - _junit is used to (de)activate file output in junit form\n        - _json is used to (de)activate file output in json form\n        \"\"\"\n        self._data = data\n        self._result = result\n        self._stdout = stdout\n        self._filename = filename\n        self._junit = junitfile\n        self._json = jsonfile\n\n        self._start_time = time.strftime('%Y-%m-%d %H:%M:%S',\n                                         time.localtime(self._data.start_system_time))\n        self._end_time = time.strftime('%Y-%m-%d %H:%M:%S',\n                                       time.localtime(self._data.end_system_time))\n\n    def write(self):\n        \"\"\"\n        Public write function\n        \"\"\"\n        if self._junit is not None:\n            self._write_to_junit()\n        if self._json is not None:\n            self._write_to_reportjson()\n\n        output = self.create_output_text()\n        if self._filename is not None:\n            with open(self._filename, 'w', encoding='utf-8') as fd:\n                fd.write(output)\n        if self._stdout:\n            print(output)\n\n    def create_output_text(self):\n        \"\"\"\n        Creates the output message\n        \"\"\"\n        output = \"\\n\"\n        output += \" ======= Results of Scenario: {} ---- {} =======\\n\".format(\n            self._data.scenario_tree.name, self._result)\n        end_line_length = len(output) - 3\n        output += \"\\n\"\n\n        # Lis of all the actors\n        output += \" > Ego vehicles:\\n\"\n        for ego_vehicle in self._data.ego_vehicles:\n            output += \"{}; \".format(ego_vehicle)\n        output += \"\\n\\n\"\n\n        output += \" > Other actors:\\n\"\n        for actor in self._data.other_actors:\n            output += \"{}; \".format(actor)\n        output += \"\\n\\n\"\n\n        # Simulation part\n        output += \" > Simulation Information\\n\"\n\n        system_time = round(self._data.scenario_duration_system, 2)\n        game_time = round(self._data.scenario_duration_game, 2)\n        ratio = round(self._data.scenario_duration_game / self._data.scenario_duration_system, 3)\n\n        list_statistics = [[\"Start Time\", \"{}\".format(self._start_time)]]\n        list_statistics.extend([[\"End Time\", \"{}\".format(self._end_time)]])\n        list_statistics.extend([[\"System Time\", \"{}s\".format(system_time)]])\n        list_statistics.extend([[\"Game Time\", \"{}s\".format(game_time)]])\n        list_statistics.extend([[\"Ratio (Game / System)\", \"{}\".format(ratio)]])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\\n\"\n\n        # Criteria part\n        output += \" > Criteria Information\\n\"\n        header = ['Actor', 'Criterion', 'Result', 'Actual Value', 'Success Value']\n        list_statistics = [header]\n\n        for criterion in self._data.scenario.get_criteria():\n            name = criterion.name\n            if criterion.optional:\n                name += \" (Opt.)\"\n            else:\n                name += \" (Req.)\"\n\n            actor = \"{} (id={})\".format(criterion.actor.type_id[8:], criterion.actor.id)\n\n            list_statistics.extend([[\n                actor, name, criterion.test_status, criterion.actual_value, criterion.success_value]])\n\n        # Timeout\n        actor = \"\"\n        criteria = \"Timeout (Req.)\"\n        result = \"SUCCESS\" if self._data.scenario_duration_game < self._data.scenario.timeout else \"FAILURE\"\n        actual_value = round(self._data.scenario_duration_game, 2)\n        expected_value = round(self._data.scenario.timeout, 2)\n\n        list_statistics.extend([[actor, criteria, result, actual_value, expected_value]])\n\n        # Global and final output message\n        list_statistics.extend([['', 'GLOBAL RESULT', self._result, '', '']])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\"\n        output += \" \" + \"=\" * end_line_length + \"\\n\"\n\n        return output\n\n    def _write_to_reportjson(self):\n        \"\"\"\n        Write a machine-readable report to JSON\n\n        The resulting report has the following format:\n        {\n            criteria: [\n                {\n                    name: \"CheckCollisions\",\n                    expected: \"0\",\n                    actual: \"2\",\n                    optional: false,\n                    success: false\n                }, ...\n            ]\n        }\n        \"\"\"\n        json_list = []\n\n        def result_dict(name, actor, optional, expected, actual, success):\n            \"\"\"\n            Convenience function to convert its arguments into a JSON-ready dict\n            :param name: Name of the test criterion\n            :param actor: Actor ID as string\n            :param optional: If the criterion is optional\n            :param expected: The expected value of the criterion (eg 0 for collisions)\n            :param actual: The actual value\n            :param success: If the test was passed\n            :return: A dict data structure that will be written to JSON\n            \"\"\"\n            return {\n                \"name\": name,\n                \"actor\": actor,\n                \"optional\": optional,\n                \"expected\": expected,\n                \"actual\": actual,\n                \"success\": success,\n            }\n\n        for criterion in self._data.scenario.get_criteria():\n            json_list.append(\n                result_dict(\n                    criterion.name,\n                    \"{}-{}\".format(criterion.actor.type_id[8:], criterion.actor.id),\n                    criterion.optional,\n                    criterion.success_value,\n                    criterion.actual_value,\n                    criterion.test_status in [\"SUCCESS\", \"ACCEPTABLE\"]\n                )\n            )\n\n        # add one entry for duration\n        timeout = self._data.scenario.timeout\n        duration = self._data.scenario_duration_game\n        json_list.append(\n            result_dict(\n                \"Duration\", \"all\", False, timeout, duration, duration <= timeout\n            )\n        )\n\n        result_object = {\n            \"scenario\": self._data.scenario_tree.name,\n            \"success\": self._result in [\"SUCCESS\", \"ACCEPTABLE\"],\n            \"criteria\": json_list\n        }\n\n        with open(self._json, \"w\", encoding='utf-8') as fp:\n            json.dump(result_object, fp, indent=4)\n\n    def _write_to_junit(self):\n        \"\"\"\n        Writing to Junit XML\n        \"\"\"\n        test_count = 0\n        failure_count = 0\n        for criterion in self._data.scenario.get_criteria():\n            test_count += 1\n            if criterion.test_status != \"SUCCESS\":\n                failure_count += 1\n\n        # handle timeout\n        test_count += 1\n        if self._data.scenario_duration_game >= self._data.scenario.timeout:\n            failure_count += 1\n\n        with open(self._junit, \"w\", encoding='utf-8') as junit_file:\n\n            junit_file.write(\"<?xml version=\\\"1.0\\\" encoding=\\\"UTF-8\\\"?>\\n\")\n\n            test_suites_string = (\"<testsuites tests=\\\"%d\\\" failures=\\\"%d\\\" disabled=\\\"0\\\" \"\n                                  \"errors=\\\"0\\\" timestamp=\\\"%s\\\" time=\\\"%5.2f\\\" \"\n                                  \"name=\\\"Simulation\\\" package=\\\"Scenarios\\\">\\n\" %\n                                  (test_count,\n                                   failure_count,\n                                   self._start_time,\n                                   self._data.scenario_duration_system))\n            junit_file.write(test_suites_string)\n\n            test_suite_string = (\"  <testsuite name=\\\"%s\\\" tests=\\\"%d\\\" failures=\\\"%d\\\" \"\n                                 \"disabled=\\\"0\\\" errors=\\\"0\\\" time=\\\"%5.2f\\\">\\n\" %\n                                 (self._data.scenario_tree.name,\n                                  test_count,\n                                  failure_count,\n                                  self._data.scenario_duration_system))\n            junit_file.write(test_suite_string)\n\n            for criterion in self._data.scenario.get_criteria():\n                testcase_name = criterion.name + \"_\" + \\\n                    criterion.actor.type_id[8:] + \"_\" + str(criterion.actor.id)\n                result_string = (\"    <testcase name=\\\"{}\\\" status=\\\"run\\\" \"\n                                 \"time=\\\"0\\\" classname=\\\"Scenarios.{}\\\">\\n\".format(\n                                     testcase_name, self._data.scenario_tree.name))\n                if criterion.test_status != \"SUCCESS\":\n                    result_string += \"      <failure message=\\\"{}\\\"  type=\\\"\\\"><![CDATA[\\n\".format(\n                        criterion.name)\n                    result_string += \"  Actual:   {}\\n\".format(\n                        criterion.actual_value)\n                    result_string += \"  Expected: {}\\n\".format(\n                        criterion.success_value)\n                    result_string += \"\\n\"\n                    result_string += \"  Exact Value: {} = {}]]></failure>\\n\".format(\n                        criterion.name, criterion.actual_value)\n                else:\n                    result_string += \"  Exact Value: {} = {}\\n\".format(\n                        criterion.name, criterion.actual_value)\n                result_string += \"    </testcase>\\n\"\n                junit_file.write(result_string)\n\n            # Handle timeout separately\n            result_string = (\"    <testcase name=\\\"Duration\\\" status=\\\"run\\\" time=\\\"{}\\\" \"\n                             \"classname=\\\"Scenarios.{}\\\">\\n\".format(\n                                 self._data.scenario_duration_system,\n                                 self._data.scenario_tree.name))\n            if self._data.scenario_duration_game >= self._data.scenario.timeout:\n                result_string += \"      <failure message=\\\"{}\\\"  type=\\\"\\\"><![CDATA[\\n\".format(\n                    \"Duration\")\n                result_string += \"  Actual:   {}\\n\".format(\n                    self._data.scenario_duration_game)\n                result_string += \"  Expected: {}\\n\".format(\n                    self._data.scenario.timeout)\n                result_string += \"\\n\"\n                result_string += \"  Exact Value: {} = {}]]></failure>\\n\".format(\n                    \"Duration\", self._data.scenario_duration_game)\n            else:\n                result_string += \"  Exact Value: {} = {}\\n\".format(\n                    \"Duration\", self._data.scenario_duration_game)\n            result_string += \"    </testcase>\\n\"\n            junit_file.write(result_string)\n\n            junit_file.write(\"  </testsuite>\\n\")\n            junit_file.write(\"</testsuites>\\n\")\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/scenario_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the ScenarioManager implementation.\nIt must not be modified and is for reference only!\n\"\"\"\n\nfrom __future__ import print_function\nimport sys\nimport time\n\nimport py_trees\n\nfrom srunner.autoagents.agent_wrapper import AgentWrapper\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.result_writer import ResultOutputProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.watchdog import Watchdog\n\n\nclass ScenarioManager(object):\n\n    \"\"\"\n    Basic scenario manager class. This class holds all functionality\n    required to start, and analyze a scenario.\n\n    The user must not modify this class.\n\n    To use the ScenarioManager:\n    1. Create an object via manager = ScenarioManager()\n    2. Load a scenario via manager.load_scenario()\n    3. Trigger the execution of the scenario manager.run_scenario()\n       This function is designed to explicitly control start and end of\n       the scenario execution\n    4. Trigger a result evaluation with manager.analyze_scenario()\n    5. If needed, cleanup with manager.stop_scenario()\n    \"\"\"\n\n    def __init__(self, debug_mode=False, sync_mode=False, timeout=2.0):\n        \"\"\"\n        Setups up the parameters, which will be filled at load_scenario()\n\n        \"\"\"\n        self.scenario = None\n        self.scenario_tree = None\n        self.ego_vehicles = None\n        self.other_actors = None\n\n        self._debug_mode = debug_mode\n        self._agent = None\n        self._sync_mode = sync_mode\n        self._watchdog = None\n        self._timeout = timeout\n\n        self._running = False\n        self._timestamp_last_run = 0.0\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = None\n        self.end_system_time = None\n\n    def _reset(self):\n        \"\"\"\n        Reset all parameters\n        \"\"\"\n        self._running = False\n        self._timestamp_last_run = 0.0\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = None\n        self.end_system_time = None\n        GameTime.restart()\n\n    def cleanup(self):\n        \"\"\"\n        This function triggers a proper termination of a scenario\n        \"\"\"\n\n        if self._watchdog is not None:\n            self._watchdog.stop()\n            self._watchdog = None\n\n        if self.scenario is not None:\n            self.scenario.terminate()\n\n        if self._agent is not None:\n            self._agent.cleanup()\n            self._agent = None\n\n        CarlaDataProvider.cleanup()\n\n    def load_scenario(self, scenario, agent=None):\n        \"\"\"\n        Load a new scenario\n        \"\"\"\n        self._reset()\n        self._agent = AgentWrapper(agent) if agent else None\n        if self._agent is not None:\n            self._sync_mode = True\n        self.scenario = scenario\n        self.scenario_tree = self.scenario.scenario_tree\n        self.ego_vehicles = scenario.ego_vehicles\n        self.other_actors = scenario.other_actors\n\n        # To print the scenario tree uncomment the next line\n        # py_trees.display.render_dot_tree(self.scenario_tree)\n\n        if self._agent is not None:\n            self._agent.setup_sensors(self.ego_vehicles[0], self._debug_mode)\n\n    def run_scenario(self):\n        \"\"\"\n        Trigger the start of the scenario and wait for it to finish/fail\n        \"\"\"\n        print(\"ScenarioManager: Running scenario {}\".format(self.scenario_tree.name))\n        self.start_system_time = time.time()\n        start_game_time = GameTime.get_time()\n\n        self._watchdog = Watchdog(float(self._timeout))\n        self._watchdog.start()\n        self._running = True\n\n        while self._running:\n            timestamp = None\n            world = CarlaDataProvider.get_world()\n            if world:\n                snapshot = world.get_snapshot()\n                if snapshot:\n                    timestamp = snapshot.timestamp\n            if timestamp:\n                self._tick_scenario(timestamp)\n\n        self.cleanup()\n\n        self.end_system_time = time.time()\n        end_game_time = GameTime.get_time()\n\n        self.scenario_duration_system = self.end_system_time - \\\n            self.start_system_time\n        self.scenario_duration_game = end_game_time - start_game_time\n\n        if self.scenario_tree.status == py_trees.common.Status.FAILURE:\n            print(\"ScenarioManager: Terminated due to failure\")\n\n    def _tick_scenario(self, timestamp):\n        \"\"\"\n        Run next tick of scenario and the agent.\n        If running synchornously, it also handles the ticking of the world.\n        \"\"\"\n\n        if self._timestamp_last_run < timestamp.elapsed_seconds and self._running:\n            self._timestamp_last_run = timestamp.elapsed_seconds\n\n            self._watchdog.update()\n\n            if self._debug_mode:\n                print(\"\\n--------- Tick ---------\\n\")\n\n            # Update game time and actor information\n            GameTime.on_carla_tick(timestamp)\n            CarlaDataProvider.on_carla_tick()\n\n            if self._agent is not None:\n                ego_action = self._agent()  # pylint: disable=not-callable\n\n            if self._agent is not None:\n                self.ego_vehicles[0].apply_control(ego_action)\n\n            # Tick scenario\n            self.scenario_tree.tick_once()\n\n            if self._debug_mode:\n                print(\"\\n\")\n                py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True)\n                sys.stdout.flush()\n\n            if self.scenario_tree.status != py_trees.common.Status.RUNNING:\n                self._running = False\n\n        if self._sync_mode and self._running and self._watchdog.get_status():\n            CarlaDataProvider.get_world().tick()\n\n    def get_running_status(self):\n        \"\"\"\n        returns:\n           bool:  False if watchdog exception occured, True otherwise\n        \"\"\"\n        return self._watchdog.get_status()\n\n    def stop_scenario(self):\n        \"\"\"\n        This function is used by the overall signal handler to terminate the scenario execution\n        \"\"\"\n        self._running = False\n\n    def analyze_scenario(self, stdout, filename, junit, json):\n        \"\"\"\n        This function is intended to be called from outside and provide\n        the final statistics about the scenario (human-readable, in form of a junit\n        report, etc.)\n        \"\"\"\n\n        failure = False\n        timeout = False\n        result = \"SUCCESS\"\n\n        criteria = self.scenario.get_criteria()\n        if len(criteria) == 0:\n            print(\"Nothing to analyze, this scenario has no criteria\")\n            return True\n\n        for criterion in criteria:\n            if (not criterion.optional and\n                    criterion.test_status != \"SUCCESS\" and\n                    criterion.test_status != \"ACCEPTABLE\"):\n                failure = True\n                result = \"FAILURE\"\n            elif criterion.test_status == \"ACCEPTABLE\":\n                result = \"ACCEPTABLE\"\n\n        if self.scenario.timeout_node.timeout and not failure:\n            timeout = True\n            result = \"TIMEOUT\"\n\n        output = ResultOutputProvider(self, result, stdout, filename, junit, json)\n        output.write()\n\n        return failure or timeout\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all atomic scenario behaviors required to realize\ncomplex, realistic scenarios such as \"follow a leading vehicle\", \"lane change\",\netc.\n\nThe atomic behaviors are implemented with py_trees.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport copy\nimport math\nimport operator\nimport os\nimport time\nimport subprocess\n\nimport numpy as np\nfrom numpy import random\nimport py_trees\nfrom py_trees.blackboard import Blackboard\nimport networkx\n\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\nfrom agents.navigation.constant_velocity_agent import ConstantVelocityAgent\nfrom agents.navigation.local_planner import RoadOption, LocalPlanner\nfrom agents.tools.misc import is_within_distance, get_speed\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.actorcontrols.actor_control import ActorControl\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.tools.scenario_helper import detect_lane_obstacle\nfrom srunner.tools.scenario_helper import generate_target_waypoint_list_multilane\n\n\nimport srunner.tools as sr_tools\n\nEPSILON = 0.001\n\n\ndef calculate_distance(location, other_location, global_planner=None):\n    \"\"\"\n    Method to calculate the distance between to locations\n\n    Note: It uses the direct distance between the current location and the\n          target location to estimate the time to arrival.\n          To be accurate, it would have to use the distance along the\n          (shortest) route between the two locations.\n    \"\"\"\n    if global_planner:\n        distance = 0\n\n        # Get the route\n        route = global_planner.trace_route(location, other_location)\n\n        # Get the distance of the route\n        for i in range(1, len(route)):\n            curr_loc = route[i][0].transform.location\n            prev_loc = route[i - 1][0].transform.location\n\n            distance += curr_loc.distance(prev_loc)\n\n        return distance\n\n    return location.distance(other_location)\n\n\ndef get_actor_control(actor):\n    \"\"\"\n    Method to return the type of control to the actor.\n    \"\"\"\n    control = actor.get_control()\n    actor_type = actor.type_id.split('.')[0]\n    if not isinstance(actor, carla.Walker):\n        control.steering = 0\n    else:\n        control.speed = 0\n\n    return control, actor_type\n\n\nclass AtomicBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Base class for all atomic behaviors used to setup a scenario\n\n    *All behaviors should use this class as parent*\n\n    Important parameters:\n    - name: Name of the atomic behavior\n    \"\"\"\n\n    def __init__(self, name, actor=None):\n        \"\"\"\n        Default init. Has to be called via super from derived class\n        \"\"\"\n        super(AtomicBehavior, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self.name = name\n        self._actor = actor\n\n    def setup(self, unused_timeout=15):\n        \"\"\"\n        Default setup\n        \"\"\"\n        self.logger.debug(\"%s.setup()\" % (self.__class__.__name__))\n        return True\n\n    def initialise(self):\n        \"\"\"\n        Initialise setup terminates WaypointFollowers\n        Check whether WF for this actor is running and terminate all active WFs\n        \"\"\"\n        if self._actor is not None:\n            try:\n                check_attr = operator.attrgetter(\"running_WF_actor_{}\".format(self._actor.id))\n                terminate_wf = copy.copy(check_attr(py_trees.blackboard.Blackboard()))\n                py_trees.blackboard.Blackboard().set(\n                    \"terminate_WF_actor_{}\".format(self._actor.id), terminate_wf, overwrite=True)\n            except AttributeError:\n                # It is ok to continue, if the Blackboard variable does not exist\n                pass\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        self.logger.debug(\"%s.terminate()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n\nclass RunScript(AtomicBehavior):\n\n    \"\"\"\n    This is an atomic behavior to start execution of an additional script.\n\n    Args:\n        script (str): String containing the interpreter, scriptpath and arguments\n            Example: \"python /path/to/script.py --arg1\"\n        base_path (str): String containing the base path of for the script\n\n    Attributes:\n        _script (str): String containing the interpreter, scriptpath and arguments\n            Example: \"python /path/to/script.py --arg1\"\n        _base_path (str): String containing the base path of for the script\n            Example: \"/path/to/\"\n\n    Note:\n        This is intended for the use with OpenSCENARIO. Be aware of security side effects.\n    \"\"\"\n\n    def __init__(self, script, base_path=None, name=\"RunScript\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(RunScript, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._script = script\n        self._base_path = base_path\n\n    def update(self):\n        \"\"\"\n        Start script\n        \"\"\"\n        path = None\n        script_components = self._script.split(' ')\n        if len(script_components) > 1:\n            path = script_components[1]\n\n        if not os.path.isfile(path):\n            path = os.path.join(self._base_path, path)\n        if not os.path.isfile(path):\n            new_status = py_trees.common.Status.FAILURE\n            print(\"Script file does not exists {}\".format(path))\n        else:\n            subprocess.Popen(self._script, shell=True, cwd=self._base_path)  # pylint: disable=consider-using-with\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass ChangeParameter(AtomicBehavior):\n    \"\"\"\n    This is an atomic behavior to change the osc parameter value.\n\n    Args:\n        parameter_ref (str): parameter name\n        value (any): ParameterRef or number\n    \"\"\"\n\n    def __init__(self, parameter_ref, value, rule=None, name=\"ChangeParameter\"):\n        super(ChangeParameter, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % self.__class__.__name__)\n        self._parameter_ref = parameter_ref\n        self._rule = rule\n        self._value = value\n\n    def update(self):\n        \"\"\"\n        update value of global osc parameter.\n        \"\"\"\n        old_value = CarlaDataProvider.get_osc_global_param_value(self._parameter_ref)\n\n        if self._rule == '+':\n            new_value = self._value + float(old_value)\n        elif self._rule == '*':\n            new_value = self._value * float(old_value)\n        else:\n            new_value = self._value\n\n        CarlaDataProvider.update_osc_global_params({self._parameter_ref: new_value})\n        new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass ChangeWeather(AtomicBehavior):\n\n    \"\"\"\n    Atomic to write a new weather configuration into the blackboard.\n    Used in combination with OSCWeatherBehavior() to have a continuous weather simulation.\n\n    The behavior immediately terminates with SUCCESS after updating the blackboard.\n\n    Args:\n        weather (srunner.scenariomanager.weather_sim.Weather): New weather settings.\n        name (string): Name of the behavior.\n            Defaults to 'UpdateWeather'.\n\n    Attributes:\n        _weather (srunner.scenariomanager.weather_sim.Weather): Weather settings.\n    \"\"\"\n\n    def __init__(self, weather, name=\"ChangeWeather\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeWeather, self).__init__(name)\n        self._weather = weather\n\n    def update(self):\n        \"\"\"\n        Write weather into blackboard and exit with success\n\n        returns:\n            py_trees.common.Status.SUCCESS\n        \"\"\"\n        py_trees.blackboard.Blackboard().set(\"CarlaWeather\", self._weather, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeRoadFriction(AtomicBehavior):\n\n    \"\"\"\n    Atomic to update the road friction in CARLA.\n\n    The behavior immediately terminates with SUCCESS after updating the friction.\n\n    Args:\n        friction (float): New friction coefficient.\n        name (string): Name of the behavior.\n            Defaults to 'UpdateRoadFriction'.\n\n    Attributes:\n        _friction (float): Friction coefficient.\n    \"\"\"\n\n    def __init__(self, friction, name=\"ChangeRoadFriction\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeRoadFriction, self).__init__(name)\n        self._friction = friction\n\n    def update(self):\n        \"\"\"\n        Update road friction. Spawns new friction blueprint and removes the old one, if existing.\n\n        returns:\n            py_trees.common.Status.SUCCESS\n        \"\"\"\n\n        for actor in CarlaDataProvider.get_all_actors().filter('static.trigger.friction'):\n            actor.destroy()\n\n        friction_bp = CarlaDataProvider.get_world().get_blueprint_library().find('static.trigger.friction')\n        extent = carla.Location(1000000.0, 1000000.0, 1000000.0)\n        friction_bp.set_attribute('friction', str(self._friction))\n        friction_bp.set_attribute('extent_x', str(extent.x))\n        friction_bp.set_attribute('extent_y', str(extent.y))\n        friction_bp.set_attribute('extent_z', str(extent.z))\n\n        # Spawn Trigger Friction\n        transform = carla.Transform()\n        transform.location = carla.Location(-10000.0, -10000.0, 0.0)\n        CarlaDataProvider.get_world().spawn_actor(friction_bp, transform)\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeActorControl(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the longitudinal/lateral control logic for an actor.\n    The (actor, controller) pair is stored inside the Blackboard.\n\n    The behavior immediately terminates with SUCCESS after the controller.\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the controller.\n        control_py_module (string): Name of the python module containing the implementation\n            of the controller.\n        args (dictionary): Additional arguments for the controller.\n        scenario_file_path (string): Additional path to controller implementation.\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorControl'.\n\n    Attributes:\n        _actor_control (ActorControl): Instance of the actor control.\n    \"\"\"\n\n    def __init__(self, actor, control_py_module, args, scenario_file_path=None, name=\"ChangeActorControl\"):\n        \"\"\"\n        Setup actor controller.\n        \"\"\"\n        super(ChangeActorControl, self).__init__(name, actor)\n\n        self._actor_control = ActorControl(actor, control_py_module=control_py_module,\n                                           args=args, scenario_file_path=scenario_file_path)\n\n    def update(self):\n        \"\"\"\n        Write (actor, controler) pair to Blackboard, or update the controller\n        if actor already exists as a key.\n\n        returns:\n            py_trees.common.Status.SUCCESS\n        \"\"\"\n\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if actor_dict:\n            if self._actor.id in actor_dict:\n                actor_dict[self._actor.id].reset()\n\n        actor_dict[self._actor.id] = self._actor_control\n        py_trees.blackboard.Blackboard().set(\"ActorsWithController\", actor_dict, overwrite=True)\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass UpdateAllActorControls(AtomicBehavior):\n\n    \"\"\"\n    Atomic to update (run one control loop step) all actor controls.\n\n    The behavior is always in RUNNING state.\n\n    Args:\n        name (string): Name of the behavior.\n            Defaults to 'UpdateAllActorControls'.\n    \"\"\"\n\n    def __init__(self, name=\"UpdateAllActorControls\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        super(UpdateAllActorControls, self).__init__(name)\n\n    def update(self):\n        \"\"\"\n        Execute one control loop step for all actor controls.\n\n        returns:\n            py_trees.common.Status.RUNNING\n        \"\"\"\n\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        for actor_id in actor_dict:\n            actor_dict[actor_id].run_step()\n\n        return py_trees.common.Status.RUNNING\n\n\nclass ChangeActorTargetSpeed(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the target speed for an actor controller.\n\n    The behavior is in RUNNING state until the distance/duration\n    conditions are satisfied, or if a second ChangeActorTargetSpeed atomic\n    for the same actor is triggered.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        target_speed (float): New target speed [m/s].\n        init_speed (boolean): Flag to indicate if the speed is the initial actor speed.\n            Defaults to False.\n        duration (float): Duration of the maneuver [s].\n            Defaults to None.\n        distance (float): Distance of the maneuver [m].\n            Defaults to None.\n        relative_actor (carla.Actor): If the target speed setting should be relative to another actor.\n            Defaults to None.\n        value (float): Offset, if the target speed setting should be relative to another actor.\n            Defaults to None.\n        value_type (string): Either 'Delta' or 'Factor' influencing how the offset to the reference actors\n            velocity is applied. Defaults to None.\n        continuous (boolean): If True, the atomic remains in RUNNING, independent of duration or distance.\n            Defaults to False.\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorTargetSpeed'.\n\n    Attributes:\n        _target_speed (float): New target speed [m/s].\n        _init_speed (boolean): Flag to indicate if the speed is the initial actor speed.\n            Defaults to False.\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n        _start_location (carla.Location): Start location of the atomic.\n            Defaults to None.\n        _duration (float): Duration of the maneuver [s].\n            Defaults to None.\n        _distance (float): Distance of the maneuver [m].\n            Defaults to None.\n        _relative_actor (carla.Actor): If the target speed setting should be relative to another actor.\n            Defaults to None.\n        _value (float): Offset, if the target speed setting should be relative to another actor.\n            Defaults to None.\n        _value_type (string): Either 'Delta' or 'Factor' influencing how the offset to the reference actors\n            velocity is applied. Defaults to None.\n        _continuous (boolean): If True, the atomic remains in RUNNING, independent of duration or distance.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self, actor, target_speed, init_speed=False,\n                 duration=None, distance=None, relative_actor=None,\n                 value=None, value_type=None, continuous=False, name=\"ChangeActorTargetSpeed\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorTargetSpeed, self).__init__(name, actor)\n\n        self._target_speed = target_speed\n        self._init_speed = init_speed\n\n        self._start_time = None\n        self._start_location = None\n\n        self._relative_actor = relative_actor\n        self._value = value\n        self._value_type = value_type\n        self._continuous = continuous\n        self._duration = duration\n        self._distance = distance\n\n    def initialise(self):\n        \"\"\"\n        Set initial parameters such as _start_time and _start_location,\n        and get (actor, controller) pair from Blackboard.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n        self._start_location = CarlaDataProvider.get_location(self._actor)\n\n        if self._relative_actor:\n            relative_velocity = CarlaDataProvider.get_velocity(self._relative_actor)\n\n            # get target velocity\n            if self._value_type == 'delta':\n                self._target_speed = relative_velocity + self._value\n            elif self._value_type == 'factor':\n                self._target_speed = relative_velocity * self._value\n            else:\n                print('self._value_type must be delta or factor')\n\n        actor_dict[self._actor.id].update_target_speed(self._target_speed, start_time=self._start_time)\n\n        if self._init_speed:\n            actor_dict[self._actor.id].set_init_speed()\n\n        super(ChangeActorTargetSpeed, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's current state and update target speed, if it is relative to another actor.\n\n        returns:\n            py_trees.common.Status.SUCCESS, if the duration or distance driven exceeded limits\n                                            if another ChangeActorTargetSpeed atomic for the same actor was triggered.\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.FAILURE, else.\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._relative_actor:\n            relative_velocity = CarlaDataProvider.get_velocity(self._relative_actor)\n\n            # get target velocity\n            if self._value_type == 'delta':\n                actor_dict[self._actor.id].update_target_speed(relative_velocity + self._value)\n            elif self._value_type == 'factor':\n                actor_dict[self._actor.id].update_target_speed(relative_velocity * self._value)\n            else:\n                print('self._value_type must be delta or factor')\n\n        # check duration and driven_distance\n        if not self._continuous:\n            if (self._duration is not None) and (GameTime.get_time() - self._start_time > self._duration):\n                new_status = py_trees.common.Status.SUCCESS\n\n            driven_distance = CarlaDataProvider.get_location(self._actor).distance(self._start_location)\n            if (self._distance is not None) and (driven_distance > self._distance):\n                new_status = py_trees.common.Status.SUCCESS\n\n        if self._distance is None and self._duration is None:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass SyncArrivalOSC(AtomicBehavior):\n\n    \"\"\"\n    Atomic to make two actors arrive at their corresponding places at the same time\n\n    The behavior is in RUNNING state until the \"main\" actor has rezached its destination\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        master_actor (carla.Actor): Reference actor to sync up to.\n        actor_target (carla.Transform): Endpoint of the actor after the behavior finishes.\n        master_target (carla.Transform): Endpoint of the master_actor after the behavior finishes.\n        final_speed (float): Speed of the actor after the behavior ends.\n        relative_to_master (boolean): Whether or not the final speed is relative to master_actor.\n            Defaults to False.\n        relative_type (string): Type of relative speed. Either 'delta' or 'factor'.\n            Defaults to ''.\n        name (string): Name of the behavior.\n            Defaults to 'SyncArrivalOSC'.\n    \"\"\"\n\n    DISTANCE_THRESHOLD = 1\n\n    def __init__(self, actor, master_actor, actor_target, master_target, final_speed,\n                 relative_to_master=False, relative_type='', name=\"SyncArrivalOSC\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super(SyncArrivalOSC, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._actor = actor\n        self._actor_target = actor_target\n        self._master_actor = master_actor\n        self._master_target = master_target\n\n        self._final_speed = final_speed\n        self._final_speed_set = False\n        self._relative_to_master = relative_to_master\n        self._relative_type = relative_type\n\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set initial parameters and get (actor, controller) pair from Blackboard.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        # Get the distance of the actor to its endpoint\n        distance = calculate_distance(\n            CarlaDataProvider.get_location(self._actor), self._actor_target.location)\n\n        # Get the time to arrival of the reference to its endpoint\n        distance_reference = calculate_distance(\n            CarlaDataProvider.get_location(self._master_actor), self._master_target.location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._master_actor)\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n        else:\n            time_reference = float('inf')\n\n        # Get the required velocity of the actor\n        desired_velocity = distance / time_reference\n        actor_dict[self._actor.id].update_target_speed(desired_velocity, start_time=self._start_time)\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity to ensure that both actors reach their target\n        positions at the same time.\n        \"\"\"\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        # Get the distance of the actor to its endpoint\n        distance = calculate_distance(\n            CarlaDataProvider.get_location(self._actor), self._actor_target.location)\n\n        if distance < self.DISTANCE_THRESHOLD:\n            return py_trees.common.Status.SUCCESS  # Behaviour ends when the actor reaches its endpoint\n\n        # Get the time to arrival of the reference to its endpoint\n        distance_reference = calculate_distance(\n            CarlaDataProvider.get_location(self._master_actor), self._master_target.location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._master_actor)\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n        else:\n            time_reference = float('inf')\n\n        # Get the required velocity of the actor\n        desired_velocity = distance / time_reference\n        actor_dict[self._actor.id].update_target_speed(desired_velocity)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, set the target speed to its desired one.\n        This function is called several times, so the use of self._final_speed_set\n        is needed to avoid interfering with other running behaviors\n        \"\"\"\n        if not self._final_speed_set:\n            try:\n                check_actors = operator.attrgetter(\"ActorsWithController\")\n                actor_dict = check_actors(py_trees.blackboard.Blackboard())\n            except AttributeError:\n                pass\n\n            if actor_dict and self._actor.id in actor_dict:\n\n                if self._relative_to_master:\n                    master_speed = CarlaDataProvider.get_velocity(self._master_actor)\n                    if self._relative_type == 'delta':\n                        final_speed = master_speed + self._final_speed\n                    elif self._relative_type == 'factor':\n                        final_speed = master_speed * self._final_speed\n                    else:\n                        print(\"'relative_type' must be delta or factor\")\n                else:\n                    final_speed = self._final_speed\n\n                actor_dict[self._actor.id].update_target_speed(final_speed)\n\n            self._final_speed_set = True\n\n        super(SyncArrivalOSC, self).terminate(new_status)\n\n\nclass ChangeActorWaypoints(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the waypoints for an actor controller.\n\n    The behavior is in RUNNING state until the last waypoint is reached, or if a\n    second waypoint related atomic for the same actor is triggered. These are:\n    - ChangeActorWaypoints\n    - ChangeActorLateralMotion\n    - ChangeActorLaneOffset\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        waypoints (List of (OSC position, OSC route option)): List of (Position, Route Option) as OpenScenario elements.\n            position will be converted to Carla transforms, considering the corresponding\n            route option (e.g. shortest, fastest)\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorWaypoints'.\n\n    Attributes:\n        _waypoints (List of (OSC position, OSC route option)): List of (Position, Route Option) as OpenScenario elements\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n\n    '''Note: When using routing options such as fastest or shortest, it is advisable to run\n             in synchronous mode\n    \"\"\"\n\n    def __init__(self, actor, waypoints, name=\"ChangeActorWaypoints\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorWaypoints, self).__init__(name, actor)\n\n        self._waypoints = waypoints\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set _start_time and get (actor, controller) pair from Blackboard.\n\n        Set waypoint list for actor controller.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        # Transforming OSC waypoints to Carla waypoints\n        carla_route_elements = []\n        for (osc_point, routing_option) in self._waypoints:\n            carla_transforms = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n                osc_point)\n            carla_route_elements.append((carla_transforms, routing_option))\n\n        # Obtain final route, considering the routing option\n        # At the moment everything besides \"shortest\" will use the CARLA GlobalPlanner\n        grp = CarlaDataProvider.get_global_route_planner()\n        route = []\n        for i, _ in enumerate(carla_route_elements):\n            if carla_route_elements[i][1] == \"shortest\":\n                route.append(carla_route_elements[i][0])\n            else:\n                if i == 0:\n                    mmap = CarlaDataProvider.get_map()\n                    ego_location = CarlaDataProvider.get_location(self._actor)\n                    ego_waypoint = mmap.get_waypoint(ego_location)\n                    try:\n                        ego_next_wp = ego_waypoint.next(1)[0]\n                    except IndexError:\n                        ego_next_wp = ego_waypoint\n                    waypoint = ego_next_wp.transform.location\n                else:\n                    waypoint = carla_route_elements[i - 1][0].location\n                waypoint_next = carla_route_elements[i][0].location\n                try:\n                    interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n                except networkx.NetworkXNoPath:\n                    print(\"WARNING: No route from {} to {} - Using direct path instead\".format(waypoint, waypoint_next))\n                    route.append(carla_route_elements[i][0])\n                    continue\n                for wp_tuple in interpolated_trace:\n                    # The router sometimes produces points that go backward, or are almost identical\n                    # We have to filter these, to avoid problems\n                    if route and wp_tuple[0].transform.location.distance(route[-1].location) > 1.0:\n                        new_heading_vec = wp_tuple[0].transform.location - route[-1].location\n                        new_heading = np.arctan2(new_heading_vec.y, new_heading_vec.x)\n                        if len(route) > 1:\n                            last_heading_vec = route[-1].location - route[-2].location\n                        else:\n                            last_heading_vec = route[-1].location - ego_next_wp.transform.location\n                        last_heading = np.arctan2(last_heading_vec.y, last_heading_vec.x)\n\n                        heading_delta = math.fabs(new_heading - last_heading)\n                        if math.fabs(heading_delta) < 0.5 or math.fabs(heading_delta) > 5.5:\n                            route.append(wp_tuple[0].transform)\n                    elif not route:\n                        route.append(wp_tuple[0].transform)\n\n        actor_dict[self._actor.id].update_waypoints(route, start_time=self._start_time)\n\n        super(ChangeActorWaypoints, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's state along the waypoint route.\n\n        returns:\n            py_trees.common.Status.SUCCESS, if the final waypoint was reached, or\n                                            if another ChangeActorWaypoints atomic for the same actor was triggered.\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.FAILURE, else.\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if actor_dict[self._actor.id].check_reached_waypoint_goal():\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass ChangeActorLateralMotion(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the waypoints for an actor controller.\n\n    The behavior is in RUNNING state until the last waypoint is reached, or if a\n    second waypoint related atomic for the same actor is triggered. These are:\n    - ChangeActorWaypoints\n    - ChangeActorLateralMotion\n    - ChangeActorLaneOffset\n\n    If an impossible lane change is asked for (due to the lack of lateral lanes,\n    next waypoints, continuous line, etc) the atomic will return a plan with the\n    waypoints until such impossibility is found.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        direction (string): Lane change direction ('left' or 'right').\n            Defaults to 'left'.\n        distance_lane_change (float): Distance of the lance change [meters].\n            Defaults to 25.\n        distance_other_lane (float): Driven distance after the lange change [meters].\n            Defaults to 100.\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorLateralMotion'.\n\n    Attributes:\n        _waypoints (List of carla.Transform): List of waypoints representing the lane change (CARLA transforms).\n        _direction (string): Lane change direction ('left' or 'right').\n        _distance_same_lane (float): Distance on the same lane before the lane change starts [meters]\n            Constant to 5.\n        _distance_other_lane (float): Max. distance on the target lane after the lance change [meters]\n            Constant to 100.\n        _distance_lane_change (float): Max. total distance of the lane change [meters].\n        _pos_before_lane_change: carla.Location of the actor before the lane change.\n            Defaults to None.\n        _target_lane_id (int): Id of the target lane\n            Defaults to None.\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, actor, direction='left', distance_lane_change=25, distance_other_lane=100,\n                 lane_changes=1, name=\"ChangeActorLateralMotion\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorLateralMotion, self).__init__(name, actor)\n\n        self._waypoints = []\n        self._direction = direction\n        self._distance_same_lane = 5\n        self._distance_other_lane = distance_other_lane\n        self._distance_lane_change = distance_lane_change\n        self._lane_changes = lane_changes\n        self._pos_before_lane_change = None\n        self._target_lane_id = None\n        self._plan = None\n\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set _start_time and get (actor, controller) pair from Blackboard.\n\n        Generate a waypoint list (route) which representes the lane change. Set\n        this waypoint list for the actor controller.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        # get start position\n        position_actor = CarlaDataProvider.get_map().get_waypoint(CarlaDataProvider.get_location(self._actor))\n\n        # calculate plan with scenario_helper function\n        self._plan, self._target_lane_id = generate_target_waypoint_list_multilane(\n            position_actor, self._direction, self._distance_same_lane,\n            self._distance_other_lane, self._distance_lane_change, check=False, lane_changes=self._lane_changes)\n\n        if self._plan:\n            for elem in self._plan:\n                self._waypoints.append(elem[0].transform)\n\n        actor_dict[self._actor.id].update_waypoints(self._waypoints, start_time=self._start_time)\n\n        super(ChangeActorLateralMotion, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's current state and if the lane change was completed\n\n        returns:\n            py_trees.common.Status.SUCCESS, if lane change was successful, or\n                                            if another ChangeActorLateralMotion atomic for the same actor was triggered.\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.FAILURE, else.\n        \"\"\"\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if not self._plan:\n            print(\"{} couldn't perform the expected lane change\".format(self._actor))\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location())\n        current_lane_id = current_position_actor.lane_id\n\n        if current_lane_id == self._target_lane_id:\n            # driving on new lane\n            distance = current_position_actor.transform.location.distance(self._pos_before_lane_change)\n\n            if distance > self._distance_other_lane:\n                # long enough distance on new lane --> SUCCESS\n                new_status = py_trees.common.Status.SUCCESS\n\n                new_waypoints = []\n                map_wp = current_position_actor\n                while len(new_waypoints) < 200:\n                    map_wps = map_wp.next(2.0)\n                    if map_wps:\n                        new_waypoints.append(map_wps[0].transform)\n                        map_wp = map_wps[0]\n                    else:\n                        break\n\n                actor_dict[self._actor.id].update_waypoints(new_waypoints, start_time=self._start_time)\n\n        else:\n            self._pos_before_lane_change = current_position_actor.transform.location\n\n        return new_status\n\n\nclass ChangeActorLaneOffset(AtomicBehavior):\n\n    \"\"\"\n    OpenSCENARIO atomic.\n    Atomic to change the offset of the controller.\n\n    The behavior is in RUNNING state until the offset os reached (if 'continuous' is set to False)\n    or forever (if 'continuous' is True). This behavior will automatically stop if a second waypoint\n    related atomic for the same actor is triggered. These are:\n    - ChangeActorWaypoints\n    - ChangeActorLateralMotion\n    - ChangeActorLaneOffset\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        offset (float): Float determined the distance to the center of the lane. Positive distance imply a\n            displacement to the right, while negative displacements are to the left.\n        relative_actor (carla.Actor): The actor from which the offset is taken from. Defaults to None\n        continuous (bool): If True, the behaviour never ends. If False, the behaviour ends when the lane\n            offset is reached. Defaults to True.\n\n    Attributes:\n        _offset (float): lane offset.\n        _relative_actor (carla.Actor): relative actor.\n        _continuous (bool): stored the value of the 'continuous' argument.\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n        _overwritten (bool): flag to check whether or not this behavior was overwritten by another. Helps\n            to avoid the missinteraction between two ChangeActorLaneOffsets.\n        _current_target_offset (float): stores the value of the offset when dealing with relative distances\n        _map (carla.Map): instance of the CARLA map.\n    \"\"\"\n\n    OFFSET_THRESHOLD = 0.1\n\n    def __init__(self, actor, offset, relative_actor=None, continuous=True, name=\"ChangeActorWaypoints\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorLaneOffset, self).__init__(name, actor)\n\n        self._offset = offset\n        self._relative_actor = relative_actor\n        self._continuous = continuous\n        self._start_time = None\n        self._current_target_offset = 0\n\n        self._overwritten = False\n        self._map = CarlaDataProvider.get_map()\n\n    def initialise(self):\n        \"\"\"\n        Set _start_time and get (actor, controller) pair from Blackboard.\n\n        Set offset for actor controller.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        actor_dict[self._actor.id].update_offset(self._offset, start_time=self._start_time)\n\n        super(ChangeActorLaneOffset, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's state along the waypoint route.\n\n        returns:\n            py_trees.common.Status.SUCCESS, if the lane offset was reached (and 'continuous' was False), or\n                                            if another waypoint atomic for the same actor was triggered\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.RUNNING, else.\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_lane_offset_command() != self._start_time:\n            # Differentiate between lane offset and other lateral commands\n            self._overwritten = True\n            return py_trees.common.Status.SUCCESS\n\n        if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        if self._relative_actor:\n            # Calculate new offset\n            relative_actor_loc = CarlaDataProvider.get_location(self._relative_actor)\n            relative_center_wp = self._map.get_waypoint(relative_actor_loc)\n\n            # Value\n            relative_center_loc = relative_center_wp.transform.location\n            relative_actor_offset = relative_actor_loc.distance(relative_center_loc)\n\n            # Sign\n            f_vec = relative_center_wp.transform.get_forward_vector()\n            d_vec = relative_actor_loc - relative_center_loc\n            cross = f_vec.x * d_vec.y - f_vec.y * d_vec.x\n\n            if cross < 0:\n                relative_actor_offset *= -1.0\n\n            self._current_target_offset = relative_actor_offset + self._offset\n            # Set the new offset\n            actor_dict[self._actor.id].update_offset(self._current_target_offset)\n\n        if not self._continuous:\n            # Calculate new offset\n            actor_loc = CarlaDataProvider.get_location(self._actor)\n            center_wp = self._map.get_waypoint(actor_loc)\n\n            # Value\n            center_loc = center_wp.transform.location\n            actor_offset = actor_loc.distance(center_loc)\n\n            # Sign\n            f_vec = center_wp.transform.get_forward_vector()\n            d_vec = actor_loc - center_loc\n            cross = f_vec.x * d_vec.y - f_vec.y * d_vec.x\n\n            if cross < 0:\n                actor_offset *= -1.0\n\n            # Check if the offset has been reached\n            if abs(actor_offset - self._current_target_offset) < self.OFFSET_THRESHOLD:\n                return py_trees.common.Status.SUCCESS\n\n        # TODO: As their is no way to check the distance to a specific lane, both checks will fail if the\n        # actors are outside its 'route lane' or at an intersection\n\n        new_status = py_trees.common.Status.RUNNING\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, the offset is set back to zero\n        \"\"\"\n\n        if not self._overwritten:\n            try:\n                check_actors = operator.attrgetter(\"ActorsWithController\")\n                actor_dict = check_actors(py_trees.blackboard.Blackboard())\n            except AttributeError:\n                pass\n\n            if actor_dict and self._actor.id in actor_dict:\n                actor_dict[self._actor.id].update_offset(0)\n\n            self._overwritten = True\n\n        super(ChangeActorLaneOffset, self).terminate(new_status)\n\n\nclass ActorTransformSetterToOSCPosition(AtomicBehavior):\n\n    \"\"\"\n    OpenSCENARIO atomic\n    This class contains an atomic behavior to set the transform of an OpenSCENARIO actor.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - osc_position: OpenSCENARIO position\n    - physics [optional]: If physics is true, the actor physics will be reactivated upon success\n\n    The behavior terminates when actor is set to the new actor transform (closer than 1 meter)\n\n    NOTE:\n    It is very important to ensure that the actor location is spawned to the new transform because of the\n    appearence of a rare runtime processing error. WaypointFollower with LocalPlanner,\n    might fail if new_status is set to success before the actor is really positioned at the new transform.\n    Therefore: calculate_distance(actor, transform) < 1 meter\n    \"\"\"\n\n    def __init__(self, actor, osc_position, physics=True, name=\"ActorTransformSetterToOSCPosition\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ActorTransformSetterToOSCPosition, self).__init__(name, actor)\n        self._osc_position = osc_position\n        self._physics = physics\n        self._osc_transform = None\n\n    def initialise(self):\n\n        super(ActorTransformSetterToOSCPosition, self).initialise()\n\n        if self._actor.is_alive:\n            self._actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n            self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0))\n\n    def update(self):\n        \"\"\"\n        Transform actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # calculate transform with method in openscenario_parser.py\n        self._osc_transform = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n            self._osc_position)\n        self._actor.set_transform(self._osc_transform)\n\n        if not self._actor.is_alive:\n            new_status = py_trees.common.Status.FAILURE\n\n        if calculate_distance(self._actor.get_location(), self._osc_transform.location) < 1.0:\n            if self._physics:\n                self._actor.set_simulate_physics(enabled=True)\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass AccelerateToVelocity(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic acceleration behavior. The controlled\n    traffic participant will accelerate with _throttle_value_ until reaching\n    a given _target_velocity_\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - throttle_value: The amount of throttle used to accelerate in [0,1]\n    - target_velocity: The target velocity the actor should reach in m/s\n\n    The behavior will terminate, if the actor's velocity is at least target_velocity\n    \"\"\"\n\n    def __init__(self, actor, throttle_value, target_velocity, name=\"Acceleration\"):\n        \"\"\"\n        Setup parameters including acceleration value (via throttle_value)\n        and target velocity\n        \"\"\"\n        super(AccelerateToVelocity, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control, self._type = get_actor_control(actor)\n        self._throttle_value = throttle_value\n        self._target_velocity = target_velocity\n\n    def initialise(self):\n        # In case of walkers, we have to extract the current heading\n        if self._type == 'walker':\n            self._control.speed = self._target_velocity\n            self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector()\n\n        super(AccelerateToVelocity, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Set throttle to throttle_value, as long as velocity is < target_velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._type == 'vehicle':\n            if CarlaDataProvider.get_velocity(self._actor) < self._target_velocity:\n                self._control.throttle = self._throttle_value\n            else:\n                new_status = py_trees.common.Status.SUCCESS\n                self._control.throttle = 0\n\n        self._actor.apply_control(self._control)\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass AccelerateToCatchUp(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic acceleration behavior.\n    The car will accelerate until it is faster than another car, in order to catch up distance.\n    This behaviour is especially useful before a lane change (e.g. LaneChange atom).\n\n    Important parameters:\n    - actor: CARLA actor to execute the behaviour\n    - other_actor: Reference CARLA actor, actor you want to catch up to\n    - throttle_value: acceleration value between 0.0 and 1.0\n    - delta_velocity: speed up to the velocity of other actor plus delta_velocity\n    - trigger_distance: distance between the actors\n    - max_distance: driven distance to catch up has to be smaller than max_distance\n\n    The behaviour will terminate succesful, when the two actors are in trigger_distance.\n    If max_distance is driven by the actor before actors are in trigger_distance,\n    then the behaviour ends with a failure.\n    \"\"\"\n\n    def __init__(self, actor, other_actor, throttle_value=1, delta_velocity=10, trigger_distance=5,\n                 max_distance=500, name=\"AccelerateToCatchUp\"):\n        \"\"\"\n        Setup parameters\n        The target_speet is calculated on the fly.\n        \"\"\"\n        super(AccelerateToCatchUp, self).__init__(name, actor)\n\n        self._other_actor = other_actor\n        self._throttle_value = throttle_value\n        self._delta_velocity = delta_velocity  # 1m/s=3.6km/h\n        self._trigger_distance = trigger_distance\n        self._max_distance = max_distance\n\n        self._control, self._type = get_actor_control(actor)\n\n        self._initial_actor_pos = None\n\n    def initialise(self):\n\n        # get initial actor position\n        self._initial_actor_pos = CarlaDataProvider.get_location(self._actor)\n        super(AccelerateToCatchUp, self).initialise()\n\n    def update(self):\n\n        # get actor speed\n        actor_speed = CarlaDataProvider.get_velocity(self._actor)\n        target_speed = CarlaDataProvider.get_velocity(self._other_actor) + self._delta_velocity\n\n        # distance between actors\n        distance = CarlaDataProvider.get_location(self._actor).distance(\n            CarlaDataProvider.get_location(self._other_actor))\n\n        # driven distance of actor\n        driven_distance = CarlaDataProvider.get_location(self._actor).distance(self._initial_actor_pos)\n\n        if actor_speed < target_speed:\n            # set throttle to throttle_value to accelerate\n            self._control.throttle = self._throttle_value\n\n        if actor_speed >= target_speed:\n            # keep velocity until the actors are in trigger distance\n            self._control.throttle = 0\n\n        self._actor.apply_control(self._control)\n\n        # new status:\n        if distance <= self._trigger_distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        elif driven_distance > self._max_distance:\n            new_status = py_trees.common.Status.FAILURE\n        else:\n            new_status = py_trees.common.Status.RUNNING\n\n        return new_status\n\n\nclass KeepVelocity(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to keep the provided velocity.\n    The controlled traffic participant will accelerate as fast as possible\n    until reaching a given _target_velocity_, which is then maintained for\n    as long as this behavior is active.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_velocity: The target velocity the actor should reach\n    - forced_speed: Whether or not to forcefully set the actors speed. This will ony be active until a collision happens\n    - duration[optional]: Duration in seconds of this behavior\n    - distance[optional]: Maximum distance in meters covered by the actor during this behavior\n\n    A termination can be enforced by providing distance or duration values.\n    Alternatively, a parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, actor, target_velocity, force_speed=False,\n                 duration=float(\"inf\"), distance=float(\"inf\"), name=\"KeepVelocity\"):\n        \"\"\"\n        Setup parameters including acceleration value (via throttle_value)\n        and target velocity\n        \"\"\"\n        super(KeepVelocity, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._target_velocity = target_velocity\n\n        self._control, self._type = get_actor_control(actor)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._waypoint = self._map.get_waypoint(self._actor.get_location())\n\n        self._forced_speed = force_speed\n        self._duration = duration\n        self._target_distance = distance\n        self._distance = 0\n        self._start_time = 0\n        self._location = None\n\n    def initialise(self):\n        self._location = CarlaDataProvider.get_location(self._actor)\n        self._start_time = GameTime.get_time()\n\n        # In case of walkers, we have to extract the current heading\n        if self._type == 'walker':\n            self._control.speed = self._target_velocity\n            self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector()\n        elif self._type == 'vehicle':\n            self._control.hand_brake = False\n        self._actor.apply_control(self._control)\n\n        super(KeepVelocity, self).initialise()\n\n    def update(self):\n        \"\"\"\n        As long as the stop condition (duration or distance) is not violated, set a new vehicle control\n        For vehicles: set throttle to throttle_value, as long as velocity is < target_velocity\n        For walkers: simply apply the given self._control\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._type == 'vehicle':\n            if not self._forced_speed:\n                if CarlaDataProvider.get_velocity(self._actor) < self._target_velocity:\n                    self._control.throttle = 1.0\n                else:\n                    self._control.throttle = 0.0\n                self._actor.apply_control(self._control)\n            else:\n                yaw = CarlaDataProvider.get_transform(self._actor).rotation.yaw * (math.pi / 180)\n                self._actor.set_target_velocity(carla.Vector3D(\n                    math.cos(yaw) * self._target_velocity, math.sin(yaw) * self._target_velocity, 0))\n\n                # Add a throttle. Useless speed-wise, but makes the bicycle riders pedal.\n                self._actor.apply_control(carla.VehicleControl(throttle=1.0))\n\n        new_location = CarlaDataProvider.get_location(self._actor)\n        self._distance += calculate_distance(self._location, new_location)\n        self._location = new_location\n\n        if self._distance > self._target_distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, the throttle should be set back to 0.,\n        to avoid further acceleration.\n        \"\"\"\n        try:\n            if self._type == 'vehicle':\n                self._control.throttle = 0.0\n            elif self._type == 'walker':\n                self._control.speed = 0.0\n            if self._actor is not None and self._actor.is_alive:\n                self._actor.apply_control(self._control)\n        except RuntimeError:\n            pass\n        super(KeepVelocity, self).terminate(new_status)\n\n\nclass ChangeAutoPilot(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to disable/enable the use of the autopilot.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - activate: True (=enable autopilot) or False (=disable autopilot)\n    - lane_change: Traffic Manager parameter. True (=enable lane changes) or False (=disable lane changes)\n    - distance_between_vehicles: Traffic Manager parameter\n    - max_speed: Traffic Manager parameter. Max speed of the actor. This will only work for road segments\n                 with the same speed limit as the first one\n\n    The behavior terminates after changing the autopilot state\n    \"\"\"\n\n    def __init__(self, actor, activate, parameters=None, name=\"ChangeAutoPilot\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeAutoPilot, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._activate = activate\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(\n            CarlaDataProvider.get_traffic_manager_port())\n        self._parameters = parameters\n\n    def update(self):\n        \"\"\"\n        De/activate autopilot\n        \"\"\"\n        self._actor.set_autopilot(self._activate, CarlaDataProvider.get_traffic_manager_port())\n\n        if self._parameters is not None:\n            if \"auto_lane_change\" in self._parameters:\n                lane_change = self._parameters[\"auto_lane_change\"]\n                self._tm.auto_lane_change(self._actor, lane_change)\n\n            if \"max_speed\" in self._parameters:\n                max_speed = self._parameters[\"max_speed\"]\n                max_road_speed = self._actor.get_speed_limit()\n                if max_road_speed is not None:\n                    percentage = (max_road_speed - max_speed) / max_road_speed * 100.0\n                    self._tm.vehicle_percentage_speed_difference(self._actor, percentage)\n                else:\n                    print(\"ChangeAutopilot: Unable to find the vehicle's speed limit\")\n\n            if \"distance_between_vehicles\" in self._parameters:\n                dist_vehicles = self._parameters[\"distance_between_vehicles\"]\n                self._tm.distance_to_leading_vehicle(self._actor, dist_vehicles)\n\n            if \"force_lane_change\" in self._parameters:\n                force_lane_change = self._parameters[\"force_lane_change\"]\n                self._tm.force_lane_change(self._actor, force_lane_change)\n\n            if \"ignore_vehicles_percentage\" in self._parameters:\n                ignore_vehicles = self._parameters[\"ignore_vehicles_percentage\"]\n                self._tm.ignore_vehicles_percentage(self._actor, ignore_vehicles)\n\n        new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass StopVehicle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic stopping behavior. The controlled traffic\n    participant will decelerate with _bake_value_ until reaching a full stop.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - brake_value: Brake value in [0,1] applied\n\n    The behavior terminates when the actor stopped moving\n    \"\"\"\n\n    def __init__(self, actor, brake_value, name=\"Stopping\"):\n        \"\"\"\n        Setup _actor and maximum braking value\n        \"\"\"\n        super(StopVehicle, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control, self._type = get_actor_control(actor)\n        if self._type == 'walker':\n            self._control.speed = 0\n        self._brake_value = brake_value\n\n    def update(self):\n        \"\"\"\n        Set brake to brake_value until reaching full stop\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._type == 'vehicle':\n            if CarlaDataProvider.get_velocity(self._actor) > EPSILON:\n                self._control.brake = self._brake_value\n            else:\n                new_status = py_trees.common.Status.SUCCESS\n                self._control.brake = 0\n        else:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass SyncArrival(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to\n    set velocity of actor so that it reaches location at the same time as\n    actor_reference. The behavior assumes that the two actors are moving\n    towards location in a straight line.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - actor_reference: Reference actor with which arrival is synchronized\n    - target_location: CARLA location where the actors should \"meet\"\n    - gain[optional]: Coefficient for actor's throttle and break controls\n    Note: In parallel to this behavior a termination behavior has to be used\n          to keep continue synchronization for a certain duration, or for a\n          certain distance, etc.\n    \"\"\"\n\n    def __init__(self, actor, actor_reference, target_location, gain=1, name=\"SyncArrival\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super(SyncArrival, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control = carla.VehicleControl()\n        self._actor_reference = actor_reference\n        self._target_location = target_location\n        self._gain = gain\n\n        self._control.steering = 0\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        distance_reference = calculate_distance(CarlaDataProvider.get_location(self._actor_reference),\n                                                self._target_location)\n        distance = calculate_distance(CarlaDataProvider.get_location(self._actor),\n                                      self._target_location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._actor_reference)\n        time_reference = float('inf')\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n\n        velocity_current = CarlaDataProvider.get_velocity(self._actor)\n        time_current = float('inf')\n        if velocity_current > 0:\n            time_current = distance / velocity_current\n\n        control_value = (self._gain) * (time_current - time_reference)\n\n        if control_value > 0:\n            self._control.throttle = min([control_value, 1])\n            self._control.brake = 0\n        else:\n            self._control.throttle = 0\n            self._control.brake = min([abs(control_value), 1])\n\n        self._actor.apply_control(self._control)\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, the throttle should be set back to 0.,\n        to avoid further acceleration.\n        \"\"\"\n        if self._actor is not None and self._actor.is_alive:\n            self._control.throttle = 0.0\n            self._control.brake = 0.0\n            self._actor.apply_control(self._control)\n        super(SyncArrival, self).terminate(new_status)\n\n\nclass SyncArrivalWithAgent(AtomicBehavior):\n\n    \"\"\"\n    Atomic to make two actors arrive at their corresponding places at the same time.\n    This uses a controller and presuposes that the actor can reach its destination by following the lane.\n\n    The behavior is in RUNNING state until the \"main\" actor has reached its destination.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        reference_actor (carla.Actor): Reference actor to sync up to.\n        actor_target (carla.Transform): Endpoint of the actor after the behavior finishes.\n        reference_target (carla.Transform): Endpoint of the reference_actor after the behavior finishes.\n        delay (float): Time difference between the actors synchronization.\n        end_dist (float): Minimum distance from the target to finish the behavior.\n        name (string): Name of the behavior.\n            Defaults to 'SyncArrivalWithAgent'.\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, actor_target, reference_target, end_dist=1,\n                 name=\"SyncArrivalWithAgent\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super().__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._actor = actor\n        self._actor_target = actor_target\n        self._reference_actor = reference_actor\n        self._reference_target = reference_target\n        self._end_dist = end_dist\n        self._agent = None\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        self._agent = ConstantVelocityAgent(\n            self._actor,\n            map_inst=CarlaDataProvider.get_map(),\n            grp_inst=CarlaDataProvider.get_global_route_planner())\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity to ensure that both actors reach their target\n        positions at the same time.\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Get the distance of the actor to its endpoint\n        distance = calculate_distance(\n            CarlaDataProvider.get_location(self._actor), self._actor_target.location)\n\n        # Check if the reference actor has passed its target\n        if distance < self._end_dist:\n            ref_dir = self._reference_target.get_forward_vector()\n            ref_veh = self._reference_target.location - self._reference_actor.get_location()\n            if ref_veh.dot(ref_dir) > 0:\n                return py_trees.common.Status.SUCCESS\n\n        # Get the time to arrival of the reference to its endpoint\n        distance_reference = calculate_distance(\n            CarlaDataProvider.get_location(self._reference_actor), self._reference_target.location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._reference_actor)\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n        else:\n            time_reference = float('inf')\n\n        # Get the required velocity of the actor\n        desired_velocity = distance / time_reference\n\n        self._agent.set_target_speed(3.6 * desired_velocity)\n        self._actor.apply_control(self._agent.run_step())\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Destroy the collision sensor of the agent\"\"\"\n        if self._agent:\n            self._agent.destroy_sensor()\n        return super().terminate(new_status)\n\n\nclass CutIn(AtomicBehavior):\n\n    \"\"\"\n    Atomic to make an actor lane change using a Python API agent, cutting in front of another one\n\n    The behavior creates a lane change path and is in RUNNING state until the \"main\" actor has finsihes it.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        reference_actor (carla.Actor): Reference actor to cut in.\n        direction (string): Side from which the cut in happens. Either 'left' or 'right'.\n        speed_perc (float): Percentage of the reference actor speed on which the cut in is performed.\n        same_lane_time (float): Amount of time spent at the same lane before cutting in.\n        other_lane_time (float): Amount of time spent at the other lane after cutting in.\n        change_time (float): Amount of time spent changing into the other\n        name (string): Name of the behavior.\n            Defaults to 'CutIn'.\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, direction, speed_perc=100,\n                 same_lane_time=0, other_lane_time=0, change_time=2,\n                 name=\"CutIn\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super().__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._reference_actor = reference_actor\n        self._direction = direction\n        self._speed_perc = speed_perc\n        self._same_lane_time = same_lane_time\n        self._other_lane_time = other_lane_time\n        self._change_time = change_time\n\n        self._map = CarlaDataProvider.get_map()\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        speed = CarlaDataProvider.get_velocity(self._reference_actor)\n        self._agent = BasicAgent(\n            self._actor,\n            3.6 * speed * self._speed_perc / 100,\n            map_inst=CarlaDataProvider.get_map(),\n            grp_inst=CarlaDataProvider.get_global_route_planner())\n        self._agent.lane_change(self._direction, self._same_lane_time, self._other_lane_time, self._change_time)\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity to ensure that both actors reach their target\n        positions at the same time.\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        if self._agent.done():\n            return py_trees.common.Status.SUCCESS\n\n        self._actor.apply_control(self._agent.run_step())\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass AddNoiseToVehicle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic jitter behavior.\n    To add noise to steer as well as throttle of the vehicle.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - steer_value: Applied steering noise in [0,1]\n    - throttle_value: Applied throttle noise in [0,1]\n\n    The behavior terminates after setting the new actor controls\n    \"\"\"\n\n    def __init__(self, actor, steer_value, throttle_value, name=\"Jittering\"):\n        \"\"\"\n        Setup actor , maximum steer value and throttle value\n        \"\"\"\n        super(AddNoiseToVehicle, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control = carla.VehicleControl()\n        self._steer_value = steer_value\n        self._throttle_value = throttle_value\n\n    def update(self):\n        \"\"\"\n        Set steer to steer_value and throttle to throttle_value until reaching full stop\n        \"\"\"\n        self._control = self._actor.get_control()\n        self._control.steer = self._steer_value\n        self._control.throttle = self._throttle_value\n        new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        self._actor.apply_control(self._control)\n\n        return new_status\n\n\nclass AddNoiseToRouteEgo(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic jitter behavior.\n    To add noise to steer as well as throttle of the vehicle.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - steer_value: Applied steering noise in [0,1]\n    - throttle_value: Applied throttle noise in [0,1]\n\n    The behavior terminates after setting the new actor controls\n    \"\"\"\n\n    def __init__(self, actor, throttle_mean, throttle_std, steer_mean, steer_std, name=\"AddNoiseToVehicle\"):\n        \"\"\"\n        Setup actor , maximum steer value and throttle value\n        \"\"\"\n        super().__init__(name, actor)\n        self._throttle_mean = throttle_mean\n        self._throttle_std = throttle_std\n        self._steer_mean = steer_mean\n        self._steer_std = steer_std\n\n        self._rng = CarlaDataProvider.get_random_seed()\n\n    def update(self):\n        \"\"\"\n        Set steer to steer_value and throttle to throttle_value until reaching full stop\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        control = py_trees.blackboard.Blackboard().get(\"AV_control\")\n        if not control:\n            print(\"WARNING: Couldn't add noise to the ego because the control couldn't be found\")\n            return new_status\n\n        throttle_noise = random.normal(self._throttle_mean, self._throttle_std)\n        control.throttle = max(0, min(1, control.throttle + throttle_noise))\n\n        steer_noise = random.normal(self._steer_mean, self._steer_std)\n        control.steer = max(-1, min(1, control.steer + steer_noise))\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        self._actor.apply_control(control)\n\n        return new_status\n\n\nclass ChangeNoiseParameters(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic jitter behavior.\n    To add noise to steer as well as throttle of the vehicle.\n\n    This behavior should be used in conjuction with AddNoiseToVehicle\n\n    The behavior terminates after one iteration\n    \"\"\"\n\n    def __init__(self, new_steer_noise, new_throttle_noise,\n                 noise_mean, noise_std, dynamic_mean_for_steer, dynamic_mean_for_throttle, name=\"ChangeJittering\"):\n        \"\"\"\n        Setup actor , maximum steer value and throttle value\n        \"\"\"\n        super(ChangeNoiseParameters, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._new_steer_noise = new_steer_noise\n        self._new_throttle_noise = new_throttle_noise\n        self._noise_mean = noise_mean\n        self._noise_std = noise_std\n        self._dynamic_mean_for_steer = dynamic_mean_for_steer\n        self._dynamic_mean_for_throttle = dynamic_mean_for_throttle\n\n        self._noise_to_apply = abs(random.normal(self._noise_mean, self._noise_std))\n\n    def update(self):\n        \"\"\"\n        Change the noise parameters from the structure copy that it receives.\n        \"\"\"\n\n        self._new_steer_noise[0] = min(0, -(self._noise_to_apply - self._dynamic_mean_for_steer))\n        self._new_throttle_noise[0] = min(self._noise_to_apply + self._dynamic_mean_for_throttle, 1)\n\n        new_status = py_trees.common.Status.SUCCESS\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass BasicAgentBehavior(AtomicBehavior):\n    \"\"\"\n    This class contains an atomic behavior, which uses the\n    basic_agent from CARLA to control the actor until\n    reaching a target location.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_location: Is the desired target location (carla.location),\n                       the actor should move to\n    The behavior terminates after reaching the target_location (within 2 meters)\n    \"\"\"\n\n    def __init__(self, actor, target_location=None, plan=None, target_speed=20, opt_dict=None, name=\"BasicAgentBehavior\"):\n        \"\"\"\n        Setup actor and maximum steer value\n        \"\"\"\n        super(BasicAgentBehavior, self).__init__(name, actor)\n        self._map = CarlaDataProvider.get_map()\n        self._target_location = target_location\n        self._target_speed = target_speed\n        self._plan = plan\n\n        self._opt_dict = opt_dict if opt_dict else {}\n        self._control = carla.VehicleControl()\n        self._agent = None\n\n        if self._target_location and self._plan:\n            raise ValueError(\"Choose either a destination or a plan, but not both\")\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        self._agent = BasicAgent(self._actor, self._target_speed, opt_dict=self._opt_dict,\n            map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner())\n        if self._plan:\n            self._agent.set_global_plan(self._plan)\n        elif self._target_location:\n            init_wp = self._map.get_waypoint(CarlaDataProvider.get_location(self._actor))\n            end_wp = self._map.get_waypoint(self._target_location)\n            self._plan = self._agent.trace_route(init_wp, end_wp)\n            self._agent.set_global_plan(self._plan)\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._agent.done():\n            new_status = py_trees.common.Status.SUCCESS\n        self._control = self._agent.run_step()\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Resets the control\"\"\"\n        self._control.throttle = 0.0\n        self._control.brake = 0.0\n        self._actor.apply_control(self._control)\n        super(BasicAgentBehavior, self).terminate(new_status)\n\n\nclass ConstantVelocityAgentBehavior(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior, which uses the\n    constant_velocity_agent from CARLA to control the actor until\n    reaching a target location.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_location: Is the desired target location (carla.location),\n                       the actor should move to\n    - plan: List of [carla.Waypoint, RoadOption] to pass to the controller\n    - target_speed: Desired speed of the actor\n    The behavior terminates after reaching the target_location (within 2 meters)\n    \"\"\"\n\n    def __init__(self, actor, target_location, target_speed=None,\n                 opt_dict=None, name=\"ConstantVelocityAgentBehavior\"):\n        \"\"\"\n        Set up actor and local planner\n        \"\"\"\n        super(ConstantVelocityAgentBehavior, self).__init__(name, actor)\n        self._target_speed = target_speed\n        self._map = CarlaDataProvider.get_map()\n        self._target_location = target_location\n        self._opt_dict = opt_dict if opt_dict else {}\n        self._control = carla.VehicleControl()\n        self._agent = None\n        self._plan = None\n\n        self._map = CarlaDataProvider.get_map()\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        self._agent = ConstantVelocityAgent(\n            self._actor, self._target_speed * 3.6, opt_dict=self._opt_dict,\n            map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner())\n        self._plan = self._agent.trace_route(\n            self._map.get_waypoint(CarlaDataProvider.get_location(self._actor)),\n            self._map.get_waypoint(self._target_location))\n        self._agent.set_global_plan(self._plan)\n\n    def update(self):\n        \"\"\"Moves the actor and waits for it to finish the plan\"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._agent.done():\n            new_status = py_trees.common.Status.SUCCESS\n\n        self._control = self._agent.run_step()\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Resets the control\"\"\"\n        self._control.throttle = 0.0\n        self._control.brake = 0.0\n        self._actor.apply_control(self._control)\n        if self._agent:\n            self._agent.destroy_sensor()\n        super(ConstantVelocityAgentBehavior, self).terminate(new_status)\n\nclass AdaptiveConstantVelocityAgentBehavior(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior, which uses the\n    constant_velocity_agent from CARLA to control the actor until\n    reaching a target location.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior.\n    - reference_actor: Reference CARLA actor to get target speed.\n    - speed_increment: Float value (m/s). \n                       How much the actor will be faster then the reference_actor.\n    - target_location: Is the desired target location (carla.location),\n                       the actor should move to. \n                       If it's None, the actor will follow the lane and never stop.\n    - plan: List of [carla.Waypoint, RoadOption] to pass to the controller.\n    The behavior terminates after reaching the target_location (within 2 meters)\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, target_location=None, speed_increment=10,\n                 opt_dict=None, name=\"AdaptiveConstantVelocityAgentBehavior\"):\n        \"\"\"\n        Set up actor and local planner\n        \"\"\"\n        super().__init__(name, actor)\n        self._speed_increment = speed_increment\n        self._reference_actor = reference_actor\n        self._target_location = target_location\n        self._opt_dict = opt_dict if opt_dict else {}\n        self._control = carla.VehicleControl()\n        self._agent = None\n        self._plan = None\n\n        self._map = CarlaDataProvider.get_map()\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        # Get target speed\n        target_speed = get_speed(self._reference_actor) + self._speed_increment * 3.6\n\n        self._agent = ConstantVelocityAgent(self._actor, target_speed, opt_dict=self._opt_dict,\n                                            map_inst=self._map, grp_inst=self._grp)\n\n        if self._target_location is not None:\n            self._plan = self._agent.trace_route(\n                self._map.get_waypoint(CarlaDataProvider.get_location(self._actor)),\n                self._map.get_waypoint(self._target_location))\n            self._agent.set_global_plan(self._plan)\n\n    def update(self):\n        \"\"\"Moves the actor and waits for it to finish the plan\"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        target_speed = get_speed(self._reference_actor) + self._speed_increment * 3.6\n        self._agent.set_target_speed(target_speed)\n\n        if self._agent.done():\n            new_status = py_trees.common.Status.SUCCESS\n\n        self._control = self._agent.run_step()\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Resets the control\"\"\"\n        self._control.throttle = 0.0\n        self._control.brake = 0.0\n        self._actor.apply_control(self._control)\n        if self._agent:\n            self._agent.destroy_sensor()\n        super().terminate(new_status)\n\nclass Idle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an idle behavior scenario\n\n    Important parameters:\n    - duration[optional]: Duration in seconds of this behavior\n\n    A termination can be enforced by providing a duration value.\n    Alternatively, a parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, duration=float(\"inf\"), name=\"Idle\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(Idle, self).__init__(name)\n        self._duration = duration\n        self._start_time = 0\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        super(Idle, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\nclass WaitForever(AtomicBehavior):\n\n    \"\"\"\n    This class contains a behavior that just waits forever.\n    Useful to stop some behavior sequences from stopping unwated parts of the behavior tree\n\n    Alternatively, a parallel termination behavior has to be used to stop it.\n    \"\"\"\n\n    def __init__(self, name=\"WaitForever\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super().__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        wait forever\n        \"\"\"\n        return py_trees.common.Status.RUNNING\n\n\nclass WaypointFollower(AtomicBehavior):\n\n    \"\"\"\n    This is an atomic behavior to follow waypoints while maintaining a given speed.\n    If no plan is provided, the actor will follow its foward waypoints indefinetely.\n    Otherwise, the behavior will end with SUCCESS upon reaching the end of the plan.\n    If no target velocity is provided, the actor continues with its current velocity.\n\n    Args:\n        actor (carla.Actor):  CARLA actor to execute the behavior.\n        target_speed (float, optional): Desired speed of the actor in m/s. Defaults to None.\n        plan ([carla.Location] or [(carla.Waypoint, carla.agent.navigation.local_planner)], optional):\n            Waypoint plan the actor should follow. Defaults to None.\n        blackboard_queue_name (str, optional):\n            Blackboard variable name, if additional actors should be created on-the-fly. Defaults to None.\n        avoid_collision (bool, optional):\n            Enable/Disable(=default) collision avoidance for vehicles/bikes. Defaults to False.\n        name (str, optional): Name of the behavior. Defaults to \"FollowWaypoints\".\n\n    Attributes:\n        actor (carla.Actor):  CARLA actor to execute the behavior.\n        name (str, optional): Name of the behavior.\n        _target_speed (float, optional): Desired speed of the actor in m/s. Defaults to None.\n        _plan ([carla.Location] or [(carla.Waypoint, carla.agent.navigation.local_planner)]):\n            Waypoint plan the actor should follow. Defaults to None.\n        _blackboard_queue_name (str):\n            Blackboard variable name, if additional actors should be created on-the-fly. Defaults to None.\n        _avoid_collision (bool): Enable/Disable(=default) collision avoidance for vehicles/bikes. Defaults to False.\n        _actor_dict: Dictonary of all actors, and their corresponding plans (e.g. {actor: plan}).\n        _local_planner_dict: Dictonary of all actors, and their corresponding local planners.\n            Either \"Walker\" for pedestrians, or a carla.agent.navigation.LocalPlanner for other actors.\n        _args_lateral_dict: Parameters for the PID of the used carla.agent.navigation.LocalPlanner.\n        _unique_id: Unique ID of the behavior based on timestamp in nanoseconds.\n\n    Note:\n        OpenScenario:\n        The WaypointFollower atomic must be called with an individual name if multiple consecutive WFs.\n        Blackboard variables with lists are used for consecutive WaypointFollower behaviors.\n        Termination of active WaypointFollowers in initialise of AtomicBehavior because any\n        following behavior must terminate the WaypointFollower.\n    \"\"\"\n\n    def __init__(self, actor, target_speed=None, plan=None, blackboard_queue_name=None,\n                 avoid_collision=False, name=\"FollowWaypoints\"):\n        \"\"\"\n        Set up actor and local planner\n        \"\"\"\n        super(WaypointFollower, self).__init__(name, actor)\n        self._actor_dict = {}\n        self._actor_dict[actor] = None\n        self._target_speed = target_speed\n        self._local_planner_dict = {}\n        self._local_planner_dict[actor] = None\n        self._plan = plan\n        self._blackboard_queue_name = blackboard_queue_name\n        if blackboard_queue_name is not None:\n            self._queue = Blackboard().get(blackboard_queue_name)\n        self._args_lateral_dict = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05}\n        self._avoid_collision = avoid_collision\n        self._unique_id = 0\n\n    def initialise(self):\n        \"\"\"\n        Delayed one-time initialization\n\n        Checks if another WaypointFollower behavior is already running for this actor.\n        If this is the case, a termination signal is sent to the running behavior.\n        \"\"\"\n        super(WaypointFollower, self).initialise()\n        self._unique_id = int(round(time.time() * 1e9))\n        try:\n            # check whether WF for this actor is already running and add new WF to running_WF list\n            check_attr = operator.attrgetter(\"running_WF_actor_{}\".format(self._actor.id))\n            running = check_attr(py_trees.blackboard.Blackboard())\n            active_wf = copy.copy(running)\n            active_wf.append(self._unique_id)\n            py_trees.blackboard.Blackboard().set(\n                \"running_WF_actor_{}\".format(self._actor.id), active_wf, overwrite=True)\n        except AttributeError:\n            # no WF is active for this actor\n            py_trees.blackboard.Blackboard().set(\"terminate_WF_actor_{}\".format(self._actor.id), [], overwrite=True)\n            py_trees.blackboard.Blackboard().set(\n                \"running_WF_actor_{}\".format(self._actor.id), [self._unique_id], overwrite=True)\n\n        for actor in self._actor_dict:\n            self._apply_local_planner(actor)\n        return True\n\n    def _apply_local_planner(self, actor):\n        \"\"\"\n        Convert the plan into locations for walkers (pedestrians), or to a waypoint list for other actors.\n        For non-walkers, activate the carla.agent.navigation.LocalPlanner module.\n        \"\"\"\n        if self._target_speed is None:\n            self._target_speed = CarlaDataProvider.get_velocity(actor)\n        else:\n            self._target_speed = self._target_speed\n\n        if isinstance(actor, carla.Walker):\n            self._local_planner_dict[actor] = \"Walker\"\n            if self._plan is not None:\n                if isinstance(self._plan[0], carla.Location):\n                    self._actor_dict[actor] = self._plan\n                else:\n                    self._actor_dict[actor] = [element[0].transform.location for element in self._plan]\n        else:\n            local_planner = LocalPlanner(  # pylint: disable=undefined-variable\n                actor, opt_dict={\n                    'target_speed': self._target_speed * 3.6,\n                    'lateral_control_dict': self._args_lateral_dict,\n                    'max_throttle': 1.0})\n\n            if self._plan is not None:\n                if isinstance(self._plan[0], carla.Location):\n                    plan = []\n                    for location in self._plan:\n                        waypoint = CarlaDataProvider.get_map().get_waypoint(location,\n                                                                            project_to_road=True,\n                                                                            lane_type=carla.LaneType.Any)\n                        plan.append((waypoint, RoadOption.LANEFOLLOW))\n                    local_planner.set_global_plan(plan)\n                else:\n                    local_planner.set_global_plan(self._plan)\n\n            self._local_planner_dict[actor] = local_planner\n            self._actor_dict[actor] = self._plan\n\n    def update(self):\n        \"\"\"\n        Compute next control step for the given waypoint plan, obtain and apply control to actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        check_term = operator.attrgetter(\"terminate_WF_actor_{}\".format(self._actor.id))\n        terminate_wf = check_term(py_trees.blackboard.Blackboard())\n\n        check_run = operator.attrgetter(\"running_WF_actor_{}\".format(self._actor.id))\n        active_wf = check_run(py_trees.blackboard.Blackboard())\n\n        # Termination of WF if the WFs unique_id is listed in terminate_wf\n        # only one WF should be active, therefore all previous WF have to be terminated\n        if self._unique_id in terminate_wf:\n            terminate_wf.remove(self._unique_id)\n            if self._unique_id in active_wf:\n                active_wf.remove(self._unique_id)\n\n            py_trees.blackboard.Blackboard().set(\n                \"terminate_WF_actor_{}\".format(self._actor.id), terminate_wf, overwrite=True)\n            py_trees.blackboard.Blackboard().set(\n                \"running_WF_actor_{}\".format(self._actor.id), active_wf, overwrite=True)\n            new_status = py_trees.common.Status.SUCCESS\n            return new_status\n\n        if self._blackboard_queue_name is not None:\n            while not self._queue.empty():\n                actor = self._queue.get()\n                if actor is not None and actor not in self._actor_dict:\n                    self._apply_local_planner(actor)\n\n        success = True\n        for actor in self._local_planner_dict:\n            local_planner = self._local_planner_dict[actor] if actor else None\n            if actor is not None and actor.is_alive and local_planner is not None:\n                # Check if the actor is a vehicle/bike\n                if not isinstance(actor, carla.Walker):\n                    control = local_planner.run_step(debug=False)\n                    if self._avoid_collision and detect_lane_obstacle(actor):\n                        control.throttle = 0.0\n                        control.brake = 1.0\n                    actor.apply_control(control)\n                    # Check if the actor reached the end of the plan\n                    # @TODO replace access to private _waypoints_queue with public getter\n                    if local_planner._waypoints_queue:  # pylint: disable=protected-access\n                        success = False\n                # If the actor is a pedestrian, we have to use the WalkerAIController\n                # The walker is sent to the next waypoint in its plan\n                else:\n                    actor_location = CarlaDataProvider.get_location(actor)\n                    success = False\n                    if self._actor_dict[actor]:\n                        location = self._actor_dict[actor][0]\n                        direction = location - actor_location\n                        direction_norm = math.sqrt(direction.x**2 + direction.y**2)\n                        control = actor.get_control()\n                        control.speed = self._target_speed\n                        control.direction = direction / direction_norm\n                        actor.apply_control(control)\n                        if direction_norm < 1.0:\n                            self._actor_dict[actor] = self._actor_dict[actor][1:]\n                            if self._actor_dict[actor] is None:\n                                success = True\n                    else:\n                        control = actor.get_control()\n                        control.speed = self._target_speed\n                        control.direction = CarlaDataProvider.get_transform(actor).rotation.get_forward_vector()\n                        actor.apply_control(control)\n\n        if success:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior,\n        the controls should be set back to 0.\n        \"\"\"\n        for actor in self._local_planner_dict:\n            if actor is not None and actor.is_alive:\n                control, _ = get_actor_control(actor)\n                actor.apply_control(control)\n                local_planner = self._local_planner_dict[actor]\n                if local_planner is not None and local_planner != \"Walker\":\n                    local_planner.reset_vehicle()\n                    local_planner = None\n\n        self._local_planner_dict = {}\n        self._actor_dict = {}\n        super(WaypointFollower, self).terminate(new_status)\n\n\nclass LaneChange(WaypointFollower):\n\n    \"\"\"\n    This class inherits from the class WaypointFollower.\n\n    This class contains an atomic lane change behavior to a parallel lane.\n    The vehicle follows a waypoint plan to the other lane, which is calculated in the initialise method.\n    This waypoint plan is calculated with a scenario helper function.\n\n    If an impossible lane change is asked for (due to the lack of lateral lanes,\n    next waypoints, continuous line, etc) the atomic will return a plan with the\n    waypoints until such impossibility is found.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - speed: speed of the actor for the lane change, in m/s\n    - direction: 'right' or 'left', depending on which lane to change\n    - distance_same_lane: straight distance before lane change, in m\n    - distance_other_lane: straight distance after lane change, in m\n    - distance_lane_change: straight distance for the lane change itself, in m\n\n    The total distance driven is greater than the sum of distance_same_lane and distance_other_lane.\n    It results from the lane change distance plus the distance_same_lane plus distance_other_lane.\n    The lane change distance is set to 25m (straight), the driven distance is slightly greater.\n\n    A parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, actor, speed=10, direction='left', distance_same_lane=5, distance_other_lane=100,\n                 distance_lane_change=25, lane_changes=1, name='LaneChange'):\n\n        self._direction = direction\n        self._distance_same_lane = distance_same_lane\n        self._distance_other_lane = distance_other_lane\n        self._distance_lane_change = distance_lane_change\n        self._lane_changes = lane_changes\n\n        self._target_lane_id = None\n        self._distance_new_lane = 0\n        self._pos_before_lane_change = None\n        self._plan = None\n\n        super(LaneChange, self).__init__(actor, target_speed=speed, name=name)\n\n    def initialise(self):\n\n        # get start position\n        position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location())\n\n        # calculate plan with scenario_helper function\n        self._plan, self._target_lane_id = generate_target_waypoint_list_multilane(\n            position_actor, self._direction, self._distance_same_lane,\n            self._distance_other_lane, self._distance_lane_change, check=True, lane_changes=self._lane_changes)\n        super(LaneChange, self).initialise()\n\n    def update(self):\n\n        if not self._plan:\n            print(\"{} couldn't perform the expected lane change\".format(self._actor))\n            return py_trees.common.Status.FAILURE\n\n        status = super(LaneChange, self).update()\n\n        current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location())\n        current_lane_id = current_position_actor.lane_id\n\n        if current_lane_id == self._target_lane_id:\n            # driving on new lane\n            distance = current_position_actor.transform.location.distance(self._pos_before_lane_change)\n\n            if distance > self._distance_other_lane:\n                # long enough distance on new lane --> SUCCESS\n                status = py_trees.common.Status.SUCCESS\n        else:\n            self._pos_before_lane_change = current_position_actor.transform.location\n\n        return status\n\n\nclass SetInitSpeed(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the init_speed of an actor,\n    succeding immeditely after initializing\n    \"\"\"\n\n    def __init__(self, actor, init_speed=10, name='SetInitSpeed'):\n\n        self._init_speed = init_speed\n        self._terminate = None\n        self._actor = actor\n\n        super(SetInitSpeed, self).__init__(name, actor)\n\n    def initialise(self):\n        \"\"\"\n        Initialize it's speed\n        \"\"\"\n\n        transform = self._actor.get_transform()\n        yaw = transform.rotation.yaw * (math.pi / 180)\n\n        vx = math.cos(yaw) * self._init_speed\n        vy = math.sin(yaw) * self._init_speed\n        self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0))\n\n    def update(self):\n        \"\"\"\n        Nothing to update, end the behavior\n        \"\"\"\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass HandBrakeVehicle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic hand brake behavior.\n    To set the hand brake value of the vehicle.\n\n    Important parameters:\n    - vehicle: CARLA actor to execute the behavior\n    - hand_brake_value to be applied in [0,1]\n\n    The behavior terminates after setting the hand brake value\n    \"\"\"\n\n    def __init__(self, vehicle, hand_brake_value, name=\"Braking\"):\n        \"\"\"\n        Setup vehicle control and brake value\n        \"\"\"\n        super(HandBrakeVehicle, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._vehicle = vehicle\n        self._control, self._type = get_actor_control(vehicle)\n        self._hand_brake_value = hand_brake_value\n\n    def update(self):\n        \"\"\"\n        Set handbrake\n        \"\"\"\n        new_status = py_trees.common.Status.SUCCESS\n        if self._type == 'vehicle':\n            self._control.hand_brake = self._hand_brake_value\n            self._vehicle.apply_control(self._control)\n        else:\n            self._hand_brake_value = None\n            self.logger.debug(\"%s.update()[%s->%s]\" %\n                              (self.__class__.__name__, self.status, new_status))\n            self._vehicle.apply_control(self._control)\n\n        return new_status\n\n\nclass ActorDestroy(AtomicBehavior):\n\n    \"\"\"\n    This class contains an actor destroy behavior.\n    Given an actor this behavior will delete it.\n\n    Important parameters:\n    - actor: CARLA actor to be deleted\n\n    The behavior terminates after removing the actor\n    \"\"\"\n\n    def __init__(self, actor, name=\"ActorDestroy\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(ActorDestroy, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n        if self._actor:\n            CarlaDataProvider.remove_actor_by_id(self._actor.id)\n            self._actor = None\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass ActorTransformSetter(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the transform\n    of an actor.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - transform: New target transform (position + orientation) of the actor\n    - physics [optional]: Change the physics of the actors to true / false. To not change the physics, use None.\n\n    The behavior terminates when actor is set to the new actor transform (closer than 1 meter)\n\n    NOTE:\n    It is very important to ensure that the actor location is spawned to the new transform because of the\n    appearence of a rare runtime processing error. WaypointFollower with LocalPlanner,\n    might fail if new_status is set to success before the actor is really positioned at the new transform.\n    Therefore: calculate_distance(actor, transform) < 1 meter\n    \"\"\"\n\n    def __init__(self, actor, transform, physics=True, name=\"ActorTransformSetter\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super(ActorTransformSetter, self).__init__(name, actor)\n        self._transform = transform\n        self._physics = physics\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        if self._actor.is_alive:\n            self._actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n            self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0))\n            self._actor.set_transform(self._transform)\n        super(ActorTransformSetter, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Transform actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if not self._actor.is_alive:\n            new_status = py_trees.common.Status.FAILURE\n\n        if calculate_distance(self._actor.get_location(), self._transform.location) < 1.0:\n            if self._physics is not None:\n                self._actor.set_simulate_physics(self._physics)\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass BatchActorTransformSetter(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the transform\n    of an actor.\n\n    Important parameters:\n    - actor_transform_list: list [carla.Actor, carla.Transform]\n    - physics [optional]: Change the physics of the actors to true / false. To not change the physics, use None.\n\n    The behavior terminates immediately\n    \"\"\"\n\n    def __init__(self, actor_transform_list, physics=True, name=\"BatchActorTransformSetter\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super().__init__(name)\n        self._actor_transform_list = actor_transform_list\n        self._physics = physics\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Transform actor\n        \"\"\"\n\n        for actor, transform in self._actor_transform_list:\n            actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n            actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0))\n            actor.set_transform(transform)\n            if self._physics is not None:\n                actor.set_simulate_physics(self._physics)\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass TrafficLightStateSetter(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the state of a given traffic light\n\n    Args:\n        actor (carla.TrafficLight): ID of the traffic light that shall be changed\n        state (carla.TrafficLightState): New target state\n\n    The behavior terminates after trying to set the new state\n    \"\"\"\n\n    def __init__(self, actor, state, name=\"TrafficLightStateSetter\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super(TrafficLightStateSetter, self).__init__(name)\n\n        self._actor = actor if \"traffic_light\" in actor.type_id else None\n        self._state = state\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Change the state of the traffic light\n        \"\"\"\n        if self._actor is None:\n            return py_trees.common.Status.FAILURE\n\n        new_status = py_trees.common.Status.RUNNING\n        if self._actor.is_alive:\n            self._actor.set_state(self._state)\n            new_status = py_trees.common.Status.SUCCESS\n        else:\n            # For some reason the actor is gone...\n            new_status = py_trees.common.Status.FAILURE\n\n        return new_status\n\n\nclass ActorSource(AtomicBehavior):\n\n    \"\"\"\n    Implementation for a behavior that will indefinitely create actors\n    at a given transform if no other actor exists in a given radius\n    from the transform.\n\n    Important parameters:\n    - actor_type_list: Type of CARLA actors to be spawned\n    - transform: Spawn location\n    - threshold: Min available free distance between other actors and the spawn location\n    - blackboard_queue_name: Name of the blackboard used to control this behavior\n    - actor_limit [optional]: Maximum number of actors to be spawned (default=7)\n\n    A parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, actor_type_list, transform, threshold, blackboard_queue_name,\n                 actor_limit=7, name=\"ActorSource\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(ActorSource, self).__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._actor_types = actor_type_list\n        self._spawn_point = transform\n        self._threshold = threshold\n        self._queue = Blackboard().get(blackboard_queue_name)\n        self._actor_limit = actor_limit\n        self._last_blocking_actor = None\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n        if self._actor_limit > 0:\n            world_actors = CarlaDataProvider.get_all_actors()\n            spawn_point_blocked = False\n            if (self._last_blocking_actor and\n                    self._spawn_point.location.distance(self._last_blocking_actor.get_location()) < self._threshold):\n                spawn_point_blocked = True\n\n            if not spawn_point_blocked:\n                for actor in world_actors:\n                    if self._spawn_point.location.distance(actor.get_location()) < self._threshold:\n                        spawn_point_blocked = True\n                        self._last_blocking_actor = actor\n                        break\n\n            if not spawn_point_blocked:\n                try:\n                    new_actor = CarlaDataProvider.request_new_actor(\n                        random.choice(self._actor_types), self._spawn_point)\n                    self._actor_limit -= 1\n                    self._queue.put(new_actor)\n                except:                             # pylint: disable=bare-except\n                    print(\"ActorSource unable to spawn actor\")\n        return new_status\n\n\nclass ActorSink(AtomicBehavior):\n\n    \"\"\"\n    Implementation for a behavior that will indefinitely destroy actors\n    that wander near a given location within a specified threshold.\n\n    Important parameters:\n    - actor_type_list: Type of CARLA actors to be spawned\n    - sink_location: Location (carla.location) at which actors will be deleted\n    - threshold: Distance around sink_location in which actors will be deleted\n\n    A parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, sink_location, threshold, name=\"ActorSink\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(ActorSink, self).__init__(name)\n        self._sink_location = sink_location\n        self._threshold = threshold\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n        CarlaDataProvider.remove_actors_in_surrounding(self._sink_location, self._threshold)\n        return new_status\n\n\nclass ActorFlow(AtomicBehavior):\n    \"\"\"\n    Behavior that indefinitely creates actors at a location,\n    controls them until another location, and then destroys them.\n    Therefore, a parallel termination behavior has to be used.\n\n    Important parameters:\n    - source_transform (carla.Transform): Transform at which actors will be spawned\n    - sink_location (carla.Location): Location at which actors will be deleted\n    - spawn_distance: Distance between spawned actors\n    - sink_distance: Actors closer to the sink than this distance will be deleted\n    - actors_speed: Speed of the actors part of the flow [m/s]\n    - initial_actors: Populates all the flow trajectory at the start\n    \"\"\"\n\n    def __init__(self, source_wp, sink_wp, spawn_dist_interval, sink_dist=2,\n                 actor_speed=20 / 3.6, initial_actors=False, initial_junction=False, name=\"ActorFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._rng = CarlaDataProvider.get_random_seed()\n        self._world = CarlaDataProvider.get_world()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(CarlaDataProvider.get_traffic_manager_port())\n\n        self._collision_bp = self._world.get_blueprint_library().find('sensor.other.collision')\n        self._is_constant_velocity_active = True\n\n        self._source_wp = source_wp\n        self._sink_wp = sink_wp\n\n        self._sink_location = self._sink_wp.transform.location\n        self._source_transform = self._source_wp.transform\n        self._source_location = self._source_transform.location\n\n        self._sink_dist = sink_dist\n        self._speed = actor_speed\n        self._initial_actors = initial_actors\n        self._initial_junction = initial_junction\n\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._attribute_filter = {'base_type': 'car', 'has_lights': True, 'special_type': ''}\n\n        self._actor_list = []\n        self._collision_sensor_list = []\n\n        self._terminated = False\n\n    def initialise(self):\n        if self._initial_actors:\n            grp = CarlaDataProvider.get_global_route_planner()\n            plan = grp.trace_route(self._source_location, self._sink_location)\n\n            ref_loc = plan[0][0].transform.location\n            for wp, _ in plan:\n                if wp.is_junction and not self._initial_junction:\n                    continue  # Spawning at junctions might break the path, so don't\n                if wp.transform.location.distance(ref_loc) < self._spawn_dist:\n                    continue\n                self._spawn_actor(wp.transform)\n                ref_loc = wp.transform.location\n                self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def _spawn_actor(self, transform):\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', transform, rolename='scenario',\n            attribute_filter=self._attribute_filter, tick=False\n        )\n        if actor is None:\n            return py_trees.common.Status.RUNNING\n\n        actor.set_autopilot(True, CarlaDataProvider.get_traffic_manager_port())\n        self._tm.set_path(actor, [self._sink_location])\n        self._tm.auto_lane_change(actor, False)\n        self._tm.set_desired_speed(actor, 3.6 * self._speed)\n        self._tm.update_vehicle_lights(actor, True)\n\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        sensor = None\n        if self._is_constant_velocity_active:\n            self._tm.ignore_vehicles_percentage(actor, 100)\n            actor.enable_constant_velocity(carla.Vector3D(self._speed, 0, 0))  # For when physics are active\n\n            sensor = self._world.spawn_actor(self._collision_bp, carla.Transform(), attach_to=actor)\n            sensor.listen(lambda _: self.stop_constant_velocity())\n\n        self._tm.ignore_lights_percentage(actor, 100)\n        self._tm.ignore_signs_percentage(actor, 100)\n        self._collision_sensor_list.append(sensor)\n        self._actor_list.append(actor)\n\n    def update(self):\n        \"\"\"Controls the created actors and creaes / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor, sensor in zip(list(self._actor_list), list(self._collision_sensor_list)):\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                if sensor is not None:\n                    sensor.stop()\n                    sensor.destroy()\n                self._collision_sensor_list.remove(sensor)\n                actor.destroy()\n                self._actor_list.remove(actor)\n\n        # Spawn new actors if needed\n        if len(self._actor_list) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_list[-1])\n            distance = self._source_location.distance(actor_location) if actor_location else 0\n\n        if distance > self._spawn_dist:\n            self._spawn_actor(self._source_transform)\n\n        return py_trees.common.Status.RUNNING\n\n    def stop_constant_velocity(self):\n        \"\"\"Stops the constant velocity behavior\"\"\"\n        self._is_constant_velocity_active = False\n        for actor in self._actor_list:\n            try:\n                actor.disable_constant_velocity()\n                self._tm.ignore_vehicles_percentage(actor, 0)\n            except RuntimeError:\n                pass\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for sensor in self._collision_sensor_list:\n            if sensor is None:\n                continue\n            try:\n                sensor.stop()\n                sensor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n        for actor in self._actor_list:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass OppositeActorFlow(AtomicBehavior):\n    \"\"\"\n    Similar to ActorFlow, but this is meant as an actor flow in the opposite direction.\n    As such, some configurations are different and for clarity, another behavior has been created\n\n    Important parameters:\n    - source_wp (carla.Waypoint): Waypoint at which actors will be spawned\n    - sink_wp (carla.Waypoint): Waypoint at which actors will be deleted\n    - spawn_dist_interval: Distance interval between spawned actors\n    - sink_dist: Actors closer to the sink than this distance will be deleted\n    - actors_speed: Speed of the actors part of the flow [m/s]\n    - offset: offset from the center lane of the actors\n    \"\"\"\n\n    def __init__(self, reference_wp, reference_actor, spawn_dist_interval,\n                 time_distance=1.5, base_distance=30, sink_dist=2, name=\"OppositeActorFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._rng = CarlaDataProvider.get_random_seed()\n        self._world = CarlaDataProvider.get_world()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(CarlaDataProvider.get_traffic_manager_port())\n\n        self._reference_wp = reference_wp\n        self._reference_actor = reference_actor\n        self._time_distance = time_distance\n        self._base_distance = base_distance\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._sink_dist = sink_dist\n\n        self._attribute_filter = {'base_type': 'car', 'has_lights': True, 'special_type': ''}\n\n        # Opposite direction needs earlier vehicle detection\n        self._opt_dict = {'base_vehicle_threshold': 10, 'detection_speed_ratio': 1.6}\n\n        self._actor_list = []\n        self._grp = CarlaDataProvider.get_global_route_planner()\n        self._map = CarlaDataProvider.get_map()\n\n        self._terminated = False\n\n    def _move_waypoint_forward(self, wp, distance):\n        \"\"\"Moves forward a certain distance, stopping at junctions\"\"\"\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n\n        return next_wp\n\n    def _move_waypoint_backwards(self, wp, distance):\n        \"\"\"Moves backwards a certain distance, stopping at junctions\"\"\"\n        dist = 0\n        prev_wp = wp\n        while dist < distance:\n            prev_wps = prev_wp.previous(1)\n            if prev_wps[0].is_junction:\n                break\n            prev_wp = prev_wps[0]\n            dist += 1\n\n        return prev_wp\n\n    def initialise(self):\n        \"\"\"Get the actor flow source and sink, depending on the reference actor speed\"\"\"\n        self._speed = self._reference_actor.get_speed_limit() # Km / h\n        self._flow_distance = self._time_distance * self._speed + self._base_distance\n\n        self._sink_wp = self._move_waypoint_forward(self._reference_wp, self._flow_distance)\n        self._source_wp = self._move_waypoint_backwards(self._reference_wp, self._flow_distance)\n\n        self._source_transform = self._source_wp.transform\n        self._source_location = self._source_transform.location\n        self._sink_location = self._sink_wp.transform.location\n\n        self._route = self._grp.trace_route(self._source_location, self._sink_location)\n\n        return super().initialise()\n\n    def _spawn_actor(self):\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._source_transform, rolename='scenario',\n            attribute_filter=self._attribute_filter, tick=False\n        )\n        if actor is None:\n            return py_trees.common.Status.RUNNING\n\n        controller = BasicAgent(actor, self._speed, self._opt_dict, self._map, self._grp)\n        controller.set_global_plan(self._route)\n        self._actor_list.append([actor, controller])\n\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def update(self):\n        \"\"\"Controls the created actors and creates / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor_data in list(self._actor_list):\n            actor, controller = actor_data\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                actor.destroy()\n                self._actor_list.remove(actor_data)\n            else:\n                actor.apply_control(controller.run_step())\n\n        # Spawn new actors if needed\n        if len(self._actor_list) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_list[-1][0])\n            distance = self._source_location.distance(actor_location) if actor_location else 0\n        if distance > self._spawn_dist:\n            self._spawn_actor()\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for actor, _ in self._actor_list:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass InvadingActorFlow(AtomicBehavior):\n    \"\"\"\n    Similar to ActorFlow, but this is meant as an actor flow in the opposite direction that invades the lane.\n    As such, some configurations are different and for clarity, another behavior has been created\n\n    Important parameters:\n    - source_wp (carla.Waypoint): Waypoint at which actors will be spawned\n    - sink_wp (carla.Waypoint): Waypoint at which actors will be deleted\n    - spawn_dist_interval: Distance interval between spawned actors\n    - sink_dist: Actors closer to the sink than this distance will be deleted\n    - actors_speed: Speed of the actors part of the flow [m/s]\n    - offset: offset from the center lane of the actors\n    \"\"\"\n\n    def __init__(self, source_wp, sink_wp, reference_actor, spawn_dist,\n                 sink_dist=2, offset=0, name=\"OppositeActorFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(CarlaDataProvider.get_traffic_manager_port())\n\n        self._reference_actor = reference_actor\n\n        self._source_wp  = source_wp\n        self._source_transform = self._source_wp.transform\n        self._source_location = self._source_transform.location\n\n        self._sink_wp = sink_wp\n        self._sink_location = self._sink_wp.transform.location\n\n        self._spawn_dist = spawn_dist\n\n        self._sink_dist = sink_dist\n\n        self._attribute_filter = {'base_type': 'car', 'has_lights': True, 'special_type': ''}\n\n        self._actor_list = []\n\n        # Opposite direction needs earlier vehicle detection\n        self._opt_dict = {'base_vehicle_threshold': 10, 'detection_speed_ratio': 2, 'distance_ratio': 0.2}\n        self._opt_dict['offset'] = offset\n\n        self._grp = CarlaDataProvider.get_global_route_planner()\n        self._map = CarlaDataProvider.get_map()\n\n        self._terminated = False\n\n    def initialise(self):\n        \"\"\"Get the actor flow source and sink, depending on the reference actor speed\"\"\"\n        self._speed = self._reference_actor.get_speed_limit()  # Km / h\n        self._route = self._grp.trace_route(self._source_location, self._sink_location)\n        return super().initialise()\n\n    def _spawn_actor(self):\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._source_transform, rolename='scenario',\n            attribute_filter=self._attribute_filter, tick=False\n        )\n        if actor is None:\n            return py_trees.common.Status.RUNNING\n\n        controller = BasicAgent(actor, self._speed, self._opt_dict, self._map, self._grp)\n        controller.set_global_plan(self._route)\n        self._actor_list.append([actor, controller])\n\n    def update(self):\n        \"\"\"Controls the created actors and creates / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor_data in list(self._actor_list):\n            actor, controller = actor_data\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                actor.destroy()\n                self._actor_list.remove(actor_data)\n            else:\n                actor.apply_control(controller.run_step())\n\n        # Spawn new actors if needed\n        if len(self._actor_list) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_list[-1][0])\n            distance = self._source_location.distance(actor_location) if actor_location else 0\n        if distance > self._spawn_dist:\n            self._spawn_actor()\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for actor, _ in self._actor_list:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass BicycleFlow(AtomicBehavior):\n    \"\"\"\n    Behavior that indefinitely creates bicycles at a location,\n    controls them until another location, and then destroys them.\n    Therefore, a parallel termination behavior has to be used.\n\n    Important parameters:\n    - plan (list(carla.Waypoint)): plan used by the bicycles.\n    - spawn_distance_interval (list(float, float)): Distance between spawned actors\n    - sink_distance (float): Actors at this distance from the sink will be deleted\n    - actors_speed (float): Speed of the actors part of the flow [m/s]\n    - initial_actors (bool): Boolean to initialy populate all the flow with bicycles\n    \"\"\"\n\n    def __init__(self, plan, spawn_dist_interval, sink_dist=2,\n                 actor_speed=20 / 3.6, initial_actors=False, name=\"BicycleFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._plan = plan\n        self._sink_dist = sink_dist\n        self._speed = actor_speed\n\n        self._source_transform = self._plan[0][0].transform\n        self._source_location = self._source_transform.location\n        self._sink_location = self._plan[-1][0].transform.location\n\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._initial_actors = initial_actors\n\n        self._opt_dict = {\"ignore_traffic_lights\": True, \"ignore_vehicles\": True}\n\n        self._actor_data = []\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n        self._terminated = False\n\n    def initialise(self):\n        if self._initial_actors:\n            ref_loc = self._plan[0][0].transform.location\n            for wp, _ in self._plan:\n                if wp.is_junction:\n                    continue  # Spawning at junctions might break the path, so don't\n                if wp.transform.location.distance(ref_loc) < self._spawn_dist:\n                    continue\n                self._spawn_actor(wp.transform)\n                ref_loc = wp.transform.location\n                self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def _spawn_actor(self, transform):\n        \"\"\"Spawn the actor\"\"\"\n        # Initial actors don't want all the plan. Remove the points behind them\n        plan = self._plan\n        actor_loc = transform.location\n        while len(plan) > 0:\n            wp, _ = plan[0]\n            loc = wp.transform.location\n            actor_heading = transform.get_forward_vector()\n            actor_wp_vec = loc - actor_loc\n            if actor_heading.dot(actor_wp_vec) < 0 or loc.distance(actor_loc) < 10:\n                plan.pop(0)\n            else:\n                break\n\n        if not plan:\n            return\n\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', transform, rolename='scenario no lights',\n            attribute_filter={'base_type': 'bicycle'}, tick=False\n        )\n        if actor is None:\n            return\n\n        controller = BasicAgent(actor, 3.6 * self._speed, opt_dict=self._opt_dict,\n            map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner())\n        controller.set_global_plan(plan)\n\n        initial_vec = plan[0][0].transform.get_forward_vector()\n        actor.set_target_velocity(self._speed * initial_vec)\n        actor.apply_control(carla.VehicleControl(throttle=1, gear=1, manual_gear_shift=True))\n\n        self._actor_data.append([actor, controller])\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def update(self):\n        \"\"\"Controls the created actors and creaes / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor_data in list(self._actor_data):\n            actor, controller = actor_data\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                actor.destroy()\n                self._actor_data.remove(actor_data)\n            else:\n                actor.apply_control(controller.run_step())\n\n        # Spawn new actors if needed\n        if len(self._actor_data) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_data[-1][0])\n            if actor_location is None:\n                distance = 0\n            else:\n                distance = self._source_location.distance(actor_location)\n\n        if distance > self._spawn_dist:\n            self._spawn_actor(self._source_transform)\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for actor, _ in self._actor_data:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass OpenVehicleDoor(AtomicBehavior):\n\n    \"\"\"\n    Implementation for a behavior that will open the door of a vehicle,\n    then close it after a while.\n\n    Important parameters:\n    - actor: Type of CARLA actors to be spawned\n    - vehicle_door: The specific door that will be opened\n    - duration: Duration of the open door\n    \"\"\"\n\n    def __init__(self, actor, vehicle_door, name=\"OpenVehicleDoor\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(OpenVehicleDoor, self).__init__(name, actor)\n        self._vehicle_door = vehicle_door\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._actor.open_door(self._vehicle_door)\n        super().initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.SUCCESS\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass TrafficLightFreezer(AtomicBehavior):\n    \"\"\"\n    Behavior that freezes a group of traffic lights for a specific amount of time,\n    returning them to their original state after ending it\n\n    Important parameters:\n    - traffic_lights_dict dict{carla.TrafficLight: carla.TrafficLightState}\n    - timeout: Amount of time the traffic lights are frozen\n    \"\"\"\n\n    def __init__(self, traffic_lights_dict, duration=10000, name=\"TrafficLightFreezer\"):\n        \"\"\"Setup class members\"\"\"\n        super(TrafficLightFreezer, self).__init__(name)\n        self._traffic_lights_dict = traffic_lights_dict\n        self._duration = duration\n        self._previous_traffic_light_info = {}\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Sets the traffic lights to the desired states and remembers their previous one.\n        These should technically be frozen, but that freezes all tls in the town\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        for tl in self._traffic_lights_dict:\n            elapsed_time = tl.get_elapsed_time()\n            self._previous_traffic_light_info[tl] = {\n                'state': tl.get_state(),\n                'green_time': tl.get_green_time(),\n                'red_time': tl.get_red_time(),\n                'yellow_time': tl.get_yellow_time()\n            }\n            tl.set_state(self._traffic_lights_dict[tl])\n            tl.set_green_time(self._duration + elapsed_time)\n            tl.set_red_time(self._duration + elapsed_time)\n            tl.set_yellow_time(self._duration + elapsed_time)\n\n    def update(self):\n        \"\"\"Waits until the adequate time has passed\"\"\"\n        if GameTime.get_time() - self._start_time > self._duration:\n            return py_trees.common.Status.SUCCESS\n        else:\n            return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"Reset all traffic lights back to their previous states\"\"\"\n        if self._previous_traffic_light_info:\n            for tl in self._traffic_lights_dict:\n                tl.set_state(self._previous_traffic_light_info[tl]['state'])\n                tl.set_green_time(self._previous_traffic_light_info[tl]['green_time'])\n                tl.set_red_time(self._previous_traffic_light_info[tl]['red_time'])\n                tl.set_yellow_time(self._previous_traffic_light_info[tl]['yellow_time'])\n\n\nclass StartRecorder(AtomicBehavior):\n\n    \"\"\"\n    Atomic that starts the CARLA recorder. Only one can be active\n    at a time, and if this isn't the case, the recorder will\n    automatically stop the previous one.\n\n    Args:\n        recorder_name (str): name of the file to write the recorded data.\n            Remember that a simple name will save the recording in\n            'CarlaUE4/Saved/'. Otherwise, if some folder appears in the name,\n            it will be considered an absolute path.\n        name (str): name of the behavior\n    \"\"\"\n\n    def __init__(self, recorder_name, name=\"StartRecorder\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(StartRecorder, self).__init__(name)\n        self._client = CarlaDataProvider.get_client()\n        self._recorder_name = recorder_name\n\n    def update(self):\n        self._client.start_recorder(self._recorder_name)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StopRecorder(AtomicBehavior):\n\n    \"\"\"\n    Atomic that stops the CARLA recorder.\n\n    Args:\n        name (str): name of the behavior\n    \"\"\"\n\n    def __init__(self, name=\"StopRecorder\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(StopRecorder, self).__init__(name)\n        self._client = CarlaDataProvider.get_client()\n\n    def update(self):\n        self._client.stop_recorder()\n        return py_trees.common.Status.SUCCESS\n\n\nclass TrafficLightManipulator(AtomicBehavior):\n\n    \"\"\"\n    Atomic behavior that manipulates traffic lights around the ego_vehicle to trigger scenarios 7 to 10.\n    This is done by setting 2 of the traffic light at the intersection to green (with some complex precomputation\n    to set everything up).\n\n    Important parameters:\n    - ego_vehicle: CARLA actor that controls this behavior\n    - subtype: string that gathers information of the route and scenario number\n      (check SUBTYPE_CONFIG_TRANSLATION below)\n    \"\"\"\n\n    RED = carla.TrafficLightState.Red\n    YELLOW = carla.TrafficLightState.Yellow\n    GREEN = carla.TrafficLightState.Green\n\n    # Time constants\n    RED_TIME = 1.5  # Minimum time the ego vehicle waits in red (seconds)\n    YELLOW_TIME = 2  # Time spent at yellow state (seconds)\n    RESET_TIME = 6  # Time waited before resetting all the junction (seconds)\n\n    # Experimental values\n    TRIGGER_DISTANCE = 10  # Distance that makes all vehicles in the lane enter the junction (meters)\n    DIST_TO_WAITING_TIME = 0.04  # Used to wait longer at larger intersections (s/m)\n\n    INT_CONF_OPP1 = {'ego': RED, 'ref': RED, 'left': RED, 'right': RED, 'opposite': GREEN}\n    INT_CONF_OPP2 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': RED, 'opposite': GREEN}\n    INT_CONF_LFT1 = {'ego': RED, 'ref': RED, 'left': GREEN, 'right': RED, 'opposite': RED}\n    INT_CONF_LFT2 = {'ego': GREEN, 'ref': GREEN, 'left': GREEN, 'right': RED, 'opposite': RED}\n    INT_CONF_RGT1 = {'ego': RED, 'ref': RED, 'left': RED, 'right': GREEN, 'opposite': RED}\n    INT_CONF_RGT2 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': GREEN, 'opposite': RED}\n\n    INT_CONF_REF1 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': RED, 'opposite': RED}\n    INT_CONF_REF2 = {'ego': YELLOW, 'ref': YELLOW, 'left': RED, 'right': RED, 'opposite': RED}\n\n    # Depending on the scenario, IN ORDER OF IMPORTANCE, the traffic light changed\n    # The list has to contain only items of the INT_CONF\n    SUBTYPE_CONFIG_TRANSLATION = {\n        'S7left': ['left', 'opposite', 'right'],\n        'S7right': ['left', 'opposite'],\n        'S7opposite': ['right', 'left', 'opposite'],\n        'S8left': ['opposite'],\n        'S9right': ['left', 'opposite']\n    }\n\n    CONFIG_TLM_TRANSLATION = {\n        'left': [INT_CONF_LFT1, INT_CONF_LFT2],\n        'right': [INT_CONF_RGT1, INT_CONF_RGT2],\n        'opposite': [INT_CONF_OPP1, INT_CONF_OPP2]\n    }\n\n    def __init__(self, ego_vehicle, subtype, debug=False, name=\"TrafficLightManipulator\"):\n        super(TrafficLightManipulator, self).__init__(name)\n        self.ego_vehicle = ego_vehicle\n        self.subtype = subtype\n        self.current_step = 1\n        self.debug = debug\n\n        self.traffic_light = None\n        self.annotations = None\n        self.configuration = None\n        self.prev_junction_state = None\n        self.junction_location = None\n        self.seconds_waited = 0\n        self.prev_time = None\n        self.max_trigger_distance = None\n        self.waiting_time = None\n        self.inside_junction = False\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n\n        new_status = py_trees.common.Status.RUNNING\n\n        # 1) Set up the parameters\n        if self.current_step == 1:\n\n            # Traffic light affecting the ego vehicle\n            self.traffic_light = CarlaDataProvider.get_next_traffic_light(self.ego_vehicle, use_cached_location=False)\n            if not self.traffic_light:\n                # nothing else to do in this iteration...\n                return new_status\n\n            # \"Topology\" of the intersection\n            self.annotations = CarlaDataProvider.annotate_trafficlight_in_group(self.traffic_light)\n\n            # Which traffic light will be modified (apart from the ego lane)\n            self.configuration = self.get_traffic_light_configuration(self.subtype, self.annotations)\n            if self.configuration is None:\n                self.current_step = 0  # End the behavior\n                return new_status\n\n            # Modify the intersection. Store the previous state\n            self.prev_junction_state = self.set_intersection_state(self.INT_CONF_REF1)\n\n            self.current_step += 1\n            if self.debug:\n                print(\"--- All set up\")\n\n        # 2) Modify the ego lane to yellow when closeby\n        elif self.current_step == 2:\n\n            ego_location = CarlaDataProvider.get_location(self.ego_vehicle)\n\n            if self.junction_location is None:\n                ego_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n                junction_waypoint = ego_waypoint.next(0.5)[0]\n                while not junction_waypoint.is_junction:\n                    next_wp = junction_waypoint.next(0.5)[0]\n                    junction_waypoint = next_wp\n                self.junction_location = junction_waypoint.transform.location\n\n            distance = ego_location.distance(self.junction_location)\n\n            # Failure check\n            if self.max_trigger_distance is None:\n                self.max_trigger_distance = distance + 1\n            if distance > self.max_trigger_distance:\n                self.current_step = 0\n\n            elif distance < self.TRIGGER_DISTANCE:\n                _ = self.set_intersection_state(self.INT_CONF_REF2)\n                self.current_step += 1\n\n            if self.debug:\n                print(\"--- Distance until traffic light changes: {}\".format(distance))\n\n        # 3) Modify the ego lane to red and the chosen one to green after several seconds\n        elif self.current_step == 3:\n\n            if self.passed_enough_time(self.YELLOW_TIME):\n                _ = self.set_intersection_state(self.CONFIG_TLM_TRANSLATION[self.configuration][0])\n\n                self.current_step += 1\n\n        # 4) Wait a bit to let vehicles enter the intersection, then set the ego lane to green\n        elif self.current_step == 4:\n\n            # Get the time in red, dependent on the intersection dimensions\n            if self.waiting_time is None:\n                self.waiting_time = self.get_waiting_time(self.annotations, self.configuration)\n\n            if self.passed_enough_time(self.waiting_time):\n                _ = self.set_intersection_state(self.CONFIG_TLM_TRANSLATION[self.configuration][1])\n\n                self.current_step += 1\n\n        # 5) Wait for the end of the intersection\n        elif self.current_step == 5:\n            # the traffic light has been manipulated, wait until the vehicle finsihes the intersection\n            ego_location = CarlaDataProvider.get_location(self.ego_vehicle)\n            ego_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n            if not self.inside_junction:\n                if ego_waypoint.is_junction:\n                    # Wait for the ego_vehicle to enter a junction\n                    self.inside_junction = True\n                else:\n                    if self.debug:\n                        print(\"--- Waiting to ENTER a junction\")\n\n            else:\n                if ego_waypoint.is_junction:\n                    if self.debug:\n                        print(\"--- Waiting to EXIT a junction\")\n                else:\n                    # And to leave it\n                    self.inside_junction = False\n                    self.current_step += 1\n\n        # 6) At the end (or if something failed), reset to the previous state\n        else:\n            if self.prev_junction_state:\n                CarlaDataProvider.reset_lights(self.prev_junction_state)\n                if self.debug:\n                    print(\"--- Returning the intersection to its previous state\")\n\n            self.variable_cleanup()\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n    def passed_enough_time(self, time_limit):\n        \"\"\"\n        Returns true or false depending on the time that has passed from the\n        first time this function was called\n        \"\"\"\n        # Start the timer\n        if self.prev_time is None:\n            self.prev_time = GameTime.get_time()\n\n        timestamp = GameTime.get_time()\n        self.seconds_waited += (timestamp - self.prev_time)\n        self.prev_time = timestamp\n\n        if self.debug:\n            print(\"--- Waited seconds: {}\".format(self.seconds_waited))\n\n        if self.seconds_waited >= time_limit:\n            self.seconds_waited = 0\n            self.prev_time = None\n\n            return True\n        return False\n\n    def set_intersection_state(self, choice):\n        \"\"\"\n        Changes the intersection to the desired state\n        \"\"\"\n        prev_state = CarlaDataProvider.update_light_states(\n            self.traffic_light,\n            self.annotations,\n            choice,\n            freeze=True)\n\n        return prev_state\n\n    def get_waiting_time(self, annotation, direction):\n        \"\"\"\n        Calculates the time the ego traffic light will remain red\n        to let vehicles enter the junction\n        \"\"\"\n\n        tl = annotation[direction][0]\n        ego_tl = annotation[\"ref\"][0]\n\n        tl_location = CarlaDataProvider.get_trafficlight_trigger_location(tl)\n        ego_tl_location = CarlaDataProvider.get_trafficlight_trigger_location(ego_tl)\n\n        distance = ego_tl_location.distance(tl_location)\n\n        return self.RED_TIME + distance * self.DIST_TO_WAITING_TIME\n\n    def get_traffic_light_configuration(self, subtype, annotations):\n        \"\"\"\n        Checks the list of possible altered traffic lights and gets\n        the first one that exists in the intersection\n\n        Important parameters:\n        - subtype: Subtype of the scenario\n        - annotations: list of the traffic light of the junction, with their direction (right, left...)\n        \"\"\"\n        configuration = None\n\n        if subtype in self.SUBTYPE_CONFIG_TRANSLATION:\n            possible_configurations = self.SUBTYPE_CONFIG_TRANSLATION[self.subtype]\n            while possible_configurations:\n                # Chose the first one and delete it\n                configuration = possible_configurations[0]\n                possible_configurations = possible_configurations[1:]\n                if configuration in annotations:\n                    if annotations[configuration]:\n                        # Found a valid configuration\n                        break\n                    else:\n                        # The traffic light doesn't exist, get another one\n                        configuration = None\n                else:\n                    if self.debug:\n                        print(\"This configuration name is wrong\")\n                    configuration = None\n\n            if configuration is None and self.debug:\n                print(\"This subtype has no traffic light available\")\n        else:\n            if self.debug:\n                print(\"This subtype is unknown\")\n\n        return configuration\n\n    def variable_cleanup(self):\n        \"\"\"\n        Resets all variables to the intial state\n        \"\"\"\n        self.current_step = 1\n        self.traffic_light = None\n        self.annotations = None\n        self.configuration = None\n        self.prev_junction_state = None\n        self.junction_location = None\n        self.max_trigger_distance = None\n        self.waiting_time = None\n        self.inside_junction = False\n\n\nclass ScenarioTriggerer(AtomicBehavior):\n\n    \"\"\"\n    Handles the triggering of the scenarios that are part of a route.\n\n    Initializes a list of blackboard variables to False, and only sets them to True when\n    the ego vehicle is very close to the scenarios\n    \"\"\"\n\n    WINDOWS_SIZE = 5\n\n    def __init__(self, actor, route, blackboard_list, distance, debug=False, name=\"ScenarioTriggerer\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(ScenarioTriggerer, self).__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._debug = debug\n\n        self._actor = actor\n        self._route = route\n        self._distance = distance\n        self._blackboard_list = blackboard_list\n        self._triggered_scenarios = []  # List of already done scenarios\n\n        self._current_index = 0\n        self._route_length = len(self._route)\n        self._waypoints, _ = zip(*self._route)\n\n    def add_blackboard(self, blackboard):\n        \"\"\"\n        Adds new blackboards to the list. Used by the runtime initialization of scenarios\n        \"\"\"\n        self._blackboard_list.append(blackboard)\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n        if location is None:\n            return new_status\n\n        lower_bound = self._current_index\n        upper_bound = min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)\n\n        shortest_distance = float('inf')\n        closest_index = -1\n\n        for index in range(lower_bound, upper_bound):\n            ref_waypoint = self._waypoints[index]\n            ref_location = ref_waypoint.location\n\n            dist_to_route = ref_location.distance(location)\n            if dist_to_route <= shortest_distance:\n                closest_index = index\n                shortest_distance = dist_to_route\n\n        if closest_index == -1 or shortest_distance == float('inf'):\n            return new_status\n\n        # Update the ego position at the route\n        self._current_index = closest_index\n\n        route_location = self._waypoints[closest_index].location\n\n        # Check which scenarios can be triggered\n        blackboard = py_trees.blackboard.Blackboard()\n        for black_var_name, scen_location in self._blackboard_list:\n\n            # Close enough\n            scen_distance = route_location.distance(scen_location)\n            condition1 = bool(scen_distance < self._distance)\n\n            # Not being currently done\n            value = blackboard.get(black_var_name)\n            condition2 = bool(not value)\n\n            # Already done, if needed\n            condition3 = bool(black_var_name not in self._triggered_scenarios)\n\n            if condition1 and condition2 and condition3:\n                _ = blackboard.set(black_var_name, True)\n                self._triggered_scenarios.append(black_var_name)\n\n                if self._debug:\n                    self._world.debug.draw_point(\n                        scen_location + carla.Location(z=4),\n                        size=0.5,\n                        life_time=0.5,\n                        color=carla.Color(255, 255, 0)\n                    )\n                    self._world.debug.draw_string(\n                        scen_location + carla.Location(z=5),\n                        str(black_var_name),\n                        False,\n                        color=carla.Color(0, 0, 0),\n                        life_time=1000\n                    )\n\n        return new_status\n\n\nclass KeepLongitudinalGap(AtomicBehavior):\n    \"\"\"\n    This class contains an atomic behavior to maintain a set gap with leading/adjacent vehicle.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - reference_actor: Reference actor the distance shall be kept to.\n    - distance: target gap between the two actors in meters\n    - distance_type: Specifies how distance should be calculated between the two actors\n\n    The behavior terminates after overwritten by other events / when target distance is reached(if continues).\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, gap, gap_type=\"distance\", max_speed=None, continues=False,\n                 freespace=False, name=\"AutoKeepDistance\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(KeepLongitudinalGap, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._reference_actor = reference_actor\n        self._gap = gap\n        self._gap_type = gap_type\n        self._continues = continues\n        self._freespace = freespace\n        self._global_rp = None\n        max_speed_limit = 100\n        self.max_speed = max_speed_limit if max_speed is None else float(max_speed)\n        if freespace and self._gap_type == \"distance\":\n            self._gap += self._reference_actor.bounding_box.extent.x + self._actor.bounding_box.extent.x\n\n        self._start_time = None\n\n    def initialise(self):\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or self._actor.id not in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n        actor_dict[self._actor.id].update_target_speed(self.max_speed, start_time=self._start_time)\n\n        self._global_rp = CarlaDataProvider.get_global_route_planner()\n\n        super(KeepLongitudinalGap, self).initialise()\n\n    def update(self):\n        \"\"\"\n        keeps track of gap and update the controller accordingly\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or self._actor.id not in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_velocity = CarlaDataProvider.get_velocity(self._actor)\n        reference_velocity = CarlaDataProvider.get_velocity(self._reference_actor)\n\n        gap = sr_tools.scenario_helper.get_distance_between_actors(self._actor, self._reference_actor,\n                                                                   distance_type=\"longitudinal\",\n                                                                   freespace=self._freespace,\n                                                                   global_planner=self._global_rp)\n        actor_transform = CarlaDataProvider.get_transform(self._actor)\n        ref_actor_transform = CarlaDataProvider.get_transform(self._reference_actor)\n        if is_within_distance(ref_actor_transform, actor_transform, float('inf'), [0, 90]) and \\\n                operator.le(gap, self._gap):\n            try:\n                factor = abs(actor_velocity - reference_velocity)/actor_velocity\n                if actor_velocity > reference_velocity:\n                    actor_velocity = actor_velocity - (factor*actor_velocity)\n                elif actor_velocity < reference_velocity and operator.gt(gap, self._gap):\n                    actor_velocity = actor_velocity + (factor*actor_velocity)\n            except ZeroDivisionError:\n                pass\n            actor_dict[self._actor.id].update_target_speed(actor_velocity)\n\n            if not self._continues:\n                if operator.le(gap, self._gap):\n                    new_status = py_trees.common.Status.SUCCESS\n        else:\n            actor_dict[self._actor.id].update_target_speed(self.max_speed)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass SwitchWrongDirectionTest(AtomicBehavior):\n\n    \"\"\"\n    Atomic that switch the OutsideRouteLanesTest criterion.\n\n    Args:\n        active (bool): True: activated; False: deactivated\n        name (str): name of the behavior\n    \"\"\"\n\n    def __init__(self, active, name=\"SwitchWrongDirectionTest\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        self._active = active\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"AC_SwitchWrongDirectionTest\", self._active, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass SwitchMinSpeedCriteria(AtomicBehavior):\n\n    def __init__(self, active, name=\"ChangeMinSpeed\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super().__init__(name)\n        self._active = active\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        keeps track of gap and update the controller accordingly\n        \"\"\"\n        new_status = py_trees.common.Status.SUCCESS\n        py_trees.blackboard.Blackboard().set(\"SwitchMinSpeedCriteria\", self._active, overwrite=True)\n        return new_status\n\n\nclass WalkerFlow(AtomicBehavior):\n    \"\"\"\n    Behavior that indefinitely creates walkers at a location,\n    controls them until another location, and then destroys them.\n    Therefore, a parallel termination behavior has to be used.\n\n    There can be more than one target location.\n\n    Important parameters:\n    - source_location (carla.Location): Location at which actors will be spawned\n    - sink_locations (list(carla.Location)): Locations at which actors will be deleted\n    - sink_locations_prob (list(float)): The probability of each sink_location\n    - spawn_dist_interval (list(float)): Distance between spawned actors\n    - random_seed : Optional. The seed of numpy's random\n    - sink_distance: Actors closer to the sink than this distance will be deleted. \n                     Probably due to the navigation module rerouting the walkers, a sink distance of 2 is reasonable.\n    \"\"\"\n    def __init__(self, source_location, sink_locations, sink_locations_prob, spawn_dist_interval, random_seed=None, sink_dist=2,\n                 name=\"WalkerFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(WalkerFlow, self).__init__(name)\n\n        if random_seed is not None:\n            self._rng = random.RandomState(random_seed)\n        else:\n            self._rng = CarlaDataProvider.get_random_seed()\n        self._world = CarlaDataProvider.get_world()\n\n        self._controller_bp = self._world.get_blueprint_library().find('controller.ai.walker')\n\n        self._source_location = source_location\n\n        self._sink_locations = sink_locations\n        self._sink_locations_prob = sink_locations_prob\n        self._sink_dist = sink_dist\n\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._batch_size_list = [1,2,3]\n\n        self._walkers = []\n\n    def update(self):\n        \"\"\"Controls the created actors and creates / removes other when needed\"\"\"\n        # Remove walkers when needed\n        for item in self._walkers:\n            walker, controller, sink_location = item\n            loc = CarlaDataProvider.get_location(walker)\n            if loc.distance(sink_location) < self._sink_dist:\n                self._destroy_walker(walker, controller)\n                self._walkers.remove(item)\n\n        # Spawn new walkers\n        if len(self._walkers) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._walkers[-1][0])\n            distance = self._source_location.distance(actor_location)\n\n        if distance > self._spawn_dist:\n            # spawn new walkers\n            walker_amount = self._rng.choice(self._batch_size_list)\n            for i in range(walker_amount):\n                spawn_tran = carla.Transform(self._source_location)\n                spawn_tran.location.y -= i\n                walker = CarlaDataProvider.request_new_actor(\n                    'walker.*', spawn_tran, rolename='scenario'\n                )\n                if walker is None:\n                    continue\n                # Use ai.walker to controll walkers\n                controller = self._world.try_spawn_actor(self._controller_bp, carla.Transform(), walker)\n                sink_location = self._rng.choice(a = self._sink_locations, p = self._sink_locations_prob)\n                controller.start()\n                controller.go_to_location(sink_location)\n                # Add to walkers list\n                self._walkers.append((walker, controller, sink_location))\n\n            self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        return py_trees.common.Status.RUNNING\n\n    def _destroy_walker(self, walker, controller):\n        controller.stop()\n        controller.destroy()\n        walker.destroy()\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        for walker, controller, _ in self._walkers:\n            try:\n                self._destroy_walker(walker, controller)\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\nclass AIWalkerBehavior(AtomicBehavior):\n    \"\"\"\n    Behavior that creates a walker controlled by AI Walker controller.\n    The walker go from source location to sink location.\n    A parallel termination behavior has to be used.\n\n    Important parameters:\n    - source_location (carla.Location): Location at which the actor will be spawned\n    - sink_location (carla.Location): Location at which the actor will be deleted\n    \"\"\"\n\n    def __init__(self, source_location, sink_location,\n                 name=\"AIWalkerBehavior\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(AIWalkerBehavior, self).__init__(name)\n\n        self._world = CarlaDataProvider.get_world()\n        self._controller_bp = self._world.get_blueprint_library().find('controller.ai.walker')\n\n        self._source_location = source_location\n\n        self._sink_location = sink_location\n        self._sink_dist = 2\n\n        self._walker = None\n        self._controller = None\n\n    def initialise(self):\n        \"\"\"\n        Spawn the walker at source location.\n        Setup the AI controller.\n\n        May throw RuntimeError if the walker can not be\n        spawned at given location.\n        \"\"\"\n        spawn_tran = carla.Transform(self._source_location)\n        self._walker = CarlaDataProvider.request_new_actor(\n            'walker.*', spawn_tran, rolename='scenario'\n        )\n        if self._walker is None:\n            raise RuntimeError(\"Couldn't spawn the walker\")\n        # Use ai.walker to controll the walker\n        self._controller = self._world.try_spawn_actor(\n            self._controller_bp, carla.Transform(), self._walker)\n        self._controller.start()\n        self._controller.go_to_location(self._sink_location)\n\n        super(AIWalkerBehavior, self).initialise()\n\n    def update(self):\n        \"\"\"Controls the created walker\"\"\"\n        # Remove walkers when needed\n        if self._walker is not None:\n            loc = CarlaDataProvider.get_location(self._walker)\n            # At the very beginning of the scenario, the get_location may return None\n            if loc is not None:\n                if loc.distance(self._sink_location) < self._sink_dist:\n                    self.terminate(py_trees.common.Status.SUCCESS)\n\n        return py_trees.common.Status.RUNNING\n\n    def _destroy_walker(self, walker, controller):\n        if controller:\n            controller.stop()\n            controller.destroy()\n        if walker:\n            walker.destroy()\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        try:\n            self._destroy_walker(self._walker, self._controller)\n        except RuntimeError:\n            pass  # Actor was already destroyed\n\n\nclass ScenarioTimeout(AtomicBehavior):\n\n    \"\"\"\n    This class is an idle behavior that waits for a set amount of time\n    before stoping.\n\n    It is meant to be used with the `ScenarioTimeoutTest` to be used at scenarios\n    that block the ego's route (such as adding obstacles) so that if the ego is\n    incapable of surpassing them, it isn't blocked forever. Instead,\n    the scenario will timeout, but it will be penalized by the `ScenarioTimeoutTest`\n\n    Parameters:\n    - duration: Duration in seconds of this behavior\n    \"\"\"\n\n    def __init__(self, duration, scenario_name, name=\"ScenarioTimeout\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super().__init__(name)\n        self._duration = duration\n        self._scenario_name = scenario_name\n        self._start_time = 0\n        self._scenario_timeout = False\n        self._terminated = False\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        py_trees.blackboard.Blackboard().set(\"AC_SwitchActorBlockedTest\", False, overwrite=True)\n        super().initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            self._scenario_timeout = True\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Modifies the blackboard to tell the `ScenarioTimeoutTest` if the timeout was triggered\n        \"\"\"\n        if not self._terminated:  # py_trees calls the terminate several times for some reason.\n            py_trees.blackboard.Blackboard().set(f\"ScenarioTimeout_{self._scenario_name}\", self._scenario_timeout, overwrite=True)\n            py_trees.blackboard.Blackboard().set(\"AC_SwitchActorBlockedTest\", True, overwrite=True)\n            self._terminated = True\n        super().terminate(new_status)\n\n\nclass MovePedestrianWithEgo(AtomicBehavior):\n\n    def __init__(self, reference_actor, actor, distance, displacement=0, name=\"TrackActor\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super().__init__(name)\n        self._actor = actor\n        self._reference_actor = reference_actor\n        self._distance = distance\n        self._displacement = displacement\n\n        added_location = carla.Location(x=self._displacement, z=-self._distance)\n        self._actor.set_location(self._reference_actor.get_location() + added_location)\n\n        self._start_time = 0\n        self._teleport_time = 5\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        added_location = carla.Location(x=self._displacement, z=-self._distance)\n        self._actor.set_location(self._reference_actor.get_location() + added_location)\n        super().initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if GameTime.get_time() - self._start_time > self._teleport_time:\n            added_location = carla.Location(x=self._displacement, z=-self._distance)\n            self._actor.set_location(self._reference_actor.get_location() + added_location)\n            self._start_time = GameTime.get_time()\n        return new_status\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_criteria.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all atomic evaluation criteria required to analyze if a\nscenario was completed successfully or failed.\n\nCriteria should run continuously to monitor the state of a single actor, multiple\nactors or environmental parameters. Hence, a termination is not required.\n\nThe atomic criteria are implemented with py_trees.\n\"\"\"\n\nimport math\nimport numpy as np\nimport py_trees\nimport shapely.geometry\n\nimport carla\nfrom agents.tools.misc import get_speed\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.traffic_events import TrafficEvent, TrafficEventType\n\n\nclass Criterion(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Base class for all criteria used to evaluate a scenario for success/failure\n\n    Important parameters (PUBLIC):\n    - name: Name of the criterion\n    - actor: Actor of the criterion\n    - optional: Indicates if a criterion is optional (not used for overall analysis)\n    - terminate on failure: Whether or not the criteria stops on failure\n\n    - test_status: Used to access the result of the criterion\n    - success_value: Result in case of success (e.g. max_speed, zero collisions, ...)\n    - acceptable_value: Result that does not mean a failure,  but is not good enough for a success\n    - actual_value: Actual result after running the scenario\n    - units: units of the 'actual_value'. This is a string and is used by the result writter\n    \"\"\"\n\n    def __init__(self,\n                 name,\n                 actor,\n                 optional=False,\n                 terminate_on_failure=False):\n        super(Criterion, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self.name = name\n        self.actor = actor\n        self.optional = optional\n        self._terminate_on_failure = terminate_on_failure\n        self.test_status = \"INIT\"   # Either \"INIT\", \"RUNNING\", \"SUCCESS\", \"ACCEPTABLE\" or \"FAILURE\"\n\n        # Attributes to compare the current state (actual_value), with the expected ones\n        self.success_value = 0\n        self.acceptable_value = None\n        self.actual_value = 0\n        self.units = \"times\"\n\n        self.events = []  # List of events (i.e collision, sidewalk invasion...)\n\n    def initialise(self):\n        \"\"\"\n        Initialise the criterion. Can be extended by the user-derived class\n        \"\"\"\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def terminate(self, new_status):\n        \"\"\"\n        Terminate the criterion. Can be extended by the user-derived class\n        \"\"\"\n        if self.test_status in ('RUNNING', 'INIT'):\n            self.test_status = \"SUCCESS\"\n\n        self.logger.debug(\"%s.terminate()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n\nclass MaxVelocityTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test for maximum velocity.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - max_velocity_allowed: maximum allowed velocity in m/s\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, max_velocity, optional=False, name=\"CheckMaximumVelocity\"):\n        \"\"\"\n        Setup actor and maximum allowed velovity\n        \"\"\"\n        super(MaxVelocityTest, self).__init__(name, actor, optional)\n        self.success_value = max_velocity\n\n    def update(self):\n        \"\"\"\n        Check velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actor is None:\n            return new_status\n\n        velocity = CarlaDataProvider.get_velocity(self.actor)\n\n        self.actual_value = max(velocity, self.actual_value)\n\n        if velocity > self.success_value:\n            self.test_status = \"FAILURE\"\n        else:\n            self.test_status = \"SUCCESS\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass DrivenDistanceTest(Criterion):\n    \"\"\"\n    This class contains an atomic test to check the driven distance\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - distance_success: If the actor's driven distance is more than this value (in meters),\n                        the test result is SUCCESS\n    - distance_acceptable: If the actor's driven distance is more than this value (in meters),\n                           the test result is ACCEPTABLE\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, distance, acceptable_distance=None, optional=False, name=\"CheckDrivenDistance\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(DrivenDistanceTest, self).__init__(name, actor, optional)\n        self.success_value = distance\n        self.acceptable_value = acceptable_distance\n        self._last_location = None\n\n    def initialise(self):\n        self._last_location = CarlaDataProvider.get_location(self.actor)\n        super(DrivenDistanceTest, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check distance\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actor is None:\n            return new_status\n\n        location = CarlaDataProvider.get_location(self.actor)\n\n        if location is None:\n            return new_status\n\n        if self._last_location is None:\n            self._last_location = location\n            return new_status\n\n        self.actual_value += location.distance(self._last_location)\n        self._last_location = location\n\n        if self.actual_value > self.success_value:\n            self.test_status = \"SUCCESS\"\n        elif (self.acceptable_value is not None and\n              self.actual_value > self.acceptable_value):\n            self.test_status = \"ACCEPTABLE\"\n        else:\n            self.test_status = \"RUNNING\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set final status\n        \"\"\"\n        if self.test_status != \"SUCCESS\":\n            self.test_status = \"FAILURE\"\n        self.actual_value = round(self.actual_value, 2)\n        super(DrivenDistanceTest, self).terminate(new_status)\n\n\nclass AverageVelocityTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test for average velocity.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - avg_velocity_success: If the actor's average velocity is more than this value (in m/s),\n                            the test result is SUCCESS\n    - avg_velocity_acceptable: If the actor's average velocity is more than this value (in m/s),\n                               the test result is ACCEPTABLE\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, velocity, acceptable_velocity=None, optional=False,\n                 name=\"CheckAverageVelocity\"):\n        \"\"\"\n        Setup actor and average velovity expected\n        \"\"\"\n        super(AverageVelocityTest, self).__init__(name, actor, optional)\n        self.success_value = velocity\n        self.acceptable_value = acceptable_velocity\n        self._last_location = None\n        self._distance = 0.0\n\n    def initialise(self):\n        self._last_location = CarlaDataProvider.get_location(self.actor)\n        super(AverageVelocityTest, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actor is None:\n            return new_status\n\n        location = CarlaDataProvider.get_location(self.actor)\n\n        if location is None:\n            return new_status\n\n        if self._last_location is None:\n            self._last_location = location\n            return new_status\n\n        self._distance += location.distance(self._last_location)\n        self._last_location = location\n\n        elapsed_time = GameTime.get_time()\n        if elapsed_time > 0.0:\n            self.actual_value = self._distance / elapsed_time\n\n        if self.actual_value > self.success_value:\n            self.test_status = \"SUCCESS\"\n        elif (self.acceptable_value is not None and\n              self.actual_value > self.acceptable_value):\n            self.test_status = \"ACCEPTABLE\"\n        else:\n            self.test_status = \"RUNNING\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set final status\n        \"\"\"\n        if self.test_status == \"RUNNING\":\n            self.test_status = \"FAILURE\"\n        super(AverageVelocityTest, self).terminate(new_status)\n\n\nclass CollisionTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test for collisions.\n\n    Args:\n    - actor (carla.Actor): CARLA actor to be used for this test\n    - other_actor (carla.Actor): only collisions with this actor will be registered\n    - other_actor_type (str): only collisions with actors including this type_id will count.\n        Additionally, the \"miscellaneous\" tag can also be used to include all static objects in the scene\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    COLLISION_RADIUS = 5  # Two collisions that happen within this distance count as one\n    MAX_ID_TIME = 5  # Two collisions with the same id that happen within this time count as one\n    EPSILON = 0.1  # Collisions at lower this speed won't be counted as the actor's fault\n\n    def __init__(self, actor, other_actor=None, other_actor_type=None,\n                 optional=False, terminate_on_failure=False, name=\"CollisionTest\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(CollisionTest, self).__init__(name, actor, optional, terminate_on_failure)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._other_actor = other_actor\n        self._other_actor_type = other_actor_type\n\n        # Attributes to store the last collisions's data\n        self._collision_sensor = None\n        self._collision_id = None\n        self._collision_time = None\n        self._collision_location = None\n\n    def initialise(self):\n        \"\"\"\n        Creates the sensor and callback\"\"\"\n        world = CarlaDataProvider.get_world()\n        blueprint = world.get_blueprint_library().find('sensor.other.collision')\n        self._collision_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor)\n        self._collision_sensor.listen(lambda event: self._count_collisions(event))\n        super(CollisionTest, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check collision count\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        actor_location = CarlaDataProvider.get_location(self.actor)\n\n        # Check if the last collision can be ignored\n        if self._collision_location:\n            distance_vector = actor_location - self._collision_location\n            if distance_vector.length() > self.COLLISION_RADIUS:\n                self._collision_location = None\n        if self._collision_id:\n            elapsed_time = GameTime.get_time() - self._collision_time\n            if elapsed_time > self.MAX_ID_TIME:\n                self._collision_id = None\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Cleanup sensor\n        \"\"\"\n        if self._collision_sensor is not None:\n            self._collision_sensor.stop()\n            self._collision_sensor.destroy()\n        self._collision_sensor = None\n        super(CollisionTest, self).terminate(new_status)\n\n    def _count_collisions(self, event):     # pylint: disable=too-many-return-statements\n        \"\"\"Update collision count\"\"\"\n        actor_location = CarlaDataProvider.get_location(self.actor)\n\n        # Check if the care about the other actor\n        if self._other_actor and self._other_actor.id != event.other_actor.id:\n            return\n\n        if self._other_actor_type:\n            if self._other_actor_type == \"miscellaneous\":  # Special OpenScenario case\n                if \"traffic\" not in event.other_actor.type_id and \"static\" not in event.other_actor.type_id:\n                    return\n            elif self._other_actor_type not in event.other_actor.type_id:\n                    return\n\n        # To avoid multiple counts of the same collision, filter some of them.\n        if self._collision_id == event.other_actor.id:\n            return\n        if self._collision_location:\n            distance_vector = actor_location - self._collision_location\n            if distance_vector.length() <= self.COLLISION_RADIUS:\n                return\n\n        # If the actor speed is 0, the collision isn't its fault\n        if CarlaDataProvider.get_velocity(self.actor) < self.EPSILON:\n            return\n\n        # The collision is valid, save the data\n        self.test_status = \"FAILURE\"\n        self.actual_value += 1\n\n        self._collision_time = GameTime.get_time()\n        self._collision_location = actor_location\n        if event.other_actor.id != 0: # Number 0: static objects -> ignore it\n            self._collision_id = event.other_actor.id\n\n        if ('static' in event.other_actor.type_id or 'traffic' in event.other_actor.type_id) \\\n                and 'sidewalk' not in event.other_actor.type_id:\n            actor_type = TrafficEventType.COLLISION_STATIC\n        elif 'vehicle' in event.other_actor.type_id:\n            actor_type = TrafficEventType.COLLISION_VEHICLE\n        elif 'walker' in event.other_actor.type_id:\n            actor_type = TrafficEventType.COLLISION_PEDESTRIAN\n        else:\n            return\n\n        collision_event = TrafficEvent(event_type=actor_type, frame=GameTime.get_frame())\n        collision_event.set_dict({'other_actor': event.other_actor, 'location': actor_location})\n        collision_event.set_message(\n            \"Agent collided against object with type={} and id={} at (x={}, y={}, z={})\".format(\n                event.other_actor.type_id,\n                event.other_actor.id,\n                round(actor_location.x, 3),\n                round(actor_location.y, 3),\n                round(actor_location.z, 3)))\n        self.events.append(collision_event)\n\n\nclass ActorBlockedTest(Criterion):\n\n    \"\"\"\n    This test will fail if the actor has had its linear velocity lower than a specific value for\n    a specific amount of time\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - min_speed: speed required [m/s]\n    - max_time: Maximum time (in seconds) the actor can remain under the speed threshold\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n\n    def __init__(self, actor, min_speed, max_time, name=\"ActorBlockedTest\", optional=False, terminate_on_failure=False):\n        \"\"\"\n        Class constructor\n        \"\"\"\n        super().__init__(name, actor, optional, terminate_on_failure)\n        self._min_speed = min_speed\n        self._max_time = max_time\n        self._time_last_valid_state = None\n        self._active = True\n        self.units = None  # We care about whether or not it fails, no units attached\n\n    def update(self):\n        \"\"\"\n        Check if the actor speed is above the min_speed\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Deactivate/Activate checking by blackboard message\n        active = py_trees.blackboard.Blackboard().get('AC_SwitchActorBlockedTest')\n        if active is not None:\n            self._active = active\n            self._time_last_valid_state = GameTime.get_time()\n            py_trees.blackboard.Blackboard().set(\"AC_SwitchActorBlockedTest\", None, overwrite=True)\n\n        if self._active:\n            linear_speed = CarlaDataProvider.get_velocity(self.actor)\n            if linear_speed is not None:\n                if linear_speed < self._min_speed and self._time_last_valid_state:\n                    if (GameTime.get_time() - self._time_last_valid_state) > self._max_time:\n                        # The actor has been \"blocked\" for too long, save the data\n                        self.test_status = \"FAILURE\"\n\n                        vehicle_location = CarlaDataProvider.get_location(self.actor)\n                        event = TrafficEvent(event_type=TrafficEventType.VEHICLE_BLOCKED, frame=GameTime.get_frame())\n                        event.set_message('Agent got blocked at (x={}, y={}, z={})'.format(\n                            round(vehicle_location.x, 3),\n                            round(vehicle_location.y, 3),\n                            round(vehicle_location.z, 3))\n                        )\n                        event.set_dict({'location': vehicle_location})\n                        self.events.append(event)\n                else:\n                    self._time_last_valid_state = GameTime.get_time()\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass KeepLaneTest(Criterion):\n    \"\"\"\n    This class contains an atomic test for keeping lane.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, optional=False, name=\"CheckKeepLane\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(KeepLaneTest, self).__init__(name, actor, optional)\n\n        world = self.actor.get_world()\n        blueprint = world.get_blueprint_library().find('sensor.other.lane_invasion')\n        self._lane_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor)\n        self._lane_sensor.listen(lambda event: self._count_lane_invasion(event))\n\n    def update(self):\n        \"\"\"\n        Check lane invasion count\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actual_value > 0:\n            self.test_status = \"FAILURE\"\n        else:\n            self.test_status = \"SUCCESS\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Cleanup sensor\n        \"\"\"\n        if self._lane_sensor is not None:\n            self._lane_sensor.destroy()\n            self._lane_sensor = None\n        super(KeepLaneTest, self).terminate(new_status)\n\n    def _count_lane_invasion(self, event):\n        \"\"\"\n        Callback to update lane invasion count\n        \"\"\"\n        self.actual_value += 1\n\n\nclass ReachedRegionTest(Criterion):\n\n    \"\"\"\n    This class contains the reached region test\n    The test is a success if the actor reaches a specified region\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - min_x, max_x, min_y, max_y: Bounding box of the checked region\n    \"\"\"\n\n    def __init__(self, actor, min_x, max_x, min_y, max_y, name=\"ReachedRegionTest\"):\n        \"\"\"\n        Setup trigger region (rectangle provided by\n        [min_x,min_y] and [max_x,max_y]\n        \"\"\"\n        super(ReachedRegionTest, self).__init__(name, actor)\n        self._min_x = min_x\n        self._max_x = max_x\n        self._min_y = min_y\n        self._max_y = max_y\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        in_region = False\n        if self.test_status != \"SUCCESS\":\n            in_region = (location.x > self._min_x and location.x < self._max_x) and (\n                location.y > self._min_y and location.y < self._max_y)\n            if in_region:\n                self.test_status = \"SUCCESS\"\n            else:\n                self.test_status = \"RUNNING\"\n\n        if self.test_status == \"SUCCESS\":\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass OffRoadTest(Criterion):\n\n    \"\"\"\n    Atomic containing a test to detect when an actor deviates from the driving lanes. This atomic can\n    fail when actor has spent a specific time outside driving lanes (defined by OpenDRIVE). Simplified\n    version of OnSidewalkTest, and doesn't relly on waypoints with *Sidewalk* lane types\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        duration (float): Time spent at sidewalks before the atomic fails.\n            If terminate_on_failure isn't active, this is ignored.\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n            when using the output argument\n        terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met.\n    \"\"\"\n\n    def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name=\"OffRoadTest\"):\n        \"\"\"\n        Setup of the variables\n        \"\"\"\n        super(OffRoadTest, self).__init__(name, actor, optional, terminate_on_failure)\n\n        self._map = CarlaDataProvider.get_map()\n        self._offroad = False\n\n        self._duration = duration\n        self._prev_time = None\n        self._time_offroad = 0\n\n    def update(self):\n        \"\"\"\n        First, transforms the actor's current position to its corresponding waypoint. This is\n        filtered to only use waypoints of type Driving or Parking. Depending on these results,\n        the actor will be considered to be outside (or inside) driving lanes.\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self.actor)\n\n        # Get the waypoint at the current location to see if the actor is offroad\n        drive_waypoint = self._map.get_waypoint(\n            current_location,\n            project_to_road=False\n        )\n        park_waypoint = self._map.get_waypoint(\n            current_location,\n            project_to_road=False,\n            lane_type=carla.LaneType.Parking\n        )\n        if drive_waypoint or park_waypoint:\n            self._offroad = False\n        else:\n            self._offroad = True\n\n        # Counts the time offroad\n        if self._offroad:\n            if self._prev_time is None:\n                self._prev_time = GameTime.get_time()\n            else:\n                curr_time = GameTime.get_time()\n                self._time_offroad += curr_time - self._prev_time\n                self._prev_time = curr_time\n        else:\n            self._prev_time = None\n\n        if self._time_offroad > self._duration:\n            self.test_status = \"FAILURE\"\n\n        if self._terminate_on_failure and self.test_status == \"FAILURE\":\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass EndofRoadTest(Criterion):\n\n    \"\"\"\n    Atomic containing a test to detect when an actor has changed to a different road\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        duration (float): Time spent after ending the road before the atomic fails.\n            If terminate_on_failure isn't active, this is ignored.\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n            when using the output argument\n        terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met.\n    \"\"\"\n\n    def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name=\"EndofRoadTest\"):\n        \"\"\"\n        Setup of the variables\n        \"\"\"\n        super(EndofRoadTest, self).__init__(name, actor, optional, terminate_on_failure)\n\n        self._map = CarlaDataProvider.get_map()\n        self._end_of_road = False\n\n        self._duration = duration\n        self._start_time = None\n        self._time_end_road = 0\n        self._road_id = None\n\n    def update(self):\n        \"\"\"\n        First, transforms the actor's current position to its corresponding waypoint. Then the road id\n        is compared with the initial one and if that's the case, a time is started\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self.actor)\n        current_waypoint = self._map.get_waypoint(current_location)\n\n        # Get the current road id\n        if self._road_id is None:\n            self._road_id = current_waypoint.road_id\n\n        else:\n            # Wait until the actor has left the road\n            if self._road_id != current_waypoint.road_id or self._start_time:\n\n                # Start counting\n                if self._start_time is None:\n                    self._start_time = GameTime.get_time()\n                    return new_status\n\n                curr_time = GameTime.get_time()\n                self._time_end_road = curr_time - self._start_time\n\n                if self._time_end_road > self._duration:\n                    self.test_status = \"FAILURE\"\n                    self.actual_value += 1\n                    return py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass OnSidewalkTest(Criterion):\n\n    \"\"\"\n    Atomic containing a test to detect sidewalk invasions of a specific actor. This atomic can\n    fail when actor has spent a specific time outside driving lanes (defined by OpenDRIVE).\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        duration (float): Time spent at sidewalks before the atomic fails.\n            If terminate_on_failure isn't active, this is ignored.\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n            when using the output argument\n        terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met.\n    \"\"\"\n\n    def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name=\"OnSidewalkTest\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(OnSidewalkTest, self).__init__(name, actor, optional, terminate_on_failure)\n\n        self._map = CarlaDataProvider.get_map()\n        self._onsidewalk_active = False\n        self._outside_lane_active = False\n\n        self._actor_location = self.actor.get_location()\n        self._wrong_sidewalk_distance = 0\n        self._wrong_outside_lane_distance = 0\n        self._sidewalk_start_location = None\n        self._outside_lane_start_location = None\n        self._duration = duration\n        self._prev_time = None\n        self._time_outside_lanes = 0\n\n    def update(self):\n        \"\"\"\n        First, transforms the actor's current position as well as its four corners to their\n        corresponding waypoints. Depending on their lane type, the actor will be considered to be\n        outside (or inside) driving lanes.\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has spent a given duration outside\n                driving lanes and terminate_on_failure is active\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and self.test_status == \"FAILURE\":\n            new_status = py_trees.common.Status.FAILURE\n\n        # Some of the vehicle parameters\n        current_tra = CarlaDataProvider.get_transform(self.actor)\n        current_loc = current_tra.location\n        current_wp = self._map.get_waypoint(current_loc, lane_type=carla.LaneType.Any)\n\n        # Case 1) Car center is at a sidewalk\n        if current_wp.lane_type == carla.LaneType.Sidewalk:\n            if not self._onsidewalk_active:\n                self._onsidewalk_active = True\n                self._sidewalk_start_location = current_loc\n\n        # Case 2) Not inside allowed zones (Driving and Parking)\n        elif current_wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n\n            # Get the vertices of the vehicle\n            heading_vec = current_tra.get_forward_vector()\n            heading_vec.z = 0\n            heading_vec = heading_vec / math.sqrt(math.pow(heading_vec.x, 2) + math.pow(heading_vec.y, 2))\n            perpendicular_vec = carla.Vector3D(-heading_vec.y, heading_vec.x, 0)\n\n            extent = self.actor.bounding_box.extent\n            x_boundary_vector = heading_vec * extent.x\n            y_boundary_vector = perpendicular_vec * extent.y\n\n            bbox = [\n                current_loc + carla.Location(x_boundary_vector - y_boundary_vector),\n                current_loc + carla.Location(x_boundary_vector + y_boundary_vector),\n                current_loc + carla.Location(-1 * x_boundary_vector - y_boundary_vector),\n                current_loc + carla.Location(-1 * x_boundary_vector + y_boundary_vector)]\n\n            bbox_wp = [\n                self._map.get_waypoint(bbox[0], lane_type=carla.LaneType.Any),\n                self._map.get_waypoint(bbox[1], lane_type=carla.LaneType.Any),\n                self._map.get_waypoint(bbox[2], lane_type=carla.LaneType.Any),\n                self._map.get_waypoint(bbox[3], lane_type=carla.LaneType.Any)]\n\n            lane_type_list = [bbox_wp[0].lane_type, bbox_wp[1].lane_type, bbox_wp[2].lane_type, bbox_wp[3].lane_type]\n\n            # Case 2.1) Not quite outside yet\n            if bbox_wp[0].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \\\n                or bbox_wp[1].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \\\n                or bbox_wp[2].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \\\n                    or bbox_wp[3].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking):\n\n                self._onsidewalk_active = False\n                self._outside_lane_active = False\n\n            # Case 2.2) At the mini Shoulders between Driving and Sidewalk\n            elif carla.LaneType.Sidewalk in lane_type_list:\n                if not self._onsidewalk_active:\n                    self._onsidewalk_active = True\n                    self._sidewalk_start_location = current_loc\n\n            else:\n                distance_vehicle_wp = current_loc.distance(current_wp.transform.location)\n\n                # Case 2.3) Outside lane\n                if distance_vehicle_wp >= current_wp.lane_width / 2:\n\n                    if not self._outside_lane_active:\n                        self._outside_lane_active = True\n                        self._outside_lane_start_location = current_loc\n\n                # Case 2.4) Very very edge case (but still inside driving lanes)\n                else:\n                    self._onsidewalk_active = False\n                    self._outside_lane_active = False\n\n        # Case 3) Driving and Parking conditions\n        else:\n            # Check for false positives at junctions\n            if current_wp.is_junction:\n                distance_vehicle_wp = math.sqrt(\n                    math.pow(current_wp.transform.location.x - current_loc.x, 2) +\n                    math.pow(current_wp.transform.location.y - current_loc.y, 2))\n\n                if distance_vehicle_wp <= current_wp.lane_width / 2:\n                    self._onsidewalk_active = False\n                    self._outside_lane_active = False\n                # Else, do nothing, the waypoint is too far to consider it a correct position\n            else:\n\n                self._onsidewalk_active = False\n                self._outside_lane_active = False\n\n        # Counts the time offroad\n        if self._onsidewalk_active or self._outside_lane_active:\n            if self._prev_time is None:\n                self._prev_time = GameTime.get_time()\n            else:\n                curr_time = GameTime.get_time()\n                self._time_outside_lanes += curr_time - self._prev_time\n                self._prev_time = curr_time\n        else:\n            self._prev_time = None\n\n        if self._time_outside_lanes > self._duration:\n            self.test_status = \"FAILURE\"\n\n        # Update the distances\n        distance_vector = CarlaDataProvider.get_location(self.actor) - self._actor_location\n        distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2))\n\n        if distance >= 0.02:  # Used to avoid micro-changes adding to considerable sums\n            self._actor_location = CarlaDataProvider.get_location(self.actor)\n\n            if self._onsidewalk_active:\n                self._wrong_sidewalk_distance += distance\n            elif self._outside_lane_active:\n                # Only add if car is outside the lane but ISN'T in a junction\n                self._wrong_outside_lane_distance += distance\n\n        # Register the sidewalk event\n        if not self._onsidewalk_active and self._wrong_sidewalk_distance > 0:\n\n            self.actual_value += 1\n\n            onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n            self._set_event_dict(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n\n            self._onsidewalk_active = False\n            self._wrong_sidewalk_distance = 0\n            self.events.append(onsidewalk_event)\n\n        # Register the outside of a lane event\n        if not self._outside_lane_active and self._wrong_outside_lane_distance > 0:\n\n            self.actual_value += 1\n\n            outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n            self._set_event_dict(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n\n            self._outside_lane_active = False\n            self._wrong_outside_lane_distance = 0\n            self.events.append(outsidelane_event)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        If there is currently an event running, it is registered\n        \"\"\"\n        # If currently at a sidewalk, register the event\n        if self._onsidewalk_active:\n\n            self.actual_value += 1\n\n            onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n            self._set_event_dict(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n\n            self._onsidewalk_active = False\n            self._wrong_sidewalk_distance = 0\n            self.events.append(onsidewalk_event)\n\n        # If currently outside of our lane, register the event\n        if self._outside_lane_active:\n\n            self.actual_value += 1\n\n            outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n            self._set_event_dict(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n\n            self._outside_lane_active = False\n            self._wrong_outside_lane_distance = 0\n            self.events.append(outsidelane_event)\n\n        super(OnSidewalkTest, self).terminate(new_status)\n\n    def _set_event_message(self, event, location, distance):\n        \"\"\"\n        Sets the message of the event\n        \"\"\"\n        if event.get_type() == TrafficEventType.ON_SIDEWALK_INFRACTION:\n            message_start = 'Agent invaded the sidewalk'\n        else:\n            message_start = 'Agent went outside the lane'\n\n        event.set_message(\n            '{} for about {} meters, starting at (x={}, y={}, z={})'.format(\n                message_start,\n                round(distance, 3),\n                round(location.x, 3),\n                round(location.y, 3),\n                round(location.z, 3)))\n\n    def _set_event_dict(self, event, location, distance):\n        \"\"\"\n        Sets the dictionary of the event\n        \"\"\"\n        event.set_dict({'location': location, 'distance': distance})\n\n\nclass OutsideRouteLanesTest(Criterion):\n\n    \"\"\"\n    Atomic to detect if the vehicle is either on a sidewalk or at a wrong lane. The distance spent outside\n    is computed and it is returned as a percentage of the route distance traveled.\n\n    Args:\n        actor (carla.ACtor): CARLA actor to be used for this test\n        route (list [carla.Location, connection]): series of locations representing the route waypoints\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    ALLOWED_OUT_DISTANCE = 0.5  # At least 0.5, due to the mini-shoulder between lanes and sidewalks\n    MAX_VEHICLE_ANGLE = 120.0  # Maximum angle between the yaw and waypoint lane\n    MAX_WAYPOINT_ANGLE = 150.0  # Maximum change between the yaw-lane angle between frames\n    WINDOWS_SIZE = 3  # Amount of additional waypoints checked (in case the first on fails)\n\n    def __init__(self, actor, route, optional=False, name=\"OutsideRouteLanesTest\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        super(OutsideRouteLanesTest, self).__init__(name, actor, optional)\n        self.units = \"%\"\n\n        self._route = route\n        self._current_index = 0\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n\n        self._map = CarlaDataProvider.get_map()\n        self._last_ego_waypoint = self._map.get_waypoint(self.actor.get_location())\n\n        self._outside_lane_active = False\n        self._wrong_lane_active = False\n        self._last_road_id = None\n        self._last_lane_id = None\n        self._total_distance = 0\n        self._wrong_distance = 0\n        self._wrong_direction_active = True\n\n        self._traffic_event = None\n\n    def update(self):\n        \"\"\"\n        Transforms the actor location and its four corners to waypoints. Depending on its types,\n        the actor will be considered to be at driving lanes, sidewalk or offroad.\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has left driving and terminate_on_failure is active\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Some of the vehicle parameters\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        # Deactivate / activate checking by blackboard message\n        active = py_trees.blackboard.Blackboard().get('AC_SwitchWrongDirectionTest')\n        if active is not None:\n            self._wrong_direction_active = active\n            py_trees.blackboard.Blackboard().set(\"AC_SwitchWrongDirectionTest\", None, overwrite=True)\n\n        self._is_outside_driving_lanes(location)\n        self._is_at_wrong_lane(location)\n\n        if self._outside_lane_active or (self._wrong_direction_active and self._wrong_lane_active):\n            self.test_status = \"FAILURE\"\n\n        # Get the traveled distance\n        for index in range(self._current_index + 1,\n                           min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)):\n            # Get the dot product to know if it has passed this location\n            route_transform = self._route_transforms[index]\n            route_location = route_transform.location\n\n            wp_dir = route_transform.get_forward_vector()  # Waypoint's forward vector\n            wp_veh = location - route_location  # vector waypoint - vehicle\n\n            if wp_veh.dot(wp_dir) > 0:\n                # Get the distance traveled and add it to the total distance\n                prev_route_location = self._route_transforms[self._current_index].location\n                new_dist = prev_route_location.distance(route_location)\n                self._total_distance += new_dist\n\n                # And to the wrong one if outside route lanes\n                if self._outside_lane_active or (self._wrong_direction_active and self._wrong_lane_active):\n                    self._wrong_distance += new_dist\n\n                if self._wrong_distance:\n                    self._set_traffic_event()\n\n                self._current_index = index\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def _set_traffic_event(self):\n        \"\"\"\n        Creates the traffic event / updates it\n        \"\"\"\n        if self._traffic_event is None:\n            self._traffic_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION, frame=GameTime.get_frame())\n            self.events.append(self._traffic_event)\n\n        percentage = self._wrong_distance / self._total_distance * 100\n        self.actual_value = round(percentage, 2)\n\n        self._traffic_event.set_message(\n            \"Agent went outside its route lanes for about {} meters \"\n            \"({}% of the completed route)\".format(\n                round(self._wrong_distance, 3),\n                round(percentage, 2)))\n\n        self._traffic_event.set_dict({\n            'distance': self._wrong_distance,\n            'percentage': percentage\n        })\n\n        self._traffic_event.set_frame(GameTime.get_frame())\n\n    def _is_outside_driving_lanes(self, location):\n        \"\"\"\n        Detects if the ego_vehicle is outside driving lanes\n        \"\"\"\n        driving_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving)\n        parking_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Parking)\n\n        driving_distance = location.distance(driving_wp.transform.location)\n        if parking_wp is not None:  # Some towns have no parking\n            parking_distance = location.distance(parking_wp.transform.location)\n        else:\n            parking_distance = float('inf')\n\n        if driving_distance >= parking_distance:\n            distance = parking_distance\n            lane_width = parking_wp.lane_width\n        else:\n            distance = driving_distance\n            lane_width = driving_wp.lane_width\n\n        self._outside_lane_active = bool(distance > (lane_width / 2 + self.ALLOWED_OUT_DISTANCE))\n\n    def _is_at_wrong_lane(self, location):\n        \"\"\"\n        Detects if the ego_vehicle has invaded a wrong lane\n        \"\"\"\n        waypoint = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving)\n        lane_id = waypoint.lane_id\n        road_id = waypoint.road_id\n\n        # Lanes and roads are too chaotic at junctions\n        if waypoint.is_junction:\n            self._wrong_lane_active = False\n        elif self._last_road_id != road_id or self._last_lane_id != lane_id:\n\n            if self._last_ego_waypoint.is_junction:\n                # Just exited a junction, check the wp direction vs the ego's one\n                wp_yaw = waypoint.transform.rotation.yaw % 360\n                actor_yaw = self.actor.get_transform().rotation.yaw % 360\n                angle = (wp_yaw - actor_yaw) % 360\n\n                if angle < self.MAX_VEHICLE_ANGLE or angle > (360 - self.MAX_VEHICLE_ANGLE):\n                    self._wrong_lane_active = False\n                else:\n                    self._wrong_lane_active = True\n\n            else:\n                # Route direction can be considered continuous, check for a big gap.\n                last_wp_yaw = self._last_ego_waypoint.transform.rotation.yaw % 360\n                wp_yaw = waypoint.transform.rotation.yaw % 360\n                angle = (last_wp_yaw - wp_yaw) % 360\n\n                if angle > self.MAX_WAYPOINT_ANGLE and angle < (360 - self.MAX_WAYPOINT_ANGLE):\n\n                    # Is the ego vehicle going back to the lane, or going out? Take the opposite\n                    self._wrong_lane_active = not bool(self._wrong_lane_active)\n\n        # Remember the last state\n        self._last_lane_id = lane_id\n        self._last_road_id = road_id\n        self._last_ego_waypoint = waypoint\n\n\nclass WrongLaneTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test to detect invasions to wrong direction lanes.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n    MAX_ALLOWED_ANGLE = 120.0\n    MAX_WAYPOINT_ANGLE = 150.0\n\n    def __init__(self, actor, optional=False, name=\"WrongLaneTest\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(WrongLaneTest, self).__init__(name, actor, optional)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._map = CarlaDataProvider.get_map()\n        self._last_lane_id = None\n        self._last_road_id = None\n\n        self._in_lane = True\n        self._wrong_distance = 0\n        self._actor_location = self.actor.get_location()\n        self._previous_lane_waypoint = self._map.get_waypoint(self.actor.get_location())\n        self._wrong_lane_start_location = None\n\n    def update(self):\n        \"\"\"\n        Check lane invasion count\n        \"\"\"\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        lane_waypoint = self._map.get_waypoint(self.actor.get_location())\n        current_lane_id = lane_waypoint.lane_id\n        current_road_id = lane_waypoint.road_id\n\n        if (self._last_road_id != current_road_id or self._last_lane_id != current_lane_id) \\\n                and not lane_waypoint.is_junction:\n            next_waypoint = lane_waypoint.next(2.0)[0]\n\n            if not next_waypoint:\n                return new_status\n\n            # The waypoint route direction can be considered continuous.\n            # Therefore just check for a big gap in waypoint directions.\n            previous_lane_direction = self._previous_lane_waypoint.transform.get_forward_vector()\n            current_lane_direction = lane_waypoint.transform.get_forward_vector()\n\n            p_lane_vector = np.array([previous_lane_direction.x, previous_lane_direction.y])\n            c_lane_vector = np.array([current_lane_direction.x, current_lane_direction.y])\n\n            waypoint_angle = math.degrees(\n                math.acos(np.clip(np.dot(p_lane_vector, c_lane_vector) /\n                                  (np.linalg.norm(p_lane_vector) * np.linalg.norm(c_lane_vector)), -1.0, 1.0)))\n\n            if waypoint_angle > self.MAX_WAYPOINT_ANGLE and self._in_lane:\n\n                self.test_status = \"FAILURE\"\n                self._in_lane = False\n                self.actual_value += 1\n                self._wrong_lane_start_location = self._actor_location\n\n            else:\n                # Reset variables\n                self._in_lane = True\n\n            # Continuity is broken after a junction so check vehicle-lane angle instead\n            if self._previous_lane_waypoint.is_junction:\n\n                vector_wp = np.array([next_waypoint.transform.location.x - lane_waypoint.transform.location.x,\n                                      next_waypoint.transform.location.y - lane_waypoint.transform.location.y])\n\n                vector_actor = np.array([math.cos(math.radians(self.actor.get_transform().rotation.yaw)),\n                                         math.sin(math.radians(self.actor.get_transform().rotation.yaw))])\n\n                vehicle_lane_angle = math.degrees(\n                    math.acos(np.clip(np.dot(vector_actor, vector_wp) / (np.linalg.norm(vector_wp)), -1.0, 1.0)))\n\n                if vehicle_lane_angle > self.MAX_ALLOWED_ANGLE:\n\n                    self.test_status = \"FAILURE\"\n                    self._in_lane = False\n                    self.actual_value += 1\n                    self._wrong_lane_start_location = self.actor.get_location()\n\n        # Keep adding \"meters\" to the counter\n        distance_vector = self.actor.get_location() - self._actor_location\n        distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2))\n\n        if distance >= 0.02:  # Used to avoid micro-changes adding add to considerable sums\n            self._actor_location = CarlaDataProvider.get_location(self.actor)\n\n            if not self._in_lane and not lane_waypoint.is_junction:\n                self._wrong_distance += distance\n\n        # Register the event\n        if self._in_lane and self._wrong_distance > 0:\n\n            wrong_way_event = TrafficEvent(event_type=TrafficEventType.WRONG_WAY_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(wrong_way_event, self._wrong_lane_start_location,\n                                    self._wrong_distance, current_road_id, current_lane_id)\n            self._set_event_dict(wrong_way_event, self._wrong_lane_start_location,\n                                 self._wrong_distance, current_road_id, current_lane_id)\n\n            self.events.append(wrong_way_event)\n            self._wrong_distance = 0\n\n        # Remember the last state\n        self._last_lane_id = current_lane_id\n        self._last_road_id = current_road_id\n        self._previous_lane_waypoint = lane_waypoint\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        If there is currently an event running, it is registered\n        \"\"\"\n        if not self._in_lane:\n\n            lane_waypoint = self._map.get_waypoint(self.actor.get_location())\n            current_lane_id = lane_waypoint.lane_id\n            current_road_id = lane_waypoint.road_id\n\n            wrong_way_event = TrafficEvent(event_type=TrafficEventType.WRONG_WAY_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(wrong_way_event, self._wrong_lane_start_location,\n                                    self._wrong_distance, current_road_id, current_lane_id)\n            self._set_event_dict(wrong_way_event, self._wrong_lane_start_location,\n                                 self._wrong_distance, current_road_id, current_lane_id)\n\n            self._wrong_distance = 0\n            self._in_lane = True\n            self.events.append(wrong_way_event)\n\n        super(WrongLaneTest, self).terminate(new_status)\n\n    def _set_event_message(self, event, location, distance, road_id, lane_id):\n        \"\"\"\n        Sets the message of the event\n        \"\"\"\n\n        event.set_message(\n            \"Agent invaded a lane in opposite direction for {} meters, starting at (x={}, y={}, z={}). \"\n            \"road_id={}, lane_id={}\".format(\n                round(distance, 3),\n                round(location.x, 3),\n                round(location.y, 3),\n                round(location.z, 3),\n                road_id,\n                lane_id))\n\n    def _set_event_dict(self, event, location, distance, road_id, lane_id):\n        \"\"\"\n        Sets the dictionary of the event\n        \"\"\"\n        event.set_dict({\n            'location': location,\n            'distance': distance,\n            'road_id': road_id,\n            'lane_id': lane_id})\n\n\nclass InRadiusRegionTest(Criterion):\n\n    \"\"\"\n    The test is a success if the actor is within a given radius of a specified region\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - x, y, radius: Position (x,y) and radius (in meters) used to get the checked region\n    \"\"\"\n\n    def __init__(self, actor, x, y, radius, name=\"InRadiusRegionTest\"):\n        \"\"\"\n        \"\"\"\n        super(InRadiusRegionTest, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._x = x     # pylint: disable=invalid-name\n        self._y = y     # pylint: disable=invalid-name\n        self._radius = radius\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        if self.test_status != \"SUCCESS\":\n            in_radius = math.sqrt(((location.x - self._x)**2) + ((location.y - self._y)**2)) < self._radius\n            if in_radius:\n                route_completion_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETED, frame=GameTime.get_frame())\n                route_completion_event.set_message(\"Destination was successfully reached\")\n                self.events.append(route_completion_event)\n                self.test_status = \"SUCCESS\"\n            else:\n                self.test_status = \"RUNNING\"\n\n        if self.test_status == \"SUCCESS\":\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InRouteTest(Criterion):\n\n    \"\"\"\n    The test is a success if the actor is never outside route. The actor can go outside of the route\n    but only for a certain amount of distance\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - route: Route to be checked\n    - offroad_max: Maximum distance (in meters) the actor can deviate from the route\n    - offroad_min: Maximum safe distance (in meters). Might eventually cause failure\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    MAX_ROUTE_PERCENTAGE = 30  # %\n    WINDOWS_SIZE = 5  # Amount of additional waypoints checked\n\n    def __init__(self, actor, route, offroad_min=None, offroad_max=30, name=\"InRouteTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super(InRouteTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self.units = None  # We care about whether or not it fails, no units attached\n\n        self._route = route\n        self._offroad_max = offroad_max\n        # Unless specified, halve of the max value\n        if offroad_min is None:\n            self._offroad_min = self._offroad_max / 2\n        else:\n            self._offroad_min = self._offroad_min\n\n        self._world = CarlaDataProvider.get_world()\n        self._route_transforms, _ = zip(*self._route)\n        self._route_length = len(self._route)\n        self._current_index = 0\n        self._out_route_distance = 0\n        self._in_safe_route = True\n\n        self._accum_meters = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            loc = tran.location\n            d = loc.distance(prev_loc)\n            accum = 0 if i == 0 else self._accum_meters[i - 1]\n\n            self._accum_meters.append(d + accum)\n            prev_loc = loc\n\n        # Blackboard variable\n        blackv = py_trees.blackboard.Blackboard()\n        _ = blackv.set(\"InRoute\", True)\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        elif self.test_status in ('RUNNING', 'INIT'):\n\n            off_route = True\n\n            shortest_distance = float('inf')\n            closest_index = -1\n\n            # Get the closest distance\n            for index in range(self._current_index,\n                               min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)):\n                ref_location = self._route_transforms[index].location\n                distance = math.sqrt(((location.x - ref_location.x) ** 2) + ((location.y - ref_location.y) ** 2))\n                if distance <= shortest_distance:\n                    closest_index = index\n                    shortest_distance = distance\n\n            if closest_index == -1 or shortest_distance == float('inf'):\n                return new_status\n\n            # Check if the actor is out of route\n            if shortest_distance < self._offroad_max:\n                off_route = False\n                self._in_safe_route = bool(shortest_distance < self._offroad_min)\n\n            # If actor advanced a step, record the distance\n            if self._current_index != closest_index:\n\n                new_dist = self._accum_meters[closest_index] - self._accum_meters[self._current_index]\n\n                # If too far from the route, add it and check if its value\n                if not self._in_safe_route:\n                    self._out_route_distance += new_dist\n                    out_route_percentage = 100 * self._out_route_distance / self._accum_meters[-1]\n                    if out_route_percentage > self.MAX_ROUTE_PERCENTAGE:\n                        off_route = True\n\n                self._current_index = closest_index\n\n            if off_route:\n                # Blackboard variable\n                blackv = py_trees.blackboard.Blackboard()\n                _ = blackv.set(\"InRoute\", False)\n\n                route_deviation_event = TrafficEvent(event_type=TrafficEventType.ROUTE_DEVIATION, frame=GameTime.get_frame())\n                route_deviation_event.set_message(\n                    \"Agent deviated from the route at (x={}, y={}, z={})\".format(\n                        round(location.x, 3),\n                        round(location.y, 3),\n                        round(location.z, 3)))\n                route_deviation_event.set_dict({'location': location})\n\n                self.events.append(route_deviation_event)\n\n                self.test_status = \"FAILURE\"\n                self.actual_value += 1\n                new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass RouteCompletionTest(Criterion):\n\n    \"\"\"\n    Check at which stage of the route is the actor at each tick\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - route: Route to be checked\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    WINDOWS_SIZE = 2\n\n    # Thresholds to return that a route has been completed\n    DISTANCE_THRESHOLD = 10.0  # meters\n    PERCENTAGE_THRESHOLD = 99  # %\n\n    def __init__(self, actor, route, name=\"RouteCompletionTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super(RouteCompletionTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self.units = \"%\"\n        self.success_value = 100\n        self._route = route\n        self._map = CarlaDataProvider.get_map()\n\n        self._index = 0\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n        self._route_accum_perc = self._get_acummulated_percentages()\n\n        self.target_location = self._route_transforms[-1].location\n\n        self._traffic_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETION, frame=0)\n        self._traffic_event.set_dict({'route_completed': self.actual_value})\n        self._traffic_event.set_message(\"Agent has completed {} of the route\".format(self.actual_value))\n        self.events.append(self._traffic_event)\n\n    def _get_acummulated_percentages(self):\n        \"\"\"Gets the accumulated percentage of each of the route transforms\"\"\"\n        accum_meters = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            d = tran.location.distance(prev_loc)\n            new_d = 0 if i == 0 else accum_meters[i - 1]\n\n            accum_meters.append(d + new_d)\n            prev_loc = tran.location\n\n        max_dist = accum_meters[-1]\n        return [x / max_dist * 100 for x in accum_meters]\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        elif self.test_status in ('RUNNING', 'INIT'):\n\n            for index in range(self._index, min(self._index + self.WINDOWS_SIZE + 1, self._route_length)):\n                # Get the dot product to know if it has passed this location\n                route_transform = self._route_transforms[index]\n                route_location = route_transform.location\n                wp_dir = route_transform.get_forward_vector()          # Waypoint's forward vector\n                wp_veh = location - route_location                     # vector route - vehicle\n\n                if wp_veh.dot(wp_dir) > 0:\n                    self._index = index\n                    self.actual_value = self._route_accum_perc[self._index]\n\n            self.actual_value = round(self.actual_value, 2)\n            self._traffic_event.set_dict({'route_completed': self.actual_value})\n            self._traffic_event.set_message(\"Agent has completed {} of the route\".format(self.actual_value))\n\n            if self.actual_value > self.PERCENTAGE_THRESHOLD \\\n                    and location.distance(self.target_location) < self.DISTANCE_THRESHOLD:\n                self.test_status = \"SUCCESS\"\n                self.actual_value = 100\n\n        elif self.test_status == \"SUCCESS\":\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set test status to failure if not successful and terminate\n        \"\"\"\n        self.actual_value = round(self.actual_value, 2)\n\n        self._traffic_event.set_dict({'route_completed': self.actual_value})\n        self._traffic_event.set_message(\"Agent has completed {} of the route\".format(self.actual_value))\n\n        if self.test_status == \"INIT\":\n            self.test_status = \"FAILURE\"\n        super(RouteCompletionTest, self).terminate(new_status)\n\n\nclass RunningRedLightTest(Criterion):\n\n    \"\"\"\n    Check if an actor is running a red light\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    DISTANCE_LIGHT = 15  # m\n\n    def __init__(self, actor, name=\"RunningRedLightTest\", terminate_on_failure=False):\n        \"\"\"\n        Init\n        \"\"\"\n        super(RunningRedLightTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._list_traffic_lights = []\n        self._last_red_light_id = None\n        self.debug = False\n\n        all_actors = CarlaDataProvider.get_all_actors()\n        for _actor in all_actors:\n            if 'traffic_light' in _actor.type_id:\n                center, waypoints = self.get_traffic_light_waypoints(_actor)\n                self._list_traffic_lights.append((_actor, center, waypoints))\n\n    # pylint: disable=no-self-use\n    def is_vehicle_crossing_line(self, seg1, seg2):\n        \"\"\"\n        check if vehicle crosses a line segment\n        \"\"\"\n        line1 = shapely.geometry.LineString([(seg1[0].x, seg1[0].y), (seg1[1].x, seg1[1].y)])\n        line2 = shapely.geometry.LineString([(seg2[0].x, seg2[0].y), (seg2[1].x, seg2[1].y)])\n        inter = line1.intersection(line2)\n\n        return not inter.is_empty\n\n    def update(self):\n        \"\"\"\n        Check if the actor is running a red light\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        transform = CarlaDataProvider.get_transform(self.actor)\n        location = transform.location\n        if location is None:\n            return new_status\n\n        veh_extent = self.actor.bounding_box.extent.x\n\n        tail_close_pt = self.rotate_point(carla.Vector3D(-0.8 * veh_extent, 0, 0), transform.rotation.yaw)\n        tail_close_pt = location + carla.Location(tail_close_pt)\n\n        tail_far_pt = self.rotate_point(carla.Vector3D(-veh_extent - 1, 0, 0), transform.rotation.yaw)\n        tail_far_pt = location + carla.Location(tail_far_pt)\n\n        for traffic_light, center, waypoints in self._list_traffic_lights:\n\n            if self.debug:\n                z = 2.1\n                if traffic_light.state == carla.TrafficLightState.Red:\n                    color = carla.Color(155, 0, 0)\n                elif traffic_light.state == carla.TrafficLightState.Green:\n                    color = carla.Color(0, 155, 0)\n                else:\n                    color = carla.Color(155, 155, 0)\n                self._world.debug.draw_point(center + carla.Location(z=z), size=0.2, color=color, life_time=0.01)\n                for wp in waypoints:\n                    text = \"{}.{}\".format(wp.road_id, wp.lane_id)\n                    self._world.debug.draw_string(\n                        wp.transform.location + carla.Location(x=1, z=z), text, color=color, life_time=0.01)\n                    self._world.debug.draw_point(\n                        wp.transform.location + carla.Location(z=z), size=0.1, color=color, life_time=0.01)\n\n            center_loc = carla.Location(center)\n\n            if self._last_red_light_id and self._last_red_light_id == traffic_light.id:\n                continue\n            if center_loc.distance(location) > self.DISTANCE_LIGHT:\n                continue\n            if traffic_light.state != carla.TrafficLightState.Red:\n                continue\n\n            for wp in waypoints:\n\n                tail_wp = self._map.get_waypoint(tail_far_pt)\n\n                # Calculate the dot product (Might be unscaled, as only its sign is important)\n                ve_dir = CarlaDataProvider.get_transform(self.actor).get_forward_vector()\n                wp_dir = wp.transform.get_forward_vector()\n\n                # Check the lane until all the \"tail\" has passed\n                if tail_wp.road_id == wp.road_id and tail_wp.lane_id == wp.lane_id and ve_dir.dot(wp_dir) > 0:\n                    # This light is red and is affecting our lane\n                    yaw_wp = wp.transform.rotation.yaw\n                    lane_width = wp.lane_width\n                    location_wp = wp.transform.location\n\n                    lft_lane_wp = self.rotate_point(carla.Vector3D(0.6 * lane_width, 0, 0), yaw_wp + 90)\n                    lft_lane_wp = location_wp + carla.Location(lft_lane_wp)\n                    rgt_lane_wp = self.rotate_point(carla.Vector3D(0.6 * lane_width, 0, 0), yaw_wp - 90)\n                    rgt_lane_wp = location_wp + carla.Location(rgt_lane_wp)\n\n                    # Is the vehicle traversing the stop line?\n                    if self.is_vehicle_crossing_line((tail_close_pt, tail_far_pt), (lft_lane_wp, rgt_lane_wp)):\n\n                        self.test_status = \"FAILURE\"\n                        self.actual_value += 1\n                        location = traffic_light.get_transform().location\n                        red_light_event = TrafficEvent(event_type=TrafficEventType.TRAFFIC_LIGHT_INFRACTION, frame=GameTime.get_frame())\n                        red_light_event.set_message(\n                            \"Agent ran a red light {} at (x={}, y={}, z={})\".format(\n                                traffic_light.id,\n                                round(location.x, 3),\n                                round(location.y, 3),\n                                round(location.z, 3)))\n                        red_light_event.set_dict({'id': traffic_light.id, 'location': location})\n\n                        self.events.append(red_light_event)\n                        self._last_red_light_id = traffic_light.id\n                        break\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def rotate_point(self, point, angle):\n        \"\"\"\n        rotate a given point by a given angle\n        \"\"\"\n        x_ = math.cos(math.radians(angle)) * point.x - math.sin(math.radians(angle)) * point.y\n        y_ = math.sin(math.radians(angle)) * point.x + math.cos(math.radians(angle)) * point.y\n        return carla.Vector3D(x_, y_, point.z)\n\n    def get_traffic_light_waypoints(self, traffic_light):\n        \"\"\"\n        get area of a given traffic light\n        \"\"\"\n        base_transform = traffic_light.get_transform()\n        base_rot = base_transform.rotation.yaw\n        area_loc = base_transform.transform(traffic_light.trigger_volume.location)\n\n        # Discretize the trigger box into points\n        area_ext = traffic_light.trigger_volume.extent\n        x_values = np.arange(-0.9 * area_ext.x, 0.9 * area_ext.x, 1.0)  # 0.9 to avoid crossing to adjacent lanes\n\n        area = []\n        for x in x_values:\n            point = self.rotate_point(carla.Vector3D(x, 0, area_ext.z), base_rot)\n            point_location = area_loc + carla.Location(x=point.x, y=point.y)\n            area.append(point_location)\n\n        # Get the waypoints of these points, removing duplicates\n        ini_wps = []\n        for pt in area:\n            wpx = self._map.get_waypoint(pt)\n            # As x_values are arranged in order, only the last one has to be checked\n            if not ini_wps or ini_wps[-1].road_id != wpx.road_id or ini_wps[-1].lane_id != wpx.lane_id:\n                ini_wps.append(wpx)\n\n        # Advance them until the intersection\n        wps = []\n        for wpx in ini_wps:\n            while not wpx.is_intersection:\n                next_wp = wpx.next(0.5)[0]\n                if next_wp and not next_wp.is_intersection:\n                    wpx = next_wp\n                else:\n                    break\n            wps.append(wpx)\n\n        return area_loc, wps\n\n\nclass RunningStopTest(Criterion):\n\n    \"\"\"\n    Check if an actor is running a stop sign\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    PROXIMITY_THRESHOLD = 4.0  # Stops closer than this distance will be detected [m]\n    SPEED_THRESHOLD = 0.1 # Minimum speed to consider the actor has stopped [m/s]\n    WAYPOINT_STEP = 0.5  # m\n\n    def __init__(self, actor, name=\"RunningStopTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super(RunningStopTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._list_stop_signs = []\n        self._target_stop_sign = None\n        self._stop_completed = False\n\n        self._last_failed_stop = None\n\n        for _actor in CarlaDataProvider.get_all_actors():\n            if 'traffic.stop' in _actor.type_id:\n                self._list_stop_signs.append(_actor)\n\n    def point_inside_boundingbox(self, point, bb_center, bb_extent, multiplier=1.2):\n        \"\"\"Checks whether or not a point is inside a bounding box.\"\"\"\n\n        # pylint: disable=invalid-name\n        A = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        B = carla.Vector2D(bb_center.x + multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        D = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y + multiplier * bb_extent.y)\n        M = carla.Vector2D(point.x, point.y)\n\n        AB = B - A\n        AD = D - A\n        AM = M - A\n        am_ab = AM.x * AB.x + AM.y * AB.y\n        ab_ab = AB.x * AB.x + AB.y * AB.y\n        am_ad = AM.x * AD.x + AM.y * AD.y\n        ad_ad = AD.x * AD.x + AD.y * AD.y\n\n        return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad  # pylint: disable=chained-comparison\n\n    def is_actor_affected_by_stop(self, wp_list, stop):\n        \"\"\"\n        Check if the given actor is affected by the stop.\n        Without using waypoints, a stop might not be detected if the actor is moving at the lane edge.\n        \"\"\"\n        # Quick distance test\n        stop_location = stop.get_transform().transform(stop.trigger_volume.location)\n        actor_location = wp_list[0].transform.location\n        if stop_location.distance(actor_location) > self.PROXIMITY_THRESHOLD:\n            return False\n\n        # Check if the any of the actor wps is inside the stop's bounding box.\n        # Using more than one waypoint removes issues with small trigger volumes and backwards movement\n        stop_extent = stop.trigger_volume.extent\n        for actor_wp in wp_list:\n            if self.point_inside_boundingbox(actor_wp.transform.location, stop_location, stop_extent):\n                return True\n\n        return False\n\n    def _scan_for_stop_sign(self, actor_transform, wp_list):\n        \"\"\"\n        Check the stop signs to see if any of them affect the actor.\n        Ignore all checks when going backwards or through an opposite direction\"\"\"\n\n        actor_direction = actor_transform.get_forward_vector()\n\n        # Ignore all when going backwards\n        actor_velocity = self.actor.get_velocity()\n        if actor_velocity.dot(actor_direction) < -0.17:  # 100º, just in case\n            return None\n\n        # Ignore all when going in the opposite direction\n        lane_direction = wp_list[0].transform.get_forward_vector()\n        if actor_direction.dot(lane_direction) < -0.17:  # 100º, just in case\n            return None\n\n        for stop in self._list_stop_signs:\n            if self.is_actor_affected_by_stop(wp_list, stop):\n                return stop\n\n    def _get_waypoints(self, actor):\n        \"\"\"Returns a list of waypoints starting from the ego location and a set amount forward\"\"\"\n        wp_list = []\n        steps = int(self.PROXIMITY_THRESHOLD / self.WAYPOINT_STEP)\n\n        # Add the actor location\n        wp = self._map.get_waypoint(actor.get_location())\n        wp_list.append(wp)\n\n        # And its forward waypoints\n        next_wp = wp\n        for _ in range(steps):\n            next_wps = next_wp.next(self.WAYPOINT_STEP)\n            if not next_wps:\n                break\n            next_wp = next_wps[0]\n            wp_list.append(next_wp)\n\n        return wp_list\n\n    def update(self):\n        \"\"\"\n        Check if the actor is running a red light\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_transform = self.actor.get_transform()\n        check_wps = self._get_waypoints(self.actor)\n\n        if not self._target_stop_sign:\n            self._target_stop_sign = self._scan_for_stop_sign(actor_transform, check_wps)\n            return new_status\n\n        if not self._stop_completed:\n            current_speed = CarlaDataProvider.get_velocity(self.actor)\n            if current_speed < self.SPEED_THRESHOLD:\n                self._stop_completed = True\n\n        if not self.is_actor_affected_by_stop(check_wps, self._target_stop_sign):\n            if not self._stop_completed and self._last_failed_stop != self._target_stop_sign.id:\n                # did we stop?\n                self.actual_value += 1\n                self.test_status = \"FAILURE\"\n                stop_location = self._target_stop_sign.get_transform().location\n                running_stop_event = TrafficEvent(event_type=TrafficEventType.STOP_INFRACTION, frame=GameTime.get_frame())\n                running_stop_event.set_message(\n                    \"Agent ran a stop with id={} at (x={}, y={}, z={})\".format(\n                        self._target_stop_sign.id,\n                        round(stop_location.x, 3),\n                        round(stop_location.y, 3),\n                        round(stop_location.z, 3)))\n                running_stop_event.set_dict({'id': self._target_stop_sign.id, 'location': stop_location})\n\n                self.events.append(running_stop_event)\n\n                self._last_failed_stop = self._target_stop_sign.id\n\n            # Reset state\n            self._target_stop_sign = None\n            self._stop_completed = False\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass MinimumSpeedRouteTest(Criterion):\n\n    \"\"\"\n    Check at which stage of the route is the actor at each tick\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - route: Route to be checked\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    WINDOWS_SIZE = 2\n    RATIO = 1\n\n    def __init__(self, actor, route, checkpoints=1, name=\"MinimumSpeedRouteTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super().__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self.units = \"%\"\n        self.success_value = 100\n        self.actual_value = 100\n\n        self._route = route\n        self._accum_dist = []\n        prev_trans = None\n        for trans, _ in route:\n            if prev_trans:\n                dist = trans.location.distance(prev_trans.location)\n                self._accum_dist.append(dist + self._accum_dist[-1])\n            else:\n                self._accum_dist.append(0)\n            prev_trans = trans\n        self._route_length = len(self._route)\n\n        self._checkpoints = checkpoints\n        self._checkpoint_dist = self._accum_dist[-1] / self._checkpoints\n\n        self._mean_speed = 0\n        self._actor_speed = 0\n        self._speed_points = 0\n\n        self._current_dist = 0\n        self._checkpoint_values = []\n\n        self._index = 0\n\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        # Check the actor progress through the route \n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        for index in range(self._index, min(self._index + self.WINDOWS_SIZE + 1, self._route_length)):\n            # Get the dot product to know if it has passed this location\n            route_transform = self._route[index][0]\n            route_location = route_transform.location\n            wp_dir = route_transform.get_forward_vector()\n            wp_veh = location - route_location\n\n            if wp_veh.dot(wp_dir) > 0:\n                self._index = index\n\n        if self._accum_dist[self._index] - self._current_dist > self._checkpoint_dist:\n            self._set_traffic_event()\n            self._current_dist = self._accum_dist[self._index]\n            self._mean_speed = 0\n            self._actor_speed = 0\n            self._speed_points = 0\n\n        # Get the actor speed\n        velocity = CarlaDataProvider.get_velocity(self.actor)\n        if velocity is None:\n            return new_status\n\n        # Get the speed of the surrounding Background Activity\n        all_vehicles = CarlaDataProvider.get_all_actors().filter('vehicle*')\n        background_vehicles = [v for v in all_vehicles if v.attributes['role_name'] == 'background']\n\n        if background_vehicles:\n            frame_mean_speed = 0\n            for vehicle in background_vehicles:\n                frame_mean_speed += CarlaDataProvider.get_velocity(vehicle)\n            frame_mean_speed /= len(background_vehicles)\n\n            # Record the data\n            self._mean_speed += frame_mean_speed\n            self._actor_speed += velocity\n            self._speed_points += 1\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def _set_traffic_event(self):\n\n        if self._speed_points > 0 and self._mean_speed:\n            self._mean_speed /= self._speed_points\n            self._actor_speed /= self._speed_points\n            checkpoint_value = round(self._actor_speed / (self.RATIO * self._mean_speed) * 100, 2)\n        else:\n            checkpoint_value = 100\n        \n        self.test_status = \"FAILURE\"\n        self._traffic_event = TrafficEvent(TrafficEventType.MIN_SPEED_INFRACTION, GameTime.get_frame())\n        self._traffic_event.set_dict({'percentage': checkpoint_value})\n        self._traffic_event.set_message(f\"Average speed is {checkpoint_value}% of the surrounding traffic's one\")\n        self.events.append(self._traffic_event)\n\n        self._checkpoint_values.append(checkpoint_value)\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set the actual value as a percentage of the two mean speeds,\n        the test status to failure if not successful and terminate\n        \"\"\"\n        # Routes end at around 99%, so make sure the last checkpoint is recorded\n        if self._accum_dist[self._index] / self._accum_dist[-1] > 0.95:\n            self._set_traffic_event()\n\n        if len(self._checkpoint_values):\n            self.actual_value = round(sum(self._checkpoint_values) / len(self._checkpoint_values), 2)\n        super().terminate(new_status)\n\n\nclass YieldToEmergencyVehicleTest(Criterion):\n\n    \"\"\"\n    Atomic Criterion to detect if the actor yields its lane to the emergency vehicle behind it.\n    Detection is done by checking if the ev is in front of the actor\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        ev (carla.Actor): The emergency vehicle\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    WAITING_TIME_THRESHOLD = 15 # Maximum time for actor to block ev\n\n    def __init__(self, actor, ev, optional=False, name=\"YieldToEmergencyVehicleTest\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        self._ev = ev\n        self._terminated = False\n        super().__init__(name, actor, optional)\n\n    def update(self):\n        \"\"\"\n        Monitor that the EV ends up in front of the actor\n\n        returns:\n            py_trees.common.Status.RUNNING\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_location = CarlaDataProvider.get_location(self.actor)\n        if not actor_location:\n            return new_status\n        ev_location = CarlaDataProvider.get_location(self._ev)\n        if not ev_location:\n            return new_status\n\n        ev_direction = CarlaDataProvider.get_transform(self._ev).get_forward_vector()\n        actor_ev_vector = actor_location - ev_location\n\n        if ev_direction.dot(actor_ev_vector) > 0:\n            self.test_status = \"FAILURE\"\n        else:\n            self.test_status = \"SUCCESS\"\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Set the traffic event, if needed\"\"\"\n        # Terminates are called multiple times. Do this only once\n        if not self._terminated:\n            if self.test_status == \"FAILURE\":\n                traffic_event = TrafficEvent(TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE, GameTime.get_frame())\n                traffic_event.set_message(\"Agent failed to yield to an emergency vehicle\")\n                self.events.append(traffic_event)\n\n            self._terminated = True\n\n        super().terminate(new_status)\n\n\nclass ScenarioTimeoutTest(Criterion):\n\n    \"\"\"\n    Atomic Criterion to detect if the actor has been incapable of finishing an scenario\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, scenario_name, optional=False, name=\"ScenarioTimeoutTest\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        super().__init__(name, actor, optional)\n        self.success_value = 0\n        self.actual_value = 0\n        self._scenario_name = scenario_name\n\n    def update(self):\n        \"\"\"wait\"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"check the blackboard for the data and update the criteria if one found\"\"\"\n\n        blackboard_name = f\"ScenarioTimeout_{self._scenario_name}\"\n\n        timeout = py_trees.blackboard.Blackboard().get(blackboard_name)\n        if timeout:\n            self.actual_value = 1\n            self.test_status = \"FAILURE\"\n\n            traffic_event = TrafficEvent(event_type=TrafficEventType.SCENARIO_TIMEOUT, frame=GameTime.get_frame())\n            traffic_event.set_message(\"Agent timed out a scenario\")\n            self.events.append(traffic_event)\n        py_trees.blackboard.Blackboard().set(blackboard_name, None, True)\n\n        super().terminate(new_status)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all atomic scenario behaviors that reflect\ntrigger conditions to either activate another behavior, or to stop\nanother behavior.\n\nFor example, such a condition could be \"InTriggerRegion\", which checks\nthat a given actor reached a certain region on the map, and then starts/stops\na behavior of this actor.\n\nThe atomics are implemented with py_trees and make use of the AtomicCondition\nbase class\n\"\"\"\n\nfrom __future__ import print_function\n\nimport operator\nimport datetime\nimport math\nimport py_trees\nimport carla\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import calculate_distance\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.tools.scenario_helper import get_distance_along_route, get_distance_between_actors\n\nimport srunner.tools as sr_tools\n\nEPSILON = 0.001\n\n\nclass AtomicCondition(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Base class for all atomic conditions used to setup a scenario\n\n    *All behaviors should use this class as parent*\n\n    Important parameters:\n    - name: Name of the atomic condition\n    \"\"\"\n\n    def __init__(self, name):\n        \"\"\"\n        Default init. Has to be called via super from derived class\n        \"\"\"\n        super(AtomicCondition, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self.name = name\n\n    def setup(self, unused_timeout=15):\n        \"\"\"\n        Default setup\n        \"\"\"\n        self.logger.debug(\"%s.setup()\" % (self.__class__.__name__))\n        return True\n\n    def initialise(self):\n        \"\"\"\n        Initialise setup\n        \"\"\"\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        self.logger.debug(\"%s.terminate()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n\nclass InTriggerDistanceToOSCPosition(AtomicCondition):\n\n    \"\"\"\n    OpenSCENARIO atomic\n    This class contains the trigger condition for a distance to an OpenSCENARIO position\n\n    Args:\n        actor (carla.Actor): CARLA actor to execute the behavior\n        osc_position (str): OpenSCENARIO position\n        distance (float): Trigger distance between the actor and the target location in meters\n        name (str): Name of the condition\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the openSCENARIO position\n    \"\"\"\n\n    def __init__(self, actor, osc_position, distance, along_route=False,\n                 comparison_operator=operator.lt, name=\"InTriggerDistanceToOSCPosition\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTriggerDistanceToOSCPosition, self).__init__(name)\n        self._actor = actor\n        self._osc_position = osc_position\n        self._distance = distance\n        self._along_route = along_route\n        self._comparison_operator = comparison_operator\n        self._map = CarlaDataProvider.get_map()\n\n        if self._along_route:\n            # Get the global route planner, used to calculate the route\n            self._grp = GlobalRoutePlanner(self._map, 0.5)\n        else:\n            self._grp = None\n\n    def initialise(self):\n        if self._distance < 0:\n            raise ValueError(\"distance value must be positive\")\n\n    def update(self):\n        \"\"\"\n        Check if actor is in trigger distance\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # calculate transform with method in openscenario_parser.py\n        osc_transform = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n            self._osc_position)\n\n        if osc_transform is not None:\n            osc_location = osc_transform.location\n            actor_location = CarlaDataProvider.get_location(self._actor)\n\n            if self._along_route:\n                # Global planner needs a location at a driving lane\n                actor_location = self._map.get_waypoint(actor_location).transform.location\n                osc_location = self._map.get_waypoint(osc_location).transform.location\n\n            distance = calculate_distance(actor_location, osc_location, self._grp)\n\n            if self._comparison_operator(distance, self._distance):\n                new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass InTimeToArrivalToOSCPosition(AtomicCondition):\n\n    \"\"\"\n    OpenSCENARIO atomic\n    This class contains a trigger if an actor arrives within a given time to an OpenSCENARIO position\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - osc_position: OpenSCENARIO position\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - name: Name of the condition\n\n    The condition terminates with SUCCESS, when the actor can reach the position within the given time\n    \"\"\"\n\n    def __init__(self, actor, osc_position, time, along_route=False,\n                 comparison_operator=operator.lt, name=\"InTimeToArrivalToOSCPosition\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTimeToArrivalToOSCPosition, self).__init__(name)\n        self._map = CarlaDataProvider.get_map()\n        self._actor = actor\n        self._osc_position = osc_position\n        self._time = float(time)\n        self._along_route = along_route\n        self._comparison_operator = comparison_operator\n\n        if self._along_route:\n            # Get the global route planner, used to calculate the route\n            self._grp = GlobalRoutePlanner(self._map, 0.5)\n        else:\n            self._grp = None\n\n    def initialise(self):\n        if self._time < 0:\n            raise ValueError(\"time value must be positive\")\n\n    def update(self):\n        \"\"\"\n        Check if actor can arrive within trigger time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # calculate transform with method in openscenario_parser.py\n        try:\n            osc_transform = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n                self._osc_position)\n        except AttributeError:\n            return py_trees.common.Status.FAILURE\n        target_location = osc_transform.location\n        actor_location = CarlaDataProvider.get_location(self._actor)\n\n        if target_location is None or actor_location is None:\n            return new_status\n\n        if self._along_route:\n            # Global planner needs a location at a driving lane\n            actor_location = self._map.get_waypoint(actor_location).transform.location\n            target_location = self._map.get_waypoint(target_location).transform.location\n\n        distance = calculate_distance(actor_location, target_location, self._grp)\n\n        actor_velocity = CarlaDataProvider.get_velocity(self._actor)\n\n        # time to arrival\n        if actor_velocity > 0:\n            time_to_arrival = distance / actor_velocity\n        elif distance == 0:\n            time_to_arrival = 0\n        else:\n            time_to_arrival = float('inf')\n\n        if self._comparison_operator(time_to_arrival, self._time):\n            new_status = py_trees.common.Status.SUCCESS\n        return new_status\n\n\nclass StandStill(AtomicCondition):\n\n    \"\"\"\n    This class contains a standstill behavior of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - duration: Duration of the behavior in seconds\n\n    The condition terminates with SUCCESS, when the actor does not move\n    \"\"\"\n\n    def __init__(self, actor, name, duration=float(\"inf\")):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(StandStill, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n\n        self._duration = duration\n        self._start_time = 0\n\n    def initialise(self):\n        \"\"\"\n        Initialize the start time of this condition\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        super(StandStill, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check if the _actor stands still (v=0)\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        velocity = CarlaDataProvider.get_velocity(self._actor)\n\n        if velocity > EPSILON:\n            self._start_time = GameTime.get_time()\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass RelativeVelocityToOtherActor(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between an actor's velocity\n    and another actor's one. The behavior returns SUCCESS when the\n    expected comparison (greater than / less than / equal to) is achieved\n\n    Args:\n        actor (carla.Actor): actor from which the velocity is taken\n        other_actor (carla.Actor): The actor with the reference velocity\n        speed (float): Difference of speed between the actors\n        name (string): Name of the condition\n        comparison_operator: Type \"operator\", used to compare the two velocities\n    \"\"\"\n\n    def __init__(self, actor, other_actor, speed, comparison_operator=operator.gt,\n                 name=\"RelativeVelocityToOtherActor\"):\n        \"\"\"\n        Setup the parameters\n        \"\"\"\n        super(RelativeVelocityToOtherActor, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._other_actor = other_actor\n        self._relative_speed = speed\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the speed of the two actors and compares them according to the comparison operator\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        curr_speed = CarlaDataProvider.get_velocity(self._actor)\n        other_speed = CarlaDataProvider.get_velocity(self._other_actor)\n\n        relative_speed = curr_speed - other_speed\n\n        if self._comparison_operator(relative_speed, self._relative_speed):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TriggerVelocity(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between an actor's speed and a reference one.\n    The behavior returns SUCCESS when the expected comparison (greater than /\n    less than / equal to) is achieved.\n\n    Args:\n        actor (carla.Actor): CARLA actor from which the speed will be taken.\n        name (string): Name of the atomic\n        target_velocity (float): velcoity to be compared with the actor's one\n        comparison_operator: Type \"operator\", used to compare the two velocities\n    \"\"\"\n\n    def __init__(self, actor, target_velocity, comparison_operator=operator.gt, name=\"TriggerVelocity\"):\n        \"\"\"\n        Setup the atomic parameters\n        \"\"\"\n        super(TriggerVelocity, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._target_velocity = target_velocity\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the speed of the actor and compares it with the reference one\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_speed = CarlaDataProvider.get_velocity(self._actor)\n\n        if self._comparison_operator(actor_speed, self._target_velocity):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TriggerAcceleration(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between an actor's acceleration\n    and a reference one. The behavior returns SUCCESS when the\n    expected comparison (greater than / less than / equal to) is achieved\n\n    Args:\n        actor (carla.Actor): CARLA actor to execute the behavior\n        name (str): Name of the condition\n        target_acceleration (float): Acceleration reference (in m/s^2) on which the success is dependent\n        comparison_operator (operator): Type \"operator\", used to compare the two acceleration\n    \"\"\"\n\n    def __init__(self, actor, target_acceleration, comparison_operator=operator.gt, name=\"TriggerAcceleration\"):\n        \"\"\"\n        Setup trigger acceleration\n        \"\"\"\n        super(TriggerAcceleration, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._target_acceleration = target_acceleration\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the accleration of the actor and compares it with the reference one\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        acceleration = self._actor.get_acceleration()\n        linear_accel = math.sqrt(math.pow(acceleration.x, 2) +\n                                 math.pow(acceleration.y, 2) +\n                                 math.pow(acceleration.z, 2))\n\n        if self._comparison_operator(linear_accel, self._target_acceleration):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TimeOfDayComparison(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between the current time of day of the simulation\n    and a given one. The behavior returns SUCCESS when the\n    expected comparison (greater than / less than / equal to) is achieved\n\n    Args:\n        datetime (datetime): CARLA actor to execute the behavior\n        name (str): Name of the condition\n        target_acceleration (float): Acceleration reference (in m/s^2) on which the success is dependent\n        comparison_operator (operator): Type \"operator\", used to compare the two acceleration\n    \"\"\"\n\n    def __init__(self, dattime, comparison_operator=operator.gt, name=\"TimeOfDayComparison\"):\n        \"\"\"\n        \"\"\"\n        super(TimeOfDayComparison, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._datetime = datetime.datetime.strptime(dattime, \"%Y-%m-%dT%H:%M:%S\")\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the time of day of the simulation and compares it with the reference one\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        try:\n            check_dtime = operator.attrgetter(\"Datetime\")\n            dtime = check_dtime(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if self._comparison_operator(dtime, self._datetime):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass OSCStartEndCondition(AtomicCondition):\n\n    \"\"\"\n    This class contains a check if a named story element has started/terminated.\n\n    Important parameters:\n    - element_name: The story element's name attribute\n    - element_type: The element type [act,scene,maneuver,event,action]\n    - rule: Either START or END\n\n    The condition terminates with SUCCESS, when the named story element starts\n    \"\"\"\n\n    def __init__(self, element_type, element_name, rule, name=\"OSCStartEndCondition\"):\n        \"\"\"\n        Setup element details\n        \"\"\"\n        super(OSCStartEndCondition, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._element_type = element_type.upper()\n        self._element_name = element_name\n        self._rule = rule.upper()\n        self._start_time = None\n        self._blackboard = py_trees.blackboard.Blackboard()\n\n    def initialise(self):\n        \"\"\"\n        Initialize the start time of this condition\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        super(OSCStartEndCondition, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check if the specified story element has started/ended since the beginning of the condition\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if new_status == py_trees.common.Status.RUNNING:\n            blackboard_variable_name = \"({}){}-{}\".format(self._element_type, self._element_name, self._rule)\n            element_start_time = self._blackboard.get(blackboard_variable_name)\n            if element_start_time and element_start_time >= self._start_time:\n                new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerRegion(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger region (condition) of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - min_x, max_x, min_y, max_y: bounding box of the trigger region\n\n    The condition terminates with SUCCESS, when the actor reached the target region\n    \"\"\"\n\n    def __init__(self, actor, min_x, max_x, min_y, max_y, name=\"TriggerRegion\"):\n        \"\"\"\n        Setup trigger region (rectangle provided by\n        [min_x,min_y] and [max_x,max_y]\n        \"\"\"\n        super(InTriggerRegion, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._min_x = min_x\n        self._max_x = max_x\n        self._min_y = min_y\n        self._max_y = max_y\n\n    def update(self):\n        \"\"\"\n        Check if the _actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n\n        if location is None:\n            return new_status\n\n        not_in_region = (location.x < self._min_x or location.x > self._max_x) or \\\n                        (location.y < self._min_y or location.y > self._max_y)\n        if not not_in_region:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToVehicle(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger distance (condition) between to actors\n    of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - reference_actor: Reference CARLA actor\n    - name: Name of the condition\n    - distance: Trigger distance between the two actors in meters\n    - distance_type: Specifies how distance should be calculated between the two actors\n    - freespace: if True distance is calculated between closest boundary points else it will be from center-center\n    - dx, dy, dz: distance to reference_location (location of reference_actor)\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the other actor\n    \"\"\"\n\n    def __init__(self, reference_actor, actor, distance, comparison_operator=operator.lt,\n                 distance_type=\"cartesianDistance\", freespace=False, name=\"TriggerDistanceToVehicle\"):\n        \"\"\"\n        Setup trigger distance\n        \"\"\"\n        super(InTriggerDistanceToVehicle, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._reference_actor = reference_actor\n        self._actor = actor\n        self._distance = distance\n        self._distance_type = distance_type\n        self._freespace = freespace\n        self._comparison_operator = comparison_operator\n\n        if distance_type == \"longitudinal\":\n            self._global_rp = CarlaDataProvider.get_global_route_planner()\n        else:\n            self._global_rp = None\n\n    def update(self):\n        \"\"\"\n        Check if the ego vehicle is within trigger distance to other actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n        reference_location = CarlaDataProvider.get_location(self._reference_actor)\n\n        if location is None or reference_location is None:\n            return new_status\n\n        distance = get_distance_between_actors(\n            self._actor, self._reference_actor, self._distance_type, self._freespace, self._global_rp)\n\n        if self._comparison_operator(distance, self._distance):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToLocation(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger (condition) for a distance to a fixed\n    location of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_location: Reference location (carla.location)\n    - name: Name of the condition\n    - distance: Trigger distance between the actor and the target location in meters\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the given location\n    \"\"\"\n\n    def __init__(self,\n                 actor,\n                 target_location,\n                 distance,\n                 comparison_operator=operator.lt,\n                 name=\"InTriggerDistanceToLocation\"):\n        \"\"\"\n        Setup trigger distance\n        \"\"\"\n        super(InTriggerDistanceToLocation, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._target_location = target_location\n        self._actor = actor\n        self._distance = distance\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Check if the actor is within trigger distance to the target location\n        \"\"\"\n\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n\n        if location is None:\n            return new_status\n\n        if self._comparison_operator(calculate_distance(\n                location, self._target_location), self._distance):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToNextIntersection(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger (condition) for a distance to the\n    next intersection of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - distance: Trigger distance between the actor and the next intersection in meters\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the next intersection\n    \"\"\"\n\n    def __init__(self, actor, distance, name=\"InTriggerDistanceToNextIntersection\"):\n        \"\"\"\n        Setup trigger distance\n        \"\"\"\n        super(InTriggerDistanceToNextIntersection, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._distance = distance\n        self._map = CarlaDataProvider.get_map()\n\n        waypoint = self._map.get_waypoint(self._actor.get_location())\n        while waypoint and not waypoint.is_intersection:\n            waypoint = waypoint.next(1)[-1]\n\n        self._final_location = waypoint.transform.location\n\n    def update(self):\n        \"\"\"\n        Check if the actor is within trigger distance to the intersection\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_waypoint = self._map.get_waypoint(CarlaDataProvider.get_location(self._actor))\n        distance = calculate_distance(current_waypoint.transform.location, self._final_location)\n\n        if distance < self._distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToLocationAlongRoute(AtomicCondition):\n\n    \"\"\"\n    Implementation for a behavior that will check if a given actor\n    is within a given distance to a given location considering a given route\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - distance: Trigger distance between the actor and the next intersection in meters\n    - route: Route to be checked\n    - location: Location on the route to be checked\n\n    The condition terminates with SUCCESS, when the actor reached the target distance\n    along its route to the given location\n    \"\"\"\n\n    def __init__(self, actor, route, location, distance, name=\"InTriggerDistanceToLocationAlongRoute\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(InTriggerDistanceToLocationAlongRoute, self).__init__(name)\n        self._map = CarlaDataProvider.get_map()\n        self._actor = actor\n        self._location = location\n        self._route = route\n        self._distance = distance\n\n        self._location_distance, _ = get_distance_along_route(self._route, self._location)\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self._actor)\n\n        if current_location is None:\n            return new_status\n\n        if current_location.distance(self._location) < self._distance + 20:\n\n            actor_distance, _ = get_distance_along_route(self._route, current_location)\n\n            # If closer than self._distance and hasn't passed the trigger point\n            if (self._location_distance < actor_distance + self._distance and\n                actor_distance < self._location_distance) or \\\n                    self._location_distance < 1.0:\n                new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass InTimeToArrivalToLocation(AtomicCondition):\n\n    \"\"\"\n    This class contains a check if a actor arrives within a given time\n    at a given location.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - location: Location to be checked in this behavior\n\n    The condition terminates with SUCCESS, when the actor can reach the target location within the given time\n    \"\"\"\n\n    _max_time_to_arrival = float('inf')  # time to arrival in seconds\n\n    def __init__(self, actor, time, location, comparison_operator=operator.lt, name=\"TimeToArrival\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTimeToArrivalToLocation, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._time = time\n        self._target_location = location\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Check if the actor can arrive at target_location within time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self._actor)\n\n        if current_location is None:\n            return new_status\n\n        distance = calculate_distance(current_location, self._target_location)\n        velocity = CarlaDataProvider.get_velocity(self._actor)\n\n        # if velocity is too small, simply use a large time to arrival\n        time_to_arrival = self._max_time_to_arrival\n        if velocity > EPSILON:\n            time_to_arrival = distance / velocity\n\n        if self._comparison_operator(time_to_arrival, self._time):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTimeToArrivalToVehicle(AtomicCondition):\n\n    \"\"\"\n    This class contains a check if a actor arrives within a given time\n    at another actor.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - other_actor: Reference actor used in this behavior\n\n    The condition terminates with SUCCESS, when the actor can reach the other vehicle within the given time\n    \"\"\"\n\n    _max_time_to_arrival = float('inf')  # time to arrival in seconds\n\n    def __init__(self, actor, other_actor, time, condition_freespace=False,\n                 along_route=False, comparison_operator=operator.lt, name=\"TimeToArrival\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTimeToArrivalToVehicle, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._map = CarlaDataProvider.get_map()\n        self._actor = actor\n        self._other_actor = other_actor\n        self._time = time\n        self._condition_freespace = condition_freespace\n        self._along_route = along_route\n        self._comparison_operator = comparison_operator\n\n        if self._along_route:\n            # Get the global route planner, used to calculate the route\n            self._grp = GlobalRoutePlanner(self._map, 0.5)\n        else:\n            self._grp = None\n\n    def update(self):\n        \"\"\"\n        Check if the ego vehicle can arrive at other actor within time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self._actor)\n        other_location = CarlaDataProvider.get_location(self._other_actor)\n\n        # Get the bounding boxes\n        if self._condition_freespace:\n            if isinstance(self._actor, (carla.Vehicle, carla.Walker)):\n                actor_extent = self._actor.bounding_box.extent.x\n            else:\n                # Patch, as currently static objects have no bounding boxes\n                actor_extent = 0\n\n            if isinstance(self._other_actor, (carla.Vehicle, carla.Walker)):\n                other_extent = self._other_actor.bounding_box.extent.x\n            else:\n                # Patch, as currently static objects have no bounding boxes\n                other_extent = 0\n\n        if current_location is None or other_location is None:\n            return new_status\n\n        current_velocity = CarlaDataProvider.get_velocity(self._actor)\n        other_velocity = CarlaDataProvider.get_velocity(self._other_actor)\n\n        if self._along_route:\n            # Global planner needs a location at a driving lane\n            current_location = self._map.get_waypoint(current_location).transform.location\n            other_location = self._map.get_waypoint(other_location).transform.location\n\n        distance = calculate_distance(current_location, other_location, self._grp)\n\n        # if velocity is too small, simply use a large time to arrival\n        time_to_arrival = self._max_time_to_arrival\n\n        if current_velocity > other_velocity:\n            if self._condition_freespace:\n                time_to_arrival = (distance - actor_extent - other_extent) / (current_velocity - other_velocity)\n            else:\n                time_to_arrival = distance / (current_velocity - other_velocity)\n\n        if self._comparison_operator(time_to_arrival, self._time):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTimeToArrivalToVehicleSideLane(InTimeToArrivalToLocation):\n\n    \"\"\"\n    This class contains a check if a actor arrives within a given time\n    at another actor's side lane. Inherits from InTimeToArrivalToLocation\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - cut_in_lane: the lane from where the other_actor will do the cut in\n    - other_actor: Reference actor used in this behavior\n\n    The condition terminates with SUCCESS, when the actor can reach the other vehicle within the given time\n    \"\"\"\n\n    _max_time_to_arrival = float('inf')  # time to arrival in seconds\n\n    def __init__(self, actor, other_actor, time, side_lane,\n                 comparison_operator=operator.lt, name=\"InTimeToArrivalToVehicleSideLane\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        self._other_actor = other_actor\n        self._side_lane = side_lane\n\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map(self._world)\n\n        other_location = other_actor.get_transform().location\n        other_waypoint = self._map.get_waypoint(other_location)\n\n        if self._side_lane == 'right':\n            other_side_waypoint = other_waypoint.get_left_lane()\n        elif self._side_lane == 'left':\n            other_side_waypoint = other_waypoint.get_right_lane()\n        else:\n            raise Exception(\"cut_in_lane must be either 'left' or 'right'\")\n\n        other_side_location = other_side_waypoint.transform.location\n\n        super(InTimeToArrivalToVehicleSideLane, self).__init__(\n            actor, time, other_side_location, comparison_operator, name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Check if the ego vehicle can arrive at other actor within time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        other_location = CarlaDataProvider.get_location(self._other_actor)\n        other_waypoint = self._map.get_waypoint(other_location)\n\n        if self._side_lane == 'right':\n            other_side_waypoint = other_waypoint.get_left_lane()\n        elif self._side_lane == 'left':\n            other_side_waypoint = other_waypoint.get_right_lane()\n        else:\n            raise Exception(\"cut_in_lane must be either 'left' or 'right'\")\n        if other_side_waypoint is None:\n            return new_status\n\n        self._target_location = other_side_waypoint.transform.location\n\n        if self._target_location is None:\n            return new_status\n\n        new_status = super(InTimeToArrivalToVehicleSideLane, self).update()\n\n        return new_status\n\n\nclass WaitUntilInFront(AtomicCondition):\n\n    \"\"\"\n    Behavior that support the creation of cut ins. It waits until the actor has passed another actor\n\n    Parameters:\n    - actor: the one getting in front of the other actor\n    - other_actor: the reference vehicle that the actor will have to get in front of\n    - factor: How much in front the actor will have to get (from 0 to infinity):\n        0: They are right next to each other\n        1: The front of the other_actor and the back of the actor are right next to each other\n    \"\"\"\n\n    def __init__(self, actor, other_actor, factor=1, check_distance=True, name=\"WaitUntilInFront\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super(WaitUntilInFront, self).__init__(name)\n        self._actor = actor\n        self._other_actor = other_actor\n        self._distance = 10\n        self._factor = max(EPSILON, factor)  # Must be > 0\n        self._check_distance = check_distance\n\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map(self._world)\n\n        actor_extent = self._actor.bounding_box.extent.x\n        other_extent = self._other_actor.bounding_box.extent.x\n        self._length = self._factor * (actor_extent + other_extent)\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Checks if the two actors meet the requirements\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        in_front = False\n        close_by = False\n\n        # Location of our actor\n        actor_location = CarlaDataProvider.get_location(self._actor)\n        if actor_location is None:\n            return new_status\n\n        # Waypoint in front of the other actor\n        other_location = CarlaDataProvider.get_location(self._other_actor)\n        other_waypoint = self._map.get_waypoint(other_location)\n        if other_waypoint is None:\n            return new_status\n        other_next_waypoints = other_waypoint.next(self._length)\n        if other_next_waypoints is None:\n            return new_status\n        other_next_waypoint = other_next_waypoints[0]\n\n        # Wait for the vehicle to be in front\n        other_dir = other_next_waypoint.transform.get_forward_vector()\n        act_other_dir = actor_location - other_next_waypoint.transform.location\n\n        if other_dir.dot(act_other_dir) > 0.0:\n            in_front = True\n\n        # Wait for it to be close-by\n        if not self._check_distance:\n            close_by = True\n        elif actor_location.distance(other_next_waypoint.transform.location) < self._distance:\n            close_by = True\n\n        if in_front and close_by:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass WaitUntilInFrontPosition(AtomicCondition):\n\n    \"\"\"\n    Behavior that support the creation of cut ins. It waits until the actor has passed another actor\n\n    Parameters:\n    - actor: the one getting in front of the other actor\n    - transform: the reference transform that the actor will have to get in front of\n    \"\"\"\n\n    def __init__(self, actor, transform, check_distance=True, distance=10, name=\"WaitUntilInFrontPosition\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super().__init__(name)\n\n        self._actor = actor\n        self._ref_transform = transform\n        self._ref_location = transform.location\n        self._ref_vector = transform.get_forward_vector()\n        self._check_distance = check_distance\n        self._distance = distance\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Checks if the two actors meet the requirements\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Is the actor in front?\n        location = CarlaDataProvider.get_location(self._actor)\n        if location is None:\n            return new_status\n\n        actor_dir = location - self._ref_location\n        in_front = actor_dir.dot(self._ref_vector) > 0.0\n\n        # Is the actor close-by?\n        if not self._check_distance or location.distance(self._ref_location) < self._distance:\n            close_by = True\n        else:\n            close_by = False\n\n        if in_front and close_by:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass DriveDistance(AtomicCondition):\n\n    \"\"\"\n    This class contains an atomic behavior to drive a certain distance.\n\n    Important parameters:\n    - actor: CARLA actor to execute the condition\n    - distance: Distance for this condition in meters\n\n    The condition terminates with SUCCESS, when the actor drove at least the given distance\n    \"\"\"\n\n    def __init__(self, actor, distance, name=\"DriveDistance\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(DriveDistance, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._target_distance = distance\n        self._distance = 0\n        self._location = None\n        self._actor = actor\n\n    def initialise(self):\n        self._location = CarlaDataProvider.get_location(self._actor)\n        super(DriveDistance, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check driven distance\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._location is None:\n            return new_status\n\n        new_location = CarlaDataProvider.get_location(self._actor)\n        self._distance += calculate_distance(self._location, new_location)\n        self._location = new_location\n\n        if self._distance > self._target_distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass AtRightmostLane(AtomicCondition):\n\n    \"\"\"\n    This class contains an atomic behavior to check if the actor is at the rightest driving lane.\n\n    Important parameters:\n    - actor: CARLA actor to execute the condition\n\n    The condition terminates with SUCCESS, when the actor enters the rightest lane\n    \"\"\"\n\n    def __init__(self, actor, name=\"AtRightmostLane\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(AtRightmostLane, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._map = CarlaDataProvider.get_map()\n\n    def update(self):\n        \"\"\"\n        Check actor waypoints\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n        waypoint = self._map.get_waypoint(location)\n        if waypoint is None:\n            return new_status\n        right_waypoint = waypoint.get_right_lane()\n        if right_waypoint is None:\n            return new_status\n        lane_type = right_waypoint.lane_type\n\n        if lane_type != carla.LaneType.Driving:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass WaitForTrafficLightState(AtomicCondition):\n\n    \"\"\"\n    This class contains an atomic behavior to wait for a given traffic light\n    to have the desired state.\n\n    Args:\n        actor (carla.TrafficLight): CARLA traffic light to execute the condition\n        state (carla.TrafficLightState): State to be checked in this condition\n\n    The condition terminates with SUCCESS, when the traffic light switches to the desired state\n    \"\"\"\n\n    def __init__(self, actor, state, name=\"WaitForTrafficLightState\"):\n        \"\"\"\n        Setup traffic_light\n        \"\"\"\n        super(WaitForTrafficLightState, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor if \"traffic_light\" in actor.type_id else None\n        self._state = state\n\n    def update(self):\n        \"\"\"\n        Set status to SUCCESS, when traffic light state matches the expected one\n        \"\"\"\n        if self._actor is None:\n            return py_trees.common.Status.FAILURE\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._actor.state == self._state:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass WaitEndIntersection(AtomicCondition):\n\n    \"\"\"\n    Atomic behavior that waits until the vehicles has gone outside the junction.\n    If currently inside no intersection, it will wait until one is found.\n    If 'junction_id' is given, it will wait until that specific junction has finished\n    \"\"\"\n\n    def __init__(self, actor, junction_id=None, debug=False, name=\"WaitEndIntersection\"):\n        super(WaitEndIntersection, self).__init__(name)\n        self.actor = actor\n        self.debug = debug\n        self._junction_id = junction_id\n        self._inside_junction = False\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        waypoint = CarlaDataProvider.get_map().get_waypoint(location)\n\n        # Wait for the actor to enter a / the junction\n        if not self._inside_junction:\n            junction = waypoint.get_junction()\n            if not junction:\n                return new_status\n            if not self._junction_id or junction.id == self._junction_id:\n                self._inside_junction = True\n\n        # And to leave it\n        elif self._inside_junction and not waypoint.is_junction:\n            if self.debug:\n                print(\"--- Leaving the junction\")\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass WaitForBlackboardVariable(AtomicCondition):\n\n    \"\"\"\n    Atomic behavior that keeps running until the blackboard variable is set to the corresponding value.\n    Used to avoid returning FAILURE if the blackboard comparison fails.\n\n    It also initially sets the variable to a given value, if given\n    \"\"\"\n\n    def __init__(self, variable_name, variable_value, var_init_value=None,\n                 debug=False, name=\"WaitForBlackboardVariable\"):\n        super(WaitForBlackboardVariable, self).__init__(name)\n        self._debug = debug\n        self._variable_name = variable_name\n        self._variable_value = variable_value\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        if var_init_value is not None:\n            blackboard = py_trees.blackboard.Blackboard()\n            _ = blackboard.set(variable_name, var_init_value)\n\n    def update(self):\n\n        new_status = py_trees.common.Status.RUNNING\n\n        blackv = py_trees.blackboard.Blackboard()\n        value = blackv.get(self._variable_name)\n        if value == self._variable_value:\n            if self._debug:\n                print(\"Blackboard variable {} set to True\".format(self._variable_name))\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass CheckParameter(AtomicCondition):\n    \"\"\"\n    Atomic behavior that keeps checking global osc parameter value with the given value.\n    The condition terminates with SUCCESS, when the comparison_operator is evaluated successfully.\n    \"\"\"\n\n    def __init__(self, parameter_ref, value, comparison_operator, debug=False, name=\"CheckParameter\"):\n        super(CheckParameter, self).__init__(name)\n        self._parameter_ref = parameter_ref\n        self._value = value\n        self._comparison_operator = comparison_operator\n        self._debug = debug\n\n    def update(self):\n        \"\"\"\n        keeps comparing global osc value with given value till it is successful.\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        current_value = CarlaDataProvider.get_osc_global_param_value(self._parameter_ref)\n        if self._comparison_operator(current_value, self._value):\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/timer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides access to the CARLA game time and contains a py_trees\ntimeout behavior using the CARLA game time\n\"\"\"\n\nimport datetime\nimport operator\nimport py_trees\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass GameTime(object):\n\n    \"\"\"\n    This (static) class provides access to the CARLA game time.\n\n    The elapsed game time can be simply retrieved by calling:\n    GameTime.get_time()\n    \"\"\"\n\n    _current_game_time = 0.0  # Elapsed game time after starting this Timer\n    _carla_time = 0.0\n    _last_frame = 0\n    _platform_timestamp = 0\n    _init = False\n\n    @staticmethod\n    def on_carla_tick(timestamp):\n        \"\"\"\n        Callback receiving the CARLA time\n        Update time only when frame is more recent that last frame\n        \"\"\"\n        if GameTime._last_frame < timestamp.frame:\n            frames = timestamp.frame - GameTime._last_frame if GameTime._init else 1\n            GameTime._current_game_time += timestamp.delta_seconds * frames\n            GameTime._last_frame = timestamp.frame\n            GameTime._platform_timestamp = datetime.datetime.now()\n            GameTime._init = True\n            GameTime._carla_time = timestamp.elapsed_seconds\n\n    @staticmethod\n    def restart():\n        \"\"\"\n        Reset game timer to 0\n        \"\"\"\n        GameTime._current_game_time = 0.0\n        GameTime._carla_time = 0.0\n        GameTime._last_frame = 0\n        GameTime._init = False\n\n    @staticmethod\n    def get_time():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._current_game_time\n\n    @staticmethod\n    def get_carla_time():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._carla_time\n\n    @staticmethod\n    def get_wallclocktime():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._platform_timestamp\n\n    @staticmethod\n    def get_frame():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._last_frame\n\n\nclass SimulationTimeCondition(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    This class contains an atomic simulation time condition behavior.\n    It uses the CARLA game time, not the system time which is used by\n    the py_trees timer.\n\n    Returns, if the provided rule was successfully evaluated\n    \"\"\"\n\n    def __init__(self, timeout, comparison_operator=operator.gt, name=\"SimulationTimeCondition\"):\n        \"\"\"\n        Setup timeout\n        \"\"\"\n        super(SimulationTimeCondition, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._timeout_value = timeout\n        self._start_time = 0.0\n        self._comparison_operator = comparison_operator\n\n    def initialise(self):\n        \"\"\"\n        Set start_time to current GameTime\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Get current game time, and compare it to the timeout value\n        Upon successfully comparison using the provided comparison_operator,\n        the status changes to SUCCESS\n        \"\"\"\n\n        elapsed_time = GameTime.get_time() - self._start_time\n\n        if not self._comparison_operator(elapsed_time, self._timeout_value):\n            new_status = py_trees.common.Status.RUNNING\n        else:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TimeOut(SimulationTimeCondition):\n\n    \"\"\"\n    This class contains an atomic timeout behavior.\n    It uses the CARLA game time, not the system time which is used by\n    the py_trees timer.\n    \"\"\"\n\n    def __init__(self, timeout, name=\"TimeOut\"):\n        \"\"\"\n        Setup timeout\n        \"\"\"\n        super(TimeOut, self).__init__(timeout, name=name)\n        self.timeout = False\n\n    def update(self):\n        \"\"\"\n        Upon reaching the timeout value the status changes to SUCCESS\n        \"\"\"\n\n        new_status = super(TimeOut, self).update()\n\n        if new_status == py_trees.common.Status.SUCCESS:\n            self.timeout = True\n\n        return new_status\n\n\nclass RouteTimeoutBehavior(py_trees.behaviour.Behaviour):\n    \"\"\"\n    Behavior responsible of the route's timeout. With an initial value,\n    it increases every time the agent advanced through the route, and is dependent on the road's speed.\n    \"\"\"\n    MIN_TIMEOUT = 300\n    TIMEOUT_ROUTE_PERC = 10\n\n    def __init__(self, ego_vehicle, route, debug=False, name=\"RouteTimeoutBehavior\"):\n        \"\"\"\n        Setup timeout\n        \"\"\"\n        super().__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._ego_vehicle = ego_vehicle\n        self._route = route\n        self._debug = debug\n\n        self._start_time = None\n        self._timeout_value = self.MIN_TIMEOUT\n        self.timeout = False\n\n        # Route variables\n        self._wsize = 3\n        self._current_index = 0\n\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n\n        self._route_accum_meters = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            loc = tran.location\n            d = loc.distance(prev_loc)\n            accum = 0 if i == 0 else self._route_accum_meters[i - 1]\n\n            self._route_accum_meters.append(d + accum)\n            prev_loc = loc\n\n    def initialise(self):\n        \"\"\"\n        Set start_time to current GameTime\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Get current game time, and compare it to the timeout value\n        Upon successfully comparison using the provided comparison_operator,\n        the status changes to SUCCESS\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        ego_location = CarlaDataProvider.get_location(self._ego_vehicle)\n        if ego_location is None:\n            return new_status\n\n        new_index = self._current_index\n\n        for index in range(self._current_index, min(self._current_index + self._wsize + 1, self._route_length)):\n            route_transform = self._route_transforms[index]\n            route_veh_vec = ego_location - route_transform.location\n            if route_veh_vec.dot(route_transform.get_forward_vector()) > 0:\n                new_index = index\n\n        # Update the timeout value\n        if new_index > self._current_index:\n            dist = self._route_accum_meters[new_index] - self._route_accum_meters[self._current_index]\n            max_speed = self._ego_vehicle.get_speed_limit() / 3.6\n            timeout_speed = max_speed * self.TIMEOUT_ROUTE_PERC / 100\n            self._timeout_value += dist / timeout_speed\n            self._current_index = new_index\n\n        elapsed_time = GameTime.get_time() - self._start_time\n        if elapsed_time > self._timeout_value:\n            new_status = py_trees.common.Status.SUCCESS\n            self.timeout = True\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/traffic_events.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of TrafficEvents\n\"\"\"\n\nfrom enum import Enum\n\n\nclass TrafficEventType(Enum):\n\n    \"\"\"\n    This enum represents different traffic events that occur during driving.\n    \"\"\"\n\n    NORMAL_DRIVING = 0\n    COLLISION_STATIC = 1\n    COLLISION_VEHICLE = 2\n    COLLISION_PEDESTRIAN = 3\n    ROUTE_DEVIATION = 4\n    ROUTE_COMPLETION = 5\n    ROUTE_COMPLETED = 6\n    TRAFFIC_LIGHT_INFRACTION = 7\n    WRONG_WAY_INFRACTION = 8\n    ON_SIDEWALK_INFRACTION = 9\n    STOP_INFRACTION = 10\n    OUTSIDE_LANE_INFRACTION = 11\n    OUTSIDE_ROUTE_LANES_INFRACTION = 12\n    VEHICLE_BLOCKED = 13\n    MIN_SPEED_INFRACTION = 14\n    YIELD_TO_EMERGENCY_VEHICLE = 15\n    SCENARIO_TIMEOUT = 16\n\n\nclass TrafficEvent(object):\n\n    \"\"\"\n    TrafficEvent definition\n    \"\"\"\n\n    def __init__(self, event_type, frame, message=\"\", dictionary=None):\n        \"\"\"\n        Initialize object\n\n        :param event_type: TrafficEventType defining the type of traffic event\n        :param frame: frame in which the event happened \n        :param message: optional message to inform users of the event\n        :param dictionary: optional dictionary with arbitrary keys and values\n        \"\"\"\n        self._type = event_type\n        self._frame = frame\n        self._message = message\n        self._dict = dictionary\n\n    def get_type(self):\n        \"\"\"return the type\"\"\"\n        return self._type\n\n    def get_frame(self):\n        \"\"\"return the frame\"\"\"\n        return self._frame\n\n    def set_frame(self, frame):\n        \"\"\"return the frame\"\"\"\n        self._frame = frame\n\n    def set_message(self, message):\n        \"\"\"Set message\"\"\"\n        self._message = message\n\n    def get_message(self):\n        \"\"\"returns the message\"\"\"\n        return self._message\n\n    def set_dict(self, dictionary):\n        \"\"\"Set dictionary\"\"\"\n        self._dict = dictionary\n\n    def get_dict(self):\n        \"\"\"returns the dictionary\"\"\"\n        return self._dict\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/watchdog.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a simple watchdog timer to detect timeouts\nIt is for example used in the ScenarioManager\n\"\"\"\nfrom __future__ import print_function\n\nimport simple_watchdog_timer as swt\ntry:\n    import thread\nexcept ImportError:\n    import _thread as thread\n\n\nclass Watchdog(object):\n    \"\"\"\n    Simple watchdog timer to detect timeouts\n\n    Args:\n        timeout (float): Timeout value of the watchdog [seconds]. If triggered, raises a KeyboardInterrupt.\n        interval (float): Time between timeout checks [seconds]. Defaults to 1% of the timeout.\n\n    Attributes:\n        _timeout (float): Timeout value of the watchdog [seconds].\n        _interval (float): Time between timeout checks [seconds].\n        _failed (bool): True if watchdog exception occured, false otherwise\n    \"\"\"\n\n    def __init__(self, timeout=1.0, interval=None):\n        \"\"\"Class constructor\"\"\"\n        self._watchdog = None\n        self._timeout = timeout + 1.0\n        self._interval = min(interval if interval is not None else self._timeout / 100, 1.0)\n        self._failed = False\n        self._watchdog_stopped = False\n\n    def start(self):\n        \"\"\"Start the watchdog\"\"\"\n        self._watchdog = swt.WDT(\n            check_interval_sec=self._interval,\n            trigger_delta_sec=self._timeout,\n            callback=self._callback\n        )\n\n    def stop(self):\n        \"\"\"Stop the watchdog\"\"\"\n        if self._watchdog is not None and not self._watchdog_stopped:\n            self.resume()  # If not resumed, the stop will block. Does nothing if already resumed\n            self._watchdog.stop()\n            self._watchdog_stopped = True\n\n    def pause(self):\n        \"\"\"Pause the watchdog\"\"\"\n        if self._watchdog is not None:\n            self._watchdog.pause()\n\n    def resume(self):\n        \"\"\"Resume the watchdog.\"\"\"\n        if self._watchdog is not None:\n            self._watchdog.resume()\n\n    def update(self):\n        \"\"\"Reset the watchdog.\"\"\"\n        if self._watchdog_stopped:\n            return\n\n        if self._watchdog is not None:\n            self._watchdog.update()\n\n    def _callback(self, watchdog):\n        \"\"\"Method called when the timer triggers. Raises a KeyboardInterrupt on\n        the main thread and stops the watchdog.\"\"\"\n        self.pause()  # Good practice to stop it after the event occurs\n        print('Watchdog exception - Timeout of {} seconds occured'.format(self._timeout))\n        self._failed = True\n        thread.interrupt_main()\n\n    def get_status(self):\n        \"\"\"returns False if watchdog exception occured, True otherwise\"\"\"\n        return not self._failed\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenariomanager/weather_sim.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a weather class and py_trees behavior\nto simulate weather in CARLA according to the astronomic\nbehavior of the sun.\n\"\"\"\n\nimport datetime\nimport math\nimport operator\n\nimport ephem\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\n\nclass Weather(object):\n\n    \"\"\"\n    Class to simulate weather in CARLA according to the astronomic behavior of the sun\n\n    The sun position (azimuth and altitude angles) is obtained by calculating its\n    astronomic position for the CARLA reference position (x=0, y=0, z=0) using the ephem\n    library.\n\n    Args:\n        carla_weather (carla.WeatherParameters): Initial weather settings.\n        dtime (datetime): Initial date and time in UTC (required for animation only).\n            Defaults to None.\n        animation (bool): Flag to allow animating the sun position over time.\n            Defaults to False.\n\n    Attributes:\n        carla_weather (carla.WeatherParameters): Weather parameters for CARLA.\n        animation (bool): Flag to allow animating the sun position over time.\n        _sun (ephem.Sun): The sun as astronomic entity.\n        _observer_location (ephem.Observer): Holds the geographical position (lat/lon/altitude)\n            for which the sun position is obtained.\n        datetime (datetime): Date and time in UTC (required for animation only).\n    \"\"\"\n\n    def __init__(self, carla_weather, dtime=None, animation=False):\n        \"\"\"\n        Class constructor\n        \"\"\"\n        self.carla_weather = carla_weather\n        self.animation = animation\n\n        self._sun = ephem.Sun()  # pylint: disable=no-member\n        self._observer_location = ephem.Observer()\n        geo_location = CarlaDataProvider.get_map().transform_to_geolocation(carla.Location(0, 0, 0))\n        self._observer_location.lon = str(geo_location.longitude)\n        self._observer_location.lat = str(geo_location.latitude)\n\n        # @TODO This requires the time to be in UTC to be accurate\n        self.datetime = dtime\n        if self.datetime:\n            self._observer_location.date = self.datetime\n\n        self.update()\n\n    def update(self, delta_time=0):\n        \"\"\"\n        If the weather animation is true, the new sun position is calculated w.r.t delta_time\n\n        Nothing happens if animation or datetime are None.\n\n        Args:\n            delta_time (float): Time passed since self.datetime [seconds].\n        \"\"\"\n        if not self.animation or not self.datetime:\n            return\n\n        self.datetime = self.datetime + datetime.timedelta(seconds=delta_time)\n        self._observer_location.date = self.datetime\n\n        self._sun.compute(self._observer_location)\n        self.carla_weather.sun_altitude_angle = math.degrees(self._sun.alt)\n        self.carla_weather.sun_azimuth_angle = math.degrees(self._sun.az)\n\n\nclass OSCWeatherBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Atomic to read weather settings from the blackboard and apply these in CARLA.\n    Used in combination with UpdateWeather() to have a continuous weather simulation.\n\n    This behavior is always in a running state and must never terminate.\n    The user must not add this behavior. It is automatically added by the ScenarioManager.\n\n    This atomic also sets the datetime to blackboard variable, used by TimeOfDayComparison atomic\n\n    Args:\n        name (string): Name of the behavior.\n            Defaults to 'WeatherBehavior'.\n\n    Attributes:\n        _weather (srunner.scenariomanager.weather_sim.Weather): Weather settings.\n        _current_time (float): Current CARLA time [seconds].\n    \"\"\"\n\n    def __init__(self, name=\"WeatherBehavior\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(OSCWeatherBehavior, self).__init__(name)\n        self._weather = None\n        self._current_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set current time to current CARLA time\n        \"\"\"\n        self._current_time = GameTime.get_time()\n\n    def update(self):\n        \"\"\"\n        Check if new weather settings are available on the blackboard, and if yes fetch these\n        into the _weather attribute.\n\n        Apply the weather settings from _weather to CARLA.\n\n        Note:\n            To minimize CARLA server interactions, the weather is only updated, when the blackboard\n            is updated, or if the weather animation flag is true. In the latter case, the update\n            frequency is 1 Hz.\n\n        returns:\n            py_trees.common.Status.RUNNING\n        \"\"\"\n\n        weather = None\n\n        try:\n            check_weather = operator.attrgetter(\"CarlaWeather\")\n            weather = check_weather(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if weather:\n            self._weather = weather\n            delattr(py_trees.blackboard.Blackboard(), \"CarlaWeather\")\n            CarlaDataProvider.get_world().set_weather(self._weather.carla_weather)\n            py_trees.blackboard.Blackboard().set(\"Datetime\", self._weather.datetime, overwrite=True)\n\n        if self._weather and self._weather.animation:\n            new_time = GameTime.get_time()\n            delta_time = new_time - self._current_time\n\n            if delta_time > 1:\n                self._weather.update(delta_time)\n                self._current_time = new_time\n                CarlaDataProvider.get_world().set_weather(self._weather.carla_weather)\n\n                py_trees.blackboard.Blackboard().set(\"Datetime\", self._weather.datetime, overwrite=True)\n\n        return py_trees.common.Status.RUNNING\n\n\nclass RouteWeatherBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Given a set of route weathers ([position, carla.WeatherParameters]),\n    monitors the ego vehicle to dynamically change the weather as the ego advanced through the route.\n\n    This behavior interpolates the desired weather between two weather keypoints and if the extreme cases\n    (0% and 100%) aren't defined, the closest one will be chosen\n    (i.e, if the route weather is at 90%, all weathers from 90% to 100% will be the one defined at 90%)\n\n    Use the debug argument to print what is the route's percentage of each route position.\n    \"\"\"\n\n    def __init__(self, ego_vehicle, route, weathers, debug=False, name=\"RouteWeatherBehavior\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super().__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._ego_vehicle = ego_vehicle\n        self._route = route\n\n        self._weathers = weathers\n        if self._weathers[0][0] != 0:  # Make sure the weather is defined at 0%\n            self._weathers.insert(0, [0, self._weathers[0]])\n        if self._weathers[-1][0] != 100:  # Make sure the weather is defined at 100%\n            self._weathers.append([100, self._weathers[-1]])\n\n        self._wsize = 3\n\n        self._current_index = 0\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n        self._route_perc = self._get_route_percentages()\n        if debug:\n            debug_perc = -1\n            for transform, perc in zip(self._route_transforms, self._route_perc):\n                location = transform.location\n                new_perc = int(perc)\n                if new_perc > debug_perc:\n                    self._world.debug.draw_string(\n                        location + carla.Location(z=1),\n                        str(new_perc),\n                        color=carla.Color(50, 50, 50),\n                        life_time=100000\n                    )\n                    debug_perc = new_perc\n        self._route_weathers = self.get_route_weathers()\n\n    def _get_route_percentages(self):\n        \"\"\"\n        Calculate the accumulated distance percentage at each point in the route\n        \"\"\"\n        accum_m = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            new_dist = tran.location.distance(prev_loc)\n            added_dist = 0 if i == 0 else accum_m[i - 1]\n            accum_m.append(new_dist + added_dist)\n            prev_loc = tran.location\n\n        max_dist = accum_m[-1]\n        return [x / max_dist * 100 for x in accum_m]\n\n    def get_route_weathers(self):\n        \"\"\"Calculate the desired weather at each point in the route\"\"\"\n        def interpolate(prev_w, next_w, perc, name):\n            x0 = prev_w[0]\n            x1 = next_w[0]\n            if x0 == x1:\n                raise ValueError(\"Two weather keypoints have the same route percentage\")\n            y0 = getattr(prev_w[1], name)\n            y1 = getattr(next_w[1], name)\n            return y0 + (y1 - y0) * (perc - x0) / (x1 - x0)\n\n        route_weathers = []\n\n        weather_index = 0\n        prev_w = self._weathers[weather_index]\n        next_w = self._weathers[weather_index + 1]\n\n        for perc in self._route_perc:\n            if perc > next_w[0]:  # Must be strictly less, or an IndexError will occur at 100%\n                weather_index += 1\n                prev_w = self._weathers[weather_index]\n                next_w = self._weathers[weather_index + 1]\n\n            weather = carla.WeatherParameters()\n            weather.cloudiness = interpolate(prev_w, next_w, perc, 'cloudiness')\n            weather.precipitation = interpolate(prev_w, next_w, perc, 'precipitation')\n            weather.precipitation_deposits = interpolate(prev_w, next_w, perc, 'precipitation_deposits')\n            weather.wind_intensity = interpolate(prev_w, next_w, perc, 'wind_intensity')\n            weather.sun_azimuth_angle = interpolate(prev_w, next_w, perc, 'sun_azimuth_angle')\n            weather.sun_altitude_angle = interpolate(prev_w, next_w, perc, 'sun_altitude_angle')\n            weather.wetness = interpolate(prev_w, next_w, perc, 'wetness')\n            weather.fog_distance = interpolate(prev_w, next_w, perc, 'fog_distance')\n            weather.fog_density = interpolate(prev_w, next_w, perc, 'fog_density')\n            weather.fog_falloff = interpolate(prev_w, next_w, perc, 'fog_falloff')\n            weather.scattering_intensity = interpolate(prev_w, next_w, perc, 'scattering_intensity')\n            weather.mie_scattering_scale = interpolate(prev_w, next_w, perc, 'mie_scattering_scale')\n            weather.rayleigh_scattering_scale = interpolate(prev_w, next_w, perc, 'rayleigh_scattering_scale')\n\n            route_weathers.append(weather)\n\n        return route_weathers\n\n    def update(self):\n        \"\"\"\n        Check the location of the ego vehicle, updating the weather if it has advanced through the route\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        ego_location = CarlaDataProvider.get_location(self._ego_vehicle)\n        if ego_location is None:\n            return new_status\n\n        new_index = self._current_index\n\n        for index in range(self._current_index, min(self._current_index + self._wsize + 1, self._route_length)):\n            route_transform = self._route_transforms[index]\n            route_veh_vec = ego_location - route_transform.location\n            if route_veh_vec.dot(route_transform.get_forward_vector()) > 0:\n                new_index = index\n\n        if new_index > self._current_index:\n            self._world.set_weather(self._route_weathers[new_index])\n        self._current_index = new_index\n\n        return new_status\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/actor_flow.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, ScenarioTimeout, WaitForever\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               WaitEndIntersection,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import (SwitchRouteSources,\n                                              ChangeOppositeBehavior,\n                                              HandleJunctionScenario,\n                                              RemoveRoadLane)\nfrom srunner.tools.scenario_helper import get_same_dir_lanes, generate_target_waypoint_in_route\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\nclass EnterActorFlow(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle runs a red light\n    in front of the ego, forcing it to react. This vehicles are 'special' ones such as police cars,\n    ambulances or firetrucks.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        ego_location = config.trigger_points[0].location\n        self._reference_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        self._sink_distance = 2\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"EnterActorFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        # Get all lanes\n        source_wps = get_same_dir_lanes(source_wp)\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        for source_wp, sink_wp in zip(source_wps, sink_wps):\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance))\n            root.add_child(ActorFlow(\n                source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n                self._flow_speed, initial_actors=True, initial_junction=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            extra_space = 20\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=source_wps,\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=extra_space\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass EnterActorFlowV2(EnterActorFlow):\n    \"\"\"\n    Variation of EnterActorFlow for special highway entry exits with dedicated lanes\n    \"\"\"\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        # Get all lanes\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n                source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n                self._flow_speed, initial_actors=True, initial_junction=True))\n        for sink_wp in sink_wps:\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        exit_wp = generate_target_waypoint_in_route(self._reference_waypoint, self.config.route)\n        exit_wp = exit_wp.next(10)[0]  # just in case the junction maneuvers don't match\n\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            self._extra_space = 20\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n            sequence_2 = py_trees.composites.Sequence()\n            sequence_2.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n            sequence_2.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=False,\n                remove_entries=[],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=self._extra_space\n            ))\n            sequence_2.add_child(WaitForever())\n            root.add_child(sequence_2)\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=[source_wp],\n                remove_exits= get_same_dir_lanes(exit_wp),\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n\nclass HighwayExit(BasicScenario):\n    \"\"\"\n    This scenario is similar to CrossActorFlow\n    It will remove the BackgroundActivity from the lane where ActorFlow starts.\n    Then vehicles (cars) will start driving from start_actor_flow location to end_actor_flow location\n    in a relatively high speed, forcing the ego to accelerate to cut in the actor flow \n    then exit from the highway.\n    This scenario works when Background Activity is running in route mode. And there should be no junctions in front of the ego.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._sink_distance = 2\n        self._end_distance = 40\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"HighwayExit\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Vehicles run from the start to the end continuously.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        grp = CarlaDataProvider.get_global_route_planner()\n        route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n        junction_id = None\n        for wp, _ in route:\n            if wp.is_junction:\n                junction_id = wp.get_junction().id\n                break\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n            source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n            self._flow_speed, initial_actors=True, initial_junction=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0], junction_id))\n\n        sequence = py_trees.composites.Sequence()\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(source_wp))\n        sequence.add_child(root)\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass MergerIntoSlowTraffic(BasicScenario):\n    \"\"\"\n    This scenario is similar to EnterActorFlow\n    It will remove the BackgroundActivity from the lane where ActorFlow starts.\n    Then vehicles (cars) will start driving from start_actor_flow location to end_actor_flow location\n    in a relatively low speed, ego car must merger into this slow traffic flow.\n    This scenario works when Background Activity is running in route mode. And applies to a confluence\n    area at a highway intersection.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        ego_location = config.trigger_points[0].location\n        self._reference_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n        self._trigger_point=config.trigger_points[0].location\n\n        self._sink_distance = 2\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"MergerIntoSlowTraffic\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        the ego vehicle mergers into a slow traffic flow from the freeway entrance.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        # Get all lanes\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        for wp in sink_wps:\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], wp.transform.location, self._sink_distance))\n        root.add_child(ActorFlow(\n            source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n            self._flow_speed, initial_actors=True, initial_junction=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            extra_space = 0\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[source_wp],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=extra_space + 20\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass MergerIntoSlowTrafficV2(MergerIntoSlowTraffic):\n    \"\"\"\n    Variation of MergerIntoSlowTraffic \n    \"\"\"\n\n    def _create_behavior(self):\n        \"\"\"\n        the ego vehicle mergers into a slow traffic flow from the freeway entrance.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n            source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n            self._flow_speed, initial_actors=True, initial_junction=True))\n        for sink_wp in sink_wps:\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        exit_wp = generate_target_waypoint_in_route(self._reference_waypoint, self.config.route)\n        exit_wp = exit_wp.next(10)[0]  # just in case the junction maneuvers don't match\n\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            self._extra_space = 20\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n        sequence_2 = py_trees.composites.Sequence()\n        sequence_2.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        sequence_2.add_child(HandleJunctionScenario(\n            clear_junction=False,\n            clear_ego_entry=False,\n            remove_entries=[],\n            remove_exits=[],\n            stop_entries=False,\n            extend_road_exit=self._extra_space\n        ))\n        sequence_2.add_child(WaitForever())\n        root.add_child(sequence_2)\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=[source_wp],\n                remove_exits=get_same_dir_lanes(exit_wp),\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n\nclass InterurbanActorFlow(BasicScenario):\n    \"\"\"\n    Scenario specifically made for the interurban intersections,\n    where the ego leaves the interurban road by turning left, crossing an actor flow.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._sink_distance = 2\n        self._end_distance = 40\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        self._reference_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        route_entry_wp, route_exit_wp = self._get_entry_exit_route_lanes(self._reference_wp, config.route)\n        route_exit_wp = route_exit_wp.next(8)[0]  # Just in case the junction maneuvers don't match\n        other_entry_wp = route_exit_wp.get_left_lane()\n        if not other_entry_wp or other_entry_wp.lane_type != carla.LaneType.Driving:\n            raise ValueError(\"Couldn't find an end position\")\n\n        self._source_wp = self._map.get_waypoint(self._start_actor_flow)\n        self._sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        self._remove_entries = [route_entry_wp, other_entry_wp, self._source_wp]\n\n        super().__init__(\"InterurbanActorFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _get_entry_exit_route_lanes(self, wp, route):\n\n        entry_wp = None\n        exit_wp = None\n\n        # Get the middle entry\n        dist = float('inf')\n        index = 0\n        for route_index, route_pos in enumerate(route):\n            route_location = route_pos[0].location\n            trigger_location = wp.transform.location\n\n            route_dist = trigger_location.distance(route_location)\n            if route_dist <= dist:\n                index = route_index\n                dist = route_dist\n\n        reached_junction = False\n        for i in range(index, len(route)):\n            route_transform, road_option = route[i]\n\n            # Enter the junction\n            if not reached_junction and (road_option in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n                reached_junction = True\n                entry_wp = self._map.get_waypoint(route[i-1][0].location)\n                entry_wp = entry_wp.previous(2)[0]  # Just in case\n\n            # End condition for the behavior, at the end of the junction\n            if reached_junction and (road_option not in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n                exit_wp = self._map.get_waypoint(route_transform.location)\n                exit_wp = exit_wp.next(2)[0]  # Just in case\n                break\n\n        return (entry_wp, exit_wp)\n\n\n    def _create_behavior(self):\n        \"\"\"\n        Create an actor flow at the opposite lane which the ego has to cross\n        \"\"\"\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, self._sink_distance, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        sequence = py_trees.composites.Sequence()\n\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=self._remove_entries,\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass InterurbanAdvancedActorFlow(BasicScenario):\n    \"\"\"\n    Scenario specifically made for the interurban intersections,\n    where the ego incorportates into the interurban road by turning left,\n    first crossing an actor flow, and then merging into another one.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._sink_distance = 2\n\n        self._reference_wp = self._map.get_waypoint(config.trigger_points[0].location)\n        self._exit_wp = generate_target_waypoint_in_route(self._reference_wp, config.route)\n\n        self._start_actor_flow_1 = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow_1 = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"InterurbanAdvancedActorFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def get_lane_key(self, waypoint):\n        return str(waypoint.road_id) + '*' + str(waypoint.lane_id)\n\n    def _get_junction_entry_wp(self, entry_wp):\n        while entry_wp.is_junction:\n            entry_wps = entry_wp.previous(0.2)\n            if len(entry_wps) == 0:\n                return None  # Stop when there's no prev\n            entry_wp = entry_wps[0]\n        return entry_wp\n\n    def _get_junction_exit_wp(self, exit_wp):\n        while exit_wp.is_junction:\n            exit_wps = exit_wp.next(0.2)\n            if len(exit_wps) == 0:\n                return None  # Stop when there's no prev\n            exit_wp = exit_wps[0]\n        return exit_wp\n\n    def _initialize_actors(self, config):\n        \n        self._source_wp_1 = self._map.get_waypoint(self._start_actor_flow_1)\n        self._sink_wp_1 = self._map.get_waypoint(self._end_actor_flow_1)\n\n        self._source_wp_2 = self._sink_wp_1.get_left_lane()\n        if not self._source_wp_2 or self._source_wp_2.lane_type != carla.LaneType.Driving:\n            raise ValueError(\"Couldn't find a position for the actor flow\")\n        self._sink_wp_2 = self._source_wp_1.get_left_lane()\n        if not self._sink_wp_2 or self._sink_wp_2.lane_type != carla.LaneType.Driving:\n            raise ValueError(\"Couldn't find a position for the actor flow\")\n\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(self._source_wp_2.transform.location, self._sink_wp_2.transform.location)\n            self._extra_space = 20\n            route_exit_wp = None\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    junction = current_wp.get_junction()\n                    break\n                route_exit_wp = current_wp\n\n            route_exit_key = self.get_lane_key(route_exit_wp)\n\n            # Get the route entry waypoint\n            route_entry_wp = self._reference_wp\n            while True:\n                next_wps = route_entry_wp.next(1)\n                if not next_wps:\n                    break\n                if next_wps[0].is_junction:\n                    break\n                route_entry_wp = next_wps[0]\n            route_entry_key = self.get_lane_key(route_entry_wp)\n\n        entry_wps = []\n        entry_keys = []\n        exit_wps = []\n        exit_keys = []\n\n        for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n\n            entry_wp = self._get_junction_entry_wp(entry_wp)\n            entry_key = self.get_lane_key(entry_wp)\n            if entry_key != route_entry_key and entry_key not in entry_keys:\n                entry_wps.append(entry_wp)\n                entry_keys.append(entry_key)\n\n            exit_wp = self._get_junction_exit_wp(exit_wp)\n            exit_key = self.get_lane_key(exit_wp)\n            if exit_key != route_exit_key and exit_key not in exit_keys:\n                exit_wps.append(exit_wp)\n                exit_keys.append(exit_key)\n\n        self._remove_entries = entry_wps\n        self._remove_exits = exit_wps\n\n    def _create_behavior(self):\n        \"\"\"\n        the ego vehicle mergers into a slow traffic flow from the freeway entrance.\n        \"\"\"\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._sink_wp_2.transform))\n        root.add_child(ActorFlow(\n            self._source_wp_1, self._sink_wp_1, self._source_dist_interval, self._sink_distance, self._flow_speed))\n        root.add_child(ActorFlow(\n            self._source_wp_2, self._sink_wp_2, self._source_dist_interval, self._sink_distance, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=self._remove_entries,\n                remove_exits=self._remove_exits,\n                stop_entries=False,\n                extend_road_exit=self._extra_space\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/background_activity.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario spawning elements to make the town dynamic and interesting\n\"\"\"\n\nfrom collections import OrderedDict\nimport py_trees\n\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import AtomicBehavior\nfrom srunner.tools.scenario_helper import get_same_dir_lanes, get_opposite_dir_lanes\n\nJUNCTION_ENTRY = 'entry'\nJUNCTION_MIDDLE = 'middle'\nJUNCTION_EXIT = 'exit'\nJUNCTION_EXIT_ROAD = 'exit_road'\nJUNCTION_EXIT_INACTIVE = 'exit_inactive'\n\nEGO_JUNCTION = 'junction'\nEGO_ROAD = 'road'\n\ndef get_lane_key(waypoint):\n    \"\"\"Returns a key corresponding to the waypoint lane. Equivalent to a 'Lane'\n    object and used to compare waypoint lanes\"\"\"\n    return '' if waypoint is None else get_road_key(waypoint) + '*' + str(waypoint.lane_id)\n\ndef get_road_key(waypoint):\n    \"\"\"Returns a key corresponding to the waypoint road. Equivalent to a 'Road'\n    object and used to compare waypoint roads\"\"\"\n    return '' if waypoint is None else str(waypoint.road_id)\n\ndef is_lane_at_road(lane_key, road_key):\n    \"\"\"Returns whether or not a lane is part of a road\"\"\"\n    return lane_key.startswith(road_key)\n\ndef get_lane_key_from_ids(road_id, lane_id):\n    \"\"\"Returns the lane corresping to a given road and lane ids\"\"\"\n    return str(road_id) + '*' + str(lane_id)\n\n\n# Debug variables\nDEBUG_ROAD = 'road'\nDEBUG_OPPOSITE = 'opposite'\nDEBUG_JUNCTION = 'junction'\nDEBUG_ENTRY = 'entry'\nDEBUG_EXIT = 'exit'\nDEBUG_CONNECT = 'connect'\n\nDEBUG_SMALL = 'small'\nDEBUG_MEDIUM = 'medium'\nDEBUG_LARGE = 'large'\n\nDEBUG_COLORS = {\n    DEBUG_ROAD: carla.Color(0, 0, 255),      # Blue\n    DEBUG_OPPOSITE: carla.Color(255, 0, 0),  # Red\n    DEBUG_JUNCTION: carla.Color(0, 0, 0),    # Black\n    DEBUG_ENTRY: carla.Color(255, 255, 0),   # Yellow\n    DEBUG_EXIT: carla.Color(0, 255, 255),    # Teal\n    DEBUG_CONNECT: carla.Color(0, 255, 0),   # Green\n}\n\nDEBUG_TYPE = {\n    DEBUG_SMALL: [0.8, 0.1],\n    DEBUG_MEDIUM: [0.5, 0.15],\n    DEBUG_LARGE: [0.2, 0.2],\n}  # Size, height\n\ndef draw_string(world, location, string='', debug_type=DEBUG_ROAD, persistent=False):\n    \"\"\"Utility function to draw debugging strings\"\"\"\n    v_shift, _ = DEBUG_TYPE.get(DEBUG_SMALL)\n    l_shift = carla.Location(z=v_shift)\n    color = DEBUG_COLORS.get(debug_type, DEBUG_ROAD)\n    life_time = 0.06 if not persistent else 100000\n    world.debug.draw_string(location + l_shift, string, False, color, life_time)\n\ndef draw_point(world, location, point_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, persistent=False):\n    \"\"\"Utility function to draw debugging points\"\"\"\n    v_shift, size = DEBUG_TYPE.get(point_type, DEBUG_SMALL)\n    l_shift = carla.Location(z=v_shift)\n    color = DEBUG_COLORS.get(debug_type, DEBUG_ROAD)\n    life_time = 0.06 if not persistent else 100000\n    world.debug.draw_point(location + l_shift, size, color, life_time)\n\ndef draw_arrow(world, location1, location2, arrow_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, persistent=False):\n    \"\"\"Utility function to draw debugging points\"\"\"\n    if location1 == location2:\n        draw_point(world, location1, arrow_type, debug_type, persistent)\n    v_shift, thickness = DEBUG_TYPE.get(arrow_type, DEBUG_SMALL)\n    l_shift = carla.Location(z=v_shift)\n    color = DEBUG_COLORS.get(debug_type, DEBUG_ROAD)\n    life_time = 0.06 if not persistent else 100000\n    world.debug.draw_arrow(location1 + l_shift, location2 + l_shift, thickness, thickness, color, life_time)\n\n\nclass Source(object):\n\n    \"\"\"\n    Source object to store its position and its responsible actors\n    \"\"\"\n\n    def __init__(self, wp, actors, entry_lane_wp='', active=True):  # pylint: disable=invalid-name\n        self.wp = wp  # pylint: disable=invalid-name\n        self.actors = actors\n        self.active = active\n\n        # For junction sources\n        self.entry_lane_wp = entry_lane_wp\n        self.previous_lane_keys = []  # Source lane and connecting lanes of the previous junction\n\n\nclass Junction(object):\n\n    \"\"\"\n    Junction object. Stores its topology as well as its state, when active\n    \"\"\"\n\n    def __init__(self, junction, junction_id, route_entry_index=None, route_exit_index=None):\n        # Topology\n        self.junctions = [junction]\n        self.id = junction_id  # pylint: disable=invalid-name\n        self.route_entry_index = route_entry_index\n        self.route_exit_index = route_exit_index\n        self.entry_lane_keys = []\n        self.exit_lane_keys = []\n        self.route_entry_keys = []\n        self.route_exit_keys = []\n        self.opposite_entry_keys = []\n        self.opposite_exit_keys = []\n        self.entry_wps = []\n        self.exit_wps = []\n        self.entry_directions = {'ref': [], 'opposite': [], 'left': [], 'right': []}\n        self.exit_directions = {'ref': [], 'opposite': [], 'left': [], 'right': []}\n\n        # State\n        self.entry_sources = []\n        self.exit_dict = OrderedDict()\n        self.actor_dict = OrderedDict()\n\n        # Junction scenario variables \n        self.stop_non_route_entries = False\n        self.clear_middle = False\n        self.inactive_entry_keys = []\n        self.inactive_exit_keys = []\n\n    def contains_wp(self, wp):\n        \"\"\"Checks whether or not a carla.Waypoint is inside the junction\"\"\"\n        if not wp.is_junction:\n            return False\n        other_id = wp.get_junction().id\n        for junction in self.junctions:\n            if other_id == junction.id:\n                return True\n        return False\n\n\nclass BackgroundBehavior(AtomicBehavior):\n    \"\"\"\n    Handles the background activity\n    \"\"\"\n\n    def __init__(self, ego_actor, route, debug=False, name=\"BackgroundBehavior\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(BackgroundBehavior, self).__init__(name)\n        self.debug = debug\n        self._map = CarlaDataProvider.get_map()\n        self._world = CarlaDataProvider.get_world()\n        self._tm_port = CarlaDataProvider.get_traffic_manager_port()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(self._tm_port)\n        self._tm.global_percentage_speed_difference(0.0)\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._attribute_filter = {'base_type': 'car', 'special_type': '', 'has_lights': True, }\n\n        # Global variables\n        self._ego_actor = ego_actor\n        self._ego_state = EGO_ROAD\n        self._ego_wp = None\n        self._ego_key = \"\"\n        self._route_index = 0\n        self._get_route_data(route)\n        self._actors_speed_perc = {}  # Dictionary actor - percentage\n        self._all_actors = []\n        self._lane_width_threshold = 2.25  # Used to stop some behaviors at narrow lanes to avoid problems [m]\n\n        self._spawn_vertical_shift = 0.2\n        self._reuse_dist = 10  # When spawning actors, might reuse actors closer to this distance\n        self._spawn_free_radius = 20  # Sources closer to the ego will not spawn actors\n        self._fake_junction_ids = []\n        self._fake_lane_pair_keys = []\n\n        # Initialisation values\n        self._vehicle_lane_change = False\n        self._vehicle_lights = True\n        self._vehicle_leading_distance = 10\n        self._vehicle_offset = 0.1\n\n        # Road variables\n        self._road_dict = {}  # Dictionary lane key -> actor source\n        self._road_checker_index = 0\n\n        self._road_front_vehicles = 2  # Amount of vehicles in front of the ego\n        self._road_back_vehicles = 2  # Amount of vehicles behind the ego\n        self._radius_increase_ratio = 1.7  # Meters the radius increases per m/s of the ego\n\n        self._base_junction_detection = 30\n        self._detection_ratio = 1.5  # Meters the radius increases per m/s of the ego\n\n        self._road_extra_front_actors = 0  # For cases where we want more space but not more vehicles\n        self._road_spawn_dist = 15  # Distance between spawned vehicles [m]\n        self._road_extra_space = 0  # Extra space for the road vehicles\n\n        self._active_road_sources = True\n\n        self._base_min_radius = 0\n        self._base_max_radius = 0\n        self._min_radius = 0\n        self._max_radius = 0\n        self._detection_dist = 0\n        self._get_road_radius()\n\n        # Junction variables\n        self._junctions = []  # List with all the junctions part of the route, in order of appearance\n        self._active_junctions = []  # List of all the active junctions\n\n        self._junction_sources_dist = 40  # Distance from the entry sources to the junction [m]\n        self._junction_sources_max_actors = 6  # Maximum vehicles alive at the same time per source\n        self._junction_spawn_dist = 15  # Distance between spawned vehicles [m]\n        self._junction_minimum_source_dist = 15  # Minimum distance between sources and their junction\n\n        self._junction_source_perc = 80  # Probability [%] of the source being created\n\n        # Opposite lane variables\n        self._opposite_actors = []\n        self._opposite_sources = []\n        self._opposite_route_index = 0\n\n        self._opposite_spawn_dist = 40  # Distance between spawned vehicles [m]\n        self._opposite_sources_dist = 80  # Distance from the ego to the opposite sources [m]. Twice the spawn distance\n\n        self._active_opposite_sources = True  # Flag to (de)activate all opposite sources\n\n        # Scenario variables:\n        self._scenario_stopped_actors = []  # Actors stopped by a hard break scenario\n        self._scenario_stopped_back_actors = []  # Actors stopped by a open doors scenario\n        self._scenario_max_speed = 0  # Max speed of the Background Activity. Deactivated with a value of 0\n        self._scenario_junction_entry = False  # Flag indicating the ego is entering a junction\n        self._scenario_junction_entry_distance = self._road_spawn_dist  # Min distance between vehicles and ego\n        self._scenario_removed_lane = False  # Flag indicating a scenario has removed a lane\n        self._scenario_remove_lane_offset = 0\n\n    def _get_route_data(self, route):\n        \"\"\"Extract the information from the route\"\"\"\n        self._route = []  # Transform the route into a list of waypoints\n        self._route_options = []  # Extract the RoadOptions from the route\n        self._accum_dist = []  # Save the total traveled distance for each waypoint\n        prev_trans = None\n        for trans, option in route:\n            self._route.append(self._map.get_waypoint(trans.location))\n            self._route_options.append(option)\n            if prev_trans:\n                dist = trans.location.distance(prev_trans.location)\n                self._accum_dist.append(dist + self._accum_dist[-1])\n            else:\n                self._accum_dist.append(0)\n            prev_trans = trans\n\n        self._route_length = len(route)\n        self._route_index = 0\n        self._route_buffer = 3\n\n    def _get_road_radius(self):\n        \"\"\"\n        Computes the min and max radius of the road behaviorm which will determine the speed of the vehicles.\n        Vehicles closer than the min radius maintain full speed, while those further than max radius are\n        stopped. Between the two, the velocity decreases linearly\"\"\"\n        self._base_min_radius = (self._road_front_vehicles + self._road_extra_front_actors) * self._road_spawn_dist\n        self._base_max_radius = (self._road_front_vehicles + self._road_extra_front_actors + 1) * self._road_spawn_dist\n        self._min_radius = self._base_min_radius + self._road_extra_space\n        self._max_radius = self._base_max_radius + self._road_extra_space\n\n    def initialise(self):\n        \"\"\"Creates the background activity actors. Pressuposes that the ego is at a road\"\"\"\n        self._create_junction_dict()\n        ego_wp = self._route[0]\n        same_dir_wps = get_same_dir_lanes(ego_wp)\n\n        self._initialise_road_behavior(same_dir_wps)\n        self._initialise_opposite_sources()\n        self._initialise_road_checker()\n\n    def update(self):\n        prev_ego_index = self._route_index\n\n        # Check if the TM destroyed an actor\n        if self._route_index > 0: # TODO: This check is due to intialization problem\n            self._check_background_actors()\n\n        # Update ego's route position. For robustness, the route point is used for most calculus\n        self._update_ego_data()\n\n        # Parameters and scenarios\n        self._update_parameters()\n\n        # Update ego state\n        if self._ego_state == EGO_JUNCTION:\n            self._monitor_ego_junction_exit()\n        self._monitor_incoming_junctions()\n\n        # Update_actors\n        if self._ego_state == EGO_JUNCTION:\n            self._update_junction_actors()\n            self._update_junction_sources()\n        else:\n            self._update_road_actors()\n\n            self._move_road_sources(prev_ego_index)\n            self._update_road_sources()\n\n            self._monitor_topology_changes(prev_ego_index)\n            self._monitor_road_changes(prev_ego_index)\n\n            self._move_opposite_sources(prev_ego_index)\n            self._update_opposite_sources()\n\n        # Update non junction sources\n        self._update_opposite_actors()\n\n        # Update the speed of all vehicles\n        self._set_actors_speed()\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"Destroy all actors\"\"\"\n        all_actors = list(self._actors_speed_perc)\n        for actor in list(all_actors):\n            self._destroy_actor(actor)\n        super(BackgroundBehavior, self).terminate(new_status)\n\n    def _check_background_actors(self):\n        \"\"\"Checks if the Traffic Manager has removed a backgroudn actor\"\"\"\n        alive_ids = [actor.id for actor in CarlaDataProvider.get_all_actors().filter('vehicle*')]\n        for actor in list(self._all_actors):\n            if actor.id not in alive_ids:\n                self._remove_actor_info(actor)\n\n    ################################\n    ##       Junction cache       ##\n    ################################\n\n    def _create_junction_dict(self):\n        \"\"\"Extracts the junctions the ego vehicle will pass through.\"\"\"\n        data = self._get_junctions_data()\n        fake_data, filtered_data = self._filter_fake_junctions(data)\n        self._get_fake_lane_pairs(fake_data)\n        route_data = self._join_complex_junctions(filtered_data)\n        self._add_junctions_topology(route_data)\n        self._junctions = route_data\n\n    def _get_junctions_data(self):\n        \"\"\"Gets all the junctions the ego passes through\"\"\"\n        junction_data = []\n        junction_num = 0\n        start_index = 0\n\n        # Ignore the junction the ego spawns at\n        for i in range(0, self._route_length - 1):\n            if not self._is_junction(self._route[i]):\n                start_index = i\n                break\n\n        for i in range(start_index, self._route_length - 1):\n            next_wp = self._route[i+1]\n            prev_junction = junction_data[-1] if len(junction_data) > 0 else None\n\n            # Searching for the junction exit\n            if prev_junction and prev_junction.route_exit_index is None:\n                if not self._is_junction(next_wp) or next_wp.get_junction().id != junction_id:\n                    prev_junction.route_exit_index = i+1\n\n            # Searching for a junction\n            elif self._is_junction(next_wp):\n                junction_id = next_wp.get_junction().id\n                if prev_junction:\n                    start_dist = self._accum_dist[i]\n                    prev_end_dist = self._accum_dist[prev_junction.route_exit_index]\n\n                # Same junction as the prev one and closer than 2 meters\n                if prev_junction and prev_junction.junctions[-1].id == junction_id:\n                    start_dist = self._accum_dist[i]\n                    prev_end_dist = self._accum_dist[prev_junction.route_exit_index]\n                    distance = start_dist - prev_end_dist\n                    if distance < 2:\n                        prev_junction.junctions.append(next_wp.get_junction())\n                        prev_junction.route_exit_index = None\n                        continue\n\n                junction_data.append(Junction(next_wp.get_junction(), junction_num, i))\n                junction_num += 1\n\n        return junction_data\n\n    def _filter_fake_junctions(self, data):\n        \"\"\"\n        Filters fake junctions. A fake junction is that which has no intersecting maneuvers\n        (i.e, no two maneuvers start / end at the same lane).\n        However, this fails for highway entry / exits with dedicated lanes, so specifically check those\n        \"\"\"\n        fake_data = []\n        filtered_data = []\n\n        for junction_data in data:\n            if len (junction_data.junctions) > 1:\n                filtered_data.append(junction_data)\n                continue  # These are always junctions\n\n            junction = junction_data.junctions[0]\n\n            found_intersecting_maneuvers = False\n            used_entries = []\n            used_exits = []\n\n            # Search for intersecting maneuvers\n            for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n                entry_key = get_lane_key(self._get_junction_entry_wp(entry_wp))\n                exit_key = get_lane_key(self._get_junction_exit_wp(exit_wp))\n\n                # Check if a maneuver starts / ends at another one.\n                # Checking if it was used isn't enough as some maneuvers are repeated in CARLA maps.\n                # Instead, check if the index of both entry and exit are different.\n                entry_index = -1 if entry_key not in used_entries else used_entries.index(entry_key)\n                exit_index = -1 if exit_key not in used_exits else used_exits.index(exit_key)\n\n                if exit_index != entry_index:\n                    found_intersecting_maneuvers = True\n                    break\n\n                used_entries.append(entry_key)\n                used_exits.append(exit_key)\n\n            if found_intersecting_maneuvers:\n                filtered_data.append(junction_data)\n                continue\n\n            # Search for highway dedicated lane entries.\n            found_highway = False\n            used_entry_roads = {}\n            used_exit_roads = {}\n            for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n                entry_road_key = get_road_key(self._get_junction_entry_wp(entry_wp))\n                exit_road_key = get_road_key(self._get_junction_exit_wp(exit_wp))\n\n                # Entries / exits with dedicated lanes have no intersecting maneuvers\n                # (as the entry / exit is a lane that finishes, not a maneuvers part of a junction),\n                # so they are missfiltered as fake junctions.\n                # Detect them by an entry road having 3 or more lanes. TODO: Improve this\n                if entry_road_key in used_entry_roads:\n                    used_entry_roads[entry_road_key] += 1\n                else:\n                    used_entry_roads[entry_road_key] = 0\n\n                if exit_road_key in used_exit_roads:\n                    used_exit_roads[exit_road_key] += 1\n                else:\n                    used_exit_roads[exit_road_key] = 0\n\n                if used_entry_roads[entry_road_key] >= 3 or used_exit_roads[exit_road_key] >= 3:\n                    found_highway = True\n                    break\n\n            if found_highway:\n                filtered_data.append(junction_data)\n                continue\n\n            fake_data.append(junction_data)\n\n            # TODO: Recheck for old CARLA maps\n\n        return fake_data, filtered_data\n\n    def _get_complex_junctions(self):\n        \"\"\"\n        Function to hardcode the topology of some complex junctions. This is done for the roundabouts,\n        as the current API doesn't offer that info as well as others such as the gas station at Town04.\n        If there are micro lanes between connected junctions, add them to the fake_lane_keys, connecting\n        them when their topology is calculated\n        \"\"\"\n        complex_junctions = []\n        fake_lane_keys = []\n\n        if 'Town03' in self._map.name:\n            # Roundabout, take it all as one\n            complex_junctions.append([\n                self._map.get_waypoint_xodr(1100, -5, 16.6).get_junction(),\n                self._map.get_waypoint_xodr(1624, -5, 25.3).get_junction(),\n                self._map.get_waypoint_xodr(1655, -5, 8.3).get_junction(),\n                self._map.get_waypoint_xodr(1772, 3, 16.2).get_junction(),\n                self._map.get_waypoint_xodr(1206, -5, 5.9).get_junction()])\n            fake_lane_keys.extend([\n                ['37*-4', '36*-4'], ['36*-4', '37*-4'],\n                ['37*-5', '36*-5'], ['36*-5', '37*-5'],\n                ['38*-4', '12*-4'], ['12*-4', '38*-4'],\n                ['38*-5', '12*-5'], ['12*-5', '38*-5']])\n\n            # Gas station\n            complex_junctions.append([\n                self._map.get_waypoint_xodr(1031, -1, 11.3).get_junction(),\n                self._map.get_waypoint_xodr(100, -1, 18.8).get_junction(),\n                self._map.get_waypoint_xodr(1959, -1, 22.7).get_junction()])\n            fake_lane_keys.extend([\n                ['32*-2', '33*-2'], ['33*-2', '32*-2'],\n                ['32*-1', '33*-1'], ['33*-1', '32*-1'],\n                ['32*4', '33*4'], ['33*4', '32*4'],\n                ['32*5', '33*5'], ['33*5', '32*5']])\n\n        elif 'Town04' in self._map.name:\n            # Gas station\n            complex_junctions.append([\n                self._map.get_waypoint_xodr(518, -1, 8.1).get_junction(),\n                self._map.get_waypoint_xodr(886, 1, 10.11).get_junction(),\n                self._map.get_waypoint_xodr(467, 1, 25.8).get_junction()])\n\n        self._fake_lane_pair_keys.extend(fake_lane_keys)\n        return complex_junctions\n\n    def _join_complex_junctions(self, filtered_data):\n        \"\"\"\n        Joins complex junctions into one. This makes it such that all the junctions,\n        as well as their connecting lanes, are treated as the same junction\n        \"\"\"\n        route_data = []\n        prev_index = -1\n\n        # If entering a complex, add all its junctions to the list\n        for junction_data in filtered_data:\n            junction = junction_data.junctions[0]\n            prev_junction = route_data[-1] if len(route_data) > 0 else None\n            complex_junctions = self._get_complex_junctions()\n\n            # Get the complex index\n            current_index = -1\n            for i, complex_junctions in enumerate(complex_junctions):\n                complex_ids = [j.id for j in complex_junctions]\n                if junction.id in complex_ids:\n                    current_index = i\n                    break\n\n            if current_index == -1:\n                # Outside a complex, add it\n                route_data.append(junction_data)\n\n            elif current_index == prev_index:\n                # Same complex as the previous junction\n                prev_junction.route_exit_index = junction_data.route_exit_index\n\n            else:\n                # New complex, add it\n                junction_ids = [j.id for j in junction_data.junctions]\n                for complex_junction in complex_junctions:\n                    if complex_junction.id not in junction_ids:\n                        junction_data.junctions.append(complex_junction)\n\n                route_data.append(junction_data)\n\n            prev_index = current_index\n\n        return route_data\n\n    def _get_fake_lane_pairs(self, fake_data):\n        \"\"\"Gets a list of entry-exit lanes of the fake junctions\"\"\"\n        for fake_junctions_data in fake_data:\n            for junction in fake_junctions_data.junctions:\n                for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n                    while self._is_junction(entry_wp):\n                        entry_wps = entry_wp.previous(0.5)\n                        if len(entry_wps) == 0:\n                            break  # Stop when there's no prev\n                        entry_wp = entry_wps[0]\n                    if self._is_junction(entry_wp):\n                        continue  # Triggered by the loops break\n\n                    while self._is_junction(exit_wp):\n                        exit_wps = exit_wp.next(0.5)\n                        if len(exit_wps) == 0:\n                            break  # Stop when there's no prev\n                        exit_wp = exit_wps[0]\n                    if self._is_junction(exit_wp):\n                        continue  # Triggered by the loops break\n\n                    self._fake_junction_ids.append(junction.id)\n                    self._fake_lane_pair_keys.append([get_lane_key(entry_wp), get_lane_key(exit_wp)])\n\n    def _get_junction_entry_wp(self, entry_wp):\n        \"\"\"For a junction waypoint, returns a waypoint outside of it that entrys into its lane\"\"\"\n        # Exit the junction\n        while self._is_junction(entry_wp):\n            entry_wps = entry_wp.previous(0.2)\n            if len(entry_wps) == 0:\n                return None  # Stop when there's no prev\n            entry_wp = entry_wps[0]\n        return entry_wp\n\n    def _get_junction_exit_wp(self, exit_wp):\n        \"\"\"For a junction waypoint, returns a waypoint outside of it from which the lane exits the junction\"\"\"\n        while self._is_junction(exit_wp):\n            exit_wps = exit_wp.next(0.2)\n            if len(exit_wps) == 0:\n                return None  # Stop when there's no prev\n            exit_wp = exit_wps[0]\n        return exit_wp\n\n    def _get_closest_junction_waypoint(self, waypoint, junction_wps):\n        \"\"\"\n        Matches a given wp to another one inside the list.\n        This is first done by checking its key, and if this fails, the closest wp is chosen\n        \"\"\"\n        # Check the lane keys\n        junction_keys = [get_lane_key(waypoint_) for waypoint_ in junction_wps]\n        if get_lane_key(waypoint) in junction_keys:\n            return waypoint\n\n        # Get the closest one\n        closest_dist = float('inf')\n        closest_junction_wp = None\n        route_location = waypoint.transform.location\n        for junction_wp in junction_wps:\n            distance = junction_wp.transform.location.distance(route_location)\n            if distance < closest_dist:\n                closest_dist = distance\n                closest_junction_wp = junction_wp\n\n        return closest_junction_wp\n\n    def _is_route_wp_behind_junction_wp(self, route_wp, junction_wp):\n        \"\"\"Checks if an actor is behind the ego. Uses the route transform\"\"\"\n        route_location = route_wp.transform.location\n        junction_transform = junction_wp.transform\n        junction_heading = junction_transform.get_forward_vector()\n        wps_vec = route_location - junction_transform.location\n        if junction_heading.x * wps_vec.x + junction_heading.y * wps_vec.y < - 0.09:  # 85º\n            return True\n        return False\n\n    def _add_junctions_topology(self, route_data):\n        \"\"\"Gets the entering and exiting lanes of a multijunction\"\"\"\n        for junction_data in route_data:\n            used_entry_lanes = []\n            used_exit_lanes = []\n            entry_lane_wps = []\n            exit_lane_wps = []\n\n            if self.debug:\n                print(' --------------------- ')\n            for junction in junction_data.junctions:\n                for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n\n                    entry_wp = self._get_junction_entry_wp(entry_wp)\n                    if not entry_wp:\n                        continue\n                    if get_lane_key(entry_wp) not in used_entry_lanes:\n                        used_entry_lanes.append(get_lane_key(entry_wp))\n                        entry_lane_wps.append(entry_wp)\n                        if self.debug:\n                            draw_point(self._world, entry_wp.transform.location, DEBUG_SMALL, DEBUG_ENTRY, True)\n\n                    exit_wp = self._get_junction_exit_wp(exit_wp)\n                    if not exit_wp:\n                        continue\n                    if get_lane_key(exit_wp) not in used_exit_lanes:\n                        used_exit_lanes.append(get_lane_key(exit_wp))\n                        exit_lane_wps.append(exit_wp)\n                        if self.debug:\n                            draw_point(self._world, exit_wp.transform.location, DEBUG_SMALL, DEBUG_EXIT, True)\n\n            # Check for connecting lanes. This is pretty much for the roundabouts, but some weird geometries\n            # make it possible for single junctions to have the same road entering and exiting. Two cases,\n            # Lanes that exit one junction and enter another (or viceversa)\n            exit_lane_keys = [get_lane_key(wp) for wp in exit_lane_wps]\n            entry_lane_keys = [get_lane_key(wp) for wp in entry_lane_wps]\n            for wp in list(entry_lane_wps):\n                if get_lane_key(wp) in exit_lane_keys:\n                    entry_lane_wps.remove(wp)\n                    if self.debug:\n                        draw_point(self._world, wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n\n            for wp in list(exit_lane_wps):\n                if get_lane_key(wp) in entry_lane_keys:\n                    exit_lane_wps.remove(wp)\n                    if self.debug:\n                        draw_point(self._world, wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n\n            # Lanes with a fake junction in the middle (maps junction exit to fake junction entry and viceversa)\n            for entry_key, exit_key in self._fake_lane_pair_keys:\n                entry_wp = None\n                for wp in entry_lane_wps:\n                    if get_lane_key(wp) == exit_key:  # A junction exit is a fake junction entry\n                        entry_wp = wp\n                        break\n                exit_wp = None\n                for wp in exit_lane_wps:\n                    if get_lane_key(wp) == entry_key:  # A junction entry is a fake junction exit\n                        exit_wp = wp\n                        break\n                if entry_wp and exit_wp:\n                    entry_lane_wps.remove(entry_wp)\n                    exit_lane_wps.remove(exit_wp)\n                    if self.debug:\n                        draw_point(self._world, entry_wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n                        draw_point(self._world, exit_wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n\n            junction_data.entry_wps = entry_lane_wps\n            junction_data.exit_wps = exit_lane_wps\n            junction_data.entry_lane_keys = entry_lane_keys\n            junction_data.exit_lane_keys = exit_lane_keys\n            for exit_wp in exit_lane_wps:\n                junction_data.exit_dict[get_lane_key(exit_wp)] = {\n                    'actors': [],\n                    'max_actors': 0,\n                    'ref_wp': None,\n                    'max_distance': 0,\n                }\n\n            # Filter the entries and exits that correspond to the route\n            route_entry_wp = self._route[junction_data.route_entry_index]\n\n            # Junction entry\n            for wp in get_same_dir_lanes(route_entry_wp):\n                junction_wp = self._get_closest_junction_waypoint(wp, entry_lane_wps)\n                junction_data.route_entry_keys.append(get_lane_key(junction_wp))\n            for wp in get_opposite_dir_lanes(route_entry_wp):\n                junction_wp = self._get_closest_junction_waypoint(wp, exit_lane_wps)\n                junction_data.opposite_exit_keys.append(get_lane_key(junction_wp))\n\n            # Junction exit\n            if junction_data.route_exit_index:  # Can be None if route ends at a junction\n                route_exit_wp = self._route[junction_data.route_exit_index]\n                for wp in get_same_dir_lanes(route_exit_wp):\n                    junction_wp = self._get_closest_junction_waypoint(wp, exit_lane_wps)\n                    junction_data.route_exit_keys.append(get_lane_key(junction_wp))\n                for wp in get_opposite_dir_lanes(route_exit_wp):\n                    junction_wp = self._get_closest_junction_waypoint(wp, entry_lane_wps)\n                    junction_data.opposite_entry_keys.append(get_lane_key(junction_wp))\n\n            # Add the entry directions of each lane with respect to the route. Used for scenarios 7 to 9\n            route_entry_yaw = route_entry_wp.transform.rotation.yaw\n            for wp in entry_lane_wps:\n                diff = (wp.transform.rotation.yaw - route_entry_yaw) % 360\n                if diff > 330.0:\n                    direction = 'ref'\n                elif diff > 225.0:\n                    direction = 'right'\n                elif diff > 135.0:\n                    direction = 'opposite'\n                elif diff > 30.0:\n                    direction = 'left'\n                else:\n                    direction = 'ref'\n\n                junction_data.entry_directions[direction].append(get_lane_key(wp))\n\n            # Supposing scenario vehicles go straight, these correspond to the exit lanes of the entry directions\n            for wp in exit_lane_wps:\n                diff = (wp.transform.rotation.yaw - route_entry_yaw) % 360\n                if diff > 330.0:\n                    direction = 'ref'\n                elif diff > 225.0:\n                    direction = 'right'\n                elif diff > 135.0:\n                    direction = 'opposite'\n                elif diff > 30.0:\n                    direction = 'left'\n                else:\n                    direction = 'ref'\n\n                junction_data.exit_directions[direction].append(get_lane_key(wp))\n\n            if self.debug:\n                exit_lane = self._route[junction_data.route_exit_index] if junction_data.route_exit_index else None\n                print('> R Entry Lane: {}'.format(get_lane_key(self._route[junction_data.route_entry_index])))\n                print('> R Exit  Lane: {}'.format(get_lane_key(exit_lane)))\n                entry_print = '> J Entry Lanes: '\n                for entry_wp in entry_lane_wps:\n                    key = get_lane_key(entry_wp)\n                    entry_print += key + ' ' * (8 - len(key))\n                print(entry_print)\n                exit_print = '> J Exit  Lanes: '\n                for exit_wp in exit_lane_wps:\n                    key = get_lane_key(exit_wp)\n                    exit_print += key + ' ' * (8 - len(key))\n                print(exit_print)\n                route_entry = '> R-J Entry Lanes: '\n                for entry_key in junction_data.route_entry_keys:\n                    route_entry += entry_key + ' ' * (8 - len(entry_key))\n                print(route_entry)\n                route_exit = '> R-J Route Exit  Lanes: '\n                for exit_key in junction_data.route_exit_keys:\n                    route_exit += exit_key + ' ' * (8 - len(exit_key))\n                print(route_exit)\n                route_oppo_entry = '> R-J Oppo Entry Lanes: '\n                for oppo_entry_key in junction_data.opposite_entry_keys:\n                    route_oppo_entry += oppo_entry_key + ' ' * (8 - len(oppo_entry_key))\n                print(route_oppo_entry)\n                route_oppo_exit = '> R-J Oppo Exit  Lanes: '\n                for oppo_exit_key in junction_data.opposite_exit_keys:\n                    route_oppo_exit += oppo_exit_key + ' ' * (8 - len(oppo_exit_key))\n                print(route_oppo_exit)\n\n    def _is_junction(self, waypoint):\n        if not waypoint.is_junction or waypoint.junction_id in self._fake_junction_ids:\n            return False\n        return True\n\n    ################################\n    ##       Mode functions       ##\n    ################################\n\n    def _add_actor_dict_element(self, actor_dict, actor, exit_lane_key='', at_oppo_entry_lane=False):\n        \"\"\"\n        Adds a new actor to the actor dictionary.\n        'exit_lane_key' is used to know at which exit lane (if any) is the vehicle\n        'at_oppo_entry_lane' whether or not the actor is part of the entry at the opposite lane the route exits through.\n        This will be the ones that aren't removed\n        \"\"\"\n        actor_dict[actor] = {\n            'state': JUNCTION_ENTRY if not exit_lane_key else JUNCTION_EXIT,\n            'exit_lane_key': exit_lane_key,\n            'at_oppo_entry_lane': at_oppo_entry_lane\n        }\n\n    def _switch_to_junction_mode(self, junction):\n        \"\"\"\n        Prepares the junction mode, removing all road behaviours.\n        Actors that are stopped via a scenario will still wait.\n        \"\"\"\n        self._ego_state = EGO_JUNCTION\n        for lane in self._road_dict:\n            for actor in self._road_dict[lane].actors:\n                # TODO: Map the actors to the junction entry to have full control of them.\n                # This should remove the 'at_oppo_entry_lane'.\n                self._add_actor_dict_element(junction.actor_dict, actor)\n                if actor not in self._scenario_stopped_actors:\n                    self._actors_speed_perc[actor] = 100\n\n        for lane_key in self._road_dict:\n            source = self._road_dict[lane_key]\n            source_key = get_lane_key(source.wp)\n            if source_key in junction.route_entry_keys:\n                junction.entry_sources.append(Source(\n                    source.wp, source.actors, entry_lane_wp=source.wp, active=source.active)\n                )\n                if source_key in junction.inactive_entry_keys:\n                    for actor in source.actors:\n                        self._destroy_actor(actor)\n                    source.active = False\n                    junction.inactive_entry_keys.remove(source_key)\n\n            # TODO: Else should map the source to the entry and add it\n\n        self._road_dict.clear()\n        self._opposite_sources.clear()\n\n    def _end_junction_behavior(self, junction):\n        \"\"\"\n        Destroys unneeded actors (those that aren't part of the route's road),\n        moving the rest to other data structures and cleaning up the variables.\n        If no other junctions are active, starts road mode\n        \"\"\"\n        actor_dict = junction.actor_dict\n        route_exit_keys = junction.route_exit_keys\n        self._active_junctions.pop(0)\n\n        # Prepare the road dictionary\n        if not self._active_junctions:\n            for wp in junction.exit_wps:\n                if get_lane_key(wp) in route_exit_keys:\n                    self._road_dict[get_lane_key(wp)] = Source(wp, [], active=self._active_road_sources)\n\n        else:\n            for wp in junction.exit_wps:\n                if get_lane_key(wp) in route_exit_keys:\n                    # TODO: entry_lane_wp isn't really this one (for cases with road changes)\n                    self._active_junctions[0].entry_sources.append(\n                        Source(wp, [], entry_lane_wp=wp, active=self._active_road_sources)\n                    )\n\n        # Handle the actors\n        for actor in list(actor_dict):\n            location = CarlaDataProvider.get_location(actor)\n            if not location or self._is_location_behind_ego(location):\n                self._destroy_actor(actor)\n                continue\n\n            # Don't destroy those that are on the route's road opposite lane.\n            # Instead, let them move freely until they are automatically destroyed.\n            self._actors_speed_perc[actor] = 100\n            if actor_dict[actor]['at_oppo_entry_lane']:\n                self._opposite_actors.append(actor)\n                self._tm.ignore_lights_percentage(actor, 100)\n                self._tm.ignore_signs_percentage(actor, 100)\n                continue\n\n            # Save those that are on the route's road\n            exit_key = actor_dict[actor]['exit_lane_key']\n            if exit_key in route_exit_keys:\n                if not self._active_junctions:\n                    self._road_dict[exit_key].actors.append(actor)\n                else:\n                    entry_sources = self._active_junctions[0].entry_sources\n                    for entry_source in entry_sources: # Add it to the back source\n                        if exit_key == get_lane_key(entry_source.wp):\n                            entry_sources.actors.append(actor)\n                            break\n                continue\n\n            # Destroy the rest\n            self._destroy_actor(actor)\n\n        # If the junction was part of a scenario, forget about it\n        self._scenario_junction_entry = False\n\n        if not self._active_junctions:\n            self._ego_state = EGO_ROAD\n            self._initialise_opposite_sources()\n            self._initialise_road_checker()\n\n    def _search_for_next_junction(self):\n        \"\"\"Check if closeby to a junction. The closest one will always be the first\"\"\"\n        if not self._junctions:\n            return None\n\n        ego_accum_dist = self._accum_dist[self._route_index]\n        junction_accum_dist = self._accum_dist[self._junctions[0].route_entry_index]\n        if junction_accum_dist - ego_accum_dist < self._detection_dist:  # Junctions closeby\n            return self._junctions.pop(0)\n\n        return None\n\n    def _initialise_connecting_lanes(self, junction):\n        \"\"\"\n        Moves the actors currently at the exit lane of the last junction\n        to entry actors of the newly created junction\n        \"\"\"\n        if len(self._active_junctions) > 0:\n            prev_junction = self._active_junctions[-1]\n            route_exit_keys = prev_junction.route_exit_keys\n            exit_dict = prev_junction.exit_dict\n            for exit_key in route_exit_keys:\n                exit_actors = exit_dict[exit_key]['actors']\n                for actor in list(exit_actors):\n                    self._remove_actor_info(actor)\n                    self._add_actor_dict_element(junction.actor_dict, actor)\n                    self._actors_speed_perc[actor] = 100\n\n    def _monitor_incoming_junctions(self):\n        \"\"\"\n        Monitors when the ego approaches a junction, triggering that junction when it happens.\n        This can be triggered even if there is another junction happening are they work independently\n        \"\"\"\n        junction = self._search_for_next_junction()\n        if not junction:\n            return\n\n        if self._ego_state == EGO_ROAD:\n            self._switch_to_junction_mode(junction)\n        self._initialise_junction_sources(junction)\n        self._initialise_junction_exits(junction)\n\n        self._initialise_connecting_lanes(junction)\n        self._active_junctions.append(junction)\n\n        # Forget the fact that a lane was removed, so that it isn't readded in the middle of the junction\n        self._scenario_removed_lane = False\n        self._scenario_remove_lane_offset = 0\n\n    def _monitor_ego_junction_exit(self):\n        \"\"\"\n        Monitors when the ego exits the junctions, preparing the road mode when that happens\n        \"\"\"\n        current_junction = self._active_junctions[0]\n        exit_index = current_junction.route_exit_index\n        if exit_index and self._route_index >= exit_index:\n            self._end_junction_behavior(current_junction)\n\n    def _add_incoming_actors(self, junction, source):\n        \"\"\"Checks nearby actors that will pass through the source, adding them to it\"\"\"\n        source_location = source.wp.transform.location\n        if not source.previous_lane_keys:\n            source.previous_lane_keys = [get_lane_key(prev_wp) for prev_wp in source.wp.previous(self._reuse_dist)]\n            source.previous_lane_keys.append(get_lane_key(source.wp))\n\n        for actor in self._all_actors:\n            if actor in source.actors:\n                continue  # Don't use actors already part of the source\n\n            actor_location = CarlaDataProvider.get_location(actor)\n            if actor_location is None:\n                continue  # No idea where the actor is, ignore it\n            if source_location.distance(actor_location) > self._reuse_dist:\n                continue  # Don't use actors far away\n\n            actor_wp = self._map.get_waypoint(actor_location)\n            if get_lane_key(actor_wp) not in source.previous_lane_keys:\n                continue  # Don't use actors that won't pass through the source\n\n            self._actors_speed_perc[actor] = 100\n            self._remove_actor_info(actor)\n            source.actors.append(actor)\n\n            at_oppo_entry_lane = get_lane_key(source.entry_lane_wp) in junction.opposite_entry_keys\n            self._add_actor_dict_element(junction.actor_dict, actor, at_oppo_entry_lane=at_oppo_entry_lane)\n\n            return actor\n\n    def _move_road_sources(self, prev_ego_index):\n        \"\"\"\n        Moves the road sources so that they are always following the ego from behind\n        \"\"\"\n        if prev_ego_index != self._route_index:\n            min_distance = self._road_back_vehicles * self._road_spawn_dist\n            for lane_key in self._road_dict:\n                source = self._road_dict[lane_key]\n\n                # If no actors are found, let the last_location be ego's location \n                # to keep moving the source waypoint forward\n                if len(source.actors) == 0:\n                    last_location = self._ego_wp.transform.location\n                else:\n                    last_location = CarlaDataProvider.get_location(source.actors[-1])\n\n                if last_location is None:\n                    continue\n\n                # Stop the sources in front of the ego (created by new lanes)\n                if not self._is_location_behind_ego(source.wp.transform.location):\n                    continue\n\n                # Stop the source from being too close to the ego or last lane vehicle\n                source_location = source.wp.transform.location\n                ego_location = self._ego_wp.transform.location\n\n                actor_dist = max(0, last_location.distance(source_location) - self._road_spawn_dist)\n                ego_dist = max(0, ego_location.distance(source_location) - min_distance)\n                move_dist = min(actor_dist, ego_dist)\n\n                # Move the source forward if needed\n                if move_dist > 0:\n                    new_source_wps = source.wp.next(move_dist)\n                    if not new_source_wps:\n                        continue\n                    source.wp = new_source_wps[0]\n\n    def _update_road_sources(self):\n        \"\"\"\n        Manages the sources that spawn actors behind the ego.\n        These are always behind the ego and will continuously spawn actors.\n        These sources also track the amount of vehicles in front of the ego,\n        removing actors if the amount is too high.\n        \"\"\"\n        for lane_key in self._road_dict:\n            source = self._road_dict[lane_key]\n            if self.debug:\n                draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_ROAD, False)\n                draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_ROAD, False)\n\n            # Ensure not too many actors are in front of the ego\n            front_veh = 0\n            for actor in source.actors:\n                location = CarlaDataProvider.get_location(actor)\n                if location and not self._is_location_behind_ego(location):\n                    front_veh += 1\n            if front_veh > self._road_front_vehicles:\n                self._destroy_actor(source.actors[0])  # This is always the front most vehicle\n\n            if not source.active:\n                continue\n            if not self._is_location_behind_ego(source.wp.transform.location):\n                continue  # Stop the sources in front of the ego (created by new lanes)\n            if len(source.actors) >= self._road_back_vehicles + self._road_front_vehicles:\n                continue\n\n            if len(source.actors) == 0:\n                location = self._ego_wp.transform.location\n            else:\n                location = CarlaDataProvider.get_location(source.actors[-1])\n                if not location:\n                    continue\n\n            distance = location.distance(source.wp.transform.location)\n\n            # Spawn a new actor if the last one is far enough\n            if distance > self._road_spawn_dist:\n                actor = self._spawn_source_actor(source, self._road_spawn_dist)\n                if actor is None:\n                    continue\n\n                # Set their initial speed, so that they don't lag behind the ego.\n                # Set the speed to the ego's one, but never surpassing by the lane's last vehicle's one\n                forward_vec = source.wp.transform.get_forward_vector()\n                speed = self._ego_actor.get_velocity().length()\n                if len(source.actors):\n                    speed = min(speed, source.actors[-1].get_velocity().length())\n                actor.set_target_velocity(speed * forward_vec)\n\n                source.actors.append(actor)\n\n    ################################\n    ## Behavior related functions ##\n    ################################\n\n    def _initialise_road_behavior(self, road_wps):\n        \"\"\"\n        Initialises the road behavior, consisting on several vehicle in front of the ego,\n        and several on the back and are only spawned outside junctions.\n        If there aren't enough actors behind, road sources will be created that will do so later on\n        \"\"\"\n        # Vehicles in front\n        for wp in road_wps:\n            spawn_wps = []\n\n            # Front spawn points\n            next_wp = wp\n            for _ in range(self._road_front_vehicles):\n                next_wps = next_wp.next(self._road_spawn_dist)\n                if len(next_wps) != 1 or self._is_junction(next_wps[0]):\n                    break  # Stop when there's no next or found a junction\n                next_wp = next_wps[0]\n                spawn_wps.insert(0, next_wp)\n\n            # Back spawn points\n            source_dist = 0\n            prev_wp = wp\n            for _ in range(self._road_back_vehicles):\n                prev_wps = prev_wp.previous(self._road_spawn_dist)\n                if len(prev_wps) != 1 or self._is_junction(prev_wps[0]):\n                    break  # Stop when there's no next or found a junction\n                prev_wp = prev_wps[0]\n                spawn_wps.append(prev_wp)\n                source_dist += self._road_spawn_dist\n\n            # Spawn actors\n            actors = self._spawn_actors(spawn_wps)\n\n            self._road_dict[get_lane_key(wp)] = Source(\n                prev_wp, actors, active=self._active_road_sources\n            )\n\n    def _initialise_opposite_sources(self):\n        \"\"\"\n        All opposite lanes have actor sources that will continually create vehicles,\n        creating the sensation of permanent traffic. The actor spawning will be done later on\n        (_update_opposite_sources). These sources are at a (somewhat) fixed distance\n        from the ego, but they never entering junctions. \n        \"\"\"\n        self._opposite_route_index = None\n        if not self._junctions:\n            next_junction_index = self._route_length - 1\n        else:\n            next_junction_index = self._junctions[0].route_entry_index\n\n        ego_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._route_index, next_junction_index):\n            if self._accum_dist[i] - ego_accum_dist > self._opposite_sources_dist:\n                self._opposite_route_index = i\n                break\n        if not self._opposite_route_index:\n            # Junction is closer than the opposite source distance\n            self._opposite_route_index = next_junction_index\n\n        oppo_wp = self._route[self._opposite_route_index]\n\n        for wp in get_opposite_dir_lanes(oppo_wp):\n            self._opposite_sources.append(Source(wp, [], active=self._active_opposite_sources))\n\n    def _initialise_road_checker(self):\n        \"\"\"\n        Gets the waypoints in front of the ego to continuously check if the road changes\n        \"\"\"\n        self._road_checker_index = None\n\n        if not self._junctions:\n            upper_limit = self._route_length - 1\n        else:\n            upper_limit = self._junctions[0].route_entry_index\n\n        ego_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._route_index, upper_limit):\n            if self._accum_dist[i] - ego_accum_dist > self._max_radius:\n                self._road_checker_index = i\n                break\n        if not self._road_checker_index:\n            self._road_checker_index = upper_limit\n\n    def _initialise_junction_sources(self, junction):\n        \"\"\"\n        Initializes the actor sources to ensure the junction is always populated. They are\n        placed at certain distance from the junction, but are stopped if another junction is found,\n        to ensure the spawned actors always move towards the activated one.\n        \"\"\"\n        for wp in junction.entry_wps:\n            entry_lane_key = get_lane_key(wp)\n            if entry_lane_key in junction.route_entry_keys:\n                continue  # Ignore the road from which the route enters\n\n            moved_dist = 0\n            prev_wp = wp\n            while moved_dist < self._junction_sources_dist:\n                prev_wps = prev_wp.previous(5)\n                if len(prev_wps) == 0 or self._is_junction(prev_wps[0]):\n                    break\n                prev_wp = prev_wps[0]\n                moved_dist += 5\n\n            # Don't add junction sources too close to the junction\n            if moved_dist < self._junction_minimum_source_dist:\n                continue\n\n            source = Source(prev_wp, [], entry_lane_wp=wp)\n            entry_lane_key = get_lane_key(wp)\n            if entry_lane_key in junction.inactive_entry_keys:\n                source.active = False\n                junction.inactive_entry_keys.remove(entry_lane_key)\n\n            junction.entry_sources.append(source)\n\n        # Real junctions aren't always full of traffic in all lanes, so deactivate some of them.\n        # Doing this after the source have been created in case another behavior activates them\n        for source in junction.entry_sources:\n            if 100 * self._rng.random() > self._junction_source_perc:\n                source.active = False\n\n    def _initialise_junction_exits(self, junction):\n        \"\"\"\n        Computes and stores the max capacity of the exit. Prepares the behavior of the next road\n        by creating actors at the route exit, and the sources that'll create actors behind the ego\n        \"\"\"\n        exit_wps = junction.exit_wps\n        route_exit_keys = junction.route_exit_keys\n\n        for wp in exit_wps:\n            max_actors = 0\n            max_distance = junction.exit_dict[get_lane_key(wp)]['max_distance']\n            exiting_wps = []\n\n            next_wp = wp\n\n            # Move the initial distance (added by the `_extent_road_exit_space`)\n            if max_distance > 0:\n                next_wps = next_wp.next(max_distance)\n                if not next_wps:\n                    continue\n                next_wp = next_wps[0]\n\n            for i in range(max(self._road_front_vehicles, 1)):\n\n                # Get the moving distance (first jump is higher to allow space for another vehicle)\n                if i == 0:\n                    move_dist = 2 * self._junction_spawn_dist\n                else:\n                    move_dist = self._junction_spawn_dist\n\n                # And move such distance\n                next_wps = next_wp.next(move_dist)\n                if len(next_wps) == 0:\n                    break  # Stop when there's no next\n                next_wp = next_wps[0]\n                if max_actors > 0 and self._is_junction(next_wp):\n                    break  # Stop when a junction is found\n\n                max_actors += 1\n                max_distance += move_dist\n                exiting_wps.insert(0, next_wp)\n\n            junction.exit_dict[get_lane_key(wp)] = {\n                'actors': [], 'max_actors': max_actors, 'ref_wp': wp, 'max_distance': max_distance\n            }\n\n            exit_lane_key = get_lane_key(wp)\n            if exit_lane_key in junction.inactive_exit_keys:\n                continue  # The exit is inactive, don't spawn anything\n\n            if exit_lane_key in route_exit_keys:\n                actors = self._spawn_actors(exiting_wps)\n                for actor in actors:\n                    self._add_actor_dict_element(junction.actor_dict, actor, exit_lane_key=exit_lane_key)\n                junction.exit_dict[exit_lane_key]['actors'] = actors\n\n    def _update_junction_sources(self):\n        \"\"\"Checks the actor sources to see if new actors have to be created\"\"\"\n        for junction in self._active_junctions:\n            actor_dict = junction.actor_dict\n            for source in junction.entry_sources:\n                if self.debug:\n                    draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_JUNCTION, False)\n                    draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_JUNCTION, False)\n\n                entry_lane_key = get_lane_key(source.entry_lane_wp)\n                at_oppo_entry_lane = entry_lane_key in junction.opposite_entry_keys\n\n                if not source.active:\n                    continue\n\n                self._add_incoming_actors(junction, source)\n\n                # Cap the amount of alive actors\n                if len(source.actors) >= self._junction_sources_max_actors:\n                    continue\n\n                # Calculate distance to the last created actor\n                if len(source.actors) == 0:\n                    actor_location = CarlaDataProvider.get_location(self._ego_actor)\n                else:\n                    actor_location = CarlaDataProvider.get_location(source.actors[-1])\n\n                if not actor_location:\n                    continue\n                distance = actor_location.distance(source.wp.transform.location)\n\n                # Spawn a new actor if the last one is far enough\n                if distance > self._junction_spawn_dist:\n                    actor = self._spawn_source_actor(source, self._junction_spawn_dist)\n                    if not actor:\n                        continue\n                    if junction.stop_non_route_entries and get_lane_key(source.entry_lane_wp) not in junction.route_entry_keys:\n                        self._actors_speed_perc[actor] = 0\n                    self._add_actor_dict_element(actor_dict, actor, at_oppo_entry_lane=at_oppo_entry_lane)\n                    source.actors.append(actor)\n\n    def _monitor_topology_changes(self, prev_index):\n        \"\"\"\n        Continually check the road in front to see if it has changed its topology.\n        If the number of lanes reduces, merge the ending lane with a side one\n        If the number of lanes increases, add a new road source.\n        \"\"\"\n        def get_road_wp(wp):\n            \"\"\"Goes backwards in the lane to match the wp with the road key dictionary\"\"\"\n            road_wp = wp\n            if get_lane_key(road_wp) in self._road_dict:\n                return road_wp\n\n            road_wp = wp\n            distance = self._max_radius\n\n            while distance > 0:\n                prev_wps = road_wp.previous(1)\n                if not prev_wps:\n                    return None\n                road_wp = prev_wps[0]\n                if get_lane_key(road_wp) in self._road_dict:\n                    return road_wp\n                distance -= 1\n\n            return None\n\n        def get_source_wp(wp):\n            \"\"\"Moves the wp forward until the lane is wide enough to fit a vehicle\"\"\"\n            source_wp = wp\n            while source_wp.lane_width < self._lane_width_threshold + 0.2:\n                source_wps = source_wp.next(1)\n                if not source_wps:\n                    return None\n                source_wp = source_wps[0]\n            return source_wp\n\n        if self.debug:\n            checker_wp = self._route[self._road_checker_index]\n            draw_point(self._world, checker_wp.transform.location, DEBUG_SMALL, DEBUG_ROAD, False)\n\n        if prev_index == self._route_index:\n            return\n\n        # Get the new route tracking wp\n        checker_index = None\n        last_index = self._junctions[0].route_entry_index if self._junctions else self._route_length - 1\n        current_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._road_checker_index, last_index):\n            accum_dist = self._accum_dist[i]\n            if accum_dist - current_accum_dist >= self._max_radius:\n                checker_index = i\n                break\n        if not checker_index:\n            checker_index = last_index\n\n        if checker_index == self._road_checker_index:\n            return\n\n        new_wps = get_same_dir_lanes(self._route[checker_index])\n        old_wps = get_same_dir_lanes(self._route[self._road_checker_index])\n\n        new_accum_dist = self._accum_dist[checker_index]\n        prev_accum_dist = self._accum_dist[self._road_checker_index]\n        route_move_dist = max(new_accum_dist - prev_accum_dist, 0.1)\n\n        if len(new_wps) > len(old_wps):\n            # Don't add anything in front if the junction entry has to be empty\n            if not self._scenario_junction_entry:\n\n                for new_wp in list(new_wps):\n\n                    prev_wps = new_wp.previous(2 * route_move_dist)  # x2, just in case\n                    if prev_wps:\n                        continue\n\n                    # Found the new lane, add the actors and source.\n                    # Don't spawn actors while the source is in front of the ego\n                    source_wp = get_source_wp(new_wp)\n                    if not source_wp:\n                        continue\n\n                    next_wp = source_wp\n                    spawn_wps = []\n                    spawn_dist = self._road_front_vehicles + CarlaDataProvider.get_velocity(self._ego_actor)\n                    for _ in range(self._road_front_vehicles):\n                        next_wps = next_wp.next(spawn_dist)\n                        if len(next_wps) != 1 or self._is_junction(next_wps[0]):\n                            break  # Stop when there's no next or found a junction\n                        next_wp = next_wps[0]\n                        spawn_wps.insert(0, next_wp)\n\n                    actors = self._spawn_actors(spawn_wps)\n\n                    if get_lane_key(source_wp) not in self._road_dict:\n                        # Lanes created away from the center won't affect the ids of other lanes, so just add the new id\n                        self._road_dict[get_lane_key(source_wp)] = Source(source_wp, actors, active=self._active_road_sources)\n                    else:\n                        # If the lane is inwards, all lanes have their id shifted by 1 outwards\n                        # TODO: Doesn't work for more than one lane.\n                        added_id = 1 if source_wp.lane_id > 0 else -1\n                        new_lane_key = get_lane_key_from_ids(source_wp.road_id, source_wp.lane_id + added_id)\n                        self._road_dict[new_lane_key] = self._road_dict[get_lane_key(source_wp)]\n                        self._road_dict[get_lane_key(source_wp)] = Source(source_wp, actors, active=self._active_road_sources)\n\n        elif len(new_wps) < len(old_wps):\n            for old_wp in list(old_wps):\n                next_wps = old_wp.next(2 * route_move_dist)  # x2, just in case\n                if next_wps:\n                    continue\n\n                # Found the lane that ends, merge it with the one on its side\n                road_wp = get_road_wp(old_wp)\n                if not road_wp:\n                    continue\n\n                # Get a side lane\n                right_wp = old_wp.get_right_lane()\n                left_wp = old_wp.get_left_lane()\n                side_road_wp = None\n                if right_wp and right_wp.lane_type == carla.LaneType.Driving:\n                    side_road_wp = get_road_wp(right_wp)\n                    side_path = [right_wp.transform.location]\n                elif left_wp and left_wp.lane_type == carla.LaneType.Driving:\n                    side_road_wp = get_road_wp(left_wp)\n                    side_path = [left_wp.transform.location]\n\n                if not side_road_wp:\n                    # No side lane found part of the road dictionary, remove them\n                    for actor in list(self._road_dict[get_lane_key(road_wp)].actors):\n                        self._destroy_actor(actor)\n                    self._road_dict.pop(get_lane_key(road_wp), None)\n                    continue\n\n                # Get the actors\n                lane_actors = self._road_dict[get_lane_key(road_wp)].actors\n                side_lane_actors = self._road_dict[get_lane_key(side_road_wp)].actors\n\n                # Get their distance to the ego\n                actors_with_dist = []\n                ego_location = self._ego_wp.transform.location\n                for actor in lane_actors + side_lane_actors:\n                    actor_location = CarlaDataProvider.get_location(actor)\n                    if not actor_location:\n                        self._destroy_actor(actor)\n                        continue\n                    dist = ego_location.distance(actor_location)\n                    if not self._is_location_behind_ego(actor_location):\n                        dist *= -1\n                    actors_with_dist.append([actor, dist])\n\n                # Sort them by distance\n                actors_sorted_with_dist = sorted(actors_with_dist, key=lambda a: a[1])\n                zero_index = len([a for a in actors_sorted_with_dist if a[1] < 0])\n                min_index = max(zero_index - self._road_front_vehicles, 0)\n                max_index = min(zero_index + self._road_front_vehicles - 1, len(actors_sorted_with_dist) - 1)\n\n                # Remove the unneeded ones, and make the ending lane actors perform a lane change\n                source_actors = []\n                for i, (actor, _) in enumerate(actors_sorted_with_dist):\n                    if i >= min_index and i <= max_index:\n                        source_actors.append(actor)\n                        self._tm.set_path(actor, side_path)\n                    else:\n                        self._destroy_actor(actor)\n\n                # And update the road dict\n                self._road_dict[get_lane_key(side_road_wp)].actors = source_actors\n                self._road_dict.pop(get_lane_key(road_wp), None)\n\n        self._road_checker_index = checker_index\n\n    def _move_opposite_sources(self, prev_index):\n        \"\"\"\n        Moves the sources of the opposite direction back. Additionally, tracks a point a certain distance\n        in front of the ego to see if the road topology has to be recalculated\n        \"\"\"\n        if self.debug:\n            for source in self._opposite_sources:\n                draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_OPPOSITE, False)\n                draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_OPPOSITE, False)\n            route_wp = self._route[self._opposite_route_index]\n            draw_point(self._world, route_wp.transform.location, DEBUG_SMALL, DEBUG_OPPOSITE, False)\n\n        if prev_index == self._route_index:\n            return\n\n        # Get the new route tracking wp\n        oppo_route_index = None\n        last_index = self._junctions[0].route_entry_index if self._junctions else self._route_length - 1\n        current_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._opposite_route_index, last_index):\n            accum_dist = self._accum_dist[i]\n            if accum_dist - current_accum_dist >= self._opposite_sources_dist:\n                oppo_route_index = i\n                break\n        if not oppo_route_index:\n            oppo_route_index = last_index\n\n        # Get the distance moved by the route reference index\n        new_accum_dist = self._accum_dist[oppo_route_index]\n        prev_accum_dist = self._accum_dist[self._opposite_route_index]\n        route_move_dist = new_accum_dist - prev_accum_dist\n        if route_move_dist <= 0:\n            return  # Sometimes a route wp is behind the pervious one, filter these out\n\n        new_opposite_wps = get_opposite_dir_lanes(self._route[oppo_route_index])\n\n        if len(new_opposite_wps) != len(self._opposite_sources):\n            # The topology has changed. Remap the new lanes to the sources\n            new_opposite_sources = []\n            for wp in new_opposite_wps:\n                location = wp.transform.location\n                new_source = None\n                for source in self._opposite_sources:\n                    if location.distance(source.wp.transform.location) < 1.1 * route_move_dist:\n                        new_source = source\n                        break\n\n                if new_source:\n                    new_source.wp = wp\n                    new_opposite_sources.append(new_source)\n                    self._opposite_sources.remove(new_source)\n                else:\n                    new_opposite_sources.append(Source(wp, []))\n\n            self._opposite_sources = new_opposite_sources\n        else:\n            # The topology hasn't changed, move the distance backwards\n            for source in self._opposite_sources:\n                wp = source.wp\n                if not self._is_junction(wp):\n                    prev_wps = wp.previous(route_move_dist)\n                    if len(prev_wps) == 0:\n                        continue\n                    prev_wp = prev_wps[0]\n                    source.wp = prev_wp\n\n        self._opposite_route_index = oppo_route_index\n\n    def _update_opposite_sources(self):\n        \"\"\"Checks the opposite actor sources to see if new actors have to be created\"\"\"\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n        for source in self._opposite_sources:\n            if not source.active:\n                continue\n\n            # Ending / starting lanes create issues as the lane width gradually decreases until reaching 0,\n            # where the lane starts / ends. Avoid spawning anything inside those parts with small lane width\n            if source.wp.lane_width < self._lane_width_threshold:\n                continue\n\n            # Calculate distance to the last created actor\n            if len(source.actors) == 0:\n                distance = self._opposite_sources_dist + 1\n            else:\n                actor_location = CarlaDataProvider.get_location(source.actors[-1])\n                if not actor_location:\n                    continue\n                distance = source.wp.transform.location.distance(actor_location)\n\n            # Spawn a new actor if the last one is far enough\n            if distance > self._opposite_spawn_dist:\n                actor = self._spawn_source_actor(source)\n                if actor is None:\n                    continue\n                self._tm.ignore_lights_percentage(actor, 100)\n                self._tm.ignore_signs_percentage(actor, 100)\n                self._opposite_actors.append(actor)\n                source.actors.append(actor)\n\n    def _update_parameters(self):\n        \"\"\"\n        Changes those parameters that have dynamic behaviors and / or that can be changed by external source.\n        This is done using py_trees' Blackboard variables and all behaviors should be at `background_manager.py`.\n        The blackboard variable is reset to None to avoid changing them back again next time.\n        \"\"\"\n        # Road behavior\n        road_behavior_data = py_trees.blackboard.Blackboard().get('BA_ChangeRoadBehavior')\n        if road_behavior_data is not None:\n            num_front_vehicles, num_back_vehicles, spawn_dist, extra_space = road_behavior_data\n            if num_front_vehicles is not None:\n                self._road_front_vehicles = num_front_vehicles\n            if num_back_vehicles is not None:\n                self._road_back_vehicles = num_back_vehicles\n            if spawn_dist is not None:\n                self._road_spawn_dist = spawn_dist\n            if extra_space is not None:\n                self._road_extra_space = extra_space\n            self._get_road_radius()\n            py_trees.blackboard.Blackboard().set('BA_ChangeRoadBehavior', None, True)\n\n        # Opposite behavior\n        opposite_behavior_data = py_trees.blackboard.Blackboard().get('BA_ChangeOppositeBehavior')\n        if opposite_behavior_data is not None:\n            source_dist, spawn_dist, active = opposite_behavior_data\n            if source_dist is not None:\n                if source_dist < self._junction_sources_dist:\n                    print('WARNING: Opposite sources distance is lower than the junction ones. Ignoring it')\n                else:\n                    self._opposite_sources_dist = source_dist\n            if spawn_dist is not None:\n                self._opposite_spawn_dist = spawn_dist\n                self._opposite_sources_dist = 2 * spawn_dist\n            if active is not None:\n                self._active_opposite_sources = active\n                for source in self._opposite_sources:\n                    source.active = active\n            py_trees.blackboard.Blackboard().set('BA_ChangeOppositeBehavior', None, True)\n\n        # Junction behavior\n        junction_behavior_data = py_trees.blackboard.Blackboard().get('BA_ChangeJunctionBehavior')\n        if junction_behavior_data is not None:\n            source_dist, spawn_dist, max_actors, source_perc = junction_behavior_data\n            if source_dist is not None:\n                if source_dist > self._opposite_sources_dist:\n                    print('WARNING: Junction sources distance is higher than the opposite ones. Ignoring it')\n                else:\n                    self._junction_sources_dist = source_dist\n            if spawn_dist:\n                self._junction_spawn_dist = spawn_dist\n            if max_actors is not None:\n                self._junction_sources_max_actors = max_actors\n            if source_perc is not None:\n                self._junction_source_perc = source_perc\n            py_trees.blackboard.Blackboard().set('BA_ChangeJunctionBehavior', None, True)\n\n        # Max speed\n        max_speed = py_trees.blackboard.Blackboard().get('BA_SetMaxSpeed')\n        if max_speed is not None:\n            self._scenario_max_speed = max_speed\n            py_trees.blackboard.Blackboard().set('BA_SetMaxSpeed', None, True)\n\n        # Stop front vehicles\n        stop_data = py_trees.blackboard.Blackboard().get('BA_StopFrontVehicles')\n        if stop_data is not None:\n            self._stop_road_front_vehicles()\n            py_trees.blackboard.Blackboard().set('BA_StopFrontVehicles', None, True)\n\n        # Start front vehicles\n        start_data = py_trees.blackboard.Blackboard().get('BA_StartFrontVehicles')\n        if start_data is not None:\n            self._start_road_front_vehicles()\n            py_trees.blackboard.Blackboard().set(\"BA_StartFrontVehicles\", None, True)\n\n        # Stop back vehicles\n        stop_back_data = py_trees.blackboard.Blackboard().get('BA_StopBackVehicles')\n        if stop_back_data is not None:\n            self._stop_road_back_vehicles()\n            py_trees.blackboard.Blackboard().set('BA_StopBackVehicles', None, True)\n\n        # Start back vehicles\n        start_back_data = py_trees.blackboard.Blackboard().get('BA_StartBackVehicles')\n        if start_back_data is not None:\n            self._start_road_back_vehicles()\n            py_trees.blackboard.Blackboard().set(\"BA_StartBackVehicles\", None, True)\n\n        # Leave space in front\n        leave_space_data = py_trees.blackboard.Blackboard().get('BA_LeaveSpaceInFront')\n        if leave_space_data is not None:\n            self._leave_space_in_front(leave_space_data)\n            py_trees.blackboard.Blackboard().set('BA_LeaveSpaceInFront', None, True)\n\n        # Leave crosssing space\n        leave_crossing_space_data = py_trees.blackboard.Blackboard().get('BA_LeaveCrossingSpace')\n        if leave_crossing_space_data is not None:\n            self._leave_crossing_space(leave_crossing_space_data)\n            py_trees.blackboard.Blackboard().set('BA_LeaveCrossingSpace', None, True)\n\n        # Remove road lane\n        remove_road_lane_data = py_trees.blackboard.Blackboard().get('BA_RemoveRoadLane')\n        if remove_road_lane_data is not None:\n            self._remove_road_lane(remove_road_lane_data)\n            py_trees.blackboard.Blackboard().set('BA_RemoveRoadLane', None, True)\n\n        # Readd road lane\n        readd_road_lane_data = py_trees.blackboard.Blackboard().get('BA_ReAddRoadLane')\n        if readd_road_lane_data is not None:\n            self._readd_road_lane(readd_road_lane_data)\n            py_trees.blackboard.Blackboard().set('BA_ReAddRoadLane', None, True)\n\n        # Adapt the BA to the junction scenario\n        junction_scenario_data = py_trees.blackboard.Blackboard().get('BA_HandleJunctionScenario')\n        if junction_scenario_data is not None:\n            self._handle_junction_scenario(junction_scenario_data)\n            py_trees.blackboard.Blackboard().set(\"BA_HandleJunctionScenario\", None, True)\n\n        # Switch route sources\n        switch_sources_data = py_trees.blackboard.Blackboard().get('BA_SwitchRouteSources')\n        if switch_sources_data is not None:\n            self._switch_route_sources(switch_sources_data)\n            py_trees.blackboard.Blackboard().set(\"BA_SwitchRouteSources\", None, True)\n\n        self._compute_parameters()\n\n    def _compute_parameters(self):\n        \"\"\"Computes the parameters that are dependent on the speed of the ego. \"\"\"\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n        self._min_radius = self._base_min_radius + self._radius_increase_ratio * ego_speed + self._road_extra_space\n        self._max_radius = self._base_max_radius + self._radius_increase_ratio * ego_speed + self._road_extra_space\n        self._detection_dist = self._base_junction_detection + self._detection_ratio * ego_speed\n\n    def _stop_road_front_vehicles(self):\n        \"\"\"\n        Stops all road vehicles in front of the ego. Use `_start_road_front_vehicles` to make them move again.\n        \"\"\"\n        for lane in self._road_dict:\n            for actor in self._road_dict[lane].actors:\n                location = CarlaDataProvider.get_location(actor)\n                if location and not self._is_location_behind_ego(location):\n                    self._scenario_stopped_actors.append(actor)\n                    self._actors_speed_perc[actor] = 0\n                    self._tm.update_vehicle_lights(actor, False)\n                    lights = actor.get_light_state()\n                    lights |= carla.VehicleLightState.Brake\n                    actor.set_light_state(carla.VehicleLightState(lights))\n\n    def _start_road_front_vehicles(self):\n        \"\"\"\n        Restarts all road vehicles stopped by `_stop_road_front_vehicles`.\n        \"\"\"\n        for actor in self._scenario_stopped_actors:\n            self._actors_speed_perc[actor] = 100\n            self._tm.update_vehicle_lights(actor, True)\n            lights = actor.get_light_state()\n            lights &= ~carla.VehicleLightState.Brake\n            actor.set_light_state(carla.VehicleLightState(lights))\n        self._scenario_stopped_actors = []\n\n    def _stop_road_back_vehicles(self):\n        \"\"\"\n        Stops all road vehicles behind the ego. Use `_start_road_back_vehicles` to make them move again.\n        \"\"\"\n        for lane in self._road_dict:\n            for actor in self._road_dict[lane].actors:\n                location = CarlaDataProvider.get_location(actor)\n                if location and self._is_location_behind_ego(location):\n                    self._actors_speed_perc[actor] = 0\n                    self._scenario_stopped_back_actors.append(actor)\n\n    def _start_road_back_vehicles(self):\n        \"\"\"\n        Restarts all road vehicles stopped by `_stop_road_back_vehicles`.\n        \"\"\"\n        for actor in self._scenario_stopped_back_actors:\n            self._actors_speed_perc[actor] = 100\n        self._scenario_stopped_back_actors = []\n\n    def _move_actors_forward(self, actors, space):\n        \"\"\"Teleports the actors forward a set distance\"\"\"\n        for actor in list(actors):\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n\n            actor_wp = self._map.get_waypoint(location)\n            new_actor_wps = actor_wp.next(space)\n            if len(new_actor_wps) > 0:\n                new_transform = new_actor_wps[0].transform\n                new_transform.location.z += 0.2\n                actor.set_transform(new_transform)\n            else:\n                self._destroy_actor(actor)\n\n    def _switch_route_sources(self, enabled):\n        \"\"\"\n        Disables all sources that are part of the ego's route\n        \"\"\"\n        self._active_road_sources = enabled\n        for lane in self._road_dict:\n            self._road_dict[lane].active = enabled\n\n        for junction in self._active_junctions:\n            for source in junction.entry_sources:\n                if get_lane_key(source.entry_lane_wp) in junction.route_entry_keys:\n                    source.active = enabled\n\n    def _leave_space_in_front(self, space):\n        \"\"\"Teleports all the vehicles in front of the ego forward\"\"\"\n        if self._ego_key not in self._road_dict:\n            return\n\n        if self._active_junctions:\n            return\n\n        front_actors = []\n        min_distance = float('inf')\n        for actor in self._road_dict[self._ego_key].actors:\n            location = CarlaDataProvider.get_location(actor)\n            if not location or self._is_location_behind_ego(location):\n                continue\n\n            front_actors.append(actor)\n            distance = location.distance(self._ego_wp.transform.location)\n            if distance < min_distance:\n                min_distance = distance\n\n        step = space - min_distance\n        if step > 0:  # Only move them if needed and only the minimum required distance\n            self._move_actors_forward(front_actors, step)\n\n    def _leave_crossing_space(self, collision_wp):\n        \"\"\"Removes all vehicle in the middle of crossing trajectory and stops the nearby ones\"\"\"\n        destruction_dist = 20\n        stop_dist = 30\n\n        opposite_wp = collision_wp.get_left_lane()\n        if not opposite_wp:\n            return  # Nothing else to do\n        opposite_loc = opposite_wp.transform.location\n\n        for actor in list(self._opposite_actors):\n            location = actor.get_location()\n            if not location:\n                continue\n\n            collision_dist = location.distance(opposite_loc)\n            if collision_dist < destruction_dist:\n                self._destroy_actor(actor)\n            elif collision_dist < stop_dist:\n                actor.set_target_velocity(carla.Vector3D())\n\n    def _remove_road_lane(self, lane_wp):\n        \"\"\"Removes a road lane\"\"\"\n        self._scenario_removed_lane = True\n        self._scenario_remove_lane_offset = 0\n        lane_key = get_lane_key(lane_wp)\n        if lane_key not in list(self._road_dict):\n            print(f\"WARNING: Couldn't find the lane to be removed, '{lane_key}' isn't part of the road behavior\")\n            return\n\n        self._road_dict[lane_key].active = False\n        for actor in list(self._road_dict[lane_key].actors):\n            self._destroy_actor(actor)\n        self._road_dict.pop(lane_key, None)\n\n    def _readd_road_lane(self, lane_offset):\n        \"\"\"Adds a ego road lane. This is expected to be used after having previously removed such lane\"\"\"\n        # Check that the ego hasn't moved close to a junction, where we don't want to reinitialize the lane\n        if not self._scenario_removed_lane:\n            return\n\n        lane_offset += self._scenario_remove_lane_offset\n\n        if lane_offset == 0:\n            add_lane_wp = self._ego_wp\n            add_lane_key = self._ego_key\n        else:\n            side_wp = self._ego_wp\n            for _ in range(abs(lane_offset)):\n                side_wp = side_wp.get_right_lane() if lane_offset > 0 else side_wp.get_left_lane()\n                if not side_wp:\n                    print(f\"WARNING: Couldn't find a lane with the desired offset\")\n                    return\n\n            add_lane_wp = side_wp\n            add_lane_key = get_lane_key(side_wp)\n\n        if add_lane_key in list(self._road_dict):\n            print(f\"WARNING: Couldn't add a lane {add_lane_key} as it is already part of the road\")\n            return\n\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n        spawn_dist = self._road_spawn_dist + 2 * ego_speed\n\n        spawn_wps = []\n\n        next_wp = add_lane_wp\n        for _ in range(self._road_front_vehicles):\n            next_wps = next_wp.next(spawn_dist)\n            if len(next_wps) != 1 or self._is_junction(next_wps[0]):\n                break  # Stop when there's no next or found a junction\n            next_wp = next_wps[0]\n            spawn_wps.insert(0, next_wp)\n\n        source_dist = 0\n        prev_wp = add_lane_wp\n        for _ in range(self._road_back_vehicles):\n            prev_wps = prev_wp.previous(spawn_dist)\n            if len(prev_wps) != 1 or self._is_junction(prev_wps[0]):\n                break  # Stop when there's no next or found a junction\n            prev_wp = prev_wps[0]\n            spawn_wps.append(prev_wp)\n            source_dist += spawn_dist\n\n        actors = []\n        for spawn_wp in spawn_wps:\n            actor = self._spawn_actor(spawn_wp)\n            if not actor:\n                continue\n            actor.set_target_velocity(spawn_wp.transform.get_forward_vector() * ego_speed)\n            actors.append(actor)\n\n        self._road_dict[add_lane_key] = Source(prev_wp, actors, active=self._active_road_sources)\n\n        self._scenario_removed_lane = False\n        self._scenario_remove_lane_offset = 0\n\n    def _handle_junction_scenario(self, junction_data):\n        \"\"\"\n        Adapts the BA to the junction scenario by clearing the junction,\n        its entries, exits, and by extending the road exit to add more space\n        \"\"\"\n        clear_junction, clear_ego_entry, remove_entries, remove_exits, stop_entries, extend_road_exit = junction_data\n\n        if clear_junction:\n            self._clear_junction_middle()\n\n        if clear_ego_entry:\n            self._clear_ego_entry()\n\n        if remove_entries:\n            self._remove_junction_entries(remove_entries)\n\n        if remove_exits:\n            self._remove_junction_exits(remove_exits)\n\n        if stop_entries:\n            self._stop_non_ego_route_entries()\n\n        if extend_road_exit:\n            self._extent_road_exit_space(extend_road_exit)\n\n        self._scenario_removed_lane = False\n        self._scenario_remove_lane_offset = 0\n\n    def _clear_junction_middle(self):\n        \"\"\"Clears the junction, and all subsequent actors that enter it\"\"\"\n        if self._active_junctions:\n            junction = self._active_junctions[0]\n            actor_dict = junction.actor_dict\n            for actor in list(actor_dict):\n                if actor_dict[actor]['state'] == JUNCTION_MIDDLE:\n                    self._destroy_actor(actor)\n            junction.clear_middle = True\n\n        elif self._junctions:\n            self._junctions[0].clear_middle = True\n\n    def _clear_ego_entry(self):\n        \"\"\"\n        Remove all actors in front of the vehicle.\n        \"\"\"\n        def handle_actors(actor_list):\n            for actor in list(actor_list):\n                location = CarlaDataProvider.get_location(actor)\n                if location and not self._is_location_behind_ego(location):\n                    self._destroy_actor(actor)\n\n        # This will make the actors behind never overtake the ego\n        self._scenario_junction_entry = True\n\n        if self._active_junctions:\n            for source in self._active_junctions[0].entry_sources:\n                handle_actors(source.actors)\n        else:\n            for lane_key in list(self._road_dict):\n                source = self._road_dict[lane_key]\n                handle_actors(source.actors)\n                source.active = False\n\n    def _remove_junction_entries(self, wps):\n        \"\"\"Removes a list of entries of the closest junction (or marks them so that they aren't spawned)\"\"\"\n        if len(self._active_junctions) > 0:\n            junction = self._active_junctions[0]\n        elif len(self._junctions) > 0:\n            junction = self._junctions[0]\n        else:\n            return\n\n        for wp in wps:\n            mapped_key = None\n            next_wp = wp\n            while not self._is_junction(next_wp):\n                lane_key = get_lane_key(next_wp)\n                if lane_key in junction.entry_lane_keys:\n                    mapped_key = lane_key\n                    break\n                next_wps = next_wp.next(1)\n                if not next_wps:\n                    break\n                next_wp = next_wps[0]\n\n            if not mapped_key:\n                print(\"WARNING: Couldn't find the asked entry to be removed\")\n                continue\n\n            if len(self._active_junctions) > 0:\n                for source in junction.entry_sources:\n                    if get_lane_key(source.wp) == mapped_key:\n                        for actor in list(source.actors):\n                            self._destroy_actor(actor)\n                        source.active = False\n            else:\n                junction.inactive_entry_keys.append(mapped_key)\n\n    def _remove_junction_exits(self, wps):\n        \"\"\"Removes a list of exit of the closest junction (or marks them so that they aren't spawned)\"\"\"\n        if len(self._active_junctions) > 0:\n            junction = self._active_junctions[0]\n        elif len(self._junctions) > 0:\n            junction = self._junctions[0]\n        else:\n            return\n\n        for wp in wps:\n\n            mapped_key = None\n            prev_wp = wp\n            while not self._is_junction(prev_wp):\n                lane_key = get_lane_key(prev_wp)\n                if lane_key in junction.exit_dict:\n                    mapped_key = lane_key\n                    break\n                prev_wps = prev_wp.next(1)\n                if not prev_wps:\n                    break\n                prev_wp = prev_wps[0]\n\n            if not mapped_key:\n                print(\"WARNING: Couldn't find the asked exit to be removed\")\n                continue\n\n            if len(self._active_junctions) > 0:\n                for actor in list(junction.exit_dict[mapped_key]['actors']):\n                    self._destroy_actor(actor)\n            else:\n                junction.inactive_exit_keys.append(mapped_key)\n\n    def _stop_non_ego_route_entries(self):\n        \"\"\"Clears the junction, and all subsequent actors that enter it\"\"\"\n        if self._active_junctions:\n\n            # Remove all actors in the middle\n            junction = self._active_junctions[0]\n            actor_dict = junction.actor_dict\n\n            entry_sources = junction.entry_sources\n            route_entry_keys = junction.route_entry_keys\n            for source in entry_sources:\n                if get_lane_key(source.entry_lane_wp) not in route_entry_keys:\n                    for actor in source.actors:\n                        if actor_dict[actor]['state'] == JUNCTION_ENTRY:\n                            self._actors_speed_perc[actor] = 0\n\n        elif self._junctions:\n            self._junctions[0].stop_non_route_entries = True\n\n    def _extent_road_exit_space(self, space):\n        \"\"\"Increases the space left by the exit vehicles at a specific road\"\"\"\n        if len(self._active_junctions) > 0:\n            junction = self._active_junctions[0]\n        elif len(self._junctions) > 0:\n            junction = self._junctions[0]\n        else:\n            return\n\n        route_lane_keys = junction.route_exit_keys\n\n        for exit_lane_key in route_lane_keys:\n            junction.exit_dict[exit_lane_key]['max_distance'] += space\n            actors = junction.exit_dict[exit_lane_key]['actors']\n            self._move_actors_forward(actors, space)\n            for actor in actors:\n                if junction.actor_dict[actor]['state'] == JUNCTION_EXIT_ROAD:\n                    self._actors_speed_perc[actor] = 100\n                    junction.actor_dict[actor]['state'] = JUNCTION_EXIT\n\n    #############################\n    ##     Actor functions     ##\n    #############################\n    def _initialise_actor(self, actor):\n        \"\"\"\n        Save the actor into the needed structures, disable its lane changes and set the leading distance.\n        \"\"\"\n        self._tm.auto_lane_change(actor, self._vehicle_lane_change)\n        self._tm.update_vehicle_lights(actor, self._vehicle_lights)\n        self._tm.distance_to_leading_vehicle(actor, self._vehicle_leading_distance)\n        self._tm.vehicle_lane_offset(actor, self._vehicle_offset)\n        self._all_actors.append(actor)\n\n    def _spawn_actor(self, spawn_wp, ego_dist=0):\n        \"\"\"Spawns an actor\"\"\"\n        ego_location = CarlaDataProvider.get_location(self._ego_actor)\n        if ego_location.distance(spawn_wp.transform.location) < ego_dist:\n            return None\n\n        spawn_transform = carla.Transform(\n            spawn_wp.transform.location + carla.Location(z=self._spawn_vertical_shift),\n            spawn_wp.transform.rotation\n        )\n\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', spawn_transform, 'background', True,\n            attribute_filter={'base_type': 'car', 'has_lights': True}, tick=False\n        )\n\n        if not actor:\n            return actor\n        self._initialise_actor(actor)\n        return actor\n\n    def _spawn_actors(self, spawn_wps, ego_dist=0):\n        \"\"\"Spawns several actors in batch\"\"\"\n        spawn_transforms = []\n        ego_location = CarlaDataProvider.get_location(self._ego_actor)\n        for wp in spawn_wps:\n            if ego_location.distance(wp.transform.location) < ego_dist:\n                continue\n            spawn_transforms.append(\n                carla.Transform(wp.transform.location + carla.Location(z=self._spawn_vertical_shift),\n                                wp.transform.rotation)\n            )\n\n        actors = CarlaDataProvider.request_new_batch_actors(\n            'vehicle.*', len(spawn_transforms), spawn_transforms, True, False, 'background',\n            attribute_filter=self._attribute_filter, tick=False)\n\n        if not actors:\n            return actors\n\n        for actor in actors:\n            self._initialise_actor(actor)\n\n        return actors\n\n    def _spawn_source_actor(self, source, ego_dist=20):\n        \"\"\"Given a source, spawns an actor at that source\"\"\"\n        ego_location = CarlaDataProvider.get_location(self._ego_actor)\n        source_transform = source.wp.transform\n        if ego_location.distance(source_transform.location) < ego_dist:\n            return None\n\n        new_transform = carla.Transform(\n            source_transform.location + carla.Location(z=self._spawn_vertical_shift),\n            source_transform.rotation\n        )\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', new_transform, rolename='background',\n            autopilot=True, random_location=False, attribute_filter=self._attribute_filter, tick=False)\n\n        if not actor:\n            return actor\n\n        self._initialise_actor(actor)\n        return actor\n\n    def _is_location_behind_ego(self, location):\n        \"\"\"Checks if an actor is behind the ego. Uses the route transform\"\"\"\n        ego_transform = self._route[self._route_index].transform\n        ego_heading = ego_transform.get_forward_vector()\n        ego_actor_vec = location - ego_transform.location\n        if ego_heading.dot(ego_actor_vec) < - 0.17:  # 100º\n            return True\n        return False\n\n    def _update_road_actors(self):\n        \"\"\"\n        Dynamically controls the actor speed in front of the ego.\n        Not applied to those behind it so that they can catch up it\n        \"\"\"\n        # Updates their speed\n        scenario_actors = self._scenario_stopped_actors + self._scenario_stopped_back_actors\n        for lane_key in self._road_dict:\n            for i, actor in enumerate(self._road_dict[lane_key].actors):\n                location = CarlaDataProvider.get_location(actor)\n                if not location:\n                    continue\n                if self.debug:\n                    string = 'R_'\n                    string += 'B' if self._is_location_behind_ego(location) else 'F'\n                    string += '_(' + str(i) + ')'\n                    string += '_[' + lane_key + ']'\n                    draw_string(self._world, location, string, DEBUG_ROAD, False)\n\n                # Actors part of scenarios are their own category, ignore them\n                if actor in scenario_actors:\n                    continue\n\n                # TODO: Lane changes are weird with the TM, so just stop them\n                actor_wp = self._map.get_waypoint(location)\n                if actor_wp.lane_width < self._lane_width_threshold:\n\n                    # Ensure only ending lanes are affected. not sure if it is needed though\n                    next_wps = actor_wp.next(0.5)\n                    if next_wps and next_wps[0].lane_width < actor_wp.lane_width:\n                        actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n                        self._actors_speed_perc[actor] = 0\n                        lights = actor.get_light_state()\n                        lights |= carla.VehicleLightState.RightBlinker\n                        lights |= carla.VehicleLightState.LeftBlinker\n                        lights |= carla.VehicleLightState.Position\n                        actor.set_light_state(carla.VehicleLightState(lights))\n                        actor.set_autopilot(False, self._tm_port)\n                        continue\n\n                self._set_road_actor_speed(location, actor)\n\n    def _set_road_actor_speed(self, location, actor, multiplier=1):\n        \"\"\"\n        Changes the speed of the vehicle depending on its distance to the ego.\n        - Front vehicles: Gradually reduces the speed the further they are.\n        - Back vehicles: Gradually reduces the speed the further they are to help them catch up to the ego.\n        - Junction scenario behavior: Don't let vehicles behind the ego surpass it.\n        \"\"\"\n        distance = location.distance(self._ego_wp.transform.location)\n        if not self._is_location_behind_ego(location):\n            percentage = (self._max_radius - distance) / (self._max_radius - self._min_radius) * 100\n            percentage *= multiplier\n            percentage = max(min(percentage, 100), 0)\n        elif not self._scenario_junction_entry:\n            percentage = distance / (self._max_radius - self._min_radius) * 100 + 100\n            percentage = max(min(percentage, 200), 0)\n        else:\n            ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n            base_percentage = ego_speed / self._ego_target_speed * 100\n            true_distance = distance - self._scenario_junction_entry_distance\n            percentage = true_distance / (self._max_radius - self._min_radius) * 100 + base_percentage\n            percentage = max(min(percentage, 100), 0)\n\n        self._actors_speed_perc[actor] = percentage\n\n    def _monitor_road_changes(self, prev_route_index):\n        \"\"\"\n        Checks if the ego changes road, remapping the route keys.\n        \"\"\"\n        def get_lane_waypoints(reference_wp, index=0):\n            if not reference_wp.is_junction:\n                wps = get_same_dir_lanes(reference_wp)\n            else: # Handle fake junction by using its entry / exit wps\n                wps = []\n                for junction_wps in reference_wp.get_junction().get_waypoints(carla.LaneType.Driving):\n                    if get_road_key(junction_wps[index]) == get_road_key(reference_wp):\n                        wps.append(junction_wps[index])\n            return wps\n\n        def get_wp_pairs(old_wps_, new_wps_, dist):\n            wp_pairs = []\n\n            unmapped_wps = new_wps_\n            for old_wp_ in old_wps_:\n                mapped = False\n                location = old_wp_.transform.location\n                for new_wp_ in unmapped_wps:\n                    if location.distance(new_wp_.transform.location) < dist:\n                        unmapped_wps.remove(new_wp_)\n                        wp_pairs.append([old_wp_, new_wp_])\n                        mapped = True\n                        break\n\n                if not mapped:\n                    wp_pairs.append([old_wp_, None])\n\n            for unmapped_wp in unmapped_wps:\n                wp_pairs.append([None, unmapped_wp])\n\n            return wp_pairs\n\n        def is_remapping_needed(current_wp, prev_wp):\n            \"\"\"The road dict mapping is needed if \"\"\"\n            # If the ego just exitted a junction, remap isn't needed\n            if self._is_junction(prev_wp):\n                return False\n\n            # If the road changes, remap\n            if get_road_key(prev_wp) != get_road_key(current_wp):\n                return True\n\n            # Some roads have starting / ending lanes in the middle. Remap if that is detected\n            prev_wps = get_same_dir_lanes(prev_wp)\n            current_wps = get_same_dir_lanes(current_wp)\n            if len(prev_wps) != len(current_wps):\n                return True\n\n            return False\n\n        def is_road_dict_unchanging(wp_pairs):\n            \"\"\"Sometimes 'monitor_topology_changes' has already done the necessary changes\"\"\"\n            road_dict_keys = list(self._road_dict)\n            if len(wp_pairs) != len(road_dict_keys):\n                return False\n\n            for _, new_wp in wp_pairs:\n                if get_lane_key(new_wp) not in road_dict_keys:\n                    return False\n            return True\n\n        if prev_route_index == self._route_index:\n            return\n        route_wp = self._route[self._route_index]\n        prev_route_wp = self._route[prev_route_index]\n\n        if not is_remapping_needed(route_wp, prev_route_wp):\n            return\n\n        new_road_dict = {}\n        old_wps = get_lane_waypoints(prev_route_wp, 1)\n        new_wps = get_lane_waypoints(route_wp, 0)\n        check_dist = 1.1 * route_wp.transform.location.distance(prev_route_wp.transform.location)\n        wp_pairs = get_wp_pairs(old_wps, new_wps, check_dist)\n        # TODO: These pairs are sometimes wrong as some fake intersections have overlapping lanes (highway entries)\n\n        if is_road_dict_unchanging(wp_pairs):\n            return\n\n        for old_wp, new_wp in wp_pairs:\n            old_key = get_lane_key(old_wp)\n            new_key = get_lane_key(new_wp)\n\n            # Lane has ended / started, no need to remap it\n            if not new_wp or not old_wp:\n                continue\n\n            if self.debug:\n                draw_arrow(self._world, old_wp.transform.location, new_wp.transform.location, DEBUG_MEDIUM, DEBUG_ROAD, True)\n\n            # Check that the lane is part of the road dictionary\n            if old_key in list(self._road_dict):\n                new_road_dict[new_key] = self._road_dict[old_key]\n                self._road_dict.pop(old_key)\n                continue\n\n        # Add the rest of the unmapped road sources, mainly those created forward at lanes that are starting\n        for lane_key in list(self._road_dict):\n            new_road_dict[lane_key] = self._road_dict.pop(lane_key)\n\n        self._road_dict = new_road_dict\n\n    def _update_junction_actors(self):\n        \"\"\"\n        Handles an actor depending on their previous state. Actors entering the junction have its exit\n        monitored through their waypoint. When they exit, they are either moved to a connecting junction,\n        or added to the exit dictionary. Actors that exited the junction will stop after a certain distance\n        \"\"\"\n        if len(self._active_junctions) == 0:\n            return\n\n        max_index = len(self._active_junctions) - 1\n        for i, junction in enumerate(self._active_junctions):\n            if self.debug:\n                route_keys = junction.route_entry_keys + junction.route_exit_keys\n                route_oppo_keys = junction.opposite_entry_keys + junction.opposite_exit_keys\n                for wp in junction.entry_wps + junction.exit_wps:\n                    if get_lane_key(wp) in route_keys:\n                        draw_point(self._world, wp.transform.location, DEBUG_MEDIUM, DEBUG_ROAD, False)\n                    elif get_lane_key(wp) in route_oppo_keys:\n                        draw_point(self._world, wp.transform.location, DEBUG_MEDIUM, DEBUG_OPPOSITE, False)\n                    else:\n                        draw_point(self._world, wp.transform.location, DEBUG_MEDIUM, DEBUG_JUNCTION, False)\n\n            actor_dict = junction.actor_dict\n            exit_dict = junction.exit_dict\n\n            scenario_entry_actor_ids = []\n            if self._scenario_junction_entry:\n                for source in junction.entry_sources:\n                    if get_lane_key(source.wp) in junction.route_entry_keys:\n                        scenario_entry_actor_ids.extend([x.id for x in source.actors])\n\n            for actor in list(actor_dict):\n                if actor not in actor_dict:\n                    continue  # Actor was removed during the loop\n                location = CarlaDataProvider.get_location(actor)\n                if not location:\n                    continue\n\n                state, exit_lane_key, _ = actor_dict[actor].values()\n                if self.debug:\n                    string = 'J' + str(i+1) + '_' + state[:2]\n                    draw_string(self._world, location, string, DEBUG_JUNCTION, False)\n\n                # Special scenario actors. Treat them as road actors\n                if actor.id in scenario_entry_actor_ids:\n                    self._set_road_actor_speed(location, actor)\n\n                # Monitor its entry\n                elif state == JUNCTION_ENTRY:\n                    actor_wp = self._map.get_waypoint(location)\n                    if self._is_junction(actor_wp) and junction.contains_wp(actor_wp):\n                        if junction.clear_middle:\n                            self._destroy_actor(actor)  # Don't clutter the junction if a junction scenario is active\n                            continue\n                        actor_dict[actor]['state'] = JUNCTION_MIDDLE\n\n                # Monitor its exit and destroy an actor if needed\n                elif state == JUNCTION_MIDDLE:\n                    actor_wp = self._map.get_waypoint(location)\n                    actor_lane_key = get_lane_key(actor_wp)\n                    if not self._is_junction(actor_wp) and actor_lane_key in exit_dict:\n                        if i < max_index and actor_lane_key in junction.route_exit_keys:\n                            # Exited through a connecting lane in the route direction.\n                            self._remove_actor_info(actor)\n                            other_junction = self._active_junctions[i+1]\n                            self._add_actor_dict_element(other_junction.actor_dict, actor)\n\n                        elif i > 0 and actor_lane_key in junction.opposite_exit_keys:\n                            # Exited through a connecting lane in the opposite direction.\n                            # THIS SHOULD NEVER HAPPEN, an entry source should have already added it.\n                            other_junction = self._active_junctions[i-1]\n                            if actor not in other_junction.actor_dict:\n                                self._remove_actor_info(actor)\n                                self._add_actor_dict_element(other_junction.actor_dict, actor, at_oppo_entry_lane=True)\n\n                        else:\n                            # Check the lane capacity\n                            exit_dict[actor_lane_key]['ref_wp'] = actor_wp\n                            actor_dict[actor]['state'] = JUNCTION_EXIT\n                            actor_dict[actor]['exit_lane_key'] = actor_lane_key\n\n                            actors = exit_dict[actor_lane_key]['actors']\n                            if len(actors) > 0 and len(actors) >= exit_dict[actor_lane_key]['max_actors']:\n                                self._destroy_actor(actors[0])  # This is always the front most vehicle\n                            actors.append(actor)\n\n                # Change them to \"road mode\" when far enough from the junction\n                elif state == JUNCTION_EXIT:\n                    distance = location.distance(exit_dict[exit_lane_key]['ref_wp'].transform.location)\n                    if distance > exit_dict[exit_lane_key]['max_distance']:\n                        if exit_lane_key in junction.route_exit_keys:\n                            actor_dict[actor]['state'] = JUNCTION_EXIT_ROAD\n                        else:\n                            self._actors_speed_perc[actor] = 0\n                            actor_dict[actor]['state'] = JUNCTION_EXIT_INACTIVE\n\n                # Set them ready to move so that the ego can smoothly cross the junction\n                elif state == JUNCTION_EXIT_ROAD:\n                    self._set_road_actor_speed(location, actor, multiplier=1.5)\n                    pass\n\n                # Wait\n                elif state == JUNCTION_EXIT_INACTIVE:\n                    pass\n\n    def _update_opposite_actors(self):\n        \"\"\"\n        Updates the opposite actors. This involves tracking their position,\n        removing them if too far behind the ego.\n        \"\"\"\n        opposite_dist = max(self._opposite_sources_dist, self._opposite_spawn_dist)\n        for actor in list(self._opposite_actors):\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            if self.debug:\n                draw_string(self._world, location, 'O', DEBUG_OPPOSITE, False)\n\n            distance = location.distance(self._ego_wp.transform.location)\n            if distance > opposite_dist and self._is_location_behind_ego(location):\n                self._destroy_actor(actor)\n                continue\n\n            # Ending / starting lanes create issues as the lane width gradually decreases until reaching 0,\n            # where the lane starts / ends. Set their speed to 0, and they'll eventually dissapear.\n            actor_wp = self._map.get_waypoint(location)\n            if actor_wp.lane_width < self._lane_width_threshold:\n                self._actors_speed_perc[actor] = 0\n\n    def _set_actors_speed(self):\n        \"\"\"\n        Sets the speed of all the BA actors, using the ego's target speed as reference.\n        This avoids issues with the speed limits, as newly created actors don't have that information\n        \"\"\"\n        for actor, percentage in self._actors_speed_perc.items():\n            speed = self._ego_target_speed * percentage / 100\n            if self._scenario_max_speed:\n                speed = min(speed, self._scenario_max_speed)\n\n            # TODO: Fix very high speed traffic\n            speed = min(speed, 90)\n            self._tm.set_desired_speed(actor, speed)\n\n    def _remove_actor_info(self, actor):\n        \"\"\"Removes all the references of the actor\"\"\"\n\n        for lane in self._road_dict:\n            if actor in self._road_dict[lane].actors:\n                self._road_dict[lane].actors.remove(actor)\n                break\n\n        if actor in self._opposite_actors:\n            self._opposite_actors.remove(actor)\n        if actor in self._scenario_stopped_actors:\n            self._scenario_stopped_actors.remove(actor)\n        if actor in self._scenario_stopped_back_actors:\n            self._scenario_stopped_back_actors.remove(actor)\n\n        for opposite_source in self._opposite_sources:\n            if actor in opposite_source.actors:\n                opposite_source.actors.remove(actor)\n                break\n\n        for junction in self._active_junctions:\n            junction.actor_dict.pop(actor, None)\n\n            for entry_source in junction.entry_sources:\n                if actor in entry_source.actors:\n                    entry_source.actors.remove(actor)\n                    break\n\n            for exit_keys in junction.exit_dict:\n                exit_actors = junction.exit_dict[exit_keys]['actors']\n                if actor in exit_actors:\n                    exit_actors.remove(actor)\n                    break\n\n        self._actors_speed_perc.pop(actor, None)\n        if actor in self._all_actors:\n            self._all_actors.remove(actor)\n\n    def _destroy_actor(self, actor):\n        \"\"\"Destroy the actor and all its references\"\"\"\n        self._remove_actor_info(actor)\n        try:\n            actor.set_autopilot(False, self._tm_port)\n            actor.destroy()\n        except RuntimeError:\n            pass\n\n    def _update_ego_data(self):\n        \"\"\"\n        Checks the ego location to see if it has moved closer to the next route waypoint,\n        updating its information. This never checks for backwards movements to avoid unnedded confusion.\n        It also saves its max speed, used as a baseline for all BA vehicles.\n        \"\"\"\n        location = CarlaDataProvider.get_location(self._ego_actor)\n\n        prev_index = self._route_index\n        for index in range(self._route_index, min(self._route_index + self._route_buffer, self._route_length)):\n            route_wp = self._route[index]\n\n            route_wp_dir = route_wp.transform.get_forward_vector()    # Waypoint's forward vector\n            veh_wp_dir = location - route_wp.transform.location       # vector waypoint - vehicle\n            dot_ve_wp = veh_wp_dir.x * route_wp_dir.x + veh_wp_dir.y * route_wp_dir.y + veh_wp_dir.z * route_wp_dir.z\n\n            if dot_ve_wp > 0:\n                self._route_index = index\n\n        # Monitor route changes for those scenario that remove and readd a specific lane\n        if self._scenario_removed_lane:\n            for i in range(prev_index, self._route_index):\n                option_1 = self._route_options[i]\n                option_2 = self._route_options[i+1]\n                if option_1 == RoadOption.CHANGELANELEFT or option_2 == RoadOption.CHANGELANELEFT:\n                    loc_1 = self._route[i].transform.location\n                    loc_2 = self._route[i+1].transform.location\n                    if abs(loc_1.distance(loc_2)) > 2.5:  # Lane offset plus a bit forward\n                        self._scenario_remove_lane_offset += 1\n                elif option_1 == RoadOption.CHANGELANERIGHT or option_2 == RoadOption.CHANGELANERIGHT:\n                    loc_1 = self._route[i].transform.location\n                    loc_2 = self._route[i+1].transform.location\n                    if abs(loc_1.distance(loc_2)) > 2.5:  # Lane offset plus a bit forward\n                        self._scenario_remove_lane_offset -= 1\n\n        self._ego_wp = self._route[self._route_index]\n        self._ego_key = get_lane_key(self._ego_wp)\n        self._ego_target_speed = self._ego_actor.get_speed_limit()\n\n        if self.debug:\n            string = 'EGO_' + self._ego_state[0].upper()\n            debug_name = DEBUG_ROAD if self._ego_state == EGO_ROAD else DEBUG_JUNCTION\n            draw_string(self._world, location, string, debug_name, False)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/background_activity_parametrizer.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule used to parse all the route and scenario configuration parameters.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import (ChangeRoadBehavior,\n                                              ChangeOppositeBehavior,\n                                              ChangeJunctionBehavior)\n\ndef get_parameter(config, name):\n    if name in config.other_parameters:\n        return float(config.other_parameters[name]['value'])\n    else:\n        return None\n\nclass BackgroundActivityParametrizer(BasicScenario):\n    \"\"\"\n    This class holds everything required to change the parameters of the background activity.\n    Mainly used to change its behavior when, for example, moving from a highway into the city,\n    where we might want a different BA behavior.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        # Road\n        self._num_front_vehicles = get_parameter(config, \"num_front_vehicles\")\n        self._num_back_vehicles = get_parameter(config, \"num_back_vehicles\")\n        self._road_spawn_dist = get_parameter(config, \"road_spawn_dist\")\n\n        # Opposite\n        self._opposite_source_dist = get_parameter(config, \"opposite_source_dist\")\n        self._opposite_max_actors = get_parameter(config, \"opposite_max_actors\")\n        self._opposite_spawn_dist = get_parameter(config, \"opposite_spawn_dist\")\n        self._opposite_active = get_parameter(config, \"opposite_active\")\n\n        # Junction\n        self._junction_source_dist = get_parameter(config, \"junction_source_dist\")\n        self._junction_max_actors = get_parameter(config, \"junction_max_actors\")\n        self._junction_spawn_dist = get_parameter(config, \"junction_spawn_dist\")\n        self._junction_source_perc = get_parameter(config, \"junction_source_perc\")\n\n        super().__init__(\"BackgroundActivityParametrizer\",\n                          ego_vehicles,\n                          config,\n                          world,\n                          debug_mode,\n                          criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n\n        sequence = py_trees.composites.Sequence()\n        sequence.add_child(ChangeRoadBehavior(self._num_front_vehicles, self._num_back_vehicles, self._road_spawn_dist))\n        sequence.add_child(ChangeJunctionBehavior(\n            self._junction_source_dist, self._junction_max_actors, self._junction_spawn_dist, self._junction_source_perc))\n        sequence.add_child(ChangeOppositeBehavior(\n            self._opposite_source_dist, self._opposite_spawn_dist, self._opposite_active))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/basic_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provide BasicScenario, the basic class of all the scenarios.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport operator\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (WaitForBlackboardVariable,\n                                                                               InTimeToArrivalToLocation)\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import WaitForever\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import TimeOut\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import UpdateAllActorControls\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import Criterion\n\n\nclass BasicScenario(object):\n\n    \"\"\"\n    Base class for user-defined scenario\n    \"\"\"\n\n    def __init__(self, name, ego_vehicles, config, world,\n                 debug_mode=False, terminate_on_failure=False, criteria_enable=False):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self.name = name\n        self.ego_vehicles = ego_vehicles\n        self.other_actors = []\n        self.parking_slots = []\n        self.config = config\n        self.world = world\n        self.debug_mode = debug_mode\n        self.terminate_on_failure = terminate_on_failure\n        self.criteria_enable = criteria_enable\n\n        self.route_mode = bool(config.route)\n        self.behavior_tree = None\n        self.criteria_tree = None\n\n        # If no timeout was provided, set it to 60 seconds\n        if not hasattr(self, 'timeout'):\n            self.timeout = 60 \n        if debug_mode:\n            py_trees.logging.level = py_trees.logging.Level.DEBUG\n\n        if not self.route_mode:\n            # Only init env for route mode, avoid duplicate initialization during runtime\n            self._initialize_environment(world)\n            \n        self._initialize_actors(config)\n\n        if CarlaDataProvider.is_runtime_init_mode():\n            world.wait_for_tick()\n        elif CarlaDataProvider.is_sync_mode():\n            world.tick()\n        else:\n            world.wait_for_tick()\n\n        # Main scenario tree\n        self.scenario_tree = py_trees.composites.Parallel(name, policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # Add a trigger and end condition to the behavior to ensure it is only activated when it is relevant\n        self.behavior_tree = py_trees.composites.Sequence()\n\n        trigger_behavior = self._setup_scenario_trigger(config)\n        if trigger_behavior:\n            self.behavior_tree.add_child(trigger_behavior)\n\n        scenario_behavior = self._create_behavior()\n        self.behavior_tree.add_child(scenario_behavior)\n        self.behavior_tree.name = scenario_behavior.name\n\n        end_behavior = self._setup_scenario_end(config)\n        if end_behavior:\n            self.behavior_tree.add_child(end_behavior)\n\n        # Create the lights behavior\n        lights = self._create_lights_behavior()\n        if lights:\n            self.scenario_tree.add_child(lights)\n\n        # Create the weather behavior\n        weather = self._create_weather_behavior()\n        if weather:\n            self.scenario_tree.add_child(weather)\n\n        # And then add it to the main tree\n        self.scenario_tree.add_child(self.behavior_tree)\n\n        # Create the criteria tree (if needed)\n        if self.criteria_enable:\n            criteria = self._create_test_criteria()\n\n            # All the work is done, thanks!\n            if isinstance(criteria, py_trees.composites.Composite):\n                self.criteria_tree = criteria\n\n            # Lazy mode, but its okay, we'll create the parallel behavior tree for you.\n            elif isinstance(criteria, list):\n                for criterion in criteria:\n                    criterion.terminate_on_failure = terminate_on_failure\n\n                self.criteria_tree = py_trees.composites.Parallel(name=\"Test Criteria\",\n                                                                  policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n                self.criteria_tree.add_children(criteria)\n                self.criteria_tree.setup(timeout=1)\n\n            else:\n                raise ValueError(\"WARNING: Scenario {} couldn't be setup, make sure the criteria is either \"\n                                 \"a list or a py_trees.composites.Composite\".format(self.name))\n\n            self.scenario_tree.add_child(self.criteria_tree)\n\n        # Create the timeout behavior\n        self.timeout_node = self._create_timeout_behavior()\n        if self.timeout_node:\n            self.scenario_tree.add_child(self.timeout_node)\n\n        # Add other nodes\n        self.scenario_tree.add_child(UpdateAllActorControls())\n\n        self.scenario_tree.setup(timeout=1)\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Default initialization of weather and road friction.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n\n        # Set the appropriate weather conditions\n        world.set_weather(self.config.weather)\n\n        # Set the appropriate road friction\n        if self.config.friction is not None:\n            friction_bp = world.get_blueprint_library().find('static.trigger.friction')\n            extent = carla.Location(1000000.0, 1000000.0, 1000000.0)\n            friction_bp.set_attribute('friction', str(self.config.friction))\n            friction_bp.set_attribute('extent_x', str(extent.x))\n            friction_bp.set_attribute('extent_y', str(extent.y))\n            friction_bp.set_attribute('extent_z', str(extent.z))\n\n            # Spawn Trigger Friction\n            transform = carla.Transform()\n            transform.location = carla.Location(-10000.0, -10000.0, 0.0)\n            world.spawn_actor(friction_bp, transform)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        if config.other_actors:\n            new_actors = CarlaDataProvider.request_new_actors(config.other_actors)\n            if not new_actors:\n                raise Exception(\"Error: Unable to add actors\")\n\n            for new_actor in new_actors:\n                self.other_actors.append(new_actor)\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"\n        This function creates a trigger maneuver, that has to be finished before the real scenario starts.\n        This implementation focuses on the first available ego vehicle.\n\n        The function can be overloaded by a user implementation inside the user-defined scenario class.\n        \"\"\"\n        if config.trigger_points and config.trigger_points[0]:\n            start_location = config.trigger_points[0].location\n        else:\n            return None\n\n        # Scenario is not part of a route, wait for the ego to move\n        if not self.route_mode or config.route_var_name is None:\n            return InTimeToArrivalToLocation(self.ego_vehicles[0], 2.0, start_location)\n\n        # Scenario is part of a route.\n        check_name = \"WaitForBlackboardVariable: {}\".format(config.route_var_name)\n        return WaitForBlackboardVariable(config.route_var_name, True, False, name=check_name)\n\n    def _setup_scenario_end(self, config):\n        \"\"\"\n        This function adds and additional behavior to the scenario, which is triggered\n        after it has ended. The Blackboard variable is set to False to indicate the scenario has ended.\n        The function can be overloaded by a user implementation inside the user-defined scenario class.\n        \"\"\"\n        if not self.route_mode or config.route_var_name is None:\n            return None\n\n        # Scenario is part of a route.\n        end_sequence = py_trees.composites.Sequence()\n        name = \"Reset Blackboard Variable: {} \".format(config.route_var_name)\n        end_sequence.add_child(py_trees.blackboard.SetBlackboardVariable(name, config.route_var_name, False))\n        end_sequence.add_child(WaitForever())  # scenario can't stop the route\n\n        return end_sequence\n\n    def _create_behavior(self):\n        \"\"\"\n        Pure virtual function to setup user-defined scenario behavior\n        \"\"\"\n        raise NotImplementedError(\n            \"This function is re-implemented by all scenarios\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Pure virtual function to setup user-defined evaluation criteria for the\n        scenario\n        \"\"\"\n        raise NotImplementedError(\n            \"This function is re-implemented by all scenarios\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Default empty initialization of the weather behavior,\n        responsible of controlling the weather during the simulation.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        pass\n\n    def _create_lights_behavior(self):\n        \"\"\"\n        Default empty initialization of the lights behavior,\n        responsible of controlling the street lights during the simulation.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        pass\n\n    def _create_timeout_behavior(self):\n        \"\"\"\n        Default initialization of the timeout behavior.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        return TimeOut(self.timeout, name=\"TimeOut\")  # Timeout node\n\n    def change_control(self, control):  # pylint: disable=no-self-use\n        \"\"\"\n        This is a function that changes the control based on the scenario determination\n        :param control: a carla vehicle control\n        :return: a control to be changed by the scenario.\n\n        Note: This method should be overriden by the user-defined scenario behavior\n        \"\"\"\n        return control\n\n    def get_criteria(self):\n        \"\"\"\n        Return the list of test criteria, including all the leaf nodes.\n        Some criteria might have trigger conditions, which have to be filtered out.\n        \"\"\"\n        criteria = []\n        if not self.criteria_tree:\n            return criteria\n\n        criteria_nodes = self._extract_nodes_from_tree(self.criteria_tree)\n        for criterion in criteria_nodes:\n            if isinstance(criterion, Criterion):\n                criteria.append(criterion)\n\n        return criteria\n\n    def _extract_nodes_from_tree(self, tree):  # pylint: disable=no-self-use\n        \"\"\"\n        Returns the list of all nodes from the given tree\n        \"\"\"\n        node_list = [tree]\n        more_nodes_exist = True\n        while more_nodes_exist:\n            more_nodes_exist = False\n            for node in node_list:\n                if node.children:\n                    node_list.remove(node)\n                    more_nodes_exist = True\n                    for child in node.children:\n                        node_list.append(child)\n\n        if len(node_list) == 1 and isinstance(node_list[0], py_trees.composites.Parallel):\n            return []\n\n        return node_list\n\n    def terminate(self):\n        \"\"\"\n        This function sets the status of all leaves in the scenario tree to INVALID\n        \"\"\"\n        # Get list of all nodes in the tree\n        node_list = self._extract_nodes_from_tree(self.scenario_tree)\n\n        # Set status to INVALID\n        for node in node_list:\n            node.terminate(py_trees.common.Status.INVALID)\n\n        # Cleanup all instantiated controllers\n        actor_dict = {}\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n        for actor_id in actor_dict:\n            actor_dict[actor_id].reset()\n        py_trees.blackboard.Blackboard().set(\"ActorsWithController\", {}, overwrite=True)\n\n    def remove_all_actors(self):\n        \"\"\"\n        Remove all actors\n        \"\"\"\n        if not hasattr(self, 'other_actors'):\n            return\n        for i, _ in enumerate(self.other_actors):\n            if self.other_actors[i] is not None:\n                if CarlaDataProvider.actor_id_exists(self.other_actors[i].id):\n                    CarlaDataProvider.remove_actor_by_id(self.other_actors[i].id)\n                self.other_actors[i] = None\n        self.other_actors = []\n\n    def get_parking_slots(self):\n        \"\"\"\n        Returns occupied parking slots.\n        \"\"\"\n        return self.parking_slots\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/blocked_intersection.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario with low visibility, the ego performs a turn only to find out that the end is blocked by another vehicle.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\nimport py_trees\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      Idle,\n                                                                      ScenarioTimeout,\n                                                                      ActorTransformSetter,\n                                                                      HandBrakeVehicle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\nfrom srunner.tools.scenario_helper import generate_target_waypoint_in_route\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\nclass BlockedIntersection(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which,\n    the ego performs a turn only to find out that the end is blocked by another vehicle.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(self._trigger_location)\n\n        self._blocker_distance = 5\n        self._trigger_distance = 13\n        self._stop_time = 10\n\n        self._scenario_timeout = 240\n\n        self._blocker_transform = None\n\n        super().__init__(\"BlockedIntersection\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        waypoint = generate_target_waypoint_in_route(self._reference_waypoint, config.route)\n        waypoint = waypoint.next(self._blocker_distance)[0]\n\n        self._blocker_transform = waypoint.transform\n\n        # Spawn the blocker vehicle\n        blocker = CarlaDataProvider.request_new_actor(\n            \"vehicle.*.*\", self._blocker_transform,\n            attribute_filter={'base_type': 'car', 'has_lights': True, 'special_type': ''}\n        )\n        if blocker is None:\n            raise Exception(\"Couldn't spawn the blocker vehicle\")\n        self.other_actors.append(blocker)\n\n        blocker.set_simulate_physics(False)\n        blocker.set_location(self._blocker_transform.location + carla.Location(z=-200))\n\n        lights = blocker.get_light_state()\n        lights |= carla.VehicleLightState.Brake\n        blocker.set_light_state(carla.VehicleLightState(lights))\n\n    def _create_behavior(self):\n        \"\"\"\n        Just wait for a while after the ego closes in on the blocker, then remove it.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"BlockedIntersection\")\n\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[],\n                remove_exits=[],\n                stop_entries=True,\n                extend_road_exit=0\n            ))\n        # Ego go behind the blocker\n        main_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        behavior = py_trees.composites.Sequence(name=\"Approach and Wait\")\n        behavior.add_child(ActorTransformSetter(self.other_actors[0], self._blocker_transform, True))\n        behavior.add_child(HandBrakeVehicle(self.other_actors[0], 1))\n        behavior.add_child(InTriggerDistanceToVehicle(\n            self.other_actors[-1], self.ego_vehicles[0], self._trigger_distance))\n        behavior.add_child(Idle(self._stop_time))\n        main_behavior.add_child(behavior)\n\n        sequence.add_child(main_behavior)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/change_lane.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nChange lane scenario:\n\nThe scenario realizes a driving behavior, in which the user-controlled ego vehicle\nfollows a fast driving car on the highway. There's a slow car driving in great distance to the fast vehicle.\nAt one point the fast vehicle is changing the lane to overtake a slow car, which is driving on the same lane.\n\nThe ego vehicle doesn't \"see\" the slow car before the lane change of the fast car, therefore it hast to react\nfast to avoid an collision. There are two options to avoid an accident:\nThe ego vehicle adjusts its velocity or changes the lane as well.\n\"\"\"\n\nimport random\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      StopVehicle,\n                                                                      LaneChange,\n                                                                      WaypointFollower,\n                                                                      Idle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle, StandStill\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass ChangeLane(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a \"change lane\" scenario involving three vehicles.\n    There are two vehicles driving in the same direction on the highway: A fast car and a slow car in front.\n    The fast car will change the lane, when it is close to the slow car.\n\n    The ego vehicle is driving right behind the fast car.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 1200\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=600):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n\n        If randomize is True, the scenario parameters are randomized\n        \"\"\"\n        self.timeout = timeout\n        self._map = CarlaDataProvider.get_map()\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        self._fast_vehicle_velocity = 70\n        self._slow_vehicle_velocity = 0\n        self._change_lane_velocity = 15\n\n        self._slow_vehicle_distance = 100\n        self._fast_vehicle_distance = 20\n        self._trigger_distance = 30\n        self._max_brake = 1\n\n        self.direction = 'left'  # direction of lane change\n        self.lane_check = 'true'  # check whether a lane change is possible\n\n        super(ChangeLane, self).__init__(\"ChangeLane\",\n                                         ego_vehicles,\n                                         config,\n                                         world,\n                                         debug_mode,\n                                         criteria_enable=criteria_enable)\n\n        if randomize:\n            self._fast_vehicle_distance = random.randint(10, 51)\n            self._fast_vehicle_velocity = random.randint(100, 201)\n            self._slow_vehicle_velocity = random.randint(1, 6)\n\n    def _initialize_actors(self, config):\n\n        # add actors from xml file\n        for actor in config.other_actors:\n            vehicle = CarlaDataProvider.request_new_actor(actor.model, actor.transform)\n            self.other_actors.append(vehicle)\n            vehicle.set_simulate_physics(enabled=False)\n\n        # fast vehicle, tesla\n        # transform visible\n        fast_car_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._fast_vehicle_distance)\n        self.fast_car_visible = carla.Transform(\n            carla.Location(fast_car_waypoint.transform.location.x,\n                           fast_car_waypoint.transform.location.y,\n                           fast_car_waypoint.transform.location.z + 1),\n            fast_car_waypoint.transform.rotation)\n\n        # slow vehicle, vw\n        # transform visible\n        slow_car_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._slow_vehicle_distance)\n        self.slow_car_visible = carla.Transform(\n            carla.Location(slow_car_waypoint.transform.location.x,\n                           slow_car_waypoint.transform.location.y,\n                           slow_car_waypoint.transform.location.z),\n            slow_car_waypoint.transform.rotation)\n\n    def _create_behavior(self):\n\n        # sequence vw\n        # make visible\n        sequence_vw = py_trees.composites.Sequence(\"VW T2\")\n        vw_visible = ActorTransformSetter(self.other_actors[1], self.slow_car_visible)\n        sequence_vw.add_child(vw_visible)\n\n        # brake, avoid rolling backwarts\n        brake = StopVehicle(self.other_actors[1], self._max_brake)\n        sequence_vw.add_child(brake)\n        sequence_vw.add_child(Idle())\n\n        # sequence tesla\n        # make visible\n        sequence_tesla = py_trees.composites.Sequence(\"Tesla\")\n        tesla_visible = ActorTransformSetter(self.other_actors[0], self.fast_car_visible)\n        sequence_tesla.add_child(tesla_visible)\n\n        # drive fast towards slow vehicle\n        just_drive = py_trees.composites.Parallel(\"DrivingTowardsSlowVehicle\",\n                                                  policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        tesla_driving_fast = WaypointFollower(self.other_actors[0], self._fast_vehicle_velocity)\n        just_drive.add_child(tesla_driving_fast)\n        distance_to_vehicle = InTriggerDistanceToVehicle(\n            self.other_actors[1], self.other_actors[0], self._trigger_distance)\n        just_drive.add_child(distance_to_vehicle)\n        sequence_tesla.add_child(just_drive)\n\n        # change lane\n        lane_change_atomic = LaneChange(self.other_actors[0], distance_other_lane=200)\n        sequence_tesla.add_child(lane_change_atomic)\n        sequence_tesla.add_child(Idle())\n\n        # ego vehicle\n        # end condition\n        endcondition = py_trees.composites.Parallel(\"Waiting for end position of ego vehicle\",\n                                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n        endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[1],\n                                                        self.ego_vehicles[0],\n                                                        distance=20,\n                                                        name=\"FinalDistance\")\n        endcondition_part2 = StandStill(self.ego_vehicles[0], name=\"FinalSpeed\", duration=1)\n        endcondition.add_child(endcondition_part1)\n        endcondition.add_child(endcondition_part2)\n\n        # build tree\n        root = py_trees.composites.Parallel(\"Parallel Behavior\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(sequence_vw)\n        root.add_child(sequence_tesla)\n        root.add_child(endcondition)\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/construction_crash_vehicle.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nObject crash without prior vehicle action scenario:\nThe scenario realizes the user controlled ego vehicle\nmoving along the road and encountering a construction setup.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      ActorTransformSetter,\n                                                                      SwitchWrongDirectionTest,\n                                                                      ScenarioTimeout,\n                                                                      Idle, WaitForever,\n                                                                      OppositeActorFlow)\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import (RemoveRoadLane,\n                                              ReAddRoadLane,\n                                              SetMaxSpeed,\n                                              ChangeOppositeBehavior)\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\nclass ConstructionObstacle(BasicScenario):\n    \"\"\"\n    This class holds everything required for a construction scenario\n    The ego vehicle is passing through a road and encounters\n    a stationary rectangular construction cones setup and traffic warning,\n    forcing it to lane change.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False,\n                 criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_distance = 30\n        self._opposite_wait_duration = 5\n        self._end_distance = 50\n\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._construction_wp = None\n\n        self._construction_transforms = []\n\n        self._distance = get_value_parameter(config, 'distance', float, 100)\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        super().__init__(\"ConstructionObstacle\", ego_vehicles, config, world, debug_mode, False, criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"Creates all props part of the construction\"\"\"\n        self._spawn_side_prop(self._reference_waypoint)\n\n        wps = self._reference_waypoint.next(self._distance)\n        if not wps:\n            raise ValueError(\"Couldn't find a viable position to set up the construction actors\")\n        self._construction_wp = wps[0]\n        self._create_construction_setup(self._construction_wp.transform, self._reference_waypoint.lane_width)\n\n        self._end_wp = self._move_waypoint_forward(self._construction_wp, self._end_distance)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_side_prop(self, wp):\n        \"\"\"Spawn the accident indication signal\"\"\"\n        prop_wp = wp\n        while True:\n            if self._direction == \"right\":\n                wp = prop_wp.get_right_lane()\n            else:\n                wp = prop_wp.get_left_lane()\n            if wp is None or wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n                break\n            prop_wp = wp\n\n        displacement = 0.3 * prop_wp.lane_width\n        r_vec = prop_wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.2)\n        spawn_transform.rotation.yaw += 90\n        signal_prop = CarlaDataProvider.request_new_actor('static.prop.warningconstruction', spawn_transform)\n        if not signal_prop:\n            raise ValueError(\"Couldn't spawn the indication prop asset\")\n        signal_prop.set_simulate_physics(False)\n        self.other_actors.append(signal_prop)\n\n    def _create_cones_side(self, start_transform, forward_vector, z_inc=0, cone_length=0, cone_offset=0):\n        \"\"\"Creates the cones at the side\"\"\"\n        _dist = 0\n        while _dist < (cone_length * cone_offset):\n            # Move forward\n            _dist += cone_offset\n            forward_dist = carla.Vector3D(0, 0, 0) + forward_vector * _dist\n\n            location = start_transform.location + forward_dist\n            location.z += z_inc\n            spawn_transform = carla.Transform(location, start_transform.rotation)\n            spawn_transform.location.z -= 200\n            cone_transform = carla.Transform(location, start_transform.rotation)\n\n            cone = CarlaDataProvider.request_new_actor('static.prop.constructioncone', spawn_transform)\n            cone.set_simulate_physics(False)\n            self.other_actors.append(cone)\n\n            self._construction_transforms.append([cone, cone_transform])\n\n    def _create_construction_setup(self, start_transform, lane_width):\n        \"\"\"Create construction setup\"\"\"\n\n        _initial_offset = {'cones': {'yaw': 270, 'k': 0.85 * lane_width / 2.0},\n                           'warning_sign': {'yaw': 180, 'k': 5, 'z': 0},\n                           'debris': {'yaw': 0, 'k': 2, 'z': 1}}\n        _prop_names = {'warning_sign': 'static.prop.trafficwarning',\n                       'debris': 'static.prop.dirtdebris02'}\n\n        _perp_angle = 90\n        _setup = {'lengths': [4, 3], 'offsets': [2, 1]}\n        _z_increment = 0.1\n\n        # Traffic warning and debris\n        for key, value in _initial_offset.items():\n            if key == 'cones':\n                continue\n            transform = carla.Transform(\n                start_transform.location,\n                start_transform.rotation)\n            transform.rotation.yaw += value['yaw']\n            transform.location += value['k'] * \\\n                transform.rotation.get_forward_vector()\n            transform.location.z += value['z']\n            transform.rotation.yaw += _perp_angle\n\n            spawn_transform = carla.Transform(transform.location, transform.rotation)\n            spawn_transform.location.z -= 200\n            static = CarlaDataProvider.request_new_actor(\n                _prop_names[key], spawn_transform)\n            static.set_simulate_physics(False)\n            self.other_actors.append(static)\n\n            self._construction_transforms.append([static, transform])\n\n        # Cones\n        side_transform = carla.Transform(\n            start_transform.location,\n            start_transform.rotation)\n        side_transform.rotation.yaw += _perp_angle\n        offset_vec = _initial_offset['cones']['k'] * side_transform.rotation.get_forward_vector()\n        if self._direction == 'right':\n            side_transform.location -= offset_vec\n        else:\n            side_transform.location += offset_vec\n\n        side_transform.rotation.yaw += _initial_offset['cones']['yaw']\n\n        for i in range(len(_setup['lengths'])):\n            self._create_cones_side(\n                side_transform,\n                forward_vector=side_transform.rotation.get_forward_vector(),\n                z_inc=_z_increment,\n                cone_length=_setup['lengths'][i],\n                cone_offset=_setup['offsets'][i])\n            side_transform.location += side_transform.get_forward_vector() * \\\n                _setup['lengths'][i] * _setup['offsets'][i]\n            if i == 0 and self._direction == 'left':\n                side_transform.rotation.yaw -= _perp_angle\n            else:\n                side_transform.rotation.yaw += _perp_angle\n\n    def _create_behavior(self):\n        \"\"\"\n        Remove the lane that would collide with the construction and add the construction props.\n        Wait until the ego is close to the construction (and a bit more) before changing the side traffic\n        Readd the traffic at the end\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"ConstructionObstacle\")\n        if self.route_mode:\n            root.add_child(RemoveRoadLane(self._reference_waypoint))\n\n        for actor, transform in self._construction_transforms:\n            root.add_child(ActorTransformSetter(actor, transform, True))\n    \n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._construction_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._opposite_wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n            root.add_child(ReAddRoadLane(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass ConstructionObstacleTwoWays(ConstructionObstacle):\n    \"\"\"\n    Variation of ConstructionObstacle where the ego has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Remove the lane that would collide with the construction and add the construction props.\n        Wait until the ego is close to the construction (and a bit more) before changing the opposite traffic\n        Readd the traffic at the end, and allow the ego to invade the opposite lane by deactivating the criteria\n        \"\"\"\n        reference_wp = self._construction_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"ConstructionObstacleTwoWays\")\n        if self.route_mode:\n            root.add_child(RemoveRoadLane(self._reference_waypoint))\n\n        for actor, transform in self._construction_transforms:\n            root.add_child(ActorTransformSetter(actor, transform, True))\n    \n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._construction_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._opposite_wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n            behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n            root.add_child(ReAddRoadLane(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/control_loss.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nControl Loss Vehicle scenario:\n\nThe scenario realizes that the vehicle looses control due to\nbad road conditions, etc. and checks to see if the vehicle\nregains control and corrects it's course.\n\"\"\"\n\nfrom numpy import random\nimport py_trees\nimport operator\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import AddNoiseToRouteEgo\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance, InTriggerDistanceToLocation\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass ControlLoss(BasicScenario):\n\n    \"\"\"\n    Implementation of \"Control Loss Vehicle\" (Traffic Scenario 01)\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self.timeout = timeout\n        self._randomize = randomize\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._map = CarlaDataProvider.get_map()\n        self._end_distance = 110\n\n        # Friction loss tends to have a much stronger steering compoenent then a throttle one\n        self._throttle_mean = 0.03\n        self._throttle_std = 0.01\n        self._steer_mean = 0.055\n        self._steer_std = 0.015\n\n        self._trigger_dist = 2\n\n        super().__init__(\"ControlLoss\", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        if self._randomize:\n            self._distance = list(self._rng.randint(low=10, high=80, size=3))\n            self._distance = sorted(self._distance)\n            self._offset = list(2 * random.rand(3) - 1)\n        else:\n            self._distance = [14, 48, 74]\n            self._offset = [-0.6, 0.8, 0.2]\n\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Get the debris locations\n        first_wp, _ = get_waypoint_in_distance(self._reference_waypoint, self._distance[0])\n        first_ground_loc = self.world.ground_projection(first_wp.transform.location + carla.Location(z=1), 2)\n        first_loc = first_ground_loc.location if first_ground_loc else first_wp.transform.location\n        self.first_transform = carla.Transform(first_loc, first_wp.transform.rotation)\n\n        second_wp, _ = get_waypoint_in_distance(self._reference_waypoint, self._distance[1])\n        second_ground_loc = self.world.ground_projection(second_wp.transform.location + carla.Location(z=1), 2)\n        second_loc = second_ground_loc.location if second_ground_loc else second_wp.transform.location\n        self.second_transform = carla.Transform(second_loc, second_wp.transform.rotation)\n\n        third_wp, _ = get_waypoint_in_distance(self._reference_waypoint, self._distance[2])\n        third_ground_loc = self.world.ground_projection(third_wp.transform.location + carla.Location(z=1), 2)\n        third_loc = third_ground_loc.location if third_ground_loc else third_wp.transform.location\n        self.third_transform = carla.Transform(third_loc, third_wp.transform.rotation)\n\n        # Spawn the debris\n        first_debris = CarlaDataProvider.request_new_actor(\n            'static.prop.dirtdebris01', self.first_transform, rolename='prop')\n        second_debris = CarlaDataProvider.request_new_actor(\n            'static.prop.dirtdebris01', self.second_transform, rolename='prop')\n        third_debris = CarlaDataProvider.request_new_actor(\n            'static.prop.dirtdebris01', self.third_transform, rolename='prop')\n\n        # Remove their physics\n        first_debris.set_simulate_physics(False)\n        second_debris.set_simulate_physics(False)\n        third_debris.set_simulate_physics(False)\n\n        self.other_actors.append(first_debris)\n        self.other_actors.append(second_debris)\n        self.other_actors.append(third_debris)\n\n    def _get_noise_parameters(self):\n        \"\"\"Randomizes the mean to be either positive or negative\"\"\"\n        return [\n            self._rng.choice([self._throttle_mean, -self._throttle_mean]),\n            self._throttle_std,\n            self._rng.choice([self._steer_mean, -self._steer_mean]),\n            self._steer_std\n        ]\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"control loss vehicle\" scenario.\n        \"\"\"\n        root = py_trees.composites.Parallel(\"ControlLoss\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        sequence = py_trees.composites.Sequence()\n\n        # First debris behavior\n        sequence.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.first_transform.location, self._trigger_dist))\n\n        noise_1 = self._get_noise_parameters()\n        noise_behavior_1 = py_trees.composites.Parallel(\"Add Noise 1\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        noise_behavior_1.add_child(AddNoiseToRouteEgo(self.ego_vehicles[0], *noise_1))\n        noise_behavior_1.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.first_transform.location, self._trigger_dist, operator.gt))\n        sequence.add_child(noise_behavior_1)\n\n        # Second debris behavior\n        sequence.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.second_transform.location, self._trigger_dist))\n\n        noise_2 = self._get_noise_parameters()\n        noise_behavior_2 = py_trees.composites.Parallel(\"Add Noise 2\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        noise_behavior_2.add_child(AddNoiseToRouteEgo(self.ego_vehicles[0], *noise_2))\n        noise_behavior_2.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.second_transform.location, self._trigger_dist, operator.gt))\n        sequence.add_child(noise_behavior_2)\n\n        # Third debris behavior\n        sequence.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.third_transform.location, self._trigger_dist))\n\n        noise_3 = self._get_noise_parameters()\n        noise_behavior_3 = py_trees.composites.Parallel(\"Add Noise 3\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        noise_behavior_3.add_child(AddNoiseToRouteEgo(self.ego_vehicles[0], *noise_3))\n        noise_behavior_3.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.third_transform.location, self._trigger_dist, operator.gt))\n        sequence.add_child(noise_behavior_3)\n\n        end_distance = self._end_distance - self._distance[-1]\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], end_distance))\n\n        root.add_child(sequence)\n        root.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/cross_bicycle_flow.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2022 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which the ego has to cross a flow of bycicles\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import BicycleFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\nfrom agents.navigation.local_planner import RoadOption\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\nclass CrossingBicycleFlow(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle runs a red light\n    in front of the ego, forcing it to react. This vehicles are 'special' ones such as police cars,\n    ambulances or firetrucks.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._start_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_dist_flow = 40  # m\n        self._sink_distance = 2\n\n        self._end_distance = 40\n\n        self._signalized_junction = False\n\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        self._green_light_delay = 5\n        self._scenario_timeout = 240\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n\n        super().__init__(\"CrossingBicycleFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        junction = starting_wp.get_junction()\n\n        # Get the plan\n        self._source_wp = self._map.get_waypoint(self._start_flow, lane_type=carla.LaneType.Biking)\n        if not self._source_wp or self._source_wp.transform.location.distance(self._start_flow) > 10:\n            raise ValueError(\"Couldn't find a biking lane at the specified location\")\n\n        self._plan = []\n        plan_step = 0\n        wp = self._source_wp\n        while True:\n            next_wps = wp.next(2)\n            if not next_wps:\n                raise ValueError(\"Couldn't find a proper plan for the bicycle flow\")\n            next_wp = next_wps\n            wp = next_wp[0]\n            self._plan.append([next_wp[0], RoadOption.LANEFOLLOW])\n\n            if plan_step == 0 and wp.is_junction:\n                plan_step += 1\n            elif plan_step == 1 and not wp.is_junction:\n                plan_step += 1\n                exit_loc = wp.transform.location\n            elif plan_step == 2 and exit_loc.distance(wp.transform.location) > self._end_dist_flow:\n                break\n\n        tls = self._world.get_traffic_lights_in_junction(junction.id)\n        if not tls:\n            self._signalized_junction = False\n        else:\n            self._signalized_junction = True\n            self._get_traffic_lights(tls, ego_junction_dist)\n\n    def _get_traffic_lights(self, tls, ego_dist):\n        \"\"\"Get the traffic light of the junction, mapping their states\"\"\"\n\n        ego_landmark = self._ego_wp.get_landmarks_of_type(ego_dist + 2, \"1000001\")[0]\n        ego_tl = self._world.get_traffic_light(ego_landmark)\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(BicycleFlow(self._plan, self._source_dist_interval, self._sink_distance, self._flow_speed, True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        # Freeze the traffic lights to allow the flow to populate the junction\n        if self._signalized_junction:\n            tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n            tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n            tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n            root.add_child(tl_freezer_sequence)\n\n        # Add the BackgroundActivity behaviors\n        if not self.route_mode:\n            return root\n\n        sequence = py_trees.composites.Sequence()\n        sequence.add_child(HandleJunctionScenario(\n            clear_junction=True,\n            clear_ego_entry=True,\n            remove_entries=[],\n            remove_exits=[],\n            stop_entries=True,\n            extend_road_exit=0\n        ))\n        sequence.add_child(root)\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/cut_in.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCut in scenario:\n\nThe scenario realizes a driving behavior on the highway.\nThe user-controlled ego vehicle is driving straight and keeping its velocity at a constant level.\nAnother car is cutting just in front, coming from left or right lane.\n\nThe ego vehicle may need to brake to avoid a collision.\n\"\"\"\n\nimport random\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      LaneChange,\n                                                                      WaypointFollower,\n                                                                      AccelerateToCatchUp)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle, DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass CutIn(BasicScenario):\n\n    \"\"\"\n    The ego vehicle is driving on a highway and another car is cutting in just in front.\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 1200\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=600):\n\n        self.timeout = timeout\n        self._map = CarlaDataProvider.get_map()\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        self._velocity = 40\n        self._delta_velocity = 10\n        self._trigger_distance = 30\n\n        # get direction from config name\n        self._config = config\n        self._direction = None\n        self._transform_visible = None\n\n        super(CutIn, self).__init__(\"CutIn\",\n                                    ego_vehicles,\n                                    config,\n                                    world,\n                                    debug_mode,\n                                    criteria_enable=criteria_enable)\n\n        if randomize:\n            self._velocity = random.randint(20, 60)\n            self._trigger_distance = random.randint(10, 40)\n\n    def _initialize_actors(self, config):\n\n        # direction of lane, on which other_actor is driving before lane change\n        if 'LEFT' in self._config.name.upper():\n            self._direction = 'left'\n\n        if 'RIGHT' in self._config.name.upper():\n            self._direction = 'right'\n\n        # add actors from xml file\n        for actor in config.other_actors:\n            vehicle = CarlaDataProvider.request_new_actor(actor.model, actor.transform)\n            self.other_actors.append(vehicle)\n            vehicle.set_simulate_physics(enabled=False)\n\n        # transform visible\n        other_actor_transform = self.other_actors[0].get_transform()\n        self._transform_visible = carla.Transform(\n            carla.Location(other_actor_transform.location.x,\n                           other_actor_transform.location.y,\n                           other_actor_transform.location.z + 105),\n            other_actor_transform.rotation)\n\n    def _create_behavior(self):\n        \"\"\"\n        Order of sequence:\n        - car_visible: spawn car at a visible transform\n        - just_drive: drive until in trigger distance to ego_vehicle\n        - accelerate: accelerate to catch up distance to ego_vehicle\n        - lane_change: change the lane\n        - endcondition: drive for a defined distance\n        \"\"\"\n\n        # car_visible\n        behaviour = py_trees.composites.Sequence(\"CarOn_{}_Lane\" .format(self._direction))\n        car_visible = ActorTransformSetter(self.other_actors[0], self._transform_visible)\n        behaviour.add_child(car_visible)\n\n        # just_drive\n        just_drive = py_trees.composites.Parallel(\n            \"DrivingStraight\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        car_driving = WaypointFollower(self.other_actors[0], self._velocity)\n        just_drive.add_child(car_driving)\n\n        trigger_distance = InTriggerDistanceToVehicle(\n            self.other_actors[0], self.ego_vehicles[0], self._trigger_distance)\n        just_drive.add_child(trigger_distance)\n        behaviour.add_child(just_drive)\n\n        # accelerate\n        accelerate = AccelerateToCatchUp(self.other_actors[0], self.ego_vehicles[0], throttle_value=1,\n                                         delta_velocity=self._delta_velocity, trigger_distance=5, max_distance=500)\n        behaviour.add_child(accelerate)\n\n        # lane_change\n        if self._direction == 'left':\n            lane_change = LaneChange(\n                self.other_actors[0], speed=None, direction='right', distance_same_lane=5, distance_other_lane=300)\n            behaviour.add_child(lane_change)\n        else:\n            lane_change = LaneChange(\n                self.other_actors[0], speed=None, direction='left', distance_same_lane=5, distance_other_lane=300)\n            behaviour.add_child(lane_change)\n\n        # endcondition\n        endcondition = DriveDistance(self.other_actors[0], 200)\n\n        # build tree\n        root = py_trees.composites.Sequence(\"Behavior\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(behaviour)\n        root.add_child(endcondition)\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria is created, which is later used in the parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors after deletion.\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/cut_in_with_static_vehicle.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n# Copyright (c) 2019-2022 Intel Corporation\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      BatchActorTransformSetter,\n                                                                      CutIn,\n                                                                      BasicAgentBehavior,\n                                                                      Idle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import RemoveRoadLane, LeaveSpaceInFront, ReAddRoadLane, ChangeRoadBehavior\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass StaticCutIn(BasicScenario):\n\n    \"\"\"\n    Cut in(with static vehicle) scenario synchronizes a vehicle that is parked at a side lane\n    to cut in in front of the ego vehicle, forcing it to break\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n\n        self._reaction_time = 2.7  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 15.0  # Min distance to the collision location that triggers the adversary [m]\n\n        self._back_vehicles = 2\n        self._front_vehicles = 3\n        self._vehicle_gap = 11\n\n        self._speed = 60 # Km/h\n\n        self._adversary_end_distance = 70\n\n        self._extra_space = 30  # Leave extra space as a vehicle is invading the ego's lane (BA parameter)\n\n        self._side_transforms = []\n        self._side_wp = None\n\n        self._attributes = {'base_type': 'car', 'has_lights': True}\n\n        self._blocker_distance = get_value_parameter(config, 'distance', float, 100)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        super().__init__(\"StaticCutIn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn the blocker vehicle\n        next_wps = self._reference_waypoint.next(self._blocker_distance)\n        if not next_wps:\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        blocker_wp = next_wps[0]\n\n        # Spawn the vehicles behind the cut in one\n        for i in range(self._back_vehicles):\n            # Move to the side\n            side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane()\n            if not side_wp:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n\n            if i == 1:\n                self._side_wp = side_wp\n\n            # Spawn the actor\n            blocker_actor = CarlaDataProvider.request_new_actor(\n                'vehicle.*', side_wp.transform, 'scenario', attribute_filter=self._attributes)\n            if not blocker_actor:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't spawn an actor\")\n            blocker_actor.apply_control(carla.VehicleControl(hand_brake=True))\n\n            blocker_actor.set_simulate_physics(False)\n            blocker_actor.set_location(side_wp.transform.location + carla.Location(z=-500))\n            self._side_transforms.append([blocker_actor, side_wp.transform])\n            self.other_actors.append(blocker_actor)\n\n            # Move to the front\n            next_wps = blocker_wp.next(self._vehicle_gap)\n            if not next_wps:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n            blocker_wp = next_wps[0]\n\n        self._collision_wp = blocker_wp\n\n        # Get the cut in behavior\n        self._plan, dist, step = ([], 0, 5)\n        next_wp = self._collision_wp\n        while dist < self._adversary_end_distance:\n            next_wps = next_wp.next(step)\n            if not next_wps:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n            next_wp = next_wps[0]\n            self._plan.append([next_wp, RoadOption.STRAIGHT])\n\n            dist += step\n\n        # Spawn the cut in vehicle\n        side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane()\n        if not side_wp:\n            for actor in self.other_actors:\n                actor.destroy()\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n\n        self._adversary_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', side_wp.transform, 'scenario', attribute_filter=self._attributes)\n        if not self._adversary_actor:\n            for actor in self.other_actors:\n                actor.destroy()\n            raise ValueError(\"Couldn't spawn an actor\")\n\n        self._adversary_actor.set_simulate_physics(False)\n        self._adversary_actor.set_location(side_wp.transform.location + carla.Location(z=-500))\n        self._side_transforms.append([self._adversary_actor, side_wp.transform])\n        self.other_actors.append(self._adversary_actor)\n\n        # This starts the engine, to allow the adversary to instantly move \n        self._adversary_actor.apply_control(carla.VehicleControl(throttle=1.0, brake=1.0)) \n\n        # Move to the front\n        next_wps = blocker_wp.next(self._vehicle_gap)\n        if not next_wps:\n            for actor in self.other_actors:\n                actor.destroy()\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        blocker_wp = next_wps[0]\n\n        # Spawn the vehicles in front of the cut in one\n        for i in range(self._front_vehicles):\n            # Move to the side\n            side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane()\n            if not side_wp:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n\n            # Spawn the actor\n            blocker_actor = CarlaDataProvider.request_new_actor(\n                'vehicle.*', side_wp.transform, 'scenario', attribute_filter=self._attributes)\n            if not blocker_actor:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't spawn an actor\")\n            blocker_actor.apply_control(carla.VehicleControl(hand_brake=True))\n\n            blocker_actor.set_simulate_physics(False)\n            blocker_actor.set_location(side_wp.transform.location + carla.Location(z=-500))\n            self._side_transforms.append([blocker_actor, side_wp.transform])\n            self.other_actors.append(blocker_actor)\n\n            # Move to the front\n            next_wps = blocker_wp.next(self._vehicle_gap)\n            if not next_wps:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n            blocker_wp = next_wps[0]\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, a parked vehicle will wait for the ego to\n        be close-by, merging into its lane, forcing it to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"StaticCutIn\")\n        if self.route_mode:\n            total_dist = self._blocker_distance\n            total_dist += self._vehicle_gap * (self._back_vehicles + self._front_vehicles + 1)\n            sequence.add_child(LeaveSpaceInFront(total_dist))\n\n        sequence.add_child(BatchActorTransformSetter(self._side_transforms))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(self._side_wp))\n\n        cut_in_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"CutIn\")\n        cut_in_direction = 'right' if self._direction == 'left' else 'left'\n\n        cut_in_movement = py_trees.composites.Sequence()\n        cut_in_movement.add_child(CutIn(\n            self._adversary_actor, self.ego_vehicles[0], cut_in_direction, change_time=3, other_lane_time=2))\n        cut_in_movement.add_child(BasicAgentBehavior(\n            self._adversary_actor, plan=self._plan, target_speed=self._speed))\n\n        cut_in_behavior.add_child(cut_in_movement)\n        cut_in_behavior.add_child(Idle(30))  # Timeout in case a collision happened\n\n        sequence.add_child(cut_in_behavior)\n\n        for actor in self.other_actors:\n            sequence.add_child(ActorDestroy(actor))\n\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=0))\n            sequence.add_child(ReAddRoadLane(1 if self._direction == 'right' else -1))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/follow_leading_vehicle.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nFollow leading vehicle scenario:\n\nThe scenario realizes a common driving behavior, in which the\nuser-controlled ego vehicle follows a leading car driving down\na given road. At some point the leading car has to slow down and\nfinally stop. The ego vehicle has to react accordingly to avoid\na collision. The scenario ends either via a timeout, or if the ego\nvehicle stopped close enough to the leading vehicle\n\"\"\"\n\nimport random\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      KeepVelocity,\n                                                                      StopVehicle,\n                                                                      WaypointFollower)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               InTriggerDistanceToNextIntersection,\n                                                                               DriveDistance,\n                                                                               StandStill)\nfrom srunner.scenariomanager.timer import TimeOut\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass FollowLeadingVehicle(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple \"Follow a leading vehicle\"\n    scenario involving two vehicles.  (Traffic Scenario 2)\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 120            # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n\n        If randomize is True, the scenario parameters are randomized\n        \"\"\"\n\n        self._map = CarlaDataProvider.get_map()\n        self._first_vehicle_location = 25\n        self._first_vehicle_speed = 10\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._other_actor_max_brake = 1.0\n        self._other_actor_stop_in_front_intersection = 20\n        self._other_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(FollowLeadingVehicle, self).__init__(\"FollowVehicle\",\n                                                   ego_vehicles,\n                                                   config,\n                                                   world,\n                                                   debug_mode,\n                                                   criteria_enable=criteria_enable)\n\n        if randomize:\n            self._ego_other_distance_start = random.randint(4, 8)\n\n            # Example code how to randomize start location\n            # distance = random.randint(20, 80)\n            # new_location, _ = get_location_in_distance(self.ego_vehicles[0], distance)\n            # waypoint = CarlaDataProvider.get_map().get_waypoint(new_location)\n            # waypoint.transform.location.z += 39\n            # self.other_actors[0].set_transform(waypoint.transform)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location)\n        transform = waypoint.transform\n        transform.location.z += 0.5\n        first_vehicle = CarlaDataProvider.request_new_actor('vehicle.nissan.patrol', transform)\n        self.other_actors.append(first_vehicle)\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"follow leading vehicle\" scenario. After\n        invoking this scenario, it will wait for the user controlled vehicle to\n        enter the start region, then make the other actor to drive until reaching\n        the next intersection. Finally, the user-controlled vehicle has to be close\n        enough to the other actor to end the scenario.\n        If this does not happen within 60 seconds, a timeout stops the scenario\n        \"\"\"\n\n        # let the other actor drive until next intersection\n        driving_to_next_intersection = py_trees.composites.Parallel(\n            \"DrivingTowardsIntersection\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        driving_to_next_intersection.add_child(WaypointFollower(self.other_actors[0], self._first_vehicle_speed))\n        driving_to_next_intersection.add_child(InTriggerDistanceToNextIntersection(\n            self.other_actors[0], self._other_actor_stop_in_front_intersection))\n\n        # stop vehicle\n        stop = StopVehicle(self.other_actors[0], self._other_actor_max_brake)\n\n        # end condition\n        endcondition = py_trees.composites.Parallel(\"Waiting for end position\",\n                                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n        endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[0],\n                                                        self.ego_vehicles[0],\n                                                        distance=20,\n                                                        name=\"FinalDistance\")\n        endcondition_part2 = StandStill(self.ego_vehicles[0], name=\"StandStill\", duration=1)\n        endcondition.add_child(endcondition_part1)\n        endcondition.add_child(endcondition_part2)\n\n        # Build behavior tree\n        sequence = py_trees.composites.Sequence(\"Sequence Behavior\")\n        sequence.add_child(driving_to_next_intersection)\n        sequence.add_child(stop)\n        sequence.add_child(endcondition)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass FollowLeadingVehicleWithObstacle(BasicScenario):\n\n    \"\"\"\n    This class holds a scenario similar to FollowLeadingVehicle\n    but there is an obstacle in front of the leading vehicle\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 120            # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._map = CarlaDataProvider.get_map()\n        self._first_actor_location = 25\n        self._second_actor_location = self._first_actor_location + 41\n        self._first_actor_speed = 10\n        self._second_actor_speed = 1.5\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._other_actor_max_brake = 1.0\n        self._first_actor_transform = None\n        self._second_actor_transform = None\n\n        super(FollowLeadingVehicleWithObstacle, self).__init__(\"FollowLeadingVehicleWithObstacle\",\n                                                               ego_vehicles,\n                                                               config,\n                                                               world,\n                                                               debug_mode,\n                                                               criteria_enable=criteria_enable)\n        if randomize:\n            self._ego_other_distance_start = random.randint(4, 8)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n\n        first_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_actor_location)\n        second_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_actor_location)\n        first_actor_transform = carla.Transform(\n            carla.Location(first_actor_waypoint.transform.location.x,\n                           first_actor_waypoint.transform.location.y,\n                           first_actor_waypoint.transform.location.z - 500),\n            first_actor_waypoint.transform.rotation)\n        self._first_actor_transform = carla.Transform(\n            carla.Location(first_actor_waypoint.transform.location.x,\n                           first_actor_waypoint.transform.location.y,\n                           first_actor_waypoint.transform.location.z + 1),\n            first_actor_waypoint.transform.rotation)\n        yaw_1 = second_actor_waypoint.transform.rotation.yaw + 90\n        second_actor_transform = carla.Transform(\n            carla.Location(second_actor_waypoint.transform.location.x,\n                           second_actor_waypoint.transform.location.y,\n                           second_actor_waypoint.transform.location.z - 500),\n            carla.Rotation(second_actor_waypoint.transform.rotation.pitch, yaw_1,\n                           second_actor_waypoint.transform.rotation.roll))\n        self._second_actor_transform = carla.Transform(\n            carla.Location(second_actor_waypoint.transform.location.x,\n                           second_actor_waypoint.transform.location.y,\n                           second_actor_waypoint.transform.location.z + 1),\n            carla.Rotation(second_actor_waypoint.transform.rotation.pitch, yaw_1,\n                           second_actor_waypoint.transform.rotation.roll))\n\n        first_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.nissan.patrol', first_actor_transform)\n        second_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.diamondback.century', second_actor_transform)\n\n        first_actor.set_simulate_physics(enabled=False)\n        second_actor.set_simulate_physics(enabled=False)\n        self.other_actors.append(first_actor)\n        self.other_actors.append(second_actor)\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"follow leading vehicle\" scenario. After\n        invoking this scenario, it will wait for the user controlled vehicle to\n        enter the start region, then make the other actor to drive towards obstacle.\n        Once obstacle clears the road, make the other actor to drive towards the\n        next intersection. Finally, the user-controlled vehicle has to be close\n        enough to the other actor to end the scenario.\n        If this does not happen within 60 seconds, a timeout stops the scenario\n        \"\"\"\n\n        # let the other actor drive until next intersection\n        driving_to_next_intersection = py_trees.composites.Parallel(\n            \"Driving towards Intersection\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        obstacle_clear_road = py_trees.composites.Parallel(\"Obstalce clearing road\",\n                                                           policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        obstacle_clear_road.add_child(DriveDistance(self.other_actors[1], 4))\n        obstacle_clear_road.add_child(KeepVelocity(self.other_actors[1], self._second_actor_speed))\n\n        stop_near_intersection = py_trees.composites.Parallel(\n            \"Waiting for end position near Intersection\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        stop_near_intersection.add_child(WaypointFollower(self.other_actors[0], 10))\n        stop_near_intersection.add_child(InTriggerDistanceToNextIntersection(self.other_actors[0], 20))\n\n        driving_to_next_intersection.add_child(WaypointFollower(self.other_actors[0], self._first_actor_speed))\n        driving_to_next_intersection.add_child(InTriggerDistanceToVehicle(self.other_actors[1],\n                                                                          self.other_actors[0], 15))\n\n        # end condition\n        endcondition = py_trees.composites.Parallel(\"Waiting for end position\",\n                                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n        endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[0],\n                                                        self.ego_vehicles[0],\n                                                        distance=20,\n                                                        name=\"FinalDistance\")\n        endcondition_part2 = StandStill(self.ego_vehicles[0], name=\"FinalSpeed\", duration=1)\n        endcondition.add_child(endcondition_part1)\n        endcondition.add_child(endcondition_part2)\n\n        # Build behavior tree\n        sequence = py_trees.composites.Sequence(\"Sequence Behavior\")\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform))\n        sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform))\n        sequence.add_child(driving_to_next_intersection)\n        sequence.add_child(StopVehicle(self.other_actors[0], self._other_actor_max_brake))\n        sequence.add_child(TimeOut(3))\n        sequence.add_child(obstacle_clear_road)\n        sequence.add_child(stop_near_intersection)\n        sequence.add_child(StopVehicle(self.other_actors[0], self._other_actor_max_brake))\n        sequence.add_child(endcondition)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n        sequence.add_child(ActorDestroy(self.other_actors[1]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/freeride.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSimple freeride scenario. No action, no triggers. Ego vehicle can simply cruise around.\n\"\"\"\n\nimport py_trees\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass FreeRide(BasicScenario):\n\n    \"\"\"\n    Implementation of a simple free ride scenario that consits only of the ego vehicle\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=10000000):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n        super(FreeRide, self).__init__(\"FreeRide\",\n                                       ego_vehicles,\n                                       config,\n                                       world,\n                                       debug_mode,\n                                       criteria_enable=criteria_enable)\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"\n        \"\"\"\n        return None\n\n    def _create_behavior(self):\n        \"\"\"\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"Sequence Behavior\")\n        sequence.add_child(Idle())\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        for ego_vehicle in self.ego_vehicles:\n            collision_criterion = CollisionTest(ego_vehicle)\n            criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/green_traffic_light.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSets the ego incoming traffic light to green. Support scenario at routes\nto let the ego gather speed\n\"\"\"\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import TrafficLightFreezer\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass PriorityAtJunction(BasicScenario):\n    \"\"\"\n    Sets the ego incoming traffic light to green. Support scenario at routes\n    to let the ego gather speed\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._tl_dict = {}\n\n        self.timeout = timeout\n        super().__init__(\"PriorityAtJunction\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Get the junction and traffic lights\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        self._get_traffic_lights(self._junction, ego_junction_dist)\n\n    def _get_traffic_lights(self, junction, junction_dist):\n        \"\"\"Get the traffic light of the junction, mapping their states\"\"\"\n        tls = self._world.get_traffic_lights_in_junction(junction.id)\n        if not tls:\n            raise ValueError(\"No traffic lights found, nothing to do here\")\n\n        ego_landmark = self._ego_wp.get_landmarks_of_type(junction_dist + 1, \"1000001\")[0]\n        ego_tl = self._world.get_traffic_light(ego_landmark)\n        for tl in tls:\n            self._tl_dict[tl] = carla.TrafficLightState.Green if tl.id == ego_tl.id else carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Freeze the traffic lights until the ego has exited the junction\n        \"\"\"\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0], self._junction.id))\n        root.add_child(TrafficLightFreezer(self._tl_dict))\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/hard_break.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2022 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nHard break scenario:\n\nThe scenario spawn a vehicle in front of the ego that drives for a while before\nsuddenly hard breaking, forcing the ego to avoid the collision\n\"\"\"\n\nimport py_trees\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import StopFrontVehicles, StartFrontVehicles\n\n\nclass HardBreakRoute(BasicScenario):\n\n    \"\"\"\n    This class uses the is the Background Activity at routes to create a hard break scenario.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 120            # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self.timeout = timeout\n        self._stop_duration = 10\n        self.end_distance = 15\n\n        super().__init__(\"HardBreak\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        pass\n\n    def _create_behavior(self):\n        \"\"\"\n        Uses the Background Activity to force a hard break on the vehicles in front of the actor,\n        then waits for a bit to check if the actor has collided. After a set duration,\n        the front vehicles will resume their movement\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"HardBreak\")\n        sequence.add_child(StopFrontVehicles())\n        sequence.add_child(Idle(self._stop_duration))\n        sequence.add_child(StartFrontVehicles())\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self.end_distance))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Empty, the route already has a collision criteria\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/highway_cut_in.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      ActorTransformSetter,\n                                                                      SyncArrivalWithAgent,\n                                                                      CutIn)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\nfrom srunner.tools.scenario_helper import generate_target_waypoint\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\nclass HighwayCutIn(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle runs a red light\n    in front of the ego, forcing it to react. This vehicles are 'special' ones such as police cars,\n    ambulances or firetrucks.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._same_lane_time = 0.3\n        self._other_lane_time = 3\n        self._change_time = 2\n        self._speed_perc = 80\n        self._cut_in_distance = 10\n        self._extra_space = 170\n\n        self._start_location = convert_dict_to_location(config.other_parameters['other_actor_location'])\n\n        super().__init__(\"HighwayCutIn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        self._other_waypoint = self._map.get_waypoint(self._start_location)\n        self._other_transform = self._other_waypoint.transform\n\n        self._cut_in_vehicle = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._other_transform, rolename='scenario',\n            attribute_filter={'base_type': 'car', 'has_lights': True}\n        )\n        self.other_actors.append(self._cut_in_vehicle)\n\n        # Move below ground\n        self._cut_in_vehicle.set_location(self._other_transform.location - carla.Location(z=100))\n        self._cut_in_vehicle.set_simulate_physics(False)\n\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        behavior = py_trees.composites.Sequence(\"HighwayCutIn\")\n\n        if self.route_mode:\n            behavior.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=False,\n                remove_entries=[self._other_waypoint],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=self._extra_space\n            ))\n        behavior.add_child(ActorTransformSetter(self._cut_in_vehicle, self._other_transform))\n\n        # Sync behavior\n        target_wp = generate_target_waypoint(self._other_waypoint)\n        front_wps = target_wp.next(self._cut_in_distance)\n        if not front_wps:\n            raise ValueError(\"Couldn't find a waypoint to perform the cut in\")\n        target_wp = front_wps[0]\n\n        trigger_wp = self._map.get_waypoint(self.config.trigger_points[0].location)\n        reference_wp = generate_target_waypoint(trigger_wp)\n        behavior.add_child(SyncArrivalWithAgent(\n            self._cut_in_vehicle, self.ego_vehicles[0], target_wp.transform, reference_wp.transform, 5))\n\n        # Cut in\n        behavior.add_child(CutIn(\n            self._cut_in_vehicle, self.ego_vehicles[0], 'left', self._speed_perc,\n            self._same_lane_time, self._other_lane_time, self._change_time, name=\"Cut_in\")\n        )\n        behavior.add_child(ActorDestroy(self._cut_in_vehicle))\n        return behavior\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/invading_turn.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario in which the ego is about to turn right \nwhen a vehicle coming from the opposite lane invades the ego's lane, forcing the ego to move right to avoid a possible collision.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (InvadingActorFlow,\n                                                                      ScenarioTimeout,\n                                                                      ActorDestroy,\n                                                                      BatchActorTransformSetter)\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitUntilInFrontPosition\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import RemoveRoadLane, ChangeOppositeBehavior, ReAddRoadLane\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass InvadingTurn(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which the ego is about to turn right \n    when a vehicle coming from the opposite lane invades the ego's lane, \n    forcing the ego to move right to avoid a possible collision.\n\n    This scenario is expected to take place on a road that has only one lane in each direction.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(\n            self._trigger_location)\n\n        self._flow_frequency = 40 # m\n        self._source_dist = 30 # Distance between source and end point\n\n        self._check_distance = 50\n\n        self._distance = get_value_parameter(config, 'distance', float, 100)\n        self._offset = get_value_parameter(config, 'offset', float, 0.25)  # meters invaded in the opposite direction\n        self._scenario_timeout = 240\n\n        self._obstacle_transforms = []\n\n        super().__init__(\"InvadingTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn adversary actor\n        next_wps = self._reference_waypoint.next(self._distance + self._source_dist)\n        if not next_wps:\n            raise ValueError(\"Couldn't find the source location for the actor flow\")\n        self._forward_wp = next_wps[0]\n        self._source_wp = self._forward_wp.get_left_lane()\n        if not self._source_wp:\n            raise ValueError(\"Couldn't find the source location for the actor flow\")\n\n        self._sink_wp = self._reference_waypoint.get_left_lane()\n        if not self._sink_wp:\n            raise ValueError(\"Couldn't find the sink location for the actor flow\")\n\n        # Lane offset\n        self._offset_constant = 0.7  # Ideally, half the vehicle lane width\n        self._true_offset = self._offset + self._sink_wp.lane_width / 2 - self._offset_constant\n        self._true_offset *= -1 # Cause left direction\n\n        self._create_obstacle()\n\n    def _create_obstacle(self):\n\n        next_wp = self._source_wp.next(10)[0]\n        obstacle_distance = 0.5 * self._distance\n        dist = 0\n        while dist < obstacle_distance:\n            next_wp = next_wp.next(5)[0]\n\n            displacement = 0.8 * next_wp.lane_width / 2\n            r_vec = next_wp.transform.get_right_vector()\n            spawn_transform = next_wp.transform\n            spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.3)\n\n            cone = CarlaDataProvider.request_new_actor('*constructioncone*', spawn_transform)\n            self.other_actors.append(cone)\n\n            self._obstacle_transforms.append([cone, spawn_transform])\n\n            transform = carla.Transform(spawn_transform.location, spawn_transform.rotation)\n            transform.location.z -= 200\n            cone.set_transform(transform)\n            cone.set_simulate_physics(False)\n\n            dist += 5\n\n        self._obstacle_transforms.reverse()  # So that the closest cones are spawned first\n\n    def _create_behavior(self):\n        \"\"\"\n        The adversary vehicle will go to the target place while invading another lane.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"InvadingTurn\")\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(self._reference_waypoint))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        sequence.add_child(BatchActorTransformSetter(self._obstacle_transforms))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(InvadingActorFlow(\n            self._source_wp, self._sink_wp, self.ego_vehicles[0], self._flow_frequency, offset=self._true_offset))\n\n        main_behavior.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._forward_wp.transform, True, self._check_distance))\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(main_behavior)\n        if self.route_mode:\n            sequence.add_child(ReAddRoadLane(0))\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        for actor in self.other_actors:\n            sequence.add_child(ActorDestroy(actor))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/left_turn_enter_flow.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a left turn\n\"\"\"\n\nimport py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass JunctionLeftTurnEnterFlow(BasicScenario):\n    \"\"\"\n    Vehicle turning left at junction scenario, with actors coming in the opposite direction.\n    The ego has to react to them, safely crossing the opposite lane\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self.timeout = timeout\n\n        self._direction = 'opposite'\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        self._end_distance = 10\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 20)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [25, 50])\n        self._scenario_timeout = 240\n\n        # The faster the flow, the further they are spawned, leaving time to react to them\n        self._source_dist = 4 * self._flow_speed\n        self._sink_dist = 2.5 * self._flow_speed\n\n        super().__init__(\"JunctionLeftTurnEnterFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the opposite entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Trying to find a lane in the {} direction but none was found\".format(self._direction))\n\n        # Get the source transform\n        source_entry_wp = self._rng.choice(source_entry_wps)\n\n        # Get the source transform\n        source_wp = source_entry_wp\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            source_wps = source_wp.previous(5)\n            if len(source_wps) == 0:\n                raise ValueError(\"Failed to find a source location as a waypoint with no previous was detected\")\n            if source_wps[0].is_junction:\n                break\n            source_wp = source_wps[0]\n            source_junction_dist += 5\n\n        self._source_wp = source_wp\n        source_transform = self._source_wp.transform\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 1)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location as a waypoint with no next was detected\")\n        self._sink_wp = sink_wps[0]\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass SignalizedJunctionLeftTurnEnterFlow(JunctionLeftTurnEnterFlow):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        # self.activate_scenario = activate_scenario\n        self.activate_scenario = True\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        source_tl = get_closest_traffic_light(self._source_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            elif tl.id == source_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"SignalizedJunctionLeftTurnEnterFlow\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=False,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        if self.activate_scenario:\n            end_condition = py_trees.composites.Sequence()\n            end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n            end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n            root.add_child(end_condition)\n            root.add_child(ActorFlow(\n                self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n            root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        # keep the traffic light behavior the same\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n\nclass NonSignalizedJunctionLeftTurnEnterFlow(JunctionLeftTurnEnterFlow):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        # self.activate_scenario = activate_scenario\n        self.activate_scenario = True\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"NonSignalizedJunctionLeftTurnEnterFlow\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=True,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        if self.activate_scenario:\n            root.add_child(ActorFlow(\n                self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/maneuver_opposite_direction.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nVehicle Maneuvering In Opposite Direction:\n\nVehicle is passing another vehicle in a rural area, in daylight, under clear\nweather conditions, at a non-junction and encroaches into another\nvehicle traveling in the opposite direction.\n\"\"\"\n\nfrom six.moves.queue import Queue   # pylint: disable=relative-import,bad-option-value\n\nimport math  # pylint: disable=wrong-import-order\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      ActorSource,\n                                                                      ActorSink,\n                                                                      WaypointFollower)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass ManeuverOppositeDirection(BasicScenario):\n\n    \"\"\"\n    \"Vehicle Maneuvering In Opposite Direction\" (Traffic Scenario 06)\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 obstacle_type='barrier', timeout=120):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        obstacle_type -> flag to select type of leading obstacle. Values: vehicle, barrier\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._first_vehicle_location = 50\n        self._second_vehicle_location = self._first_vehicle_location + 60\n        self._ego_vehicle_drive_distance = self._second_vehicle_location * 2\n        self._start_distance = self._first_vehicle_location * 0.9\n        self._opposite_speed = 5.56   # m/s\n        self._source_gap = 40   # m\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._source_transform = None\n        self._sink_location = None\n        self._blackboard_queue_name = 'ManeuverOppositeDirection/actor_flow_queue'\n        self._queue = py_trees.blackboard.Blackboard().set(self._blackboard_queue_name, Queue())\n        self._obstacle_type = obstacle_type\n        self._first_actor_transform = None\n        self._second_actor_transform = None\n        self._third_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(ManeuverOppositeDirection, self).__init__(\n            \"ManeuverOppositeDirection\",\n            ego_vehicles,\n            config,\n            world,\n            debug_mode,\n            criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        first_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location)\n        second_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_vehicle_location)\n        second_actor_waypoint = second_actor_waypoint.get_left_lane()\n\n        first_actor_transform = carla.Transform(\n            first_actor_waypoint.transform.location,\n            first_actor_waypoint.transform.rotation)\n        if self._obstacle_type == 'vehicle':\n            first_actor_model = 'vehicle.nissan.micra'\n        else:\n            first_actor_transform.rotation.yaw += 90\n            first_actor_model = 'static.prop.streetbarrier'\n            second_prop_waypoint = first_actor_waypoint.next(2.0)[0]\n            position_yaw = second_prop_waypoint.transform.rotation.yaw + 90\n            offset_location = carla.Location(\n                0.50 * second_prop_waypoint.lane_width * math.cos(math.radians(position_yaw)),\n                0.50 * second_prop_waypoint.lane_width * math.sin(math.radians(position_yaw)))\n            second_prop_transform = carla.Transform(\n                second_prop_waypoint.transform.location + offset_location, first_actor_transform.rotation)\n            second_prop_actor = CarlaDataProvider.request_new_actor(first_actor_model, second_prop_transform)\n            second_prop_actor.set_simulate_physics(True)\n        first_actor = CarlaDataProvider.request_new_actor(first_actor_model, first_actor_transform)\n        first_actor.set_simulate_physics(True)\n        second_actor = CarlaDataProvider.request_new_actor('vehicle.audi.tt', second_actor_waypoint.transform)\n\n        self.other_actors.append(first_actor)\n        self.other_actors.append(second_actor)\n        if self._obstacle_type != 'vehicle':\n            self.other_actors.append(second_prop_actor)\n\n        self._source_transform = second_actor_waypoint.transform\n        sink_waypoint = second_actor_waypoint.next(1)[0]\n        while not sink_waypoint.is_intersection:\n            sink_waypoint = sink_waypoint.next(1)[0]\n        self._sink_location = sink_waypoint.transform.location\n\n        self._first_actor_transform = first_actor_transform\n        self._second_actor_transform = second_actor_waypoint.transform\n        self._third_actor_transform = second_prop_transform\n\n    def _create_behavior(self):\n        \"\"\"\n        The behavior tree returned by this method is as follows:\n        The ego vehicle is trying to pass a leading vehicle in the same lane\n        by moving onto the oncoming lane while another vehicle is moving in the\n        opposite direction in the oncoming lane.\n        \"\"\"\n\n        # Leaf nodes\n        actor_source = ActorSource(\n            ['vehicle.audi.tt', 'vehicle.tesla.model3', 'vehicle.nissan.micra'],\n            self._source_transform, self._source_gap, self._blackboard_queue_name)\n        actor_sink = ActorSink(self._sink_location, 10)\n        ego_drive_distance = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_drive_distance)\n        waypoint_follower = WaypointFollower(\n            self.other_actors[1], self._opposite_speed,\n            blackboard_queue_name=self._blackboard_queue_name, avoid_collision=True)\n\n        # Non-leaf nodes\n        parallel_root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # Building tree\n        parallel_root.add_child(ego_drive_distance)\n        parallel_root.add_child(actor_source)\n        parallel_root.add_child(actor_sink)\n        parallel_root.add_child(waypoint_follower)\n\n        scenario_sequence = py_trees.composites.Sequence()\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform))\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform))\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[2], self._third_actor_transform))\n        scenario_sequence.add_child(parallel_root)\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[0]))\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[1]))\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[2]))\n\n        return scenario_sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/no_signal_junction_crossing.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nNon-signalized junctions: crossing negotiation:\n\nThe hero vehicle is passing through a junction without traffic lights\nAnd encounters another vehicle passing across the junction.\n\"\"\"\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      SyncArrival,\n                                                                      KeepVelocity,\n                                                                      StopVehicle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerRegion, DriveDistance, WaitEndIntersection\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass NoSignalJunctionCrossing(BasicScenario):\n\n    \"\"\"\n    Implementation class for\n    'Non-signalized junctions: crossing negotiation' scenario,\n    (Traffic Scenario 10).\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    # ego vehicle parameters\n    _ego_vehicle_max_velocity = 20\n    _ego_vehicle_driven_distance = 105\n\n    # other vehicle\n    _other_actor_max_brake = 1.0\n    _other_actor_target_velocity = 15\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n\n        self._other_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(NoSignalJunctionCrossing, self).__init__(\"NoSignalJunctionCrossing\",\n                                                       ego_vehicles,\n                                                       config,\n                                                       world,\n                                                       debug_mode,\n                                                       criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        self._other_actor_transform = config.other_actors[0].transform\n        first_vehicle_transform = carla.Transform(\n            carla.Location(config.other_actors[0].transform.location.x,\n                           config.other_actors[0].transform.location.y,\n                           config.other_actors[0].transform.location.z - 500),\n            config.other_actors[0].transform.rotation)\n        first_vehicle = CarlaDataProvider.request_new_actor(config.other_actors[0].model, first_vehicle_transform)\n        first_vehicle.set_simulate_physics(enabled=False)\n        self.other_actors.append(first_vehicle)\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, it will wait for the user\n        controlled vehicle to enter the start region,\n        then make a traffic participant to accelerate\n        until it is going fast enough to reach an intersection point.\n        at the same time as the user controlled vehicle at the junction.\n        Once the user controlled vehicle comes close to the junction,\n        the traffic participant accelerates and passes through the junction.\n        After 60 seconds, a timeout stops the scenario.\n        \"\"\"\n\n        # Creating leaf nodes\n        start_other_trigger = InTriggerRegion(\n            self.ego_vehicles[0],\n            -80, -70,\n            -75, -60)\n\n        sync_arrival = SyncArrival(\n            self.other_actors[0], self.ego_vehicles[0],\n            carla.Location(x=-74.63, y=-136.34))\n\n        pass_through_trigger = InTriggerRegion(\n            self.ego_vehicles[0],\n            -90, -70,\n            -124, -119)\n\n        keep_velocity_other = KeepVelocity(\n            self.other_actors[0],\n            self._other_actor_target_velocity)\n\n        stop_other_trigger = InTriggerRegion(\n            self.other_actors[0],\n            -45, -35,\n            -140, -130)\n\n        stop_other = StopVehicle(\n            self.other_actors[0],\n            self._other_actor_max_brake)\n\n        end_condition = InTriggerRegion(\n            self.ego_vehicles[0],\n            -90, -70,\n            -170, -156\n        )\n\n        # Creating non-leaf nodes\n        root = py_trees.composites.Sequence()\n        scenario_sequence = py_trees.composites.Sequence()\n        sync_arrival_parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        keep_velocity_other_parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # Building tree\n        root.add_child(scenario_sequence)\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform))\n        scenario_sequence.add_child(start_other_trigger)\n        scenario_sequence.add_child(sync_arrival_parallel)\n        scenario_sequence.add_child(keep_velocity_other_parallel)\n        scenario_sequence.add_child(stop_other)\n        scenario_sequence.add_child(end_condition)\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        sync_arrival_parallel.add_child(sync_arrival)\n        sync_arrival_parallel.add_child(pass_through_trigger)\n        keep_velocity_other_parallel.add_child(keep_velocity_other)\n        keep_velocity_other_parallel.add_child(stop_other_trigger)\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collison_criteria = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collison_criteria)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass NoSignalJunctionCrossingRoute(BasicScenario):\n\n    \"\"\"\n    At routes, these scenarios are simplified, as they can be triggered making\n    use of the background activity. For unsignalized intersections, just wait\n    until the ego_vehicle has left the intersection.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n        self._end_distance = 50\n\n        super(NoSignalJunctionCrossingRoute, self).__init__(\"NoSignalJunctionCrossingRoute\",\n                                                            ego_vehicles,\n                                                            config,\n                                                            world,\n                                                            debug_mode,\n                                                            criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Just wait for the ego to exit the junction, for route the BackgroundActivity already does all the job\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"UnSignalizedJunctionCrossingRoute\")\n        sequence.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/object_crash_intersection.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\"\"\"\nObject crash with prior vehicle action scenario:\nThe scenario realizes the user controlled ego vehicle\nmoving along the road and encounters a cyclist ahead after taking a right or left turn.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      HandBrakeVehicle,\n                                                                      KeepVelocity,\n                                                                      ActorTransformSetter,\n                                                                      MovePedestrianWithEgo)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           generate_target_waypoint_in_route,\n                                           get_same_dir_lanes,\n                                           get_opposite_dir_lanes)\n\nfrom srunner.tools.background_manager import LeaveCrossingSpace\n\n\ndef get_sidewalk_transform(waypoint, offset):\n    \"\"\"\n    Processes the waypoint transform to find a suitable spawning one at the sidewalk.\n    It first rotates the transform so that it is pointing towards the road and then moves a\n    bit to the side waypoint that aren't part of sidewalks, as they might be invading the road\n    \"\"\"\n\n    new_rotation = waypoint.transform.rotation\n    new_rotation.yaw += offset['yaw']\n\n    if waypoint.lane_type == carla.LaneType.Sidewalk:\n        new_location = waypoint.transform.location\n    else:\n        right_vector = waypoint.transform.get_right_vector()\n        offset_location = carla.Location(offset[\"k\"] * right_vector.x, offset[\"k\"] * right_vector.y)\n        new_location = waypoint.transform.location + offset_location\n    new_location.z += offset['z']\n\n    return carla.Transform(new_location, new_rotation)\n\n\nclass BaseVehicleTurning(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    with prior vehicle action involving a vehicle and a cyclist.\n    The ego vehicle is passing through a road and encounters\n    a cyclist after taking a turn.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n    _subtype = None\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60, name=\"BaseVehicleTurning\"):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._ego_route = config.route\n\n        self._start_distance = 11\n        self._spawn_dist = self._start_distance\n        self._number_of_attempts = 6\n        self._retry_dist = 0.4\n\n        self._adversary_transform = None\n\n        self._collision_wp = None\n        self._adversary_speed = 1.8  # Speed of the adversary [m/s]\n        self._reaction_time = 1.8  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n\n        self._offset = {\"yaw\": 270, \"z\": 0.2, \"k\": 1.5}\n\n        self.timeout = timeout\n        super(BaseVehicleTurning, self).__init__(\n            name, ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _get_target_waypoint(self):\n        \"\"\"\n        Gets the first waypoint after the junction.\n        This method depends on the subtype of VehicleTurning scenario\n        \"\"\"\n        if self._subtype == 'right':\n            return generate_target_waypoint(self._reference_waypoint, 1)\n        elif self._subtype == 'left':\n            return generate_target_waypoint(self._reference_waypoint, -1)\n        elif self._subtype == 'route':\n            return generate_target_waypoint_in_route(self._reference_waypoint, self._ego_route)\n        else:\n            raise ValueError(\"Trying to run a VehicleTurning scenario with a wrong subtype\")\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the waypoint right after the junction\n        waypoint = self._get_target_waypoint()\n        move_dist = self._start_distance\n        while self._number_of_attempts > 0:\n            parking_location = None\n\n            # Move to the front\n            waypoint = waypoint.next(move_dist)[0]\n            self._collision_wp = waypoint\n\n            # Move to the right\n            sidewalk_waypoint = waypoint\n            while sidewalk_waypoint.lane_type != carla.LaneType.Sidewalk:\n                right_wp = sidewalk_waypoint.get_right_lane()\n                if right_wp is None:\n                    break  # No more right lanes\n                sidewalk_waypoint = right_wp\n                if sidewalk_waypoint.lane_type == carla.LaneType.Parking:\n                    parking_location = sidewalk_waypoint.transform.location\n\n            # Get the adversary transform and spawn it\n            self._adversary_transform = get_sidewalk_transform(sidewalk_waypoint, self._offset)\n            adversary = CarlaDataProvider.request_new_actor('vehicle.diamondback.century', self._adversary_transform)\n            if adversary is None:\n                self._number_of_attempts -= 1\n                move_dist = self._retry_dist\n                self._spawn_dist += self._retry_dist\n                continue\n\n            # Both actors where summoned, end\n            break\n\n        if self._number_of_attempts == 0:\n            raise ValueError(\"Couldn't find viable position for the adversary\")\n\n        if parking_location:\n            self.parking_slots.append(parking_location)\n\n        if isinstance(adversary, carla.Vehicle):\n            adversary.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(adversary)\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter the in the trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        ego vehicle has to avoid the crash after a turn, but\n        continue driving after the road is clear.If this does not happen\n        within 90 seconds, a timeout stops the scenario.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"CrossingActorIntersection\")\n        collision_location = self._collision_wp.transform.location\n        collision_distance = collision_location.distance(self._adversary_transform.location)\n        collision_duration = collision_distance / self._adversary_speed\n\n        # Adversary trigger behavior\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n        sequence.add_child(HandBrakeVehicle(self.other_actors[0], False))\n\n        # Move the adversary.\n        speed_duration = 2.0 * collision_duration\n        speed_distance = 2.0 * collision_distance\n        if self.route_mode:\n            sequence.add_child(LeaveCrossingSpace(self._collision_wp))\n        sequence.add_child(KeepVelocity(\n            self.other_actors[0], self._adversary_speed, True,\n            speed_duration, speed_distance, name=\"AdversaryCrossing\")\n        )\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass VehicleTurningRight(BaseVehicleTurning):\n    \"\"\"\n    Version of the VehicleTurning scenario where\n    the adversary is placed at the right side after the junction\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._subtype = 'right'\n        super(VehicleTurningRight, self).__init__(\n            world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout, \"VehicleTurningRight\")\n\n\nclass VehicleTurningLeft(BaseVehicleTurning):\n    \"\"\"\n    Version of the VehicleTurning scenario where\n    the adversary is placed at the left side after the junction\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._subtype = 'left'\n        super(VehicleTurningLeft, self).__init__(\n            world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout, \"VehicleTurningLeft\")\n\n\nclass VehicleTurningRoute(BaseVehicleTurning):\n    \"\"\"\n    Version of the VehicleTurning scenario where\n    the adversary is placed using the route path\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._subtype = 'route'\n        super(VehicleTurningRoute, self).__init__(\n            world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout, \"VehicleTurningRoute\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Empty, the route already has a collision criteria\n        \"\"\"\n        return []\n\n\nclass VehicleTurningRoutePedestrian(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    with prior vehicle action involving a vehicle and a cyclist.\n    The ego vehicle is passing through a road and encounters\n    a cyclist after taking a turn.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n    _subtype = None\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60, name=\"VehicleTurningRoutePedestrian\"):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._ego_route = config.route\n\n        self._collision_wp = None\n        self._adversary_speed = 1.8  # Speed of the adversary [m/s]\n        self._reaction_time = 2.2  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n\n        self._offset = {\"yaw\": 270, \"z\": 1.2, \"k\": 1.5}\n\n        self.timeout = timeout\n        super().__init__(name, ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the waypoint right after the junction\n        parking_location = None\n        waypoint = generate_target_waypoint_in_route(self._reference_waypoint, self._ego_route)\n        self._collision_wp = waypoint.next(0.5)[0]  # Some wps are still part of the junction\n\n        # Get the right waypoint at the sidewalk\n        same_dir_wps = get_same_dir_lanes(self._collision_wp)\n        right_wp = same_dir_wps[0]\n        while right_wp.lane_type != carla.LaneType.Sidewalk:\n            side_wp = right_wp.get_right_lane()\n            if side_wp is None:\n                break\n            right_wp = side_wp\n            if right_wp.lane_type == carla.LaneType.Parking:\n                parking_location = right_wp.transform.location\n\n        # Get the left waypoint at the sidewalk\n        other_dir_wps = get_opposite_dir_lanes(self._collision_wp)\n        if other_dir_wps:\n            # With opposite lane\n            left_wp = other_dir_wps[-1]\n            while left_wp.lane_type != carla.LaneType.Sidewalk:\n                side_wp = left_wp.get_right_lane()\n                if side_wp is None:\n                    break\n                left_wp = side_wp\n                if left_wp.lane_type == carla.LaneType.Parking:\n                    parking_location = left_wp.transform.location\n        else:\n            # Without opposite lane\n            self._offset['yaw'] = 90\n            left_wp = same_dir_wps[-1]\n            while left_wp.lane_type != carla.LaneType.Sidewalk:\n                side_wp = left_wp.get_left_lane()\n                if side_wp is None:\n                    break\n                left_wp = side_wp\n                if left_wp.lane_type == carla.LaneType.Parking:\n                    parking_location = left_wp.transform.location\n\n        self._adversary_distance = right_wp.transform.location.distance(left_wp.transform.location)\n\n        entry_vec = self._reference_waypoint.transform.get_forward_vector()\n        exit_vec = waypoint.transform.get_forward_vector()\n        cross_prod = entry_vec.cross(exit_vec)\n        spawn_wp = right_wp if cross_prod.z < 0 else left_wp\n\n        # Get the adversary transform and spawn it\n        self._spawn_transform = get_sidewalk_transform(spawn_wp, self._offset)\n        adversary = CarlaDataProvider.request_new_actor('walker.*', self._spawn_transform)\n        if adversary is None:\n            raise ValueError(\"Couldn't spawn adversary\")\n\n        adversary.set_location(self._spawn_transform.location + carla.Location(z=-200))\n        adversary = self._replace_walker(adversary)\n\n        if parking_location:\n            self.parking_slots.append(parking_location)\n\n        self.other_actors.append(adversary)\n\n    def _create_behavior(self):\n        \"\"\"\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VehicleTurningRoutePedestrian\")\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._spawn_transform, True))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Adversary trigger behavior\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n        if self.route_mode:\n            sequence.add_child(LeaveCrossingSpace(self._collision_wp))\n\n        # Move the adversary.\n        speed_distance = self._adversary_distance\n        speed_duration = self._adversary_distance / self._adversary_speed\n        sequence.add_child(KeepVelocity(\n            self.other_actors[0], self._adversary_speed, True,\n            speed_duration, speed_distance, name=\"AdversaryCrossing\")\n        )\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, adversary):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = adversary.type_id\n        adversary.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        adversary = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not adversary:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        adversary.set_simulate_physics(False)\n        adversary.set_location(spawn_transform.location + carla.Location(z=-50))\n        return adversary\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], self.other_actors[0], 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/object_crash_vehicle.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nObject crash without prior vehicle action scenario:\nThe scenario realizes the user controlled ego vehicle\nmoving along the road and encountering a cyclist ahead.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport math\nimport py_trees\nimport carla\nfrom math import floor\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      KeepVelocity,\n                                                                      Idle,\n                                                                      ActorTransformSetter,\n                                                                      MovePedestrianWithEgo)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_location_in_distance_from_wp\n\nfrom srunner.tools.background_manager import LeaveSpaceInFront, LeaveCrossingSpace\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass StationaryObjectCrossing(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    without prior vehicle action involving a vehicle and a cyclist.\n    The ego vehicle is passing through a road and encounters\n    a stationary cyclist.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location)\n        # ego vehicle parameters\n        self._ego_vehicle_distance_driven = 40\n\n        # other vehicle parameters\n        self._other_actor_target_velocity = 10\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(StationaryObjectCrossing, self).__init__(\"Stationaryobjectcrossing\",\n                                                       ego_vehicles,\n                                                       config,\n                                                       world,\n                                                       debug_mode,\n                                                       criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        _distance = 40\n        lane_width = self._reference_waypoint.lane_width\n        location, _ = get_location_in_distance_from_wp(self._reference_waypoint, _distance)\n        waypoint = self._wmap.get_waypoint(location)\n        offset = {\"orientation\": 270, \"position\": 90, \"z\": 0.4, \"k\": 0.2}\n        position_yaw = waypoint.transform.rotation.yaw + offset['position']\n        orientation_yaw = waypoint.transform.rotation.yaw + offset['orientation']\n        offset_location = carla.Location(\n            offset['k'] * lane_width * math.cos(math.radians(position_yaw)),\n            offset['k'] * lane_width * math.sin(math.radians(position_yaw)))\n        location += offset_location\n        location.z += offset['z']\n        self.transform = carla.Transform(location, carla.Rotation(yaw=orientation_yaw))\n        static = CarlaDataProvider.request_new_actor('static.prop.container', self.transform)\n        static.set_simulate_physics(True)\n        self.other_actors.append(static)\n\n    def _create_behavior(self):\n        \"\"\"\n        Only behavior here is to wait\n        \"\"\"\n        lane_width = self.ego_vehicles[0].get_world().get_map().get_waypoint(\n            self.ego_vehicles[0].get_location()).lane_width\n        lane_width = lane_width + (1.25 * lane_width)\n\n        # leaf nodes\n        actor_stand = Idle(15)\n        actor_removed = ActorDestroy(self.other_actors[0])\n        end_condition = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_distance_driven)\n\n        # non leaf nodes\n        root = py_trees.composites.Parallel(\n            name=\"StaticObstacle\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        scenario_sequence = py_trees.composites.Sequence()\n\n        # building tree\n        root.add_child(scenario_sequence)\n        scenario_sequence.add_child(actor_stand)\n        scenario_sequence.add_child(actor_removed)\n        scenario_sequence.add_child(end_condition)\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass DynamicObjectCrossing(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    without prior vehicle action involving a vehicle and a cyclist/pedestrian,\n    The ego vehicle is passing through a road,\n    And encounters a cyclist/pedestrian crossing the road.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._num_lane_changes = 0\n\n        self._blocker_shift = 0.9\n        self._retry_dist = 0.4\n\n        self._adversary_transform = None\n        self._blocker_transform = None\n        self._collision_wp = None\n\n        self._adversary_speed = 2.0  # Speed of the adversary [m/s]\n        self._crossing_angle = get_value_parameter(config, 'crossing_angle', float, 0)\n        self._reaction_time = 2.1  # Time the agent has to react to avoid the collision [s]\n        self._reaction_time += 0.1 * floor(self._crossing_angle / 5)\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n        self.timeout = timeout\n\n        self._number_of_attempts = 6\n\n        self._distance = get_value_parameter(config, 'distance', float, 12)\n        self._blocker_model = get_value_parameter(config, 'blocker_model', str, 'static.prop.vendingmachine')\n        if abs(self._crossing_angle) > 90:\n            raise ValueError(\"'crossing_angle' must be between -90 and 90º for the pedestrian to cross the road\")\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        super(DynamicObjectCrossing, self).__init__(\"DynamicObjectCrossing\",\n                                                    ego_vehicles,\n                                                    config,\n                                                    world,\n                                                    debug_mode,\n                                                    criteria_enable=criteria_enable)\n\n    def _get_sidewalk_transform(self, waypoint, offset):\n        \"\"\"\n        Processes the waypoint transform to find a suitable spawning one at the sidewalk.\n        It first rotates the transform so that it is pointing towards the road and then moves a\n        bit to the side waypoint that aren't part of sidewalks, as they might be invading the road\n        \"\"\"\n        if self._direction == \"left\":\n            offset['yaw'] *= -1\n            offset['k'] *= -1\n\n        new_rotation = waypoint.transform.rotation\n        new_rotation.yaw += offset['yaw']\n\n        if waypoint.lane_type == carla.LaneType.Sidewalk:\n            new_location = waypoint.transform.location\n        else:\n            right_vector = waypoint.transform.get_right_vector()\n            offset_dist = offset[\"k\"]\n            offset_location = carla.Location(offset_dist * right_vector.x, offset_dist * right_vector.y)\n            new_location = waypoint.transform.location + offset_location\n        new_location.z += offset['z']\n\n        return carla.Transform(new_location, new_rotation)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the waypoint in front of the ego.\n        move_dist = self._distance\n        waypoint = self._reference_waypoint\n\n        while self._number_of_attempts > 0:\n            parking_location = None\n            self._collision_dist = 0\n\n            # Move to the front\n            location, _ = get_location_in_distance_from_wp(waypoint, move_dist, False)\n            waypoint = self._wmap.get_waypoint(location)\n            self._collision_wp = waypoint\n\n            # Move to the right\n            sidewalk_waypoint = waypoint\n            while sidewalk_waypoint.lane_type != carla.LaneType.Sidewalk:\n                if self._direction == \"right\":\n                    side_wp = sidewalk_waypoint.get_right_lane()\n                else:\n                    side_wp = sidewalk_waypoint.get_left_lane()\n                if side_wp is None:\n                    break  # No more side lanes\n                sidewalk_waypoint = side_wp\n                if side_wp.lane_type == carla.LaneType.Parking:\n                    parking_location = side_wp.transform.location\n\n            # Get the blocker transform and spawn it\n            offset = {\"yaw\": 0 if 'vehicle' in self._blocker_model else 90, \"z\": 0.0, \"k\": 1.5}\n            self._blocker_transform = self._get_sidewalk_transform(sidewalk_waypoint, offset)\n            blocker = CarlaDataProvider.request_new_actor(\n                self._blocker_model, self._blocker_transform, rolename=\"scenario no lights\")\n            if not blocker:\n                self._number_of_attempts -= 1\n                move_dist = self._retry_dist\n                print(\"Failed to spawn the blocker\")\n                continue\n\n            # Get the adversary transform and spawn it\n            walker_dist = blocker.bounding_box.extent.x + 0.5\n            wps = sidewalk_waypoint.next(walker_dist)\n            if not wps:\n                raise ValueError(\"Couldn't find a location to spawn the adversary\")\n            walker_wp = wps[0]\n\n            offset = {\"yaw\": 270 - self._crossing_angle, \"z\": 1.2, \"k\": 1.2}\n            self._adversary_transform = self._get_sidewalk_transform(walker_wp, offset)\n            adversary = CarlaDataProvider.request_new_actor('walker.*', self._adversary_transform)\n            if adversary is None:\n                blocker.destroy()\n                self._number_of_attempts -= 1\n                move_dist = self._retry_dist\n                print(\"Failed to spawn an adversary\")\n                continue\n\n            self._collision_dist += waypoint.transform.location.distance(self._adversary_transform.location)\n\n            # Both actors were succesfully spawned, end\n            break\n\n        if self._number_of_attempts == 0:\n            raise Exception(\"Couldn't find viable position for the adversary and blocker actors\")\n\n        blocker.set_simulate_physics(False)\n        adversary.set_location(self._adversary_transform.location + carla.Location(z=-200))\n        adversary = self._replace_walker(adversary)\n\n        if parking_location:\n            self.parking_slots.append(parking_location)\n\n        self.other_actors.append(adversary)\n        self.other_actors.append(blocker)\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        then after 60 seconds, a timeout stops the scenario\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"CrossingActor\")\n        if self.route_mode:\n            total_dist = self._distance + 10\n            sequence.add_child(LeaveSpaceInFront(total_dist))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._adversary_transform, True))\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        # Move the adversary\n        move_distance = 2 * self._collision_dist  # Cross the whole road (supposing symetry in both directions)\n        move_duration = move_distance / self._adversary_speed\n        if self.route_mode:\n            sequence.add_child(LeaveCrossingSpace(self._collision_wp))\n        sequence.add_child(KeepVelocity(\n            self.other_actors[0], self._adversary_speed,\n            duration=move_duration, distance=move_distance, name=\"AdversaryCrossing\"))\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(ActorDestroy(self.other_actors[1], name=\"DestroyBlocker\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, adversary):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = adversary.type_id\n        adversary.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        adversary = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not adversary:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        adversary.set_simulate_physics(False)\n        adversary.set_location(spawn_transform.location + carla.Location(z=-50))\n        return adversary\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], self.other_actors[0], 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n\n\nclass ParkingCrossingPedestrian(BasicScenario):\n\n    \"\"\"\n    Variation of DynamicObjectCrossing but now the blocker is now a vehicle\n    This class holds everything required for a simple object crash\n    without prior vehicle action involving a vehicle and a cyclist/pedestrian,\n    The ego vehicle is passing through a road,\n    And encounters a cyclist/pedestrian crossing the road.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._num_lane_changes = 0\n\n        self._adversary_speed = 2.0  # Speed of the adversary [m/s]\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n        self.timeout = timeout\n\n        self._bp_attributes = {'base_type': 'car', 'generation': 2}\n\n        self._distance = get_value_parameter(config, 'distance', float, 12)\n        self._crossing_angle = get_value_parameter(config, 'crossing_angle', float, 0)\n        if abs(self._crossing_angle) > 90:\n            raise ValueError(\"'crossing_angle' must be between -90 and 90º for the pedestrian to cross the road\")\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        # Time the agent has to react to avoid the collision [s]\n        self._reaction_time = 2.15\n        self._reaction_time += 0.1 * floor(self._crossing_angle / 5)\n\n        super().__init__(\"ParkingCrossingPedestrian\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _get_blocker_transform(self, waypoint):\n        \"\"\"Processes the driving wp to get a waypoint at the side that looks at the road\"\"\"\n        if waypoint.lane_type == carla.LaneType.Sidewalk:\n            new_location = waypoint.transform.location\n        else:\n            vector = waypoint.transform.get_right_vector()\n            if self._direction == 'left':\n                vector *= -1\n\n            offset_location = carla.Location(waypoint.lane_width * vector.x, waypoint.lane_width * vector.y)\n            new_location = waypoint.transform.location + offset_location\n        new_location.z += 0.5\n\n        return carla.Transform(new_location, waypoint.transform.rotation)\n\n    def _get_walker_transform(self, waypoint):\n        \"\"\"Processes the driving wp to get a waypoint at the side that looks at the road\"\"\"\n\n        new_rotation = waypoint.transform.rotation\n        new_rotation.yaw += 270 - self._crossing_angle if self._direction == 'right' else 90 + self._crossing_angle\n\n        if waypoint.lane_type == carla.LaneType.Sidewalk:\n            new_location = waypoint.transform.location\n        else:\n            vector = waypoint.transform.get_right_vector()\n            if self._direction == 'left':\n                vector *= -1\n\n            offset_location = carla.Location(waypoint.lane_width * vector.x, waypoint.lane_width * vector.y)\n            new_location = waypoint.transform.location + offset_location\n        new_location.z += 1.2\n\n        return carla.Transform(new_location, new_rotation)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the adversary transform and spawn it\n        wps = self._reference_waypoint.next(self._distance)\n        if not wps:\n            raise ValueError(\"Couldn't find a location to spawn the adversary\")\n        blocker_wp = wps[0]\n\n        # Get the adversary transform and spawn it\n        self._blocker_transform = self._get_blocker_transform(blocker_wp)\n        self.parking_slots.append(self._blocker_transform.location)\n        blocker = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._blocker_transform, attribute_filter=self._bp_attributes)\n        if blocker is None:\n            raise ValueError(\"Couldn't spawn the adversary\")\n        self.other_actors.append(blocker)\n        blocker.apply_control(carla.VehicleControl(hand_brake=True))\n\n        walker_dist = blocker.bounding_box.extent.x + 0.5\n        wps = blocker_wp.next(walker_dist)\n        if not wps:\n            raise ValueError(\"Couldn't find a location to spawn the adversary\")\n        walker_wp = wps[0]\n\n        # Get the adversary transform and spawn it\n        self._walker_transform = self._get_walker_transform(walker_wp)\n        self.parking_slots.append(self._walker_transform.location)\n\n        walker = CarlaDataProvider.request_new_actor('walker.*', self._walker_transform)\n        if walker is None:\n            raise ValueError(\"Couldn't spawn the adversary\")\n\n        walker.set_location(self._walker_transform.location + carla.Location(z=-200))\n        walker = self._replace_walker(walker)\n \n        self.other_actors.append(walker)\n\n        self._collision_wp = walker_wp\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        then after 60 seconds, a timeout stops the scenario\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"ParkingCrossingPedestrian\")\n        if self.route_mode:\n            total_dist = self._distance + 15\n            sequence.add_child(LeaveSpaceInFront(total_dist))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[1], self._walker_transform, True))\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        # Move the adversary\n        distance = 8.0  # Scenario is meant to be used at a one lane - one direction road\n        duration = distance / self._adversary_speed\n\n        sequence.add_child(KeepVelocity(\n            self.other_actors[1], self._adversary_speed,\n            duration=duration, distance=distance, name=\"AdversaryCrossing\"))\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[1], name=\"DestroyAdversary\"))\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyBlocker\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, walker):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = walker.type_id\n        walker.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        walker = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not walker:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        walker.set_simulate_physics(False)\n        walker.set_location(spawn_transform.location + carla.Location(z=-50))\n        return walker\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], self.other_actors[1], 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/open_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nBasic scenario class using the OpenSCENARIO definition\n\"\"\"\n\nfrom __future__ import print_function\n\nimport itertools\nimport os\nimport py_trees\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeWeather, ChangeRoadFriction, ChangeParameter\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeActorControl, ChangeActorTargetSpeed\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.weather_sim import OSCWeatherBehavior\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.openscenario_parser import OpenScenarioParser, oneshot_with_check, ParameterRef\nfrom srunner.tools.py_trees_port import Decorator\n\n\ndef repeatable_behavior(behaviour, name=None):\n    \"\"\"\n    This behaviour allows a composite with oneshot ancestors to run multiple\n    times, resetting the oneshot variables after each execution\n    \"\"\"\n    if not name:\n        name = behaviour.name\n    clear_descendant_variables = ClearBlackboardVariablesStartingWith(\n        name=\"Clear Descendant Variables of {}\".format(name),\n        variable_name_beginning=name + \">\"\n    )\n    # If it's a sequence, don't double-nest it in a redundant manner\n    if isinstance(behaviour, py_trees.composites.Sequence):\n        behaviour.add_child(clear_descendant_variables)\n        sequence = behaviour\n    else:\n        sequence = py_trees.composites.Sequence(name=\"RepeatableBehaviour of {}\".format(name))\n        sequence.add_children([behaviour, clear_descendant_variables])\n    return sequence\n\n\nclass ClearBlackboardVariablesStartingWith(py_trees.behaviours.Success):\n\n    \"\"\"\n    Clear the values starting with the specified string from the blackboard.\n\n    Args:\n        name (:obj:`str`): name of the behaviour\n        variable_name_beginning (:obj:`str`): beginning of the names of variable to clear\n    \"\"\"\n\n    def __init__(self,\n                 name=\"Clear Blackboard Variable Starting With\",\n                 variable_name_beginning=\"dummy\",\n                 ):\n        super(ClearBlackboardVariablesStartingWith, self).__init__(name)\n        self.variable_name_beginning = variable_name_beginning\n\n    def initialise(self):\n        \"\"\"\n        Delete the variables from the blackboard.\n        \"\"\"\n        blackboard_variables = [key for key, _ in py_trees.blackboard.Blackboard().__dict__.items(\n        ) if key.startswith(self.variable_name_beginning)]\n        for variable in blackboard_variables:\n            delattr(py_trees.blackboard.Blackboard(), variable)\n\n\nclass StoryElementStatusToBlackboard(Decorator):\n\n    \"\"\"\n    Reflect the status of the decorator's child story element to the blackboard.\n\n    Args:\n        child: the child behaviour or subtree\n        story_element_type: the element type [act,scene,maneuver,event,action]\n        element_name: the story element's name attribute\n    \"\"\"\n\n    def __init__(self, child, story_element_type, element_name):\n        super(StoryElementStatusToBlackboard, self).__init__(name=child.name, child=child)\n        self.story_element_type = story_element_type\n        self.element_name = element_name\n        self.blackboard = py_trees.blackboard.Blackboard()\n\n    def initialise(self):\n        \"\"\"\n        Record the elements's start time on the blackboard\n        \"\"\"\n        self.blackboard.set(\n            name=\"({}){}-{}\".format(self.story_element_type.upper(),\n                                    self.element_name, \"START\"),\n            value=GameTime.get_time(),\n            overwrite=True\n        )\n\n    def update(self):\n        \"\"\"\n        Reflect the decorated child's status\n        Returns: the decorated child's status\n        \"\"\"\n        return self.decorated.status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Terminate and mark Blackboard entry with END\n        \"\"\"\n        # Report whether we ended with End or Cancel\n        # If we were ended or cancelled, our state will be INVALID and\n        # We will have an ancestor (a parallel SUCCESS_ON_ALL) with a successful child/children\n        # It's possible we ENDed AND CANCELled if both condition groups were true simultaneously\n        # NOTE 'py_trees.common.Status.INVALID' is the status of a behaviur which was terminated by a parent\n        rules = []\n        if new_status == py_trees.common.Status.INVALID:\n            # We were terminated from above unnaturally\n            # Figure out if were ended or cancelled\n            terminating_ancestor = self.parent\n            while terminating_ancestor.status == py_trees.common.Status.INVALID:\n                terminating_ancestor = terminating_ancestor.parent\n            # We have found an ancestory which was not terminated by a parent\n            # Check what caused it to terminate its children\n            if terminating_ancestor.status == py_trees.common.Status.SUCCESS:\n                successful_children = [\n                    child.name\n                    for child\n                    in terminating_ancestor.children\n                    if child.status == py_trees.common.Status.SUCCESS]\n                if \"StopTrigger\" in successful_children:\n                    rules.append(\"END\")\n\n        # END is the default status unless we have a more detailed one\n        rules = rules or [\"END\"]\n\n        for rule in rules:\n            self.blackboard.set(\n                name=\"({}){}-{}\".format(self.story_element_type.upper(),\n                                        self.element_name, rule),\n                value=GameTime.get_time(),\n                overwrite=True\n            )\n\n\ndef get_xml_path(tree, node):\n    \"\"\"\n    Extract the full path of a node within an XML tree\n\n    Note: Catalogs are pulled from a separate file so the XML tree is split.\n          This means that in order to get the XML path, it must be done in 2 steps.\n          Some places in this python script do that by concatenating the results\n          of 2 get_xml_path calls with another \">\".\n          Example: \"Behavior>AutopilotSequence\" + \">\" + \"StartAutopilot>StartAutopilot>StartAutopilot\"\n    \"\"\"\n\n    path = \"\"\n    parent_map = {c: p for p in tree.iter() for c in p}\n\n    cur_node = node\n    while cur_node != tree:\n        path = \"{}>{}\".format(cur_node.attrib.get('name'), path)\n        cur_node = parent_map[cur_node]\n\n    path = path[:-1]\n    return path\n\n\nclass OpenScenario(BasicScenario):\n\n    \"\"\"\n    Implementation of the OpenSCENARIO scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, config_file, debug_mode=False, criteria_enable=True, timeout=300):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self.config = config\n        self.route = None\n        self.config_file = config_file\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(OpenScenario, self).__init__(self.config.name, ego_vehicles=ego_vehicles, config=config,\n                                           world=world, debug_mode=debug_mode,\n                                           terminate_on_failure=False, criteria_enable=criteria_enable)\n\n    def _initialize_parameters(self):\n        \"\"\"\n        Parse ParameterAction from Init and update global osc parameters.\n        \"\"\"\n        param_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"ParametersInit\")\n        for i, global_action in enumerate(self.config.init.find('Actions').iter('GlobalAction')):\n            maneuver_name = 'InitParams'\n            if global_action.find('ParameterAction') is not None:\n                parameter_action = global_action.find('ParameterAction')\n                parameter_ref = parameter_action.attrib.get('parameterRef')\n                if parameter_action.find('ModifyAction') is not None:\n                    action_rule = parameter_action.find('ModifyAction').find(\"Rule\")\n                    if action_rule.find(\"AddValue\") is not None:\n                        rule, value = '+', action_rule.find(\"AddValue\").attrib.get('value')\n                    else:\n                        rule, value = '*', action_rule.find(\"MultiplyByValue\").attrib.get('value')\n                else:\n                    rule, value = None, parameter_action.find('SetAction').attrib.get('value')\n                parameter_update = ChangeParameter(parameter_ref, value=ParameterRef(value), rule=rule,\n                                                   name=maneuver_name + '_%d' % i)\n                param_behavior.add_child(oneshot_with_check(variable_name=\"InitialParameters\" + '_%d' % i,\n                                                            behaviour=parameter_update))\n\n        return param_behavior\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Initialization of weather and road friction.\n        \"\"\"\n        pass\n\n    def _create_environment_behavior(self):\n        # Set the appropriate weather conditions\n\n        env_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"EnvironmentBehavior\")\n\n        weather_update = ChangeWeather(\n            OpenScenarioParser.get_weather_from_env_action(self.config.init, self.config.catalogs))\n        road_friction = ChangeRoadFriction(\n            OpenScenarioParser.get_friction_from_env_action(self.config.init, self.config.catalogs))\n        env_behavior.add_child(oneshot_with_check(variable_name=\"InitialWeather\", behaviour=weather_update))\n        env_behavior.add_child(oneshot_with_check(variable_name=\"InitRoadFriction\", behaviour=road_friction))\n\n        return env_behavior\n\n    def _create_init_behavior(self):\n\n        init_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"InitBehaviour\")\n\n        for actor in self.config.other_actors + self.config.ego_vehicles:\n            for carla_actor in self.other_actors + self.ego_vehicles:\n                if (carla_actor is not None and 'role_name' in carla_actor.attributes and\n                        carla_actor.attributes['role_name'] == actor.rolename):\n                    actor_init_behavior = py_trees.composites.Sequence(name=\"InitActor{}\".format(actor.rolename))\n\n                    controller_atomic = None\n\n                    for private in self.config.init.iter(\"Private\"):\n                        if private.attrib.get('entityRef', None) == actor.rolename:\n                            for private_action in private.iter(\"PrivateAction\"):\n                                for controller_action in private_action.iter('ControllerAction'):\n                                    module, args = OpenScenarioParser.get_controller(\n                                        controller_action, self.config.catalogs)\n                                    controller_atomic = ChangeActorControl(\n                                        carla_actor, control_py_module=module, args=args,\n                                        scenario_file_path=os.path.dirname(self.config.filename))\n\n                    if controller_atomic is None:\n                        controller_atomic = ChangeActorControl(carla_actor, control_py_module=None, args={})\n\n                    actor_init_behavior.add_child(controller_atomic)\n\n                    if actor.speed > 0:\n                        actor_init_behavior.add_child(ChangeActorTargetSpeed(carla_actor, actor.speed, init_speed=True))\n\n                    init_behavior.add_child(actor_init_behavior)\n                    break\n\n        return init_behavior\n\n    def _create_behavior(self):\n        \"\"\"\n        Basic behavior do nothing, i.e. Idle\n        \"\"\"\n\n        stories_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL,\n                                                        name=\"OSCStories\")\n        joint_actor_list = self.other_actors + self.ego_vehicles + [None]\n\n        for story in self.config.stories:\n            story_name = story.get(\"name\")\n            story_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL,\n                                                          name=story_name)\n            for act in story.iter(\"Act\"):\n\n                act_sequence = py_trees.composites.Sequence(\n                    name=\"Act StartConditions and behaviours\")\n\n                start_conditions = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"StartConditions Group\")\n\n                parallel_behavior = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"Maneuver + EndConditions Group\")\n\n                parallel_sequences = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"Maneuvers\")\n\n                for sequence in act.iter(\"ManeuverGroup\"):\n                    sequence_behavior = py_trees.composites.Sequence(name=sequence.attrib.get('name'))\n                    repetitions = sequence.attrib.get('maximumExecutionCount', 1)\n\n                    for _ in range(int(repetitions)):\n\n                        actor_ids = []\n                        for actor in sequence.iter(\"Actors\"):\n                            for entity in actor.iter(\"EntityRef\"):\n                                entity_name = entity.attrib.get('entityRef', None)\n                                for k, _ in enumerate(joint_actor_list):\n                                    if (joint_actor_list[k] and\n                                            entity_name == joint_actor_list[k].attributes['role_name']):\n                                        actor_ids.append(k)\n                                        break\n\n                        if not actor_ids:\n                            print(\"Warning: Maneuvergroup {} does not use reference actors!\".format(\n                                sequence.attrib.get('name')))\n                            actor_ids.append(len(joint_actor_list) - 1)\n\n                    # Collect catalog reference maneuvers in order to process them at the same time as normal maneuvers\n                        catalog_maneuver_list = []\n                        for catalog_reference in sequence.iter(\"CatalogReference\"):\n                            catalog_maneuver = OpenScenarioParser.get_catalog_entry(self.config.catalogs,\n                                                                                    catalog_reference)\n                            catalog_maneuver_list.append(catalog_maneuver)\n                        all_maneuvers = itertools.chain(iter(catalog_maneuver_list), sequence.iter(\"Maneuver\"))\n                        single_sequence_iteration = py_trees.composites.Parallel(\n                            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=sequence_behavior.name)\n                        for maneuver in all_maneuvers:  # Iterates through both CatalogReferences and Maneuvers\n                            maneuver_parallel = py_trees.composites.Parallel(\n                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL,\n                                name=\"Maneuver \" + maneuver.attrib.get('name'))\n                            for event in maneuver.iter(\"Event\"):\n                                event_sequence = py_trees.composites.Sequence(\n                                    name=\"Event \" + event.attrib.get('name'))\n                                parallel_actions = py_trees.composites.Parallel(\n                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"Actions\")\n                                for child in event.iter():\n                                    if child.tag == \"Action\":\n                                        for actor_id in actor_ids:\n                                            maneuver_behavior = OpenScenarioParser.convert_maneuver_to_atomic(\n                                                child, joint_actor_list[actor_id],\n                                                joint_actor_list, self.config.catalogs)\n                                            maneuver_behavior = StoryElementStatusToBlackboard(\n                                                maneuver_behavior, \"ACTION\", child.attrib.get('name'))\n                                            parallel_actions.add_child(\n                                                oneshot_with_check(variable_name=  # See note in get_xml_path\n                                                                   get_xml_path(story, sequence) + '>' + \\\n                                                                   get_xml_path(maneuver, child) + '>' + \\\n                                                                   str(actor_id),\n                                                                   behaviour=maneuver_behavior))\n\n                                    if child.tag == \"StartTrigger\":\n                                        # There is always one StartConditions block per Event\n                                        parallel_condition_groups = self._create_condition_container(\n                                            child, story, \"Parallel Condition Groups\", sequence, maneuver)\n                                        event_sequence.add_child(\n                                            parallel_condition_groups)\n\n                                parallel_actions = StoryElementStatusToBlackboard(\n                                    parallel_actions, \"EVENT\", event.attrib.get('name'))\n                                event_sequence.add_child(parallel_actions)\n                                maneuver_parallel.add_child(\n                                    oneshot_with_check(variable_name=get_xml_path(story, sequence) + '>' +\n                                                       get_xml_path(maneuver, event),  # See get_xml_path\n                                                       behaviour=event_sequence))\n                            maneuver_parallel = StoryElementStatusToBlackboard(\n                                maneuver_parallel, \"MANEUVER\", maneuver.attrib.get('name'))\n                            single_sequence_iteration.add_child(\n                                oneshot_with_check(variable_name=get_xml_path(story, sequence) + '>' +\n                                                   maneuver.attrib.get('name'),  # See get_xml_path\n                                                   behaviour=maneuver_parallel))\n\n                        # OpenSCENARIO refers to Sequences as Scenes in this instance\n                        single_sequence_iteration = StoryElementStatusToBlackboard(\n                            single_sequence_iteration, \"SCENE\", sequence.attrib.get('name'))\n                        single_sequence_iteration = repeatable_behavior(\n                            single_sequence_iteration, get_xml_path(story, sequence))\n\n                        sequence_behavior.add_child(single_sequence_iteration)\n\n                    if sequence_behavior.children:\n                        parallel_sequences.add_child(\n                            oneshot_with_check(variable_name=get_xml_path(story, sequence),\n                                               behaviour=sequence_behavior))\n\n                if parallel_sequences.children:\n                    parallel_sequences = StoryElementStatusToBlackboard(\n                        parallel_sequences, \"ACT\", act.attrib.get('name'))\n                    parallel_behavior.add_child(parallel_sequences)\n\n                start_triggers = act.find(\"StartTrigger\")\n                if list(start_triggers) is not None:\n                    for start_condition in start_triggers:\n                        parallel_start_criteria = self._create_condition_container(start_condition,\n                                                                                   story,\n                                                                                   \"StartConditions\")\n                        if parallel_start_criteria.children:\n                            start_conditions.add_child(parallel_start_criteria)\n                end_triggers = act.find(\"StopTrigger\")\n                if end_triggers is not None and list(end_triggers) is not None:\n                    for end_condition in end_triggers:\n                        parallel_end_criteria = self._create_condition_container(\n                            end_condition, story, \"EndConditions\", success_on_all=False)\n                        if parallel_end_criteria.children:\n                            parallel_behavior.add_child(parallel_end_criteria)\n\n                if start_conditions.children:\n                    act_sequence.add_child(start_conditions)\n                if parallel_behavior.children:\n                    act_sequence.add_child(parallel_behavior)\n\n                if act_sequence.children:\n                    story_behavior.add_child(act_sequence)\n\n            stories_behavior.add_child(oneshot_with_check(variable_name=get_xml_path(story, story) + '>' +\n                                                          story_name,  # See get_xml_path\n                                                          behaviour=story_behavior))\n\n        # Build behavior tree\n        behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"behavior\")\n\n        init_parameters = self._initialize_parameters()\n        if init_parameters is not None:\n            behavior.add_child(oneshot_with_check(variable_name=\"InitialParameterSettings\", behaviour=init_parameters))\n\n        env_behavior = self._create_environment_behavior()\n        if env_behavior is not None:\n            behavior.add_child(oneshot_with_check(variable_name=\"InitialEnvironmentSettings\", behaviour=env_behavior))\n\n        init_behavior = self._create_init_behavior()\n        if init_behavior is not None:\n            behavior.add_child(oneshot_with_check(variable_name=\"InitialActorSettings\", behaviour=init_behavior))\n\n        behavior.add_child(stories_behavior)\n\n        return behavior\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Sets the osc weather behavior, which will monitor other behaviors, changing the weather\n        \"\"\"\n        return OSCWeatherBehavior()\n\n    def _create_condition_container(self, node, story, name='Conditions Group', sequence=None,\n                                    maneuver=None, success_on_all=True):\n        \"\"\"\n        This is a generic function to handle conditions utilising ConditionGroups\n        Each ConditionGroup is represented as a Sequence of Conditions\n        The ConditionGroups are grouped under a SUCCESS_ON_ONE Parallel\n        \"\"\"\n\n        parallel_condition_groups = py_trees.composites.Parallel(name,\n                                                                 policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        for condition_group in node.iter(\"ConditionGroup\"):\n            if success_on_all:\n                condition_group_sequence = py_trees.composites.Parallel(\n                    name=\"Condition Group\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n            else:\n                condition_group_sequence = py_trees.composites.Parallel(\n                    name=\"Condition Group\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n            for condition in condition_group.iter(\"Condition\"):\n                criterion = OpenScenarioParser.convert_condition_to_atomic(\n                    condition, self.other_actors + self.ego_vehicles)\n                if sequence is not None and maneuver is not None:\n                    xml_path = get_xml_path(story, sequence) + '>' + \\\n                        get_xml_path(maneuver, condition)  # See note in get_xml_path\n                else:\n                    xml_path = get_xml_path(story, condition)\n                criterion = oneshot_with_check(variable_name=xml_path, behaviour=criterion)\n                condition_group_sequence.add_child(criterion)\n\n            if condition_group_sequence.children:\n                parallel_condition_groups.add_child(condition_group_sequence)\n\n        return parallel_condition_groups\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        parallel_criteria = py_trees.composites.Parallel(\"EndConditions (Criteria Group)\",\n                                                         policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        criteria = []\n        for endcondition in self.config.storyboard.iter(\"StopTrigger\"):\n            for condition in endcondition.iter(\"Condition\"):\n                if condition.attrib.get('name').startswith('criteria_'):\n                    criteria.append(condition)\n\n        for condition in criteria:\n            criterion = OpenScenarioParser.convert_condition_to_atomic(condition, self.ego_vehicles)\n            parallel_criteria.add_child(criterion)\n\n        return parallel_criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/opposite_vehicle_taking_priority.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      TrafficLightFreezer,\n                                                                      ConstantVelocityAgentBehavior,\n                                                                      Idle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               WaitEndIntersection)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (get_geometric_linear_intersection,\n                                           generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\n\n\nclass OppositeVehicleJunction(BasicScenario):\n    \"\"\"\n    Scenario in which another vehicle enters the junction a tthe same time as the ego,\n    forcing it to break to avoid a collision\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._source_dist = 30\n        self._sink_dist = 10\n        self._adversary_speed = 60 / 3.6 # m/s\n\n        if 'direction' in config.other_parameters:\n            self._direction = config.other_parameters['direction']['value']\n        else:\n            self._direction = \"right\"\n\n\n        self.timeout = timeout\n\n        self._sync_time = 2.2  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 12.0  # Min distance to the collision location that triggers the adversary [m]\n\n        self._lights = carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2\n\n        super().__init__(\"OppositeVehicleJunction\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the opposite entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Couldn't find a lane for the given direction\")\n\n        # Get the source transform\n        spawn_wp = source_entry_wps[0]\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            spawn_wps = spawn_wp.previous(1.0)\n            if len(spawn_wps) == 0:\n                raise ValueError(\"Failed to find a source location as a waypoint with no previous was detected\")\n            if spawn_wps[0].is_junction:\n                break\n            spawn_wp = spawn_wps[0]\n            source_junction_dist += 1\n        self._spawn_wp = spawn_wp\n\n        source_transform = spawn_wp.transform\n        self._spawn_location = carla.Transform(\n            source_transform.location + carla.Location(z=0.1),\n            source_transform.rotation\n        )\n        self.parking_slots.append(source_transform.location)\n\n        # Spawn the actor and move it below ground\n        opposite_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._spawn_location, attribute_filter={'special_type': 'emergency'})\n        if not opposite_actor:\n            raise Exception(\"Couldn't spawn the actor\")\n        lights = opposite_actor.get_light_state()\n        lights |= self._lights\n        opposite_actor.set_light_state(carla.VehicleLightState(lights))\n        self.other_actors.append(opposite_actor)\n\n        opposite_transform = carla.Transform(\n            source_transform.location - carla.Location(z=500),\n            source_transform.rotation\n        )\n        opposite_actor.set_transform(opposite_transform)\n        opposite_actor.set_simulate_physics(enabled=False)\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 0)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location as a waypoint with no next was detected\")\n        self._sink_wp = sink_wps[0]\n\n        # get the collision location\n        self._collision_location = get_geometric_linear_intersection(\n            starting_wp.transform.location, source_entry_wps[0].transform.location, True)\n        if not self._collision_location:\n            raise ValueError(\"Couldn't find an intersection point\")\n\n        # Get the z component\n        collision_wp = self._map.get_waypoint(self._collision_location)\n        self._collision_location.z = collision_wp.transform.location.z\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass OppositeVehicleRunningRedLight(OppositeVehicleJunction):\n    \"\"\"\n    Signalized junction version, where the other vehicle runs a red light\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        self._tl_dict = {}\n        for tl in tls:\n            if tl == ego_tl:\n                self._tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"OppositeVehicleRunningRedLight\")\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._sync_time, self._collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n\n        end_location = self._sink_wp.transform.location\n        start_location = self._spawn_wp.transform.location\n        time = start_location.distance(end_location) / self._adversary_speed\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ConstantVelocityAgentBehavior(\n            self.other_actors[0], target_location=end_location,\n            target_speed=self._adversary_speed,\n            opt_dict={'ignore_vehicles': True, 'ignore_traffic_lights': True},\n            name=\"AdversaryCrossing\")\n        )\n        main_behavior.add_child(Idle(time))\n\n        sequence.add_child(main_behavior)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n        sequence.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        tls_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        tls_behavior.add_child(TrafficLightFreezer(self._tl_dict))\n        tls_behavior.add_child(sequence)\n\n        root = py_trees.composites.Sequence()\n        if self.route_mode:\n            root.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[self._spawn_wp],\n                remove_exits=[self._sink_wp],\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n        root.add_child(ActorTransformSetter(self.other_actors[0], self._spawn_location))\n        root.add_child(tls_behavior)\n\n        return root\n\n\nclass OppositeVehicleTakingPriority(OppositeVehicleJunction):\n    \"\"\"\n    Non signalized version\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"OppositeVehicleTakingPriority\")\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._sync_time, self._collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n\n        end_location = self._sink_wp.transform.location\n        start_location = self._spawn_wp.transform.location\n        time = start_location.distance(end_location) / self._adversary_speed\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ConstantVelocityAgentBehavior(\n            self.other_actors[0], target_location=end_location,\n            target_speed=self._adversary_speed,\n            opt_dict={'ignore_vehicles': True, 'ignore_traffic_lights': True},\n            name=\"AdversaryCrossing\")\n        )\n        main_behavior.add_child(Idle(time))\n\n        sequence.add_child(main_behavior)\n\n        root = py_trees.composites.Sequence()\n        if self.route_mode:\n            root.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[self._spawn_wp],\n                remove_exits=[self._sink_wp],\n                stop_entries=True,\n                extend_road_exit=0\n            ))\n\n        root.add_child(ActorTransformSetter(self.other_actors[0], self._spawn_location))\n        root.add_child(sequence)\n        root.add_child(ActorDestroy(self.other_actors[0]))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        return root\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/other_leading_vehicle.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nOther Leading Vehicle scenario:\n\nThe scenario realizes a common driving behavior, in which the\nuser-controlled ego vehicle follows a leading car driving down\na given road. At some point the leading car has to decelerate.\nThe ego vehicle has to react accordingly by changing lane to avoid a\ncollision and follow the leading car in other lane. The scenario ends\neither via a timeout, or if the ego vehicle drives some distance.\n\"\"\"\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      WaypointFollower,\n                                                                      ActorDestroy)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass OtherLeadingVehicle(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple \"Other Leading Vehicle\"\n    scenario involving a user controlled vehicle and two other actors.\n    Traffic Scenario 05\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._first_vehicle_location = 35\n        self._second_vehicle_location = self._first_vehicle_location + 1\n        self._ego_vehicle_drive_distance = self._first_vehicle_location * 4\n        self._first_vehicle_speed = 55 / 3.6\n        self._second_vehicle_speed = 45 / 3.6\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._other_actor_max_brake = 1.0\n        self._first_actor_transform = None\n        self._second_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(OtherLeadingVehicle, self).__init__(\"VehicleDeceleratingInMultiLaneSetUp\",\n                                                  ego_vehicles,\n                                                  config,\n                                                  world,\n                                                  debug_mode,\n                                                  criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        first_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location)\n        second_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_vehicle_location)\n        second_vehicle_waypoint = second_vehicle_waypoint.get_left_lane()\n\n        first_vehicle_transform = carla.Transform(first_vehicle_waypoint.transform.location,\n                                                  first_vehicle_waypoint.transform.rotation)\n        second_vehicle_transform = carla.Transform(second_vehicle_waypoint.transform.location,\n                                                   second_vehicle_waypoint.transform.rotation)\n\n        first_vehicle = CarlaDataProvider.request_new_actor('vehicle.nissan.patrol', first_vehicle_transform)\n        second_vehicle = CarlaDataProvider.request_new_actor('vehicle.audi.tt', second_vehicle_transform)\n\n        self.other_actors.append(first_vehicle)\n        self.other_actors.append(second_vehicle)\n\n        self._first_actor_transform = first_vehicle_transform\n        self._second_actor_transform = second_vehicle_transform\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"other leading vehicle\" scenario. After\n        invoking this scenario, the user controlled vehicle has to drive towards the\n        moving other actors, then make the leading actor to decelerate when user controlled\n        vehicle is at some close distance. Finally, the user-controlled vehicle has to change\n        lane to avoid collision and follow other leading actor in other lane to end the scenario.\n        If this does not happen within 90 seconds, a timeout stops the scenario or the ego vehicle\n        drives certain distance and stops the scenario.\n        \"\"\"\n        # start condition\n        driving_in_same_direction = py_trees.composites.Parallel(\"All actors driving in same direction\",\n                                                                 policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        leading_actor_sequence_behavior = py_trees.composites.Sequence(\"Decelerating actor sequence behavior\")\n\n        # both actors moving in same direction\n        keep_velocity = py_trees.composites.Parallel(\"Trigger condition for deceleration\",\n                                                     policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        keep_velocity.add_child(WaypointFollower(self.other_actors[0], self._first_vehicle_speed, avoid_collision=True))\n        keep_velocity.add_child(InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], 55))\n\n        # Decelerating actor sequence behavior\n        decelerate = self._first_vehicle_speed / 3.2\n        leading_actor_sequence_behavior.add_child(keep_velocity)\n        leading_actor_sequence_behavior.add_child(WaypointFollower(self.other_actors[0], decelerate,\n                                                                   avoid_collision=True))\n        # end condition\n        ego_drive_distance = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_drive_distance)\n\n        # Build behavior tree\n        sequence = py_trees.composites.Sequence(\"Scenario behavior\")\n        parallel_root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        parallel_root.add_child(ego_drive_distance)\n        parallel_root.add_child(driving_in_same_direction)\n        driving_in_same_direction.add_child(leading_actor_sequence_behavior)\n        driving_in_same_direction.add_child(WaypointFollower(self.other_actors[1], self._second_vehicle_speed,\n                                                             avoid_collision=True))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform))\n        sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform))\n        sequence.add_child(parallel_root)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n        sequence.add_child(ActorDestroy(self.other_actors[1]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/parking_cut_in.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nParking cut in scenario synchronizes a vehicle that is parked at a side lane\nto cut in in front of the ego vehicle, forcing it to break\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      BasicAgentBehavior)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import LeaveSpaceInFront, ChangeRoadBehavior\n\n\nclass ParkingCutIn(BasicScenario):\n\n    \"\"\"\n    Parking cut in scenario synchronizes a vehicle that is parked at a side lane\n    to cut in in front of the ego vehicle, forcing it to break\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n\n        self._cut_in_distance = 35\n        self._blocker_distance = 28\n\n        self._adversary_speed = 13.0  # Speed of the adversary [m/s]\n        self._reaction_time = 2.35  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 10.0  # Min distance to the collision location that triggers the adversary [m]\n        self._end_distance = 30\n        self._extra_space = 20\n\n        self._bp_attributes = {'base_type': 'car', 'generation': 2, 'special_type': ''}\n\n        self.timeout = timeout\n\n        if 'direction' in config.other_parameters:\n            self._direction = config.other_parameters['direction']['value']\n        else:\n            self._direction = \"right\"\n\n        super().__init__(\"ParkingCutIn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn the blocker vehicle\n        blocker_wps = self._reference_waypoint.next(self._blocker_distance)\n        if not blocker_wps:\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        self._blocker_wp = blocker_wps[0]\n\n        if self._direction == 'left':\n            parking_wp = self._blocker_wp.get_left_lane()\n        else:\n            parking_wp = self._blocker_wp.get_right_lane()\n\n        self.parking_slots.append(parking_wp.transform.location)\n\n        self._blocker_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', parking_wp.transform, 'scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2})\n        if not self._blocker_actor:\n            raise ValueError(\"Couldn't spawn the parked actor\")\n        self._blocker_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(self._blocker_actor)\n\n        side_location = self._get_displaced_location(self._blocker_actor, parking_wp)\n        self._blocker_actor.set_location(side_location)\n\n        collision_wps = self._reference_waypoint.next(self._cut_in_distance)\n        if not collision_wps:\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        self._collision_wp = collision_wps[0]\n\n        # Get the parking direction\n        if self._direction == 'left':\n            parking_wp = self._collision_wp.get_left_lane()\n        else:\n            parking_wp = self._collision_wp.get_right_lane()\n\n        self.parking_slots.append(parking_wp.transform.location)\n\n        self._parked_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', parking_wp.transform, 'scenario', attribute_filter=self._bp_attributes)\n        if not self._parked_actor:\n            raise ValueError(\"Couldn't spawn the parked actor\")\n        self.other_actors.append(self._parked_actor)\n\n        side_location = self._get_displaced_location(self._parked_actor, parking_wp)\n        self._parked_actor.set_location(side_location)\n\n    def _get_displaced_location(self, actor, wp):\n        \"\"\"\n        Calculates the location such that the actor is at the sidemost part of the lane\n        \"\"\"\n        # Move the actor to the edge of the lane near the sidewalk\n        displacement = (wp.lane_width - actor.bounding_box.extent.y) / 4\n        displacement_vector = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            displacement_vector *= -1\n\n        new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x,\n                                                              y=displacement*displacement_vector.y,\n                                                              z=displacement*displacement_vector.z)\n        new_location.z += 0.05  # Just in case, avoid collisions with the ground\n        return new_location\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, a parked vehicle will wait for the ego to\n        be close-by, merging into its lane, forcing it to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"ParkingCutIn\")\n        if self.route_mode:\n            sequence.add_child(LeaveSpaceInFront(self._cut_in_distance + 10))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        # Move the adversary\n        cut_in = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"Cut in behavior\")\n        cut_in.add_child(BasicAgentBehavior(self.other_actors[1], opt_dict={'ignore_traffic_lights': True}))\n        cut_in.add_child(DriveDistance(self.other_actors[1], self._end_distance))\n        sequence.add_child(cut_in)\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(ActorDestroy(self.other_actors[1], name=\"DestroyBlocker\"))\n\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=0))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/parking_exit.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario in which the ego is parked between two vehicles and has to maneuver to start the route.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      ActorTransformSetter,\n                                                                      WaitForever,\n                                                                      ChangeAutoPilot,\n                                                                      ScenarioTimeout)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import ChangeRoadBehavior\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass ParkingExit(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which the ego would be teleported to the parking lane.\n    Once the scenario is triggered, the OutsideRouteLanesTest will be deactivated since the ego is out of the driving lane.\n    Then blocking vehicles will be generated in front of and behind the parking point.\n    The ego need to exit from the parking lane and then merge into the driving lane.\n    After the ego is {end_distance} meters away from the parking point, the OutsideRouteLanesTest will be activated and the scenario ends.\n\n    Note 1: For route mode, this shall be the first scenario of the route. The trigger point shall be the first point of the route waypoints.\n\n    Note 2: Make sure there are enough space for spawning blocking vehicles.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(\n            CarlaDataProvider.get_traffic_manager_port())\n        self.timeout = timeout\n\n        self._bp_attributes = {'base_type': 'car', 'generation': 2}\n        self._side_end_distance = 50\n\n        self._front_vehicle_distance = get_value_parameter(config, 'front_vehicle_distance', float, 20)\n        self._behind_vehicle_distance = get_value_parameter(config, 'behind_vehicle_distance', float, 10)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._flow_distance = get_value_parameter(config, 'flow_distance', float, 25)\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        self._end_distance = self._front_vehicle_distance + 15\n\n        # Get parking_waypoint based on trigger_point\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(self._trigger_location)\n        if self._direction == \"left\":\n            self._parking_waypoint = self._reference_waypoint.get_left_lane()\n        else:\n            self._parking_waypoint = self._reference_waypoint.get_right_lane()\n\n        if self._parking_waypoint is None:\n            raise Exception(\n                \"Couldn't find parking point on the {} side\".format(self._direction))\n\n        super().__init__(\"ParkingExit\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n\n        # Spawn the actor in front of the ego\n        front_points = self._parking_waypoint.next(\n            self._front_vehicle_distance)\n        if not front_points:\n            raise ValueError(\"Couldn't find viable position for the vehicle in front of the parking point\")\n\n        self.parking_slots.append(front_points[0].transform.location)\n\n        actor_front = CarlaDataProvider.request_new_actor(\n            'vehicle.*', front_points[0].transform, rolename='scenario no lights', attribute_filter=self._bp_attributes)\n        if actor_front is None:\n            raise ValueError(\"Couldn't spawn the vehicle in front of the parking point\")\n        actor_front.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(actor_front)\n\n        # And move it to the side\n        side_location = self._get_displaced_location(actor_front, front_points[0])\n        actor_front.set_location(side_location)\n\n        # Spawn the actor behind the ego\n        behind_points = self._parking_waypoint.previous(\n            self._behind_vehicle_distance)\n        if not behind_points:\n            raise ValueError(\"Couldn't find viable position for the vehicle behind the parking point\")\n\n        self.parking_slots.append(behind_points[0].transform.location)\n\n        actor_behind = CarlaDataProvider.request_new_actor(\n            'vehicle.*', behind_points[0].transform, rolename='scenario no lights', attribute_filter=self._bp_attributes)\n        if actor_behind is None:\n            actor_front.destroy()\n            raise ValueError(\"Couldn't spawn the vehicle behind the parking point\")\n        actor_behind.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(actor_behind)\n\n        # And move it to the side\n        side_location = self._get_displaced_location(actor_behind, behind_points[0])\n        actor_behind.set_location(side_location)\n\n        # Move the ego to its side position\n        self._ego_location = self._get_displaced_location(self.ego_vehicles[0], self._parking_waypoint)\n        self.parking_slots.append(self._ego_location)\n        self.ego_vehicles[0].set_location(self._ego_location)\n\n        # Spawn the actor at the side of the ego\n        actor_side = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._reference_waypoint.transform, attribute_filter=self._bp_attributes)\n        if actor_side is None:\n            raise ValueError(\"Couldn't spawn the vehicle at the side of the parking point\")\n        self.other_actors.append(actor_side)\n        self._tm.update_vehicle_lights(actor_side, True)\n\n        self._end_side_transform = self.ego_vehicles[0].get_transform()\n        self._end_side_transform.location.z -= 500\n\n    def _get_displaced_location(self, actor, wp):\n        \"\"\"\n        Calculates the transforming such that the actor is at the sidemost part of the lane\n        \"\"\"\n        # Move the actor to the edge of the lane near the sidewalk\n        displacement = (wp.lane_width - actor.bounding_box.extent.y) / 4\n        displacement_vector = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            displacement_vector *= -1\n\n        new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x,\n                                                              y=displacement*displacement_vector.y,\n                                                              z=displacement*displacement_vector.z)\n        new_location.z += 0.05  # Just in case, avoid collisions with the ground\n        return new_location\n\n    def _create_behavior(self):\n        \"\"\"\n        Deactivate OutsideRouteLanesTest, then move ego to the parking point,\n        generate blocking vehicles in front of and behind the ego.\n        After ego drives away, activate OutsideRouteLanesTest, end scenario.\n        \"\"\"\n\n        sequence = py_trees.composites.Sequence(name=\"ParkingExit\")\n        sequence.add_child(ChangeRoadBehavior(spawn_dist=self._flow_distance))\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        side_actor_behavior = py_trees.composites.Sequence()\n        side_actor_behavior.add_child(ChangeAutoPilot(self.other_actors[2], True))\n        side_actor_behavior.add_child(DriveDistance(self.other_actors[2], self._side_end_distance))\n        side_actor_behavior.add_child(ActorTransformSetter(self.other_actors[2], self._end_side_transform, False))\n        side_actor_behavior.add_child(WaitForever())\n        root.add_child(side_actor_behavior)\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        for actor in self.other_actors:\n            sequence.add_child(ActorDestroy(actor))\n        sequence.add_child(ChangeRoadBehavior(spawn_dist=15))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/pedestrian_crossing.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nPedestrians crossing through the middle of the lane.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      KeepVelocity,\n                                                                      WaitForever,\n                                                                      Idle,\n                                                                      ActorTransformSetter,\n                                                                      MovePedestrianWithEgo)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\nclass PedestrianCrossing(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a group of natual pedestrians crossing the road.\n    The ego vehicle is passing through a road,\n    And encounters a group of pedestrians crossing the road.\n\n    This is a single ego vehicle scenario.\n\n    Notice that the initial pedestrian will walk from the start of the junction ahead to end_walker_flow_1.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._adversary_speed = 1.3  # Speed of the adversary [m/s]\n        self._reaction_time = 3.5  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 12.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n        self.timeout = timeout\n\n        self._walker_data = [\n            {'x': 0.4, 'y': 1.5, 'z': 1.2, 'yaw': 270},\n            {'x': 1, 'y': 2.5, 'z': 1.2, 'yaw': 270},\n            {'x': 1.6, 'y': 0.5, 'z': 1.2, 'yaw': 270}\n        ]\n\n        for walker_data in self._walker_data:\n            walker_data['idle_time'] = self._rng.uniform(0, 1.5)\n            walker_data['speed'] = self._rng.uniform(1.3, 2.0)\n\n        super().__init__(\"PedestrianCrossing\",\n                          ego_vehicles,\n                          config,\n                          world,\n                          debug_mode,\n                          criteria_enable=criteria_enable)\n\n    def _get_walker_transform(self, wp, displacement):\n        disp_x = displacement['x']\n        disp_y = displacement['y']\n        disp_z = displacement['z']\n        disp_yaw = displacement['yaw']\n\n        # Displace it to the crosswalk. Move forwards towards the crosswalk\n        start_vec = wp.transform.get_forward_vector()\n        start_right_vec = wp.transform.get_right_vector()\n\n        spawn_loc = wp.transform.location + carla.Location(\n            disp_x * start_vec.x + disp_y * start_right_vec.x,\n            disp_x * start_vec.y + disp_y * start_right_vec.y,\n            disp_x * start_vec.z + disp_y * start_right_vec.z + disp_z\n        )\n\n        spawn_rotation = wp.transform.rotation\n        spawn_rotation.yaw += disp_yaw\n        return carla.Transform(spawn_loc, spawn_rotation)\n\n    def _initialize_actors(self, config):\n\n        # Get the start point of the initial pedestrian\n        collision_wp = self._reference_waypoint\n        while True:\n            next_wps = collision_wp.next(1)\n            if not next_wps:\n                raise ValueError(\"Couldn't find a waypoint to spawn the pedestrians\")\n            if next_wps[0].is_junction:\n                break\n            collision_wp = next_wps[0]\n\n        self._collision_wp = collision_wp\n\n        # Get the crosswalk start point\n        start_wp = collision_wp\n        while start_wp.lane_type != carla.LaneType.Sidewalk:\n            wp = start_wp.get_right_lane()\n            if wp is None:\n                raise ValueError(\"Couldn't find a waypoint to start the flow\")\n            start_wp = wp\n\n        # Spawn the walkers\n        for i, walker_data in enumerate(self._walker_data):\n            spawn_transform = self._get_walker_transform(start_wp, walker_data)\n            walker = CarlaDataProvider.request_new_actor('walker.*', spawn_transform)\n            if walker is None:\n                for walker in self.other_actors:\n                    walker.destroy()\n                raise ValueError(\"Failed to spawn an adversary\")\n\n            walker.set_location(spawn_transform.location + carla.Location(z=-200))\n            walker = self._replace_walker(walker)\n\n            self.other_actors.append(walker)\n\n            collision_dist = spawn_transform.location.distance(self._collision_wp.transform.location)\n\n            # Distance and duration to cross the whole road + a bit more (supposing symetry in both directions)\n            move_dist = 2.3 * collision_dist\n            walker_data['transform'] = spawn_transform\n            walker_data['distance'] = move_dist\n            walker_data['duration'] = move_dist / walker_data['speed']\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        then after 60 seconds, a timeout stops the scenario\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"PedestrianCrossing\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=[],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n\n        for walker_actor, walker_data in zip(self.other_actors, self._walker_data):\n            sequence.add_child(ActorTransformSetter(walker_actor, walker_data['transform'], True))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        # Move the walkers\n        main_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"WalkerMovement\")\n\n        for walker_actor, walker_data in zip(self.other_actors, self._walker_data):\n            walker_sequence = py_trees.composites.Sequence(name=\"WalkerCrossing\")\n            walker_sequence.add_child(Idle(walker_data['idle_time']))\n            walker_sequence.add_child(KeepVelocity(\n                walker_actor, walker_data['speed'], False, walker_data['duration'], walker_data['distance']))\n            walker_sequence.add_child(ActorDestroy(walker_actor, name=\"DestroyAdversary\"))\n            walker_sequence.add_child(WaitForever())\n\n            main_behavior.add_child(walker_sequence)\n\n        main_behavior.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n        sequence.add_child(main_behavior)\n\n        # Remove everything\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, walker):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = walker.type_id\n        walker.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        walker = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not walker:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        walker.set_simulate_physics(False)\n        walker.set_location(spawn_transform.location + carla.Location(z=-50))\n        return walker\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        for i, walker in enumerate(reversed(self.other_actors)):\n            parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], walker, 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/route_obstacles.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      SwitchWrongDirectionTest,\n                                                                      BasicAgentBehavior,\n                                                                      ScenarioTimeout,\n                                                                      Idle, WaitForever,\n                                                                      HandBrakeVehicle,\n                                                                      OppositeActorFlow)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (DriveDistance,\n                                                                               InTriggerDistanceToLocation,\n                                                                               InTriggerDistanceToVehicle,\n                                                                               WaitUntilInFront,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import LeaveSpaceInFront, SetMaxSpeed, ChangeOppositeBehavior, ChangeRoadBehavior\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass Accident(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which there is an accident\n    in front of the ego, forcing it to lane change. A police vehicle is located before\n    two other cars that have been in an accident.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n        \n        self._first_distance = 10\n        self._second_distance = 6\n\n        self._trigger_distance = 50\n        self._end_distance = 50\n        self._wait_duration = 5\n        self._offset = 0.6\n\n        self._lights = carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2 | carla.VehicleLightState.Position\n\n        self._distance = get_value_parameter(config, 'distance', float, 120)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        super().__init__(\n            \"Accident\", ego_vehicles, config, world, randomize, debug_mode, criteria_enable=criteria_enable)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_side_prop(self, wp):\n        # Spawn the accident indication signal\n        prop_wp = wp\n        while True:\n            if self._direction == \"right\":\n                wp = prop_wp.get_right_lane()\n            else:\n                wp = prop_wp.get_left_lane()\n            if wp is None or wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n                break\n            prop_wp = wp\n\n        displacement = 0.3 * prop_wp.lane_width\n        r_vec = prop_wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.2)\n        spawn_transform.rotation.yaw += 90\n        signal_prop = CarlaDataProvider.request_new_actor('static.prop.warningaccident', spawn_transform)\n        if not signal_prop:\n            raise ValueError(\"Couldn't spawn the indication prop asset\")\n        signal_prop.set_simulate_physics(False)\n        self.other_actors.append(signal_prop)\n\n    def _spawn_obstacle(self, wp, blueprint, accident_actor=False):\n        \"\"\"\n        Spawns the obstacle actor by displacing its position to the right\n        \"\"\"\n        displacement = self._offset * wp.lane_width / 2\n        r_vec = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1)\n        if accident_actor:\n            actor = CarlaDataProvider.request_new_actor(\n                blueprint, spawn_transform, rolename='scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2})\n        else:\n            actor = CarlaDataProvider.request_new_actor(\n                blueprint, spawn_transform, rolename='scenario')\n        if not actor:\n            raise ValueError(\"Couldn't spawn an obstacle actor\")\n\n        return actor\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        starting_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Spawn the accident indication signal\n        self._spawn_side_prop(starting_wp)\n\n        # Spawn the police vehicle\n        self._accident_wp = self._move_waypoint_forward(starting_wp, self._distance)\n        police_car = self._spawn_obstacle(self._accident_wp, 'vehicle.dodge.charger_police_2020')\n\n        # Set its initial conditions\n        lights = police_car.get_light_state()\n        lights |= self._lights\n        police_car.set_light_state(carla.VehicleLightState(lights))\n        police_car.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(police_car)\n\n        # Create the first vehicle that has been in the accident\n        self._first_vehicle_wp = self._move_waypoint_forward(self._accident_wp, self._first_distance)\n        first_actor = self._spawn_obstacle(self._first_vehicle_wp, 'vehicle.*', True)\n\n        # Set its initial conditions\n        first_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(first_actor)\n\n        # Create the second vehicle that has been in the accident\n        second_vehicle_wp = self._move_waypoint_forward(self._first_vehicle_wp, self._second_distance)\n        second_actor = self._spawn_obstacle(second_vehicle_wp, 'vehicle.*', True)\n\n        self._accident_wp = second_vehicle_wp\n        self._end_wp = self._move_waypoint_forward(second_vehicle_wp, self._end_distance)\n\n        # Set its initial conditions\n        second_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(second_actor)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the reach a specific point but an accident is in the middle of the road,\n        blocking its route and forcing it to lane change.\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"Accident\")\n        if self.route_mode:\n            total_dist = self._distance + self._first_distance + self._second_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._first_vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass AccidentTwoWays(Accident):\n    \"\"\"\n    Variation of the Accident scenario but the ego now has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180):\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the whole predetermined distance. Adapt the opposite flow to\n        let the ego invade the opposite lane.\n        \"\"\"\n        reference_wp = self._accident_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"AccidentTwoWays\")\n        if self.route_mode:\n            total_dist = self._distance + self._first_distance + self._second_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._first_vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n        behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\nclass ParkedObstacle(BasicScenario):\n    \"\"\"\n    Scenarios in which a parked vehicle is incorrectly parked,\n    forcing the ego to lane change out of the route's lane\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_distance = 50\n        self._end_distance = 50\n        self._wait_duration = 5\n        self._offset = 0.7\n\n        self._lights = carla.VehicleLightState.RightBlinker | carla.VehicleLightState.LeftBlinker | carla.VehicleLightState.Position\n\n        self._distance = get_value_parameter(config, 'distance', float, 120)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        super().__init__(\n            \"ParkedObstacle\", ego_vehicles, config, world, randomize, debug_mode, criteria_enable=criteria_enable)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_side_prop(self, wp):\n        # Spawn the accident indication signal\n        prop_wp = wp\n        while True:\n            if self._direction == \"right\":\n                wp = prop_wp.get_right_lane()\n            else:\n                wp = prop_wp.get_left_lane()\n            if wp is None or wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n                break\n            prop_wp = wp\n\n        displacement = 0.3 * prop_wp.lane_width\n        r_vec = prop_wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.2)\n        spawn_transform.rotation.yaw += 90\n        signal_prop = CarlaDataProvider.request_new_actor('static.prop.warningaccident', spawn_transform)\n        if not signal_prop:\n            raise ValueError(\"Couldn't spawn the indication prop asset\")\n        signal_prop.set_simulate_physics(False)\n        self.other_actors.append(signal_prop)\n\n    def _spawn_obstacle(self, wp, blueprint):\n        \"\"\"\n        Spawns the obstacle actor by displacing its position to the right\n        \"\"\"\n        displacement = self._offset * wp.lane_width / 2\n        r_vec = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1)\n        actor = CarlaDataProvider.request_new_actor(\n            blueprint, spawn_transform, rolename='scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2})\n        if not actor:\n            raise ValueError(\"Couldn't spawn an obstacle actor\")\n\n        return actor\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        self._starting_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Create the side prop\n        self._spawn_side_prop(self._starting_wp)\n\n        # Create the first vehicle that has been in the accident\n        self._vehicle_wp = self._move_waypoint_forward(self._starting_wp, self._distance)\n        parked_actor = self._spawn_obstacle(self._vehicle_wp, 'vehicle.*')\n\n        lights = parked_actor.get_light_state()\n        lights |= self._lights\n        parked_actor.set_light_state(carla.VehicleLightState(lights))\n        parked_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(parked_actor)\n\n        self._end_wp = self._move_waypoint_forward(self._vehicle_wp, self._end_distance)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the whole predetermined distance.\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"ParkedObstacle\")\n        if self.route_mode:\n            total_dist = self._distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass ParkedObstacleTwoWays(ParkedObstacle):\n    \"\"\"\n    Variation of the ParkedObstacle scenario but the ego now has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180):\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the whole predetermined distance. Adapt the opposite flow to\n        let the ego invade the opposite lane.\n        \"\"\"\n        reference_wp = self._vehicle_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"ParkedObstacleTwoWays\")\n        if self.route_mode:\n            total_dist = self._distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n        behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n\nclass HazardAtSideLane(BasicScenario):\n    \"\"\"\n    Added the dangerous scene of ego vehicles driving on roads without sidewalks,\n    with three bicycles encroaching on some roads in front.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._obstacle_distance = 9\n        self._trigger_distance = 50\n        self._end_distance = 50\n        self._extra_space = 30\n\n        self._offset = 0.55\n        self._wait_duration = 5\n\n        self._target_locs = []\n\n        self._bicycle_bps = [\"vehicle.bh.crossbike\", \"vehicle.diamondback.century\", \"vehicle.gazelle.omafiets\"]\n\n        self._distance = get_value_parameter(config, 'distance', float, 100)\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._bicycle_speed = get_value_parameter(config, 'bicycle_speed', float, 10)\n        self._bicycle_drive_distance = get_value_parameter(config, 'bicycle_drive_distance', float, 50)\n        self._scenario_timeout = 240\n\n        super().__init__(\"HazardAtSideLane\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         randomize,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_obstacle(self, wp, blueprint):\n        \"\"\"\n        Spawns the obstacle actor by displacing its position to the right\n        \"\"\"\n        displacement = self._offset * wp.lane_width / 2\n        r_vec = wp.transform.get_right_vector()\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1)\n        actor = CarlaDataProvider.request_new_actor(blueprint, spawn_transform)\n        if not actor:\n            raise ValueError(\"Couldn't spawn an obstacle actor\")\n\n        return actor\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        rng = CarlaDataProvider.get_random_seed()\n        self._starting_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Spawn the first bicycle\n        first_wp = self._move_waypoint_forward(self._starting_wp, self._distance)\n        bicycle_1 = self._spawn_obstacle(first_wp, rng.choice(self._bicycle_bps))\n\n        wps = first_wp.next(self._bicycle_drive_distance)\n        if not wps:\n            raise ValueError(\"Couldn't find an end location for the bicycles\")\n        self._target_locs.append(wps[0].transform.location)\n\n        # Set its initial conditions\n        bicycle_1.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(bicycle_1)\n\n        # Spawn the second bicycle\n        second_wp = self._move_waypoint_forward(first_wp, self._obstacle_distance)\n        bicycle_2 = self._spawn_obstacle(second_wp, rng.choice(self._bicycle_bps))\n\n        wps = second_wp.next(self._bicycle_drive_distance)\n        if not wps:\n            raise ValueError(\"Couldn't find an end location for the bicycles\")\n        self._target_locs.append(wps[0].transform.location)\n\n        # Set its initial conditions\n        bicycle_2.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(bicycle_2)\n\n    def _create_behavior(self):\n        \"\"\"\n        Activate the bicycles and wait for the ego to be close-by before changing the side traffic.\n        End condition is based on the ego behind in front of the bicycles, or timeout based.\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"HazardAtSideLane\")\n        if self.route_mode:\n            total_dist = self._distance + self._obstacle_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n            root.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        # End condition\n        end_condition = py_trees.composites.Sequence(name=\"End Condition\")\n        end_condition.add_child(WaitUntilInFront(self.ego_vehicles[0], self.other_actors[-1], check_distance=False))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        main_behavior.add_child(end_condition)\n\n        # Bicycle movement. Move them for a set distance, then stop\n        offset = self._offset * self._starting_wp.lane_width / 2\n        opt_dict = {'offset': offset}\n        for actor, target_loc in zip(self.other_actors, self._target_locs):\n            bicycle = py_trees.composites.Sequence(name=\"Bicycle behavior\")\n            bicycle.add_child(BasicAgentBehavior(actor, target_loc, target_speed=self._bicycle_speed, opt_dict=opt_dict))\n            bicycle.add_child(HandBrakeVehicle(actor, 1))  # In case of collisions\n            bicycle.add_child(WaitForever())  # Don't make the bicycle stop the parallel behavior\n            main_behavior.add_child(bicycle)\n\n        behavior = py_trees.composites.Sequence(name=\"Side lane behavior\")\n        behavior.add_child(InTriggerDistanceToVehicle(\n            self.ego_vehicles[0], self.other_actors[0], self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        main_behavior.add_child(behavior)\n\n        root.add_child(main_behavior)\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n            root.add_child(ChangeRoadBehavior(extra_space=0))\n\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass HazardAtSideLaneTwoWays(HazardAtSideLane):\n    \"\"\"\n    Variation of the HazardAtSideLane scenario but the ego now has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180):\n\n        self._opposite_frequency = get_value_parameter(config, 'frequency', float, 100)\n\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Activate the bicycles and wait for the ego to be close-by before changing the opposite traffic.\n        End condition is based on the ego behind in front of the bicycles, or timeout based.\n        \"\"\"\n\n        root = py_trees.composites.Sequence(name=\"HazardAtSideLaneTwoWays\")\n        if self.route_mode:\n            total_dist = self._distance + self._obstacle_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n            root.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        # End condition\n        end_condition = py_trees.composites.Sequence(name=\"End Condition\")\n        end_condition.add_child(WaitUntilInFront(self.ego_vehicles[0], self.other_actors[-1], check_distance=False))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        main_behavior.add_child(end_condition)\n\n        # Bicycle movement. Move them for a set distance, then stop\n        offset = self._offset * self._starting_wp.lane_width / 2\n        opt_dict = {'offset': offset}\n        for actor, target_loc in zip(self.other_actors, self._target_locs):\n            bicycle = py_trees.composites.Sequence(name=\"Bicycle behavior\")\n            bicycle.add_child(BasicAgentBehavior(actor, target_loc, target_speed=self._bicycle_speed, opt_dict=opt_dict))\n            bicycle.add_child(HandBrakeVehicle(actor, 1))  # In case of collisions\n            bicycle.add_child(WaitForever())  # Don't make the bicycle stop the parallel behavior\n            main_behavior.add_child(bicycle)\n\n        behavior = py_trees.composites.Sequence(name=\"Side lane behavior\")\n        behavior.add_child(InTriggerDistanceToVehicle(\n            self.ego_vehicles[0], self.other_actors[0], self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(spawn_dist=self._opposite_frequency))\n        behavior.add_child(WaitForever())\n\n        main_behavior.add_child(behavior)\n\n        root.add_child(main_behavior)\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(False))\n            root.add_child(ChangeOppositeBehavior(spawn_dist=40))\n            root.add_child(ChangeRoadBehavior(extra_space=0))\n\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/route_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides Challenge routes as standalone scenarios\n\"\"\"\n\nfrom __future__ import print_function\n\nimport glob\nimport os\nimport sys\nimport importlib\nimport inspect\nimport traceback\nimport py_trees\n\nfrom numpy import random\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ScenarioTriggerer, Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitForBlackboardVariable\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest,\n                                                                     InRouteTest,\n                                                                     RouteCompletionTest,\n                                                                     OutsideRouteLanesTest,\n                                                                     RunningRedLightTest,\n                                                                     RunningStopTest,\n                                                                     ActorBlockedTest,\n                                                                     MinimumSpeedRouteTest)\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.scenarios.background_activity import BackgroundBehavior\nfrom srunner.scenariomanager.weather_sim import RouteWeatherBehavior\nfrom srunner.scenariomanager.lights_sim import RouteLightsBehavior\nfrom srunner.scenariomanager.timer import RouteTimeoutBehavior\n\nfrom srunner.tools.route_parser import RouteParser, DIST_THRESHOLD\nfrom srunner.tools.route_manipulation import interpolate_trajectory\n\n\nSECONDS_GIVEN_PER_METERS = 0.4\n\n\nclass RouteScenario(BasicScenario):\n\n    \"\"\"\n    Implementation of a RouteScenario, i.e. a scenario that consists of driving along a pre-defined route,\n    along which several smaller scenarios are triggered\n    \"\"\"\n\n    def __init__(self, world, config, debug_mode=False, criteria_enable=True, timeout=300):\n        \"\"\"\n        Setup all relevant parameters and create scenarios along route\n        \"\"\"\n\n        self.config = config\n        self.route = self._get_route(config)\n        sampled_scenario_definitions = self._filter_scenarios(config.scenario_configs)\n\n        ego_vehicle = self._spawn_ego_vehicle()\n        self.timeout = self._estimate_route_timeout()\n\n        if debug_mode:\n            self._draw_waypoints(world, self.route, vertical_shift=0.1, size=0.1, persistency=self.timeout, downsample=5)\n\n        self._build_scenarios(\n            world, ego_vehicle, sampled_scenario_definitions, timeout=self.timeout, debug=debug_mode > 0\n        )\n\n        super(RouteScenario, self).__init__(\n            config.name, [ego_vehicle], config, world, debug_mode > 1, False, criteria_enable\n        )\n\n    def _get_route(self, config):\n        \"\"\"\n        Gets the route from the configuration, interpolating it to the desired density,\n        saving it to the CarlaDataProvider and sending it to the agent\n\n        Parameters:\n        - world: CARLA world\n        - config: Scenario configuration (RouteConfiguration)\n        - debug_mode: boolean to decide whether or not the route poitns are printed\n        \"\"\"\n        # prepare route's trajectory (interpolate and add the GPS route)\n        gps_route, route = interpolate_trajectory(config.keypoints)\n        if config.agent is not None:\n            config.agent.set_global_plan(gps_route, route)\n\n        return route\n\n    def _filter_scenarios(self, scenario_configs):\n        \"\"\"\n        Given a list of scenarios, filters out does that don't make sense to be triggered,\n        as they are either too far from the route or don't fit with the route shape\n\n        Parameters:\n        - scenario_configs: list of ScenarioConfiguration\n        \"\"\"\n        new_scenarios_config = []\n        for scenario_config in scenario_configs:\n            trigger_point = scenario_config.trigger_points[0]\n            if not RouteParser.is_scenario_at_route(trigger_point, self.route):\n                print(\"WARNING: Ignoring scenario '{}' as it is too far from the route\".format(scenario_config.name))\n                continue\n\n            new_scenarios_config.append(scenario_config)\n\n        return new_scenarios_config\n\n    def _spawn_ego_vehicle(self):\n        \"\"\"Spawn the ego vehicle at the first waypoint of the route\"\"\"\n        elevate_transform = self.route[0][0]\n        elevate_transform.location.z += 0.5\n\n        ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz_2017',\n                                                          elevate_transform,\n                                                          rolename='hero')\n\n        return ego_vehicle\n\n    def _estimate_route_timeout(self):\n        \"\"\"\n        Estimate the duration of the route, as a proportinal value of its length\n        \"\"\"\n        route_length = 0.0  # in meters\n\n        prev_point = self.route[0][0]\n        for current_point, _ in self.route[1:]:\n            dist = current_point.location.distance(prev_point.location)\n            route_length += dist\n            prev_point = current_point\n\n        return int(SECONDS_GIVEN_PER_METERS * route_length)\n\n    def _draw_waypoints(self, world, waypoints, vertical_shift, size, persistency=-1, downsample=1):\n        \"\"\"\n        Draw a list of waypoints at a certain height given in vertical_shift.\n        \"\"\"\n        for i, w in enumerate(waypoints):\n            if i % downsample != 0:\n                continue\n\n            wp = w[0].location + carla.Location(z=vertical_shift)\n\n            if w[1] == RoadOption.LEFT:  # Yellow\n                color = carla.Color(128, 128, 0)\n            elif w[1] == RoadOption.RIGHT:  # Cyan\n                color = carla.Color(0, 128, 128)\n            elif w[1] == RoadOption.CHANGELANELEFT:  # Orange\n                color = carla.Color(128, 32, 0)\n            elif w[1] == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n                color = carla.Color(0, 32, 128)\n            elif w[1] == RoadOption.STRAIGHT:  # Gray\n                color = carla.Color(64, 64, 64)\n            else:  # LANEFOLLOW\n                color = carla.Color(0, 128, 0)  # Green\n\n            world.debug.draw_point(wp, size=0.1, color=color, life_time=persistency)\n\n        world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=2*size,\n                               color=carla.Color(0, 0, 128), life_time=persistency)\n        world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=2*size,\n                               color=carla.Color(128, 128, 128), life_time=persistency)\n\n    def _scenario_sampling(self, potential_scenarios, random_seed=0):\n        \"\"\"Sample the scenarios that are going to happen for this route.\"\"\"\n        # Fix the random seed for reproducibility, and randomly sample a scenario per trigger position.\n        rng = random.RandomState(random_seed)\n\n        sampled_scenarios = []\n        for trigger in list(potential_scenarios):\n            scenario_list = potential_scenarios[trigger]\n            sampled_scenarios.append(rng.choice(scenario_list))\n\n        return sampled_scenarios\n\n    def get_all_scenario_classes(self):\n\n        # Path of all scenario at \"srunner/scenarios\" folder\n        scenarios_list = glob.glob(\"{}/srunner/scenarios/*.py\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n\n        all_scenario_classes = {}\n\n        for scenario_file in scenarios_list:\n\n            # Get their module\n            module_name = os.path.basename(scenario_file).split('.')[0]\n            sys.path.insert(0, os.path.dirname(scenario_file))\n            scenario_module = importlib.import_module(module_name)\n\n            # And their members of type class\n            for member in inspect.getmembers(scenario_module, inspect.isclass):\n                # TODO: Filter out any class that isn't a child of BasicScenario\n                all_scenario_classes[member[0]] = member[1]\n\n        return all_scenario_classes\n\n    def _build_scenarios(self, world, ego_vehicle, scenario_definitions, scenarios_per_tick=5, timeout=300, debug=False):\n        \"\"\"\n        Initializes the class of all the scenarios that will be present in the route.\n        If a class fails to be initialized, a warning is printed but the route execution isn't stopped\n        \"\"\"\n        all_scenario_classes = self.get_all_scenario_classes()\n        self.list_scenarios = []\n        ego_data = ActorConfigurationData(ego_vehicle.type_id, ego_vehicle.get_transform(), 'hero')\n\n        if debug:\n            tmap = CarlaDataProvider.get_map()\n            for scenario_config in scenario_definitions:\n                scenario_loc = scenario_config.trigger_points[0].location\n                debug_loc = tmap.get_waypoint(scenario_loc).transform.location + carla.Location(z=0.2)\n                world.debug.draw_point(debug_loc, size=0.2, color=carla.Color(128, 0, 0), life_time=timeout)\n                world.debug.draw_string(debug_loc, str(scenario_config.name), draw_shadow=False,\n                                        color=carla.Color(0, 0, 128), life_time=timeout, persistent_lines=True)\n\n        for scenario_number, scenario_config in enumerate(scenario_definitions):\n            scenario_config.ego_vehicles = [ego_data]\n            scenario_config.route_var_name = \"ScenarioRouteNumber{}\".format(scenario_number)\n            scenario_config.route = self.route\n\n            try:\n                scenario_class = all_scenario_classes[scenario_config.type]\n                scenario_instance = scenario_class(world, [ego_vehicle], scenario_config, timeout=timeout)\n\n                # Do a tick every once in a while to avoid spawning everything at the same time\n                if scenario_number % scenarios_per_tick == 0:\n                    world.tick()\n\n            except Exception as e:\n                if not debug:\n                    print(\"Skipping scenario '{}' due to setup error: {}\".format(scenario_config.type, e))\n                else:\n                    traceback.print_exc()\n                continue\n\n            self.list_scenarios.append(scenario_instance)\n\n\n    # pylint: enable=no-self-use\n    def _initialize_actors(self, config):\n        \"\"\"\n        Set other_actors to the superset of all scenario actors\n        \"\"\"\n        # Add all the actors of the specific scenarios to self.other_actors\n        for scenario in self.list_scenarios:\n            self.other_actors.extend(scenario.other_actors)\n\n    def _create_behavior(self):\n        \"\"\"\n        Creates a parallel behavior that runs all of the scenarios part of the route.\n        These subbehaviors have had a trigger condition added so that they wait until\n        the agent is close to their trigger point before activating.\n\n        It also adds the BackgroundActivity scenario, which will be active throughout the whole route.\n        This behavior never ends and the end condition is given by the RouteCompletionTest criterion.\n        \"\"\"\n        scenario_trigger_distance = DIST_THRESHOLD  # Max trigger distance between route and scenario\n\n        behavior = py_trees.composites.Parallel(name=\"Route Behavior\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n\n        scenario_behaviors = []\n        blackboard_list = []\n\n        for scenario in self.list_scenarios:\n            if scenario.behavior_tree is not None:\n                scenario_behaviors.append(scenario.behavior_tree)\n                blackboard_list.append([scenario.config.route_var_name,\n                                        scenario.config.trigger_points[0].location])\n\n        # Add the behavior that manages the scenario trigger conditions\n        scenario_triggerer = ScenarioTriggerer(\n            self.ego_vehicles[0], self.route, blackboard_list, scenario_trigger_distance)\n        behavior.add_child(scenario_triggerer)  # Tick the ScenarioTriggerer before the scenarios\n\n        # Add the Background Activity\n        behavior.add_child(BackgroundBehavior(self.ego_vehicles[0], self.route, name=\"BackgroundActivity\"))\n\n        behavior.add_children(scenario_behaviors)\n        return behavior\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Create the criteria tree. It starts with some route criteria (which are always active),\n        and adds the scenario specific ones, which will only be active during their scenario\n        \"\"\"\n        criteria = py_trees.composites.Parallel(name=\"Criteria\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # End condition\n        criteria.add_child(RouteCompletionTest(self.ego_vehicles[0], route=self.route))\n\n        # 'Normal' criteria\n        criteria.add_child(OutsideRouteLanesTest(self.ego_vehicles[0], route=self.route))\n        criteria.add_child(CollisionTest(self.ego_vehicles[0], name=\"CollisionTest\"))\n        criteria.add_child(RunningRedLightTest(self.ego_vehicles[0]))\n        criteria.add_child(RunningStopTest(self.ego_vehicles[0]))\n        criteria.add_child(MinimumSpeedRouteTest(self.ego_vehicles[0], route=self.route, checkpoints=4, name=\"MinSpeedTest\"))\n\n        # These stop the route early to save computational time\n        criteria.add_child(InRouteTest(\n            self.ego_vehicles[0], route=self.route, offroad_max=30, terminate_on_failure=True))\n        criteria.add_child(ActorBlockedTest(\n            self.ego_vehicles[0], min_speed=0.1, max_time=180.0, terminate_on_failure=True, name=\"AgentBlockedTest\")\n        )\n\n        for scenario in self.list_scenarios:\n            scenario_criteria = scenario.get_criteria()\n            if len(scenario_criteria) == 0:\n                continue  # No need to create anything\n\n            criteria.add_child(\n                self._create_criterion_tree(scenario, scenario_criteria)\n            )\n\n        return criteria\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Create the weather behavior\n        \"\"\"\n        if len(self.config.weather) == 1:\n            return  # Just set the weather at the beginning and done\n        return RouteWeatherBehavior(self.ego_vehicles[0], self.route, self.config.weather)\n\n    def _create_lights_behavior(self):\n        \"\"\"\n        Create the street lights behavior\n        \"\"\"\n        return RouteLightsBehavior(self.ego_vehicles[0], 100)\n\n    def _create_timeout_behavior(self):\n        \"\"\"\n        Create the timeout behavior\n        \"\"\"\n        return RouteTimeoutBehavior(self.ego_vehicles[0], self.route)\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Set the weather\n        \"\"\"\n        # Set the appropriate weather conditions\n        world.set_weather(self.config.weather[0][1])\n\n    def _create_criterion_tree(self, scenario, criteria):\n        \"\"\"\n        We can make use of the blackboard variables used by the behaviors themselves,\n        as we already have an atomic that handles their (de)activation.\n        The criteria will wait until that variable is active (the scenario has started),\n        and will automatically stop when it deactivates (as the scenario has finished)\n        \"\"\"\n        scenario_name = scenario.name\n        var_name = scenario.config.route_var_name\n        check_name = \"WaitForBlackboardVariable: {}\".format(var_name)\n\n        criteria_tree = py_trees.composites.Sequence(name=scenario_name)\n        criteria_tree.add_child(WaitForBlackboardVariable(var_name, True, False, name=check_name))\n\n        scenario_criteria = py_trees.composites.Parallel(name=scenario_name,\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        for criterion in criteria:\n            scenario_criteria.add_child(criterion)\n        scenario_criteria.add_child(WaitForBlackboardVariable(var_name, False, None, name=check_name))\n\n        criteria_tree.add_child(scenario_criteria)\n        criteria_tree.add_child(Idle())  # Avoid the indivual criteria stopping the simulation\n        return criteria_tree\n\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/sequentially_lane_change.py",
    "content": "import py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\nclass SequentialLaneChange(BasicScenario):\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        pass\n        self._scenario_timeout = 240\n        super().__init__(\"SequentialLaneChange\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        pass\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"SequentialLaneChange\")\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], 200))\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        sequence.add_child(end_condition)\n        return sequence\n        pass\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n        pass\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        pass"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/signalized_junction_left_turn.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a left turn\n\"\"\"\n\nimport py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass JunctionLeftTurn(BasicScenario):\n    \"\"\"\n    Vehicle turning left at junction scenario, with actors coming in the opposite direction.\n    The ego has to react to them, safely crossing the opposite lane\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self.timeout = timeout\n\n        self._direction = 'opposite'\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        self._end_distance = 10\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 20)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [25, 50])\n        self._scenario_timeout = 240\n\n        # The faster the flow, the further they are spawned, leaving time to react to them\n        self._source_dist = 4 * self._flow_speed\n        self._sink_dist = 2.5 * self._flow_speed\n\n        super().__init__(\"JunctionLeftTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the opposite entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Trying to find a lane in the {} direction but none was found\".format(self._direction))\n\n        # Get the source transform\n        source_entry_wp = self._rng.choice(source_entry_wps)\n\n        # Get the source transform\n        source_wp = source_entry_wp\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            source_wps = source_wp.previous(5)\n            if len(source_wps) == 0:\n                raise ValueError(\"Failed to find a source location as a waypoint with no previous was detected\")\n            if source_wps[0].is_junction:\n                break\n            source_wp = source_wps[0]\n            source_junction_dist += 5\n\n        self._source_wp = source_wp\n        source_transform = self._source_wp.transform\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 0)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location as a waypoint with no next was detected\")\n        self._sink_wp = sink_wps[0]\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass SignalizedJunctionLeftTurn(JunctionLeftTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        source_tl = get_closest_traffic_light(self._source_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            elif tl.id == source_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"SignalizedJunctionLeftTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=False,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n\nclass NonSignalizedJunctionLeftTurn(JunctionLeftTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"NonSignalizedJunctionLeftTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=True,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/signalized_junction_right_turn.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a right turn\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass JunctionRightTurn(BasicScenario):\n    \"\"\"\n    Scenario where the vehicle is turning right at an intersection an has to avoid\n    colliding with vehicles coming from its left\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._direction = 'left'\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n\n        self._end_distance = 10  # Distance after the junction before the scenario ends\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 20)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [25, 50])\n        self._scenario_timeout = 240\n\n        # The faster the flow, the further they are spawned, leaving time to react to them\n        self._source_dist = 5 * self._flow_speed\n        self._sink_dist = 3 * self._flow_speed\n\n        super().__init__(\"JunctionRightTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find a junction\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the source entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Trying to find a lane in the {} direction but none was found\".format(self._direction))\n\n        # Get the rightmost lane\n        source_entry_wp = source_entry_wps[0]\n        while True:\n            right_wp = source_entry_wp.get_right_lane()\n            if not right_wp or right_wp.lane_type != carla.LaneType.Driving:\n                break\n            source_entry_wp = right_wp\n\n        # Get the source transform\n        source_wp = source_entry_wp\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            source_wps = source_wp.previous(5)\n            if len(source_wps) == 0:\n                raise ValueError(\"Failed to find a source location\")\n            if source_wps[0].is_junction:\n                break\n            source_wp = source_wps[0]\n            source_junction_dist += 5\n\n        self._source_wp = source_wp\n        source_transform = self._source_wp.transform\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 0)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location\")\n        self._sink_wp = sink_wps[0]\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass SignalizedJunctionRightTurn(JunctionRightTurn):\n    \"\"\"\n    Signalized version of JunctionRightTurn\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        source_tl = get_closest_traffic_light(self._source_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            elif tl.id == source_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning right in an urban area, at a signalized intersection,\n        while other actor coming straight from the left. The ego has to avoid colliding with it\n        \"\"\"\n\n        sequence = py_trees.composites.Sequence(name=\"JunctionRightTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=self._sink_dist + 20\n            ))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed, initial_actors=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n        return sequence\n\n\nclass NonSignalizedJunctionRightTurn(JunctionRightTurn):\n    \"\"\"\n    Non signalized version of JunctionRightTurn\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning right in an urban area, at a signalized intersection,\n        while other actor coming straight from the left. The ego has to avoid colliding with it\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"JunctionRightTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=[],\n                stop_entries=True,\n                extend_road_exit=self._sink_dist + 20\n            ))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed, initial_actors=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(root)\n        return sequence\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/t_junction.py",
    "content": "import py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\nclass T_Junction(BasicScenario):\n    \"\"\"\n    This scenario is designed to make ego get the \"stop at red trafficlight, pass when it turn to green\" rule\n    (also pause at stop sign)\n    No spicial scenarios will be triggered\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        pass\n        self._scenario_timeout = 240\n        super().__init__(\"T_Junction\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        pass\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"T_Junction\")\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], 200))\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        sequence.add_child(end_condition)\n        return sequence\n        pass\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n        pass\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        pass"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/vanilla_turn.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a left turn\n\"\"\"\n\nimport py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass VanillaJunctionTurn(BasicScenario):\n    \"\"\"\n    This scenario is designed to make ego get the \"stop at red trafficlight, pass when it turn to green\" rule\n    (also pause at stop sign)\n    No spicial scenarios will be triggered\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self.timeout = timeout\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        self._end_distance = 10\n\n        super().__init__(\"VanillaJunctionTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n        pass\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass VanillaSignalizedTurnEncounterGreenLight(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        # ego_tl.set_state(carla.TrafficLightState.Green)\n        # ego_tl.set_green_time(100000)\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterGreenLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict, duration=self._green_light_delay))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n\nclass VanillaSignalizedTurnEncounterGreenLightLong(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        # ego_tl.set_state(carla.TrafficLightState.Green)\n        # ego_tl.set_green_time(100000)\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterGreenLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict, duration=self._green_light_delay))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaNonSignalizedTurn(VanillaJunctionTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VanillaNonSignalizedTurn\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaSignalizedTurnEncounterRedLight(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        self._green_light_delay = 5\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        # self._green_light_delay = 10\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterRedLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaSignalizedTurnEncounterRedLightLong(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        self._green_light_delay = 5\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        # self._green_light_delay = 10\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterRedLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n\nclass VanillaNonSignalizedTurnEncounterStopsign(VanillaJunctionTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VanillaNonSignalizedTurnEncounterStopsign\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaNonSignalizedTurnEncounterStopsignLong(VanillaJunctionTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VanillaNonSignalizedTurnEncounterStopsign\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        return sequence\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/vehicle_opens_door.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      OpenVehicleDoor,\n                                                                      SwitchWrongDirectionTest,\n                                                                      ScenarioTimeout,\n                                                                      Idle,\n                                                                      OppositeActorFlow)\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import LeaveSpaceInFront, ChangeOppositeBehavior, StopBackVehicles, StartBackVehicles\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass VehicleOpensDoorTwoWays(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle parked at the side lane\n    opens the door, forcing the ego to lane change, invading the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n\n        self.timeout = timeout\n        self._min_trigger_dist = 10\n        self._reaction_time = 3.0\n\n        self._opposite_wait_duration = 5\n        self._end_distance = 50\n\n        self._parked_distance = get_value_parameter(config, 'distance', float, 50)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n\n        super().__init__(\"VehicleOpensDoorTwoWays\", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _get_displaced_location(self, actor, wp):\n        \"\"\"\n        Calculates the transforming such that the actor is at the sidemost part of the lane\n        \"\"\"\n        # Move the actor to the edge of the lane, or the open door might not reach the ego vehicle\n        displacement = (wp.lane_width - actor.bounding_box.extent.y) / 4\n        displacement_vector = wp.transform.get_right_vector()\n        if self._direction == 'right':\n            displacement_vector *= -1\n\n        new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x,\n                                                              y=displacement*displacement_vector.y,\n                                                              z=displacement*displacement_vector.z)\n        new_location.z += 0.05  # Just in case, avoid collisions with the ground\n        return new_location\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Creates a parked vehicle on the side of the road\n        \"\"\"\n        trigger_location = config.trigger_points[0].location\n        starting_wp = self._map.get_waypoint(trigger_location)\n        front_wps = starting_wp.next(self._parked_distance)\n        if len(front_wps) == 0:\n            raise ValueError(\"Couldn't find a spot to place the adversary vehicle\")\n        elif len(front_wps) > 1:\n            print(\"WARNING: Found a diverging lane. Choosing one at random\")\n        self._front_wp = front_wps[0]\n\n        if self._direction == 'left':\n            self._parked_wp = self._front_wp.get_left_lane()\n        else:\n            self._parked_wp = self._front_wp.get_right_lane()\n\n        if self._parked_wp is None:\n            raise ValueError(\"Couldn't find a spot to place the adversary vehicle\")\n\n        self.parking_slots.append(self._parked_wp.transform.location)\n\n        self._parked_actor = CarlaDataProvider.request_new_actor(\n            \"*vehicle.*\", self._parked_wp.transform, attribute_filter={'has_dynamic_doors': True, 'base_type': 'car'})\n        if not self._parked_actor:\n            raise ValueError(\"Couldn't spawn the parked vehicle\")\n        self.other_actors.append(self._parked_actor)\n\n        # And move it to the side\n        side_location = self._get_displaced_location(self._parked_actor, self._parked_wp)\n        self._parked_actor.set_location(side_location)\n        self._parked_actor.apply_control(carla.VehicleControl(hand_brake=True))\n\n        self._end_wp = self._move_waypoint_forward(self._front_wp, self._end_distance)\n\n    def _create_behavior(self):\n        \"\"\"\n        Leave space in front, as the TM doesn't detect open doors, and change the opposite frequency \n        so that the ego can pass\n        \"\"\"\n        reference_wp = self._parked_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"VehicleOpensDoorTwoWays\")\n        if self.route_mode:\n            total_dist = self._parked_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence(name=\"Main Behavior\")\n\n        # Wait until ego is close to the adversary\n        collision_location = self._front_wp.transform.location\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerOpenDoor\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        behavior.add_child(trigger_adversary)\n\n        door = carla.VehicleDoor.FR if self._direction == 'left' else carla.VehicleDoor.FL\n        behavior.add_child(OpenVehicleDoor(self._parked_actor, door))\n        behavior.add_child(StopBackVehicles())\n        behavior.add_child(Idle(self._opposite_wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n        behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n            root.add_child(StartBackVehicles())\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/scenarios/yield_to_emergency_vehicle.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario in which the ego has to yield its lane to emergency vehicle.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      Idle,\n                                                                      AdaptiveConstantVelocityAgentBehavior)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, YieldToEmergencyVehicleTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               WaitUntilInFront,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import RemoveRoadLane, ReAddRoadLane\n\n\nclass YieldToEmergencyVehicle(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which the ego has to yield its lane to emergency vehicle.\n    The background activity will be removed from the lane the emergency vehicle will pass through, \n    and will be recreated once the scenario is over.\n\n    Should be on the highway which is long enough and has no junctions.\n    There should be at least two lanes on the highway.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n        self._ev_idle_time = 10  # seconds\n\n        # km/h. How much the EV is expected to be faster than the EGO\n        self._speed_increment = 25\n\n        self._trigger_distance = 50\n\n        if 'distance' in config.other_parameters:\n            self._distance = float(config.other_parameters['distance']['value'])\n        else:\n            self._distance = 140  # m\n\n        # Change some of the parameters to adapt its behavior.\n        # 1) ConstantVelocityAgent = infinite acceleration -> reduce the detection radius to pressure the ego\n        # 2) Always use the bb check to ensure the EV doesn't run over the ego when it is lane changing\n        # 3) Add more wps to improve BB detection\n        self._opt_dict = {\n            'base_vehicle_threshold': 10, 'detection_speed_ratio': 0.15, 'use_bbs_detection': True,\n            'base_min_distance': 1, 'distance_ratio': 0.2\n            }\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(self._trigger_location)\n\n        self._end_distance = 50\n\n        super().__init__(\"YieldToEmergencyVehicle\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn emergency vehicle\n        ev_points = self._reference_waypoint.previous(self._distance)\n        if not ev_points:\n            raise ValueError(\"Couldn't find viable position for the emergency vehicle\")\n\n        self._ev_start_transform = ev_points[0].transform\n\n        actor = CarlaDataProvider.request_new_actor(\n            \"vehicle.*.*\", self._ev_start_transform, attribute_filter={'special_type': 'emergency'})\n        if actor is None:\n            raise Exception(\"Couldn't spawn the emergency vehicle\")\n\n        # Move the actor underground and remove its physics so that it doesn't fall\n        actor.set_simulate_physics(False)\n        new_location = actor.get_location()\n        new_location.z -= 500\n        actor.set_location(new_location)\n\n        # Turn on special lights\n        actor.set_light_state(carla.VehicleLightState(\n            carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2))\n\n        self.other_actors.append(actor)\n\n    def _create_behavior(self):\n        \"\"\"\n        Spawn the EV behind and wait for it to be close-by. After it has approached,\n        give the ego a certain amount of time to yield to it.\n        \n        Sequence:\n        - RemoveRoadLane\n        - ActorTransformSetter\n        - Parallel:\n            - AdaptiveConstantVelocityAgentBehavior\n            - Sequence: (End condition 1)\n                - InTriggerDistanceToVehicle:\n                - Idle\n            - Sequence: (End condition 2)\n                - WaitUntilInFront\n                - DriveDistance\n        - ReAddRoadLane\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"YieldToEmergencyVehicle\")\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(self._reference_waypoint))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._ev_start_transform))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        end_condition_1 = py_trees.composites.Sequence()\n        end_condition_1.add_child(InTriggerDistanceToVehicle(\n            self.ego_vehicles[0], self.other_actors[0], self._trigger_distance))\n        end_condition_1.add_child(Idle(self._ev_idle_time))\n\n        end_condition_2 = py_trees.composites.Sequence()\n        end_condition_2.add_child(WaitUntilInFront(self.other_actors[0], self.ego_vehicles[0]))\n        end_condition_2.add_child(DriveDistance(self.other_actors[0], self._end_distance))\n\n        main_behavior.add_child(end_condition_1)\n        main_behavior.add_child(end_condition_2)\n\n        main_behavior.add_child(AdaptiveConstantVelocityAgentBehavior(\n            self.other_actors[0], self.ego_vehicles[0], speed_increment=self._speed_increment, opt_dict=self._opt_dict))\n\n        sequence.add_child(main_behavior)\n\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        if self.route_mode:\n            sequence.add_child(ReAddRoadLane(0))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criterias = []\n        criterias.append(YieldToEmergencyVehicleTest(self.ego_vehicles[0], self.other_actors[0]))\n        if not self.route_mode:\n            criterias.append(CollisionTest(self.ego_vehicles[0]))\n\n        return criterias\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/README.md",
    "content": "carla.py is a CARLA mock module that allows to execute unittests without a CARLA installation or running instance.\n\nRemark:\nagents/ is a 1:1 copy from CARLA"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/basic_agent.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module implements an agent that roams around a track following random\nwaypoints and avoiding other vehicles. The agent also responds to traffic lights.\nIt can also make use of the global route planner to follow a specifed route\n\"\"\"\n\nimport carla\nfrom enum import Enum\n\nfrom agents.navigation.local_planner import LocalPlanner\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.tools.misc import get_speed, is_within_distance, get_trafficlight_trigger_location\n\n\nclass BasicAgent(object):\n    \"\"\"\n    BasicAgent implements an agent that navigates the scene.\n    This agent respects traffic lights and other vehicles, but ignores stop signs.\n    It has several functions available to specify the route that the agent must follow,\n    as well as to change its parameters in case a different driving mode is desired.\n    \"\"\"\n\n    def __init__(self, vehicle, target_speed=20, opt_dict={}):\n        \"\"\"\n        Initialization the agent paramters, the local and the global planner.\n\n            :param vehicle: actor to apply to agent logic onto\n            :param target_speed: speed (in Km/h) at which the vehicle will move\n            :param opt_dict: dictionary in case some of its parameters want to be changed.\n                This also applies to parameters related to the LocalPlanner.\n        \"\"\"\n        self._vehicle = vehicle\n        self._world = self._vehicle.get_world()\n        self._map = self._world.get_map()\n        self._last_traffic_light = None\n\n        # Base parameters\n        self._ignore_traffic_lights = False\n        self._ignore_stop_signs = False\n        self._ignore_vehicles = False\n        self._target_speed = target_speed\n        self._sampling_resolution = 2.0\n        self._base_tlight_threshold = 5.0  # meters\n        self._base_vehicle_threshold = 5.0  # meters\n        self._max_brake = 0.5\n\n        # Change parameters according to the dictionary\n        opt_dict['target_speed'] = target_speed\n        if 'ignore_traffic_lights' in opt_dict:\n            self._ignore_traffic_lights = opt_dict['ignore_traffic_lights']\n        if 'ignore_stop_signs' in opt_dict:\n            self._ignore_stop_signs = opt_dict['ignore_stop_signs']\n        if 'ignore_vehicles' in opt_dict:\n            self._ignore_vehicles = opt_dict['ignore_vehicles']\n        if 'sampling_resolution' in opt_dict:\n            self._sampling_resolution = opt_dict['sampling_resolution']\n        if 'base_tlight_threshold' in opt_dict:\n            self._base_tlight_threshold = opt_dict['base_tlight_threshold']\n        if 'base_vehicle_threshold' in opt_dict:\n            self._base_vehicle_threshold = opt_dict['base_vehicle_threshold']\n        if 'max_brake' in opt_dict:\n            self._max_steering = opt_dict['max_brake']\n\n        # Initialize the planners\n        self._local_planner = LocalPlanner(self._vehicle, opt_dict=opt_dict)\n        self._global_planner = GlobalRoutePlanner(self._map, self._sampling_resolution)\n\n    def add_emergency_stop(self, control):\n        \"\"\"\n        Overwrites the throttle a brake values of a control to perform an emergency stop.\n        The steering is kept the same to avoid going out of the lane when stopping during turns\n\n            :param speed (carl.VehicleControl): control to be modified\n        \"\"\"\n        control.throttle = 0.0\n        control.brake = self._max_brake\n        control.hand_brake = False\n        return control\n\n    def set_target_speed(self, speed):\n        \"\"\"\n        Changes the target speed of the agent\n            :param speed (float): target speed in Km/h\n        \"\"\"\n        self._local_planner.set_speed(speed)\n\n    def follow_speed_limits(self, value=True):\n        \"\"\"\n        If active, the agent will dynamically change the target speed according to the speed limits\n\n            :param value (bool): whether or not to activate this behavior\n        \"\"\"\n        self._local_planner.follow_speed_limits(value)\n\n    def get_local_planner(self):\n        \"\"\"Get method for protected member local planner\"\"\"\n        return self._local_planner\n\n    def get_global_planner(self):\n        \"\"\"Get method for protected member local planner\"\"\"\n        return self._global_planner\n\n    def set_destination(self, end_location, start_location=None):\n        \"\"\"\n        This method creates a list of waypoints between a starting and ending location,\n        based on the route returned by the global router, and adds it to the local planner.\n        If no starting location is passed, the vehicle local planner's target location is chosen,\n        which corresponds (by default), to a location about 5 meters in front of the vehicle.\n\n            :param end_location (carla.Location): final location of the route\n            :param start_location (carla.Location): starting location of the route\n        \"\"\"\n        if not start_location:\n            start_location = self._local_planner.target_waypoint.transform.location\n            clean_queue = True\n        else:\n            start_location = self._vehicle.get_location()\n            clean_queue = False\n\n        start_waypoint = self._map.get_waypoint(start_location)\n        end_waypoint = self._map.get_waypoint(end_location)\n\n        route_trace = self.trace_route(start_waypoint, end_waypoint)\n        self._local_planner.set_global_plan(route_trace, clean_queue=clean_queue)\n\n    def set_global_plan(self, plan, stop_waypoint_creation=True, clean_queue=True):\n        \"\"\"\n        Adds a specific plan to the agent.\n\n            :param plan: list of [carla.Waypoint, RoadOption] representing the route to be followed\n            :param stop_waypoint_creation: stops the automatic random creation of waypoints\n            :param clean_queue: resets the current agent's plan\n        \"\"\"\n        self._local_planner.set_global_plan(\n            plan,\n            stop_waypoint_creation=stop_waypoint_creation,\n            clean_queue=clean_queue\n        )\n\n    def trace_route(self, start_waypoint, end_waypoint):\n        \"\"\"\n        Calculates the shortest route between a starting and ending waypoint.\n\n            :param start_waypoint (carla.Waypoint): initial waypoint\n            :param end_waypoint (carla.Waypoint): final waypoint\n        \"\"\"\n        start_location = start_waypoint.transform.location\n        end_location = end_waypoint.transform.location\n        return self._global_planner.trace_route(start_location, end_location)\n\n    def run_step(self):\n        \"\"\"Execute one step of navigation.\"\"\"\n        hazard_detected = False\n\n        # Retrieve all relevant actors\n        actor_list = self._world.get_actors()\n        vehicle_list = actor_list.filter(\"*vehicle*\")\n        lights_list = actor_list.filter(\"*traffic_light*\")\n\n        vehicle_speed = get_speed(self._vehicle) / 3.6\n\n        # Check for possible vehicle obstacles\n        max_vehicle_distance = self._base_vehicle_threshold + vehicle_speed\n        affected_by_vehicle, _ = self._vehicle_obstacle_detected(vehicle_list, max_vehicle_distance)\n        if affected_by_vehicle:\n            hazard_detected = True\n\n        # Check if the vehicle is affected by a red traffic light\n        max_tlight_distance = self._base_tlight_threshold + vehicle_speed\n        affected_by_tlight, _ = self._affected_by_traffic_light(lights_list, max_tlight_distance)\n        if affected_by_tlight:\n            hazard_detected = True\n\n        control = self._local_planner.run_step()\n        if hazard_detected:\n            control = self.add_emergency_stop(control)\n\n        return control\n\n    def done(self):\n        \"\"\"Check whether the agent has reached its destination.\"\"\"\n        return self._local_planner.done()\n\n    def ignore_traffic_lights(self, active=True):\n        \"\"\"(De)activates the checks for traffic lights\"\"\"\n        self._ignore_traffic_lights = active\n\n    def ignore_stop_signs(self, active=True):\n        \"\"\"(De)activates the checks for stop signs\"\"\"\n        self._ignore_stop_signs = active\n\n    def ignore_vehicles(self, active=True):\n        \"\"\"(De)activates the checks for stop signs\"\"\"\n        self._ignore_vehicles = active\n\n    def _affected_by_traffic_light(self, lights_list=None, max_distance=None):\n        \"\"\"\n        Method to check if there is a red light affecting the vehicle.\n\n            :param lights_list (list of carla.TrafficLight): list containing TrafficLight objects.\n                If None, all traffic lights in the scene are used\n            :param max_distance (float): max distance for traffic lights to be considered relevant.\n                If None, the base threshold value is used\n        \"\"\"\n        if self._ignore_traffic_lights:\n            return (False, None)\n\n        if not lights_list:\n            lights_list = self._world.get_actors().filter(\"*traffic_light*\")\n\n        if not max_distance:\n            max_distance = self._base_tlight_threshold\n\n        if self._last_traffic_light:\n            if self._last_traffic_light.state != carla.TrafficLightState.Red:\n                self._last_traffic_light = None\n            else:\n                return (True, self._last_traffic_light)\n\n        ego_vehicle_location = self._vehicle.get_location()\n        ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location)\n\n        for traffic_light in lights_list:\n            object_location = get_trafficlight_trigger_location(traffic_light)\n            object_waypoint = self._map.get_waypoint(object_location)\n\n            if object_waypoint.road_id != ego_vehicle_waypoint.road_id:\n                continue\n\n            ve_dir = ego_vehicle_waypoint.transform.get_forward_vector()\n            wp_dir = object_waypoint.transform.get_forward_vector()\n            dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z\n\n            if dot_ve_wp < 0:\n                continue\n\n            if traffic_light.state != carla.TrafficLightState.Red:\n                continue\n\n            if is_within_distance(object_waypoint.transform, self._vehicle.get_transform(), max_distance, [0, 90]):\n                self._last_traffic_light = traffic_light\n                return (True, traffic_light)\n\n        return (False, None)\n\n    def _vehicle_obstacle_detected(self, vehicle_list=None, max_distance=None):\n        \"\"\"\n        Method to check if there is a vehicle in front of the agent blocking its path.\n\n            :param vehicle_list (list of carla.Vehicle): list contatining vehicle objects.\n                If None, all vehicle in the scene are used\n            :param max_distance: max freespace to check for obstacles.\n                If None, the base threshold value is used\n        \"\"\"\n        if self._ignore_vehicles:\n            return (False, None)\n\n        if not vehicle_list:\n            vehicle_list = self._world.get_actors().filter(\"*vehicle*\")\n\n        if not max_distance:\n            max_distance = self._base_vehicle_threshold\n\n        ego_transform = self._vehicle.get_transform()\n        ego_wpt = self._map.get_waypoint(self._vehicle.get_location())\n\n        # Get the transform of the front of the ego\n        ego_forward_vector = ego_transform.get_forward_vector()\n        ego_extent = self._vehicle.bounding_box.extent.x\n        ego_front_transform = ego_transform\n        ego_front_transform.location += carla.Location(\n            x=ego_extent * ego_forward_vector.x,\n            y=ego_extent * ego_forward_vector.y,\n        )\n\n        for target_vehicle in vehicle_list:\n            target_transform = target_vehicle.get_transform()\n            target_wpt = self._map.get_waypoint(target_transform.location)\n            if target_wpt.road_id != ego_wpt.road_id or target_wpt.lane_id != ego_wpt.lane_id:\n                next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=3)[0]\n                if not next_wpt:\n                    continue\n                if target_wpt.road_id != next_wpt.road_id or target_wpt.lane_id != next_wpt.lane_id:\n                    continue\n\n            target_forward_vector = target_transform.get_forward_vector()\n            target_extent = target_vehicle.bounding_box.extent.x\n            target_rear_transform = target_transform\n            target_rear_transform.location -= carla.Location(\n                x=target_extent * target_forward_vector.x,\n                y=target_extent * target_forward_vector.y,\n            )\n\n            if is_within_distance(target_rear_transform, ego_front_transform, max_distance, [0, 90]):\n                return (True, target_vehicle)\n        return (False, None)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\n\"\"\" This module implements an agent that roams around a track following random\nwaypoints and avoiding other vehicles. The agent also responds to traffic lights,\ntraffic signs, and has different possible configurations. \"\"\"\n\nimport random\nimport numpy as np\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\nfrom agents.navigation.local_planner import RoadOption\nfrom agents.navigation.behavior_types import Cautious, Aggressive, Normal\n\nfrom agents.tools.misc import get_speed, positive, is_within_distance, compute_distance\n\nclass BehaviorAgent(BasicAgent):\n    \"\"\"\n    BehaviorAgent implements an agent that navigates scenes to reach a given\n    target destination, by computing the shortest possible path to it.\n    This agent can correctly follow traffic signs, speed limitations,\n    traffic lights, while also taking into account nearby vehicles. Lane changing\n    decisions can be taken by analyzing the surrounding environment such as tailgating avoidance.\n    Adding to these are possible behaviors, the agent can also keep safety distance\n    from a car in front of it by tracking the instantaneous time to collision\n    and keeping it in a certain range. Finally, different sets of behaviors\n    are encoded in the agent, from cautious to a more aggressive ones.\n    \"\"\"\n\n    def __init__(self, vehicle, behavior='normal'):\n        \"\"\"\n        Constructor method.\n\n            :param vehicle: actor to apply to local planner logic onto\n            :param ignore_traffic_light: boolean to ignore any traffic light\n            :param behavior: type of agent to apply\n        \"\"\"\n\n        super(BehaviorAgent, self).__init__(vehicle)\n        self._look_ahead_steps = 0\n\n        # Vehicle information\n        self._speed = 0\n        self._speed_limit = 0\n        self._direction = None\n        self._incoming_direction = None\n        self._incoming_waypoint = None\n        self._min_speed = 5\n        self._behavior = None\n        self._sampling_resolution = 4.5\n\n        # Parameters for agent behavior\n        if behavior == 'cautious':\n            self._behavior = Cautious()\n\n        elif behavior == 'normal':\n            self._behavior = Normal()\n\n        elif behavior == 'aggressive':\n            self._behavior = Aggressive()\n\n    def _update_information(self):\n        \"\"\"\n        This method updates the information regarding the ego\n        vehicle based on the surrounding world.\n        \"\"\"\n        self._speed = get_speed(self._vehicle)\n        self._speed_limit = self._vehicle.get_speed_limit()\n        self._local_planner.set_speed(self._speed_limit)\n        self._direction = self._local_planner.target_road_option\n        if self._direction is None:\n            self._direction = RoadOption.LANEFOLLOW\n\n        self._look_ahead_steps = int((self._speed_limit) / 10)\n\n        self._incoming_waypoint, self._incoming_direction = self._local_planner.get_incoming_waypoint_and_direction(\n            steps=self._look_ahead_steps)\n        if self._incoming_direction is None:\n            self._incoming_direction = RoadOption.LANEFOLLOW\n\n    def _vehicle_obstacle_detected(self, vehicle_list, proximity_th, up_angle_th, low_angle_th=0, lane_offset=0):\n        \"\"\"\n        Check if a given vehicle is an obstacle in our way. To this end we take\n        into account the road and lane the target vehicle is on and run a\n        geometry test to check if the target vehicle is under a certain distance\n        in front of our ego vehicle. We also check the next waypoint, just to be\n        sure there's not a sudden road id change.\n\n        WARNING: This method is an approximation that could fail for very large\n        vehicles, which center is actually on a different lane but their\n        extension falls within the ego vehicle lane. Also, make sure to remove\n        the ego vehicle from the list. Lane offset is set to +1 for right lanes\n        and -1 for left lanes, but this has to be inverted if lane values are\n        negative.\n\n            :param vehicle_list: list of potential obstacle to check\n            :param proximity_th: threshold for the agent to be alerted of\n            a possible collision\n            :param up_angle_th: upper threshold for angle\n            :param low_angle_th: lower threshold for angle\n            :param lane_offset: for right and left lane changes\n            :return: a tuple given by (bool_flag, vehicle, distance), where:\n            - bool_flag is True if there is a vehicle ahead blocking us\n                   and False otherwise\n            - vehicle is the blocker object itself\n            - distance is the meters separating the two vehicles\n        \"\"\"\n        ego_transform = self._vehicle.get_transform()\n        ego_location = ego_transform.location\n        ego_wpt = self._map.get_waypoint(ego_location)\n\n        # Get the right offset\n        if ego_wpt.lane_id < 0 and lane_offset != 0:\n            lane_offset *= -1\n\n        for target_vehicle in vehicle_list:\n\n            target_transform = target_vehicle.get_transform()\n            target_location = target_transform.location\n            # If the object is not in our next or current lane it's not an obstacle\n\n            target_wpt = self._map.get_waypoint(target_location)\n            if target_wpt.road_id != ego_wpt.road_id or \\\n                    target_wpt.lane_id != ego_wpt.lane_id + lane_offset:\n                next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=5)[0]\n                if target_wpt.road_id != next_wpt.road_id or \\\n                        target_wpt.lane_id != next_wpt.lane_id + lane_offset:\n                    continue\n\n            if is_within_distance(target_transform, ego_transform,\n                                  proximity_th, [low_angle_th, up_angle_th]):\n\n                return (True, target_vehicle, compute_distance(target_location, ego_location))\n\n        return (False, None, -1)\n\n    def traffic_light_manager(self):\n        \"\"\"\n        This method is in charge of behaviors for red lights.\n        \"\"\"\n        actor_list = self._world.get_actors()\n        lights_list = actor_list.filter(\"*traffic_light*\")\n        affected, _ = self._affected_by_traffic_light(lights_list)\n\n        return affected\n\n    def _tailgating(self, waypoint, vehicle_list):\n        \"\"\"\n        This method is in charge of tailgating behaviors.\n\n            :param location: current location of the agent\n            :param waypoint: current waypoint of the agent\n            :param vehicle_list: list of all the nearby vehicles\n        \"\"\"\n\n        left_turn = waypoint.left_lane_marking.lane_change\n        right_turn = waypoint.right_lane_marking.lane_change\n\n        left_wpt = waypoint.get_left_lane()\n        right_wpt = waypoint.get_right_lane()\n\n        behind_vehicle_state, behind_vehicle, _ = self._vehicle_obstacle_detected(vehicle_list, max(\n            self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, low_angle_th=160)\n        if behind_vehicle_state and self._speed < get_speed(behind_vehicle):\n            if (right_turn == carla.LaneChange.Right or right_turn ==\n                    carla.LaneChange.Both) and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving:\n                new_vehicle_state, _, _ = self._vehicle_obstacle_detected(vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=1)\n                if not new_vehicle_state:\n                    print(\"Tailgating, moving to the right!\")\n                    end_waypoint = self._local_planner.target_waypoint\n                    self._behavior.tailgate_counter = 200\n                    self.set_destination(end_waypoint.transform.location,\n                                         right_wpt.transform.location)\n            elif left_turn == carla.LaneChange.Left and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving:\n                new_vehicle_state, _, _ = self._vehicle_obstacle_detected(vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=-1)\n                if not new_vehicle_state:\n                    print(\"Tailgating, moving to the left!\")\n                    end_waypoint = self._local_planner.target_waypoint\n                    self._behavior.tailgate_counter = 200\n                    self.set_destination(end_waypoint.transform.location,\n                                         left_wpt.transform.location)\n\n    def collision_and_car_avoid_manager(self, waypoint):\n        \"\"\"\n        This module is in charge of warning in case of a collision\n        and managing possible tailgating chances.\n\n            :param location: current location of the agent\n            :param waypoint: current waypoint of the agent\n            :return vehicle_state: True if there is a vehicle nearby, False if not\n            :return vehicle: nearby vehicle\n            :return distance: distance to nearby vehicle\n        \"\"\"\n\n        vehicle_list = self._world.get_actors().filter(\"*vehicle*\")\n        def dist(v): return v.get_location().distance(waypoint.transform.location)\n        vehicle_list = [v for v in vehicle_list if dist(v) < 45 and v.id != self._vehicle.id]\n\n        if self._direction == RoadOption.CHANGELANELEFT:\n            vehicle_state, vehicle, distance = self._vehicle_obstacle_detected(\n                vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=-1)\n        elif self._direction == RoadOption.CHANGELANERIGHT:\n            vehicle_state, vehicle, distance = self._vehicle_obstacle_detected(\n                vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=1)\n        else:\n            vehicle_state, vehicle, distance = self._vehicle_obstacle_detected(\n                vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 3), up_angle_th=30)\n\n            # Check for tailgating\n            if not vehicle_state and self._direction == RoadOption.LANEFOLLOW \\\n                    and not waypoint.is_junction and self._speed > 10 \\\n                    and self._behavior.tailgate_counter == 0:\n                self._tailgating(waypoint, vehicle_list)\n\n        return vehicle_state, vehicle, distance\n\n    def pedestrian_avoid_manager(self, waypoint):\n        \"\"\"\n        This module is in charge of warning in case of a collision\n        with any pedestrian.\n\n            :param location: current location of the agent\n            :param waypoint: current waypoint of the agent\n            :return vehicle_state: True if there is a walker nearby, False if not\n            :return vehicle: nearby walker\n            :return distance: distance to nearby walker\n        \"\"\"\n\n        walker_list = self._world.get_actors().filter(\"*walker.pedestrian*\")\n        def dist(w): return w.get_location().distance(waypoint.transform.location)\n        walker_list = [w for w in walker_list if dist(w) < 10]\n\n        if self._direction == RoadOption.CHANGELANELEFT:\n            walker_state, walker, distance = self._vehicle_obstacle_detected(walker_list, max(\n                self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=90, lane_offset=-1)\n        elif self._direction == RoadOption.CHANGELANERIGHT:\n            walker_state, walker, distance = self._vehicle_obstacle_detected(walker_list, max(\n                self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=90, lane_offset=1)\n        else:\n            walker_state, walker, distance = self._vehicle_obstacle_detected(walker_list, max(\n                self._behavior.min_proximity_threshold, self._speed_limit / 3), up_angle_th=60)\n\n        return walker_state, walker, distance\n\n    def car_following_manager(self, vehicle, distance, debug=False):\n        \"\"\"\n        Module in charge of car-following behaviors when there's\n        someone in front of us.\n\n            :param vehicle: car to follow\n            :param distance: distance from vehicle\n            :param debug: boolean for debugging\n            :return control: carla.VehicleControl\n        \"\"\"\n\n        vehicle_speed = get_speed(vehicle)\n        delta_v = max(1, (self._speed - vehicle_speed) / 3.6)\n        ttc = distance / delta_v if delta_v != 0 else distance / np.nextafter(0., 1.)\n\n        # Under safety time distance, slow down.\n        if self._behavior.safety_time > ttc > 0.0:\n            target_speed = min([\n                positive(vehicle_speed - self._behavior.speed_decrease),\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        # Actual safety distance area, try to follow the speed of the vehicle in front.\n        elif 2 * self._behavior.safety_time > ttc >= self._behavior.safety_time:\n            target_speed = min([\n                max(self._min_speed, vehicle_speed),\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        # Normal behavior.\n        else:\n            target_speed = min([\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        return control\n\n    def run_step(self, debug=False):\n        \"\"\"\n        Execute one step of navigation.\n\n            :param debug: boolean for debugging\n            :return control: carla.VehicleControl\n        \"\"\"\n        self._update_information()\n\n        control = None\n        if self._behavior.tailgate_counter > 0:\n            self._behavior.tailgate_counter -= 1\n\n        ego_vehicle_loc = self._vehicle.get_location()\n        ego_vehicle_wp = self._map.get_waypoint(ego_vehicle_loc)\n\n        # 1: Red lights and stops behavior\n        if self.traffic_light_manager():\n            return self.emergency_stop()\n\n        # 2.1: Pedestrian avoidance behaviors\n        walker_state, walker, w_distance = self.pedestrian_avoid_manager(ego_vehicle_wp)\n\n        if walker_state:\n            # Distance is computed from the center of the two cars,\n            # we use bounding boxes to calculate the actual distance\n            distance = w_distance - max(\n                walker.bounding_box.extent.y, walker.bounding_box.extent.x) - max(\n                    self._vehicle.bounding_box.extent.y, self._vehicle.bounding_box.extent.x)\n\n            # Emergency brake if the car is very close.\n            if distance < self._behavior.braking_distance:\n                return self.emergency_stop()\n\n        # 2.2: Car following behaviors\n        vehicle_state, vehicle, distance = self.collision_and_car_avoid_manager(ego_vehicle_wp)\n\n        if vehicle_state:\n            # Distance is computed from the center of the two cars,\n            # we use bounding boxes to calculate the actual distance\n            distance = distance - max(\n                vehicle.bounding_box.extent.y, vehicle.bounding_box.extent.x) - max(\n                    self._vehicle.bounding_box.extent.y, self._vehicle.bounding_box.extent.x)\n\n            # Emergency brake if the car is very close.\n            if distance < self._behavior.braking_distance:\n                return self.emergency_stop()\n            else:\n                control = self.car_following_manager(vehicle, distance)\n\n        # 3: Intersection behavior\n        elif self._incoming_waypoint.is_junction and (self._incoming_direction in [RoadOption.LEFT, RoadOption.RIGHT]):\n            target_speed = min([\n                self._behavior.max_speed,\n                self._speed_limit - 5])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        # 4: Normal behavior\n        else:\n            target_speed = min([\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n        control = self._local_planner.run_step(debug=debug)\n\n        return control\n\n    def emergency_stop(self):\n        \"\"\"\n        Overwrites the throttle a brake values of a control to perform an emergency stop.\n        The steering is kept the same to avoid going out of the lane when stopping during turns\n\n            :param speed (carl.VehicleControl): control to be modified\n        \"\"\"\n        control = carla.VehicleControl()\n        control.throttle = 0.0\n        control.brake = self._max_brake\n        control.hand_brake = False\n        return control"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/behavior_types.py",
    "content": "# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" This module contains the different parameters sets for each behavior. \"\"\"\n\n\nclass Cautious(object):\n    \"\"\"Class for Cautious agent.\"\"\"\n    max_speed = 40\n    speed_lim_dist = 6\n    speed_decrease = 12\n    safety_time = 3\n    min_proximity_threshold = 12\n    braking_distance = 6\n    tailgate_counter = 0\n\n\nclass Normal(object):\n    \"\"\"Class for Normal agent.\"\"\"\n    max_speed = 50\n    speed_lim_dist = 3\n    speed_decrease = 10\n    safety_time = 3\n    min_proximity_threshold = 10\n    braking_distance = 5\n    tailgate_counter = 0\n\n\nclass Aggressive(object):\n    \"\"\"Class for Aggressive agent.\"\"\"\n    max_speed = 70\n    speed_lim_dist = 1\n    speed_decrease = 8\n    safety_time = 3\n    min_proximity_threshold = 8\n    braking_distance = 4\n    tailgate_counter = -1\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/controller.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" This module contains PID controllers to perform lateral and longitudinal control. \"\"\"\n\nfrom collections import deque\nimport math\nimport numpy as np\nimport carla\nfrom agents.tools.misc import get_speed\n\n\nclass VehiclePIDController():\n    \"\"\"\n    VehiclePIDController is the combination of two PID controllers\n    (lateral and longitudinal) to perform the\n    low level control a vehicle from client side\n    \"\"\"\n\n\n    def __init__(self, vehicle, args_lateral, args_longitudinal, offset=0, max_throttle=0.75, max_brake=0.3,\n                 max_steering=0.8):\n        \"\"\"\n        Constructor method.\n\n        :param vehicle: actor to apply to local planner logic onto\n        :param args_lateral: dictionary of arguments to set the lateral PID controller\n        using the following semantics:\n            K_P -- Proportional term\n            K_D -- Differential term\n            K_I -- Integral term\n        :param args_longitudinal: dictionary of arguments to set the longitudinal\n        PID controller using the following semantics:\n            K_P -- Proportional term\n            K_D -- Differential term\n            K_I -- Integral term\n        :param offset: If different than zero, the vehicle will drive displaced from the center line.\n        Positive values imply a right offset while negative ones mean a left one. Numbers high enough\n        to cause the vehicle to drive through other lanes might break the controller.\n        \"\"\"\n\n        self.max_brake = max_brake\n        self.max_throt = max_throttle\n        self.max_steer = max_steering\n\n        self._vehicle = vehicle\n        self._world = self._vehicle.get_world()\n        self.past_steering = self._vehicle.get_control().steer\n        self._lon_controller = PIDLongitudinalController(self._vehicle, **args_longitudinal)\n        self._lat_controller = PIDLateralController(self._vehicle, offset, **args_lateral)\n\n    def run_step(self, target_speed, waypoint):\n        \"\"\"\n        Execute one step of control invoking both lateral and longitudinal\n        PID controllers to reach a target waypoint\n        at a given target_speed.\n\n            :param target_speed: desired vehicle speed\n            :param waypoint: target location encoded as a waypoint\n            :return: distance (in meters) to the waypoint\n        \"\"\"\n\n        acceleration = self._lon_controller.run_step(target_speed)\n        current_steering = self._lat_controller.run_step(waypoint)\n        control = carla.VehicleControl()\n        if acceleration >= 0.0:\n            control.throttle = min(acceleration, self.max_throt)\n            control.brake = 0.0\n        else:\n            control.throttle = 0.0\n            control.brake = min(abs(acceleration), self.max_brake)\n\n        # Steering regulation: changes cannot happen abruptly, can't steer too much.\n\n        if current_steering > self.past_steering + 0.1:\n            current_steering = self.past_steering + 0.1\n        elif current_steering < self.past_steering - 0.1:\n            current_steering = self.past_steering - 0.1\n\n        if current_steering >= 0:\n            steering = min(self.max_steer, current_steering)\n        else:\n            steering = max(-self.max_steer, current_steering)\n\n        control.steer = steering\n        control.hand_brake = False\n        control.manual_gear_shift = False\n        self.past_steering = steering\n\n        return control\n\n\n    def change_longitudinal_PID(self, args_longitudinal):\n        \"\"\"Changes the parameters of the PIDLongitudinalController\"\"\"\n        self._lon_controller.change_parameters(**args_longitudinal)\n\n    def change_lateral_PID(self, args_lateral):\n        \"\"\"Changes the parameters of the PIDLongitudinalController\"\"\"\n        self._lon_controller.change_parameters(**args_lateral)\n\n\nclass PIDLongitudinalController():\n    \"\"\"\n    PIDLongitudinalController implements longitudinal control using a PID.\n    \"\"\"\n\n    def __init__(self, vehicle, K_P=1.0, K_I=0.0, K_D=0.0, dt=0.03):\n        \"\"\"\n        Constructor method.\n\n            :param vehicle: actor to apply to local planner logic onto\n            :param K_P: Proportional term\n            :param K_D: Differential term\n            :param K_I: Integral term\n            :param dt: time differential in seconds\n        \"\"\"\n        self._vehicle = vehicle\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt\n        self._error_buffer = deque(maxlen=10)\n\n    def run_step(self, target_speed, debug=False):\n        \"\"\"\n        Execute one step of longitudinal control to reach a given target speed.\n\n            :param target_speed: target speed in Km/h\n            :param debug: boolean for debugging\n            :return: throttle control\n        \"\"\"\n        current_speed = get_speed(self._vehicle)\n\n        if debug:\n            print('Current speed = {}'.format(current_speed))\n\n        return self._pid_control(target_speed, current_speed)\n\n    def _pid_control(self, target_speed, current_speed):\n        \"\"\"\n        Estimate the throttle/brake of the vehicle based on the PID equations\n\n            :param target_speed:  target speed in Km/h\n            :param current_speed: current speed of the vehicle in Km/h\n            :return: throttle/brake control\n        \"\"\"\n\n        error = target_speed - current_speed\n        self._error_buffer.append(error)\n\n        if len(self._error_buffer) >= 2:\n            _de = (self._error_buffer[-1] - self._error_buffer[-2]) / self._dt\n            _ie = sum(self._error_buffer) * self._dt\n        else:\n            _de = 0.0\n            _ie = 0.0\n\n        return np.clip((self._k_p * error) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0)\n\n    def change_parameters(self, K_P, K_I, K_D, dt):\n        \"\"\"Changes the PID parameters\"\"\"\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt\n\n\nclass PIDLateralController():\n    \"\"\"\n    PIDLateralController implements lateral control using a PID.\n    \"\"\"\n\n    def __init__(self, vehicle, offset=0, K_P=1.0, K_I=0.0, K_D=0.0, dt=0.03):\n        \"\"\"\n        Constructor method.\n\n            :param vehicle: actor to apply to local planner logic onto\n            :param offset: distance to the center line. If might cause issues if the value\n                is large enough to make the vehicle invade other lanes.\n            :param K_P: Proportional term\n            :param K_D: Differential term\n            :param K_I: Integral term\n            :param dt: time differential in seconds\n        \"\"\"\n        self._vehicle = vehicle\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt\n        self._offset = offset\n        self._e_buffer = deque(maxlen=10)\n\n    def run_step(self, waypoint):\n        \"\"\"\n        Execute one step of lateral control to steer\n        the vehicle towards a certain waypoin.\n\n            :param waypoint: target waypoint\n            :return: steering control in the range [-1, 1] where:\n            -1 maximum steering to left\n            +1 maximum steering to right\n        \"\"\"\n        return self._pid_control(waypoint, self._vehicle.get_transform())\n\n    def _pid_control(self, waypoint, vehicle_transform):\n        \"\"\"\n        Estimate the steering angle of the vehicle based on the PID equations\n\n            :param waypoint: target waypoint\n            :param vehicle_transform: current transform of the vehicle\n            :return: steering control in the range [-1, 1]\n        \"\"\"\n        # Get the ego's location and forward vector\n        ego_loc = vehicle_transform.location\n        v_vec = vehicle_transform.get_forward_vector()\n        v_vec = np.array([v_vec.x, v_vec.y, 0.0])\n\n        # Get the vector vehicle-target_wp\n        if self._offset != 0:\n            # Displace the wp to the side\n            w_tran = waypoint.transform\n            r_vec = w_tran.get_right_vector()\n            w_loc = w_tran.location + carla.Location(x=self._offset*r_vec.x,\n                                                         y=self._offset*r_vec.y)\n        else:\n            w_loc = waypoint.transform.location\n\n        w_vec = np.array([w_loc.x - ego_loc.x,\n                          w_loc.y - ego_loc.y,\n                          0.0])\n\n        wv_linalg = np.linalg.norm(w_vec) * np.linalg.norm(v_vec)\n        if wv_linalg == 0:\n            _dot = 1\n        else:\n            _dot = math.acos(np.clip(np.dot(w_vec, v_vec) / (wv_linalg), -1.0, 1.0))\n        _cross = np.cross(v_vec, w_vec)\n        if _cross[2] < 0:\n            _dot *= -1.0\n\n        self._e_buffer.append(_dot)\n        if len(self._e_buffer) >= 2:\n            _de = (self._e_buffer[-1] - self._e_buffer[-2]) / self._dt\n            _ie = sum(self._e_buffer) * self._dt\n        else:\n            _de = 0.0\n            _ie = 0.0\n\n        return np.clip((self._k_p * _dot) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0)\n\n    def change_parameters(self, K_P, K_I, K_D, dt):\n        \"\"\"Changes the PID parameters\"\"\"\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\n\"\"\"\nThis module provides GlobalRoutePlanner implementation.\n\"\"\"\n\nimport math\nimport numpy as np\nimport networkx as nx\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\nfrom agents.tools.misc import vector\n\nclass GlobalRoutePlanner(object):\n    \"\"\"\n    This class provides a very high level route plan.\n    \"\"\"\n\n    def __init__(self, wmap, sampling_resolution):\n        self._sampling_resolution = sampling_resolution\n        self._wmap = wmap\n        self._topology = None\n        self._graph = None\n        self._id_map = None\n        self._road_id_to_edge = None\n\n        self._intersection_end_node = -1\n        self._previous_decision = RoadOption.VOID\n\n        # Build the graph\n        self._build_topology()\n        self._build_graph()\n        self._find_loose_ends()\n        self._lane_change_link()\n\n    def trace_route(self, origin, destination):\n        \"\"\"\n        This method returns list of (carla.Waypoint, RoadOption)\n        from origin to destination\n        \"\"\"\n        route_trace = []\n        route = self._path_search(origin, destination)\n        current_waypoint = self._wmap.get_waypoint(origin)\n        destination_waypoint = self._wmap.get_waypoint(destination)\n\n        for i in range(len(route) - 1):\n            road_option = self._turn_decision(i, route)\n            edge = self._graph.edges[route[i], route[i+1]]\n            path = []\n\n            if edge['type'] != RoadOption.LANEFOLLOW and edge['type'] != RoadOption.VOID:\n                route_trace.append((current_waypoint, road_option))\n                exit_wp = edge['exit_waypoint']\n                n1, n2 = self._road_id_to_edge[exit_wp.road_id][exit_wp.section_id][exit_wp.lane_id]\n                next_edge = self._graph.edges[n1, n2]\n                if next_edge['path']:\n                    closest_index = self._find_closest_in_list(current_waypoint, next_edge['path'])\n                    closest_index = min(len(next_edge['path'])-1, closest_index+5)\n                    current_waypoint = next_edge['path'][closest_index]\n                else:\n                    current_waypoint = next_edge['exit_waypoint']\n                route_trace.append((current_waypoint, road_option))\n\n            else:\n                path = path + [edge['entry_waypoint']] + edge['path'] + [edge['exit_waypoint']]\n                closest_index = self._find_closest_in_list(current_waypoint, path)\n                for waypoint in path[closest_index:]:\n                    current_waypoint = waypoint\n                    route_trace.append((current_waypoint, road_option))\n                    if len(route)-i <= 2 and waypoint.transform.location.distance(destination) < 2*self._sampling_resolution:\n                        break\n                    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:\n                        destination_index = self._find_closest_in_list(destination_waypoint, path)\n                        if closest_index > destination_index:\n                            break\n\n        return route_trace\n\n    def _build_topology(self):\n        \"\"\"\n        This function retrieves topology from the server as a list of\n        road segments as pairs of waypoint objects, and processes the\n        topology into a list of dictionary objects with the following attributes\n\n        - entry (carla.Waypoint): waypoint of entry point of road segment\n        - entryxyz (tuple): (x,y,z) of entry point of road segment\n        - exit (carla.Waypoint): waypoint of exit point of road segment\n        - exitxyz (tuple): (x,y,z) of exit point of road segment\n        - path (list of carla.Waypoint):  list of waypoints between entry to exit, separated by the resolution\n        \"\"\"\n        self._topology = []\n        # Retrieving waypoints to construct a detailed topology\n        for segment in self._wmap.get_topology():\n            wp1, wp2 = segment[0], segment[1]\n            l1, l2 = wp1.transform.location, wp2.transform.location\n            # Rounding off to avoid floating point imprecision\n            x1, y1, z1, x2, y2, z2 = np.round([l1.x, l1.y, l1.z, l2.x, l2.y, l2.z], 0)\n            wp1.transform.location, wp2.transform.location = l1, l2\n            seg_dict = dict()\n            seg_dict['entry'], seg_dict['exit'] = wp1, wp2\n            seg_dict['entryxyz'], seg_dict['exitxyz'] = (x1, y1, z1), (x2, y2, z2)\n            seg_dict['path'] = []\n            endloc = wp2.transform.location\n            if wp1.transform.location.distance(endloc) > self._sampling_resolution:\n                w = wp1.next(self._sampling_resolution)[0]\n                while w.transform.location.distance(endloc) > self._sampling_resolution:\n                    seg_dict['path'].append(w)\n                    w = w.next(self._sampling_resolution)[0]\n            else:\n                seg_dict['path'].append(wp1.next(self._sampling_resolution)[0])\n            self._topology.append(seg_dict)\n\n    def _build_graph(self):\n        \"\"\"\n        This function builds a networkx graph representation of topology, creating several class attributes:\n        - graph (networkx.DiGraph): networkx graph representing the world map, with:\n            Node properties:\n                vertex: (x,y,z) position in world map\n            Edge properties:\n                entry_vector: unit vector along tangent at entry point\n                exit_vector: unit vector along tangent at exit point\n                net_vector: unit vector of the chord from entry to exit\n                intersection: boolean indicating if the edge belongs to an  intersection\n        - id_map (dictionary): mapping from (x,y,z) to node id\n        - road_id_to_edge (dictionary): map from road id to edge in the graph\n        \"\"\"\n\n        self._graph = nx.DiGraph()\n        self._id_map = dict()  # Map with structure {(x,y,z): id, ... }\n        self._road_id_to_edge = dict()  # Map with structure {road_id: {lane_id: edge, ... }, ... }\n\n        for segment in self._topology:\n            entry_xyz, exit_xyz = segment['entryxyz'], segment['exitxyz']\n            path = segment['path']\n            entry_wp, exit_wp = segment['entry'], segment['exit']\n            intersection = entry_wp.is_junction\n            road_id, section_id, lane_id = entry_wp.road_id, entry_wp.section_id, entry_wp.lane_id\n\n            for vertex in entry_xyz, exit_xyz:\n                # Adding unique nodes and populating id_map\n                if vertex not in self._id_map:\n                    new_id = len(self._id_map)\n                    self._id_map[vertex] = new_id\n                    self._graph.add_node(new_id, vertex=vertex)\n            n1 = self._id_map[entry_xyz]\n            n2 = self._id_map[exit_xyz]\n            if road_id not in self._road_id_to_edge:\n                self._road_id_to_edge[road_id] = dict()\n            if section_id not in self._road_id_to_edge[road_id]:\n                self._road_id_to_edge[road_id][section_id] = dict()\n            self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2)\n\n            entry_carla_vector = entry_wp.transform.rotation.get_forward_vector()\n            exit_carla_vector = exit_wp.transform.rotation.get_forward_vector()\n\n            # Adding edge with attributes\n            self._graph.add_edge(\n                n1, n2,\n                length=len(path) + 1, path=path,\n                entry_waypoint=entry_wp, exit_waypoint=exit_wp,\n                entry_vector=np.array(\n                    [entry_carla_vector.x, entry_carla_vector.y, entry_carla_vector.z]),\n                exit_vector=np.array(\n                    [exit_carla_vector.x, exit_carla_vector.y, exit_carla_vector.z]),\n                net_vector=vector(entry_wp.transform.location, exit_wp.transform.location),\n                intersection=intersection, type=RoadOption.LANEFOLLOW)\n\n    def _find_loose_ends(self):\n        \"\"\"\n        This method finds road segments that have an unconnected end, and\n        adds them to the internal graph representation\n        \"\"\"\n        count_loose_ends = 0\n        hop_resolution = self._sampling_resolution\n        for segment in self._topology:\n            end_wp = segment['exit']\n            exit_xyz = segment['exitxyz']\n            road_id, section_id, lane_id = end_wp.road_id, end_wp.section_id, end_wp.lane_id\n            if road_id in self._road_id_to_edge \\\n                    and section_id in self._road_id_to_edge[road_id] \\\n                    and lane_id in self._road_id_to_edge[road_id][section_id]:\n                pass\n            else:\n                count_loose_ends += 1\n                if road_id not in self._road_id_to_edge:\n                    self._road_id_to_edge[road_id] = dict()\n                if section_id not in self._road_id_to_edge[road_id]:\n                    self._road_id_to_edge[road_id][section_id] = dict()\n                n1 = self._id_map[exit_xyz]\n                n2 = -1*count_loose_ends\n                self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2)\n                next_wp = end_wp.next(hop_resolution)\n                path = []\n                while next_wp is not None and next_wp \\\n                        and next_wp[0].road_id == road_id \\\n                        and next_wp[0].section_id == section_id \\\n                        and next_wp[0].lane_id == lane_id:\n                    path.append(next_wp[0])\n                    next_wp = next_wp[0].next(hop_resolution)\n                if path:\n                    n2_xyz = (path[-1].transform.location.x,\n                              path[-1].transform.location.y,\n                              path[-1].transform.location.z)\n                    self._graph.add_node(n2, vertex=n2_xyz)\n                    self._graph.add_edge(\n                        n1, n2,\n                        length=len(path) + 1, path=path,\n                        entry_waypoint=end_wp, exit_waypoint=path[-1],\n                        entry_vector=None, exit_vector=None, net_vector=None,\n                        intersection=end_wp.is_junction, type=RoadOption.LANEFOLLOW)\n\n    def _lane_change_link(self):\n        \"\"\"\n        This method places zero cost links in the topology graph\n        representing availability of lane changes.\n        \"\"\"\n\n        for segment in self._topology:\n            left_found, right_found = False, False\n\n            for waypoint in segment['path']:\n                if not segment['entry'].is_junction:\n                    next_waypoint, next_road_option, next_segment = None, None, None\n\n                    if waypoint.right_lane_marking.lane_change & carla.LaneChange.Right and not right_found:\n                        next_waypoint = waypoint.get_right_lane()\n                        if next_waypoint is not None \\\n                                and next_waypoint.lane_type == carla.LaneType.Driving \\\n                                and waypoint.road_id == next_waypoint.road_id:\n                            next_road_option = RoadOption.CHANGELANERIGHT\n                            next_segment = self._localize(next_waypoint.transform.location)\n                            if next_segment is not None:\n                                self._graph.add_edge(\n                                    self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint,\n                                    exit_waypoint=next_waypoint, intersection=False, exit_vector=None,\n                                    path=[], length=0, type=next_road_option, change_waypoint=next_waypoint)\n                                right_found = True\n                    if waypoint.left_lane_marking.lane_change & carla.LaneChange.Left and not left_found:\n                        next_waypoint = waypoint.get_left_lane()\n                        if next_waypoint is not None \\\n                                and next_waypoint.lane_type == carla.LaneType.Driving \\\n                                and waypoint.road_id == next_waypoint.road_id:\n                            next_road_option = RoadOption.CHANGELANELEFT\n                            next_segment = self._localize(next_waypoint.transform.location)\n                            if next_segment is not None:\n                                self._graph.add_edge(\n                                    self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint,\n                                    exit_waypoint=next_waypoint, intersection=False, exit_vector=None,\n                                    path=[], length=0, type=next_road_option, change_waypoint=next_waypoint)\n                                left_found = True\n                if left_found and right_found:\n                    break\n\n    def _localize(self, location):\n        \"\"\"\n        This function finds the road segment that a given location\n        is part of, returning the edge it belongs to\n        \"\"\"\n        waypoint = self._wmap.get_waypoint(location)\n        edge = None\n        try:\n            edge = self._road_id_to_edge[waypoint.road_id][waypoint.section_id][waypoint.lane_id]\n        except KeyError:\n            pass\n        return edge\n\n    def _distance_heuristic(self, n1, n2):\n        \"\"\"\n        Distance heuristic calculator for path searching\n        in self._graph\n        \"\"\"\n        l1 = np.array(self._graph.nodes[n1]['vertex'])\n        l2 = np.array(self._graph.nodes[n2]['vertex'])\n        return np.linalg.norm(l1-l2)\n\n    def _path_search(self, origin, destination):\n        \"\"\"\n        This function finds the shortest path connecting origin and destination\n        using A* search with distance heuristic.\n        origin      :   carla.Location object of start position\n        destination :   carla.Location object of of end position\n        return      :   path as list of node ids (as int) of the graph self._graph\n        connecting origin and destination\n        \"\"\"\n        start, end = self._localize(origin), self._localize(destination)\n\n        route = nx.astar_path(\n            self._graph, source=start[0], target=end[0],\n            heuristic=self._distance_heuristic, weight='length')\n        route.append(end[1])\n        return route\n\n    def _successive_last_intersection_edge(self, index, route):\n        \"\"\"\n        This method returns the last successive intersection edge\n        from a starting index on the route.\n        This helps moving past tiny intersection edges to calculate\n        proper turn decisions.\n        \"\"\"\n\n        last_intersection_edge = None\n        last_node = None\n        for node1, node2 in [(route[i], route[i+1]) for i in range(index, len(route)-1)]:\n            candidate_edge = self._graph.edges[node1, node2]\n            if node1 == route[index]:\n                last_intersection_edge = candidate_edge\n            if candidate_edge['type'] == RoadOption.LANEFOLLOW and candidate_edge['intersection']:\n                last_intersection_edge = candidate_edge\n                last_node = node2\n            else:\n                break\n\n        return last_node, last_intersection_edge\n\n    def _turn_decision(self, index, route, threshold=math.radians(35)):\n        \"\"\"\n        This method returns the turn decision (RoadOption) for pair of edges\n        around current index of route list\n        \"\"\"\n\n        decision = None\n        previous_node = route[index-1]\n        current_node = route[index]\n        next_node = route[index+1]\n        next_edge = self._graph.edges[current_node, next_node]\n        if index > 0:\n            if self._previous_decision != RoadOption.VOID \\\n                    and self._intersection_end_node > 0 \\\n                    and self._intersection_end_node != previous_node \\\n                    and next_edge['type'] == RoadOption.LANEFOLLOW \\\n                    and next_edge['intersection']:\n                decision = self._previous_decision\n            else:\n                self._intersection_end_node = -1\n                current_edge = self._graph.edges[previous_node, current_node]\n                calculate_turn = current_edge['type'] == RoadOption.LANEFOLLOW and not current_edge[\n                    'intersection'] and next_edge['type'] == RoadOption.LANEFOLLOW and next_edge['intersection']\n                if calculate_turn:\n                    last_node, tail_edge = self._successive_last_intersection_edge(index, route)\n                    self._intersection_end_node = last_node\n                    if tail_edge is not None:\n                        next_edge = tail_edge\n                    cv, nv = current_edge['exit_vector'], next_edge['exit_vector']\n                    if cv is None or nv is None:\n                        return next_edge['type']\n                    cross_list = []\n                    for neighbor in self._graph.successors(current_node):\n                        select_edge = self._graph.edges[current_node, neighbor]\n                        if select_edge['type'] == RoadOption.LANEFOLLOW:\n                            if neighbor != route[index+1]:\n                                sv = select_edge['net_vector']\n                                cross_list.append(np.cross(cv, sv)[2])\n                    next_cross = np.cross(cv, nv)[2]\n                    deviation = math.acos(np.clip(\n                        np.dot(cv, nv)/(np.linalg.norm(cv)*np.linalg.norm(nv)), -1.0, 1.0))\n                    if not cross_list:\n                        cross_list.append(0)\n                    if deviation < threshold:\n                        decision = RoadOption.STRAIGHT\n                    elif cross_list and next_cross < min(cross_list):\n                        decision = RoadOption.LEFT\n                    elif cross_list and next_cross > max(cross_list):\n                        decision = RoadOption.RIGHT\n                    elif next_cross < 0:\n                        decision = RoadOption.LEFT\n                    elif next_cross > 0:\n                        decision = RoadOption.RIGHT\n                else:\n                    decision = next_edge['type']\n\n        else:\n            decision = next_edge['type']\n\n        self._previous_decision = decision\n        return decision\n\n    def _find_closest_in_list(self, current_waypoint, waypoint_list):\n        min_distance = float('inf')\n        closest_index = -1\n        for i, waypoint in enumerate(waypoint_list):\n            distance = waypoint.transform.location.distance(\n                current_waypoint.transform.location)\n            if distance < min_distance:\n                min_distance = distance\n                closest_index = i\n\n        return closest_index\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/local_planner.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" This module contains a local planner to perform low-level waypoint following based on PID controllers. \"\"\"\n\nfrom enum import Enum\nfrom collections import deque\nimport random\n\nimport carla\nfrom agents.navigation.controller import VehiclePIDController\nfrom agents.tools.misc import draw_waypoints, get_speed\n\n\nclass RoadOption(Enum):\n    \"\"\"\n    RoadOption represents the possible topological configurations when moving from a segment of lane to other.\n\n    \"\"\"\n    VOID = -1\n    LEFT = 1\n    RIGHT = 2\n    STRAIGHT = 3\n    LANEFOLLOW = 4\n    CHANGELANELEFT = 5\n    CHANGELANERIGHT = 6\n\n\nclass LocalPlanner(object):\n    \"\"\"\n    LocalPlanner implements the basic behavior of following a\n    trajectory of waypoints that is generated on-the-fly.\n\n    The low-level motion of the vehicle is computed by using two PID controllers,\n    one is used for the lateral control and the other for the longitudinal control (cruise speed).\n\n    When multiple paths are available (intersections) this local planner makes a random choice,\n    unless a given global plan has already been specified.\n    \"\"\"\n\n    def __init__(self, vehicle, opt_dict={}):\n        \"\"\"\n        :param vehicle: actor to apply to local planner logic onto\n        :param opt_dict: dictionary of arguments with different parameters:\n            dt: time between simulation steps\n            target_speed: desired cruise speed in Km/h\n            sampling_radius: distance between the waypoints part of the plan\n            lateral_control_dict: values of the lateral PID controller\n            longitudinal_control_dict: values of the longitudinal PID controller\n            max_throttle: maximum throttle applied to the vehicle\n            max_brake: maximum brake applied to the vehicle\n            max_steering: maximum steering applied to the vehicle\n            offset: distance between the route waypoints and the center of the lane\n        \"\"\"\n        self._vehicle = vehicle\n        self._world = self._vehicle.get_world()\n        self._map = self._world.get_map()\n\n        self._vehicle_controller = None\n        self.target_waypoint = None\n        self.target_road_option = None\n\n        self._waypoints_queue = deque(maxlen=10000)\n        self._min_waypoint_queue_length = 100\n        self._stop_waypoint_creation = False\n\n        # Base parameters\n        self._dt = 1.0 / 20.0\n        self._target_speed = 20.0  # Km/h\n        self._sampling_radius = 2.0\n        self._args_lateral_dict = {'K_P': 1.95, 'K_I': 0.05, 'K_D': 0.2, 'dt': self._dt}\n        self._args_longitudinal_dict = {'K_P': 1.0, 'K_I': 0.05, 'K_D': 0, 'dt': self._dt}\n        self._max_throt = 0.75\n        self._max_brake = 0.3\n        self._max_steer = 0.8\n        self._offset = 0\n        self._base_min_distance = 3.0\n        self._follow_speed_limits = False\n\n        # Overload parameters\n        if opt_dict:\n            if 'dt' in opt_dict:\n                self._dt = opt_dict['dt']\n            if 'target_speed' in opt_dict:\n                self._target_speed = opt_dict['target_speed']\n            if 'sampling_radius' in opt_dict:\n                self._sampling_radius = opt_dict['sampling_radius']\n            if 'lateral_control_dict' in opt_dict:\n                self._args_lateral_dict = opt_dict['lateral_control_dict']\n            if 'longitudinal_control_dict' in opt_dict:\n                self._args_longitudinal_dict = opt_dict['longitudinal_control_dict']\n            if 'max_throttle' in opt_dict:\n                self._max_throt = opt_dict['max_throttle']\n            if 'max_brake' in opt_dict:\n                self._max_brake = opt_dict['max_brake']\n            if 'max_steering' in opt_dict:\n                self._max_steer = opt_dict['max_steering']\n            if 'offset' in opt_dict:\n                self._offset = opt_dict['offset']\n            if 'base_min_distance' in opt_dict:\n                self._base_min_distance = opt_dict['base_min_distance']\n            if 'follow_speed_limits' in opt_dict:\n                self._follow_speed_limits = opt_dict['follow_speed_limits']\n\n        # initializing controller\n        self._init_controller()\n\n    def reset_vehicle(self):\n        \"\"\"Reset the ego-vehicle\"\"\"\n        self._vehicle = None\n\n    def _init_controller(self):\n        \"\"\"Controller initialization\"\"\"\n        self._vehicle_controller = VehiclePIDController(self._vehicle,\n                                                        args_lateral=self._args_lateral_dict,\n                                                        args_longitudinal=self._args_longitudinal_dict,\n                                                        offset=self._offset,\n                                                        max_throttle=self._max_throt,\n                                                        max_brake=self._max_brake,\n                                                        max_steering=self._max_steer)\n\n        # Compute the current vehicle waypoint\n        current_waypoint = self._map.get_waypoint(self._vehicle.get_location())\n        self.target_waypoint, self.target_road_option = (current_waypoint, RoadOption.LANEFOLLOW)\n        self._waypoints_queue.append((self.target_waypoint, self.target_road_option))\n\n    def set_speed(self, speed):\n        \"\"\"\n        Changes the target speed\n\n        :param speed: new target speed in Km/h\n        :return:\n        \"\"\"\n        if self._follow_speed_limits:\n            print(\"WARNING: The max speed is currently set to follow the speed limits. \"\n                  \"Use 'follow_speed_limits' to deactivate this\")\n        self._target_speed = speed\n\n    def follow_speed_limits(self, value=True):\n        \"\"\"\n        Activates a flag that makes the max speed dynamically vary according to the spped limits\n\n        :param value: bool\n        :return:\n        \"\"\"\n        self._follow_speed_limits = value\n\n    def _compute_next_waypoints(self, k=1):\n        \"\"\"\n        Add new waypoints to the trajectory queue.\n\n        :param k: how many waypoints to compute\n        :return:\n        \"\"\"\n        # check we do not overflow the queue\n        available_entries = self._waypoints_queue.maxlen - len(self._waypoints_queue)\n        k = min(available_entries, k)\n\n        for _ in range(k):\n            last_waypoint = self._waypoints_queue[-1][0]\n            next_waypoints = list(last_waypoint.next(self._sampling_radius))\n\n            if len(next_waypoints) == 0:\n                break\n            elif len(next_waypoints) == 1:\n                # only one option available ==> lanefollowing\n                next_waypoint = next_waypoints[0]\n                road_option = RoadOption.LANEFOLLOW\n            else:\n                # random choice between the possible options\n                road_options_list = _retrieve_options(\n                    next_waypoints, last_waypoint)\n                road_option = random.choice(road_options_list)\n                next_waypoint = next_waypoints[road_options_list.index(\n                    road_option)]\n\n            self._waypoints_queue.append((next_waypoint, road_option))\n\n    def set_global_plan(self, current_plan, stop_waypoint_creation=True, clean_queue=True):\n        \"\"\"\n        Adds a new plan to the local planner. A plan must be a list of [carla.Waypoint, RoadOption] pairs\n        If 'clean_queue`, erases the previous plan, and if not, it is added to the old one\n        The 'stop_waypoint_creation' flag avoids creating more random waypoints\n\n        :param current_plan: list of (carla.Waypoint, RoadOption)\n        :param stop_waypoint_creation: bool\n        :param ceal_queue: bool\n        :return:\n        \"\"\"\n        if clean_queue:\n            self._waypoints_queue.clear()\n\n        # Remake the waypoints queue if the new plan has a higher length than the queue\n        new_plan_length = len(current_plan) + len(self._waypoints_queue)\n        if new_plan_length > self._waypoints_queue.maxlen:\n            new_waypoint_queue = deque(maxlen=new_plan_length)\n            for wp in self._waypoints_queue:\n                new_waypoint_queue.append(wp)\n            self._waypoints_queue = new_waypoint_queue\n\n        for elem in current_plan:\n            self._waypoints_queue.append(elem)\n\n        self._stop_waypoint_creation = stop_waypoint_creation\n\n    def run_step(self, debug=False):\n        \"\"\"\n        Execute one step of local planning which involves running the longitudinal and lateral PID controllers to\n        follow the waypoints trajectory.\n\n        :param debug: boolean flag to activate waypoints debugging\n        :return: control to be applied\n        \"\"\"\n        if self._follow_speed_limits:\n            self._target_speed = self._vehicle.get_speed_limit()\n\n        # Add more waypoints too few in the horizon\n        if not self._stop_waypoint_creation and len(self._waypoints_queue) < self._min_waypoint_queue_length:\n            self._compute_next_waypoints(k=self._min_waypoint_queue_length)\n\n        # Purge the queue of obsolete waypoints\n        veh_location = self._vehicle.get_location()\n        vehicle_speed = get_speed(self._vehicle) / 3.6\n        self._min_distance = self._base_min_distance + 0.5 *vehicle_speed\n\n        num_waypoint_removed = 0\n        for waypoint, _ in self._waypoints_queue:\n\n            if len(self._waypoints_queue) - num_waypoint_removed == 1:\n                min_distance = 1  # Don't remove the last waypoint until very close by\n            else:\n                min_distance = self._min_distance\n\n            if veh_location.distance(waypoint.transform.location) < min_distance:\n                num_waypoint_removed += 1\n            else:\n                break\n\n        if num_waypoint_removed > 0:\n            for _ in range(num_waypoint_removed):\n                self._waypoints_queue.popleft()\n\n        # Get the target waypoint and move using the PID controllers. Stop if no target waypoint\n        if len(self._waypoints_queue) == 0:\n            control = carla.VehicleControl()\n            control.steer = 0.0\n            control.throttle = 0.0\n            control.brake = 1.0\n            control.hand_brake = False\n            control.manual_gear_shift = False\n        else:\n            self.target_waypoint, self.target_road_option = self._waypoints_queue[0]\n            control = self._vehicle_controller.run_step(self._target_speed, self.target_waypoint)\n\n        if debug:\n            draw_waypoints(self._vehicle.get_world(), [self.target_waypoint], 1.0)\n\n        return control\n\n    def get_incoming_waypoint_and_direction(self, steps=3):\n        \"\"\"\n        Returns direction and waypoint at a distance ahead defined by the user.\n\n            :param steps: number of steps to get the incoming waypoint.\n        \"\"\"\n        if len(self._waypoints_queue) > steps:\n            return self._waypoints_queue[steps]\n\n        else:\n            try:\n                wpt, direction = self._waypoints_queue[-1]\n                return wpt, direction\n            except IndexError as i:\n                return None, RoadOption.VOID\n\n    def done(self):\n        \"\"\"\n        Returns whether or not the planner has finished\n\n        :return: boolean\n        \"\"\"\n        return len(self._waypoints_queue) == 0\n\n\ndef _retrieve_options(list_waypoints, current_waypoint):\n    \"\"\"\n    Compute the type of connection between the current active waypoint and the multiple waypoints present in\n    list_waypoints. The result is encoded as a list of RoadOption enums.\n\n    :param list_waypoints: list with the possible target waypoints in case of multiple options\n    :param current_waypoint: current active waypoint\n    :return: list of RoadOption enums representing the type of connection from the active waypoint to each\n             candidate in list_waypoints\n    \"\"\"\n    options = []\n    for next_waypoint in list_waypoints:\n        # this is needed because something we are linking to\n        # the beggining of an intersection, therefore the\n        # variation in angle is small\n        next_next_waypoint = next_waypoint.next(3.0)[0]\n        link = _compute_connection(current_waypoint, next_next_waypoint)\n        options.append(link)\n\n    return options\n\n\ndef _compute_connection(current_waypoint, next_waypoint, threshold=35):\n    \"\"\"\n    Compute the type of topological connection between an active waypoint (current_waypoint) and a target waypoint\n    (next_waypoint).\n\n    :param current_waypoint: active waypoint\n    :param next_waypoint: target waypoint\n    :return: the type of topological connection encoded as a RoadOption enum:\n             RoadOption.STRAIGHT\n             RoadOption.LEFT\n             RoadOption.RIGHT\n    \"\"\"\n    n = next_waypoint.transform.rotation.yaw\n    n = n % 360.0\n\n    c = current_waypoint.transform.rotation.yaw\n    c = c % 360.0\n\n    diff_angle = (n - c) % 180.0\n    if diff_angle < threshold or diff_angle > (180 - threshold):\n        return RoadOption.STRAIGHT\n    elif diff_angle > 90.0:\n        return RoadOption.LEFT\n    else:\n        return RoadOption.RIGHT\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/tools/misc.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018 Intel Labs.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" Module with auxiliary functions. \"\"\"\n\nimport math\nimport numpy as np\nimport carla\n\ndef draw_waypoints(world, waypoints, z=0.5):\n    \"\"\"\n    Draw a list of waypoints at a certain height given in z.\n\n        :param world: carla.world object\n        :param waypoints: list or iterable container with the waypoints to draw\n        :param z: height in meters\n    \"\"\"\n    for wpt in waypoints:\n        wpt_t = wpt.transform\n        begin = wpt_t.location + carla.Location(z=z)\n        angle = math.radians(wpt_t.rotation.yaw)\n        end = begin + carla.Location(x=math.cos(angle), y=math.sin(angle))\n        world.debug.draw_arrow(begin, end, arrow_size=0.3, life_time=1.0)\n\n\ndef get_speed(vehicle):\n    \"\"\"\n    Compute speed of a vehicle in Km/h.\n\n        :param vehicle: the vehicle for which speed is calculated\n        :return: speed as a float in Km/h\n    \"\"\"\n    vel = vehicle.get_velocity()\n\n    return 3.6 * math.sqrt(vel.x ** 2 + vel.y ** 2 + vel.z ** 2)\n\ndef get_trafficlight_trigger_location(traffic_light):\n    \"\"\"\n    Calculates the yaw of the waypoint that represents the trigger volume of the traffic light\n    \"\"\"\n    def rotate_point(point, radians):\n        \"\"\"\n        rotate a given point by a given angle\n        \"\"\"\n        rotated_x = math.cos(radians) * point.x - math.sin(radians) * point.y\n        rotated_y = math.sin(radians) * point.x - math.cos(radians) * point.y\n\n        return carla.Vector3D(rotated_x, rotated_y, point.z)\n\n    base_transform = traffic_light.get_transform()\n    base_rot = base_transform.rotation.yaw\n    area_loc = base_transform.transform(traffic_light.trigger_volume.location)\n    area_ext = traffic_light.trigger_volume.extent\n\n    point = rotate_point(carla.Vector3D(0, 0, area_ext.z), math.radians(base_rot))\n    point_location = area_loc + carla.Location(x=point.x, y=point.y)\n\n    return carla.Location(point_location.x, point_location.y, point_location.z)\n\n\ndef is_within_distance(target_transform, reference_transform, max_distance, angle_interval=None):\n    \"\"\"\n    Check if a location is both within a certain distance from a reference object.\n    By using 'angle_interval', the angle between the location and reference transform\n    will also be tkaen into account, being 0 a location in front and 180, one behind.\n\n    :param target_transform: location of the target object\n    :param reference_transform: location of the reference object\n    :param max_distance: maximum allowed distance\n    :param angle_interval: only locations between [min, max] angles will be considered. This isn't checked by default.\n    :return: boolean\n    \"\"\"\n    target_vector = np.array([\n        target_transform.location.x - reference_transform.location.x,\n        target_transform.location.y - reference_transform.location.y\n    ])\n    norm_target = np.linalg.norm(target_vector)\n\n    # If the vector is too short, we can simply stop here\n    if norm_target < 0.001:\n        return True\n\n    # Further than the max distance\n    if norm_target > max_distance:\n        return False\n\n    # We don't care about the angle, nothing else to check\n    if not angle_interval:\n        return True\n\n    min_angle = angle_interval[0]\n    max_angle = angle_interval[1]\n\n    fwd = reference_transform.get_forward_vector()\n    forward_vector = np.array([fwd.x, fwd.y])\n    angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))\n\n    return min_angle < angle < max_angle\n\n\ndef compute_magnitude_angle(target_location, current_location, orientation):\n    \"\"\"\n    Compute relative angle and distance between a target_location and a current_location\n\n        :param target_location: location of the target object\n        :param current_location: location of the reference object\n        :param orientation: orientation of the reference object\n        :return: a tuple composed by the distance to the object and the angle between both objects\n    \"\"\"\n    target_vector = np.array([target_location.x - current_location.x, target_location.y - current_location.y])\n    norm_target = np.linalg.norm(target_vector)\n\n    forward_vector = np.array([math.cos(math.radians(orientation)), math.sin(math.radians(orientation))])\n    d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))\n\n    return (norm_target, d_angle)\n\n\ndef distance_vehicle(waypoint, vehicle_transform):\n    \"\"\"\n    Returns the 2D distance from a waypoint to a vehicle\n\n        :param waypoint: actual waypoint\n        :param vehicle_transform: transform of the target vehicle\n    \"\"\"\n    loc = vehicle_transform.location\n    x = waypoint.transform.location.x - loc.x\n    y = waypoint.transform.location.y - loc.y\n\n    return math.sqrt(x * x + y * y)\n\n\ndef vector(location_1, location_2):\n    \"\"\"\n    Returns the unit vector from location_1 to location_2\n\n        :param location_1, location_2: carla.Location objects\n    \"\"\"\n    x = location_2.x - location_1.x\n    y = location_2.y - location_1.y\n    z = location_2.z - location_1.z\n    norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps\n\n    return [x / norm, y / norm, z / norm]\n\n\ndef compute_distance(location_1, location_2):\n    \"\"\"\n    Euclidean distance between 3D points\n\n        :param location_1, location_2: 3D points\n    \"\"\"\n    x = location_2.x - location_1.x\n    y = location_2.y - location_1.y\n    z = location_2.z - location_1.z\n    norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps\n    return norm\n\n\ndef positive(num):\n    \"\"\"\n    Return the given number if positive, else 0\n\n        :param num: value to check\n    \"\"\"\n    return num if num > 0.0 else 0.0\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/carla_mocks/carla.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides mocked CARLA classes for unittesting\n\"\"\"\n\nimport copy\n\n\nclass command:\n    blueprint = None\n\n    def SpawnActor(blueprint, point):\n        new_command = command()\n        new_command.blueprint = copy.deepcopy(blueprint)\n        return new_command\n\n    def SetSimulatePhysics(blueprint, physics):\n        return None\n\n    def FutureActor():\n        return None\n\n    def ApplyTransform():\n        return None\n\n    def SetAutopilot(actor, autopilot, port):\n        return None\n\n    def SetVehicleLightState():\n        return None\n\n    def DestroyActor(actor):\n        return None\n\n    def then(self, other_command):\n        return self\n\n\nclass CarlaBluePrint(object):\n\n    def __init__(self):\n        self.id = 0\n        self.attributes = {'role_name': ''}\n\n    def has_attribute(self, attribute_string=''):\n        return attribute_string in self.attributes\n\n    def set_attribute(self, key, value):\n        self.attributes[key] = value\n\n    def has_tag(self, tag_string=''):\n        return False\n\n\nclass CarlaBluePrintLibrary:\n    def filter(self, filterstring):\n        return [CarlaBluePrint()]\n\n    def __len__(self):\n        return 1\n\n    def find(self, filterstring):\n        return CarlaBluePrint()\n\n\nclass GeoLocation:\n    longitude = 0\n    latitude = 0\n\n\nclass Vector3D:\n    x = 0\n    y = 0\n    z = 0\n\n    def __init__(self, x=0, y=0, z=0):\n        self.x = x\n        self.y = y\n        self.z = z\n\n\nclass Location():\n    x = 0\n    y = 0\n    z = 0\n\n    def __init__(self, x=0, y=0, z=0):\n        self.x = x\n        self.y = y\n        self.z = z\n\n    def distance(self, other):\n        return 0\n\n\nclass Rotation():\n    pitch = 0\n    roll = 0\n    yaw = 0\n\n    def __init__(self, pitch=0, roll=0, yaw=0):\n        self.pitch = pitch\n        self.roll = roll\n        self.yaw = yaw\n\n    def get_forward_vector(self):\n        return Vector3D()\n\n\nclass Transform:\n    location = Location(0, 0, 0)\n    rotation = Rotation(0, 0, 0)\n\n    def __init__(self, location=Location(0, 0, 0), rotation=Rotation(0, 0, 0)):\n        self.location = location\n        self.rotation = rotation\n\n\nclass Waypoint():\n    transform = Transform(Location(), Rotation())\n    road_id = 0\n    lane_id = 0\n    s = 0\n    lane_width = 0\n\n\nclass Map:\n    name = \"\"\n\n    def get_spawn_points(self):\n        return []\n\n    def transform_to_geolocation(self, transform):\n        return GeoLocation()\n\n    def get_waypoint(self, transform):\n        return Waypoint()\n\n    def get_waypoint_xodr(self, a, b, c):\n        return Waypoint()\n\n    def get_topology(self):\n        return []\n\n\nclass TrafficLightState:\n    Red = 0\n    Green = 1\n    Yellow = 2\n    Off = 3\n\n\nclass WeatherParameters:\n    cloudiness = 0.000000\n    cloudiness = 0.000000\n    precipitation = 0.000000\n    precipitation_deposits = 0.000000\n    wind_intensity = 0.000000\n    sun_azimuth_angle = 0.000000\n    sun_altitude_angle = 0.000000\n    fog_density = 0.000000\n    fog_distance = 0.000000\n    fog_falloff = 0.000000\n    wetness = 0.000000\n    scattering_intensity = 0.000000\n    mie_scattering_scale = 0.000000\n    rayleigh_scattering_scale = 0.033100\n\n\nclass WorldSettings:\n    synchronous_mode = False\n    no_rendering_mode = False\n    fixed_delta_seconds = 0\n    substepping = True\n    max_substep_delta_time = 0.01\n    max_substeps = 10\n    max_culling_distance = 0\n    deterministic_ragdolls = False\n\n\nclass ActorList:\n\n    def __init__(self, actor_list):\n        self.actor_list = actor_list\n\n    def filter(self, filterstring):\n        return []\n\n    def __len__(self):\n        return len(self.actor_list)\n\n    def __getitem__(self, i):\n        return self.actor_list[i]\n\n\nclass Control:\n    steer = 0\n    throttle = 0\n    brake = 0\n\n\nclass Actor:\n\n    def __init__(self):\n        self.attributes = {'role_name': ''}\n        self.id = 0\n        self.type_id = None\n        self.location = Location()\n        self.rotation = Rotation()\n        self.transform = Transform(self.location, self.rotation)\n        self.is_alive = True\n\n    def get_transform(self):\n        return self.transform\n\n    def get_location(self):\n        return self.location\n\n    def get_world(self):\n        return World()\n\n    def get_control(self):\n        return Control()\n\n    def destroy(self):\n        del self\n\n    def listen(self, callback):\n        pass\n\n\nclass Walker(Actor):\n    is_walker = True\n\n\nclass Vehicle(Actor):\n    is_vehicle = True\n\n\nclass World:\n    actors = []\n\n    def get_settings(self):\n        return WorldSettings()\n\n    def get_map(self):\n        return Map()\n\n    def get_blueprint_library(self):\n        return CarlaBluePrintLibrary()\n\n    def wait_for_tick(self):\n        pass\n\n    def get_actors(self, ids=[]):\n        actor_list = []\n        for actor in self.actors:\n            if actor.id in ids:\n                actor_list.append(actor)\n\n        return ActorList(actor_list)\n\n    def try_spawn_actor(self, blueprint, spawn_point):\n        new_actor = Vehicle()\n        new_actor.attributes['role_name'] = blueprint.attributes['role_name']\n        new_actor.id = len(self.actors)\n        self.actors.append(new_actor)\n        return new_actor\n\n    def spawn_actor(self, blueprint, spawn_point, attach_to):\n        new_actor = self.try_spawn_actor(blueprint, spawn_point)\n        return new_actor\n\n\nclass Client:\n    world = World()\n\n    def load_world(self, name):\n        return None\n\n    def get_world(self):\n        return self.world\n\n    def get_trafficmanager(self, port):\n        return None\n\n    def apply_batch_sync(self, batch, sync_mode=False):\n        class Response:\n            def __init__(self, id):\n                self.actor_id = id\n                self.error = None\n\n        reponse_list = []\n        for batch_cmd in batch:\n            if batch_cmd is not None:\n                new_actor = Vehicle()\n                new_actor.attributes['role_name'] = batch_cmd.blueprint.attributes['role_name']\n                new_actor.id = len(self.world.actors)\n                self.world.actors.append(new_actor)\n                reponse_list.append(Response(new_actor.id))\n\n        return reponse_list\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tests/test_xosc_load.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides some basic unit tests for the OpenSCENARIO feature of ScenarioRunner\n\"\"\"\n\nfrom unittest import TestCase\nimport glob\nimport carla\nfrom srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenarios.open_scenario import OpenScenario\n\n\nclass TestLoadingXOSC(TestCase):\n    \"\"\"\n    Test class to load OpenSCENARIO files and test for exceptions\n    \"\"\"\n\n    def test_all_xosc(self):\n        \"\"\"\n        Load all examples OpenSCENARIO files\n        \"\"\"\n        all_test_files = glob.glob('**/srunner/examples/*.xosc', recursive=True)\n\n        for filename in all_test_files:\n            client = carla.Client()\n            config = OpenScenarioConfiguration(filename, client, {})\n            self.assertTrue(config is not None)\n            CarlaDataProvider.set_client(client)\n            ego_vehicles = []\n            for vehicle in config.ego_vehicles:\n                ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model,\n                                                                        vehicle.transform,\n                                                                        vehicle.rolename,\n                                                                        color=vehicle.color,\n                                                                        actor_category=vehicle.category))\n\n            scenario = OpenScenario(world=client.get_world(),\n                                    ego_vehicles=ego_vehicles,\n                                    config=config,\n                                    config_file=filename,\n                                    timeout=100000)\n            self.assertTrue(scenario is not None)\n\n            CarlaDataProvider.cleanup()\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/background_manager.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSeveral atomic behaviors to help with the communication with the background activity,\nremoving its interference with other scenarios\n\"\"\"\n\nimport py_trees\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import AtomicBehavior\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass ChangeRoadBehavior(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to change the parameters of the road behavior.\n    None values imply that these values won't be changed.\n\n    Args:\n        num_front_vehicles (int): Amount of vehicles in front of the ego. Can't be negative\n        num_back_vehicles (int): Amount of vehicles behind it. Can't be negative\n        switch_source (bool): (De)activatea the road sources.\n    \"\"\"\n\n    def __init__(self, num_front_vehicles=None, num_back_vehicles=None, spawn_dist=None, extra_space=None, name=\"ChangeRoadBehavior\"):\n        self._num_front = num_front_vehicles\n        self._num_back = num_back_vehicles\n        self._spawn_dist = spawn_dist\n        self._extra_space = extra_space\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\n            \"BA_ChangeRoadBehavior\", [self._num_front, self._num_back, self._spawn_dist, self._extra_space], overwrite=True\n        )\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeOppositeBehavior(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to change the parameters of the opposite road behavior.\n    None values imply that these values won't be changed\n\n    Args:\n        source_dist (float): Distance between the opposite sources and the ego vehicle. Must be positive\n        max_actors (int): Max amount of concurrent alive actors spawned by the same source. Can't be negative\n    \"\"\"\n\n    def __init__(self, source_dist=None, spawn_dist=None, active=None, name=\"ChangeOppositeBehavior\"):\n        self._source_dist = source_dist\n        self._spawn_dist = spawn_dist\n        self._active = active\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\n            \"BA_ChangeOppositeBehavior\", [self._source_dist, self._spawn_dist, self._active], overwrite=True\n        )\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeJunctionBehavior(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to change the parameters of the junction behavior.\n    None values imply that these values won't be changed\n\n    Args:\n        source_dist (float): Distance between the junctiob sources and the junction entry. Must be positive\n        max_actors (int): Max amount of concurrent alive actors spawned by the same source. Can't be negative\n    \"\"\"\n\n    def __init__(self, source_dist=None, spawn_dist=None, max_actors=None, source_perc=None, name=\"ChangeJunctionBehavior\"):\n        self._source_dist = source_dist\n        self._spawn_dist = spawn_dist\n        self._max_actors = max_actors\n        self._perc = source_perc\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\n            \"BA_ChangeJunctionBehavior\", [self._source_dist, self._spawn_dist, self._max_actors, self._perc], overwrite=True\n        )\n        return py_trees.common.Status.SUCCESS\n\n\nclass SetMaxSpeed(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that its behavior is restriced to a maximum speed\n    \"\"\"\n\n    def __init__(self, max_speed, name=\"SetMaxSpeed\"):\n        self._max_speed = max_speed\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"BA_SetMaxSpeed\", self._max_speed, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StopFrontVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that a HardBreak scenario has to be triggered.\n    'stop_duration' is the amount of time, in seconds, the vehicles will be stopped\n    \"\"\"\n\n    def __init__(self, name=\"StopFrontVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"BA_StopFrontVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StartFrontVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that a HardBreak scenario has to be triggered.\n    'stop_duration' is the amount of time, in seconds, the vehicles will be stopped\n    \"\"\"\n\n    def __init__(self, name=\"StartFrontVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"BA_StartFrontVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StopBackVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to stop the vehicles behind the ego as to\n    not interfere with the scenarios. This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, name=\"StopBackVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_StopBackVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StartBackVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to restart the vehicles behind the ego.\n    \"\"\"\n    def __init__(self, name=\"StartBackVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_StartBackVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass LeaveSpaceInFront(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that the ego needs more space in front.\n    This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, space, name=\"LeaveSpaceInFront\"):\n        self._space = space\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_LeaveSpaceInFront\", [self._space], overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass SwitchRouteSources(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to (de)activate all route sources\n    \"\"\"\n    def __init__(self, enabled=True, name=\"SwitchRouteSources\"):\n        self._enabled = enabled\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_SwitchRouteSources\", self._enabled, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass RemoveRoadLane(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to remove its actors from the given lane \n    and stop generating new ones on this lane, or recover from stopping.\n\n    Args:\n        lane_wp (carla.Waypoint): A carla.Waypoint\n        active (bool)\n    \"\"\"\n    def __init__(self, lane_wp, name=\"RemoveRoadLane\"):\n        self._lane_wp = lane_wp\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_RemoveRoadLane\", self._lane_wp, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass ReAddRoadLane(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to readd the ego road lane.\n\n    Args:\n        offset: 0 to readd the ego lane, 1 for the right side lane, -1 for the left...\n        active (bool)\n    \"\"\"\n    def __init__(self, offset, name=\"BA_ReAddRoadLane\"):\n        self._offset = offset\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_ReAddRoadLane\", self._offset, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass LeaveSpaceInFront(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that the ego needs more space in front.\n    This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, space, name=\"LeaveSpaceInFront\"):\n        self._space = space\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_LeaveSpaceInFront\", self._space, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass LeaveCrossingSpace(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that the ego needs more space in front.\n    This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, collision_wp, name=\"LeaveCrossingSpace\"):\n        self._collision_wp = collision_wp\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_LeaveCrossingSpace\", self._collision_wp, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\nclass HandleJunctionScenario(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to adapt to a junction scenario\n\n    Args:\n        clear_junction (bool): Remove all actors inside the junction, and all that enter it afterwards\n        clear_ego_entry (bool): Remove all actors part of the ego road to ensure a smooth entry of the ego to the junction.\n        remove_entries (list): list of waypoint representing a junction entry that needs to be removed\n        remove_exits (list): list of waypoint representing a junction exit that needs to be removed\n        stop_entries (bool): Stops all the junction entries\n        extend_road_exit (float): Moves the road junction actors forward to leave more space for the scenario.\n            It also deactivates the road sources.\n        active (bool)\n    \"\"\"\n    def __init__(self, clear_junction=True, clear_ego_entry=True, remove_entries=[],\n                 remove_exits=[], stop_entries=True, extend_road_exit=0,\n                 name=\"HandleJunctionScenario\"):\n        self._clear_junction = clear_junction\n        self._clear_ego_entry = clear_ego_entry\n        self._remove_entries = remove_entries\n        self._remove_exits = remove_exits\n        self._stop_entries = stop_entries\n        self._extend_road_exit = extend_road_exit\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\n            \"BA_HandleJunctionScenario\",\n            [self._clear_junction, self._clear_ego_entry, self._remove_entries,\n             self._remove_exits, self._stop_entries, self._extend_road_exit],\n            overwrite=True)\n        return py_trees.common.Status.SUCCESS\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/openscenario_parser.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a parser for scenario configuration files based on OpenSCENARIO\n\"\"\"\n\nfrom __future__ import print_function\n\nfrom distutils.util import strtobool\nimport re\nimport copy\nimport datetime\nimport math\nimport operator\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.weather_sim import Weather\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (TrafficLightStateSetter,\n                                                                      ActorTransformSetterToOSCPosition,\n                                                                      RunScript,\n                                                                      ChangeWeather,\n                                                                      ChangeAutoPilot,\n                                                                      ChangeRoadFriction,\n                                                                      ChangeActorTargetSpeed,\n                                                                      ChangeActorControl,\n                                                                      ChangeActorWaypoints,\n                                                                      ChangeActorLateralMotion,\n                                                                      ChangeActorLaneOffset,\n                                                                      SyncArrivalOSC,\n                                                                      KeepLongitudinalGap,\n                                                                      Idle,\n                                                                      ChangeParameter)\n# pylint: disable=unused-import\n# For the following includes the pylint check is disabled, as these are accessed via globals()\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest,\n                                                                     MaxVelocityTest,\n                                                                     DrivenDistanceTest,\n                                                                     AverageVelocityTest,\n                                                                     KeepLaneTest,\n                                                                     ReachedRegionTest,\n                                                                     OnSidewalkTest,\n                                                                     WrongLaneTest,\n                                                                     InRadiusRegionTest,\n                                                                     InRouteTest,\n                                                                     RouteCompletionTest,\n                                                                     RunningRedLightTest,\n                                                                     RunningStopTest,\n                                                                     OffRoadTest,\n                                                                     EndofRoadTest)\n# pylint: enable=unused-import\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               InTriggerDistanceToOSCPosition,\n                                                                               InTimeToArrivalToOSCPosition,\n                                                                               InTimeToArrivalToVehicle,\n                                                                               DriveDistance,\n                                                                               StandStill,\n                                                                               OSCStartEndCondition,\n                                                                               TriggerAcceleration,\n                                                                               RelativeVelocityToOtherActor,\n                                                                               TimeOfDayComparison,\n                                                                               TriggerVelocity,\n                                                                               WaitForTrafficLightState,\n                                                                               CheckParameter)\nfrom srunner.scenariomanager.timer import TimeOut, SimulationTimeCondition\nfrom srunner.tools.py_trees_port import oneshot_behavior\nfrom srunner.tools.scenario_helper import get_offset_transform, get_troad_from_transform\n\n\ndef oneshot_with_check(variable_name, behaviour, name=None):\n    \"\"\"\n    Check if the blackboard contains already variable_name and\n    return a oneshot_behavior for behaviour.\n    \"\"\"\n    blackboard = py_trees.blackboard.Blackboard()\n    # check if the variable_name already exists in the blackboard\n    if blackboard.get(variable_name) is not None:\n        print(\"Warning: {} is already used before. Check your XOSC for duplicated names\".format(variable_name))\n\n    return oneshot_behavior(variable_name, behaviour, name)\n\n\nclass ParameterRef:\n    \"\"\"\n    This class stores osc parameter reference in its original form.\n    Returns the converted value whenever it is used.\n    \"\"\"\n\n    def __init__(self, reference_text) -> None:\n        # TODO: (for OSC1.1) add methods(lexer and math_interpreter) to\n        #  recognize and interpret math expression from reference_text\n        self.reference_text = str(reference_text)\n\n    def is_literal(self) -> bool:\n        \"\"\"\n        Returns: True when text is a literal/number\n        \"\"\"\n        return self._is_matching(pattern=r\"(-)?\\d+(\\.\\d*)?\")\n\n    def is_parameter(self) -> bool:\n        \"\"\"\n        Returns: True when text is a parameter\n        \"\"\"\n        return self._is_matching(pattern=r\"[$][A-Za-z_][\\w]*\")\n\n    def _is_matching(self, pattern: str) -> bool:\n        \"\"\"\n        Returns: True when pattern is matching with text\n        \"\"\"\n        match = re.search(pattern, self.reference_text)\n        if match is not None:\n            matching_string = match.group()\n            return matching_string == self.reference_text\n        return False\n\n    def get_interpreted_value(self):\n        \"\"\"\n        Returns: interpreted value from reference_text\n        \"\"\"\n        if self.is_literal():\n            value = self.reference_text\n        elif self.is_parameter():\n            value = CarlaDataProvider.get_osc_global_param_value(self.reference_text)\n            if value is None:\n                raise Exception(\"Parameter '{}' is not defined\".format(self.reference_text[1:]))\n        else:\n            value = None\n        return value\n\n    def __float__(self) -> float:\n        value = self.get_interpreted_value()\n        if value is not None:\n            return float(value)\n        else:\n            raise Exception(\"could not convert '{}' to float\".format(self.reference_text))\n\n    def __int__(self) -> int:\n        value = self.get_interpreted_value()\n        if value is not None:\n            return int(float(value))\n        else:\n            raise Exception(\"could not convert '{}' to int\".format(self.reference_text))\n\n    def __str__(self) -> str:\n        value = self.get_interpreted_value()\n        return str(value) if value is not None else self.reference_text\n\n    def __repr__(self):\n        value = self.get_interpreted_value()\n        return value if value is not None else self.reference_text\n\n    def __radd__(self, other) -> bool:\n        return other + self.__float__()\n\n    def __add__(self, other) -> bool:\n        return other + self.__float__()\n\n    def __rsub__(self, other) -> bool:\n        return other - self.__float__()\n\n    def __sub__(self, other) -> bool:\n        return self.__float__() - other\n\n    def __rmul__(self, other) -> bool:\n        return other * self.__float__()\n\n    def __mul__(self, other) -> bool:\n        return other * self.__float__()\n\n    def __truediv__(self, other) -> bool:\n        return self.__float__() / other\n\n    def __rtruediv__(self, other) -> bool:\n        return other / self.__float__()\n\n    def __eq__(self, other) -> bool:\n        return other == self.__float__()\n\n    def __ne__(self, other) -> bool:\n        return other != self.__float__()\n\n    def __ge__(self, other) -> bool:\n        return self.__float__() >= other\n\n    def __le__(self, other) -> bool:\n        return self.__float__() <= other\n\n    def __gt__(self, other) -> bool:\n        return self.__float__() > other\n\n    def __lt__(self, other) -> bool:\n        return self.__float__() < other\n\n    def __GE__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() >= other\n\n    def __LE__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() <= other\n\n    def __GT__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() > other\n\n    def __LT__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() < other\n\n    def __iadd__(self, other) -> bool:\n        return self.__float__() + other\n\n    def __isub__(self, other) -> bool:\n        return self.__float__() - other\n\n    def __abs__(self):\n        return abs(self.__float__())\n\n\nclass OpenScenarioParser(object):\n\n    \"\"\"\n    Pure static class providing conversions from OpenSCENARIO elements to ScenarioRunner elements\n    \"\"\"\n    operators = {\n        \"greaterThan\": operator.gt,\n        \"lessThan\": operator.lt,\n        \"equalTo\": operator.eq,\n        \"greaterOrEqual\": operator.ge,\n        \"lessOrEqual\": operator.le,\n        \"notEqualTo\": operator.ne\n    }\n\n    actor_types = {\n        \"pedestrian\": \"walker\",\n        \"vehicle\": \"vehicle\",\n        \"miscellaneous\": \"miscellaneous\"\n    }\n\n    tl_states = {\n        \"GREEN\": carla.TrafficLightState.Green,\n        \"YELLOW\": carla.TrafficLightState.Yellow,\n        \"RED\": carla.TrafficLightState.Red,\n        \"OFF\": carla.TrafficLightState.Off,\n    }\n\n    global_osc_parameters = {}\n    use_carla_coordinate_system = False\n    osc_filepath = None\n\n    @staticmethod\n    def get_traffic_light_from_osc_name(name):\n        \"\"\"\n        Returns a carla.TrafficLight instance that matches the name given\n        \"\"\"\n        traffic_light = None\n\n        # Given by id\n        if name.startswith(\"id=\"):\n            tl_id = int(name[3:])\n            for carla_tl in CarlaDataProvider.get_all_actors().filter('traffic.traffic_light'):\n                if carla_tl.id == tl_id:\n                    traffic_light = carla_tl\n                    break\n        # Given by position\n        elif name.startswith(\"pos=\"):\n            tl_pos = name[4:]\n            pos = tl_pos.split(\",\")\n            for carla_tl in CCarlaDataProvider.get_all_actors().filter('traffic.traffic_light'):\n                carla_tl_location = carla_tl.get_transform().location\n                distance = carla_tl_location.distance(carla.Location(float(pos[0]),\n                                                                     float(pos[1]),\n                                                                     carla_tl_location.z))\n                if distance < 2.0:\n                    traffic_light = carla_tl\n                    break\n\n        if traffic_light is None:\n            raise AttributeError(\"Unknown  traffic light {}\".format(name))\n\n        return traffic_light\n\n    @staticmethod\n    def set_osc_filepath(filepath):\n        \"\"\"\n        Set path of OSC file. This is required if for example custom commands are provided with\n        relative paths.\n        \"\"\"\n        OpenScenarioParser.osc_filepath = filepath\n\n    @staticmethod\n    def set_use_carla_coordinate_system():\n        \"\"\"\n        CARLA internally uses a left-hand coordinate system (Unreal), but OpenSCENARIO and OpenDRIVE\n        are intended for right-hand coordinate system. Hence, we need to invert the coordinates, if\n        the scenario does not use CARLA coordinates, but instead right-hand coordinates.\n        \"\"\"\n        OpenScenarioParser.use_carla_coordinate_system = True\n\n    @staticmethod\n    def set_parameters(xml_tree, additional_parameter_dict=None):\n        \"\"\"\n        Parse the xml_tree, and replace all parameter references\n        with the actual values.\n\n        Note: Parameter names must not start with \"$\", however when referencing a parameter the\n              reference has to start with \"$\".\n              https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#_re_use_mechanisms\n\n        Args:\n            xml_tree: Containing all nodes that should be updated\n            additional_parameter_dict (dictionary): Additional parameters as dict (key, value). Optional.\n\n        returns:\n            updated xml_tree, dictonary containing all parameters and their values\n        \"\"\"\n\n        parameter_dict = {}\n        parameters = xml_tree.find('ParameterDeclarations')\n\n        if parameters is None and not parameter_dict:\n            return xml_tree, parameter_dict\n\n        if parameters is None:\n            parameters = []\n\n        for parameter in parameters:\n            name = parameter.attrib.get('name')\n            value = parameter.attrib.get('value')\n            parameter_dict[name] = value\n\n        # overwrite parameters in parameters_dict by additional_parameters_dict\n        if additional_parameter_dict is not None:\n            parameter_dict = dict(list(parameter_dict.items()) + list(additional_parameter_dict.items()))\n\n        return xml_tree, parameter_dict\n\n    @staticmethod\n    def set_global_parameters(parameter_dict):\n        \"\"\"\n        Set global_osc_parameter dictionary\n\n        Args:\n            parameter_dict (Dictionary): Input for global_osc_parameter\n        \"\"\"\n        OpenScenarioParser.global_osc_parameters = parameter_dict\n        CarlaDataProvider.update_osc_global_params(parameter_dict)\n\n    @staticmethod\n    def get_catalog_entry(catalogs, catalog_reference):\n        \"\"\"\n        Get catalog entry referenced by catalog_reference included correct parameter settings\n\n        Args:\n            catalogs (Dictionary of dictionaries): List of all catalogs and their entries\n            catalog_reference (XML ElementTree): Reference containing the exact catalog to be used\n\n        returns:\n            Catalog entry (XML ElementTree)\n        \"\"\"\n        entry_name = str(ParameterRef(catalog_reference.attrib.get(\"entryName\")))\n        entry = catalogs[catalog_reference.attrib.get(\"catalogName\")][entry_name]\n        entry_copy = copy.deepcopy(entry)\n        catalog_copy = copy.deepcopy(catalog_reference)\n        entry = OpenScenarioParser.assign_catalog_parameters(entry_copy, catalog_copy)\n\n        return entry\n\n    @staticmethod\n    def assign_catalog_parameters(entry_instance, catalog_reference):\n        \"\"\"\n        Parse catalog_reference, and replace all parameter references\n        in entry_instance by the values provided in catalog_reference.\n\n        Not to be used from outside this class.\n\n        Args:\n            entry_instance (XML ElementTree): Entry to be updated\n            catalog_reference (XML ElementTree): Reference containing the exact parameter values\n\n        returns:\n            updated entry_instance with updated parameter values\n        \"\"\"\n\n        parameter_dict = {}\n        for elem in entry_instance.iter():\n            if elem.find('ParameterDeclarations') is not None:\n                parameters = elem.find('ParameterDeclarations')\n                for parameter in parameters:\n                    name = parameter.attrib.get('name')\n                    value = parameter.attrib.get('value')\n                    parameter_dict[name] = value\n\n        for parameter_assignments in catalog_reference.iter(\"ParameterAssignments\"):\n            for parameter_assignment in parameter_assignments.iter(\"ParameterAssignment\"):\n                parameter = parameter_assignment.attrib.get(\"parameterRef\")\n                value = parameter_assignment.attrib.get(\"value\")\n                parameter_dict[parameter] = value\n\n        for node in entry_instance.iter():\n            for key in node.attrib:\n                for param in sorted(parameter_dict, key=len, reverse=True):\n                    if \"$\" + param in node.attrib[key]:\n                        node.attrib[key] = node.attrib[key].replace(\"$\" + param, parameter_dict[param])\n\n        OpenScenarioParser.set_parameters(entry_instance, OpenScenarioParser.global_osc_parameters)\n\n        return entry_instance\n\n    @staticmethod\n    def get_friction_from_env_action(xml_tree, catalogs):\n        \"\"\"\n        Extract the CARLA road friction coefficient from an OSC EnvironmentAction\n\n        Args:\n            xml_tree: Containing the EnvironmentAction,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the EnvironmentAction\n\n        returns:\n           friction (float)\n        \"\"\"\n\n        if xml_tree.findall('.//EnvironmentAction'):\n            node = xml_tree.findall('.//EnvironmentAction')[0]\n            set_environment = next(node.iter(\"EnvironmentAction\"))\n        else:\n            return 1.0\n\n        if sum(1 for _ in set_environment.iter(\"Weather\")) != 0:\n            environment = set_environment.find(\"Environment\")\n        elif set_environment.find(\"CatalogReference\") is not None:\n            catalog_reference = set_environment.find(\"CatalogReference\")\n            environment = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference)\n\n        friction = 1.0\n\n        road_condition = environment.iter(\"RoadCondition\")\n        for condition in road_condition:\n            friction = condition.attrib.get('frictionScaleFactor')\n\n        return friction\n\n    @staticmethod\n    def get_weather_from_env_action(xml_tree, catalogs):\n        \"\"\"\n        Extract the CARLA weather parameters from an OSC EnvironmentAction\n\n        Args:\n            xml_tree: Containing the EnvironmentAction,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the EnvironmentAction\n\n        returns:\n           Weather (srunner.scenariomanager.weather_sim.Weather)\n        \"\"\"\n\n        if xml_tree.findall('.//EnvironmentAction'):\n            node = xml_tree.findall('.//EnvironmentAction')[0]\n            set_environment = next(node.iter(\"EnvironmentAction\"))\n        else:\n            return Weather(carla.WeatherParameters())\n\n        if sum(1 for _ in set_environment.iter(\"Weather\")) != 0:\n            environment = set_environment.find(\"Environment\")\n        elif set_environment.find(\"CatalogReference\") is not None:\n            catalog_reference = set_environment.find(\"CatalogReference\")\n            environment = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference)\n\n        weather = environment.find(\"Weather\")\n        sun = weather.find(\"Sun\")\n\n        carla_weather = carla.WeatherParameters()\n        carla_weather.sun_azimuth_angle = math.degrees(float(sun.attrib.get('azimuth', 0)))\n        carla_weather.sun_altitude_angle = math.degrees(float(sun.attrib.get('elevation', 0)))\n        carla_weather.cloudiness = 100 - float(sun.attrib.get('intensity', 0)) * 100\n        fog = weather.find(\"Fog\")\n        carla_weather.fog_distance = float(fog.attrib.get('visualRange', 'inf'))\n        if carla_weather.fog_distance < 1000:\n            carla_weather.fog_density = 100\n        carla_weather.precipitation = 0\n        carla_weather.precipitation_deposits = 0\n        carla_weather.wetness = 0\n        carla_weather.wind_intensity = 30.0\n        precepitation = weather.find(\"Precipitation\")\n        if precepitation.attrib.get('precipitationType') == \"rain\":\n            carla_weather.precipitation = float(precepitation.attrib.get('intensity')) * 100\n            carla_weather.precipitation_deposits = 100  # if it rains, make the road wet\n            carla_weather.wetness = carla_weather.precipitation\n        elif precepitation.attrib.get('type') == \"snow\":\n            raise AttributeError(\"CARLA does not support snow precipitation\")\n\n        time_of_day = environment.find(\"TimeOfDay\")\n        weather_animation = strtobool(time_of_day.attrib.get(\"animation\"))\n        time = time_of_day.attrib.get(\"dateTime\")\n        dtime = datetime.datetime.strptime(time, \"%Y-%m-%dT%H:%M:%S\")\n\n        return Weather(carla_weather, dtime, weather_animation)\n\n    @staticmethod\n    def get_controller(xml_tree, catalogs):\n        \"\"\"\n        Extract the object controller from the OSC XML or a catalog\n\n        Args:\n            xml_tree: Containing the controller information,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the EnvironmentAction\n\n        returns:\n           module: Python module containing the controller implementation\n           args: Dictonary with (key, value) parameters for the controller\n        \"\"\"\n\n        assign_action = next(xml_tree.iter(\"AssignControllerAction\"))\n\n        properties = None\n        if assign_action.find('Controller') is not None:\n            properties = assign_action.find('Controller').find('Properties')\n        elif assign_action.find(\"CatalogReference\") is not None:\n            catalog_reference = assign_action.find(\"CatalogReference\")\n            properties = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference).find('Properties')\n\n        module = None\n        args = {}\n        for prop in properties:\n            if prop.attrib.get('name') == \"module\":\n                module = prop.attrib.get('value')\n            else:\n                args[prop.attrib.get('name')] = prop.attrib.get('value')\n\n        override_action = xml_tree.find('OverrideControllerValueAction')\n        for child in override_action:\n            if strtobool(child.attrib.get('active')):\n                raise NotImplementedError(\"Controller override actions are not yet supported\")\n\n        return module, args\n\n    @staticmethod\n    def get_route(xml_tree, catalogs):\n        \"\"\"\n        Extract the route from the OSC XML or a catalog\n\n        Args:\n            xml_tree: Containing the route information,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the Route\n\n        returns:\n           waypoints: List of route waypoints = (waypoint, routing strategy)\n                      where the strategy is a string indicating if the fastest/shortest/etc.\n                      route should be used.\n        \"\"\"\n        route = None\n\n        if xml_tree.find('Route') is not None:\n            route = xml_tree.find('Route')\n        elif xml_tree.find('CatalogReference') is not None:\n            catalog_reference = xml_tree.find(\"CatalogReference\")\n            route = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference)\n        else:\n            raise AttributeError(\"Unknown private FollowRoute action\")\n\n        waypoints = []\n        if route is not None:\n            for waypoint in route.iter('Waypoint'):\n                position = waypoint.find('Position')\n                routing_option = str(waypoint.attrib.get('routeStrategy'))\n                waypoints.append((position, routing_option))\n        else:\n            raise AttributeError(\"No waypoints has been set\")\n\n        return waypoints\n\n    @staticmethod\n    def convert_position_to_transform(position, actor_list=None):\n        \"\"\"\n        Convert an OpenScenario position into a CARLA transform\n\n        Not supported: RoutePosition\n        \"\"\"\n\n        if position.find('WorldPosition') is not None:\n            world_pos = position.find('WorldPosition')\n            x = float(ParameterRef(world_pos.attrib.get('x', 0)))\n            y = float(ParameterRef(world_pos.attrib.get('y', 0)))\n            z = float(ParameterRef(world_pos.attrib.get('z', 0)))\n            yaw = math.degrees(float(ParameterRef(world_pos.attrib.get('h', 0))))\n            pitch = math.degrees(float(ParameterRef(world_pos.attrib.get('p', 0))))\n            roll = math.degrees(float(ParameterRef(world_pos.attrib.get('r', 0))))\n            if not OpenScenarioParser.use_carla_coordinate_system:\n                y = y * (-1.0)\n                yaw = yaw * (-1.0)\n            return carla.Transform(carla.Location(x=x, y=y, z=z), carla.Rotation(yaw=yaw, pitch=pitch, roll=roll))\n\n        elif ((position.find('RelativeWorldPosition') is not None) or\n              (position.find('RelativeObjectPosition') is not None) or\n              (position.find('RelativeLanePosition') is not None) or\n              (position.find('RelativeRoadPosition') is not None)):\n\n            if position.find('RelativeWorldPosition') is not None:\n                rel_pos = position.find('RelativeWorldPosition')\n            if position.find('RelativeObjectPosition') is not None:\n                rel_pos = position.find('RelativeObjectPosition')\n            if position.find('RelativeLanePosition') is not None:\n                rel_pos = position.find('RelativeLanePosition')\n            if position.find('RelativeRoadPosition') is not None:\n                rel_pos = position.find('RelativeRoadPosition')\n\n            # get relative object and relative position\n            obj = rel_pos.attrib.get('entityRef')\n            obj_actor = None\n            actor_transform = None\n\n            if actor_list is not None:\n                for actor in actor_list:\n                    if actor.rolename == obj:\n                        obj_actor = actor\n                        actor_transform = actor.transform\n            else:\n                for actor in CarlaDataProvider.get_all_actors():\n                    if 'role_name' in actor.attributes and actor.attributes['role_name'] == obj:\n                        obj_actor = actor\n                        actor_transform = obj_actor.get_transform()\n                        break\n\n            if obj_actor is None or actor_transform is None:\n                raise AttributeError(\"Object '{}' provided as position reference is not known\".format(obj))\n\n            # calculate orientation h, p, r\n            is_absolute = False\n            dyaw = 0\n            dpitch = 0\n            droll = 0\n            if rel_pos.find('Orientation') is not None:\n                orientation = rel_pos.find('Orientation')\n                is_absolute = (orientation.attrib.get('type') == \"absolute\")\n                dyaw = math.degrees(float(ParameterRef(orientation.attrib.get('h', 0))))\n                dpitch = math.degrees(float(ParameterRef(orientation.attrib.get('p', 0))))\n                droll = math.degrees(float(ParameterRef(orientation.attrib.get('r', 0))))\n\n            if not OpenScenarioParser.use_carla_coordinate_system:\n                dyaw = dyaw * (-1.0)\n\n            yaw = actor_transform.rotation.yaw\n            pitch = actor_transform.rotation.pitch\n            roll = actor_transform.rotation.roll\n\n            if not is_absolute:\n                yaw = yaw + dyaw\n                pitch = pitch + dpitch\n                roll = roll + droll\n            else:\n                yaw = dyaw\n                pitch = dpitch\n                roll = droll\n\n            # calculate location x, y, z\n            # dx, dy, dz\n            if ((position.find('RelativeWorldPosition') is not None) or\n                    (position.find('RelativeObjectPosition') is not None)):\n                dx = float(ParameterRef(rel_pos.attrib.get('dx', 0)))\n                dy = float(ParameterRef(rel_pos.attrib.get('dy', 0)))\n                dz = float(ParameterRef(rel_pos.attrib.get('dz', 0)))\n\n                if not OpenScenarioParser.use_carla_coordinate_system:\n                    dy = dy * (-1.0)\n\n                x = actor_transform.location.x + dx\n                y = actor_transform.location.y + dy\n                z = actor_transform.location.z + dz\n\n                transform = carla.Transform(carla.Location(x=x, y=y, z=z),\n                                            carla.Rotation(yaw=yaw, pitch=pitch, roll=roll))\n\n            elif position.find('RelativeLanePosition') is not None:\n                dlane = float(ParameterRef(rel_pos.attrib.get('dLane')))\n                ds = float(ParameterRef(rel_pos.attrib.get('ds')))\n                offset = float(ParameterRef(rel_pos.attrib.get('offset', 0.0)))\n\n                carla_map = CarlaDataProvider.get_map()\n                relative_waypoint = carla_map.get_waypoint(actor_transform.location)\n\n                road_id, ref_lane_id, ref_s = relative_waypoint.road_id, relative_waypoint.lane_id, relative_waypoint.s\n                target_lane_id = int(ref_lane_id + dlane)\n                waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, target_lane_id, ref_s)\n                if waypoint is not None:\n                    if ds < 0:\n                        ds = (-1.0) * ds\n                        waypoint = waypoint.previous(ds)[-1]\n                    else:\n                        waypoint = waypoint.next(ds)[-1]\n\n                if waypoint is None:\n                    raise AttributeError(\"RelativeLanePosition \" +\n                                         \"'roadId={} with ds={} and lane_id={}' does not exist\".format(road_id,\n                                                                                                       ds,\n                                                                                                       target_lane_id))\n\n                transform = waypoint.transform\n                transform.rotation.yaw = yaw\n                transform.rotation.pitch = pitch\n                transform.rotation.roll = roll\n\n                # Adapt transform according to offset\n                if abs(offset) == waypoint.lane_width:\n                    # if the offset position is exactly on lane edge its difficult to find out which lane its on.\n                    # so, when offset is on lane edge/corner adjust it to stay inside the lane\n                    # if user wants to offset out of lane then make sure offset > waypoint.lane_width\n                    if offset > 0:\n                        offset = offset - 0.05\n                    elif offset < 0:\n                        offset = offset + 0.05\n                transform = get_offset_transform(transform, offset)\n            elif position.find('RelativeRoadPosition') is not None:\n                ds = float(ParameterRef(rel_pos.attrib.get('ds')))\n                dt = float(ParameterRef(rel_pos.attrib.get('dt', 0.0)))\n                troad = get_troad_from_transform\n\n                carla_map = CarlaDataProvider.get_map()\n                relative_waypoint = carla_map.get_waypoint(actor_transform.location)\n\n                road_id, ref_lane_id, ref_s = relative_waypoint.road_id, relative_waypoint.lane_id, relative_waypoint.s\n                target_t, target_s = troad(relative_waypoint.transform) - troad(actor_transform) + dt, ref_s + ds\n                waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, ref_lane_id, target_s)\n                if waypoint is None:\n                    raise AttributeError(\"RelativeRoadPosition 'roadId={} with s={} and t={}' does not exist\".format(\n                        road_id, target_s, target_t))\n\n                transform = waypoint.transform\n                transform.rotation.yaw = yaw\n                transform.rotation.pitch = pitch\n                transform.rotation.roll = roll\n                transform = get_offset_transform(transform, target_t)\n\n            return transform\n\n        elif position.find('RoadPosition') is not None:\n            road_pos = position.find('RoadPosition')\n            road_id = int(ParameterRef(road_pos.attrib.get('roadId', 0)))\n            t = float(ParameterRef(road_pos.attrib.get('t', 0)))\n            s = float(ParameterRef(road_pos.attrib.get('s', 0)))\n\n            waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, 0, s)\n            if waypoint is None:\n                raise AttributeError(\"RoadPosition 'roadId={} with s={} and t={}' does not exist\".format(road_id, s, t))\n\n            transform = waypoint.transform\n\n            if road_pos.find('Orientation') is not None:\n                orientation = road_pos.find('Orientation')\n                dyaw = math.degrees(float(ParameterRef(orientation.attrib.get('h', 0))))\n                dpitch = math.degrees(float(ParameterRef(orientation.attrib.get('p', 0))))\n                droll = math.degrees(float(ParameterRef(orientation.attrib.get('r', 0))))\n\n                if not OpenScenarioParser.use_carla_coordinate_system:\n                    dyaw = dyaw * (-1.0)\n\n                transform.rotation.yaw = transform.rotation.yaw + dyaw\n                transform.rotation.pitch = transform.rotation.pitch + dpitch\n                transform.rotation.roll = transform.rotation.roll + droll\n\n            if not OpenScenarioParser.use_carla_coordinate_system:\n                # multiply -1 because unlike offset t road is -ve for right side\n                t = -1*t\n            transform = get_offset_transform(transform, t)\n            return transform\n\n        elif position.find('LanePosition') is not None:\n            lane_pos = position.find('LanePosition')\n            road_id = int(ParameterRef(lane_pos.attrib.get('roadId', 0)))\n            lane_id = int(ParameterRef(lane_pos.attrib.get('laneId', 0)))\n            offset = float(ParameterRef(lane_pos.attrib.get('offset', 0)))\n            s = float(ParameterRef(lane_pos.attrib.get('s', 0)))\n            waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, lane_id, s)\n            if waypoint is None:\n                raise AttributeError(\"LanePosition 'roadId={}, laneId={}, s={}, offset={}' does not exist\".format(\n                    road_id, lane_id, s, offset))\n\n            transform = waypoint.transform\n            if lane_pos.find('Orientation') is not None:\n                orientation = lane_pos.find('Orientation')\n                dyaw = math.degrees(float(ParameterRef(orientation.attrib.get('h', 0))))\n                dpitch = math.degrees(float(ParameterRef(orientation.attrib.get('p', 0))))\n                droll = math.degrees(float(ParameterRef(orientation.attrib.get('r', 0))))\n\n                if not OpenScenarioParser.use_carla_coordinate_system:\n                    dyaw = dyaw * (-1.0)\n\n                transform.rotation.yaw = transform.rotation.yaw + dyaw\n                transform.rotation.pitch = transform.rotation.pitch + dpitch\n                transform.rotation.roll = transform.rotation.roll + droll\n\n            if offset != 0:\n                forward_vector = transform.rotation.get_forward_vector()\n                orthogonal_vector = carla.Vector3D(x=-forward_vector.y, y=forward_vector.x, z=forward_vector.z)\n                transform.location.x = transform.location.x + offset * orthogonal_vector.x\n                transform.location.y = transform.location.y + offset * orthogonal_vector.y\n\n            return transform\n        elif position.find('RoutePosition') is not None:\n            raise NotImplementedError(\"Route positions are not yet supported\")\n        else:\n            raise AttributeError(\"Unknown position\")\n\n    @staticmethod\n    def convert_condition_to_atomic(condition, actor_list):\n        \"\"\"\n        Convert an OpenSCENARIO condition into a Behavior/Criterion atomic\n\n        If there is a delay defined in the condition, then the condition is checked after the delay time\n        passed by, e.g. <Condition name=\"\" delay=\"5\">.\n\n        Note: Not all conditions are currently supported.\n        \"\"\"\n\n        atomic = None\n        delay_atomic = None\n        condition_name = condition.attrib.get('name')\n\n        if condition.attrib.get('delay') is not None and float(condition.attrib.get('delay')) != 0:\n            delay = float(condition.attrib.get('delay'))\n            delay_atomic = TimeOut(delay)\n\n        if condition.find('ByEntityCondition') is not None:\n\n            trigger_actor = None    # A-priori validation ensures that this will be not None\n            triggered_actor = None\n\n            for triggering_entities in condition.find('ByEntityCondition').iter('TriggeringEntities'):\n                for entity in triggering_entities.iter('EntityRef'):\n                    for actor in actor_list:\n                        if actor is not None and entity.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            trigger_actor = actor\n                            break\n\n            for entity_condition in condition.find('ByEntityCondition').iter('EntityCondition'):\n                if entity_condition.find('EndOfRoadCondition') is not None:\n                    end_road_condition = entity_condition.find('EndOfRoadCondition')\n                    condition_duration = ParameterRef(end_road_condition.attrib.get('duration'))\n                    atomic_cls = py_trees.meta.inverter(EndofRoadTest)\n                    atomic = atomic_cls(trigger_actor, condition_duration, terminate_on_failure=True,\n                                        name=condition_name)\n                elif entity_condition.find('CollisionCondition') is not None:\n\n                    collision_condition = entity_condition.find('CollisionCondition')\n\n                    if collision_condition.find('EntityRef') is not None:\n                        collision_entity = collision_condition.find('EntityRef')\n\n                        for actor in actor_list:\n                            if collision_entity.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                                triggered_actor = actor\n                                break\n\n                        if triggered_actor is None:\n                            raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                                collision_condition.attrib.get('entityRef', None)))\n\n                        atomic_cls = py_trees.meta.inverter(CollisionTest)\n                        atomic = atomic_cls(trigger_actor, other_actor=triggered_actor, terminate_on_failure=True,\n                                            name=condition_name)\n\n                    elif collision_condition.find('ByType') is not None:\n                        collision_type = collision_condition.find('ByType').attrib.get('type', None)\n\n                        triggered_type = OpenScenarioParser.actor_types[collision_type]\n\n                        atomic_cls = py_trees.meta.inverter(CollisionTest)\n                        atomic = atomic_cls(trigger_actor, other_actor_type=triggered_type, terminate_on_failure=True,\n                                            name=condition_name)\n\n                    else:\n                        atomic_cls = py_trees.meta.inverter(CollisionTest)\n                        atomic = atomic_cls(trigger_actor, terminate_on_failure=True, name=condition_name)\n\n                elif entity_condition.find('OffroadCondition') is not None:\n                    off_condition = entity_condition.find('OffroadCondition')\n                    condition_duration = ParameterRef(off_condition.attrib.get('duration'))\n                    atomic_cls = py_trees.meta.inverter(OffRoadTest)\n                    atomic = atomic_cls(trigger_actor, condition_duration, terminate_on_failure=True,\n                                        name=condition_name)\n                elif entity_condition.find('TimeHeadwayCondition') is not None:\n                    headtime_condition = entity_condition.find('TimeHeadwayCondition')\n\n                    condition_value = ParameterRef(headtime_condition.attrib.get('value'))\n\n                    condition_rule = headtime_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    condition_freespace = strtobool(headtime_condition.attrib.get('freespace', False))\n                    condition_along_route = strtobool(headtime_condition.attrib.get('alongRoute', False))\n\n                    for actor in actor_list:\n                        if headtime_condition.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            triggered_actor = actor\n                            break\n                    if triggered_actor is None:\n                        raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                            headtime_condition.attrib.get('entityRef', None)))\n\n                    atomic = InTimeToArrivalToVehicle(\n                        trigger_actor, triggered_actor, condition_value, condition_freespace,\n                        condition_along_route, condition_operator, condition_name\n                    )\n\n                elif entity_condition.find('TimeToCollisionCondition') is not None:\n                    ttc_condition = entity_condition.find('TimeToCollisionCondition')\n\n                    condition_rule = ttc_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    condition_value = ParameterRef(ttc_condition.attrib.get('value'))\n                    condition_target = ttc_condition.find('TimeToCollisionConditionTarget')\n                    entity_ref_ = condition_target.find('EntityRef')\n\n                    condition_freespace = strtobool(ttc_condition.attrib.get('freespace', False))\n                    condition_along_route = strtobool(ttc_condition.attrib.get('alongRoute', False))\n\n                    if condition_target.find('Position') is not None:\n                        position = condition_target.find('Position')\n                        atomic = InTimeToArrivalToOSCPosition(\n                            trigger_actor, position, condition_value, condition_along_route, condition_operator)\n                    else:\n                        for actor in actor_list:\n                            if entity_ref_.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                                triggered_actor = actor\n                                break\n                        if triggered_actor is None:\n                            raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                                entity_ref_.attrib.get('entityRef', None)))\n\n                        atomic = InTimeToArrivalToVehicle(\n                            trigger_actor, triggered_actor, condition_value, condition_freespace,\n                            condition_along_route, condition_operator, condition_name)\n                elif entity_condition.find('AccelerationCondition') is not None:\n                    accel_condition = entity_condition.find('AccelerationCondition')\n                    condition_value = ParameterRef(accel_condition.attrib.get('value'))\n                    condition_rule = accel_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n                    atomic = TriggerAcceleration(\n                        trigger_actor, condition_value, condition_operator, condition_name)\n                elif entity_condition.find('StandStillCondition') is not None:\n                    ss_condition = entity_condition.find('StandStillCondition')\n                    duration = ParameterRef(ss_condition.attrib.get('duration'))\n                    atomic = StandStill(trigger_actor, condition_name, duration)\n                elif entity_condition.find('SpeedCondition') is not None:\n                    spd_condition = entity_condition.find('SpeedCondition')\n                    condition_value = ParameterRef(spd_condition.attrib.get('value'))\n                    condition_rule = spd_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    atomic = TriggerVelocity(\n                        trigger_actor, condition_value, condition_operator, condition_name)\n                elif entity_condition.find('RelativeSpeedCondition') is not None:\n                    relspd_condition = entity_condition.find('RelativeSpeedCondition')\n                    condition_value = ParameterRef(relspd_condition.attrib.get('value'))\n                    condition_rule = relspd_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    for actor in actor_list:\n                        if relspd_condition.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            triggered_actor = actor\n                            break\n\n                    if triggered_actor is None:\n                        raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                            relspd_condition.attrib.get('entityRef', None)))\n\n                    atomic = RelativeVelocityToOtherActor(\n                        trigger_actor, triggered_actor, condition_value, condition_operator, condition_name)\n                elif entity_condition.find('TraveledDistanceCondition') is not None:\n                    distance_condition = entity_condition.find('TraveledDistanceCondition')\n                    distance_value = ParameterRef(distance_condition.attrib.get('value'))\n                    atomic = DriveDistance(trigger_actor, distance_value, name=condition_name)\n                elif entity_condition.find('ReachPositionCondition') is not None:\n                    rp_condition = entity_condition.find('ReachPositionCondition')\n                    distance_value = ParameterRef(rp_condition.attrib.get('tolerance'))\n                    position = rp_condition.find('Position')\n                    atomic = InTriggerDistanceToOSCPosition(\n                        trigger_actor, position, distance_value, name=condition_name)\n                elif entity_condition.find('DistanceCondition') is not None:\n                    distance_condition = entity_condition.find('DistanceCondition')\n\n                    distance_value = ParameterRef(distance_condition.attrib.get('value'))\n\n                    distance_rule = distance_condition.attrib.get('rule')\n                    distance_operator = OpenScenarioParser.operators[distance_rule]\n\n                    distance_freespace = strtobool(distance_condition.attrib.get('freespace', False))\n                    if distance_freespace:\n                        raise NotImplementedError(\n                            \"DistanceCondition: freespace attribute is currently not implemented\")\n                    distance_along_route = strtobool(distance_condition.attrib.get('alongRoute', False))\n\n                    if distance_condition.find('Position') is not None:\n                        position = distance_condition.find('Position')\n                        atomic = InTriggerDistanceToOSCPosition(\n                            trigger_actor, position, distance_value, distance_along_route,\n                            distance_operator, name=condition_name)\n\n                elif entity_condition.find('RelativeDistanceCondition') is not None:\n                    distance_condition = entity_condition.find('RelativeDistanceCondition')\n                    distance_value = ParameterRef(distance_condition.attrib.get('value'))\n\n                    distance_freespace = distance_condition.attrib.get('freespace', \"false\") == \"true\"\n                    rel_dis_type = distance_condition.attrib.get('relativeDistanceType')\n                    for actor in actor_list:\n                        if distance_condition.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            triggered_actor = actor\n                            break\n\n                    if triggered_actor is None:\n                        raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                            distance_condition.attrib.get('entityRef', None)))\n\n                    condition_rule = distance_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n                    atomic = InTriggerDistanceToVehicle(triggered_actor, trigger_actor, distance_value,\n                                                        condition_operator, distance_type=rel_dis_type,\n                                                        freespace=distance_freespace, name=condition_name)\n        elif condition.find('ByValueCondition') is not None:\n            value_condition = condition.find('ByValueCondition')\n            if value_condition.find('ParameterCondition') is not None:\n                parameter_condition = value_condition.find('ParameterCondition')\n                arg_name = parameter_condition.attrib.get('parameterRef')\n                value = ParameterRef(parameter_condition.attrib.get('value'))\n                rule = parameter_condition.attrib.get('rule')\n                if condition_name.startswith('criteria_'):\n                    if str(value) != '':\n                        arg_value = float(value)\n                    else:\n                        arg_value = 0\n                    class_name = condition_name[9:]\n                    if class_name in globals():\n                        criterion_instance = globals()[class_name]\n                    else:\n                        raise AttributeError(\n                            \"The condition {} cannot be mapped to a criterion atomic\".format(class_name))\n\n                    atomic = py_trees.composites.Parallel(\"Evaluation Criteria for multiple ego vehicles\")\n                    for triggered_actor in actor_list:\n                        if arg_name != '':\n                            atomic.add_child(criterion_instance(triggered_actor, arg_value))\n                        else:\n                            atomic.add_child(criterion_instance(triggered_actor))\n                else:\n                    atomic = CheckParameter(arg_name, value, OpenScenarioParser.operators[rule], name=condition_name)\n            elif value_condition.find('SimulationTimeCondition') is not None:\n                simtime_condition = value_condition.find('SimulationTimeCondition')\n                value = ParameterRef(simtime_condition.attrib.get('value'))\n                rule = OpenScenarioParser.operators[simtime_condition.attrib.get('rule')]\n                atomic = SimulationTimeCondition(value, comparison_operator=rule)\n            elif value_condition.find('TimeOfDayCondition') is not None:\n                tod_condition = value_condition.find('TimeOfDayCondition')\n                condition_date = tod_condition.attrib.get('dateTime')\n                condition_rule = tod_condition.attrib.get('rule')\n                condition_operator = OpenScenarioParser.operators[condition_rule]\n                atomic = TimeOfDayComparison(condition_date, condition_operator, condition_name)\n            elif value_condition.find('StoryboardElementStateCondition') is not None:\n                state_condition = value_condition.find('StoryboardElementStateCondition')\n                element_name = state_condition.attrib.get('storyboardElementRef')\n                element_type = state_condition.attrib.get('storyboardElementType')\n                state = state_condition.attrib.get('state')\n                if state == \"startTransition\":\n                    atomic = OSCStartEndCondition(element_type, element_name, rule=\"START\", name=state + \"Condition\")\n                elif state in [\"stopTransition\", \"endTransition\", \"completeState\"]:\n                    atomic = OSCStartEndCondition(element_type, element_name, rule=\"END\", name=state + \"Condition\")\n                else:\n                    raise NotImplementedError(\n                        \"Only start, stop, endTransitions and completeState are currently supported\")\n            elif value_condition.find('UserDefinedValueCondition') is not None:\n                raise NotImplementedError(\"ByValue UserDefinedValue conditions are not yet supported\")\n            elif value_condition.find('TrafficSignalCondition') is not None:\n                tl_condition = value_condition.find('TrafficSignalCondition')\n\n                name_condition = tl_condition.attrib.get('name')\n                traffic_light = OpenScenarioParser.get_traffic_light_from_osc_name(name_condition)\n\n                tl_state = tl_condition.attrib.get('state').upper()\n                if tl_state not in OpenScenarioParser.tl_states:\n                    raise KeyError(\"CARLA only supports Green, Red, Yellow or Off\")\n                state_condition = OpenScenarioParser.tl_states[tl_state]\n\n                atomic = WaitForTrafficLightState(\n                    traffic_light, state_condition, name=condition_name)\n            elif value_condition.find('TrafficSignalControllerCondition') is not None:\n                raise NotImplementedError(\"ByValue TrafficSignalController conditions are not yet supported\")\n            else:\n                raise AttributeError(\"Unknown ByValue condition\")\n\n        else:\n            raise AttributeError(\"Unknown condition\")\n\n        if delay_atomic is not None and atomic is not None:\n            new_atomic = py_trees.composites.Sequence(\"delayed sequence\")\n            new_atomic.add_child(delay_atomic)\n            new_atomic.add_child(atomic)\n        else:\n            new_atomic = atomic\n\n        return new_atomic\n\n    @staticmethod\n    def convert_maneuver_to_atomic(action, actor, actor_list, catalogs):\n        \"\"\"\n        Convert an OpenSCENARIO maneuver action into a Behavior atomic\n\n        Note not all OpenSCENARIO actions are currently supported\n        \"\"\"\n        maneuver_name = action.attrib.get('name', 'unknown')\n\n        if action.find('GlobalAction') is not None:\n            global_action = action.find('GlobalAction')\n            if global_action.find('InfrastructureAction') is not None:\n                infrastructure_action = global_action.find('InfrastructureAction').find('TrafficSignalAction')\n                if infrastructure_action.find('TrafficSignalStateAction') is not None:\n                    traffic_light_action = infrastructure_action.find('TrafficSignalStateAction')\n\n                    name_condition = traffic_light_action.attrib.get('name')\n                    traffic_light = OpenScenarioParser.get_traffic_light_from_osc_name(name_condition)\n\n                    tl_state = traffic_light_action.attrib.get('state').upper()\n                    if tl_state not in OpenScenarioParser.tl_states:\n                        raise KeyError(\"CARLA only supports Green, Red, Yellow or Off\")\n                    traffic_light_state = OpenScenarioParser.tl_states[tl_state]\n\n                    atomic = TrafficLightStateSetter(\n                        traffic_light, traffic_light_state, name=maneuver_name + \"_\" + str(traffic_light.id))\n                else:\n                    raise NotImplementedError(\"TrafficLights can only be influenced via TrafficSignalStateAction\")\n            elif global_action.find('EnvironmentAction') is not None:\n                weather_behavior = ChangeWeather(\n                    OpenScenarioParser.get_weather_from_env_action(global_action, catalogs))\n                friction_behavior = ChangeRoadFriction(\n                    OpenScenarioParser.get_friction_from_env_action(global_action, catalogs))\n\n                env_behavior = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=maneuver_name)\n\n                env_behavior.add_child(\n                    oneshot_with_check(variable_name=maneuver_name + \">WeatherUpdate\", behaviour=weather_behavior))\n                env_behavior.add_child(\n                    oneshot_with_check(variable_name=maneuver_name + \">FrictionUpdate\", behaviour=friction_behavior))\n\n                return env_behavior\n            elif global_action.find('ParameterAction') is not None:\n                parameter_action = global_action.find('ParameterAction')\n                parameter_ref = parameter_action.attrib.get('parameterRef')\n                if parameter_action.find('ModifyAction') is not None:\n                    action_rule = parameter_action.find('ModifyAction').find(\"Rule\")\n                    if action_rule.find(\"AddValue\") is not None:\n                        rule, value = '+', action_rule.find(\"AddValue\").attrib.get('value')\n                    else:\n                        rule, value = '*', action_rule.find(\"MultiplyByValue\").attrib.get('value')\n                else:\n                    rule, value = None, parameter_action.find('SetAction').attrib.get('value')\n                atomic = ChangeParameter(parameter_ref, value=ParameterRef(value), rule=rule, name=maneuver_name)\n            else:\n                raise NotImplementedError(\"Global actions are not yet supported\")\n        elif action.find('UserDefinedAction') is not None:\n            user_defined_action = action.find('UserDefinedAction')\n            if user_defined_action.find('CustomCommandAction') is not None:\n                command = user_defined_action.find('CustomCommandAction').attrib.get('type')\n                atomic = RunScript(command, base_path=OpenScenarioParser.osc_filepath, name=maneuver_name)\n        elif action.find('PrivateAction') is not None:\n            private_action = action.find('PrivateAction')\n\n            if private_action.find('LongitudinalAction') is not None:\n                private_action = private_action.find('LongitudinalAction')\n\n                if private_action.find('SpeedAction') is not None:\n                    long_maneuver = private_action.find('SpeedAction')\n\n                    # duration and distance\n                    distance = float('inf')\n                    duration = float('inf')\n                    dimension = long_maneuver.find(\"SpeedActionDynamics\").attrib.get('dynamicsDimension')\n                    if dimension == \"distance\":\n                        distance = ParameterRef(long_maneuver.find(\"SpeedActionDynamics\").attrib.get(\n                            'value', float(\"inf\")))\n                    else:\n                        duration = ParameterRef(long_maneuver.find(\"SpeedActionDynamics\").attrib.get(\n                            'value', float(\"inf\")))\n\n                    # absolute velocity with given target speed\n                    if long_maneuver.find(\"SpeedActionTarget\").find(\"AbsoluteTargetSpeed\") is not None:\n                        target_speed = ParameterRef(long_maneuver.find(\"SpeedActionTarget\").find(\n                            \"AbsoluteTargetSpeed\").attrib.get('value', 0))\n                        atomic = ChangeActorTargetSpeed(\n                            actor, float(target_speed), distance=distance, duration=duration, name=maneuver_name)\n\n                    # relative velocity to given actor\n                    if long_maneuver.find(\"SpeedActionTarget\").find(\"RelativeTargetSpeed\") is not None:\n                        relative_speed = long_maneuver.find(\"SpeedActionTarget\").find(\"RelativeTargetSpeed\")\n                        obj = relative_speed.attrib.get('entityRef')\n                        value = ParameterRef(relative_speed.attrib.get('value', 0))\n                        value_type = relative_speed.attrib.get('speedTargetValueType')\n                        continuous = bool(strtobool(relative_speed.attrib.get('continuous')))\n\n                        for traffic_actor in actor_list:\n                            if (traffic_actor is not None and 'role_name' in traffic_actor.attributes and\n                                    traffic_actor.attributes['role_name'] == obj):\n                                obj_actor = traffic_actor\n\n                        atomic = ChangeActorTargetSpeed(actor,\n                                                        target_speed=0.0,\n                                                        relative_actor=obj_actor,\n                                                        value=value,\n                                                        value_type=value_type,\n                                                        continuous=continuous,\n                                                        distance=distance,\n                                                        duration=duration,\n                                                        name=maneuver_name)\n\n                elif private_action.find('LongitudinalDistanceAction') is not None:\n                    long_dist_action = private_action.find(\"LongitudinalDistanceAction\")\n                    obj = long_dist_action.attrib.get('entityRef')\n                    for traffic_actor in actor_list:\n                        if (traffic_actor is not None and 'role_name' in traffic_actor.attributes and\n                                traffic_actor.attributes['role_name'] == obj):\n                            obj_actor = traffic_actor\n\n                    if \"distance\" in long_dist_action.attrib and \"timeGap\" not in long_dist_action.attrib:\n                        gap_type, gap = 'distance', ParameterRef(long_dist_action.attrib.get('distance'))\n                    elif \"timeGap\" in long_dist_action.attrib and \"distance\" not in long_dist_action.attrib:\n                        raise NotImplementedError(\"LongitudinalDistanceAction: timeGap is not implemented\")\n                    else:\n                        raise ValueError(\"LongitudinalDistanceAction: \" +\n                                         \"Please specify any one attribute of [distance, timeGap]\")\n\n                    constraints = long_dist_action.find('DynamicConstraints')\n                    max_speed = constraints.attrib.get('maxSpeed', None) if constraints is not None else None\n                    continues = bool(strtobool(long_dist_action.attrib.get('continuous')))\n                    freespace = bool(strtobool(long_dist_action.attrib.get('freespace')))\n                    atomic = KeepLongitudinalGap(actor, reference_actor=obj_actor, gap=gap, gap_type=gap_type,\n                                                 max_speed=max_speed, continues=continues, freespace=freespace,\n                                                 name=maneuver_name)\n                else:\n                    raise AttributeError(\"Unknown longitudinal action\")\n            elif private_action.find('LateralAction') is not None:\n                private_action = private_action.find('LateralAction')\n                if private_action.find('LaneChangeAction') is not None:\n                    # Note: LaneChangeActions are currently only supported for RelativeTargetLane\n                    lat_maneuver = private_action.find('LaneChangeAction')\n                    target_lane_rel = ParameterRef(lat_maneuver.find(\"LaneChangeTarget\").find(\n                        \"RelativeTargetLane\").attrib.get('value', 0))\n                    direction = \"left\" if target_lane_rel > 0 else \"right\"\n                    lane_changes = abs(target_lane_rel)\n                    # duration and distance\n                    distance = float('inf')\n                    duration = float('inf')\n                    dimension = lat_maneuver.find(\"LaneChangeActionDynamics\").attrib.get('dynamicsDimension')\n                    if dimension == \"distance\":\n                        distance = ParameterRef(\n                            lat_maneuver.find(\"LaneChangeActionDynamics\").attrib.get('value', float(\"inf\")))\n                    else:\n                        duration = ParameterRef(\n                            lat_maneuver.find(\"LaneChangeActionDynamics\").attrib.get('value', float(\"inf\")))\n                    atomic = ChangeActorLateralMotion(actor, direction=direction,\n                                                      distance_lane_change=distance,\n                                                      distance_other_lane=10,\n                                                      lane_changes=lane_changes,\n                                                      name=maneuver_name)\n                elif private_action.find('LaneOffsetAction') is not None:\n                    lat_maneuver = private_action.find('LaneOffsetAction')\n                    continuous = bool(strtobool(lat_maneuver.attrib.get('continuous', \"true\")))\n                    # Parsing of the different Dynamic shapes is missing\n\n                    lane_target_offset = lat_maneuver.find('LaneOffsetTarget')\n                    if lane_target_offset.find('AbsoluteTargetLaneOffset') is not None:\n                        absolute_offset = ParameterRef(\n                            lane_target_offset.find('AbsoluteTargetLaneOffset').attrib.get('value', 0))\n                        atomic = ChangeActorLaneOffset(\n                            actor, absolute_offset, continuous=continuous, name=maneuver_name)\n\n                    elif lane_target_offset.find('RelativeTargetLaneOffset') is not None:\n                        relative_target_offset = lane_target_offset.find('RelativeTargetLaneOffset')\n                        relative_offset = ParameterRef(relative_target_offset.attrib.get('value', 0))\n\n                        relative_actor = None\n                        relative_actor_name = relative_target_offset.attrib.get('entityRef', None)\n                        for _actor in actor_list:\n                            if _actor is not None and 'role_name' in _actor.attributes:\n                                if relative_actor_name == _actor.attributes['role_name']:\n                                    relative_actor = _actor\n                                    break\n                        if relative_actor is None:\n                            raise AttributeError(\"Cannot find actor '{}' for condition\".format(relative_actor_name))\n\n                        atomic = ChangeActorLaneOffset(actor, relative_offset, relative_actor,\n                                                       continuous=continuous, name=maneuver_name)\n\n                    else:\n                        raise AttributeError(\"Unknown target offset\")\n                else:\n                    raise AttributeError(\"Unknown lateral action\")\n            elif private_action.find('VisibilityAction') is not None:\n                raise NotImplementedError(\"Visibility actions are not yet supported\")\n            elif private_action.find('SynchronizeAction') is not None:\n                sync_action = private_action.find('SynchronizeAction')\n\n                master_actor = None\n                for actor_ins in actor_list:\n                    if actor_ins is not None and 'role_name' in actor_ins.attributes:\n                        if sync_action.attrib.get('masterEntityRef', None) == actor_ins.attributes['role_name']:\n                            master_actor = actor_ins\n                            break\n\n                if master_actor is None:\n                    raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                        sync_action.attrib.get('masterEntityRef', None)))\n\n                master_position = OpenScenarioParser.convert_position_to_transform(\n                    sync_action.find('TargetPositionMaster'))\n                position = OpenScenarioParser.convert_position_to_transform(sync_action.find('TargetPosition'))\n\n                if sync_action.find(\"FinalSpeed\").find(\"AbsoluteSpeed\") is not None:\n                    final_speed = ParameterRef(sync_action.find(\"FinalSpeed\").find(\n                        \"AbsoluteSpeed\").attrib.get('value', 0))\n                    atomic = SyncArrivalOSC(\n                        actor, master_actor, position, master_position, final_speed, name=maneuver_name)\n\n                # relative velocity to given actor\n                elif sync_action.find(\"FinalSpeed\").find(\"RelativeSpeedToMaster\") is not None:\n                    relative_speed = sync_action.find(\"FinalSpeed\").find(\"RelativeSpeedToMaster\")\n                    final_speed = ParameterRef(relative_speed.attrib.get('value', 0))\n                    relative_type = relative_speed.attrib.get('speedTargetValueType')\n                    atomic = SyncArrivalOSC(\n                        actor, master_actor, position, master_position, final_speed,\n                        relative_to_master=True, relative_type=relative_type, name=maneuver_name)\n                else:\n                    raise AttributeError(\"Unknown speed action\")\n            elif private_action.find('ActivateControllerAction') is not None:\n                private_action = private_action.find('ActivateControllerAction')\n                activate = strtobool(private_action.attrib.get('longitudinal'))\n                atomic = ChangeAutoPilot(actor, activate, name=maneuver_name)\n            elif private_action.find('ControllerAction') is not None:\n                controller_action = private_action.find('ControllerAction')\n                module, args = OpenScenarioParser.get_controller(controller_action, catalogs)\n                atomic = ChangeActorControl(actor, control_py_module=module, args=args,\n                                            scenario_file_path=OpenScenarioParser.osc_filepath)\n            elif private_action.find('TeleportAction') is not None:\n                teleport_action = private_action.find('TeleportAction')\n                position = teleport_action.find('Position')\n                atomic = ActorTransformSetterToOSCPosition(actor, position, name=maneuver_name)\n            elif private_action.find('RoutingAction') is not None:\n                private_action = private_action.find('RoutingAction')\n                if private_action.find('AssignRouteAction') is not None:\n                    # @TODO: How to handle relative positions here? This might chance at runtime?!\n                    route_action = private_action.find('AssignRouteAction')\n                    waypoints = OpenScenarioParser.get_route(route_action, catalogs)\n                    atomic = ChangeActorWaypoints(actor, waypoints=waypoints, name=maneuver_name)\n                elif private_action.find('FollowTrajectoryAction') is not None:\n                    raise NotImplementedError(\"Private FollowTrajectory actions are not yet supported\")\n                elif private_action.find('AcquirePositionAction') is not None:\n                    route_action = private_action.find('AcquirePositionAction')\n                    osc_position = route_action.find('Position')\n                    waypoints = [(osc_position, 'fastest')]\n                    atomic = ChangeActorWaypoints(actor, waypoints=waypoints, name=maneuver_name)\n                else:\n                    raise AttributeError(\"Unknown private routing action\")\n            else:\n                raise AttributeError(\"Unknown private action\")\n\n        else:\n            if list(action):\n                raise AttributeError(\"Unknown action: {}\".format(maneuver_name))\n            else:\n                return Idle(duration=0, name=maneuver_name)\n\n        return atomic\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/py_trees_port.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2015 Daniel Stonier\n# Copyright (c) 2020 Intel Corporation\n#\n# License: BSD\n#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE\n\n\"\"\"\nThis module provides a backport from newer py_trees releases (> 1.0)\nTo use certain features also within ScenarioRunner, which uses py_trees\nversion 0.8.x\n\"\"\"\n\nimport py_trees\n\n\nclass Decorator(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    A decorator is responsible for handling the lifecycle of a single\n    child beneath\n\n    This is taken from py_trees 1.2 to work with our current implementation\n    that uses py_trees 0.8.2\n    \"\"\"\n\n    def __init__(self, child, name):\n        \"\"\"\n        Common initialisation steps for a decorator - type checks and\n        name construction (if None is given).\n        Args:\n            name (:obj:`str`): the decorator name\n            child (:class:`~py_trees.behaviour.Behaviour`): the child to be decorated\n        Raises:\n            TypeError: if the child is not an instance of :class:`~py_trees.behaviour.Behaviour`\n        \"\"\"\n        # Checks\n        if not isinstance(child, py_trees.behaviour.Behaviour):\n            raise TypeError(\"A decorator's child must be an instance of py_trees.behaviours.Behaviour\")\n        # Initialise\n        super(Decorator, self).__init__(name=name)\n        self.children.append(child)\n        # Give a convenient alias\n        self.decorated = self.children[0]\n        self.decorated.parent = self\n\n    def tick(self):\n        \"\"\"\n        A decorator's tick is exactly the same as a normal proceedings for\n        a Behaviour's tick except that it also ticks the decorated child node.\n        Yields:\n            :class:`~py_trees.behaviour.Behaviour`: a reference to itself or one of its children\n        \"\"\"\n        self.logger.debug(\"%s.tick()\" % self.__class__.__name__)\n        # initialise just like other behaviours/composites\n        if self.status != py_trees.common.Status.RUNNING:\n            self.initialise()\n        # interrupt proceedings and process the child node\n        # (including any children it may have as well)\n        for node in self.decorated.tick():\n            yield node\n        # resume normal proceedings for a Behaviour's tick\n        new_status = self.update()\n        if new_status not in list(py_trees.common.Status):\n            self.logger.error(\n                \"A behaviour returned an invalid status, setting to INVALID [%s][%s]\" % (new_status, self.name))\n            new_status = py_trees.common.Status.INVALID\n        if new_status != py_trees.common.Status.RUNNING:\n            self.stop(new_status)\n        self.status = new_status\n        yield self\n\n    def stop(self, new_status=py_trees.common.Status.INVALID):\n        \"\"\"\n        As with other composites, it checks if the child is running\n        and stops it if that is the case.\n        Args:\n            new_status (:class:`~py_trees.common.Status`): the behaviour is transitioning to this new status\n        \"\"\"\n        self.logger.debug(\"%s.stop(%s)\" % (self.__class__.__name__, new_status))\n        self.terminate(new_status)\n        # priority interrupt handling\n        if new_status == py_trees.common.Status.INVALID:\n            self.decorated.stop(new_status)\n        # if the decorator returns SUCCESS/FAILURE and should stop the child\n        if self.decorated.status == py_trees.common.Status.RUNNING:\n            self.decorated.stop(py_trees.common.Status.INVALID)\n        self.status = new_status\n\n    def tip(self):\n        \"\"\"\n        Get the *tip* of this behaviour's subtree (if it has one) after it's last\n        tick. This corresponds to the the deepest node that was running before the\n        subtree traversal reversed direction and headed back to this node.\n        \"\"\"\n        if self.decorated.status != py_trees.common.Status.INVALID:\n            return self.decorated.tip()\n\n        return super(Decorator, self).tip()\n\n\ndef oneshot_behavior(variable_name, behaviour, name=None):\n    \"\"\"\n    This is taken from py_trees.idiom.oneshot.\n    \"\"\"\n    if not name:\n        name = behaviour.name\n\n    subtree_root = py_trees.composites.Selector(name=name)\n\n    # Initialize the variables\n    blackboard = py_trees.blackboard.Blackboard()\n    _ = blackboard.set(variable_name, False)\n\n    # Wait until the scenario has ended\n    check_flag = py_trees.blackboard.CheckBlackboardVariable(\n        name=variable_name + \" Done?\",\n        variable_name=variable_name,\n        expected_value=True,\n        clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE\n    )\n    set_flag = py_trees.blackboard.SetBlackboardVariable(\n        name=\"Mark Done\",\n        variable_name=variable_name,\n        variable_value=True\n    )\n    # If it's a sequence, don't double-nest it in a redundant manner\n    if isinstance(behaviour, py_trees.composites.Sequence):\n        behaviour.add_child(set_flag)\n        sequence = behaviour\n    else:\n        sequence = py_trees.composites.Sequence(name=\"OneShot\")\n        sequence.add_children([behaviour, set_flag])\n\n    subtree_root.add_children([check_flag, sequence])\n    return subtree_root\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/route_manipulation.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Labs.\n# authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule to manipulate the routes, by making then more or less dense (Up to a certain parameter).\nIt also contains functions to convert the CARLA world location do GPS coordinates.\n\"\"\"\n\nimport math\nimport xml.etree.ElementTree as ET\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\ndef _location_to_gps(lat_ref, lon_ref, location):\n    \"\"\"\n    Convert from world coordinates to GPS coordinates\n    :param lat_ref: latitude reference for the current map\n    :param lon_ref: longitude reference for the current map\n    :param location: location to translate\n    :return: dictionary with lat, lon and height\n    \"\"\"\n\n    EARTH_RADIUS_EQUA = 6378137.0   # pylint: disable=invalid-name\n    scale = math.cos(lat_ref * math.pi / 180.0)\n    mx = scale * lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n    my = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + lat_ref) * math.pi / 360.0))\n    mx += location.x\n    my -= location.y\n\n    lon = mx * 180.0 / (math.pi * EARTH_RADIUS_EQUA * scale)\n    lat = 360.0 * math.atan(math.exp(my / (EARTH_RADIUS_EQUA * scale))) / math.pi - 90.0\n    z = location.z\n\n    return {'lat': lat, 'lon': lon, 'z': z}\n\n\ndef location_route_to_gps(route, lat_ref, lon_ref):\n    \"\"\"\n        Locate each waypoint of the route into gps, (lat long ) representations.\n    :param route:\n    :param lat_ref:\n    :param lon_ref:\n    :return:\n    \"\"\"\n    gps_route = []\n\n    for transform, connection in route:\n        gps_point = _location_to_gps(lat_ref, lon_ref, transform.location)\n        gps_route.append((gps_point, connection))\n\n    return gps_route\n\n\ndef _get_latlon_ref(world):\n    \"\"\"\n    Convert from waypoints world coordinates to CARLA GPS coordinates\n    :return: tuple with lat and lon coordinates\n    \"\"\"\n    xodr = world.get_map().to_opendrive()\n    tree = ET.ElementTree(ET.fromstring(xodr))\n\n    # default reference\n    lat_ref = 42.0\n    lon_ref = 2.0\n\n    for opendrive in tree.iter(\"OpenDRIVE\"):\n        for header in opendrive.iter(\"header\"):\n            for georef in header.iter(\"geoReference\"):\n                if georef.text:\n                    str_list = georef.text.split(' ')\n                    for item in str_list:\n                        if '+lat_0' in item:\n                            lat_ref = float(item.split('=')[1])\n                        if '+lon_0' in item:\n                            lon_ref = float(item.split('=')[1])\n    return lat_ref, lon_ref\n\n\ndef downsample_route(route, sample_factor):\n    \"\"\"\n    Downsample the route by some factor.\n    :param route: the trajectory , has to contain the waypoints and the road options\n    :param sample_factor: Maximum distance between samples\n    :return: returns the ids of the final route that can\n    \"\"\"\n\n    ids_to_sample = []\n    prev_option = None\n    dist = 0\n\n    for i, point in enumerate(route):\n        curr_option = point[1]\n\n        # Lane changing\n        if curr_option in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # When road option changes\n        elif prev_option != curr_option and prev_option not in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # After a certain max distance\n        elif dist > sample_factor:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # At the end\n        elif i == len(route) - 1:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # Compute the distance traveled\n        else:\n            curr_location = point[0].location\n            prev_location = route[i - 1][0].location\n            dist += curr_location.distance(prev_location)\n\n        prev_option = curr_option\n\n    return ids_to_sample\n\n\ndef interpolate_trajectory(waypoints_trajectory, hop_resolution=1.0):\n    \"\"\"\n    Given some raw keypoints interpolate a full dense trajectory to be used by the user.\n    returns the full interpolated route both in GPS coordinates and also in its original form.\n    \n    Args:\n        - waypoints_trajectory: the current coarse trajectory\n        - hop_resolution: distance between the trajectory's waypoints\n    \"\"\"\n\n    grp = GlobalRoutePlanner(CarlaDataProvider.get_map(), hop_resolution)\n    # Obtain route plan\n    lat_ref, lon_ref = _get_latlon_ref(CarlaDataProvider.get_world())\n\n    route = []\n    gps_route = []\n\n    for i in range(len(waypoints_trajectory) - 1):\n\n        waypoint = waypoints_trajectory[i]\n        waypoint_next = waypoints_trajectory[i + 1]\n        interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n        for wp, connection in interpolated_trace:\n            route.append((wp.transform, connection))\n            gps_coord = _location_to_gps(lat_ref, lon_ref, wp.transform.location)\n            gps_route.append((gps_coord, connection))\n\n    return gps_route, route\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/route_parser.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule used to parse all the route and scenario configuration parameters.\n\"\"\"\n\nimport json\nimport math\nimport xml.etree.ElementTree as ET\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\nfrom srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData\n\n# Threshold to say if a scenarios trigger position is part of the route\nDIST_THRESHOLD = 2.0\nANGLE_THRESHOLD = 10\n\n\ndef convert_elem_to_transform(elem):\n    \"\"\"Convert an ElementTree.Element to a CARLA transform\"\"\"\n    return carla.Transform(\n        carla.Location(\n            float(elem.attrib.get('x')),\n            float(elem.attrib.get('y')),\n            float(elem.attrib.get('z'))\n        ),\n        carla.Rotation(\n            roll=0.0,\n            pitch=0.0,\n            yaw=float(elem.attrib.get('yaw'))\n        )\n    )\n\n\nclass RouteParser(object):\n\n    \"\"\"\n    Pure static class used to parse all the route and scenario configuration parameters.\n    \"\"\"\n\n    @staticmethod\n    def parse_routes_file(route_filename, single_route_id=''):\n        \"\"\"\n        Returns a list of route configuration elements.\n        :param route_filename: the path to a set of routes.\n        :param single_route: If set, only this route shall be returned\n        :return: List of dicts containing the waypoints, id and town of the routes\n        \"\"\"\n\n        route_configs = []\n        tree = ET.parse(route_filename)\n        for route in tree.iter(\"route\"):\n\n            route_id = route.attrib['id']\n            if single_route_id and route_id != single_route_id:\n                continue\n\n            route_config = RouteScenarioConfiguration()\n            route_config.town = route.attrib['town']\n            route_config.name = \"RouteScenario_{}\".format(route_id)\n            route_config.weather = RouteParser.parse_weather(route)\n\n            # The list of carla.Location that serve as keypoints on this route\n            positions = []\n            for position in route.find('waypoints').iter('position'):\n                positions.append(carla.Location(x=float(position.attrib['x']),\n                                                y=float(position.attrib['y']),\n                                                z=float(position.attrib['z'])))\n            route_config.keypoints = positions\n\n            # The list of ScenarioConfigurations that store the scenario's data\n            scenario_configs = []\n            for scenario in route.find('scenarios').iter('scenario'):\n                scenario_config = ScenarioConfiguration()\n                scenario_config.name = scenario.attrib.get('name')\n                scenario_config.type = scenario.attrib.get('type')\n\n                for elem in scenario.getchildren():\n                    if elem.tag == 'trigger_point':\n                        scenario_config.trigger_points.append(convert_elem_to_transform(elem))\n                    elif elem.tag == 'other_actor':\n                        scenario_config.other_actors.append(ActorConfigurationData.parse_from_node(elem, 'scenario'))\n                    else:\n                        scenario_config.other_parameters[elem.tag] = elem.attrib\n\n                scenario_configs.append(scenario_config)\n            route_config.scenario_configs = scenario_configs\n\n            route_configs.append(route_config)\n\n        return route_configs\n\n    @staticmethod\n    def parse_weather(route):\n        \"\"\"\n        Parses all the weather information as a list of [position, carla.WeatherParameters],\n        where the position represents a % of the route.\n        \"\"\"\n        weathers = []\n\n        weathers_elem = route.find(\"weathers\")\n        if weathers_elem is None:\n            return [[0, carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)]]\n\n        for weather_elem in weathers_elem.iter('weather'):\n            route_percentage = float(weather_elem.attrib['route_percentage'])\n\n            weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)  # Base weather\n            for weather_attrib in weather_elem.attrib:\n                if hasattr(weather, weather_attrib):\n                    setattr(weather, weather_attrib, float(weather_elem.attrib[weather_attrib]))\n                elif weather_attrib != 'route_percentage':\n                    print(f\"WARNING: Ignoring '{weather_attrib}', as it isn't a weather parameter\")\n\n            weathers.append([route_percentage, weather])\n\n        weathers.sort(key=lambda x: x[0])\n        return weathers\n\n    @staticmethod\n    def is_scenario_at_route(trigger_transform, route):\n        \"\"\"\n        Check if the scenario is affecting the route.\n        This is true if the trigger position is very close to any route point\n        \"\"\"\n        def is_trigger_close(trigger_transform, route_transform):\n            \"\"\"Check if the two transforms are similar\"\"\"\n            dist = trigger_transform.location.distance(route_transform.location)\n            angle_dist = (trigger_transform.rotation.yaw - route_transform.rotation.yaw) % 360\n\n            return dist < DIST_THRESHOLD \\\n                and (angle_dist < ANGLE_THRESHOLD or angle_dist > (360 - ANGLE_THRESHOLD))\n\n        for route_transform, _ in route:\n            if is_trigger_close(trigger_transform, route_transform):\n                return True\n\n        return False\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/scenario_helper.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSummary of useful helper functions for scenarios\n\"\"\"\n\nimport math\nimport shapely.geometry\nimport shapely.affinity\n\nimport numpy as np\n\nimport carla\nfrom agents.tools.misc import vector\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\ndef get_distance_along_route(route, target_location):\n    \"\"\"\n    Calculate the distance of the given location along the route\n\n    Note: If the location is not along the route, the route length will be returned\n    \"\"\"\n\n    wmap = CarlaDataProvider.get_map()\n    covered_distance = 0\n    prev_position = None\n    found = False\n\n    # Don't use the input location, use the corresponding wp as location\n    target_location_from_wp = wmap.get_waypoint(target_location).transform.location\n\n    for position, _ in route:\n\n        location = target_location_from_wp\n\n        # Don't perform any calculations for the first route point\n        if not prev_position:\n            prev_position = position\n            continue\n\n        # Calculate distance between previous and current route point\n        interval_length_squared = ((prev_position.x - position.x) ** 2) + ((prev_position.y - position.y) ** 2)\n        distance_squared = ((location.x - prev_position.x) ** 2) + ((location.y - prev_position.y) ** 2)\n\n        # Close to the current position? Stop calculation\n        if distance_squared < 0.01:\n            break\n\n        if distance_squared < 400 and not distance_squared < interval_length_squared:\n            # Check if a neighbor lane is closer to the route\n            # Do this only in a close distance to correct route interval, otherwise the computation load is too high\n            starting_wp = wmap.get_waypoint(location)\n            wp = starting_wp.get_left_lane()\n            while wp is not None:\n                new_location = wp.transform.location\n                new_distance_squared = ((new_location.x - prev_position.x) ** 2) + (\n                    (new_location.y - prev_position.y) ** 2)\n\n                if np.sign(starting_wp.lane_id) != np.sign(wp.lane_id):\n                    break\n\n                if new_distance_squared < distance_squared:\n                    distance_squared = new_distance_squared\n                    location = new_location\n                else:\n                    break\n\n                wp = wp.get_left_lane()\n\n            wp = starting_wp.get_right_lane()\n            while wp is not None:\n                new_location = wp.transform.location\n                new_distance_squared = ((new_location.x - prev_position.x) ** 2) + (\n                    (new_location.y - prev_position.y) ** 2)\n\n                if np.sign(starting_wp.lane_id) != np.sign(wp.lane_id):\n                    break\n\n                if new_distance_squared < distance_squared:\n                    distance_squared = new_distance_squared\n                    location = new_location\n                else:\n                    break\n\n                wp = wp.get_right_lane()\n\n        if distance_squared < interval_length_squared:\n            # The location could be inside the current route interval, if route/lane ids match\n            # Note: This assumes a sufficiently small route interval\n            # An alternative is to compare orientations, however, this also does not work for\n            # long route intervals\n\n            curr_wp = wmap.get_waypoint(position)\n            prev_wp = wmap.get_waypoint(prev_position)\n            wp = wmap.get_waypoint(location)\n\n            if prev_wp and curr_wp and wp:\n                if wp.road_id in (prev_wp.road_id, curr_wp.road_id):\n                    # Roads match, now compare the sign of the lane ids\n                    if (np.sign(wp.lane_id) == np.sign(prev_wp.lane_id) or\n                            np.sign(wp.lane_id) == np.sign(curr_wp.lane_id)):\n                        # The location is within the current route interval\n                        covered_distance += math.sqrt(distance_squared)\n                        found = True\n                        break\n\n        covered_distance += math.sqrt(interval_length_squared)\n        prev_position = position\n\n    return covered_distance, found\n\n\ndef get_crossing_point(actor):\n    \"\"\"\n    Get the next crossing point location in front of the ego vehicle\n\n    @return point of crossing\n    \"\"\"\n    wp_cross = CarlaDataProvider.get_map().get_waypoint(actor.get_location())\n\n    while not wp_cross.is_intersection:\n        wp_cross = wp_cross.next(2)[0]\n\n    crossing = carla.Location(x=wp_cross.transform.location.x,\n                              y=wp_cross.transform.location.y, z=wp_cross.transform.location.z)\n\n    return crossing\n\n\ndef get_geometric_linear_intersection(ego_location, other_location, move_to_junction=False):\n    \"\"\"\n    Obtain a intersection point between two actor's location by using their waypoints (wp)\n\n    @return point of intersection of the two vehicles\n    \"\"\"\n\n    wp_ego_1 = CarlaDataProvider.get_map().get_waypoint(ego_location)\n    wp_ego_2 = wp_ego_1.next(1)[0]\n\n    if move_to_junction:\n        while True:\n            next_wp = wp_ego_2.next(1)[0]\n            if next_wp.is_junction:\n                break\n            else:\n                wp_ego_1 = wp_ego_2\n                wp_ego_2 = next_wp\n\n    ego_1_loc = wp_ego_1.transform.location\n    ego_2_loc = wp_ego_2.transform.location\n\n    wp_other_1 = CarlaDataProvider.get_world().get_map().get_waypoint(other_location)\n    wp_other_2 = wp_other_1.next(1)[0]\n\n    if move_to_junction:\n        while True:\n            next_wp = wp_other_2.next(1)[0]\n            if next_wp.is_junction:\n                break\n            else:\n                wp_other_1 = wp_other_2\n                wp_other_2 = next_wp\n\n    other_1_loc = wp_other_1.transform.location\n    other_2_loc = wp_other_2.transform.location\n\n    s = np.vstack([\n        (ego_1_loc.x, ego_1_loc.y),\n        (ego_2_loc.x, ego_2_loc.y),\n        (other_1_loc.x, other_1_loc.y),\n        (other_2_loc.x, other_2_loc.y)\n    ])\n    h = np.hstack((s, np.ones((4, 1))))\n    line1 = np.cross(h[0], h[1])\n    line2 = np.cross(h[2], h[3])\n    x, y, z = np.cross(line1, line2)\n    if z == 0:\n        return None\n\n    return carla.Location(x=x/z, y=y/z, z=0)\n\n\ndef get_location_in_distance(actor, distance):\n    \"\"\"\n    Obtain a location in a given distance from the current actor's location.\n    Note: Search is stopped on first intersection.\n\n    @return obtained location and the traveled distance\n    \"\"\"\n    waypoint = CarlaDataProvider.get_map().get_waypoint(actor.get_location())\n    traveled_distance = 0\n    while not waypoint.is_intersection and traveled_distance < distance:\n        waypoint_new = waypoint.next(1.0)[-1]\n        traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location)\n        waypoint = waypoint_new\n\n    return waypoint.transform.location, traveled_distance\n\n\ndef get_location_in_distance_from_wp(waypoint, distance, stop_at_junction=True):\n    \"\"\"\n    Obtain a location in a given distance from the current actor's location.\n    Note: Search is stopped on first intersection.\n\n    @return obtained location and the traveled distance\n    \"\"\"\n    traveled_distance = 0\n    while not (waypoint.is_intersection and stop_at_junction) and traveled_distance < distance:\n        wp_next = waypoint.next(1.0)\n        if wp_next:\n            waypoint_new = wp_next[-1]\n            traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location)\n            waypoint = waypoint_new\n        else:\n            break\n\n    return waypoint.transform.location, traveled_distance\n\n\ndef get_waypoint_in_distance(waypoint, distance, stop_at_junction=True):\n    \"\"\"\n    Obtain a waypoint in a given distance from the current actor's location.\n    Note: Search is stopped on first intersection.\n    @return obtained waypoint and the traveled distance\n    \"\"\"\n    traveled_distance = 0\n    while not (waypoint.is_intersection and stop_at_junction) and traveled_distance < distance:\n        wp_next = waypoint.next(1.0)\n        if wp_next:\n            waypoint_new = wp_next[-1]\n            traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location)\n            waypoint = waypoint_new\n        else:\n            break\n\n    return waypoint, traveled_distance\n\n\ndef generate_target_waypoint_list(waypoint, turn=0):\n    \"\"\"\n    This method follow waypoints to a junction and choose path based on turn input.\n    Turn input: LEFT -> -1, RIGHT -> 1, STRAIGHT -> 0\n    @returns a waypoint list from the starting point to the end point according to turn input\n    \"\"\"\n    reached_junction = False\n    threshold = math.radians(0.1)\n    plan = []\n    while True:\n        wp_choice = waypoint.next(2)\n        if len(wp_choice) > 1:\n            reached_junction = True\n            waypoint = choose_at_junction(waypoint, wp_choice, turn)\n        else:\n            waypoint = wp_choice[0]\n        plan.append((waypoint, RoadOption.LANEFOLLOW))\n        #   End condition for the behavior\n        if turn != 0 and reached_junction and len(plan) >= 3:\n            v_1 = vector(\n                plan[-2][0].transform.location,\n                plan[-1][0].transform.location)\n            v_2 = vector(\n                plan[-3][0].transform.location,\n                plan[-2][0].transform.location)\n            angle_wp = math.acos(\n                np.dot(v_1, v_2) / abs((np.linalg.norm(v_1) * np.linalg.norm(v_2))))\n            if angle_wp < threshold:\n                break\n        elif reached_junction and not plan[-1][0].is_intersection:\n            break\n\n    return plan, plan[-1][0]\n\n\ndef generate_target_waypoint_list_multilane(waypoint, change='left',  # pylint: disable=too-many-return-statements\n                                            distance_same_lane=10, distance_other_lane=25,\n                                            total_lane_change_distance=25, check=True,\n                                            lane_changes=1, step_distance=2):\n    \"\"\"\n    This methods generates a waypoint list which leads the vehicle to a parallel lane.\n    The change input must be 'left' or 'right', depending on which lane you want to change.\n\n    The default step distance between waypoints on the same lane is 2m.\n    The default step distance between the lane change is set to 25m.\n\n    @returns a waypoint list from the starting point to the end point on a right or left parallel lane.\n    The function might break before reaching the end point, if the asked behavior is impossible.\n    \"\"\"\n\n    plan = []\n    plan.append((waypoint, RoadOption.LANEFOLLOW))  # start position\n\n    option = RoadOption.LANEFOLLOW\n\n    # Same lane\n    distance = 0\n    while distance < distance_same_lane:\n        next_wps = plan[-1][0].next(step_distance)\n        if not next_wps:\n            return None, None\n        next_wp = next_wps[0]\n        distance += next_wp.transform.location.distance(plan[-1][0].transform.location)\n        plan.append((next_wp, RoadOption.LANEFOLLOW))\n\n    if change == 'left':\n        option = RoadOption.CHANGELANELEFT\n    elif change == 'right':\n        option = RoadOption.CHANGELANERIGHT\n    else:\n        # ERROR, input value for change must be 'left' or 'right'\n        return None, None\n\n    lane_changes_done = 0\n    lane_change_distance = total_lane_change_distance / lane_changes\n\n    # Lane change\n    while lane_changes_done < lane_changes:\n\n        # Move forward\n        next_wps = plan[-1][0].next(lane_change_distance)\n        if not next_wps:\n            return None, None\n        next_wp = next_wps[0]\n\n        # Get the side lane\n        if change == 'left':\n            if check and str(next_wp.lane_change) not in ['Left', 'Both']:\n                return None, None\n            side_wp = next_wp.get_left_lane()\n        else:\n            if check and str(next_wp.lane_change) not in ['Right', 'Both']:\n                return None, None\n            side_wp = next_wp.get_right_lane()\n\n        if not side_wp or side_wp.lane_type != carla.LaneType.Driving:\n            return None, None\n\n        # Update the plan\n        plan.append((side_wp, option))\n        lane_changes_done += 1\n\n    # Other lane\n    distance = 0\n    while distance < distance_other_lane:\n        next_wps = plan[-1][0].next(step_distance)\n        if not next_wps:\n            return None, None\n        next_wp = next_wps[0]\n        distance += next_wp.transform.location.distance(plan[-1][0].transform.location)\n        plan.append((next_wp, RoadOption.LANEFOLLOW))\n\n    target_lane_id = plan[-1][0].lane_id\n\n    return plan, target_lane_id\n\n\ndef generate_target_waypoint(waypoint, turn=0):\n    \"\"\"\n    This method follow waypoints to a junction and choose path based on turn input.\n    Turn input: LEFT -> -1, RIGHT -> 1, STRAIGHT -> 0\n    @returns a waypoint list according to turn input\n    \"\"\"\n    sampling_radius = 1\n    reached_junction = False\n    wp_list = []\n    while True:\n\n        wp_choice = waypoint.next(sampling_radius)\n        #   Choose path at intersection\n        if not reached_junction and (len(wp_choice) > 1 or wp_choice[0].is_junction):\n            reached_junction = True\n            waypoint = choose_at_junction(waypoint, wp_choice, turn)\n        else:\n            waypoint = wp_choice[0]\n        wp_list.append(waypoint)\n        #   End condition for the behavior\n        if reached_junction and not wp_list[-1].is_junction:\n            break\n    return wp_list[-1]\n\n\ndef generate_target_waypoint_in_route(waypoint, route):\n    \"\"\"\n    This method follow waypoints to a junction\n    @returns a waypoint list according to turn input\n    \"\"\"\n    target_waypoint = None\n    wmap = CarlaDataProvider.get_map()\n    reached_junction = False\n\n    # Get the route location\n    shortest_distance = float('inf')\n    for index, route_pos in enumerate(route):\n        route_location = route_pos[0].location\n        trigger_location = waypoint.transform.location\n\n        dist_to_route = trigger_location.distance(route_location)\n        if dist_to_route <= shortest_distance:\n            closest_index = index\n            shortest_distance = dist_to_route\n\n    route_location = route[closest_index][0].location\n    index = closest_index\n\n    for i in range(index, len(route)):\n        route_location = route[i][0].location\n        road_option = route[i][1]\n\n        # Enter the junction\n        if not reached_junction and (road_option in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n            reached_junction = True\n\n        # End condition for the behavior, at the end of the junction\n        if reached_junction and (road_option not in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n            target_waypoint = route_location\n            break\n\n    return wmap.get_waypoint(target_waypoint)\n\n\ndef choose_at_junction(current_waypoint, next_choices, direction=0):\n    \"\"\"\n    This function chooses the appropriate waypoint from next_choices based on direction\n    \"\"\"\n    current_transform = current_waypoint.transform\n    current_location = current_transform.location\n    projected_location = current_location + \\\n        carla.Location(\n            x=math.cos(math.radians(current_transform.rotation.yaw)),\n            y=math.sin(math.radians(current_transform.rotation.yaw)))\n    current_vector = vector(current_location, projected_location)\n    cross_list = []\n    cross_to_waypoint = {}\n    for waypoint in next_choices:\n        waypoint = waypoint.next(10)[0]\n        select_vector = vector(current_location, waypoint.transform.location)\n        cross = np.cross(current_vector, select_vector)[2]\n        cross_list.append(cross)\n        cross_to_waypoint[cross] = waypoint\n    select_cross = None\n    if direction > 0:\n        select_cross = max(cross_list)\n    elif direction < 0:\n        select_cross = min(cross_list)\n    else:\n        select_cross = min(cross_list, key=abs)\n\n    return cross_to_waypoint[select_cross]\n\n\ndef get_intersection(ego_actor, other_actor):\n    \"\"\"\n    Obtain a intersection point between two actor's location\n    @return the intersection location\n    \"\"\"\n    waypoint = CarlaDataProvider.get_map().get_waypoint(ego_actor.get_location())\n    waypoint_other = CarlaDataProvider.get_map().get_waypoint(other_actor.get_location())\n    max_dist = float(\"inf\")\n    distance = float(\"inf\")\n    while distance <= max_dist:\n        max_dist = distance\n        current_location = waypoint.transform.location\n        waypoint_choice = waypoint.next(1)\n        #   Select the straighter path at intersection\n        if len(waypoint_choice) > 1:\n            max_dot = -1 * float('inf')\n            loc_projection = current_location + carla.Location(\n                x=math.cos(math.radians(waypoint.transform.rotation.yaw)),\n                y=math.sin(math.radians(waypoint.transform.rotation.yaw)))\n            v_current = vector(current_location, loc_projection)\n            for wp_select in waypoint_choice:\n                v_select = vector(current_location, wp_select.transform.location)\n                dot_select = np.dot(v_current, v_select)\n                if dot_select > max_dot:\n                    max_dot = dot_select\n                    waypoint = wp_select\n        else:\n            waypoint = waypoint_choice[0]\n        distance = current_location.distance(waypoint_other.transform.location)\n\n    return current_location\n\n\ndef detect_lane_obstacle(actor, extension_factor=3, margin=1.02):\n    \"\"\"\n    This function identifies if an obstacle is present in front of the reference actor\n    \"\"\"\n    world_actors = CarlaDataProvider.get_all_actors().filter('vehicle.*')\n    actor_bbox = actor.bounding_box\n    actor_transform = actor.get_transform()\n    actor_location = actor_transform.location\n    actor_vector = actor_transform.rotation.get_forward_vector()\n    actor_vector = np.array([actor_vector.x, actor_vector.y])\n    actor_vector = actor_vector / np.linalg.norm(actor_vector)\n    actor_vector = actor_vector * (extension_factor - 1) * actor_bbox.extent.x\n    actor_location = actor_location + carla.Location(actor_vector[0], actor_vector[1])\n    actor_yaw = actor_transform.rotation.yaw\n\n    is_hazard = False\n    for adversary in world_actors:\n        if adversary.id != actor.id and \\\n                actor_transform.location.distance(adversary.get_location()) < 50:\n            adversary_bbox = adversary.bounding_box\n            adversary_transform = adversary.get_transform()\n            adversary_loc = adversary_transform.location\n            adversary_yaw = adversary_transform.rotation.yaw\n            overlap_adversary = RotatedRectangle(\n                adversary_loc.x, adversary_loc.y,\n                2 * margin * adversary_bbox.extent.x, 2 * margin * adversary_bbox.extent.y, adversary_yaw)\n            overlap_actor = RotatedRectangle(\n                actor_location.x, actor_location.y,\n                2 * margin * actor_bbox.extent.x * extension_factor, 2 * margin * actor_bbox.extent.y, actor_yaw)\n            overlap_area = overlap_adversary.intersection(overlap_actor).area\n            if overlap_area > 0:\n                is_hazard = True\n                break\n\n    return is_hazard\n\n\ndef get_junction_topology(junction):\n    \"\"\"\n    Given a junction, returns a two list of waypoints corresponding to the entry\n    and exit lanes of the junction\n    \"\"\"\n    def get_lane_key(waypoint):\n        return str(waypoint.road_id) + '*' + str(waypoint.lane_id)\n\n    def get_junction_entry_wp(entry_wp):\n        while entry_wp.is_junction:\n            entry_wps = entry_wp.previous(0.2)\n            if len(entry_wps) == 0:\n                return None\n            entry_wp = entry_wps[0]\n        return entry_wp\n\n    def get_junction_exit_wp(exit_wp):\n        while exit_wp.is_junction:\n            exit_wps = exit_wp.next(0.2)\n            if len(exit_wps) == 0:\n                return None\n            exit_wp = exit_wps[0]\n        return exit_wp\n\n    used_entry_lanes = []\n    used_exit_lanes = []\n    entry_wps = []\n    exit_wps = []\n    for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n        entry_wp = get_junction_entry_wp(entry_wp)\n        if not entry_wp:\n            continue\n        if get_lane_key(entry_wp) not in used_entry_lanes:\n            used_entry_lanes.append(get_lane_key(entry_wp))\n            entry_wps.append(entry_wp)\n\n        exit_wp = get_junction_exit_wp(exit_wp)\n        if not exit_wp:\n            continue\n        if get_lane_key(exit_wp) not in used_exit_lanes:\n            used_exit_lanes.append(get_lane_key(exit_wp))\n            exit_wps.append(exit_wp)\n\n    return entry_wps, exit_wps\n\n\ndef filter_junction_wp_direction(reference_wp, wp_list, direction='opposite'):\n    \"\"\"\n    Given a list of entry / exit wps of a junction, filters them according to a specific direction,\n    returning all waypoint part of lanes that are at 'direction' with respect to the reference.\n    This might fail for complex junctions, as only the wp yaws is checked, not their relative positions\n    \"\"\"\n\n    filtered_wps = []\n    reference_yaw = reference_wp.transform.rotation.yaw\n    for wp in wp_list:\n        diff = (wp.transform.rotation.yaw - reference_yaw) % 360\n        if diff > 330.0:\n            wp_direction = 'ref'\n        elif diff > 225.0:\n            wp_direction = 'right'\n        elif diff > 135.0:\n            wp_direction = 'opposite'\n        elif diff > 30.0:\n            wp_direction = 'left'\n        else:\n            wp_direction = 'ref'\n\n        if wp_direction == direction:\n            filtered_wps.append(wp)\n\n    return filtered_wps\n\n\ndef get_closest_traffic_light(waypoint, traffic_lights=None):\n    \"\"\"\n    Returns the traffic light closest to the waypoint. The distance is computed between the\n    waypoint and the traffic light's bounding box.\n    Checks all traffic lights part of 'traffic_lights', or all the town ones, if None are passed.\n    \"\"\"\n    if not traffic_lights:\n        traffic_lights = CarlaDataProvider.get_all_actors().filter('*traffic_light*')\n\n    closest_dist = float('inf')\n    closest_tl = None\n\n    wp_location = waypoint.transform.location\n    for tl in traffic_lights:\n        tl_waypoints = tl.get_stop_waypoints()\n        for tl_waypoint in tl_waypoints:\n            distance = wp_location.distance(tl_waypoint.transform.location)\n            if distance < closest_dist:\n                closest_dist = distance\n                closest_tl = tl\n\n    return closest_tl\n\n\ndef get_offset_transform(transform, offset):\n    \"\"\"\n    This function adjusts the give transform by offset and returns the new transform.\n    \"\"\"\n    if offset != 0:\n        forward_vector = transform.rotation.get_forward_vector()\n        orthogonal_vector = carla.Vector3D(x=-forward_vector.y, y=forward_vector.x, z=forward_vector.z)\n        transform.location.x = transform.location.x + offset * orthogonal_vector.x\n        transform.location.y = transform.location.y + offset * orthogonal_vector.y\n    return transform\n\n\ndef get_troad_from_transform(actor_transform):\n    \"\"\"\n    This function finds the lateral road position (t) from actor_transform\n    \"\"\"\n    actor_loc = actor_transform.location\n    c_wp = CarlaDataProvider.get_map().get_waypoint(actor_loc)\n    left_lanes, right_lanes = [], []\n    # opendrive standard: (left ==> +ve lane_id) and (right ==> -ve lane_id)\n    ref_lane = CarlaDataProvider.get_map().get_waypoint_xodr(c_wp.road_id, 0, c_wp.s)\n    for i in range(-50, 50):\n        _wp = CarlaDataProvider.get_map().get_waypoint_xodr(c_wp.road_id, i, c_wp.s)\n        if _wp:\n            if i < 0:\n                left_lanes.append(_wp)\n            elif i > 0:\n                right_lanes.append(_wp)\n\n    if left_lanes:\n        left_lane_ids = [ln.lane_id for ln in left_lanes]\n        lm_id = min(left_lane_ids)\n        lm_lane = left_lanes[left_lane_ids.index(lm_id)]\n        lm_lane_offset = lm_lane.lane_width / 2\n    else:\n        lm_lane, lm_lane_offset = ref_lane, 0\n    lm_tr = get_offset_transform(carla.Transform(lm_lane.transform.location, lm_lane.transform.rotation),\n                                 lm_lane_offset)\n    distance_from_lm_lane_edge = lm_tr.location.distance(actor_loc)\n    distance_from_lm_lane_ref_lane = lm_tr.location.distance(ref_lane.transform.location)\n    if right_lanes:\n        right_lane_ids = [ln.lane_id for ln in right_lanes]\n        rm_id = max(right_lane_ids)\n        rm_lane = right_lanes[right_lane_ids.index(rm_id)]\n        rm_lane_offset = -rm_lane.lane_width / 2\n    else:\n        rm_lane, rm_lane_offset = ref_lane, -distance_from_lm_lane_ref_lane\n    distance_from_rm_lane_edge = get_offset_transform(carla.Transform(rm_lane.transform.location,\n                                                                      rm_lane.transform.rotation),\n                                                      rm_lane_offset).location.distance(actor_loc)\n    t_road = ref_lane.transform.location.distance(actor_loc)\n    if not right_lanes or not left_lanes:\n        closest_road_edge = min(distance_from_lm_lane_edge, distance_from_rm_lane_edge)\n        if closest_road_edge == distance_from_lm_lane_edge:\n            t_road = -1*t_road\n    else:\n        if c_wp.lane_id < 0:\n            t_road = -1*t_road\n\n    return t_road\n\n\ndef get_distance_between_actors(current, target, distance_type=\"euclidianDistance\", freespace=False,\n                                global_planner=None):\n    \"\"\"\n    This function finds the distance between actors for different use cases described by distance_type and freespace\n    attributes\n    \"\"\"\n\n    target_transform = CarlaDataProvider.get_transform(target)\n    current_transform = CarlaDataProvider.get_transform(current)\n    target_wp = CarlaDataProvider.get_map().get_waypoint(target_transform.location)\n    current_wp = CarlaDataProvider.get_map().get_waypoint(current_transform.location)\n\n    extent_sum_x, extent_sum_y = 0, 0\n    if freespace:\n        if isinstance(target, (carla.Vehicle, carla.Walker)):\n            extent_sum_x = target.bounding_box.extent.x + current.bounding_box.extent.x\n            extent_sum_y = target.bounding_box.extent.y + current.bounding_box.extent.y\n    if distance_type == \"longitudinal\":\n        if not current_wp.road_id == target_wp.road_id:\n            distance = 0\n            # Get the route\n            route = global_planner.trace_route(current_transform.location, target_transform.location)\n            # Get the distance of the route\n            for i in range(1, len(route)):\n                curr_loc = route[i][0].transform.location\n                prev_loc = route[i - 1][0].transform.location\n                distance += curr_loc.distance(prev_loc)\n        else:\n            distance = abs(current_wp.s - target_wp.s)\n        if freespace:\n            distance = distance - extent_sum_x\n    elif distance_type == \"lateral\":\n        target_t = get_troad_from_transform(target_transform)\n        current_t = get_troad_from_transform(current_transform)\n        distance = abs(target_t - current_t)\n        if freespace:\n            distance = distance - extent_sum_y\n\n    elif distance_type in [\"cartesianDistance\", \"euclidianDistance\"]:\n        distance = target_transform.location.distance(current_transform.location)\n        if freespace:\n            distance = distance - extent_sum_x\n    else:\n        raise TypeError(\"unknown distance_type: {}\".format(distance_type))\n\n    # distance will be negative for feeespace when there is overlap condition\n    # truncate to 0.0 when this happens\n    distance = 0.0 if distance < 0.0 else distance\n\n    return distance\n\n\ndef get_same_dir_lanes(waypoint):\n    \"\"\"\n    Gets all the lanes with the same direction of the road of a wp.\n    Ordered from the edge lane to the center one (from outwards to inwards)\n    \"\"\"\n    same_dir_wps = [waypoint]\n\n    # Check roads on the right\n    right_wp = waypoint\n    while True:\n        possible_right_wp = right_wp.get_right_lane()\n        if possible_right_wp is None or possible_right_wp.lane_type != carla.LaneType.Driving:\n            break\n        right_wp = possible_right_wp\n        same_dir_wps.append(right_wp)\n\n    # Check roads on the left\n    left_wp = waypoint\n    while True:\n        possible_left_wp = left_wp.get_left_lane()\n        if possible_left_wp is None or possible_left_wp.lane_type != carla.LaneType.Driving:\n            break\n        if possible_left_wp.lane_id * left_wp.lane_id < 0:\n            break\n        left_wp = possible_left_wp\n        same_dir_wps.insert(0, left_wp)\n\n    return same_dir_wps\n\n\ndef get_opposite_dir_lanes(waypoint):\n    \"\"\"\n    Gets all the lanes with opposite direction of the road of a wp\n    Ordered from the center lane to the edge one (from inwards to outwards)\n    \"\"\"\n    other_dir_wps = []\n    other_dir_wp = None\n\n    # Get the first lane of the opposite direction\n    left_wp = waypoint\n    while True:\n        possible_left_wp = left_wp.get_left_lane()\n        if possible_left_wp is None:\n            break\n        if possible_left_wp.lane_id * left_wp.lane_id < 0:\n            other_dir_wp = possible_left_wp\n            break\n        left_wp = possible_left_wp\n\n    if not other_dir_wp:\n        return other_dir_wps\n\n    # Check roads on the right\n    right_wp = other_dir_wp\n    while True:\n        if right_wp.lane_type == carla.LaneType.Driving:\n            other_dir_wps.append(right_wp)\n        possible_right_wp = right_wp.get_right_lane()\n        if possible_right_wp is None:\n            break\n        right_wp = possible_right_wp\n\n    return other_dir_wps\n\n\nclass RotatedRectangle(object):\n\n    \"\"\"\n    This class contains method to draw rectangle and find intersection point.\n    \"\"\"\n\n    def __init__(self, c_x, c_y, width, height, angle):\n        self.c_x = c_x\n        self.c_y = c_y\n        self.w = width      # pylint: disable=invalid-name\n        self.h = height     # pylint: disable=invalid-name\n        self.angle = angle\n\n    def get_contour(self):\n        \"\"\"\n        create contour\n        \"\"\"\n        w = self.w\n        h = self.h\n        c = shapely.geometry.box(-w / 2.0, -h / 2.0, w / 2.0, h / 2.0)\n        rc = shapely.affinity.rotate(c, self.angle)\n        return shapely.affinity.translate(rc, self.c_x, self.c_y)\n\n    def intersection(self, other):\n        \"\"\"\n        Obtain a intersection point between two contour.\n        \"\"\"\n        return self.get_contour().intersection(other.get_contour())\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/tools/scenario_parser.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides access to a scenario configuration parser\n\"\"\"\n\nimport glob\nimport os\nimport xml.etree.ElementTree as ET\n\nimport carla\n\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData\nfrom srunner.scenarioconfigs.route_scenario_configuration import RouteConfiguration\n\n\nclass ScenarioConfigurationParser(object):\n\n    \"\"\"\n    Pure static class providing access to parser methods for scenario configuration files (*.xml)\n    \"\"\"\n\n    @staticmethod\n    def parse_scenario_configuration(scenario_name, additional_config_file_name):\n        \"\"\"\n        Parse all scenario configuration files at srunner/examples and the additional\n        config files, providing a list of ScenarioConfigurations @return\n\n        If scenario_name starts with \"group:\" all scenarios that\n        have that type are parsed and returned. Otherwise only the\n        scenario that matches the scenario_name is parsed and returned.\n        \"\"\"\n\n        if scenario_name.startswith(\"group:\"):\n            scenario_group = True\n            scenario_name = scenario_name[6:]\n        else:\n            scenario_group = False\n\n        scenario_configurations = []\n\n        list_of_config_files = glob.glob(\"{}/srunner/examples/*.xml\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        if additional_config_file_name != '':\n            list_of_config_files.append(additional_config_file_name)\n\n        for file_name in list_of_config_files:\n            tree = ET.parse(file_name)\n\n            for scenario in tree.iter(\"scenario\"):\n\n                scenario_config_name = scenario.attrib.get('name', None)\n                scenario_config_type = scenario.attrib.get('type', None)\n\n                # Check that the scenario is the correct one\n                if not scenario_group and scenario_config_name != scenario_name:\n                    continue\n                # Check that the scenario is of the correct type\n                elif scenario_group and scenario_config_type != scenario_name:\n                    continue\n\n                config = ScenarioConfiguration()\n                config.town = scenario.attrib.get('town')\n                config.name = scenario_config_name\n                config.type = scenario_config_type\n\n                for elem in scenario.getchildren():\n                    # Elements with special parsing\n                    if elem.tag == 'ego_vehicle':\n                        config.ego_vehicles.append(ActorConfigurationData.parse_from_node(elem, 'hero'))\n                        config.trigger_points.append(config.ego_vehicles[-1].transform)\n                    elif elem.tag == 'other_actor':\n                        config.other_actors.append(ActorConfigurationData.parse_from_node(elem, 'scenario'))\n                    elif elem.tag == 'weather':\n                        for weather_attrib in elem.attrib:\n                            if hasattr(config.weather, weather_attrib):\n                                setattr(config.weather, weather_attrib, float(elem.attrib[weather_attrib]))\n                            else:\n                                print(f\"WARNING: Ignoring '{weather_attrib}', as it isn't a weather parameter\")\n\n                    elif elem.tag == 'route':\n                        route_conf = RouteConfiguration()\n                        route_conf.parse_xml(elem)\n                        config.route = route_conf\n\n                    # Any other possible element, add it as a config attribute\n                    else:\n                        config.other_parameters[elem.tag] = elem.attrib\n\n                scenario_configurations.append(config)\n        return scenario_configurations\n\n    @staticmethod\n    def get_list_of_scenarios(additional_config_file_name):\n        \"\"\"\n        Parse *all* config files and provide a list with all scenarios @return\n        \"\"\"\n\n        list_of_config_files = glob.glob(\"{}/srunner/examples/*.xml\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        list_of_config_files += glob.glob(\"{}/srunner/examples/*.xosc\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        if additional_config_file_name != '':\n            list_of_config_files.append(additional_config_file_name)\n\n        scenarios = []\n        for file_name in list_of_config_files:\n            if \".xosc\" in file_name:\n                tree = ET.parse(file_name)\n                scenarios.append(\"{} (OpenSCENARIO)\".format(tree.find(\"FileHeader\").attrib.get('description', None)))\n            else:\n                tree = ET.parse(file_name)\n                for scenario in tree.iter(\"scenario\"):\n                    scenarios.append(scenario.attrib.get('name', None))\n\n        return scenarios\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/scenario_runner/srunner/utilities/code_check_and_formatting.sh",
    "content": "#!/bin/bash\n\nautopep8 scenario_runner.py --in-place --max-line-length=120\nautopep8 srunner/scenariomanager/*.py --in-place --max-line-length=120 --ignore=E731\nautopep8 srunner/scenariomanager/actorcontrols/*.py --in-place --max-line-length=120\nautopep8 srunner/scenariomanager/scenarioatomics/*.py --in-place --max-line-length=120\nautopep8 srunner/scenarios/*.py --in-place --max-line-length=120\nautopep8 srunner/autoagents/*.py --in-place --max-line-length=120\nautopep8 srunner/tools/*.py --in-place --max-line-length=120\nautopep8 srunner/scenarioconfigs/*.py --in-place --max-line-length=120\n\n\npylint --rcfile=.pylintrc --disable=I srunner/scenariomanager/\npylint --rcfile=.pylintrc srunner/scenarios/\npylint --rcfile=.pylintrc srunner/autoagents/\npylint --rcfile=.pylintrc srunner/tools/\npylint --rcfile=.pylintrc srunner/scenarioconfigs/\npylint --rcfile=.pylintrc scenario_runner.py\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/ability_benchmark.py",
    "content": "import json\nimport carla\nimport argparse\nimport xml.etree.ElementTree as ET\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nimport os\nimport atexit\nimport subprocess\nimport time\nimport random\n\nAbility = {\n    \"Overtaking\":['Accident', 'AccidentTwoWays', 'ConstructionObstacle', 'ConstructionObstacleTwoWays', 'HazardAtSideLaneTwoWays', 'HazardAtSideLane', 'ParkedObstacleTwoWays', 'ParkedObstacle', 'VehicleOpensDoorTwoWays'],\n    \"Merging\": ['CrossingBicycleFlow', 'EnterActorFlow', 'HighwayExit', 'InterurbanActorFlow', 'HighwayCutIn', 'InterurbanAdvancedActorFlow', 'MergerIntoSlowTrafficV2', 'MergerIntoSlowTraffic', 'NonSignalizedJunctionLeftTurn', 'NonSignalizedJunctionRightTurn', 'NonSignalizedJunctionLeftTurnEnterFlow', 'ParkingExit', 'SequentialLaneChange', 'SignalizedJunctionLeftTurn', 'SignalizedJunctionRightTurn', 'SignalizedJunctionLeftTurnEnterFlow'],\n    \"Emergency_Brake\": ['BlockedIntersection', 'DynamicObjectCrossing', 'HardBreakRoute', 'OppositeVehicleTakingPriority', 'OppositeVehicleRunningRedLight', 'ParkingCutIn', 'PedestrianCrossing', 'ParkingCrossingPedestrian', 'StaticCutIn', 'VehicleTurningRoute', 'VehicleTurningRoutePedestrian', 'ControlLoss'],\n    \"Give_Way\": ['InvadingTurn', 'YieldToEmergencyVehicle'],\n    \"Traffic_Signs\": ['BlockedIntersection', 'OppositeVehicleTakingPriority', 'OppositeVehicleRunningRedLight', 'PedestrianCrossing', 'VehicleTurningRoute', 'VehicleTurningRoutePedestrian', 'EnterActorFlow', 'CrossingBicycleFlow', 'NonSignalizedJunctionLeftTurn', 'NonSignalizedJunctionRightTurn', 'NonSignalizedJunctionLeftTurnEnterFlow', 'OppositeVehicleTakingPriority', 'OppositeVehicleRunningRedLight', 'PedestrianCrossing', 'SignalizedJunctionLeftTurn', 'SignalizedJunctionRightTurn', 'SignalizedJunctionLeftTurnEnterFlow', 'T_Junction', 'VanillaNonSignalizedTurn', 'VanillaSignalizedTurnEncounterGreenLight', 'VanillaSignalizedTurnEncounterRedLight', 'VanillaNonSignalizedTurnEncounterStopsign', 'VehicleTurningRoute', 'VehicleTurningRoutePedestrian']\n}\n\ndef get_infraction_status(record):\n    for infraction,  value in record['infractions'].items():\n        if infraction == \"min_speed_infractions\":\n            continue\n        elif len(value) > 0:\n            return True\n    return False\n\ndef update_Ability(scenario_name, Ability_Statistic, status):\n    for ability, scenarios in Ability.items():\n        if scenario_name in scenarios:\n            Ability_Statistic[ability][1] += 1\n            if status:\n                Ability_Statistic[ability][0] += 1\n    pass\n\ndef update_Success(scenario_name, Success_Statistic, status):\n    if scenario_name not in Success_Statistic:\n        if status:\n            Success_Statistic[scenario_name] = [1, 1]\n        else:\n            Success_Statistic[scenario_name] = [0, 1]\n    else:\n        Success_Statistic[scenario_name][1] += 1\n        if status:\n            Success_Statistic[scenario_name][0] += 1\n    pass\n\ndef get_position(xml_route):\n    waypoints_elem = xml_route.find('waypoints')\n    keypoints = waypoints_elem.findall('position')\n    return [carla.Location(float(pos.get('x')), float(pos.get('y')), float(pos.get('z'))) for pos in keypoints]\n\ndef get_route_result(records, route_id):\n    for record in records:\n        record_route_id = record['route_id'].split('_')[1]\n        if route_id == record_route_id:\n            return record\n    return None\n\ndef get_waypoint_route(locs, grp):\n    route = []\n    for i in range(len(locs) - 1):\n        loc = locs[i]\n        loc_next = locs[i + 1]\n        interpolated_trace = grp.trace_route(loc, loc_next)\n        for wp, _ in interpolated_trace:\n            route.append(wp)\n    return route\n\ndef main(args):\n    routes_file = args.file \n    result_file = args.result_file\n    Ability_Statistic = {}\n    crash_route_list = []\n    for key in Ability:\n        Ability_Statistic[key] = [0, 0.]\n    Success_Statistic = {}\n    \n    with open(result_file, 'r') as f:\n        data = json.load(f)\n    records = data[\"_checkpoint\"][\"records\"]\n                    \n    tree = ET.parse(routes_file)\n    root = tree.getroot()\n    routes = root.findall('route')\n    sorted_routes = sorted(routes, key=lambda x: x.get('town'))\n    \n    carla_path = os.environ[\"CARLA_ROOT\"]\n    cmd1 = f\"{os.path.join(carla_path, 'CarlaUE4.sh')} -RenderOffScreen -nosound -carla-rpc-port={args.port}\"\n    server = subprocess.Popen(cmd1, shell=True, preexec_fn=os.setsid)\n    print(cmd1, server.returncode, flush=True)\n    time.sleep(10)\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(300)\n    \n    current_town = sorted_routes[0].get('town')\n    world = client.load_world(current_town)\n    carla_map = world.get_map()\n    grp = GlobalRoutePlanner(carla_map, 1.0)\n    for route in sorted_routes:\n        scenarios = route.find('scenarios')\n        scenario_name = scenarios.find('scenario').get(\"type\")\n        route_id = route.get('id')\n        route_record = get_route_result(records, route_id)\n        if route_record is None:\n            crash_route_list.append((scenario_name, route_id))\n            print('No result record of route', route_id, \"in the result file\")\n            continue\n        if route_record[\"status\"] == 'Completed' or route_record[\"status\"] == \"Perfect\":\n            if get_infraction_status(route_record):\n                record_success_status = False\n            else:\n                record_success_status = True\n        else:\n            record_success_status = False\n        update_Ability(scenario_name, Ability_Statistic, record_success_status)\n        update_Success(scenario_name, Success_Statistic, record_success_status)\n        # if scenario_name in Ability[\"Traffic_Signs\"] and (scenario_name in Ability[\"Merging\"] or scenario_name in Ability[\"Emergency_Brake\"]):\n        # Only these three 'Ability's intersect\n        if scenario_name in Ability[\"Traffic_Signs\"]:\n            # Only these three 'Ability's intersect\n            if route.get('town') != current_town:\n                current_town = route.get('town')\n                print(\"Loading the town:\", current_town)\n                world = client.load_world(current_town)\n                print(\"successfully load the town:\", current_town)\n            carla_map = world.get_map()\n            grp = GlobalRoutePlanner(carla_map, 1.0)\n            location_list = get_position(route)\n            waypoint_route = get_waypoint_route(location_list, grp)\n            count = 0\n            for wp in waypoint_route:\n                count += 1\n                if wp.is_junction:\n                    break \n            if not wp.is_junction:\n                raise RuntimeError(\"This route does not contain any junction-waypoint!\")\n            # +8 to ensure the ego pass the trigger volume\n            junction_completion = float(count+8) / float(len(waypoint_route))\n            record_completion = route_record[\"scores\"][\"score_route\"] / 100.0\n            stop_infraction = route_record[\"infractions\"][\"stop_infraction\"]\n            red_light_infraction = route_record[\"infractions\"][\"red_light\"]\n            if record_completion > junction_completion and not stop_infraction and not red_light_infraction:\n                Ability_Statistic['Traffic_Signs'][0] += 1\n                Ability_Statistic['Traffic_Signs'][1] += 1\n            else:\n                Ability_Statistic['Traffic_Signs'][1] += 1\n        else:\n            pass\n        \n    Ability_Res = {}\n    for ability, statis in Ability_Statistic.items():\n        Ability_Res[ability] = float(statis[0])/float(statis[1])\n        \n    for key, value in Ability_Res.items():\n        print(key, \": \", value)\n    \n    Ability_Res['mean'] = sum(list(Ability_Res.values())) / 5\n    Ability_Res['crashed'] = crash_route_list\n    with open(f\"{result_file.split('.')[0]}_ability.json\", 'w') as file:\n        json.dump(Ability_Res, file, indent=4)\n        \n    Success_Res = {}\n    Route_num = 0\n    Succ_Route_num = 0\n    for scenario, statis in Success_Statistic.items():\n        Success_Res[scenario] = float(statis[0])/float(statis[1])\n        Succ_Route_num += statis[0]\n        Route_num += statis[1]\n    assert len(crash_route_list) == 220 - float(Route_num)\n    print(f\"Mean:{Ability_Res['mean']}\")\n    print(f'Crashed Route num: {len(crash_route_list)}, Crashed Route ID: {crash_route_list}')\n    print('Finished!')\n\nif __name__=='__main__':\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('-f', '--file', nargs=None, default=\"leaderboard/data/bench2drive220.xml\", help='route file')\n    argparser.add_argument('-r', '--result_file', nargs=None, default=\"\", help='result json file')\n    argparser.add_argument('-t', '--host', default='localhost', help='IP of the host server (default: localhost)')\n    argparser.add_argument('-p', '--port', nargs=1, default=2000, help='carla rpc port')\n    args = argparser.parse_args()\n    main(args)\n    "
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/check_carla.md",
    "content": "# Check if carla is working properly\n\n### Verification Process\n1. Run in terminal 1\n    ```bash\n        ./CarlaUE4.sh -RenderOffScreen -nosound -fps=10 -carla-rpc-port=2000\n    ```\n2. Run in terninal 2\n    ```python\n        import carla\n        client = carla.Client('localhost', 2000)\n        client.set_timeout(100.0)\n        list_map = client.get_available_maps()\n        client_version = client.get_client_version()\n        server_version = client.get_server_version()\n        world = client.get_world()\n        world = client.load_world('Town02')\n    ```\n3. If executed successfully, carla runs successfully.\n\n### Summary of some issues\n- The normal startup of carla is **blocking**. \n\n- If the process ends immediately, please check **vulkaninfo**\n    - if vulkaninfo does not exist\n        ```bash\n            apt install vulkan-tools # \tvulkaninfo\n\t        apt install libgeos-dev\n        ``` \n    - if **test only** appears, please check Ubuntu system version\n        - A100/H100/A800/H800 requires a newer version of vulkaninfo, and therefore requires Ubuntu 22.04\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/clean_carla.sh",
    "content": "#!/bin/bash\nkillall -9 -r CarlaUE4-Linux\nps -ef | grep \"carla-rpc-port\" | awk '{print $2}' | xargs kill > /dev/null 2>&1 &\nps -ef | grep \"run_evaluation\" | awk '{print $2}' | xargs kill > /dev/null 2>&1 &\nps -ef | grep \"leaderboard_evaluator\" | awk '{print $2}' | xargs kill > /dev/null 2>&1 &\nwait\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/data_collect.py",
    "content": "from srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom leaderboard.envs.sensor_interface import SensorInterface, CallBack, OpenDriveMapReader, SpeedometerReader\nimport cv2\nimport json\nimport numpy as np\nimport xml.etree.ElementTree as ET\nimport carla\nimport gzip\nfrom easydict import EasyDict\nimport math\nimport h5py\nimport laspy\nfrom utils import build_projection_matrix, convert_depth, get_relative_transform, normalize_angle, build_skeleton,  get_matrix, calculate_cube_vertices, compute_2d_distance\nfrom utils import DIS_CAR_SAVE, DIS_WALKER_SAVE, DIS_SIGN_SAVE, DIS_LIGHT_SAVE\n\nEARTH_RADIUS_EQUA = 6378137.0\n\nclass Env_Manager():\n    \n    frame_rate = 10.0 \n\n    def tick(self, input_data):\n        # control\n        control = self.manager.ego_vehicles[0].get_control()\n\n        # camera_bgr\n        cam_bgr_front = input_data['CAM_FRONT'][1][:, :, :3]\n        cam_bgr_front_left = input_data['CAM_FRONT_LEFT'][1][:, :, :3]\n        cam_bgr_front_right = input_data['CAM_FRONT_RIGHT'][1][:, :, :3]\n        cam_bgr_back = input_data['CAM_BACK'][1][:, :, :3]\n        cam_bgr_back_left = input_data['CAM_BACK_LEFT'][1][:, :, :3]\n        cam_bgr_back_right = input_data['CAM_BACK_RIGHT'][1][:, :, :3]\n        cam_bgr_top_down = input_data['TOP_DOWN'][1][:, :, :3]\n\n        # radar\n        radar_front = input_data['RADAR_FRONT'][1].astype(np.float16)\n        radar_front_left = input_data['RADAR_FRONT_LEFT'][1].astype(np.float16)\n        radar_front_right = input_data['RADAR_FRONT_RIGHT'][1].astype(np.float16)\n        radar_back_left = input_data['RADAR_BACK_LEFT'][1].astype(np.float16)\n        radar_back_right = input_data['RADAR_BACK_RIGHT'][1].astype(np.float16)\n\n        # lidar\n        lidar = input_data['LIDAR_TOP']\n        lidar_seg = input_data['LIDAR_TOP_SEG']\n\n        def lidar_to_ego_coordinate(lidar):\n            \"\"\"\n            Converts the LiDAR points given by the simulator into the ego agents\n            coordinate system\n            :param config: GlobalConfig, used to read out lidar orientation and location\n            :param lidar: the LiDAR point cloud as provided in the input of run_step\n            :return: lidar where the points are w.r.t. 0/0/0 of the car and the carla\n            coordinate system.\n            \"\"\"\n            lidar_rot = [0.0, 0.0, 0.0]\n            lidar_pos = [-0.39, 0.0, 1.84]\n\n            yaw = np.deg2rad(lidar_rot[2])\n            rotation_matrix = np.array([[np.cos(yaw), -np.sin(yaw), 0.0], [np.sin(yaw), np.cos(yaw), 0.0], [0.0, 0.0, 1.0]])\n\n            translation = np.array(lidar_pos)\n\n            # The double transpose is a trick to compute all the points together.\n            ego_lidar = (rotation_matrix @ lidar[1][:, :3].T).T + translation\n\n            return ego_lidar\n        \n        lidar = lidar_to_ego_coordinate(lidar)\n        lidar_360 = lidar\n        \n        bounding_boxes = self.get_bounding_boxes(lidar=lidar_360, radar=radar_front)\n        sensors_anno = self.get_sensors_anno()\n        \n        self.last_lidar = lidar\n        self.last_ego_transform = self.manager.ego_vehicles[0].get_transform()\n        # gps/imu\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n\n        # cam_bgr_depth\n        cam_bgr_front_depth = input_data['CAM_FRONT_DEPTH'][1][:, :, :3]\n        cam_bgr_front_left_depth = input_data['CAM_FRONT_LEFT_DEPTH'][1][:, :, :3]\n        cam_bgr_front_right_depth = input_data['CAM_FRONT_RIGHT_DEPTH'][1][:, :, :3]\n        cam_bgr_back_depth = input_data['CAM_BACK_DEPTH'][1][:, :, :3]\n        cam_bgr_back_left_depth = input_data['CAM_BACK_LEFT_DEPTH'][1][:, :, :3]\n        cam_bgr_back_right_depth = input_data['CAM_BACK_RIGHT_DEPTH'][1][:, :, :3]\n\n        # cam_sem_seg\n        cam_front_sem_seg = input_data[\"CAM_FRONT_SEM_SEG\"][1][:, :, 2]\n        cam_front_left_sem_seg = input_data[\"CAM_FRONT_LEFT_SEM_SEG\"][1][:, :, 2]\n        cam_front_right_sem_seg = input_data[\"CAM_FRONT_RIGHT_SEM_SEG\"][1][:, :, 2]\n        cam_back_sem_seg = input_data[\"CAM_BACK_SEM_SEG\"][1][:, :, 2]\n        cam_back_left_sem_seg = input_data[\"CAM_BACK_LEFT_SEM_SEG\"][1][:, :, 2]\n        cam_back_right_sem_seg = input_data[\"CAM_BACK_RIGHT_SEM_SEG\"][1][:, :, 2]\n\n        # cam_ins_seg\n        cam_front_ins_seg = input_data[\"CAM_FRONT_INS_SEG\"][1]\n        cam_front_left_ins_seg = input_data[\"CAM_FRONT_LEFT_INS_SEG\"][1]\n        cam_front_right_ins_seg = input_data[\"CAM_FRONT_RIGHT_INS_SEG\"][1]\n        cam_back_ins_seg = input_data[\"CAM_BACK_INS_SEG\"][1]\n        cam_back_left_ins_seg = input_data[\"CAM_BACK_LEFT_INS_SEG\"][1]\n        cam_back_right_ins_seg = input_data[\"CAM_BACK_RIGHT_INS_SEG\"][1]\n        \n        # cam_gray_depth, 16 bit would be ideal, but we can't afford the extra storage.\n        cam_gray_front_depth = convert_depth(cam_bgr_front_depth)\n        cam_gray_front_left_depth = convert_depth(cam_bgr_front_left_depth)\n        cam_gray_front_right_depth = convert_depth(cam_bgr_front_right_depth)\n        cam_gray_back_depth = convert_depth(cam_bgr_back_depth)\n        cam_gray_back_left_depth = convert_depth(cam_bgr_back_left_depth)\n        cam_gray_back_right_depth = convert_depth(cam_bgr_back_right_depth)\n        \n        # weather\n        weather = self._weather_to_dict(self.world.get_weather())\n\n        self.cam_bgr_mapping = {\n            'CAM_FRONT': 'cam_bgr_front',\n            'CAM_FRONT_LEFT': 'cam_bgr_front_left',\n            'CAM_FRONT_RIGHT': 'cam_bgr_front_right',\n            'CAM_BACK': 'cam_bgr_back',\n            'CAM_BACK_LEFT': 'cam_bgr_back_left',\n            'CAM_BACK_RIGHT': 'cam_bgr_back_right',\n        }\n\n        self.cam_bgr_depth_mapping = {\n            'CAM_FRONT': 'cam_bgr_front_depth',\n            'CAM_FRONT_LEFT': 'cam_bgr_front_left_depth',\n            'CAM_FRONT_RIGHT': 'cam_bgr_front_right_depth',\n            'CAM_BACK': 'cam_bgr_back_depth',\n            'CAM_BACK_LEFT': 'cam_bgr_back_left_depth',\n            'CAM_BACK_RIGHT': 'cam_bgr_back_right_depth',\n\n        }\n\n        self.cam_gray_depth_mapping = {\n            'CAM_FRONT': 'cam_gray_front_depth',\n            'CAM_FRONT_LEFT': 'cam_gray_front_left_depth',\n            'CAM_FRONT_RIGHT': 'cam_gray_front_right_depth',\n            'CAM_BACK': 'cam_gray_back_depth',\n            'CAM_BACK_LEFT': 'cam_gray_back_left_depth',\n            'CAM_BACK_RIGHT': 'cam_gray_back_right_depth',\n        }\n\n        self.cam_seg_mapping = {\n            'CAM_FRONT': 'cam_front_sem_seg',\n            'CAM_FRONT_LEFT': 'cam_front_left_sem_seg',\n            'CAM_FRONT_RIGHT': 'cam_front_right_sem_seg',\n            'CAM_BACK': 'cam_back_sem_seg',\n            'CAM_BACK_LEFT': 'cam_back_left_sem_seg',\n            'CAM_BACK_RIGHT': 'cam_back_right_sem_seg',\n        }\n\n        self.cam_ins_mapping = {\n            'CAM_FRONT': 'cam_front_ins_seg',\n            'CAM_FRONT_LEFT': 'cam_front_left_ins_seg',\n            'CAM_FRONT_RIGHT': 'cam_front_right_ins_seg',\n            'CAM_BACK': 'cam_back_ins_seg',\n            'CAM_BACK_LEFT': 'cam_back_left_ins_seg',\n            'CAM_BACK_RIGHT': 'cam_back_right_ins_seg',\n        }\n\n        self.radar_mapping = {\n            'RADAR_FRONT': 'radar_front',\n            'RADAR_FRONT_LEFT': 'radar_front_left',\n            'RADAR_FRONT_RIGHT': 'radar_front_right',\n            'RADAR_BACK_LEFT': 'radar_back_left',\n            'RADAR_BACK_RIGHT': 'radar_back_right',\n        }\n\n        self.cam_yaw_mapping = {\n            'CAM_FRONT': 0.0,\n            'CAM_FRONT_LEFT': -55.0,\n            'CAM_FRONT_RIGHT': 55.0,\n            'CAM_BACK': 180.0,\n            'CAM_BACK_LEFT': -110.0,\n            'CAM_BACK_RIGHT': 110.0,\n        }\n\n        results = {\n                # cam_bgr\n                'cam_bgr_front': cam_bgr_front,\n                'cam_bgr_front_left': cam_bgr_front_left,\n                'cam_bgr_front_right': cam_bgr_front_right,\n                'cam_bgr_back': cam_bgr_back,\n                'cam_bgr_back_left': cam_bgr_back_left,\n                'cam_bgr_back_right': cam_bgr_back_right,\n                'cam_bgr_top_down': cam_bgr_top_down,\n                # cam_sem_seg\n                'cam_front_sem_seg': cam_front_sem_seg,\n                'cam_front_left_sem_seg': cam_front_left_sem_seg,\n                'cam_front_right_sem_seg': cam_front_right_sem_seg,\n                'cam_back_sem_seg': cam_back_sem_seg,\n                'cam_back_left_sem_seg': cam_back_left_sem_seg,\n                'cam_back_right_sem_seg': cam_back_right_sem_seg,\n                # cam_ins_seg\n                'cam_front_ins_seg': cam_front_ins_seg,\n                'cam_front_left_ins_seg': cam_front_left_ins_seg,\n                'cam_front_right_ins_seg': cam_front_right_ins_seg,\n                'cam_back_ins_seg': cam_back_ins_seg,\n                'cam_back_left_ins_seg': cam_back_left_ins_seg,\n                'cam_back_right_ins_seg': cam_back_right_ins_seg,\n\n                # cam_gray_depth\n                # save the original bgr depth, please remember to post-process the depth\n                'cam_bgr_front_depth': cam_bgr_front_depth,\n                'cam_bgr_front_left_depth' : cam_bgr_front_left_depth,\n                'cam_bgr_front_right_depth': cam_bgr_front_right_depth,\n                'cam_bgr_back_depth': cam_bgr_back_depth,\n                'cam_bgr_back_left_depth': cam_bgr_back_left_depth,\n                'cam_bgr_back_right_depth': cam_bgr_back_right_depth,\n                \n                'cam_gray_front_depth': cam_gray_front_depth,\n                'cam_gray_front_left_depth': cam_gray_front_left_depth,\n                'cam_gray_front_right_depth': cam_gray_front_right_depth,\n                'cam_gray_back_depth': cam_gray_back_depth,\n                'cam_gray_back_left_depth': cam_gray_back_left_depth,\n                'cam_gray_back_right_depth': cam_gray_back_right_depth,\n                \n                # radar\n                'radar_front': radar_front,\n                'radar_front_left': radar_front_left,\n                'radar_front_right': radar_front_right,\n                'radar_back_left': radar_back_left,\n                'radar_back_right': radar_back_right,\n                # lidar\n                'lidar' : lidar_360,\n                'lidar_seg': lidar_seg,\n                # other\n                'gps': gps,\n                'speed': speed,\n                'compass': compass,\n                'weather': weather,\n                \"acceleration\":acceleration,\n                \"angular_velocity\":angular_velocity,\n                'bounding_boxes': bounding_boxes,\n                'sensors_anno': sensors_anno,\n                'throttle': control.throttle,\n                'steer': control.steer,\n                'brake': control.brake,\n                'reverse': control.reverse,\n                'town': self.town,\n                }\n        return results\n    \n    def _preprocess_sensor_spec(self, sensor_spec):\n        type_ = sensor_spec[\"type\"]\n        id_ = sensor_spec[\"id\"]\n        attributes = {}\n\n        if type_ == 'sensor.opendrive_map':\n            attributes['reading_frequency'] = sensor_spec['reading_frequency']\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        elif type_ == 'sensor.speedometer':\n            delta_time = CarlaDataProvider.get_world().get_settings().fixed_delta_seconds\n            attributes['reading_frequency'] = 1 / delta_time\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        if type_ == 'sensor.camera.rgb':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n        \n        elif type_ == 'sensor.camera.depth':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                roll=sensor_spec['roll'],\n                                                yaw=sensor_spec['yaw'])\n        \n        elif type_ == 'sensor.camera.semantic_segmentation':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                roll=sensor_spec['roll'],\n                                                yaw=sensor_spec['yaw'])\n        \n        elif type_ == 'sensor.camera.instance_segmentation':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                roll=sensor_spec['roll'],\n                                                yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.lidar.ray_cast':\n            attributes['range'] = str(sensor_spec['range'])\n            attributes['rotation_frequency'] = str(sensor_spec['rotation_frequency'])\n            attributes['channels'] = str(sensor_spec['channels'])\n            attributes['upper_fov'] = str(10)\n            attributes['lower_fov'] = str(-30)\n            attributes['points_per_second'] = str(sensor_spec['points_per_second'])\n            attributes['atmosphere_attenuation_rate'] = str(0.004)\n            attributes['dropoff_general_rate'] = str(sensor_spec['dropoff_general_rate'])\n            attributes['dropoff_intensity_limit'] = str(sensor_spec['dropoff_intensity_limit'])\n            attributes['dropoff_zero_intensity'] = str(sensor_spec['dropoff_zero_intensity'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.lidar.ray_cast_semantic':\n            attributes['range'] = str(sensor_spec['range'])\n            attributes['rotation_frequency'] = str(sensor_spec['rotation_frequency'])\n            attributes['channels'] = str(sensor_spec['channels'])\n            attributes['upper_fov'] = str(10)\n            attributes['lower_fov'] = str(-30)\n            attributes['points_per_second'] = str(sensor_spec['points_per_second'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.radar':\n            attributes['horizontal_fov'] = str(sensor_spec['horizontal_fov'])  # degrees\n            attributes['vertical_fov'] = str(sensor_spec['vertical_fov'])  # degrees\n            attributes['points_per_second'] = '1500'\n            attributes['range'] = sensor_spec['range']  # meters\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.gnss':\n            attributes['noise_alt_stddev'] = str(0.000005)\n            attributes['noise_lat_stddev'] = str(0.000005)\n            attributes['noise_lon_stddev'] = str(0.000005)\n            attributes['noise_alt_bias'] = str(0.0)\n            attributes['noise_lat_bias'] = str(0.0)\n            attributes['noise_lon_bias'] = str(0.0)\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation()\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n        elif type_ == 'sensor.other.imu':\n            attributes['noise_accel_stddev_x'] = str(0.001)\n            attributes['noise_accel_stddev_y'] = str(0.001)\n            attributes['noise_accel_stddev_z'] = str(0.015)\n            attributes['noise_gyro_stddev_x'] = str(0.001)\n            attributes['noise_gyro_stddev_y'] = str(0.001)\n            attributes['noise_gyro_stddev_z'] = str(0.001)\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n        sensor_transform = carla.Transform(sensor_location, sensor_rotation)\n\n        return type_, id_, sensor_transform, attributes\n    \n    def setup_sensors(self):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        vehicle = self.manager.ego_vehicles[0]\n        self.sensor_interface = SensorInterface()\n        world = CarlaDataProvider.get_world()\n        bp_library = world.get_blueprint_library()\n        for sensor_spec in self.sensors():\n            type_, id_, sensor_transform, attributes = self._preprocess_sensor_spec(sensor_spec)\n\n            # These are the pseudosensors (not spawned)\n            if type_ == 'sensor.opendrive_map':\n                sensor = OpenDriveMapReader(vehicle, attributes['reading_frequency'])\n            elif type_ == 'sensor.speedometer':\n                sensor = SpeedometerReader(vehicle, attributes['reading_frequency'])\n\n            # These are the sensors spawned on the carla world\n            else:\n                bp = bp_library.find(type_)\n                for key, value in attributes.items():\n                    bp.set_attribute(str(key), str(value))\n                sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)\n\n            # setup callback\n            sensor.listen(CallBack(id_, type_, sensor, self.sensor_interface))\n            self._sensors_list.append(sensor)\n\n        # Some sensors miss sending data during the first ticks, so tick several times and remove the data\n        for _ in range(10):\n            world.tick()\n    \n    def sensors(self):\n        sensors = [\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                    },\n                # camera depth \n                {\n                    'type': 'sensor.camera.depth',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT_DEPTH'\n                    },\n                # camera seg\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT_SEM_SEG'\n                    },\n                # camera seg\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT_INS_SEG'\n                    },\n                # lidar\n                {   'type': 'sensor.lidar.ray_cast',\n                    'x': -0.39, 'y': 0.0, 'z': 1.84,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 85,\n                    'rotation_frequency': 10,\n                    'channels': 64,\n                    'points_per_second': 600000,\n                    'dropoff_general_rate': 0.0,\n                    'dropoff_intensity_limit': 0.0,\n                    'dropoff_zero_intensity': 0.0,\n                    'id': 'LIDAR_TOP'\n                    },\n                {   'type': 'sensor.lidar.ray_cast_semantic',\n                    'x': -0.39, 'y': 0.0, 'z': 1.84,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 85,\n                    'rotation_frequency': 10,\n                    'channels': 64,\n                    'points_per_second': 600000,\n                    'id': 'LIDAR_TOP_SEG'\n                    },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                    },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                    },\n                # rader\n                {\n                    'type': 'sensor.other.radar', \n                    'x': 2.27, 'y': 0.0, 'z': 0.48, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_FRONT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': 1.21, 'y': -0.85, 'z': 0.74, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_FRONT_LEFT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': 1.21, 'y': 0.85, 'z': 0.74, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_FRONT_RIGHT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': -2.0, 'y': -0.67, 'z': 0.51, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_BACK_LEFT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': -2.0, 'y': 0.67, 'z': 0.51, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_BACK_RIGHT'\n                    },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                    },\n\n                ### Debug sensor, not used by the model\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.0, 'y': 0.0, 'z': 50.0,\n                    'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'TOP_DOWN'\n                    },\n            ]\n        self.sensors_mapping = {}\n        for sensor in sensors:\n            self.sensors_mapping[sensor['id']] = sensor\n        return sensors\n\n    def _get_position(self, tick_data):\n        gps = tick_data['gps']\n        gps = (gps - self._command_planner.mean) * self._command_planner.scale\n        return gps\n    \n    def get_target_gps(self, gps, compass):\n\t\t# target gps\n        def gps_to_location(gps):\n            # gps content: numpy array: [lat, lon, alt]\n            lat, lon, z = gps\n            scale = math.cos(self.lat_ref * math.pi / 180.0)\n            my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n            mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n            y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n            x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n            z = float(z)\n            location = carla.Location(x=x, y=y, z=z)\n            return location\n            pass\n        global_plan_gps = self._global_plan[:]\n        next_gps, _ = global_plan_gps[min(self.navigation_idx+1, len(global_plan_gps)-1)]\n        next_gps = np.array([next_gps['lat'], next_gps['lon'], next_gps['z']])\n        next_vec_in_global = gps_to_location(next_gps) - gps_to_location(gps)\n        ref_rot_in_global = carla.Rotation(yaw=np.rad2deg(compass)-90.0)\n        loc_in_ev = vec_global_to_ref(next_vec_in_global, ref_rot_in_global)\n        \n        if np.sqrt(loc_in_ev.x**2+loc_in_ev.y**2) < 12.0 and loc_in_ev.x < 0.0:\n            self.navigation_idx += 1\n        \n        self.navigation_idx = min(self.navigation_idx, len(self._global_plan)-2)\n        _, road_option_0 = global_plan_gps[max(0, self.navigation_idx)]\n        gps_point, road_option_1 = global_plan_gps[self.navigation_idx+1]\n        gps_point = np.array([gps_point['lat'], gps_point['lon'], gps_point['z']])\n        if (road_option_0 in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]) \\\n                and (road_option_1 not in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]):\n            road_option = road_option_1\n        else:\n            road_option = road_option_0\n\n        return np.array(gps_point, dtype=np.float32), np.array([road_option.value], dtype=np.int8)\n\n    def save(self, near_node, far_node, near_command, far_command, tick_data, should_brake):\n        frame = self.count\n        # CARLA images are already in opencv's BGR format.\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front_left' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front_left'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front_right' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front_right'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back_left' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back_left'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back_right' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back_right'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_top_down' / (f'{frame:05}.jpg')), tick_data['cam_bgr_top_down'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front' / (f'{frame:05}.png')), tick_data['cam_front_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front_left' / (f'{frame:05}.png')), tick_data['cam_front_left_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front_right' / (f'{frame:05}.png')), tick_data['cam_front_right_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back' / (f'{frame:05}.png')), tick_data['cam_back_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back_left' / (f'{frame:05}.png')), tick_data['cam_back_left_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back_right' / (f'{frame:05}.png')), tick_data['cam_back_right_sem_seg'])\n\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_front' / (f'{frame:05}.png')), tick_data['cam_front_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_front_left' / (f'{frame:05}.png')), tick_data['cam_front_left_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_front_right' / (f'{frame:05}.png')), tick_data['cam_front_right_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_back' / (f'{frame:05}.png')), tick_data['cam_back_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_back_left' / (f'{frame:05}.png')), tick_data['cam_back_left_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_back_right' / (f'{frame:05}.png')), tick_data['cam_back_right_ins_seg'])\n\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_front' / (f'{frame:05}.png')), tick_data['cam_gray_front_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_front_left' / (f'{frame:05}.png')), tick_data['cam_gray_front_left_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_front_right' / (f'{frame:05}.png')), tick_data['cam_gray_front_right_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_back' / (f'{frame:05}.png')), tick_data['cam_gray_back_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_back_left' / (f'{frame:05}.png')), tick_data['cam_gray_back_left_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_back_right' / (f'{frame:05}.png')), tick_data['cam_gray_back_right_depth'])\n        \n        with h5py.File(str(self.save_path / 'radar' / (f'{frame:05}.h5')), 'w') as f:\n            f.create_dataset('radar_front', data=tick_data['radar_front'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_front_left', data=tick_data['radar_front_left'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_front_right', data=tick_data['radar_front_right'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_back_left', data=tick_data['radar_back_left'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_back_right', data=tick_data['radar_back_right'], compression='gzip', compression_opts=9, chunks=True)\n\n        # Specialized LiDAR compression format\n        header = laspy.LasHeader(point_format=0)  # LARS point format used for storing\n        header.offsets = np.min(tick_data['lidar'], axis=0)\n        point_precision = 0.001\n        header.scales = np.array([point_precision, point_precision, point_precision])\n\n        with laspy.open(self.save_path / 'lidar' / (f'{frame:05}.laz'), mode='w', header=header) as writer:\n            point_record = laspy.ScaleAwarePointRecord.zeros(tick_data['lidar'].shape[0], header=header)\n            point_record.x = tick_data['lidar'][:, 0]\n            point_record.y = tick_data['lidar'][:, 1]\n            point_record.z = tick_data['lidar'][:, 2]\n            writer.write_points(point_record)\n\n        anno_data = {\n                'x': tick_data['pos'][0],\n                'y': tick_data['pos'][1],\n                'throttle': tick_data['throttle'],\n                'steer': tick_data['steer'],\n                'brake': tick_data['brake'],\n                'reverse': tick_data['reverse'],\n                'theta': tick_data['compass'],\n                'speed': tick_data['speed'],\n                'x_command_far': far_node[0],\n                'y_command_far': far_node[1],\n                'command_far': far_command.value,\n                'x_command_near': near_node[0],\n                'y_command_near': near_node[1],\n                'command_near': near_command.value,\n                'should_brake': should_brake,\n                'x_target': tick_data['x_target'],\n                'y_target': tick_data['y_target'],\n                # 'target_command': tick_data['target_command'].tolist(),\n                # 'target_gps': tick_data['target_gps'].tolist(),\n                'next_command': tick_data['next_command'],\n                'weather': tick_data['weather'],\n                \"acceleration\":tick_data[\"acceleration\"].tolist(),\n                \"angular_velocity\":tick_data[\"angular_velocity\"].tolist(),\n                'bounding_boxes': tick_data['bounding_boxes'],\n                'sensors': tick_data['sensors_anno'],\n                'only_ap_brake': tick_data['only_ap_brake'],\n                }\n        with gzip.open(self.save_path / 'anno' / f'{frame:05}.json.gz', 'wt', encoding='utf-8') as f:\n            json.dump(anno_data, f, indent=4)\n        if self.count > -1:\n            np.savez(self.save_path / 'expert_assessment' / f'{frame-1:05}.npz', np.concatenate((self.feature, self.value, np.array([self.action_index], dtype=np.float32))))\n            \n    # add feature (yzj)\n    def _point_inside_boundingbox(self, point, bb_center, bb_extent, multiplier=1.5):\n        A = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        B = carla.Vector2D(bb_center.x + multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        D = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y + multiplier * bb_extent.y)\n        M = carla.Vector2D(point.x, point.y)\n\n        AB = B - A\n        AD = D - A\n        AM = M - A\n        am_ab = AM.x * AB.x + AM.y * AB.y\n        ab_ab = AB.x * AB.x + AB.y * AB.y\n        am_ad = AM.x * AD.x + AM.y * AD.y\n        ad_ad = AD.x * AD.x + AD.y * AD.y\n\n        return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad \n    \n    def affected_by_traffic_light(self, traffic_light, center, window_size=50):\n        inx = min(window_size, len(CarlaDataProvider._ego_actor.route_plan))\n        if inx <= 1:\n            return False\n        for trans, _ in CarlaDataProvider._ego_actor.route_plan[:inx]:\n            if self._point_inside_boundingbox(trans.location, center, traffic_light.trigger_volume.extent):\n                return True\n        return False\n\n    def get_traffic_color(self, state):\n        if state == carla.libcarla.TrafficLightState.Green:\n            return 'green'\n        if state == carla.libcarla.TrafficLightState.Yellow:\n            return 'yellow'\n        if state == carla.libcarla.TrafficLightState.Red:\n            return 'red'\n        if state == carla.libcarla.TrafficLightState.Unknown:\n            return 'unknown'\n        if state == carla.libcarla.TrafficLightState.Off:\n            return 'off'\n        raise Exception(f\"{state} not in Green, Yellow, Red, Unknown, Off\")\n    \n    def get_affect_sign(self, actors):\n        all_actors = []\n        affect_signs = []\n        mini_sign = DIS_SIGN_SAVE + 1\n        most_affect_sign = None\n        # find all lights\n        ego_vehicle_waypoint = CarlaDataProvider.get_map().get_waypoint(self.manager.ego_vehicles[0].get_location())\n        for sign in actors:\n            flag = 0\n            sign_loc = sign.get_location()\n            if compute_2d_distance(sign_loc, self.manager.ego_vehicles[0].get_transform().location) > DIS_SIGN_SAVE:\n                continue\n            all_actors.append(sign)\n\n            # find all affect lights \n            if hasattr(sign, 'trigger_volume'):\n                sign_vol_loc = sign.trigger_volume.location\n                sign_vol_loc_world = sign.get_transform().transform(sign_vol_loc)\n                sign_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(sign_vol_loc_world)\n                while not sign_vol_loc_world_wp.is_intersection:\n                    if len(sign_vol_loc_world_wp.next(0.5)) > 0:\n                        next_sign_vol_loc_world_wp = sign_vol_loc_world_wp.next(0.5)[0]\n                    else:\n                        flag = 1\n                        break\n                    if next_sign_vol_loc_world_wp and not next_sign_vol_loc_world_wp.is_intersection:\n                        sign_vol_loc_world_wp = next_sign_vol_loc_world_wp\n                    else:\n                        break\n                if flag:\n                    continue\n                if self.affected_by_traffic_light(sign, carla.Location(x=sign_vol_loc_world_wp.transform.location.x, y=sign_vol_loc_world_wp.transform.location.y, z=0)):\n                    affect_signs.append(sign)\n                    dis = np.abs(compute_2d_distance(ego_vehicle_waypoint.transform.location, sign.get_transform().transform(sign.trigger_volume.location)))\n                    if dis < mini_sign:\n                        most_affect_sign = sign\n                        mini_sign = dis\n            else:\n                sign_vol_loc = sign.get_transform().location\n                sign_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(sign_vol_loc)\n                dis = compute_2d_distance(sign_vol_loc_world_wp.transform.location, ego_vehicle_waypoint.transform.location)\n                forward_vec = self.manager.ego_vehicles[0].get_transform().get_forward_vector()\n                ray = sign_vol_loc_world_wp.transform.location - self.manager.ego_vehicles[0].get_location()\n                if forward_vec.dot(ray) < 0:\n                    continue\n                if dis < mini_sign:\n                    most_affect_sign = sign\n                    mini_sign = dis\n        return all_actors, most_affect_sign\n\n    def get_actor_filter_traffic_sign(self):\n        actor_data = EasyDict({})\n        speed_limit_sign = list(CarlaDataProvider.get_world().get_actors().filter(\"*traffic.speed_limit*\")) # carla.libcarla.TrafficSign\n        stop_sign = list(CarlaDataProvider.get_world().get_actors().filter(\"*traffic.stop*\")) # carla.libcarla.TrafficSign\n        yield_sign = list(CarlaDataProvider.get_world().get_actors().filter(\"*traffic.yield*\")) # carla.libcarla.TrafficSign\n        warning = list(CarlaDataProvider.get_world().get_actors().filter('*warning*'))\n        dirtdebris = list(CarlaDataProvider.get_world().get_actors().filter('*dirtdebris*'))\n        cone = list(CarlaDataProvider.get_world().get_actors().filter('*cone*'))\n\n        actors = speed_limit_sign + stop_sign + yield_sign + warning + dirtdebris + cone\n        all_actors, most_affect_sign = self.get_affect_sign(actors)\n        actor_data.actors = all_actors\n        actor_data.most_affect_sign = most_affect_sign\n        return actor_data\n\n    def get_actor_filter_traffic_light(self):\n        actor_data = EasyDict({})\n        lights = CarlaDataProvider.get_world().get_actors().filter(\"*traffic_light*\")\n        all_lights = []\n        affect_lights = []\n        most_affect_light = None\n        mini_lt = DIS_LIGHT_SAVE + 1\n\n        # find all lights\n        for lt in lights:\n            flag = 0\n            lt_loc = lt.get_location()\n            if compute_2d_distance(lt_loc, self.manager.ego_vehicles[0].get_location()) > DIS_LIGHT_SAVE: # lidar range\n                continue\n            all_lights.append(lt)\n\n            # find all affect lights \n            lt_vol_loc = lt.trigger_volume.location\n            lt_vol_loc_world = lt.get_transform().transform(lt_vol_loc)\n            lt_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(lt_vol_loc_world)\n            while not lt_vol_loc_world_wp.is_intersection:\n                if len(lt_vol_loc_world_wp.next(0.5)) > 0:\n                    next_lt_vol_loc_world_wp = lt_vol_loc_world_wp.next(0.5)[0]\n                else:\n                    flag = 1\n                    break \n                if next_lt_vol_loc_world_wp and not next_lt_vol_loc_world_wp.is_intersection:\n                    lt_vol_loc_world_wp = next_lt_vol_loc_world_wp\n                else:\n                    break\n            if flag:\n                continue\n            if self.affected_by_traffic_light(lt, carla.Location(x=lt_vol_loc_world_wp.transform.location.x, y=lt_vol_loc_world_wp.transform.location.y, z=0)):\n                affect_lights.append(lt)\n                # find most affect light_actor, min_dis=DIS_LIGHT_SAVE\n                dis = np.abs(compute_2d_distance(lt.get_transform().transform(lt.trigger_volume.location), self.manager.ego_vehicles[0].get_location()))\n                forward_vec = self.manager.ego_vehicles[0].get_transform().get_forward_vector()\n                ray = lt.get_transform().transform(lt.trigger_volume.location) - self.manager.ego_vehicles[0].get_location()\n                if forward_vec.dot(ray) < 0:\n                    continue\n                if dis < mini_lt:\n                    most_affect_light = lt\n                    mini_lt = dis\n        \n        actor_data.lights = all_lights\n        actor_data.affect_lights = affect_lights\n        actor_data.most_affect_light = most_affect_light\n\n        #  get distance\n        if most_affect_light is not None:\n            trigger_volume = most_affect_light.trigger_volume\n            box = trigger_volume.extent\n            loc = trigger_volume.location\n            ori = trigger_volume.rotation.get_forward_vector()\n            trigger_loc = [loc.x, loc.y, loc.z]\n            trigger_ori = [ori.x, ori.y, ori.z]\n            trigger_box = [box.x, box.y]\n\n            world_loc = most_affect_light.get_transform().transform(loc)\n            world_loc_wp = CarlaDataProvider.get_map().get_waypoint(world_loc)\n            while not world_loc_wp.is_intersection:\n                next_world_loc_wp = world_loc_wp.next(0.5)[0]\n                if next_world_loc_wp and not next_world_loc_wp.is_intersection:\n                    world_loc_wp = next_world_loc_wp\n                else:\n                    break\n            \n            world_loc_wp = carla.Location(x=world_loc_wp.transform.location.x, y=world_loc_wp.transform.location.y, z=0)\n            pos = self.manager.ego_vehicles[0].get_location()\n            pos = carla.Location(x=pos.x, y=pos.y, z=0)\n\n            # ego2lane_dis = world_loc_wp.distance(pos)\n            ego2lane_dis = compute_2d_distance(world_loc_wp, pos)\n            ego2light_dis = compute_2d_distance(most_affect_light.get_location(), self.manager.ego_vehicles[0].get_location())\n            most_affect_light_id = most_affect_light.id\n            most_affect_light_state = self.get_traffic_color(most_affect_light.state)\n\n            # record data\n            actor_data.most_affect_light = EasyDict()\n            actor_data.most_affect_light.id = most_affect_light_id\n            actor_data.most_affect_light.state = most_affect_light_state\n            actor_data.most_affect_light.ego2lane_dis = ego2lane_dis\n            actor_data.most_affect_light.ego2light_dis = ego2light_dis\n            actor_data.most_affect_light.trigger_volume = EasyDict()\n            actor_data.most_affect_light.trigger_volume.location = trigger_loc\n            actor_data.most_affect_light.trigger_volume.orientation = trigger_ori\n            actor_data.most_affect_light.trigger_volume.extent = trigger_box\n        return actor_data \n\n        \n    def get_actor_filter_vehicle(self):\n        vehicles_dict = EasyDict({})\n\n        vehicles = self.world.get_actors().filter('*vehicle*')\n        vehicles_list = []\n        for actor in vehicles:\n            dist = compute_2d_distance(actor.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            # Filter for the vehicles within DIS_CAR_SAVE m\n            if dist < DIS_CAR_SAVE: # lidar range\n                vehicles_list.append(actor)\n        vehicles_dict.vehicle = vehicles_list\n\n        others = self.world.get_actors().filter('*static.prop.mesh*')\n        static_list = []\n        for actor in others:\n            # filter static vehicle\n            mesh_path = actor.attributes['mesh_path'].split('/Game/Carla/')[1]\n            if 'Car' in mesh_path or 'Truck' in mesh_path or 'Bus' in mesh_path or 'Motorcycle' in mesh_path or 'Bicycle' in mesh_path:\n                dist = compute_2d_distance(actor.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                # Filter for the vehicles within DIS_CAR_SAVE\n                if dist < DIS_CAR_SAVE: # lidar range\n                    static_list.append(actor)\n        vehicles_dict.static = static_list\n        return vehicles_dict\n    \n\n    def _get_forward_speed(self, transform=None, velocity=None):\n        \"\"\" Convert the vehicle transform directly to forward speed \"\"\"\n        if not velocity:\n            velocity = self.manager.ego_vehicles[0].get_velocity()\n        if not transform:\n            transform = self.manager.ego_vehicles[0].get_transform()\n\n        vel_np = np.array([velocity.x, velocity.y, velocity.z])\n        pitch = np.deg2rad(transform.rotation.pitch)\n        yaw = np.deg2rad(transform.rotation.yaw)\n        orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)])\n        speed = np.dot(vel_np, orientation)\n        return speed\n    \n    def get_sensors_anno(self):\n        results = {}\n        sensors = {}\n        for value in self.world.get_actors().filter('*sensor.camera.rgb'):\n            sensors[value.attributes['role_name']] = value\n\n        for key in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT', 'TOP_DOWN']:\n            value = sensors[key]\n            location = value.get_transform().location\n            rotation = value.get_transform().rotation\n            world2cam = value.get_transform().get_inverse_matrix()\n            width = int(value.attributes['image_size_x'])\n            height = int(value.attributes['image_size_y'])\n            fov = float(value.attributes['fov'])\n            K = build_projection_matrix(width, height, fov=fov)\n            cam2ego = get_matrix(location=[self.sensors_mapping[key]['x'], self.sensors_mapping[key]['y'], self.sensors_mapping[key]['z']], \n                                 rotation=[self.sensors_mapping[key]['pitch'], self.sensors_mapping[key]['roll'], self.sensors_mapping[key]['yaw']])\n            result ={\n                'location': [location.x, location.y, location.z], \n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'intrinsic': K.tolist(),\n                'world2cam': world2cam,\n                'cam2ego': cam2ego.tolist(),\n                'fov': fov,\n                'image_size_x': width,\n                'image_size_y': height,\n            }\n            results[key] = result\n\n        # radar\n        for value in self.world.get_actors().filter('*sensor.other.radar*'):\n            sensors[value.attributes['role_name']] = value\n\n        for key in ['RADAR_FRONT','RADAR_FRONT_LEFT','RADAR_FRONT_RIGHT', 'RADAR_BACK_LEFT', 'RADAR_BACK_RIGHT']:\n            value = sensors[key]\n            location = value.get_transform().location\n            rotation = value.get_transform().rotation\n            world2radar = value.get_transform().get_inverse_matrix()\n            radar2ego = get_matrix(location=[self.sensors_mapping[key]['x'], self.sensors_mapping[key]['y'], self.sensors_mapping[key]['z']], \n                        rotation=[self.sensors_mapping[key]['pitch'], self.sensors_mapping[key]['roll'], self.sensors_mapping[key]['yaw']])\n            result ={\n                'location': [location.x, location.y, location.z], \n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'world2radar': world2radar,\n                'radar2ego': radar2ego.tolist(),\n            }\n            results[key] = result\n        \n        # lidar\n        for value in self.world.get_actors().filter('*sensor.lidar.ray_cast*'):\n            sensors[value.attributes['role_name']] = value\n\n        for key in ['LIDAR_TOP']:\n            value = sensors[key]\n            location = value.get_transform().location\n            rotation = value.get_transform().rotation\n            world2lidar = value.get_transform().get_inverse_matrix()\n            lidar2ego = get_matrix(location=[self.sensors_mapping[key]['x'], self.sensors_mapping[key]['y'], self.sensors_mapping[key]['z']], \n                        rotation=[self.sensors_mapping[key]['pitch'], self.sensors_mapping[key]['roll'], self.sensors_mapping[key]['yaw']])\n            result ={\n                'location': [location.x, location.y, location.z], \n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'world2lidar': world2lidar,\n                'lidar2ego': lidar2ego.tolist(),\n            }\n            results[key] = result\n        return results\n\n    def get_bounding_boxes(self, lidar=None, radar=None):\n        results = []\n\n        # ego_vehicle\n        npc = self.manager.ego_vehicles[0]\n        npc_id = str(npc.id)\n        npc_type_id = npc.type_id\n        npc_base_type = npc.attributes['base_type']\n        location = npc.get_transform().location\n        rotation = npc.get_transform().rotation\n        # \n        # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n        # center, extent = get_center_and_extent(verts)\n        # from carla official\n        # bb_cords = _bounding_box_to_world(npc.bounding_box)\n        # world_cord = _vehicle_to_world(bb_cords, npc)\n        # from handcraft\n        extent = npc.bounding_box.extent\n        center = npc.get_transform().transform(npc.bounding_box.location)\n        local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n        global_verts = []\n        for l_v in local_verts:\n            g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n            global_verts.append([g_v.x, g_v.y, g_v.z])\n        ###################\n        ego_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n        ego_brake = npc.get_control().brake\n        ego_matrix = np.array(npc.get_transform().get_matrix())\n        ego_yaw = np.deg2rad(rotation.yaw)\n        road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n        lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n        section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n        world2ego = npc.get_transform().get_inverse_matrix()\n\n        result = {\n            'class': 'ego_vehicle',\n            'id': npc_id,\n            'type_id': npc_type_id,\n            'base_type': npc_base_type,\n            'location': [location.x, location.y, location.z],\n            'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n            'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n            'center': [center.x, center.y, center.z],\n            'extent': [extent.x, extent.y, extent.z],\n            'world_cord': global_verts,\n            'semantic_tags': [npc.semantic_tags],\n            'color': npc.attributes['color'],\n            'speed': ego_speed,\n            'brake': ego_brake,\n            'road_id': road_id,\n            'lane_id': lane_id,\n            'section_id': section_id,\n            'world2ego': world2ego,\n        }\n        results.append(result)\n\n        # vehicles.vehicle\n        vehicles = self.get_actor_filter_vehicle()\n        for npc in vehicles.vehicle:\n            if not npc.is_alive: continue\n            if npc.id == self.manager.ego_vehicles[0].id: continue\n            npc_id = str(npc.id)\n            location = npc.get_transform().location\n            rotation = npc.get_transform().rotation\n            road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n            lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n            section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n            # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n            # center, extent = get_center_and_extent(verts)\n            # # from carla official\n            # bb_cords = _bounding_box_to_world(npc.bounding_box)\n            # world_cord = _vehicle_to_world(bb_cords, npc)\n            # #\n            # from handcraft\n            world2vehicle = npc.get_transform().get_inverse_matrix()\n            extent = npc.bounding_box.extent\n            center = npc.get_transform().transform(npc.bounding_box.location)\n            local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n            global_verts = []\n            for l_v in local_verts:\n                g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                global_verts.append([g_v.x, g_v.y, g_v.z])\n            ###################\n            vehicle_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n            vehicle_brake = npc.get_control().brake\n            vehicle_matrix = np.array(npc.get_transform().get_matrix())\n            yaw = np.deg2rad(rotation.yaw)\n            try:\n                light_state = str(npc.get_light_state()).split('.')[-1]\n            except:\n                light_state = 'None'\n            # Computes how many LiDAR hits are on a bounding box. Used to filter invisible boxes during data loading.\n            relative_yaw = normalize_angle(yaw - ego_yaw)\n            relative_pos = get_relative_transform(ego_matrix, vehicle_matrix)\n            if not lidar is None:\n                num_in_bbox_lidar_points = self.get_lidar_points_in_bbox(relative_pos, relative_yaw, extent, lidar)\n            else:\n                num_in_bbox_lidar_points = -1\n            \n            distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            result = {\n                'class': 'vehicle',\n                'state': 'dynamic',\n                'id': npc_id,\n                'location': [location.x, location.y, location.z],\n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                'center': [center.x, center.y, center.z],\n                'extent': [extent.x, extent.y, extent.z],\n                'world_cord': global_verts,\n                'semantic_tags': npc.semantic_tags,\n                'type_id': npc.type_id,\n                'color': npc.attributes['color'],\n                'base_type': npc.attributes['base_type'],\n                'num_points': int(num_in_bbox_lidar_points),\n                'distance': distance,\n                'speed': vehicle_speed,\n                'brake': vehicle_brake,\n                'light_state': light_state,\n                'road_id': road_id,\n                'lane_id': lane_id,\n                'section_id': section_id,\n                'world2vehicle': world2vehicle,\n                # 'actor': npc, # for debug \n              }\n            results.append(result)\n        \n        # vehicles.static\n        car_bbox_list = self.world.get_level_bbs(carla.CityObjectLabel.Car) \n        bicycle_list = self.world.get_level_bbs(carla.CityObjectLabel.Bicycle)\n        bus_list = self.world.get_level_bbs(carla.CityObjectLabel.Bus)\n        motorcycle_list = self.world.get_level_bbs(carla.CityObjectLabel.Motorcycle)\n        train_list = self.world.get_level_bbs(carla.CityObjectLabel.Train)\n        truck_list = self.world.get_level_bbs(carla.CityObjectLabel.Truck)\n        vehicles_static_bbox = car_bbox_list + bicycle_list + bus_list + motorcycle_list + train_list + truck_list\n        vehicles_static_bbox_nearby = []\n        for v_s in vehicles_static_bbox:\n            if compute_2d_distance(v_s.location, self.manager.ego_vehicles[0].get_transform().location) < (DIS_LIGHT_SAVE + 20):\n                vehicles_static_bbox_nearby.append(v_s)\n        for npc in vehicles.static:\n            if not npc.is_alive: continue\n            new_bbox = None\n            min_dis = 50\n            for vehicle_bbox in vehicles_static_bbox_nearby:\n                dis = compute_2d_distance(npc.get_transform().location, vehicle_bbox.location)\n                if dis < min_dis:\n                    new_bbox = vehicle_bbox\n                    min_dis = dis\n            if min_dis > 20:\n                continue\n            if not new_bbox:\n                raise Exception('new_bbox is None')\n            if new_bbox not in vehicles_static_bbox_nearby:\n                raise Exception('new_bbox not in vehicles_static_bbox_nearby')\n            vehicles_static_bbox_nearby.remove(new_bbox)\n            npc_id = str(npc.id)\n            # location = new_bbox.location\n            # rotation = new_bbox.rotation\n            # center = new_bbox.location\n            extent = new_bbox.extent\n            ####\n            location = npc.get_transform().location\n            rotation = npc.get_transform().rotation\n            road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n            lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n            section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n            # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n            # center, extent = get_center_and_extent(verts)\n            # # from carla official\n            # bb_cords = _bounding_box_to_world(npc.bounding_box)\n            # world_cord = _vehicle_to_world(bb_cords, npc)\n            # #\n            # from handcraft\n            world2vehicle = npc.get_transform().get_inverse_matrix()\n            # extent = npc.bounding_box.extent\n            # extent = carla.Vector3D(extent.y, extent.x, extent.z) # staic need swap\n            center = npc.get_transform().transform(npc.bounding_box.location)\n            local_verts = calculate_cube_vertices(npc.bounding_box.location, extent)\n            global_verts = []\n            for l_v in local_verts:\n                g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                # g_v = np.dot(np.matrix(npc.get_transform().get_inverse_matrix()).I, [l_v[0], l_v[1], l_v[2],1])\n                global_verts.append([g_v.x, g_v.y, g_v.z])\n            ###################\n            vehicle_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n            vehicle_brake = 1.0\n            vehicle_matrix = np.array(npc.get_transform().get_matrix())\n            yaw = np.deg2rad(rotation.yaw)\n            light_state= 'NONE'\n            # Computes how many LiDAR hits are on a bounding box. Used to filter invisible boxes during data loading.\n            relative_yaw = normalize_angle(yaw - ego_yaw)\n            relative_pos = get_relative_transform(ego_matrix, vehicle_matrix)\n            if not lidar is None:\n                num_in_bbox_points = self.get_lidar_points_in_bbox(relative_pos, relative_yaw, extent, lidar)\n            else:\n                num_in_bbox_points = -1\n\n            distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            result = {\n                'class': 'vehicle',\n                'state': 'static',\n                'id': npc_id,\n                'location': [location.x, location.y, location.z],\n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                'center': [center.x, center.y, center.z],\n                'extent': [extent.x, extent.y, extent.z],\n                'world_cord': global_verts,\n                'semantic_tags': npc.semantic_tags,\n                'type_id': npc.attributes['mesh_path'],\n                'num_points': int(num_in_bbox_points),\n                'distance': distance,\n                'speed': vehicle_speed,\n                'brake': vehicle_brake,\n                'light_state': light_state,\n                'road_id': road_id,\n                'lane_id': lane_id,\n                'section_id': section_id,\n                'world2vehicle': world2vehicle,\n                # 'actor': npc, # for debug\n                }\n            results.append(result)\n        \n        # pedestrians\n        pedestrians = self.world.get_actors().filter('walker*')\n        for npc in pedestrians:\n            if not npc.is_alive: \n                continue\n            else:\n                try:\n                    if compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location) < DIS_WALKER_SAVE:\n                        npc_id = str(npc.id)\n                        location = npc.get_transform().location\n                        rotation = npc.get_transform().rotation\n                        road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n                        lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n                        section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n                        # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n                        # center, extent = get_center_and_extent(verts)\n                        # # from carla official\n                        # bb_cords = _bounding_box_to_world(npc.bounding_box)\n                        # world_cord = _vehicle_to_world(bb_cords, npc)\n                        # #\n                        # from handcraft\n                        world2ped = npc.get_transform().get_inverse_matrix()\n                        extent = npc.bounding_box.extent\n                        center = npc.get_transform().transform(npc.bounding_box.location)\n                        local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n                        global_verts = []\n                        for l_v in local_verts:\n                            g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                            global_verts.append([g_v.x, g_v.y, g_v.z])\n                        ###################\n                        walker_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n                        # walker_speed = npc.attributes['speed'] #(TODO) yzj\n                        walker_matrix = np.array(npc.get_transform().get_matrix())\n                        yaw = np.deg2rad(rotation.yaw)\n                        bones_3d_lines = build_skeleton(npc, self.skeleton_links)\n                        # Computes how many LiDAR hits are on a bounding box. Used to filter invisible boxes during data loading.\n                        relative_yaw = normalize_angle(yaw - ego_yaw)\n                        relative_pos = get_relative_transform(ego_matrix, walker_matrix)\n                        if not lidar is None:\n                            num_in_bbox_points = self.get_lidar_points_in_bbox(relative_pos, relative_yaw, extent, lidar)\n                        else:\n                            num_in_bbox_points = -1\n\n                        distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                        result = {\n                            'class': 'walker',\n                            'id': npc_id,\n                            'location': [location.x, location.y, location.z],\n                            'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                            'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                            'center': [center.x, center.y, center.z],\n                            'extent': [extent.x, extent.y, extent.z],\n                            'world_cord': global_verts,\n                            'semantic_tags': npc.semantic_tags,\n                            'type_id': npc.type_id,\n                            'gender': npc.attributes['gender'],\n                            'age': npc.attributes['age'],\n                            'num_points': int(num_in_bbox_points),\n                            'distance': distance,\n                            'speed': walker_speed,\n                            'bone': bones_3d_lines,\n                            'road_id': road_id,\n                            'lane_id': lane_id,\n                            'section_id': section_id,\n                            'world2ped': world2ped,\n                            # 'actor': npc, # for debug\n                        }\n                        results.append(result)\n                except RuntimeError:\n                    continue\n        \n        # traffic_light\n        traffic_light = self.get_actor_filter_traffic_light()\n        traffic_light_bbox = self.world.get_level_bbs(carla.CityObjectLabel.TrafficLight)\n        traffic_light_bbox_nearby = []\n        for light_bbox in traffic_light_bbox:\n            if compute_2d_distance(light_bbox.location, self.manager.ego_vehicles[0].get_transform().location) < (DIS_LIGHT_SAVE + 20):\n                traffic_light_bbox_nearby.append(light_bbox)\n        for npc in traffic_light.lights:\n            new_bbox = None\n            min_dis = 50\n            for light_bbox in traffic_light_bbox_nearby:\n                dis = compute_2d_distance(npc.get_transform().location, light_bbox.location)\n                if dis < min_dis:\n                    new_bbox = light_bbox\n                    min_dis = dis\n            if min_dis > 20:\n                continue\n            traffic_light_bbox_nearby.remove(new_bbox)\n            npc_id = str(npc.id)\n            location = new_bbox.location\n            rotation = new_bbox.rotation\n            center = new_bbox.location\n            extent = new_bbox.extent\n            road_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).road_id\n            lane_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).lane_id\n            section_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).section_id\n            volume_location = npc.get_transform().transform(npc.trigger_volume.location)\n            volume_rotation = carla.Rotation(pitch=(rotation.pitch + npc.trigger_volume.rotation.pitch)%360, roll=(rotation.roll + npc.trigger_volume.rotation.roll)%360, yaw=(rotation.yaw + npc.trigger_volume.rotation.yaw) % 360)\n            state = npc.state\n            distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            if traffic_light.most_affect_light and str(traffic_light.most_affect_light.id) == npc_id:\n                affects_ego = True\n            else:\n                affects_ego = False\n            result = {\n                'class': 'traffic_light',\n                'id': npc_id,\n                'location': [location.x, location.y, location.z],\n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'center': [center.x, center.y, center.z],\n                'extent': [extent.x, extent.y, extent.z],\n                'semantic_tags': npc.semantic_tags,\n                'type_id': npc.type_id,\n                'distance': distance,\n                'state': state,\n                'affects_ego': affects_ego,\n                'trigger_volume_location': [volume_location.x, volume_location.y, volume_location.z],\n                'trigger_volume_rotation': [volume_rotation.pitch, volume_rotation.roll, volume_rotation.yaw],\n                'trigger_volume_extent': [npc.trigger_volume.extent.x, npc.trigger_volume.extent.y, npc.trigger_volume.extent.z],\n                'road_id': road_id,\n                'lane_id': lane_id,\n                'section_id': section_id,\n                # 'actor': npc, # for debug\n                # 'new_bbox': new_bbox, # for debug\n            }\n            results.append(result)\n        \n        # traffic_sign\n        traffic_sign = self.get_actor_filter_traffic_sign()\n        traffic_sign_bbox = self.world.get_level_bbs(carla.CityObjectLabel.TrafficSigns)\n        traffic_sign_bbox_nearby = []\n        for sign_bbox in traffic_sign_bbox:\n            if compute_2d_distance(sign_bbox.location, self.manager.ego_vehicles[0].get_transform().location) < (DIS_SIGN_SAVE + 20):\n                traffic_sign_bbox_nearby.append(sign_bbox)\n\n        for npc in traffic_sign.actors:\n            if hasattr(npc, 'trigger_volume'):\n                new_bbox = None\n                min_dis = 50\n                for sign_bbox in traffic_sign_bbox_nearby:\n                    dis = compute_2d_distance(npc.get_transform().location, sign_bbox.location)\n                    if dis < min_dis:\n                        new_bbox = sign_bbox\n                        min_dis = dis\n                if min_dis > 20:\n                    continue\n                traffic_sign_bbox_nearby.remove(new_bbox)\n                npc_id = str(npc.id)\n                world2sign = npc.get_transform().get_inverse_matrix()\n                location = new_bbox.location\n                rotation = new_bbox.rotation\n                center = new_bbox.location\n                extent = new_bbox.extent\n                road_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).road_id\n                lane_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).lane_id\n                section_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).section_id\n                volume_location = npc.get_transform().transform(npc.trigger_volume.location)\n                volume_rotation = carla.Rotation(pitch=(rotation.pitch + npc.trigger_volume.rotation.pitch)%360, roll=(rotation.roll + npc.trigger_volume.rotation.roll)%360, yaw=(rotation.yaw + npc.trigger_volume.rotation.yaw) % 360)\n                distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                if traffic_sign.most_affect_sign and str(traffic_sign.most_affect_sign.id) == npc_id:\n                    affects_ego = True\n                else:\n                    affects_ego = False\n                result = {\n                    'class': 'traffic_sign',\n                    'id': npc_id,\n                    'location': [location.x, location.y, location.z],\n                    'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                    'center': [center.x, center.y, center.z],\n                    'extent': [extent.x, extent.y, extent.z],\n                    # 'extent': [extent.x, 0.5, extent.z],\n                    'semantic_tags': npc.semantic_tags,\n                    'type_id': npc.type_id,\n                    'distance': distance,\n                    'affects_ego': affects_ego,\n                    'trigger_volume_location': [volume_location.x, volume_location.y, volume_location.z],\n                    'trigger_volume_rotation': [volume_rotation.pitch, volume_rotation.roll, volume_rotation.yaw],\n                    'trigger_volume_extent': [npc.trigger_volume.extent.x, npc.trigger_volume.extent.y, npc.trigger_volume.extent.z],\n                    'road_id': road_id,\n                    'lane_id': lane_id,\n                    'section_id': section_id,\n                    'world2sign': world2sign,\n                    # 'actor': npc, # for debug\n                    # 'new_bbox': new_bbox, # for debug\n                }\n            else:\n                npc_id = str(npc.id)\n                location = npc.get_transform().location\n                rotation = npc.get_transform().rotation\n                # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n                # center, extent = get_center_and_extent(verts)\n                # from handcraft\n                world2sign = npc.get_transform().get_inverse_matrix()\n                extent = npc.bounding_box.extent\n                center = npc.get_transform().transform(npc.bounding_box.location)\n                local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n                global_verts = []\n                for l_v in local_verts:\n                    g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                    global_verts.append([g_v.x, g_v.y, g_v.z])\n                road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n                lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n                section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n                # distance = npc.get_transform().location.distance(self.manager.ego_vehicles[0].get_transform().location)\n                distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                if traffic_sign.most_affect_sign and str(traffic_sign.most_affect_sign.id) == npc_id:\n                    affects_ego = True\n                else:\n                    affects_ego = False\n\n                result = {\n                    'class': 'traffic_sign',\n                    'id': npc_id,\n                    'location': [location.x, location.y, location.z],\n                    'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                    'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                    'center': [center.x, center.y, center.z],\n                    'extent': [extent.x, extent.y, extent.z],\n                    'world_cord': global_verts,\n                    # 'extent': [extent.x, 0.5, extent.z],\n                    'semantic_tags': npc.semantic_tags,\n                    'type_id': npc.type_id,\n                    'distance': distance,\n                    'affects_ego': affects_ego,\n                    'road_id': road_id,\n                    'lane_id': lane_id,\n                    'section_id': section_id,\n                    'world2sign': world2sign,\n                    # 'actor': npc, # for debug\n                }\n            results.append(result)\n        return results\n\n    def polar_to_cartesian(self, altitude, azimuth, depth):\n        \"\"\"\n        Convert polar coordinates (altitude, azimuth, depth) to Cartesian (x, y, z).\n        Altitude and azimuth are assumed to be in radians.\n        \"\"\"\n        z = depth * np.sin(altitude)\n        r_cos_altitude = depth * np.cos(altitude)\n        x = r_cos_altitude * np.cos(azimuth)\n        y = r_cos_altitude * np.sin(azimuth)\n        return x, y, z\n\n    def get_radar_points_in_bbox(self, vehicle_pos, vehicle_yaw, extent, radar_data):\n        \"\"\"\n        Checks for a given vehicle in ego coordinate system, how many RADAR hits there are in its bounding box.\n        :param vehicle_pos: Relative position of the vehicle w.r.t. the ego [x, y, z]\n        :param vehicle_yaw: Relative orientation of the vehicle w.r.t. the ego in radians\n        :param extent: List, half extent of the bounding box [length/2, width/2, height/2]\n        :param radar_data: RADAR data with structure [altitude, azimuth, depth, velocity]\n        :return: Returns the number of RADAR hits within the bounding box of the vehicle\n        \"\"\"\n        radar_cartesian = np.array([self.polar_to_cartesian(np.radians(altitude), np.radians(azimuth), depth)\n                                    for altitude, azimuth, depth, _ in radar_data])\n\n        rotation_matrix = np.array([[np.cos(vehicle_yaw), -np.sin(vehicle_yaw), 0.0],\n                                    [np.sin(vehicle_yaw), np.cos(vehicle_yaw), 0.0],\n                                    [0.0, 0.0, 1.0]])\n\n        # Transform RADAR points to vehicle coordinate system\n        vehicle_radar = (rotation_matrix.T @ (radar_cartesian - vehicle_pos).T).T\n\n        # Half extents for the bounding box\n        x, y, z = extent\n        num_hits = ((vehicle_radar[:, 0] <= x) & (vehicle_radar[:, 0] >= -x) & \n                    (vehicle_radar[:, 1] <= y) & (vehicle_radar[:, 1] >= -y) & \n                    (vehicle_radar[:, 2] <= z) & (vehicle_radar[:, 2] >= -z)).sum()\n        return num_hits\n    \n    def get_lidar_points_in_bbox(self, vehicle_pos, vehicle_yaw, extent, lidar):\n        \"\"\"\n        Checks for a given vehicle in ego coordinate system, how many LiDAR hit there are in its bounding box.\n        :param vehicle_pos: Relative position of the vehicle w.r.t. the ego\n        :param vehicle_yaw: Relative orientation of the vehicle w.r.t. the ego\n        :param extent: List, Extent of the bounding box\n        :param lidar: LiDAR point cloud\n        :return: Returns the number of LiDAR hits within the bounding box of the\n        vehicle\n        \"\"\"\n\n        rotation_matrix = np.array([[np.cos(vehicle_yaw), -np.sin(vehicle_yaw), 0.0],\n                                    [np.sin(vehicle_yaw), np.cos(vehicle_yaw), 0.0], [0.0, 0.0, 1.0]])\n\n        # LiDAR in the with the vehicle as origin\n        vehicle_lidar = (rotation_matrix.T @ (lidar - vehicle_pos).T).T\n\n        # check points in bbox\n        x, y, z = extent.x, extent.y, extent.z\n        num_points = ((vehicle_lidar[:, 0] < x) & (vehicle_lidar[:, 0] > -x) & (vehicle_lidar[:, 1] < y) &\n                    (vehicle_lidar[:, 1] > -y) & (vehicle_lidar[:, 2] < z) & (vehicle_lidar[:, 2] > -z)).sum()\n        return num_points\n    \n    def gps_to_location(self, gps):\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n        pass\n    \n    def _get_latlon_ref(self):\n        \"\"\"\n        Convert from waypoints world coordinates to CARLA GPS coordinates\n        :return: tuple with lat and lon coordinates\n        \"\"\"\n        xodr = CarlaDataProvider.get_map().to_opendrive()\n        tree = ET.ElementTree(ET.fromstring(xodr))\n\n        # default reference\n        lat_ref = 42.0\n        lon_ref = 2.0\n\n        for opendrive in tree.iter(\"OpenDRIVE\"):\n            for header in opendrive.iter(\"header\"):\n                for georef in header.iter(\"geoReference\"):\n                    if georef.text:\n                        str_list = georef.text.split(' ')\n                        for item in str_list:\n                            if '+lat_0' in item:\n                                lat_ref = float(item.split('=')[1])\n                            if '+lon_0' in item:\n                                lon_ref = float(item.split('=')[1])\n        return lat_ref, lon_ref"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/download_mini.sh",
    "content": "#!/bin/bash\n\n# Check if huggingface-hub is installed\nif ! python -m pip show huggingface-hub > /dev/null 2>&1; then\n  echo \"huggingface-hub is not installed. Installing now...\"\n  python -m pip install huggingface-hub\nelse\n  echo \"huggingface-hub is already installed.\"\nfi\n\nmkdir Bench2Drive-mini\n\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"HardBreakRoute_Town01_Route30_Weather3.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"DynamicObjectCrossing_Town02_Route13_Weather6.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"Accident_Town03_Route156_Weather0.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"YieldToEmergencyVehicle_Town04_Route165_Weather7.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"ConstructionObstacle_Town05_Route68_Weather8.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"ParkedObstacle_Town10HD_Route371_Weather7.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"ControlLoss_Town11_Route401_Weather11.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"AccidentTwoWays_Town12_Route1444_Weather0.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"OppositeVehicleTakingPriority_Town13_Route600_Weather2.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"VehicleTurningRoute_Town15_Route443_Weather1.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/efficiency_smoothness_benchmark.py",
    "content": "from scipy.signal import savgol_filter\n# import numpy.typing as npt\nimport numpy as np\nimport json\nimport re\nimport argparse\nimport os\n\n# (1) ego_jerk_metric,\nmax_abs_mag_jerk = 8.37  # [m/s^3]\n\n# (2) ego_lat_acceleration_metric\nmax_abs_lat_accel = 4.89  # [m/s^2]\n\n# (3) ego_lon_acceleration_metric\nmax_lon_accel = 2.40  # [m/s^2]\nmin_lon_accel = -4.05\n\n# (4) ego_yaw_acceleration_metric\nmax_abs_yaw_accel = 1.93  # [rad/s^2]\n\n# (5) ego_lon_jerk_metric\nmax_abs_lon_jerk = 4.13  # [m/s^3]\n\n# (6) ego_yaw_rate_metric\nmax_abs_yaw_rate = 0.95  # [rad/s]\n\n'''\nwindow size = 8\n'''\n\ndef chunk_arrays(arrays, m):\n    chunks = [chunk_array(arr, m) for arr in arrays]\n    return chunks\n\ndef chunk_array(arr, m):\n    chunks = [arr[i * m:(i + 1) * m] for i in range((len(arr) + m - 1) // m)]\n    return chunks\n\ndef seg_compute_comfort_metric(acceleration,\n    angular_velocity,\n    forward_vector,\n    right_vector,\n    location,\n    rotation,\n    window_size: int = 7,\n    poly_order: int = 2,\n    deriv_order: int = 1,\n    time_interval: float = 0.1,\n    per_step: int = 20):\n    episode_len = len(angular_velocity)\n    if episode_len <= per_step:\n        res = compute_comfort_metric( acceleration, angular_velocity, forward_vector, right_vector, location, rotation)\n        return 1. if res else 0.\n    seg_data = chunk_arrays([acceleration, angular_velocity, forward_vector, right_vector, location, rotation], per_step)\n    \n    res = []\n    for index in range(len(seg_data[0])):\n        if len(seg_data[0][index]) < per_step:\n            continue\n        res.append(compute_comfort_metric(seg_data[0][index], seg_data[1][index], seg_data[2][index], seg_data[3][index], seg_data[4][index], seg_data[5][index]))\n    return res.count(True) / len(res)\n    pass\n\ndef compute_comfort_metric(\n    acceleration,\n    angular_velocity,\n    forward_vector,\n    right_vector,\n    location,\n    rotation,\n    window_size: int = 7,\n    poly_order: int = 2,\n    deriv_order: int = 1,\n    time_interval: float = 0.1\n):\n    window_size = min(window_size, len(acceleration))\n    if not (poly_order < window_size):\n        raise ValueError(f\"{poly_order} < {window_size} does not hold!\")\n    \n    _2d_acceleration = np.array([[v[0], v[1]] for v in acceleration])\n    _2d_forward_vector = np.array([[vec[0], vec[1]] for vec in forward_vector])\n    _2d_right_vector = np.array([[vec[0], vec[1]] for vec in right_vector])\n    _z_angular_rate = np.array([a[2] for a in angular_velocity])\n    _z_yaw_rate = _phase_unwrap(_z_angular_rate)\n    \n    lon_acc = np.einsum('ij,ij->i', _2d_acceleration, _2d_forward_vector)\n    lat_acc = np.einsum('ij,ij->i', _2d_acceleration, _2d_right_vector)\n    magnitude_acc = np.hypot(_2d_acceleration[:, 0], _2d_acceleration[:, 1])\n    \n    _z_yaw_acc = savgol_filter(\n        _z_yaw_rate,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    _z_yaw_rate = savgol_filter(\n        _z_yaw_rate,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    lon_acc = savgol_filter(\n        lon_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    lat_acc = savgol_filter(\n        lat_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    magnitude_acc = savgol_filter(\n        magnitude_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    dx = time_interval \n    magnitude_jerk = savgol_filter(\n        magnitude_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        deriv=deriv_order,\n        delta=dx,\n        axis=-1,\n    )\n    \n    lon_jerk = savgol_filter(\n        lon_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        deriv=deriv_order,\n        delta=dx,\n        axis=-1,\n    )\n    \n    res = np.array([\n        _within_bound(\n        lon_acc, min_bound=min_lon_accel, max_bound=max_lon_accel\n    ),\n        _within_bound(\n        lat_acc, min_bound=-max_abs_lat_accel, max_bound=max_abs_lat_accel\n    ),\n        _within_bound(\n        magnitude_jerk, min_bound=-max_abs_mag_jerk, max_bound=max_abs_mag_jerk\n    ),\n        _within_bound(\n        lon_jerk, min_bound=-max_abs_lon_jerk, max_bound=max_abs_lon_jerk\n    ),\n        _within_bound(\n        _z_yaw_acc, min_bound=-max_abs_yaw_accel, max_bound=max_abs_yaw_accel\n    ),\n        _within_bound(\n        _z_yaw_rate, min_bound=-max_abs_yaw_rate, max_bound=max_abs_yaw_rate\n    )\n    ])\n    res = bool(np.all(res))\n    return res\n    \ndef _approximate_derivatives(\n    y,\n    x,\n    window_size: int = 5,\n    poly_order: int = 2,\n    deriv_order: int = 1,\n    axis: int = -1,\n):\n    window_size = min(window_size, len(x))\n\n    if not (poly_order < window_size):\n        raise ValueError(f\"{poly_order} < {window_size} does not hold!\")\n\n    dx = np.diff(x, axis=-1)\n    if not (dx > 0).all():\n        raise RuntimeError(\"dx is not monotonically increasing!\")\n\n    dx = dx.mean()\n    derivative = savgol_filter(\n        y,\n        polyorder=poly_order,\n        window_size=window_size,\n        deriv=deriv_order,\n        delta=dx,\n        axis=axis,\n    )\n    return derivative\n\ndef _within_bound(\n    metric,\n    min_bound = None,\n    max_bound = None,\n):\n    \"\"\"\n    Determines wether values in batch-dim are within bounds.\n    :param metric: metric values\n    :param min_bound: minimum bound, defaults to None\n    :param max_bound: maximum bound, defaults to None\n    :return: array of booleans wether metric values are within bounds\n    \"\"\"\n    min_bound = min_bound if min_bound else float(-np.inf)\n    max_bound = max_bound if max_bound else float(np.inf)\n    metric_values = np.array(metric)\n    metric_within_bound = (metric_values > min_bound) & (metric_values < max_bound)\n    return np.all(metric_within_bound, axis=-1)\n\ndef _phase_unwrap(headings):\n    \"\"\"\n    Returns an array of heading angles equal mod 2 pi to the input heading angles,\n    and such that the difference between successive output angles is less than or\n    equal to pi radians in absolute value\n    :param headings: An array of headings (radians)\n    :return The phase-unwrapped equivalent headings.\n    \"\"\"\n    # There are some jumps in the heading (e.g. from -np.pi to +np.pi) which causes approximation of yaw to be very large.\n    # We want unwrapped[j] = headings[j] - 2*pi*adjustments[j] for some integer-valued adjustments making the absolute value of\n    # unwrapped[j+1] - unwrapped[j] at most pi:\n    # -pi <= headings[j+1] - headings[j] - 2*pi*(adjustments[j+1] - adjustments[j]) <= pi\n    # -1/2 <= (headings[j+1] - headings[j])/(2*pi) - (adjustments[j+1] - adjustments[j]) <= 1/2\n    # So adjustments[j+1] - adjustments[j] = round((headings[j+1] - headings[j]) / (2*pi)).\n    two_pi = 2.0 * np.pi\n    adjustments = np.zeros_like(headings)\n    adjustments[..., 1:] = np.cumsum(\n        np.round(np.diff(headings, axis=-1) / two_pi), axis=-1\n    )\n    unwrapped = headings - two_pi * adjustments\n    return unwrapped\n\n\ndef read_from_json(filepath, metric_dir=None):\n    with open(filepath, 'r') as f:\n        data = json.load(f)\n    all_data = []\n    driving_efficiency = []\n    for record in data[\"_checkpoint\"][\"records\"]:\n        filepath = os.path.join(metric_dir, record[\"save_name\"], 'metric_info.json')\n        temp_dict = {}\n        temp_dict[\"acceleration\"] = []\n        temp_dict[\"angular_velocity\"] = []\n        temp_dict[\"forward_vector\"] = []\n        temp_dict[\"right_vector\"] = []\n        temp_dict[\"location\"] = []\n        temp_dict[\"rotation\"] = []\n        with open(filepath, 'r') as file:\n            json_data = json.load(file)\n            for k, v in json_data.items():\n                temp_dict[\"acceleration\"].append(v[\"acceleration\"])\n                temp_dict[\"angular_velocity\"].append(v[\"angular_velocity\"])\n                temp_dict[\"forward_vector\"].append(v[\"forward_vector\"])\n                temp_dict[\"right_vector\"].append(v[\"right_vector\"])\n                temp_dict[\"location\"].append(v[\"location\"])\n                temp_dict[\"rotation\"].append(v[\"rotation\"])\n        for k, v in temp_dict.items():\n            temp_dict[k] = np.array(v)\n        all_data.append(temp_dict)\n        if len(record[\"infractions\"][\"min_speed_infractions\"]) < 1:\n            continue\n        else:\n            driving_e = []\n            for min_speed_infrac in record[\"infractions\"][\"min_speed_infractions\"]:\n                number = re.search(r\"\\b\\d+\\.?\\d*%\", min_speed_infrac)\n                if float(number.group().rstrip('%')) > 1000:\n                    continue\n                driving_e.append(float(number.group().rstrip('%')))\n            driving_e = sum(driving_e) / len(driving_e)\n            driving_efficiency.append(driving_e)\n    return all_data, driving_efficiency\n\nif __name__=='__main__':\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('-f', '--file', default=\"uniad_b2d_traj/merged.json\", help='route file')\n    argparser.add_argument('-m', '--metric_dir', default=\"eval_bench2drive220_uniad_traj/\")\n    args = argparser.parse_args()\n    all_data, driving_efficiency_list = read_from_json(args.file, args.metric_dir)\n    comfort_res = []\n    for record in all_data:\n        comfort_res.append(seg_compute_comfort_metric(**record))\n    print(f'Driving Efficiency={sum(driving_efficiency_list) / len(driving_efficiency_list)}')\n    print(f'Driving Smoothness={sum(comfort_res)/len(comfort_res)}')"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/gen_hdmap.py",
    "content": "import carla\nimport numpy as np\n\nimport cv2\n\nfrom pathlib import Path\nimport os\nimport argparse\nimport time\nimport subprocess\nimport json\n\ndef check_waypoints_status(waypoints_list):\n    first_wp = waypoints_list[0]\n    init_status = first_wp.is_junction\n    current_status = first_wp.is_junction\n    change_status_time = 0\n    for wp in waypoints_list[1:]:\n        if wp.is_junction != current_status:\n            current_status = wp.is_junction\n            change_status_time += 1\n        pass\n    if change_status_time == 0:\n        return 'Junction' if init_status else 'Normal'\n    elif change_status_time == 1:\n        return 'EnterNormal' if init_status else 'EnterJunction'\n    elif change_status_time == 2:\n        return 'PassNormal' if init_status else 'PassJunction'\n    else:\n        return 'StartJunctionMultiChange' if init_status else 'StartNormalMultiChange'\n\nclass TriggerVolumeGettor(object):\n    \n    @staticmethod\n    def get_global_bbx(actor, bbx):\n        if actor.is_alive:\n            bbx.location = actor.get_transform().transform(bbx.location)\n            bbx.rotation = actor.get_transform().rotation\n            return bbx\n        return None\n\n    @staticmethod\n    def get_corners_from_actor_list(actor_list):\n        for actor_transform, bb_loc, bb_ext in actor_list:\n\n            corners = [carla.Location(x=-bb_ext.x, y=-bb_ext.y),\n                       carla.Location(x=bb_ext.x, y=-bb_ext.y),\n                       carla.Location(x=bb_ext.x, y=0),\n                       carla.Location(x=bb_ext.x, y=bb_ext.y),\n                       carla.Location(x=-bb_ext.x, y=bb_ext.y)]\n            corners = [bb_loc + corner for corner in corners]\n\n            corners = [actor_transform.transform(corner) for corner in corners]\n            corners = [[corner.x, corner.y, corner.z] for corner in corners]\n        return corners\n    \n    @staticmethod\n    def insert_point_into_dict(lane_marking_dict, corners, road_id, parent_actor_location, Volume_Type=None):\n        if road_id not in lane_marking_dict.keys():\n            print(\"Cannot find road:\", road_id)\n            raise\n        if Volume_Type is None:\n            print(\"Missing 'Volume Type' \")\n            raise\n        if 'Trigger_Volumes' not in lane_marking_dict[road_id]:\n            lane_marking_dict[road_id]['Trigger_Volumes'] = [{'Points': corners[:], 'Type': Volume_Type, 'ParentActor_Location': parent_actor_location[:]}]\n        else:\n            lane_marking_dict[road_id]['Trigger_Volumes'].append({'Points': corners[:], 'Type': Volume_Type, 'ParentActor_Location': parent_actor_location[:]})\n    \n    @staticmethod\n    def get_stop_sign_trigger_volume(all_stop_sign_actors, lane_marking_dict, carla_map):\n        for actor in all_stop_sign_actors:\n            bb_loc = carla.Location(actor.trigger_volume.location)\n            bb_ext = carla.Vector3D(actor.trigger_volume.extent)\n            bb_ext.x = max(bb_ext.x, bb_ext.y)\n            bb_ext.y = max(bb_ext.x, bb_ext.y)\n            base_transform = actor.get_transform()\n            stop_info_list = [(carla.Transform(base_transform.location, base_transform.rotation), bb_loc, bb_ext)]\n            corners = TriggerVolumeGettor.get_corners_from_actor_list(stop_info_list)\n            \n            trigger_volume_wp = carla_map.get_waypoint(base_transform.transform(bb_loc))\n            actor_loc = actor.get_location()\n            actor_loc_points = [actor_loc.x, actor_loc.y, actor_loc.z]\n            TriggerVolumeGettor.insert_point_into_dict(lane_marking_dict, corners, trigger_volume_wp.road_id, actor_loc_points, Volume_Type='StopSign')\n            \n        pass\n    \n    @staticmethod\n    def get_traffic_light_trigger_volume(all_trafficlight_actors, lane_marking_dict, carla_map):\n        for actor in all_trafficlight_actors:\n            base_transform = actor.get_transform()\n            tv_loc = actor.trigger_volume.location\n            tv_ext = actor.trigger_volume.extent\n            x_values = np.arange(-0.9 * tv_ext.x, 0.9 * tv_ext.x, 1.0)\n            area = []\n            for x in x_values:\n                point_location = base_transform.transform(tv_loc + carla.Location(x=x)) \n                area.append(point_location)\n            ini_wps = []\n            for pt in area:\n                wpx = carla_map.get_waypoint(pt)\n                # As x_values are arranged in order, only the last one has to be checked\n                if not ini_wps or ini_wps[-1].road_id != wpx.road_id or ini_wps[-1].lane_id != wpx.lane_id:\n                    ini_wps.append(wpx)\n            \n            close2junction_points = []\n            littlefar2junction_points = []\n            for wpx in ini_wps:\n                while not wpx.is_intersection:\n                    next_wp = wpx.next(0.5)\n                    if not next_wp:\n                        break\n                    next_wp = next_wp[0]\n                    if next_wp and not next_wp.is_intersection:\n                        wpx = next_wp\n                    else:\n                        break\n                vec_forward = wpx.transform.get_forward_vector()\n                vec_right = carla.Vector3D(x=-vec_forward.y, y=vec_forward.x, z=0) # 2D\n\n                loc_left = wpx.transform.location - 0.4 * wpx.lane_width * vec_right\n                loc_right = wpx.transform.location + 0.4 * wpx.lane_width * vec_right\n                close2junction_points.append([loc_left.x, loc_left.y, loc_left.z])\n                close2junction_points.append([loc_right.x, loc_right.y, loc_right.z])\n                \n                try:\n                    loc_far_left = wpx.previous(0.5)[0].transform.location - 0.4 * wpx.lane_width * vec_right\n                    loc_far_right = wpx.previous(0.5)[0].transform.location + 0.4 * wpx.lane_width * vec_right\n                except Exception:\n                    continue\n                \n                littlefar2junction_points.append([loc_far_left.x, loc_far_left.y, loc_far_left.z])\n                littlefar2junction_points.append([loc_far_right.x, loc_far_right.y, loc_far_right.z])\n                \n            traffic_light_points = close2junction_points + littlefar2junction_points[::-1]\n            trigger_volume_wp = carla_map.get_waypoint(base_transform.transform(tv_loc))\n            actor_loc = actor.get_location()\n            actor_loc_points = [actor_loc.x, actor_loc.y, actor_loc.z]\n            TriggerVolumeGettor.insert_point_into_dict(lane_marking_dict, traffic_light_points, trigger_volume_wp.road_id, actor_loc_points, Volume_Type='TrafficLight')\n        pass\n    \n    pass\nt = 0\nclass LankMarkingGettor(object):\n\n    '''\n        structure of lane_marking_dict:\n        {\n            road_id_0: {\n                lane_id_0: [{'Points': [((location.x,y,z) array, (rotation.roll, pitch, yaw))], 'Type': 'lane_marking_type', 'Color':'color', 'Topology':[neighbor array]}, ...]\n                ... ...\n                'Trigger_Volumes': [{'Points': [(location.x,y,z) array], 'Type': 'trigger volume type', 'ParentActor_Location': (location.x,y,z)}]\n            }\n            ... ...\n        }\n        \"location array\" is an array formed as (location_x, location_y, location_z) ...\n        'lane_marking_type' is string of landmarking type, can be 'Broken', 'Solid', 'SolidSolid', 'Other', 'NONE', etc. \n        'color' is string of landmarking color, can be 'Blue', 'White', 'Yellow',  etc. \n         neighbor array contains the ('road_id', 'lane_id') of the current landmarking adjacent to, it is directional. \n         and if current 'Type' == 'Center', there will exist a 'TopologyType' key which record the current lane's topology status. \n         if there exist a trigger volume in current road, key 'Trigger_Volumes' will be added into dict \n         where 'Points' refer to the vertexs location array, 'Type' can be 'StopSign' or 'TrafficLight'\n         'ParentActor_Location' is the location of parent actor relevant to this trigger volume. \n    '''\n    \n    @staticmethod\n    def get_lanemarkings(carla_map, lane_marking_dict={}, pixels_per_meter=2, precision=0.05):\n        \n        topology = [x[0] for x in carla_map.get_topology()]\n        topology = sorted(topology, key=lambda w: w.road_id)\n        \n        for waypoint in topology:\n            waypoints = [waypoint]\n            # Generate waypoints of a road id. Stop when road id differs\n            nxt = waypoint.next(precision)\n            if len(nxt) > 0:\n                nxt = nxt[0]\n                temp_wp = nxt\n                while nxt.road_id == waypoint.road_id:\n                    waypoints.append(nxt)\n                    nxt = nxt.next(precision)\n                    if len(nxt) > 0:\n                        nxt = nxt[0]\n                    else:\n                        break\n            print(\"current road id: \", waypoint.road_id)\n            print(\"lane id:\", waypoint.lane_id)\n            LankMarkingGettor.get_lane_markings_two_side(waypoints, lane_marking_dict)\n\n    @staticmethod\n    def get_lane_markings_two_side(waypoints, lane_marking_dict):\n        left_lane_marking_list = []\n        right_lane_marking_list = []\n        \n        center_lane_list = []\n        center_lane_wps = []\n        \n        left_previous_lane_marking_type = 1\n        left_previous_lane_marking_color = 1\n        right_previous_lane_marking_type = 1\n        right_previous_lane_marking_color = 1\n        \n        center_previous_lane_id = waypoints[0].lane_id\n        \n        for waypoint in waypoints:\n            flag = False\n            if waypoint.lane_id != center_previous_lane_id:\n                if len(center_lane_list) > 1:\n                    if waypoint.road_id not in lane_marking_dict:\n                        lane_marking_dict[waypoint.road_id] = {}\n                        status = check_waypoints_status(center_lane_wps)\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n                    elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                        status = check_waypoints_status(center_lane_wps)\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n                    else:\n                        status = check_waypoints_status(center_lane_wps)\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n                flag = True\n                center_lane_list = []\n                center_lane_wps = []\n            left_lane_marking = waypoint.left_lane_marking\n            if left_lane_marking.type != left_previous_lane_marking_type or\\\n                left_lane_marking.color != left_previous_lane_marking_color or flag:\n                    if len(left_lane_marking_list) > 1:\n                        connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n                        candidate_dict = {'Points': left_lane_marking_list[:], 'Type': str(left_previous_lane_marking_type), 'Color': str(left_previous_lane_marking_color), 'Topology': connect_to[:]}\n                        if waypoint.road_id not in lane_marking_dict:\n                            lane_marking_dict[waypoint.road_id] = {}\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        else:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n                        left_lane_marking_list = []\n            right_lane_marking = waypoint.right_lane_marking\n            if right_lane_marking.type != right_previous_lane_marking_type or\\\n                right_lane_marking.color != right_previous_lane_marking_color or flag:\n                    if len(right_lane_marking_list) > 1:\n                        connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n                        candidate_dict = {'Points': right_lane_marking_list[:], 'Type': str(right_previous_lane_marking_type), 'Color': str(right_previous_lane_marking_color), 'Topology': connect_to[:]}\n                        if waypoint.road_id not in lane_marking_dict:\n                            lane_marking_dict[waypoint.road_id] = {}\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        else:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n                        right_lane_marking_list = []\n                        \n            center_lane_list.append((*LankMarkingGettor.get_lateral_shifted_transform(waypoint.transform, 0), waypoint.is_junction))\n            center_lane_wps.append(waypoint)\n            \n            left_lane_marking_list.append(LankMarkingGettor.get_lateral_shifted_transform(waypoint.transform, -0.5*waypoint.lane_width))\n            \n            right_lane_marking_list.append(LankMarkingGettor.get_lateral_shifted_transform(waypoint.transform, 0.5*waypoint.lane_width))\n            \n            left_previous_lane_marking_type = left_lane_marking.type\n            left_previous_lane_marking_color = left_lane_marking.color\n            right_previous_lane_marking_type = right_lane_marking.type\n            right_previous_lane_marking_color = right_lane_marking.color\n            center_previous_lane_id = waypoint.lane_id\n        \n        if len(left_lane_marking_list) > 1:\n            connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n            candidate_dict = {'Points': left_lane_marking_list[:], 'Type': str(left_lane_marking.type), 'Color': str(left_previous_lane_marking_color), 'Topology': connect_to[:]}\n            if waypoint.road_id not in lane_marking_dict:\n                lane_marking_dict[waypoint.road_id] = {}\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            else:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n            left_lane_marking_list = []\n        if len(right_lane_marking_list) > 1:\n            connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n            candidate_dict = {'Points': right_lane_marking_list[:], 'Type': str(right_lane_marking.type), 'Color': str(right_previous_lane_marking_color), 'Topology': connect_to[:]}\n            if waypoint.road_id not in lane_marking_dict:\n                lane_marking_dict[waypoint.road_id] = {}\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            else:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n            right_lane_marking_list = []\n        if len(center_lane_list) > 0:\n            if waypoint.road_id not in lane_marking_dict:\n                lane_marking_dict[waypoint.road_id] = {}\n                status = check_waypoints_status(center_lane_wps)\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n            elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                status = check_waypoints_status(center_lane_wps)\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n            else:\n                status = check_waypoints_status(center_lane_wps)\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n            \n    @staticmethod\n    def get_connected_road_id(waypoint):\n        next_waypoint = waypoint.next(0.05)\n        if next_waypoint is None:\n            return [None]\n        else:\n            return [(w.road_id, w.lane_id) for w in next_waypoint if w.lane_type == carla.LaneType.Driving]\n    \n    @staticmethod\n    def insert_element_into_dict(id, element, lane_marking_dict):\n        if id not in lane_marking_dict:\n            lane_marking_dict[id] = []\n            lane_marking_dict[id].append(element)\n        else:\n            lane_marking_dict[id].append(element)\n    \n    @staticmethod   \n    def get_lateral_shifted_transform(transform, shift):\n        right_vector = transform.get_right_vector()\n        x_offset = right_vector.x * shift\n        y_offset = right_vector.y * shift\n        z_offset = right_vector.z * shift\n        x = transform.location.x + x_offset\n        y = transform.location.y + y_offset\n        z = transform.location.z + z_offset\n        roll = transform.rotation.roll\n        pitch = transform.rotation.pitch\n        yaw = transform.rotation.yaw\n        return ((x, y, z), (roll, pitch, yaw))\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--save_dir', default='/maps')\n    parser.add_argument('--carla_town', default='Town12')\n\n    args = parser.parse_args()\n    carla_town = args.carla_town\n\n    client = carla.Client('localhost', 2000)\n    client.set_timeout(300)\n    world = client.load_world(carla_town)\n    print(\"******** sucessfully load the town:\", carla_town, \" ********\")\n    carla_map = world.get_map()\n\n    lane_marking_dict = {}\n    LankMarkingGettor.get_lanemarkings(world.get_map(), lane_marking_dict)\n    print(\"****** get all lanemarkings ******\")\n    \n    all_actors = world.get_actors()\n    all_stop_sign_actors = []\n    all_traffic_light_actors = []\n    for actor in all_actors:\n        if 'traffic.stop' in actor.type_id:\n            all_stop_sign_actors.append(actor)\n        if 'traffic_light' in actor.type_id:\n            all_traffic_light_actors.append(actor)\n    \n    print(\"Getting all trigger volumes ...\")\n    TriggerVolumeGettor.get_stop_sign_trigger_volume(all_stop_sign_actors, lane_marking_dict, carla_map)\n    TriggerVolumeGettor.get_traffic_light_trigger_volume(all_traffic_light_actors, lane_marking_dict, carla_map)\n    print(\"******* Have get all trigger volumes ! *********\")\n    \n    arr = np.array(list(lane_marking_dict.items()), dtype=object)\n    np.savez_compressed(args.save_dir+\"/\"+args.carla_town+\"_HD_map.npz\", arr=arr)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/generate_video.py",
    "content": "import cv2\nimport os\nimport numpy as np\nimport json\nfrom tqdm import trange\n\n\ndef create_video(images_folder, output_video, fps, font_scale, text_color, text_position):\n    images = [img for img in os.listdir(os.path.join(images_folder, 'rgb_front')) if img.endswith(\".jpg\") or img.endswith(\".png\")]\n    images.sort()\n\n    frame = cv2.imread(os.path.join(os.path.join(images_folder, 'rgb_front'), images[0]))\n    height, width, layers = frame.shape\n\n    fourcc = cv2.VideoWriter_fourcc(*'mp4v')\n    video = cv2.VideoWriter(output_video, fourcc, fps, (width, height))\n\n    for i in trange(1, len(images)):\n        image = images[i]\n        f = open(os.path.join(images_folder, f'meta/{i:04}.json'), 'r')\n        meta = json.load(f)\n        steer = float(meta['steer'])\n        throttle = float(meta['throttle'])\n        brake = float(meta['brake'])\n        # command = float(meta['command'])\n        # command_list = [\"VOID\", \"LEFT\", \"RIGHT\", \"STRAIGHT\", \"LANE FOLLOW\", \"CHANGE LANE LEFT\",  \"CHANGE LANE RIGHT\",]\n        speed = float(meta['speed'])\n        text = f'speed: {round(speed,2)}, steer: {round(steer,2)}, throttle: {round(throttle,2)}, brake: {round(brake,2)}'#, command: {command_list[int(command)]}'\n        img = cv2.imread(os.path.join(os.path.join(images_folder, 'rgb_front'), image))\n        cv2.putText(img, text, text_position, cv2.FONT_HERSHEY_SIMPLEX, font_scale, text_color, 2, cv2.LINE_AA)\n        video.write(img)\n    video.release()\n\nimages_folder = ''\noutput_video = ''\nfps = 15\nfont_scale = 1\ntext_color = (255, 255, 255)\ntext_position = (50, 50)\n\ncreate_video(images_folder, output_video, fps, font_scale, text_color, text_position)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/merge_route_json.py",
    "content": "import json\nimport glob\nimport argparse\nimport os\n\ndef merge_route_json(folder_path):\n    file_paths = glob.glob(f'{folder_path}/*.json')\n    merged_records = []\n    driving_score = []\n    success_num = 0\n    for file_path in file_paths:\n        if 'merged.json' in file_path: continue\n        with open(file_path) as file:\n            data = json.load(file)\n            records = data['_checkpoint']['records']\n            for rd in records:\n                rd.pop('index')\n                merged_records.append(rd)\n                driving_score.append(rd['scores']['score_composed'])\n                if rd['status']=='Completed' or rd['status']=='Perfect':\n                    success_flag = True\n                    for k,v in rd['infractions'].items():\n                        if len(v)>0 and k != 'min_speed_infractions':\n                            success_flag = False\n                            break\n                    if success_flag:\n                        success_num += 1\n                        print(rd['route_id'])\n    if len(merged_records) != 220:\n        print(f\"-----------------------Warning: there are {len(merged_records)} routes in your json, which does not equal to 220. All metrics (Driving Score, Success Rate, Ability) are inaccurate!!!\")\n    merged_records = sorted(merged_records, key=lambda d: d['route_id'], reverse=True)\n    _checkpoint = {\n        \"records\": merged_records\n    }\n\n    merged_data = {\n        \"_checkpoint\": _checkpoint,\n        \"driving score\": sum(driving_score) / 220,\n        \"success rate\": success_num / 220,\n        \"eval num\": len(driving_score),\n    }\n\n    with open(os.path.join(folder_path, 'merged.json'), 'w') as file:\n        json.dump(merged_data, file, indent=4)\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('-f', '--folder', help='old foo help')\n    args = parser.parse_args()\n    merge_route_json(args.folder)\n"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/split_xml.py",
    "content": "import xml.etree.ElementTree as ET\n\n\ndef split_list_into_n_parts(lst, n):\n    k, m = divmod(len(lst), n)\n    return (lst[i * k + min(i, m):(i + 1) * k + min(i + 1, m)] for i in range(n))\n\ndef main(base_route, task_num, algo, planner_type):\n    tree = ET.parse(f'{base_route}.xml')\n    root = tree.getroot()\n    case = root.findall('route')\n    results = split_list_into_n_parts(case, task_num)\n    for index, re in enumerate(results):\n        new_root = ET.Element(\"routes\")\n        for x in re:\n            new_root.append(x)\n        new_tree = ET.ElementTree(new_root)\n        new_tree.write(f'{base_route}_{index}_{algo}_{planner_type}.xml', encoding='utf-8', xml_declaration=True)\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"base_route\", type=str)\n    parser.add_argument(\"task_num\", type=int)\n    parser.add_argument(\"algo\", type=str)\n    parser.add_argument(\"planner_type\", type=str)\n    args = parser.parse_args()\n    main(args.base_route, args.task_num, args.algo, args.planner_type)"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/utils.py",
    "content": "import numpy as np\nimport cv2\nimport math\n\nWINDOW_HEIGHT = 900\nWINDOW_WIDTH = 1600\n\nDIS_CAR_SAVE = 100\nDIS_WALKER_SAVE = 100\nDIS_SIGN_SAVE = 100\nDIS_LIGHT_SAVE = 100\n\nedges = [[0,1], [1,3], [3,2], [2,0], [0,4], [4,5], [5,1], [5,7], [7,6], [6,4], [6,2], [7,3]]\n\ndef get_image_point(loc, K, w2c):\n    # Calculate 2D projection of 3D coordinate\n\n    # Format the input coordinate (loc is a carla.Position object)\n    point = np.array([loc[0], loc[1], loc[2], 1])\n    # transform to camera coordinates\n    point_camera = np.dot(w2c, point)\n\n    # New we must change from UE4's coordinate system to an \"standard\"\n    # (x, y ,z) -> (y, -z, x)\n    # and we remove the fourth componebonent also\n    point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n\n    depth = point_camera[2]\n\n    # now project 3D->2D using the camera matrix\n    point_img = np.dot(K, point_camera)\n    # normalize\n    point_img[0] /= point_img[2]\n    point_img[1] /= point_img[2]\n    \n    return point_img[0:2], depth\n\ndef point_in_canvas_wh(pos):\n    \"\"\"Return true if point is in canvas\"\"\"\n    if (pos[0] >= 0) and (pos[0] < WINDOW_WIDTH) and (pos[1] >= 0) and (pos[1] < WINDOW_HEIGHT):\n        return True\n    return False\n\ndef get_forward_vector(yaw):\n    # Convert the yaw angle from degrees to radians\n    yaw_rad = math.radians(yaw)\n    # Calculate the X and Y components of the forward vector (in a left-handed coordinate system with Z-axis upwards)\n    # Note: In a left-handed coordinate system, the positive Y direction could correspond to either forward or backward, depending on the specific application scenario\n    x = math.cos(yaw_rad)\n    y = math.sin(yaw_rad)\n    # On a horizontal plane, the Z component of the forward vector is 0\n    z = 0\n    return np.array([x, y, z])\n\ndef calculate_cube_vertices(center, extent):\n    if isinstance(center, list):\n        cx, cy, cz = center\n        x, y, z = extent\n    else:\n        cx, cy, cz = center.x,  center.y,  center.z\n        x, y, z = extent.x, extent.y, extent.z\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\ndef draw_dashed_line(img, start_point, end_point, color, thickness=1, dash_length=5):\n    \"\"\"\n    Draw a dashed line on an image.\n    Arguments:\n    - img: The image on which to draw the dashed line.\n    - start_point: The starting point of the dashed line, in the format (x, y).\n    - end_point: The ending point of the dashed line, in the format (x, y).\n    - color: The color of the dashed line, in the format (B, G, R).\n    - thickness: The thickness of the line.\n    - dash_length: The length of each dash segment in the dashed line.\n    \"\"\"\n    # Calculate total length\n    d = np.sqrt((end_point[0] - start_point[0])**2 + (end_point[1] - start_point[1])**2)\n    dx = (end_point[0] - start_point[0]) / d\n    dy = (end_point[1] - start_point[1]) / d\n\n    x, y = start_point[0], start_point[1]\n\n    while d >= dash_length:\n        # Calculate the end point of the next segment\n        x_end = x + dx * dash_length\n        y_end = y + dy * dash_length\n        cv2.line(img, (int(x), int(y)), (int(x_end), int(y_end)), color, thickness)\n\n        # Update starting point and remaining length\n        x = x_end + dx * dash_length\n        y = y_end + dy * dash_length\n        d -= 2 * dash_length\n\ndef world_to_ego(point_world, w2e):\n    point_world = np.array([point_world[0], point_world[1], point_world[2], 1])\n    point_ego = np.dot(w2e, point_world)\n    point_ego = [point_ego[1], -point_ego[0], point_ego[2]]\n    return point_ego\n\ndef vector_angle(v1, v2):\n    dot_product = np.dot(v1, v2)\n    magnitude_v1 = np.linalg.norm(v1)\n    magnitude_v2 = np.linalg.norm(v2)\n    cos_theta = dot_product / (magnitude_v1 * magnitude_v2)\n    angle_radians = np.arccos(cos_theta)\n    angle_degrees = np.degrees(angle_radians)\n    return angle_degrees\n\ndef get_weather_id(weather_conditions):\n    from xml.etree import ElementTree as ET\n    tree = ET.parse('./leaderboard/data/weather.xml')\n    root = tree.getroot()\n    def conditions_match(weather, conditions):\n        for (key, value) in weather:\n            if key == 'route_percentage' : continue\n            if str(conditions[key]) != value:\n                return False\n        return True\n    for case in root.findall('case'):\n        weather = case[0].items()\n        if conditions_match(weather, weather_conditions):\n            return case.items()[0][1]\n    return None\n\ndef compute_2d_distance(loc1, loc2):\n    return math.sqrt((loc1.x-loc2.x)**2+(loc1.y-loc2.y)**2)\n\ndef build_projection_matrix(w, h, fov, is_behind_camera=False):\n    focal = w / (2.0 * np.tan(fov * np.pi / 360.0))\n    K = np.identity(3)\n\n    if is_behind_camera:\n        K[0, 0] = K[1, 1] = -focal\n    else:\n        K[0, 0] = K[1, 1] = focal\n\n    K[0, 2] = w / 2.0\n    K[1, 2] = h / 2.0\n    return K\n\ndef convert_depth(data):\n    \"\"\"\n    Computes the normalized depth from a CARLA depth map.\n    \"\"\"\n    data = data.astype(np.float16)\n\n    normalized = np.dot(data, [65536.0, 256.0, 1.0])\n    normalized /= (256 * 256 * 256 - 1)\n    return normalized * 1000\n\ndef get_relative_transform(ego_matrix, vehicle_matrix):\n    \"\"\"\n    Returns the position of the vehicle matrix in the ego coordinate system.\n    :param ego_matrix: ndarray 4x4 Matrix of the ego vehicle in global\n    coordinates\n    :param vehicle_matrix: ndarray 4x4 Matrix of another actor in global\n    coordinates\n    :return: ndarray position of the other vehicle in the ego coordinate system\n    \"\"\"\n    relative_pos = vehicle_matrix[:3, 3] - ego_matrix[:3, 3]\n    rot = ego_matrix[:3, :3].T\n    relative_pos = rot @ relative_pos\n\n    return relative_pos\n\ndef normalize_angle(x):\n    x = x % (2 * np.pi)  # force in range [0, 2 pi)\n    if x > np.pi:  # move to [-pi, pi)\n        x -= 2 * np.pi\n    return x\n\ndef build_skeleton(ped, sk_links):\n    ######## get the pedestrian skeleton #########\n    bones = ped.get_bones()\n\n    # list where we will store the lines we will project\n    # onto the camera output\n    lines_3d = []\n\n    # cycle through the bone pairs in skeleton.txt and retrieve the joint positions\n    for link in sk_links[1:]:\n\n        # get the roots of the two bones to be joined\n        bone_transform_1 = next(filter(lambda b: b.name == link[0], bones.bone_transforms), None)\n        bone_transform_2 = next(filter(lambda b: b.name == link[1], bones.bone_transforms), None)\n\n        # some bone names aren't matched\n        if bone_transform_1 is not None and bone_transform_2 is not None:\n            lines_3d.append([(bone_transform_1.world.location.x, bone_transform_1.world.location.y, bone_transform_1.world.location.z), \n                             (bone_transform_2.world.location.x, bone_transform_2.world.location.y, bone_transform_2.world.location.z)]\n                            )\n    return lines_3d\n\ndef get_matrix(location, rotation):\n    \"\"\"\n    Creates matrix from carla transform.\n    \"\"\"\n    pitch, roll, yaw = rotation\n    x, y, z = location\n    c_y = np.cos(np.radians(yaw))\n    s_y = np.sin(np.radians(yaw))\n    c_r = np.cos(np.radians(roll))\n    s_r = np.sin(np.radians(roll))\n    c_p = np.cos(np.radians(pitch))\n    s_p = np.sin(np.radians(pitch))\n    matrix = np.matrix(np.identity(4))\n    matrix[0, 3] = x\n    matrix[1, 3] = y\n    matrix[2, 3] = z\n    matrix[0, 0] = c_p * c_y\n    matrix[0, 1] = c_y * s_p * s_r - s_y * c_r\n    matrix[0, 2] = -c_y * s_p * c_r - s_y * s_r\n    matrix[1, 0] = s_y * c_p\n    matrix[1, 1] = s_y * s_p * s_r + c_y * c_r\n    matrix[1, 2] = -s_y * s_p * c_r + c_y * s_r\n    matrix[2, 0] = s_p\n    matrix[2, 1] = -c_p * s_r\n    matrix[2, 2] = c_p * c_r\n    return matrix"
  },
  {
    "path": "close_loop/SparseDrive_MomAD/tools/visualize.py",
    "content": "import json\nimport gzip\nimport os\nimport numpy as np\nimport cv2\nimport pathlib\nimport random\nimport laspy\nimport matplotlib.cm as cm\nfrom tqdm import trange\nfrom utils import get_image_point, point_in_canvas_wh, edges, world_to_ego, get_forward_vector, calculate_cube_vertices, draw_dashed_line, vector_angle, get_weather_id\n\ndef visualize_data(file_path, map_path, vis_bbox=True,  vis_top_down=True, vis_road=True, vis_lidar_bev=True, vis_lidar_to_back_image=True, vis_lidar_to_front_image=True, vis_lidar_to_front_left_image=True):\n    print(f'file_path={file_path}')\n    print(f'map_path={map_path}')\n\n    save_path = pathlib.Path(file_path.replace('v0','v0-vis'))\n    (save_path / 'camera' / 'rgb_front_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_front_landmark').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_front_left_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_front_right_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_back_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_back_left_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_back_right_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_top_down_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'bev').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'front').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'front_left').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'back').mkdir(parents=True, exist_ok=True)\n\n    cam_map = {\n        'CAM_FRONT': 'rgb_front',\n        'CAM_FRONT_LEFT': 'rgb_front_left',\n        'CAM_FRONT_RIGHT': 'rgb_front_right',\n        'CAM_BACK': 'rgb_back', \n        'CAM_BACK_LEFT': 'rgb_back_left', \n        'CAM_BACK_RIGHT': 'rgb_back_right',\n        'TOP_DOWN': 'rgb_top_down'\n    }\n\n    folder_path = os.path.join(file_path, 'anno')\n    file_count = len([name for name in os.listdir(folder_path) if os.path.isfile(os.path.join(folder_path, name))])\n    map_info = dict(np.load(map_path, allow_pickle=True)['arr'])\n\n    for step in trange(file_count):\n        with gzip.open(os.path.join(file_path, f'anno/{step:05}.json.gz'), 'rt', encoding='utf-8') as gz_file:\n            anno = json.load(gz_file)\n        weather_id = get_weather_id(anno['weather'])\n        bounding_boxes = anno['bounding_boxes']\n        sensors_anno = anno['sensors']\n        # ========================== bbox ==========================\n        if vis_bbox:            \n            for key in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']:\n                K = sensors_anno[key]['intrinsic']\n                world2cam = sensors_anno[key]['world2cam']\n                visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n                for npc in bounding_boxes:\n                    if npc['class'] == 'ego_vehicle': continue\n                    if npc['distance'] > 75: continue\n                    if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                    if 'vehicle' in npc['class']: # vehicle\n                        forward_vec = get_forward_vector(sensors_anno[key]['rotation'][2])\n                        ray = np.array(npc['location']) - np.array(sensors_anno[key]['location'])\n                        color = (random.randint(0, 255), random.randint(0, 255), random.randint(0, 255))\n                        if forward_vec.dot(ray) > 1 and vector_angle(forward_vec, ray)<45:\n                            verts = np.array(npc['world_cord'])\n                            for edge in edges:\n                                p1, p1_depth = get_image_point(verts[edge[0]], K, world2cam)\n                                p2, p2_depth = get_image_point(verts[edge[1]],  K, world2cam)\n                                draw_dashed_line(visulize_img, (int(p1[0]),int(p1[1])), (int(p2[0]),int(p2[1])), color, 2)\n                            cv2.putText(visulize_img, npc['class']+npc['id'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                    else: # sign, light, pedestrians\n                        if npc['class'] == 'traffic_sign': \n                            npc['extent'][1] = 0.5 # traffic_sign origin y is too small\n                        \n                        forward_vec = get_forward_vector(sensors_anno[key]['rotation'][2])\n                        ray = np.array(npc['location']) - np.array(sensors_anno[key]['location'])\n                        if 'affects_ego' in npc.keys() and str(npc['affects_ego']) == 'True':\n                            color = (0, 0, 255)\n                        else:\n                            color = (255, 255, 255)\n                        if forward_vec.dot(ray) > 1 and vector_angle(forward_vec, ray)<45:\n                            if 'world_cord' in npc.keys():\n                                if 'dirtdebris' in npc['type_id']:\n                                    local_verts = calculate_cube_vertices(npc['bbx_loc'], [npc['extent'][1], npc['extent'][0], npc['extent'][2]])\n                                    verts = []\n                                    for l_v in local_verts:\n                                        g_v = np.dot(np.matrix(npc['world2sign']).I, [l_v[0], l_v[1], l_v[2],1])\n                                        verts.append(g_v.tolist()[0][:-1])\n                                else:\n                                    verts = np.array(npc['world_cord'])\n                            else:\n                                verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                            for edge in edges:\n                                p1, p1_depth = get_image_point(verts[edge[0]], K, world2cam)\n                                p2, p2_depth = get_image_point(verts[edge[1]],  K, world2cam)\n                                draw_dashed_line(visulize_img, (int(p1[0]),int(p1[1])), (int(p2[0]),int(p2[1])), color, 2)\n                            if 'affects_ego' in npc.keys():\n                                cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                            else:\n                                cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                cv2.imwrite(os.path.join(save_path, f'camera/{cam_map[key]}_3d_bbox/{step:05}.jpg'), visulize_img)\n        \n        if vis_top_down:        \n            for key in ['TOP_DOWN']:\n                K = sensors_anno[key]['intrinsic']\n                world2cam = sensors_anno[key]['world2cam']\n                visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n                road_points = map_info[anno['bounding_boxes'][0]['road_id']]\n                # draw lane\n                for r_p in road_points[anno['bounding_boxes'][0]['lane_id']]:\n                    road_point = r_p['Points']\n                    road_type = r_p['Type']\n                    road_color = r_p['Color']\n                    road_topology = r_p['Topology']\n                    for point in road_point:\n                        point = np.array([point[0][0], point[0][1], point[0][2], 1])\n                        point_camera = np.dot(world2cam, point)\n                        point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                        depth = point_camera[2]\n                        point_img = np.dot(K, point_camera)\n                        if depth >0:\n                            point_img[0] /= point_img[2]\n                            point_img[1] /= point_img[2]\n                            point_img = point_img[0:2]\n                            if point_in_canvas_wh(point_img):\n                                if road_color == 'White':\n                                    cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=1, color=(255, 255, 255), thickness=-1)\n                                    if road_type == 'Center':\n                                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 0), thickness=-1)\n                                else:\n                                    cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 255), thickness=-1)                      \n                # draw vehicle\n                for npc in bounding_boxes:\n                    if 'vehicle' in npc['class']:\n                        if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                        if npc['class'] == 'ego_vehicle':\n                            color = (255, 255, 255, 255)\n                        else:\n                            color = (255, 0, 0, 255)\n                        verts = np.array(npc['world_cord'])\n                        p1, p1_depth = get_image_point(verts[0], K, world2cam)\n                        p2, p2_depth = get_image_point(verts[2],  K, world2cam)\n                        p3, p3_depth = get_image_point(verts[4],  K, world2cam)\n                        p4, p4_depth = get_image_point(verts[6],  K, world2cam)\n                        points = np.array([p1, p2, p4, p3])\n                        height, width = visulize_img.shape[:2]\n                        blk = np.zeros((height, width, 4), np.uint8)\n                        cv2.fillConvexPoly(blk, np.round(points).astype(np.int32), color)\n                        if npc['class'] == 'ego_vehicle':\n                            visulize_img = cv2.addWeighted(visulize_img, 1.0, blk[:,:,:3], 1, 1)\n                        else:\n                            visulize_img = cv2.addWeighted(visulize_img, 1.0, blk[:,:,:3], 0.25, 1)\n                        if npc['class'] == 'ego_vehicle':\n                            cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, (0,0,0), 1)\n                        else:\n                            cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                # draw sign\n                for npc in bounding_boxes:\n                    if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                    # traffic_sign\n                    if 'traffic_sign' in npc['class']:\n                        color = (0, 0, 255, 255)\n                        if 'world_cord' in npc.keys():\n                            verts = np.array(npc['world_cord'])\n                        else:\n                            verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                        p1, p1_depth = get_image_point(verts[0], K, world2cam)\n                        p2, p2_depth = get_image_point(verts[2],  K, world2cam)\n                        p3, p3_depth = get_image_point(verts[4],  K, world2cam)\n                        p4, p4_depth = get_image_point(verts[6],  K, world2cam)\n                        points = np.array([p1, p2, p4, p3])\n                        height, width = visulize_img.shape[:2]\n                        blk = np.zeros((height, width, 4), np.uint8)\n                        cv2.fillConvexPoly(blk, np.round(points).astype(np.int32), color)\n                        visulize_img = cv2.addWeighted(visulize_img, 1.0, blk[:,:,:3], 0.25, 1)\n                        cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                    # traffic_light\n                    if 'traffic_light' in npc['class']:\n                        color = (255, 0, 0)\n                        verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                        for edge in edges:\n                            p1, p1_depth = get_image_point(verts[edge[0]], K, world2cam)\n                            p2, p2_depth = get_image_point(verts[edge[1]],  K, world2cam)\n                            cv2.line(visulize_img, (int(p1[0]),int(p1[1])), (int(p2[0]),int(p2[1])), color, 2)\n                        cv2.putText(visulize_img, 'traffic_light', (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                cv2.imwrite(os.path.join(save_path, f'camera/{cam_map[key]}_3d_bbox/{step:05}.jpg'), visulize_img)\n        # ==========================================================\n\n        # ========================== road ==========================\n        if vis_road:\n            key = 'CAM_FRONT'\n            K = sensors_anno[key]['intrinsic']\n            world2cam = sensors_anno[key]['world2cam']\n            road_points = map_info[anno['bounding_boxes'][0]['road_id']]\n            road_seg = np.zeros((900, 1600, 3), dtype=np.uint8)\n            all_road_topology = set()\n            # draw current road\n            for r_p in road_points[anno['bounding_boxes'][0]['lane_id']]:\n                road_point = r_p['Points']\n                road_type = r_p['Type']\n                road_color = r_p['Color']\n                road_topology = r_p['Topology']\n                for r_t in road_topology:\n                    all_road_topology.add(r_t)\n                for point in road_point:\n                    point = np.array([point[0][0], point[0][1], point[0][2], 1])\n                    point_camera = np.dot(world2cam, point)\n                    point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                    depth = point_camera[2]\n                    point_img = np.dot(K, point_camera)\n                    if depth >0:\n                        point_img[0] /= point_img[2]\n                        point_img[1] /= point_img[2]\n                        point_img = point_img[0:2]\n                        if point_in_canvas_wh(point_img):\n                            if road_color == 'White':\n                                cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(255, 255, 255), thickness=-1)\n                                if road_type == 'Center':\n                                    cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 0), thickness=-1)\n                            else:\n                                cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 255), thickness=-1)\n            # draw road topology\n            for r_t in all_road_topology:\n                road_points = map_info[r_t[0]][r_t[1]]\n                for r_p in road_points:\n                    road_point = r_p['Points']\n                    road_type = r_p['Type']\n                    road_color = r_p['Color']\n                    road_topology = r_p['Topology']\n                    for point in road_point:\n                        point = np.array([point[0][0], point[0][1], point[0][2], 1])\n                        point_camera = np.dot(world2cam, point)\n                        point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                        depth = point_camera[2]\n                        point_img = np.dot(K, point_camera)\n                        if depth >0:\n                            point_img[0] /= point_img[2]\n                            point_img[1] /= point_img[2]\n                            point_img = point_img[0:2]\n                            if point_in_canvas_wh(point_img):\n                                if road_color == 'White':\n                                    cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(255, 255, 255), thickness=-1)\n                                    if road_type == 'Center':\n                                        cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 0), thickness=-1)\n                                else:\n                                    cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 255), thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'camera/{cam_map[key]}_landmark/{step:05}.png'), road_seg)\n        # # ===========================================================\n\n        # ========================== lidar to bev =====================\n        if vis_lidar_bev:\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            lidar_image = np.zeros((900, 1600, 3), dtype=np.uint8)\n            header = laspy.LasHeader(point_format=0)  # LARS point format used for storing\n            header.offsets = np.min(lidars, axis=0)\n            point_precision = 0.001\n            header.scales = np.array([point_precision, point_precision, point_precision])\n            point_record = laspy.ScaleAwarePointRecord.zeros(lidars.shape[0], header=header)\n\n            point_record.x = lidars[:, 0]\n            point_record.y = lidars[:, 1]\n            point_record.z = lidars[:, 2]\n            # (x, y,z) -> (y, -x, z), the x,y plane of the lidar system is different from that of the ego-car\n            point_record.x = lidars[:, 1]\n            point_record.y = - lidars[:, 0]\n            point_record.z = lidars[:, 2]\n\n            range_x = 85.0\n            range_y = 85.0\n            range_z = 85.0\n\n            # Normalized point cloud data\n            x_normalized = (point_record.x + range_x) / (2 * range_x)\n            y_normalized = (point_record.y + range_y) / (2 * range_y)\n            z_normalized = (point_record.z + range_z) / (2 * range_z)\n\n            # Convert normalized coordinates to image pixel index\n            x_pixels = x_normalized * (lidar_image.shape[1] - 1)\n            y_pixels = y_normalized * (lidar_image.shape[0] - 1)\n\n            for x, y, z in zip(x_pixels, y_pixels, z_normalized):\n                rgb_color = (255, 255, 255)\n                cv2.circle(lidar_image, (int(x), int(y)), radius=2, color=(int(rgb_color[0]), int(rgb_color[1]), int(rgb_color[2])), thickness=-1)\n\n            cv2.imwrite(os.path.join(save_path, f'lidar_bev/{step:05}.png'), lidar_image)\n            for npc in bounding_boxes:\n                if npc['class'] not in ['vehicle', 'ego_vehicle']: continue\n                if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                verts = np.array(npc['world_cord'])\n                # verts[:, 2] = verts[:, 2] - npc['extent'][2] # carla bbox need minus z \n                if npc['class'] == 'ego_vehicle':\n                    color = (0, 255, 0)\n                else:\n                    color = (0, 128, 255)\n                for edge in edges:\n                    p1 = verts[edge[0]]\n                    p1 = world_to_ego(p1, anno['bounding_boxes'][0]['world2ego'])\n                    p1_x = (p1[0] + range_x) / (2 * range_x) * (lidar_image.shape[1] - 1)\n                    p1_y = (p1[1] + range_y) / (2 * range_y) * (lidar_image.shape[0] - 1)\n\n                    p2 = verts[edge[1]]\n                    p2 = world_to_ego(p2, anno['bounding_boxes'][0]['world2ego'])\n                    p2_x = (p2[0] + range_x) / (2 * range_x) * (lidar_image.shape[1] - 1)\n                    p2_y = (p2[1] + range_y) / (2 * range_y) * (lidar_image.shape[0] - 1)\n                    cv2.line(lidar_image, (int(p1_x), int(p1_y)), (int(p2_x), int(p2_y)), color, 2)\n\n            cv2.imwrite(os.path.join(save_path, f'lidar/bev/{step:05}.png'), lidar_image)\n        # ===========================================================\n        \n        # ================ lidar to front image =====================\n        if vis_lidar_to_front_image:\n            key = 'CAM_FRONT'\n            K = sensors_anno[key]['intrinsic']\n            visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n            ego2cam = np.matrix(sensors_anno[key]['cam2ego']).I.tolist()\n\n            # lidar in ego coordinate\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            for lidar in lidars:\n                lidar = np.array([lidar[0], lidar[1], lidar[2], 1])\n                point_camera = np.dot(ego2cam, lidar)\n                point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                depth = point_camera[2]\n                point_img = np.dot(K, point_camera)\n                if depth > 0:\n                    point_img[0] /= point_img[2]\n                    point_img[1] /= point_img[2]\n                    point_img = point_img[0:2]\n                    if point_in_canvas_wh(point_img):\n                        color_scale = min(depth / 80, 1)\n                        color = cm.rainbow(color_scale)\n                        color = tuple([int(x*255) for x in color[:3]])\n                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=2, color=color, thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'lidar/front/{step:05}_front.png'), visulize_img)\n            # ==========================================================\n\n        # ================ lidar to back image =====================\n        if vis_lidar_to_back_image:\n            key = 'CAM_BACK'\n            K = sensors_anno[key]['intrinsic']\n            visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n            ego2cam = np.matrix(sensors_anno[key]['cam2ego']).I.tolist()\n\n            # lidar in ego coordinate\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            for lidar in lidars:\n                lidar = np.array([lidar[0], lidar[1], lidar[2], 1])\n                point_camera = np.dot(ego2cam, lidar)\n                point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                depth = point_camera[2]\n                point_img = np.dot(K, point_camera)\n                if depth > 0:\n                    point_img[0] /= point_img[2]\n                    point_img[1] /= point_img[2]\n                    point_img = point_img[0:2]\n                    if point_in_canvas_wh(point_img):\n                        color_scale = min(depth / 80, 1)\n                        color = cm.rainbow(color_scale)\n                        color = tuple([int(x*255) for x in color[:3]])\n                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=2, color=color, thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'lidar/back/{step:05}_back.png'), visulize_img)\n        # ===========================================================\n\n        # ================ lidar to fomr left image =====================\n        if vis_lidar_to_front_left_image:\n            key = 'CAM_FRONT_LEFT'\n            K = sensors_anno[key]['intrinsic']\n            visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n            ego2cam = np.matrix(sensors_anno[key]['cam2ego']).I.tolist()\n\n            # lidar in ego coordinate\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            for lidar in lidars:\n                lidar = np.array([lidar[0], lidar[1], lidar[2], 1])\n                point_camera = np.dot(ego2cam, lidar)\n                point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                depth = point_camera[2]\n                point_img = np.dot(K, point_camera)\n                if depth > 0:\n                    point_img[0] /= point_img[2]\n                    point_img[1] /= point_img[2]\n                    point_img = point_img[0:2]\n                    if point_in_canvas_wh(point_img):\n                        color_scale = min(depth / 80, 1)\n                        color = cm.rainbow(color_scale)\n                        color = tuple([int(x*255) for x in color[:3]])\n                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=2, color=color, thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'lidar/front_left/{step:05}_front_left.png'), visulize_img)\n        # ===========================================================\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser(description='argparse')\n    parser.add_argument('--file_path','-f', type=str)\n    parser.add_argument('--map_path','-m', type=str)\n\n    args = parser.parse_args()\n    map_path = f'./maps/Town{args.map_path}_HD_map.npz'\n    visualize_data(args.file_path, map_path, vis_bbox=True, vis_top_down=True, vis_road=True, vis_lidar_bev=True, vis_lidar_to_back_image=True, vis_lidar_to_front_image=True, vis_lidar_to_front_left_image=True)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/analysis_tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/analysis_tools/analyze_logs.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport json\nimport numpy as np\nimport seaborn as sns\nfrom collections import defaultdict\nfrom matplotlib import pyplot as plt\n\n\ndef cal_train_time(log_dicts, args):\n    for i, log_dict in enumerate(log_dicts):\n        print(f'{\"-\" * 5}Analyze train time of {args.json_logs[i]}{\"-\" * 5}')\n        all_times = []\n        for epoch in log_dict.keys():\n            if args.include_outliers:\n                all_times.append(log_dict[epoch]['time'])\n            else:\n                all_times.append(log_dict[epoch]['time'][1:])\n        all_times = np.array(all_times)\n        epoch_ave_time = all_times.mean(-1)\n        slowest_epoch = epoch_ave_time.argmax()\n        fastest_epoch = epoch_ave_time.argmin()\n        std_over_epoch = epoch_ave_time.std()\n        print(f'slowest epoch {slowest_epoch + 1}, '\n              f'average time is {epoch_ave_time[slowest_epoch]:.4f}')\n        print(f'fastest epoch {fastest_epoch + 1}, '\n              f'average time is {epoch_ave_time[fastest_epoch]:.4f}')\n        print(f'time std over epochs is {std_over_epoch:.4f}')\n        print(f'average iter time: {np.mean(all_times):.4f} s/iter')\n        print()\n\n\ndef plot_curve(log_dicts, args):\n    if args.backend is not None:\n        plt.switch_backend(args.backend)\n    sns.set_style(args.style)\n    # if legend is None, use {filename}_{key} as legend\n    legend = args.legend\n    if legend is None:\n        legend = []\n        for json_log in args.json_logs:\n            for metric in args.keys:\n                legend.append(f'{json_log}_{metric}')\n    assert len(legend) == (len(args.json_logs) * len(args.keys))\n    metrics = args.keys\n\n    num_metrics = len(metrics)\n    for i, log_dict in enumerate(log_dicts):\n        epochs = list(log_dict.keys())\n        for j, metric in enumerate(metrics):\n            print(f'plot curve of {args.json_logs[i]}, metric is {metric}')\n            if metric not in log_dict[epochs[args.interval - 1]]:\n                raise KeyError(\n                    f'{args.json_logs[i]} does not contain metric {metric}')\n\n            if args.mode == 'eval':\n                if min(epochs) == args.interval:\n                    x0 = args.interval\n                else:\n                    # if current training is resumed from previous checkpoint\n                    # we lost information in early epochs\n                    # `xs` should start according to `min(epochs)`\n                    if min(epochs) % args.interval == 0:\n                        x0 = min(epochs)\n                    else:\n                        # find the first epoch that do eval\n                        x0 = min(epochs) + args.interval - \\\n                            min(epochs) % args.interval\n                xs = np.arange(x0, max(epochs) + 1, args.interval)\n                ys = []\n                for epoch in epochs[args.interval - 1::args.interval]:\n                    ys += log_dict[epoch][metric]\n\n                # if training is aborted before eval of the last epoch\n                # `xs` and `ys` will have different length and cause an error\n                # check if `ys[-1]` is empty here\n                if not log_dict[epoch][metric]:\n                    xs = xs[:-1]\n\n                ax = plt.gca()\n                ax.set_xticks(xs)\n                plt.xlabel('epoch')\n                plt.plot(xs, ys, label=legend[i * num_metrics + j], marker='o')\n            else:\n                xs = []\n                ys = []\n                num_iters_per_epoch = \\\n                    log_dict[epochs[args.interval-1]]['iter'][-1]\n                for epoch in epochs[args.interval - 1::args.interval]:\n                    iters = log_dict[epoch]['iter']\n                    if log_dict[epoch]['mode'][-1] == 'val':\n                        iters = iters[:-1]\n                    xs.append(\n                        np.array(iters) + (epoch - 1) * num_iters_per_epoch)\n                    ys.append(np.array(log_dict[epoch][metric][:len(iters)]))\n                xs = np.concatenate(xs)\n                ys = np.concatenate(ys)\n                plt.xlabel('iter')\n                plt.plot(\n                    xs, ys, label=legend[i * num_metrics + j], linewidth=0.5)\n            plt.legend()\n        if args.title is not None:\n            plt.title(args.title)\n    if args.out is None:\n        plt.show()\n    else:\n        print(f'save curve to: {args.out}')\n        plt.savefig(args.out)\n        plt.cla()\n\n\ndef add_plot_parser(subparsers):\n    parser_plt = subparsers.add_parser(\n        'plot_curve', help='parser for plotting curves')\n    parser_plt.add_argument(\n        'json_logs',\n        type=str,\n        nargs='+',\n        help='path of train log in json format')\n    parser_plt.add_argument(\n        '--keys',\n        type=str,\n        nargs='+',\n        default=['mAP_0.25'],\n        help='the metric that you want to plot')\n    parser_plt.add_argument('--title', type=str, help='title of figure')\n    parser_plt.add_argument(\n        '--legend',\n        type=str,\n        nargs='+',\n        default=None,\n        help='legend of each plot')\n    parser_plt.add_argument(\n        '--backend', type=str, default=None, help='backend of plt')\n    parser_plt.add_argument(\n        '--style', type=str, default='dark', help='style of plt')\n    parser_plt.add_argument('--out', type=str, default=None)\n    parser_plt.add_argument('--mode', type=str, default='train')\n    parser_plt.add_argument('--interval', type=int, default=1)\n\n\ndef add_time_parser(subparsers):\n    parser_time = subparsers.add_parser(\n        'cal_train_time',\n        help='parser for computing the average time per training iteration')\n    parser_time.add_argument(\n        'json_logs',\n        type=str,\n        nargs='+',\n        help='path of train log in json format')\n    parser_time.add_argument(\n        '--include-outliers',\n        action='store_true',\n        help='include the first value of every epoch when computing '\n        'the average time')\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Analyze Json Log')\n    # currently only support plot curve and calculate average train time\n    subparsers = parser.add_subparsers(dest='task', help='task parser')\n    add_plot_parser(subparsers)\n    add_time_parser(subparsers)\n    args = parser.parse_args()\n    return args\n\n\ndef load_json_logs(json_logs):\n    # load and convert json_logs to log_dict, key is epoch, value is a sub dict\n    # keys of sub dict is different metrics, e.g. memory, bbox_mAP\n    # value of sub dict is a list of corresponding values of all iterations\n    log_dicts = [dict() for _ in json_logs]\n    for json_log, log_dict in zip(json_logs, log_dicts):\n        with open(json_log, 'r') as log_file:\n            for line in log_file:\n                log = json.loads(line.strip())\n                # skip lines without `epoch` field\n                if 'epoch' not in log:\n                    continue\n                epoch = log.pop('epoch')\n                if epoch not in log_dict:\n                    log_dict[epoch] = defaultdict(list)\n                for k, v in log.items():\n                    log_dict[epoch][k].append(v)\n    return log_dicts\n\n\ndef main():\n    args = parse_args()\n\n    json_logs = args.json_logs\n    for json_log in json_logs:\n        assert json_log.endswith('.json')\n\n    log_dicts = load_json_logs(json_logs)\n\n    eval(args.task)(log_dicts, args)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/analysis_tools/benchmark.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport time\nimport torch\nfrom mmcv import Config\nfrom mmcv.parallel import MMDataParallel\nfrom mmcv.runner import load_checkpoint, wrap_fp16_model\nimport sys\nsys.path.append('.')\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.datasets import custom_build_dataset\n# from mmdet3d.datasets import build_dataloader, build_dataset\nfrom mmdet3d.models import build_detector\n#from tools.misc.fuse_conv_bn import fuse_module\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='MMDet benchmark a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--checkpoint', default=None, help='checkpoint file')\n    parser.add_argument('--samples', default=2000, help='samples to benchmark')\n    parser.add_argument(\n        '--log-interval', default=50, help='interval of logging')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n\n    # build the dataloader\n    # TODO: support multiple images per gpu (only minor changes are needed)\n    print(cfg.data.test)\n    dataset = custom_build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=False,\n        shuffle=False)\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    #if args.fuse_conv_bn:\n    #    model = fuse_module(model)\n\n    model = MMDataParallel(model, device_ids=[0])\n\n    model.eval()\n\n    # the first several iterations may be very slow so skip them\n    num_warmup = 5\n    pure_inf_time = 0\n\n    # benchmark with several samples and take the average\n    for i, data in enumerate(data_loader):\n        torch.cuda.synchronize()\n        start_time = time.perf_counter()\n        with torch.no_grad():\n            model(return_loss=False, rescale=True, **data)\n\n        torch.cuda.synchronize()\n        elapsed = time.perf_counter() - start_time\n\n        if i >= num_warmup:\n            pure_inf_time += elapsed\n            if (i + 1) % args.log_interval == 0:\n                fps = (i + 1 - num_warmup) / pure_inf_time\n                print(f'Done image [{i + 1:<3}/ {args.samples}], '\n                      f'fps: {fps:.1f} img / s')\n\n        if (i + 1) == args.samples:\n            pure_inf_time += elapsed\n            fps = (i + 1 - num_warmup) / pure_inf_time\n            print(f'Overall fps: {fps:.1f} img / s')\n            break\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/analysis_tools/get_params.py",
    "content": "import torch\nfile_path = './ckpts/bevformer_v4.pth'\nmodel = torch.load(file_path, map_location='cpu')\nall = 0\nfor key in list(model['state_dict'].keys()):\n    all += model['state_dict'][key].nelement()\nprint(all)\n\n# smaller 63374123\n# v4 69140395\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/analysis_tools/visual.py",
    "content": "# Based on https://github.com/nutonomy/nuscenes-devkit\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nimport mmcv\nfrom nuscenes.nuscenes import NuScenes\nfrom PIL import Image\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nfrom typing import Tuple, List, Iterable\nimport matplotlib.pyplot as plt\nimport numpy as np\nfrom PIL import Image\nfrom matplotlib import rcParams\nfrom matplotlib.axes import Axes\nfrom pyquaternion import Quaternion\nfrom PIL import Image\nfrom matplotlib import rcParams\nfrom matplotlib.axes import Axes\nfrom pyquaternion import Quaternion\nfrom tqdm import tqdm\nfrom nuscenes.utils.data_classes import LidarPointCloud, RadarPointCloud, Box\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nfrom nuscenes.eval.common.data_classes import EvalBoxes, EvalBox\nfrom nuscenes.eval.detection.data_classes import DetectionBox\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.detection.render import visualize_sample\n\n\n\n\ncams = ['CAM_FRONT',\n 'CAM_FRONT_RIGHT',\n 'CAM_BACK_RIGHT',\n 'CAM_BACK',\n 'CAM_BACK_LEFT',\n 'CAM_FRONT_LEFT']\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom nuscenes.utils.data_classes import LidarPointCloud, RadarPointCloud, Box\nfrom PIL import Image\nfrom matplotlib import rcParams\n\n\ndef render_annotation(\n        anntoken: str,\n        margin: float = 10,\n        view: np.ndarray = np.eye(4),\n        box_vis_level: BoxVisibility = BoxVisibility.ANY,\n        out_path: str = 'render.png',\n        extra_info: bool = False) -> None:\n    \"\"\"\n    Render selected annotation.\n    :param anntoken: Sample_annotation token.\n    :param margin: How many meters in each direction to include in LIDAR view.\n    :param view: LIDAR view point.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param out_path: Optional path to save the rendered figure to disk.\n    :param extra_info: Whether to render extra information below camera view.\n    \"\"\"\n    ann_record = nusc.get('sample_annotation', anntoken)\n    sample_record = nusc.get('sample', ann_record['sample_token'])\n    assert 'LIDAR_TOP' in sample_record['data'].keys(), 'Error: No LIDAR_TOP in data, unable to render.'\n\n    # Figure out which camera the object is fully visible in (this may return nothing).\n    boxes, cam = [], []\n    cams = [key for key in sample_record['data'].keys() if 'CAM' in key]\n    all_bboxes = []\n    select_cams = []\n    for cam in cams:\n        _, boxes, _ = nusc.get_sample_data(sample_record['data'][cam], box_vis_level=box_vis_level,\n                                           selected_anntokens=[anntoken])\n        if len(boxes) > 0:\n            all_bboxes.append(boxes)\n            select_cams.append(cam)\n            # We found an image that matches. Let's abort.\n    # assert len(boxes) > 0, 'Error: Could not find image where annotation is visible. ' \\\n    #                      'Try using e.g. BoxVisibility.ANY.'\n    # assert len(boxes) < 2, 'Error: Found multiple annotations. Something is wrong!'\n\n    num_cam = len(all_bboxes)\n\n    fig, axes = plt.subplots(1, num_cam + 1, figsize=(18, 9))\n    select_cams = [sample_record['data'][cam] for cam in select_cams]\n    print('bbox in cams:', select_cams)\n    # Plot LIDAR view.\n    lidar = sample_record['data']['LIDAR_TOP']\n    data_path, boxes, camera_intrinsic = nusc.get_sample_data(lidar, selected_anntokens=[anntoken])\n    LidarPointCloud.from_file(data_path).render_height(axes[0], view=view)\n    for box in boxes:\n        c = np.array(get_color(box.name)) / 255.0\n        box.render(axes[0], view=view, colors=(c, c, c))\n        corners = view_points(boxes[0].corners(), view, False)[:2, :]\n        axes[0].set_xlim([np.min(corners[0, :]) - margin, np.max(corners[0, :]) + margin])\n        axes[0].set_ylim([np.min(corners[1, :]) - margin, np.max(corners[1, :]) + margin])\n        axes[0].axis('off')\n        axes[0].set_aspect('equal')\n\n    # Plot CAMERA view.\n    for i in range(1, num_cam + 1):\n        cam = select_cams[i - 1]\n        data_path, boxes, camera_intrinsic = nusc.get_sample_data(cam, selected_anntokens=[anntoken])\n        im = Image.open(data_path)\n        axes[i].imshow(im)\n        axes[i].set_title(nusc.get('sample_data', cam)['channel'])\n        axes[i].axis('off')\n        axes[i].set_aspect('equal')\n        for box in boxes:\n            c = np.array(get_color(box.name)) / 255.0\n            box.render(axes[i], view=camera_intrinsic, normalize=True, colors=(c, c, c))\n\n        # Print extra information about the annotation below the camera view.\n        axes[i].set_xlim(0, im.size[0])\n        axes[i].set_ylim(im.size[1], 0)\n\n    if extra_info:\n        rcParams['font.family'] = 'monospace'\n\n        w, l, h = ann_record['size']\n        category = ann_record['category_name']\n        lidar_points = ann_record['num_lidar_pts']\n        radar_points = ann_record['num_radar_pts']\n\n        sample_data_record = nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])\n        pose_record = nusc.get('ego_pose', sample_data_record['ego_pose_token'])\n        dist = np.linalg.norm(np.array(pose_record['translation']) - np.array(ann_record['translation']))\n\n        information = ' \\n'.join(['category: {}'.format(category),\n                                  '',\n                                  '# lidar points: {0:>4}'.format(lidar_points),\n                                  '# radar points: {0:>4}'.format(radar_points),\n                                  '',\n                                  'distance: {:>7.3f}m'.format(dist),\n                                  '',\n                                  'width:  {:>7.3f}m'.format(w),\n                                  'length: {:>7.3f}m'.format(l),\n                                  'height: {:>7.3f}m'.format(h)])\n\n        plt.annotate(information, (0, 0), (0, -20), xycoords='axes fraction', textcoords='offset points', va='top')\n\n    if out_path is not None:\n        plt.savefig(out_path)\n\n\n\ndef get_sample_data(sample_data_token: str,\n                    box_vis_level: BoxVisibility = BoxVisibility.ANY,\n                    selected_anntokens=None,\n                    use_flat_vehicle_coordinates: bool = False):\n    \"\"\"\n    Returns the data path as well as all annotations related to that sample_data.\n    Note that the boxes are transformed into the current sensor's coordinate frame.\n    :param sample_data_token: Sample_data token.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param selected_anntokens: If provided only return the selected annotation.\n    :param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is\n                                         aligned to z-plane in the world.\n    :return: (data_path, boxes, camera_intrinsic <np.array: 3, 3>)\n    \"\"\"\n\n    # Retrieve sensor & pose records\n    sd_record = nusc.get('sample_data', sample_data_token)\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n\n    data_path = nusc.get_sample_data_path(sample_data_token)\n\n    if sensor_record['modality'] == 'camera':\n        cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n        imsize = (sd_record['width'], sd_record['height'])\n    else:\n        cam_intrinsic = None\n        imsize = None\n\n    # Retrieve all sample annotations and map to sensor coordinate system.\n    if selected_anntokens is not None:\n        boxes = list(map(nusc.get_box, selected_anntokens))\n    else:\n        boxes = nusc.get_boxes(sample_data_token)\n\n    # Make list of Box objects including coord system transforms.\n    box_list = []\n    for box in boxes:\n        if use_flat_vehicle_coordinates:\n            # Move box to ego vehicle coord system parallel to world z plane.\n            yaw = Quaternion(pose_record['rotation']).yaw_pitch_roll[0]\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(scalar=np.cos(yaw / 2), vector=[0, 0, np.sin(yaw / 2)]).inverse)\n        else:\n            # Move box to ego vehicle coord system.\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n            #  Move box to sensor coord system.\n            box.translate(-np.array(cs_record['translation']))\n            box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n        if sensor_record['modality'] == 'camera' and not \\\n                box_in_image(box, cam_intrinsic, imsize, vis_level=box_vis_level):\n            continue\n\n        box_list.append(box)\n\n    return data_path, box_list, cam_intrinsic\n\n\n\ndef get_predicted_data(sample_data_token: str,\n                       box_vis_level: BoxVisibility = BoxVisibility.ANY,\n                       selected_anntokens=None,\n                       use_flat_vehicle_coordinates: bool = False,\n                       pred_anns=None\n                       ):\n    \"\"\"\n    Returns the data path as well as all annotations related to that sample_data.\n    Note that the boxes are transformed into the current sensor's coordinate frame.\n    :param sample_data_token: Sample_data token.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param selected_anntokens: If provided only return the selected annotation.\n    :param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is\n                                         aligned to z-plane in the world.\n    :return: (data_path, boxes, camera_intrinsic <np.array: 3, 3>)\n    \"\"\"\n\n    # Retrieve sensor & pose records\n    sd_record = nusc.get('sample_data', sample_data_token)\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n\n    data_path = nusc.get_sample_data_path(sample_data_token)\n\n    if sensor_record['modality'] == 'camera':\n        cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n        imsize = (sd_record['width'], sd_record['height'])\n    else:\n        cam_intrinsic = None\n        imsize = None\n\n    # Retrieve all sample annotations and map to sensor coordinate system.\n    # if selected_anntokens is not None:\n    #    boxes = list(map(nusc.get_box, selected_anntokens))\n    # else:\n    #    boxes = nusc.get_boxes(sample_data_token)\n    boxes = pred_anns\n    # Make list of Box objects including coord system transforms.\n    box_list = []\n    for box in boxes:\n        if use_flat_vehicle_coordinates:\n            # Move box to ego vehicle coord system parallel to world z plane.\n            yaw = Quaternion(pose_record['rotation']).yaw_pitch_roll[0]\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(scalar=np.cos(yaw / 2), vector=[0, 0, np.sin(yaw / 2)]).inverse)\n        else:\n            # Move box to ego vehicle coord system.\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n            #  Move box to sensor coord system.\n            box.translate(-np.array(cs_record['translation']))\n            box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n        if sensor_record['modality'] == 'camera' and not \\\n                box_in_image(box, cam_intrinsic, imsize, vis_level=box_vis_level):\n            continue\n        box_list.append(box)\n\n    return data_path, box_list, cam_intrinsic\n\n\n\n\ndef lidiar_render(sample_token, data,out_path=None):\n    bbox_gt_list = []\n    bbox_pred_list = []\n    anns = nusc.get('sample', sample_token)['anns']\n    for ann in anns:\n        content = nusc.get('sample_annotation', ann)\n        try:\n            bbox_gt_list.append(DetectionBox(\n                sample_token=content['sample_token'],\n                translation=tuple(content['translation']),\n                size=tuple(content['size']),\n                rotation=tuple(content['rotation']),\n                velocity=nusc.box_velocity(content['token'])[:2],\n                ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                else tuple(content['ego_translation']),\n                num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                detection_name=category_to_detection_name(content['category_name']),\n                detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                attribute_name=''))\n        except:\n            pass\n\n    bbox_anns = data['results'][sample_token]\n    for content in bbox_anns:\n        bbox_pred_list.append(DetectionBox(\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name']))\n    gt_annotations = EvalBoxes()\n    pred_annotations = EvalBoxes()\n    gt_annotations.add_boxes(sample_token, bbox_gt_list)\n    pred_annotations.add_boxes(sample_token, bbox_pred_list)\n    print('green is ground truth')\n    print('blue is the predited result')\n    visualize_sample(nusc, sample_token, gt_annotations, pred_annotations, savepath=out_path+'_bev')\n\n\ndef get_color(category_name: str):\n    \"\"\"\n    Provides the default colors based on the category names.\n    This method works for the general nuScenes categories, as well as the nuScenes detection categories.\n    \"\"\"\n    a = ['noise', 'animal', 'human.pedestrian.adult', 'human.pedestrian.child', 'human.pedestrian.construction_worker',\n     'human.pedestrian.personal_mobility', 'human.pedestrian.police_officer', 'human.pedestrian.stroller',\n     'human.pedestrian.wheelchair', 'movable_object.barrier', 'movable_object.debris',\n     'movable_object.pushable_pullable', 'movable_object.trafficcone', 'static_object.bicycle_rack', 'vehicle.bicycle',\n     'vehicle.bus.bendy', 'vehicle.bus.rigid', 'vehicle.car', 'vehicle.construction', 'vehicle.emergency.ambulance',\n     'vehicle.emergency.police', 'vehicle.motorcycle', 'vehicle.trailer', 'vehicle.truck', 'flat.driveable_surface',\n     'flat.other', 'flat.sidewalk', 'flat.terrain', 'static.manmade', 'static.other', 'static.vegetation',\n     'vehicle.ego']\n    class_names = [\n        'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n        'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n    ]\n    #print(category_name)\n    if category_name == 'bicycle':\n        return nusc.colormap['vehicle.bicycle']\n    elif category_name == 'construction_vehicle':\n        return nusc.colormap['vehicle.construction']\n    elif category_name == 'traffic_cone':\n        return nusc.colormap['movable_object.trafficcone']\n\n    for key in nusc.colormap.keys():\n        if category_name in key:\n            return nusc.colormap[key]\n    return [0, 0, 0]\n\n\ndef render_sample_data(\n        sample_toekn: str,\n        with_anns: bool = True,\n        box_vis_level: BoxVisibility = BoxVisibility.ANY,\n        axes_limit: float = 40,\n        ax=None,\n        nsweeps: int = 1,\n        out_path: str = None,\n        underlay_map: bool = True,\n        use_flat_vehicle_coordinates: bool = True,\n        show_lidarseg: bool = False,\n        show_lidarseg_legend: bool = False,\n        filter_lidarseg_labels=None,\n        lidarseg_preds_bin_path: str = None,\n        verbose: bool = True,\n        show_panoptic: bool = False,\n        pred_data=None,\n      ) -> None:\n    \"\"\"\n    Render sample data onto axis.\n    :param sample_data_token: Sample_data token.\n    :param with_anns: Whether to draw box annotations.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param axes_limit: Axes limit for lidar and radar (measured in meters).\n    :param ax: Axes onto which to render.\n    :param nsweeps: Number of sweeps for lidar and radar.\n    :param out_path: Optional path to save the rendered figure to disk.\n    :param underlay_map: When set to true, lidar data is plotted onto the map. This can be slow.\n    :param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is\n        aligned to z-plane in the world. Note: Previously this method did not use flat vehicle coordinates, which\n        can lead to small errors when the vertical axis of the global frame and lidar are not aligned. The new\n        setting is more correct and rotates the plot by ~90 degrees.\n    :param show_lidarseg: When set to True, the lidar data is colored with the segmentation labels. When set\n        to False, the colors of the lidar data represent the distance from the center of the ego vehicle.\n    :param show_lidarseg_legend: Whether to display the legend for the lidarseg labels in the frame.\n    :param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None\n        or the list is empty, all classes will be displayed.\n    :param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation\n                                    predictions for the sample.\n    :param verbose: Whether to display the image after it is rendered.\n    :param show_panoptic: When set to True, the lidar data is colored with the panoptic labels. When set\n        to False, the colors of the lidar data represent the distance from the center of the ego vehicle.\n        If show_lidarseg is True, show_panoptic will be set to False.\n    \"\"\"\n    lidiar_render(sample_toekn, pred_data, out_path=out_path)\n    sample = nusc.get('sample', sample_toekn)\n    # sample = data['results'][sample_token_list[0]][0]\n    cams = [\n        'CAM_FRONT_LEFT',\n        'CAM_FRONT',\n        'CAM_FRONT_RIGHT',\n        'CAM_BACK_LEFT',\n        'CAM_BACK',\n        'CAM_BACK_RIGHT',\n    ]\n    if ax is None:\n        _, ax = plt.subplots(4, 3, figsize=(24, 18))\n    j = 0\n    for ind, cam in enumerate(cams):\n        sample_data_token = sample['data'][cam]\n\n        sd_record = nusc.get('sample_data', sample_data_token)\n        sensor_modality = sd_record['sensor_modality']\n\n        if sensor_modality in ['lidar', 'radar']:\n            assert False\n        elif sensor_modality == 'camera':\n            # Load boxes and image.\n            boxes = [Box(record['translation'], record['size'], Quaternion(record['rotation']),\n                         name=record['detection_name'], token='predicted') for record in\n                     pred_data['results'][sample_toekn] if record['detection_score'] > 0.2]\n\n            data_path, boxes_pred, camera_intrinsic = get_predicted_data(sample_data_token,\n                                                                         box_vis_level=box_vis_level, pred_anns=boxes)\n            _, boxes_gt, _ = nusc.get_sample_data(sample_data_token, box_vis_level=box_vis_level)\n            if ind == 3:\n                j += 1\n            ind = ind % 3\n            data = Image.open(data_path)\n            # mmcv.imwrite(np.array(data)[:,:,::-1], f'{cam}.png')\n            # Init axes.\n\n            # Show image.\n            ax[j, ind].imshow(data)\n            ax[j + 2, ind].imshow(data)\n\n            # Show boxes.\n            if with_anns:\n                for box in boxes_pred:\n                    c = np.array(get_color(box.name)) / 255.0\n                    box.render(ax[j, ind], view=camera_intrinsic, normalize=True, colors=(c, c, c))\n                for box in boxes_gt:\n                    c = np.array(get_color(box.name)) / 255.0\n                    box.render(ax[j + 2, ind], view=camera_intrinsic, normalize=True, colors=(c, c, c))\n\n            # Limit visible range.\n            ax[j, ind].set_xlim(0, data.size[0])\n            ax[j, ind].set_ylim(data.size[1], 0)\n            ax[j + 2, ind].set_xlim(0, data.size[0])\n            ax[j + 2, ind].set_ylim(data.size[1], 0)\n\n        else:\n            raise ValueError(\"Error: Unknown sensor modality!\")\n\n        ax[j, ind].axis('off')\n        ax[j, ind].set_title('PRED: {} {labels_type}'.format(\n            sd_record['channel'], labels_type='(predictions)' if lidarseg_preds_bin_path else ''))\n        ax[j, ind].set_aspect('equal')\n\n        ax[j + 2, ind].axis('off')\n        ax[j + 2, ind].set_title('GT:{} {labels_type}'.format(\n            sd_record['channel'], labels_type='(predictions)' if lidarseg_preds_bin_path else ''))\n        ax[j + 2, ind].set_aspect('equal')\n\n    if out_path is not None:\n        plt.savefig(out_path+'_camera', bbox_inches='tight', pad_inches=0, dpi=200)\n    if verbose:\n        plt.show()\n    plt.close()\n\nif __name__ == '__main__':\n    nusc = NuScenes(version='v1.0-trainval', dataroot='./data/nuscenes', verbose=True)\n    # render_annotation('7603b030b42a4b1caa8c443ccc1a7d52')\n    bevformer_results = mmcv.load('test/bevformer_base/Thu_Jun__9_16_22_37_2022/pts_bbox/results_nusc.json')\n    sample_token_list = list(bevformer_results['results'].keys())\n    for id in range(0, 10):\n        render_sample_data(sample_token_list[id], pred_data=bevformer_results, out_path=sample_token_list[id])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/apis/__init__.py",
    "content": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/apis/mmdet_train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport random\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom torch.nn import DataParallel\nfrom torch.nn.parallel.distributed import DistributedDataParallel\nfrom mmcv.runner import HOOKS, DistSamplerSeedHook, EpochBasedRunner, Fp16OptimizerHook, OptimizerHook, build_runner\nfrom mmcv.utils import build_from_cfg, get_root_logger\n\nfrom mmcv.core import EvalHook\nfrom mmcv.optims import build_optimizer\nfrom mmcv.datasets import build_dataset, replace_ImageToTensor\nimport time\nimport os.path as osp\nfrom mmcv.datasets.builder import build_dataloader\nfrom mmcv.core.evaluation.eval_hooks import CustomDistEvalHook\n\ndef custom_train_detector(model,\n                   dataset,\n                   cfg,\n                   distributed=False,\n                   validate=False,\n                   timestamp=None,\n                   eval_model=None,\n                   meta=None):\n    logger = get_root_logger(cfg.log_level)\n\n    # prepare data loaders\n   \n    dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]\n    #assert len(dataset)==1s\n    if 'imgs_per_gpu' in cfg.data:\n        logger.warning('\"imgs_per_gpu\" is deprecated in MMDet V2.0. '\n                       'Please use \"samples_per_gpu\" instead')\n        if 'samples_per_gpu' in cfg.data:\n            logger.warning(\n                f'Got \"imgs_per_gpu\"={cfg.data.imgs_per_gpu} and '\n                f'\"samples_per_gpu\"={cfg.data.samples_per_gpu}, \"imgs_per_gpu\"'\n                f'={cfg.data.imgs_per_gpu} is used in this experiments')\n        else:\n            logger.warning(\n                'Automatically set \"samples_per_gpu\"=\"imgs_per_gpu\"='\n                f'{cfg.data.imgs_per_gpu} in this experiments')\n        cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu\n\n    data_loaders = [\n        build_dataloader(\n            ds,\n            cfg.data.samples_per_gpu,\n            cfg.data.workers_per_gpu,\n            # cfg.gpus will be ignored if distributed\n            len(cfg.gpu_ids),\n            dist=distributed,\n            seed=cfg.seed,\n            shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n            nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n        ) for ds in dataset\n    ]\n    # put model on gpus\n    if distributed:\n        find_unused_parameters = cfg.get('find_unused_parameters', False)\n        # Sets the `find_unused_parameters` parameter in\n        # torch.nn.parallel.DistributedDataParallel\n        model = DistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n            find_unused_parameters=find_unused_parameters)\n        if eval_model is not None:\n            eval_model = DistributedDataParallel(\n                eval_model.cuda(),\n                device_ids=[torch.cuda.current_device()],\n                broadcast_buffers=False,\n                find_unused_parameters=find_unused_parameters)\n    else:\n        model = DataParallel(\n            model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n        if eval_model is not None:\n            eval_model = DataParallel(\n                eval_model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n    # build runner\n    optimizer = build_optimizer(model, cfg.optimizer)\n\n    if 'runner' not in cfg:\n        cfg.runner = {\n            'type': 'EpochBasedRunner',\n            'max_epochs': cfg.total_epochs\n        }\n        warnings.warn(\n            'config is now expected to have a `runner` section, '\n            'please set `runner` in your config.', UserWarning)\n    else:\n        if 'total_epochs' in cfg:\n            assert cfg.total_epochs == cfg.runner.max_epochs\n    if eval_model is not None:\n        runner = build_runner(\n            cfg.runner,\n            default_args=dict(\n                model=model,\n                eval_model=eval_model,\n                optimizer=optimizer,\n                work_dir=cfg.work_dir,\n                logger=logger,\n                meta=meta))\n    else:\n        runner = build_runner(\n            cfg.runner,\n            default_args=dict(\n                model=model,\n                optimizer=optimizer,\n                work_dir=cfg.work_dir,\n                logger=logger,\n                meta=meta))\n\n    # an ugly workaround to make .log and .log.json filenames the same\n    runner.timestamp = timestamp\n\n    # fp16 setting\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        optimizer_config = Fp16OptimizerHook(\n            **cfg.optimizer_config, **fp16_cfg, distributed=distributed)\n    elif distributed and 'type' not in cfg.optimizer_config:\n        optimizer_config = OptimizerHook(**cfg.optimizer_config)\n    else:\n        optimizer_config = cfg.optimizer_config\n\n    # register hooks\n    runner.register_training_hooks(cfg.lr_config, optimizer_config,\n                                   cfg.checkpoint_config, cfg.log_config,\n                                   cfg.get('momentum_config', None))\n    \n    # register profiler hook\n    #trace_config = dict(type='tb_trace', dir_name='work_dir')\n    #profiler_config = dict(on_trace_ready=trace_config)\n    #runner.register_profiler_hook(profiler_config)\n    \n    if distributed:\n        if isinstance(runner, EpochBasedRunner):\n            runner.register_hook(DistSamplerSeedHook())\n\n    # register eval hooks\n    if validate:\n        # Support batch_size > 1 in validation\n        val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1)\n        if val_samples_per_gpu > 1:\n            assert False\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.val.pipeline = replace_ImageToTensor(\n                cfg.data.val.pipeline)\n        val_dataset = build_dataset(cfg.data.val, dict(test_mode=True))\n\n        val_dataloader = build_dataloader(\n            val_dataset,\n            samples_per_gpu=val_samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n            nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n        )\n        eval_cfg = cfg.get('evaluation', {})\n        eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner'\n        eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_'))\n        eval_hook = CustomDistEvalHook if distributed else EvalHook\n        runner.register_hook(eval_hook(val_dataloader, **eval_cfg))\n\n    # user-defined hooks\n    if cfg.get('custom_hooks', None):\n        custom_hooks = cfg.custom_hooks\n        assert isinstance(custom_hooks, list), \\\n            f'custom_hooks expect list type, but got {type(custom_hooks)}'\n        for hook_cfg in cfg.custom_hooks:\n            assert isinstance(hook_cfg, dict), \\\n                'Each item in custom_hooks expects dict type, but got ' \\\n                f'{type(hook_cfg)}'\n            hook_cfg = hook_cfg.copy()\n            priority = hook_cfg.pop('priority', 'NORMAL')\n            hook = build_from_cfg(hook_cfg, HOOKS)\n            runner.register_hook(hook, priority=priority)\n    if cfg.resume_from:\n        runner.resume(cfg.resume_from)\n    elif cfg.load_from:\n        runner.load_checkpoint(cfg.load_from)\n    runner.run(data_loaders, cfg.workflow)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/apis/test.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport os.path as osp\nimport pickle\nimport shutil\nimport tempfile\nimport time\n\nimport torch\nimport torch.distributed as dist\nfrom mmcv.image import tensor2imgs\nfrom mmcv.utils import get_dist_info\n\nfrom mmcv.core import encode_mask_results\nfrom mmcv.fileio.io import dump, load\nfrom mmcv.utils import mkdir_or_exist, ProgressBar\n\nimport numpy as np\nimport pycocotools.mask as mask_util\n\ndef custom_encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code. Semantic Masks only\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = []\n    for i in range(len(cls_segms)):\n        encoded_mask_results.append(\n            mask_util.encode(\n                np.array(\n                    cls_segms[i][:, :, np.newaxis], order='F',\n                        dtype='uint8'))[0])  # encoded with RLE\n    return [encoded_mask_results]\n\ndef custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):\n    \"\"\"Test model with multiple gpus.\n    This method tests model with multiple gpus and collects the results\n    under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'\n    it encodes results to gpu tensors and use gpu communication for results\n    collection. On cpu mode it saves the results on different gpus to 'tmpdir'\n    and collects them by the rank 0 worker.\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        tmpdir (str): Path of directory to save the temporary results from\n            different gpus under cpu mode.\n        gpu_collect (bool): Option to use either gpu or cpu to collect results.\n    Returns:\n        list: The prediction results.\n    \"\"\"\n    model.eval()\n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    rank, world_size = get_dist_info()\n    if rank == 0:\n        prog_bar = ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(data, return_loss=False, rescale=True)\n            # encode mask results\n            if isinstance(result, dict):\n                if 'bbox_results' in result.keys():\n                    bbox_result = result['bbox_results']\n                    batch_size = len(result['bbox_results'])\n                    bbox_results.extend(bbox_result)\n                if 'mask_results' in result.keys() and result['mask_results'] is not None:\n                    mask_result = custom_encode_mask_results(result['mask_results'])\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n\n            #if isinstance(result[0], tuple):\n            #    assert False, 'this code is for instance segmentation, which our code will not utilize.'\n            #    result = [(bbox_results, encode_mask_results(mask_results))\n            #              for bbox_results, mask_results in result]\n        if rank == 0:\n            \n            for _ in range(batch_size * world_size):\n                prog_bar.update()\n\n    # collect results from all ranks\n    if gpu_collect:\n        bbox_results = collect_results_gpu(bbox_results, len(dataset))\n        if have_mask:\n            mask_results = collect_results_gpu(mask_results, len(dataset))\n        else:\n            mask_results = None\n    else:\n        bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)\n        tmpdir = tmpdir+'_mask' if tmpdir is not None else None\n        if have_mask:\n            mask_results = collect_results_cpu(mask_results, len(dataset), tmpdir)\n        else:\n            mask_results = None\n\n    if mask_results is None:\n        return bbox_results\n    return {'bbox_results': bbox_results, 'mask_results': mask_results}\n\n\ndef collect_results_cpu(result_part, size, tmpdir=None):\n    rank, world_size = get_dist_info()\n    # create a tmp dir if it is not specified\n    if tmpdir is None:\n        MAX_LEN = 512\n        # 32 is whitespace\n        dir_tensor = torch.full((MAX_LEN, ),\n                                32,\n                                dtype=torch.uint8,\n                                device='cuda')\n        if rank == 0:\n            mkdir_or_exist('.dist_test')\n            tmpdir = tempfile.mkdtemp(dir='.dist_test')\n            tmpdir = torch.tensor(\n                bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda')\n            dir_tensor[:len(tmpdir)] = tmpdir\n        dist.broadcast(dir_tensor, 0)\n        tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()\n    else:\n        mkdir_or_exist(tmpdir)\n    # dump the part result to the dir\n    dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl'))\n    dist.barrier()\n    # collect all parts\n    if rank != 0:\n        return None\n    else:\n        # load results of all parts from tmp dir\n        part_list = []\n        for i in range(world_size):\n            part_file = osp.join(tmpdir, f'part_{i}.pkl')\n            part_list.append(load(part_file))\n        # sort the results\n        ordered_results = []\n        '''\n        bacause we change the sample of the evaluation stage to make sure that each gpu will handle continuous sample,\n        '''\n        #for res in zip(*part_list):\n        for res in part_list:  \n            ordered_results.extend(list(res))\n        # the dataloader may pad some samples\n        ordered_results = ordered_results[:size]\n        # remove tmp dir\n        shutil.rmtree(tmpdir)\n        return ordered_results\n\n\ndef collect_results_gpu(result_part, size):\n    collect_results_cpu(result_part, size)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/apis/train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom .mmdet_train import custom_train_detector\n\ndef custom_train_model(model,\n                dataset,\n                cfg,\n                distributed=False,\n                validate=False,\n                timestamp=None,\n                eval_model=None,\n                meta=None):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in ['EncoderDecoder3D']:\n        assert False\n    else:\n        custom_train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            eval_model=eval_model,\n            meta=meta)\n\n\ndef train_model(model,\n                dataset,\n                cfg,\n                distributed=False,\n                validate=False,\n                timestamp=None,\n                meta=None):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in ['EncoderDecoder3D']:\n        train_segmentor(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta)\n    else:\n        train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/coco_instance.py",
    "content": "dataset_type = 'CocoDataset'\ndata_root = 'data/coco/'\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\ntrain_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(type='LoadAnnotations', with_bbox=True, with_mask=True),\n    dict(type='Resize', img_scale=(1333, 800), keep_ratio=True),\n    dict(type='RandomFlip', flip_ratio=0.5),\n    dict(type='Normalize', **img_norm_cfg),\n    dict(type='Pad', size_divisor=32),\n    dict(type='DefaultFormatBundle'),\n    dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels', 'gt_masks']),\n]\ntest_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(\n        type='MultiScaleFlipAug',\n        img_scale=(1333, 800),\n        flip=False,\n        transforms=[\n            dict(type='Resize', keep_ratio=True),\n            dict(type='RandomFlip'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(type='ImageToTensor', keys=['img']),\n            dict(type='Collect', keys=['img']),\n        ])\n]\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/instances_train2017.json',\n        img_prefix=data_root + 'train2017/',\n        pipeline=train_pipeline),\n    val=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/instances_val2017.json',\n        img_prefix=data_root + 'val2017/',\n        pipeline=test_pipeline),\n    test=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/instances_val2017.json',\n        img_prefix=data_root + 'val2017/',\n        pipeline=test_pipeline))\nevaluation = dict(metric=['bbox', 'segm'])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/kitti-3d-3class.py",
    "content": "# dataset settings\ndataset_type = 'KittiDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Pedestrian', 'Cyclist', 'Car']\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'kitti_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(\n        filter_by_difficulty=[-1],\n        filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),\n    classes=class_names,\n    sample_groups=dict(Car=12, Pedestrian=6, Cyclist=6))\n\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://kitti_data/'))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='ObjectNoise',\n        num_try=100,\n        translation_std=[1.0, 1.0, 0.5],\n        global_rot_range=[0.0, 0.0],\n        rot_range=[-0.78539816, 0.78539816]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=6,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'kitti_infos_train.pkl',\n            split='training',\n            pts_prefix='velodyne_reduced',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=1, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/kitti-3d-car.py",
    "content": "# dataset settings\ndataset_type = 'KittiDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Car']\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'kitti_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),\n    classes=class_names,\n    sample_groups=dict(Car=15))\n\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://kitti_data/'))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='ObjectNoise',\n        num_try=100,\n        translation_std=[1.0, 1.0, 0.5],\n        global_rot_range=[0.0, 0.0],\n        rot_range=[-0.78539816, 0.78539816]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=6,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'kitti_infos_train.pkl',\n            split='training',\n            pts_prefix='velodyne_reduced',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=1, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/lyft-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-80, -80, -5, 80, 80, 3]\n# For Lyft we usually do 9-class detection\nclass_names = [\n    'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',\n    'bicycle', 'pedestrian', 'animal'\n]\ndataset_type = 'LyftDataset'\ndata_root = 'data/lyft/'\n# Input modality for Lyft dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/lyft/': 's3://lyft/lyft/',\n#         'data/lyft/': 's3://lyft/lyft/'\n#    }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_test.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True))\n# For Lyft dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/nuim_instance.py",
    "content": "dataset_type = 'CocoDataset'\ndata_root = 'data/nuimages/'\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\ntrain_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(type='LoadAnnotations', with_bbox=True, with_mask=True),\n    dict(\n        type='Resize',\n        img_scale=[(1280, 720), (1920, 1080)],\n        multiscale_mode='range',\n        keep_ratio=True),\n    dict(type='RandomFlip', flip_ratio=0.5),\n    dict(type='Normalize', **img_norm_cfg),\n    dict(type='Pad', size_divisor=32),\n    dict(type='DefaultFormatBundle'),\n    dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels', 'gt_masks']),\n]\ntest_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(\n        type='MultiScaleFlipAug',\n        img_scale=(1600, 900),\n        flip=False,\n        transforms=[\n            dict(type='Resize', keep_ratio=True),\n            dict(type='RandomFlip'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(type='ImageToTensor', keys=['img']),\n            dict(type='Collect', keys=['img']),\n        ])\n]\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/nuimages_v1.0-train.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=train_pipeline),\n    val=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/nuimages_v1.0-val.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline),\n    test=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/nuimages_v1.0-val.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline))\nevaluation = dict(metric=['bbox', 'segm'])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/nus-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-50, -50, -5, 50, 50, 3]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\ndataset_type = 'NuScenesDataset'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=4,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/nus-mono3d.py",
    "content": "dataset_type = 'CustomNuScenesMonoDataset'\ndata_root = 'data/nuscenes/'\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\ntrain_pipeline = [\n    dict(type='LoadImageFromFileMono3D'),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox=True,\n        with_label=True,\n        with_attr_label=True,\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_bbox_depth=True),\n    dict(type='Resize', img_scale=(1600, 900), keep_ratio=True),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='Normalize', **img_norm_cfg),\n    dict(type='Pad', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='Collect3D',\n        keys=[\n            'img', 'gt_bboxes', 'gt_labels', 'attr_labels', 'gt_bboxes_3d',\n            'gt_labels_3d', 'centers2d', 'depths'\n        ]),\n]\ntest_pipeline = [\n    dict(type='LoadImageFromFileMono3D'),\n    dict(\n        type='MultiScaleFlipAug',\n        scale_factor=1.0,\n        flip=False,\n        transforms=[\n            dict(type='RandomFlip3D'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['img']),\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(type='LoadImageFromFileMono3D'),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['img'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train_mono3d.coco.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=train_pipeline,\n        modality=input_modality,\n        test_mode=False,\n        box_type_3d='Camera'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val_mono3d.coco.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='Camera'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val_mono3d.coco.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='Camera'))\nevaluation = dict(interval=2)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/range100_lyft-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-100, -100, -5, 100, 100, 3]\n# For Lyft we usually do 9-class detection\nclass_names = [\n    'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',\n    'bicycle', 'pedestrian', 'animal'\n]\ndataset_type = 'LyftDataset'\ndata_root = 'data/lyft/'\n# Input modality for Lyft dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/lyft/': 's3://lyft/lyft/',\n#         'data/lyft/': 's3://lyft/lyft/'\n#    }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_test.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True))\n# For Lyft dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/s3dis-3d-5class.py",
    "content": "# dataset settings\ndataset_type = 'S3DISDataset'\ndata_root = './data/s3dis/'\nclass_names = ('table', 'chair', 'sofa', 'bookcase', 'board')\ntrain_area = [1, 2, 3, 4, 6]\ntest_area = 5\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(type='PointSample', num_points=40000),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        # following ScanNet dataset the rotation range is 5 degrees\n        rot_range=[-0.087266, 0.087266],\n        scale_ratio_range=[1.0, 1.0],\n        shift_height=True),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.5,\n                flip_ratio_bev_vertical=0.5),\n            dict(type='PointSample', num_points=40000),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=5,\n        dataset=dict(\n            type='ConcatDataset',\n            datasets=[\n                dict(\n                    type=dataset_type,\n                    data_root=data_root,\n                    ann_file=data_root + f's3dis_infos_Area_{i}.pkl',\n                    pipeline=train_pipeline,\n                    filter_empty_gt=False,\n                    classes=class_names,\n                    box_type_3d='Depth') for i in train_area\n            ],\n            separate_eval=False)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/s3dis_seg-3d-13class.py",
    "content": "# dataset settings\ndataset_type = 'S3DISSegDataset'\ndata_root = './data/s3dis/'\nclass_names = ('ceiling', 'floor', 'wall', 'beam', 'column', 'window', 'door',\n               'table', 'chair', 'sofa', 'bookcase', 'board', 'clutter')\nnum_points = 4096\ntrain_area = [1, 2, 3, 4, 6]\ntest_area = 5\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=tuple(range(len(class_names))),\n        max_cat_id=13),\n    dict(\n        type='IndoorPatchPointSample',\n        num_points=num_points,\n        block_size=1.0,\n        ignore_index=len(class_names),\n        use_normalized_coord=True,\n        enlarge_size=0.2,\n        min_unique_num=None),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(\n        # a wrapper in order to successfully call test function\n        # actually we don't perform test-time-aug\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.0,\n                flip_ratio_bev_vertical=0.0),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\n# we need to load gt seg_mask!\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=tuple(range(len(class_names))),\n        max_cat_id=13),\n    dict(\n        type='DefaultFormatBundle3D',\n        with_label=False,\n        class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    # train on area 1, 2, 3, 4, 6\n    # test on area 5\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_files=[\n            data_root + f's3dis_infos_Area_{i}.pkl' for i in train_area\n        ],\n        pipeline=train_pipeline,\n        classes=class_names,\n        test_mode=False,\n        ignore_index=len(class_names),\n        scene_idxs=[\n            data_root + f'seg_info/Area_{i}_resampled_scene_idxs.npy'\n            for i in train_area\n        ]),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_files=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names),\n        scene_idxs=data_root +\n        f'seg_info/Area_{test_area}_resampled_scene_idxs.npy'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_files=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names)))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/scannet-3d-18class.py",
    "content": "# dataset settings\ndataset_type = 'ScanNetDataset'\ndata_root = './data/scannet/'\nclass_names = ('cabinet', 'bed', 'chair', 'sofa', 'table', 'door', 'window',\n               'bookshelf', 'picture', 'counter', 'desk', 'curtain',\n               'refrigerator', 'showercurtrain', 'toilet', 'sink', 'bathtub',\n               'garbagebin')\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_mask_3d=True,\n        with_seg_3d=True),\n    dict(type='GlobalAlignment', rotation_axis=2),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=(3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28, 33, 34,\n                       36, 39),\n        max_cat_id=40),\n    dict(type='PointSample', num_points=40000),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.087266, 0.087266],\n        scale_ratio_range=[1.0, 1.0],\n        shift_height=True),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='Collect3D',\n        keys=[\n            'points', 'gt_bboxes_3d', 'gt_labels_3d', 'pts_semantic_mask',\n            'pts_instance_mask'\n        ])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(type='GlobalAlignment', rotation_axis=2),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.5,\n                flip_ratio_bev_vertical=0.5),\n            dict(type='PointSample', num_points=40000),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(type='GlobalAlignment', rotation_axis=2),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=5,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'scannet_infos_train.pkl',\n            pipeline=train_pipeline,\n            filter_empty_gt=False,\n            classes=class_names,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='Depth')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/scannet_seg-3d-20class.py",
    "content": "# dataset settings\ndataset_type = 'ScanNetSegDataset'\ndata_root = './data/scannet/'\nclass_names = ('wall', 'floor', 'cabinet', 'bed', 'chair', 'sofa', 'table',\n               'door', 'window', 'bookshelf', 'picture', 'counter', 'desk',\n               'curtain', 'refrigerator', 'showercurtrain', 'toilet', 'sink',\n               'bathtub', 'otherfurniture')\nnum_points = 8192\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28,\n                       33, 34, 36, 39),\n        max_cat_id=40),\n    dict(\n        type='IndoorPatchPointSample',\n        num_points=num_points,\n        block_size=1.5,\n        ignore_index=len(class_names),\n        use_normalized_coord=False,\n        enlarge_size=0.2,\n        min_unique_num=None),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(\n        # a wrapper in order to successfully call test function\n        # actually we don't perform test-time-aug\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.0,\n                flip_ratio_bev_vertical=0.0),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\n# we need to load gt seg_mask!\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28,\n                       33, 34, 36, 39),\n        max_cat_id=40),\n    dict(\n        type='DefaultFormatBundle3D',\n        with_label=False,\n        class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        test_mode=False,\n        ignore_index=len(class_names),\n        scene_idxs=data_root + 'seg_info/train_resampled_scene_idxs.npy'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names)),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names)))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/sunrgbd-3d-10class.py",
    "content": "dataset_type = 'SUNRGBDDataset'\ndata_root = 'data/sunrgbd/'\nclass_names = ('bed', 'table', 'sofa', 'chair', 'toilet', 'desk', 'dresser',\n               'night_stand', 'bookshelf', 'bathtub')\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(type='LoadAnnotations3D'),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n    ),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.523599, 0.523599],\n        scale_ratio_range=[0.85, 1.15],\n        shift_height=True),\n    dict(type='PointSample', num_points=20000),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.5,\n            ),\n            dict(type='PointSample', num_points=20000),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=16,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=5,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'sunrgbd_infos_train.pkl',\n            pipeline=train_pipeline,\n            classes=class_names,\n            filter_empty_gt=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='Depth')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'sunrgbd_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'sunrgbd_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/waymoD5-3d-3class.py",
    "content": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for efficient experiments\ndataset_type = 'LidarWaymoDataset'\ndata_root = 'data/waymo-full/kitti_format/'\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://waymo_data/'))\n\nclass_names = ['Car', 'Pedestrian', 'Cyclist']\npoint_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'waymo_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(\n        filter_by_difficulty=[-1],\n        filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),\n    classes=class_names,\n    sample_groups=dict(Car=15, Pedestrian=10, Cyclist=10),\n    points_loader=dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=[0, 1, 2, 3, 4],\n        file_client_args=file_client_args))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'waymo_infos_train.pkl',\n            split='training',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR',\n            # load one frame every five frames\n            load_interval=5)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/datasets/waymoD5-3d-car.py",
    "content": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for efficient experiments\ndataset_type = 'WaymoDataset'\ndata_root = 'data/waymo/kitti_format/'\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://waymo_data/'))\n\nclass_names = ['Car']\npoint_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'waymo_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),\n    classes=class_names,\n    sample_groups=dict(Car=15),\n    points_loader=dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=[0, 1, 2, 3, 4],\n        file_client_args=file_client_args))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'waymo_infos_train.pkl',\n            split='training',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR',\n            # load one frame every five frames\n            load_interval=5)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/default_runtime.py",
    "content": "checkpoint_config = dict(interval=1)\n# yapf:disable push\n# By default we use textlogger hook and tensorboard\n# For more loggers see\n# https://mmcv.readthedocs.io/en/latest/api.html#mmcv.runner.LoggerHook\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# yapf:enable\ndist_params = dict(backend='nccl')\nlog_level = 'INFO'\nwork_dir = None\nload_from = None\nresume_from = None\nworkflow = [('train', 1)]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/3dssd.py",
    "content": "model = dict(\n    type='SSD3DNet',\n    backbone=dict(\n        type='PointNet2SAMSG',\n        in_channels=4,\n        num_points=(4096, 512, (256, 256)),\n        radii=((0.2, 0.4, 0.8), (0.4, 0.8, 1.6), (1.6, 3.2, 4.8)),\n        num_samples=((32, 32, 64), (32, 32, 64), (32, 32, 32)),\n        sa_channels=(((16, 16, 32), (16, 16, 32), (32, 32, 64)),\n                     ((64, 64, 128), (64, 64, 128), (64, 96, 128)),\n                     ((128, 128, 256), (128, 192, 256), (128, 256, 256))),\n        aggregation_channels=(64, 128, 256),\n        fps_mods=(('D-FPS'), ('FS'), ('F-FPS', 'D-FPS')),\n        fps_sample_range_lists=((-1), (-1), (512, -1)),\n        norm_cfg=dict(type='BN2d', eps=1e-3, momentum=0.1),\n        sa_cfg=dict(\n            type='PointSAModuleMSG',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False)),\n    bbox_head=dict(\n        type='SSD3DHead',\n        in_channels=256,\n        vote_module_cfg=dict(\n            in_channels=256,\n            num_points=256,\n            gt_per_seed=1,\n            conv_channels=(128, ),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),\n            with_res_feat=False,\n            vote_xyz_range=(3.0, 3.0, 2.0)),\n        vote_aggregation_cfg=dict(\n            type='PointSAModuleMSG',\n            num_point=256,\n            radii=(4.8, 6.4),\n            sample_nums=(16, 32),\n            mlp_channels=((256, 256, 256, 512), (256, 256, 512, 1024)),\n            norm_cfg=dict(type='BN2d', eps=1e-3, momentum=0.1),\n            use_xyz=True,\n            normalize_xyz=False,\n            bias=True),\n        pred_layer_cfg=dict(\n            in_channels=1536,\n            shared_conv_channels=(512, 128),\n            cls_conv_channels=(128, ),\n            reg_conv_channels=(128, ),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),\n            bias=True),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),\n        objectness_loss=dict(\n            type='CrossEntropyLoss',\n            use_sigmoid=True,\n            reduction='sum',\n            loss_weight=1.0),\n        center_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        corner_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        vote_loss=dict(type='SmoothL1Loss', reduction='sum', loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(\n        sample_mod='spec', pos_distance_thr=10.0, expand_dims_length=0.05),\n    test_cfg=dict(\n        nms_cfg=dict(type='nms', iou_thr=0.1),\n        sample_mod='spec',\n        score_thr=0.0,\n        per_class_proposal=True,\n        max_output_num=100))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/cascade_mask_rcnn_r50_fpn.py",
    "content": "# model settings\nmodel = dict(\n    type='CascadeRCNN',\n    pretrained='torchvision://resnet50',\n    backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=True),\n        norm_eval=True,\n        style='pytorch'),\n    neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        num_outs=5),\n    rpn_head=dict(\n        type='RPNHead',\n        in_channels=256,\n        feat_channels=256,\n        anchor_generator=dict(\n            type='AnchorGenerator',\n            scales=[8],\n            ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64]),\n        bbox_coder=dict(\n            type='DeltaXYWHBBoxCoder',\n            target_means=[.0, .0, .0, .0],\n            target_stds=[1.0, 1.0, 1.0, 1.0]),\n        loss_cls=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0)),\n    roi_head=dict(\n        type='CascadeRoIHead',\n        num_stages=3,\n        stage_loss_weights=[1, 0.5, 0.25],\n        bbox_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        bbox_head=[\n            dict(\n                type='Shared2FCBBoxHead',\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type='DeltaXYWHBBoxCoder',\n                    target_means=[0., 0., 0., 0.],\n                    target_stds=[0.1, 0.1, 0.2, 0.2]),\n                reg_class_agnostic=True,\n                loss_cls=dict(\n                    type='CrossEntropyLoss',\n                    use_sigmoid=False,\n                    loss_weight=1.0),\n                loss_bbox=dict(type='SmoothL1Loss', beta=1.0,\n                               loss_weight=1.0)),\n            dict(\n                type='Shared2FCBBoxHead',\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type='DeltaXYWHBBoxCoder',\n                    target_means=[0., 0., 0., 0.],\n                    target_stds=[0.05, 0.05, 0.1, 0.1]),\n                reg_class_agnostic=True,\n                loss_cls=dict(\n                    type='CrossEntropyLoss',\n                    use_sigmoid=False,\n                    loss_weight=1.0),\n                loss_bbox=dict(type='SmoothL1Loss', beta=1.0,\n                               loss_weight=1.0)),\n            dict(\n                type='Shared2FCBBoxHead',\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type='DeltaXYWHBBoxCoder',\n                    target_means=[0., 0., 0., 0.],\n                    target_stds=[0.033, 0.033, 0.067, 0.067]),\n                reg_class_agnostic=True,\n                loss_cls=dict(\n                    type='CrossEntropyLoss',\n                    use_sigmoid=False,\n                    loss_weight=1.0),\n                loss_bbox=dict(type='SmoothL1Loss', beta=1.0, loss_weight=1.0))\n        ],\n        mask_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=14, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        mask_head=dict(\n            type='FCNMaskHead',\n            num_convs=4,\n            in_channels=256,\n            conv_out_channels=256,\n            num_classes=80,\n            loss_mask=dict(\n                type='CrossEntropyLoss', use_mask=True, loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.7,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=256,\n                pos_fraction=0.5,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False),\n            allowed_border=0,\n            pos_weight=-1,\n            debug=False),\n        rpn_proposal=dict(\n            nms_across_levels=False,\n            nms_pre=2000,\n            nms_post=2000,\n            max_num=2000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=[\n            dict(\n                assigner=dict(\n                    type='MaxIoUAssigner',\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.5,\n                    min_pos_iou=0.5,\n                    match_low_quality=False,\n                    ignore_iof_thr=-1),\n                sampler=dict(\n                    type='RandomSampler',\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False),\n            dict(\n                assigner=dict(\n                    type='MaxIoUAssigner',\n                    pos_iou_thr=0.6,\n                    neg_iou_thr=0.6,\n                    min_pos_iou=0.6,\n                    match_low_quality=False,\n                    ignore_iof_thr=-1),\n                sampler=dict(\n                    type='RandomSampler',\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False),\n            dict(\n                assigner=dict(\n                    type='MaxIoUAssigner',\n                    pos_iou_thr=0.7,\n                    neg_iou_thr=0.7,\n                    min_pos_iou=0.7,\n                    match_low_quality=False,\n                    ignore_iof_thr=-1),\n                sampler=dict(\n                    type='RandomSampler',\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False)\n        ]),\n    test_cfg=dict(\n        rpn=dict(\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_post=1000,\n            max_num=1000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=dict(\n            score_thr=0.05,\n            nms=dict(type='nms', iou_threshold=0.5),\n            max_per_img=100,\n            mask_thr_binary=0.5)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/centerpoint_01voxel_second_secfpn_nus.py",
    "content": "voxel_size = [0.1, 0.1, 0.2]\nmodel = dict(\n    type='CenterPoint',\n    pts_voxel_layer=dict(\n        max_num_points=10, voxel_size=voxel_size, max_voxels=(90000, 120000)),\n    pts_voxel_encoder=dict(type='HardSimpleVFE', num_features=5),\n    pts_middle_encoder=dict(\n        type='SparseEncoder',\n        in_channels=5,\n        sparse_shape=[41, 1024, 1024],\n        output_channels=128,\n        order=('conv', 'norm', 'act'),\n        encoder_channels=((16, 16, 32), (32, 32, 64), (64, 64, 128), (128,\n                                                                      128)),\n        encoder_paddings=((0, 0, 1), (0, 0, 1), (0, 0, [0, 1, 1]), (0, 0)),\n        block_type='basicblock'),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=256,\n        out_channels=[128, 256],\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        conv_cfg=dict(type='Conv2d', bias=False)),\n    pts_neck=dict(\n        type='SECONDFPN',\n        in_channels=[128, 256],\n        out_channels=[256, 256],\n        upsample_strides=[1, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        upsample_cfg=dict(type='deconv', bias=False),\n        use_conv_for_no_stride=True),\n    pts_bbox_head=dict(\n        type='CenterHead',\n        in_channels=sum([256, 256]),\n        tasks=[\n            dict(num_class=1, class_names=['car']),\n            dict(num_class=2, class_names=['truck', 'construction_vehicle']),\n            dict(num_class=2, class_names=['bus', 'trailer']),\n            dict(num_class=1, class_names=['barrier']),\n            dict(num_class=2, class_names=['motorcycle', 'bicycle']),\n            dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),\n        ],\n        common_heads=dict(\n            reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),\n        share_conv_channel=64,\n        bbox_coder=dict(\n            type='CenterPointBBoxCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_num=500,\n            score_threshold=0.1,\n            out_size_factor=8,\n            voxel_size=voxel_size[:2],\n            code_size=9),\n        separate_head=dict(\n            type='SeparateHead', init_bias=-2.19, final_kernel=3),\n        loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),\n        loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),\n        norm_bbox=True),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[1024, 1024, 40],\n            voxel_size=voxel_size,\n            out_size_factor=8,\n            dense_reg=1,\n            gaussian_overlap=0.1,\n            max_objs=500,\n            min_radius=2,\n            code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])),\n    test_cfg=dict(\n        pts=dict(\n            post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_per_img=500,\n            max_pool_nms=False,\n            min_radius=[4, 12, 10, 1, 0.85, 0.175],\n            score_threshold=0.1,\n            out_size_factor=8,\n            voxel_size=voxel_size[:2],\n            nms_type='rotate',\n            pre_max_size=1000,\n            post_max_size=83,\n            nms_thr=0.2)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/centerpoint_02pillar_second_secfpn_nus.py",
    "content": "voxel_size = [0.2, 0.2, 8]\nmodel = dict(\n    type='CenterPoint',\n    pts_voxel_layer=dict(\n        max_num_points=20, voxel_size=voxel_size, max_voxels=(30000, 40000)),\n    pts_voxel_encoder=dict(\n        type='PillarFeatureNet',\n        in_channels=5,\n        feat_channels=[64],\n        with_distance=False,\n        voxel_size=(0.2, 0.2, 8),\n        norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.01),\n        legacy=False),\n    pts_middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=(512, 512)),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        out_channels=[64, 128, 256],\n        layer_nums=[3, 5, 5],\n        layer_strides=[2, 2, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        conv_cfg=dict(type='Conv2d', bias=False)),\n    pts_neck=dict(\n        type='SECONDFPN',\n        in_channels=[64, 128, 256],\n        out_channels=[128, 128, 128],\n        upsample_strides=[0.5, 1, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        upsample_cfg=dict(type='deconv', bias=False),\n        use_conv_for_no_stride=True),\n    pts_bbox_head=dict(\n        type='CenterHead',\n        in_channels=sum([128, 128, 128]),\n        tasks=[\n            dict(num_class=1, class_names=['car']),\n            dict(num_class=2, class_names=['truck', 'construction_vehicle']),\n            dict(num_class=2, class_names=['bus', 'trailer']),\n            dict(num_class=1, class_names=['barrier']),\n            dict(num_class=2, class_names=['motorcycle', 'bicycle']),\n            dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),\n        ],\n        common_heads=dict(\n            reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),\n        share_conv_channel=64,\n        bbox_coder=dict(\n            type='CenterPointBBoxCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_num=500,\n            score_threshold=0.1,\n            out_size_factor=4,\n            voxel_size=voxel_size[:2],\n            code_size=9),\n        separate_head=dict(\n            type='SeparateHead', init_bias=-2.19, final_kernel=3),\n        loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),\n        loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),\n        norm_bbox=True),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            out_size_factor=4,\n            dense_reg=1,\n            gaussian_overlap=0.1,\n            max_objs=500,\n            min_radius=2,\n            code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])),\n    test_cfg=dict(\n        pts=dict(\n            post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_per_img=500,\n            max_pool_nms=False,\n            min_radius=[4, 12, 10, 1, 0.85, 0.175],\n            score_threshold=0.1,\n            pc_range=[-51.2, -51.2],\n            out_size_factor=4,\n            voxel_size=voxel_size[:2],\n            nms_type='rotate',\n            pre_max_size=1000,\n            post_max_size=83,\n            nms_thr=0.2)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/fcos3d.py",
    "content": "model = dict(\n    type='FCOSMono3D',\n    pretrained='open-mmlab://detectron2/resnet101_caffe',\n    backbone=dict(\n        type='ResNet',\n        depth=101,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='caffe'),\n    neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        start_level=1,\n        add_extra_convs='on_output',\n        num_outs=5,\n        relu_before_extra_convs=True),\n    bbox_head=dict(\n        type='FCOSMono3DHead',\n        num_classes=10,\n        in_channels=256,\n        stacked_convs=2,\n        feat_channels=256,\n        use_direction_classifier=True,\n        diff_rad_by_sin=True,\n        pred_attrs=True,\n        pred_velo=True,\n        dir_offset=0.7854,  # pi/4\n        strides=[8, 16, 32, 64, 128],\n        group_reg_dims=(2, 1, 3, 1, 2),  # offset, depth, size, rot, velo\n        cls_branch=(256, ),\n        reg_branch=(\n            (256, ),  # offset\n            (256, ),  # depth\n            (256, ),  # size\n            (256, ),  # rot\n            ()  # velo\n        ),\n        dir_branch=(256, ),\n        attr_branch=(256, ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n        loss_attr=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n        loss_centerness=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        norm_on_bbox=True,\n        centerness_on_reg=True,\n        center_sampling=True,\n        conv_bias=True,\n        dcn_on_last_conv=True),\n    train_cfg=dict(\n        allowed_border=0,\n        code_weight=[1.0, 1.0, 0.2, 1.0, 1.0, 1.0, 1.0, 0.05, 0.05],\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_pre=1000,\n        nms_thr=0.8,\n        score_thr=0.05,\n        min_bbox_size=0,\n        max_per_img=200))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/groupfree3d.py",
    "content": "model = dict(\n    type='GroupFree3DNet',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=3,\n        num_points=(2048, 1024, 512, 256),\n        radius=(0.2, 0.4, 0.8, 1.2),\n        num_samples=(64, 32, 16, 16),\n        sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),\n                     (128, 128, 256)),\n        fp_channels=((256, 256), (256, 288)),\n        norm_cfg=dict(type='BN2d'),\n        sa_cfg=dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=True)),\n    bbox_head=dict(\n        type='GroupFree3DHead',\n        in_channels=288,\n        num_decoder_layers=6,\n        num_proposal=256,\n        transformerlayers=dict(\n            type='BaseTransformerLayer',\n            attn_cfgs=dict(\n                type='GroupFree3DMHA',\n                embed_dims=288,\n                num_heads=8,\n                attn_drop=0.1,\n                dropout_layer=dict(type='Dropout', drop_prob=0.1)),\n            ffn_cfgs=dict(\n                embed_dims=288,\n                feedforward_channels=2048,\n                ffn_drop=0.1,\n                act_cfg=dict(type='ReLU', inplace=True)),\n            operation_order=('self_attn', 'norm', 'cross_attn', 'norm', 'ffn',\n                             'norm')),\n        pred_layer_cfg=dict(\n            in_channels=288, shared_conv_channels=(288, 288), bias=True),\n        sampling_objectness_loss=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=8.0),\n        objectness_loss=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        center_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        size_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', beta=1.0, reduction='sum', loss_weight=10.0),\n        semantic_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(sample_mod='kps'),\n    test_cfg=dict(\n        sample_mod='kps',\n        nms_thr=0.25,\n        score_thr=0.0,\n        per_class_proposal=True,\n        prediction_stages='last'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/h3dnet.py",
    "content": "primitive_z_cfg = dict(\n    type='PrimitiveHead',\n    num_dims=2,\n    num_classes=18,\n    primitive_mode='z',\n    upper_thresh=100.0,\n    surface_thresh=0.5,\n    vote_module_cfg=dict(\n        in_channels=256,\n        vote_per_seed=1,\n        gt_per_seed=1,\n        conv_channels=(256, 256),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        norm_feats=True,\n        vote_loss=dict(\n            type='ChamferDistance',\n            mode='l1',\n            reduction='none',\n            loss_dst_weight=10.0)),\n    vote_aggregation_cfg=dict(\n        type='PointSAModule',\n        num_point=1024,\n        radius=0.3,\n        num_sample=16,\n        mlp_channels=[256, 128, 128, 128],\n        use_xyz=True,\n        normalize_xyz=True),\n    feat_channels=(128, 128),\n    conv_cfg=dict(type='Conv1d'),\n    norm_cfg=dict(type='BN1d'),\n    objectness_loss=dict(\n        type='CrossEntropyLoss',\n        class_weight=[0.4, 0.6],\n        reduction='mean',\n        loss_weight=30.0),\n    center_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_reg_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_cls_loss=dict(\n        type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n    train_cfg=dict(\n        dist_thresh=0.2,\n        var_thresh=1e-2,\n        lower_thresh=1e-6,\n        num_point=100,\n        num_point_line=10,\n        line_thresh=0.2))\n\nprimitive_xy_cfg = dict(\n    type='PrimitiveHead',\n    num_dims=1,\n    num_classes=18,\n    primitive_mode='xy',\n    upper_thresh=100.0,\n    surface_thresh=0.5,\n    vote_module_cfg=dict(\n        in_channels=256,\n        vote_per_seed=1,\n        gt_per_seed=1,\n        conv_channels=(256, 256),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        norm_feats=True,\n        vote_loss=dict(\n            type='ChamferDistance',\n            mode='l1',\n            reduction='none',\n            loss_dst_weight=10.0)),\n    vote_aggregation_cfg=dict(\n        type='PointSAModule',\n        num_point=1024,\n        radius=0.3,\n        num_sample=16,\n        mlp_channels=[256, 128, 128, 128],\n        use_xyz=True,\n        normalize_xyz=True),\n    feat_channels=(128, 128),\n    conv_cfg=dict(type='Conv1d'),\n    norm_cfg=dict(type='BN1d'),\n    objectness_loss=dict(\n        type='CrossEntropyLoss',\n        class_weight=[0.4, 0.6],\n        reduction='mean',\n        loss_weight=30.0),\n    center_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_reg_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_cls_loss=dict(\n        type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n    train_cfg=dict(\n        dist_thresh=0.2,\n        var_thresh=1e-2,\n        lower_thresh=1e-6,\n        num_point=100,\n        num_point_line=10,\n        line_thresh=0.2))\n\nprimitive_line_cfg = dict(\n    type='PrimitiveHead',\n    num_dims=0,\n    num_classes=18,\n    primitive_mode='line',\n    upper_thresh=100.0,\n    surface_thresh=0.5,\n    vote_module_cfg=dict(\n        in_channels=256,\n        vote_per_seed=1,\n        gt_per_seed=1,\n        conv_channels=(256, 256),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        norm_feats=True,\n        vote_loss=dict(\n            type='ChamferDistance',\n            mode='l1',\n            reduction='none',\n            loss_dst_weight=10.0)),\n    vote_aggregation_cfg=dict(\n        type='PointSAModule',\n        num_point=1024,\n        radius=0.3,\n        num_sample=16,\n        mlp_channels=[256, 128, 128, 128],\n        use_xyz=True,\n        normalize_xyz=True),\n    feat_channels=(128, 128),\n    conv_cfg=dict(type='Conv1d'),\n    norm_cfg=dict(type='BN1d'),\n    objectness_loss=dict(\n        type='CrossEntropyLoss',\n        class_weight=[0.4, 0.6],\n        reduction='mean',\n        loss_weight=30.0),\n    center_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=1.0,\n        loss_dst_weight=1.0),\n    semantic_reg_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=1.0,\n        loss_dst_weight=1.0),\n    semantic_cls_loss=dict(\n        type='CrossEntropyLoss', reduction='sum', loss_weight=2.0),\n    train_cfg=dict(\n        dist_thresh=0.2,\n        var_thresh=1e-2,\n        lower_thresh=1e-6,\n        num_point=100,\n        num_point_line=10,\n        line_thresh=0.2))\n\nmodel = dict(\n    type='H3DNet',\n    backbone=dict(\n        type='MultiBackbone',\n        num_streams=4,\n        suffixes=['net0', 'net1', 'net2', 'net3'],\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d', eps=1e-5, momentum=0.01),\n        act_cfg=dict(type='ReLU'),\n        backbones=dict(\n            type='PointNet2SASSG',\n            in_channels=4,\n            num_points=(2048, 1024, 512, 256),\n            radius=(0.2, 0.4, 0.8, 1.2),\n            num_samples=(64, 32, 16, 16),\n            sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),\n                         (128, 128, 256)),\n            fp_channels=((256, 256), (256, 256)),\n            norm_cfg=dict(type='BN2d'),\n            sa_cfg=dict(\n                type='PointSAModule',\n                pool_mod='max',\n                use_xyz=True,\n                normalize_xyz=True))),\n    rpn_head=dict(\n        type='VoteHead',\n        vote_module_cfg=dict(\n            in_channels=256,\n            vote_per_seed=1,\n            gt_per_seed=3,\n            conv_channels=(256, 256),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d'),\n            norm_feats=True,\n            vote_loss=dict(\n                type='ChamferDistance',\n                mode='l1',\n                reduction='none',\n                loss_dst_weight=10.0)),\n        vote_aggregation_cfg=dict(\n            type='PointSAModule',\n            num_point=256,\n            radius=0.3,\n            num_sample=16,\n            mlp_channels=[256, 128, 128, 128],\n            use_xyz=True,\n            normalize_xyz=True),\n        pred_layer_cfg=dict(\n            in_channels=128, shared_conv_channels=(128, 128), bias=True),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        objectness_loss=dict(\n            type='CrossEntropyLoss',\n            class_weight=[0.2, 0.8],\n            reduction='sum',\n            loss_weight=5.0),\n        center_loss=dict(\n            type='ChamferDistance',\n            mode='l2',\n            reduction='sum',\n            loss_src_weight=10.0,\n            loss_dst_weight=10.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        size_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        semantic_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),\n    roi_head=dict(\n        type='H3DRoIHead',\n        primitive_list=[primitive_z_cfg, primitive_xy_cfg, primitive_line_cfg],\n        bbox_head=dict(\n            type='H3DBboxHead',\n            gt_per_seed=3,\n            num_proposal=256,\n            suface_matching_cfg=dict(\n                type='PointSAModule',\n                num_point=256 * 6,\n                radius=0.5,\n                num_sample=32,\n                mlp_channels=[128 + 6, 128, 64, 32],\n                use_xyz=True,\n                normalize_xyz=True),\n            line_matching_cfg=dict(\n                type='PointSAModule',\n                num_point=256 * 12,\n                radius=0.5,\n                num_sample=32,\n                mlp_channels=[128 + 12, 128, 64, 32],\n                use_xyz=True,\n                normalize_xyz=True),\n            feat_channels=(128, 128),\n            primitive_refine_channels=[128, 128, 128],\n            upper_thresh=100.0,\n            surface_thresh=0.5,\n            line_thresh=0.5,\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d'),\n            objectness_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.2, 0.8],\n                reduction='sum',\n                loss_weight=5.0),\n            center_loss=dict(\n                type='ChamferDistance',\n                mode='l2',\n                reduction='sum',\n                loss_src_weight=10.0,\n                loss_dst_weight=10.0),\n            dir_class_loss=dict(\n                type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),\n            dir_res_loss=dict(\n                type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n            size_class_loss=dict(\n                type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),\n            size_res_loss=dict(\n                type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n            semantic_loss=dict(\n                type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),\n            cues_objectness_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.3, 0.7],\n                reduction='mean',\n                loss_weight=5.0),\n            cues_semantic_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.3, 0.7],\n                reduction='mean',\n                loss_weight=5.0),\n            proposal_objectness_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.2, 0.8],\n                reduction='none',\n                loss_weight=5.0),\n            primitive_center_loss=dict(\n                type='MSELoss', reduction='none', loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            pos_distance_thr=0.3, neg_distance_thr=0.6, sample_mod='vote'),\n        rpn_proposal=dict(use_nms=False),\n        rcnn=dict(\n            pos_distance_thr=0.3,\n            neg_distance_thr=0.6,\n            sample_mod='vote',\n            far_threshold=0.6,\n            near_threshold=0.3,\n            mask_surface_threshold=0.3,\n            label_surface_threshold=0.3,\n            mask_line_threshold=0.3,\n            label_line_threshold=0.3)),\n    test_cfg=dict(\n        rpn=dict(\n            sample_mod='seed',\n            nms_thr=0.25,\n            score_thr=0.05,\n            per_class_proposal=True,\n            use_nms=False),\n        rcnn=dict(\n            sample_mod='seed',\n            nms_thr=0.25,\n            score_thr=0.05,\n            per_class_proposal=True)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_pointpillars_fpn_lyft.py",
    "content": "_base_ = './hv_pointpillars_fpn_nus.py'\n\n# model settings (based on nuScenes model settings)\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nmodel = dict(\n    pts_voxel_layer=dict(\n        max_num_points=20,\n        point_cloud_range=[-80, -80, -5, 80, 80, 3],\n        max_voxels=(60000, 60000)),\n    pts_voxel_encoder=dict(\n        feat_channels=[64], point_cloud_range=[-80, -80, -5, 80, 80, 3]),\n    pts_middle_encoder=dict(output_shape=[640, 640]),\n    pts_bbox_head=dict(\n        num_classes=9,\n        anchor_generator=dict(\n            ranges=[[-80, -80, -1.8, 80, 80, -1.8]], custom_values=[]),\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7)),\n    # model training settings (based on nuScenes model settings)\n    train_cfg=dict(pts=dict(code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_pointpillars_fpn_nus.py",
    "content": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nvoxel_size = [0.25, 0.25, 8]\nmodel = dict(\n    type='MVXFasterRCNN',\n    pts_voxel_layer=dict(\n        max_num_points=64,\n        point_cloud_range=[-50, -50, -5, 50, 50, 3],\n        voxel_size=voxel_size,\n        max_voxels=(30000, 40000)),\n    pts_voxel_encoder=dict(\n        type='HardVFE',\n        in_channels=4,\n        feat_channels=[64, 64],\n        with_distance=False,\n        voxel_size=voxel_size,\n        with_cluster_center=True,\n        with_voxel_center=True,\n        point_cloud_range=[-50, -50, -5, 50, 50, 3],\n        norm_cfg=dict(type='naiveSyncBN1d', eps=1e-3, momentum=0.01)),\n    pts_middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=[400, 400]),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        layer_nums=[3, 5, 5],\n        layer_strides=[2, 2, 2],\n        out_channels=[64, 128, 256]),\n    pts_neck=dict(\n        type='FPN',\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        act_cfg=dict(type='ReLU'),\n        in_channels=[64, 128, 256],\n        out_channels=256,\n        start_level=0,\n        num_outs=3),\n    pts_bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=10,\n        in_channels=256,\n        feat_channels=256,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='AlignedAnchor3DRangeGenerator',\n            ranges=[[-50, -50, -1.8, 50, 50, -1.8]],\n            scales=[1, 2, 4],\n            sizes=[\n                [0.8660, 2.5981, 1.],  # 1.5/sqrt(3)\n                [0.5774, 1.7321, 1.],  # 1/sqrt(3)\n                [1., 1., 1.],\n                [0.4, 0.4, 1],\n            ],\n            custom_values=[0, 0],\n            rotations=[0, 1.57],\n            reshape_out=True),\n        assigner_per_size=False,\n        diff_rad_by_sin=True,\n        dir_offset=0.7854,  # pi/4\n        dir_limit_offset=0,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=9),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.6,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                ignore_iof_thr=-1),\n            allowed_border=0,\n            code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        pts=dict(\n            use_rotate_nms=True,\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_thr=0.2,\n            score_thr=0.05,\n            min_bbox_size=0,\n            max_num=500)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_pointpillars_fpn_range100_lyft.py",
    "content": "_base_ = './hv_pointpillars_fpn_nus.py'\n\n# model settings (based on nuScenes model settings)\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nmodel = dict(\n    pts_voxel_layer=dict(\n        max_num_points=20,\n        point_cloud_range=[-100, -100, -5, 100, 100, 3],\n        max_voxels=(60000, 60000)),\n    pts_voxel_encoder=dict(\n        feat_channels=[64], point_cloud_range=[-100, -100, -5, 100, 100, 3]),\n    pts_middle_encoder=dict(output_shape=[800, 800]),\n    pts_bbox_head=dict(\n        num_classes=9,\n        anchor_generator=dict(\n            ranges=[[-100, -100, -1.8, 100, 100, -1.8]], custom_values=[]),\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7)),\n    # model training settings (based on nuScenes model settings)\n    train_cfg=dict(pts=dict(code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_pointpillars_secfpn_kitti.py",
    "content": "voxel_size = [0.16, 0.16, 4]\n\nmodel = dict(\n    type='VoxelNet',\n    voxel_layer=dict(\n        max_num_points=32,  # max_points_per_voxel\n        point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1],\n        voxel_size=voxel_size,\n        max_voxels=(16000, 40000)  # (training, testing) max_voxels\n    ),\n    voxel_encoder=dict(\n        type='PillarFeatureNet',\n        in_channels=4,\n        feat_channels=[64],\n        with_distance=False,\n        voxel_size=voxel_size,\n        point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1]),\n    middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=[496, 432]),\n    backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        layer_nums=[3, 5, 5],\n        layer_strides=[2, 2, 2],\n        out_channels=[64, 128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        in_channels=[64, 128, 256],\n        upsample_strides=[1, 2, 4],\n        out_channels=[128, 128, 128]),\n    bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=384,\n        feat_channels=384,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='Anchor3DRangeGenerator',\n            ranges=[\n                [0, -39.68, -0.6, 70.4, 39.68, -0.6],\n                [0, -39.68, -0.6, 70.4, 39.68, -0.6],\n                [0, -39.68, -1.78, 70.4, 39.68, -1.78],\n            ],\n            sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        assigner=[\n            dict(  # for Pedestrian\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.35,\n                min_pos_iou=0.35,\n                ignore_iof_thr=-1),\n            dict(  # for Cyclist\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.35,\n                min_pos_iou=0.35,\n                ignore_iof_thr=-1),\n            dict(  # for Car\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.6,\n                neg_iou_thr=0.45,\n                min_pos_iou=0.45,\n                ignore_iof_thr=-1),\n        ],\n        allowed_border=0,\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_thr=0.01,\n        score_thr=0.1,\n        min_bbox_size=0,\n        nms_pre=100,\n        max_num=50))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_pointpillars_secfpn_waymo.py",
    "content": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nvoxel_size = [0.32, 0.32, 6]\nmodel = dict(\n    type='MVXFasterRCNN',\n    pts_voxel_layer=dict(\n        max_num_points=20,\n        point_cloud_range=[-74.88, -74.88, -2, 74.88, 74.88, 4],\n        voxel_size=voxel_size,\n        max_voxels=(32000, 32000)),\n    pts_voxel_encoder=dict(\n        type='HardVFE',\n        in_channels=5,\n        feat_channels=[64],\n        with_distance=False,\n        voxel_size=voxel_size,\n        with_cluster_center=True,\n        with_voxel_center=True,\n        point_cloud_range=[-74.88, -74.88, -2, 74.88, 74.88, 4],\n        norm_cfg=dict(type='naiveSyncBN1d', eps=1e-3, momentum=0.01)),\n    pts_middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=[468, 468]),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        layer_nums=[3, 5, 5],\n        layer_strides=[1, 2, 2],\n        out_channels=[64, 128, 256]),\n    pts_neck=dict(\n        type='SECONDFPN',\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        in_channels=[64, 128, 256],\n        upsample_strides=[1, 2, 4],\n        out_channels=[128, 128, 128]),\n    pts_bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=384,\n        feat_channels=384,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='AlignedAnchor3DRangeGenerator',\n            ranges=[[-74.88, -74.88, -0.0345, 74.88, 74.88, -0.0345],\n                    [-74.88, -74.88, -0.1188, 74.88, 74.88, -0.1188],\n                    [-74.88, -74.88, 0, 74.88, 74.88, 0]],\n            sizes=[\n                [2.08, 4.73, 1.77],  # car\n                [0.84, 1.81, 1.77],  # cyclist\n                [0.84, 0.91, 1.74]  # pedestrian\n            ],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        dir_offset=0.7854,  # pi/4\n        dir_limit_offset=0,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            assigner=[\n                dict(  # car\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.4,\n                    min_pos_iou=0.4,\n                    ignore_iof_thr=-1),\n                dict(  # cyclist\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.3,\n                    min_pos_iou=0.3,\n                    ignore_iof_thr=-1),\n                dict(  # pedestrian\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.3,\n                    min_pos_iou=0.3,\n                    ignore_iof_thr=-1),\n            ],\n            allowed_border=0,\n            code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        pts=dict(\n            use_rotate_nms=True,\n            nms_across_levels=False,\n            nms_pre=4096,\n            nms_thr=0.25,\n            score_thr=0.1,\n            min_bbox_size=0,\n            max_num=500)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_second_secfpn_kitti.py",
    "content": "voxel_size = [0.05, 0.05, 0.1]\n\nmodel = dict(\n    type='VoxelNet',\n    voxel_layer=dict(\n        max_num_points=5,\n        point_cloud_range=[0, -40, -3, 70.4, 40, 1],\n        voxel_size=voxel_size,\n        max_voxels=(16000, 40000)),\n    voxel_encoder=dict(type='HardSimpleVFE'),\n    middle_encoder=dict(\n        type='SparseEncoder',\n        in_channels=4,\n        sparse_shape=[41, 1600, 1408],\n        order=('conv', 'norm', 'act')),\n    backbone=dict(\n        type='SECOND',\n        in_channels=256,\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        out_channels=[128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        in_channels=[128, 256],\n        upsample_strides=[1, 2],\n        out_channels=[256, 256]),\n    bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=512,\n        feat_channels=512,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='Anchor3DRangeGenerator',\n            ranges=[\n                [0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                [0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                [0, -40.0, -1.78, 70.4, 40.0, -1.78],\n            ],\n            sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        assigner=[\n            dict(  # for Pedestrian\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.35,\n                neg_iou_thr=0.2,\n                min_pos_iou=0.2,\n                ignore_iof_thr=-1),\n            dict(  # for Cyclist\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.35,\n                neg_iou_thr=0.2,\n                min_pos_iou=0.2,\n                ignore_iof_thr=-1),\n            dict(  # for Car\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.6,\n                neg_iou_thr=0.45,\n                min_pos_iou=0.45,\n                ignore_iof_thr=-1),\n        ],\n        allowed_border=0,\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_thr=0.01,\n        score_thr=0.1,\n        min_bbox_size=0,\n        nms_pre=100,\n        max_num=50))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/hv_second_secfpn_waymo.py",
    "content": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nvoxel_size = [0.08, 0.08, 0.1]\nmodel = dict(\n    type='VoxelNet',\n    voxel_layer=dict(\n        max_num_points=10,\n        point_cloud_range=[-76.8, -51.2, -2, 76.8, 51.2, 4],\n        voxel_size=voxel_size,\n        max_voxels=(80000, 90000)),\n    voxel_encoder=dict(type='HardSimpleVFE', num_features=5),\n    middle_encoder=dict(\n        type='SparseEncoder',\n        in_channels=5,\n        sparse_shape=[61, 1280, 1920],\n        order=('conv', 'norm', 'act')),\n    backbone=dict(\n        type='SECOND',\n        in_channels=384,\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        out_channels=[128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        in_channels=[128, 256],\n        upsample_strides=[1, 2],\n        out_channels=[256, 256]),\n    bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=512,\n        feat_channels=512,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='AlignedAnchor3DRangeGenerator',\n            ranges=[[-76.8, -51.2, -0.0345, 76.8, 51.2, -0.0345],\n                    [-76.8, -51.2, 0, 76.8, 51.2, 0],\n                    [-76.8, -51.2, -0.1188, 76.8, 51.2, -0.1188]],\n            sizes=[\n                [2.08, 4.73, 1.77],  # car\n                [0.84, 0.91, 1.74],  # pedestrian\n                [0.84, 1.81, 1.77]  # cyclist\n            ],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        dir_offset=0.7854,  # pi/4\n        dir_limit_offset=0,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        assigner=[\n            dict(  # car\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.55,\n                neg_iou_thr=0.4,\n                min_pos_iou=0.4,\n                ignore_iof_thr=-1),\n            dict(  # pedestrian\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                ignore_iof_thr=-1),\n            dict(  # cyclist\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                ignore_iof_thr=-1)\n        ],\n        allowed_border=0,\n        code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_pre=4096,\n        nms_thr=0.25,\n        score_thr=0.1,\n        min_bbox_size=0,\n        max_num=500))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/imvotenet_image.py",
    "content": "model = dict(\n    type='ImVoteNet',\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        num_outs=5),\n    img_rpn_head=dict(\n        type='RPNHead',\n        in_channels=256,\n        feat_channels=256,\n        anchor_generator=dict(\n            type='AnchorGenerator',\n            scales=[8],\n            ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64]),\n        bbox_coder=dict(\n            type='DeltaXYWHBBoxCoder',\n            target_means=[.0, .0, .0, .0],\n            target_stds=[1.0, 1.0, 1.0, 1.0]),\n        loss_cls=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=1.0)),\n    img_roi_head=dict(\n        type='StandardRoIHead',\n        bbox_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        bbox_head=dict(\n            type='Shared2FCBBoxHead',\n            in_channels=256,\n            fc_out_channels=1024,\n            roi_feat_size=7,\n            num_classes=10,\n            bbox_coder=dict(\n                type='DeltaXYWHBBoxCoder',\n                target_means=[0., 0., 0., 0.],\n                target_stds=[0.1, 0.1, 0.2, 0.2]),\n            reg_class_agnostic=False,\n            loss_cls=dict(\n                type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n            loss_bbox=dict(type='L1Loss', loss_weight=1.0))),\n\n    # model training and testing settings\n    train_cfg=dict(\n        img_rpn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.7,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=256,\n                pos_fraction=0.5,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False),\n            allowed_border=-1,\n            pos_weight=-1,\n            debug=False),\n        img_rpn_proposal=dict(\n            nms_across_levels=False,\n            nms_pre=2000,\n            nms_post=1000,\n            max_per_img=1000,\n            nms=dict(type='nms', iou_threshold=0.7),\n            min_bbox_size=0),\n        img_rcnn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.5,\n                min_pos_iou=0.5,\n                match_low_quality=False,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=512,\n                pos_fraction=0.25,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=True),\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        img_rpn=dict(\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_post=1000,\n            max_per_img=1000,\n            nms=dict(type='nms', iou_threshold=0.7),\n            min_bbox_size=0),\n        img_rcnn=dict(\n            score_thr=0.05,\n            nms=dict(type='nms', iou_threshold=0.5),\n            max_per_img=100)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/mask_rcnn_r50_fpn.py",
    "content": "# model settings\nmodel = dict(\n    type='MaskRCNN',\n    pretrained='torchvision://resnet50',\n    backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=True),\n        norm_eval=True,\n        style='pytorch'),\n    neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        num_outs=5),\n    rpn_head=dict(\n        type='RPNHead',\n        in_channels=256,\n        feat_channels=256,\n        anchor_generator=dict(\n            type='AnchorGenerator',\n            scales=[8],\n            ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64]),\n        bbox_coder=dict(\n            type='DeltaXYWHBBoxCoder',\n            target_means=[.0, .0, .0, .0],\n            target_stds=[1.0, 1.0, 1.0, 1.0]),\n        loss_cls=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=1.0)),\n    roi_head=dict(\n        type='StandardRoIHead',\n        bbox_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        bbox_head=dict(\n            type='Shared2FCBBoxHead',\n            in_channels=256,\n            fc_out_channels=1024,\n            roi_feat_size=7,\n            num_classes=80,\n            bbox_coder=dict(\n                type='DeltaXYWHBBoxCoder',\n                target_means=[0., 0., 0., 0.],\n                target_stds=[0.1, 0.1, 0.2, 0.2]),\n            reg_class_agnostic=False,\n            loss_cls=dict(\n                type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n            loss_bbox=dict(type='L1Loss', loss_weight=1.0)),\n        mask_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=14, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        mask_head=dict(\n            type='FCNMaskHead',\n            num_convs=4,\n            in_channels=256,\n            conv_out_channels=256,\n            num_classes=80,\n            loss_mask=dict(\n                type='CrossEntropyLoss', use_mask=True, loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.7,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=256,\n                pos_fraction=0.5,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False),\n            allowed_border=-1,\n            pos_weight=-1,\n            debug=False),\n        rpn_proposal=dict(\n            nms_across_levels=False,\n            nms_pre=2000,\n            nms_post=1000,\n            max_num=1000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.5,\n                min_pos_iou=0.5,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=512,\n                pos_fraction=0.25,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=True),\n            mask_size=28,\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        rpn=dict(\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_post=1000,\n            max_num=1000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=dict(\n            score_thr=0.05,\n            nms=dict(type='nms', iou_threshold=0.5),\n            max_per_img=100,\n            mask_thr_binary=0.5)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/paconv_cuda_ssg.py",
    "content": "_base_ = './paconv_ssg.py'\n\nmodel = dict(\n    backbone=dict(\n        sa_cfg=dict(\n            type='PAConvCUDASAModule',\n            scorenet_cfg=dict(mlp_channels=[8, 16, 16]))))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/paconv_ssg.py",
    "content": "# model settings\nmodel = dict(\n    type='EncoderDecoder3D',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=9,  # [xyz, rgb, normalized_xyz]\n        num_points=(1024, 256, 64, 16),\n        radius=(None, None, None, None),  # use kNN instead of ball query\n        num_samples=(32, 32, 32, 32),\n        sa_channels=((32, 32, 64), (64, 64, 128), (128, 128, 256), (256, 256,\n                                                                    512)),\n        fp_channels=(),\n        norm_cfg=dict(type='BN2d', momentum=0.1),\n        sa_cfg=dict(\n            type='PAConvSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False,\n            paconv_num_kernels=[16, 16, 16],\n            paconv_kernel_input='w_neighbor',\n            scorenet_input='w_neighbor_dist',\n            scorenet_cfg=dict(\n                mlp_channels=[16, 16, 16],\n                score_norm='softmax',\n                temp_factor=1.0,\n                last_bn=False))),\n    decode_head=dict(\n        type='PAConvHead',\n        # PAConv model's decoder takes skip connections from beckbone\n        # different from PointNet++, it also concats input features in the last\n        # level of decoder, leading to `128 + 6` as the channel number\n        fp_channels=((768, 256, 256), (384, 256, 256), (320, 256, 128),\n                     (128 + 6, 128, 128, 128)),\n        channels=128,\n        dropout_ratio=0.5,\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        act_cfg=dict(type='ReLU'),\n        loss_decode=dict(\n            type='CrossEntropyLoss',\n            use_sigmoid=False,\n            class_weight=None,  # should be modified with dataset\n            loss_weight=1.0)),\n    # correlation loss to regularize PAConv's kernel weights\n    loss_regularization=dict(\n        type='PAConvRegularizationLoss', reduction='sum', loss_weight=10.0),\n    # model training and testing settings\n    train_cfg=dict(),\n    test_cfg=dict(mode='slide'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/parta2.py",
    "content": "# model settings\nvoxel_size = [0.05, 0.05, 0.1]\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\n\nmodel = dict(\n    type='PartA2',\n    voxel_layer=dict(\n        max_num_points=5,  # max_points_per_voxel\n        point_cloud_range=point_cloud_range,\n        voxel_size=voxel_size,\n        max_voxels=(16000, 40000)  # (training, testing) max_voxels\n    ),\n    voxel_encoder=dict(type='HardSimpleVFE'),\n    middle_encoder=dict(\n        type='SparseUNet',\n        in_channels=4,\n        sparse_shape=[41, 1600, 1408],\n        order=('conv', 'norm', 'act')),\n    backbone=dict(\n        type='SECOND',\n        in_channels=256,\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        out_channels=[128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        in_channels=[128, 256],\n        upsample_strides=[1, 2],\n        out_channels=[256, 256]),\n    rpn_head=dict(\n        type='PartA2RPNHead',\n        num_classes=3,\n        in_channels=512,\n        feat_channels=512,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='Anchor3DRangeGenerator',\n            ranges=[[0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                    [0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                    [0, -40.0, -1.78, 70.4, 40.0, -1.78]],\n            sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        assigner_per_size=True,\n        assign_per_class=True,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    roi_head=dict(\n        type='PartAggregationROIHead',\n        num_classes=3,\n        semantic_head=dict(\n            type='PointwiseSemanticHead',\n            in_channels=16,\n            extra_width=0.2,\n            seg_score_thr=0.3,\n            num_classes=3,\n            loss_seg=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                reduction='sum',\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0),\n            loss_part=dict(\n                type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0)),\n        seg_roi_extractor=dict(\n            type='Single3DRoIAwareExtractor',\n            roi_layer=dict(\n                type='RoIAwarePool3d',\n                out_size=14,\n                max_pts_per_voxel=128,\n                mode='max')),\n        part_roi_extractor=dict(\n            type='Single3DRoIAwareExtractor',\n            roi_layer=dict(\n                type='RoIAwarePool3d',\n                out_size=14,\n                max_pts_per_voxel=128,\n                mode='avg')),\n        bbox_head=dict(\n            type='PartA2BboxHead',\n            num_classes=3,\n            seg_in_channels=16,\n            part_in_channels=4,\n            seg_conv_channels=[64, 64],\n            part_conv_channels=[64, 64],\n            merge_conv_channels=[128, 128],\n            down_conv_channels=[128, 256],\n            bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n            shared_fc_channels=[256, 512, 512, 512],\n            cls_channels=[256, 256],\n            reg_channels=[256, 256],\n            dropout_ratio=0.1,\n            roi_feat_size=14,\n            with_corner_loss=True,\n            loss_bbox=dict(\n                type='SmoothL1Loss',\n                beta=1.0 / 9.0,\n                reduction='sum',\n                loss_weight=1.0),\n            loss_cls=dict(\n                type='CrossEntropyLoss',\n                use_sigmoid=True,\n                reduction='sum',\n                loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            assigner=[\n                dict(  # for Pedestrian\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.35,\n                    min_pos_iou=0.35,\n                    ignore_iof_thr=-1),\n                dict(  # for Cyclist\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.35,\n                    min_pos_iou=0.35,\n                    ignore_iof_thr=-1),\n                dict(  # for Car\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.6,\n                    neg_iou_thr=0.45,\n                    min_pos_iou=0.45,\n                    ignore_iof_thr=-1)\n            ],\n            allowed_border=0,\n            pos_weight=-1,\n            debug=False),\n        rpn_proposal=dict(\n            nms_pre=9000,\n            nms_post=512,\n            max_num=512,\n            nms_thr=0.8,\n            score_thr=0,\n            use_rotate_nms=False),\n        rcnn=dict(\n            assigner=[\n                dict(  # for Pedestrian\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(\n                        type='BboxOverlaps3D', coordinate='lidar'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.55,\n                    min_pos_iou=0.55,\n                    ignore_iof_thr=-1),\n                dict(  # for Cyclist\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(\n                        type='BboxOverlaps3D', coordinate='lidar'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.55,\n                    min_pos_iou=0.55,\n                    ignore_iof_thr=-1),\n                dict(  # for Car\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(\n                        type='BboxOverlaps3D', coordinate='lidar'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.55,\n                    min_pos_iou=0.55,\n                    ignore_iof_thr=-1)\n            ],\n            sampler=dict(\n                type='IoUNegPiecewiseSampler',\n                num=128,\n                pos_fraction=0.55,\n                neg_piece_fractions=[0.8, 0.2],\n                neg_iou_piece_thrs=[0.55, 0.1],\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False,\n                return_iou=True),\n            cls_pos_thr=0.75,\n            cls_neg_thr=0.25)),\n    test_cfg=dict(\n        rpn=dict(\n            nms_pre=1024,\n            nms_post=100,\n            max_num=100,\n            nms_thr=0.7,\n            score_thr=0,\n            use_rotate_nms=True),\n        rcnn=dict(\n            use_rotate_nms=True,\n            use_raw_score=True,\n            nms_thr=0.01,\n            score_thr=0.1)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/pointnet2_msg.py",
    "content": "_base_ = './pointnet2_ssg.py'\n\n# model settings\nmodel = dict(\n    backbone=dict(\n        _delete_=True,\n        type='PointNet2SAMSG',\n        in_channels=6,  # [xyz, rgb], should be modified with dataset\n        num_points=(1024, 256, 64, 16),\n        radii=((0.05, 0.1), (0.1, 0.2), (0.2, 0.4), (0.4, 0.8)),\n        num_samples=((16, 32), (16, 32), (16, 32), (16, 32)),\n        sa_channels=(((16, 16, 32), (32, 32, 64)), ((64, 64, 128), (64, 96,\n                                                                    128)),\n                     ((128, 196, 256), (128, 196, 256)), ((256, 256, 512),\n                                                          (256, 384, 512))),\n        aggregation_channels=(None, None, None, None),\n        fps_mods=(('D-FPS'), ('D-FPS'), ('D-FPS'), ('D-FPS')),\n        fps_sample_range_lists=((-1), (-1), (-1), (-1)),\n        dilated_group=(False, False, False, False),\n        out_indices=(0, 1, 2, 3),\n        sa_cfg=dict(\n            type='PointSAModuleMSG',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False)),\n    decode_head=dict(\n        fp_channels=((1536, 256, 256), (512, 256, 256), (352, 256, 128),\n                     (128, 128, 128, 128))))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/pointnet2_ssg.py",
    "content": "# model settings\nmodel = dict(\n    type='EncoderDecoder3D',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=6,  # [xyz, rgb], should be modified with dataset\n        num_points=(1024, 256, 64, 16),\n        radius=(0.1, 0.2, 0.4, 0.8),\n        num_samples=(32, 32, 32, 32),\n        sa_channels=((32, 32, 64), (64, 64, 128), (128, 128, 256), (256, 256,\n                                                                    512)),\n        fp_channels=(),\n        norm_cfg=dict(type='BN2d'),\n        sa_cfg=dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False)),\n    decode_head=dict(\n        type='PointNet2Head',\n        fp_channels=((768, 256, 256), (384, 256, 256), (320, 256, 128),\n                     (128, 128, 128, 128)),\n        channels=128,\n        dropout_ratio=0.5,\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        act_cfg=dict(type='ReLU'),\n        loss_decode=dict(\n            type='CrossEntropyLoss',\n            use_sigmoid=False,\n            class_weight=None,  # should be modified with dataset\n            loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(),\n    test_cfg=dict(mode='slide'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/models/votenet.py",
    "content": "model = dict(\n    type='VoteNet',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=4,\n        num_points=(2048, 1024, 512, 256),\n        radius=(0.2, 0.4, 0.8, 1.2),\n        num_samples=(64, 32, 16, 16),\n        sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),\n                     (128, 128, 256)),\n        fp_channels=((256, 256), (256, 256)),\n        norm_cfg=dict(type='BN2d'),\n        sa_cfg=dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=True)),\n    bbox_head=dict(\n        type='VoteHead',\n        vote_module_cfg=dict(\n            in_channels=256,\n            vote_per_seed=1,\n            gt_per_seed=3,\n            conv_channels=(256, 256),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d'),\n            norm_feats=True,\n            vote_loss=dict(\n                type='ChamferDistance',\n                mode='l1',\n                reduction='none',\n                loss_dst_weight=10.0)),\n        vote_aggregation_cfg=dict(\n            type='PointSAModule',\n            num_point=256,\n            radius=0.3,\n            num_sample=16,\n            mlp_channels=[256, 128, 128, 128],\n            use_xyz=True,\n            normalize_xyz=True),\n        pred_layer_cfg=dict(\n            in_channels=128, shared_conv_channels=(128, 128), bias=True),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        objectness_loss=dict(\n            type='CrossEntropyLoss',\n            class_weight=[0.2, 0.8],\n            reduction='sum',\n            loss_weight=5.0),\n        center_loss=dict(\n            type='ChamferDistance',\n            mode='l2',\n            reduction='sum',\n            loss_src_weight=10.0,\n            loss_dst_weight=10.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        size_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0 / 3.0),\n        semantic_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(\n        pos_distance_thr=0.3, neg_distance_thr=0.6, sample_mod='vote'),\n    test_cfg=dict(\n        sample_mod='seed',\n        nms_thr=0.25,\n        score_thr=0.05,\n        per_class_proposal=True))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/cosine.py",
    "content": "# This schedule is mainly used by models with dynamic voxelization\n# optimizer\nlr = 0.003  # max learning rate\noptimizer = dict(\n    type='AdamW',\n    lr=lr,\n    betas=(0.95, 0.99),  # the momentum is change during training\n    weight_decay=0.001)\noptimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))\n\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=1000,\n    warmup_ratio=1.0 / 10,\n    min_lr_ratio=1e-5)\n\nmomentum_config = None\n\nrunner = dict(type='EpochBasedRunner', max_epochs=40)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/cyclic_20e.py",
    "content": "# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 20. Please change the interval accordingly if you do not\n# use a default schedule.\n# optimizer\n# This schedule is mainly used by models on nuScenes dataset\noptimizer = dict(type='AdamW', lr=1e-4, weight_decay=0.01)\n# max_norm=10 is better for SECOND\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\nlr_config = dict(\n    policy='cyclic',\n    target_ratio=(10, 1e-4),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\nmomentum_config = dict(\n    policy='cyclic',\n    target_ratio=(0.85 / 0.95, 1),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=20)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/cyclic_40e.py",
    "content": "# The schedule is usually used by models trained on KITTI dataset\n\n# The learning rate set in the cyclic schedule is the initial learning rate\n# rather than the max learning rate. Since the target_ratio is (10, 1e-4),\n# the learning rate will change from 0.0018 to 0.018, than go to 0.0018*1e-4\nlr = 0.0018\n# The optimizer follows the setting in SECOND.Pytorch, but here we use\n# the offcial AdamW optimizer implemented by PyTorch.\noptimizer = dict(type='AdamW', lr=lr, betas=(0.95, 0.99), weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))\n# We use cyclic learning rate and momentum schedule following SECOND.Pytorch\n# https://github.com/traveller59/second.pytorch/blob/3aba19c9688274f75ebb5e576f65cfe54773c021/torchplus/train/learning_schedules_fastai.py#L69  # noqa\n# We implement them in mmcv, for more details, please refer to\n# https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/lr_updater.py#L327  # noqa\n# https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/momentum_updater.py#L130  # noqa\nlr_config = dict(\n    policy='cyclic',\n    target_ratio=(10, 1e-4),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\nmomentum_config = dict(\n    policy='cyclic',\n    target_ratio=(0.85 / 0.95, 1),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\n# Although the max_epochs is 40, this schedule is usually used we\n# RepeatDataset with repeat ratio N, thus the actual max epoch\n# number could be Nx40\nrunner = dict(type='EpochBasedRunner', max_epochs=40)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/mmdet_schedule_1x.py",
    "content": "# optimizer\noptimizer = dict(type='SGD', lr=0.02, momentum=0.9, weight_decay=0.0001)\noptimizer_config = dict(grad_clip=None)\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=0.001,\n    step=[8, 11])\nrunner = dict(type='EpochBasedRunner', max_epochs=12)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/schedule_2x.py",
    "content": "# optimizer\n# This schedule is mainly used by models on nuScenes dataset\noptimizer = dict(type='AdamW', lr=0.001, weight_decay=0.01)\n# max_norm=10 is better for SECOND\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=1000,\n    warmup_ratio=1.0 / 1000,\n    step=[20, 23])\nmomentum_config = None\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=24)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/schedule_3x.py",
    "content": "# optimizer\n# This schedule is mainly used by models on indoor dataset,\n# e.g., VoteNet on SUNRGBD and ScanNet\nlr = 0.008  # max learning rate\noptimizer = dict(type='AdamW', lr=lr, weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))\nlr_config = dict(policy='step', warmup=None, step=[24, 32])\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=36)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/seg_cosine_150e.py",
    "content": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='SGD', lr=0.2, weight_decay=0.0001, momentum=0.9)\noptimizer_config = dict(grad_clip=None)\nlr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=0.002)\nmomentum_config = None\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=150)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/seg_cosine_200e.py",
    "content": "# optimizer\n# This schedule is mainly used on ScanNet dataset in segmentation task\noptimizer = dict(type='Adam', lr=0.001, weight_decay=0.01)\noptimizer_config = dict(grad_clip=None)\nlr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)\nmomentum_config = None\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=200)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/_base_/schedules/seg_cosine_50e.py",
    "content": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='Adam', lr=0.001, weight_decay=0.001)\noptimizer_config = dict(grad_clip=None)\nlr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)\nmomentum_config = None\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=50)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformer/bevformer_base.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n#\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\n\n\n\nimg_norm_cfg = dict(\n    mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n    'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\nqueue_length = 4 # each sequence contains `queue_length` frames.\nnum_cams = 6\nmodel = dict(\n    type='BEVFormer',\n    use_grid_mask=True,\n    video_test_mode=True,\n    img_backbone=dict(\n        type='ResNet',\n        depth=101,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN2d', requires_grad=False),\n        norm_eval=True,\n        style='caffe',\n        dcn=dict(type='DCNv2', deform_groups=1, fallback_on_stride=False), # original DCNv2 will print log when perform load_state_dict\n        stage_with_dcn=(False, False, True, True)),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=4,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='BEVFormerPerceptionTransformer',\n            num_cams=num_cams,\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            num_cams=num_cams,\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range))))\n\ndataset_type = 'CustomNuScenesDataset'\ndata_root = 'data/nuscenes/'\nanno_root = 'data/infos/'\nfile_client_args = dict(backend='disk')\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=1,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=anno_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             ann_file=anno_root + 'nuscenes_infos_temporal_val.pkl',\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              ann_file=anno_root + 'nuscenes_infos_temporal_val.pkl',\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\ntotal_epochs = 24\nevaluation = dict(interval=1, pipeline=test_pipeline)\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\nload_from = 'ckpts/r101_dcn_fcos3d_pretrain.pth'\nlog_config = dict(\n    interval=1,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n\ncheckpoint_config = dict(interval=1)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformer/bevformer_base_b2d.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n#\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nimg_norm_cfg = dict(\n    mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\nqueue_length = 4 # each sequence contains `queue_length` frames.\n\nmodel = dict(\n    type='BEVFormer',\n    use_grid_mask=True,\n    video_test_mode=True,\n    img_backbone=dict(\n        type='ResNet',\n        depth=101,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN2d', requires_grad=False),\n        norm_eval=True,\n        style='caffe',\n        dcn=dict(type='DCNv2', deform_groups=1, fallback_on_stride=False), # original DCNv2 will print log when perform load_state_dict\n        stage_with_dcn=(False, False, True, True)),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=4,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=len(class_names),\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='BEVFormerPerceptionTransformer',\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=len(class_names)),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range))))\n\ndataset_type = \"B2D_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=6,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        sample_interval=5,\n        name_mapping=NameMapping,\n        eval_cfg=eval_cfg,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             ann_file=ann_file_val,\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1,sample_interval=5,        name_mapping=NameMapping,eval_cfg=eval_cfg,),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              ann_file=ann_file_val,\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality,sample_interval=5,\n              name_mapping=NameMapping,eval_cfg=eval_cfg,),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\ntotal_epochs = 2\nevaluation = dict(interval=1, pipeline=test_pipeline)\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\nload_from = 'ckpts/r101_dcn_fcos3d_pretrain.pth'\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n\ncheckpoint_config = dict(interval=1)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformer/bevformer_tiny.py",
    "content": "# BEvFormer-tiny consumes at lease 6700M GPU memory\n# compared to bevformer_base, bevformer_tiny has\n# smaller backbone: R101-DCN -> R50\n# smaller BEV: 200*200 -> 50*50\n# less encoder layers: 6 -> 3\n# smaller input size: 1600*900 -> 800*450\n# multi-scale feautres -> single scale features (C5)\n\n\n_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n#\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\n\n\n\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\n\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n    'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 1\nbev_h_ = 50\nbev_w_ = 50\nqueue_length = 3 # each sequence contains `queue_length` frames.\n\nmodel = dict(\n    type='BEVFormer',\n    use_grid_mask=True,\n    video_test_mode=True,\n    pretrained=dict(img='torchvision://resnet50'),\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(3,),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformer',\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=3,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range))))\n\ndataset_type = 'CustomNuScenesDataset'\ndata_root = 'data/nuscenes/'\nfile_client_args = dict(backend='disk')\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='RandomScaleImageMultiViewImage', scales=[0.5]),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n   \n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.5]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\ntotal_epochs = 24\nevaluation = dict(interval=1, pipeline=test_pipeline)\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n\ncheckpoint_config = dict(interval=1)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformer/bevformer_tiny_b2d.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n#\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nimg_norm_cfg = dict(\n    mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 100\nbev_w_ = 100\nqueue_length = 3 # each sequence contains `queue_length` frames.\n\nmodel = dict(\n    type='BEVFormer',\n    use_grid_mask=True,\n    video_test_mode=True,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1,2,3),\n        frozen_stages=4,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=len(class_names),\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='BEVFormerPerceptionTransformer',\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=3,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=_dim_//32,\n                            dropout=0.0),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=len(class_names)),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range))))\n\ndataset_type = \"B2D_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=6,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        sample_interval=5,\n        name_mapping=NameMapping,\n        eval_cfg=eval_cfg,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             ann_file=ann_file_val,\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1,sample_interval=5,        name_mapping=NameMapping,eval_cfg=eval_cfg,),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              ann_file=ann_file_val,\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality,sample_interval=5,\n              name_mapping=NameMapping,eval_cfg=eval_cfg,),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\ntotal_epochs = 1\nevaluation = dict(interval=1, pipeline=test_pipeline)\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n\ncheckpoint_config = dict(interval=3000, by_epoch=False)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformer_fp16/bevformer_tiny_fp16.py",
    "content": "# BEvFormer-tiny consumes at lease 6700M GPU memory\n# compared to bevformer_base, bevformer_tiny has\n# smaller backbone: R101-DCN -> R50\n# smaller BEV: 200*200 -> 50*50\n# less encoder layers: 6 -> 3\n# smaller input size: 1600*900 -> 800*450\n# multi-scale feautres -> single scale features (C5)\n\n\n_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n#\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\n\n\n\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\n\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n    'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 1\nbev_h_ = 50\nbev_w_ = 50\nqueue_length = 3 # each sequence contains `queue_length` frames.\n\nmodel = dict(\n    type='BEVFormer_fp16',\n    use_grid_mask=True,\n    video_test_mode=True,\n    pretrained=dict(img='torchvision://resnet50'),\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(3,),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformer',\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=3,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range))))\n\ndataset_type = 'CustomNuScenesDataset'\ndata_root = 'data/nuscenes/'\nfile_client_args = dict(backend='disk')\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='RandomScaleImageMultiViewImage', scales=[0.5]),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n   \n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.5]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=8,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2.8e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\ntotal_epochs = 24\nevaluation = dict(interval=1, pipeline=test_pipeline)\n\nrunner = dict(type='EpochBasedRunner_video', max_epochs=total_epochs)\n\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n\nfp16 = dict(loss_scale=512.)\ncheckpoint_config = dict(interval=1)\ncustom_hooks = [dict(type='TransferWeight',priority='LOWEST')]"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t1-24ep.py",
    "content": "# mAP: 0.3805\n# mATE: 0.7198\n# mASE: 0.2805\n# mAOE: 0.4131\n# mAVE: 0.7652\n# mAAE: 0.1951\n# NDS: 0.4529\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (0,)\ngroup_detr = 11\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [512, 544, 576, 608, 640, 672, 704, 736, 768],  #  (0.8, 1.2)\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='GlobalRotScaleTransImage',\n        rot_range=[-22.5, 22.5],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0],\n        reverse_angle=True,\n        training=True,\n        flip_dx_ratio=0.5,\n        flip_dy_ratio=0.5,\n        only_gt=True,),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead_GroupDETR',\n        group_detr=group_detr,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='GroupMultiheadAttention',\n                            group=group_detr,\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[20, ])\ntotal_epochs = 24\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t1-48ep.py",
    "content": "# mAP: 0.3953\n# mATE: 0.6941\n# mASE: 0.2765\n# mAOE: 0.4199\n# mAVE: 0.7537\n# mAAE: 0.1866\n# NDS: 0.4646\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (0,)\ngroup_detr = 11\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [512, 544, 576, 608, 640, 672, 704, 736, 768],  #  (0.8, 1.2)\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='GlobalRotScaleTransImage',\n        rot_range=[-22.5, 22.5],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0],\n        reverse_angle=True,\n        training=True,\n        flip_dx_ratio=0.5,\n        flip_dy_ratio=0.5,\n        only_gt=True,),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead_GroupDETR',\n        group_detr=group_detr,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='GroupMultiheadAttention',\n                            group=group_detr,\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[44, ])\ntotal_epochs = 48\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t1-base-24ep.py",
    "content": "# mAP: 0.3512\n# mATE: 0.7534\n# mASE: 0.2863\n# mAOE: 0.4665\n# mAVE: 0.8070\n# mAAE: 0.1861\n# NDS: 0.4257\n\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (0,)\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[20, ])\ntotal_epochs = 24\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t1-base-48ep.py",
    "content": "# mAP: 0.3594\n# mATE: 0.7327\n# mASE: 0.2814\n# mAOE: 0.4074\n# mAVE: 0.7831\n# mAAE: 0.1983\n# NDS: 0.4394\n\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (0,)\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[44, ])\ntotal_epochs = 48\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t2-24ep.py",
    "content": "# mAP: 0.4199\n# mATE: 0.6689\n# mASE: 0.2814\n# mAOE: 0.3915\n# mAVE: 0.3834\n# mAAE: 0.1928\n# NDS: 0.5182\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (-1, 0,)\ngroup_detr = 11\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [512, 544, 576, 608, 640, 672, 704, 736, 768],  #  (0.8, 1.2)\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='GlobalRotScaleTransImage',\n        rot_range=[-22.5, 22.5],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0],\n        reverse_angle=True,\n        training=True,\n        flip_dx_ratio=0.5,\n        flip_dy_ratio=0.5,\n        only_gt=True,),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead_GroupDETR',\n        group_detr=group_detr,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='GroupMultiheadAttention',\n                            group=group_detr,\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[20, ])\ntotal_epochs = 24\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t2-48ep.py",
    "content": "# mAP: 0.4313\n# mATE: 0.6557\n# mASE: 0.2775\n# mAOE: 0.3851\n# mAVE: 0.3861\n# mAAE: 0.1882\n# NDS: 0.5264\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (-1, 0,)\ngroup_detr = 11\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [512, 544, 576, 608, 640, 672, 704, 736, 768],  #  (0.8, 1.2)\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='GlobalRotScaleTransImage',\n        rot_range=[-22.5, 22.5],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0],\n        reverse_angle=True,\n        training=True,\n        flip_dx_ratio=0.5,\n        flip_dy_ratio=0.5,\n        only_gt=True,),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead_GroupDETR',\n        group_detr=group_detr,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='GroupMultiheadAttention',\n                            group=group_detr,\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[20, ])\ntotal_epochs = 24\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/bevformerv2/bevformerv2-r50-t8-24ep.py",
    "content": "# mAP: 0.4600\n# mATE: 0.6185\n# mASE: 0.2815\n# mAOE: 0.3660\n# mAVE: 0.3157\n# mAAE: 0.1902\n# NDS: 0.5528\n_base_ = [\n    '../_base_/default_runtime.py'\n]\n# Dataset\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle',\n    'pedestrian', 'traffic_cone', 'trailer', 'truck'\n]\ndataset_type = 'CustomNuScenesDatasetV2'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(mean=[103.53, 116.28, 123.675], std=[1, 1, 1], to_rgb=False)\nbev_h_ = 200\nbev_w_ = 200\nframes = (-7,-6,-5,-4,-3,-2,-1,0)\ngroup_detr = 11\nvoxel_size = [102.4 / bev_h_, 102.4 / bev_w_, 8]\nida_aug_conf = {\n    \"reisze\": [512, 544, 576, 608, 640, 672, 704, 736, 768],  #  (0.8, 1.2)\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n}\nida_aug_conf_eval = {\n    \"reisze\": [640, ],\n    \"crop\": (0, 260, 1600, 900),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": False,\n}\n# file_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='GlobalRotScaleTransImage',\n        rot_range=[-22.5, 22.5],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0],\n        reverse_angle=True,\n        training=True,\n        flip_dx_ratio=0.5,\n        flip_dy_ratio=0.5,\n        only_gt=True,),\n    dict(\n        type='ObjectRangeFilter',\n        point_cloud_range=point_cloud_range),\n    dict(\n        type='ObjectNameFilter',\n        classes=class_names),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf, training=True, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='CustomCollect3D',\n        keys=['gt_bboxes_3d', 'gt_labels_3d', 'img',\n              'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation', 'lidar2ego_rotation',\n              'timestamp', 'mono_input_dict', 'mono_ann_idx', 'aug_param']),\n    dict(type='DD3DMapper',\n         is_train=True,\n         tasks=dict(box2d_on=True, box3d_on=True),)\n]\neval_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True, ),\n    dict(type='CropResizeFlipImage', data_aug_conf=ida_aug_conf_eval, training=False, debug=False),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 640),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D',\n                 keys=['img', 'ego2global_translation', 'ego2global_rotation', 'lidar2ego_translation',\n                       'lidar2ego_rotation', 'timestamp'])\n        ])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    persistent_workers=True,\n    train=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        box_type_3d='LiDAR',\n        mono_cfg=dict(\n            name='nusc_trainval',\n            data_root='data/nuscenes/',\n            min_num_lidar_points=3,\n            min_box_visibility=0.2)),\n    val=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1),\n    test=dict(\n        type='CustomNuScenesDatasetV2',\n        frames=frames,\n        data_root='data/nuscenes/',\n        ann_file=data_root + 'nuscenes_infos_temporal_val.pkl',\n        pipeline=eval_pipeline,\n        classes=class_names,\n        modality=input_modality),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler'))\nevaluation = dict(interval=4, pipeline=eval_pipeline)\n\n# model\nload_from = './ckpts/fcos_r50_coco_2mmdet.pth'\nplugin = True\nplugin_dir = 'projects/mmdet3d_plugin/'\n_dim_ = 256\n_pos_dim_ = 128\n_ffn_dim_ = 512\n_num_levels_ = 4\n_num_mono_levels_ = 5\n\nmodel = dict(\n    type='BEVFormerV2',\n    use_grid_mask=True,\n    video_test_mode=False,\n    num_levels=_num_levels_,\n    num_mono_levels=_num_mono_levels_,\n    mono_loss_weight=1.0,\n    frames=frames,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=-1,\n        norm_cfg=dict(type='SyncBN'),\n        norm_eval=False,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_mono_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='BEVFormerHead_GroupDETR',\n        group_detr=group_detr,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        transformer=dict(\n            type='PerceptionTransformerV2',\n            embed_dims=_dim_,\n            frames=frames,\n            inter_channels=_dim_*2,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=4),\n                            embed_dims=_dim_)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='GroupMultiheadAttention',\n                            group=group_detr,\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1)\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='NMSFreeCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='SmoothL1Loss', loss_weight=0.75, beta=1.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0)),\n    fcos3d_bbox_head=dict(\n        type='NuscenesDD3D',\n        num_classes=10,\n        in_channels=_dim_,\n        strides=[8, 16, 32, 64, 128],\n        box3d_on=True,\n        feature_locations_offset='none',\n        fcos2d_cfg=dict(\n            num_cls_convs=4,\n            num_box_convs=4,\n            norm='SyncBN',\n            use_deformable=False,\n            use_scale=True,\n            box2d_scale_init_factor=1.0),\n        fcos2d_loss_cfg=dict(\n            focal_loss_alpha=0.25, focal_loss_gamma=2.0, loc_loss_type='giou'),\n        fcos3d_cfg=dict(\n            num_convs=4,\n            norm='SyncBN',\n            use_scale=True,\n            depth_scale_init_factor=0.3,\n            proj_ctr_scale_init_factor=1.0,\n            use_per_level_predictors=False,\n            class_agnostic=False,\n            use_deformable=False,\n            mean_depth_per_level=[44.921, 20.252, 11.712, 7.166, 8.548],\n            std_depth_per_level=[24.331, 9.833, 6.223, 4.611, 8.275]),\n        fcos3d_loss_cfg=dict(\n            min_depth=0.1,\n            max_depth=80.0,\n            box3d_loss_weight=2.0,\n            conf3d_loss_weight=1.0,\n            conf_3d_temperature=1.0,\n            smooth_l1_loss_beta=0.05,\n            max_loss_per_group=20,\n            predict_allocentric_rot=True,\n            scale_depth_by_focal_lengths=True,\n            scale_depth_by_focal_lengths_factor=500.0,\n            class_agnostic=False,\n            predict_distance=False,\n            canon_box_sizes=[[2.3524184, 0.5062202, 1.0413622],\n                             [0.61416006, 1.7016163, 1.3054738],\n                             [2.9139307, 10.725025, 3.2832346],\n                             [1.9751819, 4.641267, 1.74352],\n                             [2.772134, 6.565072, 3.2474296],\n                             [0.7800532, 2.138673, 1.4437162],\n                             [0.6667362, 0.7181772, 1.7616143],\n                             [0.40246472, 0.4027083, 1.0084083],\n                             [3.0059454, 12.8197, 4.1213827],\n                             [2.4986045, 6.9310856, 2.8382742]]),\n        target_assign_cfg=dict(\n            center_sample=True,\n            pos_radius=1.5,\n            sizes_of_interest=((-1, 64), (64, 128), (128, 256), (256, 512),\n                               (512, 100000000.0))),\n        nusc_loss_weight=dict(attr_loss_weight=0.2, speed_loss_weight=0.2)),\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type='HungarianAssigner3D',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='SmoothL1Cost', weight=0.75),\n                iou_cost=dict(type='IoUCost', weight=0.0),\n                pc_range=point_cloud_range))))\n\n# optimizer\noptimizer = dict(\n    type='AdamW',\n    lr=4e-4,\n    paramwise_cfg=dict(\n        custom_keys=dict(\n            img_backbone=dict(lr_mult=0.5),\n        )),\n    weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=2000,\n    warmup_ratio=1.0 / 3,\n    step=[20, ])\ntotal_epochs = 24\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/datasets/custom_lyft-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-80, -80, -5, 80, 80, 3]\n# For Lyft we usually do 9-class detection\nclass_names = [\n    'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',\n    'bicycle', 'pedestrian', 'animal'\n]\ndataset_type = 'CustomLyftDataset'\ndata_root = 'data/lyft/'\n# Input modality for Lyft dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/lyft/': 's3://lyft/lyft/',\n#         'data/lyft/': 's3://lyft/lyft/'\n#    }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True))\n# For Lyft dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/datasets/custom_nus-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-50, -50, -5, 50, 50, 3]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\ndataset_type = 'NuScenesDataset_eval_modified'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=4,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(\n        type=dataset_type,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/configs/datasets/custom_waymo-3d.py",
    "content": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for efficient experiments\ndataset_type = 'CustomWaymoDataset'\ndata_root = 'data/waymo/kitti_format/'\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://waymo_data/'))\n\nimg_norm_cfg = dict(\n    mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\nclass_names = ['Car', 'Pedestrian', 'Cyclist']\npoint_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]\ninput_modality = dict(use_lidar=False, use_camera=True)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'waymo_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(\n        filter_by_difficulty=[-1],\n        filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),\n    classes=class_names,\n    sample_groups=dict(Car=15, Pedestrian=10, Cyclist=10),\n    points_loader=dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=[0, 1, 2, 3, 4],\n        file_client_args=file_client_args))\n\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1920, 1280),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\n\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'waymo_infos_train.pkl',\n            split='training',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR',\n            # load one frame every five frames\n            load_interval=5)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=24, pipeline=test_pipeline)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/create_data.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nfrom data_converter.create_gt_database import create_groundtruth_database\nfrom data_converter import nuscenes_converter as nuscenes_converter\nfrom data_converter import lyft_converter as lyft_converter\nfrom data_converter import kitti_converter as kitti\nfrom data_converter import indoor_converter as indoor\nimport argparse\nfrom os import path as osp\nimport sys\nsys.path.append('.')\n\n\ndef kitti_data_prep(root_path, info_prefix, version, out_dir):\n    \"\"\"Prepare data related to Kitti dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        out_dir (str): Output directory of the groundtruth database info.\n    \"\"\"\n    kitti.create_kitti_info_file(root_path, info_prefix)\n    kitti.create_reduced_point_cloud(root_path, info_prefix)\n\n    info_train_path = osp.join(root_path, f'{info_prefix}_infos_train.pkl')\n    info_val_path = osp.join(root_path, f'{info_prefix}_infos_val.pkl')\n    info_trainval_path = osp.join(root_path,\n                                  f'{info_prefix}_infos_trainval.pkl')\n    info_test_path = osp.join(root_path, f'{info_prefix}_infos_test.pkl')\n    kitti.export_2d_annotation(root_path, info_train_path)\n    kitti.export_2d_annotation(root_path, info_val_path)\n    kitti.export_2d_annotation(root_path, info_trainval_path)\n    kitti.export_2d_annotation(root_path, info_test_path)\n\n    create_groundtruth_database(\n        'KittiDataset',\n        root_path,\n        info_prefix,\n        f'{out_dir}/{info_prefix}_infos_train.pkl',\n        relative_path=False,\n        mask_anno_path='instances_train.json',\n        with_mask=(version == 'mask'))\n\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    nuscenes_converter.create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n    if version == 'v1.0-test':\n        info_test_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_test.pkl')\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_test_path, version=version)\n    else:\n        info_train_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_train.pkl')\n        info_val_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_val.pkl')\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_train_path, version=version)\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_val_path, version=version)\n        # create_groundtruth_database(dataset_name, root_path, info_prefix,\n        #                             f'{out_dir}/{info_prefix}_infos_train.pkl')\n\n\ndef lyft_data_prep(root_path, info_prefix, version, max_sweeps=10):\n    \"\"\"Prepare data related to Lyft dataset.\n\n    Related data consists of '.pkl' files recording basic infos.\n    Although the ground truth database and 2D annotations are not used in\n    Lyft, it can also be generated like nuScenes.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        max_sweeps (int, optional): Number of input consecutive frames.\n            Defaults to 10.\n    \"\"\"\n    lyft_converter.create_lyft_infos(\n        root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\ndef scannet_data_prep(root_path, info_prefix, out_dir, workers):\n    \"\"\"Prepare the info file for scannet dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n    \"\"\"\n    indoor.create_indoor_info_file(\n        root_path, info_prefix, out_dir, workers=workers)\n\n\ndef s3dis_data_prep(root_path, info_prefix, out_dir, workers):\n    \"\"\"Prepare the info file for s3dis dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n    \"\"\"\n    indoor.create_indoor_info_file(\n        root_path, info_prefix, out_dir, workers=workers)\n\n\ndef sunrgbd_data_prep(root_path, info_prefix, out_dir, workers):\n    \"\"\"Prepare the info file for sunrgbd dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n    \"\"\"\n    indoor.create_indoor_info_file(\n        root_path, info_prefix, out_dir, workers=workers)\n\n\ndef waymo_data_prep(root_path,\n                    info_prefix,\n                    version,\n                    out_dir,\n                    workers,\n                    max_sweeps=5):\n    \"\"\"Prepare the info file for waymo dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n        max_sweeps (int): Number of input consecutive frames. Default: 5 \\\n            Here we store pose information of these frames for later use.\n    \"\"\"\n    from tools.data_converter import waymo_converter as waymo\n\n    splits = ['training', 'validation', 'testing']\n\n    for i, split in enumerate(splits):\n        load_dir = osp.join(root_path, 'waymo_format', split)\n        if split == 'validation':\n            save_dir = osp.join(out_dir, 'kitti_format', 'training')\n        else:\n            save_dir = osp.join(out_dir, 'kitti_format', split)\n        converter = waymo.Waymo2KITTI(\n            load_dir,\n            save_dir,\n            prefix=str(i),\n            workers=workers,\n            test_mode=(split == 'test'))\n        converter.convert()\n    # Generate waymo infos\n    out_dir = osp.join(out_dir, 'kitti_format')\n    kitti.create_waymo_info_file(out_dir, info_prefix, max_sweeps=max_sweeps)\n\n    create_groundtruth_database(\n        'WaymoDataset',\n        out_dir,\n        info_prefix,\n        f'{out_dir}/{info_prefix}_infos_train.pkl',\n        relative_path=False,\n        with_mask=False)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'kitti':\n        kitti_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=args.version,\n            out_dir=args.out_dir)\n    elif args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'lyft':\n        train_version = f'{args.version}-train'\n        lyft_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        lyft_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'waymo':\n        waymo_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=args.version,\n            out_dir=args.out_dir,\n            workers=args.workers,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'scannet':\n        scannet_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            out_dir=args.out_dir,\n            workers=args.workers)\n    elif args.dataset == 's3dis':\n        s3dis_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            out_dir=args.out_dir,\n            workers=args.workers)\n    elif args.dataset == 'sunrgbd':\n        sunrgbd_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            out_dir=args.out_dir,\n            workers=args.workers)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/create_gt_database.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport pickle\nfrom mmcv import track_iter_progress\nfrom mmcv.ops import roi_align\nfrom os import path as osp\nfrom pycocotools import mask as maskUtils\nfrom pycocotools.coco import COCO\n\nfrom mmcv.core.bbox import box_np_ops as box_np_ops\nfrom mmcv.datasets import build_dataset\nfrom mmcv.core.evaluation.bbox_overlaps import bbox_overlaps\n\n\ndef _poly2mask(mask_ann, img_h, img_w):\n    if isinstance(mask_ann, list):\n        # polygon -- a single object might consist of multiple parts\n        # we merge all parts into one mask rle code\n        rles = maskUtils.frPyObjects(mask_ann, img_h, img_w)\n        rle = maskUtils.merge(rles)\n    elif isinstance(mask_ann['counts'], list):\n        # uncompressed RLE\n        rle = maskUtils.frPyObjects(mask_ann, img_h, img_w)\n    else:\n        # rle\n        rle = mask_ann\n    mask = maskUtils.decode(rle)\n    return mask\n\n\ndef _parse_coco_ann_info(ann_info):\n    gt_bboxes = []\n    gt_labels = []\n    gt_bboxes_ignore = []\n    gt_masks_ann = []\n\n    for i, ann in enumerate(ann_info):\n        if ann.get('ignore', False):\n            continue\n        x1, y1, w, h = ann['bbox']\n        if ann['area'] <= 0:\n            continue\n        bbox = [x1, y1, x1 + w, y1 + h]\n        if ann.get('iscrowd', False):\n            gt_bboxes_ignore.append(bbox)\n        else:\n            gt_bboxes.append(bbox)\n            gt_masks_ann.append(ann['segmentation'])\n\n    if gt_bboxes:\n        gt_bboxes = np.array(gt_bboxes, dtype=np.float32)\n        gt_labels = np.array(gt_labels, dtype=np.int64)\n    else:\n        gt_bboxes = np.zeros((0, 4), dtype=np.float32)\n        gt_labels = np.array([], dtype=np.int64)\n\n    if gt_bboxes_ignore:\n        gt_bboxes_ignore = np.array(gt_bboxes_ignore, dtype=np.float32)\n    else:\n        gt_bboxes_ignore = np.zeros((0, 4), dtype=np.float32)\n\n    ann = dict(\n        bboxes=gt_bboxes, bboxes_ignore=gt_bboxes_ignore, masks=gt_masks_ann)\n\n    return ann\n\n\ndef crop_image_patch_v2(pos_proposals, pos_assigned_gt_inds, gt_masks):\n    import torch\n    from torch.nn.modules.utils import _pair\n    device = pos_proposals.device\n    num_pos = pos_proposals.size(0)\n    fake_inds = (\n        torch.arange(num_pos,\n                     device=device).to(dtype=pos_proposals.dtype)[:, None])\n    rois = torch.cat([fake_inds, pos_proposals], dim=1)  # Nx5\n    mask_size = _pair(28)\n    rois = rois.to(device=device)\n    gt_masks_th = (\n        torch.from_numpy(gt_masks).to(device).index_select(\n            0, pos_assigned_gt_inds).to(dtype=rois.dtype))\n    # Use RoIAlign could apparently accelerate the training (~0.1s/iter)\n    targets = (\n        roi_align(gt_masks_th, rois, mask_size[::-1], 1.0, 0, True).squeeze(1))\n    return targets\n\n\ndef crop_image_patch(pos_proposals, gt_masks, pos_assigned_gt_inds, org_img):\n    num_pos = pos_proposals.shape[0]\n    masks = []\n    img_patches = []\n    for i in range(num_pos):\n        gt_mask = gt_masks[pos_assigned_gt_inds[i]]\n        bbox = pos_proposals[i, :].astype(np.int32)\n        x1, y1, x2, y2 = bbox\n        w = np.maximum(x2 - x1 + 1, 1)\n        h = np.maximum(y2 - y1 + 1, 1)\n\n        mask_patch = gt_mask[y1:y1 + h, x1:x1 + w]\n        masked_img = gt_mask[..., None] * org_img\n        img_patch = masked_img[y1:y1 + h, x1:x1 + w]\n\n        img_patches.append(img_patch)\n        masks.append(mask_patch)\n    return img_patches, masks\n\n\ndef create_groundtruth_database(dataset_class_name,\n                                data_path,\n                                info_prefix,\n                                info_path=None,\n                                mask_anno_path=None,\n                                used_classes=None,\n                                database_save_path=None,\n                                db_info_save_path=None,\n                                relative_path=True,\n                                add_rgb=False,\n                                lidar_only=False,\n                                bev_only=False,\n                                coors_range=None,\n                                with_mask=False):\n    \"\"\"Given the raw data, generate the ground truth database.\n\n    Args:\n        dataset_class_name （str): Name of the input dataset.\n        data_path (str): Path of the data.\n        info_prefix (str): Prefix of the info file.\n        info_path (str): Path of the info file.\n            Default: None.\n        mask_anno_path (str): Path of the mask_anno.\n            Default: None.\n        used_classes (list[str]): Classes have been used.\n            Default: None.\n        database_save_path (str): Path to save database.\n            Default: None.\n        db_info_save_path (str): Path to save db_info.\n            Default: None.\n        relative_path (bool): Whether to use relative path.\n            Default: True.\n        with_mask (bool): Whether to use mask.\n            Default: False.\n    \"\"\"\n    print(f'Create GT Database of {dataset_class_name}')\n    dataset_cfg = dict(\n        type=dataset_class_name, data_root=data_path, ann_file=info_path)\n    if dataset_class_name == 'KittiDataset':\n        file_client_args = dict(backend='disk')\n        dataset_cfg.update(\n            test_mode=False,\n            split='training',\n            modality=dict(\n                use_lidar=True,\n                use_depth=False,\n                use_lidar_intensity=True,\n                use_camera=with_mask,\n            ),\n            pipeline=[\n                dict(\n                    type='LoadPointsFromFile',\n                    coord_type='LIDAR',\n                    load_dim=4,\n                    use_dim=4,\n                    file_client_args=file_client_args),\n                dict(\n                    type='LoadAnnotations3D',\n                    with_bbox_3d=True,\n                    with_label_3d=True,\n                    file_client_args=file_client_args)\n            ])\n\n    elif dataset_class_name == 'NuScenesDataset':\n        dataset_cfg.update(\n            use_valid_flag=True,\n            pipeline=[\n                dict(\n                    type='LoadPointsFromFile',\n                    coord_type='LIDAR',\n                    load_dim=5,\n                    use_dim=5),\n                dict(\n                    type='LoadPointsFromMultiSweeps',\n                    sweeps_num=10,\n                    use_dim=[0, 1, 2, 3, 4],\n                    pad_empty_sweeps=True,\n                    remove_close=True),\n                dict(\n                    type='LoadAnnotations3D',\n                    with_bbox_3d=True,\n                    with_label_3d=True)\n            ])\n\n    elif dataset_class_name == 'WaymoDataset':\n        file_client_args = dict(backend='disk')\n        dataset_cfg.update(\n            test_mode=False,\n            split='training',\n            modality=dict(\n                use_lidar=True,\n                use_depth=False,\n                use_lidar_intensity=True,\n                use_camera=False,\n            ),\n            pipeline=[\n                dict(\n                    type='LoadPointsFromFile',\n                    coord_type='LIDAR',\n                    load_dim=6,\n                    use_dim=5,\n                    file_client_args=file_client_args),\n                dict(\n                    type='LoadAnnotations3D',\n                    with_bbox_3d=True,\n                    with_label_3d=True,\n                    file_client_args=file_client_args)\n            ])\n\n    dataset = build_dataset(dataset_cfg)\n\n    if database_save_path is None:\n        database_save_path = osp.join(data_path, f'{info_prefix}_gt_database')\n    if db_info_save_path is None:\n        db_info_save_path = osp.join(data_path,\n                                     f'{info_prefix}_dbinfos_train.pkl')\n    mmcv.mkdir_or_exist(database_save_path)\n    all_db_infos = dict()\n    if with_mask:\n        coco = COCO(osp.join(data_path, mask_anno_path))\n        imgIds = coco.getImgIds()\n        file2id = dict()\n        for i in imgIds:\n            info = coco.loadImgs([i])[0]\n            file2id.update({info['file_name']: i})\n\n    group_counter = 0\n    for j in track_iter_progress(list(range(len(dataset)))):\n        input_dict = dataset.get_data_info(j)\n        dataset.pre_pipeline(input_dict)\n        example = dataset.pipeline(input_dict)\n        annos = example['ann_info']\n        image_idx = example['sample_idx']\n        points = example['points'].tensor.numpy()\n        gt_boxes_3d = annos['gt_bboxes_3d'].tensor.numpy()\n        names = annos['gt_names']\n        group_dict = dict()\n        if 'group_ids' in annos:\n            group_ids = annos['group_ids']\n        else:\n            group_ids = np.arange(gt_boxes_3d.shape[0], dtype=np.int64)\n        difficulty = np.zeros(gt_boxes_3d.shape[0], dtype=np.int32)\n        if 'difficulty' in annos:\n            difficulty = annos['difficulty']\n\n        num_obj = gt_boxes_3d.shape[0]\n        point_indices = box_np_ops.points_in_rbbox(points, gt_boxes_3d)\n\n        if with_mask:\n            # prepare masks\n            gt_boxes = annos['gt_bboxes']\n            img_path = osp.split(example['img_info']['filename'])[-1]\n            if img_path not in file2id.keys():\n                print(f'skip image {img_path} for empty mask')\n                continue\n            img_id = file2id[img_path]\n            kins_annIds = coco.getAnnIds(imgIds=img_id)\n            kins_raw_info = coco.loadAnns(kins_annIds)\n            kins_ann_info = _parse_coco_ann_info(kins_raw_info)\n            h, w = annos['img_shape'][:2]\n            gt_masks = [\n                _poly2mask(mask, h, w) for mask in kins_ann_info['masks']\n            ]\n            # get mask inds based on iou mapping\n            bbox_iou = bbox_overlaps(kins_ann_info['bboxes'], gt_boxes)\n            mask_inds = bbox_iou.argmax(axis=0)\n            valid_inds = (bbox_iou.max(axis=0) > 0.5)\n\n            # mask the image\n            # use more precise crop when it is ready\n            # object_img_patches = np.ascontiguousarray(\n            #     np.stack(object_img_patches, axis=0).transpose(0, 3, 1, 2))\n            # crop image patches using roi_align\n            # object_img_patches = crop_image_patch_v2(\n            #     torch.Tensor(gt_boxes),\n            #     torch.Tensor(mask_inds).long(), object_img_patches)\n            object_img_patches, object_masks = crop_image_patch(\n                gt_boxes, gt_masks, mask_inds, annos['img'])\n\n        for i in range(num_obj):\n            filename = f'{image_idx}_{names[i]}_{i}.bin'\n            abs_filepath = osp.join(database_save_path, filename)\n            rel_filepath = osp.join(f'{info_prefix}_gt_database', filename)\n\n            # save point clouds and image patches for each object\n            gt_points = points[point_indices[:, i]]\n            gt_points[:, :3] -= gt_boxes_3d[i, :3]\n\n            if with_mask:\n                if object_masks[i].sum() == 0 or not valid_inds[i]:\n                    # Skip object for empty or invalid mask\n                    continue\n                img_patch_path = abs_filepath + '.png'\n                mask_patch_path = abs_filepath + '.mask.png'\n                mmcv.imwrite(object_img_patches[i], img_patch_path)\n                mmcv.imwrite(object_masks[i], mask_patch_path)\n\n            with open(abs_filepath, 'w') as f:\n                gt_points.tofile(f)\n\n            if (used_classes is None) or names[i] in used_classes:\n                db_info = {\n                    'name': names[i],\n                    'path': rel_filepath,\n                    'image_idx': image_idx,\n                    'gt_idx': i,\n                    'box3d_lidar': gt_boxes_3d[i],\n                    'num_points_in_gt': gt_points.shape[0],\n                    'difficulty': difficulty[i],\n                }\n                local_group_id = group_ids[i]\n                # if local_group_id >= 0:\n                if local_group_id not in group_dict:\n                    group_dict[local_group_id] = group_counter\n                    group_counter += 1\n                db_info['group_id'] = group_dict[local_group_id]\n                if 'score' in annos:\n                    db_info['score'] = annos['score'][i]\n                if with_mask:\n                    db_info.update({'box2d_camera': gt_boxes[i]})\n                if names[i] in all_db_infos:\n                    all_db_infos[names[i]].append(db_info)\n                else:\n                    all_db_infos[names[i]] = [db_info]\n\n    for k, v in all_db_infos.items():\n        print(f'load {len(v)} {k} database infos')\n\n    with open(db_info_save_path, 'wb') as f:\n        pickle.dump(all_db_infos, f)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/indoor_converter.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport os\n\nfrom .s3dis_data_utils import S3DISData, S3DISSegData\nfrom .scannet_data_utils import ScanNetData, ScanNetSegData\nfrom .sunrgbd_data_utils import SUNRGBDData\n\n\ndef create_indoor_info_file(data_path,\n                            pkl_prefix='sunrgbd',\n                            save_path=None,\n                            use_v1=False,\n                            workers=4):\n    \"\"\"Create indoor information file.\n\n    Get information of the raw data and save it to the pkl file.\n\n    Args:\n        data_path (str): Path of the data.\n        pkl_prefix (str): Prefix of the pkl to be saved. Default: 'sunrgbd'.\n        save_path (str): Path of the pkl to be saved. Default: None.\n        use_v1 (bool): Whether to use v1. Default: False.\n        workers (int): Number of threads to be used. Default: 4.\n    \"\"\"\n    assert os.path.exists(data_path)\n    assert pkl_prefix in ['sunrgbd', 'scannet', 's3dis'], \\\n        f'unsupported indoor dataset {pkl_prefix}'\n    save_path = data_path if save_path is None else save_path\n    assert os.path.exists(save_path)\n\n    # generate infos for both detection and segmentation task\n    if pkl_prefix in ['sunrgbd', 'scannet']:\n        train_filename = os.path.join(save_path,\n                                      f'{pkl_prefix}_infos_train.pkl')\n        val_filename = os.path.join(save_path, f'{pkl_prefix}_infos_val.pkl')\n        if pkl_prefix == 'sunrgbd':\n            # SUN RGB-D has a train-val split\n            train_dataset = SUNRGBDData(\n                root_path=data_path, split='train', use_v1=use_v1)\n            val_dataset = SUNRGBDData(\n                root_path=data_path, split='val', use_v1=use_v1)\n        else:\n            # ScanNet has a train-val-test split\n            train_dataset = ScanNetData(root_path=data_path, split='train')\n            val_dataset = ScanNetData(root_path=data_path, split='val')\n            test_dataset = ScanNetData(root_path=data_path, split='test')\n            test_filename = os.path.join(save_path,\n                                         f'{pkl_prefix}_infos_test.pkl')\n\n        infos_train = train_dataset.get_infos(\n            num_workers=workers, has_label=True)\n        mmcv.dump(infos_train, train_filename, 'pkl')\n        print(f'{pkl_prefix} info train file is saved to {train_filename}')\n\n        infos_val = val_dataset.get_infos(num_workers=workers, has_label=True)\n        mmcv.dump(infos_val, val_filename, 'pkl')\n        print(f'{pkl_prefix} info val file is saved to {val_filename}')\n\n    if pkl_prefix == 'scannet':\n        infos_test = test_dataset.get_infos(\n            num_workers=workers, has_label=False)\n        mmcv.dump(infos_test, test_filename, 'pkl')\n        print(f'{pkl_prefix} info test file is saved to {test_filename}')\n\n    # generate infos for the semantic segmentation task\n    # e.g. re-sampled scene indexes and label weights\n    # scene indexes are used to re-sample rooms with different number of points\n    # label weights are used to balance classes with different number of points\n    if pkl_prefix == 'scannet':\n        # label weight computation function is adopted from\n        # https://github.com/charlesq34/pointnet2/blob/master/scannet/scannet_dataset.py#L24\n        train_dataset = ScanNetSegData(\n            data_root=data_path,\n            ann_file=train_filename,\n            split='train',\n            num_points=8192,\n            label_weight_func=lambda x: 1.0 / np.log(1.2 + x))\n        # TODO: do we need to generate on val set?\n        val_dataset = ScanNetSegData(\n            data_root=data_path,\n            ann_file=val_filename,\n            split='val',\n            num_points=8192,\n            label_weight_func=lambda x: 1.0 / np.log(1.2 + x))\n        # no need to generate for test set\n        train_dataset.get_seg_infos()\n        val_dataset.get_seg_infos()\n    elif pkl_prefix == 's3dis':\n        # S3DIS doesn't have a fixed train-val split\n        # it has 6 areas instead, so we generate info file for each of them\n        # in training, we will use dataset to wrap different areas\n        splits = [f'Area_{i}' for i in [1, 2, 3, 4, 5, 6]]\n        for split in splits:\n            dataset = S3DISData(root_path=data_path, split=split)\n            info = dataset.get_infos(num_workers=workers, has_label=True)\n            filename = os.path.join(save_path,\n                                    f'{pkl_prefix}_infos_{split}.pkl')\n            mmcv.dump(info, filename, 'pkl')\n            print(f'{pkl_prefix} info {split} file is saved to {filename}')\n            seg_dataset = S3DISSegData(\n                data_root=data_path,\n                ann_file=filename,\n                split=split,\n                num_points=4096,\n                label_weight_func=lambda x: 1.0 / np.log(1.2 + x))\n            seg_dataset.get_seg_infos()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/kitti_converter.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nfrom collections import OrderedDict\nfrom nuscenes.utils.geometry_utils import view_points\nfrom pathlib import Path\n\nfrom mmcv.core.bbox import box_np_ops\nfrom .kitti_data_utils import get_kitti_image_info, get_waymo_image_info\nfrom .nuscenes_converter import post_process_coords\n\nkitti_categories = ('Pedestrian', 'Cyclist', 'Car')\n\n\ndef convert_to_kitti_info_version2(info):\n    \"\"\"convert kitti info v1 to v2 if possible.\n\n    Args:\n        info (dict): Info of the input kitti data.\n            - image (dict): image info\n            - calib (dict): calibration info\n            - point_cloud (dict): point cloud info\n    \"\"\"\n    if 'image' not in info or 'calib' not in info or 'point_cloud' not in info:\n        info['image'] = {\n            'image_shape': info['img_shape'],\n            'image_idx': info['image_idx'],\n            'image_path': info['img_path'],\n        }\n        info['calib'] = {\n            'R0_rect': info['calib/R0_rect'],\n            'Tr_velo_to_cam': info['calib/Tr_velo_to_cam'],\n            'P2': info['calib/P2'],\n        }\n        info['point_cloud'] = {\n            'velodyne_path': info['velodyne_path'],\n        }\n\n\ndef _read_imageset_file(path):\n    with open(path, 'r') as f:\n        lines = f.readlines()\n    return [int(line) for line in lines]\n\n\ndef _calculate_num_points_in_gt(data_path,\n                                infos,\n                                relative_path,\n                                remove_outside=True,\n                                num_features=4):\n    for info in mmcv.track_iter_progress(infos):\n        pc_info = info['point_cloud']\n        image_info = info['image']\n        calib = info['calib']\n        if relative_path:\n            v_path = str(Path(data_path) / pc_info['velodyne_path'])\n        else:\n            v_path = pc_info['velodyne_path']\n        points_v = np.fromfile(\n            v_path, dtype=np.float32, count=-1).reshape([-1, num_features])\n        rect = calib['R0_rect']\n        Trv2c = calib['Tr_velo_to_cam']\n        P2 = calib['P2']\n        if remove_outside:\n            points_v = box_np_ops.remove_outside_points(\n                points_v, rect, Trv2c, P2, image_info['image_shape'])\n\n        # points_v = points_v[points_v[:, 0] > 0]\n        annos = info['annos']\n        num_obj = len([n for n in annos['name'] if n != 'DontCare'])\n        # annos = kitti.filter_kitti_anno(annos, ['DontCare'])\n        dims = annos['dimensions'][:num_obj]\n        loc = annos['location'][:num_obj]\n        rots = annos['rotation_y'][:num_obj]\n        gt_boxes_camera = np.concatenate([loc, dims, rots[..., np.newaxis]],\n                                         axis=1)\n        gt_boxes_lidar = box_np_ops.box_camera_to_lidar(\n            gt_boxes_camera, rect, Trv2c)\n        indices = box_np_ops.points_in_rbbox(points_v[:, :3], gt_boxes_lidar)\n        num_points_in_gt = indices.sum(0)\n        num_ignored = len(annos['dimensions']) - num_obj\n        num_points_in_gt = np.concatenate(\n            [num_points_in_gt, -np.ones([num_ignored])])\n        annos['num_points_in_gt'] = num_points_in_gt.astype(np.int32)\n\n\ndef create_kitti_info_file(data_path,\n                           pkl_prefix='kitti',\n                           save_path=None,\n                           relative_path=True):\n    \"\"\"Create info file of KITTI dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        data_path (str): Path of the data root.\n        pkl_prefix (str): Prefix of the info file to be generated.\n        save_path (str): Path to save the info file.\n        relative_path (bool): Whether to use relative path.\n    \"\"\"\n    imageset_folder = Path(data_path) / 'ImageSets'\n    train_img_ids = _read_imageset_file(str(imageset_folder / 'train.txt'))\n\n    val_img_ids = _read_imageset_file(str(imageset_folder / 'val.txt'))\n    test_img_ids = _read_imageset_file(str(imageset_folder / 'test.txt'))\n\n    print('Generate info. this may take several minutes.')\n    if save_path is None:\n        save_path = Path(data_path)\n    else:\n        save_path = Path(save_path)\n    kitti_infos_train = get_kitti_image_info(\n        data_path,\n        training=True,\n        velodyne=True,\n        calib=True,\n        image_ids=train_img_ids,\n        relative_path=relative_path)\n    _calculate_num_points_in_gt(data_path, kitti_infos_train, relative_path)\n    filename = save_path / f'{pkl_prefix}_infos_train.pkl'\n    print(f'Kitti info train file is saved to {filename}')\n    mmcv.dump(kitti_infos_train, filename)\n    kitti_infos_val = get_kitti_image_info(\n        data_path,\n        training=True,\n        velodyne=True,\n        calib=True,\n        image_ids=val_img_ids,\n        relative_path=relative_path)\n    _calculate_num_points_in_gt(data_path, kitti_infos_val, relative_path)\n    filename = save_path / f'{pkl_prefix}_infos_val.pkl'\n    print(f'Kitti info val file is saved to {filename}')\n    mmcv.dump(kitti_infos_val, filename)\n    filename = save_path / f'{pkl_prefix}_infos_trainval.pkl'\n    print(f'Kitti info trainval file is saved to {filename}')\n    mmcv.dump(kitti_infos_train + kitti_infos_val, filename)\n\n    kitti_infos_test = get_kitti_image_info(\n        data_path,\n        training=False,\n        label_info=False,\n        velodyne=True,\n        calib=True,\n        image_ids=test_img_ids,\n        relative_path=relative_path)\n    filename = save_path / f'{pkl_prefix}_infos_test.pkl'\n    print(f'Kitti info test file is saved to {filename}')\n    mmcv.dump(kitti_infos_test, filename)\n\n\ndef create_waymo_info_file(data_path,\n                           pkl_prefix='waymo',\n                           save_path=None,\n                           relative_path=True,\n                           max_sweeps=5):\n    \"\"\"Create info file of waymo dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        data_path (str): Path of the data root.\n        pkl_prefix (str): Prefix of the info file to be generated.\n        save_path (str | None): Path to save the info file.\n        relative_path (bool): Whether to use relative path.\n        max_sweeps (int): Max sweeps before the detection frame to be used.\n    \"\"\"\n    imageset_folder = Path(data_path) / 'ImageSets'\n    train_img_ids = _read_imageset_file(str(imageset_folder / 'train.txt'))\n    # val_img_ids = _read_imageset_file(str(imageset_folder / 'val.txt'))\n    # test_img_ids = _read_imageset_file(str(imageset_folder / 'test.txt'))\n    train_img_ids = [each for each in train_img_ids if each % 5 == 0]\n    print('Generate info. this may take several minutes.')\n    if save_path is None:\n        save_path = Path(data_path)\n    else:\n        save_path = Path(save_path)\n    waymo_infos_train = get_waymo_image_info(\n        data_path,\n        training=True,\n        velodyne=True,\n        calib=True,\n        pose=True,\n        image_ids=train_img_ids,\n        relative_path=relative_path,\n        max_sweeps=max_sweeps)\n    _calculate_num_points_in_gt(\n        data_path,\n        waymo_infos_train,\n        relative_path,\n        num_features=6,\n        remove_outside=False)\n    filename = save_path / f'{pkl_prefix}_infos_train.pkl'\n    print(f'Waymo info train file is saved to {filename}')\n    mmcv.dump(waymo_infos_train, filename)\n    #\n    # waymo_infos_val = get_waymo_image_info(\n    #     data_path,\n    #     training=True,\n    #     velodyne=True,\n    #     calib=True,\n    #     pose=True,\n    #     image_ids=val_img_ids,\n    #     relative_path=relative_path,\n    #     max_sweeps=max_sweeps)\n    # _calculate_num_points_in_gt(\n    #     data_path,\n    #     waymo_infos_val,\n    #     relative_path,\n    #     num_features=6,\n    #     remove_outside=False)\n    # filename = save_path / f'{pkl_prefix}_infos_val.pkl'\n    # print(f'Waymo info val file is saved to {filename}')\n    # mmcv.dump(waymo_infos_val, filename)\n    # filename = save_path / f'{pkl_prefix}_infos_trainval.pkl'\n    # print(f'Waymo info trainval file is saved to {filename}')\n    # mmcv.dump(waymo_infos_train + waymo_infos_val, filename)\n    # waymo_infos_test = get_waymo_image_info(\n    #     data_path,\n    #     training=False,\n    #     label_info=False,\n    #     velodyne=True,\n    #     calib=True,\n    #     pose=True,\n    #     image_ids=test_img_ids,\n    #     relative_path=relative_path,\n    #     max_sweeps=max_sweeps)\n    # filename = save_path / f'{pkl_prefix}_infos_test.pkl'\n    # print(f'Waymo info test file is saved to {filename}')\n    # mmcv.dump(waymo_infos_test, filename)\n\n\ndef _create_reduced_point_cloud(data_path,\n                                info_path,\n                                save_path=None,\n                                back=False,\n                                num_features=4,\n                                front_camera_id=2):\n    \"\"\"Create reduced point clouds for given info.\n\n    Args:\n        data_path (str): Path of original data.\n        info_path (str): Path of data info.\n        save_path (str | None): Path to save reduced point cloud data.\n            Default: None.\n        back (bool): Whether to flip the points to back.\n        num_features (int): Number of point features. Default: 4.\n        front_camera_id (int): The referenced/front camera ID. Default: 2.\n    \"\"\"\n    kitti_infos = mmcv.load(info_path)\n\n    for info in mmcv.track_iter_progress(kitti_infos):\n        pc_info = info['point_cloud']\n        image_info = info['image']\n        calib = info['calib']\n\n        v_path = pc_info['velodyne_path']\n        v_path = Path(data_path) / v_path\n        points_v = np.fromfile(\n            str(v_path), dtype=np.float32,\n            count=-1).reshape([-1, num_features])\n        rect = calib['R0_rect']\n        if front_camera_id == 2:\n            P2 = calib['P2']\n        else:\n            P2 = calib[f'P{str(front_camera_id)}']\n        Trv2c = calib['Tr_velo_to_cam']\n        # first remove z < 0 points\n        # keep = points_v[:, -1] > 0\n        # points_v = points_v[keep]\n        # then remove outside.\n        if back:\n            points_v[:, 0] = -points_v[:, 0]\n        points_v = box_np_ops.remove_outside_points(points_v, rect, Trv2c, P2,\n                                                    image_info['image_shape'])\n        if save_path is None:\n            save_dir = v_path.parent.parent / (v_path.parent.stem + '_reduced')\n            if not save_dir.exists():\n                save_dir.mkdir()\n            save_filename = save_dir / v_path.name\n            # save_filename = str(v_path) + '_reduced'\n            if back:\n                save_filename += '_back'\n        else:\n            save_filename = str(Path(save_path) / v_path.name)\n            if back:\n                save_filename += '_back'\n        with open(save_filename, 'w') as f:\n            points_v.tofile(f)\n\n\ndef create_reduced_point_cloud(data_path,\n                               pkl_prefix,\n                               train_info_path=None,\n                               val_info_path=None,\n                               test_info_path=None,\n                               save_path=None,\n                               with_back=False):\n    \"\"\"Create reduced point clouds for training/validation/testing.\n\n    Args:\n        data_path (str): Path of original data.\n        pkl_prefix (str): Prefix of info files.\n        train_info_path (str | None): Path of training set info.\n            Default: None.\n        val_info_path (str | None): Path of validation set info.\n            Default: None.\n        test_info_path (str | None): Path of test set info.\n            Default: None.\n        save_path (str | None): Path to save reduced point cloud data.\n        with_back (bool): Whether to flip the points to back.\n    \"\"\"\n    if train_info_path is None:\n        train_info_path = Path(data_path) / f'{pkl_prefix}_infos_train.pkl'\n    if val_info_path is None:\n        val_info_path = Path(data_path) / f'{pkl_prefix}_infos_val.pkl'\n    if test_info_path is None:\n        test_info_path = Path(data_path) / f'{pkl_prefix}_infos_test.pkl'\n\n    print('create reduced point cloud for training set')\n    _create_reduced_point_cloud(data_path, train_info_path, save_path)\n    print('create reduced point cloud for validation set')\n    _create_reduced_point_cloud(data_path, val_info_path, save_path)\n    print('create reduced point cloud for testing set')\n    _create_reduced_point_cloud(data_path, test_info_path, save_path)\n    if with_back:\n        _create_reduced_point_cloud(\n            data_path, train_info_path, save_path, back=True)\n        _create_reduced_point_cloud(\n            data_path, val_info_path, save_path, back=True)\n        _create_reduced_point_cloud(\n            data_path, test_info_path, save_path, back=True)\n\n\ndef export_2d_annotation(root_path, info_path, mono3d=True):\n    \"\"\"Export 2d annotation from the info file and raw data.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        info_path (str): Path of the info file.\n        mono3d (bool): Whether to export mono3d annotation. Default: True.\n    \"\"\"\n    # get bbox annotations for camera\n    kitti_infos = mmcv.load(info_path)\n    cat2Ids = [\n        dict(id=kitti_categories.index(cat_name), name=cat_name)\n        for cat_name in kitti_categories\n    ]\n    coco_ann_id = 0\n    coco_2d_dict = dict(annotations=[], images=[], categories=cat2Ids)\n    from os import path as osp\n    for info in mmcv.track_iter_progress(kitti_infos):\n        coco_infos = get_2d_boxes(info, occluded=[0, 1, 2, 3], mono3d=mono3d)\n        (height, width,\n         _) = mmcv.imread(osp.join(root_path,\n                                   info['image']['image_path'])).shape\n        coco_2d_dict['images'].append(\n            dict(\n                file_name=info['image']['image_path'],\n                id=info['image']['image_idx'],\n                Tri2v=info['calib']['Tr_imu_to_velo'],\n                Trv2c=info['calib']['Tr_velo_to_cam'],\n                rect=info['calib']['R0_rect'],\n                cam_intrinsic=info['calib']['P2'],\n                width=width,\n                height=height))\n        for coco_info in coco_infos:\n            if coco_info is None:\n                continue\n            # add an empty key for coco format\n            coco_info['segmentation'] = []\n            coco_info['id'] = coco_ann_id\n            coco_2d_dict['annotations'].append(coco_info)\n            coco_ann_id += 1\n    if mono3d:\n        json_prefix = f'{info_path[:-4]}_mono3d'\n    else:\n        json_prefix = f'{info_path[:-4]}'\n    mmcv.dump(coco_2d_dict, f'{json_prefix}.coco.json')\n\n\ndef get_2d_boxes(info, occluded, mono3d=True):\n    \"\"\"Get the 2D annotation records for a given info.\n\n    Args:\n        info: Information of the given sample data.\n        occluded: Integer (0, 1, 2, 3) indicating occlusion state: \\\n            0 = fully visible, 1 = partly occluded, 2 = largely occluded, \\\n            3 = unknown, -1 = DontCare\n        mono3d (bool): Whether to get boxes with mono3d annotation.\n\n    Return:\n        list[dict]: List of 2D annotation record that belongs to the input\n            `sample_data_token`.\n    \"\"\"\n    # Get calibration information\n    P2 = info['calib']['P2']\n\n    repro_recs = []\n    # if no annotations in info (test dataset), then return\n    if 'annos' not in info:\n        return repro_recs\n\n    # Get all the annotation with the specified visibilties.\n    ann_dicts = info['annos']\n    mask = [(ocld in occluded) for ocld in ann_dicts['occluded']]\n    for k in ann_dicts.keys():\n        ann_dicts[k] = ann_dicts[k][mask]\n\n    # convert dict of list to list of dict\n    ann_recs = []\n    for i in range(len(ann_dicts['occluded'])):\n        ann_rec = {}\n        for k in ann_dicts.keys():\n            ann_rec[k] = ann_dicts[k][i]\n        ann_recs.append(ann_rec)\n\n    for ann_idx, ann_rec in enumerate(ann_recs):\n        # Augment sample_annotation with token information.\n        ann_rec['sample_annotation_token'] = \\\n            f\"{info['image']['image_idx']}.{ann_idx}\"\n        ann_rec['sample_data_token'] = info['image']['image_idx']\n        sample_data_token = info['image']['image_idx']\n\n        loc = ann_rec['location'][np.newaxis, :]\n        dim = ann_rec['dimensions'][np.newaxis, :]\n        rot = ann_rec['rotation_y'][np.newaxis, np.newaxis]\n        # transform the center from [0.5, 1.0, 0.5] to [0.5, 0.5, 0.5]\n        dst = np.array([0.5, 0.5, 0.5])\n        src = np.array([0.5, 1.0, 0.5])\n        loc = loc + dim * (dst - src)\n        offset = (info['calib']['P2'][0, 3] - info['calib']['P0'][0, 3]) \\\n            / info['calib']['P2'][0, 0]\n        loc_3d = np.copy(loc)\n        loc_3d[0, 0] += offset\n        gt_bbox_3d = np.concatenate([loc, dim, rot], axis=1).astype(np.float32)\n\n        # Filter out the corners that are not in front of the calibrated\n        # sensor.\n        corners_3d = box_np_ops.center_to_corner_box3d(\n            gt_bbox_3d[:, :3],\n            gt_bbox_3d[:, 3:6],\n            gt_bbox_3d[:, 6], [0.5, 0.5, 0.5],\n            axis=1)\n        corners_3d = corners_3d[0].T  # (1, 8, 3) -> (3, 8)\n        in_front = np.argwhere(corners_3d[2, :] > 0).flatten()\n        corners_3d = corners_3d[:, in_front]\n\n        # Project 3d box to 2d.\n        camera_intrinsic = P2\n        corner_coords = view_points(corners_3d, camera_intrinsic,\n                                    True).T[:, :2].tolist()\n\n        # Keep only corners that fall within the image.\n        final_coords = post_process_coords(corner_coords)\n\n        # Skip if the convex hull of the re-projected corners\n        # does not intersect the image canvas.\n        if final_coords is None:\n            continue\n        else:\n            min_x, min_y, max_x, max_y = final_coords\n\n        # Generate dictionary record to be included in the .json file.\n        repro_rec = generate_record(ann_rec, min_x, min_y, max_x, max_y,\n                                    sample_data_token,\n                                    info['image']['image_path'])\n\n        # If mono3d=True, add 3D annotations in camera coordinates\n        if mono3d and (repro_rec is not None):\n            repro_rec['bbox_cam3d'] = np.concatenate(\n                [loc_3d, dim, rot],\n                axis=1).astype(np.float32).squeeze().tolist()\n            repro_rec['velo_cam3d'] = -1  # no velocity in KITTI\n\n            center3d = np.array(loc).reshape([1, 3])\n            center2d = box_np_ops.points_cam2img(\n                center3d, camera_intrinsic, with_depth=True)\n            repro_rec['center2d'] = center2d.squeeze().tolist()\n            # normalized center2D + depth\n            # samples with depth < 0 will be removed\n            if repro_rec['center2d'][2] <= 0:\n                continue\n\n            repro_rec['attribute_name'] = -1  # no attribute in KITTI\n            repro_rec['attribute_id'] = -1\n\n        repro_recs.append(repro_rec)\n\n    return repro_recs\n\n\ndef generate_record(ann_rec, x1, y1, x2, y2, sample_data_token, filename):\n    \"\"\"Generate one 2D annotation record given various informations on top of\n    the 2D bounding box coordinates.\n\n    Args:\n        ann_rec (dict): Original 3d annotation record.\n        x1 (float): Minimum value of the x coordinate.\n        y1 (float): Minimum value of the y coordinate.\n        x2 (float): Maximum value of the x coordinate.\n        y2 (float): Maximum value of the y coordinate.\n        sample_data_token (str): Sample data token.\n        filename (str):The corresponding image file where the annotation\n            is present.\n\n    Returns:\n        dict: A sample 2D annotation record.\n            - file_name (str): flie name\n            - image_id (str): sample data token\n            - area (float): 2d box area\n            - category_name (str): category name\n            - category_id (int): category id\n            - bbox (list[float]): left x, top y, dx, dy of 2d box\n            - iscrowd (int): whether the area is crowd\n    \"\"\"\n    repro_rec = OrderedDict()\n    repro_rec['sample_data_token'] = sample_data_token\n    coco_rec = dict()\n\n    key_mapping = {\n        'name': 'category_name',\n        'num_points_in_gt': 'num_lidar_pts',\n        'sample_annotation_token': 'sample_annotation_token',\n        'sample_data_token': 'sample_data_token',\n    }\n\n    for key, value in ann_rec.items():\n        if key in key_mapping.keys():\n            repro_rec[key_mapping[key]] = value\n\n    repro_rec['bbox_corners'] = [x1, y1, x2, y2]\n    repro_rec['filename'] = filename\n\n    coco_rec['file_name'] = filename\n    coco_rec['image_id'] = sample_data_token\n    coco_rec['area'] = (y2 - y1) * (x2 - x1)\n\n    if repro_rec['category_name'] not in kitti_categories:\n        return None\n    cat_name = repro_rec['category_name']\n    coco_rec['category_name'] = cat_name\n    coco_rec['category_id'] = kitti_categories.index(cat_name)\n    coco_rec['bbox'] = [x1, y1, x2 - x1, y2 - y1]\n    coco_rec['iscrowd'] = 0\n\n    return coco_rec\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/kitti_data_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom collections import OrderedDict\nfrom concurrent import futures as futures\nfrom os import path as osp\nfrom pathlib import Path\nfrom skimage import io\n\n\ndef get_image_index_str(img_idx, use_prefix_id=False):\n    if use_prefix_id:\n        return '{:07d}'.format(img_idx)\n    else:\n        return '{:06d}'.format(img_idx)\n\n\ndef get_kitti_info_path(idx,\n                        prefix,\n                        info_type='image_2',\n                        file_tail='.png',\n                        training=True,\n                        relative_path=True,\n                        exist_check=True,\n                        use_prefix_id=False):\n    img_idx_str = get_image_index_str(idx, use_prefix_id)\n    img_idx_str += file_tail\n    prefix = Path(prefix)\n    if training:\n        file_path = Path('training') / info_type / img_idx_str\n    else:\n        file_path = Path('testing') / info_type / img_idx_str\n    if exist_check and not (prefix / file_path).exists():\n        raise ValueError('file not exist: {}'.format(file_path))\n    if relative_path:\n        return str(file_path)\n    else:\n        return str(prefix / file_path)\n\n\ndef get_image_path(idx,\n                   prefix,\n                   training=True,\n                   relative_path=True,\n                   exist_check=True,\n                   info_type='image_2',\n                   use_prefix_id=False):\n    return get_kitti_info_path(idx, prefix, info_type, '.png', training,\n                               relative_path, exist_check, use_prefix_id)\n\n\ndef get_label_path(idx,\n                   prefix,\n                   training=True,\n                   relative_path=True,\n                   exist_check=True,\n                   info_type='label_2',\n                   use_prefix_id=False):\n    return get_kitti_info_path(idx, prefix, info_type, '.txt', training,\n                               relative_path, exist_check, use_prefix_id)\n\n\ndef get_velodyne_path(idx,\n                      prefix,\n                      training=True,\n                      relative_path=True,\n                      exist_check=True,\n                      use_prefix_id=False):\n    return get_kitti_info_path(idx, prefix, 'velodyne', '.bin', training,\n                               relative_path, exist_check, use_prefix_id)\n\n\ndef get_calib_path(idx,\n                   prefix,\n                   training=True,\n                   relative_path=True,\n                   exist_check=True,\n                   use_prefix_id=False):\n    return get_kitti_info_path(idx, prefix, 'calib', '.txt', training,\n                               relative_path, exist_check, use_prefix_id)\n\n\ndef get_pose_path(idx,\n                  prefix,\n                  training=True,\n                  relative_path=True,\n                  exist_check=True,\n                  use_prefix_id=False):\n    return get_kitti_info_path(idx, prefix, 'pose', '.txt', training,\n                               relative_path, exist_check, use_prefix_id)\n\n\ndef get_label_anno(label_path):\n    annotations = {}\n    annotations.update({\n        'name': [],\n        'truncated': [],\n        'occluded': [],\n        'alpha': [],\n        'bbox': [],\n        'dimensions': [],\n        'location': [],\n        'rotation_y': []\n    })\n    with open(label_path, 'r') as f:\n        lines = f.readlines()\n    # if len(lines) == 0 or len(lines[0]) < 15:\n    #     content = []\n    # else:\n    content = [line.strip().split(' ') for line in lines]\n    num_objects = len([x[0] for x in content if x[0] != 'DontCare'])\n    annotations['name'] = np.array([x[0] for x in content])\n    num_gt = len(annotations['name'])\n    annotations['truncated'] = np.array([float(x[1]) for x in content])\n    annotations['occluded'] = np.array([int(x[2]) for x in content])\n    annotations['alpha'] = np.array([float(x[3]) for x in content])\n    annotations['bbox'] = np.array([[float(info) for info in x[4:8]]\n                                    for x in content]).reshape(-1, 4)\n    # dimensions will convert hwl format to standard lhw(camera) format.\n    annotations['dimensions'] = np.array([[float(info) for info in x[8:11]]\n                                          for x in content\n                                          ]).reshape(-1, 3)[:, [2, 0, 1]]\n    annotations['location'] = np.array([[float(info) for info in x[11:14]]\n                                        for x in content]).reshape(-1, 3)\n    annotations['rotation_y'] = np.array([float(x[14])\n                                          for x in content]).reshape(-1)\n    if len(content) != 0 and len(content[0]) == 16:  # have score\n        annotations['score'] = np.array([float(x[15]) for x in content])\n    else:\n        annotations['score'] = np.zeros((annotations['bbox'].shape[0], ))\n    index = list(range(num_objects)) + [-1] * (num_gt - num_objects)\n    annotations['index'] = np.array(index, dtype=np.int32)\n    annotations['group_ids'] = np.arange(num_gt, dtype=np.int32)\n    return annotations\n\n\ndef _extend_matrix(mat):\n    mat = np.concatenate([mat, np.array([[0., 0., 0., 1.]])], axis=0)\n    return mat\n\n\ndef get_kitti_image_info(path,\n                         training=True,\n                         label_info=True,\n                         velodyne=False,\n                         calib=False,\n                         image_ids=7481,\n                         extend_matrix=True,\n                         num_worker=8,\n                         relative_path=True,\n                         with_imageshape=True):\n    \"\"\"\n    KITTI annotation format version 2:\n    {\n        [optional]points: [N, 3+] point cloud\n        [optional, for kitti]image: {\n            image_idx: ...\n            image_path: ...\n            image_shape: ...\n        }\n        point_cloud: {\n            num_features: 4\n            velodyne_path: ...\n        }\n        [optional, for kitti]calib: {\n            R0_rect: ...\n            Tr_velo_to_cam: ...\n            P2: ...\n        }\n        annos: {\n            location: [num_gt, 3] array\n            dimensions: [num_gt, 3] array\n            rotation_y: [num_gt] angle array\n            name: [num_gt] ground truth name array\n            [optional]difficulty: kitti difficulty\n            [optional]group_ids: used for multi-part object\n        }\n    }\n    \"\"\"\n    root_path = Path(path)\n    if not isinstance(image_ids, list):\n        image_ids = list(range(image_ids))\n\n    def map_func(idx):\n        info = {}\n        pc_info = {'num_features': 4}\n        calib_info = {}\n\n        image_info = {'image_idx': idx}\n        annotations = None\n        if velodyne:\n            pc_info['velodyne_path'] = get_velodyne_path(\n                idx, path, training, relative_path)\n        image_info['image_path'] = get_image_path(idx, path, training,\n                                                  relative_path)\n        if with_imageshape:\n            img_path = image_info['image_path']\n            if relative_path:\n                img_path = str(root_path / img_path)\n            image_info['image_shape'] = np.array(\n                io.imread(img_path).shape[:2], dtype=np.int32)\n        if label_info:\n            label_path = get_label_path(idx, path, training, relative_path)\n            if relative_path:\n                label_path = str(root_path / label_path)\n            annotations = get_label_anno(label_path)\n        info['image'] = image_info\n        info['point_cloud'] = pc_info\n        if calib:\n            calib_path = get_calib_path(\n                idx, path, training, relative_path=False)\n            with open(calib_path, 'r') as f:\n                lines = f.readlines()\n            P0 = np.array([float(info) for info in lines[0].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P1 = np.array([float(info) for info in lines[1].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P2 = np.array([float(info) for info in lines[2].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P3 = np.array([float(info) for info in lines[3].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            if extend_matrix:\n                P0 = _extend_matrix(P0)\n                P1 = _extend_matrix(P1)\n                P2 = _extend_matrix(P2)\n                P3 = _extend_matrix(P3)\n            R0_rect = np.array([\n                float(info) for info in lines[4].split(' ')[1:10]\n            ]).reshape([3, 3])\n            if extend_matrix:\n                rect_4x4 = np.zeros([4, 4], dtype=R0_rect.dtype)\n                rect_4x4[3, 3] = 1.\n                rect_4x4[:3, :3] = R0_rect\n            else:\n                rect_4x4 = R0_rect\n\n            Tr_velo_to_cam = np.array([\n                float(info) for info in lines[5].split(' ')[1:13]\n            ]).reshape([3, 4])\n            Tr_imu_to_velo = np.array([\n                float(info) for info in lines[6].split(' ')[1:13]\n            ]).reshape([3, 4])\n            if extend_matrix:\n                Tr_velo_to_cam = _extend_matrix(Tr_velo_to_cam)\n                Tr_imu_to_velo = _extend_matrix(Tr_imu_to_velo)\n            calib_info['P0'] = P0\n            calib_info['P1'] = P1\n            calib_info['P2'] = P2\n            calib_info['P3'] = P3\n            calib_info['R0_rect'] = rect_4x4\n            calib_info['Tr_velo_to_cam'] = Tr_velo_to_cam\n            calib_info['Tr_imu_to_velo'] = Tr_imu_to_velo\n            info['calib'] = calib_info\n\n        if annotations is not None:\n            info['annos'] = annotations\n            add_difficulty_to_annos(info)\n        return info\n\n    with futures.ThreadPoolExecutor(num_worker) as executor:\n        image_infos = executor.map(map_func, image_ids)\n\n    return list(image_infos)\n\n\ndef get_waymo_image_info(path,\n                         training=True,\n                         label_info=True,\n                         velodyne=False,\n                         calib=False,\n                         pose=False,\n                         image_ids=7481,\n                         extend_matrix=True,\n                         num_worker=8,\n                         relative_path=True,\n                         with_imageshape=True,\n                         max_sweeps=5):\n    \"\"\"\n    Waymo annotation format version like KITTI:\n    {\n        [optional]points: [N, 3+] point cloud\n        [optional, for kitti]image: {\n            image_idx: ...\n            image_path: ...\n            image_shape: ...\n        }\n        point_cloud: {\n            num_features: 6\n            velodyne_path: ...\n        }\n        [optional, for kitti]calib: {\n            R0_rect: ...\n            Tr_velo_to_cam0: ...\n            P0: ...\n        }\n        annos: {\n            location: [num_gt, 3] array\n            dimensions: [num_gt, 3] array\n            rotation_y: [num_gt] angle array\n            name: [num_gt] ground truth name array\n            [optional]difficulty: kitti difficulty\n            [optional]group_ids: used for multi-part object\n        }\n    }\n    \"\"\"\n    root_path = Path(path)\n    if not isinstance(image_ids, list):\n        image_ids = list(range(image_ids))\n\n    def map_func(idx):\n        info = {}\n        pc_info = {'num_features': 6}\n        calib_info = {}\n\n        image_info = {'image_idx': idx}\n        annotations = None\n        if velodyne:\n            pc_info['velodyne_path'] = get_velodyne_path(\n                idx, path, training, relative_path, use_prefix_id=True)\n            points = np.fromfile(\n                Path(path) / pc_info['velodyne_path'], dtype=np.float32)\n            points = np.copy(points).reshape(-1, pc_info['num_features'])\n            info['timestamp'] = np.int64(points[0, -1])\n            # values of the last dim are all the timestamp\n        image_info['image_path'] = get_image_path(\n            idx,\n            path,\n            training,\n            relative_path,\n            info_type='image_0',\n            use_prefix_id=True)\n        if with_imageshape:\n            img_path = image_info['image_path']\n            if relative_path:\n                img_path = str(root_path / img_path)\n            image_info['image_shape'] = np.array(\n                io.imread(img_path).shape[:2], dtype=np.int32)\n        if label_info:\n            label_path = get_label_path(\n                idx,\n                path,\n                training,\n                relative_path,\n                info_type='label_all',\n                use_prefix_id=True)\n            if relative_path:\n                label_path = str(root_path / label_path)\n            annotations = get_label_anno(label_path)\n        info['image'] = image_info\n        info['point_cloud'] = pc_info\n        if calib:\n            calib_path = get_calib_path(\n                idx, path, training, relative_path=False, use_prefix_id=True)\n            with open(calib_path, 'r') as f:\n                lines = f.readlines()\n            P0 = np.array([float(info) for info in lines[0].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P1 = np.array([float(info) for info in lines[1].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P2 = np.array([float(info) for info in lines[2].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P3 = np.array([float(info) for info in lines[3].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            P4 = np.array([float(info) for info in lines[4].split(' ')[1:13]\n                           ]).reshape([3, 4])\n            if extend_matrix:\n                P0 = _extend_matrix(P0)\n                P1 = _extend_matrix(P1)\n                P2 = _extend_matrix(P2)\n                P3 = _extend_matrix(P3)\n                P4 = _extend_matrix(P4)\n            R0_rect = np.array([\n                float(info) for info in lines[5].split(' ')[1:10]\n            ]).reshape([3, 3])\n            if extend_matrix:\n                rect_4x4 = np.zeros([4, 4], dtype=R0_rect.dtype)\n                rect_4x4[3, 3] = 1.\n                rect_4x4[:3, :3] = R0_rect\n            else:\n                rect_4x4 = R0_rect\n\n            Tr_velo_to_cam = np.array([\n                float(info) for info in lines[6].split(' ')[1:13]\n            ]).reshape([3, 4])\n            if extend_matrix:\n                Tr_velo_to_cam = _extend_matrix(Tr_velo_to_cam)\n            calib_info['P0'] = P0\n            calib_info['P1'] = P1\n            calib_info['P2'] = P2\n            calib_info['P3'] = P3\n            calib_info['P4'] = P4\n            calib_info['R0_rect'] = rect_4x4\n            calib_info['Tr_velo_to_cam'] = Tr_velo_to_cam\n            info['calib'] = calib_info\n        if pose:\n            pose_path = get_pose_path(\n                idx, path, training, relative_path=False, use_prefix_id=True)\n            info['pose'] = np.loadtxt(pose_path)\n\n        if annotations is not None:\n            info['annos'] = annotations\n            info['annos']['camera_id'] = info['annos'].pop('score')\n            add_difficulty_to_annos(info)\n\n        sweeps = []\n        prev_idx = idx\n        while len(sweeps) < max_sweeps:\n            prev_info = {}\n            prev_idx -= 1\n            prev_info['velodyne_path'] = get_velodyne_path(\n                prev_idx,\n                path,\n                training,\n                relative_path,\n                exist_check=False,\n                use_prefix_id=True)\n            if_prev_exists = osp.exists(\n                Path(path) / prev_info['velodyne_path'])\n            if if_prev_exists:\n                prev_points = np.fromfile(\n                    Path(path) / prev_info['velodyne_path'], dtype=np.float32)\n                prev_points = np.copy(prev_points).reshape(\n                    -1, pc_info['num_features'])\n                prev_info['timestamp'] = np.int64(prev_points[0, -1])\n                prev_pose_path = get_pose_path(\n                    prev_idx,\n                    path,\n                    training,\n                    relative_path=False,\n                    use_prefix_id=True)\n                prev_info['pose'] = np.loadtxt(prev_pose_path)\n                sweeps.append(prev_info)\n            else:\n                break\n        info['sweeps'] = sweeps\n\n        return info\n\n    with futures.ThreadPoolExecutor(num_worker) as executor:\n        image_infos = executor.map(map_func, image_ids)\n\n    return list(image_infos)\n\n\ndef kitti_anno_to_label_file(annos, folder):\n    folder = Path(folder)\n    for anno in annos:\n        image_idx = anno['metadata']['image_idx']\n        label_lines = []\n        for j in range(anno['bbox'].shape[0]):\n            label_dict = {\n                'name': anno['name'][j],\n                'alpha': anno['alpha'][j],\n                'bbox': anno['bbox'][j],\n                'location': anno['location'][j],\n                'dimensions': anno['dimensions'][j],\n                'rotation_y': anno['rotation_y'][j],\n                'score': anno['score'][j],\n            }\n            label_line = kitti_result_line(label_dict)\n            label_lines.append(label_line)\n        label_file = folder / f'{get_image_index_str(image_idx)}.txt'\n        label_str = '\\n'.join(label_lines)\n        with open(label_file, 'w') as f:\n            f.write(label_str)\n\n\ndef add_difficulty_to_annos(info):\n    min_height = [40, 25,\n                  25]  # minimum height for evaluated groundtruth/detections\n    max_occlusion = [\n        0, 1, 2\n    ]  # maximum occlusion level of the groundtruth used for evaluation\n    max_trunc = [\n        0.15, 0.3, 0.5\n    ]  # maximum truncation level of the groundtruth used for evaluation\n    annos = info['annos']\n    dims = annos['dimensions']  # lhw format\n    bbox = annos['bbox']\n    height = bbox[:, 3] - bbox[:, 1]\n    occlusion = annos['occluded']\n    truncation = annos['truncated']\n    diff = []\n    easy_mask = np.ones((len(dims), ), dtype=np.bool)\n    moderate_mask = np.ones((len(dims), ), dtype=np.bool)\n    hard_mask = np.ones((len(dims), ), dtype=np.bool)\n    i = 0\n    for h, o, t in zip(height, occlusion, truncation):\n        if o > max_occlusion[0] or h <= min_height[0] or t > max_trunc[0]:\n            easy_mask[i] = False\n        if o > max_occlusion[1] or h <= min_height[1] or t > max_trunc[1]:\n            moderate_mask[i] = False\n        if o > max_occlusion[2] or h <= min_height[2] or t > max_trunc[2]:\n            hard_mask[i] = False\n        i += 1\n    is_easy = easy_mask\n    is_moderate = np.logical_xor(easy_mask, moderate_mask)\n    is_hard = np.logical_xor(hard_mask, moderate_mask)\n\n    for i in range(len(dims)):\n        if is_easy[i]:\n            diff.append(0)\n        elif is_moderate[i]:\n            diff.append(1)\n        elif is_hard[i]:\n            diff.append(2)\n        else:\n            diff.append(-1)\n    annos['difficulty'] = np.array(diff, np.int32)\n    return diff\n\n\ndef kitti_result_line(result_dict, precision=4):\n    prec_float = '{' + ':.{}f'.format(precision) + '}'\n    res_line = []\n    all_field_default = OrderedDict([\n        ('name', None),\n        ('truncated', -1),\n        ('occluded', -1),\n        ('alpha', -10),\n        ('bbox', None),\n        ('dimensions', [-1, -1, -1]),\n        ('location', [-1000, -1000, -1000]),\n        ('rotation_y', -10),\n        ('score', 0.0),\n    ])\n    res_dict = [(key, None) for key, val in all_field_default.items()]\n    res_dict = OrderedDict(res_dict)\n    for key, val in result_dict.items():\n        if all_field_default[key] is None and val is None:\n            raise ValueError('you must specify a value for {}'.format(key))\n        res_dict[key] = val\n\n    for key, val in res_dict.items():\n        if key == 'name':\n            res_line.append(val)\n        elif key in ['truncated', 'alpha', 'rotation_y', 'score']:\n            if val is None:\n                res_line.append(str(all_field_default[key]))\n            else:\n                res_line.append(prec_float.format(val))\n        elif key == 'occluded':\n            if val is None:\n                res_line.append(str(all_field_default[key]))\n            else:\n                res_line.append('{}'.format(val))\n        elif key in ['bbox', 'dimensions', 'location']:\n            if val is None:\n                res_line += [str(v) for v in all_field_default[key]]\n            else:\n                res_line += [prec_float.format(v) for v in val]\n        else:\n            raise ValueError('unknown key. supported key:{}'.format(\n                res_dict.keys()))\n    return ' '.join(res_line)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/lyft_converter.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport os\nfrom logging import warning\nfrom lyft_dataset_sdk.lyftdataset import LyftDataset as Lyft\nfrom os import path as osp\nfrom pyquaternion import Quaternion\n\nfrom mmcv.datasets import LyftDataset\nfrom .nuscenes_converter import (get_2d_boxes, get_available_scenes,\n                                 obtain_sensor2top)\n\nlyft_categories = ('car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle',\n                   'motorcycle', 'bicycle', 'pedestrian', 'animal')\n\n\ndef create_lyft_infos(root_path,\n                      info_prefix,\n                      version='v1.01-train',\n                      max_sweeps=10):\n    \"\"\"Create info file of lyft dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.01-train'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    lyft = Lyft(\n        data_path=osp.join(root_path, version),\n        json_path=osp.join(root_path, version, version),\n        verbose=True)\n    available_vers = ['v1.01-train', 'v1.01-test']\n    assert version in available_vers\n    if version == 'v1.01-train':\n        train_scenes = mmcv.list_from_file('data/lyft/train.txt')\n        val_scenes = mmcv.list_from_file('data/lyft/val.txt')\n    elif version == 'v1.01-test':\n        train_scenes = mmcv.list_from_file('data/lyft/test.txt')\n        val_scenes = []\n    else:\n        raise ValueError('unknown')\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(lyft)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print(f'test scene: {len(train_scenes)}')\n    else:\n        print(f'train scene: {len(train_scenes)}, \\\n                val scene: {len(val_scenes)}')\n    train_lyft_infos, val_lyft_infos = _fill_trainval_infos(\n        lyft, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print(f'test sample: {len(train_lyft_infos)}')\n        data = dict(infos=train_lyft_infos, metadata=metadata)\n        info_name = f'{info_prefix}_infos_test'\n        info_path = osp.join(root_path, f'{info_name}.pkl')\n        mmcv.dump(data, info_path)\n    else:\n        print(f'train sample: {len(train_lyft_infos)}, \\\n                val sample: {len(val_lyft_infos)}')\n        data = dict(infos=train_lyft_infos, metadata=metadata)\n        train_info_name = f'{info_prefix}_infos_train'\n        info_path = osp.join(root_path, f'{train_info_name}.pkl')\n        mmcv.dump(data, info_path)\n        data['infos'] = val_lyft_infos\n        val_info_name = f'{info_prefix}_infos_val'\n        info_val_path = osp.join(root_path, f'{val_info_name}.pkl')\n        mmcv.dump(data, info_val_path)\n\n\ndef _fill_trainval_infos(lyft,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        lyft (:obj:`LyftDataset`): Dataset class in the Lyft dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and\n            validation set that will be saved to the info file.\n    \"\"\"\n    train_lyft_infos = []\n    val_lyft_infos = []\n\n    for sample in mmcv.track_iter_progress(lyft.sample):\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = lyft.get('sample_data', sample['data']['LIDAR_TOP'])\n        cs_record = lyft.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = lyft.get('ego_pose', sd_rec['ego_pose_token'])\n        abs_lidar_path, boxes, _ = lyft.get_sample_data(lidar_token)\n        # nuScenes devkit returns more convenient relative paths while\n        # lyft devkit returns absolute paths\n        abs_lidar_path = str(abs_lidar_path)  # absolute path\n        lidar_path = abs_lidar_path.split(f'{os.getcwd()}/')[-1]\n        # relative path\n\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = lyft.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(lyft, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = lyft.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(lyft, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = lyft.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            annotations = [\n                lyft.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in LyftDataset.NameMapping:\n                    names[i] = LyftDataset.NameMapping[names[i]]\n            names = np.array(names)\n\n            # we need to convert rot to SECOND format.\n            gt_boxes = np.concatenate([locs, dims, -rots - np.pi / 2], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n\n        if sample['scene_token'] in train_scenes:\n            train_lyft_infos.append(info)\n        else:\n            val_lyft_infos.append(info)\n\n    return train_lyft_infos, val_lyft_infos\n\n\ndef export_2d_annotation(root_path, info_path, version):\n    \"\"\"Export 2d annotation from the info file and raw data.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        info_path (str): Path of the info file.\n        version (str): Dataset version.\n    \"\"\"\n    warning.warn('DeprecationWarning: 2D annotations are not used on the '\n                 'Lyft dataset. The function export_2d_annotation will be '\n                 'deprecated.')\n    # get bbox annotations for camera\n    camera_types = [\n        'CAM_FRONT',\n        'CAM_FRONT_RIGHT',\n        'CAM_FRONT_LEFT',\n        'CAM_BACK',\n        'CAM_BACK_LEFT',\n        'CAM_BACK_RIGHT',\n    ]\n    lyft_infos = mmcv.load(info_path)['infos']\n    lyft = Lyft(\n        data_path=osp.join(root_path, version),\n        json_path=osp.join(root_path, version, version),\n        verbose=True)\n    # info_2d_list = []\n    cat2Ids = [\n        dict(id=lyft_categories.index(cat_name), name=cat_name)\n        for cat_name in lyft_categories\n    ]\n    coco_ann_id = 0\n    coco_2d_dict = dict(annotations=[], images=[], categories=cat2Ids)\n    for info in mmcv.track_iter_progress(lyft_infos):\n        for cam in camera_types:\n            cam_info = info['cams'][cam]\n            coco_infos = get_2d_boxes(\n                lyft,\n                cam_info['sample_data_token'],\n                visibilities=['', '1', '2', '3', '4'])\n            (height, width, _) = mmcv.imread(cam_info['data_path']).shape\n            coco_2d_dict['images'].append(\n                dict(\n                    file_name=cam_info['data_path'],\n                    id=cam_info['sample_data_token'],\n                    width=width,\n                    height=height))\n            for coco_info in coco_infos:\n                if coco_info is None:\n                    continue\n                # add an empty key for coco format\n                coco_info['segmentation'] = []\n                coco_info['id'] = coco_ann_id\n                coco_2d_dict['annotations'].append(coco_info)\n                coco_ann_id += 1\n    mmcv.dump(coco_2d_dict, f'{info_path[:-4]}.coco.json')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/lyft_data_fixer.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport numpy as np\nimport os\n\n\ndef fix_lyft(root_folder='./data/lyft', version='v1.01'):\n    # refer to https://www.kaggle.com/c/3d-object-detection-for-autonomous-vehicles/discussion/110000  # noqa\n    lidar_path = 'lidar/host-a011_lidar1_1233090652702363606.bin'\n    root_folder = os.path.join(root_folder, f'{version}-train')\n    lidar_path = os.path.join(root_folder, lidar_path)\n    assert os.path.isfile(lidar_path), f'Please download the complete Lyft ' \\\n        f'dataset and make sure {lidar_path} is present.'\n    points = np.fromfile(lidar_path, dtype=np.float32, count=-1)\n    try:\n        points.reshape([-1, 5])\n        print(f'This fix is not required for version {version}.')\n    except ValueError:\n        new_points = np.array(list(points) + [100.0, 1.0], dtype='float32')\n        new_points.tofile(lidar_path)\n        print(f'Appended 100.0 and 1.0 to the end of {lidar_path}.')\n\n\nparser = argparse.ArgumentParser(description='Lyft dataset fixer arg parser')\nparser.add_argument(\n    '--root-folder',\n    type=str,\n    default='./data/lyft',\n    help='specify the root path of Lyft dataset')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.01',\n    help='specify Lyft dataset version')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    fix_lyft(root_folder=args.root_folder, version=args.version)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/nuimage_converter.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport base64\nimport mmcv\nimport numpy as np\nfrom nuimages import NuImages\nfrom nuimages.utils.utils import mask_decode, name_to_index_mapping\nfrom os import path as osp\n\nnus_categories = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',\n                  'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',\n                  'barrier')\n\nNAME_MAPPING = {\n    'movable_object.barrier': 'barrier',\n    'vehicle.bicycle': 'bicycle',\n    'vehicle.bus.bendy': 'bus',\n    'vehicle.bus.rigid': 'bus',\n    'vehicle.car': 'car',\n    'vehicle.construction': 'construction_vehicle',\n    'vehicle.motorcycle': 'motorcycle',\n    'human.pedestrian.adult': 'pedestrian',\n    'human.pedestrian.child': 'pedestrian',\n    'human.pedestrian.construction_worker': 'pedestrian',\n    'human.pedestrian.police_officer': 'pedestrian',\n    'movable_object.trafficcone': 'traffic_cone',\n    'vehicle.trailer': 'trailer',\n    'vehicle.truck': 'truck',\n}\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Data converter arg parser')\n    parser.add_argument(\n        '--data-root',\n        type=str,\n        default='./data/nuimages',\n        help='specify the root path of dataset')\n    parser.add_argument(\n        '--version',\n        type=str,\n        nargs='+',\n        default=['v1.0-mini'],\n        required=False,\n        help='specify the dataset version')\n    parser.add_argument(\n        '--out-dir',\n        type=str,\n        default='./data/nuimages/annotations/',\n        required=False,\n        help='path to save the exported json')\n    parser.add_argument(\n        '--nproc',\n        type=int,\n        default=4,\n        required=False,\n        help='workers to process semantic masks')\n    parser.add_argument('--extra-tag', type=str, default='nuimages')\n    args = parser.parse_args()\n    return args\n\n\ndef get_img_annos(nuim, img_info, cat2id, out_dir, data_root, seg_root):\n    \"\"\"Get semantic segmentation map for an image.\n\n    Args:\n        nuim (obj:`NuImages`): NuImages dataset object\n        img_info (dict): Meta information of img\n\n    Returns:\n        np.ndarray: Semantic segmentation map of the image\n    \"\"\"\n    sd_token = img_info['token']\n    image_id = img_info['id']\n    name_to_index = name_to_index_mapping(nuim.category)\n\n    # Get image data.\n    width, height = img_info['width'], img_info['height']\n    semseg_mask = np.zeros((height, width)).astype('uint8')\n\n    # Load stuff / surface regions.\n    surface_anns = [\n        o for o in nuim.surface_ann if o['sample_data_token'] == sd_token\n    ]\n\n    # Draw stuff / surface regions.\n    for ann in surface_anns:\n        # Get color and mask.\n        category_token = ann['category_token']\n        category_name = nuim.get('category', category_token)['name']\n        if ann['mask'] is None:\n            continue\n        mask = mask_decode(ann['mask'])\n\n        # Draw mask for semantic segmentation.\n        semseg_mask[mask == 1] = name_to_index[category_name]\n\n    # Load object instances.\n    object_anns = [\n        o for o in nuim.object_ann if o['sample_data_token'] == sd_token\n    ]\n\n    # Sort by token to ensure that objects always appear in the\n    # instance mask in the same order.\n    object_anns = sorted(object_anns, key=lambda k: k['token'])\n\n    # Draw object instances.\n    # The 0 index is reserved for background; thus, the instances\n    # should start from index 1.\n    annotations = []\n    for i, ann in enumerate(object_anns, start=1):\n        # Get color, box, mask and name.\n        category_token = ann['category_token']\n        category_name = nuim.get('category', category_token)['name']\n        if ann['mask'] is None:\n            continue\n        mask = mask_decode(ann['mask'])\n\n        # Draw masks for semantic segmentation and instance segmentation.\n        semseg_mask[mask == 1] = name_to_index[category_name]\n\n        if category_name in NAME_MAPPING:\n            cat_name = NAME_MAPPING[category_name]\n            cat_id = cat2id[cat_name]\n\n            x_min, y_min, x_max, y_max = ann['bbox']\n            # encode calibrated instance mask\n            mask_anno = dict()\n            mask_anno['counts'] = base64.b64decode(\n                ann['mask']['counts']).decode()\n            mask_anno['size'] = ann['mask']['size']\n\n            data_anno = dict(\n                image_id=image_id,\n                category_id=cat_id,\n                bbox=[x_min, y_min, x_max - x_min, y_max - y_min],\n                area=(x_max - x_min) * (y_max - y_min),\n                segmentation=mask_anno,\n                iscrowd=0)\n            annotations.append(data_anno)\n\n    # after process, save semantic masks\n    img_filename = img_info['file_name']\n    seg_filename = img_filename.replace('jpg', 'png')\n    seg_filename = osp.join(seg_root, seg_filename)\n    mmcv.imwrite(semseg_mask, seg_filename)\n    return annotations, np.max(semseg_mask)\n\n\ndef export_nuim_to_coco(nuim, data_root, out_dir, extra_tag, version, nproc):\n    print('Process category information')\n    categories = []\n    categories = [\n        dict(id=nus_categories.index(cat_name), name=cat_name)\n        for cat_name in nus_categories\n    ]\n    cat2id = {k_v['name']: k_v['id'] for k_v in categories}\n\n    images = []\n    print('Process image meta information...')\n    for sample_info in mmcv.track_iter_progress(nuim.sample_data):\n        if sample_info['is_key_frame']:\n            img_idx = len(images)\n            images.append(\n                dict(\n                    id=img_idx,\n                    token=sample_info['token'],\n                    file_name=sample_info['filename'],\n                    width=sample_info['width'],\n                    height=sample_info['height']))\n\n    seg_root = f'{out_dir}semantic_masks'\n    mmcv.mkdir_or_exist(seg_root)\n    mmcv.mkdir_or_exist(osp.join(data_root, 'calibrated'))\n\n    global process_img_anno\n\n    def process_img_anno(img_info):\n        single_img_annos, max_cls_id = get_img_annos(nuim, img_info, cat2id,\n                                                     out_dir, data_root,\n                                                     seg_root)\n        return single_img_annos, max_cls_id\n\n    print('Process img annotations...')\n    if nproc > 1:\n        outputs = mmcv.track_parallel_progress(\n            process_img_anno, images, nproc=nproc)\n    else:\n        outputs = []\n        for img_info in mmcv.track_iter_progress(images):\n            outputs.append(process_img_anno(img_info))\n\n    # Determine the index of object annotation\n    print('Process annotation information...')\n    annotations = []\n    max_cls_ids = []\n    for single_img_annos, max_cls_id in outputs:\n        max_cls_ids.append(max_cls_id)\n        for img_anno in single_img_annos:\n            img_anno.update(id=len(annotations))\n            annotations.append(img_anno)\n\n    max_cls_id = max(max_cls_ids)\n    print(f'Max ID of class in the semantic map: {max_cls_id}')\n\n    coco_format_json = dict(\n        images=images, annotations=annotations, categories=categories)\n\n    mmcv.mkdir_or_exist(out_dir)\n    out_file = osp.join(out_dir, f'{extra_tag}_{version}.json')\n    print(f'Annotation dumped to {out_file}')\n    mmcv.dump(coco_format_json, out_file)\n\n\ndef main():\n    args = parse_args()\n    for version in args.version:\n        nuim = NuImages(\n            dataroot=args.data_root, version=version, verbose=True, lazy=True)\n        export_nuim_to_coco(nuim, args.data_root, args.out_dir, args.extra_tag,\n                            version, args.nproc)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/nuscenes_converter.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport numpy as np\nimport os\nfrom collections import OrderedDict\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.utils.geometry_utils import view_points\nfrom os import path as osp\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\nfrom typing import List, Tuple, Union\n\nfrom mmcv.core.bbox.box_np_ops import points_cam2img\nfrom mmcv.datasets import NuScenesDataset\nfrom mmcv.fileio.io import dump, load\nfrom mmcv.image.io import imread\nfrom mmcv.utils import is_filepath, check_file_exist, track_iter_progress\n\nnus_categories = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',\n                  'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',\n                  'barrier')\n\nnus_attributes = ('cycle.with_rider', 'cycle.without_rider',\n                  'pedestrian.moving', 'pedestrian.standing',\n                  'pedestrian.sitting_lying_down', 'vehicle.moving',\n                  'vehicle.parked', 'vehicle.stopped', 'None')\n\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    from nuscenes.nuscenes import NuScenes\n    from nuscenes.can_bus.can_bus_api import NuScenesCanBus\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n    else:\n        raise ValueError('unknown')\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_temporal_test.pkl'.format(info_prefix))\n        dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_temporal_train.pkl'.format(info_prefix))\n        dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_temporal_val.pkl'.format(info_prefix))\n        dump(data, info_val_path)\n\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\n\ndef _get_can_bus_info(nusc, nusc_can_bus, sample):\n    scene_name = nusc.get('scene', sample['scene_token'])['name']\n    sample_timestamp = sample['timestamp']\n    try:\n        pose_list = nusc_can_bus.get_messages(scene_name, 'pose')\n    except:\n        return np.zeros(18)  # server scenes do not have can bus information.\n    can_bus = []\n    # during each scene, the first timestamp of can_bus may be large than the first sample's timestamp\n    last_pose = pose_list[0]\n    for i, pose in enumerate(pose_list):\n        if pose['utime'] > sample_timestamp:\n            break\n        last_pose = pose\n    _ = last_pose.pop('utime')  # useless\n    pos = last_pose.pop('pos')\n    rotation = last_pose.pop('orientation')\n    can_bus.extend(pos)\n    can_bus.extend(rotation)\n    for key in last_pose.keys():\n        can_bus.extend(pose[key])  # 16 elements\n    can_bus.extend([0., 0.])\n    return np.array(can_bus)\n\n\ndef _fill_trainval_infos(nusc,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    frame_idx = 0\n    for sample in track_iter_progress(nusc.sample):\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n\n        check_file_exist(lidar_path)\n        can_bus = _get_can_bus_info(nusc, nusc_can_bus, sample)\n        ##\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'prev': sample['prev'],\n            'next': sample['next'],\n            'can_bus': can_bus,\n            'frame_idx': frame_idx,  # temporal related info\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],  # temporal related info\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n        }\n\n        if sample['next'] == '':\n            frame_idx = 0\n        else:\n            frame_idx += 1\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NuScenesDataset.NameMapping:\n                    names[i] = NuScenesDataset.NameMapping[names[i]]\n            names = np.array(names)\n            # we need to convert rot to SECOND format.\n            gt_boxes = np.concatenate([locs, dims, -rots - np.pi / 2], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\n\ndef export_2d_annotation(root_path, info_path, version, mono3d=True):\n    \"\"\"Export 2d annotation from the info file and raw data.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        info_path (str): Path of the info file.\n        version (str): Dataset version.\n        mono3d (bool): Whether to export mono3d annotation. Default: True.\n    \"\"\"\n    # get bbox annotations for camera\n    camera_types = [\n        'CAM_FRONT',\n        'CAM_FRONT_RIGHT',\n        'CAM_FRONT_LEFT',\n        'CAM_BACK',\n        'CAM_BACK_LEFT',\n        'CAM_BACK_RIGHT',\n    ]\n    nusc_infos = load(info_path)['infos']\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    # info_2d_list = []\n    cat2Ids = [\n        dict(id=nus_categories.index(cat_name), name=cat_name)\n        for cat_name in nus_categories\n    ]\n    coco_ann_id = 0\n    coco_2d_dict = dict(annotations=[], images=[], categories=cat2Ids)\n    for info in track_iter_progress(nusc_infos):\n        for cam in camera_types:\n            cam_info = info['cams'][cam]\n            coco_infos = get_2d_boxes(\n                nusc,\n                cam_info['sample_data_token'],\n                visibilities=['', '1', '2', '3', '4'],\n                mono3d=mono3d)\n            (height, width, _) = imread(cam_info['data_path']).shape\n            coco_2d_dict['images'].append(\n                dict(\n                    file_name=cam_info['data_path'].split('data/nuscenes/')\n                    [-1],\n                    id=cam_info['sample_data_token'],\n                    token=info['token'],\n                    cam2ego_rotation=cam_info['sensor2ego_rotation'],\n                    cam2ego_translation=cam_info['sensor2ego_translation'],\n                    ego2global_rotation=info['ego2global_rotation'],\n                    ego2global_translation=info['ego2global_translation'],\n                    cam_intrinsic=cam_info['cam_intrinsic'],\n                    width=width,\n                    height=height))\n            for coco_info in coco_infos:\n                if coco_info is None:\n                    continue\n                # add an empty key for coco format\n                coco_info['segmentation'] = []\n                coco_info['id'] = coco_ann_id\n                coco_2d_dict['annotations'].append(coco_info)\n                coco_ann_id += 1\n    if mono3d:\n        json_prefix = f'{info_path[:-4]}_mono3d'\n    else:\n        json_prefix = f'{info_path[:-4]}'\n    dump(coco_2d_dict, f'{json_prefix}.coco.json')\n\n\ndef get_2d_boxes(nusc,\n                 sample_data_token: str,\n                 visibilities: List[str],\n                 mono3d=True):\n    \"\"\"Get the 2D annotation records for a given `sample_data_token`.\n\n    Args:\n        sample_data_token (str): Sample data token belonging to a camera \\\n            keyframe.\n        visibilities (list[str]): Visibility filter.\n        mono3d (bool): Whether to get boxes with mono3d annotation.\n\n    Return:\n        list[dict]: List of 2D annotation record that belongs to the input\n            `sample_data_token`.\n    \"\"\"\n\n    # Get the sample data and the sample corresponding to that sample data.\n    sd_rec = nusc.get('sample_data', sample_data_token)\n\n    assert sd_rec[\n        'sensor_modality'] == 'camera', 'Error: get_2d_boxes only works' \\\n        ' for camera sample_data!'\n    if not sd_rec['is_key_frame']:\n        raise ValueError(\n            'The 2D re-projections are available only for keyframes.')\n\n    s_rec = nusc.get('sample', sd_rec['sample_token'])\n\n    # Get the calibrated sensor and ego pose\n    # record to get the transformation matrices.\n    cs_rec = nusc.get('calibrated_sensor', sd_rec['calibrated_sensor_token'])\n    pose_rec = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    camera_intrinsic = np.array(cs_rec['camera_intrinsic'])\n\n    # Get all the annotation with the specified visibilties.\n    ann_recs = [\n        nusc.get('sample_annotation', token) for token in s_rec['anns']\n    ]\n    ann_recs = [\n        ann_rec for ann_rec in ann_recs\n        if (ann_rec['visibility_token'] in visibilities)\n    ]\n\n    repro_recs = []\n\n    for ann_rec in ann_recs:\n        # Augment sample_annotation with token information.\n        ann_rec['sample_annotation_token'] = ann_rec['token']\n        ann_rec['sample_data_token'] = sample_data_token\n\n        # Get the box in global coordinates.\n        box = nusc.get_box(ann_rec['token'])\n\n        # Move them to the ego-pose frame.\n        box.translate(-np.array(pose_rec['translation']))\n        box.rotate(Quaternion(pose_rec['rotation']).inverse)\n\n        # Move them to the calibrated sensor frame.\n        box.translate(-np.array(cs_rec['translation']))\n        box.rotate(Quaternion(cs_rec['rotation']).inverse)\n\n        # Filter out the corners that are not in front of the calibrated\n        # sensor.\n        corners_3d = box.corners()\n        in_front = np.argwhere(corners_3d[2, :] > 0).flatten()\n        corners_3d = corners_3d[:, in_front]\n\n        # Project 3d box to 2d.\n        corner_coords = view_points(corners_3d, camera_intrinsic,\n                                    True).T[:, :2].tolist()\n\n        # Keep only corners that fall within the image.\n        final_coords = post_process_coords(corner_coords)\n\n        # Skip if the convex hull of the re-projected corners\n        # does not intersect the image canvas.\n        if final_coords is None:\n            continue\n        else:\n            min_x, min_y, max_x, max_y = final_coords\n\n        # Generate dictionary record to be included in the .json file.\n        repro_rec = generate_record(ann_rec, min_x, min_y, max_x, max_y,\n                                    sample_data_token, sd_rec['filename'])\n\n        # If mono3d=True, add 3D annotations in camera coordinates\n        if mono3d and (repro_rec is not None):\n            loc = box.center.tolist()\n\n            dim = box.wlh\n            dim[[0, 1, 2]] = dim[[1, 2, 0]]  # convert wlh to our lhw\n            dim = dim.tolist()\n\n            rot = box.orientation.yaw_pitch_roll[0]\n            rot = [-rot]  # convert the rot to our cam coordinate\n\n            global_velo2d = nusc.box_velocity(box.token)[:2]\n            global_velo3d = np.array([*global_velo2d, 0.0])\n            e2g_r_mat = Quaternion(pose_rec['rotation']).rotation_matrix\n            c2e_r_mat = Quaternion(cs_rec['rotation']).rotation_matrix\n            cam_velo3d = global_velo3d @ np.linalg.inv(\n                e2g_r_mat).T @ np.linalg.inv(c2e_r_mat).T\n            velo = cam_velo3d[0::2].tolist()\n\n            repro_rec['bbox_cam3d'] = loc + dim + rot\n            repro_rec['velo_cam3d'] = velo\n\n            center3d = np.array(loc).reshape([1, 3])\n            center2d = points_cam2img(\n                center3d, camera_intrinsic, with_depth=True)\n            repro_rec['center2d'] = center2d.squeeze().tolist()\n            # normalized center2D + depth\n            # if samples with depth < 0 will be removed\n            if repro_rec['center2d'][2] <= 0:\n                continue\n\n            ann_token = nusc.get('sample_annotation',\n                                 box.token)['attribute_tokens']\n            if len(ann_token) == 0:\n                attr_name = 'None'\n            else:\n                attr_name = nusc.get('attribute', ann_token[0])['name']\n            attr_id = nus_attributes.index(attr_name)\n            repro_rec['attribute_name'] = attr_name\n            repro_rec['attribute_id'] = attr_id\n\n        repro_recs.append(repro_rec)\n\n    return repro_recs\n\n\ndef post_process_coords(\n    corner_coords: List, imsize: Tuple[int, int] = (1600, 900)\n) -> Union[Tuple[float, float, float, float], None]:\n    \"\"\"Get the intersection of the convex hull of the reprojected bbox corners\n    and the image canvas, return None if no intersection.\n\n    Args:\n        corner_coords (list[int]): Corner coordinates of reprojected\n            bounding box.\n        imsize (tuple[int]): Size of the image canvas.\n\n    Return:\n        tuple [float]: Intersection of the convex hull of the 2D box\n            corners and the image canvas.\n    \"\"\"\n    polygon_from_2d_box = MultiPoint(corner_coords).convex_hull\n    img_canvas = box(0, 0, imsize[0], imsize[1])\n\n    if polygon_from_2d_box.intersects(img_canvas):\n        img_intersection = polygon_from_2d_box.intersection(img_canvas)\n        intersection_coords = np.array(\n            [coord for coord in img_intersection.exterior.coords])\n\n        min_x = min(intersection_coords[:, 0])\n        min_y = min(intersection_coords[:, 1])\n        max_x = max(intersection_coords[:, 0])\n        max_y = max(intersection_coords[:, 1])\n\n        return min_x, min_y, max_x, max_y\n    else:\n        return None\n\n\ndef generate_record(ann_rec: dict, x1: float, y1: float, x2: float, y2: float,\n                    sample_data_token: str, filename: str) -> OrderedDict:\n    \"\"\"Generate one 2D annotation record given various informations on top of\n    the 2D bounding box coordinates.\n\n    Args:\n        ann_rec (dict): Original 3d annotation record.\n        x1 (float): Minimum value of the x coordinate.\n        y1 (float): Minimum value of the y coordinate.\n        x2 (float): Maximum value of the x coordinate.\n        y2 (float): Maximum value of the y coordinate.\n        sample_data_token (str): Sample data token.\n        filename (str):The corresponding image file where the annotation\n            is present.\n\n    Returns:\n        dict: A sample 2D annotation record.\n            - file_name (str): flie name\n            - image_id (str): sample data token\n            - area (float): 2d box area\n            - category_name (str): category name\n            - category_id (int): category id\n            - bbox (list[float]): left x, top y, dx, dy of 2d box\n            - iscrowd (int): whether the area is crowd\n    \"\"\"\n    repro_rec = OrderedDict()\n    repro_rec['sample_data_token'] = sample_data_token\n    coco_rec = dict()\n\n    relevant_keys = [\n        'attribute_tokens',\n        'category_name',\n        'instance_token',\n        'next',\n        'num_lidar_pts',\n        'num_radar_pts',\n        'prev',\n        'sample_annotation_token',\n        'sample_data_token',\n        'visibility_token',\n    ]\n\n    for key, value in ann_rec.items():\n        if key in relevant_keys:\n            repro_rec[key] = value\n\n    repro_rec['bbox_corners'] = [x1, y1, x2, y2]\n    repro_rec['filename'] = filename\n\n    coco_rec['file_name'] = filename\n    coco_rec['image_id'] = sample_data_token\n    coco_rec['area'] = (y2 - y1) * (x2 - x1)\n\n    if repro_rec['category_name'] not in NuScenesDataset.NameMapping:\n        return None\n    cat_name = NuScenesDataset.NameMapping[repro_rec['category_name']]\n    coco_rec['category_name'] = cat_name\n    coco_rec['category_id'] = nus_categories.index(cat_name)\n    coco_rec['bbox'] = [x1, y1, x2 - x1, y2 - y1]\n    coco_rec['iscrowd'] = 0\n\n    return coco_rec\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/s3dis_data_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport os\nfrom concurrent import futures as futures\nfrom os import path as osp\n\n\nclass S3DISData(object):\n    \"\"\"S3DIS data.\n\n    Generate s3dis infos for s3dis_converter.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        split (str): Set split type of the data. Default: 'Area_1'.\n    \"\"\"\n\n    def __init__(self, root_path, split='Area_1'):\n        self.root_dir = root_path\n        self.split = split\n        self.data_dir = osp.join(root_path,\n                                 'Stanford3dDataset_v1.2_Aligned_Version')\n\n        # Following `GSDN <https://arxiv.org/abs/2006.12356>`_, use 5 furniture\n        # classes for detection: table, chair, sofa, bookcase, board.\n        self.cat_ids = np.array([7, 8, 9, 10, 11])\n        self.cat_ids2class = {\n            cat_id: i\n            for i, cat_id in enumerate(list(self.cat_ids))\n        }\n\n        assert split in [\n            'Area_1', 'Area_2', 'Area_3', 'Area_4', 'Area_5', 'Area_6'\n        ]\n        self.sample_id_list = os.listdir(osp.join(self.data_dir,\n                                                  split))  # conferenceRoom_1\n        for sample_id in self.sample_id_list:\n            if os.path.isfile(osp.join(self.data_dir, split, sample_id)):\n                self.sample_id_list.remove(sample_id)\n\n    def __len__(self):\n        return len(self.sample_id_list)\n\n    def get_infos(self, num_workers=4, has_label=True, sample_id_list=None):\n        \"\"\"Get data infos.\n\n        This method gets information from the raw data.\n\n        Args:\n            num_workers (int): Number of threads to be used. Default: 4.\n            has_label (bool): Whether the data has label. Default: True.\n            sample_id_list (list[int]): Index list of the sample.\n                Default: None.\n\n        Returns:\n            infos (list[dict]): Information of the raw data.\n        \"\"\"\n\n        def process_single_scene(sample_idx):\n            print(f'{self.split} sample_idx: {sample_idx}')\n            info = dict()\n            pc_info = {\n                'num_features': 6,\n                'lidar_idx': f'{self.split}_{sample_idx}'\n            }\n            info['point_cloud'] = pc_info\n            pts_filename = osp.join(self.root_dir, 's3dis_data',\n                                    f'{self.split}_{sample_idx}_point.npy')\n            pts_instance_mask_path = osp.join(\n                self.root_dir, 's3dis_data',\n                f'{self.split}_{sample_idx}_ins_label.npy')\n            pts_semantic_mask_path = osp.join(\n                self.root_dir, 's3dis_data',\n                f'{self.split}_{sample_idx}_sem_label.npy')\n\n            points = np.load(pts_filename).astype(np.float32)\n            pts_instance_mask = np.load(pts_instance_mask_path).astype(np.int)\n            pts_semantic_mask = np.load(pts_semantic_mask_path).astype(np.int)\n\n            mmcv.mkdir_or_exist(osp.join(self.root_dir, 'points'))\n            mmcv.mkdir_or_exist(osp.join(self.root_dir, 'instance_mask'))\n            mmcv.mkdir_or_exist(osp.join(self.root_dir, 'semantic_mask'))\n\n            points.tofile(\n                osp.join(self.root_dir, 'points',\n                         f'{self.split}_{sample_idx}.bin'))\n            pts_instance_mask.tofile(\n                osp.join(self.root_dir, 'instance_mask',\n                         f'{self.split}_{sample_idx}.bin'))\n            pts_semantic_mask.tofile(\n                osp.join(self.root_dir, 'semantic_mask',\n                         f'{self.split}_{sample_idx}.bin'))\n\n            info['pts_path'] = osp.join('points',\n                                        f'{self.split}_{sample_idx}.bin')\n            info['pts_instance_mask_path'] = osp.join(\n                'instance_mask', f'{self.split}_{sample_idx}.bin')\n            info['pts_semantic_mask_path'] = osp.join(\n                'semantic_mask', f'{self.split}_{sample_idx}.bin')\n            info['annos'] = self.get_bboxes(points, pts_instance_mask,\n                                            pts_semantic_mask)\n\n            return info\n\n        sample_id_list = sample_id_list if sample_id_list is not None \\\n            else self.sample_id_list\n        with futures.ThreadPoolExecutor(num_workers) as executor:\n            infos = executor.map(process_single_scene, sample_id_list)\n        return list(infos)\n\n    def get_bboxes(self, points, pts_instance_mask, pts_semantic_mask):\n        \"\"\"Convert instance masks to axis-aligned bounding boxes.\n\n        Args:\n            points (np.array): Scene points of shape (n, 6).\n            pts_instance_mask (np.ndarray): Instance labels of shape (n,).\n            pts_semantic_mask (np.ndarray): Semantic labels of shape (n,).\n\n        Returns:\n            dict: A dict containing detection infos with following keys:\n\n                - gt_boxes_upright_depth (np.ndarray): Bounding boxes\n                    of shape (n, 6)\n                - class (np.ndarray): Box labels of shape (n,)\n                - gt_num (int): Number of boxes.\n        \"\"\"\n        bboxes, labels = [], []\n        for i in range(1, pts_instance_mask.max()):\n            ids = pts_instance_mask == i\n            # check if all instance points have same semantic label\n            assert pts_semantic_mask[ids].min() == pts_semantic_mask[ids].max()\n            label = pts_semantic_mask[ids][0]\n            # keep only furniture objects\n            if label in self.cat_ids2class:\n                labels.append(self.cat_ids2class[pts_semantic_mask[ids][0]])\n                pts = points[:, :3][ids]\n                min_pts = pts.min(axis=0)\n                max_pts = pts.max(axis=0)\n                locations = (min_pts + max_pts) / 2\n                dimensions = max_pts - min_pts\n                bboxes.append(np.concatenate((locations, dimensions)))\n        annotation = dict()\n        # follow ScanNet and SUN RGB-D keys\n        annotation['gt_boxes_upright_depth'] = np.array(bboxes)\n        annotation['class'] = np.array(labels)\n        annotation['gt_num'] = len(labels)\n        return annotation\n\n\nclass S3DISSegData(object):\n    \"\"\"S3DIS dataset used to generate infos for semantic segmentation task.\n\n    Args:\n        data_root (str): Root path of the raw data.\n        ann_file (str): The generated scannet infos.\n        split (str): Set split type of the data. Default: 'train'.\n        num_points (int): Number of points in each data input. Default: 8192.\n        label_weight_func (function): Function to compute the label weight.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 data_root,\n                 ann_file,\n                 split='Area_1',\n                 num_points=4096,\n                 label_weight_func=None):\n        self.data_root = data_root\n        self.data_infos = mmcv.load(ann_file)\n        self.split = split\n        self.num_points = num_points\n\n        self.all_ids = np.arange(13)  # all possible ids\n        self.cat_ids = np.array([0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11,\n                                 12])  # used for seg task\n        self.ignore_index = len(self.cat_ids)\n\n        self.cat_id2class = np.ones((self.all_ids.shape[0],), dtype=np.int) * \\\n            self.ignore_index\n        for i, cat_id in enumerate(self.cat_ids):\n            self.cat_id2class[cat_id] = i\n\n        # label weighting function is taken from\n        # https://github.com/charlesq34/pointnet2/blob/master/scannet/scannet_dataset.py#L24\n        self.label_weight_func = (lambda x: 1.0 / np.log(1.2 + x)) if \\\n            label_weight_func is None else label_weight_func\n\n    def get_seg_infos(self):\n        scene_idxs, label_weight = self.get_scene_idxs_and_label_weight()\n        save_folder = osp.join(self.data_root, 'seg_info')\n        mmcv.mkdir_or_exist(save_folder)\n        np.save(\n            osp.join(save_folder, f'{self.split}_resampled_scene_idxs.npy'),\n            scene_idxs)\n        np.save(\n            osp.join(save_folder, f'{self.split}_label_weight.npy'),\n            label_weight)\n        print(f'{self.split} resampled scene index and label weight saved')\n\n    def _convert_to_label(self, mask):\n        \"\"\"Convert class_id in loaded segmentation mask to label.\"\"\"\n        if isinstance(mask, str):\n            if mask.endswith('npy'):\n                mask = np.load(mask)\n            else:\n                mask = np.fromfile(mask, dtype=np.long)\n        label = self.cat_id2class[mask]\n        return label\n\n    def get_scene_idxs_and_label_weight(self):\n        \"\"\"Compute scene_idxs for data sampling and label weight for loss \\\n        calculation.\n\n        We sample more times for scenes with more points. Label_weight is\n        inversely proportional to number of class points.\n        \"\"\"\n        num_classes = len(self.cat_ids)\n        num_point_all = []\n        label_weight = np.zeros((num_classes + 1, ))  # ignore_index\n        for data_info in self.data_infos:\n            label = self._convert_to_label(\n                osp.join(self.data_root, data_info['pts_semantic_mask_path']))\n            num_point_all.append(label.shape[0])\n            class_count, _ = np.histogram(label, range(num_classes + 2))\n            label_weight += class_count\n\n        # repeat scene_idx for num_scene_point // num_sample_point times\n        sample_prob = np.array(num_point_all) / float(np.sum(num_point_all))\n        num_iter = int(np.sum(num_point_all) / float(self.num_points))\n        scene_idxs = []\n        for idx in range(len(self.data_infos)):\n            scene_idxs.extend([idx] * int(round(sample_prob[idx] * num_iter)))\n        scene_idxs = np.array(scene_idxs).astype(np.int32)\n\n        # calculate label weight, adopted from PointNet++\n        label_weight = label_weight[:-1].astype(np.float32)\n        label_weight = label_weight / label_weight.sum()\n        label_weight = self.label_weight_func(label_weight).astype(np.float32)\n\n        return scene_idxs, label_weight\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/scannet_data_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport os\nfrom concurrent import futures as futures\nfrom os import path as osp\n\n\nclass ScanNetData(object):\n    \"\"\"ScanNet data.\n\n    Generate scannet infos for scannet_converter.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        split (str): Set split type of the data. Default: 'train'.\n    \"\"\"\n\n    def __init__(self, root_path, split='train'):\n        self.root_dir = root_path\n        self.split = split\n        self.split_dir = osp.join(root_path)\n        self.classes = [\n            'cabinet', 'bed', 'chair', 'sofa', 'table', 'door', 'window',\n            'bookshelf', 'picture', 'counter', 'desk', 'curtain',\n            'refrigerator', 'showercurtrain', 'toilet', 'sink', 'bathtub',\n            'garbagebin'\n        ]\n        self.cat2label = {cat: self.classes.index(cat) for cat in self.classes}\n        self.label2cat = {self.cat2label[t]: t for t in self.cat2label}\n        self.cat_ids = np.array(\n            [3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28, 33, 34, 36, 39])\n        self.cat_ids2class = {\n            nyu40id: i\n            for i, nyu40id in enumerate(list(self.cat_ids))\n        }\n        assert split in ['train', 'val', 'test']\n        split_file = osp.join(self.root_dir, 'meta_data',\n                              f'scannetv2_{split}.txt')\n        mmcv.check_file_exist(split_file)\n        self.sample_id_list = mmcv.list_from_file(split_file)\n        self.test_mode = (split == 'test')\n\n    def __len__(self):\n        return len(self.sample_id_list)\n\n    def get_aligned_box_label(self, idx):\n        box_file = osp.join(self.root_dir, 'scannet_instance_data',\n                            f'{idx}_aligned_bbox.npy')\n        mmcv.check_file_exist(box_file)\n        return np.load(box_file)\n\n    def get_unaligned_box_label(self, idx):\n        box_file = osp.join(self.root_dir, 'scannet_instance_data',\n                            f'{idx}_unaligned_bbox.npy')\n        mmcv.check_file_exist(box_file)\n        return np.load(box_file)\n\n    def get_axis_align_matrix(self, idx):\n        matrix_file = osp.join(self.root_dir, 'scannet_instance_data',\n                               f'{idx}_axis_align_matrix.npy')\n        mmcv.check_file_exist(matrix_file)\n        return np.load(matrix_file)\n\n    def get_images(self, idx):\n        paths = []\n        path = osp.join(self.root_dir, 'posed_images', idx)\n        for file in sorted(os.listdir(path)):\n            if file.endswith('.jpg'):\n                paths.append(osp.join('posed_images', idx, file))\n        return paths\n\n    def get_extrinsics(self, idx):\n        extrinsics = []\n        path = osp.join(self.root_dir, 'posed_images', idx)\n        for file in sorted(os.listdir(path)):\n            if file.endswith('.txt') and not file == 'intrinsic.txt':\n                extrinsics.append(np.loadtxt(osp.join(path, file)))\n        return extrinsics\n\n    def get_intrinsics(self, idx):\n        matrix_file = osp.join(self.root_dir, 'posed_images', idx,\n                               'intrinsic.txt')\n        mmcv.check_file_exist(matrix_file)\n        return np.loadtxt(matrix_file)\n\n    def get_infos(self, num_workers=4, has_label=True, sample_id_list=None):\n        \"\"\"Get data infos.\n\n        This method gets information from the raw data.\n\n        Args:\n            num_workers (int): Number of threads to be used. Default: 4.\n            has_label (bool): Whether the data has label. Default: True.\n            sample_id_list (list[int]): Index list of the sample.\n                Default: None.\n\n        Returns:\n            infos (list[dict]): Information of the raw data.\n        \"\"\"\n\n        def process_single_scene(sample_idx):\n            print(f'{self.split} sample_idx: {sample_idx}')\n            info = dict()\n            pc_info = {'num_features': 6, 'lidar_idx': sample_idx}\n            info['point_cloud'] = pc_info\n            pts_filename = osp.join(self.root_dir, 'scannet_instance_data',\n                                    f'{sample_idx}_vert.npy')\n            points = np.load(pts_filename)\n            mmcv.mkdir_or_exist(osp.join(self.root_dir, 'points'))\n            points.tofile(\n                osp.join(self.root_dir, 'points', f'{sample_idx}.bin'))\n            info['pts_path'] = osp.join('points', f'{sample_idx}.bin')\n\n            # update with RGB image paths if exist\n            if os.path.exists(osp.join(self.root_dir, 'posed_images')):\n                info['intrinsics'] = self.get_intrinsics(sample_idx)\n                all_extrinsics = self.get_extrinsics(sample_idx)\n                all_img_paths = self.get_images(sample_idx)\n                # some poses in ScanNet are invalid\n                extrinsics, img_paths = [], []\n                for extrinsic, img_path in zip(all_extrinsics, all_img_paths):\n                    if np.all(np.isfinite(extrinsic)):\n                        img_paths.append(img_path)\n                        extrinsics.append(extrinsic)\n                info['extrinsics'] = extrinsics\n                info['img_paths'] = img_paths\n\n            if not self.test_mode:\n                pts_instance_mask_path = osp.join(\n                    self.root_dir, 'scannet_instance_data',\n                    f'{sample_idx}_ins_label.npy')\n                pts_semantic_mask_path = osp.join(\n                    self.root_dir, 'scannet_instance_data',\n                    f'{sample_idx}_sem_label.npy')\n\n                pts_instance_mask = np.load(pts_instance_mask_path).astype(\n                    np.long)\n                pts_semantic_mask = np.load(pts_semantic_mask_path).astype(\n                    np.long)\n\n                mmcv.mkdir_or_exist(osp.join(self.root_dir, 'instance_mask'))\n                mmcv.mkdir_or_exist(osp.join(self.root_dir, 'semantic_mask'))\n\n                pts_instance_mask.tofile(\n                    osp.join(self.root_dir, 'instance_mask',\n                             f'{sample_idx}.bin'))\n                pts_semantic_mask.tofile(\n                    osp.join(self.root_dir, 'semantic_mask',\n                             f'{sample_idx}.bin'))\n\n                info['pts_instance_mask_path'] = osp.join(\n                    'instance_mask', f'{sample_idx}.bin')\n                info['pts_semantic_mask_path'] = osp.join(\n                    'semantic_mask', f'{sample_idx}.bin')\n\n            if has_label:\n                annotations = {}\n                # box is of shape [k, 6 + class]\n                aligned_box_label = self.get_aligned_box_label(sample_idx)\n                unaligned_box_label = self.get_unaligned_box_label(sample_idx)\n                annotations['gt_num'] = aligned_box_label.shape[0]\n                if annotations['gt_num'] != 0:\n                    aligned_box = aligned_box_label[:, :-1]  # k, 6\n                    unaligned_box = unaligned_box_label[:, :-1]\n                    classes = aligned_box_label[:, -1]  # k\n                    annotations['name'] = np.array([\n                        self.label2cat[self.cat_ids2class[classes[i]]]\n                        for i in range(annotations['gt_num'])\n                    ])\n                    # default names are given to aligned bbox for compatibility\n                    # we also save unaligned bbox info with marked names\n                    annotations['location'] = aligned_box[:, :3]\n                    annotations['dimensions'] = aligned_box[:, 3:6]\n                    annotations['gt_boxes_upright_depth'] = aligned_box\n                    annotations['unaligned_location'] = unaligned_box[:, :3]\n                    annotations['unaligned_dimensions'] = unaligned_box[:, 3:6]\n                    annotations[\n                        'unaligned_gt_boxes_upright_depth'] = unaligned_box\n                    annotations['index'] = np.arange(\n                        annotations['gt_num'], dtype=np.int32)\n                    annotations['class'] = np.array([\n                        self.cat_ids2class[classes[i]]\n                        for i in range(annotations['gt_num'])\n                    ])\n                axis_align_matrix = self.get_axis_align_matrix(sample_idx)\n                annotations['axis_align_matrix'] = axis_align_matrix  # 4x4\n                info['annos'] = annotations\n            return info\n\n        sample_id_list = sample_id_list if sample_id_list is not None \\\n            else self.sample_id_list\n        with futures.ThreadPoolExecutor(num_workers) as executor:\n            infos = executor.map(process_single_scene, sample_id_list)\n        return list(infos)\n\n\nclass ScanNetSegData(object):\n    \"\"\"ScanNet dataset used to generate infos for semantic segmentation task.\n\n    Args:\n        data_root (str): Root path of the raw data.\n        ann_file (str): The generated scannet infos.\n        split (str): Set split type of the data. Default: 'train'.\n        num_points (int): Number of points in each data input. Default: 8192.\n        label_weight_func (function): Function to compute the label weight.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 data_root,\n                 ann_file,\n                 split='train',\n                 num_points=8192,\n                 label_weight_func=None):\n        self.data_root = data_root\n        self.data_infos = mmcv.load(ann_file)\n        self.split = split\n        assert split in ['train', 'val', 'test']\n        self.num_points = num_points\n\n        self.all_ids = np.arange(41)  # all possible ids\n        self.cat_ids = np.array([\n            1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28, 33, 34, 36,\n            39\n        ])  # used for seg task\n        self.ignore_index = len(self.cat_ids)\n\n        self.cat_id2class = np.ones((self.all_ids.shape[0],), dtype=np.int) * \\\n            self.ignore_index\n        for i, cat_id in enumerate(self.cat_ids):\n            self.cat_id2class[cat_id] = i\n\n        # label weighting function is taken from\n        # https://github.com/charlesq34/pointnet2/blob/master/scannet/scannet_dataset.py#L24\n        self.label_weight_func = (lambda x: 1.0 / np.log(1.2 + x)) if \\\n            label_weight_func is None else label_weight_func\n\n    def get_seg_infos(self):\n        if self.split == 'test':\n            return\n        scene_idxs, label_weight = self.get_scene_idxs_and_label_weight()\n        save_folder = osp.join(self.data_root, 'seg_info')\n        mmcv.mkdir_or_exist(save_folder)\n        np.save(\n            osp.join(save_folder, f'{self.split}_resampled_scene_idxs.npy'),\n            scene_idxs)\n        np.save(\n            osp.join(save_folder, f'{self.split}_label_weight.npy'),\n            label_weight)\n        print(f'{self.split} resampled scene index and label weight saved')\n\n    def _convert_to_label(self, mask):\n        \"\"\"Convert class_id in loaded segmentation mask to label.\"\"\"\n        if isinstance(mask, str):\n            if mask.endswith('npy'):\n                mask = np.load(mask)\n            else:\n                mask = np.fromfile(mask, dtype=np.long)\n        label = self.cat_id2class[mask]\n        return label\n\n    def get_scene_idxs_and_label_weight(self):\n        \"\"\"Compute scene_idxs for data sampling and label weight for loss \\\n        calculation.\n\n        We sample more times for scenes with more points. Label_weight is\n        inversely proportional to number of class points.\n        \"\"\"\n        num_classes = len(self.cat_ids)\n        num_point_all = []\n        label_weight = np.zeros((num_classes + 1, ))  # ignore_index\n        for data_info in self.data_infos:\n            label = self._convert_to_label(\n                osp.join(self.data_root, data_info['pts_semantic_mask_path']))\n            num_point_all.append(label.shape[0])\n            class_count, _ = np.histogram(label, range(num_classes + 2))\n            label_weight += class_count\n\n        # repeat scene_idx for num_scene_point // num_sample_point times\n        sample_prob = np.array(num_point_all) / float(np.sum(num_point_all))\n        num_iter = int(np.sum(num_point_all) / float(self.num_points))\n        scene_idxs = []\n        for idx in range(len(self.data_infos)):\n            scene_idxs.extend([idx] * int(round(sample_prob[idx] * num_iter)))\n        scene_idxs = np.array(scene_idxs).astype(np.int32)\n\n        # calculate label weight, adopted from PointNet++\n        label_weight = label_weight[:-1].astype(np.float32)\n        label_weight = label_weight / label_weight.sum()\n        label_weight = self.label_weight_func(label_weight).astype(np.float32)\n\n        return scene_idxs, label_weight\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/sunrgbd_data_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nfrom concurrent import futures as futures\nfrom os import path as osp\nfrom scipy import io as sio\n\n\ndef random_sampling(points, num_points, replace=None, return_choices=False):\n    \"\"\"Random sampling.\n\n    Sampling point cloud to a certain number of points.\n\n    Args:\n        points (ndarray): Point cloud.\n        num_points (int): The number of samples.\n        replace (bool): Whether the sample is with or without replacement.\n        return_choices (bool): Whether to return choices.\n\n    Returns:\n        points (ndarray): Point cloud after sampling.\n    \"\"\"\n\n    if replace is None:\n        replace = (points.shape[0] < num_points)\n    choices = np.random.choice(points.shape[0], num_points, replace=replace)\n    if return_choices:\n        return points[choices], choices\n    else:\n        return points[choices]\n\n\nclass SUNRGBDInstance(object):\n\n    def __init__(self, line):\n        data = line.split(' ')\n        data[1:] = [float(x) for x in data[1:]]\n        self.classname = data[0]\n        self.xmin = data[1]\n        self.ymin = data[2]\n        self.xmax = data[1] + data[3]\n        self.ymax = data[2] + data[4]\n        self.box2d = np.array([self.xmin, self.ymin, self.xmax, self.ymax])\n        self.centroid = np.array([data[5], data[6], data[7]])\n        self.w = data[8]\n        self.l = data[9]  # noqa: E741\n        self.h = data[10]\n        self.orientation = np.zeros((3, ))\n        self.orientation[0] = data[11]\n        self.orientation[1] = data[12]\n        self.heading_angle = -1 * np.arctan2(self.orientation[1],\n                                             self.orientation[0])\n        self.box3d = np.concatenate([\n            self.centroid,\n            np.array([self.l * 2, self.w * 2, self.h * 2, self.heading_angle])\n        ])\n\n\nclass SUNRGBDData(object):\n    \"\"\"SUNRGBD data.\n\n    Generate scannet infos for sunrgbd_converter.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        split (str): Set split type of the data. Default: 'train'.\n        use_v1 (bool): Whether to use v1. Default: False.\n    \"\"\"\n\n    def __init__(self, root_path, split='train', use_v1=False):\n        self.root_dir = root_path\n        self.split = split\n        self.split_dir = osp.join(root_path, 'sunrgbd_trainval')\n        self.classes = [\n            'bed', 'table', 'sofa', 'chair', 'toilet', 'desk', 'dresser',\n            'night_stand', 'bookshelf', 'bathtub'\n        ]\n        self.cat2label = {cat: self.classes.index(cat) for cat in self.classes}\n        self.label2cat = {\n            label: self.classes[label]\n            for label in range(len(self.classes))\n        }\n        assert split in ['train', 'val', 'test']\n        split_file = osp.join(self.split_dir, f'{split}_data_idx.txt')\n        mmcv.check_file_exist(split_file)\n        self.sample_id_list = map(int, mmcv.list_from_file(split_file))\n        self.image_dir = osp.join(self.split_dir, 'image')\n        self.calib_dir = osp.join(self.split_dir, 'calib')\n        self.depth_dir = osp.join(self.split_dir, 'depth')\n        if use_v1:\n            self.label_dir = osp.join(self.split_dir, 'label_v1')\n        else:\n            self.label_dir = osp.join(self.split_dir, 'label')\n\n    def __len__(self):\n        return len(self.sample_id_list)\n\n    def get_image(self, idx):\n        img_filename = osp.join(self.image_dir, f'{idx:06d}.jpg')\n        return mmcv.imread(img_filename)\n\n    def get_image_shape(self, idx):\n        image = self.get_image(idx)\n        return np.array(image.shape[:2], dtype=np.int32)\n\n    def get_depth(self, idx):\n        depth_filename = osp.join(self.depth_dir, f'{idx:06d}.mat')\n        depth = sio.loadmat(depth_filename)['instance']\n        return depth\n\n    def get_calibration(self, idx):\n        calib_filepath = osp.join(self.calib_dir, f'{idx:06d}.txt')\n        lines = [line.rstrip() for line in open(calib_filepath)]\n        Rt = np.array([float(x) for x in lines[0].split(' ')])\n        Rt = np.reshape(Rt, (3, 3), order='F').astype(np.float32)\n        K = np.array([float(x) for x in lines[1].split(' ')])\n        K = np.reshape(K, (3, 3), order='F').astype(np.float32)\n        return K, Rt\n\n    def get_label_objects(self, idx):\n        label_filename = osp.join(self.label_dir, f'{idx:06d}.txt')\n        lines = [line.rstrip() for line in open(label_filename)]\n        objects = [SUNRGBDInstance(line) for line in lines]\n        return objects\n\n    def get_infos(self, num_workers=4, has_label=True, sample_id_list=None):\n        \"\"\"Get data infos.\n\n        This method gets information from the raw data.\n\n        Args:\n            num_workers (int): Number of threads to be used. Default: 4.\n            has_label (bool): Whether the data has label. Default: True.\n            sample_id_list (list[int]): Index list of the sample.\n                Default: None.\n\n        Returns:\n            infos (list[dict]): Information of the raw data.\n        \"\"\"\n\n        def process_single_scene(sample_idx):\n            print(f'{self.split} sample_idx: {sample_idx}')\n            # convert depth to points\n            SAMPLE_NUM = 50000\n            # TODO: Check whether can move the point\n            #  sampling process during training.\n            pc_upright_depth = self.get_depth(sample_idx)\n            pc_upright_depth_subsampled = random_sampling(\n                pc_upright_depth, SAMPLE_NUM)\n\n            info = dict()\n            pc_info = {'num_features': 6, 'lidar_idx': sample_idx}\n            info['point_cloud'] = pc_info\n\n            mmcv.mkdir_or_exist(osp.join(self.root_dir, 'points'))\n            pc_upright_depth_subsampled.tofile(\n                osp.join(self.root_dir, 'points', f'{sample_idx:06d}.bin'))\n\n            info['pts_path'] = osp.join('points', f'{sample_idx:06d}.bin')\n            img_path = osp.join('image', f'{sample_idx:06d}.jpg')\n            image_info = {\n                'image_idx': sample_idx,\n                'image_shape': self.get_image_shape(sample_idx),\n                'image_path': img_path\n            }\n            info['image'] = image_info\n\n            K, Rt = self.get_calibration(sample_idx)\n            calib_info = {'K': K, 'Rt': Rt}\n            info['calib'] = calib_info\n\n            if has_label:\n                obj_list = self.get_label_objects(sample_idx)\n                annotations = {}\n                annotations['gt_num'] = len([\n                    obj.classname for obj in obj_list\n                    if obj.classname in self.cat2label.keys()\n                ])\n                if annotations['gt_num'] != 0:\n                    annotations['name'] = np.array([\n                        obj.classname for obj in obj_list\n                        if obj.classname in self.cat2label.keys()\n                    ])\n                    annotations['bbox'] = np.concatenate([\n                        obj.box2d.reshape(1, 4) for obj in obj_list\n                        if obj.classname in self.cat2label.keys()\n                    ],\n                                                         axis=0)\n                    annotations['location'] = np.concatenate([\n                        obj.centroid.reshape(1, 3) for obj in obj_list\n                        if obj.classname in self.cat2label.keys()\n                    ],\n                                                             axis=0)\n                    annotations['dimensions'] = 2 * np.array([\n                        [obj.l, obj.w, obj.h] for obj in obj_list\n                        if obj.classname in self.cat2label.keys()\n                    ])  # lwh (depth) format\n                    annotations['rotation_y'] = np.array([\n                        obj.heading_angle for obj in obj_list\n                        if obj.classname in self.cat2label.keys()\n                    ])\n                    annotations['index'] = np.arange(\n                        len(obj_list), dtype=np.int32)\n                    annotations['class'] = np.array([\n                        self.cat2label[obj.classname] for obj in obj_list\n                        if obj.classname in self.cat2label.keys()\n                    ])\n                    annotations['gt_boxes_upright_depth'] = np.stack(\n                        [\n                            obj.box3d for obj in obj_list\n                            if obj.classname in self.cat2label.keys()\n                        ],\n                        axis=0)  # (K,8)\n                info['annos'] = annotations\n            return info\n\n        sample_id_list = sample_id_list if \\\n            sample_id_list is not None else self.sample_id_list\n        with futures.ThreadPoolExecutor(num_workers) as executor:\n            infos = executor.map(process_single_scene, sample_id_list)\n        return list(infos)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/data_converter/waymo_converter.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nr\"\"\"Adapted from `Waymo to KITTI converter\n    <https://github.com/caizhongang/waymo_kitti_converter>`_.\n\"\"\"\n\ntry:\n    from waymo_open_dataset import dataset_pb2\nexcept ImportError:\n    raise ImportError(\n        'Please run \"pip install waymo-open-dataset-tf-2-2-0==1.2.0\" '\n        'to install the official devkit first.')\n\nimport mmcv\nimport numpy as np\nimport tensorflow as tf\nfrom glob import glob\nfrom os.path import join\nfrom waymo_open_dataset.utils import range_image_utils, transform_utils\nfrom waymo_open_dataset.utils.frame_utils import \\\n    parse_range_image_and_camera_projection\n\n\nclass Waymo2KITTI(object):\n    \"\"\"Waymo to KITTI converter.\n\n    This class serves as the converter to change the waymo raw data to KITTI\n    format.\n\n    Args:\n        load_dir (str): Directory to load waymo raw data.\n        save_dir (str): Directory to save data in KITTI format.\n        prefix (str): Prefix of filename. In general, 0 for training, 1 for\n            validation and 2 for testing.\n        workers (str): Number of workers for the parallel process.\n        test_mode (bool): Whether in the test_mode. Default: False.\n    \"\"\"\n\n    def __init__(self,\n                 load_dir,\n                 save_dir,\n                 prefix,\n                 workers=64,\n                 test_mode=False):\n        self.filter_empty_3dboxes = True\n        self.filter_no_label_zone_points = True\n\n        self.selected_waymo_classes = ['VEHICLE', 'PEDESTRIAN', 'CYCLIST']\n\n        # Only data collected in specific locations will be converted\n        # If set None, this filter is disabled\n        # Available options: location_sf (main dataset)\n        self.selected_waymo_locations = None\n        self.save_track_id = False\n\n        # turn on eager execution for older tensorflow versions\n        if int(tf.__version__.split('.')[0]) < 2:\n            tf.enable_eager_execution()\n\n        self.lidar_list = [\n            '_FRONT', '_FRONT_RIGHT', '_FRONT_LEFT', '_SIDE_RIGHT',\n            '_SIDE_LEFT'\n        ]\n        self.type_list = [\n            'UNKNOWN', 'VEHICLE', 'PEDESTRIAN', 'SIGN', 'CYCLIST'\n        ]\n        self.waymo_to_kitti_class_map = {\n            'UNKNOWN': 'DontCare',\n            'PEDESTRIAN': 'Pedestrian',\n            'VEHICLE': 'Car',\n            'CYCLIST': 'Cyclist',\n            'SIGN': 'Sign'  # not in kitti\n        }\n\n        self.load_dir = load_dir\n        self.save_dir = save_dir\n        self.prefix = prefix\n        self.workers = int(workers)\n        self.test_mode = test_mode\n\n        self.tfrecord_pathnames = sorted(\n            glob(join(self.load_dir, '*.tfrecord')))\n\n        self.label_save_dir = f'{self.save_dir}/label_'\n        self.label_all_save_dir = f'{self.save_dir}/label_all'\n        self.image_save_dir = f'{self.save_dir}/image_'\n        self.calib_save_dir = f'{self.save_dir}/calib'\n        self.point_cloud_save_dir = f'{self.save_dir}/velodyne'\n        self.pose_save_dir = f'{self.save_dir}/pose'\n\n        self.create_folder()\n\n    def convert(self):\n        \"\"\"Convert action.\"\"\"\n        print('Start converting ...')\n        mmcv.track_parallel_progress(self.convert_one, range(len(self)),\n                                     self.workers)\n        print('\\nFinished ...')\n\n    def convert_one(self, file_idx):\n        \"\"\"Convert action for single file.\n\n        Args:\n            file_idx (int): Index of the file to be converted.\n        \"\"\"\n        pathname = self.tfrecord_pathnames[file_idx]\n        dataset = tf.data.TFRecordDataset(pathname, compression_type='')\n\n        for frame_idx, data in enumerate(dataset):\n\n            if frame_idx % 5 != 0:\n                continue\n            # print(frame_idx)\n            frame = dataset_pb2.Frame()\n            frame.ParseFromString(bytearray(data.numpy()))\n            if (self.selected_waymo_locations is not None\n                    and frame.context.stats.location\n                    not in self.selected_waymo_locations):\n                continue\n\n            self.save_image(frame, file_idx, frame_idx)\n            self.save_calib(frame, file_idx, frame_idx)\n            self.save_lidar(frame, file_idx, frame_idx)\n            self.save_pose(frame, file_idx, frame_idx)\n\n            if not self.test_mode:\n                self.save_label(frame, file_idx, frame_idx)\n\n    def __len__(self):\n        \"\"\"Length of the filename list.\"\"\"\n        return len(self.tfrecord_pathnames)\n\n    def save_image(self, frame, file_idx, frame_idx):\n        \"\"\"Parse and save the images in png format.\n\n        Args:\n            frame (:obj:`Frame`): Open dataset frame proto.\n            file_idx (int): Current file index.\n            frame_idx (int): Current frame index.\n        \"\"\"\n        for img in frame.images:\n            img_path = f'{self.image_save_dir}{str(img.name - 1)}/' + \\\n                f'{self.prefix}{str(file_idx).zfill(3)}' + \\\n                f'{str(frame_idx).zfill(3)}.png'\n            img = mmcv.imfrombytes(img.image)\n            mmcv.imwrite(img, img_path)\n\n    def save_calib(self, frame, file_idx, frame_idx):\n        \"\"\"Parse and save the calibration data.\n\n        Args:\n            frame (:obj:`Frame`): Open dataset frame proto.\n            file_idx (int): Current file index.\n            frame_idx (int): Current frame index.\n        \"\"\"\n        # waymo front camera to kitti reference camera\n        T_front_cam_to_ref = np.array([[0.0, -1.0, 0.0], [0.0, 0.0, -1.0],\n                                       [1.0, 0.0, 0.0]])\n        camera_calibs = []\n        R0_rect = [f'{i:e}' for i in np.eye(3).flatten()]\n        Tr_velo_to_cams = []\n        calib_context = ''\n\n        for camera in frame.context.camera_calibrations:\n            # extrinsic parameters\n            T_cam_to_vehicle = np.array(camera.extrinsic.transform).reshape(\n                4, 4)\n            T_vehicle_to_cam = np.linalg.inv(T_cam_to_vehicle)\n            Tr_velo_to_cam = \\\n                self.cart_to_homo(T_front_cam_to_ref) @ T_vehicle_to_cam\n            if camera.name == 1:  # FRONT = 1, see dataset.proto for details\n                self.T_velo_to_front_cam = Tr_velo_to_cam.copy()\n            Tr_velo_to_cam = Tr_velo_to_cam[:3, :].reshape((12, ))\n            Tr_velo_to_cams.append([f'{i:e}' for i in Tr_velo_to_cam])\n\n            # intrinsic parameters\n            camera_calib = np.zeros((3, 4))\n            camera_calib[0, 0] = camera.intrinsic[0]\n            camera_calib[1, 1] = camera.intrinsic[1]\n            camera_calib[0, 2] = camera.intrinsic[2]\n            camera_calib[1, 2] = camera.intrinsic[3]\n            camera_calib[2, 2] = 1\n            camera_calib = list(camera_calib.reshape(12))\n            camera_calib = [f'{i:e}' for i in camera_calib]\n            camera_calibs.append(camera_calib)\n\n        # all camera ids are saved as id-1 in the result because\n        # camera 0 is unknown in the proto\n        for i in range(5):\n            calib_context += 'P' + str(i) + ': ' + \\\n                ' '.join(camera_calibs[i]) + '\\n'\n        calib_context += 'R0_rect' + ': ' + ' '.join(R0_rect) + '\\n'\n        for i in range(5):\n            calib_context += 'Tr_velo_to_cam_' + str(i) + ': ' + \\\n                ' '.join(Tr_velo_to_cams[i]) + '\\n'\n\n        with open(\n                f'{self.calib_save_dir}/{self.prefix}' +\n                f'{str(file_idx).zfill(3)}{str(frame_idx).zfill(3)}.txt',\n                'w+') as fp_calib:\n            fp_calib.write(calib_context)\n            fp_calib.close()\n\n    def save_lidar(self, frame, file_idx, frame_idx):\n        \"\"\"Parse and save the lidar data in psd format.\n\n        Args:\n            frame (:obj:`Frame`): Open dataset frame proto.\n            file_idx (int): Current file index.\n            frame_idx (int): Current frame index.\n        \"\"\"\n        range_images, camera_projections, range_image_top_pose = \\\n            parse_range_image_and_camera_projection(frame)\n\n        # First return\n        points_0, cp_points_0, intensity_0, elongation_0 = \\\n            self.convert_range_image_to_point_cloud(\n                frame,\n                range_images,\n                camera_projections,\n                range_image_top_pose,\n                ri_index=0\n            )\n        points_0 = np.concatenate(points_0, axis=0)\n        intensity_0 = np.concatenate(intensity_0, axis=0)\n        elongation_0 = np.concatenate(elongation_0, axis=0)\n\n        # Second return\n        points_1, cp_points_1, intensity_1, elongation_1 = \\\n            self.convert_range_image_to_point_cloud(\n                frame,\n                range_images,\n                camera_projections,\n                range_image_top_pose,\n                ri_index=1\n            )\n        points_1 = np.concatenate(points_1, axis=0)\n        intensity_1 = np.concatenate(intensity_1, axis=0)\n        elongation_1 = np.concatenate(elongation_1, axis=0)\n\n        points = np.concatenate([points_0, points_1], axis=0)\n        intensity = np.concatenate([intensity_0, intensity_1], axis=0)\n        elongation = np.concatenate([elongation_0, elongation_1], axis=0)\n        timestamp = frame.timestamp_micros * np.ones_like(intensity)\n\n        # concatenate x,y,z, intensity, elongation, timestamp (6-dim)\n        point_cloud = np.column_stack(\n            (points, intensity, elongation, timestamp))\n\n        pc_path = f'{self.point_cloud_save_dir}/{self.prefix}' + \\\n            f'{str(file_idx).zfill(3)}{str(frame_idx).zfill(3)}.bin'\n        point_cloud.astype(np.float32).tofile(pc_path)\n\n    def save_label(self, frame, file_idx, frame_idx):\n        \"\"\"Parse and save the label data in txt format.\n        The relation between waymo and kitti coordinates is noteworthy:\n        1. x, y, z correspond to l, w, h (waymo) -> l, h, w (kitti)\n        2. x-y-z: front-left-up (waymo) -> right-down-front(kitti)\n        3. bbox origin at volumetric center (waymo) -> bottom center (kitti)\n        4. rotation: +x around y-axis (kitti) -> +x around z-axis (waymo)\n\n        Args:\n            frame (:obj:`Frame`): Open dataset frame proto.\n            file_idx (int): Current file index.\n            frame_idx (int): Current frame index.\n        \"\"\"\n        fp_label_all = open(\n            f'{self.label_all_save_dir}/{self.prefix}' +\n            f'{str(file_idx).zfill(3)}{str(frame_idx).zfill(3)}.txt', 'w+')\n        id_to_bbox = dict()\n        id_to_name = dict()\n        for labels in frame.projected_lidar_labels:\n            name = labels.name\n            for label in labels.labels:\n                # TODO: need a workaround as bbox may not belong to front cam\n                bbox = [\n                    label.box.center_x - label.box.length / 2,\n                    label.box.center_y - label.box.width / 2,\n                    label.box.center_x + label.box.length / 2,\n                    label.box.center_y + label.box.width / 2\n                ]\n                id_to_bbox[label.id] = bbox\n                id_to_name[label.id] = name - 1\n\n        for obj in frame.laser_labels:\n            bounding_box = None\n            name = None\n            id = obj.id\n            for lidar in self.lidar_list:\n                if id + lidar in id_to_bbox:\n                    bounding_box = id_to_bbox.get(id + lidar)\n                    name = str(id_to_name.get(id + lidar))\n                    break\n\n            if bounding_box is None or name is None:\n                name = '0'\n                bounding_box = (0, 0, 0, 0)\n\n            my_type = self.type_list[obj.type]\n\n            if my_type not in self.selected_waymo_classes:\n                continue\n\n            if self.filter_empty_3dboxes and obj.num_lidar_points_in_box < 1:\n                continue\n\n            my_type = self.waymo_to_kitti_class_map[my_type]\n\n            height = obj.box.height\n            width = obj.box.width\n            length = obj.box.length\n\n            x = obj.box.center_x\n            y = obj.box.center_y\n            z = obj.box.center_z - height / 2\n\n            # project bounding box to the virtual reference frame\n            pt_ref = self.T_velo_to_front_cam @ \\\n                np.array([x, y, z, 1]).reshape((4, 1))\n            x, y, z, _ = pt_ref.flatten().tolist()\n\n            rotation_y = -obj.box.heading - np.pi / 2\n            track_id = obj.id\n\n            # not available\n            truncated = 0\n            occluded = 0\n            alpha = -10\n\n            line = my_type + \\\n                ' {} {} {} {} {} {} {} {} {} {} {} {} {} {}\\n'.format(\n                    round(truncated, 2), occluded, round(alpha, 2),\n                    round(bounding_box[0], 2), round(bounding_box[1], 2),\n                    round(bounding_box[2], 2), round(bounding_box[3], 2),\n                    round(height, 2), round(width, 2), round(length, 2),\n                    round(x, 2), round(y, 2), round(z, 2),\n                    round(rotation_y, 2))\n\n            if self.save_track_id:\n                line_all = line[:-1] + ' ' + name + ' ' + track_id + '\\n'\n            else:\n                line_all = line[:-1] + ' ' + name + '\\n'\n\n            fp_label = open(\n                f'{self.label_save_dir}{name}/{self.prefix}' +\n                f'{str(file_idx).zfill(3)}{str(frame_idx).zfill(3)}.txt', 'a')\n            fp_label.write(line)\n            fp_label.close()\n\n            fp_label_all.write(line_all)\n\n        fp_label_all.close()\n\n    def save_pose(self, frame, file_idx, frame_idx):\n        \"\"\"Parse and save the pose data.\n\n        Note that SDC's own pose is not included in the regular training\n        of KITTI dataset. KITTI raw dataset contains ego motion files\n        but are not often used. Pose is important for algorithms that\n        take advantage of the temporal information.\n\n        Args:\n            frame (:obj:`Frame`): Open dataset frame proto.\n            file_idx (int): Current file index.\n            frame_idx (int): Current frame index.\n        \"\"\"\n        pose = np.array(frame.pose.transform).reshape(4, 4)\n        np.savetxt(\n            join(f'{self.pose_save_dir}/{self.prefix}' +\n                 f'{str(file_idx).zfill(3)}{str(frame_idx).zfill(3)}.txt'),\n            pose)\n\n    def create_folder(self):\n        \"\"\"Create folder for data preprocessing.\"\"\"\n        if not self.test_mode:\n            dir_list1 = [\n                self.label_all_save_dir, self.calib_save_dir,\n                self.point_cloud_save_dir, self.pose_save_dir\n            ]\n            dir_list2 = [self.label_save_dir, self.image_save_dir]\n        else:\n            dir_list1 = [\n                self.calib_save_dir, self.point_cloud_save_dir,\n                self.pose_save_dir\n            ]\n            dir_list2 = [self.image_save_dir]\n        for d in dir_list1:\n            mmcv.mkdir_or_exist(d)\n        for d in dir_list2:\n            for i in range(5):\n                mmcv.mkdir_or_exist(f'{d}{str(i)}')\n\n    def convert_range_image_to_point_cloud(self,\n                                           frame,\n                                           range_images,\n                                           camera_projections,\n                                           range_image_top_pose,\n                                           ri_index=0):\n        \"\"\"Convert range images to point cloud.\n\n        Args:\n            frame (:obj:`Frame`): Open dataset frame.\n            range_images (dict): Mapping from laser_name to list of two\n                range images corresponding with two returns.\n            camera_projections (dict): Mapping from laser_name to list of two\n                camera projections corresponding with two returns.\n            range_image_top_pose (:obj:`Transform`): Range image pixel pose for\n                top lidar.\n            ri_index (int): 0 for the first return, 1 for the second return.\n                Default: 0.\n\n        Returns:\n            tuple[list[np.ndarray]]: (List of points with shape [N, 3],\n                camera projections of points with shape [N, 6], intensity\n                with shape [N, 1], elongation with shape [N, 1]). All the\n                lists have the length of lidar numbers (5).\n        \"\"\"\n        calibrations = sorted(\n            frame.context.laser_calibrations, key=lambda c: c.name)\n        points = []\n        cp_points = []\n        intensity = []\n        elongation = []\n\n        frame_pose = tf.convert_to_tensor(\n            value=np.reshape(np.array(frame.pose.transform), [4, 4]))\n        # [H, W, 6]\n        range_image_top_pose_tensor = tf.reshape(\n            tf.convert_to_tensor(value=range_image_top_pose.data),\n            range_image_top_pose.shape.dims)\n        # [H, W, 3, 3]\n        range_image_top_pose_tensor_rotation = \\\n            transform_utils.get_rotation_matrix(\n                range_image_top_pose_tensor[..., 0],\n                range_image_top_pose_tensor[..., 1],\n                range_image_top_pose_tensor[..., 2])\n        range_image_top_pose_tensor_translation = \\\n            range_image_top_pose_tensor[..., 3:]\n        range_image_top_pose_tensor = transform_utils.get_transform(\n            range_image_top_pose_tensor_rotation,\n            range_image_top_pose_tensor_translation)\n        for c in calibrations:\n            range_image = range_images[c.name][ri_index]\n            if len(c.beam_inclinations) == 0:\n                beam_inclinations = range_image_utils.compute_inclination(\n                    tf.constant(\n                        [c.beam_inclination_min, c.beam_inclination_max]),\n                    height=range_image.shape.dims[0])\n            else:\n                beam_inclinations = tf.constant(c.beam_inclinations)\n\n            beam_inclinations = tf.reverse(beam_inclinations, axis=[-1])\n            extrinsic = np.reshape(np.array(c.extrinsic.transform), [4, 4])\n\n            range_image_tensor = tf.reshape(\n                tf.convert_to_tensor(value=range_image.data),\n                range_image.shape.dims)\n            pixel_pose_local = None\n            frame_pose_local = None\n            if c.name == dataset_pb2.LaserName.TOP:\n                pixel_pose_local = range_image_top_pose_tensor\n                pixel_pose_local = tf.expand_dims(pixel_pose_local, axis=0)\n                frame_pose_local = tf.expand_dims(frame_pose, axis=0)\n            range_image_mask = range_image_tensor[..., 0] > 0\n\n            if self.filter_no_label_zone_points:\n                nlz_mask = range_image_tensor[..., 3] != 1.0  # 1.0: in NLZ\n                range_image_mask = range_image_mask & nlz_mask\n\n            range_image_cartesian = \\\n                range_image_utils.extract_point_cloud_from_range_image(\n                    tf.expand_dims(range_image_tensor[..., 0], axis=0),\n                    tf.expand_dims(extrinsic, axis=0),\n                    tf.expand_dims(tf.convert_to_tensor(\n                        value=beam_inclinations), axis=0),\n                    pixel_pose=pixel_pose_local,\n                    frame_pose=frame_pose_local)\n\n            range_image_cartesian = tf.squeeze(range_image_cartesian, axis=0)\n            points_tensor = tf.gather_nd(range_image_cartesian,\n                                         tf.compat.v1.where(range_image_mask))\n\n            cp = camera_projections[c.name][ri_index]\n            cp_tensor = tf.reshape(\n                tf.convert_to_tensor(value=cp.data), cp.shape.dims)\n            cp_points_tensor = tf.gather_nd(\n                cp_tensor, tf.compat.v1.where(range_image_mask))\n            points.append(points_tensor.numpy())\n            cp_points.append(cp_points_tensor.numpy())\n\n            intensity_tensor = tf.gather_nd(range_image_tensor[..., 1],\n                                            tf.where(range_image_mask))\n            intensity.append(intensity_tensor.numpy())\n\n            elongation_tensor = tf.gather_nd(range_image_tensor[..., 2],\n                                             tf.where(range_image_mask))\n            elongation.append(elongation_tensor.numpy())\n\n        return points, cp_points, intensity, elongation\n\n    def cart_to_homo(self, mat):\n        \"\"\"Convert transformation matrix in Cartesian coordinates to\n        homogeneous format.\n\n        Args:\n            mat (np.ndarray): Transformation matrix in Cartesian.\n                The input matrix shape is 3x3 or 3x4.\n\n        Returns:\n            np.ndarray: Transformation matrix in homogeneous format.\n                The matrix shape is 4x4.\n        \"\"\"\n        ret = np.eye(4)\n        if mat.shape == (3, 3):\n            ret[:3, :3] = mat\n        elif mat.shape == (3, 4):\n            ret[:3, :] = mat\n        else:\n            raise ValueError(mat.shape)\n        return ret\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/dist_test.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nPORT=${PORT:-29203}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/test.py $CONFIG $CHECKPOINT --launcher pytorch ${@:4} --eval bbox\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-38912}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/fp16/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28508}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3} --deterministic\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/fp16/train.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\n\nimport argparse\nimport copy\nimport mmcv\nimport os\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist, wrap_fp16_model\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet3d import __version__ as mmdet3d_version\n#from mmdet3d.apis import train_model\n\nfrom mmdet3d.datasets import build_dataset\nfrom mmdet3d.models import build_model\nfrom mmdet3d.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom mmseg import __version__ as mmseg_version\n\nfrom mmcv.utils import TORCH_VERSION, digit_version\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Train a detector')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument('--work-dir', help='the dir to save logs and models')\n    parser.add_argument(\n        '--resume-from', help='the checkpoint file to resume from')\n    parser.add_argument(\n        '--no-validate',\n        action='store_true',\n        help='whether not to evaluate the checkpoint during training')\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        '--gpus',\n        type=int,\n        help='number of gpus to use '\n        '(only applicable to non-distributed training)')\n    group_gpus.add_argument(\n        '--gpu-ids',\n        type=int,\n        nargs='+',\n        help='ids of gpus to use '\n        '(only applicable to non-distributed training)')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file (deprecate), '\n        'change to --cfg-options instead.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local_rank', type=int, default=0)\n    parser.add_argument(\n        '--autoscale-lr',\n        action='store_true',\n        help='automatically scale lr with the number of gpus')\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            '--options and --cfg-options cannot be both specified, '\n            '--options is deprecated in favor of --cfg-options')\n    if args.options:\n        warnings.warn('--options is deprecated in favor of --cfg-options')\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, 'plugin'):\n        if cfg.plugin:\n            import importlib\n            if hasattr(cfg, 'plugin_dir'):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split('/')\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + '.' + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split('/')\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + '.' + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            \n            from projects.mmdet3d_plugin.bevformer.apis import custom_train_model\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0])\n    #if args.resume_from is not None:\n\n    if args.resume_from is not None and osp.isfile(args.resume_from): \n        cfg.resume_from = args.resume_from\n\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n    if digit_version(TORCH_VERSION) != digit_version('1.8.1'):\n        cfg.optimizer['type'] = 'AdamW'\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer['lr'] = cfg.optimizer['lr'] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        assert False, 'DOT NOT SUPPORT!!!'\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime())\n    log_file = osp.join(cfg.work_dir, f'{timestamp}.log')\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    if cfg.model.type in ['EncoderDecoder3D']:\n        logger_name = 'mmseg'\n    else:\n        logger_name = 'mmdet'\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level, name=logger_name)\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = '\\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()])\n    dash_line = '-' * 60 + '\\n'\n    logger.info('Environment info:\\n' + dash_line + env_info + '\\n' +\n                dash_line)\n    meta['env_info'] = env_info\n    meta['config'] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f'Distributed training: {distributed}')\n    logger.info(f'Config:\\n{cfg.pretty_text}')\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(f'Set random seed to {args.seed}, '\n                    f'deterministic: {args.deterministic}')\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta['seed'] = args.seed\n    meta['exp_name'] = osp.basename(args.config)\n\n    model = build_model(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    model.init_weights()\n\n    eval_model_config = copy.deepcopy(cfg.model)\n    eval_model = build_model(\n        eval_model_config,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    \n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(eval_model)\n\n    #eval_model.init_weights()\n    eval_model.load_state_dict(model.state_dict())\n\n    logger.info(f'Model:\\n{model}')\n    from projects.mmdet3d_plugin.datasets import custom_build_dataset\n    datasets = [custom_build_dataset(cfg.data.train)]\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if 'dataset' in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(custom_build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            mmseg_version=mmseg_version,\n            mmdet3d_version=mmdet3d_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n            PALETTE=datasets[0].PALETTE  # for segmentors\n            if hasattr(datasets[0], 'PALETTE') else None)\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    custom_train_model(\n        model,\n        datasets,\n        cfg,\n        eval_model=eval_model,\n        distributed=distributed,\n        validate=(not args.no_validate),\n        timestamp=timestamp,\n        meta=meta)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/misc/browse_dataset.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport numpy as np\nimport warnings\nfrom mmcv import Config, DictAction, mkdir_or_exist, track_iter_progress\nfrom os import path as osp\n\nfrom mmdet3d.core.bbox import (Box3DMode, CameraInstance3DBoxes, Coord3DMode,\n                               DepthInstance3DBoxes, LiDARInstance3DBoxes)\nfrom mmdet3d.core.visualizer import (show_multi_modality_result, show_result,\n                                     show_seg_result)\nfrom mmdet3d.datasets import build_dataset\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Browse a dataset')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument(\n        '--skip-type',\n        type=str,\n        nargs='+',\n        default=['Normalize'],\n        help='skip some useless pipeline')\n    parser.add_argument(\n        '--output-dir',\n        default=None,\n        type=str,\n        help='If there is no display interface, you can save it')\n    parser.add_argument(\n        '--task',\n        type=str,\n        choices=['det', 'seg', 'multi_modality-det', 'mono-det'],\n        help='Determine the visualization method depending on the task.')\n    parser.add_argument(\n        '--online',\n        action='store_true',\n        help='Whether to perform online visualization. Note that you often '\n        'need a monitor to do so.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    args = parser.parse_args()\n    return args\n\n\ndef build_data_cfg(config_path, skip_type, cfg_options):\n    \"\"\"Build data config for loading visualization data.\"\"\"\n    cfg = Config.fromfile(config_path)\n    if cfg_options is not None:\n        cfg.merge_from_dict(cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n    # extract inner dataset of `RepeatDataset` as `cfg.data.train`\n    # so we don't need to worry about it later\n    if cfg.data.train['type'] == 'RepeatDataset':\n        cfg.data.train = cfg.data.train.dataset\n    # use only first dataset for `ConcatDataset`\n    if cfg.data.train['type'] == 'ConcatDataset':\n        cfg.data.train = cfg.data.train.datasets[0]\n    train_data_cfg = cfg.data.train\n    # eval_pipeline purely consists of loading functions\n    # use eval_pipeline for data loading\n    train_data_cfg['pipeline'] = [\n        x for x in cfg.eval_pipeline if x['type'] not in skip_type\n    ]\n\n    return cfg\n\n\ndef to_depth_mode(points, bboxes):\n    \"\"\"Convert points and bboxes to Depth Coord and Depth Box mode.\"\"\"\n    if points is not None:\n        points = Coord3DMode.convert_point(points.copy(), Coord3DMode.LIDAR,\n                                           Coord3DMode.DEPTH)\n    if bboxes is not None:\n        bboxes = Box3DMode.convert(bboxes.clone(), Box3DMode.LIDAR,\n                                   Box3DMode.DEPTH)\n    return points, bboxes\n\n\ndef show_det_data(idx, dataset, out_dir, filename, show=False):\n    \"\"\"Visualize 3D point cloud and 3D bboxes.\"\"\"\n    example = dataset.prepare_train_data(idx)\n    points = example['points']._data.numpy()\n    gt_bboxes = dataset.get_ann_info(idx)['gt_bboxes_3d'].tensor\n    if dataset.box_mode_3d != Box3DMode.DEPTH:\n        points, gt_bboxes = to_depth_mode(points, gt_bboxes)\n    show_result(\n        points,\n        gt_bboxes.clone(),\n        None,\n        out_dir,\n        filename,\n        show=show,\n        snapshot=True)\n\n\ndef show_seg_data(idx, dataset, out_dir, filename, show=False):\n    \"\"\"Visualize 3D point cloud and segmentation mask.\"\"\"\n    example = dataset.prepare_train_data(idx)\n    points = example['points']._data.numpy()\n    gt_seg = example['pts_semantic_mask']._data.numpy()\n    show_seg_result(\n        points,\n        gt_seg.copy(),\n        None,\n        out_dir,\n        filename,\n        np.array(dataset.PALETTE),\n        dataset.ignore_index,\n        show=show,\n        snapshot=True)\n\n\ndef show_proj_bbox_img(idx,\n                       dataset,\n                       out_dir,\n                       filename,\n                       show=False,\n                       is_nus_mono=False):\n    \"\"\"Visualize 3D bboxes on 2D image by projection.\"\"\"\n    try:\n        example = dataset.prepare_train_data(idx)\n    except AttributeError:  # for Mono-3D datasets\n        example = dataset.prepare_train_img(idx)\n    gt_bboxes = dataset.get_ann_info(idx)['gt_bboxes_3d']\n    img_metas = example['img_metas']._data\n    img = example['img']._data.numpy()\n    # need to transpose channel to first dim\n    img = img.transpose(1, 2, 0)\n    # no 3D gt bboxes, just show img\n    if gt_bboxes.tensor.shape[0] == 0:\n        gt_bboxes = None\n    if isinstance(gt_bboxes, DepthInstance3DBoxes):\n        show_multi_modality_result(\n            img,\n            gt_bboxes,\n            None,\n            None,\n            out_dir,\n            filename,\n            box_mode='depth',\n            img_metas=img_metas,\n            show=show)\n    elif isinstance(gt_bboxes, LiDARInstance3DBoxes):\n        show_multi_modality_result(\n            img,\n            gt_bboxes,\n            None,\n            img_metas['lidar2img'],\n            out_dir,\n            filename,\n            box_mode='lidar',\n            img_metas=img_metas,\n            show=show)\n    elif isinstance(gt_bboxes, CameraInstance3DBoxes):\n        show_multi_modality_result(\n            img,\n            gt_bboxes,\n            None,\n            img_metas['cam2img'],\n            out_dir,\n            filename,\n            box_mode='camera',\n            img_metas=img_metas,\n            show=show)\n    else:\n        # can't project, just show img\n        warnings.warn(\n            f'unrecognized gt box type {type(gt_bboxes)}, only show image')\n        show_multi_modality_result(\n            img, None, None, None, out_dir, filename, show=show)\n\n\ndef main():\n    args = parse_args()\n\n    if args.output_dir is not None:\n        mkdir_or_exist(args.output_dir)\n\n    cfg = build_data_cfg(args.config, args.skip_type, args.cfg_options)\n    try:\n        dataset = build_dataset(\n            cfg.data.train, default_args=dict(filter_empty_gt=False))\n    except TypeError:  # seg dataset doesn't have `filter_empty_gt` key\n        dataset = build_dataset(cfg.data.train)\n    data_infos = dataset.data_infos\n    dataset_type = cfg.dataset_type\n\n    # configure visualization mode\n    vis_task = args.task  # 'det', 'seg', 'multi_modality-det', 'mono-det'\n\n    for idx, data_info in enumerate(track_iter_progress(data_infos)):\n        if dataset_type in ['KittiDataset', 'WaymoDataset']:\n            data_path = data_info['point_cloud']['velodyne_path']\n        elif dataset_type in [\n                'ScanNetDataset', 'SUNRGBDDataset', 'ScanNetSegDataset',\n                'S3DISSegDataset', 'S3DISDataset'\n        ]:\n            data_path = data_info['pts_path']\n        elif dataset_type in ['NuScenesDataset', 'LyftDataset']:\n            data_path = data_info['lidar_path']\n        elif dataset_type in ['NuScenesMonoDataset']:\n            data_path = data_info['file_name']\n        else:\n            raise NotImplementedError(\n                f'unsupported dataset type {dataset_type}')\n\n        file_name = osp.splitext(osp.basename(data_path))[0]\n\n        if vis_task in ['det', 'multi_modality-det']:\n            # show 3D bboxes on 3D point clouds\n            show_det_data(\n                idx, dataset, args.output_dir, file_name, show=args.online)\n        if vis_task in ['multi_modality-det', 'mono-det']:\n            # project 3D bboxes to 2D image\n            show_proj_bbox_img(\n                idx,\n                dataset,\n                args.output_dir,\n                file_name,\n                show=args.online,\n                is_nus_mono=(dataset_type == 'NuScenesMonoDataset'))\n        elif vis_task in ['seg']:\n            # show 3D segmentation mask on 3D point clouds\n            show_seg_data(\n                idx, dataset, args.output_dir, file_name, show=args.online)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/misc/print_config.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nfrom mmcv import Config, DictAction\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Print the whole config')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument(\n        '--options', nargs='+', action=DictAction, help='arguments in dict')\n    args = parser.parse_args()\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.options is not None:\n        cfg.merge_from_dict(args.options)\n    print(f'Config:\\n{cfg.pretty_text}')\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/misc/visualize_results.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport mmcv\nfrom mmcv import Config\n\nfrom mmdet3d.datasets import build_dataset\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet3D visualize the results')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--result', help='results file in pickle format')\n    parser.add_argument(\n        '--show-dir', help='directory where visualize results will be saved')\n    args = parser.parse_args()\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    if args.result is not None and \\\n            not args.result.endswith(('.pkl', '.pickle')):\n        raise ValueError('The results file must be a pkl file.')\n\n    cfg = Config.fromfile(args.config)\n    cfg.data.test.test_mode = True\n\n    # build the dataset\n    dataset = build_dataset(cfg.data.test)\n    results = mmcv.load(args.result)\n\n    if getattr(dataset, 'show', None) is not None:\n        # data loading pipeline for showing\n        eval_pipeline = cfg.get('eval_pipeline', {})\n        if eval_pipeline:\n            dataset.show(results, args.show_dir, pipeline=eval_pipeline)\n        else:\n            dataset.show(results, args.show_dir)  # use default pipeline\n    else:\n        raise NotImplementedError(\n            'Show is not implemented for dataset {}!'.format(\n                type(dataset).__name__))\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/__init__.py",
    "content": "from .hooks import *\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/apis/__init__.py",
    "content": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector\n# from .test import custom_multi_gpu_test"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/apis/mmdet_train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport random\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom torch.nn import DataParallel\nfrom torch.nn.parallel.distributed import DistributedDataParallel\nfrom mmcv.runner import (HOOKS, DistSamplerSeedHook, EpochBasedRunner,\n                         Fp16OptimizerHook, OptimizerHook,\n                         build_runner, )\nfrom mmcv.optims import build_optimizer\nfrom mmcv.utils import build_from_cfg\n\nfrom mmcv.core import EvalHook\n\nfrom mmcv.datasets import (build_dataset, replace_ImageToTensor)\nfrom mmcv.utils import get_root_logger, get_dist_info\nimport time\nimport os.path as osp\nfrom mmcv.datasets import build_dataloader\nfrom mmcv.core.evaluation.eval_hooks import CustomDistEvalHook\nfrom adzoo.bevformer.apis.test import custom_multi_gpu_test\n\ndef custom_train_detector(model,\n                   dataset,\n                   cfg,\n                   distributed=False,\n                   validate=False,\n                   timestamp=None,\n                   eval_model=None,\n                   meta=None):\n    logger = get_root_logger(cfg.log_level)\n\n    # prepare data loaders\n   \n    dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]\n    #assert len(dataset)==1s\n    if 'imgs_per_gpu' in cfg.data:\n        logger.warning('\"imgs_per_gpu\" is deprecated in MMDet V2.0. '\n                       'Please use \"samples_per_gpu\" instead')\n        if 'samples_per_gpu' in cfg.data:\n            logger.warning(\n                f'Got \"imgs_per_gpu\"={cfg.data.imgs_per_gpu} and '\n                f'\"samples_per_gpu\"={cfg.data.samples_per_gpu}, \"imgs_per_gpu\"'\n                f'={cfg.data.imgs_per_gpu} is used in this experiments')\n        else:\n            logger.warning(\n                'Automatically set \"samples_per_gpu\"=\"imgs_per_gpu\"='\n                f'{cfg.data.imgs_per_gpu} in this experiments')\n        cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu\n\n    data_loaders = [\n        build_dataloader(\n            ds,\n            cfg.data.samples_per_gpu,\n            cfg.data.workers_per_gpu,\n            # cfg.gpus will be ignored if distributed\n            len(cfg.gpu_ids),\n            dist=distributed,\n            seed=cfg.seed,\n            shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n            nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n        ) for ds in dataset\n    ]\n    \n    # import ipdb\n    # ipdb.set_trace()\n    # put model on gpus\n    if distributed:\n        find_unused_parameters = cfg.get('find_unused_parameters', False)\n        # Sets the `find_unused_parameters` parameter in\n        # torch.nn.parallel.DistributedDataParallel\n        model = DistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n            find_unused_parameters=find_unused_parameters)\n        if eval_model is not None:\n            eval_model = DistributedDataParallel(\n                eval_model.cuda(),\n                device_ids=[torch.cuda.current_device()],\n                broadcast_buffers=False,\n                find_unused_parameters=find_unused_parameters)\n    else:\n        model = DataParallel(\n            model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n        if eval_model is not None:\n            eval_model = DataParallel(\n                eval_model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n\n    # build runner\n    optimizer = build_optimizer(model, cfg.optimizer)\n\n    if 'runner' not in cfg:\n        cfg.runner = {\n            'type': 'EpochBasedRunner',\n            'max_epochs': cfg.total_epochs\n        }\n        warnings.warn(\n            'config is now expected to have a `runner` section, '\n            'please set `runner` in your config.', UserWarning)\n    else:\n        if 'total_epochs' in cfg:\n            assert cfg.total_epochs == cfg.runner.max_epochs\n    if eval_model is not None:\n        runner = build_runner(\n            cfg.runner,\n            default_args=dict(\n                model=model,\n                eval_model=eval_model,\n                optimizer=optimizer,\n                work_dir=cfg.work_dir,\n                logger=logger,\n                meta=meta))\n    else:\n        runner = build_runner(\n            cfg.runner,\n            default_args=dict(\n                model=model,\n                optimizer=optimizer,\n                work_dir=cfg.work_dir,\n                logger=logger,\n                meta=meta))\n\n    # an ugly workaround to make .log and .log.json filenames the same\n    runner.timestamp = timestamp\n\n    # fp16 setting\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        optimizer_config = Fp16OptimizerHook(\n            **cfg.optimizer_config, **fp16_cfg, distributed=distributed)\n    elif distributed and 'type' not in cfg.optimizer_config:\n        optimizer_config = OptimizerHook(**cfg.optimizer_config)\n    else:\n        optimizer_config = cfg.optimizer_config\n\n    # register hooks\n    runner.register_training_hooks(cfg.lr_config, optimizer_config,\n                                   cfg.checkpoint_config, cfg.log_config,\n                                   cfg.get('momentum_config', None))\n    \n    # register profiler hook\n    #trace_config = dict(type='tb_trace', dir_name='work_dir')\n    #profiler_config = dict(on_trace_ready=trace_config)\n    #runner.register_profiler_hook(profiler_config)\n    \n    if distributed:\n        if isinstance(runner, EpochBasedRunner):\n            runner.register_hook(DistSamplerSeedHook())\n\n    # register eval hooks\n    if validate:\n        # Support batch_size > 1 in validation\n        val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1)\n        if val_samples_per_gpu > 1:\n            assert False\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.val.pipeline = replace_ImageToTensor(\n                cfg.data.val.pipeline)\n        val_dataset = build_dataset(cfg.data.val, dict(test_mode=True))\n\n        val_dataloader = build_dataloader(\n            val_dataset,\n            samples_per_gpu=val_samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n            nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n        )\n        eval_cfg = cfg.get('evaluation', {})\n        eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner'\n        eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_'))\n        eval_hook = CustomDistEvalHook if distributed else EvalHook\n        runner.register_hook(eval_hook(val_dataloader, test_fn=custom_multi_gpu_test, **eval_cfg))\n\n    # user-defined hooks\n    if cfg.get('custom_hooks', None):\n        custom_hooks = cfg.custom_hooks\n        assert isinstance(custom_hooks, list), \\\n            f'custom_hooks expect list type, but got {type(custom_hooks)}'\n        for hook_cfg in cfg.custom_hooks:\n            assert isinstance(hook_cfg, dict), \\\n                'Each item in custom_hooks expects dict type, but got ' \\\n                f'{type(hook_cfg)}'\n            hook_cfg = hook_cfg.copy()\n            priority = hook_cfg.pop('priority', 'NORMAL')\n            hook = build_from_cfg(hook_cfg, HOOKS)\n            runner.register_hook(hook, priority=priority)\n\n    if cfg.resume_from:\n        runner.resume(cfg.resume_from)\n    elif cfg.load_from:\n        runner.load_checkpoint(cfg.load_from)\n    runner.run(data_loaders, cfg.workflow)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/apis/test.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport os.path as osp\nimport pickle\nimport shutil\nimport tempfile\nimport time\n\nimport mmcv\nimport torch\nimport torch.distributed as dist\nfrom mmcv.image import tensor2imgs\nfrom mmcv.runner import get_dist_info\n\nfrom mmdet.core import encode_mask_results\n\n\nimport mmcv\nimport numpy as np\nimport pycocotools.mask as mask_util\n\ndef custom_encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code. Semantic Masks only\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = []\n    for i in range(len(cls_segms)):\n        encoded_mask_results.append(\n            mask_util.encode(\n                np.array(\n                    cls_segms[i][:, :, np.newaxis], order='F',\n                        dtype='uint8'))[0])  # encoded with RLE\n    return [encoded_mask_results]\n\ndef custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):\n    \"\"\"Test model with multiple gpus.\n    This method tests model with multiple gpus and collects the results\n    under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'\n    it encodes results to gpu tensors and use gpu communication for results\n    collection. On cpu mode it saves the results on different gpus to 'tmpdir'\n    and collects them by the rank 0 worker.\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        tmpdir (str): Path of directory to save the temporary results from\n            different gpus under cpu mode.\n        gpu_collect (bool): Option to use either gpu or cpu to collect results.\n    Returns:\n        list: The prediction results.\n    \"\"\"\n    model.eval()\n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    rank, world_size = get_dist_info()\n    if rank == 0:\n        prog_bar = mmcv.ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(return_loss=False, rescale=True, **data)\n            # encode mask results\n            if isinstance(result, dict):\n                if 'bbox_results' in result.keys():\n                    bbox_result = result['bbox_results']\n                    batch_size = len(result['bbox_results'])\n                    bbox_results.extend(bbox_result)\n                if 'mask_results' in result.keys() and result['mask_results'] is not None:\n                    mask_result = custom_encode_mask_results(result['mask_results'])\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n\n            #if isinstance(result[0], tuple):\n            #    assert False, 'this code is for instance segmentation, which our code will not utilize.'\n            #    result = [(bbox_results, encode_mask_results(mask_results))\n            #              for bbox_results, mask_results in result]\n        if rank == 0:\n            \n            for _ in range(batch_size * world_size):\n                prog_bar.update()\n\n    # collect results from all ranks\n    if gpu_collect:\n        bbox_results = collect_results_gpu(bbox_results, len(dataset))\n        if have_mask:\n            mask_results = collect_results_gpu(mask_results, len(dataset))\n        else:\n            mask_results = None\n    else:\n        bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)\n        tmpdir = tmpdir+'_mask' if tmpdir is not None else None\n        if have_mask:\n            mask_results = collect_results_cpu(mask_results, len(dataset), tmpdir)\n        else:\n            mask_results = None\n\n    if mask_results is None:\n        return bbox_results\n    return {'bbox_results': bbox_results, 'mask_results': mask_results}\n\n\ndef collect_results_cpu(result_part, size, tmpdir=None):\n    rank, world_size = get_dist_info()\n    # create a tmp dir if it is not specified\n    if tmpdir is None:\n        MAX_LEN = 512\n        # 32 is whitespace\n        dir_tensor = torch.full((MAX_LEN, ),\n                                32,\n                                dtype=torch.uint8,\n                                device='cuda')\n        if rank == 0:\n            mmcv.mkdir_or_exist('.dist_test')\n            tmpdir = tempfile.mkdtemp(dir='.dist_test')\n            tmpdir = torch.tensor(\n                bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda')\n            dir_tensor[:len(tmpdir)] = tmpdir\n        dist.broadcast(dir_tensor, 0)\n        tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()\n    else:\n        mmcv.mkdir_or_exist(tmpdir)\n    # dump the part result to the dir\n    mmcv.dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl'))\n    dist.barrier()\n    # collect all parts\n    if rank != 0:\n        return None\n    else:\n        # load results of all parts from tmp dir\n        part_list = []\n        for i in range(world_size):\n            part_file = osp.join(tmpdir, f'part_{i}.pkl')\n            part_list.append(mmcv.load(part_file))\n        # sort the results\n        ordered_results = []\n        '''\n        bacause we change the sample of the evaluation stage to make sure that each gpu will handle continuous sample,\n        '''\n        #for res in zip(*part_list):\n        for res in part_list:  \n            ordered_results.extend(list(res))\n        # the dataloader may pad some samples\n        ordered_results = ordered_results[:size]\n        # remove tmp dir\n        shutil.rmtree(tmpdir)\n        return ordered_results\n\n\ndef collect_results_gpu(result_part, size):\n    collect_results_cpu(result_part, size)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/apis/train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom .mmdet_train import custom_train_detector\n\ndef custom_train_model(model,\n                dataset,\n                cfg,\n                distributed=False,\n                validate=False,\n                timestamp=None,\n                eval_model=None,\n                meta=None):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in ['EncoderDecoder3D']:\n        assert False\n    else:\n        custom_train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            eval_model=eval_model,\n            meta=meta)\n\n\ndef train_model(model,\n                dataset,\n                cfg,\n                distributed=False,\n                validate=False,\n                timestamp=None,\n                meta=None):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in ['EncoderDecoder3D']:\n        train_segmentor(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta)\n    else:\n        train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/hooks/__init__.py",
    "content": "from .custom_hooks import TransferWeight"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/bevformer/hooks/custom_hooks.py",
    "content": "from mmcv.runner.hooks.hook import HOOKS, Hook\n\n\n@HOOKS.register_module()\nclass TransferWeight(Hook):\n    \n    def __init__(self, every_n_inters=1):\n        self.every_n_inters=every_n_inters\n\n    def after_train_iter(self, runner):\n        if self.every_n_inner_iters(runner, self.every_n_inters):\n            runner.eval_model.load_state_dict(runner.model.state_dict())\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/__init__.py",
    "content": "from .modeling import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/datasets/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/datasets/nuscenes.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\n#import functools\nfrom collections import OrderedDict\n\nimport numpy as np\nimport seaborn as sns\nfrom torch.utils.data import Dataset\nfrom tqdm import tqdm\n\n#from detectron2.data import MetadataCatalog\nfrom mmcv.structures import BoxMode\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.utils.splits import create_splits_scenes\n\n#from tridet.data import collect_dataset_dicts\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.boxes3d import GenericBoxes3D\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.pose import Pose\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.geometry import project_points3d\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.visualization import float_to_uint8_color\n\n#  https://github.com/nutonomy/nuscenes-devkit/blob/9b209638ef3dee6d0cdc5ac700c493747f5b35fe/python-sdk/nuscenes/utils/splits.py#L189\n#     - train/val/test: The standard splits of the nuScenes dataset (700/150/150 scenes).\n#     - mini_train/mini_val: Train and val splits of the mini subset used for visualization and debugging (8/2 scenes).\n#     - train_detect/train_track: Two halves of the train split used for separating the training sets of detector and\n#         tracker if required\nDATASET_NAME_TO_VERSION = {\n    \"nusc_train\": \"v1.0-trainval\",\n    \"nusc_val\": \"v1.0-trainval\",\n    \"nusc_val-subsample-8\": \"v1.0-trainval\",\n    \"nusc_trainval\": \"v1.0-trainval\",\n    \"nusc_test\": \"v1.0-test\",\n    \"nusc_mini_train\": \"v1.0-mini\",\n    \"nusc_mini_val\": \"v1.0-mini\",\n}\n\nCAMERA_NAMES = ('CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT')\n\nATTRIBUTE_IDS = {\n    'vehicle.moving': 0,\n    'vehicle.parked': 1,\n    'vehicle.stopped': 2,\n    'pedestrian.moving': 0,\n    'pedestrian.standing': 1,\n    'pedestrian.sitting_lying_down': 2,\n    'cycle.with_rider': 0,\n    'cycle.without_rider': 1,\n}\n\nCATEGORY_IDS = OrderedDict({\n    'barrier': 0,\n    'bicycle': 1,\n    'bus': 2,\n    'car': 3,\n    'construction_vehicle': 4,\n    'motorcycle': 5,\n    'pedestrian': 6,\n    'traffic_cone': 7,\n    'trailer': 8,\n    'truck': 9,\n})\n\nCOLORS = [float_to_uint8_color(clr) for clr in sns.color_palette(\"bright\", n_colors=10)]\nCOLORMAP = OrderedDict({\n    'barrier': COLORS[8],  # yellow\n    'bicycle': COLORS[0],  # blue\n    'bus': COLORS[6],  # pink\n    'car': COLORS[2],  # green\n    'construction_vehicle': COLORS[7],  # gray\n    'motorcycle': COLORS[4],  # purple\n    'pedestrian': COLORS[1],  # orange\n    'traffic_cone': COLORS[3],  # red\n    'trailer': COLORS[9],  # skyblue\n    'truck': COLORS[5],  # brown\n})\n\nMAX_NUM_ATTRIBUTES = 3\n\n\ndef _compute_iou(box1, box2):\n    \"\"\"\n    Parameters\n    ----------\n    box1, box2:\n        (x1, y1, x2, y2)\n    \"\"\"\n    xx1 = max(box1[0], box2[0])\n    yy1 = max(box1[1], box2[1])\n    xx2 = min(box1[2], box2[2])\n    yy2 = min(box1[3], box2[3])\n    if xx1 >= xx2 or yy1 >= yy2:\n        return 0.\n    inter = (xx2 - xx1) * (yy2 - yy1)\n    a1 = (box1[2] - box1[0]) * (box1[3] - box1[1])\n    a2 = (box2[2] - box2[0]) * (box2[3] - box2[1])\n    return inter / (a1 + a2 - inter)\n\n\nclass NuscenesDataset(Dataset):\n    def __init__(self, name, data_root, datum_names=CAMERA_NAMES, min_num_lidar_points=3, min_box_visibility=0.2, **unused):\n        self.data_root = data_root\n        assert name in DATASET_NAME_TO_VERSION\n        version = DATASET_NAME_TO_VERSION[name]\n        self.nusc = NuScenes(version=version, dataroot=data_root, verbose=True)\n\n        self.datum_names = datum_names\n        self.min_num_lidar_points = min_num_lidar_points\n        self.min_box_visibility = min_box_visibility\n\n        self.dataset_item_info = self._build_dataset_item_info(name)\n\n        # Index instance tokens to their IDs\n        self._instance_token_to_id = self._index_instance_tokens()\n\n        # Construct the mapping from datum_token (image id) to index\n        print(\"Generating the mapping from image id to idx...\")\n        self.datumtoken2idx = {}\n        for idx, (datum_token, _, _, _, _) in enumerate(self.dataset_item_info):\n            self.datumtoken2idx[datum_token] = idx\n        print(\"Done.\")\n\n    def _build_dataset_item_info(self, name):\n        scenes_in_split = self._get_split_scenes(name)\n\n        dataset_items = []\n        for _, scene_token in tqdm(scenes_in_split):\n            scene = self.nusc.get('scene', scene_token)\n            sample_token = scene['first_sample_token']\n            for sample_idx in range(scene['nbr_samples']):\n                if name.endswith('subsample-8') and sample_idx % 8 > 0:\n                    # Sample-level subsampling.\n                    continue\n\n                sample = self.nusc.get('sample', sample_token)\n                for datum_name, datum_token in sample['data'].items():\n                    if datum_name not in self.datum_names:\n                        continue\n                    dataset_items.append((datum_token, sample_token, scene['name'], sample_idx, datum_name))\n                sample_token = sample['next']\n        return dataset_items\n\n    def _get_split_scenes(self, name):\n        scenes_in_splits = create_splits_scenes()\n        if name == \"nusc_trainval\":\n            scenes = scenes_in_splits[\"train\"] + scenes_in_splits[\"val\"]\n        elif name == \"nusc_val-subsample-8\":\n            scenes = scenes_in_splits[\"val\"]\n        else:\n            assert name.startswith('nusc_'), f\"Invalid dataset name: {name}\"\n            split = name[5:]\n            assert split in scenes_in_splits, f\"Invalid dataset: {split}\"\n            scenes = scenes_in_splits[split]\n\n        # Mapping from scene name to token.\n        name_to_token = {scene['name']: scene['token'] for scene in self.nusc.scene}\n        return [(name, name_to_token[name]) for name in scenes]\n\n    def __len__(self):\n        return len(self.dataset_item_info)\n\n    def _build_id(self, scene_name, sample_idx, datum_name):\n        sample_id = f\"{scene_name}_{sample_idx:03d}\"\n        image_id = f\"{sample_id}_{datum_name}\"\n        return image_id, sample_id\n\n    def _index_instance_tokens(self):\n        \"\"\"Index instance tokens for uniquely identifying instances across samples\"\"\"\n        instance_token_to_id = {}\n        for record in self.nusc.sample_annotation:\n            instance_token = record['instance_token']\n            if instance_token not in instance_token_to_id:\n                next_instance_id = len(instance_token_to_id)\n                instance_token_to_id[instance_token] = next_instance_id\n        return instance_token_to_id\n\n    def get_instance_annotations(self, annotation_list, K, image_shape, pose_WS):\n        annotations = []\n        for _ann in annotation_list:\n            ann = self.nusc.get('sample_annotation', _ann.token)\n            if ann['num_lidar_pts'] + ann['num_radar_pts'] < self.min_num_lidar_points:\n                continue\n            annotation = OrderedDict()\n\n            # --------\n            # Category\n            # --------\n            category = category_to_detection_name(ann['category_name'])\n            if category is None:\n                continue\n            annotation['category_id'] = CATEGORY_IDS[category]\n\n            # ------\n            # 3D box\n            # ------\n            # NOTE: ann['rotation'], ann['translation'] is in global frame.\n            pose_SO = Pose(wxyz=_ann.orientation, tvec=_ann.center)  # pose in sensor frame\n            # DEBUG:\n            # pose_WO_1 = Pose(np.array(ann['rotation']), np.array(ann['translation']))\n            # pose_WO_2 = pose_WS * pose_SO\n            # assert np.allclose(pose_WO_1.matrix, pose_WO_2.matrix)\n            bbox3d = GenericBoxes3D(_ann.orientation, _ann.center, _ann.wlh)\n            annotation['bbox3d'] = bbox3d.vectorize().tolist()[0]\n\n            # --------------------------------------\n            # 2D box -- project 8 corners of 3D bbox\n            # --------------------------------------\n            corners = project_points3d(bbox3d.corners.cpu().numpy().squeeze(0), K)\n            l, t = corners[:, 0].min(), corners[:, 1].min()\n            r, b = corners[:, 0].max(), corners[:, 1].max()\n\n            x1 = max(0, l)\n            y1 = max(0, t)\n            x2 = min(image_shape[1], r)\n            y2 = min(image_shape[0], b)\n\n            iou = _compute_iou([l, t, r, b], [x1, y1, x2, y2])\n            if iou < self.min_box_visibility:\n                continue\n\n            annotation['bbox'] = [x1, y1, x2, y2]\n            annotation['bbox_mode'] = BoxMode.XYXY_ABS\n\n            # --------\n            # Track ID\n            # --------\n            annotation['track_id'] = self._instance_token_to_id[ann['instance_token']]\n\n            # ---------\n            # Attribute\n            # ---------\n            attr_tokens = ann['attribute_tokens']\n            assert len(attr_tokens) < 2  # NOTE: Allow only single attrubute.\n            attribute_id = MAX_NUM_ATTRIBUTES  # By default, MAX_NUM_ATTRIBUTES -- this is to be ignored in loss compute.\n            if attr_tokens:\n                attribute = self.nusc.get('attribute', attr_tokens[0])['name']\n                attribute_id = ATTRIBUTE_IDS[attribute]\n            annotation['attribute_id'] = attribute_id\n\n            # -----\n            # Speed\n            # -----\n            vel_global = self.nusc.box_velocity(ann['token'])\n            speed = np.linalg.norm(vel_global)  # NOTE: This can be NaN.\n            # DEBUG:\n            # speed * Quaternion(ann['rotation']).rotation_matrix.T[0] ~= vel_global\n            annotation['speed'] = speed\n\n            annotations.append(annotation)\n\n        return annotations\n\n    def _get_ego_velocity(self, current, max_time_diff=1.5):\n        \"\"\"Velocity of ego-vehicle in m/s.\n        \"\"\"\n        has_prev = current['prev'] != ''\n        has_next = current['next'] != ''\n\n        # Cannot estimate velocity for a single annotation.\n        if not has_prev and not has_next:\n            return np.array([np.nan, np.nan, np.nan])\n\n        if has_prev:\n            first = self.nusc.get('sample_data', current['prev'])\n        else:\n            first = current\n\n        if has_next:\n            last = self.nusc.get('sample_data', current['next'])\n        else:\n            last = current\n\n        pos_first = self.nusc.get('ego_pose', first['ego_pose_token'])['translation']\n        pos_last = self.nusc.get('ego_pose', last['ego_pose_token'])['translation']\n        pos_diff = np.float32(pos_last) - np.float32(pos_first)\n\n        time_last = 1e-6 * last['timestamp']\n        time_first = 1e-6 * first['timestamp']\n        time_diff = time_last - time_first\n\n        if has_next and has_prev:\n            # If doing centered difference, allow for up to double the max_time_diff.\n            max_time_diff *= 2\n\n        if time_diff > max_time_diff:\n            # If time_diff is too big, don't return an estimate.\n            return np.array([np.nan, np.nan, np.nan])\n        else:\n            return pos_diff / time_diff\n\n    def __getitem__(self, idx):\n        datum_token, sample_token, scene_name, sample_idx, datum_name = self.dataset_item_info[idx]\n        datum = self.nusc.get('sample_data', datum_token)\n        assert datum['is_key_frame']\n\n        filename, _annotations, K = self.nusc.get_sample_data(datum_token)\n        image_id, sample_id = self._build_id(scene_name, sample_idx, datum_name)\n        height, width = datum['height'], datum['width']\n        d2_dict = OrderedDict(\n            file_name=filename,\n            height=height,\n            width=width,\n            image_id=image_id,\n            sample_id=sample_id,\n            sample_token=sample_token\n        )\n\n        # Intrinsics\n        d2_dict['intrinsics'] = list(K.flatten())\n\n        # Get pose of the sensor (S) from vehicle (V) frame\n        _pose_VS = self.nusc.get('calibrated_sensor', datum['calibrated_sensor_token'])\n        pose_VS = Pose(wxyz=np.float64(_pose_VS['rotation']), tvec=np.float64(_pose_VS['translation']))\n\n        # Get ego-pose of the vehicle (V) from global/world (W) frame\n        _pose_WV = self.nusc.get('ego_pose', datum['ego_pose_token'])\n        pose_WV = Pose(wxyz=np.float64(_pose_WV['rotation']), tvec=np.float64(_pose_WV['translation']))\n        pose_WS = pose_WV * pose_VS\n\n        d2_dict['pose'] = {'wxyz': list(pose_WS.quat.elements), 'tvec': list(pose_WS.tvec)}\n        d2_dict['extrinsics'] = {'wxyz': list(pose_VS.quat.elements), 'tvec': list(pose_VS.tvec)}\n\n        d2_dict['ego_speed'] = np.linalg.norm(self._get_ego_velocity(datum))\n\n        d2_dict['annotations'] = self.get_instance_annotations(_annotations, K, (height, width), pose_WS)\n\n        return d2_dict\n\n    def getitem_by_datumtoken(self, datum_token):\n        # idx = self.datumtoken2idx[datum_token]\n        # ret = self.__getitem__(idx)\n\n        datum = self.nusc.get('sample_data', datum_token)\n        sample_token = datum['sample_token']\n        filename, _annotations, K = self.nusc.get_sample_data(datum_token)\n        height, width = datum['height'], datum['width']\n        d2_dict = OrderedDict(\n            file_name=filename,\n            height=height,\n            width=width,\n            image_id=0,\n            sample_id=0,\n            sample_token=sample_token\n        )\n        # Intrinsics\n        d2_dict['intrinsics'] = list(K.flatten())\n        # Get pose of the sensor (S) from vehicle (V) frame\n        _pose_VS = self.nusc.get('calibrated_sensor', datum['calibrated_sensor_token'])\n        pose_VS = Pose(wxyz=np.float64(_pose_VS['rotation']), tvec=np.float64(_pose_VS['translation'])) \n        # Get ego-pose of the vehicle (V) from global/world (W) frame\n        _pose_WV = self.nusc.get('ego_pose', datum['ego_pose_token'])\n        pose_WV = Pose(wxyz=np.float64(_pose_WV['rotation']), tvec=np.float64(_pose_WV['translation']))\n        pose_WS = pose_WV * pose_VS\n\n        d2_dict['pose'] = {'wxyz': list(pose_WS.quat.elements), 'tvec': list(pose_WS.tvec)}\n        d2_dict['extrinsics'] = {'wxyz': list(pose_VS.quat.elements), 'tvec': list(pose_VS.tvec)}\n\n        d2_dict['ego_speed'] = np.linalg.norm(self._get_ego_velocity(datum))\n\n        d2_dict['annotations'] = self.get_instance_annotations(_annotations, K, (height, width), pose_WS)\n        return d2_dict"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/datasets/transform_utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved.\n# Copyright 2021 Toyota Research Institute.  All rights reserved.\n# Adapted from detectron2:\n#   https://github.com/facebookresearch/detectron2/blob/master/detectron2/data/detection_utils.py\nimport numpy as np\nimport torch\n\nfrom detectron2.data import transforms as T\nfrom detectron2.structures import Boxes, BoxMode, Instances\n\nfrom projects.mmdet3d_plugin.dd3d.structures.boxes3d import Boxes3D\n\n__all__ = [\"transform_instance_annotations\", \"annotations_to_instances\"]\n\n\ndef transform_instance_annotations(\n    annotation,\n    transforms,\n    image_size,\n):\n    \"\"\"Adapted from:\n        https://github.com/facebookresearch/detectron2/blob/master/detectron2/data/detection_utils.py#L254\n\n    The changes from original:\n        - The presence of 2D bounding box (i.e. \"bbox\" field) is assumed by default in d2; here it's optional.\n        - Add optional 3D bounding box support.\n        - If the instance mask annotation is in RLE, then it's decoded into polygons, not bitmask, to save memory.\n\n    ===============================================================================================================\n\n    Apply transforms to box, segmentation and keypoints annotations of a single instance.\n\n    It will use `transforms.apply_box` for the box, and\n    `transforms.apply_coords` for segmentation polygons & keypoints.\n    If you need anything more specially designed for each data structure,\n    you'll need to implement your own version of this function or the transforms.\n\n    Args:\n        annotation (dict): dict of instance annotations for a single instance.\n            It will be modified in-place.\n        transforms (TransformList or list[Transform]):\n        image_size (tuple): the height, width of the transformed image\n        keypoint_hflip_indices (ndarray[int]): see `create_keypoint_hflip_indices`.\n\n    Returns:\n        dict:\n            the same input dict with fields \"bbox\", \"segmentation\", \"keypoints\"\n            transformed according to `transforms`.\n            The \"bbox_mode\" field will be set to XYXY_ABS.\n    \"\"\"\n    if isinstance(transforms, (tuple, list)):\n        transforms = T.TransformList(transforms)\n    # (dennis.park) Here 2D bounding box is optional.\n    if \"bbox\" in annotation:\n        assert \"bbox_mode\" in annotation, \"'bbox' is present, but 'bbox_mode' is not.\"\n        # bbox is 1d (per-instance bounding box)\n        bbox = BoxMode.convert(annotation[\"bbox\"], annotation[\"bbox_mode\"], BoxMode.XYXY_ABS)\n        bbox = transforms.apply_box(np.array([bbox]))[0]\n        # clip transformed bbox to image size\n        bbox = bbox.clip(min=0)\n        bbox = np.minimum(bbox, list(image_size + image_size)[::-1])\n        annotation[\"bbox\"] = bbox\n        annotation[\"bbox_mode\"] = BoxMode.XYXY_ABS\n\n    # Vertical flipping is not implemented (`flip_transform.py`). TODO: implement if needed.\n    if \"bbox3d\" in annotation:\n        bbox3d = np.array(annotation[\"bbox3d\"])\n        annotation['bbox3d'] = transforms.apply_box3d(bbox3d)\n\n    return annotation\n\n\ndef _create_empty_instances(image_size):\n    target = Instances(image_size)\n\n    target.gt_boxes = Boxes([])\n    target.gt_classes = torch.tensor([], dtype=torch.int64)\n    target.gt_boxes3d = Boxes3D.from_vectors([], torch.eye(3, dtype=torch.float32))\n\n    return target\n\n\ndef annotations_to_instances(\n    annos,\n    image_size,\n    intrinsics=None,\n):\n    \"\"\"\n    Create an :class:`Instances` object used by the models,\n    from instance annotations in the dataset dict.\n\n    Args:\n        annos (list[dict]): a list of instance annotations in one image, each\n            element for one instance.\n        image_size (tuple): height, width\n\n    Returns:\n        Instances:\n            It will contain fields \"gt_boxes\", \"gt_classes\",\n            \"gt_masks\", \"gt_keypoints\", if they can be obtained from `annos`.\n            This is the format that builtin models expect.\n    \"\"\"\n    if len(annos) == 0:\n        return _create_empty_instances(image_size)\n\n    boxes = [BoxMode.convert(obj[\"bbox\"], obj[\"bbox_mode\"], BoxMode.XYXY_ABS) for obj in annos]\n    target = Instances(image_size)\n    target.gt_boxes = Boxes(boxes)\n\n    classes = [obj[\"category_id\"] for obj in annos]\n    classes = torch.tensor(classes, dtype=torch.int64)\n    target.gt_classes = classes\n\n    if len(annos) and \"bbox3d\" in annos[0]:\n        assert intrinsics is not None\n        target.gt_boxes3d = Boxes3D.from_vectors([anno['bbox3d'] for anno in annos], intrinsics)\n        if len(target.gt_boxes3d) != target.gt_boxes.tensor.shape[0]:\n            raise ValueError(\n                f\"The sizes of `gt_boxes3d` and `gt_boxes` do not match: a={len(target.gt_boxes3d)}, b={target.gt_boxes.tensor.shape[0]}.\"\n            )\n\n    # NOTE: add nuscenes attributes here\n    # NOTE: instances will be filtered later\n    # NuScenes attributes\n    if len(annos) and \"attribute_id\" in annos[0]:    \n        attributes = [obj[\"attribute_id\"] for obj in annos] \n        target.gt_attributes = torch.tensor(attributes, dtype=torch.int64)\n\n    # Speed (magnitude of velocity)\n    if len(annos) and \"speed\" in annos[0]:\n        speeds = [obj[\"speed\"] for obj in annos]\n        target.gt_speeds = torch.tensor(speeds, dtype=torch.float32)\n\n    assert len(boxes) == len(classes) == len(attributes) == len(speeds), \\\n        'the numbers of annotations should be the same'\n    return target\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/layers/iou_loss.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\n# Adapted from AdelaiDet:\n#   https://github.com/aim-uofa/AdelaiDet/blob/master/adet/layers/iou_loss.py\nimport torch\nfrom torch import nn\n\n\nclass IOULoss(nn.Module):\n    \"\"\"\n    Intersetion Over Union (IoU) loss which supports three\n    different IoU computations:\n\n    * IoU\n    * Linear IoU\n    * gIoU\n    \"\"\"\n    def __init__(self, loc_loss_type='iou'):\n        super(IOULoss, self).__init__()\n        self.loc_loss_type = loc_loss_type\n\n    def forward(self, pred, target, weight=None):\n        \"\"\"\n        Args:\n            pred: Nx4 predicted bounding boxes\n            target: Nx4 target bounding boxes\n            weight: N loss weight for each instance\n        \"\"\"\n        pred_left = pred[:, 0]\n        pred_top = pred[:, 1]\n        pred_right = pred[:, 2]\n        pred_bottom = pred[:, 3]\n\n        target_left = target[:, 0]\n        target_top = target[:, 1]\n        target_right = target[:, 2]\n        target_bottom = target[:, 3]\n\n        target_aera = (target_left + target_right) * \\\n                      (target_top + target_bottom)\n        pred_aera = (pred_left + pred_right) * \\\n                    (pred_top + pred_bottom)\n\n        w_intersect = torch.min(pred_left, target_left) + \\\n                      torch.min(pred_right, target_right)\n        h_intersect = torch.min(pred_bottom, target_bottom) + \\\n                      torch.min(pred_top, target_top)\n\n        g_w_intersect = torch.max(pred_left, target_left) + \\\n                        torch.max(pred_right, target_right)\n        g_h_intersect = torch.max(pred_bottom, target_bottom) + \\\n                        torch.max(pred_top, target_top)\n        ac_uion = g_w_intersect * g_h_intersect\n\n        area_intersect = w_intersect * h_intersect\n        area_union = target_aera + pred_aera - area_intersect\n\n        ious = (area_intersect + 1.0) / (area_union + 1.0)\n        gious = ious - (ac_uion - area_union) / ac_uion\n        if self.loc_loss_type == 'iou':\n            losses = -torch.log(ious)\n        elif self.loc_loss_type == 'linear_iou':\n            losses = 1 - ious\n        elif self.loc_loss_type == 'giou':\n            losses = 1 - gious\n        else:\n            raise NotImplementedError\n\n        if weight is not None:\n            return (losses * weight).sum()\n        else:\n            return losses.sum()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/layers/normalization.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\n# Adapted from AdelaiDet\n#   https://github.com/aim-uofa/AdelaiDet/\nimport logging\n\nimport torch\nfrom torch import nn\n\nLOG = logging.getLogger(__name__)\n\n\nclass Scale(nn.Module):\n    def __init__(self, init_value=1.0):\n        super(Scale, self).__init__()\n        self.scale = nn.Parameter(torch.FloatTensor([init_value]))\n\n    def forward(self, input):\n        return input * self.scale\n\n\nclass Offset(nn.Module):\n    def __init__(self, init_value=0.):\n        super(Offset, self).__init__()\n        self.bias = nn.Parameter(torch.FloatTensor([init_value]))\n\n    def forward(self, input):\n        return input + self.bias\n\n\nclass ModuleListDial(nn.ModuleList):\n    def __init__(self, modules=None):\n        super(ModuleListDial, self).__init__(modules)\n        self.cur_position = 0\n\n    def forward(self, x):\n        result = self[self.cur_position](x)\n        self.cur_position += 1\n        if self.cur_position >= len(self):\n            self.cur_position = 0\n        return result\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/layers/smooth_l1_loss.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved.\n# Copyright 2021 Toyota Research Institute.  All rights reserved.\n# Adapted from fvcore:\n#   https://github.com/facebookresearch/fvcore/blob/master/fvcore/nn/smooth_l1_loss.py\n\nimport torch\n\n\ndef smooth_l1_loss(input: torch.Tensor, target: torch.Tensor, beta: float, reduction: str = \"none\") -> torch.Tensor:\n    \"\"\"\n    Smooth L1 loss defined in the Fast R-CNN paper as:\n\n                  | 0.5 * x ** 2 / beta   if abs(x) < beta\n    smoothl1(x) = |\n                  | abs(x) - 0.5 * beta   otherwise,\n\n    where x = input - target.\n\n    Smooth L1 loss is related to Huber loss, which is defined as:\n\n                | 0.5 * x ** 2                  if abs(x) < beta\n     huber(x) = |\n                | beta * (abs(x) - 0.5 * beta)  otherwise\n\n    Smooth L1 loss is equal to huber(x) / beta. This leads to the following\n    differences:\n\n     - As beta -> 0, Smooth L1 loss converges to L1 loss, while Huber loss\n       converges to a constant 0 loss.\n     - As beta -> +inf, Smooth L1 converges to a constant 0 loss, while Huber loss\n       converges to L2 loss.\n     - For Smooth L1 loss, as beta varies, the L1 segment of the loss has a constant\n       slope of 1. For Huber loss, the slope of the L1 segment is beta.\n\n    Smooth L1 loss can be seen as exactly L1 loss, but with the abs(x) < beta\n    portion replaced with a quadratic function such that at abs(x) = beta, its\n    slope is 1. The quadratic segment smooths the L1 loss near x = 0.\n\n    Args:\n        input (Tensor): input tensor of any shape\n        target (Tensor): target value tensor with the same shape as input\n        beta (float): L1 to L2 change point.\n            For beta values < 1e-5, L1 loss is computed.\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n\n    Returns:\n        The loss with the reduction option applied.\n\n    Note:\n        PyTorch's builtin \"Smooth L1 loss\" implementation does not actually\n        implement Smooth L1 loss, nor does it implement Huber loss. It implements\n        the special case of both in which they are equal (beta=1).\n        See: https://pytorch.org/docs/stable/nn.html#torch.nn.SmoothL1Loss.\n     \"\"\"\n    # (dennis.park) Make it work with mixed precision training.\n    beta = torch.as_tensor(beta).to(input.dtype)\n    if beta < 1e-5:\n        # if beta == 0, then torch.where will result in nan gradients when\n        # the chain rule is applied due to pytorch implementation details\n        # (the False branch \"0.5 * n ** 2 / 0\" has an incoming gradient of\n        # zeros, rather than \"no gradient\"). To avoid this issue, we define\n        # small values of beta to be exactly l1 loss.\n        loss = torch.abs(input - target)\n    else:\n        n = torch.abs(input - target)\n        cond = n < beta\n        a = 0.5 * n**2\n        b = n - 0.5 * beta\n        a, b = a.to(input.dtype), b.to(input.dtype)\n        loss = torch.where(cond, a, b)\n        # loss = torch.where(cond, 0.5 * n ** 2 / beta, n - 0.5 * beta)\n\n    if reduction == \"mean\":\n        loss = loss.mean()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n    return loss\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/__init__.py",
    "content": "from .nuscenes_dd3d import NuscenesDD3D"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/core.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport torch\nfrom torch import nn\n\n#from detectron2.modeling.meta_arch.build import META_ARCH_REGISTRY\nfrom mmcv.modeling.postprocessing import detector_postprocess as resize_instances\nfrom mmcv.structures import Instances\nfrom mmcv.layers import ShapeSpec\nfrom mmcv.utils import force_fp32\n\nfrom .fcos2d import FCOS2DHead, FCOS2DInference, FCOS2DLoss\nfrom .fcos3d import FCOS3DHead, FCOS3DInference, FCOS3DLoss\n#from tridet.modeling.dd3d.postprocessing import nuscenes_sample_aggregate\nfrom .prepare_targets import DD3DTargetPreparer\n#from tridet.modeling.feature_extractor import build_feature_extractor\nfrom ..structures.image_list import ImageList\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.tensor2d import compute_features_locations as compute_locations_per_level\n\n\n#@META_ARCH_REGISTRY.register()\nclass DD3D(nn.Module):\n    def __init__(self,\n                 num_classes,\n                 in_channels,\n                 strides,\n                 fcos2d_cfg=dict(),\n                 fcos2d_loss_cfg=dict(),\n                 fcos3d_cfg=dict(),\n                 fcos3d_loss_cfg=dict(),\n                 target_assign_cfg=dict(),\n                 box3d_on=True,\n                 feature_locations_offset=\"none\"):\n        super().__init__()\n        # NOTE: do not need backbone\n        # self.backbone = build_feature_extractor(cfg)\n        # backbone_output_shape = self.backbone.output_shape()\n        # self.in_features = cfg.DD3D.IN_FEATURES or list(backbone_output_shape.keys())\n        \n        self.backbone_output_shape = [ShapeSpec(channels=in_channels, stride=s) for s in strides]\n\n        self.feature_locations_offset = feature_locations_offset\n\n        self.fcos2d_head = FCOS2DHead(num_classes=num_classes, input_shape=self.backbone_output_shape,\n                                     **fcos2d_cfg)\n        self.fcos2d_loss = FCOS2DLoss(num_classes=num_classes, **fcos2d_loss_cfg)\n        # NOTE: inference later\n        # self.fcos2d_inference = FCOS2DInference(cfg)\n\n        if box3d_on:\n            self.fcos3d_head = FCOS3DHead(num_classes=num_classes, input_shape=self.backbone_output_shape,\n                                          **fcos3d_cfg)\n            self.fcos3d_loss = FCOS3DLoss(num_classes=num_classes, **fcos3d_loss_cfg)\n            # NOTE: inference later\n            # self.fcos3d_inference = FCOS3DInference(cfg)\n            self.only_box2d = False\n        else:\n            self.only_box2d = True\n\n        self.prepare_targets = DD3DTargetPreparer(num_classes=num_classes, \n                                                  input_shape=self.backbone_output_shape,\n                                                  box3d_on=box3d_on,\n                                                  **target_assign_cfg)\n\n        # NOTE: inference later\n        # self.postprocess_in_inference = cfg.DD3D.INFERENCE.DO_POSTPROCESS\n\n        # self.do_nms = cfg.DD3D.INFERENCE.DO_NMS\n        # self.do_bev_nms = cfg.DD3D.INFERENCE.DO_BEV_NMS\n        # self.bev_nms_iou_thresh = cfg.DD3D.INFERENCE.BEV_NMS_IOU_THRESH\n\n        # nuScenes inference aggregates detections over all 6 cameras.\n        # self.nusc_sample_aggregate_in_inference = cfg.DD3D.INFERENCE.NUSC_SAMPLE_AGGREGATE\n        self.num_classes = num_classes\n\n        # NOTE: do not need normalize\n        # self.register_buffer(\"pixel_mean\", torch.Tensor(cfg.MODEL.PIXEL_MEAN).view(-1, 1, 1))\n        # self.register_buffer(\"pixel_std\", torch.Tensor(cfg.MODEL.PIXEL_STD).view(-1, 1, 1))\n\n    # NOTE:\n    # @property\n    # def device(self):\n    #     return self.pixel_mean.device\n\n    # def preprocess_image(self, x):\n    #     return (x - self.pixel_mean) / self.pixel_std\n\n    @force_fp32(apply_to=('features'))\n    def forward(self, features, batched_inputs):\n        # NOTE:\n        # images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        # images = [self.preprocess_image(x) for x in images]\n\n        # NOTE: directly use inv_intrinsics\n        # if 'intrinsics' in batched_inputs[0]:\n        #     intrinsics = [x['intrinsics'].to(self.device) for x in batched_inputs]\n        # else:\n        #     intrinsics = None\n        # images = ImageList.from_tensors(images, self.backbone.size_divisibility, intrinsics=intrinsics)\n        if 'inv_intrinsics' in batched_inputs[0]:\n            inv_intrinsics = [x['inv_intrinsics'].to(features[0].device) for x in batched_inputs]\n            inv_intrinsics = torch.stack(inv_intrinsics, dim=0)\n        else:\n            inv_intrinsics = None\n\n        # NOTE:\n        # gt_dense_depth = None\n        # if 'depth' in batched_inputs[0]:\n        #     gt_dense_depth = [x[\"depth\"].to(self.device) for x in batched_inputs]\n        #     gt_dense_depth = ImageList.from_tensors(\n        #         gt_dense_depth, self.backbone.size_divisibility, intrinsics=intrinsics\n        #     )\n\n        # NOTE: directly input feature\n        # features = self.backbone(images.tensor)\n        # features = [features[f] for f in self.in_features]\n\n        if \"instances\" in batched_inputs[0]:\n            gt_instances = [x[\"instances\"].to(features[0].device) for x in batched_inputs]\n        else:\n            gt_instances = None\n\n        locations = self.compute_locations(features)\n        logits, box2d_reg, centerness, _ = self.fcos2d_head(features)\n        if not self.only_box2d:\n            box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, dense_depth = self.fcos3d_head(features)\n        # NOTE: directly use inv_intrinsics\n        # inv_intrinsics = images.intrinsics.inverse() if images.intrinsics is not None else None\n\n        if self.training:\n            assert gt_instances is not None\n            feature_shapes = [x.shape[-2:] for x in features]\n            training_targets = self.prepare_targets(locations, gt_instances, feature_shapes)\n            # NOTE: \n            # if gt_dense_depth is not None:\n            #    training_targets.update({\"dense_depth\": gt_dense_depth})\n\n            losses = {}\n            fcos2d_loss, fcos2d_info = self.fcos2d_loss(logits, box2d_reg, centerness, training_targets)\n            losses.update(fcos2d_loss)\n\n            if not self.only_box2d:\n                fcos3d_loss = self.fcos3d_loss(\n                    box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, dense_depth, inv_intrinsics,\n                    fcos2d_info, training_targets\n                )\n                losses.update(fcos3d_loss)\n            return losses\n        else:\n            # TODO: do not support inference now\n            raise NotImplementedError\n            \n            pred_instances, fcos2d_info = self.fcos2d_inference(\n                logits, box2d_reg, centerness, locations, images.image_sizes\n            )\n            if not self.only_box2d:\n                # This adds 'pred_boxes3d' and 'scores_3d' to Instances in 'pred_instances' in place.\n                self.fcos3d_inference(\n                    box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, inv_intrinsics, pred_instances,\n                    fcos2d_info\n                )\n\n                # 3D score == 2D score x confidence.\n                score_key = \"scores_3d\"\n            else:\n                score_key = \"scores\"\n\n            # Transpose to \"image-first\", i.e. (B, L)\n            pred_instances = list(zip(*pred_instances))\n            pred_instances = [Instances.cat(instances) for instances in pred_instances]\n\n            # 2D NMS and pick top-K.\n            if self.do_nms:\n                pred_instances = self.fcos2d_inference.nms_and_top_k(pred_instances, score_key)\n\n            if not self.only_box2d and self.do_bev_nms:\n                # Bird-eye-view NMS.\n                dummy_group_idxs = {i: [i] for i, _ in enumerate(pred_instances)}\n                if 'pose' in batched_inputs[0]:\n                    poses = [x['pose'] for x in batched_inputs]\n                else:\n                    poses = [x['extrinsics'] for x in batched_inputs]\n                pred_instances = nuscenes_sample_aggregate(\n                    pred_instances,\n                    dummy_group_idxs,\n                    self.num_classes,\n                    poses,\n                    iou_threshold=self.bev_nms_iou_thresh,\n                    include_boxes3d_global=False\n                )\n\n            if self.postprocess_in_inference:\n                processed_results = []\n                for results_per_image, input_per_image, image_size in \\\n                        zip(pred_instances, batched_inputs, images.image_sizes):\n                    height = input_per_image.get(\"height\", image_size[0])\n                    width = input_per_image.get(\"width\", image_size[1])\n                    r = resize_instances(results_per_image, height, width)\n                    processed_results.append({\"instances\": r})\n            else:\n                processed_results = [{\"instances\": x} for x in pred_instances]\n\n            return processed_results\n\n    def compute_locations(self, features):\n        locations = []\n        in_strides = [x.stride for x in self.backbone_output_shape]\n        for level, feature in enumerate(features):\n            h, w = feature.size()[-2:]\n            locations_per_level = compute_locations_per_level(\n                h, w, in_strides[level], feature.dtype, feature.device, offset=self.feature_locations_offset\n            )\n            locations.append(locations_per_level)\n        return locations\n\n    def forward_train(self, features, batched_inputs):\n        self.train()\n        return self.forward(features, batched_inputs)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/disentangled_box3d_loss.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport logging\n\nimport torch\nimport torch.nn as nn\n\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.layers.smooth_l1_loss import smooth_l1_loss\n\nLOG = logging.getLogger(__name__)\n\n\nclass DisentangledBox3DLoss(nn.Module):\n    def __init__(self, smooth_l1_loss_beta, max_loss_per_group):\n        super().__init__()\n        self.smooth_l1_loss_beta = smooth_l1_loss_beta\n        self.max_loss_per_group = max_loss_per_group\n\n    def forward(self, box3d_pred, box3d_targets, locations, weights=None):\n\n        box3d_pred = box3d_pred.to(torch.float32)\n        box3d_targets = box3d_targets.to(torch.float32)\n\n        target_corners = box3d_targets.corners\n\n        disentangled_losses = {}\n        for component_key in [\"quat\", \"proj_ctr\", \"depth\", \"size\"]:\n            disentangled_boxes = box3d_targets.clone()\n            setattr(disentangled_boxes, component_key, getattr(box3d_pred, component_key))\n            pred_corners = disentangled_boxes.to(torch.float32).corners\n\n            loss = smooth_l1_loss(pred_corners, target_corners, beta=self.smooth_l1_loss_beta)\n\n            # Bound the loss\n            loss.clamp(max=self.max_loss_per_group)\n\n            if weights is not None:\n                # loss = torch.sum(loss.reshape(-1, 24) * weights.unsqueeze(-1))\n                loss = torch.sum(loss.reshape(-1, 24).mean(dim=1) * weights)\n            else:\n                loss = loss.reshape(-1, 24).mean()\n\n            disentangled_losses[\"loss_box3d_\" + component_key] = loss\n\n        entangled_l1_dist = (target_corners - box3d_pred.corners).detach().abs().reshape(-1, 24).mean(dim=1)\n\n        return disentangled_losses, entangled_l1_dist\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/fcos2d.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\n# Adapted from AdelaiDet:\n#   https://github.com/aim-uofa/AdelaiDet\nimport torch\nfrom mmcv.losses import sigmoid_focal_loss\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom mmcv.layers import batched_nms, get_norm\nfrom mmcv.structures import Instances, Boxes\nfrom torch import distributed as dist\nfrom mmcv.utils import force_fp32\nfrom mmcv.layers import Conv2d, batched_nms, cat, get_norm\n\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.layers.iou_loss import IOULoss\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.layers.normalization import ModuleListDial, Scale\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.comm import reduce_sum\n\nINF = 100000000\n\ndef get_world_size() -> int:\n    if not dist.is_available():\n        return 1\n    if not dist.is_initialized():\n        return 1\n    return dist.get_world_size()\n\ndef compute_ctrness_targets(reg_targets):\n    if len(reg_targets) == 0:\n        return reg_targets.new_zeros(len(reg_targets))\n    left_right = reg_targets[:, [0, 2]]\n    top_bottom = reg_targets[:, [1, 3]]\n    ctrness = (left_right.min(dim=-1)[0] / left_right.max(dim=-1)[0]) * \\\n                 (top_bottom.min(dim=-1)[0] / top_bottom.max(dim=-1)[0])\n    return torch.sqrt(ctrness)\n\nclass FCOS2DHead(nn.Module):\n    def __init__(self, \n                 num_classes, \n                 input_shape,\n                 num_cls_convs=4,\n                 num_box_convs=4,\n                 norm='BN',\n                 use_deformable=False,\n                 use_scale=True,\n                 box2d_scale_init_factor=1.0,\n                 version='v2'):\n        super().__init__()\n\n        self.num_classes = num_classes\n        self.in_strides = [shape.stride for shape in input_shape]\n        self.num_levels = len(input_shape)\n\n        self.use_scale = use_scale\n        self.box2d_scale_init_factor = box2d_scale_init_factor\n\n        self._version = version\n\n        in_channels = [s.channels for s in input_shape]\n        assert len(set(in_channels)) == 1, \"Each level must have the same channel!\"\n        in_channels = in_channels[0]\n\n        if use_deformable:\n            raise ValueError(\"Not supported yet.\")\n\n        head_configs = {'cls': num_cls_convs, 'box2d': num_box_convs}\n\n        for head_name, num_convs in head_configs.items():\n            tower = []\n            if self._version == \"v1\":\n                for _ in range(num_convs):\n                    conv_func = nn.Conv2d\n                    tower.append(conv_func(in_channels, in_channels, kernel_size=3, stride=1, padding=1, bias=True))\n                    if norm == \"GN\":\n                        raise NotImplementedError()\n                    elif norm == \"NaiveGN\":\n                        raise NotImplementedError()\n                    elif norm == \"BN\":\n                        tower.append(ModuleListDial([nn.BatchNorm2d(in_channels) for _ in range(self.num_levels)]))\n                    elif norm == \"SyncBN\":\n                        raise NotImplementedError()\n                    tower.append(nn.ReLU())\n            elif self._version == \"v2\":\n                for _ in range(num_convs):\n                    if norm in (\"BN\", \"FrozenBN\", \"SyncBN\", \"GN\"):\n                        # NOTE: need to add norm here!\n                        # Each FPN level has its own batchnorm layer.\n                        # NOTE: do not use dd3d train.py!\n                        # \"BN\" is converted to \"SyncBN\" in distributed training (see train.py)\n                        norm_layer = ModuleListDial([get_norm(norm, in_channels) for _ in range(self.num_levels)])\n                    else:\n                        norm_layer = get_norm(norm, in_channels)\n                    tower.append(\n                        Conv2d(\n                            in_channels,\n                            in_channels,\n                            kernel_size=3,\n                            stride=1,\n                            padding=1,\n                            bias=norm_layer is None,\n                            norm=norm_layer,\n                            activation=F.relu\n                        )\n                    )\n            else:\n                raise ValueError(f\"Invalid FCOS2D version: {self._version}\")\n            self.add_module(f'{head_name}_tower', nn.Sequential(*tower))\n\n        self.cls_logits = nn.Conv2d(in_channels, self.num_classes, kernel_size=3, stride=1, padding=1)\n        self.box2d_reg = nn.Conv2d(in_channels, 4, kernel_size=3, stride=1, padding=1)\n        self.centerness = nn.Conv2d(in_channels, 1, kernel_size=3, stride=1, padding=1)\n\n        if self.use_scale:\n            if self._version == \"v1\":\n                self.scales_reg = nn.ModuleList([\n                    Scale(init_value=stride * self.box2d_scale_init_factor) for stride in self.in_strides\n                ])\n            else:\n                self.scales_box2d_reg = nn.ModuleList([\n                    Scale(init_value=stride * self.box2d_scale_init_factor) for stride in self.in_strides\n                ])\n\n        self.init_weights()\n\n    def init_weights(self):\n\n        for tower in [self.cls_tower, self.box2d_tower]:\n            for l in tower.modules():\n                if isinstance(l, nn.Conv2d):\n                    torch.nn.init.kaiming_normal_(l.weight, mode='fan_out', nonlinearity='relu')\n                    if l.bias is not None:\n                        torch.nn.init.constant_(l.bias, 0)\n\n        predictors = [self.cls_logits, self.box2d_reg, self.centerness]\n\n        for modules in predictors:\n            for l in modules.modules():\n                if isinstance(l, nn.Conv2d):\n                    torch.nn.init.kaiming_uniform_(l.weight, a=1)\n                    if l.bias is not None:  # depth head may not have bias.\n                        torch.nn.init.constant_(l.bias, 0)\n\n    def forward(self, x):\n        logits = []\n        box2d_reg = []\n        centerness = []\n\n        extra_output = {\"cls_tower_out\": []}\n\n        for l, feature in enumerate(x):\n            cls_tower_out = self.cls_tower(feature)\n            bbox_tower_out = self.box2d_tower(feature)\n\n            # 2D box\n            logits.append(self.cls_logits(cls_tower_out))\n            centerness.append(self.centerness(bbox_tower_out))\n            box_reg = self.box2d_reg(bbox_tower_out)\n            if self.use_scale:\n                # TODO: to optimize the runtime, apply this scaling in inference (and loss compute) only on FG pixels?\n                if self._version == \"v1\":\n                    box_reg = self.scales_reg[l](box_reg)\n                else:\n                    box_reg = self.scales_box2d_reg[l](box_reg)\n            # Note that we use relu, as in the improved FCOS, instead of exp.\n            box2d_reg.append(F.relu(box_reg))\n\n            extra_output['cls_tower_out'].append(cls_tower_out)\n\n        return logits, box2d_reg, centerness, extra_output\n\n\nclass FCOS2DLoss(nn.Module):\n    def __init__(self,\n                 num_classes,\n                 focal_loss_alpha=0.25,\n                 focal_loss_gamma=2.0,\n                 loc_loss_type='giou',\n                 ):\n        super().__init__()\n        self.focal_loss_alpha = focal_loss_alpha\n        self.focal_loss_gamma = focal_loss_gamma\n\n        self.box2d_reg_loss_fn = IOULoss(loc_loss_type)\n\n        self.num_classes = num_classes\n\n    @force_fp32(apply_to=('logits', 'box2d_reg', 'centerness'))\n    def forward(self, logits, box2d_reg, centerness, targets):\n        labels = targets['labels']\n        box2d_reg_targets = targets['box2d_reg_targets']\n        pos_inds = targets[\"pos_inds\"]\n\n        if len(labels) != box2d_reg_targets.shape[0]:\n            raise ValueError(\n                f\"The size of 'labels' and 'box2d_reg_targets' does not match: a={len(labels)}, b={box2d_reg_targets.shape[0]}\"\n            )\n\n        # Flatten predictions\n        logits = cat([x.permute(0, 2, 3, 1).reshape(-1, self.num_classes) for x in logits])\n        box2d_reg_pred = cat([x.permute(0, 2, 3, 1).reshape(-1, 4) for x in box2d_reg])\n        centerness_pred = cat([x.permute(0, 2, 3, 1).reshape(-1) for x in centerness])\n\n        # -------------------\n        # Classification loss\n        # -------------------\n        num_pos_local = pos_inds.numel()\n        num_gpus = get_world_size()\n        total_num_pos = reduce_sum(pos_inds.new_tensor([num_pos_local])).item()\n        num_pos_avg = max(total_num_pos / num_gpus, 1.0)\n\n        # prepare one_hot\n        cls_target = torch.zeros_like(logits)\n        cls_target[pos_inds, labels[pos_inds]] = 1\n\n        loss_cls = sigmoid_focal_loss(\n            logits,\n            cls_target,\n            alpha=self.focal_loss_alpha,\n            gamma=self.focal_loss_gamma,\n            reduction=\"sum\",\n        ) / num_pos_avg\n\n        # NOTE: The rest of losses only consider foreground pixels.\n        box2d_reg_pred = box2d_reg_pred[pos_inds]\n        box2d_reg_targets = box2d_reg_targets[pos_inds]\n\n        centerness_pred = centerness_pred[pos_inds]\n\n        # Compute centerness targets here using 2D regression targets of foreground pixels.\n        centerness_targets = compute_ctrness_targets(box2d_reg_targets)\n\n        # Denominator for all foreground losses.\n        ctrness_targets_sum = centerness_targets.sum()\n        loss_denom = max(reduce_sum(ctrness_targets_sum).item() / num_gpus, 1e-6)\n\n        # NOTE: change the return after reduce_sum\n        if pos_inds.numel() == 0:\n            losses = {\n                \"loss_cls\": loss_cls,\n                \"loss_box2d_reg\": box2d_reg_pred.sum() * 0.,\n                \"loss_centerness\": centerness_pred.sum() * 0.,\n            }\n            return losses, {}\n\n        # ----------------------\n        # 2D box regression loss\n        # ----------------------\n        loss_box2d_reg = self.box2d_reg_loss_fn(box2d_reg_pred, box2d_reg_targets, centerness_targets) / loss_denom\n\n        # ---------------\n        # Centerness loss\n        # ---------------\n        loss_centerness = F.binary_cross_entropy_with_logits(\n            centerness_pred, centerness_targets, reduction=\"sum\"\n        ) / num_pos_avg\n\n        loss_dict = {\"loss_cls\": loss_cls, \"loss_box2d_reg\": loss_box2d_reg, \"loss_centerness\": loss_centerness}\n        extra_info = {\"loss_denom\": loss_denom, \"centerness_targets\": centerness_targets}\n\n        return loss_dict, extra_info\n\n\nclass FCOS2DInference():\n    def __init__(self, cfg):\n        self.thresh_with_ctr = cfg.DD3D.FCOS2D.INFERENCE.THRESH_WITH_CTR\n        self.pre_nms_thresh = cfg.DD3D.FCOS2D.INFERENCE.PRE_NMS_THRESH\n        self.pre_nms_topk = cfg.DD3D.FCOS2D.INFERENCE.PRE_NMS_TOPK\n        self.post_nms_topk = cfg.DD3D.FCOS2D.INFERENCE.POST_NMS_TOPK\n        self.nms_thresh = cfg.DD3D.FCOS2D.INFERENCE.NMS_THRESH\n        self.num_classes = cfg.DD3D.NUM_CLASSES\n\n    def __call__(self, logits, box2d_reg, centerness, locations, image_sizes):\n\n        pred_instances = []  # List[List[Instances]], shape = (L, B)\n        extra_info = []\n        for lvl, (logits_lvl, box2d_reg_lvl, centerness_lvl, locations_lvl) in \\\n            enumerate(zip(logits, box2d_reg, centerness, locations)):\n\n            instances_per_lvl, extra_info_per_lvl = self.forward_for_single_feature_map(\n                logits_lvl, box2d_reg_lvl, centerness_lvl, locations_lvl, image_sizes\n            )  # List of Instances; one for each image.\n\n            for instances_per_im in instances_per_lvl:\n                instances_per_im.fpn_levels = locations_lvl.new_ones(len(instances_per_im), dtype=torch.long) * lvl\n\n            pred_instances.append(instances_per_lvl)\n            extra_info.append(extra_info_per_lvl)\n\n        return pred_instances, extra_info\n\n    def forward_for_single_feature_map(self, logits, box2d_reg, centerness, locations, image_sizes):\n        N, C, _, __ = logits.shape\n\n        # put in the same format as locations\n        scores = logits.permute(0, 2, 3, 1).reshape(N, -1, C).sigmoid()\n        box2d_reg = box2d_reg.permute(0, 2, 3, 1).reshape(N, -1, 4)\n        centerness = centerness.permute(0, 2, 3, 1).reshape(N, -1).sigmoid()\n\n        # if self.thresh_with_ctr is True, we multiply the classification\n        # scores with centerness scores before applying the threshold.\n        if self.thresh_with_ctr:\n            scores = scores * centerness[:, :, None]\n\n        candidate_mask = scores > self.pre_nms_thresh\n\n        pre_nms_topk = candidate_mask.reshape(N, -1).sum(1)\n        pre_nms_topk = pre_nms_topk.clamp(max=self.pre_nms_topk)\n\n        if not self.thresh_with_ctr:\n            scores = scores * centerness[:, :, None]\n\n        results = []\n        all_fg_inds_per_im, all_topk_indices, all_class_inds_per_im = [], [], []\n        for i in range(N):\n            scores_per_im = scores[i]\n            candidate_mask_per_im = candidate_mask[i]\n            scores_per_im = scores_per_im[candidate_mask_per_im]\n\n            candidate_inds_per_im = candidate_mask_per_im.nonzero(as_tuple=False)\n            fg_inds_per_im = candidate_inds_per_im[:, 0]\n            class_inds_per_im = candidate_inds_per_im[:, 1]\n\n            # Cache info here.\n            all_fg_inds_per_im.append(fg_inds_per_im)\n            all_class_inds_per_im.append(class_inds_per_im)\n\n            box2d_reg_per_im = box2d_reg[i][fg_inds_per_im]\n            locations_per_im = locations[fg_inds_per_im]\n\n            pre_nms_topk_per_im = pre_nms_topk[i]\n\n            if candidate_mask_per_im.sum().item() > pre_nms_topk_per_im.item():\n                scores_per_im, topk_indices = \\\n                    scores_per_im.topk(pre_nms_topk_per_im, sorted=False)\n\n                class_inds_per_im = class_inds_per_im[topk_indices]\n                box2d_reg_per_im = box2d_reg_per_im[topk_indices]\n                locations_per_im = locations_per_im[topk_indices]\n            else:\n                topk_indices = None\n\n            all_topk_indices.append(topk_indices)\n\n            detections = torch.stack([\n                locations_per_im[:, 0] - box2d_reg_per_im[:, 0],\n                locations_per_im[:, 1] - box2d_reg_per_im[:, 1],\n                locations_per_im[:, 0] + box2d_reg_per_im[:, 2],\n                locations_per_im[:, 1] + box2d_reg_per_im[:, 3],\n            ],\n                                     dim=1)\n\n            instances = Instances(image_sizes[i])\n            instances.pred_boxes = Boxes(detections)\n            instances.scores = torch.sqrt(scores_per_im)\n            instances.pred_classes = class_inds_per_im\n            instances.locations = locations_per_im\n\n            results.append(instances)\n\n        extra_info = {\n            \"fg_inds_per_im\": all_fg_inds_per_im,\n            \"class_inds_per_im\": all_class_inds_per_im,\n            \"topk_indices\": all_topk_indices\n        }\n        return results, extra_info\n\n    def nms_and_top_k(self, instances_per_im, score_key_for_nms=\"scores\"):\n        results = []\n        for instances in instances_per_im:\n            if self.nms_thresh > 0:\n                # Multiclass NMS.\n                keep = batched_nms(\n                    instances.pred_boxes.tensor, instances.get(score_key_for_nms), instances.pred_classes,\n                    self.nms_thresh\n                )\n                instances = instances[keep]\n            num_detections = len(instances)\n\n            # Limit to max_per_image detections **over all classes**\n            if num_detections > self.post_nms_topk > 0:\n                scores = instances.scores\n                # image_thresh, _ = torch.kthvalue(scores.cpu(), num_detections - self.post_nms_topk + 1)\n                image_thresh, _ = torch.kthvalue(scores, num_detections - self.post_nms_topk + 1)\n                keep = scores >= image_thresh.item()\n                keep = torch.nonzero(keep).squeeze(1)\n                instances = instances[keep]\n            results.append(instances)\n        return results\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/fcos3d.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport torch\nimport torch.nn.functional as F\nfrom torch import nn\n\nfrom mmcv.layers import Conv2d, batched_nms, cat, get_norm\nfrom mmcv.utils import force_fp32\n\nfrom .disentangled_box3d_loss import DisentangledBox3DLoss\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.layers.normalization import ModuleListDial, Offset, Scale\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.boxes3d import Boxes3D\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.geometry import allocentric_to_egocentric, unproject_points2d\n\nEPS = 1e-7\n\n\ndef predictions_to_boxes3d(\n    quat,\n    proj_ctr,\n    depth,\n    size,\n    locations,\n    inv_intrinsics,\n    canon_box_sizes,\n    min_depth,\n    max_depth,\n    scale_depth_by_focal_lengths_factor,\n    scale_depth_by_focal_lengths=True,\n    quat_is_allocentric=True,\n    depth_is_distance=False\n):\n    # Normalize to make quat unit norm.\n    quat = quat / quat.norm(dim=1, keepdim=True).clamp(min=EPS)\n    # Make sure again it's numerically unit-norm.\n    quat = quat / quat.norm(dim=1, keepdim=True)\n\n    if scale_depth_by_focal_lengths:\n        pixel_size = torch.norm(torch.stack([inv_intrinsics[:, 0, 0], inv_intrinsics[:, 1, 1]], dim=-1), dim=-1)\n        depth = depth / (pixel_size * scale_depth_by_focal_lengths_factor)\n\n    if depth_is_distance:\n        depth = depth / unproject_points2d(locations, inv_intrinsics).norm(dim=1).clamp(min=EPS)\n\n    depth = depth.reshape(-1, 1).clamp(min_depth, max_depth)\n\n    proj_ctr = proj_ctr + locations\n\n    if quat_is_allocentric:\n        quat = allocentric_to_egocentric(quat, proj_ctr, inv_intrinsics)\n\n    size = (size.tanh() + 1.) * canon_box_sizes  # max size = 2 * canon_size\n\n    return Boxes3D(quat, proj_ctr, depth, size, inv_intrinsics)\n\n\nclass FCOS3DHead(nn.Module):\n    def __init__(self, \n                 num_classes,\n                 input_shape,\n                 num_convs=4,\n                 norm='BN',\n                 use_scale=True,\n                 depth_scale_init_factor=0.3,\n                 proj_ctr_scale_init_factor=1.0,\n                 use_per_level_predictors=False,\n                 class_agnostic=False,\n                 use_deformable=False,\n                 mean_depth_per_level=None,\n                 std_depth_per_level=None,\n                 ):\n        super().__init__()\n        self.num_classes = num_classes\n        self.in_strides = [shape.stride for shape in input_shape]\n        self.num_levels = len(input_shape)\n\n        self.use_scale = use_scale\n        self.depth_scale_init_factor = depth_scale_init_factor\n        self.proj_ctr_scale_init_factor = proj_ctr_scale_init_factor\n        self.use_per_level_predictors = use_per_level_predictors\n\n        self.register_buffer(\"mean_depth_per_level\", torch.Tensor(mean_depth_per_level))\n        self.register_buffer(\"std_depth_per_level\", torch.Tensor(std_depth_per_level))\n\n        in_channels = [s.channels for s in input_shape]\n        assert len(set(in_channels)) == 1, \"Each level must have the same channel!\"\n        in_channels = in_channels[0]\n\n        if use_deformable:\n            raise ValueError(\"Not supported yet.\")\n\n        box3d_tower = []\n        for i in range(num_convs):\n            if norm in (\"BN\", \"FrozenBN\", \"SyncBN\", \"GN\"):\n                # NOTE: need to add norm here!\n                # Each FPN level has its own batchnorm layer.\n                # NOTE: do not use dd3d train.py!\n                # \"BN\" is converted to \"SyncBN\" in distributed training (see train.py)\n                norm_layer = ModuleListDial([get_norm(norm, in_channels) for _ in range(self.num_levels)])\n            else:\n                norm_layer = get_norm(norm, in_channels)\n            box3d_tower.append(\n                Conv2d(\n                    in_channels,\n                    in_channels,\n                    kernel_size=3,\n                    stride=1,\n                    padding=1,\n                    bias=norm_layer is None,\n                    norm=norm_layer,\n                    activation=F.relu\n                )\n            )\n        self.add_module('box3d_tower', nn.Sequential(*box3d_tower))\n\n        num_classes = self.num_classes if not class_agnostic else 1\n        num_levels = self.num_levels if use_per_level_predictors else 1\n\n        # 3D box branches.\n        self.box3d_quat = nn.ModuleList([\n            Conv2d(in_channels, 4 * num_classes, kernel_size=3, stride=1, padding=1, bias=True)\n            for _ in range(num_levels)\n        ])\n        self.box3d_ctr = nn.ModuleList([\n            Conv2d(in_channels, 2 * num_classes, kernel_size=3, stride=1, padding=1, bias=True)\n            for _ in range(num_levels)\n        ])\n        self.box3d_depth = nn.ModuleList([\n            Conv2d(in_channels, 1 * num_classes, kernel_size=3, stride=1, padding=1, bias=(not self.use_scale))\n            for _ in range(num_levels)\n        ])\n        self.box3d_size = nn.ModuleList([\n            Conv2d(in_channels, 3 * num_classes, kernel_size=3, stride=1, padding=1, bias=True)\n            for _ in range(num_levels)\n        ])\n        self.box3d_conf = nn.ModuleList([\n            Conv2d(in_channels, 1 * num_classes, kernel_size=3, stride=1, padding=1, bias=True)\n            for _ in range(num_levels)\n        ])\n\n        if self.use_scale:\n            self.scales_proj_ctr = nn.ModuleList([\n                Scale(init_value=stride * self.proj_ctr_scale_init_factor) for stride in self.in_strides\n            ])\n            # (pre-)compute (mean, std) of depth for each level, and determine the init value here.\n            self.scales_size = nn.ModuleList([Scale(init_value=1.0) for _ in range(self.num_levels)])\n            self.scales_conf = nn.ModuleList([Scale(init_value=1.0) for _ in range(self.num_levels)])\n\n            self.scales_depth = nn.ModuleList([\n                Scale(init_value=sigma * self.depth_scale_init_factor) for sigma in self.std_depth_per_level\n            ])\n            self.offsets_depth = nn.ModuleList([Offset(init_value=b) for b in self.mean_depth_per_level])\n\n        self._init_weights()\n\n    def _init_weights(self):\n\n        for l in self.box3d_tower.modules():\n            if isinstance(l, nn.Conv2d):\n                torch.nn.init.kaiming_normal_(l.weight, mode='fan_out', nonlinearity='relu')\n                if l.bias is not None:\n                    torch.nn.init.constant_(l.bias, 0)\n\n        predictors = [self.box3d_quat, self.box3d_ctr, self.box3d_depth, self.box3d_size, self.box3d_conf]\n\n        for modules in predictors:\n            for l in modules.modules():\n                if isinstance(l, nn.Conv2d):\n                    torch.nn.init.kaiming_uniform_(l.weight, a=1)\n                    if l.bias is not None:  # depth head may not have bias.\n                        torch.nn.init.constant_(l.bias, 0)\n\n    def forward(self, x):\n        box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf = [], [], [], [], []\n        dense_depth = None\n        for l, features in enumerate(x):\n            box3d_tower_out = self.box3d_tower(features)\n\n            _l = l if self.use_per_level_predictors else 0\n\n            # 3D box\n            quat = self.box3d_quat[_l](box3d_tower_out)\n            proj_ctr = self.box3d_ctr[_l](box3d_tower_out)\n            depth = self.box3d_depth[_l](box3d_tower_out)\n            size3d = self.box3d_size[_l](box3d_tower_out)\n            conf3d = self.box3d_conf[_l](box3d_tower_out)\n\n            if self.use_scale:\n                # TODO: to optimize the runtime, apply this scaling in inference (and loss compute) only on FG pixels?\n                proj_ctr = self.scales_proj_ctr[l](proj_ctr)\n                size3d = self.scales_size[l](size3d)\n                conf3d = self.scales_conf[l](conf3d)\n                depth = self.offsets_depth[l](self.scales_depth[l](depth))\n\n            box3d_quat.append(quat)\n            box3d_ctr.append(proj_ctr)\n            box3d_depth.append(depth)\n            box3d_size.append(size3d)\n            box3d_conf.append(conf3d)\n\n        return box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, dense_depth\n\n\nclass FCOS3DLoss(nn.Module):\n    def __init__(self, \n                 num_classes,\n                 min_depth=0.1,\n                 max_depth=80.0,\n                 box3d_loss_weight=2.0,\n                 conf3d_loss_weight=1.0,\n                 conf_3d_temperature=1.0,\n                 smooth_l1_loss_beta=0.05, \n                 max_loss_per_group=20,\n                 predict_allocentric_rot=True,\n                 scale_depth_by_focal_lengths=True,\n                 scale_depth_by_focal_lengths_factor=500.0,\n                 class_agnostic=False,\n                 predict_distance=False,\n                 canon_box_sizes=None):\n        super().__init__()\n        self.canon_box_sizes = canon_box_sizes\n        self.min_depth = min_depth\n        self.max_depth = max_depth\n        self.predict_allocentric_rot = predict_allocentric_rot\n        self.scale_depth_by_focal_lengths = scale_depth_by_focal_lengths\n        self.scale_depth_by_focal_lengths_factor = scale_depth_by_focal_lengths_factor\n        self.predict_distance = predict_distance\n\n        self.box3d_reg_loss_fn = DisentangledBox3DLoss(smooth_l1_loss_beta, max_loss_per_group)\n        self.box3d_loss_weight = box3d_loss_weight\n        self.conf3d_loss_weight = conf3d_loss_weight\n        self.conf_3d_temperature = conf_3d_temperature\n\n        self.num_classes = num_classes\n        self.class_agnostic = class_agnostic\n\n    @force_fp32(apply_to=('box3d_quat', 'box3d_ctr', 'box3d_depth', 'box3d_size','box3d_conf', 'inv_intrinsics'))\n    def forward(\n        self, box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, dense_depth, inv_intrinsics, fcos2d_info,\n        targets\n    ):\n        labels = targets['labels']\n        box3d_targets = targets['box3d_targets']\n        pos_inds = targets[\"pos_inds\"]\n\n        if pos_inds.numel() == 0:\n            losses = {\n                \"loss_box3d_quat\": torch.stack([x.sum() * 0. for x in box3d_quat]).sum(), \n                \"loss_box3d_proj_ctr\": torch.stack([x.sum() * 0. for x in box3d_ctr]).sum(),\n                \"loss_box3d_depth\": torch.stack([x.sum() * 0. for x in box3d_depth]).sum(),\n                \"loss_box3d_size\": torch.stack([x.sum() * 0. for x in box3d_size]).sum(),\n                \"loss_conf3d\": torch.stack([x.sum() * 0. for x in box3d_conf]).sum()\n            }\n            return losses\n\n        if len(labels) != len(box3d_targets):\n            raise ValueError(\n                f\"The size of 'labels' and 'box3d_targets' does not match: a={len(labels)}, b={len(box3d_targets)}\"\n            )\n\n        num_classes = self.num_classes if not self.class_agnostic else 1\n\n        box3d_quat_pred = cat([x.permute(0, 2, 3, 1).reshape(-1, 4, num_classes) for x in box3d_quat])\n        box3d_ctr_pred = cat([x.permute(0, 2, 3, 1).reshape(-1, 2, num_classes) for x in box3d_ctr])\n        box3d_depth_pred = cat([x.permute(0, 2, 3, 1).reshape(-1, num_classes) for x in box3d_depth])\n        box3d_size_pred = cat([x.permute(0, 2, 3, 1).reshape(-1, 3, num_classes) for x in box3d_size])\n        box3d_conf_pred = cat([x.permute(0, 2, 3, 1).reshape(-1, num_classes) for x in box3d_conf])\n\n        # ----------------------\n        # 3D box disentangled loss\n        # ----------------------\n        box3d_targets = box3d_targets[pos_inds]\n\n        box3d_quat_pred = box3d_quat_pred[pos_inds]\n        box3d_ctr_pred = box3d_ctr_pred[pos_inds]\n        box3d_depth_pred = box3d_depth_pred[pos_inds]\n        box3d_size_pred = box3d_size_pred[pos_inds]\n        box3d_conf_pred = box3d_conf_pred[pos_inds]\n\n        if self.class_agnostic:\n            box3d_quat_pred = box3d_quat_pred.squeeze(-1)\n            box3d_ctr_pred = box3d_ctr_pred.squeeze(-1)\n            box3d_depth_pred = box3d_depth_pred.squeeze(-1)\n            box3d_size_pred = box3d_size_pred.squeeze(-1)\n            box3d_conf_pred = box3d_conf_pred.squeeze(-1)\n        else:\n            I = labels[pos_inds][..., None, None]\n            box3d_quat_pred = torch.gather(box3d_quat_pred, dim=2, index=I.repeat(1, 4, 1)).squeeze(-1)\n            box3d_ctr_pred = torch.gather(box3d_ctr_pred, dim=2, index=I.repeat(1, 2, 1)).squeeze(-1)\n            box3d_depth_pred = torch.gather(box3d_depth_pred, dim=1, index=I.squeeze(-1)).squeeze(-1)\n            box3d_size_pred = torch.gather(box3d_size_pred, dim=2, index=I.repeat(1, 3, 1)).squeeze(-1)\n            box3d_conf_pred = torch.gather(box3d_conf_pred, dim=1, index=I.squeeze(-1)).squeeze(-1)\n\n        canon_box_sizes = box3d_quat_pred.new_tensor(self.canon_box_sizes)[labels[pos_inds]]\n\n        locations = targets[\"locations\"][pos_inds]\n        im_inds = targets[\"im_inds\"][pos_inds]\n        inv_intrinsics = inv_intrinsics[im_inds]\n\n        box3d_pred = predictions_to_boxes3d(\n            box3d_quat_pred,\n            box3d_ctr_pred,\n            box3d_depth_pred,\n            box3d_size_pred,\n            locations,\n            inv_intrinsics,\n            canon_box_sizes,\n            self.min_depth,\n            self.max_depth,\n            scale_depth_by_focal_lengths_factor=self.scale_depth_by_focal_lengths_factor,\n            scale_depth_by_focal_lengths=self.scale_depth_by_focal_lengths,\n            quat_is_allocentric=self.predict_allocentric_rot,\n            depth_is_distance=self.predict_distance\n        )\n\n        centerness_targets = fcos2d_info[\"centerness_targets\"]\n        loss_denom = fcos2d_info[\"loss_denom\"]\n        losses_box3d, box3d_l1_error = self.box3d_reg_loss_fn(box3d_pred, box3d_targets, locations, centerness_targets)\n\n        losses_box3d = {k: self.box3d_loss_weight * v / loss_denom for k, v in losses_box3d.items()}\n\n        conf_3d_targets = torch.exp(-1. / self.conf_3d_temperature * box3d_l1_error)\n        loss_conf3d = F.binary_cross_entropy_with_logits(box3d_conf_pred, conf_3d_targets, reduction='none')\n        loss_conf3d = self.conf3d_loss_weight * (loss_conf3d * centerness_targets).sum() / loss_denom\n\n        losses = {\"loss_conf3d\": loss_conf3d, **losses_box3d}\n\n        return losses\n\n\nclass FCOS3DInference():\n    def __init__(self, cfg):\n        self.canon_box_sizes = cfg.DD3D.FCOS3D.CANONICAL_BOX3D_SIZES\n        self.min_depth = cfg.DD3D.FCOS3D.MIN_DEPTH\n        self.max_depth = cfg.DD3D.FCOS3D.MAX_DEPTH\n        self.predict_allocentric_rot = cfg.DD3D.FCOS3D.PREDICT_ALLOCENTRIC_ROT\n        self.scale_depth_by_focal_lengths = cfg.DD3D.FCOS3D.SCALE_DEPTH_BY_FOCAL_LENGTHS\n        self.scale_depth_by_focal_lengths_factor = cfg.DD3D.FCOS3D.SCALE_DEPTH_BY_FOCAL_LENGTHS_FACTOR\n        self.predict_distance = cfg.DD3D.FCOS3D.PREDICT_DISTANCE\n\n        self.num_classes = cfg.DD3D.NUM_CLASSES\n        self.class_agnostic = cfg.DD3D.FCOS3D.CLASS_AGNOSTIC_BOX3D\n\n    def __call__(\n        self, box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, inv_intrinsics, pred_instances, fcos2d_info\n    ):\n        # pred_instances: # List[List[Instances]], shape = (L, B)\n        for lvl, (box3d_quat_lvl, box3d_ctr_lvl, box3d_depth_lvl, box3d_size_lvl, box3d_conf_lvl) in \\\n            enumerate(zip(box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf)):\n\n            # In-place modification: update per-level pred_instances.\n            self.forward_for_single_feature_map(\n                box3d_quat_lvl, box3d_ctr_lvl, box3d_depth_lvl, box3d_size_lvl, box3d_conf_lvl, inv_intrinsics,\n                pred_instances[lvl], fcos2d_info[lvl]\n            )  # List of Instances; one for each image.\n\n    def forward_for_single_feature_map(\n        self, box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, inv_intrinsics, pred_instances, fcos2d_info\n    ):\n        N = box3d_quat.shape[0]\n\n        num_classes = self.num_classes if not self.class_agnostic else 1\n\n        box3d_quat = box3d_quat.permute(0, 2, 3, 1).reshape(N, -1, 4, num_classes)\n        box3d_ctr = box3d_ctr.permute(0, 2, 3, 1).reshape(N, -1, 2, num_classes)\n        box3d_depth = box3d_depth.permute(0, 2, 3, 1).reshape(N, -1, num_classes)\n        box3d_size = box3d_size.permute(0, 2, 3, 1).reshape(N, -1, 3, num_classes)\n        box3d_conf = box3d_conf.permute(0, 2, 3, 1).reshape(N, -1, num_classes).sigmoid()\n\n        for i in range(N):\n            fg_inds_per_im = fcos2d_info['fg_inds_per_im'][i]\n            class_inds_per_im = fcos2d_info['class_inds_per_im'][i]\n            topk_indices = fcos2d_info['topk_indices'][i]\n\n            box3d_quat_per_im = box3d_quat[i][fg_inds_per_im]\n            box3d_ctr_per_im = box3d_ctr[i][fg_inds_per_im]\n            box3d_depth_per_im = box3d_depth[i][fg_inds_per_im]\n            box3d_size_per_im = box3d_size[i][fg_inds_per_im]\n            box3d_conf_per_im = box3d_conf[i][fg_inds_per_im]\n\n            if self.class_agnostic:\n                box3d_quat_per_im = box3d_quat_per_im.squeeze(-1)\n                box3d_ctr_per_im = box3d_ctr_per_im.squeeze(-1)\n                box3d_depth_per_im = box3d_depth_per_im.squeeze(-1)\n                box3d_size_per_im = box3d_size_per_im.squeeze(-1)\n                box3d_conf_per_im = box3d_conf_per_im.squeeze(-1)\n            else:\n                I = class_inds_per_im[..., None, None]\n                box3d_quat_per_im = torch.gather(box3d_quat_per_im, dim=2, index=I.repeat(1, 4, 1)).squeeze(-1)\n                box3d_ctr_per_im = torch.gather(box3d_ctr_per_im, dim=2, index=I.repeat(1, 2, 1)).squeeze(-1)\n                box3d_depth_per_im = torch.gather(box3d_depth_per_im, dim=1, index=I.squeeze(-1)).squeeze(-1)\n                box3d_size_per_im = torch.gather(box3d_size_per_im, dim=2, index=I.repeat(1, 3, 1)).squeeze(-1)\n                box3d_conf_per_im = torch.gather(box3d_conf_per_im, dim=1, index=I.squeeze(-1)).squeeze(-1)\n\n            if topk_indices is not None:\n                box3d_quat_per_im = box3d_quat_per_im[topk_indices]\n                box3d_ctr_per_im = box3d_ctr_per_im[topk_indices]\n                box3d_depth_per_im = box3d_depth_per_im[topk_indices]\n                box3d_size_per_im = box3d_size_per_im[topk_indices]\n                box3d_conf_per_im = box3d_conf_per_im[topk_indices]\n\n            # scores_per_im = pred_instances[i].scores.square()\n            # NOTE: Before refactoring, the squared score was used. Is raw 2D score better?\n            scores_per_im = pred_instances[i].scores\n            scores_3d_per_im = scores_per_im * box3d_conf_per_im\n\n            canon_box_sizes = box3d_quat.new_tensor(self.canon_box_sizes)[pred_instances[i].pred_classes]\n            inv_K = inv_intrinsics[i][None, ...].expand(len(box3d_quat_per_im), 3, 3)\n            locations = pred_instances[i].locations\n            pred_boxes3d = predictions_to_boxes3d(\n                box3d_quat_per_im,\n                box3d_ctr_per_im,\n                box3d_depth_per_im,\n                box3d_size_per_im,\n                locations,\n                inv_K,\n                canon_box_sizes,\n                self.min_depth,\n                self.max_depth,\n                scale_depth_by_focal_lengths_factor=self.scale_depth_by_focal_lengths_factor,\n                scale_depth_by_focal_lengths=self.scale_depth_by_focal_lengths,\n                quat_is_allocentric=self.predict_allocentric_rot,\n                depth_is_distance=self.predict_distance\n            )\n\n            # In-place modification: add fields to instances.\n            pred_instances[i].pred_boxes3d = pred_boxes3d\n            pred_instances[i].scores_3d = scores_3d_per_im\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/nuscenes_dd3d.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport torch\nimport torch.nn.functional as F\nfrom mmcv.losses.fvcore_smooth_l1_loss import smooth_l1_loss\nfrom torch import nn\n\nfrom mmcv.structures import Instances\nfrom mmcv.models.builder import HEADS\nfrom mmcv.utils import force_fp32\nfrom torch import distributed as dist\nfrom mmcv.modeling.postprocessing import detector_postprocess as resize_instances\nfrom mmcv.layers import cat, Conv2d\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.datasets.nuscenes import MAX_NUM_ATTRIBUTES\nfrom .core import DD3D\nfrom .prepare_targets import DD3DTargetPreparer\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.boxes3d import Boxes3D\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.image_list import ImageList\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.comm import reduce_sum\n\nINF = 100000000.\n\ndef get_world_size() -> int:\n    if not dist.is_available():\n        return 1\n    if not dist.is_initialized():\n        return 1\n    return dist.get_world_size()\n\nclass NuscenesDD3DTargetPreparer(DD3DTargetPreparer):\n    def __init__(self, **kwargs):\n        super().__init__(**kwargs)\n        assert self.dd3d_enabled, f\"{type(self).__name__} requires dd3d_enabled = True\"\n\n    def __call__(self, locations, gt_instances, feature_shapes):\n        num_loc_list = [len(loc) for loc in locations]\n\n        # compute locations to size ranges\n        loc_to_size_range = []\n        for l, loc_per_level in enumerate(locations):\n            loc_to_size_range_per_level = loc_per_level.new_tensor(self.sizes_of_interest[l])\n            loc_to_size_range.append(loc_to_size_range_per_level[None].expand(num_loc_list[l], -1))\n\n        loc_to_size_range = torch.cat(loc_to_size_range, dim=0)\n        locations = torch.cat(locations, dim=0)\n\n        training_targets = self.compute_targets_for_locations(locations, gt_instances, loc_to_size_range, num_loc_list)\n\n        training_targets[\"locations\"] = [locations.clone() for _ in range(len(gt_instances))]\n        training_targets[\"im_inds\"] = [\n            locations.new_ones(locations.size(0), dtype=torch.long) * i for i in range(len(gt_instances))\n        ]\n\n        box2d = training_targets.pop(\"box2d\", None)\n\n        # transpose im first training_targets to level first ones\n        training_targets = {k: self._transpose(v, num_loc_list) for k, v in training_targets.items() if k != \"box2d\"}\n\n        training_targets[\"fpn_levels\"] = [\n            loc.new_ones(len(loc), dtype=torch.long) * level for level, loc in enumerate(training_targets[\"locations\"])\n        ]\n\n        # Flatten targets: (L x B x H x W, TARGET_SIZE)\n        labels = cat([x.reshape(-1) for x in training_targets[\"labels\"]])\n        box2d_reg_targets = cat([x.reshape(-1, 4) for x in training_targets[\"box2d_reg\"]])\n\n        target_inds = cat([x.reshape(-1) for x in training_targets[\"target_inds\"]])\n        locations = cat([x.reshape(-1, 2) for x in training_targets[\"locations\"]])\n        im_inds = cat([x.reshape(-1) for x in training_targets[\"im_inds\"]])\n        fpn_levels = cat([x.reshape(-1) for x in training_targets[\"fpn_levels\"]])\n\n        pos_inds = torch.nonzero(labels != self.num_classes).squeeze(1)\n\n        targets = {\n            \"labels\": labels,\n            \"box2d_reg_targets\": box2d_reg_targets,\n            \"locations\": locations,\n            \"target_inds\": target_inds,\n            \"im_inds\": im_inds,\n            \"fpn_levels\": fpn_levels,\n            \"pos_inds\": pos_inds\n        }\n\n        if self.dd3d_enabled:\n            box3d_targets = Boxes3D.cat(training_targets[\"box3d\"])\n            targets.update({\"box3d_targets\": box3d_targets})\n\n            if box2d is not None:\n                # Original format is B x L x (H x W, 4)\n                # Need to be in L x (B, 4, H, W).\n                batched_box2d = []\n                for lvl, per_lvl_box2d in enumerate(zip(*box2d)):\n                    # B x (H x W, 4)\n                    h, w = feature_shapes[lvl]\n                    batched_box2d_lvl = torch.stack([x.T.reshape(4, h, w) for x in per_lvl_box2d], dim=0)\n                    batched_box2d.append(batched_box2d_lvl)\n                targets.update({\"batched_box2d\": batched_box2d})\n\n        # Nuscenes targets -- attribute / speed\n        attributes = cat([x.reshape(-1) for x in training_targets[\"attributes\"]])\n        speeds = cat([x.reshape(-1) for x in training_targets[\"speeds\"]])\n\n        targets.update({'attributes': attributes, 'speeds': speeds})\n\n        return targets\n\n    def compute_targets_for_locations(self, locations, targets, size_ranges, num_loc_list):\n        labels = []\n        box2d_reg = []\n\n        if self.dd3d_enabled:\n            box3d = []\n\n        target_inds = []\n        xs, ys = locations[:, 0], locations[:, 1]\n\n        # NuScenes targets  -- attribute / speed\n        attributes, speeds = [], []\n\n        num_targets = 0\n        for im_i in range(len(targets)):\n            targets_per_im = targets[im_i]\n            bboxes = targets_per_im.gt_boxes.tensor\n            labels_per_im = targets_per_im.gt_classes\n\n            # no gt\n            if bboxes.numel() == 0:\n                labels.append(labels_per_im.new_zeros(locations.size(0)) + self.num_classes)\n                # reg_targets.append(locations.new_zeros((locations.size(0), 4)))\n                box2d_reg.append(locations.new_zeros((locations.size(0), 4)))\n                target_inds.append(labels_per_im.new_zeros(locations.size(0)) - 1)\n\n                if self.dd3d_enabled:\n                    box3d.append(\n                        Boxes3D(\n                            locations.new_zeros(locations.size(0), 4),\n                            locations.new_zeros(locations.size(0), 2),\n                            locations.new_zeros(locations.size(0), 1),\n                            locations.new_zeros(locations.size(0), 3),\n                            locations.new_zeros(locations.size(0), 3, 3),\n                        ).to(torch.float32)\n                    )\n                # NOTE: attributes and speeds.\n                attributes.append(labels_per_im.new_zeros(locations.size(0)))\n                speeds.append(labels_per_im.new_zeros(locations.size(0)))  \n                continue\n\n            area = targets_per_im.gt_boxes.area()\n\n            l = xs[:, None] - bboxes[:, 0][None]\n            t = ys[:, None] - bboxes[:, 1][None]\n            r = bboxes[:, 2][None] - xs[:, None]\n            b = bboxes[:, 3][None] - ys[:, None]\n            # reg_targets_per_im = torch.stack([l, t, r, b], dim=2)\n            box2d_reg_per_im = torch.stack([l, t, r, b], dim=2)\n\n            if self.center_sample:\n                is_in_boxes = self.get_sample_region(bboxes, num_loc_list, xs, ys)\n            else:\n                is_in_boxes = box2d_reg_per_im.min(dim=2)[0] > 0\n\n            max_reg_targets_per_im = box2d_reg_per_im.max(dim=2)[0]\n            # limit the regression range for each location\n            is_cared_in_the_level = \\\n                (max_reg_targets_per_im >= size_ranges[:, [0]]) & \\\n                (max_reg_targets_per_im <= size_ranges[:, [1]])\n\n            locations_to_gt_area = area[None].repeat(len(locations), 1)\n            locations_to_gt_area[is_in_boxes == 0] = INF\n            locations_to_gt_area[is_cared_in_the_level == 0] = INF\n\n            # if there are still more than one objects for a location,\n            # we choose the one with minimal area\n            locations_to_min_area, locations_to_gt_inds = locations_to_gt_area.min(dim=1)\n\n            box2d_reg_per_im = box2d_reg_per_im[range(len(locations)), locations_to_gt_inds]\n            target_inds_per_im = locations_to_gt_inds + num_targets\n            num_targets += len(targets_per_im)\n\n            labels_per_im = labels_per_im[locations_to_gt_inds]\n            labels_per_im[locations_to_min_area == INF] = self.num_classes\n\n            labels.append(labels_per_im)\n            box2d_reg.append(box2d_reg_per_im)\n            target_inds.append(target_inds_per_im)\n\n            if self.dd3d_enabled:\n                # 3D box targets\n                box3d_per_im = targets_per_im.gt_boxes3d[locations_to_gt_inds]\n                box3d.append(box3d_per_im)\n\n            # NuScenes targets  -- attribute / speed\n            attributes_per_im = targets_per_im.gt_attributes[locations_to_gt_inds]\n            speeds_per_im = targets_per_im.gt_speeds[locations_to_gt_inds]\n            attributes.append(attributes_per_im)\n            speeds.append(speeds_per_im)\n\n        ret = {\"labels\": labels, \"box2d_reg\": box2d_reg, \"target_inds\": target_inds}\n        if self.dd3d_enabled:\n            ret.update({\"box3d\": box3d})\n\n        # NuScenes targets  -- attribute / speed\n        ret.update({\"attributes\": attributes, \"speeds\": speeds})\n\n        return ret\n\n\nclass NuscenesLoss(nn.Module):\n    def __init__(self, attr_loss_weight=0.2, speed_loss_weight=0.2):\n        super().__init__()\n        self.attr_loss_weight = attr_loss_weight\n        self.speed_loss_weight = speed_loss_weight\n\n    @force_fp32(apply_to=('attr_logits', 'speeds'))\n    def forward(self, attr_logits, speeds, fcos2d_info, targets):\n        # Flatten predictions\n        attr_logits = cat([x.permute(0, 2, 3, 1).reshape(-1, MAX_NUM_ATTRIBUTES) for x in attr_logits])\n        speeds = cat([x.permute(0, 2, 3, 1).reshape(-1) for x in speeds])\n\n        pos_inds = targets['pos_inds']\n\n        losses = {}\n\n        # 1. Attributes\n        attr_logits = attr_logits[pos_inds]\n        target_attr = targets['attributes'][pos_inds]\n        valid_attr_mask = target_attr != MAX_NUM_ATTRIBUTES  # No attrs associated with class, or just attr missing.\n\n        if pos_inds.numel() == 0:\n            attr_weights = attr_logits.new_tensor(0.0) #torch.tensor(0.0).cuda()\n        else:\n            attr_weights = fcos2d_info['centerness_targets'][valid_attr_mask]\n        # Denominator for all foreground losses -- re-computed for features with valid attributes.\n        # attr_loss_denom = max(reduce_sum(attr_weights.sum()).item() / d2_comm.get_world_size(), 1e-6)\n        # NOTE: compute attr_weights_sum, and then feed it to reduce_sum() works, but not above.\n        attr_weights_sum = attr_weights.sum()\n        attr_loss_denom = max(reduce_sum(attr_weights_sum).item() / get_world_size(), 1e-6)\n\n        if valid_attr_mask.sum() == 0:\n            losses.update({\"loss_attr\": attr_logits.sum() * 0.})\n        else:\n            attr_logits = attr_logits[valid_attr_mask]\n            target_attr = target_attr[valid_attr_mask]\n\n            xent = F.cross_entropy(attr_logits, target_attr)\n            loss_attr = (xent * attr_weights).sum() / attr_loss_denom\n\n            losses.update({\"loss_attr\": self.attr_loss_weight * loss_attr})\n\n        # 2. Speed\n        speeds = speeds[pos_inds]\n        target_speeds = targets['speeds'][pos_inds]\n        # NOTE: some GT speeds are NaN.\n        valid_gt_mask = torch.logical_not(torch.isnan(target_speeds))\n\n        if pos_inds.numel() == 0:\n            speed_weights = speeds.new_tensor(0.0) #torch.tensor(0.0).cuda()\n        else:\n            speed_weights = fcos2d_info['centerness_targets'][valid_gt_mask]\n        # Denominator for all foreground losses -- re-computed for features with valid speeds.\n        # speed_loss_denom = max(reduce_sum(speed_weights.sum()).item() / d2_comm.get_world_size(), 1e-6)\n        speed_weights_sum = speed_weights.sum()\n        speed_loss_denom = max(reduce_sum(speed_weights_sum).item() / get_world_size(), 1e-6)\n\n        # NOTE: move after reduce sum\n        if pos_inds.numel() == 0:\n            losses = {\"loss_attr\": attr_logits.sum() * 0., \"loss_speed\": speeds.sum() * 0.}\n            # NOTE: This is probably un-reachable, because the training filter images with empty annotations.\n            # NOTE: If not, attr_weights can be unavailable in the reduce_sum below().\n            return losses\n\n        if valid_gt_mask.sum() == 0:\n            losses.update({\"loss_speed\": speeds.sum() * 0.})\n            # return losses\n        else:\n            speeds = speeds[valid_gt_mask]\n            target_speeds = target_speeds[valid_gt_mask]\n\n            l1_error = smooth_l1_loss(speeds, target_speeds, beta=0.05)\n            loss_speed = (l1_error * speed_weights).sum() / speed_loss_denom\n            losses.update({\"loss_speed\": self.speed_loss_weight * loss_speed})\n\n        return losses\n\n\nclass NuscenesInference():\n    def __init__(self, cfg):\n        pass\n\n    def __call__(self, attr_logits, speeds, pred_instances, fcos2d_info):\n        \"\"\"Add 'pred_attribute', 'pred_speed' to Instances in 'pred_instances'.\"\"\"\n        N = attr_logits[0].shape[0]\n        for lvl, (attr_logits_lvl, speed_lvl, info_lvl, instances_lvl) in \\\n            enumerate(zip(attr_logits, speeds, fcos2d_info, pred_instances)):\n\n            attr_logits_lvl = attr_logits_lvl.permute(0, 2, 3, 1).reshape(N, -1, MAX_NUM_ATTRIBUTES)\n            speed_lvl = speed_lvl.permute(0, 2, 3, 1).reshape(N, -1)\n            for i in range(N):\n                fg_inds_per_im = info_lvl['fg_inds_per_im'][i]\n                topk_indices = info_lvl['topk_indices'][i]\n\n                attr_logits_per_im = attr_logits_lvl[i][fg_inds_per_im]\n                speed_per_im = speed_lvl[i][fg_inds_per_im]\n\n                if topk_indices is not None:\n                    attr_logits_per_im = attr_logits_per_im[topk_indices]\n                    speed_per_im = speed_per_im[topk_indices]\n\n                if len(attr_logits_per_im) == 0:\n                    instances_lvl[i].pred_attributes = instances_lvl[i].pred_classes.new_tensor([])\n                    instances_lvl[i].pred_speeds = instances_lvl[i].scores.new_tensor([])\n                else:\n                    instances_lvl[i].pred_attributes = attr_logits_per_im.argmax(dim=1)\n                    instances_lvl[i].pred_speeds = speed_per_im\n\n\n@HEADS.register_module()\nclass NuscenesDD3D(DD3D):\n    def __init__(self, \n                 num_classes,\n                 in_channels,\n                 strides,\n                 fcos2d_cfg=dict(),\n                 fcos2d_loss_cfg=dict(),\n                 fcos3d_cfg=dict(),\n                 fcos3d_loss_cfg=dict(),\n                 target_assign_cfg=dict(),\n                 nusc_loss_weight=dict(),\n                 box3d_on=True,\n                 feature_locations_offset=\"none\"):\n        super().__init__(num_classes,\n                        in_channels,\n                        strides,\n                        fcos2d_cfg=fcos2d_cfg,\n                        fcos2d_loss_cfg=fcos2d_loss_cfg,\n                        fcos3d_cfg=fcos3d_cfg,\n                        fcos3d_loss_cfg=fcos3d_loss_cfg,\n                        target_assign_cfg=target_assign_cfg,\n                        box3d_on=box3d_on,\n                        feature_locations_offset=feature_locations_offset)\n\n        # backbone_output_shape = self.backbone_output_shape\n        # in_channels = backbone_output_shape[0].channels\n\n        # --------------------------------------------------------------------------\n        # NuScenes predictions -- attribute / speed, computed from cls_tower output.\n        # --------------------------------------------------------------------------\n        self.attr_logits = Conv2d(in_channels, MAX_NUM_ATTRIBUTES, kernel_size=3, stride=1, padding=1, bias=True)\n        self.speed = Conv2d(in_channels, 1, kernel_size=3, stride=1, padding=1, bias=True, activation=F.relu)\n\n        # init weights\n        for modules in [self.attr_logits, self.speed]:\n            for l in modules.modules():\n                if isinstance(l, nn.Conv2d):\n                    torch.nn.init.kaiming_uniform_(l.weight, a=1)\n                    if l.bias is not None:  # depth head may not have bias.\n                        torch.nn.init.constant_(l.bias, 0)\n\n        # Re-define target preparer\n        del self.prepare_targets\n        self.prepare_targets = NuscenesDD3DTargetPreparer(num_classes=num_classes, \n                                                          input_shape=self.backbone_output_shape,\n                                                          box3d_on=box3d_on,\n                                                          **target_assign_cfg)\n\n        self.nuscenes_loss = NuscenesLoss(**nusc_loss_weight)\n        # NOTE: inference later\n        # self.nuscenes_inference = NuscenesInference(cfg)\n\n        # self.num_images_per_sample = cfg.MODEL.FCOS3D.NUSC_NUM_IMAGES_PER_SAMPLE\n        # NOTE: inference later\n        # self.num_images_per_sample = cfg.DD3D.NUSC.INFERENCE.NUM_IMAGES_PER_SAMPLE\n\n        # assert self.num_images_per_sample == 6\n        # assert cfg.DATALOADER.TEST.NUM_IMAGES_PER_GROUP == 6\n\n        # NOTE: NuScenes evaluator allows max. 500 detections per sample.\n        # self.max_num_dets_per_sample = cfg.DD3D.NUSC.INFERENCE.MAX_NUM_DETS_PER_SAMPLE\n\n    @force_fp32(apply_to=('features'))\n    def forward(self, features, batched_inputs):\n        # NOTE:\n        # images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        # images = [self.preprocess_image(x) for x in images]\n\n        # NOTE: directly use inv_intrinsics\n        # if 'intrinsics' in batched_inputs[0]:\n        #     intrinsics = [x['intrinsics'].to(self.device) for x in batched_inputs]\n        # else:\n        #     intrinsics = None\n        # images = ImageList.from_tensors(images, self.backbone.size_divisibility, intrinsics=intrinsics)\n        if 'inv_intrinsics' in batched_inputs[0]:\n            inv_intrinsics = [x['inv_intrinsics'].to(features[0].device) for x in batched_inputs]\n            inv_intrinsics = torch.stack(inv_intrinsics, dim=0)\n        else:\n            inv_intrinsics = None\n\n        # NOTE:\n        # gt_dense_depth = None\n        # if 'depth' in batched_inputs[0]:\n        #     gt_dense_depth = [x[\"depth\"].to(self.device) for x in batched_inputs]\n        #     gt_dense_depth = ImageList.from_tensors(\n        #         gt_dense_depth, self.backbone.size_divisibility, intrinsics=intrinsics\n        #     )\n\n        # NOTE: directly input feature\n        # features = self.backbone(images.tensor)\n        # features = [features[f] for f in self.in_features]\n\n        if \"instances\" in batched_inputs[0]:\n            gt_instances = [x[\"instances\"].to(features[0].device) for x in batched_inputs]\n        else:\n            gt_instances = None\n\n        locations = self.compute_locations(features)\n        logits, box2d_reg, centerness, fcos2d_extra_output = self.fcos2d_head(features)\n        if not self.only_box2d:\n            box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, dense_depth = self.fcos3d_head(features)\n        # NOTE: directly use inv_intrinsics\n        # inv_intrinsics = images.intrinsics.inverse() if images.intrinsics is not None else None\n\n        # --------------------------------------------------------------------------\n        # NuScenes predictions -- attribute / speed, computed from cls_tower output.\n        # --------------------------------------------------------------------------\n        attr_logits, speeds = [], []\n        for x in fcos2d_extra_output['cls_tower_out']:\n            attr_logits.append(self.attr_logits(x))\n            speeds.append(self.speed(x))\n\n        if self.training:\n            assert gt_instances is not None\n            feature_shapes = [x.shape[-2:] for x in features]\n            training_targets = self.prepare_targets(locations, gt_instances, feature_shapes)\n            # NOTE: \n            # if gt_dense_depth is not None:\n            #    training_targets.update({\"dense_depth\": gt_dense_depth})\n\n            losses = {}\n            fcos2d_loss, fcos2d_info = self.fcos2d_loss(logits, box2d_reg, centerness, training_targets)\n            losses.update(fcos2d_loss)\n\n            if not self.only_box2d:\n                fcos3d_loss = self.fcos3d_loss(\n                    box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, dense_depth, inv_intrinsics,\n                    fcos2d_info, training_targets\n                )\n                losses.update(fcos3d_loss)\n\n            # Nuscenes loss -- attribute / speed\n            nuscenes_loss = self.nuscenes_loss(attr_logits, speeds, fcos2d_info, training_targets)\n            losses.update(nuscenes_loss)\n            return losses\n        else:\n            # TODO: do not support inference now\n            raise NotImplementedError\n            pred_instances, fcos2d_info = self.fcos2d_inference(\n                logits, box2d_reg, centerness, locations, images.image_sizes\n            )\n            if not self.only_box2d:\n                # This adds 'pred_boxes3d' and 'scores_3d' to Instances in 'pred_instances'.\n                self.fcos3d_inference(\n                    box3d_quat, box3d_ctr, box3d_depth, box3d_size, box3d_conf, inv_intrinsics, pred_instances,\n                    fcos2d_info\n                )\n                score_key = \"scores_3d\"\n            else:\n                score_key = \"scores\"\n\n            # This adds 'pred_attributes', 'pred_speed' to Instances in 'pred_instances'.\n            self.nuscenes_inference(attr_logits, speeds, pred_instances, fcos2d_info)\n\n            # Transpose to \"image-first\", i.e. (B, L)\n            pred_instances = list(zip(*pred_instances))\n            pred_instances = [Instances.cat(instances) for instances in pred_instances]\n\n            # 2D NMS and pick top-K.\n            if self.do_nms:\n                pred_instances = self.fcos2d_inference.nms_and_top_k(pred_instances, score_key)\n\n            if not self.only_box2d and self.do_bev_nms:\n                # Bird-eye-view NMS.\n                dummy_group_idxs = {i: [i] for i, _ in enumerate(pred_instances)}\n                if 'pose' in batched_inputs[0]:\n                    poses = [x['pose'] for x in batched_inputs]\n                else:\n                    poses = [x['extrinsics'] for x in batched_inputs]\n                pred_instances = nuscenes_sample_aggregate(\n                    pred_instances,\n                    dummy_group_idxs,\n                    self.num_classes,\n                    poses,\n                    iou_threshold=self.bev_nms_iou_thresh,\n                    include_boxes3d_global=False\n                )\n\n            if self.postprocess_in_inference:\n                processed_results = []\n                for results_per_image, input_per_image, image_size in \\\n                        zip(pred_instances, batched_inputs, images.image_sizes):\n                    height = input_per_image.get(\"height\", image_size[0])\n                    width = input_per_image.get(\"width\", image_size[1])\n                    r = resize_instances(results_per_image, height, width)\n                    processed_results.append({\"instances\": r})\n\n                # ----------------------------------------------------------\n                # NuScenes specific: cross-image (i.e. sample-level) BEV NMS.\n                # ----------------------------------------------------------\n                sample_tokens = [x['sample_token'] for x in batched_inputs]\n                group_idxs = get_group_idxs(sample_tokens, self.num_images_per_sample)\n\n                instances = [x['instances'] for x in processed_results]\n                global_poses = [x['pose'] for x in batched_inputs]\n\n                filtered_instances = nuscenes_sample_aggregate(\n                    instances,\n                    group_idxs,\n                    self.num_classes,\n                    global_poses,\n                    self.bev_nms_iou_thresh,\n                    max_num_dets_per_sample=self.max_num_dets_per_sample\n                )\n                processed_results = [{\"instances\": x} for x in filtered_instances]\n            else:\n                processed_results = [{\"instances\": x} for x in pred_instances]\n\n            return processed_results\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/modeling/prepare_targets.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport torch\n\nfrom mmcv.layers import cat\n\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.boxes3d import Boxes3D\n\nINF = 100000000.\n\n\nclass DD3DTargetPreparer():\n    def __init__(self, \n                 num_classes, \n                 input_shape,\n                 box3d_on=True,\n                 center_sample=True,\n                 pos_radius=1.5,\n                 sizes_of_interest=None):\n        self.num_classes = num_classes\n        self.center_sample = center_sample\n        self.strides = [shape.stride for shape in input_shape]\n        self.radius = pos_radius\n        self.dd3d_enabled = box3d_on\n\n        # generate sizes of interest\n        # NOTE:\n        # soi = []\n        # prev_size = -1\n        # for s in sizes_of_interest:\n        #     soi.append([prev_size, s])\n        #     prev_size = s\n        # soi.append([prev_size, INF])\n        self.sizes_of_interest = sizes_of_interest\n\n    def __call__(self, locations, gt_instances, feature_shapes):\n        num_loc_list = [len(loc) for loc in locations]\n\n        # compute locations to size ranges\n        loc_to_size_range = []\n        for l, loc_per_level in enumerate(locations):\n            loc_to_size_range_per_level = loc_per_level.new_tensor(self.sizes_of_interest[l])\n            loc_to_size_range.append(loc_to_size_range_per_level[None].expand(num_loc_list[l], -1))\n\n        loc_to_size_range = torch.cat(loc_to_size_range, dim=0)\n        locations = torch.cat(locations, dim=0)\n\n        training_targets = self.compute_targets_for_locations(locations, gt_instances, loc_to_size_range, num_loc_list)\n\n        training_targets[\"locations\"] = [locations.clone() for _ in range(len(gt_instances))]\n        training_targets[\"im_inds\"] = [\n            locations.new_ones(locations.size(0), dtype=torch.long) * i for i in range(len(gt_instances))\n        ]\n\n        box2d = training_targets.pop(\"box2d\", None)\n\n        # transpose im first training_targets to level first ones\n        training_targets = {k: self._transpose(v, num_loc_list) for k, v in training_targets.items() if k != \"box2d\"}\n\n        training_targets[\"fpn_levels\"] = [\n            loc.new_ones(len(loc), dtype=torch.long) * level for level, loc in enumerate(training_targets[\"locations\"])\n        ]\n\n        # Flatten targets: (L x B x H x W, TARGET_SIZE)\n        labels = cat([x.reshape(-1) for x in training_targets[\"labels\"]])\n        box2d_reg_targets = cat([x.reshape(-1, 4) for x in training_targets[\"box2d_reg\"]])\n\n        target_inds = cat([x.reshape(-1) for x in training_targets[\"target_inds\"]])\n        locations = cat([x.reshape(-1, 2) for x in training_targets[\"locations\"]])\n        im_inds = cat([x.reshape(-1) for x in training_targets[\"im_inds\"]])\n        fpn_levels = cat([x.reshape(-1) for x in training_targets[\"fpn_levels\"]])\n\n        pos_inds = torch.nonzero(labels != self.num_classes).squeeze(1)\n\n        targets = {\n            \"labels\": labels,\n            \"box2d_reg_targets\": box2d_reg_targets,\n            \"locations\": locations,\n            \"target_inds\": target_inds,\n            \"im_inds\": im_inds,\n            \"fpn_levels\": fpn_levels,\n            \"pos_inds\": pos_inds\n        }\n\n        if self.dd3d_enabled:\n            box3d_targets = Boxes3D.cat(training_targets[\"box3d\"])\n            targets.update({\"box3d_targets\": box3d_targets})\n\n            if box2d is not None:\n                # Original format is B x L x (H x W, 4)\n                # Need to be in L x (B, 4, H, W).\n                batched_box2d = []\n                for lvl, per_lvl_box2d in enumerate(zip(*box2d)):\n                    # B x (H x W, 4)\n                    h, w = feature_shapes[lvl]\n                    batched_box2d_lvl = torch.stack([x.T.reshape(4, h, w) for x in per_lvl_box2d], dim=0)\n                    batched_box2d.append(batched_box2d_lvl)\n                targets.update({\"batched_box2d\": batched_box2d})\n\n        return targets\n\n    def compute_targets_for_locations(self, locations, targets, size_ranges, num_loc_list):\n        labels = []\n        box2d_reg = []\n\n        if self.dd3d_enabled:\n            box3d = []\n\n        target_inds = []\n        xs, ys = locations[:, 0], locations[:, 1]\n\n        num_targets = 0\n        for im_i in range(len(targets)):\n            targets_per_im = targets[im_i]\n            bboxes = targets_per_im.gt_boxes.tensor\n            labels_per_im = targets_per_im.gt_classes\n\n            # no gt\n            if bboxes.numel() == 0:\n                labels.append(labels_per_im.new_zeros(locations.size(0)) + self.num_classes)\n                # reg_targets.append(locations.new_zeros((locations.size(0), 4)))\n                box2d_reg.append(locations.new_zeros((locations.size(0), 4)))\n                target_inds.append(labels_per_im.new_zeros(locations.size(0)) - 1)\n\n                if self.dd3d_enabled:\n                    box3d.append(\n                        Boxes3D(\n                            locations.new_zeros(locations.size(0), 4),\n                            locations.new_zeros(locations.size(0), 2),\n                            locations.new_zeros(locations.size(0), 1),\n                            locations.new_zeros(locations.size(0), 3),\n                            locations.new_zeros(locations.size(0), 3, 3),\n                        ).to(torch.float32)\n                    )\n                continue\n\n            area = targets_per_im.gt_boxes.area()\n\n            l = xs[:, None] - bboxes[:, 0][None]\n            t = ys[:, None] - bboxes[:, 1][None]\n            r = bboxes[:, 2][None] - xs[:, None]\n            b = bboxes[:, 3][None] - ys[:, None]\n            # reg_targets_per_im = torch.stack([l, t, r, b], dim=2)\n            box2d_reg_per_im = torch.stack([l, t, r, b], dim=2)\n\n            if self.center_sample:\n                is_in_boxes = self.get_sample_region(bboxes, num_loc_list, xs, ys)\n            else:\n                is_in_boxes = box2d_reg_per_im.min(dim=2)[0] > 0\n\n            max_reg_targets_per_im = box2d_reg_per_im.max(dim=2)[0]\n            # limit the regression range for each location\n            is_cared_in_the_level = \\\n                (max_reg_targets_per_im >= size_ranges[:, [0]]) & \\\n                (max_reg_targets_per_im <= size_ranges[:, [1]])\n\n            locations_to_gt_area = area[None].repeat(len(locations), 1)\n            locations_to_gt_area[is_in_boxes == 0] = INF\n            locations_to_gt_area[is_cared_in_the_level == 0] = INF\n\n            # if there are still more than one objects for a location,\n            # we choose the one with minimal area\n            locations_to_min_area, locations_to_gt_inds = locations_to_gt_area.min(dim=1)\n\n            box2d_reg_per_im = box2d_reg_per_im[range(len(locations)), locations_to_gt_inds]\n            target_inds_per_im = locations_to_gt_inds + num_targets\n            num_targets += len(targets_per_im)\n\n            labels_per_im = labels_per_im[locations_to_gt_inds]\n            labels_per_im[locations_to_min_area == INF] = self.num_classes\n\n            labels.append(labels_per_im)\n            box2d_reg.append(box2d_reg_per_im)\n            target_inds.append(target_inds_per_im)\n\n            if self.dd3d_enabled:\n                # 3D box targets\n                box3d_per_im = targets_per_im.gt_boxes3d[locations_to_gt_inds]\n                box3d.append(box3d_per_im)\n\n        ret = {\"labels\": labels, \"box2d_reg\": box2d_reg, \"target_inds\": target_inds}\n        if self.dd3d_enabled:\n            ret.update({\"box3d\": box3d})\n\n        return ret\n\n    def get_sample_region(self, boxes, num_loc_list, loc_xs, loc_ys):\n        center_x = boxes[..., [0, 2]].sum(dim=-1) * 0.5\n        center_y = boxes[..., [1, 3]].sum(dim=-1) * 0.5\n\n        num_gts = boxes.shape[0]\n        K = len(loc_xs)\n        boxes = boxes[None].expand(K, num_gts, 4)\n        center_x = center_x[None].expand(K, num_gts)\n        center_y = center_y[None].expand(K, num_gts)\n        center_gt = boxes.new_zeros(boxes.shape)\n        # no gt\n        if center_x.numel() == 0 or center_x[..., 0].sum() == 0:\n            return loc_xs.new_zeros(loc_xs.shape, dtype=torch.uint8)\n        beg = 0\n        for level, num_loc in enumerate(num_loc_list):\n            end = beg + num_loc\n            stride = self.strides[level] * self.radius\n            xmin = center_x[beg:end] - stride\n            ymin = center_y[beg:end] - stride\n            xmax = center_x[beg:end] + stride\n            ymax = center_y[beg:end] + stride\n            # limit sample region in gt\n            center_gt[beg:end, :, 0] = torch.where(xmin > boxes[beg:end, :, 0], xmin, boxes[beg:end, :, 0])\n            center_gt[beg:end, :, 1] = torch.where(ymin > boxes[beg:end, :, 1], ymin, boxes[beg:end, :, 1])\n            center_gt[beg:end, :, 2] = torch.where(xmax > boxes[beg:end, :, 2], boxes[beg:end, :, 2], xmax)\n            center_gt[beg:end, :, 3] = torch.where(ymax > boxes[beg:end, :, 3], boxes[beg:end, :, 3], ymax)\n            beg = end\n        left = loc_xs[:, None] - center_gt[..., 0]\n        right = center_gt[..., 2] - loc_xs[:, None]\n        top = loc_ys[:, None] - center_gt[..., 1]\n        bottom = center_gt[..., 3] - loc_ys[:, None]\n        center_bbox = torch.stack((left, top, right, bottom), -1)\n        inside_gt_bbox_mask = center_bbox.min(-1)[0] > 0\n        return inside_gt_bbox_mask\n\n    def _transpose(self, training_targets, num_loc_list):\n        '''\n        This function is used to transpose image first training targets to level first ones\n        :return: level first training targets\n        '''\n        if isinstance(training_targets[0], Boxes3D):\n            for im_i in range(len(training_targets)):\n                # training_targets[im_i] = torch.split(training_targets[im_i], num_loc_list, dim=0)\n                training_targets[im_i] = training_targets[im_i].split(num_loc_list, dim=0)\n\n            targets_level_first = []\n            for targets_per_level in zip(*training_targets):\n                targets_level_first.append(Boxes3D.cat(targets_per_level, dim=0))\n            return targets_level_first\n\n        for im_i in range(len(training_targets)):\n            training_targets[im_i] = torch.split(training_targets[im_i], num_loc_list, dim=0)\n\n        targets_level_first = []\n        for targets_per_level in zip(*training_targets):\n            targets_level_first.append(torch.cat(targets_per_level, dim=0))\n        return targets_level_first\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/structures/__init__.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nfrom .image_list import ImageList\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/structures/boxes3d.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport numpy as np\nimport torch\nfrom pyquaternion import Quaternion\nfrom torch.cuda import amp\n\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.geometry import unproject_points2d\nimport adzoo.bevformer.mmdet3d_plugin.dd3d.structures.transform3d as t3d\n# yapf: disable\nBOX3D_CORNER_MAPPING = [\n    [1, 1, 1, 1, -1, -1, -1, -1],\n    [1, -1, -1, 1, 1, -1, -1, 1],\n    [1, 1, -1, -1, 1, 1, -1, -1]\n]\n# yapf: enable\n\ndef quaternion_to_matrix(quaternions: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Convert rotations given as quaternions to rotation matrices.\n\n    Args:\n        quaternions: quaternions with real part first,\n            as tensor of shape (..., 4).\n\n    Returns:\n        Rotation matrices as tensor of shape (..., 3, 3).\n    \"\"\"\n    r, i, j, k = torch.unbind(quaternions, -1)\n    two_s = 2.0 / (quaternions * quaternions).sum(-1)\n\n    o = torch.stack(\n        (\n            1 - two_s * (j * j + k * k),\n            two_s * (i * j - k * r),\n            two_s * (i * k + j * r),\n            two_s * (i * j + k * r),\n            1 - two_s * (i * i + k * k),\n            two_s * (j * k - i * r),\n            two_s * (i * k - j * r),\n            two_s * (j * k + i * r),\n            1 - two_s * (i * i + j * j),\n        ),\n        -1,\n    )\n    return o.reshape(quaternions.shape[:-1] + (3, 3))\n\ndef _to_tensor(x, dim):\n    if isinstance(x, torch.Tensor):\n        x = x.to(torch.float32)\n    elif isinstance(x, np.ndarray) or isinstance(x, list) or isinstance(x, tuple):\n        x = torch.tensor(x, dtype=torch.float32)\n    elif isinstance(x, Quaternion):\n        x = torch.tensor(x.elements, dtype=torch.float32)\n    else:\n        raise ValueError(f\"Unsupported type: {type(x).__name__}\")\n\n    if x.ndim == 1:\n        x = x.reshape(-1, dim)\n    elif x.ndim > 2:\n        raise ValueError(f\"Invalid shape of input: {x.shape.__str__()}\")\n    return x\n\n\nclass GenericBoxes3D():\n    def __init__(self, quat, tvec, size):\n        self.quat = _to_tensor(quat, dim=4)\n        self._tvec = _to_tensor(tvec, dim=3)\n        self.size = _to_tensor(size, dim=3)\n\n    @property\n    def tvec(self):\n        return self._tvec\n\n    @property\n    @amp.autocast(enabled=False)\n    def corners(self):\n        allow_tf32 = torch.backends.cuda.matmul.allow_tf32\n        torch.backends.cuda.matmul.allow_tf32 = False\n        torch.backends.cudnn.allow_tf32 = False\n\n        translation = t3d.Translate(self.tvec, device=self.device)\n\n        R = quaternion_to_matrix(self.quat)\n        rotation = t3d.Rotate(R=R.transpose(1, 2), device=self.device)  # Need to transpose to make it work.\n\n        tfm = rotation.compose(translation)\n\n        _corners = 0.5 * self.quat.new_tensor(BOX3D_CORNER_MAPPING).T\n        # corners_in_obj_frame = self.size.unsqueeze(1) * _corners.unsqueeze(0)\n        lwh = self.size[:, [1, 0, 2]]  # wlh -> lwh\n        corners_in_obj_frame = lwh.unsqueeze(1) * _corners.unsqueeze(0)\n\n        corners3d = tfm.transform_points(corners_in_obj_frame)\n        torch.backends.cuda.matmul.allow_tf32 = allow_tf32\n        torch.backends.cudnn.allow_tf32 = allow_tf32\n        return corners3d\n\n    @classmethod\n    def from_vectors(cls, vecs, device=\"cpu\"):\n        \"\"\"\n        Parameters\n        ----------\n        vecs: Iterable[np.ndarray]\n            Iterable of 10D pose representation.\n\n        intrinsics: np.ndarray\n            (3, 3) intrinsics matrix.\n        \"\"\"\n        quats, tvecs, sizes = [], [], []\n        for vec in vecs:\n            quat = vec[:4]\n            tvec = vec[4:7]\n            size = vec[7:]\n\n            quats.append(quat)\n            tvecs.append(tvec)\n            sizes.append(size)\n\n        quats = torch.as_tensor(quats, dtype=torch.float32, device=device)\n        tvecs = torch.as_tensor(tvecs, dtype=torch.float32, device=device)\n        sizes = torch.as_tensor(sizes, device=device)\n\n        return cls(quats, tvecs, sizes)\n\n    @classmethod\n    def cat(cls, boxes_list, dim=0):\n\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0), torch.empty(0), torch.empty(0))\n        assert all([isinstance(box, GenericBoxes3D) for box in boxes_list])\n\n        # use torch.cat (v.s. layers.cat) so the returned boxes never share storage with input\n        quat = torch.cat([b.quat for b in boxes_list], dim=dim)\n        tvec = torch.cat([b.tvec for b in boxes_list], dim=dim)\n        size = torch.cat([b.size for b in boxes_list], dim=dim)\n\n        cat_boxes = cls(quat, tvec, size)\n        return cat_boxes\n\n    def split(self, split_sizes, dim=0):\n        assert sum(split_sizes) == len(self)\n        quat_list = torch.split(self.quat, split_sizes, dim=dim)\n        tvec_list = torch.split(self.tvec, split_sizes, dim=dim)\n        size_list = torch.split(self.size, split_sizes, dim=dim)\n\n        return [GenericBoxes3D(*x) for x in zip(quat_list, tvec_list, size_list)]\n\n    def __getitem__(self, item):\n        \"\"\"\n        \"\"\"\n        if isinstance(item, int):\n            return GenericBoxes3D(self.quat[item].view(1, -1), self.tvec[item].view(1, -1), self.size[item].view(1, -1))\n\n        quat = self.quat[item]\n        tvec = self.tvec[item]\n        size = self.size[item]\n\n        assert quat.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert tvec.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert size.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n\n        return GenericBoxes3D(quat, tvec, size)\n\n    def __len__(self):\n        assert len(self.quat) == len(self.tvec) == len(self.size)\n        return self.quat.shape[0]\n\n    def clone(self):\n        \"\"\"\n        \"\"\"\n        return GenericBoxes3D(self.quat.clone(), self.tvec.clone(), self.size.clone())\n\n    def vectorize(self):\n        xyz = self.tvec\n        return torch.cat([self.quat, xyz, self.size], dim=1)\n\n    @property\n    def device(self):\n        return self.quat.device\n\n    def to(self, *args, **kwargs):\n        quat = self.quat.to(*args, **kwargs)\n        tvec = self.tvec.to(*args, **kwargs)\n        size = self.size.to(*args, **kwargs)\n        return GenericBoxes3D(quat, tvec, size)\n\n\nclass Boxes3D(GenericBoxes3D):\n    \"\"\"Vision-based 3D box container.\n\n    The tvec is computed from projected center, depth, and intrinsics.\n    \"\"\"\n    def __init__(self, quat, proj_ctr, depth, size, inv_intrinsics):\n        self.quat = quat\n        self.proj_ctr = proj_ctr\n        self.depth = depth\n        self.size = size\n        self.inv_intrinsics = inv_intrinsics\n\n    @property\n    def tvec(self):\n        ray = unproject_points2d(self.proj_ctr, self.inv_intrinsics)\n        xyz = ray * self.depth\n        return xyz\n\n    @classmethod\n    def from_vectors(cls, vecs, intrinsics, device=\"cpu\"):\n        \"\"\"\n        Parameters\n        ----------\n        vecs: Iterable[np.ndarray]\n            Iterable of 10D pose representation.\n\n        intrinsics: np.ndarray\n            (3, 3) intrinsics matrix.\n        \"\"\"\n        if len(vecs) == 0:\n            quats = torch.as_tensor([], dtype=torch.float32, device=device).view(-1, 4)\n            proj_ctrs = torch.as_tensor([], dtype=torch.float32, device=device).view(-1, 2)\n            depths = torch.as_tensor([], dtype=torch.float32, device=device).view(-1, 1)\n            sizes = torch.as_tensor([], dtype=torch.float32, device=device).view(-1, 3)\n            inv_intrinsics = torch.as_tensor([], dtype=torch.float32, device=device).view(-1, 3, 3)\n            return cls(quats, proj_ctrs, depths, sizes, inv_intrinsics)\n\n        quats, proj_ctrs, depths, sizes = [], [], [], []\n        for vec in vecs:\n            quat = vec[:4]\n\n            proj_ctr = intrinsics.dot(vec[4:7])\n            proj_ctr = proj_ctr[:2] / proj_ctr[-1]\n\n            depth = vec[6:7]\n\n            size = vec[7:]\n\n            quats.append(quat)\n            proj_ctrs.append(proj_ctr)\n            depths.append(depth)\n            sizes.append(size)\n\n        quats = torch.as_tensor(np.array(quats), dtype=torch.float32, device=device)\n        proj_ctrs = torch.as_tensor(np.array(proj_ctrs), dtype=torch.float32, device=device)\n        depths = torch.as_tensor(np.array(depths), dtype=torch.float32, device=device)\n        sizes = torch.as_tensor(np.array(sizes), dtype=torch.float32, device=device)\n\n        inv_intrinsics = np.linalg.inv(intrinsics)\n        inv_intrinsics = torch.as_tensor(inv_intrinsics[None, ...], device=device).expand(len(vecs), 3, 3)\n\n        return cls(quats, proj_ctrs, depths, sizes, inv_intrinsics)\n\n    @classmethod\n    def cat(cls, boxes_list, dim=0):\n\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0), torch.empty(0), torch.empty(0), torch.empty(0), torch.empty(0))\n        assert all([isinstance(box, Boxes3D) for box in boxes_list])\n\n        # use torch.cat (v.s. layers.cat) so the returned boxes never share storage with input\n        quat = torch.cat([b.quat for b in boxes_list], dim=dim)\n        proj_ctr = torch.cat([b.proj_ctr for b in boxes_list], dim=dim)\n        depth = torch.cat([b.depth for b in boxes_list], dim=dim)\n        size = torch.cat([b.size for b in boxes_list], dim=dim)\n        inv_intrinsics = torch.cat([b.inv_intrinsics for b in boxes_list], dim=dim)\n\n        cat_boxes = cls(quat, proj_ctr, depth, size, inv_intrinsics)\n        return cat_boxes\n\n    def split(self, split_sizes, dim=0):\n        assert sum(split_sizes) == len(self)\n        quat_list = torch.split(self.quat, split_sizes, dim=dim)\n        proj_ctr_list = torch.split(self.proj_ctr, split_sizes, dim=dim)\n        depth_list = torch.split(self.depth, split_sizes, dim=dim)\n        size_list = torch.split(self.size, split_sizes, dim=dim)\n        inv_K_list = torch.split(self.inv_intrinsics, split_sizes, dim=dim)\n\n        return [Boxes3D(*x) for x in zip(quat_list, proj_ctr_list, depth_list, size_list, inv_K_list)]\n\n    def __getitem__(self, item):\n        \"\"\"\n        \"\"\"\n        if isinstance(item, int):\n            return Boxes3D(\n                self.quat[item].view(1, -1), self.proj_ctr[item].view(1, -1), self.depth[item].view(1, -1),\n                self.size[item].view(1, -1), self.inv_intrinsics[item].view(1, 3, 3)\n            )\n\n        quat = self.quat[item]\n        ctr = self.proj_ctr[item]\n        depth = self.depth[item]\n        size = self.size[item]\n        inv_K = self.inv_intrinsics[item]\n\n        assert quat.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert ctr.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert depth.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert size.dim() == 2, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert inv_K.dim() == 3, \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n        assert inv_K.shape[1:] == (3, 3), \"Indexing on Boxes3D with {} failed to return a matrix!\".format(item)\n\n        return Boxes3D(quat, ctr, depth, size, inv_K)\n\n    def __len__(self):\n        assert len(self.quat) == len(self.proj_ctr) == len(self.depth) == len(self.size) == len(self.inv_intrinsics)\n        return self.quat.shape[0]\n\n    def clone(self):\n        \"\"\"\n        \"\"\"\n        return Boxes3D(\n            self.quat.clone(), self.proj_ctr.clone(), self.depth.clone(), self.size.clone(), self.inv_intrinsics.clone()\n        )\n\n    def to(self, *args, **kwargs):\n        quat = self.quat.to(*args, **kwargs)\n        proj_ctr = self.proj_ctr.to(*args, **kwargs)\n        depth = self.depth.to(*args, **kwargs)\n        size = self.size.to(*args, **kwargs)\n        inv_K = self.inv_intrinsics.to(*args, **kwargs)\n        return Boxes3D(quat, proj_ctr, depth, size, inv_K)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/structures/image_list.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved.\n# Copyright 2021 Toyota Research Institute.  All rights reserved.\nfrom __future__ import division\n\nfrom typing import Any, List, Sequence, Tuple\n\nimport torch\nfrom torch import device\nfrom torch.nn import functional as F\n\nTORCH_VERSION = tuple(int(x) for x in torch.__version__.split(\".\")[:2])\n\ndef _as_tensor(x: Tuple[int, int]) -> torch.Tensor:\n    \"\"\"\n    An equivalent of `torch.as_tensor`, but works under tracing if input\n    is a list of tensor. `torch.as_tensor` will record a constant in tracing,\n    but this function will use `torch.stack` instead.\n    \"\"\"\n    if torch.jit.is_scripting():\n        return torch.as_tensor(x)\n    if isinstance(x, (list, tuple)) and all([isinstance(t, torch.Tensor) for t in x]):\n        return torch.stack(x)\n    return torch.as_tensor(x)\n\n\nclass ImageList(object):\n    \"\"\"\n    Adapted from detectron2:\n        https://github.com/facebookresearch/detectron2/blob/master/detectron2/structures/image_list.py)\n\n    Key differences:\n        - add optional intrinsics\n        - add optional image path (useful for debugging)\n    ==================================================================================================================\n\n    Structure that holds a list of images (of possibly\n    varying sizes) as a single tensor.\n    This works by padding the images to the same size,\n    and storing in a field the original sizes of each image\n\n    Attributes:\n        image_sizes (list[tuple[int, int]]): each tuple is (h, w)\n    \"\"\"\n    def __init__(self, tensor: torch.Tensor, image_sizes: List[Tuple[int, int]], intrinsics=None, image_paths=None):\n        \"\"\"\n        Arguments:\n            tensor (Tensor): of shape (N, H, W) or (N, C_1, ..., C_K, H, W) where K >= 1\n            image_sizes (list[tuple[int, int]]): Each tuple is (h, w). It can\n                be smaller than (H, W) due to padding.\n        \"\"\"\n        self.tensor = tensor\n        self.image_sizes = image_sizes\n        self._intrinsics = intrinsics\n        self._image_paths = image_paths\n\n    @property\n    def intrinsics(self):\n        if torch.allclose(self._intrinsics[0], torch.eye(3, device=self._intrinsics.device)):\n            # TODO: torch.inverse(images.intrinsics) often return identity, when it shouldn't. Is it pytorch bug?\n            raise ValueError(\"Intrinsics is Identity.\")\n        return self._intrinsics\n\n    @property\n    def image_paths(self):\n        return self._image_paths\n\n    def __len__(self) -> int:\n        return len(self.image_sizes)\n\n    def __getitem__(self, idx) -> torch.Tensor:\n        \"\"\"\n        Access the individual image in its original size.\n\n        Args:\n            idx: int or slice\n\n        Returns:\n            Tensor: an image of shape (H, W) or (C_1, ..., C_K, H, W) where K >= 1\n        \"\"\"\n        size = self.image_sizes[idx]\n        return self.tensor[idx, ..., :size[0], :size[1]]\n\n    @torch.jit.unused\n    def to(self, *args: Any, **kwargs: Any) -> \"ImageList\":\n        cast_tensor = self.tensor.to(*args, **kwargs)\n        return ImageList(cast_tensor, self.image_sizes, intrinsics=self.intrinsics)\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    @staticmethod\n    def from_tensors(\n        tensors: List[torch.Tensor],\n        size_divisibility: int = 0,\n        pad_value: float = 0.0,\n        intrinsics=None,\n        image_paths=None\n    ) -> \"ImageList\":\n        \"\"\"\n        Args:\n            tensors: a tuple or list of `torch.Tensor`, each of shape (Hi, Wi) or\n                (C_1, ..., C_K, Hi, Wi) where K >= 1. The Tensors will be padded\n                to the same shape with `pad_value`.\n            size_divisibility (int): If `size_divisibility > 0`, add padding to ensure\n                the common height and width is divisible by `size_divisibility`.\n                This depends on the model and many models need a divisibility of 32.\n            pad_value (float): value to pad\n\n        Returns:\n            an `ImageList`.\n        \"\"\"\n        assert len(tensors) > 0\n        assert isinstance(tensors, (tuple, list))\n        for t in tensors:\n            assert isinstance(t, torch.Tensor), type(t)\n            assert t.shape[:-2] == tensors[0].shape[:-2], t.shape\n\n        image_sizes = [(im.shape[-2], im.shape[-1]) for im in tensors]\n        image_sizes_tensor = [_as_tensor(x) for x in image_sizes]\n        max_size = torch.stack(image_sizes_tensor).max(0).values\n\n        if size_divisibility > 1:\n            stride = size_divisibility\n            # the last two dims are H,W, both subject to divisibility requirement\n            max_size = torch.div(max_size + (stride - 1),  stride, rounding_mode='floor') * stride\n\n        # handle weirdness of scripting and tracing ...\n        if torch.jit.is_scripting():\n            max_size: List[int] = max_size.to(dtype=torch.long).tolist()\n        else:\n            # https://github.com/pytorch/pytorch/issues/42448\n            if TORCH_VERSION >= (1, 7) and torch.jit.is_tracing():\n                image_sizes = image_sizes_tensor\n\n        if len(tensors) == 1:\n            # This seems slightly (2%) faster.\n            # TODO: check whether it's faster for multiple images as well\n            image_size = image_sizes[0]\n            padding_size = [0, max_size[-1] - image_size[1], 0, max_size[-2] - image_size[0]]\n            batched_imgs = F.pad(tensors[0], padding_size, value=pad_value).unsqueeze_(0)\n        else:\n            # max_size can be a tensor in tracing mode, therefore convert to list\n            batch_shape = [len(tensors)] + list(tensors[0].shape[:-2]) + list(max_size)\n            batched_imgs = tensors[0].new_full(batch_shape, pad_value)\n            for img, pad_img in zip(tensors, batched_imgs):\n                pad_img[..., :img.shape[-2], :img.shape[-1]].copy_(img)\n\n        if intrinsics is not None:\n            assert isinstance(intrinsics, (tuple, list))\n            assert len(intrinsics) == len(tensors)\n            intrinsics = torch.stack(intrinsics, dim=0)\n\n        if image_paths is not None:\n            assert len(image_paths) == len(tensors)\n\n        return ImageList(batched_imgs.contiguous(), image_sizes, intrinsics, image_paths)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/structures/pose.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport numpy as np\nfrom pyquaternion import Quaternion\n\n\nclass Pose:\n    \"\"\"SE(3) rigid transform class that allows compounding of 6-DOF poses\n    and provides common transformations that are commonly seen in geometric problems.\n    \"\"\"\n    def __init__(self, wxyz=np.float32([1., 0., 0., 0.]), tvec=np.float32([0., 0., 0.])):\n        \"\"\"Initialize a Pose with Quaternion and 3D Position\n\n        Parameters\n        ----------\n        wxyz: np.float32 or Quaternion (default: np.float32([1,0,0,0]))\n            Quaternion/Rotation (wxyz)\n\n        tvec: np.float32 (default: np.float32([0,0,0]))\n            Translation (xyz)\n        \"\"\"\n        assert isinstance(wxyz, (np.ndarray, Quaternion))\n        assert isinstance(tvec, np.ndarray)\n\n        if isinstance(wxyz, np.ndarray):\n            assert np.abs(1.0 - np.linalg.norm(wxyz)) < 1.0e-3\n\n        self.quat = Quaternion(wxyz)\n        self.tvec = tvec\n\n    def __repr__(self):\n        formatter = {'float_kind': lambda x: '%.2f' % x}\n        tvec_str = np.array2string(self.tvec, formatter=formatter)\n        return 'wxyz: {}, tvec: ({})'.format(self.quat, tvec_str)\n\n    def copy(self):\n        \"\"\"Return a copy of this pose object.\n\n        Returns\n        ----------\n        result: Pose\n            Copied pose object.\n        \"\"\"\n        return self.__class__(Quaternion(self.quat), self.tvec.copy())\n\n    def __mul__(self, other):\n        \"\"\"Left-multiply Pose with another Pose or 3D-Points.\n\n        Parameters\n        ----------\n        other: Pose or np.ndarray\n            1. Pose: Identical to oplus operation.\n               (i.e. self_pose * other_pose)\n            2. ndarray: transform [N x 3] point set\n               (i.e. X' = self_pose * X)\n\n        Returns\n        ----------\n        result: Pose or np.ndarray\n            Transformed pose or point cloud\n        \"\"\"\n        if isinstance(other, Pose):\n            assert isinstance(other, self.__class__)\n            t = self.quat.rotate(other.tvec) + self.tvec\n            q = self.quat * other.quat\n            return self.__class__(q, t)\n        elif isinstance(other, np.ndarray):\n            assert other.shape[-1] == 3, 'Point cloud is not 3-dimensional'\n            X = np.hstack([other, np.ones((len(other), 1))]).T\n            return (np.dot(self.matrix, X).T)[:, :3]\n        else:\n            return NotImplemented\n\n    def __rmul__(self, other):\n        raise NotImplementedError('Right multiply not implemented yet!')\n\n    def inverse(self):\n        \"\"\"Returns a new Pose that corresponds to the\n        inverse of this one.\n\n        Returns\n        ----------\n        result: Pose\n            Inverted pose\n        \"\"\"\n        qinv = self.quat.inverse\n        return self.__class__(qinv, qinv.rotate(-self.tvec))\n\n    @property\n    def matrix(self):\n        \"\"\"Returns a 4x4 homogeneous matrix of the form [R t; 0 1]\n\n        Returns\n        ----------\n        result: np.ndarray\n            4x4 homogeneous matrix\n        \"\"\"\n        result = self.quat.transformation_matrix\n        result[:3, 3] = self.tvec\n        return result\n\n    @property\n    def rotation_matrix(self):\n        \"\"\"Returns the 3x3 rotation matrix (R)\n\n        Returns\n        ----------\n        result: np.ndarray\n            3x3 rotation matrix\n        \"\"\"\n        result = self.quat.transformation_matrix\n        return result[:3, :3]\n\n    @property\n    def rotation(self):\n        \"\"\"Return the rotation component of the pose as a Quaternion object.\n\n        Returns\n        ----------\n        self.quat: Quaternion\n            Rotation component of the Pose object.\n        \"\"\"\n        return self.quat\n\n    @property\n    def translation(self):\n        \"\"\"Return the translation component of the pose as a np.ndarray.\n\n        Returns\n        ----------\n        self.tvec: np.ndarray\n            Translation component of the Pose object.\n        \"\"\"\n        return self.tvec\n\n    @classmethod\n    def from_matrix(cls, transformation_matrix):\n        \"\"\"Initialize pose from 4x4 transformation matrix\n\n        Parameters\n        ----------\n        transformation_matrix: np.ndarray\n            4x4 containing rotation/translation\n\n        Returns\n        -------\n        Pose\n        \"\"\"\n        return cls(wxyz=Quaternion(matrix=transformation_matrix[:3, :3]), tvec=np.float32(transformation_matrix[:3, 3]))\n\n    @classmethod\n    def from_rotation_translation(cls, rotation_matrix, tvec):\n        \"\"\"Initialize pose from rotation matrix and translation vector.\n\n        Parameters\n        ----------\n        rotation_matrix : np.ndarray\n            3x3 rotation matrix\n        tvec : np.ndarray\n            length-3 translation vector\n        \"\"\"\n        return cls(wxyz=Quaternion(matrix=rotation_matrix), tvec=np.float64(tvec))\n\n    def __eq__(self, other):\n        return self.quat == other.quat and (self.tvec == other.tvec).all()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/structures/transform3d.py",
    "content": "# Copyright (c) Meta Platforms, Inc. and affiliates.\n# All rights reserved.\n#\n# This source code is licensed under the BSD-style license found in the\n# LICENSE file in the root directory of this source tree.\n\nimport math\nimport warnings\nfrom typing import List, Optional, Union\n\nimport torch\n\nDevice = Union[str, torch.device]\n\n\ndef make_device(device: Device) -> torch.device:\n    \"\"\"\n    Makes an actual torch.device object from the device specified as\n    either a string or torch.device object. If the device is `cuda` without\n    a specific index, the index of the current device is assigned.\n\n    Args:\n        device: Device (as str or torch.device)\n\n    Returns:\n        A matching torch.device object\n    \"\"\"\n    device = torch.device(device) if isinstance(device, str) else device\n    if device.type == \"cuda\" and device.index is None:  # pyre-ignore[16]\n        # If cuda but with no index, then the current cuda device is indicated.\n        # In that case, we fix to that device\n        device = torch.device(f\"cuda:{torch.cuda.current_device()}\")\n    return device\n\n\ndef get_device(x, device: Optional[Device] = None) -> torch.device:\n    \"\"\"\n    Gets the device of the specified variable x if it is a tensor, or\n    falls back to a default CPU device otherwise. Allows overriding by\n    providing an explicit device.\n\n    Args:\n        x: a torch.Tensor to get the device from or another type\n        device: Device (as str or torch.device) to fall back to\n\n    Returns:\n        A matching torch.device object\n    \"\"\"\n\n    # User overrides device\n    if device is not None:\n        return make_device(device)\n\n    # Set device based on input tensor\n    if torch.is_tensor(x):\n        return x.device\n\n    # Default device is cpu\n    return torch.device(\"cpu\")\n\n\ndef _safe_det_3x3(t: torch.Tensor):\n    \"\"\"\n    Fast determinant calculation for a batch of 3x3 matrices.\n\n    Note, result of this function might not be the same as `torch.det()`.\n    The differences might be in the last significant digit.\n\n    Args:\n        t: Tensor of shape (N, 3, 3).\n\n    Returns:\n        Tensor of shape (N) with determinants.\n    \"\"\"\n\n    det = (\n        t[..., 0, 0] * (t[..., 1, 1] * t[..., 2, 2] - t[..., 1, 2] * t[..., 2, 1])\n        - t[..., 0, 1] * (t[..., 1, 0] * t[..., 2, 2] - t[..., 2, 0] * t[..., 1, 2])\n        + t[..., 0, 2] * (t[..., 1, 0] * t[..., 2, 1] - t[..., 2, 0] * t[..., 1, 1])\n    )\n\n    return det\n\ndef _axis_angle_rotation(axis: str, angle: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Return the rotation matrices for one of the rotations about an axis\n    of which Euler angles describe, for each value of the angle given.\n\n    Args:\n        axis: Axis label \"X\" or \"Y or \"Z\".\n        angle: any shape tensor of Euler angles in radians\n\n    Returns:\n        Rotation matrices as tensor of shape (..., 3, 3).\n    \"\"\"\n\n    cos = torch.cos(angle)\n    sin = torch.sin(angle)\n    one = torch.ones_like(angle)\n    zero = torch.zeros_like(angle)\n\n    if axis == \"X\":\n        R_flat = (one, zero, zero, zero, cos, -sin, zero, sin, cos)\n    elif axis == \"Y\":\n        R_flat = (cos, zero, sin, zero, one, zero, -sin, zero, cos)\n    elif axis == \"Z\":\n        R_flat = (cos, -sin, zero, sin, cos, zero, zero, zero, one)\n    else:\n        raise ValueError(\"letter must be either X, Y or Z.\")\n\n    return torch.stack(R_flat, -1).reshape(angle.shape + (3, 3))\n\nclass Transform3d:\n    \"\"\"\n    A Transform3d object encapsulates a batch of N 3D transformations, and knows\n    how to transform points and normal vectors. Suppose that t is a Transform3d;\n    then we can do the following:\n\n    .. code-block:: python\n\n        N = len(t)\n        points = torch.randn(N, P, 3)\n        normals = torch.randn(N, P, 3)\n        points_transformed = t.transform_points(points)    # => (N, P, 3)\n        normals_transformed = t.transform_normals(normals)  # => (N, P, 3)\n\n\n    BROADCASTING\n    Transform3d objects supports broadcasting. Suppose that t1 and tN are\n    Transform3d objects with len(t1) == 1 and len(tN) == N respectively. Then we\n    can broadcast transforms like this:\n\n    .. code-block:: python\n\n        t1.transform_points(torch.randn(P, 3))     # => (P, 3)\n        t1.transform_points(torch.randn(1, P, 3))  # => (1, P, 3)\n        t1.transform_points(torch.randn(M, P, 3))  # => (M, P, 3)\n        tN.transform_points(torch.randn(P, 3))     # => (N, P, 3)\n        tN.transform_points(torch.randn(1, P, 3))  # => (N, P, 3)\n\n\n    COMBINING TRANSFORMS\n    Transform3d objects can be combined in two ways: composing and stacking.\n    Composing is function composition. Given Transform3d objects t1, t2, t3,\n    the following all compute the same thing:\n\n    .. code-block:: python\n\n        y1 = t3.transform_points(t2.transform_points(t1.transform_points(x)))\n        y2 = t1.compose(t2).compose(t3).transform_points(x)\n        y3 = t1.compose(t2, t3).transform_points(x)\n\n\n    Composing transforms should broadcast.\n\n    .. code-block:: python\n\n        if len(t1) == 1 and len(t2) == N, then len(t1.compose(t2)) == N.\n\n    We can also stack a sequence of Transform3d objects, which represents\n    composition along the batch dimension; then the following should compute the\n    same thing.\n\n    .. code-block:: python\n\n        N, M = len(tN), len(tM)\n        xN = torch.randn(N, P, 3)\n        xM = torch.randn(M, P, 3)\n        y1 = torch.cat([tN.transform_points(xN), tM.transform_points(xM)], dim=0)\n        y2 = tN.stack(tM).transform_points(torch.cat([xN, xM], dim=0))\n\n    BUILDING TRANSFORMS\n    We provide convenience methods for easily building Transform3d objects\n    as compositions of basic transforms.\n\n    .. code-block:: python\n\n        # Scale by 0.5, then translate by (1, 2, 3)\n        t1 = Transform3d().scale(0.5).translate(1, 2, 3)\n\n        # Scale each axis by a different amount, then translate, then scale\n        t2 = Transform3d().scale(1, 3, 3).translate(2, 3, 1).scale(2.0)\n\n        t3 = t1.compose(t2)\n        tN = t1.stack(t3, t3)\n\n\n    BACKPROP THROUGH TRANSFORMS\n    When building transforms, we can also parameterize them by Torch tensors;\n    in this case we can backprop through the construction and application of\n    Transform objects, so they could be learned via gradient descent or\n    predicted by a neural network.\n\n    .. code-block:: python\n\n        s1_params = torch.randn(N, requires_grad=True)\n        t_params = torch.randn(N, 3, requires_grad=True)\n        s2_params = torch.randn(N, 3, requires_grad=True)\n\n        t = Transform3d().scale(s1_params).translate(t_params).scale(s2_params)\n        x = torch.randn(N, 3)\n        y = t.transform_points(x)\n        loss = compute_loss(y)\n        loss.backward()\n\n        with torch.no_grad():\n            s1_params -= lr * s1_params.grad\n            t_params -= lr * t_params.grad\n            s2_params -= lr * s2_params.grad\n\n    CONVENTIONS\n    We adopt a right-hand coordinate system, meaning that rotation about an axis\n    with a positive angle results in a counter clockwise rotation.\n\n    This class assumes that transformations are applied on inputs which\n    are row vectors. The internal representation of the Nx4x4 transformation\n    matrix is of the form:\n\n    .. code-block:: python\n\n        M = [\n                [Rxx, Ryx, Rzx, 0],\n                [Rxy, Ryy, Rzy, 0],\n                [Rxz, Ryz, Rzz, 0],\n                [Tx,  Ty,  Tz,  1],\n            ]\n\n    To apply the transformation to points which are row vectors, the M matrix\n    can be pre multiplied by the points:\n\n    .. code-block:: python\n\n        points = [[0, 1, 2]]  # (1 x 3) xyz coordinates of a point\n        transformed_points = points * M\n\n    \"\"\"\n\n    def __init__(\n        self,\n        dtype: torch.dtype = torch.float32,\n        device: Device = \"cpu\",\n        matrix: Optional[torch.Tensor] = None,\n    ) -> None:\n        \"\"\"\n        Args:\n            dtype: The data type of the transformation matrix.\n                to be used if `matrix = None`.\n            device: The device for storing the implemented transformation.\n                If `matrix != None`, uses the device of input `matrix`.\n            matrix: A tensor of shape (4, 4) or of shape (minibatch, 4, 4)\n                representing the 4x4 3D transformation matrix.\n                If `None`, initializes with identity using\n                the specified `device` and `dtype`.\n        \"\"\"\n\n        if matrix is None:\n            self._matrix = torch.eye(4, dtype=dtype, device=device).view(1, 4, 4)\n        else:\n            if matrix.ndim not in (2, 3):\n                raise ValueError('\"matrix\" has to be a 2- or a 3-dimensional tensor.')\n            if matrix.shape[-2] != 4 or matrix.shape[-1] != 4:\n                raise ValueError(\n                    '\"matrix\" has to be a tensor of shape (minibatch, 4, 4)'\n                )\n            # set dtype and device from matrix\n            dtype = matrix.dtype\n            device = matrix.device\n            self._matrix = matrix.view(-1, 4, 4)\n\n        self._transforms = []  # store transforms to compose\n        self._lu = None\n        self.device = make_device(device)\n        self.dtype = dtype\n\n    def __len__(self) -> int:\n        return self.get_matrix().shape[0]\n\n    def __getitem__(\n        self, index: Union[int, List[int], slice, torch.Tensor]\n    ) -> \"Transform3d\":\n        \"\"\"\n        Args:\n            index: Specifying the index of the transform to retrieve.\n                Can be an int, slice, list of ints, boolean, long tensor.\n                Supports negative indices.\n\n        Returns:\n            Transform3d object with selected transforms. The tensors are not cloned.\n        \"\"\"\n        if isinstance(index, int):\n            index = [index]\n        return self.__class__(matrix=self.get_matrix()[index])\n\n    def compose(self, *others: \"Transform3d\") -> \"Transform3d\":\n        \"\"\"\n        Return a new Transform3d representing the composition of self with the\n        given other transforms, which will be stored as an internal list.\n\n        Args:\n            *others: Any number of Transform3d objects\n\n        Returns:\n            A new Transform3d with the stored transforms\n        \"\"\"\n        out = Transform3d(dtype=self.dtype, device=self.device)\n        out._matrix = self._matrix.clone()\n        for other in others:\n            if not isinstance(other, Transform3d):\n                msg = \"Only possible to compose Transform3d objects; got %s\"\n                raise ValueError(msg % type(other))\n        out._transforms = self._transforms + list(others)\n        return out\n\n    def get_matrix(self) -> torch.Tensor:\n        \"\"\"\n        Return a matrix which is the result of composing this transform\n        with others stored in self.transforms. Where necessary transforms\n        are broadcast against each other.\n        For example, if self.transforms contains transforms t1, t2, and t3, and\n        given a set of points x, the following should be true:\n\n        .. code-block:: python\n\n            y1 = t1.compose(t2, t3).transform(x)\n            y2 = t3.transform(t2.transform(t1.transform(x)))\n            y1.get_matrix() == y2.get_matrix()\n\n        Returns:\n            A transformation matrix representing the composed inputs.\n        \"\"\"\n        composed_matrix = self._matrix.clone()\n        if len(self._transforms) > 0:\n            for other in self._transforms:\n                other_matrix = other.get_matrix()\n                composed_matrix = _broadcast_bmm(composed_matrix, other_matrix)\n        return composed_matrix\n\n    def _get_matrix_inverse(self) -> torch.Tensor:\n        \"\"\"\n        Return the inverse of self._matrix.\n        \"\"\"\n        return torch.inverse(self._matrix)\n\n    def inverse(self, invert_composed: bool = False) -> \"Transform3d\":\n        \"\"\"\n        Returns a new Transform3d object that represents an inverse of the\n        current transformation.\n\n        Args:\n            invert_composed:\n                - True: First compose the list of stored transformations\n                  and then apply inverse to the result. This is\n                  potentially slower for classes of transformations\n                  with inverses that can be computed efficiently\n                  (e.g. rotations and translations).\n                - False: Invert the individual stored transformations\n                  independently without composing them.\n\n        Returns:\n            A new Transform3d object containing the inverse of the original\n            transformation.\n        \"\"\"\n\n        tinv = Transform3d(dtype=self.dtype, device=self.device)\n\n        if invert_composed:\n            # first compose then invert\n            tinv._matrix = torch.inverse(self.get_matrix())\n        else:\n            # self._get_matrix_inverse() implements efficient inverse\n            # of self._matrix\n            i_matrix = self._get_matrix_inverse()\n\n            # 2 cases:\n            if len(self._transforms) > 0:\n                # a) Either we have a non-empty list of transforms:\n                # Here we take self._matrix and append its inverse at the\n                # end of the reverted _transforms list. After composing\n                # the transformations with get_matrix(), this correctly\n                # right-multiplies by the inverse of self._matrix\n                # at the end of the composition.\n                tinv._transforms = [t.inverse() for t in reversed(self._transforms)]\n                last = Transform3d(dtype=self.dtype, device=self.device)\n                last._matrix = i_matrix\n                tinv._transforms.append(last)\n            else:\n                # b) Or there are no stored transformations\n                # we just set inverted matrix\n                tinv._matrix = i_matrix\n\n        return tinv\n\n    def stack(self, *others: \"Transform3d\") -> \"Transform3d\":\n        \"\"\"\n        Return a new batched Transform3d representing the batch elements from\n        self and all the given other transforms all batched together.\n\n        Args:\n            *others: Any number of Transform3d objects\n\n        Returns:\n            A new Transform3d.\n        \"\"\"\n        transforms = [self] + list(others)\n        matrix = torch.cat([t.get_matrix() for t in transforms], dim=0)\n        out = Transform3d(dtype=self.dtype, device=self.device)\n        out._matrix = matrix\n        return out\n\n    def transform_points(self, points, eps: Optional[float] = None) -> torch.Tensor:\n        \"\"\"\n        Use this transform to transform a set of 3D points. Assumes row major\n        ordering of the input points.\n\n        Args:\n            points: Tensor of shape (P, 3) or (N, P, 3)\n            eps: If eps!=None, the argument is used to clamp the\n                last coordinate before performing the final division.\n                The clamping corresponds to:\n                last_coord := (last_coord.sign() + (last_coord==0)) *\n                torch.clamp(last_coord.abs(), eps),\n                i.e. the last coordinates that are exactly 0 will\n                be clamped to +eps.\n\n        Returns:\n            points_out: points of shape (N, P, 3) or (P, 3) depending\n            on the dimensions of the transform\n        \"\"\"\n        points_batch = points.clone()\n        if points_batch.dim() == 2:\n            points_batch = points_batch[None]  # (P, 3) -> (1, P, 3)\n        if points_batch.dim() != 3:\n            msg = \"Expected points to have dim = 2 or dim = 3: got shape %r\"\n            raise ValueError(msg % repr(points.shape))\n\n        N, P, _3 = points_batch.shape\n        ones = torch.ones(N, P, 1, dtype=points.dtype, device=points.device)\n        points_batch = torch.cat([points_batch, ones], dim=2)\n\n        composed_matrix = self.get_matrix()\n        points_out = _broadcast_bmm(points_batch, composed_matrix)\n        denom = points_out[..., 3:]  # denominator\n        if eps is not None:\n            denom_sign = denom.sign() + (denom == 0.0).type_as(denom)\n            denom = denom_sign * torch.clamp(denom.abs(), eps)\n        points_out = points_out[..., :3] / denom\n\n        # When transform is (1, 4, 4) and points is (P, 3) return\n        # points_out of shape (P, 3)\n        if points_out.shape[0] == 1 and points.dim() == 2:\n            points_out = points_out.reshape(points.shape)\n\n        return points_out\n\n    def transform_normals(self, normals) -> torch.Tensor:\n        \"\"\"\n        Use this transform to transform a set of normal vectors.\n\n        Args:\n            normals: Tensor of shape (P, 3) or (N, P, 3)\n\n        Returns:\n            normals_out: Tensor of shape (P, 3) or (N, P, 3) depending\n            on the dimensions of the transform\n        \"\"\"\n        if normals.dim() not in [2, 3]:\n            msg = \"Expected normals to have dim = 2 or dim = 3: got shape %r\"\n            raise ValueError(msg % (normals.shape,))\n        composed_matrix = self.get_matrix()\n\n        # TODO: inverse is bad! Solve a linear system instead\n        mat = composed_matrix[:, :3, :3]\n        normals_out = _broadcast_bmm(normals, mat.transpose(1, 2).inverse())\n\n        # This doesn't pass unit tests. TODO investigate further\n        # if self._lu is None:\n        #     self._lu = self._matrix[:, :3, :3].transpose(1, 2).lu()\n        # normals_out = normals.lu_solve(*self._lu)\n\n        # When transform is (1, 4, 4) and normals is (P, 3) return\n        # normals_out of shape (P, 3)\n        if normals_out.shape[0] == 1 and normals.dim() == 2:\n            normals_out = normals_out.reshape(normals.shape)\n\n        return normals_out\n\n    def translate(self, *args, **kwargs) -> \"Transform3d\":\n        return self.compose(\n            Translate(device=self.device, dtype=self.dtype, *args, **kwargs)\n        )\n\n    def scale(self, *args, **kwargs) -> \"Transform3d\":\n        return self.compose(\n            Scale(device=self.device, dtype=self.dtype, *args, **kwargs)\n        )\n\n    def rotate(self, *args, **kwargs) -> \"Transform3d\":\n        return self.compose(\n            Rotate(device=self.device, dtype=self.dtype, *args, **kwargs)\n        )\n\n    def rotate_axis_angle(self, *args, **kwargs) -> \"Transform3d\":\n        return self.compose(\n            RotateAxisAngle(device=self.device, dtype=self.dtype, *args, **kwargs)\n        )\n\n    def clone(self) -> \"Transform3d\":\n        \"\"\"\n        Deep copy of Transforms object. All internal tensors are cloned\n        individually.\n\n        Returns:\n            new Transforms object.\n        \"\"\"\n        other = Transform3d(dtype=self.dtype, device=self.device)\n        if self._lu is not None:\n            other._lu = [elem.clone() for elem in self._lu]\n        other._matrix = self._matrix.clone()\n        other._transforms = [t.clone() for t in self._transforms]\n        return other\n\n    def to(\n        self,\n        device: Device,\n        copy: bool = False,\n        dtype: Optional[torch.dtype] = None,\n    ) -> \"Transform3d\":\n        \"\"\"\n        Match functionality of torch.Tensor.to()\n        If copy = True or the self Tensor is on a different device, the\n        returned tensor is a copy of self with the desired torch.device.\n        If copy = False and the self Tensor already has the correct torch.device,\n        then self is returned.\n\n        Args:\n          device: Device (as str or torch.device) for the new tensor.\n          copy: Boolean indicator whether or not to clone self. Default False.\n          dtype: If not None, casts the internal tensor variables\n              to a given torch.dtype.\n\n        Returns:\n          Transform3d object.\n        \"\"\"\n        device_ = make_device(device)\n        dtype_ = self.dtype if dtype is None else dtype\n        skip_to = self.device == device_ and self.dtype == dtype_\n\n        if not copy and skip_to:\n            return self\n\n        other = self.clone()\n\n        if skip_to:\n            return other\n\n        other.device = device_\n        other.dtype = dtype_\n        other._matrix = other._matrix.to(device=device_, dtype=dtype_)\n        other._transforms = [\n            t.to(device_, copy=copy, dtype=dtype_) for t in other._transforms\n        ]\n        return other\n\n    def cpu(self) -> \"Transform3d\":\n        return self.to(\"cpu\")\n\n    def cuda(self) -> \"Transform3d\":\n        return self.to(\"cuda\")\n\n\nclass Translate(Transform3d):\n    def __init__(\n        self,\n        x,\n        y=None,\n        z=None,\n        dtype: torch.dtype = torch.float32,\n        device: Optional[Device] = None,\n    ) -> None:\n        \"\"\"\n        Create a new Transform3d representing 3D translations.\n\n        Option I: Translate(xyz, dtype=torch.float32, device='cpu')\n            xyz should be a tensor of shape (N, 3)\n\n        Option II: Translate(x, y, z, dtype=torch.float32, device='cpu')\n            Here x, y, and z will be broadcast against each other and\n            concatenated to form the translation. Each can be:\n                - A python scalar\n                - A torch scalar\n                - A 1D torch tensor\n        \"\"\"\n        xyz = _handle_input(x, y, z, dtype, device, \"Translate\")\n        super().__init__(device=xyz.device, dtype=dtype)\n        N = xyz.shape[0]\n\n        mat = torch.eye(4, dtype=dtype, device=self.device)\n        mat = mat.view(1, 4, 4).repeat(N, 1, 1)\n        mat[:, 3, :3] = xyz\n        self._matrix = mat\n\n    def _get_matrix_inverse(self) -> torch.Tensor:\n        \"\"\"\n        Return the inverse of self._matrix.\n        \"\"\"\n        inv_mask = self._matrix.new_ones([1, 4, 4])\n        inv_mask[0, 3, :3] = -1.0\n        i_matrix = self._matrix * inv_mask\n        return i_matrix\n\n\nclass Scale(Transform3d):\n    def __init__(\n        self,\n        x,\n        y=None,\n        z=None,\n        dtype: torch.dtype = torch.float32,\n        device: Optional[Device] = None,\n    ) -> None:\n        \"\"\"\n        A Transform3d representing a scaling operation, with different scale\n        factors along each coordinate axis.\n\n        Option I: Scale(s, dtype=torch.float32, device='cpu')\n            s can be one of\n                - Python scalar or torch scalar: Single uniform scale\n                - 1D torch tensor of shape (N,): A batch of uniform scale\n                - 2D torch tensor of shape (N, 3): Scale differently along each axis\n\n        Option II: Scale(x, y, z, dtype=torch.float32, device='cpu')\n            Each of x, y, and z can be one of\n                - python scalar\n                - torch scalar\n                - 1D torch tensor\n        \"\"\"\n        xyz = _handle_input(x, y, z, dtype, device, \"scale\", allow_singleton=True)\n        super().__init__(device=xyz.device, dtype=dtype)\n        N = xyz.shape[0]\n\n        # TODO: Can we do this all in one go somehow?\n        mat = torch.eye(4, dtype=dtype, device=self.device)\n        mat = mat.view(1, 4, 4).repeat(N, 1, 1)\n        mat[:, 0, 0] = xyz[:, 0]\n        mat[:, 1, 1] = xyz[:, 1]\n        mat[:, 2, 2] = xyz[:, 2]\n        self._matrix = mat\n\n    def _get_matrix_inverse(self) -> torch.Tensor:\n        \"\"\"\n        Return the inverse of self._matrix.\n        \"\"\"\n        xyz = torch.stack([self._matrix[:, i, i] for i in range(4)], dim=1)\n        ixyz = 1.0 / xyz\n        imat = torch.diag_embed(ixyz, dim1=1, dim2=2)\n        return imat\n\n\nclass Rotate(Transform3d):\n    def __init__(\n        self,\n        R: torch.Tensor,\n        dtype: torch.dtype = torch.float32,\n        device: Optional[Device] = None,\n        orthogonal_tol: float = 1e-5,\n    ) -> None:\n        \"\"\"\n        Create a new Transform3d representing 3D rotation using a rotation\n        matrix as the input.\n\n        Args:\n            R: a tensor of shape (3, 3) or (N, 3, 3)\n            orthogonal_tol: tolerance for the test of the orthogonality of R\n\n        \"\"\"\n        device_ = get_device(R, device)\n        super().__init__(device=device_, dtype=dtype)\n        if R.dim() == 2:\n            R = R[None]\n        if R.shape[-2:] != (3, 3):\n            msg = \"R must have shape (3, 3) or (N, 3, 3); got %s\"\n            raise ValueError(msg % repr(R.shape))\n        R = R.to(device=device_, dtype=dtype)\n        _check_valid_rotation_matrix(R, tol=orthogonal_tol)\n        N = R.shape[0]\n        mat = torch.eye(4, dtype=dtype, device=device_)\n        mat = mat.view(1, 4, 4).repeat(N, 1, 1)\n        mat[:, :3, :3] = R\n        self._matrix = mat\n\n    def _get_matrix_inverse(self) -> torch.Tensor:\n        \"\"\"\n        Return the inverse of self._matrix.\n        \"\"\"\n        return self._matrix.permute(0, 2, 1).contiguous()\n\n\nclass RotateAxisAngle(Rotate):\n    def __init__(\n        self,\n        angle,\n        axis: str = \"X\",\n        degrees: bool = True,\n        dtype: torch.dtype = torch.float32,\n        device: Optional[Device] = None,\n    ) -> None:\n        \"\"\"\n        Create a new Transform3d representing 3D rotation about an axis\n        by an angle.\n\n        Assuming a right-hand coordinate system, positive rotation angles result\n        in a counter clockwise rotation.\n\n        Args:\n            angle:\n                - A torch tensor of shape (N,)\n                - A python scalar\n                - A torch scalar\n            axis:\n                string: one of [\"X\", \"Y\", \"Z\"] indicating the axis about which\n                to rotate.\n                NOTE: All batch elements are rotated about the same axis.\n        \"\"\"\n        axis = axis.upper()\n        if axis not in [\"X\", \"Y\", \"Z\"]:\n            msg = \"Expected axis to be one of ['X', 'Y', 'Z']; got %s\"\n            raise ValueError(msg % axis)\n        angle = _handle_angle_input(angle, dtype, device, \"RotateAxisAngle\")\n        angle = (angle / 180.0 * math.pi) if degrees else angle\n        # We assume the points on which this transformation will be applied\n        # are row vectors. The rotation matrix returned from _axis_angle_rotation\n        # is for transforming column vectors. Therefore we transpose this matrix.\n        # R will always be of shape (N, 3, 3)\n        R = _axis_angle_rotation(axis, angle).transpose(1, 2)\n        super().__init__(device=angle.device, R=R, dtype=dtype)\n\n\ndef _handle_coord(c, dtype: torch.dtype, device: torch.device) -> torch.Tensor:\n    \"\"\"\n    Helper function for _handle_input.\n\n    Args:\n        c: Python scalar, torch scalar, or 1D torch tensor\n\n    Returns:\n        c_vec: 1D torch tensor\n    \"\"\"\n    if not torch.is_tensor(c):\n        c = torch.tensor(c, dtype=dtype, device=device)\n    if c.dim() == 0:\n        c = c.view(1)\n    if c.device != device or c.dtype != dtype:\n        c = c.to(device=device, dtype=dtype)\n    return c\n\n\ndef _handle_input(\n    x,\n    y,\n    z,\n    dtype: torch.dtype,\n    device: Optional[Device],\n    name: str,\n    allow_singleton: bool = False,\n) -> torch.Tensor:\n    \"\"\"\n    Helper function to handle parsing logic for building transforms. The output\n    is always a tensor of shape (N, 3), but there are several types of allowed\n    input.\n\n    Case I: Single Matrix\n        In this case x is a tensor of shape (N, 3), and y and z are None. Here just\n        return x.\n\n    Case II: Vectors and Scalars\n        In this case each of x, y, and z can be one of the following\n            - Python scalar\n            - Torch scalar\n            - Torch tensor of shape (N, 1) or (1, 1)\n        In this case x, y and z are broadcast to tensors of shape (N, 1)\n        and concatenated to a tensor of shape (N, 3)\n\n    Case III: Singleton (only if allow_singleton=True)\n        In this case y and z are None, and x can be one of the following:\n            - Python scalar\n            - Torch scalar\n            - Torch tensor of shape (N, 1) or (1, 1)\n        Here x will be duplicated 3 times, and we return a tensor of shape (N, 3)\n\n    Returns:\n        xyz: Tensor of shape (N, 3)\n    \"\"\"\n    device_ = get_device(x, device)\n    # If x is actually a tensor of shape (N, 3) then just return it\n    if torch.is_tensor(x) and x.dim() == 2:\n        if x.shape[1] != 3:\n            msg = \"Expected tensor of shape (N, 3); got %r (in %s)\"\n            raise ValueError(msg % (x.shape, name))\n        if y is not None or z is not None:\n            msg = \"Expected y and z to be None (in %s)\" % name\n            raise ValueError(msg)\n        return x.to(device=device_, dtype=dtype)\n\n    if allow_singleton and y is None and z is None:\n        y = x\n        z = x\n\n    # Convert all to 1D tensors\n    xyz = [_handle_coord(c, dtype, device_) for c in [x, y, z]]\n\n    # Broadcast and concatenate\n    sizes = [c.shape[0] for c in xyz]\n    N = max(sizes)\n    for c in xyz:\n        if c.shape[0] != 1 and c.shape[0] != N:\n            msg = \"Got non-broadcastable sizes %r (in %s)\" % (sizes, name)\n            raise ValueError(msg)\n    xyz = [c.expand(N) for c in xyz]\n    xyz = torch.stack(xyz, dim=1)\n    return xyz\n\n\ndef _handle_angle_input(\n    x, dtype: torch.dtype, device: Optional[Device], name: str\n) -> torch.Tensor:\n    \"\"\"\n    Helper function for building a rotation function using angles.\n    The output is always of shape (N,).\n\n    The input can be one of:\n        - Torch tensor of shape (N,)\n        - Python scalar\n        - Torch scalar\n    \"\"\"\n    device_ = get_device(x, device)\n    if torch.is_tensor(x) and x.dim() > 1:\n        msg = \"Expected tensor of shape (N,); got %r (in %s)\"\n        raise ValueError(msg % (x.shape, name))\n    else:\n        return _handle_coord(x, dtype, device_)\n\n\ndef _broadcast_bmm(a, b) -> torch.Tensor:\n    \"\"\"\n    Batch multiply two matrices and broadcast if necessary.\n\n    Args:\n        a: torch tensor of shape (P, K) or (M, P, K)\n        b: torch tensor of shape (N, K, K)\n\n    Returns:\n        a and b broadcast multiplied. The output batch dimension is max(N, M).\n\n    To broadcast transforms across a batch dimension if M != N then\n    expect that either M = 1 or N = 1. The tensor with batch dimension 1 is\n    expanded to have shape N or M.\n    \"\"\"\n    if a.dim() == 2:\n        a = a[None]\n    if len(a) != len(b):\n        if not ((len(a) == 1) or (len(b) == 1)):\n            msg = \"Expected batch dim for bmm to be equal or 1; got %r, %r\"\n            raise ValueError(msg % (a.shape, b.shape))\n        if len(a) == 1:\n            a = a.expand(len(b), -1, -1)\n        if len(b) == 1:\n            b = b.expand(len(a), -1, -1)\n    return a.bmm(b)\n\n\n@torch.no_grad()\ndef _check_valid_rotation_matrix(R, tol: float = 1e-7) -> None:\n    \"\"\"\n    Determine if R is a valid rotation matrix by checking it satisfies the\n    following conditions:\n\n    ``RR^T = I and det(R) = 1``\n\n    Args:\n        R: an (N, 3, 3) matrix\n\n    Returns:\n        None\n\n    Emits a warning if R is an invalid rotation matrix.\n    \"\"\"\n    N = R.shape[0]\n    eye = torch.eye(3, dtype=R.dtype, device=R.device)\n    eye = eye.view(1, 3, 3).expand(N, -1, -1)\n    orthogonal = torch.allclose(R.bmm(R.transpose(1, 2)), eye, atol=tol)\n    det_R = _safe_det_3x3(R)\n    no_distortion = torch.allclose(det_R, torch.ones_like(det_R))\n    if not (orthogonal and no_distortion):\n        msg = \"R is not a valid rotation matrix\"\n        warnings.warn(msg)\n    return\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/utils/comm.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport logging\nfrom functools import wraps\n\nimport torch.distributed as dist\n\nLOG = logging.getLogger(__name__)\n\n_NESTED_BROADCAST_FROM_MASTER = False\n\n\ndef get_world_size() -> int:\n    if not dist.is_available():\n        return 1\n    if not dist.is_initialized():\n        return 1\n    return dist.get_world_size()\n\ndef is_distributed():\n    return get_world_size() > 1\n\n\ndef broadcast_from_master(fn):\n    \"\"\"If distributed, only the master executes the function and broadcast the results to other workers.\n\n    Usage:\n    @broadcast_from_master\n    def foo(a, b): ...\n    \"\"\"\n    @wraps(fn)\n    def wrapper(*args, **kwargs):  # pylint: disable=unused-argument\n        global _NESTED_BROADCAST_FROM_MASTER\n\n        if not is_distributed():\n            return fn(*args, **kwargs)\n\n        if _NESTED_BROADCAST_FROM_MASTER:\n            assert d2_comm.is_main_process()\n            LOG.warning(f\"_NESTED_BROADCAST_FROM_MASTER = True, {fn.__name__}\")\n            return fn(*args, **kwargs)\n\n        if d2_comm.is_main_process():\n            _NESTED_BROADCAST_FROM_MASTER = True\n            ret = [fn(*args, **kwargs), ]\n            _NESTED_BROADCAST_FROM_MASTER = False\n        else:\n            ret = [None, ]\n        if dist.is_initialized():\n            dist.broadcast_object_list(ret)\n        ret = ret[0]\n\n        assert ret is not None\n        return ret\n\n    return wrapper\n\n\ndef master_only(fn):\n    \"\"\"If distributed, only the master executes the function.\n\n    Usage:\n    @master_only\n    def foo(a, b): ...\n    \"\"\"\n    @wraps(fn)\n    def wrapped_fn(*args, **kwargs):\n        if d2_comm.is_main_process():\n            ret = fn(*args, **kwargs)\n        d2_comm.synchronize()\n        if d2_comm.is_main_process():\n            return ret\n\n    return wrapped_fn\n\n\ndef gather_dict(dikt):\n    \"\"\"Gather python dictionaries from all workers to the rank=0 worker.\n\n    Assumption: the keys of `dikt` are disjoint across all workers.\n\n    If rank = 0, then returned aggregated dict.\n    If rank > 0, then return `None`.\n    \"\"\"\n    dict_lst = d2_comm.gather(dikt, dst=0)\n    if d2_comm.is_main_process():\n        gathered_dict = {}\n        for dic in dict_lst:\n            for k in dic.keys():\n                assert k not in gathered_dict, f\"Dictionary key overlaps: {k}\"\n            gathered_dict.update(dic)\n        return gathered_dict\n    else:\n        return None\n\n\ndef reduce_sum(tensor):\n    \"\"\"\n    Adapted from AdelaiDet:\n        https://github.com/aim-uofa/AdelaiDet/blob/master/adet/utils/comm.py\n    \"\"\"\n    if not is_distributed():\n        return tensor\n    tensor = tensor.clone()\n    dist.all_reduce(tensor, op=dist.ReduceOp.SUM)\n    return tensor\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/utils/geometry.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport logging\n\nimport cv2\nimport numpy as np\nimport torch\nimport torch.nn.functional as F\n\nLOG = logging.getLogger(__name__)\n\nPI = 3.14159265358979323846\nEPS = 1e-7\n\ndef _sqrt_positive_part(x: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Returns torch.sqrt(torch.max(0, x))\n    but with a zero subgradient where x is 0.\n    \"\"\"\n    ret = torch.zeros_like(x)\n    positive_mask = x > 0\n    ret[positive_mask] = torch.sqrt(x[positive_mask])\n    return ret\n\ndef matrix_to_quaternion(matrix: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Convert rotations given as rotation matrices to quaternions.\n\n    Args:\n        matrix: Rotation matrices as tensor of shape (..., 3, 3).\n\n    Returns:\n        quaternions with real part first, as tensor of shape (..., 4).\n    \"\"\"\n    if matrix.size(-1) != 3 or matrix.size(-2) != 3:\n        raise ValueError(f\"Invalid rotation matrix shape {matrix.shape}.\")\n\n    batch_dim = matrix.shape[:-2]\n    m00, m01, m02, m10, m11, m12, m20, m21, m22 = torch.unbind(\n        matrix.reshape(batch_dim + (9,)), dim=-1\n    )\n\n    q_abs = _sqrt_positive_part(\n        torch.stack(\n            [\n                1.0 + m00 + m11 + m22,\n                1.0 + m00 - m11 - m22,\n                1.0 - m00 + m11 - m22,\n                1.0 - m00 - m11 + m22,\n            ],\n            dim=-1,\n        )\n    )\n\n    # we produce the desired quaternion multiplied by each of r, i, j, k\n    quat_by_rijk = torch.stack(\n        [\n            torch.stack([q_abs[..., 0] ** 2, m21 - m12, m02 - m20, m10 - m01], dim=-1),\n            torch.stack([m21 - m12, q_abs[..., 1] ** 2, m10 + m01, m02 + m20], dim=-1),\n            torch.stack([m02 - m20, m10 + m01, q_abs[..., 2] ** 2, m12 + m21], dim=-1),\n            torch.stack([m10 - m01, m20 + m02, m21 + m12, q_abs[..., 3] ** 2], dim=-1),\n        ],\n        dim=-2,\n    )\n\n    # We floor here at 0.1 but the exact level is not important; if q_abs is small,\n    # the candidate won't be picked.\n    flr = torch.tensor(0.1).to(dtype=q_abs.dtype, device=q_abs.device)\n    quat_candidates = quat_by_rijk / (2.0 * q_abs[..., None].max(flr))\n\n    # if not for numerical problems, quat_candidates[i] should be same (up to a sign),\n    # forall i; we pick the best-conditioned one (with the largest denominator)\n\n    return quat_candidates[\n        F.one_hot(q_abs.argmax(dim=-1), num_classes=4) > 0.5, :  # pyre-ignore[16]\n    ].reshape(batch_dim + (4,))\n\ndef quaternion_to_matrix(quaternions: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Convert rotations given as quaternions to rotation matrices.\n\n    Args:\n        quaternions: quaternions with real part first,\n            as tensor of shape (..., 4).\n\n    Returns:\n        Rotation matrices as tensor of shape (..., 3, 3).\n    \"\"\"\n    r, i, j, k = torch.unbind(quaternions, -1)\n    two_s = 2.0 / (quaternions * quaternions).sum(-1)\n\n    o = torch.stack(\n        (\n            1 - two_s * (j * j + k * k),\n            two_s * (i * j - k * r),\n            two_s * (i * k + j * r),\n            two_s * (i * j + k * r),\n            1 - two_s * (i * i + k * k),\n            two_s * (j * k - i * r),\n            two_s * (i * k - j * r),\n            two_s * (j * k + i * r),\n            1 - two_s * (i * i + j * j),\n        ),\n        -1,\n    )\n    return o.reshape(quaternions.shape[:-1] + (3, 3))\n\ndef allocentric_to_egocentric(quat, proj_ctr, inv_intrinsics):\n    \"\"\"\n    Parameters\n    ----------\n    quat: Tensor\n        (N, 4). Batch of (allocentric) quaternions.\n\n    proj_ctr: Tensor\n        (N, 2). Projected centers. xy coordninates.\n\n    inv_intrinsics: [type]\n        (N, 3, 3). Inverted intrinsics.\n    \"\"\"\n    R_obj_to_local = quaternion_to_matrix(quat)\n\n    # ray == z-axis in local orientaion\n    ray = unproject_points2d(proj_ctr, inv_intrinsics)\n    z = ray / ray.norm(dim=1, keepdim=True)\n\n    # gram-schmit process: local_y = global_y - global_y \\dot local_z\n    y = z.new_tensor([[0., 1., 0.]]) - z[:, 1:2] * z\n    y = y / y.norm(dim=1, keepdim=True)\n    x = torch.cross(y, z, dim=1)\n\n    # local -> global\n    R_local_to_global = torch.stack([x, y, z], dim=-1)\n\n    # obj -> global\n    R_obj_to_global = torch.bmm(R_local_to_global, R_obj_to_local)\n\n    egocentric_quat = matrix_to_quaternion(R_obj_to_global)\n\n    # Make sure it's unit norm.\n    quat_norm = egocentric_quat.norm(dim=1, keepdim=True)\n    if not torch.allclose(quat_norm, torch.as_tensor(1.), atol=1e-3):\n        LOG.warning(\n            f\"Some of the input quaternions are not unit norm: min={quat_norm.min()}, max={quat_norm.max()}; therefore normalizing.\"\n        )\n        egocentric_quat = egocentric_quat / quat_norm.clamp(min=EPS)\n\n    return egocentric_quat\n\n\ndef homogenize_points(xy):\n    \"\"\"\n    Parameters\n    ----------\n    xy: Tensor\n        xy coordinates. shape=(N, ..., 2)\n        E.g., (N, 2) or (N, K, 2) or (N, H, W, 2)\n\n    Returns\n    -------\n    Tensor:\n        1. is appended to the last dimension. shape=(N, ..., 3)\n        E.g, (N, 3) or (N, K, 3) or (N, H, W, 3).\n    \"\"\"\n    # NOTE: this seems to work for arbitrary number of dimensions of input\n    pad = torch.nn.ConstantPad1d(padding=(0, 1), value=1.)\n    return pad(xy)\n\n\ndef project_points3d(Xw, K):\n    _, C = Xw.shape\n    assert C == 3\n    uv, _ = cv2.projectPoints(\n        Xw, np.zeros((3, 1), dtype=np.float32), np.zeros(3, dtype=np.float32), K, np.zeros(5, dtype=np.float32)\n    )\n    return uv.reshape(-1, 2)\n\n\ndef unproject_points2d(points2d, inv_K, scale=1.0):\n    \"\"\"\n    Parameters\n    ----------\n    points2d: Tensor\n        xy coordinates. shape=(N, ..., 2)\n        E.g., (N, 2) or (N, K, 2) or (N, H, W, 2)\n\n    inv_K: Tensor\n        Inverted intrinsics; shape=(N, 3, 3)\n\n    scale: float, default: 1.0\n        Scaling factor.\n\n    Returns\n    -------\n    Tensor:\n        Unprojected 3D point. shape=(N, ..., 3)\n        E.g., (N, 3) or (N, K, 3) or (N, H, W, 3)\n    \"\"\"\n    points2d = homogenize_points(points2d)\n    siz = points2d.size()\n    points2d = points2d.view(-1, 3).unsqueeze(-1)  # (N, 3, 1)\n    unprojected = torch.matmul(inv_K, points2d)  # (N, 3, 3) x (N, 3, 1) -> (N, 3, 1)\n    unprojected = unprojected.view(siz)\n\n    return unprojected * scale\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/utils/tasks.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nfrom collections import OrderedDict\n\n# from detectron2.config import configurable\n\n\nclass Task():\n    def __init__(self, name, is_detection_task, is_dense_prediction_task):\n        self.name = name\n        self.is_detection_task = is_detection_task\n        self.is_dense_prediction_task = is_dense_prediction_task\n\n\n# yapf: disable\nTASKS = [\n    Task(\n        name=\"box2d\",\n        is_detection_task=True,\n        is_dense_prediction_task=False,\n    ),\n    Task(\n        name=\"box3d\",\n        is_detection_task=True,\n        is_dense_prediction_task=False,\n    ),\n    Task(\n        name=\"depth\",\n        is_detection_task=False,\n        is_dense_prediction_task=True,\n    )\n]\n# yapf: enable\n\nNAME_TO_TASK = OrderedDict([(task.name, task) for task in TASKS])\n\n\nclass TaskManager():\n    #@configurable\n    def __init__(self, box2d_on=False, box3d_on=False, depth_on=False):\n        \"\"\"\n        configurable is experimental.\n        \"\"\"\n        self._box2d_on = self._mask2d_on = self._box3d_on = self._semseg2d_on = self._depth_on = False\n        tasks = []\n        if box2d_on:\n            tasks.append(NAME_TO_TASK['box2d'])\n            self._box2d_on = True\n        if box3d_on:\n            tasks.append(NAME_TO_TASK['box3d'])\n            self._box3d_on = True\n        if depth_on:\n            tasks.append(NAME_TO_TASK['depth'])\n            self._depth_on = True\n\n        if not tasks:\n            raise ValueError(\"No task specified.\")\n\n        self._tasks = tasks\n\n    @property\n    def tasks(self):\n        return self._tasks\n\n    '''@classmethod\n    def from_config(cls, cfg):\n        # yapf: disable\n        return OrderedDict(\n            box2d_on    = cfg.MODEL.BOX2D_ON,\n            box3d_on    = cfg.MODEL.BOX3D_ON,\n            depth_on    = cfg.MODEL.DEPTH_ON,\n        )\n        # yapf: enable'''\n\n    # Indicators that tells if each task is enabled.\n    @property\n    def box2d_on(self):\n        return self._box2d_on\n\n    @property\n    def box3d_on(self):\n        return self._box3d_on\n\n    @property\n    def depth_on(self):\n        return self._depth_on\n\n    @property\n    def has_dense_prediction_task(self):\n        return any([task.is_dense_prediction_task for task in self.tasks])\n\n    @property\n    def has_detection_task(self):\n        return any([task.is_detection_task for task in self.tasks])\n\n    @property\n    def task_names(self):\n        return [task.name for task in self.tasks]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/utils/tensor2d.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport torch\nimport torch.nn.functional as F\n\n\ndef compute_features_locations(h, w, stride, dtype=torch.float32, device='cpu', offset=\"none\"):\n    \"\"\"Adapted from AdelaiDet:\n        https://github.com/aim-uofa/AdelaiDet/blob/master/adet/utils/comm.py\n\n    Key differnece: offset is configurable.\n    \"\"\"\n    shifts_x = torch.arange(0, w * stride, step=stride, dtype=dtype, device=device)\n    shifts_y = torch.arange(0, h * stride, step=stride, dtype=dtype, device=device)\n    shift_y, shift_x = torch.meshgrid(shifts_y, shifts_x)\n    shift_x = shift_x.reshape(-1)\n    shift_y = shift_y.reshape(-1)\n    # (dennis.park)\n    # locations = torch.stack((shift_x, shift_y), dim=1) + stride // 2\n    locations = torch.stack((shift_x, shift_y), dim=1)\n    if offset == \"half\":\n        locations += stride // 2\n    else:\n        assert offset == \"none\"\n\n    return locations\n\n\ndef aligned_bilinear(tensor, factor, offset=\"none\"):\n    \"\"\"Adapted from AdelaiDet:\n        https://github.com/aim-uofa/AdelaiDet/blob/master/adet/utils/comm.py\n    \"\"\"\n    assert tensor.dim() == 4\n    assert factor >= 1\n    assert int(factor) == factor\n\n    if factor == 1:\n        return tensor\n\n    h, w = tensor.size()[2:]\n    tensor = F.pad(tensor, pad=(0, 1, 0, 1), mode=\"replicate\")\n    oh = factor * h + 1\n    ow = factor * w + 1\n    tensor = F.interpolate(tensor, size=(oh, ow), mode='bilinear', align_corners=True)\n    if offset == \"half\":\n        tensor = F.pad(tensor, pad=(factor // 2, 0, factor // 2, 0), mode=\"replicate\")\n\n    return tensor[:, :, :oh - 1, :ow - 1]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/dd3d/utils/visualization.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved.\n# Copyright 2021 Toyota Research Institute.  All rights reserved.\nimport colorsys\nimport os\n\nimport cv2\nimport matplotlib.colors as mplc\nimport numpy as np\nfrom PIL import Image, ImageDraw\n\n\ndef fill_color_polygon(image, polygon, color, alpha=0.5):\n    \"\"\"Color interior of polygon with alpha-blending. This function modified input in place.\n    \"\"\"\n    _mask = Image.new('L', (image.shape[1], image.shape[0]), 0)\n    ImageDraw.Draw(_mask).polygon(polygon, outline=1, fill=1)\n    mask = np.array(_mask, np.bool)\n    for c in range(3):\n        channel = image[:, :, c]\n        channel[mask] = channel[mask] * (1. - alpha) + color[c] * alpha\n\n\ndef change_color_brightness(color, brightness_factor):\n    \"\"\"\n    Copied from detectron2.utils.visualizer.py\n    -------------------------------------------\n\n    Depending on the brightness_factor, gives a lighter or darker color i.e. a color with\n    less or more saturation than the original color.\n\n    Args:\n        color: color of the polygon. Refer to `matplotlib.colors` for a full list of\n            formats that are accepted.\n        brightness_factor (float): a value in [-1.0, 1.0] range. A lightness factor of\n            0 will correspond to no change, a factor in [-1.0, 0) range will result in\n            a darker color and a factor in (0, 1.0] range will result in a lighter color.\n\n    Returns:\n        modified_color (tuple[double]): a tuple containing the RGB values of the\n            modified color. Each value in the tuple is in the [0.0, 1.0] range.\n    \"\"\"\n    assert brightness_factor >= -1.0 and brightness_factor <= 1.0\n    color = mplc.to_rgb(color)\n    polygon_color = colorsys.rgb_to_hls(*mplc.to_rgb(color))\n    modified_lightness = polygon_color[1] + (brightness_factor * polygon_color[1])\n    modified_lightness = 0.0 if modified_lightness < 0.0 else modified_lightness\n    modified_lightness = 1.0 if modified_lightness > 1.0 else modified_lightness\n    modified_color = colorsys.hls_to_rgb(polygon_color[0], modified_lightness, polygon_color[2])\n    return modified_color\n\n\ndef draw_text(ax, text, position, *, font_size, color=\"g\", horizontal_alignment=\"center\", rotation=0):\n    \"\"\"\n    Copied from Visualizer.draw_text()\n    -----------------------------------\n\n    Args:\n        text (str): class label\n        position (tuple): a tuple of the x and y coordinates to place text on image.\n        font_size (int, optional): font of the text. If not provided, a font size\n            proportional to the image width is calculated and used.\n        color: color of the text. Refer to `matplotlib.colors` for full list\n            of formats that are accepted.\n        horizontal_alignment (str): see `matplotlib.text.Text`\n        rotation: rotation angle in degrees CCW\n\n    Returns:\n        output (VisImage): image object with text drawn.\n    \"\"\"\n    # since the text background is dark, we don't want the text to be dark\n    color = np.maximum(list(mplc.to_rgb(color)), 0.2)\n    color[np.argmax(color)] = max(0.8, np.max(color))\n\n    x, y = position\n    ax.text(\n        x,\n        y,\n        text,\n        size=font_size,\n        family=\"sans-serif\",\n        bbox={\n            \"facecolor\": \"black\",\n            \"alpha\": 0.8,\n            \"pad\": 0.7,\n            \"edgecolor\": \"none\"\n        },\n        verticalalignment=\"top\",\n        horizontalalignment=horizontal_alignment,\n        color=color,\n        zorder=10,\n        rotation=rotation,\n    )\n    return ax\n\n\ndef float_to_uint8_color(float_clr):\n    assert all([c >= 0. for c in float_clr])\n    assert all([c <= 1. for c in float_clr])\n    return [int(c * 255.) for c in float_clr]\n\n\ndef mosaic(items, scale=1.0, pad=3, grid_width=None):\n    \"\"\"Creates a mosaic from list of images.\n\n    Parameters\n    ----------\n    items: list of np.ndarray\n        List of images to mosaic.\n\n    scale: float, default=1.0\n        Scale factor applied to images. scale > 1.0 enlarges images.\n\n    pad: int, default=3\n        Padding size of the images before mosaic\n\n    grid_width: int, default=None\n        Mosaic width or grid width of the mosaic\n\n    Returns\n    -------\n    image: np.array of shape (H, W, 3)\n        Image mosaic\n    \"\"\"\n    # Determine tile width and height\n    N = len(items)\n    assert N > 0, 'No items to mosaic!'\n    grid_width = grid_width if grid_width else np.ceil(np.sqrt(N)).astype(int)\n    grid_height = np.ceil(N * 1. / grid_width).astype(np.int)\n    input_size = items[0].shape[:2]\n    target_shape = (int(input_size[1] * scale), int(input_size[0] * scale))\n    mosaic_items = []\n    for j in range(grid_width * grid_height):\n        if j < N:\n            # Only the first image is scaled, the rest are re-shaped\n            # to the same size as the previous image in the mosaic\n            im = cv2.resize(items[j], dsize=target_shape)\n            mosaic_items.append(im)\n        else:\n            mosaic_items.append(np.zeros_like(mosaic_items[-1]))\n\n    # Stack W tiles horizontally first, then vertically\n    im_pad = lambda im: cv2.copyMakeBorder(im, pad, pad, pad, pad, cv2.BORDER_CONSTANT, 0)\n    mosaic_items = [im_pad(im) for im in mosaic_items]\n    hstack = [np.hstack(mosaic_items[j:j + grid_width]) for j in range(0, len(mosaic_items), grid_width)]\n    mosaic_viz = np.vstack(hstack) if len(hstack) > 1 \\\n        else hstack[0]\n    return mosaic_viz\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/models/hooks/__init__.py",
    "content": "from .hooks import GradChecker"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/mmdet3d_plugin/models/hooks/hooks.py",
    "content": "from mmcv.runner.hooks.hook import HOOKS, Hook\nfrom projects.mmdet3d_plugin.models.utils import run_time\n\n\n@HOOKS.register_module()\nclass GradChecker(Hook):\n\n    def after_train_iter(self, runner):\n        for key, val in runner.model.named_parameters():\n            if val.grad == None and val.requires_grad:\n                print('WARNNING: {key}\\'s parameters are not be used!!!!'.format(key=key))\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/model_converters/convert_votenet_checkpoints.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport tempfile\nimport torch\nfrom mmcv import Config\nfrom mmcv.runner import load_state_dict\n\nfrom mmdet3d.models import build_detector\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet3D upgrade model version(before v0.6.0) of VoteNet')\n    parser.add_argument('checkpoint', help='checkpoint file')\n    parser.add_argument('--out', help='path of the output checkpoint file')\n    args = parser.parse_args()\n    return args\n\n\ndef parse_config(config_strings):\n    \"\"\"Parse config from strings.\n\n    Args:\n        config_strings (string): strings of model config.\n\n    Returns:\n        Config: model config\n    \"\"\"\n    temp_file = tempfile.NamedTemporaryFile()\n    config_path = f'{temp_file.name}.py'\n    with open(config_path, 'w') as f:\n        f.write(config_strings)\n\n    config = Config.fromfile(config_path)\n\n    # Update backbone config\n    if 'pool_mod' in config.model.backbone:\n        config.model.backbone.pop('pool_mod')\n\n    if 'sa_cfg' not in config.model.backbone:\n        config.model.backbone['sa_cfg'] = dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=True)\n\n    if 'type' not in config.model.bbox_head.vote_aggregation_cfg:\n        config.model.bbox_head.vote_aggregation_cfg['type'] = 'PointSAModule'\n\n    # Update bbox_head config\n    if 'pred_layer_cfg' not in config.model.bbox_head:\n        config.model.bbox_head['pred_layer_cfg'] = dict(\n            in_channels=128, shared_conv_channels=(128, 128), bias=True)\n\n    if 'feat_channels' in config.model.bbox_head:\n        config.model.bbox_head.pop('feat_channels')\n\n    if 'vote_moudule_cfg' in config.model.bbox_head:\n        config.model.bbox_head['vote_module_cfg'] = config.model.bbox_head.pop(\n            'vote_moudule_cfg')\n\n    if config.model.bbox_head.vote_aggregation_cfg.use_xyz:\n        config.model.bbox_head.vote_aggregation_cfg.mlp_channels[0] -= 3\n\n    temp_file.close()\n\n    return config\n\n\ndef main():\n    \"\"\"Convert keys in checkpoints for VoteNet.\n\n    There can be some breaking changes during the development of mmdetection3d,\n    and this tool is used for upgrading checkpoints trained with old versions\n    (before v0.6.0) to the latest one.\n    \"\"\"\n    args = parse_args()\n    checkpoint = torch.load(args.checkpoint)\n    cfg = parse_config(checkpoint['meta']['config'])\n    # Build the model and load checkpoint\n    model = build_detector(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    orig_ckpt = checkpoint['state_dict']\n    converted_ckpt = orig_ckpt.copy()\n\n    if cfg['dataset_type'] == 'ScanNetDataset':\n        NUM_CLASSES = 18\n    elif cfg['dataset_type'] == 'SUNRGBDDataset':\n        NUM_CLASSES = 10\n    else:\n        raise NotImplementedError\n\n    RENAME_PREFIX = {\n        'bbox_head.conv_pred.0': 'bbox_head.conv_pred.shared_convs.layer0',\n        'bbox_head.conv_pred.1': 'bbox_head.conv_pred.shared_convs.layer1'\n    }\n\n    DEL_KEYS = [\n        'bbox_head.conv_pred.0.bn.num_batches_tracked',\n        'bbox_head.conv_pred.1.bn.num_batches_tracked'\n    ]\n\n    EXTRACT_KEYS = {\n        'bbox_head.conv_pred.conv_cls.weight':\n        ('bbox_head.conv_pred.conv_out.weight', [(0, 2), (-NUM_CLASSES, -1)]),\n        'bbox_head.conv_pred.conv_cls.bias':\n        ('bbox_head.conv_pred.conv_out.bias', [(0, 2), (-NUM_CLASSES, -1)]),\n        'bbox_head.conv_pred.conv_reg.weight':\n        ('bbox_head.conv_pred.conv_out.weight', [(2, -NUM_CLASSES)]),\n        'bbox_head.conv_pred.conv_reg.bias':\n        ('bbox_head.conv_pred.conv_out.bias', [(2, -NUM_CLASSES)])\n    }\n\n    # Delete some useless keys\n    for key in DEL_KEYS:\n        converted_ckpt.pop(key)\n\n    # Rename keys with specific prefix\n    RENAME_KEYS = dict()\n    for old_key in converted_ckpt.keys():\n        for rename_prefix in RENAME_PREFIX.keys():\n            if rename_prefix in old_key:\n                new_key = old_key.replace(rename_prefix,\n                                          RENAME_PREFIX[rename_prefix])\n                RENAME_KEYS[new_key] = old_key\n    for new_key, old_key in RENAME_KEYS.items():\n        converted_ckpt[new_key] = converted_ckpt.pop(old_key)\n\n    # Extract weights and rename the keys\n    for new_key, (old_key, indices) in EXTRACT_KEYS.items():\n        cur_layers = orig_ckpt[old_key]\n        converted_layers = []\n        for (start, end) in indices:\n            if end != -1:\n                converted_layers.append(cur_layers[start:end])\n            else:\n                converted_layers.append(cur_layers[start:])\n        converted_layers = torch.cat(converted_layers, 0)\n        converted_ckpt[new_key] = converted_layers\n        if old_key in converted_ckpt.keys():\n            converted_ckpt.pop(old_key)\n\n    # Check the converted checkpoint by loading to the model\n    load_state_dict(model, converted_ckpt, strict=True)\n    checkpoint['state_dict'] = converted_ckpt\n    torch.save(checkpoint, args.out)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/model_converters/publish_model.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport subprocess\nimport torch\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='Process a checkpoint to be published')\n    parser.add_argument('in_file', help='input checkpoint filename')\n    parser.add_argument('out_file', help='output checkpoint filename')\n    args = parser.parse_args()\n    return args\n\n\ndef process_checkpoint(in_file, out_file):\n    checkpoint = torch.load(in_file, map_location='cpu')\n    # remove optimizer for smaller file size\n    if 'optimizer' in checkpoint:\n        del checkpoint['optimizer']\n    # if it is necessary to remove some sensitive data in checkpoint['meta'],\n    # add the code here.\n    torch.save(checkpoint, out_file)\n    sha = subprocess.check_output(['sha256sum', out_file]).decode()\n    final_file = out_file.rstrip('.pth') + '-{}.pth'.format(sha[:8])\n    subprocess.Popen(['mv', out_file, final_file])\n\n\ndef main():\n    args = parse_args()\n    process_checkpoint(args.in_file, args.out_file)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/model_converters/regnet2mmdet.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport torch\nfrom collections import OrderedDict\n\n\ndef convert_stem(model_key, model_weight, state_dict, converted_names):\n    new_key = model_key.replace('stem.conv', 'conv1')\n    new_key = new_key.replace('stem.bn', 'bn1')\n    state_dict[new_key] = model_weight\n    converted_names.add(model_key)\n    print(f'Convert {model_key} to {new_key}')\n\n\ndef convert_head(model_key, model_weight, state_dict, converted_names):\n    new_key = model_key.replace('head.fc', 'fc')\n    state_dict[new_key] = model_weight\n    converted_names.add(model_key)\n    print(f'Convert {model_key} to {new_key}')\n\n\ndef convert_reslayer(model_key, model_weight, state_dict, converted_names):\n    split_keys = model_key.split('.')\n    layer, block, module = split_keys[:3]\n    block_id = int(block[1:])\n    layer_name = f'layer{int(layer[1:])}'\n    block_name = f'{block_id - 1}'\n\n    if block_id == 1 and module == 'bn':\n        new_key = f'{layer_name}.{block_name}.downsample.1.{split_keys[-1]}'\n    elif block_id == 1 and module == 'proj':\n        new_key = f'{layer_name}.{block_name}.downsample.0.{split_keys[-1]}'\n    elif module == 'f':\n        if split_keys[3] == 'a_bn':\n            module_name = 'bn1'\n        elif split_keys[3] == 'b_bn':\n            module_name = 'bn2'\n        elif split_keys[3] == 'c_bn':\n            module_name = 'bn3'\n        elif split_keys[3] == 'a':\n            module_name = 'conv1'\n        elif split_keys[3] == 'b':\n            module_name = 'conv2'\n        elif split_keys[3] == 'c':\n            module_name = 'conv3'\n        new_key = f'{layer_name}.{block_name}.{module_name}.{split_keys[-1]}'\n    else:\n        raise ValueError(f'Unsupported conversion of key {model_key}')\n    print(f'Convert {model_key} to {new_key}')\n    state_dict[new_key] = model_weight\n    converted_names.add(model_key)\n\n\ndef convert(src, dst):\n    \"\"\"Convert keys in pycls pretrained RegNet models to mmdet style.\"\"\"\n    # load caffe model\n    regnet_model = torch.load(src)\n    blobs = regnet_model['model_state']\n    # convert to pytorch style\n    state_dict = OrderedDict()\n    converted_names = set()\n    for key, weight in blobs.items():\n        if 'stem' in key:\n            convert_stem(key, weight, state_dict, converted_names)\n        elif 'head' in key:\n            convert_head(key, weight, state_dict, converted_names)\n        elif key.startswith('s'):\n            convert_reslayer(key, weight, state_dict, converted_names)\n\n    # check if all layers are converted\n    for key in blobs:\n        if key not in converted_names:\n            print(f'not converted: {key}')\n    # save checkpoint\n    checkpoint = dict()\n    checkpoint['state_dict'] = state_dict\n    torch.save(checkpoint, dst)\n\n\ndef main():\n    parser = argparse.ArgumentParser(description='Convert model keys')\n    parser.add_argument('src', help='src detectron model path')\n    parser.add_argument('dst', help='save path')\n    args = parser.parse_args()\n    convert(args.src, args.dst)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/test.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport argparse\nimport os\nimport torch\nimport warnings\nfrom mmcv.utils import get_dist_info, init_dist, wrap_fp16_model, set_random_seed, Config, DictAction, load_checkpoint\nfrom mmcv.models import build_model, fuse_conv_bn\nfrom torch.nn import DataParallel\nfrom torch.nn.parallel.distributed import DistributedDataParallel\n\nfrom mmcv.datasets import build_dataset, build_dataloader, replace_ImageToTensor\nimport time\nimport os.path as osp\nfrom adzoo.bevformer.apis.test import custom_multi_gpu_test\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet test (and eval) a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('checkpoint', help='checkpoint file')\n    parser.add_argument('--out', help='output result file in pickle format')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    parser.add_argument(\n        '--format-only',\n        action='store_true',\n        help='Format the output results without perform evaluation. It is'\n        'useful when you want to format the result to a specific format and '\n        'submit it to the test server')\n    parser.add_argument(\n        '--eval',\n        type=str,\n        nargs='+',\n        help='evaluation metrics, which depends on the dataset, e.g., \"bbox\",'\n        ' \"segm\", \"proposal\" for COCO, and \"mAP\", \"recall\" for PASCAL VOC')\n    parser.add_argument('--show', action='store_true', help='show results')\n    parser.add_argument(\n        '--show-dir', help='directory where results will be saved')\n    parser.add_argument(\n        '--gpu-collect',\n        action='store_true',\n        help='whether to use gpu to collect results.')\n    parser.add_argument(\n        '--tmpdir',\n        help='tmp directory used for collecting results from multiple '\n        'workers, available when gpu-collect is not specified')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    parser.add_argument(\n        '--options',\n        nargs='+',\n        action=DictAction,\n        help='custom options for evaluation, the key-value pair in xxx=yyy '\n        'format will be kwargs for dataset.evaluate() function (deprecate), '\n        'change to --eval-options instead.')\n    parser.add_argument(\n        '--eval-options',\n        nargs='+',\n        action=DictAction,\n        help='custom options for evaluation, the key-value pair in xxx=yyy '\n        'format will be kwargs for dataset.evaluate() function')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local-rank', type=int, default=0)\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    if args.options and args.eval_options:\n        raise ValueError(\n            '--options and --eval-options cannot be both specified, '\n            '--options is deprecated in favor of --eval-options')\n    if args.options:\n        warnings.warn('--options is deprecated in favor of --eval-options')\n        args.eval_options = args.options\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    assert args.out or args.eval or args.format_only or args.show \\\n        or args.show_dir, \\\n        ('Please specify at least one operation (save/eval/format/show the '\n         'results / save the results) with the argument \"--out\", \"--eval\"'\n         ', \"--format-only\", \"--show\" or \"--show-dir\"')\n\n    if args.eval and args.format_only:\n        raise ValueError('--eval and --format_only cannot be both specified')\n\n    if args.out is not None and not args.out.endswith(('.pkl', '.pickle')):\n        raise ValueError('The output file must be a pkl file.')\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n\n    # # import modules from plguin/xx, registry will be updated\n    # if hasattr(cfg, 'plugin'):\n    #     if cfg.plugin:\n    #         import importlib\n    #         if hasattr(cfg, 'plugin_dir'):\n    #             plugin_dir = cfg.plugin_dir\n    #             _module_dir = os.path.dirname(plugin_dir)\n    #             _module_dir = _module_dir.split('/')\n    #             _module_path = _module_dir[0]\n\n    #             for m in _module_dir[1:]:\n    #                 _module_path = _module_path + '.' + m\n    #             print(_module_path)\n    #             plg_lib = importlib.import_module(_module_path)\n    #         else:\n    #             # import dir is the dirpath for the config file\n    #             _module_dir = os.path.dirname(args.config)\n    #             _module_dir = _module_dir.split('/')\n    #             _module_path = _module_dir[0]\n    #             for m in _module_dir[1:]:\n    #                 _module_path = _module_path + '.' + m\n    #             print(_module_path)\n    #             plg_lib = importlib.import_module(_module_path)\n\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    # set tf32\n    if cfg.get('close_tf32', False):\n        torch.backends.cuda.matmul.allow_tf32 = False\n        torch.backends.cudnn.allow_tf32 = False\n\n    cfg.model.pretrained = None\n    # in case the test dataset is concatenated\n    samples_per_gpu = 1\n    if isinstance(cfg.data.test, dict):\n        cfg.data.test.test_mode = True\n        samples_per_gpu = cfg.data.test.pop('samples_per_gpu', 1)\n        if samples_per_gpu > 1:\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.test.pipeline = replace_ImageToTensor(\n                cfg.data.test.pipeline)\n    elif isinstance(cfg.data.test, list):\n        for ds_cfg in cfg.data.test:\n            ds_cfg.test_mode = True\n        samples_per_gpu = max(\n            [ds_cfg.pop('samples_per_gpu', 1) for ds_cfg in cfg.data.test])\n        if samples_per_gpu > 1:\n            for ds_cfg in cfg.data.test:\n                ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n\n    # set random seeds\n    if args.seed is not None:\n        set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # build the dataloader\n    dataset = build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=samples_per_gpu,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=distributed,\n        shuffle=False,\n        nonshuffler_sampler=cfg.data.nonshuffler_sampler,\n    )\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_model(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    checkpoint = load_checkpoint(model, args.checkpoint, map_location='cpu')\n    if args.fuse_conv_bn:\n        model = fuse_conv_bn(model)\n    # old versions did not save class info in checkpoints, this walkaround is\n    # for backward compatibility\n    if 'CLASSES' in checkpoint.get('meta', {}):\n        model.CLASSES = checkpoint['meta']['CLASSES']\n    else:\n        model.CLASSES = dataset.CLASSES\n    # palette for visualization in segmentation tasks\n    if 'PALETTE' in checkpoint.get('meta', {}):\n        model.PALETTE = checkpoint['meta']['PALETTE']\n    elif hasattr(dataset, 'PALETTE'):\n        # segmentation dataset has `PALETTE` attribute\n        model.PALETTE = dataset.PALETTE\n\n    if not distributed:\n        assert False\n        # model = MMDataParallel(model, device_ids=[0])\n        # outputs = single_gpu_test(model, data_loader, args.show, args.show_dir)\n    else:\n        model = DistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False)\n        outputs = custom_multi_gpu_test(model, data_loader, args.tmpdir,\n                                        args.gpu_collect)\n\n    rank, _ = get_dist_info()\n    if rank == 0:\n        if args.out:\n            print(f'\\nwriting results to {args.out}')\n            assert False\n            #mmcv.dump(outputs['bbox_results'], args.out)\n        kwargs = {} if args.eval_options is None else args.eval_options\n        kwargs['jsonfile_prefix'] = osp.join('test', args.config.split(\n            '/')[-1].split('.')[-2], time.ctime().replace(' ', '_').replace(':', '_'))\n        if args.format_only:\n            dataset.format_results(outputs, **kwargs)\n\n        if args.eval:\n            eval_kwargs = cfg.get('evaluation', {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                    'interval', 'tmpdir', 'start', 'gpu_collect', 'save_best',\n                    'rule'\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(dict(metric=args.eval, **kwargs))\n\n            print(dataset.evaluate(outputs, **eval_kwargs))\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/bevformer/train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n \nfrom __future__ import division\n\nimport argparse\nimport copy\nimport mmcv\nimport os\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.utils import get_dist_info, init_dist\nfrom os import path as osp\n\n\nfrom mmcv.datasets import build_dataset\nfrom mmcv.models import build_model\nfrom mmcv.utils import collect_env, get_root_logger\nfrom mmcv.utils import set_random_seed\n\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom adzoo.bevformer.mmdet3d_plugin.bevformer.apis.train import custom_train_model\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Train a detector')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument('--work-dir', help='the dir to save logs and models')\n    parser.add_argument(\n        '--resume-from', help='the checkpoint file to resume from')\n    parser.add_argument(\n        '--load-from', help='the checkpoint file to resume from')\n    parser.add_argument(\n        '--no-validate',\n        action='store_true',\n        help='whether not to evaluate the checkpoint during training')\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        '--gpus',\n        type=int,\n        help='number of gpus to use '\n        '(only applicable to non-distributed training)')\n    group_gpus.add_argument(\n        '--gpu-ids',\n        type=int,\n        nargs='+',\n        help='ids of gpus to use '\n        '(only applicable to non-distributed training)')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file (deprecate), '\n        'change to --cfg-options instead.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local-rank', type=int, default=0)\n    parser.add_argument(\n        '--autoscale-lr',\n        action='store_true',\n        help='automatically scale lr with the number of gpus')\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            '--options and --cfg-options cannot be both specified, '\n            '--options is deprecated in favor of --cfg-options')\n    if args.options:\n        warnings.warn('--options is deprecated in favor of --cfg-options')\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n\n    # set cudnn_benchmark\n    #if cfg.get('cudnn_benchmark', False):\n    torch.backends.cudnn.benchmark = True\n    # set tf32\n    # if cfg.get('close_tf32', False):\n    #     torch.backends.cuda.matmul.allow_tf32 = False\n    #     torch.backends.cudnn.allow_tf32 = False\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0])\n    # if args.resume_from is not None:\n    if args.resume_from is not None and osp.isfile(args.resume_from):\n        cfg.resume_from = args.resume_from\n    if args.load_from is not None and osp.isfile(args.load_from):\n        cfg.load_from = args.load_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n    if digit_version(TORCH_VERSION) == digit_version('1.8.1') and cfg.optimizer['type'] == 'AdamW':\n        cfg.optimizer['type'] = 'AdamW2' # fix bug in Adamw\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer['lr'] = cfg.optimizer['lr'] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    else:\n        distributed = True\n        torch.cuda.set_device(int(os.environ[\"LOCAL_RANK\"]))\n        init_dist(args.launcher, **cfg.dist_params)\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime())\n    log_file = osp.join(cfg.work_dir, f'{timestamp}.log')\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    if cfg.model.type in ['EncoderDecoder3D']:\n        logger_name = 'mmseg'\n    else:\n        logger_name = 'mmdet'\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level, name=logger_name)\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = '\\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()])\n    dash_line = '-' * 60 + '\\n'\n    logger.info('Environment info:\\n' + dash_line + env_info + '\\n' +\n                dash_line)\n    meta['env_info'] = env_info\n    meta['config'] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f'Distributed training: {distributed}')\n    logger.info(f'Config:\\n{cfg.pretty_text}')\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(f'Set random seed to {args.seed}, '\n                    f'deterministic: {args.deterministic}')\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta['seed'] = args.seed\n    meta['exp_name'] = osp.basename(args.config)\n\n    model = build_model(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    model.init_weights()\n\n    logger.info(f'Model:\\n{model}')\n    datasets = [build_dataset(cfg.data.train)]\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if 'dataset' in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n            PALETTE=datasets[0].PALETTE  # for segmentors\n            if hasattr(datasets[0], 'PALETTE') else None)\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    custom_train_model(\n        model,\n        datasets,\n        cfg,\n        distributed=distributed,\n        validate=(not args.no_validate),\n        timestamp=timestamp,\n        meta=meta)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/configs/sparsedrive_small_b2d_stage1.py",
    "content": "# ================ base config ===================\nplugin = True\nplugin_dir = \"mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(234769 // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage_sparsedrive\"),\n    dict(\n        type=\"DenseDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation_sparsedrive\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage_sparsedrive\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage_sparsedrive\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=2,\n    future_frames=6,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/configs/sparsedrive_small_b2d_stage2.py",
    "content": "# ================ base config ===================\nversion = \"mini\"\nversion = \"base\"\nlength = {'base': 234769, 'mini': 1933}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 2\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 384)\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others',\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    # 'Center',\n    # 'TrafficLight',\n    # 'StopSign',\n]\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 6\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nnum_cmd = 1\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    # depth_branch=dict(  # for auxiliary supervision only\n    #     type=\"DenseDepthNet\",\n    #     embed_dims=embed_dims,\n    #     num_depth_layers=num_depth_layers,\n    #     loss_weight=0.2,\n    # ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.9,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                # cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.9,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.25, -0.25, 0.5, -0.5),\n                    ground_height=-1.84, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(\n                type=\"SparsePoint3DDecoder\",\n                score_threshold=0.5,\n            ),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=None,\n            # plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}_b2d.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                frame_rate=1,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n                use_ego_status=False,\n                use_tp=['near',],\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_gru=False,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                num_cmd=num_cmd,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D3DDataset\"\ndata_root = \"data/bench2drive/\"\nanno_root = \"data/infos/\" if version == 'base' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    # dict(\n    #     type=\"DenseDepthMapGenerator\",\n    #     downsample=strides[:num_depth_layers],\n    # ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            # \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n            'tp_near',\n            'tp_far',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            # 'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    name_mapping=NameMapping,\n    modality=input_modality,\n    sample_interval=5,\n    past_frames=2,\n    future_frames=6,\n    use_cmd=num_cmd>1,\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'b2d_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=5,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"b2d_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\n# load_from = 'http://svcspawner.bcloud-beijing.hobot.cc/user/homespace/wenchao.sun/plat_gpu/sparsedrive_small_b2d_stage1_20e-20240903-225131.954333/output/work_dirs/latest.pth'\nload_from = \"ckpt/sparsedrive_small_b2d_stage1.pth\""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/configs/sparsedrive_small_stage1.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'mini'\nlength = {'trainval': 28130, 'mini': 323}\n\n#plugin = True\n#plugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\ntotal_batch_size = 24\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 100\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    'car',\n    'van',\n    'truck',\n    'bicycle',\n    'traffic_sign',\n    'traffic_cone',\n    'traffic_light',\n    'pedestrian',\n    'others'\n]\nmap_class_names = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    'Center',\n    'TrafficLight',\n    'StopSign'\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"B2D_VAD_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"), \n    dict(\n        type=\"MultiScaleDepthMapGenerator\", #\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-mini\",\n) # 明天直接迁移，训练，哪里报错改哪里\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=4e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.5),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/configs/sparsedrive_small_stage2.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 24\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 1\ncheckpoint_epoch_interval = 10\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=33 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"token\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=True,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\nload_from = 'ckpt/sparsedrive_stage1.pth'"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28512}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\nCUDA_VISIBLE_DEVICES=7 python -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3} --deterministic \n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/create_data.sh",
    "content": "export PYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH\n\n#python tools/data_converter/B2D_converter.py nuscenes \\\n##    --root-path ./data/nuscenes \\\n#    --canbus ./data/nuscenes \\\n#    --out-dir ./data/infos/ \\\n#    --extra-tag nuscenes \\\n#    --version v1.0\npython adzoo/sparsedrive/tools/data_converter/B2D_converter.py"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/kmeans.sh",
    "content": "python tools/kmeans/kmeans_det.py\npython tools/kmeans/kmeans_map.py\npython tools/kmeans/kmeans_motion.py\npython tools/kmeans/kmeans_plan.py"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/test.sh",
    "content": "CUDA_VISIBLE_DEVICES=0,1,2,3,4,5,6,7\\ \n   bash ./tools/dist_test.sh \\\n    projects/configs/sparsedrive_small_stage2.py \\\n    work_dirs/sparsedrive_small_stage2/iter_5860.pth \\\n    8 \\\n    --deterministic \\\n    --eval bbox\n    # --result_file ./work_dirs/sparsedrive_small_stage2/results.pkl"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/test_roboAD.sh",
    "content": "# bash ./tools/dist_test.sh \\\n#     projects/configs/sparsedrive_small_stage2.py \\\n#     ckpt/sparsedrive_stage2.pth \\\n#     8 \\\n#     --deterministic \\\n#     --ev/data/songziying/workspace/SparseDrive/scriptsal bbox\n#     # --result_file ./work_dirs/sparsedrive_small_stage2/results.pkl\nbash ./tools/dist_test.sh \\\n    projects/configs/sparsedrive_small_stage2_roboAD_6s.py \\\n    work_dirs/sparsedrive_small_stage2_roboAD_6s/iter_5860.pth\\\n    1 \\\n    --deterministic \\\n    --eval bbox\n    # --result_file ./work_dirs/sparsedrive_small_stage2_roboAD/results.pkl"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/train.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py \\\n#    1 \\\n#    --deterministic\n\n# stage2\nbash ./adzoo/sparsedrive/tools/dist_train.sh \\\n   ./adzoo/sparsedrive/configs/sparsedrive_small_stage2.py \\\n   8 \\\n   --deterministic\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/train_6s.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py \\\n#    1 \\\n#    --deterministic\n\n# stage2\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2_6s.py \\\n   8 \\\n   --deterministic\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/train_roboAD.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_stage1_roboAD.py \\\n#    1 \\\n#    --deterministic\n\n## stage2\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_stage2_roboAD.py \\\n#    8 \\\n#    --deterministic\n\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2_roboAD_6s.py \\\n   8 \\\n   --deterministic"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/scripts/visualize.sh",
    "content": "export PYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH\npython tools/visualization/visualize.py \\\n\tprojects/configs/sparsedrive_small_stage2.py \\\n\t--result-path work_dirs/sparsedrive_small_stage2/results.pkl"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/benchmark.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport time\nimport torch\nfrom mmcv import Config\nfrom mmcv.parallel import MMDataParallel\nfrom mmcv.runner import load_checkpoint, wrap_fp16_model\nimport sys\nsys.path.append('.')\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.datasets import custom_build_dataset\nfrom mmdet.models import build_detector\nfrom mmcv.cnn.utils.flops_counter import add_flops_counting_methods\nfrom mmcv.parallel import scatter\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='MMDet benchmark a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--checkpoint', default=None, help='checkpoint file')\n    parser.add_argument('--samples', default=1000, help='samples to benchmark')\n    parser.add_argument(\n        '--log-interval', default=50, help='interval of logging')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    args = parser.parse_args()\n    return args\n\n\ndef get_max_memory(model):\n    device = getattr(model, 'output_device', None)\n    mem = torch.cuda.max_memory_allocated(device=device)\n    mem_mb = torch.tensor([mem / (1024 * 1024)],\n        dtype=torch.int,\n        device=device)\n    return mem_mb.item()\n\n\ndef main():\n    args = parse_args()\n    get_flops_params(args)\n    get_mem_fps(args)\n\ndef get_mem_fps(args):\n    cfg = Config.fromfile(args.config)\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n\n    # build the dataloader\n    # TODO: support multiple images per gpu (only minor changes are needed)\n    print(cfg.data.test)\n    dataset = custom_build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=False,\n        shuffle=False)\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    # if args.fuse_conv_bn:\n    #     model = fuse_module(model)\n\n    model = MMDataParallel(model, device_ids=[0])\n\n    model.eval()\n\n    # the first several iterations may be very slow so skip them\n    num_warmup = 5\n    pure_inf_time = 0\n\n    # benchmark with several samples and take the average\n    max_memory = 0\n    for i, data in enumerate(data_loader):\n        # torch.cuda.synchronize()\n        with torch.no_grad():\n            start_time = time.perf_counter()\n            model(return_loss=False, rescale=True, **data)\n\n            torch.cuda.synchronize()\n            elapsed = time.perf_counter() - start_time\n            max_memory = max(max_memory, get_max_memory(model))\n\n        if i >= num_warmup:\n            pure_inf_time += elapsed\n            if (i + 1) % args.log_interval == 0:\n                fps = (i + 1 - num_warmup) / pure_inf_time\n                print(f'Done image [{i + 1:<3}/ {args.samples}], '\n                      f'fps: {fps:.1f} img / s, '\n                      f\"gpu mem: {max_memory} M\")\n\n        if (i + 1) == args.samples:\n            pure_inf_time += elapsed\n            fps = (i + 1 - num_warmup) / pure_inf_time\n            print(f'Overall fps: {fps:.1f} img / s')\n            break\n\n\ndef get_flops_params(args):\n    gpu_id = 0\n    cfg = Config.fromfile(args.config)\n    dataset = custom_build_dataset(cfg.data.val)\n    dataloader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=0,\n        dist=False,\n        shuffle=False,\n    )\n    data_iter = dataloader.__iter__()\n    data = next(data_iter)\n    data = scatter(data, [gpu_id])[0]\n\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    model = model.cuda(gpu_id)\n    model.eval()\n\n    bilinear_flops = 11\n    num_key_pts_det = (\n        cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"kps_generator\"][\"num_learnable_pts\"]\n        + len(cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"kps_generator\"][\"fix_scale\"])\n    )\n    deformable_agg_flops_det = (\n        cfg.num_decoder\n        * cfg.embed_dims\n        * cfg.num_levels\n        * cfg.model[\"head\"]['det_head'][\"instance_bank\"][\"num_anchor\"]\n        * cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"num_cams\"]\n        * num_key_pts_det\n        * bilinear_flops\n    )\n    num_key_pts_map = (\n        cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"num_learnable_pts\"]\n        + len(cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"fix_height\"])\n    ) * cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"num_sample\"]\n    deformable_agg_flops_map = (\n        cfg.num_decoder\n        * cfg.embed_dims\n        * cfg.num_levels\n        * cfg.model[\"head\"]['map_head'][\"instance_bank\"][\"num_anchor\"]\n        * cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"num_cams\"]\n        * num_key_pts_map\n        * bilinear_flops\n    )\n    deformable_agg_flops = deformable_agg_flops_det + deformable_agg_flops_map\n\n    for module in [\"total\", \"img_backbone\", \"img_neck\", \"head\"]:\n        if module != \"total\":\n            flops_model = add_flops_counting_methods(getattr(model, module))\n        else:\n            flops_model = add_flops_counting_methods(model)\n        flops_model.eval()\n        flops_model.start_flops_count()\n        \n        if module == \"img_backbone\":\n            flops_model(data[\"img\"].flatten(0, 1))\n        elif module == \"img_neck\":\n            flops_model(model.img_backbone(data[\"img\"].flatten(0, 1)))\n        elif module == \"head\":\n            flops_model(model.extract_feat(data[\"img\"], metas=data), data)\n        else:\n            flops_model(**data)\n        flops_count, params_count = flops_model.compute_average_flops_cost()\n        flops_count *= flops_model.__batch_counter__\n        flops_model.stop_flops_count()\n        if module == \"head\" or module == \"total\":\n            flops_count += deformable_agg_flops\n        if module == \"total\":\n            total_flops = flops_count\n            total_params = params_count\n        print(\n            f\"{module:<13} complexity: \"\n            f\"FLOPs={flops_count/ 10.**9:>8.4f} G / {flops_count/total_flops*100:>6.2f}%, \"\n            f\"Params={params_count/10**6:>8.4f} M / {params_count/total_params*100:>6.2f}%.\"\n        )\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/data_converter/B2D_converter.py",
    "content": "import os\nfrom os.path import join\nimport gzip, json, pickle\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom tqdm import tqdm\nimport copy\n# from vis_utils import calculate_cube_vertices,calculate_occlusion_stats,edges,DIS_CAR_SAVE\nimport cv2\nimport multiprocessing\nimport argparse\nfrom shapely.geometry import LineString\n# All data in the Bench2Drive dataset are in the left-handed coordinate system.\n# This code converts all coordinate systems (world coordinate system, vehicle coordinate system,\n# camera coordinate system, and lidar coordinate system) to the right-handed coordinate system\n# consistent with the nuscenes dataset.\n\nDATAROOT = 'data/bench2drive'\nMAP_ROOT = 'data/bench2drive/maps'\nOUT_DIR = 'data/infos_sparsedrive'\n# split_file = 'data/bench2drive/bench2drive_mini_train_val_split.json'\nsplit_file = 'data/splits/bench2drive_base_train_val_split.json'\n\nMAP_CLASSES = [\n    'Broken',\n    'Solid',\n    'SolidSolid',\n    'Center',\n    'TrafficLight',\n    'StopSign',\n]\npoint_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\n\nMAX_DISTANCE = 75              # Filter bounding boxes that are too far from the vehicle\nFILTER_Z_SHRESHOLD = 10        # Filter bounding boxes that are too high/low from the vehicle\nFILTER_INVISINLE = True        # Filter bounding boxes based on visibility\nNUM_VISIBLE_SHRESHOLD = 1      # Filter bounding boxes with fewer visible vertices than this value\nNUM_OUTPOINT_SHRESHOLD = 7     # Filter bounding boxes where the number of vertices outside the frame is greater than this value in all cameras\nCAMERAS = ['CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_FRONT_LEFT', 'CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']\nCAMERA_TO_FOLDER_MAP = {'CAM_FRONT':'rgb_front', 'CAM_FRONT_LEFT':'rgb_front_left', 'CAM_FRONT_RIGHT':'rgb_front_right', 'CAM_BACK':'rgb_back', 'CAM_BACK_LEFT':'rgb_back_left', 'CAM_BACK_RIGHT':'rgb_back_right'}\n\nstand_to_ue4_rotate = np.array([[ 0, 0, 1, 0],\n                                [ 1, 0, 0, 0],\n                                [ 0,-1, 0, 0],\n                                [ 0, 0, 0, 1]])\n\nlidar_to_righthand_ego = np.array([[  0, 1, 0, 0],\n                                   [ -1, 0, 0, 0],\n                                   [  0, 0, 1, 0],\n                                   [  0, 0, 0, 1]])\n\nlefthand_ego_to_lidar = np.array([[ 0, 1, 0, 0],\n                                  [ 1, 0, 0, 0],\n                                  [ 0, 0, 1, 0],\n                                  [ 0, 0, 0, 1]])\n\nleft2right = np.eye(4)\nleft2right[1,1] = -1\n\nWINDOW_HEIGHT = 900\nWINDOW_WIDTH = 1600\n\ndef point_in_canvas_hw(pos):\n    \"\"\"Return true if point is in canvas\"\"\"\n    if (pos[0] >= 0) and (pos[0] < WINDOW_HEIGHT) and (pos[1] >= 0) and (pos[1] < WINDOW_WIDTH):\n        return True\n    return False\n\ndef calculate_cube_vertices(center, extent):\n    cx, cy, cz = center\n    x, y, z = extent\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\ndef calculate_occlusion_stats(bbox_points, depth, depth_map, max_render_depth):\n    \"\"\" Draws each vertex in vertices_pos2d if it is in front of the camera\n        The color is based on whether the object is occluded or not.\n        Returns the number of visible vertices and the number of vertices outside the camera.\n    \"\"\"\n    num_visible_vertices = 0\n    num_invisible_vertices = 0\n    num_vertices_outside_camera = 0\n    points = []\n\n    for i in range(len(bbox_points)):\n        x_2d = bbox_points[i][0]\n        y_2d = bbox_points[i][1]\n        point_depth = depth[i]\n\n        # if the point is in front of the camera but not too far away\n        if max_render_depth > point_depth > 0 and point_in_canvas_hw((y_2d, x_2d)):\n            #is_occluded_v = point_is_occluded_vectorized([[y_2d, x_2d]], point_depth, depth_map)\n            is_occluded = point_is_occluded(\n                (y_2d, x_2d), point_depth, depth_map)\n                \n            if is_occluded:\n                vertex_color = (0,0,255) # bgr, red\n                num_invisible_vertices += 1\n            else:\n                num_visible_vertices += 1\n                vertex_color = (0,255,0) # bgr, green\n            points.append((x_2d, y_2d, vertex_color))\n        else:\n            num_vertices_outside_camera += 1\n    return num_visible_vertices, num_invisible_vertices, num_vertices_outside_camera, points\n\ndef point_is_occluded(point, vertex_depth, depth_map):\n    \"\"\" Checks whether or not the four pixels directly around the given point has less depth than the given vertex depth\n        If True, this means that the point is occluded.\n    \"\"\"\n    y, x = map(int, point)\n    from itertools import product\n    neigbours = product((1, -1), repeat=2)\n    is_occluded = []\n    for dy, dx in neigbours:\n        if point_in_canvas_hw((dy+y, dx+x)):\n            # If the depth map says the pixel is closer to the camera than the actual vertex\n            if depth_map[y+dy, x+dx] < vertex_depth:\n                is_occluded.append(True)\n            else:\n                is_occluded.append(False)\n    # Only say point is occluded if all four neighbours are closer to camera than vertex\n    return all(is_occluded)\n\ndef apply_trans(vec,world2ego):\n    vec = np.concatenate((vec,np.array([1])))\n    t = world2ego @ vec\n    return t[0:3]\n\ndef get_pose_matrix(dic):\n    new_matrix = np.zeros((4,4))\n    new_matrix[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=dic['theta']-np.pi/2).rotation_matrix\n    new_matrix[0,3] = dic['x']\n    new_matrix[1,3] = dic['y']\n    new_matrix[3,3] = 1\n    return new_matrix\n\ndef get_npc2world(npc):\n    for key in ['world2vehicle','world2ego','world2sign','world2ped']:\n        if key in npc.keys():\n            npc2world = np.linalg.inv(np.array(npc[key]))\n            yaw_from_matrix = np.arctan2(npc2world[1,0], npc2world[0,0])\n            yaw = npc['rotation'][-1] / 180 * np.pi\n            if abs(yaw-yaw_from_matrix)> 0.01:\n                npc2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=yaw).rotation_matrix\n            npc2world = left2right @ npc2world @ left2right\n            return npc2world\n    npc2world = np.eye(4)\n    npc2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=npc['rotation'][-1]/180*np.pi).rotation_matrix\n    npc2world[0:3,3] = np.array(npc['location'])\n    return left2right @ npc2world @ left2right\n\n\ndef get_global_trigger_vertex(center,extent,yaw_in_degree):\n    x,y = center[0],-center[1]\n    dx,dy = extent[0],extent[1]\n    yaw_in_radians = -yaw_in_degree/180*np.pi\n    vertex_in_self = np.array([[ dx, dy],\n                               [-dx, dy],\n                               [-dx,-dy],\n                               [ dx,-dy]])\n    rotate_matrix = np.array([[np.cos(yaw_in_radians),-np.sin(yaw_in_radians)],\n                              [np.sin(yaw_in_radians), np.cos(yaw_in_radians)]])\n    rotated_vertex = (rotate_matrix @ vertex_in_self.T).T\n    vertex_in_global = np.array([[x,y]]).repeat(4,axis=0) + rotated_vertex\n    return vertex_in_global\n\n\n\ndef get_image_point(loc, K, w2c):\n    point = np.array([loc[0], loc[1], loc[2], 1])\n    point_camera = np.dot(w2c, point)\n    point_camera = point_camera[0:3]\n    depth = point_camera[2]\n    point_img = np.dot(K, point_camera)\n    point_img[0] /= point_img[2]\n    point_img[1] /= point_img[2]\n    return point_img[0:2], depth\n\ndef get_action(index):\n\tDiscrete_Actions_DICT = {\n\t\t0:  (0, 0, 1, False),\n\t\t1:  (0.7, -0.5, 0, False),\n\t\t2:  (0.7, -0.3, 0, False),\n\t\t3:  (0.7, -0.2, 0, False),\n\t\t4:  (0.7, -0.1, 0, False),\n\t\t5:  (0.7, 0, 0, False),\n\t\t6:  (0.7, 0.1, 0, False),\n\t\t7:  (0.7, 0.2, 0, False),\n\t\t8:  (0.7, 0.3, 0, False),\n\t\t9:  (0.7, 0.5, 0, False),\n\t\t10: (0.3, -0.7, 0, False),\n\t\t11: (0.3, -0.5, 0, False),\n\t\t12: (0.3, -0.3, 0, False),\n\t\t13: (0.3, -0.2, 0, False),\n\t\t14: (0.3, -0.1, 0, False),\n\t\t15: (0.3, 0, 0, False),\n\t\t16: (0.3, 0.1, 0, False),\n\t\t17: (0.3, 0.2, 0, False),\n\t\t18: (0.3, 0.3, 0, False),\n\t\t19: (0.3, 0.5, 0, False),\n\t\t20: (0.3, 0.7, 0, False),\n\t\t21: (0, -1, 0, False),\n\t\t22: (0, -0.6, 0, False),\n\t\t23: (0, -0.3, 0, False),\n\t\t24: (0, -0.1, 0, False),\n\t\t25: (1, 0, 0, False),\n\t\t26: (0, 0.1, 0, False),\n\t\t27: (0, 0.3, 0, False),\n\t\t28: (0, 0.6, 0, False),\n\t\t29: (0, 1.0, 0, False),\n\t\t30: (0.5, -0.5, 0, True),\n\t\t31: (0.5, -0.3, 0, True),\n\t\t32: (0.5, -0.2, 0, True),\n\t\t33: (0.5, -0.1, 0, True),\n\t\t34: (0.5, 0, 0, True),\n\t\t35: (0.5, 0.1, 0, True),\n\t\t36: (0.5, 0.2, 0, True),\n\t\t37: (0.5, 0.3, 0, True),\n\t\t38: (0.5, 0.5, 0, True),\n\t\t}\n\tthrottle, steer, brake, reverse = Discrete_Actions_DICT[index]\n\treturn throttle, steer, brake\n\n\ndef gengrate_map(map_root):\n    map_infos = {}\n    for file_name in os.listdir(map_root):\n        if '.npz' in file_name:\n            map_info = dict(np.load(join(map_root,file_name), allow_pickle=True)['arr'])\n            town_name = file_name.split('_')[0]\n            map_infos[town_name] = {} \n            lane_points = []\n            lane_types = []\n            lane_sample_points = []\n            trigger_volumes_points = []\n            trigger_volumes_types = []\n            trigger_volumes_sample_points = []\n            for road_id, road in map_info.items():\n                for lane_id, lane in road.items():\n                    if lane_id == 'Trigger_Volumes':\n                        for single_trigger_volume in lane:\n                            points = np.array(single_trigger_volume['Points'])\n                            points[:,1] *= -1 #left2right\n                            trigger_volumes_points.append(points)\n                            trigger_volumes_sample_points.append(points.mean(axis=0))\n                            trigger_volumes_types.append(single_trigger_volume['Type'])\n                    else:\n                        for single_lane in lane:\n                            points = np.array([raw_point[0] for raw_point in single_lane['Points']])\n                            points[:,1] *= -1\n                            lane_points.append(points)\n                            lane_types.append(single_lane['Type'])\n                            lane_lenth = points.shape[0]\n                            if lane_lenth % 50 != 0:\n                                devide_points = [50*i for i in range(lane_lenth//50+1)]\n                            else:\n                                devide_points = [50*i for i in range(lane_lenth//50)]\n                            devide_points.append(lane_lenth-1)\n                            lane_sample_points_tmp = points[devide_points]\n                            lane_sample_points.append(lane_sample_points_tmp)\n            map_infos[town_name]['lane_points'] = lane_points\n            map_infos[town_name]['lane_sample_points'] = lane_sample_points\n            map_infos[town_name]['lane_types'] = lane_types\n            map_infos[town_name]['trigger_volumes_points'] = trigger_volumes_points\n            map_infos[town_name]['trigger_volumes_sample_points'] = trigger_volumes_sample_points\n            map_infos[town_name]['trigger_volumes_types'] = trigger_volumes_types\n    with open(join(OUT_DIR,'b2d_map_infos.pkl'),'wb') as f:\n        pickle.dump(map_infos,f)\n    return map_infos\n\ndef preprocess(folder_list,idx,tmp_dir,train_or_val,map_infos):\n\n    data_root = DATAROOT\n    cameras = CAMERAS\n    final_data = []\n    if idx == 0:\n        folders = tqdm(folder_list)\n    else:\n        folders = folder_list\n\n    for folder_name in folders:\n        print(folder_name)\n        folder_path = join(data_root, folder_name)\n        last_position_dict = {}\n        for ann_name in sorted(os.listdir(join(folder_path,'anno')),key= lambda x: int(x.split('.')[0])):\n            if idx == 0:\n                print(ann_name)\n            position_dict = {}\n            frame_data = {}\n            cam_gray_depth = {}\n            with gzip.open(join(folder_path,'anno',ann_name), 'rt', encoding='utf-8') as gz_file:\n                anno = json.load(gz_file) \n            frame_data['folder'] = folder_name\n            frame_data['town_name'] =  folder_name.split('/')[1].split('_')[1]\n            frame_data['command_far_xy'] = np.array([anno['x_command_far'],-anno['y_command_far']])\n            frame_data['command_far'] = anno['command_far']\n            frame_data['command_near_xy'] = np.array([anno['x_command_near'],-anno['y_command_near']])\n            frame_data['command_near'] = anno['command_near']\n            frame_data['frame_idx'] = int(ann_name.split('.')[0])\n            frame_data['timestamp'] = int(ann_name.split('.')[0]) / 10 * 1e6 # consistent with nusc\n            frame_data['token'] = folder_name + '_' + str(int(ann_name.split('.')[0])).zfill(4)\n            frame_data['ego_yaw'] = -np.nan_to_num(anno['theta'],nan=np.pi)+np.pi/2  \n            frame_data['ego_translation'] = np.array([anno['x'],-anno['y'],0])\n            frame_data['ego_vel'] = np.array([anno['speed'],0,0])\n            frame_data['ego_accel'] = np.array([anno['acceleration'][0],-anno['acceleration'][1],anno['acceleration'][2]])\n            frame_data['ego_rotation_rate'] = -np.array(anno['angular_velocity'])\n            frame_data['ego_size'] = np.array([anno['bounding_boxes'][0]['extent'][1],anno['bounding_boxes'][0]['extent'][0],anno['bounding_boxes'][0]['extent'][2]])*2\n            world2ego = left2right @ anno['bounding_boxes'][0]['world2ego'] @ left2right\n            frame_data['world2ego'] = world2ego\n            if frame_data['frame_idx'] == 0:\n                expert_file_path = join(folder_path,'expert_assessment','-0001.npz')\n            else:\n                expert_file_path = join(folder_path,'expert_assessment',str(frame_data['frame_idx']-1).zfill(5)+'.npz')\n            expert_data = np.load(expert_file_path,allow_pickle=True)['arr_0']\n            action_id = expert_data[-1]\n            # value = expert_data[-2]\n            # expert_feature = expert_data[:-2]\n            throttle, steer, brake = get_action(action_id)\n            frame_data['brake'] = brake\n            frame_data['throttle'] = throttle\n            frame_data['steer'] = steer\n            #frame_data['action_id'] = action_id\n            #frame_data['value'] = value\n            #frame_data['expert_feature'] = expert_feature\n            ###get sensor infos###\n            sensor_infos = {}\n            for cam in CAMERAS:\n                sensor_infos[cam] = {}\n                sensor_infos[cam]['cam2ego'] = left2right @ np.array(anno['sensors'][cam]['cam2ego']) @ stand_to_ue4_rotate \n                sensor_infos[cam]['intrinsic'] = np.array(anno['sensors'][cam]['intrinsic'])\n                sensor_infos[cam]['world2cam'] = np.linalg.inv(stand_to_ue4_rotate) @ np.array(anno['sensors'][cam]['world2cam']) @left2right\n                sensor_infos[cam]['data_path'] = join(folder_name,'camera',CAMERA_TO_FOLDER_MAP[cam],ann_name.split('.')[0]+'.jpg')\n                cam_gray_depth[cam] = cv2.imread(join(data_root,sensor_infos[cam]['data_path']).replace('rgb_','depth_').replace('.jpg','.png'))[:,:,0]\n            sensor_infos['LIDAR_TOP'] = {}\n            sensor_infos['LIDAR_TOP']['lidar2ego'] = left2right @ np.array(anno['sensors']['LIDAR_TOP']['lidar2ego']) @ left2right @ lidar_to_righthand_ego\n            world2lidar = lefthand_ego_to_lidar @ np.array(anno['sensors']['LIDAR_TOP']['world2lidar']) @ left2right\n            sensor_infos['LIDAR_TOP']['world2lidar'] = world2lidar\n            frame_data['sensors'] = sensor_infos\n            map_annos = get_map_anno(frame_data, map_infos)\n            frame_data[\"map_annos\"] = map_annos\n            ###get bounding_boxes infos###\n            gt_boxes = []\n            gt_names = []\n            gt_ids = []\n            num_points_list = []\n            npc2world_list = []\n            for npc in anno['bounding_boxes']:\n                if npc['class'] == 'ego_vehicle': continue\n                if npc['distance'] > MAX_DISTANCE: continue\n                if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > FILTER_Z_SHRESHOLD: continue\n                center = np.array([npc['center'][0],-npc['center'][1],npc['center'][2]]) # left hand -> right hand\n                # extent = np.array([npc['extent'][1],npc['extent'][0],npc['extent'][2]])  # lwh -> wlh\n                extent = np.array([npc['extent'][0],npc['extent'][1],npc['extent'][2]])  # lwh\n                position_dict[npc['id']] = center\n                local_center = apply_trans(center, world2lidar)\n                size = extent * 2 \n                if 'world2vehicle' in npc.keys():\n                    world2vehicle = left2right @ np.array(npc['world2vehicle'])@left2right\n                    vehicle2lidar = world2lidar @ np.linalg.inv(world2vehicle) \n                    yaw_local = np.arctan2(vehicle2lidar[1,0], vehicle2lidar[0,0])\n\n                else:\n                    yaw_local = -npc['rotation'][-1]/180*np.pi - frame_data['ego_yaw'] +np.pi / 2  \n                # yaw_local_in_lidar_box = -yaw_local - np.pi / 2  \n                yaw_local_in_lidar_box = yaw_local  \n                while yaw_local < -np.pi:\n                    yaw_local += 2*np.pi\n                while yaw_local > np.pi:\n                    yaw_local -= 2*np.pi  \n                if 'speed' in npc.keys():\n                    if 'vehicle' in npc['class']:  # only vehicles have correct speed\n                        speed = npc['speed']\n                    else:\n                        if npc['id'] in last_position_dict.keys():  #calculate speed for other object\n                            speed = np.linalg.norm((center-last_position_dict[npc['id']])[0:2]) * 10\n                        else:\n                            speed = 0\n                else:\n                    speed = 0\n                if 'num_points' in npc.keys():\n                    num_points = npc['num_points']\n                else:\n                    num_points = -1\n                npc2world = get_npc2world(npc)\n                speed_x = speed * np.cos(yaw_local)\n                speed_y = speed * np.sin(yaw_local)\n\n                ###fliter_bounding_boxes###\n                if FILTER_INVISINLE:\n                    valid = False\n                    box2lidar = np.eye(4)\n                    box2lidar[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=yaw_local).rotation_matrix\n                    box2lidar[0:3,3] = local_center\n                    lidar2box = np.linalg.inv(box2lidar)\n                    raw_verts = calculate_cube_vertices(local_center,extent)\n                    verts = []\n                    for raw_vert in raw_verts:\n                        tmp = np.dot(lidar2box, [raw_vert[0], raw_vert[1], raw_vert[2],1])\n                        tmp[0:3] += local_center\n                        verts.append(tmp.tolist()[:-1])\n                    for cam in cameras:\n                        lidar2cam = np.linalg.inv(frame_data['sensors'][cam]['cam2ego']) @ sensor_infos['LIDAR_TOP']['lidar2ego']\n                        test_points = [] \n                        test_depth = []\n                        for vert in verts:\n                            point, depth = get_image_point(vert, frame_data['sensors'][cam]['intrinsic'], lidar2cam)\n                            if depth > 0:\n                                test_points.append(point)\n                                test_depth.append(depth)\n\n                        num_visible_vertices, num_invisible_vertices, num_vertices_outside_camera, colored_points = calculate_occlusion_stats(np.array(test_points), np.array(test_depth),  cam_gray_depth[cam], max_render_depth=MAX_DISTANCE)\n                        if num_visible_vertices>NUM_VISIBLE_SHRESHOLD and num_vertices_outside_camera<NUM_OUTPOINT_SHRESHOLD:\n                            valid = True\n                            break\n                else:\n                    valid = True\n                if valid:\n                    npc2world_list.append(npc2world)\n                    num_points_list.append(num_points)            \n                    gt_boxes.append(np.concatenate([local_center,size,np.array([yaw_local_in_lidar_box,speed_x,speed_y])]))\n                    gt_names.append(npc['type_id'])\n                    gt_ids.append(int(npc['id']))\n\n            if len(gt_boxes) == 0:\n                continue\n\n            last_position_dict = position_dict.copy()    \n            gt_ids = np.array(gt_ids)\n            gt_names = np.array(gt_names)\n            num_points_list = np.array(num_points_list)\n            gt_boxes = np.stack(gt_boxes)\n            npc2world = np.stack(npc2world_list)\n            frame_data['gt_ids'] = gt_ids\n            frame_data['gt_boxes'] = gt_boxes\n            frame_data['gt_names'] = gt_names\n            frame_data['num_points'] = num_points_list\n            frame_data['npc2world'] = npc2world\n            final_data.append(frame_data)\n    \n    os.makedirs(join(OUT_DIR,tmp_dir),exist_ok=True)\n    with open(join(OUT_DIR,tmp_dir,'b2d_infos_'+train_or_val+'_'+str(idx)+'.pkl'),'wb') as f:\n        pickle.dump(final_data,f)\n\n\ndef get_map_anno(ann_info, map_infos):\n    town_name = ann_info['town_name']\n    map_info = map_infos[town_name]\n    lane_points = map_info['lane_points']\n    lane_sample_points = map_info['lane_sample_points']\n    lane_types = map_info['lane_types']\n    trigger_volumes_points = map_info['trigger_volumes_points']\n    trigger_volumes_sample_points = map_info['trigger_volumes_sample_points']\n    trigger_volumes_types = map_info['trigger_volumes_types']\n    world2lidar = np.array(ann_info['sensors']['LIDAR_TOP']['world2lidar'])\n    ego_xy = np.linalg.inv(world2lidar)[0:2,3]\n    max_distance = 50\n    chosed_idx = []\n\n    for idx in range(len(lane_sample_points)):\n        single_sample_points = lane_sample_points[idx]\n        distance = np.linalg.norm((single_sample_points[:,0:2]-ego_xy),axis=-1)\n        if np.min(distance) < max_distance:\n            chosed_idx.append(idx)\n\n    map_anno = {}\n    for i in range(len(MAP_CLASSES)):\n        map_anno[i] = []\n\n    for idx in chosed_idx:\n        if not lane_types[idx] in MAP_CLASSES:\n            continue\n        points = lane_points[idx]\n        points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n        points_in_lidar = (world2lidar @ points.T).T\n        mask = (points_in_lidar[:,0]>point_cloud_range[0]) & (points_in_lidar[:,0]<point_cloud_range[3]) & (points_in_lidar[:,1]>point_cloud_range[1]) & (points_in_lidar[:,1]<point_cloud_range[4])\n        points_in_lidar_range = points_in_lidar[mask,0:2]\n        if len(points_in_lidar_range) > 1:\n            label = MAP_CLASSES.index(lane_types[idx])\n            line = LineString(points_in_lidar_range).simplify(0.2, preserve_topology=True)\n            line = np.array(line.coords)\n            map_anno[label].append(line)\n\n    for idx in range(len(trigger_volumes_points)):\n        if not trigger_volumes_types[idx] in MAP_CLASSES:\n            continue\n        points = trigger_volumes_points[idx]\n        points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n        points_in_lidar = (world2lidar @ points.T).T\n        mask = (points_in_lidar[:,0]>point_cloud_range[0]) & (points_in_lidar[:,0]<point_cloud_range[3]) & (points_in_lidar[:,1]>point_cloud_range[1]) & (points_in_lidar[:,1]<point_cloud_range[4])\n        points_in_lidar_range = points_in_lidar[mask,0:2]\n        if mask.all():\n            label = MAP_CLASSES.index(trigger_volumes_types[idx])\n            line = LineString(points_in_lidar_range).simplify(0.2, preserve_topology=True)\n            line = np.array(line.coords)\n            map_anno[label].append(line)\n\n    return map_anno\n\ndef generate_infos(folder_list,workers,train_or_val,tmp_dir, map_infos):\n\n    folder_num = len(folder_list)\n    devide_list = [(folder_num//workers)*i for i in range(workers)]\n    devide_list.append(folder_num)\n    for i in range(workers):\n        sub_folder_list = folder_list[devide_list[i]:devide_list[i+1]]\n        process = multiprocessing.Process(target=preprocess, args=(sub_folder_list,i,tmp_dir,train_or_val, map_infos))\n        process.start()\n        process_list.append(process)\n    for i in range(workers):\n        process_list[i].join()\n    union_data = []\n    for i in range(workers):\n        with open(join(OUT_DIR,tmp_dir,'b2d_infos_'+train_or_val+'_'+str(i)+'.pkl'),'rb') as f:\n            data = pickle.load(f)\n        union_data.extend(data)\n    with open(join(OUT_DIR,'b2d_infos_'+train_or_val+'.pkl'),'wb') as f:\n        pickle.dump(union_data,f)\n        print(\"write!\")\n    print(train_or_val, len(union_data))\n\nif __name__ == \"__main__\":\n\n    os.makedirs(OUT_DIR,exist_ok=True)\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--tmp_dir', default=\"tmp_data\", )\n    args = argparser.parse_args()    \n    process_list = []\n    with open(split_file,'r') as f:\n        train_val_split = json.load(f)\n        \n    all_folder = os.listdir(join(DATAROOT,'v1'))\n    train_list = []\n    for foldername in all_folder:\n        if 'Town' in foldername and 'Route' in foldername and 'Weather' in foldername and not join('v1',foldername) in train_val_split['val']:\n            train_list.append(join('v1',foldername))   \n    print('processing map data...')\n    # map_infos = gengrate_map(MAP_ROOT)\n    with open(join(OUT_DIR,'b2d_map_infos.pkl'),'rb') as f:\n        map_infos = pickle.load(f)\n\n    #preprocess(train_list[1:2], 0, args.tmp_dir, \"train\", map_infos)\n    # print('processing train data...')\n    generate_infos(train_list, 16,'train',args.tmp_dir, map_infos)\n    # print('processing val data...')\n    # generate_infos(train_val_split['val'], 16,'val',args.tmp_dir, map_infos)\n\n    print('finish!')"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/data_converter/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/data_converter/nuscenes_converter.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_test.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/data_converter/nuscenes_converter_1_10.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n       \n        import random\n        random.shuffle(train_scenes)\n        train_scenes = train_scenes[:int(len(train_scenes)*0.1)] # 0.2 为 1/5；0.5为 1/2 以此类推\n    \n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n    # import pdb; pdb.set_trace()\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        pass\n        # print('test sample: {}'.format(len(train_nusc_infos)))\n        # data = dict(infos=train_nusc_infos, metadata=metadata)\n        # info_path = osp.join(out_path,\n        #                      '{}_infos_test.pkl'.format(info_prefix))\n        # mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_1_10_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        # data['infos'] = val_nusc_infos\n        # info_val_path = osp.join(out_path,\n        #                          '{}_infos_val.pkl'.format(info_prefix))\n        # mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n    # import pdb; pdb.set_trace()\n    predict_helper = PredictHelper(nusc)\n    trainval_samples=[]\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        if sample['scene_token'] in train_scenes:\n            trainval_samples.append(sample)\n    # import pdb; pdb.set_trace()\n    for sample in mmcv.track_iter_progress(trainval_samples):\n        \n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/data_converter/nuscenes_converter_6s.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_test_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_train_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=12):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/data_converter/nuscenes_converter_hrad_planing_scene.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\n\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        import random\n        random.shuffle(train_scenes)\n        train_scenes = train_scenes[:int(len(train_scenes)*0.1)] # 0.2 为 1/5；0.5为 1/2 以此类推\n        # import pdb; pdb.set_trace()\n        val_scenes = splits.val\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    \n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    # import pdb; pdb.set_trace()\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n    val_scenes = set(['a178a1b5415f45c08d179bd2cacdf284', 'e005041f659c47e194cd5b18ea6fc346', 'e8099a6136804f3bb9b38ff94d98eb64', 'b789de07180846cc972118ee6d1fb027', '080a52cb8f59489b9cddc7b721808088', 'ed242d80ccb34b139aaf9ab89859332e', '325cef682f064c55a255f2625c533b75', '2f56eb47c64f43df8902d9f88aa8a019', '7210f928860043b5a7e0d3dd4b3e80ff', 'f97bf749746c4c3a8ad9f1c11eab6444', 'cba3ddd5c3664a43b6a08e586e094900', 'd29527ec841045d18d04a933e7a0afd2', 'c4df079d260241ff8015218e29b42ea7', '7052d21b95fc4bae8761b8d9524f3e42', '01e4fcbe6e49483293ce45727152b36e', '19d97841d6f64eba9f6eb9b6e8c257dc', 'fcc020250f884397965ba00c1d9ad9e6'])\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        pass\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val_hrad_planing_scene.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    trainval_samples=[]\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        if sample['scene_token'] in val_scenes :\n            trainval_samples.append(sample)\n    # import pdb; pdb.set_trace()\n    for sample in mmcv.track_iter_progress(trainval_samples):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/dist_test.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nPORT=${PORT:-29611}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython3 -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/test.py $CONFIG $CHECKPOINT --launcher pytorch ${@:4}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28651}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython3 -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/fuse_conv_bn.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\n\nimport torch\nfrom mmcv.runner import save_checkpoint\nfrom torch import nn as nn\n\nfrom mmdet3d.apis import init_model\n\n\ndef fuse_conv_bn(conv, bn):\n    \"\"\"During inference, the functionary of batch norm layers is turned off but\n    only the mean and var alone channels are used, which exposes the chance to\n    fuse it with the preceding conv layers to save computations and simplify\n    network structures.\"\"\"\n    conv_w = conv.weight\n    conv_b = conv.bias if conv.bias is not None else torch.zeros_like(\n        bn.running_mean)\n\n    factor = bn.weight / torch.sqrt(bn.running_var + bn.eps)\n    conv.weight = nn.Parameter(conv_w *\n                               factor.reshape([conv.out_channels, 1, 1, 1]))\n    conv.bias = nn.Parameter((conv_b - bn.running_mean) * factor + bn.bias)\n    return conv\n\n\ndef fuse_module(m):\n    last_conv = None\n    last_conv_name = None\n\n    for name, child in m.named_children():\n        if isinstance(child, (nn.BatchNorm2d, nn.SyncBatchNorm)):\n            if last_conv is None:  # only fuse BN that is after Conv\n                continue\n            fused_conv = fuse_conv_bn(last_conv, child)\n            m._modules[last_conv_name] = fused_conv\n            # To reduce changes, set BN as Identity instead of deleting it.\n            m._modules[name] = nn.Identity()\n            last_conv = None\n        elif isinstance(child, nn.Conv2d):\n            last_conv = child\n            last_conv_name = name\n        else:\n            fuse_module(child)\n    return m\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='fuse Conv and BN layers in a model')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument('checkpoint', help='checkpoint file path')\n    parser.add_argument('out', help='output path of the converted model')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n    # build the model from a config file and a checkpoint file\n    model = init_model(args.config, args.checkpoint)\n    # fuse conv and bn layers of the model\n    fused_model = fuse_module(model)\n    save_checkpoint(fused_model, args.out)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/kmeans/kmeans_det.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nos.makedirs('data/kmeans', exist_ok=True)\nos.makedirs('vis/kmeans', exist_ok=True)\n\nK = 900\nDIS_THRESH = 55\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\ncenter = []\nfor idx in tqdm(range(len(data_infos))):\n    boxes = data_infos[idx]['gt_boxes'][:,:3]\n    if len(boxes) == 0:\n        continue\n    distance = np.linalg.norm(boxes[:, :2], axis=1)\n    center.append(boxes[distance < DIS_THRESH])\ncenter = np.concatenate(center, axis=0)\nprint(\"start clustering, may take a few minutes.\")\ncluster = KMeans(n_clusters=K).fit(center).cluster_centers_\nplt.scatter(cluster[:,0], cluster[:,1])\nplt.savefig(f'vis/kmeans/det_anchor_{K}', bbox_inches='tight')\nothers = np.array([1,1,1,1,0,0,0,0])[np.newaxis].repeat(K, axis=0)\ncluster = np.concatenate([cluster, others], axis=1)\nnp.save(f'data/kmeans/kmeans_det_{K}.npy', cluster)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/kmeans/kmeans_map.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nK = 100\nnum_sample = 20\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\ncenter = []\nfor idx in tqdm(range(len(data_infos))):\n    for cls, geoms in data_infos[idx][\"map_annos\"].items():\n        for geom in geoms:  \n            center.append(geom.mean(axis=0))\ncenter = np.stack(center, axis=0)\ncenter = KMeans(n_clusters=K).fit(center).cluster_centers_\ndelta_y = np.linspace(-4, 4, num_sample)\ndelta_x = np.zeros([num_sample])\ndelta = np.stack([delta_x, delta_y], axis=-1)\nvecs = center[:, np.newaxis] + delta[np.newaxis]\n\nfor i in range(K):\n    x = vecs[i, :, 0]\n    y = vecs[i, :, 1]\n    plt.plot(x, y, linewidth=1, marker='o', linestyle='-', markersize=2)\nplt.savefig(f'vis/kmeans/map_anchor_{K}', bbox_inches='tight')\nnp.save(f'data/kmeans/kmeans_map_{K}.npy', vecs)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/kmeans/kmeans_motion.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nCLASSES = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\n\ndef lidar2agent(trajs_offset, boxes):\n    origin = np.zeros((trajs_offset.shape[0], 1, 2), dtype=np.float32)\n    trajs_offset = np.concatenate([origin, trajs_offset], axis=1)\n    trajs = trajs_offset.cumsum(axis=1)\n    yaws = - boxes[:, 6]\n    rot_sin = np.sin(yaws)\n    rot_cos = np.cos(yaws)\n    rot_mat_T = np.stack(\n        [\n            np.stack([rot_cos, rot_sin]),\n            np.stack([-rot_sin, rot_cos]),\n        ]\n    )\n    trajs_new = np.einsum('aij,jka->aik', trajs, rot_mat_T)\n    trajs_new = trajs_new[:, 1:]\n    return trajs_new\n\nK = 6\nDIS_THRESH = 55\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\nintention = dict()\nfor i in range(len(CLASSES)):\n    intention[i] = []\nfor idx in tqdm(range(len(data_infos))):\n    info = data_infos[idx]\n    boxes = info['gt_boxes']\n    names = info['gt_names']\n    fut_masks = info['gt_agent_fut_masks']\n    trajs = info['gt_agent_fut_trajs']\n    velos = info['gt_velocity']\n    labels = []\n    for cat in names:\n        if cat in CLASSES:\n            labels.append(CLASSES.index(cat))\n        else:\n            labels.append(-1)\n    labels = np.array(labels)\n    if len(boxes) == 0:\n        continue    \n    for i in range(len(CLASSES)):\n        cls_mask = (labels == i)\n        box_cls = boxes[cls_mask]\n        fut_masks_cls = fut_masks[cls_mask]\n        trajs_cls = trajs[cls_mask]\n        velos_cls = velos[cls_mask]\n\n        distance = np.linalg.norm(box_cls[:, :2], axis=1)\n        mask = np.logical_and(\n            fut_masks_cls.sum(axis=1) == 12,\n            distance < DIS_THRESH,\n        )\n        trajs_cls = trajs_cls[mask]\n        box_cls = box_cls[mask]\n        velos_cls = velos_cls[mask]\n\n        trajs_agent = lidar2agent(trajs_cls, box_cls)\n        if trajs_agent.shape[0] == 0:\n            continue\n        intention[i].append(trajs_agent)\n\nclusters = []\nfor i in range(len(CLASSES)):\n    intention_cls = np.concatenate(intention[i], axis=0).reshape(-1, 24)\n    if intention_cls.shape[0] < K:\n        continue\n    cluster = KMeans(n_clusters=K).fit(intention_cls).cluster_centers_\n    cluster = cluster.reshape(-1, 12, 2)\n    clusters.append(cluster)\n    for j in range(K):\n        plt.scatter(cluster[j, :, 0], cluster[j, :,1])\n    plt.savefig(f'vis/kmeans/motion_intention_{CLASSES[i]}_{K}', bbox_inches='tight')\n    plt.close()\n\nclusters = np.stack(clusters, axis=0)\nnp.save(f'data/kmeans/kmeans_motion_{K}.npy', clusters)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/kmeans/kmeans_plan.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nK = 6\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\nnavi_trajs = [[], [], []]\nfor idx in tqdm(range(len(data_infos))):\n    info = data_infos[idx]\n    plan_traj = info['gt_ego_fut_trajs'].cumsum(axis=-2)\n    plan_mask = info['gt_ego_fut_masks']\n    cmd = info['gt_ego_fut_cmd'].astype(np.int32)\n    cmd = cmd.argmax(axis=-1)\n    if not plan_mask.sum() == 6:\n        continue\n    navi_trajs[cmd].append(plan_traj)\n\nclusters = []\nfor trajs in navi_trajs:\n    trajs = np.concatenate(trajs, axis=0).reshape(-1, 12)\n    cluster = KMeans(n_clusters=K).fit(trajs).cluster_centers_\n    cluster = cluster.reshape(-1, 6, 2)\n    clusters.append(cluster)\n    for j in range(K):\n        plt.scatter(cluster[j, :, 0], cluster[j, :,1])\nplt.savefig(f'vis/kmeans/plan_{K}', bbox_inches='tight')\nplt.close()\n\nclusters = np.stack(clusters, axis=0)\nnp.save(f'data/kmeans/kmeans_plan_{K}.npy', clusters)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/test.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport mmcv\nimport os\nfrom os import path as osp\n\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.cnn import fuse_conv_bn\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.runner import (\n    get_dist_info,\n    init_dist,\n    load_checkpoint,\n    wrap_fp16_model,\n)\n\nfrom mmdet.apis import single_gpu_test, multi_gpu_test, set_random_seed\nfrom mmdet.datasets import replace_ImageToTensor, build_dataset\nfrom mmdet.datasets import build_dataloader as build_dataloader_origin\nfrom mmdet.models import build_detector\n\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.apis.test import custom_multi_gpu_test\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description=\"MMDet test (and eval) a model\"\n    )\n    parser.add_argument(\"config\", help=\"test config file path\")\n    parser.add_argument(\"checkpoint\", help=\"checkpoint file\")\n    parser.add_argument(\"--out\", help=\"output result file in pickle format\")\n    parser.add_argument(\n        \"--fuse-conv-bn\",\n        action=\"store_true\",\n        help=\"Whether to fuse conv and bn, this will slightly increase\"\n        \"the inference speed\",\n    )\n    parser.add_argument(\n        \"--format-only\",\n        action=\"store_true\",\n        help=\"Format the output results without perform evaluation. It is\"\n        \"useful when you want to format the result to a specific format and \"\n        \"submit it to the test server\",\n    )\n    parser.add_argument(\n        \"--eval\",\n        type=str,\n        nargs=\"+\",\n        help='evaluation metrics, which depends on the dataset, e.g., \"bbox\",'\n        ' \"segm\", \"proposal\" for COCO, and \"mAP\", \"recall\" for PASCAL VOC',\n    )\n    parser.add_argument(\"--show\", action=\"store_true\", help=\"show results\")\n    parser.add_argument(\n        \"--show-dir\", help=\"directory where results will be saved\"\n    )\n    parser.add_argument(\n        \"--gpu-collect\",\n        action=\"store_true\",\n        help=\"whether to use gpu to collect results.\",\n    )\n    parser.add_argument(\n        \"--tmpdir\",\n        help=\"tmp directory used for collecting results from multiple \"\n        \"workers, available when gpu-collect is not specified\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"custom options for evaluation, the key-value pair in xxx=yyy \"\n        \"format will be kwargs for dataset.evaluate() function (deprecate), \"\n        \"change to --eval-options instead.\",\n    )\n    parser.add_argument(\n        \"--eval-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"custom options for evaluation, the key-value pair in xxx=yyy \"\n        \"format will be kwargs for dataset.evaluate() function\",\n    )\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\"--result_file\", type=str, default=None)\n    parser.add_argument(\"--show_only\", action=\"store_true\")\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.eval_options:\n        raise ValueError(\n            \"--options and --eval-options cannot be both specified, \"\n            \"--options is deprecated in favor of --eval-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --eval-options\")\n        args.eval_options = args.options\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    assert (\n        args.out or args.eval or args.format_only or args.show or args.show_dir\n    ), (\n        \"Please specify at least one operation (save/eval/format/show the \"\n        'results / save the results) with the argument \"--out\", \"--eval\"'\n        ', \"--format-only\", \"--show\" or \"--show-dir\"'\n    )\n\n    if args.eval and args.format_only:\n        raise ValueError(\"--eval and --format_only cannot be both specified\")\n\n    if args.out is not None and not args.out.endswith((\".pkl\", \".pickle\")):\n        raise ValueError(\"The output file must be a pkl file.\")\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    cfg.model.pretrained = None\n    # in case the test dataset is concatenated\n    samples_per_gpu = 1\n    if isinstance(cfg.data.test, dict):\n        cfg.data.test.test_mode = True\n        samples_per_gpu = cfg.data.test.pop(\"samples_per_gpu\", 1)\n        if samples_per_gpu > 1:\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.test.pipeline = replace_ImageToTensor(\n                cfg.data.test.pipeline\n            )\n    elif isinstance(cfg.data.test, list):\n        for ds_cfg in cfg.data.test:\n            ds_cfg.test_mode = True\n        samples_per_gpu = max(\n            [ds_cfg.pop(\"samples_per_gpu\", 1) for ds_cfg in cfg.data.test]\n        )\n        if samples_per_gpu > 1:\n            for ds_cfg in cfg.data.test:\n                ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n\n    # set random seeds\n    if args.seed is not None:\n        set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # set work dir\n    if cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0]) \n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    cfg.data.test.work_dir = cfg.work_dir\n    print('work_dir: ',cfg.work_dir)\n\n\n    # build the dataloader\n    dataset = build_dataset(cfg.data.test)\n    import pdb;\n    if distributed:\n        data_loader = build_dataloader(\n            dataset,\n            samples_per_gpu=samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n        )\n    else:\n        data_loader = build_dataloader_origin(\n            dataset,\n            samples_per_gpu=samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n        )\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get(\"test_cfg\"))\n    # model = build_model(cfg.model, test_cfg=cfg.get(\"test_cfg\"))\n    fp16_cfg = cfg.get(\"fp16\", None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    checkpoint = load_checkpoint(model, args.checkpoint, map_location=\"cpu\")\n    if args.fuse_conv_bn:\n        model = fuse_conv_bn(model)\n    # old versions did not save class info in checkpoints, this walkaround is\n    # for backward compatibility\n    if \"CLASSES\" in checkpoint.get(\"meta\", {}):\n        model.CLASSES = checkpoint[\"meta\"][\"CLASSES\"]\n    else:\n        model.CLASSES = dataset.CLASSES\n    # palette for visualization in segmentation tasks\n    if \"PALETTE\" in checkpoint.get(\"meta\", {}):\n        model.PALETTE = checkpoint[\"meta\"][\"PALETTE\"]\n    elif hasattr(dataset, \"PALETTE\"):\n        # segmentation dataset has `PALETTE` attribute\n        model.PALETTE = dataset.PALETTE\n\n    if args.result_file is not None:\n        # outputs = torch.load(args.result_file)\n        outputs = mmcv.load(args.result_file)\n    elif not distributed:\n        model = MMDataParallel(model, device_ids=[0])\n        outputs = single_gpu_test(model, data_loader, args.show, args.show_dir)\n    else:\n        model = MMDistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n        )\n        outputs = custom_multi_gpu_test(\n            model, data_loader, args.tmpdir, args.gpu_collect\n        )\n\n    rank, _ = get_dist_info()\n    if rank == 0:\n        if args.out:\n            print(f\"\\nwriting results to {args.out}\")\n            mmcv.dump(outputs, args.out)\n        kwargs = {} if args.eval_options is None else args.eval_options\n        if args.show_only:\n            eval_kwargs = cfg.get(\"evaluation\", {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                \"interval\",\n                \"tmpdir\",\n                \"start\",\n                \"gpu_collect\",\n                \"save_best\",\n                \"rule\",\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(kwargs)\n            dataset.show(outputs, show=True, **eval_kwargs)\n        elif args.format_only:\n            dataset.format_results(outputs, **kwargs)\n        elif args.eval:\n            eval_kwargs = cfg.get(\"evaluation\", {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                \"interval\",\n                \"tmpdir\",\n                \"start\",\n                \"gpu_collect\",\n                \"save_best\",\n                \"rule\",\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(dict(metric=args.eval, **kwargs))\n            print(eval_kwargs)\n            results_dict = dataset.evaluate(outputs, **eval_kwargs)\n            print(results_dict)\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/train.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from projects.mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    # print(\"hhhhhhhhhhhhhhh\")\n    print(cfg.data.train)\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/train_single.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\n# for single gpu debug\nBASE_DIR = os.path.dirname(os.path.abspath(__file__))\nROOT_DIR = os.path.dirname(BASE_DIR)\nsys.path.append(ROOT_DIR)\n###############\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from projects.mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/visualization/bev_render.py",
    "content": "import os\nimport numpy as np\nimport cv2\n\nimport matplotlib\nimport matplotlib.pyplot as plt\n\n#from .projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\n\ndef box3d_to_corners(box3d):\n    if isinstance(box3d, torch.Tensor):\n        box3d = box3d.detach().cpu().numpy()\n    corners_norm = np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)\n    corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n    # use relative origin [0.5, 0.5, 0]\n    corners_norm = corners_norm - np.array([0.5, 0.5, 0.5])\n    corners = box3d[:, None, [W, L, H]] * corners_norm.reshape([1, 8, 3])\n\n    # rotate around z axis\n    rot_cos = np.cos(box3d[:, YAW])\n    rot_sin = np.sin(box3d[:, YAW])\n    rot_mat = np.tile(np.eye(3)[None], (box3d.shape[0], 1, 1))\n    rot_mat[:, 0, 0] = rot_cos\n    rot_mat[:, 0, 1] = -rot_sin\n    rot_mat[:, 1, 0] = rot_sin\n    rot_mat[:, 1, 1] = rot_cos\n    corners = (rot_mat[:, None] @ corners[..., None]).squeeze(axis=-1)\n    corners += box3d[:, None, :3]\n    return corners\n \nCMD_LIST = ['Turn Right', 'Turn Left', 'Go Straight']\nCOLOR_VECTORS = ['cornflowerblue', 'royalblue', 'slategrey']\nSCORE_THRESH = 0.3\nMAP_SCORE_THRESH = 0.3\ncolor_mapping = np.asarray([\n    [0, 0, 0],\n    [255, 179, 0],\n    [128, 62, 117],\n    [255, 104, 0],\n    [166, 189, 215],\n    [193, 0, 32],\n    [206, 162, 98],\n    [129, 112, 102],\n    [0, 125, 52],\n    [246, 118, 142],\n    [0, 83, 138],\n    [255, 122, 92],\n    [83, 55, 122],\n    [255, 142, 0],\n    [179, 40, 81],\n    [244, 200, 0],\n    [127, 24, 13],\n    [147, 170, 0],\n    [89, 51, 21],\n    [241, 58, 19],\n    [35, 44, 22],\n    [112, 224, 255],\n    [70, 184, 160],\n    [153, 0, 255],\n    [71, 255, 0],\n    [255, 0, 163],\n    [255, 204, 0],\n    [0, 255, 235],\n    [255, 0, 235],\n    [255, 0, 122],\n    [255, 245, 0],\n    [10, 190, 212],\n    [214, 255, 0],\n    [0, 204, 255],\n    [20, 0, 255],\n    [255, 255, 0],\n    [0, 153, 255],\n    [0, 255, 204],\n    [41, 255, 0],\n    [173, 0, 255],\n    [0, 245, 255],\n    [71, 0, 255],\n    [0, 255, 184],\n    [0, 92, 255],\n    [184, 255, 0],\n    [255, 214, 0],\n    [25, 194, 194],\n    [92, 0, 255],\n    [220, 220, 220],\n    [255, 9, 92],\n    [112, 9, 255],\n    [8, 255, 214],\n    [255, 184, 6],\n    [10, 255, 71],\n    [255, 41, 10],\n    [7, 255, 255],\n    [224, 255, 8],\n    [102, 8, 255],\n    [255, 61, 6],\n    [255, 194, 7],\n    [0, 255, 20],\n    [255, 8, 41],\n    [255, 5, 153],\n    [6, 51, 255],\n    [235, 12, 255],\n    [160, 150, 20],\n    [0, 163, 255],\n    [140, 140, 140],\n    [250, 10, 15],\n    [20, 255, 0],\n]) / 255\n\n\nclass BEVRender:\n    def __init__(\n        self, \n        plot_choices,\n        out_dir,\n        xlim = 40,\n        ylim = 40,\n    ):\n        self.plot_choices = plot_choices\n        self.xlim = xlim\n        self.ylim = ylim\n        self.gt_dir = os.path.join(out_dir, \"bev_gt\")\n        self.pred_dir = os.path.join(out_dir, \"bev_pred\")\n        os.makedirs(self.gt_dir, exist_ok=True)\n        os.makedirs(self.pred_dir, exist_ok=True)\n\n    def reset_canvas(self):\n        plt.close()\n        self.fig, self.axes = plt.subplots(1, 1, figsize=(20, 20))\n        self.axes.set_xlim(- self.xlim, self.xlim)\n        self.axes.set_ylim(- self.ylim, self.ylim)\n        self.axes.axis('off')\n\n    def render(\n        self,\n        data, \n        result,\n        index,\n    ):\n        self.reset_canvas()\n        self.draw_detection_gt(data)\n        self.draw_motion_gt(data)\n        self.draw_map_gt(data)\n        self.draw_planning_gt(data)\n        self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_gt = os.path.join(self.gt_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_gt)\n\n        self.reset_canvas()\n        self.draw_detection_pred(result)\n        self.draw_track_pred(result)\n        self.draw_motion_pred(result)\n        self.draw_map_pred(result)\n        self.draw_planning_pred(data, result)\n        self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_pred = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_pred)\n\n        return save_path_gt, save_path_pred\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        plt.savefig(filename)\n\n    def draw_detection_gt(self, data):\n        if not self.plot_choices['det']:\n            return\n\n        for i in range(data['gt_labels_3d'].shape[0]):\n            label = data['gt_labels_3d'][i]\n            if label == -1: \n                continue\n            color = color_mapping[i % len(color_mapping)]\n\n            # draw corners\n            corners = box3d_to_corners(data['gt_bboxes_3d'])[i, [0, 3, 7, 4, 0]]\n            x = corners[:, 0]\n            y = corners[:, 1]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n            # draw line to indicate forward direction\n            forward_center = np.mean(corners[2:4], axis=0)\n            center = np.mean(corners[0:4], axis=0)\n            x = [forward_center[0], center[0]]\n            y = [forward_center[1], center[1]]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n    def draw_detection_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['det'] and \"boxes_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n\n            # draw corners\n            corners = box3d_to_corners(bboxes)[i, [0, 3, 7, 4, 0]]\n            x = corners[:, 0]\n            y = corners[:, 1]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n            # draw line to indicate forward direction\n            forward_center = np.mean(corners[2:4], axis=0)\n            center = np.mean(corners[0:4], axis=0)\n            x = [forward_center[0], center[0]]\n            y = [forward_center[1], center[1]]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n    def draw_track_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['track'] and \"anchor_queue\" in result):\n            return\n        \n        temp_bboxes = result[\"anchor_queue\"]\n        period = result[\"period\"]\n        bboxes = result['boxes_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n            center = bboxes[i, :3]\n            centers = [center]\n            for j in range(period[i]):\n                # draw corners\n                corners = box3d_to_corners(temp_bboxes[:, -1-j])[i, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color=color, linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color=color, linewidth=2, linestyle='-')\n                centers.append(center)\n\n            centers = np.stack(centers)\n            xs = centers[:, 0]\n            ys = centers[:, 1]\n            self.axes.plot(xs, ys, color=color, linewidth=2, linestyle='-')\n\n    def draw_motion_gt(self, data):\n        if not self.plot_choices['motion']:\n            return\n\n        for i in range(data['gt_labels_3d'].shape[0]):\n            label = data['gt_labels_3d'][i]\n            if label == -1: \n                continue\n            color = color_mapping[i % len(color_mapping)]\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n\n            center = data['gt_bboxes_3d'][i, :2]\n            masks = data['gt_agent_fut_masks'][i].astype(bool)\n            if masks[0] == 0:\n                continue\n            trajs = data['gt_agent_fut_trajs'][i][masks]\n            trajs = trajs.cumsum(axis=0) + center\n            trajs = np.concatenate([center.reshape(1, 2), trajs], axis=0)\n            \n            self._render_traj(trajs, traj_score=1.0,\n                            colormap='winter', dot_size=dot_size)\n\n    def draw_motion_pred(self, result, top_k=3):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['motion'] and \"trajs_3d\" in result):\n            return\n        \n        bboxes = result['boxes_3d']\n        labels = result['labels_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            label = labels[i]\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n\n            traj_score = result['trajs_score'][i].numpy()\n            traj = result['trajs_3d'][i].numpy()\n            num_modes = len(traj_score)\n            center = bboxes[i, :2][None, None].repeat(num_modes, 1, 1).numpy()\n            traj = np.concatenate([center, traj], axis=1)\n\n            sorted_ind = np.argsort(traj_score)[::-1]\n            sorted_traj = traj[sorted_ind, :, :2]\n            sorted_score = traj_score[sorted_ind]\n            norm_score = np.exp(sorted_score[0])\n\n            for j in range(top_k - 1, -1, -1):\n                viz_traj = sorted_traj[j]\n                traj_score = np.exp(sorted_score[j])/norm_score\n                self._render_traj(viz_traj, traj_score=traj_score,\n                                colormap='winter', dot_size=dot_size)\n    \n    def draw_map_gt(self, data):\n        if not self.plot_choices['map']:\n            return\n        vectors = data['map_infos']\n        for label, vector_list in vectors.items():\n            color = COLOR_VECTORS[label]\n            for vector in vector_list:\n                pts = vector[:, :2]\n                x = np.array([pt[0] for pt in pts])\n                y = np.array([pt[1] for pt in pts])\n                self.axes.plot(x, y, color=color, linewidth=3, marker='o', linestyle='-', markersize=7)\n\n    def draw_map_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['map'] and \"vectors\" in result):\n            return\n\n        for i in range(result['scores'].shape[0]):\n            score = result['scores'][i]\n            if  score < MAP_SCORE_THRESH:\n                continue\n            color = COLOR_VECTORS[result['labels'][i]]\n            pts = result['vectors'][i]\n            x = pts[:, 0]\n            y = pts[:, 1]\n            plt.plot(x, y, color=color, linewidth=3, marker='o', linestyle='-', markersize=7)\n\n    def draw_planning_gt(self, data):\n        if not self.plot_choices['planning']:\n            return\n\n        # draw planning gt\n        masks = data['gt_ego_fut_masks'].astype(bool)\n        if masks[0] != 0:\n            plan_traj = data['gt_ego_fut_trajs'][masks]\n            cmd = data['gt_ego_fut_cmd']\n            plan_traj[abs(plan_traj) < 0.01] = 0.0\n            plan_traj = plan_traj.cumsum(axis=0)\n            plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n            self._render_traj(plan_traj, traj_score=1.0,\n                colormap='autumn', dot_size=50)\n\n    def draw_planning_pred(self, data, result, top_k=3):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n\n        if self.plot_choices['track'] and \"ego_anchor_queue\" in result:\n            ego_temp_bboxes = result[\"ego_anchor_queue\"]\n            ego_period = result[\"ego_period\"]\n            for j in range(ego_period[0]):\n                # draw corners\n                corners = box3d_to_corners(ego_temp_bboxes[:, -1-j])[0, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n        # import ipdb; ipdb.set_trace()\n        plan_trajs = result['planning'].cpu().numpy()\n        num_cmd = len(CMD_LIST)\n        num_mode = plan_trajs.shape[1]\n        plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        plan_score = result['planning_score'].cpu().numpy()\n\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        plan_trajs = plan_trajs[cmd]\n        plan_score = plan_score[cmd]\n\n        sorted_ind = np.argsort(plan_score)[::-1]\n        sorted_traj = plan_trajs[sorted_ind, :, :2]\n        sorted_score = plan_score[sorted_ind]\n        norm_score = np.exp(sorted_score[0])\n\n        for j in range(top_k - 1, -1, -1):\n            viz_traj = sorted_traj[j]\n            traj_score = np.exp(sorted_score[j]) / norm_score\n            self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='autumn', dot_size=50)\n\n    def _render_traj(\n        self, \n        future_traj, \n        traj_score=1, \n        colormap='winter', \n        points_per_step=20, \n        dot_size=25\n    ):\n        total_steps = (len(future_traj) - 1) * points_per_step + 1\n        dot_colors = matplotlib.colormaps[colormap](\n            np.linspace(0, 1, total_steps))[:, :3]\n        dot_colors = dot_colors * traj_score + \\\n            (1 - traj_score) * np.ones_like(dot_colors)\n        total_xy = np.zeros((total_steps, 2))\n        for i in range(total_steps - 1):\n            unit_vec = future_traj[i // points_per_step +\n                                   1] - future_traj[i // points_per_step]\n            total_xy[i] = (i / points_per_step - i // points_per_step) * \\\n                unit_vec + future_traj[i // points_per_step]\n        total_xy[-1] = future_traj[-1]\n        self.axes.scatter(\n            total_xy[:, 0], total_xy[:, 1], c=dot_colors, s=dot_size)\n\n    def _render_sdc_car(self):\n        sdc_car_png = cv2.imread('resources/sdc_car.png')\n        sdc_car_png = cv2.cvtColor(sdc_car_png, cv2.COLOR_BGR2RGB)\n        im = self.axes.imshow(sdc_car_png, extent=(-1, 1, -2, 2))\n        im.set_zorder(2)\n\n    def _render_legend(self):\n        legend = cv2.imread('resources/legend.png')\n        legend = cv2.cvtColor(legend, cv2.COLOR_BGR2RGB)\n        self.axes.imshow(legend, extent=(15, 40, -40, -30))\n\n    def _render_command(self, data):\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        self.axes.text(-38, -38, CMD_LIST[cmd], fontsize=60)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/tools/visualization/cam_render.py",
    "content": "import os\nimport numpy as np\nimport cv2\nfrom PIL import Image\n\nimport matplotlib\nimport matplotlib.pyplot as plt\nfrom pyquaternion import Quaternion\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\n\nfrom tools.visualization.bev_render import (\n    color_mapping, \n    SCORE_THRESH, \n    MAP_SCORE_THRESH,\n    CMD_LIST\n)\n\n\nCAM_NAMES_NUSC = [\n    'CAM_FRONT_LEFT',\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_BACK_RIGHT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n]\nCAM_NAMES_NUSC_converter = [\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_FRONT_LEFT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n    'CAM_BACK_RIGHT',\n]\n\nclass CamRender:\n    def __init__(\n        self, \n        plot_choices,\n        out_dir,\n    ):\n        self.plot_choices = plot_choices\n        self.pred_dir = os.path.join(out_dir, \"cam_pred\")\n        os.makedirs(self.pred_dir, exist_ok=True)\n\n    def reset_canvas(self):\n        plt.close()\n        plt.gca().set_axis_off()\n        plt.axis('off')\n        self.fig, self.axes = plt.subplots(2, 3, figsize=(160 /3 , 20))\n        plt.tight_layout()\n\n    def render(\n        self,\n        data, \n        result,\n        index,\n    ):\n        self.reset_canvas()\n        self.render_image_data(data, index)\n        self.draw_detection_pred(data, result)\n        self.draw_motion_pred(data, result)\n        self.draw_planning_pred(data, result)\n        save_path = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path)\n        return save_path\n\n    def load_image(self, data_path, cam):\n        \"\"\"Update the axis of the plot with the provided image.\"\"\"\n        image = np.array(Image.open(data_path))\n        font = cv2.FONT_HERSHEY_SIMPLEX\n        org = (50, 60)\n        fontScale = 2\n        color = (0, 0, 0)\n        thickness = 4\n        return cv2.putText(image, cam, org, font, fontScale, color, thickness, cv2.LINE_AA)\n\n    def update_image(self, image, index, cam):\n        \"\"\"Render image data for each camera.\"\"\"\n        ax = self.get_axis(index)\n        ax.imshow(image)\n        plt.axis('off')\n        ax.axis('off')\n        ax.grid(False)\n\n    def get_axis(self, index):\n        \"\"\"Retrieve the corresponding axis based on the index.\"\"\"\n        return self.axes[index//3, index % 3]\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        plt.savefig(filename)\n\n    def render_image_data(self, data, index):\n        \"\"\"Load and annotate image based on the provided path.\"\"\"\n        for i, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            img_path = data['img_filename'][idx]\n            image = self.load_image(img_path, cam)\n            self.update_image(image, i, cam)\n    \n    def draw_detection_pred(self, data, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['det'] and \"boxes_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d'].numpy()\n        for j, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            cam_intrinsic = data['cam_intrinsic'][idx]\n            lidar2cam = data['lidar2cam']\n            extrinsic = lidar2cam[idx]\n            trans = extrinsic[3, :3]\n            rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n            imsize = (1600, 900)\n\n            for i in range(result['labels_3d'].shape[0]):\n                score = result['scores_3d'][i]\n                if score < SCORE_THRESH: \n                    continue\n                color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n                \n                center = bboxes[i, 0 : 3]\n                box_dims = bboxes[i, 3 : 6]\n                nusc_dims = box_dims[..., [1, 0, 2]]\n                quat = Quaternion(axis=[0, 0, 1], radians=bboxes[i, 6])\n                box = NuScenesBox(\n                    center,\n                    nusc_dims,\n                    quat\n                )\n                box.rotate(rot)\n                box.translate(trans)\n                if box_in_image(box, cam_intrinsic, imsize):\n                    box.render(\n                        self.axes[j // 3, j % 3], \n                        view=cam_intrinsic, \n                        normalize=True, \n                        colors=(color, color, color),\n                        linewidth=4,\n                    )\n            \n            self.axes[j//3, j % 3].set_xlim(0, imsize[0])\n            self.axes[j//3, j % 3].set_ylim(imsize[1], 0)\n\n    def draw_motion_pred(self, data, result, points_per_step=10):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['motion'] and \"trajs_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d'].numpy()\n        for j, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            cam_intrinsic = data['cam_intrinsic'][idx]\n            lidar2cam = data['lidar2cam']\n            extrinsic = lidar2cam[idx]\n            trans = extrinsic[3, :3]\n            rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n            imsize = (1600, 900)\n\n            for i in range(result['labels_3d'].shape[0]):\n                score = result['scores_3d'][i]\n                if score < SCORE_THRESH: \n                    continue\n                color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n                \n                traj_score = result['trajs_score'][i].numpy()\n                traj = result['trajs_3d'][i].numpy()\n                \n                mode_idx = traj_score.argmax()\n                traj = traj[mode_idx]\n                origin = bboxes[i, :2][None]\n                traj = np.concatenate([origin, traj], axis=0)\n                traj_expand = np.ones((traj.shape[0], 1)) \n                traj_expand[:] = bboxes[i, 2] - bboxes[i, 5] / 2\n                traj = np.concatenate([traj, traj_expand], axis=1)\n\n                center = bboxes[i, 0 : 3]\n                box_dims = bboxes[i, 3 : 6]\n                nusc_dims = box_dims[..., [1, 0, 2]]\n                quat = Quaternion(axis=[0, 0, 1], radians=bboxes[i, 6])\n                box = NuScenesBox(\n                    center,\n                    nusc_dims,\n                    quat\n                )\n                box.rotate(rot)\n                box.translate(trans)\n                if not box_in_image(box, cam_intrinsic, imsize):\n                    continue\n                traj_points = traj @ extrinsic[:3, :3] + trans\n                self._render_traj(traj_points, cam_intrinsic, j, color=color, s=15)\n\n        \n    def draw_planning_pred(self, data, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n        # for j, cam in enumerate(CAM_NAMES_NUSC[1]):\n        #     idx = CAM_NAMES_NUSC_converter.index(cam)\n        #     cam_intrinsic = data['cam_intrinsic'][idx]\n        #     lidar2cam = data['lidar2cam']\n        #     extrinsic = lidar2cam[idx]\n        #     trans = extrinsic[3, :3]\n        #     rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n        #     imsize = (1600, 900)\n\n        #     plan_trajs = result['planning'][0].cpu().numpy()\n        #     plan_trajs = plan_trajs.reshape(3, -1, 6, 2)\n        #     num_cmd = len(CMD_LIST)\n        #     num_mode = plan_trajs.shape[1]\n        #     plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        #     plan_trajs = plan_trajs.cumsum(axis=-2)\n        #     plan_score = result['planning_score'][0].cpu().numpy()\n        #     plan_score = plan_score.reshape(3, -1)\n\n        #     cmd = data['gt_ego_fut_cmd'].argmax()\n        #     plan_trajs = plan_trajs[cmd]\n        #     plan_score = plan_score[cmd]\n\n        #     mode_idx = plan_score.argmax()\n        #     plan_traj = plan_trajs[mode_idx]\n        #     traj_expand = np.ones((plan_traj.shape[0], 1)) * -2\n        #     # traj_expand[:] = bboxes[i, 2] - bboxes[i, 5] / 2\n        #     plan_traj = np.concatenate([plan_traj, traj_expand], axis=1)\n\n        #     traj_points = plan_traj @ extrinsic[:3, :3] + trans\n        #     self._render_traj(traj_points, cam_intrinsic, j)\n\n        idx = 0 ## front camera\n        cam_intrinsic = data['cam_intrinsic'][idx]\n        lidar2cam = data['lidar2cam']\n        extrinsic = lidar2cam[idx]\n        trans = extrinsic[3, :3]\n        rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n        # plan_trajs = result['planning'][0].cpu().numpy()\n        # plan_trajs = plan_trajs.reshape(3, -1, 6, 2)\n        # num_cmd = len(CMD_LIST)\n        # num_mode = plan_trajs.shape[1]\n        # plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        # plan_trajs = plan_trajs.cumsum(axis=-2)\n        # plan_score = result['planning_score'][0].cpu().numpy()\n        # plan_score = plan_score.reshape(3, -1)\n\n        # cmd = data['gt_ego_fut_cmd'].argmax()\n        # plan_trajs = plan_trajs[cmd]\n        # plan_score = plan_score[cmd]\n\n        # mode_idx = plan_score.argmax()\n        # plan_traj = plan_trajs[mode_idx]\n        plan_traj = result[\"final_planning\"]\n        plan_traj = np.concatenate((np.zeros((1, 2)), plan_traj), axis=0)\n        traj_expand = np.ones((plan_traj.shape[0], 1)) * -1.8\n        plan_traj = np.concatenate([plan_traj, traj_expand], axis=1)\n\n        traj_points = plan_traj @ extrinsic[:3, :3] + trans\n        self._render_traj(traj_points, cam_intrinsic, j=1)\n\n    def _render_traj(self, traj_points, cam_intrinsic, j, color=(1, 0.5, 0), s=150, points_per_step=10):\n        total_steps = (len(traj_points)-1) * points_per_step + 1\n        total_xy = np.zeros((total_steps, 3))\n        for k in range(total_steps-1):\n            unit_vec = traj_points[k//points_per_step +\n                                    1] - traj_points[k//points_per_step]\n            total_xy[k] = (k/points_per_step - k//points_per_step) * \\\n                unit_vec + traj_points[k//points_per_step]\n        in_range_mask = total_xy[:, 2] > 0.1\n        traj_points = view_points(\n            total_xy.T, cam_intrinsic, normalize=True)[:2, :]\n        traj_points = traj_points[:2, in_range_mask]\n        self.axes[j // 3, j % 3].scatter(traj_points[0], traj_points[1], color=color, s=s)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/sparsedrive/train.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.utils import get_dist_info, init_dist\nfrom os import path as osp\n\n\nfrom mmcv.datasets import build_dataset\nfrom mmcv.models import build_model\nfrom mmcv.utils import collect_env, get_root_logger\nfrom mmcv.utils import set_random_seed\n\nfrom mmcv.utils import TORCH_VERSION, digit_version\n#from adzoo.bevformer.mmdet3d_plugin.bevformer.apis.train import custom_train_model\n\n#from mmdet import __version__ as mmdet_version\n#from mmdet.apis import train_detector\n#from mmdet.datasets import build_dataset\n#from mmdet.models import build_detectorbuild_model\n#from mmdet.utils import collect_env, get_root_logger\n#from mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_model(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    # print(\"hhhhhhhhhhhhhhh\")\n    print(cfg.data.train)\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\", force=True\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/analyze_logs.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport json\nimport numpy as np\nimport seaborn as sns\nfrom collections import defaultdict\nfrom matplotlib import pyplot as plt\n\n\ndef cal_train_time(log_dicts, args):\n    for i, log_dict in enumerate(log_dicts):\n        print(f'{\"-\" * 5}Analyze train time of {args.json_logs[i]}{\"-\" * 5}')\n        all_times = []\n        for epoch in log_dict.keys():\n            if args.include_outliers:\n                all_times.append(log_dict[epoch]['time'])\n            else:\n                all_times.append(log_dict[epoch]['time'][1:])\n        all_times = np.array(all_times)\n        epoch_ave_time = all_times.mean(-1)\n        slowest_epoch = epoch_ave_time.argmax()\n        fastest_epoch = epoch_ave_time.argmin()\n        std_over_epoch = epoch_ave_time.std()\n        print(f'slowest epoch {slowest_epoch + 1}, '\n              f'average time is {epoch_ave_time[slowest_epoch]:.4f}')\n        print(f'fastest epoch {fastest_epoch + 1}, '\n              f'average time is {epoch_ave_time[fastest_epoch]:.4f}')\n        print(f'time std over epochs is {std_over_epoch:.4f}')\n        print(f'average iter time: {np.mean(all_times):.4f} s/iter')\n        print()\n\n\ndef plot_curve(log_dicts, args):\n    if args.backend is not None:\n        plt.switch_backend(args.backend)\n    sns.set_style(args.style)\n    # if legend is None, use {filename}_{key} as legend\n    legend = args.legend\n    if legend is None:\n        legend = []\n        for json_log in args.json_logs:\n            for metric in args.keys:\n                legend.append(f'{json_log}_{metric}')\n    assert len(legend) == (len(args.json_logs) * len(args.keys))\n    metrics = args.keys\n\n    num_metrics = len(metrics)\n    for i, log_dict in enumerate(log_dicts):\n        epochs = list(log_dict.keys())\n        for j, metric in enumerate(metrics):\n            print(f'plot curve of {args.json_logs[i]}, metric is {metric}')\n            if metric not in log_dict[epochs[args.interval - 1]]:\n                raise KeyError(\n                    f'{args.json_logs[i]} does not contain metric {metric}')\n\n            if args.mode == 'eval':\n                if min(epochs) == args.interval:\n                    x0 = args.interval\n                else:\n                    # if current training is resumed from previous checkpoint\n                    # we lost information in early epochs\n                    # `xs` should start according to `min(epochs)`\n                    if min(epochs) % args.interval == 0:\n                        x0 = min(epochs)\n                    else:\n                        # find the first epoch that do eval\n                        x0 = min(epochs) + args.interval - \\\n                            min(epochs) % args.interval\n                xs = np.arange(x0, max(epochs) + 1, args.interval)\n                ys = []\n                for epoch in epochs[args.interval - 1::args.interval]:\n                    ys += log_dict[epoch][metric]\n\n                # if training is aborted before eval of the last epoch\n                # `xs` and `ys` will have different length and cause an error\n                # check if `ys[-1]` is empty here\n                if not log_dict[epoch][metric]:\n                    xs = xs[:-1]\n\n                ax = plt.gca()\n                ax.set_xticks(xs)\n                plt.xlabel('epoch')\n                plt.plot(xs, ys, label=legend[i * num_metrics + j], marker='o')\n            else:\n                xs = []\n                ys = []\n                num_iters_per_epoch = \\\n                    log_dict[epochs[args.interval-1]]['iter'][-1]\n                for epoch in epochs[args.interval - 1::args.interval]:\n                    iters = log_dict[epoch]['iter']\n                    if log_dict[epoch]['mode'][-1] == 'val':\n                        iters = iters[:-1]\n                    xs.append(\n                        np.array(iters) + (epoch - 1) * num_iters_per_epoch)\n                    ys.append(np.array(log_dict[epoch][metric][:len(iters)]))\n                xs = np.concatenate(xs)\n                ys = np.concatenate(ys)\n                plt.xlabel('iter')\n                plt.plot(\n                    xs, ys, label=legend[i * num_metrics + j], linewidth=0.5)\n            plt.legend()\n        if args.title is not None:\n            plt.title(args.title)\n    if args.out is None:\n        plt.show()\n    else:\n        print(f'save curve to: {args.out}')\n        plt.savefig(args.out)\n        plt.cla()\n\n\ndef add_plot_parser(subparsers):\n    parser_plt = subparsers.add_parser(\n        'plot_curve', help='parser for plotting curves')\n    parser_plt.add_argument(\n        'json_logs',\n        type=str,\n        nargs='+',\n        help='path of train log in json format')\n    parser_plt.add_argument(\n        '--keys',\n        type=str,\n        nargs='+',\n        default=['mAP_0.25'],\n        help='the metric that you want to plot')\n    parser_plt.add_argument('--title', type=str, help='title of figure')\n    parser_plt.add_argument(\n        '--legend',\n        type=str,\n        nargs='+',\n        default=None,\n        help='legend of each plot')\n    parser_plt.add_argument(\n        '--backend', type=str, default=None, help='backend of plt')\n    parser_plt.add_argument(\n        '--style', type=str, default='dark', help='style of plt')\n    parser_plt.add_argument('--out', type=str, default=None)\n    parser_plt.add_argument('--mode', type=str, default='train')\n    parser_plt.add_argument('--interval', type=int, default=1)\n\n\ndef add_time_parser(subparsers):\n    parser_time = subparsers.add_parser(\n        'cal_train_time',\n        help='parser for computing the average time per training iteration')\n    parser_time.add_argument(\n        'json_logs',\n        type=str,\n        nargs='+',\n        help='path of train log in json format')\n    parser_time.add_argument(\n        '--include-outliers',\n        action='store_true',\n        help='include the first value of every epoch when computing '\n        'the average time')\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Analyze Json Log')\n    # currently only support plot curve and calculate average train time\n    subparsers = parser.add_subparsers(dest='task', help='task parser')\n    add_plot_parser(subparsers)\n    add_time_parser(subparsers)\n    args = parser.parse_args()\n    return args\n\n\ndef load_json_logs(json_logs):\n    # load and convert json_logs to log_dict, key is epoch, value is a sub dict\n    # keys of sub dict is different metrics, e.g. memory, bbox_mAP\n    # value of sub dict is a list of corresponding values of all iterations\n    log_dicts = [dict() for _ in json_logs]\n    for json_log, log_dict in zip(json_logs, log_dicts):\n        with open(json_log, 'r') as log_file:\n            for line in log_file:\n                log = json.loads(line.strip())\n                # skip lines without `epoch` field\n                if 'epoch' not in log:\n                    continue\n                epoch = log.pop('epoch')\n                if epoch not in log_dict:\n                    log_dict[epoch] = defaultdict(list)\n                for k, v in log.items():\n                    log_dict[epoch][k].append(v)\n    return log_dicts\n\n\ndef main():\n    args = parse_args()\n\n    json_logs = args.json_logs\n    for json_log in json_logs:\n        assert json_log.endswith('.json')\n\n    log_dicts = load_json_logs(json_logs)\n\n    eval(args.task)(log_dicts, args)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/benchmark.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport time\nimport torch\nfrom mmcv import Config\nfrom mmcv.parallel import MMDataParallel\nfrom mmcv.runner import load_checkpoint, wrap_fp16_model\nimport sys\nsys.path.append('.')\nfrom mmcv.datasets.builder import build_dataloader\nfrom mmcv.datasets import build_dataset\nfrom mmcv.models import build_detector\n#from tools.misc.fuse_conv_bn import fuse_module\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='MMDet benchmark a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--checkpoint', default=None, help='checkpoint file')\n    parser.add_argument('--samples', default=2000, help='samples to benchmark')\n    parser.add_argument(\n        '--log-interval', default=10, help='interval of logging')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n\n    # build the dataloader\n    # TODO: support multiple images per gpu (only minor changes are needed)\n    print(cfg.data.test)\n    dataset = build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=False,\n        shuffle=False)\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    #if args.fuse_conv_bn:\n    #    model = fuse_module(model)\n\n    model = MMDataParallel(model, device_ids=[0])\n\n    model.eval()\n\n    # the first several iterations may be very slow so skip them\n    num_warmup = 5\n    pure_inf_time = 0\n\n    # benchmark with several samples and take the average\n    for i, data in enumerate(data_loader):\n        torch.cuda.synchronize()\n        start_time = time.perf_counter()\n        with torch.no_grad():\n            model(return_loss=False, rescale=True, **data)\n\n        torch.cuda.synchronize()\n        elapsed = time.perf_counter() - start_time\n\n        if i >= num_warmup:\n            pure_inf_time += elapsed\n            if (i + 1) % args.log_interval == 0:\n                fps = (i + 1 - num_warmup) / pure_inf_time\n                print(f'Done image [{i + 1:<3}/ {args.samples}], '\n                      f'fps: {fps:.1f} img / s')\n\n        if (i + 1) == args.samples:\n            pure_inf_time += elapsed\n            fps = (i + 1 - num_warmup) / pure_inf_time\n            print(f'Overall fps: {fps:.1f} img / s')\n            break\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/visualize/render/base_render.py",
    "content": "import matplotlib.pyplot as plt\nfrom pyquaternion import Quaternion\n\n\nclass BaseRender:\n    \"\"\"\n    BaseRender class\n    \"\"\"\n\n    def __init__(\n            self,\n            figsize=(10, 10)):\n        self.figsize = figsize\n        self.fig, self.axes = None, None\n\n    def reset_canvas(self, dx=1, dy=1, tight_layout=False):\n        plt.close()\n        plt.gca().set_axis_off()\n        plt.axis('off')\n        self.fig, self.axes = plt.subplots(dx, dy, figsize=self.figsize)\n        if tight_layout:\n            plt.tight_layout()\n\n    def close_canvas(self):\n        plt.close()\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        print(f'saving to {filename}')\n        plt.savefig(filename)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/visualize/render/bev_render.py",
    "content": "import cv2\nimport numpy as np\nimport matplotlib\nimport matplotlib.pyplot as plt\nfrom pyquaternion import Quaternion\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom tools.analysis_tools.visualize.render.base_render import BaseRender\nfrom tools.analysis_tools.visualize.utils import color_mapping, AgentPredictionData\n\n\nclass BEVRender(BaseRender):\n    \"\"\"\n    Render class for BEV\n    \"\"\"\n\n    def __init__(self,\n                 figsize=(20, 20),\n                 margin: float = 50,\n                 view: np.ndarray = np.eye(4),\n                 show_gt_boxes=False):\n        super(BEVRender, self).__init__(figsize)\n        self.margin = margin\n        self.view = view\n        self.show_gt_boxes = show_gt_boxes\n\n    def set_plot_cfg(self):\n        self.axes.set_xlim([-self.margin, self.margin])\n        self.axes.set_ylim([-self.margin, self.margin])\n        self.axes.set_aspect('equal')\n        self.axes.grid(False)\n\n    def render_sample_data(self, canvas, sample_token):\n        pass\n\n    def render_anno_data(\n            self,\n            sample_token,\n            nusc,\n            predict_helper):\n        sample_record = nusc.get('sample', sample_token)\n        assert 'LIDAR_TOP' in sample_record['data'].keys(\n        ), 'Error: No LIDAR_TOP in data, unable to render.'\n        lidar_record = sample_record['data']['LIDAR_TOP']\n        data_path, boxes, _ = nusc.get_sample_data(\n            lidar_record, selected_anntokens=sample_record['anns'])\n        for box in boxes:\n            instance_token = nusc.get('sample_annotation', box.token)[\n                'instance_token']\n            future_xy_local = predict_helper.get_future_for_agent(\n                instance_token, sample_token, seconds=6, in_agent_frame=True)\n            if future_xy_local.shape[0] > 0:\n                trans = box.center\n                rot = Quaternion(matrix=box.rotation_matrix)\n                future_xy = convert_local_coords_to_global(\n                    future_xy_local, trans, rot)\n                future_xy = np.concatenate(\n                    [trans[None, :2], future_xy], axis=0)\n                c = np.array([0, 0.8, 0])\n                box.render(self.axes, view=self.view, colors=(c, c, c))\n                self._render_traj(future_xy, line_color=c, dot_color=(0, 0, 0))\n        self.axes.set_xlim([-self.margin, self.margin])\n        self.axes.set_ylim([-self.margin, self.margin])\n\n    def show_lidar_data(\n            self,\n            sample_token,\n            nusc):\n        sample_record = nusc.get('sample', sample_token)\n        assert 'LIDAR_TOP' in sample_record['data'].keys(\n        ), 'Error: No LIDAR_TOP in data, unable to render.'\n        lidar_record = sample_record['data']['LIDAR_TOP']\n        data_path, boxes, _ = nusc.get_sample_data(\n            lidar_record, selected_anntokens=sample_record['anns'])\n        LidarPointCloud.from_file(data_path).render_height(\n            self.axes, view=self.view)\n        self.axes.set_xlim([-self.margin, self.margin])\n        self.axes.set_ylim([-self.margin, self.margin])\n        self.axes.axis('off')\n        self.axes.set_aspect('equal')\n\n    def render_pred_box_data(self, agent_prediction_list):\n        for pred_agent in agent_prediction_list:\n            c = np.array([0, 1, 0])\n            if hasattr(pred_agent, 'pred_track_id') and pred_agent.pred_track_id is not None:  # this is true\n                tr_id = pred_agent.pred_track_id\n                c = color_mapping[tr_id % len(color_mapping)]\n            pred_agent.nusc_box.render(\n                axis=self.axes, view=self.view, colors=(c, c, c))\n            if pred_agent.is_sdc:\n                c = np.array([1, 0, 0])\n                pred_agent.nusc_box.render(\n                    axis=self.axes, view=self.view, colors=(c, c, c))\n\n    def render_pred_traj(self, agent_prediction_list, top_k=3):\n        for pred_agent in agent_prediction_list:\n            if pred_agent.is_sdc:\n                continue\n            sorted_ind = np.argsort(pred_agent.pred_traj_score)[\n                ::-1]  # from high to low\n            num_modes = len(sorted_ind)\n            sorted_traj = pred_agent.pred_traj[sorted_ind, :, :2]\n            sorted_score = pred_agent.pred_traj_score[sorted_ind]\n            # norm_score = np.sum(np.exp(sorted_score))\n            norm_score = np.exp(sorted_score[0])\n\n            sorted_traj = np.concatenate(\n                [np.zeros((num_modes, 1, 2)), sorted_traj], axis=1)\n            trans = pred_agent.pred_center\n            rot = Quaternion(axis=np.array([0, 0.0, 1.0]), angle=np.pi/2)\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if pred_agent.pred_label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n            # print(sorted_score)\n            for i in range(top_k-1, -1, -1):\n                viz_traj = sorted_traj[i, :, :2]\n                viz_traj = convert_local_coords_to_global(viz_traj, trans, rot)\n                traj_score = np.exp(sorted_score[i])/norm_score\n                # traj_score = [1.0, 0.01, 0.01, 0.01, 0.01, 0.01][i]\n                self._render_traj(viz_traj, traj_score=traj_score,\n                                  colormap='winter', dot_size=dot_size)\n\n    def render_pred_map_data(self, predicted_map_seg):\n        # rendered_map = map_color_dict\n        # divider, crossing, contour\n        map_color_dict = np.array(\n            [(204, 128, 0), (102, 255, 102), (102, 255, 102)])\n        rendered_map = map_color_dict[predicted_map_seg.argmax(\n            -1).reshape(-1)].reshape(200, 200, -1)\n        bg_mask = predicted_map_seg.sum(-1) == 0\n        rendered_map[bg_mask, :] = 255\n        self.axes.imshow(rendered_map, alpha=0.6,\n                         interpolation='nearest', extent=(-51.2, 51.2, -51.2, 51.2))\n\n    def render_occ_map_data(self, agent_list):\n        rendered_map = np.ones((200, 200, 3))\n        rendered_map_hsv = matplotlib.colors.rgb_to_hsv(rendered_map)\n        occ_prob_map = np.zeros((200, 200))\n        for i in range(len(agent_list)):\n            pred_agent = agent_list[i]\n            if pred_agent.pred_occ_map is None:\n                continue\n            if hasattr(pred_agent, 'pred_track_id') and pred_agent.pred_track_id is not None:  # this is true\n                tr_id = pred_agent.pred_track_id\n                c = color_mapping[tr_id % len(color_mapping)]\n            pred_occ_map = pred_agent.pred_occ_map.max(0)\n            update_mask = pred_occ_map > occ_prob_map\n            occ_prob_map[update_mask] = pred_occ_map[update_mask]\n            pred_occ_map *= update_mask\n            hsv_c = matplotlib.colors.rgb_to_hsv(c)\n            rendered_map_hsv[pred_occ_map > 0.1] = (\n                np.ones((200, 200, 1)) * hsv_c)[pred_occ_map > 0.1]\n            max_prob = pred_occ_map.max()\n            renorm_pred_occ_map = (pred_occ_map - max_prob) * 0.7 + 1\n            sat_map = (renorm_pred_occ_map * hsv_c[1])\n            rendered_map_hsv[pred_occ_map > 0.1,\n                             1] = sat_map[pred_occ_map > 0.1]\n            rendered_map = matplotlib.colors.hsv_to_rgb(rendered_map_hsv)\n        self.axes.imshow(rendered_map, alpha=0.8,\n                         interpolation='nearest', extent=(-50, 50, -50, 50))\n\n    def render_occ_map_data_time(self, agent_list, t):\n        rendered_map = np.ones((200, 200, 3))\n        rendered_map_hsv = matplotlib.colors.rgb_to_hsv(rendered_map)\n        occ_prob_map = np.zeros((200, 200))\n        for i in range(len(agent_list)):\n            pred_agent = agent_list[i]\n            if pred_agent.pred_occ_map is None:\n                continue\n            if hasattr(pred_agent, 'pred_track_id') and pred_agent.pred_track_id is not None:  # this is true\n                tr_id = pred_agent.pred_track_id\n                c = color_mapping[tr_id % len(color_mapping)]\n            pred_occ_map = pred_agent.pred_occ_map[t]\n            update_mask = pred_occ_map > occ_prob_map\n            occ_prob_map[update_mask] = pred_occ_map[update_mask]\n            pred_occ_map *= update_mask\n            hsv_c = matplotlib.colors.rgb_to_hsv(c)\n            rendered_map_hsv[pred_occ_map > 0.1] = (\n                np.ones((200, 200, 1)) * hsv_c)[pred_occ_map > 0.1]\n            max_prob = pred_occ_map.max()\n            renorm_pred_occ_map = (pred_occ_map - max_prob) * 0.7 + 1\n            sat_map = (renorm_pred_occ_map * hsv_c[1])\n            rendered_map_hsv[pred_occ_map > 0.1,\n                             1] = sat_map[pred_occ_map > 0.1]\n            rendered_map = matplotlib.colors.hsv_to_rgb(rendered_map_hsv)\n        self.axes.imshow(rendered_map, alpha=0.8,\n                         interpolation='nearest', extent=(-50, 50, -50, 50))\n\n    def render_planning_data(self, predicted_planning, show_command=False):\n        planning_traj = predicted_planning.pred_traj\n        planning_traj = np.concatenate(\n            [np.zeros((1, 2)), planning_traj], axis=0)\n        self._render_traj(planning_traj, colormap='autumn', dot_size=50)\n        if show_command:\n            self._render_command(predicted_planning.command)\n\n    def render_planning_attn_mask(self, predicted_planning):\n        planning_attn_mask = predicted_planning.attn_mask\n        planning_attn_mask = planning_attn_mask/planning_attn_mask.max()\n        cmap_name = 'plasma'\n        self.axes.imshow(planning_attn_mask, alpha=0.8, interpolation='nearest', extent=(\n            -51.2, 51.2, -51.2, 51.2), vmax=0.2, cmap=matplotlib.colormaps[cmap_name])\n\n    def render_hd_map(self, nusc, nusc_maps, sample_token):\n        sample_record = nusc.get('sample', sample_token)\n        sd_rec = nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        info = {\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'scene_token': sample_record['scene_token']\n        }\n\n        layer_names = ['road_divider', 'road_segment', 'lane_divider',\n                       'lane',  'road_divider', 'traffic_light', 'ped_crossing']\n        map_mask = obtain_map_info(nusc,\n                                   nusc_maps,\n                                   info,\n                                   patch_size=(102.4, 102.4),\n                                   canvas_size=(1024, 1024),\n                                   layer_names=layer_names)\n        map_mask = np.flip(map_mask, axis=1)\n        map_mask = np.rot90(map_mask, k=-1, axes=(1, 2))\n        map_mask = map_mask[:, ::-1] > 0\n        map_show = np.ones((1024, 1024, 3))\n        map_show[map_mask[0], :] = np.array([1.00, 0.50, 0.31])\n        map_show[map_mask[1], :] = np.array([159./255., 0.0, 1.0])\n        self.axes.imshow(map_show, alpha=0.2, interpolation='nearest',\n                         extent=(-51.2, 51.2, -51.2, 51.2))\n\n    def _render_traj(self, future_traj, traj_score=1, colormap='winter', points_per_step=20, line_color=None, dot_color=None, dot_size=25):\n        total_steps = (len(future_traj)-1) * points_per_step + 1\n        dot_colors = matplotlib.colormaps[colormap](\n            np.linspace(0, 1, total_steps))[:, :3]\n        dot_colors = dot_colors*traj_score + \\\n            (1-traj_score)*np.ones_like(dot_colors)\n        total_xy = np.zeros((total_steps, 2))\n        for i in range(total_steps-1):\n            unit_vec = future_traj[i//points_per_step +\n                                   1] - future_traj[i//points_per_step]\n            total_xy[i] = (i/points_per_step - i//points_per_step) * \\\n                unit_vec + future_traj[i//points_per_step]\n        total_xy[-1] = future_traj[-1]\n        self.axes.scatter(\n            total_xy[:, 0], total_xy[:, 1], c=dot_colors, s=dot_size)\n\n    def _render_command(self, command):\n        command_dict = ['TURN RIGHT', 'TURN LEFT', 'KEEP FORWARD']\n        self.axes.text(-48, -45, command_dict[int(command)], fontsize=45)\n\n    def render_sdc_car(self):\n        sdc_car_png = cv2.imread('sources/sdc_car.png')\n        sdc_car_png = cv2.cvtColor(sdc_car_png, cv2.COLOR_BGR2RGB)\n        self.axes.imshow(sdc_car_png, extent=(-1, 1, -2, 2))\n\n    def render_legend(self):\n        legend = cv2.imread('sources/legend.png')\n        legend = cv2.cvtColor(legend, cv2.COLOR_BGR2RGB)\n        self.axes.imshow(legend, extent=(23, 51.2, -50, -40))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/visualize/render/cam_render.py",
    "content": "import cv2\nimport numpy as np\nfrom PIL import Image\nimport matplotlib.pyplot as plt\nfrom nuscenes.utils.data_classes import LidarPointCloud, Box\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nfrom tools.analysis_tools.visualize.utils import color_mapping, AgentPredictionData\nfrom tools.analysis_tools.visualize.render.base_render import BaseRender\nfrom pyquaternion import Quaternion\n\n# Define a constant for camera names\nCAM_NAMES = [\n    'CAM_FRONT_LEFT',\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_BACK_RIGHT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n]\n\n\nclass CameraRender(BaseRender):\n    \"\"\"\n    Render class for Camera View\n    \"\"\"\n\n    def __init__(self,\n                 figsize=(53.3333, 20),\n                 show_gt_boxes=False):\n        super().__init__(figsize)\n        self.cams = CAM_NAMES\n        self.show_gt_boxes = show_gt_boxes\n\n    def get_axis(self, index):\n        \"\"\"Retrieve the corresponding axis based on the index.\"\"\"\n        return self.axes[index//3, index % 3]\n\n    def project_to_cam(self,\n                       agent_prediction_list,\n                       sample_data_token,\n                       nusc,\n                       lidar_cs_record,\n                       project_traj=False,\n                       cam=None,\n                       ):\n        \"\"\"Project predictions to camera view.\"\"\"\n        _, cs_record, pose_record, cam_intrinsic, imsize = self.get_image_info(\n            sample_data_token, nusc)\n        boxes = []\n        for agent in agent_prediction_list:\n            box = Box(agent.pred_center, agent.pred_dim, Quaternion(axis=(0.0, 0.0, 1.0), radians=agent.pred_yaw),\n                      name=agent.pred_label, token='predicted')\n            box.is_sdc = agent.is_sdc\n            if project_traj:\n                box.pred_traj = np.zeros((agent.pred_traj_max.shape[0]+1, 3))\n                box.pred_traj[:, 0] = agent.pred_center[0]\n                box.pred_traj[:, 1] = agent.pred_center[1]\n                box.pred_traj[:, 2] = agent.pred_center[2] - \\\n                    agent.pred_dim[2]/2\n                box.pred_traj[1:, :2] += agent.pred_traj_max[:, :2]\n                box.pred_traj = (Quaternion(\n                    lidar_cs_record['rotation']).rotation_matrix @ box.pred_traj.T).T\n                box.pred_traj += np.array(\n                    lidar_cs_record['translation'])[None, :]\n            box.rotate(Quaternion(lidar_cs_record['rotation']))\n            box.translate(np.array(lidar_cs_record['translation']))\n            boxes.append(box)\n        # Make list of Box objects including coord system transforms.\n\n        box_list = []\n        tr_id_list = []\n        for i, box in enumerate(boxes):\n            #  Move box to sensor coord system.\n            box.translate(-np.array(cs_record['translation']))\n            box.rotate(Quaternion(cs_record['rotation']).inverse)\n            if project_traj:\n                box.pred_traj += -np.array(cs_record['translation'])[None, :]\n                box.pred_traj = (Quaternion(\n                    cs_record['rotation']).inverse.rotation_matrix @ box.pred_traj.T).T\n\n            tr_id = agent_prediction_list[i].pred_track_id\n            if box.is_sdc and cam == 'CAM_FRONT':\n                box_list.append(box)\n            if not box_in_image(box, cam_intrinsic, imsize):\n                continue\n            box_list.append(box)\n            tr_id_list.append(tr_id)\n        return box_list, tr_id_list, cam_intrinsic, imsize\n\n    def render_image_data(self, sample_token, nusc):\n        \"\"\"Load and annotate image based on the provided path.\"\"\"\n        sample = nusc.get('sample', sample_token)\n        for i, cam in enumerate(self.cams):\n            sample_data_token = sample['data'][cam]\n            data_path, _, _, _, _ = self.get_image_info(\n                sample_data_token, nusc)\n            image = self.load_image(data_path, cam)\n            self.update_image(image, i, cam)\n\n    def load_image(self, data_path, cam):\n        \"\"\"Update the axis of the plot with the provided image.\"\"\"\n        image = np.array(Image.open(data_path))\n        font = cv2.FONT_HERSHEY_SIMPLEX\n        org = (50, 60)\n        fontScale = 2\n        color = (0, 0, 0)\n        thickness = 4\n        return cv2.putText(image, cam, org, font, fontScale, color, thickness, cv2.LINE_AA)\n\n    def update_image(self, image, index, cam):\n        \"\"\"Render image data for each camera.\"\"\"\n        ax = self.get_axis(index)\n        ax.imshow(image)\n        plt.axis('off')\n        ax.axis('off')\n        ax.grid(False)\n\n    def render_pred_track_bbox(self, predicted_agent_list, sample_token, nusc):\n        \"\"\"Render bounding box for predicted tracks.\"\"\"\n        sample = nusc.get('sample', sample_token)\n        lidar_cs_record = nusc.get('calibrated_sensor', nusc.get(\n            'sample_data', sample['data']['LIDAR_TOP'])['calibrated_sensor_token'])\n        for i, cam in enumerate(self.cams):\n            sample_data_token = sample['data'][cam]\n            box_list, tr_id_list, camera_intrinsic, imsize = self.project_to_cam(\n                predicted_agent_list, sample_data_token, nusc, lidar_cs_record)\n            for j, box in enumerate(box_list):\n                if box.is_sdc:\n                    continue\n                tr_id = tr_id_list[j]\n                if tr_id is None:\n                    tr_id = 0\n                c = color_mapping[tr_id % len(color_mapping)]\n                box.render(\n                    self.axes[i//3, i % 3], view=camera_intrinsic, normalize=True, colors=(c, c, c))\n            # plot gt\n            if self.show_gt_boxes:\n                data_path, boxes, camera_intrinsic = nusc.get_sample_data(\n                    sample_data_token, selected_anntokens=sample['anns'])\n                for j, box in enumerate(boxes):\n                    c = [0, 1, 0]\n                    box.render(\n                        self.axes[i//3, i % 3], view=camera_intrinsic, normalize=True, colors=(c, c, c))\n            self.axes[i//3, i % 3].set_xlim(0, imsize[0])\n            self.axes[i//3, i % 3].set_ylim(imsize[1], 0)\n\n    def render_pred_traj(self, predicted_agent_list, sample_token, nusc, render_sdc=False, points_per_step=10):\n        \"\"\"Render predicted trajectories.\"\"\"\n        sample = nusc.get('sample', sample_token)\n        lidar_cs_record = nusc.get('calibrated_sensor', nusc.get(\n            'sample_data', sample['data']['LIDAR_TOP'])['calibrated_sensor_token'])\n        for i, cam in enumerate(self.cams):\n            sample_data_token = sample['data'][cam]\n            box_list, tr_id_list, camera_intrinsic, imsize = self.project_to_cam(\n                predicted_agent_list, sample_data_token, nusc, lidar_cs_record, project_traj=True, cam=cam)\n            for j, box in enumerate(box_list):\n                traj_points = box.pred_traj[:, :3]\n\n                total_steps = (len(traj_points)-1) * points_per_step + 1\n                total_xy = np.zeros((total_steps, 3))\n                for k in range(total_steps-1):\n                    unit_vec = traj_points[k//points_per_step +\n                                           1] - traj_points[k//points_per_step]\n                    total_xy[k] = (k/points_per_step - k//points_per_step) * \\\n                        unit_vec + traj_points[k//points_per_step]\n                in_range_mask = total_xy[:, 2] > 0.1\n                traj_points = view_points(\n                    total_xy.T, camera_intrinsic, normalize=True)[:2, :]\n                traj_points = traj_points[:2, in_range_mask]\n                if box.is_sdc:\n                    if render_sdc:\n                        self.axes[i//3, i % 3].scatter(\n                            traj_points[0], traj_points[1], color=(1, 0.5, 0), s=150)\n                    else:\n                        continue\n                else:\n                    tr_id = tr_id_list[j]\n                    if tr_id is None:\n                        tr_id = 0\n                    c = color_mapping[tr_id % len(color_mapping)]\n                    self.axes[i//3, i %\n                              3].scatter(traj_points[0], traj_points[1], color=c, s=15)\n            self.axes[i//3, i % 3].set_xlim(0, imsize[0])\n            self.axes[i//3, i % 3].set_ylim(imsize[1], 0)\n\n    def get_image_info(self, sample_data_token, nusc):\n        \"\"\"Retrieve image information.\"\"\"\n        sd_record = nusc.get('sample_data', sample_data_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_record['calibrated_sensor_token'])\n        sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n\n        data_path = nusc.get_sample_data_path(sample_data_token)\n\n        if sensor_record['modality'] == 'camera':\n            cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n            imsize = (sd_record['width'], sd_record['height'])\n        else:\n            cam_intrinsic = None\n            imsize = None\n        return data_path, cs_record, pose_record, cam_intrinsic, imsize\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/visualize/run.py",
    "content": "import cv2\nimport torch\nimport argparse\nimport os\nimport glob\nimport numpy as np\nimport matplotlib\nimport matplotlib.pyplot as plt\nfrom nuscenes import NuScenes\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nfrom nuscenes.utils.data_classes import LidarPointCloud, Box\nfrom nuscenes.utils import splits\nfrom pyquaternion import Quaternion\nfrom mmcv.datasets.nuscenes_e2e_dataset import obtain_map_info\nfrom mmcv.datasets.eval_utils.map_api import NuScenesMap\nfrom mmcv.fileio.io import load\nfrom PIL import Image\nfrom tools.analysis_tools.visualize.utils import color_mapping, AgentPredictionData\nfrom tools.analysis_tools.visualize.render.bev_render import BEVRender\nfrom tools.analysis_tools.visualize.render.cam_render import CameraRender\n\n\nclass Visualizer:\n    \"\"\"\n    BaseRender class\n    \"\"\"\n\n    def __init__(\n            self,\n            dataroot='/mnt/petrelfs/yangjiazhi/e2e_proj/data/nus_mini',\n            version='v1.0-mini',\n            predroot=None,\n            with_occ_map=False,\n            with_map=False,\n            with_planning=False,\n            with_pred_box=True,\n            with_pred_traj=False,\n            show_gt_boxes=False,\n            show_lidar=False,\n            show_command=False,\n            show_hd_map=False,\n            show_sdc_car=False,\n            show_sdc_traj=False,\n            show_legend=False):\n        self.nusc = NuScenes(version=version, dataroot=dataroot, verbose=True)\n        self.predict_helper = PredictHelper(self.nusc)\n        self.with_occ_map = with_occ_map\n        self.with_map = with_map\n        self.with_planning = with_planning\n        self.show_lidar = show_lidar\n        self.show_command = show_command\n        self.show_hd_map = show_hd_map\n        self.show_sdc_car = show_sdc_car\n        self.show_sdc_traj = show_sdc_traj\n        self.show_legend = show_legend\n        self.with_pred_traj = with_pred_traj\n        self.with_pred_box = with_pred_box\n        self.veh_id_list = [0, 1, 2, 3, 4, 6, 7]\n        self.use_json = '.json' in predroot\n        self.token_set = set()\n        self.predictions = self._parse_predictions_multitask_pkl(predroot)\n        self.bev_render = BEVRender(show_gt_boxes=show_gt_boxes)\n        self.cam_render = CameraRender(show_gt_boxes=show_gt_boxes)\n\n        if self.show_hd_map:\n            self.nusc_maps = {\n                'boston-seaport': NuScenesMap(dataroot=dataroot, map_name='boston-seaport'),\n                'singapore-hollandvillage': NuScenesMap(dataroot=dataroot, map_name='singapore-hollandvillage'),\n                'singapore-onenorth': NuScenesMap(dataroot=dataroot, map_name='singapore-onenorth'),\n                'singapore-queenstown': NuScenesMap(dataroot=dataroot, map_name='singapore-queenstown'),\n            }\n\n    def _parse_predictions_multitask_pkl(self, predroot):\n\n        outputs = load(predroot)\n        outputs = outputs['bbox_results']\n        prediction_dict = dict()\n        for k in range(len(outputs)):\n            token = outputs[k]['token']\n            self.token_set.add(token)\n            if self.show_sdc_traj:\n                outputs[k]['boxes_3d'].tensor = torch.cat(\n                    [outputs[k]['boxes_3d'].tensor, outputs[k]['sdc_boxes_3d'].tensor], dim=0)\n                outputs[k]['scores_3d'] = torch.cat(\n                    [outputs[k]['scores_3d'], outputs[k]['sdc_scores_3d']], dim=0)\n                outputs[k]['labels_3d'] = torch.cat([outputs[k]['labels_3d'], torch.zeros(\n                    (1,), device=outputs[k]['labels_3d'].device)], dim=0)\n            # detection\n            bboxes = outputs[k]['boxes_3d']\n            scores = outputs[k]['scores_3d']\n            labels = outputs[k]['labels_3d']\n\n            track_scores = scores.cpu().detach().numpy()\n            track_labels = labels.cpu().detach().numpy()\n            track_boxes = bboxes.tensor.cpu().detach().numpy()\n\n            track_centers = bboxes.gravity_center.cpu().detach().numpy()\n            track_dims = bboxes.dims.cpu().detach().numpy()\n            track_yaw = bboxes.yaw.cpu().detach().numpy()\n\n            if 'track_ids' in outputs[k]:\n                track_ids = outputs[k]['track_ids'].cpu().detach().numpy()\n            else:\n                track_ids = None\n\n            # speed\n            track_velocity = bboxes.tensor.cpu().detach().numpy()[:, -2:]\n\n            # trajectories\n            trajs = outputs[k][f'traj'].numpy()\n            traj_scores = outputs[k][f'traj_scores'].numpy()\n\n            predicted_agent_list = []\n\n            # occflow\n            if self.with_occ_map:\n                if 'topk_query_ins_segs' in outputs[k]['occ']:\n                    occ_map = outputs[k]['occ']['topk_query_ins_segs'][0].cpu(\n                    ).numpy()\n                else:\n                    occ_map = np.zeros((1, 5, 200, 200))\n            else:\n                occ_map = None\n\n            occ_idx = 0\n            for i in range(track_scores.shape[0]):\n                if track_scores[i] < 0.25:\n                    continue\n                if occ_map is not None and track_labels[i] in self.veh_id_list:\n                    occ_map_cur = occ_map[occ_idx, :, ::-1]\n                    occ_idx += 1\n                else:\n                    occ_map_cur = None\n                if track_ids is not None:\n                    if i < len(track_ids):\n                        track_id = track_ids[i]\n                    else:\n                        track_id = 0\n                else:\n                    track_id = None\n                # if track_labels[i] not in [0, 1, 2, 3, 4, 6, 7]:\n                #     continue\n                predicted_agent_list.append(\n                    AgentPredictionData(\n                        track_scores[i],\n                        track_labels[i],\n                        track_centers[i],\n                        track_dims[i],\n                        track_yaw[i],\n                        track_velocity[i],\n                        trajs[i],\n                        traj_scores[i],\n                        pred_track_id=track_id,\n                        pred_occ_map=occ_map_cur,\n                        past_pred_traj=None\n                    )\n                )\n\n            if self.with_map:\n                map_thres = 0.7\n                score_list = outputs[k]['pts_bbox']['score_list'].cpu().numpy().transpose([\n                    1, 2, 0])\n                predicted_map_seg = outputs[k]['pts_bbox']['lane_score'].cpu().numpy().transpose([\n                    1, 2, 0])  # H, W, C\n                predicted_map_seg[..., -1] = score_list[..., -1]\n                predicted_map_seg = (predicted_map_seg > map_thres) * 1.0\n                predicted_map_seg = predicted_map_seg[::-1, :, :]\n            else:\n                predicted_map_seg = None\n\n            if self.with_planning:\n                # detection\n                bboxes = outputs[k]['sdc_boxes_3d']\n                scores = outputs[k]['sdc_scores_3d']\n                labels = 0\n\n                track_scores = scores.cpu().detach().numpy()\n                track_labels = labels\n                track_boxes = bboxes.tensor.cpu().detach().numpy()\n\n                track_centers = bboxes.gravity_center.cpu().detach().numpy()\n                track_dims = bboxes.dims.cpu().detach().numpy()\n                track_yaw = bboxes.yaw.cpu().detach().numpy()\n                track_velocity = bboxes.tensor.cpu().detach().numpy()[:, -2:]\n\n                if self.show_command:\n                    command = outputs[k]['command'][0].cpu().detach().numpy()\n                else:\n                    command = None\n                planning_agent = AgentPredictionData(\n                    track_scores[0],\n                    track_labels,\n                    track_centers[0],\n                    track_dims[0],\n                    track_yaw[0],\n                    track_velocity[0],\n                    outputs[k]['planning_traj'][0].cpu().detach().numpy(),\n                    1,\n                    pred_track_id=-1,\n                    pred_occ_map=None,\n                    past_pred_traj=None,\n                    is_sdc=True,\n                    command=command,\n                )\n                predicted_agent_list.append(planning_agent)\n            else:\n                planning_agent = None\n            prediction_dict[token] = dict(predicted_agent_list=predicted_agent_list,\n                                          predicted_map_seg=predicted_map_seg,\n                                          predicted_planning=planning_agent)\n        return prediction_dict\n\n    def visualize_bev(self, sample_token, out_filename, t=None):\n        self.bev_render.reset_canvas(dx=1, dy=1)\n        self.bev_render.set_plot_cfg()\n\n        if self.show_lidar:\n            self.bev_render.show_lidar_data(sample_token, self.nusc)\n        if self.bev_render.show_gt_boxes:\n            self.bev_render.render_anno_data(\n                sample_token, self.nusc, self.predict_helper)\n        if self.with_pred_box:\n            self.bev_render.render_pred_box_data(\n                self.predictions[sample_token]['predicted_agent_list'])\n        if self.with_pred_traj:\n            self.bev_render.render_pred_traj(\n                self.predictions[sample_token]['predicted_agent_list'])\n        if self.with_map:\n            self.bev_render.render_pred_map_data(\n                self.predictions[sample_token]['predicted_map_seg'])\n        if self.with_occ_map:\n            self.bev_render.render_occ_map_data(\n                self.predictions[sample_token]['predicted_agent_list'])\n        if self.with_planning:\n            self.bev_render.render_pred_box_data(\n                [self.predictions[sample_token]['predicted_planning']])\n            self.bev_render.render_planning_data(\n                self.predictions[sample_token]['predicted_planning'], show_command=self.show_command)\n        if self.show_hd_map:\n            self.bev_render.render_hd_map(\n                self.nusc, self.nusc_maps, sample_token)\n        if self.show_sdc_car:\n            self.bev_render.render_sdc_car()\n        if self.show_legend:\n            self.bev_render.render_legend()\n        self.bev_render.save_fig(out_filename + '.jpg')\n\n    def visualize_cam(self, sample_token, out_filename):\n        self.cam_render.reset_canvas(dx=2, dy=3, tight_layout=True)\n        self.cam_render.render_image_data(sample_token, self.nusc)\n        self.cam_render.render_pred_track_bbox(\n            self.predictions[sample_token]['predicted_agent_list'], sample_token, self.nusc)\n        self.cam_render.render_pred_traj(\n            self.predictions[sample_token]['predicted_agent_list'], sample_token, self.nusc, render_sdc=self.with_planning)\n        self.cam_render.save_fig(out_filename + '_cam.jpg')\n\n    def combine(self, out_filename):\n        # pass\n        bev_image = cv2.imread(out_filename + '.jpg')\n        cam_image = cv2.imread(out_filename + '_cam.jpg')\n        merge_image = cv2.hconcat([cam_image, bev_image])\n        cv2.imwrite(out_filename + '.jpg', merge_image)\n        os.remove(out_filename + '_cam.jpg')\n\n    def to_video(self, folder_path, out_path, fps=4, downsample=1):\n        imgs_path = glob.glob(os.path.join(folder_path, '*.jpg'))\n        imgs_path = sorted(imgs_path)\n        img_array = []\n        for img_path in imgs_path:\n            img = cv2.imread(img_path)\n            height, width, channel = img.shape\n            img = cv2.resize(img, (width//downsample, height //\n                             downsample), interpolation=cv2.INTER_AREA)\n            height, width, channel = img.shape\n            size = (width, height)\n            img_array.append(img)\n        out = cv2.VideoWriter(\n            out_path, cv2.VideoWriter_fourcc(*'DIVX'), fps, size)\n        for i in range(len(img_array)):\n            out.write(img_array[i])\n        out.release()\n\ndef main(args):\n    render_cfg = dict(\n        with_occ_map=False,\n        with_map=False,\n        with_planning=True,\n        with_pred_box=True,\n        with_pred_traj=True,\n        show_gt_boxes=False,\n        show_lidar=False,\n        show_command=True,\n        show_hd_map=False,\n        show_sdc_car=True,\n        show_legend=True,\n        show_sdc_traj=False\n    )\n\n    viser = Visualizer(version='v1.0-mini', predroot=args.predroot, dataroot='data/nuscenes', **render_cfg)\n\n    if not os.path.exists(args.out_folder):\n        os.makedirs(args.out_folder)\n\n    val_splits = splits.val\n\n    scene_token_to_name = dict()\n    for i in range(len(viser.nusc.scene)):\n        scene_token_to_name[viser.nusc.scene[i]['token']] = viser.nusc.scene[i]['name']\n\n    for i in range(len(viser.nusc.sample)):\n        sample_token = viser.nusc.sample[i]['token']\n        scene_token = viser.nusc.sample[i]['scene_token']\n\n        if scene_token_to_name[scene_token] not in val_splits:\n            continue\n\n        if sample_token not in viser.token_set:\n            print(i, sample_token, 'not in prediction pkl!')\n            continue\n\n        viser.visualize_bev(sample_token, os.path.join(args.out_folder, str(i).zfill(3)))\n\n        if args.project_to_cam:\n            viser.visualize_cam(sample_token, os.path.join(args.out_folder, str(i).zfill(3)))\n            viser.combine(os.path.join(args.out_folder, str(i).zfill(3)))\n\n    viser.to_video(args.out_folder, args.demo_video, fps=4, downsample=2)\n\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--predroot', default='/mnt/nas20/yihan01.hu/tmp/results.pkl', help='Path to results.pkl')\n    parser.add_argument('--out_folder', default='/mnt/nas20/yihan01.hu/tmp/viz/demo_test/', help='Output folder path')\n    parser.add_argument('--demo_video', default='mini_val_final.avi', help='Demo video name')\n    parser.add_argument('--project_to_cam', default=True, help='Project to cam (default: True)')\n    args = parser.parse_args()\n    main(args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/analysis_tools/visualize/utils.py",
    "content": "import numpy as np\nfrom nuscenes.utils.data_classes import LidarPointCloud, Box\nfrom pyquaternion import Quaternion\n\n\ncolor_mapping = np.asarray([\n    [0, 0, 0],\n    [255, 179, 0],\n    [128, 62, 117],\n    [255, 104, 0],\n    [166, 189, 215],\n    [193, 0, 32],\n    [206, 162, 98],\n    [129, 112, 102],\n    [0, 125, 52],\n    [246, 118, 142],\n    [0, 83, 138],\n    [255, 122, 92],\n    [83, 55, 122],\n    [255, 142, 0],\n    [179, 40, 81],\n    [244, 200, 0],\n    [127, 24, 13],\n    [147, 170, 0],\n    [89, 51, 21],\n    [241, 58, 19],\n    [35, 44, 22],\n    [112, 224, 255],\n    [70, 184, 160],\n    [153, 0, 255],\n    [71, 255, 0],\n    [255, 0, 163],\n    [255, 204, 0],\n    [0, 255, 235],\n    [255, 0, 235],\n    [255, 0, 122],\n    [255, 245, 0],\n    [10, 190, 212],\n    [214, 255, 0],\n    [0, 204, 255],\n    [20, 0, 255],\n    [255, 255, 0],\n    [0, 153, 255],\n    [0, 255, 204],\n    [41, 255, 0],\n    [173, 0, 255],\n    [0, 245, 255],\n    [71, 0, 255],\n    [0, 255, 184],\n    [0, 92, 255],\n    [184, 255, 0],\n    [255, 214, 0],\n    [25, 194, 194],\n    [92, 0, 255],\n    [220, 220, 220],\n    [255, 9, 92],\n    [112, 9, 255],\n    [8, 255, 214],\n    [255, 184, 6],\n    [10, 255, 71],\n    [255, 41, 10],\n    [7, 255, 255],\n    [224, 255, 8],\n    [102, 8, 255],\n    [255, 61, 6],\n    [255, 194, 7],\n    [0, 255, 20],\n    [255, 8, 41],\n    [255, 5, 153],\n    [6, 51, 255],\n    [235, 12, 255],\n    [160, 150, 20],\n    [0, 163, 255],\n    [140, 140, 140],\n    [250, 10, 15],\n    [20, 255, 0],\n])/255\n\n\nclass AgentPredictionData:\n    \"\"\"\n    Agent data class, includes bbox, traj, and occflow\n    \"\"\"\n\n    def __init__(self,\n                 pred_score,\n                 pred_label,\n                 pred_center,\n                 pred_dim,\n                 pred_yaw,\n                 pred_vel,\n                 pred_traj,\n                 pred_traj_score,\n                 pred_track_id=None,\n                 pred_occ_map=None,\n                 is_sdc=False,\n                 past_pred_traj=None,\n                 command=None,\n                 attn_mask=None,\n                 ):\n        self.pred_score = pred_score\n        self.pred_label = pred_label\n        self.pred_center = pred_center\n        self.pred_dim = pred_dim\n        self.pred_yaw = -pred_yaw-np.pi/2\n        self.pred_vel = pred_vel\n        self.pred_traj = pred_traj\n        self.pred_traj_score = pred_traj_score\n        self.pred_track_id = pred_track_id\n        self.pred_occ_map = pred_occ_map\n        if self.pred_traj is not None:\n            if isinstance(self.pred_traj_score, int):\n                self.pred_traj_max = self.pred_traj\n            else:\n                self.pred_traj_max = self.pred_traj[self.pred_traj_score.argmax(\n                )]\n        else:\n            self.pred_traj_max = None\n        self.nusc_box = Box(\n            center=pred_center,\n            size=pred_dim,\n            orientation=Quaternion(axis=[0, 0, 1], radians=self.pred_yaw),\n            label=pred_label,\n            score=pred_score\n        )\n        if is_sdc:\n            self.pred_center = [0, 0, -1.2+1.56/2]\n        self.is_sdc = is_sdc\n        self.past_pred_traj = past_pred_traj\n        self.command = command\n        self.attn_mask = attn_mask\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/_base_/datasets/nus-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-50, -50, -5, 50, 50, 3]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\ndataset_type = 'NuScenesDataset'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=4,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/_base_/default_runtime.py",
    "content": "checkpoint_config = dict(interval=1)\n# yapf:disable push\n# By default we use textlogger hook and tensorboard\n# For more loggers see\n# https://mmcv.readthedocs.io/en/latest/api.html#mmcv.runner.LoggerHook\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# yapf:enable\ndist_params = dict(backend='nccl')\nlog_level = 'INFO'\nwork_dir = None\nload_from = None\nresume_from = None\nworkflow = [('train', 1)]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/stage1_track_map/base_track_map.py",
    "content": "_base_ = [\"../_base_/datasets/nus-3d.py\",\n          \"../_base_/default_runtime.py\"]\n\n# Update-2023-06-12: \n# [Enhance] Update some freezing args of UniAD \n# [Bugfix] Reproduce the from-scratch results of stage1\n# 1. Remove loss_past_traj in stage1 training\n# 2. Unfreeze neck and BN\n# --> Reproduced tracking result: AMOTA 0.393\n\n\n# Unfreeze neck and BN, the from-scratch results of stage1 could be reproduced\nplugin = True\n# plugin_dir = \"projects/mmdet3d_plugin/\"\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\npatch_size = [102.4, 102.4]\nimg_norm_cfg = dict(mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\n\ninput_modality = dict(\n    use_lidar=False, use_camera=True, use_radar=False, use_map=False, use_external=True\n)\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\n_feed_dim_ = _ffn_dim_\n_dim_half_ = _pos_dim_\ncanvas_size = (bev_h_, bev_w_)\n\n# NOTE: You can change queue_length from 5 to 3 to save GPU memory, but at risk of performance drop.\nqueue_length = 3  # each sequence contains `queue_length` frames.\n\n### traj prediction args ###\npredict_steps = 12\npredict_modes = 6\nfut_steps = 4\npast_steps = 4\nuse_nonlinear_optimizer = True\n\n## occflow setting\t\nocc_n_future = 4\t\nocc_n_future_plan = 6\nocc_n_future_max = max([occ_n_future, occ_n_future_plan])\t\n\n### planning ###\nplanning_steps = 6\nuse_col_optim = True\n\n### Occ args ### \noccflow_grid_conf = {\n    'xbound': [-50.0, 50.0, 0.5],\n    'ybound': [-50.0, 50.0, 0.5],\n    'zbound': [-10.0, 10.0, 20.0],\n}\n\n# Other settings\ntrain_gt_iou_threshold=0.3\n\nmodel = dict(\n    type=\"UniAD\",\n    gt_iou_threshold=train_gt_iou_threshold,\n    queue_length=queue_length,\n    use_grid_mask=True,\n    video_test_mode=True,\n    num_query=900,\n    num_classes=10,\n    pc_range=point_cloud_range,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=101,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=4,\n        norm_cfg=dict(type=\"BN2d\", requires_grad=False),\n        norm_eval=True,\n        style=\"caffe\",\n        dcn=dict(\n            type=\"DCNv2\", deform_groups=1, fallback_on_stride=False\n        ),  # original DCNv2 will print log when perform load_state_dict\n        stage_with_dcn=(False, False, True, True),\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs=\"on_output\",\n        num_outs=4,\n        relu_before_extra_convs=True,\n    ),\n    freeze_img_backbone=True,\n    freeze_img_neck=False,\n    freeze_bn=False,\n    score_thresh=0.4,\n    filter_score_thresh=0.35,\n    qim_args=dict(\n        qim_type=\"QIMBase\",\n        merger_dropout=0,\n        update_query_pos=True,\n        fp_ratio=0.3,\n        random_drop=0.1,\n    ),  # hyper-param for query dropping mentioned in MOTR\n    mem_args=dict(\n        memory_bank_type=\"MemoryBank\",\n        memory_bank_score_thresh=0.0,\n        memory_bank_len=4,\n    ),\n    loss_cfg=dict(\n        type=\"ClipMatcher\",\n        num_classes=10,\n        weight_dict=None,\n        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n        assigner=dict(\n            type=\"HungarianAssigner3DTrack\",\n            cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n            reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n            pc_range=point_cloud_range,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_past_traj_weight=0.0,\n    ),  # loss cfg for tracking\n    pts_bbox_head=dict(\n        type=\"BEVFormerTrackHead\",\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        transformer=dict(\n            type=\"UniADPerceptionTransformer\",\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type=\"BEVFormerEncoder\",\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type=\"BEVFormerLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"TemporalSelfAttention\", embed_dims=_dim_, num_levels=1\n                        ),\n                        dict(\n                            type=\"SpatialCrossAttention\",\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type=\"MSDeformableAttention3D\",\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_,\n                            ),\n                            embed_dims=_dim_,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n            decoder=dict(\n                type=\"DetectionTransformerDecoder\",\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type=\"DetrTransformerDecoderLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"MultiheadAttention\",\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1,\n                        ),\n                        dict(\n                            type=\"CustomMSDeformableAttention\",\n                            embed_dims=_dim_,\n                            num_levels=1,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n        ),\n        bbox_coder=dict(\n            type=\"NMSFreeCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10,\n        ),\n        positional_encoding=dict(\n            type=\"LearnedPositionalEncoding\",\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_iou=dict(type=\"GIoULoss\", loss_weight=0.0),\n    ),\n    seg_head=dict(\n        type='PansegformerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        canvas_size=canvas_size,\n        pc_range=point_cloud_range,\n        num_query=300,\n        num_classes=4,\n        num_things_classes=3,\n        num_stuff_classes=1,\n        in_channels=2048,\n        sync_cls_avg_factor=True,\n        as_two_stage=False,\n        with_box_refine=True,\n        transformer=dict(\n            type='SegDeformableTransformer',\n            encoder=dict(\n                type='DetrTransformerEncoder',\n                num_layers=6,\n                transformerlayers=dict(\n                    type='BaseTransformerLayer',\n                    attn_cfgs=dict(\n                        type='MultiScaleDeformableAttention',\n                        embed_dims=_dim_,\n                        num_levels=_num_levels_,\n                         ),\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'ffn', 'norm'))),\n            decoder=dict(\n                type='DeformableDetrTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='MultiScaleDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=_num_levels_,\n                        )\n                    ],\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')\n                ),\n            ),\n        ),\n        positional_encoding=dict(\n            type='SinePositionalEncoding',\n            num_feats=_dim_half_,\n            normalize=True,\n            offset=-0.5),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n        loss_mask=dict(type='DiceLoss', loss_weight=2.0),\n        thing_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=4),\n        stuff_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=6,self_attn=True),\n        train_cfg=dict(\n            assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                ),\n            assigner_with_mask=dict(\n                type='HungarianAssigner_multi_info',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                mask_cost=dict(type='DiceCost', weight=2.0),\n                ),\n            sampler =dict(type='PseudoSampler'),\n            sampler_with_mask =dict(type='PseudoSampler_segformer'),\n        ),\n    ),\n \n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                iou_cost=dict(\n                    type=\"IoUCost\", weight=0.0\n                ),  # Fake cost. This is just to make it compatible with DETR head.\n                pc_range=point_cloud_range,\n            ),\n        )\n    ),\n)\ndataset_type = \"NuScenesE2EDataset\"\ndata_root = \"data/nuscenes/\"\ninfo_root = \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"nuscenes_infos_temporal_train.pkl\"\nann_file_val=info_root + f\"nuscenes_infos_temporal_val.pkl\"\nann_file_test=info_root + f\"nuscenes_infos_temporal_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFilesInCeph\", to_float32=True, file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(\n        type=\"LoadAnnotations3D_E2E\",\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_attr_label=False,\n\n        with_future_anns=True,  # occ_flow gt\n        with_ins_inds_3d=True,  # ins_inds \n        ins_inds_add_1=True,    # ins_inds start from 1\n    ),\n\n    dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n                                    filter_invisible=False),  # NOTE: Currently vis_token is not in pkl \n\n    dict(type=\"ObjectRangeFilterTrack\", point_cloud_range=point_cloud_range),\n    dict(type=\"ObjectNameFilterTrack\", classes=class_names),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type=\"DefaultFormatBundle3D\", class_names=class_names),\n    dict(\n        type=\"CustomCollect3D\",\n        keys=[\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            \"gt_inds\",\n            \"img\",\n            \"timestamp\",\n            \"l2g_r_mat\",\n            \"l2g_t\",\n            \"gt_fut_traj\",\n            \"gt_fut_traj_mask\",\n            \"gt_past_traj\",\n            \"gt_past_traj_mask\",\n            \"gt_sdc_bbox\",\n            \"gt_sdc_label\",\n            \"gt_sdc_fut_traj\",\n            \"gt_sdc_fut_traj_mask\",\n            \"gt_lane_labels\",\n            \"gt_lane_bboxes\",\n            \"gt_lane_masks\",\n             # Occ gt\n            # \"gt_segmentation\",\n            # \"gt_instance\", \n            # \"gt_centerness\", \n            # \"gt_offset\", \n            # \"gt_flow\",\n            # \"gt_backward_flow\",\n            # \"gt_occ_has_invalid_frame\",\n            # \"gt_occ_img_is_valid\",\n            # # gt future bbox for plan\t\n            # \"gt_future_boxes\",\t\n            # \"gt_future_labels\",\t\n            # # planning\t\n            # \"sdc_planning\",\t\n            # \"sdc_planning_mask\",\t\n            # \"command\",\n        ],\n    ),\n]\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type='LoadAnnotations3D_E2E', \n         with_bbox_3d=False,\n         with_label_3d=False, \n         with_attr_label=False,\n\n         with_future_anns=True,\n         with_ins_inds_3d=False,\n         ins_inds_add_1=True, # ins_inds start from 1\n         ),\n    dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n                                       filter_invisible=False),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"gt_lane_labels\",\n                                            \"gt_lane_bboxes\",\n                                            \"gt_lane_masks\",\n                                            \"gt_segmentation\",\n                                            \"gt_instance\", \n                                            \"gt_centerness\", \n                                            \"gt_offset\", \n                                            \"gt_flow\",\n                                            \"gt_backward_flow\",\n                                            \"gt_occ_has_invalid_frame\",\n                                            \"gt_occ_img_is_valid\",\n                                             # planning\t\n                                            \"sdc_planning\",\t\n                                            \"sdc_planning_mask\",\t\n                                            \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=1,\n    train=dict(\n        type=dataset_type,\n        file_client_args=file_client_args,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        patch_size=patch_size,\n        canvas_size=canvas_size,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        predict_steps=predict_steps,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        occ_receptive_field=3,\n        occ_n_future=occ_n_future_max,\n        occ_filter_invalid_sample=False,\n\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d=\"LiDAR\",\n    ),\n    val=dict(\n        type=dataset_type,\n        file_client_args=file_client_args,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        patch_size=patch_size,\n        canvas_size=canvas_size,\n        bev_size=(bev_h_, bev_w_),\n        predict_steps=predict_steps,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        eval_mod=['det', 'track', 'map'],\n\n        occ_receptive_field=3,\n        occ_n_future=occ_n_future_max,\n        occ_filter_invalid_sample=False,\n    ),\n    test=dict(\n        type=dataset_type,\n        file_client_args=file_client_args,\n        data_root=data_root,\n        test_mode=True,\n        ann_file=ann_file_test,\n        pipeline=test_pipeline,\n        patch_size=patch_size,\n        canvas_size=canvas_size,\n        bev_size=(bev_h_, bev_w_),\n        predict_steps=predict_steps,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        occ_n_future=occ_n_future_max,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        classes=class_names,\n        modality=input_modality,\n        eval_mod=['det', 'map', 'track'],\n    ),\n    shuffler_sampler=dict(type=\"DistributedGroupSampler\"),\n    nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n)\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n    weight_decay=0.01,\n)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\ntotal_epochs = 6\nevaluation = dict(interval=6, pipeline=test_pipeline)\nrunner = dict(type=\"EpochBasedRunner\", max_epochs=total_epochs)\nlog_config = dict(\n    interval=1, hooks=[dict(type=\"TextLoggerHook\"), dict(type=\"TensorboardLoggerHook\")]\n)\ncheckpoint_config = dict(interval=1)\nload_from = \"ckpts/bevformer_r101_dcn_24ep.pth\"\n\nfind_unused_parameters = True"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/stage1_track_map/base_track_map_b2d.py",
    "content": "_base_ = [\"../_base_/datasets/nus-3d.py\",\n          \"../_base_/default_runtime.py\"]\n\n# Update-2023-06-12: \n# [Enhance] Update some freezing args of UniAD \n# [Bugfix] Reproduce the from-scratch results of stage1\n# 1. Remove loss_past_traj in stage1 training\n# 2. Unfreeze neck and BN\n# --> Reproduced tracking result: AMOTA 0.393\n\n\n# Unfreeze neck and BN, the from-scratch results of stage1 could be reproduced\nplugin = True\n# plugin_dir = \"projects/mmdet3d_plugin/\"\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\npatch_size = [102.4, 102.4]\nimg_norm_cfg = dict(mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n# For nuScenes we usually do 10-class detection\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\n\n\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\n\ninput_modality = dict(\n    use_lidar=False, use_camera=True, use_radar=False, use_map=False, use_external=True\n)\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\n_feed_dim_ = _ffn_dim_\n_dim_half_ = _pos_dim_\ncanvas_size = (bev_h_, bev_w_)\n\n# NOTE: You can change queue_length from 5 to 3 to save GPU memory, but at risk of performance drop.\nqueue_length = 5  # each sequence contains `queue_length` frames.\n\n### traj prediction args ###\npredict_steps = 12\npredict_modes = 6\nfut_steps = 4\npast_steps = 4\nuse_nonlinear_optimizer = True\n\n## occflow setting\t\nocc_n_future = 4\t\nocc_n_future_plan = 6\nocc_n_future_max = max([occ_n_future, occ_n_future_plan])\t\n\n### planning ###\nplanning_steps = 6\nuse_col_optim = True\n\n### Occ args ### \noccflow_grid_conf = {\n    'xbound': [-50.0, 50.0, 0.5],\n    'ybound': [-50.0, 50.0, 0.5],\n    'zbound': [-10.0, 10.0, 20.0],\n}\n\n# Other settings\ntrain_gt_iou_threshold=0.3\n\nmodel = dict(\n    type=\"UniAD\",\n    gt_iou_threshold=train_gt_iou_threshold,\n    queue_length=queue_length,\n    use_grid_mask=True,\n    video_test_mode=True,\n    num_query=900,\n    num_classes=len(class_names),\n    pc_range=point_cloud_range,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=101,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=4,\n        norm_cfg=dict(type=\"BN2d\", requires_grad=False),\n        norm_eval=True,\n        style=\"caffe\",\n        dcn=dict(\n            type=\"DCNv2\", deform_groups=1, fallback_on_stride=False\n        ),  # original DCNv2 will print log when perform load_state_dict\n        stage_with_dcn=(False, False, True, True),\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs=\"on_output\",\n        num_outs=4,\n        relu_before_extra_convs=True,\n    ),\n    freeze_img_backbone=True,\n    freeze_img_neck=False,\n    freeze_bn=False,\n    score_thresh=0.4,\n    filter_score_thresh=0.35,\n    qim_args=dict(\n        qim_type=\"QIMBase\",\n        merger_dropout=0,\n        update_query_pos=True,\n        fp_ratio=0.3,\n        random_drop=0.1,\n    ),  # hyper-param for query dropping mentioned in MOTR\n    mem_args=dict(\n        memory_bank_type=\"MemoryBank\",\n        memory_bank_score_thresh=0.0,\n        memory_bank_len=4,\n    ),\n    loss_cfg=dict(\n        type=\"ClipMatcher\",\n        num_classes=len(class_names),\n        weight_dict=None,\n        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n        assigner=dict(\n            type=\"HungarianAssigner3DTrack\",\n            cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n            reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n            pc_range=point_cloud_range,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_past_traj_weight=0.0,\n    ),  # loss cfg for tracking\n    pts_bbox_head=dict(\n        type=\"BEVFormerTrackHead\",\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=len(class_names),\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        transformer=dict(\n            type=\"UniADPerceptionTransformer\",\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type=\"BEVFormerEncoder\",\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type=\"BEVFormerLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"TemporalSelfAttention\", embed_dims=_dim_, num_levels=1\n                        ),\n                        dict(\n                            type=\"SpatialCrossAttention\",\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type=\"MSDeformableAttention3D\",\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_,\n                            ),\n                            embed_dims=_dim_,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n            decoder=dict(\n                type=\"DetectionTransformerDecoder\",\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type=\"DetrTransformerDecoderLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"MultiheadAttention\",\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0,\n                        ),\n                        dict(\n                            type=\"CustomMSDeformableAttention\",\n                            embed_dims=_dim_,\n                            num_levels=1,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n        ),\n        bbox_coder=dict(\n            type=\"NMSFreeCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=len(class_names),\n        ),\n        positional_encoding=dict(\n            type=\"LearnedPositionalEncoding\",\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_iou=dict(type=\"GIoULoss\", loss_weight=0.0),\n    ),\n    seg_head=dict(\n        type='PansegformerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        canvas_size=canvas_size,\n        pc_range=point_cloud_range,\n        num_query=300,\n        num_classes=6,\n        num_things_classes=6,\n        num_stuff_classes=0,\n        in_channels=2048,\n        sync_cls_avg_factor=True,\n        as_two_stage=False,\n        with_box_refine=True,\n        transformer=dict(\n            type='SegDeformableTransformer',\n            encoder=dict(\n                type='DetrTransformerEncoder',\n                num_layers=6,\n                transformerlayers=dict(\n                    type='BaseTransformerLayer',\n                    attn_cfgs=dict(\n                        type='MultiScaleDeformableAttention',\n                        embed_dims=_dim_,\n                        num_levels=_num_levels_,\n                         ),\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'ffn', 'norm'))),\n            decoder=dict(\n                type='DeformableDetrTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                        dict(\n                            type='MultiScaleDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=_num_levels_,\n                        )\n                    ],\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')\n                ),\n            ),\n        ),\n        positional_encoding=dict(\n            type='SinePositionalEncoding',\n            num_feats=_dim_half_,\n            normalize=True,\n            offset=-0.5),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n        loss_mask=dict(type='DiceLoss', loss_weight=2.0),\n        thing_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=4),\n        stuff_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=6,self_attn=True),\n        train_cfg=dict(\n            assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                ),\n            assigner_with_mask=dict(\n                type='HungarianAssigner_multi_info',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                mask_cost=dict(type='DiceCost', weight=2.0),\n                ),\n            sampler =dict(type='PseudoSampler'),\n            sampler_with_mask =dict(type='PseudoSampler_segformer'),\n        ),\n    ),\n \n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                iou_cost=dict(\n                    type=\"IoUCost\", weight=0.0\n                ),  # Fake cost. This is just to make it compatible with DETR head.\n                pc_range=point_cloud_range,\n            ),\n        )\n    ),\n)\ndataset_type = \"B2D_E2E_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFilesInCeph\", to_float32=True, file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(\n        type=\"LoadAnnotations3D_E2E\",\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_attr_label=False,\n        with_vis_token=False,\n        with_future_anns=False,  # occ_flow gt\n        with_ins_inds_3d=True,  # ins_inds \n        ins_inds_add_1=True,    # ins_inds start from 1\n    ),\n\n    # dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n    #                                 filter_invisible=False),  # NOTE: Currently vis_token is not in pkl \n\n    dict(type=\"ObjectRangeFilterTrack\", point_cloud_range=point_cloud_range),\n    dict(type=\"ObjectNameFilterTrack\", classes=class_names),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type=\"DefaultFormatBundle3D\", class_names=class_names),\n    dict(\n        type=\"CustomCollect3D\",\n        keys=[\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            \"gt_inds\",\n            \"img\",\n            \"timestamp\",\n            \"l2g_r_mat\",\n            \"l2g_t\",\n            \"gt_fut_traj\",\n            \"gt_fut_traj_mask\",\n            \"gt_past_traj\",\n            \"gt_past_traj_mask\",\n            \"gt_sdc_bbox\",\n            \"gt_sdc_label\",\n            \"gt_sdc_fut_traj\",\n            \"gt_sdc_fut_traj_mask\",\n            \"gt_lane_labels\",\n            \"gt_lane_bboxes\",\n            \"gt_lane_masks\",\n             # Occ gt\n            # \"gt_segmentation\",\n            # \"gt_instance\", \n            # \"gt_centerness\", \n            # \"gt_offset\", \n            # \"gt_flow\",\n            # \"gt_backward_flow\",\n            # \"gt_occ_has_invalid_frame\",\n            # \"gt_occ_img_is_valid\",\n            # # gt future bbox for plan\t\n            # \"gt_future_boxes\",\t\n            # \"gt_future_labels\",\t\n            # # planning\t\n            # \"sdc_planning\",\t\n            # \"sdc_planning_mask\",\t\n            # \"command\",\n        ],\n    ),\n]\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type='LoadAnnotations3D_E2E', \n         with_bbox_3d=False,\n         with_label_3d=False, \n         with_attr_label=False,\n         with_vis_token=False,\n         with_future_anns=False,\n         with_ins_inds_3d=False,\n         ins_inds_add_1=True, # ins_inds start from 1\n         ),\n    # dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n    #                                    filter_invisible=False),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"gt_lane_labels\",\n                                            \"gt_lane_bboxes\",\n                                            \"gt_lane_masks\",\n                                            # \"gt_segmentation\",\n                                            # \"gt_instance\", \n                                            # \"gt_centerness\", \n                                            # \"gt_offset\", \n                                            # \"gt_flow\",\n                                            # \"gt_backward_flow\",\n                                            # \"gt_occ_has_invalid_frame\",\n                                            # \"gt_occ_img_is_valid\",\n                                            #  # planning\t\n                                            # \"sdc_planning\",\t\n                                            # \"sdc_planning_mask\",\t\n                                            # \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        modality=input_modality,\n        patch_size=patch_size,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        point_cloud_range=point_cloud_range,\n        box_type_3d=\"LiDAR\",\n    ),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    shuffler_sampler=dict(type=\"DistributedGroupSampler\"),\n    nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n)\n\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n    weight_decay=0.01,\n)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\ntotal_epochs = 1\nevaluation = dict(interval=1, pipeline=test_pipeline)\nrunner = dict(type=\"EpochBasedRunner\", max_epochs=total_epochs)\nlog_config = dict(\n    interval=50, hooks=[dict(type=\"TextLoggerHook\"), dict(type=\"TensorboardLoggerHook\")]\n)\ncheckpoint_config = dict(interval=3000, by_epoch=False)\n\nfind_unused_parameters = True\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/stage1_track_map/tiny_track_map_b2d.py",
    "content": "_base_ = [\"../_base_/datasets/nus-3d.py\",\n          \"../_base_/default_runtime.py\"]\n\n# Update-2023-06-12: \n# [Enhance] Update some freezing args of UniAD \n# [Bugfix] Reproduce the from-scratch results of stage1\n# 1. Remove loss_past_traj in stage1 training\n# 2. Unfreeze neck and BN\n# --> Reproduced tracking result: AMOTA 0.393\n\n\n# Unfreeze neck and BN, the from-scratch results of stage1 could be reproduced\nplugin = True\n# plugin_dir = \"projects/mmdet3d_plugin/\"\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\npatch_size = [102.4, 102.4]\nimg_norm_cfg = dict(mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n# For nuScenes we usually do 10-class detection\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\n\ninput_modality = dict(\n    use_lidar=False, use_camera=True, use_radar=False, use_map=False, use_external=True\n)\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 100\nbev_w_ = 100\n_feed_dim_ = _ffn_dim_\n_dim_half_ = _pos_dim_\ncanvas_size = (bev_h_*2, bev_w_*2)\n\n# NOTE: You can change queue_length from 5 to 3 to save GPU memory, but at risk of performance drop.\nqueue_length = 3  # each sequence contains `queue_length` frames.\n\n### traj prediction args ###\npredict_steps = 12\npredict_modes = 6\nfut_steps = 4\npast_steps = 4\nuse_nonlinear_optimizer = True\n\n## occflow setting\t\nocc_n_future = 4\t\nocc_n_future_plan = 6\nocc_n_future_max = max([occ_n_future, occ_n_future_plan])\t\n\n### planning ###\nplanning_steps = 6\nuse_col_optim = True\n\n### Occ args ### \noccflow_grid_conf = {\n    'xbound': [-50.0, 50.0, 0.5],\n    'ybound': [-50.0, 50.0, 0.5],\n    'zbound': [-10.0, 10.0, 20.0],\n}\n\n# Other settings\ntrain_gt_iou_threshold=0.3\n\nmodel = dict(\n    type=\"UniAD\",\n    gt_iou_threshold=train_gt_iou_threshold,\n    queue_length=queue_length,\n    use_grid_mask=True,\n    video_test_mode=True,\n    num_query=900,\n    num_classes=len(class_names),\n    pc_range=point_cloud_range,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1,2,3),\n        frozen_stages=4,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type=\"FPN\",\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs=\"on_output\",\n        num_outs=4,\n        relu_before_extra_convs=True,\n    ),\n    freeze_img_backbone=True,\n    freeze_img_neck=False,\n    freeze_bn=False,\n    score_thresh=0.4,\n    filter_score_thresh=0.35,\n    qim_args=dict(\n        qim_type=\"QIMBase\",\n        merger_dropout=0,\n        update_query_pos=True,\n        fp_ratio=0.3,\n        random_drop=0.1,\n    ),  # hyper-param for query dropping mentioned in MOTR\n    mem_args=dict(\n        memory_bank_type=\"MemoryBank\",\n        memory_bank_score_thresh=0.0,\n        memory_bank_len=4,\n    ),\n    loss_cfg=dict(\n        type=\"ClipMatcher\",\n        num_classes=len(class_names),\n        weight_dict=None,\n        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n        assigner=dict(\n            type=\"HungarianAssigner3DTrack\",\n            cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n            reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n            pc_range=point_cloud_range,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_past_traj_weight=0.0,\n    ),  # loss cfg for tracking\n    pts_bbox_head=dict(\n        type=\"BEVFormerTrackHead\",\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=len(class_names),\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        transformer=dict(\n            type=\"UniADPerceptionTransformer\",\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type=\"BEVFormerEncoder\",\n                num_layers=3,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type=\"BEVFormerLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"TemporalSelfAttention\", embed_dims=_dim_, num_levels=1\n                        ),\n                        dict(\n                            type=\"SpatialCrossAttention\",\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type=\"MSDeformableAttention3D\",\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_,\n                            ),\n                            embed_dims=_dim_,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n            decoder=dict(\n                type=\"DetectionTransformerDecoder\",\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type=\"DetrTransformerDecoderLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"MultiheadAttention\",\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0,\n                        ),\n                        dict(\n                            type=\"CustomMSDeformableAttention\",\n                            embed_dims=_dim_,\n                            num_levels=1,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n        ),\n        bbox_coder=dict(\n            type=\"NMSFreeCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=len(class_names),\n        ),\n        positional_encoding=dict(\n            type=\"LearnedPositionalEncoding\",\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_iou=dict(type=\"GIoULoss\", loss_weight=0.0),\n    ),\n    seg_head=dict(\n        type='PansegformerHead',\n        bev_h=bev_h_*2,\n        bev_w=bev_w_*2,\n        canvas_size=canvas_size,\n        pc_range=point_cloud_range,\n        num_query=300,\n        num_classes=6,\n        num_things_classes=6,\n        num_stuff_classes=0,\n        in_channels=2048,\n        sync_cls_avg_factor=True,\n        as_two_stage=False,\n        with_box_refine=True,\n        transformer=dict(\n            type='SegDeformableTransformer',\n            encoder=dict(\n                type='DetrTransformerEncoder',\n                num_layers=6,\n                transformerlayers=dict(\n                    type='BaseTransformerLayer',\n                    attn_cfgs=dict(\n                        type='MultiScaleDeformableAttention',\n                        embed_dims=_dim_,\n                        num_levels=_num_levels_,\n                         ),\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'ffn', 'norm'))),\n            decoder=dict(\n                type='DeformableDetrTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                        dict(\n                            type='MultiScaleDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=_num_levels_,\n                        )\n                    ],\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')\n                ),\n            ),\n        ),\n        positional_encoding=dict(\n            type='SinePositionalEncoding',\n            num_feats=_dim_half_,\n            normalize=True,\n            offset=-0.5),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n        loss_mask=dict(type='DiceLoss', loss_weight=2.0),\n        thing_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=4),\n        stuff_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=6,self_attn=True),\n        train_cfg=dict(\n            assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                ),\n            assigner_with_mask=dict(\n                type='HungarianAssigner_multi_info',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                mask_cost=dict(type='DiceCost', weight=2.0),\n                ),\n            sampler =dict(type='PseudoSampler'),\n            sampler_with_mask =dict(type='PseudoSampler_segformer'),\n        ),\n    ),\n \n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                iou_cost=dict(\n                    type=\"IoUCost\", weight=0.0\n                ),  # Fake cost. This is just to make it compatible with DETR head.\n                pc_range=point_cloud_range,\n            ),\n        )\n    ),\n)\ndataset_type = \"B2D_E2E_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFilesInCeph\", to_float32=True, file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(\n        type=\"LoadAnnotations3D_E2E\",\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_attr_label=False,\n\n        with_future_anns=False,  # occ_flow gt\n        with_ins_inds_3d=True,  # ins_inds \n        ins_inds_add_1=True,    # ins_inds start from 1\n    ),\n\n    # dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n    #                                 filter_invisible=False),  # NOTE: Currently vis_token is not in pkl \n\n    dict(type=\"ObjectRangeFilterTrack\", point_cloud_range=point_cloud_range),\n    dict(type=\"ObjectNameFilterTrack\", classes=class_names),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type=\"DefaultFormatBundle3D\", class_names=class_names),\n    dict(\n        type=\"CustomCollect3D\",\n        keys=[\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            \"gt_inds\",\n            \"img\",\n            \"timestamp\",\n            \"l2g_r_mat\",\n            \"l2g_t\",\n            \"gt_fut_traj\",\n            \"gt_fut_traj_mask\",\n            \"gt_past_traj\",\n            \"gt_past_traj_mask\",\n            \"gt_sdc_bbox\",\n            \"gt_sdc_label\",\n            \"gt_sdc_fut_traj\",\n            \"gt_sdc_fut_traj_mask\",\n            \"gt_lane_labels\",\n            \"gt_lane_bboxes\",\n            \"gt_lane_masks\",\n            #  Occ gt\n            # \"gt_segmentation\",\n            # \"gt_instance\", \n            # \"gt_centerness\", \n            # \"gt_offset\", \n            # \"gt_flow\",\n            # \"gt_backward_flow\",\n            # \"gt_occ_has_invalid_frame\",\n            # \"gt_occ_img_is_valid\",\n            # # gt future bbox for plan\t\n            # \"gt_future_boxes\",\t\n            # \"gt_future_labels\",\t\n            # # planning\t\n            # \"sdc_planning\",\t\n            # \"sdc_planning_mask\",\t\n            # \"command\",\n        ],\n    ),\n]\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type='LoadAnnotations3D_E2E', \n         with_bbox_3d=False,\n         with_label_3d=False, \n         with_attr_label=False,\n\n         with_future_anns=False,\n         with_ins_inds_3d=False,\n         ins_inds_add_1=True, # ins_inds start from 1\n         ),\n    # dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n    #                                    filter_invisible=False),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            # \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"gt_lane_labels\",\n                                            \"gt_lane_bboxes\",\n                                            \"gt_lane_masks\",\n                                            # \"gt_segmentation\",\n                                            # \"gt_instance\", \n                                            # \"gt_centerness\", \n                                            # \"gt_offset\", \n                                            # \"gt_flow\",\n                                            # \"gt_backward_flow\",\n                                            # \"gt_occ_has_invalid_frame\",\n                                            # \"gt_occ_img_is_valid\",\n                                            #  # planning\t\n                                            # \"sdc_planning\",\t\n                                            # \"sdc_planning_mask\",\t\n                                            # \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        modality=input_modality,\n        patch_size=patch_size,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        point_cloud_range=point_cloud_range,\n        box_type_3d=\"LiDAR\",\n    ),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    shuffler_sampler=dict(type=\"DistributedGroupSampler\"),\n    nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n)\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n    weight_decay=0.01,\n)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\ntotal_epochs = 1\nevaluation = dict(interval=1, pipeline=test_pipeline)\nrunner = dict(type=\"EpochBasedRunner\", max_epochs=total_epochs)\nlog_config = dict(\n    interval=1, hooks=[dict(type=\"TextLoggerHook\"), dict(type=\"TensorboardLoggerHook\")]\n)\ncheckpoint_config = dict(interval=3000, by_epoch=False)\n\nfind_unused_parameters = True"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/base_e2e.py",
    "content": "_base_ = [\"../_base_/datasets/nus-3d.py\",\n          \"../_base_/default_runtime.py\"]\n\n# Update-2023-06-12: \n# [Enhance] Update some freezing args of UniAD \nplugin = True\n# plugin_dir = \"projects/mmdet3d_plugin/\"\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\npatch_size = [102.4, 102.4]\nimg_norm_cfg = dict(mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nvehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\ngroup_id_list = [[0,1,2,3,4], [6,7], [8], [5,9]]\ninput_modality = dict(\n    use_lidar=False, use_camera=True, use_radar=False, use_map=False, use_external=True\n)\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\n_feed_dim_ = _ffn_dim_\n_dim_half_ = _pos_dim_\ncanvas_size = (bev_h_, bev_w_)\nqueue_length = 3  # each sequence contains `queue_length` frames.\n\n### traj prediction args ###\npredict_steps = 12\npredict_modes = 6\nfut_steps = 4\npast_steps = 4\nuse_nonlinear_optimizer = True\n\n## occflow setting\t\nocc_n_future = 4\t\nocc_n_future_plan = 6\t\nocc_n_future_max = max([occ_n_future, occ_n_future_plan])\t\n\n### planning ###\nplanning_steps = 6\nuse_col_optim = True\n\n### Occ args ### \noccflow_grid_conf = {\n    'xbound': [-50.0, 50.0, 0.5],\n    'ybound': [-50.0, 50.0, 0.5],\n    'zbound': [-10.0, 10.0, 20.0],\n}\n\n# Other settings\ntrain_gt_iou_threshold=0.3\n\nmodel = dict(\n    type=\"UniAD\",\n    gt_iou_threshold=train_gt_iou_threshold,\n    queue_length=queue_length,\n    use_grid_mask=True,\n    video_test_mode=True,\n    num_query=900,\n    num_classes=10,\n    vehicle_id_list=vehicle_id_list,\n    pc_range=point_cloud_range,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=101,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=4,\n        norm_cfg=dict(type=\"BN2d\", requires_grad=False),\n        norm_eval=True,\n        style=\"caffe\",\n        dcn=dict(\n            type=\"DCNv2\", deform_groups=1, fallback_on_stride=False\n        ),  # original DCNv2 will print log when perform load_state_dict\n        stage_with_dcn=(False, False, True, True),\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs=\"on_output\",\n        num_outs=4,\n        relu_before_extra_convs=True,\n    ),\n    freeze_img_backbone=True,\n    freeze_img_neck=True,\n    freeze_bn=True,\n    freeze_bev_encoder=True,\n    score_thresh=0.4,\n    filter_score_thresh=0.35,\n    qim_args=dict(\n        qim_type=\"QIMBase\",\n        merger_dropout=0,\n        update_query_pos=True,\n        fp_ratio=0.3,\n        random_drop=0.1,\n    ),  # hyper-param for query dropping mentioned in MOTR\n    mem_args=dict(\n        memory_bank_type=\"MemoryBank\",\n        memory_bank_score_thresh=0.0,\n        memory_bank_len=4,\n    ),\n    loss_cfg=dict(\n        type=\"ClipMatcher\",\n        num_classes=10,\n        weight_dict=None,\n        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n        assigner=dict(\n            type=\"HungarianAssigner3DTrack\",\n            cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n            reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n            pc_range=point_cloud_range,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n    ),  # loss cfg for tracking\n    pts_bbox_head=dict(\n        type=\"BEVFormerTrackHead\",\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=10,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        transformer=dict(\n            type=\"UniADPerceptionTransformer\",\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type=\"BEVFormerEncoder\",\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type=\"BEVFormerLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"TemporalSelfAttention\", embed_dims=_dim_, num_levels=1\n                        ),\n                        dict(\n                            type=\"SpatialCrossAttention\",\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type=\"MSDeformableAttention3D\",\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_,\n                            ),\n                            embed_dims=_dim_,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n            decoder=dict(\n                type=\"DetectionTransformerDecoder\",\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type=\"DetrTransformerDecoderLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"MultiheadAttention\",\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1,\n                        ),\n                        dict(\n                            type=\"CustomMSDeformableAttention\",\n                            embed_dims=_dim_,\n                            num_levels=1,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n        ),\n        bbox_coder=dict(\n            type=\"NMSFreeCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=10,\n        ),\n        positional_encoding=dict(\n            type=\"LearnedPositionalEncoding\",\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_iou=dict(type=\"GIoULoss\", loss_weight=0.0),\n    ),\n    seg_head=dict(\n        type='PansegformerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        canvas_size=canvas_size,\n        pc_range=point_cloud_range,\n        num_query=300,\n        num_classes=4,\n        num_things_classes=3,\n        num_stuff_classes=1,\n        in_channels=2048,\n        sync_cls_avg_factor=True,\n        as_two_stage=False,\n        with_box_refine=True,\n        transformer=dict(\n            type='SegDeformableTransformer',\n            encoder=dict(\n                type='DetrTransformerEncoder',\n                num_layers=6,\n                transformerlayers=dict(\n                    type='BaseTransformerLayer',\n                    attn_cfgs=dict(\n                        type='MultiScaleDeformableAttention',\n                        embed_dims=_dim_,\n                        num_levels=_num_levels_,\n                         ),\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'ffn', 'norm'))),\n            decoder=dict(\n                type='DeformableDetrTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='MultiScaleDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=_num_levels_,\n                        )\n                    ],\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')\n                ),\n            ),\n        ),\n        positional_encoding=dict(\n            type='SinePositionalEncoding',\n            num_feats=_dim_half_,\n            normalize=True,\n            offset=-0.5),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n        loss_mask=dict(type='DiceLoss', loss_weight=2.0),\n        thing_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=4),\n        stuff_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=6,self_attn=True),\n        train_cfg=dict(\n            assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                ),\n            assigner_with_mask=dict(\n                type='HungarianAssigner_multi_info',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                mask_cost=dict(type='DiceCost', weight=2.0),\n                ),\n            sampler =dict(type='PseudoSampler'),\n            sampler_with_mask =dict(type='PseudoSampler_segformer'),\n        ),\n    ),\n    occ_head=dict(\n        type='OccHead',\n\n        grid_conf=occflow_grid_conf,\n        ignore_index=255,\n\n        bev_proj_dim=256,\n        bev_proj_nlayers=4,\n\n        # Transformer\n        attn_mask_thresh=0.3,\n        transformer_decoder=dict(\n            type='DetrTransformerDecoder',\n            return_intermediate=True,\n            num_layers=5,\n            transformerlayers=dict(\n                type='DetrTransformerDecoderLayer',\n                attn_cfgs=dict(\n                    type='MultiheadAttention',\n                    embed_dims=256,\n                    num_heads=8,\n                    attn_drop=0.0,\n                    proj_drop=0.0,\n                    dropout_layer=None,\n                    batch_first=False),\n                ffn_cfgs=dict(\n                    embed_dims=256,\n                    feedforward_channels=2048,  # change to 512\n                    num_fcs=2,\n                    act_cfg=dict(type='ReLU', inplace=True),\n                    ffn_drop=0.0,\n                    dropout_layer=None,\n                    add_identity=True),\n                feedforward_channels=2048,\n                operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                 'ffn', 'norm')),\n            init_cfg=None),\n        # Query\n        query_dim=256,\n        query_mlp_layers=3,\n\n        aux_loss_weight=1.,\n        loss_mask=dict(\n            type='FieryBinarySegmentationLoss',\n            use_top_k=True,\n            top_k_ratio=0.25,\n            future_discount=0.95,\n            loss_weight=5.0,\n            ignore_index=255,\n        ),\n        loss_dice=dict(\n            type='DiceLossWithMasks',\n            use_sigmoid=True,\n            activate=True,\n            reduction='mean',\n            naive_dice=True,\n            eps=1.0,\n            ignore_index=255,\n            loss_weight=1.0),\n\n        \n        pan_eval=True,\n        test_seg_thresh=0.1,\n        test_with_track_score=True,\n    ),\n    motion_head=dict(\n        type='MotionHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=300,\n        num_classes=10,\n        predict_steps=predict_steps,\n        predict_modes=predict_modes,\n        embed_dims=_dim_,\n        loss_traj=dict(type='TrajLoss', \n            use_variance=True, \n            cls_loss_weight=0.5, \t\n            nll_loss_weight=0.5, \t\n            loss_weight_minade=0., \t\n            loss_weight_minfde=0.25),\n        num_cls_fcs=3,\n        pc_range=point_cloud_range,\n        group_id_list=group_id_list,\n        num_anchor=6,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        anchor_info_path='data/others/motion_anchor_infos_mode6.pkl',\n        transformerlayers=dict(\n            type='MotionTransformerDecoder',\n            pc_range=point_cloud_range,\n            embed_dims=_dim_,\n            num_layers=3,\n            transformerlayers=dict(\n                type='MotionTransformerAttentionLayer',\n                batch_first=True,\n                attn_cfgs=[\n                    dict(\n                        type='MotionDeformableAttention',\n                        num_steps=predict_steps,\n                        embed_dims=_dim_,\n                        num_levels=1,\n                        num_heads=8,\n                        num_points=4,\n                        sample_index=-1),\n                ],\n\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm')),\n        ),\n    ),\n    planning_head=dict(\n        type='PlanningHeadSingleMode',\n        embed_dims=256,\n        planning_steps=planning_steps,\n        loss_planning=dict(type='PlanningLoss'),\n        loss_collision=[dict(type='CollisionLoss', delta=0.0, weight=2.5),\n                        dict(type='CollisionLoss', delta=0.5, weight=1.0),\n                        dict(type='CollisionLoss', delta=1.0, weight=0.25)],\n        use_col_optim=use_col_optim,\n        planning_eval=True,\n        with_adapter=True,\n    ),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                iou_cost=dict(\n                    type=\"IoUCost\", weight=0.0\n                ),  # Fake cost. This is just to make it compatible with DETR head.\n                pc_range=point_cloud_range,\n            ),\n        )\n    ),\n)\ndataset_type = \"NuScenesE2EDataset\"\ndata_root = \"data/nuscenes/\"\ninfo_root = \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"nuscenes_infos_temporal_train.pkl\"\nann_file_val=info_root + f\"nuscenes_infos_temporal_val.pkl\"\nann_file_test=info_root + f\"nuscenes_infos_temporal_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFilesInCeph\", to_float32=True, file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(\n        type=\"LoadAnnotations3D_E2E\",\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_attr_label=False,\n\n        with_future_anns=True,  # occ_flow gt\n        with_ins_inds_3d=True,  # ins_inds \n        ins_inds_add_1=True,    # ins_inds start from 1\n    ),\n\n    dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n                                    filter_invisible=False),  # NOTE: Currently vis_token is not in pkl \n\n    dict(type=\"ObjectRangeFilterTrack\", point_cloud_range=point_cloud_range),\n    dict(type=\"ObjectNameFilterTrack\", classes=class_names),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type=\"DefaultFormatBundle3D\", class_names=class_names),\n    dict(\n        type=\"CustomCollect3D\",\n        keys=[\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            \"gt_inds\",\n            \"img\",\n            \"timestamp\",\n            \"l2g_r_mat\",\n            \"l2g_t\",\n            \"gt_fut_traj\",\n            \"gt_fut_traj_mask\",\n            \"gt_past_traj\",\n            \"gt_past_traj_mask\",\n            \"gt_sdc_bbox\",\n            \"gt_sdc_label\",\n            \"gt_sdc_fut_traj\",\n            \"gt_sdc_fut_traj_mask\",\n            \"gt_lane_labels\",\n            \"gt_lane_bboxes\",\n            \"gt_lane_masks\",\n             # Occ gt\n            \"gt_segmentation\",\n            \"gt_instance\", \n            \"gt_centerness\", \n            \"gt_offset\", \n            \"gt_flow\",\n            \"gt_backward_flow\",\n            \"gt_occ_has_invalid_frame\",\t\n            \"gt_occ_img_is_valid\",\t\n            # gt future bbox for plan\t\n            \"gt_future_boxes\",\t\n            \"gt_future_labels\",\t\n            # planning\t\n            \"sdc_planning\",\t\n            \"sdc_planning_mask\",\t\n            \"command\",\n        ],\n    ),\n]\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type='LoadAnnotations3D_E2E', \n         with_bbox_3d=False,\n         with_label_3d=False, \n         with_attr_label=False,\n\n         with_future_anns=True,\n         with_ins_inds_3d=False,\n         ins_inds_add_1=True, # ins_inds start from 1\n         ),\n    dict(type='GenerateOccFlowLabels', grid_conf=occflow_grid_conf, ignore_index=255, only_vehicle=True, \n                                       filter_invisible=False),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"gt_lane_labels\",\n                                            \"gt_lane_bboxes\",\n                                            \"gt_lane_masks\",\n                                            \"gt_segmentation\",\n                                            \"gt_instance\", \n                                            \"gt_centerness\", \n                                            \"gt_offset\", \n                                            \"gt_flow\",\n                                            \"gt_backward_flow\",\n                                            \"gt_occ_has_invalid_frame\",\t\n                                            \"gt_occ_img_is_valid\",\t\n                                            # planning\t\n                                            \"sdc_planning\",\t\n                                            \"sdc_planning_mask\",\t\n                                            \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=8,\n    train=dict(\n        type=dataset_type,\n        file_client_args=file_client_args,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        patch_size=patch_size,\n        canvas_size=canvas_size,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        predict_steps=predict_steps,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n\n        occ_receptive_field=3,\n        occ_n_future=occ_n_future_max,\n        occ_filter_invalid_sample=False,\n        \n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d=\"LiDAR\",\n    ),\n    val=dict(\n        type=dataset_type,\n        file_client_args=file_client_args,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        patch_size=patch_size,\n        canvas_size=canvas_size,\n        bev_size=(bev_h_, bev_w_),\n        predict_steps=predict_steps,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        eval_mod=['det', 'map', 'track','motion'],\n        \n\n        occ_receptive_field=3,\n        occ_n_future=occ_n_future_max,\n        occ_filter_invalid_sample=False,\n    ),\n    test=dict(\n        type=dataset_type,\n        file_client_args=file_client_args,\n        data_root=data_root,\n        test_mode=True,\n        ann_file=ann_file_test,\n        pipeline=test_pipeline,\n        patch_size=patch_size,\n        canvas_size=canvas_size,\n        bev_size=(bev_h_, bev_w_),\n        predict_steps=predict_steps,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        occ_n_future=occ_n_future_max,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        classes=class_names,\n        modality=input_modality,\n        eval_mod=['det', 'map', 'track','motion'],\n    ),\n    shuffler_sampler=dict(type=\"DistributedGroupSampler\"),\n    nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n)\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n    weight_decay=0.01,\n)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\ntotal_epochs = 2\nevaluation = dict(interval=1, pipeline=test_pipeline)\nrunner = dict(type=\"EpochBasedRunner\", max_epochs=total_epochs)\nlog_config = dict(\n    interval=10, hooks=[dict(type=\"TextLoggerHook\"), dict(type=\"TensorboardLoggerHook\")]\n)\ncheckpoint_config = dict(interval=1)\nload_from = \"ckpts/uniad_base_track_map.pth\"\n\nfind_unused_parameters = True"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/base_e2e_b2d.py",
    "content": "_base_ = [\"../_base_/datasets/nus-3d.py\",\n          \"../_base_/default_runtime.py\"]\n\n# Update-2023-06-12: \n# [Enhance] Update some freezing args of UniAD \n# plugin_dir = \"projects/mmdet3d_plugin/\"\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\npatch_size = [102.4, 102.4]\nimg_norm_cfg = dict(mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\n\nvehicle_id_list = [0,1,2]\ngroup_id_list =  [[0, 1, 2], [3], [7]]\n\ninput_modality = dict(\n    use_lidar=False, use_camera=True, use_radar=False, use_map=False, use_external=True\n)\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\n_feed_dim_ = _ffn_dim_\n_dim_half_ = _pos_dim_\ncanvas_size = (bev_h_, bev_w_)\nqueue_length = 3  # each sequence contains `queue_length` frames.\n\n### traj prediction args ###\npredict_steps = 12\npredict_modes = 6\nfut_steps = 4\npast_steps = 4\nuse_nonlinear_optimizer = True\n\n## occflow setting\t\nocc_n_future = 4\t\nocc_n_future_plan = 6\nocc_n_future_max = max([occ_n_future, occ_n_future_plan])\t\n\n### planning ###\nplanning_steps = 6\nuse_col_optim = True\n\n### Occ args ### \noccflow_grid_conf = {\n    'xbound': [-50.0, 50.0, 0.5],\n    'ybound': [-50.0, 50.0, 0.5],\n    'zbound': [-10.0, 10.0, 20.0],\n}\n\n# Other settings\ntrain_gt_iou_threshold=0.3\n\nmodel = dict(\n    type=\"UniAD\",\n    gt_iou_threshold=train_gt_iou_threshold,\n    queue_length=queue_length,\n    use_grid_mask=True,\n    video_test_mode=True,\n    num_query=900,\n    num_classes=len(class_names),\n    vehicle_id_list=vehicle_id_list,\n    pc_range=point_cloud_range,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=101,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=4,\n        norm_cfg=dict(type=\"BN2d\", requires_grad=False),\n        norm_eval=True,\n        style=\"caffe\",\n        dcn=dict(\n            type=\"DCNv2\", deform_groups=1, fallback_on_stride=False\n        ),  # original DCNv2 will print log when perform load_state_dict\n        stage_with_dcn=(False, False, True, True),\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs=\"on_output\",\n        num_outs=4,\n        relu_before_extra_convs=True,\n    ),\n    freeze_img_backbone=True,\n    freeze_img_neck=True,\n    freeze_bn=True,\n    freeze_bev_encoder=True,\n    score_thresh=0.4,\n    filter_score_thresh=0.35,\n    qim_args=dict(\n        qim_type=\"QIMBase\",\n        merger_dropout=0,\n        update_query_pos=True,\n        fp_ratio=0.3,\n        random_drop=0.1,\n    ),  # hyper-param for query dropping mentioned in MOTR\n    mem_args=dict(\n        memory_bank_type=\"MemoryBank\",\n        memory_bank_score_thresh=0.0,\n        memory_bank_len=4,\n    ),\n    loss_cfg=dict(\n        type=\"ClipMatcher\",\n        num_classes=len(class_names),\n        weight_dict=None,\n        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n        assigner=dict(\n            type=\"HungarianAssigner3DTrack\",\n            cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n            reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n            pc_range=point_cloud_range,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n    ),  # loss cfg for tracking\n    pts_bbox_head=dict(\n        type=\"BEVFormerTrackHead\",\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=len(class_names),\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        transformer=dict(\n            type=\"UniADPerceptionTransformer\",\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type=\"BEVFormerEncoder\",\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type=\"BEVFormerLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"TemporalSelfAttention\", embed_dims=_dim_, num_levels=1\n                        ),\n                        dict(\n                            type=\"SpatialCrossAttention\",\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type=\"MSDeformableAttention3D\",\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_,\n                            ),\n                            embed_dims=_dim_,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n            decoder=dict(\n                type=\"DetectionTransformerDecoder\",\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type=\"DetrTransformerDecoderLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"MultiheadAttention\",\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0,\n                        ),\n                        dict(\n                            type=\"CustomMSDeformableAttention\",\n                            embed_dims=_dim_,\n                            num_levels=1,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n        ),\n        bbox_coder=dict(\n            type=\"NMSFreeCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=len(class_names),\n        ),\n        positional_encoding=dict(\n            type=\"LearnedPositionalEncoding\",\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_iou=dict(type=\"GIoULoss\", loss_weight=0.0),\n    ),\n    seg_head=dict(\n        type='PansegformerHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        canvas_size=canvas_size,\n        pc_range=point_cloud_range,\n        num_query=300,\n        num_classes=6,\n        num_things_classes=6,\n        num_stuff_classes=0,\n        in_channels=2048,\n        sync_cls_avg_factor=True,\n        as_two_stage=False,\n        with_box_refine=True,\n        transformer=dict(\n            type='SegDeformableTransformer',\n            encoder=dict(\n                type='DetrTransformerEncoder',\n                num_layers=6,\n                transformerlayers=dict(\n                    type='BaseTransformerLayer',\n                    attn_cfgs=dict(\n                        type='MultiScaleDeformableAttention',\n                        embed_dims=_dim_,\n                        num_levels=_num_levels_,\n                         ),\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'ffn', 'norm'))),\n            decoder=dict(\n                type='DeformableDetrTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                        dict(\n                            type='MultiScaleDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=_num_levels_,\n                        )\n                    ],\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')\n                ),\n            ),\n        ),\n        positional_encoding=dict(\n            type='SinePositionalEncoding',\n            num_feats=_dim_half_,\n            normalize=True,\n            offset=-0.5),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n        loss_mask=dict(type='DiceLoss', loss_weight=2.0),\n        thing_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=4),\n        stuff_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=6,self_attn=True),\n        train_cfg=dict(\n            assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                ),\n            assigner_with_mask=dict(\n                type='HungarianAssigner_multi_info',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                mask_cost=dict(type='DiceCost', weight=2.0),\n                ),\n            sampler =dict(type='PseudoSampler'),\n            sampler_with_mask =dict(type='PseudoSampler_segformer'),\n        ),\n    ),\n    occ_head=dict(\n        type='OccHead',\n\n        grid_conf=occflow_grid_conf,\n        ignore_index=255,\n\n        bev_proj_dim=256,\n        bev_proj_nlayers=4,\n\n        # Transformer\n        attn_mask_thresh=0.3,\n        transformer_decoder=dict(\n            type='DetrTransformerDecoder',\n            return_intermediate=True,\n            num_layers=5,\n            transformerlayers=dict(\n                type='DetrTransformerDecoderLayer',\n                attn_cfgs=dict(\n                    type='MultiheadAttention',\n                    embed_dims=256,\n                    num_heads=8,\n                    attn_drop=0.0,\n                    proj_drop=0.0,\n                    dropout_layer=None,\n                    batch_first=False),\n                ffn_cfgs=dict(\n                    embed_dims=256,\n                    feedforward_channels=2048,  # change to 512\n                    num_fcs=2,\n                    act_cfg=dict(type='ReLU', inplace=True),\n                    ffn_drop=0.0,\n                    dropout_layer=None,\n                    add_identity=True),\n                feedforward_channels=2048,\n                operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                 'ffn', 'norm')),\n            init_cfg=None),\n        # Query\n        query_dim=256,\n        query_mlp_layers=3,\n\n        aux_loss_weight=1.,\n        loss_mask=dict(\n            type='FieryBinarySegmentationLoss',\n            use_top_k=True,\n            top_k_ratio=0.25,\n            future_discount=0.95,\n            loss_weight=5.0,\n            ignore_index=255,\n        ),\n        loss_dice=dict(\n            type='DiceLossWithMasks',\n            use_sigmoid=True,\n            activate=True,\n            reduction='mean',\n            naive_dice=True,\n            eps=1.0,\n            ignore_index=255,\n            loss_weight=1.0),\n\n        \n        pan_eval=True,\n        test_seg_thresh=0.1,\n        test_with_track_score=True,\n    ),\n    motion_head=dict(\n        type='MotionHead',\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=300,\n        num_classes=len(class_names),\n        vehicle_id_list=vehicle_id_list,\n        predict_steps=predict_steps,\n        predict_modes=predict_modes,\n        embed_dims=_dim_,\n        loss_traj=dict(type='TrajLoss', \n            use_variance=True, \n            cls_loss_weight=0.5, \t\n            nll_loss_weight=0.5, \t\n            loss_weight_minade=0., \t\n            loss_weight_minfde=0.25),\n        num_cls_fcs=3,\n        pc_range=point_cloud_range,\n        group_id_list=group_id_list,\n        num_anchor=6,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        anchor_info_path='data/others/b2d_motion_anchor_infos_mode6.pkl',\n        transformerlayers=dict(\n            type='MotionTransformerDecoder',\n            pc_range=point_cloud_range,\n            embed_dims=_dim_,\n            num_layers=3,\n            transformerlayers=dict(\n                type='MotionTransformerAttentionLayer',\n                batch_first=True,\n                attn_cfgs=[\n                    dict(\n                        type='MotionDeformableAttention',\n                        num_steps=predict_steps,\n                        embed_dims=_dim_,\n                        num_levels=1,\n                        num_heads=8,\n                        num_points=4,\n                        sample_index=-1),\n                ],\n\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm')),\n        ),\n    ),\n    planning_head=dict(\n        type='PlanningHeadSingleMode',\n        embed_dims=256,\n        command_dim=6,\n        planning_steps=planning_steps,\n        loss_planning=dict(type='PlanningLoss'),\n        loss_collision=[dict(type='CollisionLoss', delta=0.0, weight=2.5),\n                        dict(type='CollisionLoss', delta=0.5, weight=1.0),\n                        dict(type='CollisionLoss', delta=1.0, weight=0.25)],\n        use_col_optim=use_col_optim,\n        planning_eval=True,\n        with_adapter=True,\n    ),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                iou_cost=dict(\n                    type=\"IoUCost\", weight=0.0\n                ),  # Fake cost. This is just to make it compatible with DETR head.\n                pc_range=point_cloud_range,\n            ),\n        )\n    ),\n)\ndataset_type = \"B2D_E2E_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\n\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFilesInCeph\", to_float32=True, file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(\n        type=\"LoadAnnotations3D_E2E\",\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_attr_label=False,\n        with_vis_token=False,\n        with_future_anns=True,  # occ_flow gt\n        with_ins_inds_3d=True,  # ins_inds \n        ins_inds_add_1=True,    # ins_inds start from 1\n    ),\n\n    dict(type='GenerateOccFlowLabels', \n         grid_conf=occflow_grid_conf, \n         ignore_index=255, \n         only_vehicle=True, \n         filter_invisible=False,\n         all_classes = class_names,\n         vehicle_classes = ['car','van','truck','bicycle'],\n         plan_classes = ['car','van','truck','bicycle','pedestrian'],\n         ),\n\n    dict(type=\"ObjectRangeFilterTrack\", point_cloud_range=point_cloud_range),\n    dict(type=\"ObjectNameFilterTrack\", classes=class_names),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type=\"DefaultFormatBundle3D\", class_names=class_names),\n    dict(\n        type=\"CustomCollect3D\",\n        keys=[\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            \"gt_inds\",\n            \"img\",\n            \"timestamp\",\n            \"l2g_r_mat\",\n            \"l2g_t\",\n            \"gt_fut_traj\",\n            \"gt_fut_traj_mask\",\n            \"gt_past_traj\",\n            \"gt_past_traj_mask\",\n            \"gt_sdc_bbox\",\n            \"gt_sdc_label\",\n            \"gt_sdc_fut_traj\",\n            \"gt_sdc_fut_traj_mask\",\n            \"gt_lane_labels\",\n            \"gt_lane_bboxes\",\n            \"gt_lane_masks\",\n             # Occ gt\n            \"gt_segmentation\",\n            \"gt_instance\", \n            \"gt_centerness\", \n            \"gt_offset\", \n            \"gt_flow\",\n            \"gt_backward_flow\",\n            \"gt_occ_has_invalid_frame\",\t\n            \"gt_occ_img_is_valid\",\t\n            # gt future bbox for plan\t\n            \"gt_future_boxes\",\t\n            \"gt_future_labels\",\t\n            # planning\t\n            \"sdc_planning\",\t\n            \"sdc_planning_mask\",\t\n            \"command\",\n        ],\n    ),\n]\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type='LoadAnnotations3D_E2E', \n         with_bbox_3d=False,\n         with_label_3d=False, \n         with_attr_label=False,\n         with_vis_token=False,\n         with_future_anns=True,\n         with_ins_inds_3d=False,\n         ins_inds_add_1=True, # ins_inds start from 1\n         ),\n    dict(type='GenerateOccFlowLabels', \n         grid_conf=occflow_grid_conf, \n         ignore_index=255, \n         only_vehicle=True, \n         filter_invisible=False,\n         all_classes = class_names,\n         vehicle_classes = ['car','van','truck','bicycle'],\n         plan_classes = ['car','van','truck','bicycle','pedestrian'],\n         ),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"gt_lane_labels\",\n                                            \"gt_lane_bboxes\",\n                                            \"gt_lane_masks\",\n                                            \"gt_segmentation\",\n                                            \"gt_instance\", \n                                            \"gt_centerness\", \n                                            \"gt_offset\", \n                                            \"gt_flow\",\n                                            \"gt_backward_flow\",\n                                            \"gt_occ_has_invalid_frame\",\t\n                                            \"gt_occ_img_is_valid\",\t\n                                            # planning\t\n                                            \"sdc_planning\",\t\n                                            \"sdc_planning_mask\",\t\n                                            \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\n\ninference_only_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        modality=input_modality,\n        patch_size=patch_size,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        point_cloud_range=point_cloud_range,\n        box_type_3d=\"LiDAR\",\n    ),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    shuffler_sampler=dict(type=\"DistributedGroupSampler\"),\n    nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n)\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n    weight_decay=0.01,\n)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\ntotal_epochs = 2\nevaluation = dict(interval=2, pipeline=test_pipeline)\nrunner = dict(type=\"EpochBasedRunner\", max_epochs=total_epochs)\nlog_config = dict(\n    interval=50, hooks=[dict(type=\"TextLoggerHook\"), dict(type=\"TensorboardLoggerHook\")]\n)\ncheckpoint_config = dict(interval=3000, by_epoch=False)\n\n\nfind_unused_parameters = True\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/tiny_e2e_b2d.py",
    "content": "_base_ = [\"../_base_/datasets/nus-3d.py\",\n          \"../_base_/default_runtime.py\"]\n\n# Update-2023-06-12: \n# [Enhance] Update some freezing args of UniAD \n# plugin_dir = \"projects/mmdet3d_plugin/\"\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nvoxel_size = [0.2, 0.2, 8]\npatch_size = [102.4, 102.4]\nimg_norm_cfg = dict(mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\n\nvehicle_id_list = [0,1,2]\ngroup_id_list =  [[0, 1, 2], [3], [7]]\n\ninput_modality = dict(\n    use_lidar=False, use_camera=True, use_radar=False, use_map=False, use_external=True\n)\n_dim_ = 256\n_pos_dim_ = _dim_ // 2\n_ffn_dim_ = _dim_ * 2\n_num_levels_ = 4\nbev_h_ = 100\nbev_w_ = 100\n_feed_dim_ = _ffn_dim_\n_dim_half_ = _pos_dim_\ncanvas_size = (bev_h_*2, bev_w_*2)\nqueue_length = 3  # each sequence contains `queue_length` frames.\n\n### traj prediction args ###\npredict_steps = 12\npredict_modes = 6\nfut_steps = 4\npast_steps = 4\nuse_nonlinear_optimizer = True\n\n## occflow setting\t\nocc_n_future = 4\t\nocc_n_future_plan = 6\nocc_n_future_max = max([occ_n_future, occ_n_future_plan])\t\n\n### planning ###\nplanning_steps = 6\nuse_col_optim = True\n\n### Occ args ### \noccflow_grid_conf = {\n    'xbound': [-50.0, 50.0, 0.5],\n    'ybound': [-50.0, 50.0, 0.5],\n    'zbound': [-10.0, 10.0, 20.0],\n}\n\n# Other settings\ntrain_gt_iou_threshold=0.3\n\nmodel = dict(\n    type=\"UniAD\",\n    gt_iou_threshold=train_gt_iou_threshold,\n    queue_length=queue_length,\n    use_grid_mask=True,\n    video_test_mode=True,\n    prev_frame_num=10,\n    num_query=900,\n    num_classes=len(class_names),\n    vehicle_id_list=vehicle_id_list,\n    pc_range=point_cloud_range,\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1,2,3),\n        frozen_stages=4,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type=\"FPN\",\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs=\"on_output\",\n        num_outs=4,\n        relu_before_extra_convs=True,\n    ),\n    freeze_img_backbone=True,\n    freeze_img_neck=True,\n    freeze_bn=True,\n    freeze_bev_encoder=True,\n    score_thresh=0.4,\n    filter_score_thresh=0.35,\n    qim_args=dict(\n        qim_type=\"QIMBase\",\n        merger_dropout=0,\n        update_query_pos=True,\n        fp_ratio=0.3,\n        random_drop=0.1,\n    ),  # hyper-param for query dropping mentioned in MOTR\n    mem_args=dict(\n        memory_bank_type=\"MemoryBank\",\n        memory_bank_score_thresh=0.0,\n        memory_bank_len=4,\n    ),\n    loss_cfg=dict(\n        type=\"ClipMatcher\",\n        num_classes=len(class_names),\n        weight_dict=None,\n        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n        assigner=dict(\n            type=\"HungarianAssigner3DTrack\",\n            cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n            reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n            pc_range=point_cloud_range,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n    ),  # loss cfg for tracking\n    pts_bbox_head=dict(\n        type=\"BEVFormerTrackHead\",\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=900,\n        num_classes=len(class_names),\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        past_steps=past_steps,\n        fut_steps=fut_steps,\n        transformer=dict(\n            type=\"UniADPerceptionTransformer\",\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type=\"BEVFormerEncoder\",\n                num_layers=3,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type=\"BEVFormerLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"TemporalSelfAttention\", embed_dims=_dim_, num_levels=1\n                        ),\n                        dict(\n                            type=\"SpatialCrossAttention\",\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type=\"MSDeformableAttention3D\",\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_,\n                            ),\n                            embed_dims=_dim_,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n            decoder=dict(\n                type=\"DetectionTransformerDecoder\",\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type=\"DetrTransformerDecoderLayer\",\n                    attn_cfgs=[\n                        dict(\n                            type=\"MultiheadAttention\",\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0,\n                        ),\n                        dict(\n                            type=\"CustomMSDeformableAttention\",\n                            embed_dims=_dim_,\n                            num_levels=1,\n                        ),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=(\n                        \"self_attn\",\n                        \"norm\",\n                        \"cross_attn\",\n                        \"norm\",\n                        \"ffn\",\n                        \"norm\",\n                    ),\n                ),\n            ),\n        ),\n        bbox_coder=dict(\n            type=\"NMSFreeCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=point_cloud_range,\n            max_num=300,\n            voxel_size=voxel_size,\n            num_classes=len(class_names),\n        ),\n        positional_encoding=dict(\n            type=\"LearnedPositionalEncoding\",\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n        ),\n        loss_cls=dict(\n            type=\"FocalLoss\", use_sigmoid=True, gamma=2.0, alpha=0.25, loss_weight=2.0\n        ),\n        loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n        loss_iou=dict(type=\"GIoULoss\", loss_weight=0.0),\n    ),\n    seg_head=dict(\n        type='PansegformerHead',\n        bev_h=bev_h_*2,\n        bev_w=bev_w_*2,\n        canvas_size=canvas_size,\n        pc_range=point_cloud_range,\n        num_query=300,\n        num_classes=6,\n        num_things_classes=6,\n        num_stuff_classes=1,\n        in_channels=2048,\n        sync_cls_avg_factor=True,\n        as_two_stage=False,\n        with_box_refine=True,\n        transformer=dict(\n            type='SegDeformableTransformer',\n            encoder=dict(\n                type='DetrTransformerEncoder',\n                num_layers=6,\n                transformerlayers=dict(\n                    type='BaseTransformerLayer',\n                    attn_cfgs=dict(\n                        type='MultiScaleDeformableAttention',\n                        embed_dims=_dim_,\n                        num_levels=_num_levels_,\n                         ),\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'ffn', 'norm'))),\n            decoder=dict(\n                type='DeformableDetrTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                        dict(\n                            type='MultiScaleDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=_num_levels_,\n                        )\n                    ],\n                    feedforward_channels=_feed_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')\n                ),\n            ),\n        ),\n        positional_encoding=dict(\n            type='SinePositionalEncoding',\n            num_feats=_dim_half_,\n            normalize=True,\n            offset=-0.5),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n        loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n        loss_mask=dict(type='DiceLoss', loss_weight=2.0),\n        thing_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=4),\n        stuff_transformer_head=dict(type='SegMaskHead',d_model=_dim_,nhead=8,num_decoder_layers=6,self_attn=True),\n        train_cfg=dict(\n            assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                ),\n            assigner_with_mask=dict(\n                type='HungarianAssigner_multi_info',\n                cls_cost=dict(type='FocalLossCost', weight=2.0),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0, box_format='xywh'),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                mask_cost=dict(type='DiceCost', weight=2.0),\n                ),\n            sampler =dict(type='PseudoSampler'),\n            sampler_with_mask =dict(type='PseudoSampler_segformer'),\n        ),\n    ),\n    occ_head=dict(\n        type='OccHead',\n\n        grid_conf=occflow_grid_conf,\n        ignore_index=255,\n\n        bev_proj_dim=256,\n        bev_proj_nlayers=4,\n\n        # Transformer\n        attn_mask_thresh=0.3,\n        transformer_decoder=dict(\n            type='DetrTransformerDecoder',\n            return_intermediate=True,\n            num_layers=5,\n            transformerlayers=dict(\n                type='DetrTransformerDecoderLayer',\n                attn_cfgs=dict(\n                    type='MultiheadAttention',\n                    embed_dims=256,\n                    num_heads=8,\n                    attn_drop=0.0,\n                    proj_drop=0.0,\n                    dropout_layer=None,\n                    batch_first=False),\n                ffn_cfgs=dict(\n                    embed_dims=256,\n                    feedforward_channels=2048,  # change to 512\n                    num_fcs=2,\n                    act_cfg=dict(type='ReLU', inplace=True),\n                    ffn_drop=0.0,\n                    dropout_layer=None,\n                    add_identity=True),\n                feedforward_channels=2048,\n                operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                 'ffn', 'norm')),\n            init_cfg=None),\n        # Query\n        query_dim=256,\n        query_mlp_layers=3,\n\n        aux_loss_weight=1.,\n        loss_mask=dict(\n            type='FieryBinarySegmentationLoss',\n            use_top_k=True,\n            top_k_ratio=0.25,\n            future_discount=0.95,\n            loss_weight=5.0,\n            ignore_index=255,\n        ),\n        loss_dice=dict(\n            type='DiceLossWithMasks',\n            use_sigmoid=True,\n            activate=True,\n            reduction='mean',\n            naive_dice=True,\n            eps=1.0,\n            ignore_index=255,\n            loss_weight=1.0),\n\n        \n        pan_eval=True,\n        test_seg_thresh=0.1,\n        test_with_track_score=True,\n    ),\n    motion_head=dict(\n        type='MotionHead',\n        bev_h=bev_h_*2,\n        bev_w=bev_w_*2,\n        num_query=300,\n        num_classes=len(class_names),\n        predict_steps=predict_steps,\n        predict_modes=predict_modes,\n        embed_dims=_dim_,\n        loss_traj=dict(type='TrajLoss', \n            use_variance=True, \n            cls_loss_weight=0.5, \t\n            nll_loss_weight=0.5, \t\n            loss_weight_minade=0., \t\n            loss_weight_minfde=0.25),\n        num_cls_fcs=3,\n        pc_range=point_cloud_range,\n        group_id_list=group_id_list,\n        num_anchor=6,\n        use_nonlinear_optimizer=use_nonlinear_optimizer,\n        anchor_info_path='data/others/b2d_motion_anchor_infos_mode6.pkl',\n        transformerlayers=dict(\n            type='MotionTransformerDecoder',\n            pc_range=point_cloud_range,\n            embed_dims=_dim_,\n            num_layers=3,\n            transformerlayers=dict(\n                type='MotionTransformerAttentionLayer',\n                batch_first=True,\n                attn_cfgs=[\n                    dict(\n                        type='MotionDeformableAttention',\n                        num_steps=predict_steps,\n                        embed_dims=_dim_,\n                        num_levels=1,\n                        num_heads=8,\n                        num_points=4,\n                        sample_index=-1),\n                ],\n\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm')),\n        ),\n    ),\n    planning_head=dict(\n        type='PlanningHeadSingleMode',\n        embed_dims=256,\n        command_dim=6,\n        planning_steps=planning_steps,\n        loss_planning=dict(type='PlanningLoss'),\n        loss_collision=[dict(type='CollisionLoss', delta=0.0, weight=2.5),\n                        dict(type='CollisionLoss', delta=0.5, weight=1.0),\n                        dict(type='CollisionLoss', delta=1.0, weight=0.25)],\n        use_col_optim=use_col_optim,\n        planning_eval=True,\n        with_adapter=True,\n    ),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            point_cloud_range=point_cloud_range,\n            out_size_factor=4,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                iou_cost=dict(\n                    type=\"IoUCost\", weight=0.0\n                ),  # Fake cost. This is just to make it compatible with DETR head.\n                pc_range=point_cloud_range,\n            ),\n        )\n    ),\n)\ndataset_type = \"B2D_E2E_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFilesInCeph\", to_float32=True, file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(\n        type=\"LoadAnnotations3D_E2E\",\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_attr_label=False,\n        with_vis_token=False,\n        with_future_anns=True,  # occ_flow gt\n        with_ins_inds_3d=True,  # ins_inds \n        ins_inds_add_1=True,    # ins_inds start from 1\n    ),\n\n    dict(type='GenerateOccFlowLabels', \n         grid_conf=occflow_grid_conf, \n         ignore_index=255, \n         only_vehicle=True, \n         filter_invisible=False,\n         all_classes = class_names,\n         vehicle_classes = ['car','van','truck','bicycle'],\n         plan_classes = ['car','van','truck','bicycle','pedestrian'],\n         ),\n\n    dict(type=\"ObjectRangeFilterTrack\", point_cloud_range=point_cloud_range),\n    dict(type=\"ObjectNameFilterTrack\", classes=class_names),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type=\"DefaultFormatBundle3D\", class_names=class_names),\n    dict(\n        type=\"CustomCollect3D\",\n        keys=[\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            \"gt_inds\",\n            \"img\",\n            \"timestamp\",\n            \"l2g_r_mat\",\n            \"l2g_t\",\n            \"gt_fut_traj\",\n            \"gt_fut_traj_mask\",\n            \"gt_past_traj\",\n            \"gt_past_traj_mask\",\n            \"gt_sdc_bbox\",\n            \"gt_sdc_label\",\n            \"gt_sdc_fut_traj\",\n            \"gt_sdc_fut_traj_mask\",\n            \"gt_lane_labels\",\n            \"gt_lane_bboxes\",\n            \"gt_lane_masks\",\n             # Occ gt\n            \"gt_segmentation\",\n            \"gt_instance\", \n            \"gt_centerness\", \n            \"gt_offset\", \n            \"gt_flow\",\n            \"gt_backward_flow\",\n            \"gt_occ_has_invalid_frame\",\t\n            \"gt_occ_img_is_valid\",\t\n            # gt future bbox for plan\t\n            \"gt_future_boxes\",\t\n            \"gt_future_labels\",\t\n            # planning\t\n            \"sdc_planning\",\t\n            \"sdc_planning_mask\",\t\n            \"command\",\n        ],\n    ),\n]\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(type='LoadAnnotations3D_E2E', \n         with_bbox_3d=False,\n         with_label_3d=False, \n         with_attr_label=False,\n         with_vis_token=False,\n         with_future_anns=True,\n         with_ins_inds_3d=False,\n         ins_inds_add_1=True, # ins_inds start from 1\n         ),\n    dict(type='GenerateOccFlowLabels', \n         grid_conf=occflow_grid_conf, \n         ignore_index=255, \n         only_vehicle=True, \n         filter_invisible=False,\n         all_classes = class_names,\n         vehicle_classes = ['car','van','truck','bicycle'],\n         plan_classes = ['car','van','truck','bicycle','pedestrian'],\n         ),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"gt_lane_labels\",\n                                            \"gt_lane_bboxes\",\n                                            \"gt_lane_masks\",\n                                            \"gt_segmentation\",\n                                            \"gt_instance\", \n                                            \"gt_centerness\", \n                                            \"gt_offset\", \n                                            \"gt_flow\",\n                                            \"gt_backward_flow\",\n                                            \"gt_occ_has_invalid_frame\",\t\n                                            \"gt_occ_img_is_valid\",\t\n                                            # planning\t\n                                            \"sdc_planning\",\t\n                                            \"sdc_planning_mask\",\t\n                                            \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\n\ninference_only_pipeline = [\n    dict(type='LoadMultiViewImageFromFilesInCeph', to_float32=True,\n            file_client_args=file_client_args, img_root=data_root),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"PadMultiViewImage\", size_divisor=32),\n    dict(\n        type=\"MultiScaleFlipAug3D\",\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type=\"DefaultFormatBundle3D\", class_names=class_names, with_label=False\n            ),\n            dict(\n                type=\"CustomCollect3D\", keys=[\n                                            \"img\",\n                                            \"timestamp\",\n                                            \"l2g_r_mat\",\n                                            \"l2g_t\",\n                                            \"command\",\n                                        ]\n            ),\n        ],\n    ),\n]\n\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        modality=input_modality,\n        patch_size=patch_size,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        point_cloud_range=point_cloud_range,\n        box_type_3d=\"LiDAR\",\n    ),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_val,\n        pipeline=test_pipeline,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        bev_size=(bev_h_, bev_w_),\n        predict_frames=predict_steps,\n        past_frames=past_steps,\n        future_frames=fut_steps,\n        classes=class_names,\n        modality=input_modality,\n        samples_per_gpu=1,\n        point_cloud_range=point_cloud_range,\n        eval_cfg=eval_cfg,\n        #eval_mod=['det', 'track', 'map'],\n        box_type_3d=\"LiDAR\",\n    ),\n    shuffler_sampler=dict(type=\"DistributedGroupSampler\"),\n    nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n)\noptimizer = dict(\n    type=\"AdamW\",\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n    weight_decay=0.01,\n)\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\ntotal_epochs = 1\nevaluation = dict(interval=1, pipeline=test_pipeline)\nrunner = dict(type=\"EpochBasedRunner\", max_epochs=total_epochs)\nlog_config = dict(\n    interval=1, hooks=[dict(type=\"TextLoggerHook\"), dict(type=\"TensorboardLoggerHook\")]\n)\ncheckpoint_config = dict(interval=3000, by_epoch=False)\n\nfind_unused_parameters = True"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/data_converter/create_data.py",
    "content": "import argparse\nfrom os import path as osp\nimport sys\nfrom data_converter import uniad_nuscenes_converter as nuscenes_converter\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    nuscenes_converter.create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n    if version == 'v1.0-test':\n        info_test_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_test.pkl')\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_test_path, version=version)\n    else:\n        info_train_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_train.pkl')\n        info_val_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_val.pkl')\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_train_path, version=version)\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_val_path, version=version)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required=False,\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/data_converter/uniad_create_data.sh",
    "content": "\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython tools/create_data.py nuscenes --root-path ./data/nuscenes \\\n       --out-dir ./data/infos \\\n       --extra-tag nuscenes \\\n       --version v1.0 \\\n       --canbus ./data/nuscenes \\"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/data_converter/uniad_nuscenes_converter.py",
    "content": "import numpy as np\nimport os\nfrom collections import OrderedDict\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper\nfrom os import path as osp\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\nfrom typing import List, Tuple, Union\n\nfrom mmcv.core.bbox.box_np_ops import points_cam2img\nfrom mmcv.datasets import NuScenesDataset\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import is_filepath, track_iter_progress, check_file_exist\nfrom mmcv.image import imread\n\nnus_categories = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',\n                  'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',\n                  'barrier')\n\nnus_attributes = ('cycle.with_rider', 'cycle.without_rider',\n                  'pedestrian.moving', 'pedestrian.standing',\n                  'pedestrian.sitting_lying_down', 'vehicle.moving',\n                  'vehicle.parked', 'vehicle.stopped', 'None')\n\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    from nuscenes.nuscenes import NuScenes\n    from nuscenes.can_bus.can_bus_api import NuScenesCanBus\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n    else:\n        raise ValueError('unknown')\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_temporal_test.pkl'.format(info_prefix))\n        dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_temporal_train.pkl'.format(info_prefix))\n        dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_temporal_val.pkl'.format(info_prefix))\n        dump(data, info_val_path)\n\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\n\ndef _get_can_bus_info(nusc, nusc_can_bus, sample):\n    scene_name = nusc.get('scene', sample['scene_token'])['name']\n    sample_timestamp = sample['timestamp']\n    try:\n        pose_list = nusc_can_bus.get_messages(scene_name, 'pose')\n    except:\n        return np.zeros(18)  # server scenes do not have can bus information.\n    can_bus = []\n    # during each scene, the first timestamp of can_bus may be large than the first sample's timestamp\n    last_pose = pose_list[0]\n    for i, pose in enumerate(pose_list):\n        if pose['utime'] > sample_timestamp:\n            break\n        last_pose = pose\n    _ = last_pose.pop('utime')  # useless\n    pos = last_pose.pop('pos')\n    rotation = last_pose.pop('orientation')\n    can_bus.extend(pos)\n    can_bus.extend(rotation)\n    for key in last_pose.keys():\n        can_bus.extend(pose[key])  # 16 elements\n    can_bus.extend([0., 0.])\n    return np.array(can_bus)\n\ndef _get_future_traj_info(nusc, sample, predict_steps=16):\n    sample_token = sample['token']\n    ann_tokens = np.array(sample['anns'])\n    sd_rec = nusc.get('sample', sample_token)\n    fut_traj_all = []\n    fut_traj_valid_mask_all = []\n    _, boxes, _ = nusc.get_sample_data(sd_rec['data']['LIDAR_TOP'], selected_anntokens=ann_tokens)\n    predict_helper = PredictHelper(nusc)\n    for i, ann_token in enumerate(ann_tokens):\n        box = boxes[i]\n        instance_token = nusc.get('sample_annotation', ann_token)['instance_token']\n        fut_traj_local = predict_helper.get_future_for_agent(instance_token,\n                                                             sample_token,\n                                                             seconds=predict_steps//2,\n                                                             in_agent_frame=True)\n\n        fut_traj = np.zeros((predict_steps, 2))\n        fut_traj_valid_mask = np.zeros((predict_steps, 2))\n        if fut_traj_local.shape[0] > 0:\n            # trans = box.center\n            # trans = np.array([0, 0, 0])\n            # rot = Quaternion(matrix=box.rotation_matrix)\n            # fut_traj_scence_centric = convert_local_coords_to_global(fut_traj_local, trans, rot)  \n            fut_traj_scence_centric = fut_traj_local\n            fut_traj[:fut_traj_scence_centric.shape[0], :] = fut_traj_scence_centric\n            fut_traj_valid_mask[:fut_traj_scence_centric.shape[0], :] = 1\n        fut_traj_all.append(fut_traj)\n        fut_traj_valid_mask_all.append(fut_traj_valid_mask)\n    if len(ann_tokens) > 0:\n        fut_traj_all = np.stack(fut_traj_all, axis=0)\n        fut_traj_valid_mask_all = np.stack(fut_traj_valid_mask_all, axis=0)\n    else:\n        fut_traj_all = np.zeros((0, predict_steps, 2))\n        fut_traj_valid_mask_all = np.zeros((0, predict_steps, 2))\n    return fut_traj_all, fut_traj_valid_mask_all\n\ndef _fill_trainval_infos(nusc,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    frame_idx = 0\n    for sample in track_iter_progress(nusc.sample):\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n\n        check_file_exist(lidar_path)\n        can_bus = _get_can_bus_info(nusc, nusc_can_bus, sample)\n        ##\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'prev': sample['prev'],\n            'next': sample['next'],\n            'can_bus': can_bus,\n            'frame_idx': frame_idx,  # temporal related info\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],  # temporal related info\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n        }\n\n        if sample['next'] == '':\n            frame_idx = 0\n        else:\n            frame_idx += 1\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)\n            instance_inds = [nusc.getind('instance', ann['instance_token'])\n                             for ann in annotations]\n            future_traj_all, future_traj_valid_mask_all = _get_future_traj_info(nusc, sample)\n            instance_tokens = [ann['instance_token'] for ann in annotations]  # dtype('<U[length_of_str]')\n\n            # TODO: Add traj in next dataset_version\n            # future_traj_all, future_traj_valid_mask_all = _get_future_traj_info(nusc, sample)\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NuScenesDataset.NameMapping:\n                    names[i] = NuScenesDataset.NameMapping[names[i]]\n            names = np.array(names)\n            # instance_inds = [nusc.getind('instance', ann['instance_token']) for ann in annotations]\n            # we need to convert rot to SECOND format.\n            gt_boxes = np.concatenate([locs, dims, -rots - np.pi / 2], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['gt_inds'] = np.array(instance_inds)\n            info['gt_ins_tokens'] = np.array(instance_tokens)\n            info['fut_traj'] = future_traj_all\n            info['fut_traj_valid_mask'] = future_traj_valid_mask_all\n\n            # add visibility_tokens\n            visibility_tokens = [int(anno['visibility_token'])\n                                 for anno in annotations]\n            info['visibility_tokens'] = np.array(visibility_tokens)\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\n\ndef export_2d_annotation(root_path, info_path, version, mono3d=True):\n    \"\"\"Export 2d annotation from the info file and raw data.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        info_path (str): Path of the info file.\n        version (str): Dataset version.\n        mono3d (bool): Whether to export mono3d annotation. Default: True.\n    \"\"\"\n    # get bbox annotations for camera\n    camera_types = [\n        'CAM_FRONT',\n        'CAM_FRONT_RIGHT',\n        'CAM_FRONT_LEFT',\n        'CAM_BACK',\n        'CAM_BACK_LEFT',\n        'CAM_BACK_RIGHT',\n    ]\n    nusc_infos = load(info_path)['infos']\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    # info_2d_list = []\n    cat2Ids = [\n        dict(id=nus_categories.index(cat_name), name=cat_name)\n        for cat_name in nus_categories\n    ]\n    coco_ann_id = 0\n    coco_2d_dict = dict(annotations=[], images=[], categories=cat2Ids)\n    for info in track_iter_progress(nusc_infos):\n        for cam in camera_types:\n            cam_info = info['cams'][cam]\n            coco_infos = get_2d_boxes(\n                nusc,\n                cam_info['sample_data_token'],\n                visibilities=['', '1', '2', '3', '4'],\n                mono3d=mono3d)\n            (height, width, _) = imread(cam_info['data_path']).shape\n            coco_2d_dict['images'].append(\n                dict(\n                    file_name=cam_info['data_path'].split('data/nuscenes/')\n                    [-1],\n                    id=cam_info['sample_data_token'],\n                    token=info['token'],\n                    cam2ego_rotation=cam_info['sensor2ego_rotation'],\n                    cam2ego_translation=cam_info['sensor2ego_translation'],\n                    ego2global_rotation=info['ego2global_rotation'],\n                    ego2global_translation=info['ego2global_translation'],\n                    cam_intrinsic=cam_info['cam_intrinsic'],\n                    width=width,\n                    height=height))\n            for coco_info in coco_infos:\n                if coco_info is None:\n                    continue\n                # add an empty key for coco format\n                coco_info['segmentation'] = []\n                coco_info['id'] = coco_ann_id\n                coco_2d_dict['annotations'].append(coco_info)\n                coco_ann_id += 1\n    if mono3d:\n        json_prefix = f'{info_path[:-4]}_mono3d'\n    else:\n        json_prefix = f'{info_path[:-4]}'\n    dump(coco_2d_dict, f'{json_prefix}.coco.json')\n\n\ndef get_2d_boxes(nusc,\n                 sample_data_token: str,\n                 visibilities: List[str],\n                 mono3d=True):\n    \"\"\"Get the 2D annotation records for a given `sample_data_token`.\n\n    Args:\n        sample_data_token (str): Sample data token belonging to a camera \\\n            keyframe.\n        visibilities (list[str]): Visibility filter.\n        mono3d (bool): Whether to get boxes with mono3d annotation.\n\n    Return:\n        list[dict]: List of 2D annotation record that belongs to the input\n            `sample_data_token`.\n    \"\"\"\n\n    # Get the sample data and the sample corresponding to that sample data.\n    sd_rec = nusc.get('sample_data', sample_data_token)\n\n    assert sd_rec[\n        'sensor_modality'] == 'camera', 'Error: get_2d_boxes only works' \\\n        ' for camera sample_data!'\n    if not sd_rec['is_key_frame']:\n        raise ValueError(\n            'The 2D re-projections are available only for keyframes.')\n\n    s_rec = nusc.get('sample', sd_rec['sample_token'])\n\n    # Get the calibrated sensor and ego pose\n    # record to get the transformation matrices.\n    cs_rec = nusc.get('calibrated_sensor', sd_rec['calibrated_sensor_token'])\n    pose_rec = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    camera_intrinsic = np.array(cs_rec['camera_intrinsic'])\n\n    # Get all the annotation with the specified visibilties.\n    ann_recs = [\n        nusc.get('sample_annotation', token) for token in s_rec['anns']\n    ]\n    ann_recs = [\n        ann_rec for ann_rec in ann_recs\n        if (ann_rec['visibility_token'] in visibilities)\n    ]\n\n    repro_recs = []\n\n    for ann_rec in ann_recs:\n        # Augment sample_annotation with token information.\n        ann_rec['sample_annotation_token'] = ann_rec['token']\n        ann_rec['sample_data_token'] = sample_data_token\n\n        # Get the box in global coordinates.\n        box = nusc.get_box(ann_rec['token'])\n\n        # Move them to the ego-pose frame.\n        box.translate(-np.array(pose_rec['translation']))\n        box.rotate(Quaternion(pose_rec['rotation']).inverse)\n\n        # Move them to the calibrated sensor frame.\n        box.translate(-np.array(cs_rec['translation']))\n        box.rotate(Quaternion(cs_rec['rotation']).inverse)\n\n        # Filter out the corners that are not in front of the calibrated\n        # sensor.\n        corners_3d = box.corners()\n        in_front = np.argwhere(corners_3d[2, :] > 0).flatten()\n        corners_3d = corners_3d[:, in_front]\n\n        # Project 3d box to 2d.\n        corner_coords = view_points(corners_3d, camera_intrinsic,\n                                    True).T[:, :2].tolist()\n\n        # Keep only corners that fall within the image.\n        final_coords = post_process_coords(corner_coords)\n\n        # Skip if the convex hull of the re-projected corners\n        # does not intersect the image canvas.\n        if final_coords is None:\n            continue\n        else:\n            min_x, min_y, max_x, max_y = final_coords\n\n        # Generate dictionary record to be included in the .json file.\n        repro_rec = generate_record(ann_rec, min_x, min_y, max_x, max_y,\n                                    sample_data_token, sd_rec['filename'])\n\n        # If mono3d=True, add 3D annotations in camera coordinates\n        if mono3d and (repro_rec is not None):\n            loc = box.center.tolist()\n\n            dim = box.wlh\n            dim[[0, 1, 2]] = dim[[1, 2, 0]]  # convert wlh to our lhw\n            dim = dim.tolist()\n\n            rot = box.orientation.yaw_pitch_roll[0]\n            rot = [-rot]  # convert the rot to our cam coordinate\n\n            global_velo2d = nusc.box_velocity(box.token)[:2]\n            global_velo3d = np.array([*global_velo2d, 0.0])\n            e2g_r_mat = Quaternion(pose_rec['rotation']).rotation_matrix\n            c2e_r_mat = Quaternion(cs_rec['rotation']).rotation_matrix\n            cam_velo3d = global_velo3d @ np.linalg.inv(\n                e2g_r_mat).T @ np.linalg.inv(c2e_r_mat).T\n            velo = cam_velo3d[0::2].tolist()\n\n            repro_rec['bbox_cam3d'] = loc + dim + rot\n            repro_rec['velo_cam3d'] = velo\n\n            center3d = np.array(loc).reshape([1, 3])\n            center2d = points_cam2img(\n                center3d, camera_intrinsic, with_depth=True)\n            repro_rec['center2d'] = center2d.squeeze().tolist()\n            # normalized center2D + depth\n            # if samples with depth < 0 will be removed\n            if repro_rec['center2d'][2] <= 0:\n                continue\n\n            ann_token = nusc.get('sample_annotation',\n                                 box.token)['attribute_tokens']\n            if len(ann_token) == 0:\n                attr_name = 'None'\n            else:\n                attr_name = nusc.get('attribute', ann_token[0])['name']\n            attr_id = nus_attributes.index(attr_name)\n            repro_rec['attribute_name'] = attr_name\n            repro_rec['attribute_id'] = attr_id\n\n        repro_recs.append(repro_rec)\n\n    return repro_recs\n\n\ndef post_process_coords(\n    corner_coords: List, imsize: Tuple[int, int] = (1600, 900)\n) -> Union[Tuple[float, float, float, float], None]:\n    \"\"\"Get the intersection of the convex hull of the reprojected bbox corners\n    and the image canvas, return None if no intersection.\n\n    Args:\n        corner_coords (list[int]): Corner coordinates of reprojected\n            bounding box.\n        imsize (tuple[int]): Size of the image canvas.\n\n    Return:\n        tuple [float]: Intersection of the convex hull of the 2D box\n            corners and the image canvas.\n    \"\"\"\n    polygon_from_2d_box = MultiPoint(corner_coords).convex_hull\n    img_canvas = box(0, 0, imsize[0], imsize[1])\n\n    if polygon_from_2d_box.intersects(img_canvas):\n        img_intersection = polygon_from_2d_box.intersection(img_canvas)\n        intersection_coords = np.array(\n            [coord for coord in img_intersection.exterior.coords])\n\n        min_x = min(intersection_coords[:, 0])\n        min_y = min(intersection_coords[:, 1])\n        max_x = max(intersection_coords[:, 0])\n        max_y = max(intersection_coords[:, 1])\n\n        return min_x, min_y, max_x, max_y\n    else:\n        return None\n\n\ndef generate_record(ann_rec: dict, x1: float, y1: float, x2: float, y2: float,\n                    sample_data_token: str, filename: str) -> OrderedDict:\n    \"\"\"Generate one 2D annotation record given various informations on top of\n    the 2D bounding box coordinates.\n\n    Args:\n        ann_rec (dict): Original 3d annotation record.\n        x1 (float): Minimum value of the x coordinate.\n        y1 (float): Minimum value of the y coordinate.\n        x2 (float): Maximum value of the x coordinate.\n        y2 (float): Maximum value of the y coordinate.\n        sample_data_token (str): Sample data token.\n        filename (str):The corresponding image file where the annotation\n            is present.\n\n    Returns:\n        dict: A sample 2D annotation record.\n            - file_name (str): flie name\n            - image_id (str): sample data token\n            - area (float): 2d box area\n            - category_name (str): category name\n            - category_id (int): category id\n            - bbox (list[float]): left x, top y, dx, dy of 2d box\n            - iscrowd (int): whether the area is crowd\n    \"\"\"\n    repro_rec = OrderedDict()\n    repro_rec['sample_data_token'] = sample_data_token\n    coco_rec = dict()\n\n    relevant_keys = [\n        'attribute_tokens',\n        'category_name',\n        'instance_token',\n        'next',\n        'num_lidar_pts',\n        'num_radar_pts',\n        'prev',\n        'sample_annotation_token',\n        'sample_data_token',\n        'visibility_token',\n    ]\n\n    for key, value in ann_rec.items():\n        if key in relevant_keys:\n            repro_rec[key] = value\n\n    repro_rec['bbox_corners'] = [x1, y1, x2, y2]\n    repro_rec['filename'] = filename\n\n    coco_rec['file_name'] = filename\n    coco_rec['image_id'] = sample_data_token\n    coco_rec['area'] = (y2 - y1) * (x2 - x1)\n\n    if repro_rec['category_name'] not in NuScenesDataset.NameMapping:\n        return None\n    cat_name = NuScenesDataset.NameMapping[repro_rec['category_name']]\n    coco_rec['category_name'] = cat_name\n    coco_rec['category_id'] = nus_categories.index(cat_name)\n    coco_rec['bbox'] = [x1, y1, x2 - x1, y2 - y1]\n    coco_rec['iscrowd'] = 0\n\n    return coco_rec\n    "
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/test.py",
    "content": "import argparse\nimport torch\nimport os\nimport warnings\nfrom torch.nn.parallel.distributed import DistributedDataParallel\nfrom mmcv.utils import get_dist_info, init_dist, wrap_fp16_model, set_random_seed, Config, DictAction, load_checkpoint\nfrom mmcv.fileio.io import dump\nfrom mmcv.datasets import build_dataset, build_dataloader, replace_ImageToTensor\nfrom mmcv.models import build_model, fuse_conv_bn\nimport time\nimport os.path as osp\nfrom adzoo.uniad.test_utils import custom_multi_gpu_test, custom_single_gpu_test\nimport cv2\ncv2.setNumThreads(1)\n\nwarnings.filterwarnings(\"ignore\")\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet test (and eval) a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('checkpoint', help='checkpoint file')\n    parser.add_argument('--out', default='output/results.pkl', help='output result file in pickle format')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    parser.add_argument(\n        '--eval',\n        type=str,\n        nargs='+',\n        help='evaluation metrics, which depends on the dataset, e.g., \"bbox\",'\n        ' \"segm\", \"proposal\" for COCO, and \"mAP\", \"recall\" for PASCAL VOC')\n    parser.add_argument('--show', action='store_true', help='show results')\n    parser.add_argument(\n        '--show-dir', help='directory where results will be saved')\n    parser.add_argument(\n        '--gpu-collect',\n        action='store_true',\n        help='whether to use gpu to collect results.')\n    parser.add_argument(\n        '--tmpdir',\n        help='tmp directory used for collecting results from multiple '\n        'workers, available when gpu-collect is not specified')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local-rank', type=int, default=0)\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n    return args\n\n\ndef main():\n    args = parse_args()\n    cfg = Config.fromfile(args.config)\n\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n    samples_per_gpu = cfg.data.test.pop('samples_per_gpu', 1)\n    if samples_per_gpu > 1:\n        # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n        cfg.data.test.pipeline = replace_ImageToTensor(cfg.data.test.pipeline)\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    else:\n        distributed = True\n        torch.backends.cudnn.benchmark = True\n        init_dist(args.launcher, **cfg.dist_params)\n        rank, world_size = get_dist_info()\n\n    set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # Dataloader\n    dataset = build_dataset(cfg.data.test)\n    data_loader = build_dataloader(dataset,\n                                    samples_per_gpu=samples_per_gpu,\n                                    workers_per_gpu=cfg.data.workers_per_gpu,\n                                    dist=distributed,\n                                    shuffle=False,\n                                    nonshuffler_sampler=cfg.data.nonshuffler_sampler,\n                                    )\n\n    # Model\n    cfg.model.train_cfg = None\n    model = build_model(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    checkpoint = load_checkpoint(model, args.checkpoint, map_location='cpu')\n    if args.fuse_conv_bn:\n        model = fuse_conv_bn(model)\n    \n    # Add classese info\n    if 'CLASSES' in checkpoint.get('meta', {}): # for det\n        model.CLASSES = checkpoint['meta']['CLASSES']\n    else:\n        model.CLASSES = dataset.CLASSES\n    if 'PALETTE' in checkpoint.get('meta', {}):  # for seg\n        model.PALETTE = checkpoint['meta']['PALETTE']\n    elif hasattr(dataset, 'PALETTE'):\n        model.PALETTE = dataset.PALETTE\n\n    if not distributed:\n        assert False #TODO(yzj)\n        # model = MMDataParallel(model, device_ids=[0])\n        # outputs = custom_single_gpu_test(model, data_loader, args.show, args.show_dir)\n    else:\n        model = DistributedDataParallel(model.cuda(),\n                                        device_ids=[torch.cuda.current_device()],\n                                        broadcast_buffers=False,\n                                        )\n        outputs = custom_multi_gpu_test(model, data_loader, args.tmpdir, args.gpu_collect)\n\n\n\n    if rank == 0:\n        if args.out:\n            print(f'\\nwriting results to {args.out}')\n            dump(outputs, args.out)\n        kwargs = {}\n        kwargs['jsonfile_prefix'] = osp.join('test', args.config.split('/')[-1].split('.')[-2], time.ctime().replace(' ', '_').replace(':', '_'))\n\n        if args.eval:\n            eval_kwargs = cfg.get('evaluation', {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in ['interval', 'tmpdir', 'start', 'gpu_collect', 'save_best', 'rule']:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(dict(metric=args.eval, **kwargs))\n            print(dataset.evaluate(outputs, **eval_kwargs))\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/test_utils.py",
    "content": "import os\nimport os.path as osp\nimport pickle\nimport shutil\nimport tempfile\nimport time\n\nimport torch\nimport torch.distributed as dist\n\nfrom mmcv.models.dense_heads.occ_head_plugin import IntersectionOverUnion, PanopticMetric\nfrom mmcv.models.dense_heads.planning_head_plugin import UniADPlanningMetric\nfrom mmcv.utils import ProgressBar, mkdir_or_exist, get_dist_info\nfrom mmcv.fileio.io import load, dump\nimport numpy as np\nimport pycocotools.mask as mask_util\n\ndef custom_encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code. Semantic Masks only\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = []\n    for i in range(len(cls_segms)):\n        encoded_mask_results.append(\n            mask_util.encode(\n                np.array(\n                    cls_segms[i][:, :, np.newaxis], order='F',\n                        dtype='uint8'))[0])  # encoded with RLE\n    return [encoded_mask_results]\n\ndef custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):\n    \"\"\"Test model with multiple gpus.\n    This method tests model with multiple gpus and collects the results\n    under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'\n    it encodes results to gpu tensors and use gpu communication for results\n    collection. On cpu mode it saves the results on different gpus to 'tmpdir'\n    and collects them by the rank 0 worker.\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        tmpdir (str): Path of directory to save the temporary results from\n            different gpus under cpu mode.\n        gpu_collect (bool): Option to use either gpu or cpu to collect results.\n    Returns:\n        list: The prediction results.\n    \"\"\"\n    model.eval()\n\n    # Occ eval init\n    eval_occ = hasattr(model.module, 'with_occ_head') \\\n                and model.module.with_occ_head\n    if eval_occ:\n        # 30mx30m, 100mx100m at 50cm resolution\n        EVALUATION_RANGES = {'30x30': (70, 130),\n                            '100x100': (0, 200)}\n        n_classes = 2\n        iou_metrics = {}\n        for key in EVALUATION_RANGES.keys():\n            iou_metrics[key] = IntersectionOverUnion(n_classes).cuda()\n        panoptic_metrics = {}\n        for key in EVALUATION_RANGES.keys():\n            panoptic_metrics[key] = PanopticMetric(n_classes=n_classes, temporally_consistent=True).cuda()\n    \n    # Plan eval init\n    eval_planning =  hasattr(model.module, 'with_planning_head') \\\n                      and model.module.with_planning_head\n    if eval_planning:\n        planning_metrics = UniADPlanningMetric().cuda()\n        \n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    rank, world_size = get_dist_info()\n    if rank == 0:\n        prog_bar = ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n    num_occ = 0\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(data, return_loss=False, rescale=True)\n\n\n            #import pdb;pdb.set_trace()\n            \n            # # EVAL planning\n            if eval_planning:\n                # TODO: Wrap below into a func\n                segmentation = result[0]['planning']['planning_gt']['segmentation']\n                sdc_planning = result[0]['planning']['planning_gt']['sdc_planning']\n                sdc_planning_mask = result[0]['planning']['planning_gt']['sdc_planning_mask']\n                pred_sdc_traj = result[0]['planning']['result_planning']['sdc_traj']\n                result[0]['planning_traj'] = result[0]['planning']['result_planning']['sdc_traj']\n                result[0]['planning_traj_gt'] = result[0]['planning']['planning_gt']['sdc_planning']\n                result[0]['command'] = result[0]['planning']['planning_gt']['command']\n                planning_metrics(pred_sdc_traj[:, :6, :2], sdc_planning[0][0,:, :6, :2], sdc_planning_mask[0][0,:, :6, :2], segmentation[0][:, [1,2,3,4,5,6]])\n\n            # # Eval Occ\n            if eval_occ:\n                occ_has_invalid_frame = data['gt_occ_has_invalid_frame'][0]\n                occ_to_eval = not occ_has_invalid_frame.item()\n                if occ_to_eval and 'occ' in result[0].keys():\n                    num_occ += 1\n                    for key, grid in EVALUATION_RANGES.items():\n                        limits = slice(grid[0], grid[1])\n                        iou_metrics[key](result[0]['occ']['seg_out'][..., limits, limits].contiguous(),\n                                        result[0]['occ']['seg_gt'][..., limits, limits].contiguous())\n                        panoptic_metrics[key](result[0]['occ']['ins_seg_out'][..., limits, limits].contiguous().detach(),\n                                                result[0]['occ']['ins_seg_gt'][..., limits, limits].contiguous())\n\n            # Pop out unnecessary occ results, avoid appending it to cpu when collect_results_cpu\n            if os.environ.get('ENABLE_PLOT_MODE', None) is None:\n                result[0].pop('occ', None)\n                result[0].pop('planning', None)\n            else:\n                for k in ['seg_gt', 'ins_seg_gt', 'pred_ins_sigmoid', 'seg_out', 'ins_seg_out']:\n                    if k in result[0]['occ']:\n                        result[0]['occ'][k] = result[0]['occ'][k].detach().cpu()\n                for k in ['bbox', 'segm', 'labels', 'panoptic', 'drivable', 'score_list', 'lane', 'lane_score', 'stuff_score_list']:\n                    if k in result[0]['pts_bbox'] and isinstance(result[0]['pts_bbox'][k], torch.Tensor):\n                        result[0]['pts_bbox'][k] = result[0]['pts_bbox'][k].detach().cpu()\n\n            # # encode mask results\n            if isinstance(result, dict):\n                if 'bbox_results' in result.keys():\n                    bbox_result = result['bbox_results']\n                    batch_size = len(result['bbox_results'])\n                    bbox_results.extend(bbox_result)\n                if 'mask_results' in result.keys() and result['mask_results'] is not None:\n                    mask_result = custom_encode_mask_results(result['mask_results'])\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n\n\n        if rank == 0:\n            for _ in range(batch_size * world_size):\n                prog_bar.update()\n                \n        # break\n\n    # collect results from all ranks\n    if gpu_collect:\n        bbox_results = collect_results_gpu(bbox_results, len(dataset))\n        if have_mask:\n            mask_results = collect_results_gpu(mask_results, len(dataset))\n        else:\n            mask_results = None\n    else:\n        bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)\n        tmpdir = tmpdir+'_mask' if tmpdir is not None else None\n        if have_mask:\n            mask_results = collect_results_cpu(mask_results, len(dataset), tmpdir)\n        else:\n            mask_results = None\n\n    if eval_planning:\n        planning_results = planning_metrics.compute()\n        planning_metrics.reset()\n\n    ret_results = dict()\n    ret_results['bbox_results'] = bbox_results\n    if eval_occ:\n        occ_results = {}\n        for key, grid in EVALUATION_RANGES.items():\n            panoptic_scores = panoptic_metrics[key].compute()\n            for panoptic_key, value in panoptic_scores.items():\n                occ_results[f'{panoptic_key}'] = occ_results.get(f'{panoptic_key}', []) + [100 * value[1].item()]\n            panoptic_metrics[key].reset()\n\n            iou_scores = iou_metrics[key].compute()\n            occ_results['iou'] = occ_results.get('iou', []) + [100 * iou_scores[1].item()]\n            iou_metrics[key].reset()\n\n        occ_results['num_occ'] = num_occ  # count on one gpu\n        occ_results['ratio_occ'] = num_occ / len(dataset)  # count on one gpu, but reflect the relative ratio\n        ret_results['occ_results_computed'] = occ_results\n    if eval_planning:\n        ret_results['planning_results_computed'] = planning_results\n\n    if mask_results is not None:\n        ret_results['mask_results'] = mask_results\n    return ret_results\n\n\ndef collect_results_cpu(result_part, size, tmpdir=None):\n    rank, world_size = get_dist_info()\n    # create a tmp dir if it is not specified\n    if tmpdir is None:\n        MAX_LEN = 512\n        # 32 is whitespace\n        dir_tensor = torch.full((MAX_LEN, ),\n                                32,\n                                dtype=torch.uint8,\n                                device='cuda')\n        if rank == 0:\n            mkdir_or_exist('.dist_test')\n            tmpdir = tempfile.mkdtemp(dir='.dist_test')\n            tmpdir = torch.tensor(\n                bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda')\n            dir_tensor[:len(tmpdir)] = tmpdir\n        dist.broadcast(dir_tensor, 0)\n        tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()\n    else:\n        mkdir_or_exist(tmpdir)\n    # dump the part result to the dir\n    dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl'))\n    dist.barrier()\n    # collect all parts\n    if rank != 0:\n        return None\n    else:\n        # load results of all parts from tmp dir\n        part_list = []\n        for i in range(world_size):\n            part_file = osp.join(tmpdir, f'part_{i}.pkl')\n            part_list.append(load(part_file))\n        # sort the results\n        ordered_results = []\n        '''\n        bacause we change the sample of the evaluation stage to make sure that each gpu will handle continuous sample,\n        '''\n        #for res in zip(*part_list):\n        for res in part_list:  \n            ordered_results.extend(list(res))\n        # the dataloader may pad some samples\n        ordered_results = ordered_results[:size]\n        # remove tmp dir\n        shutil.rmtree(tmpdir)\n        return ordered_results\n\n\ndef collect_results_gpu(result_part, size):\n    collect_results_cpu(result_part, size)\n\ndef custom_single_gpu_test(model,\n                    data_loader,\n                    show=False,\n                    out_dir=None,\n                    show_score_thr=0.3):\n    \"\"\"Test model with single gpu.\n\n    This method tests model with single gpu and gives the 'show' option.\n    By setting ``show=True``, it saves the visualization results under\n    ``out_dir``.\n\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        show (bool): Whether to save viualization results.\n            Default: True.\n        out_dir (str): The path to save visualization results.\n            Default: None.\n\n    Returns:\n        list[dict]: The prediction results.\n    \"\"\"\n    model.eval()\n    results = []\n    dataset = data_loader.dataset\n    prog_bar = ProgressBar(len(dataset))\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(return_loss=False, rescale=True, **data)\n\n        if show:\n            # Visualize the results of MMDetection3D model\n            # 'show_results' is MMdetection3D visualization API\n            models_3d = (Base3DDetector, Base3DSegmentor,\n                         SingleStageMono3DDetector)\n            if isinstance(model.module, models_3d):\n                model.module.show_results(data, result, out_dir=out_dir)\n            # Visualize the results of MMDetection model\n            # 'show_result' is MMdetection visualization API\n            else:\n                batch_size = len(result)\n                if batch_size == 1 and isinstance(data['img'][0],\n                                                  torch.Tensor):\n                    img_tensor = data['img'][0]\n                else:\n                    img_tensor = data['img'][0].data[0]\n                img_metas = data['img_metas'][0].data[0]\n                imgs = tensor2imgs(img_tensor, **img_metas[0]['img_norm_cfg'])\n                assert len(imgs) == len(img_metas)\n\n                for i, (img, img_meta) in enumerate(zip(imgs, img_metas)):\n                    h, w, _ = img_meta['img_shape']\n                    img_show = img[:h, :w, :]\n\n                    ori_h, ori_w = img_meta['ori_shape'][:-1]\n                    img_show = imresize(img_show, (ori_w, ori_h))\n\n                    if out_dir:\n                        out_file = osp.join(out_dir, img_meta['ori_filename'])\n                    else:\n                        out_file = None\n\n                    model.module.show_result(\n                        img_show,\n                        result[i],\n                        show=show,\n                        out_file=out_file,\n                        score_thr=show_score_thr)\n        results.extend(result)\n\n        batch_size = len(result)\n        for _ in range(batch_size):\n            prog_bar.update()\n    return results"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/train.py",
    "content": "import argparse\nimport torch\nimport copy\nimport os\nimport time\nimport warnings\nfrom os import path as osp\nfrom mmcv import __version__ as mmcv_version\nfrom mmcv.datasets import build_dataset\nfrom mmcv.models import build_model\nfrom mmcv.utils import collect_env, get_root_logger, mkdir_or_exist, set_random_seed, get_dist_info, init_dist, \\\n                    Config, DictAction, TORCH_VERSION, digit_version\nfrom mmcv.datasets.builder import build_dataloader\nfrom mmcv.optims import build_optimizer\nfrom torch.nn.parallel import DataParallel, DistributedDataParallel\nfrom mmcv.core.evaluation.eval_hooks import CustomDistEvalHook\nfrom mmcv.core import EvalHook\nfrom mmcv.runner import (HOOKS, DistSamplerSeedHook, EpochBasedRunner,\n                         Fp16OptimizerHook, OptimizerHook, build_runner)\nfrom adzoo.uniad.test_utils import custom_multi_gpu_test\n\nwarnings.filterwarnings(\"ignore\")\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Train a detector')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument('--work-dir', help='the dir to save logs and models')\n    parser.add_argument(\n        '--resume-from', help='the checkpoint file to resume from')\n    parser.add_argument(\n        '--no-validate',\n        action='store_true',\n        help='whether not to evaluate the checkpoint during training')\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        '--gpus',\n        type=int,\n        help='number of gpus to use '\n        '(only applicable to non-distributed training)')\n    group_gpus.add_argument(\n        '--gpu-ids',\n        type=int,\n        nargs='+',\n        help='ids of gpus to use '\n        '(only applicable to non-distributed training)')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local_rank', type=int, default=0)\n    parser.add_argument(\n        '--autoscale-lr',\n        action='store_true',\n        help='automatically scale lr with the number of gpus')\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    return args\n\n\ndef main():\n    args = parse_args()\n    cfg = Config.fromfile(args.config)\n\n    if args.work_dir is not None:\n        cfg.work_dir = args.work_dir\n    else:\n        cfg.work_dir = osp.join('./work_dirs', osp.splitext(osp.basename(args.config))[0])\n\n    # if args.resume_from is not None:\n    if args.resume_from is not None and osp.isfile(args.resume_from):\n        cfg.resume_from = args.resume_from\n\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer['lr'] = cfg.optimizer['lr'] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    elif args.launcher == 'pytorch':\n        torch.backends.cudnn.benchmark = True\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n        rank, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # Create work_dir\n    mkdir_or_exist(osp.abspath(cfg.work_dir))\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime())\n\n    # meta info\n    meta = dict()\n    env_info_dict = collect_env()\n    env_info = '\\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()])\n    dash_line = '-' * 60 + '\\n'\n    meta['env_info'] = env_info\n    meta['config'] = cfg.pretty_text\n    meta['seed'] = args.seed\n    meta['exp_name'] = osp.basename(args.config)\n\n    # seed\n    cfg.seed = args.seed\n    set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # logger\n    log_file = osp.join(cfg.work_dir, f'{timestamp}.log')\n    logger = get_root_logger(log_file=log_file, log_level=cfg.log_level, name=cfg.model.type)\n    logger.info('Environment info:\\n' + dash_line + env_info + '\\n' + dash_line)\n    logger.info(f'Distributed training: {distributed}')\n    logger.info(f'Config:\\n{cfg.pretty_text}')\n    logger.info(f'Set random seed to {args.seed}, 'f'deterministic: {args.deterministic}')\n\n    # Dataset\n    datasets = [build_dataset(cfg.data.train)]\n\n    # Save meta info\n    if cfg.checkpoint_config is not None:\n        cfg.checkpoint_config.meta = dict(mmcv_version=mmcv_version, config=cfg.pretty_text, CLASSES=datasets[0].CLASSES, \\\n                                          PALETTE=datasets[0].PALETTE if hasattr(datasets[0], 'PALETTE') else None) # # for segmentors\n    \n    # Dataloader\n    datasets = datasets if isinstance(datasets, (list, tuple)) else [datasets]\n    data_loaders = [build_dataloader(ds,\n                        cfg.data.samples_per_gpu,\n                        cfg.data.workers_per_gpu,\n                        # cfg.gpus will be ignored if distributed\n                        len(cfg.gpu_ids),\n                        dist=distributed,\n                        seed=cfg.seed,\n                        shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n                        nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n                        ) for ds in datasets\n                        ]\n\n    # Model\n    model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n    model.init_weights()\n    model.CLASSES = datasets[0].CLASSES  # add an attribute for visualization convenience\n    logger.info(f'Model:\\n{model}')\n    if distributed:\n        find_unused_parameters = cfg.get('find_unused_parameters', False)\n        model = DistributedDataParallel(model.cuda(),\n                                        device_ids=[torch.cuda.current_device()],\n                                        broadcast_buffers=False,\n                                        find_unused_parameters=find_unused_parameters\n                                        )\n    else:\n        model = DataParallel(model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n\n    # Optimizer\n    optimizer = build_optimizer(model, cfg.optimizer)\n    optimizer_config = OptimizerHook(**cfg.optimizer_config)\n\n    # Runner\n    runner = build_runner(cfg.runner, default_args=dict(model=model,\n                                                        optimizer=optimizer,\n                                                        work_dir=cfg.work_dir,\n                                                        logger=logger,\n                                                        meta=meta))\n    runner.timestamp = timestamp\n    runner.register_training_hooks(cfg.lr_config, optimizer_config,\n                                   cfg.checkpoint_config, cfg.log_config,\n                                   cfg.get('momentum_config', None))\n    if distributed:\n        if isinstance(runner, EpochBasedRunner):\n            runner.register_hook(DistSamplerSeedHook())\n    \n    # Register eval hooks for interval eval\n    val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1)\n    if val_samples_per_gpu > 1:\n        assert False\n        # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n        cfg.data.val.pipeline = replace_ImageToTensor(\n            cfg.data.val.pipeline)\n    val_dataset = build_dataset(cfg.data.val, dict(test_mode=True))\n\n    val_dataloader = build_dataloader(\n        val_dataset,\n        samples_per_gpu=val_samples_per_gpu,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=distributed,\n        shuffle=False,\n        shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n        nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n    )\n    eval_cfg = cfg.get('evaluation', {})\n    eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner'\n    eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_'))\n    eval_hook = CustomDistEvalHook if distributed else EvalHook\n    runner.register_hook(eval_hook(val_dataloader, test_fn=custom_multi_gpu_test, **eval_cfg))\n\n    if cfg.resume_from and os.path.exists(cfg.resume_from):\n        runner.resume(cfg.resume_from)\n    elif cfg.load_from:\n        runner.load_checkpoint(cfg.load_from)\n    runner.run(data_loaders, cfg.workflow)\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/uniad_dist_eval.sh",
    "content": "#!/usr/bin/env bash\n\nT=`date +%m%d%H%M`\n\n# -------------------------------------------------- #\n# Usually you only need to customize these variables #\nCFG=$1                                               #\nCKPT=$2                                              #\nGPUS=$3                                              #    \n# -------------------------------------------------- #\nGPUS_PER_NODE=$(($GPUS<8?$GPUS:8))\n\nMASTER_PORT=${MASTER_PORT:-12145}\nWORK_DIR=$(echo ${CFG%.*} | sed -e \"s/configs/work_dirs/g\")/\n# Intermediate files and logs will be saved to UniAD/projects/work_dirs/\n\nif [ ! -d ${WORK_DIR}logs ]; then\n    mkdir -p ${WORK_DIR}logs\nfi\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch \\\n    --nproc_per_node=$GPUS_PER_NODE \\\n    --master_port=$MASTER_PORT \\\n    $(dirname \"$0\")/test.py \\\n    $CFG \\\n    $CKPT \\\n    --launcher pytorch ${@:4} \\\n    --eval bbox \\\n    --show-dir ${WORK_DIR} \\\n    2>&1 | tee ${WORK_DIR}logs/eval.$T"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/uniad_dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nT=`date +%m%d%H%M`\n\n# -------------------------------------------------- #\n# Usually you only need to customize these variables #\nCFG=$1                                               #\nGPUS=$2                                              #\n# -------------------------------------------------- #\nGPUS_PER_NODE=$(($GPUS<8?$GPUS:8))\nNNODES=`expr $GPUS / $GPUS_PER_NODE`\n\nMASTER_PORT=${MASTER_PORT:-54621}\nMASTER_ADDR=${MASTER_ADDR:-\"127.0.0.1\"}\nRANK=${RANK:-0}\n\nWORK_DIR=$(echo ${CFG%.*} | sed -e \"s/configs/work_dirs/g\")/\n# Intermediate files and logs will be saved to UniAD/projects/work_dirs/\n\nif [ ! -d ${WORK_DIR}logs ]; then\n    mkdir -p ${WORK_DIR}logs\nfi\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch \\\n    --nproc_per_node=${GPUS_PER_NODE} \\\n    --master_addr=${MASTER_ADDR} \\\n    --master_port=${MASTER_PORT} \\\n    --nnodes=${NNODES} \\\n    --node_rank=${RANK} \\\n    $(dirname \"$0\")/train.py \\\n    $CFG \\\n    --launcher pytorch ${@:3} \\\n    --deterministic \\\n    --work-dir ${WORK_DIR} \\\n    2>&1 | tee ${WORK_DIR}logs/train.$T"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/uniad/uniad_vis_result.sh",
    "content": "#!/bin/bash\n\npython ./tools/analysis_tools/visualize/run.py \\\n    --predroot PATH_TO_YOUR_PREDISION_RESULT_PKL \\\n    --out_folder PATH_TO_YOUR_OUTPUT_FOLDER \\\n    --demo_video FILENAME_OF_OUTPUT_VIDEO \\\n    --project_to_cam True"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/analysis_tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/analysis_tools/analyze_logs.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport json\nimport numpy as np\nimport seaborn as sns\nfrom collections import defaultdict\nfrom matplotlib import pyplot as plt\n\n\ndef cal_train_time(log_dicts, args):\n    for i, log_dict in enumerate(log_dicts):\n        print(f'{\"-\" * 5}Analyze train time of {args.json_logs[i]}{\"-\" * 5}')\n        all_times = []\n        for epoch in log_dict.keys():\n            if args.include_outliers:\n                all_times.append(log_dict[epoch]['time'])\n            else:\n                all_times.append(log_dict[epoch]['time'][1:])\n        all_times = np.array(all_times)\n        epoch_ave_time = all_times.mean(-1)\n        slowest_epoch = epoch_ave_time.argmax()\n        fastest_epoch = epoch_ave_time.argmin()\n        std_over_epoch = epoch_ave_time.std()\n        print(f'slowest epoch {slowest_epoch + 1}, '\n              f'average time is {epoch_ave_time[slowest_epoch]:.4f}')\n        print(f'fastest epoch {fastest_epoch + 1}, '\n              f'average time is {epoch_ave_time[fastest_epoch]:.4f}')\n        print(f'time std over epochs is {std_over_epoch:.4f}')\n        print(f'average iter time: {np.mean(all_times):.4f} s/iter')\n        print()\n\n\ndef plot_curve(log_dicts, args):\n    if args.backend is not None:\n        plt.switch_backend(args.backend)\n    sns.set_style(args.style)\n    # if legend is None, use {filename}_{key} as legend\n    legend = args.legend\n    if legend is None:\n        legend = []\n        for json_log in args.json_logs:\n            for metric in args.keys:\n                legend.append(f'{json_log}_{metric}')\n    assert len(legend) == (len(args.json_logs) * len(args.keys))\n    metrics = args.keys\n\n    num_metrics = len(metrics)\n    for i, log_dict in enumerate(log_dicts):\n        epochs = list(log_dict.keys())\n        for j, metric in enumerate(metrics):\n            print(f'plot curve of {args.json_logs[i]}, metric is {metric}')\n            if metric not in log_dict[epochs[args.interval - 1]]:\n                raise KeyError(\n                    f'{args.json_logs[i]} does not contain metric {metric}')\n\n            if args.mode == 'eval':\n                if min(epochs) == args.interval:\n                    x0 = args.interval\n                else:\n                    # if current training is resumed from previous checkpoint\n                    # we lost information in early epochs\n                    # `xs` should start according to `min(epochs)`\n                    if min(epochs) % args.interval == 0:\n                        x0 = min(epochs)\n                    else:\n                        # find the first epoch that do eval\n                        x0 = min(epochs) + args.interval - \\\n                            min(epochs) % args.interval\n                xs = np.arange(x0, max(epochs) + 1, args.interval)\n                ys = []\n                for epoch in epochs[args.interval - 1::args.interval]:\n                    ys += log_dict[epoch][metric]\n\n                # if training is aborted before eval of the last epoch\n                # `xs` and `ys` will have different length and cause an error\n                # check if `ys[-1]` is empty here\n                if not log_dict[epoch][metric]:\n                    xs = xs[:-1]\n\n                ax = plt.gca()\n                ax.set_xticks(xs)\n                plt.xlabel('epoch')\n                plt.plot(xs, ys, label=legend[i * num_metrics + j], marker='o')\n            else:\n                xs = []\n                ys = []\n                num_iters_per_epoch = \\\n                    log_dict[epochs[args.interval-1]]['iter'][-1]\n                for epoch in epochs[args.interval - 1::args.interval]:\n                    iters = log_dict[epoch]['iter']\n                    if log_dict[epoch]['mode'][-1] == 'val':\n                        iters = iters[:-1]\n                    xs.append(\n                        np.array(iters) + (epoch - 1) * num_iters_per_epoch)\n                    ys.append(np.array(log_dict[epoch][metric][:len(iters)]))\n                xs = np.concatenate(xs)\n                ys = np.concatenate(ys)\n                plt.xlabel('iter')\n                plt.plot(\n                    xs, ys, label=legend[i * num_metrics + j], linewidth=0.5)\n            plt.legend()\n        if args.title is not None:\n            plt.title(args.title)\n    if args.out is None:\n        plt.show()\n    else:\n        print(f'save curve to: {args.out}')\n        plt.savefig(args.out)\n        plt.cla()\n\n\ndef add_plot_parser(subparsers):\n    parser_plt = subparsers.add_parser(\n        'plot_curve', help='parser for plotting curves')\n    parser_plt.add_argument(\n        'json_logs',\n        type=str,\n        nargs='+',\n        help='path of train log in json format')\n    parser_plt.add_argument(\n        '--keys',\n        type=str,\n        nargs='+',\n        default=['mAP_0.25'],\n        help='the metric that you want to plot')\n    parser_plt.add_argument('--title', type=str, help='title of figure')\n    parser_plt.add_argument(\n        '--legend',\n        type=str,\n        nargs='+',\n        default=None,\n        help='legend of each plot')\n    parser_plt.add_argument(\n        '--backend', type=str, default=None, help='backend of plt')\n    parser_plt.add_argument(\n        '--style', type=str, default='dark', help='style of plt')\n    parser_plt.add_argument('--out', type=str, default=None)\n    parser_plt.add_argument('--mode', type=str, default='train')\n    parser_plt.add_argument('--interval', type=int, default=1)\n\n\ndef add_time_parser(subparsers):\n    parser_time = subparsers.add_parser(\n        'cal_train_time',\n        help='parser for computing the average time per training iteration')\n    parser_time.add_argument(\n        'json_logs',\n        type=str,\n        nargs='+',\n        help='path of train log in json format')\n    parser_time.add_argument(\n        '--include-outliers',\n        action='store_true',\n        help='include the first value of every epoch when computing '\n        'the average time')\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Analyze Json Log')\n    # currently only support plot curve and calculate average train time\n    subparsers = parser.add_subparsers(dest='task', help='task parser')\n    add_plot_parser(subparsers)\n    add_time_parser(subparsers)\n    args = parser.parse_args()\n    return args\n\n\ndef load_json_logs(json_logs):\n    # load and convert json_logs to log_dict, key is epoch, value is a sub dict\n    # keys of sub dict is different metrics, e.g. memory, bbox_mAP\n    # value of sub dict is a list of corresponding values of all iterations\n    log_dicts = [dict() for _ in json_logs]\n    for json_log, log_dict in zip(json_logs, log_dicts):\n        with open(json_log, 'r') as log_file:\n            for line in log_file:\n                log = json.loads(line.strip())\n                # skip lines without `epoch` field\n                if 'epoch' not in log:\n                    continue\n                epoch = log.pop('epoch')\n                if epoch not in log_dict:\n                    log_dict[epoch] = defaultdict(list)\n                for k, v in log.items():\n                    log_dict[epoch][k].append(v)\n    return log_dicts\n\n\ndef main():\n    args = parse_args()\n\n    json_logs = args.json_logs\n    for json_log in json_logs:\n        assert json_log.endswith('.json')\n\n    log_dicts = load_json_logs(json_logs)\n\n    eval(args.task)(log_dicts, args)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/analysis_tools/benchmark.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport time\nimport torch\nfrom mmcv import Config\nfrom mmcv.parallel import MMDataParallel\nfrom mmcv.runner import load_checkpoint, wrap_fp16_model\nimport sys\nsys.path.append('.')\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.datasets import custom_build_dataset\n# from mmdet3d.datasets import build_dataloader, build_dataset\nfrom mmdet3d.models import build_detector\n#from tools.misc.fuse_conv_bn import fuse_module\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='MMDet benchmark a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--checkpoint', default=None, help='checkpoint file')\n    parser.add_argument('--samples', default=2000, help='samples to benchmark')\n    parser.add_argument(\n        '--log-interval', default=50, help='interval of logging')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n\n    # build the dataloader\n    # TODO: support multiple images per gpu (only minor changes are needed)\n    print(cfg.data.test)\n    dataset = custom_build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=False,\n        shuffle=False)\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    #if args.fuse_conv_bn:\n    #    model = fuse_module(model)\n\n    model = MMDataParallel(model, device_ids=[0])\n\n    model.eval()\n\n    # the first several iterations may be very slow so skip them\n    num_warmup = 5\n    pure_inf_time = 0\n\n    # benchmark with several samples and take the average\n    for i, data in enumerate(data_loader):\n        torch.cuda.synchronize()\n        start_time = time.perf_counter()\n        with torch.no_grad():\n            model(return_loss=False, rescale=True, **data)\n\n        torch.cuda.synchronize()\n        elapsed = time.perf_counter() - start_time\n\n        if i >= num_warmup:\n            pure_inf_time += elapsed\n            if (i + 1) % args.log_interval == 0:\n                fps = (i + 1 - num_warmup) / pure_inf_time\n                print(f'Done image [{i + 1:<3}/ {args.samples}], '\n                      f'fps: {fps:.1f} img / s')\n\n        if (i + 1) == args.samples:\n            pure_inf_time += elapsed\n            fps = (i + 1 - num_warmup) / pure_inf_time\n            print(f'Overall fps: {fps:.1f} img / s')\n            break\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/analysis_tools/get_flops.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nimport argparse\n\nimport torch\nfrom mmcv import Config, DictAction\n\nfrom mmdet3d.models import build_model\nfrom mmdet3d.datasets import build_dataset\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\n\n# try:\n#     from mmcv.cnn import get_model_complexity_info\n# except ImportError:\n#     raise ImportError('Please upgrade mmcv to >0.6.2')\n\nimport sys\nsys.path.append('.')\n\n\nfrom functools import partial\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nimport mmcv\n\n\ndef get_model_complexity_info(model,\n                              data,\n                              input_shape=(1280, 720),\n                              print_per_layer_stat=True,\n                              as_strings=True,\n                              input_constructor=None,\n                              flush=False,\n                              ost=sys.stdout):\n    \"\"\"Get complexity information of a model.\n\n    This method can calculate FLOPs and parameter counts of a model with\n    corresponding input shape. It can also print complexity information for\n    each layer in a model.\n\n    Supported layers are listed as below:\n        - Convolutions: ``nn.Conv1d``, ``nn.Conv2d``, ``nn.Conv3d``.\n        - Activations: ``nn.ReLU``, ``nn.PReLU``, ``nn.ELU``, ``nn.LeakyReLU``,\n            ``nn.ReLU6``.\n        - Poolings: ``nn.MaxPool1d``, ``nn.MaxPool2d``, ``nn.MaxPool3d``,\n            ``nn.AvgPool1d``, ``nn.AvgPool2d``, ``nn.AvgPool3d``,\n            ``nn.AdaptiveMaxPool1d``, ``nn.AdaptiveMaxPool2d``,\n            ``nn.AdaptiveMaxPool3d``, ``nn.AdaptiveAvgPool1d``,\n            ``nn.AdaptiveAvgPool2d``, ``nn.AdaptiveAvgPool3d``.\n        - BatchNorms: ``nn.BatchNorm1d``, ``nn.BatchNorm2d``,\n            ``nn.BatchNorm3d``, ``nn.GroupNorm``, ``nn.InstanceNorm1d``,\n            ``InstanceNorm2d``, ``InstanceNorm3d``, ``nn.LayerNorm``.\n        - Linear: ``nn.Linear``.\n        - Deconvolution: ``nn.ConvTranspose2d``.\n        - Upsample: ``nn.Upsample``.\n\n    Args:\n        model (nn.Module): The model for complexity calculation.\n        input_shape (tuple): Input shape used for calculation.\n        print_per_layer_stat (bool): Whether to print complexity information\n            for each layer in a model. Default: True.\n        as_strings (bool): Output FLOPs and params counts in a string form.\n            Default: True.\n        input_constructor (None | callable): If specified, it takes a callable\n            method that generates input. otherwise, it will generate a random\n            tensor with input shape to calculate FLOPs. Default: None.\n        flush (bool): same as that in :func:`print`. Default: False.\n        ost (stream): same as ``file`` param in :func:`print`.\n            Default: sys.stdout.\n\n    Returns:\n        tuple[float | str]: If ``as_strings`` is set to True, it will return\n            FLOPs and parameter counts in a string format. otherwise, it will\n            return those in a float number format.\n    \"\"\"\n\n    assert isinstance(model, nn.Module)\n    flops_model = add_flops_counting_methods(model)\n    flops_model.eval()\n    flops_model.start_flops_count()\n    if input_constructor:\n        input = input_constructor(input_shape)\n        _ = flops_model(**input)\n    else:\n        try:\n            batch = torch.ones(()).new_empty(\n                (1, 6, 3, *input_shape),\n                dtype=next(flops_model.parameters()).dtype,\n                device=next(flops_model.parameters()).device)\n        except StopIteration:\n            # Avoid StopIteration for models which have no parameters,\n            # like `nn.Relu()`, `nn.AvgPool2d`, etc.\n            batch = torch.ones(()).new_empty((1, 6, 3, *input_shape))\n\n        # img_metas = [data['img_metas'][0].data[0]]\n        # img = data['img'][0].data[0]\n        # points = data['points'][0].data[0][0]\n        # fut_valid_flag = data['fut_valid_flag'][0].data[0]\n        # img = img.to(batch.device)\n        # points = [points.to(batch.device)]\n        # ego_his_trajs = data['ego_his_trajs'][0].data[0].to(batch.device)\n        # ego_lcf_feat = data['ego_lcf_feat'][0].data[0].to(batch.device).unsqueeze(0)\n\n        # _ = flops_model(rescale=True, img=img, img_metas=img_metas, points=points,\n        #                 fut_valid_flag=fut_valid_flag, ego_his_trajs=ego_his_trajs, ego_lcf_feat=ego_lcf_feat)\n\n        img_metas = [data['img_metas'][0].data[0]]\n        img = data['img'][0].data[0]\n        img = img.to(batch.device)\n\n        _ = flops_model(rescale=True, img=img, img_metas=img_metas)\n\n    flops_count, params_count = flops_model.compute_average_flops_cost()\n    if print_per_layer_stat:\n        print_model_with_flops(\n            flops_model, flops_count, params_count, ost=ost, flush=flush)\n    flops_model.stop_flops_count()\n\n    if as_strings:\n        return flops_to_string(flops_count), params_to_string(params_count)\n\n    return flops_count, params_count\n\n\ndef flops_to_string(flops, units='GFLOPs', precision=2):\n    \"\"\"Convert FLOPs number into a string.\n\n    Note that Here we take a multiply-add counts as one FLOP.\n\n    Args:\n        flops (float): FLOPs number to be converted.\n        units (str | None): Converted FLOPs units. Options are None, 'GFLOPs',\n            'MFLOPs', 'KFLOPs', 'FLOPs'. If set to None, it will automatically\n            choose the most suitable unit for FLOPs. Default: 'GFLOPs'.\n        precision (int): Digit number after the decimal point. Default: 2.\n\n    Returns:\n        str: The converted FLOPs number with units.\n\n    Examples:\n        >>> flops_to_string(1e9)\n        '1.0 GFLOPs'\n        >>> flops_to_string(2e5, 'MFLOPs')\n        '0.2 MFLOPs'\n        >>> flops_to_string(3e-9, None)\n        '3e-09 FLOPs'\n    \"\"\"\n    if units is None:\n        if flops // 10**9 > 0:\n            return str(round(flops / 10.**9, precision)) + ' GFLOPs'\n        elif flops // 10**6 > 0:\n            return str(round(flops / 10.**6, precision)) + ' MFLOPs'\n        elif flops // 10**3 > 0:\n            return str(round(flops / 10.**3, precision)) + ' KFLOPs'\n        else:\n            return str(flops) + ' FLOPs'\n    else:\n        if units == 'GFLOPs':\n            return str(round(flops / 10.**9, precision)) + ' ' + units\n        elif units == 'MFLOPs':\n            return str(round(flops / 10.**6, precision)) + ' ' + units\n        elif units == 'KFLOPs':\n            return str(round(flops / 10.**3, precision)) + ' ' + units\n        else:\n            return str(flops) + ' FLOPs'\n\n\ndef params_to_string(num_params, units=None, precision=2):\n    \"\"\"Convert parameter number into a string.\n\n    Args:\n        num_params (float): Parameter number to be converted.\n        units (str | None): Converted FLOPs units. Options are None, 'M',\n            'K' and ''. If set to None, it will automatically choose the most\n            suitable unit for Parameter number. Default: None.\n        precision (int): Digit number after the decimal point. Default: 2.\n\n    Returns:\n        str: The converted parameter number with units.\n\n    Examples:\n        >>> params_to_string(1e9)\n        '1000.0 M'\n        >>> params_to_string(2e5)\n        '200.0 k'\n        >>> params_to_string(3e-9)\n        '3e-09'\n    \"\"\"\n    if units is None:\n        if num_params // 10**6 > 0:\n            return str(round(num_params / 10**6, precision)) + ' M'\n        elif num_params // 10**3:\n            return str(round(num_params / 10**3, precision)) + ' k'\n        else:\n            return str(num_params)\n    else:\n        if units == 'M':\n            return str(round(num_params / 10.**6, precision)) + ' ' + units\n        elif units == 'K':\n            return str(round(num_params / 10.**3, precision)) + ' ' + units\n        else:\n            return str(num_params)\n\n\ndef print_model_with_flops(model,\n                           total_flops,\n                           total_params,\n                           units='GFLOPs',\n                           precision=3,\n                           ost=sys.stdout,\n                           flush=False):\n    \"\"\"Print a model with FLOPs for each layer.\n\n    Args:\n        model (nn.Module): The model to be printed.\n        total_flops (float): Total FLOPs of the model.\n        total_params (float): Total parameter counts of the model.\n        units (str | None): Converted FLOPs units. Default: 'GFLOPs'.\n        precision (int): Digit number after the decimal point. Default: 3.\n        ost (stream): same as `file` param in :func:`print`.\n            Default: sys.stdout.\n        flush (bool): same as that in :func:`print`. Default: False.\n\n    Example:\n        >>> class ExampleModel(nn.Module):\n\n        >>> def __init__(self):\n        >>>     super().__init__()\n        >>>     self.conv1 = nn.Conv2d(3, 8, 3)\n        >>>     self.conv2 = nn.Conv2d(8, 256, 3)\n        >>>     self.conv3 = nn.Conv2d(256, 8, 3)\n        >>>     self.avg_pool = nn.AdaptiveAvgPool2d((1, 1))\n        >>>     self.flatten = nn.Flatten()\n        >>>     self.fc = nn.Linear(8, 1)\n\n        >>> def forward(self, x):\n        >>>     x = self.conv1(x)\n        >>>     x = self.conv2(x)\n        >>>     x = self.conv3(x)\n        >>>     x = self.avg_pool(x)\n        >>>     x = self.flatten(x)\n        >>>     x = self.fc(x)\n        >>>     return x\n\n        >>> model = ExampleModel()\n        >>> x = (3, 16, 16)\n        to print the complexity information state for each layer, you can use\n        >>> get_model_complexity_info(model, x)\n        or directly use\n        >>> print_model_with_flops(model, 4579784.0, 37361)\n        ExampleModel(\n          0.037 M, 100.000% Params, 0.005 GFLOPs, 100.000% FLOPs,\n          (conv1): Conv2d(0.0 M, 0.600% Params, 0.0 GFLOPs, 0.959% FLOPs, 3, 8, kernel_size=(3, 3), stride=(1, 1))  # noqa: E501\n          (conv2): Conv2d(0.019 M, 50.020% Params, 0.003 GFLOPs, 58.760% FLOPs, 8, 256, kernel_size=(3, 3), stride=(1, 1))\n          (conv3): Conv2d(0.018 M, 49.356% Params, 0.002 GFLOPs, 40.264% FLOPs, 256, 8, kernel_size=(3, 3), stride=(1, 1))\n          (avg_pool): AdaptiveAvgPool2d(0.0 M, 0.000% Params, 0.0 GFLOPs, 0.017% FLOPs, output_size=(1, 1))\n          (flatten): Flatten(0.0 M, 0.000% Params, 0.0 GFLOPs, 0.000% FLOPs, )\n          (fc): Linear(0.0 M, 0.024% Params, 0.0 GFLOPs, 0.000% FLOPs, in_features=8, out_features=1, bias=True)\n        )\n    \"\"\"\n\n    def accumulate_params(self):\n        if is_supported_instance(self):\n            return self.__params__\n        else:\n            sum = 0\n            for m in self.children():\n                sum += m.accumulate_params()\n            return sum\n\n    def accumulate_flops(self):\n        if is_supported_instance(self):\n            return self.__flops__ / model.__batch_counter__\n        else:\n            sum = 0\n            for m in self.children():\n                sum += m.accumulate_flops()\n            return sum\n\n    def flops_repr(self):\n        accumulated_num_params = self.accumulate_params()\n        accumulated_flops_cost = self.accumulate_flops()\n        return ', '.join([\n            params_to_string(\n                accumulated_num_params, units='M', precision=precision),\n            '{:.3%} Params'.format(accumulated_num_params / total_params),\n            flops_to_string(\n                accumulated_flops_cost, units=units, precision=precision),\n            '{:.3%} FLOPs'.format(accumulated_flops_cost / total_flops),\n            self.original_extra_repr()\n        ])\n\n    def add_extra_repr(m):\n        m.accumulate_flops = accumulate_flops.__get__(m)\n        m.accumulate_params = accumulate_params.__get__(m)\n        flops_extra_repr = flops_repr.__get__(m)\n        if m.extra_repr != flops_extra_repr:\n            m.original_extra_repr = m.extra_repr\n            m.extra_repr = flops_extra_repr\n            assert m.extra_repr != m.original_extra_repr\n\n    def del_extra_repr(m):\n        if hasattr(m, 'original_extra_repr'):\n            m.extra_repr = m.original_extra_repr\n            del m.original_extra_repr\n        if hasattr(m, 'accumulate_flops'):\n            del m.accumulate_flops\n\n    model.apply(add_extra_repr)\n    print(model, file=ost, flush=flush)\n    model.apply(del_extra_repr)\n\n\ndef get_model_parameters_number(model):\n    \"\"\"Calculate parameter number of a model.\n\n    Args:\n        model (nn.module): The model for parameter number calculation.\n\n    Returns:\n        float: Parameter number of the model.\n    \"\"\"\n    num_params = sum(p.numel() for p in model.parameters() if p.requires_grad)\n    return num_params\n\n\ndef add_flops_counting_methods(net_main_module):\n    # adding additional methods to the existing module object,\n    # this is done this way so that each function has access to self object\n    net_main_module.start_flops_count = start_flops_count.__get__(\n        net_main_module)\n    net_main_module.stop_flops_count = stop_flops_count.__get__(\n        net_main_module)\n    net_main_module.reset_flops_count = reset_flops_count.__get__(\n        net_main_module)\n    net_main_module.compute_average_flops_cost = compute_average_flops_cost.__get__(  # noqa: E501\n        net_main_module)\n\n    net_main_module.reset_flops_count()\n\n    return net_main_module\n\n\ndef compute_average_flops_cost(self):\n    \"\"\"Compute average FLOPs cost.\n\n    A method to compute average FLOPs cost, which will be available after\n    `add_flops_counting_methods()` is called on a desired net object.\n\n    Returns:\n        float: Current mean flops consumption per image.\n    \"\"\"\n    batches_count = self.__batch_counter__\n    flops_sum = 0\n    for module in self.modules():\n        if is_supported_instance(module):\n            flops_sum += module.__flops__\n    params_sum = get_model_parameters_number(self)\n    return flops_sum / batches_count, params_sum\n\n\ndef start_flops_count(self):\n    \"\"\"Activate the computation of mean flops consumption per image.\n\n    A method to activate the computation of mean flops consumption per image.\n    which will be available after ``add_flops_counting_methods()`` is called on\n    a desired net object. It should be called before running the network.\n    \"\"\"\n    add_batch_counter_hook_function(self)\n\n    def add_flops_counter_hook_function(module):\n        if is_supported_instance(module):\n            if hasattr(module, '__flops_handle__'):\n                return\n\n            else:\n                handle = module.register_forward_hook(\n                    get_modules_mapping()[type(module)])\n\n            module.__flops_handle__ = handle\n\n    self.apply(partial(add_flops_counter_hook_function))\n\n\ndef stop_flops_count(self):\n    \"\"\"Stop computing the mean flops consumption per image.\n\n    A method to stop computing the mean flops consumption per image, which will\n    be available after ``add_flops_counting_methods()`` is called on a desired\n    net object. It can be called to pause the computation whenever.\n    \"\"\"\n    remove_batch_counter_hook_function(self)\n    self.apply(remove_flops_counter_hook_function)\n\n\ndef reset_flops_count(self):\n    \"\"\"Reset statistics computed so far.\n\n    A method to Reset computed statistics, which will be available after\n    `add_flops_counting_methods()` is called on a desired net object.\n    \"\"\"\n    add_batch_counter_variables_or_reset(self)\n    self.apply(add_flops_counter_variable_or_reset)\n\n\n# ---- Internal functions\ndef empty_flops_counter_hook(module, input, output):\n    module.__flops__ += 0\n\n\ndef upsample_flops_counter_hook(module, input, output):\n    output_size = output[0]\n    batch_size = output_size.shape[0]\n    output_elements_count = batch_size\n    for val in output_size.shape[1:]:\n        output_elements_count *= val\n    module.__flops__ += int(output_elements_count)\n\n\ndef relu_flops_counter_hook(module, input, output):\n    active_elements_count = output.numel()\n    module.__flops__ += int(active_elements_count)\n\n\ndef linear_flops_counter_hook(module, input, output):\n    input = input[0]\n    output_last_dim = output.shape[\n        -1]  # pytorch checks dimensions, so here we don't care much\n    module.__flops__ += int(np.prod(input.shape) * output_last_dim)\n\n\ndef pool_flops_counter_hook(module, input, output):\n    input = input[0]\n    module.__flops__ += int(np.prod(input.shape))\n\n\ndef norm_flops_counter_hook(module, input, output):\n    input = input[0]\n\n    batch_flops = np.prod(input.shape)\n    if (getattr(module, 'affine', False)\n            or getattr(module, 'elementwise_affine', False)):\n        batch_flops *= 2\n    module.__flops__ += int(batch_flops)\n\n\ndef deconv_flops_counter_hook(conv_module, input, output):\n    # Can have multiple inputs, getting the first one\n    input = input[0]\n\n    batch_size = input.shape[0]\n    input_height, input_width = input.shape[2:]\n\n    kernel_height, kernel_width = conv_module.kernel_size\n    in_channels = conv_module.in_channels\n    out_channels = conv_module.out_channels\n    groups = conv_module.groups\n\n    filters_per_channel = out_channels // groups\n    conv_per_position_flops = (\n        kernel_height * kernel_width * in_channels * filters_per_channel)\n\n    active_elements_count = batch_size * input_height * input_width\n    overall_conv_flops = conv_per_position_flops * active_elements_count\n    bias_flops = 0\n    if conv_module.bias is not None:\n        output_height, output_width = output.shape[2:]\n        bias_flops = out_channels * batch_size * output_height * output_height\n    overall_flops = overall_conv_flops + bias_flops\n\n    conv_module.__flops__ += int(overall_flops)\n\n\ndef conv_flops_counter_hook(conv_module, input, output):\n    # Can have multiple inputs, getting the first one\n    input = input[0]\n\n    batch_size = input.shape[0]\n    output_dims = list(output.shape[2:])\n\n    kernel_dims = list(conv_module.kernel_size)\n    in_channels = conv_module.in_channels\n    out_channels = conv_module.out_channels\n    groups = conv_module.groups\n\n    filters_per_channel = out_channels // groups\n    conv_per_position_flops = int(\n        np.prod(kernel_dims)) * in_channels * filters_per_channel\n\n    active_elements_count = batch_size * int(np.prod(output_dims))\n\n    overall_conv_flops = conv_per_position_flops * active_elements_count\n\n    bias_flops = 0\n\n    if conv_module.bias is not None:\n\n        bias_flops = out_channels * active_elements_count\n\n    overall_flops = overall_conv_flops + bias_flops\n\n    conv_module.__flops__ += int(overall_flops)\n\n\ndef batch_counter_hook(module, input, output):\n    batch_size = 1\n    if len(input) > 0:\n        # Can have multiple inputs, getting the first one\n        input = input[0]\n        batch_size = len(input)\n    else:\n        pass\n        print('Warning! No positional inputs found for a module, '\n              'assuming batch size is 1.')\n    module.__batch_counter__ += batch_size\n\n\ndef add_batch_counter_variables_or_reset(module):\n\n    module.__batch_counter__ = 0\n\n\ndef add_batch_counter_hook_function(module):\n    if hasattr(module, '__batch_counter_handle__'):\n        return\n\n    handle = module.register_forward_hook(batch_counter_hook)\n    module.__batch_counter_handle__ = handle\n\n\ndef remove_batch_counter_hook_function(module):\n    if hasattr(module, '__batch_counter_handle__'):\n        module.__batch_counter_handle__.remove()\n        del module.__batch_counter_handle__\n\n\ndef add_flops_counter_variable_or_reset(module):\n    if is_supported_instance(module):\n        if hasattr(module, '__flops__') or hasattr(module, '__params__'):\n            print('Warning: variables __flops__ or __params__ are already '\n                  'defined for the module' + type(module).__name__ +\n                  ' ptflops can affect your code!')\n        module.__flops__ = 0\n        module.__params__ = get_model_parameters_number(module)\n\n\ndef is_supported_instance(module):\n    if type(module) in get_modules_mapping():\n        return True\n    return False\n\n\ndef remove_flops_counter_hook_function(module):\n    if is_supported_instance(module):\n        if hasattr(module, '__flops_handle__'):\n            module.__flops_handle__.remove()\n            del module.__flops_handle__\n\n\ndef get_modules_mapping():\n    return {\n        # convolutions\n        nn.Conv1d: conv_flops_counter_hook,\n        nn.Conv2d: conv_flops_counter_hook,\n        mmcv.cnn.bricks.Conv2d: conv_flops_counter_hook,\n        nn.Conv3d: conv_flops_counter_hook,\n        mmcv.cnn.bricks.Conv3d: conv_flops_counter_hook,\n        # activations\n        nn.ReLU: relu_flops_counter_hook,\n        nn.PReLU: relu_flops_counter_hook,\n        nn.ELU: relu_flops_counter_hook,\n        nn.LeakyReLU: relu_flops_counter_hook,\n        nn.ReLU6: relu_flops_counter_hook,\n        # poolings\n        nn.MaxPool1d: pool_flops_counter_hook,\n        nn.AvgPool1d: pool_flops_counter_hook,\n        nn.AvgPool2d: pool_flops_counter_hook,\n        nn.MaxPool2d: pool_flops_counter_hook,\n        mmcv.cnn.bricks.MaxPool2d: pool_flops_counter_hook,\n        nn.MaxPool3d: pool_flops_counter_hook,\n        mmcv.cnn.bricks.MaxPool3d: pool_flops_counter_hook,\n        nn.AvgPool3d: pool_flops_counter_hook,\n        nn.AdaptiveMaxPool1d: pool_flops_counter_hook,\n        nn.AdaptiveAvgPool1d: pool_flops_counter_hook,\n        nn.AdaptiveMaxPool2d: pool_flops_counter_hook,\n        nn.AdaptiveAvgPool2d: pool_flops_counter_hook,\n        nn.AdaptiveMaxPool3d: pool_flops_counter_hook,\n        nn.AdaptiveAvgPool3d: pool_flops_counter_hook,\n        # normalizations\n        nn.BatchNorm1d: norm_flops_counter_hook,\n        nn.BatchNorm2d: norm_flops_counter_hook,\n        nn.BatchNorm3d: norm_flops_counter_hook,\n        nn.GroupNorm: norm_flops_counter_hook,\n        nn.InstanceNorm1d: norm_flops_counter_hook,\n        nn.InstanceNorm2d: norm_flops_counter_hook,\n        nn.InstanceNorm3d: norm_flops_counter_hook,\n        nn.LayerNorm: norm_flops_counter_hook,\n        # FC\n        nn.Linear: linear_flops_counter_hook,\n        mmcv.cnn.bricks.Linear: linear_flops_counter_hook,\n        # Upscale\n        nn.Upsample: upsample_flops_counter_hook,\n        # Deconvolution\n        nn.ConvTranspose2d: deconv_flops_counter_hook,\n        mmcv.cnn.bricks.ConvTranspose2d: deconv_flops_counter_hook,\n    }\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Train a detector')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument(\n        '--shape',\n        type=int,\n        nargs='+',\n        default=[40000, 4],\n        help='input point cloud size')\n    parser.add_argument(\n        '--modality',\n        type=str,\n        default='point',\n        choices=['point', 'image', 'multi'],\n        help='input data modality')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n\n    args = parse_args()\n\n    if args.modality == 'point':\n        assert len(args.shape) == 2, 'invalid input shape'\n        input_shape = tuple(args.shape)\n    elif args.modality == 'image':\n        if len(args.shape) == 1:\n            input_shape = (3, args.shape[0], args.shape[0])\n        elif len(args.shape) == 2:\n            input_shape = (3, ) + tuple(args.shape)\n        else:\n            raise ValueError('invalid input shape')\n    elif args.modality == 'multi':\n        raise NotImplementedError(\n            'FLOPs counter is currently not supported for models with '\n            'multi-modality input')\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n\n    if hasattr(cfg, 'plugin'):\n        if cfg.plugin:\n            import importlib\n            if hasattr(cfg, 'plugin_dir'):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split('/')\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + '.' + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split('/')\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + '.' + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n\n    samples_per_gpu = 1\n    from mmdet.datasets import replace_ImageToTensor\n    if isinstance(cfg.data.test, dict):\n        cfg.data.test.test_mode = True\n        samples_per_gpu = cfg.data.test.pop('samples_per_gpu', 1)\n        if samples_per_gpu > 1:\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.test.pipeline = replace_ImageToTensor(\n                cfg.data.test.pipeline)\n    elif isinstance(cfg.data.test, list):\n        for ds_cfg in cfg.data.test:\n            ds_cfg.test_mode = True\n        samples_per_gpu = max(\n            [ds_cfg.pop('samples_per_gpu', 1) for ds_cfg in cfg.data.test])\n        if samples_per_gpu > 1:\n            for ds_cfg in cfg.data.test:\n                ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)\n\n    dataset = build_dataset(cfg.data.test)\n    dataset.is_vis_on_test = True #TODO, this is a hack\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=0,\n        dist=False,\n        shuffle=False,\n        nonshuffler_sampler=cfg.data.nonshuffler_sampler,\n    )\n    for i, data in enumerate(data_loader):\n        # if ~(data['map_gt_labels_3d'].data[0][0] != -1).any():\n        #     continue\n        img = data['img'][0].data[0]\n        img_metas = data['img_metas'][0].data[0]\n        break\n\n    model = build_model(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    if torch.cuda.is_available():\n        model.cuda()\n    model.eval()\n\n    if hasattr(model, 'forward_dummy'):\n        model.forward = model.forward_dummy\n    else:\n        raise NotImplementedError(\n            'FLOPs counter is currently not supported for {}'.format(\n                model.__class__.__name__))\n\n    flops, params = get_model_complexity_info(model, data)\n    split_line = '=' * 30\n    print(f'{split_line}\\nInput shape: {input_shape}\\n'\n          f'Flops: {flops}\\nParams: {params}\\n{split_line}')\n    print('!!!Please be cautious if you use the results in papers. '\n          'You may need to check if all ops are supported and verify that the '\n          'flops computation is correct.')\n\n\nif __name__ == '__main__':\n    main()"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/analysis_tools/get_params.py",
    "content": "import torch\nYOUR_CKPT_PATH = None\nfile_path = YOUR_CKPT_PATH\nmodel = torch.load(file_path, map_location='cpu')\nall = 0\nfor key in list(model['state_dict'].keys()):\n    all += model['state_dict'][key].nelement()\nprint(all)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/analysis_tools/visualization.py",
    "content": "import sys\nsys.path.append('')\nimport os\nimport argparse\nimport os.path as osp\nfrom PIL import Image\nfrom tqdm import tqdm\nfrom typing import List, Dict\n\nimport cv2\nimport mmcv\nimport torch\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom matplotlib import rcParams\nfrom pyquaternion import Quaternion\nfrom nuscenes.nuscenes import NuScenes\nfrom mmdet.datasets.pipelines import to_tensor\nfrom matplotlib.collections import LineCollection\nfrom nuscenes.utils.data_classes import LidarPointCloud, Box\nfrom nuscenes.eval.common.data_classes import EvalBoxes, EvalBox\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility\n\nfrom projects.mmdet3d_plugin.core.bbox.structures.nuscenes_box import CustomNuscenesBox, CustomDetectionBox, color_map\nfrom projects.mmdet3d_plugin.datasets.nuscenes_vad_dataset import VectorizedLocalMap, LiDARInstanceLines\n\n\ncams = ['CAM_FRONT',\n 'CAM_FRONT_RIGHT',\n 'CAM_BACK_RIGHT',\n 'CAM_BACK',\n 'CAM_BACK_LEFT',\n 'CAM_FRONT_LEFT']\n\n\ndef render_annotation(\n        anntoken: str,\n        margin: float = 10,\n        view: np.ndarray = np.eye(4),\n        box_vis_level: BoxVisibility = BoxVisibility.ANY,\n        out_path: str = 'render.png',\n        extra_info: bool = False) -> None:\n    \"\"\"\n    Render selected annotation.\n    :param anntoken: Sample_annotation token.\n    :param margin: How many meters in each direction to include in LIDAR view.\n    :param view: LIDAR view point.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param out_path: Optional path to save the rendered figure to disk.\n    :param extra_info: Whether to render extra information below camera view.\n    \"\"\"\n    ann_record = nusc.get('sample_annotation', anntoken)\n    sample_record = nusc.get('sample', ann_record['sample_token'])\n    assert 'LIDAR_TOP' in sample_record['data'].keys(), 'Error: No LIDAR_TOP in data, unable to render.'\n\n    # Figure out which camera the object is fully visible in (this may return nothing).\n    boxes, cam = [], []\n    cams = [key for key in sample_record['data'].keys() if 'CAM' in key]\n    all_bboxes = []\n    select_cams = []\n    for cam in cams:\n        _, boxes, _ = nusc.get_sample_data(sample_record['data'][cam], box_vis_level=box_vis_level,\n                                           selected_anntokens=[anntoken])\n        if len(boxes) > 0:\n            all_bboxes.append(boxes)\n            select_cams.append(cam)\n            # We found an image that matches. Let's abort.\n    # assert len(boxes) > 0, 'Error: Could not find image where annotation is visible. ' \\\n    #                      'Try using e.g. BoxVisibility.ANY.'\n    # assert len(boxes) < 2, 'Error: Found multiple annotations. Something is wrong!'\n\n    num_cam = len(all_bboxes)\n\n    fig, axes = plt.subplots(1, num_cam + 1, figsize=(18, 9))\n    select_cams = [sample_record['data'][cam] for cam in select_cams]\n    print('bbox in cams:', select_cams)\n    # Plot LIDAR view.\n    lidar = sample_record['data']['LIDAR_TOP']\n    data_path, boxes, camera_intrinsic = nusc.get_sample_data(lidar, selected_anntokens=[anntoken])\n    LidarPointCloud.from_file(data_path).render_height(axes[0], view=view)\n    for box in boxes:\n        c = np.array(get_color(box.name)) / 255.0\n        box.render(axes[0], view=view, colors=(c, c, c))\n        corners = view_points(boxes[0].corners(), view, False)[:2, :]\n        axes[0].set_xlim([np.min(corners[0, :]) - margin, np.max(corners[0, :]) + margin])\n        axes[0].set_ylim([np.min(corners[1, :]) - margin, np.max(corners[1, :]) + margin])\n        axes[0].axis('off')\n        axes[0].set_aspect('equal')\n\n    # Plot CAMERA view.\n    for i in range(1, num_cam + 1):\n        cam = select_cams[i - 1]\n        data_path, boxes, camera_intrinsic = nusc.get_sample_data(cam, selected_anntokens=[anntoken])\n        im = Image.open(data_path)\n        axes[i].imshow(im)\n        axes[i].set_title(nusc.get('sample_data', cam)['channel'])\n        axes[i].axis('off')\n        axes[i].set_aspect('equal')\n        for box in boxes:\n            c = np.array(get_color(box.name)) / 255.0\n            box.render(axes[i], view=camera_intrinsic, normalize=True, colors=(c, c, c))\n\n        # Print extra information about the annotation below the camera view.\n        axes[i].set_xlim(0, im.size[0])\n        axes[i].set_ylim(im.size[1], 0)\n\n    if extra_info:\n        rcParams['font.family'] = 'monospace'\n\n        w, l, h = ann_record['size']\n        category = ann_record['category_name']\n        lidar_points = ann_record['num_lidar_pts']\n        radar_points = ann_record['num_radar_pts']\n\n        sample_data_record = nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])\n        pose_record = nusc.get('ego_pose', sample_data_record['ego_pose_token'])\n        dist = np.linalg.norm(np.array(pose_record['translation']) - np.array(ann_record['translation']))\n\n        information = ' \\n'.join(['category: {}'.format(category),\n                                  '',\n                                  '# lidar points: {0:>4}'.format(lidar_points),\n                                  '# radar points: {0:>4}'.format(radar_points),\n                                  '',\n                                  'distance: {:>7.3f}m'.format(dist),\n                                  '',\n                                  'width:  {:>7.3f}m'.format(w),\n                                  'length: {:>7.3f}m'.format(l),\n                                  'height: {:>7.3f}m'.format(h)])\n\n        plt.annotate(information, (0, 0), (0, -20), xycoords='axes fraction', textcoords='offset points', va='top')\n\n    if out_path is not None:\n        plt.savefig(out_path)\n\n\ndef get_sample_data(sample_data_token: str,\n                    box_vis_level: BoxVisibility = BoxVisibility.ANY,\n                    selected_anntokens=None,\n                    use_flat_vehicle_coordinates: bool = False):\n    \"\"\"\n    Returns the data path as well as all annotations related to that sample_data.\n    Note that the boxes are transformed into the current sensor's coordinate frame.\n    :param sample_data_token: Sample_data token.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param selected_anntokens: If provided only return the selected annotation.\n    :param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is\n                                         aligned to z-plane in the world.\n    :return: (data_path, boxes, camera_intrinsic <np.array: 3, 3>)\n    \"\"\"\n\n    # Retrieve sensor & pose records\n    sd_record = nusc.get('sample_data', sample_data_token)\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n\n    data_path = nusc.get_sample_data_path(sample_data_token)\n\n    if sensor_record['modality'] == 'camera':\n        cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n        imsize = (sd_record['width'], sd_record['height'])\n    else:\n        cam_intrinsic = None\n        imsize = None\n\n    # Retrieve all sample annotations and map to sensor coordinate system.\n    if selected_anntokens is not None:\n        boxes = list(map(nusc.get_box, selected_anntokens))\n    else:\n        boxes = nusc.get_boxes(sample_data_token)\n\n    # Make list of Box objects including coord system transforms.\n    box_list = []\n    for box in boxes:\n        if use_flat_vehicle_coordinates:\n            # Move box to ego vehicle coord system parallel to world z plane.\n            yaw = Quaternion(pose_record['rotation']).yaw_pitch_roll[0]\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(scalar=np.cos(yaw / 2), vector=[0, 0, np.sin(yaw / 2)]).inverse)\n        else:\n            # Move box to ego vehicle coord system.\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n            #  Move box to sensor coord system.\n            box.translate(-np.array(cs_record['translation']))\n            box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n        if sensor_record['modality'] == 'camera' and not \\\n                box_in_image(box, cam_intrinsic, imsize, vis_level=box_vis_level):\n            continue\n\n        box_list.append(box)\n\n    return data_path, box_list, cam_intrinsic\n\n\ndef get_predicted_data(sample_data_token: str,\n                       box_vis_level: BoxVisibility = BoxVisibility.ANY,\n                       selected_anntokens=None,\n                       use_flat_vehicle_coordinates: bool = False,\n                       pred_anns=None\n                       ):\n    \"\"\"\n    Returns the data path as well as all annotations related to that sample_data.\n    Note that the boxes are transformed into the current sensor's coordinate frame.\n    :param sample_data_token: Sample_data token.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param selected_anntokens: If provided only return the selected annotation.\n    :param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is\n                                         aligned to z-plane in the world.\n    :return: (data_path, boxes, camera_intrinsic <np.array: 3, 3>)\n    \"\"\"\n\n    # Retrieve sensor & pose records\n    sd_record = nusc.get('sample_data', sample_data_token)\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n\n    data_path = nusc.get_sample_data_path(sample_data_token)\n\n    if sensor_record['modality'] == 'camera':\n        cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n        imsize = (sd_record['width'], sd_record['height'])\n    else:\n        cam_intrinsic = None\n        imsize = None\n\n    # Retrieve all sample annotations and map to sensor coordinate system.\n    # if selected_anntokens is not None:\n    #    boxes = list(map(nusc.get_box, selected_anntokens))\n    # else:\n    #    boxes = nusc.get_boxes(sample_data_token)\n    boxes = pred_anns\n    # Make list of Box objects including coord system transforms.\n    box_list = []\n    for box in boxes:\n        if use_flat_vehicle_coordinates:\n            # Move box to ego vehicle coord system parallel to world z plane.\n            yaw = Quaternion(pose_record['rotation']).yaw_pitch_roll[0]\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(scalar=np.cos(yaw / 2), vector=[0, 0, np.sin(yaw / 2)]).inverse)\n        else:\n            # Move box to ego vehicle coord system.\n            box.translate(-np.array(pose_record['translation']))\n            box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n            #  Move box to sensor coord system.\n            box.translate(-np.array(cs_record['translation']))\n            box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n        if sensor_record['modality'] == 'camera' and not \\\n                box_in_image(box, cam_intrinsic, imsize, vis_level=box_vis_level):\n            continue\n        box_list.append(box)\n\n    return data_path, box_list, cam_intrinsic\n\n\ndef lidiar_render(sample_token, data, out_path=None, out_name=None, traj_use_perstep_offset=True):\n    bbox_gt_list = []\n    bbox_pred_list = []\n    sample_rec = nusc.get('sample', sample_token)\n    anns = sample_rec['anns']\n    sd_record = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n\n    for ann in anns:\n        content = nusc.get('sample_annotation', ann)\n        gt_fut_trajs, gt_fut_masks = get_gt_fut_trajs(\n            nusc=nusc, anno=content, cs_record=cs_record, \n            pose_record=pose_record, fut_ts=6\n        )\n        try:\n            bbox_gt_list.append(CustomDetectionBox(\n                sample_token=content['sample_token'],\n                translation=tuple(content['translation']),\n                size=tuple(content['size']),\n                rotation=tuple(content['rotation']),\n                velocity=nusc.box_velocity(content['token'])[:2],\n                fut_trajs=tuple(gt_fut_trajs),\n                ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                else tuple(content['ego_translation']),\n                num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                detection_name=category_to_detection_name(content['category_name']),\n                detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                attribute_name=''))\n        except:\n            pass\n\n    bbox_anns = data['results'][sample_token]\n    for content in bbox_anns:\n        bbox_pred_list.append(CustomDetectionBox(\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            fut_trajs=tuple(content['fut_traj']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name']))\n    gt_annotations = EvalBoxes()\n    pred_annotations = EvalBoxes()\n    gt_annotations.add_boxes(sample_token, bbox_gt_list)\n    pred_annotations.add_boxes(sample_token, bbox_pred_list)\n    # print('green is ground truth')\n    # print('blue is the predited result')\n    visualize_sample(nusc, sample_token, gt_annotations, pred_annotations,\n                     savepath=out_path, traj_use_perstep_offset=traj_use_perstep_offset, pred_data=data)\n\n\ndef get_color(category_name: str):\n    \"\"\"\n    Provides the default colors based on the category names.\n    This method works for the general nuScenes categories, as well as the nuScenes detection categories.\n    \"\"\"\n    a = ['noise', 'animal', 'human.pedestrian.adult', 'human.pedestrian.child', 'human.pedestrian.construction_worker',\n     'human.pedestrian.personal_mobility', 'human.pedestrian.police_officer', 'human.pedestrian.stroller',\n     'human.pedestrian.wheelchair', 'movable_object.barrier', 'movable_object.debris',\n     'movable_object.pushable_pullable', 'movable_object.trafficcone', 'static_object.bicycle_rack', 'vehicle.bicycle',\n     'vehicle.bus.bendy', 'vehicle.bus.rigid', 'vehicle.car', 'vehicle.construction', 'vehicle.emergency.ambulance',\n     'vehicle.emergency.police', 'vehicle.motorcycle', 'vehicle.trailer', 'vehicle.truck', 'flat.driveable_surface',\n     'flat.other', 'flat.sidewalk', 'flat.terrain', 'static.manmade', 'static.other', 'static.vegetation',\n     'vehicle.ego']\n    class_names = [\n        'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n        'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n    ]\n    #print(category_name)\n    if category_name == 'bicycle':\n        return nusc.colormap['vehicle.bicycle']\n    elif category_name == 'construction_vehicle':\n        return nusc.colormap['vehicle.construction']\n    elif category_name == 'traffic_cone':\n        return nusc.colormap['movable_object.trafficcone']\n\n    for key in nusc.colormap.keys():\n        if category_name in key:\n            return nusc.colormap[key]\n    return [0, 0, 0]\n\n# TODO: whether to rotate traj\ndef boxes_to_sensor(boxes: List[EvalBox], pose_record: Dict, cs_record: Dict):\n    \"\"\"\n    Map boxes from global coordinates to the vehicle's sensor coordinate system.\n    :param boxes: The boxes in global coordinates.\n    :param pose_record: The pose record of the vehicle at the current timestamp.\n    :param cs_record: The calibrated sensor record of the sensor.\n    :return: The transformed boxes.\n    \"\"\"\n    boxes_out = []\n    for box in boxes:\n        # Create Box instance.\n        box = CustomNuscenesBox(\n            box.translation, box.size, Quaternion(box.rotation), box.fut_trajs, name=box.detection_name\n        )\n        # Move box to ego vehicle coord system.\n        box.translate(-np.array(pose_record['translation']))\n        box.rotate(Quaternion(pose_record['rotation']).inverse)\n        # Move box to sensor coord system.\n        box.translate(-np.array(cs_record['translation']))\n        box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n        boxes_out.append(box)\n\n    return boxes_out\n\n\ndef get_gt_fut_trajs(nusc: NuScenes,\n                     anno,\n                     cs_record,\n                     pose_record,\n                     fut_ts) -> None:\n    \"\"\"\n    Visualizes a sample from BEV with annotations and detection results.\n    :param nusc: NuScenes object.\n    \"\"\"\n    box = Box(anno['translation'], anno['size'], Quaternion(anno['rotation']))\n    # Move box to ego vehicle coord system.\n    box.translate(-np.array(pose_record['translation']))\n    box.rotate(Quaternion(pose_record['rotation']).inverse)\n    #  Move box to sensor coord system.\n    box.translate(-np.array(cs_record['translation']))\n    box.rotate(Quaternion(cs_record['rotation']).inverse)\n    \n    # get future trajectory coords for each box\n    gt_fut_trajs = np.zeros((fut_ts, 2))  # [fut_ts*2]\n    gt_fut_masks = np.zeros((fut_ts))  # [fut_ts]\n    gt_fut_trajs[:] = box.center[:2]\n    cur_box = box\n    cur_anno = anno\n    for i in range(fut_ts):\n        if cur_anno['next'] != '':\n            anno_next = nusc.get('sample_annotation', cur_anno['next'])\n            box_next = Box(\n                anno_next['translation'], anno_next['size'], Quaternion(anno_next['rotation'])\n            )\n            # Move box to ego vehicle coord system.\n            box_next.translate(-np.array(pose_record['translation']))\n            box_next.rotate(Quaternion(pose_record['rotation']).inverse)\n            #  Move box to sensor coord system.\n            box_next.translate(-np.array(cs_record['translation']))\n            box_next.rotate(Quaternion(cs_record['rotation']).inverse)\n            # gt_fut_trajs[i] = box_next.center[:2]\n            gt_fut_trajs[i] = box_next.center[:2] - cur_box.center[:2]\n            gt_fut_masks[i] = 1\n            cur_anno = anno_next\n            cur_box = box_next\n        else:\n            # gt_fut_trajs[i:] = gt_fut_trajs[i-1]\n            gt_fut_trajs[i:] = 0\n            break         \n\n    return gt_fut_trajs.reshape(-1).tolist(), gt_fut_masks.reshape(-1).tolist()\n\ndef get_gt_vec_maps(\n    sample_token,\n    data_root='data/nuscenes/',\n    pc_range=[-15.0, -30.0, -4.0, 15.0, 30.0, 4.0],\n    padding_value=-10000,\n    map_classes=['divider', 'ped_crossing', 'boundary'],\n    map_fixed_ptsnum_per_line=20\n) -> None:\n    \"\"\"\n    Get gt vec map for a given sample.\n    \"\"\"\n    sample_rec = nusc.get('sample', sample_token)\n    sd_record = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n    lidar2ego_translation = cs_record['translation'],\n    lidar2ego_rotation = cs_record['rotation'],\n    ego2global_translation = pose_record['translation'],\n    ego2global_rotation = pose_record['rotation'],\n    map_location = nusc.get('log', nusc.get('scene', sample_rec['scene_token'])['log_token'])['location']\n\n    lidar2ego = np.eye(4)\n    lidar2ego[:3,:3] = Quaternion(cs_record['rotation']).rotation_matrix\n    lidar2ego[:3, 3] = cs_record['translation']\n    ego2global = np.eye(4)\n    ego2global[:3,:3] = Quaternion(pose_record['rotation']).rotation_matrix\n    ego2global[:3, 3] = pose_record['translation']\n    lidar2global = ego2global @ lidar2ego\n    lidar2global_translation = list(lidar2global[:3,3])\n    lidar2global_rotation = list(Quaternion(matrix=lidar2global).q)\n    patch_h = pc_range[4]-pc_range[1]\n    patch_w = pc_range[3]-pc_range[0]\n    patch_size = (patch_h, patch_w)\n\n    vector_map = VectorizedLocalMap(data_root, patch_size=patch_size,\n                                    map_classes=map_classes, \n                                    fixed_ptsnum_per_line=map_fixed_ptsnum_per_line,\n                                    padding_value=padding_value)\n\n\n    anns_results = vector_map.gen_vectorized_samples(\n        map_location, lidar2global_translation, lidar2global_rotation\n    )\n    \n    '''\n    anns_results, type: dict\n        'gt_vecs_pts_loc': list[num_vecs], vec with num_points*2 coordinates\n        'gt_vecs_pts_num': list[num_vecs], vec with num_points\n        'gt_vecs_label': list[num_vecs], vec with cls index\n    '''\n    gt_vecs_label = to_tensor(anns_results['gt_vecs_label'])\n    if isinstance(anns_results['gt_vecs_pts_loc'], LiDARInstanceLines):\n        gt_vecs_pts_loc = anns_results['gt_vecs_pts_loc']\n    else:\n        gt_vecs_pts_loc = to_tensor(anns_results['gt_vecs_pts_loc'])\n        try:\n            gt_vecs_pts_loc = gt_vecs_pts_loc.flatten(1).to(dtype=torch.float32)\n        except:\n            gt_vecs_pts_loc = gt_vecs_pts_loc\n    \n    return gt_vecs_pts_loc, gt_vecs_label\n\n\ndef visualize_sample(nusc: NuScenes,\n                     sample_token: str,\n                     gt_boxes: EvalBoxes,\n                     pred_boxes: EvalBoxes,\n                     nsweeps: int = 1,\n                     conf_th: float = 0.4,\n                     pc_range: list = [-30.0, -30.0, -4.0, 30.0, 30.0, 4.0],\n                     verbose: bool = True,\n                     savepath: str = None,\n                     traj_use_perstep_offset: bool = True,\n                     data_root='data/nuscenes/',\n                     map_pc_range: list = [-15.0, -30.0, -4.0, 15.0, 30.0, 4.0],\n                     padding_value=-10000,\n                     map_classes=['divider', 'ped_crossing', 'boundary'],\n                     map_fixed_ptsnum_per_line=20,\n                     gt_format=['fixed_num_pts'],\n                     colors_plt = ['cornflowerblue', 'royalblue', 'slategrey'],\n                     pred_data = None) -> None:\n    \"\"\"\n    Visualizes a sample from BEV with annotations and detection results.\n    :param nusc: NuScenes object.\n    :param sample_token: The nuScenes sample token.\n    :param gt_boxes: Ground truth boxes grouped by sample.\n    :param pred_boxes: Prediction grouped by sample.\n    :param nsweeps: Number of sweeps used for lidar visualization.\n    :param conf_th: The confidence threshold used to filter negatives.\n    :param eval_range: Range in meters beyond which boxes are ignored.\n    :param verbose: Whether to print to stdout.\n    :param savepath: If given, saves the the rendering here instead of displaying.\n    \"\"\"\n    # Retrieve sensor & pose records.\n    sample_rec = nusc.get('sample', sample_token)\n    sd_record = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n    cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n    # Get boxes.\n    boxes_gt_global = gt_boxes[sample_token]\n    boxes_est_global = pred_boxes[sample_token]\n    # Map GT boxes to lidar.\n    boxes_gt = boxes_to_sensor(boxes_gt_global, pose_record, cs_record)\n    # Map EST boxes to lidar.\n    boxes_est = boxes_to_sensor(boxes_est_global, pose_record, cs_record)\n    # Add scores to EST boxes.\n    for box_est, box_est_global in zip(boxes_est, boxes_est_global):\n        box_est.score = box_est_global.detection_score\n\n    # Init axes.\n    fig, axes = plt.subplots(1, 1, figsize=(4, 4))\n    plt.xlim(xmin=-30, xmax=30)\n    plt.ylim(ymin=-30, ymax=30)\n\n    # Show Pred Map\n    result_dic = pred_data['map_results'][sample_token]['vectors']\n\n    for vector in result_dic:\n        if vector['confidence_level'] < 0.6:\n            continue\n        pred_pts_3d = vector['pts']\n        pred_label_3d = vector['type']\n        pts_x = np.array([pt[0] for pt in pred_pts_3d])\n        pts_y = np.array([pt[1] for pt in pred_pts_3d])\n\n        axes.plot(pts_x, pts_y, color=colors_plt[pred_label_3d],linewidth=1,alpha=0.8,zorder=-1)\n        axes.scatter(pts_x, pts_y, color=colors_plt[pred_label_3d],s=1,alpha=0.8,zorder=-1)  \n\n    # ignore_list = ['barrier', 'motorcycle', 'bicycle', 'traffic_cone']\n    ignore_list = ['barrier', 'bicycle', 'traffic_cone']\n\n    # Show Pred boxes.\n    for i, box in enumerate(boxes_est):\n        if box.name in ignore_list:\n            continue\n        # Show only predictions with a high score.\n        assert not np.isnan(box.score), 'Error: Box score cannot be NaN!'\n        if box.score < conf_th or abs(box.center[0]) > 15 or abs(box.center[1]) > 30:\n            continue\n        box.render(axes, view=np.eye(4), colors=('tomato', 'tomato', 'tomato'), linewidth=1, box_idx=None)\n        # if box.name in ['pedestrian']:\n        #     continue\n        if traj_use_perstep_offset:\n            mode_idx = [0, 1, 2, 3, 4, 5]\n            box.render_fut_trajs_grad_color(axes, linewidth=1, mode_idx=mode_idx, fut_ts=6, cmap='autumn')\n        else:\n            box.render_fut_trajs_coords(axes, color='tomato', linewidth=1)\n\n    # Show Planning.\n    axes.plot([-0.9, -0.9], [-2, 2], color='mediumseagreen', linewidth=1, alpha=0.8)\n    axes.plot([-0.9, 0.9], [2, 2], color='mediumseagreen', linewidth=1, alpha=0.8)\n    axes.plot([0.9, 0.9], [2, -2], color='mediumseagreen', linewidth=1, alpha=0.8)\n    axes.plot([0.9, -0.9], [-2, -2], color='mediumseagreen', linewidth=1, alpha=0.8)\n    axes.plot([0.0, 0.0], [0.0, 2], color='mediumseagreen', linewidth=1, alpha=0.8)\n    plan_cmd = np.argmax(pred_data['plan_results'][sample_token][1][0,0,0])\n    plan_traj = pred_data['plan_results'][sample_token][0][plan_cmd]\n    plan_traj[abs(plan_traj) < 0.01] = 0.0\n    plan_traj = plan_traj.cumsum(axis=0)\n    plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n    plan_traj = np.stack((plan_traj[:-1], plan_traj[1:]), axis=1)\n\n    plan_vecs = None\n    for i in range(plan_traj.shape[0]):\n        plan_vec_i = plan_traj[i]\n        x_linspace = np.linspace(plan_vec_i[0, 0], plan_vec_i[1, 0], 51)\n        y_linspace = np.linspace(plan_vec_i[0, 1], plan_vec_i[1, 1], 51)\n        xy = np.stack((x_linspace, y_linspace), axis=1)\n        xy = np.stack((xy[:-1], xy[1:]), axis=1)\n        if plan_vecs is None:\n            plan_vecs = xy\n        else:\n            plan_vecs = np.concatenate((plan_vecs, xy), axis=0)\n\n    cmap = 'winter'\n    y = np.sin(np.linspace(1/2*np.pi, 3/2*np.pi, 301))\n    colors = color_map(y[:-1], cmap)\n    line_segments = LineCollection(plan_vecs, colors=colors, linewidths=1, linestyles='solid', cmap=cmap)\n    axes.add_collection(line_segments)\n\n    axes.axes.xaxis.set_ticks([])\n    axes.axes.yaxis.set_ticks([])\n    axes.axis('off')\n    fig.set_tight_layout(True)\n    fig.canvas.draw()\n    plt.savefig(savepath+'/bev_pred.png', bbox_inches='tight', dpi=200)\n    plt.close()\n\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sensor2lidar_rotation = R.T  # points @ R.T + T\n    sensor2lidar_translation = T\n\n    return sensor2lidar_rotation, sensor2lidar_translation\n\ndef render_sample_data(\n        sample_toekn: str,\n        with_anns: bool = True,\n        box_vis_level: BoxVisibility = BoxVisibility.ANY,\n        axes_limit: float = 40,\n        ax=None,\n        nsweeps: int = 1,\n        out_path: str = None,\n        out_name: str = None,\n        underlay_map: bool = True,\n        use_flat_vehicle_coordinates: bool = True,\n        show_lidarseg: bool = False,\n        show_lidarseg_legend: bool = False,\n        filter_lidarseg_labels=None,\n        lidarseg_preds_bin_path: str = None,\n        verbose: bool = True,\n        show_panoptic: bool = False,\n        pred_data=None,\n        traj_use_perstep_offset: bool = True\n      ) -> None:\n    \"\"\"\n    Render sample data onto axis.\n    :param sample_data_token: Sample_data token.\n    :param with_anns: Whether to draw box annotations.\n    :param box_vis_level: If sample_data is an image, this sets required visibility for boxes.\n    :param axes_limit: Axes limit for lidar and radar (measured in meters).\n    :param ax: Axes onto which to render.\n    :param nsweeps: Number of sweeps for lidar and radar.\n    :param out_path: Optional path to save the rendered figure to disk.\n    :param underlay_map: When set to true, lidar data is plotted onto the map. This can be slow.\n    :param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is\n        aligned to z-plane in the world. Note: Previously this method did not use flat vehicle coordinates, which\n        can lead to small errors when the vertical axis of the global frame and lidar are not aligned. The new\n        setting is more correct and rotates the plot by ~90 degrees.\n    :param show_lidarseg: When set to True, the lidar data is colored with the segmentation labels. When set\n        to False, the colors of the lidar data represent the distance from the center of the ego vehicle.\n    :param show_lidarseg_legend: Whether to display the legend for the lidarseg labels in the frame.\n    :param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None\n        or the list is empty, all classes will be displayed.\n    :param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation\n                                    predictions for the sample.\n    :param verbose: Whether to display the image after it is rendered.\n    :param show_panoptic: When set to True, the lidar data is colored with the panoptic labels. When set\n        to False, the colors of the lidar data represent the distance from the center of the ego vehicle.\n        If show_lidarseg is True, show_panoptic will be set to False.\n    \"\"\"\n    lidiar_render(sample_toekn, pred_data, out_path=out_path,\n                  out_name=out_name, traj_use_perstep_offset=traj_use_perstep_offset)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Visualize VAD predictions')\n    parser.add_argument('--result-path', help='inference result file path')\n    parser.add_argument('--save-path', help='the dir to save visualization results')\n    args = parser.parse_args()\n\n    return args\n\n\nif __name__ == '__main__':\n    args = parse_args()\n    inference_result_path = args.result_path\n    out_path = args.save_path\n    bevformer_results = mmcv.load(inference_result_path)\n    sample_token_list = list(bevformer_results['results'].keys())\n\n    nusc = NuScenes(version='v1.0-trainval', dataroot='./data/nuscenes', verbose=True)\n    \n    imgs = []\n    fourcc = cv2.VideoWriter_fourcc('m', 'p', '4', 'v')\n    video_path = osp.join(out_path, 'vis.mp4')\n    video = cv2.VideoWriter(video_path, fourcc, 10, (2933, 800), True)\n    for id in tqdm(range(len(sample_token_list))):\n        mmcv.mkdir_or_exist(out_path)\n        render_sample_data(sample_token_list[id],\n                           pred_data=bevformer_results,\n                           out_path=out_path)\n        pred_path = osp.join(out_path, 'bev_pred.png')\n        pred_img = cv2.imread(pred_path)\n        os.remove(pred_path)\n\n        sample_token = sample_token_list[id]\n        sample = nusc.get('sample', sample_token)\n        # sample = data['results'][sample_token_list[0]][0]\n        cams = [\n            'CAM_FRONT_LEFT',\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_BACK_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_RIGHT',\n        ]\n\n        cam_imgs = []\n        for cam in cams:\n            sample_data_token = sample['data'][cam]\n            sd_record = nusc.get('sample_data', sample_data_token)\n            sensor_modality = sd_record['sensor_modality']\n            if sensor_modality in ['lidar', 'radar']:\n                assert False\n            elif sensor_modality == 'camera':\n                boxes = [Box(record['translation'], record['size'], Quaternion(record['rotation']),\n                            name=record['detection_name'], token='predicted') for record in\n                        bevformer_results['results'][sample_token]]\n                data_path, boxes_pred, camera_intrinsic = get_predicted_data(sample_data_token,\n                                                                            box_vis_level=BoxVisibility.ANY,\n                                                                            pred_anns=boxes)\n                _, boxes_gt, _ = nusc.get_sample_data(sample_data_token, box_vis_level=BoxVisibility.ANY)\n\n                data = Image.open(data_path)\n \n                # Show image.\n                _, ax = plt.subplots(1, 1, figsize=(6, 12))\n                ax.imshow(data)\n\n                if cam == 'CAM_FRONT':\n                    lidar_sd_record =  nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n                    lidar_cs_record = nusc.get('calibrated_sensor', lidar_sd_record['calibrated_sensor_token'])\n                    lidar_pose_record = nusc.get('ego_pose', lidar_sd_record['ego_pose_token'])\n\n                    # get plan traj [x,y,z,w] quaternion, w=1\n                    # we set z=-1 to get points near the ground in lidar coord system\n                    plan_cmd = np.argmax(bevformer_results['plan_results'][sample_token][1][0,0,0])\n                    plan_traj = bevformer_results['plan_results'][sample_token][0][plan_cmd]\n                    plan_traj[abs(plan_traj) < 0.01] = 0.0\n                    plan_traj = plan_traj.cumsum(axis=0)\n\n                    plan_traj = np.concatenate((\n                        plan_traj[:, [0]],\n                        plan_traj[:, [1]],\n                        -1.0*np.ones((plan_traj.shape[0], 1)),\n                        np.ones((plan_traj.shape[0], 1)),\n                    ), axis=1)\n                    # add the start point in lcf\n                    plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n                    # plan_traj[0, :2] = 2*plan_traj[1, :2] - plan_traj[2, :2]\n                    plan_traj[0, 0] = 0.3\n                    plan_traj[0, 2] = -1.0\n                    plan_traj[0, 3] = 1.0\n\n                    l2e_r = lidar_cs_record['rotation']\n                    l2e_t = lidar_cs_record['translation']\n                    e2g_r = lidar_pose_record['rotation']\n                    e2g_t = lidar_pose_record['translation']\n                    l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n                    e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n                    s2l_r, s2l_t = obtain_sensor2top(nusc, sample_data_token, l2e_t, l2e_r_mat, e2g_t, e2g_r_mat, cam)\n                    # obtain lidar to image transformation matrix\n                    lidar2cam_r = np.linalg.inv(s2l_r)\n                    lidar2cam_t = s2l_t @ lidar2cam_r.T\n                    lidar2cam_rt = np.eye(4)\n                    lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                    lidar2cam_rt[3, :3] = -lidar2cam_t\n                    viewpad = np.eye(4)\n                    viewpad[:camera_intrinsic.shape[0], :camera_intrinsic.shape[1]] = camera_intrinsic\n                    lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                    plan_traj = lidar2img_rt @ plan_traj.T\n                    plan_traj = plan_traj[0:2, ...] / np.maximum(\n                        plan_traj[2:3, ...], np.ones_like(plan_traj[2:3, ...]) * 1e-5)\n                    plan_traj = plan_traj.T\n                    plan_traj = np.stack((plan_traj[:-1], plan_traj[1:]), axis=1)\n\n                    plan_vecs = None\n                    for i in range(plan_traj.shape[0]):\n                        plan_vec_i = plan_traj[i]\n                        x_linspace = np.linspace(plan_vec_i[0, 0], plan_vec_i[1, 0], 51)\n                        y_linspace = np.linspace(plan_vec_i[0, 1], plan_vec_i[1, 1], 51)\n                        xy = np.stack((x_linspace, y_linspace), axis=1)\n                        xy = np.stack((xy[:-1], xy[1:]), axis=1)\n                        if plan_vecs is None:\n                            plan_vecs = xy\n                        else:\n                            plan_vecs = np.concatenate((plan_vecs, xy), axis=0)\n\n                    cmap = 'winter'\n                    y = np.sin(np.linspace(1/2*np.pi, 3/2*np.pi, 301))\n                    colors = color_map(y[:-1], cmap)\n                    line_segments = LineCollection(plan_vecs, colors=colors, linewidths=2, linestyles='solid', cmap=cmap)\n                    ax.add_collection(line_segments)\n\n                ax.set_xlim(0, data.size[0])\n                ax.set_ylim(data.size[1], 0)\n                ax.axis('off')\n                if out_path is not None:\n                    savepath = osp.join(out_path, f'{cam}_PRED')\n                    plt.savefig(savepath, bbox_inches='tight', dpi=200, pad_inches=0.0)\n                plt.close()\n\n                # Load boxes and image.\n                data_path = osp.join(out_path, f'{cam}_PRED.png')\n                cam_img = cv2.imread(data_path)\n                lw = 6\n                tf = max(lw - 3, 1)\n                w, h = cv2.getTextSize(cam, 0, fontScale=lw / 6, thickness=tf)[0]  # text width, height\n                # color=(0, 0, 0)\n                txt_color=(255, 255, 255)\n                cv2.putText(cam_img,\n                            cam, (10, h + 10),\n                            0,\n                            lw / 6,\n                            txt_color,\n                            thickness=tf,\n                            lineType=cv2.LINE_AA)\n                cam_imgs.append(cam_img)\n            else:\n                raise ValueError(\"Error: Unknown sensor modality!\")\n\n        plan_cmd = np.argmax(bevformer_results['plan_results'][sample_token][1][0,0,0])\n        cmd_list = ['Turn Right', 'Turn Left', 'Go Straight']\n        plan_cmd_str = cmd_list[plan_cmd]\n        pred_img = cv2.copyMakeBorder(pred_img, 10, 10, 10, 10, cv2.BORDER_CONSTANT, None, value = 0)\n        # font\n        font = cv2.FONT_HERSHEY_SIMPLEX\n        # fontScale\n        fontScale = 1\n        # Line thickness of 2 px\n        thickness = 3\n        # org\n        org = (20, 40)      \n        # Blue color in BGR\n        color = (0, 0, 0)\n        # Using cv2.putText() method\n        pred_img = cv2.putText(pred_img, 'BEV', org, font, \n                        fontScale, color, thickness, cv2.LINE_AA)\n        pred_img = cv2.putText(pred_img, plan_cmd_str, (20, 770), font, \n                        fontScale, color, thickness, cv2.LINE_AA)\n        \n        sample_img = pred_img\n        cam_img_top = cv2.hconcat([cam_imgs[0], cam_imgs[1], cam_imgs[2]])\n        cam_img_down = cv2.hconcat([cam_imgs[3], cam_imgs[4], cam_imgs[5]])\n        cam_img = cv2.vconcat([cam_img_top, cam_img_down])\n        size = (2133, 800)\n        cam_img = cv2.resize(cam_img, size)\n        vis_img = cv2.hconcat([cam_img, sample_img])\n\n        video.write(vis_img)\n    \n    video.release()\n    cv2.destroyAllWindows()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/apis/__init__.py",
    "content": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector\n# from .test import custom_multi_gpu_test"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/apis/mmdet_train.py",
    "content": "import random\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom torch.nn import DataParallel\nfrom torch.nn.parallel.distributed import DistributedDataParallel\nfrom mmcv.runner import (HOOKS, DistSamplerSeedHook, EpochBasedRunner,\n                         Fp16OptimizerHook, OptimizerHook,\n                         build_runner)\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.optims import build_optimizer\nfrom mmcv.core import EvalHook\n\nfrom mmcv.datasets import (build_dataset,\n                            replace_ImageToTensor)\nfrom mmcv.utils import get_root_logger\nimport time\nimport os.path as osp\nfrom mmcv.datasets.builder import build_dataloader\nfrom mmcv.core.evaluation.eval_hooks import CustomDistEvalHook\nfrom mmcv.datasets.builder import custom_build_dataset\ndef custom_train_detector(model,\n                   dataset,\n                   cfg,\n                   distributed=False,\n                   validate=False,\n                   timestamp=None,\n                   eval_model=None,\n                   meta=None):\n    logger = get_root_logger(cfg.log_level)\n\n    # prepare data loaders\n   \n    dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]\n    #assert len(dataset)==1s\n    if 'imgs_per_gpu' in cfg.data:\n        logger.warning('\"imgs_per_gpu\" is deprecated in MMDet V2.0. '\n                       'Please use \"samples_per_gpu\" instead')\n        if 'samples_per_gpu' in cfg.data:\n            logger.warning(\n                f'Got \"imgs_per_gpu\"={cfg.data.imgs_per_gpu} and '\n                f'\"samples_per_gpu\"={cfg.data.samples_per_gpu}, \"imgs_per_gpu\"'\n                f'={cfg.data.imgs_per_gpu} is used in this experiments')\n        else:\n            logger.warning(\n                'Automatically set \"samples_per_gpu\"=\"imgs_per_gpu\"='\n                f'{cfg.data.imgs_per_gpu} in this experiments')\n        cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu\n\n    data_loaders = [\n        build_dataloader(\n            ds,\n            cfg.data.samples_per_gpu,\n            cfg.data.workers_per_gpu,\n            # cfg.gpus will be ignored if distributed\n            len(cfg.gpu_ids),\n            dist=distributed,\n            seed=cfg.seed,\n            shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n            nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n        ) for ds in dataset\n    ]\n\n    # put model on gpus\n    if distributed:\n        find_unused_parameters = cfg.get('find_unused_parameters', False)\n        # Sets the `find_unused_parameters` parameter in\n        # torch.nn.parallel.DistributedDataParallel\n        model = DistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n            find_unused_parameters=find_unused_parameters)\n        if eval_model is not None:\n            eval_model = DistributedDataParallel(\n                eval_model.cuda(),\n                device_ids=[torch.cuda.current_device()],\n                broadcast_buffers=False,\n                find_unused_parameters=find_unused_parameters)\n    else:\n        model = DataParallel(\n            model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n        if eval_model is not None:\n            eval_model = DataParallel(\n                eval_model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)\n\n\n    # build runner\n    optimizer = build_optimizer(model, cfg.optimizer)\n\n    if 'runner' not in cfg:\n        cfg.runner = {\n            'type': 'EpochBasedRunner',\n            'max_epochs': cfg.total_epochs\n        }\n        warnings.warn(\n            'config is now expected to have a `runner` section, '\n            'please set `runner` in your config.', UserWarning)\n    else:\n        if 'total_epochs' in cfg:\n            assert cfg.total_epochs == cfg.runner.max_epochs\n    if eval_model is not None:\n        runner = build_runner(\n            cfg.runner,\n            default_args=dict(\n                model=model,\n                eval_model=eval_model,\n                optimizer=optimizer,\n                work_dir=cfg.work_dir,\n                logger=logger,\n                meta=meta))\n    else:\n        runner = build_runner(\n            cfg.runner,\n            default_args=dict(\n                model=model,\n                optimizer=optimizer,\n                work_dir=cfg.work_dir,\n                logger=logger,\n                meta=meta))\n\n    # an ugly workaround to make .log and .log.json filenames the same\n    runner.timestamp = timestamp\n\n    # fp16 setting\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        optimizer_config = Fp16OptimizerHook(\n            **cfg.optimizer_config, **fp16_cfg, distributed=distributed)\n    elif distributed and 'type' not in cfg.optimizer_config:\n        optimizer_config = OptimizerHook(**cfg.optimizer_config)\n    else:\n        optimizer_config = cfg.optimizer_config\n\n    # register hooks\n    runner.register_training_hooks(cfg.lr_config, optimizer_config,\n                                   cfg.checkpoint_config, cfg.log_config,\n                                   cfg.get('momentum_config', None))\n    \n    # register profiler hook\n    #trace_config = dict(type='tb_trace', dir_name='work_dir')\n    #profiler_config = dict(on_trace_ready=trace_config)\n    #runner.register_profiler_hook(profiler_config)\n    \n    if distributed:\n        if isinstance(runner, EpochBasedRunner):\n            runner.register_hook(DistSamplerSeedHook())\n\n    # register eval hooks\n    if validate:\n        # Support batch_size > 1 in validation\n        val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1)\n        if val_samples_per_gpu > 1:\n            assert False\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.val.pipeline = replace_ImageToTensor(\n                cfg.data.val.pipeline)\n        val_dataset = custom_build_dataset(cfg.data.val, dict(test_mode=True))\n\n        val_dataloader = build_dataloader(\n            val_dataset,\n            samples_per_gpu=val_samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            shuffler_sampler=cfg.data.shuffler_sampler,  # dict(type='DistributedGroupSampler'),\n            nonshuffler_sampler=cfg.data.nonshuffler_sampler,  # dict(type='DistributedSampler'),\n        )\n        eval_cfg = cfg.get('evaluation', {})\n        eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner'\n        eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_'))\n        eval_hook = CustomDistEvalHook if distributed else EvalHook\n        runner.register_hook(eval_hook(val_dataloader, **eval_cfg))\n\n    # user-defined hooks\n    if cfg.get('custom_hooks', None):\n        custom_hooks = cfg.custom_hooks\n        assert isinstance(custom_hooks, list), \\\n            f'custom_hooks expect list type, but got {type(custom_hooks)}'\n        for hook_cfg in cfg.custom_hooks:\n            assert isinstance(hook_cfg, dict), \\\n                'Each item in custom_hooks expects dict type, but got ' \\\n                f'{type(hook_cfg)}'\n            hook_cfg = hook_cfg.copy()\n            priority = hook_cfg.pop('priority', 'NORMAL')\n            hook = build_from_cfg(hook_cfg, HOOKS)\n            runner.register_hook(hook, priority=priority)\n\n    if cfg.resume_from:\n        runner.resume(cfg.resume_from)\n    elif cfg.load_from:\n        runner.load_checkpoint(cfg.load_from)\n    runner.run(data_loaders, cfg.workflow)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/apis/test.py",
    "content": "import os.path as osp\nimport pickle\nimport shutil\nimport tempfile\nimport time\n\nimport torch\nimport torch.distributed as dist\nfrom mmcv.image import tensor2imgs\nfrom mmcv.utils import get_dist_info\n\nfrom mmcv.core import encode_mask_results\nfrom mmcv.fileio.io import dump, load\nfrom mmcv.utils import mkdir_or_exist, ProgressBar\n\nimport numpy as np\nimport pycocotools.mask as mask_util\n\ndef custom_encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code. Semantic Masks only\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = []\n    for i in range(len(cls_segms)):\n        encoded_mask_results.append(\n            mask_util.encode(\n                np.array(\n                    cls_segms[i][:, :, np.newaxis], order='F',\n                        dtype='uint8'))[0])  # encoded with RLE\n    return [encoded_mask_results]\n\ndef custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):\n    \"\"\"Test model with multiple gpus.\n    This method tests model with multiple gpus and collects the results\n    under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'\n    it encodes results to gpu tensors and use gpu communication for results\n    collection. On cpu mode it saves the results on different gpus to 'tmpdir'\n    and collects them by the rank 0 worker.\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        tmpdir (str): Path of directory to save the temporary results from\n            different gpus under cpu mode.\n        gpu_collect (bool): Option to use either gpu or cpu to collect results.\n    Returns:\n        list: The prediction results.\n    \"\"\"\n    #import pdb;pdb.set_trace()\n    model.eval()\n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    rank, world_size = get_dist_info()\n    if rank == 0:\n        prog_bar = ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n    sum_turning = 0\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(data,return_loss=False, rescale=True)\n            # encode mask results\n            if isinstance(result, dict):\n                if 'bbox_results' in result.keys():\n                    bbox_result = result['bbox_results']\n                    batch_size = len(result['bbox_results'])\n                    bbox_results.extend(bbox_result)\n                if 'mask_results' in result.keys() and result['mask_results'] is not None:\n                    mask_result = custom_encode_mask_results(result['mask_results'])\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n        if rank == 0:\n            \n            for _ in range(batch_size * world_size):\n                prog_bar.update()\n\n    # collect results from all ranks\n    if gpu_collect:\n        bbox_results = collect_results_gpu(bbox_results, len(dataset))\n        if have_mask:\n            mask_results = collect_results_gpu(mask_results, len(dataset))\n        else:\n            mask_results = None\n    else:\n        bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)\n        tmpdir = tmpdir+'_mask' if tmpdir is not None else None\n        if have_mask:\n            mask_results = collect_results_cpu(mask_results, len(dataset), tmpdir)\n        else:\n            mask_results = None\n\n    return {'bbox_results': bbox_results, 'mask_results': mask_results}\n\n\ndef collect_results_cpu(result_part, size, tmpdir=None):\n    rank, world_size = get_dist_info()\n    # create a tmp dir if it is not specified\n    if tmpdir is None:\n        MAX_LEN = 512\n        # 32 is whitespace\n        dir_tensor = torch.full((MAX_LEN, ),\n                                32,\n                                dtype=torch.uint8,\n                                device='cuda')\n        if rank == 0:\n            mkdir_or_exist('.dist_test')\n            tmpdir = tempfile.mkdtemp(dir='.dist_test')\n            tmpdir = torch.tensor(\n                bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda')\n            dir_tensor[:len(tmpdir)] = tmpdir\n        dist.broadcast(dir_tensor, 0)\n        tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()\n    else:\n        mkdir_or_exist(tmpdir)\n    # dump the part result to the dir\n    dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl'))\n    dist.barrier()\n    # collect all parts\n    if rank != 0:\n        return None\n    else:\n        # load results of all parts from tmp dir\n        part_list = []\n        for i in range(world_size):\n            part_file = osp.join(tmpdir, f'part_{i}.pkl')\n            part_list.append(load(part_file))\n        # sort the results\n        ordered_results = []\n        '''\n        bacause we change the sample of the evaluation stage to make sure that each gpu will handle continuous sample,\n        '''\n        #for res in zip(*part_list):\n        for res in part_list:  \n            ordered_results.extend(list(res))\n        # the dataloader may pad some samples\n        ordered_results = ordered_results[:size]\n        # remove tmp dir\n        shutil.rmtree(tmpdir)\n        return ordered_results\n\n\ndef collect_results_gpu(result_part, size):\n    collect_results_cpu(result_part, size)\n\n\ndef single_gpu_test(model, data_loader):\n    \"\"\"Test model with single gpu.\n\n    This method tests model with single gpu and gives the 'show' option.\n    By setting ``show=True``, it saves the visualization results under\n    ``out_dir``.\n\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        show (bool, optional): Whether to save viualization results.\n            Default: True.\n        out_dir (str, optional): The path to save visualization results.\n            Default: None.\n\n    Returns:\n        list[dict]: The prediction results.\n    \"\"\"\n    model.eval()\n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    prog_bar = ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            #import pdb;pdb.set_trace()\n            result = model(data,return_loss=False, rescale=True)\n            batch_size = len(result['bbox_results'])\n\n            # encode mask results\n            if isinstance(result, dict):\n                if 'bbox_results' in result.keys():\n                    bbox_result = result['bbox_results']\n                    batch_size = len(result['bbox_results'])\n                    bbox_results.extend(bbox_result)\n                if 'mask_results' in result.keys() and result['mask_results'] is not None:\n                    mask_result = custom_encode_mask_results(result['mask_results'])\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n\n            if isinstance(result[0], tuple):\n               assert False, 'this code is for instance segmentation, which our code will not utilize.'\n               result = [(bbox_results, encode_mask_results(mask_results))\n                         for bbox_results, mask_results in result]\n\n        for _ in range(batch_size):\n                prog_bar.update()\n\n    return {'bbox_results': bbox_results, 'mask_results': mask_results}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/apis/train.py",
    "content": "from .mmdet_train import custom_train_detector\n\n\ndef custom_train_model(model,\n                dataset,\n                cfg,\n                distributed=False,\n                validate=False,\n                timestamp=None,\n                eval_model=None,\n                meta=None):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in ['EncoderDecoder3D']:\n        assert False\n    else:\n        custom_train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            eval_model=eval_model,\n            meta=meta)\n\n\ndef train_model(model,\n                dataset,\n                cfg,\n                distributed=False,\n                validate=False,\n                timestamp=None,\n                meta=None):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in ['EncoderDecoder3D']:\n        train_segmentor(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta)\n    else:\n        train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\nvoxel_size = [0.15, 0.15, 4]\n\nimg_norm_cfg = dict(\n   mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\n# For nuScenes we usually do 10-class detection\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\nnum_classes = len(class_names)\n\n# map has classes: divider, ped_crossing, boundary\nmap_classes = ['Broken','Solid','SolidSolid','Center','TrafficLight','StopSign']\nmap_num_vec = 100\nmap_fixed_ptsnum_per_gt_line = 20 # now only support fixed_pts > 0\nmap_fixed_ptsnum_per_pred_line = 20\nmap_eval_use_same_gt_sample_num_flag = True\nmap_num_classes = len(map_classes)\npast_frames = 6\nfuture_frames = 6\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\nqueue_length = 4 # each sequence contains `queue_length` frames.\ntotal_epochs = 6\n\nmodel = dict(\n    type='MomAD',\n    use_grid_mask=True,\n    video_test_mode=True,\n    pretrained=dict(img='ckpts/resnet50-19c8e357.pth'),\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='MomADHead',\n        map_thresh=0.5,\n        dis_thresh=0.2,\n        pe_normalization=True,\n        tot_epoch=total_epochs,\n        use_traj_lr_warmup=False,\n        query_thresh=0.0,\n        query_use_fix_pad=False,\n        ego_his_encoder=None,\n        ego_lcf_feat_idx=None,\n        valid_fut_ts=6,\n        ego_fut_mode=6,\n        ego_agent_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        ego_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        use_pe=True,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=300,\n        num_classes=num_classes,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        map_num_vec=map_num_vec,\n        map_num_classes=map_num_classes,\n        map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n        map_num_pts_per_gt_vec=map_fixed_ptsnum_per_gt_line,\n        map_query_embed_type='instance_pts',\n        map_transform_method='minmax',\n        map_gt_shift_pts_pattern='v2',\n        map_dir_interval=1,\n        map_code_size=2,\n        map_code_weights=[1.0, 1.0, 1.0, 1.0],\n        transformer=dict(\n            type='VADPerceptionTransformer',\n            map_num_vec=map_num_vec,\n            map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            map_decoder=dict(\n                type='MapDetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='CustomNMSFreeCoder',\n            post_center_range=[-20, -35, -10.0, 20, 35, 10.0],\n            pc_range=point_cloud_range,\n            max_num=100,\n            voxel_size=voxel_size,\n            num_classes=num_classes),\n        map_bbox_coder=dict(\n            type='MapNMSFreeCoder',\n            post_center_range=[-20, -35, -20, -35, 20, 35, 20, 35],\n            pc_range=point_cloud_range,\n            max_num=50,\n            voxel_size=voxel_size,\n            num_classes=map_num_classes),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_traj=dict(type='L1Loss', loss_weight=0.2),\n        loss_traj_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=0.2),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_map_bbox=dict(type='L1Loss', loss_weight=0.0),\n        loss_map_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_pts=dict(type='PtsL1Loss', loss_weight=1.0),\n        loss_map_dir=dict(type='PtsDirCosLoss', loss_weight=0.005),\n        loss_plan_reg=dict(type='L1Loss', loss_weight=1.0),\n        loss_plan_cls=dict(type='FocalLoss',use_sigmoid=True,gamma=2.0,alpha=0.25,loss_weight=1.0),\n        loss_plan_bound=dict(type='PlanMapBoundLoss', loss_weight=1.0, dis_thresh=1.0),\n        loss_plan_col=dict(type='PlanCollisionLoss', loss_weight=1.0),\n        loss_plan_dir=dict(type='PlanMapDirectionLoss', loss_weight=0.5)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range),\n        map_assigner=dict(\n            type='MapHungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBoxL1Cost', weight=0.0, box_format='xywh'),\n            iou_cost=dict(type='IoUCost', iou_mode='giou', weight=0.0),\n            pts_cost=dict(type='OrderedPtsL1Cost', weight=1.0),\n            pc_range=point_cloud_range))))\n\ndataset_type = \"B2D_VAD_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='VADObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='VADObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='VADFormatBundle3D', class_names=class_names, with_ego=True),\n    dict(type='CustomCollect3D',\\\n         keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'ego_his_trajs','gt_attr_labels','ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd', 'ego_lcf_feat'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='VADObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='VADObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    # dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='VADFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D',\\\n                 keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'fut_valid_flag',\n                       'ego_his_trajs', 'ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd',\n                       'ego_lcf_feat','gt_attr_labels'])])\n]\n\ninference_only_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='VADFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D', keys=[ 'img', 'ego_fut_cmd'])])\n]\n\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=6,\n    train=dict(\n\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        modality=input_modality,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        past_frames=past_frames,\n        future_frames=future_frames,\n        point_cloud_range=point_cloud_range,\n        polyline_points_num=map_fixed_ptsnum_per_gt_line,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR',\n        #custom_eval_version='vad_nusc_detection_cvpr_2019'\n        ),\n    val=dict(type=dataset_type,\n            data_root=data_root,\n            ann_file=ann_file_val,\n            pipeline=test_pipeline,\n            classes=class_names,\n            name_mapping=NameMapping,\n            map_root=map_root,\n            map_file=map_file,\n            modality=input_modality,\n            bev_size=(bev_h_, bev_w_),\n            queue_length=queue_length,\n            past_frames=past_frames,\n            future_frames=future_frames,\n            point_cloud_range=point_cloud_range,\n            polyline_points_num=map_fixed_ptsnum_per_gt_line,\n            eval_cfg=eval_cfg\n            ),\n    test=dict(type=dataset_type,\n            data_root=data_root,\n            ann_file=ann_file_val,\n            pipeline=test_pipeline,\n            classes=class_names,\n            name_mapping=NameMapping,\n            map_root=map_root,\n            map_file=map_file,\n            modality=input_modality,\n            bev_size=(bev_h_, bev_w_),\n            queue_length=queue_length,\n            past_frames=past_frames,\n            future_frames=future_frames,\n            point_cloud_range=point_cloud_range,\n            polyline_points_num=map_fixed_ptsnum_per_gt_line,\n            eval_cfg=eval_cfg\n            ),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\n\nevaluation = dict(interval=total_epochs, pipeline=test_pipeline, metric='bbox', map_metric='chamfer')\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# fp16 = dict(loss_scale=512.)\n# find_unused_parameters = True\ncheckpoint_config = dict(interval=1, max_keep_ckpts=total_epochs)\n\n\ncustom_hooks = [dict(type='CustomSetEpochInfoHook')]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/VAD/VAD_base_e2e.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n#\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\nvoxel_size = [0.15, 0.15, 4]\n\nimg_norm_cfg = dict(\n   mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n    'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n]\nnum_classes = len(class_names)\n\n# map has classes: divider, ped_crossing, boundary\nmap_classes = ['divider', 'ped_crossing', 'boundary']\nmap_num_vec = 100\nmap_fixed_ptsnum_per_gt_line = 20 # now only support fixed_pts > 0\nmap_fixed_ptsnum_per_pred_line = 20\nmap_eval_use_same_gt_sample_num_flag = True\nmap_num_classes = len(map_classes)\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\nqueue_length = 4 # each sequence contains `queue_length` frames.\ntotal_epochs = 60\n\nmodel = dict(\n    type='VAD',\n    use_grid_mask=True,\n    video_test_mode=True,\n    pretrained=dict(img='ckpts/resnet50-19c8e357.pth'),\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='VADHead',\n        map_thresh=0.5,\n        dis_thresh=0.2,\n        pe_normalization=True,\n        tot_epoch=total_epochs,\n        use_traj_lr_warmup=False,\n        query_thresh=0.0,\n        query_use_fix_pad=False,\n        ego_his_encoder=None,\n        ego_lcf_feat_idx=None,\n        valid_fut_ts=6,\n        ego_agent_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        ego_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        use_pe=True,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=300,\n        num_classes=num_classes,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        map_num_vec=map_num_vec,\n        map_num_classes=map_num_classes,\n        map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n        map_num_pts_per_gt_vec=map_fixed_ptsnum_per_gt_line,\n        map_query_embed_type='instance_pts',\n        map_transform_method='minmax',\n        map_gt_shift_pts_pattern='v2',\n        map_dir_interval=1,\n        map_code_size=2,\n        map_code_weights=[1.0, 1.0, 1.0, 1.0],\n        transformer=dict(\n            type='VADPerceptionTransformer',\n            map_num_vec=map_num_vec,\n            map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            map_decoder=dict(\n                type='MapDetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='CustomNMSFreeCoder',\n            post_center_range=[-20, -35, -10.0, 20, 35, 10.0],\n            pc_range=point_cloud_range,\n            max_num=100,\n            voxel_size=voxel_size,\n            num_classes=num_classes),\n        map_bbox_coder=dict(\n            type='MapNMSFreeCoder',\n            post_center_range=[-20, -35, -20, -35, 20, 35, 20, 35],\n            pc_range=point_cloud_range,\n            max_num=50,\n            voxel_size=voxel_size,\n            num_classes=map_num_classes),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_traj=dict(type='L1Loss', loss_weight=0.2),\n        loss_traj_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=0.2),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_map_bbox=dict(type='L1Loss', loss_weight=0.0),\n        loss_map_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_pts=dict(type='PtsL1Loss', loss_weight=1.0),\n        loss_map_dir=dict(type='PtsDirCosLoss', loss_weight=0.005),\n        loss_plan_reg=dict(type='L1Loss', loss_weight=1.0),\n        loss_plan_bound=dict(type='PlanMapBoundLoss', loss_weight=1.0, dis_thresh=1.0),\n        loss_plan_col=dict(type='PlanCollisionLoss', loss_weight=1.0),\n        loss_plan_dir=dict(type='PlanMapDirectionLoss', loss_weight=0.5)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range),\n        map_assigner=dict(\n            type='MapHungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBoxL1Cost', weight=0.0, box_format='xywh'),\n            iou_cost=dict(type='IoUCost', iou_mode='giou', weight=0.0),\n            pts_cost=dict(type='OrderedPtsL1Cost', weight=1.0),\n            pc_range=point_cloud_range))))\n\ndataset_type = 'VADCustomNuScenesDataset'\ndata_root = 'data/nuscenes/'\nfile_client_args = dict(backend='disk')\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='VADObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='VADObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='VADFormatBundle3D', class_names=class_names, with_ego=True),\n    dict(type='CustomCollect3D',\\\n         keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'ego_his_trajs',\n               'ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd', 'ego_lcf_feat', 'gt_attr_labels'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='LoadPointsFromFile',\n         coord_type='LIDAR',\n         load_dim=5,\n         use_dim=5,\n         file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='VADObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='VADObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    # dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='VADFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D',\\\n                 keys=['points', 'gt_bboxes_3d', 'gt_labels_3d', 'img', 'fut_valid_flag',\n                       'ego_his_trajs', 'ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd',\n                       'ego_lcf_feat', 'gt_attr_labels'])])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'vad_nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        bev_size=(bev_h_, bev_w_),\n        pc_range=point_cloud_range,\n        queue_length=queue_length,\n        map_classes=map_classes,\n        map_fixed_ptsnum_per_line=map_fixed_ptsnum_per_gt_line,\n        map_eval_use_same_gt_sample_num_flag=map_eval_use_same_gt_sample_num_flag,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR',\n        custom_eval_version='vad_nusc_detection_cvpr_2019'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             pc_range=point_cloud_range,\n             ann_file=data_root + 'vad_nuscenes_infos_temporal_val.pkl',\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1,\n             map_classes=map_classes,\n             map_ann_file=data_root + 'nuscenes_map_anns_val.json',\n             map_fixed_ptsnum_per_line=map_fixed_ptsnum_per_gt_line,\n             map_eval_use_same_gt_sample_num_flag=map_eval_use_same_gt_sample_num_flag,\n             use_pkl_result=True,\n             custom_eval_version='vad_nusc_detection_cvpr_2019'),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              pc_range=point_cloud_range,\n              ann_file=data_root + 'vad_nuscenes_infos_temporal_val.pkl',\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality, samples_per_gpu=1,\n              map_classes=map_classes,\n              map_ann_file=data_root + 'nuscenes_map_anns_val.json',\n              map_fixed_ptsnum_per_line=map_fixed_ptsnum_per_gt_line,\n              map_eval_use_same_gt_sample_num_flag=map_eval_use_same_gt_sample_num_flag,\n              use_pkl_result=True,\n              custom_eval_version='vad_nusc_detection_cvpr_2019'),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\n\nevaluation = dict(interval=total_epochs, pipeline=test_pipeline, metric='bbox', map_metric='chamfer')\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n\nlog_config = dict(\n    interval=1,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# fp16 = dict(loss_scale=512.)\n# find_unused_parameters = True\ncheckpoint_config = dict(interval=1, max_keep_ckpts=total_epochs)\n\n\ncustom_hooks = [dict(type='CustomSetEpochInfoHook')]"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/VAD/VAD_base_e2e_b2d.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\nvoxel_size = [0.15, 0.15, 4]\n\nimg_norm_cfg = dict(\n   mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\n# For nuScenes we usually do 10-class detection\n\nNameMapping = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    \"vehicle.gazelle.omafiets\": 'bicycle',\n    # car\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"vehicle.audi.etron\": 'car',\n    \"vehicle.ford.crown\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.tesla.model3\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    \"vehicle.ford.ambulance\": \"van\",\n    # truck\n    \"vehicle.carlamotors.firetruck\": 'truck',\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'traffic_sign',\n    \"traffic.speed_limit.40\": 'traffic_sign',\n    \"traffic.speed_limit.50\": 'traffic_sign',\n    \"traffic.speed_limit.60\": 'traffic_sign',\n    \"traffic.speed_limit.90\": 'traffic_sign',\n    \"traffic.speed_limit.120\": 'traffic_sign',\n    \n    \"traffic.stop\": 'traffic_sign',\n    \"traffic.yield\": 'traffic_sign',\n    \"traffic.traffic_light\": 'traffic_light',\n    #=========================================\n\n    #===================Construction===========\n    \"static.prop.warningconstruction\" : 'traffic_cone',\n    \"static.prop.warningaccident\": 'traffic_cone',\n    \"static.prop.trafficwarning\": \"traffic_cone\",\n\n    #===================Construction===========\n    \"static.prop.constructioncone\": 'traffic_cone',\n\n    #=================pedestrian==============\n    \"walker.pedestrian.0001\": 'pedestrian',\n    \"walker.pedestrian.0003\": 'pedestrian',\n    \"walker.pedestrian.0004\": 'pedestrian',\n    \"walker.pedestrian.0005\": 'pedestrian',\n    \"walker.pedestrian.0007\": 'pedestrian',\n    \"walker.pedestrian.0010\": 'pedestrian',\n    \"walker.pedestrian.0013\": 'pedestrian',\n    \"walker.pedestrian.0014\": 'pedestrian',\n    \"walker.pedestrian.0015\": 'pedestrian',\n    \"walker.pedestrian.0016\": 'pedestrian',\n    \"walker.pedestrian.0017\": 'pedestrian',\n    \"walker.pedestrian.0018\": 'pedestrian',\n    \"walker.pedestrian.0019\": 'pedestrian',\n    \"walker.pedestrian.0020\": 'pedestrian',\n    \"walker.pedestrian.0021\": 'pedestrian',\n    \"walker.pedestrian.0022\": 'pedestrian',\n    \"walker.pedestrian.0025\": 'pedestrian',\n    \"walker.pedestrian.0027\": 'pedestrian',\n    \"walker.pedestrian.0030\": 'pedestrian',\n    \"walker.pedestrian.0031\": 'pedestrian',\n    \"walker.pedestrian.0032\": 'pedestrian',\n    \"walker.pedestrian.0034\": 'pedestrian',\n    \"walker.pedestrian.0035\": 'pedestrian',\n    \"walker.pedestrian.0041\": 'pedestrian',\n    \"walker.pedestrian.0042\": 'pedestrian',\n    \"walker.pedestrian.0046\": 'pedestrian',\n    \"walker.pedestrian.0047\": 'pedestrian',\n\n    # ==========================================\n    \"static.prop.dirtdebris01\": 'others',\n    \"static.prop.dirtdebris02\": 'others',\n}\n\neval_cfg = {\n            \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n            \"dist_th_tp\": 2.0,\n            \"min_recall\": 0.1,\n            \"min_precision\": 0.1,\n            \"mean_ap_weight\": 5,\n            \"class_names\":['car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian'],\n            \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n            \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'},\n            \"class_range\":{'car':(50,50),'van':(50,50),'truck':(50,50),'bicycle':(40,40),'traffic_sign':(30,30),'traffic_cone':(30,30),'traffic_light':(30,30),'pedestrian':(40,40)}\n            }\n\nclass_names = [\n'car','van','truck','bicycle','traffic_sign','traffic_cone','traffic_light','pedestrian','others'\n]\nnum_classes = len(class_names)\n\n# map has classes: divider, ped_crossing, boundary\nmap_classes = ['Broken','Solid','SolidSolid','Center','TrafficLight','StopSign']\nmap_num_vec = 100\nmap_fixed_ptsnum_per_gt_line = 20 # now only support fixed_pts > 0\nmap_fixed_ptsnum_per_pred_line = 20\nmap_eval_use_same_gt_sample_num_flag = True\nmap_num_classes = len(map_classes)\npast_frames = 6\nfuture_frames = 6\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 4\nbev_h_ = 200\nbev_w_ = 200\nqueue_length = 4 # each sequence contains `queue_length` frames.\ntotal_epochs = 6\n\nmodel = dict(\n    type='VAD',\n    use_grid_mask=True,\n    video_test_mode=True,\n    pretrained=dict(img='ckpts/resnet50-19c8e357.pth'),\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[512, 1024, 2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='VADHead',\n        map_thresh=0.5,\n        dis_thresh=0.2,\n        pe_normalization=True,\n        tot_epoch=total_epochs,\n        use_traj_lr_warmup=False,\n        query_thresh=0.0,\n        query_use_fix_pad=False,\n        ego_his_encoder=None,\n        ego_lcf_feat_idx=None,\n        valid_fut_ts=6,\n        ego_fut_mode=6,\n        ego_agent_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        ego_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.0),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.0,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        use_pe=True,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=300,\n        num_classes=num_classes,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        map_num_vec=map_num_vec,\n        map_num_classes=map_num_classes,\n        map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n        map_num_pts_per_gt_vec=map_fixed_ptsnum_per_gt_line,\n        map_query_embed_type='instance_pts',\n        map_transform_method='minmax',\n        map_gt_shift_pts_pattern='v2',\n        map_dir_interval=1,\n        map_code_size=2,\n        map_code_weights=[1.0, 1.0, 1.0, 1.0],\n        transformer=dict(\n            type='VADPerceptionTransformer',\n            map_num_vec=map_num_vec,\n            map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=6,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            map_decoder=dict(\n                type='MapDetectionTransformerDecoder',\n                num_layers=6,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.0),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.0,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='CustomNMSFreeCoder',\n            post_center_range=[-20, -35, -10.0, 20, 35, 10.0],\n            pc_range=point_cloud_range,\n            max_num=100,\n            voxel_size=voxel_size,\n            num_classes=num_classes),\n        map_bbox_coder=dict(\n            type='MapNMSFreeCoder',\n            post_center_range=[-20, -35, -20, -35, 20, 35, 20, 35],\n            pc_range=point_cloud_range,\n            max_num=50,\n            voxel_size=voxel_size,\n            num_classes=map_num_classes),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_traj=dict(type='L1Loss', loss_weight=0.2),\n        loss_traj_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=0.2),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_map_bbox=dict(type='L1Loss', loss_weight=0.0),\n        loss_map_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_pts=dict(type='PtsL1Loss', loss_weight=1.0),\n        loss_map_dir=dict(type='PtsDirCosLoss', loss_weight=0.005),\n        loss_plan_reg=dict(type='L1Loss', loss_weight=1.0),\n        loss_plan_bound=dict(type='PlanMapBoundLoss', loss_weight=1.0, dis_thresh=1.0),\n        loss_plan_col=dict(type='PlanCollisionLoss', loss_weight=1.0),\n        loss_plan_dir=dict(type='PlanMapDirectionLoss', loss_weight=0.5)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range),\n        map_assigner=dict(\n            type='MapHungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBoxL1Cost', weight=0.0, box_format='xywh'),\n            iou_cost=dict(type='IoUCost', iou_mode='giou', weight=0.0),\n            pts_cost=dict(type='OrderedPtsL1Cost', weight=1.0),\n            pc_range=point_cloud_range))))\n\ndataset_type = \"B2D_VAD_Dataset\"\ndata_root = \"data/bench2drive\"\ninfo_root = \"data/infos\"\nmap_root = \"data/bench2drive/maps\"\nmap_file = \"data/infos/b2d_map_infos.pkl\"\nfile_client_args = dict(backend=\"disk\")\nann_file_train=info_root + f\"/b2d_infos_train.pkl\"\nann_file_val=info_root + f\"/b2d_infos_val.pkl\"\nann_file_test=info_root + f\"/b2d_infos_val.pkl\"\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='VADObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='VADObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='VADFormatBundle3D', class_names=class_names, with_ego=True),\n    dict(type='CustomCollect3D',\\\n         keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'ego_his_trajs','gt_attr_labels','ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd', 'ego_lcf_feat'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='VADObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='VADObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    # dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='VADFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D',\\\n                 keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'fut_valid_flag',\n                       'ego_his_trajs', 'ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd',\n                       'ego_lcf_feat','gt_attr_labels'])])\n]\n\ninference_only_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='VADFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D', keys=[ 'img', 'ego_fut_cmd'])])\n]\n\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=0,\n    train=dict(\n\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=ann_file_train,\n        pipeline=train_pipeline,\n        classes=class_names,\n        name_mapping=NameMapping,\n        map_root=map_root,\n        map_file=map_file,\n        modality=input_modality,\n        bev_size=(bev_h_, bev_w_),\n        queue_length=queue_length,\n        past_frames=past_frames,\n        future_frames=future_frames,\n        point_cloud_range=point_cloud_range,\n        polyline_points_num=map_fixed_ptsnum_per_gt_line,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR',\n        #custom_eval_version='vad_nusc_detection_cvpr_2019'\n        ),\n    val=dict(type=dataset_type,\n            data_root=data_root,\n            ann_file=ann_file_val,\n            pipeline=test_pipeline,\n            classes=class_names,\n            name_mapping=NameMapping,\n            map_root=map_root,\n            map_file=map_file,\n            modality=input_modality,\n            bev_size=(bev_h_, bev_w_),\n            queue_length=queue_length,\n            past_frames=past_frames,\n            future_frames=future_frames,\n            point_cloud_range=point_cloud_range,\n            polyline_points_num=map_fixed_ptsnum_per_gt_line,\n            eval_cfg=eval_cfg\n            ),\n    test=dict(type=dataset_type,\n            data_root=data_root,\n            ann_file=ann_file_val,\n            pipeline=test_pipeline,\n            classes=class_names,\n            name_mapping=NameMapping,\n            map_root=map_root,\n            map_file=map_file,\n            modality=input_modality,\n            bev_size=(bev_h_, bev_w_),\n            queue_length=queue_length,\n            past_frames=past_frames,\n            future_frames=future_frames,\n            point_cloud_range=point_cloud_range,\n            polyline_points_num=map_fixed_ptsnum_per_gt_line,\n            eval_cfg=eval_cfg\n            ),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    by_epoch=False,\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\n\nevaluation = dict(interval=total_epochs, pipeline=test_pipeline, metric='bbox', map_metric='chamfer')\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# fp16 = dict(loss_scale=512.)\n# find_unused_parameters = True\ncheckpoint_config = dict(interval=1, max_keep_ckpts=total_epochs)\n\n\ncustom_hooks = [dict(type='CustomSetEpochInfoHook')]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/VAD/VAD_tiny_e2e.py",
    "content": "_base_ = [\n    '../datasets/custom_nus-3d.py',\n    '../_base_/default_runtime.py'\n]\n\n\n# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\nvoxel_size = [0.15, 0.15, 4]\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',\n    'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'\n]\nnum_classes = len(class_names)\n\n# map has classes: divider, ped_crossing, boundary\nmap_classes = ['divider', 'ped_crossing', 'boundary']\nmap_num_vec = 100\nmap_fixed_ptsnum_per_gt_line = 20 # now only support fixed_pts > 0\nmap_fixed_ptsnum_per_pred_line = 20\nmap_eval_use_same_gt_sample_num_flag = True\nmap_num_classes = len(map_classes)\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\n\n_dim_ = 256\n_pos_dim_ = _dim_//2\n_ffn_dim_ = _dim_*2\n_num_levels_ = 1\nbev_h_ = 100\nbev_w_ = 100\nqueue_length = 3 # each sequence contains `queue_length` frames.\ntotal_epochs = 60\n\nmodel = dict(\n    type='VAD',\n    use_grid_mask=True,\n    video_test_mode=True,\n    pretrained=dict(img='torchvision://resnet50'),\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(3,),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='pytorch'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[2048],\n        out_channels=_dim_,\n        start_level=0,\n        add_extra_convs='on_output',\n        num_outs=_num_levels_,\n        relu_before_extra_convs=True),\n    pts_bbox_head=dict(\n        type='VADHead',\n        map_thresh=0.5,\n        dis_thresh=0.2,\n        pe_normalization=True,\n        tot_epoch=total_epochs,\n        use_traj_lr_warmup=False,\n        query_thresh=0.0,\n        query_use_fix_pad=False,\n        ego_his_encoder=None,\n        ego_lcf_feat_idx=None,\n        valid_fut_ts=6,\n        ego_agent_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        ego_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        motion_map_decoder=dict(\n            type='CustomTransformerDecoder',\n            num_layers=1,\n            return_intermediate=False,\n            transformerlayers=dict(\n                type='BaseTransformerLayer',\n                attn_cfgs=[\n                    dict(\n                        type='MultiheadAttention',\n                        embed_dims=_dim_,\n                        num_heads=8,\n                        dropout=0.1),\n                ],\n                feedforward_channels=_ffn_dim_,\n                ffn_dropout=0.1,\n                operation_order=('cross_attn', 'norm', 'ffn', 'norm'))),\n        use_pe=True,\n        bev_h=bev_h_,\n        bev_w=bev_w_,\n        num_query=300,\n        num_classes=num_classes,\n        in_channels=_dim_,\n        sync_cls_avg_factor=True,\n        with_box_refine=True,\n        as_two_stage=False,\n        map_num_vec=map_num_vec,\n        map_num_classes=map_num_classes,\n        map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n        map_num_pts_per_gt_vec=map_fixed_ptsnum_per_gt_line,\n        map_query_embed_type='instance_pts',\n        map_transform_method='minmax',\n        map_gt_shift_pts_pattern='v2',\n        map_dir_interval=1,\n        map_code_size=2,\n        map_code_weights=[1.0, 1.0, 1.0, 1.0],\n        transformer=dict(\n            type='VADPerceptionTransformer',\n            map_num_vec=map_num_vec,\n            map_num_pts_per_vec=map_fixed_ptsnum_per_pred_line,\n            rotate_prev_bev=True,\n            use_shift=True,\n            use_can_bus=True,\n            embed_dims=_dim_,\n            encoder=dict(\n                type='BEVFormerEncoder',\n                num_layers=3,\n                pc_range=point_cloud_range,\n                num_points_in_pillar=4,\n                return_intermediate=False,\n                transformerlayers=dict(\n                    type='BEVFormerLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='TemporalSelfAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                        dict(\n                            type='SpatialCrossAttention',\n                            pc_range=point_cloud_range,\n                            deformable_attention=dict(\n                                type='MSDeformableAttention3D',\n                                embed_dims=_dim_,\n                                num_points=8,\n                                num_levels=_num_levels_),\n                            embed_dims=_dim_,\n                        )\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            decoder=dict(\n                type='DetectionTransformerDecoder',\n                num_layers=3,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                        dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm'))),\n            map_decoder=dict(\n                type='MapDetectionTransformerDecoder',\n                num_layers=3,\n                return_intermediate=True,\n                transformerlayers=dict(\n                    type='DetrTransformerDecoderLayer',\n                    attn_cfgs=[\n                        dict(\n                            type='MultiheadAttention',\n                            embed_dims=_dim_,\n                            num_heads=8,\n                            dropout=0.1),\n                         dict(\n                            type='CustomMSDeformableAttention',\n                            embed_dims=_dim_,\n                            num_levels=1),\n                    ],\n                    feedforward_channels=_ffn_dim_,\n                    ffn_dropout=0.1,\n                    operation_order=('self_attn', 'norm', 'cross_attn', 'norm',\n                                     'ffn', 'norm')))),\n        bbox_coder=dict(\n            type='CustomNMSFreeCoder',\n            post_center_range=[-20, -35, -10.0, 20, 35, 10.0],\n            pc_range=point_cloud_range,\n            max_num=100,\n            voxel_size=voxel_size,\n            num_classes=num_classes),\n        map_bbox_coder=dict(\n            type='MapNMSFreeCoder',\n            post_center_range=[-20, -35, -20, -35, 20, 35, 20, 35],\n            pc_range=point_cloud_range,\n            max_num=50,\n            voxel_size=voxel_size,\n            num_classes=map_num_classes),\n        positional_encoding=dict(\n            type='LearnedPositionalEncoding',\n            num_feats=_pos_dim_,\n            row_num_embed=bev_h_,\n            col_num_embed=bev_w_,\n            ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=0.25),\n        loss_traj=dict(type='L1Loss', loss_weight=0.2),\n        loss_traj_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=0.2),\n        loss_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=2.0),\n        loss_map_bbox=dict(type='L1Loss', loss_weight=0.0),\n        loss_map_iou=dict(type='GIoULoss', loss_weight=0.0),\n        loss_map_pts=dict(type='PtsL1Loss', loss_weight=1.0),\n        loss_map_dir=dict(type='PtsDirCosLoss', loss_weight=0.005),\n        loss_plan_reg=dict(type='L1Loss', loss_weight=1.0),\n        loss_plan_bound=dict(type='PlanMapBoundLoss', loss_weight=1.0, dis_thresh=1.0),\n        loss_plan_col=dict(type='PlanCollisionLoss', loss_weight=1.0),\n        loss_plan_dir=dict(type='PlanMapDirectionLoss', loss_weight=0.5)),\n    # model training and testing settings\n    train_cfg=dict(pts=dict(\n        grid_size=[512, 512, 1],\n        voxel_size=voxel_size,\n        point_cloud_range=point_cloud_range,\n        out_size_factor=4,\n        assigner=dict(\n            type='HungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBox3DL1Cost', weight=0.25),\n            iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.\n            pc_range=point_cloud_range),\n        map_assigner=dict(\n            type='MapHungarianAssigner3D',\n            cls_cost=dict(type='FocalLossCost', weight=2.0),\n            reg_cost=dict(type='BBoxL1Cost', weight=0.0, box_format='xywh'),\n            iou_cost=dict(type='IoUCost', iou_mode='giou', weight=0.0),\n            pts_cost=dict(type='OrderedPtsL1Cost', weight=1.0),\n            pc_range=point_cloud_range))))\n\ndataset_type = 'VADCustomNuScenesDataset'\ndata_root = 'data/nuscenes/'\nfile_client_args = dict(backend='disk')\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='CustomObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='CustomObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='RandomScaleImageMultiViewImage', scales=[0.4]),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='CustomDefaultFormatBundle3D', class_names=class_names, with_ego=True),\n    dict(type='CustomCollect3D',\\\n         keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'ego_his_trajs',\n               'ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd', 'ego_lcf_feat', 'gt_attr_labels'])\n]\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='LoadPointsFromFile',\n         coord_type='LIDAR',\n         load_dim=5,\n         use_dim=5,\n         file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=True),\n    dict(type='CustomObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='CustomObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    # dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.4]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='CustomDefaultFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D',\\\n                 keys=['points', 'gt_bboxes_3d', 'gt_labels_3d', 'img', 'fut_valid_flag',\n                       'ego_his_trajs', 'ego_fut_trajs', 'ego_fut_masks', 'ego_fut_cmd',\n                       'ego_lcf_feat', 'gt_attr_labels'])])\n]\n\ninference_only_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1600, 900),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(type='RandomScaleImageMultiViewImage', scales=[0.8]),\n            dict(type='PadMultiViewImage', size_divisor=32),\n            dict(type='VADFormatBundle3D', class_names=class_names, with_label=False, with_ego=True),\n            dict(type='CustomCollect3D', keys=[ 'img', 'ego_fut_cmd'])])\n]\n\ndata = dict(\n    samples_per_gpu=1,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'vad_nuscenes_infos_temporal_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        use_valid_flag=True,\n        bev_size=(bev_h_, bev_w_),\n        pc_range=point_cloud_range,\n        queue_length=queue_length,\n        map_classes=map_classes,\n        map_fixed_ptsnum_per_line=map_fixed_ptsnum_per_gt_line,\n        map_eval_use_same_gt_sample_num_flag=map_eval_use_same_gt_sample_num_flag,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR',\n        custom_eval_version='vad_nusc_detection_cvpr_2019'),\n    val=dict(type=dataset_type,\n             data_root=data_root,\n             pc_range=point_cloud_range,\n             ann_file=data_root + 'vad_nuscenes_infos_temporal_val.pkl',\n             pipeline=test_pipeline,  bev_size=(bev_h_, bev_w_),\n             classes=class_names, modality=input_modality, samples_per_gpu=1,\n             map_classes=map_classes,\n             map_ann_file=data_root + 'nuscenes_map_anns_val.json',\n             map_fixed_ptsnum_per_line=map_fixed_ptsnum_per_gt_line,\n             map_eval_use_same_gt_sample_num_flag=map_eval_use_same_gt_sample_num_flag,\n             use_pkl_result=True,\n             custom_eval_version='vad_nusc_detection_cvpr_2019'),\n    test=dict(type=dataset_type,\n              data_root=data_root,\n              pc_range=point_cloud_range,\n              ann_file=data_root + 'vad_nuscenes_infos_temporal_val.pkl',\n              pipeline=test_pipeline, bev_size=(bev_h_, bev_w_),\n              classes=class_names, modality=input_modality, samples_per_gpu=1,\n              map_classes=map_classes,\n              map_ann_file=data_root + 'nuscenes_map_anns_val.json',\n              map_fixed_ptsnum_per_line=map_fixed_ptsnum_per_gt_line,\n              map_eval_use_same_gt_sample_num_flag=map_eval_use_same_gt_sample_num_flag,\n              use_pkl_result=True,\n              custom_eval_version='vad_nusc_detection_cvpr_2019'),\n    shuffler_sampler=dict(type='DistributedGroupSampler'),\n    nonshuffler_sampler=dict(type='DistributedSampler')\n)\n\noptimizer = dict(\n    type='AdamW',\n    lr=2e-4,\n    paramwise_cfg=dict(\n        custom_keys={\n            'img_backbone': dict(lr_mult=0.1),\n        }),\n    weight_decay=0.01)\n\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\n# learning policy\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3)\n\nevaluation = dict(interval=total_epochs, pipeline=test_pipeline, metric='bbox', map_metric='chamfer')\n\nrunner = dict(type='EpochBasedRunner', max_epochs=total_epochs)\n\nlog_config = dict(\n    interval=100,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# fp16 = dict(loss_scale=512.)\n# find_unused_parameters = True\ncheckpoint_config = dict(interval=1, max_keep_ckpts=total_epochs)\n\n\ncustom_hooks = [dict(type='CustomSetEpochInfoHook')]"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/coco_instance.py",
    "content": "dataset_type = 'CocoDataset'\ndata_root = 'data/coco/'\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\ntrain_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(type='LoadAnnotations', with_bbox=True, with_mask=True),\n    dict(type='Resize', img_scale=(1333, 800), keep_ratio=True),\n    dict(type='RandomFlip', flip_ratio=0.5),\n    dict(type='Normalize', **img_norm_cfg),\n    dict(type='Pad', size_divisor=32),\n    dict(type='DefaultFormatBundle'),\n    dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels', 'gt_masks']),\n]\ntest_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(\n        type='MultiScaleFlipAug',\n        img_scale=(1333, 800),\n        flip=False,\n        transforms=[\n            dict(type='Resize', keep_ratio=True),\n            dict(type='RandomFlip'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(type='ImageToTensor', keys=['img']),\n            dict(type='Collect', keys=['img']),\n        ])\n]\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/instances_train2017.json',\n        img_prefix=data_root + 'train2017/',\n        pipeline=train_pipeline),\n    val=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/instances_val2017.json',\n        img_prefix=data_root + 'val2017/',\n        pipeline=test_pipeline),\n    test=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/instances_val2017.json',\n        img_prefix=data_root + 'val2017/',\n        pipeline=test_pipeline))\nevaluation = dict(metric=['bbox', 'segm'])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/kitti-3d-3class.py",
    "content": "# dataset settings\ndataset_type = 'KittiDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Pedestrian', 'Cyclist', 'Car']\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'kitti_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(\n        filter_by_difficulty=[-1],\n        filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),\n    classes=class_names,\n    sample_groups=dict(Car=12, Pedestrian=6, Cyclist=6))\n\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://kitti_data/'))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='ObjectNoise',\n        num_try=100,\n        translation_std=[1.0, 1.0, 0.5],\n        global_rot_range=[0.0, 0.0],\n        rot_range=[-0.78539816, 0.78539816]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=6,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'kitti_infos_train.pkl',\n            split='training',\n            pts_prefix='velodyne_reduced',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=1, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/kitti-3d-car.py",
    "content": "# dataset settings\ndataset_type = 'KittiDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Car']\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'kitti_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),\n    classes=class_names,\n    sample_groups=dict(Car=15))\n\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://kitti_data/'))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='ObjectNoise',\n        num_try=100,\n        translation_std=[1.0, 1.0, 0.5],\n        global_rot_range=[0.0, 0.0],\n        rot_range=[-0.78539816, 0.78539816]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=4,\n        use_dim=4,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=6,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'kitti_infos_train.pkl',\n            split='training',\n            pts_prefix='velodyne_reduced',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'kitti_infos_val.pkl',\n        split='training',\n        pts_prefix='velodyne_reduced',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=1, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/lyft-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-80, -80, -5, 80, 80, 3]\n# For Lyft we usually do 9-class detection\nclass_names = [\n    'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',\n    'bicycle', 'pedestrian', 'animal'\n]\ndataset_type = 'LyftDataset'\ndata_root = 'data/lyft/'\n# Input modality for Lyft dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/lyft/': 's3://lyft/lyft/',\n#         'data/lyft/': 's3://lyft/lyft/'\n#    }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_test.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True))\n# For Lyft dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/nuim_instance.py",
    "content": "dataset_type = 'CocoDataset'\ndata_root = 'data/nuimages/'\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\ntrain_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(type='LoadAnnotations', with_bbox=True, with_mask=True),\n    dict(\n        type='Resize',\n        img_scale=[(1280, 720), (1920, 1080)],\n        multiscale_mode='range',\n        keep_ratio=True),\n    dict(type='RandomFlip', flip_ratio=0.5),\n    dict(type='Normalize', **img_norm_cfg),\n    dict(type='Pad', size_divisor=32),\n    dict(type='DefaultFormatBundle'),\n    dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels', 'gt_masks']),\n]\ntest_pipeline = [\n    dict(type='LoadImageFromFile'),\n    dict(\n        type='MultiScaleFlipAug',\n        img_scale=(1600, 900),\n        flip=False,\n        transforms=[\n            dict(type='Resize', keep_ratio=True),\n            dict(type='RandomFlip'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(type='ImageToTensor', keys=['img']),\n            dict(type='Collect', keys=['img']),\n        ])\n]\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/nuimages_v1.0-train.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=train_pipeline),\n    val=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/nuimages_v1.0-val.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline),\n    test=dict(\n        type=dataset_type,\n        ann_file=data_root + 'annotations/nuimages_v1.0-val.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline))\nevaluation = dict(metric=['bbox', 'segm'])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/nus-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-50, -50, -5, 50, 50, 3]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\ndataset_type = 'NuScenesDataset'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=4,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/nus-mono3d.py",
    "content": "dataset_type = 'CustomNuScenesMonoDataset'\ndata_root = 'data/nuscenes/'\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)\ntrain_pipeline = [\n    dict(type='LoadImageFromFileMono3D'),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox=True,\n        with_label=True,\n        with_attr_label=True,\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_bbox_depth=True),\n    dict(type='Resize', img_scale=(1600, 900), keep_ratio=True),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='Normalize', **img_norm_cfg),\n    dict(type='Pad', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='Collect3D',\n        keys=[\n            'img', 'gt_bboxes', 'gt_labels', 'attr_labels', 'gt_bboxes_3d',\n            'gt_labels_3d', 'centers2d', 'depths'\n        ]),\n]\ntest_pipeline = [\n    dict(type='LoadImageFromFileMono3D'),\n    dict(\n        type='MultiScaleFlipAug',\n        scale_factor=1.0,\n        flip=False,\n        transforms=[\n            dict(type='RandomFlip3D'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['img']),\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(type='LoadImageFromFileMono3D'),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['img'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train_mono3d.coco.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=train_pipeline,\n        modality=input_modality,\n        test_mode=False,\n        box_type_3d='Camera'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val_mono3d.coco.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='Camera'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val_mono3d.coco.json',\n        img_prefix=data_root,\n        classes=class_names,\n        pipeline=test_pipeline,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='Camera'))\nevaluation = dict(interval=2)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/range100_lyft-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-100, -100, -5, 100, 100, 3]\n# For Lyft we usually do 9-class detection\nclass_names = [\n    'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',\n    'bicycle', 'pedestrian', 'animal'\n]\ndataset_type = 'LyftDataset'\ndata_root = 'data/lyft/'\n# Input modality for Lyft dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/lyft/': 's3://lyft/lyft/',\n#         'data/lyft/': 's3://lyft/lyft/'\n#    }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_test.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True))\n# For Lyft dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/s3dis-3d-5class.py",
    "content": "# dataset settings\ndataset_type = 'S3DISDataset'\ndata_root = './data/s3dis/'\nclass_names = ('table', 'chair', 'sofa', 'bookcase', 'board')\ntrain_area = [1, 2, 3, 4, 6]\ntest_area = 5\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(type='PointSample', num_points=40000),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        # following ScanNet dataset the rotation range is 5 degrees\n        rot_range=[-0.087266, 0.087266],\n        scale_ratio_range=[1.0, 1.0],\n        shift_height=True),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.5,\n                flip_ratio_bev_vertical=0.5),\n            dict(type='PointSample', num_points=40000),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=5,\n        dataset=dict(\n            type='ConcatDataset',\n            datasets=[\n                dict(\n                    type=dataset_type,\n                    data_root=data_root,\n                    ann_file=data_root + f's3dis_infos_Area_{i}.pkl',\n                    pipeline=train_pipeline,\n                    filter_empty_gt=False,\n                    classes=class_names,\n                    box_type_3d='Depth') for i in train_area\n            ],\n            separate_eval=False)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/s3dis_seg-3d-13class.py",
    "content": "# dataset settings\ndataset_type = 'S3DISSegDataset'\ndata_root = './data/s3dis/'\nclass_names = ('ceiling', 'floor', 'wall', 'beam', 'column', 'window', 'door',\n               'table', 'chair', 'sofa', 'bookcase', 'board', 'clutter')\nnum_points = 4096\ntrain_area = [1, 2, 3, 4, 6]\ntest_area = 5\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=tuple(range(len(class_names))),\n        max_cat_id=13),\n    dict(\n        type='IndoorPatchPointSample',\n        num_points=num_points,\n        block_size=1.0,\n        ignore_index=len(class_names),\n        use_normalized_coord=True,\n        enlarge_size=0.2,\n        min_unique_num=None),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(\n        # a wrapper in order to successfully call test function\n        # actually we don't perform test-time-aug\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.0,\n                flip_ratio_bev_vertical=0.0),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\n# we need to load gt seg_mask!\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=tuple(range(len(class_names))),\n        max_cat_id=13),\n    dict(\n        type='DefaultFormatBundle3D',\n        with_label=False,\n        class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    # train on area 1, 2, 3, 4, 6\n    # test on area 5\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_files=[\n            data_root + f's3dis_infos_Area_{i}.pkl' for i in train_area\n        ],\n        pipeline=train_pipeline,\n        classes=class_names,\n        test_mode=False,\n        ignore_index=len(class_names),\n        scene_idxs=[\n            data_root + f'seg_info/Area_{i}_resampled_scene_idxs.npy'\n            for i in train_area\n        ]),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_files=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names),\n        scene_idxs=data_root +\n        f'seg_info/Area_{test_area}_resampled_scene_idxs.npy'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_files=data_root + f's3dis_infos_Area_{test_area}.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names)))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/scannet-3d-18class.py",
    "content": "# dataset settings\ndataset_type = 'ScanNetDataset'\ndata_root = './data/scannet/'\nclass_names = ('cabinet', 'bed', 'chair', 'sofa', 'table', 'door', 'window',\n               'bookshelf', 'picture', 'counter', 'desk', 'curtain',\n               'refrigerator', 'showercurtrain', 'toilet', 'sink', 'bathtub',\n               'garbagebin')\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        with_mask_3d=True,\n        with_seg_3d=True),\n    dict(type='GlobalAlignment', rotation_axis=2),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=(3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28, 33, 34,\n                       36, 39),\n        max_cat_id=40),\n    dict(type='PointSample', num_points=40000),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.087266, 0.087266],\n        scale_ratio_range=[1.0, 1.0],\n        shift_height=True),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(\n        type='Collect3D',\n        keys=[\n            'points', 'gt_bboxes_3d', 'gt_labels_3d', 'pts_semantic_mask',\n            'pts_instance_mask'\n        ])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(type='GlobalAlignment', rotation_axis=2),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.5,\n                flip_ratio_bev_vertical=0.5),\n            dict(type='PointSample', num_points=40000),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(type='GlobalAlignment', rotation_axis=2),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=5,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'scannet_infos_train.pkl',\n            pipeline=train_pipeline,\n            filter_empty_gt=False,\n            classes=class_names,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='Depth')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/scannet_seg-3d-20class.py",
    "content": "# dataset settings\ndataset_type = 'ScanNetSegDataset'\ndata_root = './data/scannet/'\nclass_names = ('wall', 'floor', 'cabinet', 'bed', 'chair', 'sofa', 'table',\n               'door', 'window', 'bookshelf', 'picture', 'counter', 'desk',\n               'curtain', 'refrigerator', 'showercurtrain', 'toilet', 'sink',\n               'bathtub', 'otherfurniture')\nnum_points = 8192\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28,\n                       33, 34, 36, 39),\n        max_cat_id=40),\n    dict(\n        type='IndoorPatchPointSample',\n        num_points=num_points,\n        block_size=1.5,\n        ignore_index=len(class_names),\n        use_normalized_coord=False,\n        enlarge_size=0.2,\n        min_unique_num=None),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(type='NormalizePointsColor', color_mean=None),\n    dict(\n        # a wrapper in order to successfully call test function\n        # actually we don't perform test-time-aug\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.0,\n                flip_ratio_bev_vertical=0.0),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\n# we need to load gt seg_mask!\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        use_color=True,\n        load_dim=6,\n        use_dim=[0, 1, 2, 3, 4, 5]),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=False,\n        with_label_3d=False,\n        with_mask_3d=False,\n        with_seg_3d=True),\n    dict(\n        type='PointSegClassMapping',\n        valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28,\n                       33, 34, 36, 39),\n        max_cat_id=40),\n    dict(\n        type='DefaultFormatBundle3D',\n        with_label=False,\n        class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])\n]\n\ndata = dict(\n    samples_per_gpu=8,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        test_mode=False,\n        ignore_index=len(class_names),\n        scene_idxs=data_root + 'seg_info/train_resampled_scene_idxs.npy'),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names)),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'scannet_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        ignore_index=len(class_names)))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/sunrgbd-3d-10class.py",
    "content": "dataset_type = 'SUNRGBDDataset'\ndata_root = 'data/sunrgbd/'\nclass_names = ('bed', 'table', 'sofa', 'chair', 'toilet', 'desk', 'dresser',\n               'night_stand', 'bookshelf', 'bathtub')\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(type='LoadAnnotations3D'),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n    ),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.523599, 0.523599],\n        scale_ratio_range=[0.85, 1.15],\n        shift_height=True),\n    dict(type='PointSample', num_points=20000),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=True,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(\n                type='RandomFlip3D',\n                sync_2d=False,\n                flip_ratio_bev_horizontal=0.5,\n            ),\n            dict(type='PointSample', num_points=20000),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='DEPTH',\n        shift_height=False,\n        load_dim=6,\n        use_dim=[0, 1, 2]),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=16,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=5,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'sunrgbd_infos_train.pkl',\n            pipeline=train_pipeline,\n            classes=class_names,\n            filter_empty_gt=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='Depth')),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'sunrgbd_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'sunrgbd_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='Depth'))\n\nevaluation = dict(pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/waymoD5-3d-3class.py",
    "content": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for efficient experiments\ndataset_type = 'LidarWaymoDataset'\ndata_root = 'data/waymo-full/kitti_format/'\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://waymo_data/'))\n\nclass_names = ['Car', 'Pedestrian', 'Cyclist']\npoint_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'waymo_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(\n        filter_by_difficulty=[-1],\n        filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),\n    classes=class_names,\n    sample_groups=dict(Car=15, Pedestrian=10, Cyclist=10),\n    points_loader=dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=[0, 1, 2, 3, 4],\n        file_client_args=file_client_args))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'waymo_infos_train.pkl',\n            split='training',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR',\n            # load one frame every five frames\n            load_interval=5)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/datasets/waymoD5-3d-car.py",
    "content": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for efficient experiments\ndataset_type = 'WaymoDataset'\ndata_root = 'data/waymo/kitti_format/'\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://waymo_data/'))\n\nclass_names = ['Car']\npoint_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]\ninput_modality = dict(use_lidar=True, use_camera=False)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'waymo_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),\n    classes=class_names,\n    sample_groups=dict(Car=15),\n    points_loader=dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=[0, 1, 2, 3, 4],\n        file_client_args=file_client_args))\n\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadAnnotations3D',\n        with_bbox_3d=True,\n        with_label_3d=True,\n        file_client_args=file_client_args),\n    dict(type='ObjectSample', db_sampler=db_sampler),\n    dict(\n        type='RandomFlip3D',\n        sync_2d=False,\n        flip_ratio_bev_horizontal=0.5,\n        flip_ratio_bev_vertical=0.5),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.78539816, 0.78539816],\n        scale_ratio_range=[0.95, 1.05]),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=6,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'waymo_infos_train.pkl',\n            split='training',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR',\n            # load one frame every five frames\n            load_interval=5)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/default_runtime.py",
    "content": "checkpoint_config = dict(interval=1)\n# yapf:disable push\n# By default we use textlogger hook and tensorboard\n# For more loggers see\n# https://mmcv.readthedocs.io/en/latest/api.html#mmcv.runner.LoggerHook\nlog_config = dict(\n    interval=50,\n    hooks=[\n        dict(type='TextLoggerHook'),\n        dict(type='TensorboardLoggerHook')\n    ])\n# yapf:enable\ndist_params = dict(backend='nccl')\nlog_level = 'INFO'\nwork_dir = None\nload_from = None\nresume_from = None\nworkflow = [('train', 1)]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/3dssd.py",
    "content": "model = dict(\n    type='SSD3DNet',\n    backbone=dict(\n        type='PointNet2SAMSG',\n        in_channels=4,\n        num_points=(4096, 512, (256, 256)),\n        radii=((0.2, 0.4, 0.8), (0.4, 0.8, 1.6), (1.6, 3.2, 4.8)),\n        num_samples=((32, 32, 64), (32, 32, 64), (32, 32, 32)),\n        sa_channels=(((16, 16, 32), (16, 16, 32), (32, 32, 64)),\n                     ((64, 64, 128), (64, 64, 128), (64, 96, 128)),\n                     ((128, 128, 256), (128, 192, 256), (128, 256, 256))),\n        aggregation_channels=(64, 128, 256),\n        fps_mods=(('D-FPS'), ('FS'), ('F-FPS', 'D-FPS')),\n        fps_sample_range_lists=((-1), (-1), (512, -1)),\n        norm_cfg=dict(type='BN2d', eps=1e-3, momentum=0.1),\n        sa_cfg=dict(\n            type='PointSAModuleMSG',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False)),\n    bbox_head=dict(\n        type='SSD3DHead',\n        in_channels=256,\n        vote_module_cfg=dict(\n            in_channels=256,\n            num_points=256,\n            gt_per_seed=1,\n            conv_channels=(128, ),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),\n            with_res_feat=False,\n            vote_xyz_range=(3.0, 3.0, 2.0)),\n        vote_aggregation_cfg=dict(\n            type='PointSAModuleMSG',\n            num_point=256,\n            radii=(4.8, 6.4),\n            sample_nums=(16, 32),\n            mlp_channels=((256, 256, 256, 512), (256, 256, 512, 1024)),\n            norm_cfg=dict(type='BN2d', eps=1e-3, momentum=0.1),\n            use_xyz=True,\n            normalize_xyz=False,\n            bias=True),\n        pred_layer_cfg=dict(\n            in_channels=1536,\n            shared_conv_channels=(512, 128),\n            cls_conv_channels=(128, ),\n            reg_conv_channels=(128, ),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),\n            bias=True),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),\n        objectness_loss=dict(\n            type='CrossEntropyLoss',\n            use_sigmoid=True,\n            reduction='sum',\n            loss_weight=1.0),\n        center_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        corner_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=1.0),\n        vote_loss=dict(type='SmoothL1Loss', reduction='sum', loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(\n        sample_mod='spec', pos_distance_thr=10.0, expand_dims_length=0.05),\n    test_cfg=dict(\n        nms_cfg=dict(type='nms', iou_thr=0.1),\n        sample_mod='spec',\n        score_thr=0.0,\n        per_class_proposal=True,\n        max_output_num=100))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/cascade_mask_rcnn_r50_fpn.py",
    "content": "# model settings\nmodel = dict(\n    type='CascadeRCNN',\n    pretrained='torchvision://resnet50',\n    backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=True),\n        norm_eval=True,\n        style='pytorch'),\n    neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        num_outs=5),\n    rpn_head=dict(\n        type='RPNHead',\n        in_channels=256,\n        feat_channels=256,\n        anchor_generator=dict(\n            type='AnchorGenerator',\n            scales=[8],\n            ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64]),\n        bbox_coder=dict(\n            type='DeltaXYWHBBoxCoder',\n            target_means=[.0, .0, .0, .0],\n            target_stds=[1.0, 1.0, 1.0, 1.0]),\n        loss_cls=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0)),\n    roi_head=dict(\n        type='CascadeRoIHead',\n        num_stages=3,\n        stage_loss_weights=[1, 0.5, 0.25],\n        bbox_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        bbox_head=[\n            dict(\n                type='Shared2FCBBoxHead',\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type='DeltaXYWHBBoxCoder',\n                    target_means=[0., 0., 0., 0.],\n                    target_stds=[0.1, 0.1, 0.2, 0.2]),\n                reg_class_agnostic=True,\n                loss_cls=dict(\n                    type='CrossEntropyLoss',\n                    use_sigmoid=False,\n                    loss_weight=1.0),\n                loss_bbox=dict(type='SmoothL1Loss', beta=1.0,\n                               loss_weight=1.0)),\n            dict(\n                type='Shared2FCBBoxHead',\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type='DeltaXYWHBBoxCoder',\n                    target_means=[0., 0., 0., 0.],\n                    target_stds=[0.05, 0.05, 0.1, 0.1]),\n                reg_class_agnostic=True,\n                loss_cls=dict(\n                    type='CrossEntropyLoss',\n                    use_sigmoid=False,\n                    loss_weight=1.0),\n                loss_bbox=dict(type='SmoothL1Loss', beta=1.0,\n                               loss_weight=1.0)),\n            dict(\n                type='Shared2FCBBoxHead',\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type='DeltaXYWHBBoxCoder',\n                    target_means=[0., 0., 0., 0.],\n                    target_stds=[0.033, 0.033, 0.067, 0.067]),\n                reg_class_agnostic=True,\n                loss_cls=dict(\n                    type='CrossEntropyLoss',\n                    use_sigmoid=False,\n                    loss_weight=1.0),\n                loss_bbox=dict(type='SmoothL1Loss', beta=1.0, loss_weight=1.0))\n        ],\n        mask_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=14, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        mask_head=dict(\n            type='FCNMaskHead',\n            num_convs=4,\n            in_channels=256,\n            conv_out_channels=256,\n            num_classes=80,\n            loss_mask=dict(\n                type='CrossEntropyLoss', use_mask=True, loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.7,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=256,\n                pos_fraction=0.5,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False),\n            allowed_border=0,\n            pos_weight=-1,\n            debug=False),\n        rpn_proposal=dict(\n            nms_across_levels=False,\n            nms_pre=2000,\n            nms_post=2000,\n            max_num=2000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=[\n            dict(\n                assigner=dict(\n                    type='MaxIoUAssigner',\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.5,\n                    min_pos_iou=0.5,\n                    match_low_quality=False,\n                    ignore_iof_thr=-1),\n                sampler=dict(\n                    type='RandomSampler',\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False),\n            dict(\n                assigner=dict(\n                    type='MaxIoUAssigner',\n                    pos_iou_thr=0.6,\n                    neg_iou_thr=0.6,\n                    min_pos_iou=0.6,\n                    match_low_quality=False,\n                    ignore_iof_thr=-1),\n                sampler=dict(\n                    type='RandomSampler',\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False),\n            dict(\n                assigner=dict(\n                    type='MaxIoUAssigner',\n                    pos_iou_thr=0.7,\n                    neg_iou_thr=0.7,\n                    min_pos_iou=0.7,\n                    match_low_quality=False,\n                    ignore_iof_thr=-1),\n                sampler=dict(\n                    type='RandomSampler',\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False)\n        ]),\n    test_cfg=dict(\n        rpn=dict(\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_post=1000,\n            max_num=1000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=dict(\n            score_thr=0.05,\n            nms=dict(type='nms', iou_threshold=0.5),\n            max_per_img=100,\n            mask_thr_binary=0.5)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/centerpoint_01voxel_second_secfpn_nus.py",
    "content": "voxel_size = [0.1, 0.1, 0.2]\nmodel = dict(\n    type='CenterPoint',\n    pts_voxel_layer=dict(\n        max_num_points=10, voxel_size=voxel_size, max_voxels=(90000, 120000)),\n    pts_voxel_encoder=dict(type='HardSimpleVFE', num_features=5),\n    pts_middle_encoder=dict(\n        type='SparseEncoder',\n        in_channels=5,\n        sparse_shape=[41, 1024, 1024],\n        output_channels=128,\n        order=('conv', 'norm', 'act'),\n        encoder_channels=((16, 16, 32), (32, 32, 64), (64, 64, 128), (128,\n                                                                      128)),\n        encoder_paddings=((0, 0, 1), (0, 0, 1), (0, 0, [0, 1, 1]), (0, 0)),\n        block_type='basicblock'),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=256,\n        out_channels=[128, 256],\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        conv_cfg=dict(type='Conv2d', bias=False)),\n    pts_neck=dict(\n        type='SECONDFPN',\n        in_channels=[128, 256],\n        out_channels=[256, 256],\n        upsample_strides=[1, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        upsample_cfg=dict(type='deconv', bias=False),\n        use_conv_for_no_stride=True),\n    pts_bbox_head=dict(\n        type='CenterHead',\n        in_channels=sum([256, 256]),\n        tasks=[\n            dict(num_class=1, class_names=['car']),\n            dict(num_class=2, class_names=['truck', 'construction_vehicle']),\n            dict(num_class=2, class_names=['bus', 'trailer']),\n            dict(num_class=1, class_names=['barrier']),\n            dict(num_class=2, class_names=['motorcycle', 'bicycle']),\n            dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),\n        ],\n        common_heads=dict(\n            reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),\n        share_conv_channel=64,\n        bbox_coder=dict(\n            type='CenterPointBBoxCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_num=500,\n            score_threshold=0.1,\n            out_size_factor=8,\n            voxel_size=voxel_size[:2],\n            code_size=9),\n        separate_head=dict(\n            type='SeparateHead', init_bias=-2.19, final_kernel=3),\n        loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),\n        loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),\n        norm_bbox=True),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[1024, 1024, 40],\n            voxel_size=voxel_size,\n            out_size_factor=8,\n            dense_reg=1,\n            gaussian_overlap=0.1,\n            max_objs=500,\n            min_radius=2,\n            code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])),\n    test_cfg=dict(\n        pts=dict(\n            post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_per_img=500,\n            max_pool_nms=False,\n            min_radius=[4, 12, 10, 1, 0.85, 0.175],\n            score_threshold=0.1,\n            out_size_factor=8,\n            voxel_size=voxel_size[:2],\n            nms_type='rotate',\n            pre_max_size=1000,\n            post_max_size=83,\n            nms_thr=0.2)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/centerpoint_02pillar_second_secfpn_nus.py",
    "content": "voxel_size = [0.2, 0.2, 8]\nmodel = dict(\n    type='CenterPoint',\n    pts_voxel_layer=dict(\n        max_num_points=20, voxel_size=voxel_size, max_voxels=(30000, 40000)),\n    pts_voxel_encoder=dict(\n        type='PillarFeatureNet',\n        in_channels=5,\n        feat_channels=[64],\n        with_distance=False,\n        voxel_size=(0.2, 0.2, 8),\n        norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.01),\n        legacy=False),\n    pts_middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=(512, 512)),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        out_channels=[64, 128, 256],\n        layer_nums=[3, 5, 5],\n        layer_strides=[2, 2, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        conv_cfg=dict(type='Conv2d', bias=False)),\n    pts_neck=dict(\n        type='SECONDFPN',\n        in_channels=[64, 128, 256],\n        out_channels=[128, 128, 128],\n        upsample_strides=[0.5, 1, 2],\n        norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),\n        upsample_cfg=dict(type='deconv', bias=False),\n        use_conv_for_no_stride=True),\n    pts_bbox_head=dict(\n        type='CenterHead',\n        in_channels=sum([128, 128, 128]),\n        tasks=[\n            dict(num_class=1, class_names=['car']),\n            dict(num_class=2, class_names=['truck', 'construction_vehicle']),\n            dict(num_class=2, class_names=['bus', 'trailer']),\n            dict(num_class=1, class_names=['barrier']),\n            dict(num_class=2, class_names=['motorcycle', 'bicycle']),\n            dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),\n        ],\n        common_heads=dict(\n            reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),\n        share_conv_channel=64,\n        bbox_coder=dict(\n            type='CenterPointBBoxCoder',\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_num=500,\n            score_threshold=0.1,\n            out_size_factor=4,\n            voxel_size=voxel_size[:2],\n            code_size=9),\n        separate_head=dict(\n            type='SeparateHead', init_bias=-2.19, final_kernel=3),\n        loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),\n        loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),\n        norm_bbox=True),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            grid_size=[512, 512, 1],\n            voxel_size=voxel_size,\n            out_size_factor=4,\n            dense_reg=1,\n            gaussian_overlap=0.1,\n            max_objs=500,\n            min_radius=2,\n            code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])),\n    test_cfg=dict(\n        pts=dict(\n            post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            max_per_img=500,\n            max_pool_nms=False,\n            min_radius=[4, 12, 10, 1, 0.85, 0.175],\n            score_threshold=0.1,\n            pc_range=[-51.2, -51.2],\n            out_size_factor=4,\n            voxel_size=voxel_size[:2],\n            nms_type='rotate',\n            pre_max_size=1000,\n            post_max_size=83,\n            nms_thr=0.2)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/fcos3d.py",
    "content": "model = dict(\n    type='FCOSMono3D',\n    pretrained='open-mmlab://detectron2/resnet101_caffe',\n    backbone=dict(\n        type='ResNet',\n        depth=101,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='caffe'),\n    neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        start_level=1,\n        add_extra_convs='on_output',\n        num_outs=5,\n        relu_before_extra_convs=True),\n    bbox_head=dict(\n        type='FCOSMono3DHead',\n        num_classes=10,\n        in_channels=256,\n        stacked_convs=2,\n        feat_channels=256,\n        use_direction_classifier=True,\n        diff_rad_by_sin=True,\n        pred_attrs=True,\n        pred_velo=True,\n        dir_offset=0.7854,  # pi/4\n        strides=[8, 16, 32, 64, 128],\n        group_reg_dims=(2, 1, 3, 1, 2),  # offset, depth, size, rot, velo\n        cls_branch=(256, ),\n        reg_branch=(\n            (256, ),  # offset\n            (256, ),  # depth\n            (256, ),  # size\n            (256, ),  # rot\n            ()  # velo\n        ),\n        dir_branch=(256, ),\n        attr_branch=(256, ),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n        loss_attr=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n        loss_centerness=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        norm_on_bbox=True,\n        centerness_on_reg=True,\n        center_sampling=True,\n        conv_bias=True,\n        dcn_on_last_conv=True),\n    train_cfg=dict(\n        allowed_border=0,\n        code_weight=[1.0, 1.0, 0.2, 1.0, 1.0, 1.0, 1.0, 0.05, 0.05],\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_pre=1000,\n        nms_thr=0.8,\n        score_thr=0.05,\n        min_bbox_size=0,\n        max_per_img=200))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/groupfree3d.py",
    "content": "model = dict(\n    type='GroupFree3DNet',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=3,\n        num_points=(2048, 1024, 512, 256),\n        radius=(0.2, 0.4, 0.8, 1.2),\n        num_samples=(64, 32, 16, 16),\n        sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),\n                     (128, 128, 256)),\n        fp_channels=((256, 256), (256, 288)),\n        norm_cfg=dict(type='BN2d'),\n        sa_cfg=dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=True)),\n    bbox_head=dict(\n        type='GroupFree3DHead',\n        in_channels=288,\n        num_decoder_layers=6,\n        num_proposal=256,\n        transformerlayers=dict(\n            type='BaseTransformerLayer',\n            attn_cfgs=dict(\n                type='GroupFree3DMHA',\n                embed_dims=288,\n                num_heads=8,\n                attn_drop=0.1,\n                dropout_layer=dict(type='Dropout', drop_prob=0.1)),\n            ffn_cfgs=dict(\n                embed_dims=288,\n                feedforward_channels=2048,\n                ffn_drop=0.1,\n                act_cfg=dict(type='ReLU', inplace=True)),\n            operation_order=('self_attn', 'norm', 'cross_attn', 'norm', 'ffn',\n                             'norm')),\n        pred_layer_cfg=dict(\n            in_channels=288, shared_conv_channels=(288, 288), bias=True),\n        sampling_objectness_loss=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=8.0),\n        objectness_loss=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        center_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        size_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', beta=1.0, reduction='sum', loss_weight=10.0),\n        semantic_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(sample_mod='kps'),\n    test_cfg=dict(\n        sample_mod='kps',\n        nms_thr=0.25,\n        score_thr=0.0,\n        per_class_proposal=True,\n        prediction_stages='last'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/h3dnet.py",
    "content": "primitive_z_cfg = dict(\n    type='PrimitiveHead',\n    num_dims=2,\n    num_classes=18,\n    primitive_mode='z',\n    upper_thresh=100.0,\n    surface_thresh=0.5,\n    vote_module_cfg=dict(\n        in_channels=256,\n        vote_per_seed=1,\n        gt_per_seed=1,\n        conv_channels=(256, 256),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        norm_feats=True,\n        vote_loss=dict(\n            type='ChamferDistance',\n            mode='l1',\n            reduction='none',\n            loss_dst_weight=10.0)),\n    vote_aggregation_cfg=dict(\n        type='PointSAModule',\n        num_point=1024,\n        radius=0.3,\n        num_sample=16,\n        mlp_channels=[256, 128, 128, 128],\n        use_xyz=True,\n        normalize_xyz=True),\n    feat_channels=(128, 128),\n    conv_cfg=dict(type='Conv1d'),\n    norm_cfg=dict(type='BN1d'),\n    objectness_loss=dict(\n        type='CrossEntropyLoss',\n        class_weight=[0.4, 0.6],\n        reduction='mean',\n        loss_weight=30.0),\n    center_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_reg_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_cls_loss=dict(\n        type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n    train_cfg=dict(\n        dist_thresh=0.2,\n        var_thresh=1e-2,\n        lower_thresh=1e-6,\n        num_point=100,\n        num_point_line=10,\n        line_thresh=0.2))\n\nprimitive_xy_cfg = dict(\n    type='PrimitiveHead',\n    num_dims=1,\n    num_classes=18,\n    primitive_mode='xy',\n    upper_thresh=100.0,\n    surface_thresh=0.5,\n    vote_module_cfg=dict(\n        in_channels=256,\n        vote_per_seed=1,\n        gt_per_seed=1,\n        conv_channels=(256, 256),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        norm_feats=True,\n        vote_loss=dict(\n            type='ChamferDistance',\n            mode='l1',\n            reduction='none',\n            loss_dst_weight=10.0)),\n    vote_aggregation_cfg=dict(\n        type='PointSAModule',\n        num_point=1024,\n        radius=0.3,\n        num_sample=16,\n        mlp_channels=[256, 128, 128, 128],\n        use_xyz=True,\n        normalize_xyz=True),\n    feat_channels=(128, 128),\n    conv_cfg=dict(type='Conv1d'),\n    norm_cfg=dict(type='BN1d'),\n    objectness_loss=dict(\n        type='CrossEntropyLoss',\n        class_weight=[0.4, 0.6],\n        reduction='mean',\n        loss_weight=30.0),\n    center_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_reg_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=0.5,\n        loss_dst_weight=0.5),\n    semantic_cls_loss=dict(\n        type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n    train_cfg=dict(\n        dist_thresh=0.2,\n        var_thresh=1e-2,\n        lower_thresh=1e-6,\n        num_point=100,\n        num_point_line=10,\n        line_thresh=0.2))\n\nprimitive_line_cfg = dict(\n    type='PrimitiveHead',\n    num_dims=0,\n    num_classes=18,\n    primitive_mode='line',\n    upper_thresh=100.0,\n    surface_thresh=0.5,\n    vote_module_cfg=dict(\n        in_channels=256,\n        vote_per_seed=1,\n        gt_per_seed=1,\n        conv_channels=(256, 256),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        norm_feats=True,\n        vote_loss=dict(\n            type='ChamferDistance',\n            mode='l1',\n            reduction='none',\n            loss_dst_weight=10.0)),\n    vote_aggregation_cfg=dict(\n        type='PointSAModule',\n        num_point=1024,\n        radius=0.3,\n        num_sample=16,\n        mlp_channels=[256, 128, 128, 128],\n        use_xyz=True,\n        normalize_xyz=True),\n    feat_channels=(128, 128),\n    conv_cfg=dict(type='Conv1d'),\n    norm_cfg=dict(type='BN1d'),\n    objectness_loss=dict(\n        type='CrossEntropyLoss',\n        class_weight=[0.4, 0.6],\n        reduction='mean',\n        loss_weight=30.0),\n    center_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=1.0,\n        loss_dst_weight=1.0),\n    semantic_reg_loss=dict(\n        type='ChamferDistance',\n        mode='l1',\n        reduction='sum',\n        loss_src_weight=1.0,\n        loss_dst_weight=1.0),\n    semantic_cls_loss=dict(\n        type='CrossEntropyLoss', reduction='sum', loss_weight=2.0),\n    train_cfg=dict(\n        dist_thresh=0.2,\n        var_thresh=1e-2,\n        lower_thresh=1e-6,\n        num_point=100,\n        num_point_line=10,\n        line_thresh=0.2))\n\nmodel = dict(\n    type='H3DNet',\n    backbone=dict(\n        type='MultiBackbone',\n        num_streams=4,\n        suffixes=['net0', 'net1', 'net2', 'net3'],\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d', eps=1e-5, momentum=0.01),\n        act_cfg=dict(type='ReLU'),\n        backbones=dict(\n            type='PointNet2SASSG',\n            in_channels=4,\n            num_points=(2048, 1024, 512, 256),\n            radius=(0.2, 0.4, 0.8, 1.2),\n            num_samples=(64, 32, 16, 16),\n            sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),\n                         (128, 128, 256)),\n            fp_channels=((256, 256), (256, 256)),\n            norm_cfg=dict(type='BN2d'),\n            sa_cfg=dict(\n                type='PointSAModule',\n                pool_mod='max',\n                use_xyz=True,\n                normalize_xyz=True))),\n    rpn_head=dict(\n        type='VoteHead',\n        vote_module_cfg=dict(\n            in_channels=256,\n            vote_per_seed=1,\n            gt_per_seed=3,\n            conv_channels=(256, 256),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d'),\n            norm_feats=True,\n            vote_loss=dict(\n                type='ChamferDistance',\n                mode='l1',\n                reduction='none',\n                loss_dst_weight=10.0)),\n        vote_aggregation_cfg=dict(\n            type='PointSAModule',\n            num_point=256,\n            radius=0.3,\n            num_sample=16,\n            mlp_channels=[256, 128, 128, 128],\n            use_xyz=True,\n            normalize_xyz=True),\n        pred_layer_cfg=dict(\n            in_channels=128, shared_conv_channels=(128, 128), bias=True),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        objectness_loss=dict(\n            type='CrossEntropyLoss',\n            class_weight=[0.2, 0.8],\n            reduction='sum',\n            loss_weight=5.0),\n        center_loss=dict(\n            type='ChamferDistance',\n            mode='l2',\n            reduction='sum',\n            loss_src_weight=10.0,\n            loss_dst_weight=10.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        size_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        semantic_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),\n    roi_head=dict(\n        type='H3DRoIHead',\n        primitive_list=[primitive_z_cfg, primitive_xy_cfg, primitive_line_cfg],\n        bbox_head=dict(\n            type='H3DBboxHead',\n            gt_per_seed=3,\n            num_proposal=256,\n            suface_matching_cfg=dict(\n                type='PointSAModule',\n                num_point=256 * 6,\n                radius=0.5,\n                num_sample=32,\n                mlp_channels=[128 + 6, 128, 64, 32],\n                use_xyz=True,\n                normalize_xyz=True),\n            line_matching_cfg=dict(\n                type='PointSAModule',\n                num_point=256 * 12,\n                radius=0.5,\n                num_sample=32,\n                mlp_channels=[128 + 12, 128, 64, 32],\n                use_xyz=True,\n                normalize_xyz=True),\n            feat_channels=(128, 128),\n            primitive_refine_channels=[128, 128, 128],\n            upper_thresh=100.0,\n            surface_thresh=0.5,\n            line_thresh=0.5,\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d'),\n            objectness_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.2, 0.8],\n                reduction='sum',\n                loss_weight=5.0),\n            center_loss=dict(\n                type='ChamferDistance',\n                mode='l2',\n                reduction='sum',\n                loss_src_weight=10.0,\n                loss_dst_weight=10.0),\n            dir_class_loss=dict(\n                type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),\n            dir_res_loss=dict(\n                type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n            size_class_loss=dict(\n                type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),\n            size_res_loss=dict(\n                type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n            semantic_loss=dict(\n                type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),\n            cues_objectness_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.3, 0.7],\n                reduction='mean',\n                loss_weight=5.0),\n            cues_semantic_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.3, 0.7],\n                reduction='mean',\n                loss_weight=5.0),\n            proposal_objectness_loss=dict(\n                type='CrossEntropyLoss',\n                class_weight=[0.2, 0.8],\n                reduction='none',\n                loss_weight=5.0),\n            primitive_center_loss=dict(\n                type='MSELoss', reduction='none', loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            pos_distance_thr=0.3, neg_distance_thr=0.6, sample_mod='vote'),\n        rpn_proposal=dict(use_nms=False),\n        rcnn=dict(\n            pos_distance_thr=0.3,\n            neg_distance_thr=0.6,\n            sample_mod='vote',\n            far_threshold=0.6,\n            near_threshold=0.3,\n            mask_surface_threshold=0.3,\n            label_surface_threshold=0.3,\n            mask_line_threshold=0.3,\n            label_line_threshold=0.3)),\n    test_cfg=dict(\n        rpn=dict(\n            sample_mod='seed',\n            nms_thr=0.25,\n            score_thr=0.05,\n            per_class_proposal=True,\n            use_nms=False),\n        rcnn=dict(\n            sample_mod='seed',\n            nms_thr=0.25,\n            score_thr=0.05,\n            per_class_proposal=True)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_pointpillars_fpn_lyft.py",
    "content": "_base_ = './hv_pointpillars_fpn_nus.py'\n\n# model settings (based on nuScenes model settings)\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nmodel = dict(\n    pts_voxel_layer=dict(\n        max_num_points=20,\n        point_cloud_range=[-80, -80, -5, 80, 80, 3],\n        max_voxels=(60000, 60000)),\n    pts_voxel_encoder=dict(\n        feat_channels=[64], point_cloud_range=[-80, -80, -5, 80, 80, 3]),\n    pts_middle_encoder=dict(output_shape=[640, 640]),\n    pts_bbox_head=dict(\n        num_classes=9,\n        anchor_generator=dict(\n            ranges=[[-80, -80, -1.8, 80, 80, -1.8]], custom_values=[]),\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7)),\n    # model training settings (based on nuScenes model settings)\n    train_cfg=dict(pts=dict(code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_pointpillars_fpn_nus.py",
    "content": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nvoxel_size = [0.25, 0.25, 8]\nmodel = dict(\n    type='MVXFasterRCNN',\n    pts_voxel_layer=dict(\n        max_num_points=64,\n        point_cloud_range=[-50, -50, -5, 50, 50, 3],\n        voxel_size=voxel_size,\n        max_voxels=(30000, 40000)),\n    pts_voxel_encoder=dict(\n        type='HardVFE',\n        in_channels=4,\n        feat_channels=[64, 64],\n        with_distance=False,\n        voxel_size=voxel_size,\n        with_cluster_center=True,\n        with_voxel_center=True,\n        point_cloud_range=[-50, -50, -5, 50, 50, 3],\n        norm_cfg=dict(type='naiveSyncBN1d', eps=1e-3, momentum=0.01)),\n    pts_middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=[400, 400]),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        layer_nums=[3, 5, 5],\n        layer_strides=[2, 2, 2],\n        out_channels=[64, 128, 256]),\n    pts_neck=dict(\n        type='FPN',\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        act_cfg=dict(type='ReLU'),\n        in_channels=[64, 128, 256],\n        out_channels=256,\n        start_level=0,\n        num_outs=3),\n    pts_bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=10,\n        in_channels=256,\n        feat_channels=256,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='AlignedAnchor3DRangeGenerator',\n            ranges=[[-50, -50, -1.8, 50, 50, -1.8]],\n            scales=[1, 2, 4],\n            sizes=[\n                [0.8660, 2.5981, 1.],  # 1.5/sqrt(3)\n                [0.5774, 1.7321, 1.],  # 1/sqrt(3)\n                [1., 1., 1.],\n                [0.4, 0.4, 1],\n            ],\n            custom_values=[0, 0],\n            rotations=[0, 1.57],\n            reshape_out=True),\n        assigner_per_size=False,\n        diff_rad_by_sin=True,\n        dir_offset=0.7854,  # pi/4\n        dir_limit_offset=0,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=9),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.6,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                ignore_iof_thr=-1),\n            allowed_border=0,\n            code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        pts=dict(\n            use_rotate_nms=True,\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_thr=0.2,\n            score_thr=0.05,\n            min_bbox_size=0,\n            max_num=500)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_pointpillars_fpn_range100_lyft.py",
    "content": "_base_ = './hv_pointpillars_fpn_nus.py'\n\n# model settings (based on nuScenes model settings)\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nmodel = dict(\n    pts_voxel_layer=dict(\n        max_num_points=20,\n        point_cloud_range=[-100, -100, -5, 100, 100, 3],\n        max_voxels=(60000, 60000)),\n    pts_voxel_encoder=dict(\n        feat_channels=[64], point_cloud_range=[-100, -100, -5, 100, 100, 3]),\n    pts_middle_encoder=dict(output_shape=[800, 800]),\n    pts_bbox_head=dict(\n        num_classes=9,\n        anchor_generator=dict(\n            ranges=[[-100, -100, -1.8, 100, 100, -1.8]], custom_values=[]),\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7)),\n    # model training settings (based on nuScenes model settings)\n    train_cfg=dict(pts=dict(code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_pointpillars_secfpn_kitti.py",
    "content": "voxel_size = [0.16, 0.16, 4]\n\nmodel = dict(\n    type='VoxelNet',\n    voxel_layer=dict(\n        max_num_points=32,  # max_points_per_voxel\n        point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1],\n        voxel_size=voxel_size,\n        max_voxels=(16000, 40000)  # (training, testing) max_voxels\n    ),\n    voxel_encoder=dict(\n        type='PillarFeatureNet',\n        in_channels=4,\n        feat_channels=[64],\n        with_distance=False,\n        voxel_size=voxel_size,\n        point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1]),\n    middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=[496, 432]),\n    backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        layer_nums=[3, 5, 5],\n        layer_strides=[2, 2, 2],\n        out_channels=[64, 128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        in_channels=[64, 128, 256],\n        upsample_strides=[1, 2, 4],\n        out_channels=[128, 128, 128]),\n    bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=384,\n        feat_channels=384,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='Anchor3DRangeGenerator',\n            ranges=[\n                [0, -39.68, -0.6, 70.4, 39.68, -0.6],\n                [0, -39.68, -0.6, 70.4, 39.68, -0.6],\n                [0, -39.68, -1.78, 70.4, 39.68, -1.78],\n            ],\n            sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        assigner=[\n            dict(  # for Pedestrian\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.35,\n                min_pos_iou=0.35,\n                ignore_iof_thr=-1),\n            dict(  # for Cyclist\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.35,\n                min_pos_iou=0.35,\n                ignore_iof_thr=-1),\n            dict(  # for Car\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.6,\n                neg_iou_thr=0.45,\n                min_pos_iou=0.45,\n                ignore_iof_thr=-1),\n        ],\n        allowed_border=0,\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_thr=0.01,\n        score_thr=0.1,\n        min_bbox_size=0,\n        nms_pre=100,\n        max_num=50))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_pointpillars_secfpn_waymo.py",
    "content": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nvoxel_size = [0.32, 0.32, 6]\nmodel = dict(\n    type='MVXFasterRCNN',\n    pts_voxel_layer=dict(\n        max_num_points=20,\n        point_cloud_range=[-74.88, -74.88, -2, 74.88, 74.88, 4],\n        voxel_size=voxel_size,\n        max_voxels=(32000, 32000)),\n    pts_voxel_encoder=dict(\n        type='HardVFE',\n        in_channels=5,\n        feat_channels=[64],\n        with_distance=False,\n        voxel_size=voxel_size,\n        with_cluster_center=True,\n        with_voxel_center=True,\n        point_cloud_range=[-74.88, -74.88, -2, 74.88, 74.88, 4],\n        norm_cfg=dict(type='naiveSyncBN1d', eps=1e-3, momentum=0.01)),\n    pts_middle_encoder=dict(\n        type='PointPillarsScatter', in_channels=64, output_shape=[468, 468]),\n    pts_backbone=dict(\n        type='SECOND',\n        in_channels=64,\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        layer_nums=[3, 5, 5],\n        layer_strides=[1, 2, 2],\n        out_channels=[64, 128, 256]),\n    pts_neck=dict(\n        type='SECONDFPN',\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        in_channels=[64, 128, 256],\n        upsample_strides=[1, 2, 4],\n        out_channels=[128, 128, 128]),\n    pts_bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=384,\n        feat_channels=384,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='AlignedAnchor3DRangeGenerator',\n            ranges=[[-74.88, -74.88, -0.0345, 74.88, 74.88, -0.0345],\n                    [-74.88, -74.88, -0.1188, 74.88, 74.88, -0.1188],\n                    [-74.88, -74.88, 0, 74.88, 74.88, 0]],\n            sizes=[\n                [2.08, 4.73, 1.77],  # car\n                [0.84, 1.81, 1.77],  # cyclist\n                [0.84, 0.91, 1.74]  # pedestrian\n            ],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        dir_offset=0.7854,  # pi/4\n        dir_limit_offset=0,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        pts=dict(\n            assigner=[\n                dict(  # car\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.4,\n                    min_pos_iou=0.4,\n                    ignore_iof_thr=-1),\n                dict(  # cyclist\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.3,\n                    min_pos_iou=0.3,\n                    ignore_iof_thr=-1),\n                dict(  # pedestrian\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.3,\n                    min_pos_iou=0.3,\n                    ignore_iof_thr=-1),\n            ],\n            allowed_border=0,\n            code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        pts=dict(\n            use_rotate_nms=True,\n            nms_across_levels=False,\n            nms_pre=4096,\n            nms_thr=0.25,\n            score_thr=0.1,\n            min_bbox_size=0,\n            max_num=500)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_second_secfpn_kitti.py",
    "content": "voxel_size = [0.05, 0.05, 0.1]\n\nmodel = dict(\n    type='VoxelNet',\n    voxel_layer=dict(\n        max_num_points=5,\n        point_cloud_range=[0, -40, -3, 70.4, 40, 1],\n        voxel_size=voxel_size,\n        max_voxels=(16000, 40000)),\n    voxel_encoder=dict(type='HardSimpleVFE'),\n    middle_encoder=dict(\n        type='SparseEncoder',\n        in_channels=4,\n        sparse_shape=[41, 1600, 1408],\n        order=('conv', 'norm', 'act')),\n    backbone=dict(\n        type='SECOND',\n        in_channels=256,\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        out_channels=[128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        in_channels=[128, 256],\n        upsample_strides=[1, 2],\n        out_channels=[256, 256]),\n    bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=512,\n        feat_channels=512,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='Anchor3DRangeGenerator',\n            ranges=[\n                [0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                [0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                [0, -40.0, -1.78, 70.4, 40.0, -1.78],\n            ],\n            sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        assigner=[\n            dict(  # for Pedestrian\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.35,\n                neg_iou_thr=0.2,\n                min_pos_iou=0.2,\n                ignore_iof_thr=-1),\n            dict(  # for Cyclist\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.35,\n                neg_iou_thr=0.2,\n                min_pos_iou=0.2,\n                ignore_iof_thr=-1),\n            dict(  # for Car\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.6,\n                neg_iou_thr=0.45,\n                min_pos_iou=0.45,\n                ignore_iof_thr=-1),\n        ],\n        allowed_border=0,\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_thr=0.01,\n        score_thr=0.1,\n        min_bbox_size=0,\n        nms_pre=100,\n        max_num=50))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/hv_second_secfpn_waymo.py",
    "content": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n# If point cloud range is modified, do remember to change all related\n# keys in the config.\nvoxel_size = [0.08, 0.08, 0.1]\nmodel = dict(\n    type='VoxelNet',\n    voxel_layer=dict(\n        max_num_points=10,\n        point_cloud_range=[-76.8, -51.2, -2, 76.8, 51.2, 4],\n        voxel_size=voxel_size,\n        max_voxels=(80000, 90000)),\n    voxel_encoder=dict(type='HardSimpleVFE', num_features=5),\n    middle_encoder=dict(\n        type='SparseEncoder',\n        in_channels=5,\n        sparse_shape=[61, 1280, 1920],\n        order=('conv', 'norm', 'act')),\n    backbone=dict(\n        type='SECOND',\n        in_channels=384,\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        out_channels=[128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),\n        in_channels=[128, 256],\n        upsample_strides=[1, 2],\n        out_channels=[256, 256]),\n    bbox_head=dict(\n        type='Anchor3DHead',\n        num_classes=3,\n        in_channels=512,\n        feat_channels=512,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='AlignedAnchor3DRangeGenerator',\n            ranges=[[-76.8, -51.2, -0.0345, 76.8, 51.2, -0.0345],\n                    [-76.8, -51.2, 0, 76.8, 51.2, 0],\n                    [-76.8, -51.2, -0.1188, 76.8, 51.2, -0.1188]],\n            sizes=[\n                [2.08, 4.73, 1.77],  # car\n                [0.84, 0.91, 1.74],  # pedestrian\n                [0.84, 1.81, 1.77]  # cyclist\n            ],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        dir_offset=0.7854,  # pi/4\n        dir_limit_offset=0,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    # model training and testing settings\n    train_cfg=dict(\n        assigner=[\n            dict(  # car\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.55,\n                neg_iou_thr=0.4,\n                min_pos_iou=0.4,\n                ignore_iof_thr=-1),\n            dict(  # pedestrian\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                ignore_iof_thr=-1),\n            dict(  # cyclist\n                type='MaxIoUAssigner',\n                iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                ignore_iof_thr=-1)\n        ],\n        allowed_border=0,\n        code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],\n        pos_weight=-1,\n        debug=False),\n    test_cfg=dict(\n        use_rotate_nms=True,\n        nms_across_levels=False,\n        nms_pre=4096,\n        nms_thr=0.25,\n        score_thr=0.1,\n        min_bbox_size=0,\n        max_num=500))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/imvotenet_image.py",
    "content": "model = dict(\n    type='ImVoteNet',\n    img_backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=False),\n        norm_eval=True,\n        style='caffe'),\n    img_neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        num_outs=5),\n    img_rpn_head=dict(\n        type='RPNHead',\n        in_channels=256,\n        feat_channels=256,\n        anchor_generator=dict(\n            type='AnchorGenerator',\n            scales=[8],\n            ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64]),\n        bbox_coder=dict(\n            type='DeltaXYWHBBoxCoder',\n            target_means=[.0, .0, .0, .0],\n            target_stds=[1.0, 1.0, 1.0, 1.0]),\n        loss_cls=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=1.0)),\n    img_roi_head=dict(\n        type='StandardRoIHead',\n        bbox_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        bbox_head=dict(\n            type='Shared2FCBBoxHead',\n            in_channels=256,\n            fc_out_channels=1024,\n            roi_feat_size=7,\n            num_classes=10,\n            bbox_coder=dict(\n                type='DeltaXYWHBBoxCoder',\n                target_means=[0., 0., 0., 0.],\n                target_stds=[0.1, 0.1, 0.2, 0.2]),\n            reg_class_agnostic=False,\n            loss_cls=dict(\n                type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n            loss_bbox=dict(type='L1Loss', loss_weight=1.0))),\n\n    # model training and testing settings\n    train_cfg=dict(\n        img_rpn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.7,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=256,\n                pos_fraction=0.5,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False),\n            allowed_border=-1,\n            pos_weight=-1,\n            debug=False),\n        img_rpn_proposal=dict(\n            nms_across_levels=False,\n            nms_pre=2000,\n            nms_post=1000,\n            max_per_img=1000,\n            nms=dict(type='nms', iou_threshold=0.7),\n            min_bbox_size=0),\n        img_rcnn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.5,\n                min_pos_iou=0.5,\n                match_low_quality=False,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=512,\n                pos_fraction=0.25,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=True),\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        img_rpn=dict(\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_post=1000,\n            max_per_img=1000,\n            nms=dict(type='nms', iou_threshold=0.7),\n            min_bbox_size=0),\n        img_rcnn=dict(\n            score_thr=0.05,\n            nms=dict(type='nms', iou_threshold=0.5),\n            max_per_img=100)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/mask_rcnn_r50_fpn.py",
    "content": "# model settings\nmodel = dict(\n    type='MaskRCNN',\n    pretrained='torchvision://resnet50',\n    backbone=dict(\n        type='ResNet',\n        depth=50,\n        num_stages=4,\n        out_indices=(0, 1, 2, 3),\n        frozen_stages=1,\n        norm_cfg=dict(type='BN', requires_grad=True),\n        norm_eval=True,\n        style='pytorch'),\n    neck=dict(\n        type='FPN',\n        in_channels=[256, 512, 1024, 2048],\n        out_channels=256,\n        num_outs=5),\n    rpn_head=dict(\n        type='RPNHead',\n        in_channels=256,\n        feat_channels=256,\n        anchor_generator=dict(\n            type='AnchorGenerator',\n            scales=[8],\n            ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64]),\n        bbox_coder=dict(\n            type='DeltaXYWHBBoxCoder',\n            target_means=[.0, .0, .0, .0],\n            target_stds=[1.0, 1.0, 1.0, 1.0]),\n        loss_cls=dict(\n            type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n        loss_bbox=dict(type='L1Loss', loss_weight=1.0)),\n    roi_head=dict(\n        type='StandardRoIHead',\n        bbox_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        bbox_head=dict(\n            type='Shared2FCBBoxHead',\n            in_channels=256,\n            fc_out_channels=1024,\n            roi_feat_size=7,\n            num_classes=80,\n            bbox_coder=dict(\n                type='DeltaXYWHBBoxCoder',\n                target_means=[0., 0., 0., 0.],\n                target_stds=[0.1, 0.1, 0.2, 0.2]),\n            reg_class_agnostic=False,\n            loss_cls=dict(\n                type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),\n            loss_bbox=dict(type='L1Loss', loss_weight=1.0)),\n        mask_roi_extractor=dict(\n            type='SingleRoIExtractor',\n            roi_layer=dict(type='RoIAlign', output_size=14, sampling_ratio=0),\n            out_channels=256,\n            featmap_strides=[4, 8, 16, 32]),\n        mask_head=dict(\n            type='FCNMaskHead',\n            num_convs=4,\n            in_channels=256,\n            conv_out_channels=256,\n            num_classes=80,\n            loss_mask=dict(\n                type='CrossEntropyLoss', use_mask=True, loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.7,\n                neg_iou_thr=0.3,\n                min_pos_iou=0.3,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=256,\n                pos_fraction=0.5,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False),\n            allowed_border=-1,\n            pos_weight=-1,\n            debug=False),\n        rpn_proposal=dict(\n            nms_across_levels=False,\n            nms_pre=2000,\n            nms_post=1000,\n            max_num=1000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=dict(\n            assigner=dict(\n                type='MaxIoUAssigner',\n                pos_iou_thr=0.5,\n                neg_iou_thr=0.5,\n                min_pos_iou=0.5,\n                match_low_quality=True,\n                ignore_iof_thr=-1),\n            sampler=dict(\n                type='RandomSampler',\n                num=512,\n                pos_fraction=0.25,\n                neg_pos_ub=-1,\n                add_gt_as_proposals=True),\n            mask_size=28,\n            pos_weight=-1,\n            debug=False)),\n    test_cfg=dict(\n        rpn=dict(\n            nms_across_levels=False,\n            nms_pre=1000,\n            nms_post=1000,\n            max_num=1000,\n            nms_thr=0.7,\n            min_bbox_size=0),\n        rcnn=dict(\n            score_thr=0.05,\n            nms=dict(type='nms', iou_threshold=0.5),\n            max_per_img=100,\n            mask_thr_binary=0.5)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/paconv_cuda_ssg.py",
    "content": "_base_ = './paconv_ssg.py'\n\nmodel = dict(\n    backbone=dict(\n        sa_cfg=dict(\n            type='PAConvCUDASAModule',\n            scorenet_cfg=dict(mlp_channels=[8, 16, 16]))))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/paconv_ssg.py",
    "content": "# model settings\nmodel = dict(\n    type='EncoderDecoder3D',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=9,  # [xyz, rgb, normalized_xyz]\n        num_points=(1024, 256, 64, 16),\n        radius=(None, None, None, None),  # use kNN instead of ball query\n        num_samples=(32, 32, 32, 32),\n        sa_channels=((32, 32, 64), (64, 64, 128), (128, 128, 256), (256, 256,\n                                                                    512)),\n        fp_channels=(),\n        norm_cfg=dict(type='BN2d', momentum=0.1),\n        sa_cfg=dict(\n            type='PAConvSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False,\n            paconv_num_kernels=[16, 16, 16],\n            paconv_kernel_input='w_neighbor',\n            scorenet_input='w_neighbor_dist',\n            scorenet_cfg=dict(\n                mlp_channels=[16, 16, 16],\n                score_norm='softmax',\n                temp_factor=1.0,\n                last_bn=False))),\n    decode_head=dict(\n        type='PAConvHead',\n        # PAConv model's decoder takes skip connections from beckbone\n        # different from PointNet++, it also concats input features in the last\n        # level of decoder, leading to `128 + 6` as the channel number\n        fp_channels=((768, 256, 256), (384, 256, 256), (320, 256, 128),\n                     (128 + 6, 128, 128, 128)),\n        channels=128,\n        dropout_ratio=0.5,\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        act_cfg=dict(type='ReLU'),\n        loss_decode=dict(\n            type='CrossEntropyLoss',\n            use_sigmoid=False,\n            class_weight=None,  # should be modified with dataset\n            loss_weight=1.0)),\n    # correlation loss to regularize PAConv's kernel weights\n    loss_regularization=dict(\n        type='PAConvRegularizationLoss', reduction='sum', loss_weight=10.0),\n    # model training and testing settings\n    train_cfg=dict(),\n    test_cfg=dict(mode='slide'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/parta2.py",
    "content": "# model settings\nvoxel_size = [0.05, 0.05, 0.1]\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\n\nmodel = dict(\n    type='PartA2',\n    voxel_layer=dict(\n        max_num_points=5,  # max_points_per_voxel\n        point_cloud_range=point_cloud_range,\n        voxel_size=voxel_size,\n        max_voxels=(16000, 40000)  # (training, testing) max_voxels\n    ),\n    voxel_encoder=dict(type='HardSimpleVFE'),\n    middle_encoder=dict(\n        type='SparseUNet',\n        in_channels=4,\n        sparse_shape=[41, 1600, 1408],\n        order=('conv', 'norm', 'act')),\n    backbone=dict(\n        type='SECOND',\n        in_channels=256,\n        layer_nums=[5, 5],\n        layer_strides=[1, 2],\n        out_channels=[128, 256]),\n    neck=dict(\n        type='SECONDFPN',\n        in_channels=[128, 256],\n        upsample_strides=[1, 2],\n        out_channels=[256, 256]),\n    rpn_head=dict(\n        type='PartA2RPNHead',\n        num_classes=3,\n        in_channels=512,\n        feat_channels=512,\n        use_direction_classifier=True,\n        anchor_generator=dict(\n            type='Anchor3DRangeGenerator',\n            ranges=[[0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                    [0, -40.0, -0.6, 70.4, 40.0, -0.6],\n                    [0, -40.0, -1.78, 70.4, 40.0, -1.78]],\n            sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],\n            rotations=[0, 1.57],\n            reshape_out=False),\n        diff_rad_by_sin=True,\n        assigner_per_size=True,\n        assign_per_class=True,\n        bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n        loss_cls=dict(\n            type='FocalLoss',\n            use_sigmoid=True,\n            gamma=2.0,\n            alpha=0.25,\n            loss_weight=1.0),\n        loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n        loss_dir=dict(\n            type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),\n    roi_head=dict(\n        type='PartAggregationROIHead',\n        num_classes=3,\n        semantic_head=dict(\n            type='PointwiseSemanticHead',\n            in_channels=16,\n            extra_width=0.2,\n            seg_score_thr=0.3,\n            num_classes=3,\n            loss_seg=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                reduction='sum',\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0),\n            loss_part=dict(\n                type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0)),\n        seg_roi_extractor=dict(\n            type='Single3DRoIAwareExtractor',\n            roi_layer=dict(\n                type='RoIAwarePool3d',\n                out_size=14,\n                max_pts_per_voxel=128,\n                mode='max')),\n        part_roi_extractor=dict(\n            type='Single3DRoIAwareExtractor',\n            roi_layer=dict(\n                type='RoIAwarePool3d',\n                out_size=14,\n                max_pts_per_voxel=128,\n                mode='avg')),\n        bbox_head=dict(\n            type='PartA2BboxHead',\n            num_classes=3,\n            seg_in_channels=16,\n            part_in_channels=4,\n            seg_conv_channels=[64, 64],\n            part_conv_channels=[64, 64],\n            merge_conv_channels=[128, 128],\n            down_conv_channels=[128, 256],\n            bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n            shared_fc_channels=[256, 512, 512, 512],\n            cls_channels=[256, 256],\n            reg_channels=[256, 256],\n            dropout_ratio=0.1,\n            roi_feat_size=14,\n            with_corner_loss=True,\n            loss_bbox=dict(\n                type='SmoothL1Loss',\n                beta=1.0 / 9.0,\n                reduction='sum',\n                loss_weight=1.0),\n            loss_cls=dict(\n                type='CrossEntropyLoss',\n                use_sigmoid=True,\n                reduction='sum',\n                loss_weight=1.0))),\n    # model training and testing settings\n    train_cfg=dict(\n        rpn=dict(\n            assigner=[\n                dict(  # for Pedestrian\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.35,\n                    min_pos_iou=0.35,\n                    ignore_iof_thr=-1),\n                dict(  # for Cyclist\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.35,\n                    min_pos_iou=0.35,\n                    ignore_iof_thr=-1),\n                dict(  # for Car\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(type='BboxOverlapsNearest3D'),\n                    pos_iou_thr=0.6,\n                    neg_iou_thr=0.45,\n                    min_pos_iou=0.45,\n                    ignore_iof_thr=-1)\n            ],\n            allowed_border=0,\n            pos_weight=-1,\n            debug=False),\n        rpn_proposal=dict(\n            nms_pre=9000,\n            nms_post=512,\n            max_num=512,\n            nms_thr=0.8,\n            score_thr=0,\n            use_rotate_nms=False),\n        rcnn=dict(\n            assigner=[\n                dict(  # for Pedestrian\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(\n                        type='BboxOverlaps3D', coordinate='lidar'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.55,\n                    min_pos_iou=0.55,\n                    ignore_iof_thr=-1),\n                dict(  # for Cyclist\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(\n                        type='BboxOverlaps3D', coordinate='lidar'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.55,\n                    min_pos_iou=0.55,\n                    ignore_iof_thr=-1),\n                dict(  # for Car\n                    type='MaxIoUAssigner',\n                    iou_calculator=dict(\n                        type='BboxOverlaps3D', coordinate='lidar'),\n                    pos_iou_thr=0.55,\n                    neg_iou_thr=0.55,\n                    min_pos_iou=0.55,\n                    ignore_iof_thr=-1)\n            ],\n            sampler=dict(\n                type='IoUNegPiecewiseSampler',\n                num=128,\n                pos_fraction=0.55,\n                neg_piece_fractions=[0.8, 0.2],\n                neg_iou_piece_thrs=[0.55, 0.1],\n                neg_pos_ub=-1,\n                add_gt_as_proposals=False,\n                return_iou=True),\n            cls_pos_thr=0.75,\n            cls_neg_thr=0.25)),\n    test_cfg=dict(\n        rpn=dict(\n            nms_pre=1024,\n            nms_post=100,\n            max_num=100,\n            nms_thr=0.7,\n            score_thr=0,\n            use_rotate_nms=True),\n        rcnn=dict(\n            use_rotate_nms=True,\n            use_raw_score=True,\n            nms_thr=0.01,\n            score_thr=0.1)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/pointnet2_msg.py",
    "content": "_base_ = './pointnet2_ssg.py'\n\n# model settings\nmodel = dict(\n    backbone=dict(\n        _delete_=True,\n        type='PointNet2SAMSG',\n        in_channels=6,  # [xyz, rgb], should be modified with dataset\n        num_points=(1024, 256, 64, 16),\n        radii=((0.05, 0.1), (0.1, 0.2), (0.2, 0.4), (0.4, 0.8)),\n        num_samples=((16, 32), (16, 32), (16, 32), (16, 32)),\n        sa_channels=(((16, 16, 32), (32, 32, 64)), ((64, 64, 128), (64, 96,\n                                                                    128)),\n                     ((128, 196, 256), (128, 196, 256)), ((256, 256, 512),\n                                                          (256, 384, 512))),\n        aggregation_channels=(None, None, None, None),\n        fps_mods=(('D-FPS'), ('D-FPS'), ('D-FPS'), ('D-FPS')),\n        fps_sample_range_lists=((-1), (-1), (-1), (-1)),\n        dilated_group=(False, False, False, False),\n        out_indices=(0, 1, 2, 3),\n        sa_cfg=dict(\n            type='PointSAModuleMSG',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False)),\n    decode_head=dict(\n        fp_channels=((1536, 256, 256), (512, 256, 256), (352, 256, 128),\n                     (128, 128, 128, 128))))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/pointnet2_ssg.py",
    "content": "# model settings\nmodel = dict(\n    type='EncoderDecoder3D',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=6,  # [xyz, rgb], should be modified with dataset\n        num_points=(1024, 256, 64, 16),\n        radius=(0.1, 0.2, 0.4, 0.8),\n        num_samples=(32, 32, 32, 32),\n        sa_channels=((32, 32, 64), (64, 64, 128), (128, 128, 256), (256, 256,\n                                                                    512)),\n        fp_channels=(),\n        norm_cfg=dict(type='BN2d'),\n        sa_cfg=dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=False)),\n    decode_head=dict(\n        type='PointNet2Head',\n        fp_channels=((768, 256, 256), (384, 256, 256), (320, 256, 128),\n                     (128, 128, 128, 128)),\n        channels=128,\n        dropout_ratio=0.5,\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        act_cfg=dict(type='ReLU'),\n        loss_decode=dict(\n            type='CrossEntropyLoss',\n            use_sigmoid=False,\n            class_weight=None,  # should be modified with dataset\n            loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(),\n    test_cfg=dict(mode='slide'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/models/votenet.py",
    "content": "model = dict(\n    type='VoteNet',\n    backbone=dict(\n        type='PointNet2SASSG',\n        in_channels=4,\n        num_points=(2048, 1024, 512, 256),\n        radius=(0.2, 0.4, 0.8, 1.2),\n        num_samples=(64, 32, 16, 16),\n        sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),\n                     (128, 128, 256)),\n        fp_channels=((256, 256), (256, 256)),\n        norm_cfg=dict(type='BN2d'),\n        sa_cfg=dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=True)),\n    bbox_head=dict(\n        type='VoteHead',\n        vote_module_cfg=dict(\n            in_channels=256,\n            vote_per_seed=1,\n            gt_per_seed=3,\n            conv_channels=(256, 256),\n            conv_cfg=dict(type='Conv1d'),\n            norm_cfg=dict(type='BN1d'),\n            norm_feats=True,\n            vote_loss=dict(\n                type='ChamferDistance',\n                mode='l1',\n                reduction='none',\n                loss_dst_weight=10.0)),\n        vote_aggregation_cfg=dict(\n            type='PointSAModule',\n            num_point=256,\n            radius=0.3,\n            num_sample=16,\n            mlp_channels=[256, 128, 128, 128],\n            use_xyz=True,\n            normalize_xyz=True),\n        pred_layer_cfg=dict(\n            in_channels=128, shared_conv_channels=(128, 128), bias=True),\n        conv_cfg=dict(type='Conv1d'),\n        norm_cfg=dict(type='BN1d'),\n        objectness_loss=dict(\n            type='CrossEntropyLoss',\n            class_weight=[0.2, 0.8],\n            reduction='sum',\n            loss_weight=5.0),\n        center_loss=dict(\n            type='ChamferDistance',\n            mode='l2',\n            reduction='sum',\n            loss_src_weight=10.0,\n            loss_dst_weight=10.0),\n        dir_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        dir_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0),\n        size_class_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),\n        size_res_loss=dict(\n            type='SmoothL1Loss', reduction='sum', loss_weight=10.0 / 3.0),\n        semantic_loss=dict(\n            type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),\n    # model training and testing settings\n    train_cfg=dict(\n        pos_distance_thr=0.3, neg_distance_thr=0.6, sample_mod='vote'),\n    test_cfg=dict(\n        sample_mod='seed',\n        nms_thr=0.25,\n        score_thr=0.05,\n        per_class_proposal=True))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/cosine.py",
    "content": "# This schedule is mainly used by models with dynamic voxelization\n# optimizer\nlr = 0.003  # max learning rate\noptimizer = dict(\n    type='AdamW',\n    lr=lr,\n    betas=(0.95, 0.99),  # the momentum is change during training\n    weight_decay=0.001)\noptimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))\n\nlr_config = dict(\n    policy='CosineAnnealing',\n    warmup='linear',\n    warmup_iters=1000,\n    warmup_ratio=1.0 / 10,\n    min_lr_ratio=1e-5)\n\nmomentum_config = None\n\nrunner = dict(type='EpochBasedRunner', max_epochs=40)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/cyclic_20e.py",
    "content": "# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 20. Please change the interval accordingly if you do not\n# use a default schedule.\n# optimizer\n# This schedule is mainly used by models on nuScenes dataset\noptimizer = dict(type='AdamW', lr=1e-4, weight_decay=0.01)\n# max_norm=10 is better for SECOND\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\nlr_config = dict(\n    policy='cyclic',\n    target_ratio=(10, 1e-4),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\nmomentum_config = dict(\n    policy='cyclic',\n    target_ratio=(0.85 / 0.95, 1),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=20)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/cyclic_40e.py",
    "content": "# The schedule is usually used by models trained on KITTI dataset\n\n# The learning rate set in the cyclic schedule is the initial learning rate\n# rather than the max learning rate. Since the target_ratio is (10, 1e-4),\n# the learning rate will change from 0.0018 to 0.018, than go to 0.0018*1e-4\nlr = 0.0018\n# The optimizer follows the setting in SECOND.Pytorch, but here we use\n# the offcial AdamW optimizer implemented by PyTorch.\noptimizer = dict(type='AdamW', lr=lr, betas=(0.95, 0.99), weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))\n# We use cyclic learning rate and momentum schedule following SECOND.Pytorch\n# https://github.com/traveller59/second.pytorch/blob/3aba19c9688274f75ebb5e576f65cfe54773c021/torchplus/train/learning_schedules_fastai.py#L69  # noqa\n# We implement them in mmcv, for more details, please refer to\n# https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/lr_updater.py#L327  # noqa\n# https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/momentum_updater.py#L130  # noqa\nlr_config = dict(\n    policy='cyclic',\n    target_ratio=(10, 1e-4),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\nmomentum_config = dict(\n    policy='cyclic',\n    target_ratio=(0.85 / 0.95, 1),\n    cyclic_times=1,\n    step_ratio_up=0.4,\n)\n# Although the max_epochs is 40, this schedule is usually used we\n# RepeatDataset with repeat ratio N, thus the actual max epoch\n# number could be Nx40\nrunner = dict(type='EpochBasedRunner', max_epochs=40)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/mmdet_schedule_1x.py",
    "content": "# optimizer\noptimizer = dict(type='SGD', lr=0.02, momentum=0.9, weight_decay=0.0001)\noptimizer_config = dict(grad_clip=None)\n# learning policy\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=500,\n    warmup_ratio=0.001,\n    step=[8, 11])\nrunner = dict(type='EpochBasedRunner', max_epochs=12)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/schedule_2x.py",
    "content": "# optimizer\n# This schedule is mainly used by models on nuScenes dataset\noptimizer = dict(type='AdamW', lr=0.001, weight_decay=0.01)\n# max_norm=10 is better for SECOND\noptimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))\nlr_config = dict(\n    policy='step',\n    warmup='linear',\n    warmup_iters=1000,\n    warmup_ratio=1.0 / 1000,\n    step=[20, 23])\nmomentum_config = None\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=24)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/schedule_3x.py",
    "content": "# optimizer\n# This schedule is mainly used by models on indoor dataset,\n# e.g., VoteNet on SUNRGBD and ScanNet\nlr = 0.008  # max learning rate\noptimizer = dict(type='AdamW', lr=lr, weight_decay=0.01)\noptimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))\nlr_config = dict(policy='step', warmup=None, step=[24, 32])\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=36)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/seg_cosine_150e.py",
    "content": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='SGD', lr=0.2, weight_decay=0.0001, momentum=0.9)\noptimizer_config = dict(grad_clip=None)\nlr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=0.002)\nmomentum_config = None\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=150)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/seg_cosine_200e.py",
    "content": "# optimizer\n# This schedule is mainly used on ScanNet dataset in segmentation task\noptimizer = dict(type='Adam', lr=0.001, weight_decay=0.01)\noptimizer_config = dict(grad_clip=None)\nlr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)\nmomentum_config = None\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=200)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/_base_/schedules/seg_cosine_50e.py",
    "content": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='Adam', lr=0.001, weight_decay=0.001)\noptimizer_config = dict(grad_clip=None)\nlr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)\nmomentum_config = None\n\n# runtime settings\nrunner = dict(type='EpochBasedRunner', max_epochs=50)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/datasets/custom_lyft-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-80, -80, -5, 80, 80, 3]\n# For Lyft we usually do 9-class detection\nclass_names = [\n    'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',\n    'bicycle', 'pedestrian', 'animal'\n]\ndataset_type = 'CustomLyftDataset'\ndata_root = 'data/lyft/'\n# Input modality for Lyft dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=True)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/lyft/': 's3://lyft/lyft/',\n#         'data/lyft/': 's3://lyft/lyft/'\n#    }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=2,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'lyft_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True))\n# For Lyft dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/datasets/custom_nus-3d.py",
    "content": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range = [-50, -50, -5, 50, 50, 3]\n# For nuScenes we usually do 10-class detection\nclass_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\ndataset_type = 'NuScenesDataset_eval_modified'\ndata_root = 'data/nuscenes/'\n# Input modality for nuScenes dataset, this is consistent with the submission\n# format which requires the information in input_modality.\ninput_modality = dict(\n    use_lidar=True,\n    use_camera=False,\n    use_radar=False,\n    use_map=False,\n    use_external=False)\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel',\n#     path_mapping=dict({\n#         './data/nuscenes/': 's3://nuscenes/nuscenes/',\n#         'data/nuscenes/': 's3://nuscenes/nuscenes/'\n#     }))\ntrain_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),\n    dict(\n        type='GlobalRotScaleTrans',\n        rot_range=[-0.3925, 0.3925],\n        scale_ratio_range=[0.95, 1.05],\n        translation_std=[0, 0, 0]),\n    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='PointShuffle'),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])\n]\ntest_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1333, 800),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='GlobalRotScaleTrans',\n                rot_range=[0, 0],\n                scale_ratio_range=[1., 1.],\n                translation_std=[0, 0, 0]),\n            dict(type='RandomFlip3D'),\n            dict(\n                type='PointsRangeFilter', point_cloud_range=point_cloud_range),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ])\n]\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\neval_pipeline = [\n    dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args),\n    dict(\n        type='LoadPointsFromMultiSweeps',\n        sweeps_num=10,\n        file_client_args=file_client_args),\n    dict(\n        type='DefaultFormatBundle3D',\n        class_names=class_names,\n        with_label=False),\n    dict(type='Collect3D', keys=['points'])\n]\n\ndata = dict(\n    samples_per_gpu=4,\n    workers_per_gpu=4,\n    train=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_train.pkl',\n        pipeline=train_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=False,\n        # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n        # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n        box_type_3d='LiDAR'),\n    val=dict(\n        type=dataset_type,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'nuscenes_infos_val.pkl',\n        pipeline=test_pipeline,\n        classes=class_names,\n        modality=input_modality,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epochs by default, we set evaluation\n# interval to be 24. Please change the interval accordingly if you do not\n# use a default schedule.\nevaluation = dict(interval=24, pipeline=eval_pipeline)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/configs/datasets/custom_waymo-3d.py",
    "content": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for efficient experiments\ndataset_type = 'CustomWaymoDataset'\ndata_root = 'data/waymo/kitti_format/'\nfile_client_args = dict(backend='disk')\n# Uncomment the following if use ceph or other file clients.\n# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient\n# for more details.\n# file_client_args = dict(\n#     backend='petrel', path_mapping=dict(data='s3://waymo_data/'))\n\nimg_norm_cfg = dict(\n    mean=[103.530, 116.280, 123.675], std=[1.0, 1.0, 1.0], to_rgb=False)\nclass_names = ['Car', 'Pedestrian', 'Cyclist']\npoint_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]\ninput_modality = dict(use_lidar=False, use_camera=True)\ndb_sampler = dict(\n    data_root=data_root,\n    info_path=data_root + 'waymo_dbinfos_train.pkl',\n    rate=1.0,\n    prepare=dict(\n        filter_by_difficulty=[-1],\n        filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),\n    classes=class_names,\n    sample_groups=dict(Car=15, Pedestrian=10, Cyclist=10),\n    points_loader=dict(\n        type='LoadPointsFromFile',\n        coord_type='LIDAR',\n        load_dim=5,\n        use_dim=[0, 1, 2, 3, 4],\n        file_client_args=file_client_args))\n\n\n\ntrain_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='PhotoMetricDistortionMultiViewImage'),\n    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_attr_label=False),\n    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),\n    dict(type='ObjectNameFilter', classes=class_names),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(type='DefaultFormatBundle3D', class_names=class_names),\n    dict(type='CustomCollect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'])\n]\n\n\ntest_pipeline = [\n    dict(type='LoadMultiViewImageFromFiles', to_float32=True),\n    dict(type='NormalizeMultiviewImage', **img_norm_cfg),\n    dict(type='PadMultiViewImage', size_divisor=32),\n    dict(\n        type='MultiScaleFlipAug3D',\n        img_scale=(1920, 1280),\n        pts_scale_ratio=1,\n        flip=False,\n        transforms=[\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=class_names,\n                with_label=False),\n            dict(type='CustomCollect3D', keys=['img'])\n        ])\n]\n\n\n# construct a pipeline for data and gt loading in show function\n# please keep its loading function consistent with test_pipeline (e.g. client)\n\ndata = dict(\n    samples_per_gpu=2,\n    workers_per_gpu=4,\n    train=dict(\n        type='RepeatDataset',\n        times=2,\n        dataset=dict(\n            type=dataset_type,\n            data_root=data_root,\n            ann_file=data_root + 'waymo_infos_train.pkl',\n            split='training',\n            pipeline=train_pipeline,\n            modality=input_modality,\n            classes=class_names,\n            test_mode=False,\n            # we use box_type_3d='LiDAR' in kitti and nuscenes dataset\n            # and box_type_3d='Depth' in sunrgbd and scannet dataset.\n            box_type_3d='LiDAR',\n            # load one frame every five frames\n            load_interval=5)),\n    val=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'),\n    test=dict(\n        type=dataset_type,\n        data_root=data_root,\n        ann_file=data_root + 'waymo_infos_val.pkl',\n        split='training',\n        pipeline=test_pipeline,\n        modality=input_modality,\n        classes=class_names,\n        test_mode=True,\n        box_type_3d='LiDAR'))\n\nevaluation = dict(interval=24, pipeline=test_pipeline)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/create_data.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nfrom data_converter.create_gt_database import create_groundtruth_database\nfrom data_converter import nuscenes_converter as nuscenes_converter\nfrom data_converter import lyft_converter as lyft_converter\nfrom data_converter import kitti_converter as kitti\nfrom data_converter import indoor_converter as indoor\nimport argparse\nfrom os import path as osp\nimport sys\nsys.path.append('.')\n\n\ndef kitti_data_prep(root_path, info_prefix, version, out_dir):\n    \"\"\"Prepare data related to Kitti dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        out_dir (str): Output directory of the groundtruth database info.\n    \"\"\"\n    kitti.create_kitti_info_file(root_path, info_prefix)\n    kitti.create_reduced_point_cloud(root_path, info_prefix)\n\n    info_train_path = osp.join(root_path, f'{info_prefix}_infos_train.pkl')\n    info_val_path = osp.join(root_path, f'{info_prefix}_infos_val.pkl')\n    info_trainval_path = osp.join(root_path,\n                                  f'{info_prefix}_infos_trainval.pkl')\n    info_test_path = osp.join(root_path, f'{info_prefix}_infos_test.pkl')\n    kitti.export_2d_annotation(root_path, info_train_path)\n    kitti.export_2d_annotation(root_path, info_val_path)\n    kitti.export_2d_annotation(root_path, info_trainval_path)\n    kitti.export_2d_annotation(root_path, info_test_path)\n\n    create_groundtruth_database(\n        'KittiDataset',\n        root_path,\n        info_prefix,\n        f'{out_dir}/{info_prefix}_infos_train.pkl',\n        relative_path=False,\n        mask_anno_path='instances_train.json',\n        with_mask=(version == 'mask'))\n\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    nuscenes_converter.create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n    if version == 'v1.0-test':\n        info_test_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_test.pkl')\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_test_path, version=version)\n    else:\n        info_train_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_train.pkl')\n        info_val_path = osp.join(\n            out_dir, f'{info_prefix}_infos_temporal_val.pkl')\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_train_path, version=version)\n        nuscenes_converter.export_2d_annotation(\n            root_path, info_val_path, version=version)\n        # create_groundtruth_database(dataset_name, root_path, info_prefix,\n        #                             f'{out_dir}/{info_prefix}_infos_train.pkl')\n\n\ndef lyft_data_prep(root_path, info_prefix, version, max_sweeps=10):\n    \"\"\"Prepare data related to Lyft dataset.\n\n    Related data consists of '.pkl' files recording basic infos.\n    Although the ground truth database and 2D annotations are not used in\n    Lyft, it can also be generated like nuScenes.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        max_sweeps (int, optional): Number of input consecutive frames.\n            Defaults to 10.\n    \"\"\"\n    lyft_converter.create_lyft_infos(\n        root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\ndef scannet_data_prep(root_path, info_prefix, out_dir, workers):\n    \"\"\"Prepare the info file for scannet dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n    \"\"\"\n    indoor.create_indoor_info_file(\n        root_path, info_prefix, out_dir, workers=workers)\n\n\ndef s3dis_data_prep(root_path, info_prefix, out_dir, workers):\n    \"\"\"Prepare the info file for s3dis dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n    \"\"\"\n    indoor.create_indoor_info_file(\n        root_path, info_prefix, out_dir, workers=workers)\n\n\ndef sunrgbd_data_prep(root_path, info_prefix, out_dir, workers):\n    \"\"\"Prepare the info file for sunrgbd dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n    \"\"\"\n    indoor.create_indoor_info_file(\n        root_path, info_prefix, out_dir, workers=workers)\n\n\ndef waymo_data_prep(root_path,\n                    info_prefix,\n                    version,\n                    out_dir,\n                    workers,\n                    max_sweeps=5):\n    \"\"\"Prepare the info file for waymo dataset.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        out_dir (str): Output directory of the generated info file.\n        workers (int): Number of threads to be used.\n        max_sweeps (int): Number of input consecutive frames. Default: 5 \\\n            Here we store pose information of these frames for later use.\n    \"\"\"\n    from tools.data_converter import waymo_converter as waymo\n\n    splits = ['training', 'validation', 'testing']\n\n    for i, split in enumerate(splits):\n        load_dir = osp.join(root_path, 'waymo_format', split)\n        if split == 'validation':\n            save_dir = osp.join(out_dir, 'kitti_format', 'training')\n        else:\n            save_dir = osp.join(out_dir, 'kitti_format', split)\n        converter = waymo.Waymo2KITTI(\n            load_dir,\n            save_dir,\n            prefix=str(i),\n            workers=workers,\n            test_mode=(split == 'test'))\n        converter.convert()\n    # Generate waymo infos\n    out_dir = osp.join(out_dir, 'kitti_format')\n    kitti.create_waymo_info_file(out_dir, info_prefix, max_sweeps=max_sweeps)\n\n    create_groundtruth_database(\n        'WaymoDataset',\n        out_dir,\n        info_prefix,\n        f'{out_dir}/{info_prefix}_infos_train.pkl',\n        relative_path=False,\n        with_mask=False)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'kitti':\n        kitti_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=args.version,\n            out_dir=args.out_dir)\n    elif args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'lyft':\n        train_version = f'{args.version}-train'\n        lyft_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        lyft_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'waymo':\n        waymo_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            version=args.version,\n            out_dir=args.out_dir,\n            workers=args.workers,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'scannet':\n        scannet_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            out_dir=args.out_dir,\n            workers=args.workers)\n    elif args.dataset == 's3dis':\n        s3dis_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            out_dir=args.out_dir,\n            workers=args.workers)\n    elif args.dataset == 'sunrgbd':\n        sunrgbd_data_prep(\n            root_path=args.root_path,\n            info_prefix=args.extra_tag,\n            out_dir=args.out_dir,\n            workers=args.workers)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/data_converter/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/data_converter/create_gt_database.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport pickle\nfrom mmcv import track_iter_progress\nfrom mmcv.ops import roi_align\nfrom os import path as osp\nfrom pycocotools import mask as maskUtils\nfrom pycocotools.coco import COCO\n\nfrom mmdet3d.core.bbox import box_np_ops as box_np_ops\nfrom mmdet3d.datasets import build_dataset\nfrom mmdet.core.evaluation.bbox_overlaps import bbox_overlaps\n\n\ndef _poly2mask(mask_ann, img_h, img_w):\n    if isinstance(mask_ann, list):\n        # polygon -- a single object might consist of multiple parts\n        # we merge all parts into one mask rle code\n        rles = maskUtils.frPyObjects(mask_ann, img_h, img_w)\n        rle = maskUtils.merge(rles)\n    elif isinstance(mask_ann['counts'], list):\n        # uncompressed RLE\n        rle = maskUtils.frPyObjects(mask_ann, img_h, img_w)\n    else:\n        # rle\n        rle = mask_ann\n    mask = maskUtils.decode(rle)\n    return mask\n\n\ndef _parse_coco_ann_info(ann_info):\n    gt_bboxes = []\n    gt_labels = []\n    gt_bboxes_ignore = []\n    gt_masks_ann = []\n\n    for i, ann in enumerate(ann_info):\n        if ann.get('ignore', False):\n            continue\n        x1, y1, w, h = ann['bbox']\n        if ann['area'] <= 0:\n            continue\n        bbox = [x1, y1, x1 + w, y1 + h]\n        if ann.get('iscrowd', False):\n            gt_bboxes_ignore.append(bbox)\n        else:\n            gt_bboxes.append(bbox)\n            gt_masks_ann.append(ann['segmentation'])\n\n    if gt_bboxes:\n        gt_bboxes = np.array(gt_bboxes, dtype=np.float32)\n        gt_labels = np.array(gt_labels, dtype=np.int64)\n    else:\n        gt_bboxes = np.zeros((0, 4), dtype=np.float32)\n        gt_labels = np.array([], dtype=np.int64)\n\n    if gt_bboxes_ignore:\n        gt_bboxes_ignore = np.array(gt_bboxes_ignore, dtype=np.float32)\n    else:\n        gt_bboxes_ignore = np.zeros((0, 4), dtype=np.float32)\n\n    ann = dict(\n        bboxes=gt_bboxes, bboxes_ignore=gt_bboxes_ignore, masks=gt_masks_ann)\n\n    return ann\n\n\ndef crop_image_patch_v2(pos_proposals, pos_assigned_gt_inds, gt_masks):\n    import torch\n    from torch.nn.modules.utils import _pair\n    device = pos_proposals.device\n    num_pos = pos_proposals.size(0)\n    fake_inds = (\n        torch.arange(num_pos,\n                     device=device).to(dtype=pos_proposals.dtype)[:, None])\n    rois = torch.cat([fake_inds, pos_proposals], dim=1)  # Nx5\n    mask_size = _pair(28)\n    rois = rois.to(device=device)\n    gt_masks_th = (\n        torch.from_numpy(gt_masks).to(device).index_select(\n            0, pos_assigned_gt_inds).to(dtype=rois.dtype))\n    # Use RoIAlign could apparently accelerate the training (~0.1s/iter)\n    targets = (\n        roi_align(gt_masks_th, rois, mask_size[::-1], 1.0, 0, True).squeeze(1))\n    return targets\n\n\ndef crop_image_patch(pos_proposals, gt_masks, pos_assigned_gt_inds, org_img):\n    num_pos = pos_proposals.shape[0]\n    masks = []\n    img_patches = []\n    for i in range(num_pos):\n        gt_mask = gt_masks[pos_assigned_gt_inds[i]]\n        bbox = pos_proposals[i, :].astype(np.int32)\n        x1, y1, x2, y2 = bbox\n        w = np.maximum(x2 - x1 + 1, 1)\n        h = np.maximum(y2 - y1 + 1, 1)\n\n        mask_patch = gt_mask[y1:y1 + h, x1:x1 + w]\n        masked_img = gt_mask[..., None] * org_img\n        img_patch = masked_img[y1:y1 + h, x1:x1 + w]\n\n        img_patches.append(img_patch)\n        masks.append(mask_patch)\n    return img_patches, masks\n\n\ndef create_groundtruth_database(dataset_class_name,\n                                data_path,\n                                info_prefix,\n                                info_path=None,\n                                mask_anno_path=None,\n                                used_classes=None,\n                                database_save_path=None,\n                                db_info_save_path=None,\n                                relative_path=True,\n                                add_rgb=False,\n                                lidar_only=False,\n                                bev_only=False,\n                                coors_range=None,\n                                with_mask=False):\n    \"\"\"Given the raw data, generate the ground truth database.\n\n    Args:\n        dataset_class_name （str): Name of the input dataset.\n        data_path (str): Path of the data.\n        info_prefix (str): Prefix of the info file.\n        info_path (str): Path of the info file.\n            Default: None.\n        mask_anno_path (str): Path of the mask_anno.\n            Default: None.\n        used_classes (list[str]): Classes have been used.\n            Default: None.\n        database_save_path (str): Path to save database.\n            Default: None.\n        db_info_save_path (str): Path to save db_info.\n            Default: None.\n        relative_path (bool): Whether to use relative path.\n            Default: True.\n        with_mask (bool): Whether to use mask.\n            Default: False.\n    \"\"\"\n    print(f'Create GT Database of {dataset_class_name}')\n    dataset_cfg = dict(\n        type=dataset_class_name, data_root=data_path, ann_file=info_path)\n    if dataset_class_name == 'KittiDataset':\n        file_client_args = dict(backend='disk')\n        dataset_cfg.update(\n            test_mode=False,\n            split='training',\n            modality=dict(\n                use_lidar=True,\n                use_depth=False,\n                use_lidar_intensity=True,\n                use_camera=with_mask,\n            ),\n            pipeline=[\n                dict(\n                    type='LoadPointsFromFile',\n                    coord_type='LIDAR',\n                    load_dim=4,\n                    use_dim=4,\n                    file_client_args=file_client_args),\n                dict(\n                    type='LoadAnnotations3D',\n                    with_bbox_3d=True,\n                    with_label_3d=True,\n                    file_client_args=file_client_args)\n            ])\n\n    elif dataset_class_name == 'NuScenesDataset':\n        dataset_cfg.update(\n            use_valid_flag=True,\n            pipeline=[\n                dict(\n                    type='LoadPointsFromFile',\n                    coord_type='LIDAR',\n                    load_dim=5,\n                    use_dim=5),\n                dict(\n                    type='LoadPointsFromMultiSweeps',\n                    sweeps_num=10,\n                    use_dim=[0, 1, 2, 3, 4],\n                    pad_empty_sweeps=True,\n                    remove_close=True),\n                dict(\n                    type='LoadAnnotations3D',\n                    with_bbox_3d=True,\n                    with_label_3d=True)\n            ])\n\n    elif dataset_class_name == 'WaymoDataset':\n        file_client_args = dict(backend='disk')\n        dataset_cfg.update(\n            test_mode=False,\n            split='training',\n            modality=dict(\n                use_lidar=True,\n                use_depth=False,\n                use_lidar_intensity=True,\n                use_camera=False,\n            ),\n            pipeline=[\n                dict(\n                    type='LoadPointsFromFile',\n                    coord_type='LIDAR',\n                    load_dim=6,\n                    use_dim=5,\n                    file_client_args=file_client_args),\n                dict(\n                    type='LoadAnnotations3D',\n                    with_bbox_3d=True,\n                    with_label_3d=True,\n                    file_client_args=file_client_args)\n            ])\n\n    dataset = build_dataset(dataset_cfg)\n\n    if database_save_path is None:\n        database_save_path = osp.join(data_path, f'{info_prefix}_gt_database')\n    if db_info_save_path is None:\n        db_info_save_path = osp.join(data_path,\n                                     f'{info_prefix}_dbinfos_train.pkl')\n    mmcv.mkdir_or_exist(database_save_path)\n    all_db_infos = dict()\n    if with_mask:\n        coco = COCO(osp.join(data_path, mask_anno_path))\n        imgIds = coco.getImgIds()\n        file2id = dict()\n        for i in imgIds:\n            info = coco.loadImgs([i])[0]\n            file2id.update({info['file_name']: i})\n\n    group_counter = 0\n    for j in track_iter_progress(list(range(len(dataset)))):\n        input_dict = dataset.get_data_info(j)\n        dataset.pre_pipeline(input_dict)\n        example = dataset.pipeline(input_dict)\n        annos = example['ann_info']\n        image_idx = example['sample_idx']\n        points = example['points'].tensor.numpy()\n        gt_boxes_3d = annos['gt_bboxes_3d'].tensor.numpy()\n        names = annos['gt_names']\n        group_dict = dict()\n        if 'group_ids' in annos:\n            group_ids = annos['group_ids']\n        else:\n            group_ids = np.arange(gt_boxes_3d.shape[0], dtype=np.int64)\n        difficulty = np.zeros(gt_boxes_3d.shape[0], dtype=np.int32)\n        if 'difficulty' in annos:\n            difficulty = annos['difficulty']\n\n        num_obj = gt_boxes_3d.shape[0]\n        point_indices = box_np_ops.points_in_rbbox(points, gt_boxes_3d)\n\n        if with_mask:\n            # prepare masks\n            gt_boxes = annos['gt_bboxes']\n            img_path = osp.split(example['img_info']['filename'])[-1]\n            if img_path not in file2id.keys():\n                print(f'skip image {img_path} for empty mask')\n                continue\n            img_id = file2id[img_path]\n            kins_annIds = coco.getAnnIds(imgIds=img_id)\n            kins_raw_info = coco.loadAnns(kins_annIds)\n            kins_ann_info = _parse_coco_ann_info(kins_raw_info)\n            h, w = annos['img_shape'][:2]\n            gt_masks = [\n                _poly2mask(mask, h, w) for mask in kins_ann_info['masks']\n            ]\n            # get mask inds based on iou mapping\n            bbox_iou = bbox_overlaps(kins_ann_info['bboxes'], gt_boxes)\n            mask_inds = bbox_iou.argmax(axis=0)\n            valid_inds = (bbox_iou.max(axis=0) > 0.5)\n\n            # mask the image\n            # use more precise crop when it is ready\n            # object_img_patches = np.ascontiguousarray(\n            #     np.stack(object_img_patches, axis=0).transpose(0, 3, 1, 2))\n            # crop image patches using roi_align\n            # object_img_patches = crop_image_patch_v2(\n            #     torch.Tensor(gt_boxes),\n            #     torch.Tensor(mask_inds).long(), object_img_patches)\n            object_img_patches, object_masks = crop_image_patch(\n                gt_boxes, gt_masks, mask_inds, annos['img'])\n\n        for i in range(num_obj):\n            filename = f'{image_idx}_{names[i]}_{i}.bin'\n            abs_filepath = osp.join(database_save_path, filename)\n            rel_filepath = osp.join(f'{info_prefix}_gt_database', filename)\n\n            # save point clouds and image patches for each object\n            gt_points = points[point_indices[:, i]]\n            gt_points[:, :3] -= gt_boxes_3d[i, :3]\n\n            if with_mask:\n                if object_masks[i].sum() == 0 or not valid_inds[i]:\n                    # Skip object for empty or invalid mask\n                    continue\n                img_patch_path = abs_filepath + '.png'\n                mask_patch_path = abs_filepath + '.mask.png'\n                mmcv.imwrite(object_img_patches[i], img_patch_path)\n                mmcv.imwrite(object_masks[i], mask_patch_path)\n\n            with open(abs_filepath, 'w') as f:\n                gt_points.tofile(f)\n\n            if (used_classes is None) or names[i] in used_classes:\n                db_info = {\n                    'name': names[i],\n                    'path': rel_filepath,\n                    'image_idx': image_idx,\n                    'gt_idx': i,\n                    'box3d_lidar': gt_boxes_3d[i],\n                    'num_points_in_gt': gt_points.shape[0],\n                    'difficulty': difficulty[i],\n                }\n                local_group_id = group_ids[i]\n                # if local_group_id >= 0:\n                if local_group_id not in group_dict:\n                    group_dict[local_group_id] = group_counter\n                    group_counter += 1\n                db_info['group_id'] = group_dict[local_group_id]\n                if 'score' in annos:\n                    db_info['score'] = annos['score'][i]\n                if with_mask:\n                    db_info.update({'box2d_camera': gt_boxes[i]})\n                if names[i] in all_db_infos:\n                    all_db_infos[names[i]].append(db_info)\n                else:\n                    all_db_infos[names[i]] = [db_info]\n\n    for k, v in all_db_infos.items():\n        print(f'load {len(v)} {k} database infos')\n\n    with open(db_info_save_path, 'wb') as f:\n        pickle.dump(all_db_infos, f)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/data_converter/vad_nuscenes_converter.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport mmcv\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.utils.data_classes import Box\nfrom shapely.geometry import MultiPoint, box\nfrom mmdet3d.datasets import NuScenesDataset\nfrom nuscenes.utils.geometry_utils import view_points\nfrom mmdet3d.core.bbox.box_np_ops import points_cam2img\nfrom nuscenes.utils.geometry_utils import transform_matrix\n\n\nnus_categories = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',\n                  'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',\n                  'barrier')\n\nnus_attributes = ('cycle.with_rider', 'cycle.without_rider',\n                  'pedestrian.moving', 'pedestrian.standing',\n                  'pedestrian.sitting_lying_down', 'vehicle.moving',\n                  'vehicle.parked', 'vehicle.stopped', 'None')\n\nego_width, ego_length = 1.85, 4.084\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    from nuscenes.nuscenes import NuScenes\n    from nuscenes.can_bus.can_bus_api import NuScenesCanBus\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n    else:\n        raise ValueError('unknown')\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_temporal_test.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_temporal_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_temporal_val.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\n\ndef _get_can_bus_info(nusc, nusc_can_bus, sample):\n    scene_name = nusc.get('scene', sample['scene_token'])['name']\n    sample_timestamp = sample['timestamp']\n    try:\n        pose_list = nusc_can_bus.get_messages(scene_name, 'pose')\n    except:\n        return np.zeros(18)  # server scenes do not have can bus information.\n    can_bus = []\n    # during each scene, the first timestamp of can_bus may be large than the first sample's timestamp\n    last_pose = pose_list[0]\n    for i, pose in enumerate(pose_list):\n        if pose['utime'] > sample_timestamp:\n            break\n        last_pose = pose\n    _ = last_pose.pop('utime')  # useless\n    pos = last_pose.pop('pos')\n    rotation = last_pose.pop('orientation')\n    can_bus.extend(pos)\n    can_bus.extend(rotation)\n    for key in last_pose.keys():\n        can_bus.extend(pose[key])  # 16 elements\n    can_bus.extend([0., 0.])\n    return np.array(can_bus)\n\n\ndef _fill_trainval_infos(nusc,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=6,\n                         his_ts=2):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    frame_idx = 0\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        if sample['prev'] != '':\n            sample_prev = nusc.get('sample', sample['prev'])\n            sd_rec_prev = nusc.get('sample_data', sample_prev['data']['LIDAR_TOP'])\n            pose_record_prev = nusc.get('ego_pose', sd_rec_prev['ego_pose_token'])\n        else:\n            pose_record_prev = None\n        if sample['next'] != '':\n            sample_next = nusc.get('sample', sample['next'])\n            sd_rec_next = nusc.get('sample_data', sample_next['data']['LIDAR_TOP'])\n            pose_record_next = nusc.get('ego_pose', sd_rec_next['ego_pose_token'])\n        else:\n            pose_record_next = None\n\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n\n        mmcv.check_file_exist(lidar_path)\n        can_bus = _get_can_bus_info(nusc, nusc_can_bus, sample)\n        fut_valid_flag = True\n        test_sample = copy.deepcopy(sample)\n        for i in range(fut_ts):\n            if test_sample['next'] != '':\n                test_sample = nusc.get('sample', test_sample['next'])\n            else:\n                fut_valid_flag = False\n        ##\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'prev': sample['prev'],\n            'next': sample['next'],\n            'can_bus': can_bus,\n            'frame_idx': frame_idx,  # temporal related info\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],  # temporal related info\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'fut_valid_flag': fut_valid_flag,\n            'map_location': map_location\n        }\n\n        if sample['next'] == '':\n            frame_idx = 0\n        else:\n            frame_idx += 1\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NuScenesDataset.NameMapping:\n                    names[i] = NuScenesDataset.NameMapping[names[i]]\n            names = np.array(names)\n            # we need to convert rot to SECOND format.\n            gt_boxes = np.concatenate([locs, dims, -rots - np.pi / 2], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # get future coords for each box\n            # [num_box, fut_ts*2]\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_yaw = np.zeros((num_box, fut_ts))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            gt_boxes_yaw = -(gt_boxes[:,6] + np.pi / 2)\n            # agent lcf feat (x, y, yaw, vx, vy, width, length, height, type)\n            agent_lcf_feat = np.zeros((num_box, 9))\n            gt_fut_goal = np.zeros((num_box))\n            for i, anno in enumerate(annotations):\n                cur_box = boxes[i]\n                cur_anno = anno\n                agent_lcf_feat[i, 0:2] = cur_box.center[:2]\t\n                agent_lcf_feat[i, 2] = gt_boxes_yaw[i]\n                agent_lcf_feat[i, 3:5] = velocity[i]\n                agent_lcf_feat[i, 5:8] = anno['size'] # width,length,height\n                agent_lcf_feat[i, 8] = cat2idx[anno['category_name']] if anno['category_name'] in cat2idx.keys() else -1\n                for j in range(fut_ts):\n                    if cur_anno['next'] != '':\n                        anno_next = nusc.get('sample_annotation', cur_anno['next'])\n                        box_next = Box(\n                            anno_next['translation'], anno_next['size'], Quaternion(anno_next['rotation'])\n                        )\n                        # Move box to ego vehicle coord system.\n                        box_next.translate(-np.array(pose_record['translation']))\n                        box_next.rotate(Quaternion(pose_record['rotation']).inverse)\n                        #  Move box to sensor coord system.\n                        box_next.translate(-np.array(cs_record['translation']))\n                        box_next.rotate(Quaternion(cs_record['rotation']).inverse)\n                        gt_fut_trajs[i, j] = box_next.center[:2] - cur_box.center[:2]\n                        gt_fut_masks[i, j] = 1\n                        # add yaw diff\n                        _, _, box_yaw = quart_to_rpy([cur_box.orientation.x, cur_box.orientation.y,\n                                                      cur_box.orientation.z, cur_box.orientation.w])\n                        _, _, box_yaw_next = quart_to_rpy([box_next.orientation.x, box_next.orientation.y,\n                                                           box_next.orientation.z, box_next.orientation.w])\n                        gt_fut_yaw[i, j] = box_yaw_next - box_yaw\n                        cur_anno = anno_next\n                        cur_box = box_next\n                    else:\n                        gt_fut_trajs[i, j:] = 0\n                        break\n                # get agent goal\n                gt_fut_coords = np.cumsum(gt_fut_trajs[i], axis=-2)\n                coord_diff = gt_fut_coords[-1] - gt_fut_coords[0]\n                if coord_diff.max() < 1.0: # static\n                    gt_fut_goal[i] = 9\n                else:\n                    box_mot_yaw = np.arctan2(coord_diff[1], coord_diff[0]) + np.pi\n                    gt_fut_goal[i] = box_mot_yaw // (np.pi / 4)  # 0-8: goal direction class\n\n            # get ego history traj (offset format)\n            ego_his_trajs = np.zeros((his_ts+1, 3))\n            ego_his_trajs_diff = np.zeros((his_ts+1, 3))\n            sample_cur = sample\n            for i in range(his_ts, -1, -1):\n                if sample_cur is not None:\n                    pose_mat = get_global_sensor_pose(sample_cur, nusc, inverse=False)\n                    ego_his_trajs[i] = pose_mat[:3, 3]\n                    has_prev = sample_cur['prev'] != ''\n                    has_next = sample_cur['next'] != ''\n                    if has_next:\n                        sample_next = nusc.get('sample', sample_cur['next'])\n                        pose_mat_next = get_global_sensor_pose(sample_next, nusc, inverse=False)\n                        ego_his_trajs_diff[i] = pose_mat_next[:3, 3] - ego_his_trajs[i]\n                    sample_cur = nusc.get('sample', sample_cur['prev']) if has_prev else None\n                else:\n                    ego_his_trajs[i] = ego_his_trajs[i+1] - ego_his_trajs_diff[i+1]\n                    ego_his_trajs_diff[i] = ego_his_trajs_diff[i+1]\n            \n            # global to ego at lcf\n            ego_his_trajs = ego_his_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_his_trajs = np.dot(rot_mat, ego_his_trajs.T).T\n            # ego to lidar at lcf\n            ego_his_trajs = ego_his_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_his_trajs = np.dot(rot_mat, ego_his_trajs.T).T\n            ego_his_trajs = ego_his_trajs[1:] - ego_his_trajs[:-1]\n\n            # get ego futute traj (offset format)\n            ego_fut_trajs = np.zeros((fut_ts+1, 3))\n            ego_fut_masks = np.zeros((fut_ts+1))\n            sample_cur = sample\n            for i in range(fut_ts+1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc, inverse=False)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego at lcf\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar at lcf\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset from lcf\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # offset from lcf -> per-step offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]\n\n            ### ego lcf feat (vx, vy, ax, ay, w, length, width, vel, steer), w: yaw角速度\n            ego_lcf_feat = np.zeros(9)\n            # 根据odom推算自车速度及加速度\n            _, _, ego_yaw = quart_to_rpy(pose_record['rotation'])\n            ego_pos = np.array(pose_record['translation'])\n            if pose_record_prev is not None:\n                _, _, ego_yaw_prev = quart_to_rpy(pose_record_prev['rotation'])\n                ego_pos_prev = np.array(pose_record_prev['translation'])\n            if pose_record_next is not None:\n                _, _, ego_yaw_next = quart_to_rpy(pose_record_next['rotation'])\n                ego_pos_next = np.array(pose_record_next['translation'])\n            assert (pose_record_prev is not None) or (pose_record_next is not None), 'prev token and next token all empty'\n            if pose_record_prev is not None:\n                ego_w = (ego_yaw - ego_yaw_prev) / 0.5\n                ego_v = np.linalg.norm(ego_pos[:2] - ego_pos_prev[:2]) / 0.5\n                ego_vx, ego_vy = ego_v * math.cos(ego_yaw + np.pi/2), ego_v * math.sin(ego_yaw + np.pi/2)\n            else:\n                ego_w = (ego_yaw_next - ego_yaw) / 0.5\n                ego_v = np.linalg.norm(ego_pos_next[:2] - ego_pos[:2]) / 0.5\n                ego_vx, ego_vy = ego_v * math.cos(ego_yaw + np.pi/2), ego_v * math.sin(ego_yaw + np.pi/2)\n\n            ref_scene = nusc.get(\"scene\", sample['scene_token'])\n            try:\n                pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n                steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n                pose_uts = [msg['utime'] for msg in pose_msgs]\n                steer_uts = [msg['utime'] for msg in steer_msgs]\n                ref_utime = sample['timestamp']\n                pose_index = locate_message(pose_uts, ref_utime)\n                pose_data = pose_msgs[pose_index]\n                steer_index = locate_message(steer_uts, ref_utime)\n                steer_data = steer_msgs[steer_index]\n                # initial speed\n                v0 = pose_data[\"vel\"][0]  # [0] means longitudinal velocity  m/s\n                # curvature (positive: turn left)\n                steering = steer_data[\"value\"]\n                # flip x axis if in left-hand traffic (singapore)\n                flip_flag = True if map_location.startswith('singapore') else False\n                if flip_flag:\n                    steering *= -1\n                Kappa = 2 * steering / 2.588\n            except:\n                delta_x = ego_his_trajs[-1, 0] + ego_fut_trajs[0, 0]\n                delta_y = ego_his_trajs[-1, 1] + ego_fut_trajs[0, 1]\n                v0 = np.sqrt(delta_x**2 + delta_y**2)\n                Kappa = 0\n\n            ego_lcf_feat[:2] = np.array([ego_vx, ego_vy]) #can_bus[13:15]\n            ego_lcf_feat[2:4] = can_bus[7:9]\n            ego_lcf_feat[4] = ego_w #can_bus[12]\n            ego_lcf_feat[5:7] = np.array([ego_length, ego_width])\n            ego_lcf_feat[7] = v0\n            ego_lcf_feat[8] = Kappa\n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.reshape(-1, fut_ts*2).astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.reshape(-1, fut_ts).astype(np.float32)\n            info['gt_agent_lcf_feat'] = agent_lcf_feat.astype(np.float32)\n            info['gt_agent_fut_yaw'] = gt_fut_yaw.astype(np.float32)\n            info['gt_agent_fut_goal'] = gt_fut_goal.astype(np.float32)\n            info['gt_ego_his_trajs'] = ego_his_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['gt_ego_lcf_feat'] = ego_lcf_feat.astype(np.float32)\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_global_sensor_pose(rec, nusc, inverse=False):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    sd_ep = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    sd_cs = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n    if inverse is False:\n        global_from_ego = transform_matrix(sd_ep[\"translation\"], Quaternion(sd_ep[\"rotation\"]), inverse=False)\n        ego_from_sensor = transform_matrix(sd_cs[\"translation\"], Quaternion(sd_cs[\"rotation\"]), inverse=False)\n        pose = global_from_ego.dot(ego_from_sensor)\n        # translation equivalent writing\n        # pose_translation = np.array(sd_cs[\"translation\"])\n        # rot_mat = Quaternion(sd_ep['rotation']).rotation_matrix\n        # pose_translation = np.dot(rot_mat, pose_translation)\n        # # pose_translation = pose[:3, 3]\n        # pose_translation = pose_translation + np.array(sd_ep[\"translation\"])\n    else:\n        sensor_from_ego = transform_matrix(sd_cs[\"translation\"], Quaternion(sd_cs[\"rotation\"]), inverse=True)\n        ego_from_global = transform_matrix(sd_ep[\"translation\"], Quaternion(sd_ep[\"rotation\"]), inverse=True)\n        pose = sensor_from_ego.dot(ego_from_global)\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\n\ndef export_2d_annotation(root_path, info_path, version, mono3d=False):\n    \"\"\"Export 2d annotation from the info file and raw data.\n\n    Args:\n        root_path (str): Root path of the raw data.\n        info_path (str): Path of the info file.\n        version (str): Dataset version.\n        mono3d (bool): Whether to export mono3d annotation. Default: False.\n    \"\"\"\n    # get bbox annotations for camera\n    camera_types = [\n        'CAM_FRONT',\n        'CAM_FRONT_RIGHT',\n        'CAM_FRONT_LEFT',\n        'CAM_BACK',\n        'CAM_BACK_LEFT',\n        'CAM_BACK_RIGHT',\n    ]\n    nusc_infos = mmcv.load(info_path)['infos']\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    # info_2d_list = []\n    cat2Ids = [\n        dict(id=nus_categories.index(cat_name), name=cat_name)\n        for cat_name in nus_categories\n    ]\n    coco_ann_id = 0\n    coco_2d_dict = dict(annotations=[], images=[], categories=cat2Ids)\n    for info in mmcv.track_iter_progress(nusc_infos):\n        for cam in camera_types:\n            cam_info = info['cams'][cam]\n            coco_infos = get_2d_boxes(\n                nusc,\n                cam_info['sample_data_token'],\n                visibilities=['', '1', '2', '3', '4'],\n                mono3d=mono3d)\n            (height, width, _) = mmcv.imread(cam_info['data_path']).shape\n            coco_2d_dict['images'].append(\n                dict(\n                    file_name=cam_info['data_path'].split('data/nuscenes/')\n                    [-1],\n                    id=cam_info['sample_data_token'],\n                    token=info['token'],\n                    cam2ego_rotation=cam_info['sensor2ego_rotation'],\n                    cam2ego_translation=cam_info['sensor2ego_translation'],\n                    ego2global_rotation=info['ego2global_rotation'],\n                    ego2global_translation=info['ego2global_translation'],\n                    cam_intrinsic=cam_info['cam_intrinsic'],\n                    width=width,\n                    height=height))\n            for coco_info in coco_infos:\n                if coco_info is None:\n                    continue\n                # add an empty key for coco format\n                coco_info['segmentation'] = []\n                coco_info['id'] = coco_ann_id\n                coco_2d_dict['annotations'].append(coco_info)\n                coco_ann_id += 1\n    if mono3d:\n        json_prefix = f'{info_path[:-4]}_mono3d'\n    else:\n        json_prefix = f'{info_path[:-4]}'\n    mmcv.dump(coco_2d_dict, f'{json_prefix}.coco.json')\n\n\ndef get_2d_boxes(nusc,\n                 sample_data_token: str,\n                 visibilities: List[str],\n                 mono3d=True):\n    \"\"\"Get the 2D annotation records for a given `sample_data_token`.\n\n    Args:\n        sample_data_token (str): Sample data token belonging to a camera \\\n            keyframe.\n        visibilities (list[str]): Visibility filter.\n        mono3d (bool): Whether to get boxes with mono3d annotation.\n\n    Return:\n        list[dict]: List of 2D annotation record that belongs to the input\n            `sample_data_token`.\n    \"\"\"\n\n    # Get the sample data and the sample corresponding to that sample data.\n    sd_rec = nusc.get('sample_data', sample_data_token)\n\n    assert sd_rec[\n        'sensor_modality'] == 'camera', 'Error: get_2d_boxes only works' \\\n        ' for camera sample_data!'\n    if not sd_rec['is_key_frame']:\n        raise ValueError(\n            'The 2D re-projections are available only for keyframes.')\n\n    s_rec = nusc.get('sample', sd_rec['sample_token'])\n\n    # Get the calibrated sensor and ego pose\n    # record to get the transformation matrices.\n    cs_rec = nusc.get('calibrated_sensor', sd_rec['calibrated_sensor_token'])\n    pose_rec = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    camera_intrinsic = np.array(cs_rec['camera_intrinsic'])\n\n    # Get all the annotation with the specified visibilties.\n    ann_recs = [\n        nusc.get('sample_annotation', token) for token in s_rec['anns']\n    ]\n    ann_recs = [\n        ann_rec for ann_rec in ann_recs\n        if (ann_rec['visibility_token'] in visibilities)\n    ]\n\n    repro_recs = []\n\n    for ann_rec in ann_recs:\n        # Augment sample_annotation with token information.\n        ann_rec['sample_annotation_token'] = ann_rec['token']\n        ann_rec['sample_data_token'] = sample_data_token\n\n        # Get the box in global coordinates.\n        box = nusc.get_box(ann_rec['token'])\n\n        # Move them to the ego-pose frame.\n        box.translate(-np.array(pose_rec['translation']))\n        box.rotate(Quaternion(pose_rec['rotation']).inverse)\n\n        # Move them to the calibrated sensor frame.\n        box.translate(-np.array(cs_rec['translation']))\n        box.rotate(Quaternion(cs_rec['rotation']).inverse)\n\n        # Filter out the corners that are not in front of the calibrated\n        # sensor.\n        corners_3d = box.corners()\n        in_front = np.argwhere(corners_3d[2, :] > 0).flatten()\n        corners_3d = corners_3d[:, in_front]\n\n        # Project 3d box to 2d.\n        corner_coords = view_points(corners_3d, camera_intrinsic,\n                                    True).T[:, :2].tolist()\n\n        # Keep only corners that fall within the image.\n        final_coords = post_process_coords(corner_coords)\n\n        # Skip if the convex hull of the re-projected corners\n        # does not intersect the image canvas.\n        if final_coords is None:\n            continue\n        else:\n            min_x, min_y, max_x, max_y = final_coords\n\n        # Generate dictionary record to be included in the .json file.\n        repro_rec = generate_record(ann_rec, min_x, min_y, max_x, max_y,\n                                    sample_data_token, sd_rec['filename'])\n\n        # If mono3d=True, add 3D annotations in camera coordinates\n        if mono3d and (repro_rec is not None):\n            loc = box.center.tolist()\n\n            dim = box.wlh\n            dim[[0, 1, 2]] = dim[[1, 2, 0]]  # convert wlh to our lhw\n            dim = dim.tolist()\n\n            rot = box.orientation.yaw_pitch_roll[0]\n            rot = [-rot]  # convert the rot to our cam coordinate\n\n            global_velo2d = nusc.box_velocity(box.token)[:2]\n            global_velo3d = np.array([*global_velo2d, 0.0])\n            e2g_r_mat = Quaternion(pose_rec['rotation']).rotation_matrix\n            c2e_r_mat = Quaternion(cs_rec['rotation']).rotation_matrix\n            cam_velo3d = global_velo3d @ np.linalg.inv(\n                e2g_r_mat).T @ np.linalg.inv(c2e_r_mat).T\n            velo = cam_velo3d[0::2].tolist()\n\n            repro_rec['bbox_cam3d'] = loc + dim + rot\n            repro_rec['velo_cam3d'] = velo\n\n            center3d = np.array(loc).reshape([1, 3])\n            center2d = points_cam2img(\n                center3d, camera_intrinsic, with_depth=True)\n            repro_rec['center2d'] = center2d.squeeze().tolist()\n            # normalized center2D + depth\n            # if samples with depth < 0 will be removed\n            if repro_rec['center2d'][2] <= 0:\n                continue\n\n            ann_token = nusc.get('sample_annotation',\n                                 box.token)['attribute_tokens']\n            if len(ann_token) == 0:\n                attr_name = 'None'\n            else:\n                attr_name = nusc.get('attribute', ann_token[0])['name']\n            attr_id = nus_attributes.index(attr_name)\n            repro_rec['attribute_name'] = attr_name\n            repro_rec['attribute_id'] = attr_id\n\n        repro_recs.append(repro_rec)\n\n    return repro_recs\n\n\ndef post_process_coords(\n    corner_coords: List, imsize: Tuple[int, int] = (1600, 900)\n) -> Union[Tuple[float, float, float, float], None]:\n    \"\"\"Get the intersection of the convex hull of the reprojected bbox corners\n    and the image canvas, return None if no intersection.\n\n    Args:\n        corner_coords (list[int]): Corner coordinates of reprojected\n            bounding box.\n        imsize (tuple[int]): Size of the image canvas.\n\n    Return:\n        tuple [float]: Intersection of the convex hull of the 2D box\n            corners and the image canvas.\n    \"\"\"\n    polygon_from_2d_box = MultiPoint(corner_coords).convex_hull\n    img_canvas = box(0, 0, imsize[0], imsize[1])\n\n    if polygon_from_2d_box.intersects(img_canvas):\n        img_intersection = polygon_from_2d_box.intersection(img_canvas)\n        intersection_coords = np.array(\n            [coord for coord in img_intersection.exterior.coords])\n\n        min_x = min(intersection_coords[:, 0])\n        min_y = min(intersection_coords[:, 1])\n        max_x = max(intersection_coords[:, 0])\n        max_y = max(intersection_coords[:, 1])\n\n        return min_x, min_y, max_x, max_y\n    else:\n        return None\n\n\ndef generate_record(ann_rec: dict, x1: float, y1: float, x2: float, y2: float,\n                    sample_data_token: str, filename: str) -> OrderedDict:\n    \"\"\"Generate one 2D annotation record given various informations on top of\n    the 2D bounding box coordinates.\n\n    Args:\n        ann_rec (dict): Original 3d annotation record.\n        x1 (float): Minimum value of the x coordinate.\n        y1 (float): Minimum value of the y coordinate.\n        x2 (float): Maximum value of the x coordinate.\n        y2 (float): Maximum value of the y coordinate.\n        sample_data_token (str): Sample data token.\n        filename (str):The corresponding image file where the annotation\n            is present.\n\n    Returns:\n        dict: A sample 2D annotation record.\n            - file_name (str): flie name\n            - image_id (str): sample data token\n            - area (float): 2d box area\n            - category_name (str): category name\n            - category_id (int): category id\n            - bbox (list[float]): left x, top y, dx, dy of 2d box\n            - iscrowd (int): whether the area is crowd\n    \"\"\"\n    repro_rec = OrderedDict()\n    repro_rec['sample_data_token'] = sample_data_token\n    coco_rec = dict()\n\n    relevant_keys = [\n        'attribute_tokens',\n        'category_name',\n        'instance_token',\n        'next',\n        'num_lidar_pts',\n        'num_radar_pts',\n        'prev',\n        'sample_annotation_token',\n        'sample_data_token',\n        'visibility_token',\n    ]\n\n    for key, value in ann_rec.items():\n        if key in relevant_keys:\n            repro_rec[key] = value\n\n    repro_rec['bbox_corners'] = [x1, y1, x2, y2]\n    repro_rec['filename'] = filename\n\n    coco_rec['file_name'] = filename\n    coco_rec['image_id'] = sample_data_token\n    coco_rec['area'] = (y2 - y1) * (x2 - x1)\n\n    if repro_rec['category_name'] not in NuScenesDataset.NameMapping:\n        return None\n    cat_name = NuScenesDataset.NameMapping[repro_rec['category_name']]\n    coco_rec['category_name'] = cat_name\n    coco_rec['category_id'] = nus_categories.index(cat_name)\n    coco_rec['bbox'] = [x1, y1, x2 - x1, y2 - y1]\n    coco_rec['iscrowd'] = 0\n\n    return coco_rec\n\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/dist_test.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nPORT=${PORT:-29503}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/test.py $CONFIG $CHECKPOINT --launcher pytorch ${@:4} --eval bbox\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28510}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\nCUDA_VISIBLE_DEVICES=6 python -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3} --deterministic \n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/dist_train_momad.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28509}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train_momad.py $CONFIG --launcher pytorch ${@:3} --deterministic\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/misc/browse_dataset.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport numpy as np\nimport warnings\nfrom mmcv import Config, DictAction, mkdir_or_exist, track_iter_progress\nfrom os import path as osp\n\nfrom mmdet3d.core.bbox import (Box3DMode, CameraInstance3DBoxes, Coord3DMode,\n                               DepthInstance3DBoxes, LiDARInstance3DBoxes)\nfrom mmdet3d.core.visualizer import (show_multi_modality_result, show_result,\n                                     show_seg_result)\nfrom mmdet3d.datasets import build_dataset\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Browse a dataset')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument(\n        '--skip-type',\n        type=str,\n        nargs='+',\n        default=['Normalize'],\n        help='skip some useless pipeline')\n    parser.add_argument(\n        '--output-dir',\n        default=None,\n        type=str,\n        help='If there is no display interface, you can save it')\n    parser.add_argument(\n        '--task',\n        type=str,\n        choices=['det', 'seg', 'multi_modality-det', 'mono-det'],\n        help='Determine the visualization method depending on the task.')\n    parser.add_argument(\n        '--online',\n        action='store_true',\n        help='Whether to perform online visualization. Note that you often '\n        'need a monitor to do so.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    args = parser.parse_args()\n    return args\n\n\ndef build_data_cfg(config_path, skip_type, cfg_options):\n    \"\"\"Build data config for loading visualization data.\"\"\"\n    cfg = Config.fromfile(config_path)\n    if cfg_options is not None:\n        cfg.merge_from_dict(cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n    # extract inner dataset of `RepeatDataset` as `cfg.data.train`\n    # so we don't need to worry about it later\n    if cfg.data.train['type'] == 'RepeatDataset':\n        cfg.data.train = cfg.data.train.dataset\n    # use only first dataset for `ConcatDataset`\n    if cfg.data.train['type'] == 'ConcatDataset':\n        cfg.data.train = cfg.data.train.datasets[0]\n    train_data_cfg = cfg.data.train\n    # eval_pipeline purely consists of loading functions\n    # use eval_pipeline for data loading\n    train_data_cfg['pipeline'] = [\n        x for x in cfg.eval_pipeline if x['type'] not in skip_type\n    ]\n\n    return cfg\n\n\ndef to_depth_mode(points, bboxes):\n    \"\"\"Convert points and bboxes to Depth Coord and Depth Box mode.\"\"\"\n    if points is not None:\n        points = Coord3DMode.convert_point(points.copy(), Coord3DMode.LIDAR,\n                                           Coord3DMode.DEPTH)\n    if bboxes is not None:\n        bboxes = Box3DMode.convert(bboxes.clone(), Box3DMode.LIDAR,\n                                   Box3DMode.DEPTH)\n    return points, bboxes\n\n\ndef show_det_data(idx, dataset, out_dir, filename, show=False):\n    \"\"\"Visualize 3D point cloud and 3D bboxes.\"\"\"\n    example = dataset.prepare_train_data(idx)\n    points = example['points']._data.numpy()\n    gt_bboxes = dataset.get_ann_info(idx)['gt_bboxes_3d'].tensor\n    if dataset.box_mode_3d != Box3DMode.DEPTH:\n        points, gt_bboxes = to_depth_mode(points, gt_bboxes)\n    show_result(\n        points,\n        gt_bboxes.clone(),\n        None,\n        out_dir,\n        filename,\n        show=show,\n        snapshot=True)\n\n\ndef show_seg_data(idx, dataset, out_dir, filename, show=False):\n    \"\"\"Visualize 3D point cloud and segmentation mask.\"\"\"\n    example = dataset.prepare_train_data(idx)\n    points = example['points']._data.numpy()\n    gt_seg = example['pts_semantic_mask']._data.numpy()\n    show_seg_result(\n        points,\n        gt_seg.copy(),\n        None,\n        out_dir,\n        filename,\n        np.array(dataset.PALETTE),\n        dataset.ignore_index,\n        show=show,\n        snapshot=True)\n\n\ndef show_proj_bbox_img(idx,\n                       dataset,\n                       out_dir,\n                       filename,\n                       show=False,\n                       is_nus_mono=False):\n    \"\"\"Visualize 3D bboxes on 2D image by projection.\"\"\"\n    try:\n        example = dataset.prepare_train_data(idx)\n    except AttributeError:  # for Mono-3D datasets\n        example = dataset.prepare_train_img(idx)\n    gt_bboxes = dataset.get_ann_info(idx)['gt_bboxes_3d']\n    img_metas = example['img_metas']._data\n    img = example['img']._data.numpy()\n    # need to transpose channel to first dim\n    img = img.transpose(1, 2, 0)\n    # no 3D gt bboxes, just show img\n    if gt_bboxes.tensor.shape[0] == 0:\n        gt_bboxes = None\n    if isinstance(gt_bboxes, DepthInstance3DBoxes):\n        show_multi_modality_result(\n            img,\n            gt_bboxes,\n            None,\n            None,\n            out_dir,\n            filename,\n            box_mode='depth',\n            img_metas=img_metas,\n            show=show)\n    elif isinstance(gt_bboxes, LiDARInstance3DBoxes):\n        show_multi_modality_result(\n            img,\n            gt_bboxes,\n            None,\n            img_metas['lidar2img'],\n            out_dir,\n            filename,\n            box_mode='lidar',\n            img_metas=img_metas,\n            show=show)\n    elif isinstance(gt_bboxes, CameraInstance3DBoxes):\n        show_multi_modality_result(\n            img,\n            gt_bboxes,\n            None,\n            img_metas['cam2img'],\n            out_dir,\n            filename,\n            box_mode='camera',\n            img_metas=img_metas,\n            show=show)\n    else:\n        # can't project, just show img\n        warnings.warn(\n            f'unrecognized gt box type {type(gt_bboxes)}, only show image')\n        show_multi_modality_result(\n            img, None, None, None, out_dir, filename, show=show)\n\n\ndef main():\n    args = parse_args()\n\n    if args.output_dir is not None:\n        mkdir_or_exist(args.output_dir)\n\n    cfg = build_data_cfg(args.config, args.skip_type, args.cfg_options)\n    try:\n        dataset = build_dataset(\n            cfg.data.train, default_args=dict(filter_empty_gt=False))\n    except TypeError:  # seg dataset doesn't have `filter_empty_gt` key\n        dataset = build_dataset(cfg.data.train)\n    data_infos = dataset.data_infos\n    dataset_type = cfg.dataset_type\n\n    # configure visualization mode\n    vis_task = args.task  # 'det', 'seg', 'multi_modality-det', 'mono-det'\n\n    for idx, data_info in enumerate(track_iter_progress(data_infos)):\n        if dataset_type in ['KittiDataset', 'WaymoDataset']:\n            data_path = data_info['point_cloud']['velodyne_path']\n        elif dataset_type in [\n                'ScanNetDataset', 'SUNRGBDDataset', 'ScanNetSegDataset',\n                'S3DISSegDataset', 'S3DISDataset'\n        ]:\n            data_path = data_info['pts_path']\n        elif dataset_type in ['NuScenesDataset', 'LyftDataset']:\n            data_path = data_info['lidar_path']\n        elif dataset_type in ['NuScenesMonoDataset']:\n            data_path = data_info['file_name']\n        else:\n            raise NotImplementedError(\n                f'unsupported dataset type {dataset_type}')\n\n        file_name = osp.splitext(osp.basename(data_path))[0]\n\n        if vis_task in ['det', 'multi_modality-det']:\n            # show 3D bboxes on 3D point clouds\n            show_det_data(\n                idx, dataset, args.output_dir, file_name, show=args.online)\n        if vis_task in ['multi_modality-det', 'mono-det']:\n            # project 3D bboxes to 2D image\n            show_proj_bbox_img(\n                idx,\n                dataset,\n                args.output_dir,\n                file_name,\n                show=args.online,\n                is_nus_mono=(dataset_type == 'NuScenesMonoDataset'))\n        elif vis_task in ['seg']:\n            # show 3D segmentation mask on 3D point clouds\n            show_seg_data(\n                idx, dataset, args.output_dir, file_name, show=args.online)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/misc/fuse_conv_bn.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport torch\nfrom mmcv.runner import save_checkpoint\nfrom torch import nn as nn\n\nfrom mmdet.apis import init_model\n\n\ndef fuse_conv_bn(conv, bn):\n    \"\"\"During inference, the functionary of batch norm layers is turned off but\n    only the mean and var alone channels are used, which exposes the chance to\n    fuse it with the preceding conv layers to save computations and simplify\n    network structures.\"\"\"\n    conv_w = conv.weight\n    conv_b = conv.bias if conv.bias is not None else torch.zeros_like(\n        bn.running_mean)\n\n    factor = bn.weight / torch.sqrt(bn.running_var + bn.eps)\n    conv.weight = nn.Parameter(conv_w *\n                               factor.reshape([conv.out_channels, 1, 1, 1]))\n    conv.bias = nn.Parameter((conv_b - bn.running_mean) * factor + bn.bias)\n    return conv\n\n\ndef fuse_module(m):\n    last_conv = None\n    last_conv_name = None\n\n    for name, child in m.named_children():\n        if isinstance(child, (nn.BatchNorm2d, nn.SyncBatchNorm)):\n            if last_conv is None:  # only fuse BN that is after Conv\n                continue\n            fused_conv = fuse_conv_bn(last_conv, child)\n            m._modules[last_conv_name] = fused_conv\n            # To reduce changes, set BN as Identity instead of deleting it.\n            m._modules[name] = nn.Identity()\n            last_conv = None\n        elif isinstance(child, nn.Conv2d):\n            last_conv = child\n            last_conv_name = name\n        else:\n            fuse_module(child)\n    return m\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='fuse Conv and BN layers in a model')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument('checkpoint', help='checkpoint file path')\n    parser.add_argument('out', help='output path of the converted model')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n    # build the model from a config file and a checkpoint file\n    model = init_model(args.config, args.checkpoint)\n    # fuse conv and bn layers of the model\n    fused_model = fuse_module(model)\n    save_checkpoint(fused_model, args.out)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/misc/print_config.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nfrom mmcv import Config, DictAction\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Print the whole config')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument(\n        '--options', nargs='+', action=DictAction, help='arguments in dict')\n    args = parser.parse_args()\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.options is not None:\n        cfg.merge_from_dict(args.options)\n    print(f'Config:\\n{cfg.pretty_text}')\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/misc/visualize_results.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport mmcv\nfrom mmcv import Config\n\nfrom mmdet3d.datasets import build_dataset\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet3D visualize the results')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--result', help='results file in pickle format')\n    parser.add_argument(\n        '--show-dir', help='directory where visualize results will be saved')\n    args = parser.parse_args()\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    if args.result is not None and \\\n            not args.result.endswith(('.pkl', '.pickle')):\n        raise ValueError('The results file must be a pkl file.')\n\n    cfg = Config.fromfile(args.config)\n    cfg.data.test.test_mode = True\n\n    # build the dataset\n    dataset = build_dataset(cfg.data.test)\n    results = mmcv.load(args.result)\n\n    if getattr(dataset, 'show', None) is not None:\n        # data loading pipeline for showing\n        eval_pipeline = cfg.get('eval_pipeline', {})\n        if eval_pipeline:\n            dataset.show(results, args.show_dir, pipeline=eval_pipeline)\n        else:\n            dataset.show(results, args.show_dir)  # use default pipeline\n    else:\n        raise NotImplementedError(\n            'Show is not implemented for dataset {}!'.format(\n                type(dataset).__name__))\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/model_converters/convert_votenet_checkpoints.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport tempfile\nimport torch\nfrom mmcv import Config\nfrom mmcv.runner import load_state_dict\n\nfrom mmdet3d.models import build_detector\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet3D upgrade model version(before v0.6.0) of VoteNet')\n    parser.add_argument('checkpoint', help='checkpoint file')\n    parser.add_argument('--out', help='path of the output checkpoint file')\n    args = parser.parse_args()\n    return args\n\n\ndef parse_config(config_strings):\n    \"\"\"Parse config from strings.\n\n    Args:\n        config_strings (string): strings of model config.\n\n    Returns:\n        Config: model config\n    \"\"\"\n    temp_file = tempfile.NamedTemporaryFile()\n    config_path = f'{temp_file.name}.py'\n    with open(config_path, 'w') as f:\n        f.write(config_strings)\n\n    config = Config.fromfile(config_path)\n\n    # Update backbone config\n    if 'pool_mod' in config.model.backbone:\n        config.model.backbone.pop('pool_mod')\n\n    if 'sa_cfg' not in config.model.backbone:\n        config.model.backbone['sa_cfg'] = dict(\n            type='PointSAModule',\n            pool_mod='max',\n            use_xyz=True,\n            normalize_xyz=True)\n\n    if 'type' not in config.model.bbox_head.vote_aggregation_cfg:\n        config.model.bbox_head.vote_aggregation_cfg['type'] = 'PointSAModule'\n\n    # Update bbox_head config\n    if 'pred_layer_cfg' not in config.model.bbox_head:\n        config.model.bbox_head['pred_layer_cfg'] = dict(\n            in_channels=128, shared_conv_channels=(128, 128), bias=True)\n\n    if 'feat_channels' in config.model.bbox_head:\n        config.model.bbox_head.pop('feat_channels')\n\n    if 'vote_moudule_cfg' in config.model.bbox_head:\n        config.model.bbox_head['vote_module_cfg'] = config.model.bbox_head.pop(\n            'vote_moudule_cfg')\n\n    if config.model.bbox_head.vote_aggregation_cfg.use_xyz:\n        config.model.bbox_head.vote_aggregation_cfg.mlp_channels[0] -= 3\n\n    temp_file.close()\n\n    return config\n\n\ndef main():\n    \"\"\"Convert keys in checkpoints for VoteNet.\n\n    There can be some breaking changes during the development of mmdetection3d,\n    and this tool is used for upgrading checkpoints trained with old versions\n    (before v0.6.0) to the latest one.\n    \"\"\"\n    args = parse_args()\n    checkpoint = torch.load(args.checkpoint)\n    cfg = parse_config(checkpoint['meta']['config'])\n    # Build the model and load checkpoint\n    model = build_detector(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    orig_ckpt = checkpoint['state_dict']\n    converted_ckpt = orig_ckpt.copy()\n\n    if cfg['dataset_type'] == 'ScanNetDataset':\n        NUM_CLASSES = 18\n    elif cfg['dataset_type'] == 'SUNRGBDDataset':\n        NUM_CLASSES = 10\n    else:\n        raise NotImplementedError\n\n    RENAME_PREFIX = {\n        'bbox_head.conv_pred.0': 'bbox_head.conv_pred.shared_convs.layer0',\n        'bbox_head.conv_pred.1': 'bbox_head.conv_pred.shared_convs.layer1'\n    }\n\n    DEL_KEYS = [\n        'bbox_head.conv_pred.0.bn.num_batches_tracked',\n        'bbox_head.conv_pred.1.bn.num_batches_tracked'\n    ]\n\n    EXTRACT_KEYS = {\n        'bbox_head.conv_pred.conv_cls.weight':\n        ('bbox_head.conv_pred.conv_out.weight', [(0, 2), (-NUM_CLASSES, -1)]),\n        'bbox_head.conv_pred.conv_cls.bias':\n        ('bbox_head.conv_pred.conv_out.bias', [(0, 2), (-NUM_CLASSES, -1)]),\n        'bbox_head.conv_pred.conv_reg.weight':\n        ('bbox_head.conv_pred.conv_out.weight', [(2, -NUM_CLASSES)]),\n        'bbox_head.conv_pred.conv_reg.bias':\n        ('bbox_head.conv_pred.conv_out.bias', [(2, -NUM_CLASSES)])\n    }\n\n    # Delete some useless keys\n    for key in DEL_KEYS:\n        converted_ckpt.pop(key)\n\n    # Rename keys with specific prefix\n    RENAME_KEYS = dict()\n    for old_key in converted_ckpt.keys():\n        for rename_prefix in RENAME_PREFIX.keys():\n            if rename_prefix in old_key:\n                new_key = old_key.replace(rename_prefix,\n                                          RENAME_PREFIX[rename_prefix])\n                RENAME_KEYS[new_key] = old_key\n    for new_key, old_key in RENAME_KEYS.items():\n        converted_ckpt[new_key] = converted_ckpt.pop(old_key)\n\n    # Extract weights and rename the keys\n    for new_key, (old_key, indices) in EXTRACT_KEYS.items():\n        cur_layers = orig_ckpt[old_key]\n        converted_layers = []\n        for (start, end) in indices:\n            if end != -1:\n                converted_layers.append(cur_layers[start:end])\n            else:\n                converted_layers.append(cur_layers[start:])\n        converted_layers = torch.cat(converted_layers, 0)\n        converted_ckpt[new_key] = converted_layers\n        if old_key in converted_ckpt.keys():\n            converted_ckpt.pop(old_key)\n\n    # Check the converted checkpoint by loading to the model\n    load_state_dict(model, converted_ckpt, strict=True)\n    checkpoint['state_dict'] = converted_ckpt\n    torch.save(checkpoint, args.out)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/model_converters/publish_model.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport subprocess\nimport torch\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='Process a checkpoint to be published')\n    parser.add_argument('in_file', help='input checkpoint filename')\n    parser.add_argument('out_file', help='output checkpoint filename')\n    args = parser.parse_args()\n    return args\n\n\ndef process_checkpoint(in_file, out_file):\n    checkpoint = torch.load(in_file, map_location='cpu')\n    # remove optimizer for smaller file size\n    if 'optimizer' in checkpoint:\n        del checkpoint['optimizer']\n    # if it is necessary to remove some sensitive data in checkpoint['meta'],\n    # add the code here.\n    torch.save(checkpoint, out_file)\n    sha = subprocess.check_output(['sha256sum', out_file]).decode()\n    final_file = out_file.rstrip('.pth') + '-{}.pth'.format(sha[:8])\n    subprocess.Popen(['mv', out_file, final_file])\n\n\ndef main():\n    args = parse_args()\n    process_checkpoint(args.in_file, args.out_file)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/model_converters/regnet2mmdet.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport torch\nfrom collections import OrderedDict\n\n\ndef convert_stem(model_key, model_weight, state_dict, converted_names):\n    new_key = model_key.replace('stem.conv', 'conv1')\n    new_key = new_key.replace('stem.bn', 'bn1')\n    state_dict[new_key] = model_weight\n    converted_names.add(model_key)\n    print(f'Convert {model_key} to {new_key}')\n\n\ndef convert_head(model_key, model_weight, state_dict, converted_names):\n    new_key = model_key.replace('head.fc', 'fc')\n    state_dict[new_key] = model_weight\n    converted_names.add(model_key)\n    print(f'Convert {model_key} to {new_key}')\n\n\ndef convert_reslayer(model_key, model_weight, state_dict, converted_names):\n    split_keys = model_key.split('.')\n    layer, block, module = split_keys[:3]\n    block_id = int(block[1:])\n    layer_name = f'layer{int(layer[1:])}'\n    block_name = f'{block_id - 1}'\n\n    if block_id == 1 and module == 'bn':\n        new_key = f'{layer_name}.{block_name}.downsample.1.{split_keys[-1]}'\n    elif block_id == 1 and module == 'proj':\n        new_key = f'{layer_name}.{block_name}.downsample.0.{split_keys[-1]}'\n    elif module == 'f':\n        if split_keys[3] == 'a_bn':\n            module_name = 'bn1'\n        elif split_keys[3] == 'b_bn':\n            module_name = 'bn2'\n        elif split_keys[3] == 'c_bn':\n            module_name = 'bn3'\n        elif split_keys[3] == 'a':\n            module_name = 'conv1'\n        elif split_keys[3] == 'b':\n            module_name = 'conv2'\n        elif split_keys[3] == 'c':\n            module_name = 'conv3'\n        new_key = f'{layer_name}.{block_name}.{module_name}.{split_keys[-1]}'\n    else:\n        raise ValueError(f'Unsupported conversion of key {model_key}')\n    print(f'Convert {model_key} to {new_key}')\n    state_dict[new_key] = model_weight\n    converted_names.add(model_key)\n\n\ndef convert(src, dst):\n    \"\"\"Convert keys in pycls pretrained RegNet models to mmdet style.\"\"\"\n    # load caffe model\n    regnet_model = torch.load(src)\n    blobs = regnet_model['model_state']\n    # convert to pytorch style\n    state_dict = OrderedDict()\n    converted_names = set()\n    for key, weight in blobs.items():\n        if 'stem' in key:\n            convert_stem(key, weight, state_dict, converted_names)\n        elif 'head' in key:\n            convert_head(key, weight, state_dict, converted_names)\n        elif key.startswith('s'):\n            convert_reslayer(key, weight, state_dict, converted_names)\n\n    # check if all layers are converted\n    for key in blobs:\n        if key not in converted_names:\n            print(f'not converted: {key}')\n    # save checkpoint\n    checkpoint = dict()\n    checkpoint['state_dict'] = state_dict\n    torch.save(checkpoint, dst)\n\n\ndef main():\n    parser = argparse.ArgumentParser(description='Convert model keys')\n    parser.add_argument('src', help='src detectron model path')\n    parser.add_argument('dst', help='save path')\n    args = parser.parse_args()\n    convert(args.src, args.dst)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/test.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport argparse\nimport os\nimport torch\nimport warnings\nfrom mmcv.utils import get_dist_info, init_dist, wrap_fp16_model, set_random_seed, Config, DictAction, load_checkpoint\nfrom mmcv.models import build_model, fuse_conv_bn\nfrom torch.nn import DataParallel\nfrom torch.nn.parallel.distributed import DistributedDataParallel\n\nfrom mmcv.datasets import build_dataset, build_dataloader, replace_ImageToTensor\nimport time\nimport os.path as osp\nfrom adzoo.vad.apis.test import custom_multi_gpu_test, single_gpu_test\n\nimport warnings\nwarnings.filterwarnings(\"ignore\")\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='MMDet test (and eval) a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('checkpoint', help='checkpoint file')\n    parser.add_argument('--json_dir', help='json parent dir name file') # NOTE: json file parent folder name\n    parser.add_argument('--out', help='output result file in pickle format')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    parser.add_argument(\n        '--format-only',\n        action='store_true',\n        help='Format the output results without perform evaluation. It is'\n        'useful when you want to format the result to a specific format and '\n        'submit it to the test server')\n    parser.add_argument(\n        '--eval',\n        type=str,\n        nargs='+',\n        help='evaluation metrics, which depends on the dataset, e.g., \"bbox\",'\n        ' \"segm\", \"proposal\" for COCO, and \"mAP\", \"recall\" for PASCAL VOC')\n    parser.add_argument('--show', action='store_true', help='show results')\n    parser.add_argument(\n        '--show-dir', help='directory where results will be saved')\n    parser.add_argument(\n        '--gpu-collect',\n        action='store_true',\n        help='whether to use gpu to collect results.')\n    parser.add_argument(\n        '--tmpdir',\n        help='tmp directory used for collecting results from multiple '\n        'workers, available when gpu-collect is not specified')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    parser.add_argument(\n        '--options',\n        nargs='+',\n        action=DictAction,\n        help='custom options for evaluation, the key-value pair in xxx=yyy '\n        'format will be kwargs for dataset.evaluate() function (deprecate), '\n        'change to --eval-options instead.')\n    parser.add_argument(\n        '--eval-options',\n        nargs='+',\n        action=DictAction,\n        help='custom options for evaluation, the key-value pair in xxx=yyy '\n        'format will be kwargs for dataset.evaluate() function')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local_rank', type=int, default=0)\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    if args.options and args.eval_options:\n        raise ValueError(\n            '--options and --eval-options cannot be both specified, '\n            '--options is deprecated in favor of --eval-options')\n    if args.options:\n        warnings.warn('--options is deprecated in favor of --eval-options')\n        args.eval_options = args.options\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    assert args.out or args.eval or args.format_only or args.show \\\n        or args.show_dir, \\\n        ('Please specify at least one operation (save/eval/format/show the '\n         'results / save the results) with the argument \"--out\", \"--eval\"'\n         ', \"--format-only\", \"--show\" or \"--show-dir\"')\n\n    if args.eval and args.format_only:\n        raise ValueError('--eval and --format_only cannot be both specified')\n\n    if args.out is not None and not args.out.endswith(('.pkl', '.pickle')):\n        raise ValueError('The output file must be a pkl file.')\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n\n    # import modules from plguin/xx, registry will be updated\n    # if hasattr(cfg, 'plugin'):\n    #     if cfg.plugin:\n    #         import importlib\n    #         if hasattr(cfg, 'plugin_dir'):\n    #             plugin_dir = cfg.plugin_dir\n    #             _module_dir = os.path.dirname(plugin_dir)\n    #             _module_dir = _module_dir.split('/')\n    #             _module_path = _module_dir[0]\n\n    #             for m in _module_dir[1:]:\n    #                 _module_path = _module_path + '.' + m\n    #             print(_module_path)\n    #             plg_lib = importlib.import_module(_module_path)\n    #         else:\n    #             # import dir is the dirpath for the config file\n    #             _module_dir = os.path.dirname(args.config)\n    #             _module_dir = _module_dir.split('/')\n    #             _module_path = _module_dir[0]\n    #             for m in _module_dir[1:]:\n    #                 _module_path = _module_path + '.' + m\n    #             print(_module_path)\n    #             plg_lib = importlib.import_module(_module_path)\n\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    \n    if cfg.get('close_tf32', False):\n        torch.backends.cuda.matmul.allow_tf32 = False\n        torch.backends.cudnn.allow_tf32 = False\n\n    cfg.model.pretrained = None\n    # in case the test dataset is concatenated\n    samples_per_gpu = 1\n    if isinstance(cfg.data.test, dict):\n        cfg.data.test.test_mode = True\n        samples_per_gpu = cfg.data.test.pop('samples_per_gpu', 1)\n        if samples_per_gpu > 1:\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.test.pipeline = replace_ImageToTensor(\n                cfg.data.test.pipeline)\n    elif isinstance(cfg.data.test, list):\n        for ds_cfg in cfg.data.test:\n            ds_cfg.test_mode = True\n        samples_per_gpu = max(\n            [ds_cfg.pop('samples_per_gpu', 1) for ds_cfg in cfg.data.test])\n        if samples_per_gpu > 1:\n            for ds_cfg in cfg.data.test:\n                ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n\n    # set random seeds\n    if args.seed is not None:\n        set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # build the dataloader\n    dataset = build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=samples_per_gpu,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=distributed,\n        shuffle=False,\n        nonshuffler_sampler=cfg.data.nonshuffler_sampler,\n    )\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_model(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    checkpoint = load_checkpoint(model, args.checkpoint, map_location='cpu')\n    if args.fuse_conv_bn:\n        model = fuse_conv_bn(model)\n    # old versions did not save class info in checkpoints, this walkaround is\n    # for backward compatibility\n    if 'CLASSES' in checkpoint.get('meta', {}):\n        model.CLASSES = checkpoint['meta']['CLASSES']\n    else:\n        model.CLASSES = dataset.CLASSES\n    # palette for visualization in segmentation tasks\n    if 'PALETTE' in checkpoint.get('meta', {}):\n        model.PALETTE = checkpoint['meta']['PALETTE']\n    elif hasattr(dataset, 'PALETTE'):\n        # segmentation dataset has `PALETTE` attribute\n        model.PALETTE = dataset.PALETTE\n\n    if not distributed:\n        model = DataParallel(model, device_ids=[0])\n        outputs = single_gpu_test(model, data_loader)\n    else:\n        model = DistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False)\n        outputs = custom_multi_gpu_test(model, data_loader, args.tmpdir,\n                                        args.gpu_collect)\n\n\n\n    rank, _ = get_dist_info()\n    if rank == 0:\n        if args.out:\n            print(f'\\nwriting results to {args.out}')\n        kwargs = {} if args.eval_options is None else args.eval_options\n        kwargs['jsonfile_prefix'] = osp.join('test', args.config.split(\n            '/')[-1].split('.')[-2], time.ctime().replace(' ', '_').replace(':', '_'))\n        if args.format_only:\n            dataset.format_results(outputs, **kwargs)\n\n        if args.eval:\n            eval_kwargs = cfg.get('evaluation', {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                    'interval', 'tmpdir', 'start', 'gpu_collect', 'save_best',\n                    'rule'\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(dict(metric=args.eval, **kwargs))\n\n            print(dataset.evaluate(outputs['bbox_results'], **eval_kwargs))\n    \n        # # # NOTE: record to json\n        # json_path = args.json_dir\n        # if not os.path.exists(json_path):\n        #     os.makedirs(json_path)\n        \n        # metric_all = []\n        # for res in outputs['bbox_results']:\n        #     for k in res['metric_results'].keys():\n        #         if type(res['metric_results'][k]) is np.ndarray:\n        #             res['metric_results'][k] = res['metric_results'][k].tolist()\n        #     metric_all.append(res['metric_results'])\n        \n        # print('start saving to json done')\n        # with open(json_path+'/metric_record.json', \"w\", encoding=\"utf-8\") as f2:\n        #     json.dump(metric_all, f2, indent=4)\n        # print('save to json done')\n\nif __name__ == '__main__':\n    main()"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n \nfrom __future__ import division\n\nimport argparse\nimport copy\nimport mmcv\nimport os\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.utils import get_dist_info, init_dist\nfrom os import path as osp\n\n\nfrom mmcv.datasets import build_dataset\nfrom mmcv.models import build_model\nfrom mmcv.utils import collect_env, get_root_logger\nfrom mmcv.utils import set_random_seed\n\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom adzoo.bevformer.mmdet3d_plugin.bevformer.apis.train import custom_train_model\n\nimport cv2\ncv2.setNumThreads(1)\n\nimport sys\nsys.path.append('')\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Train a detector')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument('--work-dir', help='the dir to save logs and models')\n    parser.add_argument(\n        '--resume-from', help='the checkpoint file to resume from')\n    parser.add_argument(\n        '--no-validate',\n        action='store_true',\n        help='whether not to evaluate the checkpoint during training')\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        '--gpus',\n        type=int,\n        help='number of gpus to use '\n        '(only applicable to non-distributed training)')\n    group_gpus.add_argument(\n        '--gpu-ids',\n        type=int,\n        nargs='+',\n        help='ids of gpus to use '\n        '(only applicable to non-distributed training)')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file (deprecate), '\n        'change to --cfg-options instead.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local_rank', type=int, default=0)\n    parser.add_argument(\n        '--autoscale-lr',\n        action='store_true',\n        help='automatically scale lr with the number of gpus')\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            '--options and --cfg-options cannot be both specified, '\n            '--options is deprecated in favor of --cfg-options')\n    if args.options:\n        warnings.warn('--options is deprecated in favor of --cfg-options')\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    # set tf32\n    if cfg.get('close_tf32', False):\n        torch.backends.cuda.matmul.allow_tf32 = False\n        torch.backends.cudnn.allow_tf32 = False\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0])\n    # if args.resume_from is not None:\n    if args.resume_from is not None and osp.isfile(args.resume_from):\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n    if digit_version(TORCH_VERSION) == digit_version('1.8.1') and cfg.optimizer['type'] == 'AdamW':\n        cfg.optimizer['type'] = 'AdamW2' # fix bug in Adamw\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer['lr'] = cfg.optimizer['lr'] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        #import pdb;pdb.set_trace()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime())\n    log_file = osp.join(cfg.work_dir, f'{timestamp}.log')\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    if cfg.model.type in ['EncoderDecoder3D']:\n        logger_name = 'mmseg'\n    else:\n        logger_name = 'mmdet'\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level, name=logger_name)\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = '\\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()])\n    dash_line = '-' * 60 + '\\n'\n    logger.info('Environment info:\\n' + dash_line + env_info + '\\n' +\n                dash_line)\n    meta['env_info'] = env_info\n    meta['config'] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f'Distributed training: {distributed}')\n    logger.info(f'Config:\\n{cfg.pretty_text}')\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(f'Set random seed to {args.seed}, '\n                    f'deterministic: {args.deterministic}')\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta['seed'] = args.seed\n    meta['exp_name'] = osp.basename(args.config)\n\n    model = build_model(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    model.init_weights()\n\n    logger.info(f'Model:\\n{model}')\n    datasets = [build_dataset(cfg.data.train)]\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if 'dataset' in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n            PALETTE=datasets[0].PALETTE  # for segmentors\n            if hasattr(datasets[0], 'PALETTE') else None)\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    custom_train_model(\n        model,\n        datasets,\n        cfg,\n        distributed=distributed,\n        validate=(not args.no_validate),\n        timestamp=timestamp,\n        meta=meta)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/adzoo/vad/train_momad.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n \nfrom __future__ import division\n\nimport argparse\nimport copy\nimport mmcv\nimport os\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.utils import get_dist_info, init_dist\nfrom os import path as osp\n\n\nfrom mmcv.datasets import build_dataset\nfrom mmcv.models import build_model\nfrom mmcv.utils import collect_env, get_root_logger\nfrom mmcv.utils import set_random_seed\n\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom adzoo.bevformer.mmdet3d_plugin.bevformer.apis.train import custom_train_model\n\nimport cv2\ncv2.setNumThreads(1)\n\nimport sys\nsys.path.append('')\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='Train a detector')\n    parser.add_argument('config', help='train config file path')\n    parser.add_argument('--work-dir', help='the dir to save logs and models')\n    parser.add_argument(\n        '--resume-from', \n        #default=\"./work_dirs/MomAD_base_e2e_b2d/latest.pth\",\n        help='the checkpoint file to resume from')\n    parser.add_argument(\n        '--no-validate',\n        action='store_true',\n        help='whether not to evaluate the checkpoint during training')\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        '--gpus',\n        type=int,\n        help='number of gpus to use '\n        '(only applicable to non-distributed training)')\n    group_gpus.add_argument(\n        '--gpu-ids',\n        type=int,\n        nargs='+',\n        help='ids of gpus to use '\n        '(only applicable to non-distributed training)')\n    parser.add_argument('--seed', type=int, default=0, help='random seed')\n    parser.add_argument(\n        '--deterministic',\n        action='store_true',\n        help='whether to set deterministic options for CUDNN backend.')\n    parser.add_argument(\n        '--options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file (deprecate), '\n        'change to --cfg-options instead.')\n    parser.add_argument(\n        '--cfg-options',\n        nargs='+',\n        action=DictAction,\n        help='override some settings in the used config, the key-value pair '\n        'in xxx=yyy format will be merged into config file. If the value to '\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        'Note that the quotation marks are necessary and that no white space '\n        'is allowed.')\n    parser.add_argument(\n        '--launcher',\n        choices=['none', 'pytorch', 'slurm', 'mpi'],\n        default='none',\n        help='job launcher')\n    parser.add_argument('--local_rank', type=int, default=0)\n    parser.add_argument(\n        '--autoscale-lr',\n        action='store_true',\n        help='automatically scale lr with the number of gpus')\n    args = parser.parse_args()\n    if 'LOCAL_RANK' not in os.environ:\n        os.environ['LOCAL_RANK'] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            '--options and --cfg-options cannot be both specified, '\n            '--options is deprecated in favor of --cfg-options')\n    if args.options:\n        warnings.warn('--options is deprecated in favor of --cfg-options')\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get('custom_imports', None):\n        from mmcv.utils import import_modules_from_strings\n        import_modules_from_strings(**cfg['custom_imports'])\n\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    # set tf32\n    if cfg.get('close_tf32', False):\n        torch.backends.cuda.matmul.allow_tf32 = False\n        torch.backends.cudnn.allow_tf32 = False\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0])\n    # if args.resume_from is not None:\n    if args.resume_from is not None and osp.isfile(args.resume_from):\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(1, args.gpus+1)\n    if digit_version(TORCH_VERSION) == digit_version('1.8.1') and cfg.optimizer['type'] == 'AdamW':\n        cfg.optimizer['type'] = 'AdamW2' # fix bug in Adamw\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer['lr'] = cfg.optimizer['lr'] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == 'none':\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        #import pdb;pdb.set_trace()\n        #cfg.gpu_ids = [2,3,4,5,6,7]\n        #import pdb;pdb.set_trace()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime())\n    log_file = osp.join(cfg.work_dir, f'{timestamp}.log')\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    if cfg.model.type in ['EncoderDecoder3D']:\n        logger_name = 'mmseg'\n    else:\n        logger_name = 'mmdet'\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level, name=logger_name)\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = '\\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()])\n    dash_line = '-' * 60 + '\\n'\n    logger.info('Environment info:\\n' + dash_line + env_info + '\\n' +\n                dash_line)\n    meta['env_info'] = env_info\n    meta['config'] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f'Distributed training: {distributed}')\n    logger.info(f'Config:\\n{cfg.pretty_text}')\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(f'Set random seed to {args.seed}, '\n                    f'deterministic: {args.deterministic}')\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta['seed'] = args.seed\n    meta['exp_name'] = osp.basename(args.config)\n\n    model = build_model(\n        cfg.model,\n        train_cfg=cfg.get('train_cfg'),\n        test_cfg=cfg.get('test_cfg'))\n    model.init_weights()\n\n    logger.info(f'Model:\\n{model}')\n    datasets = [build_dataset(cfg.data.train)]\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if 'dataset' in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n            PALETTE=datasets[0].PALETTE  # for segmentors\n            if hasattr(datasets[0], 'PALETTE') else None)\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    custom_train_model(\n        model,\n        datasets,\n        cfg,\n        distributed=distributed,\n        validate=(not args.no_validate),\n        timestamp=timestamp,\n        meta=meta)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/docs/CONVERT_GUIDE.md",
    "content": "# Code Convert Guide\n\nThis document outlines important considerations for migrating code based on nuscenes or other datasets to bench2drive.\n\n## Models\n\nWe integrated several MMCV dependencies into the `mmcv` directory and no longer install the original libraries. You can refer to our existing methods to utilize these modules and place your own models and utils in `mmcv` directory and register them. Please make sure the mmcv directory contains all the modules you need; if not, you will need to add them.\n\n## Scripts and configs\n\nYou can place the configs and scripts for each method in the `adzoo` . Utils of each methods can also be placed here for easier management.\n\n## Details of configs\n\nTo create a config for the bench2drive dataset, note the following:\n\n- We have included the bench2drive name-to-class mapping and evaluation settings directly in the config. You can use our settings or modify them as needed.\n- Unlike the 10 classes in nuscenes, we use 9 classes in bench2drive .\n- Methods like UniAD and VAD use 3 commands on nuscenes, while bench2drive uses 6 commands obtained from CARLA.\n\n## Dataset\n\n- The coordinate system of the Bench2Drive data differs significantly from the coordinate system used by BEVFormer/UniAD/VAD.([here](https://github.com/Thinklab-SJTU/Bench2Drive/blob/main/docs/anno.md) for details). In `mmcv/datasets/prepare_B2D.py`, we convert the world coordinate system, ego coordinate system, and sensor coordinate system to match their coordinate system, including the vehicle coordinates, bounding box coordinates, and sensor extrinsics. You can refer to our code for data alignment. \n- In Nuscenes, keyframes are at 2Hz, while Bench2Drive runs at 10Hz with annotations for each frame. For reproducing UniAD and VAD, we set the window length (time interval between adjacent points in past and future trajectories) to 0.5s and the window shift to 0.1s (any frame can be selected as the current frame). This fully utilizes Bench2Drive's data and aligns the trajectories with Nuscenes.\n- For the map, Bench2Drive stores vectorized maps.  You can refer to our code to use the map, such as extracting map elements within a certain range.\n\n## Team agent\n\nTo perform closed-loop evaluation in CARLA, set up sensors to gather data from CARLA. Use this data to compute all necessary model inputs, then convert the model outputs into a `carla.VehicleControl` object.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/docs/DATA_PREP.md",
    "content": "# Prepare Bench2Drive Dataset\n\n## Download Bench2Drive\n\nDownload our dataset from ([LINK](https://github.com/Thinklab-SJTU/Bench2Drive)) and make sure the structure of data as follows:\n\n**Notice: some version of data may have slightly different folder structure. You may need to use soft link (ln -s) and change the path related code.**\n\n```\n    Bench2DriveZoo\n    ├── ...                   \n    ├── data/\n    |   ├── bench2drive/\n    |   |   ├── v1/                                          # Bench2Drive base \n    |   |   |   ├── Accident_Town03_Route101_Weather23/\n    |   |   |   ├── Accident_Town03_Route102_Weather20/\n    |   |   |   └── ...\n    |   |   └── maps/                                        # maps of Towns\n    |   |       ├── Town01_HD_map.npz\n    |   |       ├── Town02_HD_map.npz\n    |   |       └── ...\n    |   ├── others\n    |   |       └── b2d_motion_anchor_infos_mode6.pkl        # motion anchors for UniAD\n    |   └── splits\n    |           └── bench2drive_base_train_val_split.json    # trainval_split of Bench2Drive base \n\n```\n\n## Prepare Bench2Drive data info\n\nRun the following command:\n\n```\ncd mmcv/datasets\npython prepare_B2D.py --workers 16   # workers used to prepare data\n```\n\nThe command will generate `b2d_infos_train.pkl`, `b2d_infos_val.pkl`, `b2d_map_infos.pkl` under `data/infos`.\n\n*Note: This command will be by default use all routes except those in data/splits/bench2drive_base_train_val_split.json as the training set.  It will take about 1 hour to generate all the data with 16 workers for Base set (1000 clips).*\n\n\n## Structure of code\n\n\nAfter installing and data preparing, the structure of our code will be as follows:\n\n```\n    Bench2DriveZoo\n    ├── adzoo/\n    |   ├── bevformer/\n    |   ├── uniad/\n    |   └── vad/                   \n    ├── ckpts/\n    |   ├── r101_dcn_fcos3d_pretrain.pth                   # pretrain weights for bevformer\n    |   ├── resnet50-19c8e357.pth                          # image backbone pretrain weights for vad\n    |   ├── bevformer_base_b2d.pth                         # download weights you need\n    |   ├── uniad_base_b2d.pth                             # download weights you need\n    |   └── ...\n    ├── data/\n    |   ├── bench2drive/\n    |   |   ├── v1/                                        # Bench2Drive base \n    |   |   |   ├── Accident_Town03_Route101_Weather23/\n    |   |   |   ├── Accident_Town03_Route102_Weather20/\n    |   |   |   └── ...\n    |   |   └── maps/                                      # maps of Towns\n    |   |       ├── Town01_HD_map.npz\n    |   |       ├── Town02_HD_map.npz\n    |   |       └── ...\n    │   ├── infos/\n    │   │   ├── b2d_infos_train.pkl\n    │   │   ├── b2d_infos_val.pkl\n    |   |   └── b2d_map_infos.pkl\n    |   ├── others\n    |   |       └── b2d_motion_anchor_infos_mode6.pkl      # motion anchors for UniAD\n    |   └── splits\n    |           └── bench2drive_base_train_val_split.json  # trainval_split of Bench2Drive base \n    ├── docs/\n    ├── mmcv/\n    ├── team_code/  # for Closed-loop Evaluation in CARLA\n```\n\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/docs/EVAL_IN_CARLA.md",
    "content": "# Closed Loop Evaluation    \n\nPlease follow these steps to evaluate UniAD and VAD in CARLA:\n\n## Preparations\n\n- Install this repo as [doc](./INSTALL.md). \n- Clone Bench2Drive evaluation tools from [here](https://github.com/Thinklab-SJTU/Bench2Drive) and prepare CARLA For it.\n\n## Link this repo to Bench2Drive\n\n```bash\n# Add your agent code\ncd Bench2Drive/leaderboard\nmkdir team_code\nln -s Bench2DriveZoo/team_code/* ./team_code    # link UniAD,VAD agents and utils \ncd ..\nln -s Bench2DriveZoo  ./                        # link entire repo to Bench2Drive. \n```\n\n## Run evaluation \n\nFollow [this](https://github.com/Thinklab-SJTU/Bench2Drive?tab=readme-ov-file#eval-tools) to use evaluation tools of Bench2Drive.\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/docs/INSTALL.md",
    "content": "## Follow these steps to install the environment\n- **STEP 1: Create environment**\n    ```\n    ## python3.8 should be strictly followed.\n    conda create -n b2d_zoo python=3.8\n    conda activate b2d_zoo\n    ```\n- **STEP 2: Install cudatoolkit**\n    ```\n    conda install -c \"nvidia/label/cuda-11.8.0\" cuda-toolkit\n    ```\n- **STEP 3: Install torch**\n    ```\n    pip install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118\n    ```\n- **STEP 4: Set environment variables**\n    ```\n    # cuda 11.8 and GCC 9.4 is strongly recommended. Otherwise, it might encounter errors.\n    export PATH=YOUR_GCC_PATH/bin:$PATH\n    export CUDA_HOME=YOUR_CUDA_PATH/\n    ```\n- **STEP 5: Install ninja and packaging**\n    ```\n    pip install ninja packaging\n    ```\n- **STEP 6: Install our repo**\n    ```\n    pip install -v -e .\n    ```\n\n- **STEP 7: Prepare pretrained weights.**\n    create directory `ckpts`\n\n    ```\n    mkdir ckpts \n    ```\n    Download `resnet50-19c8e357.pth` form [Hugging Face](https://huggingface.co/rethinklab/Bench2DriveZoo/blob/main/resnet50-19c8e357.pth) or [Baidu Cloud](https://pan.baidu.com/s/1LlSrbYvghnv3lOlX1uLU5g?pwd=1234 ) or from Pytorch official website.\n  \n    Download `r101_dcn_fcos3d_pretrain.pth` form [Hugging Face](https://huggingface.co/rethinklab/Bench2DriveZoo/blob/main/r101_dcn_fcos3d_pretrain.pth) or [Baidu Cloud](https://pan.baidu.com/s/1o7owaQ5G66xqq2S0TldwXQ?pwd=1234) or from BEVFormer official repo.\n\n\n- **STEP 8: Install CARLA for closed-loop evaluation.**\n\n    ```\n    ## Ignore the line about downloading and extracting CARLA if you have already done so.\n    mkdir carla\n    cd carla\n    wget https://carla-releases.s3.us-east-005.backblazeb2.com/Linux/CARLA_0.9.15.tar.gz\n    tar -xvf CARLA_0.9.15.tar.gz\n    cd Import && wget https://carla-releases.s3.us-east-005.backblazeb2.com/Linux/AdditionalMaps_0.9.15.tar.gz\n    cd .. && bash ImportAssets.sh\n    export CARLA_ROOT=YOUR_CARLA_PATH\n\n    ## Important!!! Otherwise, the python environment can not find carla package\n    echo \"$CARLA_ROOT/PythonAPI/carla/dist/carla-0.9.15-py3.7-linux-x86_64.egg\" >> YOUR_CONDA_PATH/envs/YOUR_CONDA_ENV_NAME/lib/python3.7/site-packages/carla.pth # python 3.8 also works well, please set YOUR_CONDA_PATH and YOUR_CONDA_ENV_NAME\n\n    ```\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/docs/TRAIN_EVAL.md",
    "content": "# Train/Eval models\n\nYou can use following commands to train and validate [BEVFormer](https://github.com/fundamentalvision/BEVFormer), [UniAD](https://github.com/OpenDriveLab/UniAD) and [VAD](https://github.com/hustvl/VAD)\n\n## BEVFormer\n\n### Train \n\n```bash\n#train BEVFormer base\n./adzoo/bevformer/dist_train.sh ./adzoo/bevformer/configs/bevformer/bevformer_base_b2d.py 4 #N_GPUS\n#train BEVFormer tiny\n./adzoo/bevformer/dist_train.sh ./adzoo/bevformer/configs/bevformer/bevformer_tiny_b2d.py 4 #N_GPUS\n```\n### Open loop eval \n\n```bash\n#eval BEVFormer base\n./adzoo/bevformer/dist_test.sh ./adzoo/bevformer/configs/bevformer/bevformer_base_b2d.py ./ckpts/bevformer_base_b2d.pth 1 \n#test BEVFormerr tiny\n./adzoo/bevformer/dist_test.sh ./adzoo/bevformer/configs/bevformer/bevformer_tiny_b2d.py ./ckpts/bevformer_tiny_b2d.pth 1 \n```\n\n\n## UniAD\n\n### Train stage1\n```bash\n#train UniAD base\n./adzoo/uniad/uniad_dist_train.sh  ./adzoo/uniad/configs/stage1_track_map/base_track_map_b2d.py 4 \n#train UniAD tiny\n./adzoo/uniad/uniad_dist_train.sh  ./adzoo/uniad/configs/stage1_track_map/tiny_track_map_b2d.py 4 \n```\n\n### Train stage2\n```bash\n#train UniAD base\n./adzoo/uniad/uniad_dist_train.sh  ./adzoo/uniad/configs/stage2_e2e/base_e2e_b2d.py 1 \n#train UniAD tiny\n./adzoo/uniad/uniad_dist_train.sh  ./adzoo/uniad/configs/stage2_e2e/tiny_e2e_b2d.py 1 \n```\n\n\n### Open loop eval\n\n```bash\n#eval UniAD base\n./adzoo/uniad/uniad_dist_eval.sh ./adzoo/uniad/configs/stage2_e2e/base_e2e_b2d.py ./ckpts/uniad_base_b2d.pth 1\n#eval UniAD tiny\n./adzoo/uniad/uniad_dist_eval.sh ./adzoo/uniad/configs/stage2_e2e/tiny_e2e_b2d.py ./ckpts/uniad_tiny_b2d.pth 1\n```\n\n\n## VAD\n\n### Train \n\n```bash\n./adzoo/vad/dist_train.sh ./adzoo/vad/configs/VAD/VAD_base_e2e_b2d.py ./ckpts/vad_b2d_base.pth 1\n```\n\n### Open loop eval\n\n```bash\n./adzoo/vad/dist_test.sh ./adzoo/vad/configs/VAD/VAD_base_e2e_b2d.py ./ckpts/vad_b2d_base.pth 1\n```\n\n**NOTE**: UniAD and VAD use different definitions to calculate Planning L2. UniAD calculates L2 at each time step(0.5s,1.0s,1.5s,...), while VAD calculates the average over each time period(0s-0.5s,0s-1.0s,0s-1.5s,...). We retain the original calculation logic in the code, but report UniAD's Planning L2 converted to VAD's definition.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n# flake8: noqa\n__version__ = '0.0.1'\n\nfrom .fileio import *\nfrom .image import *\nfrom .utils import *\nfrom .core.bbox.coder.nms_free_coder import NMSFreeCoder\nfrom .core.bbox.match_costs import BBox3DL1Cost, DiceCost \nfrom .core.evaluation.eval_hooks import CustomDistEvalHook\nfrom .models.utils import *\nfrom .models.opt.adamw import AdamW2\nfrom .losses import *\nfrom .structures import Instances, BoxMode, Boxes\nfrom .layers import cat, Conv2d, batched_nms, get_norm"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/__init__.py",
    "content": "from .anchor import *  # noqa: F401, F403\nfrom .bbox import *  # noqa: F401, F403\nfrom .evaluation import *  # noqa: F401, F403\nfrom .points import *  # noqa: F401, F403\nfrom .mask import *  # noqa: F401, F403\nfrom .post_processing import *  # noqa: F401, F403\nfrom .utils import *  # noqa: F401, F403\n# from .seg import *  # noqa: F401, F403\nfrom .visualizer import *  # noqa: F401, F403\nfrom .voxel import *  # noqa: F401, F403\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/anchor/__init__.py",
    "content": "from .anchor_generator import (AnchorGenerator, LegacyAnchorGenerator,\n                               YOLOAnchorGenerator)\nfrom .builder import (ANCHOR_GENERATORS, PRIOR_GENERATORS,\n                      build_anchor_generator, build_prior_generator)\nfrom .point_generator import MlvlPointGenerator, PointGenerator\nfrom .utils import anchor_inside_flags, calc_region, images_to_levels\nfrom .anchor_3d_generator import (AlignedAnchor3DRangeGenerator,\n                                  AlignedAnchor3DRangeGeneratorPerCls,\n                                  Anchor3DRangeGenerator)\n\n__all__ = [\n    'AnchorGenerator', 'LegacyAnchorGenerator', 'anchor_inside_flags',\n    'PointGenerator', 'images_to_levels', 'calc_region',\n    'build_anchor_generator', 'ANCHOR_GENERATORS', 'YOLOAnchorGenerator',\n    'build_prior_generator', 'PRIOR_GENERATORS', 'MlvlPointGenerator',\n    'AlignedAnchor3DRangeGenerator', 'Anchor3DRangeGenerator',\n    'AlignedAnchor3DRangeGeneratorPerCls'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/anchor/anchor_3d_generator.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom mmcv.core.anchor import ANCHOR_GENERATORS\nfrom mmcv.utils import is_list_of\n\n\n@ANCHOR_GENERATORS.register_module()\nclass Anchor3DRangeGenerator(object):\n    \"\"\"3D Anchor Generator by range.\n\n    This anchor generator generates anchors by the given range in different\n    feature levels.\n    Due the convention in 3D detection, different anchor sizes are related to\n    different ranges for different categories. However we find this setting\n    does not effect the performance much in some datasets, e.g., nuScenes.\n\n    Args:\n        ranges (list[list[float]]): Ranges of different anchors.\n            The ranges are the same across different feature levels. But may\n            vary for different anchor sizes if size_per_range is True.\n        sizes (list[list[float]]): 3D sizes of anchors.\n        scales (list[int]): Scales of anchors in different feature levels.\n        rotations (list[float]): Rotations of anchors in a feature grid.\n        custom_values (tuple[float]): Customized values of that anchor. For\n            example, in nuScenes the anchors have velocities.\n        reshape_out (bool): Whether to reshape the output into (N x 4).\n        size_per_range: Whether to use separate ranges for different sizes.\n            If size_per_range is True, the ranges should have the same length\n            as the sizes, if not, it will be duplicated.\n    \"\"\"\n\n    def __init__(self,\n                 ranges,\n                 sizes=[[1.6, 3.9, 1.56]],\n                 scales=[1],\n                 rotations=[0, 1.5707963],\n                 custom_values=(),\n                 reshape_out=True,\n                 size_per_range=True):\n        assert is_list_of(ranges, list)\n        if size_per_range:\n            if len(sizes) != len(ranges):\n                assert len(ranges) == 1\n                ranges = ranges * len(sizes)\n            assert len(ranges) == len(sizes)\n        else:\n            assert len(ranges) == 1\n        assert is_list_of(sizes, list)\n        assert isinstance(scales, list)\n\n        self.sizes = sizes\n        self.scales = scales\n        self.ranges = ranges\n        self.rotations = rotations\n        self.custom_values = custom_values\n        self.cached_anchors = None\n        self.reshape_out = reshape_out\n        self.size_per_range = size_per_range\n\n    def __repr__(self):\n        s = self.__class__.__name__ + '('\n        s += f'anchor_range={self.ranges},\\n'\n        s += f'scales={self.scales},\\n'\n        s += f'sizes={self.sizes},\\n'\n        s += f'rotations={self.rotations},\\n'\n        s += f'reshape_out={self.reshape_out},\\n'\n        s += f'size_per_range={self.size_per_range})'\n        return s\n\n    @property\n    def num_base_anchors(self):\n        \"\"\"list[int]: Total number of base anchors in a feature grid.\"\"\"\n        num_rot = len(self.rotations)\n        num_size = torch.tensor(self.sizes).reshape(-1, 3).size(0)\n        return num_rot * num_size\n\n    @property\n    def num_levels(self):\n        \"\"\"int: Number of feature levels that the generator is applied to.\"\"\"\n        return len(self.scales)\n\n    def grid_anchors(self, featmap_sizes, device='cuda'):\n        \"\"\"Generate grid anchors in multiple feature levels.\n\n        Args:\n            featmap_sizes (list[tuple]): List of feature map sizes in\n                multiple feature levels.\n            device (str): Device where the anchors will be put on.\n\n        Returns:\n            list[torch.Tensor]: Anchors in multiple feature levels. \\\n                The sizes of each tensor should be [N, 4], where \\\n                N = width * height * num_base_anchors, width and height \\\n                are the sizes of the corresponding feature lavel, \\\n                num_base_anchors is the number of anchors for that level.\n        \"\"\"\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_anchors = []\n        for i in range(self.num_levels):\n            anchors = self.single_level_grid_anchors(\n                featmap_sizes[i], self.scales[i], device=device)\n            if self.reshape_out:\n                anchors = anchors.reshape(-1, anchors.size(-1))\n            multi_level_anchors.append(anchors)\n        return multi_level_anchors\n\n    def single_level_grid_anchors(self, featmap_size, scale, device='cuda'):\n        \"\"\"Generate grid anchors of a single level feature map.\n\n        This function is usually called by method ``self.grid_anchors``.\n\n        Args:\n            featmap_size (tuple[int]): Size of the feature map.\n            scale (float): Scale factor of the anchors in the current level.\n            device (str, optional): Device the tensor will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: Anchors in the overall feature map.\n        \"\"\"\n        # We reimplement the anchor generator using torch in cuda\n        # torch: 0.6975 s for 1000 times\n        # numpy: 4.3345 s for 1000 times\n        # which is ~5 times faster than the numpy implementation\n        if not self.size_per_range:\n            return self.anchors_single_range(\n                featmap_size,\n                self.ranges[0],\n                scale,\n                self.sizes,\n                self.rotations,\n                device=device)\n\n        mr_anchors = []\n        for anchor_range, anchor_size in zip(self.ranges, self.sizes):\n            mr_anchors.append(\n                self.anchors_single_range(\n                    featmap_size,\n                    anchor_range,\n                    scale,\n                    anchor_size,\n                    self.rotations,\n                    device=device))\n        mr_anchors = torch.cat(mr_anchors, dim=-3)\n        return mr_anchors\n\n    def anchors_single_range(self,\n                             feature_size,\n                             anchor_range,\n                             scale=1,\n                             sizes=[[1.6, 3.9, 1.56]],\n                             rotations=[0, 1.5707963],\n                             device='cuda'):\n        \"\"\"Generate anchors in a single range.\n\n        Args:\n            feature_size (list[float] | tuple[float]): Feature map size. It is\n                either a list of a tuple of [D, H, W](in order of z, y, and x).\n            anchor_range (torch.Tensor | list[float]): Range of anchors with\n                shape [6]. The order is consistent with that of anchors, i.e.,\n                (x_min, y_min, z_min, x_max, y_max, z_max).\n            scale (float | int, optional): The scale factor of anchors.\n            sizes (list[list] | np.ndarray | torch.Tensor): Anchor size with\n                shape [N, 3], in order of x, y, z.\n            rotations (list[float] | np.ndarray | torch.Tensor): Rotations of\n                anchors in a single feature grid.\n            device (str): Devices that the anchors will be put on.\n\n        Returns:\n            torch.Tensor: Anchors with shape \\\n                [*feature_size, num_sizes, num_rots, 7].\n        \"\"\"\n        if len(feature_size) == 2:\n            feature_size = [1, feature_size[0], feature_size[1]]\n        anchor_range = torch.tensor(anchor_range, device=device)\n        z_centers = torch.linspace(\n            anchor_range[2], anchor_range[5], feature_size[0], device=device)\n        y_centers = torch.linspace(\n            anchor_range[1], anchor_range[4], feature_size[1], device=device)\n        x_centers = torch.linspace(\n            anchor_range[0], anchor_range[3], feature_size[2], device=device)\n        sizes = torch.tensor(sizes, device=device).reshape(-1, 3) * scale\n        rotations = torch.tensor(rotations, device=device)\n\n        # torch.meshgrid default behavior is 'id', np's default is 'xy'\n        rets = torch.meshgrid(x_centers, y_centers, z_centers, rotations)\n        # torch.meshgrid returns a tuple rather than list\n        rets = list(rets)\n        tile_shape = [1] * 5\n        tile_shape[-2] = int(sizes.shape[0])\n        for i in range(len(rets)):\n            rets[i] = rets[i].unsqueeze(-2).repeat(tile_shape).unsqueeze(-1)\n\n        sizes = sizes.reshape([1, 1, 1, -1, 1, 3])\n        tile_size_shape = list(rets[0].shape)\n        tile_size_shape[3] = 1\n        sizes = sizes.repeat(tile_size_shape)\n        rets.insert(3, sizes)\n\n        ret = torch.cat(rets, dim=-1).permute([2, 1, 0, 3, 4, 5])\n        # [1, 200, 176, N, 2, 7] for kitti after permute\n\n        if len(self.custom_values) > 0:\n            custom_ndim = len(self.custom_values)\n            custom = ret.new_zeros([*ret.shape[:-1], custom_ndim])\n            # custom[:] = self.custom_values\n            ret = torch.cat([ret, custom], dim=-1)\n            # [1, 200, 176, N, 2, 9] for nus dataset after permute\n        return ret\n\n\n@ANCHOR_GENERATORS.register_module()\nclass AlignedAnchor3DRangeGenerator(Anchor3DRangeGenerator):\n    \"\"\"Aligned 3D Anchor Generator by range.\n\n    This anchor generator uses a different manner to generate the positions\n    of anchors' centers from :class:`Anchor3DRangeGenerator`.\n\n    Note:\n        The `align` means that the anchor's center is aligned with the voxel\n        grid, which is also the feature grid. The previous implementation of\n        :class:`Anchor3DRangeGenerator` does not generate the anchors' center\n        according to the voxel grid. Rather, it generates the center by\n        uniformly distributing the anchors inside the minimum and maximum\n        anchor ranges according to the feature map sizes.\n        However, this makes the anchors center does not match the feature grid.\n        The :class:`AlignedAnchor3DRangeGenerator` add + 1 when using the\n        feature map sizes to obtain the corners of the voxel grid. Then it\n        shifts the coordinates to the center of voxel grid and use the left\n        up corner to distribute anchors.\n\n    Args:\n        anchor_corner (bool): Whether to align with the corner of the voxel\n            grid. By default it is False and the anchor's center will be\n            the same as the corresponding voxel's center, which is also the\n            center of the corresponding greature grid.\n    \"\"\"\n\n    def __init__(self, align_corner=False, **kwargs):\n        super(AlignedAnchor3DRangeGenerator, self).__init__(**kwargs)\n        self.align_corner = align_corner\n\n    def anchors_single_range(self,\n                             feature_size,\n                             anchor_range,\n                             scale,\n                             sizes=[[1.6, 3.9, 1.56]],\n                             rotations=[0, 1.5707963],\n                             device='cuda'):\n        \"\"\"Generate anchors in a single range.\n\n        Args:\n            feature_size (list[float] | tuple[float]): Feature map size. It is\n                either a list of a tuple of [D, H, W](in order of z, y, and x).\n            anchor_range (torch.Tensor | list[float]): Range of anchors with\n                shape [6]. The order is consistent with that of anchors, i.e.,\n                (x_min, y_min, z_min, x_max, y_max, z_max).\n            scale (float | int, optional): The scale factor of anchors.\n            sizes (list[list] | np.ndarray | torch.Tensor): Anchor size with\n                shape [N, 3], in order of x, y, z.\n            rotations (list[float] | np.ndarray | torch.Tensor): Rotations of\n                anchors in a single feature grid.\n            device (str): Devices that the anchors will be put on.\n\n        Returns:\n            torch.Tensor: Anchors with shape \\\n                [*feature_size, num_sizes, num_rots, 7].\n        \"\"\"\n        if len(feature_size) == 2:\n            feature_size = [1, feature_size[0], feature_size[1]]\n        anchor_range = torch.tensor(anchor_range, device=device)\n        z_centers = torch.linspace(\n            anchor_range[2],\n            anchor_range[5],\n            feature_size[0] + 1,\n            device=device)\n        y_centers = torch.linspace(\n            anchor_range[1],\n            anchor_range[4],\n            feature_size[1] + 1,\n            device=device)\n        x_centers = torch.linspace(\n            anchor_range[0],\n            anchor_range[3],\n            feature_size[2] + 1,\n            device=device)\n        sizes = torch.tensor(sizes, device=device).reshape(-1, 3) * scale\n        rotations = torch.tensor(rotations, device=device)\n\n        # shift the anchor center\n        if not self.align_corner:\n            z_shift = (z_centers[1] - z_centers[0]) / 2\n            y_shift = (y_centers[1] - y_centers[0]) / 2\n            x_shift = (x_centers[1] - x_centers[0]) / 2\n            z_centers += z_shift\n            y_centers += y_shift\n            x_centers += x_shift\n\n        # torch.meshgrid default behavior is 'id', np's default is 'xy'\n        rets = torch.meshgrid(x_centers[:feature_size[2]],\n                              y_centers[:feature_size[1]],\n                              z_centers[:feature_size[0]], rotations)\n\n        # torch.meshgrid returns a tuple rather than list\n        rets = list(rets)\n        tile_shape = [1] * 5\n        tile_shape[-2] = int(sizes.shape[0])\n        for i in range(len(rets)):\n            rets[i] = rets[i].unsqueeze(-2).repeat(tile_shape).unsqueeze(-1)\n\n        sizes = sizes.reshape([1, 1, 1, -1, 1, 3])\n        tile_size_shape = list(rets[0].shape)\n        tile_size_shape[3] = 1\n        sizes = sizes.repeat(tile_size_shape)\n        rets.insert(3, sizes)\n\n        ret = torch.cat(rets, dim=-1).permute([2, 1, 0, 3, 4, 5])\n\n        if len(self.custom_values) > 0:\n            custom_ndim = len(self.custom_values)\n            custom = ret.new_zeros([*ret.shape[:-1], custom_ndim])\n            # TODO: check the support of custom values\n            # custom[:] = self.custom_values\n            ret = torch.cat([ret, custom], dim=-1)\n        return ret\n\n\n@ANCHOR_GENERATORS.register_module()\nclass AlignedAnchor3DRangeGeneratorPerCls(AlignedAnchor3DRangeGenerator):\n    \"\"\"3D Anchor Generator by range for per class.\n\n    This anchor generator generates anchors by the given range for per class.\n    Note that feature maps of different classes may be different.\n\n    Args:\n        kwargs (dict): Arguments are the same as those in \\\n            :class:`AlignedAnchor3DRangeGenerator`.\n    \"\"\"\n\n    def __init__(self, **kwargs):\n        super(AlignedAnchor3DRangeGeneratorPerCls, self).__init__(**kwargs)\n        assert len(self.scales) == 1, 'Multi-scale feature map levels are' + \\\n            ' not supported currently in this kind of anchor generator.'\n\n    def grid_anchors(self, featmap_sizes, device='cuda'):\n        \"\"\"Generate grid anchors in multiple feature levels.\n\n        Args:\n            featmap_sizes (list[tuple]): List of feature map sizes for \\\n                different classes in a single feature level.\n            device (str): Device where the anchors will be put on.\n\n        Returns:\n            list[list[torch.Tensor]]: Anchors in multiple feature levels. \\\n                Note that in this anchor generator, we currently only \\\n                support single feature level. The sizes of each tensor \\\n                should be [num_sizes/ranges*num_rots*featmap_size, \\\n                box_code_size].\n        \"\"\"\n        multi_level_anchors = []\n        anchors = self.multi_cls_grid_anchors(\n            featmap_sizes, self.scales[0], device=device)\n        multi_level_anchors.append(anchors)\n        return multi_level_anchors\n\n    def multi_cls_grid_anchors(self, featmap_sizes, scale, device='cuda'):\n        \"\"\"Generate grid anchors of a single level feature map for multi-class\n        with different feature map sizes.\n\n        This function is usually called by method ``self.grid_anchors``.\n\n        Args:\n            featmap_sizes (list[tuple]): List of feature map sizes for \\\n                different classes in a single feature level.\n            scale (float): Scale factor of the anchors in the current level.\n            device (str, optional): Device the tensor will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: Anchors in the overall feature map.\n        \"\"\"\n        assert len(featmap_sizes) == len(self.sizes) == len(self.ranges), \\\n            'The number of different feature map sizes anchor sizes and ' + \\\n            'ranges should be the same.'\n\n        multi_cls_anchors = []\n        for i in range(len(featmap_sizes)):\n            anchors = self.anchors_single_range(\n                featmap_sizes[i],\n                self.ranges[i],\n                scale,\n                self.sizes[i],\n                self.rotations,\n                device=device)\n            # [*featmap_size, num_sizes/ranges, num_rots, box_code_size]\n            ndim = len(featmap_sizes[i])\n            anchors = anchors.view(*featmap_sizes[i], -1, anchors.size(-1))\n            # [*featmap_size, num_sizes/ranges*num_rots, box_code_size]\n            anchors = anchors.permute(ndim, *range(0, ndim), ndim + 1)\n            # [num_sizes/ranges*num_rots, *featmap_size, box_code_size]\n            multi_cls_anchors.append(anchors.reshape(-1, anchors.size(-1)))\n            # [num_sizes/ranges*num_rots*featmap_size, box_code_size]\n        return multi_cls_anchors\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/anchor/anchor_generator.py",
    "content": "import warnings\n\nfrom mmcv.utils import is_tuple_of\nimport numpy as np\nimport torch\nfrom torch.nn.modules.utils import _pair\n\nfrom .builder import PRIOR_GENERATORS\n\n\n@PRIOR_GENERATORS.register_module()\nclass AnchorGenerator:\n    \"\"\"Standard anchor generator for 2D anchor-based detectors.\n\n    Args:\n        strides (list[int] | list[tuple[int, int]]): Strides of anchors\n            in multiple feature levels in order (w, h).\n        ratios (list[float]): The list of ratios between the height and width\n            of anchors in a single level.\n        scales (list[int] | None): Anchor scales for anchors in a single level.\n            It cannot be set at the same time if `octave_base_scale` and\n            `scales_per_octave` are set.\n        base_sizes (list[int] | None): The basic sizes\n            of anchors in multiple levels.\n            If None is given, strides will be used as base_sizes.\n            (If strides are non square, the shortest stride is taken.)\n        scale_major (bool): Whether to multiply scales first when generating\n            base anchors. If true, the anchors in the same row will have the\n            same scales. By default it is True in V2.0\n        octave_base_scale (int): The base scale of octave.\n        scales_per_octave (int): Number of scales for each octave.\n            `octave_base_scale` and `scales_per_octave` are usually used in\n            retinanet and the `scales` should be None when they are set.\n        centers (list[tuple[float, float]] | None): The centers of the anchor\n            relative to the feature grid center in multiple feature levels.\n            By default it is set to be None and not used. If a list of tuple of\n            float is given, they will be used to shift the centers of anchors.\n        center_offset (float): The offset of center in proportion to anchors'\n            width and height. By default it is 0 in V2.0.\n\n    Examples:\n        >>> from mmcv.core import AnchorGenerator\n        >>> self = AnchorGenerator([16], [1.], [1.], [9])\n        >>> all_anchors = self.grid_anchors([(2, 2)], device='cpu')\n        >>> print(all_anchors)\n        [tensor([[-4.5000, -4.5000,  4.5000,  4.5000],\n                [11.5000, -4.5000, 20.5000,  4.5000],\n                [-4.5000, 11.5000,  4.5000, 20.5000],\n                [11.5000, 11.5000, 20.5000, 20.5000]])]\n        >>> self = AnchorGenerator([16, 32], [1.], [1.], [9, 18])\n        >>> all_anchors = self.grid_anchors([(2, 2), (1, 1)], device='cpu')\n        >>> print(all_anchors)\n        [tensor([[-4.5000, -4.5000,  4.5000,  4.5000],\n                [11.5000, -4.5000, 20.5000,  4.5000],\n                [-4.5000, 11.5000,  4.5000, 20.5000],\n                [11.5000, 11.5000, 20.5000, 20.5000]]), \\\n        tensor([[-9., -9., 9., 9.]])]\n    \"\"\"\n\n    def __init__(self,\n                 strides,\n                 ratios,\n                 scales=None,\n                 base_sizes=None,\n                 scale_major=True,\n                 octave_base_scale=None,\n                 scales_per_octave=None,\n                 centers=None,\n                 center_offset=0.):\n        # check center and center_offset\n        if center_offset != 0:\n            assert centers is None, 'center cannot be set when center_offset' \\\n                                    f'!=0, {centers} is given.'\n        if not (0 <= center_offset <= 1):\n            raise ValueError('center_offset should be in range [0, 1], '\n                             f'{center_offset} is given.')\n        if centers is not None:\n            assert len(centers) == len(strides), \\\n                'The number of strides should be the same as centers, got ' \\\n                f'{strides} and {centers}'\n\n        # calculate base sizes of anchors\n        self.strides = [_pair(stride) for stride in strides]\n        self.base_sizes = [min(stride) for stride in self.strides\n                           ] if base_sizes is None else base_sizes\n        assert len(self.base_sizes) == len(self.strides), \\\n            'The number of strides should be the same as base sizes, got ' \\\n            f'{self.strides} and {self.base_sizes}'\n\n        # calculate scales of anchors\n        assert ((octave_base_scale is not None\n                 and scales_per_octave is not None) ^ (scales is not None)), \\\n            'scales and octave_base_scale with scales_per_octave cannot' \\\n            ' be set at the same time'\n        if scales is not None:\n            self.scales = torch.Tensor(scales)\n        elif octave_base_scale is not None and scales_per_octave is not None:\n            octave_scales = np.array(\n                [2**(i / scales_per_octave) for i in range(scales_per_octave)])\n            scales = octave_scales * octave_base_scale\n            self.scales = torch.Tensor(scales)\n        else:\n            raise ValueError('Either scales or octave_base_scale with '\n                             'scales_per_octave should be set')\n\n        self.octave_base_scale = octave_base_scale\n        self.scales_per_octave = scales_per_octave\n        self.ratios = torch.Tensor(ratios)\n        self.scale_major = scale_major\n        self.centers = centers\n        self.center_offset = center_offset\n        self.base_anchors = self.gen_base_anchors()\n\n    @property\n    def num_base_anchors(self):\n        \"\"\"list[int]: total number of base anchors in a feature grid\"\"\"\n        return self.num_base_priors\n\n    @property\n    def num_base_priors(self):\n        \"\"\"list[int]: The number of priors (anchors) at a point\n        on the feature grid\"\"\"\n        return [base_anchors.size(0) for base_anchors in self.base_anchors]\n\n    @property\n    def num_levels(self):\n        \"\"\"int: number of feature levels that the generator will be applied\"\"\"\n        return len(self.strides)\n\n    def gen_base_anchors(self):\n        \"\"\"Generate base anchors.\n\n        Returns:\n            list(torch.Tensor): Base anchors of a feature grid in multiple \\\n                feature levels.\n        \"\"\"\n        multi_level_base_anchors = []\n        for i, base_size in enumerate(self.base_sizes):\n            center = None\n            if self.centers is not None:\n                center = self.centers[i]\n            multi_level_base_anchors.append(\n                self.gen_single_level_base_anchors(\n                    base_size,\n                    scales=self.scales,\n                    ratios=self.ratios,\n                    center=center))\n        return multi_level_base_anchors\n\n    def gen_single_level_base_anchors(self,\n                                      base_size,\n                                      scales,\n                                      ratios,\n                                      center=None):\n        \"\"\"Generate base anchors of a single level.\n\n        Args:\n            base_size (int | float): Basic size of an anchor.\n            scales (torch.Tensor): Scales of the anchor.\n            ratios (torch.Tensor): The ratio between between the height\n                and width of anchors in a single level.\n            center (tuple[float], optional): The center of the base anchor\n                related to a single feature grid. Defaults to None.\n\n        Returns:\n            torch.Tensor: Anchors in a single-level feature maps.\n        \"\"\"\n        w = base_size\n        h = base_size\n        if center is None:\n            x_center = self.center_offset * w\n            y_center = self.center_offset * h\n        else:\n            x_center, y_center = center\n\n        h_ratios = torch.sqrt(ratios)\n        w_ratios = 1 / h_ratios\n        if self.scale_major:\n            ws = (w * w_ratios[:, None] * scales[None, :]).view(-1)\n            hs = (h * h_ratios[:, None] * scales[None, :]).view(-1)\n        else:\n            ws = (w * scales[:, None] * w_ratios[None, :]).view(-1)\n            hs = (h * scales[:, None] * h_ratios[None, :]).view(-1)\n\n        # use float anchor and the anchor's center is aligned with the\n        # pixel center\n        base_anchors = [\n            x_center - 0.5 * ws, y_center - 0.5 * hs, x_center + 0.5 * ws,\n            y_center + 0.5 * hs\n        ]\n        base_anchors = torch.stack(base_anchors, dim=-1)\n\n        return base_anchors\n\n    def _meshgrid(self, x, y, row_major=True):\n        \"\"\"Generate mesh grid of x and y.\n\n        Args:\n            x (torch.Tensor): Grids of x dimension.\n            y (torch.Tensor): Grids of y dimension.\n            row_major (bool, optional): Whether to return y grids first.\n                Defaults to True.\n\n        Returns:\n            tuple[torch.Tensor]: The mesh grids of x and y.\n        \"\"\"\n        # use shape instead of len to keep tracing while exporting to onnx\n        xx = x.repeat(y.shape[0])\n        yy = y.view(-1, 1).repeat(1, x.shape[0]).view(-1)\n        if row_major:\n            return xx, yy\n        else:\n            return yy, xx\n\n    def grid_priors(self, featmap_sizes, device='cuda'):\n        \"\"\"Generate grid anchors in multiple feature levels.\n\n        Args:\n            featmap_sizes (list[tuple]): List of feature map sizes in\n                multiple feature levels.\n            device (str): The device where the anchors will be put on.\n\n        Return:\n            list[torch.Tensor]: Anchors in multiple feature levels. \\\n                The sizes of each tensor should be [N, 4], where \\\n                N = width * height * num_base_anchors, width and height \\\n                are the sizes of the corresponding feature level, \\\n                num_base_anchors is the number of anchors for that level.\n        \"\"\"\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_anchors = []\n        for i in range(self.num_levels):\n            anchors = self.single_level_grid_priors(\n                featmap_sizes[i], level_idx=i, device=device)\n            multi_level_anchors.append(anchors)\n        return multi_level_anchors\n\n    def single_level_grid_priors(self, featmap_size, level_idx, device='cuda'):\n        \"\"\"Generate grid anchors of a single level.\n\n        Note:\n            This function is usually called by method ``self.grid_priors``.\n\n        Args:\n            featmap_size (tuple[int]): Size of the feature maps.\n            level_idx (int): The index of corresponding feature map level.\n            device (str, optional): The device the tensor will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: Anchors in the overall feature maps.\n        \"\"\"\n\n        base_anchors = self.base_anchors[level_idx].to(device)\n        feat_h, feat_w = featmap_size\n        stride_w, stride_h = self.strides[level_idx]\n        shift_x = torch.arange(0, feat_w, device=device) * stride_w\n        shift_y = torch.arange(0, feat_h, device=device) * stride_h\n\n        shift_xx, shift_yy = self._meshgrid(shift_x, shift_y)\n        shifts = torch.stack([shift_xx, shift_yy, shift_xx, shift_yy], dim=-1)\n        shifts = shifts.type_as(base_anchors)\n        # first feat_w elements correspond to the first row of shifts\n        # add A anchors (1, A, 4) to K shifts (K, 1, 4) to get\n        # shifted anchors (K, A, 4), reshape to (K*A, 4)\n\n        all_anchors = base_anchors[None, :, :] + shifts[:, None, :]\n        all_anchors = all_anchors.view(-1, 4)\n        # first A rows correspond to A anchors of (0, 0) in feature map,\n        # then (0, 1), (0, 2), ...\n        return all_anchors\n\n    def sparse_priors(self,\n                      prior_idxs,\n                      featmap_size,\n                      level_idx,\n                      dtype=torch.float32,\n                      device='cuda'):\n        \"\"\"Generate sparse anchors according to the ``prior_idxs``.\n\n        Args:\n            prior_idxs (Tensor): The index of corresponding anchors\n                in the feature map.\n            featmap_size (tuple[int]): feature map size arrange as (h, w).\n            level_idx (int): The level index of corresponding feature\n                map.\n            dtype (obj:`torch.dtype`): Date type of points.Defaults to\n                ``torch.float32``.\n            device (obj:`torch.device`): The device where the points is\n                located.\n        Returns:\n            Tensor: Anchor with shape (N, 4), N should be equal to\n                the length of ``prior_idxs``.\n        \"\"\"\n\n        height, width = featmap_size\n        num_base_anchors = self.num_base_anchors[level_idx]\n        base_anchor_id = prior_idxs % num_base_anchors\n        x = (prior_idxs //\n             num_base_anchors) % width * self.strides[level_idx][0]\n        y = (prior_idxs // width //\n             num_base_anchors) % height * self.strides[level_idx][1]\n        priors = torch.stack([x, y, x, y], 1).to(dtype).to(device) + \\\n            self.base_anchors[level_idx][base_anchor_id, :].to(device)\n\n        return priors\n\n    def grid_anchors(self, featmap_sizes, device='cuda'):\n        \"\"\"Generate grid anchors in multiple feature levels.\n\n        Args:\n            featmap_sizes (list[tuple]): List of feature map sizes in\n                multiple feature levels.\n            device (str): Device where the anchors will be put on.\n\n        Return:\n            list[torch.Tensor]: Anchors in multiple feature levels. \\\n                The sizes of each tensor should be [N, 4], where \\\n                N = width * height * num_base_anchors, width and height \\\n                are the sizes of the corresponding feature level, \\\n                num_base_anchors is the number of anchors for that level.\n        \"\"\"\n        warnings.warn('``grid_anchors`` would be deprecated soon. '\n                      'Please use ``grid_priors`` ')\n\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_anchors = []\n        for i in range(self.num_levels):\n            anchors = self.single_level_grid_anchors(\n                self.base_anchors[i].to(device),\n                featmap_sizes[i],\n                self.strides[i],\n                device=device)\n            multi_level_anchors.append(anchors)\n        return multi_level_anchors\n\n    def single_level_grid_anchors(self,\n                                  base_anchors,\n                                  featmap_size,\n                                  stride=(16, 16),\n                                  device='cuda'):\n        \"\"\"Generate grid anchors of a single level.\n\n        Note:\n            This function is usually called by method ``self.grid_anchors``.\n\n        Args:\n            base_anchors (torch.Tensor): The base anchors of a feature grid.\n            featmap_size (tuple[int]): Size of the feature maps.\n            stride (tuple[int], optional): Stride of the feature map in order\n                (w, h). Defaults to (16, 16).\n            device (str, optional): Device the tensor will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: Anchors in the overall feature maps.\n        \"\"\"\n\n        warnings.warn(\n            '``single_level_grid_anchors`` would be deprecated soon. '\n            'Please use ``single_level_grid_priors`` ')\n\n        # keep featmap_size as Tensor instead of int, so that we\n        # can covert to ONNX correctly\n        feat_h, feat_w = featmap_size\n        shift_x = torch.arange(0, feat_w, device=device) * stride[0]\n        shift_y = torch.arange(0, feat_h, device=device) * stride[1]\n\n        shift_xx, shift_yy = self._meshgrid(shift_x, shift_y)\n        shifts = torch.stack([shift_xx, shift_yy, shift_xx, shift_yy], dim=-1)\n        shifts = shifts.type_as(base_anchors)\n        # first feat_w elements correspond to the first row of shifts\n        # add A anchors (1, A, 4) to K shifts (K, 1, 4) to get\n        # shifted anchors (K, A, 4), reshape to (K*A, 4)\n\n        all_anchors = base_anchors[None, :, :] + shifts[:, None, :]\n        all_anchors = all_anchors.view(-1, 4)\n        # first A rows correspond to A anchors of (0, 0) in feature map,\n        # then (0, 1), (0, 2), ...\n        return all_anchors\n\n    def valid_flags(self, featmap_sizes, pad_shape, device='cuda'):\n        \"\"\"Generate valid flags of anchors in multiple feature levels.\n\n        Args:\n            featmap_sizes (list(tuple)): List of feature map sizes in\n                multiple feature levels.\n            pad_shape (tuple): The padded shape of the image.\n            device (str): Device where the anchors will be put on.\n\n        Return:\n            list(torch.Tensor): Valid flags of anchors in multiple levels.\n        \"\"\"\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_flags = []\n        for i in range(self.num_levels):\n            anchor_stride = self.strides[i]\n            feat_h, feat_w = featmap_sizes[i]\n            h, w = pad_shape[:2]\n            valid_feat_h = min(int(np.ceil(h / anchor_stride[1])), feat_h)\n            valid_feat_w = min(int(np.ceil(w / anchor_stride[0])), feat_w)\n            flags = self.single_level_valid_flags((feat_h, feat_w),\n                                                  (valid_feat_h, valid_feat_w),\n                                                  self.num_base_anchors[i],\n                                                  device=device)\n            multi_level_flags.append(flags)\n        return multi_level_flags\n\n    def single_level_valid_flags(self,\n                                 featmap_size,\n                                 valid_size,\n                                 num_base_anchors,\n                                 device='cuda'):\n        \"\"\"Generate the valid flags of anchor in a single feature map.\n\n        Args:\n            featmap_size (tuple[int]): The size of feature maps, arrange\n                as (h, w).\n            valid_size (tuple[int]): The valid size of the feature maps.\n            num_base_anchors (int): The number of base anchors.\n            device (str, optional): Device where the flags will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: The valid flags of each anchor in a single level \\\n                feature map.\n        \"\"\"\n        feat_h, feat_w = featmap_size\n        valid_h, valid_w = valid_size\n        assert valid_h <= feat_h and valid_w <= feat_w\n        valid_x = torch.zeros(feat_w, dtype=torch.bool, device=device)\n        valid_y = torch.zeros(feat_h, dtype=torch.bool, device=device)\n        valid_x[:valid_w] = 1\n        valid_y[:valid_h] = 1\n        valid_xx, valid_yy = self._meshgrid(valid_x, valid_y)\n        valid = valid_xx & valid_yy\n        valid = valid[:, None].expand(valid.size(0),\n                                      num_base_anchors).contiguous().view(-1)\n        return valid\n\n    def __repr__(self):\n        \"\"\"str: a string that describes the module\"\"\"\n        indent_str = '    '\n        repr_str = self.__class__.__name__ + '(\\n'\n        repr_str += f'{indent_str}strides={self.strides},\\n'\n        repr_str += f'{indent_str}ratios={self.ratios},\\n'\n        repr_str += f'{indent_str}scales={self.scales},\\n'\n        repr_str += f'{indent_str}base_sizes={self.base_sizes},\\n'\n        repr_str += f'{indent_str}scale_major={self.scale_major},\\n'\n        repr_str += f'{indent_str}octave_base_scale='\n        repr_str += f'{self.octave_base_scale},\\n'\n        repr_str += f'{indent_str}scales_per_octave='\n        repr_str += f'{self.scales_per_octave},\\n'\n        repr_str += f'{indent_str}num_levels={self.num_levels}\\n'\n        repr_str += f'{indent_str}centers={self.centers},\\n'\n        repr_str += f'{indent_str}center_offset={self.center_offset})'\n        return repr_str\n\n\n@PRIOR_GENERATORS.register_module()\nclass SSDAnchorGenerator(AnchorGenerator):\n    \"\"\"Anchor generator for SSD.\n\n    Args:\n        strides (list[int]  | list[tuple[int, int]]): Strides of anchors\n            in multiple feature levels.\n        ratios (list[float]): The list of ratios between the height and width\n            of anchors in a single level.\n        basesize_ratio_range (tuple(float)): Ratio range of anchors.\n        input_size (int): Size of feature map, 300 for SSD300,\n            512 for SSD512.\n        scale_major (bool): Whether to multiply scales first when generating\n            base anchors. If true, the anchors in the same row will have the\n            same scales. It is always set to be False in SSD.\n    \"\"\"\n\n    def __init__(self,\n                 strides,\n                 ratios,\n                 basesize_ratio_range,\n                 input_size=300,\n                 scale_major=True):\n        assert len(strides) == len(ratios)\n        assert is_tuple_of(basesize_ratio_range, float)\n\n        self.strides = [_pair(stride) for stride in strides]\n        self.input_size = input_size\n        self.centers = [(stride[0] / 2., stride[1] / 2.)\n                        for stride in self.strides]\n        self.basesize_ratio_range = basesize_ratio_range\n\n        # calculate anchor ratios and sizes\n        min_ratio, max_ratio = basesize_ratio_range\n        min_ratio = int(min_ratio * 100)\n        max_ratio = int(max_ratio * 100)\n        step = int(np.floor(max_ratio - min_ratio) / (self.num_levels - 2))\n        min_sizes = []\n        max_sizes = []\n        for ratio in range(int(min_ratio), int(max_ratio) + 1, step):\n            min_sizes.append(int(self.input_size * ratio / 100))\n            max_sizes.append(int(self.input_size * (ratio + step) / 100))\n        if self.input_size == 300:\n            if basesize_ratio_range[0] == 0.15:  # SSD300 COCO\n                min_sizes.insert(0, int(self.input_size * 7 / 100))\n                max_sizes.insert(0, int(self.input_size * 15 / 100))\n            elif basesize_ratio_range[0] == 0.2:  # SSD300 VOC\n                min_sizes.insert(0, int(self.input_size * 10 / 100))\n                max_sizes.insert(0, int(self.input_size * 20 / 100))\n            else:\n                raise ValueError(\n                    'basesize_ratio_range[0] should be either 0.15'\n                    'or 0.2 when input_size is 300, got '\n                    f'{basesize_ratio_range[0]}.')\n        elif self.input_size == 512:\n            if basesize_ratio_range[0] == 0.1:  # SSD512 COCO\n                min_sizes.insert(0, int(self.input_size * 4 / 100))\n                max_sizes.insert(0, int(self.input_size * 10 / 100))\n            elif basesize_ratio_range[0] == 0.15:  # SSD512 VOC\n                min_sizes.insert(0, int(self.input_size * 7 / 100))\n                max_sizes.insert(0, int(self.input_size * 15 / 100))\n            else:\n                raise ValueError('basesize_ratio_range[0] should be either 0.1'\n                                 'or 0.15 when input_size is 512, got'\n                                 f' {basesize_ratio_range[0]}.')\n        else:\n            raise ValueError('Only support 300 or 512 in SSDAnchorGenerator'\n                             f', got {self.input_size}.')\n\n        anchor_ratios = []\n        anchor_scales = []\n        for k in range(len(self.strides)):\n            scales = [1., np.sqrt(max_sizes[k] / min_sizes[k])]\n            anchor_ratio = [1.]\n            for r in ratios[k]:\n                anchor_ratio += [1 / r, r]  # 4 or 6 ratio\n            anchor_ratios.append(torch.Tensor(anchor_ratio))\n            anchor_scales.append(torch.Tensor(scales))\n\n        self.base_sizes = min_sizes\n        self.scales = anchor_scales\n        self.ratios = anchor_ratios\n        self.scale_major = scale_major\n        self.center_offset = 0\n        self.base_anchors = self.gen_base_anchors()\n\n    def gen_base_anchors(self):\n        \"\"\"Generate base anchors.\n\n        Returns:\n            list(torch.Tensor): Base anchors of a feature grid in multiple \\\n                feature levels.\n        \"\"\"\n        multi_level_base_anchors = []\n        for i, base_size in enumerate(self.base_sizes):\n            base_anchors = self.gen_single_level_base_anchors(\n                base_size,\n                scales=self.scales[i],\n                ratios=self.ratios[i],\n                center=self.centers[i])\n            indices = list(range(len(self.ratios[i])))\n            indices.insert(1, len(indices))\n            base_anchors = torch.index_select(base_anchors, 0,\n                                              torch.LongTensor(indices))\n            multi_level_base_anchors.append(base_anchors)\n        return multi_level_base_anchors\n\n    def __repr__(self):\n        \"\"\"str: a string that describes the module\"\"\"\n        indent_str = '    '\n        repr_str = self.__class__.__name__ + '(\\n'\n        repr_str += f'{indent_str}strides={self.strides},\\n'\n        repr_str += f'{indent_str}scales={self.scales},\\n'\n        repr_str += f'{indent_str}scale_major={self.scale_major},\\n'\n        repr_str += f'{indent_str}input_size={self.input_size},\\n'\n        repr_str += f'{indent_str}scales={self.scales},\\n'\n        repr_str += f'{indent_str}ratios={self.ratios},\\n'\n        repr_str += f'{indent_str}num_levels={self.num_levels},\\n'\n        repr_str += f'{indent_str}base_sizes={self.base_sizes},\\n'\n        repr_str += f'{indent_str}basesize_ratio_range='\n        repr_str += f'{self.basesize_ratio_range})'\n        return repr_str\n\n\n@PRIOR_GENERATORS.register_module()\nclass LegacyAnchorGenerator(AnchorGenerator):\n    \"\"\"Legacy anchor generator used in MMDetection V1.x.\n\n    Note:\n        Difference to the V2.0 anchor generator:\n\n        1. The center offset of V1.x anchors are set to be 0.5 rather than 0.\n        2. The width/height are minused by 1 when calculating the anchors' \\\n            centers and corners to meet the V1.x coordinate system.\n        3. The anchors' corners are quantized.\n\n    Args:\n        strides (list[int] | list[tuple[int]]): Strides of anchors\n            in multiple feature levels.\n        ratios (list[float]): The list of ratios between the height and width\n            of anchors in a single level.\n        scales (list[int] | None): Anchor scales for anchors in a single level.\n            It cannot be set at the same time if `octave_base_scale` and\n            `scales_per_octave` are set.\n        base_sizes (list[int]): The basic sizes of anchors in multiple levels.\n            If None is given, strides will be used to generate base_sizes.\n        scale_major (bool): Whether to multiply scales first when generating\n            base anchors. If true, the anchors in the same row will have the\n            same scales. By default it is True in V2.0\n        octave_base_scale (int): The base scale of octave.\n        scales_per_octave (int): Number of scales for each octave.\n            `octave_base_scale` and `scales_per_octave` are usually used in\n            retinanet and the `scales` should be None when they are set.\n        centers (list[tuple[float, float]] | None): The centers of the anchor\n            relative to the feature grid center in multiple feature levels.\n            By default it is set to be None and not used. It a list of float\n            is given, this list will be used to shift the centers of anchors.\n        center_offset (float): The offset of center in propotion to anchors'\n            width and height. By default it is 0.5 in V2.0 but it should be 0.5\n            in v1.x models.\n\n    Examples:\n        >>> from mmcv.core import LegacyAnchorGenerator\n        >>> self = LegacyAnchorGenerator(\n        >>>     [16], [1.], [1.], [9], center_offset=0.5)\n        >>> all_anchors = self.grid_anchors(((2, 2),), device='cpu')\n        >>> print(all_anchors)\n        [tensor([[ 0.,  0.,  8.,  8.],\n                [16.,  0., 24.,  8.],\n                [ 0., 16.,  8., 24.],\n                [16., 16., 24., 24.]])]\n    \"\"\"\n\n    def gen_single_level_base_anchors(self,\n                                      base_size,\n                                      scales,\n                                      ratios,\n                                      center=None):\n        \"\"\"Generate base anchors of a single level.\n\n        Note:\n            The width/height of anchors are minused by 1 when calculating \\\n                the centers and corners to meet the V1.x coordinate system.\n\n        Args:\n            base_size (int | float): Basic size of an anchor.\n            scales (torch.Tensor): Scales of the anchor.\n            ratios (torch.Tensor): The ratio between between the height.\n                and width of anchors in a single level.\n            center (tuple[float], optional): The center of the base anchor\n                related to a single feature grid. Defaults to None.\n\n        Returns:\n            torch.Tensor: Anchors in a single-level feature map.\n        \"\"\"\n        w = base_size\n        h = base_size\n        if center is None:\n            x_center = self.center_offset * (w - 1)\n            y_center = self.center_offset * (h - 1)\n        else:\n            x_center, y_center = center\n\n        h_ratios = torch.sqrt(ratios)\n        w_ratios = 1 / h_ratios\n        if self.scale_major:\n            ws = (w * w_ratios[:, None] * scales[None, :]).view(-1)\n            hs = (h * h_ratios[:, None] * scales[None, :]).view(-1)\n        else:\n            ws = (w * scales[:, None] * w_ratios[None, :]).view(-1)\n            hs = (h * scales[:, None] * h_ratios[None, :]).view(-1)\n\n        # use float anchor and the anchor's center is aligned with the\n        # pixel center\n        base_anchors = [\n            x_center - 0.5 * (ws - 1), y_center - 0.5 * (hs - 1),\n            x_center + 0.5 * (ws - 1), y_center + 0.5 * (hs - 1)\n        ]\n        base_anchors = torch.stack(base_anchors, dim=-1).round()\n\n        return base_anchors\n\n\n@PRIOR_GENERATORS.register_module()\nclass LegacySSDAnchorGenerator(SSDAnchorGenerator, LegacyAnchorGenerator):\n    \"\"\"Legacy anchor generator used in MMDetection V1.x.\n\n    The difference between `LegacySSDAnchorGenerator` and `SSDAnchorGenerator`\n    can be found in `LegacyAnchorGenerator`.\n    \"\"\"\n\n    def __init__(self,\n                 strides,\n                 ratios,\n                 basesize_ratio_range,\n                 input_size=300,\n                 scale_major=True):\n        super(LegacySSDAnchorGenerator,\n              self).__init__(strides, ratios, basesize_ratio_range, input_size,\n                             scale_major)\n        self.centers = [((stride - 1) / 2., (stride - 1) / 2.)\n                        for stride in strides]\n        self.base_anchors = self.gen_base_anchors()\n\n\n@PRIOR_GENERATORS.register_module()\nclass YOLOAnchorGenerator(AnchorGenerator):\n    \"\"\"Anchor generator for YOLO.\n\n    Args:\n        strides (list[int] | list[tuple[int, int]]): Strides of anchors\n            in multiple feature levels.\n        base_sizes (list[list[tuple[int, int]]]): The basic sizes\n            of anchors in multiple levels.\n    \"\"\"\n\n    def __init__(self, strides, base_sizes):\n        self.strides = [_pair(stride) for stride in strides]\n        self.centers = [(stride[0] / 2., stride[1] / 2.)\n                        for stride in self.strides]\n        self.base_sizes = []\n        num_anchor_per_level = len(base_sizes[0])\n        for base_sizes_per_level in base_sizes:\n            assert num_anchor_per_level == len(base_sizes_per_level)\n            self.base_sizes.append(\n                [_pair(base_size) for base_size in base_sizes_per_level])\n        self.base_anchors = self.gen_base_anchors()\n\n    @property\n    def num_levels(self):\n        \"\"\"int: number of feature levels that the generator will be applied\"\"\"\n        return len(self.base_sizes)\n\n    def gen_base_anchors(self):\n        \"\"\"Generate base anchors.\n\n        Returns:\n            list(torch.Tensor): Base anchors of a feature grid in multiple \\\n                feature levels.\n        \"\"\"\n        multi_level_base_anchors = []\n        for i, base_sizes_per_level in enumerate(self.base_sizes):\n            center = None\n            if self.centers is not None:\n                center = self.centers[i]\n            multi_level_base_anchors.append(\n                self.gen_single_level_base_anchors(base_sizes_per_level,\n                                                   center))\n        return multi_level_base_anchors\n\n    def gen_single_level_base_anchors(self, base_sizes_per_level, center=None):\n        \"\"\"Generate base anchors of a single level.\n\n        Args:\n            base_sizes_per_level (list[tuple[int, int]]): Basic sizes of\n                anchors.\n            center (tuple[float], optional): The center of the base anchor\n                related to a single feature grid. Defaults to None.\n\n        Returns:\n            torch.Tensor: Anchors in a single-level feature maps.\n        \"\"\"\n        x_center, y_center = center\n        base_anchors = []\n        for base_size in base_sizes_per_level:\n            w, h = base_size\n\n            # use float anchor and the anchor's center is aligned with the\n            # pixel center\n            base_anchor = torch.Tensor([\n                x_center - 0.5 * w, y_center - 0.5 * h, x_center + 0.5 * w,\n                y_center + 0.5 * h\n            ])\n            base_anchors.append(base_anchor)\n        base_anchors = torch.stack(base_anchors, dim=0)\n\n        return base_anchors\n\n    def responsible_flags(self, featmap_sizes, gt_bboxes, device='cuda'):\n        \"\"\"Generate responsible anchor flags of grid cells in multiple scales.\n\n        Args:\n            featmap_sizes (list(tuple)): List of feature map sizes in multiple\n                feature levels.\n            gt_bboxes (Tensor): Ground truth boxes, shape (n, 4).\n            device (str): Device where the anchors will be put on.\n\n        Return:\n            list(torch.Tensor): responsible flags of anchors in multiple level\n        \"\"\"\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_responsible_flags = []\n        for i in range(self.num_levels):\n            anchor_stride = self.strides[i]\n            flags = self.single_level_responsible_flags(\n                featmap_sizes[i],\n                gt_bboxes,\n                anchor_stride,\n                self.num_base_anchors[i],\n                device=device)\n            multi_level_responsible_flags.append(flags)\n        return multi_level_responsible_flags\n\n    def single_level_responsible_flags(self,\n                                       featmap_size,\n                                       gt_bboxes,\n                                       stride,\n                                       num_base_anchors,\n                                       device='cuda'):\n        \"\"\"Generate the responsible flags of anchor in a single feature map.\n\n        Args:\n            featmap_size (tuple[int]): The size of feature maps.\n            gt_bboxes (Tensor): Ground truth boxes, shape (n, 4).\n            stride (tuple(int)): stride of current level\n            num_base_anchors (int): The number of base anchors.\n            device (str, optional): Device where the flags will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: The valid flags of each anchor in a single level \\\n                feature map.\n        \"\"\"\n        feat_h, feat_w = featmap_size\n        gt_bboxes_cx = ((gt_bboxes[:, 0] + gt_bboxes[:, 2]) * 0.5).to(device)\n        gt_bboxes_cy = ((gt_bboxes[:, 1] + gt_bboxes[:, 3]) * 0.5).to(device)\n        gt_bboxes_grid_x = torch.floor(gt_bboxes_cx / stride[0]).long()\n        gt_bboxes_grid_y = torch.floor(gt_bboxes_cy / stride[1]).long()\n\n        # row major indexing\n        gt_bboxes_grid_idx = gt_bboxes_grid_y * feat_w + gt_bboxes_grid_x\n\n        responsible_grid = torch.zeros(\n            feat_h * feat_w, dtype=torch.uint8, device=device)\n        responsible_grid[gt_bboxes_grid_idx] = 1\n\n        responsible_grid = responsible_grid[:, None].expand(\n            responsible_grid.size(0), num_base_anchors).contiguous().view(-1)\n        return responsible_grid\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/anchor/builder.py",
    "content": "import warnings\n\nfrom mmcv.utils import Registry, build_from_cfg\n\nPRIOR_GENERATORS = Registry('Generator for anchors and points')\n\nANCHOR_GENERATORS = PRIOR_GENERATORS\n\n\ndef build_prior_generator(cfg, default_args=None):\n    return build_from_cfg(cfg, PRIOR_GENERATORS, default_args)\n\n\ndef build_anchor_generator(cfg, default_args=None):\n    warnings.warn(\n        '``build_anchor_generator`` would be deprecated soon, please use '\n        '``build_prior_generator`` ')\n    return build_prior_generator(cfg, default_args=default_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/anchor/point_generator.py",
    "content": "import numpy as np\nimport torch\nfrom torch.nn.modules.utils import _pair\n\nfrom .builder import PRIOR_GENERATORS\n\n\n@PRIOR_GENERATORS.register_module()\nclass PointGenerator:\n\n    def _meshgrid(self, x, y, row_major=True):\n        xx = x.repeat(len(y))\n        yy = y.view(-1, 1).repeat(1, len(x)).view(-1)\n        if row_major:\n            return xx, yy\n        else:\n            return yy, xx\n\n    def grid_points(self, featmap_size, stride=16, device='cuda'):\n        feat_h, feat_w = featmap_size\n        shift_x = torch.arange(0., feat_w, device=device) * stride\n        shift_y = torch.arange(0., feat_h, device=device) * stride\n        shift_xx, shift_yy = self._meshgrid(shift_x, shift_y)\n        stride = shift_x.new_full((shift_xx.shape[0], ), stride)\n        shifts = torch.stack([shift_xx, shift_yy, stride], dim=-1)\n        all_points = shifts.to(device)\n        return all_points\n\n    def valid_flags(self, featmap_size, valid_size, device='cuda'):\n        feat_h, feat_w = featmap_size\n        valid_h, valid_w = valid_size\n        assert valid_h <= feat_h and valid_w <= feat_w\n        valid_x = torch.zeros(feat_w, dtype=torch.bool, device=device)\n        valid_y = torch.zeros(feat_h, dtype=torch.bool, device=device)\n        valid_x[:valid_w] = 1\n        valid_y[:valid_h] = 1\n        valid_xx, valid_yy = self._meshgrid(valid_x, valid_y)\n        valid = valid_xx & valid_yy\n        return valid\n\n\n@PRIOR_GENERATORS.register_module()\nclass MlvlPointGenerator:\n    \"\"\"Standard points generator for multi-level (Mlvl) feature maps in 2D\n    points-based detectors.\n\n    Args:\n        strides (list[int] | list[tuple[int, int]]): Strides of anchors\n            in multiple feature levels in order (w, h).\n        offset (float): The offset of points, the value is normalized with\n            corresponding stride. Defaults to 0.5.\n    \"\"\"\n\n    def __init__(self, strides, offset=0.5):\n        self.strides = [_pair(stride) for stride in strides]\n        self.offset = offset\n\n    @property\n    def num_levels(self):\n        \"\"\"int: number of feature levels that the generator will be applied\"\"\"\n        return len(self.strides)\n\n    @property\n    def num_base_priors(self):\n        \"\"\"list[int]: The number of priors (points) at a point\n        on the feature grid\"\"\"\n        return [1 for _ in range(len(self.strides))]\n\n    def _meshgrid(self, x, y, row_major=True):\n        xx = x.repeat(len(y))\n        yy = y.view(-1, 1).repeat(1, len(x)).view(-1)\n        if row_major:\n            return xx, yy\n        else:\n            return yy, xx\n\n    def grid_priors(self, featmap_sizes, device='cuda', with_stride=False):\n        \"\"\"Generate grid points of multiple feature levels.\n\n        Args:\n            featmap_sizes (list[tuple]): List of feature map sizes in\n                multiple feature levels, each size arrange as\n                as (h, w).\n            device (str): The device where the anchors will be put on.\n            with_stride (bool): Whether to concatenate the stride to\n                the last dimension of points.\n\n        Return:\n            list[torch.Tensor]: Points of  multiple feature levels.\n            The sizes of each tensor should be (N, 2) when with stride is\n            ``False``, where N = width * height, width and height\n            are the sizes of the corresponding feature level,\n            and the last dimension 2 represent (coord_x, coord_y),\n            otherwise the shape should be (N, 4),\n            and the last dimension 4 represent\n            (coord_x, coord_y, stride_w, stride_h).\n        \"\"\"\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_priors = []\n        for i in range(self.num_levels):\n            priors = self.single_level_grid_priors(\n                featmap_sizes[i],\n                level_idx=i,\n                device=device,\n                with_stride=with_stride)\n            multi_level_priors.append(priors)\n        return multi_level_priors\n\n    def single_level_grid_priors(self,\n                                 featmap_size,\n                                 level_idx,\n                                 device='cuda',\n                                 with_stride=False):\n        \"\"\"Generate grid Points of a single level.\n\n        Note:\n            This function is usually called by method ``self.grid_priors``.\n\n        Args:\n            featmap_size (tuple[int]): Size of the feature maps, arrange as\n                (h, w).\n            level_idx (int): The index of corresponding feature map level.\n            device (str, optional): The device the tensor will be put on.\n                Defaults to 'cuda'.\n            with_stride (bool): Concatenate the stride to the last dimension\n                of points.\n\n        Return:\n            Tensor: Points of single feature levels.\n            The shape of tensor should be (N, 2) when with stride is\n            ``False``, where N = width * height, width and height\n            are the sizes of the corresponding feature level,\n            and the last dimension 2 represent (coord_x, coord_y),\n            otherwise the shape should be (N, 4),\n            and the last dimension 4 represent\n            (coord_x, coord_y, stride_w, stride_h).\n        \"\"\"\n        feat_h, feat_w = featmap_size\n        stride_w, stride_h = self.strides[level_idx]\n        shift_x = (torch.arange(0., feat_w, device=device) +\n                   self.offset) * stride_w\n        shift_y = (torch.arange(0., feat_h, device=device) +\n                   self.offset) * stride_h\n        shift_xx, shift_yy = self._meshgrid(shift_x, shift_y)\n        if not with_stride:\n            shifts = torch.stack([shift_xx, shift_yy], dim=-1)\n        else:\n            stride_w = shift_xx.new_full((len(shift_xx), ), stride_w)\n            stride_h = shift_xx.new_full((len(shift_yy), ), stride_h)\n            shifts = torch.stack([shift_xx, shift_yy, stride_w, stride_h],\n                                 dim=-1)\n        all_points = shifts.to(device)\n        return all_points\n\n    def valid_flags(self, featmap_sizes, pad_shape, device='cuda'):\n        \"\"\"Generate valid flags of points of multiple feature levels.\n\n        Args:\n            featmap_sizes (list(tuple)): List of feature map sizes in\n                multiple feature levels, each size arrange as\n                as (h, w).\n            pad_shape (tuple(int)): The padded shape of the image,\n                 arrange as (h, w).\n            device (str): The device where the anchors will be put on.\n\n        Return:\n            list(torch.Tensor): Valid flags of points of multiple levels.\n        \"\"\"\n        assert self.num_levels == len(featmap_sizes)\n        multi_level_flags = []\n        for i in range(self.num_levels):\n            point_stride = self.strides[i]\n            feat_h, feat_w = featmap_sizes[i]\n            h, w = pad_shape[:2]\n            valid_feat_h = min(int(np.ceil(h / point_stride[1])), feat_h)\n            valid_feat_w = min(int(np.ceil(w / point_stride[0])), feat_w)\n            flags = self.single_level_valid_flags((feat_h, feat_w),\n                                                  (valid_feat_h, valid_feat_w),\n                                                  device=device)\n            multi_level_flags.append(flags)\n        return multi_level_flags\n\n    def single_level_valid_flags(self,\n                                 featmap_size,\n                                 valid_size,\n                                 device='cuda'):\n        \"\"\"Generate the valid flags of points of a single feature map.\n\n        Args:\n            featmap_size (tuple[int]): The size of feature maps, arrange as\n                as (h, w).\n            valid_size (tuple[int]): The valid size of the feature maps.\n                The size arrange as as (h, w).\n            device (str, optional): The device where the flags will be put on.\n                Defaults to 'cuda'.\n\n        Returns:\n            torch.Tensor: The valid flags of each points in a single level \\\n                feature map.\n        \"\"\"\n        feat_h, feat_w = featmap_size\n        valid_h, valid_w = valid_size\n        assert valid_h <= feat_h and valid_w <= feat_w\n        valid_x = torch.zeros(feat_w, dtype=torch.bool, device=device)\n        valid_y = torch.zeros(feat_h, dtype=torch.bool, device=device)\n        valid_x[:valid_w] = 1\n        valid_y[:valid_h] = 1\n        valid_xx, valid_yy = self._meshgrid(valid_x, valid_y)\n        valid = valid_xx & valid_yy\n        return valid\n\n    def sparse_priors(self,\n                      prior_idxs,\n                      featmap_size,\n                      level_idx,\n                      dtype=torch.float32,\n                      device='cuda'):\n        \"\"\"Generate sparse points according to the ``prior_idxs``.\n\n        Args:\n            prior_idxs (Tensor): The index of corresponding anchors\n                in the feature map.\n            featmap_size (tuple[int]): feature map size arrange as (w, h).\n            level_idx (int): The level index of corresponding feature\n                map.\n            dtype (obj:`torch.dtype`): Date type of points. Defaults to\n                ``torch.float32``.\n            device (obj:`torch.device`): The device where the points is\n                located.\n        Returns:\n            Tensor: Anchor with shape (N, 2), N should be equal to\n            the length of ``prior_idxs``. And last dimension\n            2 represent (coord_x, coord_y).\n        \"\"\"\n        height, width = featmap_size\n        x = (prior_idxs % width + self.offset) * self.strides[level_idx][0]\n        y = ((prior_idxs // width) % height +\n             self.offset) * self.strides[level_idx][1]\n        prioris = torch.stack([x, y], 1).to(dtype)\n        prioris = prioris.to(device)\n        return prioris\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/anchor/utils.py",
    "content": "import torch\n\n\ndef images_to_levels(target, num_levels):\n    \"\"\"Convert targets by image to targets by feature level.\n\n    [target_img0, target_img1] -> [target_level0, target_level1, ...]\n    \"\"\"\n    target = torch.stack(target, 0)\n    level_targets = []\n    start = 0\n    for n in num_levels:\n        end = start + n\n        # level_targets.append(target[:, start:end].squeeze(0))\n        level_targets.append(target[:, start:end])\n        start = end\n    return level_targets\n\n\ndef anchor_inside_flags(flat_anchors,\n                        valid_flags,\n                        img_shape,\n                        allowed_border=0):\n    \"\"\"Check whether the anchors are inside the border.\n\n    Args:\n        flat_anchors (torch.Tensor): Flatten anchors, shape (n, 4).\n        valid_flags (torch.Tensor): An existing valid flags of anchors.\n        img_shape (tuple(int)): Shape of current image.\n        allowed_border (int, optional): The border to allow the valid anchor.\n            Defaults to 0.\n\n    Returns:\n        torch.Tensor: Flags indicating whether the anchors are inside a \\\n            valid range.\n    \"\"\"\n    img_h, img_w = img_shape[:2]\n    if allowed_border >= 0:\n        inside_flags = valid_flags & \\\n            (flat_anchors[:, 0] >= -allowed_border) & \\\n            (flat_anchors[:, 1] >= -allowed_border) & \\\n            (flat_anchors[:, 2] < img_w + allowed_border) & \\\n            (flat_anchors[:, 3] < img_h + allowed_border)\n    else:\n        inside_flags = valid_flags\n    return inside_flags\n\n\ndef calc_region(bbox, ratio, featmap_size=None):\n    \"\"\"Calculate a proportional bbox region.\n\n    The bbox center are fixed and the new h' and w' is h * ratio and w * ratio.\n\n    Args:\n        bbox (Tensor): Bboxes to calculate regions, shape (n, 4).\n        ratio (float): Ratio of the output region.\n        featmap_size (tuple): Feature map size used for clipping the boundary.\n\n    Returns:\n        tuple: x1, y1, x2, y2\n    \"\"\"\n    x1 = torch.round((1 - ratio) * bbox[0] + ratio * bbox[2]).long()\n    y1 = torch.round((1 - ratio) * bbox[1] + ratio * bbox[3]).long()\n    x2 = torch.round(ratio * bbox[0] + (1 - ratio) * bbox[2]).long()\n    y2 = torch.round(ratio * bbox[1] + (1 - ratio) * bbox[3]).long()\n    if featmap_size is not None:\n        x1 = x1.clamp(min=0, max=featmap_size[1])\n        y1 = y1.clamp(min=0, max=featmap_size[0])\n        x2 = x2.clamp(min=0, max=featmap_size[1])\n        y2 = y2.clamp(min=0, max=featmap_size[0])\n    return (x1, y1, x2, y2)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/__init__.py",
    "content": "from .builder import build_assigner, build_bbox_coder, build_sampler\nfrom .samplers import (PseudoSampler)\nfrom .structures import (get_box_type, limit_period,\n                         mono_cam_box2vis, points_cam2img, xywhr2xyxyr)\nfrom .transforms import (bbox2distance, bbox2result, bbox2roi,\n                         bbox_cxcywh_to_xyxy, bbox_flip, bbox_mapping,\n                         bbox_mapping_back, bbox_rescale, bbox_xyxy_to_cxcywh,\n                         distance2bbox, roi2bbox,\n                         bbox3d2result, bbox3d2roi, bbox3d_mapping_back)\nfrom .iou_calculators import (BboxOverlaps2D, bbox_overlaps, AxisAlignedBboxOverlaps3D, \n                              BboxOverlaps3D, BboxOverlapsNearest3D,\n                              axis_aligned_bbox_overlaps_3d, bbox_overlaps_3d,\n                              bbox_overlaps_nearest_3d)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/__init__.py",
    "content": "from .hungarian_assigner import HungarianAssigner\nfrom .hungarian_assigner_3d import HungarianAssigner3D\nfrom .hungarian_assigner_3d_track import HungarianAssigner3DTrack\nfrom .base_assigner import BaseAssigner\nfrom .map_hungarian_assigner_3d import MapHungarianAssigner3D\n\n# __all__ = [\n#     'HungarianAssigner', \n    \n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/assign_result.py",
    "content": "import torch\n\nfrom mmcv.utils import util_mixins\n\n\nclass AssignResult(util_mixins.NiceRepr):\n    \"\"\"Stores assignments between predicted and truth boxes.\n\n    Attributes:\n        num_gts (int): the number of truth boxes considered when computing this\n            assignment\n\n        gt_inds (LongTensor): for each predicted box indicates the 1-based\n            index of the assigned truth box. 0 means unassigned and -1 means\n            ignore.\n\n        max_overlaps (FloatTensor): the iou between the predicted box and its\n            assigned truth box.\n\n        labels (None | LongTensor): If specified, for each predicted box\n            indicates the category label of the assigned truth box.\n\n    Example:\n        >>> # An assign result between 4 predicted boxes and 9 true boxes\n        >>> # where only two boxes were assigned.\n        >>> num_gts = 9\n        >>> max_overlaps = torch.LongTensor([0, .5, .9, 0])\n        >>> gt_inds = torch.LongTensor([-1, 1, 2, 0])\n        >>> labels = torch.LongTensor([0, 3, 4, 0])\n        >>> self = AssignResult(num_gts, gt_inds, max_overlaps, labels)\n        >>> print(str(self))  # xdoctest: +IGNORE_WANT\n        <AssignResult(num_gts=9, gt_inds.shape=(4,), max_overlaps.shape=(4,),\n                      labels.shape=(4,))>\n        >>> # Force addition of gt labels (when adding gt as proposals)\n        >>> new_labels = torch.LongTensor([3, 4, 5])\n        >>> self.add_gt_(new_labels)\n        >>> print(str(self))  # xdoctest: +IGNORE_WANT\n        <AssignResult(num_gts=9, gt_inds.shape=(7,), max_overlaps.shape=(7,),\n                      labels.shape=(7,))>\n    \"\"\"\n\n    def __init__(self, num_gts, gt_inds, max_overlaps, labels=None):\n        self.num_gts = num_gts\n        self.gt_inds = gt_inds\n        self.max_overlaps = max_overlaps\n        self.labels = labels\n        # Interface for possible user-defined properties\n        self._extra_properties = {}\n\n    @property\n    def num_preds(self):\n        \"\"\"int: the number of predictions in this assignment\"\"\"\n        return len(self.gt_inds)\n\n    def set_extra_property(self, key, value):\n        \"\"\"Set user-defined new property.\"\"\"\n        assert key not in self.info\n        self._extra_properties[key] = value\n\n    def get_extra_property(self, key):\n        \"\"\"Get user-defined property.\"\"\"\n        return self._extra_properties.get(key, None)\n\n    @property\n    def info(self):\n        \"\"\"dict: a dictionary of info about the object\"\"\"\n        basic_info = {\n            'num_gts': self.num_gts,\n            'num_preds': self.num_preds,\n            'gt_inds': self.gt_inds,\n            'max_overlaps': self.max_overlaps,\n            'labels': self.labels,\n        }\n        basic_info.update(self._extra_properties)\n        return basic_info\n\n    def __nice__(self):\n        \"\"\"str: a \"nice\" summary string describing this assign result\"\"\"\n        parts = []\n        parts.append(f'num_gts={self.num_gts!r}')\n        if self.gt_inds is None:\n            parts.append(f'gt_inds={self.gt_inds!r}')\n        else:\n            parts.append(f'gt_inds.shape={tuple(self.gt_inds.shape)!r}')\n        if self.max_overlaps is None:\n            parts.append(f'max_overlaps={self.max_overlaps!r}')\n        else:\n            parts.append('max_overlaps.shape='\n                         f'{tuple(self.max_overlaps.shape)!r}')\n        if self.labels is None:\n            parts.append(f'labels={self.labels!r}')\n        else:\n            parts.append(f'labels.shape={tuple(self.labels.shape)!r}')\n        return ', '.join(parts)\n\n    @classmethod\n    def random(cls, **kwargs):\n        \"\"\"Create random AssignResult for tests or debugging.\n\n        Args:\n            num_preds: number of predicted boxes\n            num_gts: number of true boxes\n            p_ignore (float): probability of a predicted box assigned to an\n                ignored truth\n            p_assigned (float): probability of a predicted box not being\n                assigned\n            p_use_label (float | bool): with labels or not\n            rng (None | int | numpy.random.RandomState): seed or state\n\n        Returns:\n            :obj:`AssignResult`: Randomly generated assign results.\n\n        Example:\n            >>> from mmcv.core.bbox.assigners.assign_result import *  # NOQA\n            >>> self = AssignResult.random()\n            >>> print(self.info)\n        \"\"\"\n        from mmcv.core.bbox import demodata\n        rng = demodata.ensure_rng(kwargs.get('rng', None))\n\n        num_gts = kwargs.get('num_gts', None)\n        num_preds = kwargs.get('num_preds', None)\n        p_ignore = kwargs.get('p_ignore', 0.3)\n        p_assigned = kwargs.get('p_assigned', 0.7)\n        p_use_label = kwargs.get('p_use_label', 0.5)\n        num_classes = kwargs.get('p_use_label', 3)\n\n        if num_gts is None:\n            num_gts = rng.randint(0, 8)\n        if num_preds is None:\n            num_preds = rng.randint(0, 16)\n\n        if num_gts == 0:\n            max_overlaps = torch.zeros(num_preds, dtype=torch.float32)\n            gt_inds = torch.zeros(num_preds, dtype=torch.int64)\n            if p_use_label is True or p_use_label < rng.rand():\n                labels = torch.zeros(num_preds, dtype=torch.int64)\n            else:\n                labels = None\n        else:\n            import numpy as np\n            # Create an overlap for each predicted box\n            max_overlaps = torch.from_numpy(rng.rand(num_preds))\n\n            # Construct gt_inds for each predicted box\n            is_assigned = torch.from_numpy(rng.rand(num_preds) < p_assigned)\n            # maximum number of assignments constraints\n            n_assigned = min(num_preds, min(num_gts, is_assigned.sum()))\n\n            assigned_idxs = np.where(is_assigned)[0]\n            rng.shuffle(assigned_idxs)\n            assigned_idxs = assigned_idxs[0:n_assigned]\n            assigned_idxs.sort()\n\n            is_assigned[:] = 0\n            is_assigned[assigned_idxs] = True\n\n            is_ignore = torch.from_numpy(\n                rng.rand(num_preds) < p_ignore) & is_assigned\n\n            gt_inds = torch.zeros(num_preds, dtype=torch.int64)\n\n            true_idxs = np.arange(num_gts)\n            rng.shuffle(true_idxs)\n            true_idxs = torch.from_numpy(true_idxs)\n            gt_inds[is_assigned] = true_idxs[:n_assigned]\n\n            gt_inds = torch.from_numpy(\n                rng.randint(1, num_gts + 1, size=num_preds))\n            gt_inds[is_ignore] = -1\n            gt_inds[~is_assigned] = 0\n            max_overlaps[~is_assigned] = 0\n\n            if p_use_label is True or p_use_label < rng.rand():\n                if num_classes == 0:\n                    labels = torch.zeros(num_preds, dtype=torch.int64)\n                else:\n                    labels = torch.from_numpy(\n                        # remind that we set FG labels to [0, num_class-1]\n                        # since mmcv v2.0\n                        # BG cat_id: num_class\n                        rng.randint(0, num_classes, size=num_preds))\n                    labels[~is_assigned] = 0\n            else:\n                labels = None\n\n        self = cls(num_gts, gt_inds, max_overlaps, labels)\n        return self\n\n    def add_gt_(self, gt_labels):\n        \"\"\"Add ground truth as assigned results.\n\n        Args:\n            gt_labels (torch.Tensor): Labels of gt boxes\n        \"\"\"\n        self_inds = torch.arange(\n            1, len(gt_labels) + 1, dtype=torch.long, device=gt_labels.device)\n        self.gt_inds = torch.cat([self_inds, self.gt_inds])\n\n        self.max_overlaps = torch.cat(\n            [self.max_overlaps.new_ones(len(gt_labels)), self.max_overlaps])\n\n        if self.labels is not None:\n            self.labels = torch.cat([gt_labels, self.labels])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/base_assigner.py",
    "content": "from abc import ABCMeta, abstractmethod\n\n\nclass BaseAssigner(metaclass=ABCMeta):\n    \"\"\"Base assigner that assigns boxes to ground truth boxes.\"\"\"\n\n    @abstractmethod\n    def assign(self, bboxes, gt_bboxes, gt_bboxes_ignore=None, gt_labels=None):\n        \"\"\"Assign boxes to either a ground truth boxes or a negative boxes.\"\"\"\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/hungarian_assigner.py",
    "content": "import torch\n\nfrom ..builder import BBOX_ASSIGNERS\nfrom ..match_costs import build_match_cost\nfrom ..transforms import bbox_cxcywh_to_xyxy\nfrom .assign_result import AssignResult\nfrom .base_assigner import BaseAssigner\n\ntry:\n    from scipy.optimize import linear_sum_assignment\nexcept ImportError:\n    linear_sum_assignment = None\n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianAssigner(BaseAssigner):\n    \"\"\"Computes one-to-one matching between predictions and ground truth.\n\n    This class computes an assignment between the targets and the predictions\n    based on the costs. The costs are weighted sum of three components:\n    classification cost, regression L1 cost and regression iou cost. The\n    targets don't include the no_object, so generally there are more\n    predictions than targets. After the one-to-one matching, the un-matched\n    are treated as backgrounds. Thus each query prediction will be assigned\n    with `0` or a positive integer indicating the ground truth index:\n\n    - 0: negative sample, no assigned gt\n    - positive integer: positive sample, index (1-based) of assigned gt\n\n    Args:\n        cls_weight (int | float, optional): The scale factor for classification\n            cost. Default 1.0.\n        bbox_weight (int | float, optional): The scale factor for regression\n            L1 cost. Default 1.0.\n        iou_weight (int | float, optional): The scale factor for regression\n            iou cost. Default 1.0.\n        iou_calculator (dict | optional): The config for the iou calculation.\n            Default type `BboxOverlaps2D`.\n        iou_mode (str | optional): \"iou\" (intersection over union), \"iof\"\n                (intersection over foreground), or \"giou\" (generalized\n                intersection over union). Default \"giou\".\n    \"\"\"\n\n    def __init__(self,\n                 cls_cost=dict(type='ClassificationCost', weight=1.),\n                 reg_cost=dict(type='BBoxL1Cost', weight=1.0),\n                 iou_cost=dict(type='IoUCost', iou_mode='giou', weight=1.0)):\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n        self.iou_cost = build_match_cost(iou_cost)\n\n    def assign(self,\n               bbox_pred,\n               cls_pred,\n               gt_bboxes,\n               gt_labels,\n               img_meta,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"Computes one-to-one matching based on the weighted costs.\n\n        This method assign each query prediction to a ground truth or\n        background. The `assigned_gt_inds` with -1 means don't care,\n        0 means negative sample, and positive number is the index (1-based)\n        of assigned gt.\n        The assignment is done in the following steps, the order matters.\n\n        1. assign every prediction to -1\n        2. compute the weighted costs\n        3. do Hungarian matching on CPU based on the costs\n        4. assign all to 0 (background) first, then for each matched pair\n           between predictions and gts, treat this prediction as foreground\n           and assign the corresponding gt index (plus 1) to it.\n\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n            img_meta (dict): Meta information for current image.\n            gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                labelled as `ignored`. Default None.\n            eps (int | float, optional): A value added to the denominator for\n                numerical stability. Default 1e-7.\n\n        Returns:\n            :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)\n\n        # 1. assign -1 by default\n        assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),\n                                              -1,\n                                              dtype=torch.long)\n        assigned_labels = bbox_pred.new_full((num_bboxes, ),\n                                             -1,\n                                             dtype=torch.long)\n        if num_gts == 0 or num_bboxes == 0:\n            # No ground truth or boxes, return empty assignment\n            if num_gts == 0:\n                # No ground truth, assign all to background\n                assigned_gt_inds[:] = 0\n            return AssignResult(\n                num_gts, assigned_gt_inds, None, labels=assigned_labels)\n        img_h, img_w, _ = img_meta['img_shape']\n        factor = gt_bboxes.new_tensor([img_w, img_h, img_w,\n                                       img_h]).unsqueeze(0)\n\n        # 2. compute the weighted costs\n        # classification and bboxcost.\n        cls_cost = self.cls_cost(cls_pred, gt_labels)\n        # regression L1 cost\n        normalize_gt_bboxes = gt_bboxes / factor\n        reg_cost = self.reg_cost(bbox_pred, normalize_gt_bboxes)\n        # regression iou cost, defaultly giou is used in official DETR.\n        bboxes = bbox_cxcywh_to_xyxy(bbox_pred) * factor\n        iou_cost = self.iou_cost(bboxes, gt_bboxes)\n        # weighted sum of above three costs\n        cost = cls_cost + reg_cost + iou_cost\n\n        # 3. do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu()\n        if linear_sum_assignment is None:\n            raise ImportError('Please run \"pip install scipy\" '\n                              'to install scipy first.')\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        matched_row_inds = torch.from_numpy(matched_row_inds).to(\n            bbox_pred.device)\n        matched_col_inds = torch.from_numpy(matched_col_inds).to(\n            bbox_pred.device)\n\n        # 4. assign backgrounds and foregrounds\n        # assign all indices to backgrounds first\n        assigned_gt_inds[:] = 0\n        # assign foregrounds based on matching results\n        assigned_gt_inds[matched_row_inds] = matched_col_inds + 1\n        assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]\n        return AssignResult(\n            num_gts, assigned_gt_inds, None, labels=assigned_labels)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/hungarian_assigner_3d.py",
    "content": "import torch\n\nfrom mmcv.core.bbox.builder import BBOX_ASSIGNERS\nfrom .assign_result import AssignResult\nfrom .base_assigner import BaseAssigner\nfrom mmcv.core.bbox.match_costs import build_match_cost\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.core.bbox.util import normalize_bbox\n\ntry:\n    from scipy.optimize import linear_sum_assignment\nexcept ImportError:\n    linear_sum_assignment = None\n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianAssigner3D(BaseAssigner):\n    \"\"\"Computes one-to-one matching between predictions and ground truth.\n    This class computes an assignment between the targets and the predictions\n    based on the costs. The costs are weighted sum of three components:\n    classification cost, regression L1 cost and regression iou cost. The\n    targets don't include the no_object, so generally there are more\n    predictions than targets. After the one-to-one matching, the un-matched\n    are treated as backgrounds. Thus each query prediction will be assigned\n    with `0` or a positive integer indicating the ground truth index:\n    - 0: negative sample, no assigned gt\n    - positive integer: positive sample, index (1-based) of assigned gt\n    Args:\n        cls_weight (int | float, optional): The scale factor for classification\n            cost. Default 1.0.\n        bbox_weight (int | float, optional): The scale factor for regression\n            L1 cost. Default 1.0.\n        iou_weight (int | float, optional): The scale factor for regression\n            iou cost. Default 1.0.\n        iou_calculator (dict | optional): The config for the iou calculation.\n            Default type `BboxOverlaps2D`.\n        iou_mode (str | optional): \"iou\" (intersection over union), \"iof\"\n                (intersection over foreground), or \"giou\" (generalized\n                intersection over union). Default \"giou\".\n    \"\"\"\n\n    def __init__(self,\n                 cls_cost=dict(type='ClassificationCost', weight=1.),\n                 reg_cost=dict(type='BBoxL1Cost', weight=1.0),\n                 iou_cost=dict(type='IoUCost', weight=0.0),\n                 pc_range=None):\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n        self.iou_cost = build_match_cost(iou_cost)\n        self.pc_range = pc_range\n\n    def assign(self,\n               bbox_pred,\n               cls_pred,\n               gt_bboxes, \n               gt_labels,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"Computes one-to-one matching based on the weighted costs.\n        This method assign each query prediction to a ground truth or\n        background. The `assigned_gt_inds` with -1 means don't care,\n        0 means negative sample, and positive number is the index (1-based)\n        of assigned gt.\n        The assignment is done in the following steps, the order matters.\n        1. assign every prediction to -1\n        2. compute the weighted costs\n        3. do Hungarian matching on CPU based on the costs\n        4. assign all to 0 (background) first, then for each matched pair\n           between predictions and gts, treat this prediction as foreground\n           and assign the corresponding gt index (plus 1) to it.\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n            gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                labelled as `ignored`. Default None.\n            eps (int | float, optional): A value added to the denominator for\n                numerical stability. Default 1e-7.\n        Returns:\n            :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)\n\n        # 1. assign -1 by default\n        assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),\n                                              -1,\n                                              dtype=torch.long)\n        assigned_labels = bbox_pred.new_full((num_bboxes, ),\n                                             -1,\n                                             dtype=torch.long)\n        if num_gts == 0 or num_bboxes == 0:\n            # No ground truth or boxes, return empty assignment\n            if num_gts == 0:\n                # No ground truth, assign all to background\n                assigned_gt_inds[:] = 0\n            return AssignResult(\n                num_gts, assigned_gt_inds, None, labels=assigned_labels)\n\n        # 2. compute the weighted costs\n        # classification and bboxcost.\n        cls_cost = self.cls_cost(cls_pred, gt_labels)\n        # regression L1 cost\n       \n        normalized_gt_bboxes = normalize_bbox(gt_bboxes, self.pc_range)\n    \n        reg_cost = self.reg_cost(bbox_pred[:, :8], normalized_gt_bboxes[:, :8])\n      \n        # weighted sum of above two costs\n        cost = cls_cost + reg_cost\n        \n        # 3. do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu()\n        if linear_sum_assignment is None:\n            raise ImportError('Please run \"pip install scipy\" '\n                              'to install scipy first.')\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        matched_row_inds = torch.from_numpy(matched_row_inds).to(\n            bbox_pred.device)\n        matched_col_inds = torch.from_numpy(matched_col_inds).to(\n            bbox_pred.device)\n\n        # 4. assign backgrounds and foregrounds\n        # assign all indices to backgrounds first\n        assigned_gt_inds[:] = 0\n        # assign foregrounds based on matching results\n        assigned_gt_inds[matched_row_inds] = matched_col_inds + 1\n        assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]\n        return AssignResult(\n            num_gts, assigned_gt_inds, None, labels=assigned_labels)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/hungarian_assigner_3d_track.py",
    "content": "import numpy as np\nimport torch\n\nfrom mmcv.core.bbox.builder import BBOX_ASSIGNERS\nfrom mmcv.core.bbox.assigners.base_assigner import BaseAssigner\nfrom mmcv.core.bbox.match_costs import build_match_cost\ntry:\n    from scipy.optimize import linear_sum_assignment\nexcept ImportError:\n    linear_sum_assignment = None\n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianAssigner3DTrack(BaseAssigner):\n    \"\"\"Computes one-to-one matching between predictions and ground truth.\n    This class computes an assignment between the targets and the predictions\n    based on the costs. The costs are weighted sum of three components:\n    classification cost, regression L1 cost and regression iou cost. The\n    targets don't include the no_object, so generally there are more\n    predictions than targets. After the one-to-one matching, the un-matched\n    are treated as backgrounds. Thus each query prediction will be assigned\n    with `0` or a positive integer indicating the ground truth index:\n    - 0: negative sample, no assigned gt\n    - positive integer: positive sample, index (1-based) of assigned gt\n    Args:\n        cls_weight (int | float, optional): The scale factor for classification\n            cost. Default 1.0.\n        bbox_weight (int | float, optional): The scale factor for regression\n            L1 cost. Default 1.0.\n    \"\"\"\n\n    def __init__(self,\n                 cls_cost=dict(type='ClassificationCost', weight=1.),\n                 reg_cost=dict(type='BBoxL1Cost', weight=1.0),\n                 pc_range=None):\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n        self.pc_range = pc_range\n\n    def assign(self,\n               bbox_pred,\n               cls_pred,\n               gt_bboxes, \n               gt_labels,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"Computes one-to-one matching based on the weighted costs.\n        This method assign each query prediction to a ground truth or\n        background. The `assigned_gt_inds` with -1 means don't care,\n        0 means negative sample, and positive number is the index (1-based)\n        of assigned gt.\n        The assignment is done in the following steps, the order matters.\n        1. assign every prediction to -1\n        2. compute the weighted costs\n        3. do Hungarian matching on CPU based on the costs\n        4. assign all to 0 (background) first, then for each matched pair\n           between predictions and gts, treat this prediction as foreground\n           and assign the corresponding gt index (plus 1) to it.\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n            gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                labelled as `ignored`. Default None.\n            eps (int | float, optional): A value added to the denominator for\n                numerical stability. Default 1e-7.\n        Returns:\n            :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)\n\n        # 1. assign -1 by default\n        assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),\n                                              -1,\n                                              dtype=torch.long)\n        assigned_labels = bbox_pred.new_full((num_bboxes, ),\n                                             -1,\n                                             dtype=torch.long)\n        if num_gts == 0 or num_bboxes == 0:\n            # No ground truth or boxes, return empty assignment\n            if num_gts == 0:\n                # No ground truth, assign all to background\n                assigned_gt_inds[:] = 0\n            return (None, None)\n        # 2. compute the weighted costs\n        # classification and bboxcost.\n        cls_cost = self.cls_cost(cls_pred, gt_labels)\n        # regression L1 cost\n        reg_cost = self.reg_cost(bbox_pred[:, :8], gt_bboxes[:, :8])\n        # weighted sum of above three costs\n        cost = cls_cost + reg_cost\n\n        cost = torch.nan_to_num(cost)\n\n        # 3. do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu()\n        if linear_sum_assignment is None:\n            raise ImportError('Please run \"pip install scipy\" '\n                              'to install scipy first.')\n        cost = np.nan_to_num(cost)\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        matched_row_inds = torch.from_numpy(matched_row_inds).to(\n            bbox_pred.device)\n        matched_col_inds = torch.from_numpy(matched_col_inds).to(\n            bbox_pred.device)\n\n        # 4. assign backgrounds and foregrounds\n        # assign all indices to backgrounds first\n        assigned_gt_inds[:] = 0\n        # assign foregrounds based on matching results\n        assigned_gt_inds[matched_row_inds] = matched_col_inds + 1\n        assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]\n        \n        return (matched_row_inds, matched_col_inds)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/assigners/map_hungarian_assigner_3d.py",
    "content": "import torch\nimport torch.nn.functional as F\n\nfrom mmcv.core.bbox.builder import BBOX_ASSIGNERS\nfrom mmcv.core.bbox.assigners.assign_result import AssignResult\nfrom mmcv.core.bbox.assigners.base_assigner import BaseAssigner\nfrom mmcv.core.bbox.match_costs import build_match_cost\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.models.vad_utils.map_utils import (\n    normalize_2d_bbox, normalize_2d_pts, denormalize_2d_bbox\n)\n\ntry:\n    from scipy.optimize import linear_sum_assignment\nexcept ImportError:\n    linear_sum_assignment = None\n\n@BBOX_ASSIGNERS.register_module()\nclass MapHungarianAssigner3D(BaseAssigner):\n    \"\"\"Computes one-to-one matching between predictions and ground truth.\n    This class computes an assignment between the targets and the predictions\n    based on the costs. The costs are weighted sum of three components:\n    classification cost, regression L1 cost and regression iou cost. The\n    targets don't include the no_object, so generally there are more\n    predictions than targets. After the one-to-one matching, the un-matched\n    are treated as backgrounds. Thus each query prediction will be assigned\n    with `0` or a positive integer indicating the ground truth index:\n    - 0: negative sample, no assigned gt\n    - positive integer: positive sample, index (1-based) of assigned gt\n    Args:\n        cls_weight (int | float, optional): The scale factor for classification\n            cost. Default 1.0.\n        bbox_weight (int | float, optional): The scale factor for regression\n            L1 cost. Default 1.0.\n        iou_weight (int | float, optional): The scale factor for regression\n            iou cost. Default 1.0.\n        iou_calculator (dict | optional): The config for the iou calculation.\n            Default type `BboxOverlaps2D`.\n        iou_mode (str | optional): \"iou\" (intersection over union), \"iof\"\n                (intersection over foreground), or \"giou\" (generalized\n                intersection over union). Default \"giou\".\n    \"\"\"\n\n    def __init__(self,\n                 cls_cost=dict(type='ClassificationCost', weight=1.),\n                 reg_cost=dict(type='BBoxL1Cost', weight=1.0),\n                 iou_cost=dict(type='IoUCost', weight=0.0),\n                 pts_cost=dict(type='ChamferDistance',loss_src_weight=1.0,loss_dst_weight=1.0),\n                 pc_range=None):\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n        self.iou_cost = build_match_cost(iou_cost)\n        self.pts_cost = build_match_cost(pts_cost)\n        self.pc_range = pc_range\n\n    def assign(self,\n               bbox_pred,\n               cls_pred,\n               pts_pred,\n               gt_bboxes, \n               gt_labels,\n               gt_pts,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"Computes one-to-one matching based on the weighted costs.\n        This method assign each query prediction to a ground truth or\n        background. The `assigned_gt_inds` with -1 means don't care,\n        0 means negative sample, and positive number is the index (1-based)\n        of assigned gt.\n        The assignment is done in the following steps, the order matters.\n        1. assign every prediction to -1\n        2. compute the weighted costs\n        3. do Hungarian matching on CPU based on the costs\n        4. assign all to 0 (background) first, then for each matched pair\n           between predictions and gts, treat this prediction as foreground\n           and assign the corresponding gt index (plus 1) to it.\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n            gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                labelled as `ignored`. Default None.\n            eps (int | float, optional): A value added to the denominator for\n                numerical stability. Default 1e-7.\n        Returns:\n            :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        assert bbox_pred.shape[-1] == 4, \\\n            'Only support bbox pred shape is 4 dims'\n        num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)\n\n        # 1. assign -1 by default\n        assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),\n                                              -1,\n                                              dtype=torch.long)\n        assigned_labels = bbox_pred.new_full((num_bboxes, ),\n                                             -1,\n                                             dtype=torch.long)\n        if num_gts == 0 or num_bboxes == 0:\n            # No ground truth or boxes, return empty assignment\n            if num_gts == 0:\n                # No ground truth, assign all to background\n                assigned_gt_inds[:] = 0\n            return AssignResult(\n                num_gts, assigned_gt_inds, None, labels=assigned_labels), None\n\n        # 2. compute the weighted costs\n        # classification and bboxcost.\n        cls_cost = self.cls_cost(cls_pred, gt_labels)\n        # regression L1 cost\n        \n        normalized_gt_bboxes = normalize_2d_bbox(gt_bboxes, self.pc_range)\n        # normalized_gt_bboxes = gt_bboxes\n        # import pdb;pdb.set_trace()\n        reg_cost = self.reg_cost(bbox_pred[:, :4], normalized_gt_bboxes[:, :4])\n\n        _, num_orders, num_pts_per_gtline, num_coords = gt_pts.shape\n        normalized_gt_pts = normalize_2d_pts(gt_pts, self.pc_range)\n        num_pts_per_predline = pts_pred.size(1)\n        if num_pts_per_predline != num_pts_per_gtline:\n            pts_pred_interpolated = F.interpolate(pts_pred.permute(0,2,1),size=(num_pts_per_gtline),\n                                            mode='linear', align_corners=True)\n            pts_pred_interpolated = pts_pred_interpolated.permute(0,2,1).contiguous()\n        else:\n            pts_pred_interpolated = pts_pred\n        # num_q, num_pts, 2 <-> num_gt, num_pts, 2\n        pts_cost_ordered = self.pts_cost(pts_pred_interpolated, normalized_gt_pts)\n        pts_cost_ordered = pts_cost_ordered.view(num_bboxes, num_gts, num_orders)\n        pts_cost, order_index = torch.min(pts_cost_ordered, 2)\n        \n        bboxes = denormalize_2d_bbox(bbox_pred, self.pc_range)\n        iou_cost = self.iou_cost(bboxes, gt_bboxes)\n        # weighted sum of above three costs\n        cost = cls_cost + reg_cost + iou_cost + pts_cost\n        \n        # 3. do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu()\n        if linear_sum_assignment is None:\n            raise ImportError('Please run \"pip install scipy\" '\n                              'to install scipy first.')\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        matched_row_inds = torch.from_numpy(matched_row_inds).to(\n            bbox_pred.device)\n        matched_col_inds = torch.from_numpy(matched_col_inds).to(\n            bbox_pred.device)\n\n        # 4. assign backgrounds and foregrounds\n        # assign all indices to backgrounds first\n        assigned_gt_inds[:] = 0\n        # assign foregrounds based on matching results\n        assigned_gt_inds[matched_row_inds] = matched_col_inds + 1\n        assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]\n        return AssignResult(\n            num_gts, assigned_gt_inds, None, labels=assigned_labels), order_index"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/box_np_ops.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n# TODO: clean the functions in this file and move the APIs into box structures\n# in the future\n\nimport numba\nimport numpy as np\n\n\ndef camera_to_lidar(points, r_rect, velo2cam):\n    \"\"\"Convert points in camera coordinate to lidar coordinate.\n\n    Args:\n        points (np.ndarray, shape=[N, 3]): Points in camera coordinate.\n        r_rect (np.ndarray, shape=[4, 4]): Matrix to project points in\n            specific camera coordinate (e.g. CAM2) to CAM0.\n        velo2cam (np.ndarray, shape=[4, 4]): Matrix to project points in\n            camera coordinate to lidar coordinate.\n\n    Returns:\n        np.ndarray, shape=[N, 3]: Points in lidar coordinate.\n    \"\"\"\n    points_shape = list(points.shape[0:-1])\n    if points.shape[-1] == 3:\n        points = np.concatenate([points, np.ones(points_shape + [1])], axis=-1)\n    lidar_points = points @ np.linalg.inv((r_rect @ velo2cam).T)\n    return lidar_points[..., :3]\n\n\ndef box_camera_to_lidar(data, r_rect, velo2cam):\n    \"\"\"Covert boxes in camera coordinate to lidar coordinate.\n\n    Args:\n        data (np.ndarray, shape=[N, 7]): Boxes in camera coordinate.\n        r_rect (np.ndarray, shape=[4, 4]): Matrix to project points in\n            specific camera coordinate (e.g. CAM2) to CAM0.\n        velo2cam (np.ndarray, shape=[4, 4]): Matrix to project points in\n            camera coordinate to lidar coordinate.\n\n    Returns:\n        np.ndarray, shape=[N, 3]: Boxes in lidar coordinate.\n    \"\"\"\n    xyz = data[:, 0:3]\n    l, h, w = data[:, 3:4], data[:, 4:5], data[:, 5:6]\n    r = data[:, 6:7]\n    xyz_lidar = camera_to_lidar(xyz, r_rect, velo2cam)\n    return np.concatenate([xyz_lidar, w, l, h, r], axis=1)\n\n\ndef corners_nd(dims, origin=0.5):\n    \"\"\"Generate relative box corners based on length per dim and origin point.\n\n    Args:\n        dims (np.ndarray, shape=[N, ndim]): Array of length per dim\n        origin (list or array or float, optional): origin point relate to\n            smallest point. Defaults to 0.5\n\n    Returns:\n        np.ndarray, shape=[N, 2 ** ndim, ndim]: Returned corners.\n        point layout example: (2d) x0y0, x0y1, x1y0, x1y1;\n            (3d) x0y0z0, x0y0z1, x0y1z0, x0y1z1, x1y0z0, x1y0z1, x1y1z0, x1y1z1\n            where x0 < x1, y0 < y1, z0 < z1.\n    \"\"\"\n    ndim = int(dims.shape[1])\n    corners_norm = np.stack(\n        np.unravel_index(np.arange(2**ndim), [2] * ndim),\n        axis=1).astype(dims.dtype)\n    # now corners_norm has format: (2d) x0y0, x0y1, x1y0, x1y1\n    # (3d) x0y0z0, x0y0z1, x0y1z0, x0y1z1, x1y0z0, x1y0z1, x1y1z0, x1y1z1\n    # so need to convert to a format which is convenient to do other computing.\n    # for 2d boxes, format is clockwise start with minimum point\n    # for 3d boxes, please draw lines by your hand.\n    if ndim == 2:\n        # generate clockwise box corners\n        corners_norm = corners_norm[[0, 1, 3, 2]]\n    elif ndim == 3:\n        corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n    corners_norm = corners_norm - np.array(origin, dtype=dims.dtype)\n    corners = dims.reshape([-1, 1, ndim]) * corners_norm.reshape(\n        [1, 2**ndim, ndim])\n    return corners\n\n\ndef rotation_2d(points, angles):\n    \"\"\"Rotation 2d points based on origin point clockwise when angle positive.\n\n    Args:\n        points (np.ndarray): Points to be rotated with shape \\\n            (N, point_size, 2).\n        angles (np.ndarray): Rotation angle with shape (N).\n\n    Returns:\n        np.ndarray: Same shape as points.\n    \"\"\"\n    rot_sin = np.sin(angles)\n    rot_cos = np.cos(angles)\n    rot_mat_T = np.stack([[rot_cos, -rot_sin], [rot_sin, rot_cos]])\n    return np.einsum('aij,jka->aik', points, rot_mat_T)\n\n\ndef center_to_corner_box2d(centers, dims, angles=None, origin=0.5):\n    \"\"\"Convert kitti locations, dimensions and angles to corners.\n    format: center(xy), dims(xy), angles(clockwise when positive)\n\n    Args:\n        centers (np.ndarray): Locations in kitti label file with shape (N, 2).\n        dims (np.ndarray): Dimensions in kitti label file with shape (N, 2).\n        angles (np.ndarray, optional): Rotation_y in kitti label file with\n            shape (N). Defaults to None.\n        origin (list or array or float, optional): origin point relate to\n            smallest point. Defaults to 0.5.\n\n    Returns:\n        np.ndarray: Corners with the shape of (N, 4, 2).\n    \"\"\"\n    # 'length' in kitti format is in x axis.\n    # xyz(hwl)(kitti label file)<->xyz(lhw)(camera)<->z(-x)(-y)(wlh)(lidar)\n    # center in kitti format is [0.5, 1.0, 0.5] in xyz.\n    corners = corners_nd(dims, origin=origin)\n    # corners: [N, 4, 2]\n    if angles is not None:\n        corners = rotation_2d(corners, angles)\n    corners += centers.reshape([-1, 1, 2])\n    return corners\n\n\n@numba.jit(nopython=True)\ndef depth_to_points(depth, trunc_pixel):\n    \"\"\"Convert depth map to points.\n\n    Args:\n        depth (np.array, shape=[H, W]): Depth map which\n            the row of [0~`trunc_pixel`] are truncated.\n        trunc_pixel (int): The number of truncated row.\n\n    Returns:\n        np.ndarray: Points in camera coordinates.\n    \"\"\"\n    num_pts = np.sum(depth[trunc_pixel:, ] > 0.1)\n    points = np.zeros((num_pts, 3), dtype=depth.dtype)\n    x = np.array([0, 0, 1], dtype=depth.dtype)\n    k = 0\n    for i in range(trunc_pixel, depth.shape[0]):\n        for j in range(depth.shape[1]):\n            if depth[i, j] > 0.1:\n                x = np.array([j, i, 1], dtype=depth.dtype)\n                points[k] = x * depth[i, j]\n                k += 1\n    return points\n\n\ndef depth_to_lidar_points(depth, trunc_pixel, P2, r_rect, velo2cam):\n    \"\"\"Convert depth map to points in lidar coordinate.\n\n    Args:\n        depth (np.array, shape=[H, W]): Depth map which\n            the row of [0~`trunc_pixel`] are truncated.\n        trunc_pixel (int): The number of truncated row.\n        P2 (p.array, shape=[4, 4]): Intrinsics of Camera2.\n        r_rect (np.ndarray, shape=[4, 4]): Matrix to project points in\n            specific camera coordinate (e.g. CAM2) to CAM0.\n        velo2cam (np.ndarray, shape=[4, 4]): Matrix to project points in\n            camera coordinate to lidar coordinate.\n\n    Returns:\n        np.ndarray: Points in lidar coordinates.\n    \"\"\"\n    pts = depth_to_points(depth, trunc_pixel)\n    points_shape = list(pts.shape[0:-1])\n    points = np.concatenate([pts, np.ones(points_shape + [1])], axis=-1)\n    points = points @ np.linalg.inv(P2.T)\n    lidar_points = camera_to_lidar(points, r_rect, velo2cam)\n    return lidar_points\n\n\ndef rotation_3d_in_axis(points, angles, axis=0):\n    \"\"\"Rotate points in specific axis.\n\n    Args:\n        points (np.ndarray, shape=[N, point_size, 3]]):\n        angles (np.ndarray, shape=[N]]):\n        axis (int, optional): Axis to rotate at. Defaults to 0.\n\n    Returns:\n        np.ndarray: Rotated points.\n    \"\"\"\n    # points: [N, point_size, 3]\n    rot_sin = np.sin(angles)\n    rot_cos = np.cos(angles)\n    ones = np.ones_like(rot_cos)\n    zeros = np.zeros_like(rot_cos)\n    if axis == 1:\n        rot_mat_T = np.stack([[rot_cos, zeros, -rot_sin], [zeros, ones, zeros],\n                              [rot_sin, zeros, rot_cos]])\n    elif axis == 2 or axis == -1:\n        rot_mat_T = np.stack([[rot_cos, -rot_sin, zeros],\n                              [rot_sin, rot_cos, zeros], [zeros, zeros, ones]])\n    elif axis == 0:\n        rot_mat_T = np.stack([[zeros, rot_cos, -rot_sin],\n                              [zeros, rot_sin, rot_cos], [ones, zeros, zeros]])\n    else:\n        raise ValueError('axis should in range')\n\n    return np.einsum('aij,jka->aik', points, rot_mat_T)\n\n\ndef center_to_corner_box3d(centers,\n                           dims,\n                           angles=None,\n                           origin=(0.5, 1.0, 0.5),\n                           axis=1):\n    \"\"\"Convert kitti locations, dimensions and angles to corners.\n\n    Args:\n        centers (np.ndarray): Locations in kitti label file with shape (N, 3).\n        dims (np.ndarray): Dimensions in kitti label file with shape (N, 3).\n        angles (np.ndarray, optional): Rotation_y in kitti label file with\n            shape (N). Defaults to None.\n        origin (list or array or float, optional): Origin point relate to\n            smallest point. Use (0.5, 1.0, 0.5) in camera and (0.5, 0.5, 0)\n            in lidar. Defaults to (0.5, 1.0, 0.5).\n        axis (int, optional): Rotation axis. 1 for camera and 2 for lidar.\n            Defaults to 1.\n\n    Returns:\n        np.ndarray: Corners with the shape of (N, 8, 3).\n    \"\"\"\n    # 'length' in kitti format is in x axis.\n    # yzx(hwl)(kitti label file)<->xyz(lhw)(camera)<->z(-x)(-y)(wlh)(lidar)\n    # center in kitti format is [0.5, 1.0, 0.5] in xyz.\n    corners = corners_nd(dims, origin=origin)\n    # corners: [N, 8, 3]\n    if angles is not None:\n        corners = rotation_3d_in_axis(corners, angles, axis=axis)\n    corners += centers.reshape([-1, 1, 3])\n    return corners\n\n\n@numba.jit(nopython=True)\ndef box2d_to_corner_jit(boxes):\n    \"\"\"Convert box2d to corner.\n\n    Args:\n        boxes (np.ndarray, shape=[N, 5]): Boxes2d with rotation.\n\n    Returns:\n        box_corners (np.ndarray, shape=[N, 4, 2]): Box corners.\n    \"\"\"\n    num_box = boxes.shape[0]\n    corners_norm = np.zeros((4, 2), dtype=boxes.dtype)\n    corners_norm[1, 1] = 1.0\n    corners_norm[2] = 1.0\n    corners_norm[3, 0] = 1.0\n    corners_norm -= np.array([0.5, 0.5], dtype=boxes.dtype)\n    corners = boxes.reshape(num_box, 1, 5)[:, :, 2:4] * corners_norm.reshape(\n        1, 4, 2)\n    rot_mat_T = np.zeros((2, 2), dtype=boxes.dtype)\n    box_corners = np.zeros((num_box, 4, 2), dtype=boxes.dtype)\n    for i in range(num_box):\n        rot_sin = np.sin(boxes[i, -1])\n        rot_cos = np.cos(boxes[i, -1])\n        rot_mat_T[0, 0] = rot_cos\n        rot_mat_T[0, 1] = -rot_sin\n        rot_mat_T[1, 0] = rot_sin\n        rot_mat_T[1, 1] = rot_cos\n        box_corners[i] = corners[i] @ rot_mat_T + boxes[i, :2]\n    return box_corners\n\n\n@numba.njit\ndef corner_to_standup_nd_jit(boxes_corner):\n    \"\"\"Convert boxes_corner to aligned (min-max) boxes.\n\n    Args:\n        boxes_corner (np.ndarray, shape=[N, 2**dim, dim]): Boxes corners.\n\n    Returns:\n        np.ndarray, shape=[N, dim*2]: Aligned (min-max) boxes.\n    \"\"\"\n    num_boxes = boxes_corner.shape[0]\n    ndim = boxes_corner.shape[-1]\n    result = np.zeros((num_boxes, ndim * 2), dtype=boxes_corner.dtype)\n    for i in range(num_boxes):\n        for j in range(ndim):\n            result[i, j] = np.min(boxes_corner[i, :, j])\n        for j in range(ndim):\n            result[i, j + ndim] = np.max(boxes_corner[i, :, j])\n    return result\n\n\n@numba.jit(nopython=True)\ndef corner_to_surfaces_3d_jit(corners):\n    \"\"\"Convert 3d box corners from corner function above to surfaces that\n    normal vectors all direct to internal.\n\n    Args:\n        corners (np.ndarray): 3d box corners with the shape of (N, 8, 3).\n\n    Returns:\n        np.ndarray: Surfaces with the shape of (N, 6, 4, 3).\n    \"\"\"\n    # box_corners: [N, 8, 3], must from corner functions in this module\n    num_boxes = corners.shape[0]\n    surfaces = np.zeros((num_boxes, 6, 4, 3), dtype=corners.dtype)\n    corner_idxes = np.array([\n        0, 1, 2, 3, 7, 6, 5, 4, 0, 3, 7, 4, 1, 5, 6, 2, 0, 4, 5, 1, 3, 2, 6, 7\n    ]).reshape(6, 4)\n    for i in range(num_boxes):\n        for j in range(6):\n            for k in range(4):\n                surfaces[i, j, k] = corners[i, corner_idxes[j, k]]\n    return surfaces\n\n\ndef rotation_points_single_angle(points, angle, axis=0):\n    \"\"\"Rotate points with a single angle.\n\n    Args:\n        points (np.ndarray, shape=[N, 3]]):\n        angle (np.ndarray, shape=[1]]):\n        axis (int, optional): Axis to rotate at. Defaults to 0.\n\n    Returns:\n        np.ndarray: Rotated points.\n    \"\"\"\n    # points: [N, 3]\n    rot_sin = np.sin(angle)\n    rot_cos = np.cos(angle)\n    if axis == 1:\n        rot_mat_T = np.array(\n            [[rot_cos, 0, -rot_sin], [0, 1, 0], [rot_sin, 0, rot_cos]],\n            dtype=points.dtype)\n    elif axis == 2 or axis == -1:\n        rot_mat_T = np.array(\n            [[rot_cos, -rot_sin, 0], [rot_sin, rot_cos, 0], [0, 0, 1]],\n            dtype=points.dtype)\n    elif axis == 0:\n        rot_mat_T = np.array(\n            [[1, 0, 0], [0, rot_cos, -rot_sin], [0, rot_sin, rot_cos]],\n            dtype=points.dtype)\n    else:\n        raise ValueError('axis should in range')\n\n    return points @ rot_mat_T, rot_mat_T\n\n\ndef points_cam2img(points_3d, proj_mat, with_depth=False):\n    \"\"\"Project points in camera coordinates to image coordinates.\n\n    Args:\n        points_3d (np.ndarray): Points in shape (N, 3)\n        proj_mat (np.ndarray): Transformation matrix between coordinates.\n        with_depth (bool, optional): Whether to keep depth in the output.\n            Defaults to False.\n\n    Returns:\n        np.ndarray: Points in image coordinates with shape [N, 2].\n    \"\"\"\n    points_shape = list(points_3d.shape)\n    points_shape[-1] = 1\n\n    assert len(proj_mat.shape) == 2, 'The dimension of the projection'\\\n        f' matrix should be 2 instead of {len(proj_mat.shape)}.'\n    d1, d2 = proj_mat.shape[:2]\n    assert (d1 == 3 and d2 == 3) or (d1 == 3 and d2 == 4) or (\n        d1 == 4 and d2 == 4), 'The shape of the projection matrix'\\\n        f' ({d1}*{d2}) is not supported.'\n    if d1 == 3:\n        proj_mat_expanded = np.eye(4, dtype=proj_mat.dtype)\n        proj_mat_expanded[:d1, :d2] = proj_mat\n        proj_mat = proj_mat_expanded\n\n    points_4 = np.concatenate([points_3d, np.ones(points_shape)], axis=-1)\n    point_2d = points_4 @ proj_mat.T\n    point_2d_res = point_2d[..., :2] / point_2d[..., 2:3]\n\n    if with_depth:\n        points_2d_depth = np.concatenate([point_2d_res, point_2d[..., 2:3]],\n                                         axis=-1)\n        return points_2d_depth\n\n    return point_2d_res\n\n\ndef box3d_to_bbox(box3d, P2):\n    \"\"\"Convert box3d in camera coordinates to bbox in image coordinates.\n\n    Args:\n        box3d (np.ndarray, shape=[N, 7]): Boxes in camera coordinate.\n        P2 (np.array, shape=[4, 4]): Intrinsics of Camera2.\n\n    Returns:\n        np.ndarray, shape=[N, 4]: Boxes 2d in image coordinates.\n    \"\"\"\n    box_corners = center_to_corner_box3d(\n        box3d[:, :3], box3d[:, 3:6], box3d[:, 6], [0.5, 1.0, 0.5], axis=1)\n    box_corners_in_image = points_cam2img(box_corners, P2)\n    # box_corners_in_image: [N, 8, 2]\n    minxy = np.min(box_corners_in_image, axis=1)\n    maxxy = np.max(box_corners_in_image, axis=1)\n    bbox = np.concatenate([minxy, maxxy], axis=1)\n    return bbox\n\n\ndef corner_to_surfaces_3d(corners):\n    \"\"\"convert 3d box corners from corner function above to surfaces that\n    normal vectors all direct to internal.\n\n    Args:\n        corners (np.ndarray): 3D box corners with shape of (N, 8, 3).\n\n    Returns:\n        np.ndarray: Surfaces with the shape of (N, 6, 4, 3).\n    \"\"\"\n    # box_corners: [N, 8, 3], must from corner functions in this module\n    surfaces = np.array([\n        [corners[:, 0], corners[:, 1], corners[:, 2], corners[:, 3]],\n        [corners[:, 7], corners[:, 6], corners[:, 5], corners[:, 4]],\n        [corners[:, 0], corners[:, 3], corners[:, 7], corners[:, 4]],\n        [corners[:, 1], corners[:, 5], corners[:, 6], corners[:, 2]],\n        [corners[:, 0], corners[:, 4], corners[:, 5], corners[:, 1]],\n        [corners[:, 3], corners[:, 2], corners[:, 6], corners[:, 7]],\n    ]).transpose([2, 0, 1, 3])\n    return surfaces\n\n\ndef points_in_rbbox(points, rbbox, z_axis=2, origin=(0.5, 0.5, 0)):\n    \"\"\"Check points in rotated bbox and return indicces.\n\n    Args:\n        points (np.ndarray, shape=[N, 3+dim]): Points to query.\n        rbbox (np.ndarray, shape=[M, 7]): Boxes3d with rotation.\n        z_axis (int, optional): Indicate which axis is height.\n            Defaults to 2.\n        origin (tuple[int], optional): Indicate the position of\n            box center. Defaults to (0.5, 0.5, 0).\n\n    Returns:\n        np.ndarray, shape=[N, M]: Indices of points in each box.\n    \"\"\"\n    # TODO: this function is different from PointCloud3D, be careful\n    # when start to use nuscene, check the input\n    rbbox_corners = center_to_corner_box3d(\n        rbbox[:, :3], rbbox[:, 3:6], rbbox[:, 6], origin=origin, axis=z_axis)\n    surfaces = corner_to_surfaces_3d(rbbox_corners)\n    indices = points_in_convex_polygon_3d_jit(points[:, :3], surfaces)\n    return indices\n\n\ndef minmax_to_corner_2d(minmax_box):\n    \"\"\"Convert minmax box to corners2d.\n\n    Args:\n        minmax_box (np.ndarray, shape=[N, dims]): minmax boxes.\n\n    Returns:\n        np.ndarray: 2d corners of boxes\n    \"\"\"\n    ndim = minmax_box.shape[-1] // 2\n    center = minmax_box[..., :ndim]\n    dims = minmax_box[..., ndim:] - center\n    return center_to_corner_box2d(center, dims, origin=0.0)\n\n\ndef limit_period(val, offset=0.5, period=np.pi):\n    \"\"\"Limit the value into a period for periodic function.\n\n    Args:\n        val (np.ndarray): The value to be converted.\n        offset (float, optional): Offset to set the value range. \\\n            Defaults to 0.5.\n        period (float, optional): Period of the value. Defaults to np.pi.\n\n    Returns:\n        torch.Tensor: Value in the range of \\\n            [-offset * period, (1-offset) * period]\n    \"\"\"\n    return val - np.floor(val / period + offset) * period\n\n\ndef create_anchors_3d_range(feature_size,\n                            anchor_range,\n                            sizes=((1.6, 3.9, 1.56), ),\n                            rotations=(0, np.pi / 2),\n                            dtype=np.float32):\n    \"\"\"Create anchors 3d by range.\n\n    Args:\n        feature_size (list[float] | tuple[float]): Feature map size. It is\n            either a list of a tuple of [D, H, W](in order of z, y, and x).\n        anchor_range (torch.Tensor | list[float]): Range of anchors with\n            shape [6]. The order is consistent with that of anchors, i.e.,\n            (x_min, y_min, z_min, x_max, y_max, z_max).\n        sizes (list[list] | np.ndarray | torch.Tensor, optional):\n            Anchor size with shape [N, 3], in order of x, y, z.\n            Defaults to ((1.6, 3.9, 1.56), ).\n        rotations (list[float] | np.ndarray | torch.Tensor, optional):\n            Rotations of anchors in a single feature grid.\n            Defaults to (0, np.pi / 2).\n        dtype (type, optional): Data type. Default to np.float32.\n\n    Returns:\n        np.ndarray: Range based anchors with shape of \\\n            (*feature_size, num_sizes, num_rots, 7).\n    \"\"\"\n    anchor_range = np.array(anchor_range, dtype)\n    z_centers = np.linspace(\n        anchor_range[2], anchor_range[5], feature_size[0], dtype=dtype)\n    y_centers = np.linspace(\n        anchor_range[1], anchor_range[4], feature_size[1], dtype=dtype)\n    x_centers = np.linspace(\n        anchor_range[0], anchor_range[3], feature_size[2], dtype=dtype)\n    sizes = np.reshape(np.array(sizes, dtype=dtype), [-1, 3])\n    rotations = np.array(rotations, dtype=dtype)\n    rets = np.meshgrid(\n        x_centers, y_centers, z_centers, rotations, indexing='ij')\n    tile_shape = [1] * 5\n    tile_shape[-2] = int(sizes.shape[0])\n    for i in range(len(rets)):\n        rets[i] = np.tile(rets[i][..., np.newaxis, :], tile_shape)\n        rets[i] = rets[i][..., np.newaxis]  # for concat\n    sizes = np.reshape(sizes, [1, 1, 1, -1, 1, 3])\n    tile_size_shape = list(rets[0].shape)\n    tile_size_shape[3] = 1\n    sizes = np.tile(sizes, tile_size_shape)\n    rets.insert(3, sizes)\n    ret = np.concatenate(rets, axis=-1)\n    return np.transpose(ret, [2, 1, 0, 3, 4, 5])\n\n\ndef center_to_minmax_2d(centers, dims, origin=0.5):\n    \"\"\"Center to minmax.\n\n    Args:\n        centers (np.ndarray): Center points.\n        dims (np.ndarray): Dimensions.\n        origin (list or array or float, optional): Origin point relate\n            to smallest point. Defaults to 0.5.\n\n    Returns:\n        np.ndarray: Minmax points.\n    \"\"\"\n    if origin == 0.5:\n        return np.concatenate([centers - dims / 2, centers + dims / 2],\n                              axis=-1)\n    corners = center_to_corner_box2d(centers, dims, origin=origin)\n    return corners[:, [0, 2]].reshape([-1, 4])\n\n\ndef rbbox2d_to_near_bbox(rbboxes):\n    \"\"\"convert rotated bbox to nearest 'standing' or 'lying' bbox.\n\n    Args:\n        rbboxes (np.ndarray): Rotated bboxes with shape of \\\n            (N, 5(x, y, xdim, ydim, rad)).\n\n    Returns:\n        np.ndarray: Bounding boxes with the shpae of\n            (N, 4(xmin, ymin, xmax, ymax)).\n    \"\"\"\n    rots = rbboxes[..., -1]\n    rots_0_pi_div_2 = np.abs(limit_period(rots, 0.5, np.pi))\n    cond = (rots_0_pi_div_2 > np.pi / 4)[..., np.newaxis]\n    bboxes_center = np.where(cond, rbboxes[:, [0, 1, 3, 2]], rbboxes[:, :4])\n    bboxes = center_to_minmax_2d(bboxes_center[:, :2], bboxes_center[:, 2:])\n    return bboxes\n\n\n@numba.jit(nopython=True)\ndef iou_jit(boxes, query_boxes, mode='iou', eps=0.0):\n    \"\"\"Calculate box iou. Note that jit version runs ~10x faster than the\n    box_overlaps function in mmdet3d.core.evaluation.\n\n    Args:\n        boxes (np.ndarray): Input bounding boxes with shape of (N, 4).\n        query_boxes (np.ndarray): Query boxes with shape of (K, 4).\n        mode (str, optional): IoU mode. Defaults to 'iou'.\n        eps (float, optional): Value added to denominator. Defaults to 0.\n\n    Returns:\n        np.ndarray: Overlap between boxes and query_boxes\n            with the shape of [N, K].\n    \"\"\"\n    N = boxes.shape[0]\n    K = query_boxes.shape[0]\n    overlaps = np.zeros((N, K), dtype=boxes.dtype)\n    for k in range(K):\n        box_area = ((query_boxes[k, 2] - query_boxes[k, 0] + eps) *\n                    (query_boxes[k, 3] - query_boxes[k, 1] + eps))\n        for n in range(N):\n            iw = (\n                min(boxes[n, 2], query_boxes[k, 2]) -\n                max(boxes[n, 0], query_boxes[k, 0]) + eps)\n            if iw > 0:\n                ih = (\n                    min(boxes[n, 3], query_boxes[k, 3]) -\n                    max(boxes[n, 1], query_boxes[k, 1]) + eps)\n                if ih > 0:\n                    if mode == 'iou':\n                        ua = ((boxes[n, 2] - boxes[n, 0] + eps) *\n                              (boxes[n, 3] - boxes[n, 1] + eps) + box_area -\n                              iw * ih)\n                    else:\n                        ua = ((boxes[n, 2] - boxes[n, 0] + eps) *\n                              (boxes[n, 3] - boxes[n, 1] + eps))\n                    overlaps[n, k] = iw * ih / ua\n    return overlaps\n\n\ndef projection_matrix_to_CRT_kitti(proj):\n    \"\"\"Split projection matrix of kitti.\n\n    P = C @ [R|T]\n    C is upper triangular matrix, so we need to inverse CR and use QR\n    stable for all kitti camera projection matrix.\n\n    Args:\n        proj (p.array, shape=[4, 4]): Intrinsics of camera.\n\n    Returns:\n        tuple[np.ndarray]: Splited matrix of C, R and T.\n    \"\"\"\n\n    CR = proj[0:3, 0:3]\n    CT = proj[0:3, 3]\n    RinvCinv = np.linalg.inv(CR)\n    Rinv, Cinv = np.linalg.qr(RinvCinv)\n    C = np.linalg.inv(Cinv)\n    R = np.linalg.inv(Rinv)\n    T = Cinv @ CT\n    return C, R, T\n\n\ndef remove_outside_points(points, rect, Trv2c, P2, image_shape):\n    \"\"\"Remove points which are outside of image.\n\n    Args:\n        points (np.ndarray, shape=[N, 3+dims]): Total points.\n        rect (np.ndarray, shape=[4, 4]): Matrix to project points in\n            specific camera coordinate (e.g. CAM2) to CAM0.\n        Trv2c (np.ndarray, shape=[4, 4]): Matrix to project points in\n            camera coordinate to lidar coordinate.\n        P2 (p.array, shape=[4, 4]): Intrinsics of Camera2.\n        image_shape (list[int]): Shape of image.\n\n    Returns:\n        np.ndarray, shape=[N, 3+dims]: Filtered points.\n    \"\"\"\n    # 5x faster than remove_outside_points_v1(2ms vs 10ms)\n    C, R, T = projection_matrix_to_CRT_kitti(P2)\n    image_bbox = [0, 0, image_shape[1], image_shape[0]]\n    frustum = get_frustum(image_bbox, C)\n    frustum -= T\n    frustum = np.linalg.inv(R) @ frustum.T\n    frustum = camera_to_lidar(frustum.T, rect, Trv2c)\n    frustum_surfaces = corner_to_surfaces_3d_jit(frustum[np.newaxis, ...])\n    indices = points_in_convex_polygon_3d_jit(points[:, :3], frustum_surfaces)\n    points = points[indices.reshape([-1])]\n    return points\n\n\ndef get_frustum(bbox_image, C, near_clip=0.001, far_clip=100):\n    \"\"\"Get frustum corners in camera coordinates.\n\n    Args:\n        bbox_image (list[int]): box in image coordinates.\n        C (np.ndarray): Intrinsics.\n        near_clip (float, optional): Nearest distance of frustum.\n            Defaults to 0.001.\n        far_clip (float, optional): Farthest distance of frustum.\n            Defaults to 100.\n\n    Returns:\n        np.ndarray, shape=[8, 3]: coordinates of frustum corners.\n    \"\"\"\n    fku = C[0, 0]\n    fkv = -C[1, 1]\n    u0v0 = C[0:2, 2]\n    z_points = np.array(\n        [near_clip] * 4 + [far_clip] * 4, dtype=C.dtype)[:, np.newaxis]\n    b = bbox_image\n    box_corners = np.array(\n        [[b[0], b[1]], [b[0], b[3]], [b[2], b[3]], [b[2], b[1]]],\n        dtype=C.dtype)\n    near_box_corners = (box_corners - u0v0) / np.array(\n        [fku / near_clip, -fkv / near_clip], dtype=C.dtype)\n    far_box_corners = (box_corners - u0v0) / np.array(\n        [fku / far_clip, -fkv / far_clip], dtype=C.dtype)\n    ret_xy = np.concatenate([near_box_corners, far_box_corners],\n                            axis=0)  # [8, 2]\n    ret_xyz = np.concatenate([ret_xy, z_points], axis=1)\n    return ret_xyz\n\n\ndef surface_equ_3d(polygon_surfaces):\n    \"\"\"\n\n    Args:\n        polygon_surfaces (np.ndarray): Polygon surfaces with shape of\n            [num_polygon, max_num_surfaces, max_num_points_of_surface, 3].\n            All surfaces' normal vector must direct to internal.\n            Max_num_points_of_surface must at least 3.\n\n    Returns:\n        tuple: normal vector and its direction.\n    \"\"\"\n    # return [a, b, c], d in ax+by+cz+d=0\n    # polygon_surfaces: [num_polygon, num_surfaces, num_points_of_polygon, 3]\n    surface_vec = polygon_surfaces[:, :, :2, :] - \\\n        polygon_surfaces[:, :, 1:3, :]\n    # normal_vec: [..., 3]\n    normal_vec = np.cross(surface_vec[:, :, 0, :], surface_vec[:, :, 1, :])\n    # print(normal_vec.shape, points[..., 0, :].shape)\n    # d = -np.inner(normal_vec, points[..., 0, :])\n    d = np.einsum('aij, aij->ai', normal_vec, polygon_surfaces[:, :, 0, :])\n    return normal_vec, -d\n\n\n@numba.njit\ndef _points_in_convex_polygon_3d_jit(points, polygon_surfaces, normal_vec, d,\n                                     num_surfaces):\n    \"\"\"\n    Args:\n        points (np.ndarray): Input points with shape of (num_points, 3).\n        polygon_surfaces (np.ndarray): Polygon surfaces with shape of\n            (num_polygon, max_num_surfaces, max_num_points_of_surface, 3).\n            All surfaces' normal vector must direct to internal.\n            Max_num_points_of_surface must at least 3.\n        normal_vec (np.ndarray): Normal vector of polygon_surfaces.\n        d (int): Directions of normal vector.\n        num_surfaces (np.ndarray): Number of surfaces a polygon contains\n            shape of (num_polygon).\n\n    Returns:\n        np.ndarray: Result matrix with the shape of [num_points, num_polygon].\n    \"\"\"\n    max_num_surfaces, max_num_points_of_surface = polygon_surfaces.shape[1:3]\n    num_points = points.shape[0]\n    num_polygons = polygon_surfaces.shape[0]\n    ret = np.ones((num_points, num_polygons), dtype=np.bool_)\n    sign = 0.0\n    for i in range(num_points):\n        for j in range(num_polygons):\n            for k in range(max_num_surfaces):\n                if k > num_surfaces[j]:\n                    break\n                sign = (\n                    points[i, 0] * normal_vec[j, k, 0] +\n                    points[i, 1] * normal_vec[j, k, 1] +\n                    points[i, 2] * normal_vec[j, k, 2] + d[j, k])\n                if sign >= 0:\n                    ret[i, j] = False\n                    break\n    return ret\n\n\ndef points_in_convex_polygon_3d_jit(points,\n                                    polygon_surfaces,\n                                    num_surfaces=None):\n    \"\"\"Check points is in 3d convex polygons.\n\n    Args:\n        points (np.ndarray): Input points with shape of (num_points, 3).\n        polygon_surfaces (np.ndarray): Polygon surfaces with shape of\n            (num_polygon, max_num_surfaces, max_num_points_of_surface, 3).\n            All surfaces' normal vector must direct to internal.\n            Max_num_points_of_surface must at least 3.\n        num_surfaces (np.ndarray, optional): Number of surfaces a polygon\n            contains shape of (num_polygon). Defaults to None.\n\n    Returns:\n        np.ndarray: Result matrix with the shape of [num_points, num_polygon].\n    \"\"\"\n    max_num_surfaces, max_num_points_of_surface = polygon_surfaces.shape[1:3]\n    # num_points = points.shape[0]\n    num_polygons = polygon_surfaces.shape[0]\n    if num_surfaces is None:\n        num_surfaces = np.full((num_polygons, ), 9999999, dtype=np.int64)\n    normal_vec, d = surface_equ_3d(polygon_surfaces[:, :, :3, :])\n    # normal_vec: [num_polygon, max_num_surfaces, 3]\n    # d: [num_polygon, max_num_surfaces]\n    return _points_in_convex_polygon_3d_jit(points, polygon_surfaces,\n                                            normal_vec, d, num_surfaces)\n\n\n@numba.jit\ndef points_in_convex_polygon_jit(points, polygon, clockwise=True):\n    \"\"\"Check points is in 2d convex polygons. True when point in polygon.\n\n    Args:\n        points (np.ndarray): Input points with the shape of [num_points, 2].\n        polygon (np.ndarray): Input polygon with the shape of\n            [num_polygon, num_points_of_polygon, 2].\n        clockwise (bool, optional): Indicate polygon is clockwise. Defaults\n            to True.\n\n    Returns:\n        np.ndarray: Result matrix with the shape of [num_points, num_polygon].\n    \"\"\"\n    # first convert polygon to directed lines\n    num_points_of_polygon = polygon.shape[1]\n    num_points = points.shape[0]\n    num_polygons = polygon.shape[0]\n    # if clockwise:\n    #     vec1 = polygon - polygon[:, [num_points_of_polygon - 1] +\n    #                              list(range(num_points_of_polygon - 1)), :]\n    # else:\n    #     vec1 = polygon[:, [num_points_of_polygon - 1] +\n    #                    list(range(num_points_of_polygon - 1)), :] - polygon\n    # vec1: [num_polygon, num_points_of_polygon, 2]\n    vec1 = np.zeros((2), dtype=polygon.dtype)\n    ret = np.zeros((num_points, num_polygons), dtype=np.bool_)\n    success = True\n    cross = 0.0\n    for i in range(num_points):\n        for j in range(num_polygons):\n            success = True\n            for k in range(num_points_of_polygon):\n                if clockwise:\n                    vec1 = polygon[j, k] - polygon[j, k - 1]\n                else:\n                    vec1 = polygon[j, k - 1] - polygon[j, k]\n                cross = vec1[1] * (polygon[j, k, 0] - points[i, 0])\n                cross -= vec1[0] * (polygon[j, k, 1] - points[i, 1])\n                if cross >= 0:\n                    success = False\n                    break\n            ret[i, j] = success\n    return ret\n\n\ndef boxes3d_to_corners3d_lidar(boxes3d, bottom_center=True):\n    \"\"\"Convert kitti center boxes to corners.\n\n        7 -------- 4\n       /|         /|\n      6 -------- 5 .\n      | |        | |\n      . 3 -------- 0\n      |/         |/\n      2 -------- 1\n\n    Args:\n        boxes3d (np.ndarray): Boxes with shape of (N, 7)\n            [x, y, z, w, l, h, ry] in LiDAR coords, see the definition of ry\n            in KITTI dataset.\n        bottom_center (bool, optional): Whether z is on the bottom center\n            of object. Defaults to True.\n\n    Returns:\n        np.ndarray: Box corners with the shape of [N, 8, 3].\n    \"\"\"\n    boxes_num = boxes3d.shape[0]\n    w, l, h = boxes3d[:, 3], boxes3d[:, 4], boxes3d[:, 5]\n    x_corners = np.array(\n        [w / 2., -w / 2., -w / 2., w / 2., w / 2., -w / 2., -w / 2., w / 2.],\n        dtype=np.float32).T\n    y_corners = np.array(\n        [-l / 2., -l / 2., l / 2., l / 2., -l / 2., -l / 2., l / 2., l / 2.],\n        dtype=np.float32).T\n    if bottom_center:\n        z_corners = np.zeros((boxes_num, 8), dtype=np.float32)\n        z_corners[:, 4:8] = h.reshape(boxes_num, 1).repeat(4, axis=1)  # (N, 8)\n    else:\n        z_corners = np.array([\n            -h / 2., -h / 2., -h / 2., -h / 2., h / 2., h / 2., h / 2., h / 2.\n        ],\n                             dtype=np.float32).T\n\n    ry = boxes3d[:, 6]\n    zeros, ones = np.zeros(\n        ry.size, dtype=np.float32), np.ones(\n            ry.size, dtype=np.float32)\n    rot_list = np.array([[np.cos(ry), -np.sin(ry), zeros],\n                         [np.sin(ry), np.cos(ry), zeros], [zeros, zeros,\n                                                           ones]])  # (3, 3, N)\n    R_list = np.transpose(rot_list, (2, 0, 1))  # (N, 3, 3)\n\n    temp_corners = np.concatenate((x_corners.reshape(\n        -1, 8, 1), y_corners.reshape(-1, 8, 1), z_corners.reshape(-1, 8, 1)),\n                                  axis=2)  # (N, 8, 3)\n    rotated_corners = np.matmul(temp_corners, R_list)  # (N, 8, 3)\n    x_corners = rotated_corners[:, :, 0]\n    y_corners = rotated_corners[:, :, 1]\n    z_corners = rotated_corners[:, :, 2]\n\n    x_loc, y_loc, z_loc = boxes3d[:, 0], boxes3d[:, 1], boxes3d[:, 2]\n\n    x = x_loc.reshape(-1, 1) + x_corners.reshape(-1, 8)\n    y = y_loc.reshape(-1, 1) + y_corners.reshape(-1, 8)\n    z = z_loc.reshape(-1, 1) + z_corners.reshape(-1, 8)\n\n    corners = np.concatenate(\n        (x.reshape(-1, 8, 1), y.reshape(-1, 8, 1), z.reshape(-1, 8, 1)),\n        axis=2)\n\n    return corners.astype(np.float32)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/builder.py",
    "content": "from mmcv.utils import Registry, build_from_cfg\n\nBBOX_ASSIGNERS = Registry('bbox_assigner')\nBBOX_SAMPLERS = Registry('bbox_sampler')\nBBOX_CODERS = Registry('bbox_coder')\n\n\ndef build_assigner(cfg, **default_args):\n    \"\"\"Builder of box assigner.\"\"\"\n    return build_from_cfg(cfg, BBOX_ASSIGNERS, default_args)\n\n\ndef build_sampler(cfg, **default_args):\n    \"\"\"Builder of box sampler.\"\"\"\n    return build_from_cfg(cfg, BBOX_SAMPLERS, default_args)\n\n\ndef build_bbox_coder(cfg, **default_args):\n    \"\"\"Builder of box coder.\"\"\"\n    return build_from_cfg(cfg, BBOX_CODERS, default_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/coder/__init__.py",
    "content": "from .nms_free_coder import NMSFreeCoder\nfrom .detr3d_track_coder import DETRTrack3DCoder\nfrom mmcv.core.bbox import build_bbox_coder\nfrom .fut_nms_free_coder import CustomNMSFreeCoder\nfrom .map_nms_free_coder import MapNMSFreeCoder\n\n__all__ = [\n    'build_bbox_coder', \n    'NMSFreeCoder', 'DETRTrack3DCoder',\n    'CustomNMSFreeCoder','MapNMSFreeCoder'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/coder/base_bbox_coder.py",
    "content": "from abc import ABCMeta, abstractmethod\n\n\nclass BaseBBoxCoder(metaclass=ABCMeta):\n    \"\"\"Base bounding box coder.\"\"\"\n\n    def __init__(self, **kwargs):\n        pass\n\n    @abstractmethod\n    def encode(self, bboxes, gt_bboxes):\n        \"\"\"Encode deltas between bboxes and ground truth boxes.\"\"\"\n\n    @abstractmethod\n    def decode(self, bboxes, bboxes_pred):\n        \"\"\"Decode the predicted bboxes according to prediction and base\n        boxes.\"\"\"\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/coder/detr3d_track_coder.py",
    "content": "import torch\n\nfrom mmcv.core.bbox.coder.base_bbox_coder import BaseBBoxCoder\nfrom mmcv.core.bbox.builder import BBOX_CODERS\nfrom ..util import normalize_bbox, denormalize_bbox\nfrom ..structures.utils import xywhr2xyxyr\nfrom mmcv.ops.iou3d import nms_bev\n\n@BBOX_CODERS.register_module()\nclass DETRTrack3DCoder(BaseBBoxCoder):\n    \"\"\"Bbox coder for DETR3D.\n    Args:\n        pc_range (list[float]): Range of point cloud.\n        post_center_range (list[float]): Limit of the center.\n            Default: None.\n        max_num (int): Max number to be kept. Default: 100.\n        score_threshold (float): Threshold to filter boxes based on score.\n            Default: None.\n        code_size (int): Code size of bboxes. Default: 9\n    \"\"\"\n\n    def __init__(self,\n                 pc_range,\n                 post_center_range=None,\n                 max_num=100,\n                 score_threshold=0.2,\n                 num_classes=7,\n                 with_nms=False,\n                 iou_thres=0.3):\n        \n        self.pc_range = pc_range\n        self.post_center_range = post_center_range\n        self.max_num = max_num\n        self.score_threshold = score_threshold\n        self.num_classes = num_classes\n        self.with_nms = with_nms\n        self.nms_iou_thres = iou_thres\n\n    def encode(self):\n        pass\n\n    def decode_single(self, cls_scores, bbox_preds, \n                      track_scores, obj_idxes, with_mask=True, img_metas=None):\n        \"\"\"Decode bboxes.\n        Args:\n            cls_scores (Tensor): Outputs from the classification head, \\\n                shape [num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            bbox_preds (Tensor): Outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [num_query, 9].\n\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        max_num = self.max_num\n        max_num = min(cls_scores.size(0), self.max_num)\n\n        cls_scores = cls_scores.sigmoid()\n        _, indexs = cls_scores.max(dim=-1)\n        labels = indexs % self.num_classes\n\n        _, bbox_index = track_scores.topk(max_num)\n        \n        labels = labels[bbox_index]\n        bbox_preds = bbox_preds[bbox_index]\n        track_scores = track_scores[bbox_index]\n        obj_idxes = obj_idxes[bbox_index]\n\n        scores = track_scores\n        \n        final_box_preds = denormalize_bbox(bbox_preds, self.pc_range)   \n        final_scores = track_scores\n        final_preds = labels\n\n        # use score threshold\n        if self.score_threshold is not None:\n            thresh_mask = final_scores > self.score_threshold\n\n        if self.with_nms:\n            boxes_for_nms = xywhr2xyxyr(img_metas[0]['box_type_3d'](final_box_preds[:, :], 9).bev)\n            nms_mask = boxes_for_nms.new_zeros(boxes_for_nms.shape[0]) > 0\n            # print(self.nms_iou_thres)\n            try:\n                selected = nms_bev(\n                    boxes_for_nms,\n                    final_scores,\n                    thresh=self.nms_iou_thres)\n                nms_mask[selected] = True\n            except:\n                print('Error', boxes_for_nms, final_scores)\n                nms_mask = boxes_for_nms.new_ones(boxes_for_nms.shape[0]) > 0\n        if self.post_center_range is not None:\n            self.post_center_range = torch.tensor(\n                self.post_center_range, device=scores.device)\n            mask = (final_box_preds[..., :3] >=\n                    self.post_center_range[:3]).all(1)\n            mask &= (final_box_preds[..., :3] <=\n                     self.post_center_range[3:]).all(1)\n\n            if self.score_threshold:\n                mask &= thresh_mask\n            if not with_mask:\n                mask = torch.ones_like(mask) > 0\n            if self.with_nms:\n                mask &= nms_mask\n\n            boxes3d = final_box_preds[mask]\n            scores = final_scores[mask]\n            labels = final_preds[mask]\n            track_scores = track_scores[mask]\n            obj_idxes = obj_idxes[mask]\n            predictions_dict = {\n                'bboxes': boxes3d,\n                'scores': scores,\n                'labels': labels,\n                'track_scores': track_scores,\n                'obj_idxes': obj_idxes,\n                'bbox_index': bbox_index,\n                'mask': mask\n            }\n\n        else:\n            raise NotImplementedError(\n                'Need to reorganize output as a batch, only '\n                'support post_center_range is not None for now!')\n        return predictions_dict\n\n    def decode(self, preds_dicts, with_mask=True, img_metas=None):\n        \"\"\"Decode bboxes.\n        Args:\n            cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n                Note: before sigmoid!\n            bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        all_cls_scores = preds_dicts['cls_scores']\n        all_bbox_preds = preds_dicts['bbox_preds']\n        track_scores = preds_dicts['track_scores']\n        obj_idxes = preds_dicts['obj_idxes']\n        \n        batch_size = all_cls_scores.size()[0]\n        predictions_list = []\n        # bs size = 1\n        predictions_list.append(self.decode_single(\n            all_cls_scores, all_bbox_preds,\n            track_scores, obj_idxes, with_mask, img_metas))\n        #for i in range(batch_size):\n        #    predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i]))\n        return predictions_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/coder/fut_nms_free_coder.py",
    "content": "import torch\n\nfrom mmcv.core.bbox.coder.base_bbox_coder import BaseBBoxCoder\nfrom mmcv.core.bbox.builder import BBOX_CODERS\nfrom mmcv.core.bbox.util import denormalize_bbox\nimport numpy as np\n\n\n@BBOX_CODERS.register_module()\nclass CustomNMSFreeCoder(BaseBBoxCoder):\n    \"\"\"Bbox coder for NMS-free detector.\n    Args:\n        pc_range (list[float]): Range of point cloud.\n        post_center_range (list[float]): Limit of the center.\n            Default: None.\n        max_num (int): Max number to be kept. Default: 100.\n        score_threshold (float): Threshold to filter boxes based on score.\n            Default: None.\n        code_size (int): Code size of bboxes. Default: 9\n    \"\"\"\n\n    def __init__(self,\n                 pc_range,\n                 voxel_size=None,\n                 post_center_range=None,\n                 max_num=100,\n                 score_threshold=None,\n                 num_classes=10):\n        self.pc_range = pc_range\n        self.voxel_size = voxel_size\n        self.post_center_range = post_center_range\n        self.max_num = max_num\n        self.score_threshold = score_threshold\n        self.num_classes = num_classes\n\n    def encode(self):\n\n        pass\n\n    def decode_single(self, cls_scores, bbox_preds, traj_preds):\n        \"\"\"Decode bboxes.\n        Args:\n            cls_scores (Tensor): Outputs from the classification head, \\\n                shape [num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            bbox_preds (Tensor): Outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [num_query, 9].\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        max_num = self.max_num\n\n        cls_scores = cls_scores.sigmoid()\n        scores, indexs = cls_scores.view(-1).topk(max_num)\n        labels = indexs % self.num_classes\n        bbox_index = indexs // self.num_classes\n        bbox_preds = bbox_preds[bbox_index]\n        traj_preds = traj_preds[bbox_index]\n       \n        final_box_preds = denormalize_bbox(bbox_preds, self.pc_range)   \n        final_scores = scores \n        final_preds = labels\n        final_traj_preds = traj_preds\n\n        # use score threshold\n        if self.score_threshold is not None:\n            thresh_mask = final_scores > self.score_threshold\n            tmp_score = self.score_threshold\n            while thresh_mask.sum() == 0:\n                tmp_score *= 0.9\n                if tmp_score < 0.01:\n                    thresh_mask = final_scores > -1\n                    break\n                thresh_mask = final_scores >= tmp_score\n\n        if self.post_center_range is not None:\n            self.post_center_range = torch.tensor(\n                self.post_center_range, device=scores.device)\n            mask = (final_box_preds[..., :3] >=\n                    self.post_center_range[:3]).all(1)\n            mask &= (final_box_preds[..., :3] <=\n                     self.post_center_range[3:]).all(1)\n\n            if self.score_threshold:\n                mask &= thresh_mask\n\n            boxes3d = final_box_preds[mask]\n            scores = final_scores[mask]\n            labels = final_preds[mask]\n            trajs = final_traj_preds[mask]\n\n            predictions_dict = {\n                'bboxes': boxes3d,\n                'scores': scores,\n                'labels': labels,\n                'trajs': trajs\n            }\n\n        else:\n            raise NotImplementedError(\n                'Need to reorganize output as a batch, only '\n                'support post_center_range is not None for now!')\n        return predictions_dict\n\n    def decode(self, preds_dicts):\n        \"\"\"Decode bboxes.\n        Args:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        all_cls_scores = preds_dicts['all_cls_scores'][-1]\n        all_bbox_preds = preds_dicts['all_bbox_preds'][-1]\n        all_traj_preds = preds_dicts['all_traj_preds'][-1]\n        \n        batch_size = all_cls_scores.size()[0]\n        predictions_list = []\n        for i in range(batch_size):\n            predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i], all_traj_preds[i]))\n        return predictions_list\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/coder/map_nms_free_coder.py",
    "content": "import torch\n\nfrom mmcv.core.bbox.coder.base_bbox_coder import BaseBBoxCoder\nfrom mmcv.core.bbox.builder import BBOX_CODERS\nfrom mmcv.models.vad_utils.map_utils import (\n    denormalize_2d_pts, denormalize_2d_bbox\n)\n\n\n@BBOX_CODERS.register_module()\nclass MapNMSFreeCoder(BaseBBoxCoder):\n    \"\"\"Bbox coder for NMS-free detector.\n    Args:\n        pc_range (list[float]): Range of point cloud.\n        post_center_range (list[float]): Limit of the center.\n            Default: None.\n        max_num (int): Max number to be kept. Default: 100.\n        score_threshold (float): Threshold to filter boxes based on score.\n            Default: None.\n        code_size (int): Code size of bboxes. Default: 9\n    \"\"\"\n\n    def __init__(self,\n                 pc_range,\n                 voxel_size=None,\n                 post_center_range=None,\n                 max_num=100,\n                 score_threshold=None,\n                 num_classes=10):\n        self.pc_range = pc_range\n        self.voxel_size = voxel_size\n        self.post_center_range = post_center_range\n        self.max_num = max_num\n        self.score_threshold = score_threshold\n        self.num_classes = num_classes\n\n    def encode(self):\n\n        pass\n\n    def decode_single(self, cls_scores, bbox_preds, pts_preds):\n        \"\"\"Decode bboxes.\n        Args:\n            cls_scores (Tensor): Outputs from the classification head, \\\n                shape [num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            bbox_preds (Tensor): Outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [num_query, 9].\n            pts_preds (Tensor):\n                Shape [num_query, fixed_num_pts, 2]\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        max_num = self.max_num\n\n        cls_scores = cls_scores.sigmoid()\n        scores, indexs = cls_scores.view(-1).topk(max_num)\n        labels = indexs % self.num_classes\n        bbox_index = indexs // self.num_classes\n        bbox_preds = bbox_preds[bbox_index]\n        pts_preds = pts_preds[bbox_index]\n       \n        final_box_preds = denormalize_2d_bbox(bbox_preds, self.pc_range) \n        final_pts_preds = denormalize_2d_pts(pts_preds, self.pc_range) #num_q,num_p,2\n        # final_box_preds = bbox_preds \n        final_scores = scores \n        final_preds = labels \n\n        # use score threshold\n        if self.score_threshold is not None:\n            thresh_mask = final_scores > self.score_threshold\n            tmp_score = self.score_threshold\n            while thresh_mask.sum() == 0:\n                tmp_score *= 0.9\n                if tmp_score < 0.01:\n                    thresh_mask = final_scores > -1\n                    break\n                thresh_mask = final_scores >= tmp_score\n\n        if self.post_center_range is not None:\n            self.post_center_range = torch.tensor(\n                self.post_center_range, device=scores.device)\n            mask = (final_box_preds[..., :4] >= self.post_center_range[:4]).all(1)\n            mask &= (final_box_preds[..., :4] <= self.post_center_range[4:]).all(1)\n\n            if self.score_threshold:\n                mask &= thresh_mask\n\n            boxes3d = final_box_preds[mask]\n            scores = final_scores[mask]\n            pts = final_pts_preds[mask]\n            labels = final_preds[mask]\n            predictions_dict = {\n                'map_bboxes': boxes3d,\n                'map_scores': scores,\n                'map_labels': labels,\n                'map_pts': pts,\n            }\n\n        else:\n            raise NotImplementedError(\n                'Need to reorganize output as a batch, only '\n                'support post_center_range is not None for now!')\n        return predictions_dict\n\n    def decode(self, preds_dicts):\n        \"\"\"Decode bboxes.\n        Args:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        all_cls_scores = preds_dicts['map_all_cls_scores'][-1]\n        all_bbox_preds = preds_dicts['map_all_bbox_preds'][-1]\n        all_pts_preds = preds_dicts['map_all_pts_preds'][-1]\n        batch_size = all_cls_scores.size()[0]\n        predictions_list = []\n        for i in range(batch_size):\n            predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i],all_pts_preds[i]))\n        return predictions_list"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/coder/nms_free_coder.py",
    "content": "import torch\n\nfrom mmcv.core.bbox.coder.base_bbox_coder import BaseBBoxCoder\nfrom mmcv.core.bbox.builder import BBOX_CODERS\nfrom mmcv.core.bbox.util import denormalize_bbox\nimport numpy as np\n\n\n@BBOX_CODERS.register_module()\nclass NMSFreeCoder(BaseBBoxCoder):\n    \"\"\"Bbox coder for NMS-free detector.\n    Args:\n        pc_range (list[float]): Range of point cloud.\n        post_center_range (list[float]): Limit of the center.\n            Default: None.\n        max_num (int): Max number to be kept. Default: 100.\n        score_threshold (float): Threshold to filter boxes based on score.\n            Default: None.\n        code_size (int): Code size of bboxes. Default: 9\n    \"\"\"\n\n    def __init__(self,\n                 pc_range,\n                 voxel_size=None,\n                 post_center_range=None,\n                 max_num=100,\n                 score_threshold=None,\n                 num_classes=10):\n        self.pc_range = pc_range\n        self.voxel_size = voxel_size\n        self.post_center_range = post_center_range\n        self.max_num = max_num\n        self.score_threshold = score_threshold\n        self.num_classes = num_classes\n\n    def encode(self):\n\n        pass\n\n    def decode_single(self, cls_scores, bbox_preds):\n        \"\"\"Decode bboxes.\n        Args:\n            cls_scores (Tensor): Outputs from the classification head, \\\n                shape [num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            bbox_preds (Tensor): Outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [num_query, 9].\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        max_num = min(self.max_num, cls_scores.shape[0])\n\n        cls_scores = cls_scores.sigmoid()\n        scores, indexs = cls_scores.view(-1).topk(max_num)\n        labels = indexs % self.num_classes\n        bbox_index = indexs // self.num_classes\n        bbox_preds = bbox_preds[bbox_index]\n       \n        final_box_preds = denormalize_bbox(bbox_preds, self.pc_range)   \n        final_scores = scores \n        final_preds = labels \n\n        # use score threshold\n        if self.score_threshold is not None:\n            thresh_mask = final_scores > self.score_threshold\n            tmp_score = self.score_threshold\n            while thresh_mask.sum() == 0:\n                tmp_score *= 0.9\n                if tmp_score < 0.01:\n                    thresh_mask = final_scores > -1\n                    break\n                thresh_mask = final_scores >= tmp_score\n\n        if self.post_center_range is not None:\n            self.post_center_range = torch.tensor(\n                self.post_center_range, device=scores.device)\n            mask = (final_box_preds[..., :3] >=\n                    self.post_center_range[:3]).all(1)\n            mask &= (final_box_preds[..., :3] <=\n                     self.post_center_range[3:]).all(1)\n\n            if self.score_threshold:\n                mask &= thresh_mask\n\n            boxes3d = final_box_preds[mask]\n            scores = final_scores[mask]\n\n            labels = final_preds[mask]\n            predictions_dict = {\n                'bboxes': boxes3d,\n                'scores': scores,\n                'labels': labels,\n                'mask': mask,\n                'bbox_index': bbox_index\n            }\n\n        else:\n            raise NotImplementedError(\n                'Need to reorganize output as a batch, only '\n                'support post_center_range is not None for now!')\n        return predictions_dict\n\n    def decode(self, preds_dicts):\n        \"\"\"Decode bboxes.\n        Args:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n        Returns:\n            list[dict]: Decoded boxes.\n        \"\"\"\n        all_cls_scores = preds_dicts['all_cls_scores'][-1]\n        all_bbox_preds = preds_dicts['all_bbox_preds'][-1]\n        \n        batch_size = all_cls_scores.size()[0]\n        predictions_list = []\n        for i in range(batch_size):\n            predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i]))\n        return predictions_list\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/iou_calculators/__init__.py",
    "content": "from .builder import build_iou_calculator\nfrom .iou2d_calculator import BboxOverlaps2D, bbox_overlaps\nfrom .iou3d_calculator import (AxisAlignedBboxOverlaps3D, BboxOverlaps3D,\n                               BboxOverlapsNearest3D,\n                               axis_aligned_bbox_overlaps_3d, bbox_overlaps_3d,\n                               bbox_overlaps_nearest_3d)\n\n__all__ = ['build_iou_calculator', 'BboxOverlaps2D', 'bbox_overlaps',\n           'BboxOverlapsNearest3D', 'BboxOverlaps3D', 'bbox_overlaps_nearest_3d',\n            'bbox_overlaps_3d', 'AxisAlignedBboxOverlaps3D',\n            'axis_aligned_bbox_overlaps_3d']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/iou_calculators/builder.py",
    "content": "from mmcv.utils import Registry, build_from_cfg\n\nIOU_CALCULATORS = Registry('IoU calculator')\n\n\ndef build_iou_calculator(cfg, default_args=None):\n    \"\"\"Builder of IoU calculator.\"\"\"\n    return build_from_cfg(cfg, IOU_CALCULATORS, default_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/iou_calculators/iou2d_calculator.py",
    "content": "import torch\n\nfrom .builder import IOU_CALCULATORS\n\n\ndef cast_tensor_type(x, scale=1., dtype=None):\n    if dtype == 'fp16':\n        # scale is for preventing overflows\n        x = (x / scale).half()\n    return x\n\n\ndef fp16_clamp(x, min=None, max=None):\n    if not x.is_cuda and x.dtype == torch.float16:\n        # clamp for cpu float16, tensor fp16 has no clamp implementation\n        return x.float().clamp(min, max).half()\n\n    return x.clamp(min, max)\n\n\n@IOU_CALCULATORS.register_module()\nclass BboxOverlaps2D:\n    \"\"\"2D Overlaps (e.g. IoUs, GIoUs) Calculator.\"\"\"\n\n    def __init__(self, scale=1., dtype=None):\n        self.scale = scale\n        self.dtype = dtype\n\n    def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):\n        \"\"\"Calculate IoU between 2D bboxes.\n\n        Args:\n            bboxes1 (Tensor): bboxes have shape (m, 4) in <x1, y1, x2, y2>\n                format, or shape (m, 5) in <x1, y1, x2, y2, score> format.\n            bboxes2 (Tensor): bboxes have shape (m, 4) in <x1, y1, x2, y2>\n                format, shape (m, 5) in <x1, y1, x2, y2, score> format, or be\n                empty. If ``is_aligned `` is ``True``, then m and n must be\n                equal.\n            mode (str): \"iou\" (intersection over union), \"iof\" (intersection\n                over foreground), or \"giou\" (generalized intersection over\n                union).\n            is_aligned (bool, optional): If True, then m and n must be equal.\n                Default False.\n\n        Returns:\n            Tensor: shape (m, n) if ``is_aligned `` is False else shape (m,)\n        \"\"\"\n        assert bboxes1.size(-1) in [0, 4, 5]\n        assert bboxes2.size(-1) in [0, 4, 5]\n        if bboxes2.size(-1) == 5:\n            bboxes2 = bboxes2[..., :4]\n        if bboxes1.size(-1) == 5:\n            bboxes1 = bboxes1[..., :4]\n\n        if self.dtype == 'fp16':\n            # change tensor type to save cpu and cuda memory and keep speed\n            bboxes1 = cast_tensor_type(bboxes1, self.scale, self.dtype)\n            bboxes2 = cast_tensor_type(bboxes2, self.scale, self.dtype)\n            overlaps = bbox_overlaps(bboxes1, bboxes2, mode, is_aligned)\n            if not overlaps.is_cuda and overlaps.dtype == torch.float16:\n                # resume cpu float32\n                overlaps = overlaps.float()\n            return overlaps\n\n        return bbox_overlaps(bboxes1, bboxes2, mode, is_aligned)\n\n    def __repr__(self):\n        \"\"\"str: a string describing the module\"\"\"\n        repr_str = self.__class__.__name__ + f'(' \\\n            f'scale={self.scale}, dtype={self.dtype})'\n        return repr_str\n\n\ndef bbox_overlaps(bboxes1, bboxes2, mode='iou', is_aligned=False, eps=1e-6):\n    \"\"\"Calculate overlap between two set of bboxes.\n\n    FP16 Contributed by https://github.com/open-mmlab/mmdetection/pull/4889\n    Note:\n        Assume bboxes1 is M x 4, bboxes2 is N x 4, when mode is 'iou',\n        there are some new generated variable when calculating IOU\n        using bbox_overlaps function:\n\n        1) is_aligned is False\n            area1: M x 1\n            area2: N x 1\n            lt: M x N x 2\n            rb: M x N x 2\n            wh: M x N x 2\n            overlap: M x N x 1\n            union: M x N x 1\n            ious: M x N x 1\n\n            Total memory:\n                S = (9 x N x M + N + M) * 4 Byte,\n\n            When using FP16, we can reduce:\n                R = (9 x N x M + N + M) * 4 / 2 Byte\n                R large than (N + M) * 4 * 2 is always true when N and M >= 1.\n                Obviously, N + M <= N * M < 3 * N * M, when N >=2 and M >=2,\n                           N + 1 < 3 * N, when N or M is 1.\n\n            Given M = 40 (ground truth), N = 400000 (three anchor boxes\n            in per grid, FPN, R-CNNs),\n                R = 275 MB (one times)\n\n            A special case (dense detection), M = 512 (ground truth),\n                R = 3516 MB = 3.43 GB\n\n            When the batch size is B, reduce:\n                B x R\n\n            Therefore, CUDA memory runs out frequently.\n\n            Experiments on GeForce RTX 2080Ti (11019 MiB):\n\n            |   dtype   |   M   |   N   |   Use    |   Real   |   Ideal   |\n            |:----:|:----:|:----:|:----:|:----:|:----:|\n            |   FP32   |   512 | 400000 | 8020 MiB |   --   |   --   |\n            |   FP16   |   512 | 400000 |   4504 MiB | 3516 MiB | 3516 MiB |\n            |   FP32   |   40 | 400000 |   1540 MiB |   --   |   --   |\n            |   FP16   |   40 | 400000 |   1264 MiB |   276MiB   | 275 MiB |\n\n        2) is_aligned is True\n            area1: N x 1\n            area2: N x 1\n            lt: N x 2\n            rb: N x 2\n            wh: N x 2\n            overlap: N x 1\n            union: N x 1\n            ious: N x 1\n\n            Total memory:\n                S = 11 x N * 4 Byte\n\n            When using FP16, we can reduce:\n                R = 11 x N * 4 / 2 Byte\n\n        So do the 'giou' (large than 'iou').\n\n        Time-wise, FP16 is generally faster than FP32.\n\n        When gpu_assign_thr is not -1, it takes more time on cpu\n        but not reduce memory.\n        There, we can reduce half the memory and keep the speed.\n\n    If ``is_aligned `` is ``False``, then calculate the overlaps between each\n    bbox of bboxes1 and bboxes2, otherwise the overlaps between each aligned\n    pair of bboxes1 and bboxes2.\n\n    Args:\n        bboxes1 (Tensor): shape (B, m, 4) in <x1, y1, x2, y2> format or empty.\n        bboxes2 (Tensor): shape (B, n, 4) in <x1, y1, x2, y2> format or empty.\n            B indicates the batch dim, in shape (B1, B2, ..., Bn).\n            If ``is_aligned `` is ``True``, then m and n must be equal.\n        mode (str): \"iou\" (intersection over union), \"iof\" (intersection over\n            foreground) or \"giou\" (generalized intersection over union).\n            Default \"iou\".\n        is_aligned (bool, optional): If True, then m and n must be equal.\n            Default False.\n        eps (float, optional): A value added to the denominator for numerical\n            stability. Default 1e-6.\n\n    Returns:\n        Tensor: shape (m, n) if ``is_aligned `` is False else shape (m,)\n\n    Example:\n        >>> bboxes1 = torch.FloatTensor([\n        >>>     [0, 0, 10, 10],\n        >>>     [10, 10, 20, 20],\n        >>>     [32, 32, 38, 42],\n        >>> ])\n        >>> bboxes2 = torch.FloatTensor([\n        >>>     [0, 0, 10, 20],\n        >>>     [0, 10, 10, 19],\n        >>>     [10, 10, 20, 20],\n        >>> ])\n        >>> overlaps = bbox_overlaps(bboxes1, bboxes2)\n        >>> assert overlaps.shape == (3, 3)\n        >>> overlaps = bbox_overlaps(bboxes1, bboxes2, is_aligned=True)\n        >>> assert overlaps.shape == (3, )\n\n    Example:\n        >>> empty = torch.empty(0, 4)\n        >>> nonempty = torch.FloatTensor([[0, 0, 10, 9]])\n        >>> assert tuple(bbox_overlaps(empty, nonempty).shape) == (0, 1)\n        >>> assert tuple(bbox_overlaps(nonempty, empty).shape) == (1, 0)\n        >>> assert tuple(bbox_overlaps(empty, empty).shape) == (0, 0)\n    \"\"\"\n\n    assert mode in ['iou', 'iof', 'giou'], f'Unsupported mode {mode}'\n    # Either the boxes are empty or the length of boxes' last dimension is 4\n    assert (bboxes1.size(-1) == 4 or bboxes1.size(0) == 0)\n    assert (bboxes2.size(-1) == 4 or bboxes2.size(0) == 0)\n\n    # Batch dim must be the same\n    # Batch dim: (B1, B2, ... Bn)\n    assert bboxes1.shape[:-2] == bboxes2.shape[:-2]\n    batch_shape = bboxes1.shape[:-2]\n\n    rows = bboxes1.size(-2)\n    cols = bboxes2.size(-2)\n    if is_aligned:\n        assert rows == cols\n\n    if rows * cols == 0:\n        if is_aligned:\n            return bboxes1.new(batch_shape + (rows, ))\n        else:\n            return bboxes1.new(batch_shape + (rows, cols))\n\n    area1 = (bboxes1[..., 2] - bboxes1[..., 0]) * (\n        bboxes1[..., 3] - bboxes1[..., 1])\n    area2 = (bboxes2[..., 2] - bboxes2[..., 0]) * (\n        bboxes2[..., 3] - bboxes2[..., 1])\n\n    if is_aligned:\n        lt = torch.max(bboxes1[..., :2], bboxes2[..., :2])  # [B, rows, 2]\n        rb = torch.min(bboxes1[..., 2:], bboxes2[..., 2:])  # [B, rows, 2]\n\n        wh = fp16_clamp(rb - lt, min=0)\n        overlap = wh[..., 0] * wh[..., 1]\n\n        if mode in ['iou', 'giou']:\n            union = area1 + area2 - overlap\n        else:\n            union = area1\n        if mode == 'giou':\n            enclosed_lt = torch.min(bboxes1[..., :2], bboxes2[..., :2])\n            enclosed_rb = torch.max(bboxes1[..., 2:], bboxes2[..., 2:])\n    else:\n        lt = torch.max(bboxes1[..., :, None, :2],\n                       bboxes2[..., None, :, :2])  # [B, rows, cols, 2]\n        rb = torch.min(bboxes1[..., :, None, 2:],\n                       bboxes2[..., None, :, 2:])  # [B, rows, cols, 2]\n\n        wh = fp16_clamp(rb - lt, min=0)\n        overlap = wh[..., 0] * wh[..., 1]\n\n        if mode in ['iou', 'giou']:\n            union = area1[..., None] + area2[..., None, :] - overlap\n        else:\n            union = area1[..., None]\n        if mode == 'giou':\n            enclosed_lt = torch.min(bboxes1[..., :, None, :2],\n                                    bboxes2[..., None, :, :2])\n            enclosed_rb = torch.max(bboxes1[..., :, None, 2:],\n                                    bboxes2[..., None, :, 2:])\n\n    eps = union.new_tensor([eps])\n    union = torch.max(union, eps)\n    ious = overlap / union\n    if mode in ['iou', 'iof']:\n        return ious\n    # calculate gious\n    enclose_wh = fp16_clamp(enclosed_rb - enclosed_lt, min=0)\n    enclose_area = enclose_wh[..., 0] * enclose_wh[..., 1]\n    enclose_area = torch.max(enclose_area, eps)\n    gious = ious - (enclose_area - union) / enclose_area\n    return gious\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/iou_calculators/iou3d_calculator.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom .iou2d_calculator import bbox_overlaps\nfrom .builder import IOU_CALCULATORS\nfrom ..structures.utils import get_box_type\n\n\n@IOU_CALCULATORS.register_module()\nclass BboxOverlapsNearest3D(object):\n    \"\"\"Nearest 3D IoU Calculator.\n\n    Note:\n        This IoU calculator first finds the nearest 2D boxes in bird eye view\n        (BEV), and then calculates the 2D IoU using :meth:`bbox_overlaps`.\n\n    Args:\n        coordinate (str): 'camera', 'lidar', or 'depth' coordinate system.\n    \"\"\"\n\n    def __init__(self, coordinate='lidar'):\n        assert coordinate in ['camera', 'lidar', 'depth']\n        self.coordinate = coordinate\n\n    def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):\n        \"\"\"Calculate nearest 3D IoU.\n\n        Note:\n            If ``is_aligned`` is ``False``, then it calculates the ious between\n            each bbox of bboxes1 and bboxes2, otherwise it calculates the ious\n            between each aligned pair of bboxes1 and bboxes2.\n\n        Args:\n            bboxes1 (torch.Tensor): shape (N, 7+N) [x, y, z, h, w, l, ry, v].\n            bboxes2 (torch.Tensor): shape (M, 7+N) [x, y, z, h, w, l, ry, v].\n            mode (str): \"iou\" (intersection over union) or iof\n                (intersection over foreground).\n            is_aligned (bool): Whether the calculation is aligned.\n\n        Return:\n            torch.Tensor: If ``is_aligned`` is ``True``, return ious between \\\n                bboxes1 and bboxes2 with shape (M, N). If ``is_aligned`` is \\\n                ``False``, return shape is M.\n        \"\"\"\n        return bbox_overlaps_nearest_3d(bboxes1, bboxes2, mode, is_aligned,\n                                        self.coordinate)\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(coordinate={self.coordinate}'\n        return repr_str\n\n\n@IOU_CALCULATORS.register_module()\nclass BboxOverlaps3D(object):\n    \"\"\"3D IoU Calculator.\n\n    Args:\n        coordinate (str): The coordinate system, valid options are\n            'camera', 'lidar', and 'depth'.\n    \"\"\"\n\n    def __init__(self, coordinate):\n        assert coordinate in ['camera', 'lidar', 'depth']\n        self.coordinate = coordinate\n\n    def __call__(self, bboxes1, bboxes2, mode='iou'):\n        \"\"\"Calculate 3D IoU using cuda implementation.\n\n        Note:\n            This function calculate the IoU of 3D boxes based on their volumes.\n            IoU calculator ``:class:BboxOverlaps3D`` uses this function to\n            calculate the actual 3D IoUs of boxes.\n\n        Args:\n            bboxes1 (torch.Tensor): shape (N, 7+C) [x, y, z, h, w, l, ry].\n            bboxes2 (torch.Tensor): shape (M, 7+C) [x, y, z, h, w, l, ry].\n            mode (str): \"iou\" (intersection over union) or\n                iof (intersection over foreground).\n\n        Return:\n            torch.Tensor: Bbox overlaps results of bboxes1 and bboxes2 \\\n                with shape (M, N) (aligned mode is not supported currently).\n        \"\"\"\n        return bbox_overlaps_3d(bboxes1, bboxes2, mode, self.coordinate)\n\n    def __repr__(self):\n        \"\"\"str: return a string that describes the module\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(coordinate={self.coordinate}'\n        return repr_str\n\n\ndef bbox_overlaps_nearest_3d(bboxes1,\n                             bboxes2,\n                             mode='iou',\n                             is_aligned=False,\n                             coordinate='lidar'):\n    \"\"\"Calculate nearest 3D IoU.\n\n    Note:\n        This function first finds the nearest 2D boxes in bird eye view\n        (BEV), and then calculates the 2D IoU using :meth:`bbox_overlaps`.\n        Ths IoU calculator :class:`BboxOverlapsNearest3D` uses this\n        function to calculate IoUs of boxes.\n\n        If ``is_aligned`` is ``False``, then it calculates the ious between\n        each bbox of bboxes1 and bboxes2, otherwise the ious between each\n        aligned pair of bboxes1 and bboxes2.\n\n    Args:\n        bboxes1 (torch.Tensor): shape (N, 7+C) [x, y, z, h, w, l, ry, v].\n        bboxes2 (torch.Tensor): shape (M, 7+C) [x, y, z, h, w, l, ry, v].\n        mode (str): \"iou\" (intersection over union) or iof\n            (intersection over foreground).\n        is_aligned (bool): Whether the calculation is aligned\n\n    Return:\n        torch.Tensor: If ``is_aligned`` is ``True``, return ious between \\\n            bboxes1 and bboxes2 with shape (M, N). If ``is_aligned`` is \\\n            ``False``, return shape is M.\n    \"\"\"\n    assert bboxes1.size(-1) == bboxes2.size(-1) >= 7\n\n    box_type, _ = get_box_type(coordinate)\n\n    bboxes1 = box_type(bboxes1, box_dim=bboxes1.shape[-1])\n    bboxes2 = box_type(bboxes2, box_dim=bboxes2.shape[-1])\n\n    # Change the bboxes to bev\n    # box conversion and iou calculation in torch version on CUDA\n    # is 10x faster than that in numpy version\n    bboxes1_bev = bboxes1.nearest_bev\n    bboxes2_bev = bboxes2.nearest_bev\n\n    ret = bbox_overlaps(\n        bboxes1_bev, bboxes2_bev, mode=mode, is_aligned=is_aligned)\n    return ret\n\n\ndef bbox_overlaps_3d(bboxes1, bboxes2, mode='iou', coordinate='camera'):\n    \"\"\"Calculate 3D IoU using cuda implementation.\n\n    Note:\n        This function calculates the IoU of 3D boxes based on their volumes.\n        IoU calculator :class:`BboxOverlaps3D` uses this function to\n        calculate the actual IoUs of boxes.\n\n    Args:\n        bboxes1 (torch.Tensor): shape (N, 7+C) [x, y, z, h, w, l, ry].\n        bboxes2 (torch.Tensor): shape (M, 7+C) [x, y, z, h, w, l, ry].\n        mode (str): \"iou\" (intersection over union) or\n            iof (intersection over foreground).\n        coordinate (str): 'camera' or 'lidar' coordinate system.\n\n    Return:\n        torch.Tensor: Bbox overlaps results of bboxes1 and bboxes2 \\\n            with shape (M, N) (aligned mode is not supported currently).\n    \"\"\"\n    assert bboxes1.size(-1) == bboxes2.size(-1) >= 7\n\n    box_type, _ = get_box_type(coordinate)\n\n    bboxes1 = box_type(bboxes1, box_dim=bboxes1.shape[-1])\n    bboxes2 = box_type(bboxes2, box_dim=bboxes2.shape[-1])\n\n    return bboxes1.overlaps(bboxes1, bboxes2, mode=mode)\n\n\n@IOU_CALCULATORS.register_module()\nclass AxisAlignedBboxOverlaps3D(object):\n    \"\"\"Axis-aligned 3D Overlaps (IoU) Calculator.\"\"\"\n\n    def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):\n        \"\"\"Calculate IoU between 2D bboxes.\n\n        Args:\n            bboxes1 (Tensor): shape (B, m, 6) in <x1, y1, z1, x2, y2, z2>\n                format or empty.\n            bboxes2 (Tensor): shape (B, n, 6) in <x1, y1, z1, x2, y2, z2>\n                format or empty.\n                B indicates the batch dim, in shape (B1, B2, ..., Bn).\n                If ``is_aligned`` is ``True``, then m and n must be equal.\n            mode (str): \"iou\" (intersection over union) or \"giou\" (generalized\n                intersection over union).\n            is_aligned (bool, optional): If True, then m and n must be equal.\n                Default False.\n        Returns:\n            Tensor: shape (m, n) if ``is_aligned`` is False else shape (m,)\n        \"\"\"\n        assert bboxes1.size(-1) == bboxes2.size(-1) == 6\n        return axis_aligned_bbox_overlaps_3d(bboxes1, bboxes2, mode,\n                                             is_aligned)\n\n    def __repr__(self):\n        \"\"\"str: a string describing the module\"\"\"\n        repr_str = self.__class__.__name__ + '()'\n        return repr_str\n\n\ndef axis_aligned_bbox_overlaps_3d(bboxes1,\n                                  bboxes2,\n                                  mode='iou',\n                                  is_aligned=False,\n                                  eps=1e-6):\n    \"\"\"Calculate overlap between two set of axis aligned 3D bboxes. If\n    ``is_aligned`` is ``False``, then calculate the overlaps between each bbox\n    of bboxes1 and bboxes2, otherwise the overlaps between each aligned pair of\n    bboxes1 and bboxes2.\n\n    Args:\n        bboxes1 (Tensor): shape (B, m, 6) in <x1, y1, z1, x2, y2, z2>\n            format or empty.\n        bboxes2 (Tensor): shape (B, n, 6) in <x1, y1, z1, x2, y2, z2>\n            format or empty.\n            B indicates the batch dim, in shape (B1, B2, ..., Bn).\n            If ``is_aligned`` is ``True``, then m and n must be equal.\n        mode (str): \"iou\" (intersection over union) or \"giou\" (generalized\n            intersection over union).\n        is_aligned (bool, optional): If True, then m and n must be equal.\n            Default False.\n        eps (float, optional): A value added to the denominator for numerical\n            stability. Default 1e-6.\n\n    Returns:\n        Tensor: shape (m, n) if ``is_aligned`` is False else shape (m,)\n\n    Example:\n        >>> bboxes1 = torch.FloatTensor([\n        >>>     [0, 0, 0, 10, 10, 10],\n        >>>     [10, 10, 10, 20, 20, 20],\n        >>>     [32, 32, 32, 38, 40, 42],\n        >>> ])\n        >>> bboxes2 = torch.FloatTensor([\n        >>>     [0, 0, 0, 10, 20, 20],\n        >>>     [0, 10, 10, 10, 19, 20],\n        >>>     [10, 10, 10, 20, 20, 20],\n        >>> ])\n        >>> overlaps = axis_aligned_bbox_overlaps_3d(bboxes1, bboxes2)\n        >>> assert overlaps.shape == (3, 3)\n        >>> overlaps = bbox_overlaps(bboxes1, bboxes2, is_aligned=True)\n        >>> assert overlaps.shape == (3, )\n    Example:\n        >>> empty = torch.empty(0, 6)\n        >>> nonempty = torch.FloatTensor([[0, 0, 0, 10, 9, 10]])\n        >>> assert tuple(bbox_overlaps(empty, nonempty).shape) == (0, 1)\n        >>> assert tuple(bbox_overlaps(nonempty, empty).shape) == (1, 0)\n        >>> assert tuple(bbox_overlaps(empty, empty).shape) == (0, 0)\n    \"\"\"\n\n    assert mode in ['iou', 'giou'], f'Unsupported mode {mode}'\n    # Either the boxes are empty or the length of boxes's last dimenstion is 6\n    assert (bboxes1.size(-1) == 6 or bboxes1.size(0) == 0)\n    assert (bboxes2.size(-1) == 6 or bboxes2.size(0) == 0)\n\n    # Batch dim must be the same\n    # Batch dim: (B1, B2, ... Bn)\n    assert bboxes1.shape[:-2] == bboxes2.shape[:-2]\n    batch_shape = bboxes1.shape[:-2]\n\n    rows = bboxes1.size(-2)\n    cols = bboxes2.size(-2)\n    if is_aligned:\n        assert rows == cols\n\n    if rows * cols == 0:\n        if is_aligned:\n            return bboxes1.new(batch_shape + (rows, ))\n        else:\n            return bboxes1.new(batch_shape + (rows, cols))\n\n    area1 = (bboxes1[..., 3] -\n             bboxes1[..., 0]) * (bboxes1[..., 4] - bboxes1[..., 1]) * (\n                 bboxes1[..., 5] - bboxes1[..., 2])\n    area2 = (bboxes2[..., 3] -\n             bboxes2[..., 0]) * (bboxes2[..., 4] - bboxes2[..., 1]) * (\n                 bboxes2[..., 5] - bboxes2[..., 2])\n\n    if is_aligned:\n        lt = torch.max(bboxes1[..., :3], bboxes2[..., :3])  # [B, rows, 3]\n        rb = torch.min(bboxes1[..., 3:], bboxes2[..., 3:])  # [B, rows, 3]\n\n        wh = (rb - lt).clamp(min=0)  # [B, rows, 2]\n        overlap = wh[..., 0] * wh[..., 1] * wh[..., 2]\n\n        if mode in ['iou', 'giou']:\n            union = area1 + area2 - overlap\n        else:\n            union = area1\n        if mode == 'giou':\n            enclosed_lt = torch.min(bboxes1[..., :3], bboxes2[..., :3])\n            enclosed_rb = torch.max(bboxes1[..., 3:], bboxes2[..., 3:])\n    else:\n        lt = torch.max(bboxes1[..., :, None, :3],\n                       bboxes2[..., None, :, :3])  # [B, rows, cols, 3]\n        rb = torch.min(bboxes1[..., :, None, 3:],\n                       bboxes2[..., None, :, 3:])  # [B, rows, cols, 3]\n\n        wh = (rb - lt).clamp(min=0)  # [B, rows, cols, 3]\n        overlap = wh[..., 0] * wh[..., 1] * wh[..., 2]\n\n        if mode in ['iou', 'giou']:\n            union = area1[..., None] + area2[..., None, :] - overlap\n        if mode == 'giou':\n            enclosed_lt = torch.min(bboxes1[..., :, None, :3],\n                                    bboxes2[..., None, :, :3])\n            enclosed_rb = torch.max(bboxes1[..., :, None, 3:],\n                                    bboxes2[..., None, :, 3:])\n\n    eps = union.new_tensor([eps])\n    union = torch.max(union, eps)\n    ious = overlap / union\n    if mode in ['iou']:\n        return ious\n    # calculate gious\n    enclose_wh = (enclosed_rb - enclosed_lt).clamp(min=0)\n    enclose_area = enclose_wh[..., 0] * enclose_wh[..., 1] * enclose_wh[..., 2]\n    enclose_area = torch.max(enclose_area, eps)\n    gious = ious - (enclose_area - union) / enclose_area\n    return gious\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/match_costs/__init__.py",
    "content": "from .builder import build_match_cost\nfrom .match_cost import BBoxL1Cost, ClassificationCost, FocalLossCost, IoUCost, BBox3DL1Cost, DiceCost\n\n__all__ = [\n    'build_match_cost', 'ClassificationCost', 'BBoxL1Cost', 'IoUCost',\n    'FocalLossCost', 'BBox3DL1Cost', 'DiceCost'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/match_costs/builder.py",
    "content": "from mmcv.utils import Registry, build_from_cfg\n\nMATCH_COST = Registry('Match Cost')\n\n\ndef build_match_cost(cfg, default_args=None):\n    \"\"\"Builder of IoU calculator.\"\"\"\n    return build_from_cfg(cfg, MATCH_COST, default_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/match_costs/match_cost.py",
    "content": "import torch\nimport torch.nn.functional as F\nfrom mmcv.core.bbox.iou_calculators import bbox_overlaps\nfrom mmcv.core.bbox.transforms import bbox_cxcywh_to_xyxy, bbox_xyxy_to_cxcywh\nfrom .builder import MATCH_COST\n\n\n@MATCH_COST.register_module()\nclass BBoxL1Cost:\n    \"\"\"BBoxL1Cost.\n\n     Args:\n         weight (int | float, optional): loss_weight\n         box_format (str, optional): 'xyxy' for DETR, 'xywh' for Sparse_RCNN\n\n     Examples:\n         >>> from mmcv.core.bbox.match_costs.match_cost import BBoxL1Cost\n         >>> import torch\n         >>> self = BBoxL1Cost()\n         >>> bbox_pred = torch.rand(1, 4)\n         >>> gt_bboxes= torch.FloatTensor([[0, 0, 2, 4], [1, 2, 3, 4]])\n         >>> factor = torch.tensor([10, 8, 10, 8])\n         >>> self(bbox_pred, gt_bboxes, factor)\n         tensor([[1.6172, 1.6422]])\n    \"\"\"\n\n    def __init__(self, weight=1., box_format='xyxy'):\n        self.weight = weight\n        assert box_format in ['xyxy', 'xywh']\n        self.box_format = box_format\n\n    def __call__(self, bbox_pred, gt_bboxes):\n        \"\"\"\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            gt_bboxes (Tensor): Ground truth boxes with normalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n\n        Returns:\n            torch.Tensor: bbox_cost value with weight\n        \"\"\"\n        if self.box_format == 'xywh':\n            gt_bboxes = bbox_xyxy_to_cxcywh(gt_bboxes)\n        elif self.box_format == 'xyxy':\n            bbox_pred = bbox_cxcywh_to_xyxy(bbox_pred)\n        bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)\n        return bbox_cost * self.weight\n\n\n@MATCH_COST.register_module()\nclass FocalLossCost:\n    \"\"\"FocalLossCost.\n\n     Args:\n         weight (int | float, optional): loss_weight\n         alpha (int | float, optional): focal_loss alpha\n         gamma (int | float, optional): focal_loss gamma\n         eps (float, optional): default 1e-12\n\n     Examples:\n         >>> from mmcv.core.bbox.match_costs.match_cost import FocalLossCost\n         >>> import torch\n         >>> self = FocalLossCost()\n         >>> cls_pred = torch.rand(4, 3)\n         >>> gt_labels = torch.tensor([0, 1, 2])\n         >>> factor = torch.tensor([10, 8, 10, 8])\n         >>> self(cls_pred, gt_labels)\n         tensor([[-0.3236, -0.3364, -0.2699],\n                [-0.3439, -0.3209, -0.4807],\n                [-0.4099, -0.3795, -0.2929],\n                [-0.1950, -0.1207, -0.2626]])\n    \"\"\"\n\n    def __init__(self, weight=1., alpha=0.25, gamma=2, eps=1e-12):\n        self.weight = weight\n        self.alpha = alpha\n        self.gamma = gamma\n        self.eps = eps\n\n    def __call__(self, cls_pred, gt_labels):\n        \"\"\"\n        Args:\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n\n        Returns:\n            torch.Tensor: cls_cost value with weight\n        \"\"\"\n        cls_pred = cls_pred.sigmoid()\n        neg_cost = -(1 - cls_pred + self.eps).log() * (\n            1 - self.alpha) * cls_pred.pow(self.gamma)\n        pos_cost = -(cls_pred + self.eps).log() * self.alpha * (\n            1 - cls_pred).pow(self.gamma)\n        cls_cost = pos_cost[:, gt_labels] - neg_cost[:, gt_labels]\n        return cls_cost * self.weight\n\n\n@MATCH_COST.register_module()\nclass ClassificationCost:\n    \"\"\"ClsSoftmaxCost.\n\n     Args:\n         weight (int | float, optional): loss_weight\n\n     Examples:\n         >>> from mmcv.core.bbox.match_costs.match_cost import \\\n         ... ClassificationCost\n         >>> import torch\n         >>> self = ClassificationCost()\n         >>> cls_pred = torch.rand(4, 3)\n         >>> gt_labels = torch.tensor([0, 1, 2])\n         >>> factor = torch.tensor([10, 8, 10, 8])\n         >>> self(cls_pred, gt_labels)\n         tensor([[-0.3430, -0.3525, -0.3045],\n                [-0.3077, -0.2931, -0.3992],\n                [-0.3664, -0.3455, -0.2881],\n                [-0.3343, -0.2701, -0.3956]])\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n\n    def __call__(self, cls_pred, gt_labels):\n        \"\"\"\n        Args:\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n\n        Returns:\n            torch.Tensor: cls_cost value with weight\n        \"\"\"\n        # Following the official DETR repo, contrary to the loss that\n        # NLL is used, we approximate it in 1 - cls_score[gt_label].\n        # The 1 is a constant that doesn't change the matching,\n        # so it can be omitted.\n        cls_score = cls_pred.softmax(-1)\n        cls_cost = -cls_score[:, gt_labels]\n        return cls_cost * self.weight\n\n\n@MATCH_COST.register_module()\nclass IoUCost:\n    \"\"\"IoUCost.\n\n     Args:\n         iou_mode (str, optional): iou mode such as 'iou' | 'giou'\n         weight (int | float, optional): loss weight\n\n     Examples:\n         >>> from mmcv.core.bbox.match_costs.match_cost import IoUCost\n         >>> import torch\n         >>> self = IoUCost()\n         >>> bboxes = torch.FloatTensor([[1,1, 2, 2], [2, 2, 3, 4]])\n         >>> gt_bboxes = torch.FloatTensor([[0, 0, 2, 4], [1, 2, 3, 4]])\n         >>> self(bboxes, gt_bboxes)\n         tensor([[-0.1250,  0.1667],\n                [ 0.1667, -0.5000]])\n    \"\"\"\n\n    def __init__(self, iou_mode='giou', weight=1.):\n        self.weight = weight\n        self.iou_mode = iou_mode\n\n    def __call__(self, bboxes, gt_bboxes):\n        \"\"\"\n        Args:\n            bboxes (Tensor): Predicted boxes with unnormalized coordinates\n                (x1, y1, x2, y2). Shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n\n        Returns:\n            torch.Tensor: iou_cost value with weight\n        \"\"\"\n        # overlaps: [num_bboxes, num_gt]\n        overlaps = bbox_overlaps(\n            bboxes, gt_bboxes, mode=self.iou_mode, is_aligned=False)\n        # The 1 is a constant that doesn't change the matching, so omitted.\n        iou_cost = -overlaps\n        return iou_cost * self.weight\n    \n    \n@MATCH_COST.register_module()\nclass BBox3DL1Cost(object):\n    \"\"\"BBox3DL1Cost.\n     Args:\n         weight (int | float, optional): loss_weight\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n\n    def __call__(self, bbox_pred, gt_bboxes):\n        \"\"\"\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            gt_bboxes (Tensor): Ground truth boxes with normalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n        Returns:\n            torch.Tensor: bbox_cost value with weight\n        \"\"\"\n        bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)\n        return bbox_cost * self.weight\n\n#@weighted_loss\ndef smooth_l1_loss(pred, target, beta=1.0):\n    \"\"\"Smooth L1 loss.\n    Args:\n        pred (torch.Tensor): The prediction.\n        target (torch.Tensor): The learning target of the prediction.\n        beta (float, optional): The threshold in the piecewise function.\n            Defaults to 1.0.\n    Returns:\n        torch.Tensor: Calculated loss\n    \"\"\"\n    assert beta > 0\n    if target.numel() == 0:\n        return pred.sum() * 0\n\n    # assert pred.size() == target.size()\n    diff = torch.abs(pred - target)\n    loss = torch.where(diff < beta, 0.5 * diff * diff / beta,\n                       diff - 0.5 * beta)\n    return loss.sum(-1)\n\n\n@MATCH_COST.register_module()\nclass SmoothL1Cost(object):\n    \"\"\"SmoothL1Cost.\n     Args:\n         weight (int | float, optional): loss weight\n\n     Examples:\n         >>> from mmdet.core.bbox.match_costs.match_cost import IoUCost\n         >>> import torch\n         >>> self = IoUCost()\n         >>> bboxes = torch.FloatTensor([[1,1, 2, 2], [2, 2, 3, 4]])\n         >>> gt_bboxes = torch.FloatTensor([[0, 0, 2, 4], [1, 2, 3, 4]])\n         >>> self(bboxes, gt_bboxes)\n         tensor([[-0.1250,  0.1667],\n                [ 0.1667, -0.5000]])\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n\n    def __call__(self, input, target):\n        \"\"\"\n        Args:\n            bboxes (Tensor): Predicted boxes with unnormalized coordinates\n                (x1, y1, x2, y2). Shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n\n        Returns:\n            torch.Tensor: iou_cost value with weight\n        \"\"\"\n        N1, C = input.shape\n        N2, C = target.shape\n        input = input.contiguous().view(N1, C)[:, None, :]\n        target = target.contiguous().view(N2, C)[None, :, :]\n        cost = smooth_l1_loss(input, target)\n\n        return cost * self.weight\n\n\n@MATCH_COST.register_module()\nclass DiceCost(object):\n    \"\"\"IoUCost.\n\n     Args:\n         iou_mode (str, optional): iou mode such as 'iou' | 'giou'\n         weight (int | float, optional): loss weight\n\n     Examples:\n         >>> from mmcv.core.bbox.match_costs.match_cost import IoUCost\n         >>> import torch\n         >>> self = IoUCost()\n         >>> bboxes = torch.FloatTensor([[1,1, 2, 2], [2, 2, 3, 4]])\n         >>> gt_bboxes = torch.FloatTensor([[0, 0, 2, 4], [1, 2, 3, 4]])\n         >>> self(bboxes, gt_bboxes)\n         tensor([[-0.1250,  0.1667],\n                [ 0.1667, -0.5000]])\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n        self.count = 0\n\n    def __call__(self, input, target):\n        \"\"\"\n        Args:\n            bboxes (Tensor): Predicted boxes with unnormalized coordinates\n                (x1, y1, x2, y2). Shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n\n        Returns:\n            torch.Tensor: iou_cost value with weight\n        \"\"\"\n        # overlaps: [num_bboxes, num_gt]\n        # print('INPUT', input.shape)\n        # print('target',target.shape)\n\n        N1, H1, W1 = input.shape\n        N2, H2, W2 = target.shape\n\n        if H1 != H2 or W1 != W2:\n            target = F.interpolate(target.unsqueeze(0), size=(H1, W1), mode='bilinear').squeeze(0)\n\n        input = input.contiguous().view(N1, -1)[:, None, :]\n        target = target.contiguous().view(N2, -1)[None, :, :]\n\n        a = torch.sum(input * target, -1)\n        b = torch.sum(input * input, -1) + 0.001\n        c = torch.sum(target * target, -1) + 0.001\n        d = (2 * a) / (b + c)\n        return (1 - d) * self.weight\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/samplers/__init__.py",
    "content": "from .pseudo_sampler import PseudoSampler\n\n\n__all__ = [\n    'PseudoSampler'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/samplers/base_sampler.py",
    "content": "from abc import ABCMeta, abstractmethod\n\nimport torch\n\nfrom .sampling_result import SamplingResult\n\n\nclass BaseSampler(metaclass=ABCMeta):\n    \"\"\"Base class of samplers.\"\"\"\n\n    def __init__(self,\n                 num,\n                 pos_fraction,\n                 neg_pos_ub=-1,\n                 add_gt_as_proposals=True,\n                 **kwargs):\n        self.num = num\n        self.pos_fraction = pos_fraction\n        self.neg_pos_ub = neg_pos_ub\n        self.add_gt_as_proposals = add_gt_as_proposals\n        self.pos_sampler = self\n        self.neg_sampler = self\n\n    @abstractmethod\n    def _sample_pos(self, assign_result, num_expected, **kwargs):\n        \"\"\"Sample positive samples.\"\"\"\n        pass\n\n    @abstractmethod\n    def _sample_neg(self, assign_result, num_expected, **kwargs):\n        \"\"\"Sample negative samples.\"\"\"\n        pass\n\n    def sample(self,\n               assign_result,\n               bboxes,\n               gt_bboxes,\n               gt_labels=None,\n               **kwargs):\n        \"\"\"Sample positive and negative bboxes.\n\n        This is a simple implementation of bbox sampling given candidates,\n        assigning results and ground truth bboxes.\n\n        Args:\n            assign_result (:obj:`AssignResult`): Bbox assigning results.\n            bboxes (Tensor): Boxes to be sampled from.\n            gt_bboxes (Tensor): Ground truth bboxes.\n            gt_labels (Tensor, optional): Class labels of ground truth bboxes.\n\n        Returns:\n            :obj:`SamplingResult`: Sampling result.\n\n        Example:\n            >>> from mmcv.core.bbox import RandomSampler\n            >>> from mmcv.core.bbox import AssignResult\n            >>> from mmcv.core.bbox.demodata import ensure_rng, random_boxes\n            >>> rng = ensure_rng(None)\n            >>> assign_result = AssignResult.random(rng=rng)\n            >>> bboxes = random_boxes(assign_result.num_preds, rng=rng)\n            >>> gt_bboxes = random_boxes(assign_result.num_gts, rng=rng)\n            >>> gt_labels = None\n            >>> self = RandomSampler(num=32, pos_fraction=0.5, neg_pos_ub=-1,\n            >>>                      add_gt_as_proposals=False)\n            >>> self = self.sample(assign_result, bboxes, gt_bboxes, gt_labels)\n        \"\"\"\n        if len(bboxes.shape) < 2:\n            bboxes = bboxes[None, :]\n\n        bboxes = bboxes[:, :4]\n\n        gt_flags = bboxes.new_zeros((bboxes.shape[0], ), dtype=torch.uint8)\n        if self.add_gt_as_proposals and len(gt_bboxes) > 0:\n            if gt_labels is None:\n                raise ValueError(\n                    'gt_labels must be given when add_gt_as_proposals is True')\n            bboxes = torch.cat([gt_bboxes, bboxes], dim=0)\n            assign_result.add_gt_(gt_labels)\n            gt_ones = bboxes.new_ones(gt_bboxes.shape[0], dtype=torch.uint8)\n            gt_flags = torch.cat([gt_ones, gt_flags])\n\n        num_expected_pos = int(self.num * self.pos_fraction)\n        pos_inds = self.pos_sampler._sample_pos(\n            assign_result, num_expected_pos, bboxes=bboxes, **kwargs)\n        # We found that sampled indices have duplicated items occasionally.\n        # (may be a bug of PyTorch)\n        pos_inds = pos_inds.unique()\n        num_sampled_pos = pos_inds.numel()\n        num_expected_neg = self.num - num_sampled_pos\n        if self.neg_pos_ub >= 0:\n            _pos = max(1, num_sampled_pos)\n            neg_upper_bound = int(self.neg_pos_ub * _pos)\n            if num_expected_neg > neg_upper_bound:\n                num_expected_neg = neg_upper_bound\n        neg_inds = self.neg_sampler._sample_neg(\n            assign_result, num_expected_neg, bboxes=bboxes, **kwargs)\n        neg_inds = neg_inds.unique()\n\n        sampling_result = SamplingResult(pos_inds, neg_inds, bboxes, gt_bboxes,\n                                         assign_result, gt_flags)\n        return sampling_result\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/samplers/pseudo_sampler.py",
    "content": "import torch\n\nfrom ..builder import BBOX_SAMPLERS\nfrom .base_sampler import BaseSampler\nfrom .sampling_result import SamplingResult\n\n\n@BBOX_SAMPLERS.register_module()\nclass PseudoSampler(BaseSampler):\n    \"\"\"A pseudo sampler that does not do sampling actually.\"\"\"\n\n    def __init__(self, **kwargs):\n        pass\n\n    def _sample_pos(self, **kwargs):\n        \"\"\"Sample positive samples.\"\"\"\n        raise NotImplementedError\n\n    def _sample_neg(self, **kwargs):\n        \"\"\"Sample negative samples.\"\"\"\n        raise NotImplementedError\n\n    def sample(self, assign_result, bboxes, gt_bboxes, **kwargs):\n        \"\"\"Directly returns the positive and negative indices  of samples.\n\n        Args:\n            assign_result (:obj:`AssignResult`): Assigned results\n            bboxes (torch.Tensor): Bounding boxes\n            gt_bboxes (torch.Tensor): Ground truth boxes\n\n        Returns:\n            :obj:`SamplingResult`: sampler results\n        \"\"\"\n        pos_inds = torch.nonzero(\n            assign_result.gt_inds > 0, as_tuple=False).squeeze(-1).unique()\n        neg_inds = torch.nonzero(\n            assign_result.gt_inds == 0, as_tuple=False).squeeze(-1).unique()\n        gt_flags = bboxes.new_zeros(bboxes.shape[0], dtype=torch.uint8)\n        sampling_result = SamplingResult(pos_inds, neg_inds, bboxes, gt_bboxes,\n                                         assign_result, gt_flags)\n        return sampling_result\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/samplers/sampling_result.py",
    "content": "import torch\n\nfrom mmcv.utils import util_mixins\n\n\nclass SamplingResult(util_mixins.NiceRepr):\n    \"\"\"Bbox sampling result.\n\n    Example:\n        >>> # xdoctest: +IGNORE_WANT\n        >>> from mmcv.core.bbox.samplers.sampling_result import *  # NOQA\n        >>> self = SamplingResult.random(rng=10)\n        >>> print(f'self = {self}')\n        self = <SamplingResult({\n            'neg_bboxes': torch.Size([12, 4]),\n            'neg_inds': tensor([ 0,  1,  2,  4,  5,  6,  7,  8,  9, 10, 11, 12]),\n            'num_gts': 4,\n            'pos_assigned_gt_inds': tensor([], dtype=torch.int64),\n            'pos_bboxes': torch.Size([0, 4]),\n            'pos_inds': tensor([], dtype=torch.int64),\n            'pos_is_gt': tensor([], dtype=torch.uint8)\n        })>\n    \"\"\"\n\n    def __init__(self, pos_inds, neg_inds, bboxes, gt_bboxes, assign_result,\n                 gt_flags):\n        self.pos_inds = pos_inds\n        self.neg_inds = neg_inds\n        self.pos_bboxes = bboxes[pos_inds]\n        self.neg_bboxes = bboxes[neg_inds]\n        self.pos_is_gt = gt_flags[pos_inds]\n\n        self.num_gts = gt_bboxes.shape[0]\n        self.pos_assigned_gt_inds = assign_result.gt_inds[pos_inds] - 1\n\n        if gt_bboxes.numel() == 0:\n            # hack for index error case\n            assert self.pos_assigned_gt_inds.numel() == 0\n            self.pos_gt_bboxes = torch.empty_like(gt_bboxes).view(-1, 4)\n        else:\n            if len(gt_bboxes.shape) < 2:\n                gt_bboxes = gt_bboxes.view(-1, 4)\n\n            self.pos_gt_bboxes = gt_bboxes[self.pos_assigned_gt_inds, :]\n\n        if assign_result.labels is not None:\n            self.pos_gt_labels = assign_result.labels[pos_inds]\n        else:\n            self.pos_gt_labels = None\n\n    @property\n    def bboxes(self):\n        \"\"\"torch.Tensor: concatenated positive and negative boxes\"\"\"\n        return torch.cat([self.pos_bboxes, self.neg_bboxes])\n\n    def to(self, device):\n        \"\"\"Change the device of the data inplace.\n\n        Example:\n            >>> self = SamplingResult.random()\n            >>> print(f'self = {self.to(None)}')\n            >>> # xdoctest: +REQUIRES(--gpu)\n            >>> print(f'self = {self.to(0)}')\n        \"\"\"\n        _dict = self.__dict__\n        for key, value in _dict.items():\n            if isinstance(value, torch.Tensor):\n                _dict[key] = value.to(device)\n        return self\n\n    def __nice__(self):\n        data = self.info.copy()\n        data['pos_bboxes'] = data.pop('pos_bboxes').shape\n        data['neg_bboxes'] = data.pop('neg_bboxes').shape\n        parts = [f\"'{k}': {v!r}\" for k, v in sorted(data.items())]\n        body = '    ' + ',\\n    '.join(parts)\n        return '{\\n' + body + '\\n}'\n\n    @property\n    def info(self):\n        \"\"\"Returns a dictionary of info about the object.\"\"\"\n        return {\n            'pos_inds': self.pos_inds,\n            'neg_inds': self.neg_inds,\n            'pos_bboxes': self.pos_bboxes,\n            'neg_bboxes': self.neg_bboxes,\n            'pos_is_gt': self.pos_is_gt,\n            'num_gts': self.num_gts,\n            'pos_assigned_gt_inds': self.pos_assigned_gt_inds,\n        }\n\n    @classmethod\n    def random(cls, rng=None, **kwargs):\n        \"\"\"\n        Args:\n            rng (None | int | numpy.random.RandomState): seed or state.\n            kwargs (keyword arguments):\n                - num_preds: number of predicted boxes\n                - num_gts: number of true boxes\n                - p_ignore (float): probability of a predicted box assigned to \\\n                    an ignored truth.\n                - p_assigned (float): probability of a predicted box not being \\\n                    assigned.\n                - p_use_label (float | bool): with labels or not.\n\n        Returns:\n            :obj:`SamplingResult`: Randomly generated sampling result.\n\n        Example:\n            >>> from mmcv.core.bbox.samplers.sampling_result import *  # NOQA\n            >>> self = SamplingResult.random()\n            >>> print(self.__dict__)\n        \"\"\"\n        from mmcv.core.bbox.samplers.random_sampler import RandomSampler\n        from mmcv.core.bbox.assigners.assign_result import AssignResult\n        from mmcv.core.bbox import demodata\n        rng = demodata.ensure_rng(rng)\n\n        # make probabalistic?\n        num = 32\n        pos_fraction = 0.5\n        neg_pos_ub = -1\n\n        assign_result = AssignResult.random(rng=rng, **kwargs)\n\n        # Note we could just compute an assignment\n        bboxes = demodata.random_boxes(assign_result.num_preds, rng=rng)\n        gt_bboxes = demodata.random_boxes(assign_result.num_gts, rng=rng)\n\n        if rng.rand() > 0.2:\n            # sometimes algorithms squeeze their data, be robust to that\n            gt_bboxes = gt_bboxes.squeeze()\n            bboxes = bboxes.squeeze()\n\n        if assign_result.labels is None:\n            gt_labels = None\n        else:\n            gt_labels = None  # todo\n\n        if gt_labels is None:\n            add_gt_as_proposals = False\n        else:\n            add_gt_as_proposals = True  # make probabalistic?\n\n        sampler = RandomSampler(\n            num,\n            pos_fraction,\n            neg_pos_ub=neg_pos_ub,\n            add_gt_as_proposals=add_gt_as_proposals,\n            rng=rng)\n        self = sampler.sample(assign_result, bboxes, gt_bboxes, gt_labels)\n        return self\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n\nfrom .utils import (get_box_type, get_proj_mat_by_coord_type, limit_period,\n                    mono_cam_box2vis, points_cam2img, rotation_3d_in_axis,\n                    xywhr2xyxyr)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/base_box3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom abc import abstractmethod\n\n# from mmcv.ops.iou3d import iou3d_cuda\nfrom .utils import limit_period, xywhr2xyxyr\nfrom mmcv.ops.iou3d_det import iou3d_cuda\n\n\nclass BaseInstance3DBoxes(object):\n    \"\"\"Base class for 3D Boxes.\n\n    Note:\n        The box is bottom centered, i.e. the relative position of origin in\n        the box is (0.5, 0.5, 0).\n\n    Args:\n        tensor (torch.Tensor | np.ndarray | list): a N x box_dim matrix.\n        box_dim (int): Number of the dimension of a box.\n            Each row is (x, y, z, x_size, y_size, z_size, yaw).\n            Default to 7.\n        with_yaw (bool): Whether the box is with yaw rotation.\n            If False, the value of yaw will be set to 0 as minmax boxes.\n            Default to True.\n        origin (tuple[float]): The relative position of origin in the box.\n            Default to (0.5, 0.5, 0). This will guide the box be converted to\n            (0.5, 0.5, 0) mode.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x box_dim.\n        box_dim (int): Integer indicating the dimension of a box.\n            Each row is (x, y, z, x_size, y_size, z_size, yaw, ...).\n        with_yaw (bool): If True, the value of yaw will be set to 0 as minmax\n            boxes.\n    \"\"\"\n\n    def __init__(self, tensor, box_dim=7, with_yaw=True, origin=(0.5, 0.5, 0)):\n        if isinstance(tensor, torch.Tensor):\n            device = tensor.device\n        else:\n            device = torch.device('cpu')\n        tensor = torch.as_tensor(tensor, dtype=torch.float32, device=device)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that\n            # does not depend on the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((0, box_dim)).to(\n                dtype=torch.float32, device=device)\n        assert tensor.dim() == 2 and tensor.size(-1) == box_dim, tensor.size()\n\n        if tensor.shape[-1] == 6:\n            # If the dimension of boxes is 6, we expand box_dim by padding\n            # 0 as a fake yaw and set with_yaw to False.\n            assert box_dim == 6\n            fake_rot = tensor.new_zeros(tensor.shape[0], 1)\n            tensor = torch.cat((tensor, fake_rot), dim=-1)\n            self.box_dim = box_dim + 1\n            self.with_yaw = False\n        else:\n            self.box_dim = box_dim\n            self.with_yaw = with_yaw\n        self.tensor = tensor.clone()\n\n        if origin != (0.5, 0.5, 0):\n            dst = self.tensor.new_tensor((0.5, 0.5, 0))\n            src = self.tensor.new_tensor(origin)\n            self.tensor[:, :3] += self.tensor[:, 3:6] * (dst - src)\n\n    @property\n    def volume(self):\n        \"\"\"torch.Tensor: A vector with volume of each box.\"\"\"\n        return self.tensor[:, 3] * self.tensor[:, 4] * self.tensor[:, 5]\n\n    @property\n    def dims(self):\n        \"\"\"torch.Tensor: Corners of each box with size (N, 8, 3).\"\"\"\n        return self.tensor[:, 3:6]\n\n    @property\n    def yaw(self):\n        \"\"\"torch.Tensor: A vector with yaw of each box.\"\"\"\n        return self.tensor[:, 6]\n\n    @property\n    def height(self):\n        \"\"\"torch.Tensor: A vector with height of each box.\"\"\"\n        return self.tensor[:, 5]\n\n    @property\n    def top_height(self):\n        \"\"\"torch.Tensor: A vector with the top height of each box.\"\"\"\n        return self.bottom_height + self.height\n\n    @property\n    def bottom_height(self):\n        \"\"\"torch.Tensor: A vector with bottom's height of each box.\"\"\"\n        return self.tensor[:, 2]\n\n    @property\n    def center(self):\n        \"\"\"Calculate the center of all the boxes.\n\n        Note:\n            In the MMDetection3D's convention, the bottom center is\n            usually taken as the default center.\n\n            The relative position of the centers in different kinds of\n            boxes are different, e.g., the relative center of a boxes is\n            (0.5, 1.0, 0.5) in camera and (0.5, 0.5, 0) in lidar.\n            It is recommended to use ``bottom_center`` or ``gravity_center``\n            for more clear usage.\n\n        Returns:\n            torch.Tensor: A tensor with center of each box.\n        \"\"\"\n        return self.bottom_center\n\n    @property\n    def bottom_center(self):\n        \"\"\"torch.Tensor: A tensor with center of each box.\"\"\"\n        return self.tensor[:, :3]\n\n    @property\n    def gravity_center(self):\n        \"\"\"torch.Tensor: A tensor with center of each box.\"\"\"\n        pass\n\n    @property\n    def corners(self):\n        \"\"\"torch.Tensor: a tensor with 8 corners of each box.\"\"\"\n        pass\n\n    @abstractmethod\n    def rotate(self, angle, points=None):\n        \"\"\"Rotate boxes with points (optional) with the given angle or \\\n        rotation matrix.\n\n        Args:\n            angle (float | torch.Tensor | np.ndarray):\n                Rotation angle or rotation matrix.\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, optional):\n                Points to rotate. Defaults to None.\n        \"\"\"\n        pass\n\n    @abstractmethod\n    def flip(self, bev_direction='horizontal'):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\"\"\"\n        pass\n\n    def translate(self, trans_vector):\n        \"\"\"Translate boxes with the given translation vector.\n\n        Args:\n            trans_vector (torch.Tensor): Translation vector of size 1x3.\n        \"\"\"\n        if not isinstance(trans_vector, torch.Tensor):\n            trans_vector = self.tensor.new_tensor(trans_vector)\n        self.tensor[:, :3] += trans_vector\n\n    def in_range_3d(self, box_range):\n        \"\"\"Check whether the boxes are in the given range.\n\n        Args:\n            box_range (list | torch.Tensor): The range of box\n                (x_min, y_min, z_min, x_max, y_max, z_max)\n\n        Note:\n            In the original implementation of SECOND, checking whether\n            a box in the range checks whether the points are in a convex\n            polygon, we try to reduce the burden for simpler cases.\n\n        Returns:\n            torch.Tensor: A binary vector indicating whether each box is \\\n                inside the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > box_range[0])\n                          & (self.tensor[:, 1] > box_range[1])\n                          & (self.tensor[:, 2] > box_range[2])\n                          & (self.tensor[:, 0] < box_range[3])\n                          & (self.tensor[:, 1] < box_range[4])\n                          & (self.tensor[:, 2] < box_range[5]))\n        return in_range_flags\n\n    @abstractmethod\n    def in_range_bev(self, box_range):\n        \"\"\"Check whether the boxes are in the given range.\n\n        Args:\n            box_range (list | torch.Tensor): The range of box\n                in order of (x_min, y_min, x_max, y_max).\n\n        Returns:\n            torch.Tensor: Indicating whether each box is inside \\\n                the reference range.\n        \"\"\"\n        pass\n\n    @abstractmethod\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`Box3DMode`): The target Box mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: The converted box of the same type \\\n                in the `dst` mode.\n        \"\"\"\n        pass\n\n    def scale(self, scale_factor):\n        \"\"\"Scale the box with horizontal and vertical scaling factors.\n\n        Args:\n            scale_factors (float): Scale factors to scale the boxes.\n        \"\"\"\n        self.tensor[:, :6] *= scale_factor\n        self.tensor[:, 7:] *= scale_factor\n\n    def limit_yaw(self, offset=0.5, period=np.pi):\n        \"\"\"Limit the yaw to a given period and offset.\n\n        Args:\n            offset (float): The offset of the yaw.\n            period (float): The expected period.\n        \"\"\"\n        self.tensor[:, 6] = limit_period(self.tensor[:, 6], offset, period)\n\n    def nonempty(self, threshold: float = 0.0):\n        \"\"\"Find boxes that are non-empty.\n\n        A box is considered empty,\n        if either of its side is no larger than threshold.\n\n        Args:\n            threshold (float): The threshold of minimal sizes.\n\n        Returns:\n            torch.Tensor: A binary vector which represents whether each \\\n                box is empty (False) or non-empty (True).\n        \"\"\"\n        box = self.tensor\n        size_x = box[..., 3]\n        size_y = box[..., 4]\n        size_z = box[..., 5]\n        keep = ((size_x > threshold)\n                & (size_y > threshold) & (size_z > threshold))\n        return keep\n\n    def __getitem__(self, item):\n        \"\"\"\n        Note:\n            The following usage are allowed:\n            1. `new_boxes = boxes[3]`:\n                return a `Boxes` that contains only one box.\n            2. `new_boxes = boxes[2:10]`:\n                return a slice of boxes.\n            3. `new_boxes = boxes[vector]`:\n                where vector is a torch.BoolTensor with `length = len(boxes)`.\n                Nonzero elements in the vector will be selected.\n            Note that the returned Boxes might share storage with this Boxes,\n            subject to Pytorch's indexing semantics.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: A new object of  \\\n                :class:`BaseInstances3DBoxes` after indexing.\n        \"\"\"\n        original_type = type(self)\n        if isinstance(item, int):\n            return original_type(\n                self.tensor[item].view(1, -1),\n                box_dim=self.box_dim,\n                with_yaw=self.with_yaw)\n        b = self.tensor[item]\n        assert b.dim() == 2, \\\n            f'Indexing on Boxes with {item} failed to return a matrix!'\n        return original_type(b, box_dim=self.box_dim, with_yaw=self.with_yaw)\n\n    def __len__(self):\n        \"\"\"int: Number of boxes in the current object.\"\"\"\n        return self.tensor.shape[0]\n\n    def __repr__(self):\n        \"\"\"str: Return a strings that describes the object.\"\"\"\n        return self.__class__.__name__ + '(\\n    ' + str(self.tensor) + ')'\n\n    @classmethod\n    def cat(cls, boxes_list):\n        \"\"\"Concatenate a list of Boxes into a single Boxes.\n\n        Args:\n            boxes_list (list[:obj:`BaseInstance3DBoxes`]): List of boxes.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: The concatenated Boxes.\n        \"\"\"\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0))\n        assert all(isinstance(box, cls) for box in boxes_list)\n\n        # use torch.cat (v.s. layers.cat)\n        # so the returned boxes never share storage with input\n        cat_boxes = cls(\n            torch.cat([b.tensor for b in boxes_list], dim=0),\n            box_dim=boxes_list[0].tensor.shape[1],\n            with_yaw=boxes_list[0].with_yaw)\n        return cat_boxes\n\n    def to(self, device):\n        \"\"\"Convert current boxes to a specific device.\n\n        Args:\n            device (str | :obj:`torch.device`): The name of the device.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: A new boxes object on the \\\n                specific device.\n        \"\"\"\n        original_type = type(self)\n        return original_type(\n            self.tensor.to(device),\n            box_dim=self.box_dim,\n            with_yaw=self.with_yaw)\n\n    def clone(self):\n        \"\"\"Clone the Boxes.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: Box object with the same properties \\\n                as self.\n        \"\"\"\n        original_type = type(self)\n        return original_type(\n            self.tensor.clone(), box_dim=self.box_dim, with_yaw=self.with_yaw)\n\n    @property\n    def device(self):\n        \"\"\"str: The device of the boxes are on.\"\"\"\n        return self.tensor.device\n\n    def __iter__(self):\n        \"\"\"Yield a box as a Tensor of shape (4,) at a time.\n\n        Returns:\n            torch.Tensor: A box of shape (4,).\n        \"\"\"\n        yield from self.tensor\n\n    @classmethod\n    def height_overlaps(cls, boxes1, boxes2, mode='iou'):\n        \"\"\"Calculate height overlaps of two boxes.\n\n        Note:\n            This function calculates the height overlaps between boxes1 and\n            boxes2,  boxes1 and boxes2 should be in the same type.\n\n        Args:\n            boxes1 (:obj:`BaseInstance3DBoxes`): Boxes 1 contain N boxes.\n            boxes2 (:obj:`BaseInstance3DBoxes`): Boxes 2 contain M boxes.\n            mode (str, optional): Mode of iou calculation. Defaults to 'iou'.\n\n        Returns:\n            torch.Tensor: Calculated iou of boxes.\n        \"\"\"\n        assert isinstance(boxes1, BaseInstance3DBoxes)\n        assert isinstance(boxes2, BaseInstance3DBoxes)\n        assert type(boxes1) == type(boxes2), '\"boxes1\" and \"boxes2\" should' \\\n            f'be in the same type, got {type(boxes1)} and {type(boxes2)}.'\n\n        boxes1_top_height = boxes1.top_height.view(-1, 1)\n        boxes1_bottom_height = boxes1.bottom_height.view(-1, 1)\n        boxes2_top_height = boxes2.top_height.view(1, -1)\n        boxes2_bottom_height = boxes2.bottom_height.view(1, -1)\n\n        heighest_of_bottom = torch.max(boxes1_bottom_height,\n                                       boxes2_bottom_height)\n        lowest_of_top = torch.min(boxes1_top_height, boxes2_top_height)\n        overlaps_h = torch.clamp(lowest_of_top - heighest_of_bottom, min=0)\n        return overlaps_h\n\n    @classmethod\n    def overlaps(cls, boxes1, boxes2, mode='iou'):\n        \"\"\"Calculate 3D overlaps of two boxes.\n\n        Note:\n            This function calculates the overlaps between ``boxes1`` and\n            ``boxes2``, ``boxes1`` and ``boxes2`` should be in the same type.\n\n        Args:\n            boxes1 (:obj:`BaseInstance3DBoxes`): Boxes 1 contain N boxes.\n            boxes2 (:obj:`BaseInstance3DBoxes`): Boxes 2 contain M boxes.\n            mode (str, optional): Mode of iou calculation. Defaults to 'iou'.\n\n        Returns:\n            torch.Tensor: Calculated iou of boxes' heights.\n        \"\"\"\n        assert isinstance(boxes1, BaseInstance3DBoxes)\n        assert isinstance(boxes2, BaseInstance3DBoxes)\n        assert type(boxes1) == type(boxes2), '\"boxes1\" and \"boxes2\" should' \\\n            f'be in the same type, got {type(boxes1)} and {type(boxes2)}.'\n\n        assert mode in ['iou', 'iof']\n\n        rows = len(boxes1)\n        cols = len(boxes2)\n        if rows * cols == 0:\n            return boxes1.tensor.new(rows, cols)\n\n        # height overlap\n        overlaps_h = cls.height_overlaps(boxes1, boxes2)\n\n        # obtain BEV boxes in XYXYR format\n        boxes1_bev = xywhr2xyxyr(boxes1.bev)\n        boxes2_bev = xywhr2xyxyr(boxes2.bev)\n\n        # bev overlap\n        overlaps_bev = boxes1_bev.new_zeros(\n            (boxes1_bev.shape[0], boxes2_bev.shape[0])).cuda()  # (N, M)\n        iou3d_cuda.boxes_overlap_bev_gpu(boxes1_bev.contiguous().cuda(),\n                                         boxes2_bev.contiguous().cuda(),\n                                         overlaps_bev)\n\n        # 3d overlaps\n        overlaps_3d = overlaps_bev.to(boxes1.device) * overlaps_h\n\n        volume1 = boxes1.volume.view(-1, 1)\n        volume2 = boxes2.volume.view(1, -1)\n\n        if mode == 'iou':\n            # the clamp func is used to avoid division of 0\n            iou3d = overlaps_3d / torch.clamp(\n                volume1 + volume2 - overlaps_3d, min=1e-8)\n        else:\n            iou3d = overlaps_3d / torch.clamp(volume1, min=1e-8)\n\n        return iou3d\n\n    def new_box(self, data):\n        \"\"\"Create a new box object with data.\n\n        The new box and its tensor has the similar properties \\\n            as self and self.tensor, respectively.\n\n        Args:\n            data (torch.Tensor | numpy.array | list): Data to be copied.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: A new bbox object with ``data``, \\\n                the object's other properties are similar to ``self``.\n        \"\"\"\n        new_tensor = self.tensor.new_tensor(data) \\\n            if not isinstance(data, torch.Tensor) else data.to(self.device)\n        original_type = type(self)\n        return original_type(\n            new_tensor, box_dim=self.box_dim, with_yaw=self.with_yaw)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/box_3d_mode.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom enum import IntEnum, unique\n\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .cam_box3d import CameraInstance3DBoxes\nfrom .depth_box3d import DepthInstance3DBoxes\nfrom .lidar_box3d import LiDARInstance3DBoxes\n\n\n@unique\nclass Box3DMode(IntEnum):\n    r\"\"\"Enum of different ways to represent a box.\n\n    Coordinates in LiDAR:\n\n    .. code-block:: none\n\n                    up z\n                       ^   x front\n                       |  /\n                       | /\n        left y <------ 0\n\n    The relative coordinate of bottom center in a LiDAR box is (0.5, 0.5, 0),\n    and the yaw is around the z axis, thus the rotation axis=2.\n\n    Coordinates in camera:\n\n    .. code-block:: none\n\n                z front\n               /\n              /\n             0 ------> x right\n             |\n             |\n             v\n        down y\n\n    The relative coordinate of bottom center in a CAM box is [0.5, 1.0, 0.5],\n    and the yaw is around the y axis, thus the rotation axis=1.\n\n    Coordinates in Depth mode:\n\n    .. code-block:: none\n\n        up z\n           ^   y front\n           |  /\n           | /\n           0 ------> x right\n\n    The relative coordinate of bottom center in a DEPTH box is (0.5, 0.5, 0),\n    and the yaw is around the z axis, thus the rotation axis=2.\n    \"\"\"\n\n    LIDAR = 0\n    CAM = 1\n    DEPTH = 2\n\n    @staticmethod\n    def convert(box, src, dst, rt_mat=None):\n        \"\"\"Convert boxes from `src` mode to `dst` mode.\n\n        Args:\n            box (tuple | list | np.ndarray |\n                torch.Tensor | BaseInstance3DBoxes):\n                Can be a k-tuple, k-list or an Nxk array/tensor, where k = 7.\n            src (:obj:`Box3DMode`): The src Box mode.\n            dst (:obj:`Box3DMode`): The target Box mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            (tuple | list | np.ndarray | torch.Tensor | BaseInstance3DBoxes): \\\n                The converted box of the same type.\n        \"\"\"\n        if src == dst:\n            return box\n\n        is_numpy = isinstance(box, np.ndarray)\n        is_Instance3DBoxes = isinstance(box, BaseInstance3DBoxes)\n        single_box = isinstance(box, (list, tuple))\n        if single_box:\n            assert len(box) >= 7, (\n                'Box3DMode.convert takes either a k-tuple/list or '\n                'an Nxk array/tensor, where k >= 7')\n            arr = torch.tensor(box)[None, :]\n        else:\n            # avoid modifying the input box\n            if is_numpy:\n                arr = torch.from_numpy(np.asarray(box)).clone()\n            elif is_Instance3DBoxes:\n                arr = box.tensor.clone()\n            else:\n                arr = box.clone()\n\n        # convert box from `src` mode to `dst` mode.\n        x_size, y_size, z_size = arr[..., 3:4], arr[..., 4:5], arr[..., 5:6]\n        if src == Box3DMode.LIDAR and dst == Box3DMode.CAM:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, -1, 0], [0, 0, -1], [1, 0, 0]])\n            xyz_size = torch.cat([y_size, z_size, x_size], dim=-1)\n        elif src == Box3DMode.CAM and dst == Box3DMode.LIDAR:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, 0, 1], [-1, 0, 0], [0, -1, 0]])\n            xyz_size = torch.cat([z_size, x_size, y_size], dim=-1)\n        elif src == Box3DMode.DEPTH and dst == Box3DMode.CAM:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[1, 0, 0], [0, 0, 1], [0, -1, 0]])\n            xyz_size = torch.cat([x_size, z_size, y_size], dim=-1)\n        elif src == Box3DMode.CAM and dst == Box3DMode.DEPTH:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[1, 0, 0], [0, 0, -1], [0, 1, 0]])\n            xyz_size = torch.cat([x_size, z_size, y_size], dim=-1)\n        elif src == Box3DMode.LIDAR and dst == Box3DMode.DEPTH:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, -1, 0], [1, 0, 0], [0, 0, 1]])\n            xyz_size = torch.cat([y_size, x_size, z_size], dim=-1)\n        elif src == Box3DMode.DEPTH and dst == Box3DMode.LIDAR:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, 1, 0], [-1, 0, 0], [0, 0, 1]])\n            xyz_size = torch.cat([y_size, x_size, z_size], dim=-1)\n        else:\n            raise NotImplementedError(\n                f'Conversion from Box3DMode {src} to {dst} '\n                'is not supported yet')\n\n        if not isinstance(rt_mat, torch.Tensor):\n            rt_mat = arr.new_tensor(rt_mat)\n        if rt_mat.size(1) == 4:\n            extended_xyz = torch.cat(\n                [arr[:, :3], arr.new_ones(arr.size(0), 1)], dim=-1)\n            xyz = extended_xyz @ rt_mat.t()\n        else:\n            xyz = arr[:, :3] @ rt_mat.t()\n\n        remains = arr[..., 6:]\n        arr = torch.cat([xyz[:, :3], xyz_size, remains], dim=-1)\n\n        # convert arr to the original type\n        original_type = type(box)\n        if single_box:\n            return original_type(arr.flatten().tolist())\n        if is_numpy:\n            return arr.numpy()\n        elif is_Instance3DBoxes:\n            if dst == Box3DMode.CAM:\n                target_type = CameraInstance3DBoxes\n            elif dst == Box3DMode.LIDAR:\n                target_type = LiDARInstance3DBoxes\n            elif dst == Box3DMode.DEPTH:\n                target_type = DepthInstance3DBoxes\n            else:\n                raise NotImplementedError(\n                    f'Conversion to {dst} through {original_type}'\n                    ' is not supported yet')\n            return target_type(\n                arr, box_dim=arr.size(-1), with_yaw=box.with_yaw)\n        else:\n            return arr\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/cam_box3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmcv.core.points import BasePoints\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .utils import limit_period, rotation_3d_in_axis\n\n\nclass CameraInstance3DBoxes(BaseInstance3DBoxes):\n    \"\"\"3D boxes of instances in CAM coordinates.\n\n    Coordinates in camera:\n\n    .. code-block:: none\n\n                z front (yaw=-0.5*pi)\n               /\n              /\n             0 ------> x right (yaw=0)\n             |\n             |\n             v\n        down y\n\n    The relative coordinate of bottom center in a CAM box is (0.5, 1.0, 0.5),\n    and the yaw is around the y axis, thus the rotation axis=1.\n    The yaw is 0 at the positive direction of x axis, and decreases from\n    the positive direction of x to the positive direction of z.\n\n    A refactor is ongoing to make the three coordinate systems\n    easier to understand and convert between each other.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x box_dim.\n        box_dim (int): Integer indicates the dimension of a box\n            Each row is (x, y, z, x_size, y_size, z_size, yaw, ...).\n        with_yaw (bool): If True, the value of yaw will be set to 0 as minmax\n            boxes.\n    \"\"\"\n\n    def __init__(self,\n                 tensor,\n                 box_dim=7,\n                 with_yaw=True,\n                 origin=(0.5, 1.0, 0.5)):\n        if isinstance(tensor, torch.Tensor):\n            device = tensor.device\n        else:\n            device = torch.device('cpu')\n        tensor = torch.as_tensor(tensor, dtype=torch.float32, device=device)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that\n            # does not depend on the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((0, box_dim)).to(\n                dtype=torch.float32, device=device)\n        assert tensor.dim() == 2 and tensor.size(-1) == box_dim, tensor.size()\n\n        if tensor.shape[-1] == 6:\n            # If the dimension of boxes is 6, we expand box_dim by padding\n            # 0 as a fake yaw and set with_yaw to False.\n            assert box_dim == 6\n            fake_rot = tensor.new_zeros(tensor.shape[0], 1)\n            tensor = torch.cat((tensor, fake_rot), dim=-1)\n            self.box_dim = box_dim + 1\n            self.with_yaw = False\n        else:\n            self.box_dim = box_dim\n            self.with_yaw = with_yaw\n        self.tensor = tensor.clone()\n\n        if origin != (0.5, 1.0, 0.5):\n            dst = self.tensor.new_tensor((0.5, 1.0, 0.5))\n            src = self.tensor.new_tensor(origin)\n            self.tensor[:, :3] += self.tensor[:, 3:6] * (dst - src)\n\n    @property\n    def height(self):\n        \"\"\"torch.Tensor: A vector with height of each box.\"\"\"\n        return self.tensor[:, 4]\n\n    @property\n    def top_height(self):\n        \"\"\"torch.Tensor: A vector with the top height of each box.\"\"\"\n        # the positive direction is down rather than up\n        return self.bottom_height - self.height\n\n    @property\n    def bottom_height(self):\n        \"\"\"torch.Tensor: A vector with bottom's height of each box.\"\"\"\n        return self.tensor[:, 1]\n\n    @property\n    def gravity_center(self):\n        \"\"\"torch.Tensor: A tensor with center of each box.\"\"\"\n        bottom_center = self.bottom_center\n        gravity_center = torch.zeros_like(bottom_center)\n        gravity_center[:, [0, 2]] = bottom_center[:, [0, 2]]\n        gravity_center[:, 1] = bottom_center[:, 1] - self.tensor[:, 4] * 0.5\n        return gravity_center\n\n    @property\n    def corners(self):\n        \"\"\"torch.Tensor: Coordinates of corners of all the boxes in\n                         shape (N, 8, 3).\n\n        Convert the boxes to  in clockwise order, in the form of\n        (x0y0z0, x0y0z1, x0y1z1, x0y1z0, x1y0z0, x1y0z1, x1y1z1, x1y1z0)\n\n        .. code-block:: none\n\n                         front z\n                              /\n                             /\n               (x0, y0, z1) + -----------  + (x1, y0, z1)\n                           /|            / |\n                          / |           /  |\n            (x0, y0, z0) + ----------- +   + (x1, y1, z1)\n                         |  /      .   |  /\n                         | / origin    | /\n            (x0, y1, z0) + ----------- + -------> x right\n                         |             (x1, y1, z0)\n                         |\n                         v\n                    down y\n        \"\"\"\n        # TODO: rotation_3d_in_axis function do not support\n        #  empty tensor currently.\n        assert len(self.tensor) != 0\n        dims = self.dims\n        corners_norm = torch.from_numpy(\n            np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)).to(\n                device=dims.device, dtype=dims.dtype)\n\n        corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n        # use relative origin [0.5, 1, 0.5]\n        corners_norm = corners_norm - dims.new_tensor([0.5, 1, 0.5])\n        corners = dims.view([-1, 1, 3]) * corners_norm.reshape([1, 8, 3])\n\n        # rotate around y axis\n        corners = rotation_3d_in_axis(corners, self.tensor[:, 6], axis=1)\n        corners += self.tensor[:, :3].view(-1, 1, 3)\n        return corners\n\n    @property\n    def bev(self):\n        \"\"\"torch.Tensor: A n x 5 tensor of 2D BEV box of each box\n        with rotation in XYWHR format.\"\"\"\n        return self.tensor[:, [0, 2, 3, 5, 6]]\n\n    @property\n    def nearest_bev(self):\n        \"\"\"torch.Tensor: A tensor of 2D BEV box of each box\n        without rotation.\"\"\"\n        # Obtain BEV boxes with rotation in XZWHR format\n        bev_rotated_boxes = self.bev\n        # convert the rotation to a valid range\n        rotations = bev_rotated_boxes[:, -1]\n        normed_rotations = torch.abs(limit_period(rotations, 0.5, np.pi))\n\n        # find the center of boxes\n        conditions = (normed_rotations > np.pi / 4)[..., None]\n        bboxes_xywh = torch.where(conditions, bev_rotated_boxes[:,\n                                                                [0, 1, 3, 2]],\n                                  bev_rotated_boxes[:, :4])\n\n        centers = bboxes_xywh[:, :2]\n        dims = bboxes_xywh[:, 2:]\n        bev_boxes = torch.cat([centers - dims / 2, centers + dims / 2], dim=-1)\n        return bev_boxes\n\n    def rotate(self, angle, points=None):\n        \"\"\"Rotate boxes with points (optional) with the given angle or \\\n        rotation matrix.\n\n        Args:\n            angle (float | torch.Tensor | np.ndarray):\n                Rotation angle or rotation matrix.\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, optional):\n                Points to rotate. Defaults to None.\n\n        Returns:\n            tuple or None: When ``points`` is None, the function returns \\\n                None, otherwise it returns the rotated points and the \\\n                rotation matrix ``rot_mat_T``.\n        \"\"\"\n        if not isinstance(angle, torch.Tensor):\n            angle = self.tensor.new_tensor(angle)\n        assert angle.shape == torch.Size([3, 3]) or angle.numel() == 1, \\\n            f'invalid rotation angle shape {angle.shape}'\n\n        if angle.numel() == 1:\n            rot_sin = torch.sin(angle)\n            rot_cos = torch.cos(angle)\n            rot_mat_T = self.tensor.new_tensor([[rot_cos, 0, -rot_sin],\n                                                [0, 1, 0],\n                                                [rot_sin, 0, rot_cos]])\n        else:\n            rot_mat_T = angle\n            rot_sin = rot_mat_T[2, 0]\n            rot_cos = rot_mat_T[0, 0]\n            angle = np.arctan2(rot_sin, rot_cos)\n\n        self.tensor[:, :3] = self.tensor[:, :3] @ rot_mat_T\n        self.tensor[:, 6] += angle\n\n        if points is not None:\n            if isinstance(points, torch.Tensor):\n                points[:, :3] = points[:, :3] @ rot_mat_T\n            elif isinstance(points, np.ndarray):\n                rot_mat_T = rot_mat_T.numpy()\n                points[:, :3] = np.dot(points[:, :3], rot_mat_T)\n            elif isinstance(points, BasePoints):\n                # clockwise\n                points.rotate(-angle)\n            else:\n                raise ValueError\n            return points, rot_mat_T\n\n    def flip(self, bev_direction='horizontal', points=None):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\n\n        In CAM coordinates, it flips the x (horizontal) or z (vertical) axis.\n\n        Args:\n            bev_direction (str): Flip direction (horizontal or vertical).\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, None):\n                Points to flip. Defaults to None.\n\n        Returns:\n            torch.Tensor, numpy.ndarray or None: Flipped points.\n        \"\"\"\n        assert bev_direction in ('horizontal', 'vertical')\n        if bev_direction == 'horizontal':\n            self.tensor[:, 0::7] = -self.tensor[:, 0::7]\n            if self.with_yaw:\n                self.tensor[:, 6] = -self.tensor[:, 6] + np.pi\n        elif bev_direction == 'vertical':\n            self.tensor[:, 2::7] = -self.tensor[:, 2::7]\n            if self.with_yaw:\n                self.tensor[:, 6] = -self.tensor[:, 6]\n\n        if points is not None:\n            assert isinstance(points, (torch.Tensor, np.ndarray, BasePoints))\n            if isinstance(points, (torch.Tensor, np.ndarray)):\n                if bev_direction == 'horizontal':\n                    points[:, 0] = -points[:, 0]\n                elif bev_direction == 'vertical':\n                    points[:, 2] = -points[:, 2]\n            elif isinstance(points, BasePoints):\n                points.flip(bev_direction)\n            return points\n\n    def in_range_bev(self, box_range):\n        \"\"\"Check whether the boxes are in the given range.\n\n        Args:\n            box_range (list | torch.Tensor): The range of box\n                (x_min, z_min, x_max, z_max).\n\n        Note:\n            The original implementation of SECOND checks whether boxes in\n            a range by checking whether the points are in a convex\n            polygon, we reduce the burden for simpler cases.\n\n        Returns:\n            torch.Tensor: Indicating whether each box is inside \\\n                the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > box_range[0])\n                          & (self.tensor[:, 2] > box_range[1])\n                          & (self.tensor[:, 0] < box_range[2])\n                          & (self.tensor[:, 2] < box_range[3]))\n        return in_range_flags\n\n    @classmethod\n    def height_overlaps(cls, boxes1, boxes2, mode='iou'):\n        \"\"\"Calculate height overlaps of two boxes.\n\n        This function calculates the height overlaps between ``boxes1`` and\n        ``boxes2``, where ``boxes1`` and ``boxes2`` should be in the same type.\n\n        Args:\n            boxes1 (:obj:`CameraInstance3DBoxes`): Boxes 1 contain N boxes.\n            boxes2 (:obj:`CameraInstance3DBoxes`): Boxes 2 contain M boxes.\n            mode (str, optional): Mode of iou calculation. Defaults to 'iou'.\n\n        Returns:\n            torch.Tensor: Calculated iou of boxes' heights.\n        \"\"\"\n        assert isinstance(boxes1, CameraInstance3DBoxes)\n        assert isinstance(boxes2, CameraInstance3DBoxes)\n\n        boxes1_top_height = boxes1.top_height.view(-1, 1)\n        boxes1_bottom_height = boxes1.bottom_height.view(-1, 1)\n        boxes2_top_height = boxes2.top_height.view(1, -1)\n        boxes2_bottom_height = boxes2.bottom_height.view(1, -1)\n\n        # In camera coordinate system\n        # from up to down is the positive direction\n        heighest_of_bottom = torch.min(boxes1_bottom_height,\n                                       boxes2_bottom_height)\n        lowest_of_top = torch.max(boxes1_top_height, boxes2_top_height)\n        overlaps_h = torch.clamp(heighest_of_bottom - lowest_of_top, min=0)\n        return overlaps_h\n\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`Box3DMode`): The target Box mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from ``src`` coordinates to ``dst`` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`:  \\\n                The converted box of the same type in the ``dst`` mode.\n        \"\"\"\n        from .box_3d_mode import Box3DMode\n        return Box3DMode.convert(\n            box=self, src=Box3DMode.CAM, dst=dst, rt_mat=rt_mat)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/coord_3d_mode.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom enum import IntEnum, unique\n\nfrom mmcv.core.points import (BasePoints, CameraPoints, DepthPoints,\n                                 LiDARPoints)\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .cam_box3d import CameraInstance3DBoxes\nfrom .depth_box3d import DepthInstance3DBoxes\nfrom .lidar_box3d import LiDARInstance3DBoxes\n\n\n@unique\nclass Coord3DMode(IntEnum):\n    r\"\"\"Enum of different ways to represent a box\n        and point cloud.\n\n    Coordinates in LiDAR:\n\n    .. code-block:: none\n\n                    up z\n                       ^   x front\n                       |  /\n                       | /\n        left y <------ 0\n\n    The relative coordinate of bottom center in a LiDAR box is (0.5, 0.5, 0),\n    and the yaw is around the z axis, thus the rotation axis=2.\n\n    Coordinates in camera:\n\n    .. code-block:: none\n\n                z front\n               /\n              /\n             0 ------> x right\n             |\n             |\n             v\n        down y\n\n    The relative coordinate of bottom center in a CAM box is [0.5, 1.0, 0.5],\n    and the yaw is around the y axis, thus the rotation axis=1.\n\n    Coordinates in Depth mode:\n\n    .. code-block:: none\n\n        up z\n           ^   y front\n           |  /\n           | /\n           0 ------> x right\n\n    The relative coordinate of bottom center in a DEPTH box is (0.5, 0.5, 0),\n    and the yaw is around the z axis, thus the rotation axis=2.\n    \"\"\"\n\n    LIDAR = 0\n    CAM = 1\n    DEPTH = 2\n\n    @staticmethod\n    def convert(input, src, dst, rt_mat=None):\n        \"\"\"Convert boxes or points from `src` mode to `dst` mode.\"\"\"\n        if isinstance(input, BaseInstance3DBoxes):\n            return Coord3DMode.convert_box(input, src, dst, rt_mat=rt_mat)\n        elif isinstance(input, BasePoints):\n            return Coord3DMode.convert_point(input, src, dst, rt_mat=rt_mat)\n        else:\n            raise NotImplementedError\n\n    @staticmethod\n    def convert_box(box, src, dst, rt_mat=None):\n        \"\"\"Convert boxes from `src` mode to `dst` mode.\n\n        Args:\n            box (tuple | list | np.ndarray |\n                torch.Tensor | BaseInstance3DBoxes):\n                Can be a k-tuple, k-list or an Nxk array/tensor, where k = 7.\n            src (:obj:`CoordMode`): The src Box mode.\n            dst (:obj:`CoordMode`): The target Box mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            (tuple | list | np.ndarray | torch.Tensor | BaseInstance3DBoxes): \\\n                The converted box of the same type.\n        \"\"\"\n        if src == dst:\n            return box\n\n        is_numpy = isinstance(box, np.ndarray)\n        is_Instance3DBoxes = isinstance(box, BaseInstance3DBoxes)\n        single_box = isinstance(box, (list, tuple))\n        if single_box:\n            assert len(box) >= 7, (\n                'CoordMode.convert takes either a k-tuple/list or '\n                'an Nxk array/tensor, where k >= 7')\n            arr = torch.tensor(box)[None, :]\n        else:\n            # avoid modifying the input box\n            if is_numpy:\n                arr = torch.from_numpy(np.asarray(box)).clone()\n            elif is_Instance3DBoxes:\n                arr = box.tensor.clone()\n            else:\n                arr = box.clone()\n\n        # convert box from `src` mode to `dst` mode.\n        x_size, y_size, z_size = arr[..., 3:4], arr[..., 4:5], arr[..., 5:6]\n        if src == Coord3DMode.LIDAR and dst == Coord3DMode.CAM:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, -1, 0], [0, 0, -1], [1, 0, 0]])\n            xyz_size = torch.cat([y_size, z_size, x_size], dim=-1)\n        elif src == Coord3DMode.CAM and dst == Coord3DMode.LIDAR:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, 0, 1], [-1, 0, 0], [0, -1, 0]])\n            xyz_size = torch.cat([z_size, x_size, y_size], dim=-1)\n        elif src == Coord3DMode.DEPTH and dst == Coord3DMode.CAM:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[1, 0, 0], [0, 0, 1], [0, -1, 0]])\n            xyz_size = torch.cat([x_size, z_size, y_size], dim=-1)\n        elif src == Coord3DMode.CAM and dst == Coord3DMode.DEPTH:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[1, 0, 0], [0, 0, -1], [0, 1, 0]])\n            xyz_size = torch.cat([x_size, z_size, y_size], dim=-1)\n        elif src == Coord3DMode.LIDAR and dst == Coord3DMode.DEPTH:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, -1, 0], [1, 0, 0], [0, 0, 1]])\n            xyz_size = torch.cat([y_size, x_size, z_size], dim=-1)\n        elif src == Coord3DMode.DEPTH and dst == Coord3DMode.LIDAR:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, 1, 0], [-1, 0, 0], [0, 0, 1]])\n            xyz_size = torch.cat([y_size, x_size, z_size], dim=-1)\n        else:\n            raise NotImplementedError(\n                f'Conversion from Coord3DMode {src} to {dst} '\n                'is not supported yet')\n\n        if not isinstance(rt_mat, torch.Tensor):\n            rt_mat = arr.new_tensor(rt_mat)\n        if rt_mat.size(1) == 4:\n            extended_xyz = torch.cat(\n                [arr[:, :3], arr.new_ones(arr.size(0), 1)], dim=-1)\n            xyz = extended_xyz @ rt_mat.t()\n        else:\n            xyz = arr[:, :3] @ rt_mat.t()\n\n        remains = arr[..., 6:]\n        arr = torch.cat([xyz[:, :3], xyz_size, remains], dim=-1)\n\n        # convert arr to the original type\n        original_type = type(box)\n        if single_box:\n            return original_type(arr.flatten().tolist())\n        if is_numpy:\n            return arr.numpy()\n        elif is_Instance3DBoxes:\n            if dst == Coord3DMode.CAM:\n                target_type = CameraInstance3DBoxes\n            elif dst == Coord3DMode.LIDAR:\n                target_type = LiDARInstance3DBoxes\n            elif dst == Coord3DMode.DEPTH:\n                target_type = DepthInstance3DBoxes\n            else:\n                raise NotImplementedError(\n                    f'Conversion to {dst} through {original_type}'\n                    ' is not supported yet')\n            return target_type(\n                arr, box_dim=arr.size(-1), with_yaw=box.with_yaw)\n        else:\n            return arr\n\n    @staticmethod\n    def convert_point(point, src, dst, rt_mat=None):\n        \"\"\"Convert points from `src` mode to `dst` mode.\n\n        Args:\n            point (tuple | list | np.ndarray |\n                torch.Tensor | BasePoints):\n                Can be a k-tuple, k-list or an Nxk array/tensor.\n            src (:obj:`CoordMode`): The src Point mode.\n            dst (:obj:`CoordMode`): The target Point mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            (tuple | list | np.ndarray | torch.Tensor | BasePoints): \\\n                The converted point of the same type.\n        \"\"\"\n        if src == dst:\n            return point\n\n        is_numpy = isinstance(point, np.ndarray)\n        is_InstancePoints = isinstance(point, BasePoints)\n        single_point = isinstance(point, (list, tuple))\n        if single_point:\n            assert len(point) >= 3, (\n                'CoordMode.convert takes either a k-tuple/list or '\n                'an Nxk array/tensor, where k >= 3')\n            arr = torch.tensor(point)[None, :]\n        else:\n            # avoid modifying the input point\n            if is_numpy:\n                arr = torch.from_numpy(np.asarray(point)).clone()\n            elif is_InstancePoints:\n                arr = point.tensor.clone()\n            else:\n                arr = point.clone()\n\n        # convert point from `src` mode to `dst` mode.\n        # TODO: LIDAR\n        # only implemented provided Rt matrix in cam-depth conversion\n        if src == Coord3DMode.LIDAR and dst == Coord3DMode.CAM:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, -1, 0], [0, 0, -1], [1, 0, 0]])\n        elif src == Coord3DMode.CAM and dst == Coord3DMode.LIDAR:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, 0, 1], [-1, 0, 0], [0, -1, 0]])\n        elif src == Coord3DMode.DEPTH and dst == Coord3DMode.CAM:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[1, 0, 0], [0, 0, -1], [0, 1, 0]])\n        elif src == Coord3DMode.CAM and dst == Coord3DMode.DEPTH:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[1, 0, 0], [0, 0, 1], [0, -1, 0]])\n        elif src == Coord3DMode.LIDAR and dst == Coord3DMode.DEPTH:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, -1, 0], [1, 0, 0], [0, 0, 1]])\n        elif src == Coord3DMode.DEPTH and dst == Coord3DMode.LIDAR:\n            if rt_mat is None:\n                rt_mat = arr.new_tensor([[0, 1, 0], [-1, 0, 0], [0, 0, 1]])\n        else:\n            raise NotImplementedError(\n                f'Conversion from Coord3DMode {src} to {dst} '\n                'is not supported yet')\n\n        if not isinstance(rt_mat, torch.Tensor):\n            rt_mat = arr.new_tensor(rt_mat)\n        if rt_mat.size(1) == 4:\n            extended_xyz = torch.cat(\n                [arr[:, :3], arr.new_ones(arr.size(0), 1)], dim=-1)\n            xyz = extended_xyz @ rt_mat.t()\n        else:\n            xyz = arr[:, :3] @ rt_mat.t()\n\n        remains = arr[:, 3:]\n        arr = torch.cat([xyz[:, :3], remains], dim=-1)\n\n        # convert arr to the original type\n        original_type = type(point)\n        if single_point:\n            return original_type(arr.flatten().tolist())\n        if is_numpy:\n            return arr.numpy()\n        elif is_InstancePoints:\n            if dst == Coord3DMode.CAM:\n                target_type = CameraPoints\n            elif dst == Coord3DMode.LIDAR:\n                target_type = LiDARPoints\n            elif dst == Coord3DMode.DEPTH:\n                target_type = DepthPoints\n            else:\n                raise NotImplementedError(\n                    f'Conversion to {dst} through {original_type}'\n                    ' is not supported yet')\n            return target_type(\n                arr,\n                points_dim=arr.size(-1),\n                attribute_dims=point.attribute_dims)\n        else:\n            return arr\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/depth_box3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmcv.core.points import BasePoints\nfrom mmcv.ops.roiaware_pool3d import points_in_boxes_batch\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .utils import limit_period, rotation_3d_in_axis\n\n\nclass DepthInstance3DBoxes(BaseInstance3DBoxes):\n    \"\"\"3D boxes of instances in Depth coordinates.\n\n    Coordinates in Depth:\n\n    .. code-block:: none\n\n                    up z    y front (yaw=-0.5*pi)\n                       ^   ^\n                       |  /\n                       | /\n                       0 ------> x right (yaw=0)\n\n    The relative coordinate of bottom center in a Depth box is (0.5, 0.5, 0),\n    and the yaw is around the z axis, thus the rotation axis=2.\n    The yaw is 0 at the positive direction of x axis, and decreases from\n    the positive direction of x to the positive direction of y.\n    Also note that rotation of DepthInstance3DBoxes is counterclockwise,\n    which is reverse to the definition of the yaw angle (clockwise).\n\n    A refactor is ongoing to make the three coordinate systems\n    easier to understand and convert between each other.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x box_dim.\n        box_dim (int): Integer indicates the dimension of a box\n            Each row is (x, y, z, x_size, y_size, z_size, yaw, ...).\n        with_yaw (bool): If True, the value of yaw will be set to 0 as minmax\n            boxes.\n    \"\"\"\n\n    @property\n    def gravity_center(self):\n        \"\"\"torch.Tensor: A tensor with center of each box.\"\"\"\n        bottom_center = self.bottom_center\n        gravity_center = torch.zeros_like(bottom_center)\n        gravity_center[:, :2] = bottom_center[:, :2]\n        gravity_center[:, 2] = bottom_center[:, 2] + self.tensor[:, 5] * 0.5\n        return gravity_center\n\n    @property\n    def corners(self):\n        \"\"\"torch.Tensor: Coordinates of corners of all the boxes\n        in shape (N, 8, 3).\n\n        Convert the boxes to corners in clockwise order, in form of\n        ``(x0y0z0, x0y0z1, x0y1z1, x0y1z0, x1y0z0, x1y0z1, x1y1z1, x1y1z0)``\n\n        .. code-block:: none\n\n                                           up z\n                            front y           ^\n                                 /            |\n                                /             |\n                  (x0, y1, z1) + -----------  + (x1, y1, z1)\n                              /|            / |\n                             / |           /  |\n               (x0, y0, z1) + ----------- +   + (x1, y1, z0)\n                            |  /      .   |  /\n                            | / origin    | /\n               (x0, y0, z0) + ----------- + --------> right x\n                                          (x1, y0, z0)\n        \"\"\"\n        # TODO: rotation_3d_in_axis function do not support\n        #  empty tensor currently.\n        assert len(self.tensor) != 0\n        dims = self.dims\n        corners_norm = torch.from_numpy(\n            np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)).to(\n                device=dims.device, dtype=dims.dtype)\n\n        corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n        # use relative origin (0.5, 0.5, 0)\n        corners_norm = corners_norm - dims.new_tensor([0.5, 0.5, 0])\n        corners = dims.view([-1, 1, 3]) * corners_norm.reshape([1, 8, 3])\n\n        # rotate around z axis\n        corners = rotation_3d_in_axis(corners, self.tensor[:, 6], axis=2)\n        corners += self.tensor[:, :3].view(-1, 1, 3)\n        return corners\n\n    @property\n    def bev(self):\n        \"\"\"torch.Tensor: A n x 5 tensor of 2D BEV box of each box\n        in XYWHR format.\"\"\"\n        return self.tensor[:, [0, 1, 3, 4, 6]]\n\n    @property\n    def nearest_bev(self):\n        \"\"\"torch.Tensor: A tensor of 2D BEV box of each box\n        without rotation.\"\"\"\n        # Obtain BEV boxes with rotation in XYWHR format\n        bev_rotated_boxes = self.bev\n        # convert the rotation to a valid range\n        rotations = bev_rotated_boxes[:, -1]\n        normed_rotations = torch.abs(limit_period(rotations, 0.5, np.pi))\n\n        # find the center of boxes\n        conditions = (normed_rotations > np.pi / 4)[..., None]\n        bboxes_xywh = torch.where(conditions, bev_rotated_boxes[:,\n                                                                [0, 1, 3, 2]],\n                                  bev_rotated_boxes[:, :4])\n\n        centers = bboxes_xywh[:, :2]\n        dims = bboxes_xywh[:, 2:]\n        bev_boxes = torch.cat([centers - dims / 2, centers + dims / 2], dim=-1)\n        return bev_boxes\n\n    def rotate(self, angle, points=None):\n        \"\"\"Rotate boxes with points (optional) with the given angle or \\\n        rotation matrix.\n\n        Args:\n            angle (float | torch.Tensor | np.ndarray):\n                Rotation angle or rotation matrix.\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, optional):\n                Points to rotate. Defaults to None.\n\n        Returns:\n            tuple or None: When ``points`` is None, the function returns \\\n                None, otherwise it returns the rotated points and the \\\n                rotation matrix ``rot_mat_T``.\n        \"\"\"\n        if not isinstance(angle, torch.Tensor):\n            angle = self.tensor.new_tensor(angle)\n        assert angle.shape == torch.Size([3, 3]) or angle.numel() == 1, \\\n            f'invalid rotation angle shape {angle.shape}'\n\n        if angle.numel() == 1:\n            rot_sin = torch.sin(angle)\n            rot_cos = torch.cos(angle)\n            rot_mat_T = self.tensor.new_tensor([[rot_cos, -rot_sin, 0],\n                                                [rot_sin, rot_cos, 0],\n                                                [0, 0, 1]]).T\n        else:\n            rot_mat_T = angle.T\n            rot_sin = rot_mat_T[0, 1]\n            rot_cos = rot_mat_T[0, 0]\n            angle = np.arctan2(rot_sin, rot_cos)\n\n        self.tensor[:, 0:3] = self.tensor[:, 0:3] @ rot_mat_T\n        if self.with_yaw:\n            self.tensor[:, 6] -= angle\n        else:\n            corners_rot = self.corners @ rot_mat_T\n            new_x_size = corners_rot[..., 0].max(\n                dim=1, keepdim=True)[0] - corners_rot[..., 0].min(\n                    dim=1, keepdim=True)[0]\n            new_y_size = corners_rot[..., 1].max(\n                dim=1, keepdim=True)[0] - corners_rot[..., 1].min(\n                    dim=1, keepdim=True)[0]\n            self.tensor[:, 3:5] = torch.cat((new_x_size, new_y_size), dim=-1)\n\n        if points is not None:\n            if isinstance(points, torch.Tensor):\n                points[:, :3] = points[:, :3] @ rot_mat_T\n            elif isinstance(points, np.ndarray):\n                rot_mat_T = rot_mat_T.numpy()\n                points[:, :3] = np.dot(points[:, :3], rot_mat_T)\n            elif isinstance(points, BasePoints):\n                # anti-clockwise\n                points.rotate(angle)\n            else:\n                raise ValueError\n            return points, rot_mat_T\n\n    def flip(self, bev_direction='horizontal', points=None):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\n\n        In Depth coordinates, it flips x (horizontal) or y (vertical) axis.\n\n        Args:\n            bev_direction (str): Flip direction (horizontal or vertical).\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, None):\n                Points to flip. Defaults to None.\n\n        Returns:\n            torch.Tensor, numpy.ndarray or None: Flipped points.\n        \"\"\"\n        assert bev_direction in ('horizontal', 'vertical')\n        if bev_direction == 'horizontal':\n            self.tensor[:, 0::7] = -self.tensor[:, 0::7]\n            if self.with_yaw:\n                self.tensor[:, 6] = -self.tensor[:, 6] + np.pi\n        elif bev_direction == 'vertical':\n            self.tensor[:, 1::7] = -self.tensor[:, 1::7]\n            if self.with_yaw:\n                self.tensor[:, 6] = -self.tensor[:, 6]\n\n        if points is not None:\n            assert isinstance(points, (torch.Tensor, np.ndarray, BasePoints))\n            if isinstance(points, (torch.Tensor, np.ndarray)):\n                if bev_direction == 'horizontal':\n                    points[:, 0] = -points[:, 0]\n                elif bev_direction == 'vertical':\n                    points[:, 1] = -points[:, 1]\n            elif isinstance(points, BasePoints):\n                points.flip(bev_direction)\n            return points\n\n    def in_range_bev(self, box_range):\n        \"\"\"Check whether the boxes are in the given range.\n\n        Args:\n            box_range (list | torch.Tensor): The range of box\n                (x_min, y_min, x_max, y_max).\n\n        Note:\n            In the original implementation of SECOND, checking whether\n            a box in the range checks whether the points are in a convex\n            polygon, we try to reduce the burdun for simpler cases.\n\n        Returns:\n            torch.Tensor: Indicating whether each box is inside \\\n                the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > box_range[0])\n                          & (self.tensor[:, 1] > box_range[1])\n                          & (self.tensor[:, 0] < box_range[2])\n                          & (self.tensor[:, 1] < box_range[3]))\n        return in_range_flags\n\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`Box3DMode`): The target Box mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from ``src`` coordinates to ``dst`` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`DepthInstance3DBoxes`: \\\n                The converted box of the same type in the ``dst`` mode.\n        \"\"\"\n        from .box_3d_mode import Box3DMode\n        return Box3DMode.convert(\n            box=self, src=Box3DMode.DEPTH, dst=dst, rt_mat=rt_mat)\n\n    def points_in_boxes(self, points):\n        \"\"\"Find points that are in boxes (CUDA).\n\n        Args:\n            points (torch.Tensor): Points in shape [1, M, 3] or [M, 3], \\\n                3 dimensions are [x, y, z] in LiDAR coordinate.\n\n        Returns:\n            torch.Tensor: The index of boxes each point lies in with shape \\\n                of (B, M, T).\n        \"\"\"\n        from .box_3d_mode import Box3DMode\n\n        # to lidar\n        points_lidar = points.clone()\n        points_lidar = points_lidar[..., [1, 0, 2]]\n        points_lidar[..., 1] *= -1\n        if points.dim() == 2:\n            points_lidar = points_lidar.unsqueeze(0)\n        else:\n            assert points.dim() == 3 and points_lidar.shape[0] == 1\n\n        boxes_lidar = self.convert_to(Box3DMode.LIDAR).tensor\n        boxes_lidar = boxes_lidar.to(points.device).unsqueeze(0)\n        box_idxs_of_pts = points_in_boxes_batch(points_lidar, boxes_lidar)\n\n        return box_idxs_of_pts.squeeze(0)\n\n    def enlarged_box(self, extra_width):\n        \"\"\"Enlarge the length, width and height boxes.\n\n        Args:\n            extra_width (float | torch.Tensor): Extra width to enlarge the box.\n\n        Returns:\n            :obj:`LiDARInstance3DBoxes`: Enlarged boxes.\n        \"\"\"\n        enlarged_boxes = self.tensor.clone()\n        enlarged_boxes[:, 3:6] += extra_width * 2\n        # bottom center z minus extra_width\n        enlarged_boxes[:, 2] -= extra_width\n        return self.new_box(enlarged_boxes)\n\n    def get_surface_line_center(self):\n        \"\"\"Compute surface and line center of bounding boxes.\n\n        Returns:\n            torch.Tensor: Surface and line center of bounding boxes.\n        \"\"\"\n        obj_size = self.dims\n        center = self.gravity_center.view(-1, 1, 3)\n        batch_size = center.shape[0]\n\n        rot_sin = torch.sin(-self.yaw)\n        rot_cos = torch.cos(-self.yaw)\n        rot_mat_T = self.yaw.new_zeros(tuple(list(self.yaw.shape) + [3, 3]))\n        rot_mat_T[..., 0, 0] = rot_cos\n        rot_mat_T[..., 0, 1] = -rot_sin\n        rot_mat_T[..., 1, 0] = rot_sin\n        rot_mat_T[..., 1, 1] = rot_cos\n        rot_mat_T[..., 2, 2] = 1\n\n        # Get the object surface center\n        offset = obj_size.new_tensor([[0, 0, 1], [0, 0, -1], [0, 1, 0],\n                                      [0, -1, 0], [1, 0, 0], [-1, 0, 0]])\n        offset = offset.view(1, 6, 3) / 2\n        surface_3d = (offset *\n                      obj_size.view(batch_size, 1, 3).repeat(1, 6, 1)).reshape(\n                          -1, 3)\n\n        # Get the object line center\n        offset = obj_size.new_tensor([[1, 0, 1], [-1, 0, 1], [0, 1, 1],\n                                      [0, -1, 1], [1, 0, -1], [-1, 0, -1],\n                                      [0, 1, -1], [0, -1, -1], [1, 1, 0],\n                                      [1, -1, 0], [-1, 1, 0], [-1, -1, 0]])\n        offset = offset.view(1, 12, 3) / 2\n\n        line_3d = (offset *\n                   obj_size.view(batch_size, 1, 3).repeat(1, 12, 1)).reshape(\n                       -1, 3)\n\n        surface_rot = rot_mat_T.repeat(6, 1, 1)\n        surface_3d = torch.matmul(\n            surface_3d.unsqueeze(-2), surface_rot.transpose(2, 1)).squeeze(-2)\n        surface_center = center.repeat(1, 6, 1).reshape(-1, 3) + surface_3d\n\n        line_rot = rot_mat_T.repeat(12, 1, 1)\n        line_3d = torch.matmul(\n            line_3d.unsqueeze(-2), line_rot.transpose(2, 1)).squeeze(-2)\n        line_center = center.repeat(1, 12, 1).reshape(-1, 3) + line_3d\n\n        return surface_center, line_center\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/lidar_box3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmcv.core.points import BasePoints\nfrom mmcv.ops.roiaware_pool3d import points_in_boxes_gpu\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .utils import limit_period, rotation_3d_in_axis\n\n\nclass LiDARInstance3DBoxes(BaseInstance3DBoxes):\n    \"\"\"3D boxes of instances in LIDAR coordinates.\n\n    Coordinates in LiDAR:\n\n    .. code-block:: none\n\n                            up z    x front (yaw=-0.5*pi)\n                               ^   ^\n                               |  /\n                               | /\n      (yaw=-pi) left y <------ 0 -------- (yaw=0)\n\n    The relative coordinate of bottom center in a LiDAR box is (0.5, 0.5, 0),\n    and the yaw is around the z axis, thus the rotation axis=2.\n    The yaw is 0 at the negative direction of y axis, and decreases from\n    the negative direction of y to the positive direction of x.\n\n    A refactor is ongoing to make the three coordinate systems\n    easier to understand and convert between each other.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x box_dim.\n        box_dim (int): Integer indicating the dimension of a box.\n            Each row is (x, y, z, x_size, y_size, z_size, yaw, ...).\n        with_yaw (bool): If True, the value of yaw will be set to 0 as minmax\n            boxes.\n    \"\"\"\n\n    @property\n    def gravity_center(self):\n        \"\"\"torch.Tensor: A tensor with center of each box.\"\"\"\n        bottom_center = self.bottom_center\n        gravity_center = torch.zeros_like(bottom_center)\n        gravity_center[:, :2] = bottom_center[:, :2]\n        gravity_center[:, 2] = bottom_center[:, 2] + self.tensor[:, 5] * 0.5\n        return gravity_center\n\n    @property\n    def corners(self):\n        \"\"\"torch.Tensor: Coordinates of corners of all the boxes\n        in shape (N, 8, 3).\n\n        Convert the boxes to corners in clockwise order, in form of\n        ``(x0y0z0, x0y0z1, x0y1z1, x0y1z0, x1y0z0, x1y0z1, x1y1z1, x1y1z0)``\n\n        .. code-block:: none\n\n                                           up z\n                            front x           ^\n                                 /            |\n                                /             |\n                  (x1, y0, z1) + -----------  + (x1, y1, z1)\n                              /|            / |\n                             / |           /  |\n               (x0, y0, z1) + ----------- +   + (x1, y1, z0)\n                            |  /      .   |  /\n                            | / origin    | /\n            left y<-------- + ----------- + (x0, y1, z0)\n                (x0, y0, z0)\n        \"\"\"\n        # TODO: rotation_3d_in_axis function do not support\n        #  empty tensor currently.\n        assert len(self.tensor) != 0\n        dims = self.dims\n        corners_norm = torch.from_numpy(\n            np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)).to(\n                device=dims.device, dtype=dims.dtype)\n\n        corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n        # use relative origin [0.5, 0.5, 0]\n        corners_norm = corners_norm - dims.new_tensor([0.5, 0.5, 0])\n        corners = dims.view([-1, 1, 3]) * corners_norm.reshape([1, 8, 3])\n\n        # rotate around z axis\n        corners = rotation_3d_in_axis(corners, self.tensor[:, 6], axis=2)\n        corners += self.tensor[:, :3].view(-1, 1, 3)\n        return corners\n\n    @property\n    def bev(self):\n        \"\"\"torch.Tensor: 2D BEV box of each box with rotation\n        in XYWHR format.\"\"\"\n        return self.tensor[:, [0, 1, 3, 4, 6]]\n\n    @property\n    def nearest_bev(self):\n        \"\"\"torch.Tensor: A tensor of 2D BEV box of each box\n        without rotation.\"\"\"\n        # Obtain BEV boxes with rotation in XYWHR format\n        bev_rotated_boxes = self.bev\n        # convert the rotation to a valid range\n        rotations = bev_rotated_boxes[:, -1]\n        normed_rotations = torch.abs(limit_period(rotations, 0.5, np.pi))\n\n        # find the center of boxes\n        conditions = (normed_rotations > np.pi / 4)[..., None]\n        bboxes_xywh = torch.where(conditions, bev_rotated_boxes[:,\n                                                                [0, 1, 3, 2]],\n                                  bev_rotated_boxes[:, :4])\n\n        centers = bboxes_xywh[:, :2]\n        dims = bboxes_xywh[:, 2:]\n        bev_boxes = torch.cat([centers - dims / 2, centers + dims / 2], dim=-1)\n        return bev_boxes\n\n    def rotate(self, angle, points=None):\n        \"\"\"Rotate boxes with points (optional) with the given angle or \\\n        rotation matrix.\n\n        Args:\n            angles (float | torch.Tensor | np.ndarray):\n                Rotation angle or rotation matrix.\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, optional):\n                Points to rotate. Defaults to None.\n\n        Returns:\n            tuple or None: When ``points`` is None, the function returns \\\n                None, otherwise it returns the rotated points and the \\\n                rotation matrix ``rot_mat_T``.\n        \"\"\"\n        if not isinstance(angle, torch.Tensor):\n            angle = self.tensor.new_tensor(angle)\n        assert angle.shape == torch.Size([3, 3]) or angle.numel() == 1, \\\n            f'invalid rotation angle shape {angle.shape}'\n\n        if angle.numel() == 1:\n            rot_sin = torch.sin(angle)\n            rot_cos = torch.cos(angle)\n            rot_mat_T = self.tensor.new_tensor([[rot_cos, -rot_sin, 0],\n                                                [rot_sin, rot_cos, 0],\n                                                [0, 0, 1]])\n        else:\n            rot_mat_T = angle\n            rot_sin = rot_mat_T[1, 0]\n            rot_cos = rot_mat_T[0, 0]\n            angle = np.arctan2(rot_sin, rot_cos)\n\n        self.tensor[:, :3] = self.tensor[:, :3] @ rot_mat_T\n        self.tensor[:, 6] += angle\n\n        if self.tensor.shape[1] == 9:\n            # rotate velo vector\n            self.tensor[:, 7:9] = self.tensor[:, 7:9] @ rot_mat_T[:2, :2]\n\n        if points is not None:\n            if isinstance(points, torch.Tensor):\n                points[:, :3] = points[:, :3] @ rot_mat_T\n            elif isinstance(points, np.ndarray):\n                rot_mat_T = rot_mat_T.numpy()\n                points[:, :3] = np.dot(points[:, :3], rot_mat_T)\n            elif isinstance(points, BasePoints):\n                # clockwise\n                points.rotate(-angle)\n            else:\n                raise ValueError\n            return points, rot_mat_T\n\n    def flip(self, bev_direction='horizontal', points=None):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\n\n        In LIDAR coordinates, it flips the y (horizontal) or x (vertical) axis.\n\n        Args:\n            bev_direction (str): Flip direction (horizontal or vertical).\n            points (torch.Tensor, numpy.ndarray, :obj:`BasePoints`, None):\n                Points to flip. Defaults to None.\n\n        Returns:\n            torch.Tensor, numpy.ndarray or None: Flipped points.\n        \"\"\"\n        assert bev_direction in ('horizontal', 'vertical')\n        if bev_direction == 'horizontal':\n            self.tensor[:, 1::7] = -self.tensor[:, 1::7]\n            if self.with_yaw:\n                self.tensor[:, 6] = -self.tensor[:, 6] + np.pi\n        elif bev_direction == 'vertical':\n            self.tensor[:, 0::7] = -self.tensor[:, 0::7]\n            if self.with_yaw:\n                self.tensor[:, 6] = -self.tensor[:, 6]\n\n        if points is not None:\n            assert isinstance(points, (torch.Tensor, np.ndarray, BasePoints))\n            if isinstance(points, (torch.Tensor, np.ndarray)):\n                if bev_direction == 'horizontal':\n                    points[:, 1] = -points[:, 1]\n                elif bev_direction == 'vertical':\n                    points[:, 0] = -points[:, 0]\n            elif isinstance(points, BasePoints):\n                points.flip(bev_direction)\n            return points\n\n    def in_range_bev(self, box_range):\n        \"\"\"Check whether the boxes are in the given range.\n\n        Args:\n            box_range (list | torch.Tensor): the range of box\n                (x_min, y_min, x_max, y_max)\n\n        Note:\n            The original implementation of SECOND checks whether boxes in\n            a range by checking whether the points are in a convex\n            polygon, we reduce the burden for simpler cases.\n\n        Returns:\n            torch.Tensor: Whether each box is inside the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > box_range[0])\n                          & (self.tensor[:, 1] > box_range[1])\n                          & (self.tensor[:, 0] < box_range[2])\n                          & (self.tensor[:, 1] < box_range[3]))\n        return in_range_flags\n\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`Box3DMode`): the target Box mode\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from ``src`` coordinates to ``dst`` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BaseInstance3DBoxes`: \\\n                The converted box of the same type in the ``dst`` mode.\n        \"\"\"\n        from .box_3d_mode import Box3DMode\n        return Box3DMode.convert(\n            box=self, src=Box3DMode.LIDAR, dst=dst, rt_mat=rt_mat)\n\n    def enlarged_box(self, extra_width):\n        \"\"\"Enlarge the length, width and height boxes.\n\n        Args:\n            extra_width (float | torch.Tensor): Extra width to enlarge the box.\n\n        Returns:\n            :obj:`LiDARInstance3DBoxes`: Enlarged boxes.\n        \"\"\"\n        enlarged_boxes = self.tensor.clone()\n        enlarged_boxes[:, 3:6] += extra_width * 2\n        # bottom center z minus extra_width\n        enlarged_boxes[:, 2] -= extra_width\n        return self.new_box(enlarged_boxes)\n\n    def points_in_boxes(self, points):\n        \"\"\"Find the box which the points are in.\n\n        Args:\n            points (torch.Tensor): Points in shape (N, 3).\n\n        Returns:\n            torch.Tensor: The index of box where each point are in.\n        \"\"\"\n        box_idx = points_in_boxes_gpu(\n            points.unsqueeze(0),\n            self.tensor.unsqueeze(0).to(points.device)).squeeze(0)\n        return box_idx\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/nuscenes_box.py",
    "content": "# nuScenes dev-kit.\n# Code written by Oscar Beijbom, 2018.\n\nimport copy\nfrom typing import Tuple, List\n\nimport cv2\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom matplotlib.axes import Axes\nfrom matplotlib.collections import LineCollection\nfrom pyquaternion import Quaternion\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.eval.common.data_classes import EvalBox\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES, ATTRIBUTE_NAMES\n\n\ndef color_map(data, cmap):\n    \"\"\"数值映射为颜色\"\"\"\n    \n    dmin, dmax = np.nanmin(data), np.nanmax(data)\n    cmo = plt.cm.get_cmap(cmap)\n    cs, k = list(), 256/cmo.N\n    \n    for i in range(cmo.N):\n        c = cmo(i)\n        for j in range(int(i*k), int((i+1)*k)):\n            cs.append(c)\n    cs = np.array(cs)\n    data = np.uint8(255*(data-dmin)/(dmax-dmin))\n    \n    return cs[data]\n\nclass CustomNuscenesBox:\n    \"\"\" Simple data class representing a 3d box including, label, score and velocity. \"\"\"\n\n    def __init__(self,\n                 center: List[float],\n                 size: List[float],\n                 orientation: Quaternion,\n                 fut_trajs: List[float],\n                 label: int = np.nan,\n                 score: float = np.nan,\n                 velocity: Tuple = (np.nan, np.nan, np.nan),\n                 name: str = None,\n                 token: str = None):\n        \"\"\"\n        :param center: Center of box given as x, y, z.\n        :param size: Size of box in width, length, height.\n        :param orientation: Box orientation.\n        :param label: Integer label, optional.\n        :param score: Classification score, optional.\n        :param velocity: Box velocity in x, y, z direction.\n        :param name: Box name, optional. Can be used e.g. for denote category name.\n        :param token: Unique string identifier from DB.\n        \"\"\"\n        assert not np.any(np.isnan(center))\n        assert not np.any(np.isnan(size))\n        assert len(center) == 3\n        assert len(size) == 3\n        assert type(orientation) == Quaternion\n\n        self.center = np.array(center)\n        self.wlh = np.array(size)\n        self.orientation = orientation\n        self.label = int(label) if not np.isnan(label) else label\n        self.score = float(score) if not np.isnan(score) else score\n        self.velocity = np.array(velocity)\n        self.name = name\n        self.token = token\n        self.fut_trajs = np.array(fut_trajs)\n\n    def __eq__(self, other):\n        center = np.allclose(self.center, other.center)\n        wlh = np.allclose(self.wlh, other.wlh)\n        orientation = np.allclose(self.orientation.elements, other.orientation.elements)\n        label = (self.label == other.label) or (np.isnan(self.label) and np.isnan(other.label))\n        score = (self.score == other.score) or (np.isnan(self.score) and np.isnan(other.score))\n        vel = (np.allclose(self.velocity, other.velocity) or\n               (np.all(np.isnan(self.velocity)) and np.all(np.isnan(other.velocity))))\n\n        return center and wlh and orientation and label and score and vel\n\n    def __repr__(self):\n        repr_str = 'label: {}, score: {:.2f}, xyz: [{:.2f}, {:.2f}, {:.2f}], wlh: [{:.2f}, {:.2f}, {:.2f}], ' \\\n                   'rot axis: [{:.2f}, {:.2f}, {:.2f}], ang(degrees): {:.2f}, ang(rad): {:.2f}, ' \\\n                   'vel: {:.2f}, {:.2f}, {:.2f}, name: {}, token: {}'\n\n        return repr_str.format(self.label, self.score, self.center[0], self.center[1], self.center[2], self.wlh[0],\n                               self.wlh[1], self.wlh[2], self.orientation.axis[0], self.orientation.axis[1],\n                               self.orientation.axis[2], self.orientation.degrees, self.orientation.radians,\n                               self.velocity[0], self.velocity[1], self.velocity[2], self.name, self.token)\n\n    @property\n    def rotation_matrix(self) -> np.ndarray:\n        \"\"\"\n        Return a rotation matrix.\n        :return: <np.float: 3, 3>. The box's rotation matrix.\n        \"\"\"\n        return self.orientation.rotation_matrix\n\n    def translate(self, x: np.ndarray) -> None:\n        \"\"\"\n        Applies a translation.\n        :param x: <np.float: 3, 1>. Translation in x, y, z direction.\n        \"\"\"\n        self.center += x\n\n    def rotate(self, quaternion: Quaternion) -> None:\n        \"\"\"\n        Rotates box.\n        :param quaternion: Rotation to apply.\n        \"\"\"\n        self.center = np.dot(quaternion.rotation_matrix, self.center)\n        self.orientation = quaternion * self.orientation\n        self.velocity = np.dot(quaternion.rotation_matrix, self.velocity)\n\n    def corners(self, wlh_factor: float = 1.0) -> np.ndarray:\n        \"\"\"\n        Returns the bounding box corners.\n        :param wlh_factor: Multiply w, l, h by a factor to scale the box.\n        :return: <np.float: 3, 8>. First four corners are the ones facing forward.\n            The last four are the ones facing backwards.\n        \"\"\"\n        w, l, h = self.wlh * wlh_factor\n\n        # 3D bounding box corners. (Convention: x points forward, y to the left, z up.)\n        x_corners = l / 2 * np.array([1,  1,  1,  1, -1, -1, -1, -1])\n        y_corners = w / 2 * np.array([1, -1, -1,  1,  1, -1, -1,  1])\n        z_corners = h / 2 * np.array([1,  1, -1, -1,  1,  1, -1, -1])\n        corners = np.vstack((x_corners, y_corners, z_corners))\n\n        # Rotate\n        corners = np.dot(self.orientation.rotation_matrix, corners)\n\n        # Translate\n        x, y, z = self.center\n        corners[0, :] = corners[0, :] + x\n        corners[1, :] = corners[1, :] + y\n        corners[2, :] = corners[2, :] + z\n\n        return corners\n\n    def bottom_corners(self) -> np.ndarray:\n        \"\"\"\n        Returns the four bottom corners.\n        :return: <np.float: 3, 4>. Bottom corners. First two face forward, last two face backwards.\n        \"\"\"\n        return self.corners()[:, [2, 3, 7, 6]]\n\n    def render(self,\n               axis: Axes,\n               view: np.ndarray = np.eye(3),\n               normalize: bool = False,\n               colors: Tuple = ('b', 'r', 'k'),\n               linewidth: float = 2,\n               box_idx=None,\n               alpha=0.5) -> None:\n        \"\"\"\n        Renders the box in the provided Matplotlib axis.\n        :param axis: Axis onto which the box should be drawn.\n        :param view: <np.array: 3, 3>. Define a projection in needed (e.g. for drawing projection in an image).\n        :param normalize: Whether to normalize the remaining coordinate.\n        :param colors: (<Matplotlib.colors>: 3). Valid Matplotlib colors (<str> or normalized RGB tuple) for front,\n            back and sides.\n        :param linewidth: Width in pixel of the box sides.\n        \"\"\"\n        corners = view_points(self.corners(), view, normalize=normalize)[:2, :]\n\n        def draw_rect(selected_corners, color, alpha):\n            prev = selected_corners[-1]\n            for corner in selected_corners:\n                axis.plot([prev[0], corner[0]], [prev[1], corner[1]], color=color, linewidth=linewidth, alpha=alpha)\n                prev = corner\n\n        # Draw the sides\n        for i in range(4):\n            axis.plot([corners.T[i][0], corners.T[i + 4][0]],\n                      [corners.T[i][1], corners.T[i + 4][1]],\n                      color=colors[2], linewidth=linewidth, alpha=alpha)\n\n        # Draw front (first 4 corners) and rear (last 4 corners) rectangles(3d)/lines(2d)\n        draw_rect(corners.T[:4], colors[0], alpha)\n        draw_rect(corners.T[4:], colors[1], alpha)\n\n        # Draw line indicating the front\n        center_bottom_forward = np.mean(corners.T[2:4], axis=0)\n        center_bottom = np.mean(corners.T[[2, 3, 7, 6]], axis=0)\n        axis.plot([center_bottom[0], center_bottom_forward[0]],\n                  [center_bottom[1], center_bottom_forward[1]],\n                  color=colors[0], linewidth=linewidth, alpha=alpha)\n        if box_idx is not None and center_bottom[0] > -35 and center_bottom[1] > -35 \\\n            and center_bottom[0] < 35 and center_bottom[1] < 35:\n            text = f'{box_idx}'\n            axis.text(center_bottom[0], center_bottom[1], text, ha='left', fontsize=5)\n    \n    def render_fut_trajs(self,\n               axis: Axes,\n               color: str = 'b',\n               linewidth: float = 1,\n               fut_ts: int = 6,\n               mode_idx=None) -> None:\n        \"\"\"\n        Renders the box in the provided Matplotlib axis.\n        :param axis: Axis onto which the box should be drawn.\n        :param view: <np.array: 3, 3>. Define a projection in needed (e.g. for drawing projection in an image).\n        :param normalize: Whether to normalize the remaining coordinate.\n        :param colors: (<Matplotlib.colors>: 3). Valid Matplotlib colors (<str> or normalized RGB tuple) for front,\n            back and sides.\n        :param linewidth: Width in pixel of the box sides.\n        \"\"\"\n\n        fut_coords = self.fut_trajs.reshape((-1, fut_ts, 2))\n        if mode_idx is not None:\n            fut_coords = fut_coords[[mode_idx]]\n        alpha = 0.8\n        for i in range(fut_coords.shape[0]):\n            fut_coord = fut_coords[i]\n            fut_coord = fut_coord.cumsum(axis=-2)\n            fut_coord = fut_coord + self.center[:2]\n            if np.abs(fut_coord[-1] - self.center[:2]).max() >= 10:\n                if color == 'g':\n                    axis.scatter(fut_coord[-1, 0], fut_coord[-1, 1], c=color, marker='*', s=70, alpha=alpha)\n                elif color == 'b':\n                    axis.scatter(fut_coord[-1, 0], fut_coord[-1, 1], c=color, marker='o', s=20, alpha=alpha)\n                if mode_idx is None and fut_coord[-1, 0] > -35 and fut_coord[-1, 1] > -35 \\\n                    and fut_coord[-1, 0] < 35 and fut_coord[-1, 1] < 35:\n                    text = f'{i}'\n                    axis.text(fut_coord[-1, 0], fut_coord[-1, 1], text, ha='left', fontsize=5)\n            axis.plot(\n                [self.center[0], fut_coord[0, 0]],\n                [self.center[1], fut_coord[0, 1]],\n                color=color, linewidth=linewidth, alpha=alpha\n            )\n            for i in range(fut_coord.shape[0]-1):\n                axis.plot(\n                    [fut_coord[i, 0], fut_coord[i+1, 0]],\n                    [fut_coord[i, 1], fut_coord[i+1, 1]],\n                    color=color, linewidth=linewidth, alpha=alpha\n                )\n\n    def render_fut_trajs_grad_color(self,\n               axis: Axes,\n               linewidth: float = 1,\n               linestyles='solid',\n               cmap='viridis',\n               fut_ts: int = 6,\n               alpha: int = 0.8,\n               mode_idx=None) -> None:\n        \"\"\"\n        Renders the box in the provided Matplotlib axis.\n        :param axis: Axis onto which the box should be drawn.\n        :param view: <np.array: 3, 3>. Define a projection in needed (e.g. for drawing projection in an image).\n        :param normalize: Whether to normalize the remaining coordinate.\n        :param colors: (<Matplotlib.colors>: 3). Valid Matplotlib colors (<str> or normalized RGB tuple) for front,\n            back and sides.\n        :param linewidth: Width in pixel of the box sides.\n        \"\"\"\n\n        fut_coords = self.fut_trajs.reshape((-1, fut_ts, 2))\n        if mode_idx is not None:\n            fut_coords = fut_coords[[mode_idx]]\n\n        for i in range(fut_coords.shape[0]):\n            fut_coord = fut_coords[i]\n            fut_coord = fut_coord.cumsum(axis=-2)\n            fut_coord = fut_coord + self.center[:2]\n            fut_coord = np.concatenate((self.center[np.newaxis, :2], fut_coord), axis=0)\n            fut_coord_segments = np.stack((fut_coord[:-1], fut_coord[1:]), axis=1)\n\n            fut_vecs = None\n            for j in range(fut_coord_segments.shape[0]):\n                fut_vec_j = fut_coord_segments[j]\n                x_linspace = np.linspace(fut_vec_j[0, 0], fut_vec_j[1, 0], 51)\n                y_linspace = np.linspace(fut_vec_j[0, 1], fut_vec_j[1, 1], 51)\n                xy = np.stack((x_linspace, y_linspace), axis=1)\n                xy = np.stack((xy[:-1], xy[1:]), axis=1)\n                if fut_vecs is None:\n                    fut_vecs = xy\n                else:\n                    fut_vecs = np.concatenate((fut_vecs, xy), axis=0)\n\n            y = np.sin(np.linspace(3/2*np.pi, 5/2*np.pi, 301))\n            colors = color_map(y[:-1], cmap)\n            line_segments = LineCollection(fut_vecs, colors=colors, linewidths=linewidth, linestyles=linestyles, cmap=cmap)\n\n            # if mode_idx is None and abs(fut_coord[-1, 0]) < 35 and abs(fut_coord[-1, 1]) < 35:\n            #     text = f'{i}'\n            #     axis.text(fut_coord[-1, 0], fut_coord[-1, 1], text, ha='left', fontsize=5)\n\n            axis.add_collection(line_segments)\n\n    def render_fut_trajs_coords(self,\n               axis: Axes,\n               color: str = 'b',\n               linewidth: float = 1,\n               fut_ts: int = 12) -> None:\n        \"\"\"\n        Renders the box in the provided Matplotlib axis.\n        :param axis: Axis onto which the box should be drawn.\n        :param view: <np.array: 3, 3>. Define a projection in needed (e.g. for drawing projection in an image).\n        :param normalize: Whether to normalize the remaining coordinate.\n        :param colors: (<Matplotlib.colors>: 3). Valid Matplotlib colors (<str> or normalized RGB tuple) for front,\n            back and sides.\n        :param linewidth: Width in pixel of the box sides.\n        \"\"\"\n\n        fut_coords = self.fut_trajs.reshape((-1, fut_ts, 2))\n        alpha = 0.2 if color == 'b' else 1\n        for i in range(fut_coords.shape[0]):\n            fut_coord = fut_coords[i]\n            fut_coord = fut_coord + self.center[:2]\n            if np.abs(fut_coord[-1] - self.center[:2]).max() >= 10:\n                if color == 'g':\n                    axis.scatter(fut_coord[-1, 0], fut_coord[-1, 1], c=color, marker='*', s=70, alpha=alpha)\n                elif color == 'b':\n                    axis.scatter(fut_coord[-1, 0], fut_coord[-1, 1], c=color, marker='o', s=20, alpha=alpha)\n            axis.plot(\n                [self.center[0], fut_coord[0, 0]],\n                [self.center[1], fut_coord[0, 1]],\n                color=color, linewidth=linewidth, alpha=alpha\n            )\n            for i in range(fut_coord.shape[0]-1):\n                axis.plot(\n                    [fut_coord[i, 0], fut_coord[i+1, 0]],\n                    [fut_coord[i, 1], fut_coord[i+1, 1]],\n                    color=color, linewidth=linewidth, alpha=alpha\n                )\n\n    def render_cv2(self,\n                   im: np.ndarray,\n                   view: np.ndarray = np.eye(3),\n                   normalize: bool = False,\n                   colors: Tuple = ((0, 0, 255), (255, 0, 0), (155, 155, 155)),\n                   linewidth: int = 2) -> None:\n        \"\"\"\n        Renders box using OpenCV2.\n        :param im: <np.array: width, height, 3>. Image array. Channels are in BGR order.\n        :param view: <np.array: 3, 3>. Define a projection if needed (e.g. for drawing projection in an image).\n        :param normalize: Whether to normalize the remaining coordinate.\n        :param colors: ((R, G, B), (R, G, B), (R, G, B)). Colors for front, side & rear.\n        :param linewidth: Linewidth for plot.\n        \"\"\"\n        corners = view_points(self.corners(), view, normalize=normalize)[:2, :]\n\n        def draw_rect(selected_corners, color):\n            prev = selected_corners[-1]\n            for corner in selected_corners:\n                cv2.line(im,\n                         (int(prev[0]), int(prev[1])),\n                         (int(corner[0]), int(corner[1])),\n                         color, linewidth)\n                prev = corner\n\n        # Draw the sides\n        for i in range(4):\n            cv2.line(im,\n                     (int(corners.T[i][0]), int(corners.T[i][1])),\n                     (int(corners.T[i + 4][0]), int(corners.T[i + 4][1])),\n                     colors[2][::-1], linewidth)\n\n        # Draw front (first 4 corners) and rear (last 4 corners) rectangles(3d)/lines(2d)\n        draw_rect(corners.T[:4], colors[0][::-1])\n        draw_rect(corners.T[4:], colors[1][::-1])\n\n        # Draw line indicating the front\n        center_bottom_forward = np.mean(corners.T[2:4], axis=0)\n        center_bottom = np.mean(corners.T[[2, 3, 7, 6]], axis=0)\n        cv2.line(im,\n                 (int(center_bottom[0]), int(center_bottom[1])),\n                 (int(center_bottom_forward[0]), int(center_bottom_forward[1])),\n                 colors[0][::-1], linewidth)\n\n    def copy(self) -> 'CustomNuscenesBox':\n        \"\"\"\n        Create a copy of self.\n        :return: A copy.\n        \"\"\"\n        return copy.deepcopy(self)\n\n\nclass CustomDetectionBox(EvalBox):\n    \"\"\" Data class used during detection evaluation. Can be a prediction or ground truth.\"\"\"\n\n    def __init__(self,\n                 sample_token: str = \"\",\n                 translation: Tuple[float, float, float] = (0, 0, 0),\n                 size: Tuple[float, float, float] = (0, 0, 0),\n                 rotation: Tuple[float, float, float, float] = (0, 0, 0, 0),\n                 velocity: Tuple[float, float] = (0, 0),\n                 ego_translation: Tuple[float, float, float] = (0, 0, 0),  # Translation to ego vehicle in meters.\n                 num_pts: int = -1,  # Nbr. LIDAR or RADAR inside the box. Only for gt boxes.\n                 detection_name: str = 'car',  # The class name used in the detection challenge.\n                 detection_score: float = -1.0,  # GT samples do not have a score.\n                 attribute_name: str = '',  # Box attribute. Each box can have at most 1 attribute.\n                 fut_trajs=None):  # future trajectories of a pred box, shape=[fut_ts*2].\n\n        super().__init__(sample_token, translation, size, rotation, velocity, ego_translation, num_pts)\n\n        assert detection_name is not None, 'Error: detection_name cannot be empty!'\n        assert detection_name in DETECTION_NAMES, 'Error: Unknown detection_name %s' % detection_name\n\n        assert attribute_name in ATTRIBUTE_NAMES or attribute_name == '', \\\n            'Error: Unknown attribute_name %s' % attribute_name\n\n        assert type(detection_score) == float, 'Error: detection_score must be a float!'\n        assert not np.any(np.isnan(detection_score)), 'Error: detection_score may not be NaN!'\n\n        # Assign.\n        self.detection_name = detection_name\n        self.detection_score = detection_score\n        self.attribute_name = attribute_name\n        self.fut_trajs = fut_trajs\n\n    def __eq__(self, other):\n        return (self.sample_token == other.sample_token and\n                self.translation == other.translation and\n                self.size == other.size and\n                self.rotation == other.rotation and\n                self.velocity == other.velocity and\n                self.ego_translation == other.ego_translation and\n                self.num_pts == other.num_pts and\n                self.detection_name == other.detection_name and\n                self.detection_score == other.detection_score and\n                self.attribute_name == other.attribute_name and\n                self.fut_trajs == other.fut_trajs)\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'fut_trajs': self.fut_trajs\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(sample_token=content['sample_token'],\n                   translation=tuple(content['translation']),\n                   size=tuple(content['size']),\n                   rotation=tuple(content['rotation']),\n                   velocity=tuple(content['velocity']),\n                   fut_trajs=tuple(content['fut_trajs']),\n                   ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                   else tuple(content['ego_translation']),\n                   num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                   detection_name=content['detection_name'],\n                   detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                   attribute_name=content['attribute_name'])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/structures/utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom logging import warning\n\n\ndef limit_period(val, offset=0.5, period=np.pi):\n    \"\"\"Limit the value into a period for periodic function.\n\n    Args:\n        val (torch.Tensor): The value to be converted.\n        offset (float, optional): Offset to set the value range. \\\n            Defaults to 0.5.\n        period ([type], optional): Period of the value. Defaults to np.pi.\n\n    Returns:\n        torch.Tensor: Value in the range of \\\n            [-offset * period, (1-offset) * period]\n    \"\"\"\n    return val - torch.floor(val / period + offset) * period\n\n\ndef rotation_3d_in_axis(points, angles, axis=0):\n    \"\"\"Rotate points by angles according to axis.\n\n    Args:\n        points (torch.Tensor): Points of shape (N, M, 3).\n        angles (torch.Tensor): Vector of angles in shape (N,)\n        axis (int, optional): The axis to be rotated. Defaults to 0.\n\n    Raises:\n        ValueError: when the axis is not in range [0, 1, 2], it will \\\n            raise value error.\n\n    Returns:\n        torch.Tensor: Rotated points in shape (N, M, 3)\n    \"\"\"\n    rot_sin = torch.sin(angles)\n    rot_cos = torch.cos(angles)\n    ones = torch.ones_like(rot_cos)\n    zeros = torch.zeros_like(rot_cos)\n    if axis == 1:\n        rot_mat_T = torch.stack([\n            torch.stack([rot_cos, zeros, -rot_sin]),\n            torch.stack([zeros, ones, zeros]),\n            torch.stack([rot_sin, zeros, rot_cos])\n        ])\n    elif axis == 2 or axis == -1:\n        rot_mat_T = torch.stack([\n            torch.stack([rot_cos, -rot_sin, zeros]),\n            torch.stack([rot_sin, rot_cos, zeros]),\n            torch.stack([zeros, zeros, ones])\n        ])\n    elif axis == 0:\n        rot_mat_T = torch.stack([\n            torch.stack([zeros, rot_cos, -rot_sin]),\n            torch.stack([zeros, rot_sin, rot_cos]),\n            torch.stack([ones, zeros, zeros])\n        ])\n    else:\n        raise ValueError(f'axis should in range [0, 1, 2], got {axis}')\n\n    return torch.einsum('aij,jka->aik', (points, rot_mat_T))\n\n\ndef xywhr2xyxyr(boxes_xywhr):\n    \"\"\"Convert a rotated boxes in XYWHR format to XYXYR format.\n\n    Args:\n        boxes_xywhr (torch.Tensor): Rotated boxes in XYWHR format.\n\n    Returns:\n        torch.Tensor: Converted boxes in XYXYR format.\n    \"\"\"\n    boxes = torch.zeros_like(boxes_xywhr)\n    half_w = boxes_xywhr[:, 2] / 2\n    half_h = boxes_xywhr[:, 3] / 2\n\n    boxes[:, 0] = boxes_xywhr[:, 0] - half_w\n    boxes[:, 1] = boxes_xywhr[:, 1] - half_h\n    boxes[:, 2] = boxes_xywhr[:, 0] + half_w\n    boxes[:, 3] = boxes_xywhr[:, 1] + half_h\n    boxes[:, 4] = boxes_xywhr[:, 4]\n    return boxes\n\n\ndef get_box_type(box_type):\n    \"\"\"Get the type and mode of box structure.\n\n    Args:\n        box_type (str): The type of box structure.\n            The valid value are \"LiDAR\", \"Camera\", or \"Depth\".\n\n    Returns:\n        tuple: Box type and box mode.\n    \"\"\"\n    from .box_3d_mode import (Box3DMode, CameraInstance3DBoxes,\n                              DepthInstance3DBoxes, LiDARInstance3DBoxes)\n    box_type_lower = box_type.lower()\n    if box_type_lower == 'lidar':\n        box_type_3d = LiDARInstance3DBoxes\n        box_mode_3d = Box3DMode.LIDAR\n    elif box_type_lower == 'camera':\n        box_type_3d = CameraInstance3DBoxes\n        box_mode_3d = Box3DMode.CAM\n    elif box_type_lower == 'depth':\n        box_type_3d = DepthInstance3DBoxes\n        box_mode_3d = Box3DMode.DEPTH\n    else:\n        raise ValueError('Only \"box_type\" of \"camera\", \"lidar\", \"depth\"'\n                         f' are supported, got {box_type}')\n\n    return box_type_3d, box_mode_3d\n\n\ndef points_cam2img(points_3d, proj_mat, with_depth=False):\n    \"\"\"Project points from camera coordicates to image coordinates.\n\n    Args:\n        points_3d (torch.Tensor): Points in shape (N, 3).\n        proj_mat (torch.Tensor): Transformation matrix between coordinates.\n        with_depth (bool, optional): Whether to keep depth in the output.\n            Defaults to False.\n\n    Returns:\n        torch.Tensor: Points in image coordinates with shape [N, 2].\n    \"\"\"\n    points_num = list(points_3d.shape)[:-1]\n\n    points_shape = np.concatenate([points_num, [1]], axis=0).tolist()\n    assert len(proj_mat.shape) == 2, 'The dimension of the projection'\\\n        f' matrix should be 2 instead of {len(proj_mat.shape)}.'\n    d1, d2 = proj_mat.shape[:2]\n    assert (d1 == 3 and d2 == 3) or (d1 == 3 and d2 == 4) or (\n        d1 == 4 and d2 == 4), 'The shape of the projection matrix'\\\n        f' ({d1}*{d2}) is not supported.'\n    if d1 == 3:\n        proj_mat_expanded = torch.eye(\n            4, device=proj_mat.device, dtype=proj_mat.dtype)\n        proj_mat_expanded[:d1, :d2] = proj_mat\n        proj_mat = proj_mat_expanded\n\n    # previous implementation use new_zeros, new_one yeilds better results\n    points_4 = torch.cat(\n        [points_3d, points_3d.new_ones(*points_shape)], dim=-1)\n    point_2d = torch.matmul(points_4, proj_mat.t())\n    point_2d_res = point_2d[..., :2] / point_2d[..., 2:3]\n\n    if with_depth:\n        return torch.cat([point_2d_res, point_2d[..., 2:3]], dim=-1)\n    return point_2d_res\n\n\ndef mono_cam_box2vis(cam_box):\n    \"\"\"This is a post-processing function on the bboxes from Mono-3D task. If\n    we want to perform projection visualization, we need to:\n\n        1. rotate the box along x-axis for np.pi / 2 (roll)\n        2. change orientation from local yaw to global yaw\n        3. convert yaw by (np.pi / 2 - yaw)\n\n    After applying this function, we can project and draw it on 2D images.\n\n    Args:\n        cam_box (:obj:`CameraInstance3DBoxes`): 3D bbox in camera coordinate \\\n            system before conversion. Could be gt bbox loaded from dataset or \\\n                network prediction output.\n\n    Returns:\n        :obj:`CameraInstance3DBoxes`: Box after conversion.\n    \"\"\"\n    warning.warn('DeprecationWarning: The hack of yaw and dimension in the '\n                 'monocular 3D detection on nuScenes has been removed. The '\n                 'function mono_cam_box2vis will be deprecated.')\n    from . import CameraInstance3DBoxes\n    assert isinstance(cam_box, CameraInstance3DBoxes), \\\n        'input bbox should be CameraInstance3DBoxes!'\n\n    loc = cam_box.gravity_center\n    dim = cam_box.dims\n    yaw = cam_box.yaw\n    feats = cam_box.tensor[:, 7:]\n    # rotate along x-axis for np.pi / 2\n    # see also here: https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/datasets/nuscenes_mono_dataset.py#L557  # noqa\n    dim[:, [1, 2]] = dim[:, [2, 1]]\n    # change local yaw to global yaw for visualization\n    # refer to https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/datasets/nuscenes_mono_dataset.py#L164-L166  # noqa\n    yaw += torch.atan2(loc[:, 0], loc[:, 2])\n    # convert yaw by (-yaw - np.pi / 2)\n    # this is because mono 3D box class such as `NuScenesBox` has different\n    # definition of rotation with our `CameraInstance3DBoxes`\n    yaw = -yaw - np.pi / 2\n    cam_box = torch.cat([loc, dim, yaw[:, None], feats], dim=1)\n    cam_box = CameraInstance3DBoxes(\n        cam_box, box_dim=cam_box.shape[-1], origin=(0.5, 0.5, 0.5))\n\n    return cam_box\n\n\ndef get_proj_mat_by_coord_type(img_meta, coord_type):\n    \"\"\"Obtain image features using points.\n\n    Args:\n        img_meta (dict): Meta info.\n        coord_type (str): 'DEPTH' or 'CAMERA' or 'LIDAR'.\n            Can be case-insensitive.\n\n    Returns:\n        torch.Tensor: transformation matrix.\n    \"\"\"\n    coord_type = coord_type.upper()\n    mapping = {'LIDAR': 'lidar2img', 'DEPTH': 'depth2img', 'CAMERA': 'cam2img'}\n    assert coord_type in mapping.keys()\n    return img_meta[mapping[coord_type]]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/transforms.py",
    "content": "import numpy as np\nimport torch\n\n\ndef bbox_flip(bboxes, img_shape, direction='horizontal'):\n    \"\"\"Flip bboxes horizontally or vertically.\n\n    Args:\n        bboxes (Tensor): Shape (..., 4*k)\n        img_shape (tuple): Image shape.\n        direction (str): Flip direction, options are \"horizontal\", \"vertical\",\n            \"diagonal\". Default: \"horizontal\"\n\n    Returns:\n        Tensor: Flipped bboxes.\n    \"\"\"\n    assert bboxes.shape[-1] % 4 == 0\n    assert direction in ['horizontal', 'vertical', 'diagonal']\n    flipped = bboxes.clone()\n    if direction == 'horizontal':\n        flipped[..., 0::4] = img_shape[1] - bboxes[..., 2::4]\n        flipped[..., 2::4] = img_shape[1] - bboxes[..., 0::4]\n    elif direction == 'vertical':\n        flipped[..., 1::4] = img_shape[0] - bboxes[..., 3::4]\n        flipped[..., 3::4] = img_shape[0] - bboxes[..., 1::4]\n    else:\n        flipped[..., 0::4] = img_shape[1] - bboxes[..., 2::4]\n        flipped[..., 1::4] = img_shape[0] - bboxes[..., 3::4]\n        flipped[..., 2::4] = img_shape[1] - bboxes[..., 0::4]\n        flipped[..., 3::4] = img_shape[0] - bboxes[..., 1::4]\n    return flipped\n\n\ndef bbox_mapping(bboxes,\n                 img_shape,\n                 scale_factor,\n                 flip,\n                 flip_direction='horizontal'):\n    \"\"\"Map bboxes from the original image scale to testing scale.\"\"\"\n    new_bboxes = bboxes * bboxes.new_tensor(scale_factor)\n    if flip:\n        new_bboxes = bbox_flip(new_bboxes, img_shape, flip_direction)\n    return new_bboxes\n\n\ndef bbox_mapping_back(bboxes,\n                      img_shape,\n                      scale_factor,\n                      flip,\n                      flip_direction='horizontal'):\n    \"\"\"Map bboxes from testing scale to original image scale.\"\"\"\n    new_bboxes = bbox_flip(bboxes, img_shape,\n                           flip_direction) if flip else bboxes\n    new_bboxes = new_bboxes.view(-1, 4) / new_bboxes.new_tensor(scale_factor)\n    return new_bboxes.view(bboxes.shape)\n\n\ndef bbox2roi(bbox_list):\n    \"\"\"Convert a list of bboxes to roi format.\n\n    Args:\n        bbox_list (list[Tensor]): a list of bboxes corresponding to a batch\n            of images.\n\n    Returns:\n        Tensor: shape (n, 5), [batch_ind, x1, y1, x2, y2]\n    \"\"\"\n    rois_list = []\n    for img_id, bboxes in enumerate(bbox_list):\n        if bboxes.size(0) > 0:\n            img_inds = bboxes.new_full((bboxes.size(0), 1), img_id)\n            rois = torch.cat([img_inds, bboxes[:, :4]], dim=-1)\n        else:\n            rois = bboxes.new_zeros((0, 5))\n        rois_list.append(rois)\n    rois = torch.cat(rois_list, 0)\n    return rois\n\n\ndef roi2bbox(rois):\n    \"\"\"Convert rois to bounding box format.\n\n    Args:\n        rois (torch.Tensor): RoIs with the shape (n, 5) where the first\n            column indicates batch id of each RoI.\n\n    Returns:\n        list[torch.Tensor]: Converted boxes of corresponding rois.\n    \"\"\"\n    bbox_list = []\n    img_ids = torch.unique(rois[:, 0].cpu(), sorted=True)\n    for img_id in img_ids:\n        inds = (rois[:, 0] == img_id.item())\n        bbox = rois[inds, 1:]\n        bbox_list.append(bbox)\n    return bbox_list\n\n\ndef bbox2result(bboxes, labels, num_classes):\n    \"\"\"Convert detection results to a list of numpy arrays.\n\n    Args:\n        bboxes (torch.Tensor | np.ndarray): shape (n, 5)\n        labels (torch.Tensor | np.ndarray): shape (n, )\n        num_classes (int): class number, including background class\n\n    Returns:\n        list(ndarray): bbox results of each class\n    \"\"\"\n    if bboxes.shape[0] == 0:\n        return [np.zeros((0, 5), dtype=np.float32) for i in range(num_classes)]\n    else:\n        if isinstance(bboxes, torch.Tensor):\n            bboxes = bboxes.detach().cpu().numpy()\n            labels = labels.detach().cpu().numpy()\n        return [bboxes[labels == i, :] for i in range(num_classes)]\n\n\ndef distance2bbox(points, distance, max_shape=None):\n    \"\"\"Decode distance prediction to bounding box.\n\n    Args:\n        points (Tensor): Shape (B, N, 2) or (N, 2).\n        distance (Tensor): Distance from the given point to 4\n            boundaries (left, top, right, bottom). Shape (B, N, 4) or (N, 4)\n        max_shape (Sequence[int] or torch.Tensor or Sequence[\n            Sequence[int]],optional): Maximum bounds for boxes, specifies\n            (H, W, C) or (H, W). If priors shape is (B, N, 4), then\n            the max_shape should be a Sequence[Sequence[int]]\n            and the length of max_shape should also be B.\n\n    Returns:\n        Tensor: Boxes with shape (N, 4) or (B, N, 4)\n    \"\"\"\n    x1 = points[..., 0] - distance[..., 0]\n    y1 = points[..., 1] - distance[..., 1]\n    x2 = points[..., 0] + distance[..., 2]\n    y2 = points[..., 1] + distance[..., 3]\n\n    bboxes = torch.stack([x1, y1, x2, y2], -1)\n\n    if max_shape is not None:\n        # clip bboxes with dynamic `min` and `max` for onnx\n        if torch.onnx.is_in_onnx_export():\n            from mmcv.core.export import dynamic_clip_for_onnx\n            x1, y1, x2, y2 = dynamic_clip_for_onnx(x1, y1, x2, y2, max_shape)\n            bboxes = torch.stack([x1, y1, x2, y2], dim=-1)\n            return bboxes\n        if not isinstance(max_shape, torch.Tensor):\n            max_shape = x1.new_tensor(max_shape)\n        max_shape = max_shape[..., :2].type_as(x1)\n        if max_shape.ndim == 2:\n            assert bboxes.ndim == 3\n            assert max_shape.size(0) == bboxes.size(0)\n\n        min_xy = x1.new_tensor(0)\n        max_xy = torch.cat([max_shape, max_shape],\n                           dim=-1).flip(-1).unsqueeze(-2)\n        bboxes = torch.where(bboxes < min_xy, min_xy, bboxes)\n        bboxes = torch.where(bboxes > max_xy, max_xy, bboxes)\n\n    return bboxes\n\n\ndef bbox2distance(points, bbox, max_dis=None, eps=0.1):\n    \"\"\"Decode bounding box based on distances.\n\n    Args:\n        points (Tensor): Shape (n, 2), [x, y].\n        bbox (Tensor): Shape (n, 4), \"xyxy\" format\n        max_dis (float): Upper bound of the distance.\n        eps (float): a small value to ensure target < max_dis, instead <=\n\n    Returns:\n        Tensor: Decoded distances.\n    \"\"\"\n    left = points[:, 0] - bbox[:, 0]\n    top = points[:, 1] - bbox[:, 1]\n    right = bbox[:, 2] - points[:, 0]\n    bottom = bbox[:, 3] - points[:, 1]\n    if max_dis is not None:\n        left = left.clamp(min=0, max=max_dis - eps)\n        top = top.clamp(min=0, max=max_dis - eps)\n        right = right.clamp(min=0, max=max_dis - eps)\n        bottom = bottom.clamp(min=0, max=max_dis - eps)\n    return torch.stack([left, top, right, bottom], -1)\n\n\ndef bbox_rescale(bboxes, scale_factor=1.0):\n    \"\"\"Rescale bounding box w.r.t. scale_factor.\n\n    Args:\n        bboxes (Tensor): Shape (n, 4) for bboxes or (n, 5) for rois\n        scale_factor (float): rescale factor\n\n    Returns:\n        Tensor: Rescaled bboxes.\n    \"\"\"\n    if bboxes.size(1) == 5:\n        bboxes_ = bboxes[:, 1:]\n        inds_ = bboxes[:, 0]\n    else:\n        bboxes_ = bboxes\n    cx = (bboxes_[:, 0] + bboxes_[:, 2]) * 0.5\n    cy = (bboxes_[:, 1] + bboxes_[:, 3]) * 0.5\n    w = bboxes_[:, 2] - bboxes_[:, 0]\n    h = bboxes_[:, 3] - bboxes_[:, 1]\n    w = w * scale_factor\n    h = h * scale_factor\n    x1 = cx - 0.5 * w\n    x2 = cx + 0.5 * w\n    y1 = cy - 0.5 * h\n    y2 = cy + 0.5 * h\n    if bboxes.size(1) == 5:\n        rescaled_bboxes = torch.stack([inds_, x1, y1, x2, y2], dim=-1)\n    else:\n        rescaled_bboxes = torch.stack([x1, y1, x2, y2], dim=-1)\n    return rescaled_bboxes\n\n\ndef bbox_cxcywh_to_xyxy(bbox):\n    \"\"\"Convert bbox coordinates from (cx, cy, w, h) to (x1, y1, x2, y2).\n\n    Args:\n        bbox (Tensor): Shape (n, 4) for bboxes.\n\n    Returns:\n        Tensor: Converted bboxes.\n    \"\"\"\n    cx, cy, w, h = bbox.split((1, 1, 1, 1), dim=-1)\n    bbox_new = [(cx - 0.5 * w), (cy - 0.5 * h), (cx + 0.5 * w), (cy + 0.5 * h)]\n    return torch.cat(bbox_new, dim=-1)\n\n\ndef bbox_xyxy_to_cxcywh(bbox):\n    \"\"\"Convert bbox coordinates from (x1, y1, x2, y2) to (cx, cy, w, h).\n\n    Args:\n        bbox (Tensor): Shape (n, 4) for bboxes.\n\n    Returns:\n        Tensor: Converted bboxes.\n    \"\"\"\n    x1, y1, x2, y2 = bbox.split((1, 1, 1, 1), dim=-1)\n    bbox_new = [(x1 + x2) / 2, (y1 + y2) / 2, (x2 - x1), (y2 - y1)]\n    return torch.cat(bbox_new, dim=-1)\n\ndef bbox3d_mapping_back(bboxes, scale_factor, flip_horizontal, flip_vertical):\n    \"\"\"Map bboxes from testing scale to original image scale.\n\n    Args:\n        bboxes (:obj:`BaseInstance3DBoxes`): Boxes to be mapped back.\n        scale_factor (float): Scale factor.\n        flip_horizontal (bool): Whether to flip horizontally.\n        flip_vertical (bool): Whether to flip vertically.\n\n    Returns:\n        :obj:`BaseInstance3DBoxes`: Boxes mapped back.\n    \"\"\"\n    new_bboxes = bboxes.clone()\n    if flip_horizontal:\n        new_bboxes.flip('horizontal')\n    if flip_vertical:\n        new_bboxes.flip('vertical')\n    new_bboxes.scale(1 / scale_factor)\n\n    return new_bboxes\n\n\ndef bbox3d2roi(bbox_list):\n    \"\"\"Convert a list of bounding boxes to roi format.\n\n    Args:\n        bbox_list (list[torch.Tensor]): A list of bounding boxes\n            corresponding to a batch of images.\n\n    Returns:\n        torch.Tensor: Region of interests in shape (n, c), where \\\n            the channels are in order of [batch_ind, x, y ...].\n    \"\"\"\n    rois_list = []\n    for img_id, bboxes in enumerate(bbox_list):\n        if bboxes.size(0) > 0:\n            img_inds = bboxes.new_full((bboxes.size(0), 1), img_id)\n            rois = torch.cat([img_inds, bboxes], dim=-1)\n        else:\n            rois = torch.zeros_like(bboxes)\n        rois_list.append(rois)\n    rois = torch.cat(rois_list, 0)\n    return rois\n\n\ndef bbox3d2result(bboxes, scores, labels, attrs=None):\n    \"\"\"Convert detection results to a list of numpy arrays.\n\n    Args:\n        bboxes (torch.Tensor): Bounding boxes with shape of (n, 5).\n        labels (torch.Tensor): Labels with shape of (n, ).\n        scores (torch.Tensor): Scores with shape of (n, ).\n        attrs (torch.Tensor, optional): Attributes with shape of (n, ). \\\n            Defaults to None.\n\n    Returns:\n        dict[str, torch.Tensor]: Bounding box results in cpu mode.\n\n            - boxes_3d (torch.Tensor): 3D boxes.\n            - scores (torch.Tensor): Prediction scores.\n            - labels_3d (torch.Tensor): Box labels.\n            - attrs_3d (torch.Tensor, optional): Box attributes.\n    \"\"\"\n    result_dict = dict(\n        boxes_3d=bboxes.to('cpu'),\n        scores_3d=scores.cpu(),\n        labels_3d=labels.cpu())\n\n    if attrs is not None:\n        result_dict['attrs_3d'] = attrs.cpu()\n\n    return result_dict\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/bbox/util.py",
    "content": "import torch \n\n\ndef normalize_bbox(bboxes, pc_range):\n\n    cx = bboxes[..., 0:1]\n    cy = bboxes[..., 1:2]\n    cz = bboxes[..., 2:3]\n    w = bboxes[..., 3:4].log()\n    l = bboxes[..., 4:5].log()\n    h = bboxes[..., 5:6].log()\n\n    rot = bboxes[..., 6:7]\n    if bboxes.size(-1) > 7:\n        vx = bboxes[..., 7:8] \n        vy = bboxes[..., 8:9]\n        normalized_bboxes = torch.cat(\n            (cx, cy, w, l, cz, h, rot.sin(), rot.cos(), vx, vy), dim=-1\n        )\n    else:\n        normalized_bboxes = torch.cat(\n            (cx, cy, w, l, cz, h, rot.sin(), rot.cos()), dim=-1\n        )\n    return normalized_bboxes\n\ndef denormalize_bbox(normalized_bboxes, pc_range):\n    # rotation \n    rot_sine = normalized_bboxes[..., 6:7]\n\n    rot_cosine = normalized_bboxes[..., 7:8]\n    rot = torch.atan2(rot_sine, rot_cosine)\n\n    # center in the bev\n    cx = normalized_bboxes[..., 0:1]\n    cy = normalized_bboxes[..., 1:2]\n    cz = normalized_bboxes[..., 4:5]\n   \n    # size\n    w = normalized_bboxes[..., 2:3]\n    l = normalized_bboxes[..., 3:4]\n    h = normalized_bboxes[..., 5:6]\n\n    w = w.exp() \n    l = l.exp() \n    h = h.exp() \n    if normalized_bboxes.size(-1) > 8:\n         # velocity \n        vx = normalized_bboxes[:, 8:9]\n        vy = normalized_bboxes[:, 9:10]\n        denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot, vx, vy], dim=-1)\n    else:\n        denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot], dim=-1)\n    return denormalized_bboxes"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/__init__.py",
    "content": "from .indoor_eval import indoor_eval\nfrom .kitti_utils import kitti_eval, kitti_eval_coco_style\nfrom .lyft_eval import lyft_eval\nfrom .seg_eval import seg_eval\nfrom .class_names import (cityscapes_classes, coco_classes, dataset_aliases,\n                          get_classes, get_palette, imagenet_det_classes,\n                          imagenet_vid_classes, voc_classes)\nfrom .eval_hooks import DistEvalHook, EvalHook, CustomDistEvalHook\nfrom .mean_ap import average_precision, eval_map, print_map_summary\nfrom .recall import (eval_recalls, plot_iou_recall, plot_num_recall,\n                     print_recall_summary)\nfrom .metrics import eval_metrics, mean_dice, mean_fscore, mean_iou\nfrom .metric_motion import get_ade,get_best_preds,get_fde"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/bbox_overlaps.py",
    "content": "import numpy as np\n\n\ndef bbox_overlaps(bboxes1, bboxes2, mode='iou', eps=1e-6):\n    \"\"\"Calculate the ious between each bbox of bboxes1 and bboxes2.\n\n    Args:\n        bboxes1(ndarray): shape (n, 4)\n        bboxes2(ndarray): shape (k, 4)\n        mode(str): iou (intersection over union) or iof (intersection\n            over foreground)\n\n    Returns:\n        ious(ndarray): shape (n, k)\n    \"\"\"\n\n    assert mode in ['iou', 'iof']\n\n    bboxes1 = bboxes1.astype(np.float32)\n    bboxes2 = bboxes2.astype(np.float32)\n    rows = bboxes1.shape[0]\n    cols = bboxes2.shape[0]\n    ious = np.zeros((rows, cols), dtype=np.float32)\n    if rows * cols == 0:\n        return ious\n    exchange = False\n    if bboxes1.shape[0] > bboxes2.shape[0]:\n        bboxes1, bboxes2 = bboxes2, bboxes1\n        ious = np.zeros((cols, rows), dtype=np.float32)\n        exchange = True\n    area1 = (bboxes1[:, 2] - bboxes1[:, 0]) * (bboxes1[:, 3] - bboxes1[:, 1])\n    area2 = (bboxes2[:, 2] - bboxes2[:, 0]) * (bboxes2[:, 3] - bboxes2[:, 1])\n    for i in range(bboxes1.shape[0]):\n        x_start = np.maximum(bboxes1[i, 0], bboxes2[:, 0])\n        y_start = np.maximum(bboxes1[i, 1], bboxes2[:, 1])\n        x_end = np.minimum(bboxes1[i, 2], bboxes2[:, 2])\n        y_end = np.minimum(bboxes1[i, 3], bboxes2[:, 3])\n        overlap = np.maximum(x_end - x_start, 0) * np.maximum(\n            y_end - y_start, 0)\n        if mode == 'iou':\n            union = area1[i] + area2 - overlap\n        else:\n            union = area1[i] if not exchange else area2\n        union = np.maximum(union, eps)\n        ious[i, :] = overlap / union\n    if exchange:\n        ious = ious.T\n    return ious\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/class_names.py",
    "content": "from mmcv.utils import is_str\n\ndef ade_classes():\n    \"\"\"ADE20K class names for external use.\"\"\"\n    return [\n        'wall', 'building', 'sky', 'floor', 'tree', 'ceiling', 'road', 'bed ',\n        'windowpane', 'grass', 'cabinet', 'sidewalk', 'person', 'earth',\n        'door', 'table', 'mountain', 'plant', 'curtain', 'chair', 'car',\n        'water', 'painting', 'sofa', 'shelf', 'house', 'sea', 'mirror', 'rug',\n        'field', 'armchair', 'seat', 'fence', 'desk', 'rock', 'wardrobe',\n        'lamp', 'bathtub', 'railing', 'cushion', 'base', 'box', 'column',\n        'signboard', 'chest of drawers', 'counter', 'sand', 'sink',\n        'skyscraper', 'fireplace', 'refrigerator', 'grandstand', 'path',\n        'stairs', 'runway', 'case', 'pool table', 'pillow', 'screen door',\n        'stairway', 'river', 'bridge', 'bookcase', 'blind', 'coffee table',\n        'toilet', 'flower', 'book', 'hill', 'bench', 'countertop', 'stove',\n        'palm', 'kitchen island', 'computer', 'swivel chair', 'boat', 'bar',\n        'arcade machine', 'hovel', 'bus', 'towel', 'light', 'truck', 'tower',\n        'chandelier', 'awning', 'streetlight', 'booth', 'television receiver',\n        'airplane', 'dirt track', 'apparel', 'pole', 'land', 'bannister',\n        'escalator', 'ottoman', 'bottle', 'buffet', 'poster', 'stage', 'van',\n        'ship', 'fountain', 'conveyer belt', 'canopy', 'washer', 'plaything',\n        'swimming pool', 'stool', 'barrel', 'basket', 'waterfall', 'tent',\n        'bag', 'minibike', 'cradle', 'oven', 'ball', 'food', 'step', 'tank',\n        'trade name', 'microwave', 'pot', 'animal', 'bicycle', 'lake',\n        'dishwasher', 'screen', 'blanket', 'sculpture', 'hood', 'sconce',\n        'vase', 'traffic light', 'tray', 'ashcan', 'fan', 'pier', 'crt screen',\n        'plate', 'monitor', 'bulletin board', 'shower', 'radiator', 'glass',\n        'clock', 'flag'\n    ]\n\ndef ade_palette():\n    \"\"\"ADE20K palette for external use.\"\"\"\n    return [[120, 120, 120], [180, 120, 120], [6, 230, 230], [80, 50, 50],\n            [4, 200, 3], [120, 120, 80], [140, 140, 140], [204, 5, 255],\n            [230, 230, 230], [4, 250, 7], [224, 5, 255], [235, 255, 7],\n            [150, 5, 61], [120, 120, 70], [8, 255, 51], [255, 6, 82],\n            [143, 255, 140], [204, 255, 4], [255, 51, 7], [204, 70, 3],\n            [0, 102, 200], [61, 230, 250], [255, 6, 51], [11, 102, 255],\n            [255, 7, 71], [255, 9, 224], [9, 7, 230], [220, 220, 220],\n            [255, 9, 92], [112, 9, 255], [8, 255, 214], [7, 255, 224],\n            [255, 184, 6], [10, 255, 71], [255, 41, 10], [7, 255, 255],\n            [224, 255, 8], [102, 8, 255], [255, 61, 6], [255, 194, 7],\n            [255, 122, 8], [0, 255, 20], [255, 8, 41], [255, 5, 153],\n            [6, 51, 255], [235, 12, 255], [160, 150, 20], [0, 163, 255],\n            [140, 140, 140], [250, 10, 15], [20, 255, 0], [31, 255, 0],\n            [255, 31, 0], [255, 224, 0], [153, 255, 0], [0, 0, 255],\n            [255, 71, 0], [0, 235, 255], [0, 173, 255], [31, 0, 255],\n            [11, 200, 200], [255, 82, 0], [0, 255, 245], [0, 61, 255],\n            [0, 255, 112], [0, 255, 133], [255, 0, 0], [255, 163, 0],\n            [255, 102, 0], [194, 255, 0], [0, 143, 255], [51, 255, 0],\n            [0, 82, 255], [0, 255, 41], [0, 255, 173], [10, 0, 255],\n            [173, 255, 0], [0, 255, 153], [255, 92, 0], [255, 0, 255],\n            [255, 0, 245], [255, 0, 102], [255, 173, 0], [255, 0, 20],\n            [255, 184, 184], [0, 31, 255], [0, 255, 61], [0, 71, 255],\n            [255, 0, 204], [0, 255, 194], [0, 255, 82], [0, 10, 255],\n            [0, 112, 255], [51, 0, 255], [0, 194, 255], [0, 122, 255],\n            [0, 255, 163], [255, 153, 0], [0, 255, 10], [255, 112, 0],\n            [143, 255, 0], [82, 0, 255], [163, 255, 0], [255, 235, 0],\n            [8, 184, 170], [133, 0, 255], [0, 255, 92], [184, 0, 255],\n            [255, 0, 31], [0, 184, 255], [0, 214, 255], [255, 0, 112],\n            [92, 255, 0], [0, 224, 255], [112, 224, 255], [70, 184, 160],\n            [163, 0, 255], [153, 0, 255], [71, 255, 0], [255, 0, 163],\n            [255, 204, 0], [255, 0, 143], [0, 255, 235], [133, 255, 0],\n            [255, 0, 235], [245, 0, 255], [255, 0, 122], [255, 245, 0],\n            [10, 190, 212], [214, 255, 0], [0, 204, 255], [20, 0, 255],\n            [255, 255, 0], [0, 153, 255], [0, 41, 255], [0, 255, 204],\n            [41, 0, 255], [41, 255, 0], [173, 0, 255], [0, 245, 255],\n            [71, 0, 255], [122, 0, 255], [0, 255, 184], [0, 92, 255],\n            [184, 255, 0], [0, 133, 255], [255, 214, 0], [25, 194, 194],\n            [102, 255, 0], [92, 0, 255]]\n\ndef wider_face_classes():\n    return ['face']\n\n\ndef voc_classes():\n    return [\n        'aeroplane', 'bicycle', 'bird', 'boat', 'bottle', 'bus', 'car', 'cat',\n        'chair', 'cow', 'diningtable', 'dog', 'horse', 'motorbike', 'person',\n        'pottedplant', 'sheep', 'sofa', 'train', 'tvmonitor'\n    ]\n    \ndef voc_palette():\n    \"\"\"Pascal VOC palette for external use.\"\"\"\n    return [[0, 0, 0], [128, 0, 0], [0, 128, 0], [128, 128, 0], [0, 0, 128],\n            [128, 0, 128], [0, 128, 128], [128, 128, 128], [64, 0, 0],\n            [192, 0, 0], [64, 128, 0], [192, 128, 0], [64, 0, 128],\n            [192, 0, 128], [64, 128, 128], [192, 128, 128], [0, 64, 0],\n            [128, 64, 0], [0, 192, 0], [128, 192, 0], [0, 64, 128]]\n\n\ndef imagenet_det_classes():\n    return [\n        'accordion', 'airplane', 'ant', 'antelope', 'apple', 'armadillo',\n        'artichoke', 'axe', 'baby_bed', 'backpack', 'bagel', 'balance_beam',\n        'banana', 'band_aid', 'banjo', 'baseball', 'basketball', 'bathing_cap',\n        'beaker', 'bear', 'bee', 'bell_pepper', 'bench', 'bicycle', 'binder',\n        'bird', 'bookshelf', 'bow_tie', 'bow', 'bowl', 'brassiere', 'burrito',\n        'bus', 'butterfly', 'camel', 'can_opener', 'car', 'cart', 'cattle',\n        'cello', 'centipede', 'chain_saw', 'chair', 'chime', 'cocktail_shaker',\n        'coffee_maker', 'computer_keyboard', 'computer_mouse', 'corkscrew',\n        'cream', 'croquet_ball', 'crutch', 'cucumber', 'cup_or_mug', 'diaper',\n        'digital_clock', 'dishwasher', 'dog', 'domestic_cat', 'dragonfly',\n        'drum', 'dumbbell', 'electric_fan', 'elephant', 'face_powder', 'fig',\n        'filing_cabinet', 'flower_pot', 'flute', 'fox', 'french_horn', 'frog',\n        'frying_pan', 'giant_panda', 'goldfish', 'golf_ball', 'golfcart',\n        'guacamole', 'guitar', 'hair_dryer', 'hair_spray', 'hamburger',\n        'hammer', 'hamster', 'harmonica', 'harp', 'hat_with_a_wide_brim',\n        'head_cabbage', 'helmet', 'hippopotamus', 'horizontal_bar', 'horse',\n        'hotdog', 'iPod', 'isopod', 'jellyfish', 'koala_bear', 'ladle',\n        'ladybug', 'lamp', 'laptop', 'lemon', 'lion', 'lipstick', 'lizard',\n        'lobster', 'maillot', 'maraca', 'microphone', 'microwave', 'milk_can',\n        'miniskirt', 'monkey', 'motorcycle', 'mushroom', 'nail', 'neck_brace',\n        'oboe', 'orange', 'otter', 'pencil_box', 'pencil_sharpener', 'perfume',\n        'person', 'piano', 'pineapple', 'ping-pong_ball', 'pitcher', 'pizza',\n        'plastic_bag', 'plate_rack', 'pomegranate', 'popsicle', 'porcupine',\n        'power_drill', 'pretzel', 'printer', 'puck', 'punching_bag', 'purse',\n        'rabbit', 'racket', 'ray', 'red_panda', 'refrigerator',\n        'remote_control', 'rubber_eraser', 'rugby_ball', 'ruler',\n        'salt_or_pepper_shaker', 'saxophone', 'scorpion', 'screwdriver',\n        'seal', 'sheep', 'ski', 'skunk', 'snail', 'snake', 'snowmobile',\n        'snowplow', 'soap_dispenser', 'soccer_ball', 'sofa', 'spatula',\n        'squirrel', 'starfish', 'stethoscope', 'stove', 'strainer',\n        'strawberry', 'stretcher', 'sunglasses', 'swimming_trunks', 'swine',\n        'syringe', 'table', 'tape_player', 'tennis_ball', 'tick', 'tie',\n        'tiger', 'toaster', 'traffic_light', 'train', 'trombone', 'trumpet',\n        'turtle', 'tv_or_monitor', 'unicycle', 'vacuum', 'violin',\n        'volleyball', 'waffle_iron', 'washer', 'water_bottle', 'watercraft',\n        'whale', 'wine_bottle', 'zebra'\n    ]\n\n\ndef imagenet_vid_classes():\n    return [\n        'airplane', 'antelope', 'bear', 'bicycle', 'bird', 'bus', 'car',\n        'cattle', 'dog', 'domestic_cat', 'elephant', 'fox', 'giant_panda',\n        'hamster', 'horse', 'lion', 'lizard', 'monkey', 'motorcycle', 'rabbit',\n        'red_panda', 'sheep', 'snake', 'squirrel', 'tiger', 'train', 'turtle',\n        'watercraft', 'whale', 'zebra'\n    ]\n\n\ndef coco_classes():\n    return [\n        'person', 'bicycle', 'car', 'motorcycle', 'airplane', 'bus', 'train',\n        'truck', 'boat', 'traffic_light', 'fire_hydrant', 'stop_sign',\n        'parking_meter', 'bench', 'bird', 'cat', 'dog', 'horse', 'sheep',\n        'cow', 'elephant', 'bear', 'zebra', 'giraffe', 'backpack', 'umbrella',\n        'handbag', 'tie', 'suitcase', 'frisbee', 'skis', 'snowboard',\n        'sports_ball', 'kite', 'baseball_bat', 'baseball_glove', 'skateboard',\n        'surfboard', 'tennis_racket', 'bottle', 'wine_glass', 'cup', 'fork',\n        'knife', 'spoon', 'bowl', 'banana', 'apple', 'sandwich', 'orange',\n        'broccoli', 'carrot', 'hot_dog', 'pizza', 'donut', 'cake', 'chair',\n        'couch', 'potted_plant', 'bed', 'dining_table', 'toilet', 'tv',\n        'laptop', 'mouse', 'remote', 'keyboard', 'cell_phone', 'microwave',\n        'oven', 'toaster', 'sink', 'refrigerator', 'book', 'clock', 'vase',\n        'scissors', 'teddy_bear', 'hair_drier', 'toothbrush'\n    ]\n\n\ndef cityscapes_classes():\n    return [\n        'person', 'rider', 'car', 'truck', 'bus', 'train', 'motorcycle',\n        'bicycle'\n    ]\n    \ndef cityscapes_palette():\n    \"\"\"Cityscapes palette for external use.\"\"\"\n    return [[128, 64, 128], [244, 35, 232], [70, 70, 70], [102, 102, 156],\n            [190, 153, 153], [153, 153, 153], [250, 170, 30], [220, 220, 0],\n            [107, 142, 35], [152, 251, 152], [70, 130, 180], [220, 20, 60],\n            [255, 0, 0], [0, 0, 142], [0, 0, 70], [0, 60, 100], [0, 80, 100],\n            [0, 0, 230], [119, 11, 32]]\n\n\ndataset_aliases = {\n    'voc': ['voc', 'pascal_voc', 'voc07', 'voc12'],\n    'imagenet_det': ['det', 'imagenet_det', 'ilsvrc_det'],\n    'imagenet_vid': ['vid', 'imagenet_vid', 'ilsvrc_vid'],\n    'coco': ['coco', 'mscoco', 'ms_coco'],\n    'wider_face': ['WIDERFaceDataset', 'wider_face', 'WIDERFace'],\n    'cityscapes': ['cityscapes'],\n    'ade': ['ade', 'ade20k']\n}\n\n\ndef get_classes(dataset):\n    \"\"\"Get class names of a dataset.\"\"\"\n    alias2name = {}\n    for name, aliases in dataset_aliases.items():\n        for alias in aliases:\n            alias2name[alias] = name\n\n    if is_str(dataset):\n        if dataset in alias2name:\n            labels = eval(alias2name[dataset] + '_classes()')\n        else:\n            raise ValueError(f'Unrecognized dataset: {dataset}')\n    else:\n        raise TypeError(f'dataset must a str, but got {type(dataset)}')\n    return labels\n\n\ndef get_palette(dataset):\n    \"\"\"Get class palette (RGB) of a dataset.\"\"\"\n    alias2name = {}\n    for name, aliases in dataset_aliases.items():\n        for alias in aliases:\n            alias2name[alias] = name\n\n    if is_str(dataset):\n        if dataset in alias2name:\n            labels = eval(alias2name[dataset] + '_palette()')\n        else:\n            raise ValueError(f'Unrecognized dataset: {dataset}')\n    else:\n        raise TypeError(f'dataset must a str, but got {type(dataset)}')\n    return labels\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/eval_hooks.py",
    "content": "import bisect\nimport os.path as osp\n\nimport torch.distributed as dist\nfrom mmcv.runner import DistEvalHook as BaseDistEvalHook\nfrom mmcv.runner import EvalHook as BaseEvalHook\nfrom mmcv.utils import is_list_of\nfrom torch.nn.modules.batchnorm import _BatchNorm\n\n\nclass EvalHook(BaseEvalHook):\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        if not self._should_evaluate(runner):\n            return\n\n        results = self.test_fn(runner.model, self.dataloader, show=False)\n        runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)\n        key_score = self.evaluate(runner, results)\n        if self.save_best:\n            self._save_ckpt(runner, key_score)\n\n\nclass DistEvalHook(BaseDistEvalHook):\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        # Synchronization of BatchNorm's buffer (running_mean\n        # and running_var) is not supported in the DDP of pytorch,\n        # which may cause the inconsistent performance of models in\n        # different ranks, so we broadcast BatchNorm's buffers\n        # of rank 0 to other ranks to avoid this.\n        if self.broadcast_bn_buffer:\n            model = runner.model\n            for name, module in model.named_modules():\n                if isinstance(module,\n                              _BatchNorm) and module.track_running_stats:\n                    dist.broadcast(module.running_var, 0)\n                    dist.broadcast(module.running_mean, 0)\n\n        if not self._should_evaluate(runner):\n            return\n\n        tmpdir = self.tmpdir\n        if tmpdir is None:\n            tmpdir = osp.join(runner.work_dir, '.eval_hook')\n\n        results = self.test_fn(\n            runner.model,\n            self.dataloader,\n            tmpdir=tmpdir,\n            gpu_collect=self.gpu_collect)\n        if runner.rank == 0:\n            print('\\n')\n            runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)\n            key_score = self.evaluate(runner, results)\n\n            if self.save_best:\n                self._save_ckpt(runner, key_score)\n                \ndef _calc_dynamic_intervals(start_interval, dynamic_interval_list):\n    assert is_list_of(dynamic_interval_list, tuple)\n\n    dynamic_milestones = [0]\n    dynamic_milestones.extend(\n        [dynamic_interval[0] for dynamic_interval in dynamic_interval_list])\n    dynamic_intervals = [start_interval]\n    dynamic_intervals.extend(\n        [dynamic_interval[1] for dynamic_interval in dynamic_interval_list])\n    return dynamic_milestones, dynamic_intervals\n\n\nclass CustomDistEvalHook(BaseDistEvalHook):\n\n    def __init__(self, *args, dynamic_intervals=None,  **kwargs):\n        super(CustomDistEvalHook, self).__init__(*args, **kwargs)\n        self.use_dynamic_intervals = dynamic_intervals is not None\n        if self.use_dynamic_intervals:\n            self.dynamic_milestones, self.dynamic_intervals = \\\n                _calc_dynamic_intervals(self.interval, dynamic_intervals)\n\n    def _decide_interval(self, runner):\n        if self.use_dynamic_intervals:\n            progress = runner.epoch if self.by_epoch else runner.iter\n            step = bisect.bisect(self.dynamic_milestones, (progress + 1))\n            # Dynamically modify the evaluation interval\n            self.interval = self.dynamic_intervals[step - 1]\n\n    def before_train_epoch(self, runner):\n        \"\"\"Evaluate the model only at the start of training by epoch.\"\"\"\n        self._decide_interval(runner)\n        super().before_train_epoch(runner)\n\n    def before_train_iter(self, runner):\n        self._decide_interval(runner)\n        super().before_train_iter(runner)\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        # Synchronization of BatchNorm's buffer (running_mean\n        # and running_var) is not supported in the DDP of pytorch,\n        # which may cause the inconsistent performance of models in\n        # different ranks, so we broadcast BatchNorm's buffers\n        # of rank 0 to other ranks to avoid this.\n        if self.broadcast_bn_buffer:\n            model = runner.model\n            for name, module in model.named_modules():\n                if isinstance(module,\n                              _BatchNorm) and module.track_running_stats:\n                    dist.broadcast(module.running_var, 0)\n                    dist.broadcast(module.running_mean, 0)\n\n        if not self._should_evaluate(runner):\n            return\n\n        tmpdir = self.tmpdir\n        if tmpdir is None:\n            tmpdir = osp.join(runner.work_dir, '.eval_hook')\n\n        results = self.test_fn(\n            runner.model,\n            self.dataloader,\n            tmpdir=tmpdir,\n            gpu_collect=self.gpu_collect)\n        if runner.rank == 0:\n            print('\\n')\n            runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)\n\n            key_score = self.evaluate(runner, results)\n\n            if self.save_best:\n                self._save_ckpt(runner, key_score)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/indoor_eval.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\n\n\ndef average_precision(recalls, precisions, mode='area'):\n    \"\"\"Calculate average precision (for single or multiple scales).\n\n    Args:\n        recalls (np.ndarray): Recalls with shape of (num_scales, num_dets) \\\n            or (num_dets, ).\n        precisions (np.ndarray): Precisions with shape of \\\n            (num_scales, num_dets) or (num_dets, ).\n        mode (str): 'area' or '11points', 'area' means calculating the area\n            under precision-recall curve, '11points' means calculating\n            the average precision of recalls at [0, 0.1, ..., 1]\n\n    Returns:\n        float or np.ndarray: Calculated average precision.\n    \"\"\"\n    if recalls.ndim == 1:\n        recalls = recalls[np.newaxis, :]\n        precisions = precisions[np.newaxis, :]\n\n    assert recalls.shape == precisions.shape\n    assert recalls.ndim == 2\n\n    num_scales = recalls.shape[0]\n    ap = np.zeros(num_scales, dtype=np.float32)\n    if mode == 'area':\n        zeros = np.zeros((num_scales, 1), dtype=recalls.dtype)\n        ones = np.ones((num_scales, 1), dtype=recalls.dtype)\n        mrec = np.hstack((zeros, recalls, ones))\n        mpre = np.hstack((zeros, precisions, zeros))\n        for i in range(mpre.shape[1] - 1, 0, -1):\n            mpre[:, i - 1] = np.maximum(mpre[:, i - 1], mpre[:, i])\n        for i in range(num_scales):\n            ind = np.where(mrec[i, 1:] != mrec[i, :-1])[0]\n            ap[i] = np.sum(\n                (mrec[i, ind + 1] - mrec[i, ind]) * mpre[i, ind + 1])\n    elif mode == '11points':\n        for i in range(num_scales):\n            for thr in np.arange(0, 1 + 1e-3, 0.1):\n                precs = precisions[i, recalls[i, :] >= thr]\n                prec = precs.max() if precs.size > 0 else 0\n                ap[i] += prec\n            ap /= 11\n    else:\n        raise ValueError(\n            'Unrecognized mode, only \"area\" and \"11points\" are supported')\n    return ap\n\n\ndef eval_det_cls(pred, gt, iou_thr=None):\n    \"\"\"Generic functions to compute precision/recall for object detection for a\n    single class.\n\n    Args:\n        pred (dict): Predictions mapping from image id to bounding boxes \\\n            and scores.\n        gt (dict): Ground truths mapping from image id to bounding boxes.\n        iou_thr (list[float]): A list of iou thresholds.\n\n    Return:\n        tuple (np.ndarray, np.ndarray, float): Recalls, precisions and \\\n            average precision.\n    \"\"\"\n\n    # {img_id: {'bbox': box structure, 'det': matched list}}\n    class_recs = {}\n    npos = 0\n    for img_id in gt.keys():\n        cur_gt_num = len(gt[img_id])\n        if cur_gt_num != 0:\n            gt_cur = torch.zeros([cur_gt_num, 7], dtype=torch.float32)\n            for i in range(cur_gt_num):\n                gt_cur[i] = gt[img_id][i].tensor\n            bbox = gt[img_id][0].new_box(gt_cur)\n        else:\n            bbox = gt[img_id]\n        det = [[False] * len(bbox) for i in iou_thr]\n        npos += len(bbox)\n        class_recs[img_id] = {'bbox': bbox, 'det': det}\n\n    # construct dets\n    image_ids = []\n    confidence = []\n    ious = []\n    for img_id in pred.keys():\n        cur_num = len(pred[img_id])\n        if cur_num == 0:\n            continue\n        pred_cur = torch.zeros((cur_num, 7), dtype=torch.float32)\n        box_idx = 0\n        for box, score in pred[img_id]:\n            image_ids.append(img_id)\n            confidence.append(score)\n            pred_cur[box_idx] = box.tensor\n            box_idx += 1\n        pred_cur = box.new_box(pred_cur)\n        gt_cur = class_recs[img_id]['bbox']\n        if len(gt_cur) > 0:\n            # calculate iou in each image\n            iou_cur = pred_cur.overlaps(pred_cur, gt_cur)\n            for i in range(cur_num):\n                ious.append(iou_cur[i])\n        else:\n            for i in range(cur_num):\n                ious.append(np.zeros(1))\n\n    confidence = np.array(confidence)\n\n    # sort by confidence\n    sorted_ind = np.argsort(-confidence)\n    image_ids = [image_ids[x] for x in sorted_ind]\n    ious = [ious[x] for x in sorted_ind]\n\n    # go down dets and mark TPs and FPs\n    nd = len(image_ids)\n    tp_thr = [np.zeros(nd) for i in iou_thr]\n    fp_thr = [np.zeros(nd) for i in iou_thr]\n    for d in range(nd):\n        R = class_recs[image_ids[d]]\n        iou_max = -np.inf\n        BBGT = R['bbox']\n        cur_iou = ious[d]\n\n        if len(BBGT) > 0:\n            # compute overlaps\n            for j in range(len(BBGT)):\n                # iou = get_iou_main(get_iou_func, (bb, BBGT[j,...]))\n                iou = cur_iou[j]\n                if iou > iou_max:\n                    iou_max = iou\n                    jmax = j\n\n        for iou_idx, thresh in enumerate(iou_thr):\n            if iou_max > thresh:\n                if not R['det'][iou_idx][jmax]:\n                    tp_thr[iou_idx][d] = 1.\n                    R['det'][iou_idx][jmax] = 1\n                else:\n                    fp_thr[iou_idx][d] = 1.\n            else:\n                fp_thr[iou_idx][d] = 1.\n\n    ret = []\n    for iou_idx, thresh in enumerate(iou_thr):\n        # compute precision recall\n        fp = np.cumsum(fp_thr[iou_idx])\n        tp = np.cumsum(tp_thr[iou_idx])\n        recall = tp / float(npos)\n        # avoid divide by zero in case the first detection matches a difficult\n        # ground truth\n        precision = tp / np.maximum(tp + fp, np.finfo(np.float64).eps)\n        ap = average_precision(recall, precision)\n        ret.append((recall, precision, ap))\n\n    return ret\n\n\ndef eval_map_recall(pred, gt, ovthresh=None):\n    \"\"\"Evaluate mAP and recall.\n\n    Generic functions to compute precision/recall for object detection\n        for multiple classes.\n\n    Args:\n        pred (dict): Information of detection results,\n            which maps class_id and predictions.\n        gt (dict): Information of ground truths, which maps class_id and \\\n            ground truths.\n        ovthresh (list[float]): iou threshold.\n            Default: None.\n\n    Return:\n        tuple[dict]: dict results of recall, AP, and precision for all classes.\n    \"\"\"\n\n    ret_values = {}\n    for classname in gt.keys():\n        if classname in pred:\n            ret_values[classname] = eval_det_cls(pred[classname],\n                                                 gt[classname], ovthresh)\n    recall = [{} for i in ovthresh]\n    precision = [{} for i in ovthresh]\n    ap = [{} for i in ovthresh]\n\n    for label in gt.keys():\n        for iou_idx, thresh in enumerate(ovthresh):\n            if label in pred:\n                recall[iou_idx][label], precision[iou_idx][label], ap[iou_idx][\n                    label] = ret_values[label][iou_idx]\n            else:\n                recall[iou_idx][label] = np.zeros(1)\n                precision[iou_idx][label] = np.zeros(1)\n                ap[iou_idx][label] = np.zeros(1)\n\n    return recall, precision, ap\n\n\ndef indoor_eval(gt_annos,\n                dt_annos,\n                metric,\n                label2cat,\n                logger=None,\n                box_type_3d=None,\n                box_mode_3d=None):\n    \"\"\"Indoor Evaluation.\n\n    Evaluate the result of the detection.\n\n    Args:\n        gt_annos (list[dict]): Ground truth annotations.\n        dt_annos (list[dict]): Detection annotations. the dict\n            includes the following keys\n\n            - labels_3d (torch.Tensor): Labels of boxes.\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): \\\n                3D bounding boxes in Depth coordinate.\n            - scores_3d (torch.Tensor): Scores of boxes.\n        metric (list[float]): IoU thresholds for computing average precisions.\n        label2cat (dict): Map from label to category.\n        logger (logging.Logger | str | None): The way to print the mAP\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n\n    Return:\n        dict[str, float]: Dict of results.\n    \"\"\"\n    assert len(dt_annos) == len(gt_annos)\n    pred = {}  # map {class_id: pred}\n    gt = {}  # map {class_id: gt}\n    for img_id in range(len(dt_annos)):\n        # parse detected annotations\n        det_anno = dt_annos[img_id]\n        for i in range(len(det_anno['labels_3d'])):\n            label = det_anno['labels_3d'].numpy()[i]\n            bbox = det_anno['boxes_3d'].convert_to(box_mode_3d)[i]\n            score = det_anno['scores_3d'].numpy()[i]\n            if label not in pred:\n                pred[int(label)] = {}\n            if img_id not in pred[label]:\n                pred[int(label)][img_id] = []\n            if label not in gt:\n                gt[int(label)] = {}\n            if img_id not in gt[label]:\n                gt[int(label)][img_id] = []\n            pred[int(label)][img_id].append((bbox, score))\n\n        # parse gt annotations\n        gt_anno = gt_annos[img_id]\n        if gt_anno['gt_num'] != 0:\n            gt_boxes = box_type_3d(\n                gt_anno['gt_boxes_upright_depth'],\n                box_dim=gt_anno['gt_boxes_upright_depth'].shape[-1],\n                origin=(0.5, 0.5, 0.5)).convert_to(box_mode_3d)\n            labels_3d = gt_anno['class']\n        else:\n            gt_boxes = box_type_3d(np.array([], dtype=np.float32))\n            labels_3d = np.array([], dtype=np.int64)\n\n        for i in range(len(labels_3d)):\n            label = labels_3d[i]\n            bbox = gt_boxes[i]\n            if label not in gt:\n                gt[label] = {}\n            if img_id not in gt[label]:\n                gt[label][img_id] = []\n            gt[label][img_id].append(bbox)\n\n    rec, prec, ap = eval_map_recall(pred, gt, metric)\n    ret_dict = dict()\n    header = ['classes']\n    table_columns = [[label2cat[label]\n                      for label in ap[0].keys()] + ['Overall']]\n\n    for i, iou_thresh in enumerate(metric):\n        header.append(f'AP_{iou_thresh:.2f}')\n        header.append(f'AR_{iou_thresh:.2f}')\n        rec_list = []\n        for label in ap[i].keys():\n            ret_dict[f'{label2cat[label]}_AP_{iou_thresh:.2f}'] = float(\n                ap[i][label][0])\n        ret_dict[f'mAP_{iou_thresh:.2f}'] = float(\n            np.mean(list(ap[i].values())))\n\n        table_columns.append(list(map(float, list(ap[i].values()))))\n        table_columns[-1] += [ret_dict[f'mAP_{iou_thresh:.2f}']]\n        table_columns[-1] = [f'{x:.4f}' for x in table_columns[-1]]\n\n        for label in rec[i].keys():\n            ret_dict[f'{label2cat[label]}_rec_{iou_thresh:.2f}'] = float(\n                rec[i][label][-1])\n            rec_list.append(rec[i][label][-1])\n        ret_dict[f'mAR_{iou_thresh:.2f}'] = float(np.mean(rec_list))\n\n        table_columns.append(list(map(float, rec_list)))\n        table_columns[-1] += [ret_dict[f'mAR_{iou_thresh:.2f}']]\n        table_columns[-1] = [f'{x:.4f}' for x in table_columns[-1]]\n\n    table_data = [header]\n    table_rows = list(zip(*table_columns))\n    table_data += table_rows\n    table = AsciiTable(table_data)\n    table.inner_footing_row_border = True\n    print_log('\\n' + table.table, logger=logger)\n\n    return ret_dict\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/kitti_utils/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .eval import kitti_eval, kitti_eval_coco_style\n\n__all__ = ['kitti_eval', 'kitti_eval_coco_style']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/kitti_utils/eval.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport gc\nimport io as sysio\nimport numba\nimport numpy as np\n\n\n@numba.jit\ndef get_thresholds(scores: np.ndarray, num_gt, num_sample_pts=41):\n    scores.sort()\n    scores = scores[::-1]\n    current_recall = 0\n    thresholds = []\n    for i, score in enumerate(scores):\n        l_recall = (i + 1) / num_gt\n        if i < (len(scores) - 1):\n            r_recall = (i + 2) / num_gt\n        else:\n            r_recall = l_recall\n        if (((r_recall - current_recall) < (current_recall - l_recall))\n                and (i < (len(scores) - 1))):\n            continue\n        # recall = l_recall\n        thresholds.append(score)\n        current_recall += 1 / (num_sample_pts - 1.0)\n    return thresholds\n\n\ndef clean_data(gt_anno, dt_anno, current_class, difficulty):\n    CLASS_NAMES = ['car', 'pedestrian', 'cyclist']\n    MIN_HEIGHT = [40, 25, 25]\n    MAX_OCCLUSION = [0, 1, 2]\n    MAX_TRUNCATION = [0.15, 0.3, 0.5]\n    dc_bboxes, ignored_gt, ignored_dt = [], [], []\n    current_cls_name = CLASS_NAMES[current_class].lower()\n    num_gt = len(gt_anno['name'])\n    num_dt = len(dt_anno['name'])\n    num_valid_gt = 0\n    for i in range(num_gt):\n        bbox = gt_anno['bbox'][i]\n        gt_name = gt_anno['name'][i].lower()\n        height = bbox[3] - bbox[1]\n        valid_class = -1\n        if (gt_name == current_cls_name):\n            valid_class = 1\n        elif (current_cls_name == 'Pedestrian'.lower()\n              and 'Person_sitting'.lower() == gt_name):\n            valid_class = 0\n        elif (current_cls_name == 'Car'.lower() and 'Van'.lower() == gt_name):\n            valid_class = 0\n        else:\n            valid_class = -1\n        ignore = False\n        if ((gt_anno['occluded'][i] > MAX_OCCLUSION[difficulty])\n                or (gt_anno['truncated'][i] > MAX_TRUNCATION[difficulty])\n                or (height <= MIN_HEIGHT[difficulty])):\n            ignore = True\n        if valid_class == 1 and not ignore:\n            ignored_gt.append(0)\n            num_valid_gt += 1\n        elif (valid_class == 0 or (ignore and (valid_class == 1))):\n            ignored_gt.append(1)\n        else:\n            ignored_gt.append(-1)\n    # for i in range(num_gt):\n        if gt_anno['name'][i] == 'DontCare':\n            dc_bboxes.append(gt_anno['bbox'][i])\n    for i in range(num_dt):\n        if (dt_anno['name'][i].lower() == current_cls_name):\n            valid_class = 1\n        else:\n            valid_class = -1\n        height = abs(dt_anno['bbox'][i, 3] - dt_anno['bbox'][i, 1])\n        if height < MIN_HEIGHT[difficulty]:\n            ignored_dt.append(1)\n        elif valid_class == 1:\n            ignored_dt.append(0)\n        else:\n            ignored_dt.append(-1)\n\n    return num_valid_gt, ignored_gt, ignored_dt, dc_bboxes\n\n\n@numba.jit(nopython=True)\ndef image_box_overlap(boxes, query_boxes, criterion=-1):\n    N = boxes.shape[0]\n    K = query_boxes.shape[0]\n    overlaps = np.zeros((N, K), dtype=boxes.dtype)\n    for k in range(K):\n        qbox_area = ((query_boxes[k, 2] - query_boxes[k, 0]) *\n                     (query_boxes[k, 3] - query_boxes[k, 1]))\n        for n in range(N):\n            iw = (\n                min(boxes[n, 2], query_boxes[k, 2]) -\n                max(boxes[n, 0], query_boxes[k, 0]))\n            if iw > 0:\n                ih = (\n                    min(boxes[n, 3], query_boxes[k, 3]) -\n                    max(boxes[n, 1], query_boxes[k, 1]))\n                if ih > 0:\n                    if criterion == -1:\n                        ua = ((boxes[n, 2] - boxes[n, 0]) *\n                              (boxes[n, 3] - boxes[n, 1]) + qbox_area -\n                              iw * ih)\n                    elif criterion == 0:\n                        ua = ((boxes[n, 2] - boxes[n, 0]) *\n                              (boxes[n, 3] - boxes[n, 1]))\n                    elif criterion == 1:\n                        ua = qbox_area\n                    else:\n                        ua = 1.0\n                    overlaps[n, k] = iw * ih / ua\n    return overlaps\n\n\ndef bev_box_overlap(boxes, qboxes, criterion=-1):\n    from .rotate_iou import rotate_iou_gpu_eval\n    riou = rotate_iou_gpu_eval(boxes, qboxes, criterion)\n    return riou\n\n\n@numba.jit(nopython=True, parallel=True)\ndef d3_box_overlap_kernel(boxes, qboxes, rinc, criterion=-1):\n    # ONLY support overlap in CAMERA, not lidar.\n    # TODO: change to use prange for parallel mode, should check the difference\n    N, K = boxes.shape[0], qboxes.shape[0]\n    for i in numba.prange(N):\n        for j in numba.prange(K):\n            if rinc[i, j] > 0:\n                # iw = (min(boxes[i, 1] + boxes[i, 4], qboxes[j, 1] +\n                #         qboxes[j, 4]) - max(boxes[i, 1], qboxes[j, 1]))\n                iw = (\n                    min(boxes[i, 1], qboxes[j, 1]) -\n                    max(boxes[i, 1] - boxes[i, 4],\n                        qboxes[j, 1] - qboxes[j, 4]))\n\n                if iw > 0:\n                    area1 = boxes[i, 3] * boxes[i, 4] * boxes[i, 5]\n                    area2 = qboxes[j, 3] * qboxes[j, 4] * qboxes[j, 5]\n                    inc = iw * rinc[i, j]\n                    if criterion == -1:\n                        ua = (area1 + area2 - inc)\n                    elif criterion == 0:\n                        ua = area1\n                    elif criterion == 1:\n                        ua = area2\n                    else:\n                        ua = inc\n                    rinc[i, j] = inc / ua\n                else:\n                    rinc[i, j] = 0.0\n\n\ndef d3_box_overlap(boxes, qboxes, criterion=-1):\n    from .rotate_iou import rotate_iou_gpu_eval\n    rinc = rotate_iou_gpu_eval(boxes[:, [0, 2, 3, 5, 6]],\n                               qboxes[:, [0, 2, 3, 5, 6]], 2)\n    d3_box_overlap_kernel(boxes, qboxes, rinc, criterion)\n    return rinc\n\n\n@numba.jit(nopython=True)\ndef compute_statistics_jit(overlaps,\n                           gt_datas,\n                           dt_datas,\n                           ignored_gt,\n                           ignored_det,\n                           dc_bboxes,\n                           metric,\n                           min_overlap,\n                           thresh=0,\n                           compute_fp=False,\n                           compute_aos=False):\n\n    det_size = dt_datas.shape[0]\n    gt_size = gt_datas.shape[0]\n    dt_scores = dt_datas[:, -1]\n    dt_alphas = dt_datas[:, 4]\n    gt_alphas = gt_datas[:, 4]\n    dt_bboxes = dt_datas[:, :4]\n    # gt_bboxes = gt_datas[:, :4]\n\n    assigned_detection = [False] * det_size\n    ignored_threshold = [False] * det_size\n    if compute_fp:\n        for i in range(det_size):\n            if (dt_scores[i] < thresh):\n                ignored_threshold[i] = True\n    NO_DETECTION = -10000000\n    tp, fp, fn, similarity = 0, 0, 0, 0\n    # thresholds = [0.0]\n    # delta = [0.0]\n    thresholds = np.zeros((gt_size, ))\n    thresh_idx = 0\n    delta = np.zeros((gt_size, ))\n    delta_idx = 0\n    for i in range(gt_size):\n        if ignored_gt[i] == -1:\n            continue\n        det_idx = -1\n        valid_detection = NO_DETECTION\n        max_overlap = 0\n        assigned_ignored_det = False\n\n        for j in range(det_size):\n            if (ignored_det[j] == -1):\n                continue\n            if (assigned_detection[j]):\n                continue\n            if (ignored_threshold[j]):\n                continue\n            overlap = overlaps[j, i]\n            dt_score = dt_scores[j]\n            if (not compute_fp and (overlap > min_overlap)\n                    and dt_score > valid_detection):\n                det_idx = j\n                valid_detection = dt_score\n            elif (compute_fp and (overlap > min_overlap)\n                  and (overlap > max_overlap or assigned_ignored_det)\n                  and ignored_det[j] == 0):\n                max_overlap = overlap\n                det_idx = j\n                valid_detection = 1\n                assigned_ignored_det = False\n            elif (compute_fp and (overlap > min_overlap)\n                  and (valid_detection == NO_DETECTION)\n                  and ignored_det[j] == 1):\n                det_idx = j\n                valid_detection = 1\n                assigned_ignored_det = True\n\n        if (valid_detection == NO_DETECTION) and ignored_gt[i] == 0:\n            fn += 1\n        elif ((valid_detection != NO_DETECTION)\n              and (ignored_gt[i] == 1 or ignored_det[det_idx] == 1)):\n            assigned_detection[det_idx] = True\n        elif valid_detection != NO_DETECTION:\n            tp += 1\n            # thresholds.append(dt_scores[det_idx])\n            thresholds[thresh_idx] = dt_scores[det_idx]\n            thresh_idx += 1\n            if compute_aos:\n                # delta.append(gt_alphas[i] - dt_alphas[det_idx])\n                delta[delta_idx] = gt_alphas[i] - dt_alphas[det_idx]\n                delta_idx += 1\n\n            assigned_detection[det_idx] = True\n    if compute_fp:\n        for i in range(det_size):\n            if (not (assigned_detection[i] or ignored_det[i] == -1\n                     or ignored_det[i] == 1 or ignored_threshold[i])):\n                fp += 1\n        nstuff = 0\n        if metric == 0:\n            overlaps_dt_dc = image_box_overlap(dt_bboxes, dc_bboxes, 0)\n            for i in range(dc_bboxes.shape[0]):\n                for j in range(det_size):\n                    if (assigned_detection[j]):\n                        continue\n                    if (ignored_det[j] == -1 or ignored_det[j] == 1):\n                        continue\n                    if (ignored_threshold[j]):\n                        continue\n                    if overlaps_dt_dc[j, i] > min_overlap:\n                        assigned_detection[j] = True\n                        nstuff += 1\n        fp -= nstuff\n        if compute_aos:\n            tmp = np.zeros((fp + delta_idx, ))\n            # tmp = [0] * fp\n            for i in range(delta_idx):\n                tmp[i + fp] = (1.0 + np.cos(delta[i])) / 2.0\n                # tmp.append((1.0 + np.cos(delta[i])) / 2.0)\n            # assert len(tmp) == fp + tp\n            # assert len(delta) == tp\n            if tp > 0 or fp > 0:\n                similarity = np.sum(tmp)\n            else:\n                similarity = -1\n    return tp, fp, fn, similarity, thresholds[:thresh_idx]\n\n\ndef get_split_parts(num, num_part):\n    same_part = num // num_part\n    remain_num = num % num_part\n    if remain_num == 0:\n        return [same_part] * num_part\n    else:\n        return [same_part] * num_part + [remain_num]\n\n\n@numba.jit(nopython=True)\ndef fused_compute_statistics(overlaps,\n                             pr,\n                             gt_nums,\n                             dt_nums,\n                             dc_nums,\n                             gt_datas,\n                             dt_datas,\n                             dontcares,\n                             ignored_gts,\n                             ignored_dets,\n                             metric,\n                             min_overlap,\n                             thresholds,\n                             compute_aos=False):\n    gt_num = 0\n    dt_num = 0\n    dc_num = 0\n    for i in range(gt_nums.shape[0]):\n        for t, thresh in enumerate(thresholds):\n            overlap = overlaps[dt_num:dt_num + dt_nums[i],\n                               gt_num:gt_num + gt_nums[i]]\n\n            gt_data = gt_datas[gt_num:gt_num + gt_nums[i]]\n            dt_data = dt_datas[dt_num:dt_num + dt_nums[i]]\n            ignored_gt = ignored_gts[gt_num:gt_num + gt_nums[i]]\n            ignored_det = ignored_dets[dt_num:dt_num + dt_nums[i]]\n            dontcare = dontcares[dc_num:dc_num + dc_nums[i]]\n            tp, fp, fn, similarity, _ = compute_statistics_jit(\n                overlap,\n                gt_data,\n                dt_data,\n                ignored_gt,\n                ignored_det,\n                dontcare,\n                metric,\n                min_overlap=min_overlap,\n                thresh=thresh,\n                compute_fp=True,\n                compute_aos=compute_aos)\n            pr[t, 0] += tp\n            pr[t, 1] += fp\n            pr[t, 2] += fn\n            if similarity != -1:\n                pr[t, 3] += similarity\n        gt_num += gt_nums[i]\n        dt_num += dt_nums[i]\n        dc_num += dc_nums[i]\n\n\ndef calculate_iou_partly(gt_annos, dt_annos, metric, num_parts=50):\n    \"\"\"Fast iou algorithm. this function can be used independently to do result\n    analysis. Must be used in CAMERA coordinate system.\n\n    Args:\n        gt_annos (dict): Must from get_label_annos() in kitti_common.py.\n        dt_annos (dict): Must from get_label_annos() in kitti_common.py.\n        metric (int): Eval type. 0: bbox, 1: bev, 2: 3d.\n        num_parts (int): A parameter for fast calculate algorithm.\n    \"\"\"\n    assert len(gt_annos) == len(dt_annos)\n    total_dt_num = np.stack([len(a['name']) for a in dt_annos], 0)\n    total_gt_num = np.stack([len(a['name']) for a in gt_annos], 0)\n    num_examples = len(gt_annos)\n    split_parts = get_split_parts(num_examples, num_parts)\n    parted_overlaps = []\n    example_idx = 0\n\n    for num_part in split_parts:\n        gt_annos_part = gt_annos[example_idx:example_idx + num_part]\n        dt_annos_part = dt_annos[example_idx:example_idx + num_part]\n        if metric == 0:\n            gt_boxes = np.concatenate([a['bbox'] for a in gt_annos_part], 0)\n            dt_boxes = np.concatenate([a['bbox'] for a in dt_annos_part], 0)\n            overlap_part = image_box_overlap(gt_boxes, dt_boxes)\n        elif metric == 1:\n            loc = np.concatenate(\n                [a['location'][:, [0, 2]] for a in gt_annos_part], 0)\n            dims = np.concatenate(\n                [a['dimensions'][:, [0, 2]] for a in gt_annos_part], 0)\n            rots = np.concatenate([a['rotation_y'] for a in gt_annos_part], 0)\n            gt_boxes = np.concatenate([loc, dims, rots[..., np.newaxis]],\n                                      axis=1)\n            loc = np.concatenate(\n                [a['location'][:, [0, 2]] for a in dt_annos_part], 0)\n            dims = np.concatenate(\n                [a['dimensions'][:, [0, 2]] for a in dt_annos_part], 0)\n            rots = np.concatenate([a['rotation_y'] for a in dt_annos_part], 0)\n            dt_boxes = np.concatenate([loc, dims, rots[..., np.newaxis]],\n                                      axis=1)\n            overlap_part = bev_box_overlap(gt_boxes,\n                                           dt_boxes).astype(np.float64)\n        elif metric == 2:\n            loc = np.concatenate([a['location'] for a in gt_annos_part], 0)\n            dims = np.concatenate([a['dimensions'] for a in gt_annos_part], 0)\n            rots = np.concatenate([a['rotation_y'] for a in gt_annos_part], 0)\n            gt_boxes = np.concatenate([loc, dims, rots[..., np.newaxis]],\n                                      axis=1)\n            loc = np.concatenate([a['location'] for a in dt_annos_part], 0)\n            dims = np.concatenate([a['dimensions'] for a in dt_annos_part], 0)\n            rots = np.concatenate([a['rotation_y'] for a in dt_annos_part], 0)\n            dt_boxes = np.concatenate([loc, dims, rots[..., np.newaxis]],\n                                      axis=1)\n            overlap_part = d3_box_overlap(gt_boxes,\n                                          dt_boxes).astype(np.float64)\n        else:\n            raise ValueError('unknown metric')\n        parted_overlaps.append(overlap_part)\n        example_idx += num_part\n    overlaps = []\n    example_idx = 0\n    for j, num_part in enumerate(split_parts):\n        gt_annos_part = gt_annos[example_idx:example_idx + num_part]\n        dt_annos_part = dt_annos[example_idx:example_idx + num_part]\n        gt_num_idx, dt_num_idx = 0, 0\n        for i in range(num_part):\n            gt_box_num = total_gt_num[example_idx + i]\n            dt_box_num = total_dt_num[example_idx + i]\n            overlaps.append(\n                parted_overlaps[j][gt_num_idx:gt_num_idx + gt_box_num,\n                                   dt_num_idx:dt_num_idx + dt_box_num])\n            gt_num_idx += gt_box_num\n            dt_num_idx += dt_box_num\n        example_idx += num_part\n\n    return overlaps, parted_overlaps, total_gt_num, total_dt_num\n\n\ndef _prepare_data(gt_annos, dt_annos, current_class, difficulty):\n    gt_datas_list = []\n    dt_datas_list = []\n    total_dc_num = []\n    ignored_gts, ignored_dets, dontcares = [], [], []\n    total_num_valid_gt = 0\n    for i in range(len(gt_annos)):\n        rets = clean_data(gt_annos[i], dt_annos[i], current_class, difficulty)\n        num_valid_gt, ignored_gt, ignored_det, dc_bboxes = rets\n        ignored_gts.append(np.array(ignored_gt, dtype=np.int64))\n        ignored_dets.append(np.array(ignored_det, dtype=np.int64))\n        if len(dc_bboxes) == 0:\n            dc_bboxes = np.zeros((0, 4)).astype(np.float64)\n        else:\n            dc_bboxes = np.stack(dc_bboxes, 0).astype(np.float64)\n        total_dc_num.append(dc_bboxes.shape[0])\n        dontcares.append(dc_bboxes)\n        total_num_valid_gt += num_valid_gt\n        gt_datas = np.concatenate(\n            [gt_annos[i]['bbox'], gt_annos[i]['alpha'][..., np.newaxis]], 1)\n        dt_datas = np.concatenate([\n            dt_annos[i]['bbox'], dt_annos[i]['alpha'][..., np.newaxis],\n            dt_annos[i]['score'][..., np.newaxis]\n        ], 1)\n        gt_datas_list.append(gt_datas)\n        dt_datas_list.append(dt_datas)\n    total_dc_num = np.stack(total_dc_num, axis=0)\n    return (gt_datas_list, dt_datas_list, ignored_gts, ignored_dets, dontcares,\n            total_dc_num, total_num_valid_gt)\n\n\ndef eval_class(gt_annos,\n               dt_annos,\n               current_classes,\n               difficultys,\n               metric,\n               min_overlaps,\n               compute_aos=False,\n               num_parts=200):\n    \"\"\"Kitti eval. support 2d/bev/3d/aos eval. support 0.5:0.05:0.95 coco AP.\n\n    Args:\n        gt_annos (dict): Must from get_label_annos() in kitti_common.py.\n        dt_annos (dict): Must from get_label_annos() in kitti_common.py.\n        current_classes (list[int]): 0: car, 1: pedestrian, 2: cyclist.\n        difficultys (list[int]): Eval difficulty, 0: easy, 1: normal, 2: hard\n        metric (int): Eval type. 0: bbox, 1: bev, 2: 3d\n        min_overlaps (float): Min overlap. format:\n            [num_overlap, metric, class].\n        num_parts (int): A parameter for fast calculate algorithm\n\n    Returns:\n        dict[str, np.ndarray]: recall, precision and aos\n    \"\"\"\n    assert len(gt_annos) == len(dt_annos)\n    num_examples = len(gt_annos)\n    if num_examples < num_parts:\n        num_parts = num_examples\n    split_parts = get_split_parts(num_examples, num_parts)\n\n    rets = calculate_iou_partly(dt_annos, gt_annos, metric, num_parts)\n    overlaps, parted_overlaps, total_dt_num, total_gt_num = rets\n    N_SAMPLE_PTS = 41\n    num_minoverlap = len(min_overlaps)\n    num_class = len(current_classes)\n    num_difficulty = len(difficultys)\n    precision = np.zeros(\n        [num_class, num_difficulty, num_minoverlap, N_SAMPLE_PTS])\n    recall = np.zeros(\n        [num_class, num_difficulty, num_minoverlap, N_SAMPLE_PTS])\n    aos = np.zeros([num_class, num_difficulty, num_minoverlap, N_SAMPLE_PTS])\n    for m, current_class in enumerate(current_classes):\n        for idx_l, difficulty in enumerate(difficultys):\n            rets = _prepare_data(gt_annos, dt_annos, current_class, difficulty)\n            (gt_datas_list, dt_datas_list, ignored_gts, ignored_dets,\n             dontcares, total_dc_num, total_num_valid_gt) = rets\n            for k, min_overlap in enumerate(min_overlaps[:, metric, m]):\n                thresholdss = []\n                for i in range(len(gt_annos)):\n                    rets = compute_statistics_jit(\n                        overlaps[i],\n                        gt_datas_list[i],\n                        dt_datas_list[i],\n                        ignored_gts[i],\n                        ignored_dets[i],\n                        dontcares[i],\n                        metric,\n                        min_overlap=min_overlap,\n                        thresh=0.0,\n                        compute_fp=False)\n                    tp, fp, fn, similarity, thresholds = rets\n                    thresholdss += thresholds.tolist()\n                thresholdss = np.array(thresholdss)\n                thresholds = get_thresholds(thresholdss, total_num_valid_gt)\n                thresholds = np.array(thresholds)\n                pr = np.zeros([len(thresholds), 4])\n                idx = 0\n                for j, num_part in enumerate(split_parts):\n                    gt_datas_part = np.concatenate(\n                        gt_datas_list[idx:idx + num_part], 0)\n                    dt_datas_part = np.concatenate(\n                        dt_datas_list[idx:idx + num_part], 0)\n                    dc_datas_part = np.concatenate(\n                        dontcares[idx:idx + num_part], 0)\n                    ignored_dets_part = np.concatenate(\n                        ignored_dets[idx:idx + num_part], 0)\n                    ignored_gts_part = np.concatenate(\n                        ignored_gts[idx:idx + num_part], 0)\n                    fused_compute_statistics(\n                        parted_overlaps[j],\n                        pr,\n                        total_gt_num[idx:idx + num_part],\n                        total_dt_num[idx:idx + num_part],\n                        total_dc_num[idx:idx + num_part],\n                        gt_datas_part,\n                        dt_datas_part,\n                        dc_datas_part,\n                        ignored_gts_part,\n                        ignored_dets_part,\n                        metric,\n                        min_overlap=min_overlap,\n                        thresholds=thresholds,\n                        compute_aos=compute_aos)\n                    idx += num_part\n                for i in range(len(thresholds)):\n                    recall[m, idx_l, k, i] = pr[i, 0] / (pr[i, 0] + pr[i, 2])\n                    precision[m, idx_l, k, i] = pr[i, 0] / (\n                        pr[i, 0] + pr[i, 1])\n                    if compute_aos:\n                        aos[m, idx_l, k, i] = pr[i, 3] / (pr[i, 0] + pr[i, 1])\n                for i in range(len(thresholds)):\n                    precision[m, idx_l, k, i] = np.max(\n                        precision[m, idx_l, k, i:], axis=-1)\n                    recall[m, idx_l, k, i] = np.max(\n                        recall[m, idx_l, k, i:], axis=-1)\n                    if compute_aos:\n                        aos[m, idx_l, k, i] = np.max(\n                            aos[m, idx_l, k, i:], axis=-1)\n    ret_dict = {\n        'recall': recall,\n        'precision': precision,\n        'orientation': aos,\n    }\n\n    # clean temp variables\n    del overlaps\n    del parted_overlaps\n\n    gc.collect()\n    return ret_dict\n\n\ndef get_mAP(prec):\n    sums = 0\n    for i in range(0, prec.shape[-1], 4):\n        sums = sums + prec[..., i]\n    return sums / 11 * 100\n\n\ndef print_str(value, *arg, sstream=None):\n    if sstream is None:\n        sstream = sysio.StringIO()\n    sstream.truncate(0)\n    sstream.seek(0)\n    print(value, *arg, file=sstream)\n    return sstream.getvalue()\n\n\ndef do_eval(gt_annos,\n            dt_annos,\n            current_classes,\n            min_overlaps,\n            eval_types=['bbox', 'bev', '3d']):\n    # min_overlaps: [num_minoverlap, metric, num_class]\n    difficultys = [0, 1, 2]\n    mAP_bbox = None\n    mAP_aos = None\n    if 'bbox' in eval_types:\n        ret = eval_class(\n            gt_annos,\n            dt_annos,\n            current_classes,\n            difficultys,\n            0,\n            min_overlaps,\n            compute_aos=('aos' in eval_types))\n        # ret: [num_class, num_diff, num_minoverlap, num_sample_points]\n        mAP_bbox = get_mAP(ret['precision'])\n        if 'aos' in eval_types:\n            mAP_aos = get_mAP(ret['orientation'])\n\n    mAP_bev = None\n    if 'bev' in eval_types:\n        ret = eval_class(gt_annos, dt_annos, current_classes, difficultys, 1,\n                         min_overlaps)\n        mAP_bev = get_mAP(ret['precision'])\n\n    mAP_3d = None\n    if '3d' in eval_types:\n        ret = eval_class(gt_annos, dt_annos, current_classes, difficultys, 2,\n                         min_overlaps)\n        mAP_3d = get_mAP(ret['precision'])\n    return mAP_bbox, mAP_bev, mAP_3d, mAP_aos\n\n\ndef do_coco_style_eval(gt_annos, dt_annos, current_classes, overlap_ranges,\n                       compute_aos):\n    # overlap_ranges: [range, metric, num_class]\n    min_overlaps = np.zeros([10, *overlap_ranges.shape[1:]])\n    for i in range(overlap_ranges.shape[1]):\n        for j in range(overlap_ranges.shape[2]):\n            min_overlaps[:, i, j] = np.linspace(*overlap_ranges[:, i, j])\n    mAP_bbox, mAP_bev, mAP_3d, mAP_aos = do_eval(gt_annos, dt_annos,\n                                                 current_classes, min_overlaps,\n                                                 compute_aos)\n    # ret: [num_class, num_diff, num_minoverlap]\n    mAP_bbox = mAP_bbox.mean(-1)\n    mAP_bev = mAP_bev.mean(-1)\n    mAP_3d = mAP_3d.mean(-1)\n    if mAP_aos is not None:\n        mAP_aos = mAP_aos.mean(-1)\n    return mAP_bbox, mAP_bev, mAP_3d, mAP_aos\n\n\ndef kitti_eval(gt_annos,\n               dt_annos,\n               current_classes,\n               eval_types=['bbox', 'bev', '3d']):\n    \"\"\"KITTI evaluation.\n\n    Args:\n        gt_annos (list[dict]): Contain gt information of each sample.\n        dt_annos (list[dict]): Contain detected information of each sample.\n        current_classes (list[str]): Classes to evaluation.\n        eval_types (list[str], optional): Types to eval.\n            Defaults to ['bbox', 'bev', '3d'].\n\n    Returns:\n        tuple: String and dict of evaluation results.\n    \"\"\"\n    assert len(eval_types) > 0, 'must contain at least one evaluation type'\n    if 'aos' in eval_types:\n        assert 'bbox' in eval_types, 'must evaluate bbox when evaluating aos'\n    overlap_0_7 = np.array([[0.7, 0.5, 0.5, 0.7,\n                             0.5], [0.7, 0.5, 0.5, 0.7, 0.5],\n                            [0.7, 0.5, 0.5, 0.7, 0.5]])\n    overlap_0_5 = np.array([[0.7, 0.5, 0.5, 0.7, 0.5],\n                            [0.5, 0.25, 0.25, 0.5, 0.25],\n                            [0.5, 0.25, 0.25, 0.5, 0.25]])\n    min_overlaps = np.stack([overlap_0_7, overlap_0_5], axis=0)  # [2, 3, 5]\n    class_to_name = {\n        0: 'Car',\n        1: 'Pedestrian',\n        2: 'Cyclist',\n        3: 'Van',\n        4: 'Person_sitting',\n    }\n    name_to_class = {v: n for n, v in class_to_name.items()}\n    if not isinstance(current_classes, (list, tuple)):\n        current_classes = [current_classes]\n    current_classes_int = []\n    for curcls in current_classes:\n        if isinstance(curcls, str):\n            current_classes_int.append(name_to_class[curcls])\n        else:\n            current_classes_int.append(curcls)\n    current_classes = current_classes_int\n    min_overlaps = min_overlaps[:, :, current_classes]\n    result = ''\n    # check whether alpha is valid\n    compute_aos = False\n    pred_alpha = False\n    valid_alpha_gt = False\n    for anno in dt_annos:\n        mask = (anno['alpha'] != -10)\n        if anno['alpha'][mask].shape[0] != 0:\n            pred_alpha = True\n            break\n    for anno in gt_annos:\n        if anno['alpha'][0] != -10:\n            valid_alpha_gt = True\n            break\n    compute_aos = (pred_alpha and valid_alpha_gt)\n    if compute_aos:\n        eval_types.append('aos')\n\n    mAPbbox, mAPbev, mAP3d, mAPaos = do_eval(gt_annos, dt_annos,\n                                             current_classes, min_overlaps,\n                                             eval_types)\n\n    ret_dict = {}\n    difficulty = ['easy', 'moderate', 'hard']\n    for j, curcls in enumerate(current_classes):\n        # mAP threshold array: [num_minoverlap, metric, class]\n        # mAP result: [num_class, num_diff, num_minoverlap]\n        curcls_name = class_to_name[curcls]\n        for i in range(min_overlaps.shape[0]):\n            # prepare results for print\n            result += ('{} AP@{:.2f}, {:.2f}, {:.2f}:\\n'.format(\n                curcls_name, *min_overlaps[i, :, j]))\n            if mAPbbox is not None:\n                result += 'bbox AP:{:.4f}, {:.4f}, {:.4f}\\n'.format(\n                    *mAPbbox[j, :, i])\n            if mAPbev is not None:\n                result += 'bev  AP:{:.4f}, {:.4f}, {:.4f}\\n'.format(\n                    *mAPbev[j, :, i])\n            if mAP3d is not None:\n                result += '3d   AP:{:.4f}, {:.4f}, {:.4f}\\n'.format(\n                    *mAP3d[j, :, i])\n\n            if compute_aos:\n                result += 'aos  AP:{:.2f}, {:.2f}, {:.2f}\\n'.format(\n                    *mAPaos[j, :, i])\n\n            # prepare results for logger\n            for idx in range(3):\n                if i == 0:\n                    postfix = f'{difficulty[idx]}_strict'\n                else:\n                    postfix = f'{difficulty[idx]}_loose'\n                prefix = f'KITTI/{curcls_name}'\n                if mAP3d is not None:\n                    ret_dict[f'{prefix}_3D_{postfix}'] = mAP3d[j, idx, i]\n                if mAPbev is not None:\n                    ret_dict[f'{prefix}_BEV_{postfix}'] = mAPbev[j, idx, i]\n                if mAPbbox is not None:\n                    ret_dict[f'{prefix}_2D_{postfix}'] = mAPbbox[j, idx, i]\n\n    # calculate mAP over all classes if there are multiple classes\n    if len(current_classes) > 1:\n        # prepare results for print\n        result += ('\\nOverall AP@{}, {}, {}:\\n'.format(*difficulty))\n        if mAPbbox is not None:\n            mAPbbox = mAPbbox.mean(axis=0)\n            result += 'bbox AP:{:.4f}, {:.4f}, {:.4f}\\n'.format(*mAPbbox[:, 0])\n        if mAPbev is not None:\n            mAPbev = mAPbev.mean(axis=0)\n            result += 'bev  AP:{:.4f}, {:.4f}, {:.4f}\\n'.format(*mAPbev[:, 0])\n        if mAP3d is not None:\n            mAP3d = mAP3d.mean(axis=0)\n            result += '3d   AP:{:.4f}, {:.4f}, {:.4f}\\n'.format(*mAP3d[:, 0])\n        if compute_aos:\n            mAPaos = mAPaos.mean(axis=0)\n            result += 'aos  AP:{:.2f}, {:.2f}, {:.2f}\\n'.format(*mAPaos[:, 0])\n\n        # prepare results for logger\n        for idx in range(3):\n            postfix = f'{difficulty[idx]}'\n            if mAP3d is not None:\n                ret_dict[f'KITTI/Overall_3D_{postfix}'] = mAP3d[idx, 0]\n            if mAPbev is not None:\n                ret_dict[f'KITTI/Overall_BEV_{postfix}'] = mAPbev[idx, 0]\n            if mAPbbox is not None:\n                ret_dict[f'KITTI/Overall_2D_{postfix}'] = mAPbbox[idx, 0]\n\n    return result, ret_dict\n\n\ndef kitti_eval_coco_style(gt_annos, dt_annos, current_classes):\n    \"\"\"coco style evaluation of kitti.\n\n    Args:\n        gt_annos (list[dict]): Contain gt information of each sample.\n        dt_annos (list[dict]): Contain detected information of each sample.\n        current_classes (list[str]): Classes to evaluation.\n\n    Returns:\n        string: Evaluation results.\n    \"\"\"\n    class_to_name = {\n        0: 'Car',\n        1: 'Pedestrian',\n        2: 'Cyclist',\n        3: 'Van',\n        4: 'Person_sitting',\n    }\n    class_to_range = {\n        0: [0.5, 0.95, 10],\n        1: [0.25, 0.7, 10],\n        2: [0.25, 0.7, 10],\n        3: [0.5, 0.95, 10],\n        4: [0.25, 0.7, 10],\n    }\n    name_to_class = {v: n for n, v in class_to_name.items()}\n    if not isinstance(current_classes, (list, tuple)):\n        current_classes = [current_classes]\n    current_classes_int = []\n    for curcls in current_classes:\n        if isinstance(curcls, str):\n            current_classes_int.append(name_to_class[curcls])\n        else:\n            current_classes_int.append(curcls)\n    current_classes = current_classes_int\n    overlap_ranges = np.zeros([3, 3, len(current_classes)])\n    for i, curcls in enumerate(current_classes):\n        overlap_ranges[:, :, i] = np.array(class_to_range[curcls])[:,\n                                                                   np.newaxis]\n    result = ''\n    # check whether alpha is valid\n    compute_aos = False\n    for anno in dt_annos:\n        if anno['alpha'].shape[0] != 0:\n            if anno['alpha'][0] != -10:\n                compute_aos = True\n            break\n    mAPbbox, mAPbev, mAP3d, mAPaos = do_coco_style_eval(\n        gt_annos, dt_annos, current_classes, overlap_ranges, compute_aos)\n    for j, curcls in enumerate(current_classes):\n        # mAP threshold array: [num_minoverlap, metric, class]\n        # mAP result: [num_class, num_diff, num_minoverlap]\n        o_range = np.array(class_to_range[curcls])[[0, 2, 1]]\n        o_range[1] = (o_range[2] - o_range[0]) / (o_range[1] - 1)\n        result += print_str((f'{class_to_name[curcls]} '\n                             'coco AP@{:.2f}:{:.2f}:{:.2f}:'.format(*o_range)))\n        result += print_str((f'bbox AP:{mAPbbox[j, 0]:.2f}, '\n                             f'{mAPbbox[j, 1]:.2f}, '\n                             f'{mAPbbox[j, 2]:.2f}'))\n        result += print_str((f'bev  AP:{mAPbev[j, 0]:.2f}, '\n                             f'{mAPbev[j, 1]:.2f}, '\n                             f'{mAPbev[j, 2]:.2f}'))\n        result += print_str((f'3d   AP:{mAP3d[j, 0]:.2f}, '\n                             f'{mAP3d[j, 1]:.2f}, '\n                             f'{mAP3d[j, 2]:.2f}'))\n        if compute_aos:\n            result += print_str((f'aos  AP:{mAPaos[j, 0]:.2f}, '\n                                 f'{mAPaos[j, 1]:.2f}, '\n                                 f'{mAPaos[j, 2]:.2f}'))\n    return result\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/kitti_utils/rotate_iou.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n#####################\n# Based on https://github.com/hongzhenwang/RRPN-revise\n# Licensed under The MIT License\n# Author: yanyan, scrin@foxmail.com\n#####################\nimport math\nimport numba\nimport numpy as np\nfrom numba import cuda\n\n\n@numba.jit(nopython=True)\ndef div_up(m, n):\n    return m // n + (m % n > 0)\n\n\n@cuda.jit('(float32[:], float32[:], float32[:])', device=True, inline=True)\ndef trangle_area(a, b, c):\n    return ((a[0] - c[0]) * (b[1] - c[1]) - (a[1] - c[1]) *\n            (b[0] - c[0])) / 2.0\n\n\n@cuda.jit('(float32[:], int32)', device=True, inline=True)\ndef area(int_pts, num_of_inter):\n    area_val = 0.0\n    for i in range(num_of_inter - 2):\n        area_val += abs(\n            trangle_area(int_pts[:2], int_pts[2 * i + 2:2 * i + 4],\n                         int_pts[2 * i + 4:2 * i + 6]))\n    return area_val\n\n\n@cuda.jit('(float32[:], int32)', device=True, inline=True)\ndef sort_vertex_in_convex_polygon(int_pts, num_of_inter):\n    if num_of_inter > 0:\n        center = cuda.local.array((2, ), dtype=numba.float32)\n        center[:] = 0.0\n        for i in range(num_of_inter):\n            center[0] += int_pts[2 * i]\n            center[1] += int_pts[2 * i + 1]\n        center[0] /= num_of_inter\n        center[1] /= num_of_inter\n        v = cuda.local.array((2, ), dtype=numba.float32)\n        vs = cuda.local.array((16, ), dtype=numba.float32)\n        for i in range(num_of_inter):\n            v[0] = int_pts[2 * i] - center[0]\n            v[1] = int_pts[2 * i + 1] - center[1]\n            d = math.sqrt(v[0] * v[0] + v[1] * v[1])\n            v[0] = v[0] / d\n            v[1] = v[1] / d\n            if v[1] < 0:\n                v[0] = -2 - v[0]\n            vs[i] = v[0]\n        j = 0\n        temp = 0\n        for i in range(1, num_of_inter):\n            if vs[i - 1] > vs[i]:\n                temp = vs[i]\n                tx = int_pts[2 * i]\n                ty = int_pts[2 * i + 1]\n                j = i\n                while j > 0 and vs[j - 1] > temp:\n                    vs[j] = vs[j - 1]\n                    int_pts[j * 2] = int_pts[j * 2 - 2]\n                    int_pts[j * 2 + 1] = int_pts[j * 2 - 1]\n                    j -= 1\n\n                vs[j] = temp\n                int_pts[j * 2] = tx\n                int_pts[j * 2 + 1] = ty\n\n\n@cuda.jit(\n    '(float32[:], float32[:], int32, int32, float32[:])',\n    device=True,\n    inline=True)\ndef line_segment_intersection(pts1, pts2, i, j, temp_pts):\n    A = cuda.local.array((2, ), dtype=numba.float32)\n    B = cuda.local.array((2, ), dtype=numba.float32)\n    C = cuda.local.array((2, ), dtype=numba.float32)\n    D = cuda.local.array((2, ), dtype=numba.float32)\n\n    A[0] = pts1[2 * i]\n    A[1] = pts1[2 * i + 1]\n\n    B[0] = pts1[2 * ((i + 1) % 4)]\n    B[1] = pts1[2 * ((i + 1) % 4) + 1]\n\n    C[0] = pts2[2 * j]\n    C[1] = pts2[2 * j + 1]\n\n    D[0] = pts2[2 * ((j + 1) % 4)]\n    D[1] = pts2[2 * ((j + 1) % 4) + 1]\n    BA0 = B[0] - A[0]\n    BA1 = B[1] - A[1]\n    DA0 = D[0] - A[0]\n    CA0 = C[0] - A[0]\n    DA1 = D[1] - A[1]\n    CA1 = C[1] - A[1]\n    acd = DA1 * CA0 > CA1 * DA0\n    bcd = (D[1] - B[1]) * (C[0] - B[0]) > (C[1] - B[1]) * (D[0] - B[0])\n    if acd != bcd:\n        abc = CA1 * BA0 > BA1 * CA0\n        abd = DA1 * BA0 > BA1 * DA0\n        if abc != abd:\n            DC0 = D[0] - C[0]\n            DC1 = D[1] - C[1]\n            ABBA = A[0] * B[1] - B[0] * A[1]\n            CDDC = C[0] * D[1] - D[0] * C[1]\n            DH = BA1 * DC0 - BA0 * DC1\n            Dx = ABBA * DC0 - BA0 * CDDC\n            Dy = ABBA * DC1 - BA1 * CDDC\n            temp_pts[0] = Dx / DH\n            temp_pts[1] = Dy / DH\n            return True\n    return False\n\n\n@cuda.jit(\n    '(float32[:], float32[:], int32, int32, float32[:])',\n    device=True,\n    inline=True)\ndef line_segment_intersection_v1(pts1, pts2, i, j, temp_pts):\n    a = cuda.local.array((2, ), dtype=numba.float32)\n    b = cuda.local.array((2, ), dtype=numba.float32)\n    c = cuda.local.array((2, ), dtype=numba.float32)\n    d = cuda.local.array((2, ), dtype=numba.float32)\n\n    a[0] = pts1[2 * i]\n    a[1] = pts1[2 * i + 1]\n\n    b[0] = pts1[2 * ((i + 1) % 4)]\n    b[1] = pts1[2 * ((i + 1) % 4) + 1]\n\n    c[0] = pts2[2 * j]\n    c[1] = pts2[2 * j + 1]\n\n    d[0] = pts2[2 * ((j + 1) % 4)]\n    d[1] = pts2[2 * ((j + 1) % 4) + 1]\n\n    area_abc = trangle_area(a, b, c)\n    area_abd = trangle_area(a, b, d)\n\n    if area_abc * area_abd >= 0:\n        return False\n\n    area_cda = trangle_area(c, d, a)\n    area_cdb = area_cda + area_abc - area_abd\n\n    if area_cda * area_cdb >= 0:\n        return False\n    t = area_cda / (area_abd - area_abc)\n\n    dx = t * (b[0] - a[0])\n    dy = t * (b[1] - a[1])\n    temp_pts[0] = a[0] + dx\n    temp_pts[1] = a[1] + dy\n    return True\n\n\n@cuda.jit('(float32, float32, float32[:])', device=True, inline=True)\ndef point_in_quadrilateral(pt_x, pt_y, corners):\n    ab0 = corners[2] - corners[0]\n    ab1 = corners[3] - corners[1]\n\n    ad0 = corners[6] - corners[0]\n    ad1 = corners[7] - corners[1]\n\n    ap0 = pt_x - corners[0]\n    ap1 = pt_y - corners[1]\n\n    abab = ab0 * ab0 + ab1 * ab1\n    abap = ab0 * ap0 + ab1 * ap1\n    adad = ad0 * ad0 + ad1 * ad1\n    adap = ad0 * ap0 + ad1 * ap1\n\n    return abab >= abap and abap >= 0 and adad >= adap and adap >= 0\n\n\n@cuda.jit('(float32[:], float32[:], float32[:])', device=True, inline=True)\ndef quadrilateral_intersection(pts1, pts2, int_pts):\n    num_of_inter = 0\n    for i in range(4):\n        if point_in_quadrilateral(pts1[2 * i], pts1[2 * i + 1], pts2):\n            int_pts[num_of_inter * 2] = pts1[2 * i]\n            int_pts[num_of_inter * 2 + 1] = pts1[2 * i + 1]\n            num_of_inter += 1\n        if point_in_quadrilateral(pts2[2 * i], pts2[2 * i + 1], pts1):\n            int_pts[num_of_inter * 2] = pts2[2 * i]\n            int_pts[num_of_inter * 2 + 1] = pts2[2 * i + 1]\n            num_of_inter += 1\n    temp_pts = cuda.local.array((2, ), dtype=numba.float32)\n    for i in range(4):\n        for j in range(4):\n            has_pts = line_segment_intersection(pts1, pts2, i, j, temp_pts)\n            if has_pts:\n                int_pts[num_of_inter * 2] = temp_pts[0]\n                int_pts[num_of_inter * 2 + 1] = temp_pts[1]\n                num_of_inter += 1\n\n    return num_of_inter\n\n\n@cuda.jit('(float32[:], float32[:])', device=True, inline=True)\ndef rbbox_to_corners(corners, rbbox):\n    # generate clockwise corners and rotate it clockwise\n    angle = rbbox[4]\n    a_cos = math.cos(angle)\n    a_sin = math.sin(angle)\n    center_x = rbbox[0]\n    center_y = rbbox[1]\n    x_d = rbbox[2]\n    y_d = rbbox[3]\n    corners_x = cuda.local.array((4, ), dtype=numba.float32)\n    corners_y = cuda.local.array((4, ), dtype=numba.float32)\n    corners_x[0] = -x_d / 2\n    corners_x[1] = -x_d / 2\n    corners_x[2] = x_d / 2\n    corners_x[3] = x_d / 2\n    corners_y[0] = -y_d / 2\n    corners_y[1] = y_d / 2\n    corners_y[2] = y_d / 2\n    corners_y[3] = -y_d / 2\n    for i in range(4):\n        corners[2 * i] = a_cos * corners_x[i] + a_sin * corners_y[i] + center_x\n        corners[2 * i +\n                1] = -a_sin * corners_x[i] + a_cos * corners_y[i] + center_y\n\n\n@cuda.jit('(float32[:], float32[:])', device=True, inline=True)\ndef inter(rbbox1, rbbox2):\n    \"\"\"Compute intersection of two rotated boxes.\n\n    Args:\n        rbox1 (np.ndarray, shape=[5]): Rotated 2d box.\n        rbox2 (np.ndarray, shape=[5]): Rotated 2d box.\n\n    Returns:\n        float: Intersection of two rotated boxes.\n    \"\"\"\n    corners1 = cuda.local.array((8, ), dtype=numba.float32)\n    corners2 = cuda.local.array((8, ), dtype=numba.float32)\n    intersection_corners = cuda.local.array((16, ), dtype=numba.float32)\n\n    rbbox_to_corners(corners1, rbbox1)\n    rbbox_to_corners(corners2, rbbox2)\n\n    num_intersection = quadrilateral_intersection(corners1, corners2,\n                                                  intersection_corners)\n    sort_vertex_in_convex_polygon(intersection_corners, num_intersection)\n    # print(intersection_corners.reshape([-1, 2])[:num_intersection])\n\n    return area(intersection_corners, num_intersection)\n\n\n@cuda.jit('(float32[:], float32[:], int32)', device=True, inline=True)\ndef devRotateIoUEval(rbox1, rbox2, criterion=-1):\n    \"\"\"Compute rotated iou on device.\n\n    Args:\n        rbox1 (np.ndarray, shape=[5]): Rotated 2d box.\n        rbox2 (np.ndarray, shape=[5]): Rotated 2d box.\n        criterion (int, optional): Indicate different type of iou.\n            -1 indicate `area_inter / (area1 + area2 - area_inter)`,\n            0 indicate `area_inter / area1`,\n            1 indicate `area_inter / area2`.\n\n    Returns:\n        float: iou between two input boxes.\n    \"\"\"\n    area1 = rbox1[2] * rbox1[3]\n    area2 = rbox2[2] * rbox2[3]\n    area_inter = inter(rbox1, rbox2)\n    if criterion == -1:\n        return area_inter / (area1 + area2 - area_inter)\n    elif criterion == 0:\n        return area_inter / area1\n    elif criterion == 1:\n        return area_inter / area2\n    else:\n        return area_inter\n\n\n@cuda.jit(\n    '(int64, int64, float32[:], float32[:], float32[:], int32)',\n    fastmath=False)\ndef rotate_iou_kernel_eval(N,\n                           K,\n                           dev_boxes,\n                           dev_query_boxes,\n                           dev_iou,\n                           criterion=-1):\n    \"\"\"Kernel of computing rotated iou.\n\n    Args:\n        N (int): The number of boxes.\n        K (int): The number of query boxes.\n        dev_boxes (np.ndarray): Boxes on device.\n        dev_query_boxes (np.ndarray): Query boxes on device.\n        dev_iou (np.ndarray): Computed iou to return.\n        criterion (int, optional): Indicate different type of iou.\n            -1 indicate `area_inter / (area1 + area2 - area_inter)`,\n            0 indicate `area_inter / area1`,\n            1 indicate `area_inter / area2`.\n    \"\"\"\n    threadsPerBlock = 8 * 8\n    row_start = cuda.blockIdx.x\n    col_start = cuda.blockIdx.y\n    tx = cuda.threadIdx.x\n    row_size = min(N - row_start * threadsPerBlock, threadsPerBlock)\n    col_size = min(K - col_start * threadsPerBlock, threadsPerBlock)\n    block_boxes = cuda.shared.array(shape=(64 * 5, ), dtype=numba.float32)\n    block_qboxes = cuda.shared.array(shape=(64 * 5, ), dtype=numba.float32)\n\n    dev_query_box_idx = threadsPerBlock * col_start + tx\n    dev_box_idx = threadsPerBlock * row_start + tx\n    if (tx < col_size):\n        block_qboxes[tx * 5 + 0] = dev_query_boxes[dev_query_box_idx * 5 + 0]\n        block_qboxes[tx * 5 + 1] = dev_query_boxes[dev_query_box_idx * 5 + 1]\n        block_qboxes[tx * 5 + 2] = dev_query_boxes[dev_query_box_idx * 5 + 2]\n        block_qboxes[tx * 5 + 3] = dev_query_boxes[dev_query_box_idx * 5 + 3]\n        block_qboxes[tx * 5 + 4] = dev_query_boxes[dev_query_box_idx * 5 + 4]\n    if (tx < row_size):\n        block_boxes[tx * 5 + 0] = dev_boxes[dev_box_idx * 5 + 0]\n        block_boxes[tx * 5 + 1] = dev_boxes[dev_box_idx * 5 + 1]\n        block_boxes[tx * 5 + 2] = dev_boxes[dev_box_idx * 5 + 2]\n        block_boxes[tx * 5 + 3] = dev_boxes[dev_box_idx * 5 + 3]\n        block_boxes[tx * 5 + 4] = dev_boxes[dev_box_idx * 5 + 4]\n    cuda.syncthreads()\n    if tx < row_size:\n        for i in range(col_size):\n            offset = (\n                row_start * threadsPerBlock * K + col_start * threadsPerBlock +\n                tx * K + i)\n            dev_iou[offset] = devRotateIoUEval(block_qboxes[i * 5:i * 5 + 5],\n                                               block_boxes[tx * 5:tx * 5 + 5],\n                                               criterion)\n\n\ndef rotate_iou_gpu_eval(boxes, query_boxes, criterion=-1, device_id=0):\n    \"\"\"Rotated box iou running in gpu. 500x faster than cpu version (take 5ms\n    in one example with numba.cuda code). convert from [this project](\n    https://github.com/hongzhenwang/RRPN-revise/tree/master/lib/rotation).\n\n    Args:\n        boxes (torch.Tensor): rbboxes. format: centers, dims,\n            angles(clockwise when positive) with the shape of [N, 5].\n        query_boxes (float tensor: [K, 5]): rbboxes to compute iou with boxes.\n        device_id (int, optional): Defaults to 0. Device to use.\n        criterion (int, optional): Indicate different type of iou.\n            -1 indicate `area_inter / (area1 + area2 - area_inter)`,\n            0 indicate `area_inter / area1`,\n            1 indicate `area_inter / area2`.\n\n    Returns:\n        np.ndarray: IoU results.\n    \"\"\"\n    boxes = boxes.astype(np.float32)\n    query_boxes = query_boxes.astype(np.float32)\n    N = boxes.shape[0]\n    K = query_boxes.shape[0]\n    iou = np.zeros((N, K), dtype=np.float32)\n    if N == 0 or K == 0:\n        return iou\n    threadsPerBlock = 8 * 8\n    cuda.select_device(device_id)\n    blockspergrid = (div_up(N, threadsPerBlock), div_up(K, threadsPerBlock))\n\n    stream = cuda.stream()\n    with stream.auto_synchronize():\n        boxes_dev = cuda.to_device(boxes.reshape([-1]), stream)\n        query_boxes_dev = cuda.to_device(query_boxes.reshape([-1]), stream)\n        iou_dev = cuda.to_device(iou.reshape([-1]), stream)\n        rotate_iou_kernel_eval[blockspergrid, threadsPerBlock,\n                               stream](N, K, boxes_dev, query_boxes_dev,\n                                       iou_dev, criterion)\n        iou_dev.copy_to_host(iou.reshape([-1]), stream=stream)\n    return iou.astype(boxes.dtype)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/lyft_eval.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom lyft_dataset_sdk.eval.detection.mAP_evaluation import (Box3D, get_ap,\n                                                            get_class_names,\n                                                            get_ious,\n                                                            group_by_key,\n                                                            wrap_in_box)\nfrom mmcv.utils import print_log, track_iter_progress\nfrom mmcv.fileio.io import dump, load\nfrom os import path as osp\nfrom terminaltables import AsciiTable\n\n\n# def load_lyft_gts(lyft, data_root, eval_split, logger=None):\n#     \"\"\"Loads ground truth boxes from database.\n\n#     Args:\n#         lyft (:obj:`LyftDataset`): Lyft class in the sdk.\n#         data_root (str): Root of data for reading splits.\n#         eval_split (str): Name of the split for evaluation.\n#         logger (logging.Logger | str | None): Logger used for printing\n#         related information during evaluation. Default: None.\n\n#     Returns:\n#         list[dict]: List of annotation dictionaries.\n#     \"\"\"\n#     split_scenes = mmcv.list_from_file(\n#         osp.join(data_root, f'{eval_split}.txt'))\n\n#     # Read out all sample_tokens in DB.\n#     sample_tokens_all = [s['token'] for s in lyft.sample]\n#     assert len(sample_tokens_all) > 0, 'Error: Database has no samples!'\n\n#     if eval_split == 'test':\n#         # Check that you aren't trying to cheat :)\n#         assert len(lyft.sample_annotation) > 0, \\\n#             'Error: You are trying to evaluate on the test set \\\n#              but you do not have the annotations!'\n\n#     sample_tokens = []\n#     for sample_token in sample_tokens_all:\n#         scene_token = lyft.get('sample', sample_token)['scene_token']\n#         scene_record = lyft.get('scene', scene_token)\n#         if scene_record['name'] in split_scenes:\n#             sample_tokens.append(sample_token)\n\n#     all_annotations = []\n\n#     print_log('Loading ground truth annotations...', logger=logger)\n#     # Load annotations and filter predictions and annotations.\n#     for sample_token in track_iter_progress(sample_tokens):\n#         sample = lyft.get('sample', sample_token)\n#         sample_annotation_tokens = sample['anns']\n#         for sample_annotation_token in sample_annotation_tokens:\n#             # Get label name in detection task and filter unused labels.\n#             sample_annotation = \\\n#                 lyft.get('sample_annotation', sample_annotation_token)\n#             detection_name = sample_annotation['category_name']\n#             if detection_name is None:\n#                 continue\n#             annotation = {\n#                 'sample_token': sample_token,\n#                 'translation': sample_annotation['translation'],\n#                 'size': sample_annotation['size'],\n#                 'rotation': sample_annotation['rotation'],\n#                 'name': detection_name,\n#             }\n#             all_annotations.append(annotation)\n\n#     return all_annotations\n\n\ndef load_lyft_predictions(res_path):\n    \"\"\"Load Lyft predictions from json file.\n\n    Args:\n        res_path (str): Path of result json file recording detections.\n\n    Returns:\n        list[dict]: List of prediction dictionaries.\n    \"\"\"\n    predictions = load(res_path)\n    predictions = predictions['results']\n    all_preds = []\n    for sample_token in predictions.keys():\n        all_preds.extend(predictions[sample_token])\n    return all_preds\n\n\ndef lyft_eval(lyft, data_root, res_path, eval_set, output_dir, logger=None):\n    \"\"\"Evaluation API for Lyft dataset.\n\n    Args:\n        lyft (:obj:`LyftDataset`): Lyft class in the sdk.\n        data_root (str): Root of data for reading splits.\n        res_path (str): Path of result json file recording detections.\n        eval_set (str): Name of the split for evaluation.\n        output_dir (str): Output directory for output json files.\n        logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n\n    Returns:\n        dict[str, float]: The evaluation results.\n    \"\"\"\n    # evaluate by lyft metrics\n    gts = load_lyft_gts(lyft, data_root, eval_set, logger)\n    predictions = load_lyft_predictions(res_path)\n\n    class_names = get_class_names(gts)\n    print('Calculating mAP@0.5:0.95...')\n\n    iou_thresholds = [0.5, 0.55, 0.6, 0.65, 0.7, 0.75, 0.8, 0.85, 0.9, 0.95]\n    metrics = {}\n    average_precisions = \\\n        get_classwise_aps(gts, predictions, class_names, iou_thresholds)\n    APs_data = [['IOU', 0.5, 0.55, 0.6, 0.65, 0.7, 0.75, 0.8, 0.85, 0.9, 0.95]]\n\n    mAPs = np.mean(average_precisions, axis=0)\n    mAPs_cate = np.mean(average_precisions, axis=1)\n    final_mAP = np.mean(mAPs)\n\n    metrics['average_precisions'] = average_precisions.tolist()\n    metrics['mAPs'] = mAPs.tolist()\n    metrics['Final mAP'] = float(final_mAP)\n    metrics['class_names'] = class_names\n    metrics['mAPs_cate'] = mAPs_cate.tolist()\n\n    APs_data = [['class', 'mAP@0.5:0.95']]\n    for i in range(len(class_names)):\n        row = [class_names[i], round(mAPs_cate[i], 3)]\n        APs_data.append(row)\n    APs_data.append(['Overall', round(final_mAP, 3)])\n    APs_table = AsciiTable(APs_data, title='mAPs@0.5:0.95')\n    APs_table.inner_footing_row_border = True\n    print_log(APs_table.table, logger=logger)\n\n    res_path = osp.join(output_dir, 'lyft_metrics.json')\n    dump(metrics, res_path)\n    return metrics\n\n\ndef get_classwise_aps(gt, predictions, class_names, iou_thresholds):\n    \"\"\"Returns an array with an average precision per class.\n\n    Note: Ground truth and predictions should have the following format.\n\n    .. code-block::\n\n    gt = [{\n        'sample_token': '0f0e3ce89d2324d8b45aa55a7b4f8207\n                         fbb039a550991a5149214f98cec136ac',\n        'translation': [974.2811881299899, 1714.6815014457964,\n                        -23.689857123368846],\n        'size': [1.796, 4.488, 1.664],\n        'rotation': [0.14882026466054782, 0, 0, 0.9888642620837121],\n        'name': 'car'\n    }]\n\n    predictions = [{\n        'sample_token': '0f0e3ce89d2324d8b45aa55a7b4f8207\n                         fbb039a550991a5149214f98cec136ac',\n        'translation': [971.8343488872263, 1713.6816097857359,\n                        -25.82534357061308],\n        'size': [2.519726579986132, 7.810161372666739, 3.483438286096803],\n        'rotation': [0.10913582721095375, 0.04099572636992043,\n                     0.01927712319721745, 1.029328402625659],\n        'name': 'car',\n        'score': 0.3077029437237213\n    }]\n\n    Args:\n        gt (list[dict]): list of dictionaries in the format described below.\n        predictions (list[dict]): list of dictionaries in the format\n            described below.\n        class_names (list[str]): list of the class names.\n        iou_thresholds (list[float]): IOU thresholds used to calculate\n            TP / FN\n\n    Returns:\n        np.ndarray: an array with an average precision per class.\n    \"\"\"\n    assert all([0 <= iou_th <= 1 for iou_th in iou_thresholds])\n\n    gt_by_class_name = group_by_key(gt, 'name')\n    pred_by_class_name = group_by_key(predictions, 'name')\n\n    average_precisions = np.zeros((len(class_names), len(iou_thresholds)))\n\n    for class_id, class_name in enumerate(class_names):\n        if class_name in pred_by_class_name:\n            recalls, precisions, average_precision = get_single_class_aps(\n                gt_by_class_name[class_name], pred_by_class_name[class_name],\n                iou_thresholds)\n            average_precisions[class_id, :] = average_precision\n\n    return average_precisions\n\n\ndef get_single_class_aps(gt, predictions, iou_thresholds):\n    \"\"\"Compute recall and precision for all iou thresholds. Adapted from\n    LyftDatasetDevkit.\n\n    Args:\n        gt (list[dict]): list of dictionaries in the format described above.\n        predictions (list[dict]): list of dictionaries in the format \\\n            described below.\n        iou_thresholds (list[float]): IOU thresholds used to calculate \\\n            TP / FN\n\n    Returns:\n        tuple[np.ndarray]: Returns (recalls, precisions, average precisions)\n            for each class.\n    \"\"\"\n    num_gts = len(gt)\n    image_gts = group_by_key(gt, 'sample_token')\n    image_gts = wrap_in_box(image_gts)\n\n    sample_gt_checked = {\n        sample_token: np.zeros((len(boxes), len(iou_thresholds)))\n        for sample_token, boxes in image_gts.items()\n    }\n\n    predictions = sorted(predictions, key=lambda x: x['score'], reverse=True)\n\n    # go down dets and mark TPs and FPs\n    num_predictions = len(predictions)\n    tps = np.zeros((num_predictions, len(iou_thresholds)))\n    fps = np.zeros((num_predictions, len(iou_thresholds)))\n\n    for prediction_index, prediction in enumerate(predictions):\n        predicted_box = Box3D(**prediction)\n\n        sample_token = prediction['sample_token']\n\n        max_overlap = -np.inf\n        jmax = -1\n\n        if sample_token in image_gts:\n            gt_boxes = image_gts[sample_token]\n            # gt_boxes per sample\n            gt_checked = sample_gt_checked[sample_token]\n            # gt flags per sample\n        else:\n            gt_boxes = []\n            gt_checked = None\n\n        if len(gt_boxes) > 0:\n            overlaps = get_ious(gt_boxes, predicted_box)\n\n            max_overlap = np.max(overlaps)\n\n            jmax = np.argmax(overlaps)\n\n        for i, iou_threshold in enumerate(iou_thresholds):\n            if max_overlap > iou_threshold:\n                if gt_checked[jmax, i] == 0:\n                    tps[prediction_index, i] = 1.0\n                    gt_checked[jmax, i] = 1\n                else:\n                    fps[prediction_index, i] = 1.0\n            else:\n                fps[prediction_index, i] = 1.0\n\n    # compute precision recall\n    fps = np.cumsum(fps, axis=0)\n    tps = np.cumsum(tps, axis=0)\n\n    recalls = tps / float(num_gts)\n    # avoid divide by zero in case the first detection\n    # matches a difficult ground truth\n    precisions = tps / np.maximum(tps + fps, np.finfo(np.float64).eps)\n\n    aps = []\n    for i in range(len(iou_thresholds)):\n        recall = recalls[:, i]\n        precision = precisions[:, i]\n        assert np.all(0 <= recall) & np.all(recall <= 1)\n        assert np.all(0 <= precision) & np.all(precision <= 1)\n        ap = get_ap(recall, precision)\n        aps.append(ap)\n\n    aps = np.array(aps)\n\n    return recalls, precisions, aps\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/mean_ap.py",
    "content": "from multiprocessing import Pool\nimport numpy as np\nfrom mmcv.utils import print_log, is_str\nfrom terminaltables import AsciiTable\n\nfrom .bbox_overlaps import bbox_overlaps\nfrom .class_names import get_classes\n\n\ndef average_precision(recalls, precisions, mode='area'):\n    \"\"\"Calculate average precision (for single or multiple scales).\n\n    Args:\n        recalls (ndarray): shape (num_scales, num_dets) or (num_dets, )\n        precisions (ndarray): shape (num_scales, num_dets) or (num_dets, )\n        mode (str): 'area' or '11points', 'area' means calculating the area\n            under precision-recall curve, '11points' means calculating\n            the average precision of recalls at [0, 0.1, ..., 1]\n\n    Returns:\n        float or ndarray: calculated average precision\n    \"\"\"\n    no_scale = False\n    if recalls.ndim == 1:\n        no_scale = True\n        recalls = recalls[np.newaxis, :]\n        precisions = precisions[np.newaxis, :]\n    assert recalls.shape == precisions.shape and recalls.ndim == 2\n    num_scales = recalls.shape[0]\n    ap = np.zeros(num_scales, dtype=np.float32)\n    if mode == 'area':\n        zeros = np.zeros((num_scales, 1), dtype=recalls.dtype)\n        ones = np.ones((num_scales, 1), dtype=recalls.dtype)\n        mrec = np.hstack((zeros, recalls, ones))\n        mpre = np.hstack((zeros, precisions, zeros))\n        for i in range(mpre.shape[1] - 1, 0, -1):\n            mpre[:, i - 1] = np.maximum(mpre[:, i - 1], mpre[:, i])\n        for i in range(num_scales):\n            ind = np.where(mrec[i, 1:] != mrec[i, :-1])[0]\n            ap[i] = np.sum(\n                (mrec[i, ind + 1] - mrec[i, ind]) * mpre[i, ind + 1])\n    elif mode == '11points':\n        for i in range(num_scales):\n            for thr in np.arange(0, 1 + 1e-3, 0.1):\n                precs = precisions[i, recalls[i, :] >= thr]\n                prec = precs.max() if precs.size > 0 else 0\n                ap[i] += prec\n        ap /= 11\n    else:\n        raise ValueError(\n            'Unrecognized mode, only \"area\" and \"11points\" are supported')\n    if no_scale:\n        ap = ap[0]\n    return ap\n\n\ndef tpfp_imagenet(det_bboxes,\n                  gt_bboxes,\n                  gt_bboxes_ignore=None,\n                  default_iou_thr=0.5,\n                  area_ranges=None):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        default_iou_thr (float): IoU threshold to be considered as matched for\n            medium and large bboxes (small ones have special rules).\n            Default: 0.5.\n        area_ranges (list[tuple] | None): Range of bbox areas to be evaluated,\n            in the format [(min1, max1), (min2, max2), ...]. Default: None.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n            each array is (num_scales, m).\n    \"\"\"\n    # an indicator of ignored gts\n    gt_ignore_inds = np.concatenate(\n        (np.zeros(gt_bboxes.shape[0], dtype=np.bool),\n         np.ones(gt_bboxes_ignore.shape[0], dtype=np.bool)))\n    # stack gt_bboxes and gt_bboxes_ignore for convenience\n    gt_bboxes = np.vstack((gt_bboxes, gt_bboxes_ignore))\n\n    num_dets = det_bboxes.shape[0]\n    num_gts = gt_bboxes.shape[0]\n    if area_ranges is None:\n        area_ranges = [(None, None)]\n    num_scales = len(area_ranges)\n    # tp and fp are of shape (num_scales, num_gts), each row is tp or fp\n    # of a certain scale.\n    tp = np.zeros((num_scales, num_dets), dtype=np.float32)\n    fp = np.zeros((num_scales, num_dets), dtype=np.float32)\n    if gt_bboxes.shape[0] == 0:\n        if area_ranges == [(None, None)]:\n            fp[...] = 1\n        else:\n            det_areas = (det_bboxes[:, 2] - det_bboxes[:, 0]) * (\n                det_bboxes[:, 3] - det_bboxes[:, 1])\n            for i, (min_area, max_area) in enumerate(area_ranges):\n                fp[i, (det_areas >= min_area) & (det_areas < max_area)] = 1\n        return tp, fp\n    ious = bbox_overlaps(det_bboxes, gt_bboxes - 1)\n    gt_w = gt_bboxes[:, 2] - gt_bboxes[:, 0]\n    gt_h = gt_bboxes[:, 3] - gt_bboxes[:, 1]\n    iou_thrs = np.minimum((gt_w * gt_h) / ((gt_w + 10.0) * (gt_h + 10.0)),\n                          default_iou_thr)\n    # sort all detections by scores in descending order\n    sort_inds = np.argsort(-det_bboxes[:, -1])\n    for k, (min_area, max_area) in enumerate(area_ranges):\n        gt_covered = np.zeros(num_gts, dtype=bool)\n        # if no area range is specified, gt_area_ignore is all False\n        if min_area is None:\n            gt_area_ignore = np.zeros_like(gt_ignore_inds, dtype=bool)\n        else:\n            gt_areas = gt_w * gt_h\n            gt_area_ignore = (gt_areas < min_area) | (gt_areas >= max_area)\n        for i in sort_inds:\n            max_iou = -1\n            matched_gt = -1\n            # find best overlapped available gt\n            for j in range(num_gts):\n                # different from PASCAL VOC: allow finding other gts if the\n                # best overlapped ones are already matched by other det bboxes\n                if gt_covered[j]:\n                    continue\n                elif ious[i, j] >= iou_thrs[j] and ious[i, j] > max_iou:\n                    max_iou = ious[i, j]\n                    matched_gt = j\n            # there are 4 cases for a det bbox:\n            # 1. it matches a gt, tp = 1, fp = 0\n            # 2. it matches an ignored gt, tp = 0, fp = 0\n            # 3. it matches no gt and within area range, tp = 0, fp = 1\n            # 4. it matches no gt but is beyond area range, tp = 0, fp = 0\n            if matched_gt >= 0:\n                gt_covered[matched_gt] = 1\n                if not (gt_ignore_inds[matched_gt]\n                        or gt_area_ignore[matched_gt]):\n                    tp[k, i] = 1\n            elif min_area is None:\n                fp[k, i] = 1\n            else:\n                bbox = det_bboxes[i, :4]\n                area = (bbox[2] - bbox[0]) * (bbox[3] - bbox[1])\n                if area >= min_area and area < max_area:\n                    fp[k, i] = 1\n    return tp, fp\n\n\ndef tpfp_default(det_bboxes,\n                 gt_bboxes,\n                 gt_bboxes_ignore=None,\n                 iou_thr=0.5,\n                 area_ranges=None):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        area_ranges (list[tuple] | None): Range of bbox areas to be evaluated,\n            in the format [(min1, max1), (min2, max2), ...]. Default: None.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n            each array is (num_scales, m).\n    \"\"\"\n    # an indicator of ignored gts\n    gt_ignore_inds = np.concatenate(\n        (np.zeros(gt_bboxes.shape[0], dtype=np.bool),\n         np.ones(gt_bboxes_ignore.shape[0], dtype=np.bool)))\n    # stack gt_bboxes and gt_bboxes_ignore for convenience\n    gt_bboxes = np.vstack((gt_bboxes, gt_bboxes_ignore))\n\n    num_dets = det_bboxes.shape[0]\n    num_gts = gt_bboxes.shape[0]\n    if area_ranges is None:\n        area_ranges = [(None, None)]\n    num_scales = len(area_ranges)\n    # tp and fp are of shape (num_scales, num_gts), each row is tp or fp of\n    # a certain scale\n    tp = np.zeros((num_scales, num_dets), dtype=np.float32)\n    fp = np.zeros((num_scales, num_dets), dtype=np.float32)\n\n    # if there is no gt bboxes in this image, then all det bboxes\n    # within area range are false positives\n    if gt_bboxes.shape[0] == 0:\n        if area_ranges == [(None, None)]:\n            fp[...] = 1\n        else:\n            det_areas = (det_bboxes[:, 2] - det_bboxes[:, 0]) * (\n                det_bboxes[:, 3] - det_bboxes[:, 1])\n            for i, (min_area, max_area) in enumerate(area_ranges):\n                fp[i, (det_areas >= min_area) & (det_areas < max_area)] = 1\n        return tp, fp\n\n    ious = bbox_overlaps(det_bboxes, gt_bboxes)\n    # for each det, the max iou with all gts\n    ious_max = ious.max(axis=1)\n    # for each det, which gt overlaps most with it\n    ious_argmax = ious.argmax(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-det_bboxes[:, -1])\n    for k, (min_area, max_area) in enumerate(area_ranges):\n        gt_covered = np.zeros(num_gts, dtype=bool)\n        # if no area range is specified, gt_area_ignore is all False\n        if min_area is None:\n            gt_area_ignore = np.zeros_like(gt_ignore_inds, dtype=bool)\n        else:\n            gt_areas = (gt_bboxes[:, 2] - gt_bboxes[:, 0]) * (\n                gt_bboxes[:, 3] - gt_bboxes[:, 1])\n            gt_area_ignore = (gt_areas < min_area) | (gt_areas >= max_area)\n        for i in sort_inds:\n            if ious_max[i] >= iou_thr:\n                matched_gt = ious_argmax[i]\n                if not (gt_ignore_inds[matched_gt]\n                        or gt_area_ignore[matched_gt]):\n                    if not gt_covered[matched_gt]:\n                        gt_covered[matched_gt] = True\n                        tp[k, i] = 1\n                    else:\n                        fp[k, i] = 1\n                # otherwise ignore this detected bbox, tp = 0, fp = 0\n            elif min_area is None:\n                fp[k, i] = 1\n            else:\n                bbox = det_bboxes[i, :4]\n                area = (bbox[2] - bbox[0]) * (bbox[3] - bbox[1])\n                if area >= min_area and area < max_area:\n                    fp[k, i] = 1\n    return tp, fp\n\n\ndef get_cls_results(det_results, annotations, class_id):\n    \"\"\"Get det results and gt information of a certain class.\n\n    Args:\n        det_results (list[list]): Same as `eval_map()`.\n        annotations (list[dict]): Same as `eval_map()`.\n        class_id (int): ID of a specific class.\n\n    Returns:\n        tuple[list[np.ndarray]]: detected bboxes, gt bboxes, ignored gt bboxes\n    \"\"\"\n    cls_dets = [img_res[class_id] for img_res in det_results]\n    cls_gts = []\n    cls_gts_ignore = []\n    for ann in annotations:\n        gt_inds = ann['labels'] == class_id\n        cls_gts.append(ann['bboxes'][gt_inds, :])\n\n        if ann.get('labels_ignore', None) is not None:\n            ignore_inds = ann['labels_ignore'] == class_id\n            cls_gts_ignore.append(ann['bboxes_ignore'][ignore_inds, :])\n        else:\n            cls_gts_ignore.append(np.empty((0, 4), dtype=np.float32))\n\n    return cls_dets, cls_gts, cls_gts_ignore\n\n\ndef eval_map(det_results,\n             annotations,\n             scale_ranges=None,\n             iou_thr=0.5,\n             dataset=None,\n             logger=None,\n             tpfp_fn=None,\n             nproc=4):\n    \"\"\"Evaluate mAP of a dataset.\n\n    Args:\n        det_results (list[list]): [[cls1_det, cls2_det, ...], ...].\n            The outer list indicates images, and the inner list indicates\n            per-class detected bboxes.\n        annotations (list[dict]): Ground truth annotations where each item of\n            the list indicates an image. Keys of annotations are:\n\n            - `bboxes`: numpy array of shape (n, 4)\n            - `labels`: numpy array of shape (n, )\n            - `bboxes_ignore` (optional): numpy array of shape (k, 4)\n            - `labels_ignore` (optional): numpy array of shape (k, )\n        scale_ranges (list[tuple] | None): Range of scales to be evaluated,\n            in the format [(min1, max1), (min2, max2), ...]. A range of\n            (32, 64) means the area range between (32**2, 64**2).\n            Default: None.\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        dataset (list[str] | str | None): Dataset name or dataset classes,\n            there are minor differences in metrics for different datsets, e.g.\n            \"voc07\", \"imagenet_det\", etc. Default: None.\n        logger (logging.Logger | str | None): The way to print the mAP\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n        tpfp_fn (callable | None): The function used to determine true/\n            false positives. If None, :func:`tpfp_default` is used as default\n            unless dataset is 'det' or 'vid' (:func:`tpfp_imagenet` in this\n            case). If it is given as a function, then this function is used\n            to evaluate tp & fp. Default None.\n        nproc (int): Processes used for computing TP and FP.\n            Default: 4.\n\n    Returns:\n        tuple: (mAP, [dict, dict, ...])\n    \"\"\"\n    assert len(det_results) == len(annotations)\n\n    num_imgs = len(det_results)\n    num_scales = len(scale_ranges) if scale_ranges is not None else 1\n    num_classes = len(det_results[0])  # positive class num\n    area_ranges = ([(rg[0]**2, rg[1]**2) for rg in scale_ranges]\n                   if scale_ranges is not None else None)\n\n    pool = Pool(nproc)\n    eval_results = []\n    for i in range(num_classes):\n        # get gt and det bboxes of this class\n        cls_dets, cls_gts, cls_gts_ignore = get_cls_results(\n            det_results, annotations, i)\n        # choose proper function according to datasets to compute tp and fp\n        if tpfp_fn is None:\n            if dataset in ['det', 'vid']:\n                tpfp_fn = tpfp_imagenet\n            else:\n                tpfp_fn = tpfp_default\n        if not callable(tpfp_fn):\n            raise ValueError(\n                f'tpfp_fn has to be a function or None, but got {tpfp_fn}')\n\n        # compute tp and fp for each image with multiple processes\n        tpfp = pool.starmap(\n            tpfp_fn,\n            zip(cls_dets, cls_gts, cls_gts_ignore,\n                [iou_thr for _ in range(num_imgs)],\n                [area_ranges for _ in range(num_imgs)]))\n        tp, fp = tuple(zip(*tpfp))\n        # calculate gt number of each scale\n        # ignored gts or gts beyond the specific scale are not counted\n        num_gts = np.zeros(num_scales, dtype=int)\n        for j, bbox in enumerate(cls_gts):\n            if area_ranges is None:\n                num_gts[0] += bbox.shape[0]\n            else:\n                gt_areas = (bbox[:, 2] - bbox[:, 0]) * (\n                    bbox[:, 3] - bbox[:, 1])\n                for k, (min_area, max_area) in enumerate(area_ranges):\n                    num_gts[k] += np.sum((gt_areas >= min_area)\n                                         & (gt_areas < max_area))\n        # sort all det bboxes by score, also sort tp and fp\n        cls_dets = np.vstack(cls_dets)\n        num_dets = cls_dets.shape[0]\n        sort_inds = np.argsort(-cls_dets[:, -1])\n        tp = np.hstack(tp)[:, sort_inds]\n        fp = np.hstack(fp)[:, sort_inds]\n        # calculate recall and precision with tp and fp\n        tp = np.cumsum(tp, axis=1)\n        fp = np.cumsum(fp, axis=1)\n        eps = np.finfo(np.float32).eps\n        recalls = tp / np.maximum(num_gts[:, np.newaxis], eps)\n        precisions = tp / np.maximum((tp + fp), eps)\n        # calculate AP\n        if scale_ranges is None:\n            recalls = recalls[0, :]\n            precisions = precisions[0, :]\n            num_gts = num_gts.item()\n        mode = 'area' if dataset != 'voc07' else '11points'\n        ap = average_precision(recalls, precisions, mode)\n        eval_results.append({\n            'num_gts': num_gts,\n            'num_dets': num_dets,\n            'recall': recalls,\n            'precision': precisions,\n            'ap': ap\n        })\n    pool.close()\n    if scale_ranges is not None:\n        # shape (num_classes, num_scales)\n        all_ap = np.vstack([cls_result['ap'] for cls_result in eval_results])\n        all_num_gts = np.vstack(\n            [cls_result['num_gts'] for cls_result in eval_results])\n        mean_ap = []\n        for i in range(num_scales):\n            if np.any(all_num_gts[:, i] > 0):\n                mean_ap.append(all_ap[all_num_gts[:, i] > 0, i].mean())\n            else:\n                mean_ap.append(0.0)\n    else:\n        aps = []\n        for cls_result in eval_results:\n            if cls_result['num_gts'] > 0:\n                aps.append(cls_result['ap'])\n        mean_ap = np.array(aps).mean().item() if aps else 0.0\n\n    print_map_summary(\n        mean_ap, eval_results, dataset, area_ranges, logger=logger)\n\n    return mean_ap, eval_results\n\n\ndef print_map_summary(mean_ap,\n                      results,\n                      dataset=None,\n                      scale_ranges=None,\n                      logger=None):\n    \"\"\"Print mAP and results of each class.\n\n    A table will be printed to show the gts/dets/recall/AP of each class and\n    the mAP.\n\n    Args:\n        mean_ap (float): Calculated from `eval_map()`.\n        results (list[dict]): Calculated from `eval_map()`.\n        dataset (list[str] | str | None): Dataset name or dataset classes.\n        scale_ranges (list[tuple] | None): Range of scales to be evaluated.\n        logger (logging.Logger | str | None): The way to print the mAP\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n    \"\"\"\n\n    if logger == 'silent':\n        return\n\n    if isinstance(results[0]['ap'], np.ndarray):\n        num_scales = len(results[0]['ap'])\n    else:\n        num_scales = 1\n\n    if scale_ranges is not None:\n        assert len(scale_ranges) == num_scales\n\n    num_classes = len(results)\n\n    recalls = np.zeros((num_scales, num_classes), dtype=np.float32)\n    aps = np.zeros((num_scales, num_classes), dtype=np.float32)\n    num_gts = np.zeros((num_scales, num_classes), dtype=int)\n    for i, cls_result in enumerate(results):\n        if cls_result['recall'].size > 0:\n            recalls[:, i] = np.array(cls_result['recall'], ndmin=2)[:, -1]\n        aps[:, i] = cls_result['ap']\n        num_gts[:, i] = cls_result['num_gts']\n\n    if dataset is None:\n        label_names = [str(i) for i in range(num_classes)]\n    elif is_str(dataset):\n        label_names = get_classes(dataset)\n    else:\n        label_names = dataset\n\n    if not isinstance(mean_ap, list):\n        mean_ap = [mean_ap]\n\n    header = ['class', 'gts', 'dets', 'recall', 'ap']\n    for i in range(num_scales):\n        if scale_ranges is not None:\n            print_log(f'Scale range {scale_ranges[i]}', logger=logger)\n        table_data = [header]\n        for j in range(num_classes):\n            row_data = [\n                label_names[j], num_gts[i, j], results[j]['num_dets'],\n                f'{recalls[i, j]:.3f}', f'{aps[i, j]:.3f}'\n            ]\n            table_data.append(row_data)\n        table_data.append(['mAP', '', '', '', f'{mean_ap[i]:.3f}'])\n        table = AsciiTable(table_data)\n        table.inner_footing_row_border = True\n        print_log('\\n' + table.table, logger=logger)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/metric_motion.py",
    "content": "# <Copyright 2019, Argo AI, LLC. Released under the MIT license.>\n\n\"\"\"This module evaluates the forecasted trajectories against the ground truth.\"\"\"\n\nimport math\nfrom typing import Dict, List, Optional\n\nimport numpy as np\nimport torch\n\nLOW_PROB_THRESHOLD_FOR_METRICS = 0.05\n\n\ndef get_ade(forecasted_trajectory: torch.Tensor, gt_trajectory: torch.Tensor) -> float:\n    \"\"\"Compute Average Displacement Error.\n    Args:\n        forecasted_trajectory: Predicted trajectory with shape [fut_ts, 2]\n        gt_trajectory: Ground truth trajectory with shape [fut_ts, 2]\n    Returns:\n        ade: Average Displacement Error\n    \"\"\"\n    pred_len = forecasted_trajectory.shape[0]\n    ade = float(\n        sum(\n            torch.sqrt(\n                (forecasted_trajectory[i, 0] - gt_trajectory[i, 0]) ** 2\n                + (forecasted_trajectory[i, 1] - gt_trajectory[i, 1]) ** 2\n            )\n            for i in range(pred_len)\n        )\n        / pred_len\n    )\n    return ade\n\ndef get_best_preds(\n    forecasted_trajectory: torch.Tensor,\n    gt_trajectory: torch.Tensor\n) -> float:\n    \"\"\"Compute min Average Displacement Error.\n    Args:\n        forecasted_trajectory: Predicted trajectory with shape [k, fut_ts, 2]\n        gt_trajectory: Ground truth trajectory with shape [fut_ts, 2]\n        gt_fut_masks: Ground truth traj mask with shape (fut_ts)\n    Returns:\n        best_forecasted_trajectory: Predicted trajectory with shape [fut_ts, 2]\n    \"\"\"\n\n    # [k, fut_ts]\n    dist = torch.linalg.norm(gt_trajectory[None] - forecasted_trajectory, dim=-1)\n    dist = dist[..., -1]\n    dist[torch.isnan(dist)] = 0\n    min_mode_idx = torch.argmin(dist, dim=-1)\n\n    return forecasted_trajectory[min_mode_idx]\n\ndef get_fde(forecasted_trajectory: torch.Tensor, gt_trajectory: torch.Tensor) -> float:\n    \"\"\"Compute Final Displacement Error.\n    Args:\n        forecasted_trajectory: Predicted trajectory with shape [fut_ts, 2]\n        gt_trajectory: Ground truth trajectory with shape [fut_ts, 2]\n    Returns:\n        fde: Final Displacement Error\n    \"\"\"\n    fde = float(\n        torch.sqrt(\n            (forecasted_trajectory[-1, 0] - gt_trajectory[-1, 0]) ** 2\n            + (forecasted_trajectory[-1, 1] - gt_trajectory[-1, 1]) ** 2\n        )\n    )\n    return fde\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/metrics.py",
    "content": "from collections import OrderedDict\nfrom mmcv.image import imread\nimport numpy as np\nimport torch\n\n\ndef f_score(precision, recall, beta=1):\n    \"\"\"calcuate the f-score value.\n\n    Args:\n        precision (float | torch.Tensor): The precision value.\n        recall (float | torch.Tensor): The recall value.\n        beta (int): Determines the weight of recall in the combined score.\n            Default: False.\n\n    Returns:\n        [torch.tensor]: The f-score value.\n    \"\"\"\n    score = (1 + beta**2) * (precision * recall) / (\n        (beta**2 * precision) + recall)\n    return score\n\n\ndef intersect_and_union(pred_label,\n                        label,\n                        num_classes,\n                        ignore_index,\n                        label_map=dict(),\n                        reduce_zero_label=False):\n    \"\"\"Calculate intersection and Union.\n\n    Args:\n        pred_label (ndarray | str): Prediction segmentation map\n            or predict result filename.\n        label (ndarray | str): Ground truth segmentation map\n            or label filename.\n        num_classes (int): Number of categories.\n        ignore_index (int): Index that will be ignored in evaluation.\n        label_map (dict): Mapping old labels to new labels. The parameter will\n            work only when label is str. Default: dict().\n        reduce_zero_label (bool): Wether ignore zero label. The parameter will\n            work only when label is str. Default: False.\n\n     Returns:\n         torch.Tensor: The intersection of prediction and ground truth\n            histogram on all classes.\n         torch.Tensor: The union of prediction and ground truth histogram on\n            all classes.\n         torch.Tensor: The prediction histogram on all classes.\n         torch.Tensor: The ground truth histogram on all classes.\n    \"\"\"\n\n    if isinstance(pred_label, str):\n        pred_label = torch.from_numpy(np.load(pred_label))\n    else:\n        pred_label = torch.from_numpy((pred_label))\n\n    if isinstance(label, str):\n        label = torch.from_numpy(\n            imread(label, flag='unchanged', backend='pillow'))\n    else:\n        label = torch.from_numpy(label)\n\n    if label_map is not None:\n        for old_id, new_id in label_map.items():\n            label[label == old_id] = new_id\n    if reduce_zero_label:\n        label[label == 0] = 255\n        label = label - 1\n        label[label == 254] = 255\n\n    mask = (label != ignore_index)\n    pred_label = pred_label[mask]\n    label = label[mask]\n\n    intersect = pred_label[pred_label == label]\n    area_intersect = torch.histc(\n        intersect.float(), bins=(num_classes), min=0, max=num_classes - 1)\n    area_pred_label = torch.histc(\n        pred_label.float(), bins=(num_classes), min=0, max=num_classes - 1)\n    area_label = torch.histc(\n        label.float(), bins=(num_classes), min=0, max=num_classes - 1)\n    area_union = area_pred_label + area_label - area_intersect\n    return area_intersect, area_union, area_pred_label, area_label\n\n\ndef total_intersect_and_union(results,\n                              gt_seg_maps,\n                              num_classes,\n                              ignore_index,\n                              label_map=dict(),\n                              reduce_zero_label=False):\n    \"\"\"Calculate Total Intersection and Union.\n\n    Args:\n        results (list[ndarray] | list[str]): List of prediction segmentation\n            maps or list of prediction result filenames.\n        gt_seg_maps (list[ndarray] | list[str]): list of ground truth\n            segmentation maps or list of label filenames.\n        num_classes (int): Number of categories.\n        ignore_index (int): Index that will be ignored in evaluation.\n        label_map (dict): Mapping old labels to new labels. Default: dict().\n        reduce_zero_label (bool): Wether ignore zero label. Default: False.\n\n     Returns:\n         ndarray: The intersection of prediction and ground truth histogram\n             on all classes.\n         ndarray: The union of prediction and ground truth histogram on all\n             classes.\n         ndarray: The prediction histogram on all classes.\n         ndarray: The ground truth histogram on all classes.\n    \"\"\"\n    num_imgs = len(results)\n    assert len(gt_seg_maps) == num_imgs\n    total_area_intersect = torch.zeros((num_classes, ), dtype=torch.float64)\n    total_area_union = torch.zeros((num_classes, ), dtype=torch.float64)\n    total_area_pred_label = torch.zeros((num_classes, ), dtype=torch.float64)\n    total_area_label = torch.zeros((num_classes, ), dtype=torch.float64)\n    for i in range(num_imgs):\n        area_intersect, area_union, area_pred_label, area_label = \\\n            intersect_and_union(\n                results[i], gt_seg_maps[i], num_classes, ignore_index,\n                label_map, reduce_zero_label)\n        total_area_intersect += area_intersect\n        total_area_union += area_union\n        total_area_pred_label += area_pred_label\n        total_area_label += area_label\n    return total_area_intersect, total_area_union, total_area_pred_label, \\\n        total_area_label\n\n\ndef mean_iou(results,\n             gt_seg_maps,\n             num_classes,\n             ignore_index,\n             nan_to_num=None,\n             label_map=dict(),\n             reduce_zero_label=False):\n    \"\"\"Calculate Mean Intersection and Union (mIoU)\n\n    Args:\n        results (list[ndarray] | list[str]): List of prediction segmentation\n            maps or list of prediction result filenames.\n        gt_seg_maps (list[ndarray] | list[str]): list of ground truth\n            segmentation maps or list of label filenames.\n        num_classes (int): Number of categories.\n        ignore_index (int): Index that will be ignored in evaluation.\n        nan_to_num (int, optional): If specified, NaN values will be replaced\n            by the numbers defined by the user. Default: None.\n        label_map (dict): Mapping old labels to new labels. Default: dict().\n        reduce_zero_label (bool): Wether ignore zero label. Default: False.\n\n     Returns:\n        dict[str, float | ndarray]:\n            <aAcc> float: Overall accuracy on all images.\n            <Acc> ndarray: Per category accuracy, shape (num_classes, ).\n            <IoU> ndarray: Per category IoU, shape (num_classes, ).\n    \"\"\"\n    iou_result = eval_metrics(\n        results=results,\n        gt_seg_maps=gt_seg_maps,\n        num_classes=num_classes,\n        ignore_index=ignore_index,\n        metrics=['mIoU'],\n        nan_to_num=nan_to_num,\n        label_map=label_map,\n        reduce_zero_label=reduce_zero_label)\n    return iou_result\n\n\ndef mean_dice(results,\n              gt_seg_maps,\n              num_classes,\n              ignore_index,\n              nan_to_num=None,\n              label_map=dict(),\n              reduce_zero_label=False):\n    \"\"\"Calculate Mean Dice (mDice)\n\n    Args:\n        results (list[ndarray] | list[str]): List of prediction segmentation\n            maps or list of prediction result filenames.\n        gt_seg_maps (list[ndarray] | list[str]): list of ground truth\n            segmentation maps or list of label filenames.\n        num_classes (int): Number of categories.\n        ignore_index (int): Index that will be ignored in evaluation.\n        nan_to_num (int, optional): If specified, NaN values will be replaced\n            by the numbers defined by the user. Default: None.\n        label_map (dict): Mapping old labels to new labels. Default: dict().\n        reduce_zero_label (bool): Wether ignore zero label. Default: False.\n\n     Returns:\n        dict[str, float | ndarray]: Default metrics.\n            <aAcc> float: Overall accuracy on all images.\n            <Acc> ndarray: Per category accuracy, shape (num_classes, ).\n            <Dice> ndarray: Per category dice, shape (num_classes, ).\n    \"\"\"\n\n    dice_result = eval_metrics(\n        results=results,\n        gt_seg_maps=gt_seg_maps,\n        num_classes=num_classes,\n        ignore_index=ignore_index,\n        metrics=['mDice'],\n        nan_to_num=nan_to_num,\n        label_map=label_map,\n        reduce_zero_label=reduce_zero_label)\n    return dice_result\n\n\ndef mean_fscore(results,\n                gt_seg_maps,\n                num_classes,\n                ignore_index,\n                nan_to_num=None,\n                label_map=dict(),\n                reduce_zero_label=False,\n                beta=1):\n    \"\"\"Calculate Mean Intersection and Union (mIoU)\n\n    Args:\n        results (list[ndarray] | list[str]): List of prediction segmentation\n            maps or list of prediction result filenames.\n        gt_seg_maps (list[ndarray] | list[str]): list of ground truth\n            segmentation maps or list of label filenames.\n        num_classes (int): Number of categories.\n        ignore_index (int): Index that will be ignored in evaluation.\n        nan_to_num (int, optional): If specified, NaN values will be replaced\n            by the numbers defined by the user. Default: None.\n        label_map (dict): Mapping old labels to new labels. Default: dict().\n        reduce_zero_label (bool): Wether ignore zero label. Default: False.\n        beta (int): Determines the weight of recall in the combined score.\n            Default: False.\n\n\n     Returns:\n        dict[str, float | ndarray]: Default metrics.\n            <aAcc> float: Overall accuracy on all images.\n            <Fscore> ndarray: Per category recall, shape (num_classes, ).\n            <Precision> ndarray: Per category precision, shape (num_classes, ).\n            <Recall> ndarray: Per category f-score, shape (num_classes, ).\n    \"\"\"\n    fscore_result = eval_metrics(\n        results=results,\n        gt_seg_maps=gt_seg_maps,\n        num_classes=num_classes,\n        ignore_index=ignore_index,\n        metrics=['mFscore'],\n        nan_to_num=nan_to_num,\n        label_map=label_map,\n        reduce_zero_label=reduce_zero_label,\n        beta=beta)\n    return fscore_result\n\n\ndef eval_metrics(results,\n                 gt_seg_maps,\n                 num_classes,\n                 ignore_index,\n                 metrics=['mIoU'],\n                 nan_to_num=None,\n                 label_map=dict(),\n                 reduce_zero_label=False,\n                 beta=1):\n    \"\"\"Calculate evaluation metrics\n    Args:\n        results (list[ndarray] | list[str]): List of prediction segmentation\n            maps or list of prediction result filenames.\n        gt_seg_maps (list[ndarray] | list[str]): list of ground truth\n            segmentation maps or list of label filenames.\n        num_classes (int): Number of categories.\n        ignore_index (int): Index that will be ignored in evaluation.\n        metrics (list[str] | str): Metrics to be evaluated, 'mIoU' and 'mDice'.\n        nan_to_num (int, optional): If specified, NaN values will be replaced\n            by the numbers defined by the user. Default: None.\n        label_map (dict): Mapping old labels to new labels. Default: dict().\n        reduce_zero_label (bool): Wether ignore zero label. Default: False.\n     Returns:\n        float: Overall accuracy on all images.\n        ndarray: Per category accuracy, shape (num_classes, ).\n        ndarray: Per category evaluation metrics, shape (num_classes, ).\n    \"\"\"\n    if isinstance(metrics, str):\n        metrics = [metrics]\n    allowed_metrics = ['mIoU', 'mDice', 'mFscore']\n    if not set(metrics).issubset(set(allowed_metrics)):\n        raise KeyError('metrics {} is not supported'.format(metrics))\n\n    total_area_intersect, total_area_union, total_area_pred_label, \\\n        total_area_label = total_intersect_and_union(\n            results, gt_seg_maps, num_classes, ignore_index, label_map,\n            reduce_zero_label)\n    all_acc = total_area_intersect.sum() / total_area_label.sum()\n    ret_metrics = OrderedDict({'aAcc': all_acc})\n    for metric in metrics:\n        if metric == 'mIoU':\n            iou = total_area_intersect / total_area_union\n            acc = total_area_intersect / total_area_label\n            ret_metrics['IoU'] = iou\n            ret_metrics['Acc'] = acc\n        elif metric == 'mDice':\n            dice = 2 * total_area_intersect / (\n                total_area_pred_label + total_area_label)\n            acc = total_area_intersect / total_area_label\n            ret_metrics['Dice'] = dice\n            ret_metrics['Acc'] = acc\n        elif metric == 'mFscore':\n            precision = total_area_intersect / total_area_pred_label\n            recall = total_area_intersect / total_area_label\n            f_value = torch.tensor(\n                [f_score(x[0], x[1], beta) for x in zip(precision, recall)])\n            ret_metrics['Fscore'] = f_value\n            ret_metrics['Precision'] = precision\n            ret_metrics['Recall'] = recall\n\n    ret_metrics = {\n        metric: value.numpy()\n        for metric, value in ret_metrics.items()\n    }\n    if nan_to_num is not None:\n        ret_metrics = OrderedDict({\n            metric: np.nan_to_num(metric_value, nan=nan_to_num)\n            for metric, metric_value in ret_metrics.items()\n        })\n    return ret_metrics\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/recall.py",
    "content": "from collections.abc import Sequence\n\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\n\nfrom .bbox_overlaps import bbox_overlaps\n\n\ndef _recalls(all_ious, proposal_nums, thrs):\n\n    img_num = all_ious.shape[0]\n    total_gt_num = sum([ious.shape[0] for ious in all_ious])\n\n    _ious = np.zeros((proposal_nums.size, total_gt_num), dtype=np.float32)\n    for k, proposal_num in enumerate(proposal_nums):\n        tmp_ious = np.zeros(0)\n        for i in range(img_num):\n            ious = all_ious[i][:, :proposal_num].copy()\n            gt_ious = np.zeros((ious.shape[0]))\n            if ious.size == 0:\n                tmp_ious = np.hstack((tmp_ious, gt_ious))\n                continue\n            for j in range(ious.shape[0]):\n                gt_max_overlaps = ious.argmax(axis=1)\n                max_ious = ious[np.arange(0, ious.shape[0]), gt_max_overlaps]\n                gt_idx = max_ious.argmax()\n                gt_ious[j] = max_ious[gt_idx]\n                box_idx = gt_max_overlaps[gt_idx]\n                ious[gt_idx, :] = -1\n                ious[:, box_idx] = -1\n            tmp_ious = np.hstack((tmp_ious, gt_ious))\n        _ious[k, :] = tmp_ious\n\n    _ious = np.fliplr(np.sort(_ious, axis=1))\n    recalls = np.zeros((proposal_nums.size, thrs.size))\n    for i, thr in enumerate(thrs):\n        recalls[:, i] = (_ious >= thr).sum(axis=1) / float(total_gt_num)\n\n    return recalls\n\n\ndef set_recall_param(proposal_nums, iou_thrs):\n    \"\"\"Check proposal_nums and iou_thrs and set correct format.\"\"\"\n    if isinstance(proposal_nums, Sequence):\n        _proposal_nums = np.array(proposal_nums)\n    elif isinstance(proposal_nums, int):\n        _proposal_nums = np.array([proposal_nums])\n    else:\n        _proposal_nums = proposal_nums\n\n    if iou_thrs is None:\n        _iou_thrs = np.array([0.5])\n    elif isinstance(iou_thrs, Sequence):\n        _iou_thrs = np.array(iou_thrs)\n    elif isinstance(iou_thrs, float):\n        _iou_thrs = np.array([iou_thrs])\n    else:\n        _iou_thrs = iou_thrs\n\n    return _proposal_nums, _iou_thrs\n\n\ndef eval_recalls(gts,\n                 proposals,\n                 proposal_nums=None,\n                 iou_thrs=0.5,\n                 logger=None):\n    \"\"\"Calculate recalls.\n\n    Args:\n        gts (list[ndarray]): a list of arrays of shape (n, 4)\n        proposals (list[ndarray]): a list of arrays of shape (k, 4) or (k, 5)\n        proposal_nums (int | Sequence[int]): Top N proposals to be evaluated.\n        iou_thrs (float | Sequence[float]): IoU thresholds. Default: 0.5.\n        logger (logging.Logger | str | None): The way to print the recall\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n\n    Returns:\n        ndarray: recalls of different ious and proposal nums\n    \"\"\"\n\n    img_num = len(gts)\n    assert img_num == len(proposals)\n\n    proposal_nums, iou_thrs = set_recall_param(proposal_nums, iou_thrs)\n\n    all_ious = []\n    for i in range(img_num):\n        if proposals[i].ndim == 2 and proposals[i].shape[1] == 5:\n            scores = proposals[i][:, 4]\n            sort_idx = np.argsort(scores)[::-1]\n            img_proposal = proposals[i][sort_idx, :]\n        else:\n            img_proposal = proposals[i]\n        prop_num = min(img_proposal.shape[0], proposal_nums[-1])\n        if gts[i] is None or gts[i].shape[0] == 0:\n            ious = np.zeros((0, img_proposal.shape[0]), dtype=np.float32)\n        else:\n            ious = bbox_overlaps(gts[i], img_proposal[:prop_num, :4])\n        all_ious.append(ious)\n    all_ious = np.array(all_ious)\n    recalls = _recalls(all_ious, proposal_nums, iou_thrs)\n\n    print_recall_summary(recalls, proposal_nums, iou_thrs, logger=logger)\n    return recalls\n\n\ndef print_recall_summary(recalls,\n                         proposal_nums,\n                         iou_thrs,\n                         row_idxs=None,\n                         col_idxs=None,\n                         logger=None):\n    \"\"\"Print recalls in a table.\n\n    Args:\n        recalls (ndarray): calculated from `bbox_recalls`\n        proposal_nums (ndarray or list): top N proposals\n        iou_thrs (ndarray or list): iou thresholds\n        row_idxs (ndarray): which rows(proposal nums) to print\n        col_idxs (ndarray): which cols(iou thresholds) to print\n        logger (logging.Logger | str | None): The way to print the recall\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n    \"\"\"\n    proposal_nums = np.array(proposal_nums, dtype=np.int32)\n    iou_thrs = np.array(iou_thrs)\n    if row_idxs is None:\n        row_idxs = np.arange(proposal_nums.size)\n    if col_idxs is None:\n        col_idxs = np.arange(iou_thrs.size)\n    row_header = [''] + iou_thrs[col_idxs].tolist()\n    table_data = [row_header]\n    for i, num in enumerate(proposal_nums[row_idxs]):\n        row = [f'{val:.3f}' for val in recalls[row_idxs[i], col_idxs].tolist()]\n        row.insert(0, num)\n        table_data.append(row)\n    table = AsciiTable(table_data)\n    print_log('\\n' + table.table, logger=logger)\n\n\ndef plot_num_recall(recalls, proposal_nums):\n    \"\"\"Plot Proposal_num-Recalls curve.\n\n    Args:\n        recalls(ndarray or list): shape (k,)\n        proposal_nums(ndarray or list): same shape as `recalls`\n    \"\"\"\n    if isinstance(proposal_nums, np.ndarray):\n        _proposal_nums = proposal_nums.tolist()\n    else:\n        _proposal_nums = proposal_nums\n    if isinstance(recalls, np.ndarray):\n        _recalls = recalls.tolist()\n    else:\n        _recalls = recalls\n\n    import matplotlib.pyplot as plt\n    f = plt.figure()\n    plt.plot([0] + _proposal_nums, [0] + _recalls)\n    plt.xlabel('Proposal num')\n    plt.ylabel('Recall')\n    plt.axis([0, proposal_nums.max(), 0, 1])\n    f.show()\n\n\ndef plot_iou_recall(recalls, iou_thrs):\n    \"\"\"Plot IoU-Recalls curve.\n\n    Args:\n        recalls(ndarray or list): shape (k,)\n        iou_thrs(ndarray or list): same shape as `recalls`\n    \"\"\"\n    if isinstance(iou_thrs, np.ndarray):\n        _iou_thrs = iou_thrs.tolist()\n    else:\n        _iou_thrs = iou_thrs\n    if isinstance(recalls, np.ndarray):\n        _recalls = recalls.tolist()\n    else:\n        _recalls = recalls\n\n    import matplotlib.pyplot as plt\n    f = plt.figure()\n    plt.plot(_iou_thrs + [1.0], _recalls + [0.])\n    plt.xlabel('IoU')\n    plt.ylabel('Recall')\n    plt.axis([iou_thrs.min(), 1, 0, 1])\n    f.show()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/seg_eval.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\n\n\ndef fast_hist(preds, labels, num_classes):\n    \"\"\"Compute the confusion matrix for every batch.\n\n    Args:\n        preds (np.ndarray):  Prediction labels of points with shape of\n        (num_points, ).\n        labels (np.ndarray): Ground truth labels of points with shape of\n        (num_points, ).\n        num_classes (int): number of classes\n\n    Returns:\n        np.ndarray: Calculated confusion matrix.\n    \"\"\"\n\n    k = (labels >= 0) & (labels < num_classes)\n    bin_count = np.bincount(\n        num_classes * labels[k].astype(int) + preds[k],\n        minlength=num_classes**2)\n    return bin_count[:num_classes**2].reshape(num_classes, num_classes)\n\n\ndef per_class_iou(hist):\n    \"\"\"Compute the per class iou.\n\n    Args:\n        hist(np.ndarray):  Overall confusion martix\n        (num_classes, num_classes ).\n\n    Returns:\n        np.ndarray: Calculated per class iou\n    \"\"\"\n\n    return np.diag(hist) / (hist.sum(1) + hist.sum(0) - np.diag(hist))\n\n\ndef get_acc(hist):\n    \"\"\"Compute the overall accuracy.\n\n    Args:\n        hist(np.ndarray):  Overall confusion martix\n        (num_classes, num_classes ).\n\n    Returns:\n        float: Calculated overall acc\n    \"\"\"\n\n    return np.diag(hist).sum() / hist.sum()\n\n\ndef get_acc_cls(hist):\n    \"\"\"Compute the class average accuracy.\n\n    Args:\n        hist(np.ndarray):  Overall confusion martix\n        (num_classes, num_classes ).\n\n    Returns:\n        float: Calculated class average acc\n    \"\"\"\n\n    return np.nanmean(np.diag(hist) / hist.sum(axis=1))\n\n\ndef seg_eval(gt_labels, seg_preds, label2cat, ignore_index, logger=None):\n    \"\"\"Semantic Segmentation  Evaluation.\n\n    Evaluate the result of the Semantic Segmentation.\n\n    Args:\n        gt_labels (list[torch.Tensor]): Ground truth labels.\n        seg_preds  (list[torch.Tensor]): Predictions.\n        label2cat (dict): Map from label to category name.\n        ignore_index (int): Index that will be ignored in evaluation.\n        logger (logging.Logger | str | None): The way to print the mAP\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n\n    Returns:\n        dict[str, float]: Dict of results.\n    \"\"\"\n    assert len(seg_preds) == len(gt_labels)\n    num_classes = len(label2cat)\n\n    hist_list = []\n    for i in range(len(gt_labels)):\n        gt_seg = gt_labels[i].clone().numpy().astype(np.int)\n        pred_seg = seg_preds[i].clone().numpy().astype(np.int)\n\n        # filter out ignored points\n        pred_seg[gt_seg == ignore_index] = -1\n        gt_seg[gt_seg == ignore_index] = -1\n\n        # calculate one instance result\n        hist_list.append(fast_hist(pred_seg, gt_seg, num_classes))\n\n    iou = per_class_iou(sum(hist_list))\n    miou = np.nanmean(iou)\n    acc = get_acc(sum(hist_list))\n    acc_cls = get_acc_cls(sum(hist_list))\n\n    header = ['classes']\n    for i in range(len(label2cat)):\n        header.append(label2cat[i])\n    header.extend(['miou', 'acc', 'acc_cls'])\n\n    ret_dict = dict()\n    table_columns = [['results']]\n    for i in range(len(label2cat)):\n        ret_dict[label2cat[i]] = float(iou[i])\n        table_columns.append([f'{iou[i]:.4f}'])\n    ret_dict['miou'] = float(miou)\n    ret_dict['acc'] = float(acc)\n    ret_dict['acc_cls'] = float(acc_cls)\n\n    table_columns.append([f'{miou:.4f}'])\n    table_columns.append([f'{acc:.4f}'])\n    table_columns.append([f'{acc_cls:.4f}'])\n\n    table_data = [header]\n    table_rows = list(zip(*table_columns))\n    table_data += table_rows\n    table = AsciiTable(table_data)\n    table.inner_footing_row_border = True\n    print_log('\\n' + table.table, logger=logger)\n\n    return ret_dict\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/evaluation/waymo_utils/prediction_kitti_to_waymo.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nr\"\"\"Adapted from `Waymo to KITTI converter\n    <https://github.com/caizhongang/waymo_kitti_converter>`_.\n\"\"\"\n\ntry:\n    from waymo_open_dataset import dataset_pb2 as open_dataset\nexcept ImportError:\n    raise ImportError(\n        'Please run \"pip install waymo-open-dataset-tf-2-1-0==1.2.0\" '\n        'to install the official devkit first.')\n\nfrom mmcv.utils import mkdir_or_exist, track_parallel_progress\nimport numpy as np\nimport tensorflow as tf\nfrom glob import glob\nfrom os.path import join\nfrom waymo_open_dataset import label_pb2\nfrom waymo_open_dataset.protos import metrics_pb2\n\n\nclass KITTI2Waymo(object):\n    \"\"\"KITTI predictions to Waymo converter.\n\n    This class serves as the converter to change predictions from KITTI to\n    Waymo format.\n\n    Args:\n        kitti_result_files (list[dict]): Predictions in KITTI format.\n        waymo_tfrecords_dir (str): Directory to load waymo raw data.\n        waymo_results_save_dir (str): Directory to save converted predictions\n            in waymo format (.bin files).\n        waymo_results_final_path (str): Path to save combined\n            predictions in waymo format (.bin file), like 'a/b/c.bin'.\n        prefix (str): Prefix of filename. In general, 0 for training, 1 for\n            validation and 2 for testing.\n        workers (str): Number of parallel processes.\n    \"\"\"\n\n    def __init__(self,\n                 kitti_result_files,\n                 waymo_tfrecords_dir,\n                 waymo_results_save_dir,\n                 waymo_results_final_path,\n                 prefix,\n                 workers=64):\n\n        self.kitti_result_files = kitti_result_files\n        self.waymo_tfrecords_dir = waymo_tfrecords_dir\n        self.waymo_results_save_dir = waymo_results_save_dir\n        self.waymo_results_final_path = waymo_results_final_path\n        self.prefix = prefix\n        self.workers = int(workers)\n        self.name2idx = {}\n        for idx, result in enumerate(kitti_result_files):\n            if len(result['sample_idx']) > 0:\n                self.name2idx[str(result['sample_idx'][0])] = idx\n\n        # turn on eager execution for older tensorflow versions\n        if int(tf.__version__.split('.')[0]) < 2:\n            tf.enable_eager_execution()\n\n        self.k2w_cls_map = {\n            'Car': label_pb2.Label.TYPE_VEHICLE,\n            'Pedestrian': label_pb2.Label.TYPE_PEDESTRIAN,\n            'Sign': label_pb2.Label.TYPE_SIGN,\n            'Cyclist': label_pb2.Label.TYPE_CYCLIST,\n        }\n\n        self.T_ref_to_front_cam = np.array([[0.0, 0.0, 1.0, 0.0],\n                                            [-1.0, 0.0, 0.0, 0.0],\n                                            [0.0, -1.0, 0.0, 0.0],\n                                            [0.0, 0.0, 0.0, 1.0]])\n\n        self.get_file_names()\n        self.create_folder()\n\n    def get_file_names(self):\n        \"\"\"Get file names of waymo raw data.\"\"\"\n        self.waymo_tfrecord_pathnames = sorted(\n            glob(join(self.waymo_tfrecords_dir, '*.tfrecord')))\n        print(len(self.waymo_tfrecord_pathnames), 'tfrecords found.')\n\n    def create_folder(self):\n        \"\"\"Create folder for data conversion.\"\"\"\n        mkdir_or_exist(self.waymo_results_save_dir)\n\n    def parse_objects(self, kitti_result, T_k2w, context_name,\n                      frame_timestamp_micros):\n        \"\"\"Parse one prediction with several instances in kitti format and\n        convert them to `Object` proto.\n\n        Args:\n            kitti_result (dict): Predictions in kitti format.\n\n                - name (np.ndarray): Class labels of predictions.\n                - dimensions (np.ndarray): Height, width, length of boxes.\n                - location (np.ndarray): Bottom center of boxes (x, y, z).\n                - rotation_y (np.ndarray): Orientation of boxes.\n                - score (np.ndarray): Scores of predictions.\n            T_k2w (np.ndarray): Transformation matrix from kitti to waymo.\n            context_name (str): Context name of the frame.\n            frame_timestamp_micros (int): Frame timestamp.\n\n        Returns:\n            :obj:`Object`: Predictions in waymo dataset Object proto.\n        \"\"\"\n\n        def parse_one_object(instance_idx):\n            \"\"\"Parse one instance in kitti format and convert them to `Object`\n            proto.\n\n            Args:\n                instance_idx (int): Index of the instance to be converted.\n\n            Returns:\n                :obj:`Object`: Predicted instance in waymo dataset \\\n                    Object proto.\n            \"\"\"\n            cls = kitti_result['name'][instance_idx]\n            length = round(kitti_result['dimensions'][instance_idx, 0], 4)\n            height = round(kitti_result['dimensions'][instance_idx, 1], 4)\n            width = round(kitti_result['dimensions'][instance_idx, 2], 4)\n            x = round(kitti_result['location'][instance_idx, 0], 4)\n            y = round(kitti_result['location'][instance_idx, 1], 4)\n            z = round(kitti_result['location'][instance_idx, 2], 4)\n            rotation_y = round(kitti_result['rotation_y'][instance_idx], 4)\n            score = round(kitti_result['score'][instance_idx], 4)\n\n            # y: downwards; move box origin from bottom center (kitti) to\n            # true center (waymo)\n            y -= height / 2\n            # frame transformation: kitti -> waymo\n            x, y, z = self.transform(T_k2w, x, y, z)\n\n            # different conventions\n            heading = -(rotation_y + np.pi / 2)\n            while heading < -np.pi:\n                heading += 2 * np.pi\n            while heading > np.pi:\n                heading -= 2 * np.pi\n\n            box = label_pb2.Label.Box()\n            box.center_x = x\n            box.center_y = y\n            box.center_z = z\n            box.length = length\n            box.width = width\n            box.height = height\n            box.heading = heading\n\n            o = metrics_pb2.Object()\n            o.object.box.CopyFrom(box)\n            o.object.type = self.k2w_cls_map[cls]\n            o.score = score\n\n            o.context_name = context_name\n            o.frame_timestamp_micros = frame_timestamp_micros\n\n            return o\n\n        objects = metrics_pb2.Objects()\n\n        for instance_idx in range(len(kitti_result['name'])):\n            o = parse_one_object(instance_idx)\n            objects.objects.append(o)\n\n        return objects\n\n    def convert_one(self, file_idx):\n        \"\"\"Convert action for single file.\n\n        Args:\n            file_idx (int): Index of the file to be converted.\n        \"\"\"\n        file_pathname = self.waymo_tfrecord_pathnames[file_idx]\n        file_data = tf.data.TFRecordDataset(file_pathname, compression_type='')\n\n        for frame_num, frame_data in enumerate(file_data):\n            frame = open_dataset.Frame()\n            frame.ParseFromString(bytearray(frame_data.numpy()))\n\n            filename = f'{self.prefix}{file_idx:03d}{frame_num:03d}'\n\n            for camera in frame.context.camera_calibrations:\n                # FRONT = 1, see dataset.proto for details\n                if camera.name == 1:\n                    T_front_cam_to_vehicle = np.array(\n                        camera.extrinsic.transform).reshape(4, 4)\n\n            T_k2w = T_front_cam_to_vehicle @ self.T_ref_to_front_cam\n\n            context_name = frame.context.name\n            frame_timestamp_micros = frame.timestamp_micros\n\n            if filename in self.name2idx:\n                kitti_result = \\\n                    self.kitti_result_files[self.name2idx[filename]]\n                objects = self.parse_objects(kitti_result, T_k2w, context_name,\n                                             frame_timestamp_micros)\n            else:\n                print(filename, 'not found.')\n                objects = metrics_pb2.Objects()\n\n            with open(\n                    join(self.waymo_results_save_dir, f'{filename}.bin'),\n                    'wb') as f:\n                f.write(objects.SerializeToString())\n\n    def convert(self):\n        \"\"\"Convert action.\"\"\"\n        print('Start converting ...')\n        track_parallel_progress(self.convert_one, range(len(self)),\n                                     self.workers)\n        print('\\nFinished ...')\n\n        # combine all files into one .bin\n        pathnames = sorted(glob(join(self.waymo_results_save_dir, '*.bin')))\n        combined = self.combine(pathnames)\n\n        with open(self.waymo_results_final_path, 'wb') as f:\n            f.write(combined.SerializeToString())\n\n    def __len__(self):\n        \"\"\"Length of the filename list.\"\"\"\n        return len(self.waymo_tfrecord_pathnames)\n\n    def transform(self, T, x, y, z):\n        \"\"\"Transform the coordinates with matrix T.\n\n        Args:\n            T (np.ndarray): Transformation matrix.\n            x(float): Coordinate in x axis.\n            y(float): Coordinate in y axis.\n            z(float): Coordinate in z axis.\n\n        Returns:\n            list: Coordinates after transformation.\n        \"\"\"\n        pt_bef = np.array([x, y, z, 1.0]).reshape(4, 1)\n        pt_aft = np.matmul(T, pt_bef)\n        return pt_aft[:3].flatten().tolist()\n\n    def combine(self, pathnames):\n        \"\"\"Combine predictions in waymo format for each sample together.\n\n        Args:\n            pathnames (str): Paths to save predictions.\n\n        Returns:\n            :obj:`Objects`: Combined predictions in Objects proto.\n        \"\"\"\n        combined = metrics_pb2.Objects()\n\n        for pathname in pathnames:\n            objects = metrics_pb2.Objects()\n            with open(pathname, 'rb') as f:\n                objects.ParseFromString(f.read())\n            for o in objects.objects:\n                combined.objects.append(o)\n\n        return combined\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/mask/__init__.py",
    "content": "from .mask_target import mask_target\nfrom .utils import encode_mask_results, split_combined_polys\n\n__all__ = [\n    'split_combined_polys', 'mask_target', 'encode_mask_results'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/mask/mask_target.py",
    "content": "import numpy as np\nimport torch\nfrom torch.nn.modules.utils import _pair\n\n\ndef mask_target(pos_proposals_list, pos_assigned_gt_inds_list, gt_masks_list,\n                cfg):\n    \"\"\"Compute mask target for positive proposals in multiple images.\n\n    Args:\n        pos_proposals_list (list[Tensor]): Positive proposals in multiple\n            images.\n        pos_assigned_gt_inds_list (list[Tensor]): Assigned GT indices for each\n            positive proposals.\n        gt_masks_list (list[:obj:`BaseInstanceMasks`]): Ground truth masks of\n            each image.\n        cfg (dict): Config dict that specifies the mask size.\n\n    Returns:\n        list[Tensor]: Mask target of each image.\n\n    Example:\n        >>> import mmcv\n        >>> import mmdet\n        >>> from mmcv.core.mask import BitmapMasks\n        >>> from mmcv.core.mask.mask_target import *\n        >>> H, W = 17, 18\n        >>> cfg = mmcv.Config({'mask_size': (13, 14)})\n        >>> rng = np.random.RandomState(0)\n        >>> # Positive proposals (tl_x, tl_y, br_x, br_y) for each image\n        >>> pos_proposals_list = [\n        >>>     torch.Tensor([\n        >>>         [ 7.2425,  5.5929, 13.9414, 14.9541],\n        >>>         [ 7.3241,  3.6170, 16.3850, 15.3102],\n        >>>     ]),\n        >>>     torch.Tensor([\n        >>>         [ 4.8448, 6.4010, 7.0314, 9.7681],\n        >>>         [ 5.9790, 2.6989, 7.4416, 4.8580],\n        >>>         [ 0.0000, 0.0000, 0.1398, 9.8232],\n        >>>     ]),\n        >>> ]\n        >>> # Corresponding class index for each proposal for each image\n        >>> pos_assigned_gt_inds_list = [\n        >>>     torch.LongTensor([7, 0]),\n        >>>     torch.LongTensor([5, 4, 1]),\n        >>> ]\n        >>> # Ground truth mask for each true object for each image\n        >>> gt_masks_list = [\n        >>>     BitmapMasks(rng.rand(8, H, W), height=H, width=W),\n        >>>     BitmapMasks(rng.rand(6, H, W), height=H, width=W),\n        >>> ]\n        >>> mask_targets = mask_target(\n        >>>     pos_proposals_list, pos_assigned_gt_inds_list,\n        >>>     gt_masks_list, cfg)\n        >>> assert mask_targets.shape == (5,) + cfg['mask_size']\n    \"\"\"\n    cfg_list = [cfg for _ in range(len(pos_proposals_list))]\n    mask_targets = map(mask_target_single, pos_proposals_list,\n                       pos_assigned_gt_inds_list, gt_masks_list, cfg_list)\n    mask_targets = list(mask_targets)\n    if len(mask_targets) > 0:\n        mask_targets = torch.cat(mask_targets)\n    return mask_targets\n\n\ndef mask_target_single(pos_proposals, pos_assigned_gt_inds, gt_masks, cfg):\n    \"\"\"Compute mask target for each positive proposal in the image.\n\n    Args:\n        pos_proposals (Tensor): Positive proposals.\n        pos_assigned_gt_inds (Tensor): Assigned GT inds of positive proposals.\n        gt_masks (:obj:`BaseInstanceMasks`): GT masks in the format of Bitmap\n            or Polygon.\n        cfg (dict): Config dict that indicate the mask size.\n\n    Returns:\n        Tensor: Mask target of each positive proposals in the image.\n\n    Example:\n        >>> import mmcv\n        >>> import mmdet\n        >>> from mmcv.core.mask import BitmapMasks\n        >>> from mmcv.core.mask.mask_target import *  # NOQA\n        >>> H, W = 32, 32\n        >>> cfg = mmcv.Config({'mask_size': (7, 11)})\n        >>> rng = np.random.RandomState(0)\n        >>> # Masks for each ground truth box (relative to the image)\n        >>> gt_masks_data = rng.rand(3, H, W)\n        >>> gt_masks = BitmapMasks(gt_masks_data, height=H, width=W)\n        >>> # Predicted positive boxes in one image\n        >>> pos_proposals = torch.FloatTensor([\n        >>>     [ 16.2,   5.5, 19.9, 20.9],\n        >>>     [ 17.3,  13.6, 19.3, 19.3],\n        >>>     [ 14.8,  16.4, 17.0, 23.7],\n        >>>     [  0.0,   0.0, 16.0, 16.0],\n        >>>     [  4.0,   0.0, 20.0, 16.0],\n        >>> ])\n        >>> # For each predicted proposal, its assignment to a gt mask\n        >>> pos_assigned_gt_inds = torch.LongTensor([0, 1, 2, 1, 1])\n        >>> mask_targets = mask_target_single(\n        >>>     pos_proposals, pos_assigned_gt_inds, gt_masks, cfg)\n        >>> assert mask_targets.shape == (5,) + cfg['mask_size']\n    \"\"\"\n    device = pos_proposals.device\n    mask_size = _pair(cfg.mask_size)\n    binarize = not cfg.get('soft_mask_target', False)\n    num_pos = pos_proposals.size(0)\n    if num_pos > 0:\n        proposals_np = pos_proposals.cpu().numpy()\n        maxh, maxw = gt_masks.height, gt_masks.width\n        proposals_np[:, [0, 2]] = np.clip(proposals_np[:, [0, 2]], 0, maxw)\n        proposals_np[:, [1, 3]] = np.clip(proposals_np[:, [1, 3]], 0, maxh)\n        pos_assigned_gt_inds = pos_assigned_gt_inds.cpu().numpy()\n\n        mask_targets = gt_masks.crop_and_resize(\n            proposals_np,\n            mask_size,\n            device=device,\n            inds=pos_assigned_gt_inds,\n            binarize=binarize).to_ndarray()\n\n        mask_targets = torch.from_numpy(mask_targets).float().to(device)\n    else:\n        mask_targets = pos_proposals.new_zeros((0, ) + mask_size)\n\n    return mask_targets\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/mask/structures.py",
    "content": "from abc import ABCMeta, abstractmethod\n\nimport cv2\nimport numpy as np\nimport pycocotools.mask as maskUtils\nimport torch\nfrom mmcv.ops.roi_align import roi_align\nfrom mmcv.image import rescale_size, imrescale, imresize, imflip, impad, imtranslate, imshear, imrotate\n\n\nclass BaseInstanceMasks(metaclass=ABCMeta):\n    \"\"\"Base class for instance masks.\"\"\"\n\n    @abstractmethod\n    def rescale(self, scale, interpolation='nearest'):\n        \"\"\"Rescale masks as large as possible while keeping the aspect ratio.\n        For details can refer to `mmcv.imrescale`.\n\n        Args:\n            scale (tuple[int]): The maximum size (h, w) of rescaled mask.\n            interpolation (str): Same as :func:`mmcv.imrescale`.\n\n        Returns:\n            BaseInstanceMasks: The rescaled masks.\n        \"\"\"\n\n    @abstractmethod\n    def resize(self, out_shape, interpolation='nearest'):\n        \"\"\"Resize masks to the given out_shape.\n\n        Args:\n            out_shape: Target (h, w) of resized mask.\n            interpolation (str): See :func:`mmcv.imresize`.\n\n        Returns:\n            BaseInstanceMasks: The resized masks.\n        \"\"\"\n\n    @abstractmethod\n    def flip(self, flip_direction='horizontal'):\n        \"\"\"Flip masks alone the given direction.\n\n        Args:\n            flip_direction (str): Either 'horizontal' or 'vertical'.\n\n        Returns:\n            BaseInstanceMasks: The flipped masks.\n        \"\"\"\n\n    @abstractmethod\n    def pad(self, out_shape, pad_val):\n        \"\"\"Pad masks to the given size of (h, w).\n\n        Args:\n            out_shape (tuple[int]): Target (h, w) of padded mask.\n            pad_val (int): The padded value.\n\n        Returns:\n            BaseInstanceMasks: The padded masks.\n        \"\"\"\n\n    @abstractmethod\n    def crop(self, bbox):\n        \"\"\"Crop each mask by the given bbox.\n\n        Args:\n            bbox (ndarray): Bbox in format [x1, y1, x2, y2], shape (4, ).\n\n        Return:\n            BaseInstanceMasks: The cropped masks.\n        \"\"\"\n\n    @abstractmethod\n    def crop_and_resize(self,\n                        bboxes,\n                        out_shape,\n                        inds,\n                        device,\n                        interpolation='bilinear',\n                        binarize=True):\n        \"\"\"Crop and resize masks by the given bboxes.\n\n        This function is mainly used in mask targets computation.\n        It firstly align mask to bboxes by assigned_inds, then crop mask by the\n        assigned bbox and resize to the size of (mask_h, mask_w)\n\n        Args:\n            bboxes (Tensor): Bboxes in format [x1, y1, x2, y2], shape (N, 4)\n            out_shape (tuple[int]): Target (h, w) of resized mask\n            inds (ndarray): Indexes to assign masks to each bbox,\n                shape (N,) and values should be between [0, num_masks - 1].\n            device (str): Device of bboxes\n            interpolation (str): See `mmcv.imresize`\n            binarize (bool): if True fractional values are rounded to 0 or 1\n                after the resize operation. if False and unsupported an error\n                will be raised. Defaults to True.\n\n        Return:\n            BaseInstanceMasks: the cropped and resized masks.\n        \"\"\"\n\n    @abstractmethod\n    def expand(self, expanded_h, expanded_w, top, left):\n        \"\"\"see :class:`Expand`.\"\"\"\n\n    @property\n    @abstractmethod\n    def areas(self):\n        \"\"\"ndarray: areas of each instance.\"\"\"\n\n    @abstractmethod\n    def to_ndarray(self):\n        \"\"\"Convert masks to the format of ndarray.\n\n        Return:\n            ndarray: Converted masks in the format of ndarray.\n        \"\"\"\n\n    @abstractmethod\n    def to_tensor(self, dtype, device):\n        \"\"\"Convert masks to the format of Tensor.\n\n        Args:\n            dtype (str): Dtype of converted mask.\n            device (torch.device): Device of converted masks.\n\n        Returns:\n            Tensor: Converted masks in the format of Tensor.\n        \"\"\"\n\n    @abstractmethod\n    def translate(self,\n                  out_shape,\n                  offset,\n                  direction='horizontal',\n                  fill_val=0,\n                  interpolation='bilinear'):\n        \"\"\"Translate the masks.\n\n        Args:\n            out_shape (tuple[int]): Shape for output mask, format (h, w).\n            offset (int | float): The offset for translate.\n            direction (str): The translate direction, either \"horizontal\"\n                or \"vertical\".\n            fill_val (int | float): Border value. Default 0.\n            interpolation (str): Same as :func:`mmcv.imtranslate`.\n\n        Returns:\n            Translated masks.\n        \"\"\"\n\n    def shear(self,\n              out_shape,\n              magnitude,\n              direction='horizontal',\n              border_value=0,\n              interpolation='bilinear'):\n        \"\"\"Shear the masks.\n\n        Args:\n            out_shape (tuple[int]): Shape for output mask, format (h, w).\n            magnitude (int | float): The magnitude used for shear.\n            direction (str): The shear direction, either \"horizontal\"\n                or \"vertical\".\n            border_value (int | tuple[int]): Value used in case of a\n                constant border. Default 0.\n            interpolation (str): Same as in :func:`mmcv.imshear`.\n\n        Returns:\n            ndarray: Sheared masks.\n        \"\"\"\n\n    @abstractmethod\n    def rotate(self, out_shape, angle, center=None, scale=1.0, fill_val=0):\n        \"\"\"Rotate the masks.\n\n        Args:\n            out_shape (tuple[int]): Shape for output mask, format (h, w).\n            angle (int | float): Rotation angle in degrees. Positive values\n                mean counter-clockwise rotation.\n            center (tuple[float], optional): Center point (w, h) of the\n                rotation in source image. If not specified, the center of\n                the image will be used.\n            scale (int | float): Isotropic scale factor.\n            fill_val (int | float): Border value. Default 0 for masks.\n\n        Returns:\n            Rotated masks.\n        \"\"\"\n\n\nclass BitmapMasks(BaseInstanceMasks):\n    \"\"\"This class represents masks in the form of bitmaps.\n\n    Args:\n        masks (ndarray): ndarray of masks in shape (N, H, W), where N is\n            the number of objects.\n        height (int): height of masks\n        width (int): width of masks\n\n    Example:\n        >>> from mmcv.core.mask.structures import *  # NOQA\n        >>> num_masks, H, W = 3, 32, 32\n        >>> rng = np.random.RandomState(0)\n        >>> masks = (rng.rand(num_masks, H, W) > 0.1).astype(np.int)\n        >>> self = BitmapMasks(masks, height=H, width=W)\n\n        >>> # demo crop_and_resize\n        >>> num_boxes = 5\n        >>> bboxes = np.array([[0, 0, 30, 10.0]] * num_boxes)\n        >>> out_shape = (14, 14)\n        >>> inds = torch.randint(0, len(self), size=(num_boxes,))\n        >>> device = 'cpu'\n        >>> interpolation = 'bilinear'\n        >>> new = self.crop_and_resize(\n        ...     bboxes, out_shape, inds, device, interpolation)\n        >>> assert len(new) == num_boxes\n        >>> assert new.height, new.width == out_shape\n    \"\"\"\n\n    def __init__(self, masks, height, width):\n        self.height = height\n        self.width = width\n        if len(masks) == 0:\n            self.masks = np.empty((0, self.height, self.width), dtype=np.uint8)\n        else:\n            assert isinstance(masks, (list, np.ndarray))\n            if isinstance(masks, list):\n                assert isinstance(masks[0], np.ndarray)\n                assert masks[0].ndim == 2  # (H, W)\n            else:\n                assert masks.ndim == 3  # (N, H, W)\n\n            self.masks = np.stack(masks).reshape(-1, height, width)\n            assert self.masks.shape[1] == self.height\n            assert self.masks.shape[2] == self.width\n\n    def __getitem__(self, index):\n        \"\"\"Index the BitmapMask.\n\n        Args:\n            index (int | ndarray): Indices in the format of integer or ndarray.\n\n        Returns:\n            :obj:`BitmapMasks`: Indexed bitmap masks.\n        \"\"\"\n        masks = self.masks[index].reshape(-1, self.height, self.width)\n        return BitmapMasks(masks, self.height, self.width)\n\n    def __iter__(self):\n        return iter(self.masks)\n\n    def __repr__(self):\n        s = self.__class__.__name__ + '('\n        s += f'num_masks={len(self.masks)}, '\n        s += f'height={self.height}, '\n        s += f'width={self.width})'\n        return s\n\n    def __len__(self):\n        \"\"\"Number of masks.\"\"\"\n        return len(self.masks)\n\n    def rescale(self, scale, interpolation='nearest'):\n        \"\"\"See :func:`BaseInstanceMasks.rescale`.\"\"\"\n        if len(self.masks) == 0:\n            new_w, new_h = rescale_size((self.width, self.height), scale)\n            rescaled_masks = np.empty((0, new_h, new_w), dtype=np.uint8)\n        else:\n            rescaled_masks = np.stack([\n                imrescale(mask, scale, interpolation=interpolation)\n                for mask in self.masks\n            ])\n        height, width = rescaled_masks.shape[1:]\n        return BitmapMasks(rescaled_masks, height, width)\n\n    def resize(self, out_shape, interpolation='nearest'):\n        \"\"\"See :func:`BaseInstanceMasks.resize`.\"\"\"\n        if len(self.masks) == 0:\n            resized_masks = np.empty((0, *out_shape), dtype=np.uint8)\n        else:\n            resized_masks = np.stack([\n                imresize(\n                    mask, out_shape[::-1], interpolation=interpolation)\n                for mask in self.masks\n            ])\n        return BitmapMasks(resized_masks, *out_shape)\n\n    def flip(self, flip_direction='horizontal'):\n        \"\"\"See :func:`BaseInstanceMasks.flip`.\"\"\"\n        assert flip_direction in ('horizontal', 'vertical', 'diagonal')\n\n        if len(self.masks) == 0:\n            flipped_masks = self.masks\n        else:\n            flipped_masks = np.stack([\n                imflip(mask, direction=flip_direction)\n                for mask in self.masks\n            ])\n        return BitmapMasks(flipped_masks, self.height, self.width)\n\n    def pad(self, out_shape, pad_val=0):\n        \"\"\"See :func:`BaseInstanceMasks.pad`.\"\"\"\n        if len(self.masks) == 0:\n            padded_masks = np.empty((0, *out_shape), dtype=np.uint8)\n        else:\n            padded_masks = np.stack([\n                impad(mask, shape=out_shape, pad_val=pad_val)\n                for mask in self.masks\n            ])\n        return BitmapMasks(padded_masks, *out_shape)\n\n    def crop(self, bbox):\n        \"\"\"See :func:`BaseInstanceMasks.crop`.\"\"\"\n        assert isinstance(bbox, np.ndarray)\n        assert bbox.ndim == 1\n\n        # clip the boundary\n        bbox = bbox.copy()\n        bbox[0::2] = np.clip(bbox[0::2], 0, self.width)\n        bbox[1::2] = np.clip(bbox[1::2], 0, self.height)\n        x1, y1, x2, y2 = bbox\n        w = np.maximum(x2 - x1, 1)\n        h = np.maximum(y2 - y1, 1)\n\n        if len(self.masks) == 0:\n            cropped_masks = np.empty((0, h, w), dtype=np.uint8)\n        else:\n            cropped_masks = self.masks[:, y1:y1 + h, x1:x1 + w]\n        return BitmapMasks(cropped_masks, h, w)\n\n    def crop_and_resize(self,\n                        bboxes,\n                        out_shape,\n                        inds,\n                        device='cpu',\n                        interpolation='bilinear',\n                        binarize=True):\n        \"\"\"See :func:`BaseInstanceMasks.crop_and_resize`.\"\"\"\n        if len(self.masks) == 0:\n            empty_masks = np.empty((0, *out_shape), dtype=np.uint8)\n            return BitmapMasks(empty_masks, *out_shape)\n\n        # convert bboxes to tensor\n        if isinstance(bboxes, np.ndarray):\n            bboxes = torch.from_numpy(bboxes).to(device=device)\n        if isinstance(inds, np.ndarray):\n            inds = torch.from_numpy(inds).to(device=device)\n\n        num_bbox = bboxes.shape[0]\n        fake_inds = torch.arange(\n            num_bbox, device=device).to(dtype=bboxes.dtype)[:, None]\n        rois = torch.cat([fake_inds, bboxes], dim=1)  # Nx5\n        rois = rois.to(device=device)\n        if num_bbox > 0:\n            gt_masks_th = torch.from_numpy(self.masks).to(device).index_select(\n                0, inds).to(dtype=rois.dtype)\n            targets = roi_align(gt_masks_th[:, None, :, :], rois, out_shape,\n                                1.0, 0, 'avg', True).squeeze(1)\n            if binarize:\n                resized_masks = (targets >= 0.5).cpu().numpy()\n            else:\n                resized_masks = targets.cpu().numpy()\n        else:\n            resized_masks = []\n        return BitmapMasks(resized_masks, *out_shape)\n\n    def expand(self, expanded_h, expanded_w, top, left):\n        \"\"\"See :func:`BaseInstanceMasks.expand`.\"\"\"\n        if len(self.masks) == 0:\n            expanded_mask = np.empty((0, expanded_h, expanded_w),\n                                     dtype=np.uint8)\n        else:\n            expanded_mask = np.zeros((len(self), expanded_h, expanded_w),\n                                     dtype=np.uint8)\n            expanded_mask[:, top:top + self.height,\n                          left:left + self.width] = self.masks\n        return BitmapMasks(expanded_mask, expanded_h, expanded_w)\n\n    def translate(self,\n                  out_shape,\n                  offset,\n                  direction='horizontal',\n                  fill_val=0,\n                  interpolation='bilinear'):\n        \"\"\"Translate the BitmapMasks.\n\n        Args:\n            out_shape (tuple[int]): Shape for output mask, format (h, w).\n            offset (int | float): The offset for translate.\n            direction (str): The translate direction, either \"horizontal\"\n                or \"vertical\".\n            fill_val (int | float): Border value. Default 0 for masks.\n            interpolation (str): Same as :func:`mmcv.imtranslate`.\n\n        Returns:\n            BitmapMasks: Translated BitmapMasks.\n\n        Example:\n            >>> from mmcv.core.mask.structures import BitmapMasks\n            >>> self = BitmapMasks.random(dtype=np.uint8)\n            >>> out_shape = (32, 32)\n            >>> offset = 4\n            >>> direction = 'horizontal'\n            >>> fill_val = 0\n            >>> interpolation = 'bilinear'\n            >>> # Note, There seem to be issues when:\n            >>> # * out_shape is different than self's shape\n            >>> # * the mask dtype is not supported by cv2.AffineWarp\n            >>> new = self.translate(out_shape, offset, direction, fill_val,\n            >>>                      interpolation)\n            >>> assert len(new) == len(self)\n            >>> assert new.height, new.width == out_shape\n        \"\"\"\n        if len(self.masks) == 0:\n            translated_masks = np.empty((0, *out_shape), dtype=np.uint8)\n        else:\n            translated_masks = imtranslate(\n                self.masks.transpose((1, 2, 0)),\n                offset,\n                direction,\n                border_value=fill_val,\n                interpolation=interpolation)\n            if translated_masks.ndim == 2:\n                translated_masks = translated_masks[:, :, None]\n            translated_masks = translated_masks.transpose(\n                (2, 0, 1)).astype(self.masks.dtype)\n        return BitmapMasks(translated_masks, *out_shape)\n\n    def shear(self,\n              out_shape,\n              magnitude,\n              direction='horizontal',\n              border_value=0,\n              interpolation='bilinear'):\n        \"\"\"Shear the BitmapMasks.\n\n        Args:\n            out_shape (tuple[int]): Shape for output mask, format (h, w).\n            magnitude (int | float): The magnitude used for shear.\n            direction (str): The shear direction, either \"horizontal\"\n                or \"vertical\".\n            border_value (int | tuple[int]): Value used in case of a\n                constant border.\n            interpolation (str): Same as in :func:`mmcv.imshear`.\n\n        Returns:\n            BitmapMasks: The sheared masks.\n        \"\"\"\n        if len(self.masks) == 0:\n            sheared_masks = np.empty((0, *out_shape), dtype=np.uint8)\n        else:\n            sheared_masks = imshear(\n                self.masks.transpose((1, 2, 0)),\n                magnitude,\n                direction,\n                border_value=border_value,\n                interpolation=interpolation)\n            if sheared_masks.ndim == 2:\n                sheared_masks = sheared_masks[:, :, None]\n            sheared_masks = sheared_masks.transpose(\n                (2, 0, 1)).astype(self.masks.dtype)\n        return BitmapMasks(sheared_masks, *out_shape)\n\n    def rotate(self, out_shape, angle, center=None, scale=1.0, fill_val=0):\n        \"\"\"Rotate the BitmapMasks.\n\n        Args:\n            out_shape (tuple[int]): Shape for output mask, format (h, w).\n            angle (int | float): Rotation angle in degrees. Positive values\n                mean counter-clockwise rotation.\n            center (tuple[float], optional): Center point (w, h) of the\n                rotation in source image. If not specified, the center of\n                the image will be used.\n            scale (int | float): Isotropic scale factor.\n            fill_val (int | float): Border value. Default 0 for masks.\n\n        Returns:\n            BitmapMasks: Rotated BitmapMasks.\n        \"\"\"\n        if len(self.masks) == 0:\n            rotated_masks = np.empty((0, *out_shape), dtype=self.masks.dtype)\n        else:\n            rotated_masks = imrotate(\n                self.masks.transpose((1, 2, 0)),\n                angle,\n                center=center,\n                scale=scale,\n                border_value=fill_val)\n            if rotated_masks.ndim == 2:\n                # case when only one mask, (h, w)\n                rotated_masks = rotated_masks[:, :, None]  # (h, w, 1)\n            rotated_masks = rotated_masks.transpose(\n                (2, 0, 1)).astype(self.masks.dtype)\n        return BitmapMasks(rotated_masks, *out_shape)\n\n    @property\n    def areas(self):\n        \"\"\"See :py:attr:`BaseInstanceMasks.areas`.\"\"\"\n        return self.masks.sum((1, 2))\n\n    def to_ndarray(self):\n        \"\"\"See :func:`BaseInstanceMasks.to_ndarray`.\"\"\"\n        return self.masks\n\n    def to_tensor(self, dtype, device):\n        \"\"\"See :func:`BaseInstanceMasks.to_tensor`.\"\"\"\n        return torch.tensor(self.masks, dtype=dtype, device=device)\n\n    @classmethod\n    def random(cls,\n               num_masks=3,\n               height=32,\n               width=32,\n               dtype=np.uint8,\n               rng=None):\n        \"\"\"Generate random bitmap masks for demo / testing purposes.\n\n        Example:\n            >>> from mmcv.core.mask.structures import BitmapMasks\n            >>> self = BitmapMasks.random()\n            >>> print('self = {}'.format(self))\n            self = BitmapMasks(num_masks=3, height=32, width=32)\n        \"\"\"\n        from mmcv.utils.util_random import ensure_rng\n        rng = ensure_rng(rng)\n        masks = (rng.rand(num_masks, height, width) > 0.1).astype(dtype)\n        self = cls(masks, height=height, width=width)\n        return self\n\n\nclass PolygonMasks(BaseInstanceMasks):\n    \"\"\"This class represents masks in the form of polygons.\n\n    Polygons is a list of three levels. The first level of the list\n    corresponds to objects, the second level to the polys that compose the\n    object, the third level to the poly coordinates\n\n    Args:\n        masks (list[list[ndarray]]): The first level of the list\n            corresponds to objects, the second level to the polys that\n            compose the object, the third level to the poly coordinates\n        height (int): height of masks\n        width (int): width of masks\n\n    Example:\n        >>> from mmcv.core.mask.structures import *  # NOQA\n        >>> masks = [\n        >>>     [ np.array([0, 0, 10, 0, 10, 10., 0, 10, 0, 0]) ]\n        >>> ]\n        >>> height, width = 16, 16\n        >>> self = PolygonMasks(masks, height, width)\n\n        >>> # demo translate\n        >>> new = self.translate((16, 16), 4., direction='horizontal')\n        >>> assert np.all(new.masks[0][0][1::2] == masks[0][0][1::2])\n        >>> assert np.all(new.masks[0][0][0::2] == masks[0][0][0::2] + 4)\n\n        >>> # demo crop_and_resize\n        >>> num_boxes = 3\n        >>> bboxes = np.array([[0, 0, 30, 10.0]] * num_boxes)\n        >>> out_shape = (16, 16)\n        >>> inds = torch.randint(0, len(self), size=(num_boxes,))\n        >>> device = 'cpu'\n        >>> interpolation = 'bilinear'\n        >>> new = self.crop_and_resize(\n        ...     bboxes, out_shape, inds, device, interpolation)\n        >>> assert len(new) == num_boxes\n        >>> assert new.height, new.width == out_shape\n    \"\"\"\n\n    def __init__(self, masks, height, width):\n        assert isinstance(masks, list)\n        if len(masks) > 0:\n            assert isinstance(masks[0], list)\n            assert isinstance(masks[0][0], np.ndarray)\n\n        self.height = height\n        self.width = width\n        self.masks = masks\n\n    def __getitem__(self, index):\n        \"\"\"Index the polygon masks.\n\n        Args:\n            index (ndarray | List): The indices.\n\n        Returns:\n            :obj:`PolygonMasks`: The indexed polygon masks.\n        \"\"\"\n        if isinstance(index, np.ndarray):\n            index = index.tolist()\n        if isinstance(index, list):\n            masks = [self.masks[i] for i in index]\n        else:\n            try:\n                masks = self.masks[index]\n            except Exception:\n                raise ValueError(\n                    f'Unsupported input of type {type(index)} for indexing!')\n        if len(masks) and isinstance(masks[0], np.ndarray):\n            masks = [masks]  # ensure a list of three levels\n        return PolygonMasks(masks, self.height, self.width)\n\n    def __iter__(self):\n        return iter(self.masks)\n\n    def __repr__(self):\n        s = self.__class__.__name__ + '('\n        s += f'num_masks={len(self.masks)}, '\n        s += f'height={self.height}, '\n        s += f'width={self.width})'\n        return s\n\n    def __len__(self):\n        \"\"\"Number of masks.\"\"\"\n        return len(self.masks)\n\n    def rescale(self, scale, interpolation=None):\n        \"\"\"see :func:`BaseInstanceMasks.rescale`\"\"\"\n        new_w, new_h = rescale_size((self.width, self.height), scale)\n        if len(self.masks) == 0:\n            rescaled_masks = PolygonMasks([], new_h, new_w)\n        else:\n            rescaled_masks = self.resize((new_h, new_w))\n        return rescaled_masks\n\n    def resize(self, out_shape, interpolation=None):\n        \"\"\"see :func:`BaseInstanceMasks.resize`\"\"\"\n        if len(self.masks) == 0:\n            resized_masks = PolygonMasks([], *out_shape)\n        else:\n            h_scale = out_shape[0] / self.height\n            w_scale = out_shape[1] / self.width\n            resized_masks = []\n            for poly_per_obj in self.masks:\n                resized_poly = []\n                for p in poly_per_obj:\n                    p = p.copy()\n                    p[0::2] *= w_scale\n                    p[1::2] *= h_scale\n                    resized_poly.append(p)\n                resized_masks.append(resized_poly)\n            resized_masks = PolygonMasks(resized_masks, *out_shape)\n        return resized_masks\n\n    def flip(self, flip_direction='horizontal'):\n        \"\"\"see :func:`BaseInstanceMasks.flip`\"\"\"\n        assert flip_direction in ('horizontal', 'vertical', 'diagonal')\n        if len(self.masks) == 0:\n            flipped_masks = PolygonMasks([], self.height, self.width)\n        else:\n            flipped_masks = []\n            for poly_per_obj in self.masks:\n                flipped_poly_per_obj = []\n                for p in poly_per_obj:\n                    p = p.copy()\n                    if flip_direction == 'horizontal':\n                        p[0::2] = self.width - p[0::2]\n                    elif flip_direction == 'vertical':\n                        p[1::2] = self.height - p[1::2]\n                    else:\n                        p[0::2] = self.width - p[0::2]\n                        p[1::2] = self.height - p[1::2]\n                    flipped_poly_per_obj.append(p)\n                flipped_masks.append(flipped_poly_per_obj)\n            flipped_masks = PolygonMasks(flipped_masks, self.height,\n                                         self.width)\n        return flipped_masks\n\n    def crop(self, bbox):\n        \"\"\"see :func:`BaseInstanceMasks.crop`\"\"\"\n        assert isinstance(bbox, np.ndarray)\n        assert bbox.ndim == 1\n\n        # clip the boundary\n        bbox = bbox.copy()\n        bbox[0::2] = np.clip(bbox[0::2], 0, self.width)\n        bbox[1::2] = np.clip(bbox[1::2], 0, self.height)\n        x1, y1, x2, y2 = bbox\n        w = np.maximum(x2 - x1, 1)\n        h = np.maximum(y2 - y1, 1)\n\n        if len(self.masks) == 0:\n            cropped_masks = PolygonMasks([], h, w)\n        else:\n            cropped_masks = []\n            for poly_per_obj in self.masks:\n                cropped_poly_per_obj = []\n                for p in poly_per_obj:\n                    # pycocotools will clip the boundary\n                    p = p.copy()\n                    p[0::2] -= bbox[0]\n                    p[1::2] -= bbox[1]\n                    cropped_poly_per_obj.append(p)\n                cropped_masks.append(cropped_poly_per_obj)\n            cropped_masks = PolygonMasks(cropped_masks, h, w)\n        return cropped_masks\n\n    def pad(self, out_shape, pad_val=0):\n        \"\"\"padding has no effect on polygons`\"\"\"\n        return PolygonMasks(self.masks, *out_shape)\n\n    def expand(self, *args, **kwargs):\n        \"\"\"TODO: Add expand for polygon\"\"\"\n        raise NotImplementedError\n\n    def crop_and_resize(self,\n                        bboxes,\n                        out_shape,\n                        inds,\n                        device='cpu',\n                        interpolation='bilinear',\n                        binarize=True):\n        \"\"\"see :func:`BaseInstanceMasks.crop_and_resize`\"\"\"\n        out_h, out_w = out_shape\n        if len(self.masks) == 0:\n            return PolygonMasks([], out_h, out_w)\n\n        if not binarize:\n            raise ValueError('Polygons are always binary, '\n                             'setting binarize=False is unsupported')\n\n        resized_masks = []\n        for i in range(len(bboxes)):\n            mask = self.masks[inds[i]]\n            bbox = bboxes[i, :]\n            x1, y1, x2, y2 = bbox\n            w = np.maximum(x2 - x1, 1)\n            h = np.maximum(y2 - y1, 1)\n            h_scale = out_h / max(h, 0.1)  # avoid too large scale\n            w_scale = out_w / max(w, 0.1)\n\n            resized_mask = []\n            for p in mask:\n                p = p.copy()\n                # crop\n                # pycocotools will clip the boundary\n                p[0::2] -= bbox[0]\n                p[1::2] -= bbox[1]\n\n                # resize\n                p[0::2] *= w_scale\n                p[1::2] *= h_scale\n                resized_mask.append(p)\n            resized_masks.append(resized_mask)\n        return PolygonMasks(resized_masks, *out_shape)\n\n    def translate(self,\n                  out_shape,\n                  offset,\n                  direction='horizontal',\n                  fill_val=None,\n                  interpolation=None):\n        \"\"\"Translate the PolygonMasks.\n\n        Example:\n            >>> self = PolygonMasks.random(dtype=np.int)\n            >>> out_shape = (self.height, self.width)\n            >>> new = self.translate(out_shape, 4., direction='horizontal')\n            >>> assert np.all(new.masks[0][0][1::2] == self.masks[0][0][1::2])\n            >>> assert np.all(new.masks[0][0][0::2] == self.masks[0][0][0::2] + 4)  # noqa: E501\n        \"\"\"\n        assert fill_val is None or fill_val == 0, 'Here fill_val is not '\\\n            f'used, and defaultly should be None or 0. got {fill_val}.'\n        if len(self.masks) == 0:\n            translated_masks = PolygonMasks([], *out_shape)\n        else:\n            translated_masks = []\n            for poly_per_obj in self.masks:\n                translated_poly_per_obj = []\n                for p in poly_per_obj:\n                    p = p.copy()\n                    if direction == 'horizontal':\n                        p[0::2] = np.clip(p[0::2] + offset, 0, out_shape[1])\n                    elif direction == 'vertical':\n                        p[1::2] = np.clip(p[1::2] + offset, 0, out_shape[0])\n                    translated_poly_per_obj.append(p)\n                translated_masks.append(translated_poly_per_obj)\n            translated_masks = PolygonMasks(translated_masks, *out_shape)\n        return translated_masks\n\n    def shear(self,\n              out_shape,\n              magnitude,\n              direction='horizontal',\n              border_value=0,\n              interpolation='bilinear'):\n        \"\"\"See :func:`BaseInstanceMasks.shear`.\"\"\"\n        if len(self.masks) == 0:\n            sheared_masks = PolygonMasks([], *out_shape)\n        else:\n            sheared_masks = []\n            if direction == 'horizontal':\n                shear_matrix = np.stack([[1, magnitude],\n                                         [0, 1]]).astype(np.float32)\n            elif direction == 'vertical':\n                shear_matrix = np.stack([[1, 0], [magnitude,\n                                                  1]]).astype(np.float32)\n            for poly_per_obj in self.masks:\n                sheared_poly = []\n                for p in poly_per_obj:\n                    p = np.stack([p[0::2], p[1::2]], axis=0)  # [2, n]\n                    new_coords = np.matmul(shear_matrix, p)  # [2, n]\n                    new_coords[0, :] = np.clip(new_coords[0, :], 0,\n                                               out_shape[1])\n                    new_coords[1, :] = np.clip(new_coords[1, :], 0,\n                                               out_shape[0])\n                    sheared_poly.append(\n                        new_coords.transpose((1, 0)).reshape(-1))\n                sheared_masks.append(sheared_poly)\n            sheared_masks = PolygonMasks(sheared_masks, *out_shape)\n        return sheared_masks\n\n    def rotate(self, out_shape, angle, center=None, scale=1.0, fill_val=0):\n        \"\"\"See :func:`BaseInstanceMasks.rotate`.\"\"\"\n        if len(self.masks) == 0:\n            rotated_masks = PolygonMasks([], *out_shape)\n        else:\n            rotated_masks = []\n            rotate_matrix = cv2.getRotationMatrix2D(center, -angle, scale)\n            for poly_per_obj in self.masks:\n                rotated_poly = []\n                for p in poly_per_obj:\n                    p = p.copy()\n                    coords = np.stack([p[0::2], p[1::2]], axis=1)  # [n, 2]\n                    # pad 1 to convert from format [x, y] to homogeneous\n                    # coordinates format [x, y, 1]\n                    coords = np.concatenate(\n                        (coords, np.ones((coords.shape[0], 1), coords.dtype)),\n                        axis=1)  # [n, 3]\n                    rotated_coords = np.matmul(\n                        rotate_matrix[None, :, :],\n                        coords[:, :, None])[..., 0]  # [n, 2, 1] -> [n, 2]\n                    rotated_coords[:, 0] = np.clip(rotated_coords[:, 0], 0,\n                                                   out_shape[1])\n                    rotated_coords[:, 1] = np.clip(rotated_coords[:, 1], 0,\n                                                   out_shape[0])\n                    rotated_poly.append(rotated_coords.reshape(-1))\n                rotated_masks.append(rotated_poly)\n            rotated_masks = PolygonMasks(rotated_masks, *out_shape)\n        return rotated_masks\n\n    def to_bitmap(self):\n        \"\"\"convert polygon masks to bitmap masks.\"\"\"\n        bitmap_masks = self.to_ndarray()\n        return BitmapMasks(bitmap_masks, self.height, self.width)\n\n    @property\n    def areas(self):\n        \"\"\"Compute areas of masks.\n\n        This func is modified from `detectron2\n        <https://github.com/facebookresearch/detectron2/blob/ffff8acc35ea88ad1cb1806ab0f00b4c1c5dbfd9/detectron2/structures/masks.py#L387>`_.\n        The function only works with Polygons using the shoelace formula.\n\n        Return:\n            ndarray: areas of each instance\n        \"\"\"  # noqa: W501\n        area = []\n        for polygons_per_obj in self.masks:\n            area_per_obj = 0\n            for p in polygons_per_obj:\n                area_per_obj += self._polygon_area(p[0::2], p[1::2])\n            area.append(area_per_obj)\n        return np.asarray(area)\n\n    def _polygon_area(self, x, y):\n        \"\"\"Compute the area of a component of a polygon.\n\n        Using the shoelace formula:\n        https://stackoverflow.com/questions/24467972/calculate-area-of-polygon-given-x-y-coordinates\n\n        Args:\n            x (ndarray): x coordinates of the component\n            y (ndarray): y coordinates of the component\n\n        Return:\n            float: the are of the component\n        \"\"\"  # noqa: 501\n        return 0.5 * np.abs(\n            np.dot(x, np.roll(y, 1)) - np.dot(y, np.roll(x, 1)))\n\n    def to_ndarray(self):\n        \"\"\"Convert masks to the format of ndarray.\"\"\"\n        if len(self.masks) == 0:\n            return np.empty((0, self.height, self.width), dtype=np.uint8)\n        bitmap_masks = []\n        for poly_per_obj in self.masks:\n            bitmap_masks.append(\n                polygon_to_bitmap(poly_per_obj, self.height, self.width))\n        return np.stack(bitmap_masks)\n\n    def to_tensor(self, dtype, device):\n        \"\"\"See :func:`BaseInstanceMasks.to_tensor`.\"\"\"\n        if len(self.masks) == 0:\n            return torch.empty((0, self.height, self.width),\n                               dtype=dtype,\n                               device=device)\n        ndarray_masks = self.to_ndarray()\n        return torch.tensor(ndarray_masks, dtype=dtype, device=device)\n\n    @classmethod\n    def random(cls,\n               num_masks=3,\n               height=32,\n               width=32,\n               n_verts=5,\n               dtype=np.float32,\n               rng=None):\n        \"\"\"Generate random polygon masks for demo / testing purposes.\n\n        Adapted from [1]_\n\n        References:\n            .. [1] https://gitlab.kitware.com/computer-vision/kwimage/-/blob/928cae35ca8/kwimage/structs/polygon.py#L379  # noqa: E501\n\n        Example:\n            >>> from mmcv.core.mask.structures import PolygonMasks\n            >>> self = PolygonMasks.random()\n            >>> print('self = {}'.format(self))\n        \"\"\"\n        from mmcv.utils.util_random import ensure_rng\n        rng = ensure_rng(rng)\n\n        def _gen_polygon(n, irregularity, spikeyness):\n            \"\"\"Creates the polygon by sampling points on a circle around the\n            centre.  Random noise is added by varying the angular spacing\n            between sequential points, and by varying the radial distance of\n            each point from the centre.\n\n            Based on original code by Mike Ounsworth\n\n            Args:\n                n (int): number of vertices\n                irregularity (float): [0,1] indicating how much variance there\n                    is in the angular spacing of vertices. [0,1] will map to\n                    [0, 2pi/numberOfVerts]\n                spikeyness (float): [0,1] indicating how much variance there is\n                    in each vertex from the circle of radius aveRadius. [0,1]\n                    will map to [0, aveRadius]\n\n            Returns:\n                a list of vertices, in CCW order.\n            \"\"\"\n            from scipy.stats import truncnorm\n            # Generate around the unit circle\n            cx, cy = (0.0, 0.0)\n            radius = 1\n\n            tau = np.pi * 2\n\n            irregularity = np.clip(irregularity, 0, 1) * 2 * np.pi / n\n            spikeyness = np.clip(spikeyness, 1e-9, 1)\n\n            # generate n angle steps\n            lower = (tau / n) - irregularity\n            upper = (tau / n) + irregularity\n            angle_steps = rng.uniform(lower, upper, n)\n\n            # normalize the steps so that point 0 and point n+1 are the same\n            k = angle_steps.sum() / (2 * np.pi)\n            angles = (angle_steps / k).cumsum() + rng.uniform(0, tau)\n\n            # Convert high and low values to be wrt the standard normal range\n            # https://docs.scipy.org/doc/scipy/reference/generated/scipy.stats.truncnorm.html\n            low = 0\n            high = 2 * radius\n            mean = radius\n            std = spikeyness\n            a = (low - mean) / std\n            b = (high - mean) / std\n            tnorm = truncnorm(a=a, b=b, loc=mean, scale=std)\n\n            # now generate the points\n            radii = tnorm.rvs(n, random_state=rng)\n            x_pts = cx + radii * np.cos(angles)\n            y_pts = cy + radii * np.sin(angles)\n\n            points = np.hstack([x_pts[:, None], y_pts[:, None]])\n\n            # Scale to 0-1 space\n            points = points - points.min(axis=0)\n            points = points / points.max(axis=0)\n\n            # Randomly place within 0-1 space\n            points = points * (rng.rand() * .8 + .2)\n            min_pt = points.min(axis=0)\n            max_pt = points.max(axis=0)\n\n            high = (1 - max_pt)\n            low = (0 - min_pt)\n            offset = (rng.rand(2) * (high - low)) + low\n            points = points + offset\n            return points\n\n        def _order_vertices(verts):\n            \"\"\"\n            References:\n                https://stackoverflow.com/questions/1709283/how-can-i-sort-a-coordinate-list-for-a-rectangle-counterclockwise\n            \"\"\"\n            mlat = verts.T[0].sum() / len(verts)\n            mlng = verts.T[1].sum() / len(verts)\n\n            tau = np.pi * 2\n            angle = (np.arctan2(mlat - verts.T[0], verts.T[1] - mlng) +\n                     tau) % tau\n            sortx = angle.argsort()\n            verts = verts.take(sortx, axis=0)\n            return verts\n\n        # Generate a random exterior for each requested mask\n        masks = []\n        for _ in range(num_masks):\n            exterior = _order_vertices(_gen_polygon(n_verts, 0.9, 0.9))\n            exterior = (exterior * [(width, height)]).astype(dtype)\n            masks.append([exterior.ravel()])\n\n        self = cls(masks, height, width)\n        return self\n\n\ndef polygon_to_bitmap(polygons, height, width):\n    \"\"\"Convert masks from the form of polygons to bitmaps.\n\n    Args:\n        polygons (list[ndarray]): masks in polygon representation\n        height (int): mask height\n        width (int): mask width\n\n    Return:\n        ndarray: the converted masks in bitmap representation\n    \"\"\"\n    rles = maskUtils.frPyObjects(polygons, height, width)\n    rle = maskUtils.merge(rles)\n    bitmap_mask = maskUtils.decode(rle).astype(np.bool)\n    return bitmap_mask\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/mask/utils.py",
    "content": "from mmcv.utils import slice_list\nimport numpy as np\nimport pycocotools.mask as mask_util\n\n\ndef split_combined_polys(polys, poly_lens, polys_per_mask):\n    \"\"\"Split the combined 1-D polys into masks.\n\n    A mask is represented as a list of polys, and a poly is represented as\n    a 1-D array. In dataset, all masks are concatenated into a single 1-D\n    tensor. Here we need to split the tensor into original representations.\n\n    Args:\n        polys (list): a list (length = image num) of 1-D tensors\n        poly_lens (list): a list (length = image num) of poly length\n        polys_per_mask (list): a list (length = image num) of poly number\n            of each mask\n\n    Returns:\n        list: a list (length = image num) of list (length = mask num) of \\\n            list (length = poly num) of numpy array.\n    \"\"\"\n    mask_polys_list = []\n    for img_id in range(len(polys)):\n        polys_single = polys[img_id]\n        polys_lens_single = poly_lens[img_id].tolist()\n        polys_per_mask_single = polys_per_mask[img_id].tolist()\n\n        split_polys = slice_list(polys_single, polys_lens_single)\n        mask_polys = slice_list(split_polys, polys_per_mask_single)\n        mask_polys_list.append(mask_polys)\n    return mask_polys_list\n\n\n# TODO: move this function to more proper place\ndef encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code.\n\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    if isinstance(mask_results, tuple):  # mask scoring\n        cls_segms, cls_mask_scores = mask_results\n    else:\n        cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = [[] for _ in range(num_classes)]\n    for i in range(len(cls_segms)):\n        for cls_segm in cls_segms[i]:\n            encoded_mask_results[i].append(\n                mask_util.encode(\n                    np.array(\n                        cls_segm[:, :, np.newaxis], order='F',\n                        dtype='uint8'))[0])  # encoded with RLE\n    if isinstance(mask_results, tuple):\n        return encoded_mask_results, cls_mask_scores\n    else:\n        return encoded_mask_results\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/points/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\nfrom .cam_points import CameraPoints\nfrom .depth_points import DepthPoints\nfrom .lidar_points import LiDARPoints\n\n__all__ = ['BasePoints', 'CameraPoints', 'DepthPoints', 'LiDARPoints']\n\n\ndef get_points_type(points_type):\n    \"\"\"Get the class of points according to coordinate type.\n\n    Args:\n        points_type (str): The type of points coordinate.\n            The valid value are \"CAMERA\", \"LIDAR\", or \"DEPTH\".\n\n    Returns:\n        class: Points type.\n    \"\"\"\n    if points_type == 'CAMERA':\n        points_cls = CameraPoints\n    elif points_type == 'LIDAR':\n        points_cls = LiDARPoints\n    elif points_type == 'DEPTH':\n        points_cls = DepthPoints\n    else:\n        raise ValueError('Only \"points_type\" of \"CAMERA\", \"LIDAR\", or \"DEPTH\"'\n                         f' are supported, got {points_type}')\n\n    return points_cls\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/points/base_points.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nimport warnings\nfrom abc import abstractmethod\n\n\nclass BasePoints(object):\n    \"\"\"Base class for Points.\n\n    Args:\n        tensor (torch.Tensor | np.ndarray | list): a N x points_dim matrix.\n        points_dim (int): Number of the dimension of a point.\n            Each row is (x, y, z). Default to 3.\n        attribute_dims (dict): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x points_dim.\n        points_dim (int): Integer indicating the dimension of a point.\n            Each row is (x, y, z, ...).\n        attribute_dims (bool): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n        rotation_axis (int): Default rotation axis for points rotation.\n    \"\"\"\n\n    def __init__(self, tensor, points_dim=3, attribute_dims=None):\n        if isinstance(tensor, torch.Tensor):\n            device = tensor.device\n        else:\n            device = torch.device('cpu')\n        tensor = torch.as_tensor(tensor, dtype=torch.float32, device=device)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that\n            # does not depend on the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((0, points_dim)).to(\n                dtype=torch.float32, device=device)\n        assert tensor.dim() == 2 and tensor.size(-1) == \\\n            points_dim, tensor.size()\n\n        self.tensor = tensor\n        self.points_dim = points_dim\n        self.attribute_dims = attribute_dims\n        self.rotation_axis = 0\n\n    @property\n    def coord(self):\n        \"\"\"torch.Tensor: Coordinates of each point with size (N, 3).\"\"\"\n        return self.tensor[:, :3]\n\n    @coord.setter\n    def coord(self, tensor):\n        \"\"\"Set the coordinates of each point.\"\"\"\n        try:\n            tensor = tensor.reshape(self.shape[0], 3)\n        except (RuntimeError, ValueError):  # for torch.Tensor and np.ndarray\n            raise ValueError(f'got unexpected shape {tensor.shape}')\n        if not isinstance(tensor, torch.Tensor):\n            tensor = self.tensor.new_tensor(tensor)\n        self.tensor[:, :3] = tensor\n\n    @property\n    def height(self):\n        \"\"\"torch.Tensor: A vector with height of each point.\"\"\"\n        if self.attribute_dims is not None and \\\n                'height' in self.attribute_dims.keys():\n            return self.tensor[:, self.attribute_dims['height']]\n        else:\n            return None\n\n    @height.setter\n    def height(self, tensor):\n        \"\"\"Set the height of each point.\"\"\"\n        try:\n            tensor = tensor.reshape(self.shape[0])\n        except (RuntimeError, ValueError):  # for torch.Tensor and np.ndarray\n            raise ValueError(f'got unexpected shape {tensor.shape}')\n        if not isinstance(tensor, torch.Tensor):\n            tensor = self.tensor.new_tensor(tensor)\n        if self.attribute_dims is not None and \\\n                'height' in self.attribute_dims.keys():\n            self.tensor[:, self.attribute_dims['height']] = tensor\n        else:\n            # add height attribute\n            if self.attribute_dims is None:\n                self.attribute_dims = dict()\n            attr_dim = self.shape[1]\n            self.tensor = torch.cat([self.tensor, tensor.unsqueeze(1)], dim=1)\n            self.attribute_dims.update(dict(height=attr_dim))\n            self.points_dim += 1\n\n    @property\n    def color(self):\n        \"\"\"torch.Tensor: A vector with color of each point.\"\"\"\n        if self.attribute_dims is not None and \\\n                'color' in self.attribute_dims.keys():\n            return self.tensor[:, self.attribute_dims['color']]\n        else:\n            return None\n\n    @color.setter\n    def color(self, tensor):\n        \"\"\"Set the color of each point.\"\"\"\n        try:\n            tensor = tensor.reshape(self.shape[0], 3)\n        except (RuntimeError, ValueError):  # for torch.Tensor and np.ndarray\n            raise ValueError(f'got unexpected shape {tensor.shape}')\n        if tensor.max() >= 256 or tensor.min() < 0:\n            warnings.warn('point got color value beyond [0, 255]')\n        if not isinstance(tensor, torch.Tensor):\n            tensor = self.tensor.new_tensor(tensor)\n        if self.attribute_dims is not None and \\\n                'color' in self.attribute_dims.keys():\n            self.tensor[:, self.attribute_dims['color']] = tensor\n        else:\n            # add color attribute\n            if self.attribute_dims is None:\n                self.attribute_dims = dict()\n            attr_dim = self.shape[1]\n            self.tensor = torch.cat([self.tensor, tensor], dim=1)\n            self.attribute_dims.update(\n                dict(color=[attr_dim, attr_dim + 1, attr_dim + 2]))\n            self.points_dim += 3\n\n    @property\n    def shape(self):\n        \"\"\"torch.Shape: Shape of points.\"\"\"\n        return self.tensor.shape\n\n    def shuffle(self):\n        \"\"\"Shuffle the points.\n\n        Returns:\n            torch.Tensor: The shuffled index.\n        \"\"\"\n        idx = torch.randperm(self.__len__(), device=self.tensor.device)\n        self.tensor = self.tensor[idx]\n        return idx\n\n    def rotate(self, rotation, axis=None):\n        \"\"\"Rotate points with the given rotation matrix or angle.\n\n        Args:\n            rotation (float, np.ndarray, torch.Tensor): Rotation matrix\n                or angle.\n            axis (int): Axis to rotate at. Defaults to None.\n        \"\"\"\n        if not isinstance(rotation, torch.Tensor):\n            rotation = self.tensor.new_tensor(rotation)\n        assert rotation.shape == torch.Size([3, 3]) or \\\n            rotation.numel() == 1, f'invalid rotation shape {rotation.shape}'\n\n        if axis is None:\n            axis = self.rotation_axis\n\n        if rotation.numel() == 1:\n            rot_sin = torch.sin(rotation)\n            rot_cos = torch.cos(rotation)\n            if axis == 1:\n                rot_mat_T = rotation.new_tensor([[rot_cos, 0, -rot_sin],\n                                                 [0, 1, 0],\n                                                 [rot_sin, 0, rot_cos]])\n            elif axis == 2 or axis == -1:\n                rot_mat_T = rotation.new_tensor([[rot_cos, -rot_sin, 0],\n                                                 [rot_sin, rot_cos, 0],\n                                                 [0, 0, 1]])\n            elif axis == 0:\n                rot_mat_T = rotation.new_tensor([[0, rot_cos, -rot_sin],\n                                                 [0, rot_sin, rot_cos],\n                                                 [1, 0, 0]])\n            else:\n                raise ValueError('axis should in range')\n            rot_mat_T = rot_mat_T.T\n        elif rotation.numel() == 9:\n            rot_mat_T = rotation\n        else:\n            raise NotImplementedError\n        self.tensor[:, :3] = self.tensor[:, :3] @ rot_mat_T\n\n        return rot_mat_T\n\n    @abstractmethod\n    def flip(self, bev_direction='horizontal'):\n        \"\"\"Flip the points in BEV along given BEV direction.\"\"\"\n        pass\n\n    def translate(self, trans_vector):\n        \"\"\"Translate points with the given translation vector.\n\n        Args:\n            trans_vector (np.ndarray, torch.Tensor): Translation\n                vector of size 3 or nx3.\n        \"\"\"\n        if not isinstance(trans_vector, torch.Tensor):\n            trans_vector = self.tensor.new_tensor(trans_vector)\n        trans_vector = trans_vector.squeeze(0)\n        if trans_vector.dim() == 1:\n            assert trans_vector.shape[0] == 3\n        elif trans_vector.dim() == 2:\n            assert trans_vector.shape[0] == self.tensor.shape[0] and \\\n                trans_vector.shape[1] == 3\n        else:\n            raise NotImplementedError(\n                f'Unsupported translation vector of shape {trans_vector.shape}'\n            )\n        self.tensor[:, :3] += trans_vector\n\n    def in_range_3d(self, point_range):\n        \"\"\"Check whether the points are in the given range.\n\n        Args:\n            point_range (list | torch.Tensor): The range of point\n                (x_min, y_min, z_min, x_max, y_max, z_max)\n\n        Note:\n            In the original implementation of SECOND, checking whether\n            a box in the range checks whether the points are in a convex\n            polygon, we try to reduce the burden for simpler cases.\n\n        Returns:\n            torch.Tensor: A binary vector indicating whether each point is \\\n                inside the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > point_range[0])\n                          & (self.tensor[:, 1] > point_range[1])\n                          & (self.tensor[:, 2] > point_range[2])\n                          & (self.tensor[:, 0] < point_range[3])\n                          & (self.tensor[:, 1] < point_range[4])\n                          & (self.tensor[:, 2] < point_range[5]))\n        return in_range_flags\n\n    @abstractmethod\n    def in_range_bev(self, point_range):\n        \"\"\"Check whether the points are in the given range.\n\n        Args:\n            point_range (list | torch.Tensor): The range of point\n                in order of (x_min, y_min, x_max, y_max).\n\n        Returns:\n            torch.Tensor: Indicating whether each point is inside \\\n                the reference range.\n        \"\"\"\n        pass\n\n    @abstractmethod\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`CoordMode`): The target Box mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BasePoints`: The converted box of the same type \\\n                in the `dst` mode.\n        \"\"\"\n        pass\n\n    def scale(self, scale_factor):\n        \"\"\"Scale the points with horizontal and vertical scaling factors.\n\n        Args:\n            scale_factors (float): Scale factors to scale the points.\n        \"\"\"\n        self.tensor[:, :3] *= scale_factor\n\n    def __getitem__(self, item):\n        \"\"\"\n        Note:\n            The following usage are allowed:\n            1. `new_points = points[3]`:\n                return a `Points` that contains only one point.\n            2. `new_points = points[2:10]`:\n                return a slice of points.\n            3. `new_points = points[vector]`:\n                where vector is a torch.BoolTensor with `length = len(points)`.\n                Nonzero elements in the vector will be selected.\n            4. `new_points = points[3:11, vector]`:\n                return a slice of points and attribute dims.\n            5. `new_points = points[4:12, 2]`:\n                return a slice of points with single attribute.\n            Note that the returned Points might share storage with this Points,\n            subject to Pytorch's indexing semantics.\n\n        Returns:\n            :obj:`BasePoints`: A new object of  \\\n                :class:`BasePoints` after indexing.\n        \"\"\"\n        original_type = type(self)\n        if isinstance(item, int):\n            return original_type(\n                self.tensor[item].view(1, -1),\n                points_dim=self.points_dim,\n                attribute_dims=self.attribute_dims)\n        elif isinstance(item, tuple) and len(item) == 2:\n            if isinstance(item[1], slice):\n                start = 0 if item[1].start is None else item[1].start\n                stop = self.tensor.shape[1] if \\\n                    item[1].stop is None else item[1].stop\n                step = 1 if item[1].step is None else item[1].step\n                item = list(item)\n                item[1] = list(range(start, stop, step))\n                item = tuple(item)\n            elif isinstance(item[1], int):\n                item = list(item)\n                item[1] = [item[1]]\n                item = tuple(item)\n            p = self.tensor[item[0], item[1]]\n\n            keep_dims = list(\n                set(item[1]).intersection(set(range(3, self.tensor.shape[1]))))\n            if self.attribute_dims is not None:\n                attribute_dims = self.attribute_dims.copy()\n                for key in self.attribute_dims.keys():\n                    cur_attribute_dims = attribute_dims[key]\n                    if isinstance(cur_attribute_dims, int):\n                        cur_attribute_dims = [cur_attribute_dims]\n                    intersect_attr = list(\n                        set(cur_attribute_dims).intersection(set(keep_dims)))\n                    if len(intersect_attr) == 1:\n                        attribute_dims[key] = intersect_attr[0]\n                    elif len(intersect_attr) > 1:\n                        attribute_dims[key] = intersect_attr\n                    else:\n                        attribute_dims.pop(key)\n            else:\n                attribute_dims = None\n        elif isinstance(item, (slice, np.ndarray, torch.Tensor)):\n            p = self.tensor[item]\n            attribute_dims = self.attribute_dims\n        else:\n            raise NotImplementedError(f'Invalid slice {item}!')\n\n        assert p.dim() == 2, \\\n            f'Indexing on Points with {item} failed to return a matrix!'\n        return original_type(\n            p, points_dim=p.shape[1], attribute_dims=attribute_dims)\n\n    def __len__(self):\n        \"\"\"int: Number of points in the current object.\"\"\"\n        return self.tensor.shape[0]\n\n    def __repr__(self):\n        \"\"\"str: Return a strings that describes the object.\"\"\"\n        return self.__class__.__name__ + '(\\n    ' + str(self.tensor) + ')'\n\n    @classmethod\n    def cat(cls, points_list):\n        \"\"\"Concatenate a list of Points into a single Points.\n\n        Args:\n            points_list (list[:obj:`BasePoints`]): List of points.\n\n        Returns:\n            :obj:`BasePoints`: The concatenated Points.\n        \"\"\"\n        assert isinstance(points_list, (list, tuple))\n        if len(points_list) == 0:\n            return cls(torch.empty(0))\n        assert all(isinstance(points, cls) for points in points_list)\n\n        # use torch.cat (v.s. layers.cat)\n        # so the returned points never share storage with input\n        cat_points = cls(\n            torch.cat([p.tensor for p in points_list], dim=0),\n            points_dim=points_list[0].tensor.shape[1],\n            attribute_dims=points_list[0].attribute_dims)\n        return cat_points\n\n    def to(self, device):\n        \"\"\"Convert current points to a specific device.\n\n        Args:\n            device (str | :obj:`torch.device`): The name of the device.\n\n        Returns:\n            :obj:`BasePoints`: A new boxes object on the \\\n                specific device.\n        \"\"\"\n        original_type = type(self)\n        return original_type(\n            self.tensor.to(device),\n            points_dim=self.points_dim,\n            attribute_dims=self.attribute_dims)\n\n    def clone(self):\n        \"\"\"Clone the Points.\n\n        Returns:\n            :obj:`BasePoints`: Box object with the same properties \\\n                as self.\n        \"\"\"\n        original_type = type(self)\n        return original_type(\n            self.tensor.clone(),\n            points_dim=self.points_dim,\n            attribute_dims=self.attribute_dims)\n\n    @property\n    def device(self):\n        \"\"\"str: The device of the points are on.\"\"\"\n        return self.tensor.device\n\n    def __iter__(self):\n        \"\"\"Yield a point as a Tensor of shape (4,) at a time.\n\n        Returns:\n            torch.Tensor: A point of shape (4,).\n        \"\"\"\n        yield from self.tensor\n\n    def new_point(self, data):\n        \"\"\"Create a new point object with data.\n\n        The new point and its tensor has the similar properties \\\n            as self and self.tensor, respectively.\n\n        Args:\n            data (torch.Tensor | numpy.array | list): Data to be copied.\n\n        Returns:\n            :obj:`BasePoints`: A new point object with ``data``, \\\n                the object's other properties are similar to ``self``.\n        \"\"\"\n        new_tensor = self.tensor.new_tensor(data) \\\n            if not isinstance(data, torch.Tensor) else data.to(self.device)\n        original_type = type(self)\n        return original_type(\n            new_tensor,\n            points_dim=self.points_dim,\n            attribute_dims=self.attribute_dims)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/points/cam_points.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\n\n\nclass CameraPoints(BasePoints):\n    \"\"\"Points of instances in CAM coordinates.\n\n    Args:\n        tensor (torch.Tensor | np.ndarray | list): a N x points_dim matrix.\n        points_dim (int): Number of the dimension of a point.\n            Each row is (x, y, z). Default to 3.\n        attribute_dims (dict): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x points_dim.\n        points_dim (int): Integer indicating the dimension of a point.\n            Each row is (x, y, z, ...).\n        attribute_dims (bool): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n        rotation_axis (int): Default rotation axis for points rotation.\n    \"\"\"\n\n    def __init__(self, tensor, points_dim=3, attribute_dims=None):\n        super(CameraPoints, self).__init__(\n            tensor, points_dim=points_dim, attribute_dims=attribute_dims)\n        self.rotation_axis = 1\n\n    def flip(self, bev_direction='horizontal'):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\"\"\"\n        if bev_direction == 'horizontal':\n            self.tensor[:, 0] = -self.tensor[:, 0]\n        elif bev_direction == 'vertical':\n            self.tensor[:, 2] = -self.tensor[:, 2]\n\n    def in_range_bev(self, point_range):\n        \"\"\"Check whether the points are in the given range.\n\n        Args:\n            point_range (list | torch.Tensor): The range of point\n                in order of (x_min, y_min, x_max, y_max).\n\n        Returns:\n            torch.Tensor: Indicating whether each point is inside \\\n                the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > point_range[0])\n                          & (self.tensor[:, 2] > point_range[1])\n                          & (self.tensor[:, 0] < point_range[2])\n                          & (self.tensor[:, 2] < point_range[3]))\n        return in_range_flags\n\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`CoordMode`): The target Point mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BasePoints`: The converted point of the same type \\\n                in the `dst` mode.\n        \"\"\"\n        from mmcv.core.bbox import Coord3DMode\n        return Coord3DMode.convert_point(\n            point=self, src=Coord3DMode.CAM, dst=dst, rt_mat=rt_mat)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/points/depth_points.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\n\n\nclass DepthPoints(BasePoints):\n    \"\"\"Points of instances in DEPTH coordinates.\n\n    Args:\n        tensor (torch.Tensor | np.ndarray | list): a N x points_dim matrix.\n        points_dim (int): Number of the dimension of a point.\n            Each row is (x, y, z). Default to 3.\n        attribute_dims (dict): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x points_dim.\n        points_dim (int): Integer indicating the dimension of a point.\n            Each row is (x, y, z, ...).\n        attribute_dims (bool): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n        rotation_axis (int): Default rotation axis for points rotation.\n    \"\"\"\n\n    def __init__(self, tensor, points_dim=3, attribute_dims=None):\n        super(DepthPoints, self).__init__(\n            tensor, points_dim=points_dim, attribute_dims=attribute_dims)\n        self.rotation_axis = 2\n\n    def flip(self, bev_direction='horizontal'):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\"\"\"\n        if bev_direction == 'horizontal':\n            self.tensor[:, 0] = -self.tensor[:, 0]\n        elif bev_direction == 'vertical':\n            self.tensor[:, 1] = -self.tensor[:, 1]\n\n    def in_range_bev(self, point_range):\n        \"\"\"Check whether the points are in the given range.\n\n        Args:\n            point_range (list | torch.Tensor): The range of point\n                in order of (x_min, y_min, x_max, y_max).\n\n        Returns:\n            torch.Tensor: Indicating whether each point is inside \\\n                the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > point_range[0])\n                          & (self.tensor[:, 1] > point_range[1])\n                          & (self.tensor[:, 0] < point_range[2])\n                          & (self.tensor[:, 1] < point_range[3]))\n        return in_range_flags\n\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`CoordMode`): The target Point mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BasePoints`: The converted point of the same type \\\n                in the `dst` mode.\n        \"\"\"\n        from mmcv.core.bbox import Coord3DMode\n        return Coord3DMode.convert_point(\n            point=self, src=Coord3DMode.DEPTH, dst=dst, rt_mat=rt_mat)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/points/lidar_points.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\n\n\nclass LiDARPoints(BasePoints):\n    \"\"\"Points of instances in LIDAR coordinates.\n\n    Args:\n        tensor (torch.Tensor | np.ndarray | list): a N x points_dim matrix.\n        points_dim (int): Number of the dimension of a point.\n            Each row is (x, y, z). Default to 3.\n        attribute_dims (dict): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n\n    Attributes:\n        tensor (torch.Tensor): Float matrix of N x points_dim.\n        points_dim (int): Integer indicating the dimension of a point.\n            Each row is (x, y, z, ...).\n        attribute_dims (bool): Dictionary to indicate the meaning of extra\n            dimension. Default to None.\n        rotation_axis (int): Default rotation axis for points rotation.\n    \"\"\"\n\n    def __init__(self, tensor, points_dim=3, attribute_dims=None):\n        super(LiDARPoints, self).__init__(\n            tensor, points_dim=points_dim, attribute_dims=attribute_dims)\n        self.rotation_axis = 2\n\n    def flip(self, bev_direction='horizontal'):\n        \"\"\"Flip the boxes in BEV along given BEV direction.\"\"\"\n        if bev_direction == 'horizontal':\n            self.tensor[:, 1] = -self.tensor[:, 1]\n        elif bev_direction == 'vertical':\n            self.tensor[:, 0] = -self.tensor[:, 0]\n\n    def in_range_bev(self, point_range):\n        \"\"\"Check whether the points are in the given range.\n\n        Args:\n            point_range (list | torch.Tensor): The range of point\n                in order of (x_min, y_min, x_max, y_max).\n\n        Returns:\n            torch.Tensor: Indicating whether each point is inside \\\n                the reference range.\n        \"\"\"\n        in_range_flags = ((self.tensor[:, 0] > point_range[0])\n                          & (self.tensor[:, 1] > point_range[1])\n                          & (self.tensor[:, 0] < point_range[2])\n                          & (self.tensor[:, 1] < point_range[3]))\n        return in_range_flags\n\n    def convert_to(self, dst, rt_mat=None):\n        \"\"\"Convert self to ``dst`` mode.\n\n        Args:\n            dst (:obj:`CoordMode`): The target Point mode.\n            rt_mat (np.ndarray | torch.Tensor): The rotation and translation\n                matrix between different coordinates. Defaults to None.\n                The conversion from `src` coordinates to `dst` coordinates\n                usually comes along the change of sensors, e.g., from camera\n                to LiDAR. This requires a transformation matrix.\n\n        Returns:\n            :obj:`BasePoints`: The converted point of the same type \\\n                in the `dst` mode.\n        \"\"\"\n        from mmcv.core.bbox import Coord3DMode\n        return Coord3DMode.convert_point(\n            point=self, src=Coord3DMode.LIDAR, dst=dst, rt_mat=rt_mat)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/post_processing/__init__.py",
    "content": "# from .merge_augs import (merge_aug_bboxes, merge_aug_masks,\n#                          merge_aug_scores, merge_aug_bboxes_3d)\nfrom .box3d_nms import aligned_3d_nms, box3d_multiclass_nms, circle_nms\n\n# __all__ = [\n#     'merge_aug_bboxes',\n#     'merge_aug_scores', 'merge_aug_masks', 'box3d_multiclass_nms',\n#     'aligned_3d_nms', 'merge_aug_bboxes_3d', 'circle_nms'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/post_processing/bbox_nms.py",
    "content": "import torch\nfrom mmcv.ops.nms import batched_nms\n\nfrom mmcv.core.bbox.iou_calculators import bbox_overlaps\n\n\ndef multiclass_nms(multi_bboxes,\n                   multi_scores,\n                   score_thr,\n                   nms_cfg,\n                   max_num=-1,\n                   score_factors=None,\n                   return_inds=False):\n    \"\"\"NMS for multi-class bboxes.\n\n    Args:\n        multi_bboxes (Tensor): shape (n, #class*4) or (n, 4)\n        multi_scores (Tensor): shape (n, #class), where the last column\n            contains scores of the background class, but this will be ignored.\n        score_thr (float): bbox threshold, bboxes with scores lower than it\n            will not be considered.\n        nms_thr (float): NMS IoU threshold\n        max_num (int, optional): if there are more than max_num bboxes after\n            NMS, only top max_num will be kept. Default to -1.\n        score_factors (Tensor, optional): The factors multiplied to scores\n            before applying NMS. Default to None.\n        return_inds (bool, optional): Whether return the indices of kept\n            bboxes. Default to False.\n\n    Returns:\n        tuple: (dets, labels, indices (optional)), tensors of shape (k, 5),\n            (k), and (k). Dets are boxes with scores. Labels are 0-based.\n    \"\"\"\n    num_classes = multi_scores.size(1) - 1\n    # exclude background category\n    if multi_bboxes.shape[1] > 4:\n        bboxes = multi_bboxes.view(multi_scores.size(0), -1, 4)\n    else:\n        bboxes = multi_bboxes[:, None].expand(\n            multi_scores.size(0), num_classes, 4)\n\n    scores = multi_scores[:, :-1]\n\n    labels = torch.arange(num_classes, dtype=torch.long)\n    labels = labels.view(1, -1).expand_as(scores)\n\n    bboxes = bboxes.reshape(-1, 4)\n    scores = scores.reshape(-1)\n    labels = labels.reshape(-1)\n\n    if not torch.onnx.is_in_onnx_export():\n        # NonZero not supported  in TensorRT\n        # remove low scoring boxes\n        valid_mask = scores > score_thr\n    # multiply score_factor after threshold to preserve more bboxes, improve\n    # mAP by 1% for YOLOv3\n    if score_factors is not None:\n        # expand the shape to match original shape of score\n        score_factors = score_factors.view(-1, 1).expand(\n            multi_scores.size(0), num_classes)\n        score_factors = score_factors.reshape(-1)\n        scores = scores * score_factors\n\n    if not torch.onnx.is_in_onnx_export():\n        # NonZero not supported  in TensorRT\n        inds = valid_mask.nonzero(as_tuple=False).squeeze(1)\n        bboxes, scores, labels = bboxes[inds], scores[inds], labels[inds]\n    else:\n        # TensorRT NMS plugin has invalid output filled with -1\n        # add dummy data to make detection output correct.\n        bboxes = torch.cat([bboxes, bboxes.new_zeros(1, 4)], dim=0)\n        scores = torch.cat([scores, scores.new_zeros(1)], dim=0)\n        labels = torch.cat([labels, labels.new_zeros(1)], dim=0)\n\n    if bboxes.numel() == 0:\n        if torch.onnx.is_in_onnx_export():\n            raise RuntimeError('[ONNX Error] Can not record NMS '\n                               'as it has not been executed this time')\n        dets = torch.cat([bboxes, scores[:, None]], -1)\n        if return_inds:\n            return dets, labels, inds\n        else:\n            return dets, labels\n\n    dets, keep = batched_nms(bboxes, scores, labels, nms_cfg)\n\n    if max_num > 0:\n        dets = dets[:max_num]\n        keep = keep[:max_num]\n\n    if return_inds:\n        return dets, labels[keep], keep\n    else:\n        return dets, labels[keep]\n\n\ndef fast_nms(multi_bboxes,\n             multi_scores,\n             multi_coeffs,\n             score_thr,\n             iou_thr,\n             top_k,\n             max_num=-1):\n    \"\"\"Fast NMS in `YOLACT <https://arxiv.org/abs/1904.02689>`_.\n\n    Fast NMS allows already-removed detections to suppress other detections so\n    that every instance can be decided to be kept or discarded in parallel,\n    which is not possible in traditional NMS. This relaxation allows us to\n    implement Fast NMS entirely in standard GPU-accelerated matrix operations.\n\n    Args:\n        multi_bboxes (Tensor): shape (n, #class*4) or (n, 4)\n        multi_scores (Tensor): shape (n, #class+1), where the last column\n            contains scores of the background class, but this will be ignored.\n        multi_coeffs (Tensor): shape (n, #class*coeffs_dim).\n        score_thr (float): bbox threshold, bboxes with scores lower than it\n            will not be considered.\n        iou_thr (float): IoU threshold to be considered as conflicted.\n        top_k (int): if there are more than top_k bboxes before NMS,\n            only top top_k will be kept.\n        max_num (int): if there are more than max_num bboxes after NMS,\n            only top max_num will be kept. If -1, keep all the bboxes.\n            Default: -1.\n\n    Returns:\n        tuple: (dets, labels, coefficients), tensors of shape (k, 5), (k, 1),\n            and (k, coeffs_dim). Dets are boxes with scores.\n            Labels are 0-based.\n    \"\"\"\n\n    scores = multi_scores[:, :-1].t()  # [#class, n]\n    scores, idx = scores.sort(1, descending=True)\n\n    idx = idx[:, :top_k].contiguous()\n    scores = scores[:, :top_k]  # [#class, topk]\n    num_classes, num_dets = idx.size()\n    boxes = multi_bboxes[idx.view(-1), :].view(num_classes, num_dets, 4)\n    coeffs = multi_coeffs[idx.view(-1), :].view(num_classes, num_dets, -1)\n\n    iou = bbox_overlaps(boxes, boxes)  # [#class, topk, topk]\n    iou.triu_(diagonal=1)\n    iou_max, _ = iou.max(dim=1)\n\n    # Now just filter out the ones higher than the threshold\n    keep = iou_max <= iou_thr\n\n    # Second thresholding introduces 0.2 mAP gain at negligible time cost\n    keep *= scores > score_thr\n\n    # Assign each kept detection to its corresponding class\n    classes = torch.arange(\n        num_classes, device=boxes.device)[:, None].expand_as(keep)\n    classes = classes[keep]\n\n    boxes = boxes[keep]\n    coeffs = coeffs[keep]\n    scores = scores[keep]\n\n    # Only keep the top max_num highest scores across all classes\n    scores, idx = scores.sort(0, descending=True)\n    if max_num > 0:\n        idx = idx[:max_num]\n        scores = scores[:max_num]\n\n    classes = classes[idx]\n    boxes = boxes[idx]\n    coeffs = coeffs[idx]\n\n    cls_dets = torch.cat([boxes, scores[:, None]], dim=1)\n    return cls_dets, classes, coeffs\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/post_processing/box3d_nms.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numba\nimport numpy as np\nimport torch\n\nfrom mmcv.ops.iou3d_det.iou3d_utils import nms_gpu, nms_normal_gpu\n\n\ndef box3d_multiclass_nms(mlvl_bboxes,\n                         mlvl_bboxes_for_nms,\n                         mlvl_scores,\n                         score_thr,\n                         max_num,\n                         cfg,\n                         mlvl_dir_scores=None,\n                         mlvl_attr_scores=None,\n                         mlvl_bboxes2d=None):\n    \"\"\"Multi-class nms for 3D boxes.\n\n    Args:\n        mlvl_bboxes (torch.Tensor): Multi-level boxes with shape (N, M).\n            M is the dimensions of boxes.\n        mlvl_bboxes_for_nms (torch.Tensor): Multi-level boxes with shape\n            (N, 5) ([x1, y1, x2, y2, ry]). N is the number of boxes.\n        mlvl_scores (torch.Tensor): Multi-level boxes with shape\n            (N, C + 1). N is the number of boxes. C is the number of classes.\n        score_thr (float): Score thredhold to filter boxes with low\n            confidence.\n        max_num (int): Maximum number of boxes will be kept.\n        cfg (dict): Configuration dict of NMS.\n        mlvl_dir_scores (torch.Tensor, optional): Multi-level scores\n            of direction classifier. Defaults to None.\n        mlvl_attr_scores (torch.Tensor, optional): Multi-level scores\n            of attribute classifier. Defaults to None.\n        mlvl_bboxes2d (torch.Tensor, optional): Multi-level 2D bounding\n            boxes. Defaults to None.\n\n    Returns:\n        tuple[torch.Tensor]: Return results after nms, including 3D \\\n            bounding boxes, scores, labels, direction scores, attribute \\\n            scores (optional) and 2D bounding boxes (optional).\n    \"\"\"\n    # do multi class nms\n    # the fg class id range: [0, num_classes-1]\n    num_classes = mlvl_scores.shape[1] - 1\n    bboxes = []\n    scores = []\n    labels = []\n    dir_scores = []\n    attr_scores = []\n    bboxes2d = []\n    for i in range(0, num_classes):\n        # get bboxes and scores of this class\n        cls_inds = mlvl_scores[:, i] > score_thr\n        if not cls_inds.any():\n            continue\n\n        _scores = mlvl_scores[cls_inds, i]\n        _bboxes_for_nms = mlvl_bboxes_for_nms[cls_inds, :]\n\n        if cfg.use_rotate_nms:\n            nms_func = nms_gpu\n        else:\n            nms_func = nms_normal_gpu\n\n        selected = nms_func(_bboxes_for_nms, _scores, cfg.nms_thr)\n        _mlvl_bboxes = mlvl_bboxes[cls_inds, :]\n        bboxes.append(_mlvl_bboxes[selected])\n        scores.append(_scores[selected])\n        cls_label = mlvl_bboxes.new_full((len(selected), ),\n                                         i,\n                                         dtype=torch.long)\n        labels.append(cls_label)\n\n        if mlvl_dir_scores is not None:\n            _mlvl_dir_scores = mlvl_dir_scores[cls_inds]\n            dir_scores.append(_mlvl_dir_scores[selected])\n        if mlvl_attr_scores is not None:\n            _mlvl_attr_scores = mlvl_attr_scores[cls_inds]\n            attr_scores.append(_mlvl_attr_scores[selected])\n        if mlvl_bboxes2d is not None:\n            _mlvl_bboxes2d = mlvl_bboxes2d[cls_inds]\n            bboxes2d.append(_mlvl_bboxes2d[selected])\n\n    if bboxes:\n        bboxes = torch.cat(bboxes, dim=0)\n        scores = torch.cat(scores, dim=0)\n        labels = torch.cat(labels, dim=0)\n        if mlvl_dir_scores is not None:\n            dir_scores = torch.cat(dir_scores, dim=0)\n        if mlvl_attr_scores is not None:\n            attr_scores = torch.cat(attr_scores, dim=0)\n        if mlvl_bboxes2d is not None:\n            bboxes2d = torch.cat(bboxes2d, dim=0)\n        if bboxes.shape[0] > max_num:\n            _, inds = scores.sort(descending=True)\n            inds = inds[:max_num]\n            bboxes = bboxes[inds, :]\n            labels = labels[inds]\n            scores = scores[inds]\n            if mlvl_dir_scores is not None:\n                dir_scores = dir_scores[inds]\n            if mlvl_attr_scores is not None:\n                attr_scores = attr_scores[inds]\n            if mlvl_bboxes2d is not None:\n                bboxes2d = bboxes2d[inds]\n    else:\n        bboxes = mlvl_scores.new_zeros((0, mlvl_bboxes.size(-1)))\n        scores = mlvl_scores.new_zeros((0, ))\n        labels = mlvl_scores.new_zeros((0, ), dtype=torch.long)\n        if mlvl_dir_scores is not None:\n            dir_scores = mlvl_scores.new_zeros((0, ))\n        if mlvl_attr_scores is not None:\n            attr_scores = mlvl_scores.new_zeros((0, ))\n        if mlvl_bboxes2d is not None:\n            bboxes2d = mlvl_scores.new_zeros((0, 4))\n\n    results = (bboxes, scores, labels)\n\n    if mlvl_dir_scores is not None:\n        results = results + (dir_scores, )\n    if mlvl_attr_scores is not None:\n        results = results + (attr_scores, )\n    if mlvl_bboxes2d is not None:\n        results = results + (bboxes2d, )\n\n    return results\n\n\ndef aligned_3d_nms(boxes, scores, classes, thresh):\n    \"\"\"3d nms for aligned boxes.\n\n    Args:\n        boxes (torch.Tensor): Aligned box with shape [n, 6].\n        scores (torch.Tensor): Scores of each box.\n        classes (torch.Tensor): Class of each box.\n        thresh (float): Iou threshold for nms.\n\n    Returns:\n        torch.Tensor: Indices of selected boxes.\n    \"\"\"\n    x1 = boxes[:, 0]\n    y1 = boxes[:, 1]\n    z1 = boxes[:, 2]\n    x2 = boxes[:, 3]\n    y2 = boxes[:, 4]\n    z2 = boxes[:, 5]\n    area = (x2 - x1) * (y2 - y1) * (z2 - z1)\n    zero = boxes.new_zeros(1, )\n\n    score_sorted = torch.argsort(scores)\n    pick = []\n    while (score_sorted.shape[0] != 0):\n        last = score_sorted.shape[0]\n        i = score_sorted[-1]\n        pick.append(i)\n\n        xx1 = torch.max(x1[i], x1[score_sorted[:last - 1]])\n        yy1 = torch.max(y1[i], y1[score_sorted[:last - 1]])\n        zz1 = torch.max(z1[i], z1[score_sorted[:last - 1]])\n        xx2 = torch.min(x2[i], x2[score_sorted[:last - 1]])\n        yy2 = torch.min(y2[i], y2[score_sorted[:last - 1]])\n        zz2 = torch.min(z2[i], z2[score_sorted[:last - 1]])\n        classes1 = classes[i]\n        classes2 = classes[score_sorted[:last - 1]]\n        inter_l = torch.max(zero, xx2 - xx1)\n        inter_w = torch.max(zero, yy2 - yy1)\n        inter_h = torch.max(zero, zz2 - zz1)\n\n        inter = inter_l * inter_w * inter_h\n        iou = inter / (area[i] + area[score_sorted[:last - 1]] - inter)\n        iou = iou * (classes1 == classes2).float()\n        score_sorted = score_sorted[torch.nonzero(\n            iou <= thresh, as_tuple=False).flatten()]\n\n    indices = boxes.new_tensor(pick, dtype=torch.long)\n    return indices\n\n\n@numba.jit(nopython=True)\ndef circle_nms(dets, thresh, post_max_size=83):\n    \"\"\"Circular NMS.\n\n    An object is only counted as positive if no other center\n    with a higher confidence exists within a radius r using a\n    bird-eye view distance metric.\n\n    Args:\n        dets (torch.Tensor): Detection results with the shape of [N, 3].\n        thresh (float): Value of threshold.\n        post_max_size (int): Max number of prediction to be kept. Defaults\n            to 83\n\n    Returns:\n        torch.Tensor: Indexes of the detections to be kept.\n    \"\"\"\n    x1 = dets[:, 0]\n    y1 = dets[:, 1]\n    scores = dets[:, 2]\n    order = scores.argsort()[::-1].astype(np.int32)  # highest->lowest\n    ndets = dets.shape[0]\n    suppressed = np.zeros((ndets), dtype=np.int32)\n    keep = []\n    for _i in range(ndets):\n        i = order[_i]  # start with highest score box\n        if suppressed[\n                i] == 1:  # if any box have enough iou with this, remove it\n            continue\n        keep.append(i)\n        for _j in range(_i + 1, ndets):\n            j = order[_j]\n            if suppressed[j] == 1:\n                continue\n            # calculate center distance between i and j box\n            dist = (x1[i] - x1[j])**2 + (y1[i] - y1[j])**2\n\n            # ovr = inter / areas[j]\n            if dist <= thresh:\n                suppressed[j] = 1\n    return keep[:post_max_size]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/post_processing/merge_augs.py",
    "content": "import copy\nimport warnings\n\nimport numpy as np\nimport torch\nfrom mmcv import ConfigDict\nfrom mmcv.ops import nms\n\nfrom mmcv.ops.iou3d_det.iou3d_utils import nms_gpu, nms_normal_gpu\nfrom ..bbox.transforms import bbox_mapping_back, bbox3d2result, bbox3d_mapping_back\nfrom ..bbox.structures.utils import xywhr2xyxyr\n\ndef merge_aug_proposals(aug_proposals, img_metas, cfg):\n    \"\"\"Merge augmented proposals (multiscale, flip, etc.)\n\n    Args:\n        aug_proposals (list[Tensor]): proposals from different testing\n            schemes, shape (n, 5). Note that they are not rescaled to the\n            original image size.\n\n        img_metas (list[dict]): list of image info dict where each dict has:\n            'img_shape', 'scale_factor', 'flip', and may also contain\n            'filename', 'ori_shape', 'pad_shape', and 'img_norm_cfg'.\n            For details on the values of these keys see\n            `mmcv/datasets/pipelines/formatting.py:Collect`.\n\n        cfg (dict): rpn test config.\n\n    Returns:\n        Tensor: shape (n, 4), proposals corresponding to original image scale.\n    \"\"\"\n\n    cfg = copy.deepcopy(cfg)\n\n    # deprecate arguments warning\n    if 'nms' not in cfg or 'max_num' in cfg or 'nms_thr' in cfg:\n        warnings.warn(\n            'In rpn_proposal or test_cfg, '\n            'nms_thr has been moved to a dict named nms as '\n            'iou_threshold, max_num has been renamed as max_per_img, '\n            'name of original arguments and the way to specify '\n            'iou_threshold of NMS will be deprecated.')\n    if 'nms' not in cfg:\n        cfg.nms = ConfigDict(dict(type='nms', iou_threshold=cfg.nms_thr))\n    if 'max_num' in cfg:\n        if 'max_per_img' in cfg:\n            assert cfg.max_num == cfg.max_per_img, f'You set max_num and ' \\\n                f'max_per_img at the same time, but get {cfg.max_num} ' \\\n                f'and {cfg.max_per_img} respectively' \\\n                f'Please delete max_num which will be deprecated.'\n        else:\n            cfg.max_per_img = cfg.max_num\n    if 'nms_thr' in cfg:\n        assert cfg.nms.iou_threshold == cfg.nms_thr, f'You set ' \\\n            f'iou_threshold in nms and ' \\\n            f'nms_thr at the same time, but get ' \\\n            f'{cfg.nms.iou_threshold} and {cfg.nms_thr}' \\\n            f' respectively. Please delete the nms_thr ' \\\n            f'which will be deprecated.'\n\n    recovered_proposals = []\n    for proposals, img_info in zip(aug_proposals, img_metas):\n        img_shape = img_info['img_shape']\n        scale_factor = img_info['scale_factor']\n        flip = img_info['flip']\n        flip_direction = img_info['flip_direction']\n        _proposals = proposals.clone()\n        _proposals[:, :4] = bbox_mapping_back(_proposals[:, :4], img_shape,\n                                              scale_factor, flip,\n                                              flip_direction)\n        recovered_proposals.append(_proposals)\n    aug_proposals = torch.cat(recovered_proposals, dim=0)\n    merged_proposals, _ = nms(aug_proposals[:, :4].contiguous(),\n                              aug_proposals[:, -1].contiguous(),\n                              cfg.nms.iou_threshold)\n    scores = merged_proposals[:, 4]\n    _, order = scores.sort(0, descending=True)\n    num = min(cfg.max_per_img, merged_proposals.shape[0])\n    order = order[:num]\n    merged_proposals = merged_proposals[order, :]\n    return merged_proposals\n\n\ndef merge_aug_bboxes(aug_bboxes, aug_scores, img_metas, rcnn_test_cfg):\n    \"\"\"Merge augmented detection bboxes and scores.\n\n    Args:\n        aug_bboxes (list[Tensor]): shape (n, 4*#class)\n        aug_scores (list[Tensor] or None): shape (n, #class)\n        img_shapes (list[Tensor]): shape (3, ).\n        rcnn_test_cfg (dict): rcnn test config.\n\n    Returns:\n        tuple: (bboxes, scores)\n    \"\"\"\n    recovered_bboxes = []\n    for bboxes, img_info in zip(aug_bboxes, img_metas):\n        img_shape = img_info[0]['img_shape']\n        scale_factor = img_info[0]['scale_factor']\n        flip = img_info[0]['flip']\n        flip_direction = img_info[0]['flip_direction']\n        bboxes = bbox_mapping_back(bboxes, img_shape, scale_factor, flip,\n                                   flip_direction)\n        recovered_bboxes.append(bboxes)\n    bboxes = torch.stack(recovered_bboxes).mean(dim=0)\n    if aug_scores is None:\n        return bboxes\n    else:\n        scores = torch.stack(aug_scores).mean(dim=0)\n        return bboxes, scores\n\n\ndef merge_aug_scores(aug_scores):\n    \"\"\"Merge augmented bbox scores.\"\"\"\n    if isinstance(aug_scores[0], torch.Tensor):\n        return torch.mean(torch.stack(aug_scores), dim=0)\n    else:\n        return np.mean(aug_scores, axis=0)\n\n\ndef merge_aug_masks(aug_masks, img_metas, rcnn_test_cfg, weights=None):\n    \"\"\"Merge augmented mask prediction.\n\n    Args:\n        aug_masks (list[ndarray]): shape (n, #class, h, w)\n        img_shapes (list[ndarray]): shape (3, ).\n        rcnn_test_cfg (dict): rcnn test config.\n\n    Returns:\n        tuple: (bboxes, scores)\n    \"\"\"\n    recovered_masks = []\n    for mask, img_info in zip(aug_masks, img_metas):\n        flip = img_info[0]['flip']\n        flip_direction = img_info[0]['flip_direction']\n        if flip:\n            if flip_direction == 'horizontal':\n                mask = mask[:, :, :, ::-1]\n            elif flip_direction == 'vertical':\n                mask = mask[:, :, ::-1, :]\n            elif flip_direction == 'diagonal':\n                mask = mask[:, :, :, ::-1]\n                mask = mask[:, :, ::-1, :]\n            else:\n                raise ValueError(\n                    f\"Invalid flipping direction '{flip_direction}'\")\n        recovered_masks.append(mask)\n\n    if weights is None:\n        merged_masks = np.mean(recovered_masks, axis=0)\n    else:\n        merged_masks = np.average(\n            np.array(recovered_masks), axis=0, weights=np.array(weights))\n    return merged_masks\n\ndef merge_aug_bboxes_3d(aug_results, img_metas, test_cfg):\n    \"\"\"Merge augmented detection 3D bboxes and scores.\n\n    Args:\n        aug_results (list[dict]): The dict of detection results.\n            The dict contains the following keys\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n        img_metas (list[dict]): Meta information of each sample.\n        test_cfg (dict): Test config.\n\n    Returns:\n        dict: Bounding boxes results in cpu mode, containing merged results.\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Merged detection bbox.\n            - scores_3d (torch.Tensor): Merged detection scores.\n            - labels_3d (torch.Tensor): Merged predicted box labels.\n    \"\"\"\n\n    assert len(aug_results) == len(img_metas), \\\n        '\"aug_results\" should have the same length as \"img_metas\", got len(' \\\n        f'aug_results)={len(aug_results)} and len(img_metas)={len(img_metas)}'\n\n    recovered_bboxes = []\n    recovered_scores = []\n    recovered_labels = []\n\n    for bboxes, img_info in zip(aug_results, img_metas):\n        scale_factor = img_info[0]['pcd_scale_factor']\n        pcd_horizontal_flip = img_info[0]['pcd_horizontal_flip']\n        pcd_vertical_flip = img_info[0]['pcd_vertical_flip']\n        recovered_scores.append(bboxes['scores_3d'])\n        recovered_labels.append(bboxes['labels_3d'])\n        bboxes = bbox3d_mapping_back(bboxes['boxes_3d'], scale_factor,\n                                     pcd_horizontal_flip, pcd_vertical_flip)\n        recovered_bboxes.append(bboxes)\n\n    aug_bboxes = recovered_bboxes[0].cat(recovered_bboxes)\n    aug_bboxes_for_nms = xywhr2xyxyr(aug_bboxes.bev)\n    aug_scores = torch.cat(recovered_scores, dim=0)\n    aug_labels = torch.cat(recovered_labels, dim=0)\n\n    # TODO: use a more elegent way to deal with nms\n    if test_cfg.use_rotate_nms:\n        nms_func = nms_gpu\n    else:\n        nms_func = nms_normal_gpu\n\n    merged_bboxes = []\n    merged_scores = []\n    merged_labels = []\n\n    # Apply multi-class nms when merge bboxes\n    if len(aug_labels) == 0:\n        return bbox3d2result(aug_bboxes, aug_scores, aug_labels)\n\n    for class_id in range(torch.max(aug_labels).item() + 1):\n        class_inds = (aug_labels == class_id)\n        bboxes_i = aug_bboxes[class_inds]\n        bboxes_nms_i = aug_bboxes_for_nms[class_inds, :]\n        scores_i = aug_scores[class_inds]\n        labels_i = aug_labels[class_inds]\n        if len(bboxes_nms_i) == 0:\n            continue\n        selected = nms_func(bboxes_nms_i, scores_i, test_cfg.nms_thr)\n\n        merged_bboxes.append(bboxes_i[selected, :])\n        merged_scores.append(scores_i[selected])\n        merged_labels.append(labels_i[selected])\n\n    merged_bboxes = merged_bboxes[0].cat(merged_bboxes)\n    merged_scores = torch.cat(merged_scores, dim=0)\n    merged_labels = torch.cat(merged_labels, dim=0)\n\n    _, order = merged_scores.sort(0, descending=True)\n    num = min(test_cfg.max_num, len(aug_bboxes))\n    order = order[:num]\n\n    merged_bboxes = merged_bboxes[order]\n    merged_scores = merged_scores[order]\n    merged_labels = merged_labels[order]\n\n    return bbox3d2result(merged_bboxes, merged_scores, merged_labels)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/utils/__init__.py",
    "content": "from .dist_utils import DistOptimizerHook, allreduce_grads, reduce_mean\nfrom .misc import flip_tensor, mask2ndarray, multi_apply, unmap, add_prefix\nfrom .gaussian import draw_heatmap_gaussian, gaussian_2d, gaussian_radius\n\n__all__ = [\n    'allreduce_grads', 'DistOptimizerHook', 'reduce_mean', 'multi_apply',\n    'unmap', 'mask2ndarray', 'flip_tensor', 'add_prefix',\n    'gaussian_2d', 'gaussian_radius', 'draw_heatmap_gaussian'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/utils/dist_utils.py",
    "content": "import warnings\nfrom collections import OrderedDict\n\nimport torch.distributed as dist\nfrom mmcv.runner import OptimizerHook\nfrom torch._utils import (_flatten_dense_tensors, _take_tensors,\n                          _unflatten_dense_tensors)\n\n\ndef _allreduce_coalesced(tensors, world_size, bucket_size_mb=-1):\n    if bucket_size_mb > 0:\n        bucket_size_bytes = bucket_size_mb * 1024 * 1024\n        buckets = _take_tensors(tensors, bucket_size_bytes)\n    else:\n        buckets = OrderedDict()\n        for tensor in tensors:\n            tp = tensor.type()\n            if tp not in buckets:\n                buckets[tp] = []\n            buckets[tp].append(tensor)\n        buckets = buckets.values()\n\n    for bucket in buckets:\n        flat_tensors = _flatten_dense_tensors(bucket)\n        dist.all_reduce(flat_tensors)\n        flat_tensors.div_(world_size)\n        for tensor, synced in zip(\n                bucket, _unflatten_dense_tensors(flat_tensors, bucket)):\n            tensor.copy_(synced)\n\n\ndef allreduce_grads(params, coalesce=True, bucket_size_mb=-1):\n    \"\"\"Allreduce gradients.\n\n    Args:\n        params (list[torch.Parameters]): List of parameters of a model\n        coalesce (bool, optional): Whether allreduce parameters as a whole.\n            Defaults to True.\n        bucket_size_mb (int, optional): Size of bucket, the unit is MB.\n            Defaults to -1.\n    \"\"\"\n    grads = [\n        param.grad.data for param in params\n        if param.requires_grad and param.grad is not None\n    ]\n    world_size = dist.get_world_size()\n    if coalesce:\n        _allreduce_coalesced(grads, world_size, bucket_size_mb)\n    else:\n        for tensor in grads:\n            dist.all_reduce(tensor.div_(world_size))\n\n\nclass DistOptimizerHook(OptimizerHook):\n    \"\"\"Deprecated optimizer hook for distributed training.\"\"\"\n\n    def __init__(self, *args, **kwargs):\n        warnings.warn('\"DistOptimizerHook\" is deprecated, please switch to'\n                      '\"mmcv.runner.OptimizerHook\".')\n        super().__init__(*args, **kwargs)\n\n\ndef reduce_mean(tensor):\n    \"\"\"\"Obtain the mean of tensor on different GPUs.\"\"\"\n    if not (dist.is_available() and dist.is_initialized()):\n        return tensor\n    tensor = tensor.clone()\n    dist.all_reduce(tensor.div_(dist.get_world_size()), op=dist.ReduceOp.SUM)\n    return tensor\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/utils/gaussian.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\n\ndef gaussian_2d(shape, sigma=1):\n    \"\"\"Generate gaussian map.\n\n    Args:\n        shape (list[int]): Shape of the map.\n        sigma (float): Sigma to generate gaussian map.\n            Defaults to 1.\n\n    Returns:\n        np.ndarray: Generated gaussian map.\n    \"\"\"\n    m, n = [(ss - 1.) / 2. for ss in shape]\n    y, x = np.ogrid[-m:m + 1, -n:n + 1]\n\n    h = np.exp(-(x * x + y * y) / (2 * sigma * sigma))\n    h[h < np.finfo(h.dtype).eps * h.max()] = 0\n    return h\n\n\ndef draw_heatmap_gaussian(heatmap, center, radius, k=1):\n    \"\"\"Get gaussian masked heatmap.\n\n    Args:\n        heatmap (torch.Tensor): Heatmap to be masked.\n        center (torch.Tensor): Center coord of the heatmap.\n        radius (int): Radius of gausian.\n        K (int): Multiple of masked_gaussian. Defaults to 1.\n\n    Returns:\n        torch.Tensor: Masked heatmap.\n    \"\"\"\n    diameter = 2 * radius + 1\n    gaussian = gaussian_2d((diameter, diameter), sigma=diameter / 6)\n\n    x, y = int(center[0]), int(center[1])\n\n    height, width = heatmap.shape[0:2]\n\n    left, right = min(x, radius), min(width - x, radius + 1)\n    top, bottom = min(y, radius), min(height - y, radius + 1)\n\n    masked_heatmap = heatmap[y - top:y + bottom, x - left:x + right]\n    masked_gaussian = torch.from_numpy(\n        gaussian[radius - top:radius + bottom,\n                 radius - left:radius + right]).to(heatmap.device,\n                                                   torch.float32)\n    if min(masked_gaussian.shape) > 0 and min(masked_heatmap.shape) > 0:\n        torch.max(masked_heatmap, masked_gaussian * k, out=masked_heatmap)\n    return heatmap\n\n\ndef gaussian_radius(det_size, min_overlap=0.5):\n    \"\"\"Get radius of gaussian.\n\n    Args:\n        det_size (tuple[torch.Tensor]): Size of the detection result.\n        min_overlap (float): Gaussian_overlap. Defaults to 0.5.\n\n    Returns:\n        torch.Tensor: Computed radius.\n    \"\"\"\n    height, width = det_size\n\n    a1 = 1\n    b1 = (height + width)\n    c1 = width * height * (1 - min_overlap) / (1 + min_overlap)\n    sq1 = torch.sqrt(b1**2 - 4 * a1 * c1)\n    r1 = (b1 + sq1) / 2\n\n    a2 = 4\n    b2 = 2 * (height + width)\n    c2 = (1 - min_overlap) * width * height\n    sq2 = torch.sqrt(b2**2 - 4 * a2 * c2)\n    r2 = (b2 + sq2) / 2\n\n    a3 = 4 * min_overlap\n    b3 = -2 * min_overlap * (height + width)\n    c3 = (min_overlap - 1) * width * height\n    sq3 = torch.sqrt(b3**2 - 4 * a3 * c3)\n    r3 = (b3 + sq3) / 2\n    return min(r1, r2, r3)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/utils/misc.py",
    "content": "from functools import partial\n\nimport numpy as np\nimport torch\nfrom six.moves import map, zip\n\nfrom ..mask.structures import BitmapMasks, PolygonMasks\n\n\ndef multi_apply(func, *args, **kwargs):\n    \"\"\"Apply function to a list of arguments.\n\n    Note:\n        This function applies the ``func`` to multiple inputs and\n        map the multiple outputs of the ``func`` into different\n        list. Each list contains the same type of outputs corresponding\n        to different inputs.\n\n    Args:\n        func (Function): A function that will be applied to a list of\n            arguments\n\n    Returns:\n        tuple(list): A tuple containing multiple list, each list contains \\\n            a kind of returned results by the function\n    \"\"\"\n    pfunc = partial(func, **kwargs) if kwargs else func\n    map_results = map(pfunc, *args)\n    return tuple(map(list, zip(*map_results)))\n\n\ndef unmap(data, count, inds, fill=0):\n    \"\"\"Unmap a subset of item (data) back to the original set of items (of size\n    count)\"\"\"\n    if data.dim() == 1:\n        ret = data.new_full((count, ), fill)\n        ret[inds.type(torch.bool)] = data\n    else:\n        new_size = (count, ) + data.size()[1:]\n        ret = data.new_full(new_size, fill)\n        ret[inds.type(torch.bool), :] = data\n    return ret\n\n\ndef mask2ndarray(mask):\n    \"\"\"Convert Mask to ndarray..\n\n    Args:\n        mask (:obj:`BitmapMasks` or :obj:`PolygonMasks` or\n        torch.Tensor or np.ndarray): The mask to be converted.\n\n    Returns:\n        np.ndarray: Ndarray mask of shape (n, h, w) that has been converted\n    \"\"\"\n    if isinstance(mask, (BitmapMasks, PolygonMasks)):\n        mask = mask.to_ndarray()\n    elif isinstance(mask, torch.Tensor):\n        mask = mask.detach().cpu().numpy()\n    elif not isinstance(mask, np.ndarray):\n        raise TypeError(f'Unsupported {type(mask)} data type')\n    return mask\n\n\ndef flip_tensor(src_tensor, flip_direction):\n    \"\"\"flip tensor base on flip_direction.\n\n    Args:\n        src_tensor (Tensor): input feature map, shape (B, C, H, W).\n        flip_direction (str): The flipping direction. Options are\n          'horizontal', 'vertical', 'diagonal'.\n\n    Returns:\n        out_tensor (Tensor): Flipped tensor.\n    \"\"\"\n    assert src_tensor.ndim == 4\n    valid_directions = ['horizontal', 'vertical', 'diagonal']\n    assert flip_direction in valid_directions\n    if flip_direction == 'horizontal':\n        out_tensor = torch.flip(src_tensor, [3])\n    elif flip_direction == 'vertical':\n        out_tensor = torch.flip(src_tensor, [2])\n    else:\n        out_tensor = torch.flip(src_tensor, [2, 3])\n    return out_tensor\n\ndef add_prefix(inputs, prefix):\n    \"\"\"Add prefix for dict.\n\n    Args:\n        inputs (dict): The input dict with str keys.\n        prefix (str): The prefix to add.\n\n    Returns:\n\n        dict: The dict with keys updated with ``prefix``.\n    \"\"\"\n\n    outputs = dict()\n    for name, value in inputs.items():\n        outputs[f'{prefix}.{name}'] = value\n\n    return outputs\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/visualization/__init__.py",
    "content": "from .image import (color_val_matplotlib, imshow_det_bboxes,\n                    imshow_gt_det_bboxes, imshow, color_val)\n\n__all__ = ['imshow_det_bboxes', 'imshow_gt_det_bboxes', 'color_val_matplotlib']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/visualization/image.py",
    "content": "import matplotlib.pyplot as plt\nimport numpy as np\nimport cv2\nimport pycocotools.mask as mask_util\nfrom matplotlib.collections import PatchCollection\nfrom matplotlib.patches import Polygon\nfrom enum import Enum\nfrom mmcv.utils import concat_list, is_str\nfrom mmcv.image import imread, imwrite\nfrom mmcv.image import bgr2rgb, rgb2bgr\nfrom ..utils import mask2ndarray\n\nEPS = 1e-2\n\n\nclass Color(Enum):\n    \"\"\"An enum that defines common colors.\n\n    Contains red, green, blue, cyan, yellow, magenta, white and black.\n    \"\"\"\n    red = (0, 0, 255)\n    green = (0, 255, 0)\n    blue = (255, 0, 0)\n    cyan = (255, 255, 0)\n    yellow = (0, 255, 255)\n    magenta = (255, 0, 255)\n    white = (255, 255, 255)\n    black = (0, 0, 0)\n\n\ndef color_val(color):\n    \"\"\"Convert various input to color tuples.\n\n    Args:\n        color (:obj:`Color`/str/tuple/int/ndarray): Color inputs\n\n    Returns:\n        tuple[int]: A tuple of 3 integers indicating BGR channels.\n    \"\"\"\n    if is_str(color):\n        return Color[color].value\n    elif isinstance(color, Color):\n        return color.value\n    elif isinstance(color, tuple):\n        assert len(color) == 3\n        for channel in color:\n            assert 0 <= channel <= 255\n        return color\n    elif isinstance(color, int):\n        assert 0 <= color <= 255\n        return color, color, color\n    elif isinstance(color, np.ndarray):\n        assert color.ndim == 1 and color.size == 3\n        assert np.all((color >= 0) & (color <= 255))\n        color = color.astype(np.uint8)\n        return tuple(color)\n    else:\n        raise TypeError(f'Invalid type for color: {type(color)}')\n\n\n\ndef color_val_matplotlib(color):\n    \"\"\"Convert various input in BGR order to normalized RGB matplotlib color\n    tuples,\n\n    Args:\n        color (:obj:`Color`/str/tuple/int/ndarray): Color inputs\n\n    Returns:\n        tuple[float]: A tuple of 3 normalized floats indicating RGB channels.\n    \"\"\"\n    color = color_val(color)\n    color = [color / 255 for color in color[::-1]]\n    return tuple(color)\n\ndef imshow(img, win_name='', wait_time=0):\n    \"\"\"Show an image.\n\n    Args:\n        img (str or ndarray): The image to be displayed.\n        win_name (str): The window name.\n        wait_time (int): Value of waitKey param.\n    \"\"\"\n    cv2.imshow(win_name, imread(img))\n    if wait_time == 0:  # prevent from hanging if windows was closed\n        while True:\n            ret = cv2.waitKey(1)\n\n            closed = cv2.getWindowProperty(win_name, cv2.WND_PROP_VISIBLE) < 1\n            # if user closed window or if some key pressed\n            if closed or ret != -1:\n                break\n    else:\n        ret = cv2.waitKey(wait_time)\n\n\ndef imshow_det_bboxes(img,\n                      bboxes,\n                      labels,\n                      segms=None,\n                      class_names=None,\n                      score_thr=0,\n                      bbox_color='green',\n                      text_color='green',\n                      mask_color=None,\n                      thickness=2,\n                      font_size=13,\n                      win_name='',\n                      show=True,\n                      wait_time=0,\n                      out_file=None):\n    \"\"\"Draw bboxes and class labels (with scores) on an image.\n\n    Args:\n        img (str or ndarray): The image to be displayed.\n        bboxes (ndarray): Bounding boxes (with scores), shaped (n, 4) or\n            (n, 5).\n        labels (ndarray): Labels of bboxes.\n        segms (ndarray or None): Masks, shaped (n,h,w) or None\n        class_names (list[str]): Names of each classes.\n        score_thr (float): Minimum score of bboxes to be shown.  Default: 0\n        bbox_color (str or tuple(int) or :obj:`Color`):Color of bbox lines.\n           The tuple of color should be in BGR order. Default: 'green'\n        text_color (str or tuple(int) or :obj:`Color`):Color of texts.\n           The tuple of color should be in BGR order. Default: 'green'\n        mask_color (str or tuple(int) or :obj:`Color`, optional):\n           Color of masks. The tuple of color should be in BGR order.\n           Default: None\n        thickness (int): Thickness of lines. Default: 2\n        font_size (int): Font size of texts. Default: 13\n        show (bool): Whether to show the image. Default: True\n        win_name (str): The window name. Default: ''\n        wait_time (float): Value of waitKey param. Default: 0.\n        out_file (str, optional): The filename to write the image.\n            Default: None\n\n    Returns:\n        ndarray: The image with bboxes drawn on it.\n    \"\"\"\n    assert bboxes.ndim == 2, \\\n        f' bboxes ndim should be 2, but its ndim is {bboxes.ndim}.'\n    assert labels.ndim == 1, \\\n        f' labels ndim should be 1, but its ndim is {labels.ndim}.'\n    assert bboxes.shape[0] == labels.shape[0], \\\n        'bboxes.shape[0] and labels.shape[0] should have the same length.'\n    assert bboxes.shape[1] == 4 or bboxes.shape[1] == 5, \\\n        f' bboxes.shape[1] should be 4 or 5, but its {bboxes.shape[1]}.'\n    img = imread(img).astype(np.uint8)\n\n    if score_thr > 0:\n        assert bboxes.shape[1] == 5\n        scores = bboxes[:, -1]\n        inds = scores > score_thr\n        bboxes = bboxes[inds, :]\n        labels = labels[inds]\n        if segms is not None:\n            segms = segms[inds, ...]\n\n    mask_colors = []\n    if labels.shape[0] > 0:\n        if mask_color is None:\n            # random color\n            np.random.seed(42)\n            mask_colors = [\n                np.random.randint(0, 256, (1, 3), dtype=np.uint8)\n                for _ in range(max(labels) + 1)\n            ]\n        else:\n            # specify  color\n            mask_colors = [\n                np.array(color_val(mask_color)[::-1], dtype=np.uint8)\n            ] * (\n                max(labels) + 1)\n\n    bbox_color = color_val_matplotlib(bbox_color)\n    text_color = color_val_matplotlib(text_color)\n\n    img = bgr2rgb(img)\n    width, height = img.shape[1], img.shape[0]\n    img = np.ascontiguousarray(img)\n\n    fig = plt.figure(win_name, frameon=False)\n    plt.title(win_name)\n    canvas = fig.canvas\n    dpi = fig.get_dpi()\n    # add a small EPS to avoid precision lost due to matplotlib's truncation\n    # (https://github.com/matplotlib/matplotlib/issues/15363)\n    fig.set_size_inches((width + EPS) / dpi, (height + EPS) / dpi)\n\n    # remove white edges by set subplot margin\n    plt.subplots_adjust(left=0, right=1, bottom=0, top=1)\n    ax = plt.gca()\n    ax.axis('off')\n\n    polygons = []\n    color = []\n    for i, (bbox, label) in enumerate(zip(bboxes, labels)):\n        bbox_int = bbox.astype(np.int32)\n        poly = [[bbox_int[0], bbox_int[1]], [bbox_int[0], bbox_int[3]],\n                [bbox_int[2], bbox_int[3]], [bbox_int[2], bbox_int[1]]]\n        np_poly = np.array(poly).reshape((4, 2))\n        polygons.append(Polygon(np_poly))\n        color.append(bbox_color)\n        label_text = class_names[\n            label] if class_names is not None else f'class {label}'\n        if len(bbox) > 4:\n            label_text += f'|{bbox[-1]:.02f}'\n        ax.text(\n            bbox_int[0],\n            bbox_int[1],\n            f'{label_text}',\n            bbox={\n                'facecolor': 'black',\n                'alpha': 0.8,\n                'pad': 0.7,\n                'edgecolor': 'none'\n            },\n            color=text_color,\n            fontsize=font_size,\n            verticalalignment='top',\n            horizontalalignment='left')\n        if segms is not None:\n            color_mask = mask_colors[labels[i]]\n            mask = segms[i].astype(bool)\n            img[mask] = img[mask] * 0.5 + color_mask * 0.5\n\n    plt.imshow(img)\n\n    p = PatchCollection(\n        polygons, facecolor='none', edgecolors=color, linewidths=thickness)\n    ax.add_collection(p)\n\n    stream, _ = canvas.print_to_buffer()\n    buffer = np.frombuffer(stream, dtype='uint8')\n    img_rgba = buffer.reshape(height, width, 4)\n    rgb, alpha = np.split(img_rgba, [3], axis=2)\n    img = rgb.astype('uint8')\n    img = rgb2bgr(img)\n\n    if show:\n        # We do not use cv2 for display because in some cases, opencv will\n        # conflict with Qt, it will output a warning: Current thread\n        # is not the object's thread. You can refer to\n        # https://github.com/opencv/opencv-python/issues/46 for details\n        if wait_time == 0:\n            plt.show()\n        else:\n            plt.show(block=False)\n            plt.pause(wait_time)\n    if out_file is not None:\n        imwrite(img, out_file)\n\n    plt.close()\n\n    return img\n\n\ndef imshow_gt_det_bboxes(img,\n                         annotation,\n                         result,\n                         class_names=None,\n                         score_thr=0,\n                         gt_bbox_color=(255, 102, 61),\n                         gt_text_color=(255, 102, 61),\n                         gt_mask_color=(255, 102, 61),\n                         det_bbox_color=(72, 101, 241),\n                         det_text_color=(72, 101, 241),\n                         det_mask_color=(72, 101, 241),\n                         thickness=2,\n                         font_size=13,\n                         win_name='',\n                         show=True,\n                         wait_time=0,\n                         out_file=None):\n    \"\"\"General visualization GT and result function.\n\n    Args:\n      img (str or ndarray): The image to be displayed.)\n      annotation (dict): Ground truth annotations where contain keys of\n          'gt_bboxes' and 'gt_labels' or 'gt_masks'\n      result (tuple[list] or list): The detection result, can be either\n          (bbox, segm) or just bbox.\n      class_names (list[str]): Names of each classes.\n      score_thr (float): Minimum score of bboxes to be shown.  Default: 0\n      gt_bbox_color (str or tuple(int) or :obj:`Color`):Color of bbox lines.\n           The tuple of color should be in BGR order. Default: (255, 102, 61)\n      gt_text_color (str or tuple(int) or :obj:`Color`):Color of texts.\n           The tuple of color should be in BGR order. Default: (255, 102, 61)\n      gt_mask_color (str or tuple(int) or :obj:`Color`, optional):\n           Color of masks. The tuple of color should be in BGR order.\n           Default: (255, 102, 61)\n      det_bbox_color (str or tuple(int) or :obj:`Color`):Color of bbox lines.\n           The tuple of color should be in BGR order. Default: (72, 101, 241)\n      det_text_color (str or tuple(int) or :obj:`Color`):Color of texts.\n           The tuple of color should be in BGR order. Default: (72, 101, 241)\n      det_mask_color (str or tuple(int) or :obj:`Color`, optional):\n           Color of masks. The tuple of color should be in BGR order.\n           Default: (72, 101, 241)\n      thickness (int): Thickness of lines. Default: 2\n      font_size (int): Font size of texts. Default: 13\n      win_name (str): The window name. Default: ''\n      show (bool): Whether to show the image. Default: True\n      wait_time (float): Value of waitKey param. Default: 0.\n      out_file (str, optional): The filename to write the image.\n         Default: None\n\n    Returns:\n        ndarray: The image with bboxes or masks drawn on it.\n    \"\"\"\n    assert 'gt_bboxes' in annotation\n    assert 'gt_labels' in annotation\n    assert isinstance(\n        result,\n        (tuple, list)), f'Expected tuple or list, but get {type(result)}'\n\n    gt_masks = annotation.get('gt_masks', None)\n    if gt_masks is not None:\n        gt_masks = mask2ndarray(gt_masks)\n\n    img = imread(img)\n\n    img = imshow_det_bboxes(\n        img,\n        annotation['gt_bboxes'],\n        annotation['gt_labels'],\n        gt_masks,\n        class_names=class_names,\n        bbox_color=gt_bbox_color,\n        text_color=gt_text_color,\n        mask_color=gt_mask_color,\n        thickness=thickness,\n        font_size=font_size,\n        win_name=win_name,\n        show=False)\n\n    if isinstance(result, tuple):\n        bbox_result, segm_result = result\n        if isinstance(segm_result, tuple):\n            segm_result = segm_result[0]  # ms rcnn\n    else:\n        bbox_result, segm_result = result, None\n\n    bboxes = np.vstack(bbox_result)\n    labels = [\n        np.full(bbox.shape[0], i, dtype=np.int32)\n        for i, bbox in enumerate(bbox_result)\n    ]\n    labels = np.concatenate(labels)\n\n    segms = None\n    if segm_result is not None and len(labels) > 0:  # non empty\n        segms = concat_list(segm_result)\n        segms = mask_util.decode(segms)\n        segms = segms.transpose(2, 0, 1)\n\n    img = imshow_det_bboxes(\n        img,\n        bboxes,\n        labels,\n        segms=segms,\n        class_names=class_names,\n        score_thr=score_thr,\n        bbox_color=det_bbox_color,\n        text_color=det_text_color,\n        mask_color=det_mask_color,\n        thickness=thickness,\n        font_size=font_size,\n        win_name=win_name,\n        show=show,\n        wait_time=wait_time,\n        out_file=out_file)\n    return img\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/visualizer/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .show_result import (show_multi_modality_result, show_result,\n                          show_seg_result)\n\n__all__ = ['show_result', 'show_seg_result', 'show_multi_modality_result']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/visualizer/image_vis.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport cv2\nimport numpy as np\nimport torch\nfrom matplotlib import pyplot as plt\n\n\ndef project_pts_on_img(points,\n                       raw_img,\n                       lidar2img_rt,\n                       max_distance=70,\n                       thickness=-1):\n    \"\"\"Project the 3D points cloud on 2D image.\n\n    Args:\n        points (numpy.array): 3D points cloud (x, y, z) to visualize.\n        raw_img (numpy.array): The numpy array of image.\n        lidar2img_rt (numpy.array, shape=[4, 4]): The projection matrix\n            according to the camera intrinsic parameters.\n        max_distance (float): the max distance of the points cloud.\n            Default: 70.\n        thickness (int, optional): The thickness of 2D points. Default: -1.\n    \"\"\"\n    img = raw_img.copy()\n    num_points = points.shape[0]\n    pts_4d = np.concatenate([points[:, :3], np.ones((num_points, 1))], axis=-1)\n    pts_2d = pts_4d @ lidar2img_rt.T\n\n    # cam_points is Tensor of Nx4 whose last column is 1\n    # transform camera coordinate to image coordinate\n    pts_2d[:, 2] = np.clip(pts_2d[:, 2], a_min=1e-5, a_max=99999)\n    pts_2d[:, 0] /= pts_2d[:, 2]\n    pts_2d[:, 1] /= pts_2d[:, 2]\n\n    fov_inds = ((pts_2d[:, 0] < img.shape[1])\n                & (pts_2d[:, 0] >= 0)\n                & (pts_2d[:, 1] < img.shape[0])\n                & (pts_2d[:, 1] >= 0))\n\n    imgfov_pts_2d = pts_2d[fov_inds, :3]  # u, v, d\n\n    cmap = plt.cm.get_cmap('hsv', 256)\n    cmap = np.array([cmap(i) for i in range(256)])[:, :3] * 255\n    for i in range(imgfov_pts_2d.shape[0]):\n        depth = imgfov_pts_2d[i, 2]\n        color = cmap[np.clip(int(max_distance * 10 / depth), 0, 255), :]\n        cv2.circle(\n            img,\n            center=(int(np.round(imgfov_pts_2d[i, 0])),\n                    int(np.round(imgfov_pts_2d[i, 1]))),\n            radius=1,\n            color=tuple(color),\n            thickness=thickness,\n        )\n    cv2.imshow('project_pts_img', img.astype(np.uint8))\n    cv2.waitKey(100)\n\n\ndef plot_rect3d_on_img(img,\n                       num_rects,\n                       rect_corners,\n                       color=(0, 255, 0),\n                       thickness=1):\n    \"\"\"Plot the boundary lines of 3D rectangular on 2D images.\n\n    Args:\n        img (numpy.array): The numpy array of image.\n        num_rects (int): Number of 3D rectangulars.\n        rect_corners (numpy.array): Coordinates of the corners of 3D\n            rectangulars. Should be in the shape of [num_rect, 8, 2].\n        color (tuple[int]): The color to draw bboxes. Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    line_indices = ((0, 1), (0, 3), (0, 4), (1, 2), (1, 5), (3, 2), (3, 7),\n                    (4, 5), (4, 7), (2, 6), (5, 6), (6, 7))\n    for i in range(num_rects):\n        corners = rect_corners[i].astype(np.int)\n        for start, end in line_indices:\n            cv2.line(img, (corners[start, 0], corners[start, 1]),\n                     (corners[end, 0], corners[end, 1]), color, thickness,\n                     cv2.LINE_AA)\n\n    return img.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d_on_img(bboxes3d,\n                             raw_img,\n                             lidar2img_rt,\n                             img_metas,\n                             color=(0, 255, 0),\n                             thickness=1):\n    \"\"\"Project the 3D bbox on 2D plane and draw on input image.\n\n    Args:\n        bboxes3d (:obj:`LiDARInstance3DBoxes`):\n            3d bbox in lidar coordinate system to visualize.\n        raw_img (numpy.array): The numpy array of image.\n        lidar2img_rt (numpy.array, shape=[4, 4]): The projection matrix\n            according to the camera intrinsic parameters.\n        img_metas (dict): Useless here.\n        color (tuple[int]): The color to draw bboxes. Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    img = raw_img.copy()\n    corners_3d = bboxes3d.corners\n    num_bbox = corners_3d.shape[0]\n    pts_4d = np.concatenate(\n        [corners_3d.reshape(-1, 3),\n         np.ones((num_bbox * 8, 1))], axis=-1)\n    lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n    if isinstance(lidar2img_rt, torch.Tensor):\n        lidar2img_rt = lidar2img_rt.cpu().numpy()\n    pts_2d = pts_4d @ lidar2img_rt.T\n\n    pts_2d[:, 2] = np.clip(pts_2d[:, 2], a_min=1e-5, a_max=1e5)\n    pts_2d[:, 0] /= pts_2d[:, 2]\n    pts_2d[:, 1] /= pts_2d[:, 2]\n    imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)\n\n    return plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, color, thickness)\n\n\n# TODO: remove third parameter in all functions here in favour of img_metas\ndef draw_depth_bbox3d_on_img(bboxes3d,\n                             raw_img,\n                             calibs,\n                             img_metas,\n                             color=(0, 255, 0),\n                             thickness=1):\n    \"\"\"Project the 3D bbox on 2D plane and draw on input image.\n\n    Args:\n        bboxes3d (:obj:`DepthInstance3DBoxes`, shape=[M, 7]):\n            3d bbox in depth coordinate system to visualize.\n        raw_img (numpy.array): The numpy array of image.\n        calibs (dict): Camera calibration information, Rt and K.\n        img_metas (dict): Used in coordinates transformation.\n        color (tuple[int]): The color to draw bboxes. Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    from mmcv.core.bbox import points_cam2img\n    from mmcv.models import apply_3d_transformation\n\n    img = raw_img.copy()\n    img_metas = copy.deepcopy(img_metas)\n    corners_3d = bboxes3d.corners\n    num_bbox = corners_3d.shape[0]\n    points_3d = corners_3d.reshape(-1, 3)\n\n    # first reverse the data transformations\n    xyz_depth = apply_3d_transformation(\n        points_3d, 'DEPTH', img_metas, reverse=True)\n\n    # project to 2d to get image coords (uv)\n    uv_origin = points_cam2img(xyz_depth,\n                               xyz_depth.new_tensor(img_metas['depth2img']))\n    uv_origin = (uv_origin - 1).round()\n    imgfov_pts_2d = uv_origin[..., :2].reshape(num_bbox, 8, 2).numpy()\n\n    return plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, color, thickness)\n\n\ndef draw_camera_bbox3d_on_img(bboxes3d,\n                              raw_img,\n                              cam2img,\n                              img_metas,\n                              color=(0, 255, 0),\n                              thickness=1):\n    \"\"\"Project the 3D bbox on 2D plane and draw on input image.\n\n    Args:\n        bboxes3d (:obj:`CameraInstance3DBoxes`, shape=[M, 7]):\n            3d bbox in camera coordinate system to visualize.\n        raw_img (numpy.array): The numpy array of image.\n        cam2img (dict): Camera intrinsic matrix,\n            denoted as `K` in depth bbox coordinate system.\n        img_metas (dict): Useless here.\n        color (tuple[int]): The color to draw bboxes. Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    from mmcv.core.bbox import points_cam2img\n\n    img = raw_img.copy()\n    cam2img = copy.deepcopy(cam2img)\n    corners_3d = bboxes3d.corners\n    num_bbox = corners_3d.shape[0]\n    points_3d = corners_3d.reshape(-1, 3)\n    if not isinstance(cam2img, torch.Tensor):\n        cam2img = torch.from_numpy(np.array(cam2img))\n    cam2img = cam2img.reshape(3, 3).float().cpu()\n\n    # project to 2d to get image coords (uv)\n    uv_origin = points_cam2img(points_3d, cam2img)\n    uv_origin = (uv_origin - 1).round()\n    imgfov_pts_2d = uv_origin[..., :2].reshape(num_bbox, 8, 2).numpy()\n\n    return plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, color, thickness)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/visualizer/open3d_vis.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport numpy as np\nimport torch\n\ntry:\n    import open3d as o3d\n    from open3d import geometry\nexcept ImportError:\n    raise ImportError(\n        'Please run \"pip install open3d\" to install open3d first.')\n\n\ndef _draw_points(points,\n                 vis,\n                 points_size=2,\n                 point_color=(0.5, 0.5, 0.5),\n                 mode='xyz'):\n    \"\"\"Draw points on visualizer.\n\n    Args:\n        points (numpy.array | torch.tensor, shape=[N, 3+C]):\n            points to visualize.\n        vis (:obj:`open3d.visualization.Visualizer`): open3d visualizer.\n        points_size (int): the size of points to show on visualizer.\n            Default: 2.\n        point_color (tuple[float]): the color of points.\n            Default: (0.5, 0.5, 0.5).\n        mode (str):  indicate type of the input points, avaliable mode\n            ['xyz', 'xyzrgb']. Default: 'xyz'.\n\n    Returns:\n        tuple: points, color of each point.\n    \"\"\"\n    vis.get_render_option().point_size = points_size  # set points size\n    if isinstance(points, torch.Tensor):\n        points = points.cpu().numpy()\n\n    points = points.copy()\n    pcd = geometry.PointCloud()\n    if mode == 'xyz':\n        pcd.points = o3d.utility.Vector3dVector(points[:, :3])\n        points_colors = np.tile(np.array(point_color), (points.shape[0], 1))\n    elif mode == 'xyzrgb':\n        pcd.points = o3d.utility.Vector3dVector(points[:, :3])\n        points_colors = points[:, 3:6]\n        # normalize to [0, 1] for open3d drawing\n        if not ((points_colors >= 0.0) & (points_colors <= 1.0)).all():\n            points_colors /= 255.0\n    else:\n        raise NotImplementedError\n\n    pcd.colors = o3d.utility.Vector3dVector(points_colors)\n    vis.add_geometry(pcd)\n\n    return pcd, points_colors\n\n\ndef _draw_bboxes(bbox3d,\n                 vis,\n                 points_colors,\n                 pcd=None,\n                 bbox_color=(0, 1, 0),\n                 points_in_box_color=(1, 0, 0),\n                 rot_axis=2,\n                 center_mode='lidar_bottom',\n                 mode='xyz'):\n    \"\"\"Draw bbox on visualizer and change the color of points inside bbox3d.\n\n    Args:\n        bbox3d (numpy.array | torch.tensor, shape=[M, 7]):\n            3d bbox (x, y, z, dx, dy, dz, yaw) to visualize.\n        vis (:obj:`open3d.visualization.Visualizer`): open3d visualizer.\n        points_colors (numpy.array): color of each points.\n        pcd (:obj:`open3d.geometry.PointCloud`): point cloud. Default: None.\n        bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).\n        points_in_box_color (tuple[float]):\n            the color of points inside bbox3d. Default: (1, 0, 0).\n        rot_axis (int): rotation axis of bbox. Default: 2.\n        center_mode (bool): indicate the center of bbox is bottom center\n            or gravity center. avaliable mode\n            ['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.\n        mode (str):  indicate type of the input points, avaliable mode\n            ['xyz', 'xyzrgb']. Default: 'xyz'.\n    \"\"\"\n    if isinstance(bbox3d, torch.Tensor):\n        bbox3d = bbox3d.cpu().numpy()\n    bbox3d = bbox3d.copy()\n\n    in_box_color = np.array(points_in_box_color)\n    for i in range(len(bbox3d)):\n        center = bbox3d[i, 0:3]\n        dim = bbox3d[i, 3:6]\n        yaw = np.zeros(3)\n        yaw[rot_axis] = -bbox3d[i, 6]\n        rot_mat = geometry.get_rotation_matrix_from_xyz(yaw)\n\n        if center_mode == 'lidar_bottom':\n            center[rot_axis] += dim[\n                rot_axis] / 2  # bottom center to gravity center\n        elif center_mode == 'camera_bottom':\n            center[rot_axis] -= dim[\n                rot_axis] / 2  # bottom center to gravity center\n        box3d = geometry.OrientedBoundingBox(center, rot_mat, dim)\n\n        line_set = geometry.LineSet.create_from_oriented_bounding_box(box3d)\n        line_set.paint_uniform_color(bbox_color)\n        # draw bboxes on visualizer\n        vis.add_geometry(line_set)\n\n        # change the color of points which are in box\n        if pcd is not None and mode == 'xyz':\n            indices = box3d.get_point_indices_within_bounding_box(pcd.points)\n            points_colors[indices] = in_box_color\n\n    # update points colors\n    if pcd is not None:\n        pcd.colors = o3d.utility.Vector3dVector(points_colors)\n        vis.update_geometry(pcd)\n\n\ndef show_pts_boxes(points,\n                   bbox3d=None,\n                   show=True,\n                   save_path=None,\n                   points_size=2,\n                   point_color=(0.5, 0.5, 0.5),\n                   bbox_color=(0, 1, 0),\n                   points_in_box_color=(1, 0, 0),\n                   rot_axis=2,\n                   center_mode='lidar_bottom',\n                   mode='xyz'):\n    \"\"\"Draw bbox and points on visualizer.\n\n    Args:\n        points (numpy.array | torch.tensor, shape=[N, 3+C]):\n            points to visualize.\n        bbox3d (numpy.array | torch.tensor, shape=[M, 7]):\n            3d bbox (x, y, z, dx, dy, dz, yaw) to visualize. Default: None.\n        show (bool): whether to show the visualization results. Default: True.\n        save_path (str): path to save visualized results. Default: None.\n        points_size (int): the size of points to show on visualizer.\n            Default: 2.\n        point_color (tuple[float]): the color of points.\n            Default: (0.5, 0.5, 0.5).\n        bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).\n        points_in_box_color (tuple[float]):\n            the color of points which are in bbox3d. Default: (1, 0, 0).\n        rot_axis (int): rotation axis of bbox. Default: 2.\n        center_mode (bool): indicate the center of bbox is bottom center\n            or gravity center. avaliable mode\n            ['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.\n        mode (str):  indicate type of the input points, avaliable mode\n            ['xyz', 'xyzrgb']. Default: 'xyz'.\n    \"\"\"\n    # TODO: support score and class info\n    assert 0 <= rot_axis <= 2\n\n    # init visualizer\n    vis = o3d.visualization.Visualizer()\n    vis.create_window()\n    mesh_frame = geometry.TriangleMesh.create_coordinate_frame(\n        size=1, origin=[0, 0, 0])  # create coordinate frame\n    vis.add_geometry(mesh_frame)\n\n    # draw points\n    pcd, points_colors = _draw_points(points, vis, points_size, point_color,\n                                      mode)\n\n    # draw boxes\n    if bbox3d is not None:\n        _draw_bboxes(bbox3d, vis, points_colors, pcd, bbox_color,\n                     points_in_box_color, rot_axis, center_mode, mode)\n\n    if show:\n        vis.run()\n\n    if save_path is not None:\n        vis.capture_screen_image(save_path)\n\n    vis.destroy_window()\n\n\ndef _draw_bboxes_ind(bbox3d,\n                     vis,\n                     indices,\n                     points_colors,\n                     pcd=None,\n                     bbox_color=(0, 1, 0),\n                     points_in_box_color=(1, 0, 0),\n                     rot_axis=2,\n                     center_mode='lidar_bottom',\n                     mode='xyz'):\n    \"\"\"Draw bbox on visualizer and change the color or points inside bbox3d\n    with indices.\n\n    Args:\n        bbox3d (numpy.array | torch.tensor, shape=[M, 7]):\n            3d bbox (x, y, z, dx, dy, dz, yaw) to visualize.\n        vis (:obj:`open3d.visualization.Visualizer`): open3d visualizer.\n        indices (numpy.array | torch.tensor, shape=[N, M]):\n            indicate which bbox3d that each point lies in.\n        points_colors (numpy.array): color of each points.\n        pcd (:obj:`open3d.geometry.PointCloud`): point cloud. Default: None.\n        bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).\n        points_in_box_color (tuple[float]):\n            the color of points which are in bbox3d. Default: (1, 0, 0).\n        rot_axis (int): rotation axis of bbox. Default: 2.\n        center_mode (bool): indicate the center of bbox is bottom center\n            or gravity center. avaliable mode\n            ['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.\n        mode (str):  indicate type of the input points, avaliable mode\n            ['xyz', 'xyzrgb']. Default: 'xyz'.\n    \"\"\"\n    if isinstance(bbox3d, torch.Tensor):\n        bbox3d = bbox3d.cpu().numpy()\n    if isinstance(indices, torch.Tensor):\n        indices = indices.cpu().numpy()\n    bbox3d = bbox3d.copy()\n\n    in_box_color = np.array(points_in_box_color)\n    for i in range(len(bbox3d)):\n        center = bbox3d[i, 0:3]\n        dim = bbox3d[i, 3:6]\n        yaw = np.zeros(3)\n        # TODO: fix problem of current coordinate system\n        # dim[0], dim[1] = dim[1], dim[0]  # for current coordinate\n        # yaw[rot_axis] = -(bbox3d[i, 6] - 0.5 * np.pi)\n        yaw[rot_axis] = -bbox3d[i, 6]\n        rot_mat = geometry.get_rotation_matrix_from_xyz(yaw)\n        if center_mode == 'lidar_bottom':\n            center[rot_axis] += dim[\n                rot_axis] / 2  # bottom center to gravity center\n        elif center_mode == 'camera_bottom':\n            center[rot_axis] -= dim[\n                rot_axis] / 2  # bottom center to gravity center\n        box3d = geometry.OrientedBoundingBox(center, rot_mat, dim)\n\n        line_set = geometry.LineSet.create_from_oriented_bounding_box(box3d)\n        line_set.paint_uniform_color(bbox_color)\n        # draw bboxes on visualizer\n        vis.add_geometry(line_set)\n\n        # change the color of points which are in box\n        if pcd is not None and mode == 'xyz':\n            points_colors[indices[:, i].astype(np.bool)] = in_box_color\n\n    # update points colors\n    if pcd is not None:\n        pcd.colors = o3d.utility.Vector3dVector(points_colors)\n        vis.update_geometry(pcd)\n\n\ndef show_pts_index_boxes(points,\n                         bbox3d=None,\n                         show=True,\n                         indices=None,\n                         save_path=None,\n                         points_size=2,\n                         point_color=(0.5, 0.5, 0.5),\n                         bbox_color=(0, 1, 0),\n                         points_in_box_color=(1, 0, 0),\n                         rot_axis=2,\n                         center_mode='lidar_bottom',\n                         mode='xyz'):\n    \"\"\"Draw bbox and points on visualizer with indices that indicate which\n    bbox3d that each point lies in.\n\n    Args:\n        points (numpy.array | torch.tensor, shape=[N, 3+C]):\n            points to visualize.\n        bbox3d (numpy.array | torch.tensor, shape=[M, 7]):\n            3d bbox (x, y, z, dx, dy, dz, yaw) to visualize. Default: None.\n        show (bool): whether to show the visualization results. Default: True.\n        indices (numpy.array | torch.tensor, shape=[N, M]):\n            indicate which bbox3d that each point lies in. Default: None.\n        save_path (str): path to save visualized results. Default: None.\n        points_size (int): the size of points to show on visualizer.\n            Default: 2.\n        point_color (tuple[float]): the color of points.\n            Default: (0.5, 0.5, 0.5).\n        bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).\n        points_in_box_color (tuple[float]):\n            the color of points which are in bbox3d. Default: (1, 0, 0).\n        rot_axis (int): rotation axis of bbox. Default: 2.\n        center_mode (bool): indicate the center of bbox is bottom center\n            or gravity center. avaliable mode\n            ['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.\n        mode (str):  indicate type of the input points, avaliable mode\n            ['xyz', 'xyzrgb']. Default: 'xyz'.\n    \"\"\"\n    # TODO: support score and class info\n    assert 0 <= rot_axis <= 2\n\n    # init visualizer\n    vis = o3d.visualization.Visualizer()\n    vis.create_window()\n    mesh_frame = geometry.TriangleMesh.create_coordinate_frame(\n        size=1, origin=[0, 0, 0])  # create coordinate frame\n    vis.add_geometry(mesh_frame)\n\n    # draw points\n    pcd, points_colors = _draw_points(points, vis, points_size, point_color,\n                                      mode)\n\n    # draw boxes\n    if bbox3d is not None:\n        _draw_bboxes_ind(bbox3d, vis, indices, points_colors, pcd, bbox_color,\n                         points_in_box_color, rot_axis, center_mode, mode)\n\n    if show:\n        vis.run()\n\n    if save_path is not None:\n        vis.capture_screen_image(save_path)\n\n    vis.destroy_window()\n\n\nclass Visualizer(object):\n    r\"\"\"Online visualizer implemented with Open3d.\n\n    Args:\n        points (numpy.array, shape=[N, 3+C]): Points to visualize. The Points\n            cloud is in mode of Coord3DMode.DEPTH (please refer to\n            core.structures.coord_3d_mode).\n        bbox3d (numpy.array, shape=[M, 7]): 3d bbox (x, y, z, dx, dy, dz, yaw)\n            to visualize. The 3d bbox is in mode of Box3DMode.DEPTH with\n            gravity_center (please refer to core.structures.box_3d_mode).\n            Default: None.\n        save_path (str): path to save visualized results. Default: None.\n        points_size (int): the size of points to show on visualizer.\n            Default: 2.\n        point_color (tuple[float]): the color of points.\n            Default: (0.5, 0.5, 0.5).\n        bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).\n        points_in_box_color (tuple[float]):\n            the color of points which are in bbox3d. Default: (1, 0, 0).\n        rot_axis (int): rotation axis of bbox. Default: 2.\n        center_mode (bool): indicate the center of bbox is bottom center\n            or gravity center. avaliable mode\n            ['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.\n        mode (str):  indicate type of the input points, avaliable mode\n            ['xyz', 'xyzrgb']. Default: 'xyz'.\n    \"\"\"\n\n    def __init__(self,\n                 points,\n                 bbox3d=None,\n                 save_path=None,\n                 points_size=2,\n                 point_color=(0.5, 0.5, 0.5),\n                 bbox_color=(0, 1, 0),\n                 points_in_box_color=(1, 0, 0),\n                 rot_axis=2,\n                 center_mode='lidar_bottom',\n                 mode='xyz'):\n        super(Visualizer, self).__init__()\n        assert 0 <= rot_axis <= 2\n\n        # init visualizer\n        self.o3d_visualizer = o3d.visualization.Visualizer()\n        self.o3d_visualizer.create_window()\n        mesh_frame = geometry.TriangleMesh.create_coordinate_frame(\n            size=1, origin=[0, 0, 0])  # create coordinate frame\n        self.o3d_visualizer.add_geometry(mesh_frame)\n\n        self.points_size = points_size\n        self.point_color = point_color\n        self.bbox_color = bbox_color\n        self.points_in_box_color = points_in_box_color\n        self.rot_axis = rot_axis\n        self.center_mode = center_mode\n        self.mode = mode\n        self.seg_num = 0\n\n        # draw points\n        if points is not None:\n            self.pcd, self.points_colors = _draw_points(\n                points, self.o3d_visualizer, points_size, point_color, mode)\n\n        # draw boxes\n        if bbox3d is not None:\n            _draw_bboxes(bbox3d, self.o3d_visualizer, self.points_colors,\n                         self.pcd, bbox_color, points_in_box_color, rot_axis,\n                         center_mode, mode)\n\n    def add_bboxes(self, bbox3d, bbox_color=None, points_in_box_color=None):\n        \"\"\"Add bounding box to visualizer.\n\n        Args:\n            bbox3d (numpy.array, shape=[M, 7]):\n                3D bbox (x, y, z, dx, dy, dz, yaw) to be visualized.\n                The 3d bbox is in mode of Box3DMode.DEPTH with\n                gravity_center (please refer to core.structures.box_3d_mode).\n            bbox_color (tuple[float]): the color of bbox. Defaule: None.\n            points_in_box_color (tuple[float]): the color of points which\n                are in bbox3d. Defaule: None.\n        \"\"\"\n        if bbox_color is None:\n            bbox_color = self.bbox_color\n        if points_in_box_color is None:\n            points_in_box_color = self.points_in_box_color\n        _draw_bboxes(bbox3d, self.o3d_visualizer, self.points_colors, self.pcd,\n                     bbox_color, points_in_box_color, self.rot_axis,\n                     self.center_mode, self.mode)\n\n    def add_seg_mask(self, seg_mask_colors):\n        \"\"\"Add segmentation mask to visualizer via per-point colorization.\n\n        Args:\n            seg_mask_colors (numpy.array, shape=[N, 6]):\n                The segmentation mask whose first 3 dims are point coordinates\n                and last 3 dims are converted colors.\n        \"\"\"\n        # we can't draw the colors on existing points\n        # in case gt and pred mask would overlap\n        # instead we set a large offset along x-axis for each seg mask\n        self.seg_num += 1\n        offset = (np.array(self.pcd.points).max(0) -\n                  np.array(self.pcd.points).min(0))[0] * 1.2 * self.seg_num\n        mesh_frame = geometry.TriangleMesh.create_coordinate_frame(\n            size=1, origin=[offset, 0, 0])  # create coordinate frame for seg\n        self.o3d_visualizer.add_geometry(mesh_frame)\n        seg_points = copy.deepcopy(seg_mask_colors)\n        seg_points[:, 0] += offset\n        _draw_points(\n            seg_points, self.o3d_visualizer, self.points_size, mode='xyzrgb')\n\n    def show(self, save_path=None):\n        \"\"\"Visualize the points cloud.\n\n        Args:\n            save_path (str): path to save image. Default: None.\n        \"\"\"\n\n        self.o3d_visualizer.run()\n\n        if save_path is not None:\n            self.o3d_visualizer.capture_screen_image(save_path)\n\n        self.o3d_visualizer.destroy_window()\n        return\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/visualizer/show_result.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport trimesh\nfrom os import path as osp\n\nfrom mmcv.utils import mkdir_or_exist\nfrom mmcv.image import imwrite\n\nfrom .image_vis import (draw_camera_bbox3d_on_img, draw_depth_bbox3d_on_img,\n                        draw_lidar_bbox3d_on_img)\n\n\ndef _write_obj(points, out_filename):\n    \"\"\"Write points into ``obj`` format for meshlab visualization.\n\n    Args:\n        points (np.ndarray): Points in shape (N, dim).\n        out_filename (str): Filename to be saved.\n    \"\"\"\n    N = points.shape[0]\n    fout = open(out_filename, 'w')\n    for i in range(N):\n        if points.shape[1] == 6:\n            c = points[i, 3:].astype(int)\n            fout.write(\n                'v %f %f %f %d %d %d\\n' %\n                (points[i, 0], points[i, 1], points[i, 2], c[0], c[1], c[2]))\n\n        else:\n            fout.write('v %f %f %f\\n' %\n                       (points[i, 0], points[i, 1], points[i, 2]))\n    fout.close()\n\n\ndef _write_oriented_bbox(scene_bbox, out_filename):\n    \"\"\"Export oriented (around Z axis) scene bbox to meshes.\n\n    Args:\n        scene_bbox(list[ndarray] or ndarray): xyz pos of center and\n            3 lengths (dx,dy,dz) and heading angle around Z axis.\n            Y forward, X right, Z upward. heading angle of positive X is 0,\n            heading angle of positive Y is 90 degrees.\n        out_filename(str): Filename.\n    \"\"\"\n\n    def heading2rotmat(heading_angle):\n        rotmat = np.zeros((3, 3))\n        rotmat[2, 2] = 1\n        cosval = np.cos(heading_angle)\n        sinval = np.sin(heading_angle)\n        rotmat[0:2, 0:2] = np.array([[cosval, -sinval], [sinval, cosval]])\n        return rotmat\n\n    def convert_oriented_box_to_trimesh_fmt(box):\n        ctr = box[:3]\n        lengths = box[3:6]\n        trns = np.eye(4)\n        trns[0:3, 3] = ctr\n        trns[3, 3] = 1.0\n        trns[0:3, 0:3] = heading2rotmat(box[6])\n        box_trimesh_fmt = trimesh.creation.box(lengths, trns)\n        return box_trimesh_fmt\n\n    if len(scene_bbox) == 0:\n        scene_bbox = np.zeros((1, 7))\n    scene = trimesh.scene.Scene()\n    for box in scene_bbox:\n        scene.add_geometry(convert_oriented_box_to_trimesh_fmt(box))\n\n    mesh_list = trimesh.util.concatenate(scene.dump())\n    # save to obj file\n    trimesh.io.export.export_mesh(mesh_list, out_filename, file_type='obj')\n\n    return\n\n\ndef show_result(points,\n                gt_bboxes,\n                pred_bboxes,\n                out_dir,\n                filename,\n                show=True,\n                snapshot=False):\n    \"\"\"Convert results into format that is directly readable for meshlab.\n\n    Args:\n        points (np.ndarray): Points.\n        gt_bboxes (np.ndarray): Ground truth boxes.\n        pred_bboxes (np.ndarray): Predicted boxes.\n        out_dir (str): Path of output directory\n        filename (str): Filename of the current frame.\n        show (bool): Visualize the results online. Defaults to False.\n        snapshot (bool): Whether to save the online results. Defaults to False.\n    \"\"\"\n    result_path = osp.join(out_dir, filename)\n    mkdir_or_exist(result_path)\n\n    if show:\n        from .open3d_vis import Visualizer\n\n        vis = Visualizer(points)\n        if pred_bboxes is not None:\n            vis.add_bboxes(bbox3d=pred_bboxes)\n        if gt_bboxes is not None:\n            vis.add_bboxes(bbox3d=gt_bboxes, bbox_color=(0, 0, 1))\n        show_path = osp.join(result_path,\n                             f'{filename}_online.png') if snapshot else None\n        vis.show(show_path)\n\n    if points is not None:\n        _write_obj(points, osp.join(result_path, f'{filename}_points.obj'))\n\n    if gt_bboxes is not None:\n        # bottom center to gravity center\n        gt_bboxes[..., 2] += gt_bboxes[..., 5] / 2\n        # the positive direction for yaw in meshlab is clockwise\n        gt_bboxes[:, 6] *= -1\n        _write_oriented_bbox(gt_bboxes,\n                             osp.join(result_path, f'{filename}_gt.obj'))\n\n    if pred_bboxes is not None:\n        # bottom center to gravity center\n        pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2\n        # the positive direction for yaw in meshlab is clockwise\n        pred_bboxes[:, 6] *= -1\n        _write_oriented_bbox(pred_bboxes,\n                             osp.join(result_path, f'{filename}_pred.obj'))\n\n\ndef show_seg_result(points,\n                    gt_seg,\n                    pred_seg,\n                    out_dir,\n                    filename,\n                    palette,\n                    ignore_index=None,\n                    show=True,\n                    snapshot=False):\n    \"\"\"Convert results into format that is directly readable for meshlab.\n\n    Args:\n        points (np.ndarray): Points.\n        gt_seg (np.ndarray): Ground truth segmentation mask.\n        pred_seg (np.ndarray): Predicted segmentation mask.\n        out_dir (str): Path of output directory\n        filename (str): Filename of the current frame.\n        palette (np.ndarray): Mapping between class labels and colors.\n        ignore_index (int, optional): The label index to be ignored, e.g. \\\n            unannotated points. Defaults to None.\n        show (bool, optional): Visualize the results online. Defaults to False.\n        snapshot (bool, optional): Whether to save the online results. \\\n            Defaults to False.\n    \"\"\"\n    # we need 3D coordinates to visualize segmentation mask\n    if gt_seg is not None or pred_seg is not None:\n        assert points is not None, \\\n            '3D coordinates are required for segmentation visualization'\n\n    # filter out ignored points\n    if gt_seg is not None and ignore_index is not None:\n        if points is not None:\n            points = points[gt_seg != ignore_index]\n        if pred_seg is not None:\n            pred_seg = pred_seg[gt_seg != ignore_index]\n        gt_seg = gt_seg[gt_seg != ignore_index]\n\n    if gt_seg is not None:\n        gt_seg_color = palette[gt_seg]\n        gt_seg_color = np.concatenate([points[:, :3], gt_seg_color], axis=1)\n    if pred_seg is not None:\n        pred_seg_color = palette[pred_seg]\n        pred_seg_color = np.concatenate([points[:, :3], pred_seg_color],\n                                        axis=1)\n\n    result_path = osp.join(out_dir, filename)\n    mkdir_or_exist(result_path)\n\n    # online visualization of segmentation mask\n    # we show three masks in a row, scene_points, gt_mask, pred_mask\n    if show:\n        from .open3d_vis import Visualizer\n        mode = 'xyzrgb' if points.shape[1] == 6 else 'xyz'\n        vis = Visualizer(points, mode=mode)\n        if gt_seg is not None:\n            vis.add_seg_mask(gt_seg_color)\n        if pred_seg is not None:\n            vis.add_seg_mask(pred_seg_color)\n        show_path = osp.join(result_path,\n                             f'{filename}_online.png') if snapshot else None\n        vis.show(show_path)\n\n    if points is not None:\n        _write_obj(points, osp.join(result_path, f'{filename}_points.obj'))\n\n    if gt_seg is not None:\n        _write_obj(gt_seg_color, osp.join(result_path, f'{filename}_gt.obj'))\n\n    if pred_seg is not None:\n        _write_obj(pred_seg_color, osp.join(result_path,\n                                            f'{filename}_pred.obj'))\n\n\ndef show_multi_modality_result(img,\n                               gt_bboxes,\n                               pred_bboxes,\n                               proj_mat,\n                               out_dir,\n                               filename,\n                               box_mode='lidar',\n                               img_metas=None,\n                               show=True,\n                               gt_bbox_color=(61, 102, 255),\n                               pred_bbox_color=(241, 101, 72)):\n    \"\"\"Convert multi-modality detection results into 2D results.\n\n    Project the predicted 3D bbox to 2D image plane and visualize them.\n\n    Args:\n        img (np.ndarray): The numpy array of image in cv2 fashion.\n        gt_bboxes (:obj:`BaseInstance3DBoxes`): Ground truth boxes.\n        pred_bboxes (:obj:`BaseInstance3DBoxes`): Predicted boxes.\n        proj_mat (numpy.array, shape=[4, 4]): The projection matrix\n            according to the camera intrinsic parameters.\n        out_dir (str): Path of output directory.\n        filename (str): Filename of the current frame.\n        box_mode (str): Coordinate system the boxes are in. Should be one of\n           'depth', 'lidar' and 'camera'. Defaults to 'lidar'.\n        img_metas (dict): Used in projecting depth bbox.\n        show (bool): Visualize the results online. Defaults to False.\n        gt_bbox_color (str or tuple(int)): Color of bbox lines.\n           The tuple of color should be in BGR order. Default: (255, 102, 61)\n        pred_bbox_color (str or tuple(int)): Color of bbox lines.\n           The tuple of color should be in BGR order. Default: (72, 101, 241)\n    \"\"\"\n    if box_mode == 'depth':\n        draw_bbox = draw_depth_bbox3d_on_img\n    elif box_mode == 'lidar':\n        draw_bbox = draw_lidar_bbox3d_on_img\n    elif box_mode == 'camera':\n        draw_bbox = draw_camera_bbox3d_on_img\n    else:\n        raise NotImplementedError(f'unsupported box mode {box_mode}')\n\n    result_path = osp.join(out_dir, filename)\n    mkdir_or_exist(result_path)\n\n    if show:\n        show_img = img.copy()\n        if gt_bboxes is not None:\n            show_img = draw_bbox(\n                gt_bboxes, show_img, proj_mat, img_metas, color=gt_bbox_color)\n        if pred_bboxes is not None:\n            show_img = draw_bbox(\n                pred_bboxes,\n                show_img,\n                proj_mat,\n                img_metas,\n                color=pred_bbox_color)\n        mmcv.imshow(show_img, win_name='project_bbox3d_img', wait_time=0)\n\n    if img is not None:\n        imwrite(img, osp.join(result_path, f'{filename}_img.png'))\n\n    if gt_bboxes is not None:\n        gt_img = draw_bbox(\n            gt_bboxes, img, proj_mat, img_metas, color=gt_bbox_color)\n        imwrite(gt_img, osp.join(result_path, f'{filename}_gt.png'))\n\n    if pred_bboxes is not None:\n        pred_img = draw_bbox(\n            pred_bboxes, img, proj_mat, img_metas, color=pred_bbox_color)\n        imwrite(pred_img, osp.join(result_path, f'{filename}_pred.png'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/voxel/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .builder import build_voxel_generator\nfrom .voxel_generator import VoxelGenerator\n\n__all__ = ['build_voxel_generator', 'VoxelGenerator']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/voxel/builder.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom . import voxel_generator\nfrom mmcv.utils import obj_from_dict\n\ndef build_voxel_generator(cfg, **kwargs):\n    \"\"\"Builder of voxel generator.\"\"\"\n    if isinstance(cfg, voxel_generator.VoxelGenerator):\n        return cfg\n    elif isinstance(cfg, dict):\n        return obj_from_dict(\n            cfg, voxel_generator, default_args=kwargs)\n    else:\n        raise TypeError('Invalid type {} for building a sampler'.format(\n            type(cfg)))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/core/voxel/voxel_generator.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numba\nimport numpy as np\n\n\nclass VoxelGenerator(object):\n    \"\"\"Voxel generator in numpy implementation.\n\n    Args:\n        voxel_size (list[float]): Size of a single voxel\n        point_cloud_range (list[float]): Range of points\n        max_num_points (int): Maximum number of points in a single voxel\n        max_voxels (int, optional): Maximum number of voxels.\n            Defaults to 20000.\n    \"\"\"\n\n    def __init__(self,\n                 voxel_size,\n                 point_cloud_range,\n                 max_num_points,\n                 max_voxels=20000):\n\n        point_cloud_range = np.array(point_cloud_range, dtype=np.float32)\n        # [0, -40, -3, 70.4, 40, 1]\n        voxel_size = np.array(voxel_size, dtype=np.float32)\n        grid_size = (point_cloud_range[3:] -\n                     point_cloud_range[:3]) / voxel_size\n        grid_size = np.round(grid_size).astype(np.int64)\n\n        self._voxel_size = voxel_size\n        self._point_cloud_range = point_cloud_range\n        self._max_num_points = max_num_points\n        self._max_voxels = max_voxels\n        self._grid_size = grid_size\n\n    def generate(self, points):\n        \"\"\"Generate voxels given points.\"\"\"\n        return points_to_voxel(points, self._voxel_size,\n                               self._point_cloud_range, self._max_num_points,\n                               True, self._max_voxels)\n\n    @property\n    def voxel_size(self):\n        \"\"\"list[float]: Size of a single voxel.\"\"\"\n        return self._voxel_size\n\n    @property\n    def max_num_points_per_voxel(self):\n        \"\"\"int: Maximum number of points per voxel.\"\"\"\n        return self._max_num_points\n\n    @property\n    def point_cloud_range(self):\n        \"\"\"list[float]: Range of point cloud.\"\"\"\n        return self._point_cloud_range\n\n    @property\n    def grid_size(self):\n        \"\"\"np.ndarray: The size of grids.\"\"\"\n        return self._grid_size\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        indent = ' ' * (len(repr_str) + 1)\n        repr_str += f'(voxel_size={self._voxel_size},\\n'\n        repr_str += indent + 'point_cloud_range='\n        repr_str += f'{self._point_cloud_range.tolist()},\\n'\n        repr_str += indent + f'max_num_points={self._max_num_points},\\n'\n        repr_str += indent + f'max_voxels={self._max_voxels},\\n'\n        repr_str += indent + f'grid_size={self._grid_size.tolist()}'\n        repr_str += ')'\n        return repr_str\n\n\ndef points_to_voxel(points,\n                    voxel_size,\n                    coors_range,\n                    max_points=35,\n                    reverse_index=True,\n                    max_voxels=20000):\n    \"\"\"convert kitti points(N, >=3) to voxels.\n\n    Args:\n        points (np.ndarray): [N, ndim]. points[:, :3] contain xyz points and \\\n            points[:, 3:] contain other information such as reflectivity.\n        voxel_size (list, tuple, np.ndarray): [3] xyz, indicate voxel size\n        coors_range (list[float | tuple[float] | ndarray]): Voxel range. \\\n            format: xyzxyz, minmax\n        max_points (int): Indicate maximum points contained in a voxel.\n        reverse_index (bool): Whether return reversed coordinates. \\\n            if points has xyz format and reverse_index is True, output \\\n            coordinates will be zyx format, but points in features always \\\n            xyz format.\n        max_voxels (int): Maximum number of voxels this function creates. \\\n            For second, 20000 is a good choice. Points should be shuffled for \\\n            randomness before this function because max_voxels drops points.\n\n    Returns:\n        tuple[np.ndarray]:\n            voxels: [M, max_points, ndim] float tensor. only contain points.\n            coordinates: [M, 3] int32 tensor.\n            num_points_per_voxel: [M] int32 tensor.\n    \"\"\"\n    if not isinstance(voxel_size, np.ndarray):\n        voxel_size = np.array(voxel_size, dtype=points.dtype)\n    if not isinstance(coors_range, np.ndarray):\n        coors_range = np.array(coors_range, dtype=points.dtype)\n    voxelmap_shape = (coors_range[3:] - coors_range[:3]) / voxel_size\n    voxelmap_shape = tuple(np.round(voxelmap_shape).astype(np.int32).tolist())\n    if reverse_index:\n        voxelmap_shape = voxelmap_shape[::-1]\n    # don't create large array in jit(nopython=True) code.\n    num_points_per_voxel = np.zeros(shape=(max_voxels, ), dtype=np.int32)\n    coor_to_voxelidx = -np.ones(shape=voxelmap_shape, dtype=np.int32)\n    voxels = np.zeros(\n        shape=(max_voxels, max_points, points.shape[-1]), dtype=points.dtype)\n    coors = np.zeros(shape=(max_voxels, 3), dtype=np.int32)\n    if reverse_index:\n        voxel_num = _points_to_voxel_reverse_kernel(\n            points, voxel_size, coors_range, num_points_per_voxel,\n            coor_to_voxelidx, voxels, coors, max_points, max_voxels)\n\n    else:\n        voxel_num = _points_to_voxel_kernel(points, voxel_size, coors_range,\n                                            num_points_per_voxel,\n                                            coor_to_voxelidx, voxels, coors,\n                                            max_points, max_voxels)\n\n    coors = coors[:voxel_num]\n    voxels = voxels[:voxel_num]\n    num_points_per_voxel = num_points_per_voxel[:voxel_num]\n\n    return voxels, coors, num_points_per_voxel\n\n\n@numba.jit(nopython=True)\ndef _points_to_voxel_reverse_kernel(points,\n                                    voxel_size,\n                                    coors_range,\n                                    num_points_per_voxel,\n                                    coor_to_voxelidx,\n                                    voxels,\n                                    coors,\n                                    max_points=35,\n                                    max_voxels=20000):\n    \"\"\"convert kitti points(N, >=3) to voxels.\n\n    Args:\n        points (np.ndarray): [N, ndim]. points[:, :3] contain xyz points and \\\n            points[:, 3:] contain other information such as reflectivity.\n        voxel_size (list, tuple, np.ndarray): [3] xyz, indicate voxel size \\\n        coors_range (list[float | tuple[float] | ndarray]): Range of voxels. \\\n            format: xyzxyz, minmax\n        num_points_per_voxel (int): Number of points per voxel.\n        coor_to_voxel_idx (np.ndarray): A voxel grid of shape (D, H, W), \\\n            which has the same shape as the complete voxel map. It indicates \\\n            the index of each corresponding voxel.\n        voxels (np.ndarray): Created empty voxels.\n        coors (np.ndarray): Created coordinates of each voxel.\n        max_points (int): Indicate maximum points contained in a voxel.\n        max_voxels (int): Maximum number of voxels this function create. \\\n            for second, 20000 is a good choice. Points should be shuffled for \\\n            randomness before this function because max_voxels drops points.\n\n    Returns:\n        tuple[np.ndarray]:\n            voxels: Shape [M, max_points, ndim], only contain points.\n            coordinates: Shape [M, 3].\n            num_points_per_voxel: Shape [M].\n    \"\"\"\n    # put all computations to one loop.\n    # we shouldn't create large array in main jit code, otherwise\n    # reduce performance\n    N = points.shape[0]\n    # ndim = points.shape[1] - 1\n    ndim = 3\n    ndim_minus_1 = ndim - 1\n    grid_size = (coors_range[3:] - coors_range[:3]) / voxel_size\n    # np.round(grid_size)\n    # grid_size = np.round(grid_size).astype(np.int64)(np.int32)\n    grid_size = np.round(grid_size, 0, grid_size).astype(np.int32)\n    coor = np.zeros(shape=(3, ), dtype=np.int32)\n    voxel_num = 0\n    failed = False\n    for i in range(N):\n        failed = False\n        for j in range(ndim):\n            c = np.floor((points[i, j] - coors_range[j]) / voxel_size[j])\n            if c < 0 or c >= grid_size[j]:\n                failed = True\n                break\n            coor[ndim_minus_1 - j] = c\n        if failed:\n            continue\n        voxelidx = coor_to_voxelidx[coor[0], coor[1], coor[2]]\n        if voxelidx == -1:\n            voxelidx = voxel_num\n            if voxel_num >= max_voxels:\n                continue\n            voxel_num += 1\n            coor_to_voxelidx[coor[0], coor[1], coor[2]] = voxelidx\n            coors[voxelidx] = coor\n        num = num_points_per_voxel[voxelidx]\n        if num < max_points:\n            voxels[voxelidx, num] = points[i]\n            num_points_per_voxel[voxelidx] += 1\n    return voxel_num\n\n\n@numba.jit(nopython=True)\ndef _points_to_voxel_kernel(points,\n                            voxel_size,\n                            coors_range,\n                            num_points_per_voxel,\n                            coor_to_voxelidx,\n                            voxels,\n                            coors,\n                            max_points=35,\n                            max_voxels=20000):\n    \"\"\"convert kitti points(N, >=3) to voxels.\n\n    Args:\n        points (np.ndarray): [N, ndim]. points[:, :3] contain xyz points and \\\n            points[:, 3:] contain other information such as reflectivity.\n        voxel_size (list, tuple, np.ndarray): [3] xyz, indicate voxel size.\n        coors_range (list[float | tuple[float] | ndarray]): Range of voxels. \\\n            format: xyzxyz, minmax\n        num_points_per_voxel (int): Number of points per voxel.\n        coor_to_voxel_idx (np.ndarray): A voxel grid of shape (D, H, W), \\\n            which has the same shape as the complete voxel map. It indicates \\\n            the index of each corresponding voxel.\n        voxels (np.ndarray): Created empty voxels.\n        coors (np.ndarray): Created coordinates of each voxel.\n        max_points (int): Indicate maximum points contained in a voxel.\n        max_voxels (int): Maximum number of voxels this function create. \\\n            for second, 20000 is a good choice. Points should be shuffled for \\\n            randomness before this function because max_voxels drops points.\n\n    Returns:\n        tuple[np.ndarray]:\n            voxels: Shape [M, max_points, ndim], only contain points.\n            coordinates: Shape [M, 3].\n            num_points_per_voxel: Shape [M].\n    \"\"\"\n    N = points.shape[0]\n    # ndim = points.shape[1] - 1\n    ndim = 3\n    grid_size = (coors_range[3:] - coors_range[:3]) / voxel_size\n    # grid_size = np.round(grid_size).astype(np.int64)(np.int32)\n    grid_size = np.round(grid_size, 0, grid_size).astype(np.int32)\n\n    # lower_bound = coors_range[:3]\n    # upper_bound = coors_range[3:]\n    coor = np.zeros(shape=(3, ), dtype=np.int32)\n    voxel_num = 0\n    failed = False\n    for i in range(N):\n        failed = False\n        for j in range(ndim):\n            c = np.floor((points[i, j] - coors_range[j]) / voxel_size[j])\n            if c < 0 or c >= grid_size[j]:\n                failed = True\n                break\n            coor[j] = c\n        if failed:\n            continue\n        voxelidx = coor_to_voxelidx[coor[0], coor[1], coor[2]]\n        if voxelidx == -1:\n            voxelidx = voxel_num\n            if voxel_num >= max_voxels:\n                continue\n            voxel_num += 1\n            coor_to_voxelidx[coor[0], coor[1], coor[2]] = voxelidx\n            coors[voxelidx] = coor\n        num = num_points_per_voxel[voxelidx]\n        if num < max_points:\n            voxels[voxelidx, num] = points[i]\n            num_points_per_voxel[voxelidx] += 1\n    return voxel_num\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/B2D_dataset.py",
    "content": "import copy\nimport numpy as np\nfrom mmcv.datasets import DATASETS\nfrom os import path as osp\nimport torch\nfrom pyquaternion import Quaternion\nfrom mmcv.utils import save_tensor\nfrom mmcv.parallel import DataContainer as DC\nimport random\nfrom .custom_3d import Custom3DDataset\nfrom .pipelines import Compose\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import track_iter_progress, mkdir_or_exist\nimport tempfile\nfrom .nuscenes_styled_eval_utils import DetectionMetrics, EvalBoxes, DetectionBox,center_distance,accumulate,DetectionMetricDataList,calc_ap, calc_tp, quaternion_yaw\nimport json\n\n@DATASETS.register_module()\nclass B2D_Dataset(Custom3DDataset):\n\n\n    def __init__(self, queue_length=4, bev_size=(200, 200),overlap_test=False,with_velocity=True,sample_interval=5,name_mapping= None,eval_cfg = None ,*args, **kwargs):\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.overlap_test = overlap_test\n        self.with_velocity = with_velocity\n        if name_mapping is not None:\n            self.NameMapping  = name_mapping\n        else:\n            self.NameMapping = {\n                'vehicle.bh.crossbike': 'bicycle',\n                \"vehicle.diamondback.century\": 'bicycle',\n                \"vehicle.chevrolet.impala\": 'car',\n                \"vehicle.dodge.charger_2020\": 'car',\n                \"vehicle.dodge.charger_police_2020\": 'car',\n                \"vehicle.lincoln.mkz_2017\": 'car',\n                \"vehicle.lincoln.mkz_2020\": 'car',\n                \"vehicle.mini.cooper_s_2021\": 'car',\n                \"vehicle.mercedes.coupe_2020\": 'car',\n                \"vehicle.ford.mustang\": 'car',\n                \"vehicle.nissan.patrol_2021\": 'car',\n                \"vehicle.audi.tt\": 'car',\n                \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n                \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n                \"traffic.speed_limit.30\": 'speed_limit',\n                \"traffic.speed_limit.40\": 'speed_limit',\n                \"traffic.speed_limit.50\": 'speed_limit',\n                \"traffic.speed_limit.60\": 'speed_limit',\n                \"traffic.traffic_light\": 'traffic_light',\n                \"traffic.stop\": 'stop',\n            }\n        if eval_cfg is not None:\n            self.eval_cfg  = eval_cfg\n        else:\n            self.eval_cfg = {\n                \"dist_ths\": [0.5, 1.0, 2.0, 4.0],\n                \"dist_th_tp\": 2.0,\n                \"min_recall\": 0.1,\n                \"min_precision\": 0.1,\n                \"mean_ap_weight\": 5,\n                \"class_names\":['car','van','bicycle'],\n                \"tp_metrics\":['trans_err', 'scale_err', 'orient_err', 'vel_err'],\n                \"err_name_maping\":{'trans_err': 'mATE','scale_err': 'mASE','orient_err': 'mAOE','vel_err': 'mAVE','attr_err': 'mAAE'}\n            }\n        self.sample_interval = sample_interval\n\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        queue = []\n        index_list = list(range(index-self.queue_length*self.sample_interval, index,self.sample_interval))\n        random.shuffle(index_list)\n        index_list = sorted(index_list[1:])\n        index_list.append(index)\n        for i in index_list:\n            i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            self.pre_pipeline(input_dict)\n            example = self.pipeline(input_dict)\n            if self.filter_empty_gt and \\\n                    (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n                return None\n            queue.append(example)\n        return self.union2one(queue)\n\n\n    def union2one(self, queue):\n        imgs_list = [each['img'].data for each in queue]\n        metas_map = {}\n        prev_scene_token = None\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if metas_map[i]['folder'] != prev_scene_token:\n                metas_map[i]['prev_bev_exists'] = False\n                prev_scene_token = metas_map[i]['folder']\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev_exists'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n        queue[-1]['img'] = DC(torch.stack(imgs_list), cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n        return queue\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n\n        input_dict = dict(\n            folder=info['folder'],\n            scene_token=info['folder'],\n            frame_idx=info['frame_idx'],\n            ego_yaw=np.nan_to_num(info['ego_yaw'],nan=90),\n            ego_translation=info['ego_translation'],\n            sensors=info['sensors'],\n            gt_ids=info['gt_ids'],\n            gt_boxes=info['gt_boxes'],\n            gt_names=info['gt_names'],\n            ego_vel = info['ego_vel'],\n            ego_accel = info['ego_accel'],\n            ego_rotation_rate = info['ego_rotation_rate'],\n        )\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            lidar2ego = info['sensors']['LIDAR_TOP']['lidar2ego']\n            for sensor_type, cam_info in info['sensors'].items():\n                if not 'CAM' in sensor_type:\n                    continue\n                image_paths.append(osp.join(self.data_root,cam_info['data_path']))\n                cam2ego = cam_info['cam2ego']\n                intrinsic = cam_info['intrinsic']\n                intrinsic_pad = np.eye(4)\n                intrinsic_pad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2cam = self.invert_pose(cam2ego) @ lidar2ego\n                lidar2img = intrinsic_pad @ lidar2cam\n                lidar2img_rts.append(lidar2img)\n                cam_intrinsics.append(intrinsic_pad)\n                lidar2cam_rts.append(lidar2cam)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                ))\n\n        if not self.test_mode:\n            annos = self.get_ann_info(index)\n            input_dict['ann_info'] = annos\n        yaw = input_dict['ego_yaw']\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=yaw))\n        if yaw < 0:\n            yaw += 2*np.pi\n        yaw_in_degree = yaw / np.pi * 180 \n        can_bus = np.zeros(18)\n        can_bus[:3] = input_dict['ego_translation']\n        can_bus[3:7] = rotation\n        can_bus[7:10] = input_dict['ego_vel']\n        can_bus[10:13] = input_dict['ego_accel']\n        can_bus[13:16] = input_dict['ego_rotation_rate']\n        can_bus[16] = yaw\n        can_bus[17] = yaw_in_degree\n        input_dict['can_bus'] = can_bus\n\n        return input_dict\n    \n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n        mask = (info['num_points'] >= -1)\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_labels_3d = []\n\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n        if not self.with_velocity:\n            gt_bboxes_3d = gt_bboxes_3d[:,0:7]\n\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d)\n        return anns_results\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n        \n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n        result_path = result_files['pts_bbox']\n        with open(result_path) as f:\n            result_data = json.load(f)\n        pred_boxes = EvalBoxes.deserialize(result_data['results'], DetectionBox)\n        meta = result_data['meta']\n\n\n        gt_boxes = self.load_gt()\n\n        metric_data_list = DetectionMetricDataList()\n        for class_name in self.eval_cfg['class_names']:\n            for dist_th in self.eval_cfg['dist_ths']:\n                md = accumulate(gt_boxes, pred_boxes, class_name, center_distance, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics = DetectionMetrics(self.eval_cfg)\n\n        for class_name in self.eval_cfg['class_names']:\n            # Compute APs.\n            for dist_th in self.eval_cfg['dist_ths']:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.eval_cfg['min_recall'], self.eval_cfg['min_precision'])\n                metrics.add_label_ap(class_name, dist_th, ap)\n\n            # Compute TP metrics.\n            for metric_name in self.eval_cfg['tp_metrics']:\n                metric_data = metric_data_list[(class_name, self.eval_cfg['dist_th_tp'])]\n                tp = calc_tp(metric_data, self.eval_cfg['min_recall'], metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        metrics_summary = metrics.serialize()\n        metrics_summary['meta'] = meta.copy()\n        print('mAP: %.4f' % (metrics_summary['mean_ap']))\n        err_name_mapping = {\n            'trans_err': 'mATE',\n            'scale_err': 'mASE',\n            'orient_err': 'mAOE',\n            'vel_err': 'mAVE',\n        }\n        for tp_name, tp_val in metrics_summary['tp_errors'].items():\n            print('%s: %.4f' % (err_name_mapping[tp_name], tp_val))\n        print('NDS: %.4f' % (metrics_summary['nd_score']))\n        #print('Eval time: %.1fs' % metrics_summary['eval_time'])\n\n        # Print per-class metrics.\n        print()\n        print('Per-class results:')\n        print('Object Class\\tAP\\tATE\\tASE\\tAOE\\tAVE')\n        class_aps = metrics_summary['mean_dist_aps']\n        class_tps = metrics_summary['label_tp_errors']\n        for class_name in class_aps.keys():\n            print('%s\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f'\n                  % (class_name, class_aps[class_name],\n                     class_tps[class_name]['trans_err'],\n                     class_tps[class_name]['scale_err'],\n                     class_tps[class_name]['orient_err'],\n                     class_tps[class_name]['vel_err']))        \n\n        detail = dict()\n        metric_prefix = 'bbox_NuScenes'\n        for name in self.eval_cfg['class_names']:\n            for k, v in metrics_summary['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,self.eval_cfg['err_name_maping'][k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics_summary['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics_summary['mean_ap']\n\n\n        return detail\n    \n\n    def load_gt(self):\n        all_annotations = EvalBoxes()\n        for i in range(len(self.data_infos)):\n            sample_boxes = []\n            sample_data = self.data_infos[i]\n\n            gt_boxes = sample_data['gt_boxes']\n            \n            for j in range(gt_boxes.shape[0]):\n                class_name = self.NameMapping[sample_data['gt_names'][j]]\n                if not class_name in self.eval_cfg['class_range'].keys():\n                    continue\n                range_x, range_y = self.eval_cfg['class_range'][class_name]\n                if abs(gt_boxes[j,0]) > range_x or abs(gt_boxes[j,1]) > range_y:\n                    continue\n                sample_boxes.append(DetectionBox(\n                                                sample_token=sample_data['folder']+'_'+str(sample_data['frame_idx']),\n                                                translation=gt_boxes[j,0:3],\n                                                size=gt_boxes[j,3:6],\n                                                rotation=list(Quaternion(axis=[0, 0, 1], radians=-gt_boxes[j,6]-np.pi/2)),\n                                                velocity=gt_boxes[j,7:9],\n                                                num_pts=int(sample_data['num_points'][j]),\n                                                detection_name=self.NameMapping[sample_data['gt_names'][j]],\n                                                detection_score=-1.0,  \n                                                attribute_name=self.NameMapping[sample_data['gt_names'][j]]\n                                                ))\n            all_annotations.add_boxes(sample_data['folder']+'_'+str(sample_data['frame_idx']), sample_boxes)\n        return all_annotations\n    \n    def _format_bbox(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n\n\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            #pdb.set_trace()\n            annos = []\n            box3d = det['boxes_3d']\n            scores = det['scores_3d']\n            labels = det['labels_3d']\n            box_gravity_center = box3d.gravity_center\n            box_dims = box3d.dims\n            box_yaw = box3d.yaw.numpy()\n            box_yaw = -box_yaw - np.pi / 2\n            sample_token = self.data_infos[sample_id]['folder'] + '_' + str(self.data_infos[sample_id]['frame_idx'])\n\n\n\n            for i in range(len(box3d)):\n                #import pdb;pdb.set_trace()\n                quat = list(Quaternion(axis=[0, 0, 1], radians=box_yaw[i]))\n                velocity = [box3d.tensor[i, 7].item(),box3d.tensor[i, 8].item()]\n                name = mapped_class_names[labels[i]]\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box_gravity_center[i].tolist(),\n                    size=box_dims[i].tolist(),\n                    rotation=quat,\n                    velocity=velocity,\n                    detection_name=name,\n                    detection_score=scores[i].item(),\n                    attribute_name=name)\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n        }\n\n        mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path  \n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        return result_files, tmp_dir\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/B2D_e2e_dataset.py",
    "content": "import copy\nimport numpy as np\nimport os\nfrom os import path as osp\nimport torch\nimport random\nimport json, pickle\nimport tempfile\nimport cv2\nfrom pyquaternion import Quaternion\nfrom mmcv.datasets import DATASETS\nfrom mmcv.utils import save_tensor\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import track_iter_progress, mkdir_or_exist\nfrom mmcv.datasets.pipelines import to_tensor\nfrom .custom_3d import Custom3DDataset\nfrom .pipelines import Compose\nfrom .nuscenes_styled_eval_utils import DetectionMetrics, EvalBoxes, DetectionBox,center_distance,accumulate,DetectionMetricDataList,calc_ap, calc_tp, quaternion_yaw\nfrom prettytable import PrettyTable\n\n\n\n@DATASETS.register_module()\nclass B2D_E2E_Dataset(Custom3DDataset):\n    def __init__(self, queue_length=4, bev_size=(200, 200),overlap_test=False,with_velocity=True,sample_interval=5,name_mapping= None,eval_cfg = None, map_root =None,map_file=None,past_frames=4, future_frames=4,predict_frames=12,planning_frames=6,patch_size = [102.4, 102.4],point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0] ,occ_receptive_field=3,occ_n_future=6,occ_filter_invalid_sample=False,occ_filter_by_valid_flag=False,eval_mod=None,*args, **kwargs):\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.bev_size = (200, 200)\n        self.overlap_test = overlap_test\n        self.with_velocity = with_velocity\n        self.NameMapping  = name_mapping\n        self.eval_cfg  = eval_cfg\n        self.sample_interval = sample_interval\n        self.past_frames = past_frames\n        self.future_frames = future_frames\n        self.predict_frames = predict_frames\n        self.planning_frames = planning_frames\n        self.map_root = map_root\n        self.map_file = map_file\n        self.point_cloud_range = np.array(point_cloud_range)\n        self.patch_size = patch_size\n        self.occ_receptive_field = occ_receptive_field  # past + current\n        self.occ_n_future = occ_n_future  # future only\n        self.occ_filter_invalid_sample = occ_filter_invalid_sample\n        self.occ_filter_by_valid_flag = occ_filter_by_valid_flag\n        self.occ_only_total_frames = 7  # NOTE: hardcode, not influenced by planning   \n        self.eval_mod = eval_mod     \n        self.map_element_class = {'Broken':0, 'Solid':1, 'SolidSolid':2,'Center':3,'TrafficLight':4,'StopSign':5}\n        with open(self.map_file,'rb') as f: \n            self.map_infos = pickle.load(f)\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        queue = []\n        index_list = list(range(index-self.queue_length*self.sample_interval, index,self.sample_interval))\n        random.shuffle(index_list)\n        index_list = sorted(index_list[1:])\n        index_list.append(index)\n        for i in index_list:\n            i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            self.pre_pipeline(input_dict)\n            example = self.pipeline(input_dict)\n            if self.filter_empty_gt and \\\n                    (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n                return None\n            queue.append(example)\n        return self.union2one(queue)\n    \n    def union2one(self, queue):\n        imgs_list = [each['img'].data for each in queue]\n        gt_labels_3d_list = [each['gt_labels_3d'].data for each in queue]\n        gt_sdc_label_list = [each['gt_sdc_label'].data for each in queue]\n        gt_inds_list = [to_tensor(each['gt_inds']) for each in queue]\n        gt_bboxes_3d_list = [each['gt_bboxes_3d'].data for each in queue]\n        gt_past_traj_list = [to_tensor(each['gt_past_traj']) for each in queue]\n        gt_past_traj_mask_list = [ to_tensor(each['gt_past_traj_mask']) for each in queue]\n        gt_sdc_bbox_list = [each['gt_sdc_bbox'].data for each in queue]\n        l2g_r_mat_list = [to_tensor(each['l2g_r_mat']) for each in queue]\n        l2g_t_list = [to_tensor(each['l2g_t']) for each in queue]\n        timestamp_list = [to_tensor(each['timestamp']) for each in queue]\n        gt_fut_traj = to_tensor(queue[-1]['gt_fut_traj'])\n        gt_fut_traj_mask = to_tensor(queue[-1]['gt_fut_traj_mask'])\n        if 'gt_future_boxes' in queue[-1]:\n            gt_future_boxes_list = queue[-1]['gt_future_boxes']\n        else:\n            gt_future_boxes_list = None\n        if 'gt_future_labels' in queue[-1]:    \n            gt_future_labels_list = [to_tensor(each) for each in queue[-1]['gt_future_labels']]\n        else:\n            gt_future_labels_list = None\n\n        metas_map = {}\n        prev_scene_token = None\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if metas_map[i]['folder'] != prev_scene_token:\n                metas_map[i]['prev_bev_exists'] = False\n                prev_scene_token = metas_map[i]['folder']\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev_exists'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n        queue[-1]['img'] = DC(torch.stack(imgs_list), cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n        queue['gt_labels_3d'] = DC(gt_labels_3d_list)\n        queue['gt_sdc_label'] = DC(gt_sdc_label_list)\n        queue['gt_inds'] = DC(gt_inds_list)\n        queue['gt_bboxes_3d'] = DC(gt_bboxes_3d_list, cpu_only=True)\n        queue['gt_sdc_bbox'] = DC(gt_sdc_bbox_list, cpu_only=True)\n        queue['l2g_r_mat'] = DC(l2g_r_mat_list)\n        queue['l2g_t'] = DC(l2g_t_list)\n        queue['timestamp'] = DC(timestamp_list)\n        queue['gt_fut_traj'] = DC(gt_fut_traj)\n        queue['gt_fut_traj_mask'] = DC(gt_fut_traj_mask)\n        queue['gt_past_traj'] = DC(gt_past_traj_list)\n        queue['gt_past_traj_mask'] = DC(gt_past_traj_mask_list)\n        if gt_future_boxes_list is not None:\n            queue['gt_future_boxes'] = DC(gt_future_boxes_list, cpu_only=True)\n        if gt_future_labels_list is not None:\n            queue['gt_future_labels'] = DC(gt_future_labels_list)\n\n        return queue\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n\n\n        gt_masks,gt_labels,gt_bboxes = self.get_map_info(index)\n\n\n        input_dict = dict(\n            folder=info['folder'],\n            scene_token=info['folder'],\n            frame_idx=info['frame_idx'],\n            ego_yaw=np.nan_to_num(info['ego_yaw'],nan=np.pi/2),\n            ego_translation=info['ego_translation'],\n            sensors=info['sensors'],\n            world2lidar=info['sensors']['LIDAR_TOP']['world2lidar'],\n            gt_ids=info['gt_ids'],\n            gt_boxes=info['gt_boxes'],\n            gt_names=info['gt_names'],\n            ego_vel = info['ego_vel'],\n            ego_accel = info['ego_accel'],\n            ego_rotation_rate = info['ego_rotation_rate'],\n            npc2world = info['npc2world'],\n            gt_lane_labels=gt_labels,\n            gt_lane_bboxes=gt_bboxes,\n            gt_lane_masks=gt_masks,\n            timestamp=info['frame_idx']/10\n\n        )\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            lidar2ego = info['sensors']['LIDAR_TOP']['lidar2ego']\n            for sensor_type, cam_info in info['sensors'].items():\n                if not 'CAM' in sensor_type:\n                    continue\n                image_paths.append(osp.join(self.data_root,cam_info['data_path']))\n                # obtain lidar to image transformation matrix\n                cam2ego = cam_info['cam2ego']\n                intrinsic = cam_info['intrinsic']\n                intrinsic_pad = np.eye(4)\n                intrinsic_pad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2cam = self.invert_pose(cam2ego) @ lidar2ego\n                lidar2img = intrinsic_pad @ lidar2cam\n                lidar2img_rts.append(lidar2img)\n                cam_intrinsics.append(intrinsic_pad)\n                lidar2cam_rts.append(lidar2cam)\n            ego2world = np.eye(4)\n            ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=input_dict['ego_yaw']).rotation_matrix\n            ego2world[0:3,3] = input_dict['ego_translation']\n            lidar2global = ego2world @ lidar2ego\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                    l2g_r_mat=lidar2global[0:3,0:3],\n                    l2g_t=lidar2global[0:3,3]\n\n                ))\n\n        annos = self.get_ann_info(index)\n        input_dict['ann_info'] = annos\n        yaw = input_dict['ego_yaw']\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=yaw))\n        if yaw < 0:\n            yaw += 2*np.pi\n        yaw_in_degree = yaw / np.pi * 180 \n        \n        can_bus = np.zeros(18)\n        can_bus[:3] = input_dict['ego_translation']\n        can_bus[3:7] = rotation\n        can_bus[7:10] = input_dict['ego_vel']\n        can_bus[10:13] = input_dict['ego_accel']\n        can_bus[13:16] = input_dict['ego_rotation_rate']\n        can_bus[16] = yaw\n        can_bus[17] = yaw_in_degree\n        input_dict['can_bus'] = can_bus\n        all_frames = []\n        for adj_idx in range(index-self.occ_receptive_field+1,index+self.occ_n_future+1):\n            if adj_idx<0 or adj_idx>=len(self.data_infos):\n                all_frames.append(-1)\n            elif self.data_infos[adj_idx]['folder'] != self.data_infos[index]['folder']:\n                all_frames.append(-1)\n            else: \n                all_frames.append(adj_idx)\n            \n        future_frames = all_frames[self.occ_receptive_field-1:]\n        input_dict['occ_has_invalid_frame'] = (-1 in all_frames[:self.occ_only_total_frames])\n        input_dict['occ_img_is_valid'] = np.array(all_frames) >= 0\n        occ_future_ann_infos = []\n        for future_frame in future_frames:\n            if future_frame >= 0:\n                occ_future_ann_infos.append(\n                    self.get_ann_boxes_only(future_frame),\n                )\n            else:\n                occ_future_ann_infos.append(None)\n        input_dict['occ_future_ann_infos'] = occ_future_ann_infos\n\n        input_dict.update(self.occ_get_transforms(future_frames))\n        sdc_planning, sdc_planning_mask = self.get_ego_future_xy(index,self.sample_interval,self.planning_frames)\n        input_dict['sdc_planning'] = sdc_planning\n        input_dict['sdc_planning_mask'] = sdc_planning_mask\n        command = info['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        input_dict['command'] = command\n\n        return input_dict\n\n\n    def get_map_info(self, index):\n\n        gt_masks = []\n        gt_labels = []\n        gt_bboxes = []\n\n        ann_info = self.data_infos[index]\n        town_name = ann_info['town_name']\n        map_info = self.map_infos[town_name]\n        lane_points = map_info['lane_points']\n        lane_sample_points = map_info['lane_sample_points']\n        lane_types = map_info['lane_types']\n        trigger_volumes_points = map_info['trigger_volumes_points']\n        trigger_volumes_sample_points = map_info['trigger_volumes_sample_points']\n        trigger_volumes_types = map_info['trigger_volumes_types']\n        world2lidar = np.array(ann_info['sensors']['LIDAR_TOP']['world2lidar'])\n        ego_xy = np.linalg.inv(world2lidar)[0:2,3]\n\n        #1st search\n        max_distance = 100\n        chosed_idx = []\n        for idx in range(len(lane_sample_points)):\n            single_sample_points = lane_sample_points[idx]\n            distance = np.linalg.norm((single_sample_points[:,0:2]-ego_xy),axis=-1)\n            if np.min(distance) < max_distance:\n                chosed_idx.append(idx)\n\n        for idx in chosed_idx:\n            if not lane_types[idx] in self.map_element_class.keys():\n                continue\n            points = lane_points[idx]\n            points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n            points_in_ego = (world2lidar @ points.T).T\n            #print(points_in_ego)\n            mask = (points_in_ego[:,0]>self.point_cloud_range[0]) & (points_in_ego[:,0]<self.point_cloud_range[3]) & (points_in_ego[:,1]>self.point_cloud_range[1]) & (points_in_ego[:,1]<self.point_cloud_range[4])\n            points_in_ego_range = points_in_ego[mask,0:2]\n            if len(points_in_ego_range) > 1:\n                gt_mask = np.zeros(self.bev_size,dtype=np.uint8)\n                normalized_points = np.zeros_like(points_in_ego_range)\n                normalized_points[:,0] = (points_in_ego_range[:,0] + self.patch_size[0]/2)*(self.bev_size[0]/self.patch_size[0])\n                normalized_points[:,1] = (points_in_ego_range[:,1] + self.patch_size[1]/2)*(self.bev_size[1]/self.patch_size[1])\n                cv2.polylines(gt_mask, [normalized_points.astype(np.int32)], False, color=1, thickness=2)\n                gt_label =  self.map_element_class[lane_types[idx]]\n                gt_masks.append(gt_mask)\n                gt_labels.append(gt_label)\n                ys, xs = np.where(gt_mask==1)\n                gt_bboxes.append([min(xs), min(ys), max(xs), max(ys)]) \n\n        for idx in range(len(trigger_volumes_points)):\n            if not trigger_volumes_types[idx] in self.map_element_class.keys():\n                continue\n            points = trigger_volumes_points[idx]\n            points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n            points_in_ego = (world2lidar @ points.T).T\n            mask = (points_in_ego[:,0]>self.point_cloud_range[0]) & (points_in_ego[:,0]<self.point_cloud_range[3]) & (points_in_ego[:,1]>self.point_cloud_range[1]) & (points_in_ego[:,1]<self.point_cloud_range[4])\n            points_in_ego_range = points_in_ego[mask,0:2]\n            if mask.all():\n                gt_mask = np.zeros(self.bev_size,dtype=np.uint8)\n                normalized_points = np.zeros_like(points_in_ego_range)\n                normalized_points[:,0] = (points_in_ego_range[:,0] + self.patch_size[0]/2)*(self.bev_size[0]/self.patch_size[0])\n                normalized_points[:,1] = (points_in_ego_range[:,1] + self.patch_size[1]/2)*(self.bev_size[1]/self.patch_size[1])\n                cv2.fillConvexPoly(gt_mask, normalized_points.astype(np.int32), color=1)\n                gt_label = self.map_element_class[trigger_volumes_types[idx]]\n                gt_masks.append(gt_mask)\n                gt_labels.append(gt_label)\n                ys, xs = np.where(gt_mask==1)\n                gt_bboxes.append([min(xs), min(ys), max(xs), max(ys)]) \n\n        if len(gt_masks) == 0:\n            gt_masks.append(np.zeros(self.bev_size,dtype=np.uint8))\n            gt_labels.append(-1)\n            gt_bboxes.append([0,0,0,0])\n\n        gt_masks = np.stack(gt_masks)\n        gt_labels = np.array(gt_labels)\n        gt_bboxes = np.array(gt_bboxes)\n\n        return gt_masks,gt_labels,gt_bboxes\n\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n        mask = (info['num_points'] >= -1)\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_inds = info['gt_ids']\n        gt_labels_3d = []\n\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n        if not self.with_velocity:\n            gt_bboxes_3d = gt_bboxes_3d[:,0:7]\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        \n        ego_future_track, ego_future_mask = self.get_ego_future_xy(index,self.sample_interval,self.predict_frames)\n        past_track, past_mask = self.get_past_or_future_xy(index,self.sample_interval,self.past_frames,past_or_future='past',local_xy=True)\n        predict_track, predict_mask = self.get_past_or_future_xy(index,self.sample_interval,self.predict_frames,past_or_future='future',local_xy=False)\n        mask = (past_mask.sum((1,2))>0).astype(np.int)\n        future_track = predict_track[:,0:self.future_frames,:]*mask[:,None,None]\n        future_mask = predict_mask[:,0:self.future_frames,:]*mask[:,None,None]\n        full_past_track = np.concatenate([past_track,future_track],axis=1)\n        full_past_mask = np.concatenate([past_mask,future_mask],axis=1)\n        gt_sdc_bbox, gt_sdc_label =self.generate_sdc_info(index)\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n            gt_inds=gt_inds,\n            gt_fut_traj=predict_track,\n            gt_fut_traj_mask=predict_mask,\n            gt_past_traj=full_past_track,\n            gt_past_traj_mask=full_past_mask,\n            gt_sdc_bbox=gt_sdc_bbox,\n            gt_sdc_label=gt_sdc_label,\n            gt_sdc_fut_traj=ego_future_track[:,:,0:2],\n            gt_sdc_fut_traj_mask=ego_future_mask,\n            )\n        return anns_results\n\n    def get_ann_boxes_only(self, index):\n\n        info = self.data_infos[index]\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n        gt_bboxes_3d = info['gt_boxes']\n        gt_names_3d = info['gt_names']\n        gt_inds = info['gt_ids']\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            \n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n        if not self.with_velocity:\n            gt_bboxes_3d = gt_bboxes_3d[:,0:7]\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        boxes_annos = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_inds=gt_inds,\n            )\n        return boxes_annos\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n        \n    def generate_sdc_info(self,idx):\n\n        info = self.data_infos[idx]\n        ego_size = info['ego_size']\n        ego_vel = info['ego_vel']\n        psudo_sdc_bbox = np.array([0.0, 0.0, 0.0, ego_size[0], ego_size[1], ego_size[2], -np.pi, ego_vel[1], ego_vel[0] ])\n        if not self.with_velocity:\n            psudo_sdc_bbox = psudo_sdc_bbox[0:7]\n        gt_bboxes_3d = np.array([psudo_sdc_bbox]).astype(np.float32)\n        gt_names_3d = ['car']\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        # the nuscenes box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n  \n        gt_labels_3d = DC(to_tensor(gt_labels_3d))\n        gt_bboxes_3d = DC(gt_bboxes_3d, cpu_only=True)\n\n        return gt_bboxes_3d, gt_labels_3d\n\n    def get_past_or_future_xy(self,idx,sample_rate,frames,past_or_future,local_xy=False):\n\n        assert past_or_future in ['past','future']\n        if past_or_future == 'past':\n            adj_idx_list = range(idx-sample_rate,idx-(frames+1)*sample_rate,-sample_rate)\n        else:\n            adj_idx_list = range(idx+sample_rate,idx+(frames+1)*sample_rate,sample_rate)\n\n        cur_frame = self.data_infos[idx]\n        box_ids = cur_frame['gt_ids']\n        adj_track = np.zeros((len(box_ids),frames,2))\n        adj_mask = np.zeros((len(box_ids),frames,2))\n        world2lidar_ego_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for i in range(len(box_ids)):\n            box_id = box_ids[i]\n            cur_box2lidar = world2lidar_ego_cur @ cur_frame['npc2world'][i]\n            cur_xy = cur_box2lidar[0:2,3]      \n            for j in range(len(adj_idx_list)):\n                adj_idx = adj_idx_list[j]\n                if adj_idx <0 or adj_idx>=len(self.data_infos):\n                    break\n                adj_frame = self.data_infos[adj_idx]\n                if adj_frame['folder'] != cur_frame ['folder']:\n                    break\n                if len(np.where(adj_frame['gt_ids']==box_id)[0])==0:\n                    continue\n                assert len(np.where(adj_frame['gt_ids']==box_id)[0]) == 1 , np.where(adj_frame['gt_ids']==box_id)[0]\n                adj_idx = np.where(adj_frame['gt_ids']==box_id)[0][0]\n                adj_box2lidar = world2lidar_ego_cur @ adj_frame['npc2world'][adj_idx]\n                adj_xy = adj_box2lidar[0:2,3]    \n                if local_xy:\n                    adj_xy -= cur_xy\n                adj_track[i,j,:] = adj_xy\n                adj_mask[i,j,:] = 1\n        return adj_track, adj_mask\n\n    def get_ego_future_xy(self,idx,sample_rate,frames):\n\n        adj_idx_list = range(idx+sample_rate,idx+(frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        adj_track = np.zeros((1,frames,3))\n        adj_mask = np.zeros((1,frames,2))\n        world2lidar_ego_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for j in range(len(adj_idx_list)):\n            adj_idx = adj_idx_list[j]\n            if adj_idx <0 or adj_idx>=len(self.data_infos):\n                break\n            adj_frame = self.data_infos[adj_idx]\n            if adj_frame['folder'] != cur_frame ['folder']:\n                break\n            world2lidar_ego_adj = adj_frame['sensors']['LIDAR_TOP']['world2lidar']\n            adj2cur_lidar = world2lidar_ego_cur @ np.linalg.inv(world2lidar_ego_adj)\n            xy = adj2cur_lidar[0:2,3]\n            yaw = np.arctan2(adj2cur_lidar[1,0],adj2cur_lidar[0,0])\n            yaw = -yaw -np.pi\n            while yaw > np.pi:\n                yaw -= np.pi*2\n            while yaw < -np.pi:\n                yaw += np.pi*2\n            adj_track[0,j,0:2] = xy\n            adj_track[0,j,2] = yaw\n            adj_mask[0,j,:] = 1\n\n        return adj_track, adj_mask\n\n    def occ_get_transforms(self, indices, data_type=torch.float32):\n\n        l2e_r_mats = []\n        l2e_t_vecs = []\n        e2g_r_mats = []\n        e2g_t_vecs = []\n\n        for index in indices:\n            if index == -1:\n                l2e_r_mats.append(None)\n                l2e_t_vecs.append(None)\n                e2g_r_mats.append(None)\n                e2g_t_vecs.append(None)\n            else:\n                info = self.data_infos[index]\n                lidar2ego = info['sensors']['LIDAR_TOP']['lidar2ego']\n                l2e_r = lidar2ego[0:3,0:3]\n                l2e_t = lidar2ego[0:3,3]\n                ego2global = np.linalg.inv(info['world2ego'])\n                e2g_r = ego2global[0:3,0:3]\n                e2g_t = ego2global[0:3,3]\n                l2e_r_mats.append(torch.tensor(l2e_r).to(data_type))\n                l2e_t_vecs.append(torch.tensor(l2e_t).to(data_type))\n                e2g_r_mats.append(torch.tensor(e2g_r).to(data_type))\n                e2g_t_vecs.append(torch.tensor(e2g_t).to(data_type))\n        res = {\n            'occ_l2e_r_mats': l2e_r_mats,\n            'occ_l2e_t_vecs': l2e_t_vecs,\n            'occ_e2g_r_mats': e2g_r_mats,\n            'occ_e2g_t_vecs': e2g_t_vecs,\n        }\n\n        return res\n\n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n\n        # NOTE:Curremtly we only support evaluation on detection and planning \n\n        result_files, tmp_dir = self.format_results(results['bbox_results'], jsonfile_prefix)    \n        result_path = result_files\n        with open(result_path) as f:\n            result_data = json.load(f)\n        pred_boxes = EvalBoxes.deserialize(result_data['results'], DetectionBox)\n        meta = result_data['meta']\n\n        gt_boxes = self.load_gt()\n\n        metric_data_list = DetectionMetricDataList()\n        for class_name in self.eval_cfg['class_names']:\n            for dist_th in self.eval_cfg['dist_ths']:\n                md = accumulate(gt_boxes, pred_boxes, class_name, center_distance, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics = DetectionMetrics(self.eval_cfg)\n\n        for class_name in self.eval_cfg['class_names']:\n            # Compute APs.\n            for dist_th in self.eval_cfg['dist_ths']:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.eval_cfg['min_recall'], self.eval_cfg['min_precision'])\n                metrics.add_label_ap(class_name, dist_th, ap)\n\n            # Compute TP metrics.\n            for metric_name in self.eval_cfg['tp_metrics']:\n                metric_data = metric_data_list[(class_name, self.eval_cfg['dist_th_tp'])]\n                tp = calc_tp(metric_data, self.eval_cfg['min_recall'], metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        metrics_summary = metrics.serialize()\n        metrics_summary['meta'] = meta.copy()\n        print('mAP: %.4f' % (metrics_summary['mean_ap']))\n        err_name_mapping = {\n            'trans_err': 'mATE',\n            'scale_err': 'mASE',\n            'orient_err': 'mAOE',\n            'vel_err': 'mAVE',\n        }\n        for tp_name, tp_val in metrics_summary['tp_errors'].items():\n            print('%s: %.4f' % (err_name_mapping[tp_name], tp_val))\n        print('NDS: %.4f' % (metrics_summary['nd_score']))\n        #print('Eval time: %.1fs' % metrics_summary['eval_time'])\n\n        # Print per-class metrics.\n        print()\n        print('Per-class results:')\n        print('Object Class\\tAP\\tATE\\tASE\\tAOE\\tAVE')\n        class_aps = metrics_summary['mean_dist_aps']\n        class_tps = metrics_summary['label_tp_errors']\n        for class_name in class_aps.keys():\n            print('%s\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f'\n                  % (class_name, class_aps[class_name],\n                     class_tps[class_name]['trans_err'],\n                     class_tps[class_name]['scale_err'],\n                     class_tps[class_name]['orient_err'],\n                     class_tps[class_name]['vel_err']))        \n\n        detail = dict()\n        metric_prefix = 'bbox_NuScenes'\n        for name in self.eval_cfg['class_names']:\n            for k, v in metrics_summary['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,self.eval_cfg['err_name_maping'][k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics_summary['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics_summary['mean_ap']\n\n        if 'planning_results_computed' in results.keys():\n                planning_results_computed = results['planning_results_computed']\n                planning_tab = PrettyTable()\n                planning_tab.field_names = [\n                    \"metrics\", \"0.5s\", \"1.0s\", \"1.5s\", \"2.0s\", \"2.5s\", \"3.0s\"]\n                for key in planning_results_computed.keys():\n                    value = planning_results_computed[key]\n                    row_value = []\n                    row_value.append(key)\n                    for i in range(len(value)):\n                        row_value.append('%.4f' % float(value[i]))\n                    planning_tab.add_row(row_value)\n                print(planning_tab)\n\n\n        return detail\n\n    def load_gt(self):\n        all_annotations = EvalBoxes()\n        for i in range(len(self.data_infos)):\n            sample_boxes = []\n            sample_data = self.data_infos[i]\n\n            gt_boxes = sample_data['gt_boxes']\n            \n            for j in range(gt_boxes.shape[0]):\n                class_name = self.NameMapping[sample_data['gt_names'][j]]\n                if not class_name in self.eval_cfg['class_range'].keys():\n                    continue\n                range_x, range_y = self.eval_cfg['class_range'][class_name]\n                if abs(gt_boxes[j,0]) > range_x or abs(gt_boxes[j,1]) > range_y:\n                    continue\n                sample_boxes.append(DetectionBox(\n                                                sample_token=sample_data['folder']+'_'+str(sample_data['frame_idx']),\n                                                translation=gt_boxes[j,0:3],\n                                                size=gt_boxes[j,3:6],\n                                                rotation=list(Quaternion(axis=[0, 0, 1], radians=-gt_boxes[j,6]-np.pi/2)),\n                                                velocity=gt_boxes[j,7:9],\n                                                num_pts=int(sample_data['num_points'][j]),\n                                                detection_name=self.NameMapping[sample_data['gt_names'][j]],\n                                                detection_score=-1.0,  \n                                                attribute_name=self.NameMapping[sample_data['gt_names'][j]]\n                                                ))\n            all_annotations.add_boxes(sample_data['folder']+'_'+str(sample_data['frame_idx']), sample_boxes)\n        return all_annotations\n    \n    def _format_bbox(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n\n\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            #pdb.set_trace()\n            annos = []\n            box3d = det['boxes_3d']\n            scores = det['scores_3d']\n            labels = det['labels_3d']\n            box_gravity_center = box3d.gravity_center\n            box_dims = box3d.dims\n            box_yaw = box3d.yaw.numpy()\n            box_yaw = -box_yaw - np.pi / 2\n            sample_token = self.data_infos[sample_id]['folder'] + '_' + str(self.data_infos[sample_id]['frame_idx'])\n\n\n\n            for i in range(len(box3d)):\n                #import pdb;pdb.set_trace()\n                quat = list(Quaternion(axis=[0, 0, 1], radians=box_yaw[i]))\n                velocity = [box3d.tensor[i, 7].item(),box3d.tensor[i, 8].item()]\n                name = mapped_class_names[labels[i]]\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box_gravity_center[i].tolist(),\n                    size=box_dims[i].tolist(),\n                    rotation=quat,\n                    velocity=velocity,\n                    detection_name=name,\n                    detection_score=scores[i].item(),\n                    attribute_name=name)\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n        }\n\n        mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path  \n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        return result_files, tmp_dir\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/B2D_sparsedrive_dataset.py",
    "content": "import copy\nimport numpy as np\nimport os\nfrom os import path as osp\nimport torch\nimport random\nimport json, pickle\nimport tempfile\nimport cv2\nimport pyquaternion\nfrom pyquaternion import Quaternion\nimport mmcv\nfrom mmcv.datasets import DATASETS\nfrom mmcv.utils import save_tensor\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import track_iter_progress, mkdir_or_exist\nfrom mmcv.datasets.pipelines import to_tensor\nfrom .custom_3d import Custom3DDataset\nfrom .pipelines import Compose\nfrom mmcv.datasets.map_utils.struct import LiDARInstanceLines\nfrom shapely.geometry import LineString\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom .vad_custom_nuscenes_eval import NuScenesEval_custom\nfrom nuscenes.eval.common.utils import center_distance\nimport random\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom mmcv.core.bbox.structures.nuscenes_box import CustomNuscenesBox\nfrom shapely import affinity, ops\nfrom shapely.geometry import LineString, box, MultiPolygon, MultiLineString\nfrom nuscenes.map_expansion.map_api import NuScenesMap, NuScenesMapExplorer\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES\nfrom mmcv.datasets.map_utils.mean_ap import eval_map\nfrom mmcv.datasets.map_utils.mean_ap import format_res_gt_by_classes\nfrom .nuscenes_styled_eval_utils import DetectionMetrics, EvalBoxes, DetectionBox,center_distance,accumulate,DetectionMetricDataList,calc_ap, calc_tp, quaternion_yaw\n\n@DATASETS.register_module()\nclass B2D_SparseDrive_Dataset(Custom3DDataset):\n\n\n    def __init__(self, queue_length=4, bev_size=(200, 200),overlap_test=False,with_velocity=True,sample_interval=5,name_mapping= None,eval_cfg = None, map_root =None,map_file=None,past_frames=2, future_frames=6,point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0] ,polyline_points_num=20,*args, **kwargs):\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.bev_size = bev_size\n        self.overlap_test = overlap_test\n        self.with_velocity = with_velocity\n        self.NameMapping  = name_mapping\n        self.eval_cfg  = eval_cfg\n        self.sample_interval = sample_interval\n        self.past_frames = past_frames\n        self.future_frames = future_frames\n        self.map_root = map_root\n        self.map_file = map_file\n        self.point_cloud_range = np.array(point_cloud_range)\n        self.polyline_points_num = polyline_points_num\n        self.map_element_class = {'Broken':0, 'Solid':1, 'SolidSolid':2,'Center':3,'TrafficLight':4,'StopSign':5}\n        self.MAPCLASSES = list(self.map_element_class.keys())\n        self.NUM_MAPCLASSES = len(self.MAPCLASSES)\n        self.map_eval_use_same_gt_sample_num_flag = True\n        self.map_ann_file = 'data/infos'\n        self.eval_cfg  = eval_cfg\n        with open(self.map_file,'rb') as f: \n            self.map_infos = pickle.load(f)\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        queue = []\n        index_list = list(range(index-self.queue_length*self.sample_interval, index,self.sample_interval))\n        random.shuffle(index_list)\n        index_list = sorted(index_list[1:])\n        index_list.append(index)\n        for i in index_list:\n            i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            self.pre_pipeline(input_dict)\n            example = self.pipeline(input_dict)\n            gt_labels,gt_bboxes = self.get_map_info(index)\n            example['map_gt_labels_3d'] = DC(gt_labels, cpu_only=False)\n            example['map_gt_bboxes_3d'] = DC(gt_bboxes, cpu_only=True)\n            \n            if self.filter_empty_gt and \\\n                    (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n                return None\n            queue.append(example)\n        return self.union2one(queue)\n\n\n    def union2one(self, queue):\n        imgs_list = [each['img'].data for each in queue]\n        metas_map = {}\n        prev_scene_token = None\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if metas_map[i]['folder'] != prev_scene_token:\n                metas_map[i]['prev_bev_exists'] = False\n                prev_scene_token = metas_map[i]['folder']\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev_exists'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n        queue[-1]['img'] = DC(torch.stack(imgs_list), cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n        return queue\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n\n        input_dict = dict(\n            folder=info['folder'],\n            scene_token=info['folder'],\n            frame_idx=info['frame_idx'],\n            ego_yaw=np.nan_to_num(info['ego_yaw'],nan=np.pi/2),\n            ego_translation=info['ego_translation'],\n            sensors=info['sensors'],\n            world2lidar=info['sensors']['LIDAR_TOP']['world2lidar'],\n            gt_ids=info['gt_ids'],\n            gt_boxes=info['gt_boxes'],\n            gt_names=info['gt_names'],\n            ego_vel = info['ego_vel'],\n            ego_accel = info['ego_accel'],\n            ego_rotation_rate = info['ego_rotation_rate'],\n            npc2world = info['npc2world'],\n            timestamp=info['frame_idx']/10\n        )\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            lidar2ego = info['sensors']['LIDAR_TOP']['lidar2ego']\n            lidar2global =  self.invert_pose(info['sensors']['LIDAR_TOP']['world2lidar'])\n            for sensor_type, cam_info in info['sensors'].items():\n                if not 'CAM' in sensor_type:\n                    continue\n                image_paths.append(osp.join(self.data_root,cam_info['data_path']))\n                # obtain lidar to image transformation matrix\n                cam2ego = cam_info['cam2ego']\n                intrinsic = cam_info['intrinsic']\n                intrinsic_pad = np.eye(4)\n                intrinsic_pad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2cam = self.invert_pose(cam2ego) @ lidar2ego\n                lidar2img = intrinsic_pad @ lidar2cam\n                lidar2img_rts.append(lidar2img)\n                cam_intrinsics.append(intrinsic_pad)\n                lidar2cam_rts.append(lidar2cam)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                    l2g_r_mat=lidar2global[0:3,0:3],\n                    l2g_t=lidar2global[0:3,3]\n\n                ))\n            \n        #if not self.test_mode:\n        annos = self.get_ann_info(index)\n        input_dict['ann_info'] = annos\n        yaw = input_dict['ego_yaw']\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=yaw))\n        \n        if yaw < 0:\n            yaw += 2*np.pi\n        yaw_in_degree = yaw / np.pi * 180 \n        \n        can_bus = np.zeros(18)\n        can_bus[:3] = input_dict['ego_translation']\n        can_bus[3:7] = rotation\n        can_bus[7:10] = input_dict['ego_vel']\n        can_bus[10:13] = input_dict['ego_accel']\n        can_bus[13:16] = input_dict['ego_rotation_rate']\n        can_bus[16] = yaw\n        can_bus[17] = yaw_in_degree\n        input_dict['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = input_dict['ego_translation'][0:2]\n        ego_lcf_feat[2:4] = input_dict['ego_accel'][2:4]\n        ego_lcf_feat[4] = input_dict['ego_rotation_rate'][-1]\n        ego_lcf_feat[5] = info['ego_size'][1]\n        ego_lcf_feat[6] = info['ego_size'][0]\n        ego_lcf_feat[7] = np.sqrt(input_dict['ego_translation'][0]**2+input_dict['ego_translation'][1]**2)\n        ego_lcf_feat[8] = info['steer']\n        ego_his_trajs, ego_fut_trajs, ego_fut_masks, command = self.get_ego_trajs(index,self.sample_interval,self.past_frames,self.future_frames)\n        input_dict['ego_his_trajs'] = ego_his_trajs\n        input_dict['ego_fut_trajs'] = ego_fut_trajs\n        input_dict['ego_fut_masks'] = ego_fut_masks\n        input_dict['ego_fut_cmd'] = command\n        input_dict['ego_lcf_feat'] = ego_lcf_feat\n        input_dict['fut_valid_flag'] = (ego_fut_masks==1).all() \n\n        return input_dict\n\n\n    def get_map_info(self, index):\n\n        gt_masks = []\n        gt_labels = []\n        gt_bboxes = []\n\n        ann_info = self.data_infos[index]\n        town_name = ann_info['town_name']\n        map_info = self.map_infos[town_name]\n        lane_points = map_info['lane_points']\n        lane_sample_points = map_info['lane_sample_points']\n        lane_types = map_info['lane_types']\n        trigger_volumes_points = map_info['trigger_volumes_points']\n        trigger_volumes_sample_points = map_info['trigger_volumes_sample_points']\n        trigger_volumes_types = map_info['trigger_volumes_types']\n        world2lidar = np.array(ann_info['sensors']['LIDAR_TOP']['world2lidar'])\n        ego_xy = np.linalg.inv(world2lidar)[0:2,3]\n        max_distance = 50\n        chosed_idx = []\n\n        for idx in range(len(lane_sample_points)):\n            single_sample_points = lane_sample_points[idx]\n            distance = np.linalg.norm((single_sample_points[:,0:2]-ego_xy),axis=-1)\n            if np.min(distance) < max_distance:\n                chosed_idx.append(idx)\n\n        polylines = []\n        for idx in chosed_idx:\n            if not lane_types[idx] in self.map_element_class.keys():\n                continue\n            points = lane_points[idx]\n            points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n            points_in_lidar = (world2lidar @ points.T).T\n            mask = (points_in_lidar[:,0]>self.point_cloud_range[0]) & (points_in_lidar[:,0]<self.point_cloud_range[3]) & (points_in_lidar[:,1]>self.point_cloud_range[1]) & (points_in_lidar[:,1]<self.point_cloud_range[4])\n            points_in_lidar_range = points_in_lidar[mask,0:2]\n            if len(points_in_lidar_range) > 1:\n                polylines.append(LineString(points_in_lidar_range))\n                gt_label =  self.map_element_class[lane_types[idx]]\n                gt_labels.append(gt_label)\n\n        for idx in range(len(trigger_volumes_points)):\n            if not trigger_volumes_types[idx] in self.map_element_class.keys():\n                continue\n            points = trigger_volumes_points[idx]\n            points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n            points_in_lidar = (world2lidar @ points.T).T\n            mask = (points_in_lidar[:,0]>self.point_cloud_range[0]) & (points_in_lidar[:,0]<self.point_cloud_range[3]) & (points_in_lidar[:,1]>self.point_cloud_range[1]) & (points_in_lidar[:,1]<self.point_cloud_range[4])\n            points_in_lidar_range = points_in_lidar[mask,0:2]\n            if mask.all():\n                polylines.append(LineString(np.concatenate((points_in_lidar_range,points_in_lidar_range[0:1]),axis=0)))\n                gt_label = self.map_element_class[trigger_volumes_types[idx]]\n                gt_labels.append(gt_label)\n\n        gt_labels = torch.tensor(gt_labels)\n        gt_bboxes = LiDARInstanceLines(polylines,fixed_num=self.polyline_points_num,patch_size=(self.point_cloud_range[4]-self.point_cloud_range[1],self.point_cloud_range[3]-self.point_cloud_range[0]))\n        return gt_labels,gt_bboxes\n\n\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n        mask = (info['num_points'] != 0)\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_inds = info['gt_ids']\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if not self.with_velocity:\n            gt_bboxes_3d = gt_bboxes_3d[:,0:7]\n\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        attr_labels = self.get_box_attr_labels(index,self.sample_interval,self.future_frames)\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n            attr_labels=attr_labels[mask],\n            )\n        return anns_results\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def get_ego_trajs(self,idx,sample_rate,past_frames,future_frames):\n\n        adj_idx_list = range(idx-past_frames*sample_rate,idx+(future_frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        full_adj_track = np.zeros((past_frames+future_frames+1,2))\n        full_adj_adj_mask = np.zeros(past_frames+future_frames+1)\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for j in range(len(adj_idx_list)):\n            adj_idx = adj_idx_list[j]\n            if adj_idx <0 or adj_idx>=len(self.data_infos):\n                break\n            adj_frame = self.data_infos[adj_idx]\n            if adj_frame['folder'] != cur_frame ['folder']:\n                break\n            world2lidar_ego_adj = adj_frame['sensors']['LIDAR_TOP']['world2lidar']\n            adj2cur_lidar = world2lidar_lidar_cur @ np.linalg.inv(world2lidar_ego_adj)\n            xy = adj2cur_lidar[0:2,3]\n            full_adj_track[j,0:2] = xy\n            full_adj_adj_mask[j] = 1\n        offset_track = full_adj_track[1:] - full_adj_track[:-1]\n        for j in range(past_frames-1,-1,-1):\n            if full_adj_adj_mask[j] == 0:\n                offset_track[j] = offset_track[j+1]\n        for j in range(past_frames,past_frames+future_frames,1):\n\n            if full_adj_adj_mask[j+1] == 0 :\n                offset_track[j] = 0\n        command = self.command2hot(cur_frame['command_near'])\n        return offset_track[:past_frames].copy(), offset_track[past_frames:].copy(), full_adj_adj_mask[-future_frames:].copy(), command\n    \n    def command2hot(self,command,max_dim=6):\n        if command < 0:\n            command = 4\n        command -= 1\n        cmd_one_hot = np.zeros(max_dim)\n        cmd_one_hot[command] = 1\n        return cmd_one_hot\n\n    def get_box_attr_labels(self,idx,sample_rate,frames):\n\n\n        adj_idx_list = range(idx,idx+(frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        cur_box_names = cur_frame['gt_names']\n        for i in range(len(cur_box_names)):\n            if cur_box_names[i] in self.NameMapping.keys():\n                cur_box_names[i] = self.NameMapping[cur_box_names[i]]\n        cur_boxes = cur_frame['gt_boxes'].copy()\n        box_ids = cur_frame['gt_ids']\n        future_track = np.zeros((len(box_ids),frames+1,2))\n        future_mask = np.zeros((len(box_ids),frames+1))\n        future_yaw = np.zeros((len(box_ids),frames+1))\n        gt_fut_goal = np.zeros((len(box_ids),1))\n        agent_lcf_feat = np.zeros((len(box_ids),9))\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for i in range(len(box_ids)):\n            agent_lcf_feat[i,0:2] = cur_boxes[i,0:2]\n            agent_lcf_feat[i,2] = cur_boxes[i,6]\n            agent_lcf_feat[i,3:5] = cur_boxes[i,7:]\n            agent_lcf_feat[i,5:8] = cur_boxes[i,3:6]\n            cur_box_name = cur_box_names[i]\n            if cur_box_name in self.CLASSES:\n                agent_lcf_feat[i, 8] = self.CLASSES.index(cur_box_name)\n            else:\n                agent_lcf_feat[i, 8] = -1\n\n            box_id = box_ids[i]\n            cur_box2lidar = world2lidar_lidar_cur @ cur_frame['npc2world'][i]\n            cur_xy = cur_box2lidar[0:2,3]      \n            for j in range(len(adj_idx_list)):\n                adj_idx = adj_idx_list[j]\n                if adj_idx <0 or adj_idx>=len(self.data_infos):\n                    break\n                adj_frame = self.data_infos[adj_idx]\n                if adj_frame['folder'] != cur_frame ['folder']:\n                    break\n                if len(np.where(adj_frame['gt_ids']==box_id)[0])==0:\n                    continue\n                assert len(np.where(adj_frame['gt_ids']==box_id)[0]) == 1 , np.where(adj_frame['gt_ids']==box_id)[0]\n                adj_idx = np.where(adj_frame['gt_ids']==box_id)[0][0]\n                adj_box2lidar = world2lidar_lidar_cur @ adj_frame['npc2world'][adj_idx]\n                adj_xy = adj_box2lidar[0:2,3]    \n                future_track[i,j,:] = adj_xy\n                future_mask[i,j] = 1\n                future_yaw[i,j] = np.arctan2(adj_box2lidar[1,0],adj_box2lidar[0,0])\n\n            coord_diff = future_track[i,-1] - future_track[i,0]\n            if coord_diff.max() < 1.0: # static\n                gt_fut_goal[i] = 9\n            else:\n                box_mot_yaw = np.arctan2(coord_diff[1], coord_diff[0]) + np.pi\n                gt_fut_goal[i] = box_mot_yaw // (np.pi / 4)  # 0-8: goal direction class\n\n        future_track_offset = future_track[:,1:,:] - future_track[:,:-1,:]\n        future_mask_offset = future_mask[:,1:]\n        future_track_offset[future_mask_offset==0] = 0\n        future_yaw_offset = future_yaw[:,1:] - future_yaw[:,:-1]\n        mask1 = np.where(future_yaw_offset>np.pi)\n        mask2 = np.where(future_yaw_offset<-np.pi)\n        future_yaw_offset[mask1] -=np.pi*2 \n        future_yaw_offset[mask2] +=np.pi*2\n        attr_labels = np.concatenate([future_track_offset.reshape(-1,frames*2), future_mask_offset, gt_fut_goal, agent_lcf_feat, future_yaw_offset],axis=-1).astype(np.float32)\n        return attr_labels.copy()\n\n\n\n    def load_gt(self):\n        all_annotations = EvalBoxes()\n        for i in range(len(self.data_infos)):\n            sample_boxes = []\n            sample_data = self.data_infos[i]\n            gt_boxes = sample_data['gt_boxes']\n            for j in range(gt_boxes.shape[0]):\n                class_name = self.NameMapping[sample_data['gt_names'][j]]\n                if not class_name in self.eval_cfg['class_range'].keys():\n                    continue\n                range_x, range_y = self.eval_cfg['class_range'][class_name]\n                if abs(gt_boxes[j,0]) > range_x or abs(gt_boxes[j,1]) > range_y:\n                    continue\n                sample_boxes.append(DetectionBox(\n                                                sample_token=sample_data['folder']+'_'+str(sample_data['frame_idx']),\n                                                translation=gt_boxes[j,0:3],\n                                                size=gt_boxes[j,3:6],\n                                                rotation=list(Quaternion(axis=[0, 0, 1], radians=-gt_boxes[j,6]-np.pi/2)),\n                                                velocity=gt_boxes[j,7:9],\n                                                num_pts=int(sample_data['num_points'][j]),\n                                                detection_name=class_name,\n                                                detection_score=-1.0,  \n                                                attribute_name=class_name\n                                                ))\n            all_annotations.add_boxes(sample_data['folder']+'_'+str(sample_data['frame_idx']), sample_boxes)\n        return all_annotations\n\n\n\n    def _format_gt(self):\n        gt_annos = []\n        print('Start to convert gt map format...')\n        # assert self.map_ann_file is not None\n        if (not os.path.exists(self.map_ann_file)) :\n            dataset_length = len(self)\n            prog_bar = mmcv.ProgressBar(dataset_length)\n            mapped_class_names = self.MAPCLASSES\n            for sample_id in range(dataset_length):\n                sample_token = self.data_infos[sample_id]['folder'] +  '_' + str(self.data_infos[sample_id]['frame_idx'])\n                gt_anno = {}\n                gt_anno['sample_token'] = sample_token\n                # gt_sample_annos = []\n                gt_sample_dict = {}\n                gt_labels , gt_bboxes = self.get_map_info(sample_id)\n                gt_vecs = gt_bboxes.instance_list\n                gt_vec_list = []\n                for i, (gt_label, gt_vec) in enumerate(zip(gt_labels, gt_vecs)):\n                    name = mapped_class_names[gt_label]\n                    anno = dict(\n                        pts=np.array(list(gt_vec.coords)),\n                        pts_num=len(list(gt_vec.coords)),\n                        cls_name=name,\n                        type=gt_label,\n                    )\n                    gt_vec_list.append(anno)\n                gt_anno['vectors']=gt_vec_list\n                gt_annos.append(gt_anno)\n\n                prog_bar.update()\n            nusc_submissions = {\n                'GTs': gt_annos\n            }\n            print('\\n GT anns writes to', self.map_ann_file)\n            dump(nusc_submissions, self.map_ann_file)\n        else:\n            print(f'{self.map_ann_file} exist, not update')\n\n\n    def _format_bbox(self, results, jsonfile_prefix=None, score_thresh=0.2):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n\n        nusc_annos = {}\n        det_mapped_class_names = self.CLASSES\n        # assert self.map_ann_file is not None\n        map_pred_annos = {}\n        map_mapped_class_names = self.MAPCLASSES\n        plan_annos = {}\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            #pdb.set_trace()\n            annos = []\n            box3d = det['boxes_3d']\n            scores = det['scores_3d']\n            labels = det['labels_3d']\n            box_gravity_center = box3d.gravity_center\n            box_dims = box3d.dims\n            box_yaw = box3d.yaw.numpy()\n            box_yaw = -box_yaw - np.pi / 2\n            sample_token = self.data_infos[sample_id]['folder'] + '_' + str(self.data_infos[sample_id]['frame_idx'])\n            for i in range(len(box3d)):\n                #import pdb;pdb.set_trace()\n                if scores[i] < score_thresh:\n                    continue\n                quat = list(Quaternion(axis=[0, 0, 1], radians=box_yaw[i]))\n                velocity = [box3d.tensor[i, 7].item(),box3d.tensor[i, 8].item()]\n                name = det_mapped_class_names[labels[i]]\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box_gravity_center[i].tolist(),\n                    size=box_dims[i].tolist(),\n                    rotation=quat,\n                    velocity=velocity,\n                    detection_name=name,\n                    detection_score=scores[i].item(),\n                    attribute_name=name)\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n            map_pred_anno = {}\n            vecs = output_to_vecs(det)\n            sample_token = self.data_infos[sample_id]['folder'] +  '_' + str(self.data_infos[sample_id]['frame_idx'])\n            map_pred_anno['sample_token'] = sample_token\n            pred_vec_list=[]\n            for i, vec in enumerate(vecs):\n                name = map_mapped_class_names[vec['label']]\n                anno = dict(\n                    # sample_token=sample_token,\n                    pts=vec['pts'],\n                    pts_num=len(vec['pts']),\n                    cls_name=name,\n                    type=vec['label'],\n                    confidence_level=vec['score'])\n                pred_vec_list.append(anno)\n                # annos.append(nusc_anno)\n            # nusc_annos[sample_token] = annos\n            map_pred_anno['vectors'] = pred_vec_list\n            map_pred_annos[sample_token] = map_pred_anno\n\n        # NOTE: Eval on map is VERY SLOW for the first time(about 3 hours) because load map ground trurh is slow. \n        #       So we do not eval map by default.\n        # if not os.path.exists(self.map_ann_file):\n        #     self._format_gt()\n        # else:\n        #     print(f'{self.map_ann_file} exist, not update')\n        # with open(self.map_ann_file,'r') as f:\n        #     GT_anns = json.load(f)\n        # gt_annos = GT_anns['GTs']\n\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n            'map_results': map_pred_annos,\n            'plan_results': plan_annos\n            # 'GTs': gt_annos\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path\n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        if isinstance(results, dict):\n            # print(f'results must be a list, but get dict, keys={results.keys()}')\n            # assert isinstance(results, list)\n            results = results['bbox_results']\n        assert isinstance(results, list)\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        # currently the output prediction results could be in two formats\n        # 1. list of dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...)\n        # 2. list of dict('pts_bbox' or 'img_bbox':\n        #     dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...))\n        # this is a workaround to enable evaluation of both formats on nuScenes\n        # refer to https://github.com/open-mmlab/mmdetection3d/issues/449\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                if name == 'metric_results':\n                    continue\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        return result_files, tmp_dir\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         map_metric='chamfer',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        detail = dict()\n        with open(result_path,'r') as f:\n            result_data = json.load(f)\n        pred_boxes = EvalBoxes.deserialize(result_data['results'], DetectionBox)\n        meta = result_data['meta']\n\n\n\n        gt_boxes = self.load_gt()\n\n        metric_data_list = DetectionMetricDataList()\n        for class_name in self.eval_cfg['class_names']:\n            for dist_th in self.eval_cfg['dist_ths']:\n                md = accumulate(gt_boxes, pred_boxes, class_name, center_distance, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics = DetectionMetrics(self.eval_cfg)\n\n        for class_name in self.eval_cfg['class_names']:\n            # Compute APs.\n            for dist_th in self.eval_cfg['dist_ths']:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.eval_cfg['min_recall'], self.eval_cfg['min_precision'])\n                metrics.add_label_ap(class_name, dist_th, ap)\n\n            # Compute TP metrics.\n            for metric_name in self.eval_cfg['tp_metrics']:\n                metric_data = metric_data_list[(class_name, self.eval_cfg['dist_th_tp'])]\n                tp = calc_tp(metric_data, self.eval_cfg['min_recall'], metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        metrics_summary = metrics.serialize()\n        metrics_summary['meta'] = meta.copy()\n        print('mAP: %.4f' % (metrics_summary['mean_ap']))\n        err_name_mapping = {\n            'trans_err': 'mATE',\n            'scale_err': 'mASE',\n            'orient_err': 'mAOE',\n            'vel_err': 'mAVE',\n        }\n        for tp_name, tp_val in metrics_summary['tp_errors'].items():\n            print('%s: %.4f' % (err_name_mapping[tp_name], tp_val))\n        print('NDS: %.4f' % (metrics_summary['nd_score']))\n        #print('Eval time: %.1fs' % metrics_summary['eval_time'])\n\n        # Print per-class metrics.\n        print()\n        print('Per-class results:')\n        print('Object Class\\tAP\\tATE\\tASE\\tAOE\\tAVE')\n        class_aps = metrics_summary['mean_dist_aps']\n        class_tps = metrics_summary['label_tp_errors']\n        for class_name in class_aps.keys():\n            print('%s\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f'\n                  % (class_name, class_aps[class_name],\n                     class_tps[class_name]['trans_err'],\n                     class_tps[class_name]['scale_err'],\n                     class_tps[class_name]['orient_err'],\n                     class_tps[class_name]['vel_err']))        \n\n        detail = dict()\n        metric_prefix = 'bbox_NuScenes'\n        for name in self.eval_cfg['class_names']:\n            for k, v in metrics_summary['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,self.eval_cfg['err_name_maping'][k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics_summary['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics_summary['mean_ap']\n\n\n        # from mmcv.datasets.map_utils.mean_ap import eval_map\n        # from mmcv.datasets.map_utils.mean_ap import format_res_gt_by_classes\n        # result_path = osp.abspath(result_path)\n        \n        # print('Formating results & gts by classes')\n        # pred_results = load(result_path)\n        # map_results = pred_results['map_results']\n        # gt_anns = load(self.map_ann_file)\n        # map_annotations = gt_anns['GTs']\n        # cls_gens, cls_gts = format_res_gt_by_classes(result_path,\n        #                                              map_results,\n        #                                              map_annotations,\n        #                                              cls_names=self.MAPCLASSES,\n        #                                              num_pred_pts_per_instance=self.polyline_points_num,\n        #                                              eval_use_same_gt_sample_num_flag=self.map_eval_use_same_gt_sample_num_flag,\n        #                                              pc_range=self.point_cloud_range)\n        # map_metrics = map_metric if isinstance(map_metric, list) else [map_metric]\n        # allowed_metrics = ['chamfer', 'iou']\n        # for metric in map_metrics:\n        #     if metric not in allowed_metrics:\n        #         raise KeyError(f'metric {metric} is not supported')\n        # for metric in map_metrics:\n        #     print('-*'*10+f'use metric:{metric}'+'-*'*10)\n        #     if metric == 'chamfer':\n        #         thresholds = [0.5,1.0,1.5]\n        #     elif metric == 'iou':\n        #         thresholds= np.linspace(.5, 0.95, int(np.round((0.95 - .5) / .05)) + 1, endpoint=True)\n        #     cls_aps = np.zeros((len(thresholds),self.NUM_MAPCLASSES))\n        #     for i, thr in enumerate(thresholds):\n        #         print('-*'*10+f'threshhold:{thr}'+'-*'*10)\n        #         mAP, cls_ap = eval_map(\n        #                         map_results,\n        #                         map_annotations,\n        #                         cls_gens,\n        #                         cls_gts,\n        #                         threshold=thr,\n        #                         cls_names=self.MAPCLASSES,\n        #                         logger=logger,\n        #                         num_pred_pts_per_instance=self.polyline_points_num,\n        #                         pc_range=self.point_cloud_range,\n        #                         metric=metric)\n        #         for j in range(self.NUM_MAPCLASSES):\n        #             cls_aps[i, j] = cls_ap[j]['ap']\n        #     for i, name in enumerate(self.MAPCLASSES):\n        #         print('{}: {}'.format(name, cls_aps.mean(0)[i]))\n        #         detail['NuscMap_{}/{}_AP'.format(metric,name)] =  cls_aps.mean(0)[i]\n        #     print('map: {}'.format(cls_aps.mean(0).mean()))\n        #     detail['NuscMap_{}/mAP'.format(metric)] = cls_aps.mean(0).mean()\n        #     for i, name in enumerate(self.MAPCLASSES):\n        #         for j, thr in enumerate(thresholds):\n        #             if metric == 'chamfer':\n        #                 detail['NuscMap_{}/{}_AP_thr_{}'.format(metric,name,thr)]=cls_aps[j][i]\n        #             elif metric == 'iou':\n        #                 if thr == 0.5 or thr == 0.75:\n        #                     detail['NuscMap_{}/{}_AP_thr_{}'.format(metric,name,thr)]=cls_aps[j][i]\n\n        return detail\n    \n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 map_metric='chamfer',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n        result_metric_names = ['EPA', 'ADE', 'FDE', 'MR']\n        motion_cls_names = ['car', 'pedestrian']\n        motion_metric_names = ['gt', 'cnt_ade', 'cnt_fde', 'hit',\n                               'fp', 'ADE', 'FDE', 'MR']\n        all_metric_dict = {}\n        for met in motion_metric_names:\n            for cls in motion_cls_names:\n                all_metric_dict[met+'_'+cls] = 0.0\n        result_dict = {}\n        for met in result_metric_names:\n            for cls in motion_cls_names:\n                result_dict[met+'_'+cls] = 0.0\n        \n        alpha = 0.5\n\n        for i in range(len(results)):\n            for key in all_metric_dict.keys():\n                all_metric_dict[key] += results[i]['metric_results'][key]\n        \n        for cls in motion_cls_names:\n            result_dict['EPA_'+cls] = (all_metric_dict['hit_'+cls] - \\\n                 alpha * all_metric_dict['fp_'+cls]) / all_metric_dict['gt_'+cls]\n            result_dict['ADE_'+cls] = all_metric_dict['ADE_'+cls] / all_metric_dict['cnt_ade_'+cls]\n            result_dict['FDE_'+cls] = all_metric_dict['FDE_'+cls] / all_metric_dict['cnt_fde_'+cls]\n            result_dict['MR_'+cls] = all_metric_dict['MR_'+cls] / all_metric_dict['cnt_fde_'+cls]\n        \n        print('\\n')\n        print('-------------- Motion Prediction --------------')\n        for k, v in result_dict.items():\n            print(f'{k}: {v}')\n\n        # NOTE: print planning metric\n        print('\\n')\n        print('-------------- Planning --------------')\n        metric_dict = None\n        num_valid = 0\n        for res in results:\n            if res['metric_results']['fut_valid_flag']:\n                num_valid += 1\n            else:\n                continue\n            if metric_dict is None:\n                metric_dict = copy.deepcopy(res['metric_results'])\n            else:\n                for k in res['metric_results'].keys():\n                    metric_dict[k] += res['metric_results'][k]\n        \n        for k in metric_dict:\n            metric_dict[k] = metric_dict[k] / num_valid\n            print(\"{}:{}\".format(k, metric_dict[k]))\n\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print('Evaluating bboxes of {}'.format(name))\n                ret_dict = self._evaluate_single(result_files[name], metric=metric, map_metric=map_metric)\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(result_files, metric=metric, map_metric=map_metric)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\ndef output_to_nusc_box(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n\n    Args:\n        detection (dict): Detection results.\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n    trajs = detection['trajs_3d'].numpy()\n\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        velocity = (*box3d.tensor[i, 7:9], 0.0)\n        # velo_val = np.linalg.norm(box3d[i, 7:9])\n        # velo_ori = box3d[i, 6]\n        # velocity = (\n        # velo_val * np.cos(velo_ori), velo_val * np.sin(velo_ori), 0.0)\n        box = CustomNuscenesBox(\n            center=box_gravity_center[i],\n            size=box_dims[i],\n            orientation=quat,\n            fut_trajs=trajs[i],\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(info,\n                             boxes,\n                             classes,\n                             eval_configs,\n                             eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from ego to global coordinate.\n\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str): Evaluation version.\n            Default: 'detection_cvpr_2019'\n\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    for box in boxes:\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info['lidar2ego_rotation']))\n        box.translate(np.array(info['lidar2ego_translation']))\n        # filter det in ego.\n        cls_range_x_map = eval_configs.class_range_x\n        cls_range_y_map = eval_configs.class_range_y\n        x_distance, y_distance = box.center[0], box.center[1]\n        det_range_x = cls_range_x_map[classes[box.label]]\n        det_range_y = cls_range_y_map[classes[box.label]]\n        if abs(x_distance) > det_range_x or abs(y_distance) > det_range_y:\n            continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n    return box_list\n\ndef output_to_vecs(detection):\n    box3d = detection['map_boxes_3d'].numpy()\n    scores = detection['map_scores_3d'].numpy()\n    labels = detection['map_labels_3d'].numpy()\n    pts = detection['map_pts_3d'].numpy()\n\n    vec_list = []\n    # import pdb;pdb.set_trace()\n    for i in range(box3d.shape[0]):\n        vec = dict(\n            bbox = box3d[i], # xyxy\n            label=labels[i],\n            score=scores[i],\n            pts=pts[i],\n        )\n        vec_list.append(vec)\n    return vec_list"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/B2D_vad_dataset.py",
    "content": "import copy\nimport numpy as np\nimport os\nfrom os import path as osp\nimport torch\nimport random\nimport json, pickle\nimport tempfile\nimport cv2\nimport pyquaternion\nfrom pyquaternion import Quaternion\nimport mmcv\nfrom mmcv.datasets import DATASETS\nfrom mmcv.utils import save_tensor\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import track_iter_progress, mkdir_or_exist\nfrom mmcv.datasets.pipelines import to_tensor\nfrom .custom_3d import Custom3DDataset\nfrom .pipelines import Compose\nfrom mmcv.datasets.map_utils.struct import LiDARInstanceLines\nfrom shapely.geometry import LineString\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom .vad_custom_nuscenes_eval import NuScenesEval_custom\nfrom nuscenes.eval.common.utils import center_distance\nimport random\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom mmcv.core.bbox.structures.nuscenes_box import CustomNuscenesBox\nfrom shapely import affinity, ops\nfrom shapely.geometry import LineString, box, MultiPolygon, MultiLineString\nfrom nuscenes.map_expansion.map_api import NuScenesMap, NuScenesMapExplorer\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES\nfrom mmcv.datasets.map_utils.mean_ap import eval_map\nfrom mmcv.datasets.map_utils.mean_ap import format_res_gt_by_classes\nfrom .nuscenes_styled_eval_utils import DetectionMetrics, EvalBoxes, DetectionBox,center_distance,accumulate,DetectionMetricDataList,calc_ap, calc_tp, quaternion_yaw\n\n@DATASETS.register_module()\nclass B2D_VAD_Dataset(Custom3DDataset):\n\n\n    def __init__(self, queue_length=4, bev_size=(200, 200),overlap_test=False,with_velocity=True,sample_interval=5,name_mapping= None,eval_cfg = None, map_root =None,map_file=None,past_frames=6, future_frames=6,point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0] ,polyline_points_num=20,*args, **kwargs):\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.bev_size = bev_size\n        self.overlap_test = overlap_test\n        self.with_velocity = with_velocity\n        self.NameMapping  = name_mapping\n        self.eval_cfg  = eval_cfg\n        self.sample_interval = sample_interval\n        self.past_frames = past_frames\n        self.future_frames = future_frames\n        self.map_root = map_root\n        self.map_file = map_file\n        self.point_cloud_range = np.array(point_cloud_range)\n        self.polyline_points_num = polyline_points_num\n        self.map_element_class = {'Broken':0, 'Solid':1, 'SolidSolid':2,'Center':3,'TrafficLight':4,'StopSign':5}\n        self.MAPCLASSES = list(self.map_element_class.keys())\n        self.NUM_MAPCLASSES = len(self.MAPCLASSES)\n        self.map_eval_use_same_gt_sample_num_flag = True\n        self.map_ann_file = 'data/infos'\n        self.eval_cfg  = eval_cfg\n        with open(self.map_file,'rb') as f: \n            self.map_infos = pickle.load(f)\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        queue = []\n        index_list = list(range(index-self.queue_length*self.sample_interval, index,self.sample_interval))\n        random.shuffle(index_list)\n        index_list = sorted(index_list[1:])\n        index_list.append(index)\n        for i in index_list:\n            i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            self.pre_pipeline(input_dict)\n            example = self.pipeline(input_dict)\n            gt_labels,gt_bboxes = self.get_map_info(index)\n            example['map_gt_labels_3d'] = DC(gt_labels, cpu_only=False)\n            example['map_gt_bboxes_3d'] = DC(gt_bboxes, cpu_only=True)\n            \n            if self.filter_empty_gt and \\\n                    (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n                return None\n            queue.append(example)\n        return self.union2one(queue)\n\n\n    def union2one(self, queue):\n        imgs_list = [each['img'].data for each in queue]\n        metas_map = {}\n        prev_scene_token = None\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if metas_map[i]['folder'] != prev_scene_token:\n                metas_map[i]['prev_bev_exists'] = False\n                prev_scene_token = metas_map[i]['folder']\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev_exists'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n        queue[-1]['img'] = DC(torch.stack(imgs_list), cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n        #import pdb;pdb.set_trace()\n        return queue\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        info = self.data_infos[index]\n\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n\n        input_dict = dict(\n            folder=info['folder'],\n            scene_token=info['folder'],\n            frame_idx=info['frame_idx'],\n            ego_yaw=np.nan_to_num(info['ego_yaw'],nan=np.pi/2),\n            ego_translation=info['ego_translation'],\n            sensors=info['sensors'],\n            world2lidar=info['sensors']['LIDAR_TOP']['world2lidar'],\n            gt_ids=info['gt_ids'],\n            gt_boxes=info['gt_boxes'],\n            gt_names=info['gt_names'],\n            ego_vel = info['ego_vel'],\n            ego_accel = info['ego_accel'],\n            ego_rotation_rate = info['ego_rotation_rate'],\n            npc2world = info['npc2world'],\n            timestamp=info['frame_idx']/10\n        )\n        \n        #import pdb;pdb.set_trace()\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            lidar2ego = info['sensors']['LIDAR_TOP']['lidar2ego']\n            lidar2global =  self.invert_pose(info['sensors']['LIDAR_TOP']['world2lidar'])\n            for sensor_type, cam_info in info['sensors'].items():\n                if not 'CAM' in sensor_type:\n                    continue\n                image_paths.append(osp.join(self.data_root,cam_info['data_path']))\n                # obtain lidar to image transformation matrix\n                cam2ego = cam_info['cam2ego']\n                intrinsic = cam_info['intrinsic']\n                intrinsic_pad = np.eye(4)\n                intrinsic_pad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2cam = self.invert_pose(cam2ego) @ lidar2ego\n                lidar2img = intrinsic_pad @ lidar2cam\n                lidar2img_rts.append(lidar2img)\n                cam_intrinsics.append(intrinsic_pad)\n                lidar2cam_rts.append(lidar2cam)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                    l2g_r_mat=lidar2global[0:3,0:3],\n                    l2g_t=lidar2global[0:3,3]\n\n                ))\n            \n        #if not self.test_mode:\n        annos = self.get_ann_info(index)\n        input_dict['ann_info'] = annos\n        yaw = input_dict['ego_yaw']\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=yaw))\n        \n        if yaw < 0:\n            yaw += 2*np.pi\n        yaw_in_degree = yaw / np.pi * 180 \n        \n        can_bus = np.zeros(18)\n        can_bus[:3] = input_dict['ego_translation']\n        can_bus[3:7] = rotation\n        can_bus[7:10] = input_dict['ego_vel']\n        can_bus[10:13] = input_dict['ego_accel']\n        can_bus[13:16] = input_dict['ego_rotation_rate']\n        can_bus[16] = yaw\n        can_bus[17] = yaw_in_degree\n        input_dict['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = input_dict['ego_translation'][0:2]\n        ego_lcf_feat[2:4] = input_dict['ego_accel'][2:4]\n        ego_lcf_feat[4] = input_dict['ego_rotation_rate'][-1]\n        ego_lcf_feat[5] = info['ego_size'][1]\n        ego_lcf_feat[6] = info['ego_size'][0]\n        ego_lcf_feat[7] = np.sqrt(input_dict['ego_translation'][0]**2+input_dict['ego_translation'][1]**2)\n        ego_lcf_feat[8] = info['steer']\n        ego_his_trajs, ego_fut_trajs, ego_fut_masks, command = self.get_ego_trajs(index,self.sample_interval,self.past_frames,self.future_frames)\n        #import pdb;pdb.set_trace()\n        input_dict['ego_his_trajs'] = ego_his_trajs\n        input_dict['ego_fut_trajs'] = ego_fut_trajs\n        input_dict['ego_fut_masks'] = ego_fut_masks\n        input_dict['ego_fut_cmd'] = command\n        #import pdb;pdb.set_trace()\n        input_dict['ego_lcf_feat'] = ego_lcf_feat\n        input_dict['fut_valid_flag'] = (ego_fut_masks==1).all() \n\n        return input_dict\n\n\n    def get_map_info(self, index):\n\n        gt_masks = []\n        gt_labels = []\n        gt_bboxes = []\n\n        ann_info = self.data_infos[index]\n        town_name = ann_info['town_name']\n        map_info = self.map_infos[town_name]\n        lane_points = map_info['lane_points']\n        lane_sample_points = map_info['lane_sample_points']\n        lane_types = map_info['lane_types']\n        trigger_volumes_points = map_info['trigger_volumes_points']\n        trigger_volumes_sample_points = map_info['trigger_volumes_sample_points']\n        trigger_volumes_types = map_info['trigger_volumes_types']\n        world2lidar = np.array(ann_info['sensors']['LIDAR_TOP']['world2lidar'])\n        ego_xy = np.linalg.inv(world2lidar)[0:2,3]\n        max_distance = 50\n        chosed_idx = []\n\n        for idx in range(len(lane_sample_points)):\n            single_sample_points = lane_sample_points[idx]\n            distance = np.linalg.norm((single_sample_points[:,0:2]-ego_xy),axis=-1)\n            if np.min(distance) < max_distance:\n                chosed_idx.append(idx)\n\n        polylines = []\n        for idx in chosed_idx:\n            if not lane_types[idx] in self.map_element_class.keys():\n                continue\n            points = lane_points[idx]\n            points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n            points_in_lidar = (world2lidar @ points.T).T\n            mask = (points_in_lidar[:,0]>self.point_cloud_range[0]) & (points_in_lidar[:,0]<self.point_cloud_range[3]) & (points_in_lidar[:,1]>self.point_cloud_range[1]) & (points_in_lidar[:,1]<self.point_cloud_range[4])\n            points_in_lidar_range = points_in_lidar[mask,0:2]\n            if len(points_in_lidar_range) > 1:\n                polylines.append(LineString(points_in_lidar_range))\n                gt_label =  self.map_element_class[lane_types[idx]]\n                gt_labels.append(gt_label)\n\n        for idx in range(len(trigger_volumes_points)):\n            if not trigger_volumes_types[idx] in self.map_element_class.keys():\n                continue\n            points = trigger_volumes_points[idx]\n            points = np.concatenate([points,np.ones((points.shape[0],1))],axis=-1)\n            points_in_lidar = (world2lidar @ points.T).T\n            mask = (points_in_lidar[:,0]>self.point_cloud_range[0]) & (points_in_lidar[:,0]<self.point_cloud_range[3]) & (points_in_lidar[:,1]>self.point_cloud_range[1]) & (points_in_lidar[:,1]<self.point_cloud_range[4])\n            points_in_lidar_range = points_in_lidar[mask,0:2]\n            if mask.all():\n                polylines.append(LineString(np.concatenate((points_in_lidar_range,points_in_lidar_range[0:1]),axis=0)))\n                gt_label = self.map_element_class[trigger_volumes_types[idx]]\n                gt_labels.append(gt_label)\n\n        gt_labels = torch.tensor(gt_labels)\n        gt_bboxes = LiDARInstanceLines(polylines,fixed_num=self.polyline_points_num,patch_size=(self.point_cloud_range[4]-self.point_cloud_range[1],self.point_cloud_range[3]-self.point_cloud_range[0]))\n        return gt_labels,gt_bboxes\n\n\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n\n        for i in range(len(info['gt_names'])):\n            if info['gt_names'][i] in self.NameMapping.keys():\n                info['gt_names'][i] = self.NameMapping[info['gt_names'][i]]\n        mask = (info['num_points'] != 0)\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_inds = info['gt_ids']\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if not self.with_velocity:\n            gt_bboxes_3d = gt_bboxes_3d[:,0:7]\n\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        attr_labels = self.get_box_attr_labels(index,self.sample_interval,self.future_frames)\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n            attr_labels=attr_labels[mask],\n            )\n        return anns_results\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def get_ego_trajs(self,idx,sample_rate,past_frames,future_frames):\n        #import pdb;pdb.set_trace()\n        # idx = 128386\n        adj_idx_list = range(idx-past_frames*sample_rate,idx+(future_frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        full_adj_track = np.zeros((past_frames+future_frames+1,2))\n        full_adj_adj_mask = np.zeros(past_frames+future_frames+1)\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for j in range(len(adj_idx_list)):\n            adj_idx = adj_idx_list[j]\n            if adj_idx <0 or adj_idx>=len(self.data_infos):\n                break\n            adj_frame = self.data_infos[adj_idx]\n            if adj_frame['folder'] != cur_frame ['folder']:\n                break\n            world2lidar_ego_adj = adj_frame['sensors']['LIDAR_TOP']['world2lidar']\n            adj2cur_lidar = world2lidar_lidar_cur @ np.linalg.inv(world2lidar_ego_adj)\n            xy = adj2cur_lidar[0:2,3]\n            full_adj_track[j,0:2] = xy\n            full_adj_adj_mask[j] = 1\n        offset_track = full_adj_track[1:] - full_adj_track[:-1]\n        for j in range(past_frames-1,-1,-1):\n            if full_adj_adj_mask[j] == 0:\n                offset_track[j] = offset_track[j+1]\n        for j in range(past_frames,past_frames+future_frames,1):\n\n            if full_adj_adj_mask[j+1] == 0 :\n                offset_track[j] = 0\n        command = self.command2hot(cur_frame['command_near'])\n        return offset_track[:past_frames].copy(), offset_track[past_frames:].copy(), full_adj_adj_mask[-future_frames:].copy(), command\n    \n    def command2hot(self,command,max_dim=6):\n        if command < 0:\n            command = 4\n        command -= 1\n        cmd_one_hot = np.zeros(max_dim)\n        cmd_one_hot[command] = 1\n        return cmd_one_hot\n\n    def get_box_attr_labels(self,idx,sample_rate,frames):\n\n\n        adj_idx_list = range(idx,idx+(frames+1)*sample_rate,sample_rate)\n        cur_frame = self.data_infos[idx]\n        cur_box_names = cur_frame['gt_names']\n        for i in range(len(cur_box_names)):\n            if cur_box_names[i] in self.NameMapping.keys():\n                cur_box_names[i] = self.NameMapping[cur_box_names[i]]\n        cur_boxes = cur_frame['gt_boxes'].copy()\n        box_ids = cur_frame['gt_ids']\n        future_track = np.zeros((len(box_ids),frames+1,2))\n        future_mask = np.zeros((len(box_ids),frames+1))\n        future_yaw = np.zeros((len(box_ids),frames+1))\n        gt_fut_goal = np.zeros((len(box_ids),1))\n        agent_lcf_feat = np.zeros((len(box_ids),9))\n        world2lidar_lidar_cur = cur_frame['sensors']['LIDAR_TOP']['world2lidar']\n        for i in range(len(box_ids)):\n            agent_lcf_feat[i,0:2] = cur_boxes[i,0:2]\n            agent_lcf_feat[i,2] = cur_boxes[i,6]\n            agent_lcf_feat[i,3:5] = cur_boxes[i,7:]\n            agent_lcf_feat[i,5:8] = cur_boxes[i,3:6]\n            cur_box_name = cur_box_names[i]\n            if cur_box_name in self.CLASSES:\n                agent_lcf_feat[i, 8] = self.CLASSES.index(cur_box_name)\n            else:\n                agent_lcf_feat[i, 8] = -1\n\n            box_id = box_ids[i]\n            cur_box2lidar = world2lidar_lidar_cur @ cur_frame['npc2world'][i]\n            cur_xy = cur_box2lidar[0:2,3]      \n            for j in range(len(adj_idx_list)):\n                adj_idx = adj_idx_list[j]\n                if adj_idx <0 or adj_idx>=len(self.data_infos):\n                    break\n                adj_frame = self.data_infos[adj_idx]\n                if adj_frame['folder'] != cur_frame ['folder']:\n                    break\n                if len(np.where(adj_frame['gt_ids']==box_id)[0])==0:\n                    continue\n                assert len(np.where(adj_frame['gt_ids']==box_id)[0]) == 1 , np.where(adj_frame['gt_ids']==box_id)[0]\n                adj_idx = np.where(adj_frame['gt_ids']==box_id)[0][0]\n                adj_box2lidar = world2lidar_lidar_cur @ adj_frame['npc2world'][adj_idx]\n                adj_xy = adj_box2lidar[0:2,3]    \n                future_track[i,j,:] = adj_xy\n                future_mask[i,j] = 1\n                future_yaw[i,j] = np.arctan2(adj_box2lidar[1,0],adj_box2lidar[0,0])\n\n            coord_diff = future_track[i,-1] - future_track[i,0]\n            if coord_diff.max() < 1.0: # static\n                gt_fut_goal[i] = 9\n            else:\n                box_mot_yaw = np.arctan2(coord_diff[1], coord_diff[0]) + np.pi\n                gt_fut_goal[i] = box_mot_yaw // (np.pi / 4)  # 0-8: goal direction class\n\n        future_track_offset = future_track[:,1:,:] - future_track[:,:-1,:]\n        future_mask_offset = future_mask[:,1:]\n        future_track_offset[future_mask_offset==0] = 0\n        future_yaw_offset = future_yaw[:,1:] - future_yaw[:,:-1]\n        mask1 = np.where(future_yaw_offset>np.pi)\n        mask2 = np.where(future_yaw_offset<-np.pi)\n        future_yaw_offset[mask1] -=np.pi*2 \n        future_yaw_offset[mask2] +=np.pi*2\n        attr_labels = np.concatenate([future_track_offset.reshape(-1,frames*2), future_mask_offset, gt_fut_goal, agent_lcf_feat, future_yaw_offset],axis=-1).astype(np.float32)\n        return attr_labels.copy()\n\n\n\n    def load_gt(self):\n        all_annotations = EvalBoxes()\n        for i in range(len(self.data_infos)):\n            sample_boxes = []\n            sample_data = self.data_infos[i]\n            gt_boxes = sample_data['gt_boxes']\n            for j in range(gt_boxes.shape[0]):\n                class_name = self.NameMapping[sample_data['gt_names'][j]]\n                if not class_name in self.eval_cfg['class_range'].keys():\n                    continue\n                range_x, range_y = self.eval_cfg['class_range'][class_name]\n                if abs(gt_boxes[j,0]) > range_x or abs(gt_boxes[j,1]) > range_y:\n                    continue\n                sample_boxes.append(DetectionBox(\n                                                sample_token=sample_data['folder']+'_'+str(sample_data['frame_idx']),\n                                                translation=gt_boxes[j,0:3],\n                                                size=gt_boxes[j,3:6],\n                                                rotation=list(Quaternion(axis=[0, 0, 1], radians=-gt_boxes[j,6]-np.pi/2)),\n                                                velocity=gt_boxes[j,7:9],\n                                                num_pts=int(sample_data['num_points'][j]),\n                                                detection_name=class_name,\n                                                detection_score=-1.0,  \n                                                attribute_name=class_name\n                                                ))\n            all_annotations.add_boxes(sample_data['folder']+'_'+str(sample_data['frame_idx']), sample_boxes)\n        return all_annotations\n\n\n\n    def _format_gt(self):\n        gt_annos = []\n        print('Start to convert gt map format...')\n        # assert self.map_ann_file is not None\n        if (not os.path.exists(self.map_ann_file)) :\n            dataset_length = len(self)\n            prog_bar = mmcv.ProgressBar(dataset_length)\n            mapped_class_names = self.MAPCLASSES\n            for sample_id in range(dataset_length):\n                sample_token = self.data_infos[sample_id]['folder'] +  '_' + str(self.data_infos[sample_id]['frame_idx'])\n                gt_anno = {}\n                gt_anno['sample_token'] = sample_token\n                # gt_sample_annos = []\n                gt_sample_dict = {}\n                gt_labels , gt_bboxes = self.get_map_info(sample_id)\n                gt_vecs = gt_bboxes.instance_list\n                gt_vec_list = []\n                for i, (gt_label, gt_vec) in enumerate(zip(gt_labels, gt_vecs)):\n                    name = mapped_class_names[gt_label]\n                    anno = dict(\n                        pts=np.array(list(gt_vec.coords)),\n                        pts_num=len(list(gt_vec.coords)),\n                        cls_name=name,\n                        type=gt_label,\n                    )\n                    gt_vec_list.append(anno)\n                gt_anno['vectors']=gt_vec_list\n                gt_annos.append(gt_anno)\n\n                prog_bar.update()\n            nusc_submissions = {\n                'GTs': gt_annos\n            }\n            print('\\n GT anns writes to', self.map_ann_file)\n            dump(nusc_submissions, self.map_ann_file)\n        else:\n            print(f'{self.map_ann_file} exist, not update')\n\n\n    def _format_bbox(self, results, jsonfile_prefix=None, score_thresh=0.2):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n\n        nusc_annos = {}\n        det_mapped_class_names = self.CLASSES\n        # assert self.map_ann_file is not None\n        map_pred_annos = {}\n        map_mapped_class_names = self.MAPCLASSES\n        plan_annos = {}\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            #pdb.set_trace()\n            annos = []\n            box3d = det['boxes_3d']\n            scores = det['scores_3d']\n            labels = det['labels_3d']\n            box_gravity_center = box3d.gravity_center\n            box_dims = box3d.dims\n            box_yaw = box3d.yaw.numpy()\n            box_yaw = -box_yaw - np.pi / 2\n            sample_token = self.data_infos[sample_id]['folder'] + '_' + str(self.data_infos[sample_id]['frame_idx'])\n            for i in range(len(box3d)):\n                #import pdb;pdb.set_trace()\n                if scores[i] < score_thresh:\n                    continue\n                quat = list(Quaternion(axis=[0, 0, 1], radians=box_yaw[i]))\n                velocity = [box3d.tensor[i, 7].item(),box3d.tensor[i, 8].item()]\n                name = det_mapped_class_names[labels[i]]\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box_gravity_center[i].tolist(),\n                    size=box_dims[i].tolist(),\n                    rotation=quat,\n                    velocity=velocity,\n                    detection_name=name,\n                    detection_score=scores[i].item(),\n                    attribute_name=name)\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n            map_pred_anno = {}\n            vecs = output_to_vecs(det)\n            sample_token = self.data_infos[sample_id]['folder'] +  '_' + str(self.data_infos[sample_id]['frame_idx'])\n            map_pred_anno['sample_token'] = sample_token\n            pred_vec_list=[]\n            for i, vec in enumerate(vecs):\n                name = map_mapped_class_names[vec['label']]\n                anno = dict(\n                    # sample_token=sample_token,\n                    pts=vec['pts'],\n                    pts_num=len(vec['pts']),\n                    cls_name=name,\n                    type=vec['label'],\n                    confidence_level=vec['score'])\n                pred_vec_list.append(anno)\n                # annos.append(nusc_anno)\n            # nusc_annos[sample_token] = annos\n            map_pred_anno['vectors'] = pred_vec_list\n            map_pred_annos[sample_token] = map_pred_anno\n\n        # NOTE: Eval on map is VERY SLOW for the first time(about 3 hours) because load map ground trurh is slow. \n        #       So we do not eval map by default.\n        # if not os.path.exists(self.map_ann_file):\n        #     self._format_gt()\n        # else:\n        #     print(f'{self.map_ann_file} exist, not update')\n        # with open(self.map_ann_file,'r') as f:\n        #     GT_anns = json.load(f)\n        # gt_annos = GT_anns['GTs']\n\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n            'map_results': map_pred_annos,\n            'plan_results': plan_annos\n            # 'GTs': gt_annos\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path\n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        if isinstance(results, dict):\n            # print(f'results must be a list, but get dict, keys={results.keys()}')\n            # assert isinstance(results, list)\n            results = results['bbox_results']\n        assert isinstance(results, list)\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        # currently the output prediction results could be in two formats\n        # 1. list of dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...)\n        # 2. list of dict('pts_bbox' or 'img_bbox':\n        #     dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...))\n        # this is a workaround to enable evaluation of both formats on nuScenes\n        # refer to https://github.com/open-mmlab/mmdetection3d/issues/449\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                if name == 'metric_results':\n                    continue\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        return result_files, tmp_dir\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         map_metric='chamfer',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        detail = dict()\n        with open(result_path,'r') as f:\n            result_data = json.load(f)\n        pred_boxes = EvalBoxes.deserialize(result_data['results'], DetectionBox)\n        meta = result_data['meta']\n\n\n\n        gt_boxes = self.load_gt()\n\n        metric_data_list = DetectionMetricDataList()\n        for class_name in self.eval_cfg['class_names']:\n            for dist_th in self.eval_cfg['dist_ths']:\n                md = accumulate(gt_boxes, pred_boxes, class_name, center_distance, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics = DetectionMetrics(self.eval_cfg)\n\n        for class_name in self.eval_cfg['class_names']:\n            # Compute APs.\n            for dist_th in self.eval_cfg['dist_ths']:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.eval_cfg['min_recall'], self.eval_cfg['min_precision'])\n                metrics.add_label_ap(class_name, dist_th, ap)\n\n            # Compute TP metrics.\n            for metric_name in self.eval_cfg['tp_metrics']:\n                metric_data = metric_data_list[(class_name, self.eval_cfg['dist_th_tp'])]\n                tp = calc_tp(metric_data, self.eval_cfg['min_recall'], metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        metrics_summary = metrics.serialize()\n        metrics_summary['meta'] = meta.copy()\n        print('mAP: %.4f' % (metrics_summary['mean_ap']))\n        err_name_mapping = {\n            'trans_err': 'mATE',\n            'scale_err': 'mASE',\n            'orient_err': 'mAOE',\n            'vel_err': 'mAVE',\n        }\n        for tp_name, tp_val in metrics_summary['tp_errors'].items():\n            print('%s: %.4f' % (err_name_mapping[tp_name], tp_val))\n        print('NDS: %.4f' % (metrics_summary['nd_score']))\n        #print('Eval time: %.1fs' % metrics_summary['eval_time'])\n\n        # Print per-class metrics.\n        print()\n        print('Per-class results:')\n        print('Object Class\\tAP\\tATE\\tASE\\tAOE\\tAVE')\n        class_aps = metrics_summary['mean_dist_aps']\n        class_tps = metrics_summary['label_tp_errors']\n        for class_name in class_aps.keys():\n            print('%s\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f'\n                  % (class_name, class_aps[class_name],\n                     class_tps[class_name]['trans_err'],\n                     class_tps[class_name]['scale_err'],\n                     class_tps[class_name]['orient_err'],\n                     class_tps[class_name]['vel_err']))        \n\n        detail = dict()\n        metric_prefix = 'bbox_NuScenes'\n        for name in self.eval_cfg['class_names']:\n            for k, v in metrics_summary['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics_summary['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,self.eval_cfg['err_name_maping'][k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics_summary['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics_summary['mean_ap']\n\n\n        # from mmcv.datasets.map_utils.mean_ap import eval_map\n        # from mmcv.datasets.map_utils.mean_ap import format_res_gt_by_classes\n        # result_path = osp.abspath(result_path)\n        \n        # print('Formating results & gts by classes')\n        # pred_results = load(result_path)\n        # map_results = pred_results['map_results']\n        # gt_anns = load(self.map_ann_file)\n        # map_annotations = gt_anns['GTs']\n        # cls_gens, cls_gts = format_res_gt_by_classes(result_path,\n        #                                              map_results,\n        #                                              map_annotations,\n        #                                              cls_names=self.MAPCLASSES,\n        #                                              num_pred_pts_per_instance=self.polyline_points_num,\n        #                                              eval_use_same_gt_sample_num_flag=self.map_eval_use_same_gt_sample_num_flag,\n        #                                              pc_range=self.point_cloud_range)\n        # map_metrics = map_metric if isinstance(map_metric, list) else [map_metric]\n        # allowed_metrics = ['chamfer', 'iou']\n        # for metric in map_metrics:\n        #     if metric not in allowed_metrics:\n        #         raise KeyError(f'metric {metric} is not supported')\n        # for metric in map_metrics:\n        #     print('-*'*10+f'use metric:{metric}'+'-*'*10)\n        #     if metric == 'chamfer':\n        #         thresholds = [0.5,1.0,1.5]\n        #     elif metric == 'iou':\n        #         thresholds= np.linspace(.5, 0.95, int(np.round((0.95 - .5) / .05)) + 1, endpoint=True)\n        #     cls_aps = np.zeros((len(thresholds),self.NUM_MAPCLASSES))\n        #     for i, thr in enumerate(thresholds):\n        #         print('-*'*10+f'threshhold:{thr}'+'-*'*10)\n        #         mAP, cls_ap = eval_map(\n        #                         map_results,\n        #                         map_annotations,\n        #                         cls_gens,\n        #                         cls_gts,\n        #                         threshold=thr,\n        #                         cls_names=self.MAPCLASSES,\n        #                         logger=logger,\n        #                         num_pred_pts_per_instance=self.polyline_points_num,\n        #                         pc_range=self.point_cloud_range,\n        #                         metric=metric)\n        #         for j in range(self.NUM_MAPCLASSES):\n        #             cls_aps[i, j] = cls_ap[j]['ap']\n        #     for i, name in enumerate(self.MAPCLASSES):\n        #         print('{}: {}'.format(name, cls_aps.mean(0)[i]))\n        #         detail['NuscMap_{}/{}_AP'.format(metric,name)] =  cls_aps.mean(0)[i]\n        #     print('map: {}'.format(cls_aps.mean(0).mean()))\n        #     detail['NuscMap_{}/mAP'.format(metric)] = cls_aps.mean(0).mean()\n        #     for i, name in enumerate(self.MAPCLASSES):\n        #         for j, thr in enumerate(thresholds):\n        #             if metric == 'chamfer':\n        #                 detail['NuscMap_{}/{}_AP_thr_{}'.format(metric,name,thr)]=cls_aps[j][i]\n        #             elif metric == 'iou':\n        #                 if thr == 0.5 or thr == 0.75:\n        #                     detail['NuscMap_{}/{}_AP_thr_{}'.format(metric,name,thr)]=cls_aps[j][i]\n\n        return detail\n    \n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 map_metric='chamfer',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n        result_metric_names = ['EPA', 'ADE', 'FDE', 'MR']\n        motion_cls_names = ['car', 'pedestrian']\n        motion_metric_names = ['gt', 'cnt_ade', 'cnt_fde', 'hit',\n                               'fp', 'ADE', 'FDE', 'MR']\n        all_metric_dict = {}\n        for met in motion_metric_names:\n            for cls in motion_cls_names:\n                all_metric_dict[met+'_'+cls] = 0.0\n        result_dict = {}\n        for met in result_metric_names:\n            for cls in motion_cls_names:\n                result_dict[met+'_'+cls] = 0.0\n        \n        alpha = 0.5\n\n        for i in range(len(results)):\n            for key in all_metric_dict.keys():\n                all_metric_dict[key] += results[i]['metric_results'][key]\n        \n        for cls in motion_cls_names:\n            result_dict['EPA_'+cls] = (all_metric_dict['hit_'+cls] - \\\n                 alpha * all_metric_dict['fp_'+cls]) / all_metric_dict['gt_'+cls]\n            result_dict['ADE_'+cls] = all_metric_dict['ADE_'+cls] / all_metric_dict['cnt_ade_'+cls]\n            result_dict['FDE_'+cls] = all_metric_dict['FDE_'+cls] / all_metric_dict['cnt_fde_'+cls]\n            result_dict['MR_'+cls] = all_metric_dict['MR_'+cls] / all_metric_dict['cnt_fde_'+cls]\n        \n        print('\\n')\n        print('-------------- Motion Prediction --------------')\n        for k, v in result_dict.items():\n            print(f'{k}: {v}')\n\n        # NOTE: print planning metric\n        print('\\n')\n        print('-------------- Planning --------------')\n        metric_dict = None\n        num_valid = 0\n        for res in results:\n            if res['metric_results']['fut_valid_flag']:\n                num_valid += 1\n            else:\n                continue\n            if metric_dict is None:\n                metric_dict = copy.deepcopy(res['metric_results'])\n            else:\n                for k in res['metric_results'].keys():\n                    metric_dict[k] += res['metric_results'][k]\n        \n        for k in metric_dict:\n            metric_dict[k] = metric_dict[k] / num_valid\n            print(\"{}:{}\".format(k, metric_dict[k]))\n\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print('Evaluating bboxes of {}'.format(name))\n                ret_dict = self._evaluate_single(result_files[name], metric=metric, map_metric=map_metric)\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(result_files, metric=metric, map_metric=map_metric)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\ndef output_to_nusc_box(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n\n    Args:\n        detection (dict): Detection results.\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n    trajs = detection['trajs_3d'].numpy()\n\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        velocity = (*box3d.tensor[i, 7:9], 0.0)\n        # velo_val = np.linalg.norm(box3d[i, 7:9])\n        # velo_ori = box3d[i, 6]\n        # velocity = (\n        # velo_val * np.cos(velo_ori), velo_val * np.sin(velo_ori), 0.0)\n        box = CustomNuscenesBox(\n            center=box_gravity_center[i],\n            size=box_dims[i],\n            orientation=quat,\n            fut_trajs=trajs[i],\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(info,\n                             boxes,\n                             classes,\n                             eval_configs,\n                             eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from ego to global coordinate.\n\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str): Evaluation version.\n            Default: 'detection_cvpr_2019'\n\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    for box in boxes:\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info['lidar2ego_rotation']))\n        box.translate(np.array(info['lidar2ego_translation']))\n        # filter det in ego.\n        cls_range_x_map = eval_configs.class_range_x\n        cls_range_y_map = eval_configs.class_range_y\n        x_distance, y_distance = box.center[0], box.center[1]\n        det_range_x = cls_range_x_map[classes[box.label]]\n        det_range_y = cls_range_y_map[classes[box.label]]\n        if abs(x_distance) > det_range_x or abs(y_distance) > det_range_y:\n            continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n    return box_list\n\ndef output_to_vecs(detection):\n    box3d = detection['map_boxes_3d'].numpy()\n    scores = detection['map_scores_3d'].numpy()\n    labels = detection['map_labels_3d'].numpy()\n    pts = detection['map_pts_3d'].numpy()\n\n    vec_list = []\n    # import pdb;pdb.set_trace()\n    for i in range(box3d.shape[0]):\n        vec = dict(\n            bbox = box3d[i], # xyxy\n            label=labels[i],\n            score=scores[i],\n            pts=pts[i],\n        )\n        vec_list.append(vec)\n    return vec_list"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/__init__.py",
    "content": "from .builder import DATASETS, PIPELINES, build_dataloader, build_dataset\nfrom .custom_3d import Custom3DDataset\nfrom .custom import CustomDataset\nfrom .nuscenes_dataset import NuScenesDataset\nfrom .nuscenes_e2e_dataset import NuScenesE2EDataset\nfrom .samplers import DistributedGroupSampler, DistributedSampler, GroupSampler\nfrom .utils import replace_ImageToTensor\nfrom .custom_nuscenes_dataset_v2 import CustomNuScenesDatasetV2\nfrom .custom_nuscenes_dataset import CustomNuScenesDataset\nfrom .dd3d_nuscenes_dataset import DD3DNuscenesDataset\nfrom .lyft_dataset import LyftDataset\nfrom .B2D_dataset import B2D_Dataset\nfrom .B2D_e2e_dataset import B2D_E2E_Dataset\nfrom .nuscenes_vad_dataset import VADCustomNuScenesDataset\nfrom .B2D_vad_dataset import B2D_VAD_Dataset\nfrom .B2D_sparsedrive_dataset import B2D_SparseDrive_Dataset"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/api_wrappers/__init__.py",
    "content": "from .coco_api import COCO, COCOeval\n\n__all__ = ['COCO', 'COCOeval']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/api_wrappers/coco_api.py",
    "content": "# This file add snake case alias for coco api\n\nimport warnings\n\nimport pycocotools\nfrom pycocotools.coco import COCO as _COCO\nfrom pycocotools.cocoeval import COCOeval as _COCOeval\n\n\nclass COCO(_COCO):\n    \"\"\"This class is almost the same as official pycocotools package.\n\n    It implements some snake case function aliases. So that the COCO class has\n    the same interface as LVIS class.\n    \"\"\"\n\n    def __init__(self, annotation_file=None):\n        if getattr(pycocotools, '__version__', '0') >= '12.0.2':\n            warnings.warn(\n                'mmpycocotools is deprecated. Please install official pycocotools by \"pip install pycocotools\"',  # noqa: E501\n                UserWarning)\n        super().__init__(annotation_file=annotation_file)\n        self.img_ann_map = self.imgToAnns\n        self.cat_img_map = self.catToImgs\n\n    def get_ann_ids(self, img_ids=[], cat_ids=[], area_rng=[], iscrowd=None):\n        return self.getAnnIds(img_ids, cat_ids, area_rng, iscrowd)\n\n    def get_cat_ids(self, cat_names=[], sup_names=[], cat_ids=[]):\n        return self.getCatIds(cat_names, sup_names, cat_ids)\n\n    def get_img_ids(self, img_ids=[], cat_ids=[]):\n        return self.getImgIds(img_ids, cat_ids)\n\n    def load_anns(self, ids):\n        return self.loadAnns(ids)\n\n    def load_cats(self, ids):\n        return self.loadCats(ids)\n\n    def load_imgs(self, ids):\n        return self.loadImgs(ids)\n\n\n# just for the ease of import\nCOCOeval = _COCOeval\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/builder.py",
    "content": "import copy\nimport platform\nimport random\nfrom functools import partial\n\nimport numpy as np\nfrom mmcv.parallel import collate\nfrom mmcv.utils import Registry, build_from_cfg, get_dist_info\nfrom torch.utils.data import DataLoader\n\n# DATASETS = Registry('dataset')\n# PIPELINES = Registry('pipeline')\n# OBJECTSAMPLERS = Registry('Object sampler')\n\nfrom .samplers import DistributedGroupSampler, DistributedSampler, GroupSampler\n# from .dataset_wrappers import CBGSDataset, ClassBalancedDataset, ConcatDataset, RepeatDataset\nfrom .samplers.sampler import build_sampler\n\nif platform.system() != 'Windows':\n    # https://github.com/pytorch/pytorch/issues/973\n    import resource\n    rlimit = resource.getrlimit(resource.RLIMIT_NOFILE)\n    hard_limit = rlimit[1]\n    soft_limit = min(4096, hard_limit)\n    resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit))\n\nDATASETS = Registry('dataset')\nPIPELINES = Registry('pipeline')\nOBJECTSAMPLERS = Registry('Object sampler')\n\n\n\ndef _concat_dataset(cfg, default_args=None):\n    from .dataset_wrappers import ConcatDataset\n    ann_files = cfg['ann_file']\n    img_prefixes = cfg.get('img_prefix', None)\n    seg_prefixes = cfg.get('seg_prefix', None)\n    proposal_files = cfg.get('proposal_file', None)\n    separate_eval = cfg.get('separate_eval', True)\n\n    datasets = []\n    num_dset = len(ann_files)\n    for i in range(num_dset):\n        data_cfg = copy.deepcopy(cfg)\n        # pop 'separate_eval' since it is not a valid key for common datasets.\n        if 'separate_eval' in data_cfg:\n            data_cfg.pop('separate_eval')\n        data_cfg['ann_file'] = ann_files[i]\n        if isinstance(img_prefixes, (list, tuple)):\n            data_cfg['img_prefix'] = img_prefixes[i]\n        if isinstance(seg_prefixes, (list, tuple)):\n            data_cfg['seg_prefix'] = seg_prefixes[i]\n        if isinstance(proposal_files, (list, tuple)):\n            data_cfg['proposal_file'] = proposal_files[i]\n        datasets.append(build_dataset(data_cfg, default_args))\n\n    return ConcatDataset(datasets, separate_eval)\n\n\n\n\ndef build_dataset(cfg, default_args=None):\n    from mmcv.datasets.dataset_wrappers import CBGSDataset\n    from mmcv.datasets.dataset_wrappers import (ClassBalancedDataset,\n                                                 ConcatDataset, RepeatDataset)\n    if isinstance(cfg, (list, tuple)):\n        dataset = ConcatDataset([build_dataset(c, default_args) for c in cfg])\n    elif cfg['type'] == 'ConcatDataset':\n        dataset = ConcatDataset(\n            [build_dataset(c, default_args) for c in cfg['datasets']],\n            cfg.get('separate_eval', True))\n    elif cfg['type'] == 'RepeatDataset':\n        dataset = RepeatDataset(\n            build_dataset(cfg['dataset'], default_args), cfg['times'])\n    elif cfg['type'] == 'ClassBalancedDataset':\n        dataset = ClassBalancedDataset(\n            build_dataset(cfg['dataset'], default_args), cfg['oversample_thr'])\n    elif cfg['type'] == 'CBGSDataset':\n        dataset = CBGSDataset(build_dataset(cfg['dataset'], default_args))\n    elif isinstance(cfg.get('ann_file'), (list, tuple)):\n        dataset = _concat_dataset(cfg, default_args)\n    else:\n        dataset = build_from_cfg(cfg, DATASETS, default_args)\n\n    return dataset\n\n\ndef build_dataloader(dataset,\n                     samples_per_gpu,\n                     workers_per_gpu,\n                     num_gpus=1,\n                     dist=True,\n                     shuffle=True,\n                     seed=None,\n                     shuffler_sampler=None,\n                     nonshuffler_sampler=None,\n                     **kwargs):\n    \"\"\"Build PyTorch DataLoader.\n    In distributed training, each GPU/process has a dataloader.\n    In non-distributed training, there is only one dataloader for all GPUs.\n    Args:\n        dataset (Dataset): A PyTorch dataset.\n        samples_per_gpu (int): Number of training samples on each GPU, i.e.,\n            batch size of each GPU.\n        workers_per_gpu (int): How many subprocesses to use for data loading\n            for each GPU.\n        num_gpus (int): Number of GPUs. Only used in non-distributed training.\n        dist (bool): Distributed training/test or not. Default: True.\n        shuffle (bool): Whether to shuffle the data at every epoch.\n            Default: True.\n        kwargs: any keyword argument to be used to initialize DataLoader\n    Returns:\n        DataLoader: A PyTorch dataloader.\n    \"\"\"\n    rank, world_size = get_dist_info()\n    if dist:\n        # DistributedGroupSampler will definitely shuffle the data to satisfy\n        # that images on each GPU are in the same group\n        if shuffle:\n            sampler = build_sampler(shuffler_sampler if shuffler_sampler is not None else dict(type='DistributedGroupSampler'),\n                                     dict(\n                                         dataset=dataset,\n                                         samples_per_gpu=samples_per_gpu,\n                                         num_replicas=world_size,\n                                         rank=rank,\n                                         seed=seed)\n                                     )\n\n        else:\n            sampler = build_sampler(nonshuffler_sampler if nonshuffler_sampler is not None else dict(type='DistributedSampler'),\n                                     dict(\n                                         dataset=dataset,\n                                         num_replicas=world_size,\n                                         rank=rank,\n                                         shuffle=shuffle,\n                                         seed=seed)\n                                     )\n\n        batch_size = samples_per_gpu\n        num_workers = workers_per_gpu\n    else:\n        # assert False, 'not support in bevformer'\n        print('WARNING!!!!, Only can be used for obtain inference speed!!!!')\n        sampler = GroupSampler(dataset, samples_per_gpu) if shuffle else None\n        batch_size = num_gpus * samples_per_gpu\n        num_workers = num_gpus * workers_per_gpu\n\n    init_fn = partial(\n        worker_init_fn, num_workers=num_workers, rank=rank,\n        seed=seed) if seed is not None else None\n    data_loader = DataLoader(\n        dataset,\n        batch_size=batch_size,\n        sampler=sampler,\n        num_workers=num_workers,\n        collate_fn=partial(collate, samples_per_gpu=samples_per_gpu),\n        pin_memory=False,\n        worker_init_fn=init_fn,\n        **kwargs)\n\n    return data_loader\n\n\ndef worker_init_fn(worker_id, num_workers, rank, seed):\n    # The seed of each worker equals to\n    # num_worker * rank + worker_id + user_seed\n    worker_seed = num_workers * rank + worker_id + seed\n    np.random.seed(worker_seed)\n    random.seed(worker_seed)\n\n\nif platform.system() != 'Windows':\n    # https://github.com/pytorch/pytorch/issues/973\n    import resource\n    rlimit = resource.getrlimit(resource.RLIMIT_NOFILE)\n    base_soft_limit = rlimit[0]\n    hard_limit = rlimit[1]\n    soft_limit = min(max(4096, base_soft_limit), hard_limit)\n    resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit))\n\ndef custom_build_dataset(cfg, default_args=None):\n    from mmdet3d.datasets.dataset_wrappers import CBGSDataset\n    from mmdet.datasets.dataset_wrappers import (ClassBalancedDataset,\n                                                 ConcatDataset, RepeatDataset)\n    if isinstance(cfg, (list, tuple)):\n        dataset = ConcatDataset([custom_build_dataset(c, default_args) for c in cfg])\n    elif cfg['type'] == 'ConcatDataset':\n        dataset = ConcatDataset(\n            [custom_build_dataset(c, default_args) for c in cfg['datasets']],\n            cfg.get('separate_eval', True))\n    elif cfg['type'] == 'RepeatDataset':\n        dataset = RepeatDataset(\n            custom_build_dataset(cfg['dataset'], default_args), cfg['times'])\n    elif cfg['type'] == 'ClassBalancedDataset':\n        dataset = ClassBalancedDataset(\n            custom_build_dataset(cfg['dataset'], default_args), cfg['oversample_thr'])\n    elif cfg['type'] == 'CBGSDataset':\n        dataset = CBGSDataset(custom_build_dataset(cfg['dataset'], default_args))\n    elif isinstance(cfg.get('ann_file'), (list, tuple)):\n        dataset = _concat_dataset(cfg, default_args)\n    else:\n        dataset = build_from_cfg(cfg, DATASETS, default_args)\n\n    return dataset"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/coco.py",
    "content": "import itertools\nimport logging\nimport os.path as osp\nimport tempfile\nimport warnings\nfrom collections import OrderedDict\n\nfrom mmcv.fileio.io import load, dump\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\n\nfrom mmcv.core import eval_recalls\nfrom .api_wrappers import COCO, COCOeval\nfrom .builder import DATASETS\nfrom .custom import CustomDataset\n\n\n@DATASETS.register_module()\nclass CocoDataset(CustomDataset):\n\n    CLASSES = ('person', 'bicycle', 'car', 'motorcycle', 'airplane', 'bus',\n               'train', 'truck', 'boat', 'traffic light', 'fire hydrant',\n               'stop sign', 'parking meter', 'bench', 'bird', 'cat', 'dog',\n               'horse', 'sheep', 'cow', 'elephant', 'bear', 'zebra', 'giraffe',\n               'backpack', 'umbrella', 'handbag', 'tie', 'suitcase', 'frisbee',\n               'skis', 'snowboard', 'sports ball', 'kite', 'baseball bat',\n               'baseball glove', 'skateboard', 'surfboard', 'tennis racket',\n               'bottle', 'wine glass', 'cup', 'fork', 'knife', 'spoon', 'bowl',\n               'banana', 'apple', 'sandwich', 'orange', 'broccoli', 'carrot',\n               'hot dog', 'pizza', 'donut', 'cake', 'chair', 'couch',\n               'potted plant', 'bed', 'dining table', 'toilet', 'tv', 'laptop',\n               'mouse', 'remote', 'keyboard', 'cell phone', 'microwave',\n               'oven', 'toaster', 'sink', 'refrigerator', 'book', 'clock',\n               'vase', 'scissors', 'teddy bear', 'hair drier', 'toothbrush')\n\n    def load_annotations(self, ann_file):\n        \"\"\"Load annotation from COCO style annotation file.\n\n        Args:\n            ann_file (str): Path of annotation file.\n\n        Returns:\n            list[dict]: Annotation info from COCO api.\n        \"\"\"\n\n        self.coco = COCO(ann_file)\n        # The order of returned `cat_ids` will not\n        # change with the order of the CLASSES\n        self.cat_ids = self.coco.get_cat_ids(cat_names=self.CLASSES)\n\n        self.cat2label = {cat_id: i for i, cat_id in enumerate(self.cat_ids)}\n        self.img_ids = self.coco.get_img_ids()\n        data_infos = []\n        total_ann_ids = []\n        for i in self.img_ids:\n            info = self.coco.load_imgs([i])[0]\n            info['filename'] = info['file_name']\n            data_infos.append(info)\n            ann_ids = self.coco.get_ann_ids(img_ids=[i])\n            total_ann_ids.extend(ann_ids)\n        assert len(set(total_ann_ids)) == len(\n            total_ann_ids), f\"Annotation ids in '{ann_file}' are not unique!\"\n        return data_infos\n\n    def get_ann_info(self, idx):\n        \"\"\"Get COCO annotation by index.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            dict: Annotation info of specified index.\n        \"\"\"\n\n        img_id = self.data_infos[idx]['id']\n        ann_ids = self.coco.get_ann_ids(img_ids=[img_id])\n        ann_info = self.coco.load_anns(ann_ids)\n        return self._parse_ann_info(self.data_infos[idx], ann_info)\n\n    def get_cat_ids(self, idx):\n        \"\"\"Get COCO category ids by index.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            list[int]: All categories in the image of specified index.\n        \"\"\"\n\n        img_id = self.data_infos[idx]['id']\n        ann_ids = self.coco.get_ann_ids(img_ids=[img_id])\n        ann_info = self.coco.load_anns(ann_ids)\n        return [ann['category_id'] for ann in ann_info]\n\n    def _filter_imgs(self, min_size=32):\n        \"\"\"Filter images too small or without ground truths.\"\"\"\n        valid_inds = []\n        # obtain images that contain annotation\n        ids_with_ann = set(_['image_id'] for _ in self.coco.anns.values())\n        # obtain images that contain annotations of the required categories\n        ids_in_cat = set()\n        for i, class_id in enumerate(self.cat_ids):\n            ids_in_cat |= set(self.coco.cat_img_map[class_id])\n        # merge the image id sets of the two conditions and use the merged set\n        # to filter out images if self.filter_empty_gt=True\n        ids_in_cat &= ids_with_ann\n\n        valid_img_ids = []\n        for i, img_info in enumerate(self.data_infos):\n            img_id = self.img_ids[i]\n            if self.filter_empty_gt and img_id not in ids_in_cat:\n                continue\n            if min(img_info['width'], img_info['height']) >= min_size:\n                valid_inds.append(i)\n                valid_img_ids.append(img_id)\n        self.img_ids = valid_img_ids\n        return valid_inds\n\n    def _parse_ann_info(self, img_info, ann_info):\n        \"\"\"Parse bbox and mask annotation.\n\n        Args:\n            ann_info (list[dict]): Annotation info of an image.\n            with_mask (bool): Whether to parse mask annotations.\n\n        Returns:\n            dict: A dict containing the following keys: bboxes, bboxes_ignore,\\\n                labels, masks, seg_map. \"masks\" are raw annotations and not \\\n                decoded into binary masks.\n        \"\"\"\n        gt_bboxes = []\n        gt_labels = []\n        gt_bboxes_ignore = []\n        gt_masks_ann = []\n        for i, ann in enumerate(ann_info):\n            if ann.get('ignore', False):\n                continue\n            x1, y1, w, h = ann['bbox']\n            inter_w = max(0, min(x1 + w, img_info['width']) - max(x1, 0))\n            inter_h = max(0, min(y1 + h, img_info['height']) - max(y1, 0))\n            if inter_w * inter_h == 0:\n                continue\n            if ann['area'] <= 0 or w < 1 or h < 1:\n                continue\n            if ann['category_id'] not in self.cat_ids:\n                continue\n            bbox = [x1, y1, x1 + w, y1 + h]\n            if ann.get('iscrowd', False):\n                gt_bboxes_ignore.append(bbox)\n            else:\n                gt_bboxes.append(bbox)\n                gt_labels.append(self.cat2label[ann['category_id']])\n                gt_masks_ann.append(ann.get('segmentation', None))\n\n        if gt_bboxes:\n            gt_bboxes = np.array(gt_bboxes, dtype=np.float32)\n            gt_labels = np.array(gt_labels, dtype=np.int64)\n        else:\n            gt_bboxes = np.zeros((0, 4), dtype=np.float32)\n            gt_labels = np.array([], dtype=np.int64)\n\n        if gt_bboxes_ignore:\n            gt_bboxes_ignore = np.array(gt_bboxes_ignore, dtype=np.float32)\n        else:\n            gt_bboxes_ignore = np.zeros((0, 4), dtype=np.float32)\n\n        seg_map = img_info['filename'].replace('jpg', 'png')\n\n        ann = dict(\n            bboxes=gt_bboxes,\n            labels=gt_labels,\n            bboxes_ignore=gt_bboxes_ignore,\n            masks=gt_masks_ann,\n            seg_map=seg_map)\n\n        return ann\n\n    def xyxy2xywh(self, bbox):\n        \"\"\"Convert ``xyxy`` style bounding boxes to ``xywh`` style for COCO\n        evaluation.\n\n        Args:\n            bbox (numpy.ndarray): The bounding boxes, shape (4, ), in\n                ``xyxy`` order.\n\n        Returns:\n            list[float]: The converted bounding boxes, in ``xywh`` order.\n        \"\"\"\n\n        _bbox = bbox.tolist()\n        return [\n            _bbox[0],\n            _bbox[1],\n            _bbox[2] - _bbox[0],\n            _bbox[3] - _bbox[1],\n        ]\n\n    def _proposal2json(self, results):\n        \"\"\"Convert proposal results to COCO json style.\"\"\"\n        json_results = []\n        for idx in range(len(self)):\n            img_id = self.img_ids[idx]\n            bboxes = results[idx]\n            for i in range(bboxes.shape[0]):\n                data = dict()\n                data['image_id'] = img_id\n                data['bbox'] = self.xyxy2xywh(bboxes[i])\n                data['score'] = float(bboxes[i][4])\n                data['category_id'] = 1\n                json_results.append(data)\n        return json_results\n\n    def _det2json(self, results):\n        \"\"\"Convert detection results to COCO json style.\"\"\"\n        json_results = []\n        for idx in range(len(self)):\n            img_id = self.img_ids[idx]\n            result = results[idx]\n            for label in range(len(result)):\n                bboxes = result[label]\n                for i in range(bboxes.shape[0]):\n                    data = dict()\n                    data['image_id'] = img_id\n                    data['bbox'] = self.xyxy2xywh(bboxes[i])\n                    data['score'] = float(bboxes[i][4])\n                    data['category_id'] = self.cat_ids[label]\n                    json_results.append(data)\n        return json_results\n\n    def _segm2json(self, results):\n        \"\"\"Convert instance segmentation results to COCO json style.\"\"\"\n        bbox_json_results = []\n        segm_json_results = []\n        for idx in range(len(self)):\n            img_id = self.img_ids[idx]\n            det, seg = results[idx]\n            for label in range(len(det)):\n                # bbox results\n                bboxes = det[label]\n                for i in range(bboxes.shape[0]):\n                    data = dict()\n                    data['image_id'] = img_id\n                    data['bbox'] = self.xyxy2xywh(bboxes[i])\n                    data['score'] = float(bboxes[i][4])\n                    data['category_id'] = self.cat_ids[label]\n                    bbox_json_results.append(data)\n\n                # segm results\n                # some detectors use different scores for bbox and mask\n                if isinstance(seg, tuple):\n                    segms = seg[0][label]\n                    mask_score = seg[1][label]\n                else:\n                    segms = seg[label]\n                    mask_score = [bbox[4] for bbox in bboxes]\n                for i in range(bboxes.shape[0]):\n                    data = dict()\n                    data['image_id'] = img_id\n                    data['bbox'] = self.xyxy2xywh(bboxes[i])\n                    data['score'] = float(mask_score[i])\n                    data['category_id'] = self.cat_ids[label]\n                    if isinstance(segms[i]['counts'], bytes):\n                        segms[i]['counts'] = segms[i]['counts'].decode()\n                    data['segmentation'] = segms[i]\n                    segm_json_results.append(data)\n        return bbox_json_results, segm_json_results\n\n    def results2json(self, results, outfile_prefix):\n        \"\"\"Dump the detection results to a COCO style json file.\n\n        There are 3 types of results: proposals, bbox predictions, mask\n        predictions, and they have different data types. This method will\n        automatically recognize the type, and dump them to json files.\n\n        Args:\n            results (list[list | tuple | ndarray]): Testing results of the\n                dataset.\n            outfile_prefix (str): The filename prefix of the json files. If the\n                prefix is \"somepath/xxx\", the json files will be named\n                \"somepath/xxx.bbox.json\", \"somepath/xxx.segm.json\",\n                \"somepath/xxx.proposal.json\".\n\n        Returns:\n            dict[str: str]: Possible keys are \"bbox\", \"segm\", \"proposal\", and \\\n                values are corresponding filenames.\n        \"\"\"\n        result_files = dict()\n        if isinstance(results[0], list):\n            json_results = self._det2json(results)\n            result_files['bbox'] = f'{outfile_prefix}.bbox.json'\n            result_files['proposal'] = f'{outfile_prefix}.bbox.json'\n            dump(json_results, result_files['bbox'])\n        elif isinstance(results[0], tuple):\n            json_results = self._segm2json(results)\n            result_files['bbox'] = f'{outfile_prefix}.bbox.json'\n            result_files['proposal'] = f'{outfile_prefix}.bbox.json'\n            result_files['segm'] = f'{outfile_prefix}.segm.json'\n            dump(json_results[0], result_files['bbox'])\n            dump(json_results[1], result_files['segm'])\n        elif isinstance(results[0], np.ndarray):\n            json_results = self._proposal2json(results)\n            result_files['proposal'] = f'{outfile_prefix}.proposal.json'\n            dump(json_results, result_files['proposal'])\n        else:\n            raise TypeError('invalid type of results')\n        return result_files\n\n    def fast_eval_recall(self, results, proposal_nums, iou_thrs, logger=None):\n        gt_bboxes = []\n        for i in range(len(self.img_ids)):\n            ann_ids = self.coco.get_ann_ids(img_ids=self.img_ids[i])\n            ann_info = self.coco.load_anns(ann_ids)\n            if len(ann_info) == 0:\n                gt_bboxes.append(np.zeros((0, 4)))\n                continue\n            bboxes = []\n            for ann in ann_info:\n                if ann.get('ignore', False) or ann['iscrowd']:\n                    continue\n                x1, y1, w, h = ann['bbox']\n                bboxes.append([x1, y1, x1 + w, y1 + h])\n            bboxes = np.array(bboxes, dtype=np.float32)\n            if bboxes.shape[0] == 0:\n                bboxes = np.zeros((0, 4))\n            gt_bboxes.append(bboxes)\n\n        recalls = eval_recalls(\n            gt_bboxes, results, proposal_nums, iou_thrs, logger=logger)\n        ar = recalls.mean(axis=1)\n        return ar\n\n    def format_results(self, results, jsonfile_prefix=None, **kwargs):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[tuple | numpy.ndarray]): Testing results of the\n                dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: (result_files, tmp_dir), result_files is a dict containing \\\n                the json filepaths, tmp_dir is the temporal directory created \\\n                for saving json files when jsonfile_prefix is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        assert len(results) == len(self), (\n            'The length of results is not equal to the dataset len: {} != {}'.\n            format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n        result_files = self.results2json(results, jsonfile_prefix)\n        return result_files, tmp_dir\n\n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 classwise=False,\n                 proposal_nums=(100, 300, 1000),\n                 iou_thrs=None,\n                 metric_items=None):\n        \"\"\"Evaluation in COCO protocol.\n\n        Args:\n            results (list[list | tuple]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated. Options are\n                'bbox', 'segm', 'proposal', 'proposal_fast'.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            classwise (bool): Whether to evaluating the AP for each class.\n            proposal_nums (Sequence[int]): Proposal number used for evaluating\n                recalls, such as recall@100, recall@1000.\n                Default: (100, 300, 1000).\n            iou_thrs (Sequence[float], optional): IoU threshold used for\n                evaluating recalls/mAPs. If set to a list, the average of all\n                IoUs will also be computed. If not specified, [0.50, 0.55,\n                0.60, 0.65, 0.70, 0.75, 0.80, 0.85, 0.90, 0.95] will be used.\n                Default: None.\n            metric_items (list[str] | str, optional): Metric items that will\n                be returned. If not specified, ``['AR@100', 'AR@300',\n                'AR@1000', 'AR_s@1000', 'AR_m@1000', 'AR_l@1000' ]`` will be\n                used when ``metric=='proposal'``, ``['mAP', 'mAP_50', 'mAP_75',\n                'mAP_s', 'mAP_m', 'mAP_l']`` will be used when\n                ``metric=='bbox' or metric=='segm'``.\n\n        Returns:\n            dict[str, float]: COCO style evaluation metric.\n        \"\"\"\n\n        metrics = metric if isinstance(metric, list) else [metric]\n        allowed_metrics = ['bbox', 'segm', 'proposal', 'proposal_fast']\n        for metric in metrics:\n            if metric not in allowed_metrics:\n                raise KeyError(f'metric {metric} is not supported')\n        if iou_thrs is None:\n            iou_thrs = np.linspace(\n                .5, 0.95, int(np.round((0.95 - .5) / .05)) + 1, endpoint=True)\n        if metric_items is not None:\n            if not isinstance(metric_items, list):\n                metric_items = [metric_items]\n\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n\n        eval_results = OrderedDict()\n        cocoGt = self.coco\n        for metric in metrics:\n            msg = f'Evaluating {metric}...'\n            if logger is None:\n                msg = '\\n' + msg\n            print_log(msg, logger=logger)\n\n            if metric == 'proposal_fast':\n                ar = self.fast_eval_recall(\n                    results, proposal_nums, iou_thrs, logger='silent')\n                log_msg = []\n                for i, num in enumerate(proposal_nums):\n                    eval_results[f'AR@{num}'] = ar[i]\n                    log_msg.append(f'\\nAR@{num}\\t{ar[i]:.4f}')\n                log_msg = ''.join(log_msg)\n                print_log(log_msg, logger=logger)\n                continue\n\n            iou_type = 'bbox' if metric == 'proposal' else metric\n            if metric not in result_files:\n                raise KeyError(f'{metric} is not in results')\n            try:\n                predictions = load(result_files[metric])\n                if iou_type == 'segm':\n                    # Refer to https://github.com/cocodataset/cocoapi/blob/master/PythonAPI/pycocotools/coco.py#L331  # noqa\n                    # When evaluating mask AP, if the results contain bbox,\n                    # cocoapi will use the box area instead of the mask area\n                    # for calculating the instance area. Though the overall AP\n                    # is not affected, this leads to different\n                    # small/medium/large mask AP results.\n                    for x in predictions:\n                        x.pop('bbox')\n                    warnings.simplefilter('once')\n                    warnings.warn(\n                        'The key \"bbox\" is deleted for more accurate mask AP '\n                        'of small/medium/large instances since v2.12.0. This '\n                        'does not change the overall mAP calculation.',\n                        UserWarning)\n                cocoDt = cocoGt.loadRes(predictions)\n            except IndexError:\n                print_log(\n                    'The testing results of the whole dataset is empty.',\n                    logger=logger,\n                    level=logging.ERROR)\n                break\n\n            cocoEval = COCOeval(cocoGt, cocoDt, iou_type)\n            cocoEval.params.catIds = self.cat_ids\n            cocoEval.params.imgIds = self.img_ids\n            cocoEval.params.maxDets = list(proposal_nums)\n            cocoEval.params.iouThrs = iou_thrs\n            # mapping of cocoEval.stats\n            coco_metric_names = {\n                'mAP': 0,\n                'mAP_50': 1,\n                'mAP_75': 2,\n                'mAP_s': 3,\n                'mAP_m': 4,\n                'mAP_l': 5,\n                'AR@100': 6,\n                'AR@300': 7,\n                'AR@1000': 8,\n                'AR_s@1000': 9,\n                'AR_m@1000': 10,\n                'AR_l@1000': 11\n            }\n            if metric_items is not None:\n                for metric_item in metric_items:\n                    if metric_item not in coco_metric_names:\n                        raise KeyError(\n                            f'metric item {metric_item} is not supported')\n\n            if metric == 'proposal':\n                cocoEval.params.useCats = 0\n                cocoEval.evaluate()\n                cocoEval.accumulate()\n                cocoEval.summarize()\n                if metric_items is None:\n                    metric_items = [\n                        'AR@100', 'AR@300', 'AR@1000', 'AR_s@1000',\n                        'AR_m@1000', 'AR_l@1000'\n                    ]\n\n                for item in metric_items:\n                    val = float(\n                        f'{cocoEval.stats[coco_metric_names[item]]:.3f}')\n                    eval_results[item] = val\n            else:\n                cocoEval.evaluate()\n                cocoEval.accumulate()\n                cocoEval.summarize()\n                if classwise:  # Compute per-category AP\n                    # Compute per-category AP\n                    # from https://github.com/facebookresearch/detectron2/\n                    precisions = cocoEval.eval['precision']\n                    # precision: (iou, recall, cls, area range, max dets)\n                    assert len(self.cat_ids) == precisions.shape[2]\n\n                    results_per_category = []\n                    for idx, catId in enumerate(self.cat_ids):\n                        # area range index 0: all area ranges\n                        # max dets index -1: typically 100 per image\n                        nm = self.coco.loadCats(catId)[0]\n                        precision = precisions[:, :, idx, 0, -1]\n                        precision = precision[precision > -1]\n                        if precision.size:\n                            ap = np.mean(precision)\n                        else:\n                            ap = float('nan')\n                        results_per_category.append(\n                            (f'{nm[\"name\"]}', f'{float(ap):0.3f}'))\n\n                    num_columns = min(6, len(results_per_category) * 2)\n                    results_flatten = list(\n                        itertools.chain(*results_per_category))\n                    headers = ['category', 'AP'] * (num_columns // 2)\n                    results_2d = itertools.zip_longest(*[\n                        results_flatten[i::num_columns]\n                        for i in range(num_columns)\n                    ])\n                    table_data = [headers]\n                    table_data += [result for result in results_2d]\n                    table = AsciiTable(table_data)\n                    print_log('\\n' + table.table, logger=logger)\n\n                if metric_items is None:\n                    metric_items = [\n                        'mAP', 'mAP_50', 'mAP_75', 'mAP_s', 'mAP_m', 'mAP_l'\n                    ]\n\n                for metric_item in metric_items:\n                    key = f'{metric}_{metric_item}'\n                    val = float(\n                        f'{cocoEval.stats[coco_metric_names[metric_item]]:.3f}'\n                    )\n                    eval_results[key] = val\n                ap = cocoEval.stats[:6]\n                eval_results[f'{metric}_mAP_copypaste'] = (\n                    f'{ap[0]:.3f} {ap[1]:.3f} {ap[2]:.3f} {ap[3]:.3f} '\n                    f'{ap[4]:.3f} {ap[5]:.3f}')\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n        return eval_results\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/custom.py",
    "content": "import os.path as osp\nimport warnings\nfrom collections import OrderedDict\n\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom mmcv.fileio.io import load\nfrom mmcv.fileio.parse import list_from_file\nfrom terminaltables import AsciiTable\nfrom torch.utils.data import Dataset\n\nfrom mmcv.core import eval_map, eval_recalls\nfrom .builder import DATASETS\nfrom .pipelines import Compose\n\n\n@DATASETS.register_module()\nclass CustomDataset(Dataset):\n    \"\"\"Custom dataset for detection.\n\n    The annotation format is shown as follows. The `ann` field is optional for\n    testing.\n\n    .. code-block:: none\n\n        [\n            {\n                'filename': 'a.jpg',\n                'width': 1280,\n                'height': 720,\n                'ann': {\n                    'bboxes': <np.ndarray> (n, 4) in (x1, y1, x2, y2) order.\n                    'labels': <np.ndarray> (n, ),\n                    'bboxes_ignore': <np.ndarray> (k, 4), (optional field)\n                    'labels_ignore': <np.ndarray> (k, 4) (optional field)\n                }\n            },\n            ...\n        ]\n\n    Args:\n        ann_file (str): Annotation file path.\n        pipeline (list[dict]): Processing pipeline.\n        classes (str | Sequence[str], optional): Specify classes to load.\n            If is None, ``cls.CLASSES`` will be used. Default: None.\n        data_root (str, optional): Data root for ``ann_file``,\n            ``img_prefix``, ``seg_prefix``, ``proposal_file`` if specified.\n        test_mode (bool, optional): If set True, annotation will not be loaded.\n        filter_empty_gt (bool, optional): If set true, images without bounding\n            boxes of the dataset's classes will be filtered out. This option\n            only works when `test_mode=False`, i.e., we never filter images\n            during tests.\n    \"\"\"\n\n    CLASSES = None\n\n    def __init__(self,\n                 ann_file,\n                 pipeline,\n                 classes=None,\n                 data_root=None,\n                 img_prefix='',\n                 seg_prefix=None,\n                 proposal_file=None,\n                 test_mode=False,\n                 filter_empty_gt=True):\n        self.ann_file = ann_file\n        self.data_root = data_root\n        self.img_prefix = img_prefix\n        self.seg_prefix = seg_prefix\n        self.proposal_file = proposal_file\n        self.test_mode = test_mode\n        self.filter_empty_gt = filter_empty_gt\n        self.CLASSES = self.get_classes(classes)\n\n        # join paths if data_root is specified\n        if self.data_root is not None:\n            if not osp.isabs(self.ann_file):\n                self.ann_file = osp.join(self.data_root, self.ann_file)\n            if not (self.img_prefix is None or osp.isabs(self.img_prefix)):\n                self.img_prefix = osp.join(self.data_root, self.img_prefix)\n            if not (self.seg_prefix is None or osp.isabs(self.seg_prefix)):\n                self.seg_prefix = osp.join(self.data_root, self.seg_prefix)\n            if not (self.proposal_file is None\n                    or osp.isabs(self.proposal_file)):\n                self.proposal_file = osp.join(self.data_root,\n                                              self.proposal_file)\n        # load annotations (and proposals)\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if self.proposal_file is not None:\n            self.proposals = self.load_proposals(self.proposal_file)\n        else:\n            self.proposals = None\n\n        # filter images too small and containing no annotations\n        if not test_mode:\n            valid_inds = self._filter_imgs()\n            self.data_infos = [self.data_infos[i] for i in valid_inds]\n            if self.proposals is not None:\n                self.proposals = [self.proposals[i] for i in valid_inds]\n            # set group flag for the sampler\n            self._set_group_flag()\n\n        # processing pipeline\n        self.pipeline = Compose(pipeline)\n\n    def __len__(self):\n        \"\"\"Total number of samples of data.\"\"\"\n        return len(self.data_infos)\n\n    def load_annotations(self, ann_file):\n        \"\"\"Load annotation from annotation file.\"\"\"\n        return load(ann_file)\n\n    def load_proposals(self, proposal_file):\n        \"\"\"Load proposal from proposal file.\"\"\"\n        return load(proposal_file)\n\n    def get_ann_info(self, idx):\n        \"\"\"Get annotation by index.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            dict: Annotation info of specified index.\n        \"\"\"\n\n        return self.data_infos[idx]['ann']\n\n    def get_cat_ids(self, idx):\n        \"\"\"Get category ids by index.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            list[int]: All categories in the image of specified index.\n        \"\"\"\n\n        return self.data_infos[idx]['ann']['labels'].astype(np.int).tolist()\n\n    def pre_pipeline(self, results):\n        \"\"\"Prepare results dict for pipeline.\"\"\"\n        results['img_prefix'] = self.img_prefix\n        results['seg_prefix'] = self.seg_prefix\n        results['proposal_file'] = self.proposal_file\n        results['bbox_fields'] = []\n        results['mask_fields'] = []\n        results['seg_fields'] = []\n\n    def _filter_imgs(self, min_size=32):\n        \"\"\"Filter images too small.\"\"\"\n        if self.filter_empty_gt:\n            warnings.warn(\n                'CustomDataset does not support filtering empty gt images.')\n        valid_inds = []\n        for i, img_info in enumerate(self.data_infos):\n            if min(img_info['width'], img_info['height']) >= min_size:\n                valid_inds.append(i)\n        return valid_inds\n\n    def _set_group_flag(self):\n        \"\"\"Set flag according to image aspect ratio.\n\n        Images with aspect ratio greater than 1 will be set as group 1,\n        otherwise group 0.\n        \"\"\"\n        self.flag = np.zeros(len(self), dtype=np.uint8)\n        for i in range(len(self)):\n            img_info = self.data_infos[i]\n            if img_info['width'] / img_info['height'] > 1:\n                self.flag[i] = 1\n\n    def _rand_another(self, idx):\n        \"\"\"Get another random index from the same group as the given index.\"\"\"\n        pool = np.where(self.flag == self.flag[idx])[0]\n        return np.random.choice(pool)\n\n    def __getitem__(self, idx):\n        \"\"\"Get training/test data after pipeline.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            dict: Training/test data (with annotation if `test_mode` is set \\\n                True).\n        \"\"\"\n\n        if self.test_mode:\n            return self.prepare_test_img(idx)\n        while True:\n            data = self.prepare_train_img(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def prepare_train_img(self, idx):\n        \"\"\"Get training data and annotations after pipeline.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            dict: Training data and annotation after pipeline with new keys \\\n                introduced by pipeline.\n        \"\"\"\n\n        img_info = self.data_infos[idx]\n        ann_info = self.get_ann_info(idx)\n        results = dict(img_info=img_info, ann_info=ann_info)\n        if self.proposals is not None:\n            results['proposals'] = self.proposals[idx]\n        self.pre_pipeline(results)\n        return self.pipeline(results)\n\n    def prepare_test_img(self, idx):\n        \"\"\"Get testing data  after pipeline.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            dict: Testing data after pipeline with new keys introduced by \\\n                pipeline.\n        \"\"\"\n\n        img_info = self.data_infos[idx]\n        results = dict(img_info=img_info)\n        if self.proposals is not None:\n            results['proposals'] = self.proposals[idx]\n        self.pre_pipeline(results)\n        return self.pipeline(results)\n\n    @classmethod\n    def get_classes(cls, classes=None):\n        \"\"\"Get class names of current dataset.\n\n        Args:\n            classes (Sequence[str] | str | None): If classes is None, use\n                default CLASSES defined by builtin dataset. If classes is a\n                string, take it as a file name. The file contains the name of\n                classes where each line contains one class name. If classes is\n                a tuple or list, override the CLASSES defined by the dataset.\n\n        Returns:\n            tuple[str] or list[str]: Names of categories of the dataset.\n        \"\"\"\n        if classes is None:\n            return cls.CLASSES\n\n        if isinstance(classes, str):\n            # take it as a file path\n            class_names = list_from_file(classes)\n        elif isinstance(classes, (tuple, list)):\n            class_names = classes\n        else:\n            raise ValueError(f'Unsupported type {type(classes)} of classes.')\n\n        return class_names\n\n    def format_results(self, results, **kwargs):\n        \"\"\"Place holder to format result to dataset specific output.\"\"\"\n\n    def evaluate(self,\n                 results,\n                 metric='mAP',\n                 logger=None,\n                 proposal_nums=(100, 300, 1000),\n                 iou_thr=0.5,\n                 scale_ranges=None):\n        \"\"\"Evaluate the dataset.\n\n        Args:\n            results (list): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | None | str): Logger used for printing\n                related information during evaluation. Default: None.\n            proposal_nums (Sequence[int]): Proposal number used for evaluating\n                recalls, such as recall@100, recall@1000.\n                Default: (100, 300, 1000).\n            iou_thr (float | list[float]): IoU threshold. Default: 0.5.\n            scale_ranges (list[tuple] | None): Scale ranges for evaluating mAP.\n                Default: None.\n        \"\"\"\n\n        if not isinstance(metric, str):\n            assert len(metric) == 1\n            metric = metric[0]\n        allowed_metrics = ['mAP', 'recall']\n        if metric not in allowed_metrics:\n            raise KeyError(f'metric {metric} is not supported')\n        annotations = [self.get_ann_info(i) for i in range(len(self))]\n        eval_results = OrderedDict()\n        iou_thrs = [iou_thr] if isinstance(iou_thr, float) else iou_thr\n        if metric == 'mAP':\n            assert isinstance(iou_thrs, list)\n            mean_aps = []\n            for iou_thr in iou_thrs:\n                print_log(f'\\n{\"-\" * 15}iou_thr: {iou_thr}{\"-\" * 15}')\n                mean_ap, _ = eval_map(\n                    results,\n                    annotations,\n                    scale_ranges=scale_ranges,\n                    iou_thr=iou_thr,\n                    dataset=self.CLASSES,\n                    logger=logger)\n                mean_aps.append(mean_ap)\n                eval_results[f'AP{int(iou_thr * 100):02d}'] = round(mean_ap, 3)\n            eval_results['mAP'] = sum(mean_aps) / len(mean_aps)\n        elif metric == 'recall':\n            gt_bboxes = [ann['bboxes'] for ann in annotations]\n            recalls = eval_recalls(\n                gt_bboxes, results, proposal_nums, iou_thr, logger=logger)\n            for i, num in enumerate(proposal_nums):\n                for j, iou in enumerate(iou_thrs):\n                    eval_results[f'recall@{num}@{iou}'] = recalls[i, j]\n            if recalls.shape[1] > 1:\n                ar = recalls.mean(axis=1)\n                for i, num in enumerate(proposal_nums):\n                    eval_results[f'AR@{num}'] = ar[i]\n        return eval_results\n\n    def __repr__(self):\n        \"\"\"Print the number of instance number.\"\"\"\n        dataset_type = 'Test' if self.test_mode else 'Train'\n        result = (f'\\n{self.__class__.__name__} {dataset_type} dataset '\n                  f'with number of images {len(self)}, '\n                  f'and instance counts: \\n')\n        if self.CLASSES is None:\n            result += 'Category names are not provided. \\n'\n            return result\n        instance_count = np.zeros(len(self.CLASSES) + 1).astype(int)\n        # count the instance number in each image\n        for idx in range(len(self)):\n            label = self.get_ann_info(idx)['labels']\n            unique, counts = np.unique(label, return_counts=True)\n            if len(unique) > 0:\n                # add the occurrence number to each class\n                instance_count[unique] += counts\n            else:\n                # background is the last index\n                instance_count[-1] += 1\n        # create a table with category count\n        table_data = [['category', 'count'] * 5]\n        row_data = []\n        for cls, count in enumerate(instance_count):\n            if cls < len(self.CLASSES):\n                row_data += [f'{cls} [{self.CLASSES[cls]}]', f'{count}']\n            else:\n                # add the background number\n                row_data += ['-1 background', f'{count}']\n            if len(row_data) == 10:\n                table_data.append(row_data)\n                row_data = []\n\n        table = AsciiTable(table_data)\n        result += table.table\n        return result\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/custom_3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved. \nimport numpy as np\nimport tempfile\nimport warnings\nfrom os import path as osp\nfrom torch.utils.data import Dataset\n\nfrom mmcv.datasets.builder import DATASETS\nfrom ..core.bbox import get_box_type\nfrom .pipelines import Compose\nfrom .utils import extract_result_dict, get_loading_pipeline\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.fileio.parse import list_from_file\n\n@DATASETS.register_module()\nclass Custom3DDataset(Dataset):\n    \"\"\"Customized 3D dataset.\n\n    This is the base dataset of SUNRGB-D, ScanNet, nuScenes, and KITTI\n    dataset.\n\n    Args:\n        data_root (str): Path of dataset root.\n        ann_file (str): Path of annotation file.\n        pipeline (list[dict], optional): Pipeline used for data processing.\n            Defaults to None.\n        classes (tuple[str], optional): Classes used in the dataset.\n            Defaults to None.\n        modality (dict, optional): Modality to specify the sensor data used\n            as input. Defaults to None.\n        box_type_3d (str, optional): Type of 3D box of this dataset.\n            Based on the `box_type_3d`, the dataset will encapsulate the box\n            to its original format then converted them to `box_type_3d`.\n            Defaults to 'LiDAR'. Available options includes\n\n            - 'LiDAR': Box in LiDAR coordinates.\n            - 'Depth': Box in depth coordinates, usually for indoor dataset.\n            - 'Camera': Box in camera coordinates.\n        filter_empty_gt (bool, optional): Whether to filter empty GT.\n            Defaults to True.\n        test_mode (bool, optional): Whether the dataset is in test mode.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self,\n                 data_root,\n                 ann_file,\n                 pipeline=None,\n                 classes=None,\n                 modality=None,\n                 box_type_3d='LiDAR',\n                 filter_empty_gt=True,\n                 test_mode=False):\n        super().__init__()\n        self.data_root = data_root\n        self.ann_file = ann_file\n        self.test_mode = test_mode\n        self.modality = modality\n        self.filter_empty_gt = filter_empty_gt\n        self.box_type_3d, self.box_mode_3d = get_box_type(box_type_3d)\n\n        self.CLASSES = self.get_classes(classes)\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if pipeline is not None:\n            self.pipeline = Compose(pipeline)\n\n        # set group flag for the sampler\n        if not self.test_mode:\n            self._set_group_flag()\n\n    def load_annotations(self, ann_file):\n        \"\"\"Load annotations from ann_file.\n\n        Args:\n            ann_file (str): Path of the annotation file.\n\n        Returns:\n            list[dict]: List of annotations.\n        \"\"\"\n        return load(ann_file)\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - file_name (str): Filename of point clouds.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n        sample_idx = info['point_cloud']['lidar_idx']\n        pts_filename = osp.join(self.data_root, info['pts_path'])\n\n        input_dict = dict(\n            pts_filename=pts_filename,\n            sample_idx=sample_idx,\n            file_name=pts_filename)\n\n        if not self.test_mode:\n            annos = self.get_ann_info(index)\n            input_dict['ann_info'] = annos\n            if self.filter_empty_gt and ~(annos['gt_labels_3d'] != -1).any():\n                return None\n        return input_dict\n\n    def pre_pipeline(self, results):\n        \"\"\"Initialization before data preparation.\n\n        Args:\n            results (dict): Dict before data preprocessing.\n\n                - img_fields (list): Image fields.\n                - bbox3d_fields (list): 3D bounding boxes fields.\n                - pts_mask_fields (list): Mask fields of points.\n                - pts_seg_fields (list): Mask fields of point segments.\n                - bbox_fields (list): Fields of bounding boxes.\n                - mask_fields (list): Fields of masks.\n                - seg_fields (list): Segment fields.\n                - box_type_3d (str): 3D box type.\n                - box_mode_3d (str): 3D box mode.\n        \"\"\"\n        results['img_fields'] = []\n        results['bbox3d_fields'] = []\n        results['pts_mask_fields'] = []\n        results['pts_seg_fields'] = []\n        results['bbox_fields'] = []\n        results['mask_fields'] = []\n        results['seg_fields'] = []\n        results['box_type_3d'] = self.box_type_3d\n        results['box_mode_3d'] = self.box_mode_3d\n\n    def prepare_train_data(self, index):\n        \"\"\"Training data preparation.\n\n        Args:\n            index (int): Index for accessing the target data.\n\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        input_dict = self.get_data_info(index)\n        if input_dict is None:\n            return None\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        if self.filter_empty_gt and \\\n                (example is None or\n                    ~(example['gt_labels_3d']._data != -1).any()):\n            return None\n        return example\n\n    def prepare_test_data(self, index):\n        \"\"\"Prepare data for testing.\n\n        Args:\n            index (int): Index for accessing the target data.\n\n        Returns:\n            dict: Testing data dict of the corresponding index.\n        \"\"\"\n        input_dict = self.get_data_info(index)\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        return example\n\n    @classmethod\n    def get_classes(cls, classes=None):\n        \"\"\"Get class names of current dataset.\n\n        Args:\n            classes (Sequence[str] | str | None): If classes is None, use\n                default CLASSES defined by builtin dataset. If classes is a\n                string, take it as a file name. The file contains the name of\n                classes where each line contains one class name. If classes is\n                a tuple or list, override the CLASSES defined by the dataset.\n\n        Return:\n            list[str]: A list of class names.\n        \"\"\"\n        if classes is None:\n            return cls.CLASSES\n\n        if isinstance(classes, str):\n            # take it as a file path\n            class_names = list_from_file(classes)\n        elif isinstance(classes, (tuple, list)):\n            class_names = classes\n        else:\n            raise ValueError(f'Unsupported type {type(classes)} of classes.')\n\n        return class_names\n\n    def format_results(self,\n                       outputs,\n                       pklfile_prefix=None,\n                       submission_prefix=None):\n        \"\"\"Format the results to pkl file.\n\n        Args:\n            outputs (list[dict]): Testing results of the dataset.\n            pklfile_prefix (str | None): The prefix of pkl files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: (outputs, tmp_dir), outputs is the detection results, \\\n                tmp_dir is the temporal directory created for saving json \\\n                files when ``jsonfile_prefix`` is not specified.\n        \"\"\"\n        if pklfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            pklfile_prefix = osp.join(tmp_dir.name, 'results')\n            out = f'{pklfile_prefix}.pkl'\n        dump(outputs, out)\n        return outputs, tmp_dir\n\n    def evaluate(self,\n                 results,\n                 metric=None,\n                 iou_thr=(0.25, 0.5),\n                 logger=None,\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluate.\n\n        Evaluation in indoor protocol.\n\n        Args:\n            results (list[dict]): List of results.\n            metric (str | list[str]): Metrics to be evaluated.\n            iou_thr (list[float]): AP IoU thresholds.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict: Evaluation results.\n        \"\"\"\n        from mmcv.core.evaluation import indoor_eval\n        assert isinstance(\n            results, list), f'Expect results to be list, got {type(results)}.'\n        assert len(results) > 0, 'Expect length of results > 0.'\n        assert len(results) == len(self.data_infos)\n        assert isinstance(\n            results[0], dict\n        ), f'Expect elements in results to be dict, got {type(results[0])}.'\n        gt_annos = [info['annos'] for info in self.data_infos]\n        label2cat = {i: cat_id for i, cat_id in enumerate(self.CLASSES)}\n        ret_dict = indoor_eval(\n            gt_annos,\n            results,\n            iou_thr,\n            label2cat,\n            logger=logger,\n            box_type_3d=self.box_type_3d,\n            box_mode_3d=self.box_mode_3d)\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n\n        return ret_dict\n\n    def _build_default_pipeline(self):\n        \"\"\"Build the default pipeline for this dataset.\"\"\"\n        raise NotImplementedError('_build_default_pipeline is not implemented '\n                                  f'for dataset {self.__class__.__name__}')\n\n    def _get_pipeline(self, pipeline):\n        \"\"\"Get data loading pipeline in self.show/evaluate function.\n\n        Args:\n            pipeline (list[dict] | None): Input pipeline. If None is given, \\\n                get from self.pipeline.\n        \"\"\"\n        if pipeline is None:\n            if not hasattr(self, 'pipeline') or self.pipeline is None:\n                warnings.warn(\n                    'Use default pipeline for data loading, this may cause '\n                    'errors when data is on ceph')\n                return self._build_default_pipeline()\n            loading_pipeline = get_loading_pipeline(self.pipeline.transforms)\n            return Compose(loading_pipeline)\n        return Compose(pipeline)\n\n    def _extract_data(self, index, pipeline, key, load_annos=False):\n        \"\"\"Load data using input pipeline and extract data according to key.\n\n        Args:\n            index (int): Index for accessing the target data.\n            pipeline (:obj:`Compose`): Composed data loading pipeline.\n            key (str | list[str]): One single or a list of data key.\n            load_annos (bool): Whether to load data annotations.\n                If True, need to set self.test_mode as False before loading.\n\n        Returns:\n            np.ndarray | torch.Tensor | list[np.ndarray | torch.Tensor]:\n                A single or a list of loaded data.\n        \"\"\"\n        assert pipeline is not None, 'data loading pipeline is not provided'\n        # when we want to load ground-truth via pipeline (e.g. bbox, seg mask)\n        # we need to set self.test_mode as False so that we have 'annos'\n        if load_annos:\n            original_test_mode = self.test_mode\n            self.test_mode = False\n        input_dict = self.get_data_info(index)\n        self.pre_pipeline(input_dict)\n        example = pipeline(input_dict)\n\n        # extract data items according to keys\n        if isinstance(key, str):\n            data = extract_result_dict(example, key)\n        else:\n            data = [extract_result_dict(example, k) for k in key]\n        if load_annos:\n            self.test_mode = original_test_mode\n\n        return data\n\n    def __len__(self):\n        \"\"\"Return the length of data infos.\n\n        Returns:\n            int: Length of data infos.\n        \"\"\"\n        return len(self.data_infos)\n\n    def _rand_another(self, idx):\n        \"\"\"Randomly get another item with the same flag.\n\n        Returns:\n            int: Another index of item with the same flag.\n        \"\"\"\n        pool = np.where(self.flag == self.flag[idx])[0]\n        return np.random.choice(pool)\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def _set_group_flag(self):\n        \"\"\"Set flag according to image aspect ratio.\n\n        Images with aspect ratio greater than 1 will be set as group 1,\n        otherwise group 0. In 3D datasets, they are all the same, thus are all\n        zeros.\n        \"\"\"\n        self.flag = np.zeros(len(self), dtype=np.uint8)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/custom_nuscenes_dataset.py",
    "content": "import copy\n\nimport numpy as np\nfrom mmcv.datasets import DATASETS\nfrom mmcv.datasets import NuScenesDataset\nfrom os import path as osp\nfrom mmcv.datasets import DATASETS\nimport torch\nimport numpy as np\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom .nuscnes_eval import NuScenesEval_custom\nfrom mmcv.utils import save_tensor\nfrom mmcv.parallel import DataContainer as DC\nimport random\nfrom mmcv.fileio.io import load\n\n\n@DATASETS.register_module()\nclass CustomNuScenesDataset(NuScenesDataset):\n    r\"\"\"NuScenes Dataset.\n\n    This datset only add camera intrinsics and extrinsics to the results.\n    \"\"\"\n\n    def __init__(self, queue_length=4, bev_size=(200, 200), overlap_test=False, *args, **kwargs):\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.overlap_test = overlap_test\n        self.bev_size = bev_size\n        \n        \n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        queue = []\n        index_list = list(range(index-self.queue_length, index))\n        random.shuffle(index_list)\n        index_list = sorted(index_list[1:])\n        index_list.append(index)\n        for i in index_list:\n            i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            self.pre_pipeline(input_dict)\n            example = self.pipeline(input_dict)\n            if self.filter_empty_gt and \\\n                    (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n                return None\n            queue.append(example)\n        return self.union2one(queue)\n\n\n    def union2one(self, queue):\n        imgs_list = [each['img'].data for each in queue]\n        metas_map = {}\n        prev_scene_token = None\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if metas_map[i]['scene_token'] != prev_scene_token:\n                metas_map[i]['prev_bev_exists'] = False\n                prev_scene_token = metas_map[i]['scene_token']\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev_exists'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n        queue[-1]['img'] = DC(torch.stack(imgs_list), cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n        return queue\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n        # standard protocal modified from SECOND.Pytorch\n        input_dict = dict(\n            sample_idx=info['token'],\n            pts_filename=info['lidar_path'],\n            sweeps=info['sweeps'],\n            ego2global_translation=info['ego2global_translation'],\n            ego2global_rotation=info['ego2global_rotation'],\n            prev_idx=info['prev'],\n            next_idx=info['next'],\n            scene_token=info['scene_token'],\n            can_bus=info['can_bus'],\n            frame_idx=info['frame_idx'],\n            timestamp=info['timestamp'] / 1e6,\n        )\n#(['CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_FRONT_LEFT', 'CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT'])\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            for cam_type, cam_info in info['cams'].items():\n                # if cam_type in ['CAM_FRONT','CAM_BACK_LEFT']:\n                #     continue\n                image_paths.append(cam_info['data_path'])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info['sensor2lidar_rotation'])\n                lidar2cam_t = cam_info[\n                    'sensor2lidar_translation'] @ lidar2cam_r.T\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = cam_info['cam_intrinsic']\n                viewpad = np.eye(4)\n                viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                lidar2img_rts.append(lidar2img_rt)\n\n                cam_intrinsics.append(viewpad)\n                lidar2cam_rts.append(lidar2cam_rt.T)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                ))\n\n        if not self.test_mode:\n            annos = self.get_ann_info(index)\n            input_dict['ann_info'] = annos\n\n        rotation = Quaternion(input_dict['ego2global_rotation'])\n        translation = input_dict['ego2global_translation']\n        can_bus = input_dict['can_bus']\n        can_bus[:3] = translation\n        can_bus[3:7] = rotation\n        patch_angle = quaternion_yaw(rotation) / np.pi * 180\n        if patch_angle < 0:\n            patch_angle += 360\n        can_bus[-2] = patch_angle / 180 * np.pi\n        can_bus[-1] = patch_angle\n\n        return input_dict\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        self.nusc = NuScenes(version=self.version, dataroot=self.data_root,\n                             verbose=True)\n\n        import pdb\n        pdb.set_trace()\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        self.nusc_eval = NuScenesEval_custom(\n            self.nusc,\n            config=self.eval_detection_configs,\n            result_path=result_path,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=True,\n            overlap_test=self.overlap_test,\n            data_infos=self.data_infos\n        )\n        self.nusc_eval.main(plot_examples=0, render_curves=False)\n        # record metrics\n        metrics = load(osp.join(output_dir, 'metrics_summary.json'))\n        detail = dict()\n        metric_prefix = f'{result_name}_NuScenes'\n        for name in self.CLASSES:\n            for k, v in metrics['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,\n                                      self.ErrNameMapping[k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics['mean_ap']\n        return detail\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/custom_nuscenes_dataset_v2.py",
    "content": "import copy\nfrom .nuscenes_dataset import NuScenesDataset\nfrom .dd3d_nuscenes_dataset import DD3DNuscenesDataset\nfrom os import path as osp\nfrom mmcv.datasets import DATASETS\nimport torch\nimport numpy as np\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom .nuscnes_eval import NuScenesEval_custom\nfrom mmcv.parallel import DataContainer as DC\nfrom collections import defaultdict, OrderedDict\n\n\n@DATASETS.register_module()\nclass CustomNuScenesDatasetV2(NuScenesDataset):\n    def __init__(self, frames=(),mono_cfg=None, overlap_test=False,*args, **kwargs):\n        super().__init__(*args, **kwargs)\n        self.frames = frames\n        self.queue_length = len(frames)\n        self.overlap_test = overlap_test\n        self.mono_cfg = mono_cfg\n        if not self.test_mode and mono_cfg is not None:\n            self.mono_dataset = DD3DNuscenesDataset(**mono_cfg)\n\n    def prepare_test_data(self, index):\n        \"\"\"Prepare data for testing.\n\n        Args:\n            index (int): Index for accessing the target data.\n\n        Returns:\n            dict: Testing data dict of the corresponding index.\n        \"\"\"\n        data_queue = OrderedDict()\n        input_dict = self.get_data_info(index)\n        cur_scene_token = input_dict['scene_token']\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        data_queue[0] = example\n        \n        for frame_idx in self.frames:\n            chosen_idx = index + frame_idx\n            if frame_idx ==0 or chosen_idx <0 or chosen_idx >= len(self.data_infos):\n                continue\n            info = self.data_infos[chosen_idx]\n            input_dict = self.prepare_input_dict(info)\n            if input_dict['scene_token'] == cur_scene_token:\n                self.pre_pipeline(input_dict)\n                example = self.pipeline(input_dict)\n                data_queue[frame_idx] = example\n\n        data_queue = OrderedDict(sorted(data_queue.items()))\n        ret = defaultdict(list)\n        for i in range(len(data_queue[0]['img'])):\n            single_aug_data_queue = {}\n            for t in data_queue.keys():\n                single_example = {}\n                for key ,value in data_queue[t].items():\n                    single_example[key] = value[i]\n                single_aug_data_queue[t] = single_example\n            single_aug_data_queue = OrderedDict(sorted(single_aug_data_queue.items()))\n            single_aug_sample = self.union2one(single_aug_data_queue)\n\n            for key, value in single_aug_sample.items():\n                ret[key].append(value)\n        return ret\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        data_queue = OrderedDict()\n        input_dict = self.get_data_info(index)\n        if input_dict is None:\n            return None \n        cur_scene_token = input_dict['scene_token']\n        # cur_frame_idx = input_dict['frame_idx']\n        ann_info = copy.deepcopy(input_dict['ann_info'])\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        if self.filter_empty_gt and \\\n                (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n            return None\n        data_queue[0] = example\n        aug_param = copy.deepcopy(example['aug_param']) if 'aug_param' in example else {}\n        \n        # frame_idx_to_idx = self.scene_to_frame_idx_to_idx[cur_scene_token]\n        for frame_idx in self.frames:\n            chosen_idx = index + frame_idx\n            if frame_idx ==0 or chosen_idx <0 or chosen_idx >= len(self.data_infos):\n                continue\n            info = self.data_infos[chosen_idx]\n            input_dict = self.prepare_input_dict(info)\n            if input_dict['scene_token'] == cur_scene_token:\n                input_dict['ann_info'] = copy.deepcopy(ann_info) # only for pipeline, should never be used \n                self.pre_pipeline(input_dict)\n                input_dict['aug_param'] = copy.deepcopy(aug_param)\n                example = self.pipeline(input_dict)\n                data_queue[frame_idx] = example\n\n        data_queue = OrderedDict(sorted(data_queue.items()))\n        return self.union2one(data_queue)\n\n    def union2one(self, queue: dict):\n        \"\"\"\n        convert sample queue into one single sample.\n        \"\"\"\n        imgs_list = [each['img'].data for each in queue.values()]\n        lidar2ego = np.eye(4, dtype=np.float32)\n        lidar2ego[:3, :3] = Quaternion(queue[0]['lidar2ego_rotation']).rotation_matrix\n        lidar2ego[:3, 3] = queue[0]['lidar2ego_translation']\n\n        egocurr2global = np.eye(4, dtype=np.float32)\n        egocurr2global[:3,:3] = Quaternion(queue[0]['ego2global_rotation']).rotation_matrix\n        egocurr2global[:3,3] = queue[0]['ego2global_translation']\n        metas_map = {}\n        for i, each in queue.items():\n            metas_map[i] = each['img_metas'].data\n            metas_map[i]['timestamp'] = each['timestamp']\n            if 'aug_param' in each:\n                metas_map[i]['aug_param'] = each['aug_param']\n            if i == 0:\n                metas_map[i]['lidaradj2lidarcurr'] = None\n            else:\n                egoadj2global = np.eye(4, dtype=np.float32)\n                egoadj2global[:3,:3] = Quaternion(each['ego2global_rotation']).rotation_matrix\n                egoadj2global[:3,3] = each['ego2global_translation']\n\n                lidaradj2lidarcurr = np.linalg.inv(lidar2ego) @ np.linalg.inv(egocurr2global) @ egoadj2global @ lidar2ego\n                metas_map[i]['lidaradj2lidarcurr'] = lidaradj2lidarcurr\n                for i_cam in range(len(metas_map[i]['lidar2img'])):\n                    metas_map[i]['lidar2img'][i_cam] = metas_map[i]['lidar2img'][i_cam] @ np.linalg.inv(lidaradj2lidarcurr)\n        queue[0]['img'] = DC(torch.stack(imgs_list),\n                              cpu_only=False, stack=True)\n        queue[0]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[0]\n        return queue\n\n    def prepare_input_dict(self, info):\n        # standard protocal modified from SECOND.Pytorch\n        input_dict = dict(\n            sample_idx=info['token'],\n            pts_filename=info['lidar_path'],\n            sweeps=info['sweeps'],\n            ego2global_translation=info['ego2global_translation'],\n            ego2global_rotation=info['ego2global_rotation'],\n            lidar2ego_translation=info['lidar2ego_translation'],\n            lidar2ego_rotation=info['lidar2ego_rotation'],\n            prev=info['prev'],\n            next=info['next'],\n            scene_token=info['scene_token'],\n            frame_idx=info['frame_idx'],\n            timestamp=info['timestamp'] / 1e6,\n        )\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            for cam_type, cam_info in info['cams'].items():\n                image_paths.append(cam_info['data_path'])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info['sensor2lidar_rotation'])\n                lidar2cam_t = cam_info[\n                    'sensor2lidar_translation'] @ lidar2cam_r.T\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = cam_info['cam_intrinsic']\n                viewpad = np.eye(4)\n                viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                lidar2img_rts.append(lidar2img_rt)\n\n                cam_intrinsics.append(viewpad)\n                lidar2cam_rts.append(lidar2cam_rt.T)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam2img=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                ))\n\n        return input_dict\n\n    def filter_crowd_annotations(self, data_dict):\n        for ann in data_dict[\"annotations\"]:\n            if ann.get(\"iscrowd\", 0) == 0:\n                return True\n        return False\n\n    def get_data_info(self, index):\n        info = self.data_infos[index]\n        input_dict = self.prepare_input_dict(info)\n        if not self.test_mode:\n            annos = self.get_ann_info(index)\n            input_dict['ann_info'] = annos\n\n        if not self.test_mode and self.mono_cfg is not None:\n            if input_dict is None:\n                return None\n            info = self.data_infos[index]\n            img_ids = []\n            for cam_type, cam_info in info['cams'].items():\n                img_ids.append(cam_info['sample_data_token'])\n\n            mono_input_dict = []; mono_ann_index = []\n            for i, img_id in enumerate(img_ids):\n                tmp_dict = self.mono_dataset.getitem_by_datumtoken(img_id)\n                if tmp_dict is not None:\n                    if self.filter_crowd_annotations(tmp_dict):\n                        mono_input_dict.append(tmp_dict)\n                        mono_ann_index.append(i)\n\n            # filter empth annotation\n            if len(mono_ann_index) == 0:\n                return None\n\n            mono_ann_index = DC(mono_ann_index, cpu_only=True)\n            input_dict['mono_input_dict'] = mono_input_dict\n            input_dict['mono_ann_idx'] = mono_ann_index\n        return input_dict\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        self.nusc = NuScenes(version=self.version, dataroot=self.data_root,\n                             verbose=True)\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        self.nusc_eval = NuScenesEval_custom(\n            self.nusc,\n            config=self.eval_detection_configs,\n            result_path=result_path,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=True,\n            overlap_test=self.overlap_test,\n            data_infos=self.data_infos\n        )\n        self.nusc_eval.main(plot_examples=0, render_curves=False)\n        # record metrics\n        metrics = mmcv.load(osp.join(output_dir, 'metrics_summary.json'))\n        detail = dict()\n        metric_prefix = f'{result_name}_NuScenes'\n        for name in self.CLASSES:\n            for k, v in metrics['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,\n                                      self.ErrNameMapping[k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics['mean_ap']\n        return detail"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/data_utils/data_utils.py",
    "content": "import math\nimport numpy as np\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nimport pyquaternion\n\n\ndef output_to_nusc_box(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n    Args:\n        detection (dict): Detection results.\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n    if 'track_ids' in detection:\n        ids = detection['track_ids'].numpy()\n    else:\n        ids = np.ones_like(labels)\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        velocity = (*box3d.tensor[i, 7:9], 0.0)\n        # velo_val = np.linalg.norm(box3d[i, 7:9])\n        # velo_ori = box3d[i, 6]\n        # velocity = (\n        # velo_val * np.cos(velo_ori), velo_val * np.sin(velo_ori), 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box.token = ids[i]\n        box_list.append(box)\n    return box_list\n\n\ndef output_to_nusc_box_det(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n\n    Args:\n        detection (dict): Detection results.\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    if 'boxes_3d_det' in detection:\n        box3d = detection['boxes_3d_det']\n        scores = detection['scores_3d_det'].numpy()\n        labels = detection['labels_3d_det'].numpy()\n    else:\n        box3d = detection['boxes_3d']\n        scores = detection['scores_3d'].numpy()\n        labels = detection['labels_3d'].numpy()\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        velocity = (*box3d.tensor[i, 7:9], 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(info,\n                             boxes,\n                             classes,\n                             eval_configs,\n                             eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from ego to global coordinate.\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str, optional): Evaluation version.\n            Default: 'detection_cvpr_2019'\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    keep_idx = []\n    for i, box in enumerate(boxes):\n        # Move box to ego vehicle coord system\n        box.rotate(Quaternion(info['lidar2ego_rotation']))\n        box.translate(np.array(info['lidar2ego_translation']))\n        # filter det in ego.\n        cls_range_map = eval_configs.class_range\n        radius = np.linalg.norm(box.center[:2], 2)\n        det_range = cls_range_map[classes[box.label]]\n        if radius > det_range:\n            continue\n        # Move box to global coord system\n        box.rotate(Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n        keep_idx.append(i)\n    return box_list, keep_idx\n\n\ndef obtain_map_info(nusc,\n                    nusc_maps,\n                    sample,\n                    patch_size=(102.4, 102.4),\n                    canvas_size=(256, 256),\n                    layer_names=['lane_divider', 'road_divider'],\n                    thickness=10):\n    \"\"\"\n    Export 2d annotation from the info file and raw data.\n    \"\"\"\n    l2e_r = sample['lidar2ego_rotation']\n    l2e_t = sample['lidar2ego_translation']\n    e2g_r = sample['ego2global_rotation']\n    e2g_t = sample['ego2global_translation']\n    l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n    e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n    scene = nusc.get('scene', sample['scene_token'])\n    log = nusc.get('log', scene['log_token'])\n    nusc_map = nusc_maps[log['location']]\n    if layer_names is None:\n        layer_names = nusc_map.non_geometric_layers\n\n    l2g_r_mat = (l2e_r_mat.T @ e2g_r_mat.T).T\n    l2g_t = l2e_t @ e2g_r_mat.T + e2g_t\n    patch_box = (l2g_t[0], l2g_t[1], patch_size[0], patch_size[1])\n    patch_angle = math.degrees(Quaternion(matrix=l2g_r_mat).yaw_pitch_roll[0])\n\n    map_mask = nusc_map.get_map_mask(\n        patch_box, patch_angle, layer_names, canvas_size=canvas_size)\n    map_mask = map_mask[-2] | map_mask[-1]\n    map_mask = map_mask[np.newaxis, :]\n    map_mask = map_mask.transpose((2, 1, 0)).squeeze(2)  # (H, W, C)\n\n    erode = nusc_map.get_map_mask(patch_box, patch_angle, [\n                                  'drivable_area'], canvas_size=canvas_size)\n    erode = erode.transpose((2, 1, 0)).squeeze(2)\n\n    map_mask = np.concatenate([erode[None], map_mask[None]], axis=0)\n    return map_mask\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/data_utils/rasterize.py",
    "content": "import cv2\nimport numpy as np\nfrom shapely import affinity\nfrom shapely.geometry import LineString, box\n\n\ndef get_patch_coord(patch_box, patch_angle=0.0):\n    patch_x, patch_y, patch_h, patch_w = patch_box\n\n    x_min = patch_x - patch_w / 2.0\n    y_min = patch_y - patch_h / 2.0\n    x_max = patch_x + patch_w / 2.0\n    y_max = patch_y + patch_h / 2.0\n\n    patch = box(x_min, y_min, x_max, y_max)\n    patch = affinity.rotate(patch, patch_angle, origin=(\n        patch_x, patch_y), use_radians=False)\n\n    return patch\n\n\ndef get_discrete_degree(vec, angle_class=36):\n    deg = np.mod(np.degrees(np.arctan2(vec[1], vec[0])), 360)\n    deg = (int(deg / (360 / angle_class) + 0.5) % angle_class) + 1\n    return deg\n\n\ndef mask_for_lines(lines, mask, thickness, idx, type='index', angle_class=36):\n    coords = np.asarray(list(lines.coords), np.int32)\n    coords = coords.reshape((-1, 2))\n    if len(coords) < 2:\n        return mask, idx\n    if type == 'backward':\n        coords = np.flip(coords, 0)\n\n    if type == 'index':\n        cv2.polylines(mask, [coords], False, color=idx, thickness=thickness)\n        idx += 1\n    else:\n        for i in range(len(coords) - 1):\n            cv2.polylines(mask, [coords[i:]], False, color=get_discrete_degree(\n                coords[i + 1] - coords[i], angle_class=angle_class), thickness=thickness)\n    return mask, idx\n\n\ndef line_geom_to_mask(layer_geom, confidence_levels, local_box, canvas_size, thickness, idx, type='index', angle_class=36):\n    patch_x, patch_y, patch_h, patch_w = local_box\n\n    patch = get_patch_coord(local_box)\n\n    canvas_h = canvas_size[0]\n    canvas_w = canvas_size[1]\n    scale_height = canvas_h / patch_h\n    scale_width = canvas_w / patch_w\n\n    trans_x = -patch_x + patch_w / 2.0\n    trans_y = -patch_y + patch_h / 2.0\n\n    map_mask = np.zeros(canvas_size, np.uint8)\n\n    for line in layer_geom:\n        if isinstance(line, tuple):\n            line, confidence = line\n        else:\n            confidence = None\n        new_line = line.intersection(patch)\n        if not new_line.is_empty:\n            new_line = affinity.affine_transform(\n                new_line, [1.0, 0.0, 0.0, 1.0, trans_x, trans_y])\n            new_line = affinity.scale(\n                new_line, xfact=scale_width, yfact=scale_height, origin=(0, 0))\n            confidence_levels.append(confidence)\n            if new_line.geom_type == 'MultiLineString':\n                for new_single_line in new_line:\n                    map_mask, idx = mask_for_lines(\n                        new_single_line, map_mask, thickness, idx, type, angle_class)\n            else:\n                map_mask, idx = mask_for_lines(\n                    new_line, map_mask, thickness, idx, type, angle_class)\n    return map_mask, idx\n\n\ndef overlap_filter(mask, filter_mask):\n    C, _, _ = mask.shape\n    for c in range(C-1, -1, -1):\n        filter = np.repeat((filter_mask[c] != 0)[None, :], c, axis=0)\n        mask[:c][filter] = 0\n\n    return mask\n\n\ndef preprocess_map(vectors, patch_size, canvas_size, num_classes, thickness, angle_class):\n    confidence_levels = [-1]\n    vector_num_list = {}\n    for i in range(num_classes):\n        vector_num_list[i] = []\n\n    for vector in vectors:\n        if vector['pts_num'] >= 2:\n            vector_num_list[vector['type']].append(\n                LineString(vector['pts'][:vector['pts_num']]))\n\n    local_box = (0.0, 0.0, patch_size[0], patch_size[1])\n\n    idx = 1\n    filter_masks = []\n    instance_masks = []\n    forward_masks = []\n    backward_masks = []\n    for i in range(num_classes):\n        map_mask, idx = line_geom_to_mask(\n            vector_num_list[i], confidence_levels, local_box, canvas_size, thickness, idx)\n        instance_masks.append(map_mask)\n        filter_mask, _ = line_geom_to_mask(\n            vector_num_list[i], confidence_levels, local_box, canvas_size, thickness + 4, 1)\n        filter_masks.append(filter_mask)\n        forward_mask, _ = line_geom_to_mask(\n            vector_num_list[i], confidence_levels, local_box, canvas_size, thickness, 1, type='forward', angle_class=angle_class)\n        forward_masks.append(forward_mask)\n        backward_mask, _ = line_geom_to_mask(\n            vector_num_list[i], confidence_levels, local_box, canvas_size, thickness, 1, type='backward', angle_class=angle_class)\n        backward_masks.append(backward_mask)\n\n    filter_masks = np.stack(filter_masks)\n    instance_masks = np.stack(instance_masks)\n    forward_masks = np.stack(forward_masks)\n    backward_masks = np.stack(backward_masks)\n\n    instance_masks = overlap_filter(instance_masks, filter_masks)\n    forward_masks = overlap_filter(\n        forward_masks, filter_masks).sum(0).astype('int32')\n    backward_masks = overlap_filter(\n        backward_masks, filter_masks).sum(0).astype('int32')\n\n    semantic_masks = instance_masks != 0\n\n    return semantic_masks, instance_masks, forward_masks, backward_masks\n\n\ndef rasterize_map(vectors, patch_size, canvas_size, num_classes, thickness):\n    confidence_levels = [-1]\n    vector_num_list = {}\n    for i in range(num_classes):\n        vector_num_list[i] = []\n\n    for vector in vectors:\n        if vector['pts_num'] >= 2:\n            vector_num_list[vector['type']].append(\n                (LineString(vector['pts'][:vector['pts_num']]), vector.get('confidence_level', 1)))\n\n    local_box = (0.0, 0.0, patch_size[0], patch_size[1])\n\n    idx = 1\n    masks = []\n    for i in range(num_classes):\n        map_mask, idx = line_geom_to_mask(\n            vector_num_list[i], confidence_levels, local_box, canvas_size, thickness, idx)\n        masks.append(map_mask)\n\n    return np.stack(masks), confidence_levels\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/data_utils/trajectory_api.py",
    "content": "import numpy as np\nfrom nuscenes.prediction import (PredictHelper,\n                                 convert_local_coords_to_global,\n                                 convert_global_coords_to_local)\nfrom mmcv.core.bbox.structures.box_3d_mode import Box3DMode\nfrom mmcv.core.bbox.structures.coord_3d_mode import Coord3DMode\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.datasets.pipelines import to_tensor\n\nclass NuScenesTraj(object):\n    def __init__(self,\n                 nusc,\n                 predict_steps,\n                 planning_steps,\n                 past_steps,\n                 fut_steps,\n                 with_velocity,\n                 CLASSES,\n                 box_mode_3d,\n                 use_nonlinear_optimizer=False):\n        super().__init__()\n        self.nusc = nusc\n        self.prepare_sdc_vel_info()\n        self.predict_steps = predict_steps\n        self.planning_steps = planning_steps\n        self.past_steps = past_steps\n        self.fut_steps = fut_steps\n        self.with_velocity = with_velocity\n        self.CLASSES = CLASSES\n        self.box_mode_3d = box_mode_3d\n        self.predict_helper = PredictHelper(self.nusc)\n        self.use_nonlinear_optimizer = use_nonlinear_optimizer\n\n    def get_traj_label(self, sample_token, ann_tokens):\n        sd_rec = self.nusc.get('sample', sample_token)\n        fut_traj_all = []\n        fut_traj_valid_mask_all = []\n        past_traj_all = []\t\n        past_traj_valid_mask_all = []\n        _, boxes, _ = self.nusc.get_sample_data(sd_rec['data']['LIDAR_TOP'], selected_anntokens=ann_tokens)\n        for i, ann_token in enumerate(ann_tokens):\n            box = boxes[i]\n            instance_token = self.nusc.get('sample_annotation', ann_token)['instance_token']\n            fut_traj_local = self.predict_helper.get_future_for_agent(instance_token, sample_token, seconds=6, in_agent_frame=True)\n            past_traj_local = self.predict_helper.get_past_for_agent(instance_token, sample_token, seconds=2, in_agent_frame=True)\n\n            fut_traj = np.zeros((self.predict_steps, 2))\n            fut_traj_valid_mask = np.zeros((self.predict_steps, 2))\n            past_traj = np.zeros((self.past_steps + self.fut_steps, 2))\t\t\n            past_traj_valid_mask = np.zeros((self.past_steps + self.fut_steps, 2))\n            if fut_traj_local.shape[0] > 0:\n                if self.use_nonlinear_optimizer:\n                    trans = box.center\n                else:\n                    trans = np.array([0, 0, 0])\n                rot = Quaternion(matrix=box.rotation_matrix)\n                fut_traj_scence_centric = convert_local_coords_to_global(fut_traj_local, trans, rot) \n                fut_traj[:fut_traj_scence_centric.shape[0], :] = fut_traj_scence_centric\n                fut_traj_valid_mask[:fut_traj_scence_centric.shape[0], :] = 1\n            if past_traj_local.shape[0] > 0:\t\t\t\n                trans = np.array([0, 0, 0])\t\t\n                rot = Quaternion(matrix=box.rotation_matrix)\t\t\n                past_traj_scence_centric = convert_local_coords_to_global(past_traj_local, trans, rot) \t\t\n                past_traj[:past_traj_scence_centric.shape[0], :] = past_traj_scence_centric\t\t\n                past_traj_valid_mask[:past_traj_scence_centric.shape[0], :] = 1\n\n                if fut_traj_local.shape[0] > 0:\n                    fut_steps = min(self.fut_steps, fut_traj_scence_centric.shape[0])\n                    past_traj[self.past_steps:self.past_steps+fut_steps, :] = fut_traj_scence_centric[:fut_steps]\n                    past_traj_valid_mask[self.past_steps:self.past_steps+fut_steps, :] = 1\n\n            fut_traj_all.append(fut_traj)\t\t\n            fut_traj_valid_mask_all.append(fut_traj_valid_mask)\t\t\n            past_traj_all.append(past_traj)\t\t\n            past_traj_valid_mask_all.append(past_traj_valid_mask)\t\t\n        if len(ann_tokens) > 0:\t\t\n            fut_traj_all = np.stack(fut_traj_all, axis=0)\t\t\n            fut_traj_valid_mask_all = np.stack(fut_traj_valid_mask_all, axis=0)\t\t\n            past_traj_all = np.stack(past_traj_all, axis=0)\t\t\n            past_traj_valid_mask_all = np.stack(past_traj_valid_mask_all, axis=0)\t\t\n        else:\t\t\n            fut_traj_all = np.zeros((0, self.predict_steps, 2))\t\t\n            fut_traj_valid_mask_all = np.zeros((0, self.predict_steps, 2))\t\t\n            past_traj_all = np.zeros((0, self.predict_steps, 2))\t\t\n            past_traj_valid_mask_all = np.zeros((0, self.predict_steps, 2))\t\t\n        return fut_traj_all, fut_traj_valid_mask_all, past_traj_all, past_traj_valid_mask_all\n\n    def get_vel_transform_mats(self, sample):\n        sd_rec = self.nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        cs_record = self.nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = self.nusc.get('ego_pose', sd_rec['ego_pose_token'])\n\n        l2e_r = cs_record['rotation']\n        l2e_t = cs_record['translation']\n        e2g_r = pose_record['rotation']\n        e2g_t = pose_record['translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        return l2e_r_mat, e2g_r_mat\n\n    def get_vel_and_time(self, sample):\n        lidar_token = sample['data']['LIDAR_TOP']\n        lidar_top = self.nusc.get('sample_data', lidar_token)\n        pose = self.nusc.get('ego_pose', lidar_top['ego_pose_token'])\n        xyz = pose['translation']\n        timestamp = sample['timestamp']\n        return xyz, timestamp\n        \n    def prepare_sdc_vel_info(self):\n        # generate sdc velocity info for all samples\n        # Note that these velocity values are converted from \n        # global frame to lidar frame\n        # as aligned with bbox gts\n\n        self.sdc_vel_info = {}\n        for scene in self.nusc.scene:\n            scene_token = scene['token']\n\n            # we cannot infer vel for the last sample, therefore we skip it\n            last_sample_token = scene['last_sample_token']\n            sample_token = scene['first_sample_token']\n            sample = self.nusc.get('sample', sample_token)\n            xyz, time = self.get_vel_and_time(sample)\n            while sample['token'] != last_sample_token:\n                next_sample_token = sample['next']\n                next_sample = self.nusc.get('sample', next_sample_token)\n                next_xyz, next_time = self.get_vel_and_time(next_sample)\n                dc = np.array(next_xyz) - np.array(xyz) \n                dt = (next_time - time) / 1e6\n                vel = dc/dt\n\n                # global frame to lidar frame\n                l2e_r_mat, e2g_r_mat = self.get_vel_transform_mats(sample)\n                vel = vel @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                vel = vel[:2]\n\n                self.sdc_vel_info[sample['token']] = vel\n                xyz, time = next_xyz, next_time\n                sample = next_sample\n\n            # set first sample's vel equal to second sample's\n            last_sample = self.nusc.get('sample', last_sample_token)\n            second_last_sample_token = last_sample['prev']\n            self.sdc_vel_info[last_sample_token] = self.sdc_vel_info[second_last_sample_token]                \n\n    def generate_sdc_info(self, sdc_vel, as_lidar_instance3d_box=False):\n        # sdc dim from https://forum.nuscenes.org/t/dimensions-of-the-ego-vehicle-used-to-gather-data/550\n        psudo_sdc_bbox = np.array([0.0, 0.0, 0.0, 1.73, 4.08, 1.56, -np.pi])\n        if self.with_velocity:\n            psudo_sdc_bbox = np.concatenate([psudo_sdc_bbox, sdc_vel], axis=-1)\n        gt_bboxes_3d = np.array([psudo_sdc_bbox]).astype(np.float32)\n        gt_names_3d = ['car']\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        # the nuscenes box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        \n        if as_lidar_instance3d_box:\n            # if we do not want the batch the box in to DataContrainer\n            return gt_bboxes_3d\n\n        gt_labels_3d = DC(to_tensor(gt_labels_3d))\n        gt_bboxes_3d = DC(gt_bboxes_3d, cpu_only=True)\n\n        return gt_bboxes_3d, gt_labels_3d\n\n    def get_sdc_traj_label(self, sample_token):\n        sd_rec = self.nusc.get('sample', sample_token)\n        lidar_top_data_start = self.nusc.get('sample_data', sd_rec['data']['LIDAR_TOP'])\n        ego_pose_start = self.nusc.get('ego_pose', lidar_top_data_start['ego_pose_token'])\n\n        sdc_fut_traj = []\n        for _ in range(self.predict_steps):\n            next_annotation_token = sd_rec['next']\n            if next_annotation_token=='':\n                break\n            sd_rec = self.nusc.get('sample', next_annotation_token)\n            lidar_top_data_next = self.nusc.get('sample_data', sd_rec['data']['LIDAR_TOP'])\n            ego_pose_next = self.nusc.get('ego_pose', lidar_top_data_next['ego_pose_token'])\n            sdc_fut_traj.append(ego_pose_next['translation'][:2])  # global xy pos of sdc at future step i\n        \n        sdc_fut_traj_all = np.zeros((1, self.predict_steps, 2))\n        sdc_fut_traj_valid_mask_all = np.zeros((1, self.predict_steps, 2))\n        n_valid_timestep = len(sdc_fut_traj)\n        if n_valid_timestep>0:\n            sdc_fut_traj = np.stack(sdc_fut_traj, axis=0)  #(t,2)\n            sdc_fut_traj = convert_global_coords_to_local(\n                coordinates=sdc_fut_traj,\n                translation=ego_pose_start['translation'],\n                rotation=ego_pose_start['rotation'],\n            )\n            sdc_fut_traj_all[:,:n_valid_timestep,:] = sdc_fut_traj\n            sdc_fut_traj_valid_mask_all[:,:n_valid_timestep,:] = 1\n\n        return sdc_fut_traj_all, sdc_fut_traj_valid_mask_all\n    \n    def get_l2g_transform(self, sample):\n        sd_rec = self.nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        cs_record = self.nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = self.nusc.get('ego_pose', sd_rec['ego_pose_token'])\n\n        l2e_r = cs_record['rotation']\n        l2e_t = np.array(cs_record['translation'])\n        e2g_r = pose_record['rotation']\n        e2g_t = np.array(pose_record['translation'])\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        return l2e_r_mat, l2e_t, e2g_r_mat, e2g_t\n\n    def get_sdc_planning_label(self, sample_token):\n        sd_rec = self.nusc.get('sample', sample_token)\n        l2e_r_mat_init, l2e_t_init, e2g_r_mat_init, e2g_t_init = self.get_l2g_transform(sd_rec)\n        \n\n        planning = []\n        for _ in range(self.planning_steps):\n            next_annotation_token = sd_rec['next']\n            if next_annotation_token=='':\n                break\n            sd_rec = self.nusc.get('sample', next_annotation_token)\n            l2e_r_mat_curr, l2e_t_curr, e2g_r_mat_curr, e2g_t_curr = self.get_l2g_transform(sd_rec)  # (lidar to global at current frame)\n            \n            # bbox of sdc under current lidar frame\n            next_bbox3d = self.generate_sdc_info(self.sdc_vel_info[next_annotation_token], as_lidar_instance3d_box=True)\n\n            # to bbox under curr ego frame\n            next_bbox3d.rotate(l2e_r_mat_curr.T)\n            next_bbox3d.translate(l2e_t_curr)\n\n            # to bbox under world frame\n            next_bbox3d.rotate(e2g_r_mat_curr.T)\n            next_bbox3d.translate(e2g_t_curr)\n\n            # to bbox under initial ego frame, first inverse translate, then inverse rotate \n            next_bbox3d.translate(- e2g_t_init)\n            m1 = np.linalg.inv(e2g_r_mat_init)\n            next_bbox3d.rotate(m1.T)\n\n            # to bbox under curr ego frame, first inverse translate, then inverse rotate\n            next_bbox3d.translate(- l2e_t_init)\n            m2 = np.linalg.inv(l2e_r_mat_init)\n            next_bbox3d.rotate(m2.T)\n            \n            planning.append(next_bbox3d)\n\n        planning_all = np.zeros((1, self.planning_steps, 3))\n        planning_mask_all = np.zeros((1, self.planning_steps, 2))\n        n_valid_timestep = len(planning)\n        if n_valid_timestep>0:\n            planning = [p.tensor.squeeze(0) for p in planning]\n            planning = np.stack(planning, axis=0)  # (valid_t, 9)\n            planning = planning[:, [0,1,6]]  # (x, y, yaw)\n            planning_all[:,:n_valid_timestep,:] = planning\n            planning_mask_all[:,:n_valid_timestep,:] = 1\n\n        mask = planning_mask_all[0].any(axis=1)\n        if mask.sum() == 0:\n            command = 2 #'FORWARD'\n        elif planning_all[0, mask][-1][0] >= 2:\n            command = 0 #'RIGHT' \n        elif planning_all[0, mask][-1][0] <= -2:\n            command = 1 #'LEFT'\n        else:\n            command = 2 #'FORWARD'\n        \n        return planning_all, planning_mask_all, command"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/data_utils/vector_map.py",
    "content": "import numpy as np\nfrom nuscenes.map_expansion.map_api import NuScenesMap, NuScenesMapExplorer\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom shapely import affinity, ops\nfrom shapely.geometry import LineString, box, MultiPolygon, MultiLineString\n\nCLASS2LABEL = {\n    'road_divider': 0,\n    'lane_divider': 0,\n    'ped_crossing': 1,\n    'contours': 2,\n    'others': -1\n}\n\nclass VectorizedLocalMap(object):\n    def __init__(self,\n                 dataroot,\n                 patch_size,\n                 canvas_size,\n                 line_classes=['road_divider', 'lane_divider'],\n                 ped_crossing_classes=['ped_crossing'],\n                 contour_classes=['road_segment', 'lane'],\n                 sample_dist=1,\n                 num_samples=250,\n                 padding=False,\n                 normalize=False,\n                 fixed_num=-1):\n        '''\n        Args:\n            fixed_num = -1 : no fixed num\n        '''\n        super().__init__()\n        self.data_root = dataroot\n        self.MAPS = ['boston-seaport', 'singapore-hollandvillage',\n                     'singapore-onenorth', 'singapore-queenstown']\n        self.line_classes = line_classes\n        self.ped_crossing_classes = ped_crossing_classes\n        self.polygon_classes = contour_classes\n        self.nusc_maps = {}\n        self.map_explorer = {}\n        for loc in self.MAPS:\n            self.nusc_maps[loc] = NuScenesMap(dataroot=self.data_root, map_name=loc)\n            self.map_explorer[loc] = NuScenesMapExplorer(self.nusc_maps[loc])\n\n        self.patch_size = patch_size\n        self.canvas_size = canvas_size\n        self.sample_dist = sample_dist\n        self.num_samples = num_samples\n        self.padding = padding\n        self.normalize = normalize\n        self.fixed_num = fixed_num\n\n    def gen_vectorized_samples(self, location, ego2global_translation, ego2global_rotation):\n        map_pose = ego2global_translation[:2]\n        rotation = Quaternion(ego2global_rotation)\n\n        patch_box = (map_pose[0], map_pose[1], self.patch_size[0], self.patch_size[1])\n        patch_angle = quaternion_yaw(rotation) / np.pi * 180\n\n        line_geom = self.get_map_geom(patch_box, patch_angle, self.line_classes, location)\n        line_vector_dict = self.line_geoms_to_vectors(line_geom)\n\n        ped_geom = self.get_map_geom(patch_box, patch_angle, self.ped_crossing_classes, location)\n        # ped_vector_list = self.ped_geoms_to_vectors(ped_geom)\n        ped_vector_list = self.line_geoms_to_vectors(ped_geom)['ped_crossing']\n\n        polygon_geom = self.get_map_geom(patch_box, patch_angle, self.polygon_classes, location)\n        poly_bound_list = self.poly_geoms_to_vectors(polygon_geom)\n\n        vectors = []\n        for line_type, vects in line_vector_dict.items():\n            for line, length in vects:\n                vectors.append((line.astype(float), length, CLASS2LABEL.get(line_type, -1)))\n\n        for ped_line, length in ped_vector_list:\n            vectors.append((ped_line.astype(float), length, CLASS2LABEL.get('ped_crossing', -1)))\n\n        for contour, length in poly_bound_list:\n            vectors.append((contour.astype(float), length, CLASS2LABEL.get('contours', -1)))\n\n        # filter out -1\n        filtered_vectors = []\n        for pts, pts_num, type in vectors:\n            if type != -1:\n                filtered_vectors.append({\n                    'pts': pts,\n                    'pts_num': pts_num,\n                    'type': type\n                })\n\n        return filtered_vectors\n\n    def get_map_geom(self, patch_box, patch_angle, layer_names, location):\n        map_geom = []\n        for layer_name in layer_names:\n            if layer_name in self.line_classes:\n                geoms = self.map_explorer[location]._get_layer_line(patch_box, patch_angle, layer_name)\n                map_geom.append((layer_name, geoms))\n            elif layer_name in self.polygon_classes:\n                geoms = self.map_explorer[location]._get_layer_polygon(patch_box, patch_angle, layer_name)\n                map_geom.append((layer_name, geoms))\n            elif layer_name in self.ped_crossing_classes:\n                geoms = self.get_ped_crossing_line(patch_box, patch_angle, location)\n                # geoms = self.map_explorer[location]._get_layer_polygon(patch_box, patch_angle, layer_name)\n                map_geom.append((layer_name, geoms))\n        return map_geom\n\n    def _one_type_line_geom_to_vectors(self, line_geom):\n        line_vectors = []\n        for line in line_geom:\n            if not line.is_empty:\n                if line.geom_type == 'MultiLineString':\n                    for single_line in line.geoms:\n                        line_vectors.append(self.sample_pts_from_line(single_line))\n                elif line.geom_type == 'LineString':\n                    line_vectors.append(self.sample_pts_from_line(line))\n                else:\n                    raise NotImplementedError\n        return line_vectors\n\n    def poly_geoms_to_vectors(self, polygon_geom):\n        roads = polygon_geom[0][1]\n        lanes = polygon_geom[1][1]\n        union_roads = ops.unary_union(roads)\n        union_lanes = ops.unary_union(lanes)\n        union_segments = ops.unary_union([union_roads, union_lanes])\n        max_x = self.patch_size[1] / 2\n        max_y = self.patch_size[0] / 2\n        local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n        exteriors = []\n        interiors = []\n        if union_segments.geom_type != 'MultiPolygon':\n            union_segments = MultiPolygon([union_segments])\n        for poly in union_segments.geoms:\n            exteriors.append(poly.exterior)\n            for inter in poly.interiors:\n                interiors.append(inter)\n\n        results = []\n        for ext in exteriors:\n            if ext.is_ccw:\n                ext.coords = list(ext.coords)[::-1]\n            lines = ext.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        for inter in interiors:\n            if not inter.is_ccw:\n                inter.coords = list(inter.coords)[::-1]\n            lines = inter.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        return self._one_type_line_geom_to_vectors(results)\n\n    def line_geoms_to_vectors(self, line_geom):\n        line_vectors_dict = dict()\n        for line_type, a_type_of_lines in line_geom:\n            one_type_vectors = self._one_type_line_geom_to_vectors(a_type_of_lines)\n            line_vectors_dict[line_type] = one_type_vectors\n\n        return line_vectors_dict\n\n    def ped_geoms_to_vectors(self, ped_geom):\n        ped_geom = ped_geom[0][1]\n        union_ped = ops.unary_union(ped_geom)\n        if union_ped.geom_type != 'MultiPolygon':\n            union_ped = MultiPolygon([union_ped])\n\n        max_x = self.patch_size[1] / 2\n        max_y = self.patch_size[0] / 2\n        local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n        results = []\n        for ped_poly in union_ped:\n            # rect = ped_poly.minimum_rotated_rectangle\n            ext = ped_poly.exterior\n            if not ext.is_ccw:\n                ext.coords = list(ext.coords)[::-1]\n            lines = ext.intersection(local_patch)\n            results.append(lines)\n\n        return self._one_type_line_geom_to_vectors(results)\n\n    def get_ped_crossing_line(self, patch_box, patch_angle, location):\n        def add_line(poly_xy, idx, patch, patch_angle, patch_x, patch_y, line_list):\n            points = [(p0, p1) for p0, p1 in zip(poly_xy[0, idx:idx + 2], poly_xy[1, idx:idx + 2])]\n            line = LineString(points)\n            line = line.intersection(patch)\n            if not line.is_empty:\n                line = affinity.rotate(line, -patch_angle, origin=(patch_x, patch_y), use_radians=False)\n                line = affinity.affine_transform(line, [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                line_list.append(line)\n\n        patch_x = patch_box[0]\n        patch_y = patch_box[1]\n\n        patch = NuScenesMapExplorer.get_patch_coord(patch_box, patch_angle)\n        line_list = []\n        records = getattr(self.nusc_maps[location], 'ped_crossing')\n        for record in records:\n            polygon = self.map_explorer[location].extract_polygon(record['polygon_token'])\n            poly_xy = np.array(polygon.exterior.xy)\n            dist = np.square(poly_xy[:, 1:] - poly_xy[:, :-1]).sum(0)\n            x1, x2 = np.argsort(dist)[-2:]\n\n            add_line(poly_xy, x1, patch, patch_angle, patch_x, patch_y, line_list)\n            add_line(poly_xy, x2, patch, patch_angle, patch_x, patch_y, line_list)\n\n        return line_list\n\n    def sample_pts_from_line(self, line):\n        if self.fixed_num < 0:\n            distances = np.arange(0, line.length, self.sample_dist)\n            sampled_points = np.array([list(line.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n        else:\n            # fixed number of points, so distance is line.length / self.fixed_num\n            distances = np.linspace(0, line.length, self.fixed_num)\n            sampled_points = np.array([list(line.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n\n        if self.normalize:\n            sampled_points = sampled_points / np.array([self.patch_size[1], self.patch_size[0]])\n\n        num_valid = len(sampled_points)\n\n        if not self.padding or self.fixed_num > 0:\n            # fixed num sample can return now!\n            return sampled_points, num_valid\n\n        # fixed distance sampling need padding!\n        num_valid = len(sampled_points)\n\n        if self.fixed_num < 0:\n            if num_valid < self.num_samples:\n                padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            else:\n                sampled_points = sampled_points[:self.num_samples, :]\n                num_valid = self.num_samples\n\n            if self.normalize:\n                sampled_points = sampled_points / np.array([self.patch_size[1], self.patch_size[0]])\n                num_valid = len(sampled_points)\n\n        return sampled_points, num_valid\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/dataset_wrappers.py",
    "content": "import bisect\nimport math\nfrom collections import defaultdict\n\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom torch.utils.data.dataset import ConcatDataset as _ConcatDataset\n\nfrom .builder import DATASETS\nfrom .coco import CocoDataset\n\n\n@DATASETS.register_module()\nclass ConcatDataset(_ConcatDataset):\n    \"\"\"A wrapper of concatenated dataset.\n\n    Same as :obj:`torch.utils.data.dataset.ConcatDataset`, but\n    concat the group flag for image aspect ratio.\n\n    Args:\n        datasets (list[:obj:`Dataset`]): A list of datasets.\n        separate_eval (bool): Whether to evaluate the results\n            separately if it is used as validation dataset.\n            Defaults to True.\n    \"\"\"\n\n    def __init__(self, datasets, separate_eval=True):\n        super(ConcatDataset, self).__init__(datasets)\n        self.CLASSES = datasets[0].CLASSES\n        self.separate_eval = separate_eval\n        if not separate_eval:\n            if any([isinstance(ds, CocoDataset) for ds in datasets]):\n                raise NotImplementedError(\n                    'Evaluating concatenated CocoDataset as a whole is not'\n                    ' supported! Please set \"separate_eval=True\"')\n            elif len(set([type(ds) for ds in datasets])) != 1:\n                raise NotImplementedError(\n                    'All the datasets should have same types')\n\n        if hasattr(datasets[0], 'flag'):\n            flags = []\n            for i in range(0, len(datasets)):\n                flags.append(datasets[i].flag)\n            self.flag = np.concatenate(flags)\n\n    def get_cat_ids(self, idx):\n        \"\"\"Get category ids of concatenated dataset by index.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            list[int]: All categories in the image of specified index.\n        \"\"\"\n\n        if idx < 0:\n            if -idx > len(self):\n                raise ValueError(\n                    'absolute value of index should not exceed dataset length')\n            idx = len(self) + idx\n        dataset_idx = bisect.bisect_right(self.cumulative_sizes, idx)\n        if dataset_idx == 0:\n            sample_idx = idx\n        else:\n            sample_idx = idx - self.cumulative_sizes[dataset_idx - 1]\n        return self.datasets[dataset_idx].get_cat_ids(sample_idx)\n\n    def evaluate(self, results, logger=None, **kwargs):\n        \"\"\"Evaluate the results.\n\n        Args:\n            results (list[list | tuple]): Testing results of the dataset.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n\n        Returns:\n            dict[str: float]: AP results of the total dataset or each separate\n            dataset if `self.separate_eval=True`.\n        \"\"\"\n        assert len(results) == self.cumulative_sizes[-1], \\\n            ('Dataset and results have different sizes: '\n             f'{self.cumulative_sizes[-1]} v.s. {len(results)}')\n\n        # Check whether all the datasets support evaluation\n        for dataset in self.datasets:\n            assert hasattr(dataset, 'evaluate'), \\\n                    f'{type(dataset)} does not implement evaluate function'\n\n        if self.separate_eval:\n            dataset_idx = -1\n            total_eval_results = dict()\n            for size, dataset in zip(self.cumulative_sizes, self.datasets):\n                start_idx = 0 if dataset_idx == -1 else \\\n                    self.cumulative_sizes[dataset_idx]\n                end_idx = self.cumulative_sizes[dataset_idx + 1]\n\n                results_per_dataset = results[start_idx:end_idx]\n                print_log(\n                    f'\\nEvaluateing {dataset.ann_file} with '\n                    f'{len(results_per_dataset)} images now',\n                    logger=logger)\n\n                eval_results_per_dataset = dataset.evaluate(\n                    results_per_dataset, logger=logger, **kwargs)\n                dataset_idx += 1\n                for k, v in eval_results_per_dataset.items():\n                    total_eval_results.update({f'{dataset_idx}_{k}': v})\n\n            return total_eval_results\n        elif any([isinstance(ds, CocoDataset) for ds in self.datasets]):\n            raise NotImplementedError(\n                'Evaluating concatenated CocoDataset as a whole is not'\n                ' supported! Please set \"separate_eval=True\"')\n        elif len(set([type(ds) for ds in self.datasets])) != 1:\n            raise NotImplementedError(\n                'All the datasets should have same types')\n        else:\n            original_data_infos = self.datasets[0].data_infos\n            self.datasets[0].data_infos = sum(\n                [dataset.data_infos for dataset in self.datasets], [])\n            eval_results = self.datasets[0].evaluate(\n                results, logger=logger, **kwargs)\n            self.datasets[0].data_infos = original_data_infos\n            return eval_results\n\n\n@DATASETS.register_module()\nclass RepeatDataset:\n    \"\"\"A wrapper of repeated dataset.\n\n    The length of repeated dataset will be `times` larger than the original\n    dataset. This is useful when the data loading time is long but the dataset\n    is small. Using RepeatDataset can reduce the data loading time between\n    epochs.\n\n    Args:\n        dataset (:obj:`Dataset`): The dataset to be repeated.\n        times (int): Repeat times.\n    \"\"\"\n\n    def __init__(self, dataset, times):\n        self.dataset = dataset\n        self.times = times\n        self.CLASSES = dataset.CLASSES\n        if hasattr(self.dataset, 'flag'):\n            self.flag = np.tile(self.dataset.flag, times)\n\n        self._ori_len = len(self.dataset)\n\n    def __getitem__(self, idx):\n        return self.dataset[idx % self._ori_len]\n\n    def get_cat_ids(self, idx):\n        \"\"\"Get category ids of repeat dataset by index.\n\n        Args:\n            idx (int): Index of data.\n\n        Returns:\n            list[int]: All categories in the image of specified index.\n        \"\"\"\n\n        return self.dataset.get_cat_ids(idx % self._ori_len)\n\n    def __len__(self):\n        \"\"\"Length after repetition.\"\"\"\n        return self.times * self._ori_len\n\n\n# Modified from https://github.com/facebookresearch/detectron2/blob/41d475b75a230221e21d9cac5d69655e3415e3a4/detectron2/data/samplers/distributed_sampler.py#L57 # noqa\n@DATASETS.register_module()\nclass ClassBalancedDataset:\n    \"\"\"A wrapper of repeated dataset with repeat factor.\n\n    Suitable for training on class imbalanced datasets like LVIS. Following\n    the sampling strategy in the `paper <https://arxiv.org/abs/1908.03195>`_,\n    in each epoch, an image may appear multiple times based on its\n    \"repeat factor\".\n    The repeat factor for an image is a function of the frequency the rarest\n    category labeled in that image. The \"frequency of category c\" in [0, 1]\n    is defined by the fraction of images in the training set (without repeats)\n    in which category c appears.\n    The dataset needs to instantiate :func:`self.get_cat_ids` to support\n    ClassBalancedDataset.\n\n    The repeat factor is computed as followed.\n\n    1. For each category c, compute the fraction # of images\n       that contain it: :math:`f(c)`\n    2. For each category c, compute the category-level repeat factor:\n       :math:`r(c) = max(1, sqrt(t/f(c)))`\n    3. For each image I, compute the image-level repeat factor:\n       :math:`r(I) = max_{c in I} r(c)`\n\n    Args:\n        dataset (:obj:`CustomDataset`): The dataset to be repeated.\n        oversample_thr (float): frequency threshold below which data is\n            repeated. For categories with ``f_c >= oversample_thr``, there is\n            no oversampling. For categories with ``f_c < oversample_thr``, the\n            degree of oversampling following the square-root inverse frequency\n            heuristic above.\n        filter_empty_gt (bool, optional): If set true, images without bounding\n            boxes will not be oversampled. Otherwise, they will be categorized\n            as the pure background class and involved into the oversampling.\n            Default: True.\n    \"\"\"\n\n    def __init__(self, dataset, oversample_thr, filter_empty_gt=True):\n        self.dataset = dataset\n        self.oversample_thr = oversample_thr\n        self.filter_empty_gt = filter_empty_gt\n        self.CLASSES = dataset.CLASSES\n\n        repeat_factors = self._get_repeat_factors(dataset, oversample_thr)\n        repeat_indices = []\n        for dataset_idx, repeat_factor in enumerate(repeat_factors):\n            repeat_indices.extend([dataset_idx] * math.ceil(repeat_factor))\n        self.repeat_indices = repeat_indices\n\n        flags = []\n        if hasattr(self.dataset, 'flag'):\n            for flag, repeat_factor in zip(self.dataset.flag, repeat_factors):\n                flags.extend([flag] * int(math.ceil(repeat_factor)))\n            assert len(flags) == len(repeat_indices)\n        self.flag = np.asarray(flags, dtype=np.uint8)\n\n    def _get_repeat_factors(self, dataset, repeat_thr):\n        \"\"\"Get repeat factor for each images in the dataset.\n\n        Args:\n            dataset (:obj:`CustomDataset`): The dataset\n            repeat_thr (float): The threshold of frequency. If an image\n                contains the categories whose frequency below the threshold,\n                it would be repeated.\n\n        Returns:\n            list[float]: The repeat factors for each images in the dataset.\n        \"\"\"\n\n        # 1. For each category c, compute the fraction # of images\n        #   that contain it: f(c)\n        category_freq = defaultdict(int)\n        num_images = len(dataset)\n        for idx in range(num_images):\n            cat_ids = set(self.dataset.get_cat_ids(idx))\n            if len(cat_ids) == 0 and not self.filter_empty_gt:\n                cat_ids = set([len(self.CLASSES)])\n            for cat_id in cat_ids:\n                category_freq[cat_id] += 1\n        for k, v in category_freq.items():\n            category_freq[k] = v / num_images\n\n        # 2. For each category c, compute the category-level repeat factor:\n        #    r(c) = max(1, sqrt(t/f(c)))\n        category_repeat = {\n            cat_id: max(1.0, math.sqrt(repeat_thr / cat_freq))\n            for cat_id, cat_freq in category_freq.items()\n        }\n\n        # 3. For each image I, compute the image-level repeat factor:\n        #    r(I) = max_{c in I} r(c)\n        repeat_factors = []\n        for idx in range(num_images):\n            cat_ids = set(self.dataset.get_cat_ids(idx))\n            if len(cat_ids) == 0 and not self.filter_empty_gt:\n                cat_ids = set([len(self.CLASSES)])\n            repeat_factor = 1\n            if len(cat_ids) > 0:\n                repeat_factor = max(\n                    {category_repeat[cat_id]\n                     for cat_id in cat_ids})\n            repeat_factors.append(repeat_factor)\n\n        return repeat_factors\n\n    def __getitem__(self, idx):\n        ori_index = self.repeat_indices[idx]\n        return self.dataset[ori_index]\n\n    def __len__(self):\n        \"\"\"Length after repetition.\"\"\"\n        return len(self.repeat_indices)\n    \n@DATASETS.register_module()\nclass CBGSDataset(object):\n    \"\"\"A wrapper of class sampled dataset with ann_file path. Implementation of\n    paper `Class-balanced Grouping and Sampling for Point Cloud 3D Object\n    Detection <https://arxiv.org/abs/1908.09492.>`_.\n\n    Balance the number of scenes under different classes.\n\n    Args:\n        dataset (:obj:`CustomDataset`): The dataset to be class sampled.\n    \"\"\"\n\n    def __init__(self, dataset):\n        self.dataset = dataset\n        self.CLASSES = dataset.CLASSES\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.sample_indices = self._get_sample_indices()\n        # self.dataset.data_infos = self.data_infos\n        if hasattr(self.dataset, 'flag'):\n            self.flag = np.array(\n                [self.dataset.flag[ind] for ind in self.sample_indices],\n                dtype=np.uint8)\n\n    def _get_sample_indices(self):\n        \"\"\"Load annotations from ann_file.\n\n        Args:\n            ann_file (str): Path of the annotation file.\n\n        Returns:\n            list[dict]: List of annotations after class sampling.\n        \"\"\"\n        class_sample_idxs = {cat_id: [] for cat_id in self.cat2id.values()}\n        for idx in range(len(self.dataset)):\n            sample_cat_ids = self.dataset.get_cat_ids(idx)\n            for cat_id in sample_cat_ids:\n                class_sample_idxs[cat_id].append(idx)\n        duplicated_samples = sum(\n            [len(v) for _, v in class_sample_idxs.items()])\n        class_distribution = {\n            k: len(v) / duplicated_samples\n            for k, v in class_sample_idxs.items()\n        }\n\n        sample_indices = []\n\n        frac = 1.0 / len(self.CLASSES)\n        ratios = [frac / v for v in class_distribution.values()]\n        for cls_inds, ratio in zip(list(class_sample_idxs.values()), ratios):\n            sample_indices += np.random.choice(cls_inds,\n                                               int(len(cls_inds) *\n                                                   ratio)).tolist()\n        return sample_indices\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        ori_idx = self.sample_indices[idx]\n        return self.dataset[ori_idx]\n\n    def __len__(self):\n        \"\"\"Return the length of data infos.\n\n        Returns:\n            int: Length of data infos.\n        \"\"\"\n        return len(self.sample_indices)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/dd3d_nuscenes_dataset.py",
    "content": "# Copyright 2021 Toyota Research Institute.  All rights reserved.\n#import functools\nfrom collections import OrderedDict\n\nimport numpy as np\nimport seaborn as sns\nfrom torch.utils.data import Dataset\nfrom tqdm import tqdm\n\nfrom mmcv.structures import BoxMode\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.utils.splits import create_splits_scenes\n\n#from tridet.data import collect_dataset_dicts\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.boxes3d import GenericBoxes3D\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.structures.pose import Pose\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.geometry import project_points3d\nfrom adzoo.bevformer.mmdet3d_plugin.dd3d.utils.visualization import float_to_uint8_color\n\n#  https://github.com/nutonomy/nuscenes-devkit/blob/9b209638ef3dee6d0cdc5ac700c493747f5b35fe/python-sdk/nuscenes/utils/splits.py#L189\n#     - train/val/test: The standard splits of the nuScenes dataset (700/150/150 scenes).\n#     - mini_train/mini_val: Train and val splits of the mini subset used for visualization and debugging (8/2 scenes).\n#     - train_detect/train_track: Two halves of the train split used for separating the training sets of detector and\n#         tracker if required\nDATASET_NAME_TO_VERSION = {\n    \"nusc_train\": \"v1.0-trainval\",\n    \"nusc_val\": \"v1.0-trainval\",\n    \"nusc_val-subsample-8\": \"v1.0-trainval\",\n    \"nusc_trainval\": \"v1.0-trainval\",\n    \"nusc_test\": \"v1.0-test\",\n    \"nusc_mini_train\": \"v1.0-mini\",\n    \"nusc_mini_val\": \"v1.0-mini\",\n}\n\nCAMERA_NAMES = ('CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT')\n\nATTRIBUTE_IDS = {\n    'vehicle.moving': 0,\n    'vehicle.parked': 1,\n    'vehicle.stopped': 2,\n    'pedestrian.moving': 0,\n    'pedestrian.standing': 1,\n    'pedestrian.sitting_lying_down': 2,\n    'cycle.with_rider': 0,\n    'cycle.without_rider': 1,\n}\n\nCATEGORY_IDS = OrderedDict({\n    'barrier': 0,\n    'bicycle': 1,\n    'bus': 2,\n    'car': 3,\n    'construction_vehicle': 4,\n    'motorcycle': 5,\n    'pedestrian': 6,\n    'traffic_cone': 7,\n    'trailer': 8,\n    'truck': 9,\n})\n\nCOLORS = [float_to_uint8_color(clr) for clr in sns.color_palette(\"bright\", n_colors=10)]\nCOLORMAP = OrderedDict({\n    'barrier': COLORS[8],  # yellow\n    'bicycle': COLORS[0],  # blue\n    'bus': COLORS[6],  # pink\n    'car': COLORS[2],  # green\n    'construction_vehicle': COLORS[7],  # gray\n    'motorcycle': COLORS[4],  # purple\n    'pedestrian': COLORS[1],  # orange\n    'traffic_cone': COLORS[3],  # red\n    'trailer': COLORS[9],  # skyblue\n    'truck': COLORS[5],  # brown\n})\n\nMAX_NUM_ATTRIBUTES = 3\n\n\ndef _compute_iou(box1, box2):\n    \"\"\"\n    Parameters\n    ----------\n    box1, box2:\n        (x1, y1, x2, y2)\n    \"\"\"\n    xx1 = max(box1[0], box2[0])\n    yy1 = max(box1[1], box2[1])\n    xx2 = min(box1[2], box2[2])\n    yy2 = min(box1[3], box2[3])\n    if xx1 >= xx2 or yy1 >= yy2:\n        return 0.\n    inter = (xx2 - xx1) * (yy2 - yy1)\n    a1 = (box1[2] - box1[0]) * (box1[3] - box1[1])\n    a2 = (box2[2] - box2[0]) * (box2[3] - box2[1])\n    return inter / (a1 + a2 - inter)\n\n\nclass DD3DNuscenesDataset(Dataset):\n    def __init__(self, name, data_root, datum_names=CAMERA_NAMES, min_num_lidar_points=3, min_box_visibility=0.2, **unused):\n        self.data_root = data_root\n        assert name in DATASET_NAME_TO_VERSION\n        version = DATASET_NAME_TO_VERSION[name]\n        self.nusc = NuScenes(version=version, dataroot=data_root, verbose=True)\n\n        self.datum_names = datum_names\n        self.min_num_lidar_points = min_num_lidar_points\n        self.min_box_visibility = min_box_visibility\n\n        self.dataset_item_info = self._build_dataset_item_info(name)\n\n        # Index instance tokens to their IDs\n        self._instance_token_to_id = self._index_instance_tokens()\n\n        # Construct the mapping from datum_token (image id) to index\n        print(\"Generating the mapping from image id to idx...\")\n        self.datumtoken2idx = {}\n        for idx, (datum_token, _, _, _, _) in enumerate(self.dataset_item_info):\n            self.datumtoken2idx[datum_token] = idx\n        print(\"Done.\")\n\n    def _build_dataset_item_info(self, name):\n        scenes_in_split = self._get_split_scenes(name)\n\n        dataset_items = []\n        for _, scene_token in tqdm(scenes_in_split):\n            scene = self.nusc.get('scene', scene_token)\n            sample_token = scene['first_sample_token']\n            for sample_idx in range(scene['nbr_samples']):\n                if name.endswith('subsample-8') and sample_idx % 8 > 0:\n                    # Sample-level subsampling.\n                    continue\n\n                sample = self.nusc.get('sample', sample_token)\n                for datum_name, datum_token in sample['data'].items():\n                    if datum_name not in self.datum_names:\n                        continue\n                    dataset_items.append((datum_token, sample_token, scene['name'], sample_idx, datum_name))\n                sample_token = sample['next']\n        return dataset_items\n\n    def _get_split_scenes(self, name):\n        scenes_in_splits = create_splits_scenes()\n        if name == \"nusc_trainval\":\n            scenes = scenes_in_splits[\"train\"] + scenes_in_splits[\"val\"]\n        elif name == \"nusc_val-subsample-8\":\n            scenes = scenes_in_splits[\"val\"]\n        else:\n            assert name.startswith('nusc_'), f\"Invalid dataset name: {name}\"\n            split = name[5:]\n            assert split in scenes_in_splits, f\"Invalid dataset: {split}\"\n            scenes = scenes_in_splits[split]\n\n        # Mapping from scene name to token.\n        name_to_token = {scene['name']: scene['token'] for scene in self.nusc.scene}\n        return [(name, name_to_token[name]) for name in scenes]\n\n    def __len__(self):\n        return len(self.dataset_item_info)\n\n    def _build_id(self, scene_name, sample_idx, datum_name):\n        sample_id = f\"{scene_name}_{sample_idx:03d}\"\n        image_id = f\"{sample_id}_{datum_name}\"\n        return image_id, sample_id\n\n    def _index_instance_tokens(self):\n        \"\"\"Index instance tokens for uniquely identifying instances across samples\"\"\"\n        instance_token_to_id = {}\n        for record in self.nusc.sample_annotation:\n            instance_token = record['instance_token']\n            if instance_token not in instance_token_to_id:\n                next_instance_id = len(instance_token_to_id)\n                instance_token_to_id[instance_token] = next_instance_id\n        return instance_token_to_id\n\n    def get_instance_annotations(self, annotation_list, K, image_shape, pose_WS):\n        annotations = []\n        for _ann in annotation_list:\n            ann = self.nusc.get('sample_annotation', _ann.token)\n            if ann['num_lidar_pts'] + ann['num_radar_pts'] < self.min_num_lidar_points:\n                continue\n            annotation = OrderedDict()\n\n            # --------\n            # Category\n            # --------\n            category = category_to_detection_name(ann['category_name'])\n            if category is None:\n                continue\n            annotation['category_id'] = CATEGORY_IDS[category]\n\n            # ------\n            # 3D box\n            # ------\n            # NOTE: ann['rotation'], ann['translation'] is in global frame.\n            pose_SO = Pose(wxyz=_ann.orientation, tvec=_ann.center)  # pose in sensor frame\n            # DEBUG:\n            # pose_WO_1 = Pose(np.array(ann['rotation']), np.array(ann['translation']))\n            # pose_WO_2 = pose_WS * pose_SO\n            # assert np.allclose(pose_WO_1.matrix, pose_WO_2.matrix)\n            bbox3d = GenericBoxes3D(_ann.orientation, _ann.center, _ann.wlh)\n            annotation['bbox3d'] = bbox3d.vectorize().tolist()[0]\n\n            # --------------------------------------\n            # 2D box -- project 8 corners of 3D bbox\n            # --------------------------------------\n            corners = project_points3d(bbox3d.corners.cpu().numpy().squeeze(0), K)\n            l, t = corners[:, 0].min(), corners[:, 1].min()\n            r, b = corners[:, 0].max(), corners[:, 1].max()\n\n            x1 = max(0, l)\n            y1 = max(0, t)\n            x2 = min(image_shape[1], r)\n            y2 = min(image_shape[0], b)\n\n            iou = _compute_iou([l, t, r, b], [x1, y1, x2, y2])\n            if iou < self.min_box_visibility:\n                continue\n\n            annotation['bbox'] = [x1, y1, x2, y2]\n            annotation['bbox_mode'] = BoxMode.XYXY_ABS\n\n            # --------\n            # Track ID\n            # --------\n            annotation['track_id'] = self._instance_token_to_id[ann['instance_token']]\n\n            # ---------\n            # Attribute\n            # ---------\n            attr_tokens = ann['attribute_tokens']\n            assert len(attr_tokens) < 2  # NOTE: Allow only single attrubute.\n            attribute_id = MAX_NUM_ATTRIBUTES  # By default, MAX_NUM_ATTRIBUTES -- this is to be ignored in loss compute.\n            if attr_tokens:\n                attribute = self.nusc.get('attribute', attr_tokens[0])['name']\n                attribute_id = ATTRIBUTE_IDS[attribute]\n            annotation['attribute_id'] = attribute_id\n\n            # -----\n            # Speed\n            # -----\n            vel_global = self.nusc.box_velocity(ann['token'])\n            speed = np.linalg.norm(vel_global)  # NOTE: This can be NaN.\n            # DEBUG:\n            # speed * Quaternion(ann['rotation']).rotation_matrix.T[0] ~= vel_global\n            annotation['speed'] = speed\n\n            annotations.append(annotation)\n\n        return annotations\n\n    def _get_ego_velocity(self, current, max_time_diff=1.5):\n        \"\"\"Velocity of ego-vehicle in m/s.\n        \"\"\"\n        has_prev = current['prev'] != ''\n        has_next = current['next'] != ''\n\n        # Cannot estimate velocity for a single annotation.\n        if not has_prev and not has_next:\n            return np.array([np.nan, np.nan, np.nan])\n\n        if has_prev:\n            first = self.nusc.get('sample_data', current['prev'])\n        else:\n            first = current\n\n        if has_next:\n            last = self.nusc.get('sample_data', current['next'])\n        else:\n            last = current\n\n        pos_first = self.nusc.get('ego_pose', first['ego_pose_token'])['translation']\n        pos_last = self.nusc.get('ego_pose', last['ego_pose_token'])['translation']\n        pos_diff = np.float32(pos_last) - np.float32(pos_first)\n\n        time_last = 1e-6 * last['timestamp']\n        time_first = 1e-6 * first['timestamp']\n        time_diff = time_last - time_first\n\n        if has_next and has_prev:\n            # If doing centered difference, allow for up to double the max_time_diff.\n            max_time_diff *= 2\n\n        if time_diff > max_time_diff:\n            # If time_diff is too big, don't return an estimate.\n            return np.array([np.nan, np.nan, np.nan])\n        else:\n            return pos_diff / time_diff\n\n    def __getitem__(self, idx):\n        datum_token, sample_token, scene_name, sample_idx, datum_name = self.dataset_item_info[idx]\n        datum = self.nusc.get('sample_data', datum_token)\n        assert datum['is_key_frame']\n\n        filename, _annotations, K = self.nusc.get_sample_data(datum_token)\n        image_id, sample_id = self._build_id(scene_name, sample_idx, datum_name)\n        height, width = datum['height'], datum['width']\n        d2_dict = OrderedDict(\n            file_name=filename,\n            height=height,\n            width=width,\n            image_id=image_id,\n            sample_id=sample_id,\n            sample_token=sample_token\n        )\n\n        # Intrinsics\n        d2_dict['intrinsics'] = list(K.flatten())\n\n        # Get pose of the sensor (S) from vehicle (V) frame\n        _pose_VS = self.nusc.get('calibrated_sensor', datum['calibrated_sensor_token'])\n        pose_VS = Pose(wxyz=np.float64(_pose_VS['rotation']), tvec=np.float64(_pose_VS['translation']))\n\n        # Get ego-pose of the vehicle (V) from global/world (W) frame\n        _pose_WV = self.nusc.get('ego_pose', datum['ego_pose_token'])\n        pose_WV = Pose(wxyz=np.float64(_pose_WV['rotation']), tvec=np.float64(_pose_WV['translation']))\n        pose_WS = pose_WV * pose_VS\n\n        d2_dict['pose'] = {'wxyz': list(pose_WS.quat.elements), 'tvec': list(pose_WS.tvec)}\n        d2_dict['extrinsics'] = {'wxyz': list(pose_VS.quat.elements), 'tvec': list(pose_VS.tvec)}\n\n        d2_dict['ego_speed'] = np.linalg.norm(self._get_ego_velocity(datum))\n\n        d2_dict['annotations'] = self.get_instance_annotations(_annotations, K, (height, width), pose_WS)\n\n        return d2_dict\n\n    def getitem_by_datumtoken(self, datum_token):\n        # idx = self.datumtoken2idx[datum_token]\n        # ret = self.__getitem__(idx)\n\n        datum = self.nusc.get('sample_data', datum_token)\n        sample_token = datum['sample_token']\n        filename, _annotations, K = self.nusc.get_sample_data(datum_token)\n        height, width = datum['height'], datum['width']\n        d2_dict = OrderedDict(\n            file_name=filename,\n            height=height,\n            width=width,\n            image_id=0,\n            sample_id=0,\n            sample_token=sample_token\n        )\n        # Intrinsics\n        d2_dict['intrinsics'] = list(K.flatten())\n        # Get pose of the sensor (S) from vehicle (V) frame\n        _pose_VS = self.nusc.get('calibrated_sensor', datum['calibrated_sensor_token'])\n        pose_VS = Pose(wxyz=np.float64(_pose_VS['rotation']), tvec=np.float64(_pose_VS['translation'])) \n        # Get ego-pose of the vehicle (V) from global/world (W) frame\n        _pose_WV = self.nusc.get('ego_pose', datum['ego_pose_token'])\n        pose_WV = Pose(wxyz=np.float64(_pose_WV['rotation']), tvec=np.float64(_pose_WV['translation']))\n        pose_WS = pose_WV * pose_VS\n\n        d2_dict['pose'] = {'wxyz': list(pose_WS.quat.elements), 'tvec': list(pose_WS.tvec)}\n        d2_dict['extrinsics'] = {'wxyz': list(pose_VS.quat.elements), 'tvec': list(pose_VS.tvec)}\n\n        d2_dict['ego_speed'] = np.linalg.norm(self._get_ego_velocity(datum))\n\n        d2_dict['annotations'] = self.get_instance_annotations(_annotations, K, (height, width), pose_WS)\n        return d2_dict"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/eval_utils/eval_utils.py",
    "content": "import json\nimport torch\nimport tqdm\nfrom typing import List, Dict, Tuple, Callable, Union\nfrom nuscenes import NuScenes\nfrom pyquaternion import Quaternion\nimport numpy as np\nfrom .metric_utils import min_ade, min_fde, miss_rate\n\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom nuscenes.eval.common.data_classes import EvalBox, EvalBoxes\nfrom nuscenes.eval.detection.data_classes import DetectionBox\nfrom nuscenes.eval.detection.data_classes import DetectionMetricData, DetectionMetricDataList, DetectionMetrics\nfrom nuscenes.eval.common.utils import center_distance, scale_iou, yaw_diff, velocity_l2, attr_acc, cummean\n\ndef category_to_motion_name(category_name: str):\n    \"\"\"\n    Default label mapping from nuScenes to nuScenes detection classes.\n    Note that pedestrian does not include personal_mobility, stroller and wheelchair.\n    :param category_name: Generic nuScenes class.\n    :return: nuScenes detection class.\n    \"\"\"\n    detection_mapping = {\n        'movable_object.barrier': 'barrier',\n        'vehicle.bicycle': 'car',\n        'vehicle.bus.bendy': 'car',\n        'vehicle.bus.rigid': 'car',\n        'vehicle.car': 'car',\n        'vehicle.construction': 'car',\n        'vehicle.motorcycle': 'car',\n        'human.pedestrian.adult': 'pedestrian',\n        'human.pedestrian.child': 'pedestrian',\n        'human.pedestrian.construction_worker': 'pedestrian',\n        'human.pedestrian.police_officer': 'pedestrian',\n        'movable_object.trafficcone': 'barrier',\n        'vehicle.trailer': 'car',\n        'vehicle.truck': 'car'\n    }\n\n    if category_name in detection_mapping:\n        return detection_mapping[category_name]\n    else:\n        return None\n\ndef detection_prediction_category_to_motion_name(category_name: str):\n    \"\"\"\n    Default label mapping from nuScenes to nuScenes detection classes.\n    Note that pedestrian does not include personal_mobility, stroller and wheelchair.\n    :param category_name: Generic nuScenes class.\n    :return: nuScenes detection class.\n    \"\"\"\n    detection_mapping = {\n        'car': 'car',\n        'truck': 'car',\n        'construction_vehicle': 'car',\n        'bus': 'car',\n        'trailer': 'car',\n        'motorcycle': 'car',\n        'bicycle': 'car',\n        'pedestrian': 'pedestrian',\n        'traffic_cone': 'barrier',\n        'barrier': 'barrier',\n    }\n\n    if category_name in detection_mapping:\n        return detection_mapping[category_name]\n    else:\n        return None\n\nclass DetectionMotionMetrics(DetectionMetrics):\n    \"\"\" Stores average precision and true positive metric results. Provides properties to summarize. \"\"\"\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized dictionary. \"\"\"\n\n        cfg = DetectionConfig.deserialize(content['cfg'])\n        metrics = cls(cfg=cfg)\n        metrics.add_runtime(content['eval_time'])\n\n        for detection_name, label_aps in content['label_aps'].items():\n            for dist_th, ap in label_aps.items():\n                metrics.add_label_ap(detection_name=detection_name, dist_th=float(dist_th), ap=float(ap))\n\n        for detection_name, label_tps in content['label_tp_errors'].items():\n            for metric_name, tp in label_tps.items():\n                metrics.add_label_tp(detection_name=detection_name, metric_name=metric_name, tp=float(tp))\n\n        return metrics\n\nclass DetectionMotionMetricDataList(DetectionMetricDataList):\n    \"\"\" This stores a set of MetricData in a dict indexed by (name, match-distance). \"\"\"\n    @classmethod\n    def deserialize(cls, content: dict):\n        mdl = cls()\n        for key, md in content.items():\n            name, distance = key.split(':')\n            mdl.set(name, float(distance), DetectionMotionMetricData.deserialize(md))\n        return mdl\n\nclass DetectionMotionMetricData(DetectionMetricData):\n    \"\"\" This class holds accumulated and interpolated data required to calculate the detection metrics. \"\"\"\n\n    nelem = 101\n\n    def __init__(self,\n                 recall: np.array,\n                 precision: np.array,\n                 confidence: np.array,\n                 trans_err: np.array,\n                 vel_err: np.array,\n                 scale_err: np.array,\n                 orient_err: np.array,\n                 attr_err: np.array,\n                 min_ade_err: np.array,\n                 min_fde_err: np.array,\n                 miss_rate_err: np.array):\n\n        # Assert lengths.\n        assert len(recall) == self.nelem\n        assert len(precision) == self.nelem\n        assert len(confidence) == self.nelem\n        assert len(trans_err) == self.nelem\n        assert len(vel_err) == self.nelem\n        assert len(scale_err) == self.nelem\n        assert len(orient_err) == self.nelem\n        assert len(attr_err) == self.nelem\n        assert len(min_ade_err) == self.nelem\n        assert len(min_fde_err) == self.nelem\n        assert len(miss_rate_err) == self.nelem\n\n        # Assert ordering.\n        assert all(confidence == sorted(confidence, reverse=True))  # Confidences should be descending.\n        assert all(recall == sorted(recall))  # Recalls should be ascending.\n\n        # Set attributes explicitly to help IDEs figure out what is going on.\n        self.recall = recall\n        self.precision = precision\n        self.confidence = confidence\n        self.trans_err = trans_err\n        self.vel_err = vel_err\n        self.scale_err = scale_err\n        self.orient_err = orient_err\n        self.attr_err = attr_err\n        self.min_ade_err = min_ade_err\n        self.min_fde_err = min_fde_err\n        self.miss_rate_err = miss_rate_err\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.serialize().keys():\n            eq = eq and np.array_equal(getattr(self, key), getattr(other, key))\n        return eq\n\n    @property\n    def max_recall_ind(self):\n        \"\"\" Returns index of max recall achieved. \"\"\"\n\n        # Last instance of confidence > 0 is index of max achieved recall.\n        non_zero = np.nonzero(self.confidence)[0]\n        if len(non_zero) == 0:  # If there are no matches, all the confidence values will be zero.\n            max_recall_ind = 0\n        else:\n            max_recall_ind = non_zero[-1]\n\n        return max_recall_ind\n\n    @property\n    def max_recall(self):\n        \"\"\" Returns max recall achieved. \"\"\"\n\n        return self.recall[self.max_recall_ind]\n\n    def serialize(self):\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'recall': self.recall.tolist(),\n            'precision': self.precision.tolist(),\n            'confidence': self.confidence.tolist(),\n            'trans_err': self.trans_err.tolist(),\n            'vel_err': self.vel_err.tolist(),\n            'scale_err': self.scale_err.tolist(),\n            'orient_err': self.orient_err.tolist(),\n            'attr_err': self.attr_err.tolist(),\n            'min_ade_err': self.min_ade_err.tolist(),\n            'min_fde_err': self.min_fde_err.tolist(),\n            'miss_rate_err': self.miss_rate_err.tolist(),\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(recall=np.array(content['recall']),\n                   precision=np.array(content['precision']),\n                   confidence=np.array(content['confidence']),\n                   trans_err=np.array(content['trans_err']),\n                   vel_err=np.array(content['vel_err']),\n                   scale_err=np.array(content['scale_err']),\n                   orient_err=np.array(content['orient_err']),\n                   attr_err=np.array(content['attr_err']),\n                   min_ade_err=np.array(content['min_ade_err']),\n                   min_fde_err=np.array(content['min_fde_err']),\n                   miss_rate_err=np.array(content['miss_rate_err']))\n\n    @classmethod\n    def no_predictions(cls):\n        \"\"\" Returns a md instance corresponding to having no predictions. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.zeros(cls.nelem),\n                   confidence=np.zeros(cls.nelem),\n                   trans_err=np.ones(cls.nelem),\n                   vel_err=np.ones(cls.nelem),\n                   scale_err=np.ones(cls.nelem),\n                   orient_err=np.ones(cls.nelem),\n                   attr_err=np.ones(cls.nelem),\n                   min_ade_err=np.ones(cls.nelem),\n                   min_fde_err=np.ones(cls.nelem),\n                   miss_rate_err=np.ones(cls.nelem))\n\n    @classmethod\n    def random_md(cls):\n        \"\"\" Returns an md instance corresponding to a random results. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.random.random(cls.nelem),\n                   confidence=np.linspace(0, 1, cls.nelem)[::-1],\n                   trans_err=np.random.random(cls.nelem),\n                   vel_err=np.random.random(cls.nelem),\n                   scale_err=np.random.random(cls.nelem),\n                   orient_err=np.random.random(cls.nelem),\n                   attr_err=np.random.random(cls.nelem),\n                   min_ade_err=np.random.random(cls.nelem),\n                   min_fde_err=np.random.random(cls.nelem),\n                   miss_rate_err=np.random.random(cls.nelem))\n\n\nclass DetectionMotionBox(DetectionBox):\n    def __init__(self,\n                 sample_token: str = \"\",\n                 translation: Tuple[float, float, float] = (0, 0, 0),\n                 size: Tuple[float, float, float] = (0, 0, 0),\n                 rotation: Tuple[float, float, float, float] = (0, 0, 0, 0),\n                 velocity: Tuple[float, float] = (0, 0),\n                 ego_translation: [float, float, float] = (0, 0, 0),  # Translation to ego vehicle in meters.\n                 num_pts: int = -1,  # Nbr. LIDAR or RADAR inside the box. Only for gt boxes.\n                 detection_name: str = 'car',  # The class name used in the detection challenge.\n                 detection_score: float = -1.0,  # GT samples do not have a score.\n                 attribute_name: str = '',\n                 traj=None,\n                 traj_scores=None):  # Box attribute. Each box can have at most 1 attribute.\n        super(DetectionBox, self).__init__(sample_token, translation, size, rotation, velocity, ego_translation, num_pts)\n        assert detection_name is not None, 'Error: detection_name cannot be empty!'\n        # assert detection_name in DETECTION_NAMES, 'Error: Unknown detection_name %s' % detection_name\n\n        # assert attribute_name in ATTRIBUTE_NAMES or attribute_name == '', \\\n        #     'Error: Unknown attribute_name %s' % attribute_name\n\n        assert type(detection_score) == float, 'Error: detection_score must be a float!'\n        assert not np.any(np.isnan(detection_score)), 'Error: detection_score may not be NaN!'\n\n        # Assign.\n        self.detection_name = detection_name\n        self.attribute_name = attribute_name\n        self.detection_score = detection_score\n        self.traj = traj\n        self.traj_scores = traj_scores\n        self.traj_index = None\n\n    def __eq__(self, other):\n        return (self.sample_token == other.sample_token and\n                self.translation == other.translation and\n                self.size == other.size and\n                self.rotation == other.rotation and\n                self.velocity == other.velocity and\n                self.ego_translation == other.ego_translation and\n                self.num_pts == other.num_pts and\n                self.detection_name == other.detection_name and\n                self.detection_score == other.detection_score and\n                self.attribute_name == other.attribute_name and \n                np.all(self.traj == other.traj) and\n                np.all(self.traj_scores == other.traj_scores))\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'traj': self.traj,\n            'traj_scores': self.traj_scores\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(sample_token=content['sample_token'],\n                   translation=tuple(content['translation']),\n                   size=tuple(content['size']),\n                   rotation=tuple(content['rotation']),\n                   velocity=tuple(content['velocity']),\n                   ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                   else tuple(content['ego_translation']),\n                   num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                   detection_name=content['detection_name'],\n                   detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                   attribute_name=content['attribute_name'], \n                   traj=content['predict_traj'],\n                   traj_scores=content['predict_traj_score'])\n\nclass DetectionMotionBox_modified(DetectionMotionBox):\n    def __init__(self, *args, token=None, visibility=None, index=None, **kwargs):\n        '''\n        add annotation token\n        '''\n        super().__init__(*args, **kwargs)\n        self.token = token\n        self.visibility = visibility\n        self.index = index\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'token': self.token,\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'visibility': self.visibility,\n            'index': self.index,\n            'traj': self.traj,\n            'traj_scores': self.traj_scores\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(\n            token=content['token'],\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name'],\n            visibility=content['visibility'],\n            index=content['index'],\n            traj=content['traj'],\n        )\n\n\ndef load_prediction(result_path: str, max_boxes_per_sample: int, box_cls, verbose: bool = False, category_convert_type='detection_category') \\\n        -> Tuple[EvalBoxes, Dict]:\n    \"\"\"\n    Loads object predictions from file.\n    :param result_path: Path to the .json result file provided by the user.\n    :param max_boxes_per_sample: Maximim number of boxes allowed per sample.\n    :param box_cls: Type of box to load, e.g. DetectionBox, DetectionMotionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The deserialized results and meta data.\n    \"\"\"\n\n    # Load from file and check that the format is correct.\n    with open(result_path) as f:\n        data = json.load(f)\n    assert 'results' in data, 'Error: No field `results` in result file. Please note that the result format changed.' \\\n                              'See https://www.nuscenes.org/object-detection for more information.'\n\n    if category_convert_type == 'motion_category':\n        for key in data['results'].keys():\n            for i in range(len(data['results'][key])):\n                data['results'][key][i]['detection_name'] = detection_prediction_category_to_motion_name(data['results'][key][i]['detection_name']) \n    # Deserialize results and get meta data.\n    all_results = EvalBoxes.deserialize(data['results'], box_cls)\n    meta = data['meta']\n    if verbose:\n        print(\"Loaded results from {}. Found detections for {} samples.\"\n              .format(result_path, len(all_results.sample_tokens)))\n\n    # Check that each sample has no more than x predicted boxes.\n    for sample_token in all_results.sample_tokens:\n        assert len(all_results.boxes[sample_token]) <= max_boxes_per_sample, \\\n            \"Error: Only <= %d boxes per sample allowed!\" % max_boxes_per_sample\n\n    return all_results, meta\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False, category_convert_type='detection_category'):\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n    predict_helper = PredictHelper(nusc)\n    # Init.\n    if box_cls == DetectionMotionBox_modified:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n    index_map = {}\n    for scene in nusc.scene:\n        first_sample_token = scene['first_sample_token']\n        sample = nusc.get('sample', first_sample_token)\n        index_map[first_sample_token] = 1\n        index = 2\n        while sample['next'] != '':\n            sample = nusc.get('sample', sample['next'])\n            index_map[sample['token']] = index\n            index += 1\n\n    sample_tokens = []\n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n\n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == DetectionMotionBox_modified:\n                # Get label name in detection task and filter unused labels.\n                if category_convert_type == 'detection_category':\n                    detection_name = category_to_detection_name(sample_annotation['category_name'])\n                elif category_convert_type == 'motion_category':\n                    detection_name = category_to_motion_name(sample_annotation['category_name'])\n                else:\n                    raise NotImplementedError\n                if detection_name is None:\n                    continue\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n                instance_token = nusc.get('sample_annotation', sample_annotation['token'])['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(instance_token, sample_token, seconds=6, in_agent_frame=True)\n                fut_traj_scence_centric = np.zeros((0,))\n                if fut_traj_local.shape[0] > 0:\n                    _, boxes, _ = nusc.get_sample_data(sample['data']['LIDAR_TOP'], selected_anntokens=[sample_annotation['token']])\n                    box = boxes[0]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scence_centric = convert_local_coords_to_global(fut_traj_local, trans, rot) \n                    \n                sample_boxes.append(\n                    box_cls(\n                        token=sample_annotation_token,\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        visibility=sample_annotation['visibility_token'],\n                        index=index_map[sample_token],\n                        traj=fut_traj_scence_centric,\n                    )\n                )\n            elif box_cls == TrackingBox:\n                assert False\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\ndef prediction_metrics(gt_box_match, pred_box):\n    pred_traj = np.array(pred_box.traj)\n    gt_traj_steps = gt_box_match.traj.reshape((-1, 2))\n    valid_steps = gt_traj_steps.shape[0]\n    if valid_steps <= 0:\n        return np.array([0]), np.array([0]), 0\n    nmodes = pred_traj.shape[0]\n    pred_steps = pred_traj.shape[1]\n    valid_mask = np.zeros((pred_steps, ))\n    gt_traj = np.zeros((pred_steps, 2))\n    gt_traj[:valid_steps, :] = gt_traj_steps\n    valid_mask[: valid_steps] = 1\n    pred_traj = torch.tensor(pred_traj[None])\n    gt_traj = torch.tensor(gt_traj[None])\n    valid_mask = torch.tensor(valid_mask[None])\n    ade_err, inds = min_ade(pred_traj, gt_traj, 1 - valid_mask)\n    fde_err, inds = min_fde(pred_traj, gt_traj, 1 - valid_mask)\n    mr_err = miss_rate(pred_traj, gt_traj, 1 - valid_mask, dist_thresh=2)\n    return ade_err.numpy(), fde_err.numpy(), mr_err.numpy()\n\n\ndef accumulate(gt_boxes: EvalBoxes,\n               pred_boxes: EvalBoxes,\n               class_name: str,\n               dist_fcn: Callable,\n               dist_th: float,\n               verbose: bool = False) -> DetectionMotionMetricData:\n    \"\"\"\n    Average Precision over predefined different recall thresholds for a single distance threshold.\n    The recall/conf thresholds and other raw metrics will be used in secondary metrics.\n    :param gt_boxes: Maps every sample_token to a list of its sample_annotations.\n    :param pred_boxes: Maps every sample_token to a list of its sample_results.\n    :param class_name: Class to compute AP on.\n    :param dist_fcn: Distance function used to match detections and ground truths.\n    :param dist_th: Distance threshold for a match.\n    :param verbose: If true, print debug messages.\n    :return: (average_prec, metrics). The average precision value and raw data for a number of metrics.\n    \"\"\"\n    # ---------------------------------------------\n    # Organize input and initialize accumulators.\n    # ---------------------------------------------\n\n    # Count the positives.\n    npos = len([1 for gt_box in gt_boxes.all if gt_box.detection_name == class_name])\n    if verbose:\n        print(\"Found {} GT of class {} out of {} total across {} samples.\".\n              format(npos, class_name, len(gt_boxes.all), len(gt_boxes.sample_tokens)))\n\n    # For missing classes in the GT, return a data structure corresponding to no predictions.\n    if npos == 0:\n        return DetectionMotionMetricData.no_predictions(), 0, 0, 0\n\n    # Organize the predictions in a single list.\n    pred_boxes_list = [box for box in pred_boxes.all if box.detection_name == class_name]\n    pred_confs = [box.detection_score for box in pred_boxes_list]\n\n    if verbose:\n        print(\"Found {} PRED of class {} out of {} total across {} samples.\".\n              format(len(pred_confs), class_name, len(pred_boxes.all), len(pred_boxes.sample_tokens)))\n\n    # Sort by confidence.\n    sortind = [i for (v, i) in sorted((v, i) for (i, v) in enumerate(pred_confs))][::-1]\n\n    # Do the actual matching.\n    tp = []  # Accumulator of true positives.\n    fp = []  # Accumulator of false positives.\n    conf = []  # Accumulator of confidences.\n\n    # match_data holds the extra metrics we calculate for each match.\n    match_data = {'trans_err': [],\n                  'vel_err': [],\n                  'scale_err': [],\n                  'orient_err': [],\n                  'attr_err': [],\n                  'conf': [],\n                  'min_ade_err': [],\n                  'min_fde_err': [],\n                  'miss_rate_err': []}\n\n    # ---------------------------------------------\n    # Match and accumulate match data.\n    # ---------------------------------------------\n\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th\n\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n\n            #  Update tp, fp and confs.\n            tp.append(1)\n            fp.append(0)\n            conf.append(pred_box.detection_score)\n\n            # Since it is a match, update match data also.\n            gt_box_match = gt_boxes[pred_box.sample_token][match_gt_idx]\n            \n            match_data['trans_err'].append(center_distance(gt_box_match, pred_box))\n            match_data['vel_err'].append(velocity_l2(gt_box_match, pred_box))\n            match_data['scale_err'].append(1 - scale_iou(gt_box_match, pred_box))\n\n            # Barrier orientation is only determined up to 180 degree. (For cones orientation is discarded later)\n            period = np.pi if class_name == 'barrier' else 2 * np.pi\n            match_data['orient_err'].append(yaw_diff(gt_box_match, pred_box, period=period))\n\n            match_data['attr_err'].append(1 - attr_acc(gt_box_match, pred_box))\n            minade, minfde, m_r = prediction_metrics(gt_box_match, pred_box)\n            \n            match_data['min_ade_err'].append(minade)\n            match_data['min_fde_err'].append(minfde)\n            match_data['miss_rate_err'].append(m_r)\n            match_data['conf'].append(pred_box.detection_score)\n\n        else:\n            # No match. Mark this as a false positive.\n            tp.append(0)\n            fp.append(1)\n            conf.append(pred_box.detection_score)\n\n    # Check if we have any matches. If not, just return a \"no predictions\" array.\n    if len(match_data['trans_err']) == 0:\n        return DetectionMotionMetricData.no_predictions(), 0, 0, 0\n\n    # ---------------------------------------------\n    # Calculate and interpolate precision and recall\n    # ---------------------------------------------\n\n    # Accumulate.\n    N_tp = np.sum(tp)\n    N_fp = np.sum(fp)\n    tp = np.cumsum(tp).astype(float)\n    fp = np.cumsum(fp).astype(float)\n    conf = np.array(conf)\n\n\n    # Calculate precision and recall.\n    prec = tp / (fp + tp)\n    rec = tp / float(npos)\n\n    rec_interp = np.linspace(0, 1, DetectionMotionMetricData.nelem)  # 101 steps, from 0% to 100% recall.\n    prec = np.interp(rec_interp, rec, prec, right=0)\n    conf = np.interp(rec_interp, rec, conf, right=0)\n    rec = rec_interp\n\n    # ---------------------------------------------\n    # Re-sample the match-data to match, prec, recall and conf.\n    # ---------------------------------------------\n\n    for key in match_data.keys():\n        if key == \"conf\":\n            continue  # Confidence is used as reference to align with fp and tp. So skip in this step.\n\n        else:\n            # For each match_data, we first calculate the accumulated mean.\n            tmp = cummean(np.array(match_data[key]))\n\n            # Then interpolate based on the confidences. (Note reversing since np.interp needs increasing arrays)\n            match_data[key] = np.interp(conf[::-1], match_data['conf'][::-1], tmp[::-1])[::-1]\n\n    # ---------------------------------------------\n    # Done. Instantiate MetricData and return\n    # ---------------------------------------------\n    return DetectionMotionMetricData(recall=rec,\n                               precision=prec,\n                               confidence=conf,\n                               trans_err=match_data['trans_err'],\n                               vel_err=match_data['vel_err'],\n                               scale_err=match_data['scale_err'],\n                               orient_err=match_data['orient_err'],\n                               attr_err=match_data['attr_err'],\n                               min_ade_err=match_data['min_ade_err'],\n                               min_fde_err=match_data['min_fde_err'],\n                               miss_rate_err=match_data['miss_rate_err']\n                               ), N_tp, N_fp, npos\n\n\n\ndef accumulate_motion(gt_boxes: EvalBoxes,\n               pred_boxes: EvalBoxes,\n               class_name: str,\n               dist_fcn: Callable,\n               traj_fcn: Callable,\n               dist_th: float,\n               traj_dist_th: float,\n               verbose: bool = False,\n               final_step: float = 12) -> DetectionMotionMetricData:\n    \"\"\"\n    Average Precision over predefined different recall thresholds for a single distance threshold.\n    The recall/conf thresholds and other raw metrics will be used in secondary metrics.\n    :param gt_boxes: Maps every sample_token to a list of its sample_annotations.\n    :param pred_boxes: Maps every sample_token to a list of its sample_results.\n    :param class_name: Class to compute AP on.\n    :param dist_fcn: Distance function used to match detections and ground truths.\n    :param dist_th: Distance threshold for a match.\n    :param verbose: If true, print debug messages.\n    :return: (average_prec, metrics). The average precision value and raw data for a number of metrics.\n    \"\"\"\n    # ---------------------------------------------\n    # Organize input and initialize accumulators.\n    # ---------------------------------------------\n\n    # Count the positives.\n    npos = len([1 for gt_box in gt_boxes.all if gt_box.detection_name == class_name])\n    if verbose:\n        print(\"Found {} GT of class {} out of {} total across {} samples.\".\n              format(npos, class_name, len(gt_boxes.all), len(gt_boxes.sample_tokens)))\n\n    # For missing classes in the GT, return a data structure corresponding to no predictions.\n    if npos == 0:\n        return DetectionMotionMetricData.no_predictions(), 0, 0, 0\n\n    # \n    # Organize the predictions in a single list.\n    pred_boxes_list = []\n    pred_confs = []\n\n    pred_boxes_list = [box for box in pred_boxes.all if box.detection_name == class_name]\n    pred_confs = [box.detection_score for box in pred_boxes_list]\n    # for box in pred_boxes.all:\n    #     if box.detection_name == class_name:\n    #         box.traj_scores = np.exp(box.traj_scores)\n    #         for i in range(len(box.traj_scores)):\n    #             box.traj_index = i\n    #             pred_boxes_list.append(box)\n    # pred_confs = [box.detection_score * box.traj_scores[box.traj_index]  for box in pred_boxes_list]\n\n    if verbose:\n        print(\"Found {} PRED of class {} out of {} total across {} samples.\".\n              format(len(pred_confs), class_name, len(pred_boxes.all), len(pred_boxes.sample_tokens)))\n\n    # Sort by confidence.\n    sortind = [i for (v, i) in sorted((v, i) for (i, v) in enumerate(pred_confs))][::-1]\n\n    # Do the actual matching.\n    tp = []  # Accumulator of true positives.\n    fp = []  # Accumulator of false positives.\n    conf = []  # Accumulator of confidences.\n\n    # match_data holds the extra metrics we calculate for each match.\n    match_data = {'trans_err': [],\n                  'vel_err': [],\n                  'scale_err': [],\n                  'orient_err': [],\n                  'attr_err': [],\n                  'conf': [],\n                  'min_ade_err': [],\n                  'min_fde_err': [],\n                  'miss_rate_err': []}\n\n    # ---------------------------------------------\n    # Match and accumulate match data.\n    # ---------------------------------------------\n\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n                    fde_distance = traj_fcn(gt_box, pred_box, final_step)\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th and fde_distance < traj_dist_th\n\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n\n            #  Update tp, fp and confs.\n            tp.append(1)\n            fp.append(0)\n            conf.append(pred_box.detection_score)\n\n            # Since it is a match, update match data also.\n            gt_box_match = gt_boxes[pred_box.sample_token][match_gt_idx]\n            \n            match_data['trans_err'].append(center_distance(gt_box_match, pred_box))\n            match_data['vel_err'].append(velocity_l2(gt_box_match, pred_box))\n            match_data['scale_err'].append(1 - scale_iou(gt_box_match, pred_box))\n\n            # Barrier orientation is only determined up to 180 degree. (For cones orientation is discarded later)\n            period = np.pi if class_name == 'barrier' else 2 * np.pi\n            match_data['orient_err'].append(yaw_diff(gt_box_match, pred_box, period=period))\n\n            match_data['attr_err'].append(1 - attr_acc(gt_box_match, pred_box))\n            minade, minfde, m_r = prediction_metrics(gt_box_match, pred_box)\n            \n            match_data['min_ade_err'].append(minade)\n            match_data['min_fde_err'].append(minfde)\n            match_data['miss_rate_err'].append(m_r)\n            match_data['conf'].append(pred_box.detection_score)\n\n        else:\n            # No match. Mark this as a false positive.\n            tp.append(0)\n            fp.append(1)\n            conf.append(pred_box.detection_score)\n            # conf.append(pred_box.detection_score * pred_box.traj_scores[pred_box.traj_index])\n    # \n    # Check if we have any matches. If not, just return a \"no predictions\" array.\n    if len(match_data['trans_err']) == 0:\n        return DetectionMotionMetricData.no_predictions(), 0, 0, 0\n\n    # ---------------------------------------------\n    # Calculate and interpolate precision and recall\n    # ---------------------------------------------\n\n    # Accumulate.\n    N_tp = np.sum(tp)\n    N_fp = np.sum(fp)\n    tp = np.cumsum(tp).astype(float)\n    fp = np.cumsum(fp).astype(float)\n    conf = np.array(conf)\n\n    # Calculate precision and recall.\n    prec = tp / (fp + tp)\n    rec = tp / float(npos)\n\n\n\n    rec_interp = np.linspace(0, 1, DetectionMotionMetricData.nelem)  # 101 steps, from 0% to 100% recall.\n    prec = np.interp(rec_interp, rec, prec, right=0)\n    conf = np.interp(rec_interp, rec, conf, right=0)\n    rec = rec_interp\n\n    # ---------------------------------------------\n    # Re-sample the match-data to match, prec, recall and conf.\n    # ---------------------------------------------\n\n    for key in match_data.keys():\n        if key == \"conf\":\n            continue  # Confidence is used as reference to align with fp and tp. So skip in this step.\n\n        else:\n            # For each match_data, we first calculate the accumulated mean.\n            tmp = cummean(np.array(match_data[key]))\n\n            # Then interpolate based on the confidences. (Note reversing since np.interp needs increasing arrays)\n            match_data[key] = np.interp(conf[::-1], match_data['conf'][::-1], tmp[::-1])[::-1]\n\n    # ---------------------------------------------\n    # Done. Instantiate MetricData and return\n    # ---------------------------------------------\n    return DetectionMotionMetricData(recall=rec,\n                               precision=prec,\n                               confidence=conf,\n                               trans_err=match_data['trans_err'],\n                               vel_err=match_data['vel_err'],\n                               scale_err=match_data['scale_err'],\n                               orient_err=match_data['orient_err'],\n                               attr_err=match_data['attr_err'],\n                               min_ade_err=match_data['min_ade_err'],\n                               min_fde_err=match_data['min_fde_err'],\n                               miss_rate_err=match_data['miss_rate_err']\n                               ), N_tp, N_fp, npos"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/eval_utils/map_api.py",
    "content": "# nuScenes dev-kit.\n# Code written by Sergi Adipraja Widjaja, 2019.\n# + Map mask by Kiwoo Shin, 2019.\n# + Methods operating on NuScenesMap and NuScenes by Holger Caesar, 2019.\n\nimport json\nimport os\nimport random\nfrom typing import Dict, List, Tuple, Optional, Union\n\nimport cv2\nimport math\nimport descartes\nimport matplotlib.gridspec as gridspec\nimport matplotlib.pyplot as plt\nimport numpy as np\nfrom PIL import Image\nfrom matplotlib.axes import Axes\nfrom matplotlib.figure import Figure\nfrom matplotlib.patches import Rectangle, Arrow\nfrom mpl_toolkits.axes_grid1.inset_locator import mark_inset\nfrom pyquaternion import Quaternion\nfrom shapely import affinity\nfrom shapely.geometry import Polygon, MultiPolygon, LineString, Point, box\nfrom tqdm import tqdm\n\nfrom nuscenes.map_expansion.arcline_path_utils import discretize_lane, ArcLinePath\nfrom nuscenes.map_expansion.bitmap import BitMap\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.utils.geometry_utils import view_points\nfrom functools import partial\n\n# Recommended style to use as the plots will show grids.\nplt.style.use('seaborn-whitegrid')\n\n# Define a map geometry type for polygons and lines.\nGeometry = Union[Polygon, LineString]\n\nlocations = ['singapore-onenorth', 'singapore-hollandvillage', 'singapore-queenstown', 'boston-seaport']\n\n\nclass NuScenesMap:\n    \"\"\"\n    NuScenesMap database class for querying and retrieving information from the semantic maps.\n    Before using this class please use the provided tutorial `map_expansion_tutorial.ipynb`.\n\n    Below you can find the map origins (south western corner, in [lat, lon]) for each of the 4 maps in nuScenes:\n    boston-seaport: [42.336849169438615, -71.05785369873047]\n    singapore-onenorth: [1.2882100868743724, 103.78475189208984]\n    singapore-hollandvillage: [1.2993652317780957, 103.78217697143555]\n    singapore-queenstown: [1.2782562240223188, 103.76741409301758]\n\n    The dimensions of the maps are as follows ([width, height] in meters):\n    singapore-onenorth: [1585.6, 2025.0]\n    singapore-hollandvillage: [2808.3, 2922.9]\n    singapore-queenstown: [3228.6, 3687.1]\n    boston-seaport: [2979.5, 2118.1]\n    The rasterized semantic maps (e.g. singapore-onenorth.png) published with nuScenes v1.0 have a scale of 10px/m,\n    hence the above numbers are the image dimensions divided by 10.\n\n    We use the same WGS 84 Web Mercator (EPSG:3857) projection as Google Maps/Earth.\n    \"\"\"\n    def __init__(self,\n                 dataroot: str = '/data/sets/nuscenes',\n                 map_name: str = 'singapore-onenorth'):\n        \"\"\"\n        Loads the layers, create reverse indices and shortcuts, initializes the explorer class.\n        :param dataroot: Path to the layers in the form of a .json file.\n        :param map_name: Which map out of `singapore-onenorth`, `singepore-hollandvillage`, `singapore-queenstown`,\n        `boston-seaport` that we want to load.\n        \"\"\"\n        assert map_name in locations, 'Error: Unknown map name %s!' % map_name\n\n        self.dataroot = dataroot\n        self.map_name = map_name\n\n        self.geometric_layers = ['polygon', 'line', 'node']\n\n        # These are the non-geometric layers which have polygons as the geometric descriptors.\n        self.non_geometric_polygon_layers = ['drivable_area', 'road_segment', 'road_block', 'lane', 'ped_crossing',\n                                             'walkway', 'stop_line', 'carpark_area']\n\n        # We want to be able to search for lane connectors, but not render them.\n        self.lookup_polygon_layers = self.non_geometric_polygon_layers + ['lane_connector']\n\n        # These are the non-geometric layers which have line strings as the geometric descriptors.\n        self.non_geometric_line_layers = ['road_divider', 'lane_divider', 'traffic_light']\n        self.non_geometric_layers = self.non_geometric_polygon_layers + self.non_geometric_line_layers\n        self.layer_names = self.geometric_layers + self.lookup_polygon_layers + self.non_geometric_line_layers\n\n        # Load the selected map.\n        self.json_fname = os.path.join(self.dataroot, 'maps', 'expansion', '{}.json'.format(self.map_name))\n        with open(self.json_fname, 'r') as fh:\n            self.json_obj = json.load(fh)\n\n        # Parse the map version and print an error for deprecated maps.\n        if 'version' in self.json_obj:\n            self.version = self.json_obj['version']\n        else:\n            self.version = '1.0'\n        if self.version < '1.3':\n            raise Exception('Error: You are using an outdated map version (%s)! '\n                            'Please go to https://www.nuscenes.org/download to download the latest map!')\n\n        self.canvas_edge = self.json_obj['canvas_edge']\n        self._load_layers()\n        self._make_token2ind()\n        self._make_shortcuts()\n\n        self.explorer = NuScenesMapExplorer(self)\n\n    def _load_layer(self, layer_name: str) -> List[dict]:\n        \"\"\"\n        Returns a list of records corresponding to the layer name.\n        :param layer_name: Name of the layer that will be loaded.\n        :return: A list of records corresponding to a layer.\n        \"\"\"\n        return self.json_obj[layer_name]\n\n    def _load_layer_dict(self, layer_name: str) -> Dict[str, Union[dict, list]]:\n        \"\"\"\n        Returns a dict of records corresponding to the layer name.\n        :param layer_name: Name of the layer that will be loaded.\n        :return: A dict of records corresponding to a layer.\n        \"\"\"\n        return self.json_obj[layer_name]\n\n    def _load_layers(self) -> None:\n        \"\"\" Loads each available layer. \"\"\"\n\n        # Explicit assignment of layers are necessary to help the IDE determine valid class members.\n        self.polygon = self._load_layer('polygon')\n        self.line = self._load_layer('line')\n        self.node = self._load_layer('node')\n        self.drivable_area = self._load_layer('drivable_area')\n        self.road_segment = self._load_layer('road_segment')\n        self.road_block = self._load_layer('road_block')\n        self.lane = self._load_layer('lane')\n        self.ped_crossing = self._load_layer('ped_crossing')\n        self.walkway = self._load_layer('walkway')\n        self.stop_line = self._load_layer('stop_line')\n        self.carpark_area = self._load_layer('carpark_area')\n        self.road_divider = self._load_layer('road_divider')\n        self.lane_divider = self._load_layer('lane_divider')\n        self.traffic_light = self._load_layer('traffic_light')\n\n        self.arcline_path_3: Dict[str, List[dict]] = self._load_layer_dict('arcline_path_3')\n        self.connectivity: Dict[str, dict] = self._load_layer_dict('connectivity')\n        self.lane_connector = self._load_layer('lane_connector')\n\n    def _make_token2ind(self) -> None:\n        \"\"\" Store the mapping from token to layer index for each layer. \"\"\"\n        self._token2ind = dict()\n        for layer_name in self.layer_names:\n            self._token2ind[layer_name] = dict()\n\n            for ind, member in enumerate(getattr(self, layer_name)):\n                self._token2ind[layer_name][member['token']] = ind\n\n    def _make_shortcuts(self) -> None:\n        \"\"\" Makes the record shortcuts. \"\"\"\n\n        # Makes a shortcut between non geometric records to their nodes.\n        for layer_name in self.non_geometric_polygon_layers:\n            if layer_name == 'drivable_area':  # Drivable area has more than one geometric representation.\n                pass\n            else:\n                for record in self.__dict__[layer_name]:\n                    polygon_obj = self.get('polygon', record['polygon_token'])\n                    record['exterior_node_tokens'] = polygon_obj['exterior_node_tokens']\n                    record['holes'] = polygon_obj['holes']\n\n        for layer_name in self.non_geometric_line_layers:\n            for record in self.__dict__[layer_name]:\n                record['node_tokens'] = self.get('line', record['line_token'])['node_tokens']\n\n        # Makes a shortcut between stop lines to their cues, there's different cues for different types of stop line.\n        # Refer to `_get_stop_line_cue()` for details.\n        for record in self.stop_line:\n            cue = self._get_stop_line_cue(record)\n            record['cue'] = cue\n\n        # Makes a shortcut between lanes to their lane divider segment nodes.\n        for record in self.lane:\n            record['left_lane_divider_segment_nodes'] = [self.get('node', segment['node_token']) for segment in\n                                                         record['left_lane_divider_segments']]\n            record['right_lane_divider_segment_nodes'] = [self.get('node', segment['node_token']) for segment in\n                                                          record['right_lane_divider_segments']]\n\n    def _get_stop_line_cue(self, stop_line_record: dict) -> List[dict]:\n        \"\"\"\n        Get the different cues for different types of stop lines.\n        :param stop_line_record: A single stop line record.\n        :return: The cue for that stop line.\n        \"\"\"\n        if stop_line_record['stop_line_type'] in ['PED_CROSSING', 'TURN_STOP']:\n            return [self.get('ped_crossing', token) for token in stop_line_record['ped_crossing_tokens']]\n        elif stop_line_record['stop_line_type'] in ['STOP_SIGN', 'YIELD']:\n            return []\n        elif stop_line_record['stop_line_type'] == 'TRAFFIC_LIGHT':\n            return [self.get('traffic_light', token) for token in stop_line_record['traffic_light_tokens']]\n\n    def get(self, layer_name: str, token: str) -> dict:\n        \"\"\"\n        Returns a record from the layer in constant runtime.\n        :param layer_name: Name of the layer that we are interested in.\n        :param token: Token of the record.\n        :return: A single layer record.\n        \"\"\"\n        assert layer_name in self.layer_names, \"Layer {} not found\".format(layer_name)\n\n        return getattr(self, layer_name)[self.getind(layer_name, token)]\n\n    def getind(self, layer_name: str, token: str) -> int:\n        \"\"\"\n        This returns the index of the record in a layer in constant runtime.\n        :param layer_name: Name of the layer we are interested in.\n        :param token: Token of the record.\n        :return: The index of the record in the layer, layer is an array.\n        \"\"\"\n        return self._token2ind[layer_name][token]\n\n    def render_record(self,\n                      layer_name: str,\n                      token: str,\n                      alpha: float = 0.5,\n                      figsize: Tuple[float, float] = None,\n                      other_layers: List[str] = None,\n                      bitmap: Optional[BitMap] = None) -> Tuple[Figure, Tuple[Axes, Axes]]:\n        \"\"\"\n         Render a single map record. By default will also render 3 layers which are `drivable_area`, `lane`,\n         and `walkway` unless specified by `other_layers`.\n         :param layer_name: Name of the layer that we are interested in.\n         :param token: Token of the record that you want to render.\n         :param alpha: The opacity of each layer that gets rendered.\n         :param figsize: Size of the whole figure.\n         :param other_layers: What other layers to render aside from the one specified in `layer_name`.\n         :param bitmap: Optional BitMap object to render below the other map layers.\n         :return: The matplotlib figure and axes of the rendered layers.\n         \"\"\"\n        return self.explorer.render_record(layer_name, token, alpha,\n                                           figsize=figsize, other_layers=other_layers, bitmap=bitmap)\n\n    def render_layers(self,\n                      layer_names: List[str],\n                      alpha: float = 0.5,\n                      figsize: Union[None, float, Tuple[float, float]] = None,\n                      tokens: List[str] = None,\n                      bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Render a list of layer names.\n        :param layer_names: A list of layer names.\n        :param alpha: The opacity of each layer that gets rendered.\n        :param figsize: Size of the whole figure.\n        :param tokens: Optional list of tokens to render. None means all tokens are rendered.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: The matplotlib figure and axes of the rendered layers.\n        \"\"\"\n        return self.explorer.render_layers(layer_names, alpha,\n                                           figsize=figsize, tokens=tokens, bitmap=bitmap)\n\n    def render_map_patch(self,\n                         box_coords: Tuple[float, float, float, float],\n                         layer_names: List[str] = None,\n                         alpha: float = 0.5,\n                         figsize: Tuple[int, int] = (15, 15),\n                         render_egoposes_range: bool = True,\n                         render_legend: bool = True,\n                         bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Renders a rectangular patch specified by `box_coords`. By default renders all layers.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param layer_names: All the non geometric layers that we want to render.\n        :param alpha: The opacity of each layer.\n        :param figsize: Size of the whole figure.\n        :param render_egoposes_range: Whether to render a rectangle around all ego poses.\n        :param render_legend: Whether to render the legend of map layers.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: The matplotlib figure and axes of the rendered layers.\n        \"\"\"\n        return self.explorer.render_map_patch(box_coords, layer_names=layer_names, alpha=alpha, figsize=figsize,\n                                              render_egoposes_range=render_egoposes_range,\n                                              render_legend=render_legend, bitmap=bitmap)\n\n    def render_map_in_image(self,\n                            nusc: NuScenes,\n                            sample_token: str,\n                            camera_channel: str = 'CAM_FRONT',\n                            alpha: float = 0.3,\n                            patch_radius: float = 10000,\n                            min_polygon_area: float = 1000,\n                            render_behind_cam: bool = True,\n                            render_outside_im: bool = True,\n                            layer_names: List[str] = None,\n                            verbose: bool = True,\n                            out_path: str = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Render a nuScenes camera image and overlay the polygons for the specified map layers.\n        Note that the projections are not always accurate as the localization is in 2d.\n        :param nusc: The NuScenes instance to load the image from.\n        :param sample_token: The image's corresponding sample_token.\n        :param camera_channel: Camera channel name, e.g. 'CAM_FRONT'.\n        :param alpha: The transparency value of the layers to render in [0, 1].\n        :param patch_radius: The radius in meters around the ego car in which to select map records.\n        :param min_polygon_area: Minimum area a polygon needs to have to be rendered.\n        :param render_behind_cam: Whether to render polygons where any point is behind the camera.\n        :param render_outside_im: Whether to render polygons where any point is outside the image.\n        :param layer_names: The names of the layers to render, e.g. ['lane'].\n            If set to None, the recommended setting will be used.\n        :param verbose: Whether to print to stdout.\n        :param out_path: Optional path to save the rendered figure to disk.\n        \"\"\"\n        return self.explorer.render_map_in_image(\n            nusc, sample_token, camera_channel=camera_channel, alpha=alpha,\n            patch_radius=patch_radius, min_polygon_area=min_polygon_area,\n            render_behind_cam=render_behind_cam, render_outside_im=render_outside_im,\n            layer_names=layer_names, verbose=verbose, out_path=out_path)\n\n    def get_map_mask_in_image(self,\n                              nusc: NuScenes,\n                              sample_token: str,\n                              camera_channel: str = 'CAM_FRONT',\n                              alpha: float = 0.3,\n                              patch_radius: float = 10000,\n                              min_polygon_area: float = 1000,\n                              render_behind_cam: bool = True,\n                              render_outside_im: bool = True,\n                              layer_names: List[str] = None,\n                              verbose: bool = False,\n                              out_path: str = None):\n        \"\"\"\n        Render a nuScenes camera image and overlay the polygons for the specified map layers.\n        Note that the projections are not always accurate as the localization is in 2d.\n        :param nusc: The NuScenes instance to load the image from.\n        :param sample_token: The image's corresponding sample_token.\n        :param camera_channel: Camera channel name, e.g. 'CAM_FRONT'.\n        :param alpha: The transparency value of the layers to render in [0, 1].\n        :param patch_radius: The radius in meters around the ego car in which to select map records.\n        :param min_polygon_area: Minimum area a polygon needs to have to be rendered.\n        :param render_behind_cam: Whether to render polygons where any point is behind the camera.\n        :param render_outside_im: Whether to render polygons where any point is outside the image.\n        :param layer_names: The names of the layers to render, e.g. ['lane'].\n            If set to None, the recommended setting will be used.\n        :param verbose: Whether to print to stdout.\n        :param out_path: Optional path to save the rendered figure to disk.\n        \"\"\"\n        return self.explorer.get_map_mask_in_image(\n            nusc, sample_token, camera_channel=camera_channel, alpha=alpha,\n            patch_radius=patch_radius, min_polygon_area=min_polygon_area,\n            render_behind_cam=render_behind_cam, render_outside_im=render_outside_im,\n            layer_names=layer_names, verbose=verbose, out_path=out_path)\n\n    def render_egoposes_on_fancy_map(self,\n                                     nusc: NuScenes,\n                                     scene_tokens: List = None,\n                                     verbose: bool = True,\n                                     out_path: str = None,\n                                     render_egoposes: bool = True,\n                                     render_egoposes_range: bool = True,\n                                     render_legend: bool = True,\n                                     bitmap: Optional[BitMap] = None) -> Tuple[np.ndarray, Figure, Axes]:\n        \"\"\"\n        Renders each ego pose of a list of scenes on the map (around 40 poses per scene).\n        This method is heavily inspired by NuScenes.render_egoposes_on_map(), but uses the map expansion pack maps.\n        :param nusc: The NuScenes instance to load the ego poses from.\n        :param scene_tokens: Optional list of scene tokens corresponding to the current map location.\n        :param verbose: Whether to show status messages and progress bar.\n        :param out_path: Optional path to save the rendered figure to disk.\n        :param render_egoposes: Whether to render ego poses.\n        :param render_egoposes_range: Whether to render a rectangle around all ego poses.\n        :param render_legend: Whether to render the legend of map layers.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: <np.float32: n, 2>. Returns a matrix with n ego poses in global map coordinates.\n        \"\"\"\n        return self.explorer.render_egoposes_on_fancy_map(nusc, scene_tokens=scene_tokens,\n                                                          verbose=verbose, out_path=out_path,\n                                                          render_egoposes=render_egoposes,\n                                                          render_egoposes_range=render_egoposes_range,\n                                                          render_legend=render_legend, bitmap=bitmap)\n\n    def render_centerlines(self,\n                           resolution_meters: float = 0.5,\n                           figsize: Union[None, float, Tuple[float, float]] = None,\n                           bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Render the centerlines of all lanes and lane connectors.\n        :param resolution_meters: How finely to discretize the lane. Smaller values ensure curved\n            lanes are properly represented.\n        :param figsize: Size of the figure.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        \"\"\"\n        return self.explorer.render_centerlines(resolution_meters=resolution_meters, figsize=figsize, bitmap=bitmap)\n\n    def render_map_mask(self,\n                        patch_box: Tuple[float, float, float, float],\n                        patch_angle: float,\n                        layer_names: List[str] = None,\n                        canvas_size: Tuple[int, int] = (100, 100),\n                        figsize: Tuple[int, int] = (15, 15),\n                        n_row: int = 2) -> Tuple[Figure, List[Axes]]:\n        \"\"\"\n        Render map mask of the patch specified by patch_box and patch_angle.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n        :param layer_names: A list of layer names to be returned.\n        :param canvas_size: Size of the output mask (h, w).\n        :param figsize: Size of the figure.\n        :param n_row: Number of rows with plots.\n        :return: The matplotlib figure and a list of axes of the rendered layers.\n        \"\"\"\n        return self.explorer.render_map_mask(patch_box, patch_angle,\n                                             layer_names=layer_names, canvas_size=canvas_size,\n                                             figsize=figsize, n_row=n_row)\n\n    def get_map_mask(self,\n                     patch_box: Optional[Tuple[float, float, float, float]],\n                     patch_angle: float,\n                     layer_names: List[str] = None,\n                     canvas_size: Optional[Tuple[int, int]] = (100, 100)) -> np.ndarray:\n        \"\"\"\n        Return list of map mask layers of the specified patch.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width]. If None, this plots the entire map.\n        :param patch_angle: Patch orientation in degrees. North-facing corresponds to 0.\n        :param layer_names: A list of layer names to be extracted, or None for all non-geometric layers.\n        :param canvas_size: Size of the output mask (h, w). If None, we use the default resolution of 10px/m.\n        :return: Stacked numpy array of size [c x h x w] with c channels and the same width/height as the canvas.\n        \"\"\"\n        return self.explorer.get_map_mask(patch_box, patch_angle, layer_names=layer_names, canvas_size=canvas_size)\n\n    def get_map_geom(self,\n                     patch_box: Tuple[float, float, float, float],\n                     patch_angle: float,\n                     layer_names: List[str]) -> List[Tuple[str, List[Geometry]]]:\n        \"\"\"\n        Returns a list of geometries in the specified patch_box.\n        These are unscaled, but aligned with the patch angle.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n                            North-facing corresponds to 0.\n        :param layer_names: A list of layer names to be extracted, or None for all non-geometric layers.\n        :return: List of layer names and their corresponding geometries.\n        \"\"\"\n        return self.explorer.get_map_geom(patch_box, patch_angle, layer_names)\n\n    def get_records_in_patch(self,\n                             box_coords: Tuple[float, float, float, float],\n                             layer_names: List[str] = None,\n                             mode: str = 'intersect') -> Dict[str, List[str]]:\n        \"\"\"\n        Get all the record token that intersects or is within a particular rectangular patch.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param layer_names: Names of the layers that we want to retrieve in a particular patch. By default will always\n        look at the all non geometric layers.\n        :param mode: \"intersect\" will return all non geometric records that intersects the patch, \"within\" will return\n        all non geometric records that are within the patch.\n        :return: Dictionary of layer_name - tokens pairs.\n        \"\"\"\n        return self.explorer.get_records_in_patch(box_coords, layer_names=layer_names, mode=mode)\n\n    def is_record_in_patch(self,\n                           layer_name: str,\n                           token: str,\n                           box_coords: Tuple[float, float, float, float],\n                           mode: str = 'intersect') -> bool:\n        \"\"\"\n        Query whether a particular record is in a rectangular patch\n        :param layer_name: The layer name of the record.\n        :param token: The record token.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param mode: \"intersect\" means it will return True if the geometric object intersects the patch, \"within\" will\n                     return True if the geometric object is within the patch.\n        :return: Boolean value on whether a particular record intersects or within a particular patch.\n        \"\"\"\n        return self.explorer.is_record_in_patch(layer_name, token, box_coords, mode=mode)\n\n    def layers_on_point(self, x: float, y: float, layer_names: List[str] = None) -> Dict[str, str]:\n        \"\"\"\n        Returns all the polygonal layers that a particular point is on.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :param layer_names: The names of the layers to search for.\n        :return: All the polygonal layers that a particular point is on. {<layer name>: <list of tokens>}\n        \"\"\"\n        return self.explorer.layers_on_point(x, y, layer_names=layer_names)\n\n    def record_on_point(self, x: float, y: float, layer_name: str) -> str:\n        \"\"\"\n        Query what record of a layer a particular point is on.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :param layer_name: The non geometric polygonal layer name that we are interested in.\n        :return: The first token of a layer a particular point is on or '' if no layer is found.\n        \"\"\"\n        return self.explorer.record_on_point(x, y, layer_name)\n\n    def extract_polygon(self, polygon_token: str) -> Polygon:\n        \"\"\"\n        Construct a shapely Polygon object out of a polygon token.\n        :param polygon_token: The token of the polygon record.\n        :return: The polygon wrapped in a shapely Polygon object.\n        \"\"\"\n        return self.explorer.extract_polygon(polygon_token)\n\n    def extract_line(self, line_token: str) -> LineString:\n        \"\"\"\n        Construct a shapely LineString object out of a line token.\n        :param line_token: The token of the line record.\n        :return: The line wrapped in a LineString object.\n        \"\"\"\n        return self.explorer.extract_line(line_token)\n\n    def get_bounds(self, layer_name: str, token: str) -> Tuple[float, float, float, float]:\n        \"\"\"\n        Get the bounds of the geometric object that corresponds to a non geometric record.\n        :param layer_name: Name of the layer that we are interested in.\n        :param token: Token of the record.\n        :return: min_x, min_y, max_x, max_y of of the line representation.\n        \"\"\"\n        return self.explorer.get_bounds(layer_name, token)\n\n    def get_records_in_radius(self, x: float, y: float, radius: float,\n                              layer_names: List[str], mode: str = 'intersect') -> Dict[str, List[str]]:\n        \"\"\"\n        Get all the record tokens that intersect a square patch of side length 2*radius centered on (x,y).\n        :param x: X-coordinate in global frame.\n        :param y: y-coordinate in global frame.\n        :param radius: All records within radius meters of point (x, y) will be returned.\n        :param layer_names: Names of the layers that we want to retrieve. By default will always\n        look at the all non geometric layers.\n        :param mode: \"intersect\" will return all non geometric records that intersects the patch, \"within\" will return\n        all non geometric records that are within the patch.\n        :return: Dictionary of layer_name - tokens pairs.\n        \"\"\"\n\n        patch = (x - radius, y - radius, x + radius, y + radius)\n        return self.explorer.get_records_in_patch(patch, layer_names, mode=mode)\n\n    def discretize_centerlines(self, resolution_meters: float) -> List[np.array]:\n        \"\"\"\n        Discretize the centerlines of lanes and lane connectors.\n        :param resolution_meters: How finely to discretize the lane. Smaller values ensure curved\n            lanes are properly represented.\n        :return: A list of np.arrays with x, y and z values for each point.\n        \"\"\"\n        pose_lists = []\n        for lane in self.lane + self.lane_connector:\n            my_lane = self.arcline_path_3.get(lane['token'], [])\n            discretized = np.array(discretize_lane(my_lane, resolution_meters))\n            pose_lists.append(discretized)\n\n        return pose_lists\n\n    def discretize_lanes(self, tokens: List[str],\n                         resolution_meters: float) -> Dict[str, List[Tuple[float, float, float]]]:\n        \"\"\"\n        Discretizes a list of lane/lane connector tokens.\n        :param tokens: List of lane and/or lane connector record tokens. Can be retrieved with\n            get_records_in_radius or get_records_in_patch.\n        :param resolution_meters: How finely to discretize the splines.\n        :return: Mapping from lane/lane connector token to sequence of poses along the lane.\n        \"\"\"\n\n        return {ID: discretize_lane(self.arcline_path_3.get(ID, []), resolution_meters) for ID in tokens}\n\n    def _get_connected_lanes(self, lane_token: str, incoming_outgoing: str) -> List[str]:\n        \"\"\"\n        Helper for getting the lanes connected to a given lane\n        :param lane_token: Token for the lane.\n        :param incoming_outgoing: Whether to get incoming or outgoing lanes\n        :return: List of lane tokens this lane is connected to.\n        \"\"\"\n\n        if lane_token not in self.connectivity:\n            raise ValueError(f\"{lane_token} is not a valid lane.\")\n\n        return self.connectivity[lane_token][incoming_outgoing]\n\n    def get_outgoing_lane_ids(self, lane_token: str) -> List[str]:\n        \"\"\"\n        Get the out-going lanes.\n        :param lane_token: Token for the lane.\n        :return: List of lane tokens that start at the end of this lane.\n        \"\"\"\n\n        return self._get_connected_lanes(lane_token, 'outgoing')\n\n    def get_incoming_lane_ids(self, lane_token: str) -> List[str]:\n        \"\"\"\n        Get the incoming lanes.\n        :param lane_token: Token for the lane.\n        :return: List of lane tokens that end at the start of this lane.\n        \"\"\"\n\n        return self._get_connected_lanes(lane_token, 'incoming')\n\n    def get_arcline_path(self, lane_token: str) -> List[ArcLinePath]:\n        \"\"\"\n        Get the arcline path representation for a lane.\n        Note: This function was previously called `get_lane()`, but renamed to avoid confusion between lanes and\n              arcline paths.\n        :param lane_token: Token for the lane.\n        :return: Arc line path representation of the lane.\n        \"\"\"\n\n        arcline_path = self.arcline_path_3.get(lane_token)\n        if not arcline_path:\n            raise ValueError(f'Error: Lane with token {lane_token} does not have a valid arcline path!')\n\n        return arcline_path\n\n    def get_closest_lane(self, x: float, y: float, radius: float = 5) -> str:\n        \"\"\"\n        Get closest lane id within a radius of query point. The distance from a point (x, y) to a lane is\n        the minimum l2 distance from (x, y) to a point on the lane.\n        :param x: X coordinate in global coordinate frame.\n        :param y: Y Coordinate in global coordinate frame.\n        :param radius: Radius around point to consider.\n        :return: Lane id of closest lane within radius.\n        \"\"\"\n\n        lanes = self.get_records_in_radius(x, y, radius, ['lane', 'lane_connector'])\n        lanes = lanes['lane'] + lanes['lane_connector']\n\n        discrete_points = self.discretize_lanes(lanes, 0.5)\n\n        current_min = np.inf\n\n        min_id = \"\"\n        for lane_id, points in discrete_points.items():\n\n            distance = np.linalg.norm(np.array(points)[:, :2] - [x, y], axis=1).min()\n            if distance <= current_min:\n                current_min = distance\n                min_id = lane_id\n\n        return min_id\n\n    def render_next_roads(self,\n                          x: float,\n                          y: float,\n                          alpha: float = 0.5,\n                          figsize: Union[None, float, Tuple[float, float]] = None,\n                          bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Renders the possible next roads from a point of interest.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :param alpha: The opacity of each layer that gets rendered.\n        :param figsize: Size of the whole figure.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        \"\"\"\n        return self.explorer.render_next_roads(x, y, alpha, figsize=figsize, bitmap=bitmap)\n\n    def get_next_roads(self, x: float, y: float) -> Dict[str, List[str]]:\n        \"\"\"\n        Get the possible next roads from a point of interest.\n        Returns road_segment, road_block and lane.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :return: Dictionary of layer_name - tokens pairs.\n        \"\"\"\n        # Filter out irrelevant layers.\n        road_layers = ['road_segment', 'road_block', 'lane']\n        layers = self.explorer.layers_on_point(x, y)\n        rel_layers = {layer: layers[layer] for layer in road_layers}\n\n        # Pick most fine-grained road layer (lane, road_block, road_segment) object that contains the point.\n        rel_layer = None\n        rel_token = None\n        for layer in road_layers[::-1]:\n            if rel_layers[layer] != '':\n                rel_layer = layer\n                rel_token = rel_layers[layer]\n                break\n        assert rel_layer is not None, 'Error: No suitable layer in the specified point location!'\n\n        # Get all records that overlap with the bounding box of the selected road.\n        box_coords = self.explorer.get_bounds(rel_layer, rel_token)\n        intersect = self.explorer.get_records_in_patch(box_coords, road_layers, mode='intersect')\n\n        # Go through all objects within the bounding box.\n        result = {layer: [] for layer in road_layers}\n        if rel_layer == 'road_segment':\n            # For road segments, we do not have a direction.\n            # Return objects that have ANY exterior points in common with the relevant layer.\n            rel_exterior_nodes = self.get(rel_layer, rel_token)['exterior_node_tokens']\n            for layer in road_layers:\n                for token in intersect[layer]:\n                    exterior_nodes = self.get(layer, token)['exterior_node_tokens']\n                    if any(n in exterior_nodes for n in rel_exterior_nodes) \\\n                            and token != rel_layers[layer]:\n                        result[layer].append(token)\n        else:\n            # For lanes and road blocks, the next road is indicated by the edge line.\n            # Return objects where ALL edge line nodes are included in the exterior nodes.\n            to_edge_line = self.get(rel_layer, rel_token)['to_edge_line_token']\n            to_edge_nodes = self.get('line', to_edge_line)['node_tokens']\n            for layer in road_layers:\n                for token in intersect[layer]:\n                    exterior_nodes = self.get(layer, token)['exterior_node_tokens']\n                    if all(n in exterior_nodes for n in to_edge_nodes) \\\n                            and token != rel_layers[layer]:\n                        result[layer].append(token)\n        return result\n\n\nclass NuScenesMapExplorer:\n    \"\"\" Helper class to explore the nuScenes map data. \"\"\"\n    def __init__(self,\n                 map_api: NuScenesMap,\n                 representative_layers: Tuple[str] = ('drivable_area', 'lane', 'walkway'),\n                 color_map: dict = None):\n        \"\"\"\n        :param map_api: NuScenesMap database class.\n        :param representative_layers: These are the layers that we feel are representative of the whole mapping data.\n        :param color_map: Color map.\n        \"\"\"\n        # Mutable default argument.\n        if color_map is None:\n            color_map = dict(drivable_area='#a6cee3',\n                             road_segment='#1f78b4',\n                             road_block='#b2df8a',\n                             lane='#33a02c',\n                             ped_crossing='#fb9a99',\n                             walkway='#e31a1c',\n                             stop_line='#fdbf6f',\n                             carpark_area='#ff7f00',\n                             road_divider='#cab2d6',\n                             lane_divider='#6a3d9a',\n                             traffic_light='#7e772e')\n\n        self.map_api = map_api\n        self.representative_layers = representative_layers\n        self.color_map = color_map\n\n        self.canvas_max_x = self.map_api.canvas_edge[0]\n        self.canvas_min_x = 0\n        self.canvas_max_y = self.map_api.canvas_edge[1]\n        self.canvas_min_y = 0\n        self.canvas_aspect_ratio = (self.canvas_max_x - self.canvas_min_x) / (self.canvas_max_y - self.canvas_min_y)\n\n    def render_centerlines(self,\n                           resolution_meters: float,\n                           figsize: Union[None, float, Tuple[float, float]] = None,\n                           bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Render the centerlines of all lanes and lane connectors.\n        :param resolution_meters: How finely to discretize the lane. Smaller values ensure curved\n            lanes are properly represented.\n        :param figsize: Size of the figure.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        \"\"\"\n        # Discretize all lanes and lane connectors.\n        pose_lists = self.map_api.discretize_centerlines(resolution_meters)\n\n        # Render connectivity lines.\n        fig = plt.figure(figsize=self._get_figsize(figsize))\n        ax = fig.add_axes([0, 0, 1, 1 / self.canvas_aspect_ratio])\n\n        if bitmap is not None:\n            bitmap.render(self.map_api.canvas_edge, ax)\n\n        for pose_list in pose_lists:\n            if len(pose_list) > 0:\n                plt.plot(pose_list[:, 0], pose_list[:, 1])\n\n        return fig, ax\n\n    def render_map_mask(self,\n                        patch_box: Tuple[float, float, float, float],\n                        patch_angle: float,\n                        layer_names: List[str],\n                        canvas_size: Tuple[int, int],\n                        figsize: Tuple[int, int],\n                        n_row: int = 2) -> Tuple[Figure, List[Axes]]:\n        \"\"\"\n        Render map mask of the patch specified by patch_box and patch_angle.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n        :param layer_names: A list of layer names to be extracted.\n        :param canvas_size: Size of the output mask (h, w).\n        :param figsize: Size of the figure.\n        :param n_row: Number of rows with plots.\n        :return: The matplotlib figure and a list of axes of the rendered layers.\n        \"\"\"\n        if layer_names is None:\n            layer_names = self.map_api.non_geometric_layers\n\n        map_mask = self.get_map_mask(patch_box, patch_angle, layer_names, canvas_size)\n\n        # If no canvas_size is specified, retrieve the default from the output of get_map_mask.\n        if canvas_size is None:\n            canvas_size = map_mask.shape[1:]\n\n        fig = plt.figure(figsize=figsize)\n        ax = fig.add_axes([0, 0, 1, 1])\n        ax.set_xlim(0, canvas_size[1])\n        ax.set_ylim(0, canvas_size[0])\n\n        n_col = len(map_mask) // n_row\n        gs = gridspec.GridSpec(n_row, n_col)\n        gs.update(wspace=0.025, hspace=0.05)\n        for i in range(len(map_mask)):\n            r = i // n_col\n            c = i - r * n_col\n            subax = plt.subplot(gs[r, c])\n            subax.imshow(map_mask[i], origin='lower')\n            subax.text(canvas_size[0] * 0.5, canvas_size[1] * 1.1, layer_names[i])\n            subax.grid(False)\n\n        return fig, fig.axes\n\n    def get_map_geom(self,\n                     patch_box: Tuple[float, float, float, float],\n                     patch_angle: float,\n                     layer_names: List[str]) -> List[Tuple[str, List[Geometry]]]:\n        \"\"\"\n        Returns a list of geometries in the specified patch_box.\n        These are unscaled, but aligned with the patch angle.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n                            North-facing corresponds to 0.\n        :param layer_names: A list of layer names to be extracted, or None for all non-geometric layers.\n        :return: List of layer names and their corresponding geometries.\n        \"\"\"\n        # If None, return all geometric layers.\n        if layer_names is None:\n            layer_names = self.map_api.non_geometric_layers\n\n        # Get each layer name and geometry and store them in a list.\n        map_geom = []\n        for layer_name in layer_names:\n            layer_geom = self._get_layer_geom(patch_box, patch_angle, layer_name)\n            if layer_geom is None:\n                continue\n            map_geom.append((layer_name, layer_geom))\n\n        return map_geom\n\n    def map_geom_to_mask(self,\n                         map_geom: List[Tuple[str, List[Geometry]]],\n                         local_box: Tuple[float, float, float, float],\n                         canvas_size: Tuple[int, int]) -> np.ndarray:\n        \"\"\"\n        Return list of map mask layers of the specified patch.\n        :param map_geom: List of layer names and their corresponding geometries.\n        :param local_box: The local patch box defined as (x_center, y_center, height, width), where typically\n            x_center = y_center = 0.\n        :param canvas_size: Size of the output mask (h, w).\n        :return: Stacked numpy array of size [c x h x w] with c channels and the same height/width as the canvas.\n        \"\"\"\n        # Get each layer mask and stack them into a numpy tensor.\n        map_mask = []\n        for layer_name, layer_geom in map_geom:\n            layer_mask = self._layer_geom_to_mask(layer_name, layer_geom, local_box, canvas_size)\n            if layer_mask is not None:\n                map_mask.append(layer_mask)\n\n        return np.array(map_mask)\n\n    def get_map_mask(self,\n                     patch_box: Optional[Tuple[float, float, float, float]],\n                     patch_angle: float,\n                     layer_names: List[str] = None,\n                     canvas_size: Tuple[int, int] = (100, 100)) -> np.ndarray:\n        \"\"\"\n        Return list of map mask layers of the specified patch.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width]. If None, this plots the entire map.\n        :param patch_angle: Patch orientation in degrees. North-facing corresponds to 0.\n        :param layer_names: A list of layer names to be extracted, or None for all non-geometric layers.\n        :param canvas_size: Size of the output mask (h, w). If None, we use the default resolution of 10px/m.\n        :return: Stacked numpy array of size [c x h x w] with c channels and the same width/height as the canvas.\n        \"\"\"\n        # For some combination of parameters, we need to know the size of the current map.\n        if self.map_api.map_name == 'singapore-onenorth':\n            map_dims = [1585.6, 2025.0]\n        elif self.map_api.map_name == 'singapore-hollandvillage':\n            map_dims = [2808.3, 2922.9]\n        elif self.map_api.map_name == 'singapore-queenstown':\n            map_dims = [3228.6, 3687.1]\n        elif self.map_api.map_name == 'boston-seaport':\n            map_dims = [2979.5, 2118.1]\n        else:\n            raise Exception('Error: Invalid map!')\n\n        # If None, return the entire map.\n        if patch_box is None:\n            patch_box = [map_dims[0] / 2, map_dims[1] / 2, map_dims[1], map_dims[0]]\n\n        # If None, return all geometric layers.\n        if layer_names is None:\n            layer_names = self.map_api.non_geometric_layers\n\n        # If None, return the specified patch in the original scale of 10px/m.\n        if canvas_size is None:\n            map_scale = 10\n            canvas_size = np.array((patch_box[2], patch_box[3])) * map_scale\n            canvas_size = tuple(np.round(canvas_size).astype(np.int32))\n\n        # Get geometry of each layer.\n        map_geom = self.get_map_geom(patch_box, patch_angle, layer_names)\n\n        # Convert geometry of each layer into mask and stack them into a numpy tensor.\n        # Convert the patch box from global coordinates to local coordinates by setting the center to (0, 0).\n        local_box = (0.0, 0.0, patch_box[2], patch_box[3])\n        map_mask = self.map_geom_to_mask(map_geom, local_box, canvas_size)\n        assert np.all(map_mask.shape[1:] == canvas_size)\n\n        return map_mask\n\n    def render_record(self,\n                      layer_name: str,\n                      token: str,\n                      alpha: float = 0.5,\n                      figsize: Union[None, float, Tuple[float, float]] = None,\n                      other_layers: List[str] = None,\n                      bitmap: Optional[BitMap] = None) -> Tuple[Figure, Tuple[Axes, Axes]]:\n        \"\"\"\n        Render a single map record.\n        By default will also render 3 layers which are `drivable_area`, `lane`, and `walkway` unless specified by\n        `other_layers`.\n        :param layer_name: Name of the layer that we are interested in.\n        :param token: Token of the record that you want to render.\n        :param alpha: The opacity of each layer that gets rendered.\n        :param figsize: Size of the whole figure.\n        :param other_layers: What other layers to render aside from the one specified in `layer_name`.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: The matplotlib figure and axes of the rendered layers.\n        \"\"\"\n        if other_layers is None:\n            other_layers = list(self.representative_layers)\n\n        for other_layer in other_layers:\n            if other_layer not in self.map_api.non_geometric_layers:\n                raise ValueError(\"{} is not a non geometric layer\".format(layer_name))\n\n        x1, y1, x2, y2 = self.map_api.get_bounds(layer_name, token)\n\n        local_width = x2 - x1\n        local_height = y2 - y1\n        assert local_height > 0, 'Error: Map has 0 height!'\n        local_aspect_ratio = local_width / local_height\n\n        # We obtained the values 0.65 and 0.66 by trials.\n        fig = plt.figure(figsize=self._get_figsize(figsize))\n        global_ax = fig.add_axes([0, 0, 0.65, 0.65 / self.canvas_aspect_ratio])\n        local_ax = fig.add_axes([0.66, 0.66 / self.canvas_aspect_ratio, 0.34, 0.34 / local_aspect_ratio])\n\n        # To make sure the sequence of the layer overlays is always consistent after typesetting set().\n        random.seed('nutonomy')\n\n        if bitmap is not None:\n            bitmap.render(self.map_api.canvas_edge, global_ax)\n            bitmap.render(self.map_api.canvas_edge, local_ax)\n\n        layer_names = other_layers + [layer_name]\n        layer_names = list(set(layer_names))\n\n        for layer in layer_names:\n            self._render_layer(global_ax, layer, alpha)\n\n        for layer in layer_names:\n            self._render_layer(local_ax, layer, alpha)\n\n        if layer_name == 'drivable_area':\n            # Bad output aesthetically if we add spacing between the objects and the axes for drivable area.\n            local_ax_xlim = (x1, x2)\n            local_ax_ylim = (y1, y2)\n        else:\n            # Add some spacing between the object and the axes.\n            local_ax_xlim = (x1 - local_width / 3, x2 + local_width / 3)\n            local_ax_ylim = (y1 - local_height / 3, y2 + local_height / 3)\n\n            # Draws the rectangular patch on the local_ax.\n            local_ax.add_patch(Rectangle((x1, y1), local_width, local_height, linestyle='-.', color='red', fill=False,\n                                         lw=2))\n\n        local_ax.set_xlim(*local_ax_xlim)\n        local_ax.set_ylim(*local_ax_ylim)\n        local_ax.set_title('Local View')\n\n        global_ax.set_xlim(self.canvas_min_x, self.canvas_max_x)\n        global_ax.set_ylim(self.canvas_min_y, self.canvas_max_y)\n        global_ax.set_title('Global View')\n        global_ax.legend()\n\n        # Adds the zoomed in effect to the plot.\n        mark_inset(global_ax, local_ax, loc1=2, loc2=4)\n\n        return fig, (global_ax, local_ax)\n\n    def render_layers(self,\n                      layer_names: List[str],\n                      alpha: float,\n                      figsize: Union[None, float, Tuple[float, float]],\n                      tokens: List[str] = None,\n                      bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Render a list of layers.\n        :param layer_names: A list of layer names.\n        :param alpha: The opacity of each layer.\n        :param figsize: Size of the whole figure.\n        :param tokens: Optional list of tokens to render. None means all tokens are rendered.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: The matplotlib figure and axes of the rendered layers.\n        \"\"\"\n        fig = plt.figure(figsize=self._get_figsize(figsize))\n        ax = fig.add_axes([0, 0, 1, 1 / self.canvas_aspect_ratio])\n\n        ax.set_xlim(self.canvas_min_x, self.canvas_max_x)\n        ax.set_ylim(self.canvas_min_y, self.canvas_max_y)\n\n        if bitmap is not None:\n            bitmap.render(self.map_api.canvas_edge, ax)\n\n        layer_names = list(set(layer_names))\n        for layer_name in layer_names:\n            self._render_layer(ax, layer_name, alpha, tokens)\n\n        ax.legend()\n\n        return fig, ax\n\n    def render_map_patch(self,\n                         box_coords: Tuple[float, float, float, float],\n                         layer_names: List[str] = None,\n                         alpha: float = 0.5,\n                         figsize: Tuple[float, float] = (15, 15),\n                         render_egoposes_range: bool = True,\n                         render_legend: bool = True,\n                         bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Renders a rectangular patch specified by `box_coords`. By default renders all layers.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param layer_names: All the non geometric layers that we want to render.\n        :param alpha: The opacity of each layer.\n        :param figsize: Size of the whole figure.\n        :param render_egoposes_range: Whether to render a rectangle around all ego poses.\n        :param render_legend: Whether to render the legend of map layers.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: The matplotlib figure and axes of the rendered layers.\n        \"\"\"\n        x_min, y_min, x_max, y_max = box_coords\n\n        if layer_names is None:\n            layer_names = self.map_api.non_geometric_layers\n\n        fig = plt.figure(figsize=figsize)\n\n        local_width = x_max - x_min\n        local_height = y_max - y_min\n        assert local_height > 0, 'Error: Map patch has 0 height!'\n        local_aspect_ratio = local_width / local_height\n\n        ax = fig.add_axes([0, 0, 1, 1 / local_aspect_ratio])\n\n        if bitmap is not None:\n            bitmap.render(self.map_api.canvas_edge, ax)\n\n        for layer_name in layer_names:\n            self._render_layer(ax, layer_name, alpha)\n\n        x_margin = np.minimum(local_width / 4, 50)\n        y_margin = np.minimum(local_height / 4, 10)\n        ax.set_xlim(x_min - x_margin, x_max + x_margin)\n        ax.set_ylim(y_min - y_margin, y_max + y_margin)\n\n        if render_egoposes_range:\n            ax.add_patch(Rectangle((x_min, y_min), local_width, local_height, fill=False, linestyle='-.', color='red',\n                                   lw=2))\n            ax.text(x_min + local_width / 100, y_min + local_height / 2, \"%g m\" % local_height,\n                    fontsize=14, weight='bold')\n            ax.text(x_min + local_width / 2, y_min + local_height / 100, \"%g m\" % local_width,\n                    fontsize=14, weight='bold')\n\n        if render_legend:\n            ax.legend(frameon=True, loc='upper right')\n\n        return fig, ax\n\n    def render_map_in_image(self,\n                            nusc: NuScenes,\n                            sample_token: str,\n                            camera_channel: str = 'CAM_FRONT',\n                            alpha: float = 0.3,\n                            patch_radius: float = 10000,\n                            min_polygon_area: float = 1000,\n                            render_behind_cam: bool = True,\n                            render_outside_im: bool = True,\n                            layer_names: List[str] = None,\n                            verbose: bool = True,\n                            out_path: str = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Render a nuScenes camera image and overlay the polygons for the specified map layers.\n        Note that the projections are not always accurate as the localization is in 2d.\n        :param nusc: The NuScenes instance to load the image from.\n        :param sample_token: The image's corresponding sample_token.\n        :param camera_channel: Camera channel name, e.g. 'CAM_FRONT'.\n        :param alpha: The transparency value of the layers to render in [0, 1].\n        :param patch_radius: The radius in meters around the ego car in which to select map records.\n        :param min_polygon_area: Minimum area a polygon needs to have to be rendered.\n        :param render_behind_cam: Whether to render polygons where any point is behind the camera.\n        :param render_outside_im: Whether to render polygons where any point is outside the image.\n        :param layer_names: The names of the layers to render, e.g. ['lane'].\n            If set to None, the recommended setting will be used.\n        :param verbose: Whether to print to stdout.\n        :param out_path: Optional path to save the rendered figure to disk.\n        \"\"\"\n        near_plane = 1e-8\n\n        if verbose:\n            print('Warning: Note that the projections are not always accurate as the localization is in 2d.')\n\n        # Default layers.\n        if layer_names is None:\n            layer_names = ['road_segment', 'lane', 'ped_crossing', 'walkway', 'stop_line', 'carpark_area']\n\n        # Check layers whether we can render them.\n        for layer_name in layer_names:\n            assert layer_name in self.map_api.non_geometric_polygon_layers, \\\n                'Error: Can only render non-geometry polygons: %s' % layer_names\n\n        # Check that NuScenesMap was loaded for the correct location.\n        sample_record = nusc.get('sample', sample_token)\n        scene_record = nusc.get('scene', sample_record['scene_token'])\n        log_record = nusc.get('log', scene_record['log_token'])\n        log_location = log_record['location']\n        assert self.map_api.map_name == log_location, \\\n            'Error: NuScenesMap loaded for location %s, should be %s!' % (self.map_api.map_name, log_location)\n\n        # Grab the front camera image and intrinsics.\n        cam_token = sample_record['data'][camera_channel]\n        cam_record = nusc.get('sample_data', cam_token)\n        cam_path = nusc.get_sample_data_path(cam_token)\n        im = Image.open(cam_path)\n        im_size = im.size\n        cs_record = nusc.get('calibrated_sensor', cam_record['calibrated_sensor_token'])\n        cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n\n        # Retrieve the current map.\n        poserecord = nusc.get('ego_pose', cam_record['ego_pose_token'])\n        ego_pose = poserecord['translation']\n        box_coords = (\n            ego_pose[0] - patch_radius,\n            ego_pose[1] - patch_radius,\n            ego_pose[0] + patch_radius,\n            ego_pose[1] + patch_radius,\n        )\n        records_in_patch = self.get_records_in_patch(box_coords, layer_names, 'intersect')\n\n        # Init axes.\n        fig = plt.figure(figsize=(9, 16))\n        ax = fig.add_axes([0, 0, 1, 1])\n        ax.set_xlim(0, im_size[0])\n        ax.set_ylim(0, im_size[1])\n        ax.imshow(im)\n\n        # Retrieve and render each record.\n        for layer_name in layer_names:\n            for token in records_in_patch[layer_name]:\n                record = self.map_api.get(layer_name, token)\n                if layer_name == 'drivable_area':\n                    polygon_tokens = record['polygon_tokens']\n                else:\n                    polygon_tokens = [record['polygon_token']]\n\n                for polygon_token in polygon_tokens:\n                    polygon = self.map_api.extract_polygon(polygon_token)\n\n                    # Convert polygon nodes to pointcloud with 0 height.\n                    points = np.array(polygon.exterior.xy)\n                    points = np.vstack((points, np.zeros((1, points.shape[1]))))\n\n                    # Transform into the ego vehicle frame for the timestamp of the image.\n                    points = points - np.array(poserecord['translation']).reshape((-1, 1))\n                    points = np.dot(Quaternion(poserecord['rotation']).rotation_matrix.T, points)\n\n                    # Transform into the camera.\n                    points = points - np.array(cs_record['translation']).reshape((-1, 1))\n                    points = np.dot(Quaternion(cs_record['rotation']).rotation_matrix.T, points)\n\n                    # Remove points that are partially behind the camera.\n                    depths = points[2, :]\n                    behind = depths < near_plane\n                    if np.all(behind):\n                        continue\n\n                    if render_behind_cam:\n                        # Perform clipping on polygons that are partially behind the camera.\n                        points = NuScenesMapExplorer._clip_points_behind_camera(points, near_plane)\n                    elif np.any(behind):\n                        # Otherwise ignore any polygon that is partially behind the camera.\n                        continue\n\n                    # Ignore polygons with less than 3 points after clipping.\n                    if len(points) == 0 or points.shape[1] < 3:\n                        continue\n\n                    # Take the actual picture (matrix multiplication with camera-matrix + renormalization).\n                    points = view_points(points, cam_intrinsic, normalize=True)\n\n                    # Skip polygons where all points are outside the image.\n                    # Leave a margin of 1 pixel for aesthetic reasons.\n                    inside = np.ones(points.shape[1], dtype=bool)\n                    inside = np.logical_and(inside, points[0, :] > 1)\n                    inside = np.logical_and(inside, points[0, :] < im.size[0] - 1)\n                    inside = np.logical_and(inside, points[1, :] > 1)\n                    inside = np.logical_and(inside, points[1, :] < im.size[1] - 1)\n                    if render_outside_im:\n                        if np.all(np.logical_not(inside)):\n                            continue\n                    else:\n                        if np.any(np.logical_not(inside)):\n                            continue\n\n                    points = points[:2, :]\n                    points = [(p0, p1) for (p0, p1) in zip(points[0], points[1])]\n                    polygon_proj = Polygon(points)\n\n                    # Filter small polygons\n                    if polygon_proj.area < min_polygon_area:\n                        continue\n\n                    label = layer_name\n                    ax.add_patch(descartes.PolygonPatch(polygon_proj, fc=self.color_map[layer_name], alpha=alpha,\n                                                        label=label))\n\n        # Display the image.\n        plt.axis('off')\n        ax.invert_yaxis()\n\n        if out_path is not None:\n            plt.tight_layout()\n            plt.savefig(out_path, bbox_inches='tight', pad_inches=0)\n\n        return fig, ax\n\n    @staticmethod\n    def points_transform(points, poserecord, cs_record, cam_intrinsic, im_size, near_plane=1e-8,\n                         render_behind_cam=True, render_outside_im=True):\n        points = np.vstack((points, np.zeros((1, points.shape[1]))))\n\n        # Transform into the ego vehicle frame for the timestamp of the image.\n        points = points - np.array(poserecord['translation']).reshape((-1, 1))\n        points = np.dot(Quaternion(poserecord['rotation']).rotation_matrix.T, points)\n\n        # Transform into the camera.\n        points = points - np.array(cs_record['translation']).reshape((-1, 1))\n        points = np.dot(Quaternion(cs_record['rotation']).rotation_matrix.T, points)\n\n        # Remove points that are partially behind the camera.\n        depths = points[2, :]\n        behind = depths < near_plane\n        if np.all(behind):\n            return None\n\n        if render_behind_cam:\n            # Perform clipping on polygons that are partially behind the camera.\n            points = NuScenesMapExplorer._clip_points_behind_camera(points, near_plane)\n\n        elif np.any(behind):\n            # Otherwise ignore any polygon that is partially behind the camera.\n            return None\n\n        # Take the actual picture (matrix multiplication with camera-matrix + renormalization).\n        points = view_points(points, cam_intrinsic, normalize=True)\n\n        # Skip polygons where all points are outside the image.\n        # Leave a margin of 1 pixel for aesthetic reasons.\n        inside = np.ones(points.shape[1], dtype=bool)\n        inside = np.logical_and(inside, points[0, :] > 1)\n        inside = np.logical_and(inside, points[0, :] < im_size[0] - 1)\n        inside = np.logical_and(inside, points[1, :] > 1)\n        inside = np.logical_and(inside, points[1, :] < im_size[1] - 1)\n\n        if render_outside_im:\n            if np.all(np.logical_not(inside)):\n                return None\n        else:\n            if np.any(np.logical_not(inside)):\n                return None\n\n        # points = points[:, inside]\n\n        # Ignore polygons with less than 3 points after clipping.\n        if len(points) == 0 or points.shape[1] < 3:\n            return None\n\n        points = points[:2, :]\n        points = [(p0, p1) for (p0, p1) in zip(points[0], points[1])]\n        return points\n\n    def get_map_mask_in_image(self,\n                              nusc: NuScenes,\n                              sample_token: str,\n                              camera_channel: str = 'CAM_FRONT',\n                              alpha: float = 0.3,\n                              patch_radius: float = 10000,\n                              min_polygon_area: float = 1000,\n                              render_behind_cam: bool = True,\n                              render_outside_im: bool = True,\n                              layer_names: List[str] = None,\n                              verbose: bool = False,\n                              out_path: str = None) -> np.ndarray:\n        \"\"\"\n        Render a nuScenes camera image and overlay the polygons for the specified map layers.\n        Note that the projections are not always accurate as the localization is in 2d.\n        :param nusc: The NuScenes instance to load the image from.\n        :param sample_token: The image's corresponding sample_token.\n        :param camera_channel: Camera channel name, e.g. 'CAM_FRONT'.\n        :param alpha: The transparency value of the layers to render in [0, 1].\n        :param patch_radius: The radius in meters around the ego car in which to select map records.\n        :param min_polygon_area: Minimum area a polygon needs to have to be rendered.\n        :param render_behind_cam: Whether to render polygons where any point is behind the camera.\n        :param render_outside_im: Whether to render polygons where any point is outside the image.\n        :param layer_names: The names of the layers to render, e.g. ['lane'].\n            If set to None, the recommended setting will be used.\n        :param verbose: Whether to print to stdout.\n        :param out_path: Optional path to save the rendered figure to disk.\n        \"\"\"\n        near_plane = 1e-8\n        if verbose:\n            print('Warning: Note that the projections are not always accurate as the localization is in 2d.')\n\n        # Default layers.\n        if layer_names is None:\n            layer_names = ['road_segment', 'lane', 'ped_crossing', 'walkway', 'stop_line', 'carpark_area']\n\n        # # Check layers whether we can render them.\n        # for layer_name in layer_names:\n        #     assert layer_name in self.map_api.non_geometric_polygon_layers, \\\n        #         'Error: Can only render non-geometry polygons: %s' % layer_names\n\n        # Check that NuScenesMap was loaded for the correct location.\n        sample_record = nusc.get('sample', sample_token)\n        scene_record = nusc.get('scene', sample_record['scene_token'])\n        log_record = nusc.get('log', scene_record['log_token'])\n        log_location = log_record['location']\n        assert self.map_api.map_name == log_location, \\\n            'Error: NuScenesMap loaded for location %s, should be %s!' % (self.map_api.map_name, log_location)\n\n        # Grab the front camera image and intrinsics.\n        cam_token = sample_record['data'][camera_channel]\n        cam_record = nusc.get('sample_data', cam_token)\n        cam_path = nusc.get_sample_data_path(cam_token)\n        im = Image.open(cam_path)\n        im_size = im.size\n        cs_record = nusc.get('calibrated_sensor', cam_record['calibrated_sensor_token'])\n        cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n\n        # Retrieve the current map.\n        poserecord = nusc.get('ego_pose', cam_record['ego_pose_token'])\n        ego_pose = poserecord['translation']\n        box_coords = (\n            ego_pose[0] - patch_radius,\n            ego_pose[1] - patch_radius,\n            ego_pose[0] + patch_radius,\n            ego_pose[1] + patch_radius,\n        )\n        records_in_patch = self.get_records_in_patch(box_coords, layer_names, 'intersect')\n\n        if out_path is not None:\n            # Init axes.\n            fig = plt.figure(figsize=(9, 16))\n            ax = fig.add_axes([0, 0, 1, 1])\n            ax.set_xlim(0, im_size[0])\n            ax.set_ylim(0, im_size[1])\n            ax.imshow(im)\n\n        points_transform = partial(self.points_transform, poserecord=poserecord, cs_record=cs_record,\n                                   cam_intrinsic=cam_intrinsic, near_plane=near_plane, im_size=im_size,\n                                   render_behind_cam=render_behind_cam, render_outside_im=render_outside_im)\n\n        # Retrieve and render each record.\n        map_geom = []\n        for layer_name in layer_names:\n            if layer_name in self.map_api.non_geometric_line_layers:\n                line_list = []\n                for token in records_in_patch[layer_name]:\n                    record = self.map_api.get(layer_name, token)\n                    line = self.map_api.extract_line(record['line_token'])\n                    if line.is_empty:  # Skip lines without nodes.\n                        continue\n                    points = np.array(line.xy)\n                    points = points_transform(points)\n                    if points is None:\n                        continue\n                    line = LineString(points)\n                    line_list.append(line)\n                    # For visualize\n                    if out_path is not None:\n                        polygon = Polygon(points)\n                        ax.add_patch(descartes.PolygonPatch(polygon, fc=self.color_map[layer_name],\n                                                            alpha=alpha, label=layer_name))\n                map_geom.append((layer_name, line_list))\n            elif layer_name == 'drivable_area':\n                polygon_list = []\n                for token in records_in_patch[layer_name]:\n                    record = self.map_api.get(layer_name, token)\n                    polygons = [self.map_api.extract_polygon(polygon_token) for polygon_token in\n                                record['polygon_tokens']]\n                    for polygon in polygons:\n                        ex_points = np.array(polygon.exterior.xy)\n                        ex_points = points_transform(ex_points)\n                        if ex_points is None:\n                            continue\n                        interiors = []\n                        for interior in polygon.interiors:\n                            in_points = np.array(interior.xy)\n                            in_points = points_transform(in_points)\n                            if in_points is None:\n                                continue\n                            interiors.append(in_points)\n                        polygon = Polygon(ex_points, interiors)\n                        polygon = polygon.buffer(0.01)\n                        if polygon.geom_type == 'Polygon':\n                            polygon = MultiPolygon([polygon])\n                        # Filter small polygons\n                        if polygon.area < min_polygon_area:\n                            continue\n                        polygon_list.append(polygon)\n                        # For visualize\n                        if out_path is not None:\n                            ax.add_patch(descartes.PolygonPatch(polygon, fc=self.color_map[layer_name],\n                                                                alpha=alpha, label=layer_name))\n                map_geom.append((layer_name, polygon_list))\n            else:\n                polygon_list = []\n                for token in records_in_patch[layer_name]:\n                    record = self.map_api.get(layer_name, token)\n                    polygon = self.map_api.extract_polygon(record['polygon_token'])\n                    if polygon.is_valid:\n                        if not polygon.is_empty:\n                            ex_points = np.array(polygon.exterior.xy)\n                            ex_points = points_transform(ex_points)\n                            if ex_points is None:\n                                continue\n                            interiors = []\n                            for interior in polygon.interiors:\n                                in_points = np.array(interior.xy)\n                                in_points = points_transform(in_points)\n                                if in_points is None:\n                                    continue\n                                interiors.append(in_points)\n                            polygon = Polygon(ex_points, interiors)\n                            polygon = polygon.buffer(0.01)\n                            if polygon.geom_type == 'Polygon':\n                                polygon = MultiPolygon([polygon])\n                            # Filter small polygons\n                            if polygon.area < min_polygon_area:\n                                continue\n                            polygon_list.append(polygon)\n                            # For visualize\n                            if out_path is not None:\n                                ax.add_patch(descartes.PolygonPatch(polygon, fc=self.color_map[layer_name],\n                                                                    alpha=alpha, label=layer_name))\n                map_geom.append((layer_name, polygon_list))\n\n        # For visualize\n        if out_path is not None:\n            # Display the image.\n            plt.axis('off')\n            ax.invert_yaxis()\n            plt.tight_layout()\n            plt.savefig(out_path, bbox_inches='tight', pad_inches=0)\n            plt.close()\n\n        # Convert geometry of each layer into mask and stack them into a numpy tensor.\n        # Convert the patch box from global coordinates to local coordinates by setting the center to (0, 0).\n        local_box = (im_size[0] // 2, im_size[1] // 2, im_size[1], im_size[0])\n        canvas_size = (im_size[1], im_size[0])\n        img_mask = self.map_geom_to_mask(map_geom, local_box, canvas_size)\n        assert np.all(img_mask.shape[1:] == canvas_size)\n        return img_mask\n\n    def render_egoposes_on_fancy_map(self,\n                                     nusc: NuScenes,\n                                     scene_tokens: List = None,\n                                     verbose: bool = True,\n                                     out_path: str = None,\n                                     render_egoposes: bool = True,\n                                     render_egoposes_range: bool = True,\n                                     render_legend: bool = True,\n                                     bitmap: Optional[BitMap] = None) -> Tuple[np.ndarray, Figure, Axes]:\n        \"\"\"\n        Renders each ego pose of a list of scenes on the map (around 40 poses per scene).\n        This method is heavily inspired by NuScenes.render_egoposes_on_map(), but uses the map expansion pack maps.\n        Note that the maps are constantly evolving, whereas we only released a single snapshot of the data.\n        Therefore for some scenes there is a bad fit between ego poses and maps.\n        :param nusc: The NuScenes instance to load the ego poses from.\n        :param scene_tokens: Optional list of scene tokens corresponding to the current map location.\n        :param verbose: Whether to show status messages and progress bar.\n        :param out_path: Optional path to save the rendered figure to disk.\n        :param render_egoposes: Whether to render ego poses.\n        :param render_egoposes_range: Whether to render a rectangle around all ego poses.\n        :param render_legend: Whether to render the legend of map layers.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        :return: <np.float32: n, 2>. Returns a matrix with n ego poses in global map coordinates.\n        \"\"\"\n        # Settings\n        patch_margin = 2\n        min_diff_patch = 30\n\n        # Ids of scenes with a bad match between localization and map.\n        scene_blacklist = [499, 515, 517]\n\n        # Get logs by location.\n        log_location = self.map_api.map_name\n        log_tokens = [log['token'] for log in nusc.log if log['location'] == log_location]\n        assert len(log_tokens) > 0, 'Error: This split has 0 scenes for location %s!' % log_location\n\n        # Filter scenes.\n        scene_tokens_location = [e['token'] for e in nusc.scene if e['log_token'] in log_tokens]\n        if scene_tokens is not None:\n            scene_tokens_location = [t for t in scene_tokens_location if t in scene_tokens]\n        assert len(scene_tokens_location) > 0, 'Error: Found 0 valid scenes for location %s!' % log_location\n\n        map_poses = []\n        if verbose:\n            print('Adding ego poses to map...')\n        for scene_token in tqdm(scene_tokens_location, disable=not verbose):\n            # Check that the scene is from the correct location.\n            scene_record = nusc.get('scene', scene_token)\n            scene_name = scene_record['name']\n            scene_id = int(scene_name.replace('scene-', ''))\n            log_record = nusc.get('log', scene_record['log_token'])\n            assert log_record['location'] == log_location, \\\n                'Error: The provided scene_tokens do not correspond to the provided map location!'\n\n            # Print a warning if the localization is known to be bad.\n            if verbose and scene_id in scene_blacklist:\n                print('Warning: %s is known to have a bad fit between ego pose and map.' % scene_name)\n\n            # For each sample in the scene, store the ego pose.\n            sample_tokens = nusc.field2token('sample', 'scene_token', scene_token)\n            for sample_token in sample_tokens:\n                sample_record = nusc.get('sample', sample_token)\n\n                # Poses are associated with the sample_data. Here we use the lidar sample_data.\n                sample_data_record = nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])\n                pose_record = nusc.get('ego_pose', sample_data_record['ego_pose_token'])\n\n                # Calculate the pose on the map and append.\n                map_poses.append(pose_record['translation'])\n\n        # Check that ego poses aren't empty.\n        assert len(map_poses) > 0, 'Error: Found 0 ego poses. Please check the inputs.'\n\n        # Compute number of close ego poses.\n        if verbose:\n            print('Creating plot...')\n        map_poses = np.vstack(map_poses)[:, :2]\n\n        # Render the map patch with the current ego poses.\n        min_patch = np.floor(map_poses.min(axis=0) - patch_margin)\n        max_patch = np.ceil(map_poses.max(axis=0) + patch_margin)\n        diff_patch = max_patch - min_patch\n        if any(diff_patch < min_diff_patch):\n            center_patch = (min_patch + max_patch) / 2\n            diff_patch = np.maximum(diff_patch, min_diff_patch)\n            min_patch = center_patch - diff_patch / 2\n            max_patch = center_patch + diff_patch / 2\n        my_patch = (min_patch[0], min_patch[1], max_patch[0], max_patch[1])\n        fig, ax = self.render_map_patch(my_patch, self.map_api.non_geometric_layers, figsize=(10, 10),\n                                        render_egoposes_range=render_egoposes_range,\n                                        render_legend=render_legend, bitmap=bitmap)\n\n        # Plot in the same axis as the map.\n        # Make sure these are plotted \"on top\".\n        if render_egoposes:\n            ax.scatter(map_poses[:, 0], map_poses[:, 1], s=20, c='k', alpha=1.0, zorder=2)\n        plt.axis('off')\n\n        if out_path is not None:\n            plt.savefig(out_path, bbox_inches='tight', pad_inches=0)\n\n        return map_poses, fig, ax\n\n    def render_next_roads(self,\n                          x: float,\n                          y: float,\n                          alpha: float = 0.5,\n                          figsize: Union[None, float, Tuple[float, float]] = None,\n                          bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]:\n        \"\"\"\n        Renders the possible next roads from a point of interest.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :param alpha: The opacity of each layer that gets rendered.\n        :param figsize: Size of the whole figure.\n        :param bitmap: Optional BitMap object to render below the other map layers.\n        \"\"\"\n        # Get next roads.\n        next_roads = self.map_api.get_next_roads(x, y)\n        layer_names = []\n        tokens = []\n        for layer_name, layer_tokens in next_roads.items():\n            if len(layer_tokens) > 0:\n                layer_names.append(layer_name)\n                tokens.extend(layer_tokens)\n\n        # Render them.\n        fig, ax = self.render_layers(layer_names, alpha, figsize, tokens=tokens, bitmap=bitmap)\n\n        # Render current location with an x.\n        ax.plot(x, y, 'x', markersize=12, color='red')\n\n        return fig, ax\n\n    @staticmethod\n    def _clip_points_behind_camera(points, near_plane: float):\n        \"\"\"\n        Perform clipping on polygons that are partially behind the camera.\n        This method is necessary as the projection does not work for points behind the camera.\n        Hence we compute the line between the point and the camera and follow that line until we hit the near plane of\n        the camera. Then we use that point.\n        :param points: <np.float32: 3, n> Matrix of points, where each point (x, y, z) is along each column.\n        :param near_plane: If we set the near_plane distance of the camera to 0 then some points will project to\n            infinity. Therefore we need to clip these points at the near plane.\n        :return: The clipped version of the polygon. This may have fewer points than the original polygon if some lines\n            were entirely behind the polygon.\n        \"\"\"\n        points_clipped = []\n        # Loop through each line on the polygon.\n        # For each line where exactly 1 endpoints is behind the camera, move the point along the line until\n        # it hits the near plane of the camera (clipping).\n        assert points.shape[0] == 3\n        point_count = points.shape[1]\n        for line_1 in range(point_count):\n            line_2 = (line_1 + 1) % point_count\n            point_1 = points[:, line_1]\n            point_2 = points[:, line_2]\n            z_1 = point_1[2]\n            z_2 = point_2[2]\n\n            if z_1 >= near_plane and z_2 >= near_plane:\n                # Both points are in front.\n                # Add both points unless the first is already added.\n                if len(points_clipped) == 0 or all(points_clipped[-1] != point_1):\n                    points_clipped.append(point_1)\n                points_clipped.append(point_2)\n            elif z_1 < near_plane and z_2 < near_plane:\n                # Both points are in behind.\n                # Don't add anything.\n                continue\n            else:\n                # One point is in front, one behind.\n                # By convention pointA is behind the camera and pointB in front.\n                if z_1 <= z_2:\n                    point_a = points[:, line_1]\n                    point_b = points[:, line_2]\n                else:\n                    point_a = points[:, line_2]\n                    point_b = points[:, line_1]\n                z_a = point_a[2]\n                z_b = point_b[2]\n\n                # Clip line along near plane.\n                pointdiff = point_b - point_a\n                alpha = (near_plane - z_b) / (z_a - z_b)\n                clipped = point_a + (1 - alpha) * pointdiff\n                assert np.abs(clipped[2] - near_plane) < 1e-6\n\n                # Add the first point (if valid and not duplicate), the clipped point and the second point (if valid).\n                if z_1 >= near_plane and (len(points_clipped) == 0 or all(points_clipped[-1] != point_1)):\n                    points_clipped.append(point_1)\n                points_clipped.append(clipped)\n                if z_2 >= near_plane:\n                    points_clipped.append(point_2)\n\n        points_clipped = np.array(points_clipped).transpose()\n        return points_clipped\n\n    def get_records_in_patch(self,\n                             box_coords: Tuple[float, float, float, float],\n                             layer_names: List[str] = None,\n                             mode: str = 'intersect') -> Dict[str, List[str]]:\n        \"\"\"\n        Get all the record token that intersects or within a particular rectangular patch.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param layer_names: Names of the layers that we want to retrieve in a particular patch.\n            By default will always look for all non geometric layers.\n        :param mode: \"intersect\" will return all non geometric records that intersects the patch,\n            \"within\" will return all non geometric records that are within the patch.\n        :return: Dictionary of layer_name - tokens pairs.\n        \"\"\"\n        if mode not in ['intersect', 'within']:\n            raise ValueError(\"Mode {} is not valid, choice=('intersect', 'within')\".format(mode))\n\n        if layer_names is None:\n            layer_names = self.map_api.non_geometric_layers\n\n        records_in_patch = dict()\n        for layer_name in layer_names:\n            layer_records = []\n            for record in getattr(self.map_api, layer_name):\n                token = record['token']\n                if self.is_record_in_patch(layer_name, token, box_coords, mode):\n                    layer_records.append(token)\n\n            records_in_patch.update({layer_name: layer_records})\n\n        return records_in_patch\n\n    def is_record_in_patch(self,\n                           layer_name: str,\n                           token: str,\n                           box_coords: Tuple[float, float, float, float],\n                           mode: str = 'intersect') -> bool:\n        \"\"\"\n        Query whether a particular record is in a rectangular patch.\n        :param layer_name: The layer name of the record.\n        :param token: The record token.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param mode: \"intersect\" means it will return True if the geometric object intersects the patch and False\n        otherwise, \"within\" will return True if the geometric object is within the patch and False otherwise.\n        :return: Boolean value on whether a particular record intersects or is within a particular patch.\n        \"\"\"\n        if mode not in ['intersect', 'within']:\n            raise ValueError(\"Mode {} is not valid, choice=('intersect', 'within')\".format(mode))\n\n        if layer_name in self.map_api.lookup_polygon_layers:\n            return self._is_polygon_record_in_patch(token, layer_name, box_coords, mode)\n        elif layer_name in self.map_api.non_geometric_line_layers:\n            return self._is_line_record_in_patch(token, layer_name, box_coords,  mode)\n        else:\n            raise ValueError(\"{} is not a valid layer\".format(layer_name))\n\n    def layers_on_point(self, x: float, y: float, layer_names: List[str] = None) -> Dict[str, str]:\n        \"\"\"\n        Returns all the polygonal layers that a particular point is on.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :param layer_names: The names of the layers to search for.\n        :return: All the polygonal layers that a particular point is on.\n        \"\"\"\n        # Default option.\n        if layer_names is None:\n            layer_names = self.map_api.non_geometric_polygon_layers\n\n        layers_on_point = dict()\n        for layer_name in layer_names:\n            layers_on_point.update({layer_name: self.record_on_point(x, y, layer_name)})\n\n        return layers_on_point\n\n    def record_on_point(self, x: float, y: float, layer_name: str) -> str:\n        \"\"\"\n        Query what record of a layer a particular point is on.\n        :param x: x coordinate of the point of interest.\n        :param y: y coordinate of the point of interest.\n        :param layer_name: The non geometric polygonal layer name that we are interested in.\n        :return: The first token of a layer a particular point is on or '' if no layer is found.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_polygon_layers:\n            raise ValueError(\"{} is not a polygon layer\".format(layer_name))\n\n        point = Point(x, y)\n        records = getattr(self.map_api, layer_name)\n\n        if layer_name == 'drivable_area':\n            for record in records:\n                polygons = [self.map_api.extract_polygon(polygon_token) for polygon_token in record['polygon_tokens']]\n                for polygon in polygons:\n                    if point.within(polygon):\n                        return record['token']\n                    else:\n                        pass\n        else:\n            for record in records:\n                polygon = self.map_api.extract_polygon(record['polygon_token'])\n                if point.within(polygon):\n                    return record['token']\n                else:\n                    pass\n\n        # If nothing is found, return an empty string.\n        return ''\n\n    def extract_polygon(self, polygon_token: str) -> Polygon:\n        \"\"\"\n        Construct a shapely Polygon object out of a polygon token.\n        :param polygon_token: The token of the polygon record.\n        :return: The polygon wrapped in a shapely Polygon object.\n        \"\"\"\n        polygon_record = self.map_api.get('polygon', polygon_token)\n\n        exterior_coords = [(self.map_api.get('node', token)['x'], self.map_api.get('node', token)['y'])\n                           for token in polygon_record['exterior_node_tokens']]\n\n        interiors = []\n        for hole in polygon_record['holes']:\n            interior_coords = [(self.map_api.get('node', token)['x'], self.map_api.get('node', token)['y'])\n                               for token in hole['node_tokens']]\n            if len(interior_coords) > 0:  # Add only non-empty holes.\n                interiors.append(interior_coords)\n\n        return Polygon(exterior_coords, interiors)\n\n    def extract_line(self, line_token: str) -> LineString:\n        \"\"\"\n        Construct a shapely LineString object out of a line token.\n        :param line_token: The token of the line record.\n        :return: The line wrapped in a LineString object.\n        \"\"\"\n        line_record = self.map_api.get('line', line_token)\n        line_nodes = [(self.map_api.get('node', token)['x'], self.map_api.get('node', token)['y'])\n                      for token in line_record['node_tokens']]\n\n        return LineString(line_nodes)\n\n    def get_bounds(self, layer_name: str, token: str) -> Tuple[float, float, float, float]:\n        \"\"\"\n        Get the bounds of the geometric object that corresponds to a non geometric record.\n        :param layer_name: Name of the layer that we are interested in.\n        :param token: Token of the record.\n        :return: min_x, min_y, max_x, max_y of the line representation.\n        \"\"\"\n        if layer_name in self.map_api.non_geometric_polygon_layers:\n            return self._get_polygon_bounds(layer_name, token)\n        elif layer_name in self.map_api.non_geometric_line_layers:\n            return self._get_line_bounds(layer_name, token)\n        else:\n            raise ValueError(\"{} is not a valid layer\".format(layer_name))\n\n    def _get_polygon_bounds(self, layer_name: str, token: str) -> Tuple[float, float, float, float]:\n        \"\"\"\n        Get the extremities of the polygon object that corresponds to a non geometric record.\n        :param layer_name: Name of the layer that we are interested in.\n        :param token: Token of the record.\n        :return: min_x, min_y, max_x, max_y of of the polygon or polygons (for drivable_area) representation.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_polygon_layers:\n            raise ValueError(\"{} is not a record with polygon representation\".format(token))\n\n        record = self.map_api.get(layer_name, token)\n\n        if layer_name == 'drivable_area':\n            polygons = [self.map_api.get('polygon', polygon_token) for polygon_token in record['polygon_tokens']]\n            exterior_node_coords = []\n\n            for polygon in polygons:\n                nodes = [self.map_api.get('node', node_token) for node_token in polygon['exterior_node_tokens']]\n                node_coords = [(node['x'], node['y']) for node in nodes]\n                exterior_node_coords.extend(node_coords)\n\n            exterior_node_coords = np.array(exterior_node_coords)\n        else:\n            exterior_nodes = [self.map_api.get('node', token) for token in record['exterior_node_tokens']]\n            exterior_node_coords = np.array([(node['x'], node['y']) for node in exterior_nodes])\n\n        xs = exterior_node_coords[:, 0]\n        ys = exterior_node_coords[:, 1]\n\n        x2 = xs.max()\n        x1 = xs.min()\n        y2 = ys.max()\n        y1 = ys.min()\n\n        return x1, y1, x2, y2\n\n    def _get_line_bounds(self, layer_name: str, token: str) -> Tuple[float, float, float, float]:\n        \"\"\"\n        Get the bounds of the line object that corresponds to a non geometric record.\n        :param layer_name: Name of the layer that we are interested in.\n        :param token: Token of the record.\n        :return: min_x, min_y, max_x, max_y of of the line representation.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_line_layers:\n            raise ValueError(\"{} is not a record with line representation\".format(token))\n\n        record = self.map_api.get(layer_name, token)\n        nodes = [self.map_api.get('node', node_token) for node_token in record['node_tokens']]\n        node_coords = [(node['x'], node['y']) for node in nodes]\n        node_coords = np.array(node_coords)\n\n        xs = node_coords[:, 0]\n        ys = node_coords[:, 1]\n\n        x2 = xs.max()\n        x1 = xs.min()\n        y2 = ys.max()\n        y1 = ys.min()\n\n        return x1, y1, x2, y2\n\n    def _is_polygon_record_in_patch(self,\n                                    token: str,\n                                    layer_name: str,\n                                    box_coords: Tuple[float, float, float, float],\n                                    mode: str = 'intersect') -> bool:\n        \"\"\"\n        Query whether a particular polygon record is in a rectangular patch.\n        :param layer_name: The layer name of the record.\n        :param token: The record token.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param mode: \"intersect\" means it will return True if the geometric object intersects the patch and False\n        otherwise, \"within\" will return True if the geometric object is within the patch and False otherwise.\n        :return: Boolean value on whether a particular polygon record intersects or is within a particular patch.\n        \"\"\"\n        if layer_name not in self.map_api.lookup_polygon_layers:\n            raise ValueError('{} is not a polygonal layer'.format(layer_name))\n\n        x_min, y_min, x_max, y_max = box_coords\n        record = self.map_api.get(layer_name, token)\n        rectangular_patch = box(x_min, y_min, x_max, y_max)\n\n        if layer_name == 'drivable_area':\n            polygons = [self.map_api.extract_polygon(polygon_token) for polygon_token in record['polygon_tokens']]\n            geom = MultiPolygon(polygons)\n        else:\n            geom = self.map_api.extract_polygon(record['polygon_token'])\n\n        if mode == 'intersect':\n            return geom.intersects(rectangular_patch)\n        elif mode == 'within':\n            return geom.within(rectangular_patch)\n\n    def _is_line_record_in_patch(self,\n                                 token: str,\n                                 layer_name: str,\n                                 box_coords: Tuple[float, float, float, float],\n                                 mode: str = 'intersect') -> bool:\n        \"\"\"\n        Query whether a particular line record is in a rectangular patch.\n        :param layer_name: The layer name of the record.\n        :param token: The record token.\n        :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max).\n        :param mode: \"intersect\" means it will return True if the geometric object intersects the patch and False\n        otherwise, \"within\" will return True if the geometric object is within the patch and False otherwise.\n        :return: Boolean value on whether a particular line  record intersects or is within a particular patch.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_line_layers:\n            raise ValueError(\"{} is not a line layer\".format(layer_name))\n\n        # Retrieve nodes of this line.\n        record = self.map_api.get(layer_name, token)\n        node_recs = [self.map_api.get('node', node_token) for node_token in record['node_tokens']]\n        node_coords = [[node['x'], node['y']] for node in node_recs]\n        node_coords = np.array(node_coords)\n\n        # A few lines in Queenstown have zero nodes. In this case we return False.\n        if len(node_coords) == 0:\n            return False\n\n        # Check that nodes fall inside the path.\n        x_min, y_min, x_max, y_max = box_coords\n        cond_x = np.logical_and(node_coords[:, 0] < x_max, node_coords[:, 0] > x_min)\n        cond_y = np.logical_and(node_coords[:, 1] < y_max, node_coords[:, 1] > y_min)\n        cond = np.logical_and(cond_x, cond_y)\n        if mode == 'intersect':\n            return np.any(cond)\n        elif mode == 'within':\n            return np.all(cond)\n\n    def _render_layer(self, ax: Axes, layer_name: str, alpha: float, tokens: List[str] = None) -> None:\n        \"\"\"\n        Wrapper method that renders individual layers on an axis.\n        :param ax: The matplotlib axes where the layer will get rendered.\n        :param layer_name: Name of the layer that we are interested in.\n        :param alpha: The opacity of the layer to be rendered.\n        :param tokens: Optional list of tokens to render. None means all tokens are rendered.\n        \"\"\"\n        if layer_name in self.map_api.non_geometric_polygon_layers:\n            self._render_polygon_layer(ax, layer_name, alpha, tokens)\n        elif layer_name in self.map_api.non_geometric_line_layers:\n            self._render_line_layer(ax, layer_name, alpha, tokens)\n        else:\n            raise ValueError(\"{} is not a valid layer\".format(layer_name))\n\n    def _render_polygon_layer(self, ax: Axes, layer_name: str, alpha: float, tokens: List[str] = None) -> None:\n        \"\"\"\n        Renders an individual non-geometric polygon layer on an axis.\n        :param ax: The matplotlib axes where the layer will get rendered.\n        :param layer_name: Name of the layer that we are interested in.\n        :param alpha: The opacity of the layer to be rendered.\n        :param tokens: Optional list of tokens to render. None means all tokens are rendered.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_polygon_layers:\n            raise ValueError('{} is not a polygonal layer'.format(layer_name))\n\n        first_time = True\n        records = getattr(self.map_api, layer_name)\n        if tokens is not None:\n            records = [r for r in records if r['token'] in tokens]\n        if layer_name == 'drivable_area':\n            for record in records:\n                polygons = [self.map_api.extract_polygon(polygon_token) for polygon_token in record['polygon_tokens']]\n\n                for polygon in polygons:\n                    if first_time:\n                        label = layer_name\n                        first_time = False\n                    else:\n                        label = None\n                    ax.add_patch(descartes.PolygonPatch(polygon, fc=self.color_map[layer_name], alpha=alpha,\n                                                        label=label))\n        else:\n            for record in records:\n                polygon = self.map_api.extract_polygon(record['polygon_token'])\n\n                if first_time:\n                    label = layer_name\n                    first_time = False\n                else:\n                    label = None\n\n                ax.add_patch(descartes.PolygonPatch(polygon, fc=self.color_map[layer_name], alpha=alpha,\n                                                    label=label))\n\n    def _render_line_layer(self, ax: Axes, layer_name: str, alpha: float, tokens: List[str] = None) -> None:\n        \"\"\"\n        Renders an individual non-geometric line layer on an axis.\n        :param ax: The matplotlib axes where the layer will get rendered.\n        :param layer_name: Name of the layer that we are interested in.\n        :param alpha: The opacity of the layer to be rendered.\n        :param tokens: Optional list of tokens to render. None means all tokens are rendered.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_line_layers:\n            raise ValueError(\"{} is not a line layer\".format(layer_name))\n\n        first_time = True\n        records = getattr(self.map_api, layer_name)\n        if tokens is not None:\n            records = [r for r in records if r['token'] in tokens]\n        for record in records:\n            if first_time:\n                label = layer_name\n                first_time = False\n            else:\n                label = None\n            line = self.map_api.extract_line(record['line_token'])\n            if line.is_empty:  # Skip lines without nodes\n                continue\n            xs, ys = line.xy\n\n            if layer_name == 'traffic_light':\n                # Draws an arrow with the physical traffic light as the starting point, pointing to the direction on\n                # where the traffic light points.\n                ax.add_patch(Arrow(xs[0], ys[0], xs[1]-xs[0], ys[1]-ys[0], color=self.color_map[layer_name],\n                                   label=label))\n            else:\n                ax.plot(xs, ys, color=self.color_map[layer_name], alpha=alpha, label=label)\n\n    def _get_layer_geom(self,\n                        patch_box: Tuple[float, float, float, float],\n                        patch_angle: float,\n                        layer_name: str) -> List[Geometry]:\n        \"\"\"\n        Wrapper method that gets the geometries for each layer.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n        :param layer_name: Name of map layer to be converted to binary map mask patch.\n        :return: List of geometries for the given layer.\n        \"\"\"\n        if layer_name in self.map_api.non_geometric_polygon_layers:\n            return self._get_layer_polygon(patch_box, patch_angle, layer_name)\n        elif layer_name in self.map_api.non_geometric_line_layers:\n            return self._get_layer_line(patch_box, patch_angle, layer_name)\n        else:\n            raise ValueError(\"{} is not a valid layer\".format(layer_name))\n\n    def _layer_geom_to_mask(self,\n                            layer_name: str,\n                            layer_geom: List[Geometry],\n                            local_box: Tuple[float, float, float, float],\n                            canvas_size: Tuple[int, int]) -> np.ndarray:\n        \"\"\"\n        Wrapper method that gets the mask for each layer's geometries.\n        :param layer_name: The name of the layer for which we get the masks.\n        :param layer_geom: List of the geometries of the layer specified in layer_name.\n        :param local_box: The local patch box defined as (x_center, y_center, height, width), where typically\n            x_center = y_center = 0.\n        :param canvas_size: Size of the output mask (h, w).\n        \"\"\"\n        if layer_name in self.map_api.non_geometric_polygon_layers:\n            return self._polygon_geom_to_mask(layer_geom, local_box, layer_name, canvas_size)\n        elif layer_name in self.map_api.non_geometric_line_layers:\n            return self._line_geom_to_mask(layer_geom, local_box, layer_name, canvas_size)\n        else:\n            raise ValueError(\"{} is not a valid layer\".format(layer_name))\n\n    @staticmethod\n    def mask_for_polygons(polygons: MultiPolygon, mask: np.ndarray) -> np.ndarray:\n        \"\"\"\n        Convert a polygon or multipolygon list to an image mask ndarray.\n        :param polygons: List of Shapely polygons to be converted to numpy array.\n        :param mask: Canvas where mask will be generated.\n        :return: Numpy ndarray polygon mask.\n        \"\"\"\n        if not polygons:\n            return mask\n\n        def int_coords(x):\n            # function to round and convert to int\n            return np.array(x).round().astype(np.int32)\n        exteriors = [int_coords(poly.exterior.coords) for poly in polygons]\n        interiors = [int_coords(pi.coords) for poly in polygons for pi in poly.interiors]\n        cv2.fillPoly(mask, exteriors, 1)\n        cv2.fillPoly(mask, interiors, 0)\n        return mask\n\n    @staticmethod\n    def mask_for_lines(lines: LineString, mask: np.ndarray) -> np.ndarray:\n        \"\"\"\n        Convert a Shapely LineString back to an image mask ndarray.\n        :param lines: List of shapely LineStrings to be converted to a numpy array.\n        :param mask: Canvas where mask will be generated.\n        :return: Numpy ndarray line mask.\n        \"\"\"\n        if lines.geom_type == 'MultiLineString':\n            for line in lines:\n                coords = np.asarray(list(line.coords), np.int32)\n                coords = coords.reshape((-1, 2))\n                cv2.polylines(mask, [coords], False, 1, 2)\n        else:\n            coords = np.asarray(list(lines.coords), np.int32)\n            coords = coords.reshape((-1, 2))\n            cv2.polylines(mask, [coords], False, 1, 2)\n\n        return mask\n\n    def _polygon_geom_to_mask(self,\n                              layer_geom: List[Polygon],\n                              local_box: Tuple[float, float, float, float],\n                              layer_name: str,\n                              canvas_size: Tuple[int, int]) -> np.ndarray:\n        \"\"\"\n        Convert polygon inside patch to binary mask and return the map patch.\n        :param layer_geom: list of polygons for each map layer\n        :param local_box: The local patch box defined as (x_center, y_center, height, width), where typically\n            x_center = y_center = 0.\n        :param layer_name: name of map layer to be converted to binary map mask patch.\n        :param canvas_size: Size of the output mask (h, w).\n        :return: Binary map mask patch with the size canvas_size.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_polygon_layers:\n            raise ValueError('{} is not a polygonal layer'.format(layer_name))\n\n        patch_x, patch_y, patch_h, patch_w = local_box\n\n        patch = self.get_patch_coord(local_box)\n\n        canvas_h = canvas_size[0]\n        canvas_w = canvas_size[1]\n\n        scale_height = canvas_h / patch_h\n        scale_width = canvas_w / patch_w\n\n        trans_x = -patch_x + patch_w / 2.0\n        trans_y = -patch_y + patch_h / 2.0\n\n        map_mask = np.zeros(canvas_size, np.uint8)\n\n        for polygon in layer_geom:\n            new_polygon = polygon.intersection(patch)\n            if not new_polygon.is_empty:\n                new_polygon = affinity.affine_transform(new_polygon,\n                                                        [1.0, 0.0, 0.0, 1.0, trans_x, trans_y])\n                new_polygon = affinity.scale(new_polygon, xfact=scale_width, yfact=scale_height, origin=(0, 0))\n\n                if new_polygon.geom_type == 'Polygon':\n                    new_polygon = MultiPolygon([new_polygon])\n\n                # if new_polygon.area < 1000:\n                #     continue\n\n                if not isinstance(new_polygon, MultiPolygon):\n                    print(new_polygon)\n                    \n                    continue\n\n                map_mask = self.mask_for_polygons(new_polygon, map_mask)\n\n        return map_mask\n\n    def _line_geom_to_mask(self,\n                           layer_geom: List[LineString],\n                           local_box: Tuple[float, float, float, float],\n                           layer_name: str,\n                           canvas_size: Tuple[int, int]) -> Optional[np.ndarray]:\n        \"\"\"\n        Convert line inside patch to binary mask and return the map patch.\n        :param layer_geom: list of LineStrings for each map layer\n        :param local_box: The local patch box defined as (x_center, y_center, height, width), where typically\n            x_center = y_center = 0.\n        :param layer_name: name of map layer to be converted to binary map mask patch.\n        :param canvas_size: Size of the output mask (h, w).\n        :return: Binary map mask patch in a canvas size.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_line_layers:\n            raise ValueError(\"{} is not a line layer\".format(layer_name))\n\n        patch_x, patch_y, patch_h, patch_w = local_box\n\n        patch = self.get_patch_coord(local_box)\n\n        canvas_h = canvas_size[0]\n        canvas_w = canvas_size[1]\n        scale_height = canvas_h/patch_h\n        scale_width = canvas_w/patch_w\n\n        trans_x = -patch_x + patch_w / 2.0\n        trans_y = -patch_y + patch_h / 2.0\n\n        map_mask = np.zeros(canvas_size, np.uint8)\n\n        if layer_name == 'traffic_light':\n            return None\n\n        for line in layer_geom:\n            new_line = line.intersection(patch)\n            if not new_line.is_empty:\n                new_line = affinity.affine_transform(new_line,\n                                                     [1.0, 0.0, 0.0, 1.0, trans_x, trans_y])\n                new_line = affinity.scale(new_line, xfact=scale_width, yfact=scale_height, origin=(0, 0))\n\n                map_mask = self.mask_for_lines(new_line, map_mask)\n        return map_mask\n\n    def _get_layer_polygon(self,\n                           patch_box: Tuple[float, float, float, float],\n                           patch_angle: float,\n                           layer_name: str) -> List[Polygon]:\n        \"\"\"\n         Retrieve the polygons of a particular layer within the specified patch.\n         :param patch_box: Patch box defined as [x_center, y_center, height, width].\n         :param patch_angle: Patch orientation in degrees.\n         :param layer_name: name of map layer to be extracted.\n         :return: List of Polygon in a patch box.\n         \"\"\"\n        if layer_name not in self.map_api.non_geometric_polygon_layers:\n            raise ValueError('{} is not a polygonal layer'.format(layer_name))\n\n        patch_x = patch_box[0]\n        patch_y = patch_box[1]\n\n        patch = self.get_patch_coord(patch_box, patch_angle)\n\n        records = getattr(self.map_api, layer_name)\n\n        polygon_list = []\n        if layer_name == 'drivable_area':\n            for record in records:\n                polygons = [self.map_api.extract_polygon(polygon_token) for polygon_token in record['polygon_tokens']]\n\n                for polygon in polygons:\n                    new_polygon = polygon.intersection(patch)\n                    if not new_polygon.is_empty:\n                        new_polygon = affinity.rotate(new_polygon, -patch_angle,\n                                                      origin=(patch_x, patch_y), use_radians=False)\n                        new_polygon = affinity.affine_transform(new_polygon,\n                                                                [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                        if new_polygon.geom_type == 'Polygon':\n                            new_polygon = MultiPolygon([new_polygon])\n                        polygon_list.append(new_polygon)\n\n        else:\n            for record in records:\n                polygon = self.map_api.extract_polygon(record['polygon_token'])\n\n                if polygon.is_valid:\n                    new_polygon = polygon.intersection(patch)\n                    if not new_polygon.is_empty:\n                        new_polygon = affinity.rotate(new_polygon, -patch_angle,\n                                                      origin=(patch_x, patch_y), use_radians=False)\n                        new_polygon = affinity.affine_transform(new_polygon,\n                                                                [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                        if new_polygon.geom_type == 'Polygon':\n                            new_polygon = MultiPolygon([new_polygon])\n                        polygon_list.append(new_polygon)\n\n        return polygon_list\n\n    def _get_layer_line(self,\n                        patch_box: Tuple[float, float, float, float],\n                        patch_angle: float,\n                        layer_name: str) -> Optional[List[LineString]]:\n        \"\"\"\n        Retrieve the lines of a particular layer within the specified patch.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n        :param layer_name: name of map layer to be converted to binary map mask patch.\n        :return: List of LineString in a patch box.\n        \"\"\"\n        if layer_name not in self.map_api.non_geometric_line_layers:\n            raise ValueError(\"{} is not a line layer\".format(layer_name))\n\n        if layer_name == 'traffic_light':\n            return None\n\n        patch_x = patch_box[0]\n        patch_y = patch_box[1]\n\n        patch = self.get_patch_coord(patch_box, patch_angle)\n\n        line_list = []\n        records = getattr(self.map_api, layer_name)\n        for record in records:\n            line = self.map_api.extract_line(record['line_token'])\n            if line.is_empty:  # Skip lines without nodes.\n                continue\n\n            new_line = line.intersection(patch)\n            if not new_line.is_empty:\n                new_line = affinity.rotate(new_line, -patch_angle,\n                                           origin=(patch_x, patch_y), use_radians=False)\n                new_line = affinity.affine_transform(new_line,\n                                                     [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                line_list.append(new_line)\n\n        return line_list\n\n    @staticmethod\n    def get_patch_coord(patch_box: Tuple[float, float, float, float],\n                        patch_angle: float = 0.0) -> Polygon:\n        \"\"\"\n        Convert patch_box to shapely Polygon coordinates.\n        :param patch_box: Patch box defined as [x_center, y_center, height, width].\n        :param patch_angle: Patch orientation in degrees.\n        :return: Box Polygon for patch_box.\n        \"\"\"\n        patch_x, patch_y, patch_h, patch_w = patch_box\n\n        x_min = patch_x - patch_w / 2.0\n        y_min = patch_y - patch_h / 2.0\n        x_max = patch_x + patch_w / 2.0\n        y_max = patch_y + patch_h / 2.0\n\n        patch = box(x_min, y_min, x_max, y_max)\n        patch = affinity.rotate(patch, patch_angle, origin=(patch_x, patch_y), use_radians=False)\n\n        return patch\n\n    def _get_figsize(self, figsize: Union[None, float, Tuple[float, float]]) -> Tuple[float, float]:\n        \"\"\"\n        Utility function that scales the figure size by the map canvas size.\n        If figsize is:\n        - None      => Return default scale.\n        - Scalar    => Scale canvas size.\n        - Two-tuple => Use the specified figure size.\n        :param figsize: The input figure size.\n        :return: The output figure size.\n        \"\"\"\n        # Divide canvas size by arbitrary scalar to get into cm range.\n        canvas_size = np.array(self.map_api.canvas_edge)[::-1] / 200\n\n        if figsize is None:\n            return tuple(canvas_size)\n        elif type(figsize) in [int, float]:\n            return tuple(canvas_size * figsize)\n        elif type(figsize) == tuple and len(figsize) == 2:\n            return figsize\n        else:\n            raise Exception('Error: Invalid figsize: %s' % figsize)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/eval_utils/metric_utils.py",
    "content": "import torch\nimport math\nimport numpy as np\nfrom typing import List, Dict, Tuple, Callable, Union\n\ndef min_ade(traj: torch.Tensor, traj_gt: torch.Tensor,\n            masks: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Computes average displacement error for the best trajectory is a set,\n    with respect to ground truth\n    :param traj: predictions, shape [batch_size, num_modes, sequence_length, 2]\n    :param traj_gt: ground truth trajectory, shape\n    [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth, shape\n    [batch_size, sequence_length]\n    :return errs, inds: errors and indices for modes with min error, shape\n    [batch_size]\n    \"\"\"\n    num_modes = traj.shape[1]\n    traj_gt_rpt = traj_gt.unsqueeze(1).repeat(1, num_modes, 1, 1)\n    masks_rpt = masks.unsqueeze(1).repeat(1, num_modes, 1)\n    err = traj_gt_rpt - traj[:, :, :, 0:2]\n    err = torch.pow(err, exponent=2)\n    err = torch.sum(err, dim=3)\n    err = torch.pow(err, exponent=0.5)\n    err = torch.sum(err * (1 - masks_rpt), dim=2) / \\\n        torch.clip(torch.sum((1 - masks_rpt), dim=2), min=1)\n    err, inds = torch.min(err, dim=1)\n\n    return err, inds\n\n\ndef min_fde(traj: torch.Tensor, traj_gt: torch.Tensor,\n            masks: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Computes final displacement error for the best trajectory is a set,\n    with respect to ground truth\n    :param traj: predictions, shape [batch_size, num_modes, sequence_length, 2]\n    :param traj_gt: ground truth trajectory, shape\n    [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth, shape\n    [batch_size, sequence_length]\n    :return errs, inds: errors and indices for modes with min error,\n    shape [batch_size]\n    \"\"\"\n    num_modes = traj.shape[1]\n    traj_gt_rpt = traj_gt.unsqueeze(1).repeat(1, num_modes, 1, 1)\n    lengths = torch.sum(1 - masks, dim=1).long()\n    inds = lengths.unsqueeze(1).unsqueeze(\n        2).unsqueeze(3).repeat(1, num_modes, 1, 2) - 1\n\n    traj_last = torch.gather(traj[..., :2], dim=2, index=inds).squeeze(2)\n    traj_gt_last = torch.gather(traj_gt_rpt, dim=2, index=inds).squeeze(2)\n\n    err = traj_gt_last - traj_last[..., 0:2]\n    err = torch.pow(err, exponent=2)\n    err = torch.sum(err, dim=2)\n    err = torch.pow(err, exponent=0.5)\n    err, inds = torch.min(err, dim=1)\n\n    return err, inds\n\n\ndef miss_rate(\n        traj: torch.Tensor,\n        traj_gt: torch.Tensor,\n        masks: torch.Tensor,\n        dist_thresh: float = 2) -> torch.Tensor:\n    \"\"\"\n    Computes miss rate for mini batch of trajectories,\n    with respect to ground truth and given distance threshold\n    :param traj: predictions, shape [batch_size, num_modes, sequence_length, 2]\n    :param traj_gt: ground truth trajectory,\n    shape [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth,\n    shape [batch_size, sequence_length]\n    :param dist_thresh: distance threshold for computing miss rate.\n    :return errs, inds: errors and indices for modes with min error,\n    shape [batch_size]\n    \"\"\"\n    num_modes = traj.shape[1]\n\n    traj_gt_rpt = traj_gt.unsqueeze(1).repeat(1, num_modes, 1, 1)\n    masks_rpt = masks.unsqueeze(1).repeat(1, num_modes, 1)\n    dist = traj_gt_rpt - traj[:, :, :, 0:2]\n    dist = torch.pow(dist, exponent=2)\n    dist = torch.sum(dist, dim=3)\n    dist = torch.pow(dist, exponent=0.5)\n    dist[masks_rpt.bool()] = -math.inf\n    dist, _ = torch.max(dist, dim=2)\n    dist, _ = torch.min(dist, dim=1)\n    m_r = torch.sum(torch.as_tensor(dist > dist_thresh)) / len(dist)\n\n    return m_r\n\ndef traj_fde(gt_box, pred_box, final_step):\n    if gt_box.traj.shape[0] <= 0:\n        return np.inf\n    final_step = min(gt_box.traj.shape[0], final_step)\n    gt_final = gt_box.traj[None, final_step-1]\n    pred_final = np.array(pred_box.traj)[:,final_step-1,:]\n    err = gt_final - pred_final\n    err = np.sqrt(np.sum(np.square(gt_final - pred_final), axis=-1))\n    return np.min(err)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/eval_utils/nuscenes_eval.py",
    "content": "import argparse\nimport copy\nimport json\nimport numpy as np\nimport os\nimport time\nfrom typing import Tuple, Dict, Any\nimport tqdm\nfrom matplotlib import pyplot as plt\nfrom pyquaternion import Quaternion\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import load_prediction, load_gt, add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.common.render import setup_axis\nfrom nuscenes.eval.detection.algo import accumulate, calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import TP_METRICS, TP_METRICS_UNITS, PRETTY_DETECTION_NAMES, PRETTY_TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, DetectionMetricDataList\nfrom nuscenes.eval.detection.evaluate import NuScenesEval\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, dist_pr_curve\nfrom nuscenes.eval.tracking.data_classes import TrackingBox\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points, BoxVisibility\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.detection.utils import category_to_detection_name\n\n\nAxis = Any\n\ndef class_tp_curve(md_list: DetectionMetricDataList,\n                   metrics: DetectionMetrics,\n                   detection_name: str,\n                   min_recall: float,\n                   dist_th_tp: float,\n                   savepath: str = None,\n                   ax: Axis = None) -> None:\n    \"\"\"\n    Plot the true positive curve for the specified class.\n    :param md_list: DetectionMetricDataList instance.\n    :param metrics: DetectionMetrics instance.\n    :param detection_name:\n    :param min_recall: Minimum recall value.\n    :param dist_th_tp: The distance threshold used to determine matches.\n    :param savepath: If given, saves the the rendering here instead of displaying.\n    :param ax: Axes onto which to render.\n    \"\"\"\n    # Get metric data for given detection class with tp distance threshold.\n\n    md = md_list[(detection_name, dist_th_tp)]\n    min_recall_ind = round(100 * min_recall)\n    if min_recall_ind <= md.max_recall_ind:\n        # For traffic_cone and barrier only a subset of the metrics are plotted.\n        rel_metrics = [m for m in TP_METRICS if not np.isnan(metrics.get_label_tp(detection_name, m))]\n        ylimit = max([max(getattr(md, metric)[min_recall_ind:md.max_recall_ind + 1]) for metric in rel_metrics]) * 1.1\n    else:\n        ylimit = 1.0\n\n    # Prepare axis.\n    if ax is None:\n        ax = setup_axis(title=PRETTY_DETECTION_NAMES[detection_name], xlabel='Recall', ylabel='Error', xlim=1,\n                        min_recall=min_recall)\n    ax.set_ylim(0, ylimit)\n\n    # Plot the recall vs. error curve for each tp metric.\n    for metric in TP_METRICS:\n        tp = metrics.get_label_tp(detection_name, metric)\n\n        # Plot only if we have valid data.\n        if tp is not np.nan and min_recall_ind <= md.max_recall_ind:\n            recall, error = md.recall[:md.max_recall_ind + 1], getattr(md, metric)[:md.max_recall_ind + 1]\n        else:\n            recall, error = [], []\n\n        # Change legend based on tp value\n        if tp is np.nan:\n            label = '{}: n/a'.format(PRETTY_TP_METRICS[metric])\n        elif min_recall_ind > md.max_recall_ind:\n            label = '{}: nan'.format(PRETTY_TP_METRICS[metric])\n        else:\n            label = '{}: {:.2f} ({})'.format(PRETTY_TP_METRICS[metric], tp, TP_METRICS_UNITS[metric])\n        if metric == 'trans_err':\n            label += f' ({md.max_recall_ind})'  # add recall\n            print(f'Recall: {detection_name}: {md.max_recall_ind/100}')\n        ax.plot(recall, error, label=label)\n    ax.axvline(x=md.max_recall, linestyle='-.', color=(0, 0, 0, 0.3))\n    ax.legend(loc='best')\n\n    if savepath is not None:\n        plt.savefig(savepath)\n        plt.close()\n\n\nclass DetectionBox_modified(DetectionBox):\n    def __init__(self, *args, token=None, visibility=None, index=None, **kwargs):\n        '''\n        add annotation token\n        '''\n        super().__init__(*args, **kwargs)\n        self.token = token\n        self.visibility = visibility\n        self.index = index\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'token': self.token,\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'visibility': self.visibility,\n            'index': self.index\n\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(\n            token=content['token'],\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name'],\n            visibility=content['visibility'],\n            index=content['index'],\n        )\n\n\ndef center_in_image(box, intrinsic: np.ndarray, imsize: Tuple[int, int], vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible inside an image without accounting for occlusions.\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    center_3d = box.center.reshape(3, 1)\n    center_img = view_points(center_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(center_img[0, :] > 0, center_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, center_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, center_img[1, :] > 0)\n    visible = np.logical_and(visible, center_3d[2, :] > 1)\n\n    in_front = center_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if vis_level == BoxVisibility.ALL:\n        return all(visible) and all(in_front)\n    elif vis_level == BoxVisibility.ANY:\n        return any(visible) and all(in_front)\n    elif vis_level == BoxVisibility.NONE:\n        return True\n    else:\n        raise ValueError(\"vis_level: {} not valid\".format(vis_level))\n\n\ndef exist_corners_in_image_but_not_all(box, intrinsic: np.ndarray, imsize: Tuple[int, int],\n                                       vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible in images but not all corners in image .\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    corners_3d = box.corners()\n    corners_img = view_points(corners_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(corners_img[0, :] > 0, corners_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, corners_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, corners_img[1, :] > 0)\n    visible = np.logical_and(visible, corners_3d[2, :] > 1)\n\n    in_front = corners_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if any(visible) and not all(visible) and all(in_front):\n        return True\n    else:\n        return False\n\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False):\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n\n    # Init.\n    if box_cls == DetectionBox_modified:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n    index_map = {}\n    for scene in nusc.scene:\n        first_sample_token = scene['first_sample_token']\n        sample = nusc.get('sample', first_sample_token)\n        index_map[first_sample_token] = 1\n        index = 2\n        while sample['next'] != '':\n            sample = nusc.get('sample', sample['next'])\n            index_map[sample['token']] = index\n            index += 1\n\n    sample_tokens = []\n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n\n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == DetectionBox_modified:\n                # Get label name in detection task and filter unused labels.\n                detection_name = category_to_detection_name(sample_annotation['category_name'])\n                if detection_name is None:\n                    continue\n\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n\n                sample_boxes.append(\n                    box_cls(\n                        token=sample_annotation_token,\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        visibility=sample_annotation['visibility_token'],\n                        index=index_map[sample_token]\n                    )\n                )\n            elif box_cls == TrackingBox:\n                assert False\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\n\ndef filter_eval_boxes_by_id(nusc: NuScenes,\n                            eval_boxes: EvalBoxes,\n                            id=None,\n                            verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.token in id:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_visibility(\n        ori_eval_boxes: EvalBoxes,\n        visibility=None,\n        verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.visibility == visibility:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After visibility based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_by_sample_token(ori_eval_boxes, valid_sample_tokens=[],  verbose=False):\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    for sample_token in eval_boxes.sample_tokens:\n        if sample_token not in valid_sample_tokens:\n            eval_boxes.boxes.pop(sample_token)\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_overlap(nusc: NuScenes,\n                                 eval_boxes: EvalBoxes,\n                                 verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. basedon overlap .\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    cams = ['CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_BACK_RIGHT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_FRONT_LEFT']\n\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        sample_record = nusc.get('sample', sample_token)\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            count = 0\n            for cam in cams:\n                '''\n                copy-paste form nuscens\n                '''\n                sample_data_token = sample_record['data'][cam]\n                sd_record = nusc.get('sample_data', sample_data_token)\n                cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n                sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n                pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n                cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n                imsize = (sd_record['width'], sd_record['height'])\n                new_box = Box(box.translation, box.size, Quaternion(box.rotation),\n                              name=box.detection_name, token='')\n\n                # Move box to ego vehicle coord system.\n                new_box.translate(-np.array(pose_record['translation']))\n                new_box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n                #  Move box to sensor coord system.\n                new_box.translate(-np.array(cs_record['translation']))\n                new_box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n                if center_in_image(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                    count += 1\n                # if exist_corners_in_image_but_not_all(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                #    count += 1\n\n            if count > 1:\n                with open('center_overlap.txt', 'a') as f:\n                    try:\n                        f.write(box.token + '\\n')\n                    except:\n                        pass\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    verbose = True\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\nclass NuScenesEval_custom(NuScenesEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as DetectionEval.\n    \"\"\"\n\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 overlap_test=False,\n                 eval_mask=False,\n                 data_infos=None\n                 ):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n        self.overlap_test = overlap_test\n        self.eval_mask = eval_mask\n        self.data_infos = data_infos\n        # Check result file exists.\n        assert os.path.exists(result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, DetectionBox,\n                                                     verbose=verbose)\n        self.gt_boxes = load_gt(self.nusc, self.eval_set, DetectionBox_modified, verbose=verbose)\n\n        # assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n        #     \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        # Filter boxes (distance, points per box, etc.).\n\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(nusc, self.pred_boxes, self.cfg.class_range, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(nusc, self.gt_boxes, self.cfg.class_range, verbose=verbose)\n\n        if self.overlap_test:\n            self.pred_boxes = filter_eval_boxes_by_overlap(self.nusc, self.pred_boxes)\n\n            self.gt_boxes = filter_eval_boxes_by_overlap(self.nusc, self.gt_boxes, verbose=True)\n\n        self.all_gt = copy.deepcopy(self.gt_boxes)\n        self.all_preds = copy.deepcopy(self.pred_boxes)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n        self.index_map = {}\n        for scene in nusc.scene:\n            first_sample_token = scene['first_sample_token']\n            sample = nusc.get('sample', first_sample_token)\n            self.index_map[first_sample_token] = 1\n            index = 2\n            while sample['next'] != '':\n                sample = nusc.get('sample', sample['next'])\n                self.index_map[sample['token']] = index\n                index += 1\n\n    def update_gt(self, type_='vis', visibility='1', index=1):\n        if type_ == 'vis':\n            self.visibility_test = True\n            if self.visibility_test:\n                '''[{'description': 'visibility of whole object is between 0 and 40%',\n                'token': '1',\n                'level': 'v0-40'},\n                {'description': 'visibility of whole object is between 40 and 60%',\n                'token': '2',\n                'level': 'v40-60'},\n                {'description': 'visibility of whole object is between 60 and 80%',\n                'token': '3',\n                'level': 'v60-80'},\n                {'description': 'visibility of whole object is between 80 and 100%',\n                'token': '4',\n                'level': 'v80-100'}]'''\n\n                self.gt_boxes = filter_eval_boxes_by_visibility(self.all_gt, visibility, verbose=True)\n\n        elif type_ == 'ord':\n\n            valid_tokens = [key for (key, value) in self.index_map.items() if value == index]\n            # from IPython import embed\n            # embed()\n            self.gt_boxes = filter_by_sample_token(self.all_gt, valid_tokens)\n            self.pred_boxes = filter_by_sample_token(self.all_preds, valid_tokens)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n\n    def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMetricDataList()\n\n        # print(self.cfg.dist_fcn_callable, self.cfg.dist_ths)\n        # self.cfg.dist_ths = [0.3]\n        # self.cfg.dist_fcn_callable\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md = accumulate(self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMetrics(self.cfg)\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.cfg.min_recall, self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in ['attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(md_list, metrics, min_precision=self.cfg.min_precision, min_recall=self.cfg.min_recall,\n                     dist_th_tp=self.cfg.dist_th_tp, savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(md_list, metrics, detection_name, self.cfg.min_precision, self.cfg.min_recall,\n                           savepath=savepath(detection_name + '_pr'))\n\n            class_tp_curve(md_list, metrics, detection_name, self.cfg.min_recall, self.cfg.dist_th_tp,\n                           savepath=savepath(detection_name + '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(md_list, metrics, dist_th, self.cfg.min_precision, self.cfg.min_recall,\n                          savepath=savepath('dist_pr_' + str(dist_th)))\n\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(description='Evaluate nuScenes detection results.',\n                                     formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument('result_path', type=str, help='The submission as a JSON file.')\n    parser.add_argument('--output_dir', type=str, default='~/nuscenes-metrics',\n                        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument('--eval_set', type=str, default='val',\n                        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='data/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument('--version', type=str, default='v1.0-trainval',\n                        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument('--config_path', type=str, default='',\n                        help='Path to the configuration file.'\n                             'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument('--plot_examples', type=int, default=0,\n                        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = NuScenesEval_custom(nusc_, config=cfg_, result_path=result_path_, eval_set=eval_set_,\n                                    output_dir=output_dir_, verbose=verbose_)\n    for vis in ['1', '2', '3', '4']:\n        nusc_eval.update_gt(type_='vis', visibility=vis)\n        print(f'================ {vis} ===============')\n        nusc_eval.main(plot_examples=plot_examples_, render_curves=render_curves_)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/eval_utils/nuscenes_eval_motion.py",
    "content": "import argparse\nimport copy\nimport json\nimport os\nimport time\nfrom typing import Tuple, Dict, Any\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.detection.data_classes import DetectionConfig\nfrom nuscenes.eval.detection.evaluate import NuScenesEval\nfrom pyquaternion import Quaternion\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.eval.common.loaders import add_center_dist, filter_eval_boxes\nimport tqdm\nfrom nuscenes.utils.geometry_utils import view_points, BoxVisibility\nimport pycocotools.mask as mask_util\nimport argparse\nimport json\nimport os\nimport random\nimport time\nfrom typing import Tuple, Dict, Any\n\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom mmcv.core.bbox.iou_calculators import BboxOverlaps3D\nfrom IPython import embed\nimport json\nfrom typing import Any\n\nimport numpy as np\nfrom matplotlib import pyplot as plt\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.render import setup_axis\nfrom nuscenes.eval.common.utils import boxes_to_sensor\nfrom nuscenes.eval.detection.constants import TP_METRICS, DETECTION_NAMES, DETECTION_COLORS, TP_METRICS_UNITS, \\\n    PRETTY_DETECTION_NAMES, PRETTY_TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionMetrics, DetectionMetricData, DetectionMetricDataList\nfrom nuscenes.utils.data_classes import LidarPointCloud\nfrom nuscenes.utils.geometry_utils import view_points\nfrom .eval_utils import load_prediction, load_gt, accumulate, accumulate_motion, \\\n    DetectionMotionBox, DetectionMotionBox_modified, DetectionMotionMetricData, \\\n    DetectionMotionMetrics, DetectionMotionMetricDataList\nfrom .metric_utils import traj_fde\nfrom prettytable import PrettyTable\n\nTP_METRICS = [\n    'trans_err',\n    'scale_err',\n    'orient_err',\n    'vel_err',\n    'attr_err',\n    'min_ade_err',\n    'min_fde_err',\n    'miss_rate_err']\nTP_TRAJ_METRICS = ['min_ade_err', 'min_fde_err', 'miss_rate_err']\nAxis = Any\n\n\ndef class_tp_curve(md_list: DetectionMetricDataList,\n                   metrics: DetectionMetrics,\n                   detection_name: str,\n                   min_recall: float,\n                   dist_th_tp: float,\n                   savepath: str = None,\n                   ax: Axis = None) -> None:\n    \"\"\"\n    Plot the true positive curve for the specified class.\n    :param md_list: DetectionMetricDataList instance.\n    :param metrics: DetectionMetrics instance.\n    :param detection_name:\n    :param min_recall: Minimum recall value.\n    :param dist_th_tp: The distance threshold used to determine matches.\n    :param savepath: If given, saves the the rendering here instead of displaying.\n    :param ax: Axes onto which to render.\n    \"\"\"\n    # Get metric data for given detection class with tp distance threshold.\n\n    md = md_list[(detection_name, dist_th_tp)]\n    min_recall_ind = round(100 * min_recall)\n    if min_recall_ind <= md.max_recall_ind:\n        # For traffic_cone and barrier only a subset of the metrics are\n        # plotted.\n        rel_metrics = [\n            m for m in TP_METRICS if not np.isnan(\n                metrics.get_label_tp(\n                    detection_name, m))]\n        ylimit = max([max(getattr(md, metric)[min_recall_ind:md.max_recall_ind + 1])\n                     for metric in rel_metrics]) * 1.1\n    else:\n        ylimit = 1.0\n\n    # Prepare axis.\n    if ax is None:\n        ax = setup_axis(\n            title=PRETTY_DETECTION_NAMES[detection_name],\n            xlabel='Recall',\n            ylabel='Error',\n            xlim=1,\n            min_recall=min_recall)\n    ax.set_ylim(0, ylimit)\n\n    # Plot the recall vs. error curve for each tp metric.\n    for metric in TP_METRICS:\n        tp = metrics.get_label_tp(detection_name, metric)\n\n        # Plot only if we have valid data.\n        if tp is not np.nan and min_recall_ind <= md.max_recall_ind:\n            recall, error = md.recall[:md.max_recall_ind +\n                                      1], getattr(md, metric)[:md.max_recall_ind + 1]\n        else:\n            recall, error = [], []\n\n        # Change legend based on tp value\n        if tp is np.nan:\n            label = '{}: n/a'.format(PRETTY_TP_METRICS[metric])\n        elif min_recall_ind > md.max_recall_ind:\n            label = '{}: nan'.format(PRETTY_TP_METRICS[metric])\n        else:\n            label = '{}: {:.2f} ({})'.format(\n                PRETTY_TP_METRICS[metric], tp, TP_METRICS_UNITS[metric])\n        if metric == 'trans_err':\n            label += f' ({md.max_recall_ind})'  # add recall\n            print(f'Recall: {detection_name}: {md.max_recall_ind/100}')\n        ax.plot(recall, error, label=label)\n    ax.axvline(x=md.max_recall, linestyle='-.', color=(0, 0, 0, 0.3))\n    ax.legend(loc='best')\n\n    if savepath is not None:\n        plt.savefig(savepath)\n        plt.close()\n\n\ndef center_in_image(box,\n                    intrinsic: np.ndarray,\n                    imsize: Tuple[int,\n                                  int],\n                    vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible inside an image without accounting for occlusions.\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    center_3d = box.center.reshape(3, 1)\n    center_img = view_points(center_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(\n        center_img[0, :] > 0, center_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, center_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, center_img[1, :] > 0)\n    visible = np.logical_and(visible, center_3d[2, :] > 1)\n\n    # True if a corner is at least 0.1 meter in front of the camera.\n    in_front = center_3d[2, :] > 0.1\n\n    if vis_level == BoxVisibility.ALL:\n        return all(visible) and all(in_front)\n    elif vis_level == BoxVisibility.ANY:\n        return any(visible) and all(in_front)\n    elif vis_level == BoxVisibility.NONE:\n        return True\n    else:\n        raise ValueError(\"vis_level: {} not valid\".format(vis_level))\n\n\ndef exist_corners_in_image_but_not_all(box,\n                                       intrinsic: np.ndarray,\n                                       imsize: Tuple[int,\n                                                     int],\n                                       vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible in images but not all corners in image .\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    corners_3d = box.corners()\n    corners_img = view_points(corners_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(\n        corners_img[0, :] > 0, corners_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, corners_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, corners_img[1, :] > 0)\n    visible = np.logical_and(visible, corners_3d[2, :] > 1)\n\n    # True if a corner is at least 0.1 meter in front of the camera.\n    in_front = corners_3d[2, :] > 0.1\n\n    if any(visible) and not all(visible) and all(in_front):\n        return True\n    else:\n        return False\n\n\ndef filter_eval_boxes_by_id(nusc: NuScenes,\n                            eval_boxes: EvalBoxes,\n                            id=None,\n                            verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.token in id:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_visibility(\n        ori_eval_boxes: EvalBoxes,\n        visibility=None,\n        verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.visibility == visibility:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After visibility based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_by_sample_token(\n        ori_eval_boxes,\n        valid_sample_tokens=[],\n        verbose=False):\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    for sample_token in eval_boxes.sample_tokens:\n        if sample_token not in valid_sample_tokens:\n            eval_boxes.boxes.pop(sample_token)\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_overlap(nusc: NuScenes,\n                                 eval_boxes: EvalBoxes,\n                                 verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. basedon overlap .\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    cams = ['CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_BACK_RIGHT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_FRONT_LEFT']\n\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        sample_record = nusc.get('sample', sample_token)\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            count = 0\n            for cam in cams:\n                '''\n                copy-paste form nuscens\n                '''\n                sample_data_token = sample_record['data'][cam]\n                sd_record = nusc.get('sample_data', sample_data_token)\n                cs_record = nusc.get(\n                    'calibrated_sensor',\n                    sd_record['calibrated_sensor_token'])\n                sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n                pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n                cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n                imsize = (sd_record['width'], sd_record['height'])\n                new_box = Box(\n                    box.translation,\n                    box.size,\n                    Quaternion(\n                        box.rotation),\n                    name=box.detection_name,\n                    token='')\n\n                # Move box to ego vehicle coord system.\n                new_box.translate(-np.array(pose_record['translation']))\n                new_box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n                #  Move box to sensor coord system.\n                new_box.translate(-np.array(cs_record['translation']))\n                new_box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n                if center_in_image(\n                        new_box,\n                        cam_intrinsic,\n                        imsize,\n                        vis_level=BoxVisibility.ANY):\n                    count += 1\n                # if exist_corners_in_image_but_not_all(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                #    count += 1\n\n            if count > 1:\n                with open('center_overlap.txt', 'a') as f:\n                    try:\n                        f.write(box.token + '\\n')\n                    except BaseException:\n                        pass\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    verbose = True\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\nclass MotionEval(NuScenesEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as DetectionEval.\n    \"\"\"\n\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 overlap_test=False,\n                 eval_mask=False,\n                 data_infos=None,\n                 category_convert_type='motion_category',\n                 ):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n        self.overlap_test = overlap_test\n        self.eval_mask = eval_mask\n        self.data_infos = data_infos\n        # Check result file exists.\n        assert os.path.exists(\n            result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, DetectionMotionBox,\n                                                     verbose=verbose, category_convert_type=category_convert_type)\n        self.gt_boxes = load_gt(\n            self.nusc,\n            self.eval_set,\n            DetectionMotionBox_modified,\n            verbose=verbose,\n            category_convert_type=category_convert_type)\n\n        assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n            \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        # Filter boxes (distance, points per box, etc.).\n\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(\n            nusc, self.pred_boxes, self.cfg.class_range, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(\n            nusc, self.gt_boxes, self.cfg.class_range, verbose=verbose)\n\n        if self.overlap_test:\n            self.pred_boxes = filter_eval_boxes_by_overlap(\n                self.nusc, self.pred_boxes)\n\n            self.gt_boxes = filter_eval_boxes_by_overlap(\n                self.nusc, self.gt_boxes, verbose=True)\n\n        self.all_gt = copy.deepcopy(self.gt_boxes)\n        self.all_preds = copy.deepcopy(self.pred_boxes)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n        self.index_map = {}\n        for scene in nusc.scene:\n            first_sample_token = scene['first_sample_token']\n            sample = nusc.get('sample', first_sample_token)\n            self.index_map[first_sample_token] = 1\n            index = 2\n            while sample['next'] != '':\n                sample = nusc.get('sample', sample['next'])\n                self.index_map[sample['token']] = index\n                index += 1\n\n    def update_gt(self, type_='vis', visibility='1', index=1):\n        if type_ == 'vis':\n            self.visibility_test = True\n            if self.visibility_test:\n                '''[{'description': 'visibility of whole object is between 0 and 40%',\n                'token': '1',\n                'level': 'v0-40'},\n                {'description': 'visibility of whole object is between 40 and 60%',\n                'token': '2',\n                'level': 'v40-60'},\n                {'description': 'visibility of whole object is between 60 and 80%',\n                'token': '3',\n                'level': 'v60-80'},\n                {'description': 'visibility of whole object is between 80 and 100%',\n                'token': '4',\n                'level': 'v80-100'}]'''\n\n                self.gt_boxes = filter_eval_boxes_by_visibility(\n                    self.all_gt, visibility, verbose=True)\n\n        elif type_ == 'ord':\n\n            valid_tokens = [\n                key for (\n                    key,\n                    value) in self.index_map.items() if value == index]\n            # from IPython import embed\n            # embed()\n            self.gt_boxes = filter_by_sample_token(self.all_gt, valid_tokens)\n            self.pred_boxes = filter_by_sample_token(\n                self.all_preds, valid_tokens)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n    def evaluate(self) -> Tuple[DetectionMotionMetrics,\n                                DetectionMotionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMotionMetricDataList()\n\n        # print(self.cfg.dist_fcn_callable, self.cfg.dist_ths)\n        # self.cfg.dist_ths = [0.3]\n        # self.cfg.dist_fcn_callable\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md, _, _, _ = accumulate(\n                    self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMotionMetrics(self.cfg)\n\n        traj_metrics = {}\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(\n                    metric_data,\n                    self.cfg.min_recall,\n                    self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(\n                    class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in [\n                        'attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                    if metric_name in TP_TRAJ_METRICS:\n                        if class_name not in traj_metrics:\n                            traj_metrics[class_name] = {}\n                        traj_metrics[class_name][metric_name] = tp\n                metrics.add_label_tp(class_name, metric_name, tp)\n        print_traj_metrics(traj_metrics)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def evaluate_motion(\n            self) -> Tuple[DetectionMotionMetrics, DetectionMotionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        self.cfg.dist_ths = [1.0]\n        self.cfg.dist_th_tp = 1.0  # center dist for detection\n        traj_dist_th = 2.0  # FDE for traj\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMotionMetricDataList()\n\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md, _, _, _ = accumulate_motion(\n                    self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, traj_fde, dist_th, traj_dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMotionMetrics(self.cfg)\n\n        traj_metrics = {}\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(\n                    metric_data,\n                    self.cfg.min_recall,\n                    self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(\n                    class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in [\n                        'attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                    if metric_name in TP_TRAJ_METRICS:\n                        if class_name not in traj_metrics:\n                            traj_metrics[class_name] = {}\n                        traj_metrics[class_name][metric_name] = tp\n                metrics.add_label_tp(class_name, metric_name, tp)\n        print_traj_metrics(traj_metrics)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def evaluate_epa(\n            self) -> Tuple[DetectionMotionMetrics, DetectionMotionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        self.cfg.dist_ths = [2.0]\n        self.cfg.dist_th_tp = 2.0  # center dist for detection\n        traj_dist_th = 2.0  # FDE for traj\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMotionMetricDataList()\n\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md, N_det_tp, N_det_fp, N_det_gt = accumulate(\n                    self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                md, N_det_traj_tp, N_det_traj_fp, N_det_traj_gt = accumulate_motion(\n                    self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, traj_fde, dist_th, traj_dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                EPA = (N_det_traj_tp - 0.5 * N_det_fp) / (N_det_gt + 1e-5)\n                print(N_det_traj_tp, N_det_fp, N_det_gt)\n                print('EPA ', class_name, EPA)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMotionMetrics(self.cfg)\n\n        traj_metrics = {}\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(\n                    metric_data,\n                    self.cfg.min_recall,\n                    self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(\n                    class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in [\n                        'attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                    if metric_name in TP_TRAJ_METRICS:\n                        if class_name not in traj_metrics:\n                            traj_metrics[class_name] = {}\n                        traj_metrics[class_name][metric_name] = tp\n                metrics.add_label_tp(class_name, metric_name, tp)\n        print_traj_metrics(traj_metrics)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def main(self,\n             plot_examples: int = 0,\n             render_curves: bool = True,\n             eval_mode: str = 'standard') -> Dict[str, Any]:\n        \"\"\"\n        Main function that loads the evaluation code, visualizes samples, runs the evaluation and renders stat plots.\n        :param plot_examples: How many example visualizations to write to disk.\n        :param render_curves: Whether to render PR and TP curves to disk.\n        :return: A dict that stores the high-level metrics and meta data.\n        \"\"\"\n        if plot_examples > 0:\n            # Select a random but fixed subset to plot.\n            random.seed(42)\n            sample_tokens = list(self.sample_tokens)\n            random.shuffle(sample_tokens)\n            sample_tokens = sample_tokens[:plot_examples]\n\n            # Visualize samples.\n            example_dir = os.path.join(self.output_dir, 'examples')\n            if not os.path.isdir(example_dir):\n                os.mkdir(example_dir)\n            for sample_token in sample_tokens:\n                visualize_sample(self.nusc,\n                                 sample_token,\n                                 self.gt_boxes if self.eval_set != 'test' else EvalBoxes(),\n                                 # Don't render test GT.\n                                 self.pred_boxes,\n                                 eval_range=max(self.cfg.class_range.values()),\n                                 savepath=os.path.join(example_dir, '{}.png'.format(sample_token)))\n\n        # Run evaluation.\n        if eval_mode == 'motion_map':\n            metrics, metric_data_list = self.evaluate_motion()\n        elif eval_mode == 'standard':\n            metrics, metric_data_list = self.evaluate()\n        elif eval_mode == 'epa':\n            metrics, metric_data_list = self.evaluate_epa()\n        else:\n            raise NotImplementedError\n        # Render PR and TP curves.\n        if render_curves:\n            self.render(metrics, metric_data_list)\n\n        # Dump the metric data, meta and metrics to disk.\n        if self.verbose:\n            print('Saving metrics to: %s' % self.output_dir)\n        metrics_summary = metrics.serialize()\n        metrics_summary['meta'] = self.meta.copy()\n        with open(os.path.join(self.output_dir, 'metrics_summary.json'), 'w') as f:\n            json.dump(metrics_summary, f, indent=2)\n        with open(os.path.join(self.output_dir, 'metrics_details.json'), 'w') as f:\n            json.dump(metric_data_list.serialize(), f, indent=2)\n\n        # Print high-level metrics.\n        print('mAP: %.4f' % (metrics_summary['mean_ap']))\n        err_name_mapping = {\n            'trans_err': 'mATE',\n            'scale_err': 'mASE',\n            'orient_err': 'mAOE',\n            'vel_err': 'mAVE',\n            'attr_err': 'mAAE'\n        }\n        for tp_name, tp_val in metrics_summary['tp_errors'].items():\n            print('%s: %.4f' % (err_name_mapping[tp_name], tp_val))\n        print('NDS: %.4f' % (metrics_summary['nd_score']))\n        print('Eval time: %.1fs' % metrics_summary['eval_time'])\n\n        # Print per-class metrics.\n        print()\n        print('Per-class results:')\n        print('Object Class\\tAP\\tATE\\tASE\\tAOE\\tAVE\\tAAE')\n        class_aps = metrics_summary['mean_dist_aps']\n        class_tps = metrics_summary['label_tp_errors']\n        for class_name in class_aps.keys():\n            print('%s\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f\\t%.3f'\n                  % (class_name, class_aps[class_name],\n                     class_tps[class_name]['trans_err'],\n                     class_tps[class_name]['scale_err'],\n                     class_tps[class_name]['orient_err'],\n                     class_tps[class_name]['vel_err'],\n                     class_tps[class_name]['attr_err']))\n\n        return metrics_summary\n\n    def render(self, metrics: DetectionMetrics,\n               md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(\n            md_list,\n            metrics,\n            min_precision=self.cfg.min_precision,\n            min_recall=self.cfg.min_recall,\n            dist_th_tp=self.cfg.dist_th_tp,\n            savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(\n                md_list,\n                metrics,\n                detection_name,\n                self.cfg.min_precision,\n                self.cfg.min_recall,\n                savepath=savepath(\n                    detection_name +\n                    '_pr'))\n\n            class_tp_curve(\n                md_list,\n                metrics,\n                detection_name,\n                self.cfg.min_recall,\n                self.cfg.dist_th_tp,\n                savepath=savepath(\n                    detection_name +\n                    '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(\n                md_list,\n                metrics,\n                dist_th,\n                self.cfg.min_precision,\n                self.cfg.min_recall,\n                savepath=savepath(\n                    'dist_pr_' +\n                    str(dist_th)))\n\n\ndef print_traj_metrics(metrics):\n    class_names = metrics.keys()\n    x = PrettyTable()\n    x.field_names = [\"class names\"] + TP_TRAJ_METRICS\n    for class_name in metrics.keys():\n        row_data = [class_name]\n        for m in TP_TRAJ_METRICS:\n            row_data.append('%.4f' % metrics[class_name][m])\n        x.add_row(row_data)\n    print(x)\n\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(\n        description='Evaluate nuScenes detection results.',\n        formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument(\n        'result_path',\n        type=str,\n        help='The submission as a JSON file.')\n    parser.add_argument(\n        '--output_dir',\n        type=str,\n        default='~/nuscenes-metrics',\n        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument(\n        '--eval_set',\n        type=str,\n        default='val',\n        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='data/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument(\n        '--version',\n        type=str,\n        default='v1.0-trainval',\n        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument(\n        '--config_path',\n        type=str,\n        default='',\n        help='Path to the configuration file.'\n        'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument(\n        '--plot_examples',\n        type=int,\n        default=0,\n        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = MotionEval(\n        nusc_,\n        config=cfg_,\n        result_path=result_path_,\n        eval_set=eval_set_,\n        output_dir=output_dir_,\n        verbose=verbose_)\n    for vis in ['1', '2', '3', '4']:\n        nusc_eval.update_gt(type_='vis', visibility=vis)\n        print(f'================ {vis} ===============')\n        nusc_eval.main(\n            plot_examples=plot_examples_,\n            render_curves=render_curves_)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/lyft_dataset.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport os\nimport pandas as pd\nimport tempfile\nfrom lyft_dataset_sdk.lyftdataset import LyftDataset as Lyft\nfrom lyft_dataset_sdk.utils.data_classes import Box as LyftBox\nfrom os import path as osp\nfrom pyquaternion import Quaternion\n\nfrom mmcv.core.evaluation.lyft_eval import lyft_eval\nfrom mmcv.datasets import DATASETS\nfrom mmcv.core import show_result\n# from mmcv.core.bbox import Box3DMode, Coord3DMode, LiDARInstance3DBoxes\nfrom mmcv.core.bbox.structures.box_3d_mode import Box3DMode\nfrom mmcv.core.bbox.structures.coord_3d_mode import Coord3DMode\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom .custom_3d import Custom3DDataset\nfrom .pipelines import Compose\n\n\n@DATASETS.register_module()\nclass LyftDataset(Custom3DDataset):\n    r\"\"\"Lyft Dataset.\n\n    This class serves as the API for experiments on the Lyft Dataset.\n\n    Please refer to\n    `<https://www.kaggle.com/c/3d-object-detection-for-autonomous-vehicles/data>`_\n    for data downloading.\n\n    Args:\n        ann_file (str): Path of annotation file.\n        pipeline (list[dict], optional): Pipeline used for data processing.\n            Defaults to None.\n        data_root (str): Path of dataset root.\n        classes (tuple[str], optional): Classes used in the dataset.\n            Defaults to None.\n        load_interval (int, optional): Interval of loading the dataset. It is\n            used to uniformly sample the dataset. Defaults to 1.\n        modality (dict, optional): Modality to specify the sensor data used\n            as input. Defaults to None.\n        box_type_3d (str, optional): Type of 3D box of this dataset.\n            Based on the `box_type_3d`, the dataset will encapsulate the box\n            to its original format then converted them to `box_type_3d`.\n            Defaults to 'LiDAR' in this dataset. Available options includes\n\n            - 'LiDAR': Box in LiDAR coordinates.\n            - 'Depth': Box in depth coordinates, usually for indoor dataset.\n            - 'Camera': Box in camera coordinates.\n        filter_empty_gt (bool, optional): Whether to filter empty GT.\n            Defaults to True.\n        test_mode (bool, optional): Whether the dataset is in test mode.\n            Defaults to False.\n    \"\"\"  # noqa: E501\n    NameMapping = {\n        'bicycle': 'bicycle',\n        'bus': 'bus',\n        'car': 'car',\n        'emergency_vehicle': 'emergency_vehicle',\n        'motorcycle': 'motorcycle',\n        'other_vehicle': 'other_vehicle',\n        'pedestrian': 'pedestrian',\n        'truck': 'truck',\n        'animal': 'animal'\n    }\n    DefaultAttribute = {\n        'car': 'is_stationary',\n        'truck': 'is_stationary',\n        'bus': 'is_stationary',\n        'emergency_vehicle': 'is_stationary',\n        'other_vehicle': 'is_stationary',\n        'motorcycle': 'is_stationary',\n        'bicycle': 'is_stationary',\n        'pedestrian': 'is_stationary',\n        'animal': 'is_stationary'\n    }\n    CLASSES = ('car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle',\n               'motorcycle', 'bicycle', 'pedestrian', 'animal')\n\n    def __init__(self,\n                 ann_file,\n                 pipeline=None,\n                 data_root=None,\n                 classes=None,\n                 load_interval=1,\n                 modality=None,\n                 box_type_3d='LiDAR',\n                 filter_empty_gt=True,\n                 test_mode=False):\n        self.load_interval = load_interval\n        super().__init__(\n            data_root=data_root,\n            ann_file=ann_file,\n            pipeline=pipeline,\n            classes=classes,\n            modality=modality,\n            box_type_3d=box_type_3d,\n            filter_empty_gt=filter_empty_gt,\n            test_mode=test_mode)\n\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n\n    def load_annotations(self, ann_file):\n        \"\"\"Load annotations from ann_file.\n\n        Args:\n            ann_file (str): Path of the annotation file.\n\n        Returns:\n            list[dict]: List of annotations sorted by timestamps.\n        \"\"\"\n        data = mmcv.load(ann_file)\n        data_infos = list(sorted(data['infos'], key=lambda e: e['timestamp']))\n        data_infos = data_infos[::self.load_interval]\n        self.metadata = data['metadata']\n        self.version = self.metadata['version']\n        return data_infos\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): sample index\n                - pts_filename (str): filename of point clouds\n                - sweeps (list[dict]): infos of sweeps\n                - timestamp (float): sample timestamp\n                - img_filename (str, optional): image filename\n                - lidar2img (list[np.ndarray], optional): transformations \\\n                    from lidar to different cameras\n                - ann_info (dict): annotation info\n        \"\"\"\n        info = self.data_infos[index]\n\n        # standard protocal modified from SECOND.Pytorch\n        input_dict = dict(\n            sample_idx=info['token'],\n            pts_filename=info['lidar_path'],\n            sweeps=info['sweeps'],\n            timestamp=info['timestamp'] / 1e6,\n        )\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            for cam_type, cam_info in info['cams'].items():\n                image_paths.append(cam_info['data_path'])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info['sensor2lidar_rotation'])\n                lidar2cam_t = cam_info[\n                    'sensor2lidar_translation'] @ lidar2cam_r.T\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = cam_info['cam_intrinsic']\n                viewpad = np.eye(4)\n                viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                lidar2img_rts.append(lidar2img_rt)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                ))\n\n        if not self.test_mode:\n            annos = self.get_ann_info(index)\n            input_dict['ann_info'] = annos\n\n        return input_dict\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes.\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        gt_bboxes_3d = info['gt_boxes']\n        gt_names_3d = info['gt_names']\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if 'gt_shape' in info:\n            gt_shape = info['gt_shape']\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_shape], axis=-1)\n\n        # the lyft box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n        )\n        return anns_results\n\n    def _format_bbox(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n        lyft_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_lyft_box(det)\n            sample_token = self.data_infos[sample_id]['token']\n            boxes = lidar_lyft_box_to_global(self.data_infos[sample_id], boxes)\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                lyft_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    name=name,\n                    score=box.score)\n                annos.append(lyft_anno)\n            lyft_annos[sample_token] = annos\n        lyft_submissions = {\n            'meta': self.modality,\n            'results': lyft_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_lyft.json')\n        print('Results writes to', res_path)\n        mmcv.dump(lyft_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in Lyft protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        lyft = Lyft(\n            data_path=osp.join(self.data_root, self.version),\n            json_path=osp.join(self.data_root, self.version, self.version),\n            verbose=True)\n        eval_set_map = {\n            'v1.01-train': 'val',\n        }\n        metrics = lyft_eval(lyft, self.data_root, result_path,\n                            eval_set_map[self.version], output_dir, logger)\n\n        # record metrics\n        detail = dict()\n        metric_prefix = f'{result_name}_Lyft'\n\n        for i, name in enumerate(metrics['class_names']):\n            AP = float(metrics['mAPs_cate'][i])\n            detail[f'{metric_prefix}/{name}_AP'] = AP\n\n        detail[f'{metric_prefix}/mAP'] = metrics['Final mAP']\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None, csv_savepath=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            csv_savepath (str | None): The path for saving csv files.\n                It includes the file path and the csv filename,\n                e.g., \"a/b/filename.csv\". If not specified,\n                the result will not be converted to csv file.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        assert len(results) == len(self), (\n            'The length of results is not equal to the dataset len: {} != {}'.\n            format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        # currently the output prediction results could be in two formats\n        # 1. list of dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...)\n        # 2. list of dict('pts_bbox' or 'img_bbox':\n        #     dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...))\n        # this is a workaround to enable evaluation of both formats on Lyft\n        # refer to https://github.com/open-mmlab/mmdetection3d/issues/449\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        if csv_savepath is not None:\n            self.json2csv(result_files['pts_bbox'], csv_savepath)\n        return result_files, tmp_dir\n\n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 csv_savepath=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in Lyft protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            csv_savepath (str | None): The path for saving csv files.\n                It includes the file path and the csv filename,\n                e.g., \"a/b/filename.csv\". If not specified,\n                the result will not be converted to csv file.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Evaluation results.\n        \"\"\"\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix,\n                                                    csv_savepath)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print(f'Evaluating bboxes of {name}')\n                ret_dict = self._evaluate_single(result_files[name])\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(result_files)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\n    def _build_default_pipeline(self):\n        \"\"\"Build the default pipeline for this dataset.\"\"\"\n        pipeline = [\n            dict(\n                type='LoadPointsFromFile',\n                coord_type='LIDAR',\n                load_dim=5,\n                use_dim=5,\n                file_client_args=dict(backend='disk')),\n            dict(\n                type='LoadPointsFromMultiSweeps',\n                sweeps_num=10,\n                file_client_args=dict(backend='disk')),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=self.CLASSES,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ]\n        return Compose(pipeline)\n\n    def show(self, results, out_dir, show=True, pipeline=None):\n        \"\"\"Results visualization.\n\n        Args:\n            results (list[dict]): List of bounding boxes results.\n            out_dir (str): Output directory of visualization result.\n            show (bool): Visualize the results online.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n        \"\"\"\n        assert out_dir is not None, 'Expect out_dir, got none.'\n        pipeline = self._get_pipeline(pipeline)\n        for i, result in enumerate(results):\n            if 'pts_bbox' in result.keys():\n                result = result['pts_bbox']\n            data_info = self.data_infos[i]\n            pts_path = data_info['lidar_path']\n            file_name = osp.split(pts_path)[-1].split('.')[0]\n            points = self._extract_data(i, pipeline, 'points').numpy()\n            points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,\n                                               Coord3DMode.DEPTH)\n            inds = result['scores_3d'] > 0.1\n            gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()\n            show_gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,\n                                               Box3DMode.DEPTH)\n            pred_bboxes = result['boxes_3d'][inds].tensor.numpy()\n            show_pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,\n                                                 Box3DMode.DEPTH)\n            show_result(points, show_gt_bboxes, show_pred_bboxes, out_dir,\n                        file_name, show)\n\n    def json2csv(self, json_path, csv_savepath):\n        \"\"\"Convert the json file to csv format for submission.\n\n        Args:\n            json_path (str): Path of the result json file.\n            csv_savepath (str): Path to save the csv file.\n        \"\"\"\n        results = mmcv.load(json_path)['results']\n        sample_list_path = osp.join(self.data_root, 'sample_submission.csv')\n        data = pd.read_csv(sample_list_path)\n        Id_list = list(data['Id'])\n        pred_list = list(data['PredictionString'])\n        cnt = 0\n        print('Converting the json to csv...')\n        for token in results.keys():\n            cnt += 1\n            predictions = results[token]\n            prediction_str = ''\n            for i in range(len(predictions)):\n                prediction_str += \\\n                    str(predictions[i]['score']) + ' ' + \\\n                    str(predictions[i]['translation'][0]) + ' ' + \\\n                    str(predictions[i]['translation'][1]) + ' ' + \\\n                    str(predictions[i]['translation'][2]) + ' ' + \\\n                    str(predictions[i]['size'][0]) + ' ' + \\\n                    str(predictions[i]['size'][1]) + ' ' + \\\n                    str(predictions[i]['size'][2]) + ' ' + \\\n                    str(Quaternion(list(predictions[i]['rotation']))\n                        .yaw_pitch_roll[0]) + ' ' + \\\n                    predictions[i]['name'] + ' '\n            prediction_str = prediction_str[:-1]\n            idx = Id_list.index(token)\n            pred_list[idx] = prediction_str\n        df = pd.DataFrame({'Id': Id_list, 'PredictionString': pred_list})\n        mmcv.mkdir_or_exist(os.path.dirname(csv_savepath))\n        df.to_csv(csv_savepath, index=False)\n\n\ndef output_to_lyft_box(detection):\n    \"\"\"Convert the output to the box class in the Lyft.\n\n    Args:\n        detection (dict): Detection results.\n\n    Returns:\n        list[:obj:`LyftBox`]: List of standard LyftBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        box = LyftBox(\n            box_gravity_center[i],\n            box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i])\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_lyft_box_to_global(info, boxes):\n    \"\"\"Convert the box from ego to global coordinate.\n\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`LyftBox`]): List of predicted LyftBoxes.\n\n    Returns:\n        list: List of standard LyftBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    for box in boxes:\n        # Move box to ego vehicle coord system\n        box.rotate(Quaternion(info['lidar2ego_rotation']))\n        box.translate(np.array(info['lidar2ego_translation']))\n        # Move box to global coord system\n        box.rotate(Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n    return box_list"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/map_utils/mean_ap.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom multiprocessing import Pool\nfrom shapely.geometry import LineString, Polygon\nimport mmcv\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\nimport json\nfrom os import path as osp\nimport os\nfrom functools import partial\nfrom .tpfp import tpfp_gen, custom_tpfp_gen\nfrom mmcv.fileio.io import dump,load\n\ndef average_precision(recalls, precisions, mode='area'):\n    \"\"\"Calculate average precision (for single or multiple scales).\n\n    Args:\n        recalls (ndarray): shape (num_scales, num_dets) or (num_dets, )\n        precisions (ndarray): shape (num_scales, num_dets) or (num_dets, )\n        mode (str): 'area' or '11points', 'area' means calculating the area\n            under precision-recall curve, '11points' means calculating\n            the average precision of recalls at [0, 0.1, ..., 1]\n\n    Returns:\n        float or ndarray: calculated average precision\n    \"\"\"\n    no_scale = False\n    if recalls.ndim == 1:\n        no_scale = True\n        recalls = recalls[np.newaxis, :]\n        precisions = precisions[np.newaxis, :]\n    assert recalls.shape == precisions.shape and recalls.ndim == 2\n    num_scales = recalls.shape[0]\n    ap = np.zeros(num_scales, dtype=np.float32)\n    if mode == 'area':\n        zeros = np.zeros((num_scales, 1), dtype=recalls.dtype)\n        ones = np.ones((num_scales, 1), dtype=recalls.dtype)\n        mrec = np.hstack((zeros, recalls, ones))\n        mpre = np.hstack((zeros, precisions, zeros))\n        for i in range(mpre.shape[1] - 1, 0, -1):\n            mpre[:, i - 1] = np.maximum(mpre[:, i - 1], mpre[:, i])\n        for i in range(num_scales):\n            ind = np.where(mrec[i, 1:] != mrec[i, :-1])[0]\n            ap[i] = np.sum(\n                (mrec[i, ind + 1] - mrec[i, ind]) * mpre[i, ind + 1])\n    elif mode == '11points':\n        for i in range(num_scales):\n            for thr in np.arange(0, 1 + 1e-3, 0.1):\n                precs = precisions[i, recalls[i, :] >= thr]\n                prec = precs.max() if precs.size > 0 else 0\n                ap[i] += prec\n        ap /= 11\n    else:\n        raise ValueError(\n            'Unrecognized mode, only \"area\" and \"11points\" are supported')\n    if no_scale:\n        ap = ap[0]\n    return ap\n\ndef get_cls_results(gen_results, \n                    annotations, \n                    num_sample=100, \n                    num_pred_pts_per_instance=30,\n                    eval_use_same_gt_sample_num_flag=False,\n                    class_id=0, \n                    fix_interval=False):\n    \"\"\"Get det results and gt information of a certain class.\n\n    Args:\n        gen_results (list[list]): Same as `eval_map()`.\n        annotations (list[dict]): Same as `eval_map()`.\n        class_id (int): ID of a specific class.\n\n    Returns:\n        tuple[list[np.ndarray]]: detected bboxes, gt bboxes\n    \"\"\"\n    # if len(gen_results) == 0 or \n\n    cls_gens, cls_scores = [], []\n    for res in gen_results['vectors']:\n        if res['type'] == class_id:\n            if len(res['pts']) < 2:\n                continue\n            if not eval_use_same_gt_sample_num_flag:\n                sampled_points = np.array(res['pts'])\n            else:\n                line = res['pts']\n                line = LineString(line)\n\n                if fix_interval:\n                    distances = list(np.arange(1., line.length, 1.))\n                    distances = [0,] + distances + [line.length,]\n                    sampled_points = np.array([list(line.interpolate(distance).coords)\n                                            for distance in distances]).reshape(-1, 2)\n                else:\n                    distances = np.linspace(0, line.length, num_sample)\n                    sampled_points = np.array([list(line.interpolate(distance).coords)\n                                                for distance in distances]).reshape(-1, 2)\n                \n            cls_gens.append(sampled_points)\n            cls_scores.append(res['confidence_level'])\n    num_res = len(cls_gens)\n    if num_res > 0:\n        cls_gens = np.stack(cls_gens).reshape(num_res,-1)\n        cls_scores = np.array(cls_scores)[:,np.newaxis]\n        cls_gens = np.concatenate([cls_gens,cls_scores],axis=-1)\n        # print(f'for class {i}, cls_gens has shape {cls_gens.shape}')\n    else:\n        if not eval_use_same_gt_sample_num_flag:\n            cls_gens = np.zeros((0,num_pred_pts_per_instance*2+1))\n        else:\n            cls_gens = np.zeros((0,num_sample*2+1))\n        # print(f'for class {i}, cls_gens has shape {cls_gens.shape}')\n\n    cls_gts = []\n    for ann in annotations['vectors']:\n        if ann['type'] == class_id:\n            # line = ann['pts'] +  np.array((1,1)) # for hdmapnet\n            line = ann['pts']\n            # line = ann['pts'].cumsum(0)\n            line = LineString(line)\n            distances = np.linspace(0, line.length, num_sample)\n            sampled_points = np.array([list(line.interpolate(distance).coords)\n                                        for distance in distances]).reshape(-1, 2)\n            \n            cls_gts.append(sampled_points)\n    num_gts = len(cls_gts)\n    if num_gts > 0:\n        cls_gts = np.stack(cls_gts).reshape(num_gts,-1)\n    else:\n        cls_gts = np.zeros((0,num_sample*2))\n    return cls_gens, cls_gts\n    # ones = np.ones((num_gts,1))\n    # tmp_cls_gens = np.concatenate([cls_gts,ones],axis=-1)\n    # return tmp_cls_gens, cls_gts\n\ndef format_res_gt_by_classes(result_path,\n                             gen_results,\n                             annotations,\n                             cls_names=None,\n                             num_pred_pts_per_instance=30,\n                             eval_use_same_gt_sample_num_flag=False,\n                             pc_range=[-15.0, -30.0, -5.0, 15.0, 30.0, 3.0],\n                             nproc=24):\n    assert cls_names is not None\n    timer = mmcv.Timer()\n    num_fixed_sample_pts = 100\n    fix_interval = False\n    print('results path: {}'.format(result_path))\n\n    output_dir = osp.join(*osp.split(result_path)[:-1])\n    assert len(gen_results) == len(annotations)\n\n    pool = Pool(nproc)\n    cls_gens, cls_gts = {}, {}\n    print('Formatting ...')\n    formatting_file = 'cls_formatted.pkl'\n    formatting_file = osp.join(output_dir,formatting_file)\n\n    # for vis\n    if False:\n        from PIL import Image\n        import matplotlib.pyplot as plt\n        from matplotlib import transforms\n        from matplotlib.patches import Rectangle\n\n        show_dir = osp.join(output_dir,'vis_json')\n        mmcv.mkdir_or_exist(osp.abspath(show_dir))\n        # import pdb;pdb.set_trace()\n        car_img = Image.open('./figs/lidar_car.png')\n        colors_plt = ['r', 'b', 'g']\n        for i in range(20):\n\n            plt.figure(figsize=(2, 4))\n            plt.xlim(pc_range[0], pc_range[3])\n            plt.ylim(pc_range[1], pc_range[4])\n            plt.axis('off')\n\n            for line in gen_results[i]['vectors']:\n                l = np.array(line['pts'])\n                plt.plot(l[:,0],l[:,1],'-', \n                # color=colors[line['type']]\n                color = 'red',\n                )\n\n            for line in annotations[i]['vectors']:\n                # l = np.array(line['pts']) + np.array((1,1))\n                l = np.array(line['pts'])\n                # l = line['pts']\n                plt.plot(l[:,0],l[:,1],'-', \n                    # color=colors[line['type']],\n                    color = 'blue',\n                    )\n            plt.imshow(car_img, extent=[-1.2, 1.2, -1.5, 1.5])\n            map_path = osp.join(show_dir, 'COMPARE_MAP_{}.jpg'.format(i))\n            plt.savefig(map_path, bbox_inches='tight', dpi=400)\n            plt.close()\n\n    for i, clsname in enumerate(cls_names):\n\n        gengts = pool.starmap(\n                    partial(get_cls_results, num_sample=num_fixed_sample_pts,\n                        num_pred_pts_per_instance=num_pred_pts_per_instance,\n                        eval_use_same_gt_sample_num_flag=eval_use_same_gt_sample_num_flag,class_id=i,fix_interval=fix_interval),\n                    zip(list(gen_results.values()), annotations))   \n        # gengts = map(partial(get_cls_results, num_sample=num_fixed_sample_pts, class_id=i,fix_interval=fix_interval),\n        #             zip(gen_results, annotations))\n        # import pdb;pdb.set_trace()\n        gens, gts = tuple(zip(*gengts))\n        cls_gens[clsname] = gens\n        cls_gts[clsname] = gts\n    \n    dump([cls_gens, cls_gts],formatting_file)\n    print('Cls data formatting done in {:2f}s!! with {}'.format(float(timer.since_start()),formatting_file))\n    pool.close()\n    return cls_gens, cls_gts\n\ndef eval_map(gen_results,\n             annotations,\n             cls_gens,\n             cls_gts,\n             threshold=0.5,\n             cls_names=None,\n             logger=None,\n             tpfp_fn=None,\n             pc_range=[-15.0, -30.0, -5.0, 15.0, 30.0, 3.0],\n             metric=None,\n             num_pred_pts_per_instance=30,\n             nproc=24):\n    timer = mmcv.Timer()\n    pool = Pool(nproc)\n\n    eval_results = []\n    \n    for i, clsname in enumerate(cls_names):\n        \n        # get gt and det bboxes of this class\n        cls_gen = cls_gens[clsname]\n        cls_gt = cls_gts[clsname]\n        # choose proper function according to datasets to compute tp and fp\n        # XXX\n        # func_name = cls2func[clsname]\n        # tpfp_fn = tpfp_fn_dict[tpfp_fn_name]\n        tpfp_fn = custom_tpfp_gen\n        # Trick for serialized\n        # only top-level function can be serized\n        # somehow use partitial the return function is defined\n        # at the top level.\n\n        # tpfp = tpfp_fn(cls_gen[i], cls_gt[i],threshold=threshold, metric=metric)\n        # import pdb; pdb.set_trace()\n        # TODO this is a hack\n        tpfp_fn = partial(tpfp_fn, threshold=threshold, metric=metric)\n        args = []\n        # compute tp and fp for each image with multiple processes\n        tpfp = pool.starmap(\n            tpfp_fn,\n            zip(cls_gen, cls_gt, *args))\n        # import pdb;pdb.set_trace()\n        tp, fp = tuple(zip(*tpfp))\n\n\n\n        # map_results = map(\n        #     tpfp_fn,\n        #     cls_gen, cls_gt)\n        # tp, fp = tuple(map(list, zip(*map_results)))\n\n\n        # debug and testing\n        # for i in range(len(cls_gen)):\n        #     # print(i)\n        #     tpfp = tpfp_fn(cls_gen[i], cls_gt[i],threshold=threshold)\n        #     print(i)\n        #     tpfp = (tpfp,)\n        #     print(tpfp)\n        # i = 0 \n        # tpfp = tpfp_fn(cls_gen[i], cls_gt[i],threshold=threshold)\n        # import pdb; pdb.set_trace()\n\n        # XXX\n        \n        num_gts = 0\n        for j, bbox in enumerate(cls_gt):\n            num_gts += bbox.shape[0]\n\n        # sort all det bboxes by score, also sort tp and fp\n        # import pdb;pdb.set_trace()\n        cls_gen = np.vstack(cls_gen)\n        num_dets = cls_gen.shape[0]\n        sort_inds = np.argsort(-cls_gen[:, -1]) #descending, high score front\n        tp = np.hstack(tp)[sort_inds]\n        fp = np.hstack(fp)[sort_inds]\n        \n        # calculate recall and precision with tp and fp\n        # num_det*num_res\n        tp = np.cumsum(tp, axis=0)\n        fp = np.cumsum(fp, axis=0)\n        eps = np.finfo(np.float32).eps\n        recalls = tp / np.maximum(num_gts, eps)\n        precisions = tp / np.maximum((tp + fp), eps)\n\n        # calculate AP\n        # if dataset != 'voc07' else '11points'\n        mode = 'area'\n        ap = average_precision(recalls, precisions, mode)\n        eval_results.append({\n            'num_gts': num_gts,\n            'num_dets': num_dets,\n            'recall': recalls,\n            'precision': precisions,\n            'ap': ap\n        })\n        print('cls:{} done in {:2f}s!!'.format(clsname,float(timer.since_last_check())))\n    pool.close()\n    aps = []\n    for cls_result in eval_results:\n        if cls_result['num_gts'] > 0:\n            aps.append(cls_result['ap'])\n    mean_ap = np.array(aps).mean().item() if len(aps) else 0.0\n\n    print_map_summary(\n        mean_ap, eval_results, class_name=cls_names, logger=logger)\n\n    return mean_ap, eval_results\n\n\n\ndef print_map_summary(mean_ap,\n                      results,\n                      class_name=None,\n                      scale_ranges=None,\n                      logger=None):\n    \"\"\"Print mAP and results of each class.\n\n    A table will be printed to show the gts/dets/recall/AP of each class and\n    the mAP.\n\n    Args:\n        mean_ap (float): Calculated from `eval_map()`.\n        results (list[dict]): Calculated from `eval_map()`.\n        dataset (list[str] | str | None): Dataset name or dataset classes.\n        scale_ranges (list[tuple] | None): Range of scales to be evaluated.\n        logger (logging.Logger | str | None): The way to print the mAP\n            summary. See `mmcv.utils.print_log()` for details. Default: None.\n    \"\"\"\n\n    if logger == 'silent':\n        return\n\n    if isinstance(results[0]['ap'], np.ndarray):\n        num_scales = len(results[0]['ap'])\n    else:\n        num_scales = 1\n\n    if scale_ranges is not None:\n        assert len(scale_ranges) == num_scales\n\n    num_classes = len(results)\n\n    recalls = np.zeros((num_scales, num_classes), dtype=np.float32)\n    aps = np.zeros((num_scales, num_classes), dtype=np.float32)\n    num_gts = np.zeros((num_scales, num_classes), dtype=int)\n    for i, cls_result in enumerate(results):\n        if cls_result['recall'].size > 0:\n            recalls[:, i] = np.array(cls_result['recall'], ndmin=2)[:, -1]\n        aps[:, i] = cls_result['ap']\n        num_gts[:, i] = cls_result['num_gts']\n\n    label_names = class_name\n\n    if not isinstance(mean_ap, list):\n        mean_ap = [mean_ap]\n\n    header = ['class', 'gts', 'dets', 'recall', 'ap']\n    for i in range(num_scales):\n        if scale_ranges is not None:\n            print_log(f'Scale range {scale_ranges[i]}', logger=logger)\n        table_data = [header]\n        for j in range(num_classes):\n            row_data = [\n                label_names[j], num_gts[i, j], results[j]['num_dets'],\n                f'{recalls[i, j]:.3f}', f'{aps[i, j]:.3f}'\n            ]\n            table_data.append(row_data)\n        table_data.append(['mAP', '', '', '', f'{mean_ap[i]:.3f}'])\n        table = AsciiTable(table_data)\n        table.inner_footing_row_border = True\n        print_log('\\n' + table.table, logger=logger)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/map_utils/struct.py",
    "content": "import numpy as np\nimport torch\nfrom shapely.geometry import LineString\nfrom mmcv.datasets.pipelines import to_tensor\n\nclass LiDARInstanceLines(object):\n    \"\"\"Line instance in LIDAR coordinates\n\n    \"\"\"\n    def __init__(self, \n                 instance_line_list, \n                 sample_dist=1,\n                 num_samples=250,\n                 padding=False,\n                 fixed_num=-1,\n                 padding_value=-10000,\n                 patch_size=None):\n        assert isinstance(instance_line_list, list)\n        assert patch_size is not None\n        if len(instance_line_list) != 0:\n            assert isinstance(instance_line_list[0], LineString)\n        self.patch_size = patch_size\n        self.max_x = self.patch_size[1] / 2\n        self.max_y = self.patch_size[0] / 2\n        self.sample_dist = sample_dist\n        self.num_samples = num_samples\n        self.padding = padding\n        self.fixed_num = fixed_num\n        self.padding_value = padding_value\n\n        self.instance_list = instance_line_list\n\n    @property\n    def start_end_points(self):\n        \"\"\"\n        return torch.Tensor([N,4]), in xstart, ystart, xend, yend form\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_se_points_list = []\n        for instance in self.instance_list:\n            se_points = []\n            se_points.extend(instance.coords[0])\n            se_points.extend(instance.coords[-1])\n            instance_se_points_list.append(se_points)\n        instance_se_points_array = np.array(instance_se_points_list)\n        instance_se_points_tensor = to_tensor(instance_se_points_array)\n        instance_se_points_tensor = instance_se_points_tensor.to(\n                                dtype=torch.float32)\n        instance_se_points_tensor[:,0] = torch.clamp(instance_se_points_tensor[:,0], min=-self.max_x,max=self.max_x)\n        instance_se_points_tensor[:,1] = torch.clamp(instance_se_points_tensor[:,1], min=-self.max_y,max=self.max_y)\n        instance_se_points_tensor[:,2] = torch.clamp(instance_se_points_tensor[:,2], min=-self.max_x,max=self.max_x)\n        instance_se_points_tensor[:,3] = torch.clamp(instance_se_points_tensor[:,3], min=-self.max_y,max=self.max_y)\n        return instance_se_points_tensor\n\n    @property\n    def bbox(self):\n        \"\"\"\n        return torch.Tensor([N,4]), in xmin, ymin, xmax, ymax form\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_bbox_list = []\n        for instance in self.instance_list:\n            # bounds is bbox: [xmin, ymin, xmax, ymax]\n            instance_bbox_list.append(instance.bounds)\n        instance_bbox_array = np.array(instance_bbox_list)\n        instance_bbox_tensor = to_tensor(instance_bbox_array)\n        instance_bbox_tensor = instance_bbox_tensor.to(\n                            dtype=torch.float32)\n        instance_bbox_tensor[:,0] = torch.clamp(instance_bbox_tensor[:,0], min=-self.max_x,max=self.max_x)\n        instance_bbox_tensor[:,1] = torch.clamp(instance_bbox_tensor[:,1], min=-self.max_y,max=self.max_y)\n        instance_bbox_tensor[:,2] = torch.clamp(instance_bbox_tensor[:,2], min=-self.max_x,max=self.max_x)\n        instance_bbox_tensor[:,3] = torch.clamp(instance_bbox_tensor[:,3], min=-self.max_y,max=self.max_y)\n        return instance_bbox_tensor\n\n    @property\n    def fixed_num_sampled_points(self):\n        \"\"\"\n        return torch.Tensor([N,fixed_num,2]), in xmin, ymin, xmax, ymax form\n            N means the num of instances\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_points_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n            instance_points_list.append(sampled_points)\n        instance_points_array = np.array(instance_points_list)\n        instance_points_tensor = to_tensor(instance_points_array)\n        instance_points_tensor = instance_points_tensor.to(\n                            dtype=torch.float32)\n        instance_points_tensor[:,:,0] = torch.clamp(instance_points_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n        instance_points_tensor[:,:,1] = torch.clamp(instance_points_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n        return instance_points_tensor\n\n    @property\n    def fixed_num_sampled_points_ambiguity(self):\n        \"\"\"\n        return torch.Tensor([N,fixed_num,2]), in xmin, ymin, xmax, ymax form\n            N means the num of instances\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_points_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n            instance_points_list.append(sampled_points)\n        instance_points_array = np.array(instance_points_list)\n        instance_points_tensor = to_tensor(instance_points_array)\n        instance_points_tensor = instance_points_tensor.to(\n                            dtype=torch.float32)\n        instance_points_tensor[:,:,0] = torch.clamp(instance_points_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n        instance_points_tensor[:,:,1] = torch.clamp(instance_points_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n        instance_points_tensor = instance_points_tensor.unsqueeze(1)\n        return instance_points_tensor\n\n    @property\n    def fixed_num_sampled_points_torch(self):\n        \"\"\"\n        return torch.Tensor([N,fixed_num,2]), in xmin, ymin, xmax, ymax form\n            N means the num of instances\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_points_list = []\n        for instance in self.instance_list:\n            # distances = np.linspace(0, instance.length, self.fixed_num)\n            # sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n            poly_pts = to_tensor(np.array(list(instance.coords)))\n            poly_pts = poly_pts.unsqueeze(0).permute(0,2,1)\n            sampled_pts = torch.nn.functional.interpolate(poly_pts,size=(self.fixed_num),mode='linear',align_corners=True)\n            sampled_pts = sampled_pts.permute(0,2,1).squeeze(0)\n            instance_points_list.append(sampled_pts)\n        # instance_points_array = np.array(instance_points_list)\n        # instance_points_tensor = to_tensor(instance_points_array)\n        instance_points_tensor = torch.stack(instance_points_list,dim=0)\n        instance_points_tensor = instance_points_tensor.to(\n                            dtype=torch.float32)\n        instance_points_tensor[:,:,0] = torch.clamp(instance_points_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n        instance_points_tensor[:,:,1] = torch.clamp(instance_points_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n        return instance_points_tensor\n\n    @property\n    def shift_fixed_num_sampled_points(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            fixed_num = fixed_num_pts.shape[0]\n            shift_pts_list = []\n            if is_poly:\n                # import pdb;pdb.set_trace()\n                for shift_right_i in range(fixed_num):\n                    shift_pts_list.append(fixed_num_pts.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([fixed_num-shift_pts.shape[0],fixed_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v1(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            pts_num = fixed_num_pts.shape[0]\n            shift_num = pts_num - 1\n            if is_poly:\n                pts_to_shift = fixed_num_pts[:-1,:]\n            shift_pts_list = []\n            if is_poly:\n                for shift_right_i in range(shift_num):\n                    shift_pts_list.append(pts_to_shift.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            if is_poly:\n                _, _, num_coords = shift_pts.shape\n                tmp_shift_pts = shift_pts.new_zeros((shift_num, pts_num, num_coords))\n                tmp_shift_pts[:,:-1,:] = shift_pts\n                tmp_shift_pts[:,-1,:] = shift_pts[:,0,:]\n                shift_pts = tmp_shift_pts\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([shift_num-shift_pts.shape[0],pts_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v2(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instances_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            poly_pts = np.array(list(instance.coords))\n            start_pts = poly_pts[0]\n            end_pts = poly_pts[-1]\n            is_poly = np.equal(start_pts, end_pts)\n            is_poly = is_poly.all()\n            shift_pts_list = []\n            pts_num, coords_num = poly_pts.shape\n            shift_num = pts_num - 1\n            final_shift_num = self.fixed_num - 1\n            if is_poly:\n                pts_to_shift = poly_pts[:-1,:]\n                for shift_right_i in range(shift_num):\n                    shift_pts = np.roll(pts_to_shift,shift_right_i,axis=0)\n                    pts_to_concat = shift_pts[0]\n                    pts_to_concat = np.expand_dims(pts_to_concat,axis=0)\n                    shift_pts = np.concatenate((shift_pts,pts_to_concat),axis=0)\n                    shift_instance = LineString(shift_pts)\n                    shift_sampled_points = np.array([list(shift_instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                    shift_pts_list.append(shift_sampled_points)\n                # import pdb;pdb.set_trace()\n            else:\n                sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                flip_sampled_points = np.flip(sampled_points, axis=0)\n                shift_pts_list.append(sampled_points)\n                shift_pts_list.append(flip_sampled_points)\n            \n            multi_shifts_pts = np.stack(shift_pts_list,axis=0)\n            shifts_num,_,_ = multi_shifts_pts.shape\n\n            if shifts_num > final_shift_num:\n                index = np.random.choice(multi_shifts_pts.shape[0], final_shift_num, replace=False)\n                multi_shifts_pts = multi_shifts_pts[index]\n            \n            multi_shifts_pts_tensor = to_tensor(multi_shifts_pts)\n            multi_shifts_pts_tensor = multi_shifts_pts_tensor.to(\n                            dtype=torch.float32)\n            \n            multi_shifts_pts_tensor[:,:,0] = torch.clamp(multi_shifts_pts_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n            multi_shifts_pts_tensor[:,:,1] = torch.clamp(multi_shifts_pts_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n            # if not is_poly:\n            if multi_shifts_pts_tensor.shape[0] < final_shift_num:\n                padding = torch.full([final_shift_num-multi_shifts_pts_tensor.shape[0],self.fixed_num,2], self.padding_value)\n                multi_shifts_pts_tensor = torch.cat([multi_shifts_pts_tensor,padding],dim=0)\n            instances_list.append(multi_shifts_pts_tensor)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v3(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instances_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            poly_pts = np.array(list(instance.coords))\n            start_pts = poly_pts[0]\n            end_pts = poly_pts[-1]\n            is_poly = np.equal(start_pts, end_pts)\n            is_poly = is_poly.all()\n            shift_pts_list = []\n            pts_num, coords_num = poly_pts.shape\n            shift_num = pts_num - 1\n            final_shift_num = self.fixed_num - 1\n            if is_poly:\n                pts_to_shift = poly_pts[:-1,:]\n                for shift_right_i in range(shift_num):\n                    shift_pts = np.roll(pts_to_shift,shift_right_i,axis=0)\n                    pts_to_concat = shift_pts[0]\n                    pts_to_concat = np.expand_dims(pts_to_concat,axis=0)\n                    shift_pts = np.concatenate((shift_pts,pts_to_concat),axis=0)\n                    shift_instance = LineString(shift_pts)\n                    shift_sampled_points = np.array([list(shift_instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                    shift_pts_list.append(shift_sampled_points)\n                flip_pts_to_shift = np.flip(pts_to_shift, axis=0)\n                for shift_right_i in range(shift_num):\n                    shift_pts = np.roll(flip_pts_to_shift,shift_right_i,axis=0)\n                    pts_to_concat = shift_pts[0]\n                    pts_to_concat = np.expand_dims(pts_to_concat,axis=0)\n                    shift_pts = np.concatenate((shift_pts,pts_to_concat),axis=0)\n                    shift_instance = LineString(shift_pts)\n                    shift_sampled_points = np.array([list(shift_instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                    shift_pts_list.append(shift_sampled_points)\n                # import pdb;pdb.set_trace()\n            else:\n                sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                flip_sampled_points = np.flip(sampled_points, axis=0)\n                shift_pts_list.append(sampled_points)\n                shift_pts_list.append(flip_sampled_points)\n            \n            multi_shifts_pts = np.stack(shift_pts_list,axis=0)\n            shifts_num,_,_ = multi_shifts_pts.shape\n            # import pdb;pdb.set_trace()\n            if shifts_num > 2*final_shift_num:\n                index = np.random.choice(shift_num, final_shift_num, replace=False)\n                flip0_shifts_pts = multi_shifts_pts[index]\n                flip1_shifts_pts = multi_shifts_pts[index+shift_num]\n                multi_shifts_pts = np.concatenate((flip0_shifts_pts,flip1_shifts_pts),axis=0)\n            \n            multi_shifts_pts_tensor = to_tensor(multi_shifts_pts)\n            multi_shifts_pts_tensor = multi_shifts_pts_tensor.to(\n                            dtype=torch.float32)\n            \n            multi_shifts_pts_tensor[:,:,0] = torch.clamp(multi_shifts_pts_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n            multi_shifts_pts_tensor[:,:,1] = torch.clamp(multi_shifts_pts_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n            # if not is_poly:\n            if multi_shifts_pts_tensor.shape[0] < 2*final_shift_num:\n                padding = torch.full([final_shift_num*2-multi_shifts_pts_tensor.shape[0],self.fixed_num,2], self.padding_value)\n                multi_shifts_pts_tensor = torch.cat([multi_shifts_pts_tensor,padding],dim=0)\n            instances_list.append(multi_shifts_pts_tensor)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v4(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            pts_num = fixed_num_pts.shape[0]\n            shift_num = pts_num - 1\n            shift_pts_list = []\n            if is_poly:\n                pts_to_shift = fixed_num_pts[:-1,:]\n                for shift_right_i in range(shift_num):\n                    shift_pts_list.append(pts_to_shift.roll(shift_right_i,0))\n                flip_pts_to_shift = pts_to_shift.flip(0)\n                for shift_right_i in range(shift_num):\n                    shift_pts_list.append(flip_pts_to_shift.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            if is_poly:\n                _, _, num_coords = shift_pts.shape\n                tmp_shift_pts = shift_pts.new_zeros((shift_num*2, pts_num, num_coords))\n                tmp_shift_pts[:,:-1,:] = shift_pts\n                tmp_shift_pts[:,-1,:] = shift_pts[:,0,:]\n                shift_pts = tmp_shift_pts\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([shift_num*2-shift_pts.shape[0],pts_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_torch(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points_torch\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            fixed_num = fixed_num_pts.shape[0]\n            shift_pts_list = []\n            if is_poly:\n                # import pdb;pdb.set_trace()\n                for shift_right_i in range(fixed_num):\n                    shift_pts_list.append(fixed_num_pts.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([fixed_num-shift_pts.shape[0],fixed_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/map_utils/tpfp.py",
    "content": "import mmcv\nimport numpy as np\n\nfrom mmcv.core.evaluation.bbox_overlaps import bbox_overlaps\nfrom .tpfp_chamfer import vec_iou, convex_iou, rbbox_iou, polyline_score, custom_polyline_score\nfrom shapely.geometry import LineString, Polygon\n# from vecmapnet_ops.ops.iou import convex_iou\n\ndef tpfp_bbox(det_bboxes,\n              gt_bboxes,\n              gt_bbox_masks,\n              threshold=0.5):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        use_legacy_coordinate (bool): Whether to use coordinate system in\n            mmdet v1.x. which means width, height should be\n            calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.\n            Default: False.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n        each array is (num_scales, m).\n    \"\"\"\n\n    num_dets = len(det_bboxes)\n    num_gts = len(gt_bboxes)\n\n    # tp and fp\n    tp = np.zeros((num_dets), dtype=np.float32)\n    fp = np.zeros((num_dets), dtype=np.float32)\n\n    # if there is no gt bboxes in this image, then all det bboxes\n    # within area range are false positives\n    # XXX\n    if num_gts == 0:\n        fp[...] = 1\n        return tp, fp\n    \n    if num_dets == 0:\n        return tp, fp\n    \n    # # distance matrix: n x m\n    bbox_p = det_bboxes[:, :-1].reshape(num_dets,-1,2)\n    bbox_g = gt_bboxes.reshape(num_gts,-1,2)\n    bbox_gm = gt_bbox_masks.reshape(num_gts,-1,2)\n    matrix = convex_iou(bbox_p,bbox_g,bbox_gm)\n\n    # for each det, the max iou with all gts\n    matrix_max = matrix.max(axis=1)\n    # for each det, which gt overlaps most with it\n    matrix_argmax = matrix.argmax(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-det_bboxes[:, -1])\n\n    gt_covered = np.zeros(num_gts, dtype=bool)\n\n    # tp = 0 and fp = 0 means ignore this detected bbox,\n    for i in sort_inds:\n        if matrix_max[i] >= threshold:\n            matched_gt = matrix_argmax[i]\n            if not gt_covered[matched_gt]:\n                gt_covered[matched_gt] = True\n                tp[i] = 1\n            else:\n                fp[i] = 1\n        else:\n            fp[i] = 1\n\n    return tp, fp\n\n\ndef tpfp_rbbox(det_bboxes,\n              gt_bboxes,\n              gt_bbox_masks,\n              threshold=0.5):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        use_legacy_coordinate (bool): Whether to use coordinate system in\n            mmdet v1.x. which means width, height should be\n            calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.\n            Default: False.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n        each array is (num_scales, m).\n    \"\"\"\n\n    num_dets = len(det_bboxes)\n    num_gts = len(gt_bboxes)\n\n    # tp and fp\n    tp = np.zeros((num_dets), dtype=np.float32)\n    fp = np.zeros((num_dets), dtype=np.float32)\n\n    # if there is no gt bboxes in this image, then all det bboxes\n    # within area range are false positives\n    # XXX\n    if num_gts == 0:\n        fp[...] = 1\n        return tp, fp\n    \n    if num_dets == 0:\n        return tp, fp\n    \n    # # distance matrix: n x m\n    bbox_p = det_bboxes[:, :-1].reshape(num_dets,-1,2)\n    bbox_g = gt_bboxes.reshape(num_gts,-1,2)\n    bbox_gm = gt_bbox_masks.reshape(num_gts,-1,2)\n    matrix = rbbox_iou(bbox_p,bbox_g,bbox_gm)\n\n    # for each det, the max iou with all gts\n    matrix_max = matrix.max(axis=1)\n    # for each det, which gt overlaps most with it\n    matrix_argmax = matrix.argmax(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-det_bboxes[:, -1])\n\n    gt_covered = np.zeros(num_gts, dtype=bool)\n\n    # tp = 0 and fp = 0 means ignore this detected bbox,\n    for i in sort_inds:\n        if matrix_max[i] >= threshold:\n            matched_gt = matrix_argmax[i]\n            if not gt_covered[matched_gt]:\n                gt_covered[matched_gt] = True\n                tp[i] = 1\n            else:\n                fp[i] = 1\n        else:\n            fp[i] = 1\n\n    return tp, fp\n\n\ndef tpfp_det(det_bboxes,\n             gt_bboxes,\n             threshold=0.5):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        use_legacy_coordinate (bool): Whether to use coordinate system in\n            mmdet v1.x. which means width, height should be\n            calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.\n            Default: False.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n        each array is (num_scales, m).\n    \"\"\"\n\n    num_dets = det_bboxes.shape[0]\n    num_gts = gt_bboxes.shape[0]\n\n    # tp and fp\n    tp = np.zeros((num_dets), dtype=np.float32)\n    fp = np.zeros((num_dets), dtype=np.float32)\n\n    # if there is no gt bboxes in this image, then all det bboxes\n    # within area range are false positives\n    # XXX\n    if num_gts == 0:\n        fp[...] = 1\n        return tp, fp\n    \n    if num_dets == 0:\n        return tp, fp\n    \n    # # distance matrix: n x m\n    matrix = vec_iou(\n            det_bboxes[:, :-1].reshape(num_dets,-1,2), \n            gt_bboxes.reshape(num_gts,-1,2))\n    # for each det, the max iou with all gts\n    matrix_max = matrix.max(axis=1)\n    # for each det, which gt overlaps most with it\n    matrix_argmax = matrix.argmax(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-det_bboxes[:, -1])\n\n    gt_covered = np.zeros(num_gts, dtype=bool)\n\n    # tp = 0 and fp = 0 means ignore this detected bbox,\n    for i in sort_inds:\n        if matrix_max[i] >= threshold:\n            matched_gt = matrix_argmax[i]\n            if not gt_covered[matched_gt]:\n                gt_covered[matched_gt] = True\n                tp[i] = 1\n            else:\n                fp[i] = 1\n        else:\n            fp[i] = 1\n\n    return tp, fp\n\n\ndef tpfp_gen(gen_lines,\n             gt_lines,\n             threshold=0.5,\n             metric='POR'):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        use_legacy_coordinate (bool): Whether to use coordinate system in\n            mmdet v1.x. which means width, height should be\n            calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.\n            Default: False.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n        each array is (num_scales, m).\n    \"\"\"\n\n    num_gens = gen_lines.shape[0]\n    num_gts = gt_lines.shape[0]\n    \n    # tp and fp\n    tp = np.zeros((num_gens), dtype=np.float32)\n    fp = np.zeros((num_gens), dtype=np.float32)\n\n    # if there is no gt bboxes in this image, then all det bboxes\n    # within area range are false positives\n    if num_gts == 0:\n        fp[...] = 1\n        return tp, fp\n    \n    if num_gens == 0:\n        return tp, fp\n    \n    gen_scores = gen_lines[:,-1] # n\n    # distance matrix: n x m\n\n    # matrix = custom_polyline_score(\n    #         gen_lines[:,:-1].reshape(num_gens,-1,2), \n    #         gt_lines.reshape(num_gts,-1,2),linewidth=2.,metric=metric)\n\n    # TODO MAY bug here\n    matrix = polyline_score(\n            gen_lines[:,:-1].reshape(num_gens,-1,2), \n            gt_lines.reshape(num_gts,-1,2),linewidth=2.,metric=metric)\n    # for each det, the max iou with all gts\n    matrix_max = matrix.max(axis=1)\n    # for each det, which gt overlaps most with it\n    matrix_argmax = matrix.argmax(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-gen_scores)\n\n    gt_covered = np.zeros(num_gts, dtype=bool)\n\n    # tp = 0 and fp = 0 means ignore this detected bbox,\n    for i in sort_inds:\n        if matrix_max[i] >= threshold:\n            matched_gt = matrix_argmax[i]\n            if not gt_covered[matched_gt]:\n                gt_covered[matched_gt] = True\n                tp[i] = 1\n            else:\n                fp[i] = 1\n        else:\n            fp[i] = 1\n\n    return tp, fp\n\n\ndef custom_tpfp_gen(gen_lines,\n             gt_lines,\n             threshold=0.5,\n             metric='chamfer'):\n    \"\"\"Check if detected bboxes are true positive or false positive.\n\n    Args:\n        det_bbox (ndarray): Detected bboxes of this image, of shape (m, 5).\n        gt_bboxes (ndarray): GT bboxes of this image, of shape (n, 4).\n        gt_bboxes_ignore (ndarray): Ignored gt bboxes of this image,\n            of shape (k, 4). Default: None\n        iou_thr (float): IoU threshold to be considered as matched.\n            Default: 0.5.\n        use_legacy_coordinate (bool): Whether to use coordinate system in\n            mmdet v1.x. which means width, height should be\n            calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.\n            Default: False.\n\n    Returns:\n        tuple[np.ndarray]: (tp, fp) whose elements are 0 and 1. The shape of\n        each array is (num_scales, m).\n    \"\"\"\n    if metric == 'chamfer':\n        if threshold >0:\n            threshold= -threshold\n    # else:\n    #     raise NotImplementedError\n\n    # import pdb;pdb.set_trace()\n    num_gens = gen_lines.shape[0]\n    num_gts = gt_lines.shape[0]\n    \n    # tp and fp\n    tp = np.zeros((num_gens), dtype=np.float32)\n    fp = np.zeros((num_gens), dtype=np.float32)\n\n    # if there is no gt bboxes in this image, then all det bboxes\n    # within area range are false positives\n    if num_gts == 0:\n        fp[...] = 1\n        return tp, fp\n    \n    if num_gens == 0:\n        return tp, fp\n    \n    gen_scores = gen_lines[:,-1] # n\n    # distance matrix: n x m\n\n    matrix = custom_polyline_score(\n            gen_lines[:,:-1].reshape(num_gens,-1,2), \n            gt_lines.reshape(num_gts,-1,2),linewidth=2.,metric=metric)\n    # for each det, the max iou with all gts\n    matrix_max = matrix.max(axis=1)\n    # for each det, which gt overlaps most with it\n    matrix_argmax = matrix.argmax(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-gen_scores)\n\n    gt_covered = np.zeros(num_gts, dtype=bool)\n\n    # tp = 0 and fp = 0 means ignore this detected bbox,\n    for i in sort_inds:\n        if matrix_max[i] >= threshold:\n            matched_gt = matrix_argmax[i]\n            if not gt_covered[matched_gt]:\n                gt_covered[matched_gt] = True\n                tp[i] = 1\n            else:\n                fp[i] = 1\n        else:\n            fp[i] = 1\n\n    return tp, fp\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/map_utils/tpfp_chamfer.py",
    "content": "# from ..chamfer_dist import ChamferDistance\nimport numpy as np\nfrom shapely.geometry import LineString, Polygon\nfrom shapely.strtree import STRtree\nfrom shapely.geometry import CAP_STYLE, JOIN_STYLE\nfrom scipy.spatial import distance\nimport similaritymeasures\n\n# def chamfer_distance(pred_bbox, gt_bbox):\n\n#     cd_dist_func = ChamferDistance.vec_cd_dist(\n#         pred, pred_mask, tgt, tgt_mask)()\n\n\ndef vec_iou(pred_lines, gt_lines):\n    '''\n        each line with 1 meter width\n        pred_lines: num_preds, npts, 2\n        gt_lines: num_gts, npts, 2\n    '''\n\n    num_preds = pred_lines.shape[0]\n    num_gts = gt_lines.shape[0]\n\n    pred_lines_shapely = \\\n        [LineString(i).buffer(1.,\n            cap_style=CAP_STYLE.round, join_style=JOIN_STYLE.round)\n                          for i in pred_lines]\n    gt_lines_shapely =\\\n        [LineString(i).buffer(1.,\n            cap_style=CAP_STYLE.round, join_style=JOIN_STYLE.round)\n                        for i in gt_lines]\n\n    # construct tree\n    tree = STRtree(gt_lines_shapely)\n    index_by_id = dict((id(pt), i) for i, pt in enumerate(gt_lines_shapely))\n\n    iou_matrix = np.zeros((num_preds, num_gts))\n\n    for i, pline in enumerate(pred_lines_shapely):\n\n        for o in tree.query(pline):\n            if o.intersects(pline):\n                gt_id = index_by_id[id(o)]\n\n                inter = o.intersection(pline).area\n                union = o.union(pline).area\n                iou_matrix[i, gt_id] = inter / union\n\n    return iou_matrix\n\ndef convex_iou(pred_lines, gt_lines, gt_mask):\n    '''\n        each line with 1 meter width\n        pred_lines: num_preds, List [npts, 2]\n        gt_lines: num_gts, npts, 2\n        gt_mask: num_gts, npts, 2\n    '''\n\n    num_preds = len(pred_lines)\n    num_gts = len(gt_lines)\n\n    pred_lines_shapely = \\\n        [Polygon(i).convex_hull for i in pred_lines]\n    gt_lines_shapely =\\\n        [Polygon(i[m].reshape(-1,2)).convex_hull for i,m in zip(gt_lines,gt_mask)]\n\n    # construct tree\n    tree = STRtree(pred_lines_shapely)\n    index_by_id = dict((id(pt), i) for i, pt in enumerate(pred_lines_shapely))\n\n    iou_matrix = np.zeros((num_preds, num_gts))\n\n    for i, pline in enumerate(gt_lines_shapely):\n\n        for o in tree.query(pline):\n            if o.intersects(pline):\n                pred_id = index_by_id[id(o)]\n\n                inter = o.intersection(pline).area\n                union = o.union(pline).area\n                iou_matrix[pred_id, i] = inter / union\n\n    return iou_matrix\n\ndef rbbox_iou(pred_lines, gt_lines, gt_mask):\n    '''\n        each line with 1 meter width\n        pred_lines: num_preds, List [npts, 2]\n        gt_lines: num_gts, npts, 2\n        gt_mask: num_gts, npts, 2\n    '''\n\n    num_preds = len(pred_lines)\n    num_gts = len(gt_lines)\n\n    pred_lines_shapely = \\\n        [Polygon(i).minimum_rotated_rectangle for i in pred_lines]\n    gt_lines_shapely =\\\n        [Polygon(i[m].reshape(-1,2)) for i,m in zip(gt_lines,gt_mask)]\n\n    # construct tree\n    tree = STRtree(pred_lines_shapely)\n    index_by_id = dict((id(pt), i) for i, pt in enumerate(pred_lines_shapely))\n\n    iou_matrix = np.zeros((num_preds, num_gts))\n\n    for i, pline in enumerate(gt_lines_shapely):\n\n        for o in tree.query(pline):\n            if o.intersects(pline):\n                pred_id = index_by_id[id(o)]\n\n                inter = o.intersection(pline).area\n                union = o.union(pline).area\n                iou_matrix[pred_id, i] = inter / union\n\n    return iou_matrix\n\n\ndef polyline_score(pred_lines, gt_lines, linewidth=1., metric='POR'):\n    '''\n        each line with 1 meter width\n        pred_lines: num_preds, List [npts, 2]\n        gt_lines: num_gts, npts, 2\n        gt_mask: num_gts, npts, 2\n    '''\n    positive_threshold = 1.\n    num_preds = len(pred_lines)\n    num_gts = len(gt_lines)\n    line_length = pred_lines.shape[1]\n\n    # gt_lines = gt_lines + np.array((1.,1.))\n\n    pred_lines_shapely = \\\n        [LineString(i).buffer(linewidth,\n            cap_style=CAP_STYLE.flat, join_style=JOIN_STYLE.mitre)\n                          for i in pred_lines]\n    gt_lines_shapely =\\\n        [LineString(i).buffer(linewidth,\n            cap_style=CAP_STYLE.flat, join_style=JOIN_STYLE.mitre)\n                        for i in gt_lines]\n\n    # construct tree\n    tree = STRtree(pred_lines_shapely)\n    index_by_id = dict((id(pt), i) for i, pt in enumerate(pred_lines_shapely))\n\n    if metric=='POR':\n        iou_matrix = np.zeros((num_preds, num_gts),dtype=np.float64)\n    elif metric=='frechet':\n        iou_matrix = np.full((num_preds, num_gts), -100.)\n    elif metric=='chamfer':\n        iou_matrix = np.full((num_preds, num_gts), -100.)\n    elif metric=='chamfer_v2':\n        iou_matrix = np.full((num_preds, num_gts), -100.)\n\n    for i, pline in enumerate(gt_lines_shapely):\n\n        for o in tree.query(pline):\n            if o.intersects(pline):\n                pred_id = index_by_id[id(o)]\n\n                if metric=='POR':\n                    dist_mat = distance.cdist(\n                        pred_lines[pred_id], gt_lines[i], 'euclidean')\n                    \n                    valid_ab = (dist_mat.min(-1) < positive_threshold).sum()\n                    valid_ba = (dist_mat.min(-2) < positive_threshold).sum()\n\n                    iou_matrix[pred_id, i] = min(valid_ba,valid_ab) / line_length\n                    # iou_matrix[pred_id, i] = ((valid_ba+valid_ab)/2) / line_length\n                    # assert iou_matrix[pred_id, i] <= 1. and iou_matrix[pred_id, i] >= 0.\n                elif metric=='frechet':\n                    fdistance_1 = \\\n                        -similaritymeasures.frechet_dist(pred_lines[pred_id], gt_lines[i])\n                    fdistance_2 = \\\n                        -similaritymeasures.frechet_dist(pred_lines[pred_id][::-1], gt_lines[i])\n                    fdistance = max(fdistance_1,fdistance_2)\n                    iou_matrix[pred_id, i] = fdistance\n\n                elif metric=='chamfer':\n                    dist_mat = distance.cdist(\n                        pred_lines[pred_id], gt_lines[i], 'euclidean')\n                    \n                    valid_ab = dist_mat.min(-1).sum()\n                    valid_ba = dist_mat.min(-2).sum()\n\n                    iou_matrix[pred_id, i] = -(valid_ba+valid_ab)/(2*line_length)\n                    # if iou_matrix[pred_id, i] == 0:\n                    #     import ipdb; ipdb.set_trace()\n                elif metric=='chamfer_v2':\n                    dist_mat = distance.cdist(\n                        pred_lines[pred_id], gt_lines[i], 'euclidean')\n                    \n                    valid_ab = dist_mat.min(-1).sum()\n                    valid_ba = dist_mat.min(-2).sum()\n\n                    iou_matrix[pred_id, i] = -(valid_ba/pred_lines[pred_id].shape[0]\n                                                +valid_ab/gt_lines[i].shape[0])/2\n                    # if iou_matrix[pred_id, i] == 0:\n                    #     import ipdb; ipdb.set_trace()\n\n    \n    # if True:\n    #     import matplotlib.pyplot as plt\n    #     print('pred num', num_preds)\n    #     print('gt num', num_gts)\n    #     for i in range(num_preds):\n    #         plt.plot(pred_lines[i][:,0],pred_lines[i][:,1],'-',color='red',alpha=0.5)\n    #     for i in range(num_gts):\n    #         plt.plot(gt_lines[i][:,0],gt_lines[i][:,1],'-',color='blue',alpha=0.5)\n    #     plt.savefig('test.png')\n    #     plt.close()\n    return iou_matrix\n\n\ndef custom_polyline_score(pred_lines, gt_lines, linewidth=1., metric='chamfer'):\n    '''\n        each line with 1 meter width\n        pred_lines: num_preds, List [npts, 2]\n        gt_lines: num_gts, npts, 2\n        gt_mask: num_gts, npts, 2\n    '''\n    if metric == 'iou':\n        linewidth = 1.0\n    positive_threshold = 1.\n    num_preds = len(pred_lines)\n    num_gts = len(gt_lines)\n    line_length = pred_lines.shape[1]\n\n    # gt_lines = gt_lines + np.array((1.,1.))\n\n    pred_lines_shapely = \\\n        [LineString(i).buffer(linewidth,\n            cap_style=CAP_STYLE.flat, join_style=JOIN_STYLE.mitre)\n                          for i in pred_lines]\n    gt_lines_shapely =\\\n        [LineString(i).buffer(linewidth,\n            cap_style=CAP_STYLE.flat, join_style=JOIN_STYLE.mitre)\n                        for i in gt_lines]\n\n    # construct tree\n    tree = STRtree(pred_lines_shapely)\n    index_by_id = dict((id(pt), i) for i, pt in enumerate(pred_lines_shapely))\n\n\n    if metric=='chamfer':\n        iou_matrix = np.full((num_preds, num_gts), -100.)\n    elif metric=='iou':\n        iou_matrix = np.zeros((num_preds, num_gts),dtype=np.float64)\n    else:\n        raise NotImplementedError\n\n    for i, pline in enumerate(gt_lines_shapely):\n\n        for o in tree.query(pline):\n            if o.intersects(pline):\n                pred_id = index_by_id[id(o)]\n\n                if metric=='chamfer':\n                    dist_mat = distance.cdist(\n                        pred_lines[pred_id], gt_lines[i], 'euclidean')\n                    # import pdb;pdb.set_trace()\n                    valid_ab = dist_mat.min(-1).mean()\n                    valid_ba = dist_mat.min(-2).mean()\n\n                    iou_matrix[pred_id, i] = -(valid_ba+valid_ab)/2\n                elif metric=='iou':\n                    inter = o.intersection(pline).area\n                    union = o.union(pline).area\n                    iou_matrix[pred_id, i] = inter / union\n\n    return iou_matrix\n\nif __name__ == '__main__':\n    import torch\n\n    line1 = torch.tensor([\n        [1, 5], [3, 5], [5, 5]\n    ])\n\n    line0 = torch.tensor([\n        [3, 6], [4, 8], [5, 6]\n    ])\n\n    line2 = torch.tensor([\n        [1, 4], [3, 4], [5, 4]\n    ])\n\n    line3 = torch.tensor([\n        [4, 4], [3, 3], [5, 3]\n    ])\n\n    gt = torch.stack((line2, line3), dim=0).type(torch.float32)\n    pred = torch.stack((line0, line1), dim=0).type(torch.float32)\n\n    # import ipdb; ipdb.set_trace()\n    import mmcv\n    # with mmcv.Timer():\n    #     gt = upsampler(gt, pts=10)\n    #     pred = upsampler(pred, pts=10)\n\n    import matplotlib.pyplot as plt\n    from shapely.geometry import LineString\n    from descartes import PolygonPatch\n    \n    iou_matrix = vec_iou(pred,gt)\n    print(iou_matrix)\n    # import pdb;pdb.set_trace()\n    score_matrix = custom_polyline_score(pred, gt, linewidth=1., metric='chamfer')\n    print(score_matrix)\n    fig, ax = plt.subplots()\n    for i in gt:\n        i = i.numpy()\n        plt.plot(i[:, 0], i[:, 1], 'o', color='red')\n        plt.plot(i[:, 0], i[:, 1], '-', color='red')\n\n        dilated = LineString(i).buffer(1, cap_style=CAP_STYLE.round, join_style=JOIN_STYLE.round)\n        patch1 = PolygonPatch(dilated, fc='red', ec='red', alpha=0.5, zorder=-1)\n        ax.add_patch(patch1)\n\n    for i in pred:\n        i = i.numpy()\n        plt.plot(i[:, 0], i[:, 1], 'o', color='blue')\n        plt.plot(i[:, 0], i[:, 1], '-', color='blue')\n\n        dilated = LineString(i).buffer(1, cap_style=CAP_STYLE.flat, join_style=JOIN_STYLE.mitre)\n        patch1 = PolygonPatch(dilated, fc='blue', ec='blue', alpha=0.5, zorder=-1)\n        ax.add_patch(patch1)\n\n\n    ax.axis('equal')\n\n\n    plt.savefig('test3.png')    "
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscenes_dataset.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport pyquaternion\nimport tempfile\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom os import path as osp\n\nfrom mmcv.datasets import DATASETS\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import track_iter_progress, mkdir_or_exist\nfrom mmcv.core import show_result\nfrom mmcv.core.bbox.structures.box_3d_mode import Box3DMode\nfrom mmcv.core.bbox.structures.coord_3d_mode import Coord3DMode\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom .custom_3d import Custom3DDataset\nfrom .pipelines import Compose\n\n\n@DATASETS.register_module()\nclass NuScenesDataset(Custom3DDataset):\n    r\"\"\"NuScenes Dataset.\n\n    This class serves as the API for experiments on the NuScenes Dataset.\n\n    Please refer to `NuScenes Dataset <https://www.nuscenes.org/download>`_\n    for data downloading.\n\n    Args:\n        ann_file (str): Path of annotation file.\n        pipeline (list[dict], optional): Pipeline used for data processing.\n            Defaults to None.\n        data_root (str): Path of dataset root.\n        classes (tuple[str], optional): Classes used in the dataset.\n            Defaults to None.\n        load_interval (int, optional): Interval of loading the dataset. It is\n            used to uniformly sample the dataset. Defaults to 1.\n        with_velocity (bool, optional): Whether include velocity prediction\n            into the experiments. Defaults to True.\n        modality (dict, optional): Modality to specify the sensor data used\n            as input. Defaults to None.\n        box_type_3d (str, optional): Type of 3D box of this dataset.\n            Based on the `box_type_3d`, the dataset will encapsulate the box\n            to its original format then converted them to `box_type_3d`.\n            Defaults to 'LiDAR' in this dataset. Available options includes.\n            - 'LiDAR': Box in LiDAR coordinates.\n            - 'Depth': Box in depth coordinates, usually for indoor dataset.\n            - 'Camera': Box in camera coordinates.\n        filter_empty_gt (bool, optional): Whether to filter empty GT.\n            Defaults to True.\n        test_mode (bool, optional): Whether the dataset is in test mode.\n            Defaults to False.\n        eval_version (bool, optional): Configuration version of evaluation.\n            Defaults to  'detection_cvpr_2019'.\n        use_valid_flag (bool): Whether to use `use_valid_flag` key in the info\n            file as mask to filter gt_boxes and gt_names. Defaults to False.\n    \"\"\"\n    NameMapping = {\n        'movable_object.barrier': 'barrier',\n        'vehicle.bicycle': 'bicycle',\n        'vehicle.bus.bendy': 'bus',\n        'vehicle.bus.rigid': 'bus',\n        'vehicle.car': 'car',\n        'vehicle.construction': 'construction_vehicle',\n        'vehicle.motorcycle': 'motorcycle',\n        'human.pedestrian.adult': 'pedestrian',\n        'human.pedestrian.child': 'pedestrian',\n        'human.pedestrian.construction_worker': 'pedestrian',\n        'human.pedestrian.police_officer': 'pedestrian',\n        'movable_object.trafficcone': 'traffic_cone',\n        'vehicle.trailer': 'trailer',\n        'vehicle.truck': 'truck'\n    }\n    DefaultAttribute = {\n        'car': 'vehicle.parked',\n        'pedestrian': 'pedestrian.moving',\n        'trailer': 'vehicle.parked',\n        'truck': 'vehicle.parked',\n        'bus': 'vehicle.moving',\n        'motorcycle': 'cycle.without_rider',\n        'construction_vehicle': 'vehicle.parked',\n        'bicycle': 'cycle.without_rider',\n        'barrier': '',\n        'traffic_cone': '',\n    }\n    AttrMapping = {\n        'cycle.with_rider': 0,\n        'cycle.without_rider': 1,\n        'pedestrian.moving': 2,\n        'pedestrian.standing': 3,\n        'pedestrian.sitting_lying_down': 4,\n        'vehicle.moving': 5,\n        'vehicle.parked': 6,\n        'vehicle.stopped': 7,\n    }\n    AttrMapping_rev = [\n        'cycle.with_rider',\n        'cycle.without_rider',\n        'pedestrian.moving',\n        'pedestrian.standing',\n        'pedestrian.sitting_lying_down',\n        'vehicle.moving',\n        'vehicle.parked',\n        'vehicle.stopped',\n    ]\n    # https://github.com/nutonomy/nuscenes-devkit/blob/57889ff20678577025326cfc24e57424a829be0a/python-sdk/nuscenes/eval/detection/evaluate.py#L222 # noqa\n    ErrNameMapping = {\n        'trans_err': 'mATE',\n        'scale_err': 'mASE',\n        'orient_err': 'mAOE',\n        'vel_err': 'mAVE',\n        'attr_err': 'mAAE'\n    }\n    CLASSES = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',\n               'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',\n               'barrier')\n\n    def __init__(self,\n                 ann_file,\n                 pipeline=None,\n                 data_root=None,\n                 classes=None,\n                 load_interval=1,\n                 with_velocity=True,\n                 modality=None,\n                 box_type_3d='LiDAR',\n                 filter_empty_gt=True,\n                 test_mode=False,\n                 eval_version='detection_cvpr_2019',\n                 use_valid_flag=False):\n        self.load_interval = load_interval\n        self.use_valid_flag = use_valid_flag\n        super().__init__(\n            data_root=data_root,\n            ann_file=ann_file,\n            pipeline=pipeline,\n            classes=classes,\n            modality=modality,\n            box_type_3d=box_type_3d,\n            filter_empty_gt=filter_empty_gt,\n            test_mode=test_mode)\n\n        self.with_velocity = with_velocity\n        self.eval_version = eval_version\n        from nuscenes.eval.detection.config import config_factory\n        self.eval_detection_configs = config_factory(self.eval_version)\n        # self.eval_detection_configs.class_names = list(self.eval_detection_configs.class_names)\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n\n    def get_cat_ids(self, idx):\n        \"\"\"Get category distribution of single scene.\n\n        Args:\n            idx (int): Index of the data_info.\n\n        Returns:\n            dict[list]: for each category, if the current scene\n                contains such boxes, store a list containing idx,\n                otherwise, store empty list.\n        \"\"\"\n        info = self.data_infos[idx]\n        if self.use_valid_flag:\n            mask = info['valid_flag']\n            gt_names = set(info['gt_names'][mask])\n        else:\n            gt_names = set(info['gt_names'])\n\n        cat_ids = []\n        for name in gt_names:\n            if name in self.CLASSES:\n                cat_ids.append(self.cat2id[name])\n        return cat_ids\n\n    def load_annotations(self, ann_file):\n        \"\"\"Load annotations from ann_file.\n\n        Args:\n            ann_file (str): Path of the annotation file.\n\n        Returns:\n            list[dict]: List of annotations sorted by timestamps.\n        \"\"\"\n        data = load(ann_file)\n        data_infos = list(sorted(data['infos'], key=lambda e: e['timestamp']))\n        data_infos = data_infos[::self.load_interval]\n        self.metadata = data['metadata']\n        self.version = self.metadata['version']\n        return data_infos\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n        # standard protocal modified from SECOND.Pytorch\n        input_dict = dict(\n            sample_idx=info['token'],\n            pts_filename=info['lidar_path'],\n            sweeps=info['sweeps'],\n            timestamp=info['timestamp'] / 1e6,\n        )\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            for cam_type, cam_info in info['cams'].items():\n                image_paths.append(cam_info['data_path'])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info['sensor2lidar_rotation'])\n                lidar2cam_t = cam_info[\n                    'sensor2lidar_translation'] @ lidar2cam_r.T\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = cam_info['cam_intrinsic']\n                viewpad = np.eye(4)\n                viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                lidar2img_rts.append(lidar2img_rt)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                ))\n\n        if not self.test_mode:\n            annos = self.get_ann_info(index)\n            input_dict['ann_info'] = annos\n\n        return input_dict\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n        if self.use_valid_flag:\n            mask = info['valid_flag']\n        else:\n            mask = info['num_lidar_pts'] > 0\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info['gt_velocity'][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        # the nuscenes box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d)\n        return anns_results\n\n    def _format_bbox(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n\n        # import pdb\n        # pdb.set_trace()\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(det)\n            sample_token = self.data_infos[sample_id]['token']\n            boxes = lidar_nusc_box_to_global(self.data_infos[sample_id], boxes,\n                                             mapped_class_names,\n                                             self.eval_detection_configs,\n                                             self.eval_version)\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if np.sqrt(box.velocity[0]**2 + box.velocity[1]**2) > 0.2:\n                    if name in [\n                            'car',\n                            'construction_vehicle',\n                            'bus',\n                            'truck',\n                            'trailer',\n                    ]:\n                        attr = 'vehicle.moving'\n                    elif name in ['bicycle', 'motorcycle']:\n                        attr = 'cycle.with_rider'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n                else:\n                    if name in ['pedestrian']:\n                        attr = 'pedestrian.standing'\n                    elif name in ['bus']:\n                        attr = 'vehicle.stopped'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                    detection_name=name,\n                    detection_score=box.score,\n                    attribute_name=attr)\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n        }\n\n        #pdb.set_trace()\n\n        mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        from nuscenes.eval.detection.evaluate import NuScenesEval\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        nusc_eval = NuScenesEval(\n            nusc,\n            config=self.eval_detection_configs,\n            result_path=result_path,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False)\n        nusc_eval.main(render_curves=False)\n\n        # record metrics\n        metrics = load(osp.join(output_dir, 'metrics_summary.json'))\n        detail = dict()\n        metric_prefix = f'{result_name}_NuScenes'\n        for name in self.CLASSES:\n            for k, v in metrics['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,\n                                      self.ErrNameMapping[k])] = val\n\n        detail['{}/NDS'.format(metric_prefix)] = metrics['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics['mean_ap']\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        assert len(results) == len(self), (\n            'The length of results is not equal to the dataset len: {} != {}'.\n            format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        # currently the output prediction results could be in two formats\n        # 1. list of dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...)\n        # 2. list of dict('pts_bbox' or 'img_bbox':\n        #     dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...))\n        # this is a workaround to enable evaluation of both formats on nuScenes\n        # refer to https://github.com/open-mmlab/mmcvection3d/issues/449\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        return result_files, tmp_dir\n\n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print('Evaluating bboxes of {}'.format(name))\n                ret_dict = self._evaluate_single(result_files[name])\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(result_files)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\n    def _build_default_pipeline(self):\n        \"\"\"Build the default pipeline for this dataset.\"\"\"\n        pipeline = [\n            dict(\n                type='LoadPointsFromFile',\n                coord_type='LIDAR',\n                load_dim=5,\n                use_dim=5,\n                file_client_args=dict(backend='disk')),\n            dict(\n                type='LoadPointsFromMultiSweeps',\n                sweeps_num=10,\n                file_client_args=dict(backend='disk')),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=self.CLASSES,\n                with_label=False),\n            dict(type='Collect3D', keys=['points'])\n        ]\n        return Compose(pipeline)\n\n    def show(self, results, out_dir, show=True, pipeline=None):\n        \"\"\"Results visualization.\n\n        Args:\n            results (list[dict]): List of bounding boxes results.\n            out_dir (str): Output directory of visualization result.\n            show (bool): Visualize the results online.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n        \"\"\"\n        assert out_dir is not None, 'Expect out_dir, got none.'\n        pipeline = self._get_pipeline(pipeline)\n        for i, result in enumerate(results):\n            if 'pts_bbox' in result.keys():\n                result = result['pts_bbox']\n            data_info = self.data_infos[i]\n            pts_path = data_info['lidar_path']\n            file_name = osp.split(pts_path)[-1].split('.')[0]\n            points = self._extract_data(i, pipeline, 'points').numpy()\n            # for now we convert points into depth mode\n            points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,\n                                               Coord3DMode.DEPTH)\n            inds = result['scores_3d'] > 0.1\n            gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()\n            show_gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,\n                                               Box3DMode.DEPTH)\n            pred_bboxes = result['boxes_3d'][inds].tensor.numpy()\n            show_pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,\n                                                 Box3DMode.DEPTH)\n            show_result(points, show_gt_bboxes, show_pred_bboxes, out_dir,\n                        file_name, show)\n\n\ndef output_to_nusc_box(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n\n    Args:\n        detection (dict): Detection results.\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        velocity = (*box3d.tensor[i, 7:9], 0.0)\n        # velo_val = np.linalg.norm(box3d[i, 7:9])\n        # velo_ori = box3d[i, 6]\n        # velocity = (\n        # velo_val * np.cos(velo_ori), velo_val * np.sin(velo_ori), 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(info,\n                             boxes,\n                             classes,\n                             eval_configs,\n                             eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from ego to global coordinate.\n\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str): Evaluation version.\n            Default: 'detection_cvpr_2019'\n\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    for box in boxes:\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info['lidar2ego_rotation']))\n        box.translate(np.array(info['lidar2ego_translation']))\n        # filter det in ego.\n        cls_range_map = eval_configs.class_range\n        radius = np.linalg.norm(box.center[:2], 2)\n        det_range = cls_range_map[classes[box.label]]\n        if radius > det_range:\n            continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n    return box_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscenes_e2e_dataset.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport copy\nimport numpy as np\nimport torch\nfrom mmcv.datasets import DATASETS\nfrom mmcv.datasets.pipelines import to_tensor\nfrom mmcv.datasets import NuScenesDataset\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom mmcv.fileio.file_client import FileClient\nfrom mmcv.fileio.io import load, dump\nfrom mmcv.utils import track_iter_progress, mkdir_or_exist\nfrom os import path as osp\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom .eval_utils.nuscenes_eval import NuScenesEval_custom\nfrom nuscenes.eval.tracking.evaluate import TrackingEval\nfrom .eval_utils.nuscenes_eval_motion import MotionEval\nfrom nuscenes.eval.common.config import config_factory\nimport tempfile\nfrom mmcv.parallel import DataContainer as DC\nimport random\nimport pickle\nfrom prettytable import PrettyTable\n\nfrom nuscenes import NuScenes\nfrom mmcv.datasets.data_utils.vector_map import VectorizedLocalMap\nfrom mmcv.datasets.data_utils.rasterize import preprocess_map\nfrom mmcv.datasets.eval_utils.map_api import NuScenesMap\nfrom mmcv.datasets.data_utils.trajectory_api import NuScenesTraj\nfrom .data_utils.data_utils import lidar_nusc_box_to_global, obtain_map_info, output_to_nusc_box, output_to_nusc_box_det\nfrom nuscenes.prediction import convert_local_coords_to_global\n\n\n@DATASETS.register_module()\nclass NuScenesE2EDataset(NuScenesDataset):\n    r\"\"\"NuScenes E2E Dataset.\n\n    This dataset only add camera intrinsics and extrinsics to the results.\n    \"\"\"\n\n    def __init__(self,\n                 queue_length=4,\n                 bev_size=(200, 200),\n                 patch_size=(102.4, 102.4),\n                 canvas_size=(200, 200),\n                 overlap_test=False,\n                 predict_steps=12,\n                 planning_steps=6,\n                 past_steps=4,\n                 fut_steps=4,\n                 use_nonlinear_optimizer=False,\n                 lane_ann_file=None,\n                 eval_mod=None,\n\n                 # For debug\n                 is_debug=False,\n                 len_debug=30,\n\n                 # Occ dataset\n                 enbale_temporal_aug=False,\n                 occ_receptive_field=3,\n                 occ_n_future=4,\n                 occ_filter_invalid_sample=False,\n                 occ_filter_by_valid_flag=False,\n\n                 file_client_args=dict(backend='disk'),\n                 *args, \n                 **kwargs):\n        # init before super init since it is called in parent class\n        self.file_client_args = file_client_args\n        self.file_client = FileClient(**file_client_args)\n\n        self.is_debug = is_debug\n        self.len_debug = len_debug\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.overlap_test = overlap_test\n        self.bev_size = bev_size\n        self.predict_steps = predict_steps\n        self.planning_steps = planning_steps\n        self.past_steps = past_steps\n        self.fut_steps = fut_steps\n        self.scene_token = None\n        self.lane_infos = self.load_annotations(lane_ann_file) \\\n            if lane_ann_file else None\n        self.eval_mod = eval_mod\n\n        self.use_nonlinear_optimizer = use_nonlinear_optimizer\n\n        self.nusc = NuScenes(version=self.version,\n                             dataroot=self.data_root, verbose=True)\n\n        self.map_num_classes = 3\n        if canvas_size[0] == 50:\n            self.thickness = 1\n        elif canvas_size[0] == 200:\n            self.thickness = 2\n        else:\n            assert False\n        self.angle_class = 36\n        self.patch_size = patch_size\n        self.canvas_size = canvas_size\n        self.nusc_maps = {\n            'boston-seaport': NuScenesMap(dataroot=self.data_root, map_name='boston-seaport'),\n            'singapore-hollandvillage': NuScenesMap(dataroot=self.data_root, map_name='singapore-hollandvillage'),\n            'singapore-onenorth': NuScenesMap(dataroot=self.data_root, map_name='singapore-onenorth'),\n            'singapore-queenstown': NuScenesMap(dataroot=self.data_root, map_name='singapore-queenstown'),\n        }\n        self.vector_map = VectorizedLocalMap(\n            self.data_root,\n            patch_size=self.patch_size,\n            canvas_size=self.canvas_size)\n        self.traj_api = NuScenesTraj(self.nusc,\n                                     self.predict_steps,\n                                     self.planning_steps,\n                                     self.past_steps,\n                                     self.fut_steps,\n                                     self.with_velocity,\n                                     self.CLASSES,\n                                     self.box_mode_3d,\n                                     self.use_nonlinear_optimizer)\n\n        # Occ\n        self.enbale_temporal_aug = enbale_temporal_aug\n        assert self.enbale_temporal_aug is False\n\n        self.occ_receptive_field = occ_receptive_field  # past + current\n        self.occ_n_future = occ_n_future  # future only\n        self.occ_filter_invalid_sample = occ_filter_invalid_sample\n        self.occ_filter_by_valid_flag = occ_filter_by_valid_flag\n        self.occ_only_total_frames = 7  # NOTE: hardcode, not influenced by planning\n\n    def __len__(self):\n        if not self.is_debug:\n            return len(self.data_infos)\n        else:\n            return self.len_debug\n\n    def load_annotations(self, ann_file):\n        \"\"\"Load annotations from ann_file.\n        Args:\n            ann_file (str): Path of the annotation file.\n\n        Returns:\n            list[dict]: List of annotations sorted by timestamps.\n        \"\"\"\n        if self.file_client_args['backend'] == 'disk':\n            # data_infos = mmcv.load(ann_file)\n            data = pickle.loads(self.file_client.get(ann_file))\n            data_infos = list(\n                sorted(data['infos'], key=lambda e: e['timestamp']))\n            data_infos = data_infos[::self.load_interval]\n            self.metadata = data['metadata']\n            self.version = self.metadata['version']\n        elif self.file_client_args['backend'] == 'petrel':\n            data = pickle.loads(self.file_client.get(ann_file))\n            data_infos = list(\n                sorted(data['infos'], key=lambda e: e['timestamp']))\n            data_infos = data_infos[::self.load_interval]\n            self.metadata = data['metadata']\n            self.version = self.metadata['version']\n        else:\n            assert False, 'Invalid file_client_args!'\n        return data_infos\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n                img: queue_length, 6, 3, H, W\n                img_metas: img_metas of each frame (list)\n                gt_globals_3d: gt_globals of each frame (list)\n                gt_bboxes_3d: gt_bboxes of each frame (list)\n                gt_inds: gt_inds of each frame (list)\n        \"\"\"\n        data_queue = []\n        self.enbale_temporal_aug = False\n        if self.enbale_temporal_aug:\n            # temporal aug\n            prev_indexs_list = list(range(index-self.queue_length, index))\n            random.shuffle(prev_indexs_list)\n            prev_indexs_list = sorted(prev_indexs_list[1:], reverse=True)\n            input_dict = self.get_data_info(index)\n        else:\n            # ensure the first and final frame in same scene\n            final_index = index\n            first_index = index - self.queue_length + 1\n            if first_index < 0:\n                return None\n            if self.data_infos[first_index]['scene_token'] != \\\n                    self.data_infos[final_index]['scene_token']:\n                return None\n            # current timestamp\n            input_dict = self.get_data_info(final_index)\n            prev_indexs_list = list(reversed(range(first_index, final_index)))\n        if input_dict is None:\n            return None\n        frame_idx = input_dict['frame_idx']\n        scene_token = input_dict['scene_token']\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n\n        assert example['gt_labels_3d'].data.shape[0] == example['gt_fut_traj'].shape[0]\n        assert example['gt_labels_3d'].data.shape[0] == example['gt_past_traj'].shape[0]\n\n        if self.filter_empty_gt and \\\n                (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n            return None\n        data_queue.insert(0, example)\n\n        # retrieve previous infos\n\n        for i in prev_indexs_list:\n            if self.enbale_temporal_aug:\n                i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            if input_dict['frame_idx'] < frame_idx and input_dict['scene_token'] == scene_token:\n                self.pre_pipeline(input_dict)\n                example = self.pipeline(input_dict)\n                if self.filter_empty_gt and \\\n                        (example is None or ~(example['gt_labels_3d']._data != -1).any()):\n                    return None\n                frame_idx = input_dict['frame_idx']\n            assert example['gt_labels_3d'].data.shape[0] == example['gt_fut_traj'].shape[0]\n            assert example['gt_labels_3d'].data.shape[0] == example['gt_past_traj'].shape[0]\n            data_queue.insert(0, copy.deepcopy(example))\n        data_queue = self.union2one(data_queue)\n        return data_queue\n\n    def prepare_test_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n                img: queue_length, 6, 3, H, W\n                img_metas: img_metas of each frame (list)\n                gt_labels_3d: gt_labels of each frame (list)\n                gt_bboxes_3d: gt_bboxes of each frame (list)\n                gt_inds: gt_inds of each frame(list)\n        \"\"\"\n\n        input_dict = self.get_data_info(index)\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        data_dict = {}\n        for key, value in example.items():\n            if 'l2g' in key:\n                data_dict[key] = to_tensor(value[0])\n            else:\n                data_dict[key] = value\n        return data_dict\n\n    def union2one(self, queue):\n        \"\"\"\n        convert sample dict into one single sample.\n        \"\"\"\n        imgs_list = [each['img'].data for each in queue]\n        gt_labels_3d_list = [each['gt_labels_3d'].data for each in queue]\n        gt_sdc_label_list = [each['gt_sdc_label'].data for each in queue]\n        gt_inds_list = [to_tensor(each['gt_inds']) for each in queue]\n        gt_bboxes_3d_list = [each['gt_bboxes_3d'].data for each in queue]\n        gt_past_traj_list = [to_tensor(each['gt_past_traj']) for each in queue]\n        gt_past_traj_mask_list = [\n            to_tensor(each['gt_past_traj_mask']) for each in queue]\n        gt_sdc_bbox_list = [each['gt_sdc_bbox'].data for each in queue]\n        l2g_r_mat_list = [to_tensor(each['l2g_r_mat']) for each in queue]\n        l2g_t_list = [to_tensor(each['l2g_t']) for each in queue]\n        timestamp_list = [to_tensor(each['timestamp']) for each in queue]\n        gt_fut_traj = to_tensor(queue[-1]['gt_fut_traj'])\n        gt_fut_traj_mask = to_tensor(queue[-1]['gt_fut_traj_mask'])\n        # gt_sdc_fut_traj = to_tensor(queue[-1]['gt_sdc_fut_traj'])\n        # gt_sdc_fut_traj_mask = to_tensor(queue[-1]['gt_sdc_fut_traj_mask'])\n        # gt_future_boxes_list = queue[-1]['gt_future_boxes']\n        # gt_future_labels_list = [to_tensor(each)\n        #                          for each in queue[-1]['gt_future_labels']]\n\n        metas_map = {}\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if i == 0:\n                metas_map[i]['prev_bev'] = False\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n\n        queue[-1]['img'] = DC(torch.stack(imgs_list),\n                              cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n\n        queue['gt_labels_3d'] = DC(gt_labels_3d_list)\n        queue['gt_sdc_label'] = DC(gt_sdc_label_list)\n        queue['gt_inds'] = DC(gt_inds_list)\n        queue['gt_bboxes_3d'] = DC(gt_bboxes_3d_list, cpu_only=True)\n        queue['gt_sdc_bbox'] = DC(gt_sdc_bbox_list, cpu_only=True)\n        queue['l2g_r_mat'] = DC(l2g_r_mat_list)\n        queue['l2g_t'] = DC(l2g_t_list)\n        queue['timestamp'] = DC(timestamp_list)\n        queue['gt_fut_traj'] = DC(gt_fut_traj)\n        queue['gt_fut_traj_mask'] = DC(gt_fut_traj_mask)\n        queue['gt_past_traj'] = DC(gt_past_traj_list)\n        queue['gt_past_traj_mask'] = DC(gt_past_traj_mask_list)\n        # queue['gt_future_boxes'] = DC(gt_future_boxes_list, cpu_only=True)\n        # queue['gt_future_labels'] = DC(gt_future_labels_list)\n        return queue\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n                - gt_inds (np.ndarray): Instance ids of ground truths.\n                - gt_fut_traj (np.ndarray): .\n                - gt_fut_traj_mask (np.ndarray): .\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n        if self.use_valid_flag:\n            mask = info['valid_flag']\n        else:\n            mask = info['num_lidar_pts'] > 0\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_inds = info['gt_inds'][mask]\n\n        sample = self.nusc.get('sample', info['token'])\n        ann_tokens = np.array(sample['anns'])[mask]\n        assert ann_tokens.shape[0] == gt_bboxes_3d.shape[0]\n\n        gt_fut_traj, gt_fut_traj_mask, gt_past_traj, gt_past_traj_mask = self.traj_api.get_traj_label(\n            info['token'], ann_tokens)\n\n        sdc_vel = self.traj_api.sdc_vel_info[info['token']]\n        gt_sdc_bbox, gt_sdc_label = self.traj_api.generate_sdc_info(sdc_vel)\n        gt_sdc_fut_traj, gt_sdc_fut_traj_mask = self.traj_api.get_sdc_traj_label(\n            info['token'])\n\n        sdc_planning, sdc_planning_mask, command = self.traj_api.get_sdc_planning_label(\n            info['token'])\n\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info['gt_velocity'][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        # the nuscenes box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n            gt_inds=gt_inds,\n            gt_fut_traj=gt_fut_traj,\n            gt_fut_traj_mask=gt_fut_traj_mask,\n            gt_past_traj=gt_past_traj,\n            gt_past_traj_mask=gt_past_traj_mask,\n            gt_sdc_bbox=gt_sdc_bbox,\n            gt_sdc_label=gt_sdc_label,\n            gt_sdc_fut_traj=gt_sdc_fut_traj,\n            gt_sdc_fut_traj_mask=gt_sdc_fut_traj_mask,\n            sdc_planning=sdc_planning,\n            sdc_planning_mask=sdc_planning_mask,\n            command=command,\n        )\n        assert gt_fut_traj.shape[0] == gt_labels_3d.shape[0]\n        assert gt_past_traj.shape[0] == gt_labels_3d.shape[0]\n        return anns_results\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n\n        # semantic format\n        lane_info = self.lane_infos[index] if self.lane_infos else None\n        # panoptic format\n        location = self.nusc.get('log', self.nusc.get(\n            'scene', info['scene_token'])['log_token'])['location']\n        vectors = self.vector_map.gen_vectorized_samples(location,\n                                                         info['ego2global_translation'],\n                                                         info['ego2global_rotation'])\n        semantic_masks, instance_masks, forward_masks, backward_masks = preprocess_map(vectors,\n                                                                                       self.patch_size,\n                                                                                       self.canvas_size,\n                                                                                       self.map_num_classes,\n                                                                                       self.thickness,\n                                                                                       self.angle_class)\n        instance_masks = np.rot90(instance_masks, k=-1, axes=(1, 2))\n        instance_masks = torch.tensor(instance_masks.copy())\n        gt_labels = []\n        gt_bboxes = []\n        gt_masks = []\n        for cls in range(self.map_num_classes):\n            for i in np.unique(instance_masks[cls]):\n                if i == 0:\n                    continue\n                gt_mask = (instance_masks[cls] == i).to(torch.uint8)\n                ys, xs = np.where(gt_mask)\n                gt_bbox = [min(xs), min(ys), max(xs), max(ys)]\n                gt_labels.append(cls)\n                gt_bboxes.append(gt_bbox)\n                gt_masks.append(gt_mask)\n        map_mask = obtain_map_info(self.nusc,\n                                   self.nusc_maps,\n                                   info,\n                                   patch_size=self.patch_size,\n                                   canvas_size=self.canvas_size,\n                                   layer_names=['lane_divider', 'road_divider'])\n        map_mask = np.flip(map_mask, axis=1)\n        map_mask = np.rot90(map_mask, k=-1, axes=(1, 2))\n        map_mask = torch.tensor(map_mask.copy())\n        for i, gt_mask in enumerate(map_mask[:-1]):\n            ys, xs = np.where(gt_mask)\n            gt_bbox = [min(xs), min(ys), max(xs), max(ys)]\n            gt_labels.append(i + self.map_num_classes)\n            gt_bboxes.append(gt_bbox)\n            gt_masks.append(gt_mask)\n        gt_labels = torch.tensor(gt_labels)\n        gt_bboxes = torch.tensor(np.stack(gt_bboxes))\n        gt_masks = torch.stack(gt_masks)\n\n        # standard protocal modified from SECOND.Pytorch\n        input_dict = dict(\n            sample_idx=info['token'],\n            pts_filename=info['lidar_path'],\n            sweeps=info['sweeps'],\n            ego2global_translation=info['ego2global_translation'],\n            ego2global_rotation=info['ego2global_rotation'],\n            prev_idx=info['prev'],\n            next_idx=info['next'],\n            scene_token=info['scene_token'],\n            can_bus=info['can_bus'],\n            frame_idx=info['frame_idx'],\n            timestamp=info['timestamp'] / 1e6,\n            map_filename=lane_info['maps']['map_mask'] if lane_info else None,\n            gt_lane_labels=gt_labels,\n            gt_lane_bboxes=gt_bboxes,\n            gt_lane_masks=gt_masks,\n        )\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        l2g_r_mat = l2e_r_mat.T @ e2g_r_mat.T\n        l2g_t = l2e_t @ e2g_r_mat.T + e2g_t\n\n        input_dict.update(\n            dict(\n                l2g_r_mat=l2g_r_mat.astype(np.float32),\n                l2g_t=l2g_t.astype(np.float32)))\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            for cam_type, cam_info in info['cams'].items():\n                image_paths.append(cam_info['data_path'])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info['sensor2lidar_rotation'])\n                lidar2cam_t = cam_info[\n                    'sensor2lidar_translation'] @ lidar2cam_r.T\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = cam_info['cam_intrinsic']\n                viewpad = np.eye(4)\n                viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                lidar2img_rts.append(lidar2img_rt)\n\n                cam_intrinsics.append(viewpad)\n                lidar2cam_rts.append(lidar2cam_rt.T)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                ))\n\n        # if not self.test_mode:\n        annos = self.get_ann_info(index)\n        input_dict['ann_info'] = annos\n        if 'sdc_planning' in input_dict['ann_info'].keys():\n            input_dict['sdc_planning'] = input_dict['ann_info']['sdc_planning']\n            input_dict['sdc_planning_mask'] = input_dict['ann_info']['sdc_planning_mask']\n            input_dict['command'] = input_dict['ann_info']['command']\n\n        rotation = Quaternion(input_dict['ego2global_rotation'])\n        translation = input_dict['ego2global_translation']\n        can_bus = input_dict['can_bus']\n        can_bus[:3] = translation\n        can_bus[3:7] = rotation\n        patch_angle = quaternion_yaw(rotation) / np.pi * 180\n        if patch_angle < 0:\n            patch_angle += 360\n        can_bus[-2] = patch_angle / 180 * np.pi\n        can_bus[-1] = patch_angle\n\n        # TODO: Warp all those below occupancy-related codes into a function\n        prev_indices, future_indices = self.occ_get_temporal_indices(\n            index, self.occ_receptive_field, self.occ_n_future)\n\n        # ego motions of all frames are needed\n        all_frames = prev_indices + [index] + future_indices\n\n        # whether invalid frames is present\n        # \n        has_invalid_frame = -1 in all_frames[:self.occ_only_total_frames]\n        # NOTE: This can only represent 7 frames in total as it influence evaluation\n        input_dict['occ_has_invalid_frame'] = has_invalid_frame\n        input_dict['occ_img_is_valid'] = np.array(all_frames) >= 0\n\n        # might have None if not in the same sequence\n        future_frames = [index] + future_indices\n\n        # get lidar to ego to global transforms for each curr and fut index\n        occ_transforms = self.occ_get_transforms(\n            future_frames)  # might have None\n        input_dict.update(occ_transforms)\n\n        # for (current and) future frames, detection labels are needed\n        # generate detection labels for current + future frames\n        input_dict['occ_future_ann_infos'] = \\\n            self.get_future_detection_infos(future_frames)\n        return input_dict\n\n    def get_future_detection_infos(self, future_frames):\n        detection_ann_infos = []\n        for future_frame in future_frames:\n            if future_frame >= 0:\n                detection_ann_infos.append(\n                    self.occ_get_detection_ann_info(future_frame),\n                )\n            else:\n                detection_ann_infos.append(None)\n        return detection_ann_infos\n\n    def occ_get_temporal_indices(self, index, receptive_field, n_future):\n        current_scene_token = self.data_infos[index]['scene_token']\n\n        # generate the past\n        previous_indices = []\n\n        for t in range(- receptive_field + 1, 0):\n            index_t = index + t\n            if index_t >= 0 and self.data_infos[index_t]['scene_token'] == current_scene_token:\n                previous_indices.append(index_t)\n            else:\n                previous_indices.append(-1)  # for invalid indices\n\n        # generate the future\n        future_indices = []\n\n        for t in range(1, n_future + 1):\n            index_t = index + t\n            if index_t < len(self.data_infos) and self.data_infos[index_t]['scene_token'] == current_scene_token:\n                future_indices.append(index_t)\n            else:\n                # NOTE: How to deal the invalid indices???\n                future_indices.append(-1)\n\n        return previous_indices, future_indices\n\n    def occ_get_transforms(self, indices, data_type=torch.float32):\n        \"\"\"\n        get l2e, e2g rotation and translation for each valid frame\n        \"\"\"\n        l2e_r_mats = []\n        l2e_t_vecs = []\n        e2g_r_mats = []\n        e2g_t_vecs = []\n\n        for index in indices:\n            if index == -1:\n                l2e_r_mats.append(None)\n                l2e_t_vecs.append(None)\n                e2g_r_mats.append(None)\n                e2g_t_vecs.append(None)\n            else:\n                info = self.data_infos[index]\n                l2e_r = info['lidar2ego_rotation']\n                l2e_t = info['lidar2ego_translation']\n                e2g_r = info['ego2global_rotation']\n                e2g_t = info['ego2global_translation']\n\n                l2e_r_mat = torch.from_numpy(Quaternion(l2e_r).rotation_matrix)\n                e2g_r_mat = torch.from_numpy(Quaternion(e2g_r).rotation_matrix)\n\n                l2e_r_mats.append(l2e_r_mat.to(data_type))\n                l2e_t_vecs.append(torch.tensor(l2e_t).to(data_type))\n                e2g_r_mats.append(e2g_r_mat.to(data_type))\n                e2g_t_vecs.append(torch.tensor(e2g_t).to(data_type))\n\n        res = {\n            'occ_l2e_r_mats': l2e_r_mats,\n            'occ_l2e_t_vecs': l2e_t_vecs,\n            'occ_e2g_r_mats': e2g_r_mats,\n            'occ_e2g_t_vecs': e2g_t_vecs,\n        }\n\n        return res\n\n    def occ_get_detection_ann_info(self, index):\n        info = self.data_infos[index].copy()\n        gt_bboxes_3d = info['gt_boxes'].copy()\n        gt_names_3d = info['gt_names'].copy()\n        gt_ins_inds = info['gt_inds'].copy()\n\n        gt_vis_tokens = info.get('visibility_tokens', None)\n\n        if self.use_valid_flag:\n            gt_valid_flag = info['valid_flag']\n        else:\n            gt_valid_flag = info['num_lidar_pts'] > 0\n\n        assert self.occ_filter_by_valid_flag is False\n        if self.occ_filter_by_valid_flag:\n            gt_bboxes_3d = gt_bboxes_3d[gt_valid_flag]\n            gt_names_3d = gt_names_3d[gt_valid_flag]\n            gt_ins_inds = gt_ins_inds[gt_valid_flag]\n            gt_vis_tokens = gt_vis_tokens[gt_valid_flag]\n\n        # cls_name to cls_id\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info['gt_velocity']\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        # the nuscenes box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            # gt_names=gt_names_3d,\n            gt_inds=gt_ins_inds,\n            gt_vis_tokens=gt_vis_tokens,\n        )\n\n        return anns_results\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def _format_bbox(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n        nusc_annos = {}\n        nusc_map_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            annos = []\n            sample_token = self.data_infos[sample_id]['token']\n\n            if 'map' in self.eval_mod:\n                map_annos = {}\n                for key, value in det['ret_iou'].items():\n                    map_annos[key] = float(value.numpy()[0])\n                    nusc_map_annos[sample_token] = map_annos\n\n            if 'boxes_3d' not in det:\n                nusc_annos[sample_token] = annos\n                continue\n\n            boxes = output_to_nusc_box(det)\n            boxes_ego = copy.deepcopy(boxes)\n            boxes, keep_idx = lidar_nusc_box_to_global(self.data_infos[sample_id], boxes,\n                                                       mapped_class_names,\n                                                       self.eval_detection_configs,\n                                                       self.eval_version)\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if np.sqrt(box.velocity[0]**2 + box.velocity[1]**2) > 0.2:\n                    if name in [\n                            'car',\n                            'construction_vehicle',\n                            'bus',\n                            'truck',\n                            'trailer',\n                    ]:\n                        attr = 'vehicle.moving'\n                    elif name in ['bicycle', 'motorcycle']:\n                        attr = 'cycle.with_rider'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n                else:\n                    if name in ['pedestrian']:\n                        attr = 'pedestrian.standing'\n                    elif name in ['bus']:\n                        attr = 'vehicle.stopped'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n\n                # center_ = box.center.tolist()\n                # change from ground height to center height\n                # center_[2] = center_[2] + (box.wlh.tolist()[2] / 2.0)\n                if name not in ['car', 'truck', 'bus', 'trailer', 'motorcycle',\n                                'bicycle', 'pedestrian', ]:\n                    continue\n\n                box_ego = boxes_ego[keep_idx[i]]\n                trans = box_ego.center\n                if 'traj' in det:\n                    traj_local = det['traj'][keep_idx[i]].numpy()[..., :2]\n                    traj_scores = det['traj_scores'][keep_idx[i]].numpy()\n                else:\n                    traj_local = np.zeros((0,))\n                    traj_scores = np.zeros((0,))\n                traj_ego = np.zeros_like(traj_local)\n                rot = Quaternion(axis=np.array([0, 0.0, 1.0]), angle=np.pi/2)\n                for kk in range(traj_ego.shape[0]):\n                    traj_ego[kk] = convert_local_coords_to_global(\n                        traj_local[kk], trans, rot)\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                    detection_name=name,\n                    detection_score=box.score,\n                    attribute_name=attr,\n                    tracking_name=name,\n                    tracking_score=box.score,\n                    tracking_id=box.token,\n                    predict_traj=traj_ego,\n                    predict_traj_score=traj_scores,\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n            'map_results': nusc_map_annos,\n        }\n\n        mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path\n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        result_files = self._format_bbox(results, jsonfile_prefix)\n\n        return result_files, tmp_dir\n\n    def _format_bbox_det(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(track_iter_progress(results)):\n            annos = []\n            sample_token = self.data_infos[sample_id]['token']\n\n            if det is None:\n                nusc_annos[sample_token] = annos\n                continue\n\n            boxes = output_to_nusc_box_det(det)\n            boxes_ego = copy.deepcopy(boxes)\n            boxes, keep_idx = lidar_nusc_box_to_global(self.data_infos[sample_id], boxes,\n                                                       mapped_class_names,\n                                                       self.eval_detection_configs,\n                                                       self.eval_version)\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if np.sqrt(box.velocity[0]**2 + box.velocity[1]**2) > 0.2:\n                    if name in [\n                            'car',\n                            'construction_vehicle',\n                            'bus',\n                            'truck',\n                            'trailer',\n                    ]:\n                        attr = 'vehicle.moving'\n                    elif name in ['bicycle', 'motorcycle']:\n                        attr = 'cycle.with_rider'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n                else:\n                    if name in ['pedestrian']:\n                        attr = 'pedestrian.standing'\n                    elif name in ['bus']:\n                        attr = 'vehicle.stopped'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                    detection_name=name,\n                    detection_score=box.score,\n                    attribute_name=attr,\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n        }\n\n        mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_nusc_det.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path\n\n    def format_results_det(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results_det')\n        else:\n            tmp_dir = None\n\n        result_files = self._format_bbox_det(results, jsonfile_prefix)\n        return result_files, tmp_dir\n\n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n        if isinstance(results, dict):\n            if 'occ_results_computed' in results.keys():\n                occ_results_computed = results['occ_results_computed']\n                out_metrics = ['iou']\n\n                # pan_eval\n                if occ_results_computed.get('pq', None) is not None:\n                    out_metrics = ['iou', 'pq', 'sq', 'rq']\n\n                print(\"Occ-flow Val Results:\")\n                for panoptic_key in out_metrics:\n                    print(panoptic_key)\n                    # HERE!! connect\n                    print(' & '.join(\n                        [f'{x:.1f}' for x in occ_results_computed[panoptic_key]]))\n\n                if 'num_occ' in occ_results_computed.keys() and 'ratio_occ' in occ_results_computed.keys():\n                    print(\n                        f\"num occ evaluated:{occ_results_computed['num_occ']}\")\n                    print(\n                        f\"ratio occ evaluated: {occ_results_computed['ratio_occ'] * 100:.1f}%\")\n            if 'planning_results_computed' in results.keys():\n                planning_results_computed = results['planning_results_computed']\n                planning_tab = PrettyTable()\n                planning_tab.field_names = [\n                    \"metrics\", \"0.5s\", \"1.0s\", \"1.5s\", \"2.0s\", \"2.5s\", \"3.0s\"]\n                for key in planning_results_computed.keys():\n                    value = planning_results_computed[key]\n                    row_value = []\n                    row_value.append(key)\n                    for i in range(len(value)):\n                        row_value.append('%.4f' % float(value[i]))\n                    planning_tab.add_row(row_value)\n                print(planning_tab)\n            results = results['bbox_results']  # get bbox_results\n\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n        result_files_det, tmp_dir = self.format_results_det(\n            results, jsonfile_prefix)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print('Evaluating bboxes of {}'.format(name))\n                ret_dict = self._evaluate_single(\n                    result_files[name], result_files_det[name])\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(\n                result_files, result_files_det)\n\n        if 'map' in self.eval_mod:\n            drivable_intersection = 0\n            drivable_union = 0\n            lanes_intersection = 0\n            lanes_union = 0\n            divider_intersection = 0\n            divider_union = 0\n            crossing_intersection = 0\n            crossing_union = 0\n            contour_intersection = 0\n            contour_union = 0\n            for i in range(len(results)):\n                drivable_intersection += results[i]['ret_iou']['drivable_intersection']\n                drivable_union += results[i]['ret_iou']['drivable_union']\n                lanes_intersection += results[i]['ret_iou']['lanes_intersection']\n                lanes_union += results[i]['ret_iou']['lanes_union']\n                divider_intersection += results[i]['ret_iou']['divider_intersection']\n                divider_union += results[i]['ret_iou']['divider_union']\n                crossing_intersection += results[i]['ret_iou']['crossing_intersection']\n                crossing_union += results[i]['ret_iou']['crossing_union']\n                contour_intersection += results[i]['ret_iou']['contour_intersection']\n                contour_union += results[i]['ret_iou']['contour_union']\n            results_dict.update({'drivable_iou': float(drivable_intersection / drivable_union),\n                                 'lanes_iou': float(lanes_intersection / lanes_union),\n                                 'divider_iou': float(divider_intersection / divider_union),\n                                 'crossing_iou': float(crossing_intersection / crossing_union),\n                                 'contour_iou': float(contour_intersection / contour_union)})\n\n            print(results_dict)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\n    def _evaluate_single(self,\n                         result_path,\n                         result_path_det,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n\n        # TODO: fix the evaluation pipelines\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        output_dir_det = osp.join(output_dir, 'det')\n        output_dir_track = osp.join(output_dir, 'track')\n        output_dir_motion = osp.join(output_dir, 'motion')\n        mkdir_or_exist(output_dir_det)\n        mkdir_or_exist(output_dir_track)\n        mkdir_or_exist(output_dir_motion)\n\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        detail = dict()\n\n        if 'det' in self.eval_mod:\n            self.nusc_eval = NuScenesEval_custom(\n                self.nusc,\n                config=self.eval_detection_configs,\n                result_path=result_path_det,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir_det,\n                verbose=True,\n                overlap_test=self.overlap_test,\n                data_infos=self.data_infos\n            )\n            self.nusc_eval.main(plot_examples=0, render_curves=False)\n            # record metrics\n            metrics = load(\n                osp.join(\n                    output_dir_det,\n                    'metrics_summary.json'))\n            metric_prefix = f'{result_name}_NuScenes'\n            for name in self.CLASSES:\n                for k, v in metrics['label_aps'][name].items():\n                    val = float('{:.4f}'.format(v))\n                    detail['{}/{}_AP_dist_{}'.format(\n                        metric_prefix, name, k)] = val\n                for k, v in metrics['label_tp_errors'][name].items():\n                    val = float('{:.4f}'.format(v))\n                    detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n                for k, v in metrics['tp_errors'].items():\n                    val = float('{:.4f}'.format(v))\n                    detail['{}/{}'.format(metric_prefix,\n                                          self.ErrNameMapping[k])] = val\n            detail['{}/NDS'.format(metric_prefix)] = metrics['nd_score']\n            detail['{}/mAP'.format(metric_prefix)] = metrics['mean_ap']\n\n        if 'track' in self.eval_mod:\n            cfg = config_factory(\"tracking_nips_2019\")\n            self.nusc_eval_track = TrackingEval(\n                config=cfg,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir_track,\n                verbose=True,\n                nusc_version=self.version,\n                nusc_dataroot=self.data_root\n            )\n            self.nusc_eval_track.main()\n            # record metrics\n            metrics = load(\n                osp.join(\n                    output_dir_track,\n                    'metrics_summary.json'))\n            keys = ['amota', 'amotp', 'recall', 'motar',\n                    'gt', 'mota', 'motp', 'mt', 'ml', 'faf',\n                    'tp', 'fp', 'fn', 'ids', 'frag', 'tid', 'lgd']\n            for key in keys:\n                detail['{}/{}'.format(metric_prefix, key)] = metrics[key]\n\n        # if 'map' in self.eval_mod:\n        #     for i, ret_iou in enumerate(ret_ious):\n        #         detail['iou_{}'.format(i)] = ret_iou\n\n        if 'motion' in self.eval_mod:\n            self.nusc_eval_motion = MotionEval(\n                self.nusc,\n                config=self.eval_detection_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n                overlap_test=self.overlap_test,\n                data_infos=self.data_infos,\n                category_convert_type='motion_category'\n            )\n            print('-'*50)\n            print(\n                'Evaluate on motion category, merge class for vehicles and pedestrians...')\n            print('evaluate standard motion metrics...')\n            self.nusc_eval_motion.main(\n                plot_examples=0,\n                render_curves=False,\n                eval_mode='standard')\n            print('evaluate motion mAP-minFDE metrics...')\n            self.nusc_eval_motion.main(\n                plot_examples=0,\n                render_curves=False,\n                eval_mode='motion_map')\n            print('evaluate EPA motion metrics...')\n            self.nusc_eval_motion.main(\n                plot_examples=0,\n                render_curves=False,\n                eval_mode='epa')\n            print('-'*50)\n            print('Evaluate on detection category...')\n            self.nusc_eval_motion = MotionEval(\n                self.nusc,\n                config=self.eval_detection_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n                overlap_test=self.overlap_test,\n                data_infos=self.data_infos,\n                category_convert_type='detection_category'\n            )\n            print('evaluate standard motion metrics...')\n            self.nusc_eval_motion.main(\n                plot_examples=0,\n                render_curves=False,\n                eval_mode='standard')\n            print('evaluate EPA motion metrics...')\n            self.nusc_eval_motion.main(\n                plot_examples=0,\n                render_curves=False,\n                eval_mode='motion_map')\n            print('evaluate EPA motion metrics...')\n            self.nusc_eval_motion.main(\n                plot_examples=0,\n                render_curves=False,\n                eval_mode='epa')\n\n        return detail\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscenes_eval.py",
    "content": "import argparse\nimport copy\nimport json\nimport os\nimport time\nimport cv2\nimport argparse\nimport random\nimport tqdm\nimport torch\nfrom typing import Tuple, Dict, Any\nfrom mmcv.fileio.io import dump,load\nfrom torchvision.transforms.functional import rotate\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.detection.data_classes import DetectionConfig\nfrom nuscenes.eval.detection.evaluate import NuScenesEval\nfrom nuscenes.eval.detection.data_classes import DetectionBox\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.tracking.data_classes import TrackingBox\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nimport pycocotools.mask as mask_util\n# from projects.mmdet3d_plugin.models.utils.visual import save_tensor\nfrom nuscenes.eval.common.loaders import load_gt, add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import accumulate, calc_ap, calc_tp\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, dist_pr_curve, visualize_sample\nfrom matplotlib import pyplot as plt\nfrom nuscenes.eval.common.render import setup_axis\nfrom nuscenes.eval.detection.constants import TP_METRICS, DETECTION_NAMES, DETECTION_COLORS, TP_METRICS_UNITS, \\\n    PRETTY_DETECTION_NAMES, PRETTY_TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionMetrics, DetectionMetricData, DetectionMetricDataList\nimport mmcv\n\n\nAxis = Any\n\ndef class_tp_curve(md_list: DetectionMetricDataList,\n                   metrics: DetectionMetrics,\n                   detection_name: str,\n                   min_recall: float,\n                   dist_th_tp: float,\n                   savepath: str = None,\n                   ax: Axis = None) -> None:\n    \"\"\"\n    Plot the true positive curve for the specified class.\n    :param md_list: DetectionMetricDataList instance.\n    :param metrics: DetectionMetrics instance.\n    :param detection_name:\n    :param min_recall: Minimum recall value.\n    :param dist_th_tp: The distance threshold used to determine matches.\n    :param savepath: If given, saves the the rendering here instead of displaying.\n    :param ax: Axes onto which to render.\n    \"\"\"\n    # Get metric data for given detection class with tp distance threshold.\n\n    md = md_list[(detection_name, dist_th_tp)]\n    min_recall_ind = round(100 * min_recall)\n    if min_recall_ind <= md.max_recall_ind:\n        # For traffic_cone and barrier only a subset of the metrics are plotted.\n        rel_metrics = [m for m in TP_METRICS if not np.isnan(metrics.get_label_tp(detection_name, m))]\n        ylimit = max([max(getattr(md, metric)[min_recall_ind:md.max_recall_ind + 1]) for metric in rel_metrics]) * 1.1\n    else:\n        ylimit = 1.0\n\n    # Prepare axis.\n    if ax is None:\n        ax = setup_axis(title=PRETTY_DETECTION_NAMES[detection_name], xlabel='Recall', ylabel='Error', xlim=1,\n                        min_recall=min_recall)\n    ax.set_ylim(0, ylimit)\n\n    # Plot the recall vs. error curve for each tp metric.\n    for metric in TP_METRICS:\n        tp = metrics.get_label_tp(detection_name, metric)\n\n        # Plot only if we have valid data.\n        if tp is not np.nan and min_recall_ind <= md.max_recall_ind:\n            recall, error = md.recall[:md.max_recall_ind + 1], getattr(md, metric)[:md.max_recall_ind + 1]\n        else:\n            recall, error = [], []\n\n        # Change legend based on tp value\n        if tp is np.nan:\n            label = '{}: n/a'.format(PRETTY_TP_METRICS[metric])\n        elif min_recall_ind > md.max_recall_ind:\n            label = '{}: nan'.format(PRETTY_TP_METRICS[metric])\n        else:\n            label = '{}: {:.2f} ({})'.format(PRETTY_TP_METRICS[metric], tp, TP_METRICS_UNITS[metric])\n        if metric == 'trans_err':\n            label += f' ({md.max_recall_ind})'  # add recall\n            print(f'Recall: {detection_name}: {md.max_recall_ind/100}')\n        ax.plot(recall, error, label=label)\n    ax.axvline(x=md.max_recall, linestyle='-.', color=(0, 0, 0, 0.3))\n    ax.legend(loc='best')\n\n    if savepath is not None:\n        plt.savefig(savepath)\n        plt.close()\n\n\nclass DetectionBox_modified(DetectionBox):\n    def __init__(self, *args, token=None, visibility=None, index=None, **kwargs):\n        '''\n        add annotation token\n        '''\n        super().__init__(*args, **kwargs)\n        self.token = token\n        self.visibility = visibility\n        self.index = index\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'token': self.token,\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'visibility': self.visibility,\n            'index': self.index\n\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(\n            token=content['token'],\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name'],\n            visibility=content['visibility'],\n            index=content['index'],\n        )\n\n\ndef center_in_image(box, intrinsic: np.ndarray, imsize: Tuple[int, int], vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible inside an image without accounting for occlusions.\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    center_3d = box.center.reshape(3, 1)\n    center_img = view_points(center_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(center_img[0, :] > 0, center_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, center_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, center_img[1, :] > 0)\n    visible = np.logical_and(visible, center_3d[2, :] > 1)\n\n    in_front = center_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if vis_level == BoxVisibility.ALL:\n        return all(visible) and all(in_front)\n    elif vis_level == BoxVisibility.ANY:\n        return any(visible) and all(in_front)\n    elif vis_level == BoxVisibility.NONE:\n        return True\n    else:\n        raise ValueError(\"vis_level: {} not valid\".format(vis_level))\n\n\ndef exist_corners_in_image_but_not_all(box, intrinsic: np.ndarray, imsize: Tuple[int, int],\n                                       vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible in images but not all corners in image .\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    corners_3d = box.corners()\n    corners_img = view_points(corners_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(corners_img[0, :] > 0, corners_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, corners_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, corners_img[1, :] > 0)\n    visible = np.logical_and(visible, corners_3d[2, :] > 1)\n\n    in_front = corners_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if any(visible) and not all(visible) and all(in_front):\n        return True\n    else:\n        return False\n\ndef load_prediction(result_path: str, max_boxes_per_sample: int, box_cls, verbose: bool = False) \\\n        -> Tuple[EvalBoxes, Dict]:\n    \"\"\"\n    Loads object predictions from file.\n    :param result_path: Path to the .json result file provided by the user.\n    :param max_boxes_per_sample: Maximim number of boxes allowed per sample.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The deserialized results and meta data.\n    \"\"\"\n\n    # Load from file and check that the format is correct.\n    # with open(result_path) as f:\n    #     data = json.load(f)\n    data = load(result_path)\n    assert 'results' in data, 'Error: No field `results` in result file. Please note that the result format changed.' \\\n                              'See https://www.nuscenes.org/object-detection for more information.'\n\n    # Deserialize results and get meta data.\n    all_results = EvalBoxes.deserialize(data['results'], box_cls)\n    meta = data['meta']\n    if verbose:\n        print(\"Loaded results from {}. Found detections for {} samples.\"\n              .format(result_path, len(all_results.sample_tokens)))\n\n    # Check that each sample has no more than x predicted boxes.\n    for sample_token in all_results.sample_tokens:\n        assert len(all_results.boxes[sample_token]) <= max_boxes_per_sample, \\\n            \"Error: Only <= %d boxes per sample allowed!\" % max_boxes_per_sample\n\n    return all_results, meta\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False):\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n\n    # Init.\n    if box_cls == DetectionBox_modified:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n    index_map = {}\n    for scene in nusc.scene:\n        first_sample_token = scene['first_sample_token']\n        sample = nusc.get('sample', first_sample_token)\n        index_map[first_sample_token] = 1\n        index = 2\n        while sample['next'] != '':\n            sample = nusc.get('sample', sample['next'])\n            index_map[sample['token']] = index\n            index += 1\n\n    sample_tokens = []\n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n\n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == DetectionBox_modified:\n                # Get label name in detection task and filter unused labels.\n                detection_name = category_to_detection_name(sample_annotation['category_name'])\n                if detection_name is None:\n                    continue\n\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n\n                sample_boxes.append(\n                    box_cls(\n                        token=sample_annotation_token,\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        visibility=sample_annotation['visibility_token'],\n                        index=index_map[sample_token]\n                    )\n                )\n            elif box_cls == TrackingBox:\n                assert False\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\n\ndef filter_eval_boxes_by_id(nusc: NuScenes,\n                            eval_boxes: EvalBoxes,\n                            id=None,\n                            verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.token in id:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_visibility(\n        ori_eval_boxes: EvalBoxes,\n        visibility=None,\n        verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.visibility == visibility:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After visibility based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_by_sample_token(ori_eval_boxes, valid_sample_tokens=[],  verbose=False):\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    for sample_token in eval_boxes.sample_tokens:\n        if sample_token not in valid_sample_tokens:\n            eval_boxes.boxes.pop(sample_token)\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_overlap(nusc: NuScenes,\n                                 eval_boxes: EvalBoxes,\n                                 verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. basedon overlap .\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    cams = ['CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_BACK_RIGHT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_FRONT_LEFT']\n\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        sample_record = nusc.get('sample', sample_token)\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            count = 0\n            for cam in cams:\n                '''\n                copy-paste form nuscens\n                '''\n                sample_data_token = sample_record['data'][cam]\n                sd_record = nusc.get('sample_data', sample_data_token)\n                cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n                sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n                pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n                cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n                imsize = (sd_record['width'], sd_record['height'])\n                new_box = Box(box.translation, box.size, Quaternion(box.rotation),\n                              name=box.detection_name, token='')\n\n                # Move box to ego vehicle coord system.\n                new_box.translate(-np.array(pose_record['translation']))\n                new_box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n                #  Move box to sensor coord system.\n                new_box.translate(-np.array(cs_record['translation']))\n                new_box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n                if center_in_image(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                    count += 1\n                # if exist_corners_in_image_but_not_all(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                #    count += 1\n\n            if count > 1:\n                with open('center_overlap.txt', 'a') as f:\n                    try:\n                        f.write(box.token + '\\n')\n                    except:\n                        pass\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    verbose = True\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\nclass NuScenesEval_custom(NuScenesEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as DetectionEval.\n    \"\"\"\n\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 overlap_test=False,\n                 eval_mask=False,\n                 data_infos=None\n                 ):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n        self.overlap_test = overlap_test\n        self.eval_mask = eval_mask\n        self.data_infos = data_infos\n        # Check result file exists.\n        assert os.path.exists(result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, DetectionBox,\n                                                     verbose=verbose)\n        self.gt_boxes = load_gt(self.nusc, self.eval_set, DetectionBox_modified, verbose=verbose)\n\n        assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n            \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        # Filter boxes (distance, points per box, etc.).\n\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(nusc, self.pred_boxes, self.cfg.class_range, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(nusc, self.gt_boxes, self.cfg.class_range, verbose=verbose)\n\n        if self.overlap_test:\n            self.pred_boxes = filter_eval_boxes_by_overlap(self.nusc, self.pred_boxes)\n\n            self.gt_boxes = filter_eval_boxes_by_overlap(self.nusc, self.gt_boxes, verbose=True)\n\n        self.all_gt = copy.deepcopy(self.gt_boxes)\n        self.all_preds = copy.deepcopy(self.pred_boxes)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n        self.index_map = {}\n        for scene in nusc.scene:\n            first_sample_token = scene['first_sample_token']\n            sample = nusc.get('sample', first_sample_token)\n            self.index_map[first_sample_token] = 1\n            index = 2\n            while sample['next'] != '':\n                sample = nusc.get('sample', sample['next'])\n                self.index_map[sample['token']] = index\n                index += 1\n\n    def update_gt(self, type_='vis', visibility='1', index=1):\n        if type_ == 'vis':\n            self.visibility_test = True\n            if self.visibility_test:\n                '''[{'description': 'visibility of whole object is between 0 and 40%',\n                'token': '1',\n                'level': 'v0-40'},\n                {'description': 'visibility of whole object is between 40 and 60%',\n                'token': '2',\n                'level': 'v40-60'},\n                {'description': 'visibility of whole object is between 60 and 80%',\n                'token': '3',\n                'level': 'v60-80'},\n                {'description': 'visibility of whole object is between 80 and 100%',\n                'token': '4',\n                'level': 'v80-100'}]'''\n\n                self.gt_boxes = filter_eval_boxes_by_visibility(self.all_gt, visibility, verbose=True)\n\n        elif type_ == 'ord':\n\n            valid_tokens = [key for (key, value) in self.index_map.items() if value == index]\n            # from IPython import embed\n            # embed()\n            self.gt_boxes = filter_by_sample_token(self.all_gt, valid_tokens)\n            self.pred_boxes = filter_by_sample_token(self.all_preds, valid_tokens)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n\n    def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMetricDataList()\n\n        # print(self.cfg.dist_fcn_callable, self.cfg.dist_ths)\n        # self.cfg.dist_ths = [0.3]\n        # self.cfg.dist_fcn_callable\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md = accumulate(self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMetrics(self.cfg)\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.cfg.min_recall, self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in ['attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(md_list, metrics, min_precision=self.cfg.min_precision, min_recall=self.cfg.min_recall,\n                     dist_th_tp=self.cfg.dist_th_tp, savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(md_list, metrics, detection_name, self.cfg.min_precision, self.cfg.min_recall,\n                           savepath=savepath(detection_name + '_pr'))\n\n            class_tp_curve(md_list, metrics, detection_name, self.cfg.min_recall, self.cfg.dist_th_tp,\n                           savepath=savepath(detection_name + '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(md_list, metrics, dist_th, self.cfg.min_precision, self.cfg.min_recall,\n                          savepath=savepath('dist_pr_' + str(dist_th)))\n\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(description='Evaluate nuScenes detection results.',\n                                     formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument('result_path', type=str, help='The submission as a JSON file.')\n    parser.add_argument('--output_dir', type=str, default='~/nuscenes-metrics',\n                        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument('--eval_set', type=str, default='val',\n                        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='data/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument('--version', type=str, default='v1.0-trainval',\n                        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument('--config_path', type=str, default='',\n                        help='Path to the configuration file.'\n                             'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument('--plot_examples', type=int, default=0,\n                        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = NuScenesEval_custom(nusc_, config=cfg_, result_path=result_path_, eval_set=eval_set_,\n                                    output_dir=output_dir_, verbose=verbose_)\n    for vis in ['1', '2', '3', '4']:\n        nusc_eval.update_gt(type_='vis', visibility=vis)\n        print(f'================ {vis} ===============')\n        nusc_eval.main(plot_examples=plot_examples_, render_curves=render_curves_)\n    #for index in range(1, 41):\n    #    nusc_eval.update_gt(type_='ord', index=index)\n    #\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscenes_mono_dataset.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport mmcv\nimport numpy as np\nimport pyquaternion\nimport tempfile\nimport torch\nimport warnings\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom os import path as osp\n\nfrom mmdet3d.core import bbox3d2result, box3d_multiclass_nms, xywhr2xyxyr\nfrom mmdet.datasets import DATASETS, CocoDataset\nfrom mmdet3d.core import show_multi_modality_result\nfrom mmdet3d.core.bbox import CameraInstance3DBoxes, get_box_type\nfrom mmdet3d.datasets.pipelines import Compose\nfrom mmdet3d.datasets.utils import extract_result_dict, get_loading_pipeline\n\n\n@DATASETS.register_module()\nclass CustomNuScenesMonoDataset(CocoDataset):\n    r\"\"\"Monocular 3D detection on NuScenes Dataset.\n    This class serves as the API for experiments on the NuScenes Dataset.\n    Please refer to `NuScenes Dataset <https://www.nuscenes.org/download>`_\n    for data downloading.\n    Args:\n        ann_file (str): Path of annotation file.\n        data_root (str): Path of dataset root.\n        load_interval (int, optional): Interval of loading the dataset. It is\n            used to uniformly sample the dataset. Defaults to 1.\n        with_velocity (bool, optional): Whether include velocity prediction\n            into the experiments. Defaults to True.\n        modality (dict, optional): Modality to specify the sensor data used\n            as input. Defaults to None.\n        box_type_3d (str, optional): Type of 3D box of this dataset.\n            Based on the `box_type_3d`, the dataset will encapsulate the box\n            to its original format then converted them to `box_type_3d`.\n            Defaults to 'Camera' in this class. Available options includes.\n            - 'LiDAR': Box in LiDAR coordinates.\n            - 'Depth': Box in depth coordinates, usually for indoor dataset.\n            - 'Camera': Box in camera coordinates.\n        eval_version (str, optional): Configuration version of evaluation.\n            Defaults to  'detection_cvpr_2019'.\n        use_valid_flag (bool): Whether to use `use_valid_flag` key in the info\n            file as mask to filter gt_boxes and gt_names. Defaults to False.\n        version (str, optional): Dataset version. Defaults to 'v1.0-trainval'.\n    \"\"\"\n    CLASSES = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',\n               'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',\n               'barrier')\n    DefaultAttribute = {\n        'car': 'vehicle.parked',\n        'pedestrian': 'pedestrian.moving',\n        'trailer': 'vehicle.parked',\n        'truck': 'vehicle.parked',\n        'bus': 'vehicle.moving',\n        'motorcycle': 'cycle.without_rider',\n        'construction_vehicle': 'vehicle.parked',\n        'bicycle': 'cycle.without_rider',\n        'barrier': '',\n        'traffic_cone': '',\n    }\n    # https://github.com/nutonomy/nuscenes-devkit/blob/57889ff20678577025326cfc24e57424a829be0a/python-sdk/nuscenes/eval/detection/evaluate.py#L222 # noqa\n    ErrNameMapping = {\n        'trans_err': 'mATE',\n        'scale_err': 'mASE',\n        'orient_err': 'mAOE',\n        'vel_err': 'mAVE',\n        'attr_err': 'mAAE'\n    }\n\n    def __init__(self,\n                 data_root,\n                 load_interval=1,\n                 with_velocity=True,\n                 modality=None,\n                 box_type_3d='Camera',\n                 eval_version='detection_cvpr_2019',\n                 use_valid_flag=False,\n                 overlap_test=False,\n                 version='v1.0-trainval',\n                 **kwargs):\n        super().__init__(**kwargs)\n        # overlap_test = True\n        self.data_root = data_root\n        self.overlap_test = overlap_test\n        self.load_interval = load_interval\n        self.with_velocity = with_velocity\n        self.modality = modality\n        self.box_type_3d, self.box_mode_3d = get_box_type(box_type_3d)\n        self.eval_version = eval_version\n        self.use_valid_flag = use_valid_flag\n        self.bbox_code_size = 9\n        self.version = version\n        if self.eval_version is not None:\n            from nuscenes.eval.detection.config import config_factory\n            self.eval_detection_configs = config_factory(self.eval_version)\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=True,\n                use_lidar=False,\n                use_radar=False,\n                use_map=False,\n                use_external=False)\n\n    def pre_pipeline(self, results):\n        \"\"\"Initialization before data preparation.\n        Args:\n            results (dict): Dict before data preprocessing.\n                - img_fields (list): Image fields.\n                - bbox3d_fields (list): 3D bounding boxes fields.\n                - pts_mask_fields (list): Mask fields of points.\n                - pts_seg_fields (list): Mask fields of point segments.\n                - bbox_fields (list): Fields of bounding boxes.\n                - mask_fields (list): Fields of masks.\n                - seg_fields (list): Segment fields.\n                - box_type_3d (str): 3D box type.\n                - box_mode_3d (str): 3D box mode.\n        \"\"\"\n        results['img_prefix'] = ''  # self.img_prefix\n        # print('img_prefix', self.img_prefix)\n        results['seg_prefix'] = self.seg_prefix\n        results['proposal_file'] = self.proposal_file\n        results['img_fields'] = []\n        results['bbox3d_fields'] = []\n        results['pts_mask_fields'] = []\n        results['pts_seg_fields'] = []\n        results['bbox_fields'] = []\n        results['mask_fields'] = []\n        results['seg_fields'] = []\n        results['box_type_3d'] = self.box_type_3d\n        results['box_mode_3d'] = self.box_mode_3d\n\n    def _parse_ann_info(self, img_info, ann_info):\n        \"\"\"Parse bbox annotation.\n        Args:\n            img_info (list[dict]): Image info.\n            ann_info (list[dict]): Annotation info of an image.\n        Returns:\n            dict: A dict containing the following keys: bboxes, labels, \\\n                gt_bboxes_3d, gt_labels_3d, attr_labels, centers2d, \\\n                depths, bboxes_ignore, masks, seg_map\n        \"\"\"\n        gt_bboxes = []\n        gt_labels = []\n        attr_labels = []\n        gt_bboxes_ignore = []\n        gt_masks_ann = []\n        gt_bboxes_cam3d = []\n        centers2d = []\n        depths = []\n        for i, ann in enumerate(ann_info):\n            if ann.get('ignore', False):\n                continue\n            x1, y1, w, h = ann['bbox']\n            inter_w = max(0, min(x1 + w, img_info['width']) - max(x1, 0))\n            inter_h = max(0, min(y1 + h, img_info['height']) - max(y1, 0))\n            if inter_w * inter_h == 0:\n                continue\n            if ann['area'] <= 0 or w < 1 or h < 1:\n                continue\n            if ann['category_id'] not in self.cat_ids:\n                continue\n            bbox = [x1, y1, x1 + w, y1 + h]\n            if ann.get('iscrowd', False):\n                gt_bboxes_ignore.append(bbox)\n            else:\n                gt_bboxes.append(bbox)\n                gt_labels.append(self.cat2label[ann['category_id']])\n                attr_labels.append(ann['attribute_id'])\n                gt_masks_ann.append(ann.get('segmentation', None))\n                # 3D annotations in camera coordinates\n                bbox_cam3d = np.array(ann['bbox_cam3d']).reshape(1, -1)\n                velo_cam3d = np.array(ann['velo_cam3d']).reshape(1, 2)\n                nan_mask = np.isnan(velo_cam3d[:, 0])\n                velo_cam3d[nan_mask] = [0.0, 0.0]\n                bbox_cam3d = np.concatenate([bbox_cam3d, velo_cam3d], axis=-1)\n                gt_bboxes_cam3d.append(bbox_cam3d.squeeze())\n                # 2.5D annotations in camera coordinates\n                center2d = ann['center2d'][:2]\n                depth = ann['center2d'][2]\n                centers2d.append(center2d)\n                depths.append(depth)\n\n        if gt_bboxes:\n            gt_bboxes = np.array(gt_bboxes, dtype=np.float32)\n            gt_labels = np.array(gt_labels, dtype=np.int64)\n            attr_labels = np.array(attr_labels, dtype=np.int64)\n        else:\n            gt_bboxes = np.zeros((0, 4), dtype=np.float32)\n            gt_labels = np.array([], dtype=np.int64)\n            attr_labels = np.array([], dtype=np.int64)\n\n        if gt_bboxes_cam3d:\n            gt_bboxes_cam3d = np.array(gt_bboxes_cam3d, dtype=np.float32)\n            centers2d = np.array(centers2d, dtype=np.float32)\n            depths = np.array(depths, dtype=np.float32)\n        else:\n            gt_bboxes_cam3d = np.zeros((0, self.bbox_code_size),\n                                       dtype=np.float32)\n            centers2d = np.zeros((0, 2), dtype=np.float32)\n            depths = np.zeros((0), dtype=np.float32)\n\n        gt_bboxes_cam3d = CameraInstance3DBoxes(\n            gt_bboxes_cam3d,\n            box_dim=gt_bboxes_cam3d.shape[-1],\n            origin=(0.5, 0.5, 0.5))\n        gt_labels_3d = copy.deepcopy(gt_labels)\n\n        if gt_bboxes_ignore:\n            gt_bboxes_ignore = np.array(gt_bboxes_ignore, dtype=np.float32)\n        else:\n            gt_bboxes_ignore = np.zeros((0, 4), dtype=np.float32)\n\n        seg_map = img_info['filename'].replace('jpg', 'png')\n\n        ann = dict(\n            bboxes=gt_bboxes,\n            labels=gt_labels,\n            gt_bboxes_3d=gt_bboxes_cam3d,\n            gt_labels_3d=gt_labels_3d,\n            attr_labels=attr_labels,\n            centers2d=centers2d,\n            depths=depths,\n            bboxes_ignore=gt_bboxes_ignore,\n            masks=gt_masks_ann,\n            seg_map=seg_map)\n\n        return ann\n\n    def get_attr_name(self, attr_idx, label_name):\n        \"\"\"Get attribute from predicted index.\n        This is a workaround to predict attribute when the predicted velocity\n        is not reliable. We map the predicted attribute index to the one\n        in the attribute set. If it is consistent with the category, we will\n        keep it. Otherwise, we will use the default attribute.\n        Args:\n            attr_idx (int): Attribute index.\n            label_name (str): Predicted category name.\n        Returns:\n            str: Predicted attribute name.\n        \"\"\"\n        # TODO: Simplify the variable name\n        AttrMapping_rev2 = [\n            'cycle.with_rider', 'cycle.without_rider', 'pedestrian.moving',\n            'pedestrian.standing', 'pedestrian.sitting_lying_down',\n            'vehicle.moving', 'vehicle.parked', 'vehicle.stopped', 'None'\n        ]\n        if label_name == 'car' or label_name == 'bus' \\\n            or label_name == 'truck' or label_name == 'trailer' \\\n                or label_name == 'construction_vehicle':\n            if AttrMapping_rev2[attr_idx] == 'vehicle.moving' or \\\n                AttrMapping_rev2[attr_idx] == 'vehicle.parked' or \\\n                    AttrMapping_rev2[attr_idx] == 'vehicle.stopped':\n                return AttrMapping_rev2[attr_idx]\n            else:\n                return CustomNuScenesMonoDataset.DefaultAttribute[label_name]\n        elif label_name == 'pedestrian':\n            if AttrMapping_rev2[attr_idx] == 'pedestrian.moving' or \\\n                AttrMapping_rev2[attr_idx] == 'pedestrian.standing' or \\\n                    AttrMapping_rev2[attr_idx] == \\\n                    'pedestrian.sitting_lying_down':\n                return AttrMapping_rev2[attr_idx]\n            else:\n                return CustomNuScenesMonoDataset.DefaultAttribute[label_name]\n        elif label_name == 'bicycle' or label_name == 'motorcycle':\n            if AttrMapping_rev2[attr_idx] == 'cycle.with_rider' or \\\n                    AttrMapping_rev2[attr_idx] == 'cycle.without_rider':\n                return AttrMapping_rev2[attr_idx]\n            else:\n                return CustomNuScenesMonoDataset.DefaultAttribute[label_name]\n        else:\n            return CustomNuScenesMonoDataset.DefaultAttribute[label_name]\n\n    def _format_bbox(self, results, jsonfile_prefix=None):\n        \"\"\"Convert the results to the standard format.\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print('Start to convert detection format...')\n\n        CAM_NUM = 6\n\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n\n            if sample_id % CAM_NUM == 0:\n                boxes_per_frame = []\n                attrs_per_frame = []\n\n            # need to merge results from images of the same sample\n            annos = []\n            boxes, attrs = output_to_nusc_box(det)\n            sample_token = self.data_infos[sample_id]['token']\n            boxes, attrs = cam_nusc_box_to_global(self.data_infos[sample_id],\n                                                  boxes, attrs,\n                                                  mapped_class_names,\n                                                  self.eval_detection_configs,\n                                                  self.eval_version)\n\n            boxes_per_frame.extend(boxes)\n            attrs_per_frame.extend(attrs)\n            # Remove redundant predictions caused by overlap of images\n            if (sample_id + 1) % CAM_NUM != 0:\n                continue\n            boxes = global_nusc_box_to_cam(\n                self.data_infos[sample_id + 1 - CAM_NUM], boxes_per_frame,\n                mapped_class_names, self.eval_detection_configs,\n                self.eval_version)\n            cam_boxes3d, scores, labels = nusc_box_to_cam_box3d(boxes)\n            # box nms 3d over 6 images in a frame\n            # TODO: move this global setting into config\n            nms_cfg = dict(\n                use_rotate_nms=True,\n                nms_across_levels=False,\n                nms_pre=4096,\n                nms_thr=0.05,\n                score_thr=0.01,\n                min_bbox_size=0,\n                max_per_frame=500)\n            from mmcv import Config\n            nms_cfg = Config(nms_cfg)\n            cam_boxes3d_for_nms = xywhr2xyxyr(cam_boxes3d.bev)\n            boxes3d = cam_boxes3d.tensor\n            # generate attr scores from attr labels\n            attrs = labels.new_tensor([attr for attr in attrs_per_frame])\n            boxes3d, scores, labels, attrs = box3d_multiclass_nms(\n                boxes3d,\n                cam_boxes3d_for_nms,\n                scores,\n                nms_cfg.score_thr,\n                nms_cfg.max_per_frame,\n                nms_cfg,\n                mlvl_attr_scores=attrs)\n            cam_boxes3d = CameraInstance3DBoxes(boxes3d, box_dim=9)\n            det = bbox3d2result(cam_boxes3d, scores, labels, attrs)\n            boxes, attrs = output_to_nusc_box(det)\n            boxes, attrs = cam_nusc_box_to_global(\n                self.data_infos[sample_id + 1 - CAM_NUM], boxes, attrs,\n                mapped_class_names, self.eval_detection_configs,\n                self.eval_version)\n\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                attr = self.get_attr_name(attrs[i], name)\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                    detection_name=name,\n                    detection_score=box.score,\n                    attribute_name=attr)\n                annos.append(nusc_anno)\n            # other views results of the same frame should be concatenated\n            if sample_token in nusc_annos:\n                nusc_annos[sample_token].extend(annos)\n            else:\n                nusc_annos[sample_token] = annos\n\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        mmcv.dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='img_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'img_bbox'.\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        #from nuscenes.eval.detection.evaluate import NuScenesEval\n        from .nuscnes_eval import NuScenesEval_custom\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        self.nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        # nusc_eval = NuScenesEval(\n        #     nusc,\n        #     config=self.eval_detection_configs,\n        #     result_path=result_path,\n        #     eval_set=eval_set_map[self.version],\n        #     output_dir=output_dir,\n        #     verbose=False)\n        self.nusc_eval = NuScenesEval_custom(\n            self.nusc,\n            config=self.eval_detection_configs,\n            result_path=result_path,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=True,\n            overlap_test=self.overlap_test,\n            data_infos=self.data_infos\n            )\n\n        self.nusc_eval.main(render_curves=True)\n\n        # record metrics\n        metrics = mmcv.load(osp.join(output_dir, 'metrics_summary.json'))\n        detail = dict()\n        metric_prefix = f'{result_name}_NuScenes'\n        for name in self.CLASSES:\n            for k, v in metrics['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,\n                                      self.ErrNameMapping[k])] = val\n\n        detail['{}/NDS'.format(metric_prefix)] = metrics['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics['mean_ap']\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None, **kwargs):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n        Args:\n            results (list[tuple | numpy.ndarray]): Testing results of the\n                dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n        Returns:\n            tuple: (result_files, tmp_dir), result_files is a dict containing \\\n                the json filepaths, tmp_dir is the temporal directory created \\\n                for saving json files when jsonfile_prefix is not specified.\n        \"\"\"\n        assert isinstance(results, list), 'results must be a list'\n        assert len(results) == len(self), (\n            'The length of results is not equal to the dataset len: {} != {}'.\n            format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        # currently the output prediction results could be in two formats\n        # 1. list of dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...)\n        # 2. list of dict('pts_bbox' or 'img_bbox':\n        #     dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...))\n        # this is a workaround to enable evaluation of both formats on nuScenes\n        # refer to https://github.com/open-mmlab/mmdetection3d/issues/449\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                # not evaluate 2D predictions on nuScenes\n                if '2d' in name:\n                    continue\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n\n        return result_files, tmp_dir\n\n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['img_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print('Evaluating bboxes of {}'.format(name))\n                ret_dict = self._evaluate_single(result_files[name])\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(result_files)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\n    def _extract_data(self, index, pipeline, key, load_annos=False):\n        \"\"\"Load data using input pipeline and extract data according to key.\n        Args:\n            index (int): Index for accessing the target data.\n            pipeline (:obj:`Compose`): Composed data loading pipeline.\n            key (str | list[str]): One single or a list of data key.\n            load_annos (bool): Whether to load data annotations.\n                If True, need to set self.test_mode as False before loading.\n        Returns:\n            np.ndarray | torch.Tensor | list[np.ndarray | torch.Tensor]:\n                A single or a list of loaded data.\n        \"\"\"\n        assert pipeline is not None, 'data loading pipeline is not provided'\n        img_info = self.data_infos[index]\n        input_dict = dict(img_info=img_info)\n\n        if load_annos:\n            ann_info = self.get_ann_info(index)\n            input_dict.update(dict(ann_info=ann_info))\n\n        self.pre_pipeline(input_dict)\n        example = pipeline(input_dict)\n\n        # extract data items according to keys\n        if isinstance(key, str):\n            data = extract_result_dict(example, key)\n        else:\n            data = [extract_result_dict(example, k) for k in key]\n\n        return data\n\n    def _get_pipeline(self, pipeline):\n        \"\"\"Get data loading pipeline in self.show/evaluate function.\n        Args:\n            pipeline (list[dict] | None): Input pipeline. If None is given, \\\n                get from self.pipeline.\n        \"\"\"\n        if pipeline is None:\n            if not hasattr(self, 'pipeline') or self.pipeline is None:\n                warnings.warn(\n                    'Use default pipeline for data loading, this may cause '\n                    'errors when data is on ceph')\n                return self._build_default_pipeline()\n            loading_pipeline = get_loading_pipeline(self.pipeline.transforms)\n            return Compose(loading_pipeline)\n        return Compose(pipeline)\n\n    def _build_default_pipeline(self):\n        \"\"\"Build the default pipeline for this dataset.\"\"\"\n        pipeline = [\n            dict(type='LoadImageFromFileMono3D'),\n            dict(\n                type='DefaultFormatBundle3D',\n                class_names=self.CLASSES,\n                with_label=False),\n            dict(type='Collect3D', keys=['img'])\n        ]\n        return Compose(pipeline)\n\n    def show(self, results, out_dir, show=True, pipeline=None):\n        \"\"\"Results visualization.\n        Args:\n            results (list[dict]): List of bounding boxes results.\n            out_dir (str): Output directory of visualization result.\n            show (bool): Visualize the results online.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n        \"\"\"\n        assert out_dir is not None, 'Expect out_dir, got none.'\n        pipeline = self._get_pipeline(pipeline)\n        for i, result in enumerate(results):\n            if 'img_bbox' in result.keys():\n                result = result['img_bbox']\n            data_info = self.data_infos[i]\n            img_path = data_info['file_name']\n            file_name = osp.split(img_path)[-1].split('.')[0]\n            img, img_metas = self._extract_data(i, pipeline,\n                                                ['img', 'img_metas'])\n            # need to transpose channel to first dim\n            img = img.numpy().transpose(1, 2, 0)\n            gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d']\n            pred_bboxes = result['boxes_3d']\n            show_multi_modality_result(\n                img,\n                gt_bboxes,\n                pred_bboxes,\n                img_metas['cam2img'],\n                out_dir,\n                file_name,\n                box_mode='camera',\n                show=show)\n\n\ndef output_to_nusc_box(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n    Args:\n        detection (dict): Detection results.\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n            - attrs_3d (torch.Tensor, optional): Predicted attributes.\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n    attrs = None\n    if 'attrs_3d' in detection:\n        attrs = detection['attrs_3d'].numpy()\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n\n    # convert the dim/rot to nuscbox convention\n    box_dims[:, [0, 1, 2]] = box_dims[:, [2, 0, 1]]\n    box_yaw = -box_yaw\n\n    box_list = []\n    for i in range(len(box3d)):\n        q1 = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        q2 = pyquaternion.Quaternion(axis=[1, 0, 0], radians=np.pi / 2)\n        quat = q2 * q1\n        velocity = (box3d.tensor[i, 7], 0.0, box3d.tensor[i, 8])\n        box = NuScenesBox(\n            box_gravity_center[i],\n            box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box_list.append(box)\n    return box_list, attrs\n\n\ndef cam_nusc_box_to_global(info,\n                           boxes,\n                           attrs,\n                           classes,\n                           eval_configs,\n                           eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from camera to global coordinate.\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str): Evaluation version.\n            Default: 'detection_cvpr_2019'\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    attr_list = []\n    for (box, attr) in zip(boxes, attrs):\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info['cam2ego_rotation']))\n        box.translate(np.array(info['cam2ego_translation']))\n        # filter det in ego.\n        cls_range_map = eval_configs.class_range\n        radius = np.linalg.norm(box.center[:2], 2)\n        det_range = cls_range_map[classes[box.label]]\n        if radius > det_range:\n            continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n        attr_list.append(attr)\n    return box_list, attr_list\n\n\ndef global_nusc_box_to_cam(info,\n                           boxes,\n                           classes,\n                           eval_configs,\n                           eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from global to camera coordinate.\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str): Evaluation version.\n            Default: 'detection_cvpr_2019'\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    for box in boxes:\n        # Move box to ego vehicle coord system\n        box.translate(-np.array(info['ego2global_translation']))\n        box.rotate(\n            pyquaternion.Quaternion(info['ego2global_rotation']).inverse)\n        # filter det in ego.\n        cls_range_map = eval_configs.class_range\n        radius = np.linalg.norm(box.center[:2], 2)\n        det_range = cls_range_map[classes[box.label]]\n        if radius > det_range:\n            continue\n        # Move box to camera coord system\n        box.translate(-np.array(info['cam2ego_translation']))\n        box.rotate(pyquaternion.Quaternion(info['cam2ego_rotation']).inverse)\n        box_list.append(box)\n    return box_list\n\n\ndef nusc_box_to_cam_box3d(boxes):\n    \"\"\"Convert boxes from :obj:`NuScenesBox` to :obj:`CameraInstance3DBoxes`.\n    Args:\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n    Returns:\n        tuple (:obj:`CameraInstance3DBoxes` | torch.Tensor | torch.Tensor): \\\n            Converted 3D bounding boxes, scores and labels.\n    \"\"\"\n    locs = torch.Tensor([b.center for b in boxes]).view(-1, 3)\n    dims = torch.Tensor([b.wlh for b in boxes]).view(-1, 3)\n    rots = torch.Tensor([b.orientation.yaw_pitch_roll[0]\n                         for b in boxes]).view(-1, 1)\n    velocity = torch.Tensor([b.velocity[:2] for b in boxes]).view(-1, 2)\n\n    # convert nusbox to cambox convention\n    dims[:, [0, 1, 2]] = dims[:, [1, 2, 0]]\n    rots = -rots\n\n    boxes_3d = torch.cat([locs, dims, rots, velocity], dim=1).cuda()\n    cam_boxes3d = CameraInstance3DBoxes(\n        boxes_3d, box_dim=9, origin=(0.5, 0.5, 0.5))\n    scores = torch.Tensor([b.score for b in boxes]).cuda()\n    labels = torch.LongTensor([b.label for b in boxes]).cuda()\n    nms_scores = scores.new_zeros(scores.shape[0], 10 + 1)\n    indices = labels.new_tensor(list(range(scores.shape[0])))\n    nms_scores[indices, labels] = scores\n    return cam_boxes3d, nms_scores, labels"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscenes_styled_eval_utils.py",
    "content": "from collections import defaultdict\nfrom typing import List, Dict, Tuple, Union, Callable\nimport abc\nimport numpy as np\nfrom pyquaternion import Quaternion\n\n\ndef center_distance(gt_box, pred_box) -> float:\n    \"\"\"\n    L2 distance between the box centers (xy only).\n    :param gt_box: GT annotation sample.\n    :param pred_box: Predicted sample.\n    :return: L2 distance.\n    \"\"\"\n    return np.linalg.norm(np.array(pred_box.translation[:2]) - np.array(gt_box.translation[:2]))\n\n\ndef velocity_l2(gt_box, pred_box) -> float:\n    \"\"\"\n    L2 distance between the velocity vectors (xy only).\n    If the predicted velocities are nan, we return inf, which is subsequently clipped to 1.\n    :param gt_box: GT annotation sample.\n    :param pred_box: Predicted sample.\n    :return: L2 distance.\n    \"\"\"\n    return np.linalg.norm(np.array(pred_box.velocity) - np.array(gt_box.velocity))\n\n\ndef yaw_diff(gt_box, eval_box, period: float = 2*np.pi) -> float:\n    \"\"\"\n    Returns the yaw angle difference between the orientation of two boxes.\n    :param gt_box: Ground truth box.\n    :param eval_box: Predicted box.\n    :param period: Periodicity in radians for assessing angle difference.\n    :return: Yaw angle difference in radians in [0, pi].\n    \"\"\"\n    yaw_gt = quaternion_yaw(Quaternion(gt_box.rotation))\n    yaw_est = quaternion_yaw(Quaternion(eval_box.rotation))\n\n    return abs(angle_diff(yaw_gt, yaw_est, period))\n\n\ndef angle_diff(x: float, y: float, period: float) -> float:\n    \"\"\"\n    Get the smallest angle difference between 2 angles: the angle from y to x.\n    :param x: To angle.\n    :param y: From angle.\n    :param period: Periodicity in radians for assessing angle difference.\n    :return: <float>. Signed smallest between-angle difference in range (-pi, pi).\n    \"\"\"\n\n    # calculate angle difference, modulo to [0, 2*pi]\n    diff = (x - y + period / 2) % period - period / 2\n    if diff > np.pi:\n        diff = diff - (2 * np.pi)  # shift (pi, 2*pi] to (-pi, 0]\n\n    return diff\n\n\ndef attr_acc(gt_box, pred_box) -> float:\n    \"\"\"\n    Computes the classification accuracy for the attribute of this class (if any).\n    If the GT class has no attributes or the annotation is missing attributes, we assign an accuracy of nan, which is\n    ignored later on.\n    :param gt_box: GT annotation sample.\n    :param pred_box: Predicted sample.\n    :return: Attribute classification accuracy (0 or 1) or nan if GT annotation does not have any attributes.\n    \"\"\"\n    if gt_box.attribute_name == '':\n        # If the class does not have attributes or this particular sample is missing attributes, return nan, which is\n        # ignored later. Note that about 0.4% of the sample_annotations have no attributes, although they should.\n        acc = np.nan\n    else:\n        # Check that label is correct.\n        acc = float(gt_box.attribute_name == pred_box.attribute_name)\n    return acc\n\n\ndef scale_iou(sample_annotation, sample_result) -> float:\n    \"\"\"\n    This method compares predictions to the ground truth in terms of scale.\n    It is equivalent to intersection over union (IOU) between the two boxes in 3D,\n    if we assume that the boxes are aligned, i.e. translation and rotation are considered identical.\n    :param sample_annotation: GT annotation sample.\n    :param sample_result: Predicted sample.\n    :return: Scale IOU.\n    \"\"\"\n    # Validate inputs.\n    sa_size = np.array(sample_annotation.size)\n    sr_size = np.array(sample_result.size)\n    assert all(sa_size > 0), 'Error: sample_annotation sizes must be >0.'\n    assert all(sr_size > 0), 'Error: sample_result sizes must be >0.'\n\n    # Compute IOU.\n    min_wlh = np.minimum(sa_size, sr_size)\n    volume_annotation = np.prod(sa_size)\n    volume_result = np.prod(sr_size)\n    intersection = np.prod(min_wlh)  # type: float\n    union = volume_annotation + volume_result - intersection  # type: float\n    iou = intersection / union\n\n    return iou\n\n\ndef quaternion_yaw(q: Quaternion) -> float:\n    \"\"\"\n    Calculate the yaw angle from a quaternion.\n    Note that this only works for a quaternion that represents a box in lidar or global coordinate frame.\n    It does not work for a box in the camera frame.\n    :param q: Quaternion of interest.\n    :return: Yaw angle in radians.\n    \"\"\"\n\n    # Project into xy plane.\n    v = np.dot(q.rotation_matrix, np.array([1, 0, 0]))\n\n    # Measure yaw using arctan.\n    yaw = np.arctan2(v[1], v[0])\n\n    return yaw\n\n\n\ndef cummean(x: np.array) -> np.array:\n    \"\"\"\n    Computes the cumulative mean up to each position in a NaN sensitive way\n    - If all values are NaN return an array of ones.\n    - If some values are NaN, accumulate arrays discording those entries.\n    \"\"\"\n    if sum(np.isnan(x)) == len(x):\n        # Is all numbers in array are NaN's.\n        return np.ones(len(x))  # If all errors are NaN set to error to 1 for all operating points.\n    else:\n        # Accumulate in a nan-aware manner.\n        sum_vals = np.nancumsum(x.astype(float))  # Cumulative sum ignoring nans.\n        count_vals = np.cumsum(~np.isnan(x))  # Number of non-nans up to each position.\n        return np.divide(sum_vals, count_vals, out=np.zeros_like(sum_vals), where=count_vals != 0)\n    \n\nclass DetectionMetricData(abc.ABC):\n    \"\"\" This class holds accumulated and interpolated data required to calculate the detection metrics. \"\"\"\n\n    nelem = 101\n\n    def __init__(self,\n                 recall: np.array,\n                 precision: np.array,\n                 confidence: np.array,\n                 trans_err: np.array,\n                 vel_err: np.array,\n                 scale_err: np.array,\n                 orient_err: np.array,\n                 attr_err: np.array):\n\n        # Assert lengths.\n        assert len(recall) == self.nelem\n        assert len(precision) == self.nelem\n        assert len(confidence) == self.nelem\n        assert len(trans_err) == self.nelem\n        assert len(vel_err) == self.nelem\n        assert len(scale_err) == self.nelem\n        assert len(orient_err) == self.nelem\n        assert len(attr_err) == self.nelem\n\n        # Assert ordering.\n        assert all(confidence == sorted(confidence, reverse=True))  # Confidences should be descending.\n        assert all(recall == sorted(recall))  # Recalls should be ascending.\n\n        # Set attributes explicitly to help IDEs figure out what is going on.\n        self.recall = recall\n        self.precision = precision\n        self.confidence = confidence\n        self.trans_err = trans_err\n        self.vel_err = vel_err\n        self.scale_err = scale_err\n        self.orient_err = orient_err\n        self.attr_err = attr_err\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.serialize().keys():\n            eq = eq and np.array_equal(getattr(self, key), getattr(other, key))\n        return eq\n\n    @property\n    def max_recall_ind(self):\n        \"\"\" Returns index of max recall achieved. \"\"\"\n\n        # Last instance of confidence > 0 is index of max achieved recall.\n        non_zero = np.nonzero(self.confidence)[0]\n        if len(non_zero) == 0:  # If there are no matches, all the confidence values will be zero.\n            max_recall_ind = 0\n        else:\n            max_recall_ind = non_zero[-1]\n\n        return max_recall_ind\n\n    @property\n    def max_recall(self):\n        \"\"\" Returns max recall achieved. \"\"\"\n\n        return self.recall[self.max_recall_ind]\n\n    def serialize(self):\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'recall': self.recall.tolist(),\n            'precision': self.precision.tolist(),\n            'confidence': self.confidence.tolist(),\n            'trans_err': self.trans_err.tolist(),\n            'vel_err': self.vel_err.tolist(),\n            'scale_err': self.scale_err.tolist(),\n            'orient_err': self.orient_err.tolist(),\n            'attr_err': self.attr_err.tolist(),\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(recall=np.array(content['recall']),\n                   precision=np.array(content['precision']),\n                   confidence=np.array(content['confidence']),\n                   trans_err=np.array(content['trans_err']),\n                   vel_err=np.array(content['vel_err']),\n                   scale_err=np.array(content['scale_err']),\n                   orient_err=np.array(content['orient_err']),\n                   attr_err=np.array(content['attr_err']))\n\n    @classmethod\n    def no_predictions(cls):\n        \"\"\" Returns a md instance corresponding to having no predictions. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.zeros(cls.nelem),\n                   confidence=np.zeros(cls.nelem),\n                   trans_err=np.ones(cls.nelem),\n                   vel_err=np.ones(cls.nelem),\n                   scale_err=np.ones(cls.nelem),\n                   orient_err=np.ones(cls.nelem),\n                   attr_err=np.ones(cls.nelem))\n\n    @classmethod\n    def random_md(cls):\n        \"\"\" Returns an md instance corresponding to a random results. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.random.random(cls.nelem),\n                   confidence=np.linspace(0, 1, cls.nelem)[::-1],\n                   trans_err=np.random.random(cls.nelem),\n                   vel_err=np.random.random(cls.nelem),\n                   scale_err=np.random.random(cls.nelem),\n                   orient_err=np.random.random(cls.nelem),\n                   attr_err=np.random.random(cls.nelem))\n    \n\nclass DetectionMetricDataList:\n    \"\"\" This stores a set of MetricData in a dict indexed by (name, match-distance). \"\"\"\n\n    def __init__(self):\n        self.md = {}\n\n    def __getitem__(self, key):\n        return self.md[key]\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.md.keys():\n            eq = eq and self[key] == other[key]\n        return eq\n\n    def get_class_data(self, detection_name: str) -> List[Tuple[DetectionMetricData, float]]:\n        \"\"\" Get all the MetricData entries for a certain detection_name. \"\"\"\n        return [(md, dist_th) for (name, dist_th), md in self.md.items() if name == detection_name]\n\n    def get_dist_data(self, dist_th: float) -> List[Tuple[DetectionMetricData, str]]:\n        \"\"\" Get all the MetricData entries for a certain match_distance. \"\"\"\n        return [(md, detection_name) for (detection_name, dist), md in self.md.items() if dist == dist_th]\n\n    def set(self, detection_name: str, match_distance: float, data: DetectionMetricData):\n        \"\"\" Sets the MetricData entry for a certain detection_name and match_distance. \"\"\"\n        self.md[(detection_name, match_distance)] = data\n\n    def serialize(self) -> dict:\n        return {key[0] + ':' + str(key[1]): value.serialize() for key, value in self.md.items()}\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        mdl = cls()\n        for key, md in content.items():\n            name, distance = key.split(':')\n            mdl.set(name, float(distance), DetectionMetricData.deserialize(md))\n        return mdl\n\nclass DetectionMetrics:\n    \"\"\" Stores average precision and true positive metric results. Provides properties to summarize. \"\"\"\n\n    def __init__(self, cfg: dict):\n\n        self.cfg = cfg\n        self._label_aps = defaultdict(lambda: defaultdict(float))\n        self._label_tp_errors = defaultdict(lambda: defaultdict(float))\n        self.eval_time = None\n\n    def add_label_ap(self, detection_name: str, dist_th: float, ap: float) -> None:\n        self._label_aps[detection_name][dist_th] = ap\n\n    def get_label_ap(self, detection_name: str, dist_th: float) -> float:\n        return self._label_aps[detection_name][dist_th]\n\n    def add_label_tp(self, detection_name: str, metric_name: str, tp: float):\n        self._label_tp_errors[detection_name][metric_name] = tp\n\n    def get_label_tp(self, detection_name: str, metric_name: str) -> float:\n        return self._label_tp_errors[detection_name][metric_name]\n\n    def add_runtime(self, eval_time: float) -> None:\n        self.eval_time = eval_time\n\n    @property\n    def mean_dist_aps(self) -> Dict[str, float]:\n        \"\"\" Calculates the mean over distance thresholds for each label. \"\"\"\n        return {class_name: np.mean(list(d.values())) for class_name, d in self._label_aps.items()}\n\n    @property\n    def mean_ap(self) -> float:\n        \"\"\" Calculates the mean AP by averaging over distance thresholds and classes. \"\"\"\n        return float(np.mean(list(self.mean_dist_aps.values())))\n\n    @property\n    def tp_errors(self) -> Dict[str, float]:\n        \"\"\" Calculates the mean true positive error across all classes for each metric. \"\"\"\n        errors = {}\n        for metric_name in self.cfg['tp_metrics']:\n            class_errors = []\n            for detection_name in self.cfg['class_names']:\n                class_errors.append(self.get_label_tp(detection_name, metric_name))\n\n            errors[metric_name] = float(np.nanmean(class_errors))\n\n        return errors\n\n    @property\n    def tp_scores(self) -> Dict[str, float]:\n        scores = {}\n        tp_errors = self.tp_errors\n        for metric_name in self.cfg['tp_metrics']:\n\n            # We convert the true positive errors to \"scores\" by 1-error.\n            score = 1.0 - tp_errors[metric_name]\n\n            # Some of the true positive errors are unbounded, so we bound the scores to min 0.\n            score = max(0.0, score)\n\n            scores[metric_name] = score\n\n        return scores\n\n    @property\n    def nd_score(self) -> float:\n        \"\"\"\n        Compute the nuScenes detection score (NDS, weighted sum of the individual scores).\n        :return: The NDS.\n        \"\"\"\n        # Summarize.\n        total = float(self.cfg['mean_ap_weight'] * self.mean_ap + np.sum(list(self.tp_scores.values())))\n\n        # Normalize.\n        total = total / float(self.cfg['mean_ap_weight'] + len(self.tp_scores.keys()))\n\n        return total\n    \n\n    def serialize(self):\n        return {\n            'label_aps': self._label_aps,\n            'mean_dist_aps': self.mean_dist_aps,\n            'mean_ap': self.mean_ap,\n            'label_tp_errors': self._label_tp_errors,\n            'tp_errors': self.tp_errors,\n            'tp_scores': self.tp_scores,\n            'nd_score': self.nd_score,\n            'eval_time': self.eval_time,\n            'cfg': self.cfg\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized dictionary. \"\"\"\n\n        cfg = content['cfg']\n        metrics = cls(cfg=cfg)\n        metrics.add_runtime(content['eval_time'])\n\n        for detection_name, label_aps in content['label_aps'].items():\n            for dist_th, ap in label_aps.items():\n                metrics.add_label_ap(detection_name=detection_name, dist_th=float(dist_th), ap=float(ap))\n\n        for detection_name, label_tps in content['label_tp_errors'].items():\n            for metric_name, tp in label_tps.items():\n                metrics.add_label_tp(detection_name=detection_name, metric_name=metric_name, tp=float(tp))\n\n        return metrics\n\n    def __eq__(self, other):\n        eq = True\n        eq = eq and self._label_aps == other._label_aps\n        eq = eq and self._label_tp_errors == other._label_tp_errors\n        eq = eq and self.eval_time == other.eval_time\n        eq = eq and self.cfg == other.cfg\n\n        return eq\n    \n\nclass DetectionBox(abc.ABC):\n    \"\"\" Data class used during detection evaluation. Can be a prediction or ground truth.\"\"\"\n\n    def __init__(self,\n                 sample_token: str = \"\",\n                 translation: Tuple[float, float, float] = (0, 0, 0),\n                 size: Tuple[float, float, float] = (0, 0, 0),\n                 rotation: Tuple[float, float, float, float] = (0, 0, 0, 0),\n                 velocity: Tuple[float, float] = (0, 0),\n                 ego_translation: Tuple[float, float, float] = (0, 0, 0),  # Translation to ego vehicle in meters.\n                 num_pts: int = -1,  # Nbr. LIDAR or RADAR inside the box. Only for gt boxes.\n                 detection_name: str = 'car',  # The class name used in the detection challenge.\n                 detection_score: float = -1.0,  # GT samples do not have a score.\n                 attribute_name: str = ''):  # Box attribute. Each box can have at most 1 attribute.\n\n\n        assert detection_name is not None, 'Error: detection_name cannot be empty!'\n        # assert detection_name in DETECTION_NAMES, 'Error: Unknown detection_name %s' % detection_name\n\n        # assert attribute_name in ATTRIBUTE_NAMES or attribute_name == '', \\\n        #     'Error: Unknown attribute_name %s' % attribute_name\n\n        assert type(detection_score) == float, 'Error: detection_score must be a float!'\n        assert not np.any(np.isnan(detection_score)), 'Error: detection_score may not be NaN!'\n        self.sample_token = sample_token\n        self.translation = translation\n        self.size = size\n        self.rotation = rotation\n        self.velocity = velocity\n        self.ego_translation = ego_translation\n        self.num_pts = num_pts\n        self.detection_name = detection_name\n        self.detection_score = detection_score\n        self.attribute_name = attribute_name\n\n    def __eq__(self, other):\n        return (self.sample_token == other.sample_token and\n                self.translation == other.translation and\n                self.size == other.size and\n                self.rotation == other.rotation and\n                self.velocity == other.velocity and\n                self.ego_translation == other.ego_translation and\n                self.num_pts == other.num_pts and\n                self.detection_name == other.detection_name and\n                self.detection_score == other.detection_score and\n                self.attribute_name == other.attribute_name)\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(sample_token=content['sample_token'],\n                   translation=tuple(content['translation']),\n                   size=tuple(content['size']),\n                   rotation=tuple(content['rotation']),\n                   velocity=tuple(content['velocity']),\n                   ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                   else tuple(content['ego_translation']),\n                   num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                   detection_name=content['detection_name'],\n                   detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                   attribute_name=content['attribute_name'])\n    @property\n    def ego_dist(self) -> float:\n        \"\"\" Compute the distance from this box to the ego vehicle in 2D. \"\"\"\n        return np.sqrt(np.sum(np.array(self.ego_translation[:2]) ** 2))    \n\n\n\n\n\nclass EvalBoxes:\n    \"\"\" Data class that groups EvalBox instances by sample. \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the EvalBoxes for GT or predictions.\n        \"\"\"\n        self.boxes = defaultdict(list)\n\n    def __repr__(self):\n        return \"EvalBoxes with {} boxes across {} samples\".format(len(self.all), len(self.sample_tokens))\n\n    def __getitem__(self, item) -> List[DetectionBox]:\n        return self.boxes[item]\n\n    def __eq__(self, other):\n        if not set(self.sample_tokens) == set(other.sample_tokens):\n            return False\n        for token in self.sample_tokens:\n            if not len(self[token]) == len(other[token]):\n                return False\n            for box1, box2 in zip(self[token], other[token]):\n                if box1 != box2:\n                    return False\n        return True\n\n    def __len__(self):\n        return len(self.boxes)\n\n    @property\n    def all(self) -> List[DetectionBox]:\n        \"\"\" Returns all EvalBoxes in a list. \"\"\"\n        ab = []\n        for sample_token in self.sample_tokens:\n            ab.extend(self[sample_token])\n        return ab\n\n    @property\n    def sample_tokens(self) -> List[str]:\n        \"\"\" Returns a list of all keys. \"\"\"\n        return list(self.boxes.keys())\n\n    def add_boxes(self, sample_token: str, boxes: List[DetectionBox]) -> None:\n        \"\"\" Adds a list of boxes. \"\"\"\n        self.boxes[sample_token].extend(boxes)\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {key: [box.serialize() for box in boxes] for key, boxes in self.boxes.items()}\n\n    @classmethod\n    def deserialize(cls, content: dict, box_cls):\n        \"\"\"\n        Initialize from serialized content.\n        :param content: A dictionary with the serialized content of the box.\n        :param box_cls: The class of the boxes, DetectionBox or TrackingBox.\n        \"\"\"\n        eb = cls()\n        for sample_token, boxes in content.items():\n            eb.add_boxes(sample_token, [box_cls.deserialize(box) for box in boxes])\n        return eb\n    \n\ndef accumulate(gt_boxes,\n               pred_boxes,\n               class_name: str,\n               dist_fcn: Callable,\n               dist_th: float,\n               verbose: bool = False) -> DetectionMetricData:\n    \"\"\"\n    Average Precision over predefined different recall thresholds for a single distance threshold.\n    The recall/conf thresholds and other raw metrics will be used in secondary metrics.\n    :param gt_boxes: Maps every sample_token to a list of its sample_annotations.\n    :param pred_boxes: Maps every sample_token to a list of its sample_results.\n    :param class_name: Class to compute AP on.\n    :param dist_fcn: Distance function used to match detections and ground truths.\n    :param dist_th: Distance threshold for a match.\n    :param verbose: If true, print debug messages.\n    :return: (average_prec, metrics). The average precision value and raw data for a number of metrics.\n    \"\"\"\n    # ---------------------------------------------\n    # Organize input and initialize accumulators.\n    # ---------------------------------------------\n\n    # Count the positives.\n    npos = len([1 for gt_box in gt_boxes.all if gt_box.detection_name == class_name])\n    if verbose:\n        print(\"Found {} GT of class {} out of {} total across {} samples.\".\n              format(npos, class_name, len(gt_boxes.all), len(gt_boxes.sample_tokens)))\n\n    # For missing classes in the GT, return a data structure corresponding to no predictions.\n    if npos == 0:\n        return DetectionMetricData.no_predictions()\n\n    # Organize the predictions in a single list.\n    pred_boxes_list = [box for box in pred_boxes.all if box.detection_name == class_name]\n    pred_confs = [box.detection_score for box in pred_boxes_list]\n\n    if verbose:\n        print(\"Found {} PRED of class {} out of {} total across {} samples.\".\n              format(len(pred_confs), class_name, len(pred_boxes.all), len(pred_boxes.sample_tokens)))\n\n    # Sort by confidence.\n    sortind = [i for (v, i) in sorted((v, i) for (i, v) in enumerate(pred_confs))][::-1]\n\n    # Do the actual matching.\n    tp = []  # Accumulator of true positives.\n    fp = []  # Accumulator of false positives.\n    conf = []  # Accumulator of confidences.\n\n    # match_data holds the extra metrics we calculate for each match.\n    match_data = {'trans_err': [],\n                  'vel_err': [],\n                  'scale_err': [],\n                  'orient_err': [],\n                  'attr_err': [],\n                  'conf': []}\n\n    # ---------------------------------------------\n    # Match and accumulate match data.\n    # ---------------------------------------------\n\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th\n\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n\n            #  Update tp, fp and confs.\n            tp.append(1)\n            fp.append(0)\n            conf.append(pred_box.detection_score)\n\n            # Since it is a match, update match data also.\n            gt_box_match = gt_boxes[pred_box.sample_token][match_gt_idx]\n\n            match_data['trans_err'].append(center_distance(gt_box_match, pred_box))\n            match_data['vel_err'].append(velocity_l2(gt_box_match, pred_box))\n            match_data['scale_err'].append(1 - scale_iou(gt_box_match, pred_box))\n\n            # Barrier orientation is only determined up to 180 degree. (For cones orientation is discarded later)\n            period = np.pi if class_name == 'barrier' else 2 * np.pi\n            match_data['orient_err'].append(yaw_diff(gt_box_match, pred_box, period=period))\n\n            match_data['attr_err'].append(1 - attr_acc(gt_box_match, pred_box))\n            match_data['conf'].append(pred_box.detection_score)\n\n        else:\n            # No match. Mark this as a false positive.\n            tp.append(0)\n            fp.append(1)\n            conf.append(pred_box.detection_score)\n\n    # Check if we have any matches. If not, just return a \"no predictions\" array.\n    if len(match_data['trans_err']) == 0:\n        return DetectionMetricData.no_predictions()\n\n    # ---------------------------------------------\n    # Calculate and interpolate precision and recall\n    # ---------------------------------------------\n\n    # Accumulate.\n    tp = np.cumsum(tp).astype(float)\n    fp = np.cumsum(fp).astype(float)\n    conf = np.array(conf)\n\n    # Calculate precision and recall.\n    prec = tp / (fp + tp)\n    rec = tp / float(npos)\n\n    rec_interp = np.linspace(0, 1, DetectionMetricData.nelem)  # 101 steps, from 0% to 100% recall.\n    prec = np.interp(rec_interp, rec, prec, right=0)\n    conf = np.interp(rec_interp, rec, conf, right=0)\n    rec = rec_interp\n\n    # ---------------------------------------------\n    # Re-sample the match-data to match, prec, recall and conf.\n    # ---------------------------------------------\n\n    for key in match_data.keys():\n        if key == \"conf\":\n            continue  # Confidence is used as reference to align with fp and tp. So skip in this step.\n\n        else:\n            # For each match_data, we first calculate the accumulated mean.\n            tmp = cummean(np.array(match_data[key]))\n\n            # Then interpolate based on the confidences. (Note reversing since np.interp needs increasing arrays)\n            match_data[key] = np.interp(conf[::-1], match_data['conf'][::-1], tmp[::-1])[::-1]\n\n    # ---------------------------------------------\n    # Done. Instantiate MetricData and return\n    # ---------------------------------------------\n    return DetectionMetricData(recall=rec,\n                               precision=prec,\n                               confidence=conf,\n                               trans_err=match_data['trans_err'],\n                               vel_err=match_data['vel_err'],\n                               scale_err=match_data['scale_err'],\n                               orient_err=match_data['orient_err'],\n                               attr_err=match_data['attr_err'])\n\n\n\ndef calc_ap(md: DetectionMetricData, min_recall: float, min_precision: float) -> float:\n    \"\"\" Calculated average precision. \"\"\"\n\n    assert 0 <= min_precision < 1\n    assert 0 <= min_recall <= 1\n\n    prec = np.copy(md.precision)\n    prec = prec[round(100 * min_recall) + 1:]  # Clip low recalls. +1 to exclude the min recall bin.\n    prec -= min_precision  # Clip low precision\n    prec[prec < 0] = 0\n    return float(np.mean(prec)) / (1.0 - min_precision)\n\n\ndef calc_tp(md: DetectionMetricData, min_recall: float, metric_name: str) -> float:\n    \"\"\" Calculates true positive errors. \"\"\"\n\n    first_ind = round(100 * min_recall) + 1  # +1 to exclude the error at min recall.\n    last_ind = md.max_recall_ind  # First instance of confidence = 0 is index of max achieved recall.\n    if last_ind < first_ind:\n        return 1.0  # Assign 1 here. If this happens for all classes, the score for that TP metric will be 0.\n    else:\n        return float(np.mean(getattr(md, metric_name)[first_ind: last_ind + 1]))  # +1 to include error at max recall.\n    \n    \ndef quaternion_yaw(q: Quaternion) -> float:\n    \"\"\"\n    Calculate the yaw angle from a quaternion.\n    Note that this only works for a quaternion that represents a box in lidar or global coordinate frame.\n    It does not work for a box in the camera frame.\n    :param q: Quaternion of interest.\n    :return: Yaw angle in radians.\n    \"\"\"\n\n    # Project into xy plane.\n    v = np.dot(q.rotation_matrix, np.array([1, 0, 0]))\n\n    # Measure yaw using arctan.\n    yaw = np.arctan2(v[1], v[0])\n\n    return yaw"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscenes_vad_dataset.py",
    "content": "import os\nimport json\nimport copy\nimport tempfile\nfrom typing import Dict, List\nfrom mmcv.fileio.io import dump,load\nimport numpy as np\nfrom .builder import DATASETS\nfrom mmcv.datasets import NuScenesDataset\nimport pyquaternion\nimport mmcv\nfrom os import path as osp\nimport torch\nimport numpy as np\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom .vad_custom_nuscenes_eval import NuScenesEval_custom\nfrom nuscenes.eval.common.utils import center_distance\nfrom mmcv.utils.visual import save_tensor\nfrom mmcv.parallel import DataContainer as DC\nimport random\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom mmcv.core.bbox.structures.nuscenes_box import CustomNuscenesBox\nfrom shapely import affinity, ops\nfrom shapely.geometry import LineString, box, MultiPolygon, MultiLineString\nfrom mmcv.datasets.pipelines import to_tensor\nfrom nuscenes.map_expansion.map_api import NuScenesMap, NuScenesMapExplorer\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES\n\n\nclass LiDARInstanceLines(object):\n    \"\"\"Line instance in LIDAR coordinates\n\n    \"\"\"\n    def __init__(self, \n                 instance_line_list, \n                 sample_dist=1,\n                 num_samples=250,\n                 padding=False,\n                 fixed_num=-1,\n                 padding_value=-10000,\n                 patch_size=None):\n        assert isinstance(instance_line_list, list)\n        assert patch_size is not None\n        if len(instance_line_list) != 0:\n            assert isinstance(instance_line_list[0], LineString)\n        self.patch_size = patch_size\n        self.max_x = self.patch_size[1] / 2\n        self.max_y = self.patch_size[0] / 2\n        self.sample_dist = sample_dist\n        self.num_samples = num_samples\n        self.padding = padding\n        self.fixed_num = fixed_num\n        self.padding_value = padding_value\n\n        self.instance_list = instance_line_list\n\n    @property\n    def start_end_points(self):\n        \"\"\"\n        return torch.Tensor([N,4]), in xstart, ystart, xend, yend form\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_se_points_list = []\n        for instance in self.instance_list:\n            se_points = []\n            se_points.extend(instance.coords[0])\n            se_points.extend(instance.coords[-1])\n            instance_se_points_list.append(se_points)\n        instance_se_points_array = np.array(instance_se_points_list)\n        instance_se_points_tensor = to_tensor(instance_se_points_array)\n        instance_se_points_tensor = instance_se_points_tensor.to(\n                                dtype=torch.float32)\n        instance_se_points_tensor[:,0] = torch.clamp(instance_se_points_tensor[:,0], min=-self.max_x,max=self.max_x)\n        instance_se_points_tensor[:,1] = torch.clamp(instance_se_points_tensor[:,1], min=-self.max_y,max=self.max_y)\n        instance_se_points_tensor[:,2] = torch.clamp(instance_se_points_tensor[:,2], min=-self.max_x,max=self.max_x)\n        instance_se_points_tensor[:,3] = torch.clamp(instance_se_points_tensor[:,3], min=-self.max_y,max=self.max_y)\n        return instance_se_points_tensor\n\n    @property\n    def bbox(self):\n        \"\"\"\n        return torch.Tensor([N,4]), in xmin, ymin, xmax, ymax form\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_bbox_list = []\n        for instance in self.instance_list:\n            # bounds is bbox: [xmin, ymin, xmax, ymax]\n            instance_bbox_list.append(instance.bounds)\n        instance_bbox_array = np.array(instance_bbox_list)\n        instance_bbox_tensor = to_tensor(instance_bbox_array)\n        instance_bbox_tensor = instance_bbox_tensor.to(\n                            dtype=torch.float32)\n        instance_bbox_tensor[:,0] = torch.clamp(instance_bbox_tensor[:,0], min=-self.max_x,max=self.max_x)\n        instance_bbox_tensor[:,1] = torch.clamp(instance_bbox_tensor[:,1], min=-self.max_y,max=self.max_y)\n        instance_bbox_tensor[:,2] = torch.clamp(instance_bbox_tensor[:,2], min=-self.max_x,max=self.max_x)\n        instance_bbox_tensor[:,3] = torch.clamp(instance_bbox_tensor[:,3], min=-self.max_y,max=self.max_y)\n        return instance_bbox_tensor\n\n    @property\n    def fixed_num_sampled_points(self):\n        \"\"\"\n        return torch.Tensor([N,fixed_num,2]), in xmin, ymin, xmax, ymax form\n            N means the num of instances\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_points_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n            instance_points_list.append(sampled_points)\n        instance_points_array = np.array(instance_points_list)\n        instance_points_tensor = to_tensor(instance_points_array)\n        instance_points_tensor = instance_points_tensor.to(\n                            dtype=torch.float32)\n        instance_points_tensor[:,:,0] = torch.clamp(instance_points_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n        instance_points_tensor[:,:,1] = torch.clamp(instance_points_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n        return instance_points_tensor\n\n    @property\n    def fixed_num_sampled_points_ambiguity(self):\n        \"\"\"\n        return torch.Tensor([N,fixed_num,2]), in xmin, ymin, xmax, ymax form\n            N means the num of instances\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_points_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n            instance_points_list.append(sampled_points)\n        instance_points_array = np.array(instance_points_list)\n        instance_points_tensor = to_tensor(instance_points_array)\n        instance_points_tensor = instance_points_tensor.to(\n                            dtype=torch.float32)\n        instance_points_tensor[:,:,0] = torch.clamp(instance_points_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n        instance_points_tensor[:,:,1] = torch.clamp(instance_points_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n        instance_points_tensor = instance_points_tensor.unsqueeze(1)\n        return instance_points_tensor\n\n    @property\n    def fixed_num_sampled_points_torch(self):\n        \"\"\"\n        return torch.Tensor([N,fixed_num,2]), in xmin, ymin, xmax, ymax form\n            N means the num of instances\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instance_points_list = []\n        for instance in self.instance_list:\n            # distances = np.linspace(0, instance.length, self.fixed_num)\n            # sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n            poly_pts = to_tensor(np.array(list(instance.coords)))\n            poly_pts = poly_pts.unsqueeze(0).permute(0,2,1)\n            sampled_pts = torch.nn.functional.interpolate(poly_pts,size=(self.fixed_num),mode='linear',align_corners=True)\n            sampled_pts = sampled_pts.permute(0,2,1).squeeze(0)\n            instance_points_list.append(sampled_pts)\n        # instance_points_array = np.array(instance_points_list)\n        # instance_points_tensor = to_tensor(instance_points_array)\n        instance_points_tensor = torch.stack(instance_points_list,dim=0)\n        instance_points_tensor = instance_points_tensor.to(\n                            dtype=torch.float32)\n        instance_points_tensor[:,:,0] = torch.clamp(instance_points_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n        instance_points_tensor[:,:,1] = torch.clamp(instance_points_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n        return instance_points_tensor\n\n    @property\n    def shift_fixed_num_sampled_points(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            fixed_num = fixed_num_pts.shape[0]\n            shift_pts_list = []\n            if is_poly:\n                # import pdb;pdb.set_trace()\n                for shift_right_i in range(fixed_num):\n                    shift_pts_list.append(fixed_num_pts.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([fixed_num-shift_pts.shape[0],fixed_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v1(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            pts_num = fixed_num_pts.shape[0]\n            shift_num = pts_num - 1\n            if is_poly:\n                pts_to_shift = fixed_num_pts[:-1,:]\n            shift_pts_list = []\n            if is_poly:\n                for shift_right_i in range(shift_num):\n                    shift_pts_list.append(pts_to_shift.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            if is_poly:\n                _, _, num_coords = shift_pts.shape\n                tmp_shift_pts = shift_pts.new_zeros((shift_num, pts_num, num_coords))\n                tmp_shift_pts[:,:-1,:] = shift_pts\n                tmp_shift_pts[:,-1,:] = shift_pts[:,0,:]\n                shift_pts = tmp_shift_pts\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([shift_num-shift_pts.shape[0],pts_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v2(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instances_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            poly_pts = np.array(list(instance.coords))\n            start_pts = poly_pts[0]\n            end_pts = poly_pts[-1]\n            is_poly = np.equal(start_pts, end_pts)\n            is_poly = is_poly.all()\n            shift_pts_list = []\n            pts_num, coords_num = poly_pts.shape\n            shift_num = pts_num - 1\n            final_shift_num = self.fixed_num - 1\n            if is_poly:\n                pts_to_shift = poly_pts[:-1,:]\n                for shift_right_i in range(shift_num):\n                    shift_pts = np.roll(pts_to_shift,shift_right_i,axis=0)\n                    pts_to_concat = shift_pts[0]\n                    pts_to_concat = np.expand_dims(pts_to_concat,axis=0)\n                    shift_pts = np.concatenate((shift_pts,pts_to_concat),axis=0)\n                    shift_instance = LineString(shift_pts)\n                    shift_sampled_points = np.array([list(shift_instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                    shift_pts_list.append(shift_sampled_points)\n                # import pdb;pdb.set_trace()\n            else:\n                sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                flip_sampled_points = np.flip(sampled_points, axis=0)\n                shift_pts_list.append(sampled_points)\n                shift_pts_list.append(flip_sampled_points)\n            \n            multi_shifts_pts = np.stack(shift_pts_list,axis=0)\n            shifts_num,_,_ = multi_shifts_pts.shape\n\n            if shifts_num > final_shift_num:\n                index = np.random.choice(multi_shifts_pts.shape[0], final_shift_num, replace=False)\n                multi_shifts_pts = multi_shifts_pts[index]\n            \n            multi_shifts_pts_tensor = to_tensor(multi_shifts_pts)\n            multi_shifts_pts_tensor = multi_shifts_pts_tensor.to(\n                            dtype=torch.float32)\n            \n            multi_shifts_pts_tensor[:,:,0] = torch.clamp(multi_shifts_pts_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n            multi_shifts_pts_tensor[:,:,1] = torch.clamp(multi_shifts_pts_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n            # if not is_poly:\n            if multi_shifts_pts_tensor.shape[0] < final_shift_num:\n                padding = torch.full([final_shift_num-multi_shifts_pts_tensor.shape[0],self.fixed_num,2], self.padding_value)\n                multi_shifts_pts_tensor = torch.cat([multi_shifts_pts_tensor,padding],dim=0)\n            instances_list.append(multi_shifts_pts_tensor)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v3(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        assert len(self.instance_list) != 0\n        instances_list = []\n        for instance in self.instance_list:\n            distances = np.linspace(0, instance.length, self.fixed_num)\n            poly_pts = np.array(list(instance.coords))\n            start_pts = poly_pts[0]\n            end_pts = poly_pts[-1]\n            is_poly = np.equal(start_pts, end_pts)\n            is_poly = is_poly.all()\n            shift_pts_list = []\n            pts_num, coords_num = poly_pts.shape\n            shift_num = pts_num - 1\n            final_shift_num = self.fixed_num - 1\n            if is_poly:\n                pts_to_shift = poly_pts[:-1,:]\n                for shift_right_i in range(shift_num):\n                    shift_pts = np.roll(pts_to_shift,shift_right_i,axis=0)\n                    pts_to_concat = shift_pts[0]\n                    pts_to_concat = np.expand_dims(pts_to_concat,axis=0)\n                    shift_pts = np.concatenate((shift_pts,pts_to_concat),axis=0)\n                    shift_instance = LineString(shift_pts)\n                    shift_sampled_points = np.array([list(shift_instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                    shift_pts_list.append(shift_sampled_points)\n                flip_pts_to_shift = np.flip(pts_to_shift, axis=0)\n                for shift_right_i in range(shift_num):\n                    shift_pts = np.roll(flip_pts_to_shift,shift_right_i,axis=0)\n                    pts_to_concat = shift_pts[0]\n                    pts_to_concat = np.expand_dims(pts_to_concat,axis=0)\n                    shift_pts = np.concatenate((shift_pts,pts_to_concat),axis=0)\n                    shift_instance = LineString(shift_pts)\n                    shift_sampled_points = np.array([list(shift_instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                    shift_pts_list.append(shift_sampled_points)\n                # import pdb;pdb.set_trace()\n            else:\n                sampled_points = np.array([list(instance.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n                flip_sampled_points = np.flip(sampled_points, axis=0)\n                shift_pts_list.append(sampled_points)\n                shift_pts_list.append(flip_sampled_points)\n            \n            multi_shifts_pts = np.stack(shift_pts_list,axis=0)\n            shifts_num,_,_ = multi_shifts_pts.shape\n            # import pdb;pdb.set_trace()\n            if shifts_num > 2*final_shift_num:\n                index = np.random.choice(shift_num, final_shift_num, replace=False)\n                flip0_shifts_pts = multi_shifts_pts[index]\n                flip1_shifts_pts = multi_shifts_pts[index+shift_num]\n                multi_shifts_pts = np.concatenate((flip0_shifts_pts,flip1_shifts_pts),axis=0)\n            \n            multi_shifts_pts_tensor = to_tensor(multi_shifts_pts)\n            multi_shifts_pts_tensor = multi_shifts_pts_tensor.to(\n                            dtype=torch.float32)\n            \n            multi_shifts_pts_tensor[:,:,0] = torch.clamp(multi_shifts_pts_tensor[:,:,0], min=-self.max_x,max=self.max_x)\n            multi_shifts_pts_tensor[:,:,1] = torch.clamp(multi_shifts_pts_tensor[:,:,1], min=-self.max_y,max=self.max_y)\n            # if not is_poly:\n            if multi_shifts_pts_tensor.shape[0] < 2*final_shift_num:\n                padding = torch.full([final_shift_num*2-multi_shifts_pts_tensor.shape[0],self.fixed_num,2], self.padding_value)\n                multi_shifts_pts_tensor = torch.cat([multi_shifts_pts_tensor,padding],dim=0)\n            instances_list.append(multi_shifts_pts_tensor)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_v4(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            pts_num = fixed_num_pts.shape[0]\n            shift_num = pts_num - 1\n            shift_pts_list = []\n            if is_poly:\n                pts_to_shift = fixed_num_pts[:-1,:]\n                for shift_right_i in range(shift_num):\n                    shift_pts_list.append(pts_to_shift.roll(shift_right_i,0))\n                flip_pts_to_shift = pts_to_shift.flip(0)\n                for shift_right_i in range(shift_num):\n                    shift_pts_list.append(flip_pts_to_shift.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            if is_poly:\n                _, _, num_coords = shift_pts.shape\n                tmp_shift_pts = shift_pts.new_zeros((shift_num*2, pts_num, num_coords))\n                tmp_shift_pts[:,:-1,:] = shift_pts\n                tmp_shift_pts[:,-1,:] = shift_pts[:,0,:]\n                shift_pts = tmp_shift_pts\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([shift_num*2-shift_pts.shape[0],pts_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    @property\n    def shift_fixed_num_sampled_points_torch(self):\n        \"\"\"\n        return  [instances_num, num_shifts, fixed_num, 2]\n        \"\"\"\n        fixed_num_sampled_points = self.fixed_num_sampled_points_torch\n        instances_list = []\n        is_poly = False\n        # is_line = False\n        # import pdb;pdb.set_trace()\n        for fixed_num_pts in fixed_num_sampled_points:\n            # [fixed_num, 2]\n            is_poly = fixed_num_pts[0].equal(fixed_num_pts[-1])\n            fixed_num = fixed_num_pts.shape[0]\n            shift_pts_list = []\n            if is_poly:\n                # import pdb;pdb.set_trace()\n                for shift_right_i in range(fixed_num):\n                    shift_pts_list.append(fixed_num_pts.roll(shift_right_i,0))\n            else:\n                shift_pts_list.append(fixed_num_pts)\n                shift_pts_list.append(fixed_num_pts.flip(0))\n            shift_pts = torch.stack(shift_pts_list,dim=0)\n\n            shift_pts[:,:,0] = torch.clamp(shift_pts[:,:,0], min=-self.max_x,max=self.max_x)\n            shift_pts[:,:,1] = torch.clamp(shift_pts[:,:,1], min=-self.max_y,max=self.max_y)\n\n            if not is_poly:\n                padding = torch.full([fixed_num-shift_pts.shape[0],fixed_num,2], self.padding_value)\n                shift_pts = torch.cat([shift_pts,padding],dim=0)\n                # padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                # sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            instances_list.append(shift_pts)\n        instances_tensor = torch.stack(instances_list, dim=0)\n        instances_tensor = instances_tensor.to(\n                            dtype=torch.float32)\n        return instances_tensor\n\n    # @property\n    # def polyline_points(self):\n    #     \"\"\"\n    #     return [[x0,y0],[x1,y1],...]\n    #     \"\"\"\n    #     assert len(self.instance_list) != 0\n    #     for instance in self.instance_list:\n\n\nclass VectorizedLocalMap(object):\n    CLASS2LABEL = {\n        'road_divider': 0,\n        'lane_divider': 0,\n        'ped_crossing': 1,\n        'contours': 2,\n        'others': -1\n    }\n    def __init__(self,\n                 dataroot,\n                 patch_size,\n                 map_classes=['divider','ped_crossing','boundary'],\n                 line_classes=['road_divider', 'lane_divider'],\n                 ped_crossing_classes=['ped_crossing'],\n                 contour_classes=['road_segment', 'lane'],\n                 sample_dist=1,\n                 num_samples=250,\n                 padding=False,\n                 fixed_ptsnum_per_line=-1,\n                 padding_value=-10000,):\n        '''\n        Args:\n            fixed_ptsnum_per_line = -1 : no fixed num\n        '''\n        super().__init__()\n        self.data_root = dataroot\n        self.MAPS = ['boston-seaport', 'singapore-hollandvillage',\n                     'singapore-onenorth', 'singapore-queenstown']\n        self.vec_classes = map_classes\n        self.line_classes = line_classes\n        self.ped_crossing_classes = ped_crossing_classes\n        self.polygon_classes = contour_classes\n        self.nusc_maps = {}\n        self.map_explorer = {}\n        for loc in self.MAPS:\n            self.nusc_maps[loc] = NuScenesMap(dataroot=self.data_root, map_name=loc)\n            self.map_explorer[loc] = NuScenesMapExplorer(self.nusc_maps[loc])\n\n        self.patch_size = patch_size\n        self.sample_dist = sample_dist\n        self.num_samples = num_samples\n        self.padding = padding\n        self.fixed_num = fixed_ptsnum_per_line\n        self.padding_value = padding_value\n\n    def gen_vectorized_samples(self, location, lidar2global_translation, lidar2global_rotation):\n        '''\n        use lidar2global to get gt map layers\n        '''\n        \n        map_pose = lidar2global_translation[:2]\n        rotation = Quaternion(lidar2global_rotation)\n\n        patch_box = (map_pose[0], map_pose[1], self.patch_size[0], self.patch_size[1])\n        patch_angle = quaternion_yaw(rotation) / np.pi * 180\n        # import pdb;pdb.set_trace()\n        vectors = []\n        for vec_class in self.vec_classes:\n            if vec_class == 'divider':\n                line_geom = self.get_map_geom(patch_box, patch_angle, self.line_classes, location)\n                line_instances_dict = self.line_geoms_to_instances(line_geom)     \n                for line_type, instances in line_instances_dict.items():\n                    for instance in instances:\n                        vectors.append((instance, self.CLASS2LABEL.get(line_type, -1)))\n            elif vec_class == 'ped_crossing':\n                ped_geom = self.get_map_geom(patch_box, patch_angle, self.ped_crossing_classes, location)\n                # ped_vector_list = self.ped_geoms_to_vectors(ped_geom)\n                ped_instance_list = self.ped_poly_geoms_to_instances(ped_geom)\n                # import pdb;pdb.set_trace()\n                for instance in ped_instance_list:\n                    vectors.append((instance, self.CLASS2LABEL.get('ped_crossing', -1)))\n            elif vec_class == 'boundary':\n                polygon_geom = self.get_map_geom(patch_box, patch_angle, self.polygon_classes, location)\n                # import pdb;pdb.set_trace()\n                poly_bound_list = self.poly_geoms_to_instances(polygon_geom)\n                # import pdb;pdb.set_trace()\n                for contour in poly_bound_list:\n                    vectors.append((contour, self.CLASS2LABEL.get('contours', -1)))\n            else:\n                raise ValueError(f'WRONG vec_class: {vec_class}')\n\n        # filter out -1\n        filtered_vectors = []\n        gt_pts_loc_3d = []\n        gt_pts_num_3d = []\n        gt_labels = []\n        gt_instance = []\n        for instance, type in vectors:\n            if type != -1:\n                gt_instance.append(instance)\n                gt_labels.append(type)\n        \n        gt_instance = LiDARInstanceLines(gt_instance,self.sample_dist,\n                        self.num_samples, self.padding, self.fixed_num,self.padding_value, patch_size=self.patch_size)\n\n        anns_results = dict(\n            gt_vecs_pts_loc=gt_instance,\n            gt_vecs_label=gt_labels,\n\n        )\n        # import pdb;pdb.set_trace()\n        return anns_results\n\n    def get_map_geom(self, patch_box, patch_angle, layer_names, location):\n        map_geom = []\n        for layer_name in layer_names:\n            if layer_name in self.line_classes:\n                # import pdb;pdb.set_trace()\n                geoms = self.get_divider_line(patch_box, patch_angle, layer_name, location)\n                # import pdb;pdb.set_trace()\n                # geoms = self.map_explorer[location]._get_layer_line(patch_box, patch_angle, layer_name)\n                map_geom.append((layer_name, geoms))\n            elif layer_name in self.polygon_classes:\n                geoms = self.get_contour_line(patch_box, patch_angle, layer_name, location)\n                # geoms = self.map_explorer[location]._get_layer_polygon(patch_box, patch_angle, layer_name)\n                map_geom.append((layer_name, geoms))\n            elif layer_name in self.ped_crossing_classes:\n                geoms = self.get_ped_crossing_line(patch_box, patch_angle, location)\n                # geoms = self.map_explorer[location]._get_layer_polygon(patch_box, patch_angle, layer_name)\n                map_geom.append((layer_name, geoms))\n        return map_geom\n\n    def _one_type_line_geom_to_vectors(self, line_geom):\n        line_vectors = []\n        \n        for line in line_geom:\n            if not line.is_empty:\n                if line.geom_type == 'MultiLineString':\n                    for single_line in line.geoms:\n                        line_vectors.append(self.sample_pts_from_line(single_line))\n                elif line.geom_type == 'LineString':\n                    line_vectors.append(self.sample_pts_from_line(line))\n                else:\n                    raise NotImplementedError\n        return line_vectors\n\n    def _one_type_line_geom_to_instances(self, line_geom):\n        line_instances = []\n        \n        for line in line_geom:\n            if not line.is_empty:\n                if line.geom_type == 'MultiLineString':\n                    for single_line in line.geoms:\n                        line_instances.append(single_line)\n                elif line.geom_type == 'LineString':\n                    line_instances.append(line)\n                else:\n                    raise NotImplementedError\n        return line_instances\n\n    def poly_geoms_to_vectors(self, polygon_geom):\n        roads = polygon_geom[0][1]\n        lanes = polygon_geom[1][1]\n        union_roads = ops.unary_union(roads)\n        union_lanes = ops.unary_union(lanes)\n        union_segments = ops.unary_union([union_roads, union_lanes])\n        max_x = self.patch_size[1] / 2\n        max_y = self.patch_size[0] / 2\n        local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n        exteriors = []\n        interiors = []\n        if union_segments.geom_type != 'MultiPolygon':\n            union_segments = MultiPolygon([union_segments])\n        for poly in union_segments.geoms:\n            exteriors.append(poly.exterior)\n            for inter in poly.interiors:\n                interiors.append(inter)\n\n        results = []\n        for ext in exteriors:\n            if ext.is_ccw:\n                ext.coords = list(ext.coords)[::-1]\n            lines = ext.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        for inter in interiors:\n            if not inter.is_ccw:\n                inter.coords = list(inter.coords)[::-1]\n            lines = inter.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        return self._one_type_line_geom_to_vectors(results)\n\n    def ped_poly_geoms_to_instances(self, ped_geom):\n        # import pdb;pdb.set_trace()\n        ped = ped_geom[0][1]\n        union_segments = ops.unary_union(ped)\n        max_x = self.patch_size[1] / 2\n        max_y = self.patch_size[0] / 2\n        # local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n        local_patch = box(-max_x - 0.2, -max_y - 0.2, max_x + 0.2, max_y + 0.2)\n        exteriors = []\n        interiors = []\n        if union_segments.geom_type != 'MultiPolygon':\n            union_segments = MultiPolygon([union_segments])\n        for poly in union_segments.geoms:\n            exteriors.append(poly.exterior)\n            for inter in poly.interiors:\n                interiors.append(inter)\n\n        results = []\n        for ext in exteriors:\n            if ext.is_ccw:\n                ext.coords = list(ext.coords)[::-1]\n            lines = ext.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        for inter in interiors:\n            if not inter.is_ccw:\n                inter.coords = list(inter.coords)[::-1]\n            lines = inter.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        return self._one_type_line_geom_to_instances(results)\n\n\n    def poly_geoms_to_instances(self, polygon_geom):\n        roads = polygon_geom[0][1]\n        lanes = polygon_geom[1][1]\n        union_roads = ops.unary_union(roads)\n        union_lanes = ops.unary_union(lanes)\n        union_segments = ops.unary_union([union_roads, union_lanes])\n        max_x = self.patch_size[1] / 2\n        max_y = self.patch_size[0] / 2\n        local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n        exteriors = []\n        interiors = []\n        if union_segments.geom_type != 'MultiPolygon':\n            union_segments = MultiPolygon([union_segments])\n        for poly in union_segments.geoms:\n            exteriors.append(poly.exterior)\n            for inter in poly.interiors:\n                interiors.append(inter)\n\n        results = []\n        for ext in exteriors:\n            if ext.is_ccw:\n                ext.coords = list(ext.coords)[::-1]\n            lines = ext.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        for inter in interiors:\n            if not inter.is_ccw:\n                inter.coords = list(inter.coords)[::-1]\n            lines = inter.intersection(local_patch)\n            if isinstance(lines, MultiLineString):\n                lines = ops.linemerge(lines)\n            results.append(lines)\n\n        return self._one_type_line_geom_to_instances(results)\n\n    def line_geoms_to_vectors(self, line_geom):\n        line_vectors_dict = dict()\n        for line_type, a_type_of_lines in line_geom:\n            one_type_vectors = self._one_type_line_geom_to_vectors(a_type_of_lines)\n            line_vectors_dict[line_type] = one_type_vectors\n\n        return line_vectors_dict\n    def line_geoms_to_instances(self, line_geom):\n        line_instances_dict = dict()\n        for line_type, a_type_of_lines in line_geom:\n            one_type_instances = self._one_type_line_geom_to_instances(a_type_of_lines)\n            line_instances_dict[line_type] = one_type_instances\n\n        return line_instances_dict\n\n    def ped_geoms_to_vectors(self, ped_geom):\n        ped_geom = ped_geom[0][1]\n        union_ped = ops.unary_union(ped_geom)\n        if union_ped.geom_type != 'MultiPolygon':\n            union_ped = MultiPolygon([union_ped])\n\n        max_x = self.patch_size[1] / 2\n        max_y = self.patch_size[0] / 2\n        local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n        results = []\n        for ped_poly in union_ped:\n            # rect = ped_poly.minimum_rotated_rectangle\n            ext = ped_poly.exterior\n            if not ext.is_ccw:\n                ext.coords = list(ext.coords)[::-1]\n            lines = ext.intersection(local_patch)\n            results.append(lines)\n\n        return self._one_type_line_geom_to_vectors(results)\n\n    def get_contour_line(self,patch_box,patch_angle,layer_name,location):\n        if layer_name not in self.map_explorer[location].map_api.non_geometric_polygon_layers:\n            raise ValueError('{} is not a polygonal layer'.format(layer_name))\n\n        patch_x = patch_box[0]\n        patch_y = patch_box[1]\n\n        patch = self.map_explorer[location].get_patch_coord(patch_box, patch_angle)\n\n        records = getattr(self.map_explorer[location].map_api, layer_name)\n\n        polygon_list = []\n        if layer_name == 'drivable_area':\n            for record in records:\n                polygons = [self.map_explorer[location].map_api.extract_polygon(polygon_token) for polygon_token in record['polygon_tokens']]\n\n                for polygon in polygons:\n                    new_polygon = polygon.intersection(patch)\n                    if not new_polygon.is_empty:\n                        new_polygon = affinity.rotate(new_polygon, -patch_angle,\n                                                      origin=(patch_x, patch_y), use_radians=False)\n                        new_polygon = affinity.affine_transform(new_polygon,\n                                                                [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                        if new_polygon.geom_type == 'Polygon':\n                            new_polygon = MultiPolygon([new_polygon])\n                        polygon_list.append(new_polygon)\n\n        else:\n            for record in records:\n                polygon = self.map_explorer[location].map_api.extract_polygon(record['polygon_token'])\n\n                if polygon.is_valid:\n                    new_polygon = polygon.intersection(patch)\n                    if not new_polygon.is_empty:\n                        new_polygon = affinity.rotate(new_polygon, -patch_angle,\n                                                      origin=(patch_x, patch_y), use_radians=False)\n                        new_polygon = affinity.affine_transform(new_polygon,\n                                                                [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                        if new_polygon.geom_type == 'Polygon':\n                            new_polygon = MultiPolygon([new_polygon])\n                        polygon_list.append(new_polygon)\n\n        return polygon_list\n\n    def get_divider_line(self,patch_box,patch_angle,layer_name,location):\n        if layer_name not in self.map_explorer[location].map_api.non_geometric_line_layers:\n            raise ValueError(\"{} is not a line layer\".format(layer_name))\n\n        if layer_name == 'traffic_light':\n            return None\n\n        patch_x = patch_box[0]\n        patch_y = patch_box[1]\n\n        patch = self.map_explorer[location].get_patch_coord(patch_box, patch_angle)\n\n        line_list = []\n        records = getattr(self.map_explorer[location].map_api, layer_name)\n        for record in records:\n            line = self.map_explorer[location].map_api.extract_line(record['line_token'])\n            if line.is_empty:  # Skip lines without nodes.\n                continue\n\n            new_line = line.intersection(patch)\n            if not new_line.is_empty:\n                new_line = affinity.rotate(new_line, -patch_angle, origin=(patch_x, patch_y), use_radians=False)\n                new_line = affinity.affine_transform(new_line,\n                                                     [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                line_list.append(new_line)\n\n        return line_list\n\n    def get_ped_crossing_line(self, patch_box, patch_angle, location):\n        patch_x = patch_box[0]\n        patch_y = patch_box[1]\n\n        patch = self.map_explorer[location].get_patch_coord(patch_box, patch_angle)\n        polygon_list = []\n        records = getattr(self.map_explorer[location].map_api, 'ped_crossing')\n        # records = getattr(self.nusc_maps[location], 'ped_crossing')\n        for record in records:\n            polygon = self.map_explorer[location].map_api.extract_polygon(record['polygon_token'])\n            if polygon.is_valid:\n                new_polygon = polygon.intersection(patch)\n                if not new_polygon.is_empty:\n                    new_polygon = affinity.rotate(new_polygon, -patch_angle,\n                                                      origin=(patch_x, patch_y), use_radians=False)\n                    new_polygon = affinity.affine_transform(new_polygon,\n                                                            [1.0, 0.0, 0.0, 1.0, -patch_x, -patch_y])\n                    if new_polygon.geom_type == 'Polygon':\n                        new_polygon = MultiPolygon([new_polygon])\n                    polygon_list.append(new_polygon)\n\n        return polygon_list\n\n    def sample_pts_from_line(self, line):\n        if self.fixed_num < 0:\n            distances = np.arange(0, line.length, self.sample_dist)\n            sampled_points = np.array([list(line.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n        else:\n            # fixed number of points, so distance is line.length / self.fixed_num\n            distances = np.linspace(0, line.length, self.fixed_num)\n            sampled_points = np.array([list(line.interpolate(distance).coords) for distance in distances]).reshape(-1, 2)\n\n            # tmpdistances = np.linspace(0, line.length, 2)\n            # tmpsampled_points = np.array([list(line.interpolate(tmpdistance).coords) for tmpdistance in tmpdistances]).reshape(-1, 2)\n        # import pdb;pdb.set_trace()\n        # if self.normalize:\n        #     sampled_points = sampled_points / np.array([self.patch_size[1], self.patch_size[0]])\n\n        num_valid = len(sampled_points)\n\n        if not self.padding or self.fixed_num > 0:\n            # fixed num sample can return now!\n            return sampled_points, num_valid\n\n        # fixed distance sampling need padding!\n        num_valid = len(sampled_points)\n\n        if self.fixed_num < 0:\n            if num_valid < self.num_samples:\n                padding = np.zeros((self.num_samples - len(sampled_points), 2))\n                sampled_points = np.concatenate([sampled_points, padding], axis=0)\n            else:\n                sampled_points = sampled_points[:self.num_samples, :]\n                num_valid = self.num_samples\n\n            # if self.normalize:\n            #     sampled_points = sampled_points / np.array([self.patch_size[1], self.patch_size[0]])\n            #     num_valid = len(sampled_points)\n\n        return sampled_points, num_valid\n\n\n###############################################################################################################\n###############################################################################################################\n###############################################################################################################\n\nclass v1CustomDetectionConfig:\n    \"\"\" Data class that specifies the detection evaluation settings. \"\"\"\n\n    def __init__(self,\n                 class_range_x: Dict[str, int],\n                 class_range_y: Dict[str, int],\n                 dist_fcn: str,\n                 dist_ths: List[float],\n                 dist_th_tp: float,\n                 min_recall: float,\n                 min_precision: float,\n                 max_boxes_per_sample: int,\n                 mean_ap_weight: int):\n\n        assert set(class_range_x.keys()) == set(DETECTION_NAMES), \"Class count mismatch.\"\n        assert dist_th_tp in dist_ths, \"dist_th_tp must be in set of dist_ths.\"\n\n        self.class_range_x = class_range_x\n        self.class_range_y = class_range_y\n        self.dist_fcn = dist_fcn\n        self.dist_ths = dist_ths\n        self.dist_th_tp = dist_th_tp\n        self.min_recall = min_recall\n        self.min_precision = min_precision\n        self.max_boxes_per_sample = max_boxes_per_sample\n        self.mean_ap_weight = mean_ap_weight\n\n        self.class_names = self.class_range_y.keys()\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.serialize().keys():\n            eq = eq and np.array_equal(getattr(self, key), getattr(other, key))\n        return eq\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'class_range_x': self.class_range_x,\n            'class_range_y': self.class_range_y,\n            'dist_fcn': self.dist_fcn,\n            'dist_ths': self.dist_ths,\n            'dist_th_tp': self.dist_th_tp,\n            'min_recall': self.min_recall,\n            'min_precision': self.min_precision,\n            'max_boxes_per_sample': self.max_boxes_per_sample,\n            'mean_ap_weight': self.mean_ap_weight\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized dictionary. \"\"\"\n        return cls(content['class_range_x'],\n                   content['class_range_y'],\n                   content['dist_fcn'],\n                   content['dist_ths'],\n                   content['dist_th_tp'],\n                   content['min_recall'],\n                   content['min_precision'],\n                   content['max_boxes_per_sample'],\n                   content['mean_ap_weight'])\n\n    @property\n    def dist_fcn_callable(self):\n        \"\"\" Return the distance function corresponding to the dist_fcn string. \"\"\"\n        if self.dist_fcn == 'center_distance':\n            return center_distance\n        else:\n            raise Exception('Error: Unknown distance function %s!' % self.dist_fcn)\n\n@DATASETS.register_module()\nclass VADCustomNuScenesDataset(NuScenesDataset):\n    r\"\"\"Custom NuScenes Dataset.\n    \"\"\"\n    MAPCLASSES = ('divider',)\n    def __init__(\n        self,\n        queue_length=4,\n        bev_size=(200, 200),\n        overlap_test=False,\n        with_attr=True,\n        fut_ts=6,\n        pc_range=[-51.2, -51.2, -5.0, 51.2, 51.2, 3.0],\n        map_classes=None,\n        map_ann_file=None,\n        map_fixed_ptsnum_per_line=-1,\n        map_eval_use_same_gt_sample_num_flag=False,\n        padding_value=-10000,\n        use_pkl_result=False,\n        custom_eval_version='vad_nusc_detection_cvpr_2019',\n        *args,\n        **kwargs\n    ):\n        super().__init__(*args, **kwargs)\n        self.queue_length = queue_length\n        self.overlap_test = overlap_test\n        self.bev_size = bev_size\n        self.with_attr = with_attr\n        self.fut_ts = fut_ts\n        self.use_pkl_result = use_pkl_result\n\n        self.custom_eval_version = custom_eval_version\n        # Check if config exists.\n        this_dir = os.path.dirname(os.path.abspath(__file__))\n        cfg_path = os.path.join(this_dir, '%s.json' % self.custom_eval_version)\n        assert os.path.exists(cfg_path), \\\n            'Requested unknown configuration {}'.format(self.custom_eval_version)\n        # Load config file and deserialize it.\n        with open(cfg_path, 'r') as f:\n            data = json.load(f)\n        self.custom_eval_detection_configs = v1CustomDetectionConfig.deserialize(data)\n\n        self.map_ann_file = map_ann_file\n        self.MAPCLASSES = self.get_map_classes(map_classes)\n        self.NUM_MAPCLASSES = len(self.MAPCLASSES)\n        self.pc_range = pc_range\n        patch_h = pc_range[4]-pc_range[1]\n        patch_w = pc_range[3]-pc_range[0]\n        self.patch_size = (patch_h, patch_w)\n        self.padding_value = padding_value\n        self.fixed_num = map_fixed_ptsnum_per_line\n        self.eval_use_same_gt_sample_num_flag = map_eval_use_same_gt_sample_num_flag\n        self.vector_map = VectorizedLocalMap(kwargs['data_root'], \n                            patch_size=self.patch_size, map_classes=self.MAPCLASSES, \n                            fixed_ptsnum_per_line=map_fixed_ptsnum_per_line,\n                            padding_value=self.padding_value)\n        self.is_vis_on_test = True\n\n    @classmethod\n    def get_map_classes(cls, map_classes=None):\n        \"\"\"Get class names of current dataset.\n\n        Args:\n            classes (Sequence[str] | str | None): If classes is None, use\n                default CLASSES defined by builtin dataset. If classes is a\n                string, take it as a file name. The file contains the name of\n                classes where each line contains one class name. If classes is\n                a tuple or list, override the CLASSES defined by the dataset.\n\n        Return:\n            list[str]: A list of class names.\n        \"\"\"\n        if map_classes is None:\n            return cls.MAPCLASSES\n\n        if isinstance(map_classes, str):\n            # take it as a file path\n            class_names = mmcv.list_from_file(map_classes)\n        elif isinstance(map_classes, (tuple, list)):\n            class_names = map_classes\n        else:\n            raise ValueError(f'Unsupported type {type(map_classes)} of map classes.')\n\n        return class_names\n\n    def vectormap_pipeline(self, example, input_dict):\n        '''\n        `example` type: <class 'dict'>\n            keys: 'img_metas', 'gt_bboxes_3d', 'gt_labels_3d', 'img';\n                  all keys type is 'DataContainer';\n                  'img_metas' cpu_only=True, type is dict, others are false;\n                  'gt_labels_3d' shape torch.size([num_samples]), stack=False,\n                                padding_value=0, cpu_only=False\n                  'gt_bboxes_3d': stack=False, cpu_only=True\n        '''\n        # import pdb;pdb.set_trace()\n        lidar2ego = np.eye(4)\n        lidar2ego[:3,:3] = Quaternion(input_dict['lidar2ego_rotation']).rotation_matrix\n        lidar2ego[:3, 3] = input_dict['lidar2ego_translation']\n        ego2global = np.eye(4)\n        ego2global[:3,:3] = Quaternion(input_dict['ego2global_rotation']).rotation_matrix\n        ego2global[:3, 3] = input_dict['ego2global_translation']\n\n        lidar2global = ego2global @ lidar2ego\n\n        lidar2global_translation = list(lidar2global[:3,3])\n        lidar2global_rotation = list(Quaternion(matrix=lidar2global).q)\n\n        location = input_dict['map_location']\n        ego2global_translation = input_dict['ego2global_translation']\n        ego2global_rotation = input_dict['ego2global_rotation']\n        anns_results = self.vector_map.gen_vectorized_samples(\n            location, lidar2global_translation, lidar2global_rotation\n        )\n        \n        '''\n        anns_results, type: dict\n            'gt_vecs_pts_loc': list[num_vecs], vec with num_points*2 coordinates\n            'gt_vecs_pts_num': list[num_vecs], vec with num_points\n            'gt_vecs_label': list[num_vecs], vec with cls index\n        '''\n        gt_vecs_label = to_tensor(anns_results['gt_vecs_label'])\n        if isinstance(anns_results['gt_vecs_pts_loc'], LiDARInstanceLines):\n            gt_vecs_pts_loc = anns_results['gt_vecs_pts_loc']\n        else:\n            gt_vecs_pts_loc = to_tensor(anns_results['gt_vecs_pts_loc'])\n            try:\n                gt_vecs_pts_loc = gt_vecs_pts_loc.flatten(1).to(dtype=torch.float32)\n            except:\n                # empty tensor, will be passed in train, \n                # but we preserve it for test\n                gt_vecs_pts_loc = gt_vecs_pts_loc\n\n        example['map_gt_labels_3d'] = DC(gt_vecs_label, cpu_only=False)\n        example['map_gt_bboxes_3d'] = DC(gt_vecs_pts_loc, cpu_only=True)\n\n        return example\n\n    def prepare_train_data(self, index):\n        \"\"\"\n        Training data preparation.\n        Args:\n            index (int): Index for accessing the target data.\n        Returns:\n            dict: Training data dict of the corresponding index.\n        \"\"\"\n        data_queue = []\n\n        # temporal aug\n        prev_indexs_list = list(range(index-self.queue_length, index))\n        random.shuffle(prev_indexs_list)\n        prev_indexs_list = sorted(prev_indexs_list[1:], reverse=True)\n        ##\n\n        input_dict = self.get_data_info(index)\n        if input_dict is None:\n            return None\n        frame_idx = input_dict['frame_idx']\n        scene_token = input_dict['scene_token']\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        example = self.vectormap_pipeline(example,input_dict)\n        if self.filter_empty_gt and \\\n                ((example is None or ~(example['gt_labels_3d']._data != -1).any()) or \\\n                    (example is None or ~(example['map_gt_labels_3d']._data != -1).any())):\n            return None\n        data_queue.insert(0, example)\n        for i in prev_indexs_list:\n            i = max(0, i)\n            input_dict = self.get_data_info(i)\n            if input_dict is None:\n                return None\n            if input_dict['frame_idx'] < frame_idx and input_dict['scene_token'] == scene_token:\n                self.pre_pipeline(input_dict)\n                example = self.pipeline(input_dict)\n                example = self.vectormap_pipeline(example,input_dict)\n                if self.filter_empty_gt and \\\n                        (example is None or ~(example['gt_labels_3d']._data != -1).any()) and \\\n                            (example is None or ~(example['map_gt_labels_3d']._data != -1).any()):\n                    return None\n                frame_idx = input_dict['frame_idx']\n            data_queue.insert(0, copy.deepcopy(example))\n        return self.union2one(data_queue)\n\n    def prepare_test_data(self, index):\n        \"\"\"Prepare data for testing.\n\n        Args:\n            index (int): Index for accessing the target data.\n\n        Returns:\n            dict: Testing data dict of the corresponding index.\n        \"\"\"\n        input_dict = self.get_data_info(index)\n        self.pre_pipeline(input_dict)\n        example = self.pipeline(input_dict)\n        if self.is_vis_on_test:\n            example = self.vectormap_pipeline(example, input_dict)\n        return example\n\n    def union2one(self, queue):\n        \"\"\"\n        convert sample queue into one single sample.\n        \"\"\"\n        imgs_list = [each['img'].data for each in queue]\n        metas_map = {}\n        prev_pos = None\n        prev_angle = None\n        for i, each in enumerate(queue):\n            metas_map[i] = each['img_metas'].data\n            if i == 0:\n                metas_map[i]['prev_bev'] = False\n                prev_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                prev_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] = 0\n                metas_map[i]['can_bus'][-1] = 0\n            else:\n                metas_map[i]['prev_bev'] = True\n                tmp_pos = copy.deepcopy(metas_map[i]['can_bus'][:3])\n                tmp_angle = copy.deepcopy(metas_map[i]['can_bus'][-1])\n                metas_map[i]['can_bus'][:3] -= prev_pos\n                metas_map[i]['can_bus'][-1] -= prev_angle\n                prev_pos = copy.deepcopy(tmp_pos)\n                prev_angle = copy.deepcopy(tmp_angle)\n\n        queue[-1]['img'] = DC(torch.stack(imgs_list),\n                              cpu_only=False, stack=True)\n        queue[-1]['img_metas'] = DC(metas_map, cpu_only=True)\n        queue = queue[-1]\n        return queue\n\n    def get_ann_info(self, index):\n        \"\"\"Get annotation info according to the given index.\n\n        Args:\n            index (int): Index of the annotation data to get.\n\n        Returns:\n            dict: Annotation information consists of the following keys:\n\n                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \\\n                    3D ground truth bboxes\n                - gt_labels_3d (np.ndarray): Labels of ground truths.\n                - gt_names (list[str]): Class names of ground truths.\n        \"\"\"\n        info = self.data_infos[index]\n        # filter out bbox containing no points\n        if self.use_valid_flag:\n            mask = info['valid_flag']\n        else:\n            mask = info['num_lidar_pts'] > 0\n        gt_bboxes_3d = info['gt_boxes'][mask]\n        gt_names_3d = info['gt_names'][mask]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info['gt_velocity'][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n        \n        if self.with_attr:\n            gt_fut_trajs = info['gt_agent_fut_trajs'][mask]\n            gt_fut_masks = info['gt_agent_fut_masks'][mask]\n            gt_fut_goal = info['gt_agent_fut_goal'][mask]\n            gt_lcf_feat = info['gt_agent_lcf_feat'][mask]\n            gt_fut_yaw = info['gt_agent_fut_yaw'][mask]\n            attr_labels = np.concatenate(\n                [gt_fut_trajs, gt_fut_masks, gt_fut_goal[..., None], gt_lcf_feat, gt_fut_yaw], axis=-1\n            ).astype(np.float32)\n\n        # the nuscenes box center is [0.5, 0.5, 0.5], we change it to be\n        # the same as KITTI (0.5, 0.5, 0)\n        gt_bboxes_3d = LiDARInstance3DBoxes(\n            gt_bboxes_3d,\n            box_dim=gt_bboxes_3d.shape[-1],\n            origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)\n        \n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n            attr_labels=attr_labels)\n\n        return anns_results\n\n    def get_data_info(self, index):\n        \"\"\"Get data info according to the given index.\n\n        Args:\n            index (int): Index of the sample data to get.\n\n        Returns:\n            dict: Data information that will be passed to the data \\\n                preprocessing pipelines. It includes the following keys:\n\n                - sample_idx (str): Sample index.\n                - pts_filename (str): Filename of point clouds.\n                - sweeps (list[dict]): Infos of sweeps.\n                - timestamp (float): Sample timestamp.\n                - img_filename (str, optional): Image filename.\n                - lidar2img (list[np.ndarray], optional): Transformations \\\n                    from lidar to different cameras.\n                - ann_info (dict): Annotation info.\n        \"\"\"\n        info = self.data_infos[index]\n        # standard protocal modified from SECOND.Pytorch\n        input_dict = dict(\n            sample_idx=info['token'],\n            #pts_filename=info['lidar_path'],\n            #sweeps=info['sweeps'],\n            ego2global_translation=info['ego2global_translation'],\n            ego2global_rotation=info['ego2global_rotation'],\n            lidar2ego_translation=info['lidar2ego_translation'],\n            lidar2ego_rotation=info['lidar2ego_rotation'],\n            prev_idx=info['prev'],\n            next_idx=info['next'],\n            scene_token=info['scene_token'],\n            can_bus=info['can_bus'],\n            frame_idx=info['frame_idx'],\n            timestamp=info['timestamp'] / 1e6,\n            fut_valid_flag=info['fut_valid_flag'],\n            map_location=info['map_location'],\n            ego_his_trajs=info['gt_ego_his_trajs'],\n            ego_fut_trajs=info['gt_ego_fut_trajs'],\n            ego_fut_masks=info['gt_ego_fut_masks'],\n            ego_fut_cmd=info['gt_ego_fut_cmd'],\n            ego_lcf_feat=info['gt_ego_lcf_feat']\n        )\n        # lidar to ego transform\n        lidar2ego = np.eye(4).astype(np.float32)\n        lidar2ego[:3, :3] = Quaternion(info[\"lidar2ego_rotation\"]).rotation_matrix\n        lidar2ego[:3, 3] = info[\"lidar2ego_translation\"]\n        input_dict[\"lidar2ego\"] = lidar2ego\n\n        if self.modality['use_camera']:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsics = []\n            input_dict[\"camera2ego\"] = []\n            input_dict[\"camera_intrinsics\"] = []\n            for cam_type, cam_info in info['cams'].items():\n                image_paths.append(cam_info['data_path'])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info['sensor2lidar_rotation'])\n                lidar2cam_t = cam_info[\n                    'sensor2lidar_translation'] @ lidar2cam_r.T\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = cam_info['cam_intrinsic']\n                viewpad = np.eye(4)\n                viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = (viewpad @ lidar2cam_rt.T)\n                lidar2img_rts.append(lidar2img_rt)\n\n                cam_intrinsics.append(viewpad)\n                lidar2cam_rts.append(lidar2cam_rt.T)\n            \n                # camera to ego transform\n                camera2ego = np.eye(4).astype(np.float32)\n                camera2ego[:3, :3] = Quaternion(\n                    cam_info[\"sensor2ego_rotation\"]\n                ).rotation_matrix\n                camera2ego[:3, 3] = cam_info[\"sensor2ego_translation\"]\n                input_dict[\"camera2ego\"].append(camera2ego)\n                # camera intrinsics\n                camera_intrinsics = np.eye(4).astype(np.float32)\n                camera_intrinsics[:3, :3] = cam_info[\"cam_intrinsic\"]\n                input_dict[\"camera_intrinsics\"].append(camera_intrinsics)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    cam_intrinsic=cam_intrinsics,\n                    lidar2cam=lidar2cam_rts,\n                ))\n\n        # NOTE: now we load gt in test_mode for evaluating\n        # if not self.test_mode:\n        #     annos = self.get_ann_info(index)\n        #     input_dict['ann_info'] = annos\n\n        annos = self.get_ann_info(index)\n        input_dict['ann_info'] = annos\n\n        rotation = Quaternion(input_dict['ego2global_rotation'])\n        translation = input_dict['ego2global_translation']\n        can_bus = input_dict['can_bus']\n        can_bus[:3] = translation\n        can_bus[3:7] = rotation\n        patch_angle = quaternion_yaw(rotation) / np.pi * 180\n        if patch_angle < 0:\n            patch_angle += 360\n        can_bus[-2] = patch_angle / 180 * np.pi\n        can_bus[-1] = patch_angle\n\n        lidar2ego = np.eye(4)\n        lidar2ego[:3,:3] = Quaternion(input_dict['lidar2ego_rotation']).rotation_matrix\n        lidar2ego[:3, 3] = input_dict['lidar2ego_translation']\n        ego2global = np.eye(4)\n        ego2global[:3,:3] = Quaternion(input_dict['ego2global_rotation']).rotation_matrix\n        ego2global[:3, 3] = input_dict['ego2global_translation']\n        lidar2global = ego2global @ lidar2ego\n        input_dict['lidar2global'] = lidar2global\n\n        return input_dict\n\n    def __getitem__(self, idx):\n        \"\"\"Get item from infos according to the given index.\n        Returns:\n            dict: Data dictionary of the corresponding index.\n        \"\"\"\n        if self.test_mode:\n            return self.prepare_test_data(idx)\n        while True:\n\n            data = self.prepare_train_data(idx)\n            if data is None:\n                idx = self._rand_another(idx)\n                continue\n            return data\n\n    def _format_gt(self):\n        gt_annos = []\n        print('Start to convert gt map format...')\n        # assert self.map_ann_file is not None\n        if (not os.path.exists(self.map_ann_file)) :\n            dataset_length = len(self)\n            prog_bar = mmcv.ProgressBar(dataset_length)\n            mapped_class_names = self.MAPCLASSES\n            for sample_id in range(dataset_length):\n                sample_token = self.data_infos[sample_id]['token']\n                gt_anno = {}\n                gt_anno['sample_token'] = sample_token\n                # gt_sample_annos = []\n                gt_sample_dict = {}\n                gt_sample_dict = self.vectormap_pipeline(gt_sample_dict, self.data_infos[sample_id])\n                gt_labels = gt_sample_dict['map_gt_labels_3d'].data.numpy()\n                gt_vecs = gt_sample_dict['map_gt_bboxes_3d'].data.instance_list\n                gt_vec_list = []\n                for i, (gt_label, gt_vec) in enumerate(zip(gt_labels, gt_vecs)):\n                    name = mapped_class_names[gt_label]\n                    anno = dict(\n                        pts=np.array(list(gt_vec.coords)),\n                        pts_num=len(list(gt_vec.coords)),\n                        cls_name=name,\n                        type=gt_label,\n                    )\n                    gt_vec_list.append(anno)\n                gt_anno['vectors']=gt_vec_list\n                gt_annos.append(gt_anno)\n\n                prog_bar.update()\n            nusc_submissions = {\n                'GTs': gt_annos\n            }\n            print('\\n GT anns writes to', self.map_ann_file)\n            dump(nusc_submissions, self.map_ann_file)\n        else:\n            print(f'{self.map_ann_file} exist, not update')\n\n    def _format_bbox(self, results, jsonfile_prefix=None, score_thresh=0.2):\n        \"\"\"Convert the results to the standard format.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str): The prefix of the output jsonfile.\n                You can specify the output directory/filename by\n                modifying the jsonfile_prefix. Default: None.\n\n        Returns:\n            str: Path of the output json file.\n        \"\"\"\n        nusc_annos = {}\n        det_mapped_class_names = self.CLASSES\n\n        # assert self.map_ann_file is not None\n        map_pred_annos = {}\n        map_mapped_class_names = self.MAPCLASSES\n\n        plan_annos = {}\n\n        print('Start to convert detection format...')\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(det)\n            sample_token = self.data_infos[sample_id]['token']\n\n            plan_annos[sample_token] = [det['ego_fut_preds'], det['ego_fut_cmd']]\n\n            boxes = lidar_nusc_box_to_global(self.data_infos[sample_id], boxes,\n                                             det_mapped_class_names,\n                                             self.custom_eval_detection_configs,\n                                             self.eval_version)\n            for i, box in enumerate(boxes):\n                if box.score < score_thresh:\n                    continue\n                name = det_mapped_class_names[box.label]\n                if np.sqrt(box.velocity[0]**2 + box.velocity[1]**2) > 0.2:\n                    if name in [\n                            'car',\n                            'construction_vehicle',\n                            'bus',\n                            'truck',\n                            'trailer',\n                    ]:\n                        attr = 'vehicle.moving'\n                    elif name in ['bicycle', 'motorcycle']:\n                        attr = 'cycle.with_rider'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n                else:\n                    if name in ['pedestrian']:\n                        attr = 'pedestrian.standing'\n                    elif name in ['bus']:\n                        attr = 'vehicle.stopped'\n                    else:\n                        attr = NuScenesDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                    detection_name=name,\n                    detection_score=box.score,\n                    attribute_name=attr,\n                    fut_traj=box.fut_trajs.tolist())\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n\n\n            map_pred_anno = {}\n            vecs = output_to_vecs(det)\n            sample_token = self.data_infos[sample_id]['token']\n            map_pred_anno['sample_token'] = sample_token\n            pred_vec_list=[]\n            for i, vec in enumerate(vecs):\n                name = map_mapped_class_names[vec['label']]\n                anno = dict(\n                    # sample_token=sample_token,\n                    pts=vec['pts'],\n                    pts_num=len(vec['pts']),\n                    cls_name=name,\n                    type=vec['label'],\n                    confidence_level=vec['score'])\n                pred_vec_list.append(anno)\n                # annos.append(nusc_anno)\n            # nusc_annos[sample_token] = annos\n            map_pred_anno['vectors'] = pred_vec_list\n            map_pred_annos[sample_token] = map_pred_anno\n\n        if not os.path.exists(self.map_ann_file):\n            self._format_gt()\n        else:\n            print(f'{self.map_ann_file} exist, not update')\n        # with open(self.map_ann_file,'r') as f:\n        #     GT_anns = json.load(f)\n        # gt_annos = GT_anns['GTs']\n\n        nusc_submissions = {\n            'meta': self.modality,\n            'results': nusc_annos,\n            'map_results': map_pred_annos,\n            'plan_results': plan_annos\n            # 'GTs': gt_annos\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        if self.use_pkl_result:\n            res_path = osp.join(jsonfile_prefix, 'results_nusc.pkl')\n        else:\n            res_path = osp.join(jsonfile_prefix, 'results_nusc.json')\n        print('Results writes to', res_path)\n        dump(nusc_submissions, res_path)\n        return res_path\n\n    def format_results(self, results, jsonfile_prefix=None):\n        \"\"\"Format the results to json (standard format for COCO evaluation).\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n\n        Returns:\n            tuple: Returns (result_files, tmp_dir), where `result_files` is a \\\n                dict containing the json filepaths, `tmp_dir` is the temporal \\\n                directory created for saving json files when \\\n                `jsonfile_prefix` is not specified.\n        \"\"\"\n        if isinstance(results, dict):\n            # print(f'results must be a list, but get dict, keys={results.keys()}')\n            # assert isinstance(results, list)\n            results = results['bbox_results']\n        assert isinstance(results, list)\n        # assert len(results) == len(self), (\n        #     'The length of results is not equal to the dataset len: {} != {}'.\n        #     format(len(results), len(self)))\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, 'results')\n        else:\n            tmp_dir = None\n\n        # currently the output prediction results could be in two formats\n        # 1. list of dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...)\n        # 2. list of dict('pts_bbox' or 'img_bbox':\n        #     dict('boxes_3d': ..., 'scores_3d': ..., 'labels_3d': ...))\n        # this is a workaround to enable evaluation of both formats on nuScenes\n        # refer to https://github.com/open-mmlab/mmdetection3d/issues/449\n        if not ('pts_bbox' in results[0] or 'img_bbox' in results[0]):\n            result_files = self._format_bbox(results, jsonfile_prefix)\n        else:\n            # should take the inner dict out of 'pts_bbox' or 'img_bbox' dict\n            result_files = dict()\n            for name in results[0]:\n                if name == 'metric_results':\n                    continue\n                print(f'\\nFormating bboxes of {name}')\n                results_ = [out[name] for out in results]\n                tmp_file_ = osp.join(jsonfile_prefix, name)\n                result_files.update(\n                    {name: self._format_bbox(results_, tmp_file_)})\n        return result_files, tmp_dir\n\n    def _evaluate_single(self,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         map_metric='chamfer',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        detail = dict()\n        from nuscenes import NuScenes\n        self.nusc = NuScenes(version=self.version, dataroot=self.data_root,\n                             verbose=False)\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        self.nusc_eval = NuScenesEval_custom(\n            self.nusc,\n            config=self.custom_eval_detection_configs,\n            result_path=result_path,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False,\n            overlap_test=self.overlap_test,\n            data_infos=self.data_infos\n        )\n        self.nusc_eval.main(plot_examples=0, render_curves=False)\n        # record metrics\n        metrics = load(osp.join(output_dir, 'metrics_summary.json'))\n        metric_prefix = f'{result_name}_NuScenes'\n        for name in self.CLASSES:\n            for k, v in metrics['label_aps'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_AP_dist_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['label_tp_errors'][name].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}_{}'.format(metric_prefix, name, k)] = val\n            for k, v in metrics['tp_errors'].items():\n                val = float('{:.4f}'.format(v))\n                detail['{}/{}'.format(metric_prefix,\n                                      self.ErrNameMapping[k])] = val\n        detail['{}/NDS'.format(metric_prefix)] = metrics['nd_score']\n        detail['{}/mAP'.format(metric_prefix)] = metrics['mean_ap']\n\n\n        from mmcv.datasets.map_utils.mean_ap import eval_map\n        from mmcv.datasets.map_utils.mean_ap import format_res_gt_by_classes\n        result_path = osp.abspath(result_path)\n        \n        print('Formating results & gts by classes')\n        pred_results = load(result_path)\n        map_results = pred_results['map_results']\n        gt_anns = load(self.map_ann_file)\n        map_annotations = gt_anns['GTs']\n        cls_gens, cls_gts = format_res_gt_by_classes(result_path,\n                                                     map_results,\n                                                     map_annotations,\n                                                     cls_names=self.MAPCLASSES,\n                                                     num_pred_pts_per_instance=self.fixed_num,\n                                                     eval_use_same_gt_sample_num_flag=self.eval_use_same_gt_sample_num_flag,\n                                                     pc_range=self.pc_range)\n        map_metrics = map_metric if isinstance(map_metric, list) else [map_metric]\n        allowed_metrics = ['chamfer', 'iou']\n        for metric in map_metrics:\n            if metric not in allowed_metrics:\n                raise KeyError(f'metric {metric} is not supported')\n        for metric in map_metrics:\n            print('-*'*10+f'use metric:{metric}'+'-*'*10)\n            if metric == 'chamfer':\n                thresholds = [0.5,1.0,1.5]\n            elif metric == 'iou':\n                thresholds= np.linspace(.5, 0.95, int(np.round((0.95 - .5) / .05)) + 1, endpoint=True)\n            cls_aps = np.zeros((len(thresholds),self.NUM_MAPCLASSES))\n            for i, thr in enumerate(thresholds):\n                print('-*'*10+f'threshhold:{thr}'+'-*'*10)\n                mAP, cls_ap = eval_map(\n                                map_results,\n                                map_annotations,\n                                cls_gens,\n                                cls_gts,\n                                threshold=thr,\n                                cls_names=self.MAPCLASSES,\n                                logger=logger,\n                                num_pred_pts_per_instance=self.fixed_num,\n                                pc_range=self.pc_range,\n                                metric=metric)\n                for j in range(self.NUM_MAPCLASSES):\n                    cls_aps[i, j] = cls_ap[j]['ap']\n            for i, name in enumerate(self.MAPCLASSES):\n                print('{}: {}'.format(name, cls_aps.mean(0)[i]))\n                detail['NuscMap_{}/{}_AP'.format(metric,name)] =  cls_aps.mean(0)[i]\n            print('map: {}'.format(cls_aps.mean(0).mean()))\n            detail['NuscMap_{}/mAP'.format(metric)] = cls_aps.mean(0).mean()\n            for i, name in enumerate(self.MAPCLASSES):\n                for j, thr in enumerate(thresholds):\n                    if metric == 'chamfer':\n                        detail['NuscMap_{}/{}_AP_thr_{}'.format(metric,name,thr)]=cls_aps[j][i]\n                    elif metric == 'iou':\n                        if thr == 0.5 or thr == 0.75:\n                            detail['NuscMap_{}/{}_AP_thr_{}'.format(metric,name,thr)]=cls_aps[j][i]\n\n        return detail\n    \n    def evaluate(self,\n                 results,\n                 metric='bbox',\n                 map_metric='chamfer',\n                 logger=None,\n                 jsonfile_prefix=None,\n                 result_names=['pts_bbox'],\n                 show=False,\n                 out_dir=None,\n                 pipeline=None):\n        \"\"\"Evaluation in nuScenes protocol.\n\n        Args:\n            results (list[dict]): Testing results of the dataset.\n            metric (str | list[str]): Metrics to be evaluated.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            jsonfile_prefix (str | None): The prefix of json files. It includes\n                the file path and the prefix of filename, e.g., \"a/b/prefix\".\n                If not specified, a temp file will be created. Default: None.\n            show (bool): Whether to visualize.\n                Default: False.\n            out_dir (str): Path to save the visualization results.\n                Default: None.\n            pipeline (list[dict], optional): raw data loading for showing.\n                Default: None.\n\n        Returns:\n            dict[str, float]: Results of each evaluation metric.\n        \"\"\"\n        result_metric_names = ['EPA', 'ADE', 'FDE', 'MR']\n        motion_cls_names = ['car', 'pedestrian']\n        motion_metric_names = ['gt', 'cnt_ade', 'cnt_fde', 'hit',\n                               'fp', 'ADE', 'FDE', 'MR']\n        all_metric_dict = {}\n        for met in motion_metric_names:\n            for cls in motion_cls_names:\n                all_metric_dict[met+'_'+cls] = 0.0\n        result_dict = {}\n        for met in result_metric_names:\n            for cls in motion_cls_names:\n                result_dict[met+'_'+cls] = 0.0\n        \n        alpha = 0.5\n\n        for i in range(len(results)):\n            for key in all_metric_dict.keys():\n                all_metric_dict[key] += results[i]['metric_results'][key]\n        \n        for cls in motion_cls_names:\n            result_dict['EPA_'+cls] = (all_metric_dict['hit_'+cls] - \\\n                 alpha * all_metric_dict['fp_'+cls]) / all_metric_dict['gt_'+cls]\n            result_dict['ADE_'+cls] = all_metric_dict['ADE_'+cls] / all_metric_dict['cnt_ade_'+cls]\n            result_dict['FDE_'+cls] = all_metric_dict['FDE_'+cls] / all_metric_dict['cnt_fde_'+cls]\n            result_dict['MR_'+cls] = all_metric_dict['MR_'+cls] / all_metric_dict['cnt_fde_'+cls]\n        \n        print('\\n')\n        print('-------------- Motion Prediction --------------')\n        for k, v in result_dict.items():\n            print(f'{k}: {v}')\n\n        # NOTE: print planning metric\n        print('\\n')\n        print('-------------- Planning --------------')\n        metric_dict = None\n        num_valid = 0\n        for res in results:\n            if res['metric_results']['fut_valid_flag']:\n                num_valid += 1\n            else:\n                continue\n            if metric_dict is None:\n                metric_dict = copy.deepcopy(res['metric_results'])\n            else:\n                for k in res['metric_results'].keys():\n                    metric_dict[k] += res['metric_results'][k]\n        \n        for k in metric_dict:\n            metric_dict[k] = metric_dict[k] / num_valid\n            print(\"{}:{}\".format(k, metric_dict[k]))\n\n        result_files, tmp_dir = self.format_results(results, jsonfile_prefix)\n\n        if isinstance(result_files, dict):\n            results_dict = dict()\n            for name in result_names:\n                print('Evaluating bboxes of {}'.format(name))\n                ret_dict = self._evaluate_single(result_files[name], metric=metric, map_metric=map_metric)\n            results_dict.update(ret_dict)\n        elif isinstance(result_files, str):\n            results_dict = self._evaluate_single(result_files, metric=metric, map_metric=map_metric)\n\n        if tmp_dir is not None:\n            tmp_dir.cleanup()\n\n        if show:\n            self.show(results, out_dir, pipeline=pipeline)\n        return results_dict\n\ndef output_to_nusc_box(detection):\n    \"\"\"Convert the output to the box class in the nuScenes.\n\n    Args:\n        detection (dict): Detection results.\n\n            - boxes_3d (:obj:`BaseInstance3DBoxes`): Detection bbox.\n            - scores_3d (torch.Tensor): Detection scores.\n            - labels_3d (torch.Tensor): Predicted box labels.\n\n    Returns:\n        list[:obj:`NuScenesBox`]: List of standard NuScenesBoxes.\n    \"\"\"\n    box3d = detection['boxes_3d']\n    scores = detection['scores_3d'].numpy()\n    labels = detection['labels_3d'].numpy()\n    trajs = detection['trajs_3d'].numpy()\n\n\n    box_gravity_center = box3d.gravity_center.numpy()\n    box_dims = box3d.dims.numpy()\n    box_yaw = box3d.yaw.numpy()\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        velocity = (*box3d.tensor[i, 7:9], 0.0)\n        # velo_val = np.linalg.norm(box3d[i, 7:9])\n        # velo_ori = box3d[i, 6]\n        # velocity = (\n        # velo_val * np.cos(velo_ori), velo_val * np.sin(velo_ori), 0.0)\n        box = CustomNuscenesBox(\n            center=box_gravity_center[i],\n            size=box_dims[i],\n            orientation=quat,\n            fut_trajs=trajs[i],\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity)\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(info,\n                             boxes,\n                             classes,\n                             eval_configs,\n                             eval_version='detection_cvpr_2019'):\n    \"\"\"Convert the box from ego to global coordinate.\n\n    Args:\n        info (dict): Info for a specific sample data, including the\n            calibration information.\n        boxes (list[:obj:`NuScenesBox`]): List of predicted NuScenesBoxes.\n        classes (list[str]): Mapped classes in the evaluation.\n        eval_configs (object): Evaluation configuration object.\n        eval_version (str): Evaluation version.\n            Default: 'detection_cvpr_2019'\n\n    Returns:\n        list: List of standard NuScenesBoxes in the global\n            coordinate.\n    \"\"\"\n    box_list = []\n    for box in boxes:\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info['lidar2ego_rotation']))\n        box.translate(np.array(info['lidar2ego_translation']))\n        # filter det in ego.\n        cls_range_x_map = eval_configs.class_range_x\n        cls_range_y_map = eval_configs.class_range_y\n        x_distance, y_distance = box.center[0], box.center[1]\n        det_range_x = cls_range_x_map[classes[box.label]]\n        det_range_y = cls_range_y_map[classes[box.label]]\n        if abs(x_distance) > det_range_x or abs(y_distance) > det_range_y:\n            continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info['ego2global_rotation']))\n        box.translate(np.array(info['ego2global_translation']))\n        box_list.append(box)\n    return box_list\n\ndef output_to_vecs(detection):\n    box3d = detection['map_boxes_3d'].numpy()\n    scores = detection['map_scores_3d'].numpy()\n    labels = detection['map_labels_3d'].numpy()\n    pts = detection['map_pts_3d'].numpy()\n\n    vec_list = []\n    # import pdb;pdb.set_trace()\n    for i in range(box3d.shape[0]):\n        vec = dict(\n            bbox = box3d[i], # xyxy\n            label=labels[i],\n            score=scores[i],\n            pts=pts[i],\n        )\n        vec_list.append(vec)\n    return vec_list"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/nuscnes_eval.py",
    "content": "import argparse\nimport copy\nimport json\nimport os\nimport time\nfrom typing import Tuple, Dict, Any\nimport torch\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.detection.data_classes import DetectionConfig\nfrom nuscenes.eval.detection.evaluate import NuScenesEval\nfrom pyquaternion import Quaternion\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.detection.data_classes import DetectionBox\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.tracking.data_classes import TrackingBox\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import points_in_box\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.common.loaders import load_prediction, add_center_dist, filter_eval_boxes\nimport tqdm\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nfrom torchvision.transforms.functional import rotate\nimport pycocotools.mask as mask_util\n# from projects.mmdet3d_plugin.models.utils.visual import save_tensor\nfrom torchvision.transforms.functional import rotate\nimport cv2\nimport argparse\nimport json\nimport os\nimport random\nimport time\nfrom typing import Tuple, Dict, Any\n\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import load_prediction, load_gt, add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import accumulate, calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom mmcv.core.bbox import BboxOverlaps3D\nfrom IPython import embed\nimport json\nfrom typing import Any\n\nimport numpy as np\nfrom matplotlib import pyplot as plt\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.render import setup_axis\nfrom nuscenes.eval.common.utils import boxes_to_sensor\nfrom nuscenes.eval.detection.constants import TP_METRICS, DETECTION_NAMES, DETECTION_COLORS, TP_METRICS_UNITS, \\\n    PRETTY_DETECTION_NAMES, PRETTY_TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionMetrics, DetectionMetricData, DetectionMetricDataList\nfrom nuscenes.utils.data_classes import LidarPointCloud\nfrom nuscenes.utils.geometry_utils import view_points\n\n\n\nAxis = Any\n\ndef class_tp_curve(md_list: DetectionMetricDataList,\n                   metrics: DetectionMetrics,\n                   detection_name: str,\n                   min_recall: float,\n                   dist_th_tp: float,\n                   savepath: str = None,\n                   ax: Axis = None) -> None:\n    \"\"\"\n    Plot the true positive curve for the specified class.\n    :param md_list: DetectionMetricDataList instance.\n    :param metrics: DetectionMetrics instance.\n    :param detection_name:\n    :param min_recall: Minimum recall value.\n    :param dist_th_tp: The distance threshold used to determine matches.\n    :param savepath: If given, saves the the rendering here instead of displaying.\n    :param ax: Axes onto which to render.\n    \"\"\"\n    # Get metric data for given detection class with tp distance threshold.\n\n    md = md_list[(detection_name, dist_th_tp)]\n    min_recall_ind = round(100 * min_recall)\n    if min_recall_ind <= md.max_recall_ind:\n        # For traffic_cone and barrier only a subset of the metrics are plotted.\n        rel_metrics = [m for m in TP_METRICS if not np.isnan(metrics.get_label_tp(detection_name, m))]\n        ylimit = max([max(getattr(md, metric)[min_recall_ind:md.max_recall_ind + 1]) for metric in rel_metrics]) * 1.1\n    else:\n        ylimit = 1.0\n\n    # Prepare axis.\n    if ax is None:\n        ax = setup_axis(title=PRETTY_DETECTION_NAMES[detection_name], xlabel='Recall', ylabel='Error', xlim=1,\n                        min_recall=min_recall)\n    ax.set_ylim(0, ylimit)\n\n    # Plot the recall vs. error curve for each tp metric.\n    for metric in TP_METRICS:\n        tp = metrics.get_label_tp(detection_name, metric)\n\n        # Plot only if we have valid data.\n        if tp is not np.nan and min_recall_ind <= md.max_recall_ind:\n            recall, error = md.recall[:md.max_recall_ind + 1], getattr(md, metric)[:md.max_recall_ind + 1]\n        else:\n            recall, error = [], []\n\n        # Change legend based on tp value\n        if tp is np.nan:\n            label = '{}: n/a'.format(PRETTY_TP_METRICS[metric])\n        elif min_recall_ind > md.max_recall_ind:\n            label = '{}: nan'.format(PRETTY_TP_METRICS[metric])\n        else:\n            label = '{}: {:.2f} ({})'.format(PRETTY_TP_METRICS[metric], tp, TP_METRICS_UNITS[metric])\n        if metric == 'trans_err':\n            label += f' ({md.max_recall_ind})'  # add recall\n            print(f'Recall: {detection_name}: {md.max_recall_ind/100}')\n        ax.plot(recall, error, label=label)\n    ax.axvline(x=md.max_recall, linestyle='-.', color=(0, 0, 0, 0.3))\n    ax.legend(loc='best')\n\n    if savepath is not None:\n        plt.savefig(savepath)\n        plt.close()\n\n\nclass DetectionBox_modified(DetectionBox):\n    def __init__(self, *args, token=None, visibility=None, index=None, **kwargs):\n        '''\n        add annotation token\n        '''\n        super().__init__(*args, **kwargs)\n        self.token = token\n        self.visibility = visibility\n        self.index = index\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'token': self.token,\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'visibility': self.visibility,\n            'index': self.index\n\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(\n            token=content['token'],\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name'],\n            visibility=content['visibility'],\n            index=content['index'],\n        )\n\n\ndef center_in_image(box, intrinsic: np.ndarray, imsize: Tuple[int, int], vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible inside an image without accounting for occlusions.\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    center_3d = box.center.reshape(3, 1)\n    center_img = view_points(center_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(center_img[0, :] > 0, center_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, center_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, center_img[1, :] > 0)\n    visible = np.logical_and(visible, center_3d[2, :] > 1)\n\n    in_front = center_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if vis_level == BoxVisibility.ALL:\n        return all(visible) and all(in_front)\n    elif vis_level == BoxVisibility.ANY:\n        return any(visible) and all(in_front)\n    elif vis_level == BoxVisibility.NONE:\n        return True\n    else:\n        raise ValueError(\"vis_level: {} not valid\".format(vis_level))\n\n\ndef exist_corners_in_image_but_not_all(box, intrinsic: np.ndarray, imsize: Tuple[int, int],\n                                       vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible in images but not all corners in image .\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    corners_3d = box.corners()\n    corners_img = view_points(corners_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(corners_img[0, :] > 0, corners_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, corners_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, corners_img[1, :] > 0)\n    visible = np.logical_and(visible, corners_3d[2, :] > 1)\n\n    in_front = corners_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if any(visible) and not all(visible) and all(in_front):\n        return True\n    else:\n        return False\n\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False):\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n\n    # Init.\n    if box_cls == DetectionBox_modified:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n    index_map = {}\n    for scene in nusc.scene:\n        first_sample_token = scene['first_sample_token']\n        sample = nusc.get('sample', first_sample_token)\n        index_map[first_sample_token] = 1\n        index = 2\n        while sample['next'] != '':\n            sample = nusc.get('sample', sample['next'])\n            index_map[sample['token']] = index\n            index += 1\n\n    sample_tokens = []\n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n\n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == DetectionBox_modified:\n                # Get label name in detection task and filter unused labels.\n                detection_name = category_to_detection_name(sample_annotation['category_name'])\n                if detection_name is None:\n                    continue\n\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n\n                sample_boxes.append(\n                    box_cls(\n                        token=sample_annotation_token,\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        visibility=sample_annotation['visibility_token'],\n                        index=index_map[sample_token]\n                    )\n                )\n            elif box_cls == TrackingBox:\n                assert False\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\n\ndef filter_eval_boxes_by_id(nusc: NuScenes,\n                            eval_boxes: EvalBoxes,\n                            id=None,\n                            verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.token in id:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_visibility(\n        ori_eval_boxes: EvalBoxes,\n        visibility=None,\n        verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.visibility == visibility:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After visibility based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_by_sample_token(ori_eval_boxes, valid_sample_tokens=[],  verbose=False):\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    for sample_token in eval_boxes.sample_tokens:\n        if sample_token not in valid_sample_tokens:\n            eval_boxes.boxes.pop(sample_token)\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_overlap(nusc: NuScenes,\n                                 eval_boxes: EvalBoxes,\n                                 verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. basedon overlap .\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    cams = ['CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_BACK_RIGHT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_FRONT_LEFT']\n\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        sample_record = nusc.get('sample', sample_token)\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            count = 0\n            for cam in cams:\n                '''\n                copy-paste form nuscens\n                '''\n                sample_data_token = sample_record['data'][cam]\n                sd_record = nusc.get('sample_data', sample_data_token)\n                cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n                sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n                pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n                cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n                imsize = (sd_record['width'], sd_record['height'])\n                new_box = Box(box.translation, box.size, Quaternion(box.rotation),\n                              name=box.detection_name, token='')\n\n                # Move box to ego vehicle coord system.\n                new_box.translate(-np.array(pose_record['translation']))\n                new_box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n                #  Move box to sensor coord system.\n                new_box.translate(-np.array(cs_record['translation']))\n                new_box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n                if center_in_image(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                    count += 1\n                # if exist_corners_in_image_but_not_all(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                #    count += 1\n\n            if count > 1:\n                with open('center_overlap.txt', 'a') as f:\n                    try:\n                        f.write(box.token + '\\n')\n                    except:\n                        pass\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    verbose = True\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\nclass NuScenesEval_custom(NuScenesEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as DetectionEval.\n    \"\"\"\n\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 overlap_test=False,\n                 eval_mask=False,\n                 data_infos=None\n                 ):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n        self.overlap_test = overlap_test\n        self.eval_mask = eval_mask\n        self.data_infos = data_infos\n        # Check result file exists.\n        assert os.path.exists(result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, DetectionBox,\n                                                     verbose=verbose)\n        self.gt_boxes = load_gt(self.nusc, self.eval_set, DetectionBox_modified, verbose=verbose)\n\n        assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n            \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        # self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        # self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        import pdb\n        pdb.set_trace()\n\n\n\n        # Filter boxes (distance, points per box, etc.).\n\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(nusc, self.pred_boxes, self.cfg.class_range, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(nusc, self.gt_boxes, self.cfg.class_range, verbose=verbose)\n\n        if self.overlap_test:\n            self.pred_boxes = filter_eval_boxes_by_overlap(self.nusc, self.pred_boxes)\n\n            self.gt_boxes = filter_eval_boxes_by_overlap(self.nusc, self.gt_boxes, verbose=True)\n\n        self.all_gt = copy.deepcopy(self.gt_boxes)\n        self.all_preds = copy.deepcopy(self.pred_boxes)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n        self.index_map = {}\n        for scene in nusc.scene:\n            first_sample_token = scene['first_sample_token']\n            sample = nusc.get('sample', first_sample_token)\n            self.index_map[first_sample_token] = 1\n            index = 2\n            while sample['next'] != '':\n                sample = nusc.get('sample', sample['next'])\n                self.index_map[sample['token']] = index\n                index += 1\n\n    def update_gt(self, type_='vis', visibility='1', index=1):\n        if type_ == 'vis':\n            self.visibility_test = True\n            if self.visibility_test:\n                '''[{'description': 'visibility of whole object is between 0 and 40%',\n                'token': '1',\n                'level': 'v0-40'},\n                {'description': 'visibility of whole object is between 40 and 60%',\n                'token': '2',\n                'level': 'v40-60'},\n                {'description': 'visibility of whole object is between 60 and 80%',\n                'token': '3',\n                'level': 'v60-80'},\n                {'description': 'visibility of whole object is between 80 and 100%',\n                'token': '4',\n                'level': 'v80-100'}]'''\n\n                self.gt_boxes = filter_eval_boxes_by_visibility(self.all_gt, visibility, verbose=True)\n\n        elif type_ == 'ord':\n\n            valid_tokens = [key for (key, value) in self.index_map.items() if value == index]\n            # from IPython import embed\n            # embed()\n            self.gt_boxes = filter_by_sample_token(self.all_gt, valid_tokens)\n            self.pred_boxes = filter_by_sample_token(self.all_preds, valid_tokens)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n\n    def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMetricDataList()\n\n        # print(self.cfg.dist_fcn_callable, self.cfg.dist_ths)\n        # self.cfg.dist_ths = [0.3]\n        # self.cfg.dist_fcn_callable\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md = accumulate(self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMetrics(self.cfg)\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.cfg.min_recall, self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in ['attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(md_list, metrics, min_precision=self.cfg.min_precision, min_recall=self.cfg.min_recall,\n                     dist_th_tp=self.cfg.dist_th_tp, savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(md_list, metrics, detection_name, self.cfg.min_precision, self.cfg.min_recall,\n                           savepath=savepath(detection_name + '_pr'))\n\n            class_tp_curve(md_list, metrics, detection_name, self.cfg.min_recall, self.cfg.dist_th_tp,\n                           savepath=savepath(detection_name + '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(md_list, metrics, dist_th, self.cfg.min_precision, self.cfg.min_recall,\n                          savepath=savepath('dist_pr_' + str(dist_th)))\n\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(description='Evaluate nuScenes detection results.',\n                                     formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument('result_path', type=str, help='The submission as a JSON file.')\n    parser.add_argument('--output_dir', type=str, default='~/nuscenes-metrics',\n                        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument('--eval_set', type=str, default='val',\n                        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='data/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument('--version', type=str, default='v1.0-trainval',\n                        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument('--config_path', type=str, default='',\n                        help='Path to the configuration file.'\n                             'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument('--plot_examples', type=int, default=0,\n                        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = NuScenesEval_custom(nusc_, config=cfg_, result_path=result_path_, eval_set=eval_set_,\n                                    output_dir=output_dir_, verbose=verbose_)\n    for vis in ['1', '2', '3', '4']:\n        nusc_eval.update_gt(type_='vis', visibility=vis)\n        print(f'================ {vis} ===============')\n        nusc_eval.main(plot_examples=plot_examples_, render_curves=render_curves_)\n    #for index in range(1, 41):\n    #    nusc_eval.update_gt(type_='ord', index=index)\n    #\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/__init__.py",
    "content": "from .compose import Compose\nfrom .formating import (Collect, Collect3D, DefaultFormatBundle, DefaultFormatBundle3D, \n                        CustomDefaultFormatBundle3D, ImageToTensor,\n                        ToDataContainer, ToTensor, Transpose, to_tensor,VADFormatBundle3D)\nfrom .loading import (LoadAnnotations, LoadImageFromFile, LoadImageFromWebcam,\n                      LoadMultiChannelImageFromFiles, LoadProposals,\n                      LoadAnnotations3D, LoadImageFromFileMono3D,\n                      LoadMultiViewImageFromFiles, LoadPointsFromFile,\n                      LoadPointsFromMultiSweeps, NormalizePointsColor,\n                      PointSegClassMapping, LoadAnnotations3D_E2E, CustomLoadPointsFromMultiSweeps, CustomLoadPointsFromFile)\nfrom .test_time_aug import MultiScaleFlipAug, MultiScaleFlipAug3D\nfrom .transforms_3d import (BackgroundPointsFilter, GlobalAlignment,\n                            GlobalRotScaleTrans, IndoorPatchPointSample,\n                            IndoorPointSample, ObjectNameFilter, ObjectNoise,\n                            ObjectRangeFilter, ObjectSample, PointSample,\n                            PointShuffle, PointsRangeFilter,\n                            RandomDropPointsColor, RandomFlip3D,\n                            RandomJitterPoints, VoxelBasedPointSampler,\n                            PadMultiViewImage, NormalizeMultiviewImage, \n                            PhotoMetricDistortionMultiViewImage, CustomCollect3D, \n                            RandomScaleImageMultiViewImage,VADObjectRangeFilter,VADObjectNameFilter,CustomPointsRangeFilter)\nfrom .transforms import (Albu, CutOut, Expand, MinIoURandomCrop, Normalize,\n                         Pad, PhotoMetricDistortion, RandomCenterCropPad,\n                         RandomCrop, RandomFlip, RandomShift, Resize,\n                         SegRescale)\nfrom .occflow_label import GenerateOccFlowLabels\n\nfrom .augment import ResizeCropFlipImage,BBoxRotation\n\n# __all__ = [\n#     'Compose', 'to_tensor', 'ToTensor', 'ImageToTensor', 'ToDataContainer',\n#     'Transpose', 'Collect', 'DefaultFormatBundle', 'LoadAnnotations',\n#     'LoadImageFromFile', 'LoadImageFromWebcam',\n#     'LoadMultiChannelImageFromFiles', 'LoadProposals', 'MultiScaleFlipAug',\n#     'Resize', 'RandomFlip', 'Pad', 'RandomCrop', 'Normalize', 'SegRescale',\n#     'MinIoURandomCrop', 'Expand', 'PhotoMetricDistortion', 'Albu',\n#     'InstaBoost', 'RandomCenterCropPad', 'AutoAugment', 'CutOut', 'Shear',\n#     'Rotate', 'ColorTransform', 'EqualizeTransform', 'BrightnessTransform',\n#     'ContrastTransform', 'Translate', 'RandomShift',\n#     'ObjectSample', 'RandomFlip3D', 'ObjectNoise', 'GlobalRotScaleTrans',\n#     'PointShuffle', 'ObjectRangeFilter', 'PointsRangeFilter', 'Collect3D',\n#     'LoadMultiViewImageFromFiles', 'LoadPointsFromFile',\n#     'DefaultFormatBundle3D', 'DataBaseSampler',\n#     'NormalizePointsColor', 'LoadAnnotations3D', 'IndoorPointSample',\n#     'PointSample', 'PointSegClassMapping', 'MultiScaleFlipAug3D',\n#     'LoadPointsFromMultiSweeps', 'BackgroundPointsFilter',\n#     'VoxelBasedPointSampler', 'GlobalAlignment', 'IndoorPatchPointSample',\n#     'LoadImageFromFileMono3D', 'ObjectNameFilter', 'RandomDropPointsColor',\n#     'RandomJitterPoints', 'CustomDefaultFormatBundle3D', 'LoadAnnotations3D_E2E',\n#     'GenerateOccFlowLabels', 'PadMultiViewImage', 'NormalizeMultiviewImage', \n#     'PhotoMetricDistortionMultiViewImage', 'CustomCollect3D', 'RandomScaleImageMultiViewImage'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/augment.py",
    "content": "\nimport torch\n\nimport numpy as np\nfrom numpy import random\nimport mmcv\nfrom PIL import Image\nfrom ..builder import PIPELINES\n\n@PIPELINES.register_module()\nclass ResizeCropFlipImage(object):\n    def __call__(self, results):\n        aug_config = results.get(\"aug_config\")\n        if aug_config is None:\n            return results\n        imgs = results[\"img\"]\n        N = len(imgs)\n        new_imgs = []\n        for i in range(N):\n            img, mat = self._img_transform(\n                np.uint8(imgs[i]), aug_config,\n            )\n            new_imgs.append(np.array(img).astype(np.float32))\n            results[\"lidar2img\"][i] = mat @ results[\"lidar2img\"][i]\n            if \"cam_intrinsic\" in results:\n                results[\"cam_intrinsic\"][i][:3, :3] *= aug_config[\"resize\"]\n                # results[\"cam_intrinsic\"][i][:3, :3] = (\n                #     mat[:3, :3] @ results[\"cam_intrinsic\"][i][:3, :3]\n                # )\n\n        results[\"img\"] = new_imgs\n        results[\"img_shape\"] = [x.shape[:2] for x in new_imgs]\n        return results\n\n    def _img_transform(self, img, aug_configs):\n        H, W = img.shape[:2]\n        resize = aug_configs.get(\"resize\", 1)\n        resize_dims = (int(W * resize), int(H * resize))\n        crop = aug_configs.get(\"crop\", [0, 0, *resize_dims])\n        flip = aug_configs.get(\"flip\", False)\n        rotate = aug_configs.get(\"rotate\", 0)\n\n        origin_dtype = img.dtype\n        if origin_dtype != np.uint8:\n            min_value = img.min()\n            max_vaule = img.max()\n            scale = 255 / (max_vaule - min_value)\n            img = (img - min_value) * scale\n            img = np.uint8(img)\n        img = Image.fromarray(img)\n        img = img.resize(resize_dims).crop(crop)\n        if flip:\n            img = img.transpose(method=Image.FLIP_LEFT_RIGHT)\n        img = img.rotate(rotate)\n        img = np.array(img).astype(np.float32)\n        if origin_dtype != np.uint8:\n            img = img.astype(np.float32)\n            img = img / scale + min_value\n\n        transform_matrix = np.eye(3)\n        transform_matrix[:2, :2] *= resize\n        transform_matrix[:2, 2] -= np.array(crop[:2])\n        if flip:\n            flip_matrix = np.array(\n                [[-1, 0, crop[2] - crop[0]], [0, 1, 0], [0, 0, 1]]\n            )\n            transform_matrix = flip_matrix @ transform_matrix\n        rotate = rotate / 180 * np.pi\n        rot_matrix = np.array(\n            [\n                [np.cos(rotate), np.sin(rotate), 0],\n                [-np.sin(rotate), np.cos(rotate), 0],\n                [0, 0, 1],\n            ]\n        )\n        rot_center = np.array([crop[2] - crop[0], crop[3] - crop[1]]) / 2\n        rot_matrix[:2, 2] = -rot_matrix[:2, :2] @ rot_center + rot_center\n        transform_matrix = rot_matrix @ transform_matrix\n        extend_matrix = np.eye(4)\n        extend_matrix[:3, :3] = transform_matrix\n        return img, extend_matrix\n\n@PIPELINES.register_module()\nclass BBoxRotation(object):\n    def __call__(self, results):\n        angle = results[\"aug_config\"][\"rotate_3d\"]\n        rot_cos = np.cos(angle)\n        rot_sin = np.sin(angle)\n\n        rot_mat = np.array(\n            [\n                [rot_cos, -rot_sin, 0, 0],\n                [rot_sin, rot_cos, 0, 0],\n                [0, 0, 1, 0],\n                [0, 0, 0, 1],\n            ]\n        )\n        rot_mat_inv = np.linalg.inv(rot_mat)\n\n        num_view = len(results[\"lidar2img\"])\n        for view in range(num_view):\n            results[\"lidar2img\"][view] = (\n                results[\"lidar2img\"][view] @ rot_mat_inv\n            )\n        if \"lidar2global\" in results:\n            results[\"lidar2global\"] = results[\"lidar2global\"] @ rot_mat_inv\n        if \"gt_bboxes_3d\" in results:\n            results[\"gt_bboxes_3d\"] = self.box_rotate(\n                results[\"gt_bboxes_3d\"], angle\n            )\n        return results\n\n    @staticmethod\n    def box_rotate(bbox_3d, angle):\n        rot_cos = np.cos(angle)\n        rot_sin = np.sin(angle)\n        rot_mat_T = np.array(\n            [[rot_cos, rot_sin, 0], [-rot_sin, rot_cos, 0], [0, 0, 1]]\n        )\n        bbox_3d[:, :3] = bbox_3d[:, :3] @ rot_mat_T\n        bbox_3d[:, 6] += angle\n        if bbox_3d.shape[-1] > 7:\n            vel_dims = bbox_3d[:, 7:].shape[-1]\n            bbox_3d[:, 7:] = bbox_3d[:, 7:] @ rot_mat_T[:vel_dims, :vel_dims]\n        return bbox_3d\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/compose.py",
    "content": "import collections\n\nfrom mmcv.utils import build_from_cfg\n\nfrom ..builder import PIPELINES\n\n\n@PIPELINES.register_module()\nclass Compose:\n    \"\"\"Compose multiple transforms sequentially.\n\n    Args:\n        transforms (Sequence[dict | callable]): Sequence of transform object or\n            config dict to be composed.\n    \"\"\"\n\n    def __init__(self, transforms):\n        assert isinstance(transforms, collections.abc.Sequence)\n        self.transforms = []\n        for transform in transforms:\n            if isinstance(transform, dict):\n                transform = build_from_cfg(transform, PIPELINES)\n                self.transforms.append(transform)\n            elif callable(transform):\n                self.transforms.append(transform)\n            else:\n                raise TypeError('transform must be callable or a dict')\n\n    def __call__(self, data):\n        \"\"\"Call function to apply transforms sequentially.\n\n        Args:\n            data (dict): A result dict contains the data to transform.\n\n        Returns:\n           dict: Transformed data.\n        \"\"\"\n\n        for t in self.transforms:\n            data = t(data)\n            if data is None:\n                return None\n        return data\n\n    def __repr__(self):\n        format_string = self.__class__.__name__ + '('\n        for t in self.transforms:\n            format_string += '\\n'\n            format_string += f'    {t}'\n        format_string += '\\n)'\n        return format_string\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/data_augment_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numba\nimport numpy as np\nimport warnings\nfrom numba.errors import NumbaPerformanceWarning\n\nfrom mmcv.core.bbox import box_np_ops\n\nwarnings.filterwarnings('ignore', category=NumbaPerformanceWarning)\n\n\n@numba.njit\ndef _rotation_box2d_jit_(corners, angle, rot_mat_T):\n    \"\"\"Rotate 2D boxes.\n\n    Args:\n        corners (np.ndarray): Corners of boxes.\n        angle (float): Rotation angle.\n        rot_mat_T (np.ndarray): Transposed rotation matrix.\n    \"\"\"\n    rot_sin = np.sin(angle)\n    rot_cos = np.cos(angle)\n    rot_mat_T[0, 0] = rot_cos\n    rot_mat_T[0, 1] = -rot_sin\n    rot_mat_T[1, 0] = rot_sin\n    rot_mat_T[1, 1] = rot_cos\n    corners[:] = corners @ rot_mat_T\n\n\n@numba.jit(nopython=True)\ndef box_collision_test(boxes, qboxes, clockwise=True):\n    \"\"\"Box collision test.\n\n    Args:\n        boxes (np.ndarray): Corners of current boxes.\n        qboxes (np.ndarray): Boxes to be avoid colliding.\n        clockwise (bool): Whether the corners are in clockwise order.\n            Default: True.\n    \"\"\"\n    N = boxes.shape[0]\n    K = qboxes.shape[0]\n    ret = np.zeros((N, K), dtype=np.bool_)\n    slices = np.array([1, 2, 3, 0])\n    lines_boxes = np.stack((boxes, boxes[:, slices, :]),\n                           axis=2)  # [N, 4, 2(line), 2(xy)]\n    lines_qboxes = np.stack((qboxes, qboxes[:, slices, :]), axis=2)\n    # vec = np.zeros((2,), dtype=boxes.dtype)\n    boxes_standup = box_np_ops.corner_to_standup_nd_jit(boxes)\n    qboxes_standup = box_np_ops.corner_to_standup_nd_jit(qboxes)\n    for i in range(N):\n        for j in range(K):\n            # calculate standup first\n            iw = (\n                min(boxes_standup[i, 2], qboxes_standup[j, 2]) -\n                max(boxes_standup[i, 0], qboxes_standup[j, 0]))\n            if iw > 0:\n                ih = (\n                    min(boxes_standup[i, 3], qboxes_standup[j, 3]) -\n                    max(boxes_standup[i, 1], qboxes_standup[j, 1]))\n                if ih > 0:\n                    for k in range(4):\n                        for box_l in range(4):\n                            A = lines_boxes[i, k, 0]\n                            B = lines_boxes[i, k, 1]\n                            C = lines_qboxes[j, box_l, 0]\n                            D = lines_qboxes[j, box_l, 1]\n                            acd = (D[1] - A[1]) * (C[0] -\n                                                   A[0]) > (C[1] - A[1]) * (\n                                                       D[0] - A[0])\n                            bcd = (D[1] - B[1]) * (C[0] -\n                                                   B[0]) > (C[1] - B[1]) * (\n                                                       D[0] - B[0])\n                            if acd != bcd:\n                                abc = (C[1] - A[1]) * (B[0] - A[0]) > (\n                                    B[1] - A[1]) * (\n                                        C[0] - A[0])\n                                abd = (D[1] - A[1]) * (B[0] - A[0]) > (\n                                    B[1] - A[1]) * (\n                                        D[0] - A[0])\n                                if abc != abd:\n                                    ret[i, j] = True  # collision.\n                                    break\n                        if ret[i, j] is True:\n                            break\n                    if ret[i, j] is False:\n                        # now check complete overlap.\n                        # box overlap qbox:\n                        box_overlap_qbox = True\n                        for box_l in range(4):  # point l in qboxes\n                            for k in range(4):  # corner k in boxes\n                                vec = boxes[i, k] - boxes[i, (k + 1) % 4]\n                                if clockwise:\n                                    vec = -vec\n                                cross = vec[1] * (\n                                    boxes[i, k, 0] - qboxes[j, box_l, 0])\n                                cross -= vec[0] * (\n                                    boxes[i, k, 1] - qboxes[j, box_l, 1])\n                                if cross >= 0:\n                                    box_overlap_qbox = False\n                                    break\n                            if box_overlap_qbox is False:\n                                break\n\n                        if box_overlap_qbox is False:\n                            qbox_overlap_box = True\n                            for box_l in range(4):  # point box_l in boxes\n                                for k in range(4):  # corner k in qboxes\n                                    vec = qboxes[j, k] - qboxes[j, (k + 1) % 4]\n                                    if clockwise:\n                                        vec = -vec\n                                    cross = vec[1] * (\n                                        qboxes[j, k, 0] - boxes[i, box_l, 0])\n                                    cross -= vec[0] * (\n                                        qboxes[j, k, 1] - boxes[i, box_l, 1])\n                                    if cross >= 0:  #\n                                        qbox_overlap_box = False\n                                        break\n                                if qbox_overlap_box is False:\n                                    break\n                            if qbox_overlap_box:\n                                ret[i, j] = True  # collision.\n                        else:\n                            ret[i, j] = True  # collision.\n    return ret\n\n\n@numba.njit\ndef noise_per_box(boxes, valid_mask, loc_noises, rot_noises):\n    \"\"\"Add noise to every box (only on the horizontal plane).\n\n    Args:\n        boxes (np.ndarray): Input boxes with shape (N, 5).\n        valid_mask (np.ndarray): Mask to indicate which boxes are valid\n            with shape (N).\n        loc_noises (np.ndarray): Location noises with shape (N, M, 3).\n        rot_noises (np.ndarray): Rotation noises with shape (N, M).\n\n    Returns:\n        np.ndarray: Mask to indicate whether the noise is\n            added successfully (pass the collision test).\n    \"\"\"\n    num_boxes = boxes.shape[0]\n    num_tests = loc_noises.shape[1]\n    box_corners = box_np_ops.box2d_to_corner_jit(boxes)\n    current_corners = np.zeros((4, 2), dtype=boxes.dtype)\n    rot_mat_T = np.zeros((2, 2), dtype=boxes.dtype)\n    success_mask = -np.ones((num_boxes, ), dtype=np.int64)\n    # print(valid_mask)\n    for i in range(num_boxes):\n        if valid_mask[i]:\n            for j in range(num_tests):\n                current_corners[:] = box_corners[i]\n                current_corners -= boxes[i, :2]\n                _rotation_box2d_jit_(current_corners, rot_noises[i, j],\n                                     rot_mat_T)\n                current_corners += boxes[i, :2] + loc_noises[i, j, :2]\n                coll_mat = box_collision_test(\n                    current_corners.reshape(1, 4, 2), box_corners)\n                coll_mat[0, i] = False\n                # print(coll_mat)\n                if not coll_mat.any():\n                    success_mask[i] = j\n                    box_corners[i] = current_corners\n                    break\n    return success_mask\n\n\n@numba.njit\ndef noise_per_box_v2_(boxes, valid_mask, loc_noises, rot_noises,\n                      global_rot_noises):\n    \"\"\"Add noise to every box (only on the horizontal plane). Version 2 used\n    when enable global rotations.\n\n    Args:\n        boxes (np.ndarray): Input boxes with shape (N, 5).\n        valid_mask (np.ndarray): Mask to indicate which boxes are valid\n            with shape (N).\n        loc_noises (np.ndarray): Location noises with shape (N, M, 3).\n        rot_noises (np.ndarray): Rotation noises with shape (N, M).\n\n    Returns:\n        np.ndarray: Mask to indicate whether the noise is\n            added successfully (pass the collision test).\n    \"\"\"\n    num_boxes = boxes.shape[0]\n    num_tests = loc_noises.shape[1]\n    box_corners = box_np_ops.box2d_to_corner_jit(boxes)\n    current_corners = np.zeros((4, 2), dtype=boxes.dtype)\n    current_box = np.zeros((1, 5), dtype=boxes.dtype)\n    rot_mat_T = np.zeros((2, 2), dtype=boxes.dtype)\n    dst_pos = np.zeros((2, ), dtype=boxes.dtype)\n    success_mask = -np.ones((num_boxes, ), dtype=np.int64)\n    corners_norm = np.zeros((4, 2), dtype=boxes.dtype)\n    corners_norm[1, 1] = 1.0\n    corners_norm[2] = 1.0\n    corners_norm[3, 0] = 1.0\n    corners_norm -= np.array([0.5, 0.5], dtype=boxes.dtype)\n    corners_norm = corners_norm.reshape(4, 2)\n    for i in range(num_boxes):\n        if valid_mask[i]:\n            for j in range(num_tests):\n                current_box[0, :] = boxes[i]\n                current_radius = np.sqrt(boxes[i, 0]**2 + boxes[i, 1]**2)\n                current_grot = np.arctan2(boxes[i, 0], boxes[i, 1])\n                dst_grot = current_grot + global_rot_noises[i, j]\n                dst_pos[0] = current_radius * np.sin(dst_grot)\n                dst_pos[1] = current_radius * np.cos(dst_grot)\n                current_box[0, :2] = dst_pos\n                current_box[0, -1] += (dst_grot - current_grot)\n\n                rot_sin = np.sin(current_box[0, -1])\n                rot_cos = np.cos(current_box[0, -1])\n                rot_mat_T[0, 0] = rot_cos\n                rot_mat_T[0, 1] = -rot_sin\n                rot_mat_T[1, 0] = rot_sin\n                rot_mat_T[1, 1] = rot_cos\n                current_corners[:] = current_box[\n                    0, 2:4] * corners_norm @ rot_mat_T + current_box[0, :2]\n                current_corners -= current_box[0, :2]\n                _rotation_box2d_jit_(current_corners, rot_noises[i, j],\n                                     rot_mat_T)\n                current_corners += current_box[0, :2] + loc_noises[i, j, :2]\n                coll_mat = box_collision_test(\n                    current_corners.reshape(1, 4, 2), box_corners)\n                coll_mat[0, i] = False\n                if not coll_mat.any():\n                    success_mask[i] = j\n                    box_corners[i] = current_corners\n                    loc_noises[i, j, :2] += (dst_pos - boxes[i, :2])\n                    rot_noises[i, j] += (dst_grot - current_grot)\n                    break\n    return success_mask\n\n\ndef _select_transform(transform, indices):\n    \"\"\"Select transform.\n\n    Args:\n        transform (np.ndarray): Transforms to select from.\n        indices (np.ndarray): Mask to indicate which transform to select.\n\n    Returns:\n        np.ndarray: Selected transforms.\n    \"\"\"\n    result = np.zeros((transform.shape[0], *transform.shape[2:]),\n                      dtype=transform.dtype)\n    for i in range(transform.shape[0]):\n        if indices[i] != -1:\n            result[i] = transform[i, indices[i]]\n    return result\n\n\n@numba.njit\ndef _rotation_matrix_3d_(rot_mat_T, angle, axis):\n    \"\"\"Get the 3D rotation matrix.\n\n    Args:\n        rot_mat_T (np.ndarray): Transposed rotation matrix.\n        angle (float): Rotation angle.\n        axis (int): Rotation axis.\n    \"\"\"\n    rot_sin = np.sin(angle)\n    rot_cos = np.cos(angle)\n    rot_mat_T[:] = np.eye(3)\n    if axis == 1:\n        rot_mat_T[0, 0] = rot_cos\n        rot_mat_T[0, 2] = -rot_sin\n        rot_mat_T[2, 0] = rot_sin\n        rot_mat_T[2, 2] = rot_cos\n    elif axis == 2 or axis == -1:\n        rot_mat_T[0, 0] = rot_cos\n        rot_mat_T[0, 1] = -rot_sin\n        rot_mat_T[1, 0] = rot_sin\n        rot_mat_T[1, 1] = rot_cos\n    elif axis == 0:\n        rot_mat_T[1, 1] = rot_cos\n        rot_mat_T[1, 2] = -rot_sin\n        rot_mat_T[2, 1] = rot_sin\n        rot_mat_T[2, 2] = rot_cos\n\n\n@numba.njit\ndef points_transform_(points, centers, point_masks, loc_transform,\n                      rot_transform, valid_mask):\n    \"\"\"Apply transforms to points and box centers.\n\n    Args:\n        points (np.ndarray): Input points.\n        centers (np.ndarray): Input box centers.\n        point_masks (np.ndarray): Mask to indicate which points need\n            to be transformed.\n        loc_transform (np.ndarray): Location transform to be applied.\n        rot_transform (np.ndarray): Rotation transform to be applied.\n        valid_mask (np.ndarray): Mask to indicate which boxes are valid.\n    \"\"\"\n    num_box = centers.shape[0]\n    num_points = points.shape[0]\n    rot_mat_T = np.zeros((num_box, 3, 3), dtype=points.dtype)\n    for i in range(num_box):\n        _rotation_matrix_3d_(rot_mat_T[i], rot_transform[i], 2)\n    for i in range(num_points):\n        for j in range(num_box):\n            if valid_mask[j]:\n                if point_masks[i, j] == 1:\n                    points[i, :3] -= centers[j, :3]\n                    points[i:i + 1, :3] = points[i:i + 1, :3] @ rot_mat_T[j]\n                    points[i, :3] += centers[j, :3]\n                    points[i, :3] += loc_transform[j]\n                    break  # only apply first box's transform\n\n\n@numba.njit\ndef box3d_transform_(boxes, loc_transform, rot_transform, valid_mask):\n    \"\"\"Transform 3D boxes.\n\n    Args:\n        boxes (np.ndarray): 3D boxes to be transformed.\n        loc_transform (np.ndarray): Location transform to be applied.\n        rot_transform (np.ndarray): Rotation transform to be applied.\n        valid_mask (np.ndarray | None): Mask to indicate which boxes are valid.\n    \"\"\"\n    num_box = boxes.shape[0]\n    for i in range(num_box):\n        if valid_mask[i]:\n            boxes[i, :3] += loc_transform[i]\n            boxes[i, 6] += rot_transform[i]\n\n\ndef noise_per_object_v3_(gt_boxes,\n                         points=None,\n                         valid_mask=None,\n                         rotation_perturb=np.pi / 4,\n                         center_noise_std=1.0,\n                         global_random_rot_range=np.pi / 4,\n                         num_try=100):\n    \"\"\"Random rotate or remove each groundtruth independently. use kitti viewer\n    to test this function points_transform_\n\n    Args:\n        gt_boxes (np.ndarray): Ground truth boxes with shape (N, 7).\n        points (np.ndarray | None): Input point cloud with shape (M, 4).\n            Default: None.\n        valid_mask (np.ndarray | None): Mask to indicate which boxes are valid.\n            Default: None.\n        rotation_perturb (float): Rotation perturbation. Default: pi / 4.\n        center_noise_std (float): Center noise standard deviation.\n            Default: 1.0.\n        global_random_rot_range (float): Global random rotation range.\n            Default: pi/4.\n        num_try (int): Number of try. Default: 100.\n    \"\"\"\n    num_boxes = gt_boxes.shape[0]\n    if not isinstance(rotation_perturb, (list, tuple, np.ndarray)):\n        rotation_perturb = [-rotation_perturb, rotation_perturb]\n    if not isinstance(global_random_rot_range, (list, tuple, np.ndarray)):\n        global_random_rot_range = [\n            -global_random_rot_range, global_random_rot_range\n        ]\n    enable_grot = np.abs(global_random_rot_range[0] -\n                         global_random_rot_range[1]) >= 1e-3\n\n    if not isinstance(center_noise_std, (list, tuple, np.ndarray)):\n        center_noise_std = [\n            center_noise_std, center_noise_std, center_noise_std\n        ]\n    if valid_mask is None:\n        valid_mask = np.ones((num_boxes, ), dtype=np.bool_)\n    center_noise_std = np.array(center_noise_std, dtype=gt_boxes.dtype)\n\n    loc_noises = np.random.normal(\n        scale=center_noise_std, size=[num_boxes, num_try, 3])\n    rot_noises = np.random.uniform(\n        rotation_perturb[0], rotation_perturb[1], size=[num_boxes, num_try])\n    gt_grots = np.arctan2(gt_boxes[:, 0], gt_boxes[:, 1])\n    grot_lowers = global_random_rot_range[0] - gt_grots\n    grot_uppers = global_random_rot_range[1] - gt_grots\n    global_rot_noises = np.random.uniform(\n        grot_lowers[..., np.newaxis],\n        grot_uppers[..., np.newaxis],\n        size=[num_boxes, num_try])\n\n    origin = (0.5, 0.5, 0)\n    gt_box_corners = box_np_ops.center_to_corner_box3d(\n        gt_boxes[:, :3],\n        gt_boxes[:, 3:6],\n        gt_boxes[:, 6],\n        origin=origin,\n        axis=2)\n\n    # TODO: rewrite this noise box function?\n    if not enable_grot:\n        selected_noise = noise_per_box(gt_boxes[:, [0, 1, 3, 4, 6]],\n                                       valid_mask, loc_noises, rot_noises)\n    else:\n        selected_noise = noise_per_box_v2_(gt_boxes[:, [0, 1, 3, 4, 6]],\n                                           valid_mask, loc_noises, rot_noises,\n                                           global_rot_noises)\n\n    loc_transforms = _select_transform(loc_noises, selected_noise)\n    rot_transforms = _select_transform(rot_noises, selected_noise)\n    surfaces = box_np_ops.corner_to_surfaces_3d_jit(gt_box_corners)\n    if points is not None:\n        # TODO: replace this points_in_convex function by my tools?\n        point_masks = box_np_ops.points_in_convex_polygon_3d_jit(\n            points[:, :3], surfaces)\n        points_transform_(points, gt_boxes[:, :3], point_masks, loc_transforms,\n                          rot_transforms, valid_mask)\n\n    box3d_transform_(gt_boxes, loc_transforms, rot_transforms, valid_mask)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/formating.py",
    "content": "from collections.abc import Sequence\n\nimport numpy as np\nimport torch\nfrom mmcv.parallel import DataContainer as DC\n\nfrom mmcv.core.bbox.structures.base_box3d import BaseInstance3DBoxes\nfrom mmcv.core.points import BasePoints\nfrom mmcv.utils import is_str\nfrom ..builder import PIPELINES\n\n\ndef to_tensor(data):\n    \"\"\"Convert objects of various python types to :obj:`torch.Tensor`.\n\n    Supported types are: :class:`numpy.ndarray`, :class:`torch.Tensor`,\n    :class:`Sequence`, :class:`int` and :class:`float`.\n\n    Args:\n        data (torch.Tensor | numpy.ndarray | Sequence | int | float): Data to\n            be converted.\n    \"\"\"\n\n    if isinstance(data, torch.Tensor):\n        return data\n    elif isinstance(data, np.ndarray):\n        return torch.from_numpy(data)\n    elif isinstance(data, Sequence) and not is_str(data):\n        return torch.tensor(data)\n    elif isinstance(data, int):\n        return torch.LongTensor([data])\n    elif isinstance(data, float):\n        return torch.FloatTensor([data])\n    else:\n        raise TypeError(f'type {type(data)} cannot be converted to tensor.')\n\n\n@PIPELINES.register_module()\nclass ToTensor:\n    \"\"\"Convert some results to :obj:`torch.Tensor` by given keys.\n\n    Args:\n        keys (Sequence[str]): Keys that need to be converted to Tensor.\n    \"\"\"\n\n    def __init__(self, keys):\n        self.keys = keys\n\n    def __call__(self, results):\n        \"\"\"Call function to convert data in results to :obj:`torch.Tensor`.\n\n        Args:\n            results (dict): Result dict contains the data to convert.\n\n        Returns:\n            dict: The result dict contains the data converted\n                to :obj:`torch.Tensor`.\n        \"\"\"\n        for key in self.keys:\n            results[key] = to_tensor(results[key])\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + f'(keys={self.keys})'\n\n\n@PIPELINES.register_module()\nclass ImageToTensor:\n    \"\"\"Convert image to :obj:`torch.Tensor` by given keys.\n\n    The dimension order of input image is (H, W, C). The pipeline will convert\n    it to (C, H, W). If only 2 dimension (H, W) is given, the output would be\n    (1, H, W).\n\n    Args:\n        keys (Sequence[str]): Key of images to be converted to Tensor.\n    \"\"\"\n\n    def __init__(self, keys):\n        self.keys = keys\n\n    def __call__(self, results):\n        \"\"\"Call function to convert image in results to :obj:`torch.Tensor` and\n        transpose the channel order.\n\n        Args:\n            results (dict): Result dict contains the image data to convert.\n\n        Returns:\n            dict: The result dict contains the image converted\n                to :obj:`torch.Tensor` and transposed to (C, H, W) order.\n        \"\"\"\n        for key in self.keys:\n            img = results[key]\n            if len(img.shape) < 3:\n                img = np.expand_dims(img, -1)\n            results[key] = to_tensor(img.transpose(2, 0, 1))\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + f'(keys={self.keys})'\n\n\n@PIPELINES.register_module()\nclass Transpose:\n    \"\"\"Transpose some results by given keys.\n\n    Args:\n        keys (Sequence[str]): Keys of results to be transposed.\n        order (Sequence[int]): Order of transpose.\n    \"\"\"\n\n    def __init__(self, keys, order):\n        self.keys = keys\n        self.order = order\n\n    def __call__(self, results):\n        \"\"\"Call function to transpose the channel order of data in results.\n\n        Args:\n            results (dict): Result dict contains the data to transpose.\n\n        Returns:\n            dict: The result dict contains the data transposed to \\\n                ``self.order``.\n        \"\"\"\n        for key in self.keys:\n            results[key] = results[key].transpose(self.order)\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + \\\n            f'(keys={self.keys}, order={self.order})'\n\n\n@PIPELINES.register_module()\nclass ToDataContainer:\n    \"\"\"Convert results to :obj:`mmcv.DataContainer` by given fields.\n\n    Args:\n        fields (Sequence[dict]): Each field is a dict like\n            ``dict(key='xxx', **kwargs)``. The ``key`` in result will\n            be converted to :obj:`mmcv.DataContainer` with ``**kwargs``.\n            Default: ``(dict(key='img', stack=True), dict(key='gt_bboxes'),\n            dict(key='gt_labels'))``.\n    \"\"\"\n\n    def __init__(self,\n                 fields=(dict(key='img', stack=True), dict(key='gt_bboxes'),\n                         dict(key='gt_labels'))):\n        self.fields = fields\n\n    def __call__(self, results):\n        \"\"\"Call function to convert data in results to\n        :obj:`mmcv.DataContainer`.\n\n        Args:\n            results (dict): Result dict contains the data to convert.\n\n        Returns:\n            dict: The result dict contains the data converted to \\\n                :obj:`mmcv.DataContainer`.\n        \"\"\"\n\n        for field in self.fields:\n            field = field.copy()\n            key = field.pop('key')\n            results[key] = DC(results[key], **field)\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + f'(fields={self.fields})'\n\n\n@PIPELINES.register_module()\nclass DefaultFormatBundle:\n    \"\"\"Default formatting bundle.\n\n    It simplifies the pipeline of formatting common fields, including \"img\",\n    \"proposals\", \"gt_bboxes\", \"gt_labels\", \"gt_masks\" and \"gt_semantic_seg\".\n    These fields are formatted as follows.\n\n    - img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)\n    - proposals: (1)to tensor, (2)to DataContainer\n    - gt_bboxes: (1)to tensor, (2)to DataContainer\n    - gt_bboxes_ignore: (1)to tensor, (2)to DataContainer\n    - gt_labels: (1)to tensor, (2)to DataContainer\n    - gt_masks: (1)to tensor, (2)to DataContainer (cpu_only=True)\n    - gt_semantic_seg: (1)unsqueeze dim-0 (2)to tensor, \\\n                       (3)to DataContainer (stack=True)\n    \"\"\"\n\n    def __call__(self, results):\n        \"\"\"Call function to transform and format common fields in results.\n\n        Args:\n            results (dict): Result dict contains the data to convert.\n\n        Returns:\n            dict: The result dict contains the data that is formatted with \\\n                default bundle.\n        \"\"\"\n\n        if 'img' in results:\n            img = results['img']\n            # add default meta keys\n            results = self._add_default_meta_keys(results)\n            if len(img.shape) < 3:\n                img = np.expand_dims(img, -1)\n            img = np.ascontiguousarray(img.transpose(2, 0, 1))\n            results['img'] = DC(to_tensor(img), stack=True)\n        for key in ['proposals', 'gt_bboxes', 'gt_bboxes_ignore', 'gt_labels']:\n            if key not in results:\n                continue\n            results[key] = DC(to_tensor(results[key]))\n        if 'gt_masks' in results:\n            results['gt_masks'] = DC(results['gt_masks'], cpu_only=True)\n        if 'gt_semantic_seg' in results:\n            results['gt_semantic_seg'] = DC(\n                to_tensor(results['gt_semantic_seg'][None, ...]), stack=True)\n        return results\n\n    def _add_default_meta_keys(self, results):\n        \"\"\"Add default meta keys.\n\n        We set default meta keys including `pad_shape`, `scale_factor` and\n        `img_norm_cfg` to avoid the case where no `Resize`, `Normalize` and\n        `Pad` are implemented during the whole pipeline.\n\n        Args:\n            results (dict): Result dict contains the data to convert.\n\n        Returns:\n            results (dict): Updated result dict contains the data to convert.\n        \"\"\"\n        img = results['img']\n        results.setdefault('pad_shape', img.shape)\n        results.setdefault('scale_factor', 1.0)\n        num_channels = 1 if len(img.shape) < 3 else img.shape[2]\n        results.setdefault(\n            'img_norm_cfg',\n            dict(\n                mean=np.zeros(num_channels, dtype=np.float32),\n                std=np.ones(num_channels, dtype=np.float32),\n                to_rgb=False))\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__\n\n\n@PIPELINES.register_module()\nclass Collect:\n    \"\"\"Collect data from the loader relevant to the specific task.\n\n    This is usually the last stage of the data loader pipeline. Typically keys\n    is set to some subset of \"img\", \"proposals\", \"gt_bboxes\",\n    \"gt_bboxes_ignore\", \"gt_labels\", and/or \"gt_masks\".\n\n    The \"img_meta\" item is always populated.  The contents of the \"img_meta\"\n    dictionary depends on \"meta_keys\". By default this includes:\n\n        - \"img_shape\": shape of the image input to the network as a tuple \\\n            (h, w, c).  Note that images may be zero padded on the \\\n            bottom/right if the batch tensor is larger than this shape.\n\n        - \"scale_factor\": a float indicating the preprocessing scale\n\n        - \"flip\": a boolean indicating if image flip transform was used\n\n        - \"filename\": path to the image file\n\n        - \"ori_shape\": original shape of the image as a tuple (h, w, c)\n\n        - \"pad_shape\": image shape after padding\n\n        - \"img_norm_cfg\": a dict of normalization information:\n\n            - mean - per channel mean subtraction\n            - std - per channel std divisor\n            - to_rgb - bool indicating if bgr was converted to rgb\n\n    Args:\n        keys (Sequence[str]): Keys of results to be collected in ``data``.\n        meta_keys (Sequence[str], optional): Meta keys to be converted to\n            ``mmcv.DataContainer`` and collected in ``data[img_metas]``.\n            Default: ``('filename', 'ori_filename', 'ori_shape', 'img_shape',\n            'pad_shape', 'scale_factor', 'flip', 'flip_direction',\n            'img_norm_cfg')``\n    \"\"\"\n\n    def __init__(self,\n                 keys,\n                 meta_keys=('filename', 'ori_filename', 'ori_shape',\n                            'img_shape', 'pad_shape', 'scale_factor', 'flip',\n                            'flip_direction', 'img_norm_cfg')):\n        self.keys = keys\n        self.meta_keys = meta_keys\n\n    def __call__(self, results):\n        \"\"\"Call function to collect keys in results. The keys in ``meta_keys``\n        will be converted to :obj:mmcv.DataContainer.\n\n        Args:\n            results (dict): Result dict contains the data to collect.\n\n        Returns:\n            dict: The result dict contains the following keys\n\n                - keys in``self.keys``\n                - ``img_metas``\n        \"\"\"\n\n        data = {}\n        img_meta = {}\n        for key in self.meta_keys:\n            img_meta[key] = results[key]\n        data['img_metas'] = DC(img_meta, cpu_only=True)\n        for key in self.keys:\n            data[key] = results[key]\n        return data\n\n    def __repr__(self):\n        return self.__class__.__name__ + \\\n            f'(keys={self.keys}, meta_keys={self.meta_keys})'\n\n\n@PIPELINES.register_module()\nclass WrapFieldsToLists:\n    \"\"\"Wrap fields of the data dictionary into lists for evaluation.\n\n    This class can be used as a last step of a test or validation\n    pipeline for single image evaluation or inference.\n\n    Example:\n        >>> test_pipeline = [\n        >>>    dict(type='LoadImageFromFile'),\n        >>>    dict(type='Normalize',\n                    mean=[123.675, 116.28, 103.53],\n                    std=[58.395, 57.12, 57.375],\n                    to_rgb=True),\n        >>>    dict(type='Pad', size_divisor=32),\n        >>>    dict(type='ImageToTensor', keys=['img']),\n        >>>    dict(type='Collect', keys=['img']),\n        >>>    dict(type='WrapFieldsToLists')\n        >>> ]\n    \"\"\"\n\n    def __call__(self, results):\n        \"\"\"Call function to wrap fields into lists.\n\n        Args:\n            results (dict): Result dict contains the data to wrap.\n\n        Returns:\n            dict: The result dict where value of ``self.keys`` are wrapped \\\n                into list.\n        \"\"\"\n\n        # Wrap dict fields into lists\n        for key, val in results.items():\n            results[key] = [val]\n        return results\n\n    def __repr__(self):\n        return f'{self.__class__.__name__}()'\n    \n\nPIPELINES._module_dict.pop('DefaultFormatBundle')\n\n@PIPELINES.register_module()\nclass DefaultFormatBundle(object):\n    \"\"\"Default formatting bundle.\n\n    It simplifies the pipeline of formatting common fields, including \"img\",\n    \"proposals\", \"gt_bboxes\", \"gt_labels\", \"gt_masks\" and \"gt_semantic_seg\".\n    These fields are formatted as follows.\n\n    - img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)\n    - proposals: (1)to tensor, (2)to DataContainer\n    - gt_bboxes: (1)to tensor, (2)to DataContainer\n    - gt_bboxes_ignore: (1)to tensor, (2)to DataContainer\n    - gt_labels: (1)to tensor, (2)to DataContainer\n    - gt_masks: (1)to tensor, (2)to DataContainer (cpu_only=True)\n    - gt_semantic_seg: (1)unsqueeze dim-0 (2)to tensor, \\\n                       (3)to DataContainer (stack=True)\n    \"\"\"\n\n    def __init__(self, ):\n        return\n\n    def __call__(self, results):\n        \"\"\"Call function to transform and format common fields in results.\n\n        Args:\n            results (dict): Result dict contains the data to convert.\n\n        Returns:\n            dict: The result dict contains the data that is formatted with\n                default bundle.\n        \"\"\"\n        if 'img' in results:\n            if isinstance(results['img'], list):\n                # process multiple imgs in single frame\n                imgs = [img.transpose(2, 0, 1) for img in results['img']]\n                imgs = np.ascontiguousarray(np.stack(imgs, axis=0))\n                results['img'] = DC(to_tensor(imgs), stack=True)\n            else:\n                img = np.ascontiguousarray(results['img'].transpose(2, 0, 1))\n                results['img'] = DC(to_tensor(img), stack=True)\n        for key in [\n                'proposals', 'gt_bboxes', 'gt_bboxes_ignore', 'gt_labels',\n                'gt_labels_3d', 'attr_labels', 'pts_instance_mask',\n                'pts_semantic_mask', 'centers2d', 'depths'\n        ]:\n            if key not in results:\n                continue\n            if isinstance(results[key], list):\n                results[key] = DC([to_tensor(res) for res in results[key]])\n            else:\n                results[key] = DC(to_tensor(results[key]))\n        if 'gt_bboxes_3d' in results:\n            if isinstance(results['gt_bboxes_3d'], BaseInstance3DBoxes):\n                results['gt_bboxes_3d'] = DC(\n                    results['gt_bboxes_3d'], cpu_only=True)\n            else:\n                results['gt_bboxes_3d'] = DC(\n                    to_tensor(results['gt_bboxes_3d']))\n\n        if 'gt_masks' in results:\n            results['gt_masks'] = DC(results['gt_masks'], cpu_only=True)\n        if 'gt_semantic_seg' in results:\n            results['gt_semantic_seg'] = DC(\n                to_tensor(results['gt_semantic_seg'][None, ...]), stack=True)\n\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__\n\n\n@PIPELINES.register_module()\nclass Collect3D(object):\n    \"\"\"Collect data from the loader relevant to the specific task.\n\n    This is usually the last stage of the data loader pipeline. Typically keys\n    is set to some subset of \"img\", \"proposals\", \"gt_bboxes\",\n    \"gt_bboxes_ignore\", \"gt_labels\", and/or \"gt_masks\".\n\n    The \"img_meta\" item is always populated.  The contents of the \"img_meta\"\n    dictionary depends on \"meta_keys\". By default this includes:\n\n        - 'img_shape': shape of the image input to the network as a tuple \\\n            (h, w, c).  Note that images may be zero padded on the \\\n            bottom/right if the batch tensor is larger than this shape.\n        - 'scale_factor': a float indicating the preprocessing scale\n        - 'flip': a boolean indicating if image flip transform was used\n        - 'filename': path to the image file\n        - 'ori_shape': original shape of the image as a tuple (h, w, c)\n        - 'pad_shape': image shape after padding\n        - 'lidar2img': transform from lidar to image\n        - 'depth2img': transform from depth to image\n        - 'cam2img': transform from camera to image\n        - 'pcd_horizontal_flip': a boolean indicating if point cloud is \\\n            flipped horizontally\n        - 'pcd_vertical_flip': a boolean indicating if point cloud is \\\n            flipped vertically\n        - 'box_mode_3d': 3D box mode\n        - 'box_type_3d': 3D box type\n        - 'img_norm_cfg': a dict of normalization information:\n            - mean: per channel mean subtraction\n            - std: per channel std divisor\n            - to_rgb: bool indicating if bgr was converted to rgb\n        - 'pcd_trans': point cloud transformations\n        - 'sample_idx': sample index\n        - 'pcd_scale_factor': point cloud scale factor\n        - 'pcd_rotation': rotation applied to point cloud\n        - 'pts_filename': path to point cloud file.\n\n    Args:\n        keys (Sequence[str]): Keys of results to be collected in ``data``.\n        meta_keys (Sequence[str], optional): Meta keys to be converted to\n            ``mmcv.DataContainer`` and collected in ``data[img_metas]``.\n            Default: ('filename', 'ori_shape', 'img_shape', 'lidar2img',\n            'depth2img', 'cam2img', 'pad_shape', 'scale_factor', 'flip',\n            'pcd_horizontal_flip', 'pcd_vertical_flip', 'box_mode_3d',\n            'box_type_3d', 'img_norm_cfg', 'pcd_trans',\n            'sample_idx', 'pcd_scale_factor', 'pcd_rotation', 'pts_filename')\n    \"\"\"\n\n    def __init__(self,\n                 keys,\n                 meta_keys=('filename', 'ori_shape', 'img_shape', 'lidar2img',\n                            'depth2img', 'cam2img', 'pad_shape',\n                            'scale_factor', 'flip', 'pcd_horizontal_flip',\n                            'pcd_vertical_flip', 'box_mode_3d', 'box_type_3d',\n                            'img_norm_cfg', 'pcd_trans', 'sample_idx',\n                            'pcd_scale_factor', 'pcd_rotation', 'pts_filename',\n                            'transformation_3d_flow')):\n        self.keys = keys\n        self.meta_keys = meta_keys\n\n    def __call__(self, results):\n        \"\"\"Call function to collect keys in results. The keys in ``meta_keys``\n        will be converted to :obj:`mmcv.DataContainer`.\n\n        Args:\n            results (dict): Result dict contains the data to collect.\n\n        Returns:\n            dict: The result dict contains the following keys\n                - keys in ``self.keys``\n                - ``img_metas``\n        \"\"\"\n        data = {}\n        img_metas = {}\n        for key in self.meta_keys:\n            if key in results:\n                img_metas[key] = results[key]\n\n        data['img_metas'] = DC(img_metas, cpu_only=True)\n        for key in self.keys:\n            data[key] = results[key]\n        return data\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        return self.__class__.__name__ + \\\n            f'(keys={self.keys}, meta_keys={self.meta_keys})'\n\n\n@PIPELINES.register_module()\nclass DefaultFormatBundle3D(DefaultFormatBundle):\n    \"\"\"Default formatting bundle.\n\n    It simplifies the pipeline of formatting common fields for voxels,\n    including \"proposals\", \"gt_bboxes\", \"gt_labels\", \"gt_masks\" and\n    \"gt_semantic_seg\".\n    These fields are formatted as follows.\n\n    - img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)\n    - proposals: (1)to tensor, (2)to DataContainer\n    - gt_bboxes: (1)to tensor, (2)to DataContainer\n    - gt_bboxes_ignore: (1)to tensor, (2)to DataContainer\n    - gt_labels: (1)to tensor, (2)to DataContainer\n    \"\"\"\n\n    def __init__(self, class_names, with_gt=True, with_label=True):\n        super(DefaultFormatBundle3D, self).__init__()\n        self.class_names = class_names\n        self.with_gt = with_gt\n        self.with_label = with_label\n\n    def __call__(self, results):\n        \"\"\"Call function to transform and format common fields in results.\n\n        Args:\n            results (dict): Result dict contains the data to convert.\n\n        Returns:\n            dict: The result dict contains the data that is formatted with\n                default bundle.\n        \"\"\"\n        # Format 3D data\n        if 'points' in results:\n            assert isinstance(results['points'], BasePoints)\n            results['points'] = DC(results['points'].tensor)\n\n        for key in ['voxels', 'coors', 'voxel_centers', 'num_points']:\n            if key not in results:\n                continue\n            results[key] = DC(to_tensor(results[key]), stack=False)\n\n        if self.with_gt:\n            # Clean GT bboxes in the final\n            if 'gt_bboxes_3d_mask' in results:\n                gt_bboxes_3d_mask = results['gt_bboxes_3d_mask']\n                results['gt_bboxes_3d'] = results['gt_bboxes_3d'][\n                    gt_bboxes_3d_mask]\n                if 'gt_names_3d' in results:\n                    results['gt_names_3d'] = results['gt_names_3d'][\n                        gt_bboxes_3d_mask]\n                if 'centers2d' in results:\n                    results['centers2d'] = results['centers2d'][\n                        gt_bboxes_3d_mask]\n                if 'depths' in results:\n                    results['depths'] = results['depths'][gt_bboxes_3d_mask]\n            if 'gt_bboxes_mask' in results:\n                gt_bboxes_mask = results['gt_bboxes_mask']\n                if 'gt_bboxes' in results:\n                    results['gt_bboxes'] = results['gt_bboxes'][gt_bboxes_mask]\n                results['gt_names'] = results['gt_names'][gt_bboxes_mask]\n            if self.with_label:\n                if 'gt_names' in results and len(results['gt_names']) == 0:\n                    results['gt_labels'] = np.array([], dtype=np.int64)\n                    results['attr_labels'] = np.array([], dtype=np.int64)\n                elif 'gt_names' in results and isinstance(\n                        results['gt_names'][0], list):\n                    # gt_labels might be a list of list in multi-view setting\n                    results['gt_labels'] = [\n                        np.array([self.class_names.index(n) for n in res],\n                                 dtype=np.int64) for res in results['gt_names']\n                    ]\n                elif 'gt_names' in results:\n                    results['gt_labels'] = np.array([\n                        self.class_names.index(n) for n in results['gt_names']\n                    ],\n                                                    dtype=np.int64)\n                # we still assume one pipeline for one frame LiDAR\n                # thus, the 3D name is list[string]\n                if 'gt_names_3d' in results:\n                    results['gt_labels_3d'] = np.array([\n                        self.class_names.index(n)\n                        for n in results['gt_names_3d']\n                    ],\n                                                       dtype=np.int64)\n        results = super(DefaultFormatBundle3D, self).__call__(results)\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(class_names={self.class_names}, '\n        repr_str += f'with_gt={self.with_gt}, with_label={self.with_label})'\n        return repr_str\n    \n@PIPELINES.register_module()\nclass CustomDefaultFormatBundle3D(DefaultFormatBundle3D):\n    \"\"\"Default formatting bundle.\n    It simplifies the pipeline of formatting common fields for voxels,\n    including \"proposals\", \"gt_bboxes\", \"gt_labels\", \"gt_masks\" and\n    \"gt_semantic_seg\".\n    These fields are formatted as follows.\n    - img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)\n    - proposals: (1)to tensor, (2)to DataContainer\n    - gt_bboxes: (1)to tensor, (2)to DataContainer\n    - gt_bboxes_ignore: (1)to tensor, (2)to DataContainer\n    - gt_labels: (1)to tensor, (2)to DataContainer\n    \"\"\"\n\n    def __call__(self, results):\n        \"\"\"Call function to transform and format common fields in results.\n        Args:\n            results (dict): Result dict contains the data to convert.\n        Returns:\n            dict: The result dict contains the data that is formatted with\n                default bundle.\n        \"\"\"\n        # Format 3D data\n        results = super(CustomDefaultFormatBundle3D, self).__call__(results)\n        results['gt_map_masks'] = DC(\n            to_tensor(results['gt_map_masks']), stack=True)\n\n        return results\n\n@PIPELINES.register_module()\nclass VADFormatBundle3D(DefaultFormatBundle3D):\n    \"\"\"Default formatting bundle.\n    It simplifies the pipeline of formatting common fields for voxels,\n    including \"proposals\", \"gt_bboxes\", \"gt_labels\", \"gt_masks\" and\n    \"gt_semantic_seg\".\n    These fields are formatted as follows.\n    - img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)\n    - proposals: (1)to tensor, (2)to DataContainer\n    - gt_bboxes: (1)to tensor, (2)to DataContainer\n    - gt_bboxes_ignore: (1)to tensor, (2)to DataContainer\n    - gt_labels: (1)to tensor, (2)to DataContainer\n    \"\"\"\n    def __init__(self, class_names, with_gt=True, with_label=True, with_ego=True):\n        super(VADFormatBundle3D, self).__init__(class_names, with_gt, with_label)\n        self.with_ego = with_ego\n\n\n    def __call__(self, results):\n        \"\"\"Call function to transform and format common fields in results.\n        Args:\n            results (dict): Result dict contains the data to convert.\n        Returns:\n            dict: The result dict contains the data that is formatted with\n                default bundle.\n        \"\"\"\n        # Format 3D data\n        results = super(VADFormatBundle3D, self).__call__(results)\n        # results['gt_map_masks'] = DC(to_tensor(results['gt_map_masks']), stack=True)\n        if self.with_ego:\n            if 'ego_his_trajs' in results:\n                results['ego_his_trajs'] = DC(to_tensor(results['ego_his_trajs'][None, ...]), stack=True)\n            if 'ego_fut_trajs' in results:\n                results['ego_fut_trajs'] = DC(to_tensor(results['ego_fut_trajs'][None, ...]), stack=True)\n            if 'ego_fut_masks' in results:\n                results['ego_fut_masks'] = DC(to_tensor(results['ego_fut_masks'][None, None, ...]), stack=True)\n            if 'ego_fut_cmd' in results:\n                results['ego_fut_cmd'] = DC(to_tensor(results['ego_fut_cmd'][None, None, ...]), stack=True)\n            if 'ego_lcf_feat' in results:\n                results['ego_lcf_feat'] = DC(to_tensor(results['ego_lcf_feat'][None, None, ...]), stack=True)\n            if 'gt_attr_labels' in results:\n                results['gt_attr_labels'] = DC(to_tensor(results['gt_attr_labels']), cpu_only=False)\n                \n        return results\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/loading.py",
    "content": "import os\nimport os.path as osp\nimport torch\nimport mmcv\nimport numpy as np\nimport pycocotools.mask as maskUtils\nfrom einops import rearrange\nfrom mmcv.core.points import BasePoints, get_points_type\nfrom mmcv.fileio.file_client import FileClient\nfrom mmcv.image import imfrombytes, imread\nfrom mmcv.utils import check_file_exist\nfrom mmcv.core.mask.structures import BitmapMasks, PolygonMasks\n# from mmcv.datasets.pipelines.loading import LoadAnnotations, LoadImageFromFile\nfrom ..builder import PIPELINES\n\n\n@PIPELINES.register_module()\nclass LoadImageFromFile:\n    \"\"\"Load an image from file.\n\n    Required keys are \"img_prefix\" and \"img_info\" (a dict that must contain the\n    key \"filename\"). Added or updated keys are \"filename\", \"img\", \"img_shape\",\n    \"ori_shape\" (same as `img_shape`), \"pad_shape\" (same as `img_shape`),\n    \"scale_factor\" (1.0) and \"img_norm_cfg\" (means=0 and stds=1).\n\n    Args:\n        to_float32 (bool): Whether to convert the loaded image to a float32\n            numpy array. If set to False, the loaded image is an uint8 array.\n            Defaults to False.\n        color_type (str): The flag argument for :func:`mmcv.imfrombytes`.\n            Defaults to 'color'.\n        file_client_args (dict): Arguments to instantiate a FileClient.\n            See :class:`mmcv.fileio.FileClient` for details.\n            Defaults to ``dict(backend='disk')``.\n    \"\"\"\n\n    def __init__(self,\n                 to_float32=False,\n                 color_type='color',\n                 file_client_args=dict(backend='disk')):\n        self.to_float32 = to_float32\n        self.color_type = color_type\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n\n    def __call__(self, results):\n        \"\"\"Call functions to load image and get image meta information.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded image and meta information.\n        \"\"\"\n\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n\n        if results['img_prefix'] is not None:\n            filename = osp.join(results['img_prefix'],\n                                results['img_info']['filename'])\n        else:\n            filename = results['img_info']['filename']\n\n        img_bytes = self.file_client.get(filename)\n        img = imfrombytes(img_bytes, flag=self.color_type)\n        if self.to_float32:\n            img = img.astype(np.float32)\n\n        results['filename'] = filename\n        results['ori_filename'] = results['img_info']['filename']\n        results['img'] = img\n        results['img_shape'] = img.shape\n        results['ori_shape'] = img.shape\n        results['img_fields'] = ['img']\n        return results\n\n    def __repr__(self):\n        repr_str = (f'{self.__class__.__name__}('\n                    f'to_float32={self.to_float32}, '\n                    f\"color_type='{self.color_type}', \"\n                    f'file_client_args={self.file_client_args})')\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadImageFromWebcam(LoadImageFromFile):\n    \"\"\"Load an image from webcam.\n\n    Similar with :obj:`LoadImageFromFile`, but the image read from webcam is in\n    ``results['img']``.\n    \"\"\"\n\n    def __call__(self, results):\n        \"\"\"Call functions to add image meta information.\n\n        Args:\n            results (dict): Result dict with Webcam read image in\n                ``results['img']``.\n\n        Returns:\n            dict: The dict contains loaded image and meta information.\n        \"\"\"\n\n        img = results['img']\n        if self.to_float32:\n            img = img.astype(np.float32)\n\n        results['filename'] = None\n        results['ori_filename'] = None\n        results['img'] = img\n        results['img_shape'] = img.shape\n        results['ori_shape'] = img.shape\n        results['img_fields'] = ['img']\n        return results\n\n\n@PIPELINES.register_module()\nclass LoadMultiChannelImageFromFiles:\n    \"\"\"Load multi-channel images from a list of separate channel files.\n\n    Required keys are \"img_prefix\" and \"img_info\" (a dict that must contain the\n    key \"filename\", which is expected to be a list of filenames).\n    Added or updated keys are \"filename\", \"img\", \"img_shape\",\n    \"ori_shape\" (same as `img_shape`), \"pad_shape\" (same as `img_shape`),\n    \"scale_factor\" (1.0) and \"img_norm_cfg\" (means=0 and stds=1).\n\n    Args:\n        to_float32 (bool): Whether to convert the loaded image to a float32\n            numpy array. If set to False, the loaded image is an uint8 array.\n            Defaults to False.\n        color_type (str): The flag argument for :func:`mmcv.imfrombytes`.\n            Defaults to 'color'.\n        file_client_args (dict): Arguments to instantiate a FileClient.\n            See :class:`mmcv.fileio.FileClient` for details.\n            Defaults to ``dict(backend='disk')``.\n    \"\"\"\n\n    def __init__(self,\n                 to_float32=False,\n                 color_type='unchanged',\n                 file_client_args=dict(backend='disk')):\n        self.to_float32 = to_float32\n        self.color_type = color_type\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n\n    def __call__(self, results):\n        \"\"\"Call functions to load multiple images and get images meta\n        information.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded images and meta information.\n        \"\"\"\n\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n\n        if results['img_prefix'] is not None:\n            filename = [\n                osp.join(results['img_prefix'], fname)\n                for fname in results['img_info']['filename']\n            ]\n        else:\n            filename = results['img_info']['filename']\n\n        img = []\n        for name in filename:\n            img_bytes = self.file_client.get(name)\n            img.append(imfrombytes(img_bytes, flag=self.color_type))\n        img = np.stack(img, axis=-1)\n        if self.to_float32:\n            img = img.astype(np.float32)\n\n        results['filename'] = filename\n        results['ori_filename'] = results['img_info']['filename']\n        results['img'] = img\n        results['img_shape'] = img.shape\n        results['ori_shape'] = img.shape\n        # Set initial values for default meta_keys\n        results['pad_shape'] = img.shape\n        results['scale_factor'] = 1.0\n        num_channels = 1 if len(img.shape) < 3 else img.shape[2]\n        results['img_norm_cfg'] = dict(\n            mean=np.zeros(num_channels, dtype=np.float32),\n            std=np.ones(num_channels, dtype=np.float32),\n            to_rgb=False)\n        return results\n\n    def __repr__(self):\n        repr_str = (f'{self.__class__.__name__}('\n                    f'to_float32={self.to_float32}, '\n                    f\"color_type='{self.color_type}', \"\n                    f'file_client_args={self.file_client_args})')\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadAnnotations:\n    \"\"\"Load multiple types of annotations.\n\n    Args:\n        with_bbox (bool): Whether to parse and load the bbox annotation.\n             Default: True.\n        with_label (bool): Whether to parse and load the label annotation.\n            Default: True.\n        with_mask (bool): Whether to parse and load the mask annotation.\n             Default: False.\n        with_seg (bool): Whether to parse and load the semantic segmentation\n            annotation. Default: False.\n        poly2mask (bool): Whether to convert the instance masks from polygons\n            to bitmaps. Default: True.\n        file_client_args (dict): Arguments to instantiate a FileClient.\n            See :class:`mmcv.fileio.FileClient` for details.\n            Defaults to ``dict(backend='disk')``.\n    \"\"\"\n\n    def __init__(self,\n                 with_bbox=True,\n                 with_label=True,\n                 with_mask=False,\n                 with_seg=False,\n                 poly2mask=True,\n                 file_client_args=dict(backend='disk')):\n        self.with_bbox = with_bbox\n        self.with_label = with_label\n        self.with_mask = with_mask\n        self.with_seg = with_seg\n        self.poly2mask = poly2mask\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n\n    def _load_bboxes(self, results):\n        \"\"\"Private function to load bounding box annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded bounding box annotations.\n        \"\"\"\n\n        ann_info = results['ann_info']\n        results['gt_bboxes'] = ann_info['bboxes'].copy()\n\n        gt_bboxes_ignore = ann_info.get('bboxes_ignore', None)\n        if gt_bboxes_ignore is not None:\n            results['gt_bboxes_ignore'] = gt_bboxes_ignore.copy()\n            results['bbox_fields'].append('gt_bboxes_ignore')\n        results['bbox_fields'].append('gt_bboxes')\n        return results\n\n    def _load_labels(self, results):\n        \"\"\"Private function to load label annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded label annotations.\n        \"\"\"\n\n        results['gt_labels'] = results['ann_info']['labels'].copy()\n        return results\n\n    def _poly2mask(self, mask_ann, img_h, img_w):\n        \"\"\"Private function to convert masks represented with polygon to\n        bitmaps.\n\n        Args:\n            mask_ann (list | dict): Polygon mask annotation input.\n            img_h (int): The height of output mask.\n            img_w (int): The width of output mask.\n\n        Returns:\n            numpy.ndarray: The decode bitmap mask of shape (img_h, img_w).\n        \"\"\"\n\n        if isinstance(mask_ann, list):\n            # polygon -- a single object might consist of multiple parts\n            # we merge all parts into one mask rle code\n            rles = maskUtils.frPyObjects(mask_ann, img_h, img_w)\n            rle = maskUtils.merge(rles)\n        elif isinstance(mask_ann['counts'], list):\n            # uncompressed RLE\n            rle = maskUtils.frPyObjects(mask_ann, img_h, img_w)\n        else:\n            # rle\n            rle = mask_ann\n        mask = maskUtils.decode(rle)\n        return mask\n\n    def process_polygons(self, polygons):\n        \"\"\"Convert polygons to list of ndarray and filter invalid polygons.\n\n        Args:\n            polygons (list[list]): Polygons of one instance.\n\n        Returns:\n            list[numpy.ndarray]: Processed polygons.\n        \"\"\"\n\n        polygons = [np.array(p) for p in polygons]\n        valid_polygons = []\n        for polygon in polygons:\n            if len(polygon) % 2 == 0 and len(polygon) >= 6:\n                valid_polygons.append(polygon)\n        return valid_polygons\n\n    def _load_masks(self, results):\n        \"\"\"Private function to load mask annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded mask annotations.\n                If ``self.poly2mask`` is set ``True``, `gt_mask` will contain\n                :obj:`PolygonMasks`. Otherwise, :obj:`BitmapMasks` is used.\n        \"\"\"\n\n        h, w = results['img_info']['height'], results['img_info']['width']\n        gt_masks = results['ann_info']['masks']\n        if self.poly2mask:\n            gt_masks = BitmapMasks(\n                [self._poly2mask(mask, h, w) for mask in gt_masks], h, w)\n        else:\n            gt_masks = PolygonMasks(\n                [self.process_polygons(polygons) for polygons in gt_masks], h,\n                w)\n        results['gt_masks'] = gt_masks\n        results['mask_fields'].append('gt_masks')\n        return results\n\n    def _load_semantic_seg(self, results):\n        \"\"\"Private function to load semantic segmentation annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`dataset`.\n\n        Returns:\n            dict: The dict contains loaded semantic segmentation annotations.\n        \"\"\"\n\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n\n        filename = osp.join(results['seg_prefix'],\n                            results['ann_info']['seg_map'])\n        img_bytes = self.file_client.get(filename)\n        results['gt_semantic_seg'] = imfrombytes(\n            img_bytes, flag='unchanged').squeeze()\n        results['seg_fields'].append('gt_semantic_seg')\n        return results\n\n    def __call__(self, results):\n        \"\"\"Call function to load multiple types annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded bounding box, label, mask and\n                semantic segmentation annotations.\n        \"\"\"\n\n        if self.with_bbox:\n            results = self._load_bboxes(results)\n            if results is None:\n                return None\n        if self.with_label:\n            results = self._load_labels(results)\n        if self.with_mask:\n            results = self._load_masks(results)\n        if self.with_seg:\n            results = self._load_semantic_seg(results)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(with_bbox={self.with_bbox}, '\n        repr_str += f'with_label={self.with_label}, '\n        repr_str += f'with_mask={self.with_mask}, '\n        repr_str += f'with_seg={self.with_seg}, '\n        repr_str += f'poly2mask={self.poly2mask}, '\n        repr_str += f'poly2mask={self.file_client_args})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadProposals:\n    \"\"\"Load proposal pipeline.\n\n    Required key is \"proposals\". Updated keys are \"proposals\", \"bbox_fields\".\n\n    Args:\n        num_max_proposals (int, optional): Maximum number of proposals to load.\n            If not specified, all proposals will be loaded.\n    \"\"\"\n\n    def __init__(self, num_max_proposals=None):\n        self.num_max_proposals = num_max_proposals\n\n    def __call__(self, results):\n        \"\"\"Call function to load proposals from file.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded proposal annotations.\n        \"\"\"\n\n        proposals = results['proposals']\n        if proposals.shape[1] not in (4, 5):\n            raise AssertionError(\n                'proposals should have shapes (n, 4) or (n, 5), '\n                f'but found {proposals.shape}')\n        proposals = proposals[:, :4]\n\n        if self.num_max_proposals is not None:\n            proposals = proposals[:self.num_max_proposals]\n\n        if len(proposals) == 0:\n            proposals = np.array([[0, 0, 0, 0]], dtype=np.float32)\n        results['proposals'] = proposals\n        results['bbox_fields'].append('proposals')\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + \\\n            f'(num_max_proposals={self.num_max_proposals})'\n\n\n@PIPELINES.register_module()\nclass FilterAnnotations:\n    \"\"\"Filter invalid annotations.\n\n    Args:\n        min_gt_bbox_wh (tuple[int]): Minimum width and height of ground truth\n            boxes.\n    \"\"\"\n\n    def __init__(self, min_gt_bbox_wh):\n        # TODO: add more filter options\n        self.min_gt_bbox_wh = min_gt_bbox_wh\n\n    def __call__(self, results):\n        assert 'gt_bboxes' in results\n        gt_bboxes = results['gt_bboxes']\n        w = gt_bboxes[:, 2] - gt_bboxes[:, 0]\n        h = gt_bboxes[:, 3] - gt_bboxes[:, 1]\n        keep = (w > self.min_gt_bbox_wh[0]) & (h > self.min_gt_bbox_wh[1])\n        if not keep.any():\n            return None\n        else:\n            keys = ('gt_bboxes', 'gt_labels', 'gt_masks', 'gt_semantic_seg')\n            for key in keys:\n                if key in results:\n                    results[key] = results[key][keep]\n            return results\n        \n\n@PIPELINES.register_module()\nclass LoadMultiViewImageFromFiles(object):\n    \"\"\"Load multi channel images from a list of separate channel files.\n\n    Expects results['img_filename'] to be a list of filenames.\n\n    Args:\n        to_float32 (bool): Whether to convert the img to float32.\n            Defaults to False.\n        color_type (str): Color type of the file. Defaults to 'unchanged'.\n    \"\"\"\n\n    def __init__(self, to_float32=False, color_type='unchanged'):\n        self.to_float32 = to_float32\n        self.color_type = color_type\n\n    def __call__(self, results):\n        \"\"\"Call function to load multi-view image from files.\n\n        Args:\n            results (dict): Result dict containing multi-view image filenames.\n\n        Returns:\n            dict: The result dict containing the multi-view image data. \\\n                Added keys and values are described below.\n\n                - filename (str): Multi-view image filenames.\n                - img (np.ndarray): Multi-view image arrays.\n                - img_shape (tuple[int]): Shape of multi-view image arrays.\n                - ori_shape (tuple[int]): Shape of original image arrays.\n                - pad_shape (tuple[int]): Shape of padded image arrays.\n                - scale_factor (float): Scale factor.\n                - img_norm_cfg (dict): Normalization configuration of images.\n        \"\"\"\n        filename = results['img_filename']\n        # img is of shape (h, w, c, num_views)\n        img = np.stack(\n            [imread(name, self.color_type) for name in filename], axis=-1)\n        if self.to_float32:\n            img = img.astype(np.float32)\n        results['filename'] = filename\n        # unravel to list, see `DefaultFormatBundle` in formating.py\n        # which will transpose each image separately and then stack into array\n        results['img'] = [img[..., i] for i in range(img.shape[-1])]\n        results['img_shape'] = img.shape\n        results['ori_shape'] = img.shape\n        # Set initial values for default meta_keys\n        results['pad_shape'] = img.shape\n        results['scale_factor'] = 1.0\n        num_channels = 1 if len(img.shape) < 3 else img.shape[2]\n        results['img_norm_cfg'] = dict(\n            mean=np.zeros(num_channels, dtype=np.float32),\n            std=np.ones(num_channels, dtype=np.float32),\n            to_rgb=False)\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(to_float32={self.to_float32}, '\n        repr_str += f\"color_type='{self.color_type}')\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadImageFromFileMono3D(LoadImageFromFile):\n    \"\"\"Load an image from file in monocular 3D object detection. Compared to 2D\n    detection, additional camera parameters need to be loaded.\n\n    Args:\n        kwargs (dict): Arguments are the same as those in \\\n            :class:`LoadImageFromFile`.\n    \"\"\"\n\n    def __call__(self, results):\n        \"\"\"Call functions to load image and get image meta information.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv.CustomDataset`.\n\n        Returns:\n            dict: The dict contains loaded image and meta information.\n        \"\"\"\n        super().__call__(results)\n        results['cam2img'] = results['img_info']['cam_intrinsic']\n        return results\n\n\n@PIPELINES.register_module()\nclass LoadPointsFromMultiSweeps(object):\n    \"\"\"Load points from multiple sweeps.\n\n    This is usually used for nuScenes dataset to utilize previous sweeps.\n\n    Args:\n        sweeps_num (int): Number of sweeps. Defaults to 10.\n        load_dim (int): Dimension number of the loaded points. Defaults to 5.\n        use_dim (list[int]): Which dimension to use. Defaults to [0, 1, 2, 4].\n        file_client_args (dict): Config dict of file clients, refer to\n            https://github.com/open-mmlab/mmcv/blob/master/mmcv/fileio/file_client.py\n            for more details. Defaults to dict(backend='disk').\n        pad_empty_sweeps (bool): Whether to repeat keyframe when\n            sweeps is empty. Defaults to False.\n        remove_close (bool): Whether to remove close points.\n            Defaults to False.\n        test_mode (bool): If test_model=True used for testing, it will not\n            randomly sample sweeps but select the nearest N frames.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self,\n                 sweeps_num=10,\n                 load_dim=5,\n                 use_dim=[0, 1, 2, 4],\n                 file_client_args=dict(backend='disk'),\n                 pad_empty_sweeps=False,\n                 remove_close=False,\n                 test_mode=False):\n        self.load_dim = load_dim\n        self.sweeps_num = sweeps_num\n        self.use_dim = use_dim\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n        self.pad_empty_sweeps = pad_empty_sweeps\n        self.remove_close = remove_close\n        self.test_mode = test_mode\n\n    def _load_points(self, pts_filename):\n        \"\"\"Private function to load point clouds data.\n\n        Args:\n            pts_filename (str): Filename of point clouds data.\n\n        Returns:\n            np.ndarray: An array containing point clouds data.\n        \"\"\"\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n        try:\n            pts_bytes = self.file_client.get(pts_filename)\n            points = np.frombuffer(pts_bytes, dtype=np.float32)\n        except ConnectionError:\n            check_file_exist(pts_filename)\n            if pts_filename.endswith('.npy'):\n                points = np.load(pts_filename)\n            else:\n                points = np.fromfile(pts_filename, dtype=np.float32)\n        return points\n\n    def _remove_close(self, points, radius=1.0):\n        \"\"\"Removes point too close within a certain radius from origin.\n\n        Args:\n            points (np.ndarray | :obj:`BasePoints`): Sweep points.\n            radius (float): Radius below which points are removed.\n                Defaults to 1.0.\n\n        Returns:\n            np.ndarray: Points after removing.\n        \"\"\"\n        if isinstance(points, np.ndarray):\n            points_numpy = points\n        elif isinstance(points, BasePoints):\n            points_numpy = points.tensor.numpy()\n        else:\n            raise NotImplementedError\n        x_filt = np.abs(points_numpy[:, 0]) < radius\n        y_filt = np.abs(points_numpy[:, 1]) < radius\n        not_close = np.logical_not(np.logical_and(x_filt, y_filt))\n        return points[not_close]\n\n    def __call__(self, results):\n        \"\"\"Call function to load multi-sweep point clouds from files.\n\n        Args:\n            results (dict): Result dict containing multi-sweep point cloud \\\n                filenames.\n\n        Returns:\n            dict: The result dict containing the multi-sweep points data. \\\n                Added key and value are described below.\n\n                - points (np.ndarray | :obj:`BasePoints`): Multi-sweep point \\\n                    cloud arrays.\n        \"\"\"\n        points = results['points']\n        points.tensor[:, 4] = 0\n        sweep_points_list = [points]\n        ts = results['timestamp']\n        if self.pad_empty_sweeps and len(results['sweeps']) == 0:\n            for i in range(self.sweeps_num):\n                if self.remove_close:\n                    sweep_points_list.append(self._remove_close(points))\n                else:\n                    sweep_points_list.append(points)\n        else:\n            if len(results['sweeps']) <= self.sweeps_num:\n                choices = np.arange(len(results['sweeps']))\n            elif self.test_mode:\n                choices = np.arange(self.sweeps_num)\n            else:\n                choices = np.random.choice(\n                    len(results['sweeps']), self.sweeps_num, replace=False)\n            for idx in choices:\n                sweep = results['sweeps'][idx]\n                points_sweep = self._load_points(sweep['data_path'])\n                points_sweep = np.copy(points_sweep).reshape(-1, self.load_dim)\n                if self.remove_close:\n                    points_sweep = self._remove_close(points_sweep)\n                sweep_ts = sweep['timestamp'] / 1e6\n                points_sweep[:, :3] = points_sweep[:, :3] @ sweep[\n                    'sensor2lidar_rotation'].T\n                points_sweep[:, :3] += sweep['sensor2lidar_translation']\n                points_sweep[:, 4] = ts - sweep_ts\n                points_sweep = points.new_point(points_sweep)\n                sweep_points_list.append(points_sweep)\n\n        points = points.cat(sweep_points_list)\n        points = points[:, self.use_dim]\n        results['points'] = points\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        return f'{self.__class__.__name__}(sweeps_num={self.sweeps_num})'\n\n\n@PIPELINES.register_module()\nclass PointSegClassMapping(object):\n    \"\"\"Map original semantic class to valid category ids.\n\n    Map valid classes as 0~len(valid_cat_ids)-1 and\n    others as len(valid_cat_ids).\n\n    Args:\n        valid_cat_ids (tuple[int]): A tuple of valid category.\n        max_cat_id (int): The max possible cat_id in input segmentation mask.\n            Defaults to 40.\n    \"\"\"\n\n    def __init__(self, valid_cat_ids, max_cat_id=40):\n        assert max_cat_id >= np.max(valid_cat_ids), \\\n            'max_cat_id should be greater than maximum id in valid_cat_ids'\n\n        self.valid_cat_ids = valid_cat_ids\n        self.max_cat_id = int(max_cat_id)\n\n        # build cat_id to class index mapping\n        neg_cls = len(valid_cat_ids)\n        self.cat_id2class = np.ones(\n            self.max_cat_id + 1, dtype=np.int) * neg_cls\n        for cls_idx, cat_id in enumerate(valid_cat_ids):\n            self.cat_id2class[cat_id] = cls_idx\n\n    def __call__(self, results):\n        \"\"\"Call function to map original semantic class to valid category ids.\n\n        Args:\n            results (dict): Result dict containing point semantic masks.\n\n        Returns:\n            dict: The result dict containing the mapped category ids. \\\n                Updated key and value are described below.\n\n                - pts_semantic_mask (np.ndarray): Mapped semantic masks.\n        \"\"\"\n        assert 'pts_semantic_mask' in results\n        pts_semantic_mask = results['pts_semantic_mask']\n\n        converted_pts_sem_mask = self.cat_id2class[pts_semantic_mask]\n\n        results['pts_semantic_mask'] = converted_pts_sem_mask\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(valid_cat_ids={self.valid_cat_ids}, '\n        repr_str += f'max_cat_id={self.max_cat_id})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass NormalizePointsColor(object):\n    \"\"\"Normalize color of points.\n\n    Args:\n        color_mean (list[float]): Mean color of the point cloud.\n    \"\"\"\n\n    def __init__(self, color_mean):\n        self.color_mean = color_mean\n\n    def __call__(self, results):\n        \"\"\"Call function to normalize color of points.\n\n        Args:\n            results (dict): Result dict containing point clouds data.\n\n        Returns:\n            dict: The result dict containing the normalized points. \\\n                Updated key and value are described below.\n\n                - points (:obj:`BasePoints`): Points after color normalization.\n        \"\"\"\n        points = results['points']\n        assert points.attribute_dims is not None and \\\n            'color' in points.attribute_dims.keys(), \\\n            'Expect points have color attribute'\n        if self.color_mean is not None:\n            points.color = points.color - \\\n                points.color.new_tensor(self.color_mean)\n        points.color = points.color / 255.0\n        results['points'] = points\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(color_mean={self.color_mean})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadPointsFromFile(object):\n    \"\"\"Load Points From File.\n\n    Load sunrgbd and scannet points from file.\n\n    Args:\n        coord_type (str): The type of coordinates of points cloud.\n            Available options includes:\n            - 'LIDAR': Points in LiDAR coordinates.\n            - 'DEPTH': Points in depth coordinates, usually for indoor dataset.\n            - 'CAMERA': Points in camera coordinates.\n        load_dim (int): The dimension of the loaded points.\n            Defaults to 6.\n        use_dim (list[int]): Which dimensions of the points to be used.\n            Defaults to [0, 1, 2]. For KITTI dataset, set use_dim=4\n            or use_dim=[0, 1, 2, 3] to use the intensity dimension.\n        shift_height (bool): Whether to use shifted height. Defaults to False.\n        use_color (bool): Whether to use color features. Defaults to False.\n        file_client_args (dict): Config dict of file clients, refer to\n            https://github.com/open-mmlab/mmcv/blob/master/mmcv/fileio/file_client.py\n            for more details. Defaults to dict(backend='disk').\n    \"\"\"\n\n    def __init__(self,\n                 coord_type,\n                 load_dim=6,\n                 use_dim=[0, 1, 2],\n                 shift_height=False,\n                 use_color=False,\n                 file_client_args=dict(backend='disk')):\n        self.shift_height = shift_height\n        self.use_color = use_color\n        if isinstance(use_dim, int):\n            use_dim = list(range(use_dim))\n        assert max(use_dim) < load_dim, \\\n            f'Expect all used dimensions < {load_dim}, got {use_dim}'\n        assert coord_type in ['CAMERA', 'LIDAR', 'DEPTH']\n\n        self.coord_type = coord_type\n        self.load_dim = load_dim\n        self.use_dim = use_dim\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n\n    def _load_points(self, pts_filename):\n        \"\"\"Private function to load point clouds data.\n\n        Args:\n            pts_filename (str): Filename of point clouds data.\n\n        Returns:\n            np.ndarray: An array containing point clouds data.\n        \"\"\"\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n        try:\n            pts_bytes = self.file_client.get(pts_filename)\n            points = np.frombuffer(pts_bytes, dtype=np.float32)\n        except ConnectionError:\n            check_file_exist(pts_filename)\n            if pts_filename.endswith('.npy'):\n                points = np.load(pts_filename)\n            else:\n                points = np.fromfile(pts_filename, dtype=np.float32)\n\n        return points\n\n    def __call__(self, results):\n        \"\"\"Call function to load points data from file.\n\n        Args:\n            results (dict): Result dict containing point clouds data.\n\n        Returns:\n            dict: The result dict containing the point clouds data. \\\n                Added key and value are described below.\n\n                - points (:obj:`BasePoints`): Point clouds data.\n        \"\"\"\n        pts_filename = results['pts_filename']\n        points = self._load_points(pts_filename)\n        points = points.reshape(-1, self.load_dim)\n        points = points[:, self.use_dim]\n        attribute_dims = None\n\n        if self.shift_height:\n            floor_height = np.percentile(points[:, 2], 0.99)\n            height = points[:, 2] - floor_height\n            points = np.concatenate(\n                [points[:, :3],\n                 np.expand_dims(height, 1), points[:, 3:]], 1)\n            attribute_dims = dict(height=3)\n\n        if self.use_color:\n            assert len(self.use_dim) >= 6\n            if attribute_dims is None:\n                attribute_dims = dict()\n            attribute_dims.update(\n                dict(color=[\n                    points.shape[1] - 3,\n                    points.shape[1] - 2,\n                    points.shape[1] - 1,\n                ]))\n\n        points_class = get_points_type(self.coord_type)\n        points = points_class(\n            points, points_dim=points.shape[-1], attribute_dims=attribute_dims)\n        results['points'] = points\n\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__ + '('\n        repr_str += f'shift_height={self.shift_height}, '\n        repr_str += f'use_color={self.use_color}, '\n        repr_str += f'file_client_args={self.file_client_args}, '\n        repr_str += f'load_dim={self.load_dim}, '\n        repr_str += f'use_dim={self.use_dim})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadAnnotations3D(LoadAnnotations):\n    \"\"\"Load Annotations3D.\n\n    Load instance mask and semantic mask of points and\n    encapsulate the items into related fields.\n\n    Args:\n        with_bbox_3d (bool, optional): Whether to load 3D boxes.\n            Defaults to True.\n        with_label_3d (bool, optional): Whether to load 3D labels.\n            Defaults to True.\n        with_attr_label (bool, optional): Whether to load attribute label.\n            Defaults to False.\n        with_mask_3d (bool, optional): Whether to load 3D instance masks.\n            for points. Defaults to False.\n        with_seg_3d (bool, optional): Whether to load 3D semantic masks.\n            for points. Defaults to False.\n        with_bbox (bool, optional): Whether to load 2D boxes.\n            Defaults to False.\n        with_label (bool, optional): Whether to load 2D labels.\n            Defaults to False.\n        with_mask (bool, optional): Whether to load 2D instance masks.\n            Defaults to False.\n        with_seg (bool, optional): Whether to load 2D semantic masks.\n            Defaults to False.\n        with_bbox_depth (bool, optional): Whether to load 2.5D boxes.\n            Defaults to False.\n        poly2mask (bool, optional): Whether to convert polygon annotations\n            to bitmasks. Defaults to True.\n        seg_3d_dtype (dtype, optional): Dtype of 3D semantic masks.\n            Defaults to int64\n        file_client_args (dict): Config dict of file clients, refer to\n            https://github.com/open-mmlab/mmcv/blob/master/mmcv/fileio/file_client.py\n            for more details.\n    \"\"\"\n\n    def __init__(self,\n                 with_bbox_3d=True,\n                 with_label_3d=True,\n                 with_attr_label=False,\n                 with_mask_3d=False,\n                 with_seg_3d=False,\n                 with_bbox=False,\n                 with_label=False,\n                 with_mask=False,\n                 with_seg=False,\n                 with_bbox_depth=False,\n                 poly2mask=True,\n                 seg_3d_dtype='int',\n                 file_client_args=dict(backend='disk')):\n        super().__init__(\n            with_bbox,\n            with_label,\n            with_mask,\n            with_seg,\n            poly2mask,\n            file_client_args=file_client_args)\n        self.with_bbox_3d = with_bbox_3d\n        self.with_bbox_depth = with_bbox_depth\n        self.with_label_3d = with_label_3d\n        self.with_attr_label = with_attr_label\n        self.with_mask_3d = with_mask_3d\n        self.with_seg_3d = with_seg_3d\n        self.seg_3d_dtype = seg_3d_dtype\n\n    def _load_bboxes_3d(self, results):\n        \"\"\"Private function to load 3D bounding box annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded 3D bounding box annotations.\n        \"\"\"\n        results['gt_bboxes_3d'] = results['ann_info']['gt_bboxes_3d']\n        results['bbox3d_fields'].append('gt_bboxes_3d')\n        return results\n\n    def _load_bboxes_depth(self, results):\n        \"\"\"Private function to load 2.5D bounding box annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded 2.5D bounding box annotations.\n        \"\"\"\n        results['centers2d'] = results['ann_info']['centers2d']\n        results['depths'] = results['ann_info']['depths']\n        return results\n\n    def _load_labels_3d(self, results):\n        \"\"\"Private function to load label annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded label annotations.\n        \"\"\"\n        results['gt_labels_3d'] = results['ann_info']['gt_labels_3d']\n        return results\n\n    def _load_attr_labels(self, results):\n        \"\"\"Private function to load label annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded label annotations.\n        \"\"\"\n        results['attr_labels'] = results['ann_info']['attr_labels']\n        return results\n\n    def _load_masks_3d(self, results):\n        \"\"\"Private function to load 3D mask annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded 3D mask annotations.\n        \"\"\"\n        pts_instance_mask_path = results['ann_info']['pts_instance_mask_path']\n\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n        try:\n            mask_bytes = self.file_client.get(pts_instance_mask_path)\n            pts_instance_mask = np.frombuffer(mask_bytes, dtype=np.int)\n        except ConnectionError:\n            check_file_exist(pts_instance_mask_path)\n            pts_instance_mask = np.fromfile(\n                pts_instance_mask_path, dtype=np.long)\n\n        results['pts_instance_mask'] = pts_instance_mask\n        results['pts_mask_fields'].append('pts_instance_mask')\n        return results\n\n    def _load_semantic_seg_3d(self, results):\n        \"\"\"Private function to load 3D semantic segmentation annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing the semantic segmentation annotations.\n        \"\"\"\n        pts_semantic_mask_path = results['ann_info']['pts_semantic_mask_path']\n\n        if self.file_client is None:\n            self.file_client = FileClient(**self.file_client_args)\n        try:\n            mask_bytes = self.file_client.get(pts_semantic_mask_path)\n            # add .copy() to fix read-only bug\n            pts_semantic_mask = np.frombuffer(\n                mask_bytes, dtype=self.seg_3d_dtype).copy()\n        except ConnectionError:\n            check_file_exist(pts_semantic_mask_path)\n            pts_semantic_mask = np.fromfile(\n                pts_semantic_mask_path, dtype=np.long)\n\n        results['pts_semantic_mask'] = pts_semantic_mask\n        results['pts_seg_fields'].append('pts_semantic_mask')\n        return results\n\n    def __call__(self, results):\n        \"\"\"Call function to load multiple types annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded 3D bounding box, label, mask and\n                semantic segmentation annotations.\n        \"\"\"\n        results = super().__call__(results)\n        if self.with_bbox_3d:\n            results = self._load_bboxes_3d(results)\n            if results is None:\n                return None\n        if self.with_bbox_depth:\n            results = self._load_bboxes_depth(results)\n            if results is None:\n                return None\n        if self.with_label_3d:\n            results = self._load_labels_3d(results)\n        if self.with_attr_label:\n            results = self._load_attr_labels(results)\n        if self.with_mask_3d:\n            results = self._load_masks_3d(results)\n        if self.with_seg_3d:\n            results = self._load_semantic_seg_3d(results)\n\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        indent_str = '    '\n        repr_str = self.__class__.__name__ + '(\\n'\n        repr_str += f'{indent_str}with_bbox_3d={self.with_bbox_3d}, '\n        repr_str += f'{indent_str}with_label_3d={self.with_label_3d}, '\n        repr_str += f'{indent_str}with_attr_label={self.with_attr_label}, '\n        repr_str += f'{indent_str}with_mask_3d={self.with_mask_3d}, '\n        repr_str += f'{indent_str}with_seg_3d={self.with_seg_3d}, '\n        repr_str += f'{indent_str}with_bbox={self.with_bbox}, '\n        repr_str += f'{indent_str}with_label={self.with_label}, '\n        repr_str += f'{indent_str}with_mask={self.with_mask}, '\n        repr_str += f'{indent_str}with_seg={self.with_seg}, '\n        repr_str += f'{indent_str}with_bbox_depth={self.with_bbox_depth}, '\n        repr_str += f'{indent_str}poly2mask={self.poly2mask})'\n        return repr_str\n\n@PIPELINES.register_module()\nclass LoadMultiViewImageFromFilesInCeph(object):\n    \"\"\"Load multi channel images from a list of separate channel files.\n\n    Expects results['img_filename'] to be a list of filenames.\n\n    Args:\n        to_float32 (bool): Whether to convert the img to float32.\n            Defaults to False.\n        color_type (str): Color type of the file. Defaults to 'unchanged'.\n    \"\"\"\n\n    def __init__(self, to_float32=False, color_type='unchanged', file_client_args=dict(backend='disk'), img_root=''):\n        self.to_float32 = to_float32\n        self.color_type = color_type\n        self.file_client_args = file_client_args.copy()\n        self.file_client = FileClient(**self.file_client_args)\n        self.img_root = img_root\n\n    def __call__(self, results):\n        \"\"\"Call function to load multi-view image from files.\n\n        Args:\n            results (dict): Result dict containing multi-view image filenames.\n\n        Returns:\n            dict: The result dict containing the multi-view image data. \\\n                Added keys and values are described below.\n\n                - filename (list of str): Multi-view image filenames.\n                - img (np.ndarray): Multi-view image arrays.\n                - img_shape (tuple[int]): Shape of multi-view image arrays.\n                - ori_shape (tuple[int]): Shape of original image arrays.\n                - pad_shape (tuple[int]): Shape of padded image arrays.\n                - scale_factor (float): Scale factor.\n                - img_norm_cfg (dict): Normalization configuration of images.\n        \"\"\"\n        images_multiView = []\n        filename = results['img_filename']\n        for img_path in filename:\n            # img_path = os.path.join(self.img_root, img_path)\n            if self.file_client_args['backend'] == 'petrel':\n                img_bytes = self.file_client.get(img_path)\n                img = imfrombytes(img_bytes)\n            elif self.file_client_args['backend'] == 'disk':\n                img = imread(img_path, self.color_type)\n            images_multiView.append(img)\n        # img is of shape (h, w, c, num_views)\n        img = np.stack(\n            #[mmcv.imread(name, self.color_type) for name in filename], axis=-1)\n            images_multiView, axis=-1)\n        if self.to_float32:\n            img = img.astype(np.float32)\n        results['filename'] = filename\n        # unravel to list, see `DefaultFormatBundle` in formating.py\n        # which will transpose each image separately and then stack into array\n        results['img'] = [img[..., i] for i in range(img.shape[-1])]\n        results['img_shape'] = img.shape\n        results['ori_shape'] = img.shape\n        # Set initial values for default meta_keys\n        results['pad_shape'] = img.shape\n        results['scale_factor'] = 1.0\n        num_channels = 1 if len(img.shape) < 3 else img.shape[2]\n        results['img_norm_cfg'] = dict(\n            mean=np.zeros(num_channels, dtype=np.float32),\n            std=np.ones(num_channels, dtype=np.float32),\n            to_rgb=False)\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(to_float32={self.to_float32}, '\n        repr_str += f\"color_type='{self.color_type}')\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadAnnotations3D_E2E(LoadAnnotations3D):\n    \"\"\"Load Annotations3D.\n\n    Load instance mask and semantic mask of points and\n    encapsulate the items into related fields.\n\n    Args:\n        with_bbox_3d (bool, optional): Whether to load 3D boxes.\n            Defaults to True.\n        with_label_3d (bool, optional): Whether to load 3D labels.\n            Defaults to True.\n        with_attr_label (bool, optional): Whether to load attribute label.\n            Defaults to False.\n        with_mask_3d (bool, optional): Whether to load 3D instance masks.\n            for points. Defaults to False.\n        with_seg_3d (bool, optional): Whether to load 3D semantic masks.\n            for points. Defaults to False.\n        with_bbox (bool, optional): Whether to load 2D boxes.\n            Defaults to False.\n        with_label (bool, optional): Whether to load 2D labels.\n            Defaults to False.\n        with_mask (bool, optional): Whether to load 2D instance masks.\n            Defaults to False.\n        with_seg (bool, optional): Whether to load 2D semantic masks.\n            Defaults to False.\n        with_bbox_depth (bool, optional): Whether to load 2.5D boxes.\n            Defaults to False.\n        poly2mask (bool, optional): Whether to convert polygon annotations\n            to bitmasks. Defaults to True.\n        seg_3d_dtype (dtype, optional): Dtype of 3D semantic masks.\n            Defaults to int64\n        file_client_args (dict): Config dict of file clients, refer to\n            https://github.com/open-mmlab/mmcv/blob/master/mmcv/fileio/file_client.py\n            for more details.\n    \"\"\"\n    def __init__(self,\n                 with_future_anns=False,\n                 with_ins_inds_3d=False,\n                 with_vis_token=True,\n                 ins_inds_add_1=False,  # NOTE: make ins_inds start from 1, not 0\n                 **kwargs):\n        super().__init__(**kwargs)\n        self.with_future_anns = with_future_anns\n        self.with_ins_inds_3d = with_ins_inds_3d\n        self.with_vis_token = with_vis_token\n        self.ins_inds_add_1 = ins_inds_add_1\n    \n    def _load_future_anns(self, results):\n        \"\"\"Private function to load 3D bounding box annotations.\n\n        Args:\n            results (dict): Result dict from :obj:`mmcv3d.CustomDataset`.\n\n        Returns:\n            dict: The dict containing loaded 3D bounding box annotations.\n        \"\"\"\n\n        gt_bboxes_3d = []\n        gt_labels_3d = []\n        gt_inds_3d = []\n        # gt_valid_flags = []\n        gt_vis_tokens  = []\n\n        for ann_info in results['occ_future_ann_infos']:\n            if ann_info is not None:\n                gt_bboxes_3d.append(ann_info['gt_bboxes_3d'])\n                gt_labels_3d.append(ann_info['gt_labels_3d'])\n                \n                ann_gt_inds = ann_info['gt_inds']\n                if self.ins_inds_add_1:\n                    ann_gt_inds += 1\n                    # NOTE: sdc query is changed from -10 -> -9\n                gt_inds_3d.append(ann_gt_inds)\n\n                # gt_valid_flags.append(ann_info['gt_valid_flag'])\n                if self.with_vis_token:\n                    gt_vis_tokens.append(ann_info['gt_vis_tokens'])\n            else:\n                # invalid frame\n                gt_bboxes_3d.append(None)\n                gt_labels_3d.append(None)\n                gt_inds_3d.append(None)\n                # gt_valid_flags.append(None)\n                if self.with_vis_token:\n                    gt_vis_tokens.append(None)\n\n        results['future_gt_bboxes_3d'] = gt_bboxes_3d\n        # results['future_bbox3d_fields'].append('gt_bboxes_3d')  # Field is used for augmentations, not needed here\n        results['future_gt_labels_3d'] = gt_labels_3d\n        results['future_gt_inds'] = gt_inds_3d\n        # results['future_gt_valid_flag'] = gt_valid_flags\n        if self.with_vis_token:\n            results['future_gt_vis_tokens'] = gt_vis_tokens\n\n        return results \n  \n    def _load_ins_inds_3d(self, results):\n        ann_gt_inds = results['ann_info']['gt_inds'].copy() # TODO: note here\n\n        # NOTE: Avoid gt_inds generated twice\n        results['ann_info'].pop('gt_inds')\n        \n        if self.ins_inds_add_1:\n            ann_gt_inds += 1\n        results['gt_inds'] = ann_gt_inds\n        return results\n\n    def __call__(self, results):\n        results = super().__call__(results)\n        \n        if self.with_future_anns:\n            results = self._load_future_anns(results)\n        if self.with_ins_inds_3d:\n            results = self._load_ins_inds_3d(results)\n        \n        # Generate ann for plan\n        if 'occ_future_ann_infos_for_plan' in results.keys():\n            results = self._load_future_anns_plan(results)\n        \n        return results\n\n    def __repr__(self):\n        repr_str = super().__repr__()\n        indent_str = '    '\n        repr_str += f'{indent_str}with_future_anns={self.with_future_anns}, '\n        repr_str += f'{indent_str}with_ins_inds_3d={self.with_ins_inds_3d}, '\n        \n        return repr_str\n\n\ndef load_augmented_point_cloud(path, virtual=False, reduce_beams=32):\n    # NOTE: following Tianwei's implementation, it is hard coded for nuScenes\n    points = np.fromfile(path, dtype=np.float32).reshape(-1, 5)\n    # NOTE: path definition different from Tianwei's implementation.\n    tokens = path.split(\"/\")\n    vp_dir = \"_VIRTUAL\" if reduce_beams == 32 else f\"_VIRTUAL_{reduce_beams}BEAMS\"\n    seg_path = os.path.join(\n        *tokens[:-3],\n        \"virtual_points\",\n        tokens[-3],\n        tokens[-2] + vp_dir,\n        tokens[-1] + \".pkl.npy\",\n    )\n    assert os.path.exists(seg_path)\n    data_dict = np.load(seg_path, allow_pickle=True).item()\n\n    virtual_points1 = data_dict[\"real_points\"]\n    # NOTE: add zero reflectance to virtual points instead of removing them from real points\n    virtual_points2 = np.concatenate(\n        [\n            data_dict[\"virtual_points\"][:, :3],\n            np.zeros([data_dict[\"virtual_points\"].shape[0], 1]),\n            data_dict[\"virtual_points\"][:, 3:],\n        ],\n        axis=-1,\n    )\n\n    points = np.concatenate(\n        [\n            points,\n            np.ones([points.shape[0], virtual_points1.shape[1] - points.shape[1] + 1]),\n        ],\n        axis=1,\n    )\n    virtual_points1 = np.concatenate(\n        [virtual_points1, np.zeros([virtual_points1.shape[0], 1])], axis=1\n    )\n    # note: this part is different from Tianwei's implementation, we don't have duplicate foreground real points.\n    if len(data_dict[\"real_points_indice\"]) > 0:\n        points[data_dict[\"real_points_indice\"]] = virtual_points1\n    if virtual:\n        virtual_points2 = np.concatenate(\n            [virtual_points2, -1 * np.ones([virtual_points2.shape[0], 1])], axis=1\n        )\n        points = np.concatenate([points, virtual_points2], axis=0).astype(np.float32)\n    return points\n\n\ndef reduce_LiDAR_beams(pts, reduce_beams_to=32):\n    # print(pts.size())\n    if isinstance(pts, np.ndarray):\n        pts = torch.from_numpy(pts)\n    radius = torch.sqrt(pts[:, 0].pow(2) + pts[:, 1].pow(2) + pts[:, 2].pow(2))\n    sine_theta = pts[:, 2] / radius\n    # [-pi/2, pi/2]\n    theta = torch.asin(sine_theta)\n    phi = torch.atan2(pts[:, 1], pts[:, 0])\n\n    top_ang = 0.1862\n    down_ang = -0.5353\n\n    beam_range = torch.zeros(32)\n    beam_range[0] = top_ang\n    beam_range[31] = down_ang\n\n    for i in range(1, 31):\n        beam_range[i] = beam_range[i - 1] - 0.023275\n    # beam_range = [1, 0.18, 0.15, 0.13, 0.11, 0.085, 0.065, 0.03, 0.01, -0.01, -0.03, -0.055, -0.08, -0.105, -0.13, -0.155, -0.18, -0.205, -0.228, -0.251, -0.275,\n    #                -0.295, -0.32, -0.34, -0.36, -0.38, -0.40, -0.425, -0.45, -0.47, -0.49, -0.52, -0.54]\n\n    num_pts, _ = pts.size()\n    mask = torch.zeros(num_pts)\n    if reduce_beams_to == 16:\n        for id in [1, 3, 5, 7, 9, 11, 13, 15, 17, 19, 21, 23, 25, 27, 29, 31]:\n            beam_mask = (theta < (beam_range[id - 1] - 0.012)) * (\n                theta > (beam_range[id] - 0.012)\n            )\n            mask = mask + beam_mask\n        mask = mask.bool()\n    elif reduce_beams_to == 4:\n        for id in [7, 9, 11, 13]:\n            beam_mask = (theta < (beam_range[id - 1] - 0.012)) * (\n                theta > (beam_range[id] - 0.012)\n            )\n            mask = mask + beam_mask\n        mask = mask.bool()\n    # [?] pick the 14th beam\n    elif reduce_beams_to == 1:\n        chosen_beam_id = 9\n        mask = (theta < (beam_range[chosen_beam_id - 1] - 0.012)) * (\n            theta > (beam_range[chosen_beam_id] - 0.012)\n        )\n    else:\n        raise NotImplementedError\n    # points = copy.copy(pts)\n    points = pts[mask]\n    # print(points.size())\n    return points.numpy()\n\n@PIPELINES.register_module()\nclass CustomLoadPointsFromMultiSweeps:\n    \"\"\"Load points from multiple sweeps.\n\n    This is usually used for nuScenes dataset to utilize previous sweeps.\n\n    Args:\n        sweeps_num (int): Number of sweeps. Defaults to 10.\n        load_dim (int): Dimension number of the loaded points. Defaults to 5.\n        use_dim (list[int]): Which dimension to use. Defaults to [0, 1, 2, 4].\n        pad_empty_sweeps (bool): Whether to repeat keyframe when\n            sweeps is empty. Defaults to False.\n        remove_close (bool): Whether to remove close points.\n            Defaults to False.\n        test_mode (bool): If test_model=True used for testing, it will not\n            randomly sample sweeps but select the nearest N frames.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(\n        self,\n        sweeps_num=10,\n        load_dim=5,\n        use_dim=[0, 1, 2, 4],\n        pad_empty_sweeps=False,\n        remove_close=False,\n        test_mode=False,\n        load_augmented=None,\n        reduce_beams=None,\n    ):\n        self.load_dim = load_dim\n        self.sweeps_num = sweeps_num\n        if isinstance(use_dim, int):\n            use_dim = list(range(use_dim))\n        self.use_dim = use_dim\n        self.pad_empty_sweeps = pad_empty_sweeps\n        self.remove_close = remove_close\n        self.test_mode = test_mode\n        self.load_augmented = load_augmented\n        self.reduce_beams = reduce_beams\n\n    def _load_points(self, lidar_path):\n        \"\"\"Private function to load point clouds data.\n\n        Args:\n            lidar_path (str): Filename of point clouds data.\n\n        Returns:\n            np.ndarray: An array containing point clouds data.\n        \"\"\"\n        mmcv.check_file_exist(lidar_path)\n        if self.load_augmented:\n            assert self.load_augmented in [\"pointpainting\", \"mvp\"]\n            virtual = self.load_augmented == \"mvp\"\n            points = load_augmented_point_cloud(\n                lidar_path, virtual=virtual, reduce_beams=self.reduce_beams\n            )\n        elif lidar_path.endswith(\".npy\"):\n            points = np.load(lidar_path)\n        else:\n            points = np.fromfile(lidar_path, dtype=np.float32)\n        return points\n\n    def _remove_close(self, points, radius=1.0):\n        \"\"\"Removes point too close within a certain radius from origin.\n\n        Args:\n            points (np.ndarray | :obj:`BasePoints`): Sweep points.\n            radius (float): Radius below which points are removed.\n                Defaults to 1.0.\n\n        Returns:\n            np.ndarray: Points after removing.\n        \"\"\"\n        if isinstance(points, np.ndarray):\n            points_numpy = points\n        elif isinstance(points, BasePoints):\n            points_numpy = points.tensor.numpy()\n        else:\n            raise NotImplementedError\n        x_filt = np.abs(points_numpy[:, 0]) < radius\n        y_filt = np.abs(points_numpy[:, 1]) < radius\n        not_close = np.logical_not(np.logical_and(x_filt, y_filt))\n        return points[not_close]\n\n    def __call__(self, results):\n        \"\"\"Call function to load multi-sweep point clouds from files.\n\n        Args:\n            results (dict): Result dict containing multi-sweep point cloud \\\n                filenames.\n\n        Returns:\n            dict: The result dict containing the multi-sweep points data. \\\n                Added key and value are described below.\n\n                - points (np.ndarray | :obj:`BasePoints`): Multi-sweep point \\\n                    cloud arrays.\n        \"\"\"\n        points = results[\"points\"]\n        points.tensor[:, 4] = 0\n        sweep_points_list = [points]\n        ts = results[\"timestamp\"] / 1e6\n        if self.pad_empty_sweeps and len(results[\"sweeps\"]) == 0:\n            for i in range(self.sweeps_num):\n                if self.remove_close:\n                    sweep_points_list.append(self._remove_close(points))\n                else:\n                    sweep_points_list.append(points)\n        else:\n            if len(results[\"sweeps\"]) <= self.sweeps_num:\n                choices = np.arange(len(results[\"sweeps\"]))\n            elif self.test_mode:\n                choices = np.arange(self.sweeps_num)\n            else:\n                # NOTE: seems possible to load frame -11?\n                if not self.load_augmented:\n                    choices = np.random.choice(\n                        len(results[\"sweeps\"]), self.sweeps_num, replace=False\n                    )\n                else:\n                    # don't allow to sample the earliest frame, match with Tianwei's implementation.\n                    choices = np.random.choice(\n                        len(results[\"sweeps\"]) - 1, self.sweeps_num, replace=False\n                    )\n            for idx in choices:\n                sweep = results[\"sweeps\"][idx]\n                points_sweep = self._load_points(sweep[\"data_path\"])\n                points_sweep = np.copy(points_sweep).reshape(-1, self.load_dim)\n\n                # TODO: make it more general\n                if self.reduce_beams and self.reduce_beams < 32:\n                    points_sweep = reduce_LiDAR_beams(points_sweep, self.reduce_beams)\n\n                if self.remove_close:\n                    points_sweep = self._remove_close(points_sweep)\n                sweep_ts = sweep[\"timestamp\"] / 1e6\n                points_sweep[:, :3] = (\n                    points_sweep[:, :3] @ sweep[\"sensor2lidar_rotation\"].T\n                )\n                points_sweep[:, :3] += sweep[\"sensor2lidar_translation\"]\n                points_sweep[:, 4] = ts - sweep_ts\n                points_sweep = points.new_point(points_sweep)\n                sweep_points_list.append(points_sweep)\n\n        points = points.cat(sweep_points_list)\n        points = points[:, self.use_dim]\n        results[\"points\"] = points\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        return f\"{self.__class__.__name__}(sweeps_num={self.sweeps_num})\"\n\n\n\n@PIPELINES.register_module()\nclass CustomLoadPointsFromFile:\n    \"\"\"Load Points From File.\n\n    Load sunrgbd and scannet points from file.\n\n    Args:\n        coord_type (str): The type of coordinates of points cloud.\n            Available options includes:\n            - 'LIDAR': Points in LiDAR coordinates.\n            - 'DEPTH': Points in depth coordinates, usually for indoor dataset.\n            - 'CAMERA': Points in camera coordinates.\n        load_dim (int): The dimension of the loaded points.\n            Defaults to 6.\n        use_dim (list[int]): Which dimensions of the points to be used.\n            Defaults to [0, 1, 2]. For KITTI dataset, set use_dim=4\n            or use_dim=[0, 1, 2, 3] to use the intensity dimension.\n        shift_height (bool): Whether to use shifted height. Defaults to False.\n        use_color (bool): Whether to use color features. Defaults to False.\n    \"\"\"\n\n    def __init__(\n        self,\n        coord_type,\n        load_dim=6,\n        use_dim=[0, 1, 2],\n        shift_height=False,\n        use_color=False,\n        load_augmented=None,\n        reduce_beams=None,\n    ):\n        self.shift_height = shift_height\n        self.use_color = use_color\n        if isinstance(use_dim, int):\n            use_dim = list(range(use_dim))\n        assert (\n            max(use_dim) < load_dim\n        ), f\"Expect all used dimensions < {load_dim}, got {use_dim}\"\n        assert coord_type in [\"CAMERA\", \"LIDAR\", \"DEPTH\"]\n\n        self.coord_type = coord_type\n        self.load_dim = load_dim\n        self.use_dim = use_dim\n        self.load_augmented = load_augmented\n        self.reduce_beams = reduce_beams\n\n    def _load_points(self, lidar_path):\n        \"\"\"Private function to load point clouds data.\n\n        Args:\n            lidar_path (str): Filename of point clouds data.\n\n        Returns:\n            np.ndarray: An array containing point clouds data.\n        \"\"\"\n        mmcv.check_file_exist(lidar_path)\n        if self.load_augmented:\n            assert self.load_augmented in [\"pointpainting\", \"mvp\"]\n            virtual = self.load_augmented == \"mvp\"\n            points = load_augmented_point_cloud(\n                lidar_path, virtual=virtual, reduce_beams=self.reduce_beams\n            )\n        elif lidar_path.endswith(\".npy\"):\n            points = np.load(lidar_path)\n        else:\n            points = np.fromfile(lidar_path, dtype=np.float32)\n\n        return points\n\n    def __call__(self, results):\n        \"\"\"Call function to load points data from file.\n\n        Args:\n            results (dict): Result dict containing point clouds data.\n\n        Returns:\n            dict: The result dict containing the point clouds data. \\\n                Added key and value are described below.\n\n                - points (:obj:`BasePoints`): Point clouds data.\n        \"\"\"\n        lidar_path = results[\"pts_filename\"]\n        points = self._load_points(lidar_path)\n        points = points.reshape(-1, self.load_dim)\n        # TODO: make it more general\n        if self.reduce_beams and self.reduce_beams < 32:\n            points = reduce_LiDAR_beams(points, self.reduce_beams)\n        points = points[:, self.use_dim]\n        attribute_dims = None\n\n        if self.shift_height:\n            floor_height = np.percentile(points[:, 2], 0.99)\n            height = points[:, 2] - floor_height\n            points = np.concatenate(\n                [points[:, :3], np.expand_dims(height, 1), points[:, 3:]], 1\n            )\n            attribute_dims = dict(height=3)\n\n        if self.use_color:\n            assert len(self.use_dim) >= 6\n            if attribute_dims is None:\n                attribute_dims = dict()\n            attribute_dims.update(\n                dict(\n                    color=[\n                        points.shape[1] - 3,\n                        points.shape[1] - 2,\n                        points.shape[1] - 1,\n                    ]\n                )\n            )\n\n        points_class = get_points_type(self.coord_type)\n        points = points_class(\n            points, points_dim=points.shape[-1], attribute_dims=attribute_dims\n        )\n        results[\"points\"] = points\n\n        return results\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/occflow_label.py",
    "content": "import torch\nimport numpy as np\nimport cv2\n\nfrom mmcv.models.dense_heads.occ_head_plugin import calculate_birds_eye_view_parameters\n\nfrom mmcv.datasets.builder import PIPELINES\nimport os\n\n@PIPELINES.register_module()\nclass GenerateOccFlowLabels(object):\n    def __init__(self, grid_conf, ignore_index=255, only_vehicle=True, filter_invisible=True, deal_instance_255=False,all_classes = None,vehicle_classes = None,plan_classes = None):\n        self.grid_conf = grid_conf\n        self.bev_resolution, self.bev_start_position, self.bev_dimension = calculate_birds_eye_view_parameters(\n            grid_conf['xbound'], grid_conf['ybound'], grid_conf['zbound'],\n        )\n        # convert numpy\n        self.bev_resolution = self.bev_resolution.numpy()\n        self.bev_start_position = self.bev_start_position.numpy()\n        self.bev_dimension = self.bev_dimension.numpy()\n        self.spatial_extent = (grid_conf['xbound'][1], grid_conf['ybound'][1])\n        self.ignore_index = ignore_index\n        self.only_vehicle = only_vehicle\n        self.filter_invisible = filter_invisible\n        self.deal_instance_255 = deal_instance_255\n        assert self.deal_instance_255 is False\n\n        \n        if all_classes is None:\n            all_classes = ['car', 'truck', 'construction_vehicle', 'bus', 'trailer',\n                        'barrier', 'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone']\n        if vehicle_classes is None:\n            vehicle_classes = ['car', 'bus', 'construction_vehicle',\n                           'bicycle', 'motorcycle', 'truck', 'trailer']\n        if plan_classes is None:\n            plan_classes = vehicle_classes + ['pedestrian']\n\n        self.vehicle_cls_ids = np.array([all_classes.index(\n            cls_name) for cls_name in vehicle_classes])\n\n        self.plan_cls_ids = np.array([all_classes.index(\n            cls_name) for cls_name in plan_classes])\n        \n        if only_vehicle:\n            self.filter_cls_ids = self.vehicle_cls_ids\n        else:\n            self.filter_cls_ids = self.plan_cls_ids\n\n    def reframe_boxes(self, boxes, t_init, t_curr):\n        l2e_r_mat_curr = t_curr['l2e_r']\n        l2e_t_curr = t_curr['l2e_t']\n        e2g_r_mat_curr = t_curr['e2g_r']\n        e2g_t_curr = t_curr['e2g_t']\n\n        l2e_r_mat_init = t_init['l2e_r']\n        l2e_t_init = t_init['l2e_t']\n        e2g_r_mat_init = t_init['e2g_r']\n        e2g_t_init = t_init['e2g_t']\n\n        # to bbox under curr ego frame  # TODO: Uncomment\n        boxes.rotate(l2e_r_mat_curr.T)\n        boxes.translate(l2e_t_curr)\n\n        # to bbox under world frame\n        boxes.rotate(e2g_r_mat_curr.T)\n        boxes.translate(e2g_t_curr)\n\n        # to bbox under initial ego frame, first inverse translate, then inverse rotate \n        boxes.translate(- e2g_t_init)\n        m1 = np.linalg.inv(e2g_r_mat_init)\n        boxes.rotate(m1.T)\n\n        # to bbox under curr ego frame, first inverse translate, then inverse rotate\n        boxes.translate(- l2e_t_init)\n        m2 = np.linalg.inv(l2e_r_mat_init)\n        boxes.rotate(m2.T)\n\n        return boxes\n\n    def __call__(self, results):\n        \"\"\"\n        # Given lidar frame bboxes for curr frame and each future frame,\n        # generate segmentation, instance, centerness, offset, and fwd flow map\n        \"\"\"\n        # Avoid ignoring obj with index = self.ignore_index\n        SPECIAL_INDEX = -20\n\n        all_gt_bboxes_3d = results['future_gt_bboxes_3d']\n        all_gt_labels_3d = results['future_gt_labels_3d']\n        all_gt_inds = results['future_gt_inds']\n        if 'future_gt_vis_tokens' in results.keys():\n            all_vis_tokens = results['future_gt_vis_tokens']\n        else:\n            all_vis_tokens = None\n        num_frame = len(all_gt_bboxes_3d)\n\n        # motion related transforms, of seq lengths\n        l2e_r_mats = results['occ_l2e_r_mats']\n        l2e_t_vecs = results['occ_l2e_t_vecs']\n        e2g_r_mats = results['occ_e2g_r_mats']\n        e2g_t_vecs = results['occ_e2g_t_vecs']\n\n        # reference frame transform\n        t_ref = dict(l2e_r=l2e_r_mats[0], l2e_t=l2e_t_vecs[0], e2g_r=e2g_r_mats[0], e2g_t=e2g_t_vecs[0])\n        \n        segmentations = []\n        instances = []\n        gt_future_boxes = []\n        gt_future_labels = []\n\n        # num_frame is 5\n        for i in range(num_frame):\n            # bbox, label, index of curr frame\n            gt_bboxes_3d, gt_labels_3d = all_gt_bboxes_3d[i], all_gt_labels_3d[i]\n            ins_inds = all_gt_inds[i]\n            if all_vis_tokens is not None:\n                vis_tokens = all_vis_tokens[i]\n            else:\n                vis_tokens = None\n            \n            if gt_bboxes_3d is None:\n                # for invalid samples, no loss calculated\n                segmentation = np.ones(\n                    (self.bev_dimension[1], self.bev_dimension[0])) * self.ignore_index\n                instance = np.ones(\n                    (self.bev_dimension[1], self.bev_dimension[0])) * self.ignore_index\n            else:\n                # reframe bboxes to reference frame\n                t_curr = dict(l2e_r=l2e_r_mats[i], l2e_t=l2e_t_vecs[i], e2g_r=e2g_r_mats[i], e2g_t=e2g_t_vecs[i])\n                ref_bboxes_3d = self.reframe_boxes(gt_bboxes_3d, t_ref, t_curr)\n                gt_future_boxes.append(ref_bboxes_3d)\n                gt_future_labels.append(gt_labels_3d)\n\n                # for valid samples\n                segmentation = np.zeros(\n                    (self.bev_dimension[1], self.bev_dimension[0]))\n                instance = np.zeros(\n                    (self.bev_dimension[1], self.bev_dimension[0]))\n\n                if self.only_vehicle:\n                    vehicle_mask = np.isin(gt_labels_3d, self.filter_cls_ids)\n                    ref_bboxes_3d = ref_bboxes_3d[vehicle_mask]\n                    gt_labels_3d = gt_labels_3d[vehicle_mask]\n                    ins_inds      = ins_inds[vehicle_mask]\n                    if vis_tokens is not None:\n                        vis_tokens = vis_tokens[vehicle_mask]\n\n                if self.filter_invisible:\n                    assert vis_tokens is not None\n                    visible_mask = (vis_tokens != 1)   # obj are filtered out with visibility(1) between 0 and 40% \n                    ref_bboxes_3d = ref_bboxes_3d[visible_mask]\n                    gt_labels_3d = gt_labels_3d[visible_mask]\n                    ins_inds = ins_inds[visible_mask]\n\n                # valid sample and has objects\n                if len(ref_bboxes_3d.tensor) > 0:                    \n                    bbox_corners = ref_bboxes_3d.corners[:, [\n                        0, 3, 7, 4], :2].numpy()\n                    bbox_corners = np.round(\n                        (bbox_corners - self.bev_start_position[:2] + self.bev_resolution[:2] / 2.0) / self.bev_resolution[:2]).astype(np.int32)\n\n                    for index, gt_ind in enumerate(ins_inds):\n                        if gt_ind == self.ignore_index:\n                            gt_ind = SPECIAL_INDEX   # 255 -> -20\n                        poly_region = bbox_corners[index]\n\n                        cv2.fillPoly(segmentation, [poly_region], 1.0)\n                        cv2.fillPoly(instance, [poly_region], int(gt_ind))\n\n            segmentations.append(segmentation)\n            instances.append(instance)\n\n        # segmentation = 1 where objects are located\n        segmentations = torch.from_numpy(\n            np.stack(segmentations, axis=0)).long()\n        instances = torch.from_numpy(np.stack(instances, axis=0)).long()\n\n        # generate heatmap & offset from segmentation & instance\n        instance_centerness, instance_offset, instance_flow, instance_backward_flow = self.center_offset_flow(\n            instances, \n            all_gt_inds, \n            ignore_index=255,\n            )\n\n        invalid_mask = (segmentations[:, 0, 0] == self.ignore_index)\n        instance_centerness[invalid_mask] = self.ignore_index\n\n        results['gt_occ_has_invalid_frame'] = results.pop('occ_has_invalid_frame')\n        results['gt_occ_img_is_valid'] = results.pop('occ_img_is_valid')\n        results.update({\n            'gt_segmentation': segmentations,\n            'gt_instance': instances,\n            'gt_centerness': instance_centerness,\n            'gt_offset': instance_offset,\n            'gt_flow': instance_flow,\n            'gt_backward_flow': instance_backward_flow,\n            'gt_future_boxes': gt_future_boxes,\n            'gt_future_labels': gt_future_labels\n        })\n        return results\n\n    def center_offset_flow(self, instance_img, all_gt_inds, ignore_index=255, sigma=3.0):\n        seq_len, h, w = instance_img.shape\n        # heatmap\n        center_label = torch.zeros(seq_len, 1, h, w)\n        # offset from parts to centers\n        offset_label = ignore_index * torch.ones(seq_len, 2, h, w)\n        # future flow\n        future_displacement_label = ignore_index * torch.ones(seq_len, 2, h, w)\n\n        # backward flow\n        backward_flow = ignore_index * torch.ones(seq_len, 2, h, w)\n\n        # x is vertical displacement, y is horizontal displacement\n        x, y = torch.meshgrid(torch.arange(h, dtype=torch.float),\n                            torch.arange(w, dtype=torch.float))\n\n        gt_inds_all = []\n        for ins_inds_per_frame in all_gt_inds:\n            if ins_inds_per_frame is None:\n                continue\n            for ins_ind in ins_inds_per_frame:\n                gt_inds_all.append(ins_ind)\n        gt_inds_unique = np.unique(np.array(gt_inds_all))\n\n        # iterate over all instances across this sequence\n        for instance_id in gt_inds_unique:\n            instance_id = int(instance_id)\n            prev_xc = None\n            prev_yc = None\n            prev_mask = None\n            for t in range(seq_len):\n                instance_mask = (instance_img[t] == instance_id)\n                if instance_mask.sum() == 0:\n                    # this instance is not in this frame\n                    prev_xc = None\n                    prev_yc = None\n                    prev_mask = None\n                    continue\n\n                # the Bird-Eye-View center of the instance\n                xc = x[instance_mask].mean()\n                yc = y[instance_mask].mean()\n\n                off_x = xc - x\n                off_y = yc - y\n                g = torch.exp(-(off_x ** 2 + off_y ** 2) / sigma ** 2)\n                center_label[t, 0] = torch.maximum(center_label[t, 0], g)\n                offset_label[t, 0, instance_mask] = off_x[instance_mask]\n                offset_label[t, 1, instance_mask] = off_y[instance_mask]\n\n                if prev_xc is not None and instance_mask.sum() > 0:\n                    delta_x = xc - prev_xc\n                    delta_y = yc - prev_yc\n                    future_displacement_label[t-1, 0, prev_mask] = delta_x\n                    future_displacement_label[t-1, 1, prev_mask] = delta_y\n                    backward_flow[t-1, 0, instance_mask] = -1 * delta_x\n                    backward_flow[t-1, 1, instance_mask] = -1 * delta_y\n                        \n                prev_xc = xc\n                prev_yc = yc\n                prev_mask = instance_mask\n        \n        return center_label, offset_label, future_displacement_label, backward_flow\n\n\n    def visualize_instances(self, instances, vis_root=''):\n        if vis_root is not None and vis_root != '':\n            os.makedirs(vis_root, exist_ok=True)\n            \n        for i, ins in enumerate(instances):\n            ins_c = ins.astype(np.uint8)\n            ins_c = cv2.applyColorMap(ins_c, cv2.COLORMAP_JET)\n            save_path = os.path.join(vis_root, '{}.png'.format(i))\n            cv2.imwrite(save_path, ins_c)\n        \n        vid_path = os.path.join(vis_root, 'vid_ins.avi')\n        height, width = instances[0].shape\n        size = (height, width)\n        v_out = cv2.VideoWriter(vid_path, cv2.VideoWriter_fourcc(*'DIVX'), 4, size)\n        for i in range(len(instances)):\n            ins_c = instances[i].astype(np.uint8)\n            ins_c = cv2.applyColorMap(ins_c, cv2.COLORMAP_JET)\n            v_out.write(ins_c)\n        v_out.release()\n        return\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/test_time_aug.py",
    "content": "import warnings\n\nfrom mmcv.utils import is_list_of\nfrom copy import deepcopy\nfrom ..builder import PIPELINES\nfrom .compose import Compose\n\n\n@PIPELINES.register_module()\nclass MultiScaleFlipAug:\n    \"\"\"Test-time augmentation with multiple scales and flipping.\n\n    An example configuration is as followed:\n\n    .. code-block::\n\n        img_scale=[(1333, 400), (1333, 800)],\n        flip=True,\n        transforms=[\n            dict(type='Resize', keep_ratio=True),\n            dict(type='RandomFlip'),\n            dict(type='Normalize', **img_norm_cfg),\n            dict(type='Pad', size_divisor=32),\n            dict(type='ImageToTensor', keys=['img']),\n            dict(type='Collect', keys=['img']),\n        ]\n\n    After MultiScaleFLipAug with above configuration, the results are wrapped\n    into lists of the same length as followed:\n\n    .. code-block::\n\n        dict(\n            img=[...],\n            img_shape=[...],\n            scale=[(1333, 400), (1333, 400), (1333, 800), (1333, 800)]\n            flip=[False, True, False, True]\n            ...\n        )\n\n    Args:\n        transforms (list[dict]): Transforms to apply in each augmentation.\n        img_scale (tuple | list[tuple] | None): Images scales for resizing.\n        scale_factor (float | list[float] | None): Scale factors for resizing.\n        flip (bool): Whether apply flip augmentation. Default: False.\n        flip_direction (str | list[str]): Flip augmentation directions,\n            options are \"horizontal\", \"vertical\" and \"diagonal\". If\n            flip_direction is a list, multiple flip augmentations will be\n            applied. It has no effect when flip == False. Default:\n            \"horizontal\".\n    \"\"\"\n\n    def __init__(self,\n                 transforms,\n                 img_scale=None,\n                 scale_factor=None,\n                 flip=False,\n                 flip_direction='horizontal'):\n        self.transforms = Compose(transforms)\n        assert (img_scale is None) ^ (scale_factor is None), (\n            'Must have but only one variable can be setted')\n        if img_scale is not None:\n            self.img_scale = img_scale if isinstance(img_scale,\n                                                     list) else [img_scale]\n            self.scale_key = 'scale'\n            assert is_list_of(self.img_scale, tuple)\n        else:\n            self.img_scale = scale_factor if isinstance(\n                scale_factor, list) else [scale_factor]\n            self.scale_key = 'scale_factor'\n\n        self.flip = flip\n        self.flip_direction = flip_direction if isinstance(\n            flip_direction, list) else [flip_direction]\n        assert is_list_of(self.flip_direction, str)\n        if not self.flip and self.flip_direction != ['horizontal']:\n            warnings.warn(\n                'flip_direction has no effect when flip is set to False')\n        if (self.flip\n                and not any([t['type'] == 'RandomFlip' for t in transforms])):\n            warnings.warn(\n                'flip has no effect when RandomFlip is not in transforms')\n\n    def __call__(self, results):\n        \"\"\"Call function to apply test time augment transforms on results.\n\n        Args:\n            results (dict): Result dict contains the data to transform.\n\n        Returns:\n           dict[str: list]: The augmented data, where each value is wrapped\n               into a list.\n        \"\"\"\n\n        aug_data = []\n        flip_args = [(False, None)]\n        if self.flip:\n            flip_args += [(True, direction)\n                          for direction in self.flip_direction]\n        for scale in self.img_scale:\n            for flip, direction in flip_args:\n                _results = results.copy()\n                _results[self.scale_key] = scale\n                _results['flip'] = flip\n                _results['flip_direction'] = direction\n                data = self.transforms(_results)\n                aug_data.append(data)\n        # list of dict to dict of list\n        aug_data_dict = {key: [] for key in aug_data[0]}\n        for data in aug_data:\n            for key, val in data.items():\n                aug_data_dict[key].append(val)\n        return aug_data_dict\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(transforms={self.transforms}, '\n        repr_str += f'img_scale={self.img_scale}, flip={self.flip}, '\n        repr_str += f'flip_direction={self.flip_direction})'\n        return repr_str\n    \n@PIPELINES.register_module()\nclass MultiScaleFlipAug3D(object):\n    \"\"\"Test-time augmentation with multiple scales and flipping.\n\n    Args:\n        transforms (list[dict]): Transforms to apply in each augmentation.\n        img_scale (tuple | list[tuple]: Images scales for resizing.\n        pts_scale_ratio (float | list[float]): Points scale ratios for\n            resizing.\n        flip (bool): Whether apply flip augmentation. Defaults to False.\n        flip_direction (str | list[str]): Flip augmentation directions\n            for images, options are \"horizontal\" and \"vertical\".\n            If flip_direction is list, multiple flip augmentations will\n            be applied. It has no effect when ``flip == False``.\n            Defaults to \"horizontal\".\n        pcd_horizontal_flip (bool): Whether apply horizontal flip augmentation\n            to point cloud. Defaults to True. Note that it works only when\n            'flip' is turned on.\n        pcd_vertical_flip (bool): Whether apply vertical flip augmentation\n            to point cloud. Defaults to True. Note that it works only when\n            'flip' is turned on.\n    \"\"\"\n\n    def __init__(self,\n                 transforms,\n                 img_scale,\n                 pts_scale_ratio,\n                 flip=False,\n                 flip_direction='horizontal',\n                 pcd_horizontal_flip=False,\n                 pcd_vertical_flip=False):\n        self.transforms = Compose(transforms)\n        self.img_scale = img_scale if isinstance(img_scale,\n                                                 list) else [img_scale]\n        self.pts_scale_ratio = pts_scale_ratio \\\n            if isinstance(pts_scale_ratio, list) else[float(pts_scale_ratio)]\n\n        assert is_list_of(self.img_scale, tuple)\n        assert is_list_of(self.pts_scale_ratio, float)\n\n        self.flip = flip\n        self.pcd_horizontal_flip = pcd_horizontal_flip\n        self.pcd_vertical_flip = pcd_vertical_flip\n\n        self.flip_direction = flip_direction if isinstance(\n            flip_direction, list) else [flip_direction]\n        assert is_list_of(self.flip_direction, str)\n        if not self.flip and self.flip_direction != ['horizontal']:\n            warnings.warn(\n                'flip_direction has no effect when flip is set to False')\n        if (self.flip and not any([(t['type'] == 'RandomFlip3D'\n                                    or t['type'] == 'RandomFlip')\n                                   for t in transforms])):\n            warnings.warn(\n                'flip has no effect when RandomFlip is not in transforms')\n\n    def __call__(self, results):\n        \"\"\"Call function to augment common fields in results.\n\n        Args:\n            results (dict): Result dict contains the data to augment.\n\n        Returns:\n            dict: The result dict contains the data that is augmented with \\\n                different scales and flips.\n        \"\"\"\n        aug_data = []\n\n        # modified from `flip_aug = [False, True] if self.flip else [False]`\n        # to reduce unnecessary scenes when using double flip augmentation\n        # during test time\n        flip_aug = [True] if self.flip else [False]\n        pcd_horizontal_flip_aug = [False, True] \\\n            if self.flip and self.pcd_horizontal_flip else [False]\n        pcd_vertical_flip_aug = [False, True] \\\n            if self.flip and self.pcd_vertical_flip else [False]\n        for scale in self.img_scale:\n            for pts_scale_ratio in self.pts_scale_ratio:\n                for flip in flip_aug:\n                    for pcd_horizontal_flip in pcd_horizontal_flip_aug:\n                        for pcd_vertical_flip in pcd_vertical_flip_aug:\n                            for direction in self.flip_direction:\n                                # results.copy will cause bug\n                                # since it is shallow copy\n                                _results = deepcopy(results)\n                                _results['scale'] = scale\n                                _results['flip'] = flip\n                                _results['pcd_scale_factor'] = \\\n                                    pts_scale_ratio\n                                _results['flip_direction'] = direction\n                                _results['pcd_horizontal_flip'] = \\\n                                    pcd_horizontal_flip\n                                _results['pcd_vertical_flip'] = \\\n                                    pcd_vertical_flip\n                                data = self.transforms(_results)\n                                aug_data.append(data)\n        # list of dict to dict of list\n        aug_data_dict = {key: [] for key in aug_data[0]}\n        for data in aug_data:\n            for key, val in data.items():\n                aug_data_dict[key].append(val)\n        return aug_data_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(transforms={self.transforms}, '\n        repr_str += f'img_scale={self.img_scale}, flip={self.flip}, '\n        repr_str += f'pts_scale_ratio={self.pts_scale_ratio}, '\n        repr_str += f'flip_direction={self.flip_direction})'\n        return repr_str\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/transforms.py",
    "content": "import copy\nimport inspect\n\nimport numpy as np\nfrom numpy import random\n\nfrom mmcv.core.mask.structures import PolygonMasks\nfrom mmcv.core.evaluation.bbox_overlaps import bbox_overlaps\nfrom mmcv.utils import is_list_of, is_str\nfrom mmcv.image import imrescale, imresize, imflip, impad, impad_to_multiple, imnormalize, bgr2hsv, hsv2bgr\nfrom ..builder import PIPELINES\n\ntry:\n    from imagecorruptions import corrupt\nexcept ImportError:\n    corrupt = None\n\ntry:\n    import albumentations\n    from albumentations import Compose\nexcept ImportError:\n    albumentations = None\n    Compose = None\n\n\n@PIPELINES.register_module()\nclass Resize:\n    \"\"\"Resize images & bbox & mask.\n\n    This transform resizes the input image to some scale. Bboxes and masks are\n    then resized with the same scale factor. If the input dict contains the key\n    \"scale\", then the scale in the input dict is used, otherwise the specified\n    scale in the init method is used. If the input dict contains the key\n    \"scale_factor\" (if MultiScaleFlipAug does not give img_scale but\n    scale_factor), the actual scale will be computed by image shape and\n    scale_factor.\n\n    `img_scale` can either be a tuple (single-scale) or a list of tuple\n    (multi-scale). There are 3 multiscale modes:\n\n    - ``ratio_range is not None``: randomly sample a ratio from the ratio \\\n      range and multiply it with the image scale.\n    - ``ratio_range is None`` and ``multiscale_mode == \"range\"``: randomly \\\n      sample a scale from the multiscale range.\n    - ``ratio_range is None`` and ``multiscale_mode == \"value\"``: randomly \\\n      sample a scale from multiple scales.\n\n    Args:\n        img_scale (tuple or list[tuple]): Images scales for resizing.\n        multiscale_mode (str): Either \"range\" or \"value\".\n        ratio_range (tuple[float]): (min_ratio, max_ratio)\n        keep_ratio (bool): Whether to keep the aspect ratio when resizing the\n            image.\n        bbox_clip_border (bool, optional): Whether clip the objects outside\n            the border of the image. Defaults to True.\n        backend (str): Image resize backend, choices are 'cv2' and 'pillow'.\n            These two backends generates slightly different results. Defaults\n            to 'cv2'.\n        override (bool, optional): Whether to override `scale` and\n            `scale_factor` so as to call resize twice. Default False. If True,\n            after the first resizing, the existed `scale` and `scale_factor`\n            will be ignored so the second resizing can be allowed.\n            This option is a work-around for multiple times of resize in DETR.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self,\n                 img_scale=None,\n                 multiscale_mode='range',\n                 ratio_range=None,\n                 keep_ratio=True,\n                 bbox_clip_border=True,\n                 backend='cv2',\n                 override=False):\n        if img_scale is None:\n            self.img_scale = None\n        else:\n            if isinstance(img_scale, list):\n                self.img_scale = img_scale\n            else:\n                self.img_scale = [img_scale]\n            assert is_list_of(self.img_scale, tuple)\n\n        if ratio_range is not None:\n            # mode 1: given a scale and a range of image ratio\n            assert len(self.img_scale) == 1\n        else:\n            # mode 2: given multiple scales or a range of scales\n            assert multiscale_mode in ['value', 'range']\n\n        self.backend = backend\n        self.multiscale_mode = multiscale_mode\n        self.ratio_range = ratio_range\n        self.keep_ratio = keep_ratio\n        # TODO: refactor the override option in Resize\n        self.override = override\n        self.bbox_clip_border = bbox_clip_border\n\n    @staticmethod\n    def random_select(img_scales):\n        \"\"\"Randomly select an img_scale from given candidates.\n\n        Args:\n            img_scales (list[tuple]): Images scales for selection.\n\n        Returns:\n            (tuple, int): Returns a tuple ``(img_scale, scale_dix)``, \\\n                where ``img_scale`` is the selected image scale and \\\n                ``scale_idx`` is the selected index in the given candidates.\n        \"\"\"\n\n        assert is_list_of(img_scales, tuple)\n        scale_idx = np.random.randint(len(img_scales))\n        img_scale = img_scales[scale_idx]\n        return img_scale, scale_idx\n\n    @staticmethod\n    def random_sample(img_scales):\n        \"\"\"Randomly sample an img_scale when ``multiscale_mode=='range'``.\n\n        Args:\n            img_scales (list[tuple]): Images scale range for sampling.\n                There must be two tuples in img_scales, which specify the lower\n                and upper bound of image scales.\n\n        Returns:\n            (tuple, None): Returns a tuple ``(img_scale, None)``, where \\\n                ``img_scale`` is sampled scale and None is just a placeholder \\\n                to be consistent with :func:`random_select`.\n        \"\"\"\n\n        assert is_list_of(img_scales, tuple) and len(img_scales) == 2\n        img_scale_long = [max(s) for s in img_scales]\n        img_scale_short = [min(s) for s in img_scales]\n        long_edge = np.random.randint(\n            min(img_scale_long),\n            max(img_scale_long) + 1)\n        short_edge = np.random.randint(\n            min(img_scale_short),\n            max(img_scale_short) + 1)\n        img_scale = (long_edge, short_edge)\n        return img_scale, None\n\n    @staticmethod\n    def random_sample_ratio(img_scale, ratio_range):\n        \"\"\"Randomly sample an img_scale when ``ratio_range`` is specified.\n\n        A ratio will be randomly sampled from the range specified by\n        ``ratio_range``. Then it would be multiplied with ``img_scale`` to\n        generate sampled scale.\n\n        Args:\n            img_scale (tuple): Images scale base to multiply with ratio.\n            ratio_range (tuple[float]): The minimum and maximum ratio to scale\n                the ``img_scale``.\n\n        Returns:\n            (tuple, None): Returns a tuple ``(scale, None)``, where \\\n                ``scale`` is sampled ratio multiplied with ``img_scale`` and \\\n                None is just a placeholder to be consistent with \\\n                :func:`random_select`.\n        \"\"\"\n\n        assert isinstance(img_scale, tuple) and len(img_scale) == 2\n        min_ratio, max_ratio = ratio_range\n        assert min_ratio <= max_ratio\n        ratio = np.random.random_sample() * (max_ratio - min_ratio) + min_ratio\n        scale = int(img_scale[0] * ratio), int(img_scale[1] * ratio)\n        return scale, None\n\n    def _random_scale(self, results):\n        \"\"\"Randomly sample an img_scale according to ``ratio_range`` and\n        ``multiscale_mode``.\n\n        If ``ratio_range`` is specified, a ratio will be sampled and be\n        multiplied with ``img_scale``.\n        If multiple scales are specified by ``img_scale``, a scale will be\n        sampled according to ``multiscale_mode``.\n        Otherwise, single scale will be used.\n\n        Args:\n            results (dict): Result dict from :obj:`dataset`.\n\n        Returns:\n            dict: Two new keys 'scale` and 'scale_idx` are added into \\\n                ``results``, which would be used by subsequent pipelines.\n        \"\"\"\n\n        if self.ratio_range is not None:\n            scale, scale_idx = self.random_sample_ratio(\n                self.img_scale[0], self.ratio_range)\n        elif len(self.img_scale) == 1:\n            scale, scale_idx = self.img_scale[0], 0\n        elif self.multiscale_mode == 'range':\n            scale, scale_idx = self.random_sample(self.img_scale)\n        elif self.multiscale_mode == 'value':\n            scale, scale_idx = self.random_select(self.img_scale)\n        else:\n            raise NotImplementedError\n\n        results['scale'] = scale\n        results['scale_idx'] = scale_idx\n\n    def _resize_img(self, results):\n        \"\"\"Resize images with ``results['scale']``.\"\"\"\n        for key in results.get('img_fields', ['img']):\n            if self.keep_ratio:\n                img, scale_factor = imrescale(\n                    results[key],\n                    results['scale'],\n                    return_scale=True,\n                    backend=self.backend)\n                # the w_scale and h_scale has minor difference\n                # a real fix should be done in the mmcv.imrescale in the future\n                new_h, new_w = img.shape[:2]\n                h, w = results[key].shape[:2]\n                w_scale = new_w / w\n                h_scale = new_h / h\n            else:\n                img, w_scale, h_scale = imresize(\n                    results[key],\n                    results['scale'],\n                    return_scale=True,\n                    backend=self.backend)\n            results[key] = img\n\n            scale_factor = np.array([w_scale, h_scale, w_scale, h_scale],\n                                    dtype=np.float32)\n            results['img_shape'] = img.shape\n            # in case that there is no padding\n            results['pad_shape'] = img.shape\n            results['scale_factor'] = scale_factor\n            results['keep_ratio'] = self.keep_ratio\n\n    def _resize_bboxes(self, results):\n        \"\"\"Resize bounding boxes with ``results['scale_factor']``.\"\"\"\n        for key in results.get('bbox_fields', []):\n            bboxes = results[key] * results['scale_factor']\n            if self.bbox_clip_border:\n                img_shape = results['img_shape']\n                bboxes[:, 0::2] = np.clip(bboxes[:, 0::2], 0, img_shape[1])\n                bboxes[:, 1::2] = np.clip(bboxes[:, 1::2], 0, img_shape[0])\n            results[key] = bboxes\n\n    def _resize_masks(self, results):\n        \"\"\"Resize masks with ``results['scale']``\"\"\"\n        for key in results.get('mask_fields', []):\n            if results[key] is None:\n                continue\n            if self.keep_ratio:\n                results[key] = results[key].rescale(results['scale'])\n            else:\n                results[key] = results[key].resize(results['img_shape'][:2])\n\n    def _resize_seg(self, results):\n        \"\"\"Resize semantic segmentation map with ``results['scale']``.\"\"\"\n        for key in results.get('seg_fields', []):\n            if self.keep_ratio:\n                gt_seg = imrescale(\n                    results[key],\n                    results['scale'],\n                    interpolation='nearest',\n                    backend=self.backend)\n            else:\n                gt_seg = imresize(\n                    results[key],\n                    results['scale'],\n                    interpolation='nearest',\n                    backend=self.backend)\n            results['gt_semantic_seg'] = gt_seg\n\n    def __call__(self, results):\n        \"\"\"Call function to resize images, bounding boxes, masks, semantic\n        segmentation map.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Resized results, 'img_shape', 'pad_shape', 'scale_factor', \\\n                'keep_ratio' keys are added into result dict.\n        \"\"\"\n\n        if 'scale' not in results:\n            if 'scale_factor' in results:\n                img_shape = results['img'].shape[:2]\n                scale_factor = results['scale_factor']\n                assert isinstance(scale_factor, float)\n                results['scale'] = tuple(\n                    [int(x * scale_factor) for x in img_shape][::-1])\n            else:\n                self._random_scale(results)\n        else:\n            if not self.override:\n                assert 'scale_factor' not in results, (\n                    'scale and scale_factor cannot be both set.')\n            else:\n                results.pop('scale')\n                if 'scale_factor' in results:\n                    results.pop('scale_factor')\n                self._random_scale(results)\n\n        self._resize_img(results)\n        self._resize_bboxes(results)\n        self._resize_masks(results)\n        self._resize_seg(results)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(img_scale={self.img_scale}, '\n        repr_str += f'multiscale_mode={self.multiscale_mode}, '\n        repr_str += f'ratio_range={self.ratio_range}, '\n        repr_str += f'keep_ratio={self.keep_ratio}, '\n        repr_str += f'bbox_clip_border={self.bbox_clip_border})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass RandomFlip:\n    \"\"\"Flip the image & bbox & mask.\n\n    If the input dict contains the key \"flip\", then the flag will be used,\n    otherwise it will be randomly decided by a ratio specified in the init\n    method.\n\n    When random flip is enabled, ``flip_ratio``/``direction`` can either be a\n    float/string or tuple of float/string. There are 3 flip modes:\n\n    - ``flip_ratio`` is float, ``direction`` is string: the image will be\n        ``direction``ly flipped with probability of ``flip_ratio`` .\n        E.g., ``flip_ratio=0.5``, ``direction='horizontal'``,\n        then image will be horizontally flipped with probability of 0.5.\n    - ``flip_ratio`` is float, ``direction`` is list of string: the image wil\n        be ``direction[i]``ly flipped with probability of\n        ``flip_ratio/len(direction)``.\n        E.g., ``flip_ratio=0.5``, ``direction=['horizontal', 'vertical']``,\n        then image will be horizontally flipped with probability of 0.25,\n        vertically with probability of 0.25.\n    - ``flip_ratio`` is list of float, ``direction`` is list of string:\n        given ``len(flip_ratio) == len(direction)``, the image wil\n        be ``direction[i]``ly flipped with probability of ``flip_ratio[i]``.\n        E.g., ``flip_ratio=[0.3, 0.5]``, ``direction=['horizontal',\n        'vertical']``, then image will be horizontally flipped with probability\n         of 0.3, vertically with probability of 0.5\n\n    Args:\n        flip_ratio (float | list[float], optional): The flipping probability.\n            Default: None.\n        direction(str | list[str], optional): The flipping direction. Options\n            are 'horizontal', 'vertical', 'diagonal'. Default: 'horizontal'.\n            If input is a list, the length must equal ``flip_ratio``. Each\n            element in ``flip_ratio`` indicates the flip probability of\n            corresponding direction.\n    \"\"\"\n\n    def __init__(self, flip_ratio=None, direction='horizontal'):\n        if isinstance(flip_ratio, list):\n            assert is_list_of(flip_ratio, float)\n            assert 0 <= sum(flip_ratio) <= 1\n        elif isinstance(flip_ratio, float):\n            assert 0 <= flip_ratio <= 1\n        elif flip_ratio is None:\n            pass\n        else:\n            raise ValueError('flip_ratios must be None, float, '\n                             'or list of float')\n        self.flip_ratio = flip_ratio\n\n        valid_directions = ['horizontal', 'vertical', 'diagonal']\n        if isinstance(direction, str):\n            assert direction in valid_directions\n        elif isinstance(direction, list):\n            assert is_list_of(direction, str)\n            assert set(direction).issubset(set(valid_directions))\n        else:\n            raise ValueError('direction must be either str or list of str')\n        self.direction = direction\n\n        if isinstance(flip_ratio, list):\n            assert len(self.flip_ratio) == len(self.direction)\n\n    def bbox_flip(self, bboxes, img_shape, direction):\n        \"\"\"Flip bboxes horizontally.\n\n        Args:\n            bboxes (numpy.ndarray): Bounding boxes, shape (..., 4*k)\n            img_shape (tuple[int]): Image shape (height, width)\n            direction (str): Flip direction. Options are 'horizontal',\n                'vertical'.\n\n        Returns:\n            numpy.ndarray: Flipped bounding boxes.\n        \"\"\"\n\n        assert bboxes.shape[-1] % 4 == 0\n        flipped = bboxes.copy()\n        if direction == 'horizontal':\n            w = img_shape[1]\n            flipped[..., 0::4] = w - bboxes[..., 2::4]\n            flipped[..., 2::4] = w - bboxes[..., 0::4]\n        elif direction == 'vertical':\n            h = img_shape[0]\n            flipped[..., 1::4] = h - bboxes[..., 3::4]\n            flipped[..., 3::4] = h - bboxes[..., 1::4]\n        elif direction == 'diagonal':\n            w = img_shape[1]\n            h = img_shape[0]\n            flipped[..., 0::4] = w - bboxes[..., 2::4]\n            flipped[..., 1::4] = h - bboxes[..., 3::4]\n            flipped[..., 2::4] = w - bboxes[..., 0::4]\n            flipped[..., 3::4] = h - bboxes[..., 1::4]\n        else:\n            raise ValueError(f\"Invalid flipping direction '{direction}'\")\n        return flipped\n\n    def __call__(self, results):\n        \"\"\"Call function to flip bounding boxes, masks, semantic segmentation\n        maps.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Flipped results, 'flip', 'flip_direction' keys are added \\\n                into result dict.\n        \"\"\"\n\n        if 'flip' not in results:\n            if isinstance(self.direction, list):\n                # None means non-flip\n                direction_list = self.direction + [None]\n            else:\n                # None means non-flip\n                direction_list = [self.direction, None]\n\n            if isinstance(self.flip_ratio, list):\n                non_flip_ratio = 1 - sum(self.flip_ratio)\n                flip_ratio_list = self.flip_ratio + [non_flip_ratio]\n            else:\n                non_flip_ratio = 1 - self.flip_ratio\n                # exclude non-flip\n                single_ratio = self.flip_ratio / (len(direction_list) - 1)\n                flip_ratio_list = [single_ratio] * (len(direction_list) -\n                                                    1) + [non_flip_ratio]\n\n            cur_dir = np.random.choice(direction_list, p=flip_ratio_list)\n\n            results['flip'] = cur_dir is not None\n        if 'flip_direction' not in results:\n            results['flip_direction'] = cur_dir\n        if results['flip']:\n            # flip image\n            for key in results.get('img_fields', ['img']):\n                results[key] = imflip(\n                    results[key], direction=results['flip_direction'])\n            # flip bboxes\n            for key in results.get('bbox_fields', []):\n                results[key] = self.bbox_flip(results[key],\n                                              results['img_shape'],\n                                              results['flip_direction'])\n            # flip masks\n            for key in results.get('mask_fields', []):\n                results[key] = results[key].flip(results['flip_direction'])\n\n            # flip segs\n            for key in results.get('seg_fields', []):\n                results[key] = imflip(\n                    results[key], direction=results['flip_direction'])\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + f'(flip_ratio={self.flip_ratio})'\n\n\n@PIPELINES.register_module()\nclass RandomShift:\n    \"\"\"Shift the image and box given shift pixels and probability.\n\n    Args:\n        shift_ratio (float): Probability of shifts. Default 0.5.\n        max_shift_px (int): The max pixels for shifting. Default 32.\n        filter_thr_px (int): The width and height threshold for filtering.\n            The bbox and the rest of the targets below the width and\n            height threshold will be filtered. Default 1.\n    \"\"\"\n\n    def __init__(self, shift_ratio=0.5, max_shift_px=32, filter_thr_px=1):\n        assert 0 <= shift_ratio <= 1\n        assert max_shift_px >= 0\n        self.shift_ratio = shift_ratio\n        self.max_shift_px = max_shift_px\n        self.filter_thr_px = int(filter_thr_px)\n        # The key correspondence from bboxes to labels.\n        self.bbox2label = {\n            'gt_bboxes': 'gt_labels',\n            'gt_bboxes_ignore': 'gt_labels_ignore'\n        }\n\n    def __call__(self, results):\n        \"\"\"Call function to random shift images, bounding boxes.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Shift results.\n        \"\"\"\n        if random.random() < self.shift_ratio:\n            img_shape = results['img'].shape[:2]\n\n            random_shift_x = random.randint(-self.max_shift_px,\n                                            self.max_shift_px)\n            random_shift_y = random.randint(-self.max_shift_px,\n                                            self.max_shift_px)\n            new_x = max(0, random_shift_x)\n            orig_x = max(0, -random_shift_x)\n            new_y = max(0, random_shift_y)\n            orig_y = max(0, -random_shift_y)\n\n            # TODO: support mask and semantic segmentation maps.\n            for key in results.get('bbox_fields', []):\n                bboxes = results[key].copy()\n                bboxes[..., 0::2] += random_shift_x\n                bboxes[..., 1::2] += random_shift_y\n\n                # clip border\n                bboxes[..., 0::2] = np.clip(bboxes[..., 0::2], 0, img_shape[1])\n                bboxes[..., 1::2] = np.clip(bboxes[..., 1::2], 0, img_shape[0])\n\n                # remove invalid bboxes\n                bbox_w = bboxes[..., 2] - bboxes[..., 0]\n                bbox_h = bboxes[..., 3] - bboxes[..., 1]\n                valid_inds = (bbox_w > self.filter_thr_px) & (\n                    bbox_h > self.filter_thr_px)\n                # If the shift does not contain any gt-bbox area, skip this\n                # image.\n                if key == 'gt_bboxes' and not valid_inds.any():\n                    return results\n                bboxes = bboxes[valid_inds]\n                results[key] = bboxes\n\n                # label fields. e.g. gt_labels and gt_labels_ignore\n                label_key = self.bbox2label.get(key)\n                if label_key in results:\n                    results[label_key] = results[label_key][valid_inds]\n\n            for key in results.get('img_fields', ['img']):\n                img = results[key]\n                new_img = np.zeros_like(img)\n                img_h, img_w = img.shape[:2]\n                new_h = img_h - np.abs(random_shift_y)\n                new_w = img_w - np.abs(random_shift_x)\n                new_img[new_y:new_y + new_h, new_x:new_x + new_w] \\\n                    = img[orig_y:orig_y + new_h, orig_x:orig_x + new_w]\n                results[key] = new_img\n\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(max_shift_px={self.max_shift_px}, '\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass Pad:\n    \"\"\"Pad the image & mask.\n\n    There are two padding modes: (1) pad to a fixed size and (2) pad to the\n    minimum size that is divisible by some number.\n    Added keys are \"pad_shape\", \"pad_fixed_size\", \"pad_size_divisor\",\n\n    Args:\n        size (tuple, optional): Fixed padding size.\n        size_divisor (int, optional): The divisor of padded size.\n        pad_val (float, optional): Padding value, 0 by default.\n    \"\"\"\n\n    def __init__(self, size=None, size_divisor=None, pad_val=0):\n        self.size = size\n        self.size_divisor = size_divisor\n        self.pad_val = pad_val\n        # only one of size and size_divisor should be valid\n        assert size is not None or size_divisor is not None\n        assert size is None or size_divisor is None\n\n    def _pad_img(self, results):\n        \"\"\"Pad images according to ``self.size``.\"\"\"\n        for key in results.get('img_fields', ['img']):\n            if self.size is not None:\n                padded_img = impad(\n                    results[key], shape=self.size, pad_val=self.pad_val)\n            elif self.size_divisor is not None:\n                padded_img = impad_to_multiple(\n                    results[key], self.size_divisor, pad_val=self.pad_val)\n            results[key] = padded_img\n        results['pad_shape'] = padded_img.shape\n        results['pad_fixed_size'] = self.size\n        results['pad_size_divisor'] = self.size_divisor\n\n    def _pad_masks(self, results):\n        \"\"\"Pad masks according to ``results['pad_shape']``.\"\"\"\n        pad_shape = results['pad_shape'][:2]\n        for key in results.get('mask_fields', []):\n            results[key] = results[key].pad(pad_shape, pad_val=self.pad_val)\n\n    def _pad_seg(self, results):\n        \"\"\"Pad semantic segmentation map according to\n        ``results['pad_shape']``.\"\"\"\n        for key in results.get('seg_fields', []):\n            results[key] = impad(\n                results[key], shape=results['pad_shape'][:2])\n\n    def __call__(self, results):\n        \"\"\"Call function to pad images, masks, semantic segmentation maps.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Updated result dict.\n        \"\"\"\n        self._pad_img(results)\n        self._pad_masks(results)\n        self._pad_seg(results)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(size={self.size}, '\n        repr_str += f'size_divisor={self.size_divisor}, '\n        repr_str += f'pad_val={self.pad_val})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass Normalize:\n    \"\"\"Normalize the image.\n\n    Added key is \"img_norm_cfg\".\n\n    Args:\n        mean (sequence): Mean values of 3 channels.\n        std (sequence): Std values of 3 channels.\n        to_rgb (bool): Whether to convert the image from BGR to RGB,\n            default is true.\n    \"\"\"\n\n    def __init__(self, mean, std, to_rgb=True):\n        self.mean = np.array(mean, dtype=np.float32)\n        self.std = np.array(std, dtype=np.float32)\n        self.to_rgb = to_rgb\n\n    def __call__(self, results):\n        \"\"\"Call function to normalize images.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Normalized results, 'img_norm_cfg' key is added into\n                result dict.\n        \"\"\"\n        for key in results.get('img_fields', ['img']):\n            results[key] = imnormalize(results[key], self.mean, self.std,\n                                            self.to_rgb)\n        results['img_norm_cfg'] = dict(\n            mean=self.mean, std=self.std, to_rgb=self.to_rgb)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(mean={self.mean}, std={self.std}, to_rgb={self.to_rgb})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass RandomCrop:\n    \"\"\"Random crop the image & bboxes & masks.\n\n    The absolute `crop_size` is sampled based on `crop_type` and `image_size`,\n    then the cropped results are generated.\n\n    Args:\n        crop_size (tuple): The relative ratio or absolute pixels of\n            height and width.\n        crop_type (str, optional): one of \"relative_range\", \"relative\",\n            \"absolute\", \"absolute_range\". \"relative\" randomly crops\n            (h * crop_size[0], w * crop_size[1]) part from an input of size\n            (h, w). \"relative_range\" uniformly samples relative crop size from\n            range [crop_size[0], 1] and [crop_size[1], 1] for height and width\n            respectively. \"absolute\" crops from an input with absolute size\n            (crop_size[0], crop_size[1]). \"absolute_range\" uniformly samples\n            crop_h in range [crop_size[0], min(h, crop_size[1])] and crop_w\n            in range [crop_size[0], min(w, crop_size[1])]. Default \"absolute\".\n        allow_negative_crop (bool, optional): Whether to allow a crop that does\n            not contain any bbox area. Default False.\n        bbox_clip_border (bool, optional): Whether clip the objects outside\n            the border of the image. Defaults to True.\n\n    Note:\n        - If the image is smaller than the absolute crop size, return the\n            original image.\n        - The keys for bboxes, labels and masks must be aligned. That is,\n          `gt_bboxes` corresponds to `gt_labels` and `gt_masks`, and\n          `gt_bboxes_ignore` corresponds to `gt_labels_ignore` and\n          `gt_masks_ignore`.\n        - If the crop does not contain any gt-bbox region and\n          `allow_negative_crop` is set to False, skip this image.\n    \"\"\"\n\n    def __init__(self,\n                 crop_size,\n                 crop_type='absolute',\n                 allow_negative_crop=False,\n                 bbox_clip_border=True):\n        if crop_type not in [\n                'relative_range', 'relative', 'absolute', 'absolute_range'\n        ]:\n            raise ValueError(f'Invalid crop_type {crop_type}.')\n        if crop_type in ['absolute', 'absolute_range']:\n            assert crop_size[0] > 0 and crop_size[1] > 0\n            assert isinstance(crop_size[0], int) and isinstance(\n                crop_size[1], int)\n        else:\n            assert 0 < crop_size[0] <= 1 and 0 < crop_size[1] <= 1\n        self.crop_size = crop_size\n        self.crop_type = crop_type\n        self.allow_negative_crop = allow_negative_crop\n        self.bbox_clip_border = bbox_clip_border\n        # The key correspondence from bboxes to labels and masks.\n        self.bbox2label = {\n            'gt_bboxes': 'gt_labels',\n            'gt_bboxes_ignore': 'gt_labels_ignore'\n        }\n        self.bbox2mask = {\n            'gt_bboxes': 'gt_masks',\n            'gt_bboxes_ignore': 'gt_masks_ignore'\n        }\n\n    def _crop_data(self, results, crop_size, allow_negative_crop):\n        \"\"\"Function to randomly crop images, bounding boxes, masks, semantic\n        segmentation maps.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n            crop_size (tuple): Expected absolute size after cropping, (h, w).\n            allow_negative_crop (bool): Whether to allow a crop that does not\n                contain any bbox area. Default to False.\n\n        Returns:\n            dict: Randomly cropped results, 'img_shape' key in result dict is\n                updated according to crop size.\n        \"\"\"\n        assert crop_size[0] > 0 and crop_size[1] > 0\n        for key in results.get('img_fields', ['img']):\n            img = results[key]\n            margin_h = max(img.shape[0] - crop_size[0], 0)\n            margin_w = max(img.shape[1] - crop_size[1], 0)\n            offset_h = np.random.randint(0, margin_h + 1)\n            offset_w = np.random.randint(0, margin_w + 1)\n            crop_y1, crop_y2 = offset_h, offset_h + crop_size[0]\n            crop_x1, crop_x2 = offset_w, offset_w + crop_size[1]\n\n            # crop the image\n            img = img[crop_y1:crop_y2, crop_x1:crop_x2, ...]\n            img_shape = img.shape\n            results[key] = img\n        results['img_shape'] = img_shape\n\n        # crop bboxes accordingly and clip to the image boundary\n        for key in results.get('bbox_fields', []):\n            # e.g. gt_bboxes and gt_bboxes_ignore\n            bbox_offset = np.array([offset_w, offset_h, offset_w, offset_h],\n                                   dtype=np.float32)\n            bboxes = results[key] - bbox_offset\n            if self.bbox_clip_border:\n                bboxes[:, 0::2] = np.clip(bboxes[:, 0::2], 0, img_shape[1])\n                bboxes[:, 1::2] = np.clip(bboxes[:, 1::2], 0, img_shape[0])\n            valid_inds = (bboxes[:, 2] > bboxes[:, 0]) & (\n                bboxes[:, 3] > bboxes[:, 1])\n            # If the crop does not contain any gt-bbox area and\n            # allow_negative_crop is False, skip this image.\n            if (key == 'gt_bboxes' and not valid_inds.any()\n                    and not allow_negative_crop):\n                return None\n            results[key] = bboxes[valid_inds, :]\n            # label fields. e.g. gt_labels and gt_labels_ignore\n            label_key = self.bbox2label.get(key)\n            if label_key in results:\n                results[label_key] = results[label_key][valid_inds]\n\n            # mask fields, e.g. gt_masks and gt_masks_ignore\n            mask_key = self.bbox2mask.get(key)\n            if mask_key in results:\n                results[mask_key] = results[mask_key][\n                    valid_inds.nonzero()[0]].crop(\n                        np.asarray([crop_x1, crop_y1, crop_x2, crop_y2]))\n\n        # crop semantic seg\n        for key in results.get('seg_fields', []):\n            results[key] = results[key][crop_y1:crop_y2, crop_x1:crop_x2]\n\n        return results\n\n    def _get_crop_size(self, image_size):\n        \"\"\"Randomly generates the absolute crop size based on `crop_type` and\n        `image_size`.\n\n        Args:\n            image_size (tuple): (h, w).\n\n        Returns:\n            crop_size (tuple): (crop_h, crop_w) in absolute pixels.\n        \"\"\"\n        h, w = image_size\n        if self.crop_type == 'absolute':\n            return (min(self.crop_size[0], h), min(self.crop_size[1], w))\n        elif self.crop_type == 'absolute_range':\n            assert self.crop_size[0] <= self.crop_size[1]\n            crop_h = np.random.randint(\n                min(h, self.crop_size[0]),\n                min(h, self.crop_size[1]) + 1)\n            crop_w = np.random.randint(\n                min(w, self.crop_size[0]),\n                min(w, self.crop_size[1]) + 1)\n            return crop_h, crop_w\n        elif self.crop_type == 'relative':\n            crop_h, crop_w = self.crop_size\n            return int(h * crop_h + 0.5), int(w * crop_w + 0.5)\n        elif self.crop_type == 'relative_range':\n            crop_size = np.asarray(self.crop_size, dtype=np.float32)\n            crop_h, crop_w = crop_size + np.random.rand(2) * (1 - crop_size)\n            return int(h * crop_h + 0.5), int(w * crop_w + 0.5)\n\n    def __call__(self, results):\n        \"\"\"Call function to randomly crop images, bounding boxes, masks,\n        semantic segmentation maps.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Randomly cropped results, 'img_shape' key in result dict is\n                updated according to crop size.\n        \"\"\"\n        image_size = results['img'].shape[:2]\n        crop_size = self._get_crop_size(image_size)\n        results = self._crop_data(results, crop_size, self.allow_negative_crop)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(crop_size={self.crop_size}, '\n        repr_str += f'crop_type={self.crop_type}, '\n        repr_str += f'allow_negative_crop={self.allow_negative_crop}, '\n        repr_str += f'bbox_clip_border={self.bbox_clip_border})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass SegRescale:\n    \"\"\"Rescale semantic segmentation maps.\n\n    Args:\n        scale_factor (float): The scale factor of the final output.\n        backend (str): Image rescale backend, choices are 'cv2' and 'pillow'.\n            These two backends generates slightly different results. Defaults\n            to 'cv2'.\n    \"\"\"\n\n    def __init__(self, scale_factor=1, backend='cv2'):\n        self.scale_factor = scale_factor\n        self.backend = backend\n\n    def __call__(self, results):\n        \"\"\"Call function to scale the semantic segmentation map.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Result dict with semantic segmentation map scaled.\n        \"\"\"\n\n        for key in results.get('seg_fields', []):\n            if self.scale_factor != 1:\n                results[key] = imrescale(\n                    results[key],\n                    self.scale_factor,\n                    interpolation='nearest',\n                    backend=self.backend)\n        return results\n\n    def __repr__(self):\n        return self.__class__.__name__ + f'(scale_factor={self.scale_factor})'\n\n\n@PIPELINES.register_module()\nclass PhotoMetricDistortion:\n    \"\"\"Apply photometric distortion to image sequentially, every transformation\n    is applied with a probability of 0.5. The position of random contrast is in\n    second or second to last.\n\n    1. random brightness\n    2. random contrast (mode 0)\n    3. convert color from BGR to HSV\n    4. random saturation\n    5. random hue\n    6. convert color from HSV to BGR\n    7. random contrast (mode 1)\n    8. randomly swap channels\n\n    Args:\n        brightness_delta (int): delta of brightness.\n        contrast_range (tuple): range of contrast.\n        saturation_range (tuple): range of saturation.\n        hue_delta (int): delta of hue.\n    \"\"\"\n\n    def __init__(self,\n                 brightness_delta=32,\n                 contrast_range=(0.5, 1.5),\n                 saturation_range=(0.5, 1.5),\n                 hue_delta=18):\n        self.brightness_delta = brightness_delta\n        self.contrast_lower, self.contrast_upper = contrast_range\n        self.saturation_lower, self.saturation_upper = saturation_range\n        self.hue_delta = hue_delta\n\n    def __call__(self, results):\n        \"\"\"Call function to perform photometric distortion on images.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Result dict with images distorted.\n        \"\"\"\n\n        if 'img_fields' in results:\n            assert results['img_fields'] == ['img'], \\\n                'Only single img_fields is allowed'\n        img = results['img']\n        assert img.dtype == np.float32, \\\n            'PhotoMetricDistortion needs the input image of dtype np.float32,'\\\n            ' please set \"to_float32=True\" in \"LoadImageFromFile\" pipeline'\n        # random brightness\n        if random.randint(2):\n            delta = random.uniform(-self.brightness_delta,\n                                   self.brightness_delta)\n            img += delta\n\n        # mode == 0 --> do random contrast first\n        # mode == 1 --> do random contrast last\n        mode = random.randint(2)\n        if mode == 1:\n            if random.randint(2):\n                alpha = random.uniform(self.contrast_lower,\n                                       self.contrast_upper)\n                img *= alpha\n\n        # convert color from BGR to HSV\n        img = bgr2hsv(img)\n\n        # random saturation\n        if random.randint(2):\n            img[..., 1] *= random.uniform(self.saturation_lower,\n                                          self.saturation_upper)\n\n        # random hue\n        if random.randint(2):\n            img[..., 0] += random.uniform(-self.hue_delta, self.hue_delta)\n            img[..., 0][img[..., 0] > 360] -= 360\n            img[..., 0][img[..., 0] < 0] += 360\n\n        # convert color from HSV to BGR\n        img = hsv2bgr(img)\n\n        # random contrast\n        if mode == 0:\n            if random.randint(2):\n                alpha = random.uniform(self.contrast_lower,\n                                       self.contrast_upper)\n                img *= alpha\n\n        # randomly swap channels\n        if random.randint(2):\n            img = img[..., random.permutation(3)]\n\n        results['img'] = img\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(\\nbrightness_delta={self.brightness_delta},\\n'\n        repr_str += 'contrast_range='\n        repr_str += f'{(self.contrast_lower, self.contrast_upper)},\\n'\n        repr_str += 'saturation_range='\n        repr_str += f'{(self.saturation_lower, self.saturation_upper)},\\n'\n        repr_str += f'hue_delta={self.hue_delta})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass Expand:\n    \"\"\"Random expand the image & bboxes.\n\n    Randomly place the original image on a canvas of 'ratio' x original image\n    size filled with mean values. The ratio is in the range of ratio_range.\n\n    Args:\n        mean (tuple): mean value of dataset.\n        to_rgb (bool): if need to convert the order of mean to align with RGB.\n        ratio_range (tuple): range of expand ratio.\n        prob (float): probability of applying this transformation\n    \"\"\"\n\n    def __init__(self,\n                 mean=(0, 0, 0),\n                 to_rgb=True,\n                 ratio_range=(1, 4),\n                 seg_ignore_label=None,\n                 prob=0.5):\n        self.to_rgb = to_rgb\n        self.ratio_range = ratio_range\n        if to_rgb:\n            self.mean = mean[::-1]\n        else:\n            self.mean = mean\n        self.min_ratio, self.max_ratio = ratio_range\n        self.seg_ignore_label = seg_ignore_label\n        self.prob = prob\n\n    def __call__(self, results):\n        \"\"\"Call function to expand images, bounding boxes.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Result dict with images, bounding boxes expanded\n        \"\"\"\n\n        if random.uniform(0, 1) > self.prob:\n            return results\n\n        if 'img_fields' in results:\n            assert results['img_fields'] == ['img'], \\\n                'Only single img_fields is allowed'\n        img = results['img']\n\n        h, w, c = img.shape\n        ratio = random.uniform(self.min_ratio, self.max_ratio)\n        # speedup expand when meets large image\n        if np.all(self.mean == self.mean[0]):\n            expand_img = np.empty((int(h * ratio), int(w * ratio), c),\n                                  img.dtype)\n            expand_img.fill(self.mean[0])\n        else:\n            expand_img = np.full((int(h * ratio), int(w * ratio), c),\n                                 self.mean,\n                                 dtype=img.dtype)\n        left = int(random.uniform(0, w * ratio - w))\n        top = int(random.uniform(0, h * ratio - h))\n        expand_img[top:top + h, left:left + w] = img\n\n        results['img'] = expand_img\n        # expand bboxes\n        for key in results.get('bbox_fields', []):\n            results[key] = results[key] + np.tile(\n                (left, top), 2).astype(results[key].dtype)\n\n        # expand masks\n        for key in results.get('mask_fields', []):\n            results[key] = results[key].expand(\n                int(h * ratio), int(w * ratio), top, left)\n\n        # expand segs\n        for key in results.get('seg_fields', []):\n            gt_seg = results[key]\n            expand_gt_seg = np.full((int(h * ratio), int(w * ratio)),\n                                    self.seg_ignore_label,\n                                    dtype=gt_seg.dtype)\n            expand_gt_seg[top:top + h, left:left + w] = gt_seg\n            results[key] = expand_gt_seg\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(mean={self.mean}, to_rgb={self.to_rgb}, '\n        repr_str += f'ratio_range={self.ratio_range}, '\n        repr_str += f'seg_ignore_label={self.seg_ignore_label})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass MinIoURandomCrop:\n    \"\"\"Random crop the image & bboxes, the cropped patches have minimum IoU\n    requirement with original image & bboxes, the IoU threshold is randomly\n    selected from min_ious.\n\n    Args:\n        min_ious (tuple): minimum IoU threshold for all intersections with\n        bounding boxes\n        min_crop_size (float): minimum crop's size (i.e. h,w := a*h, a*w,\n        where a >= min_crop_size).\n        bbox_clip_border (bool, optional): Whether clip the objects outside\n            the border of the image. Defaults to True.\n\n    Note:\n        The keys for bboxes, labels and masks should be paired. That is, \\\n        `gt_bboxes` corresponds to `gt_labels` and `gt_masks`, and \\\n        `gt_bboxes_ignore` to `gt_labels_ignore` and `gt_masks_ignore`.\n    \"\"\"\n\n    def __init__(self,\n                 min_ious=(0.1, 0.3, 0.5, 0.7, 0.9),\n                 min_crop_size=0.3,\n                 bbox_clip_border=True):\n        # 1: return ori img\n        self.min_ious = min_ious\n        self.sample_mode = (1, *min_ious, 0)\n        self.min_crop_size = min_crop_size\n        self.bbox_clip_border = bbox_clip_border\n        self.bbox2label = {\n            'gt_bboxes': 'gt_labels',\n            'gt_bboxes_ignore': 'gt_labels_ignore'\n        }\n        self.bbox2mask = {\n            'gt_bboxes': 'gt_masks',\n            'gt_bboxes_ignore': 'gt_masks_ignore'\n        }\n\n    def __call__(self, results):\n        \"\"\"Call function to crop images and bounding boxes with minimum IoU\n        constraint.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Result dict with images and bounding boxes cropped, \\\n                'img_shape' key is updated.\n        \"\"\"\n\n        if 'img_fields' in results:\n            assert results['img_fields'] == ['img'], \\\n                'Only single img_fields is allowed'\n        img = results['img']\n        assert 'bbox_fields' in results\n        boxes = [results[key] for key in results['bbox_fields']]\n        boxes = np.concatenate(boxes, 0)\n        h, w, c = img.shape\n        while True:\n            mode = random.choice(self.sample_mode)\n            self.mode = mode\n            if mode == 1:\n                return results\n\n            min_iou = mode\n            for i in range(50):\n                new_w = random.uniform(self.min_crop_size * w, w)\n                new_h = random.uniform(self.min_crop_size * h, h)\n\n                # h / w in [0.5, 2]\n                if new_h / new_w < 0.5 or new_h / new_w > 2:\n                    continue\n\n                left = random.uniform(w - new_w)\n                top = random.uniform(h - new_h)\n\n                patch = np.array(\n                    (int(left), int(top), int(left + new_w), int(top + new_h)))\n                # Line or point crop is not allowed\n                if patch[2] == patch[0] or patch[3] == patch[1]:\n                    continue\n                overlaps = bbox_overlaps(\n                    patch.reshape(-1, 4), boxes.reshape(-1, 4)).reshape(-1)\n                if len(overlaps) > 0 and overlaps.min() < min_iou:\n                    continue\n\n                # center of boxes should inside the crop img\n                # only adjust boxes and instance masks when the gt is not empty\n                if len(overlaps) > 0:\n                    # adjust boxes\n                    def is_center_of_bboxes_in_patch(boxes, patch):\n                        center = (boxes[:, :2] + boxes[:, 2:]) / 2\n                        mask = ((center[:, 0] > patch[0]) *\n                                (center[:, 1] > patch[1]) *\n                                (center[:, 0] < patch[2]) *\n                                (center[:, 1] < patch[3]))\n                        return mask\n\n                    mask = is_center_of_bboxes_in_patch(boxes, patch)\n                    if not mask.any():\n                        continue\n                    for key in results.get('bbox_fields', []):\n                        boxes = results[key].copy()\n                        mask = is_center_of_bboxes_in_patch(boxes, patch)\n                        boxes = boxes[mask]\n                        if self.bbox_clip_border:\n                            boxes[:, 2:] = boxes[:, 2:].clip(max=patch[2:])\n                            boxes[:, :2] = boxes[:, :2].clip(min=patch[:2])\n                        boxes -= np.tile(patch[:2], 2)\n\n                        results[key] = boxes\n                        # labels\n                        label_key = self.bbox2label.get(key)\n                        if label_key in results:\n                            results[label_key] = results[label_key][mask]\n\n                        # mask fields\n                        mask_key = self.bbox2mask.get(key)\n                        if mask_key in results:\n                            results[mask_key] = results[mask_key][\n                                mask.nonzero()[0]].crop(patch)\n                # adjust the img no matter whether the gt is empty before crop\n                img = img[patch[1]:patch[3], patch[0]:patch[2]]\n                results['img'] = img\n                results['img_shape'] = img.shape\n\n                # seg fields\n                for key in results.get('seg_fields', []):\n                    results[key] = results[key][patch[1]:patch[3],\n                                                patch[0]:patch[2]]\n                return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(min_ious={self.min_ious}, '\n        repr_str += f'min_crop_size={self.min_crop_size}, '\n        repr_str += f'bbox_clip_border={self.bbox_clip_border})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass Corrupt:\n    \"\"\"Corruption augmentation.\n\n    Corruption transforms implemented based on\n    `imagecorruptions <https://github.com/bethgelab/imagecorruptions>`_.\n\n    Args:\n        corruption (str): Corruption name.\n        severity (int, optional): The severity of corruption. Default: 1.\n    \"\"\"\n\n    def __init__(self, corruption, severity=1):\n        self.corruption = corruption\n        self.severity = severity\n\n    def __call__(self, results):\n        \"\"\"Call function to corrupt image.\n\n        Args:\n            results (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Result dict with images corrupted.\n        \"\"\"\n\n        if corrupt is None:\n            raise RuntimeError('imagecorruptions is not installed')\n        if 'img_fields' in results:\n            assert results['img_fields'] == ['img'], \\\n                'Only single img_fields is allowed'\n        results['img'] = corrupt(\n            results['img'].astype(np.uint8),\n            corruption_name=self.corruption,\n            severity=self.severity)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(corruption={self.corruption}, '\n        repr_str += f'severity={self.severity})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass Albu:\n    \"\"\"Albumentation augmentation.\n\n    Adds custom transformations from Albumentations library.\n    Please, visit `https://albumentations.readthedocs.io`\n    to get more information.\n\n    An example of ``transforms`` is as followed:\n\n    .. code-block::\n\n        [\n            dict(\n                type='ShiftScaleRotate',\n                shift_limit=0.0625,\n                scale_limit=0.0,\n                rotate_limit=0,\n                interpolation=1,\n                p=0.5),\n            dict(\n                type='RandomBrightnessContrast',\n                brightness_limit=[0.1, 0.3],\n                contrast_limit=[0.1, 0.3],\n                p=0.2),\n            dict(type='ChannelShuffle', p=0.1),\n            dict(\n                type='OneOf',\n                transforms=[\n                    dict(type='Blur', blur_limit=3, p=1.0),\n                    dict(type='MedianBlur', blur_limit=3, p=1.0)\n                ],\n                p=0.1),\n        ]\n\n    Args:\n        transforms (list[dict]): A list of albu transformations\n        bbox_params (dict): Bbox_params for albumentation `Compose`\n        keymap (dict): Contains {'input key':'albumentation-style key'}\n        skip_img_without_anno (bool): Whether to skip the image if no ann left\n            after aug\n    \"\"\"\n\n    def __init__(self,\n                 transforms,\n                 bbox_params=None,\n                 keymap=None,\n                 update_pad_shape=False,\n                 skip_img_without_anno=False):\n        if Compose is None:\n            raise RuntimeError('albumentations is not installed')\n\n        # Args will be modified later, copying it will be safer\n        transforms = copy.deepcopy(transforms)\n        if bbox_params is not None:\n            bbox_params = copy.deepcopy(bbox_params)\n        if keymap is not None:\n            keymap = copy.deepcopy(keymap)\n        self.transforms = transforms\n        self.filter_lost_elements = False\n        self.update_pad_shape = update_pad_shape\n        self.skip_img_without_anno = skip_img_without_anno\n\n        # A simple workaround to remove masks without boxes\n        if (isinstance(bbox_params, dict) and 'label_fields' in bbox_params\n                and 'filter_lost_elements' in bbox_params):\n            self.filter_lost_elements = True\n            self.origin_label_fields = bbox_params['label_fields']\n            bbox_params['label_fields'] = ['idx_mapper']\n            del bbox_params['filter_lost_elements']\n\n        self.bbox_params = (\n            self.albu_builder(bbox_params) if bbox_params else None)\n        self.aug = Compose([self.albu_builder(t) for t in self.transforms],\n                           bbox_params=self.bbox_params)\n\n        if not keymap:\n            self.keymap_to_albu = {\n                'img': 'image',\n                'gt_masks': 'masks',\n                'gt_bboxes': 'bboxes'\n            }\n        else:\n            self.keymap_to_albu = keymap\n        self.keymap_back = {v: k for k, v in self.keymap_to_albu.items()}\n\n    def albu_builder(self, cfg):\n        \"\"\"Import a module from albumentations.\n\n        It inherits some of :func:`build_from_cfg` logic.\n\n        Args:\n            cfg (dict): Config dict. It should at least contain the key \"type\".\n\n        Returns:\n            obj: The constructed object.\n        \"\"\"\n\n        assert isinstance(cfg, dict) and 'type' in cfg\n        args = cfg.copy()\n\n        obj_type = args.pop('type')\n        if is_str(obj_type):\n            if albumentations is None:\n                raise RuntimeError('albumentations is not installed')\n            obj_cls = getattr(albumentations, obj_type)\n        elif inspect.isclass(obj_type):\n            obj_cls = obj_type\n        else:\n            raise TypeError(\n                f'type must be a str or valid type, but got {type(obj_type)}')\n\n        if 'transforms' in args:\n            args['transforms'] = [\n                self.albu_builder(transform)\n                for transform in args['transforms']\n            ]\n\n        return obj_cls(**args)\n\n    @staticmethod\n    def mapper(d, keymap):\n        \"\"\"Dictionary mapper. Renames keys according to keymap provided.\n\n        Args:\n            d (dict): old dict\n            keymap (dict): {'old_key':'new_key'}\n        Returns:\n            dict: new dict.\n        \"\"\"\n\n        updated_dict = {}\n        for k, v in zip(d.keys(), d.values()):\n            new_k = keymap.get(k, k)\n            updated_dict[new_k] = d[k]\n        return updated_dict\n\n    def __call__(self, results):\n        # dict to albumentations format\n        results = self.mapper(results, self.keymap_to_albu)\n        # TODO: add bbox_fields\n        if 'bboxes' in results:\n            # to list of boxes\n            if isinstance(results['bboxes'], np.ndarray):\n                results['bboxes'] = [x for x in results['bboxes']]\n            # add pseudo-field for filtration\n            if self.filter_lost_elements:\n                results['idx_mapper'] = np.arange(len(results['bboxes']))\n\n        # TODO: Support mask structure in albu\n        if 'masks' in results:\n            if isinstance(results['masks'], PolygonMasks):\n                raise NotImplementedError(\n                    'Albu only supports BitMap masks now')\n            ori_masks = results['masks']\n            if albumentations.__version__ < '0.5':\n                results['masks'] = results['masks'].masks\n            else:\n                results['masks'] = [mask for mask in results['masks'].masks]\n\n        results = self.aug(**results)\n\n        if 'bboxes' in results:\n            if isinstance(results['bboxes'], list):\n                results['bboxes'] = np.array(\n                    results['bboxes'], dtype=np.float32)\n            results['bboxes'] = results['bboxes'].reshape(-1, 4)\n\n            # filter label_fields\n            if self.filter_lost_elements:\n\n                for label in self.origin_label_fields:\n                    results[label] = np.array(\n                        [results[label][i] for i in results['idx_mapper']])\n                if 'masks' in results:\n                    results['masks'] = np.array(\n                        [results['masks'][i] for i in results['idx_mapper']])\n                    results['masks'] = ori_masks.__class__(\n                        results['masks'], results['image'].shape[0],\n                        results['image'].shape[1])\n\n                if (not len(results['idx_mapper'])\n                        and self.skip_img_without_anno):\n                    return None\n\n        if 'gt_labels' in results:\n            if isinstance(results['gt_labels'], list):\n                results['gt_labels'] = np.array(results['gt_labels'])\n            results['gt_labels'] = results['gt_labels'].astype(np.int64)\n\n        # back to the original format\n        results = self.mapper(results, self.keymap_back)\n\n        # update final shape\n        if self.update_pad_shape:\n            results['pad_shape'] = results['img'].shape\n\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__ + f'(transforms={self.transforms})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass RandomCenterCropPad:\n    \"\"\"Random center crop and random around padding for CornerNet.\n\n    This operation generates randomly cropped image from the original image and\n    pads it simultaneously. Different from :class:`RandomCrop`, the output\n    shape may not equal to ``crop_size`` strictly. We choose a random value\n    from ``ratios`` and the output shape could be larger or smaller than\n    ``crop_size``. The padding operation is also different from :class:`Pad`,\n    here we use around padding instead of right-bottom padding.\n\n    The relation between output image (padding image) and original image:\n\n    .. code:: text\n\n                        output image\n\n               +----------------------------+\n               |          padded area       |\n        +------|----------------------------|----------+\n        |      |         cropped area       |          |\n        |      |         +---------------+  |          |\n        |      |         |    .   center |  |          | original image\n        |      |         |        range  |  |          |\n        |      |         +---------------+  |          |\n        +------|----------------------------|----------+\n               |          padded area       |\n               +----------------------------+\n\n    There are 5 main areas in the figure:\n\n    - output image: output image of this operation, also called padding\n      image in following instruction.\n    - original image: input image of this operation.\n    - padded area: non-intersect area of output image and original image.\n    - cropped area: the overlap of output image and original image.\n    - center range: a smaller area where random center chosen from.\n      center range is computed by ``border`` and original image's shape\n      to avoid our random center is too close to original image's border.\n\n    Also this operation act differently in train and test mode, the summary\n    pipeline is listed below.\n\n    Train pipeline:\n\n    1. Choose a ``random_ratio`` from ``ratios``, the shape of padding image\n       will be ``random_ratio * crop_size``.\n    2. Choose a ``random_center`` in center range.\n    3. Generate padding image with center matches the ``random_center``.\n    4. Initialize the padding image with pixel value equals to ``mean``.\n    5. Copy the cropped area to padding image.\n    6. Refine annotations.\n\n    Test pipeline:\n\n    1. Compute output shape according to ``test_pad_mode``.\n    2. Generate padding image with center matches the original image\n       center.\n    3. Initialize the padding image with pixel value equals to ``mean``.\n    4. Copy the ``cropped area`` to padding image.\n\n    Args:\n        crop_size (tuple | None): expected size after crop, final size will\n            computed according to ratio. Requires (h, w) in train mode, and\n            None in test mode.\n        ratios (tuple): random select a ratio from tuple and crop image to\n            (crop_size[0] * ratio) * (crop_size[1] * ratio).\n            Only available in train mode.\n        border (int): max distance from center select area to image border.\n            Only available in train mode.\n        mean (sequence): Mean values of 3 channels.\n        std (sequence): Std values of 3 channels.\n        to_rgb (bool): Whether to convert the image from BGR to RGB.\n        test_mode (bool): whether involve random variables in transform.\n            In train mode, crop_size is fixed, center coords and ratio is\n            random selected from predefined lists. In test mode, crop_size\n            is image's original shape, center coords and ratio is fixed.\n        test_pad_mode (tuple): padding method and padding shape value, only\n            available in test mode. Default is using 'logical_or' with\n            127 as padding shape value.\n\n            - 'logical_or': final_shape = input_shape | padding_shape_value\n            - 'size_divisor': final_shape = int(\n              ceil(input_shape / padding_shape_value) * padding_shape_value)\n        test_pad_add_pix (int): Extra padding pixel in test mode. Default 0.\n        bbox_clip_border (bool, optional): Whether clip the objects outside\n            the border of the image. Defaults to True.\n    \"\"\"\n\n    def __init__(self,\n                 crop_size=None,\n                 ratios=(0.9, 1.0, 1.1),\n                 border=128,\n                 mean=None,\n                 std=None,\n                 to_rgb=None,\n                 test_mode=False,\n                 test_pad_mode=('logical_or', 127),\n                 test_pad_add_pix=0,\n                 bbox_clip_border=True):\n        if test_mode:\n            assert crop_size is None, 'crop_size must be None in test mode'\n            assert ratios is None, 'ratios must be None in test mode'\n            assert border is None, 'border must be None in test mode'\n            assert isinstance(test_pad_mode, (list, tuple))\n            assert test_pad_mode[0] in ['logical_or', 'size_divisor']\n        else:\n            assert isinstance(crop_size, (list, tuple))\n            assert crop_size[0] > 0 and crop_size[1] > 0, (\n                'crop_size must > 0 in train mode')\n            assert isinstance(ratios, (list, tuple))\n            assert test_pad_mode is None, (\n                'test_pad_mode must be None in train mode')\n\n        self.crop_size = crop_size\n        self.ratios = ratios\n        self.border = border\n        # We do not set default value to mean, std and to_rgb because these\n        # hyper-parameters are easy to forget but could affect the performance.\n        # Please use the same setting as Normalize for performance assurance.\n        assert mean is not None and std is not None and to_rgb is not None\n        self.to_rgb = to_rgb\n        self.input_mean = mean\n        self.input_std = std\n        if to_rgb:\n            self.mean = mean[::-1]\n            self.std = std[::-1]\n        else:\n            self.mean = mean\n            self.std = std\n        self.test_mode = test_mode\n        self.test_pad_mode = test_pad_mode\n        self.test_pad_add_pix = test_pad_add_pix\n        self.bbox_clip_border = bbox_clip_border\n\n    def _get_border(self, border, size):\n        \"\"\"Get final border for the target size.\n\n        This function generates a ``final_border`` according to image's shape.\n        The area between ``final_border`` and ``size - final_border`` is the\n        ``center range``. We randomly choose center from the ``center range``\n        to avoid our random center is too close to original image's border.\n        Also ``center range`` should be larger than 0.\n\n        Args:\n            border (int): The initial border, default is 128.\n            size (int): The width or height of original image.\n        Returns:\n            int: The final border.\n        \"\"\"\n        k = 2 * border / size\n        i = pow(2, np.ceil(np.log2(np.ceil(k))) + (k == int(k)))\n        return border // i\n\n    def _filter_boxes(self, patch, boxes):\n        \"\"\"Check whether the center of each box is in the patch.\n\n        Args:\n            patch (list[int]): The cropped area, [left, top, right, bottom].\n            boxes (numpy array, (N x 4)): Ground truth boxes.\n\n        Returns:\n            mask (numpy array, (N,)): Each box is inside or outside the patch.\n        \"\"\"\n        center = (boxes[:, :2] + boxes[:, 2:]) / 2\n        mask = (center[:, 0] > patch[0]) * (center[:, 1] > patch[1]) * (\n            center[:, 0] < patch[2]) * (\n                center[:, 1] < patch[3])\n        return mask\n\n    def _crop_image_and_paste(self, image, center, size):\n        \"\"\"Crop image with a given center and size, then paste the cropped\n        image to a blank image with two centers align.\n\n        This function is equivalent to generating a blank image with ``size``\n        as its shape. Then cover it on the original image with two centers (\n        the center of blank image and the random center of original image)\n        aligned. The overlap area is paste from the original image and the\n        outside area is filled with ``mean pixel``.\n\n        Args:\n            image (np array, H x W x C): Original image.\n            center (list[int]): Target crop center coord.\n            size (list[int]): Target crop size. [target_h, target_w]\n\n        Returns:\n            cropped_img (np array, target_h x target_w x C): Cropped image.\n            border (np array, 4): The distance of four border of\n                ``cropped_img`` to the original image area, [top, bottom,\n                left, right]\n            patch (list[int]): The cropped area, [left, top, right, bottom].\n        \"\"\"\n        center_y, center_x = center\n        target_h, target_w = size\n        img_h, img_w, img_c = image.shape\n\n        x0 = max(0, center_x - target_w // 2)\n        x1 = min(center_x + target_w // 2, img_w)\n        y0 = max(0, center_y - target_h // 2)\n        y1 = min(center_y + target_h // 2, img_h)\n        patch = np.array((int(x0), int(y0), int(x1), int(y1)))\n\n        left, right = center_x - x0, x1 - center_x\n        top, bottom = center_y - y0, y1 - center_y\n\n        cropped_center_y, cropped_center_x = target_h // 2, target_w // 2\n        cropped_img = np.zeros((target_h, target_w, img_c), dtype=image.dtype)\n        for i in range(img_c):\n            cropped_img[:, :, i] += self.mean[i]\n        y_slice = slice(cropped_center_y - top, cropped_center_y + bottom)\n        x_slice = slice(cropped_center_x - left, cropped_center_x + right)\n        cropped_img[y_slice, x_slice, :] = image[y0:y1, x0:x1, :]\n\n        border = np.array([\n            cropped_center_y - top, cropped_center_y + bottom,\n            cropped_center_x - left, cropped_center_x + right\n        ],\n                          dtype=np.float32)\n\n        return cropped_img, border, patch\n\n    def _train_aug(self, results):\n        \"\"\"Random crop and around padding the original image.\n\n        Args:\n            results (dict): Image infomations in the augment pipeline.\n\n        Returns:\n            results (dict): The updated dict.\n        \"\"\"\n        img = results['img']\n        h, w, c = img.shape\n        boxes = results['gt_bboxes']\n        while True:\n            scale = random.choice(self.ratios)\n            new_h = int(self.crop_size[0] * scale)\n            new_w = int(self.crop_size[1] * scale)\n            h_border = self._get_border(self.border, h)\n            w_border = self._get_border(self.border, w)\n\n            for i in range(50):\n                center_x = random.randint(low=w_border, high=w - w_border)\n                center_y = random.randint(low=h_border, high=h - h_border)\n\n                cropped_img, border, patch = self._crop_image_and_paste(\n                    img, [center_y, center_x], [new_h, new_w])\n\n                mask = self._filter_boxes(patch, boxes)\n                # if image do not have valid bbox, any crop patch is valid.\n                if not mask.any() and len(boxes) > 0:\n                    continue\n\n                results['img'] = cropped_img\n                results['img_shape'] = cropped_img.shape\n                results['pad_shape'] = cropped_img.shape\n\n                x0, y0, x1, y1 = patch\n\n                left_w, top_h = center_x - x0, center_y - y0\n                cropped_center_x, cropped_center_y = new_w // 2, new_h // 2\n\n                # crop bboxes accordingly and clip to the image boundary\n                for key in results.get('bbox_fields', []):\n                    mask = self._filter_boxes(patch, results[key])\n                    bboxes = results[key][mask]\n                    bboxes[:, 0:4:2] += cropped_center_x - left_w - x0\n                    bboxes[:, 1:4:2] += cropped_center_y - top_h - y0\n                    if self.bbox_clip_border:\n                        bboxes[:, 0:4:2] = np.clip(bboxes[:, 0:4:2], 0, new_w)\n                        bboxes[:, 1:4:2] = np.clip(bboxes[:, 1:4:2], 0, new_h)\n                    keep = (bboxes[:, 2] > bboxes[:, 0]) & (\n                        bboxes[:, 3] > bboxes[:, 1])\n                    bboxes = bboxes[keep]\n                    results[key] = bboxes\n                    if key in ['gt_bboxes']:\n                        if 'gt_labels' in results:\n                            labels = results['gt_labels'][mask]\n                            labels = labels[keep]\n                            results['gt_labels'] = labels\n                        if 'gt_masks' in results:\n                            raise NotImplementedError(\n                                'RandomCenterCropPad only supports bbox.')\n\n                # crop semantic seg\n                for key in results.get('seg_fields', []):\n                    raise NotImplementedError(\n                        'RandomCenterCropPad only supports bbox.')\n                return results\n\n    def _test_aug(self, results):\n        \"\"\"Around padding the original image without cropping.\n\n        The padding mode and value are from ``test_pad_mode``.\n\n        Args:\n            results (dict): Image infomations in the augment pipeline.\n\n        Returns:\n            results (dict): The updated dict.\n        \"\"\"\n        img = results['img']\n        h, w, c = img.shape\n        results['img_shape'] = img.shape\n        if self.test_pad_mode[0] in ['logical_or']:\n            # self.test_pad_add_pix is only used for centernet\n            target_h = (h | self.test_pad_mode[1]) + self.test_pad_add_pix\n            target_w = (w | self.test_pad_mode[1]) + self.test_pad_add_pix\n        elif self.test_pad_mode[0] in ['size_divisor']:\n            divisor = self.test_pad_mode[1]\n            target_h = int(np.ceil(h / divisor)) * divisor\n            target_w = int(np.ceil(w / divisor)) * divisor\n        else:\n            raise NotImplementedError(\n                'RandomCenterCropPad only support two testing pad mode:'\n                'logical-or and size_divisor.')\n\n        cropped_img, border, _ = self._crop_image_and_paste(\n            img, [h // 2, w // 2], [target_h, target_w])\n        results['img'] = cropped_img\n        results['pad_shape'] = cropped_img.shape\n        results['border'] = border\n        return results\n\n    def __call__(self, results):\n        img = results['img']\n        assert img.dtype == np.float32, (\n            'RandomCenterCropPad needs the input image of dtype np.float32,'\n            ' please set \"to_float32=True\" in \"LoadImageFromFile\" pipeline')\n        h, w, c = img.shape\n        assert c == len(self.mean)\n        if self.test_mode:\n            return self._test_aug(results)\n        else:\n            return self._train_aug(results)\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(crop_size={self.crop_size}, '\n        repr_str += f'ratios={self.ratios}, '\n        repr_str += f'border={self.border}, '\n        repr_str += f'mean={self.input_mean}, '\n        repr_str += f'std={self.input_std}, '\n        repr_str += f'to_rgb={self.to_rgb}, '\n        repr_str += f'test_mode={self.test_mode}, '\n        repr_str += f'test_pad_mode={self.test_pad_mode}, '\n        repr_str += f'bbox_clip_border={self.bbox_clip_border})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass CutOut:\n    \"\"\"CutOut operation.\n\n    Randomly drop some regions of image used in\n    `Cutout <https://arxiv.org/abs/1708.04552>`_.\n\n    Args:\n        n_holes (int | tuple[int, int]): Number of regions to be dropped.\n            If it is given as a list, number of holes will be randomly\n            selected from the closed interval [`n_holes[0]`, `n_holes[1]`].\n        cutout_shape (tuple[int, int] | list[tuple[int, int]]): The candidate\n            shape of dropped regions. It can be `tuple[int, int]` to use a\n            fixed cutout shape, or `list[tuple[int, int]]` to randomly choose\n            shape from the list.\n        cutout_ratio (tuple[float, float] | list[tuple[float, float]]): The\n            candidate ratio of dropped regions. It can be `tuple[float, float]`\n            to use a fixed ratio or `list[tuple[float, float]]` to randomly\n            choose ratio from the list. Please note that `cutout_shape`\n            and `cutout_ratio` cannot be both given at the same time.\n        fill_in (tuple[float, float, float] | tuple[int, int, int]): The value\n            of pixel to fill in the dropped regions. Default: (0, 0, 0).\n    \"\"\"\n\n    def __init__(self,\n                 n_holes,\n                 cutout_shape=None,\n                 cutout_ratio=None,\n                 fill_in=(0, 0, 0)):\n\n        assert (cutout_shape is None) ^ (cutout_ratio is None), \\\n            'Either cutout_shape or cutout_ratio should be specified.'\n        assert (isinstance(cutout_shape, (list, tuple))\n                or isinstance(cutout_ratio, (list, tuple)))\n        if isinstance(n_holes, tuple):\n            assert len(n_holes) == 2 and 0 <= n_holes[0] < n_holes[1]\n        else:\n            n_holes = (n_holes, n_holes)\n        self.n_holes = n_holes\n        self.fill_in = fill_in\n        self.with_ratio = cutout_ratio is not None\n        self.candidates = cutout_ratio if self.with_ratio else cutout_shape\n        if not isinstance(self.candidates, list):\n            self.candidates = [self.candidates]\n\n    def __call__(self, results):\n        \"\"\"Call function to drop some regions of image.\"\"\"\n        h, w, c = results['img'].shape\n        n_holes = np.random.randint(self.n_holes[0], self.n_holes[1] + 1)\n        for _ in range(n_holes):\n            x1 = np.random.randint(0, w)\n            y1 = np.random.randint(0, h)\n            index = np.random.randint(0, len(self.candidates))\n            if not self.with_ratio:\n                cutout_w, cutout_h = self.candidates[index]\n            else:\n                cutout_w = int(self.candidates[index][0] * w)\n                cutout_h = int(self.candidates[index][1] * h)\n\n            x2 = np.clip(x1 + cutout_w, 0, w)\n            y2 = np.clip(y1 + cutout_h, 0, h)\n            results['img'][y1:y2, x1:x2, :] = self.fill_in\n\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(n_holes={self.n_holes}, '\n        repr_str += (f'cutout_ratio={self.candidates}, ' if self.with_ratio\n                     else f'cutout_shape={self.candidates}, ')\n        repr_str += f'fill_in={self.fill_in})'\n        return repr_str"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/transforms_3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom numpy import random\nimport warnings\nfrom mmcv import is_tuple_of\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.parallel import DataContainer as DC\n\nfrom mmcv.core.voxel.voxel_generator import VoxelGenerator\nfrom mmcv.core.bbox.structures.cam_box3d import CameraInstance3DBoxes\nfrom mmcv.core.bbox.structures.depth_box3d import DepthInstance3DBoxes\nfrom mmcv.core.bbox.structures.lidar_box3d import LiDARInstance3DBoxes\nfrom mmcv.core.bbox import box_np_ops\nfrom mmcv.datasets.builder import PIPELINES\nfrom mmcv.datasets.pipelines.transforms import RandomFlip\nfrom mmcv.image import impad, impad_to_multiple, imnormalize, imresize, bgr2hsv, hsv2bgr\nfrom ..builder import OBJECTSAMPLERS\nfrom .data_augment_utils import noise_per_object_v3_\n\n\n@PIPELINES.register_module()\nclass RandomDropPointsColor(object):\n    r\"\"\"Randomly set the color of points to all zeros.\n\n    Once this transform is executed, all the points' color will be dropped.\n    Refer to `PAConv <https://github.com/CVMI-Lab/PAConv/blob/main/scene_seg/\n    util/transform.py#L223>`_ for more details.\n\n    Args:\n        drop_ratio (float): The probability of dropping point colors.\n            Defaults to 0.2.\n    \"\"\"\n\n    def __init__(self, drop_ratio=0.2):\n        assert isinstance(drop_ratio, (int, float)) and 0 <= drop_ratio <= 1, \\\n            f'invalid drop_ratio value {drop_ratio}'\n        self.drop_ratio = drop_ratio\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to drop point colors.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after color dropping, \\\n                'points' key is updated in the result dict.\n        \"\"\"\n        points = input_dict['points']\n        assert points.attribute_dims is not None and \\\n            'color' in points.attribute_dims, \\\n            'Expect points have color attribute'\n\n        # this if-expression is a bit strange\n        # `RandomDropPointsColor` is used in training 3D segmentor PAConv\n        # we discovered in our experiments that, using\n        # `if np.random.rand() > 1.0 - self.drop_ratio` consistently leads to\n        # better results than using `if np.random.rand() < self.drop_ratio`\n        # so we keep this hack in our codebase\n        if np.random.rand() > 1.0 - self.drop_ratio:\n            points.color = points.color * 0.0\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(drop_ratio={self.drop_ratio})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass RandomFlip3D(RandomFlip):\n    \"\"\"Flip the points & bbox.\n\n    If the input dict contains the key \"flip\", then the flag will be used,\n    otherwise it will be randomly decided by a ratio specified in the init\n    method.\n\n    Args:\n        sync_2d (bool, optional): Whether to apply flip according to the 2D\n            images. If True, it will apply the same flip as that to 2D images.\n            If False, it will decide whether to flip randomly and independently\n            to that of 2D images. Defaults to True.\n        flip_ratio_bev_horizontal (float, optional): The flipping probability\n            in horizontal direction. Defaults to 0.0.\n        flip_ratio_bev_vertical (float, optional): The flipping probability\n            in vertical direction. Defaults to 0.0.\n    \"\"\"\n\n    def __init__(self,\n                 sync_2d=True,\n                 flip_ratio_bev_horizontal=0.0,\n                 flip_ratio_bev_vertical=0.0,\n                 **kwargs):\n        super(RandomFlip3D, self).__init__(\n            flip_ratio=flip_ratio_bev_horizontal, **kwargs)\n        self.sync_2d = sync_2d\n        self.flip_ratio_bev_vertical = flip_ratio_bev_vertical\n        if flip_ratio_bev_horizontal is not None:\n            assert isinstance(\n                flip_ratio_bev_horizontal,\n                (int, float)) and 0 <= flip_ratio_bev_horizontal <= 1\n        if flip_ratio_bev_vertical is not None:\n            assert isinstance(\n                flip_ratio_bev_vertical,\n                (int, float)) and 0 <= flip_ratio_bev_vertical <= 1\n\n    def random_flip_data_3d(self, input_dict, direction='horizontal'):\n        \"\"\"Flip 3D data randomly.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n            direction (str): Flip direction. Default: horizontal.\n\n        Returns:\n            dict: Flipped results, 'points', 'bbox3d_fields' keys are \\\n                updated in the result dict.\n        \"\"\"\n        assert direction in ['horizontal', 'vertical']\n        if len(input_dict['bbox3d_fields']) == 0:  # test mode\n            input_dict['bbox3d_fields'].append('empty_box3d')\n            input_dict['empty_box3d'] = input_dict['box_type_3d'](\n                np.array([], dtype=np.float32))\n        assert len(input_dict['bbox3d_fields']) == 1\n        for key in input_dict['bbox3d_fields']:\n            if 'points' in input_dict:\n                input_dict['points'] = input_dict[key].flip(\n                    direction, points=input_dict['points'])\n            else:\n                input_dict[key].flip(direction)\n        if 'centers2d' in input_dict:\n            assert self.sync_2d is True and direction == 'horizontal', \\\n                'Only support sync_2d=True and horizontal flip with images'\n            w = input_dict['ori_shape'][1]\n            input_dict['centers2d'][..., 0] = \\\n                w - input_dict['centers2d'][..., 0]\n            # need to modify the horizontal position of camera center\n            # along u-axis in the image (flip like centers2d)\n            # ['cam2img'][0][2] = c_u\n            # see more details and examples at\n            # https://github.com/open-mmlab/mmcvection3d/pull/744\n            input_dict['cam2img'][0][2] = w - input_dict['cam2img'][0][2]\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to flip points, values in the ``bbox3d_fields`` and \\\n        also flip 2D image and its annotations.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Flipped results, 'flip', 'flip_direction', \\\n                'pcd_horizontal_flip' and 'pcd_vertical_flip' keys are added \\\n                into result dict.\n        \"\"\"\n        # filp 2D image and its annotations\n        super(RandomFlip3D, self).__call__(input_dict)\n\n        if self.sync_2d:\n            input_dict['pcd_horizontal_flip'] = input_dict['flip']\n            input_dict['pcd_vertical_flip'] = False\n        else:\n            if 'pcd_horizontal_flip' not in input_dict:\n                flip_horizontal = True if np.random.rand(\n                ) < self.flip_ratio else False\n                input_dict['pcd_horizontal_flip'] = flip_horizontal\n            if 'pcd_vertical_flip' not in input_dict:\n                flip_vertical = True if np.random.rand(\n                ) < self.flip_ratio_bev_vertical else False\n                input_dict['pcd_vertical_flip'] = flip_vertical\n\n        if 'transformation_3d_flow' not in input_dict:\n            input_dict['transformation_3d_flow'] = []\n\n        if input_dict['pcd_horizontal_flip']:\n            self.random_flip_data_3d(input_dict, 'horizontal')\n            input_dict['transformation_3d_flow'].extend(['HF'])\n        if input_dict['pcd_vertical_flip']:\n            self.random_flip_data_3d(input_dict, 'vertical')\n            input_dict['transformation_3d_flow'].extend(['VF'])\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(sync_2d={self.sync_2d},'\n        repr_str += f' flip_ratio_bev_vertical={self.flip_ratio_bev_vertical})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass RandomJitterPoints(object):\n    \"\"\"Randomly jitter point coordinates.\n\n    Different from the global translation in ``GlobalRotScaleTrans``, here we \\\n        apply different noises to each point in a scene.\n\n    Args:\n        jitter_std (list[float]): The standard deviation of jittering noise.\n            This applies random noise to all points in a 3D scene, which is \\\n            sampled from a gaussian distribution whose standard deviation is \\\n            set by ``jitter_std``. Defaults to [0.01, 0.01, 0.01]\n        clip_range (list[float] | None): Clip the randomly generated jitter \\\n            noise into this range. If None is given, don't perform clipping.\n            Defaults to [-0.05, 0.05]\n\n    Note:\n        This transform should only be used in point cloud segmentation tasks \\\n            because we don't transform ground-truth bboxes accordingly.\n        For similar transform in detection task, please refer to `ObjectNoise`.\n    \"\"\"\n\n    def __init__(self,\n                 jitter_std=[0.01, 0.01, 0.01],\n                 clip_range=[-0.05, 0.05]):\n        seq_types = (list, tuple, np.ndarray)\n        if not isinstance(jitter_std, seq_types):\n            assert isinstance(jitter_std, (int, float)), \\\n                f'unsupported jitter_std type {type(jitter_std)}'\n            jitter_std = [jitter_std, jitter_std, jitter_std]\n        self.jitter_std = jitter_std\n\n        if clip_range is not None:\n            if not isinstance(clip_range, seq_types):\n                assert isinstance(clip_range, (int, float)), \\\n                    f'unsupported clip_range type {type(clip_range)}'\n                clip_range = [-clip_range, clip_range]\n        self.clip_range = clip_range\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to jitter all the points in the scene.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after adding noise to each point, \\\n                'points' key is updated in the result dict.\n        \"\"\"\n        points = input_dict['points']\n        jitter_std = np.array(self.jitter_std, dtype=np.float32)\n        jitter_noise = \\\n            np.random.randn(points.shape[0], 3) * jitter_std[None, :]\n        if self.clip_range is not None:\n            jitter_noise = np.clip(jitter_noise, self.clip_range[0],\n                                   self.clip_range[1])\n\n        points.translate(jitter_noise)\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(jitter_std={self.jitter_std},'\n        repr_str += f' clip_range={self.clip_range})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass ObjectSample(object):\n    \"\"\"Sample GT objects to the data.\n\n    Args:\n        db_sampler (dict): Config dict of the database sampler.\n        sample_2d (bool): Whether to also paste 2D image patch to the images\n            This should be true when applying multi-modality cut-and-paste.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self, db_sampler, sample_2d=False):\n        self.sampler_cfg = db_sampler\n        self.sample_2d = sample_2d\n        if 'type' not in db_sampler.keys():\n            db_sampler['type'] = 'DataBaseSampler'\n        self.db_sampler = build_from_cfg(db_sampler, OBJECTSAMPLERS)\n\n    @staticmethod\n    def remove_points_in_boxes(points, boxes):\n        \"\"\"Remove the points in the sampled bounding boxes.\n\n        Args:\n            points (:obj:`BasePoints`): Input point cloud array.\n            boxes (np.ndarray): Sampled ground truth boxes.\n\n        Returns:\n            np.ndarray: Points with those in the boxes removed.\n        \"\"\"\n        masks = box_np_ops.points_in_rbbox(points.coord.numpy(), boxes)\n        points = points[np.logical_not(masks.any(-1))]\n        return points\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to sample ground truth objects to the data.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after object sampling augmentation, \\\n                'points', 'gt_bboxes_3d', 'gt_labels_3d' keys are updated \\\n                in the result dict.\n        \"\"\"\n        gt_bboxes_3d = input_dict['gt_bboxes_3d']\n        gt_labels_3d = input_dict['gt_labels_3d']\n\n        # change to float for blending operation\n        points = input_dict['points']\n        if self.sample_2d:\n            img = input_dict['img']\n            gt_bboxes_2d = input_dict['gt_bboxes']\n            # Assume for now 3D & 2D bboxes are the same\n            sampled_dict = self.db_sampler.sample_all(\n                gt_bboxes_3d.tensor.numpy(),\n                gt_labels_3d,\n                gt_bboxes_2d=gt_bboxes_2d,\n                img=img)\n        else:\n            sampled_dict = self.db_sampler.sample_all(\n                gt_bboxes_3d.tensor.numpy(), gt_labels_3d, img=None)\n\n        if sampled_dict is not None:\n            sampled_gt_bboxes_3d = sampled_dict['gt_bboxes_3d']\n            sampled_points = sampled_dict['points']\n            sampled_gt_labels = sampled_dict['gt_labels_3d']\n\n            gt_labels_3d = np.concatenate([gt_labels_3d, sampled_gt_labels],\n                                          axis=0)\n            gt_bboxes_3d = gt_bboxes_3d.new_box(\n                np.concatenate(\n                    [gt_bboxes_3d.tensor.numpy(), sampled_gt_bboxes_3d]))\n\n            points = self.remove_points_in_boxes(points, sampled_gt_bboxes_3d)\n            # check the points dimension\n            points = points.cat([sampled_points, points])\n\n            if self.sample_2d:\n                sampled_gt_bboxes_2d = sampled_dict['gt_bboxes_2d']\n                gt_bboxes_2d = np.concatenate(\n                    [gt_bboxes_2d, sampled_gt_bboxes_2d]).astype(np.float32)\n\n                input_dict['gt_bboxes'] = gt_bboxes_2d\n                input_dict['img'] = sampled_dict['img']\n\n        input_dict['gt_bboxes_3d'] = gt_bboxes_3d\n        input_dict['gt_labels_3d'] = gt_labels_3d.astype(np.long)\n        input_dict['points'] = points\n\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f' sample_2d={self.sample_2d},'\n        repr_str += f' data_root={self.sampler_cfg.data_root},'\n        repr_str += f' info_path={self.sampler_cfg.info_path},'\n        repr_str += f' rate={self.sampler_cfg.rate},'\n        repr_str += f' prepare={self.sampler_cfg.prepare},'\n        repr_str += f' classes={self.sampler_cfg.classes},'\n        repr_str += f' sample_groups={self.sampler_cfg.sample_groups}'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass ObjectNoise(object):\n    \"\"\"Apply noise to each GT objects in the scene.\n\n    Args:\n        translation_std (list[float], optional): Standard deviation of the\n            distribution where translation noise are sampled from.\n            Defaults to [0.25, 0.25, 0.25].\n        global_rot_range (list[float], optional): Global rotation to the scene.\n            Defaults to [0.0, 0.0].\n        rot_range (list[float], optional): Object rotation range.\n            Defaults to [-0.15707963267, 0.15707963267].\n        num_try (int, optional): Number of times to try if the noise applied is\n            invalid. Defaults to 100.\n    \"\"\"\n\n    def __init__(self,\n                 translation_std=[0.25, 0.25, 0.25],\n                 global_rot_range=[0.0, 0.0],\n                 rot_range=[-0.15707963267, 0.15707963267],\n                 num_try=100):\n        self.translation_std = translation_std\n        self.global_rot_range = global_rot_range\n        self.rot_range = rot_range\n        self.num_try = num_try\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to apply noise to each ground truth in the scene.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after adding noise to each object, \\\n                'points', 'gt_bboxes_3d' keys are updated in the result dict.\n        \"\"\"\n        gt_bboxes_3d = input_dict['gt_bboxes_3d']\n        points = input_dict['points']\n\n        # TODO: check this inplace function\n        numpy_box = gt_bboxes_3d.tensor.numpy()\n        numpy_points = points.tensor.numpy()\n\n        noise_per_object_v3_(\n            numpy_box,\n            numpy_points,\n            rotation_perturb=self.rot_range,\n            center_noise_std=self.translation_std,\n            global_random_rot_range=self.global_rot_range,\n            num_try=self.num_try)\n\n        input_dict['gt_bboxes_3d'] = gt_bboxes_3d.new_box(numpy_box)\n        input_dict['points'] = points.new_point(numpy_points)\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(num_try={self.num_try},'\n        repr_str += f' translation_std={self.translation_std},'\n        repr_str += f' global_rot_range={self.global_rot_range},'\n        repr_str += f' rot_range={self.rot_range})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass GlobalAlignment(object):\n    \"\"\"Apply global alignment to 3D scene points by rotation and translation.\n\n    Args:\n        rotation_axis (int): Rotation axis for points and bboxes rotation.\n\n    Note:\n        We do not record the applied rotation and translation as in \\\n            GlobalRotScaleTrans. Because usually, we do not need to reverse \\\n            the alignment step.\n        For example, ScanNet 3D detection task uses aligned ground-truth \\\n            bounding boxes for evaluation.\n    \"\"\"\n\n    def __init__(self, rotation_axis):\n        self.rotation_axis = rotation_axis\n\n    def _trans_points(self, input_dict, trans_factor):\n        \"\"\"Private function to translate points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n            trans_factor (np.ndarray): Translation vector to be applied.\n\n        Returns:\n            dict: Results after translation, 'points' is updated in the dict.\n        \"\"\"\n        input_dict['points'].translate(trans_factor)\n\n    def _rot_points(self, input_dict, rot_mat):\n        \"\"\"Private function to rotate bounding boxes and points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n            rot_mat (np.ndarray): Rotation matrix to be applied.\n\n        Returns:\n            dict: Results after rotation, 'points' is updated in the dict.\n        \"\"\"\n        # input should be rot_mat_T so I transpose it here\n        input_dict['points'].rotate(rot_mat.T)\n\n    def _check_rot_mat(self, rot_mat):\n        \"\"\"Check if rotation matrix is valid for self.rotation_axis.\n\n        Args:\n            rot_mat (np.ndarray): Rotation matrix to be applied.\n        \"\"\"\n        is_valid = np.allclose(np.linalg.det(rot_mat), 1.0)\n        valid_array = np.zeros(3)\n        valid_array[self.rotation_axis] = 1.0\n        is_valid &= (rot_mat[self.rotation_axis, :] == valid_array).all()\n        is_valid &= (rot_mat[:, self.rotation_axis] == valid_array).all()\n        assert is_valid, f'invalid rotation matrix {rot_mat}'\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to shuffle points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after global alignment, 'points' and keys in \\\n                input_dict['bbox3d_fields'] are updated in the result dict.\n        \"\"\"\n        assert 'axis_align_matrix' in input_dict['ann_info'].keys(), \\\n            'axis_align_matrix is not provided in GlobalAlignment'\n\n        axis_align_matrix = input_dict['ann_info']['axis_align_matrix']\n        assert axis_align_matrix.shape == (4, 4), \\\n            f'invalid shape {axis_align_matrix.shape} for axis_align_matrix'\n        rot_mat = axis_align_matrix[:3, :3]\n        trans_vec = axis_align_matrix[:3, -1]\n\n        self._check_rot_mat(rot_mat)\n        self._rot_points(input_dict, rot_mat)\n        self._trans_points(input_dict, trans_vec)\n\n        return input_dict\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(rotation_axis={self.rotation_axis})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass GlobalRotScaleTrans(object):\n    \"\"\"Apply global rotation, scaling and translation to a 3D scene.\n\n    Args:\n        rot_range (list[float]): Range of rotation angle.\n            Defaults to [-0.78539816, 0.78539816] (close to [-pi/4, pi/4]).\n        scale_ratio_range (list[float]): Range of scale ratio.\n            Defaults to [0.95, 1.05].\n        translation_std (list[float]): The standard deviation of translation\n            noise. This applies random translation to a scene by a noise, which\n            is sampled from a gaussian distribution whose standard deviation\n            is set by ``translation_std``. Defaults to [0, 0, 0]\n        shift_height (bool): Whether to shift height.\n            (the fourth dimension of indoor points) when scaling.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self,\n                 rot_range=[-0.78539816, 0.78539816],\n                 scale_ratio_range=[0.95, 1.05],\n                 translation_std=[0, 0, 0],\n                 shift_height=False):\n        seq_types = (list, tuple, np.ndarray)\n        if not isinstance(rot_range, seq_types):\n            assert isinstance(rot_range, (int, float)), \\\n                f'unsupported rot_range type {type(rot_range)}'\n            rot_range = [-rot_range, rot_range]\n        self.rot_range = rot_range\n\n        assert isinstance(scale_ratio_range, seq_types), \\\n            f'unsupported scale_ratio_range type {type(scale_ratio_range)}'\n        self.scale_ratio_range = scale_ratio_range\n\n        if not isinstance(translation_std, seq_types):\n            assert isinstance(translation_std, (int, float)), \\\n                f'unsupported translation_std type {type(translation_std)}'\n            translation_std = [\n                translation_std, translation_std, translation_std\n            ]\n        assert all([std >= 0 for std in translation_std]), \\\n            'translation_std should be positive'\n        self.translation_std = translation_std\n        self.shift_height = shift_height\n\n    def _trans_bbox_points(self, input_dict):\n        \"\"\"Private function to translate bounding boxes and points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after translation, 'points', 'pcd_trans' \\\n                and keys in input_dict['bbox3d_fields'] are updated \\\n                in the result dict.\n        \"\"\"\n        translation_std = np.array(self.translation_std, dtype=np.float32)\n        trans_factor = np.random.normal(scale=translation_std, size=3).T\n\n        input_dict['points'].translate(trans_factor)\n        input_dict['pcd_trans'] = trans_factor\n        for key in input_dict['bbox3d_fields']:\n            input_dict[key].translate(trans_factor)\n\n    def _rot_bbox_points(self, input_dict):\n        \"\"\"Private function to rotate bounding boxes and points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after rotation, 'points', 'pcd_rotation' \\\n                and keys in input_dict['bbox3d_fields'] are updated \\\n                in the result dict.\n        \"\"\"\n        rotation = self.rot_range\n        noise_rotation = np.random.uniform(rotation[0], rotation[1])\n\n        # if no bbox in input_dict, only rotate points\n        if len(input_dict['bbox3d_fields']) == 0:\n            rot_mat_T = input_dict['points'].rotate(noise_rotation)\n            input_dict['pcd_rotation'] = rot_mat_T\n            return\n\n        # rotate points with bboxes\n        for key in input_dict['bbox3d_fields']:\n            if len(input_dict[key].tensor) != 0:\n                points, rot_mat_T = input_dict[key].rotate(\n                    noise_rotation, input_dict['points'])\n                input_dict['points'] = points\n                input_dict['pcd_rotation'] = rot_mat_T\n\n    def _scale_bbox_points(self, input_dict):\n        \"\"\"Private function to scale bounding boxes and points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after scaling, 'points'and keys in \\\n                input_dict['bbox3d_fields'] are updated in the result dict.\n        \"\"\"\n        scale = input_dict['pcd_scale_factor']\n        points = input_dict['points']\n        points.scale(scale)\n        if self.shift_height:\n            assert 'height' in points.attribute_dims.keys(), \\\n                'setting shift_height=True but points have no height attribute'\n            points.tensor[:, points.attribute_dims['height']] *= scale\n        input_dict['points'] = points\n\n        for key in input_dict['bbox3d_fields']:\n            input_dict[key].scale(scale)\n\n    def _random_scale(self, input_dict):\n        \"\"\"Private function to randomly set the scale factor.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after scaling, 'pcd_scale_factor' are updated \\\n                in the result dict.\n        \"\"\"\n        scale_factor = np.random.uniform(self.scale_ratio_range[0],\n                                         self.scale_ratio_range[1])\n        input_dict['pcd_scale_factor'] = scale_factor\n\n    def __call__(self, input_dict):\n        \"\"\"Private function to rotate, scale and translate bounding boxes and \\\n        points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after scaling, 'points', 'pcd_rotation',\n                'pcd_scale_factor', 'pcd_trans' and keys in \\\n                input_dict['bbox3d_fields'] are updated in the result dict.\n        \"\"\"\n        if 'transformation_3d_flow' not in input_dict:\n            input_dict['transformation_3d_flow'] = []\n\n        self._rot_bbox_points(input_dict)\n\n        if 'pcd_scale_factor' not in input_dict:\n            self._random_scale(input_dict)\n        self._scale_bbox_points(input_dict)\n\n        self._trans_bbox_points(input_dict)\n\n        input_dict['transformation_3d_flow'].extend(['R', 'S', 'T'])\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(rot_range={self.rot_range},'\n        repr_str += f' scale_ratio_range={self.scale_ratio_range},'\n        repr_str += f' translation_std={self.translation_std},'\n        repr_str += f' shift_height={self.shift_height})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass PointShuffle(object):\n    \"\"\"Shuffle input points.\"\"\"\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to shuffle points.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        idx = input_dict['points'].shuffle()\n        idx = idx.numpy()\n\n        pts_instance_mask = input_dict.get('pts_instance_mask', None)\n        pts_semantic_mask = input_dict.get('pts_semantic_mask', None)\n\n        if pts_instance_mask is not None:\n            input_dict['pts_instance_mask'] = pts_instance_mask[idx]\n\n        if pts_semantic_mask is not None:\n            input_dict['pts_semantic_mask'] = pts_semantic_mask[idx]\n\n        return input_dict\n\n    def __repr__(self):\n        return self.__class__.__name__\n\n\n@PIPELINES.register_module()\nclass ObjectRangeFilter(object):\n    \"\"\"Filter objects by the range.\n\n    Args:\n        point_cloud_range (list[float]): Point cloud range.\n    \"\"\"\n\n    def __init__(self, point_cloud_range):\n        self.pcd_range = np.array(point_cloud_range, dtype=np.float32)\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by the range.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        # Check points instance type and initialise bev_range\n        if isinstance(input_dict['gt_bboxes_3d'],\n                      (LiDARInstance3DBoxes, DepthInstance3DBoxes)):\n            bev_range = self.pcd_range[[0, 1, 3, 4]]\n        elif isinstance(input_dict['gt_bboxes_3d'], CameraInstance3DBoxes):\n            bev_range = self.pcd_range[[0, 2, 3, 5]]\n\n        gt_bboxes_3d = input_dict['gt_bboxes_3d']\n        gt_labels_3d = input_dict['gt_labels_3d']\n        mask = gt_bboxes_3d.in_range_bev(bev_range)\n        gt_bboxes_3d = gt_bboxes_3d[mask]\n        # mask is a torch tensor but gt_labels_3d is still numpy array\n        # using mask to index gt_labels_3d will cause bug when\n        # len(gt_labels_3d) == 1, where mask=1 will be interpreted\n        # as gt_labels_3d[1] and cause out of index error\n        gt_labels_3d = gt_labels_3d[mask.numpy().astype(np.bool)]\n\n        # limit rad to [-pi, pi]\n        gt_bboxes_3d.limit_yaw(offset=0.5, period=2 * np.pi)\n        input_dict['gt_bboxes_3d'] = gt_bboxes_3d\n        input_dict['gt_labels_3d'] = gt_labels_3d\n\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(point_cloud_range={self.pcd_range.tolist()})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass PointsRangeFilter(object):\n    \"\"\"Filter points by the range.\n\n    Args:\n        point_cloud_range (list[float]): Point cloud range.\n    \"\"\"\n\n    def __init__(self, point_cloud_range):\n        self.pcd_range = np.array(point_cloud_range, dtype=np.float32)\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter points by the range.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        points = input_dict['points']\n        points_mask = points.in_range_3d(self.pcd_range)\n        clean_points = points[points_mask]\n        input_dict['points'] = clean_points\n        points_mask = points_mask.numpy()\n\n        pts_instance_mask = input_dict.get('pts_instance_mask', None)\n        pts_semantic_mask = input_dict.get('pts_semantic_mask', None)\n\n        if pts_instance_mask is not None:\n            input_dict['pts_instance_mask'] = pts_instance_mask[points_mask]\n\n        if pts_semantic_mask is not None:\n            input_dict['pts_semantic_mask'] = pts_semantic_mask[points_mask]\n\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(point_cloud_range={self.pcd_range.tolist()})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass ObjectNameFilter(object):\n    \"\"\"Filter GT objects by their names.\n\n    Args:\n        classes (list[str]): List of class names to be kept for training.\n    \"\"\"\n\n    def __init__(self, classes):\n        self.classes = classes\n        self.labels = list(range(len(self.classes)))\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by their names.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        gt_labels_3d = input_dict['gt_labels_3d']\n        gt_bboxes_mask = np.array([n in self.labels for n in gt_labels_3d],\n                                  dtype=np.bool_)\n        input_dict['gt_bboxes_3d'] = input_dict['gt_bboxes_3d'][gt_bboxes_mask]\n        input_dict['gt_labels_3d'] = input_dict['gt_labels_3d'][gt_bboxes_mask]\n\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(classes={self.classes})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass PointSample(object):\n    \"\"\"Point sample.\n\n    Sampling data to a certain number.\n\n    Args:\n        num_points (int): Number of points to be sampled.\n        sample_range (float, optional): The range where to sample points.\n            If not None, the points with depth larger than `sample_range` are\n            prior to be sampled. Defaults to None.\n        replace (bool, optional): Whether the sampling is with or without\n            replacement. Defaults to False.\n    \"\"\"\n\n    def __init__(self, num_points, sample_range=None, replace=False):\n        self.num_points = num_points\n        self.sample_range = sample_range\n        self.replace = replace\n\n    def _points_random_sampling(self,\n                                points,\n                                num_samples,\n                                sample_range=None,\n                                replace=False,\n                                return_choices=False):\n        \"\"\"Points random sampling.\n\n        Sample points to a certain number.\n\n        Args:\n            points (np.ndarray | :obj:`BasePoints`): 3D Points.\n            num_samples (int): Number of samples to be sampled.\n            sample_range (float, optional): Indicating the range where the\n                points will be sampled. Defaults to None.\n            replace (bool, optional): Sampling with or without replacement.\n                Defaults to None.\n            return_choices (bool, optional): Whether return choice.\n                Defaults to False.\n        Returns:\n            tuple[np.ndarray] | np.ndarray:\n                - points (np.ndarray | :obj:`BasePoints`): 3D Points.\n                - choices (np.ndarray, optional): The generated random samples.\n        \"\"\"\n        if not replace:\n            replace = (points.shape[0] < num_samples)\n        point_range = range(len(points))\n        if sample_range is not None and not replace:\n            # Only sampling the near points when len(points) >= num_samples\n            depth = np.linalg.norm(points.tensor, axis=1)\n            far_inds = np.where(depth > sample_range)[0]\n            near_inds = np.where(depth <= sample_range)[0]\n            # in case there are too many far points\n            if len(far_inds) > num_samples:\n                far_inds = np.random.choice(\n                    far_inds, num_samples, replace=False)\n            point_range = near_inds\n            num_samples -= len(far_inds)\n        choices = np.random.choice(point_range, num_samples, replace=replace)\n        if sample_range is not None and not replace:\n            choices = np.concatenate((far_inds, choices))\n            # Shuffle points after sampling\n            np.random.shuffle(choices)\n        if return_choices:\n            return points[choices], choices\n        else:\n            return points[choices]\n\n    def __call__(self, results):\n        \"\"\"Call function to sample points to in indoor scenes.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Results after sampling, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        points = results['points']\n        # Points in Camera coord can provide the depth information.\n        # TODO: Need to suport distance-based sampling for other coord system.\n        if self.sample_range is not None:\n            from mmcv.core.points import CameraPoints\n            assert isinstance(points, CameraPoints), \\\n                'Sampling based on distance is only appliable for CAMERA coord'\n        points, choices = self._points_random_sampling(\n            points,\n            self.num_points,\n            self.sample_range,\n            self.replace,\n            return_choices=True)\n        results['points'] = points\n\n        pts_instance_mask = results.get('pts_instance_mask', None)\n        pts_semantic_mask = results.get('pts_semantic_mask', None)\n\n        if pts_instance_mask is not None:\n            pts_instance_mask = pts_instance_mask[choices]\n            results['pts_instance_mask'] = pts_instance_mask\n\n        if pts_semantic_mask is not None:\n            pts_semantic_mask = pts_semantic_mask[choices]\n            results['pts_semantic_mask'] = pts_semantic_mask\n\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(num_points={self.num_points},'\n        repr_str += f' sample_range={self.sample_range},'\n        repr_str += f' replace={self.replace})'\n\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass IndoorPointSample(PointSample):\n    \"\"\"Indoor point sample.\n\n    Sampling data to a certain number.\n    NOTE: IndoorPointSample is deprecated in favor of PointSample\n\n    Args:\n        num_points (int): Number of points to be sampled.\n    \"\"\"\n\n    def __init__(self, *args, **kwargs):\n        warnings.warn(\n            'IndoorPointSample is deprecated in favor of PointSample')\n        super(IndoorPointSample, self).__init__(*args, **kwargs)\n\n\n@PIPELINES.register_module()\nclass IndoorPatchPointSample(object):\n    r\"\"\"Indoor point sample within a patch. Modified from `PointNet++ <https://\n    github.com/charlesq34/pointnet2/blob/master/scannet/scannet_dataset.py>`_.\n\n    Sampling data to a certain number for semantic segmentation.\n\n    Args:\n        num_points (int): Number of points to be sampled.\n        block_size (float, optional): Size of a block to sample points from.\n            Defaults to 1.5.\n        sample_rate (float, optional): Stride used in sliding patch generation.\n            This parameter is unused in `IndoorPatchPointSample` and thus has\n            been deprecated. We plan to remove it in the future.\n            Defaults to None.\n        ignore_index (int, optional): Label index that won't be used for the\n            segmentation task. This is set in PointSegClassMapping as neg_cls.\n            If not None, will be used as a patch selection criterion.\n            Defaults to None.\n        use_normalized_coord (bool, optional): Whether to use normalized xyz as\n            additional features. Defaults to False.\n        num_try (int, optional): Number of times to try if the patch selected\n            is invalid. Defaults to 10.\n        enlarge_size (float | None, optional): Enlarge the sampled patch to\n            [-block_size / 2 - enlarge_size, block_size / 2 + enlarge_size] as\n            an augmentation. If None, set it as 0. Defaults to 0.2.\n        min_unique_num (int | None, optional): Minimum number of unique points\n            the sampled patch should contain. If None, use PointNet++'s method\n            to judge uniqueness. Defaults to None.\n        eps (float, optional): A value added to patch boundary to guarantee\n            points coverage. Defaults to 1e-2.\n\n    Note:\n        This transform should only be used in the training process of point\n            cloud segmentation tasks. For the sliding patch generation and\n            inference process in testing, please refer to the `slide_inference`\n            function of `EncoderDecoder3D` class.\n    \"\"\"\n\n    def __init__(self,\n                 num_points,\n                 block_size=1.5,\n                 sample_rate=None,\n                 ignore_index=None,\n                 use_normalized_coord=False,\n                 num_try=10,\n                 enlarge_size=0.2,\n                 min_unique_num=None,\n                 eps=1e-2):\n        self.num_points = num_points\n        self.block_size = block_size\n        self.ignore_index = ignore_index\n        self.use_normalized_coord = use_normalized_coord\n        self.num_try = num_try\n        self.enlarge_size = enlarge_size if enlarge_size is not None else 0.0\n        self.min_unique_num = min_unique_num\n        self.eps = eps\n\n        if sample_rate is not None:\n            warnings.warn(\n                \"'sample_rate' has been deprecated and will be removed in \"\n                'the future. Please remove them from your code.')\n\n    def _input_generation(self, coords, patch_center, coord_max, attributes,\n                          attribute_dims, point_type):\n        \"\"\"Generating model input.\n\n        Generate input by subtracting patch center and adding additional \\\n            features. Currently support colors and normalized xyz as features.\n\n        Args:\n            coords (np.ndarray): Sampled 3D Points.\n            patch_center (np.ndarray): Center coordinate of the selected patch.\n            coord_max (np.ndarray): Max coordinate of all 3D Points.\n            attributes (np.ndarray): features of input points.\n            attribute_dims (dict): Dictionary to indicate the meaning of extra\n                dimension.\n            point_type (type): class of input points inherited from BasePoints.\n\n        Returns:\n            :obj:`BasePoints`: The generated input data.\n        \"\"\"\n        # subtract patch center, the z dimension is not centered\n        centered_coords = coords.copy()\n        centered_coords[:, 0] -= patch_center[0]\n        centered_coords[:, 1] -= patch_center[1]\n\n        if self.use_normalized_coord:\n            normalized_coord = coords / coord_max\n            attributes = np.concatenate([attributes, normalized_coord], axis=1)\n            if attribute_dims is None:\n                attribute_dims = dict()\n            attribute_dims.update(\n                dict(normalized_coord=[\n                    attributes.shape[1], attributes.shape[1] +\n                    1, attributes.shape[1] + 2\n                ]))\n\n        points = np.concatenate([centered_coords, attributes], axis=1)\n        points = point_type(\n            points, points_dim=points.shape[1], attribute_dims=attribute_dims)\n\n        return points\n\n    def _patch_points_sampling(self, points, sem_mask):\n        \"\"\"Patch points sampling.\n\n        First sample a valid patch.\n        Then sample points within that patch to a certain number.\n\n        Args:\n            points (:obj:`BasePoints`): 3D Points.\n            sem_mask (np.ndarray): semantic segmentation mask for input points.\n\n        Returns:\n            tuple[:obj:`BasePoints`, np.ndarray] | :obj:`BasePoints`:\n\n                - points (:obj:`BasePoints`): 3D Points.\n                - choices (np.ndarray): The generated random samples.\n        \"\"\"\n        coords = points.coord.numpy()\n        attributes = points.tensor[:, 3:].numpy()\n        attribute_dims = points.attribute_dims\n        point_type = type(points)\n\n        coord_max = np.amax(coords, axis=0)\n        coord_min = np.amin(coords, axis=0)\n\n        for _ in range(self.num_try):\n            # random sample a point as patch center\n            cur_center = coords[np.random.choice(coords.shape[0])]\n\n            # boundary of a patch, which would be enlarged by\n            # `self.enlarge_size` as an augmentation\n            cur_max = cur_center + np.array(\n                [self.block_size / 2.0, self.block_size / 2.0, 0.0])\n            cur_min = cur_center - np.array(\n                [self.block_size / 2.0, self.block_size / 2.0, 0.0])\n            cur_max[2] = coord_max[2]\n            cur_min[2] = coord_min[2]\n            cur_choice = np.sum(\n                (coords >= (cur_min - self.enlarge_size)) *\n                (coords <= (cur_max + self.enlarge_size)),\n                axis=1) == 3\n\n            if not cur_choice.any():  # no points in this patch\n                continue\n\n            cur_coords = coords[cur_choice, :]\n            cur_sem_mask = sem_mask[cur_choice]\n            point_idxs = np.where(cur_choice)[0]\n            mask = np.sum(\n                (cur_coords >= (cur_min - self.eps)) * (cur_coords <=\n                                                        (cur_max + self.eps)),\n                axis=1) == 3\n\n            # two criteria for patch sampling, adopted from PointNet++\n            # 1. selected patch should contain enough unique points\n            if self.min_unique_num is None:\n                # use PointNet++'s method as default\n                # [31, 31, 62] are just some big values used to transform\n                # coords from 3d array to 1d and then check their uniqueness\n                # this is used in all the ScanNet code following PointNet++\n                vidx = np.ceil(\n                    (cur_coords[mask, :] - cur_min) / (cur_max - cur_min) *\n                    np.array([31.0, 31.0, 62.0]))\n                vidx = np.unique(vidx[:, 0] * 31.0 * 62.0 + vidx[:, 1] * 62.0 +\n                                 vidx[:, 2])\n                flag1 = len(vidx) / 31.0 / 31.0 / 62.0 >= 0.02\n            else:\n                # if `min_unique_num` is provided, directly compare with it\n                flag1 = mask.sum() >= self.min_unique_num\n\n            # 2. selected patch should contain enough annotated points\n            if self.ignore_index is None:\n                flag2 = True\n            else:\n                flag2 = np.sum(cur_sem_mask != self.ignore_index) / \\\n                               len(cur_sem_mask) >= 0.7\n\n            if flag1 and flag2:\n                break\n\n        # sample idx to `self.num_points`\n        if point_idxs.size >= self.num_points:\n            # no duplicate in sub-sampling\n            choices = np.random.choice(\n                point_idxs, self.num_points, replace=False)\n        else:\n            # do not use random choice here to avoid some points not counted\n            dup = np.random.choice(point_idxs.size,\n                                   self.num_points - point_idxs.size)\n            idx_dup = np.concatenate(\n                [np.arange(point_idxs.size),\n                 np.array(dup)], 0)\n            choices = point_idxs[idx_dup]\n\n        # construct model input\n        points = self._input_generation(coords[choices], cur_center, coord_max,\n                                        attributes[choices], attribute_dims,\n                                        point_type)\n\n        return points, choices\n\n    def __call__(self, results):\n        \"\"\"Call function to sample points to in indoor scenes.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after sampling, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        points = results['points']\n\n        assert 'pts_semantic_mask' in results.keys(), \\\n            'semantic mask should be provided in training and evaluation'\n        pts_semantic_mask = results['pts_semantic_mask']\n\n        points, choices = self._patch_points_sampling(points,\n                                                      pts_semantic_mask)\n\n        results['points'] = points\n        results['pts_semantic_mask'] = pts_semantic_mask[choices]\n        pts_instance_mask = results.get('pts_instance_mask', None)\n        if pts_instance_mask is not None:\n            results['pts_instance_mask'] = pts_instance_mask[choices]\n\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(num_points={self.num_points},'\n        repr_str += f' block_size={self.block_size},'\n        repr_str += f' ignore_index={self.ignore_index},'\n        repr_str += f' use_normalized_coord={self.use_normalized_coord},'\n        repr_str += f' num_try={self.num_try},'\n        repr_str += f' enlarge_size={self.enlarge_size},'\n        repr_str += f' min_unique_num={self.min_unique_num},'\n        repr_str += f' eps={self.eps})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass BackgroundPointsFilter(object):\n    \"\"\"Filter background points near the bounding box.\n\n    Args:\n        bbox_enlarge_range (tuple[float], float): Bbox enlarge range.\n    \"\"\"\n\n    def __init__(self, bbox_enlarge_range):\n        assert (is_tuple_of(bbox_enlarge_range, float)\n                and len(bbox_enlarge_range) == 3) \\\n            or isinstance(bbox_enlarge_range, float), \\\n            f'Invalid arguments bbox_enlarge_range {bbox_enlarge_range}'\n\n        if isinstance(bbox_enlarge_range, float):\n            bbox_enlarge_range = [bbox_enlarge_range] * 3\n        self.bbox_enlarge_range = np.array(\n            bbox_enlarge_range, dtype=np.float32)[np.newaxis, :]\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter points by the range.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        points = input_dict['points']\n        gt_bboxes_3d = input_dict['gt_bboxes_3d']\n\n        # avoid groundtruth being modified\n        gt_bboxes_3d_np = gt_bboxes_3d.tensor.clone().numpy()\n        gt_bboxes_3d_np[:, :3] = gt_bboxes_3d.gravity_center.clone().numpy()\n\n        enlarged_gt_bboxes_3d = gt_bboxes_3d_np.copy()\n        enlarged_gt_bboxes_3d[:, 3:6] += self.bbox_enlarge_range\n        points_numpy = points.tensor.clone().numpy()\n        foreground_masks = box_np_ops.points_in_rbbox(\n            points_numpy, gt_bboxes_3d_np, origin=(0.5, 0.5, 0.5))\n        enlarge_foreground_masks = box_np_ops.points_in_rbbox(\n            points_numpy, enlarged_gt_bboxes_3d, origin=(0.5, 0.5, 0.5))\n        foreground_masks = foreground_masks.max(1)\n        enlarge_foreground_masks = enlarge_foreground_masks.max(1)\n        valid_masks = ~np.logical_and(~foreground_masks,\n                                      enlarge_foreground_masks)\n\n        input_dict['points'] = points[valid_masks]\n        pts_instance_mask = input_dict.get('pts_instance_mask', None)\n        if pts_instance_mask is not None:\n            input_dict['pts_instance_mask'] = pts_instance_mask[valid_masks]\n\n        pts_semantic_mask = input_dict.get('pts_semantic_mask', None)\n        if pts_semantic_mask is not None:\n            input_dict['pts_semantic_mask'] = pts_semantic_mask[valid_masks]\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(bbox_enlarge_range={self.bbox_enlarge_range.tolist()})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass VoxelBasedPointSampler(object):\n    \"\"\"Voxel based point sampler.\n\n    Apply voxel sampling to multiple sweep points.\n\n    Args:\n        cur_sweep_cfg (dict): Config for sampling current points.\n        prev_sweep_cfg (dict): Config for sampling previous points.\n        time_dim (int): Index that indicate the time dimention\n            for input points.\n    \"\"\"\n\n    def __init__(self, cur_sweep_cfg, prev_sweep_cfg=None, time_dim=3):\n        self.cur_voxel_generator = VoxelGenerator(**cur_sweep_cfg)\n        self.cur_voxel_num = self.cur_voxel_generator._max_voxels\n        self.time_dim = time_dim\n        if prev_sweep_cfg is not None:\n            assert prev_sweep_cfg['max_num_points'] == \\\n                cur_sweep_cfg['max_num_points']\n            self.prev_voxel_generator = VoxelGenerator(**prev_sweep_cfg)\n            self.prev_voxel_num = self.prev_voxel_generator._max_voxels\n        else:\n            self.prev_voxel_generator = None\n            self.prev_voxel_num = 0\n\n    def _sample_points(self, points, sampler, point_dim):\n        \"\"\"Sample points for each points subset.\n\n        Args:\n            points (np.ndarray): Points subset to be sampled.\n            sampler (VoxelGenerator): Voxel based sampler for\n                each points subset.\n            point_dim (int): The dimention of each points\n\n        Returns:\n            np.ndarray: Sampled points.\n        \"\"\"\n        voxels, coors, num_points_per_voxel = sampler.generate(points)\n        if voxels.shape[0] < sampler._max_voxels:\n            padding_points = np.zeros([\n                sampler._max_voxels - voxels.shape[0], sampler._max_num_points,\n                point_dim\n            ],\n                                      dtype=points.dtype)\n            padding_points[:] = voxels[0]\n            sample_points = np.concatenate([voxels, padding_points], axis=0)\n        else:\n            sample_points = voxels\n\n        return sample_points\n\n    def __call__(self, results):\n        \"\"\"Call function to sample points from multiple sweeps.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after sampling, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        points = results['points']\n        original_dim = points.shape[1]\n\n        # TODO: process instance and semantic mask while _max_num_points\n        # is larger than 1\n        # Extend points with seg and mask fields\n        map_fields2dim = []\n        start_dim = original_dim\n        points_numpy = points.tensor.numpy()\n        extra_channel = [points_numpy]\n        for idx, key in enumerate(results['pts_mask_fields']):\n            map_fields2dim.append((key, idx + start_dim))\n            extra_channel.append(results[key][..., None])\n\n        start_dim += len(results['pts_mask_fields'])\n        for idx, key in enumerate(results['pts_seg_fields']):\n            map_fields2dim.append((key, idx + start_dim))\n            extra_channel.append(results[key][..., None])\n\n        points_numpy = np.concatenate(extra_channel, axis=-1)\n\n        # Split points into two part, current sweep points and\n        # previous sweeps points.\n        # TODO: support different sampling methods for next sweeps points\n        # and previous sweeps points.\n        cur_points_flag = (points_numpy[:, self.time_dim] == 0)\n        cur_sweep_points = points_numpy[cur_points_flag]\n        prev_sweeps_points = points_numpy[~cur_points_flag]\n        if prev_sweeps_points.shape[0] == 0:\n            prev_sweeps_points = cur_sweep_points\n\n        # Shuffle points before sampling\n        np.random.shuffle(cur_sweep_points)\n        np.random.shuffle(prev_sweeps_points)\n\n        cur_sweep_points = self._sample_points(cur_sweep_points,\n                                               self.cur_voxel_generator,\n                                               points_numpy.shape[1])\n        if self.prev_voxel_generator is not None:\n            prev_sweeps_points = self._sample_points(prev_sweeps_points,\n                                                     self.prev_voxel_generator,\n                                                     points_numpy.shape[1])\n\n            points_numpy = np.concatenate(\n                [cur_sweep_points, prev_sweeps_points], 0)\n        else:\n            points_numpy = cur_sweep_points\n\n        if self.cur_voxel_generator._max_num_points == 1:\n            points_numpy = points_numpy.squeeze(1)\n        results['points'] = points.new_point(points_numpy[..., :original_dim])\n\n        # Restore the correspoinding seg and mask fields\n        for key, dim_index in map_fields2dim:\n            results[key] = points_numpy[..., dim_index]\n\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n\n        def _auto_indent(repr_str, indent):\n            repr_str = repr_str.split('\\n')\n            repr_str = [' ' * indent + t + '\\n' for t in repr_str]\n            repr_str = ''.join(repr_str)[:-1]\n            return repr_str\n\n        repr_str = self.__class__.__name__\n        indent = 4\n        repr_str += '(\\n'\n        repr_str += ' ' * indent + f'num_cur_sweep={self.cur_voxel_num},\\n'\n        repr_str += ' ' * indent + f'num_prev_sweep={self.prev_voxel_num},\\n'\n        repr_str += ' ' * indent + f'time_dim={self.time_dim},\\n'\n        repr_str += ' ' * indent + 'cur_voxel_generator=\\n'\n        repr_str += f'{_auto_indent(repr(self.cur_voxel_generator), 8)},\\n'\n        repr_str += ' ' * indent + 'prev_voxel_generator=\\n'\n        repr_str += f'{_auto_indent(repr(self.prev_voxel_generator), 8)})'\n        return repr_str\n\n@PIPELINES.register_module()\nclass PadMultiViewImage(object):\n    \"\"\"Pad the multi-view image.\n    There are two padding modes: (1) pad to a fixed size and (2) pad to the\n    minimum size that is divisible by some number.\n    Added keys are \"pad_shape\", \"pad_fixed_size\", \"pad_size_divisor\",\n    Args:\n        size (tuple, optional): Fixed padding size.\n        size_divisor (int, optional): The divisor of padded size.\n        pad_val (float, optional): Padding value, 0 by default.\n    \"\"\"\n\n    def __init__(self, size=None, size_divisor=None, pad_val=0):\n        self.size = size\n        self.size_divisor = size_divisor\n        self.pad_val = pad_val\n        # only one of size and size_divisor should be valid\n        assert size is not None or size_divisor is not None\n        assert size is None or size_divisor is None\n\n    def _pad_img(self, results):\n        \"\"\"Pad images according to ``self.size``.\"\"\"\n        if self.size is not None:\n            padded_img = [impad(\n                img, shape=self.size, pad_val=self.pad_val) for img in results['img']]\n        elif self.size_divisor is not None:\n            padded_img = [impad_to_multiple(\n                img, self.size_divisor, pad_val=self.pad_val) for img in results['img']]\n        \n        results['ori_shape'] = [img.shape for img in results['img']]\n        results['img'] = padded_img\n        results['img_shape'] = [img.shape for img in padded_img]\n        results['pad_shape'] = [img.shape for img in padded_img]\n        results['pad_fixed_size'] = self.size\n        results['pad_size_divisor'] = self.size_divisor\n\n    def __call__(self, results):\n        \"\"\"Call function to pad images, masks, semantic segmentation maps.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Updated result dict.\n        \"\"\"\n        self._pad_img(results)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(size={self.size}, '\n        repr_str += f'size_divisor={self.size_divisor}, '\n        repr_str += f'pad_val={self.pad_val})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass NormalizeMultiviewImage(object):\n    \"\"\"Normalize the image.\n    Added key is \"img_norm_cfg\".\n    Args:\n        mean (sequence): Mean values of 3 channels.\n        std (sequence): Std values of 3 channels.\n        to_rgb (bool): Whether to convert the image from BGR to RGB,\n            default is true.\n    \"\"\"\n\n    def __init__(self, mean, std, to_rgb=True):\n        self.mean = np.array(mean, dtype=np.float32)\n        self.std = np.array(std, dtype=np.float32)\n        self.to_rgb = to_rgb\n\n\n    def __call__(self, results):\n        \"\"\"Call function to normalize images.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Normalized results, 'img_norm_cfg' key is added into\n                result dict.\n        \"\"\"\n\n        results['img'] = [imnormalize(img, self.mean, self.std, self.to_rgb) for img in results['img']]\n        results['img_norm_cfg'] = dict(\n            mean=self.mean, std=self.std, to_rgb=self.to_rgb)\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(mean={self.mean}, std={self.std}, to_rgb={self.to_rgb})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass PhotoMetricDistortionMultiViewImage:\n    \"\"\"Apply photometric distortion to image sequentially, every transformation\n    is applied with a probability of 0.5. The position of random contrast is in\n    second or second to last.\n    1. random brightness\n    2. random contrast (mode 0)\n    3. convert color from BGR to HSV\n    4. random saturation\n    5. random hue\n    6. convert color from HSV to BGR\n    7. random contrast (mode 1)\n    8. randomly swap channels\n    Args:\n        brightness_delta (int): delta of brightness.\n        contrast_range (tuple): range of contrast.\n        saturation_range (tuple): range of saturation.\n        hue_delta (int): delta of hue.\n    \"\"\"\n\n    def __init__(self,\n                 brightness_delta=32,\n                 contrast_range=(0.5, 1.5),\n                 saturation_range=(0.5, 1.5),\n                 hue_delta=18):\n        self.brightness_delta = brightness_delta\n        self.contrast_lower, self.contrast_upper = contrast_range\n        self.saturation_lower, self.saturation_upper = saturation_range\n        self.hue_delta = hue_delta\n\n    def __call__(self, results):\n        \"\"\"Call function to perform photometric distortion on images.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Result dict with images distorted.\n        \"\"\"\n        imgs = results['img']\n        new_imgs = []\n        for img in imgs:\n            assert img.dtype == np.float32, \\\n                'PhotoMetricDistortion needs the input image of dtype np.float32,'\\\n                ' please set \"to_float32=True\" in \"LoadImageFromFile\" pipeline'\n            # random brightness\n            if random.randint(2):\n                delta = random.uniform(-self.brightness_delta,\n                                    self.brightness_delta)\n                img += delta\n\n            # mode == 0 --> do random contrast first\n            # mode == 1 --> do random contrast last\n            mode = random.randint(2)\n            if mode == 1:\n                if random.randint(2):\n                    alpha = random.uniform(self.contrast_lower,\n                                        self.contrast_upper)\n                    img *= alpha\n\n            # convert color from BGR to HSV\n            img = bgr2hsv(img)\n\n            # random saturation\n            if random.randint(2):\n                img[..., 1] *= random.uniform(self.saturation_lower,\n                                            self.saturation_upper)\n\n            # random hue\n            if random.randint(2):\n                img[..., 0] += random.uniform(-self.hue_delta, self.hue_delta)\n                img[..., 0][img[..., 0] > 360] -= 360\n                img[..., 0][img[..., 0] < 0] += 360\n\n            # convert color from HSV to BGR\n            img = hsv2bgr(img)\n\n            # random contrast\n            if mode == 0:\n                if random.randint(2):\n                    alpha = random.uniform(self.contrast_lower,\n                                        self.contrast_upper)\n                    img *= alpha\n\n            # randomly swap channels\n            if random.randint(2):\n                img = img[..., random.permutation(3)]\n            new_imgs.append(img)\n        results['img'] = new_imgs\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(\\nbrightness_delta={self.brightness_delta},\\n'\n        repr_str += 'contrast_range='\n        repr_str += f'{(self.contrast_lower, self.contrast_upper)},\\n'\n        repr_str += 'saturation_range='\n        repr_str += f'{(self.saturation_lower, self.saturation_upper)},\\n'\n        repr_str += f'hue_delta={self.hue_delta})'\n        return repr_str\n\n\n\n@PIPELINES.register_module()\nclass CustomCollect3D(object):\n    \"\"\"Collect data from the loader relevant to the specific task.\n    This is usually the last stage of the data loader pipeline. Typically keys\n    is set to some subset of \"img\", \"proposals\", \"gt_bboxes\",\n    \"gt_bboxes_ignore\", \"gt_labels\", and/or \"gt_masks\".\n    The \"img_meta\" item is always populated.  The contents of the \"img_meta\"\n    dictionary depends on \"meta_keys\". By default this includes:\n        - 'img_shape': shape of the image input to the network as a tuple \\\n            (h, w, c).  Note that images may be zero padded on the \\\n            bottom/right if the batch tensor is larger than this shape.\n        - 'scale_factor': a float indicating the preprocessing scale\n        - 'flip': a boolean indicating if image flip transform was used\n        - 'filename': path to the image file\n        - 'ori_shape': original shape of the image as a tuple (h, w, c)\n        - 'pad_shape': image shape after padding\n        - 'lidar2img': transform from lidar to image\n        - 'depth2img': transform from depth to image\n        - 'cam2img': transform from camera to image\n        - 'pcd_horizontal_flip': a boolean indicating if point cloud is \\\n            flipped horizontally\n        - 'pcd_vertical_flip': a boolean indicating if point cloud is \\\n            flipped vertically\n        - 'box_mode_3d': 3D box mode\n        - 'box_type_3d': 3D box type\n        - 'img_norm_cfg': a dict of normalization information:\n            - mean: per channel mean subtraction\n            - std: per channel std divisor\n            - to_rgb: bool indicating if bgr was converted to rgb\n        - 'pcd_trans': point cloud transformations\n        - 'sample_idx': sample index\n        - 'pcd_scale_factor': point cloud scale factor\n        - 'pcd_rotation': rotation applied to point cloud\n        - 'pts_filename': path to point cloud file.\n    Args:\n        keys (Sequence[str]): Keys of results to be collected in ``data``.\n        meta_keys (Sequence[str], optional): Meta keys to be converted to\n            ``mmcv.DataContainer`` and collected in ``data[img_metas]``.\n            Default: ('filename', 'ori_shape', 'img_shape', 'lidar2img',\n            'depth2img', 'cam2img', 'pad_shape', 'scale_factor', 'flip',\n            'pcd_horizontal_flip', 'pcd_vertical_flip', 'box_mode_3d',\n            'box_type_3d', 'img_norm_cfg', 'pcd_trans',\n            'sample_idx', 'pcd_scale_factor', 'pcd_rotation', 'pts_filename')\n    \"\"\"\n\n    def __init__(self,\n                 keys,\n                 meta_keys=('filename', 'ori_shape', 'img_shape', 'lidar2img',\n                            'depth2img', 'cam2img', 'pad_shape',\n                            'scale_factor', 'flip', 'pcd_horizontal_flip',\n                            'pcd_vertical_flip', 'box_mode_3d', 'box_type_3d',\n                            'img_norm_cfg', 'pcd_trans', 'sample_idx', 'prev_idx', 'next_idx',\n                            'pcd_scale_factor', 'pcd_rotation', 'pts_filename',\n                            'transformation_3d_flow', 'scene_token',\n                            'can_bus','folder','frame_idx'\n                            )):\n        # TODO(yzj) bevformer meta_keys has lidar2cam\n        self.keys = keys\n        self.meta_keys = meta_keys\n\n    def __call__(self, results):\n        \"\"\"Call function to collect keys in results. The keys in ``meta_keys``\n        will be converted to :obj:`mmcv.DataContainer`.\n        Args:\n            results (dict): Result dict contains the data to collect.\n        Returns:\n            dict: The result dict contains the following keys\n                - keys in ``self.keys``\n                - ``img_metas``\n        \"\"\"\n       \n        data = {}\n        img_metas = {}\n        for key in self.meta_keys:\n            if key in results:\n                img_metas[key] = results[key]\n\n        data['img_metas'] = DC(img_metas, cpu_only=True)\n        for key in self.keys:\n            data[key] = results[key]\n        return data\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        return self.__class__.__name__ + \\\n            f'(keys={self.keys}, meta_keys={self.meta_keys})'\n\n\n\n@PIPELINES.register_module()\nclass RandomScaleImageMultiViewImage(object):\n    \"\"\"Random scale the image\n    Args:\n        scales\n    \"\"\"\n\n    def __init__(self, scales=[]):\n        self.scales = scales\n        assert len(self.scales)==1\n\n    def __call__(self, results):\n        \"\"\"Call function to pad images, masks, semantic segmentation maps.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Updated result dict.\n        \"\"\"\n        rand_ind = np.random.permutation(range(len(self.scales)))[0]\n        rand_scale = self.scales[rand_ind]\n\n        y_size = [int(img.shape[0] * rand_scale) for img in results['img']]\n        x_size = [int(img.shape[1] * rand_scale) for img in results['img']]\n        scale_factor = np.eye(4)\n        scale_factor[0, 0] *= rand_scale\n        scale_factor[1, 1] *= rand_scale\n        results['img'] = [imresize(img, (x_size[idx], y_size[idx]), return_scale=False) for idx, img in\n                          enumerate(results['img'])]\n        lidar2img = [scale_factor @ l2i for l2i in results['lidar2img']]\n        results['lidar2img'] = lidar2img\n        results['img_shape'] = [img.shape for img in results['img']]\n        results['ori_shape'] = [img.shape for img in results['img']]\n\n        return results\n\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(size={self.scales}, '\n        return repr_str\n\n@PIPELINES.register_module()\nclass ObjectRangeFilterTrack(object):\n    \"\"\"Filter objects by the range.\n    Args:\n        point_cloud_range (list[float]): Point cloud range.\n    \"\"\"\n\n    def __init__(self, point_cloud_range):\n        self.pcd_range = np.array(point_cloud_range, dtype=np.float32)\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by the range.\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        # Check points instance type and initialise bev_range\n        if isinstance(input_dict['gt_bboxes_3d'],\n                      (LiDARInstance3DBoxes, DepthInstance3DBoxes)):\n            bev_range = self.pcd_range[[0, 1, 3, 4]]\n        elif isinstance(input_dict['gt_bboxes_3d'], CameraInstance3DBoxes):\n            bev_range = self.pcd_range[[0, 2, 3, 5]]\n\n        if 'gt_inds' in input_dict['ann_info'].keys():\n            input_dict['gt_inds'] = input_dict['ann_info']['gt_inds']\n        if 'gt_fut_traj' in input_dict['ann_info'].keys():\n            input_dict['gt_fut_traj'] = input_dict['ann_info']['gt_fut_traj']\n        if 'gt_fut_traj_mask' in input_dict['ann_info'].keys():\n            input_dict['gt_fut_traj_mask'] = input_dict['ann_info']['gt_fut_traj_mask']\n        if 'gt_past_traj' in input_dict['ann_info'].keys():\n            input_dict['gt_past_traj'] = input_dict['ann_info']['gt_past_traj']\n        if 'gt_past_traj_mask' in input_dict['ann_info'].keys():\n            input_dict['gt_past_traj_mask'] = input_dict['ann_info']['gt_past_traj_mask']\n        if 'gt_sdc_bbox' in input_dict['ann_info'].keys():\n            input_dict['gt_sdc_bbox'] = input_dict['ann_info']['gt_sdc_bbox']\n            input_dict['gt_sdc_label'] = input_dict['ann_info']['gt_sdc_label']\n            input_dict['gt_sdc_fut_traj'] = input_dict['ann_info']['gt_sdc_fut_traj']\n            input_dict['gt_sdc_fut_traj_mask'] = input_dict['ann_info']['gt_sdc_fut_traj_mask']\n\n        gt_bboxes_3d = input_dict['gt_bboxes_3d']\n        gt_labels_3d = input_dict['gt_labels_3d']\n        gt_inds = input_dict['gt_inds']\n        gt_fut_traj = input_dict['gt_fut_traj']\n        gt_fut_traj_mask = input_dict['gt_fut_traj_mask']\n        gt_past_traj = input_dict['gt_past_traj']\n        gt_past_traj_mask = input_dict['gt_past_traj_mask']\n\n        mask = gt_bboxes_3d.in_range_bev(bev_range)\n        gt_bboxes_3d = gt_bboxes_3d[mask]\n        # mask is a torch tensor but gt_labels_3d is still numpy array\n        # using mask to index gt_labels_3d will cause bug when\n        # len(gt_labels_3d) == 1, where mask=1 will be interpreted\n        # as gt_labels_3d[1] and cause out of index error\n        mask = mask.numpy().astype(np.bool)\n        gt_labels_3d = gt_labels_3d[mask]\n        gt_inds = gt_inds[mask]\n        gt_fut_traj = gt_fut_traj[mask]\n        gt_fut_traj_mask = gt_fut_traj_mask[mask]\n        gt_past_traj = gt_past_traj[mask]\n        gt_past_traj_mask = gt_past_traj_mask[mask]\n\n        # limit rad to [-pi, pi]\n        gt_bboxes_3d.limit_yaw(offset=0.5, period=2 * np.pi)\n        input_dict['gt_bboxes_3d'] = gt_bboxes_3d\n        input_dict['gt_labels_3d'] = gt_labels_3d\n        input_dict['gt_inds'] = gt_inds\n        input_dict['gt_fut_traj'] = gt_fut_traj\n        input_dict['gt_fut_traj_mask'] = gt_fut_traj_mask\n        input_dict['gt_past_traj'] = gt_past_traj\n        input_dict['gt_past_traj_mask'] = gt_past_traj_mask\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(point_cloud_range={self.pcd_range.tolist()})'\n        return repr_str\n\n@PIPELINES.register_module()\nclass ObjectNameFilterTrack(object):\n    \"\"\"Filter GT objects by their names.\n    Args:\n        classes (list[str]): List of class names to be kept for training.\n    \"\"\"\n\n    def __init__(self, classes):\n        self.classes = classes\n        self.labels = list(range(len(self.classes)))\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by their names.\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        gt_labels_3d = input_dict['gt_labels_3d']\n        gt_bboxes_mask = np.array([n in self.labels for n in gt_labels_3d],\n                                  dtype=np.bool_)\n        input_dict['gt_bboxes_3d'] = input_dict['gt_bboxes_3d'][gt_bboxes_mask]\n        input_dict['gt_labels_3d'] = input_dict['gt_labels_3d'][gt_bboxes_mask]\n        input_dict['gt_inds'] = input_dict['gt_inds'][gt_bboxes_mask]\n        input_dict['gt_fut_traj'] = input_dict['gt_fut_traj'][gt_bboxes_mask]\n        input_dict['gt_fut_traj_mask'] = input_dict['gt_fut_traj_mask'][gt_bboxes_mask]\n        input_dict['gt_past_traj'] = input_dict['gt_past_traj'][gt_bboxes_mask]\n        input_dict['gt_past_traj_mask'] = input_dict['gt_past_traj_mask'][gt_bboxes_mask]\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(classes={self.classes})'\n        return repr_str\n\n@PIPELINES.register_module()\nclass CustomObjectRangeFilter(ObjectRangeFilter):\n    def __call__(self, results):\n        \"\"\"Call function to filter objects by the range.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d'\n                keys are updated in the result dict.\n        \"\"\"\n        # Check points instance type and initialise bev_range\n        if isinstance(results['gt_bboxes_3d'],\n                        (LiDARInstance3DBoxes, DepthInstance3DBoxes)):\n            bev_range = self.pcd_range[[0, 1, 3, 4]]\n        elif isinstance(results['gt_bboxes_3d'], CameraInstance3DBoxes):\n            bev_range = self.pcd_range[[0, 2, 3, 5]]\n\n        gt_bboxes_3d = results['gt_bboxes_3d']\n        gt_labels_3d = results['gt_labels_3d']\n        mask = gt_bboxes_3d.in_range_bev(bev_range)\n        gt_bboxes_3d = gt_bboxes_3d[mask]\n        # mask is a torch tensor but gt_labels_3d is still numpy array\n        # using mask to index gt_labels_3d will cause bug when\n        # len(gt_labels_3d) == 1, where mask=1 will be interpreted\n        # as gt_labels_3d[1] and cause out of index error\n        gt_labels_3d = gt_labels_3d[mask.numpy().astype(np.bool)]\n\n        # limit rad to [-pi, pi]\n        gt_bboxes_3d.limit_yaw(offset=0.5, period=2 * np.pi)\n        results['gt_bboxes_3d'] = gt_bboxes_3d\n        results['gt_labels_3d'] = gt_labels_3d\n        # results['ann_tokens'] = results['ann_tokens'][mask.numpy().astype(np.bool)]\n\n        return results\n\n@PIPELINES.register_module()\nclass CustomObjectNameFilter(ObjectNameFilter):\n    def __call__(self, results):\n        \"\"\"Call function to filter objects by their names.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d'\n                keys are updated in the result dict.\n        \"\"\"\n        gt_labels_3d = results['gt_labels_3d']\n        gt_bboxes_mask = np.array([n in self.labels for n in gt_labels_3d],\n                                  dtype=np.bool_)\n        results['gt_bboxes_3d'] = results['gt_bboxes_3d'][gt_bboxes_mask]\n        results['gt_labels_3d'] = results['gt_labels_3d'][gt_bboxes_mask]\n        # results['ann_tokens'] = results['ann_tokens'][gt_bboxes_mask]\n\n        return results\n\n\n@PIPELINES.register_module()\nclass VADObjectRangeFilter(object):\n    \"\"\"Filter objects by the range, and also filter corresponding fut trajs\n\n    Args:\n        point_cloud_range (list[float]): Point cloud range.\n    \"\"\"\n\n    def __init__(self, point_cloud_range):\n        self.pcd_range = np.array(point_cloud_range, dtype=np.float32)\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by the range.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        # Check points instance type and initialise bev_range\n        if isinstance(input_dict['gt_bboxes_3d'],\n                      (LiDARInstance3DBoxes, DepthInstance3DBoxes)):\n            bev_range = self.pcd_range[[0, 1, 3, 4]]\n        elif isinstance(input_dict['gt_bboxes_3d'], CameraInstance3DBoxes):\n            bev_range = self.pcd_range[[0, 2, 3, 5]]\n\n        gt_bboxes_3d = input_dict['gt_bboxes_3d']\n        gt_labels_3d = input_dict['gt_labels_3d']\n        \n        \n        mask = gt_bboxes_3d.in_range_bev(bev_range)\n        gt_bboxes_3d = gt_bboxes_3d[mask]\n        # mask is a torch tensor but gt_labels_3d is still numpy array\n        # using mask to index gt_labels_3d will cause bug when\n        # len(gt_labels_3d) == 1, where mask=1 will be interpreted\n        # as gt_labels_3d[1] and cause out of index error\n        gt_labels_3d = gt_labels_3d[mask.numpy().astype(np.bool)]\n        \n\n        # limit rad to [-pi, pi]\n        gt_bboxes_3d.limit_yaw(offset=0.5, period=2 * np.pi)\n        input_dict['gt_bboxes_3d'] = gt_bboxes_3d\n        input_dict['gt_labels_3d'] = gt_labels_3d\n\n        if 'attr_labels' in input_dict:\n            gt_attr_labels = input_dict['attr_labels']\n            gt_attr_labels = gt_attr_labels[mask.numpy().astype(np.bool)]\n            input_dict['gt_attr_labels'] = gt_attr_labels\n\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(point_cloud_range={self.pcd_range.tolist()})'\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass VADObjectNameFilter(object):\n    \"\"\"Filter GT objects by their names, , and also filter corresponding fut trajs\n\n    Args:\n        classes (list[str]): List of class names to be kept for training.\n    \"\"\"\n\n    def __init__(self, classes):\n        self.classes = classes\n        self.labels = list(range(len(self.classes)))\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by their names.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        gt_labels_3d = input_dict['gt_labels_3d']\n        gt_bboxes_mask = np.array([n in self.labels for n in gt_labels_3d],\n                                  dtype=np.bool_)\n        input_dict['gt_bboxes_3d'] = input_dict['gt_bboxes_3d'][gt_bboxes_mask]\n        input_dict['gt_labels_3d'] = input_dict['gt_labels_3d'][gt_bboxes_mask]\n        if 'gt_attr_labels' in input_dict:\n            input_dict['gt_attr_labels'] = input_dict['gt_attr_labels'][gt_bboxes_mask]\n\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(classes={self.classes})'\n        return repr_str\n\n@PIPELINES.register_module()\nclass CustomPointsRangeFilter:\n    \"\"\"Filter points by the range.\n    Args:\n        point_cloud_range (list[float]): Point cloud range.\n    \"\"\"\n\n    def __init__(self, point_cloud_range):\n        self.pcd_range = np.array(point_cloud_range, dtype=np.float32)\n\n    def __call__(self, data):\n        \"\"\"Call function to filter points by the range.\n        Args:\n            data (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Results after filtering, 'points', 'pts_instance_mask' \\\n                and 'pts_semantic_mask' keys are updated in the result dict.\n        \"\"\"\n        points = data[\"points\"]\n        points_mask = points.in_range_3d(self.pcd_range)\n        clean_points = points[points_mask]\n        data[\"points\"] = clean_points\n        return data"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/pipelines/vectorize.py",
    "content": "from typing import List, Tuple, Union, Dict\n\nimport numpy as np\nfrom shapely.geometry import LineString\nfrom numpy.typing import NDArray\n\nfrom mmcv.parallel import DataContainer as DC\nfrom ..builder import PIPELINES\n\n@PIPELINES.register_module(force=True)\nclass VectorizeMap(object):\n    \"\"\"Generate vectoized map and put into `semantic_mask` key.\n    Concretely, shapely geometry objects are converted into sample points (ndarray).\n    We use args `sample_num`, `sample_dist`, `simplify` to specify sampling method.\n\n    Args:\n        roi_size (tuple or list): bev range .\n        normalize (bool): whether to normalize points to range (0, 1).\n        coords_dim (int): dimension of point coordinates.\n        simplify (bool): whether to use simpily function. If true, `sample_num` \\\n            and `sample_dist` will be ignored.\n        sample_num (int): number of points to interpolate from a polyline. Set to -1 to ignore.\n        sample_dist (float): interpolate distance. Set to -1 to ignore.\n    \"\"\"\n\n    def __init__(self, \n                 roi_size: Union[Tuple, List], \n                 normalize: bool,\n                 coords_dim: int=2,\n                 simplify: bool=False, \n                 sample_num: int=-1, \n                 sample_dist: float=-1, \n                 permute: bool=False\n        ):\n        self.coords_dim = coords_dim\n        self.sample_num = sample_num\n        self.sample_dist = sample_dist\n        self.roi_size = np.array(roi_size)\n        self.normalize = normalize\n        self.simplify = simplify\n        self.permute = permute\n\n        if sample_dist > 0:\n            assert sample_num < 0 and not simplify\n            self.sample_fn = self.interp_fixed_dist\n        elif sample_num > 0:\n            assert sample_dist < 0 and not simplify\n            self.sample_fn = self.interp_fixed_num\n        else:\n            assert simplify\n\n    def interp_fixed_num(self, line: LineString) -> NDArray:\n        ''' Interpolate a line to fixed number of points.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n\n        distances = np.linspace(0, line.length, self.sample_num)\n        sampled_points = np.array([list(line.interpolate(distance).coords) \n            for distance in distances]).squeeze()\n\n        return sampled_points\n\n    def interp_fixed_dist(self, line: LineString) -> NDArray:\n        ''' Interpolate a line at fixed interval.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n\n        distances = list(np.arange(self.sample_dist, line.length, self.sample_dist))\n        # make sure to sample at least two points when sample_dist > line.length\n        distances = [0,] + distances + [line.length,] \n        \n        sampled_points = np.array([list(line.interpolate(distance).coords)\n                                for distance in distances]).squeeze()\n        \n        return sampled_points\n    \n    def get_vectorized_lines(self, map_geoms: Dict) -> Dict:\n        ''' Vectorize map elements. Iterate over the input dict and apply the \n        specified sample funcion.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            vectors (array): dict of vectorized map elements.\n        '''\n\n        vectors = {}\n        for label, geom_list in map_geoms.items():\n            vectors[label] = []\n            for geom in geom_list:\n                if geom.geom_type == 'LineString':\n                    if self.simplify:\n                        line = geom.simplify(0.2, preserve_topology=True)\n                        line = np.array(line.coords)\n                    else:\n                        line = self.sample_fn(geom)\n                    line = line[:, :self.coords_dim]\n\n                    if self.normalize:\n                        line = self.normalize_line(line)\n                    if self.permute:\n                        line = self.permute_line(line)\n                    vectors[label].append(line)\n\n                elif geom.geom_type == 'Polygon':\n                    # polygon objects will not be vectorized\n                    continue\n                \n                else:\n                    raise ValueError('map geoms must be either LineString or Polygon!')\n        return vectors\n    \n    def normalize_line(self, line: NDArray) -> NDArray:\n        ''' Convert points to range (0, 1).\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            normalized (array): normalized points.\n        '''\n\n        origin = -np.array([self.roi_size[0]/2, self.roi_size[1]/2])\n\n        line[:, :2] = line[:, :2] - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        line[:, :2] = line[:, :2] / (self.roi_size + eps)\n\n        return line\n    \n    def permute_line(self, line: np.ndarray, padding=1e5):\n        '''\n        (num_pts, 2) -> (num_permute, num_pts, 2)\n        where num_permute = 2 * (num_pts - 1)\n        '''\n        is_closed = np.allclose(line[0], line[-1], atol=1e-3)\n        num_points = len(line)\n        permute_num = num_points - 1\n        permute_lines_list = []\n        if is_closed:\n            pts_to_permute = line[:-1, :] # throw away replicate start end pts\n            for shift_i in range(permute_num):\n                permute_lines_list.append(np.roll(pts_to_permute, shift_i, axis=0))\n            flip_pts_to_permute = np.flip(pts_to_permute, axis=0)\n            for shift_i in range(permute_num):\n                permute_lines_list.append(np.roll(flip_pts_to_permute, shift_i, axis=0))\n        else:\n            permute_lines_list.append(line)\n            permute_lines_list.append(np.flip(line, axis=0))\n\n        permute_lines_array = np.stack(permute_lines_list, axis=0)\n\n        if is_closed:\n            tmp = np.zeros((permute_num * 2, num_points, self.coords_dim))\n            tmp[:, :-1, :] = permute_lines_array\n            tmp[:, -1, :] = permute_lines_array[:, 0, :] # add replicate start end pts\n            permute_lines_array = tmp\n\n        else:\n            # padding\n            padding = np.full([permute_num * 2 - 2, num_points, self.coords_dim], padding)\n            permute_lines_array = np.concatenate((permute_lines_array, padding), axis=0)\n        \n        return permute_lines_array\n    \n    def __call__(self, input_dict):\n        if \"map_geoms\" not in input_dict:\n            return input_dict\n        map_geoms = input_dict['map_geoms']\n        vectors = self.get_vectorized_lines(map_geoms)\n\n        if self.permute:\n            gt_map_labels, gt_map_pts = [], []\n            for label, vecs in vectors.items():\n                for vec in vecs:\n                    gt_map_labels.append(label)\n                    gt_map_pts.append(vec)\n            input_dict['gt_map_labels'] = np.array(gt_map_labels, dtype=np.int64)\n            input_dict['gt_map_pts'] = np.array(gt_map_pts, dtype=np.float32).reshape(-1, 2 * (self.sample_num - 1), self.sample_num, self.coords_dim)\n        else:\n            input_dict['vectors'] = DC(vectors, stack=False, cpu_only=True)\n        \n        return input_dict\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(simplify={self.simplify}, '\n        repr_str += f'sample_num={self.sample_num}), '\n        repr_str += f'sample_dist={self.sample_dist}), ' \n        repr_str += f'roi_size={self.roi_size})'\n        repr_str += f'normalize={self.normalize})'\n        repr_str += f'coords_dim={self.coords_dim})'\n\n        return repr_str"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/prepare_B2D.py",
    "content": "import os\nfrom os.path import join\nimport gzip, json, pickle\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom tqdm import tqdm\nfrom vis_utils import calculate_cube_vertices,calculate_occlusion_stats,edges,DIS_CAR_SAVE\nimport cv2\nimport multiprocessing\nimport argparse\n# All data in the Bench2Drive dataset are in the left-handed coordinate system.\n# This code converts all coordinate systems (world coordinate system, vehicle coordinate system,\n# camera coordinate system, and lidar coordinate system) to the right-handed coordinate system\n# consistent with the nuscenes dataset.\n\nDATAROOT = '../../data/bench2drive'\nMAP_ROOT = '../../data/bench2drive/maps'\nOUT_DIR = '../../data/infos'\n\nMAX_DISTANCE = 75              # Filter bounding boxes that are too far from the vehicle\nFILTER_Z_SHRESHOLD = 10        # Filter bounding boxes that are too high/low from the vehicle\nFILTER_INVISINLE = True        # Filter bounding boxes based on visibility\nNUM_VISIBLE_SHRESHOLD = 1      # Filter bounding boxes with fewer visible vertices than this value\nNUM_OUTPOINT_SHRESHOLD = 7     # Filter bounding boxes where the number of vertices outside the frame is greater than this value in all cameras\nCAMERAS = ['CAM_FRONT', 'CAM_FRONT_LEFT', 'CAM_FRONT_RIGHT', 'CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']\nCAMERA_TO_FOLDER_MAP = {'CAM_FRONT':'rgb_front', 'CAM_FRONT_LEFT':'rgb_front_left', 'CAM_FRONT_RIGHT':'rgb_front_right', 'CAM_BACK':'rgb_back', 'CAM_BACK_LEFT':'rgb_back_left', 'CAM_BACK_RIGHT':'rgb_back_right'}\n\nstand_to_ue4_rotate = np.array([[ 0, 0, 1, 0],\n                                [ 1, 0, 0, 0],\n                                [ 0,-1, 0, 0],\n                                [ 0, 0, 0, 1]])\n\nlidar_to_righthand_ego = np.array([[  0, 1, 0, 0],\n                                   [ -1, 0, 0, 0],\n                                   [  0, 0, 1, 0],\n                                   [  0, 0, 0, 1]])\n\nlefthand_ego_to_lidar = np.array([[ 0, 1, 0, 0],\n                                  [ 1, 0, 0, 0],\n                                  [ 0, 0, 1, 0],\n                                  [ 0, 0, 0, 1]])\n\nleft2right = np.eye(4)\nleft2right[1,1] = -1\n\ndef apply_trans(vec,world2ego):\n    vec = np.concatenate((vec,np.array([1])))\n    t = world2ego @ vec\n    return t[0:3]\n\ndef get_pose_matrix(dic):\n    new_matrix = np.zeros((4,4))\n    new_matrix[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=dic['theta']-np.pi/2).rotation_matrix\n    new_matrix[0,3] = dic['x']\n    new_matrix[1,3] = dic['y']\n    new_matrix[3,3] = 1\n    return new_matrix\n\ndef get_npc2world(npc):\n    for key in ['world2vehicle','world2ego','world2sign','world2ped']:\n        if key in npc.keys():\n            npc2world = np.linalg.inv(np.array(npc[key]))\n            yaw_from_matrix = np.arctan2(npc2world[1,0], npc2world[0,0])\n            yaw = npc['rotation'][-1] / 180 * np.pi\n            if abs(yaw-yaw_from_matrix)> 0.01:\n                npc2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=yaw).rotation_matrix\n            npc2world = left2right @ npc2world @ left2right\n            return npc2world\n    npc2world = np.eye(4)\n    npc2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=npc['rotation'][-1]/180*np.pi).rotation_matrix\n    npc2world[0:3,3] = np.array(npc['location'])\n    return left2right @ npc2world @ left2right\n\n\ndef get_global_trigger_vertex(center,extent,yaw_in_degree):\n    x,y = center[0],-center[1]\n    dx,dy = extent[0],extent[1]\n    yaw_in_radians = -yaw_in_degree/180*np.pi\n    vertex_in_self = np.array([[ dx, dy],\n                               [-dx, dy],\n                               [-dx,-dy],\n                               [ dx,-dy]])\n    rotate_matrix = np.array([[np.cos(yaw_in_radians),-np.sin(yaw_in_radians)],\n                              [np.sin(yaw_in_radians), np.cos(yaw_in_radians)]])\n    rotated_vertex = (rotate_matrix @ vertex_in_self.T).T\n    vertex_in_global = np.array([[x,y]]).repeat(4,axis=0) + rotated_vertex\n    return vertex_in_global\n\n\n\ndef get_image_point(loc, K, w2c):\n    point = np.array([loc[0], loc[1], loc[2], 1])\n    point_camera = np.dot(w2c, point)\n    point_camera = point_camera[0:3]\n    depth = point_camera[2]\n    point_img = np.dot(K, point_camera)\n    point_img[0] /= point_img[2]\n    point_img[1] /= point_img[2]\n    return point_img[0:2], depth\n\ndef get_action(index):\n\tDiscrete_Actions_DICT = {\n\t\t0:  (0, 0, 1, False),\n\t\t1:  (0.7, -0.5, 0, False),\n\t\t2:  (0.7, -0.3, 0, False),\n\t\t3:  (0.7, -0.2, 0, False),\n\t\t4:  (0.7, -0.1, 0, False),\n\t\t5:  (0.7, 0, 0, False),\n\t\t6:  (0.7, 0.1, 0, False),\n\t\t7:  (0.7, 0.2, 0, False),\n\t\t8:  (0.7, 0.3, 0, False),\n\t\t9:  (0.7, 0.5, 0, False),\n\t\t10: (0.3, -0.7, 0, False),\n\t\t11: (0.3, -0.5, 0, False),\n\t\t12: (0.3, -0.3, 0, False),\n\t\t13: (0.3, -0.2, 0, False),\n\t\t14: (0.3, -0.1, 0, False),\n\t\t15: (0.3, 0, 0, False),\n\t\t16: (0.3, 0.1, 0, False),\n\t\t17: (0.3, 0.2, 0, False),\n\t\t18: (0.3, 0.3, 0, False),\n\t\t19: (0.3, 0.5, 0, False),\n\t\t20: (0.3, 0.7, 0, False),\n\t\t21: (0, -1, 0, False),\n\t\t22: (0, -0.6, 0, False),\n\t\t23: (0, -0.3, 0, False),\n\t\t24: (0, -0.1, 0, False),\n\t\t25: (1, 0, 0, False),\n\t\t26: (0, 0.1, 0, False),\n\t\t27: (0, 0.3, 0, False),\n\t\t28: (0, 0.6, 0, False),\n\t\t29: (0, 1.0, 0, False),\n\t\t30: (0.5, -0.5, 0, True),\n\t\t31: (0.5, -0.3, 0, True),\n\t\t32: (0.5, -0.2, 0, True),\n\t\t33: (0.5, -0.1, 0, True),\n\t\t34: (0.5, 0, 0, True),\n\t\t35: (0.5, 0.1, 0, True),\n\t\t36: (0.5, 0.2, 0, True),\n\t\t37: (0.5, 0.3, 0, True),\n\t\t38: (0.5, 0.5, 0, True),\n\t\t}\n\tthrottle, steer, brake, reverse = Discrete_Actions_DICT[index]\n\treturn throttle, steer, brake\n\n\ndef gengrate_map(map_root):\n    map_infos = {}\n    for file_name in os.listdir(map_root):\n        if '.npz' in file_name:\n            map_info = dict(np.load(join(map_root,file_name), allow_pickle=True)['arr'])\n            town_name = file_name.split('_')[0]\n            map_infos[town_name] = {} \n            lane_points = []\n            lane_types = []\n            lane_sample_points = []\n            trigger_volumes_points = []\n            trigger_volumes_types = []\n            trigger_volumes_sample_points = []\n            for road_id, road in map_info.items():\n                for lane_id, lane in road.items():\n                    if lane_id == 'Trigger_Volumes':\n                        for single_trigger_volume in lane:\n                            points = np.array(single_trigger_volume['Points'])\n                            points[:,1] *= -1 #left2right\n                            trigger_volumes_points.append(points)\n                            trigger_volumes_sample_points.append(points.mean(axis=0))\n                            trigger_volumes_types.append(single_trigger_volume['Type'])\n                    else:\n                        for single_lane in lane:\n                            points = np.array([raw_point[0] for raw_point in single_lane['Points']])\n                            points[:,1] *= -1\n                            lane_points.append(points)\n                            lane_types.append(single_lane['Type'])\n                            lane_lenth = points.shape[0]\n                            if lane_lenth % 50 != 0:\n                                devide_points = [50*i for i in range(lane_lenth//50+1)]\n                            else:\n                                devide_points = [50*i for i in range(lane_lenth//50)]\n                            devide_points.append(lane_lenth-1)\n                            lane_sample_points_tmp = points[devide_points]\n                            lane_sample_points.append(lane_sample_points_tmp)\n            map_infos[town_name]['lane_points'] = lane_points\n            map_infos[town_name]['lane_sample_points'] = lane_sample_points\n            map_infos[town_name]['lane_types'] = lane_types\n            map_infos[town_name]['trigger_volumes_points'] = trigger_volumes_points\n            map_infos[town_name]['trigger_volumes_sample_points'] = trigger_volumes_sample_points\n            map_infos[town_name]['trigger_volumes_types'] = trigger_volumes_types\n    with open(join(OUT_DIR,'b2d_map_infos.pkl'),'wb') as f:\n        pickle.dump(map_infos,f)\n\ndef preprocess(folder_list,idx,tmp_dir,train_or_val):\n\n    data_root = DATAROOT\n    cameras = CAMERAS\n    final_data = []\n    if idx == 0:\n        folders = tqdm(folder_list)\n    else:\n        folders = folder_list\n\n    for folder_name in folders:\n        folder_path = join(data_root, folder_name)\n        last_position_dict = {}\n        for ann_name in sorted(os.listdir(join(folder_path,'anno')),key= lambda x: int(x.split('.')[0])):\n            position_dict = {}\n            frame_data = {}\n            cam_gray_depth = {}\n            with gzip.open(join(folder_path,'anno',ann_name), 'rt', encoding='utf-8') as gz_file:\n                anno = json.load(gz_file) \n            frame_data['folder'] = folder_name\n            frame_data['town_name'] =  folder_name.split('/')[1].split('_')[1]\n            frame_data['command_far_xy'] = np.array([anno['x_command_far'],-anno['y_command_far']])\n            frame_data['command_far'] = anno['command_far']\n            frame_data['command_near_xy'] = np.array([anno['x_command_near'],-anno['y_command_near']])\n            frame_data['command_near'] = anno['command_near']\n            frame_data['frame_idx'] = int(ann_name.split('.')[0])\n            frame_data['ego_yaw'] = -np.nan_to_num(anno['theta'],nan=np.pi)+np.pi/2  \n            frame_data['ego_translation'] = np.array([anno['x'],-anno['y'],0])\n            frame_data['ego_vel'] = np.array([anno['speed'],0,0])\n            frame_data['ego_accel'] = np.array([anno['acceleration'][0],-anno['acceleration'][1],anno['acceleration'][2]])\n            frame_data['ego_rotation_rate'] = -np.array(anno['angular_velocity'])\n            frame_data['ego_size'] = np.array([anno['bounding_boxes'][0]['extent'][1],anno['bounding_boxes'][0]['extent'][0],anno['bounding_boxes'][0]['extent'][2]])*2\n            world2ego = left2right @ anno['bounding_boxes'][0]['world2ego'] @ left2right\n            frame_data['world2ego'] = world2ego\n            if frame_data['frame_idx'] == 0:\n                expert_file_path = join(folder_path,'expert_assessment','-0001.npz')\n            else:\n                expert_file_path = join(folder_path,'expert_assessment',str(frame_data['frame_idx']-1).zfill(5)+'.npz')\n            expert_data = np.load(expert_file_path,allow_pickle=True)['arr_0']\n            action_id = expert_data[-1]\n            # value = expert_data[-2]\n            # expert_feature = expert_data[:-2]\n            throttle, steer, brake = get_action(action_id)\n            frame_data['brake'] = brake\n            frame_data['throttle'] = throttle\n            frame_data['steer'] = steer\n            #frame_data['action_id'] = action_id\n            #frame_data['value'] = value\n            #frame_data['expert_feature'] = expert_feature\n            ###get sensor infos###\n            sensor_infos = {}\n            for cam in CAMERAS:\n                sensor_infos[cam] = {}\n                sensor_infos[cam]['cam2ego'] = left2right @ np.array(anno['sensors'][cam]['cam2ego']) @ stand_to_ue4_rotate \n                sensor_infos[cam]['intrinsic'] = np.array(anno['sensors'][cam]['intrinsic'])\n                sensor_infos[cam]['world2cam'] = np.linalg.inv(stand_to_ue4_rotate) @ np.array(anno['sensors'][cam]['world2cam']) @left2right\n                sensor_infos[cam]['data_path'] = join(folder_name,'camera',CAMERA_TO_FOLDER_MAP[cam],ann_name.split('.')[0]+'.jpg')\n                cam_gray_depth[cam] = cv2.imread(join(data_root,sensor_infos[cam]['data_path']).replace('rgb_','depth_').replace('.jpg','.png'))[:,:,0]\n            sensor_infos['LIDAR_TOP'] = {}\n            sensor_infos['LIDAR_TOP']['lidar2ego'] = left2right @ np.array(anno['sensors']['LIDAR_TOP']['lidar2ego']) @ left2right @ lidar_to_righthand_ego\n            world2lidar = lefthand_ego_to_lidar @ np.array(anno['sensors']['LIDAR_TOP']['world2lidar']) @ left2right\n            sensor_infos['LIDAR_TOP']['world2lidar'] = world2lidar\n            frame_data['sensors'] = sensor_infos\n            ###get bounding_boxes infos###\n            gt_boxes = []\n            gt_names = []\n            gt_ids = []\n            num_points_list = []\n            npc2world_list = []\n            for npc in anno['bounding_boxes']:\n                if npc['class'] == 'ego_vehicle': continue\n                if npc['distance'] > MAX_DISTANCE: continue\n                if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > FILTER_Z_SHRESHOLD: continue\n                center = np.array([npc['center'][0],-npc['center'][1],npc['center'][2]]) # left hand -> right hand\n                extent = np.array([npc['extent'][1],npc['extent'][0],npc['extent'][2]])  # lwh -> wlh\n                position_dict[npc['id']] = center\n                local_center = apply_trans(center, world2lidar)\n                size = extent * 2 \n                if 'world2vehicle' in npc.keys():\n                    world2vehicle = left2right @ np.array(npc['world2vehicle'])@left2right\n                    vehicle2lidar = world2lidar @ np.linalg.inv(world2vehicle) \n                    yaw_local = np.arctan2(vehicle2lidar[1,0], vehicle2lidar[0,0])\n\n                else:\n                    yaw_local = -npc['rotation'][-1]/180*np.pi - frame_data['ego_yaw'] +np.pi / 2  \n                yaw_local_in_lidar_box = -yaw_local - np.pi / 2  \n                while yaw_local < -np.pi:\n                    yaw_local += 2*np.pi\n                while yaw_local > np.pi:\n                    yaw_local -= 2*np.pi  \n                if 'speed' in npc.keys():\n                    if 'vehicle' in npc['class']:  # only vehicles have correct speed\n                        speed = npc['speed']\n                    else:\n                        if npc['id'] in last_position_dict.keys():  #calculate speed for other object\n                            speed = np.linalg.norm((center-last_position_dict[npc['id']])[0:2]) * 10\n                        else:\n                            speed = 0\n                else:\n                    speed = 0\n                if 'num_points' in npc.keys():\n                    num_points = npc['num_points']\n                else:\n                    num_points = -1\n                npc2world = get_npc2world(npc)\n                speed_x = speed * np.cos(yaw_local)\n                speed_y = speed * np.sin(yaw_local)\n\n                ###fliter_bounding_boxes###\n                if FILTER_INVISINLE:\n                    valid = False\n                    box2lidar = np.eye(4)\n                    box2lidar[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=yaw_local).rotation_matrix\n                    box2lidar[0:3,3] = local_center\n                    lidar2box = np.linalg.inv(box2lidar)\n                    raw_verts = calculate_cube_vertices(local_center,extent)\n                    verts = []\n                    for raw_vert in raw_verts:\n                        tmp = np.dot(lidar2box, [raw_vert[0], raw_vert[1], raw_vert[2],1])\n                        tmp[0:3] += local_center\n                        verts.append(tmp.tolist()[:-1])\n                    for cam in cameras:\n                        lidar2cam = np.linalg.inv(frame_data['sensors'][cam]['cam2ego']) @ sensor_infos['LIDAR_TOP']['lidar2ego']\n                        test_points = [] \n                        test_depth = []\n                        for vert in verts:\n                            point, depth = get_image_point(vert, frame_data['sensors'][cam]['intrinsic'], lidar2cam)\n                            if depth > 0:\n                                test_points.append(point)\n                                test_depth.append(depth)\n\n                        num_visible_vertices, num_invisible_vertices, num_vertices_outside_camera, colored_points = calculate_occlusion_stats(np.array(test_points), np.array(test_depth),  cam_gray_depth[cam], max_render_depth=MAX_DISTANCE)\n                        if num_visible_vertices>NUM_VISIBLE_SHRESHOLD and num_vertices_outside_camera<NUM_OUTPOINT_SHRESHOLD:\n                            valid = True\n                            break\n                else:\n                    valid = True\n                if valid:\n                    npc2world_list.append(npc2world)\n                    num_points_list.append(num_points)            \n                    gt_boxes.append(np.concatenate([local_center,size,np.array([yaw_local_in_lidar_box,speed_x,speed_y])]))\n                    gt_names.append(npc['type_id'])\n                    gt_ids.append(int(npc['id']))\n\n            if len(gt_boxes) == 0:\n                continue\n\n            last_position_dict = position_dict.copy()    \n            gt_ids = np.array(gt_ids)\n            gt_names = np.array(gt_names)\n            num_points_list = np.array(num_points_list)\n            gt_boxes = np.stack(gt_boxes)\n            npc2world = np.stack(npc2world_list)\n            frame_data['gt_ids'] = gt_ids\n            frame_data['gt_boxes'] = gt_boxes\n            frame_data['gt_names'] = gt_names\n            frame_data['num_points'] = num_points_list\n            frame_data['npc2world'] = npc2world\n            final_data.append(frame_data)\n    \n    os.makedirs(join(OUT_DIR,tmp_dir),exist_ok=True)\n    with open(join(OUT_DIR,tmp_dir,'b2d_infos_'+train_or_val+'_'+str(idx)+'.pkl'),'wb') as f:\n        pickle.dump(final_data,f)\n\n\ndef generate_infos(folder_list,workers,train_or_val,tmp_dir):\n\n    folder_num = len(folder_list)\n    devide_list = [(folder_num//workers)*i for i in range(workers)]\n    devide_list.append(folder_num)\n    for i in range(workers):\n        sub_folder_list = folder_list[devide_list[i]:devide_list[i+1]]\n        process = multiprocessing.Process(target=preprocess, args=(sub_folder_list,i,tmp_dir,train_or_val))\n        process.start()\n        process_list.append(process)\n    for i in range(workers):\n        process_list[i].join()\n    union_data = []\n    for i in range(workers):\n        with open(join(OUT_DIR,tmp_dir,'b2d_infos_'+train_or_val+'_'+str(i)+'.pkl'),'rb') as f:\n            data = pickle.load(f)\n        union_data.extend(data)\n    with open(join(OUT_DIR,'b2d_infos_'+train_or_val+'.pkl'),'wb') as f:\n        pickle.dump(union_data,f)\n\nif __name__ == \"__main__\":\n\n\n    os.makedirs(OUT_DIR,exist_ok=True)\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--workers',type=int, default= 4, help='num of workers to prepare dataset')\n    argparser.add_argument('--tmp_dir', default=\"tmp_data\", )\n    args = argparser.parse_args()    \n    workers = args.workers\n    process_list = []\n    with open('../../data/splits/bench2drive_base_train_val_split.json','r') as f:\n        train_val_split = json.load(f)\n        \n    all_folder = os.listdir(join(DATAROOT,'v1'))\n    train_list = []\n    for foldername in all_folder:\n        if 'Town' in foldername and 'Route' in foldername and 'Weather' in foldername and not join('v1',foldername) in train_val_split['val']:\n            train_list.append(join('v1',foldername))   \n    print('processing train data...')\n    generate_infos(train_list,workers,'train',args.tmp_dir)\n    process_list = []\n    print('processing val data...')\n    generate_infos(train_val_split['val'],workers,'val',args.tmp_dir)\n    print('processing map data...')\n    gengrate_map(MAP_ROOT)\n    print('finish!')"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/samplers/__init__.py",
    "content": "from .distributed_sampler import DistributedSampler\nfrom .sampler import SAMPLER, build_sampler\nfrom .group_sampler import DistributedGroupSampler, GroupSampler\n\n# __all__ = ['DistributedSampler', 'DistributedGroupSampler', 'GroupSampler']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/samplers/distributed_sampler.py",
    "content": "import math\n\nimport torch\nfrom torch.utils.data import DistributedSampler as _DistributedSampler\nfrom .sampler import SAMPLER\n\n\n@SAMPLER.register_module()\nclass DistributedSampler(_DistributedSampler):\n\n    def __init__(self,\n                 dataset=None,\n                 num_replicas=None,\n                 rank=None,\n                 shuffle=True,\n                 seed=0):\n        super().__init__(\n            dataset, num_replicas=num_replicas, rank=rank, shuffle=shuffle)\n        # for the compatibility from PyTorch 1.3+\n        self.seed = seed if seed is not None else 0\n\n    def __iter__(self):\n        # deterministically shuffle based on epoch\n        if self.shuffle:\n            assert False\n        else:\n            indices = torch.arange(len(self.dataset)).tolist()\n\n        # add extra samples to make it evenly divisible\n        # in case that indices is shorter than half of total_size\n        indices = (indices *\n                   math.ceil(self.total_size / len(indices)))[:self.total_size]\n        assert len(indices) == self.total_size\n\n        # subsample\n        per_replicas = self.total_size//self.num_replicas\n        # indices = indices[self.rank:self.total_size:self.num_replicas]\n        indices = indices[self.rank*per_replicas:(self.rank+1)*per_replicas]\n        assert len(indices) == self.num_samples\n\n        return iter(indices)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/samplers/group_sampler.py",
    "content": "import math\n\nimport numpy as np\nimport torch\nfrom mmcv.utils import get_dist_info\nfrom torch.utils.data import Sampler\nfrom .sampler import SAMPLER\nimport random\nfrom IPython import embed\n\n\nclass GroupSampler(Sampler):\n\n    def __init__(self, dataset, samples_per_gpu=1):\n        assert hasattr(dataset, 'flag')\n        self.dataset = dataset\n        self.samples_per_gpu = samples_per_gpu\n        self.flag = dataset.flag.astype(np.int64)\n        self.group_sizes = np.bincount(self.flag)\n        self.num_samples = 0\n        for i, size in enumerate(self.group_sizes):\n            self.num_samples += int(np.ceil(\n                size / self.samples_per_gpu)) * self.samples_per_gpu\n\n    def __iter__(self):\n        indices = []\n        for i, size in enumerate(self.group_sizes):\n            if size == 0:\n                continue\n            indice = np.where(self.flag == i)[0]\n            assert len(indice) == size\n            np.random.shuffle(indice)\n            num_extra = int(np.ceil(size / self.samples_per_gpu)\n                            ) * self.samples_per_gpu - len(indice)\n            indice = np.concatenate(\n                [indice, np.random.choice(indice, num_extra)])\n            indices.append(indice)\n        indices = np.concatenate(indices)\n        indices = [\n            indices[i * self.samples_per_gpu:(i + 1) * self.samples_per_gpu]\n            for i in np.random.permutation(\n                range(len(indices) // self.samples_per_gpu))\n        ]\n        indices = np.concatenate(indices)\n        indices = indices.astype(np.int64).tolist()\n        assert len(indices) == self.num_samples\n        return iter(indices)\n\n    def __len__(self):\n        return self.num_samples\n\n@SAMPLER.register_module()\nclass DistributedGroupSampler(Sampler):\n    \"\"\"Sampler that restricts data loading to a subset of the dataset.\n    It is especially useful in conjunction with\n    :class:`torch.nn.parallel.DistributedDataParallel`. In such case, each\n    process can pass a DistributedSampler instance as a DataLoader sampler,\n    and load a subset of the original dataset that is exclusive to it.\n    .. note::\n        Dataset is assumed to be of constant size.\n    Arguments:\n        dataset: Dataset used for sampling.\n        num_replicas (optional): Number of processes participating in\n            distributed training.\n        rank (optional): Rank of the current process within num_replicas.\n        seed (int, optional): random seed used to shuffle the sampler if\n            ``shuffle=True``. This number should be identical across all\n            processes in the distributed group. Default: 0.\n    \"\"\"\n\n    def __init__(self,\n                 dataset,\n                 samples_per_gpu=1,\n                 num_replicas=None,\n                 rank=None,\n                 seed=0):\n        _rank, _num_replicas = get_dist_info()\n        if num_replicas is None:\n            num_replicas = _num_replicas\n        if rank is None:\n            rank = _rank\n        self.dataset = dataset\n        self.samples_per_gpu = samples_per_gpu\n        self.num_replicas = num_replicas\n        self.rank = rank\n        self.epoch = 0\n        self.seed = seed if seed is not None else 0\n\n        assert hasattr(self.dataset, 'flag')\n        self.flag = self.dataset.flag\n        self.group_sizes = np.bincount(self.flag)\n\n        self.num_samples = 0\n        for i, j in enumerate(self.group_sizes):\n            self.num_samples += int(\n                math.ceil(self.group_sizes[i] * 1.0 / self.samples_per_gpu /\n                          self.num_replicas)) * self.samples_per_gpu\n        self.total_size = self.num_samples * self.num_replicas\n\n    def __iter__(self):\n        # deterministically shuffle based on epoch\n        g = torch.Generator()\n        g.manual_seed(self.epoch + self.seed)\n\n        indices = []\n        for i, size in enumerate(self.group_sizes):\n            if size > 0:\n                indice = np.where(self.flag == i)[0]\n                assert len(indice) == size\n                # TODO: check whether torch.randperm() can be replaced by\n                # numpy.random.permutation().\n                indice = indice[list(\n                    torch.randperm(int(size), generator=g).numpy())].tolist()\n                extra = int(\n                    math.ceil(\n                        size * 1.0 / self.samples_per_gpu / self.num_replicas)\n                ) * self.samples_per_gpu * self.num_replicas - len(indice)\n                # pad indice\n                tmp = indice.copy()\n                for _ in range(extra // size):\n                    indice.extend(tmp)\n                indice.extend(tmp[:extra % size])\n                indices.extend(indice)\n\n        assert len(indices) == self.total_size\n\n        indices = [\n            indices[j] for i in list(\n                torch.randperm(\n                    len(indices) // self.samples_per_gpu, generator=g))\n            for j in range(i * self.samples_per_gpu, (i + 1) *\n                           self.samples_per_gpu)\n        ]\n\n        # subsample\n        offset = self.num_samples * self.rank\n        indices = indices[offset:offset + self.num_samples]\n        assert len(indices) == self.num_samples\n\n        return iter(indices)\n\n    def __len__(self):\n        return self.num_samples\n\n    def set_epoch(self, epoch):\n        self.epoch = epoch\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/samplers/sampler.py",
    "content": "from mmcv.utils.registry import Registry, build_from_cfg\n\nSAMPLER = Registry('sampler')\n\n\ndef build_sampler(cfg, default_args):\n    return build_from_cfg(cfg, SAMPLER, default_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/utils.py",
    "content": "import copy\nimport warnings\nfrom mmcv.models import VGG\nfrom mmcv.runner.hooks import HOOKS, Hook\n\nfrom mmcv.datasets.pipelines import (Collect3D, DefaultFormatBundle3D,\n                                        LoadAnnotations3D,\n                                        LoadImageFromFileMono3D,\n                                        LoadMultiViewImageFromFiles,\n                                        LoadPointsFromFile,\n                                        LoadPointsFromMultiSweeps,\n                                        MultiScaleFlipAug3D,\n                                        PointSegClassMapping)\n\nfrom mmcv.datasets.builder import PIPELINES\nfrom mmcv.datasets.pipelines import LoadAnnotations, LoadImageFromFile\nfrom mmcv.models.dense_heads import GARPNHead, RPNHead\nfrom mmcv.models.roi_heads.mask_heads import FusedSemanticHead\nfrom mmcv.parallel import DataContainer\n\n\ndef replace_ImageToTensor(pipelines):\n    \"\"\"Replace the ImageToTensor transform in a data pipeline to\n    DefaultFormatBundle, which is normally useful in batch inference.\n\n    Args:\n        pipelines (list[dict]): Data pipeline configs.\n\n    Returns:\n        list: The new pipeline list with all ImageToTensor replaced by\n            DefaultFormatBundle.\n\n    Examples:\n        >>> pipelines = [\n        ...    dict(type='LoadImageFromFile'),\n        ...    dict(\n        ...        type='MultiScaleFlipAug',\n        ...        img_scale=(1333, 800),\n        ...        flip=False,\n        ...        transforms=[\n        ...            dict(type='Resize', keep_ratio=True),\n        ...            dict(type='RandomFlip'),\n        ...            dict(type='Normalize', mean=[0, 0, 0], std=[1, 1, 1]),\n        ...            dict(type='Pad', size_divisor=32),\n        ...            dict(type='ImageToTensor', keys=['img']),\n        ...            dict(type='Collect', keys=['img']),\n        ...        ])\n        ...    ]\n        >>> expected_pipelines = [\n        ...    dict(type='LoadImageFromFile'),\n        ...    dict(\n        ...        type='MultiScaleFlipAug',\n        ...        img_scale=(1333, 800),\n        ...        flip=False,\n        ...        transforms=[\n        ...            dict(type='Resize', keep_ratio=True),\n        ...            dict(type='RandomFlip'),\n        ...            dict(type='Normalize', mean=[0, 0, 0], std=[1, 1, 1]),\n        ...            dict(type='Pad', size_divisor=32),\n        ...            dict(type='DefaultFormatBundle'),\n        ...            dict(type='Collect', keys=['img']),\n        ...        ])\n        ...    ]\n        >>> assert expected_pipelines == replace_ImageToTensor(pipelines)\n    \"\"\"\n    pipelines = copy.deepcopy(pipelines)\n    for i, pipeline in enumerate(pipelines):\n        if pipeline['type'] == 'MultiScaleFlipAug':\n            assert 'transforms' in pipeline\n            pipeline['transforms'] = replace_ImageToTensor(\n                pipeline['transforms'])\n        elif pipeline['type'] == 'ImageToTensor':\n            warnings.warn(\n                '\"ImageToTensor\" pipeline is replaced by '\n                '\"DefaultFormatBundle\" for batch inference. It is '\n                'recommended to manually replace it in the test '\n                'data pipeline in your config file.', UserWarning)\n            pipelines[i] = {'type': 'DefaultFormatBundle'}\n    return pipelines\n\n\n# def get_loading_pipeline(pipeline):\n#     \"\"\"Only keep loading image and annotations related configuration.\n\n#     Args:\n#         pipeline (list[dict]): Data pipeline configs.\n\n#     Returns:\n#         list[dict]: The new pipeline list with only keep\n#             loading image and annotations related configuration.\n\n#     Examples:\n#         >>> pipelines = [\n#         ...    dict(type='LoadImageFromFile'),\n#         ...    dict(type='LoadAnnotations', with_bbox=True),\n#         ...    dict(type='Resize', img_scale=(1333, 800), keep_ratio=True),\n#         ...    dict(type='RandomFlip', flip_ratio=0.5),\n#         ...    dict(type='Normalize', **img_norm_cfg),\n#         ...    dict(type='Pad', size_divisor=32),\n#         ...    dict(type='DefaultFormatBundle'),\n#         ...    dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels'])\n#         ...    ]\n#         >>> expected_pipelines = [\n#         ...    dict(type='LoadImageFromFile'),\n#         ...    dict(type='LoadAnnotations', with_bbox=True)\n#         ...    ]\n#         >>> assert expected_pipelines ==\\\n#         ...        get_loading_pipeline(pipelines)\n#     \"\"\"\n#     loading_pipeline_cfg = []\n#     for cfg in pipeline:\n#         obj_cls = PIPELINES.get(cfg['type'])\n#         # TODO：use more elegant way to distinguish loading modules\n#         if obj_cls is not None and obj_cls in (LoadImageFromFile,\n#                                                LoadAnnotations):\n#             loading_pipeline_cfg.append(cfg)\n#     assert len(loading_pipeline_cfg) == 2, \\\n#         'The data pipeline in your config file must include ' \\\n#         'loading image and annotations related pipeline.'\n#     return loading_pipeline_cfg\n\n\n@HOOKS.register_module()\nclass NumClassCheckHook(Hook):\n\n    def _check_head(self, runner):\n        \"\"\"Check whether the `num_classes` in head matches the length of\n        `CLASSSES` in `dataset`.\n\n        Args:\n            runner (obj:`EpochBasedRunner`): Epoch based Runner.\n        \"\"\"\n        model = runner.model\n        dataset = runner.data_loader.dataset\n        if dataset.CLASSES is None:\n            runner.logger.warning(\n                f'Please set `CLASSES` '\n                f'in the {dataset.__class__.__name__} and'\n                f'check if it is consistent with the `num_classes` '\n                f'of head')\n        else:\n            assert type(dataset.CLASSES) is not str, \\\n                (f'`CLASSES` in {dataset.__class__.__name__}'\n                 f'should be a tuple of str.'\n                 f'Add comma if number of classes is 1 as '\n                 f'CLASSES = ({dataset.CLASSES},)')\n            for name, module in model.named_modules():\n                if hasattr(module, 'num_classes') and not isinstance(\n                        module, (RPNHead, VGG, FusedSemanticHead, GARPNHead)):\n                    assert module.num_classes == len(dataset.CLASSES), \\\n                        (f'The `num_classes` ({module.num_classes}) in '\n                         f'{module.__class__.__name__} of '\n                         f'{model.__class__.__name__} does not matches '\n                         f'the length of `CLASSES` '\n                         f'{len(dataset.CLASSES)}) in '\n                         f'{dataset.__class__.__name__}')\n\n    def before_train_epoch(self, runner):\n        \"\"\"Check whether the training dataset is compatible with head.\n\n        Args:\n            runner (obj:`EpochBasedRunner`): Epoch based Runner.\n        \"\"\"\n        self._check_head(runner)\n\n    def before_val_epoch(self, runner):\n        \"\"\"Check whether the dataset in val epoch is compatible with head.\n\n        Args:\n            runner (obj:`EpochBasedRunner`): Epoch based Runner.\n        \"\"\"\n        self._check_head(runner)\n        \n        \ndef is_loading_function(transform):\n    \"\"\"Judge whether a transform function is a loading function.\n\n    Note: `MultiScaleFlipAug3D` is a wrapper for multiple pipeline functions,\n    so we need to search if its inner transforms contain any loading function.\n\n    Args:\n        transform (dict | :obj:`Pipeline`): A transform config or a function.\n\n    Returns:\n        bool | None: Whether it is a loading function. None means can't judge.\n            When transform is `MultiScaleFlipAug3D`, we return None.\n    \"\"\"\n    # TODO: use more elegant way to distinguish loading modules\n    loading_functions = (LoadImageFromFile, LoadPointsFromFile,\n                         LoadAnnotations3D, LoadMultiViewImageFromFiles,\n                         LoadPointsFromMultiSweeps, DefaultFormatBundle3D,\n                         Collect3D, LoadImageFromFileMono3D,\n                         PointSegClassMapping)\n    if isinstance(transform, dict):\n        obj_cls = PIPELINES.get(transform['type'])\n        if obj_cls is None:\n            return False\n        if obj_cls in loading_functions:\n            return True\n        if obj_cls in (MultiScaleFlipAug3D, ):\n            return None\n    elif callable(transform):\n        if isinstance(transform, loading_functions):\n            return True\n        if isinstance(transform, MultiScaleFlipAug3D):\n            return None\n    return False\n\n\ndef get_loading_pipeline(pipeline):\n    \"\"\"Only keep loading image, points and annotations related configuration.\n\n    Args:\n        pipeline (list[dict] | list[:obj:`Pipeline`]):\n            Data pipeline configs or list of pipeline functions.\n\n    Returns:\n        list[dict] | list[:obj:`Pipeline`]): The new pipeline list with only\n            keep loading image, points and annotations related configuration.\n\n    Examples:\n        >>> pipelines = [\n        ...    dict(type='LoadPointsFromFile',\n        ...         coord_type='LIDAR', load_dim=4, use_dim=4),\n        ...    dict(type='LoadImageFromFile'),\n        ...    dict(type='LoadAnnotations3D',\n        ...         with_bbox=True, with_label_3d=True),\n        ...    dict(type='Resize',\n        ...         img_scale=[(640, 192), (2560, 768)], keep_ratio=True),\n        ...    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),\n        ...    dict(type='PointsRangeFilter',\n        ...         point_cloud_range=point_cloud_range),\n        ...    dict(type='ObjectRangeFilter',\n        ...         point_cloud_range=point_cloud_range),\n        ...    dict(type='PointShuffle'),\n        ...    dict(type='Normalize', **img_norm_cfg),\n        ...    dict(type='Pad', size_divisor=32),\n        ...    dict(type='DefaultFormatBundle3D', class_names=class_names),\n        ...    dict(type='Collect3D',\n        ...         keys=['points', 'img', 'gt_bboxes_3d', 'gt_labels_3d'])\n        ...    ]\n        >>> expected_pipelines = [\n        ...    dict(type='LoadPointsFromFile',\n        ...         coord_type='LIDAR', load_dim=4, use_dim=4),\n        ...    dict(type='LoadImageFromFile'),\n        ...    dict(type='LoadAnnotations3D',\n        ...         with_bbox=True, with_label_3d=True),\n        ...    dict(type='DefaultFormatBundle3D', class_names=class_names),\n        ...    dict(type='Collect3D',\n        ...         keys=['points', 'img', 'gt_bboxes_3d', 'gt_labels_3d'])\n        ...    ]\n        >>> assert expected_pipelines ==\\\n        ...        get_loading_pipeline(pipelines)\n    \"\"\"\n    loading_pipeline = []\n    for transform in pipeline:\n        is_loading = is_loading_function(transform)\n        if is_loading is None:  # MultiScaleFlipAug3D\n            # extract its inner pipeline\n            if isinstance(transform, dict):\n                inner_pipeline = transform.get('transforms', [])\n            else:\n                inner_pipeline = transform.transforms.transforms\n            loading_pipeline.extend(get_loading_pipeline(inner_pipeline))\n        elif is_loading:\n            loading_pipeline.append(transform)\n    assert len(loading_pipeline) > 0, \\\n        'The data pipeline in your config file must include ' \\\n        'loading step.'\n    return loading_pipeline\n\n\ndef extract_result_dict(results, key):\n    \"\"\"Extract and return the data corresponding to key in result dict.\n\n    ``results`` is a dict output from `pipeline(input_dict)`, which is the\n        loaded data from ``Dataset`` class.\n    The data terms inside may be wrapped in list, tuple and DataContainer, so\n        this function essentially extracts data from these wrappers.\n\n    Args:\n        results (dict): Data loaded using pipeline.\n        key (str): Key of the desired data.\n\n    Returns:\n        np.ndarray | torch.Tensor | None: Data term.\n    \"\"\"\n    if key not in results.keys():\n        return None\n    # results[key] may be data or list[data] or tuple[data]\n    # data may be wrapped inside DataContainer\n    data = results[key]\n    if isinstance(data, (list, tuple)):\n        data = data[0]\n    if isinstance(data, DataContainer):\n        data = data._data\n    return data\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/vad_custom_nuscenes_eval.py",
    "content": "import argparse\nimport copy\nimport json\nimport os\nimport time\nfrom typing import Tuple, Dict, Any\nfrom mmcv.fileio.io import dump,load\nimport torch\nimport numpy as np\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.detection.evaluate import NuScenesEval\nfrom pyquaternion import Quaternion\nfrom nuscenes.eval.detection.data_classes import DetectionBox\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.tracking.data_classes import TrackingBox\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import points_in_box\nfrom nuscenes.utils.splits import create_splits_scenes\nimport tqdm\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\nimport pycocotools.mask as mask_util\n# from projects.mmdet3d_plugin.models.utils.visual import save_tensor\nfrom torchvision.transforms.functional import rotate\nimport cv2\nimport argparse\nimport random\nfrom nuscenes.eval.common.loaders import load_gt, add_center_dist\nfrom nuscenes.eval.detection.algo import accumulate, calc_ap, calc_tp\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox,  DetectionMetricData,DetectionMetricDataList\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom IPython import embed\nfrom matplotlib import pyplot as plt\nfrom nuscenes.eval.common.render import setup_axis\nfrom nuscenes.eval.common.utils import boxes_to_sensor\nfrom nuscenes.eval.detection.constants import TP_METRICS, DETECTION_NAMES, DETECTION_COLORS, TP_METRICS_UNITS, \\\n    PRETTY_DETECTION_NAMES, PRETTY_TP_METRICS\nfrom nuscenes.utils.data_classes import LidarPointCloud\nimport mmcv\n\n\nAxis = Any\n\ndef class_tp_curve(md_list: DetectionMetricDataList,\n                   metrics: DetectionMetrics,\n                   detection_name: str,\n                   min_recall: float,\n                   dist_th_tp: float,\n                   savepath: str = None,\n                   ax: Axis = None) -> None:\n    \"\"\"\n    Plot the true positive curve for the specified class.\n    :param md_list: DetectionMetricDataList instance.\n    :param metrics: DetectionMetrics instance.\n    :param detection_name:\n    :param min_recall: Minimum recall value.\n    :param dist_th_tp: The distance threshold used to determine matches.\n    :param savepath: If given, saves the the rendering here instead of displaying.\n    :param ax: Axes onto which to render.\n    \"\"\"\n    # Get metric data for given detection class with tp distance threshold.\n\n    md = md_list[(detection_name, dist_th_tp)]\n    min_recall_ind = round(100 * min_recall)\n    if min_recall_ind <= md.max_recall_ind:\n        # For traffic_cone and barrier only a subset of the metrics are plotted.\n        rel_metrics = [m for m in TP_METRICS if not np.isnan(metrics.get_label_tp(detection_name, m))]\n        ylimit = max([max(getattr(md, metric)[min_recall_ind:md.max_recall_ind + 1]) for metric in rel_metrics]) * 1.1\n    else:\n        ylimit = 1.0\n\n    # Prepare axis.\n    if ax is None:\n        ax = setup_axis(title=PRETTY_DETECTION_NAMES[detection_name], xlabel='Recall', ylabel='Error', xlim=1,\n                        min_recall=min_recall)\n    ax.set_ylim(0, ylimit)\n\n    # Plot the recall vs. error curve for each tp metric.\n    for metric in TP_METRICS:\n        tp = metrics.get_label_tp(detection_name, metric)\n\n        # Plot only if we have valid data.\n        if tp is not np.nan and min_recall_ind <= md.max_recall_ind:\n            recall, error = md.recall[:md.max_recall_ind + 1], getattr(md, metric)[:md.max_recall_ind + 1]\n        else:\n            recall, error = [], []\n\n        # Change legend based on tp value\n        if tp is np.nan:\n            label = '{}: n/a'.format(PRETTY_TP_METRICS[metric])\n        elif min_recall_ind > md.max_recall_ind:\n            label = '{}: nan'.format(PRETTY_TP_METRICS[metric])\n        else:\n            label = '{}: {:.2f} ({})'.format(PRETTY_TP_METRICS[metric], tp, TP_METRICS_UNITS[metric])\n        if metric == 'trans_err':\n            label += f' ({md.max_recall_ind})'  # add recall\n            print(f'Recall: {detection_name}: {md.max_recall_ind/100}')\n        ax.plot(recall, error, label=label)\n    ax.axvline(x=md.max_recall, linestyle='-.', color=(0, 0, 0, 0.3))\n    ax.legend(loc='best')\n\n    if savepath is not None:\n        plt.savefig(savepath)\n        plt.close()\n\n\nclass DetectionBox_modified(DetectionBox):\n    def __init__(self, *args, token=None, visibility=None, index=None, **kwargs):\n        '''\n        add annotation token\n        '''\n        super().__init__(*args, **kwargs)\n        self.token = token\n        self.visibility = visibility\n        self.index = index\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'token': self.token,\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'visibility': self.visibility,\n            'index': self.index\n\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(\n            token=content['token'],\n            sample_token=content['sample_token'],\n            translation=tuple(content['translation']),\n            size=tuple(content['size']),\n            rotation=tuple(content['rotation']),\n            velocity=tuple(content['velocity']),\n            ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n            else tuple(content['ego_translation']),\n            num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n            detection_name=content['detection_name'],\n            detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n            attribute_name=content['attribute_name'],\n            visibility=content['visibility'],\n            index=content['index'],\n        )\n\n\ndef center_in_image(box, intrinsic: np.ndarray, imsize: Tuple[int, int], vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible inside an image without accounting for occlusions.\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    center_3d = box.center.reshape(3, 1)\n    center_img = view_points(center_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(center_img[0, :] > 0, center_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, center_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, center_img[1, :] > 0)\n    visible = np.logical_and(visible, center_3d[2, :] > 1)\n\n    in_front = center_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if vis_level == BoxVisibility.ALL:\n        return all(visible) and all(in_front)\n    elif vis_level == BoxVisibility.ANY:\n        return any(visible) and all(in_front)\n    elif vis_level == BoxVisibility.NONE:\n        return True\n    else:\n        raise ValueError(\"vis_level: {} not valid\".format(vis_level))\n\n\ndef exist_corners_in_image_but_not_all(box, intrinsic: np.ndarray, imsize: Tuple[int, int],\n                                       vis_level: int = BoxVisibility.ANY) -> bool:\n    \"\"\"\n    Check if a box is visible in images but not all corners in image .\n    :param box: The box to be checked.\n    :param intrinsic: <float: 3, 3>. Intrinsic camera matrix.\n    :param imsize: (width, height).\n    :param vis_level: One of the enumerations of <BoxVisibility>.\n    :return True if visibility condition is satisfied.\n    \"\"\"\n\n    corners_3d = box.corners()\n    corners_img = view_points(corners_3d, intrinsic, normalize=True)[:2, :]\n\n    visible = np.logical_and(corners_img[0, :] > 0, corners_img[0, :] < imsize[0])\n    visible = np.logical_and(visible, corners_img[1, :] < imsize[1])\n    visible = np.logical_and(visible, corners_img[1, :] > 0)\n    visible = np.logical_and(visible, corners_3d[2, :] > 1)\n\n    in_front = corners_3d[2, :] > 0.1  # True if a corner is at least 0.1 meter in front of the camera.\n\n    if any(visible) and not all(visible) and all(in_front):\n        return True\n    else:\n        return False\n\ndef load_prediction(result_path: str, max_boxes_per_sample: int, box_cls, verbose: bool = False) \\\n        -> Tuple[EvalBoxes, Dict]:\n    \"\"\"\n    Loads object predictions from file.\n    :param result_path: Path to the .json result file provided by the user.\n    :param max_boxes_per_sample: Maximim number of boxes allowed per sample.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The deserialized results and meta data.\n    \"\"\"\n\n    # Load from file and check that the format is correct.\n    # with open(result_path) as f:\n    #     data = json.load(f)\n    data = load(result_path)\n    assert 'results' in data, 'Error: No field `results` in result file. Please note that the result format changed.' \\\n                              'See https://www.nuscenes.org/object-detection for more information.'\n\n    # Deserialize results and get meta data.\n    all_results = EvalBoxes.deserialize(data['results'], box_cls)\n    meta = data['meta']\n    if verbose:\n        print(\"Loaded results from {}. Found detections for {} samples.\"\n              .format(result_path, len(all_results.sample_tokens)))\n\n    # Check that each sample has no more than x predicted boxes.\n    for sample_token in all_results.sample_tokens:\n        assert len(all_results.boxes[sample_token]) <= max_boxes_per_sample, \\\n            \"Error: Only <= %d boxes per sample allowed!\" % max_boxes_per_sample\n\n    return all_results, meta\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False):\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n\n    # Init.\n    if box_cls == DetectionBox_modified:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n    index_map = {}\n    for scene in nusc.scene:\n        first_sample_token = scene['first_sample_token']\n        sample = nusc.get('sample', first_sample_token)\n        index_map[first_sample_token] = 1\n        index = 2\n        while sample['next'] != '':\n            sample = nusc.get('sample', sample['next'])\n            index_map[sample['token']] = index\n            index += 1\n\n    sample_tokens = []\n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n\n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == DetectionBox_modified:\n                # Get label name in detection task and filter unused labels.\n                detection_name = category_to_detection_name(sample_annotation['category_name'])\n                if detection_name is None:\n                    continue\n\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n\n                sample_boxes.append(\n                    box_cls(\n                        token=sample_annotation_token,\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        visibility=sample_annotation['visibility_token'],\n                        index=index_map[sample_token]\n                    )\n                )\n            elif box_cls == TrackingBox:\n                assert False\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\n\ndef filter_eval_boxes_by_id(nusc: NuScenes,\n                            eval_boxes: EvalBoxes,\n                            id=None,\n                            verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.token in id:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_visibility(\n        ori_eval_boxes: EvalBoxes,\n        visibility=None,\n        verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param is: the anns token set that used to keep bboxes.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.visibility == visibility:\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After visibility based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\n\ndef filter_by_sample_token(ori_eval_boxes, valid_sample_tokens=[],  verbose=False):\n    eval_boxes = copy.deepcopy(ori_eval_boxes)\n    for sample_token in eval_boxes.sample_tokens:\n        if sample_token not in valid_sample_tokens:\n            eval_boxes.boxes.pop(sample_token)\n    return eval_boxes\n\n\ndef filter_eval_boxes_by_overlap(nusc: NuScenes,\n                                 eval_boxes: EvalBoxes,\n                                 verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. basedon overlap .\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n\n    # Accumulators for number of filtered boxes.\n    cams = ['CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_BACK_RIGHT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_FRONT_LEFT']\n\n    total, anns_filter = 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on anns\n        total += len(eval_boxes[sample_token])\n        sample_record = nusc.get('sample', sample_token)\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            count = 0\n            for cam in cams:\n                '''\n                copy-paste form nuscens\n                '''\n                sample_data_token = sample_record['data'][cam]\n                sd_record = nusc.get('sample_data', sample_data_token)\n                cs_record = nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])\n                sensor_record = nusc.get('sensor', cs_record['sensor_token'])\n                pose_record = nusc.get('ego_pose', sd_record['ego_pose_token'])\n                cam_intrinsic = np.array(cs_record['camera_intrinsic'])\n                imsize = (sd_record['width'], sd_record['height'])\n                new_box = Box(box.translation, box.size, Quaternion(box.rotation),\n                              name=box.detection_name, token='')\n\n                # Move box to ego vehicle coord system.\n                new_box.translate(-np.array(pose_record['translation']))\n                new_box.rotate(Quaternion(pose_record['rotation']).inverse)\n\n                #  Move box to sensor coord system.\n                new_box.translate(-np.array(cs_record['translation']))\n                new_box.rotate(Quaternion(cs_record['rotation']).inverse)\n\n                if center_in_image(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                    count += 1\n                # if exist_corners_in_image_but_not_all(new_box, cam_intrinsic, imsize, vis_level=BoxVisibility.ANY):\n                #    count += 1\n\n            if count > 1:\n                with open('center_overlap.txt', 'a') as f:\n                    try:\n                        f.write(box.token + '\\n')\n                    except:\n                        pass\n                filtered_boxes.append(box)\n        anns_filter += len(filtered_boxes)\n        eval_boxes.boxes[sample_token] = filtered_boxes\n\n    verbose = True\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After anns based filtering: %d\" % anns_filter)\n\n    return eval_boxes\n\ndef _get_box_class_field(eval_boxes: EvalBoxes) -> str:\n    \"\"\"\n    Retrieve the name of the class field in the boxes.\n    This parses through all boxes until it finds a valid box.\n    If there are no valid boxes, this function throws an exception.\n    :param eval_boxes: The EvalBoxes used for evaluation.\n    :return: The name of the class field in the boxes, e.g. detection_name or tracking_name.\n    \"\"\"\n    assert len(eval_boxes.boxes) > 0\n    box = None\n    for val in eval_boxes.boxes.values():\n        if len(val) > 0:\n            box = val[0]\n            break\n    if isinstance(box, DetectionBox):\n        class_field = 'detection_name'\n    elif isinstance(box, TrackingBox):\n        class_field = 'tracking_name'\n    else:\n        raise Exception('Error: Invalid box type: %s' % box)\n\n    return class_field\n\ndef filter_eval_boxes(nusc: NuScenes,\n                      eval_boxes: EvalBoxes,\n                      max_dist_x: Dict[str, float],\n                      max_dist_y: Dict[str, float],\n                      verbose: bool = False) -> EvalBoxes:\n    \"\"\"\n    Applies filtering to boxes. Distance, bike-racks and points per box.\n    :param nusc: An instance of the NuScenes class.\n    :param eval_boxes: An instance of the EvalBoxes class.\n    :param max_dist: Maps the detection name to the eval distance threshold for that class.\n    :param verbose: Whether to print to stdout.\n    \"\"\"\n    # Retrieve box type for detectipn/tracking boxes.\n    class_field = _get_box_class_field(eval_boxes)\n\n    # Accumulators for number of filtered boxes.\n    total, dist_filter, point_filter, bike_rack_filter = 0, 0, 0, 0\n    for ind, sample_token in enumerate(eval_boxes.sample_tokens):\n\n        # Filter on distance first.\n        total += len(eval_boxes[sample_token])\n        eval_boxes.boxes[sample_token] = [box for box in eval_boxes[sample_token] if\n                                          abs(box.ego_translation[0]) < max_dist_x[box.__getattribute__(class_field)] \\\n                                          and abs(box.ego_translation[1]) < max_dist_y[box.__getattribute__(class_field)]]\n        dist_filter += len(eval_boxes[sample_token])\n\n        # Then remove boxes with zero points in them. Eval boxes have -1 points by default.\n        eval_boxes.boxes[sample_token] = [box for box in eval_boxes[sample_token] if not box.num_pts == 0]\n        point_filter += len(eval_boxes[sample_token])\n\n        # Perform bike-rack filtering.\n        sample_anns = nusc.get('sample', sample_token)['anns']\n        bikerack_recs = [nusc.get('sample_annotation', ann) for ann in sample_anns if\n                         nusc.get('sample_annotation', ann)['category_name'] == 'static_object.bicycle_rack']\n        bikerack_boxes = [Box(rec['translation'], rec['size'], Quaternion(rec['rotation'])) for rec in bikerack_recs]\n        filtered_boxes = []\n        for box in eval_boxes[sample_token]:\n            if box.__getattribute__(class_field) in ['bicycle', 'motorcycle']:\n                in_a_bikerack = False\n                for bikerack_box in bikerack_boxes:\n                    if np.sum(points_in_box(bikerack_box, np.expand_dims(np.array(box.translation), axis=1))) > 0:\n                        in_a_bikerack = True\n                if not in_a_bikerack:\n                    filtered_boxes.append(box)\n            else:\n                filtered_boxes.append(box)\n\n        eval_boxes.boxes[sample_token] = filtered_boxes\n        bike_rack_filter += len(eval_boxes.boxes[sample_token])\n\n    if verbose:\n        print(\"=> Original number of boxes: %d\" % total)\n        print(\"=> After distance based filtering: %d\" % dist_filter)\n        print(\"=> After LIDAR and RADAR points based filtering: %d\" % point_filter)\n        print(\"=> After bike rack filtering: %d\" % bike_rack_filter)\n\n    return eval_boxes\n\nclass NuScenesEval_custom(NuScenesEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as DetectionEval.\n    \"\"\"\n\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 overlap_test=False,\n                 eval_mask=False,\n                 data_infos=None\n                 ):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n        self.overlap_test = overlap_test\n        self.eval_mask = eval_mask\n        self.data_infos = data_infos\n        # Check result file exists.\n        assert os.path.exists(result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, DetectionBox,\n                                                     verbose=verbose)\n        self.gt_boxes = load_gt(self.nusc, self.eval_set, DetectionBox_modified, verbose=verbose)\n\n        # assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n        #     \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        # Filter boxes (distance, points per box, etc.).\n\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(nusc, self.pred_boxes, self.cfg.class_range_x, self.cfg.class_range_y, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(nusc, self.gt_boxes, self.cfg.class_range_x, self.cfg.class_range_y, verbose=verbose)\n\n        if self.overlap_test:\n            self.pred_boxes = filter_eval_boxes_by_overlap(self.nusc, self.pred_boxes)\n\n            self.gt_boxes = filter_eval_boxes_by_overlap(self.nusc, self.gt_boxes, verbose=True)\n\n        self.all_gt = copy.deepcopy(self.gt_boxes)\n        self.all_preds = copy.deepcopy(self.pred_boxes)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n        self.index_map = {}\n        for scene in nusc.scene:\n            first_sample_token = scene['first_sample_token']\n            sample = nusc.get('sample', first_sample_token)\n            self.index_map[first_sample_token] = 1\n            index = 2\n            while sample['next'] != '':\n                sample = nusc.get('sample', sample['next'])\n                self.index_map[sample['token']] = index\n                index += 1\n\n    def update_gt(self, type_='vis', visibility='1', index=1):\n        if type_ == 'vis':\n            self.visibility_test = True\n            if self.visibility_test:\n                '''[{'description': 'visibility of whole object is between 0 and 40%',\n                'token': '1',\n                'level': 'v0-40'},\n                {'description': 'visibility of whole object is between 40 and 60%',\n                'token': '2',\n                'level': 'v40-60'},\n                {'description': 'visibility of whole object is between 60 and 80%',\n                'token': '3',\n                'level': 'v60-80'},\n                {'description': 'visibility of whole object is between 80 and 100%',\n                'token': '4',\n                'level': 'v80-100'}]'''\n\n                self.gt_boxes = filter_eval_boxes_by_visibility(self.all_gt, visibility, verbose=True)\n\n        elif type_ == 'ord':\n\n            valid_tokens = [key for (key, value) in self.index_map.items() if value == index]\n            # from IPython import embed\n            # embed()\n            self.gt_boxes = filter_by_sample_token(self.all_gt, valid_tokens)\n            self.pred_boxes = filter_by_sample_token(self.all_preds, valid_tokens)\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n\n    def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMetricDataList()\n\n        # print(self.cfg.dist_fcn_callable, self.cfg.dist_ths)\n        # self.cfg.dist_ths = [0.3]\n        # self.cfg.dist_fcn_callable\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md = accumulate(self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        metrics = DetectionMetrics(self.cfg)\n        for class_name in self.cfg.class_names:\n            # Compute APs.\n            for dist_th in self.cfg.dist_ths:\n                metric_data = metric_data_list[(class_name, dist_th)]\n                ap = calc_ap(metric_data, self.cfg.min_recall, self.cfg.min_precision)\n                metrics.add_label_ap(class_name, dist_th, ap)\n            # Compute TP metrics.\n            for metric_name in TP_METRICS:\n                metric_data = metric_data_list[(class_name, self.cfg.dist_th_tp)]\n                if class_name in ['traffic_cone'] and metric_name in ['attr_err', 'vel_err', 'orient_err']:\n                    tp = np.nan\n                elif class_name in ['barrier'] and metric_name in ['attr_err', 'vel_err']:\n                    tp = np.nan\n                else:\n                    tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                metrics.add_label_tp(class_name, metric_name, tp)\n\n        # Compute evaluation time.\n        metrics.add_runtime(time.time() - start_time)\n\n        return metrics, metric_data_list\n\n    def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(md_list, metrics, min_precision=self.cfg.min_precision, min_recall=self.cfg.min_recall,\n                     dist_th_tp=self.cfg.dist_th_tp, savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(md_list, metrics, detection_name, self.cfg.min_precision, self.cfg.min_recall,\n                           savepath=savepath(detection_name + '_pr'))\n\n            class_tp_curve(md_list, metrics, detection_name, self.cfg.min_recall, self.cfg.dist_th_tp,\n                           savepath=savepath(detection_name + '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(md_list, metrics, dist_th, self.cfg.min_precision, self.cfg.min_recall,\n                          savepath=savepath('dist_pr_' + str(dist_th)))\n\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(description='Evaluate nuScenes detection results.',\n                                     formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument('result_path', type=str, help='The submission as a JSON file.')\n    parser.add_argument('--output_dir', type=str, default='~/nuscenes-metrics',\n                        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument('--eval_set', type=str, default='val',\n                        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='data/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument('--version', type=str, default='v1.0-trainval',\n                        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument('--config_path', type=str, default='',\n                        help='Path to the configuration file.'\n                             'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument('--plot_examples', type=int, default=0,\n                        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = NuScenesEval_custom(nusc_, config=cfg_, result_path=result_path_, eval_set=eval_set_,\n                                    output_dir=output_dir_, verbose=verbose_)\n    for vis in ['1', '2', '3', '4']:\n        nusc_eval.update_gt(type_='vis', visibility=vis)\n        print(f'================ {vis} ===============')\n        nusc_eval.main(plot_examples=plot_examples_, render_curves=render_curves_)\n    #for index in range(1, 41):\n    #    nusc_eval.update_gt(type_='ord', index=index)\n    #\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/datasets/vis_utils.py",
    "content": "import numpy as np\nimport cv2\nfrom matplotlib import cm\nimport math\nimport open3d as o3d\nimport os\n\nWINDOW_HEIGHT = 900\nWINDOW_WIDTH = 1600\n\nDIS_CAR_SAVE = 50\nDIS_WALKER_SAVE = 50\nDIS_SIGN_SAVE = 50\nDIS_LIGHT_SAVE = 50\n\nedges = [[0,1], [1,3], [3,2], [2,0], [0,4], [4,5], [5,1], [5,7], [7,6], [6,4], [6,2], [7,3]]\n\ncarla_bbox_edges = [\n    (0, 1), (1, 2), (2, 3), (3, 0),  # Bottom face\n    (4, 5), (5, 6), (6, 7), (7, 4),  # Top face\n    (0, 4), (1, 5), (2, 6), (3, 7)   # Side edges connecting top and bottom faces\n]\n\nVIRIDIS = np.array(cm.get_cmap('plasma').colors)\nVID_RANGE = np.linspace(0.0, 1.0, VIRIDIS.shape[0])\nLABEL_COLORS = np.array([\n    (255, 255, 255), # None\n    (70, 70, 70),    # Building\n    (100, 40, 40),   # Fences\n    (55, 90, 80),    # Other\n    (220, 20, 60),   # Pedestrian\n    (153, 153, 153), # Pole\n    (157, 234, 50),  # RoadLines\n    (128, 64, 128),  # Road\n    (244, 35, 232),  # Sidewalk\n    (107, 142, 35),  # Vegetation\n    (0, 0, 142),     # Vehicle\n    (102, 102, 156), # Wall\n    (220, 220, 0),   # TrafficSign\n    (70, 130, 180),  # Sky\n    (81, 0, 81),     # Ground\n    (150, 100, 100), # Bridge\n    (230, 150, 140), # RailTrack\n    (180, 165, 180), # GuardRail\n    (250, 170, 30),  # TrafficLight\n    (110, 190, 160), # Static\n    (170, 120, 50),  # Dynamic\n    (45, 60, 150),   # Water\n    (145, 170, 100), # Terrain\n]) / 255.0 # normalize each channel [0-1] since is what Open3D uses\n\nSEM_SEG_LABEL_COLORS = {\n         0 : (  0,   0,   0),   # unlabeled      \n            # cityscape\n         1 : (128,  64, 128),   # road           \n         2 : (244,  35, 232),   # sidewalk       \n         3 : ( 70,  70,  70),   # building       \n         4 : (102, 102, 156),   # wall           \n         5 : (190, 153, 153),   # fence          \n         6 : (153, 153, 153),   # pole           \n         7 : (250, 170,  30),   # traffic light  \n         8 : (220, 220,   0),   # traffic sign   \n         9 : (107, 142,  35),   # vegetation     \n        10 : (152, 251, 152),   # terrain        \n        11 : ( 70, 130, 180),   # sky            \n        12 : (220,  20,  60),   # pedestrian     \n        13 : (255,   0,   0),   # rider          \n        14 : (  0,   0, 142),   # Car            \n        15 : (  0,   0,  70),   # truck          \n        16 : (  0,  60, 100),   # bus            \n        17 : (  0,  80, 100),   # train          \n        18 : (  0,   0, 230),   # motorcycle     \n        19 : (119,  11,  32),   # bicycle        \n            # custom\n        20 : (110, 190, 160),   # static    \n        21 : (170, 120,  50),   # dynamic   \n        22 : ( 55,  90,  80),   # other     \n        23 : ( 45,  60, 150),   # water     \n        24 : (157, 234,  50),   # road line \n        25 : ( 81,   0,  81),   # ground    \n        26 : (150, 100, 100),   # bridge    \n        27 : (230, 150, 140),   # rail track\n        28 : (180, 165, 180),   # guard rail\n}\n\nuniad_class_names = [\n    'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',\n    'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'\n]\n\ncarla_class_name = [\n    'car', 'truck', 'bus', 'van', 'motorcycle', 'bicycle', 'pedestrian', \n]\n\nTYPE_ID_MAP = {\n    #=================vehicle=================\n    # bicycle\n    'vehicle.bh.crossbike': 'bicycle',\n    \"vehicle.diamondback.century\": 'bicycle',\n    # car\n    \"vehicle.chevrolet.impala\": 'car',\n    \"vehicle.dodge.charger_2020\": 'car',\n    \"vehicle.dodge.charger_police_2020\": 'car',\n    \"vehicle.lincoln.mkz_2017\": 'car',\n    \"vehicle.lincoln.mkz_2020\": 'car',\n    \"vehicle.mini.cooper_s_2021\": 'car',\n    \"vehicle.mercedes.coupe_2020\": 'car',\n    \"vehicle.ford.mustang\": 'car',\n    \"vehicle.nissan.patrol_2021\": 'car',\n    \"vehicle.audi.tt\": 'car',\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked\": 'car',\n    # bus\n    # van\n    \"/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked\": \"van\",\n    #=========================================\n\n    #=================traffic sign============\n    # traffic.speed_limit\n    \"traffic.speed_limit.30\": 'speed_limit',\n    \"traffic.speed_limit.40\": 'speed_limit',\n    \"traffic.speed_limit.50\": 'speed_limit',\n    # traffic.traffic_light\n    \"traffic.traffic_light\": 'traffic_light',\n    # traffic.stop\n    \"traffic.stop\": 'stop',\n    #=========================================\n}\n\ndef calc_projected_2d_bbox(vertices_pos2d):\n    \"\"\" Takes in all vertices in pixel projection and calculates min and max of all x and y coordinates.\n        Returns left top, right bottom pixel coordinates for the 2d bounding box as a list of four values.\n        Note that vertices_pos2d contains a list of (y_pos2d, x_pos2d) tuples, or None\n    \"\"\"\n    x_coords = vertices_pos2d[:, 0]\n    y_coords = vertices_pos2d[:, 1]\n    min_x, max_x = np.min(x_coords), np.max(x_coords)\n    min_y, max_y = np.min(y_coords), np.max(y_coords)\n    return [min_x, min_y, max_x, max_y]\n\ndef calculate_occlusion(bbox, point_depth, agent, depth_map):\n    \"\"\"Calculate the occlusion value of a 2D bounding box.\n    Iterate through each point (pixel) in the bounding box and declare it occluded only\n    if the 4 surroinding points (pixels) are closer to the camera (by using the help of depth map)\n    than the actual distance to the middle of the 3D bounding boxe and some margin (the extent of the object)\n    \"\"\"\n    bbox_3d_mid = np.mean(point_depth)\n    min_x, min_y, max_x, max_y = calc_projected_2d_bbox(bbox)\n    height, width, length = agent.bounding_box.extent.z, agent.bounding_box.extent.x, agent.bounding_box.extent.y\n\n    #depth_margin should depend on the rotation of the object but this solution works fine\n    depth_margin = np.max([2 * width, 2 * length])\n    is_occluded = []\n\n    for x in range(int(min_x), int(max_x)):\n        for y in range(int(min_y), int(max_y)):\n            is_occluded.append(point_is_occluded(\n                (y, x), bbox_3d_mid - depth_margin, depth_map))\n\n    occlusion = ((float(np.sum(is_occluded))) / ((max_x-min_x) * (max_y-min_y)))\n    #discretize the 0–1 occlusion value into KITTI’s {0,1,2,3} labels by equally dividing the interval into 4 parts\n    # occlusion = np.digitize(occlusion, bins=[0.25, 0.50, 0.75])\n    return occlusion\n\ndef calculate_occlusion_vectorized(bbox, point_depth, extent, depth_map):\n    \"\"\"Calculate the occlusion value of a 2D bounding box.\n    Iterate through each point (pixel) in the bounding box and declare it occluded only\n    if the 4 surroinding points (pixels) are closer to the camera (by using the help of depth map)\n    than the actual distance to the middle of the 3D bounding boxe and some margin (the extent of the object)\n    \"\"\"\n    bbox_3d_mid = np.mean(point_depth)\n    min_x, min_y, max_x, max_y = calc_projected_2d_bbox(bbox)\n    height, width, length = extent[2], extent[0], extent[1]\n    depth_margin = np.max([2 * width, 2 * length])\n    count_num = (max_x - min_x) * (max_y - min_y)\n    if count_num > 10000:\n        p = 100 / count_num\n    elif count_num > 1000:\n        p = 100 / count_num\n    elif count_num > 100:\n        p = 100 / count_num\n    else:\n        p = 1\n    sample_step_approx = int(np.sqrt(1/p))\n\n    # x, y = np.meshgrid(np.arange(min_x, max_x), np.arange(min_y, max_y))\n    x, y = np.meshgrid(np.arange(min_x, max_x, sample_step_approx), np.arange(min_y, max_y, sample_step_approx))\n    points = np.stack((y.flatten(), x.flatten()), axis=1)\n    is_occluded_array = point_is_occluded_single(points, bbox_3d_mid - depth_margin, depth_map)\n    occlusion = is_occluded_array.mean()\n    #discretize the 0–1 occlusion value into KITTI’s {0,1,2,3} labels by equally dividing the interval into 4 parts\n    # occlusion = np.digitize(occlusion, bins=[0.25, 0.50, 0.75])\n    return occlusion\n\ndef calc_bbox2d_area(bbox_2d):\n    \"\"\" Calculate the area of the given 2d bbox\n    Input is assumed to be xmin, ymin, xmax, ymax tuple \n    \"\"\"\n    xmin, ymin, xmax, ymax = bbox_2d\n    return (ymax - ymin) * (xmax - xmin)\n\ndef calculate_truncation(uncropped_bbox, cropped_bbox):\n    \"Calculate how much of the object's 2D uncropped bounding box is outside the image boundary\"\n\n    area_cropped = calc_bbox2d_area(cropped_bbox)\n    area_uncropped = calc_bbox2d_area(uncropped_bbox)\n    truncation = 1.0 - float(area_cropped / area_uncropped)\n    return truncation\n\ndef crop_boxes_in_canvas(cam_bboxes):\n    neg_x_inds = np.where(cam_bboxes[:, 0] < 0)[0]\n    out_x_inds = np.where(cam_bboxes[:, 0] > WINDOW_WIDTH)[0]\n    neg_y_inds = np.where(cam_bboxes[:, 1] < 0)[0]\n    out_y_inds = np.where(cam_bboxes[:, 1] > WINDOW_HEIGHT)[0]\n    cam_bboxes[neg_x_inds, 0] = 0\n    cam_bboxes[out_x_inds, 0] = WINDOW_HEIGHT\n    cam_bboxes[neg_y_inds, 1] = 0\n    cam_bboxes[out_y_inds, 1] = WINDOW_WIDTH\n    return cam_bboxes\n\ndef point_is_occluded(point, vertex_depth, depth_map):\n    \"\"\" Checks whether or not the four pixels directly around the given point has less depth than the given vertex depth\n        If True, this means that the point is occluded.\n    \"\"\"\n    y, x = map(int, point)\n    from itertools import product\n    neigbours = product((1, -1), repeat=2)\n    is_occluded = []\n    for dy, dx in neigbours:\n        if point_in_canvas_hw((dy+y, dx+x)):\n            # If the depth map says the pixel is closer to the camera than the actual vertex\n            if depth_map[y+dy, x+dx] < vertex_depth:\n                is_occluded.append(True)\n            else:\n                is_occluded.append(False)\n    # Only say point is occluded if all four neighbours are closer to camera than vertex\n    return all(is_occluded)\n\ndef point_is_occluded_single(points, vertex_depth, depth_map, canvas_shape=(WINDOW_HEIGHT, WINDOW_WIDTH)):\n    '''\n    Simplified version that checks occlusion based only on the points' own depth\n    '''\n    points = np.asarray(points).astype(np.int32)\n    y, x = points[:, 0], points[:, 1]\n        \n    valid = (y >= 0) & (y < canvas_shape[0]) & \\\n            (x >= 0) & (x < canvas_shape[1])\n    \n    is_occluded = np.zeros(len(points), dtype=bool)\n    try:\n        is_occluded[valid] = depth_map[y[valid], x[valid]] < vertex_depth\n    except:\n        pass\n    return is_occluded\n\ndef point_is_occluded_vectorized(points, vertex_depth, depth_map, canvas_shape=(WINDOW_HEIGHT, WINDOW_WIDTH)):\n    '''\n    Equivalent to point_is_occluded\n    '''\n    points = np.asarray(points).astype(np.int32)\n    y, x = points[:, 0], points[:, 1]\n    \n    dy, dx = np.array([1, 1, -1, -1]), np.array([1, -1, 1, -1])\n    neighbour_y = y[:, np.newaxis] + dy\n    neighbour_x = x[:, np.newaxis] + dx\n    \n    valid = (neighbour_y >= 0) & (neighbour_y < canvas_shape[0]) & \\\n            (neighbour_x >= 0) & (neighbour_x < canvas_shape[1])\n    \n    neighbour_depths = np.full(neighbour_y.shape, np.inf)\n    for i in range(4):\n        mask = valid[:, i]\n        neighbour_depths[mask, i] = depth_map[neighbour_y[mask, i], neighbour_x[mask, i]]\n    \n    is_occluded = np.logical_and.reduce(neighbour_depths < vertex_depth, axis=1) & np.any(valid, axis=1)\n    return is_occluded\n\ndef draw_3d_bbox_vertex(image, points):\n    for x_2d, y_2d, vertex_color in points:\n        cv2.circle(image, (int(x_2d), int(y_2d)), radius=3, color=vertex_color, thickness=1)\n\ndef calculate_occlusion_stats(bbox_points, depth, depth_map, max_render_depth):\n    \"\"\" Draws each vertex in vertices_pos2d if it is in front of the camera\n        The color is based on whether the object is occluded or not.\n        Returns the number of visible vertices and the number of vertices outside the camera.\n    \"\"\"\n    num_visible_vertices = 0\n    num_invisible_vertices = 0\n    num_vertices_outside_camera = 0\n    points = []\n\n    for i in range(len(bbox_points)):\n        x_2d = bbox_points[i][0]\n        y_2d = bbox_points[i][1]\n        point_depth = depth[i]\n\n        # if the point is in front of the camera but not too far away\n        if max_render_depth > point_depth > 0 and point_in_canvas_hw((y_2d, x_2d)):\n            #is_occluded_v = point_is_occluded_vectorized([[y_2d, x_2d]], point_depth, depth_map)\n            is_occluded = point_is_occluded(\n                (y_2d, x_2d), point_depth, depth_map)\n                \n            if is_occluded:\n                vertex_color = (0,0,255) # bgr, red\n                num_invisible_vertices += 1\n            else:\n                num_visible_vertices += 1\n                vertex_color = (0,255,0) # bgr, green\n            points.append((x_2d, y_2d, vertex_color))\n        else:\n            num_vertices_outside_camera += 1\n    return num_visible_vertices, num_invisible_vertices, num_vertices_outside_camera, points\n\ndef get_intrinsic_matrix(camera):\n\n    width = int(camera.attributes['image_size_x'])\n    height = int(camera.attributes['image_size_y'])\n    fov = float(camera.attributes['fov'])\n\n    k = np.identity(3)\n    k[0, 2] = width / 2.0\n    k[1, 2] = height / 2.0\n    k[0, 0] = k[1, 1] = width / (2.0 * np.tan(fov * np.pi / 360.0))\n\n    return k\n\ndef get_image_point(loc, K, w2c):\n    # Calculate 2D projection of 3D coordinate\n\n    # Format the input coordinate (loc is a carla.Position object)\n    point = np.array([loc[0], loc[1], loc[2], 1])\n    # transform to camera coordinates\n    point_camera = np.dot(w2c, point)\n\n    # New we must change from UE4's coordinate system to an \"standard\"\n    # (x, y ,z) -> (y, -z, x)\n    # and we remove the fourth componebonent also\n    point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n\n    depth = point_camera[2]\n\n    # now project 3D->2D using the camera matrix\n    point_img = np.dot(K, point_camera)\n    # normalize\n    point_img[0] /= point_img[2]\n    point_img[1] /= point_img[2]\n    \n    return point_img[0:2], depth\n\ndef point_in_canvas_hw(pos):\n    \"\"\"Return true if point is in canvas\"\"\"\n    if (pos[0] >= 0) and (pos[0] < WINDOW_HEIGHT) and (pos[1] >= 0) and (pos[1] < WINDOW_WIDTH):\n        return True\n    return False\n\ndef point_in_canvas_wh(pos):\n    \"\"\"Return true if point is in canvas\"\"\"\n    if (pos[0] >= 0) and (pos[0] < WINDOW_WIDTH) and (pos[1] >= 0) and (pos[1] < WINDOW_HEIGHT):\n        return True\n    return False\n\ndef build_projection_matrix(w, h, fov, is_behind_camera=False):\n    focal = w / (2.0 * np.tan(fov * np.pi / 360.0))\n    K = np.identity(3)\n\n    if is_behind_camera:\n        K[0, 0] = K[1, 1] = -focal\n    else:\n        K[0, 0] = K[1, 1] = focal\n\n    K[0, 2] = w / 2.0\n    K[1, 2] = h / 2.0\n    return K\n\ndef rotate_3d(vector, theta):\n    theta = np.radians(theta)\n    R = np.array([[np.cos(theta), -np.sin(theta), 0],\n                [np.sin(theta), np.cos(theta), 0],\n                [0, 0, 1]])\n\n    v_rotated = np.dot(R, vector)\n    return np.array([v_rotated[0], v_rotated[1], v_rotated[2]])\n\ndef normalize_angle_degree(x):\n    x = x % 360.0\n    if x > 180.0:\n        x -= 360.0\n    return x\n\n\ndef algin_lidar(lidar, translation, yaw):\n    \"\"\"\n    Translates and rotates a LiDAR into a new coordinate system.\n    Rotation is inverse to translation and yaw\n    :param lidar: numpy LiDAR point cloud (N,3)\n    :param translation: translations in meters\n    :param yaw: yaw angle in radians\n    :return: numpy LiDAR point cloud in the new coordinate system.\n    \"\"\"\n\n    rotation_matrix = np.array([[np.cos(yaw), -np.sin(yaw), 0.0], [np.sin(yaw), np.cos(yaw), 0.0], [0.0, 0.0, 1.0]])\n\n    aligned_lidar = (rotation_matrix.T @ (lidar - translation).T).T\n\n    return aligned_lidar\n\ndef convert_depth(data):\n    \"\"\"\n    Computes the normalized depth from a CARLA depth map.\n    \"\"\"\n    data = data.astype(np.float16)\n\n    normalized = np.dot(data, [65536.0, 256.0, 1.0])\n    normalized /= (256 * 256 * 256 - 1)\n    return normalized * 1000\n\ndef get_relative_transform(ego_matrix, vehicle_matrix):\n    \"\"\"\n    Returns the position of the vehicle matrix in the ego coordinate system.\n    :param ego_matrix: ndarray 4x4 Matrix of the ego vehicle in global\n    coordinates\n    :param vehicle_matrix: ndarray 4x4 Matrix of another actor in global\n    coordinates\n    :return: ndarray position of the other vehicle in the ego coordinate system\n    \"\"\"\n    relative_pos = vehicle_matrix[:3, 3] - ego_matrix[:3, 3]\n    rot = ego_matrix[:3, :3].T\n    relative_pos = rot @ relative_pos\n\n    return relative_pos\n\ndef normalize_angle(x):\n    x = x % (2 * np.pi)  # force in range [0, 2 pi)\n    if x > np.pi:  # move to [-pi, pi)\n        x -= 2 * np.pi\n    return x\n\ndef build_skeleton(ped, sk_links):\n\n    ######## get the pedestrian skeleton #########\n    bones = ped.get_bones()\n\n    # list where we will store the lines we will project\n    # onto the camera output\n    lines_3d = []\n\n    # cycle through the bone pairs in skeleton.txt and retrieve the joint positions\n    for link in sk_links[1:]:\n\n        # get the roots of the two bones to be joined\n        bone_transform_1 = next(filter(lambda b: b.name == link[0], bones.bone_transforms), None)\n        bone_transform_2 = next(filter(lambda b: b.name == link[1], bones.bone_transforms), None)\n\n        # some bone names aren't matched\n        if bone_transform_1 is not None and bone_transform_2 is not None:\n            lines_3d.append([(bone_transform_1.world.location.x, bone_transform_1.world.location.y, bone_transform_1.world.location.z), \n                             (bone_transform_2.world.location.x, bone_transform_2.world.location.y, bone_transform_2.world.location.z)]\n                            )\n    return lines_3d\n\ndef get_center_and_extent(verts):\n    sum_x = sum_y = sum_z = 0\n    max_x = max_y = max_z = float('-inf')\n    min_x = min_y = min_z = float('inf')\n\n    for pos in verts:\n        sum_x += pos.x\n        sum_y += pos.y\n        sum_z += pos.z\n        \n        max_x = max(max_x, pos.x)\n        max_y = max(max_y, pos.y)\n        max_z = max(max_z, pos.z)\n        \n        min_x = min(min_x, pos.x)\n        min_y = min(min_y, pos.y)\n        min_z = min(min_z, pos.z)\n    \n    center = (sum_x / 8, sum_y / 8, sum_z / 8)\n    \n    extent = ((max_x - min_x)/2, (max_y - min_y)/2, (max_z - min_z)/2)\n    return center, extent\n\ndef get_forward_vector(yaw):\n\n    yaw_rad = math.radians(yaw)\n\n    x = math.cos(yaw_rad)\n    y = math.sin(yaw_rad)\n\n    z = 0\n    return np.array([x, y, z])\n\ndef calculate_cube_vertices(center, extent):\n    cx, cy, cz = center\n    x, y, z = extent\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\n\ndef calculate_cube_vertices_2(center, extent):\n    cx, cy, cz = center.x,  center.y,  center.z\n    x, y, z = extent.x, extent.y, extent.z\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\ndef calculate_cube_vertices_3(center, extent):\n    cx, cy, cz = center[0],  center[1],  center[2]\n    x, y, z = extent[0], extent[1], extent[2]\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\n\n\n\ndef draw_dashed_line(img, start_point, end_point, color, thickness=1, dash_length=5):\n\n    d = np.sqrt((end_point[0] - start_point[0])**2 + (end_point[1] - start_point[1])**2)\n    dx = (end_point[0] - start_point[0]) / d\n    dy = (end_point[1] - start_point[1]) / d\n\n    x, y = start_point[0], start_point[1]\n\n    while d >= dash_length:\n  \n        x_end = x + dx * dash_length\n        y_end = y + dy * dash_length\n        cv2.line(img, (int(x), int(y)), (int(x_end), int(y_end)), color, thickness)\n        x = x_end + dx * dash_length\n        y = y_end + dy * dash_length\n        d -= 2 * dash_length\n\ndef get_matrix(location, rotation):\n    \"\"\"\n    Creates matrix from carla transform.\n    \"\"\"\n    pitch, roll, yaw = rotation\n    x, y, z = location\n    c_y = np.cos(np.radians(yaw))\n    s_y = np.sin(np.radians(yaw))\n    c_r = np.cos(np.radians(roll))\n    s_r = np.sin(np.radians(roll))\n    c_p = np.cos(np.radians(pitch))\n    s_p = np.sin(np.radians(pitch))\n    matrix = np.matrix(np.identity(4))\n    matrix[0, 3] = x\n    matrix[1, 3] = y\n    matrix[2, 3] = z\n    matrix[0, 0] = c_p * c_y\n    matrix[0, 1] = c_y * s_p * s_r - s_y * c_r\n    matrix[0, 2] = -c_y * s_p * c_r - s_y * s_r\n    matrix[1, 0] = s_y * c_p\n    matrix[1, 1] = s_y * s_p * s_r + c_y * c_r\n    matrix[1, 2] = -s_y * s_p * c_r + c_y * s_r\n    matrix[2, 0] = s_p\n    matrix[2, 1] = -c_p * s_r\n    matrix[2, 2] = c_p * c_r\n    return matrix\n\ndef euler_to_rotation_matrix(pitch, roll, yaw):\n    Ry_pitch = np.array([\n        [np.cos(pitch), 0, np.sin(pitch)],\n        [0, 1, 0],\n        [-np.sin(pitch), 0, np.cos(pitch)]\n    ])\n    Rx_roll = np.array([\n        [1, 0, 0],\n        [0, np.cos(roll), -np.sin(roll)],\n        [0, np.sin(roll), np.cos(roll)]\n    ])\n    Rz_yaw = np.array([\n        [np.cos(yaw), -np.sin(yaw), 0],\n        [np.sin(yaw), np.cos(yaw), 0],\n        [0, 0, 1]\n    ])\n    return np.dot(Rz_yaw, np.dot(Rx_roll, Ry_pitch))\n\ndef world_to_ego_no(point_world, ego_location, ego_rotation):\n    rotation_matrix = euler_to_rotation_matrix(np.radians(ego_rotation[0]),\n                                               np.radians(ego_rotation[1]),\n                                               np.radians(ego_rotation[2]))\n    \n    point_relative = np.array(point_world) - np.array(ego_location)\n    point = np.dot(rotation_matrix, point_relative)\n    # (x, y ,z) -> (y, -x, z)\n    point = [point[0], -point[1], point[2]]\n    return point\n\ndef world_to_ego(point_world, w2e):\n    point_world = np.array([point_world[0], point_world[1], point_world[2], 1])\n    point_ego = np.dot(w2e, point_world)\n    point_ego = [point_ego[1], -point_ego[0], point_ego[2]]\n    return point_ego\n\ndef world_to_lidar(point_world, w2l):\n    point_world = np.array([point_world[0], point_world[1], point_world[2], 1])\n    point_lidar = np.dot(w2l, point_world)\n    return point_lidar\n\ndef vector_angle(v1, v2):\n    dot_product = np.dot(v1, v2)\n    magnitude_v1 = np.linalg.norm(v1)\n    magnitude_v2 = np.linalg.norm(v2)\n    cos_theta = dot_product / (magnitude_v1 * magnitude_v2)\n    angle_radians = np.arccos(cos_theta)\n    angle_degrees = np.degrees(angle_radians)\n    return angle_degrees\n\ndef get_weather_id(weather_conditions):\n    from xml.etree import ElementTree as ET\n    tree = ET.parse('./weather.xml')\n    root = tree.getroot()\n    def conditions_match(weather, conditions):\n        for (key, value) in weather:\n            if key == 'route_percentage' : continue\n            if str(conditions[key]) != value:\n                return False\n        return True\n    for case in root.findall('case'):\n        weather = case[0].items()\n        if conditions_match(weather, weather_conditions):\n            return case.items()[0][1]\n    return None\n\n\ndef static_weather(path):\n    import gzip\n    import json\n    static_dict = {}\n    for dir in os.listdir(path):\n        for d1 in os.listdir(os.path.join(path, dir)):\n            if os.path.exists(os.path.join(path, dir, d1, 'anno/00000.json.gz')):\n                with gzip.open(os.path.join(path, dir, d1, 'anno/00000.json.gz'), 'rt', encoding='utf-8') as gz_file:\n                    anno = json.load(gz_file)\n                    weather = anno['weather']\n                    weather_id = get_weather_id(weather)\n                    static_dict[weather_id] = static_dict.get(weather_id, 0) + 1\n    print(static_dict)\n    return \n\nif __name__ == '__main__':\n\n    path = ''\n    static_weather(path)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n# from .file_client import BaseStorageBackend, FileClient\n# from .io import dump, load, imread #register_handler\n# from .handlers import PickleHandler, JsonHandler\n# from .parse import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/file_client.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport inspect\nimport os\nimport os.path as osp\nimport re\nimport tempfile\nimport warnings\nfrom abc import ABCMeta, abstractmethod\nfrom contextlib import contextmanager\nfrom pathlib import Path\nfrom typing import Iterable, Iterator, Optional, Tuple, Union\nfrom urllib.request import urlopen\nfrom mmcv.utils.misc import has_method\nfrom mmcv.utils.path import is_filepath, mkdir_or_exist\n\n\nclass BaseStorageBackend(metaclass=ABCMeta):\n    \"\"\"Abstract class of storage backends.\n\n    All backends need to implement two apis: ``get()`` and ``get_text()``.\n    ``get()`` reads the file as a byte stream and ``get_text()`` reads the file\n    as texts.\n    \"\"\"\n\n    # a flag to indicate whether the backend can create a symlink for a file\n    _allow_symlink = False\n\n    @property\n    def name(self):\n        return self.__class__.__name__\n\n    @property\n    def allow_symlink(self):\n        return self._allow_symlink\n\n    @abstractmethod\n    def get(self, filepath):\n        pass\n\n    @abstractmethod\n    def get_text(self, filepath):\n        pass\n\n\nclass CephBackend(BaseStorageBackend):\n    \"\"\"Ceph storage backend (for internal use).\n\n    Args:\n        path_mapping (dict|None): path mapping dict from local path to Petrel\n            path. When ``path_mapping={'src': 'dst'}``, ``src`` in ``filepath``\n            will be replaced by ``dst``. Default: None.\n\n    .. warning::\n        :class:`mmcv.fileio.file_client.CephBackend` will be deprecated,\n        please use :class:`mmcv.fileio.file_client.PetrelBackend` instead.\n    \"\"\"\n\n    def __init__(self, path_mapping=None):\n        try:\n            import ceph\n        except ImportError:\n            raise ImportError('Please install ceph to enable CephBackend.')\n\n        warnings.warn(\n            'CephBackend will be deprecated, please use PetrelBackend instead')\n        self._client = ceph.S3Client()\n        assert isinstance(path_mapping, dict) or path_mapping is None\n        self.path_mapping = path_mapping\n\n    def get(self, filepath):\n        filepath = str(filepath)\n        if self.path_mapping is not None:\n            for k, v in self.path_mapping.items():\n                filepath = filepath.replace(k, v)\n        value = self._client.Get(filepath)\n        value_buf = memoryview(value)\n        return value_buf\n\n    def get_text(self, filepath, encoding=None):\n        raise NotImplementedError\n\n\nclass PetrelBackend(BaseStorageBackend):\n    \"\"\"Petrel storage backend (for internal use).\n\n    PetrelBackend supports reading and writing data to multiple clusters.\n    If the file path contains the cluster name, PetrelBackend will read data\n    from specified cluster or write data to it. Otherwise, PetrelBackend will\n    access the default cluster.\n\n    Args:\n        path_mapping (dict, optional): Path mapping dict from local path to\n            Petrel path. When ``path_mapping={'src': 'dst'}``, ``src`` in\n            ``filepath`` will be replaced by ``dst``. Default: None.\n        enable_mc (bool, optional): Whether to enable memcached support.\n            Default: True.\n\n    Examples:\n        >>> filepath1 = 's3://path/of/file'\n        >>> filepath2 = 'cluster-name:s3://path/of/file'\n        >>> client = PetrelBackend()\n        >>> client.get(filepath1)  # get data from default cluster\n        >>> client.get(filepath2)  # get data from 'cluster-name' cluster\n    \"\"\"\n\n    def __init__(self,\n                 path_mapping: Optional[dict] = None,\n                 enable_mc: bool = True):\n        try:\n            from petrel_client import client\n        except ImportError:\n            raise ImportError('Please install petrel_client to enable '\n                              'PetrelBackend.')\n\n        self._client = client.Client(enable_mc=enable_mc)\n        assert isinstance(path_mapping, dict) or path_mapping is None\n        self.path_mapping = path_mapping\n\n    def _map_path(self, filepath: Union[str, Path]) -> str:\n        \"\"\"Map ``filepath`` to a string path whose prefix will be replaced by\n        :attr:`self.path_mapping`.\n\n        Args:\n            filepath (str): Path to be mapped.\n        \"\"\"\n        filepath = str(filepath)\n        if self.path_mapping is not None:\n            for k, v in self.path_mapping.items():\n                filepath = filepath.replace(k, v)\n        return filepath\n\n    def _format_path(self, filepath: str) -> str:\n        \"\"\"Convert a ``filepath`` to standard format of petrel oss.\n\n        If the ``filepath`` is concatenated by ``os.path.join``, in a Windows\n        environment, the ``filepath`` will be the format of\n        's3://bucket_name\\\\image.jpg'. By invoking :meth:`_format_path`, the\n        above ``filepath`` will be converted to 's3://bucket_name/image.jpg'.\n\n        Args:\n            filepath (str): Path to be formatted.\n        \"\"\"\n        return re.sub(r'\\\\+', '/', filepath)\n\n    def get(self, filepath: Union[str, Path]) -> memoryview:\n        \"\"\"Read data from a given ``filepath`` with 'rb' mode.\n\n        Args:\n            filepath (str or Path): Path to read data.\n\n        Returns:\n            memoryview: A memory view of expected bytes object to avoid\n                copying. The memoryview object can be converted to bytes by\n                ``value_buf.tobytes()``.\n        \"\"\"\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        value = self._client.Get(filepath)\n        value_buf = memoryview(value)\n        return value_buf\n\n    def get_text(self,\n                 filepath: Union[str, Path],\n                 encoding: str = 'utf-8') -> str:\n        \"\"\"Read data from a given ``filepath`` with 'r' mode.\n\n        Args:\n            filepath (str or Path): Path to read data.\n            encoding (str): The encoding format used to open the ``filepath``.\n                Default: 'utf-8'.\n\n        Returns:\n            str: Expected text reading from ``filepath``.\n        \"\"\"\n        return str(self.get(filepath), encoding=encoding)\n\n    def put(self, obj: bytes, filepath: Union[str, Path]) -> None:\n        \"\"\"Save data to a given ``filepath``.\n\n        Args:\n            obj (bytes): Data to be saved.\n            filepath (str or Path): Path to write data.\n        \"\"\"\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        self._client.put(filepath, obj)\n\n    def put_text(self,\n                 obj: str,\n                 filepath: Union[str, Path],\n                 encoding: str = 'utf-8') -> None:\n        \"\"\"Save data to a given ``filepath``.\n\n        Args:\n            obj (str): Data to be written.\n            filepath (str or Path): Path to write data.\n            encoding (str): The encoding format used to encode the ``obj``.\n                Default: 'utf-8'.\n        \"\"\"\n        self.put(bytes(obj, encoding=encoding), filepath)\n\n    def remove(self, filepath: Union[str, Path]) -> None:\n        \"\"\"Remove a file.\n\n        Args:\n            filepath (str or Path): Path to be removed.\n        \"\"\"\n        if not has_method(self._client, 'delete'):\n            raise NotImplementedError(\n                ('Current version of Petrel Python SDK has not supported '\n                 'the `delete` method, please use a higher version or dev'\n                 ' branch instead.'))\n\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        self._client.delete(filepath)\n\n    def exists(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path exists.\n\n        Args:\n            filepath (str or Path): Path to be checked whether exists.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` exists, ``False`` otherwise.\n        \"\"\"\n        if not (has_method(self._client, 'contains')\n                and has_method(self._client, 'isdir')):\n            raise NotImplementedError(\n                ('Current version of Petrel Python SDK has not supported '\n                 'the `contains` and `isdir` methods, please use a higher'\n                 'version or dev branch instead.'))\n\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        return self._client.contains(filepath) or self._client.isdir(filepath)\n\n    def isdir(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path is a directory.\n\n        Args:\n            filepath (str or Path): Path to be checked whether it is a\n                directory.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` points to a directory,\n                ``False`` otherwise.\n        \"\"\"\n        if not has_method(self._client, 'isdir'):\n            raise NotImplementedError(\n                ('Current version of Petrel Python SDK has not supported '\n                 'the `isdir` method, please use a higher version or dev'\n                 ' branch instead.'))\n\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        return self._client.isdir(filepath)\n\n    def isfile(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path is a file.\n\n        Args:\n            filepath (str or Path): Path to be checked whether it is a file.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` points to a file, ``False``\n                otherwise.\n        \"\"\"\n        if not has_method(self._client, 'contains'):\n            raise NotImplementedError(\n                ('Current version of Petrel Python SDK has not supported '\n                 'the `contains` method, please use a higher version or '\n                 'dev branch instead.'))\n\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        return self._client.contains(filepath)\n\n    def join_path(self, filepath: Union[str, Path],\n                  *filepaths: Union[str, Path]) -> str:\n        \"\"\"Concatenate all file paths.\n\n        Args:\n            filepath (str or Path): Path to be concatenated.\n\n        Returns:\n            str: The result after concatenation.\n        \"\"\"\n        filepath = self._format_path(self._map_path(filepath))\n        if filepath.endswith('/'):\n            filepath = filepath[:-1]\n        formatted_paths = [filepath]\n        for path in filepaths:\n            formatted_paths.append(self._format_path(self._map_path(path)))\n        return '/'.join(formatted_paths)\n\n    @contextmanager\n    def get_local_path(self, filepath: Union[str, Path]) -> Iterable[str]:\n        \"\"\"Download a file from ``filepath`` and return a temporary path.\n\n        ``get_local_path`` is decorated by :meth:`contxtlib.contextmanager`. It\n        can be called with ``with`` statement, and when exists from the\n        ``with`` statement, the temporary path will be released.\n\n        Args:\n            filepath (str | Path): Download a file from ``filepath``.\n\n        Examples:\n            >>> client = PetrelBackend()\n            >>> # After existing from the ``with`` clause,\n            >>> # the path will be removed\n            >>> with client.get_local_path('s3://path/of/your/file') as path:\n            ...     # do something here\n\n        Yields:\n            Iterable[str]: Only yield one temporary path.\n        \"\"\"\n        filepath = self._map_path(filepath)\n        filepath = self._format_path(filepath)\n        assert self.isfile(filepath)\n        try:\n            f = tempfile.NamedTemporaryFile(delete=False)\n            f.write(self.get(filepath))\n            f.close()\n            yield f.name\n        finally:\n            os.remove(f.name)\n\n    def list_dir_or_file(self,\n                         dir_path: Union[str, Path],\n                         list_dir: bool = True,\n                         list_file: bool = True,\n                         suffix: Optional[Union[str, Tuple[str]]] = None,\n                         recursive: bool = False) -> Iterator[str]:\n        \"\"\"Scan a directory to find the interested directories or files in\n        arbitrary order.\n\n        Note:\n            Petrel has no concept of directories but it simulates the directory\n            hierarchy in the filesystem through public prefixes. In addition,\n            if the returned path ends with '/', it means the path is a public\n            prefix which is a logical directory.\n\n        Note:\n            :meth:`list_dir_or_file` returns the path relative to ``dir_path``.\n            In addition, the returned path of directory will not contains the\n            suffix '/' which is consistent with other backends.\n\n        Args:\n            dir_path (str | Path): Path of the directory.\n            list_dir (bool): List the directories. Default: True.\n            list_file (bool): List the path of files. Default: True.\n            suffix (str or tuple[str], optional):  File suffix\n                that we are interested in. Default: None.\n            recursive (bool): If set to True, recursively scan the\n                directory. Default: False.\n\n        Yields:\n            Iterable[str]: A relative path to ``dir_path``.\n        \"\"\"\n        if not has_method(self._client, 'list'):\n            raise NotImplementedError(\n                ('Current version of Petrel Python SDK has not supported '\n                 'the `list` method, please use a higher version or dev'\n                 ' branch instead.'))\n\n        dir_path = self._map_path(dir_path)\n        dir_path = self._format_path(dir_path)\n        if list_dir and suffix is not None:\n            raise TypeError(\n                '`list_dir` should be False when `suffix` is not None')\n\n        if (suffix is not None) and not isinstance(suffix, (str, tuple)):\n            raise TypeError('`suffix` must be a string or tuple of strings')\n\n        # Petrel's simulated directory hierarchy assumes that directory paths\n        # should end with `/`\n        if not dir_path.endswith('/'):\n            dir_path += '/'\n\n        root = dir_path\n\n        def _list_dir_or_file(dir_path, list_dir, list_file, suffix,\n                              recursive):\n            for path in self._client.list(dir_path):\n                # the `self.isdir` is not used here to determine whether path\n                # is a directory, because `self.isdir` relies on\n                # `self._client.list`\n                if path.endswith('/'):  # a directory path\n                    next_dir_path = self.join_path(dir_path, path)\n                    if list_dir:\n                        # get the relative path and exclude the last\n                        # character '/'\n                        rel_dir = next_dir_path[len(root):-1]\n                        yield rel_dir\n                    if recursive:\n                        yield from _list_dir_or_file(next_dir_path, list_dir,\n                                                     list_file, suffix,\n                                                     recursive)\n                else:  # a file path\n                    absolute_path = self.join_path(dir_path, path)\n                    rel_path = absolute_path[len(root):]\n                    if (suffix is None\n                            or rel_path.endswith(suffix)) and list_file:\n                        yield rel_path\n\n        return _list_dir_or_file(dir_path, list_dir, list_file, suffix,\n                                 recursive)\n\n\nclass MemcachedBackend(BaseStorageBackend):\n    \"\"\"Memcached storage backend.\n\n    Attributes:\n        server_list_cfg (str): Config file for memcached server list.\n        client_cfg (str): Config file for memcached client.\n        sys_path (str | None): Additional path to be appended to `sys.path`.\n            Default: None.\n    \"\"\"\n\n    def __init__(self, server_list_cfg, client_cfg, sys_path=None):\n        if sys_path is not None:\n            import sys\n            sys.path.append(sys_path)\n        try:\n            import mc\n        except ImportError:\n            raise ImportError(\n                'Please install memcached to enable MemcachedBackend.')\n\n        self.server_list_cfg = server_list_cfg\n        self.client_cfg = client_cfg\n        self._client = mc.MemcachedClient.GetInstance(self.server_list_cfg,\n                                                      self.client_cfg)\n        # mc.pyvector servers as a point which points to a memory cache\n        self._mc_buffer = mc.pyvector()\n\n    def get(self, filepath):\n        filepath = str(filepath)\n        import mc\n        self._client.Get(filepath, self._mc_buffer)\n        value_buf = mc.ConvertBuffer(self._mc_buffer)\n        return value_buf\n\n    def get_text(self, filepath, encoding=None):\n        raise NotImplementedError\n\n\nclass LmdbBackend(BaseStorageBackend):\n    \"\"\"Lmdb storage backend.\n\n    Args:\n        db_path (str): Lmdb database path.\n        readonly (bool, optional): Lmdb environment parameter. If True,\n            disallow any write operations. Default: True.\n        lock (bool, optional): Lmdb environment parameter. If False, when\n            concurrent access occurs, do not lock the database. Default: False.\n        readahead (bool, optional): Lmdb environment parameter. If False,\n            disable the OS filesystem readahead mechanism, which may improve\n            random read performance when a database is larger than RAM.\n            Default: False.\n\n    Attributes:\n        db_path (str): Lmdb database path.\n    \"\"\"\n\n    def __init__(self,\n                 db_path,\n                 readonly=True,\n                 lock=False,\n                 readahead=False,\n                 **kwargs):\n        try:\n            import lmdb\n        except ImportError:\n            raise ImportError('Please install lmdb to enable LmdbBackend.')\n\n        self.db_path = str(db_path)\n        self._client = lmdb.open(\n            self.db_path,\n            readonly=readonly,\n            lock=lock,\n            readahead=readahead,\n            **kwargs)\n\n    def get(self, filepath):\n        \"\"\"Get values according to the filepath.\n\n        Args:\n            filepath (str | obj:`Path`): Here, filepath is the lmdb key.\n        \"\"\"\n        filepath = str(filepath)\n        with self._client.begin(write=False) as txn:\n            value_buf = txn.get(filepath.encode('ascii'))\n        return value_buf\n\n    def get_text(self, filepath, encoding=None):\n        raise NotImplementedError\n\n\nclass HardDiskBackend(BaseStorageBackend):\n    \"\"\"Raw hard disks storage backend.\"\"\"\n\n    _allow_symlink = True\n\n    def get(self, filepath: Union[str, Path]) -> bytes:\n        \"\"\"Read data from a given ``filepath`` with 'rb' mode.\n\n        Args:\n            filepath (str or Path): Path to read data.\n\n        Returns:\n            bytes: Expected bytes object.\n        \"\"\"\n        with open(filepath, 'rb') as f:\n            value_buf = f.read()\n        return value_buf\n\n    def get_text(self,\n                 filepath: Union[str, Path],\n                 encoding: str = 'utf-8') -> str:\n        \"\"\"Read data from a given ``filepath`` with 'r' mode.\n\n        Args:\n            filepath (str or Path): Path to read data.\n            encoding (str): The encoding format used to open the ``filepath``.\n                Default: 'utf-8'.\n\n        Returns:\n            str: Expected text reading from ``filepath``.\n        \"\"\"\n        with open(filepath, 'r', encoding=encoding) as f:\n            value_buf = f.read()\n        return value_buf\n\n    def put(self, obj: bytes, filepath: Union[str, Path]) -> None:\n        \"\"\"Write data to a given ``filepath`` with 'wb' mode.\n\n        Note:\n            ``put`` will create a directory if the directory of ``filepath``\n            does not exist.\n\n        Args:\n            obj (bytes): Data to be written.\n            filepath (str or Path): Path to write data.\n        \"\"\"\n        mkdir_or_exist(osp.dirname(filepath))\n        with open(filepath, 'wb') as f:\n            f.write(obj)\n\n    def put_text(self,\n                 obj: str,\n                 filepath: Union[str, Path],\n                 encoding: str = 'utf-8') -> None:\n        \"\"\"Write data to a given ``filepath`` with 'w' mode.\n\n        Note:\n            ``put_text`` will create a directory if the directory of\n            ``filepath`` does not exist.\n\n        Args:\n            obj (str): Data to be written.\n            filepath (str or Path): Path to write data.\n            encoding (str): The encoding format used to open the ``filepath``.\n                Default: 'utf-8'.\n        \"\"\"\n        mkdir_or_exist(osp.dirname(filepath))\n        with open(filepath, 'w', encoding=encoding) as f:\n            f.write(obj)\n\n    def remove(self, filepath: Union[str, Path]) -> None:\n        \"\"\"Remove a file.\n\n        Args:\n            filepath (str or Path): Path to be removed.\n        \"\"\"\n        os.remove(filepath)\n\n    def exists(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path exists.\n\n        Args:\n            filepath (str or Path): Path to be checked whether exists.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` exists, ``False`` otherwise.\n        \"\"\"\n        return osp.exists(filepath)\n\n    def isdir(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path is a directory.\n\n        Args:\n            filepath (str or Path): Path to be checked whether it is a\n                directory.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` points to a directory,\n                ``False`` otherwise.\n        \"\"\"\n        return osp.isdir(filepath)\n\n    def isfile(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path is a file.\n\n        Args:\n            filepath (str or Path): Path to be checked whether it is a file.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` points to a file, ``False``\n                otherwise.\n        \"\"\"\n        return osp.isfile(filepath)\n\n    def join_path(self, filepath: Union[str, Path],\n                  *filepaths: Union[str, Path]) -> str:\n        \"\"\"Concatenate all file paths.\n\n        Join one or more filepath components intelligently. The return value\n        is the concatenation of filepath and any members of *filepaths.\n\n        Args:\n            filepath (str or Path): Path to be concatenated.\n\n        Returns:\n            str: The result of concatenation.\n        \"\"\"\n        return osp.join(filepath, *filepaths)\n\n    @contextmanager\n    def get_local_path(\n            self, filepath: Union[str, Path]) -> Iterable[Union[str, Path]]:\n        \"\"\"Only for unified API and do nothing.\"\"\"\n        yield filepath\n\n    def list_dir_or_file(self,\n                         dir_path: Union[str, Path],\n                         list_dir: bool = True,\n                         list_file: bool = True,\n                         suffix: Optional[Union[str, Tuple[str]]] = None,\n                         recursive: bool = False) -> Iterator[str]:\n        \"\"\"Scan a directory to find the interested directories or files in\n        arbitrary order.\n\n        Note:\n            :meth:`list_dir_or_file` returns the path relative to ``dir_path``.\n\n        Args:\n            dir_path (str | Path): Path of the directory.\n            list_dir (bool): List the directories. Default: True.\n            list_file (bool): List the path of files. Default: True.\n            suffix (str or tuple[str], optional):  File suffix\n                that we are interested in. Default: None.\n            recursive (bool): If set to True, recursively scan the\n                directory. Default: False.\n\n        Yields:\n            Iterable[str]: A relative path to ``dir_path``.\n        \"\"\"\n        if list_dir and suffix is not None:\n            raise TypeError('`suffix` should be None when `list_dir` is True')\n\n        if (suffix is not None) and not isinstance(suffix, (str, tuple)):\n            raise TypeError('`suffix` must be a string or tuple of strings')\n\n        root = dir_path\n\n        def _list_dir_or_file(dir_path, list_dir, list_file, suffix,\n                              recursive):\n            for entry in os.scandir(dir_path):\n                if not entry.name.startswith('.') and entry.is_file():\n                    rel_path = osp.relpath(entry.path, root)\n                    if (suffix is None\n                            or rel_path.endswith(suffix)) and list_file:\n                        yield rel_path\n                elif osp.isdir(entry.path):\n                    if list_dir:\n                        rel_dir = osp.relpath(entry.path, root)\n                        yield rel_dir\n                    if recursive:\n                        yield from _list_dir_or_file(entry.path, list_dir,\n                                                     list_file, suffix,\n                                                     recursive)\n\n        return _list_dir_or_file(dir_path, list_dir, list_file, suffix,\n                                 recursive)\n\n\nclass HTTPBackend(BaseStorageBackend):\n    \"\"\"HTTP and HTTPS storage bachend.\"\"\"\n\n    def get(self, filepath):\n        value_buf = urlopen(filepath).read()\n        return value_buf\n\n    def get_text(self, filepath, encoding='utf-8'):\n        value_buf = urlopen(filepath).read()\n        return value_buf.decode(encoding)\n\n    @contextmanager\n    def get_local_path(self, filepath: str) -> Iterable[str]:\n        \"\"\"Download a file from ``filepath``.\n\n        ``get_local_path`` is decorated by :meth:`contxtlib.contextmanager`. It\n        can be called with ``with`` statement, and when exists from the\n        ``with`` statement, the temporary path will be released.\n\n        Args:\n            filepath (str): Download a file from ``filepath``.\n\n        Examples:\n            >>> client = HTTPBackend()\n            >>> # After existing from the ``with`` clause,\n            >>> # the path will be removed\n            >>> with client.get_local_path('http://path/of/your/file') as path:\n            ...     # do something here\n        \"\"\"\n        try:\n            f = tempfile.NamedTemporaryFile(delete=False)\n            f.write(self.get(filepath))\n            f.close()\n            yield f.name\n        finally:\n            os.remove(f.name)\n\n\nclass FileClient:\n    \"\"\"A general file client to access files in different backends.\n\n    The client loads a file or text in a specified backend from its path\n    and returns it as a binary or text file. There are two ways to choose a\n    backend, the name of backend and the prefix of path. Although both of them\n    can be used to choose a storage backend, ``backend`` has a higher priority\n    that is if they are all set, the storage backend will be chosen by the\n    backend argument. If they are all `None`, the disk backend will be chosen.\n    Note that It can also register other backend accessor with a given name,\n    prefixes, and backend class. In addition, We use the singleton pattern to\n    avoid repeated object creation. If the arguments are the same, the same\n    object will be returned.\n\n    Args:\n        backend (str, optional): The storage backend type. Options are \"disk\",\n            \"ceph\", \"memcached\", \"lmdb\", \"http\" and \"petrel\". Default: None.\n        prefix (str, optional): The prefix of the registered storage backend.\n            Options are \"s3\", \"http\", \"https\". Default: None.\n\n    Examples:\n        >>> # only set backend\n        >>> file_client = FileClient(backend='petrel')\n        >>> # only set prefix\n        >>> file_client = FileClient(prefix='s3')\n        >>> # set both backend and prefix but use backend to choose client\n        >>> file_client = FileClient(backend='petrel', prefix='s3')\n        >>> # if the arguments are the same, the same object is returned\n        >>> file_client1 = FileClient(backend='petrel')\n        >>> file_client1 is file_client\n        True\n\n    Attributes:\n        client (:obj:`BaseStorageBackend`): The backend object.\n    \"\"\"\n\n    _backends = {\n        'disk': HardDiskBackend,\n        'ceph': CephBackend,\n        'memcached': MemcachedBackend,\n        'lmdb': LmdbBackend,\n        'petrel': PetrelBackend,\n        'http': HTTPBackend,\n    }\n    # This collection is used to record the overridden backends, and when a\n    # backend appears in the collection, the singleton pattern is disabled for\n    # that backend, because if the singleton pattern is used, then the object\n    # returned will be the backend before overwriting\n    _overridden_backends = set()\n    _prefix_to_backends = {\n        's3': PetrelBackend,\n        'http': HTTPBackend,\n        'https': HTTPBackend,\n    }\n    _overridden_prefixes = set()\n\n    _instances = {}\n\n    def __new__(cls, backend=None, prefix=None, **kwargs):\n        if backend is None and prefix is None:\n            backend = 'disk'\n        if backend is not None and backend not in cls._backends:\n            raise ValueError(\n                f'Backend {backend} is not supported. Currently supported ones'\n                f' are {list(cls._backends.keys())}')\n        if prefix is not None and prefix not in cls._prefix_to_backends:\n            raise ValueError(\n                f'prefix {prefix} is not supported. Currently supported ones '\n                f'are {list(cls._prefix_to_backends.keys())}')\n\n        # concatenate the arguments to a unique key for determining whether\n        # objects with the same arguments were created\n        arg_key = f'{backend}:{prefix}'\n        for key, value in kwargs.items():\n            arg_key += f':{key}:{value}'\n\n        # if a backend was overridden, it will create a new object\n        if (arg_key in cls._instances\n                and backend not in cls._overridden_backends\n                and prefix not in cls._overridden_prefixes):\n            _instance = cls._instances[arg_key]\n        else:\n            # create a new object and put it to _instance\n            _instance = super().__new__(cls)\n            if backend is not None:\n                _instance.client = cls._backends[backend](**kwargs)\n            else:\n                _instance.client = cls._prefix_to_backends[prefix](**kwargs)\n\n            cls._instances[arg_key] = _instance\n\n        return _instance\n\n    @property\n    def name(self):\n        return self.client.name\n\n    @property\n    def allow_symlink(self):\n        return self.client.allow_symlink\n\n    @staticmethod\n    def parse_uri_prefix(uri: Union[str, Path]) -> Optional[str]:\n        \"\"\"Parse the prefix of a uri.\n\n        Args:\n            uri (str | Path): Uri to be parsed that contains the file prefix.\n\n        Examples:\n            >>> FileClient.parse_uri_prefix('s3://path/of/your/file')\n            's3'\n\n        Returns:\n            str | None: Return the prefix of uri if the uri contains '://'\n                else ``None``.\n        \"\"\"\n        assert is_filepath(uri)\n        uri = str(uri)\n        if '://' not in uri:\n            return None\n        else:\n            prefix, _ = uri.split('://')\n            # In the case of PetrelBackend, the prefix may contains the cluster\n            # name like clusterName:s3\n            if ':' in prefix:\n                _, prefix = prefix.split(':')\n            return prefix\n\n    @classmethod\n    def infer_client(cls,\n                     file_client_args: Optional[dict] = None,\n                     uri: Optional[Union[str, Path]] = None) -> 'FileClient':\n        \"\"\"Infer a suitable file client based on the URI and arguments.\n\n        Args:\n            file_client_args (dict, optional): Arguments to instantiate a\n                FileClient. Default: None.\n            uri (str | Path, optional): Uri to be parsed that contains the file\n                prefix. Default: None.\n\n        Examples:\n            >>> uri = 's3://path/of/your/file'\n            >>> file_client = FileClient.infer_client(uri=uri)\n            >>> file_client_args = {'backend': 'petrel'}\n            >>> file_client = FileClient.infer_client(file_client_args)\n\n        Returns:\n            FileClient: Instantiated FileClient object.\n        \"\"\"\n        assert file_client_args is not None or uri is not None\n        if file_client_args is None:\n            file_prefix = cls.parse_uri_prefix(uri)  # type: ignore\n            return cls(prefix=file_prefix)\n        else:\n            return cls(**file_client_args)\n\n    @classmethod\n    def _register_backend(cls, name, backend, force=False, prefixes=None):\n        if not isinstance(name, str):\n            raise TypeError('the backend name should be a string, '\n                            f'but got {type(name)}')\n        if not inspect.isclass(backend):\n            raise TypeError(\n                f'backend should be a class but got {type(backend)}')\n        if not issubclass(backend, BaseStorageBackend):\n            raise TypeError(\n                f'backend {backend} is not a subclass of BaseStorageBackend')\n        if not force and name in cls._backends:\n            raise KeyError(\n                f'{name} is already registered as a storage backend, '\n                'add \"force=True\" if you want to override it')\n\n        if name in cls._backends and force:\n            cls._overridden_backends.add(name)\n        cls._backends[name] = backend\n\n        if prefixes is not None:\n            if isinstance(prefixes, str):\n                prefixes = [prefixes]\n            else:\n                assert isinstance(prefixes, (list, tuple))\n            for prefix in prefixes:\n                if prefix not in cls._prefix_to_backends:\n                    cls._prefix_to_backends[prefix] = backend\n                elif (prefix in cls._prefix_to_backends) and force:\n                    cls._overridden_prefixes.add(prefix)\n                    cls._prefix_to_backends[prefix] = backend\n                else:\n                    raise KeyError(\n                        f'{prefix} is already registered as a storage backend,'\n                        ' add \"force=True\" if you want to override it')\n\n    @classmethod\n    def register_backend(cls, name, backend=None, force=False, prefixes=None):\n        \"\"\"Register a backend to FileClient.\n\n        This method can be used as a normal class method or a decorator.\n\n        .. code-block:: python\n\n            class NewBackend(BaseStorageBackend):\n\n                def get(self, filepath):\n                    return filepath\n\n                def get_text(self, filepath):\n                    return filepath\n\n            FileClient.register_backend('new', NewBackend)\n\n        or\n\n        .. code-block:: python\n\n            @FileClient.register_backend('new')\n            class NewBackend(BaseStorageBackend):\n\n                def get(self, filepath):\n                    return filepath\n\n                def get_text(self, filepath):\n                    return filepath\n\n        Args:\n            name (str): The name of the registered backend.\n            backend (class, optional): The backend class to be registered,\n                which must be a subclass of :class:`BaseStorageBackend`.\n                When this method is used as a decorator, backend is None.\n                Defaults to None.\n            force (bool, optional): Whether to override the backend if the name\n                has already been registered. Defaults to False.\n            prefixes (str or list[str] or tuple[str], optional): The prefixes\n                of the registered storage backend. Default: None.\n                `New in version 1.3.15.`\n        \"\"\"\n        if backend is not None:\n            cls._register_backend(\n                name, backend, force=force, prefixes=prefixes)\n            return\n\n        def _register(backend_cls):\n            cls._register_backend(\n                name, backend_cls, force=force, prefixes=prefixes)\n            return backend_cls\n\n        return _register\n\n    def get(self, filepath: Union[str, Path]) -> Union[bytes, memoryview]:\n        \"\"\"Read data from a given ``filepath`` with 'rb' mode.\n\n        Note:\n            There are two types of return values for ``get``, one is ``bytes``\n            and the other is ``memoryview``. The advantage of using memoryview\n            is that you can avoid copying, and if you want to convert it to\n            ``bytes``, you can use ``.tobytes()``.\n\n        Args:\n            filepath (str or Path): Path to read data.\n\n        Returns:\n            bytes | memoryview: Expected bytes object or a memory view of the\n                bytes object.\n        \"\"\"\n        return self.client.get(filepath)\n\n    def get_text(self, filepath: Union[str, Path], encoding='utf-8') -> str:\n        \"\"\"Read data from a given ``filepath`` with 'r' mode.\n\n        Args:\n            filepath (str or Path): Path to read data.\n            encoding (str): The encoding format used to open the ``filepath``.\n                Default: 'utf-8'.\n\n        Returns:\n            str: Expected text reading from ``filepath``.\n        \"\"\"\n        return self.client.get_text(filepath, encoding)\n\n    def put(self, obj: bytes, filepath: Union[str, Path]) -> None:\n        \"\"\"Write data to a given ``filepath`` with 'wb' mode.\n\n        Note:\n            ``put`` should create a directory if the directory of ``filepath``\n            does not exist.\n\n        Args:\n            obj (bytes): Data to be written.\n            filepath (str or Path): Path to write data.\n        \"\"\"\n        self.client.put(obj, filepath)\n\n    def put_text(self, obj: str, filepath: Union[str, Path]) -> None:\n        \"\"\"Write data to a given ``filepath`` with 'w' mode.\n\n        Note:\n            ``put_text`` should create a directory if the directory of\n            ``filepath`` does not exist.\n\n        Args:\n            obj (str): Data to be written.\n            filepath (str or Path): Path to write data.\n            encoding (str, optional): The encoding format used to open the\n                `filepath`. Default: 'utf-8'.\n        \"\"\"\n        self.client.put_text(obj, filepath)\n\n    def remove(self, filepath: Union[str, Path]) -> None:\n        \"\"\"Remove a file.\n\n        Args:\n            filepath (str, Path): Path to be removed.\n        \"\"\"\n        self.client.remove(filepath)\n\n    def exists(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path exists.\n\n        Args:\n            filepath (str or Path): Path to be checked whether exists.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` exists, ``False`` otherwise.\n        \"\"\"\n        return self.client.exists(filepath)\n\n    def isdir(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path is a directory.\n\n        Args:\n            filepath (str or Path): Path to be checked whether it is a\n                directory.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` points to a directory,\n                ``False`` otherwise.\n        \"\"\"\n        return self.client.isdir(filepath)\n\n    def isfile(self, filepath: Union[str, Path]) -> bool:\n        \"\"\"Check whether a file path is a file.\n\n        Args:\n            filepath (str or Path): Path to be checked whether it is a file.\n\n        Returns:\n            bool: Return ``True`` if ``filepath`` points to a file, ``False``\n                otherwise.\n        \"\"\"\n        return self.client.isfile(filepath)\n\n    def join_path(self, filepath: Union[str, Path],\n                  *filepaths: Union[str, Path]) -> str:\n        \"\"\"Concatenate all file paths.\n\n        Join one or more filepath components intelligently. The return value\n        is the concatenation of filepath and any members of *filepaths.\n\n        Args:\n            filepath (str or Path): Path to be concatenated.\n\n        Returns:\n            str: The result of concatenation.\n        \"\"\"\n        return self.client.join_path(filepath, *filepaths)\n\n    @contextmanager\n    def get_local_path(self, filepath: Union[str, Path]) -> Iterable[str]:\n        \"\"\"Download data from ``filepath`` and write the data to local path.\n\n        ``get_local_path`` is decorated by :meth:`contxtlib.contextmanager`. It\n        can be called with ``with`` statement, and when exists from the\n        ``with`` statement, the temporary path will be released.\n\n        Note:\n            If the ``filepath`` is a local path, just return itself.\n\n        .. warning::\n            ``get_local_path`` is an experimental interface that may change in\n            the future.\n\n        Args:\n            filepath (str or Path): Path to be read data.\n\n        Examples:\n            >>> file_client = FileClient(prefix='s3')\n            >>> with file_client.get_local_path('s3://bucket/abc.jpg') as path:\n            ...     # do something here\n\n        Yields:\n            Iterable[str]: Only yield one path.\n        \"\"\"\n        with self.client.get_local_path(str(filepath)) as local_path:\n            yield local_path\n\n    def list_dir_or_file(self,\n                         dir_path: Union[str, Path],\n                         list_dir: bool = True,\n                         list_file: bool = True,\n                         suffix: Optional[Union[str, Tuple[str]]] = None,\n                         recursive: bool = False) -> Iterator[str]:\n        \"\"\"Scan a directory to find the interested directories or files in\n        arbitrary order.\n\n        Note:\n            :meth:`list_dir_or_file` returns the path relative to ``dir_path``.\n\n        Args:\n            dir_path (str | Path): Path of the directory.\n            list_dir (bool): List the directories. Default: True.\n            list_file (bool): List the path of files. Default: True.\n            suffix (str or tuple[str], optional):  File suffix\n                that we are interested in. Default: None.\n            recursive (bool): If set to True, recursively scan the\n                directory. Default: False.\n\n        Yields:\n            Iterable[str]: A relative path to ``dir_path``.\n        \"\"\"\n        yield from self.client.list_dir_or_file(dir_path, list_dir, list_file,\n                                                suffix, recursive)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/handlers/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base import BaseFileHandler\nfrom .json_handler import JsonHandler\nfrom .pickle_handler import PickleHandler"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/handlers/base.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom abc import ABCMeta, abstractmethod\n\n\nclass BaseFileHandler(metaclass=ABCMeta):\n    # `str_like` is a flag to indicate whether the type of file object is\n    # str-like object or bytes-like object. Pickle only processes bytes-like\n    # objects but json only processes str-like object. If it is str-like\n    # object, `StringIO` will be used to process the buffer.\n    str_like = True\n\n    @abstractmethod\n    def load_from_fileobj(self, file, **kwargs):\n        pass\n\n    @abstractmethod\n    def dump_to_fileobj(self, obj, file, **kwargs):\n        pass\n\n    @abstractmethod\n    def dump_to_str(self, obj, **kwargs):\n        pass\n\n    def load_from_path(self, filepath, mode='r', **kwargs):\n        with open(filepath, mode) as f:\n            return self.load_from_fileobj(f, **kwargs)\n\n    def dump_to_path(self, obj, filepath, mode='w', **kwargs):\n        with open(filepath, mode) as f:\n            self.dump_to_fileobj(obj, f, **kwargs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/handlers/json_handler.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport json\n\nimport numpy as np\n\nfrom .base import BaseFileHandler\n\n\ndef set_default(obj):\n    \"\"\"Set default json values for non-serializable values.\n\n    It helps convert ``set``, ``range`` and ``np.ndarray`` data types to list.\n    It also converts ``np.generic`` (including ``np.int32``, ``np.float32``,\n    etc.) into plain numbers of plain python built-in types.\n    \"\"\"\n    if isinstance(obj, (set, range)):\n        return list(obj)\n    elif isinstance(obj, np.ndarray):\n        return obj.tolist()\n    elif isinstance(obj, np.generic):\n        return obj.item()\n    raise TypeError(f'{type(obj)} is unsupported for json dump')\n\n\nclass JsonHandler(BaseFileHandler):\n\n    def load_from_fileobj(self, file):\n        return json.load(file)\n\n    def dump_to_fileobj(self, obj, file, **kwargs):\n        kwargs.setdefault('default', set_default)\n        json.dump(obj, file, **kwargs)\n\n    def dump_to_str(self, obj, **kwargs):\n        kwargs.setdefault('default', set_default)\n        return json.dumps(obj, **kwargs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/handlers/pickle_handler.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport pickle\n\nfrom .base import BaseFileHandler\n\n\nclass PickleHandler(BaseFileHandler):\n\n    str_like = False\n\n    def load_from_fileobj(self, file, **kwargs):\n        return pickle.load(file, **kwargs)\n\n    def load_from_path(self, filepath, **kwargs):\n        return super(PickleHandler, self).load_from_path(\n            filepath, mode='rb', **kwargs)\n\n    def dump_to_str(self, obj, **kwargs):\n        kwargs.setdefault('protocol', 2)\n        return pickle.dumps(obj, **kwargs)\n\n    def dump_to_fileobj(self, obj, file, **kwargs):\n        kwargs.setdefault('protocol', 2)\n        pickle.dump(obj, file, **kwargs)\n\n    def dump_to_path(self, obj, filepath, **kwargs):\n        super(PickleHandler, self).dump_to_path(\n            obj, filepath, mode='wb', **kwargs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/io.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom io import BytesIO, StringIO\nfrom pathlib import Path\n\nfrom ..utils.misc import is_list_of, is_str\nfrom .handlers import BaseFileHandler, JsonHandler, PickleHandler\n\nfile_handlers = {\n    'json': JsonHandler(),\n    # 'yaml': YamlHandler(),\n    # 'yml': YamlHandler(),\n    'pickle': PickleHandler(),\n    'pkl': PickleHandler()\n}\n\n\ndef load(file, file_format=None, file_client_args=None, **kwargs):\n    \"\"\"Load data from json/yaml/pickle files.\n\n    This method provides a unified api for loading data from serialized files.\n\n    Note:\n        In v1.3.16 and later, ``load`` supports loading data from serialized\n        files those can be storaged in different backends.\n\n    Args:\n        file (str or :obj:`Path` or file-like object): Filename or a file-like\n            object.\n        file_format (str, optional): If not specified, the file format will be\n            inferred from the file extension, otherwise use the specified one.\n            Currently supported formats include \"json\", \"yaml/yml\" and\n            \"pickle/pkl\".\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n\n    Examples:\n        >>> load('/path/of/your/file')  # file is storaged in disk\n        >>> load('https://path/of/your/file')  # file is storaged in Internet\n        >>> load('s3://path/of/your/file')  # file is storaged in petrel\n\n    Returns:\n        The content from the file.\n    \"\"\"\n    #TODO(JIAZI)\n    from .file_client import FileClient\n    if isinstance(file, Path):\n        file = str(file)\n    if file_format is None and is_str(file):\n        file_format = file.split('.')[-1]\n    if file_format not in file_handlers:\n        raise TypeError(f'Unsupported format: {file_format}')\n\n    handler = file_handlers[file_format]\n    if is_str(file):\n        file_client = FileClient.infer_client(file_client_args, file)\n        if handler.str_like:\n            with StringIO(file_client.get_text(file)) as f:\n                obj = handler.load_from_fileobj(f, **kwargs)\n        else:\n            with BytesIO(file_client.get(file)) as f:\n                obj = handler.load_from_fileobj(f, **kwargs)\n    elif hasattr(file, 'read'):\n        obj = handler.load_from_fileobj(file, **kwargs)\n    else:\n        raise TypeError('\"file\" must be a filepath str or a file-object')\n    return obj\n\n\ndef dump(obj, file=None, file_format=None, file_client_args=None, **kwargs):\n    \"\"\"Dump data to json/yaml/pickle strings or files.\n\n    This method provides a unified api for dumping data as strings or to files,\n    and also supports custom arguments for each file format.\n\n    Note:\n        In v1.3.16 and later, ``dump`` supports dumping data as strings or to\n        files which is saved to different backends.\n\n    Args:\n        obj (any): The python object to be dumped.\n        file (str or :obj:`Path` or file-like object, optional): If not\n            specified, then the object is dumped to a str, otherwise to a file\n            specified by the filename or file-like object.\n        file_format (str, optional): Same as :func:`load`.\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n\n    Examples:\n        >>> dump('hello world', '/path/of/your/file')  # disk\n        >>> dump('hello world', 's3://path/of/your/file')  # ceph or petrel\n\n    Returns:\n        bool: True for success, False otherwise.\n    \"\"\"\n    #TODO(JIAZI)\n    from .file_client import FileClient\n    if isinstance(file, Path):\n        file = str(file)\n    if file_format is None:\n        if is_str(file):\n            file_format = file.split('.')[-1]\n        elif file is None:\n            raise ValueError(\n                'file_format must be specified since file is None')\n    if file_format not in file_handlers:\n        raise TypeError(f'Unsupported format: {file_format}')\n\n    handler = file_handlers[file_format]\n    if file is None:\n        return handler.dump_to_str(obj, **kwargs)\n    elif is_str(file):\n        file_client = FileClient.infer_client(file_client_args, file)\n        if handler.str_like:\n            with StringIO() as f:\n                handler.dump_to_fileobj(obj, f, **kwargs)\n                file_client.put_text(f.getvalue(), file)\n        else:\n            with BytesIO() as f:\n                handler.dump_to_fileobj(obj, f, **kwargs)\n                file_client.put(f.getvalue(), file)\n    elif hasattr(file, 'write'):\n        handler.dump_to_fileobj(obj, file, **kwargs)\n    else:\n        raise TypeError('\"file\" must be a filename str or a file-object')\n\n\ndef _register_handler(handler, file_formats):\n    \"\"\"Register a handler for some file extensions.\n\n    Args:\n        handler (:obj:`BaseFileHandler`): Handler to be registered.\n        file_formats (str or list[str]): File formats to be handled by this\n            handler.\n    \"\"\"\n    if not isinstance(handler, BaseFileHandler):\n        raise TypeError(\n            f'handler must be a child of BaseFileHandler, not {type(handler)}')\n    if isinstance(file_formats, str):\n        file_formats = [file_formats]\n    if not is_list_of(file_formats, str):\n        raise TypeError('file_formats must be a str or a list of str')\n    for ext in file_formats:\n        file_handlers[ext] = handler\n\n\ndef register_handler(file_formats, **kwargs):\n\n    def wrap(cls):\n        _register_handler(cls(**kwargs), file_formats)\n        return cls\n\n    return wrap\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/fileio/parse.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n\nfrom io import StringIO\n\nfrom .file_client import FileClient\n\n\ndef list_from_file(filename,\n                   prefix='',\n                   offset=0,\n                   max_num=0,\n                   encoding='utf-8',\n                   file_client_args=None):\n    \"\"\"Load a text file and parse the content as a list of strings.\n\n    Note:\n        In v1.3.16 and later, ``list_from_file`` supports loading a text file\n        which can be storaged in different backends and parsing the content as\n        a list for strings.\n\n    Args:\n        filename (str): Filename.\n        prefix (str): The prefix to be inserted to the beginning of each item.\n        offset (int): The offset of lines.\n        max_num (int): The maximum number of lines to be read,\n            zeros and negatives mean no limitation.\n        encoding (str): Encoding used to open the file. Default utf-8.\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n\n    Examples:\n        >>> list_from_file('/path/of/your/file')  # disk\n        ['hello', 'world']\n        >>> list_from_file('s3://path/of/your/file')  # ceph or petrel\n        ['hello', 'world']\n\n    Returns:\n        list[str]: A list of strings.\n    \"\"\"\n    cnt = 0\n    item_list = []\n    file_client = FileClient.infer_client(file_client_args, filename)\n    with StringIO(file_client.get_text(filename, encoding)) as f:\n        for _ in range(offset):\n            f.readline()\n        for line in f:\n            if 0 < max_num <= cnt:\n                break\n            item_list.append(prefix + line.rstrip('\\n\\r'))\n            cnt += 1\n    return item_list\n\n\ndef dict_from_file(filename,\n                   key_type=str,\n                   encoding='utf-8',\n                   file_client_args=None):\n    \"\"\"Load a text file and parse the content as a dict.\n\n    Each line of the text file will be two or more columns split by\n    whitespaces or tabs. The first column will be parsed as dict keys, and\n    the following columns will be parsed as dict values.\n\n    Note:\n        In v1.3.16 and later, ``dict_from_file`` supports loading a text file\n        which can be storaged in different backends and parsing the content as\n        a dict.\n\n    Args:\n        filename(str): Filename.\n        key_type(type): Type of the dict keys. str is user by default and\n            type conversion will be performed if specified.\n        encoding (str): Encoding used to open the file. Default utf-8.\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n\n    Examples:\n        >>> dict_from_file('/path/of/your/file')  # disk\n        {'key1': 'value1', 'key2': 'value2'}\n        >>> dict_from_file('s3://path/of/your/file')  # ceph or petrel\n        {'key1': 'value1', 'key2': 'value2'}\n\n    Returns:\n        dict: The parsed contents.\n    \"\"\"\n    mapping = {}\n    file_client = FileClient.infer_client(file_client_args, filename)\n    with StringIO(file_client.get_text(filename, encoding)) as f:\n        for line in f:\n            items = line.rstrip('\\n').split()\n            assert len(items) >= 2\n            key = key_type(items[0])\n            val = items[1:] if len(items) > 2 else items[1]\n            mapping[key] = val\n    return mapping\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/image/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .geometric import (cutout, imcrop, imflip, imflip_, impad,\n                        impad_to_multiple, imrescale, imresize, imresize_like,\n                        imresize_to_multiple, imrotate, imshear, imtranslate,\n                        rescale_size)\nfrom .io import imfrombytes, imread, imwrite, supported_backends, use_backend\nfrom .photometric import (adjust_brightness, adjust_color, adjust_contrast,\n                          adjust_lighting, adjust_sharpness, auto_contrast,\n                          clahe, imdenormalize, imequalize, iminvert,\n                          imnormalize, imnormalize_, lut_transform, posterize,\n                          solarize)\nfrom .misc import tensor2imgs\nfrom .colorspace import (bgr2gray, bgr2hls, bgr2hsv, bgr2rgb, bgr2ycbcr,\n                         gray2bgr, gray2rgb, hls2bgr, hsv2bgr, imconvert,\n                         rgb2bgr, rgb2gray, rgb2ycbcr, ycbcr2bgr, ycbcr2rgb)\n# __all__ = [\n#     'bgr2gray', 'bgr2hls', 'bgr2hsv', 'bgr2rgb', 'gray2bgr', 'gray2rgb',\n#     'hls2bgr', 'hsv2bgr', 'imconvert', 'rgb2bgr', 'rgb2gray', 'imrescale',\n#     'imresize', 'imresize_like', 'imresize_to_multiple', 'rescale_size',\n#     'imcrop', 'imflip', 'imflip_', 'impad', 'impad_to_multiple', 'imrotate',\n#     'imfrombytes', 'imread', 'imwrite', 'supported_backends', 'use_backend',\n#     'imdenormalize', 'imnormalize', 'imnormalize_', 'iminvert', 'posterize',\n#     'solarize', 'rgb2ycbcr', 'bgr2ycbcr', 'ycbcr2rgb', 'ycbcr2bgr',\n#     'tensor2imgs', 'imshear', 'imtranslate', 'adjust_color', 'imequalize',\n#     'adjust_brightness', 'adjust_contrast', 'lut_transform', 'clahe',\n#     'adjust_sharpness', 'auto_contrast', 'cutout', 'adjust_lighting'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/image/colorspace.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport cv2\nimport numpy as np\n\n\ndef imconvert(img, src, dst):\n    \"\"\"Convert an image from the src colorspace to dst colorspace.\n\n    Args:\n        img (ndarray): The input image.\n        src (str): The source colorspace, e.g., 'rgb', 'hsv'.\n        dst (str): The destination colorspace, e.g., 'rgb', 'hsv'.\n\n    Returns:\n        ndarray: The converted image.\n    \"\"\"\n    code = getattr(cv2, f'COLOR_{src.upper()}2{dst.upper()}')\n    out_img = cv2.cvtColor(img, code)\n    return out_img\n\n\ndef bgr2gray(img, keepdim=False):\n    \"\"\"Convert a BGR image to grayscale image.\n\n    Args:\n        img (ndarray): The input image.\n        keepdim (bool): If False (by default), then return the grayscale image\n            with 2 dims, otherwise 3 dims.\n\n    Returns:\n        ndarray: The converted grayscale image.\n    \"\"\"\n    out_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)\n    if keepdim:\n        out_img = out_img[..., None]\n    return out_img\n\n\ndef rgb2gray(img, keepdim=False):\n    \"\"\"Convert a RGB image to grayscale image.\n\n    Args:\n        img (ndarray): The input image.\n        keepdim (bool): If False (by default), then return the grayscale image\n            with 2 dims, otherwise 3 dims.\n\n    Returns:\n        ndarray: The converted grayscale image.\n    \"\"\"\n    out_img = cv2.cvtColor(img, cv2.COLOR_RGB2GRAY)\n    if keepdim:\n        out_img = out_img[..., None]\n    return out_img\n\n\ndef gray2bgr(img):\n    \"\"\"Convert a grayscale image to BGR image.\n\n    Args:\n        img (ndarray): The input image.\n\n    Returns:\n        ndarray: The converted BGR image.\n    \"\"\"\n    img = img[..., None] if img.ndim == 2 else img\n    out_img = cv2.cvtColor(img, cv2.COLOR_GRAY2BGR)\n    return out_img\n\n\ndef gray2rgb(img):\n    \"\"\"Convert a grayscale image to RGB image.\n\n    Args:\n        img (ndarray): The input image.\n\n    Returns:\n        ndarray: The converted RGB image.\n    \"\"\"\n    img = img[..., None] if img.ndim == 2 else img\n    out_img = cv2.cvtColor(img, cv2.COLOR_GRAY2RGB)\n    return out_img\n\n\ndef _convert_input_type_range(img):\n    \"\"\"Convert the type and range of the input image.\n\n    It converts the input image to np.float32 type and range of [0, 1].\n    It is mainly used for pre-processing the input image in colorspace\n    conversion functions such as rgb2ycbcr and ycbcr2rgb.\n\n    Args:\n        img (ndarray): The input image. It accepts:\n            1. np.uint8 type with range [0, 255];\n            2. np.float32 type with range [0, 1].\n\n    Returns:\n        (ndarray): The converted image with type of np.float32 and range of\n            [0, 1].\n    \"\"\"\n    img_type = img.dtype\n    img = img.astype(np.float32)\n    if img_type == np.float32:\n        pass\n    elif img_type == np.uint8:\n        img /= 255.\n    else:\n        raise TypeError('The img type should be np.float32 or np.uint8, '\n                        f'but got {img_type}')\n    return img\n\n\ndef _convert_output_type_range(img, dst_type):\n    \"\"\"Convert the type and range of the image according to dst_type.\n\n    It converts the image to desired type and range. If `dst_type` is np.uint8,\n    images will be converted to np.uint8 type with range [0, 255]. If\n    `dst_type` is np.float32, it converts the image to np.float32 type with\n    range [0, 1].\n    It is mainly used for post-processing images in colorspace conversion\n    functions such as rgb2ycbcr and ycbcr2rgb.\n\n    Args:\n        img (ndarray): The image to be converted with np.float32 type and\n            range [0, 255].\n        dst_type (np.uint8 | np.float32): If dst_type is np.uint8, it\n            converts the image to np.uint8 type with range [0, 255]. If\n            dst_type is np.float32, it converts the image to np.float32 type\n            with range [0, 1].\n\n    Returns:\n        (ndarray): The converted image with desired type and range.\n    \"\"\"\n    if dst_type not in (np.uint8, np.float32):\n        raise TypeError('The dst_type should be np.float32 or np.uint8, '\n                        f'but got {dst_type}')\n    if dst_type == np.uint8:\n        img = img.round()\n    else:\n        img /= 255.\n    return img.astype(dst_type)\n\n\ndef rgb2ycbcr(img, y_only=False):\n    \"\"\"Convert a RGB image to YCbCr image.\n\n    This function produces the same results as Matlab's `rgb2ycbcr` function.\n    It implements the ITU-R BT.601 conversion for standard-definition\n    television. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#ITU-R_BT.601_conversion.\n\n    It differs from a similar function in cv2.cvtColor: `RGB <-> YCrCb`.\n    In OpenCV, it implements a JPEG conversion. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#JPEG_conversion.\n\n    Args:\n        img (ndarray): The input image. It accepts:\n            1. np.uint8 type with range [0, 255];\n            2. np.float32 type with range [0, 1].\n        y_only (bool): Whether to only return Y channel. Default: False.\n\n    Returns:\n        ndarray: The converted YCbCr image. The output image has the same type\n            and range as input image.\n    \"\"\"\n    img_type = img.dtype\n    img = _convert_input_type_range(img)\n    if y_only:\n        out_img = np.dot(img, [65.481, 128.553, 24.966]) + 16.0\n    else:\n        out_img = np.matmul(\n            img, [[65.481, -37.797, 112.0], [128.553, -74.203, -93.786],\n                  [24.966, 112.0, -18.214]]) + [16, 128, 128]\n    out_img = _convert_output_type_range(out_img, img_type)\n    return out_img\n\n\ndef bgr2ycbcr(img, y_only=False):\n    \"\"\"Convert a BGR image to YCbCr image.\n\n    The bgr version of rgb2ycbcr.\n    It implements the ITU-R BT.601 conversion for standard-definition\n    television. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#ITU-R_BT.601_conversion.\n\n    It differs from a similar function in cv2.cvtColor: `BGR <-> YCrCb`.\n    In OpenCV, it implements a JPEG conversion. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#JPEG_conversion.\n\n    Args:\n        img (ndarray): The input image. It accepts:\n            1. np.uint8 type with range [0, 255];\n            2. np.float32 type with range [0, 1].\n        y_only (bool): Whether to only return Y channel. Default: False.\n\n    Returns:\n        ndarray: The converted YCbCr image. The output image has the same type\n            and range as input image.\n    \"\"\"\n    img_type = img.dtype\n    img = _convert_input_type_range(img)\n    if y_only:\n        out_img = np.dot(img, [24.966, 128.553, 65.481]) + 16.0\n    else:\n        out_img = np.matmul(\n            img, [[24.966, 112.0, -18.214], [128.553, -74.203, -93.786],\n                  [65.481, -37.797, 112.0]]) + [16, 128, 128]\n    out_img = _convert_output_type_range(out_img, img_type)\n    return out_img\n\n\ndef ycbcr2rgb(img):\n    \"\"\"Convert a YCbCr image to RGB image.\n\n    This function produces the same results as Matlab's ycbcr2rgb function.\n    It implements the ITU-R BT.601 conversion for standard-definition\n    television. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#ITU-R_BT.601_conversion.\n\n    It differs from a similar function in cv2.cvtColor: `YCrCb <-> RGB`.\n    In OpenCV, it implements a JPEG conversion. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#JPEG_conversion.\n\n    Args:\n        img (ndarray): The input image. It accepts:\n            1. np.uint8 type with range [0, 255];\n            2. np.float32 type with range [0, 1].\n\n    Returns:\n        ndarray: The converted RGB image. The output image has the same type\n            and range as input image.\n    \"\"\"\n    img_type = img.dtype\n    img = _convert_input_type_range(img) * 255\n    out_img = np.matmul(img, [[0.00456621, 0.00456621, 0.00456621],\n                              [0, -0.00153632, 0.00791071],\n                              [0.00625893, -0.00318811, 0]]) * 255.0 + [\n                                  -222.921, 135.576, -276.836\n                              ]\n    out_img = _convert_output_type_range(out_img, img_type)\n    return out_img\n\n\ndef ycbcr2bgr(img):\n    \"\"\"Convert a YCbCr image to BGR image.\n\n    The bgr version of ycbcr2rgb.\n    It implements the ITU-R BT.601 conversion for standard-definition\n    television. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#ITU-R_BT.601_conversion.\n\n    It differs from a similar function in cv2.cvtColor: `YCrCb <-> BGR`.\n    In OpenCV, it implements a JPEG conversion. See more details in\n    https://en.wikipedia.org/wiki/YCbCr#JPEG_conversion.\n\n    Args:\n        img (ndarray): The input image. It accepts:\n            1. np.uint8 type with range [0, 255];\n            2. np.float32 type with range [0, 1].\n\n    Returns:\n        ndarray: The converted BGR image. The output image has the same type\n            and range as input image.\n    \"\"\"\n    img_type = img.dtype\n    img = _convert_input_type_range(img) * 255\n    out_img = np.matmul(img, [[0.00456621, 0.00456621, 0.00456621],\n                              [0.00791071, -0.00153632, 0],\n                              [0, -0.00318811, 0.00625893]]) * 255.0 + [\n                                  -276.836, 135.576, -222.921\n                              ]\n    out_img = _convert_output_type_range(out_img, img_type)\n    return out_img\n\n\ndef convert_color_factory(src, dst):\n\n    code = getattr(cv2, f'COLOR_{src.upper()}2{dst.upper()}')\n\n    def convert_color(img):\n        out_img = cv2.cvtColor(img, code)\n        return out_img\n\n    convert_color.__doc__ = f\"\"\"Convert a {src.upper()} image to {dst.upper()}\n        image.\n\n    Args:\n        img (ndarray or str): The input image.\n\n    Returns:\n        ndarray: The converted {dst.upper()} image.\n    \"\"\"\n\n    return convert_color\n\n\nbgr2rgb = convert_color_factory('bgr', 'rgb')\n\nrgb2bgr = convert_color_factory('rgb', 'bgr')\n\nbgr2hsv = convert_color_factory('bgr', 'hsv')\n\nhsv2bgr = convert_color_factory('hsv', 'bgr')\n\nbgr2hls = convert_color_factory('bgr', 'hls')\n\nhls2bgr = convert_color_factory('hls', 'bgr')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/image/geometric.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numbers\n\nimport cv2\nimport numpy as np\n\nfrom ..utils import to_2tuple\nfrom .io import imread_backend\n\ntry:\n    from PIL import Image\nexcept ImportError:\n    Image = None\n\n\ndef _scale_size(size, scale):\n    \"\"\"Rescale a size by a ratio.\n\n    Args:\n        size (tuple[int]): (w, h).\n        scale (float | tuple(float)): Scaling factor.\n\n    Returns:\n        tuple[int]: scaled size.\n    \"\"\"\n    if isinstance(scale, (float, int)):\n        scale = (scale, scale)\n    w, h = size\n    return int(w * float(scale[0]) + 0.5), int(h * float(scale[1]) + 0.5)\n\n\ncv2_interp_codes = {\n    'nearest': cv2.INTER_NEAREST,\n    'bilinear': cv2.INTER_LINEAR,\n    'bicubic': cv2.INTER_CUBIC,\n    'area': cv2.INTER_AREA,\n    'lanczos': cv2.INTER_LANCZOS4\n}\n\nif Image is not None:\n    pillow_interp_codes = {\n        'nearest': Image.NEAREST,\n        'bilinear': Image.BILINEAR,\n        'bicubic': Image.BICUBIC,\n        'box': Image.BOX,\n        'lanczos': Image.LANCZOS,\n        'hamming': Image.HAMMING\n    }\n\n\ndef imresize(img,\n             size,\n             return_scale=False,\n             interpolation='bilinear',\n             out=None,\n             backend=None):\n    \"\"\"Resize image to a given size.\n\n    Args:\n        img (ndarray): The input image.\n        size (tuple[int]): Target size (w, h).\n        return_scale (bool): Whether to return `w_scale` and `h_scale`.\n        interpolation (str): Interpolation method, accepted values are\n            \"nearest\", \"bilinear\", \"bicubic\", \"area\", \"lanczos\" for 'cv2'\n            backend, \"nearest\", \"bilinear\" for 'pillow' backend.\n        out (ndarray): The output destination.\n        backend (str | None): The image resize backend type. Options are `cv2`,\n            `pillow`, `None`. If backend is None, the global imread_backend\n            specified by ``mmcv.use_backend()`` will be used. Default: None.\n\n    Returns:\n        tuple | ndarray: (`resized_img`, `w_scale`, `h_scale`) or\n            `resized_img`.\n    \"\"\"\n    h, w = img.shape[:2]\n    if backend is None:\n        backend = imread_backend\n    if backend not in ['cv2', 'pillow']:\n        raise ValueError(f'backend: {backend} is not supported for resize.'\n                         f\"Supported backends are 'cv2', 'pillow'\")\n\n    if backend == 'pillow':\n        assert img.dtype == np.uint8, 'Pillow backend only support uint8 type'\n        pil_image = Image.fromarray(img)\n        pil_image = pil_image.resize(size, pillow_interp_codes[interpolation])\n        resized_img = np.array(pil_image)\n    else:\n        resized_img = cv2.resize(\n            img, size, dst=out, interpolation=cv2_interp_codes[interpolation])\n    if not return_scale:\n        return resized_img\n    else:\n        w_scale = size[0] / w\n        h_scale = size[1] / h\n        return resized_img, w_scale, h_scale\n\n\ndef imresize_to_multiple(img,\n                         divisor,\n                         size=None,\n                         scale_factor=None,\n                         keep_ratio=False,\n                         return_scale=False,\n                         interpolation='bilinear',\n                         out=None,\n                         backend=None):\n    \"\"\"Resize image according to a given size or scale factor and then rounds\n    up the the resized or rescaled image size to the nearest value that can be\n    divided by the divisor.\n\n    Args:\n        img (ndarray): The input image.\n        divisor (int | tuple): Resized image size will be a multiple of\n            divisor. If divisor is a tuple, divisor should be\n            (w_divisor, h_divisor).\n        size (None | int | tuple[int]): Target size (w, h). Default: None.\n        scale_factor (None | float | tuple[float]): Multiplier for spatial\n            size. Should match input size if it is a tuple and the 2D style is\n            (w_scale_factor, h_scale_factor). Default: None.\n        keep_ratio (bool): Whether to keep the aspect ratio when resizing the\n            image. Default: False.\n        return_scale (bool): Whether to return `w_scale` and `h_scale`.\n        interpolation (str): Interpolation method, accepted values are\n            \"nearest\", \"bilinear\", \"bicubic\", \"area\", \"lanczos\" for 'cv2'\n            backend, \"nearest\", \"bilinear\" for 'pillow' backend.\n        out (ndarray): The output destination.\n        backend (str | None): The image resize backend type. Options are `cv2`,\n            `pillow`, `None`. If backend is None, the global imread_backend\n            specified by ``mmcv.use_backend()`` will be used. Default: None.\n\n    Returns:\n        tuple | ndarray: (`resized_img`, `w_scale`, `h_scale`) or\n            `resized_img`.\n    \"\"\"\n    h, w = img.shape[:2]\n    if size is not None and scale_factor is not None:\n        raise ValueError('only one of size or scale_factor should be defined')\n    elif size is None and scale_factor is None:\n        raise ValueError('one of size or scale_factor should be defined')\n    elif size is not None:\n        size = to_2tuple(size)\n        if keep_ratio:\n            size = rescale_size((w, h), size, return_scale=False)\n    else:\n        size = _scale_size((w, h), scale_factor)\n\n    divisor = to_2tuple(divisor)\n    size = tuple([int(np.ceil(s / d)) * d for s, d in zip(size, divisor)])\n    resized_img, w_scale, h_scale = imresize(\n        img,\n        size,\n        return_scale=True,\n        interpolation=interpolation,\n        out=out,\n        backend=backend)\n    if return_scale:\n        return resized_img, w_scale, h_scale\n    else:\n        return resized_img\n\n\ndef imresize_like(img,\n                  dst_img,\n                  return_scale=False,\n                  interpolation='bilinear',\n                  backend=None):\n    \"\"\"Resize image to the same size of a given image.\n\n    Args:\n        img (ndarray): The input image.\n        dst_img (ndarray): The target image.\n        return_scale (bool): Whether to return `w_scale` and `h_scale`.\n        interpolation (str): Same as :func:`resize`.\n        backend (str | None): Same as :func:`resize`.\n\n    Returns:\n        tuple or ndarray: (`resized_img`, `w_scale`, `h_scale`) or\n            `resized_img`.\n    \"\"\"\n    h, w = dst_img.shape[:2]\n    return imresize(img, (w, h), return_scale, interpolation, backend=backend)\n\n\ndef rescale_size(old_size, scale, return_scale=False):\n    \"\"\"Calculate the new size to be rescaled to.\n\n    Args:\n        old_size (tuple[int]): The old size (w, h) of image.\n        scale (float | tuple[int]): The scaling factor or maximum size.\n            If it is a float number, then the image will be rescaled by this\n            factor, else if it is a tuple of 2 integers, then the image will\n            be rescaled as large as possible within the scale.\n        return_scale (bool): Whether to return the scaling factor besides the\n            rescaled image size.\n\n    Returns:\n        tuple[int]: The new rescaled image size.\n    \"\"\"\n    w, h = old_size\n    if isinstance(scale, (float, int)):\n        if scale <= 0:\n            raise ValueError(f'Invalid scale {scale}, must be positive.')\n        scale_factor = scale\n    elif isinstance(scale, tuple):\n        max_long_edge = max(scale)\n        max_short_edge = min(scale)\n        scale_factor = min(max_long_edge / max(h, w),\n                           max_short_edge / min(h, w))\n    else:\n        raise TypeError(\n            f'Scale must be a number or tuple of int, but got {type(scale)}')\n\n    new_size = _scale_size((w, h), scale_factor)\n\n    if return_scale:\n        return new_size, scale_factor\n    else:\n        return new_size\n\n\ndef imrescale(img,\n              scale,\n              return_scale=False,\n              interpolation='bilinear',\n              backend=None):\n    \"\"\"Resize image while keeping the aspect ratio.\n\n    Args:\n        img (ndarray): The input image.\n        scale (float | tuple[int]): The scaling factor or maximum size.\n            If it is a float number, then the image will be rescaled by this\n            factor, else if it is a tuple of 2 integers, then the image will\n            be rescaled as large as possible within the scale.\n        return_scale (bool): Whether to return the scaling factor besides the\n            rescaled image.\n        interpolation (str): Same as :func:`resize`.\n        backend (str | None): Same as :func:`resize`.\n\n    Returns:\n        ndarray: The rescaled image.\n    \"\"\"\n    h, w = img.shape[:2]\n    new_size, scale_factor = rescale_size((w, h), scale, return_scale=True)\n    rescaled_img = imresize(\n        img, new_size, interpolation=interpolation, backend=backend)\n    if return_scale:\n        return rescaled_img, scale_factor\n    else:\n        return rescaled_img\n\n\ndef imflip(img, direction='horizontal'):\n    \"\"\"Flip an image horizontally or vertically.\n\n    Args:\n        img (ndarray): Image to be flipped.\n        direction (str): The flip direction, either \"horizontal\" or\n            \"vertical\" or \"diagonal\".\n\n    Returns:\n        ndarray: The flipped image.\n    \"\"\"\n    assert direction in ['horizontal', 'vertical', 'diagonal']\n    if direction == 'horizontal':\n        return np.flip(img, axis=1)\n    elif direction == 'vertical':\n        return np.flip(img, axis=0)\n    else:\n        return np.flip(img, axis=(0, 1))\n\n\ndef imflip_(img, direction='horizontal'):\n    \"\"\"Inplace flip an image horizontally or vertically.\n\n    Args:\n        img (ndarray): Image to be flipped.\n        direction (str): The flip direction, either \"horizontal\" or\n            \"vertical\" or \"diagonal\".\n\n    Returns:\n        ndarray: The flipped image (inplace).\n    \"\"\"\n    assert direction in ['horizontal', 'vertical', 'diagonal']\n    if direction == 'horizontal':\n        return cv2.flip(img, 1, img)\n    elif direction == 'vertical':\n        return cv2.flip(img, 0, img)\n    else:\n        return cv2.flip(img, -1, img)\n\n\ndef imrotate(img,\n             angle,\n             center=None,\n             scale=1.0,\n             border_value=0,\n             interpolation='bilinear',\n             auto_bound=False):\n    \"\"\"Rotate an image.\n\n    Args:\n        img (ndarray): Image to be rotated.\n        angle (float): Rotation angle in degrees, positive values mean\n            clockwise rotation.\n        center (tuple[float], optional): Center point (w, h) of the rotation in\n            the source image. If not specified, the center of the image will be\n            used.\n        scale (float): Isotropic scale factor.\n        border_value (int): Border value.\n        interpolation (str): Same as :func:`resize`.\n        auto_bound (bool): Whether to adjust the image size to cover the whole\n            rotated image.\n\n    Returns:\n        ndarray: The rotated image.\n    \"\"\"\n    if center is not None and auto_bound:\n        raise ValueError('`auto_bound` conflicts with `center`')\n    h, w = img.shape[:2]\n    if center is None:\n        center = ((w - 1) * 0.5, (h - 1) * 0.5)\n    assert isinstance(center, tuple)\n\n    matrix = cv2.getRotationMatrix2D(center, -angle, scale)\n    if auto_bound:\n        cos = np.abs(matrix[0, 0])\n        sin = np.abs(matrix[0, 1])\n        new_w = h * sin + w * cos\n        new_h = h * cos + w * sin\n        matrix[0, 2] += (new_w - w) * 0.5\n        matrix[1, 2] += (new_h - h) * 0.5\n        w = int(np.round(new_w))\n        h = int(np.round(new_h))\n    rotated = cv2.warpAffine(\n        img,\n        matrix, (w, h),\n        flags=cv2_interp_codes[interpolation],\n        borderValue=border_value)\n    return rotated\n\n\ndef bbox_clip(bboxes, img_shape):\n    \"\"\"Clip bboxes to fit the image shape.\n\n    Args:\n        bboxes (ndarray): Shape (..., 4*k)\n        img_shape (tuple[int]): (height, width) of the image.\n\n    Returns:\n        ndarray: Clipped bboxes.\n    \"\"\"\n    assert bboxes.shape[-1] % 4 == 0\n    cmin = np.empty(bboxes.shape[-1], dtype=bboxes.dtype)\n    cmin[0::2] = img_shape[1] - 1\n    cmin[1::2] = img_shape[0] - 1\n    clipped_bboxes = np.maximum(np.minimum(bboxes, cmin), 0)\n    return clipped_bboxes\n\n\ndef bbox_scaling(bboxes, scale, clip_shape=None):\n    \"\"\"Scaling bboxes w.r.t the box center.\n\n    Args:\n        bboxes (ndarray): Shape(..., 4).\n        scale (float): Scaling factor.\n        clip_shape (tuple[int], optional): If specified, bboxes that exceed the\n            boundary will be clipped according to the given shape (h, w).\n\n    Returns:\n        ndarray: Scaled bboxes.\n    \"\"\"\n    if float(scale) == 1.0:\n        scaled_bboxes = bboxes.copy()\n    else:\n        w = bboxes[..., 2] - bboxes[..., 0] + 1\n        h = bboxes[..., 3] - bboxes[..., 1] + 1\n        dw = (w * (scale - 1)) * 0.5\n        dh = (h * (scale - 1)) * 0.5\n        scaled_bboxes = bboxes + np.stack((-dw, -dh, dw, dh), axis=-1)\n    if clip_shape is not None:\n        return bbox_clip(scaled_bboxes, clip_shape)\n    else:\n        return scaled_bboxes\n\n\ndef imcrop(img, bboxes, scale=1.0, pad_fill=None):\n    \"\"\"Crop image patches.\n\n    3 steps: scale the bboxes -> clip bboxes -> crop and pad.\n\n    Args:\n        img (ndarray): Image to be cropped.\n        bboxes (ndarray): Shape (k, 4) or (4, ), location of cropped bboxes.\n        scale (float, optional): Scale ratio of bboxes, the default value\n            1.0 means no padding.\n        pad_fill (Number | list[Number]): Value to be filled for padding.\n            Default: None, which means no padding.\n\n    Returns:\n        list[ndarray] | ndarray: The cropped image patches.\n    \"\"\"\n    chn = 1 if img.ndim == 2 else img.shape[2]\n    if pad_fill is not None:\n        if isinstance(pad_fill, (int, float)):\n            pad_fill = [pad_fill for _ in range(chn)]\n        assert len(pad_fill) == chn\n\n    _bboxes = bboxes[None, ...] if bboxes.ndim == 1 else bboxes\n    scaled_bboxes = bbox_scaling(_bboxes, scale).astype(np.int32)\n    clipped_bbox = bbox_clip(scaled_bboxes, img.shape)\n\n    patches = []\n    for i in range(clipped_bbox.shape[0]):\n        x1, y1, x2, y2 = tuple(clipped_bbox[i, :])\n        if pad_fill is None:\n            patch = img[y1:y2 + 1, x1:x2 + 1, ...]\n        else:\n            _x1, _y1, _x2, _y2 = tuple(scaled_bboxes[i, :])\n            if chn == 1:\n                patch_shape = (_y2 - _y1 + 1, _x2 - _x1 + 1)\n            else:\n                patch_shape = (_y2 - _y1 + 1, _x2 - _x1 + 1, chn)\n            patch = np.array(\n                pad_fill, dtype=img.dtype) * np.ones(\n                    patch_shape, dtype=img.dtype)\n            x_start = 0 if _x1 >= 0 else -_x1\n            y_start = 0 if _y1 >= 0 else -_y1\n            w = x2 - x1 + 1\n            h = y2 - y1 + 1\n            patch[y_start:y_start + h, x_start:x_start + w,\n                  ...] = img[y1:y1 + h, x1:x1 + w, ...]\n        patches.append(patch)\n\n    if bboxes.ndim == 1:\n        return patches[0]\n    else:\n        return patches\n\n\ndef impad(img,\n          *,\n          shape=None,\n          padding=None,\n          pad_val=0,\n          padding_mode='constant'):\n    \"\"\"Pad the given image to a certain shape or pad on all sides with\n    specified padding mode and padding value.\n\n    Args:\n        img (ndarray): Image to be padded.\n        shape (tuple[int]): Expected padding shape (h, w). Default: None.\n        padding (int or tuple[int]): Padding on each border. If a single int is\n            provided this is used to pad all borders. If tuple of length 2 is\n            provided this is the padding on left/right and top/bottom\n            respectively. If a tuple of length 4 is provided this is the\n            padding for the left, top, right and bottom borders respectively.\n            Default: None. Note that `shape` and `padding` can not be both\n            set.\n        pad_val (Number | Sequence[Number]): Values to be filled in padding\n            areas when padding_mode is 'constant'. Default: 0.\n        padding_mode (str): Type of padding. Should be: constant, edge,\n            reflect or symmetric. Default: constant.\n\n            - constant: pads with a constant value, this value is specified\n                with pad_val.\n            - edge: pads with the last value at the edge of the image.\n            - reflect: pads with reflection of image without repeating the\n                last value on the edge. For example, padding [1, 2, 3, 4]\n                with 2 elements on both sides in reflect mode will result\n                in [3, 2, 1, 2, 3, 4, 3, 2].\n            - symmetric: pads with reflection of image repeating the last\n                value on the edge. For example, padding [1, 2, 3, 4] with\n                2 elements on both sides in symmetric mode will result in\n                [2, 1, 1, 2, 3, 4, 4, 3]\n\n    Returns:\n        ndarray: The padded image.\n    \"\"\"\n\n    assert (shape is not None) ^ (padding is not None)\n    if shape is not None:\n        padding = (0, 0, shape[1] - img.shape[1], shape[0] - img.shape[0])\n\n    # check pad_val\n    if isinstance(pad_val, tuple):\n        assert len(pad_val) == img.shape[-1]\n    elif not isinstance(pad_val, numbers.Number):\n        raise TypeError('pad_val must be a int or a tuple. '\n                        f'But received {type(pad_val)}')\n\n    # check padding\n    if isinstance(padding, tuple) and len(padding) in [2, 4]:\n        if len(padding) == 2:\n            padding = (padding[0], padding[1], padding[0], padding[1])\n    elif isinstance(padding, numbers.Number):\n        padding = (padding, padding, padding, padding)\n    else:\n        raise ValueError('Padding must be a int or a 2, or 4 element tuple.'\n                         f'But received {padding}')\n\n    # check padding mode\n    assert padding_mode in ['constant', 'edge', 'reflect', 'symmetric']\n\n    border_type = {\n        'constant': cv2.BORDER_CONSTANT,\n        'edge': cv2.BORDER_REPLICATE,\n        'reflect': cv2.BORDER_REFLECT_101,\n        'symmetric': cv2.BORDER_REFLECT\n    }\n    img = cv2.copyMakeBorder(\n        img,\n        padding[1],\n        padding[3],\n        padding[0],\n        padding[2],\n        border_type[padding_mode],\n        value=pad_val)\n\n    return img\n\n\ndef impad_to_multiple(img, divisor, pad_val=0):\n    \"\"\"Pad an image to ensure each edge to be multiple to some number.\n\n    Args:\n        img (ndarray): Image to be padded.\n        divisor (int): Padded image edges will be multiple to divisor.\n        pad_val (Number | Sequence[Number]): Same as :func:`impad`.\n\n    Returns:\n        ndarray: The padded image.\n    \"\"\"\n    pad_h = int(np.ceil(img.shape[0] / divisor)) * divisor\n    pad_w = int(np.ceil(img.shape[1] / divisor)) * divisor\n    return impad(img, shape=(pad_h, pad_w), pad_val=pad_val)\n\n\ndef cutout(img, shape, pad_val=0):\n    \"\"\"Randomly cut out a rectangle from the original img.\n\n    Args:\n        img (ndarray): Image to be cutout.\n        shape (int | tuple[int]): Expected cutout shape (h, w). If given as a\n            int, the value will be used for both h and w.\n        pad_val (int | float | tuple[int | float]): Values to be filled in the\n            cut area. Defaults to 0.\n\n    Returns:\n        ndarray: The cutout image.\n    \"\"\"\n\n    channels = 1 if img.ndim == 2 else img.shape[2]\n    if isinstance(shape, int):\n        cut_h, cut_w = shape, shape\n    else:\n        assert isinstance(shape, tuple) and len(shape) == 2, \\\n            f'shape must be a int or a tuple with length 2, but got type ' \\\n            f'{type(shape)} instead.'\n        cut_h, cut_w = shape\n    if isinstance(pad_val, (int, float)):\n        pad_val = tuple([pad_val] * channels)\n    elif isinstance(pad_val, tuple):\n        assert len(pad_val) == channels, \\\n            'Expected the num of elements in tuple equals the channels' \\\n            'of input image. Found {} vs {}'.format(\n                len(pad_val), channels)\n    else:\n        raise TypeError(f'Invalid type {type(pad_val)} for `pad_val`')\n\n    img_h, img_w = img.shape[:2]\n    y0 = np.random.uniform(img_h)\n    x0 = np.random.uniform(img_w)\n\n    y1 = int(max(0, y0 - cut_h / 2.))\n    x1 = int(max(0, x0 - cut_w / 2.))\n    y2 = min(img_h, y1 + cut_h)\n    x2 = min(img_w, x1 + cut_w)\n\n    if img.ndim == 2:\n        patch_shape = (y2 - y1, x2 - x1)\n    else:\n        patch_shape = (y2 - y1, x2 - x1, channels)\n\n    img_cutout = img.copy()\n    patch = np.array(\n        pad_val, dtype=img.dtype) * np.ones(\n            patch_shape, dtype=img.dtype)\n    img_cutout[y1:y2, x1:x2, ...] = patch\n\n    return img_cutout\n\n\ndef _get_shear_matrix(magnitude, direction='horizontal'):\n    \"\"\"Generate the shear matrix for transformation.\n\n    Args:\n        magnitude (int | float): The magnitude used for shear.\n        direction (str): The flip direction, either \"horizontal\"\n            or \"vertical\".\n\n    Returns:\n        ndarray: The shear matrix with dtype float32.\n    \"\"\"\n    if direction == 'horizontal':\n        shear_matrix = np.float32([[1, magnitude, 0], [0, 1, 0]])\n    elif direction == 'vertical':\n        shear_matrix = np.float32([[1, 0, 0], [magnitude, 1, 0]])\n    return shear_matrix\n\n\ndef imshear(img,\n            magnitude,\n            direction='horizontal',\n            border_value=0,\n            interpolation='bilinear'):\n    \"\"\"Shear an image.\n\n    Args:\n        img (ndarray): Image to be sheared with format (h, w)\n            or (h, w, c).\n        magnitude (int | float): The magnitude used for shear.\n        direction (str): The flip direction, either \"horizontal\"\n            or \"vertical\".\n        border_value (int | tuple[int]): Value used in case of a\n            constant border.\n        interpolation (str): Same as :func:`resize`.\n\n    Returns:\n        ndarray: The sheared image.\n    \"\"\"\n    assert direction in ['horizontal',\n                         'vertical'], f'Invalid direction: {direction}'\n    height, width = img.shape[:2]\n    if img.ndim == 2:\n        channels = 1\n    elif img.ndim == 3:\n        channels = img.shape[-1]\n    if isinstance(border_value, int):\n        border_value = tuple([border_value] * channels)\n    elif isinstance(border_value, tuple):\n        assert len(border_value) == channels, \\\n            'Expected the num of elements in tuple equals the channels' \\\n            'of input image. Found {} vs {}'.format(\n                len(border_value), channels)\n    else:\n        raise ValueError(\n            f'Invalid type {type(border_value)} for `border_value`')\n    shear_matrix = _get_shear_matrix(magnitude, direction)\n    sheared = cv2.warpAffine(\n        img,\n        shear_matrix,\n        (width, height),\n        # Note case when the number elements in `border_value`\n        # greater than 3 (e.g. shearing masks whose channels large\n        # than 3) will raise TypeError in `cv2.warpAffine`.\n        # Here simply slice the first 3 values in `border_value`.\n        borderValue=border_value[:3],\n        flags=cv2_interp_codes[interpolation])\n    return sheared\n\n\ndef _get_translate_matrix(offset, direction='horizontal'):\n    \"\"\"Generate the translate matrix.\n\n    Args:\n        offset (int | float): The offset used for translate.\n        direction (str): The translate direction, either\n            \"horizontal\" or \"vertical\".\n\n    Returns:\n        ndarray: The translate matrix with dtype float32.\n    \"\"\"\n    if direction == 'horizontal':\n        translate_matrix = np.float32([[1, 0, offset], [0, 1, 0]])\n    elif direction == 'vertical':\n        translate_matrix = np.float32([[1, 0, 0], [0, 1, offset]])\n    return translate_matrix\n\n\ndef imtranslate(img,\n                offset,\n                direction='horizontal',\n                border_value=0,\n                interpolation='bilinear'):\n    \"\"\"Translate an image.\n\n    Args:\n        img (ndarray): Image to be translated with format\n            (h, w) or (h, w, c).\n        offset (int | float): The offset used for translate.\n        direction (str): The translate direction, either \"horizontal\"\n            or \"vertical\".\n        border_value (int | tuple[int]): Value used in case of a\n            constant border.\n        interpolation (str): Same as :func:`resize`.\n\n    Returns:\n        ndarray: The translated image.\n    \"\"\"\n    assert direction in ['horizontal',\n                         'vertical'], f'Invalid direction: {direction}'\n    height, width = img.shape[:2]\n    if img.ndim == 2:\n        channels = 1\n    elif img.ndim == 3:\n        channels = img.shape[-1]\n    if isinstance(border_value, int):\n        border_value = tuple([border_value] * channels)\n    elif isinstance(border_value, tuple):\n        assert len(border_value) == channels, \\\n            'Expected the num of elements in tuple equals the channels' \\\n            'of input image. Found {} vs {}'.format(\n                len(border_value), channels)\n    else:\n        raise ValueError(\n            f'Invalid type {type(border_value)} for `border_value`.')\n    translate_matrix = _get_translate_matrix(offset, direction)\n    translated = cv2.warpAffine(\n        img,\n        translate_matrix,\n        (width, height),\n        # Note case when the number elements in `border_value`\n        # greater than 3 (e.g. translating masks whose channels\n        # large than 3) will raise TypeError in `cv2.warpAffine`.\n        # Here simply slice the first 3 values in `border_value`.\n        borderValue=border_value[:3],\n        flags=cv2_interp_codes[interpolation])\n    return translated\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/image/io.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport io\nimport os.path as osp\nfrom pathlib import Path\n\nimport cv2\nimport numpy as np\nfrom cv2 import (IMREAD_COLOR, IMREAD_GRAYSCALE, IMREAD_IGNORE_ORIENTATION,\n                 IMREAD_UNCHANGED)\n\nfrom mmcv.utils import check_file_exist, is_str, mkdir_or_exist\n\ntry:\n    from turbojpeg import TJCS_RGB, TJPF_BGR, TJPF_GRAY, TurboJPEG\nexcept ImportError:\n    TJCS_RGB = TJPF_GRAY = TJPF_BGR = TurboJPEG = None\n\ntry:\n    from PIL import Image, ImageOps\nexcept ImportError:\n    Image = None\n\ntry:\n    import tifffile\nexcept ImportError:\n    tifffile = None\n\njpeg = None\nsupported_backends = ['cv2', 'turbojpeg', 'pillow', 'tifffile']\n\nimread_flags = {\n    'color': IMREAD_COLOR,\n    'grayscale': IMREAD_GRAYSCALE,\n    'unchanged': IMREAD_UNCHANGED,\n    'color_ignore_orientation': IMREAD_IGNORE_ORIENTATION | IMREAD_COLOR,\n    'grayscale_ignore_orientation':\n    IMREAD_IGNORE_ORIENTATION | IMREAD_GRAYSCALE\n}\n\nimread_backend = 'cv2'\n\n\ndef use_backend(backend):\n    \"\"\"Select a backend for image decoding.\n\n    Args:\n        backend (str): The image decoding backend type. Options are `cv2`,\n        `pillow`, `turbojpeg` (see https://github.com/lilohuang/PyTurboJPEG)\n        and `tifffile`. `turbojpeg` is faster but it only supports `.jpeg`\n        file format.\n    \"\"\"\n    assert backend in supported_backends\n    global imread_backend\n    imread_backend = backend\n    if imread_backend == 'turbojpeg':\n        if TurboJPEG is None:\n            raise ImportError('`PyTurboJPEG` is not installed')\n        global jpeg\n        if jpeg is None:\n            jpeg = TurboJPEG()\n    elif imread_backend == 'pillow':\n        if Image is None:\n            raise ImportError('`Pillow` is not installed')\n    elif imread_backend == 'tifffile':\n        if tifffile is None:\n            raise ImportError('`tifffile` is not installed')\n\n\ndef _jpegflag(flag='color', channel_order='bgr'):\n    channel_order = channel_order.lower()\n    if channel_order not in ['rgb', 'bgr']:\n        raise ValueError('channel order must be either \"rgb\" or \"bgr\"')\n\n    if flag == 'color':\n        if channel_order == 'bgr':\n            return TJPF_BGR\n        elif channel_order == 'rgb':\n            return TJCS_RGB\n    elif flag == 'grayscale':\n        return TJPF_GRAY\n    else:\n        raise ValueError('flag must be \"color\" or \"grayscale\"')\n\n\ndef _pillow2array(img, flag='color', channel_order='bgr'):\n    \"\"\"Convert a pillow image to numpy array.\n\n    Args:\n        img (:obj:`PIL.Image.Image`): The image loaded using PIL\n        flag (str): Flags specifying the color type of a loaded image,\n            candidates are 'color', 'grayscale' and 'unchanged'.\n            Default to 'color'.\n        channel_order (str): The channel order of the output image array,\n            candidates are 'bgr' and 'rgb'. Default to 'bgr'.\n\n    Returns:\n        np.ndarray: The converted numpy array\n    \"\"\"\n    channel_order = channel_order.lower()\n    if channel_order not in ['rgb', 'bgr']:\n        raise ValueError('channel order must be either \"rgb\" or \"bgr\"')\n\n    if flag == 'unchanged':\n        array = np.array(img)\n        if array.ndim >= 3 and array.shape[2] >= 3:  # color image\n            array[:, :, :3] = array[:, :, (2, 1, 0)]  # RGB to BGR\n    else:\n        # Handle exif orientation tag\n        if flag in ['color', 'grayscale']:\n            img = ImageOps.exif_transpose(img)\n        # If the image mode is not 'RGB', convert it to 'RGB' first.\n        if img.mode != 'RGB':\n            if img.mode != 'LA':\n                # Most formats except 'LA' can be directly converted to RGB\n                img = img.convert('RGB')\n            else:\n                # When the mode is 'LA', the default conversion will fill in\n                #  the canvas with black, which sometimes shadows black objects\n                #  in the foreground.\n                #\n                # Therefore, a random color (124, 117, 104) is used for canvas\n                img_rgba = img.convert('RGBA')\n                img = Image.new('RGB', img_rgba.size, (124, 117, 104))\n                img.paste(img_rgba, mask=img_rgba.split()[3])  # 3 is alpha\n        if flag in ['color', 'color_ignore_orientation']:\n            array = np.array(img)\n            if channel_order != 'rgb':\n                array = array[:, :, ::-1]  # RGB to BGR\n        elif flag in ['grayscale', 'grayscale_ignore_orientation']:\n            img = img.convert('L')\n            array = np.array(img)\n        else:\n            raise ValueError(\n                'flag must be \"color\", \"grayscale\", \"unchanged\", '\n                f'\"color_ignore_orientation\" or \"grayscale_ignore_orientation\"'\n                f' but got {flag}')\n    return array\n\n\ndef imread(img_or_path, flag='color', channel_order='bgr', backend=None):\n    \"\"\"Read an image.\n\n    Args:\n        img_or_path (ndarray or str or Path): Either a numpy array or str or\n            pathlib.Path. If it is a numpy array (loaded image), then\n            it will be returned as is.\n        flag (str): Flags specifying the color type of a loaded image,\n            candidates are `color`, `grayscale`, `unchanged`,\n            `color_ignore_orientation` and `grayscale_ignore_orientation`.\n            By default, `cv2` and `pillow` backend would rotate the image\n            according to its EXIF info unless called with `unchanged` or\n            `*_ignore_orientation` flags. `turbojpeg` and `tifffile` backend\n            always ignore image's EXIF info regardless of the flag.\n            The `turbojpeg` backend only supports `color` and `grayscale`.\n        channel_order (str): Order of channel, candidates are `bgr` and `rgb`.\n        backend (str | None): The image decoding backend type. Options are\n            `cv2`, `pillow`, `turbojpeg`, `tifffile`, `None`.\n            If backend is None, the global imread_backend specified by\n            ``mmcv.use_backend()`` will be used. Default: None.\n\n    Returns:\n        ndarray: Loaded image array.\n    \"\"\"\n\n    if backend is None:\n        backend = imread_backend\n    if backend not in supported_backends:\n        raise ValueError(f'backend: {backend} is not supported. Supported '\n                         \"backends are 'cv2', 'turbojpeg', 'pillow'\")\n    if isinstance(img_or_path, Path):\n        img_or_path = str(img_or_path)\n\n    if isinstance(img_or_path, np.ndarray):\n        return img_or_path\n    elif is_str(img_or_path):\n        check_file_exist(img_or_path,\n                         f'img file does not exist: {img_or_path}')\n        if backend == 'turbojpeg':\n            with open(img_or_path, 'rb') as in_file:\n                img = jpeg.decode(in_file.read(),\n                                  _jpegflag(flag, channel_order))\n                if img.shape[-1] == 1:\n                    img = img[:, :, 0]\n            return img\n        elif backend == 'pillow':\n            img = Image.open(img_or_path)\n            img = _pillow2array(img, flag, channel_order)\n            return img\n        elif backend == 'tifffile':\n            img = tifffile.imread(img_or_path)\n            return img\n        else:\n            flag = imread_flags[flag] if is_str(flag) else flag\n            img = cv2.imread(img_or_path, flag)\n            if flag == IMREAD_COLOR and channel_order == 'rgb':\n                cv2.cvtColor(img, cv2.COLOR_BGR2RGB, img)\n            return img\n    else:\n        raise TypeError('\"img\" must be a numpy array or a str or '\n                        'a pathlib.Path object')\n\n\ndef imfrombytes(content, flag='color', channel_order='bgr', backend=None):\n    \"\"\"Read an image from bytes.\n\n    Args:\n        content (bytes): Image bytes got from files or other streams.\n        flag (str): Same as :func:`imread`.\n        backend (str | None): The image decoding backend type. Options are\n            `cv2`, `pillow`, `turbojpeg`, `None`. If backend is None, the\n            global imread_backend specified by ``mmcv.use_backend()`` will be\n            used. Default: None.\n\n    Returns:\n        ndarray: Loaded image array.\n    \"\"\"\n\n    if backend is None:\n        backend = imread_backend\n    if backend not in supported_backends:\n        raise ValueError(f'backend: {backend} is not supported. Supported '\n                         \"backends are 'cv2', 'turbojpeg', 'pillow'\")\n    if backend == 'turbojpeg':\n        img = jpeg.decode(content, _jpegflag(flag, channel_order))\n        if img.shape[-1] == 1:\n            img = img[:, :, 0]\n        return img\n    elif backend == 'pillow':\n        buff = io.BytesIO(content)\n        img = Image.open(buff)\n        img = _pillow2array(img, flag, channel_order)\n        return img\n    else:\n        img_np = np.frombuffer(content, np.uint8)\n        flag = imread_flags[flag] if is_str(flag) else flag\n        img = cv2.imdecode(img_np, flag)\n        if flag == IMREAD_COLOR and channel_order == 'rgb':\n            cv2.cvtColor(img, cv2.COLOR_BGR2RGB, img)\n        return img\n\n\ndef imwrite(img, file_path, params=None, auto_mkdir=True):\n    \"\"\"Write image to file.\n\n    Args:\n        img (ndarray): Image array to be written.\n        file_path (str): Image file path.\n        params (None or list): Same as opencv :func:`imwrite` interface.\n        auto_mkdir (bool): If the parent folder of `file_path` does not exist,\n            whether to create it automatically.\n\n    Returns:\n        bool: Successful or not.\n    \"\"\"\n    if auto_mkdir:\n        dir_name = osp.abspath(osp.dirname(file_path))\n        mkdir_or_exist(dir_name)\n    return cv2.imwrite(file_path, img, params)\n\n\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/image/misc.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom mmcv.image import imdenormalize\n\ntry:\n    import torch\nexcept ImportError:\n    torch = None\n\n\ndef tensor2imgs(tensor, mean=(0, 0, 0), std=(1, 1, 1), to_rgb=True):\n    \"\"\"Convert tensor to 3-channel images.\n\n    Args:\n        tensor (torch.Tensor): Tensor that contains multiple images, shape (\n            N, C, H, W).\n        mean (tuple[float], optional): Mean of images. Defaults to (0, 0, 0).\n        std (tuple[float], optional): Standard deviation of images.\n            Defaults to (1, 1, 1).\n        to_rgb (bool, optional): Whether the tensor was converted to RGB\n            format in the first place. If so, convert it back to BGR.\n            Defaults to True.\n\n    Returns:\n        list[np.ndarray]: A list that contains multiple images.\n    \"\"\"\n\n    if torch is None:\n        raise RuntimeError('pytorch is not installed')\n    assert torch.is_tensor(tensor) and tensor.ndim == 4\n    assert len(mean) == 3\n    assert len(std) == 3\n\n    num_imgs = tensor.size(0)\n    mean = np.array(mean, dtype=np.float32)\n    std = np.array(std, dtype=np.float32)\n    imgs = []\n    for img_id in range(num_imgs):\n        img = tensor[img_id, ...].cpu().numpy().transpose(1, 2, 0)\n        img = imdenormalize(\n            img, mean, std, to_bgr=to_rgb).astype(np.uint8)\n        imgs.append(np.ascontiguousarray(img))\n    return imgs\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/image/photometric.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport cv2\nimport numpy as np\n\nfrom ..utils import is_tuple_of\nfrom .colorspace import bgr2gray, gray2bgr\n\n\ndef imnormalize(img, mean, std, to_rgb=True):\n    \"\"\"Normalize an image with mean and std.\n\n    Args:\n        img (ndarray): Image to be normalized.\n        mean (ndarray): The mean to be used for normalize.\n        std (ndarray): The std to be used for normalize.\n        to_rgb (bool): Whether to convert to rgb.\n\n    Returns:\n        ndarray: The normalized image.\n    \"\"\"\n    img = img.copy().astype(np.float32)\n    return imnormalize_(img, mean, std, to_rgb)\n\n\ndef imnormalize_(img, mean, std, to_rgb=True):\n    \"\"\"Inplace normalize an image with mean and std.\n\n    Args:\n        img (ndarray): Image to be normalized.\n        mean (ndarray): The mean to be used for normalize.\n        std (ndarray): The std to be used for normalize.\n        to_rgb (bool): Whether to convert to rgb.\n\n    Returns:\n        ndarray: The normalized image.\n    \"\"\"\n    # cv2 inplace normalization does not accept uint8\n    assert img.dtype != np.uint8\n    mean = np.float64(mean.reshape(1, -1))\n    stdinv = 1 / np.float64(std.reshape(1, -1))\n    if to_rgb:\n        cv2.cvtColor(img, cv2.COLOR_BGR2RGB, img)  # inplace\n    cv2.subtract(img, mean, img)  # inplace\n    cv2.multiply(img, stdinv, img)  # inplace\n    return img\n\n\ndef imdenormalize(img, mean, std, to_bgr=True):\n    assert img.dtype != np.uint8\n    mean = mean.reshape(1, -1).astype(np.float64)\n    std = std.reshape(1, -1).astype(np.float64)\n    img = cv2.multiply(img, std)  # make a copy\n    cv2.add(img, mean, img)  # inplace\n    if to_bgr:\n        cv2.cvtColor(img, cv2.COLOR_RGB2BGR, img)  # inplace\n    return img\n\n\ndef iminvert(img):\n    \"\"\"Invert (negate) an image.\n\n    Args:\n        img (ndarray): Image to be inverted.\n\n    Returns:\n        ndarray: The inverted image.\n    \"\"\"\n    return np.full_like(img, 255) - img\n\n\ndef solarize(img, thr=128):\n    \"\"\"Solarize an image (invert all pixel values above a threshold)\n\n    Args:\n        img (ndarray): Image to be solarized.\n        thr (int): Threshold for solarizing (0 - 255).\n\n    Returns:\n        ndarray: The solarized image.\n    \"\"\"\n    img = np.where(img < thr, img, 255 - img)\n    return img\n\n\ndef posterize(img, bits):\n    \"\"\"Posterize an image (reduce the number of bits for each color channel)\n\n    Args:\n        img (ndarray): Image to be posterized.\n        bits (int): Number of bits (1 to 8) to use for posterizing.\n\n    Returns:\n        ndarray: The posterized image.\n    \"\"\"\n    shift = 8 - bits\n    img = np.left_shift(np.right_shift(img, shift), shift)\n    return img\n\n\ndef adjust_color(img, alpha=1, beta=None, gamma=0):\n    r\"\"\"It blends the source image and its gray image:\n\n    .. math::\n        output = img * alpha + gray\\_img * beta + gamma\n\n    Args:\n        img (ndarray): The input source image.\n        alpha (int | float): Weight for the source image. Default 1.\n        beta (int | float): Weight for the converted gray image.\n            If None, it's assigned the value (1 - `alpha`).\n        gamma (int | float): Scalar added to each sum.\n            Same as :func:`cv2.addWeighted`. Default 0.\n\n    Returns:\n        ndarray: Colored image which has the same size and dtype as input.\n    \"\"\"\n    gray_img = bgr2gray(img)\n    gray_img = np.tile(gray_img[..., None], [1, 1, 3])\n    if beta is None:\n        beta = 1 - alpha\n    colored_img = cv2.addWeighted(img, alpha, gray_img, beta, gamma)\n    if not colored_img.dtype == np.uint8:\n        # Note when the dtype of `img` is not the default `np.uint8`\n        # (e.g. np.float32), the value in `colored_img` got from cv2\n        # is not guaranteed to be in range [0, 255], so here clip\n        # is needed.\n        colored_img = np.clip(colored_img, 0, 255)\n    return colored_img\n\n\ndef imequalize(img):\n    \"\"\"Equalize the image histogram.\n\n    This function applies a non-linear mapping to the input image,\n    in order to create a uniform distribution of grayscale values\n    in the output image.\n\n    Args:\n        img (ndarray): Image to be equalized.\n\n    Returns:\n        ndarray: The equalized image.\n    \"\"\"\n\n    def _scale_channel(im, c):\n        \"\"\"Scale the data in the corresponding channel.\"\"\"\n        im = im[:, :, c]\n        # Compute the histogram of the image channel.\n        histo = np.histogram(im, 256, (0, 255))[0]\n        # For computing the step, filter out the nonzeros.\n        nonzero_histo = histo[histo > 0]\n        step = (np.sum(nonzero_histo) - nonzero_histo[-1]) // 255\n        if not step:\n            lut = np.array(range(256))\n        else:\n            # Compute the cumulative sum, shifted by step // 2\n            # and then normalized by step.\n            lut = (np.cumsum(histo) + (step // 2)) // step\n            # Shift lut, prepending with 0.\n            lut = np.concatenate([[0], lut[:-1]], 0)\n            # handle potential integer overflow\n            lut[lut > 255] = 255\n        # If step is zero, return the original image.\n        # Otherwise, index from lut.\n        return np.where(np.equal(step, 0), im, lut[im])\n\n    # Scales each channel independently and then stacks\n    # the result.\n    s1 = _scale_channel(img, 0)\n    s2 = _scale_channel(img, 1)\n    s3 = _scale_channel(img, 2)\n    equalized_img = np.stack([s1, s2, s3], axis=-1)\n    return equalized_img.astype(img.dtype)\n\n\ndef adjust_brightness(img, factor=1.):\n    \"\"\"Adjust image brightness.\n\n    This function controls the brightness of an image. An\n    enhancement factor of 0.0 gives a black image.\n    A factor of 1.0 gives the original image. This function\n    blends the source image and the degenerated black image:\n\n    .. math::\n        output = img * factor + degenerated * (1 - factor)\n\n    Args:\n        img (ndarray): Image to be brightened.\n        factor (float): A value controls the enhancement.\n            Factor 1.0 returns the original image, lower\n            factors mean less color (brightness, contrast,\n            etc), and higher values more. Default 1.\n\n    Returns:\n        ndarray: The brightened image.\n    \"\"\"\n    degenerated = np.zeros_like(img)\n    # Note manually convert the dtype to np.float32, to\n    # achieve as close results as PIL.ImageEnhance.Brightness.\n    # Set beta=1-factor, and gamma=0\n    brightened_img = cv2.addWeighted(\n        img.astype(np.float32), factor, degenerated.astype(np.float32),\n        1 - factor, 0)\n    brightened_img = np.clip(brightened_img, 0, 255)\n    return brightened_img.astype(img.dtype)\n\n\ndef adjust_contrast(img, factor=1.):\n    \"\"\"Adjust image contrast.\n\n    This function controls the contrast of an image. An\n    enhancement factor of 0.0 gives a solid grey\n    image. A factor of 1.0 gives the original image. It\n    blends the source image and the degenerated mean image:\n\n    .. math::\n        output = img * factor + degenerated * (1 - factor)\n\n    Args:\n        img (ndarray): Image to be contrasted. BGR order.\n        factor (float): Same as :func:`mmcv.adjust_brightness`.\n\n    Returns:\n        ndarray: The contrasted image.\n    \"\"\"\n    gray_img = bgr2gray(img)\n    hist = np.histogram(gray_img, 256, (0, 255))[0]\n    mean = round(np.sum(gray_img) / np.sum(hist))\n    degenerated = (np.ones_like(img[..., 0]) * mean).astype(img.dtype)\n    degenerated = gray2bgr(degenerated)\n    contrasted_img = cv2.addWeighted(\n        img.astype(np.float32), factor, degenerated.astype(np.float32),\n        1 - factor, 0)\n    contrasted_img = np.clip(contrasted_img, 0, 255)\n    return contrasted_img.astype(img.dtype)\n\n\ndef auto_contrast(img, cutoff=0):\n    \"\"\"Auto adjust image contrast.\n\n    This function maximize (normalize) image contrast by first removing cutoff\n    percent of the lightest and darkest pixels from the histogram and remapping\n    the image so that the darkest pixel becomes black (0), and the lightest\n    becomes white (255).\n\n    Args:\n        img (ndarray): Image to be contrasted. BGR order.\n        cutoff (int | float | tuple): The cutoff percent of the lightest and\n            darkest pixels to be removed. If given as tuple, it shall be\n            (low, high). Otherwise, the single value will be used for both.\n            Defaults to 0.\n\n    Returns:\n        ndarray: The contrasted image.\n    \"\"\"\n\n    def _auto_contrast_channel(im, c, cutoff):\n        im = im[:, :, c]\n        # Compute the histogram of the image channel.\n        histo = np.histogram(im, 256, (0, 255))[0]\n        # Remove cut-off percent pixels from histo\n        histo_sum = np.cumsum(histo)\n        cut_low = histo_sum[-1] * cutoff[0] // 100\n        cut_high = histo_sum[-1] - histo_sum[-1] * cutoff[1] // 100\n        histo_sum = np.clip(histo_sum, cut_low, cut_high) - cut_low\n        histo = np.concatenate([[histo_sum[0]], np.diff(histo_sum)], 0)\n\n        # Compute mapping\n        low, high = np.nonzero(histo)[0][0], np.nonzero(histo)[0][-1]\n        # If all the values have been cut off, return the origin img\n        if low >= high:\n            return im\n        scale = 255.0 / (high - low)\n        offset = -low * scale\n        lut = np.array(range(256))\n        lut = lut * scale + offset\n        lut = np.clip(lut, 0, 255)\n        return lut[im]\n\n    if isinstance(cutoff, (int, float)):\n        cutoff = (cutoff, cutoff)\n    else:\n        assert isinstance(cutoff, tuple), 'cutoff must be of type int, ' \\\n            f'float or tuple, but got {type(cutoff)} instead.'\n    # Auto adjusts contrast for each channel independently and then stacks\n    # the result.\n    s1 = _auto_contrast_channel(img, 0, cutoff)\n    s2 = _auto_contrast_channel(img, 1, cutoff)\n    s3 = _auto_contrast_channel(img, 2, cutoff)\n    contrasted_img = np.stack([s1, s2, s3], axis=-1)\n    return contrasted_img.astype(img.dtype)\n\n\ndef adjust_sharpness(img, factor=1., kernel=None):\n    \"\"\"Adjust image sharpness.\n\n    This function controls the sharpness of an image. An\n    enhancement factor of 0.0 gives a blurred image. A\n    factor of 1.0 gives the original image. And a factor\n    of 2.0 gives a sharpened image. It blends the source\n    image and the degenerated mean image:\n\n    .. math::\n        output = img * factor + degenerated * (1 - factor)\n\n    Args:\n        img (ndarray): Image to be sharpened. BGR order.\n        factor (float): Same as :func:`mmcv.adjust_brightness`.\n        kernel (np.ndarray, optional): Filter kernel to be applied on the img\n            to obtain the degenerated img. Defaults to None.\n\n    Note:\n        No value sanity check is enforced on the kernel set by users. So with\n        an inappropriate kernel, the ``adjust_sharpness`` may fail to perform\n        the function its name indicates but end up performing whatever\n        transform determined by the kernel.\n\n    Returns:\n        ndarray: The sharpened image.\n    \"\"\"\n\n    if kernel is None:\n        # adopted from PIL.ImageFilter.SMOOTH\n        kernel = np.array([[1., 1., 1.], [1., 5., 1.], [1., 1., 1.]]) / 13\n    assert isinstance(kernel, np.ndarray), \\\n        f'kernel must be of type np.ndarray, but got {type(kernel)} instead.'\n    assert kernel.ndim == 2, \\\n        f'kernel must have a dimension of 2, but got {kernel.ndim} instead.'\n\n    degenerated = cv2.filter2D(img, -1, kernel)\n    sharpened_img = cv2.addWeighted(\n        img.astype(np.float32), factor, degenerated.astype(np.float32),\n        1 - factor, 0)\n    sharpened_img = np.clip(sharpened_img, 0, 255)\n    return sharpened_img.astype(img.dtype)\n\n\ndef adjust_lighting(img, eigval, eigvec, alphastd=0.1, to_rgb=True):\n    \"\"\"AlexNet-style PCA jitter.\n\n    This data augmentation is proposed in `ImageNet Classification with Deep\n    Convolutional Neural Networks\n    <https://dl.acm.org/doi/pdf/10.1145/3065386>`_.\n\n    Args:\n        img (ndarray): Image to be adjusted lighting. BGR order.\n        eigval (ndarray): the eigenvalue of the convariance matrix of pixel\n            values, respectively.\n        eigvec (ndarray): the eigenvector of the convariance matrix of pixel\n            values, respectively.\n        alphastd (float): The standard deviation for distribution of alpha.\n            Defaults to 0.1\n        to_rgb (bool): Whether to convert img to rgb.\n\n    Returns:\n        ndarray: The adjusted image.\n    \"\"\"\n    assert isinstance(eigval, np.ndarray) and isinstance(eigvec, np.ndarray), \\\n        f'eigval and eigvec should both be of type np.ndarray, got ' \\\n        f'{type(eigval)} and {type(eigvec)} instead.'\n\n    assert eigval.ndim == 1 and eigvec.ndim == 2\n    assert eigvec.shape == (3, eigval.shape[0])\n    n_eigval = eigval.shape[0]\n    assert isinstance(alphastd, float), 'alphastd should be of type float, ' \\\n        f'got {type(alphastd)} instead.'\n\n    img = img.copy().astype(np.float32)\n    if to_rgb:\n        cv2.cvtColor(img, cv2.COLOR_BGR2RGB, img)  # inplace\n\n    alpha = np.random.normal(0, alphastd, n_eigval)\n    alter = eigvec \\\n        * np.broadcast_to(alpha.reshape(1, n_eigval), (3, n_eigval)) \\\n        * np.broadcast_to(eigval.reshape(1, n_eigval), (3, n_eigval))\n    alter = np.broadcast_to(alter.sum(axis=1).reshape(1, 1, 3), img.shape)\n    img_adjusted = img + alter\n    return img_adjusted\n\n\ndef lut_transform(img, lut_table):\n    \"\"\"Transform array by look-up table.\n\n    The function lut_transform fills the output array with values from the\n    look-up table. Indices of the entries are taken from the input array.\n\n    Args:\n        img (ndarray): Image to be transformed.\n        lut_table (ndarray): look-up table of 256 elements; in case of\n            multi-channel input array, the table should either have a single\n            channel (in this case the same table is used for all channels) or\n            the same number of channels as in the input array.\n\n    Returns:\n        ndarray: The transformed image.\n    \"\"\"\n    assert isinstance(img, np.ndarray)\n    assert 0 <= np.min(img) and np.max(img) <= 255\n    assert isinstance(lut_table, np.ndarray)\n    assert lut_table.shape == (256, )\n\n    return cv2.LUT(np.array(img, dtype=np.uint8), lut_table)\n\n\ndef clahe(img, clip_limit=40.0, tile_grid_size=(8, 8)):\n    \"\"\"Use CLAHE method to process the image.\n\n    See `ZUIDERVELD,K. Contrast Limited Adaptive Histogram Equalization[J].\n    Graphics Gems, 1994:474-485.` for more information.\n\n    Args:\n        img (ndarray): Image to be processed.\n        clip_limit (float): Threshold for contrast limiting. Default: 40.0.\n        tile_grid_size (tuple[int]): Size of grid for histogram equalization.\n            Input image will be divided into equally sized rectangular tiles.\n            It defines the number of tiles in row and column. Default: (8, 8).\n\n    Returns:\n        ndarray: The processed image.\n    \"\"\"\n    assert isinstance(img, np.ndarray)\n    assert img.ndim == 2\n    assert isinstance(clip_limit, (float, int))\n    assert is_tuple_of(tile_grid_size, int)\n    assert len(tile_grid_size) == 2\n\n    clahe = cv2.createCLAHE(clip_limit, tile_grid_size)\n    return clahe.apply(np.array(img, dtype=np.uint8))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .batch_norm import get_norm\nfrom .nms import batched_nms\nfrom .shape_spec import ShapeSpec\nfrom .wrappers import cat, Conv2d\nfrom .roi_align import ROIAlign"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/aspp.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom copy import deepcopy\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom .batch_norm import get_norm\nfrom .blocks import DepthwiseSeparableConv2d\nfrom .wrappers import Conv2d\n\n\nclass ASPP(nn.Module):\n    \"\"\"\n    Atrous Spatial Pyramid Pooling (ASPP).\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        dilations,\n        *,\n        norm,\n        activation,\n        pool_kernel_size=None,\n        dropout: float = 0.0,\n        use_depthwise_separable_conv=False,\n    ):\n        \"\"\"\n        Args:\n            in_channels (int): number of input channels for ASPP.\n            out_channels (int): number of output channels.\n            dilations (list): a list of 3 dilations in ASPP.\n            norm (str or callable): normalization for all conv layers.\n                See :func:`layers.get_norm` for supported format. norm is\n                applied to all conv layers except the conv following\n                global average pooling.\n            activation (callable): activation function.\n            pool_kernel_size (tuple, list): the average pooling size (kh, kw)\n                for image pooling layer in ASPP. If set to None, it always\n                performs global average pooling. If not None, it must be\n                divisible by the shape of inputs in forward(). It is recommended\n                to use a fixed input feature size in training, and set this\n                option to match this size, so that it performs global average\n                pooling in training, and the size of the pooling window stays\n                consistent in inference.\n            dropout (float): apply dropout on the output of ASPP. It is used in\n                the official DeepLab implementation with a rate of 0.1:\n                https://github.com/tensorflow/models/blob/21b73d22f3ed05b650e85ac50849408dd36de32e/research/deeplab/model.py#L532  # noqa\n            use_depthwise_separable_conv (bool): use DepthwiseSeparableConv2d\n                for 3x3 convs in ASPP, proposed in :paper:`DeepLabV3+`.\n        \"\"\"\n        super(ASPP, self).__init__()\n        assert len(dilations) == 3, \"ASPP expects 3 dilations, got {}\".format(len(dilations))\n        self.pool_kernel_size = pool_kernel_size\n        self.dropout = dropout\n        use_bias = norm == \"\"\n        self.convs = nn.ModuleList()\n        # conv 1x1\n        self.convs.append(\n            Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=1,\n                bias=use_bias,\n                norm=get_norm(norm, out_channels),\n                activation=deepcopy(activation),\n            )\n        )\n        weight_init.c2_xavier_fill(self.convs[-1])\n        # atrous convs\n        for dilation in dilations:\n            if use_depthwise_separable_conv:\n                self.convs.append(\n                    DepthwiseSeparableConv2d(\n                        in_channels,\n                        out_channels,\n                        kernel_size=3,\n                        padding=dilation,\n                        dilation=dilation,\n                        norm1=norm,\n                        activation1=deepcopy(activation),\n                        norm2=norm,\n                        activation2=deepcopy(activation),\n                    )\n                )\n            else:\n                self.convs.append(\n                    Conv2d(\n                        in_channels,\n                        out_channels,\n                        kernel_size=3,\n                        padding=dilation,\n                        dilation=dilation,\n                        bias=use_bias,\n                        norm=get_norm(norm, out_channels),\n                        activation=deepcopy(activation),\n                    )\n                )\n                weight_init.c2_xavier_fill(self.convs[-1])\n        # image pooling\n        # We do not add BatchNorm because the spatial resolution is 1x1,\n        # the original TF implementation has BatchNorm.\n        if pool_kernel_size is None:\n            image_pooling = nn.Sequential(\n                nn.AdaptiveAvgPool2d(1),\n                Conv2d(in_channels, out_channels, 1, bias=True, activation=deepcopy(activation)),\n            )\n        else:\n            image_pooling = nn.Sequential(\n                nn.AvgPool2d(kernel_size=pool_kernel_size, stride=1),\n                Conv2d(in_channels, out_channels, 1, bias=True, activation=deepcopy(activation)),\n            )\n        weight_init.c2_xavier_fill(image_pooling[1])\n        self.convs.append(image_pooling)\n\n        self.project = Conv2d(\n            5 * out_channels,\n            out_channels,\n            kernel_size=1,\n            bias=use_bias,\n            norm=get_norm(norm, out_channels),\n            activation=deepcopy(activation),\n        )\n        weight_init.c2_xavier_fill(self.project)\n\n    def forward(self, x):\n        size = x.shape[-2:]\n        if self.pool_kernel_size is not None:\n            if size[0] % self.pool_kernel_size[0] or size[1] % self.pool_kernel_size[1]:\n                raise ValueError(\n                    \"`pool_kernel_size` must be divisible by the shape of inputs. \"\n                    \"Input size: {} `pool_kernel_size`: {}\".format(size, self.pool_kernel_size)\n                )\n        res = []\n        for conv in self.convs:\n            res.append(conv(x))\n        res[-1] = F.interpolate(res[-1], size=size, mode=\"bilinear\", align_corners=False)\n        res = torch.cat(res, dim=1)\n        res = self.project(res)\n        res = F.dropout(res, self.dropout, training=self.training) if self.dropout > 0 else res\n        return res\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/batch_norm.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nimport torch.distributed as dist\nfrom torch import nn\nfrom torch.nn import functional as F\nfrom torch.autograd.function import Function\nfrom .wrappers import BatchNorm2d\nTORCH_VERSION = tuple(int(x) for x in torch.__version__.split(\".\")[:2])\n\ndef get_world_size() -> int:\n    if not dist.is_available():\n        return 1\n    if not dist.is_initialized():\n        return 1\n    return dist.get_world_size()\n\nclass _AllReduce(Function):\n    @staticmethod\n    def forward(ctx, input: torch.Tensor) -> torch.Tensor:\n        input_list = [torch.zeros_like(input) for k in range(dist.get_world_size())]\n        # Use allgather instead of allreduce since I don't trust in-place operations ..\n        dist.all_gather(input_list, input, async_op=False)\n        inputs = torch.stack(input_list, dim=0)\n        return torch.sum(inputs, dim=0)\n\n    @staticmethod\n    def backward(ctx, grad_output: torch.Tensor) -> torch.Tensor:\n        dist.all_reduce(grad_output, async_op=False)\n        return grad_output\n\ndef differentiable_all_reduce(input: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Differentiable counterpart of `dist.all_reduce`.\n    \"\"\"\n    if (\n        not dist.is_available()\n        or not dist.is_initialized()\n        or dist.get_world_size() == 1\n    ):\n        return input\n    return _AllReduce.apply(input)\n\n\nclass FrozenBatchNorm2d(nn.Module):\n    \"\"\"\n    BatchNorm2d where the batch statistics and the affine parameters are fixed.\n\n    It contains non-trainable buffers called\n    \"weight\" and \"bias\", \"running_mean\", \"running_var\",\n    initialized to perform identity transformation.\n\n    The pre-trained backbone models from Caffe2 only contain \"weight\" and \"bias\",\n    which are computed from the original four parameters of BN.\n    The affine transform `x * weight + bias` will perform the equivalent\n    computation of `(x - running_mean) / sqrt(running_var) * weight + bias`.\n    When loading a backbone model from Caffe2, \"running_mean\" and \"running_var\"\n    will be left unchanged as identity transformation.\n\n    Other pre-trained backbone models may contain all 4 parameters.\n\n    The forward is implemented by `F.batch_norm(..., training=False)`.\n    \"\"\"\n\n    _version = 3\n\n    def __init__(self, num_features, eps=1e-5):\n        super().__init__()\n        self.num_features = num_features\n        self.eps = eps\n        self.register_buffer(\"weight\", torch.ones(num_features))\n        self.register_buffer(\"bias\", torch.zeros(num_features))\n        self.register_buffer(\"running_mean\", torch.zeros(num_features))\n        self.register_buffer(\"running_var\", torch.ones(num_features) - eps)\n        self.register_buffer(\"num_batches_tracked\", None)\n\n    def forward(self, x):\n        if x.requires_grad:\n            # When gradients are needed, F.batch_norm will use extra memory\n            # because its backward op computes gradients for weight/bias as well.\n            scale = self.weight * (self.running_var + self.eps).rsqrt()\n            bias = self.bias - self.running_mean * scale\n            scale = scale.reshape(1, -1, 1, 1)\n            bias = bias.reshape(1, -1, 1, 1)\n            out_dtype = x.dtype  # may be half\n            return x * scale.to(out_dtype) + bias.to(out_dtype)\n        else:\n            # When gradients are not needed, F.batch_norm is a single fused op\n            # and provide more optimization opportunities.\n            return F.batch_norm(\n                x,\n                self.running_mean,\n                self.running_var,\n                self.weight,\n                self.bias,\n                training=False,\n                eps=self.eps,\n            )\n\n    def _load_from_state_dict(\n        self,\n        state_dict,\n        prefix,\n        local_metadata,\n        strict,\n        missing_keys,\n        unexpected_keys,\n        error_msgs,\n    ):\n        version = local_metadata.get(\"version\", None)\n\n        if version is None or version < 2:\n            # No running_mean/var in early versions\n            # This will silent the warnings\n            if prefix + \"running_mean\" not in state_dict:\n                state_dict[prefix + \"running_mean\"] = torch.zeros_like(self.running_mean)\n            if prefix + \"running_var\" not in state_dict:\n                state_dict[prefix + \"running_var\"] = torch.ones_like(self.running_var)\n\n        super()._load_from_state_dict(\n            state_dict,\n            prefix,\n            local_metadata,\n            strict,\n            missing_keys,\n            unexpected_keys,\n            error_msgs,\n        )\n\n    def __repr__(self):\n        return \"FrozenBatchNorm2d(num_features={}, eps={})\".format(self.num_features, self.eps)\n\n    @classmethod\n    def convert_frozen_batchnorm(cls, module):\n        \"\"\"\n        Convert all BatchNorm/SyncBatchNorm in module into FrozenBatchNorm.\n\n        Args:\n            module (torch.nn.Module):\n\n        Returns:\n            If module is BatchNorm/SyncBatchNorm, returns a new module.\n            Otherwise, in-place convert module and return it.\n\n        Similar to convert_sync_batchnorm in\n        https://github.com/pytorch/pytorch/blob/master/torch/nn/modules/batchnorm.py\n        \"\"\"\n        bn_module = nn.modules.batchnorm\n        bn_module = (bn_module.BatchNorm2d, bn_module.SyncBatchNorm)\n        res = module\n        if isinstance(module, bn_module):\n            res = cls(module.num_features)\n            if module.affine:\n                res.weight.data = module.weight.data.clone().detach()\n                res.bias.data = module.bias.data.clone().detach()\n            res.running_mean.data = module.running_mean.data\n            res.running_var.data = module.running_var.data\n            res.eps = module.eps\n            res.num_batches_tracked = module.num_batches_tracked\n        else:\n            for name, child in module.named_children():\n                new_child = cls.convert_frozen_batchnorm(child)\n                if new_child is not child:\n                    res.add_module(name, new_child)\n        return res\n\n    @classmethod\n    def convert_frozenbatchnorm2d_to_batchnorm2d(cls, module: nn.Module) -> nn.Module:\n        \"\"\"\n        Convert all FrozenBatchNorm2d to BatchNorm2d\n\n        Args:\n            module (torch.nn.Module):\n\n        Returns:\n            If module is FrozenBatchNorm2d, returns a new module.\n            Otherwise, in-place convert module and return it.\n\n        This is needed for quantization:\n            https://fb.workplace.com/groups/1043663463248667/permalink/1296330057982005/\n        \"\"\"\n\n        res = module\n        if isinstance(module, FrozenBatchNorm2d):\n            res = torch.nn.BatchNorm2d(module.num_features, module.eps)\n\n            res.weight.data = module.weight.data.clone().detach()\n            res.bias.data = module.bias.data.clone().detach()\n            res.running_mean.data = module.running_mean.data.clone().detach()\n            res.running_var.data = module.running_var.data.clone().detach()\n            res.eps = module.eps\n            res.num_batches_tracked = module.num_batches_tracked\n        else:\n            for name, child in module.named_children():\n                new_child = cls.convert_frozenbatchnorm2d_to_batchnorm2d(child)\n                if new_child is not child:\n                    res.add_module(name, new_child)\n        return res\n\n\ndef get_norm(norm, out_channels):\n    \"\"\"\n    Args:\n        norm (str or callable): either one of BN, SyncBN, FrozenBN, GN;\n            or a callable that takes a channel number and returns\n            the normalization layer as a nn.Module.\n\n    Returns:\n        nn.Module or None: the normalization layer\n    \"\"\"\n    if norm is None:\n        return None\n    if isinstance(norm, str):\n        if len(norm) == 0:\n            return None\n        norm = {\n            \"BN\": BatchNorm2d,\n            # Fixed in https://github.com/pytorch/pytorch/pull/36382\n            \"SyncBN\": NaiveSyncBatchNorm if TORCH_VERSION <= (1, 5) else nn.SyncBatchNorm,\n            \"FrozenBN\": FrozenBatchNorm2d,\n            \"GN\": lambda channels: nn.GroupNorm(32, channels),\n            # for debugging:\n            \"nnSyncBN\": nn.SyncBatchNorm,\n            \"naiveSyncBN\": NaiveSyncBatchNorm,\n            # expose stats_mode N as an option to caller, required for zero-len inputs\n            \"naiveSyncBN_N\": lambda channels: NaiveSyncBatchNorm(channels, stats_mode=\"N\"),\n            \"LN\": lambda channels: LayerNorm(channels),\n        }[norm]\n    return norm(out_channels)\n\n\nclass NaiveSyncBatchNorm(BatchNorm2d):\n    \"\"\"\n    In PyTorch<=1.5, ``nn.SyncBatchNorm`` has incorrect gradient\n    when the batch size on each worker is different.\n    (e.g., when scale augmentation is used, or when it is applied to mask head).\n\n    This is a slower but correct alternative to `nn.SyncBatchNorm`.\n\n    Note:\n        There isn't a single definition of Sync BatchNorm.\n\n        When ``stats_mode==\"\"``, this module computes overall statistics by using\n        statistics of each worker with equal weight.  The result is true statistics\n        of all samples (as if they are all on one worker) only when all workers\n        have the same (N, H, W). This mode does not support inputs with zero batch size.\n\n        When ``stats_mode==\"N\"``, this module computes overall statistics by weighting\n        the statistics of each worker by their ``N``. The result is true statistics\n        of all samples (as if they are all on one worker) only when all workers\n        have the same (H, W). It is slower than ``stats_mode==\"\"``.\n\n        Even though the result of this module may not be the true statistics of all samples,\n        it may still be reasonable because it might be preferrable to assign equal weights\n        to all workers, regardless of their (H, W) dimension, instead of putting larger weight\n        on larger images. From preliminary experiments, little difference is found between such\n        a simplified implementation and an accurate computation of overall mean & variance.\n    \"\"\"\n\n    def __init__(self, *args, stats_mode=\"\", **kwargs):\n        super().__init__(*args, **kwargs)\n        assert stats_mode in [\"\", \"N\"]\n        self._stats_mode = stats_mode\n\n    def forward(self, input):\n        if get_world_size() == 1 or not self.training:\n            return super().forward(input)\n\n        B, C = input.shape[0], input.shape[1]\n\n        half_input = input.dtype == torch.float16\n        if half_input:\n            # fp16 does not have good enough numerics for the reduction here\n            input = input.float()\n        mean = torch.mean(input, dim=[0, 2, 3])\n        meansqr = torch.mean(input * input, dim=[0, 2, 3])\n\n        if self._stats_mode == \"\":\n            assert B > 0, 'SyncBatchNorm(stats_mode=\"\") does not support zero batch size.'\n            vec = torch.cat([mean, meansqr], dim=0)\n            vec = differentiable_all_reduce(vec) * (1.0 / dist.get_world_size())\n            mean, meansqr = torch.split(vec, C)\n            momentum = self.momentum\n        else:\n            if B == 0:\n                vec = torch.zeros([2 * C + 1], device=mean.device, dtype=mean.dtype)\n                vec = vec + input.sum()  # make sure there is gradient w.r.t input\n            else:\n                vec = torch.cat(\n                    [\n                        mean,\n                        meansqr,\n                        torch.ones([1], device=mean.device, dtype=mean.dtype),\n                    ],\n                    dim=0,\n                )\n            vec = differentiable_all_reduce(vec * B)\n\n            total_batch = vec[-1].detach()\n            momentum = total_batch.clamp(max=1) * self.momentum  # no update if total_batch is 0\n            mean, meansqr, _ = torch.split(vec / total_batch.clamp(min=1), C)  # avoid div-by-zero\n\n        var = meansqr - mean * mean\n        invstd = torch.rsqrt(var + self.eps)\n        scale = self.weight * invstd\n        bias = self.bias - mean * scale\n        scale = scale.reshape(1, -1, 1, 1)\n        bias = bias.reshape(1, -1, 1, 1)\n\n        self.running_mean += momentum * (mean.detach() - self.running_mean)\n        self.running_var += momentum * (var.detach() - self.running_var)\n        ret = input * scale + bias\n        if half_input:\n            ret = ret.half()\n        return ret\n\n\nclass CycleBatchNormList(nn.ModuleList):\n    \"\"\"\n    Implement domain-specific BatchNorm by cycling.\n\n    When a BatchNorm layer is used for multiple input domains or input\n    features, it might need to maintain a separate test-time statistics\n    for each domain. See Sec 5.2 in :paper:`rethinking-batchnorm`.\n\n    This module implements it by using N separate BN layers\n    and it cycles through them every time a forward() is called.\n\n    NOTE: The caller of this module MUST guarantee to always call\n    this module by multiple of N times. Otherwise its test-time statistics\n    will be incorrect.\n    \"\"\"\n\n    def __init__(self, length: int, bn_class=nn.BatchNorm2d, **kwargs):\n        \"\"\"\n        Args:\n            length: number of BatchNorm layers to cycle.\n            bn_class: the BatchNorm class to use\n            kwargs: arguments of the BatchNorm class, such as num_features.\n        \"\"\"\n        self._affine = kwargs.pop(\"affine\", True)\n        super().__init__([bn_class(**kwargs, affine=False) for k in range(length)])\n        if self._affine:\n            # shared affine, domain-specific BN\n            channels = self[0].num_features\n            self.weight = nn.Parameter(torch.ones(channels))\n            self.bias = nn.Parameter(torch.zeros(channels))\n        self._pos = 0\n\n    def forward(self, x):\n        ret = self[self._pos](x)\n        self._pos = (self._pos + 1) % len(self)\n\n        if self._affine:\n            w = self.weight.reshape(1, -1, 1, 1)\n            b = self.bias.reshape(1, -1, 1, 1)\n            return ret * w + b\n        else:\n            return ret\n\n    def extra_repr(self):\n        return f\"affine={self._affine}\"\n\n\nclass LayerNorm(nn.Module):\n    \"\"\"\n    A LayerNorm variant, popularized by Transformers, that performs point-wise mean and\n    variance normalization over the channel dimension for inputs that have shape\n    (batch_size, channels, height, width).\n    https://github.com/facebookresearch/ConvNeXt/blob/d1fa8f6fef0a165b27399986cc2bdacc92777e40/models/convnext.py#L119  # noqa B950\n    \"\"\"\n\n    def __init__(self, normalized_shape, eps=1e-6):\n        super().__init__()\n        self.weight = nn.Parameter(torch.ones(normalized_shape))\n        self.bias = nn.Parameter(torch.zeros(normalized_shape))\n        self.eps = eps\n        self.normalized_shape = (normalized_shape,)\n\n    def forward(self, x):\n        u = x.mean(1, keepdim=True)\n        s = (x - u).pow(2).mean(1, keepdim=True)\n        x = (x - u) / torch.sqrt(s + self.eps)\n        x = self.weight[:, None, None] * x + self.bias[:, None, None]\n        return x\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/blocks.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport fvcore.nn.weight_init as weight_init\nfrom torch import nn\n\nfrom .batch_norm import FrozenBatchNorm2d, get_norm\nfrom .wrappers import Conv2d\n\n\n\"\"\"\nCNN building blocks.\n\"\"\"\n\n\nclass CNNBlockBase(nn.Module):\n    \"\"\"\n    A CNN block is assumed to have input channels, output channels and a stride.\n    The input and output of `forward()` method must be NCHW tensors.\n    The method can perform arbitrary computation but must match the given\n    channels and stride specification.\n\n    Attribute:\n        in_channels (int):\n        out_channels (int):\n        stride (int):\n    \"\"\"\n\n    def __init__(self, in_channels, out_channels, stride):\n        \"\"\"\n        The `__init__` method of any subclass should also contain these arguments.\n\n        Args:\n            in_channels (int):\n            out_channels (int):\n            stride (int):\n        \"\"\"\n        super().__init__()\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.stride = stride\n\n    def freeze(self):\n        \"\"\"\n        Make this block not trainable.\n        This method sets all parameters to `requires_grad=False`,\n        and convert all BatchNorm layers to FrozenBatchNorm\n\n        Returns:\n            the block itself\n        \"\"\"\n        for p in self.parameters():\n            p.requires_grad = False\n        FrozenBatchNorm2d.convert_frozen_batchnorm(self)\n        return self\n\n\nclass DepthwiseSeparableConv2d(nn.Module):\n    \"\"\"\n    A kxk depthwise convolution + a 1x1 convolution.\n\n    In :paper:`xception`, norm & activation are applied on the second conv.\n    :paper:`mobilenet` uses norm & activation on both convs.\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size=3,\n        padding=1,\n        dilation=1,\n        *,\n        norm1=None,\n        activation1=None,\n        norm2=None,\n        activation2=None,\n    ):\n        \"\"\"\n        Args:\n            norm1, norm2 (str or callable): normalization for the two conv layers.\n            activation1, activation2 (callable(Tensor) -> Tensor): activation\n                function for the two conv layers.\n        \"\"\"\n        super().__init__()\n        self.depthwise = Conv2d(\n            in_channels,\n            in_channels,\n            kernel_size=kernel_size,\n            padding=padding,\n            dilation=dilation,\n            groups=in_channels,\n            bias=not norm1,\n            norm=get_norm(norm1, in_channels),\n            activation=activation1,\n        )\n        self.pointwise = Conv2d(\n            in_channels,\n            out_channels,\n            kernel_size=1,\n            bias=not norm2,\n            norm=get_norm(norm2, out_channels),\n            activation=activation2,\n        )\n\n        # default initialization\n        weight_init.c2_msra_fill(self.depthwise)\n        weight_init.c2_msra_fill(self.pointwise)\n\n    def forward(self, x):\n        return self.pointwise(self.depthwise(x))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/README.md",
    "content": "\n\nTo add a new Op:\n\n1. Create a new directory\n2. Implement new ops there\n3. Delcare its Python interface in `vision.cpp`.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/ROIAlignRotated/ROIAlignRotated.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\nat::Tensor ROIAlignRotated_forward_cpu(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio);\n\nat::Tensor ROIAlignRotated_backward_cpu(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio);\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor ROIAlignRotated_forward_cuda(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio);\n\nat::Tensor ROIAlignRotated_backward_cuda(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio);\n#endif\n\n// Interface for Python\ninline at::Tensor ROIAlignRotated_forward(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const double spatial_scale,\n    const int64_t pooled_height,\n    const int64_t pooled_width,\n    const int64_t sampling_ratio) {\n  if (input.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return ROIAlignRotated_forward_cuda(\n        input,\n        rois,\n        spatial_scale,\n        pooled_height,\n        pooled_width,\n        sampling_ratio);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  return ROIAlignRotated_forward_cpu(\n      input, rois, spatial_scale, pooled_height, pooled_width, sampling_ratio);\n}\n\ninline at::Tensor ROIAlignRotated_backward(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const double spatial_scale,\n    const int64_t pooled_height,\n    const int64_t pooled_width,\n    const int64_t batch_size,\n    const int64_t channels,\n    const int64_t height,\n    const int64_t width,\n    const int64_t sampling_ratio) {\n  if (grad.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return ROIAlignRotated_backward_cuda(\n        grad,\n        rois,\n        spatial_scale,\n        pooled_height,\n        pooled_width,\n        batch_size,\n        channels,\n        height,\n        width,\n        sampling_ratio);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  return ROIAlignRotated_backward_cpu(\n      grad,\n      rois,\n      spatial_scale,\n      pooled_height,\n      pooled_width,\n      batch_size,\n      channels,\n      height,\n      width,\n      sampling_ratio);\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/ROIAlignRotated/ROIAlignRotated_cpu.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/TensorUtils.h>\n#include \"ROIAlignRotated.h\"\n\n// Note: this implementation originates from the Caffe2 ROIAlignRotated Op\n// and PyTorch ROIAlign (non-rotated) Op implementations.\n// The key difference between this implementation and those ones is\n// we don't do \"legacy offset\" in this version, as there aren't many previous\n// works, if any, using the \"legacy\" ROIAlignRotated Op.\n// This would make the interface a bit cleaner.\n\nnamespace detectron2 {\n\nnamespace {\ntemplate <typename T>\nstruct PreCalc {\n  int pos1;\n  int pos2;\n  int pos3;\n  int pos4;\n  T w1;\n  T w2;\n  T w3;\n  T w4;\n};\n\ntemplate <typename T>\nvoid pre_calc_for_bilinear_interpolate(\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int iy_upper,\n    const int ix_upper,\n    T roi_start_h,\n    T roi_start_w,\n    T bin_size_h,\n    T bin_size_w,\n    int roi_bin_grid_h,\n    int roi_bin_grid_w,\n    T roi_center_h,\n    T roi_center_w,\n    T cos_theta,\n    T sin_theta,\n    std::vector<PreCalc<T>>& pre_calc) {\n  int pre_calc_index = 0;\n  for (int ph = 0; ph < pooled_height; ph++) {\n    for (int pw = 0; pw < pooled_width; pw++) {\n      for (int iy = 0; iy < iy_upper; iy++) {\n        const T yy = roi_start_h + ph * bin_size_h +\n            static_cast<T>(iy + .5f) * bin_size_h /\n                static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n        for (int ix = 0; ix < ix_upper; ix++) {\n          const T xx = roi_start_w + pw * bin_size_w +\n              static_cast<T>(ix + .5f) * bin_size_w /\n                  static_cast<T>(roi_bin_grid_w);\n\n          // Rotate by theta around the center and translate\n          // In image space, (y, x) is the order for Right Handed System,\n          // and this is essentially multiplying the point by a rotation matrix\n          // to rotate it counterclockwise through angle theta.\n          T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n          T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n          // deal with: inverse elements are out of feature map boundary\n          if (y < -1.0 || y > height || x < -1.0 || x > width) {\n            // empty\n            PreCalc<T> pc;\n            pc.pos1 = 0;\n            pc.pos2 = 0;\n            pc.pos3 = 0;\n            pc.pos4 = 0;\n            pc.w1 = 0;\n            pc.w2 = 0;\n            pc.w3 = 0;\n            pc.w4 = 0;\n            pre_calc[pre_calc_index] = pc;\n            pre_calc_index += 1;\n            continue;\n          }\n\n          if (y < 0) {\n            y = 0;\n          }\n          if (x < 0) {\n            x = 0;\n          }\n\n          int y_low = (int)y;\n          int x_low = (int)x;\n          int y_high;\n          int x_high;\n\n          if (y_low >= height - 1) {\n            y_high = y_low = height - 1;\n            y = (T)y_low;\n          } else {\n            y_high = y_low + 1;\n          }\n\n          if (x_low >= width - 1) {\n            x_high = x_low = width - 1;\n            x = (T)x_low;\n          } else {\n            x_high = x_low + 1;\n          }\n\n          T ly = y - y_low;\n          T lx = x - x_low;\n          T hy = 1. - ly, hx = 1. - lx;\n          T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n          // save weights and indices\n          PreCalc<T> pc;\n          pc.pos1 = y_low * width + x_low;\n          pc.pos2 = y_low * width + x_high;\n          pc.pos3 = y_high * width + x_low;\n          pc.pos4 = y_high * width + x_high;\n          pc.w1 = w1;\n          pc.w2 = w2;\n          pc.w3 = w3;\n          pc.w4 = w4;\n          pre_calc[pre_calc_index] = pc;\n\n          pre_calc_index += 1;\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid bilinear_interpolate_gradient(\n    const int height,\n    const int width,\n    T y,\n    T x,\n    T& w1,\n    T& w2,\n    T& w3,\n    T& w4,\n    int& x_low,\n    int& x_high,\n    int& y_low,\n    int& y_high) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n\ntemplate <class T>\ninline void add(T* address, const T& val) {\n  *address += val;\n}\n\n} // namespace\n\ntemplate <typename T>\nvoid ROIAlignRotatedForward(\n    const int nthreads,\n    const T* input,\n    const T& spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    const T* rois,\n    T* output) {\n  int n_rois = nthreads / channels / pooled_width / pooled_height;\n  // (n, c, ph, pw) is an element in the pooled output\n  // can be parallelized using omp\n  // #pragma omp parallel for num_threads(32)\n  for (int n = 0; n < n_rois; n++) {\n    int index_n = n * channels * pooled_width * pooled_height;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    AT_ASSERTM(\n        roi_width >= 0 && roi_height >= 0,\n        \"ROIs in ROIAlignRotated do not have non-negative size!\");\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // We do average (integral) pooling inside a bin\n    const T count = std::max(roi_bin_grid_h * roi_bin_grid_w, 1); // e.g. = 4\n\n    // we want to precalculate indices and weights shared by all channels,\n    // this is the key point of optimization\n    std::vector<PreCalc<T>> pre_calc(\n        roi_bin_grid_h * roi_bin_grid_w * pooled_width * pooled_height);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    pre_calc_for_bilinear_interpolate(\n        height,\n        width,\n        pooled_height,\n        pooled_width,\n        roi_bin_grid_h,\n        roi_bin_grid_w,\n        roi_start_h,\n        roi_start_w,\n        bin_size_h,\n        bin_size_w,\n        roi_bin_grid_h,\n        roi_bin_grid_w,\n        roi_center_h,\n        roi_center_w,\n        cos_theta,\n        sin_theta,\n        pre_calc);\n\n    for (int c = 0; c < channels; c++) {\n      int index_n_c = index_n + c * pooled_width * pooled_height;\n      const T* offset_input =\n          input + (roi_batch_ind * channels + c) * height * width;\n      int pre_calc_index = 0;\n\n      for (int ph = 0; ph < pooled_height; ph++) {\n        for (int pw = 0; pw < pooled_width; pw++) {\n          int index = index_n_c + ph * pooled_width + pw;\n\n          T output_val = 0.;\n          for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n            for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n              PreCalc<T> pc = pre_calc[pre_calc_index];\n              output_val += pc.w1 * offset_input[pc.pos1] +\n                  pc.w2 * offset_input[pc.pos2] +\n                  pc.w3 * offset_input[pc.pos3] + pc.w4 * offset_input[pc.pos4];\n\n              pre_calc_index += 1;\n            }\n          }\n          output_val /= count;\n\n          output[index] = output_val;\n        } // for pw\n      } // for ph\n    } // for c\n  } // for n\n}\n\ntemplate <typename T>\nvoid ROIAlignRotatedBackward(\n    const int nthreads,\n    // may not be contiguous. should index using n_stride, etc\n    const T* grad_output,\n    const T& spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    T* grad_input,\n    const T* rois,\n    const int n_stride,\n    const int c_stride,\n    const int h_stride,\n    const int w_stride) {\n  for (int index = 0; index < nthreads; index++) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    AT_ASSERTM(\n        roi_width >= 0 && roi_height >= 0,\n        \"ROIs in ROIAlignRotated do not have non-negative size!\");\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    T* offset_grad_input =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n\n    int output_offset = n * n_stride + c * c_stride;\n    const T* offset_grad_output = grad_output + output_offset;\n    const T grad_output_this_bin =\n        offset_grad_output[ph * h_stride + pw * w_stride];\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (integral) pooling inside a bin\n    const T count = roi_bin_grid_h * roi_bin_grid_w; // e.g. = 4\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n      const T yy = roi_start_h + ph * bin_size_h +\n          static_cast<T>(iy + .5f) * bin_size_h /\n              static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n            static_cast<T>(ix + .5f) * bin_size_w /\n                static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n\n        bilinear_interpolate_gradient(\n            height, width, y, x, w1, w2, w3, w4, x_low, x_high, y_low, y_high);\n\n        T g1 = grad_output_this_bin * w1 / count;\n        T g2 = grad_output_this_bin * w2 / count;\n        T g3 = grad_output_this_bin * w3 / count;\n        T g4 = grad_output_this_bin * w4 / count;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          // atomic add is not needed for now since it is single threaded\n          add(offset_grad_input + y_low * width + x_low, static_cast<T>(g1));\n          add(offset_grad_input + y_low * width + x_high, static_cast<T>(g2));\n          add(offset_grad_input + y_high * width + x_low, static_cast<T>(g3));\n          add(offset_grad_input + y_high * width + x_high, static_cast<T>(g4));\n        } // if\n      } // ix\n    } // iy\n  } // for\n} // ROIAlignRotatedBackward\n\nat::Tensor ROIAlignRotated_forward_cpu(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio) {\n  AT_ASSERTM(input.device().is_cpu(), \"input must be a CPU tensor\");\n  AT_ASSERTM(rois.device().is_cpu(), \"rois must be a CPU tensor\");\n\n  at::TensorArg input_t{input, \"input\", 1}, rois_t{rois, \"rois\", 2};\n\n  at::CheckedFrom c = \"ROIAlign_forward_cpu\";\n  at::checkAllSameType(c, {input_t, rois_t});\n\n  auto num_rois = rois.size(0);\n  auto channels = input.size(1);\n  auto height = input.size(2);\n  auto width = input.size(3);\n\n  at::Tensor output = at::zeros(\n      {num_rois, channels, pooled_height, pooled_width}, input.options());\n\n  auto output_size = num_rois * pooled_height * pooled_width * channels;\n\n  if (output.numel() == 0) {\n    return output;\n  }\n\n  auto input_ = input.contiguous(), rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        ROIAlignRotatedForward<scalar_t>(\n            output_size,\n            input_.data_ptr<scalar_t>(),\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            rois_.data_ptr<scalar_t>(),\n            output.data_ptr<scalar_t>());\n      });\n  return output;\n}\n\nat::Tensor ROIAlignRotated_backward_cpu(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio) {\n  AT_ASSERTM(grad.device().is_cpu(), \"grad must be a CPU tensor\");\n  AT_ASSERTM(rois.device().is_cpu(), \"rois must be a CPU tensor\");\n\n  at::TensorArg grad_t{grad, \"grad\", 1}, rois_t{rois, \"rois\", 2};\n\n  at::CheckedFrom c = \"ROIAlignRotated_backward_cpu\";\n  at::checkAllSameType(c, {grad_t, rois_t});\n\n  at::Tensor grad_input =\n      at::zeros({batch_size, channels, height, width}, grad.options());\n\n  // handle possibly empty gradients\n  if (grad.numel() == 0) {\n    return grad_input;\n  }\n\n  // get stride values to ensure indexing into gradients is correct.\n  int n_stride = grad.stride(0);\n  int c_stride = grad.stride(1);\n  int h_stride = grad.stride(2);\n  int w_stride = grad.stride(3);\n\n  auto rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        ROIAlignRotatedBackward<scalar_t>(\n            grad.numel(),\n            grad.data_ptr<scalar_t>(),\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            grad_input.data_ptr<scalar_t>(),\n            rois_.data_ptr<scalar_t>(),\n            n_stride,\n            c_stride,\n            h_stride,\n            w_stride);\n      });\n  return grad_input;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/ROIAlignRotated/ROIAlignRotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n\n// TODO make it in a common file\n#define CUDA_1D_KERNEL_LOOP(i, n)                            \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < n; \\\n       i += blockDim.x * gridDim.x)\n\n// Note: this implementation originates from the Caffe2 ROIAlignRotated Op\n// and PyTorch ROIAlign (non-rotated) Op implementations.\n// The key difference between this implementation and those ones is\n// we don't do \"legacy offset\" in this version, as there aren't many previous\n// works, if any, using the \"legacy\" ROIAlignRotated Op.\n// This would make the interface a bit cleaner.\n\nnamespace detectron2 {\n\nnamespace {\n\ntemplate <typename T>\n__device__ T bilinear_interpolate(\n    const T* input,\n    const int height,\n    const int width,\n    T y,\n    T x) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    return 0;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  int y_low = (int)y;\n  int x_low = (int)x;\n  int y_high;\n  int x_high;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n  // do bilinear interpolation\n  T v1 = input[y_low * width + x_low];\n  T v2 = input[y_low * width + x_high];\n  T v3 = input[y_high * width + x_low];\n  T v4 = input[y_high * width + x_high];\n  T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  return val;\n}\n\ntemplate <typename T>\n__device__ void bilinear_interpolate_gradient(\n    const int height,\n    const int width,\n    T y,\n    T x,\n    T& w1,\n    T& w2,\n    T& w3,\n    T& w4,\n    int& x_low,\n    int& x_high,\n    int& y_low,\n    int& y_high) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n\n} // namespace\n\ntemplate <typename T>\n__global__ void RoIAlignRotatedForward(\n    const int nthreads,\n    const T* input,\n    const T spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    const T* rois,\n    T* top_data) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    const T* offset_input =\n        input + (roi_batch_ind * channels + c) * height * width;\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (inte  gral) pooling inside a bin\n    const T count = max(roi_bin_grid_h * roi_bin_grid_w, 1); // e.g. = 4\n\n    T output_val = 0.;\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) // e.g., iy = 0, 1\n    {\n      const T yy = roi_start_h + ph * bin_size_h +\n          static_cast<T>(iy + .5f) * bin_size_h /\n              static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n            static_cast<T>(ix + .5f) * bin_size_w /\n                static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T val = bilinear_interpolate(offset_input, height, width, y, x);\n        output_val += val;\n      }\n    }\n    output_val /= count;\n\n    top_data[index] = output_val;\n  }\n}\n\ntemplate <typename T>\n__global__ void RoIAlignRotatedBackwardFeature(\n    const int nthreads,\n    const T* top_diff,\n    const int num_rois,\n    const T spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    T* bottom_diff,\n    const T* rois) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    T* offset_bottom_diff =\n        bottom_diff + (roi_batch_ind * channels + c) * height * width;\n\n    int top_offset = (n * channels + c) * pooled_height * pooled_width;\n    const T* offset_top_diff = top_diff + top_offset;\n    const T top_diff_this_bin = offset_top_diff[ph * pooled_width + pw];\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (integral) pooling inside a bin\n    const T count = roi_bin_grid_h * roi_bin_grid_w; // e.g. = 4\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) // e.g., iy = 0, 1\n    {\n      const T yy = roi_start_h + ph * bin_size_h +\n          static_cast<T>(iy + .5f) * bin_size_h /\n              static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n            static_cast<T>(ix + .5f) * bin_size_w /\n                static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n\n        bilinear_interpolate_gradient(\n            height, width, y, x, w1, w2, w3, w4, x_low, x_high, y_low, y_high);\n\n        T g1 = top_diff_this_bin * w1 / count;\n        T g2 = top_diff_this_bin * w2 / count;\n        T g3 = top_diff_this_bin * w3 / count;\n        T g4 = top_diff_this_bin * w4 / count;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          atomicAdd(\n              offset_bottom_diff + y_low * width + x_low, static_cast<T>(g1));\n          atomicAdd(\n              offset_bottom_diff + y_low * width + x_high, static_cast<T>(g2));\n          atomicAdd(\n              offset_bottom_diff + y_high * width + x_low, static_cast<T>(g3));\n          atomicAdd(\n              offset_bottom_diff + y_high * width + x_high, static_cast<T>(g4));\n        } // if\n      } // ix\n    } // iy\n  } // CUDA_1D_KERNEL_LOOP\n} // RoIAlignRotatedBackward\n\nat::Tensor ROIAlignRotated_forward_cuda(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio) {\n  AT_ASSERTM(input.device().is_cuda(), \"input must be a CUDA tensor\");\n  AT_ASSERTM(rois.device().is_cuda(), \"rois must be a CUDA tensor\");\n  at::TensorArg input_t{input, \"input\", 1}, rois_t{rois, \"rois\", 2};\n\n  at::CheckedFrom c = \"ROIAlignRotated_forward_cuda\";\n  at::checkAllSameGPU(c, {input_t, rois_t});\n  at::checkAllSameType(c, {input_t, rois_t});\n  at::cuda::CUDAGuard device_guard(input.device());\n\n  auto num_rois = rois.size(0);\n  auto channels = input.size(1);\n  auto height = input.size(2);\n  auto width = input.size(3);\n\n  auto output = at::empty(\n      {num_rois, channels, pooled_height, pooled_width}, input.options());\n  auto output_size = num_rois * pooled_height * pooled_width * channels;\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 grid(std::min(\n      at::cuda::ATenCeilDiv(\n          static_cast<int64_t>(output_size), static_cast<int64_t>(512)),\n      static_cast<int64_t>(4096)));\n  dim3 block(512);\n\n  if (output.numel() == 0) {\n    AT_CUDA_CHECK(cudaGetLastError());\n    return output;\n  }\n\n  auto input_ = input.contiguous(), rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES(\n      input.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        RoIAlignRotatedForward<scalar_t><<<grid, block, 0, stream>>>(\n            output_size,\n            input_.data_ptr<scalar_t>(),\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            rois_.data_ptr<scalar_t>(),\n            output.data_ptr<scalar_t>());\n      });\n  cudaDeviceSynchronize();\n  AT_CUDA_CHECK(cudaGetLastError());\n  return output;\n}\n\n// TODO remove the dependency on input and use instead its sizes -> save memory\nat::Tensor ROIAlignRotated_backward_cuda(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio) {\n  AT_ASSERTM(grad.device().is_cuda(), \"grad must be a CUDA tensor\");\n  AT_ASSERTM(rois.device().is_cuda(), \"rois must be a CUDA tensor\");\n\n  at::TensorArg grad_t{grad, \"grad\", 1}, rois_t{rois, \"rois\", 2};\n  at::CheckedFrom c = \"ROIAlign_backward_cuda\";\n  at::checkAllSameGPU(c, {grad_t, rois_t});\n  at::checkAllSameType(c, {grad_t, rois_t});\n  at::cuda::CUDAGuard device_guard(grad.device());\n\n  auto num_rois = rois.size(0);\n  auto grad_input =\n      at::zeros({batch_size, channels, height, width}, grad.options());\n\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 grid(std::min(\n      at::cuda::ATenCeilDiv(\n          static_cast<int64_t>(grad.numel()), static_cast<int64_t>(512)),\n      static_cast<int64_t>(4096)));\n  dim3 block(512);\n\n  // handle possibly empty gradients\n  if (grad.numel() == 0) {\n    AT_CUDA_CHECK(cudaGetLastError());\n    return grad_input;\n  }\n\n  auto grad_ = grad.contiguous(), rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES(\n      grad.scalar_type(), \"ROIAlignRotated_backward\", [&] {\n        RoIAlignRotatedBackwardFeature<scalar_t><<<grid, block, 0, stream>>>(\n            grad.numel(),\n            grad_.data_ptr<scalar_t>(),\n            num_rois,\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            grad_input.data_ptr<scalar_t>(),\n            rois_.data_ptr<scalar_t>());\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n  return grad_input;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/box_iou_rotated/box_iou_rotated.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\nat::Tensor box_iou_rotated_cpu(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2);\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor box_iou_rotated_cuda(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2);\n#endif\n\n// Interface for Python\n// inline is needed to prevent multiple function definitions when this header is\n// included by different cpps\ninline at::Tensor box_iou_rotated(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2) {\n  assert(boxes1.device().is_cuda() == boxes2.device().is_cuda());\n  if (boxes1.device().is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return box_iou_rotated_cuda(boxes1.contiguous(), boxes2.contiguous());\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n\n  return box_iou_rotated_cpu(boxes1.contiguous(), boxes2.contiguous());\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/box_iou_rotated/box_iou_rotated_cpu.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include \"box_iou_rotated.h\"\n#include \"box_iou_rotated_utils.h\"\n\nnamespace detectron2 {\n\ntemplate <typename T>\nvoid box_iou_rotated_cpu_kernel(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2,\n    at::Tensor& ious) {\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n\n  for (int i = 0; i < num_boxes1; i++) {\n    for (int j = 0; j < num_boxes2; j++) {\n      ious[i * num_boxes2 + j] = single_box_iou_rotated<T>(\n          boxes1[i].data_ptr<T>(), boxes2[j].data_ptr<T>());\n    }\n  }\n}\n\nat::Tensor box_iou_rotated_cpu(\n    // input must be contiguous:\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2) {\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n  at::Tensor ious =\n      at::empty({num_boxes1 * num_boxes2}, boxes1.options().dtype(at::kFloat));\n\n  box_iou_rotated_cpu_kernel<float>(boxes1, boxes2, ious);\n\n  // reshape from 1d array to 2d array\n  auto shape = std::vector<int64_t>{num_boxes1, num_boxes2};\n  return ious.reshape(shape);\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/box_iou_rotated/box_iou_rotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n#include \"box_iou_rotated_utils.h\"\n\nnamespace detectron2 {\n\n// 2D block with 32 * 16 = 512 threads per block\nconst int BLOCK_DIM_X = 32;\nconst int BLOCK_DIM_Y = 16;\n\ntemplate <typename T>\n__global__ void box_iou_rotated_cuda_kernel(\n    const int n_boxes1,\n    const int n_boxes2,\n    const T* dev_boxes1,\n    const T* dev_boxes2,\n    T* dev_ious) {\n  const int row_start = blockIdx.x * blockDim.x;\n  const int col_start = blockIdx.y * blockDim.y;\n\n  const int row_size = min(n_boxes1 - row_start, blockDim.x);\n  const int col_size = min(n_boxes2 - col_start, blockDim.y);\n\n  __shared__ float block_boxes1[BLOCK_DIM_X * 5];\n  __shared__ float block_boxes2[BLOCK_DIM_Y * 5];\n\n  // It's safe to copy using threadIdx.x since BLOCK_DIM_X >= BLOCK_DIM_Y\n  if (threadIdx.x < row_size && threadIdx.y == 0) {\n    block_boxes1[threadIdx.x * 5 + 0] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 0];\n    block_boxes1[threadIdx.x * 5 + 1] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 1];\n    block_boxes1[threadIdx.x * 5 + 2] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 2];\n    block_boxes1[threadIdx.x * 5 + 3] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 3];\n    block_boxes1[threadIdx.x * 5 + 4] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 4];\n  }\n\n  if (threadIdx.x < col_size && threadIdx.y == 0) {\n    block_boxes2[threadIdx.x * 5 + 0] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 0];\n    block_boxes2[threadIdx.x * 5 + 1] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 1];\n    block_boxes2[threadIdx.x * 5 + 2] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 2];\n    block_boxes2[threadIdx.x * 5 + 3] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 3];\n    block_boxes2[threadIdx.x * 5 + 4] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size && threadIdx.y < col_size) {\n    int offset = (row_start + threadIdx.x) * n_boxes2 + col_start + threadIdx.y;\n    dev_ious[offset] = single_box_iou_rotated<T>(\n        block_boxes1 + threadIdx.x * 5, block_boxes2 + threadIdx.y * 5);\n  }\n}\n\nat::Tensor box_iou_rotated_cuda(\n    // input must be contiguous\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2) {\n  using scalar_t = float;\n  AT_ASSERTM(\n      boxes1.scalar_type() == at::kFloat, \"boxes1 must be a float tensor\");\n  AT_ASSERTM(\n      boxes2.scalar_type() == at::kFloat, \"boxes2 must be a float tensor\");\n  AT_ASSERTM(boxes1.is_cuda(), \"boxes1 must be a CUDA tensor\");\n  AT_ASSERTM(boxes2.is_cuda(), \"boxes2 must be a CUDA tensor\");\n  at::cuda::CUDAGuard device_guard(boxes1.device());\n\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n\n  at::Tensor ious =\n      at::empty({num_boxes1 * num_boxes2}, boxes1.options().dtype(at::kFloat));\n\n  bool transpose = false;\n  if (num_boxes1 > 0 && num_boxes2 > 0) {\n    scalar_t *data1 = boxes1.data_ptr<scalar_t>(),\n             *data2 = boxes2.data_ptr<scalar_t>();\n\n    if (num_boxes2 > 65535 * BLOCK_DIM_Y) {\n      AT_ASSERTM(\n          num_boxes1 <= 65535 * BLOCK_DIM_Y,\n          \"Too many boxes for box_iou_rotated_cuda!\");\n      // x dim is allowed to be large, but y dim cannot,\n      // so we transpose the two to avoid \"invalid configuration argument\"\n      // error. We assume one of them is small. Otherwise the result is hard to\n      // fit in memory anyway.\n      std::swap(num_boxes1, num_boxes2);\n      std::swap(data1, data2);\n      transpose = true;\n    }\n\n    const int blocks_x =\n        at::cuda::ATenCeilDiv(static_cast<int>(num_boxes1), BLOCK_DIM_X);\n    const int blocks_y =\n        at::cuda::ATenCeilDiv(static_cast<int>(num_boxes2), BLOCK_DIM_Y);\n\n    dim3 blocks(blocks_x, blocks_y);\n    dim3 threads(BLOCK_DIM_X, BLOCK_DIM_Y);\n    cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n    box_iou_rotated_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n        num_boxes1,\n        num_boxes2,\n        data1,\n        data2,\n        (scalar_t*)ious.data_ptr<scalar_t>());\n\n    AT_CUDA_CHECK(cudaGetLastError());\n  }\n\n  // reshape from 1d array to 2d array\n  auto shape = std::vector<int64_t>{num_boxes1, num_boxes2};\n  if (transpose) {\n    return ious.view(shape).t();\n  } else {\n    return ious.view(shape);\n  }\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/box_iou_rotated/box_iou_rotated_utils.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n\n#include <cassert>\n#include <cmath>\n\n#if defined(__CUDACC__) || __HCC__ == 1 || __HIP__ == 1\n// Designates functions callable from the host (CPU) and the device (GPU)\n#define HOST_DEVICE __host__ __device__\n#define HOST_DEVICE_INLINE HOST_DEVICE __forceinline__\n#else\n#include <algorithm>\n#define HOST_DEVICE\n#define HOST_DEVICE_INLINE HOST_DEVICE inline\n#endif\n\nnamespace detectron2 {\n\nnamespace {\n\ntemplate <typename T>\nstruct RotatedBox {\n  T x_ctr, y_ctr, w, h, a;\n};\n\ntemplate <typename T>\nstruct Point {\n  T x, y;\n  HOST_DEVICE_INLINE Point(const T& px = 0, const T& py = 0) : x(px), y(py) {}\n  HOST_DEVICE_INLINE Point operator+(const Point& p) const {\n    return Point(x + p.x, y + p.y);\n  }\n  HOST_DEVICE_INLINE Point& operator+=(const Point& p) {\n    x += p.x;\n    y += p.y;\n    return *this;\n  }\n  HOST_DEVICE_INLINE Point operator-(const Point& p) const {\n    return Point(x - p.x, y - p.y);\n  }\n  HOST_DEVICE_INLINE Point operator*(const T coeff) const {\n    return Point(x * coeff, y * coeff);\n  }\n};\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T dot_2d(const Point<T>& A, const Point<T>& B) {\n  return A.x * B.x + A.y * B.y;\n}\n\n// R: result type. can be different from input type\ntemplate <typename T, typename R = T>\nHOST_DEVICE_INLINE R cross_2d(const Point<T>& A, const Point<T>& B) {\n  return static_cast<R>(A.x) * static_cast<R>(B.y) -\n      static_cast<R>(B.x) * static_cast<R>(A.y);\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE void get_rotated_vertices(\n    const RotatedBox<T>& box,\n    Point<T> (&pts)[4]) {\n  // M_PI / 180. == 0.01745329251\n  double theta = box.a * 0.01745329251;\n  T cosTheta2 = (T)cos(theta) * 0.5f;\n  T sinTheta2 = (T)sin(theta) * 0.5f;\n\n  // y: top --> down; x: left --> right\n  pts[0].x = box.x_ctr + sinTheta2 * box.h + cosTheta2 * box.w;\n  pts[0].y = box.y_ctr + cosTheta2 * box.h - sinTheta2 * box.w;\n  pts[1].x = box.x_ctr - sinTheta2 * box.h + cosTheta2 * box.w;\n  pts[1].y = box.y_ctr - cosTheta2 * box.h - sinTheta2 * box.w;\n  pts[2].x = 2 * box.x_ctr - pts[0].x;\n  pts[2].y = 2 * box.y_ctr - pts[0].y;\n  pts[3].x = 2 * box.x_ctr - pts[1].x;\n  pts[3].y = 2 * box.y_ctr - pts[1].y;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE int get_intersection_points(\n    const Point<T> (&pts1)[4],\n    const Point<T> (&pts2)[4],\n    Point<T> (&intersections)[24]) {\n  // Line vector\n  // A line from p1 to p2 is: p1 + (p2-p1)*t, t=[0,1]\n  Point<T> vec1[4], vec2[4];\n  for (int i = 0; i < 4; i++) {\n    vec1[i] = pts1[(i + 1) % 4] - pts1[i];\n    vec2[i] = pts2[(i + 1) % 4] - pts2[i];\n  }\n\n  // When computing the intersection area, it doesn't hurt if we have\n  // more (duplicated/approximate) intersections/vertices than needed,\n  // while it can cause drastic difference if we miss an intersection/vertex.\n  // Therefore, we add an epsilon to relax the comparisons between\n  // the float point numbers that decide the intersection points.\n  double EPS = 1e-5;\n\n  // Line test - test all line combos for intersection\n  int num = 0; // number of intersections\n  for (int i = 0; i < 4; i++) {\n    for (int j = 0; j < 4; j++) {\n      // Solve for 2x2 Ax=b\n      T det = cross_2d<T>(vec2[j], vec1[i]);\n\n      // This takes care of parallel lines\n      if (fabs(det) <= 1e-14) {\n        continue;\n      }\n\n      auto vec12 = pts2[j] - pts1[i];\n\n      T t1 = cross_2d<T>(vec2[j], vec12) / det;\n      T t2 = cross_2d<T>(vec1[i], vec12) / det;\n\n      if (t1 > -EPS && t1 < 1.0f + EPS && t2 > -EPS && t2 < 1.0f + EPS) {\n        intersections[num++] = pts1[i] + vec1[i] * t1;\n      }\n    }\n  }\n\n  // Check for vertices of rect1 inside rect2\n  {\n    const auto& AB = vec2[0];\n    const auto& DA = vec2[3];\n    auto ABdotAB = dot_2d<T>(AB, AB);\n    auto ADdotAD = dot_2d<T>(DA, DA);\n    for (int i = 0; i < 4; i++) {\n      // assume ABCD is the rectangle, and P is the point to be judged\n      // P is inside ABCD iff. P's projection on AB lies within AB\n      // and P's projection on AD lies within AD\n\n      auto AP = pts1[i] - pts2[0];\n\n      auto APdotAB = dot_2d<T>(AP, AB);\n      auto APdotAD = -dot_2d<T>(AP, DA);\n\n      if ((APdotAB > -EPS) && (APdotAD > -EPS) && (APdotAB < ABdotAB + EPS) &&\n          (APdotAD < ADdotAD + EPS)) {\n        intersections[num++] = pts1[i];\n      }\n    }\n  }\n\n  // Reverse the check - check for vertices of rect2 inside rect1\n  {\n    const auto& AB = vec1[0];\n    const auto& DA = vec1[3];\n    auto ABdotAB = dot_2d<T>(AB, AB);\n    auto ADdotAD = dot_2d<T>(DA, DA);\n    for (int i = 0; i < 4; i++) {\n      auto AP = pts2[i] - pts1[0];\n\n      auto APdotAB = dot_2d<T>(AP, AB);\n      auto APdotAD = -dot_2d<T>(AP, DA);\n\n      if ((APdotAB > -EPS) && (APdotAD > -EPS) && (APdotAB < ABdotAB + EPS) &&\n          (APdotAD < ADdotAD + EPS)) {\n        intersections[num++] = pts2[i];\n      }\n    }\n  }\n\n  return num;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE int convex_hull_graham(\n    const Point<T> (&p)[24],\n    const int& num_in,\n    Point<T> (&q)[24],\n    bool shift_to_zero = false) {\n  assert(num_in >= 2);\n\n  // Step 1:\n  // Find point with minimum y\n  // if more than 1 points have the same minimum y,\n  // pick the one with the minimum x.\n  int t = 0;\n  for (int i = 1; i < num_in; i++) {\n    if (p[i].y < p[t].y || (p[i].y == p[t].y && p[i].x < p[t].x)) {\n      t = i;\n    }\n  }\n  auto& start = p[t]; // starting point\n\n  // Step 2:\n  // Subtract starting point from every points (for sorting in the next step)\n  for (int i = 0; i < num_in; i++) {\n    q[i] = p[i] - start;\n  }\n\n  // Swap the starting point to position 0\n  auto tmp = q[0];\n  q[0] = q[t];\n  q[t] = tmp;\n\n  // Step 3:\n  // Sort point 1 ~ num_in according to their relative cross-product values\n  // (essentially sorting according to angles)\n  // If the angles are the same, sort according to their distance to origin\n  T dist[24];\n#if defined(__CUDACC__) || __HCC__ == 1 || __HIP__ == 1\n  // compute distance to origin before sort, and sort them together with the\n  // points\n  for (int i = 0; i < num_in; i++) {\n    dist[i] = dot_2d<T>(q[i], q[i]);\n  }\n\n  // CUDA version\n  // In the future, we can potentially use thrust\n  // for sorting here to improve speed (though not guaranteed)\n  for (int i = 1; i < num_in - 1; i++) {\n    for (int j = i + 1; j < num_in; j++) {\n      T crossProduct = cross_2d<T>(q[i], q[j]);\n      if ((crossProduct < -1e-6) ||\n          (fabs(crossProduct) < 1e-6 && dist[i] > dist[j])) {\n        auto q_tmp = q[i];\n        q[i] = q[j];\n        q[j] = q_tmp;\n        auto dist_tmp = dist[i];\n        dist[i] = dist[j];\n        dist[j] = dist_tmp;\n      }\n    }\n  }\n#else\n  // CPU version\n  // std::sort(\n  //     q + 1, q + num_in, [](const Point<T>& A, const Point<T>& B) -> bool {\n  //       T temp = cross_2d<T>(A, B);\n\n  // if (fabs(temp) < 1e-6) {\n  //   return dot_2d<T>(A, A) < dot_2d<T>(B, B);\n  // } else {\n  //   return temp > 0;\n  // }\n  // });\n  for (int i = 0; i < num_in; i++) {\n    dist[i] = dot_2d<T>(q[i], q[i]);\n  }\n\n  for (int i = 1; i < num_in - 1; i++) {\n    for (int j = i + 1; j < num_in; j++) {\n      T crossProduct = cross_2d<T>(q[i], q[j]);\n      if ((crossProduct < -1e-6) ||\n          (fabs(crossProduct) < 1e-6 && dist[i] > dist[j])) {\n        auto q_tmp = q[i];\n        q[i] = q[j];\n        q[j] = q_tmp;\n        auto dist_tmp = dist[i];\n        dist[i] = dist[j];\n        dist[j] = dist_tmp;\n      }\n    }\n  }\n\n  // compute distance to origin after sort, since the points are now different.\n  for (int i = 0; i < num_in; i++) {\n    dist[i] = dot_2d<T>(q[i], q[i]);\n  }\n\n#endif\n\n  // Step 4:\n  // Make sure there are at least 2 points (that don't overlap with each other)\n  // in the stack\n  int k; // index of the non-overlapped second point\n  for (k = 1; k < num_in; k++) {\n    if (dist[k] > 1e-8) {\n      break;\n    }\n  }\n  if (k == num_in) {\n    // We reach the end, which means the convex hull is just one point\n    q[0] = p[t];\n    return 1;\n  }\n  q[1] = q[k];\n  int m = 2; // 2 points in the stack\n  // Step 5:\n  // Finally we can start the scanning process.\n  // When a non-convex relationship between the 3 points is found\n  // (either concave shape or duplicated points),\n  // we pop the previous point from the stack\n  // until the 3-point relationship is convex again, or\n  // until the stack only contains two points\n  for (int i = k + 1; i < num_in; i++) {\n    while (m > 1) {\n      auto q1 = q[i] - q[m - 2], q2 = q[m - 1] - q[m - 2];\n      // cross_2d() uses FMA and therefore computes round(round(q1.x*q2.y) -\n      // q2.x*q1.y) So it may not return 0 even when q1==q2. Therefore we\n      // compare round(q1.x*q2.y) and round(q2.x*q1.y) directly. (round means\n      // round to nearest floating point).\n      if (q1.x * q2.y >= q2.x * q1.y)\n        m--;\n      else\n        break;\n    }\n    // Using double also helps, but float can solve the issue for now.\n    // while (m > 1 && cross_2d<T, double>(q[i] - q[m - 2], q[m - 1] - q[m - 2])\n    // >= 0) {\n    //     m--;\n    // }\n    q[m++] = q[i];\n  }\n\n  // Step 6 (Optional):\n  // In general sense we need the original coordinates, so we\n  // need to shift the points back (reverting Step 2)\n  // But if we're only interested in getting the area/perimeter of the shape\n  // We can simply return.\n  if (!shift_to_zero) {\n    for (int i = 0; i < m; i++) {\n      q[i] += start;\n    }\n  }\n\n  return m;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T polygon_area(const Point<T> (&q)[24], const int& m) {\n  if (m <= 2) {\n    return 0;\n  }\n\n  T area = 0;\n  for (int i = 1; i < m - 1; i++) {\n    area += fabs(cross_2d<T>(q[i] - q[0], q[i + 1] - q[0]));\n  }\n\n  return area / 2.0;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T rotated_boxes_intersection(\n    const RotatedBox<T>& box1,\n    const RotatedBox<T>& box2) {\n  // There are up to 4 x 4 + 4 + 4 = 24 intersections (including dups) returned\n  // from rotated_rect_intersection_pts\n  Point<T> intersectPts[24], orderedPts[24];\n\n  Point<T> pts1[4];\n  Point<T> pts2[4];\n  get_rotated_vertices<T>(box1, pts1);\n  get_rotated_vertices<T>(box2, pts2);\n\n  int num = get_intersection_points<T>(pts1, pts2, intersectPts);\n\n  if (num <= 2) {\n    return 0.0;\n  }\n\n  // Convex Hull to order the intersection points in clockwise order and find\n  // the contour area.\n  int num_convex = convex_hull_graham<T>(intersectPts, num, orderedPts, true);\n  return polygon_area<T>(orderedPts, num_convex);\n}\n\n} // namespace\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T\nsingle_box_iou_rotated(T const* const box1_raw, T const* const box2_raw) {\n  // shift center to the middle point to achieve higher precision in result\n  RotatedBox<T> box1, box2;\n  auto center_shift_x = (box1_raw[0] + box2_raw[0]) / 2.0;\n  auto center_shift_y = (box1_raw[1] + box2_raw[1]) / 2.0;\n  box1.x_ctr = box1_raw[0] - center_shift_x;\n  box1.y_ctr = box1_raw[1] - center_shift_y;\n  box1.w = box1_raw[2];\n  box1.h = box1_raw[3];\n  box1.a = box1_raw[4];\n  box2.x_ctr = box2_raw[0] - center_shift_x;\n  box2.y_ctr = box2_raw[1] - center_shift_y;\n  box2.w = box2_raw[2];\n  box2.h = box2_raw[3];\n  box2.a = box2_raw[4];\n\n  T area1 = box1.w * box1.h;\n  T area2 = box2.w * box2.h;\n  if (area1 < 1e-14 || area2 < 1e-14) {\n    return 0.f;\n  }\n\n  T intersection = rotated_boxes_intersection<T>(box1, box2);\n  T iou = intersection / (area1 + area2 - intersection);\n  return iou;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/cocoeval/cocoeval.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include \"cocoeval.h\"\n#include <time.h>\n#include <algorithm>\n#include <cstdint>\n#include <numeric>\n\nusing namespace pybind11::literals;\n\nnamespace detectron2 {\n\nnamespace COCOeval {\n\n// Sort detections from highest score to lowest, such that\n// detection_instances[detection_sorted_indices[t]] >=\n// detection_instances[detection_sorted_indices[t+1]].  Use stable_sort to match\n// original COCO API\nvoid SortInstancesByDetectionScore(\n    const std::vector<InstanceAnnotation>& detection_instances,\n    std::vector<uint64_t>* detection_sorted_indices) {\n  detection_sorted_indices->resize(detection_instances.size());\n  std::iota(\n      detection_sorted_indices->begin(), detection_sorted_indices->end(), 0);\n  std::stable_sort(\n      detection_sorted_indices->begin(),\n      detection_sorted_indices->end(),\n      [&detection_instances](size_t j1, size_t j2) {\n        return detection_instances[j1].score > detection_instances[j2].score;\n      });\n}\n\n// Partition the ground truth objects based on whether or not to ignore them\n// based on area\nvoid SortInstancesByIgnore(\n    const std::array<double, 2>& area_range,\n    const std::vector<InstanceAnnotation>& ground_truth_instances,\n    std::vector<uint64_t>* ground_truth_sorted_indices,\n    std::vector<bool>* ignores) {\n  ignores->clear();\n  ignores->reserve(ground_truth_instances.size());\n  for (auto o : ground_truth_instances) {\n    ignores->push_back(\n        o.ignore || o.area < area_range[0] || o.area > area_range[1]);\n  }\n\n  ground_truth_sorted_indices->resize(ground_truth_instances.size());\n  std::iota(\n      ground_truth_sorted_indices->begin(),\n      ground_truth_sorted_indices->end(),\n      0);\n  std::stable_sort(\n      ground_truth_sorted_indices->begin(),\n      ground_truth_sorted_indices->end(),\n      [&ignores](size_t j1, size_t j2) {\n        return (int)(*ignores)[j1] < (int)(*ignores)[j2];\n      });\n}\n\n// For each IOU threshold, greedily match each detected instance to a ground\n// truth instance (if possible) and store the results\nvoid MatchDetectionsToGroundTruth(\n    const std::vector<InstanceAnnotation>& detection_instances,\n    const std::vector<uint64_t>& detection_sorted_indices,\n    const std::vector<InstanceAnnotation>& ground_truth_instances,\n    const std::vector<uint64_t>& ground_truth_sorted_indices,\n    const std::vector<bool>& ignores,\n    const std::vector<std::vector<double>>& ious,\n    const std::vector<double>& iou_thresholds,\n    const std::array<double, 2>& area_range,\n    ImageEvaluation* results) {\n  // Initialize memory to store return data matches and ignore\n  const int num_iou_thresholds = iou_thresholds.size();\n  const int num_ground_truth = ground_truth_sorted_indices.size();\n  const int num_detections = detection_sorted_indices.size();\n  std::vector<uint64_t> ground_truth_matches(\n      num_iou_thresholds * num_ground_truth, 0);\n  std::vector<uint64_t>& detection_matches = results->detection_matches;\n  std::vector<bool>& detection_ignores = results->detection_ignores;\n  std::vector<bool>& ground_truth_ignores = results->ground_truth_ignores;\n  detection_matches.resize(num_iou_thresholds * num_detections, 0);\n  detection_ignores.resize(num_iou_thresholds * num_detections, false);\n  ground_truth_ignores.resize(num_ground_truth);\n  for (auto g = 0; g < num_ground_truth; ++g) {\n    ground_truth_ignores[g] = ignores[ground_truth_sorted_indices[g]];\n  }\n\n  for (auto t = 0; t < num_iou_thresholds; ++t) {\n    for (auto d = 0; d < num_detections; ++d) {\n      // information about best match so far (match=-1 -> unmatched)\n      double best_iou = std::min(iou_thresholds[t], 1 - 1e-10);\n      int match = -1;\n      for (auto g = 0; g < num_ground_truth; ++g) {\n        // if this ground truth instance is already matched and not a\n        // crowd, it cannot be matched to another detection\n        if (ground_truth_matches[t * num_ground_truth + g] > 0 &&\n            !ground_truth_instances[ground_truth_sorted_indices[g]].is_crowd) {\n          continue;\n        }\n\n        // if detected instance matched to a regular ground truth\n        // instance, we can break on the first ground truth instance\n        // tagged as ignore (because they are sorted by the ignore tag)\n        if (match >= 0 && !ground_truth_ignores[match] &&\n            ground_truth_ignores[g]) {\n          break;\n        }\n\n        // if IOU overlap is the best so far, store the match appropriately\n        if (ious[d][ground_truth_sorted_indices[g]] >= best_iou) {\n          best_iou = ious[d][ground_truth_sorted_indices[g]];\n          match = g;\n        }\n      }\n      // if match was made, store id of match for both detection and\n      // ground truth\n      if (match >= 0) {\n        detection_ignores[t * num_detections + d] = ground_truth_ignores[match];\n        detection_matches[t * num_detections + d] =\n            ground_truth_instances[ground_truth_sorted_indices[match]].id;\n        ground_truth_matches[t * num_ground_truth + match] =\n            detection_instances[detection_sorted_indices[d]].id;\n      }\n\n      // set unmatched detections outside of area range to ignore\n      const InstanceAnnotation& detection =\n          detection_instances[detection_sorted_indices[d]];\n      detection_ignores[t * num_detections + d] =\n          detection_ignores[t * num_detections + d] ||\n          (detection_matches[t * num_detections + d] == 0 &&\n           (detection.area < area_range[0] || detection.area > area_range[1]));\n    }\n  }\n\n  // store detection score results\n  results->detection_scores.resize(detection_sorted_indices.size());\n  for (size_t d = 0; d < detection_sorted_indices.size(); ++d) {\n    results->detection_scores[d] =\n        detection_instances[detection_sorted_indices[d]].score;\n  }\n}\n\nstd::vector<ImageEvaluation> EvaluateImages(\n    const std::vector<std::array<double, 2>>& area_ranges,\n    int max_detections,\n    const std::vector<double>& iou_thresholds,\n    const ImageCategoryInstances<std::vector<double>>& image_category_ious,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_ground_truth_instances,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_detection_instances) {\n  const int num_area_ranges = area_ranges.size();\n  const int num_images = image_category_ground_truth_instances.size();\n  const int num_categories =\n      image_category_ious.size() > 0 ? image_category_ious[0].size() : 0;\n  std::vector<uint64_t> detection_sorted_indices;\n  std::vector<uint64_t> ground_truth_sorted_indices;\n  std::vector<bool> ignores;\n  std::vector<ImageEvaluation> results_all(\n      num_images * num_area_ranges * num_categories);\n\n  // Store results for each image, category, and area range combination. Results\n  // for each IOU threshold are packed into the same ImageEvaluation object\n  for (auto i = 0; i < num_images; ++i) {\n    for (auto c = 0; c < num_categories; ++c) {\n      const std::vector<InstanceAnnotation>& ground_truth_instances =\n          image_category_ground_truth_instances[i][c];\n      const std::vector<InstanceAnnotation>& detection_instances =\n          image_category_detection_instances[i][c];\n\n      SortInstancesByDetectionScore(\n          detection_instances, &detection_sorted_indices);\n      if ((int)detection_sorted_indices.size() > max_detections) {\n        detection_sorted_indices.resize(max_detections);\n      }\n\n      for (size_t a = 0; a < area_ranges.size(); ++a) {\n        SortInstancesByIgnore(\n            area_ranges[a],\n            ground_truth_instances,\n            &ground_truth_sorted_indices,\n            &ignores);\n\n        MatchDetectionsToGroundTruth(\n            detection_instances,\n            detection_sorted_indices,\n            ground_truth_instances,\n            ground_truth_sorted_indices,\n            ignores,\n            image_category_ious[i][c],\n            iou_thresholds,\n            area_ranges[a],\n            &results_all\n                [c * num_area_ranges * num_images + a * num_images + i]);\n      }\n    }\n  }\n\n  return results_all;\n}\n\n// Convert a python list to a vector\ntemplate <typename T>\nstd::vector<T> list_to_vec(const py::list& l) {\n  std::vector<T> v(py::len(l));\n  for (int i = 0; i < (int)py::len(l); ++i) {\n    v[i] = l[i].cast<T>();\n  }\n  return v;\n}\n\n// Helper function to Accumulate()\n// Considers the evaluation results applicable to a particular category, area\n// range, and max_detections parameter setting, which begin at\n// evaluations[evaluation_index].  Extracts a sorted list of length n of all\n// applicable detection instances concatenated across all images in the dataset,\n// which are represented by the outputs evaluation_indices, detection_scores,\n// image_detection_indices, and detection_sorted_indices--all of which are\n// length n. evaluation_indices[i] stores the applicable index into\n// evaluations[] for instance i, which has detection score detection_score[i],\n// and is the image_detection_indices[i]'th of the list of detections\n// for the image containing i.  detection_sorted_indices[] defines a sorted\n// permutation of the 3 other outputs\nint BuildSortedDetectionList(\n    const std::vector<ImageEvaluation>& evaluations,\n    const int64_t evaluation_index,\n    const int64_t num_images,\n    const int max_detections,\n    std::vector<uint64_t>* evaluation_indices,\n    std::vector<double>* detection_scores,\n    std::vector<uint64_t>* detection_sorted_indices,\n    std::vector<uint64_t>* image_detection_indices) {\n  assert(evaluations.size() >= evaluation_index + num_images);\n\n  // Extract a list of object instances of the applicable category, area\n  // range, and max detections requirements such that they can be sorted\n  image_detection_indices->clear();\n  evaluation_indices->clear();\n  detection_scores->clear();\n  image_detection_indices->reserve(num_images * max_detections);\n  evaluation_indices->reserve(num_images * max_detections);\n  detection_scores->reserve(num_images * max_detections);\n  int num_valid_ground_truth = 0;\n  for (auto i = 0; i < num_images; ++i) {\n    const ImageEvaluation& evaluation = evaluations[evaluation_index + i];\n\n    for (int d = 0;\n         d < (int)evaluation.detection_scores.size() && d < max_detections;\n         ++d) { // detected instances\n      evaluation_indices->push_back(evaluation_index + i);\n      image_detection_indices->push_back(d);\n      detection_scores->push_back(evaluation.detection_scores[d]);\n    }\n    for (auto ground_truth_ignore : evaluation.ground_truth_ignores) {\n      if (!ground_truth_ignore) {\n        ++num_valid_ground_truth;\n      }\n    }\n  }\n\n  // Sort detections by decreasing score, using stable sort to match\n  // python implementation\n  detection_sorted_indices->resize(detection_scores->size());\n  std::iota(\n      detection_sorted_indices->begin(), detection_sorted_indices->end(), 0);\n  std::stable_sort(\n      detection_sorted_indices->begin(),\n      detection_sorted_indices->end(),\n      [&detection_scores](size_t j1, size_t j2) {\n        return (*detection_scores)[j1] > (*detection_scores)[j2];\n      });\n\n  return num_valid_ground_truth;\n}\n\n// Helper function to Accumulate()\n// Compute a precision recall curve given a sorted list of detected instances\n// encoded in evaluations, evaluation_indices, detection_scores,\n// detection_sorted_indices, image_detection_indices (see\n// BuildSortedDetectionList()). Using vectors precisions and recalls\n// and temporary storage, output the results into precisions_out, recalls_out,\n// and scores_out, which are large buffers containing many precion/recall curves\n// for all possible parameter settings, with precisions_out_index and\n// recalls_out_index defining the applicable indices to store results.\nvoid ComputePrecisionRecallCurve(\n    const int64_t precisions_out_index,\n    const int64_t precisions_out_stride,\n    const int64_t recalls_out_index,\n    const std::vector<double>& recall_thresholds,\n    const int iou_threshold_index,\n    const int num_iou_thresholds,\n    const int num_valid_ground_truth,\n    const std::vector<ImageEvaluation>& evaluations,\n    const std::vector<uint64_t>& evaluation_indices,\n    const std::vector<double>& detection_scores,\n    const std::vector<uint64_t>& detection_sorted_indices,\n    const std::vector<uint64_t>& image_detection_indices,\n    std::vector<double>* precisions,\n    std::vector<double>* recalls,\n    std::vector<double>* precisions_out,\n    std::vector<double>* scores_out,\n    std::vector<double>* recalls_out) {\n  assert(recalls_out->size() > recalls_out_index);\n\n  // Compute precision/recall for each instance in the sorted list of detections\n  int64_t true_positives_sum = 0, false_positives_sum = 0;\n  precisions->clear();\n  recalls->clear();\n  precisions->reserve(detection_sorted_indices.size());\n  recalls->reserve(detection_sorted_indices.size());\n  assert(!evaluations.empty() || detection_sorted_indices.empty());\n  for (auto detection_sorted_index : detection_sorted_indices) {\n    const ImageEvaluation& evaluation =\n        evaluations[evaluation_indices[detection_sorted_index]];\n    const auto num_detections =\n        evaluation.detection_matches.size() / num_iou_thresholds;\n    const auto detection_index = iou_threshold_index * num_detections +\n        image_detection_indices[detection_sorted_index];\n    assert(evaluation.detection_matches.size() > detection_index);\n    assert(evaluation.detection_ignores.size() > detection_index);\n    const int64_t detection_match =\n        evaluation.detection_matches[detection_index];\n    const bool detection_ignores =\n        evaluation.detection_ignores[detection_index];\n    const auto true_positive = detection_match > 0 && !detection_ignores;\n    const auto false_positive = detection_match == 0 && !detection_ignores;\n    if (true_positive) {\n      ++true_positives_sum;\n    }\n    if (false_positive) {\n      ++false_positives_sum;\n    }\n\n    const double recall =\n        static_cast<double>(true_positives_sum) / num_valid_ground_truth;\n    recalls->push_back(recall);\n    const int64_t num_valid_detections =\n        true_positives_sum + false_positives_sum;\n    const double precision = num_valid_detections > 0\n        ? static_cast<double>(true_positives_sum) / num_valid_detections\n        : 0.0;\n    precisions->push_back(precision);\n  }\n\n  (*recalls_out)[recalls_out_index] = !recalls->empty() ? recalls->back() : 0;\n\n  for (int64_t i = static_cast<int64_t>(precisions->size()) - 1; i > 0; --i) {\n    if ((*precisions)[i] > (*precisions)[i - 1]) {\n      (*precisions)[i - 1] = (*precisions)[i];\n    }\n  }\n\n  // Sample the per instance precision/recall list at each recall threshold\n  for (size_t r = 0; r < recall_thresholds.size(); ++r) {\n    // first index in recalls >= recall_thresholds[r]\n    std::vector<double>::iterator low = std::lower_bound(\n        recalls->begin(), recalls->end(), recall_thresholds[r]);\n    size_t precisions_index = low - recalls->begin();\n\n    const auto results_ind = precisions_out_index + r * precisions_out_stride;\n    assert(results_ind < precisions_out->size());\n    assert(results_ind < scores_out->size());\n    if (precisions_index < precisions->size()) {\n      (*precisions_out)[results_ind] = (*precisions)[precisions_index];\n      (*scores_out)[results_ind] =\n          detection_scores[detection_sorted_indices[precisions_index]];\n    } else {\n      (*precisions_out)[results_ind] = 0;\n      (*scores_out)[results_ind] = 0;\n    }\n  }\n}\npy::dict Accumulate(\n    const py::object& params,\n    const std::vector<ImageEvaluation>& evaluations) {\n  const std::vector<double> recall_thresholds =\n      list_to_vec<double>(params.attr(\"recThrs\"));\n  const std::vector<int> max_detections =\n      list_to_vec<int>(params.attr(\"maxDets\"));\n  const int num_iou_thresholds = py::len(params.attr(\"iouThrs\"));\n  const int num_recall_thresholds = py::len(params.attr(\"recThrs\"));\n  const int num_categories = params.attr(\"useCats\").cast<int>() == 1\n      ? py::len(params.attr(\"catIds\"))\n      : 1;\n  const int num_area_ranges = py::len(params.attr(\"areaRng\"));\n  const int num_max_detections = py::len(params.attr(\"maxDets\"));\n  const int num_images = py::len(params.attr(\"imgIds\"));\n\n  std::vector<double> precisions_out(\n      num_iou_thresholds * num_recall_thresholds * num_categories *\n          num_area_ranges * num_max_detections,\n      -1);\n  std::vector<double> recalls_out(\n      num_iou_thresholds * num_categories * num_area_ranges *\n          num_max_detections,\n      -1);\n  std::vector<double> scores_out(\n      num_iou_thresholds * num_recall_thresholds * num_categories *\n          num_area_ranges * num_max_detections,\n      -1);\n\n  // Consider the list of all detected instances in the entire dataset in one\n  // large list.  evaluation_indices, detection_scores,\n  // image_detection_indices, and detection_sorted_indices all have the same\n  // length as this list, such that each entry corresponds to one detected\n  // instance\n  std::vector<uint64_t> evaluation_indices; // indices into evaluations[]\n  std::vector<double> detection_scores; // detection scores of each instance\n  std::vector<uint64_t> detection_sorted_indices; // sorted indices of all\n                                                  // instances in the dataset\n  std::vector<uint64_t>\n      image_detection_indices; // indices into the list of detected instances in\n                               // the same image as each instance\n  std::vector<double> precisions, recalls;\n\n  for (auto c = 0; c < num_categories; ++c) {\n    for (auto a = 0; a < num_area_ranges; ++a) {\n      for (auto m = 0; m < num_max_detections; ++m) {\n        // The COCO PythonAPI assumes evaluations[] (the return value of\n        // COCOeval::EvaluateImages() is one long list storing results for each\n        // combination of category, area range, and image id, with categories in\n        // the outermost loop and images in the innermost loop.\n        const int64_t evaluations_index =\n            c * num_area_ranges * num_images + a * num_images;\n        int num_valid_ground_truth = BuildSortedDetectionList(\n            evaluations,\n            evaluations_index,\n            num_images,\n            max_detections[m],\n            &evaluation_indices,\n            &detection_scores,\n            &detection_sorted_indices,\n            &image_detection_indices);\n\n        if (num_valid_ground_truth == 0) {\n          continue;\n        }\n\n        for (auto t = 0; t < num_iou_thresholds; ++t) {\n          // recalls_out is a flattened vectors representing a\n          // num_iou_thresholds X num_categories X num_area_ranges X\n          // num_max_detections matrix\n          const int64_t recalls_out_index =\n              t * num_categories * num_area_ranges * num_max_detections +\n              c * num_area_ranges * num_max_detections +\n              a * num_max_detections + m;\n\n          // precisions_out and scores_out are flattened vectors\n          // representing a num_iou_thresholds X num_recall_thresholds X\n          // num_categories X num_area_ranges X num_max_detections matrix\n          const int64_t precisions_out_stride =\n              num_categories * num_area_ranges * num_max_detections;\n          const int64_t precisions_out_index = t * num_recall_thresholds *\n                  num_categories * num_area_ranges * num_max_detections +\n              c * num_area_ranges * num_max_detections +\n              a * num_max_detections + m;\n\n          ComputePrecisionRecallCurve(\n              precisions_out_index,\n              precisions_out_stride,\n              recalls_out_index,\n              recall_thresholds,\n              t,\n              num_iou_thresholds,\n              num_valid_ground_truth,\n              evaluations,\n              evaluation_indices,\n              detection_scores,\n              detection_sorted_indices,\n              image_detection_indices,\n              &precisions,\n              &recalls,\n              &precisions_out,\n              &scores_out,\n              &recalls_out);\n        }\n      }\n    }\n  }\n\n  time_t rawtime;\n  struct tm local_time;\n  std::array<char, 200> buffer;\n  time(&rawtime);\n#ifdef _WIN32\n  localtime_s(&local_time, &rawtime);\n#else\n  localtime_r(&rawtime, &local_time);\n#endif\n  strftime(\n      buffer.data(), 200, \"%Y-%m-%d %H:%num_max_detections:%S\", &local_time);\n  return py::dict(\n      \"params\"_a = params,\n      \"counts\"_a = std::vector<int64_t>(\n          {num_iou_thresholds,\n           num_recall_thresholds,\n           num_categories,\n           num_area_ranges,\n           num_max_detections}),\n      \"date\"_a = buffer,\n      \"precision\"_a = precisions_out,\n      \"recall\"_a = recalls_out,\n      \"scores\"_a = scores_out);\n}\n\n} // namespace COCOeval\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/cocoeval/cocoeval.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n\n#include <pybind11/numpy.h>\n#include <pybind11/pybind11.h>\n#include <pybind11/stl.h>\n#include <pybind11/stl_bind.h>\n#include <vector>\n\nnamespace py = pybind11;\n\nnamespace detectron2 {\n\nnamespace COCOeval {\n\n// Annotation data for a single object instance in an image\nstruct InstanceAnnotation {\n  InstanceAnnotation(\n      uint64_t id,\n      double score,\n      double area,\n      bool is_crowd,\n      bool ignore)\n      : id{id}, score{score}, area{area}, is_crowd{is_crowd}, ignore{ignore} {}\n  uint64_t id;\n  double score = 0.;\n  double area = 0.;\n  bool is_crowd = false;\n  bool ignore = false;\n};\n\n// Stores intermediate results for evaluating detection results for a single\n// image that has D detected instances and G ground truth instances. This stores\n// matches between detected and ground truth instances\nstruct ImageEvaluation {\n  // For each of the D detected instances, the id of the matched ground truth\n  // instance, or 0 if unmatched\n  std::vector<uint64_t> detection_matches;\n\n  // The detection score of each of the D detected instances\n  std::vector<double> detection_scores;\n\n  // Marks whether or not each of G instances was ignored from evaluation (e.g.,\n  // because it's outside area_range)\n  std::vector<bool> ground_truth_ignores;\n\n  // Marks whether or not each of D instances was ignored from evaluation (e.g.,\n  // because it's outside aRng)\n  std::vector<bool> detection_ignores;\n};\n\ntemplate <class T>\nusing ImageCategoryInstances = std::vector<std::vector<std::vector<T>>>;\n\n// C++ implementation of COCO API cocoeval.py::COCOeval.evaluateImg().  For each\n// combination of image, category, area range settings, and IOU thresholds to\n// evaluate, it matches detected instances to ground truth instances and stores\n// the results into a vector of ImageEvaluation results, which will be\n// interpreted by the COCOeval::Accumulate() function to produce precion-recall\n// curves.  The parameters of nested vectors have the following semantics:\n//   image_category_ious[i][c][d][g] is the intersection over union of the d'th\n//     detected instance and g'th ground truth instance of\n//     category category_ids[c] in image image_ids[i]\n//   image_category_ground_truth_instances[i][c] is a vector of ground truth\n//     instances in image image_ids[i] of category category_ids[c]\n//   image_category_detection_instances[i][c] is a vector of detected\n//     instances in image image_ids[i] of category category_ids[c]\nstd::vector<ImageEvaluation> EvaluateImages(\n    const std::vector<std::array<double, 2>>& area_ranges, // vector of 2-tuples\n    int max_detections,\n    const std::vector<double>& iou_thresholds,\n    const ImageCategoryInstances<std::vector<double>>& image_category_ious,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_ground_truth_instances,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_detection_instances);\n\n// C++ implementation of COCOeval.accumulate(), which generates precision\n// recall curves for each set of category, IOU threshold, detection area range,\n// and max number of detections parameters.  It is assumed that the parameter\n// evaluations is the return value of the functon COCOeval::EvaluateImages(),\n// which was called with the same parameter settings params\npy::dict Accumulate(\n    const py::object& params,\n    const std::vector<ImageEvaluation>& evalutations);\n\n} // namespace COCOeval\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/cuda_version.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n#include <cuda_runtime_api.h>\n\nnamespace detectron2 {\nint get_cudart_version() {\n// Not a ROCM platform: Either HIP is not used, or\n// it is used, but platform is not ROCM (i.e. it is CUDA)\n#if !defined(__HIP_PLATFORM_AMD__)\n  return CUDART_VERSION;\n#else\n  int version = 0;\n\n#if HIP_VERSION_MAJOR != 0\n  // Create a convention similar to that of CUDA, as assumed by other\n  // parts of the code.\n\n  version = HIP_VERSION_MINOR;\n  version += (HIP_VERSION_MAJOR * 100);\n#else\n  hipRuntimeGetVersion(&version);\n#endif\n  return version;\n#endif\n}\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/deformable/deform_conv.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nint deform_conv_forward_cuda(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor offset,\n    at::Tensor output,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step);\n\nint deform_conv_backward_input_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradInput,\n    at::Tensor gradOffset,\n    at::Tensor weight,\n    at::Tensor columns,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step);\n\nint deform_conv_backward_parameters_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradWeight, // at::Tensor gradBias,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    float scale,\n    int im2col_step);\n\nvoid modulated_deform_conv_cuda_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor output,\n    at::Tensor columns,\n    int kernel_h,\n    int kernel_w,\n    const int stride_h,\n    const int stride_w,\n    const int pad_h,\n    const int pad_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int group,\n    const int deformable_group,\n    const bool with_bias);\n\nvoid modulated_deform_conv_cuda_backward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor columns,\n    at::Tensor grad_input,\n    at::Tensor grad_weight,\n    at::Tensor grad_bias,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask,\n    at::Tensor grad_output,\n    int kernel_h,\n    int kernel_w,\n    int stride_h,\n    int stride_w,\n    int pad_h,\n    int pad_w,\n    int dilation_h,\n    int dilation_w,\n    int group,\n    int deformable_group,\n    const bool with_bias);\n\n#endif\n\ninline int deform_conv_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor offset,\n    at::Tensor output,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  if (input.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return deform_conv_forward_cuda(\n        input,\n        weight,\n        offset,\n        output,\n        columns,\n        ones,\n        kW,\n        kH,\n        dW,\n        dH,\n        padW,\n        padH,\n        dilationW,\n        dilationH,\n        group,\n        deformable_group,\n        im2col_step);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline int deform_conv_backward_input(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradInput,\n    at::Tensor gradOffset,\n    at::Tensor weight,\n    at::Tensor columns,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  if (gradOutput.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(input.is_cuda(), \"input tensor is not on GPU!\");\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return deform_conv_backward_input_cuda(\n        input,\n        offset,\n        gradOutput,\n        gradInput,\n        gradOffset,\n        weight,\n        columns,\n        kW,\n        kH,\n        dW,\n        dH,\n        padW,\n        padH,\n        dilationW,\n        dilationH,\n        group,\n        deformable_group,\n        im2col_step);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline int deform_conv_backward_filter(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradWeight, // at::Tensor gradBias,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    float scale,\n    int im2col_step) {\n  if (gradOutput.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(input.is_cuda(), \"input tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return deform_conv_backward_parameters_cuda(\n        input,\n        offset,\n        gradOutput,\n        gradWeight,\n        columns,\n        ones,\n        kW,\n        kH,\n        dW,\n        dH,\n        padW,\n        padH,\n        dilationW,\n        dilationH,\n        group,\n        deformable_group,\n        scale,\n        im2col_step);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline void modulated_deform_conv_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor output,\n    at::Tensor columns,\n    int kernel_h,\n    int kernel_w,\n    const int stride_h,\n    const int stride_w,\n    const int pad_h,\n    const int pad_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int group,\n    const int deformable_group,\n    const bool with_bias) {\n  if (input.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(bias.is_cuda(), \"bias tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return modulated_deform_conv_cuda_forward(\n        input,\n        weight,\n        bias,\n        ones,\n        offset,\n        mask,\n        output,\n        columns,\n        kernel_h,\n        kernel_w,\n        stride_h,\n        stride_w,\n        pad_h,\n        pad_w,\n        dilation_h,\n        dilation_w,\n        group,\n        deformable_group,\n        with_bias);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline void modulated_deform_conv_backward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor columns,\n    at::Tensor grad_input,\n    at::Tensor grad_weight,\n    at::Tensor grad_bias,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask,\n    at::Tensor grad_output,\n    int kernel_h,\n    int kernel_w,\n    int stride_h,\n    int stride_w,\n    int pad_h,\n    int pad_w,\n    int dilation_h,\n    int dilation_w,\n    int group,\n    int deformable_group,\n    const bool with_bias) {\n  if (grad_output.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(input.is_cuda(), \"input tensor is not on GPU!\");\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(bias.is_cuda(), \"bias tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return modulated_deform_conv_cuda_backward(\n        input,\n        weight,\n        bias,\n        ones,\n        offset,\n        mask,\n        columns,\n        grad_input,\n        grad_weight,\n        grad_bias,\n        grad_offset,\n        grad_mask,\n        grad_output,\n        kernel_h,\n        kernel_w,\n        stride_h,\n        stride_w,\n        pad_h,\n        pad_w,\n        dilation_h,\n        dilation_w,\n        group,\n        deformable_group,\n        with_bias);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/deformable/deform_conv_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n// modified from\n// https://github.com/open-mmlab/mmdetection/blob/master/mmdet/ops/dcn/src/deform_conv_cuda.cpp\n// Original license: Apache 2.0\n\n// modify from\n// https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/blob/mmdetection/mmdet/ops/dcn/src/deform_conv_cuda.c\n// Original license: Apache 2.0\n\n#include <torch/types.h>\n\n#include \"deform_conv.h\"\n\n#include <cmath>\n#include <vector>\n\nnamespace detectron2 {\n\nvoid deformable_im2col(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor data_col);\n\nvoid deformable_col2im(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_im);\n\nvoid deformable_col2im_coord(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_offset);\n\nvoid modulated_deformable_im2col_cuda(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor data_col);\n\nvoid modulated_deformable_col2im_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_im);\n\nvoid modulated_deformable_col2im_coord_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask);\n\nvoid shape_check(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor* gradOutput,\n    at::Tensor weight,\n    int kH,\n    int kW,\n    int dH,\n    int dW,\n    int padH,\n    int padW,\n    int dilationH,\n    int dilationW,\n    int group,\n    int deformable_group) {\n  TORCH_CHECK(\n      weight.ndimension() == 4,\n      \"4D weight tensor (nOutputPlane,nInputPlane,kH,kW) expected, \"\n      \"but got: %s\",\n      weight.ndimension());\n\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  TORCH_CHECK(\n      kW > 0 && kH > 0,\n      \"kernel size should be greater than zero, but got kH: %d kW: %d\",\n      kH,\n      kW);\n\n  TORCH_CHECK(\n      (weight.size(2) == kH && weight.size(3) == kW),\n      \"kernel size should be consistent with weight, \",\n      \"but got kH: %d kW: %d weight.size(2): %d, weight.size(3): %d\",\n      kH,\n      kW,\n      weight.size(2),\n      weight.size(3));\n\n  TORCH_CHECK(\n      dW > 0 && dH > 0,\n      \"stride should be greater than zero, but got dH: %d dW: %d\",\n      dH,\n      dW);\n\n  TORCH_CHECK(\n      dilationW > 0 && dilationH > 0,\n      \"dilation should be greater than 0, but got dilationH: %d dilationW: %d\",\n      dilationH,\n      dilationW);\n\n  int ndim = input.ndimension();\n  int dimf = 0;\n  int dimh = 1;\n  int dimw = 2;\n\n  if (ndim == 4) {\n    dimf++;\n    dimh++;\n    dimw++;\n  }\n\n  TORCH_CHECK(\n      ndim == 3 || ndim == 4,\n      \"3D or 4D input tensor expected but got: %s\",\n      ndim);\n\n  long nInputPlane = weight.size(1) * group;\n  long inputHeight = input.size(dimh);\n  long inputWidth = input.size(dimw);\n  long nOutputPlane = weight.size(0);\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n\n  TORCH_CHECK(\n      nInputPlane % deformable_group == 0,\n      \"input channels must divide deformable group size\");\n\n  if (outputWidth < 1 || outputHeight < 1)\n    AT_ERROR(\n        \"Given input size: (%ld x %ld x %ld). \"\n        \"Calculated output size: (%ld x %ld x %ld). Output size is too small\",\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        nOutputPlane,\n        outputHeight,\n        outputWidth);\n\n  TORCH_CHECK(\n      input.size(1) == nInputPlane,\n      \"invalid number of input planes, expected: %d, but got: %d\",\n      nInputPlane,\n      input.size(1));\n\n  TORCH_CHECK(\n      (inputHeight + 2 * padH >= kH && inputWidth + 2 * padW >= kW),\n      \"input image is smaller than kernel\");\n\n  TORCH_CHECK(\n      (offset.size(2) == outputHeight && offset.size(3) == outputWidth),\n      \"invalid spatial size of offset, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      outputHeight,\n      outputWidth,\n      offset.size(2),\n      offset.size(3));\n\n  TORCH_CHECK(\n      (offset.size(1) == deformable_group * 2 * kH * kW),\n      \"invalid number of channels of offset\");\n\n  if (gradOutput != NULL) {\n    TORCH_CHECK(\n        gradOutput->size(dimf) == nOutputPlane,\n        \"invalid number of gradOutput planes, expected: %d, but got: %d\",\n        nOutputPlane,\n        gradOutput->size(dimf));\n\n    TORCH_CHECK(\n        (gradOutput->size(dimh) == outputHeight &&\n         gradOutput->size(dimw) == outputWidth),\n        \"invalid size of gradOutput, expected height: %d width: %d , but \"\n        \"got height: %d width: %d\",\n        outputHeight,\n        outputWidth,\n        gradOutput->size(dimh),\n        gradOutput->size(dimw));\n  }\n}\n\nint deform_conv_forward_cuda(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor offset,\n    at::Tensor output,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  // todo: resize columns to include im2col: done\n  // todo: add im2col_step as input\n  // todo: add new output buffer and transpose it to output (or directly\n  // transpose output) todo: possibly change data indexing because of\n  // parallel_imgs\n\n  shape_check(\n      input,\n      offset,\n      NULL,\n      weight,\n      kH,\n      kW,\n      dH,\n      dW,\n      padH,\n      padW,\n      dilationH,\n      dilationW,\n      group,\n      deformable_group);\n\n  input = input.contiguous();\n  offset = offset.contiguous();\n  weight = weight.contiguous();\n\n  int batch = 1;\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input.unsqueeze_(0);\n    offset.unsqueeze_(0);\n  }\n\n  // todo: assert batchsize dividable by im2col_step\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = weight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), \"invalid batch size of offset\");\n\n  output = output.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nOutputPlane,\n       outputHeight,\n       outputWidth});\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < outputHeight * outputWidth) {\n    ones = at::ones({outputHeight, outputWidth}, input.options());\n  }\n\n  input = input.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  offset = offset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n\n  at::Tensor output_buffer = at::zeros(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step * outputHeight,\n       outputWidth},\n      output.options());\n\n  output_buffer = output_buffer.view(\n      {output_buffer.size(0),\n       group,\n       output_buffer.size(1) / group,\n       output_buffer.size(2),\n       output_buffer.size(3)});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    deformable_im2col(\n        input[elt],\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        columns);\n\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      output_buffer[elt][g] = output_buffer[elt][g]\n                                  .flatten(1)\n                                  .addmm_(weight[g].flatten(1), columns[g])\n                                  .view_as(output_buffer[elt][g]);\n    }\n  }\n\n  output_buffer = output_buffer.view(\n      {output_buffer.size(0),\n       output_buffer.size(1) * output_buffer.size(2),\n       output_buffer.size(3),\n       output_buffer.size(4)});\n\n  output_buffer = output_buffer.view(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step,\n       outputHeight,\n       outputWidth});\n  output_buffer.transpose_(1, 2);\n  output.copy_(output_buffer);\n  output = output.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    output = output.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n    offset = offset.view({offset.size(1), offset.size(2), offset.size(3)});\n  }\n\n  return 1;\n}\n\nint deform_conv_backward_input_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradInput,\n    at::Tensor gradOffset,\n    at::Tensor weight,\n    at::Tensor columns,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  shape_check(\n      input,\n      offset,\n      &gradOutput,\n      weight,\n      kH,\n      kW,\n      dH,\n      dW,\n      padH,\n      padW,\n      dilationH,\n      dilationW,\n      group,\n      deformable_group);\n\n  input = input.contiguous();\n  offset = offset.contiguous();\n  gradOutput = gradOutput.contiguous();\n  weight = weight.contiguous();\n\n  int batch = 1;\n\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input = input.view({1, input.size(0), input.size(1), input.size(2)});\n    offset = offset.view({1, offset.size(0), offset.size(1), offset.size(2)});\n    gradOutput = gradOutput.view(\n        {1, gradOutput.size(0), gradOutput.size(1), gradOutput.size(2)});\n  }\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = weight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), 3, \"invalid batch size of offset\");\n  gradInput = gradInput.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  // change order of grad output\n  gradOutput = gradOutput.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nOutputPlane,\n       outputHeight,\n       outputWidth});\n  gradOutput.transpose_(1, 2);\n\n  gradInput = gradInput.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  input = input.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  gradOffset = gradOffset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n  offset = offset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    // divide into groups\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n    gradOutput = gradOutput.view(\n        {gradOutput.size(0),\n         group,\n         gradOutput.size(1) / group,\n         gradOutput.size(2),\n         gradOutput.size(3),\n         gradOutput.size(4)});\n\n    for (int g = 0; g < group; g++) {\n      columns[g] = columns[g].addmm_(\n          weight[g].flatten(1).transpose(0, 1),\n          gradOutput[elt][g].flatten(1),\n          0.0f,\n          1.0f);\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    gradOutput = gradOutput.view(\n        {gradOutput.size(0),\n         gradOutput.size(1) * gradOutput.size(2),\n         gradOutput.size(3),\n         gradOutput.size(4),\n         gradOutput.size(5)});\n\n    deformable_col2im_coord(\n        columns,\n        input[elt],\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        gradOffset[elt]);\n\n    deformable_col2im(\n        columns,\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        gradInput[elt]);\n  }\n\n  gradOutput.transpose_(1, 2);\n  gradOutput =\n      gradOutput.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  gradInput = gradInput.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  gradOffset = gradOffset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    gradOutput = gradOutput.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n    gradInput = gradInput.view({nInputPlane, inputHeight, inputWidth});\n    offset = offset.view({offset.size(1), offset.size(2), offset.size(3)});\n    gradOffset =\n        gradOffset.view({offset.size(1), offset.size(2), offset.size(3)});\n  }\n\n  return 1;\n}\n\nint deform_conv_backward_parameters_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradWeight, // at::Tensor gradBias,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    float scale,\n    int im2col_step) {\n  // todo: transpose and reshape outGrad\n  // todo: reshape columns\n  // todo: add im2col_step as input\n\n  shape_check(\n      input,\n      offset,\n      &gradOutput,\n      gradWeight,\n      kH,\n      kW,\n      dH,\n      dW,\n      padH,\n      padW,\n      dilationH,\n      dilationW,\n      group,\n      deformable_group);\n\n  input = input.contiguous();\n  offset = offset.contiguous();\n  gradOutput = gradOutput.contiguous();\n\n  int batch = 1;\n\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input = input.view(\n        at::IntList({1, input.size(0), input.size(1), input.size(2)}));\n    gradOutput = gradOutput.view(\n        {1, gradOutput.size(0), gradOutput.size(1), gradOutput.size(2)});\n  }\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = gradWeight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), \"invalid batch size of offset\");\n\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  gradOutput = gradOutput.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nOutputPlane,\n       outputHeight,\n       outputWidth});\n  gradOutput.transpose_(1, 2);\n\n  at::Tensor gradOutputBuffer = at::zeros_like(gradOutput);\n  gradOutputBuffer = gradOutputBuffer.view(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step,\n       outputHeight,\n       outputWidth});\n  gradOutputBuffer.copy_(gradOutput);\n  // gradOutput is not contiguous, so we do reshape (instead of view) next\n  gradOutputBuffer = gradOutputBuffer.reshape(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step * outputHeight,\n       outputWidth});\n\n  gradOutput.transpose_(1, 2);\n  gradOutput =\n      gradOutput.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  input = input.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  offset = offset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    deformable_im2col(\n        input[elt],\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        columns);\n\n    // divide into group\n    gradOutputBuffer = gradOutputBuffer.view(\n        {gradOutputBuffer.size(0),\n         group,\n         gradOutputBuffer.size(1) / group,\n         gradOutputBuffer.size(2),\n         gradOutputBuffer.size(3)});\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    gradWeight = gradWeight.view(\n        {group,\n         gradWeight.size(0) / group,\n         gradWeight.size(1),\n         gradWeight.size(2),\n         gradWeight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      gradWeight[g] = gradWeight[g]\n                          .flatten(1)\n                          .addmm_(\n                              gradOutputBuffer[elt][g].flatten(1),\n                              columns[g].transpose(1, 0),\n                              1.0,\n                              scale)\n                          .view_as(gradWeight[g]);\n    }\n    gradOutputBuffer = gradOutputBuffer.view(\n        {gradOutputBuffer.size(0),\n         gradOutputBuffer.size(1) * gradOutputBuffer.size(2),\n         gradOutputBuffer.size(3),\n         gradOutputBuffer.size(4)});\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    gradWeight = gradWeight.view(\n        {gradWeight.size(0) * gradWeight.size(1),\n         gradWeight.size(2),\n         gradWeight.size(3),\n         gradWeight.size(4)});\n  }\n\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    gradOutput = gradOutput.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n  }\n\n  return 1;\n}\n\nvoid modulated_deform_conv_cuda_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor output,\n    at::Tensor columns,\n    int kernel_h,\n    int kernel_w,\n    const int stride_h,\n    const int stride_w,\n    const int pad_h,\n    const int pad_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int group,\n    const int deformable_group,\n    const bool with_bias) {\n  shape_check(\n      input,\n      offset,\n      NULL,\n      weight,\n      kernel_h,\n      kernel_w,\n      stride_h,\n      stride_w,\n      pad_h,\n      pad_w,\n      dilation_h,\n      dilation_w,\n      group,\n      deformable_group);\n\n  TORCH_CHECK(input.is_contiguous(), \"input tensor has to be contiguous\");\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  const int batch = input.size(0);\n  const int channels = input.size(1);\n  const int height = input.size(2);\n  const int width = input.size(3);\n\n  const int channels_out = weight.size(0);\n  const int channels_kernel = weight.size(1);\n  const int kernel_h_ = weight.size(2);\n  const int kernel_w_ = weight.size(3);\n\n  if (kernel_h_ != kernel_h || kernel_w_ != kernel_w)\n    AT_ERROR(\n        \"Input shape and kernel shape wont match: (%d x %d vs %d x %d).\",\n        kernel_h_,\n        kernel_w,\n        kernel_h_,\n        kernel_w_);\n  if (channels != channels_kernel * group)\n    AT_ERROR(\n        \"Input shape and kernel channels wont match: (%d vs %d).\",\n        channels,\n        channels_kernel * group);\n\n  const int height_out =\n      (height + 2 * pad_h - (dilation_h * (kernel_h - 1) + 1)) / stride_h + 1;\n  const int width_out =\n      (width + 2 * pad_w - (dilation_w * (kernel_w - 1) + 1)) / stride_w + 1;\n\n  // mask shape check\n  TORCH_CHECK(\n      (mask.size(2) == height_out && mask.size(3) == width_out),\n      \"invalid spatial size of mask, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      height_out,\n      width_out,\n      mask.size(2),\n      mask.size(3));\n\n  TORCH_CHECK(\n      (mask.size(1) == deformable_group * kernel_h * kernel_w),\n      \"invalid number of channels of mask\");\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < height_out * width_out) {\n    // Resize plane and fill with ones...\n    ones = at::ones({height_out, width_out}, input.options());\n  }\n\n  // resize output\n  output = output.view({batch, channels_out, height_out, width_out}).zero_();\n  // resize temporary columns\n  columns = at::zeros(\n      {channels * kernel_h * kernel_w, 1 * height_out * width_out},\n      input.options());\n\n  output = output.view(\n      {output.size(0),\n       group,\n       output.size(1) / group,\n       output.size(2),\n       output.size(3)});\n\n  for (int b = 0; b < batch; b++) {\n    modulated_deformable_im2col_cuda(\n        input[b],\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        columns);\n\n    // divide into group\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n\n    for (int g = 0; g < group; g++) {\n      output[b][g] = output[b][g]\n                         .flatten(1)\n                         .addmm_(weight[g].flatten(1), columns[g])\n                         .view_as(output[b][g]);\n    }\n\n    weight = weight.view(\n        {weight.size(0) * weight.size(1),\n         weight.size(2),\n         weight.size(3),\n         weight.size(4)});\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n  }\n\n  output = output.view(\n      {output.size(0),\n       output.size(1) * output.size(2),\n       output.size(3),\n       output.size(4)});\n\n  if (with_bias) {\n    output += bias.view({1, bias.size(0), 1, 1});\n  }\n}\n\nvoid modulated_deform_conv_cuda_backward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor columns,\n    at::Tensor grad_input,\n    at::Tensor grad_weight,\n    at::Tensor grad_bias,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask,\n    at::Tensor grad_output,\n    int kernel_h,\n    int kernel_w,\n    int stride_h,\n    int stride_w,\n    int pad_h,\n    int pad_w,\n    int dilation_h,\n    int dilation_w,\n    int group,\n    int deformable_group,\n    const bool with_bias) {\n  shape_check(\n      input,\n      offset,\n      &grad_output,\n      weight,\n      kernel_h,\n      kernel_w,\n      stride_h,\n      stride_w,\n      pad_h,\n      pad_w,\n      dilation_h,\n      dilation_w,\n      group,\n      deformable_group);\n\n  TORCH_CHECK(input.is_contiguous(), \"input tensor has to be contiguous\");\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  const int batch = input.size(0);\n  const int channels = input.size(1);\n  const int height = input.size(2);\n  const int width = input.size(3);\n\n  const int channels_kernel = weight.size(1);\n  const int kernel_h_ = weight.size(2);\n  const int kernel_w_ = weight.size(3);\n  if (kernel_h_ != kernel_h || kernel_w_ != kernel_w)\n    AT_ERROR(\n        \"Input shape and kernel shape wont match: (%d x %d vs %d x %d).\",\n        kernel_h_,\n        kernel_w,\n        kernel_h_,\n        kernel_w_);\n  if (channels != channels_kernel * group)\n    AT_ERROR(\n        \"Input shape and kernel channels wont match: (%d vs %d).\",\n        channels,\n        channels_kernel * group);\n\n  const int height_out =\n      (height + 2 * pad_h - (dilation_h * (kernel_h - 1) + 1)) / stride_h + 1;\n  const int width_out =\n      (width + 2 * pad_w - (dilation_w * (kernel_w - 1) + 1)) / stride_w + 1;\n\n  // mask shape check\n  TORCH_CHECK(\n      (mask.size(2) == height_out && mask.size(3) == width_out),\n      \"invalid spatial size of mask, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      height_out,\n      width_out,\n      mask.size(2),\n      mask.size(3));\n\n  TORCH_CHECK(\n      (mask.size(1) == deformable_group * kernel_h * kernel_w),\n      \"invalid number of channels of mask\");\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < height_out * width_out) {\n    // Resize plane and fill with ones...\n    ones = at::ones({height_out, width_out}, input.options());\n  }\n\n  grad_input = grad_input.view({batch, channels, height, width});\n  columns = at::zeros(\n      {channels * kernel_h * kernel_w, height_out * width_out},\n      input.options());\n\n  grad_output = grad_output.view(\n      {grad_output.size(0),\n       group,\n       grad_output.size(1) / group,\n       grad_output.size(2),\n       grad_output.size(3)});\n\n  for (int b = 0; b < batch; b++) {\n    // divide int group\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      columns[g].addmm_(\n          weight[g].flatten(1).transpose(0, 1),\n          grad_output[b][g].flatten(1),\n          0.0f,\n          1.0f);\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    weight = weight.view(\n        {weight.size(0) * weight.size(1),\n         weight.size(2),\n         weight.size(3),\n         weight.size(4)});\n\n    // gradient w.r.t. input coordinate data\n    modulated_deformable_col2im_coord_cuda(\n        columns,\n        input[b],\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        grad_offset[b],\n        grad_mask[b]);\n    // gradient w.r.t. input data\n    modulated_deformable_col2im_cuda(\n        columns,\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        grad_input[b]);\n\n    // gradient w.r.t. weight, dWeight should accumulate across the batch and\n    // group\n    modulated_deformable_im2col_cuda(\n        input[b],\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        columns);\n\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    grad_weight = grad_weight.view(\n        {group,\n         grad_weight.size(0) / group,\n         grad_weight.size(1),\n         grad_weight.size(2),\n         grad_weight.size(3)});\n    if (with_bias)\n      grad_bias = grad_bias.view({group, grad_bias.size(0) / group});\n\n    for (int g = 0; g < group; g++) {\n      grad_weight[g] =\n          grad_weight[g]\n              .flatten(1)\n              .addmm_(grad_output[b][g].flatten(1), columns[g].transpose(0, 1))\n              .view_as(grad_weight[g]);\n      if (with_bias) {\n        grad_bias[g] =\n            grad_bias[g]\n                .view({-1, 1})\n                .addmm_(grad_output[b][g].flatten(1), ones.view({-1, 1}))\n                .view(-1);\n      }\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    grad_weight = grad_weight.view(\n        {grad_weight.size(0) * grad_weight.size(1),\n         grad_weight.size(2),\n         grad_weight.size(3),\n         grad_weight.size(4)});\n    if (with_bias)\n      grad_bias = grad_bias.view({grad_bias.size(0) * grad_bias.size(1)});\n  }\n  grad_output = grad_output.view(\n      {grad_output.size(0) * grad_output.size(1),\n       grad_output.size(2),\n       grad_output.size(3),\n       grad_output.size(4)});\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/deformable/deform_conv_cuda_kernel.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n// modified from\n// https://github.com/open-mmlab/mmdetection/blob/master/mmdet/ops/dcn/src/deform_conv_cuda_kernel.cu\n// Original license: Apache 2.0\n// clang-format off\n\n// modify from\n// https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/blob/mmdetection/mmdet/ops/dcn/src/deform_conv_cuda_kernel.cu\n\n/*!\n ******************* BEGIN Caffe Copyright Notice and Disclaimer *****************\n *\n * COPYRIGHT\n *\n * All contributions by the University of California:\n * Copyright (c) 2014-2017 The Regents of the University of California (Regents)\n * All rights reserved.\n *\n * All other contributions:\n * Copyright (c) 2014-2017, the respective contributors\n * All rights reserved.\n *\n * Caffe uses a shared copyright model: each contributor holds copyright over\n * their contributions to Caffe. The project versioning records all such\n * contribution and copyright details. If a contributor wants to further mark\n * their specific copyright on a particular contribution, they should indicate\n * their copyright solely in the commit message of the change when it is\n * committed.\n *\n * LICENSE\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n * 1. Redistributions of source code must retain the above copyright notice, this\n * list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above copyright notice,\n * this list of conditions and the following disclaimer in the documentation\n * and/or other materials provided with the distribution.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n *AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n *IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE\n *FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\n *DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\n *SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\n *OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\n *OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n *\n * CONTRIBUTION AGREEMENT\n *\n * By contributing to the BVLC/caffe repository through pull-request, comment,\n * or otherwise, the contributor releases their content to the\n * license and copyright terms herein.\n *\n ***************** END Caffe Copyright Notice and Disclaimer *********************\n *\n * Copyright (c) 2018 Microsoft\n * Licensed under The MIT License [see LICENSE for details]\n * \\file modulated_deformable_im2col.cuh\n * \\brief Function definitions of converting an image to\n * column matrix based on kernel, padding, dilation, and offset.\n * These functions are mainly used in deformable convolution operators.\n * \\ref: https://arxiv.org/abs/1703.06211\n * \\author Yuwen Xiong, Haozhi Qi, Jifeng Dai, Xizhou Zhu, Han Hu, Dazhi Cheng\n */\n\n#include <ATen/ATen.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <float.h>\n#include <math.h>\n#include <stdio.h>\n#include <THC/THCAtomics.cuh>\n\nusing namespace at;\n\n#define CUDA_KERNEL_LOOP(i, n)                                 \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < (n); \\\n       i += blockDim.x * gridDim.x)\n\n\nnamespace {\n\nconst int CUDA_NUM_THREADS = 1024;\nconst int kMaxGridNum = 65535;\n\ninline int GET_BLOCKS(const int N) {\n  return std::min(kMaxGridNum, (N + CUDA_NUM_THREADS - 1) / CUDA_NUM_THREADS);\n}\n\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t deformable_im2col_bilinear(\n    const scalar_t* bottom_data,\n    const int data_width,\n    const int height,\n    const int width,\n    scalar_t h,\n    scalar_t w) {\n  int h_low = floor(h);\n  int w_low = floor(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  scalar_t lh = h - h_low;\n  scalar_t lw = w - w_low;\n  scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0)\n    v1 = bottom_data[h_low * data_width + w_low];\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = bottom_data[h_low * data_width + w_high];\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = bottom_data[h_high * data_width + w_low];\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = bottom_data[h_high * data_width + w_high];\n\n  scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t get_gradient_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int h,\n    const int w,\n    const int height,\n    const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t get_coordinate_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int height,\n    const int width,\n    const scalar_t* im_data,\n    const int data_width,\n    const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__global__ void deformable_im2col_gpu_kernel(\n    const int n,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int num_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* data_col) {\n  CUDA_KERNEL_LOOP(index, n) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n    scalar_t* data_col_ptr = data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    // const scalar_t* data_im_ptr = data_im + ((b_col * num_channels + c_im) *\n    // height + h_in) * width + w_in;\n    const scalar_t* data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b_col * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n        const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n        scalar_t val = static_cast<scalar_t>(0);\n        const scalar_t h_im = h_in + i * dilation_h + offset_h;\n        const scalar_t w_im = w_in + j * dilation_w + offset_w;\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width) {\n          // const scalar_t map_h = i * dilation_h + offset_h;\n          // const scalar_t map_w = j * dilation_w + offset_w;\n          // const int cur_height = height - h_in;\n          // const int cur_width = width - w_in;\n          // val = deformable_im2col_bilinear(data_im_ptr, width, cur_height,\n          // cur_width, map_h, map_w);\n          val = deformable_im2col_bilinear(\n              data_im_ptr, width, height, width, h_im, w_im);\n        }\n        *data_col_ptr = val;\n        data_col_ptr += batch_size * height_col * width_col;\n      }\n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void deformable_col2im_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_im) {\n  CUDA_KERNEL_LOOP(index, n) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n    const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n    const scalar_t cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const scalar_t cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const scalar_t cur_top_grad = data_col[index];\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          scalar_t weight = get_gradient_weight(\n              cur_inv_h_data,\n              cur_inv_w_data,\n              cur_h + dy,\n              cur_w + dx,\n              height,\n              width);\n          atomicAdd(grad_im + cur_bottom_grad_pos, weight * cur_top_grad);\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void deformable_col2im_coord_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int offset_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_offset) {\n  CUDA_KERNEL_LOOP(index, n) {\n    scalar_t val = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const scalar_t* data_col_ptr = data_col +\n        deformable_group_index * channel_per_deformable_group * batch_size *\n            width_col * height_col;\n    const scalar_t* data_im_ptr = data_im +\n        (b * deformable_group + deformable_group_index) *\n            channel_per_deformable_group / kernel_h / kernel_w * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n      const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n      scalar_t inv_h = h_in + i * dilation_h + offset_h;\n      scalar_t inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width) {\n        inv_h = inv_w = -2;\n      }\n      const scalar_t weight = get_coordinate_weight(\n          inv_h,\n          inv_w,\n          height,\n          width,\n          data_im_ptr + cnt * height * width,\n          width,\n          bp_dir);\n      val += weight * data_col_ptr[col_pos];\n      cnt += 1;\n    }\n\n    grad_offset[index] = val;\n  }\n}\n\n\nnamespace detectron2 {\n\nvoid deformable_im2col(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor data_col) {\n  // num_axes should be smaller than block size\n  // todo: check parallel_imgs is correctly passed in\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = channels * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_im.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"deformable_im2col_gpu\", ([&] {\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n\n        deformable_im2col_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_im_,\n            data_offset_,\n            height,\n            width,\n            ksize_h,\n            ksize_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            parallel_imgs,\n            channels,\n            deformable_group,\n            height_col,\n            width_col,\n            data_col_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\"error in deformable_im2col: %s\\n\", cudaGetErrorString(err));\n  }\n}\n\n\nvoid deformable_col2im(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_im) {\n  // todo: make sure parallel_imgs is passed in correctly\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels =\n      channels * ksize_h * ksize_w * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t* grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        deformable_col2im_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_offset_,\n            channels,\n            height,\n            width,\n            ksize_h,\n            ksize_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            parallel_imgs,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_im_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\"error in deformable_col2im: %s\\n\", cudaGetErrorString(err));\n  }\n}\n\n\nvoid deformable_col2im_coord(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_offset) {\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = height_col * width_col * 2 * ksize_h * ksize_w *\n      deformable_group * parallel_imgs;\n  int channel_per_deformable_group =\n      channels * ksize_h * ksize_w / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_coord_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t* grad_offset_ = grad_offset.data_ptr<scalar_t>();\n\n        deformable_col2im_coord_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_im_,\n            data_offset_,\n            channels,\n            height,\n            width,\n            ksize_h,\n            ksize_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            parallel_imgs,\n            2 * ksize_h * ksize_w * deformable_group,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_offset_);\n      }));\n}\n\n} // namespace detectron2\n\n\ntemplate <typename scalar_t>\n__device__ scalar_t dmcn_im2col_bilinear(\n    const scalar_t* bottom_data,\n    const int data_width,\n    const int height,\n    const int width,\n    scalar_t h,\n    scalar_t w) {\n  int h_low = floor(h);\n  int w_low = floor(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  scalar_t lh = h - h_low;\n  scalar_t lw = w - w_low;\n  scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0)\n    v1 = bottom_data[h_low * data_width + w_low];\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = bottom_data[h_low * data_width + w_high];\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = bottom_data[h_high * data_width + w_low];\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = bottom_data[h_high * data_width + w_high];\n\n  scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t dmcn_get_gradient_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int h,\n    const int w,\n    const int height,\n    const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t dmcn_get_coordinate_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int height,\n    const int width,\n    const scalar_t* im_data,\n    const int data_width,\n    const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__global__ void modulated_deformable_im2col_gpu_kernel(\n    const int n,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const scalar_t* data_mask,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int num_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* data_col) {\n  CUDA_KERNEL_LOOP(index, n) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n\n    scalar_t* data_col_ptr = data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    // const float* data_im_ptr = data_im + ((b_col * num_channels + c_im) *\n    // height + h_in) * width + w_in;\n    const scalar_t* data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b_col * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n\n    const scalar_t* data_mask_ptr = data_mask +\n        (b_col * deformable_group + deformable_group_index) * kernel_h *\n            kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const int data_mask_hw_ptr =\n            ((i * kernel_w + j) * height_col + h_col) * width_col + w_col;\n        const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n        const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n        const scalar_t mask = data_mask_ptr[data_mask_hw_ptr];\n        scalar_t val = static_cast<scalar_t>(0);\n        const scalar_t h_im = h_in + i * dilation_h + offset_h;\n        const scalar_t w_im = w_in + j * dilation_w + offset_w;\n        // if (h_im >= 0 && w_im >= 0 && h_im < height && w_im < width) {\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width) {\n          // const float map_h = i * dilation_h + offset_h;\n          // const float map_w = j * dilation_w + offset_w;\n          // const int cur_height = height - h_in;\n          // const int cur_width = width - w_in;\n          // val = dmcn_im2col_bilinear(data_im_ptr, width, cur_height,\n          // cur_width, map_h, map_w);\n          val = dmcn_im2col_bilinear(\n              data_im_ptr, width, height, width, h_im, w_im);\n        }\n        *data_col_ptr = val * mask;\n        data_col_ptr += batch_size * height_col * width_col;\n        // data_col_ptr += height_col * width_col;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void modulated_deformable_col2im_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_offset,\n    const scalar_t* data_mask,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_im) {\n  CUDA_KERNEL_LOOP(index, n) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n    const scalar_t* data_mask_ptr = data_mask +\n        (b * deformable_group + deformable_group_index) * kernel_h * kernel_w *\n            height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const int data_mask_hw_ptr =\n        ((i * kernel_w + j) * height_col + h_out) * width_col + w_out;\n    const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n    const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n    const scalar_t mask = data_mask_ptr[data_mask_hw_ptr];\n    const scalar_t cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const scalar_t cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const scalar_t cur_top_grad = data_col[index] * mask;\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          scalar_t weight = dmcn_get_gradient_weight(\n              cur_inv_h_data,\n              cur_inv_w_data,\n              cur_h + dy,\n              cur_w + dx,\n              height,\n              width);\n          atomicAdd(grad_im + cur_bottom_grad_pos, weight * cur_top_grad);\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void modulated_deformable_col2im_coord_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const scalar_t* data_mask,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int offset_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_offset,\n    scalar_t* grad_mask) {\n  CUDA_KERNEL_LOOP(index, n) {\n    scalar_t val = 0, mval = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const scalar_t* data_col_ptr = data_col +\n        deformable_group_index * channel_per_deformable_group * batch_size *\n            width_col * height_col;\n    const scalar_t* data_im_ptr = data_im +\n        (b * deformable_group + deformable_group_index) *\n            channel_per_deformable_group / kernel_h / kernel_w * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n    const scalar_t* data_mask_ptr = data_mask +\n        (b * deformable_group + deformable_group_index) * kernel_h * kernel_w *\n            height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const int data_mask_hw_ptr =\n          (((i * kernel_w + j) * height_col + h_out) * width_col + w_out);\n      const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n      const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n      const scalar_t mask = data_mask_ptr[data_mask_hw_ptr];\n      scalar_t inv_h = h_in + i * dilation_h + offset_h;\n      scalar_t inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width) {\n        inv_h = inv_w = -2;\n      } else {\n        mval += data_col_ptr[col_pos] *\n            dmcn_im2col_bilinear(\n                    data_im_ptr + cnt * height * width,\n                    width,\n                    height,\n                    width,\n                    inv_h,\n                    inv_w);\n      }\n      const scalar_t weight = dmcn_get_coordinate_weight(\n          inv_h,\n          inv_w,\n          height,\n          width,\n          data_im_ptr + cnt * height * width,\n          width,\n          bp_dir);\n      val += weight * data_col_ptr[col_pos] * mask;\n      cnt += 1;\n    }\n    // KERNEL_ASSIGN(grad_offset[index], offset_req, val);\n    grad_offset[index] = val;\n    if (offset_c % 2 == 0)\n      // KERNEL_ASSIGN(grad_mask[(((b * deformable_group +\n      // deformable_group_index) * kernel_h * kernel_w + offset_c / 2) *\n      // height_col + h) * width_col + w], mask_req, mval);\n      grad_mask\n          [(((b * deformable_group + deformable_group_index) * kernel_h *\n                 kernel_w +\n             offset_c / 2) *\n                height_col +\n            h) *\n               width_col +\n           w] = mval;\n  }\n}\n\n\nnamespace detectron2 {\n\nvoid modulated_deformable_im2col_cuda(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor data_col) {\n  // num_axes should be smaller than block size\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels = channels * batch_size * height_col * width_col;\n\n  at::cuda::CUDAGuard device_guard(data_im.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"modulated_deformable_im2col_gpu\", ([&] {\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t* data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n\n        modulated_deformable_im2col_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_im_,\n            data_offset_,\n            data_mask_,\n            height_im,\n            width_im,\n            kernel_h,\n            kenerl_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            batch_size,\n            channels,\n            deformable_group,\n            height_col,\n            width_col,\n            data_col_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\n        \"error in modulated_deformable_im2col_cuda: %s\\n\",\n        cudaGetErrorString(err));\n  }\n}\n\nvoid modulated_deformable_col2im_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_im) {\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels =\n      channels * kernel_h * kernel_w * batch_size * height_col * width_col;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t* data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t* grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_offset_,\n            data_mask_,\n            channels,\n            height_im,\n            width_im,\n            kernel_h,\n            kernel_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            batch_size,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_im_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\n        \"error in modulated_deformable_col2im_cuda: %s\\n\",\n        cudaGetErrorString(err));\n  }\n}\n\nvoid modulated_deformable_col2im_coord_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask) {\n  const int num_kernels = batch_size * height_col * width_col * 2 * kernel_h *\n      kernel_w * deformable_group;\n  const int channel_per_deformable_group =\n      channels * kernel_h * kernel_w / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_coord_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t* data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t* grad_offset_ = grad_offset.data_ptr<scalar_t>();\n        scalar_t* grad_mask_ = grad_mask.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_coord_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_im_,\n            data_offset_,\n            data_mask_,\n            channels,\n            height_im,\n            width_im,\n            kernel_h,\n            kernel_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            batch_size,\n            2 * kernel_h * kernel_w * deformable_group,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_offset_,\n            grad_mask_);\n      }));\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\n        \"error in modulated_deformable_col2im_coord_cuda: %s\\n\",\n        cudaGetErrorString(err));\n  }\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/nms_rotated/nms_rotated.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\nat::Tensor nms_rotated_cpu(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold);\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor nms_rotated_cuda(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold);\n#endif\n\n// Interface for Python\n// inline is needed to prevent multiple function definitions when this header is\n// included by different cpps\ninline at::Tensor nms_rotated(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold) {\n  assert(dets.device().is_cuda() == scores.device().is_cuda());\n  if (dets.device().is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return nms_rotated_cuda(\n        dets.contiguous(), scores.contiguous(), iou_threshold);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n\n  return nms_rotated_cpu(dets.contiguous(), scores.contiguous(), iou_threshold);\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/nms_rotated/nms_rotated_cpu.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include \"../box_iou_rotated/box_iou_rotated_utils.h\"\n#include \"nms_rotated.h\"\n\nnamespace detectron2 {\n\ntemplate <typename scalar_t>\nat::Tensor nms_rotated_cpu_kernel(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold) {\n  // nms_rotated_cpu_kernel is modified from torchvision's nms_cpu_kernel,\n  // however, the code in this function is much shorter because\n  // we delegate the IoU computation for rotated boxes to\n  // the single_box_iou_rotated function in box_iou_rotated_utils.h\n  AT_ASSERTM(dets.device().is_cpu(), \"dets must be a CPU tensor\");\n  AT_ASSERTM(scores.device().is_cpu(), \"scores must be a CPU tensor\");\n  AT_ASSERTM(\n      dets.scalar_type() == scores.scalar_type(),\n      \"dets should have the same type as scores\");\n\n  if (dets.numel() == 0) {\n    return at::empty({0}, dets.options().dtype(at::kLong));\n  }\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n\n  auto ndets = dets.size(0);\n  at::Tensor suppressed_t = at::zeros({ndets}, dets.options().dtype(at::kByte));\n  at::Tensor keep_t = at::zeros({ndets}, dets.options().dtype(at::kLong));\n\n  auto suppressed = suppressed_t.data_ptr<uint8_t>();\n  auto keep = keep_t.data_ptr<int64_t>();\n  auto order = order_t.data_ptr<int64_t>();\n\n  int64_t num_to_keep = 0;\n\n  for (int64_t _i = 0; _i < ndets; _i++) {\n    auto i = order[_i];\n    if (suppressed[i] == 1) {\n      continue;\n    }\n\n    keep[num_to_keep++] = i;\n\n    for (int64_t _j = _i + 1; _j < ndets; _j++) {\n      auto j = order[_j];\n      if (suppressed[j] == 1) {\n        continue;\n      }\n\n      auto ovr = single_box_iou_rotated<scalar_t>(\n          dets[i].data_ptr<scalar_t>(), dets[j].data_ptr<scalar_t>());\n      if (ovr >= iou_threshold) {\n        suppressed[j] = 1;\n      }\n    }\n  }\n  return keep_t.narrow(/*dim=*/0, /*start=*/0, /*length=*/num_to_keep);\n}\n\nat::Tensor nms_rotated_cpu(\n    // input must be contiguous\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold) {\n  auto result = at::empty({0}, dets.options());\n\n  AT_DISPATCH_FLOATING_TYPES(dets.scalar_type(), \"nms_rotated\", [&] {\n    result = nms_rotated_cpu_kernel<scalar_t>(dets, scores, iou_threshold);\n  });\n  return result;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/nms_rotated/nms_rotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n#ifdef WITH_CUDA\n#include \"../box_iou_rotated/box_iou_rotated_utils.h\"\n#endif\n// TODO avoid this when pytorch supports \"same directory\" hipification\n#ifdef WITH_HIP\n#include \"box_iou_rotated/box_iou_rotated_utils.h\"\n#endif\n\nusing namespace detectron2;\n\nnamespace {\nint const threadsPerBlock = sizeof(unsigned long long) * 8;\n}\n\ntemplate <typename T>\n__global__ void nms_rotated_cuda_kernel(\n    const int n_boxes,\n    const double iou_threshold,\n    const T* dev_boxes,\n    unsigned long long* dev_mask) {\n  // nms_rotated_cuda_kernel is modified from torchvision's nms_cuda_kernel\n\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n\n  // if (row_start > col_start) return;\n\n  const int row_size =\n      min(n_boxes - row_start * threadsPerBlock, threadsPerBlock);\n  const int col_size =\n      min(n_boxes - col_start * threadsPerBlock, threadsPerBlock);\n\n  // Compared to nms_cuda_kernel, where each box is represented with 4 values\n  // (x1, y1, x2, y2), each rotated box is represented with 5 values\n  // (x_center, y_center, width, height, angle_degrees) here.\n  __shared__ T block_boxes[threadsPerBlock * 5];\n  if (threadIdx.x < col_size) {\n    block_boxes[threadIdx.x * 5 + 0] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 0];\n    block_boxes[threadIdx.x * 5 + 1] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 1];\n    block_boxes[threadIdx.x * 5 + 2] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 2];\n    block_boxes[threadIdx.x * 5 + 3] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 3];\n    block_boxes[threadIdx.x * 5 + 4] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size) {\n    const int cur_box_idx = threadsPerBlock * row_start + threadIdx.x;\n    const T* cur_box = dev_boxes + cur_box_idx * 5;\n    int i = 0;\n    unsigned long long t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = threadIdx.x + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      // Instead of devIoU used by original horizontal nms, here\n      // we use the single_box_iou_rotated function from box_iou_rotated_utils.h\n      if (single_box_iou_rotated<T>(cur_box, block_boxes + i * 5) >\n          iou_threshold) {\n        t |= 1ULL << i;\n      }\n    }\n    const int col_blocks = at::cuda::ATenCeilDiv(n_boxes, threadsPerBlock);\n    dev_mask[cur_box_idx * col_blocks + col_start] = t;\n  }\n}\n\nnamespace detectron2 {\n\nat::Tensor nms_rotated_cuda(\n    // input must be contiguous\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    double iou_threshold) {\n  // using scalar_t = float;\n  AT_ASSERTM(dets.is_cuda(), \"dets must be a CUDA tensor\");\n  AT_ASSERTM(scores.is_cuda(), \"scores must be a CUDA tensor\");\n  at::cuda::CUDAGuard device_guard(dets.device());\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n  auto dets_sorted = dets.index_select(0, order_t);\n\n  auto dets_num = dets.size(0);\n\n  const int col_blocks =\n      at::cuda::ATenCeilDiv(static_cast<int>(dets_num), threadsPerBlock);\n\n  at::Tensor mask =\n      at::empty({dets_num * col_blocks}, dets.options().dtype(at::kLong));\n\n  dim3 blocks(col_blocks, col_blocks);\n  dim3 threads(threadsPerBlock);\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES(\n      dets_sorted.scalar_type(), \"nms_rotated_kernel_cuda\", [&] {\n        nms_rotated_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n            dets_num,\n            iou_threshold,\n            dets_sorted.data_ptr<scalar_t>(),\n            (unsigned long long*)mask.data_ptr<int64_t>());\n      });\n\n  at::Tensor mask_cpu = mask.to(at::kCPU);\n  unsigned long long* mask_host =\n      (unsigned long long*)mask_cpu.data_ptr<int64_t>();\n\n  std::vector<unsigned long long> remv(col_blocks);\n  memset(&remv[0], 0, sizeof(unsigned long long) * col_blocks);\n\n  at::Tensor keep =\n      at::empty({dets_num}, dets.options().dtype(at::kLong).device(at::kCPU));\n  int64_t* keep_out = keep.data_ptr<int64_t>();\n\n  int num_to_keep = 0;\n  for (int i = 0; i < dets_num; i++) {\n    int nblock = i / threadsPerBlock;\n    int inblock = i % threadsPerBlock;\n\n    if (!(remv[nblock] & (1ULL << inblock))) {\n      keep_out[num_to_keep++] = i;\n      unsigned long long* p = mask_host + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv[j] |= p[j];\n      }\n    }\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n  return order_t.index(\n      {keep.narrow(/*dim=*/0, /*start=*/0, /*length=*/num_to_keep)\n           .to(order_t.device(), keep.scalar_type())});\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/csrc/vision.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n#include <torch/extension.h>\n#include \"ROIAlignRotated/ROIAlignRotated.h\"\n#include \"box_iou_rotated/box_iou_rotated.h\"\n#include \"cocoeval/cocoeval.h\"\n#include \"deformable/deform_conv.h\"\n#include \"nms_rotated/nms_rotated.h\"\n\nnamespace detectron2 {\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nextern int get_cudart_version();\n#endif\n\nstd::string get_cuda_version() {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n  std::ostringstream oss;\n\n#if defined(WITH_CUDA)\n  oss << \"CUDA \";\n#else\n  oss << \"HIP \";\n#endif\n\n  // copied from\n  // https://github.com/pytorch/pytorch/blob/master/aten/src/ATen/cuda/detail/CUDAHooks.cpp#L231\n  auto printCudaStyleVersion = [&](int v) {\n    oss << (v / 1000) << \".\" << (v / 10 % 100);\n    if (v % 10 != 0) {\n      oss << \".\" << (v % 10);\n    }\n  };\n  printCudaStyleVersion(get_cudart_version());\n  return oss.str();\n#else // neither CUDA nor HIP\n  return std::string(\"not available\");\n#endif\n}\n\nbool has_cuda() {\n#if defined(WITH_CUDA)\n  return true;\n#else\n  return false;\n#endif\n}\n\n// similar to\n// https://github.com/pytorch/pytorch/blob/master/aten/src/ATen/Version.cpp\nstd::string get_compiler_version() {\n  std::ostringstream ss;\n#if defined(__GNUC__)\n#ifndef __clang__\n\n#if ((__GNUC__ <= 4) && (__GNUC_MINOR__ <= 8))\n#error \"GCC >= 4.9 is required!\"\n#endif\n\n  { ss << \"GCC \" << __GNUC__ << \".\" << __GNUC_MINOR__; }\n#endif\n#endif\n\n#if defined(__clang_major__)\n  {\n    ss << \"clang \" << __clang_major__ << \".\" << __clang_minor__ << \".\"\n       << __clang_patchlevel__;\n  }\n#endif\n\n#if defined(_MSC_VER)\n  { ss << \"MSVC \" << _MSC_FULL_VER; }\n#endif\n  return ss.str();\n}\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"get_compiler_version\", &get_compiler_version, \"get_compiler_version\");\n  m.def(\"get_cuda_version\", &get_cuda_version, \"get_cuda_version\");\n  m.def(\"has_cuda\", &has_cuda, \"has_cuda\");\n\n  m.def(\"deform_conv_forward\", &deform_conv_forward, \"deform_conv_forward\");\n  m.def(\n      \"deform_conv_backward_input\",\n      &deform_conv_backward_input,\n      \"deform_conv_backward_input\");\n  m.def(\n      \"deform_conv_backward_filter\",\n      &deform_conv_backward_filter,\n      \"deform_conv_backward_filter\");\n  m.def(\n      \"modulated_deform_conv_forward\",\n      &modulated_deform_conv_forward,\n      \"modulated_deform_conv_forward\");\n  m.def(\n      \"modulated_deform_conv_backward\",\n      &modulated_deform_conv_backward,\n      \"modulated_deform_conv_backward\");\n\n  m.def(\"COCOevalAccumulate\", &COCOeval::Accumulate, \"COCOeval::Accumulate\");\n  m.def(\n      \"COCOevalEvaluateImages\",\n      &COCOeval::EvaluateImages,\n      \"COCOeval::EvaluateImages\");\n  pybind11::class_<COCOeval::InstanceAnnotation>(m, \"InstanceAnnotation\")\n      .def(pybind11::init<uint64_t, double, double, bool, bool>());\n  pybind11::class_<COCOeval::ImageEvaluation>(m, \"ImageEvaluation\")\n      .def(pybind11::init<>());\n}\n\nTORCH_LIBRARY(detectron2, m) {\n  m.def(\"nms_rotated\", &nms_rotated);\n  m.def(\"box_iou_rotated\", &box_iou_rotated);\n  m.def(\"roi_align_rotated_forward\", &ROIAlignRotated_forward);\n  m.def(\"roi_align_rotated_backward\", &ROIAlignRotated_backward);\n}\n} // namespace detectron2\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/deform_conv.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom functools import lru_cache\nimport torch\nfrom torch import nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair\nfrom torchvision.ops import deform_conv2d\n\nfrom detectron2.utils.develop import create_dummy_class, create_dummy_func\n\nfrom .wrappers import _NewEmptyTensorOp\n\n\nclass _DeformConv(Function):\n    @staticmethod\n    def forward(\n        ctx,\n        input,\n        offset,\n        weight,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n        im2col_step=64,\n    ):\n        if input is not None and input.dim() != 4:\n            raise ValueError(\n                \"Expected 4D tensor as input, got {}D tensor instead.\".format(input.dim())\n            )\n        ctx.stride = _pair(stride)\n        ctx.padding = _pair(padding)\n        ctx.dilation = _pair(dilation)\n        ctx.groups = groups\n        ctx.deformable_groups = deformable_groups\n        ctx.im2col_step = im2col_step\n\n        ctx.save_for_backward(input, offset, weight)\n\n        output = input.new_empty(\n            _DeformConv._output_size(input, weight, ctx.padding, ctx.dilation, ctx.stride)\n        )\n\n        ctx.bufs_ = [input.new_empty(0), input.new_empty(0)]  # columns, ones\n\n        if not input.is_cuda:\n            # TODO: let torchvision support full features of our deformconv.\n            if deformable_groups != 1:\n                raise NotImplementedError(\n                    \"Deformable Conv with deformable_groups != 1 is not supported on CPUs!\"\n                )\n            return deform_conv2d(\n                input, offset, weight, stride=stride, padding=padding, dilation=dilation\n            )\n        else:\n            cur_im2col_step = _DeformConv._cal_im2col_step(input.shape[0], ctx.im2col_step)\n            assert (input.shape[0] % cur_im2col_step) == 0, \"im2col step must divide batchsize\"\n\n            _C.deform_conv_forward(\n                input,\n                weight,\n                offset,\n                output,\n                ctx.bufs_[0],\n                ctx.bufs_[1],\n                weight.size(3),\n                weight.size(2),\n                ctx.stride[1],\n                ctx.stride[0],\n                ctx.padding[1],\n                ctx.padding[0],\n                ctx.dilation[1],\n                ctx.dilation[0],\n                ctx.groups,\n                ctx.deformable_groups,\n                cur_im2col_step,\n            )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        input, offset, weight = ctx.saved_tensors\n\n        grad_input = grad_offset = grad_weight = None\n\n        if not grad_output.is_cuda:\n            raise NotImplementedError(\"Deformable Conv is not supported on CPUs!\")\n        else:\n            cur_im2col_step = _DeformConv._cal_im2col_step(input.shape[0], ctx.im2col_step)\n            assert (input.shape[0] % cur_im2col_step) == 0, \"im2col step must divide batchsize\"\n\n            if ctx.needs_input_grad[0] or ctx.needs_input_grad[1]:\n                grad_input = torch.zeros_like(input)\n                grad_offset = torch.zeros_like(offset)\n                _C.deform_conv_backward_input(\n                    input,\n                    offset,\n                    grad_output,\n                    grad_input,\n                    grad_offset,\n                    weight,\n                    ctx.bufs_[0],\n                    weight.size(3),\n                    weight.size(2),\n                    ctx.stride[1],\n                    ctx.stride[0],\n                    ctx.padding[1],\n                    ctx.padding[0],\n                    ctx.dilation[1],\n                    ctx.dilation[0],\n                    ctx.groups,\n                    ctx.deformable_groups,\n                    cur_im2col_step,\n                )\n\n            if ctx.needs_input_grad[2]:\n                grad_weight = torch.zeros_like(weight)\n                _C.deform_conv_backward_filter(\n                    input,\n                    offset,\n                    grad_output,\n                    grad_weight,\n                    ctx.bufs_[0],\n                    ctx.bufs_[1],\n                    weight.size(3),\n                    weight.size(2),\n                    ctx.stride[1],\n                    ctx.stride[0],\n                    ctx.padding[1],\n                    ctx.padding[0],\n                    ctx.dilation[1],\n                    ctx.dilation[0],\n                    ctx.groups,\n                    ctx.deformable_groups,\n                    1,\n                    cur_im2col_step,\n                )\n\n        return grad_input, grad_offset, grad_weight, None, None, None, None, None, None\n\n    @staticmethod\n    def _output_size(input, weight, padding, dilation, stride):\n        channels = weight.size(0)\n        output_size = (input.size(0), channels)\n        for d in range(input.dim() - 2):\n            in_size = input.size(d + 2)\n            pad = padding[d]\n            kernel = dilation[d] * (weight.size(d + 2) - 1) + 1\n            stride_ = stride[d]\n            output_size += ((in_size + (2 * pad) - kernel) // stride_ + 1,)\n        if not all(map(lambda s: s > 0, output_size)):\n            raise ValueError(\n                \"convolution input is too small (output would be {})\".format(\n                    \"x\".join(map(str, output_size))\n                )\n            )\n        return output_size\n\n    @staticmethod\n    @lru_cache(maxsize=128)\n    def _cal_im2col_step(input_size, default_size):\n        \"\"\"\n        Calculate proper im2col step size, which should be divisible by input_size and not larger\n        than prefer_size. Meanwhile the step size should be as large as possible to be more\n        efficient. So we choose the largest one among all divisors of input_size which are smaller\n        than prefer_size.\n        :param input_size: input batch size .\n        :param default_size: default preferred im2col step size.\n        :return: the largest proper step size.\n        \"\"\"\n        if input_size <= default_size:\n            return input_size\n        best_step = 1\n        for step in range(2, min(int(math.sqrt(input_size)) + 1, default_size)):\n            if input_size % step == 0:\n                if input_size // step <= default_size:\n                    return input_size // step\n                best_step = step\n\n        return best_step\n\n\nclass _ModulatedDeformConv(Function):\n    @staticmethod\n    def forward(\n        ctx,\n        input,\n        offset,\n        mask,\n        weight,\n        bias=None,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n    ):\n        ctx.stride = stride\n        ctx.padding = padding\n        ctx.dilation = dilation\n        ctx.groups = groups\n        ctx.deformable_groups = deformable_groups\n        ctx.with_bias = bias is not None\n        if not ctx.with_bias:\n            bias = input.new_empty(1)  # fake tensor\n        if not input.is_cuda:\n            raise NotImplementedError(\"Deformable Conv is not supported on CPUs!\")\n        if (\n            weight.requires_grad\n            or mask.requires_grad\n            or offset.requires_grad\n            or input.requires_grad\n        ):\n            ctx.save_for_backward(input, offset, mask, weight, bias)\n        output = input.new_empty(_ModulatedDeformConv._infer_shape(ctx, input, weight))\n        ctx._bufs = [input.new_empty(0), input.new_empty(0)]\n        _C.modulated_deform_conv_forward(\n            input,\n            weight,\n            bias,\n            ctx._bufs[0],\n            offset,\n            mask,\n            output,\n            ctx._bufs[1],\n            weight.shape[2],\n            weight.shape[3],\n            ctx.stride,\n            ctx.stride,\n            ctx.padding,\n            ctx.padding,\n            ctx.dilation,\n            ctx.dilation,\n            ctx.groups,\n            ctx.deformable_groups,\n            ctx.with_bias,\n        )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        if not grad_output.is_cuda:\n            raise NotImplementedError(\"Deformable Conv is not supported on CPUs!\")\n        input, offset, mask, weight, bias = ctx.saved_tensors\n        grad_input = torch.zeros_like(input)\n        grad_offset = torch.zeros_like(offset)\n        grad_mask = torch.zeros_like(mask)\n        grad_weight = torch.zeros_like(weight)\n        grad_bias = torch.zeros_like(bias)\n        _C.modulated_deform_conv_backward(\n            input,\n            weight,\n            bias,\n            ctx._bufs[0],\n            offset,\n            mask,\n            ctx._bufs[1],\n            grad_input,\n            grad_weight,\n            grad_bias,\n            grad_offset,\n            grad_mask,\n            grad_output,\n            weight.shape[2],\n            weight.shape[3],\n            ctx.stride,\n            ctx.stride,\n            ctx.padding,\n            ctx.padding,\n            ctx.dilation,\n            ctx.dilation,\n            ctx.groups,\n            ctx.deformable_groups,\n            ctx.with_bias,\n        )\n        if not ctx.with_bias:\n            grad_bias = None\n\n        return (\n            grad_input,\n            grad_offset,\n            grad_mask,\n            grad_weight,\n            grad_bias,\n            None,\n            None,\n            None,\n            None,\n            None,\n        )\n\n    @staticmethod\n    def _infer_shape(ctx, input, weight):\n        n = input.size(0)\n        channels_out = weight.size(0)\n        height, width = input.shape[2:4]\n        kernel_h, kernel_w = weight.shape[2:4]\n        height_out = (\n            height + 2 * ctx.padding - (ctx.dilation * (kernel_h - 1) + 1)\n        ) // ctx.stride + 1\n        width_out = (\n            width + 2 * ctx.padding - (ctx.dilation * (kernel_w - 1) + 1)\n        ) // ctx.stride + 1\n        return n, channels_out, height_out, width_out\n\n\ndeform_conv = _DeformConv.apply\nmodulated_deform_conv = _ModulatedDeformConv.apply\n\n\nclass DeformConv(nn.Module):\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n        bias=False,\n        norm=None,\n        activation=None,\n    ):\n        \"\"\"\n        Deformable convolution from :paper:`deformconv`.\n\n        Arguments are similar to :class:`Conv2D`. Extra arguments:\n\n        Args:\n            deformable_groups (int): number of groups used in deformable convolution.\n            norm (nn.Module, optional): a normalization layer\n            activation (callable(Tensor) -> Tensor): a callable activation function\n        \"\"\"\n        super(DeformConv, self).__init__()\n\n        assert not bias\n        assert in_channels % groups == 0, \"in_channels {} cannot be divisible by groups {}\".format(\n            in_channels, groups\n        )\n        assert (\n            out_channels % groups == 0\n        ), \"out_channels {} cannot be divisible by groups {}\".format(out_channels, groups)\n\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.stride = _pair(stride)\n        self.padding = _pair(padding)\n        self.dilation = _pair(dilation)\n        self.groups = groups\n        self.deformable_groups = deformable_groups\n        self.norm = norm\n        self.activation = activation\n\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // self.groups, *self.kernel_size)\n        )\n        self.bias = None\n\n        nn.init.kaiming_uniform_(self.weight, nonlinearity=\"relu\")\n\n    def forward(self, x, offset):\n        if x.numel() == 0:\n            # When input is empty, we want to return a empty tensor with \"correct\" shape,\n            # So that the following operations will not panic\n            # if they check for the shape of the tensor.\n            # This computes the height and width of the output tensor\n            output_shape = [\n                (i + 2 * p - (di * (k - 1) + 1)) // s + 1\n                for i, p, di, k, s in zip(\n                    x.shape[-2:], self.padding, self.dilation, self.kernel_size, self.stride\n                )\n            ]\n            output_shape = [x.shape[0], self.weight.shape[0]] + output_shape\n            return _NewEmptyTensorOp.apply(x, output_shape)\n\n        x = deform_conv(\n            x,\n            offset,\n            self.weight,\n            self.stride,\n            self.padding,\n            self.dilation,\n            self.groups,\n            self.deformable_groups,\n        )\n        if self.norm is not None:\n            x = self.norm(x)\n        if self.activation is not None:\n            x = self.activation(x)\n        return x\n\n    def extra_repr(self):\n        tmpstr = \"in_channels=\" + str(self.in_channels)\n        tmpstr += \", out_channels=\" + str(self.out_channels)\n        tmpstr += \", kernel_size=\" + str(self.kernel_size)\n        tmpstr += \", stride=\" + str(self.stride)\n        tmpstr += \", padding=\" + str(self.padding)\n        tmpstr += \", dilation=\" + str(self.dilation)\n        tmpstr += \", groups=\" + str(self.groups)\n        tmpstr += \", deformable_groups=\" + str(self.deformable_groups)\n        tmpstr += \", bias=False\"\n        return tmpstr\n\n\nclass ModulatedDeformConv(nn.Module):\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n        bias=True,\n        norm=None,\n        activation=None,\n    ):\n        \"\"\"\n        Modulated deformable convolution from :paper:`deformconv2`.\n\n        Arguments are similar to :class:`Conv2D`. Extra arguments:\n\n        Args:\n            deformable_groups (int): number of groups used in deformable convolution.\n            norm (nn.Module, optional): a normalization layer\n            activation (callable(Tensor) -> Tensor): a callable activation function\n        \"\"\"\n        super(ModulatedDeformConv, self).__init__()\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.stride = stride\n        self.padding = padding\n        self.dilation = dilation\n        self.groups = groups\n        self.deformable_groups = deformable_groups\n        self.with_bias = bias\n        self.norm = norm\n        self.activation = activation\n\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // groups, *self.kernel_size)\n        )\n        if bias:\n            self.bias = nn.Parameter(torch.Tensor(out_channels))\n        else:\n            self.bias = None\n\n        nn.init.kaiming_uniform_(self.weight, nonlinearity=\"relu\")\n        if self.bias is not None:\n            nn.init.constant_(self.bias, 0)\n\n    def forward(self, x, offset, mask):\n        if x.numel() == 0:\n            output_shape = [\n                (i + 2 * p - (di * (k - 1) + 1)) // s + 1\n                for i, p, di, k, s in zip(\n                    x.shape[-2:], self.padding, self.dilation, self.kernel_size, self.stride\n                )\n            ]\n            output_shape = [x.shape[0], self.weight.shape[0]] + output_shape\n            return _NewEmptyTensorOp.apply(x, output_shape)\n\n        x = modulated_deform_conv(\n            x,\n            offset,\n            mask,\n            self.weight,\n            self.bias,\n            self.stride,\n            self.padding,\n            self.dilation,\n            self.groups,\n            self.deformable_groups,\n        )\n        if self.norm is not None:\n            x = self.norm(x)\n        if self.activation is not None:\n            x = self.activation(x)\n        return x\n\n    def extra_repr(self):\n        tmpstr = \"in_channels=\" + str(self.in_channels)\n        tmpstr += \", out_channels=\" + str(self.out_channels)\n        tmpstr += \", kernel_size=\" + str(self.kernel_size)\n        tmpstr += \", stride=\" + str(self.stride)\n        tmpstr += \", padding=\" + str(self.padding)\n        tmpstr += \", dilation=\" + str(self.dilation)\n        tmpstr += \", groups=\" + str(self.groups)\n        tmpstr += \", deformable_groups=\" + str(self.deformable_groups)\n        tmpstr += \", bias=\" + str(self.with_bias)\n        return tmpstr\n\n\ntry:\n    from detectron2 import _C\nexcept ImportError:\n    # TODO: register ops natively so there is no need to import _C.\n    _msg = \"detectron2 is not compiled successfully, please build following the instructions!\"\n    _args = (\"detectron2._C\", _msg)\n    DeformConv = create_dummy_class(\"DeformConv\", *_args)\n    ModulatedDeformConv = create_dummy_class(\"ModulatedDeformConv\", *_args)\n    deform_conv = create_dummy_func(\"deform_conv\", *_args)\n    modulated_deform_conv = create_dummy_func(\"modulated_deform_conv\", *_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/losses.py",
    "content": "import math\nimport torch\n\n\ndef diou_loss(\n    boxes1: torch.Tensor,\n    boxes2: torch.Tensor,\n    reduction: str = \"none\",\n    eps: float = 1e-7,\n) -> torch.Tensor:\n    \"\"\"\n    Distance Intersection over Union Loss (Zhaohui Zheng et. al)\n    https://arxiv.org/abs/1911.08287\n    Args:\n        boxes1, boxes2 (Tensor): box locations in XYXY format, shape (N, 4) or (4,).\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n        eps (float): small number to prevent division by zero\n    \"\"\"\n\n    x1, y1, x2, y2 = boxes1.unbind(dim=-1)\n    x1g, y1g, x2g, y2g = boxes2.unbind(dim=-1)\n\n    # TODO: use torch._assert_async() when pytorch 1.8 support is dropped\n    assert (x2 >= x1).all(), \"bad box: x1 larger than x2\"\n    assert (y2 >= y1).all(), \"bad box: y1 larger than y2\"\n\n    # Intersection keypoints\n    xkis1 = torch.max(x1, x1g)\n    ykis1 = torch.max(y1, y1g)\n    xkis2 = torch.min(x2, x2g)\n    ykis2 = torch.min(y2, y2g)\n\n    intsct = torch.zeros_like(x1)\n    mask = (ykis2 > ykis1) & (xkis2 > xkis1)\n    intsct[mask] = (xkis2[mask] - xkis1[mask]) * (ykis2[mask] - ykis1[mask])\n    union = (x2 - x1) * (y2 - y1) + (x2g - x1g) * (y2g - y1g) - intsct + eps\n    iou = intsct / union\n\n    # smallest enclosing box\n    xc1 = torch.min(x1, x1g)\n    yc1 = torch.min(y1, y1g)\n    xc2 = torch.max(x2, x2g)\n    yc2 = torch.max(y2, y2g)\n    diag_len = ((xc2 - xc1) ** 2) + ((yc2 - yc1) ** 2) + eps\n\n    # centers of boxes\n    x_p = (x2 + x1) / 2\n    y_p = (y2 + y1) / 2\n    x_g = (x1g + x2g) / 2\n    y_g = (y1g + y2g) / 2\n    distance = ((x_p - x_g) ** 2) + ((y_p - y_g) ** 2)\n\n    # Eqn. (7)\n    loss = 1 - iou + (distance / diag_len)\n    if reduction == \"mean\":\n        loss = loss.mean() if loss.numel() > 0 else 0.0 * loss.sum()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n\n    return loss\n\n\ndef ciou_loss(\n    boxes1: torch.Tensor,\n    boxes2: torch.Tensor,\n    reduction: str = \"none\",\n    eps: float = 1e-7,\n) -> torch.Tensor:\n    \"\"\"\n    Complete Intersection over Union Loss (Zhaohui Zheng et. al)\n    https://arxiv.org/abs/1911.08287\n    Args:\n        boxes1, boxes2 (Tensor): box locations in XYXY format, shape (N, 4) or (4,).\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n        eps (float): small number to prevent division by zero\n    \"\"\"\n\n    x1, y1, x2, y2 = boxes1.unbind(dim=-1)\n    x1g, y1g, x2g, y2g = boxes2.unbind(dim=-1)\n\n    # TODO: use torch._assert_async() when pytorch 1.8 support is dropped\n    assert (x2 >= x1).all(), \"bad box: x1 larger than x2\"\n    assert (y2 >= y1).all(), \"bad box: y1 larger than y2\"\n\n    # Intersection keypoints\n    xkis1 = torch.max(x1, x1g)\n    ykis1 = torch.max(y1, y1g)\n    xkis2 = torch.min(x2, x2g)\n    ykis2 = torch.min(y2, y2g)\n\n    intsct = torch.zeros_like(x1)\n    mask = (ykis2 > ykis1) & (xkis2 > xkis1)\n    intsct[mask] = (xkis2[mask] - xkis1[mask]) * (ykis2[mask] - ykis1[mask])\n    union = (x2 - x1) * (y2 - y1) + (x2g - x1g) * (y2g - y1g) - intsct + eps\n    iou = intsct / union\n\n    # smallest enclosing box\n    xc1 = torch.min(x1, x1g)\n    yc1 = torch.min(y1, y1g)\n    xc2 = torch.max(x2, x2g)\n    yc2 = torch.max(y2, y2g)\n    diag_len = ((xc2 - xc1) ** 2) + ((yc2 - yc1) ** 2) + eps\n\n    # centers of boxes\n    x_p = (x2 + x1) / 2\n    y_p = (y2 + y1) / 2\n    x_g = (x1g + x2g) / 2\n    y_g = (y1g + y2g) / 2\n    distance = ((x_p - x_g) ** 2) + ((y_p - y_g) ** 2)\n\n    # width and height of boxes\n    w_pred = x2 - x1\n    h_pred = y2 - y1\n    w_gt = x2g - x1g\n    h_gt = y2g - y1g\n    v = (4 / (math.pi**2)) * torch.pow((torch.atan(w_gt / h_gt) - torch.atan(w_pred / h_pred)), 2)\n    with torch.no_grad():\n        alpha = v / (1 - iou + v + eps)\n\n    # Eqn. (10)\n    loss = 1 - iou + (distance / diag_len) + alpha * v\n    if reduction == \"mean\":\n        loss = loss.mean() if loss.numel() > 0 else 0.0 * loss.sum()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n\n    return loss\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/mask_ops.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Tuple\nimport torch\nfrom PIL import Image\nfrom torch.nn import functional as F\n\n__all__ = [\"paste_masks_in_image\"]\n\n\nBYTES_PER_FLOAT = 4\n# TODO: This memory limit may be too much or too little. It would be better to\n# determine it based on available resources.\nGPU_MEM_LIMIT = 1024**3  # 1 GB memory limit\n\n\ndef _do_paste_mask(masks, boxes, img_h: int, img_w: int, skip_empty: bool = True):\n    \"\"\"\n    Args:\n        masks: N, 1, H, W\n        boxes: N, 4\n        img_h, img_w (int):\n        skip_empty (bool): only paste masks within the region that\n            tightly bound all boxes, and returns the results this region only.\n            An important optimization for CPU.\n\n    Returns:\n        if skip_empty == False, a mask of shape (N, img_h, img_w)\n        if skip_empty == True, a mask of shape (N, h', w'), and the slice\n            object for the corresponding region.\n    \"\"\"\n    # On GPU, paste all masks together (up to chunk size)\n    # by using the entire image to sample the masks\n    # Compared to pasting them one by one,\n    # this has more operations but is faster on COCO-scale dataset.\n    device = masks.device\n\n    if skip_empty and not torch.jit.is_scripting():\n        x0_int, y0_int = torch.clamp(boxes.min(dim=0).values.floor()[:2] - 1, min=0).to(\n            dtype=torch.int32\n        )\n        x1_int = torch.clamp(boxes[:, 2].max().ceil() + 1, max=img_w).to(dtype=torch.int32)\n        y1_int = torch.clamp(boxes[:, 3].max().ceil() + 1, max=img_h).to(dtype=torch.int32)\n    else:\n        x0_int, y0_int = 0, 0\n        x1_int, y1_int = img_w, img_h\n    x0, y0, x1, y1 = torch.split(boxes, 1, dim=1)  # each is Nx1\n\n    N = masks.shape[0]\n\n    img_y = torch.arange(y0_int, y1_int, device=device, dtype=torch.float32) + 0.5\n    img_x = torch.arange(x0_int, x1_int, device=device, dtype=torch.float32) + 0.5\n    img_y = (img_y - y0) / (y1 - y0) * 2 - 1\n    img_x = (img_x - x0) / (x1 - x0) * 2 - 1\n    # img_x, img_y have shapes (N, w), (N, h)\n\n    gx = img_x[:, None, :].expand(N, img_y.size(1), img_x.size(1))\n    gy = img_y[:, :, None].expand(N, img_y.size(1), img_x.size(1))\n    grid = torch.stack([gx, gy], dim=3)\n\n    if not torch.jit.is_scripting():\n        if not masks.dtype.is_floating_point:\n            masks = masks.float()\n    img_masks = F.grid_sample(masks, grid.to(masks.dtype), align_corners=False)\n\n    if skip_empty and not torch.jit.is_scripting():\n        return img_masks[:, 0], (slice(y0_int, y1_int), slice(x0_int, x1_int))\n    else:\n        return img_masks[:, 0], ()\n\n\n# Annotate boxes as Tensor (but not Boxes) in order to use scripting\n@torch.jit.script_if_tracing\ndef paste_masks_in_image(\n    masks: torch.Tensor, boxes: torch.Tensor, image_shape: Tuple[int, int], threshold: float = 0.5\n):\n    \"\"\"\n    Paste a set of masks that are of a fixed resolution (e.g., 28 x 28) into an image.\n    The location, height, and width for pasting each mask is determined by their\n    corresponding bounding boxes in boxes.\n\n    Note:\n        This is a complicated but more accurate implementation. In actual deployment, it is\n        often enough to use a faster but less accurate implementation.\n        See :func:`paste_mask_in_image_old` in this file for an alternative implementation.\n\n    Args:\n        masks (tensor): Tensor of shape (Bimg, Hmask, Wmask), where Bimg is the number of\n            detected object instances in the image and Hmask, Wmask are the mask width and mask\n            height of the predicted mask (e.g., Hmask = Wmask = 28). Values are in [0, 1].\n        boxes (Boxes or Tensor): A Boxes of length Bimg or Tensor of shape (Bimg, 4).\n            boxes[i] and masks[i] correspond to the same object instance.\n        image_shape (tuple): height, width\n        threshold (float): A threshold in [0, 1] for converting the (soft) masks to\n            binary masks.\n\n    Returns:\n        img_masks (Tensor): A tensor of shape (Bimg, Himage, Wimage), where Bimg is the\n        number of detected object instances and Himage, Wimage are the image width\n        and height. img_masks[i] is a binary mask for object instance i.\n    \"\"\"\n\n    assert masks.shape[-1] == masks.shape[-2], \"Only square mask predictions are supported\"\n    N = len(masks)\n    if N == 0:\n        return masks.new_empty((0,) + image_shape, dtype=torch.uint8)\n    if not isinstance(boxes, torch.Tensor):\n        boxes = boxes.tensor\n    device = boxes.device\n    assert len(boxes) == N, boxes.shape\n\n    img_h, img_w = image_shape\n\n    # The actual implementation split the input into chunks,\n    # and paste them chunk by chunk.\n    if device.type == \"cpu\" or torch.jit.is_scripting():\n        # CPU is most efficient when they are pasted one by one with skip_empty=True\n        # so that it performs minimal number of operations.\n        num_chunks = N\n    else:\n        # GPU benefits from parallelism for larger chunks, but may have memory issue\n        # int(img_h) because shape may be tensors in tracing\n        num_chunks = int(np.ceil(N * int(img_h) * int(img_w) * BYTES_PER_FLOAT / GPU_MEM_LIMIT))\n        assert (\n            num_chunks <= N\n        ), \"Default GPU_MEM_LIMIT in mask_ops.py is too small; try increasing it\"\n    chunks = torch.chunk(torch.arange(N, device=device), num_chunks)\n\n    img_masks = torch.zeros(\n        N, img_h, img_w, device=device, dtype=torch.bool if threshold >= 0 else torch.uint8\n    )\n    for inds in chunks:\n        masks_chunk, spatial_inds = _do_paste_mask(\n            masks[inds, None, :, :], boxes[inds], img_h, img_w, skip_empty=device.type == \"cpu\"\n        )\n\n        if threshold >= 0:\n            masks_chunk = (masks_chunk >= threshold).to(dtype=torch.bool)\n        else:\n            # for visualization and debugging\n            masks_chunk = (masks_chunk * 255).to(dtype=torch.uint8)\n\n        if torch.jit.is_scripting():  # Scripting does not use the optimized codepath\n            img_masks[inds] = masks_chunk\n        else:\n            img_masks[(inds,) + spatial_inds] = masks_chunk\n    return img_masks\n\n\n# The below are the original paste function (from Detectron1) which has\n# larger quantization error.\n# It is faster on CPU, while the aligned one is faster on GPU thanks to grid_sample.\n\n\ndef paste_mask_in_image_old(mask, box, img_h, img_w, threshold):\n    \"\"\"\n    Paste a single mask in an image.\n    This is a per-box implementation of :func:`paste_masks_in_image`.\n    This function has larger quantization error due to incorrect pixel\n    modeling and is not used any more.\n\n    Args:\n        mask (Tensor): A tensor of shape (Hmask, Wmask) storing the mask of a single\n            object instance. Values are in [0, 1].\n        box (Tensor): A tensor of shape (4, ) storing the x0, y0, x1, y1 box corners\n            of the object instance.\n        img_h, img_w (int): Image height and width.\n        threshold (float): Mask binarization threshold in [0, 1].\n\n    Returns:\n        im_mask (Tensor):\n            The resized and binarized object mask pasted into the original\n            image plane (a tensor of shape (img_h, img_w)).\n    \"\"\"\n    # Conversion from continuous box coordinates to discrete pixel coordinates\n    # via truncation (cast to int32). This determines which pixels to paste the\n    # mask onto.\n    box = box.to(dtype=torch.int32)  # Continuous to discrete coordinate conversion\n    # An example (1D) box with continuous coordinates (x0=0.7, x1=4.3) will map to\n    # a discrete coordinates (x0=0, x1=4). Note that box is mapped to 5 = x1 - x0 + 1\n    # pixels (not x1 - x0 pixels).\n    samples_w = box[2] - box[0] + 1  # Number of pixel samples, *not* geometric width\n    samples_h = box[3] - box[1] + 1  # Number of pixel samples, *not* geometric height\n\n    # Resample the mask from it's original grid to the new samples_w x samples_h grid\n    mask = Image.fromarray(mask.cpu().numpy())\n    mask = mask.resize((samples_w, samples_h), resample=Image.BILINEAR)\n    mask = np.array(mask, copy=False)\n\n    if threshold >= 0:\n        mask = np.array(mask > threshold, dtype=np.uint8)\n        mask = torch.from_numpy(mask)\n    else:\n        # for visualization and debugging, we also\n        # allow it to return an unmodified mask\n        mask = torch.from_numpy(mask * 255).to(torch.uint8)\n\n    im_mask = torch.zeros((img_h, img_w), dtype=torch.uint8)\n    x_0 = max(box[0], 0)\n    x_1 = min(box[2] + 1, img_w)\n    y_0 = max(box[1], 0)\n    y_1 = min(box[3] + 1, img_h)\n\n    im_mask[y_0:y_1, x_0:x_1] = mask[\n        (y_0 - box[1]) : (y_1 - box[1]), (x_0 - box[0]) : (x_1 - box[0])\n    ]\n    return im_mask\n\n\n# Our pixel modeling requires extrapolation for any continuous\n# coordinate < 0.5 or > length - 0.5. When sampling pixels on the masks,\n# we would like this extrapolation to be an interpolation between boundary values and zero,\n# instead of using absolute zero or boundary values.\n# Therefore `paste_mask_in_image_old` is often used with zero padding around the masks like this:\n# masks, scale = pad_masks(masks[:, 0, :, :], 1)\n# boxes = scale_boxes(boxes.tensor, scale)\n\n\ndef pad_masks(masks, padding):\n    \"\"\"\n    Args:\n        masks (tensor): A tensor of shape (B, M, M) representing B masks.\n        padding (int): Number of cells to pad on all sides.\n\n    Returns:\n        The padded masks and the scale factor of the padding size / original size.\n    \"\"\"\n    B = masks.shape[0]\n    M = masks.shape[-1]\n    pad2 = 2 * padding\n    scale = float(M + pad2) / M\n    padded_masks = masks.new_zeros((B, M + pad2, M + pad2))\n    padded_masks[:, padding:-padding, padding:-padding] = masks\n    return padded_masks, scale\n\n\ndef scale_boxes(boxes, scale):\n    \"\"\"\n    Args:\n        boxes (tensor): A tensor of shape (B, 4) representing B boxes with 4\n            coords representing the corners x0, y0, x1, y1,\n        scale (float): The box scaling factor.\n\n    Returns:\n        Scaled boxes.\n    \"\"\"\n    w_half = (boxes[:, 2] - boxes[:, 0]) * 0.5\n    h_half = (boxes[:, 3] - boxes[:, 1]) * 0.5\n    x_c = (boxes[:, 2] + boxes[:, 0]) * 0.5\n    y_c = (boxes[:, 3] + boxes[:, 1]) * 0.5\n\n    w_half *= scale\n    h_half *= scale\n\n    scaled_boxes = torch.zeros_like(boxes)\n    scaled_boxes[:, 0] = x_c - w_half\n    scaled_boxes[:, 2] = x_c + w_half\n    scaled_boxes[:, 1] = y_c - h_half\n    scaled_boxes[:, 3] = y_c + h_half\n    return scaled_boxes\n\n\n@torch.jit.script_if_tracing\ndef _paste_masks_tensor_shape(\n    masks: torch.Tensor,\n    boxes: torch.Tensor,\n    image_shape: Tuple[torch.Tensor, torch.Tensor],\n    threshold: float = 0.5,\n):\n    \"\"\"\n    A wrapper of paste_masks_in_image where image_shape is Tensor.\n    During tracing, shapes might be tensors instead of ints. The Tensor->int\n    conversion should be scripted rather than traced.\n    \"\"\"\n    return paste_masks_in_image(masks, boxes, (int(image_shape[0]), int(image_shape[1])), threshold)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/nms.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport torch\nfrom torchvision.ops import boxes as box_ops\nfrom torchvision.ops import nms  # noqa . for compatibility\n\n\ndef batched_nms(\n    boxes: torch.Tensor, scores: torch.Tensor, idxs: torch.Tensor, iou_threshold: float\n):\n    \"\"\"\n    Same as torchvision.ops.boxes.batched_nms, but with float().\n    \"\"\"\n    assert boxes.shape[-1] == 4\n    # Note: Torchvision already has a strategy (https://github.com/pytorch/vision/issues/1311)\n    # to decide whether to use coordinate trick or for loop to implement batched_nms. So we\n    # just call it directly.\n    # Fp16 does not have enough range for batched NMS, so adding float().\n    return box_ops.batched_nms(boxes.float(), scores, idxs, iou_threshold)\n\n\n# Note: this function (nms_rotated) might be moved into\n# torchvision/ops/boxes.py in the future\ndef nms_rotated(boxes: torch.Tensor, scores: torch.Tensor, iou_threshold: float):\n    \"\"\"\n    Performs non-maximum suppression (NMS) on the rotated boxes according\n    to their intersection-over-union (IoU).\n\n    Rotated NMS iteratively removes lower scoring rotated boxes which have an\n    IoU greater than iou_threshold with another (higher scoring) rotated box.\n\n    Note that RotatedBox (5, 3, 4, 2, -90) covers exactly the same region as\n    RotatedBox (5, 3, 4, 2, 90) does, and their IoU will be 1. However, they\n    can be representing completely different objects in certain tasks, e.g., OCR.\n\n    As for the question of whether rotated-NMS should treat them as faraway boxes\n    even though their IOU is 1, it depends on the application and/or ground truth annotation.\n\n    As an extreme example, consider a single character v and the square box around it.\n\n    If the angle is 0 degree, the object (text) would be read as 'v';\n\n    If the angle is 90 degrees, the object (text) would become '>';\n\n    If the angle is 180 degrees, the object (text) would become '^';\n\n    If the angle is 270/-90 degrees, the object (text) would become '<'\n\n    All of these cases have IoU of 1 to each other, and rotated NMS that only\n    uses IoU as criterion would only keep one of them with the highest score -\n    which, practically, still makes sense in most cases because typically\n    only one of theses orientations is the correct one. Also, it does not matter\n    as much if the box is only used to classify the object (instead of transcribing\n    them with a sequential OCR recognition model) later.\n\n    On the other hand, when we use IoU to filter proposals that are close to the\n    ground truth during training, we should definitely take the angle into account if\n    we know the ground truth is labeled with the strictly correct orientation (as in,\n    upside-down words are annotated with -180 degrees even though they can be covered\n    with a 0/90/-90 degree box, etc.)\n\n    The way the original dataset is annotated also matters. For example, if the dataset\n    is a 4-point polygon dataset that does not enforce ordering of vertices/orientation,\n    we can estimate a minimum rotated bounding box to this polygon, but there's no way\n    we can tell the correct angle with 100% confidence (as shown above, there could be 4 different\n    rotated boxes, with angles differed by 90 degrees to each other, covering the exactly\n    same region). In that case we have to just use IoU to determine the box\n    proximity (as many detection benchmarks (even for text) do) unless there're other\n    assumptions we can make (like width is always larger than height, or the object is not\n    rotated by more than 90 degrees CCW/CW, etc.)\n\n    In summary, not considering angles in rotated NMS seems to be a good option for now,\n    but we should be aware of its implications.\n\n    Args:\n        boxes (Tensor[N, 5]): Rotated boxes to perform NMS on. They are expected to be in\n           (x_center, y_center, width, height, angle_degrees) format.\n        scores (Tensor[N]): Scores for each one of the rotated boxes\n        iou_threshold (float): Discards all overlapping rotated boxes with IoU < iou_threshold\n\n    Returns:\n        keep (Tensor): int64 tensor with the indices of the elements that have been kept\n        by Rotated NMS, sorted in decreasing order of scores\n    \"\"\"\n    return torch.ops.detectron2.nms_rotated(boxes, scores, iou_threshold)\n\n\n# Note: this function (batched_nms_rotated) might be moved into\n# torchvision/ops/boxes.py in the future\n\n\n@torch.jit.script_if_tracing\ndef batched_nms_rotated(\n    boxes: torch.Tensor, scores: torch.Tensor, idxs: torch.Tensor, iou_threshold: float\n):\n    \"\"\"\n    Performs non-maximum suppression in a batched fashion.\n\n    Each index value correspond to a category, and NMS\n    will not be applied between elements of different categories.\n\n    Args:\n        boxes (Tensor[N, 5]):\n           boxes where NMS will be performed. They\n           are expected to be in (x_ctr, y_ctr, width, height, angle_degrees) format\n        scores (Tensor[N]):\n           scores for each one of the boxes\n        idxs (Tensor[N]):\n           indices of the categories for each one of the boxes.\n        iou_threshold (float):\n           discards all overlapping boxes\n           with IoU < iou_threshold\n\n    Returns:\n        Tensor:\n            int64 tensor with the indices of the elements that have been kept\n            by NMS, sorted in decreasing order of scores\n    \"\"\"\n    assert boxes.shape[-1] == 5\n\n    if boxes.numel() == 0:\n        return torch.empty((0,), dtype=torch.int64, device=boxes.device)\n    boxes = boxes.float()  # fp16 does not have enough range for batched NMS\n    # Strategy: in order to perform NMS independently per class,\n    # we add an offset to all the boxes. The offset is dependent\n    # only on the class idx, and is large enough so that boxes\n    # from different classes do not overlap\n\n    # Note that batched_nms in torchvision/ops/boxes.py only uses max_coordinate,\n    # which won't handle negative coordinates correctly.\n    # Here by using min_coordinate we can make sure the negative coordinates are\n    # correctly handled.\n    max_coordinate = (\n        torch.max(boxes[:, 0], boxes[:, 1]) + torch.max(boxes[:, 2], boxes[:, 3]) / 2\n    ).max()\n    min_coordinate = (\n        torch.min(boxes[:, 0], boxes[:, 1]) - torch.max(boxes[:, 2], boxes[:, 3]) / 2\n    ).min()\n    offsets = idxs.to(boxes) * (max_coordinate - min_coordinate + 1)\n    boxes_for_nms = boxes.clone()  # avoid modifying the original values in boxes\n    boxes_for_nms[:, :2] += offsets[:, None]\n    keep = nms_rotated(boxes_for_nms, scores, iou_threshold)\n    return keep\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/roi_align.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom torch import nn\nfrom torchvision.ops import roi_align\n\n\n# NOTE: torchvision's RoIAlign has a different default aligned=False\nclass ROIAlign(nn.Module):\n    def __init__(self, output_size, spatial_scale, sampling_ratio, aligned=True):\n        \"\"\"\n        Args:\n            output_size (tuple): h, w\n            spatial_scale (float): scale the input boxes by this number\n            sampling_ratio (int): number of inputs samples to take for each output\n                sample. 0 to take samples densely.\n            aligned (bool): if False, use the legacy implementation in\n                Detectron. If True, align the results more perfectly.\n\n        Note:\n            The meaning of aligned=True:\n\n            Given a continuous coordinate c, its two neighboring pixel indices (in our\n            pixel model) are computed by floor(c - 0.5) and ceil(c - 0.5). For example,\n            c=1.3 has pixel neighbors with discrete indices [0] and [1] (which are sampled\n            from the underlying signal at continuous coordinates 0.5 and 1.5). But the original\n            roi_align (aligned=False) does not subtract the 0.5 when computing neighboring\n            pixel indices and therefore it uses pixels with a slightly incorrect alignment\n            (relative to our pixel model) when performing bilinear interpolation.\n\n            With `aligned=True`,\n            we first appropriately scale the ROI and then shift it by -0.5\n            prior to calling roi_align. This produces the correct neighbors; see\n            detectron2/tests/test_roi_align.py for verification.\n\n            The difference does not make a difference to the model's performance if\n            ROIAlign is used together with conv layers.\n        \"\"\"\n        super().__init__()\n        self.output_size = output_size\n        self.spatial_scale = spatial_scale\n        self.sampling_ratio = sampling_ratio\n        self.aligned = aligned\n\n        from torchvision import __version__\n\n        version = tuple(int(x) for x in __version__.split(\".\")[:2])\n        # https://github.com/pytorch/vision/pull/2438\n        assert version >= (0, 7), \"Require torchvision >= 0.7\"\n\n    def forward(self, input, rois):\n        \"\"\"\n        Args:\n            input: NCHW images\n            rois: Bx5 boxes. First column is the index into N. The other 4 columns are xyxy.\n        \"\"\"\n        assert rois.dim() == 2 and rois.size(1) == 5\n        if input.is_quantized:\n            input = input.dequantize()\n        return roi_align(\n            input,\n            rois.to(dtype=input.dtype),\n            self.output_size,\n            self.spatial_scale,\n            self.sampling_ratio,\n            self.aligned,\n        )\n\n    def __repr__(self):\n        tmpstr = self.__class__.__name__ + \"(\"\n        tmpstr += \"output_size=\" + str(self.output_size)\n        tmpstr += \", spatial_scale=\" + str(self.spatial_scale)\n        tmpstr += \", sampling_ratio=\" + str(self.sampling_ratio)\n        tmpstr += \", aligned=\" + str(self.aligned)\n        tmpstr += \")\"\n        return tmpstr\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/roi_align_rotated.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nfrom torch import nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair\n\n\nclass _ROIAlignRotated(Function):\n    @staticmethod\n    def forward(ctx, input, roi, output_size, spatial_scale, sampling_ratio):\n        ctx.save_for_backward(roi)\n        ctx.output_size = _pair(output_size)\n        ctx.spatial_scale = spatial_scale\n        ctx.sampling_ratio = sampling_ratio\n        ctx.input_shape = input.size()\n        output = torch.ops.detectron2.roi_align_rotated_forward(\n            input, roi, spatial_scale, output_size[0], output_size[1], sampling_ratio\n        )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        (rois,) = ctx.saved_tensors\n        output_size = ctx.output_size\n        spatial_scale = ctx.spatial_scale\n        sampling_ratio = ctx.sampling_ratio\n        bs, ch, h, w = ctx.input_shape\n        grad_input = torch.ops.detectron2.roi_align_rotated_backward(\n            grad_output,\n            rois,\n            spatial_scale,\n            output_size[0],\n            output_size[1],\n            bs,\n            ch,\n            h,\n            w,\n            sampling_ratio,\n        )\n        return grad_input, None, None, None, None, None\n\n\nroi_align_rotated = _ROIAlignRotated.apply\n\n\nclass ROIAlignRotated(nn.Module):\n    def __init__(self, output_size, spatial_scale, sampling_ratio):\n        \"\"\"\n        Args:\n            output_size (tuple): h, w\n            spatial_scale (float): scale the input boxes by this number\n            sampling_ratio (int): number of inputs samples to take for each output\n                sample. 0 to take samples densely.\n\n        Note:\n            ROIAlignRotated supports continuous coordinate by default:\n            Given a continuous coordinate c, its two neighboring pixel indices (in our\n            pixel model) are computed by floor(c - 0.5) and ceil(c - 0.5). For example,\n            c=1.3 has pixel neighbors with discrete indices [0] and [1] (which are sampled\n            from the underlying signal at continuous coordinates 0.5 and 1.5).\n        \"\"\"\n        super(ROIAlignRotated, self).__init__()\n        self.output_size = output_size\n        self.spatial_scale = spatial_scale\n        self.sampling_ratio = sampling_ratio\n\n    def forward(self, input, rois):\n        \"\"\"\n        Args:\n            input: NCHW images\n            rois: Bx6 boxes. First column is the index into N.\n                The other 5 columns are (x_ctr, y_ctr, width, height, angle_degrees).\n        \"\"\"\n        assert rois.dim() == 2 and rois.size(1) == 6\n        orig_dtype = input.dtype\n        if orig_dtype == torch.float16:\n            input = input.float()\n            rois = rois.float()\n        output_size = _pair(self.output_size)\n\n        # Scripting for Autograd is currently unsupported.\n        # This is a quick fix without having to rewrite code on the C++ side\n        if torch.jit.is_scripting() or torch.jit.is_tracing():\n            return torch.ops.detectron2.roi_align_rotated_forward(\n                input, rois, self.spatial_scale, output_size[0], output_size[1], self.sampling_ratio\n            ).to(dtype=orig_dtype)\n\n        return roi_align_rotated(\n            input, rois, self.output_size, self.spatial_scale, self.sampling_ratio\n        ).to(dtype=orig_dtype)\n\n    def __repr__(self):\n        tmpstr = self.__class__.__name__ + \"(\"\n        tmpstr += \"output_size=\" + str(self.output_size)\n        tmpstr += \", spatial_scale=\" + str(self.spatial_scale)\n        tmpstr += \", sampling_ratio=\" + str(self.sampling_ratio)\n        tmpstr += \")\"\n        return tmpstr\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/rotated_boxes.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom __future__ import absolute_import, division, print_function, unicode_literals\nimport torch\n\n\ndef pairwise_iou_rotated(boxes1, boxes2):\n    \"\"\"\n    Return intersection-over-union (Jaccard index) of boxes.\n\n    Both sets of boxes are expected to be in\n    (x_center, y_center, width, height, angle) format.\n\n    Arguments:\n        boxes1 (Tensor[N, 5])\n        boxes2 (Tensor[M, 5])\n\n    Returns:\n        iou (Tensor[N, M]): the NxM matrix containing the pairwise\n            IoU values for every element in boxes1 and boxes2\n    \"\"\"\n    return torch.ops.detectron2.box_iou_rotated(boxes1, boxes2)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/shape_spec.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\nfrom dataclasses import dataclass\nfrom typing import Optional\n\n\n@dataclass\nclass ShapeSpec:\n    \"\"\"\n    A simple structure that contains basic shape specification about a tensor.\n    It is often used as the auxiliary inputs/outputs of models,\n    to complement the lack of shape inference ability among pytorch modules.\n    \"\"\"\n\n    channels: Optional[int] = None\n    height: Optional[int] = None\n    width: Optional[int] = None\n    stride: Optional[int] = None\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/layers/wrappers.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nWrappers around on some nn functions, mainly to support empty tensors.\n\nIdeally, add support directly in PyTorch to empty tensors in those functions.\n\nThese can be removed once https://github.com/pytorch/pytorch/issues/12013\nis implemented\n\"\"\"\n\nimport warnings\nfrom typing import List, Optional\nimport torch\nfrom torch.nn import functional as F\n\nTORCH_VERSION = tuple(int(x) for x in torch.__version__.split(\".\")[:2])\n\n\ndef shapes_to_tensor(x: List[int], device: Optional[torch.device] = None) -> torch.Tensor:\n    \"\"\"\n    Turn a list of integer scalars or integer Tensor scalars into a vector,\n    in a way that's both traceable and scriptable.\n\n    In tracing, `x` should be a list of scalar Tensor, so the output can trace to the inputs.\n    In scripting or eager, `x` should be a list of int.\n    \"\"\"\n    if torch.jit.is_scripting():\n        return torch.as_tensor(x, device=device)\n    if torch.jit.is_tracing():\n        assert all(\n            [isinstance(t, torch.Tensor) for t in x]\n        ), \"Shape should be tensor during tracing!\"\n        # as_tensor should not be used in tracing because it records a constant\n        ret = torch.stack(x)\n        if ret.device != device:  # avoid recording a hard-coded device if not necessary\n            ret = ret.to(device=device)\n        return ret\n    return torch.as_tensor(x, device=device)\n\n\ndef check_if_dynamo_compiling():\n    if TORCH_VERSION >= (1, 14):\n        from torch._dynamo import is_compiling\n\n        return is_compiling()\n    else:\n        return False\n\n\ndef cat(tensors: List[torch.Tensor], dim: int = 0):\n    \"\"\"\n    Efficient version of torch.cat that avoids a copy if there is only a single element in a list\n    \"\"\"\n    assert isinstance(tensors, (list, tuple))\n    if len(tensors) == 1:\n        return tensors[0]\n    return torch.cat(tensors, dim)\n\n\ndef empty_input_loss_func_wrapper(loss_func):\n    def wrapped_loss_func(input, target, *, reduction=\"mean\", **kwargs):\n        \"\"\"\n        Same as `loss_func`, but returns 0 (instead of nan) for empty inputs.\n        \"\"\"\n        if target.numel() == 0 and reduction == \"mean\":\n            return input.sum() * 0.0  # connect the gradient\n        return loss_func(input, target, reduction=reduction, **kwargs)\n\n    return wrapped_loss_func\n\n\ncross_entropy = empty_input_loss_func_wrapper(F.cross_entropy)\n\n\nclass _NewEmptyTensorOp(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, x, new_shape):\n        ctx.shape = x.shape\n        return x.new_empty(new_shape)\n\n    @staticmethod\n    def backward(ctx, grad):\n        shape = ctx.shape\n        return _NewEmptyTensorOp.apply(grad, shape), None\n\n\nclass Conv2d(torch.nn.Conv2d):\n    \"\"\"\n    A wrapper around :class:`torch.nn.Conv2d` to support empty inputs and more features.\n    \"\"\"\n\n    def __init__(self, *args, **kwargs):\n        \"\"\"\n        Extra keyword arguments supported in addition to those in `torch.nn.Conv2d`:\n\n        Args:\n            norm (nn.Module, optional): a normalization layer\n            activation (callable(Tensor) -> Tensor): a callable activation function\n\n        It assumes that norm layer is used before activation.\n        \"\"\"\n        norm = kwargs.pop(\"norm\", None)\n        activation = kwargs.pop(\"activation\", None)\n        super().__init__(*args, **kwargs)\n\n        self.norm = norm\n        self.activation = activation\n\n    def forward(self, x):\n        # torchscript does not support SyncBatchNorm yet\n        # https://github.com/pytorch/pytorch/issues/40507\n        # and we skip these codes in torchscript since:\n        # 1. currently we only support torchscript in evaluation mode\n        # 2. features needed by exporting module to torchscript are added in PyTorch 1.6 or\n        # later version, `Conv2d` in these PyTorch versions has already supported empty inputs.\n        if not torch.jit.is_scripting():\n            # Dynamo doesn't support context managers yet\n            is_dynamo_compiling = check_if_dynamo_compiling()\n            if not is_dynamo_compiling:\n                with warnings.catch_warnings(record=True):\n                    if x.numel() == 0 and self.training:\n                        # https://github.com/pytorch/pytorch/issues/12013\n                        assert not isinstance(\n                            self.norm, torch.nn.SyncBatchNorm\n                        ), \"SyncBatchNorm does not support empty inputs!\"\n\n        x = F.conv2d(\n            x, self.weight, self.bias, self.stride, self.padding, self.dilation, self.groups\n        )\n        if self.norm is not None:\n            x = self.norm(x)\n        if self.activation is not None:\n            x = self.activation(x)\n        return x\n\n\nConvTranspose2d = torch.nn.ConvTranspose2d\nBatchNorm2d = torch.nn.BatchNorm2d\ninterpolate = F.interpolate\nLinear = torch.nn.Linear\n\n\ndef nonzero_tuple(x):\n    \"\"\"\n    A 'as_tuple=True' version of torch.nonzero to support torchscript.\n    because of https://github.com/pytorch/pytorch/issues/38718\n    \"\"\"\n    if torch.jit.is_scripting():\n        if x.dim() == 0:\n            return x.unsqueeze(0).nonzero().unbind(1)\n        return x.nonzero().unbind(1)\n    else:\n        return x.nonzero(as_tuple=True)\n\n\n@torch.jit.script_if_tracing\ndef move_device_like(src: torch.Tensor, dst: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Tracing friendly way to cast tensor to another tensor's device. Device will be treated\n    as constant during tracing, scripting the casting process as whole can workaround this issue.\n    \"\"\"\n    return src.to(dst.device)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/__init__.py",
    "content": "from .track_loss import ClipMatcher\nfrom .dice_loss import DiceLoss\nfrom .occflow_loss import *\nfrom .traj_loss import TrajLoss\nfrom .planning_loss import PlanningLoss, CollisionLoss\nfrom .fvcore_smooth_l1_loss import smooth_l1_loss\nfrom .focal_loss import sigmoid_focal_loss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/dice_loss.py",
    "content": "import torch\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.models.losses.utils import weighted_loss\nfrom mmcv.models.builder import LOSSES\n\n@weighted_loss\ndef dice_loss(input, target,mask=None,eps=0.001):\n    N,H,W = input.shape\n    \n    input = input.contiguous().view(N, H*W)\n    target = target.contiguous().view(N, H*W).float()\n    if mask is not None:\n      mask = mask.contiguous().view(N, H*W).float()\n      input = input * mask\n      target = target * mask\n    a = torch.sum(input * target, 1)\n    b = torch.sum(input * input, 1) + eps\n    c = torch.sum(target * target, 1) + eps\n    d = (2 * a) / (b + c)\n    return 1 - d\n\n@LOSSES.register_module()\nclass DiceLoss(nn.Module):\n\n    def __init__(self, eps=1e-6, reduction='mean', loss_weight=1.0):\n        super(DiceLoss, self).__init__()\n        self.eps = eps\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n        self.count = 0\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                mask=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        #if weight is not None and weight.dim() > 1:\n            # TODO: remove this in the future\n            # reduce the weight of shape (n,w,h) to (n,) to match the\n            # giou_loss of shape (n,)\n            #assert weight.shape == pred.shape\n            #weight = weight.mean((-2,-1))\n        loss = self.loss_weight * dice_loss(\n            pred,\n            target,\n            weight,\n            mask=mask,\n            eps=self.eps,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        #print('DiceLoss',loss, avg_factor)\n        return loss\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/focal_loss.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved.\n\n# pyre-strict\n\nimport torch\nfrom torch.nn import functional as F\n\n\ndef sigmoid_focal_loss(\n    inputs: torch.Tensor,\n    targets: torch.Tensor,\n    alpha: float = -1,\n    gamma: float = 2,\n    reduction: str = \"none\",\n) -> torch.Tensor:\n    \"\"\"\n    Loss used in RetinaNet for dense detection: https://arxiv.org/abs/1708.02002.\n    Args:\n        inputs: A float tensor of arbitrary shape.\n                The predictions for each example.\n        targets: A float tensor with the same shape as inputs. Stores the binary\n                 classification label for each element in inputs\n                (0 for the negative class and 1 for the positive class).\n        alpha: (optional) Weighting factor in range (0,1) to balance\n                positive vs negative examples. Default = -1 (no weighting).\n        gamma: Exponent of the modulating factor (1 - p_t) to\n               balance easy vs hard examples.\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n    Returns:\n        Loss tensor with the reduction option applied.\n    \"\"\"\n    inputs = inputs.float()\n    targets = targets.float()\n    p = torch.sigmoid(inputs)\n    ce_loss = F.binary_cross_entropy_with_logits(inputs, targets, reduction=\"none\")\n    p_t = p * targets + (1 - p) * (1 - targets)\n    loss = ce_loss * ((1 - p_t) ** gamma)\n\n    if alpha >= 0:\n        alpha_t = alpha * targets + (1 - alpha) * (1 - targets)\n        loss = alpha_t * loss\n\n    if reduction == \"mean\":\n        loss = loss.mean()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n\n    return loss\n\n\n# pyre-fixme[9]: sigmoid_focal_loss_jit has type `ScriptModule`; used as\n#  `ScriptFunction[..., typing.Any]`.\nsigmoid_focal_loss_jit: \"torch.jit.ScriptModule\" = torch.jit.script(sigmoid_focal_loss)\n\n\ndef sigmoid_focal_loss_star(\n    inputs: torch.Tensor,\n    targets: torch.Tensor,\n    alpha: float = -1,\n    gamma: float = 1,\n    reduction: str = \"none\",\n) -> torch.Tensor:\n    \"\"\"\n    FL* described in RetinaNet paper Appendix: https://arxiv.org/abs/1708.02002.\n    Args:\n        inputs: A float tensor of arbitrary shape.\n                The predictions for each example.\n        targets: A float tensor with the same shape as inputs. Stores the binary\n                 classification label for each element in inputs\n                (0 for the negative class and 1 for the positive class).\n        alpha: (optional) Weighting factor in range (0,1) to balance\n                positive vs negative examples. Default = -1 (no weighting).\n        gamma: Gamma parameter described in FL*. Default = 1 (no weighting).\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n    Returns:\n        Loss tensor with the reduction option applied.\n    \"\"\"\n    inputs = inputs.float()\n    targets = targets.float()\n    shifted_inputs = gamma * (inputs * (2 * targets - 1))\n    loss = -(F.logsigmoid(shifted_inputs)) / gamma\n\n    if alpha >= 0:\n        alpha_t = alpha * targets + (1 - alpha) * (1 - targets)\n        loss *= alpha_t\n\n    if reduction == \"mean\":\n        loss = loss.mean()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n\n    return loss\n\n\n# pyre-fixme[9]: sigmoid_focal_loss_star_jit has type `ScriptModule`; used as\n#  `ScriptFunction[..., typing.Any]`.\nsigmoid_focal_loss_star_jit: \"torch.jit.ScriptModule\" = torch.jit.script(\n    sigmoid_focal_loss_star\n)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/fvcore_smooth_l1_loss.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved.\n\n# pyre-strict\n\nimport torch\n\n\ndef smooth_l1_loss(\n    input: torch.Tensor, target: torch.Tensor, beta: float, reduction: str = \"none\"\n) -> torch.Tensor:\n    \"\"\"\n    Smooth L1 loss defined in the Fast R-CNN paper as:\n    ::\n                      | 0.5 * x ** 2 / beta   if abs(x) < beta\n        smoothl1(x) = |\n                      | abs(x) - 0.5 * beta   otherwise,\n\n    where x = input - target.\n\n    Smooth L1 loss is related to Huber loss, which is defined as:\n    ::\n                    | 0.5 * x ** 2                  if abs(x) < beta\n         huber(x) = |\n                    | beta * (abs(x) - 0.5 * beta)  otherwise\n\n    Smooth L1 loss is equal to huber(x) / beta. This leads to the following\n    differences:\n\n     - As beta -> 0, Smooth L1 loss converges to L1 loss, while Huber loss\n       converges to a constant 0 loss.\n     - As beta -> +inf, Smooth L1 converges to a constant 0 loss, while Huber loss\n       converges to L2 loss.\n     - For Smooth L1 loss, as beta varies, the L1 segment of the loss has a constant\n       slope of 1. For Huber loss, the slope of the L1 segment is beta.\n\n    Smooth L1 loss can be seen as exactly L1 loss, but with the abs(x) < beta\n    portion replaced with a quadratic function such that at abs(x) = beta, its\n    slope is 1. The quadratic segment smooths the L1 loss near x = 0.\n\n    Args:\n        input (Tensor): input tensor of any shape\n        target (Tensor): target value tensor with the same shape as input\n        beta (float): L1 to L2 change point.\n            For beta values < 1e-5, L1 loss is computed.\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n\n    Returns:\n        The loss with the reduction option applied.\n\n    Note:\n        PyTorch's builtin \"Smooth L1 loss\" implementation does not actually\n        implement Smooth L1 loss, nor does it implement Huber loss. It implements\n        the special case of both in which they are equal (beta=1).\n        See: https://pytorch.org/docs/stable/nn.html#torch.nn.SmoothL1Loss.\n    \"\"\"\n    if beta < 1e-5:\n        # if beta == 0, then torch.where will result in nan gradients when\n        # the chain rule is applied due to pytorch implementation details\n        # (the False branch \"0.5 * n ** 2 / 0\" has an incoming gradient of\n        # zeros, rather than \"no gradient\"). To avoid this issue, we define\n        # small values of beta to be exactly l1 loss.\n        loss = torch.abs(input - target)\n    else:\n        n = torch.abs(input - target)\n        cond = n < beta\n        # pyre-fixme[58]: `**` is not supported for operand types `Tensor` and `int`.\n        loss = torch.where(cond, 0.5 * n**2 / beta, n - 0.5 * beta)\n\n    if reduction == \"mean\":\n        loss = loss.mean() if loss.numel() > 0 else 0.0 * loss.sum()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n    return loss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/occflow_loss.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n# Modified from Fiery (https://github.com/wayveai/fiery)                          #\n#---------------------------------------------------------------------------------#\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom einops import rearrange\nfrom mmcv.models.builder import LOSSES\nfrom mmcv.models.losses.utils import weight_reduce_loss\n\n@LOSSES.register_module()\nclass FieryBinarySegmentationLoss(nn.Module):\n    def __init__(self, use_top_k=False, top_k_ratio=1.0, future_discount=1.0, loss_weight=1.0, ignore_index=255):\n        super().__init__()\n        self.use_top_k = use_top_k\n        self.top_k_ratio = top_k_ratio\n        self.future_discount = future_discount\n        self.loss_weight = loss_weight\n        self.ignore_index = ignore_index\n\n    def forward(self, prediction, target, frame_mask=None):\n        n_gt, s, h, w = prediction.size()\n        assert prediction.size() == target.size(), f\"{prediction.size()}, {target.size()}\"\n\n        # Deal target > 1 (ignore_index)\n        keep_mask = (target.long() != self.ignore_index).float()\n        target = target * keep_mask\n\n        loss = F.binary_cross_entropy_with_logits(\n            prediction,\n            target.float(),\n            reduction='none',\n        )\n        assert loss.size() == prediction.size(), f\"{loss.size()}, {prediction.size()}\"\n        \n        # Deal ignore_index\n        if self.ignore_index is not None:\n            # keep_mask = (target.long() != self.ignore_index).float()\n            loss = loss * keep_mask\n\n        # Filter out losses of invalid future sample\n        if frame_mask is not None:\n            assert frame_mask.size(0) == s, f\"{frame_mask.size()}\"\n            if frame_mask.sum().item() == 0:\n                return prediction.sum() * 0.\n            frame_mask = frame_mask.view(1, s, 1, 1)\n            loss = loss * frame_mask.float()\n        \n        future_discounts = self.future_discount ** torch.arange(s, device=loss.device, dtype=loss.dtype)\n        future_discounts = future_discounts.view(1, s, 1, 1)\n        loss = loss * future_discounts\n\n        loss = loss.view(n_gt, s, -1)\n        if self.use_top_k:\n            # Penalises the top-k hardest pixels\n            k = int(self.top_k_ratio * loss.shape[2])\n            loss, _ = torch.sort(loss, dim=2, descending=True)\n            loss = loss[:, :, :k]\n\n        return self.loss_weight * torch.mean(loss)\n        \ndef dice_loss(pred,\n              target,\n              weight=None,\n              eps=1e-3,\n              reduction='mean',\n              naive_dice=False,\n              avg_factor=None,\n              ignore_index=None,\n              frame_mask=None):\n    \"\"\"Calculate dice loss, there are two forms of dice loss is supported:\n\n        - the one proposed in `V-Net: Fully Convolutional Neural\n            Networks for Volumetric Medical Image Segmentation\n            <https://arxiv.org/abs/1606.04797>`_.\n        - the dice loss in which the power of the number in the\n            denominator is the first power instead of the second\n            power.\n\n    Args:\n        pred (torch.Tensor): The prediction, has a shape (n, *)\n        target (torch.Tensor): The learning label of the prediction,\n            shape (n, *), same shape of pred.\n        weight (torch.Tensor, optional): The weight of loss for each\n            prediction, has a shape (n,). Defaults to None.\n        eps (float): Avoid dividing by zero. Default: 1e-3.\n        reduction (str, optional): The method used to reduce the loss into\n            a scalar. Defaults to 'mean'.\n            Options are \"none\", \"mean\" and \"sum\".\n        naive_dice (bool, optional): If false, use the dice\n                loss defined in the V-Net paper, otherwise, use the\n                naive dice loss in which the power of the number in the\n                denominator is the first power instead of the second\n                power.Defaults to False.\n        avg_factor (int, optional): Average factor that is used to average\n            the loss. Defaults to None.\n    \"\"\"\n    n, s, h, w = pred.size()\n    assert pred.size() == target.size(),  \\\n                f\"{pred.size()}, {target.size()}\"\n    \n    # Ignore invalid index(255)\n    if ignore_index is not None:\n        keep_mask = (target.long() != ignore_index)\n        target = target * keep_mask.float()\n        pred   = pred   * keep_mask.float()\n\n    # Ignore invalid frame\n    if frame_mask is not None:\n        assert frame_mask.size(0) == s, f\"{frame_mask.size()}\"\n        if frame_mask.sum().item() == 0:\n            return pred.sum() * 0.\n        frame_mask = frame_mask.view(1, s, 1, 1)\n        target = target * frame_mask.float()\n        pred   = pred   * frame_mask.float()\n\n    input = pred.flatten(1)\n    target = target.flatten(1).float()\n\n    a = torch.sum(input * target, 1)\n    if naive_dice:\n        b = torch.sum(input, 1)\n        c = torch.sum(target, 1)\n        d = (2 * a + eps) / (b + c + eps)\n    else:\n        b = torch.sum(input * input, 1) + eps\n        c = torch.sum(target * target, 1) + eps\n        d = (2 * a) / (b + c)\n\n    loss = 1 - d\n    if weight is not None:\n        assert weight.ndim == loss.ndim\n        assert len(weight) == len(pred)\n    loss = weight_reduce_loss(loss, weight, reduction, avg_factor)\n    return loss\n\n@LOSSES.register_module()\nclass DiceLossWithMasks(nn.Module):\n    def __init__(self,\n                 use_sigmoid=True,\n                 activate=True,\n                 reduction='mean',\n                 naive_dice=False,\n                 loss_weight=1.0,\n                 ignore_index=255,\n                 eps=1e-3):\n        \"\"\"Compute dice loss.\n\n        Args:\n            use_sigmoid (bool, optional): Whether to the prediction is\n                used for sigmoid or softmax. Defaults to True.\n            activate (bool): Whether to activate the predictions inside,\n                this will disable the inside sigmoid operation.\n                Defaults to True.\n            reduction (str, optional): The method used\n                to reduce the loss. Options are \"none\",\n                \"mean\" and \"sum\". Defaults to 'mean'.\n            naive_dice (bool, optional): If false, use the dice\n                loss defined in the V-Net paper, otherwise, use the\n                naive dice loss in which the power of the number in the\n                denominator is the first power instead of the second\n                power. Defaults to False.\n            loss_weight (float, optional): Weight of loss. Defaults to 1.0.\n            eps (float): Avoid dividing by zero. Defaults to 1e-3.\n        \"\"\"\n\n        super(DiceLossWithMasks, self).__init__()\n        self.use_sigmoid = use_sigmoid\n        self.reduction = reduction\n        self.naive_dice = naive_dice\n        self.loss_weight = loss_weight\n        self.eps = eps\n        self.activate = activate\n        self.ignore_index = ignore_index\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                reduction_override=None,\n                avg_factor=None,\n                frame_mask=None\n                ):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction, has a shape (n, *).\n            target (torch.Tensor): The label of the prediction,\n                shape (n, *), same shape of pred.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction, has a shape (n,). Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Options are \"none\", \"mean\" and \"sum\".\n\n        Returns:\n            torch.Tensor: The calculated loss\n        \"\"\"\n\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        if self.activate:\n            if self.use_sigmoid:\n                pred = pred.sigmoid()\n            else:\n                raise NotImplementedError\n\n        loss = self.loss_weight * dice_loss(\n            pred,\n            target,\n            weight,\n            eps=self.eps,\n            reduction=reduction,\n            naive_dice=self.naive_dice,\n            avg_factor=avg_factor,\n            ignore_index=self.ignore_index,\n            frame_mask=frame_mask)\n\n        return loss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/planning_loss.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom typing import Tuple\nimport pickle\nfrom mmcv.models import LOSSES\n\n\n@LOSSES.register_module()\nclass PlanningLoss(nn.Module):\n    def __init__(self, loss_type='L2'):\n        super(PlanningLoss, self).__init__()\n        self.loss_type = loss_type\n    \n    def forward(self, sdc_traj, gt_sdc_fut_traj, mask):\n        err = sdc_traj[..., :2] - gt_sdc_fut_traj[..., :2]\n        err = torch.pow(err, exponent=2)\n        err = torch.sum(err, dim=-1)\n        err = torch.pow(err, exponent=0.5)\n        return torch.sum(err * mask)/(torch.sum(mask) + 1e-5)\n\n\n@LOSSES.register_module()\nclass CollisionLoss(nn.Module):\n    def __init__(self, delta=0.5, weight=1.0):\n        super(CollisionLoss, self).__init__()\n        self.w = 1.85 + delta\n        self.h = 4.084 + delta\n        self.weight = weight\n    \n    def forward(self, sdc_traj_all, sdc_planning_gt, sdc_planning_gt_mask, future_gt_bbox):\n        # sdc_traj_all (1, 6, 2)\n        # sdc_planning_gt (1,6,3)\n        # sdc_planning_gt_mask (1, 6)\n        # future_gt_bbox 6x[lidarboxinstance]\n        n_futures = len(future_gt_bbox)\n        inter_sum = sdc_traj_all.new_zeros(1, )\n        dump_sdc = []\n        for i in range(n_futures):\n            if len(future_gt_bbox[i].tensor) > 0:\n                future_gt_bbox_corners = future_gt_bbox[i].corners[:, [0,3,4,7], :2] # (N, 8, 3) -> (N, 4, 2) only bev \n                # sdc_yaw = -sdc_planning_gt[0, i, 2].to(sdc_traj_all.dtype) - 1.5708\n                sdc_yaw = sdc_planning_gt[0, i, 2].to(sdc_traj_all.dtype)\n                sdc_bev_box = self.to_corners([sdc_traj_all[0, i, 0], sdc_traj_all[0, i, 1], self.w, self.h, sdc_yaw])\n                dump_sdc.append(sdc_bev_box.cpu().detach().numpy())\n                for j in range(future_gt_bbox_corners.shape[0]):\n                    inter_sum += self.inter_bbox(sdc_bev_box, future_gt_bbox_corners[j].to(sdc_traj_all.device))\n        return inter_sum * self.weight\n        \n    def inter_bbox(self, corners_a, corners_b):\n        xa1, ya1 = torch.max(corners_a[:, 0]), torch.max(corners_a[:, 1])\n        xa2, ya2 = torch.min(corners_a[:, 0]), torch.min(corners_a[:, 1])\n        xb1, yb1 = torch.max(corners_b[:, 0]), torch.max(corners_b[:, 1])\n        xb2, yb2 = torch.min(corners_b[:, 0]), torch.min(corners_b[:, 1])\n        \n        xi1, yi1 = min(xa1, xb1), min(ya1, yb1)\n        xi2, yi2 = max(xa2, xb2), max(ya2, yb2)\n        intersect = max((xi1 - xi2), xi1.new_zeros(1, ).to(xi1.device)) * max((yi1 - yi2), xi1.new_zeros(1,).to(xi1.device))\n        return intersect\n\n    def to_corners(self, bbox):\n        x, y, w, l, theta = bbox\n        corners = torch.tensor([\n            [w/2, -l/2], [w/2, l/2], [-w/2, l/2], [-w/2,-l/2]  \n        ]).to(x.device) # 4,2\n        rot_mat = torch.tensor(\n            [[torch.cos(theta), torch.sin(theta)],\n             [-torch.sin(theta), torch.cos(theta)]]\n        ).to(x.device)\n        new_corners = rot_mat @ corners.T + torch.tensor(bbox[:2])[:, None].to(x.device)\n        return new_corners.T"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/track_loss.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n# Modified from MOTR (https://github.com/megvii-research/MOTR)                    #\n#---------------------------------------------------------------------------------#\n\nimport copy\nfrom distutils.command.build import build\nimport math\nfrom xmlrpc.client import Boolean\nimport numpy as np\nimport torch\nimport torch.nn.functional as F\nimport torch.distributed as dist\nimport torch.nn as nn\nfrom typing import List\nfrom mmcv.models.dense_heads.track_head_plugin import Instances\nfrom mmcv.core import build_assigner\nfrom mmcv.models import build_loss\nfrom mmcv.models.builder import LOSSES\nfrom mmcv.core import reduce_mean\nfrom mmcv.core.bbox.iou_calculators.iou3d_calculator import (\n    bbox_overlaps_nearest_3d as iou_3d, )\nfrom mmcv.core.bbox.util import denormalize_bbox\n\n\ndef is_dist_avail_and_initialized():\n    if not dist.is_available():\n        return False\n    if not dist.is_initialized():\n        return False\n    return True\n\n\ndef get_world_size():\n    if not is_dist_avail_and_initialized():\n        return 1\n    return dist.get_world_size()\n\n\n@torch.no_grad()\ndef accuracy(output, target, topk=(1, )):\n    \"\"\"Computes the precision@k for the specified values of k\"\"\"\n    if target.numel() == 0:\n        return [torch.zeros([], device=output.device)]\n    maxk = max(topk)\n    batch_size = target.size(0)\n\n    _, pred = output.topk(maxk, 1, True, True)\n    pred = pred.t()\n    correct = pred.eq(target.view(1, -1).expand_as(pred))\n\n    res = []\n    for k in topk:\n        correct_k = correct[:k].view(-1).float().sum(0)\n        res.append(correct_k.mul_(100.0 / batch_size))\n    return res\n\n\n@LOSSES.register_module()\nclass ClipMatcher(nn.Module):\n    def __init__(\n            self,\n            num_classes,\n            weight_dict,\n            code_weights=[\n                1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2, 0.2\n            ],\n            loss_past_traj_weight=1.0,\n            assigner=dict(\n                type=\"HungarianAssigner3D\",\n                cls_cost=dict(type=\"FocalLossCost\", weight=2.0),\n                reg_cost=dict(type=\"BBox3DL1Cost\", weight=0.25),\n                pc_range=[-51.2, -51.2, -5.0, 51.2, 51.2, 3.0],\n            ),\n            loss_cls=dict(type=\"FocalLoss\",\n                          use_sigmoid=True,\n                          gamma=2.0,\n                          alpha=0.25,\n                          loss_weight=2.0),\n            loss_bbox=dict(type=\"L1Loss\", loss_weight=0.25),\n    ):\n        \"\"\"Create the criterion.\n        Parameters:\n            num_classes: number of object categories, omitting the special no-object category\n            weight_dict: dict containing as key the names of the losses and as values their relative weight.\n            eos_coef: relative classification weight applied to the no-object category\n        \"\"\"\n        super().__init__()\n        self.num_classes = num_classes\n        self.matcher = build_assigner(assigner)\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bboxes = build_loss(loss_bbox)\n        self.loss_predictions = nn.SmoothL1Loss(reduction=\"none\", beta=1.0)\n        self.register_buffer(\"code_weights\",\n                             torch.tensor(code_weights, requires_grad=False))\n\n        self.weight_dict = weight_dict\n        self.loss_past_traj_weight = loss_past_traj_weight\n        # self.losses = ['labels', 'boxes', 'cardinality']\n        self.losses = [\"labels\", \"boxes\", \"past_trajs\"]\n        self.focal_loss = True\n        self.losses_dict = {}\n        self._current_frame_idx = 0\n\n    def _get_src_permutation_idx(self, indices):\n        # permute predictions following indices\n        batch_idx = torch.cat(\n            [torch.full_like(src, i) for i, (src, _) in enumerate(indices)])\n        src_idx = torch.cat([src for (src, _) in indices])\n        return batch_idx, src_idx\n\n    def _get_tgt_permutation_idx(self, indices):\n        # permute targets following indices\n        batch_idx = torch.cat(\n            [torch.full_like(tgt, i) for i, (_, tgt) in enumerate(indices)])\n        tgt_idx = torch.cat([tgt for (_, tgt) in indices])\n        return batch_idx, tgt_idx\n\n    def initialize_for_single_clip(self, gt_instances: List[Instances]):\n        self.gt_instances = gt_instances\n        self.num_samples = 0\n        self.sample_device = None\n        self._current_frame_idx = 0\n        self.losses_dict = {}\n\n    def _step(self):\n        self._current_frame_idx += 1\n\n    def calc_loss_for_track_scores(self, track_instances: Instances):\n        frame_id = self._current_frame_idx - 1\n        gt_instances = self.gt_instances[frame_id]\n        outputs = {\n            \"pred_logits\": track_instances.track_scores[None],\n        }\n        device = track_instances.track_scores.device\n\n        num_tracks = len(track_instances)\n        src_idx = torch.arange(num_tracks, dtype=torch.long, device=device)\n        tgt_idx = (track_instances.matched_gt_idxes\n                   )  # -1 for FP tracks and disappeared tracks\n\n        track_losses = self.get_loss(\n            \"labels\",\n            outputs=outputs,\n            gt_instances=[gt_instances],\n            indices=[(src_idx, tgt_idx)],\n            num_boxes=1,\n        )\n        self.losses_dict.update({\n            \"frame_{}_track_{}\".format(frame_id, key): value\n            for key, value in track_losses.items()\n        })\n\n    def get_num_boxes(self, num_samples):\n        num_boxes = torch.as_tensor(num_samples,\n                                    dtype=torch.float,\n                                    device=self.sample_device)\n        if is_dist_avail_and_initialized():\n            torch.distributed.all_reduce(num_boxes)\n        num_boxes = torch.clamp(num_boxes / get_world_size(), min=1).item()\n        return num_boxes\n\n    @torch.no_grad()\n    def loss_cardinality(self, outputs, targets, indices):\n        \"\"\"Compute the cardinality error, ie the absolute error in the number of predicted non-empty boxes\n        This is not really a loss, it is intended for logging purposes only. It doesn't propagate gradients\n        \"\"\"\n        pred_logits = outputs[\"pred_logits\"]\n        device = pred_logits.device\n        tgt_lengths = torch.as_tensor([len(v.labels) for v in targets],\n                                      device=device)\n        # Count the number of predictions that are NOT \"no-object\" (which is the last class)\n        card_pred = (pred_logits.argmax(-1) !=\n                     pred_logits.shape[-1] - 1).sum(1)\n        card_err = F.l1_loss(card_pred.float(), tgt_lengths.float())\n        losses = {\"cardinality_error\": card_err}\n        return losses\n\n    def get_loss(self, loss, outputs, gt_instances, indices, **kwargs):\n        loss_map = {\n            \"labels\": self.loss_labels,\n            \"cardinality\": self.loss_cardinality,\n            \"boxes\": self.loss_boxes,\n            \"past_trajs\": self.loss_past_trajs,\n        }\n        assert loss in loss_map, f\"do you really want to compute {loss} loss?\"\n        return loss_map[loss](outputs, gt_instances, indices, **kwargs)\n\n    def loss_past_trajs(self, outputs, gt_instances: List[Instances],\n                   indices: List[tuple]):\n        # We ignore the regression loss of the track-disappear slots.\n        # TODO: Make this filter process more elegant.\n        filtered_idx = []\n        for src_per_img, tgt_per_img in indices:\n            keep = tgt_per_img != -1\n            filtered_idx.append((src_per_img[keep], tgt_per_img[keep]))\n        indices = filtered_idx\n        idx = self._get_src_permutation_idx(indices)\n        src_trajs = outputs[\"pred_past_trajs\"][idx]\n        target_trajs = torch.cat(\n            [\n                gt_per_img.past_traj[i]\n                for gt_per_img, (_, i) in zip(gt_instances, indices)\n            ],\n            dim=0,\n        )\n        target_trajs_mask = torch.cat(\n            [\n                gt_per_img.past_traj_mask[i]\n                for gt_per_img, (_, i) in zip(gt_instances, indices)\n            ],\n            dim=0,\n        )\n\n        # for pad target, don't calculate regression loss, judged by whether obj_id=-1\n        target_obj_ids = torch.cat(\n            [\n                gt_per_img.obj_ids[i]\n                for gt_per_img, (_, i) in zip(gt_instances, indices)\n            ],\n            dim=0,\n        )  # size(16)\n        # [num_matched]\n        mask = target_obj_ids != -1\n        loss_trajs = self.compute_past_traj_loss(src_trajs[mask], target_trajs[mask], target_trajs_mask[mask])\n        losses = {}\n        losses[\"loss_past_trajs\"] = loss_trajs * self.loss_past_traj_weight\n        return losses\n    \n    def compute_past_traj_loss(self, src, tgt, tgt_mask):\n        loss = torch.abs(src - tgt) * tgt_mask\n        return torch.sum(loss)/ (torch.sum(tgt_mask>0) + 1e-5)\n\n    def loss_boxes(self, outputs, gt_instances: List[Instances],\n                   indices: List[tuple]):\n        \"\"\"Compute the losses related to the bounding boxes, the L1 regression loss and the GIoU loss\n        targets dicts must contain the key \"boxes\" containing a tensor of dim [nb_target_boxes, 4]\n        The target boxes are expected in format (center_x, center_y, h, w), normalized by the image size.\n        \"\"\"\n        # We ignore the regression loss of the track-disappear slots.\n        # TODO: Make this filter process more elegant.\n        filtered_idx = []\n        for src_per_img, tgt_per_img in indices:\n            keep = tgt_per_img != -1\n            filtered_idx.append((src_per_img[keep], tgt_per_img[keep]))\n        indices = filtered_idx\n        idx = self._get_src_permutation_idx(indices)\n        src_boxes = outputs[\"pred_boxes\"][idx]\n        sdc_boxes = outputs[\"pred_sdc_boxes\"][0, -1:]\n        target_sdc_boxes = gt_instances[0].sdc_boxes[:1]\n        target_boxes = torch.cat(\n            [\n                gt_per_img.boxes[i]\n                for gt_per_img, (_, i) in zip(gt_instances, indices)\n            ],\n            dim=0,\n        )\n        \n        src_boxes = torch.cat([src_boxes, sdc_boxes], dim=0)\n        target_boxes = torch.cat([target_boxes, target_sdc_boxes], dim=0)\n\n        # for pad target, don't calculate regression loss, judged by whether obj_id=-1\n        target_obj_ids = torch.cat(\n            [\n                gt_per_img.obj_ids[i]\n                for gt_per_img, (_, i) in zip(gt_instances, indices)\n            ],\n            dim=0,\n        )\n        # [num_matched]\n\n        target_obj_ids = torch.cat([target_obj_ids, torch.zeros(1).to(target_obj_ids.device)], dim=0)\n        mask = target_obj_ids != -1\n        bbox_weights = torch.ones_like(target_boxes) * self.code_weights\n        avg_factor = src_boxes[mask].size(0)\n        avg_factor = reduce_mean(target_boxes.new_tensor([avg_factor]))\n        loss_bbox = self.loss_bboxes(\n            src_boxes[mask],\n            target_boxes[mask],\n            bbox_weights[mask],\n            avg_factor=avg_factor.item(),\n        )\n        \n        losses = {}\n        losses[\"loss_bbox\"] = loss_bbox\n\n        return losses\n\n    def loss_labels(self,\n                    outputs,\n                    gt_instances: List[Instances],\n                    indices,\n                    log=False):\n        \"\"\"Classification loss (NLL)\n        targets dicts must contain the key \"labels\" containing a tensor of dim [nb_target_boxes]\n\n        indices: [(src_idx, tgt_idx)]\n        \"\"\"\n        # [bs=1, num_query, num_classes]\n        src_logits = outputs[\"pred_logits\"]\n        sdc_logits = outputs[\"pred_sdc_logits\"]\n        # batch_idx, src_idx\n        idx = self._get_src_permutation_idx(indices)\n        # [bs, num_query]\n        target_classes = torch.full(\n            src_logits.shape[:2],\n            self.num_classes,\n            dtype=torch.int64,\n            device=src_logits.device,\n        )\n        # The matched gt for disappear track query is set -1.\n        labels = []\n        for gt_per_img, (_, J) in zip(gt_instances, indices):\n            labels_per_img = torch.ones_like(J) * self.num_classes\n            # set labels of track-appear slots to num_classes\n            if len(gt_per_img) > 0:\n                labels_per_img[J != -1] = gt_per_img.labels[J[J != -1]]\n            labels.append(labels_per_img)\n        # [num_matched]\n        target_classes_o = torch.cat(labels)\n        # [bs, num_query]\n        target_classes[idx] = target_classes_o\n        target_sdc_classes = gt_instances[0].sdc_labels[0:1].unsqueeze(0)\n        if sdc_logits is not None:\n            src_logits = torch.cat([src_logits, sdc_logits], dim=1)\n            target_classes = torch.cat([target_classes, target_sdc_classes], dim=1)\n        label_weights = torch.ones_like(target_classes)\n        # float tensor\n        avg_factor = target_classes_o.numel(\n        )  # pos + mathced gt for disapper track\n        avg_factor += 1 # sdc\n        \n        avg_factor = reduce_mean(src_logits.new_tensor([avg_factor]))\n        loss_ce = self.loss_cls(\n            src_logits.flatten(0, 1),\n            target_classes.flatten(0),\n            label_weights.flatten(0),\n            avg_factor,\n        )\n\n        losses = {\"loss_cls\": loss_ce}\n\n        if log:\n            # TODO this should probably be a separate loss, not hacked in this one here\n            losses[\"class_error\"] = 100 - accuracy(src_logits[idx],\n                                                   target_classes_o)[0]\n\n        return losses\n\n    def match_for_single_frame(self,\n                               outputs: dict,\n                               dec_lvl: int,\n                               if_step=False,\n                               ):\n        outputs_without_aux = {\n            k: v\n            for k, v in outputs.items() if k != \"aux_outputs\"\n        }\n\n        gt_instances_i = self.gt_instances[\n            self._current_frame_idx]  # gt instances of i-th image.\n        track_instances: Instances = outputs_without_aux[\"track_instances\"]\n        pred_logits_i = track_instances.pred_logits\n        pred_boxes_i = track_instances.pred_boxes\n        # modified the hard code, 900:901, sdc query\n        pred_sdc_logits_i = track_instances.pred_logits[900:901].unsqueeze(0) \n        pred_sdc_boxes_i = track_instances.pred_boxes[900:901].unsqueeze(0) \n        # -2 means the sdc query in this code\n        track_instances.obj_idxes[900]=-2\n        pred_past_trajs_i = track_instances.pred_past_trajs  # predicted past trajs of i-th image.\n\n        obj_idxes = gt_instances_i.obj_ids\n        obj_idxes_list = obj_idxes.detach().cpu().numpy().tolist()\n        obj_idx_to_gt_idx = {\n            obj_idx: gt_idx\n            for gt_idx, obj_idx in enumerate(obj_idxes_list)\n        }\n        outputs_i = {\n            \"pred_logits\": pred_logits_i.unsqueeze(0),\n            \"pred_sdc_logits\": pred_sdc_logits_i,\n            \"pred_boxes\": pred_boxes_i.unsqueeze(0),\n            \"pred_sdc_boxes\": pred_sdc_boxes_i,\n            \"pred_past_trajs\": pred_past_trajs_i.unsqueeze(0),\n        }\n        # step1. inherit and update the previous tracks.\n        num_disappear_track = 0\n        for j in range(len(track_instances)):\n            obj_id = track_instances.obj_idxes[j].item()\n            # set new target idx.\n            if obj_id >= 0:\n                if obj_id in obj_idx_to_gt_idx:\n                    track_instances.matched_gt_idxes[j] = obj_idx_to_gt_idx[\n                        obj_id]\n                else:\n                    num_disappear_track += 1\n                    track_instances.matched_gt_idxes[\n                        j] = -1  # track-disappear case.\n            else:\n                track_instances.matched_gt_idxes[j] = -1\n\n        full_track_idxes = torch.arange(\n            len(track_instances), dtype=torch.long).to(pred_logits_i.device)\n        # previsouly tracked, which is matched by rule\n        matched_track_idxes = track_instances.obj_idxes >= 0\n        prev_matched_indices = torch.stack(\n            [\n                full_track_idxes[matched_track_idxes],\n                track_instances.matched_gt_idxes[matched_track_idxes],\n            ],\n            dim=1,\n        ).to(pred_logits_i.device)\n\n        # step2. select the unmatched slots.\n        # note that the FP tracks whose obj_idxes are -2 will not be selected here.\n        unmatched_track_idxes = full_track_idxes[track_instances.obj_idxes ==\n                                                 -1]\n\n        # step3. select the untracked gt instances (new tracks).\n        tgt_indexes = track_instances.matched_gt_idxes\n        tgt_indexes = tgt_indexes[tgt_indexes != -1]\n\n        tgt_state = torch.zeros(len(gt_instances_i)).to(pred_logits_i.device)\n        tgt_state[tgt_indexes] = 1\n        # new tgt indexes\n        untracked_tgt_indexes = torch.arange(len(gt_instances_i)).to(\n            pred_logits_i.device)[tgt_state == 0]\n        # untracked_tgt_indexes = select_unmatched_indexes(tgt_indexes, len(gt_instances_i))\n        # [num_untracked]\n        untracked_gt_instances = gt_instances_i[untracked_tgt_indexes]\n\n        def match_for_single_decoder_layer(unmatched_outputs, matcher):\n            bbox_preds, cls_preds = (\n                unmatched_outputs[\"pred_boxes\"],\n                unmatched_outputs[\"pred_logits\"],\n            )\n            bs, num_querys = bbox_preds.shape[:2]\n            # Also concat the target labels and boxes\n            targets = [untracked_gt_instances]\n            if isinstance(targets[0], Instances):\n                # [num_box], [num_box, 9] (un-normalized bboxes)\n                gt_labels = torch.cat(\n                    [gt_per_img.labels for gt_per_img in targets])\n                gt_bboxes = torch.cat(\n                    [gt_per_img.boxes for gt_per_img in targets])\n            else:\n                gt_labels = torch.cat([v[\"labels\"] for v in targets])\n                gt_bboxes = torch.cat([v[\"boxes\"] for v in targets])\n\n            bbox_pred = bbox_preds[0]\n            cls_pred = cls_preds[0]\n\n            src_idx, tgt_idx = matcher.assign(bbox_pred, cls_pred, gt_bboxes,\n                                              gt_labels)\n            if src_idx is None:\n                return None\n            # concat src and tgt.\n            new_matched_indices = torch.stack([\n                unmatched_track_idxes[src_idx], untracked_tgt_indexes[tgt_idx]\n            ],\n                                              dim=1).to(pred_logits_i.device)\n            return new_matched_indices\n\n        # step4. do matching between the unmatched slots and GTs.\n        unmatched_outputs = {\n            # [bs, num_pred, num_classes]\n            \"pred_logits\":\n            track_instances.pred_logits[unmatched_track_idxes].unsqueeze(0),\n            # [bs, num_pred, box_dim]\n            \"pred_boxes\":\n            track_instances.pred_boxes[unmatched_track_idxes].unsqueeze(0),\n        }\n        # [num_new_matched, 2]\n        new_matched_indices = match_for_single_decoder_layer(\n            unmatched_outputs, self.matcher)\n\n        # step5. update obj_idxes according to the new matching result.\n        if new_matched_indices is not None:\n            track_instances.obj_idxes[\n                new_matched_indices[:, 0]] = gt_instances_i.obj_ids[\n                    new_matched_indices[:, 1]].long()\n            track_instances.matched_gt_idxes[\n                new_matched_indices[:, 0]] = new_matched_indices[:, 1]\n\n            # step6. calculate iou3d.\n            active_idxes = (track_instances.obj_idxes >=\n                            0) & (track_instances.matched_gt_idxes >= 0)\n            active_track_boxes = track_instances.pred_boxes[active_idxes]\n            with torch.no_grad():\n                if len(active_track_boxes) > 0:\n                    gt_boxes = gt_instances_i.boxes[\n                        track_instances.matched_gt_idxes[active_idxes]]\n                    iou_3ds = iou_3d(\n                        denormalize_bbox(gt_boxes, None)[..., :7],\n                        denormalize_bbox(active_track_boxes, None)[..., :7],\n                    )\n                    track_instances.iou[active_idxes] = torch.tensor([\n                        iou_3ds[i, i] for i in range(gt_boxes.shape[0])\n                    ]).to(gt_boxes.device)\n\n            # step7. merge the unmatched pairs and the matched pairs.\n            # [num_new_macthed + num_prev_mathed, 2]\n            matched_indices = torch.cat(\n                [new_matched_indices, prev_matched_indices], dim=0)\n        else:\n            matched_indices = prev_matched_indices\n        # step8. calculate losses.\n        self.num_samples += len(gt_instances_i) + num_disappear_track\n        self.sample_device = pred_logits_i.device\n\n        for loss in self.losses:\n            new_track_loss = self.get_loss(\n                loss,\n                outputs=outputs_i,\n                gt_instances=[gt_instances_i],\n                indices=[(matched_indices[:, 0], matched_indices[:, 1])],\n            )\n            self.losses_dict.update({\n                \"frame_{}_{}_{}\".format(self._current_frame_idx, key, dec_lvl):\n                value\n                for key, value in new_track_loss.items()\n            })\n        if \"aux_outputs\" in outputs:\n            for i, aux_outputs in enumerate(outputs[\"aux_outputs\"]):\n                unmatched_outputs_layer = {\n                    \"pred_logits\":\n                    aux_outputs[\"pred_logits\"][\n                        0, unmatched_track_idxes].unsqueeze(0),\n                    \"pred_boxes\":\n                    aux_outputs[\"pred_boxes\"][\n                        0, unmatched_track_idxes].unsqueeze(0),\n                }\n                new_matched_indices_layer = match_for_single_decoder_layer(\n                    unmatched_outputs_layer, self.matcher)\n                matched_indices_layer = torch.cat(\n                    [new_matched_indices_layer, prev_matched_indices], dim=0)\n                for loss in self.losses:\n                    if loss == \"masks\":\n                        # Intermediate masks losses are too costly to compute, we ignore them.\n                        continue\n                    l_dict = self.get_loss(\n                        loss,\n                        aux_outputs,\n                        gt_instances=[gt_instances_i],\n                        indices=[(matched_indices_layer[:, 0],\n                                  matched_indices_layer[:, 1])],\n                    )\n                    self.losses_dict.update({\n                        \"frame_{}_aux{}_{}\".format(self._current_frame_idx, i,\n                                                   key): value\n                        for key, value in l_dict.items()\n                    })\n        if if_step:\n            self._step()\n        return track_instances, matched_indices\n\n    def forward(self, outputs, input_data: dict):\n        # losses of each frame are calculated during the model's forwarding and are outputted by the model as outputs['losses_dict].\n        losses = outputs.pop(\"losses_dict\")\n        num_samples = self.get_num_boxes(self.num_samples)\n        for loss_name, loss in losses.items():\n            losses[loss_name] /= num_samples\n        return losses\n\n    def prediction_loss(self, track_instances, predictions):\n\n        decay_ratio = 1.0\n        for i in range(self._current_frame_idx, len(self.gt_instances)):\n            gt_instances_i = self.gt_instances[\n                i]  # gt instances of i-th image.\n\n            pred_boxes_i = predictions[i - self._current_frame_idx]\n\n            obj_idxes = gt_instances_i.obj_ids\n            obj_idxes_list = obj_idxes.detach().cpu().numpy().tolist()\n            obj_idx_to_gt_idx = {\n                obj_idx: gt_idx\n                for gt_idx, obj_idx in enumerate(obj_idxes_list)\n            }\n\n            num_paired = 0\n            for j in range(len(track_instances)):\n                obj_id = track_instances.obj_idxes[j].item()\n                # set new target idx.\n                if obj_id >= 0:\n                    if obj_id in obj_idx_to_gt_idx:\n                        track_instances.matched_gt_idxes[\n                            j] = obj_idx_to_gt_idx[obj_id]\n                        num_paired += 1\n                    else:\n                        track_instances.matched_gt_idxes[\n                            j] = -1  # track-disappear case.\n                else:\n                    track_instances.matched_gt_idxes[j] = -1\n\n            if num_paired > 0:\n                if_paired_i = track_instances.matched_gt_idxes >= 0\n\n                paired_pred_boxes_i = pred_boxes_i[if_paired_i]\n\n                paired_gt_instances = gt_instances_i[\n                    track_instances.matched_gt_idxes[if_paired_i]]\n                normalized_bboxes = paired_gt_instances.boxes\n                cx = normalized_bboxes[..., 0:1]\n                cy = normalized_bboxes[..., 1:2]\n                cz = normalized_bboxes[..., 4:5]\n\n                gt_boxes_i = torch.cat([cx, cy, cz], dim=-1)\n\n                pred_loss_i = (0.2 * decay_ratio * self.loss_predictions(\n                    paired_pred_boxes_i, gt_boxes_i).sum(dim=-1).mean())\n\n                self.losses_dict[\"pred_loss_{}\".format(i)] = pred_loss_i\n            else:\n                self.losses_dict[\"pred_loss_{}\".format(i)] = torch.tensor(\n                    [0.0]).cuda()\n\n            decay_ratio = decay_ratio * 0.5"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/losses/traj_loss.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport math\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom typing import Tuple\n\nfrom mmcv.models import LOSSES\n\n@LOSSES.register_module()\nclass TrajLoss(nn.Module):\n    \"\"\"\n    MTP loss modified to include variances. Uses MSE for mode selection.\n    Can also be used with\n    Multipath outputs, with residuals added to anchors.\n    \"\"\"\n\n    def __init__(self, use_variance=False, cls_loss_weight=1., nll_loss_weight=1., loss_weight_minade=0., loss_weight_minfde=1., loss_weight_mr=1.):\n        \"\"\"\n        Initialize MTP loss\n        :param args: Dictionary with the following (optional) keys\n            use_variance: bool, whether or not to use variances for computing\n            regression component of loss,\n                default: False\n            alpha: float, relative weight assigned to classification component,\n            compared to regression component\n                of loss, default: 1\n        \"\"\"\n        super(TrajLoss, self).__init__()\n        self.use_variance = use_variance\n        self.cls_loss_weight = cls_loss_weight\n        self.nll_loss_weight = nll_loss_weight\n        self.loss_weight_minade = loss_weight_minade\n        self.loss_weight_minfde = loss_weight_minfde\n\n    def forward(self,\n                traj_prob, \n                traj_preds, \n                gt_future_traj, \n                gt_future_traj_valid_mask):\n        \"\"\"\n        Compute MTP loss\n        :param predictions: Dictionary with 'traj': predicted trajectories\n        and 'probs': mode (log) probabilities\n        :param ground_truth: Either a tensor with ground truth trajectories\n        or a dictionary\n        :return:\n        \"\"\"\n        # Unpack arguments\n        traj = traj_preds # (b, nmodes, seq, 5)\n        log_probs = traj_prob\n        traj_gt = gt_future_traj\n\n        # Useful variables\n        batch_size = traj.shape[0]\n        sequence_length = traj.shape[2]\n        pred_params = 5 if self.use_variance else 2\n\n        # Masks for variable length ground truth trajectories\n        masks = 1 - gt_future_traj_valid_mask.to(traj.dtype)\n\n        l_minfde, inds = min_fde(traj, traj_gt, masks)\n        try:\n            l_mr = miss_rate(traj, traj_gt, masks)\n        except:\n            l_mr = torch.zeros_like(l_minfde)\n        l_minade, inds = min_ade(traj, traj_gt, masks)\n        inds_rep = inds.repeat(\n            sequence_length,\n            pred_params, 1, 1).permute(3, 2, 0, 1)\n\n        # Calculate MSE or NLL loss for trajectories corresponding to selected\n        # outputs:\n        traj_best = traj.gather(1, inds_rep).squeeze(dim=1)\n\n        if self.use_variance:\n            l_reg = traj_nll(traj_best, traj_gt, masks)\n        else:\n            l_reg = l_minade\n\n        # Compute classification loss\n        l_class = - torch.squeeze(log_probs.gather(1, inds.unsqueeze(1)))\n\n        l_reg = torch.sum(l_reg)/(batch_size + 1e-5) \n        l_class = torch.sum(l_class)/(batch_size + 1e-5)\n        l_minade = torch.sum(l_minade)/(batch_size + 1e-5) \n        l_minfde = torch.sum(l_minfde)/(batch_size + 1e-5) \n\n        loss = l_class * self.cls_loss_weight + l_reg * self.nll_loss_weight + l_minade * self.loss_weight_minade + l_minfde * self.loss_weight_minfde\n        return loss, l_class, l_reg, l_minade, l_minfde, l_mr\n\ndef min_ade(traj: torch.Tensor, traj_gt: torch.Tensor,\n            masks: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Computes average displacement error for the best trajectory is a set,\n    with respect to ground truth\n    :param traj: predictions, shape [batch_size, num_modes, sequence_length, 2]\n    :param traj_gt: ground truth trajectory, shape\n    [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth, shape\n    [batch_size, sequence_length]\n    :return errs, inds: errors and indices for modes with min error, shape\n    [batch_size]\n    \"\"\"\n    num_modes = traj.shape[1]\n    traj_gt_rpt = traj_gt.unsqueeze(1).repeat(1, num_modes, 1, 1)\n    masks_rpt = masks.unsqueeze(1).repeat(1, num_modes, 1)\n    err = traj_gt_rpt - traj[:, :, :, 0:2]\n    err = torch.pow(err, exponent=2)\n    err = torch.sum(err, dim=3)\n    err = torch.pow(err, exponent=0.5)\n    err = torch.sum(err * (1 - masks_rpt), dim=2) / \\\n        torch.clip(torch.sum((1 - masks_rpt), dim=2), min=1)\n    err, inds = torch.min(err, dim=1)\n\n    return err, inds\n\ndef traj_nll(\n        pred_dist: torch.Tensor,\n        traj_gt: torch.Tensor,\n        masks: torch.Tensor):\n    \"\"\"\n    Computes negative log likelihood of ground truth trajectory under a\n    predictive distribution with a single mode,\n    with a bivariate Gaussian distribution predicted at each time in the\n    prediction horizon\n\n    :param pred_dist: parameters of a bivariate Gaussian distribution,\n    shape [batch_size, sequence_length, 5]\n    :param traj_gt: ground truth trajectory,\n    shape [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth,\n    shape [batch_size, sequence_length]\n    :return:\n    \"\"\"\n    mu_x = pred_dist[:, :, 0]\n    mu_y = pred_dist[:, :, 1]\n    x = traj_gt[:, :, 0]\n    y = traj_gt[:, :, 1]\n\n    sig_x = pred_dist[:, :, 2]\n    sig_y = pred_dist[:, :, 3]\n    rho = pred_dist[:, :, 4]\n    ohr = torch.pow(1 - torch.pow(rho, 2), -0.5)\n\n    nll = 0.5 * torch.pow(ohr, 2) * \\\n        (torch.pow(sig_x, 2) * torch.pow(x - mu_x, 2) + torch.pow(sig_y, 2) *\n         torch.pow(y - mu_y, 2) - 2 * rho * torch.pow(sig_x, 1) *\n         torch.pow(sig_y, 1) * (x - mu_x) * (y - mu_y)) - \\\n        torch.log(sig_x * sig_y * ohr) + 1.8379\n\n    nll[nll.isnan()] = 0\n    nll[nll.isinf()] = 0\n\n    nll = torch.sum(nll * (1 - masks), dim=1) / (torch.sum((1 - masks), dim=1) + 1e-5)\n    # Note: Normalizing with torch.sum((1 - masks), dim=1) makes values\n    # somewhat comparable for trajectories of\n    # different lengths\n\n    return nll\n\ndef min_fde(traj: torch.Tensor, traj_gt: torch.Tensor,\n            masks: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Computes final displacement error for the best trajectory is a set,\n    with respect to ground truth\n    :param traj: predictions, shape [batch_size, num_modes, sequence_length, 2]\n    :param traj_gt: ground truth trajectory, shape\n    [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth, shape\n    [batch_size, sequence_length]\n    :return errs, inds: errors and indices for modes with min error,\n    shape [batch_size]\n    \"\"\"\n    num_modes = traj.shape[1]\n    lengths = torch.sum(1 - masks, dim=1).long()\n    valid_mask = lengths > 0\n    traj = traj[valid_mask]\n    traj_gt = traj_gt[valid_mask]\n    masks = masks[valid_mask]\n    traj_gt_rpt = traj_gt.unsqueeze(1).repeat(1, num_modes, 1, 1)\n    lengths = torch.sum(1 - masks, dim=1).long()\n    inds = lengths.unsqueeze(1).unsqueeze(\n        2).unsqueeze(3).repeat(1, num_modes, 1, 2) - 1\n\n    traj_last = torch.gather(traj[..., :2], dim=2, index=inds).squeeze(2)\n    traj_gt_last = torch.gather(traj_gt_rpt, dim=2, index=inds).squeeze(2)\n\n    err = traj_gt_last - traj_last[..., 0:2]\n    err = torch.pow(err, exponent=2)\n    err = torch.sum(err, dim=2)\n    err = torch.pow(err, exponent=0.5)\n    err, inds = torch.min(err, dim=1)\n\n    return err, inds\n\n\ndef miss_rate(\n        traj: torch.Tensor,\n        traj_gt: torch.Tensor,\n        masks: torch.Tensor,\n        dist_thresh: float = 2) -> torch.Tensor:\n    \"\"\"\n    Computes miss rate for mini batch of trajectories,\n    with respect to ground truth and given distance threshold\n    :param traj: predictions, shape [batch_size, num_modes, sequence_length, 2]\n    :param traj_gt: ground truth trajectory,\n    shape [batch_size, sequence_length, 2]\n    :param masks: masks for varying length ground truth,\n    shape [batch_size, sequence_length]\n    :param dist_thresh: distance threshold for computing miss rate.\n    :return errs, inds: errors and indices for modes with min error,\n    shape [batch_size]\n    \"\"\"\n    num_modes = traj.shape[1]\n\n    traj_gt_rpt = traj_gt.unsqueeze(1).repeat(1, num_modes, 1, 1)\n    masks_rpt = masks.unsqueeze(1).repeat(1, num_modes, 1)\n    dist = traj_gt_rpt - traj[:, :, :, 0:2]\n    dist = torch.pow(dist, exponent=2)\n    dist = torch.sum(dist, dim=3)\n    dist = torch.pow(dist, exponent=0.5)\n    dist[masks_rpt.bool()] = -math.inf\n    dist, _ = torch.max(dist, dim=2)\n    dist, _ = torch.min(dist, dim=1)\n    m_r = torch.sum(torch.as_tensor(dist > dist_thresh)) / len(dist)\n\n    return m_r\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/metrics/classification.py",
    "content": "# Copyright The PyTorch Lightning team.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\nfrom functools import wraps\nfrom typing import Callable, Optional, Sequence, Tuple\n\nimport torch\nfrom .utils import get_num_classes as __gnc\nfrom .utils import to_categorical as __tc\nfrom .distributed import rank_zero_warn\n\n\ndef to_categorical(tensor: torch.Tensor, argmax_dim: int = 1) -> torch.Tensor:\n    \"\"\"\n    Converts a tensor of probabilities to a dense label tensor\n\n    .. warning :: Deprecated in favor of :func:`~mmcv.pytorch_lightning.metrics.utils.to_categorical`\n\n    \"\"\"\n    rank_zero_warn(\n        \"This `to_categorical` was deprecated in v1.1.0 in favor of\"\n        \" `from mmcv.pytorch_lightning.metrics.utils import to_categorical`.\"\n        \" It will be removed in v1.3.0\", DeprecationWarning\n    )\n    return __tc(tensor)\n\n\ndef get_num_classes(\n    pred: torch.Tensor,\n    target: torch.Tensor,\n    num_classes: Optional[int] = None,\n) -> int:\n    \"\"\"\n    Calculates the number of classes for a given prediction and target tensor.\n\n    .. warning :: Deprecated in favor of :func:`~mmcv.pytorch_lightning.metrics.utils.get_num_classes`\n\n    \"\"\"\n    rank_zero_warn(\n        \"This `get_num_classes` was deprecated in v1.1.0 in favor of\"\n        \" `from mmcv.pytorch_lightning.metrics.utils import get_num_classes`.\"\n        \" It will be removed in v1.3.0\", DeprecationWarning\n    )\n    return __gnc(pred, target, num_classes)\n\n\ndef stat_scores(\n    pred: torch.Tensor,\n    target: torch.Tensor,\n    class_index: int,\n    argmax_dim: int = 1,\n) -> Tuple[torch.Tensor, torch.Tensor, torch.Tensor, torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Calculates the number of true positive, false positive, true negative\n    and false negative for a specific class\n\n    Args:\n        pred: prediction tensor\n        target: target tensor\n        class_index: class to calculate over\n        argmax_dim: if pred is a tensor of probabilities, this indicates the\n            axis the argmax transformation will be applied over\n\n    Return:\n        True Positive, False Positive, True Negative, False Negative, Support\n\n    Example:\n\n        >>> x = torch.tensor([1, 2, 3])\n        >>> y = torch.tensor([0, 2, 3])\n        >>> tp, fp, tn, fn, sup = stat_scores(x, y, class_index=1)\n        >>> tp, fp, tn, fn, sup\n        (tensor(0), tensor(1), tensor(2), tensor(0), tensor(0))\n\n    \"\"\"\n    if pred.ndim == target.ndim + 1:\n        pred = to_categorical(pred, argmax_dim=argmax_dim)\n\n    tp = ((pred == class_index) * (target == class_index)).to(torch.long).sum()\n    fp = ((pred == class_index) * (target != class_index)).to(torch.long).sum()\n    tn = ((pred != class_index) * (target != class_index)).to(torch.long).sum()\n    fn = ((pred != class_index) * (target == class_index)).to(torch.long).sum()\n    sup = (target == class_index).to(torch.long).sum()\n\n    return tp, fp, tn, fn, sup\n\n\n# todo: remove in 1.4\ndef stat_scores_multiple_classes(\n    pred: torch.Tensor,\n    target: torch.Tensor,\n    num_classes: Optional[int] = None,\n    argmax_dim: int = 1,\n    reduction: str = 'none',\n) -> Tuple[torch.Tensor, torch.Tensor, torch.Tensor, torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Calculates the number of true positive, false positive, true negative\n    and false negative for each class\n\n    .. warning :: Deprecated in favor of :func:`~mmcv.pytorch_lightning.metrics.functional.stat_scores`\n\n    Raises:\n        ValueError:\n            If ``reduction`` is not one of ``\"none\"``, ``\"sum\"`` or ``\"elementwise_mean\"``.\n    \"\"\"\n\n    rank_zero_warn(\n        \"This `stat_scores_multiple_classes` was deprecated in v1.2.0 in favor of\"\n        \" `from mmcv.pytorch_lightning.metrics.functional import stat_scores`.\"\n        \" It will be removed in v1.4.0\", DeprecationWarning\n    )\n    if pred.ndim == target.ndim + 1:\n        pred = to_categorical(pred, argmax_dim=argmax_dim)\n\n    num_classes = get_num_classes(pred=pred, target=target, num_classes=num_classes)\n\n    if pred.dtype != torch.bool:\n        pred = pred.clamp_max(max=num_classes)\n    if target.dtype != torch.bool:\n        target = target.clamp_max(max=num_classes)\n\n    possible_reductions = ('none', 'sum', 'elementwise_mean')\n    if reduction not in possible_reductions:\n        raise ValueError(\"reduction type %s not supported\" % reduction)\n\n    if reduction == 'none':\n        pred = pred.view((-1, )).long()\n        target = target.view((-1, )).long()\n\n        tps = torch.zeros((num_classes + 1, ), device=pred.device)\n        fps = torch.zeros((num_classes + 1, ), device=pred.device)\n        fns = torch.zeros((num_classes + 1, ), device=pred.device)\n        sups = torch.zeros((num_classes + 1, ), device=pred.device)\n\n        match_true = (pred == target).float()\n        match_false = 1 - match_true\n\n        tps.scatter_add_(0, pred, match_true)\n        fps.scatter_add_(0, pred, match_false)\n        fns.scatter_add_(0, target, match_false)\n        tns = pred.size(0) - (tps + fps + fns)\n        sups.scatter_add_(0, target, torch.ones_like(match_true))\n\n        tps = tps[:num_classes]\n        fps = fps[:num_classes]\n        tns = tns[:num_classes]\n        fns = fns[:num_classes]\n        sups = sups[:num_classes]\n\n    elif reduction == 'sum' or reduction == 'elementwise_mean':\n        count_match_true = (pred == target).sum().float()\n        oob_tp, oob_fp, oob_tn, oob_fn, oob_sup = stat_scores(pred, target, num_classes, argmax_dim)\n\n        tps = count_match_true - oob_tp\n        fps = pred.nelement() - count_match_true - oob_fp\n        fns = pred.nelement() - count_match_true - oob_fn\n        tns = pred.nelement() * (num_classes + 1) - (tps + fps + fns + oob_tn)\n        sups = pred.nelement() - oob_sup.float()\n\n        if reduction == 'elementwise_mean':\n            tps /= num_classes\n            fps /= num_classes\n            fns /= num_classes\n            tns /= num_classes\n            sups /= num_classes\n\n    return tps.float(), fps.float(), tns.float(), fns.float(), sups.float()\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/metrics/compositional.py",
    "content": "# Copyright The PyTorch Lightning team.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\nfrom typing import Callable, Union\n\nimport torch\nfrom torchmetrics.metric import CompositionalMetric as _CompositionalMetric\n\nfrom .metric import Metric\nfrom .distributed import rank_zero_warn\n\n\nclass CompositionalMetric(_CompositionalMetric):\n    r\"\"\"\n    This implementation refers to :class:`~torchmetrics.metric.CompositionalMetric`.\n\n    .. warning:: This metric is deprecated, use ``torchmetrics.metric.CompositionalMetric``. Will be removed in v1.5.0.\n    \"\"\"\n\n    def __init__(\n        self,\n        operator: Callable,\n        metric_a: Union[Metric, int, float, torch.Tensor],\n        metric_b: Union[Metric, int, float, torch.Tensor, None],\n    ):\n        rank_zero_warn(\n            \"This `Metric` was deprecated since v1.3.0 in favor of `torchmetrics.Metric`.\"\n            \" It will be removed in v1.5.0\", DeprecationWarning\n        )\n        super().__init__(operator=operator, metric_a=metric_a, metric_b=metric_b)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/metrics/distributed.py",
    "content": "# Copyright The PyTorch Lightning team.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nimport logging\nimport os\nimport warnings\nfrom functools import wraps\nfrom typing import Any, Optional, Union\n\nimport torch\n\nlog = logging.getLogger(__name__)\n\nif torch.distributed.is_available():\n    from torch.distributed import group, ReduceOp\n\nelse:\n\n    class ReduceOp:\n        SUM = None\n\n    class group:\n        WORLD = None\n\n\ndef rank_zero_only(fn):\n\n    @wraps(fn)\n    def wrapped_fn(*args, **kwargs):\n        if rank_zero_only.rank == 0:\n            return fn(*args, **kwargs)\n\n    return wrapped_fn\n\n\n# add the attribute to the function but don't overwrite in case Trainer has already set it\nrank_zero_only.rank = getattr(rank_zero_only, 'rank', int(os.environ.get('LOCAL_RANK', 0)))\n\n\ndef _warn(*args, **kwargs):\n    warnings.warn(*args, **kwargs)\n\n\ndef _info(*args, **kwargs):\n    log.info(*args, **kwargs)\n\n\ndef _debug(*args, **kwargs):\n    log.debug(*args, **kwargs)\n\n\nrank_zero_debug = rank_zero_only(_debug)\nrank_zero_info = rank_zero_only(_info)\nrank_zero_warn = rank_zero_only(_warn)\n\n\ndef find_free_network_port() -> int:\n    \"\"\"\n    Finds a free port on localhost.\n    It is useful in single-node training when we don't want to connect to a real master node but\n    have to set the `MASTER_PORT` environment variable.\n    \"\"\"\n    import socket\n    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)\n    s.bind((\"\", 0))\n    s.listen(1)\n    port = s.getsockname()[1]\n    s.close()\n    return port\n\n\ndef gather_all_tensors(result: Union[torch.Tensor], group: Optional[Any] = None):\n    \"\"\"\n    Function to gather all tensors from several ddp processes onto a list that\n    is broadcasted to all processes\n\n    Args:\n        result: the value to sync\n        group: the process group to gather results from. Defaults to all processes (world)\n\n    Return:\n        gathered_result: list with size equal to the process group where\n            gathered_result[i] corresponds to result tensor from process i\n    \"\"\"\n    if group is None:\n        group = torch.distributed.group.WORLD\n\n    # convert tensors to contiguous format\n    result = result.contiguous()\n\n    world_size = torch.distributed.get_world_size(group)\n\n    gathered_result = [torch.zeros_like(result) for _ in range(world_size)]\n\n    # sync and broadcast all\n    torch.distributed.barrier(group=group)\n    torch.distributed.all_gather(gathered_result, result, group)\n\n    return gathered_result\n\n\ndef sync_ddp_if_available(\n    result: Union[torch.Tensor],\n    group: Optional[Any] = None,\n    reduce_op: Optional[Union[ReduceOp, str]] = None\n) -> torch.Tensor:\n    \"\"\"\n    Function to reduce a tensor across worker processes during distributed training\n    Args:\n        result: the value to sync and reduce (typically tensor or number)\n        group: the process group to gather results from. Defaults to all processes (world)\n        reduce_op: the reduction operation. Defaults to sum.\n            Can also be a string of 'avg', 'mean' to calculate the mean during reduction.\n\n    Return:\n        reduced value\n    \"\"\"\n    if torch.distributed.is_available() and torch.distributed.is_initialized():\n        return sync_ddp(result, group=group, reduce_op=reduce_op)\n    return result\n\n\ndef sync_ddp(\n    result: Union[torch.Tensor],\n    group: Optional[Any] = None,\n    reduce_op: Optional[Union[ReduceOp, str]] = None\n) -> torch.Tensor:\n    \"\"\"\n    Function to reduce the tensors from several ddp processes to one master process\n\n    Args:\n        result: the value to sync and reduce (typically tensor or number)\n        group: the process group to gather results from. Defaults to all processes (world)\n        reduce_op: the reduction operation. Defaults to sum.\n            Can also be a string of 'avg', 'mean' to calculate the mean during reduction.\n\n    Return:\n        reduced value\n    \"\"\"\n    divide_by_world_size = False\n\n    if group is None:\n        group = torch.distributed.group.WORLD\n\n    op = reduce_op if isinstance(reduce_op, ReduceOp) else ReduceOp.SUM\n\n    if isinstance(reduce_op, str) and reduce_op.lower() in (\"avg\", \"mean\"):\n        divide_by_world_size = True\n\n    # sync all processes before reduction\n    torch.distributed.barrier(group=group)\n    torch.distributed.all_reduce(result, op=op, group=group, async_op=False)\n\n    if divide_by_world_size:\n        result = result / torch.distributed.get_world_size(group)\n\n    return result\n\n\nclass AllGatherGrad(torch.autograd.Function):\n\n    @staticmethod\n    def forward(ctx, tensor, group=group.WORLD):\n        ctx.group = group\n\n        gathered_tensor = [torch.zeros_like(tensor) for _ in range(torch.distributed.get_world_size())]\n\n        torch.distributed.all_gather(gathered_tensor, tensor, group=group)\n        gathered_tensor = torch.stack(gathered_tensor, dim=0)\n\n        return gathered_tensor\n\n    @staticmethod\n    def backward(ctx, *grad_output):\n        grad_output = torch.cat(grad_output)\n\n        torch.distributed.all_reduce(grad_output, op=torch.distributed.ReduceOp.SUM, async_op=False, group=ctx.group)\n\n        return grad_output[torch.distributed.get_rank()]\n\n\ndef all_gather_ddp_if_available(\n    tensor: Union[torch.Tensor], group: Optional[Any] = None, sync_grads: bool = False\n) -> torch.Tensor:\n    \"\"\"\n    Function to gather a tensor from several distributed processes\n\n    Args:\n        tensor: tensor of shape (batch, ...)\n        group: the process group to gather results from. Defaults to all processes (world)\n        sync_grads: flag that allows users to synchronize gradients for all_gather op\n\n    Return:\n        A tensor of shape (world_size, batch, ...)\n    \"\"\"\n    group = group if group is not None else torch.distributed.group.WORLD\n    if torch.distributed.is_available() and torch.distributed.is_initialized():\n        if sync_grads:\n            return AllGatherGrad.apply(tensor, group)\n        else:\n            with torch.no_grad():\n                return AllGatherGrad.apply(tensor, group)\n    return tensor\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/metrics/metric.py",
    "content": "# Copyright The PyTorch Lightning team.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\nfrom typing import Any, Callable, Dict, List, Optional, Tuple, Union\n\nimport torch\nfrom torchmetrics import Metric as _Metric\nfrom torchmetrics import MetricCollection as _MetricCollection\n\nfrom mmcv.metrics.distributed import rank_zero_warn\n\n\nclass Metric(_Metric):\n    r\"\"\"\n    This implementation refers to :class:`~torchmetrics.Metric`.\n\n    .. warning:: This metric is deprecated, use ``torchmetrics.Metric``. Will be removed in v1.5.0.\n    \"\"\"\n\n    def __init__(\n        self,\n        dist_sync_on_step: bool = False,\n        process_group: Optional[Any] = None,\n        dist_sync_fn: Callable = None,\n    ):\n        rank_zero_warn(\n            \"This `Metric` was deprecated since v1.3.0 in favor of `torchmetrics.Metric`.\"\n            \" It will be removed in v1.5.0\", DeprecationWarning\n        )\n        super().__init__(\n            dist_sync_on_step=dist_sync_on_step,\n            process_group=process_group,\n            dist_sync_fn=dist_sync_fn,\n        )\n\n    def __hash__(self):\n        return super().__hash__()\n\n    def __add__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.add, self, other)\n\n    def __and__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.bitwise_and, self, other)\n\n    def __eq__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.eq, self, other)\n\n    def __floordiv__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.floor_divide, self, other)\n\n    def __ge__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.ge, self, other)\n\n    def __gt__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.gt, self, other)\n\n    def __le__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.le, self, other)\n\n    def __lt__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.lt, self, other)\n\n    def __matmul__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.matmul, self, other)\n\n    def __mod__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.fmod, self, other)\n\n    def __mul__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.mul, self, other)\n\n    def __ne__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.ne, self, other)\n\n    def __or__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.bitwise_or, self, other)\n\n    def __pow__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.pow, self, other)\n\n    def __radd__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.add, other, self)\n\n    def __rand__(self, other: Any):\n        from .compositional import CompositionalMetric\n\n        # swap them since bitwise_and only supports that way and it's commutative\n        return CompositionalMetric(torch.bitwise_and, self, other)\n\n    def __rfloordiv__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.floor_divide, other, self)\n\n    def __rmatmul__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.matmul, other, self)\n\n    def __rmod__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.fmod, other, self)\n\n    def __rmul__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.mul, other, self)\n\n    def __ror__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.bitwise_or, other, self)\n\n    def __rpow__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.pow, other, self)\n\n    def __rsub__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.sub, other, self)\n\n    def __rtruediv__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.true_divide, other, self)\n\n    def __rxor__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.bitwise_xor, other, self)\n\n    def __sub__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.sub, self, other)\n\n    def __truediv__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.true_divide, self, other)\n\n    def __xor__(self, other: Any):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.bitwise_xor, self, other)\n\n    def __abs__(self):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.abs, self, None)\n\n    def __inv__(self):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.bitwise_not, self, None)\n\n    def __invert__(self):\n        return self.__inv__()\n\n    def __neg__(self):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(_neg, self, None)\n\n    def __pos__(self):\n        from .compositional import CompositionalMetric\n        return CompositionalMetric(torch.abs, self, None)\n\n\ndef _neg(tensor: torch.Tensor):\n    return -torch.abs(tensor)\n\n\nclass MetricCollection(_MetricCollection):\n    r\"\"\"\n    This implementation refers to :class:`~torchmetrics.MetricCollection`.\n\n    .. warning:: This metric is deprecated, use ``torchmetrics.MetricCollection``. Will be removed in v1.5.0.\n    \"\"\"\n\n    def __init__(self, metrics: Union[List[Metric], Tuple[Metric], Dict[str, Metric]]):\n        rank_zero_warn(\n            \"This `MetricCollection` was deprecated since v1.3.0 in favor of `torchmetrics.MetricCollection`.\"\n            \" It will be removed in v1.5.0\", DeprecationWarning\n        )\n        super().__init__(metrics=metrics)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/metrics/reduction.py",
    "content": "# Copyright The PyTorch Lightning team.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\nimport torch\n\nfrom .utils import reduce as __reduce\nfrom .distributed import rank_zero_warn\n\ndef reduce(to_reduce: torch.Tensor, reduction: str) -> torch.Tensor:\n    rank_zero_warn(\n        \"This `reduce` was deprecated in v1.1.0 in favor of\"\n        \" `mmcv.pytorch_lightning.metrics.utils import reduce`.\"\n        \" It will be removed in v1.3.0\", DeprecationWarning\n    )\n    return __reduce(to_reduce=to_reduce, reduction=reduction)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/metrics/utils.py",
    "content": "# Copyright The PyTorch Lightning team.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\nfrom typing import Optional, Tuple\n\nimport torch\n\nfrom .distributed import rank_zero_warn\n\nMETRIC_EPS = 1e-6\n\n\ndef dim_zero_cat(x):\n    x = x if isinstance(x, (list, tuple)) else [x]\n    return torch.cat(x, dim=0)\n\n\ndef dim_zero_sum(x):\n    return torch.sum(x, dim=0)\n\n\ndef dim_zero_mean(x):\n    return torch.mean(x, dim=0)\n\n\ndef _flatten(x):\n    return [item for sublist in x for item in sublist]\n\n\ndef _check_same_shape(pred: torch.Tensor, target: torch.Tensor):\n    \"\"\" Check that predictions and target have the same shape, else raise error \"\"\"\n    if pred.shape != target.shape:\n        raise RuntimeError(\"Predictions and targets are expected to have the same shape\")\n\n\ndef _input_format_classification_one_hot(\n    num_classes: int,\n    preds: torch.Tensor,\n    target: torch.Tensor,\n    threshold: float = 0.5,\n    multilabel: bool = False\n) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"Convert preds and target tensors into one hot spare label tensors\n\n    Args:\n        num_classes: number of classes\n        preds: either tensor with labels, tensor with probabilities/logits or\n            multilabel tensor\n        target: tensor with ground true labels\n        threshold: float used for thresholding multilabel input\n        multilabel: boolean flag indicating if input is multilabel\n\n    Returns:\n        preds: one hot tensor of shape [num_classes, -1] with predicted labels\n        target: one hot tensors of shape [num_classes, -1] with true labels\n    \"\"\"\n    if not (preds.ndim == target.ndim or preds.ndim == target.ndim + 1):\n        raise ValueError(\"preds and target must have same number of dimensions, or one additional dimension for preds\")\n\n    if preds.ndim == target.ndim + 1:\n        # multi class probabilites\n        preds = torch.argmax(preds, dim=1)\n\n    if preds.ndim == target.ndim and preds.dtype in (torch.long, torch.int) and num_classes > 1 and not multilabel:\n        # multi-class\n        preds = to_onehot(preds, num_classes=num_classes)\n        target = to_onehot(target, num_classes=num_classes)\n\n    elif preds.ndim == target.ndim and preds.is_floating_point():\n        # binary or multilabel probablities\n        preds = (preds >= threshold).long()\n\n    # transpose class as first dim and reshape\n    if preds.ndim > 1:\n        preds = preds.transpose(1, 0)\n        target = target.transpose(1, 0)\n\n    return preds.reshape(num_classes, -1), target.reshape(num_classes, -1)\n\n\ndef to_onehot(\n    label_tensor: torch.Tensor,\n    num_classes: Optional[int] = None,\n) -> torch.Tensor:\n    \"\"\"\n    Converts a dense label tensor to one-hot format\n\n    Args:\n        label_tensor: dense label tensor, with shape [N, d1, d2, ...]\n        num_classes: number of classes C\n\n    Output:\n        A sparse label tensor with shape [N, C, d1, d2, ...]\n\n    Example:\n\n        >>> x = torch.tensor([1, 2, 3])\n        >>> to_onehot(x)\n        tensor([[0, 1, 0, 0],\n                [0, 0, 1, 0],\n                [0, 0, 0, 1]])\n\n    \"\"\"\n    if num_classes is None:\n        num_classes = int(label_tensor.max().detach().item() + 1)\n\n    tensor_onehot = torch.zeros(\n        label_tensor.shape[0],\n        num_classes,\n        *label_tensor.shape[1:],\n        dtype=label_tensor.dtype,\n        device=label_tensor.device,\n    )\n    index = label_tensor.long().unsqueeze(1).expand_as(tensor_onehot)\n    return tensor_onehot.scatter_(1, index, 1.0)\n\n\ndef select_topk(prob_tensor: torch.Tensor, topk: int = 1, dim: int = 1) -> torch.Tensor:\n    \"\"\"\n    Convert a probability tensor to binary by selecting top-k highest entries.\n\n    Args:\n        prob_tensor: dense tensor of shape ``[..., C, ...]``, where ``C`` is in the\n            position defined by the ``dim`` argument\n        topk: number of highest entries to turn into 1s\n        dim: dimension on which to compare entries\n\n    Output:\n        A binary tensor of the same shape as the input tensor of type torch.int32\n\n    Example:\n        >>> x = torch.tensor([[1.1, 2.0, 3.0], [2.0, 1.0, 0.5]])\n        >>> select_topk(x, topk=2)\n        tensor([[0, 1, 1],\n                [1, 1, 0]], dtype=torch.int32)\n    \"\"\"\n    zeros = torch.zeros_like(prob_tensor)\n    topk_tensor = zeros.scatter(dim, prob_tensor.topk(k=topk, dim=dim).indices, 1.0)\n    return topk_tensor.int()\n\n\ndef to_categorical(tensor: torch.Tensor, argmax_dim: int = 1) -> torch.Tensor:\n    \"\"\"\n    Converts a tensor of probabilities to a dense label tensor\n\n    Args:\n        tensor: probabilities to get the categorical label [N, d1, d2, ...]\n        argmax_dim: dimension to apply\n\n    Return:\n        A tensor with categorical labels [N, d2, ...]\n\n    Example:\n\n        >>> x = torch.tensor([[0.2, 0.5], [0.9, 0.1]])\n        >>> to_categorical(x)\n        tensor([1, 0])\n\n    \"\"\"\n    return torch.argmax(tensor, dim=argmax_dim)\n\n\ndef get_num_classes(\n    pred: torch.Tensor,\n    target: torch.Tensor,\n    num_classes: Optional[int] = None,\n) -> int:\n    \"\"\"\n    Calculates the number of classes for a given prediction and target tensor.\n\n    Args:\n        pred: predicted values\n        target: true labels\n        num_classes: number of classes if known\n\n    Return:\n        An integer that represents the number of classes.\n    \"\"\"\n    num_target_classes = int(target.max().detach().item() + 1)\n    num_pred_classes = int(pred.max().detach().item() + 1)\n    num_all_classes = max(num_target_classes, num_pred_classes)\n\n    if num_classes is None:\n        num_classes = num_all_classes\n    elif num_classes != num_all_classes:\n        rank_zero_warn(\n            f\"You have set {num_classes} number of classes which is\"\n            f\" different from predicted ({num_pred_classes}) and\"\n            f\" target ({num_target_classes}) number of classes\",\n            RuntimeWarning,\n        )\n    return num_classes\n\n\ndef reduce(to_reduce: torch.Tensor, reduction: str) -> torch.Tensor:\n    \"\"\"\n    Reduces a given tensor by a given reduction method\n\n    Args:\n        to_reduce : the tensor, which shall be reduced\n       reduction :  a string specifying the reduction method ('elementwise_mean', 'none', 'sum')\n\n    Return:\n        reduced Tensor\n\n    Raise:\n        ValueError if an invalid reduction parameter was given\n    \"\"\"\n    if reduction == \"elementwise_mean\":\n        return torch.mean(to_reduce)\n    if reduction == \"none\":\n        return to_reduce\n    if reduction == \"sum\":\n        return torch.sum(to_reduce)\n    raise ValueError(\"Reduction parameter unknown.\")\n\n\ndef class_reduce(\n    num: torch.Tensor, denom: torch.Tensor, weights: torch.Tensor, class_reduction: str = \"none\"\n) -> torch.Tensor:\n    \"\"\"\n    Function used to reduce classification metrics of the form `num / denom * weights`.\n    For example for calculating standard accuracy the num would be number of\n    true positives per class, denom would be the support per class, and weights\n    would be a tensor of 1s\n\n    Args:\n        num: numerator tensor\n        denom: denominator tensor\n        weights: weights for each class\n        class_reduction: reduction method for multiclass problems\n\n            - ``'micro'``: calculate metrics globally (default)\n            - ``'macro'``: calculate metrics for each label, and find their unweighted mean.\n            - ``'weighted'``: calculate metrics for each label, and find their weighted mean.\n            - ``'none'`` or ``None``: returns calculated metric per class\n\n    Raises:\n        ValueError:\n            If ``class_reduction`` is none of ``\"micro\"``, ``\"macro\"``, ``\"weighted\"``, ``\"none\"`` or ``None``.\n    \"\"\"\n    valid_reduction = (\"micro\", \"macro\", \"weighted\", \"none\", None)\n    if class_reduction == \"micro\":\n        fraction = torch.sum(num) / torch.sum(denom)\n    else:\n        fraction = num / denom\n\n    # We need to take care of instances where the denom can be 0\n    # for some (or all) classes which will produce nans\n    fraction[fraction != fraction] = 0\n\n    if class_reduction == \"micro\":\n        return fraction\n    elif class_reduction == \"macro\":\n        return torch.mean(fraction)\n    elif class_reduction == \"weighted\":\n        return torch.sum(fraction * (weights.float() / torch.sum(weights)))\n    elif class_reduction == \"none\" or class_reduction is None:\n        return fraction\n\n    raise ValueError(\n        f\"Reduction parameter {class_reduction} unknown.\"\n        f\" Choose between one of these: {valid_reduction}\"\n    )\n\n\ndef _stable_1d_sort(x: torch, N: int = 2049):\n    \"\"\"\n    Stable sort of 1d tensors. Pytorch defaults to a stable sorting algorithm\n    if number of elements are larger than 2048. This function pads the tensors,\n    makes the sort and returns the sorted array (with the padding removed)\n    See this discussion: https://discuss.pytorch.org/t/is-torch-sort-stable/20714\n    \"\"\"\n    if x.ndim > 1:\n        raise ValueError('Stable sort only works on 1d tensors')\n    n = x.numel()\n    if N - n > 0:\n        x_max = x.max()\n        x = torch.cat([x, (x_max + 1) * torch.ones(N - n, dtype=x.dtype, device=x.device)], 0)\n    x_sort = x.sort()\n    i = min(N, n)\n    return x_sort.values[:i], x_sort.indices[:i]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/modeling/postprocessing.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nfrom torch.nn import functional as F\n\nfrom mmcv.structures import Instances, ROIMasks\n\n\n# perhaps should rename to \"resize_instance\"\ndef detector_postprocess(\n    results: Instances, output_height: int, output_width: int, mask_threshold: float = 0.5\n):\n    \"\"\"\n    Resize the output instances.\n    The input images are often resized when entering an object detector.\n    As a result, we often need the outputs of the detector in a different\n    resolution from its inputs.\n\n    This function will resize the raw outputs of an R-CNN detector\n    to produce outputs according to the desired output resolution.\n\n    Args:\n        results (Instances): the raw outputs from the detector.\n            `results.image_size` contains the input image resolution the detector sees.\n            This object might be modified in-place.\n        output_height, output_width: the desired output resolution.\n    Returns:\n        Instances: the resized output from the model, based on the output resolution\n    \"\"\"\n    if isinstance(output_width, torch.Tensor):\n        # This shape might (but not necessarily) be tensors during tracing.\n        # Converts integer tensors to float temporaries to ensure true\n        # division is performed when computing scale_x and scale_y.\n        output_width_tmp = output_width.float()\n        output_height_tmp = output_height.float()\n        new_size = torch.stack([output_height, output_width])\n    else:\n        new_size = (output_height, output_width)\n        output_width_tmp = output_width\n        output_height_tmp = output_height\n\n    scale_x, scale_y = (\n        output_width_tmp / results.image_size[1],\n        output_height_tmp / results.image_size[0],\n    )\n    results = Instances(new_size, **results.get_fields())\n\n    if results.has(\"pred_boxes\"):\n        output_boxes = results.pred_boxes\n    elif results.has(\"proposal_boxes\"):\n        output_boxes = results.proposal_boxes\n    else:\n        output_boxes = None\n    assert output_boxes is not None, \"Predictions must contain boxes!\"\n\n    output_boxes.scale(scale_x, scale_y)\n    output_boxes.clip(results.image_size)\n\n    results = results[output_boxes.nonempty()]\n\n    if results.has(\"pred_masks\"):\n        if isinstance(results.pred_masks, ROIMasks):\n            roi_masks = results.pred_masks\n        else:\n            # pred_masks is a tensor of shape (N, 1, M, M)\n            roi_masks = ROIMasks(results.pred_masks[:, 0, :, :])\n        results.pred_masks = roi_masks.to_bitmasks(\n            results.pred_boxes, output_height, output_width, mask_threshold\n        ).tensor  # TODO return ROIMasks/BitMask object in the future\n\n    if results.has(\"pred_keypoints\"):\n        results.pred_keypoints[:, :, 0] *= scale_x\n        results.pred_keypoints[:, :, 1] *= scale_y\n\n    return results\n\n\ndef sem_seg_postprocess(result, img_size, output_height, output_width):\n    \"\"\"\n    Return semantic segmentation predictions in the original resolution.\n\n    The input images are often resized when entering semantic segmentor. Moreover, in same\n    cases, they also padded inside segmentor to be divisible by maximum network stride.\n    As a result, we often need the predictions of the segmentor in a different\n    resolution from its inputs.\n\n    Args:\n        result (Tensor): semantic segmentation prediction logits. A tensor of shape (C, H, W),\n            where C is the number of classes, and H, W are the height and width of the prediction.\n        img_size (tuple): image size that segmentor is taking as input.\n        output_height, output_width: the desired output resolution.\n\n    Returns:\n        semantic segmentation prediction (Tensor): A tensor of the shape\n            (C, output_height, output_width) that contains per-pixel soft predictions.\n    \"\"\"\n    result = result[:, : img_size[0], : img_size[1]].expand(1, -1, -1, -1)\n    result = F.interpolate(\n        result, size=(output_height, output_width), mode=\"bilinear\", align_corners=False\n    )[0]\n    return result"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/__init__.py",
    "content": "from .backbones import *  # noqa: F401,F403\nfrom .builder import (BACKBONES, DETECTORS, HEADS, LOSSES, NECKS,\n                      ROI_EXTRACTORS, SHARED_HEADS, FUSION_LAYERS, \n                      MIDDLE_ENCODERS, VOXEL_ENCODERS, SEGMENTORS,\n                      build_backbone, build_detector, build_fusion_layer,\n                      build_head, build_loss, build_middle_encoder, \n                      build_model, build_neck, build_roi_extractor, \n                      build_shared_head, build_voxel_encoder, build_segmentor)\nfrom .dense_heads import *  # noqa: F401,F403\nfrom .detectors import *  # noqa: F401,F403\nfrom .losses import *  # noqa: F401,F403\nfrom .necks import *  # noqa: F401,F403\nfrom .bricks import *\nfrom .utils import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/backbones/__init__.py",
    "content": "from .resnet import ResNet, ResNetV1d\nfrom  .vgg import VGG\nfrom .base_module import BaseModule, ModuleList, Sequential\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/backbones/base_module.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport warnings\nfrom abc import ABCMeta\nfrom collections import defaultdict\nfrom logging import FileHandler\n\nimport torch.nn as nn\n\nfrom mmcv.utils import master_only\nfrom mmcv.utils.logging import get_logger, logger_initialized, print_log\n\n\nclass BaseModule(nn.Module, metaclass=ABCMeta):\n    \"\"\"Base module for all modules in openmmlab.\n\n    ``BaseModule`` is a wrapper of ``torch.nn.Module`` with additional\n    functionality of parameter initialization. Compared with\n    ``torch.nn.Module``, ``BaseModule`` mainly adds three attributes.\n\n        - ``init_cfg``: the config to control the initialization.\n        - ``init_weights``: The function of parameter\n            initialization and recording initialization\n            information.\n        - ``_params_init_info``: Used to track the parameter\n            initialization information. This attribute only\n            exists during executing the ``init_weights``.\n\n    Args:\n        init_cfg (dict, optional): Initialization config dict.\n    \"\"\"\n\n    def __init__(self, init_cfg=None):\n        \"\"\"Initialize BaseModule, inherited from `torch.nn.Module`\"\"\"\n\n        # NOTE init_cfg can be defined in different levels, but init_cfg\n        # in low levels has a higher priority.\n\n        super(BaseModule, self).__init__()\n        # define default value of init_cfg instead of hard code\n        # in init_weights() function\n        self._is_init = False\n\n        self.init_cfg = copy.deepcopy(init_cfg)\n\n        # Backward compatibility in derived classes\n        # if pretrained is not None:\n        #     warnings.warn('DeprecationWarning: pretrained is a deprecated \\\n        #         key, please consider using init_cfg')\n        #     self.init_cfg = dict(type='Pretrained', checkpoint=pretrained)\n\n    @property\n    def is_init(self):\n        return self._is_init\n\n    def init_weights(self):\n        \"\"\"Initialize the weights.\"\"\"\n\n        is_top_level_module = False\n        # check if it is top-level module\n        if not hasattr(self, '_params_init_info'):\n            # The `_params_init_info` is used to record the initialization\n            # information of the parameters\n            # the key should be the obj:`nn.Parameter` of model and the value\n            # should be a dict containing\n            # - init_info (str): The string that describes the initialization.\n            # - tmp_mean_value (FloatTensor): The mean of the parameter,\n            #       which indicates whether the parameter has been modified.\n            # this attribute would be deleted after all parameters\n            # is initialized.\n            self._params_init_info = defaultdict(dict)\n            is_top_level_module = True\n\n            # Initialize the `_params_init_info`,\n            # When detecting the `tmp_mean_value` of\n            # the corresponding parameter is changed, update related\n            # initialization information\n            for name, param in self.named_parameters():\n                self._params_init_info[param][\n                    'init_info'] = f'The value is the same before and ' \\\n                                   f'after calling `init_weights` ' \\\n                                   f'of {self.__class__.__name__} '\n                self._params_init_info[param][\n                    'tmp_mean_value'] = param.data.mean()\n\n            # pass `params_init_info` to all submodules\n            # All submodules share the same `params_init_info`,\n            # so it will be updated when parameters are\n            # modified at any level of the model.\n            for sub_module in self.modules():\n                sub_module._params_init_info = self._params_init_info\n\n        # Get the initialized logger, if not exist,\n        # create a logger named `mmcv`\n        logger_names = list(logger_initialized.keys())\n        logger_name = logger_names[0] if logger_names else 'mmcv'\n\n        from ..utils import initialize\n        from ..utils.weight_init import update_init_info\n        module_name = self.__class__.__name__\n        if not self._is_init:\n            if self.init_cfg:\n                print_log(\n                    f'initialize {module_name} with init_cfg {self.init_cfg}',\n                    logger=logger_name)\n                initialize(self, self.init_cfg)\n                if isinstance(self.init_cfg, dict):\n                    # prevent the parameters of\n                    # the pre-trained model\n                    # from being overwritten by\n                    # the `init_weights`\n                    if self.init_cfg['type'] == 'Pretrained':\n                        return\n\n            for m in self.children():\n                if hasattr(m, 'init_weights'):\n                    m.init_weights()\n                    # users may overload the `init_weights`\n                    update_init_info(\n                        m,\n                        init_info=f'Initialized by '\n                        f'user-defined `init_weights`'\n                        f' in {m.__class__.__name__} ')\n\n            self._is_init = True\n        else:\n            warnings.warn(f'init_weights of {self.__class__.__name__} has '\n                          f'been called more than once.')\n\n        if is_top_level_module:\n            self._dump_init_info(logger_name)\n\n            for sub_module in self.modules():\n                del sub_module._params_init_info\n\n    @master_only\n    def _dump_init_info(self, logger_name):\n        \"\"\"Dump the initialization information to a file named\n        `initialization.log.json` in workdir.\n\n        Args:\n            logger_name (str): The name of logger.\n        \"\"\"\n\n        logger = get_logger(logger_name)\n\n        with_file_handler = False\n        # dump the information to the logger file if there is a `FileHandler`\n        for handler in logger.handlers:\n            if isinstance(handler, FileHandler):\n                handler.stream.write(\n                    'Name of parameter - Initialization information\\n')\n                for name, param in self.named_parameters():\n                    handler.stream.write(\n                        f'\\n{name} - {param.shape}: '\n                        f\"\\n{self._params_init_info[param]['init_info']} \\n\")\n                handler.stream.flush()\n                with_file_handler = True\n        if not with_file_handler:\n            for name, param in self.named_parameters():\n                print_log(\n                    f'\\n{name} - {param.shape}: '\n                    f\"\\n{self._params_init_info[param]['init_info']} \\n \",\n                    logger=logger_name)\n\n    def __repr__(self):\n        s = super().__repr__()\n        if self.init_cfg:\n            s += f'\\ninit_cfg={self.init_cfg}'\n        return s\n\n\nclass Sequential(BaseModule, nn.Sequential):\n    \"\"\"Sequential module in openmmlab.\n\n    Args:\n        init_cfg (dict, optional): Initialization config dict.\n    \"\"\"\n\n    def __init__(self, *args, init_cfg=None):\n        BaseModule.__init__(self, init_cfg)\n        nn.Sequential.__init__(self, *args)\n\n\nclass ModuleList(BaseModule, nn.ModuleList):\n    \"\"\"ModuleList in openmmlab.\n\n    Args:\n        modules (iterable, optional): an iterable of modules to add.\n        init_cfg (dict, optional): Initialization config dict.\n    \"\"\"\n\n    def __init__(self, modules=None, init_cfg=None):\n        BaseModule.__init__(self, init_cfg)\n        nn.ModuleList.__init__(self, modules)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/backbones/resnet.py",
    "content": "import warnings\n\nimport torch.nn as nn\nimport torch.utils.checkpoint as cp\nfrom mmcv.models.bricks import build_conv_layer, build_norm_layer, build_plugin_layer\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom torch.nn.modules.batchnorm import _BatchNorm\n\nfrom ..builder import BACKBONES\nfrom ..utils import ResLayer\n\n\nclass BasicBlock(BaseModule):\n    expansion = 1\n\n    def __init__(self,\n                 inplanes,\n                 planes,\n                 stride=1,\n                 dilation=1,\n                 downsample=None,\n                 style='pytorch',\n                 with_cp=False,\n                 conv_cfg=None,\n                 norm_cfg=dict(type='BN'),\n                 dcn=None,\n                 plugins=None,\n                 init_cfg=None):\n        super(BasicBlock, self).__init__(init_cfg)\n        assert dcn is None, 'Not implemented yet.'\n        assert plugins is None, 'Not implemented yet.'\n\n        self.norm1_name, norm1 = build_norm_layer(norm_cfg, planes, postfix=1)\n        self.norm2_name, norm2 = build_norm_layer(norm_cfg, planes, postfix=2)\n\n        self.conv1 = build_conv_layer(\n            conv_cfg,\n            inplanes,\n            planes,\n            3,\n            stride=stride,\n            padding=dilation,\n            dilation=dilation,\n            bias=False)\n        self.add_module(self.norm1_name, norm1)\n        self.conv2 = build_conv_layer(\n            conv_cfg, planes, planes, 3, padding=1, bias=False)\n        self.add_module(self.norm2_name, norm2)\n\n        self.relu = nn.ReLU(inplace=True)\n        self.downsample = downsample\n        self.stride = stride\n        self.dilation = dilation\n        self.with_cp = with_cp\n\n    @property\n    def norm1(self):\n        \"\"\"nn.Module: normalization layer after the first convolution layer\"\"\"\n        return getattr(self, self.norm1_name)\n\n    @property\n    def norm2(self):\n        \"\"\"nn.Module: normalization layer after the second convolution layer\"\"\"\n        return getattr(self, self.norm2_name)\n\n    def forward(self, x):\n        \"\"\"Forward function.\"\"\"\n\n        def _inner_forward(x):\n            identity = x\n\n            out = self.conv1(x)\n            out = self.norm1(out)\n            out = self.relu(out)\n\n            out = self.conv2(out)\n            out = self.norm2(out)\n\n            if self.downsample is not None:\n                identity = self.downsample(x)\n\n            out += identity\n\n            return out\n\n        if self.with_cp and x.requires_grad:\n            out = cp.checkpoint(_inner_forward, x)\n        else:\n            out = _inner_forward(x)\n\n        out = self.relu(out)\n\n        return out\n\n\nclass Bottleneck(BaseModule):\n    expansion = 4\n\n    def __init__(self,\n                 inplanes,\n                 planes,\n                 stride=1,\n                 dilation=1,\n                 downsample=None,\n                 style='pytorch',\n                 with_cp=False,\n                 conv_cfg=None,\n                 norm_cfg=dict(type='BN'),\n                 dcn=None,\n                 plugins=None,\n                 init_cfg=None):\n        \"\"\"Bottleneck block for ResNet.\n\n        If style is \"pytorch\", the stride-two layer is the 3x3 conv layer, if\n        it is \"caffe\", the stride-two layer is the first 1x1 conv layer.\n        \"\"\"\n        super(Bottleneck, self).__init__(init_cfg)\n        assert style in ['pytorch', 'caffe']\n        assert dcn is None or isinstance(dcn, dict)\n        assert plugins is None or isinstance(plugins, list)\n        if plugins is not None:\n            allowed_position = ['after_conv1', 'after_conv2', 'after_conv3']\n            assert all(p['position'] in allowed_position for p in plugins)\n\n        self.inplanes = inplanes\n        self.planes = planes\n        self.stride = stride\n        self.dilation = dilation\n        self.style = style\n        self.with_cp = with_cp\n        self.conv_cfg = conv_cfg\n        self.norm_cfg = norm_cfg\n        self.dcn = dcn\n        self.with_dcn = dcn is not None\n        self.plugins = plugins\n        self.with_plugins = plugins is not None\n\n        if self.with_plugins:\n            # collect plugins for conv1/conv2/conv3\n            self.after_conv1_plugins = [\n                plugin['cfg'] for plugin in plugins\n                if plugin['position'] == 'after_conv1'\n            ]\n            self.after_conv2_plugins = [\n                plugin['cfg'] for plugin in plugins\n                if plugin['position'] == 'after_conv2'\n            ]\n            self.after_conv3_plugins = [\n                plugin['cfg'] for plugin in plugins\n                if plugin['position'] == 'after_conv3'\n            ]\n\n        if self.style == 'pytorch':\n            self.conv1_stride = 1\n            self.conv2_stride = stride\n        else:\n            self.conv1_stride = stride\n            self.conv2_stride = 1\n\n        self.norm1_name, norm1 = build_norm_layer(norm_cfg, planes, postfix=1)\n        self.norm2_name, norm2 = build_norm_layer(norm_cfg, planes, postfix=2)\n        self.norm3_name, norm3 = build_norm_layer(\n            norm_cfg, planes * self.expansion, postfix=3)\n\n        self.conv1 = build_conv_layer(\n            conv_cfg,\n            inplanes,\n            planes,\n            kernel_size=1,\n            stride=self.conv1_stride,\n            bias=False)\n        self.add_module(self.norm1_name, norm1)\n        fallback_on_stride = False\n        if self.with_dcn:\n            fallback_on_stride = dcn.pop('fallback_on_stride', False)\n        if not self.with_dcn or fallback_on_stride:\n            self.conv2 = build_conv_layer(\n                conv_cfg,\n                planes,\n                planes,\n                kernel_size=3,\n                stride=self.conv2_stride,\n                padding=dilation,\n                dilation=dilation,\n                bias=False)\n        else:\n            assert self.conv_cfg is None, 'conv_cfg must be None for DCN'\n            self.conv2 = build_conv_layer(\n                dcn,\n                planes,\n                planes,\n                kernel_size=3,\n                stride=self.conv2_stride,\n                padding=dilation,\n                dilation=dilation,\n                bias=False)\n\n        self.add_module(self.norm2_name, norm2)\n        self.conv3 = build_conv_layer(\n            conv_cfg,\n            planes,\n            planes * self.expansion,\n            kernel_size=1,\n            bias=False)\n        self.add_module(self.norm3_name, norm3)\n\n        self.relu = nn.ReLU(inplace=True)\n        self.downsample = downsample\n\n        if self.with_plugins:\n            self.after_conv1_plugin_names = self.make_block_plugins(\n                planes, self.after_conv1_plugins)\n            self.after_conv2_plugin_names = self.make_block_plugins(\n                planes, self.after_conv2_plugins)\n            self.after_conv3_plugin_names = self.make_block_plugins(\n                planes * self.expansion, self.after_conv3_plugins)\n\n    def make_block_plugins(self, in_channels, plugins):\n        \"\"\"make plugins for block.\n\n        Args:\n            in_channels (int): Input channels of plugin.\n            plugins (list[dict]): List of plugins cfg to build.\n\n        Returns:\n            list[str]: List of the names of plugin.\n        \"\"\"\n        assert isinstance(plugins, list)\n        plugin_names = []\n        for plugin in plugins:\n            plugin = plugin.copy()\n            name, layer = build_plugin_layer(\n                plugin,\n                in_channels=in_channels,\n                postfix=plugin.pop('postfix', ''))\n            assert not hasattr(self, name), f'duplicate plugin {name}'\n            self.add_module(name, layer)\n            plugin_names.append(name)\n        return plugin_names\n\n    def forward_plugin(self, x, plugin_names):\n        out = x\n        for name in plugin_names:\n            out = getattr(self, name)(x)\n        return out\n\n    @property\n    def norm1(self):\n        \"\"\"nn.Module: normalization layer after the first convolution layer\"\"\"\n        return getattr(self, self.norm1_name)\n\n    @property\n    def norm2(self):\n        \"\"\"nn.Module: normalization layer after the second convolution layer\"\"\"\n        return getattr(self, self.norm2_name)\n\n    @property\n    def norm3(self):\n        \"\"\"nn.Module: normalization layer after the third convolution layer\"\"\"\n        return getattr(self, self.norm3_name)\n\n    def forward(self, x):\n        \"\"\"Forward function.\"\"\"\n\n        def _inner_forward(x):\n            identity = x\n            out = self.conv1(x)\n            out = self.norm1(out)\n            out = self.relu(out)\n\n            if self.with_plugins:\n                out = self.forward_plugin(out, self.after_conv1_plugin_names)\n\n            out = self.conv2(out)\n            out = self.norm2(out)\n            out = self.relu(out)\n\n            if self.with_plugins:\n                out = self.forward_plugin(out, self.after_conv2_plugin_names)\n\n            out = self.conv3(out)\n            out = self.norm3(out)\n\n            if self.with_plugins:\n                out = self.forward_plugin(out, self.after_conv3_plugin_names)\n\n            if self.downsample is not None:\n                identity = self.downsample(x)\n\n            out += identity\n\n            return out\n\n        if self.with_cp and x.requires_grad:\n            out = cp.checkpoint(_inner_forward, x)\n        else:\n            out = _inner_forward(x)\n\n        out = self.relu(out)\n\n        return out\n\n\n@BACKBONES.register_module()\nclass ResNet(BaseModule):\n    \"\"\"ResNet backbone.\n\n    Args:\n        depth (int): Depth of resnet, from {18, 34, 50, 101, 152}.\n        stem_channels (int | None): Number of stem channels. If not specified,\n            it will be the same as `base_channels`. Default: None.\n        base_channels (int): Number of base channels of res layer. Default: 64.\n        in_channels (int): Number of input image channels. Default: 3.\n        num_stages (int): Resnet stages. Default: 4.\n        strides (Sequence[int]): Strides of the first block of each stage.\n        dilations (Sequence[int]): Dilation of each stage.\n        out_indices (Sequence[int]): Output from which stages.\n        style (str): `pytorch` or `caffe`. If set to \"pytorch\", the stride-two\n            layer is the 3x3 conv layer, otherwise the stride-two layer is\n            the first 1x1 conv layer.\n        deep_stem (bool): Replace 7x7 conv in input stem with 3 3x3 conv\n        avg_down (bool): Use AvgPool instead of stride conv when\n            downsampling in the bottleneck.\n        frozen_stages (int): Stages to be frozen (stop grad and set eval mode).\n            -1 means not freezing any parameters.\n        norm_cfg (dict): Dictionary to construct and config norm layer.\n        norm_eval (bool): Whether to set norm layers to eval mode, namely,\n            freeze running stats (mean and var). Note: Effect on Batch Norm\n            and its variants only.\n        plugins (list[dict]): List of plugins for stages, each dict contains:\n\n            - cfg (dict, required): Cfg dict to build plugin.\n            - position (str, required): Position inside block to insert\n              plugin, options are 'after_conv1', 'after_conv2', 'after_conv3'.\n            - stages (tuple[bool], optional): Stages to apply plugin, length\n              should be same as 'num_stages'.\n        with_cp (bool): Use checkpoint or not. Using checkpoint will save some\n            memory while slowing down the training speed.\n        zero_init_residual (bool): Whether to use zero init for last norm layer\n            in resblocks to let them behave as identity.\n        pretrained (str, optional): model pretrained path. Default: None\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n            Default: None\n\n    Example:\n        >>> from mmcv.models import ResNet\n        >>> import torch\n        >>> self = ResNet(depth=18)\n        >>> self.eval()\n        >>> inputs = torch.rand(1, 3, 32, 32)\n        >>> level_outputs = self.forward(inputs)\n        >>> for level_out in level_outputs:\n        ...     print(tuple(level_out.shape))\n        (1, 64, 8, 8)\n        (1, 128, 4, 4)\n        (1, 256, 2, 2)\n        (1, 512, 1, 1)\n    \"\"\"\n\n    arch_settings = {\n        18: (BasicBlock, (2, 2, 2, 2)),\n        34: (BasicBlock, (3, 4, 6, 3)),\n        50: (Bottleneck, (3, 4, 6, 3)),\n        101: (Bottleneck, (3, 4, 23, 3)),\n        152: (Bottleneck, (3, 8, 36, 3))\n    }\n\n    def __init__(self,\n                 depth,\n                 in_channels=3,\n                 stem_channels=None,\n                 base_channels=64,\n                 num_stages=4,\n                 strides=(1, 2, 2, 2),\n                 dilations=(1, 1, 1, 1),\n                 out_indices=(0, 1, 2, 3),\n                 style='pytorch',\n                 deep_stem=False,\n                 avg_down=False,\n                 frozen_stages=-1,\n                 conv_cfg=None,\n                 norm_cfg=dict(type='BN', requires_grad=True),\n                 norm_eval=True,\n                 dcn=None,\n                 stage_with_dcn=(False, False, False, False),\n                 plugins=None,\n                 with_cp=False,\n                 zero_init_residual=True,\n                 pretrained=None,\n                 init_cfg=None):\n        super(ResNet, self).__init__(init_cfg)\n        self.zero_init_residual = zero_init_residual\n        if depth not in self.arch_settings:\n            raise KeyError(f'invalid depth {depth} for resnet')\n\n        block_init_cfg = None\n        assert not (init_cfg and pretrained), \\\n            'init_cfg and pretrained cannot be setting at the same time'\n        if isinstance(pretrained, str):\n            warnings.warn('DeprecationWarning: pretrained is deprecated, '\n                          'please use \"init_cfg\" instead')\n            self.init_cfg = dict(type='Pretrained', checkpoint=pretrained)\n        elif pretrained is None:\n            if init_cfg is None:\n                self.init_cfg = [\n                    dict(type='Kaiming', layer='Conv2d'),\n                    dict(\n                        type='Constant',\n                        val=1,\n                        layer=['_BatchNorm', 'GroupNorm'])\n                ]\n                block = self.arch_settings[depth][0]\n                if self.zero_init_residual:\n                    if block is BasicBlock:\n                        block_init_cfg = dict(\n                            type='Constant',\n                            val=0,\n                            override=dict(name='norm2'))\n                    elif block is Bottleneck:\n                        block_init_cfg = dict(\n                            type='Constant',\n                            val=0,\n                            override=dict(name='norm3'))\n        else:\n            raise TypeError('pretrained must be a str or None')\n\n        self.depth = depth\n        if stem_channels is None:\n            stem_channels = base_channels\n        self.stem_channels = stem_channels\n        self.base_channels = base_channels\n        self.num_stages = num_stages\n        assert num_stages >= 1 and num_stages <= 4\n        self.strides = strides\n        self.dilations = dilations\n        assert len(strides) == len(dilations) == num_stages\n        self.out_indices = out_indices\n        assert max(out_indices) < num_stages\n        self.style = style\n        self.deep_stem = deep_stem\n        self.avg_down = avg_down\n        self.frozen_stages = frozen_stages\n        self.conv_cfg = conv_cfg\n        self.norm_cfg = norm_cfg\n        self.with_cp = with_cp\n        self.norm_eval = norm_eval\n        self.dcn = dcn\n        self.stage_with_dcn = stage_with_dcn\n        if dcn is not None:\n            assert len(stage_with_dcn) == num_stages\n        self.plugins = plugins\n        self.block, stage_blocks = self.arch_settings[depth]\n        self.stage_blocks = stage_blocks[:num_stages]\n        self.inplanes = stem_channels\n\n        self._make_stem_layer(in_channels, stem_channels)\n\n        self.res_layers = []\n        for i, num_blocks in enumerate(self.stage_blocks):\n            stride = strides[i]\n            dilation = dilations[i]\n            dcn = self.dcn if self.stage_with_dcn[i] else None\n            if plugins is not None:\n                stage_plugins = self.make_stage_plugins(plugins, i)\n            else:\n                stage_plugins = None\n            planes = base_channels * 2**i\n            res_layer = self.make_res_layer(\n                block=self.block,\n                inplanes=self.inplanes,\n                planes=planes,\n                num_blocks=num_blocks,\n                stride=stride,\n                dilation=dilation,\n                style=self.style,\n                avg_down=self.avg_down,\n                with_cp=with_cp,\n                conv_cfg=conv_cfg,\n                norm_cfg=norm_cfg,\n                dcn=dcn,\n                plugins=stage_plugins,\n                init_cfg=block_init_cfg)\n            self.inplanes = planes * self.block.expansion\n            layer_name = f'layer{i + 1}'\n            self.add_module(layer_name, res_layer)\n            self.res_layers.append(layer_name)\n\n        self._freeze_stages()\n\n        self.feat_dim = self.block.expansion * base_channels * 2**(\n            len(self.stage_blocks) - 1)\n\n    def make_stage_plugins(self, plugins, stage_idx):\n        \"\"\"Make plugins for ResNet ``stage_idx`` th stage.\n\n        Currently we support to insert ``context_block``,\n        ``empirical_attention_block``, ``nonlocal_block`` into the backbone\n        like ResNet/ResNeXt. They could be inserted after conv1/conv2/conv3 of\n        Bottleneck.\n\n        An example of plugins format could be:\n\n        Examples:\n            >>> plugins=[\n            ...     dict(cfg=dict(type='xxx', arg1='xxx'),\n            ...          stages=(False, True, True, True),\n            ...          position='after_conv2'),\n            ...     dict(cfg=dict(type='yyy'),\n            ...          stages=(True, True, True, True),\n            ...          position='after_conv3'),\n            ...     dict(cfg=dict(type='zzz', postfix='1'),\n            ...          stages=(True, True, True, True),\n            ...          position='after_conv3'),\n            ...     dict(cfg=dict(type='zzz', postfix='2'),\n            ...          stages=(True, True, True, True),\n            ...          position='after_conv3')\n            ... ]\n            >>> self = ResNet(depth=18)\n            >>> stage_plugins = self.make_stage_plugins(plugins, 0)\n            >>> assert len(stage_plugins) == 3\n\n        Suppose ``stage_idx=0``, the structure of blocks in the stage would be:\n\n        .. code-block:: none\n\n            conv1-> conv2->conv3->yyy->zzz1->zzz2\n\n        Suppose 'stage_idx=1', the structure of blocks in the stage would be:\n\n        .. code-block:: none\n\n            conv1-> conv2->xxx->conv3->yyy->zzz1->zzz2\n\n        If stages is missing, the plugin would be applied to all stages.\n\n        Args:\n            plugins (list[dict]): List of plugins cfg to build. The postfix is\n                required if multiple same type plugins are inserted.\n            stage_idx (int): Index of stage to build\n\n        Returns:\n            list[dict]: Plugins for current stage\n        \"\"\"\n        stage_plugins = []\n        for plugin in plugins:\n            plugin = plugin.copy()\n            stages = plugin.pop('stages', None)\n            assert stages is None or len(stages) == self.num_stages\n            # whether to insert plugin into current stage\n            if stages is None or stages[stage_idx]:\n                stage_plugins.append(plugin)\n\n        return stage_plugins\n\n    def make_res_layer(self, **kwargs):\n        \"\"\"Pack all blocks in a stage into a ``ResLayer``.\"\"\"\n        return ResLayer(**kwargs)\n\n    @property\n    def norm1(self):\n        \"\"\"nn.Module: the normalization layer named \"norm1\" \"\"\"\n        return getattr(self, self.norm1_name)\n\n    def _make_stem_layer(self, in_channels, stem_channels):\n        if self.deep_stem:\n            self.stem = nn.Sequential(\n                build_conv_layer(\n                    self.conv_cfg,\n                    in_channels,\n                    stem_channels // 2,\n                    kernel_size=3,\n                    stride=2,\n                    padding=1,\n                    bias=False),\n                build_norm_layer(self.norm_cfg, stem_channels // 2)[1],\n                nn.ReLU(inplace=True),\n                build_conv_layer(\n                    self.conv_cfg,\n                    stem_channels // 2,\n                    stem_channels // 2,\n                    kernel_size=3,\n                    stride=1,\n                    padding=1,\n                    bias=False),\n                build_norm_layer(self.norm_cfg, stem_channels // 2)[1],\n                nn.ReLU(inplace=True),\n                build_conv_layer(\n                    self.conv_cfg,\n                    stem_channels // 2,\n                    stem_channels,\n                    kernel_size=3,\n                    stride=1,\n                    padding=1,\n                    bias=False),\n                build_norm_layer(self.norm_cfg, stem_channels)[1],\n                nn.ReLU(inplace=True))\n        else:\n            self.conv1 = build_conv_layer(\n                self.conv_cfg,\n                in_channels,\n                stem_channels,\n                kernel_size=7,\n                stride=2,\n                padding=3,\n                bias=False)\n            self.norm1_name, norm1 = build_norm_layer(\n                self.norm_cfg, stem_channels, postfix=1)\n            self.add_module(self.norm1_name, norm1)\n            self.relu = nn.ReLU(inplace=True)\n        self.maxpool = nn.MaxPool2d(kernel_size=3, stride=2, padding=1)\n\n    def _freeze_stages(self):\n        if self.frozen_stages >= 0:\n            if self.deep_stem:\n                self.stem.eval()\n                for param in self.stem.parameters():\n                    param.requires_grad = False\n            else:\n                self.norm1.eval()\n                for m in [self.conv1, self.norm1]:\n                    for param in m.parameters():\n                        param.requires_grad = False\n\n        for i in range(1, self.frozen_stages + 1):\n            m = getattr(self, f'layer{i}')\n            m.eval()\n            for param in m.parameters():\n                param.requires_grad = False\n\n    def forward(self, x):\n        \"\"\"Forward function.\"\"\"\n        if self.deep_stem:\n            x = self.stem(x)\n        else:\n            x = self.conv1(x)\n            x = self.norm1(x)\n            x = self.relu(x)\n        x = self.maxpool(x)\n        outs = []\n        for i, layer_name in enumerate(self.res_layers):\n            res_layer = getattr(self, layer_name)\n            x = res_layer(x)\n            if i in self.out_indices:\n                outs.append(x)\n        return tuple(outs)\n\n    def train(self, mode=True):\n        \"\"\"Convert the model into training mode while keep normalization layer\n        freezed.\"\"\"\n        super(ResNet, self).train(mode)\n        self._freeze_stages()\n        if mode and self.norm_eval:\n            for m in self.modules():\n                # trick: eval have effect on BatchNorm only\n                if isinstance(m, _BatchNorm):\n                    m.eval()\n\n\n@BACKBONES.register_module()\nclass ResNetV1d(ResNet):\n    r\"\"\"ResNetV1d variant described in `Bag of Tricks\n    <https://arxiv.org/pdf/1812.01187.pdf>`_.\n\n    Compared with default ResNet(ResNetV1b), ResNetV1d replaces the 7x7 conv in\n    the input stem with three 3x3 convs. And in the downsampling block, a 2x2\n    avg_pool with stride 2 is added before conv, whose stride is changed to 1.\n    \"\"\"\n\n    def __init__(self, **kwargs):\n        super(ResNetV1d, self).__init__(\n            deep_stem=True, avg_down=True, **kwargs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/backbones/vgg.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport logging\n\nimport torch.nn as nn\n\nfrom ..utils.weight_init import constant_init, kaiming_init, normal_init\n\n\ndef conv3x3(in_planes, out_planes, dilation=1):\n    \"\"\"3x3 convolution with padding.\"\"\"\n    return nn.Conv2d(\n        in_planes,\n        out_planes,\n        kernel_size=3,\n        padding=dilation,\n        dilation=dilation)\n\n\ndef make_vgg_layer(inplanes,\n                   planes,\n                   num_blocks,\n                   dilation=1,\n                   with_bn=False,\n                   ceil_mode=False):\n    layers = []\n    for _ in range(num_blocks):\n        layers.append(conv3x3(inplanes, planes, dilation))\n        if with_bn:\n            layers.append(nn.BatchNorm2d(planes))\n        layers.append(nn.ReLU(inplace=True))\n        inplanes = planes\n    layers.append(nn.MaxPool2d(kernel_size=2, stride=2, ceil_mode=ceil_mode))\n\n    return layers\n\n\nclass VGG(nn.Module):\n    \"\"\"VGG backbone.\n\n    Args:\n        depth (int): Depth of vgg, from {11, 13, 16, 19}.\n        with_bn (bool): Use BatchNorm or not.\n        num_classes (int): number of classes for classification.\n        num_stages (int): VGG stages, normally 5.\n        dilations (Sequence[int]): Dilation of each stage.\n        out_indices (Sequence[int]): Output from which stages.\n        frozen_stages (int): Stages to be frozen (all param fixed). -1 means\n            not freezing any parameters.\n        bn_eval (bool): Whether to set BN layers as eval mode, namely, freeze\n            running stats (mean and var).\n        bn_frozen (bool): Whether to freeze weight and bias of BN layers.\n    \"\"\"\n\n    arch_settings = {\n        11: (1, 1, 2, 2, 2),\n        13: (2, 2, 2, 2, 2),\n        16: (2, 2, 3, 3, 3),\n        19: (2, 2, 4, 4, 4)\n    }\n\n    def __init__(self,\n                 depth,\n                 with_bn=False,\n                 num_classes=-1,\n                 num_stages=5,\n                 dilations=(1, 1, 1, 1, 1),\n                 out_indices=(0, 1, 2, 3, 4),\n                 frozen_stages=-1,\n                 bn_eval=True,\n                 bn_frozen=False,\n                 ceil_mode=False,\n                 with_last_pool=True):\n        super(VGG, self).__init__()\n        if depth not in self.arch_settings:\n            raise KeyError(f'invalid depth {depth} for vgg')\n        assert num_stages >= 1 and num_stages <= 5\n        stage_blocks = self.arch_settings[depth]\n        self.stage_blocks = stage_blocks[:num_stages]\n        assert len(dilations) == num_stages\n        assert max(out_indices) <= num_stages\n\n        self.num_classes = num_classes\n        self.out_indices = out_indices\n        self.frozen_stages = frozen_stages\n        self.bn_eval = bn_eval\n        self.bn_frozen = bn_frozen\n\n        self.inplanes = 3\n        start_idx = 0\n        vgg_layers = []\n        self.range_sub_modules = []\n        for i, num_blocks in enumerate(self.stage_blocks):\n            num_modules = num_blocks * (2 + with_bn) + 1\n            end_idx = start_idx + num_modules\n            dilation = dilations[i]\n            planes = 64 * 2**i if i < 4 else 512\n            vgg_layer = make_vgg_layer(\n                self.inplanes,\n                planes,\n                num_blocks,\n                dilation=dilation,\n                with_bn=with_bn,\n                ceil_mode=ceil_mode)\n            vgg_layers.extend(vgg_layer)\n            self.inplanes = planes\n            self.range_sub_modules.append([start_idx, end_idx])\n            start_idx = end_idx\n        if not with_last_pool:\n            vgg_layers.pop(-1)\n            self.range_sub_modules[-1][1] -= 1\n        self.module_name = 'features'\n        self.add_module(self.module_name, nn.Sequential(*vgg_layers))\n\n        if self.num_classes > 0:\n            self.classifier = nn.Sequential(\n                nn.Linear(512 * 7 * 7, 4096),\n                nn.ReLU(True),\n                nn.Dropout(),\n                nn.Linear(4096, 4096),\n                nn.ReLU(True),\n                nn.Dropout(),\n                nn.Linear(4096, num_classes),\n            )\n\n    def init_weights(self, pretrained=None):\n        if isinstance(pretrained, str):\n            logger = logging.getLogger()\n            from ...runner import load_checkpoint\n            load_checkpoint(self, pretrained, strict=False, logger=logger)\n        elif pretrained is None:\n            for m in self.modules():\n                if isinstance(m, nn.Conv2d):\n                    kaiming_init(m)\n                elif isinstance(m, nn.BatchNorm2d):\n                    constant_init(m, 1)\n                elif isinstance(m, nn.Linear):\n                    normal_init(m, std=0.01)\n        else:\n            raise TypeError('pretrained must be a str or None')\n\n    def forward(self, x):\n        outs = []\n        vgg_layers = getattr(self, self.module_name)\n        for i in range(len(self.stage_blocks)):\n            for j in range(*self.range_sub_modules[i]):\n                vgg_layer = vgg_layers[j]\n                x = vgg_layer(x)\n            if i in self.out_indices:\n                outs.append(x)\n        if self.num_classes > 0:\n            x = x.view(x.size(0), -1)\n            x = self.classifier(x)\n            outs.append(x)\n        if len(outs) == 1:\n            return outs[0]\n        else:\n            return tuple(outs)\n\n    def train(self, mode=True):\n        super(VGG, self).train(mode)\n        if self.bn_eval:\n            for m in self.modules():\n                if isinstance(m, nn.BatchNorm2d):\n                    m.eval()\n                    if self.bn_frozen:\n                        for params in m.parameters():\n                            params.requires_grad = False\n        vgg_layers = getattr(self, self.module_name)\n        if mode and self.frozen_stages >= 0:\n            for i in range(self.frozen_stages):\n                for j in range(*self.range_sub_modules[i]):\n                    mod = vgg_layers[j]\n                    mod.eval()\n                    for param in mod.parameters():\n                        param.requires_grad = False\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/backbones/vovnet.py",
    "content": "\nfrom collections import OrderedDict\nfrom mmcv.runner import BaseModule\nfrom mmdet.models.builder import BACKBONES\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom torch.nn.modules.batchnorm import _BatchNorm\n\n\nVoVNet19_slim_dw_eSE = {\n    'stem': [64, 64, 64],\n    'stage_conv_ch': [64, 80, 96, 112],\n    'stage_out_ch': [112, 256, 384, 512],\n    \"layer_per_block\": 3,\n    \"block_per_stage\": [1, 1, 1, 1],\n    \"eSE\": True,\n    \"dw\": True\n}\n\nVoVNet19_dw_eSE = {\n    'stem': [64, 64, 64],\n    \"stage_conv_ch\": [128, 160, 192, 224],\n    \"stage_out_ch\": [256, 512, 768, 1024],\n    \"layer_per_block\": 3,\n    \"block_per_stage\": [1, 1, 1, 1],\n    \"eSE\": True,\n    \"dw\": True\n}\n\nVoVNet19_slim_eSE = {\n    'stem': [64, 64, 128],\n    'stage_conv_ch': [64, 80, 96, 112],\n    'stage_out_ch': [112, 256, 384, 512],\n    'layer_per_block': 3,\n    'block_per_stage': [1, 1, 1, 1],\n    'eSE': True,\n    \"dw\": False\n}\n\nVoVNet19_eSE = {\n    'stem': [64, 64, 128],\n    \"stage_conv_ch\": [128, 160, 192, 224],\n    \"stage_out_ch\": [256, 512, 768, 1024],\n    \"layer_per_block\": 3,\n    \"block_per_stage\": [1, 1, 1, 1],\n    \"eSE\": True,\n    \"dw\": False\n}\n\nVoVNet39_eSE = {\n    'stem': [64, 64, 128],\n    \"stage_conv_ch\": [128, 160, 192, 224],\n    \"stage_out_ch\": [256, 512, 768, 1024],\n    \"layer_per_block\": 5,\n    \"block_per_stage\": [1, 1, 2, 2],\n    \"eSE\": True,\n    \"dw\": False\n}\n\nVoVNet57_eSE = {\n    'stem': [64, 64, 128],\n    \"stage_conv_ch\": [128, 160, 192, 224],\n    \"stage_out_ch\": [256, 512, 768, 1024],\n    \"layer_per_block\": 5,\n    \"block_per_stage\": [1, 1, 4, 3],\n    \"eSE\": True,\n    \"dw\": False\n}\n\nVoVNet99_eSE = {\n    'stem': [64, 64, 128],\n    \"stage_conv_ch\": [128, 160, 192, 224],\n    \"stage_out_ch\": [256, 512, 768, 1024],\n    \"layer_per_block\": 5,\n    \"block_per_stage\": [1, 3, 9, 3],\n    \"eSE\": True,\n    \"dw\": False\n}\n\n_STAGE_SPECS = {\n    \"V-19-slim-dw-eSE\": VoVNet19_slim_dw_eSE,\n    \"V-19-dw-eSE\": VoVNet19_dw_eSE,\n    \"V-19-slim-eSE\": VoVNet19_slim_eSE,\n    \"V-19-eSE\": VoVNet19_eSE,\n    \"V-39-eSE\": VoVNet39_eSE,\n    \"V-57-eSE\": VoVNet57_eSE,\n    \"V-99-eSE\": VoVNet99_eSE,\n}\n\n\ndef dw_conv3x3(in_channels, out_channels, module_name, postfix, stride=1, kernel_size=3, padding=1):\n    \"\"\"3x3 convolution with padding\"\"\"\n    return [\n        (\n            '{}_{}/dw_conv3x3'.format(module_name, postfix),\n            nn.Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=kernel_size,\n                stride=stride,\n                padding=padding,\n                groups=out_channels,\n                bias=False\n            )\n        ),\n        (\n            '{}_{}/pw_conv1x1'.format(module_name, postfix),\n            nn.Conv2d(in_channels, out_channels, kernel_size=1, stride=1, padding=0, groups=1, bias=False)\n        ),\n        ('{}_{}/pw_norm'.format(module_name, postfix), nn.BatchNorm2d(out_channels)),\n        ('{}_{}/pw_relu'.format(module_name, postfix), nn.ReLU(inplace=True)),\n    ]\n\n\ndef conv3x3(in_channels, out_channels, module_name, postfix, stride=1, groups=1, kernel_size=3, padding=1):\n    \"\"\"3x3 convolution with padding\"\"\"\n    return [\n        (\n            f\"{module_name}_{postfix}/conv\",\n            nn.Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=kernel_size,\n                stride=stride,\n                padding=padding,\n                groups=groups,\n                bias=False,\n            ),\n        ),\n        (f\"{module_name}_{postfix}/norm\", nn.BatchNorm2d(out_channels)),\n        (f\"{module_name}_{postfix}/relu\", nn.ReLU(inplace=True)),\n    ]\n\n\ndef conv1x1(in_channels, out_channels, module_name, postfix, stride=1, groups=1, kernel_size=1, padding=0):\n    \"\"\"1x1 convolution with padding\"\"\"\n    return [\n        (\n            f\"{module_name}_{postfix}/conv\",\n            nn.Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=kernel_size,\n                stride=stride,\n                padding=padding,\n                groups=groups,\n                bias=False,\n            ),\n        ),\n        (f\"{module_name}_{postfix}/norm\", nn.BatchNorm2d(out_channels)),\n        (f\"{module_name}_{postfix}/relu\", nn.ReLU(inplace=True)),\n    ]\n\n\nclass Hsigmoid(nn.Module):\n    def __init__(self, inplace=True):\n        super(Hsigmoid, self).__init__()\n        self.inplace = inplace\n\n    def forward(self, x):\n        return F.relu6(x + 3.0, inplace=self.inplace) / 6.0\n\n\nclass eSEModule(nn.Module):\n    def __init__(self, channel, reduction=4):\n        super(eSEModule, self).__init__()\n        self.avg_pool = nn.AdaptiveAvgPool2d(1)\n        self.fc = nn.Conv2d(channel, channel, kernel_size=1, padding=0)\n        self.hsigmoid = Hsigmoid()\n\n    def forward(self, x):\n        input = x\n        x = self.avg_pool(x)\n        x = self.fc(x)\n        x = self.hsigmoid(x)\n        return input * x\n\n\nclass _OSA_module(nn.Module):\n    def __init__(\n        self, in_ch, stage_ch, concat_ch, layer_per_block, module_name, SE=False, identity=False, depthwise=False\n    ):\n\n        super(_OSA_module, self).__init__()\n\n        self.identity = identity\n        self.depthwise = depthwise\n        self.isReduced = False\n        self.layers = nn.ModuleList()\n        in_channel = in_ch\n        if self.depthwise and in_channel != stage_ch:\n            self.isReduced = True\n            self.conv_reduction = nn.Sequential(\n                OrderedDict(conv1x1(in_channel, stage_ch, \"{}_reduction\".format(module_name), \"0\"))\n            )\n        for i in range(layer_per_block):\n            if self.depthwise:\n                self.layers.append(nn.Sequential(OrderedDict(dw_conv3x3(stage_ch, stage_ch, module_name, i))))\n            else:\n                self.layers.append(nn.Sequential(OrderedDict(conv3x3(in_channel, stage_ch, module_name, i))))\n            in_channel = stage_ch\n\n        # feature aggregation\n        in_channel = in_ch + layer_per_block * stage_ch\n        self.concat = nn.Sequential(OrderedDict(conv1x1(in_channel, concat_ch, module_name, \"concat\")))\n\n        self.ese = eSEModule(concat_ch)\n\n    def forward(self, x):\n\n        identity_feat = x\n\n        output = []\n        output.append(x)\n        if self.depthwise and self.isReduced:\n            x = self.conv_reduction(x)\n        for layer in self.layers:\n            x = layer(x)\n            output.append(x)\n\n        x = torch.cat(output, dim=1)\n        xt = self.concat(x)\n\n        xt = self.ese(xt)\n\n        if self.identity:\n            xt = xt + identity_feat\n\n        return xt\n\n\nclass _OSA_stage(nn.Sequential):\n    def __init__(\n        self, in_ch, stage_ch, concat_ch, block_per_stage, layer_per_block, stage_num, SE=False, depthwise=False\n    ):\n\n        super(_OSA_stage, self).__init__()\n\n        if not stage_num == 2:\n            self.add_module(\"Pooling\", nn.MaxPool2d(kernel_size=3, stride=2, ceil_mode=True))\n\n        if block_per_stage != 1:\n            SE = False\n        module_name = f\"OSA{stage_num}_1\"\n        self.add_module(\n            module_name, _OSA_module(in_ch, stage_ch, concat_ch, layer_per_block, module_name, SE, depthwise=depthwise)\n        )\n        for i in range(block_per_stage - 1):\n            if i != block_per_stage - 2:  # last block\n                SE = False\n            module_name = f\"OSA{stage_num}_{i + 2}\"\n            self.add_module(\n                module_name,\n                _OSA_module(\n                    concat_ch,\n                    stage_ch,\n                    concat_ch,\n                    layer_per_block,\n                    module_name,\n                    SE,\n                    identity=True,\n                    depthwise=depthwise\n                ),\n            )\n\n\n@BACKBONES.register_module()\nclass VoVNet(BaseModule):\n    def __init__(self, spec_name, input_ch=3, out_features=None, \n                 frozen_stages=-1, norm_eval=True, pretrained=None, init_cfg=None):\n        \"\"\"\n        Args:\n            input_ch(int) : the number of input channel\n            out_features (list[str]): name of the layers whose outputs should\n                be returned in forward. Can be anything in \"stem\", \"stage2\" ...\n        \"\"\"\n        super(VoVNet, self).__init__(init_cfg)\n        self.frozen_stages = frozen_stages\n        self.norm_eval = norm_eval\n\n        if isinstance(pretrained, str):\n            warnings.warn('DeprecationWarning: pretrained is deprecated, '\n                          'please use \"init_cfg\" instead')\n            self.init_cfg = dict(type='Pretrained', checkpoint=pretrained)\n        stage_specs = _STAGE_SPECS[spec_name]\n\n        stem_ch = stage_specs[\"stem\"]\n        config_stage_ch = stage_specs[\"stage_conv_ch\"]\n        config_concat_ch = stage_specs[\"stage_out_ch\"]\n        block_per_stage = stage_specs[\"block_per_stage\"]\n        layer_per_block = stage_specs[\"layer_per_block\"]\n        SE = stage_specs[\"eSE\"]\n        depthwise = stage_specs[\"dw\"]\n\n        self._out_features = out_features\n\n        # Stem module\n        conv_type = dw_conv3x3 if depthwise else conv3x3\n        stem = conv3x3(input_ch, stem_ch[0], \"stem\", \"1\", 2)\n        stem += conv_type(stem_ch[0], stem_ch[1], \"stem\", \"2\", 1)\n        stem += conv_type(stem_ch[1], stem_ch[2], \"stem\", \"3\", 2)\n        self.add_module(\"stem\", nn.Sequential((OrderedDict(stem))))\n        current_stirde = 4\n        self._out_feature_strides = {\"stem\": current_stirde, \"stage2\": current_stirde}\n        self._out_feature_channels = {\"stem\": stem_ch[2]}\n\n        stem_out_ch = [stem_ch[2]]\n        in_ch_list = stem_out_ch + config_concat_ch[:-1]\n        # OSA stages\n        self.stage_names = []\n        for i in range(4):  # num_stages\n            name = \"stage%d\" % (i + 2)  # stage 2 ... stage 5\n            self.stage_names.append(name)\n            self.add_module(\n                name,\n                _OSA_stage(\n                    in_ch_list[i],\n                    config_stage_ch[i],\n                    config_concat_ch[i],\n                    block_per_stage[i],\n                    layer_per_block,\n                    i + 2,\n                    SE,\n                    depthwise,\n                ),\n            )\n\n            self._out_feature_channels[name] = config_concat_ch[i]\n            if not i == 0:\n                self._out_feature_strides[name] = current_stirde = int(current_stirde * 2)\n\n        # initialize weights\n        # self._initialize_weights()\n\n    def _initialize_weights(self):\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                nn.init.kaiming_normal_(m.weight)\n\n    def forward(self, x):\n        outputs = {}\n        x = self.stem(x)\n        if \"stem\" in self._out_features:\n            outputs[\"stem\"] = x\n        for name in self.stage_names:\n            x = getattr(self, name)(x)\n            if name in self._out_features:\n                outputs[name] = x\n\n        return outputs\n\n    def _freeze_stages(self):\n        if self.frozen_stages >= 0:\n            m = getattr(self, 'stem')\n            m.eval()\n            for param in m.parameters():\n                param.requires_grad = False\n\n        for i in range(1, self.frozen_stages + 1):\n            m = getattr(self, f'stage{i+1}')\n            m.eval()\n            for param in m.parameters():\n                param.requires_grad = False\n\n    def train(self, mode=True):\n        \"\"\"Convert the model into training mode while keep normalization layer\n        freezed.\"\"\"\n        super(VoVNet, self).train(mode)\n        self._freeze_stages()\n        if mode and self.norm_eval:\n            for m in self.modules():\n                # trick: eval have effect on BatchNorm only\n                if isinstance(m, _BatchNorm):\n                    m.eval()"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .activation import build_activation_layer\nfrom .conv import build_conv_layer\nfrom .plugin import build_plugin_layer\nfrom .conv_module import ConvModule\nfrom .drop import Dropout, DropPath\nfrom .norm import build_norm_layer, is_norm\nfrom .wrappers import (Conv2d, Conv3d, ConvTranspose2d, ConvTranspose3d,\n                       Linear, MaxPool2d, MaxPool3d)\nfrom .registry import (ACTIVATION_LAYERS, CONV_LAYERS, NORM_LAYERS,\n                       PADDING_LAYERS, PLUGIN_LAYERS, UPSAMPLE_LAYERS)\nfrom .transformer import build_positional_encoding"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/activation.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nfrom mmcv.utils import build_from_cfg, digit_version, TORCH_VERSION\nfrom .registry import ACTIVATION_LAYERS\n\nfor module in [\n        nn.ReLU, nn.LeakyReLU, nn.PReLU, nn.RReLU, nn.ReLU6, nn.ELU,\n        nn.Sigmoid, nn.Tanh\n]:\n    ACTIVATION_LAYERS.register_module(module=module)\n\n\n@ACTIVATION_LAYERS.register_module(name='Clip')\n@ACTIVATION_LAYERS.register_module()\nclass Clamp(nn.Module):\n    \"\"\"Clamp activation layer.\n\n    This activation function is to clamp the feature map value within\n    :math:`[min, max]`. More details can be found in ``torch.clamp()``.\n\n    Args:\n        min (Number | optional): Lower-bound of the range to be clamped to.\n            Default to -1.\n        max (Number | optional): Upper-bound of the range to be clamped to.\n            Default to 1.\n    \"\"\"\n\n    def __init__(self, min=-1., max=1.):\n        super(Clamp, self).__init__()\n        self.min = min\n        self.max = max\n\n    def forward(self, x):\n        \"\"\"Forward function.\n\n        Args:\n            x (torch.Tensor): The input tensor.\n\n        Returns:\n            torch.Tensor: Clamped tensor.\n        \"\"\"\n        return torch.clamp(x, min=self.min, max=self.max)\n\n\nclass GELU(nn.Module):\n    r\"\"\"Applies the Gaussian Error Linear Units function:\n\n    .. math::\n        \\text{GELU}(x) = x * \\Phi(x)\n    where :math:`\\Phi(x)` is the Cumulative Distribution Function for\n    Gaussian Distribution.\n\n    Shape:\n        - Input: :math:`(N, *)` where `*` means, any number of additional\n          dimensions\n        - Output: :math:`(N, *)`, same shape as the input\n\n    .. image:: scripts/activation_images/GELU.png\n\n    Examples::\n\n        >>> m = nn.GELU()\n        >>> input = torch.randn(2)\n        >>> output = m(input)\n    \"\"\"\n\n    def forward(self, input):\n        return F.gelu(input)\n\n\nif (digit_version(TORCH_VERSION) < digit_version('1.4')):\n    ACTIVATION_LAYERS.register_module(module=GELU)\nelse:\n    ACTIVATION_LAYERS.register_module(module=nn.GELU)\n\n\ndef build_activation_layer(cfg):\n    \"\"\"Build activation layer.\n\n    Args:\n        cfg (dict): The activation layer config, which should contain:\n            - type (str): Layer type.\n            - layer args: Args needed to instantiate an activation layer.\n\n    Returns:\n        nn.Module: Created activation layer.\n    \"\"\"\n    return build_from_cfg(cfg, ACTIVATION_LAYERS)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/conv.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom torch import nn\n\nfrom .registry import CONV_LAYERS\n\nCONV_LAYERS.register_module('Conv1d', module=nn.Conv1d)\nCONV_LAYERS.register_module('Conv2d', module=nn.Conv2d)\nCONV_LAYERS.register_module('Conv3d', module=nn.Conv3d)\nCONV_LAYERS.register_module('Conv', module=nn.Conv2d)\n\n\ndef build_conv_layer(cfg, *args, **kwargs):\n    \"\"\"Build convolution layer.\n\n    Args:\n        cfg (None or dict): The conv layer config, which should contain:\n            - type (str): Layer type.\n            - layer args: Args needed to instantiate an conv layer.\n        args (argument list): Arguments passed to the `__init__`\n            method of the corresponding conv layer.\n        kwargs (keyword arguments): Keyword arguments passed to the `__init__`\n            method of the corresponding conv layer.\n\n    Returns:\n        nn.Module: Created conv layer.\n    \"\"\"\n    if cfg is None:\n        cfg_ = dict(type='Conv2d')\n    else:\n        if not isinstance(cfg, dict):\n            raise TypeError('cfg must be a dict')\n        if 'type' not in cfg:\n            raise KeyError('the cfg dict must contain the key \"type\"')\n        cfg_ = cfg.copy()\n\n    layer_type = cfg_.pop('type')\n    if layer_type not in CONV_LAYERS:\n        raise KeyError(f'Unrecognized norm type {layer_type}')\n    else:\n        conv_layer = CONV_LAYERS.get(layer_type)\n\n    layer = conv_layer(*args, **kwargs, **cfg_)\n\n    return layer\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/conv_module.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\n\nimport torch.nn as nn\n\nfrom torch.nn.modules.instancenorm import _InstanceNorm\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom ..utils import constant_init, kaiming_init\nfrom .activation import build_activation_layer\nfrom .conv import build_conv_layer\nfrom .norm import build_norm_layer\nfrom .padding import build_padding_layer\nfrom .registry import PLUGIN_LAYERS\n\n\n@PLUGIN_LAYERS.register_module()\nclass ConvModule(nn.Module):\n    \"\"\"A conv block that bundles conv/norm/activation layers.\n\n    This block simplifies the usage of convolution layers, which are commonly\n    used with a norm layer (e.g., BatchNorm) and activation layer (e.g., ReLU).\n    It is based upon three build methods: `build_conv_layer()`,\n    `build_norm_layer()` and `build_activation_layer()`.\n\n    Besides, we add some additional features in this module.\n    1. Automatically set `bias` of the conv layer.\n    2. Spectral norm is supported.\n    3. More padding modes are supported. Before PyTorch 1.5, nn.Conv2d only\n    supports zero and circular padding, and we add \"reflect\" padding mode.\n\n    Args:\n        in_channels (int): Number of channels in the input feature map.\n            Same as that in ``nn._ConvNd``.\n        out_channels (int): Number of channels produced by the convolution.\n            Same as that in ``nn._ConvNd``.\n        kernel_size (int | tuple[int]): Size of the convolving kernel.\n            Same as that in ``nn._ConvNd``.\n        stride (int | tuple[int]): Stride of the convolution.\n            Same as that in ``nn._ConvNd``.\n        padding (int | tuple[int]): Zero-padding added to both sides of\n            the input. Same as that in ``nn._ConvNd``.\n        dilation (int | tuple[int]): Spacing between kernel elements.\n            Same as that in ``nn._ConvNd``.\n        groups (int): Number of blocked connections from input channels to\n            output channels. Same as that in ``nn._ConvNd``.\n        bias (bool | str): If specified as `auto`, it will be decided by the\n            norm_cfg. Bias will be set as True if `norm_cfg` is None, otherwise\n            False. Default: \"auto\".\n        conv_cfg (dict): Config dict for convolution layer. Default: None,\n            which means using conv2d.\n        norm_cfg (dict): Config dict for normalization layer. Default: None.\n        act_cfg (dict): Config dict for activation layer.\n            Default: dict(type='ReLU').\n        inplace (bool): Whether to use inplace mode for activation.\n            Default: True.\n        with_spectral_norm (bool): Whether use spectral norm in conv module.\n            Default: False.\n        padding_mode (str): If the `padding_mode` has not been supported by\n            current `Conv2d` in PyTorch, we will use our own padding layer\n            instead. Currently, we support ['zeros', 'circular'] with official\n            implementation and ['reflect'] with our own implementation.\n            Default: 'zeros'.\n        order (tuple[str]): The order of conv/norm/activation layers. It is a\n            sequence of \"conv\", \"norm\" and \"act\". Common examples are\n            (\"conv\", \"norm\", \"act\") and (\"act\", \"conv\", \"norm\").\n            Default: ('conv', 'norm', 'act').\n    \"\"\"\n\n    _abbr_ = 'conv_block'\n\n    def __init__(self,\n                 in_channels,\n                 out_channels,\n                 kernel_size,\n                 stride=1,\n                 padding=0,\n                 dilation=1,\n                 groups=1,\n                 bias='auto',\n                 conv_cfg=None,\n                 norm_cfg=None,\n                 act_cfg=dict(type='ReLU'),\n                 inplace=True,\n                 with_spectral_norm=False,\n                 padding_mode='zeros',\n                 order=('conv', 'norm', 'act')):\n        super(ConvModule, self).__init__()\n        assert conv_cfg is None or isinstance(conv_cfg, dict)\n        assert norm_cfg is None or isinstance(norm_cfg, dict)\n        assert act_cfg is None or isinstance(act_cfg, dict)\n        official_padding_mode = ['zeros', 'circular']\n        self.conv_cfg = conv_cfg\n        self.norm_cfg = norm_cfg\n        self.act_cfg = act_cfg\n        self.inplace = inplace\n        self.with_spectral_norm = with_spectral_norm\n        self.with_explicit_padding = padding_mode not in official_padding_mode\n        self.order = order\n        assert isinstance(self.order, tuple) and len(self.order) == 3\n        assert set(order) == set(['conv', 'norm', 'act'])\n\n        self.with_norm = norm_cfg is not None\n        self.with_activation = act_cfg is not None\n        # if the conv layer is before a norm layer, bias is unnecessary.\n        if bias == 'auto':\n            bias = not self.with_norm\n        self.with_bias = bias\n\n        if self.with_explicit_padding:\n            pad_cfg = dict(type=padding_mode)\n            self.padding_layer = build_padding_layer(pad_cfg, padding)\n\n        # reset padding to 0 for conv module\n        conv_padding = 0 if self.with_explicit_padding else padding\n        # build convolution layer\n        self.conv = build_conv_layer(\n            conv_cfg,\n            in_channels,\n            out_channels,\n            kernel_size,\n            stride=stride,\n            padding=conv_padding,\n            dilation=dilation,\n            groups=groups,\n            bias=bias)\n        # export the attributes of self.conv to a higher level for convenience\n        self.in_channels = self.conv.in_channels\n        self.out_channels = self.conv.out_channels\n        self.kernel_size = self.conv.kernel_size\n        self.stride = self.conv.stride\n        self.padding = padding\n        self.dilation = self.conv.dilation\n        self.transposed = self.conv.transposed\n        self.output_padding = self.conv.output_padding\n        self.groups = self.conv.groups\n\n        if self.with_spectral_norm:\n            self.conv = nn.utils.spectral_norm(self.conv)\n\n        # build normalization layers\n        if self.with_norm:\n            # norm layer is after conv layer\n            if order.index('norm') > order.index('conv'):\n                norm_channels = out_channels\n            else:\n                norm_channels = in_channels\n            self.norm_name, norm = build_norm_layer(norm_cfg, norm_channels)\n            self.add_module(self.norm_name, norm)\n            if self.with_bias:\n                if isinstance(norm, (_BatchNorm, _InstanceNorm)):\n                    warnings.warn(\n                        'Unnecessary conv bias before batch/instance norm')\n        else:\n            self.norm_name = None\n\n        # build activation layer\n        if self.with_activation:\n            act_cfg_ = act_cfg.copy()\n            # nn.Tanh has no 'inplace' argument\n            if act_cfg_['type'] not in [\n                    'Tanh', 'PReLU', 'Sigmoid', 'HSigmoid', 'Swish'\n            ]:\n                act_cfg_.setdefault('inplace', inplace)\n            self.activate = build_activation_layer(act_cfg_)\n\n        # Use msra init by default\n        self.init_weights()\n\n    @property\n    def norm(self):\n        if self.norm_name:\n            return getattr(self, self.norm_name)\n        else:\n            return None\n\n    def init_weights(self):\n        # 1. It is mainly for customized conv layers with their own\n        #    initialization manners by calling their own ``init_weights()``,\n        #    and we do not want ConvModule to override the initialization.\n        # 2. For customized conv layers without their own initialization\n        #    manners (that is, they don't have their own ``init_weights()``)\n        #    and PyTorch's conv layers, they will be initialized by\n        #    this method with default ``kaiming_init``.\n        # Note: For PyTorch's conv layers, they will be overwritten by our\n        #    initialization implementation using default ``kaiming_init``.\n        if not hasattr(self.conv, 'init_weights'):\n            if self.with_activation and self.act_cfg['type'] == 'LeakyReLU':\n                nonlinearity = 'leaky_relu'\n                a = self.act_cfg.get('negative_slope', 0.01)\n            else:\n                nonlinearity = 'relu'\n                a = 0\n            kaiming_init(self.conv, a=a, nonlinearity=nonlinearity)\n        if self.with_norm:\n            constant_init(self.norm, 1, bias=0)\n\n    def forward(self, x, activate=True, norm=True):\n        for layer in self.order:\n            if layer == 'conv':\n                if self.with_explicit_padding:\n                    x = self.padding_layer(x)\n                x = self.conv(x)\n            elif layer == 'norm' and norm and self.with_norm:\n                x = self.norm(x)\n            elif layer == 'act' and activate and self.with_activation:\n                x = self.activate(x)\n        return x\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/drop.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nimport torch.nn as nn\n\nfrom mmcv import build_from_cfg\nfrom .registry import DROPOUT_LAYERS\n\n\ndef drop_path(x, drop_prob=0., training=False):\n    \"\"\"Drop paths (Stochastic Depth) per sample (when applied in main path of\n    residual blocks).\n\n    We follow the implementation\n    https://github.com/rwightman/pytorch-image-models/blob/a2727c1bf78ba0d7b5727f5f95e37fb7f8866b1f/timm/models/layers/drop.py  # noqa: E501\n    \"\"\"\n    if drop_prob == 0. or not training:\n        return x\n    keep_prob = 1 - drop_prob\n    # handle tensors with different dimensions, not just 4D tensors.\n    shape = (x.shape[0], ) + (1, ) * (x.ndim - 1)\n    random_tensor = keep_prob + torch.rand(\n        shape, dtype=x.dtype, device=x.device)\n    output = x.div(keep_prob) * random_tensor.floor()\n    return output\n\n\n@DROPOUT_LAYERS.register_module()\nclass DropPath(nn.Module):\n    \"\"\"Drop paths (Stochastic Depth) per sample  (when applied in main path of\n    residual blocks).\n\n    We follow the implementation\n    https://github.com/rwightman/pytorch-image-models/blob/a2727c1bf78ba0d7b5727f5f95e37fb7f8866b1f/timm/models/layers/drop.py  # noqa: E501\n\n    Args:\n        drop_prob (float): Probability of the path to be zeroed. Default: 0.1\n    \"\"\"\n\n    def __init__(self, drop_prob=0.1):\n        super(DropPath, self).__init__()\n        self.drop_prob = drop_prob\n\n    def forward(self, x):\n        return drop_path(x, self.drop_prob, self.training)\n\n\n@DROPOUT_LAYERS.register_module()\nclass Dropout(nn.Dropout):\n    \"\"\"A wrapper for ``torch.nn.Dropout``, We rename the ``p`` of\n    ``torch.nn.Dropout`` to ``drop_prob`` so as to be consistent with\n    ``DropPath``\n\n    Args:\n        drop_prob (float): Probability of the elements to be\n            zeroed. Default: 0.5.\n        inplace (bool):  Do the operation inplace or not. Default: False.\n    \"\"\"\n\n    def __init__(self, drop_prob=0.5, inplace=False):\n        super().__init__(p=drop_prob, inplace=inplace)\n\n\ndef build_dropout(cfg, default_args=None):\n    \"\"\"Builder for drop out layers.\"\"\"\n    return build_from_cfg(cfg, DROPOUT_LAYERS, default_args)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/norm.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport inspect\n\nimport torch.nn as nn\n\nfrom mmcv.utils import is_tuple_of\nfrom torch.nn.modules.instancenorm import _InstanceNorm\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom .registry import NORM_LAYERS\n\nNORM_LAYERS.register_module('BN', module=nn.BatchNorm2d)\nNORM_LAYERS.register_module('BN1d', module=nn.BatchNorm1d)\nNORM_LAYERS.register_module('BN2d', module=nn.BatchNorm2d)\nNORM_LAYERS.register_module('BN3d', module=nn.BatchNorm3d)\nNORM_LAYERS.register_module('SyncBN', module=nn.SyncBatchNorm)\nNORM_LAYERS.register_module('GN', module=nn.GroupNorm)\nNORM_LAYERS.register_module('LN', module=nn.LayerNorm)\nNORM_LAYERS.register_module('IN', module=nn.InstanceNorm2d)\nNORM_LAYERS.register_module('IN1d', module=nn.InstanceNorm1d)\nNORM_LAYERS.register_module('IN2d', module=nn.InstanceNorm2d)\nNORM_LAYERS.register_module('IN3d', module=nn.InstanceNorm3d)\n\n\ndef infer_abbr(class_type):\n    \"\"\"Infer abbreviation from the class name.\n\n    When we build a norm layer with `build_norm_layer()`, we want to preserve\n    the norm type in variable names, e.g, self.bn1, self.gn. This method will\n    infer the abbreviation to map class types to abbreviations.\n\n    Rule 1: If the class has the property \"_abbr_\", return the property.\n    Rule 2: If the parent class is _BatchNorm, GroupNorm, LayerNorm or\n    InstanceNorm, the abbreviation of this layer will be \"bn\", \"gn\", \"ln\" and\n    \"in\" respectively.\n    Rule 3: If the class name contains \"batch\", \"group\", \"layer\" or \"instance\",\n    the abbreviation of this layer will be \"bn\", \"gn\", \"ln\" and \"in\"\n    respectively.\n    Rule 4: Otherwise, the abbreviation falls back to \"norm\".\n\n    Args:\n        class_type (type): The norm layer type.\n\n    Returns:\n        str: The inferred abbreviation.\n    \"\"\"\n    if not inspect.isclass(class_type):\n        raise TypeError(\n            f'class_type must be a type, but got {type(class_type)}')\n    if hasattr(class_type, '_abbr_'):\n        return class_type._abbr_\n    if issubclass(class_type, _InstanceNorm):  # IN is a subclass of BN\n        return 'in'\n    elif issubclass(class_type, _BatchNorm):\n        return 'bn'\n    elif issubclass(class_type, nn.GroupNorm):\n        return 'gn'\n    elif issubclass(class_type, nn.LayerNorm):\n        return 'ln'\n    else:\n        class_name = class_type.__name__.lower()\n        if 'batch' in class_name:\n            return 'bn'\n        elif 'group' in class_name:\n            return 'gn'\n        elif 'layer' in class_name:\n            return 'ln'\n        elif 'instance' in class_name:\n            return 'in'\n        else:\n            return 'norm_layer'\n\n\ndef build_norm_layer(cfg, num_features, postfix=''):\n    \"\"\"Build normalization layer.\n\n    Args:\n        cfg (dict): The norm layer config, which should contain:\n\n            - type (str): Layer type.\n            - layer args: Args needed to instantiate a norm layer.\n            - requires_grad (bool, optional): Whether stop gradient updates.\n        num_features (int): Number of input channels.\n        postfix (int | str): The postfix to be appended into norm abbreviation\n            to create named layer.\n\n    Returns:\n        (str, nn.Module): The first element is the layer name consisting of\n            abbreviation and postfix, e.g., bn1, gn. The second element is the\n            created norm layer.\n    \"\"\"\n    if not isinstance(cfg, dict):\n        raise TypeError('cfg must be a dict')\n    if 'type' not in cfg:\n        raise KeyError('the cfg dict must contain the key \"type\"')\n    cfg_ = cfg.copy()\n\n    layer_type = cfg_.pop('type')\n    if layer_type not in NORM_LAYERS:\n        raise KeyError(f'Unrecognized norm type {layer_type}')\n\n    norm_layer = NORM_LAYERS.get(layer_type)\n    abbr = infer_abbr(norm_layer)\n\n    assert isinstance(postfix, (int, str))\n    name = abbr + str(postfix)\n\n    requires_grad = cfg_.pop('requires_grad', True)\n    cfg_.setdefault('eps', 1e-5)\n    if layer_type != 'GN':\n        layer = norm_layer(num_features, **cfg_)\n        if layer_type == 'SyncBN' and hasattr(layer, '_specify_ddp_gpu_num'):\n            layer._specify_ddp_gpu_num(1)\n    else:\n        assert 'num_groups' in cfg_\n        layer = norm_layer(num_channels=num_features, **cfg_)\n\n    for param in layer.parameters():\n        param.requires_grad = requires_grad\n\n    return name, layer\n\n\ndef is_norm(layer, exclude=None):\n    \"\"\"Check if a layer is a normalization layer.\n\n    Args:\n        layer (nn.Module): The layer to be checked.\n        exclude (type | tuple[type]): Types to be excluded.\n\n    Returns:\n        bool: Whether the layer is a norm layer.\n    \"\"\"\n    if exclude is not None:\n        if not isinstance(exclude, tuple):\n            exclude = (exclude, )\n        if not is_tuple_of(exclude, type):\n            raise TypeError(\n                f'\"exclude\" must be either None or type or a tuple of types, '\n                f'but got {type(exclude)}: {exclude}')\n\n    if exclude and isinstance(layer, exclude):\n        return False\n\n    all_norm_bases = (_BatchNorm, _InstanceNorm, nn.GroupNorm, nn.LayerNorm)\n    return isinstance(layer, all_norm_bases)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/padding.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch.nn as nn\n\nfrom .registry import PADDING_LAYERS\n\nPADDING_LAYERS.register_module('zero', module=nn.ZeroPad2d)\nPADDING_LAYERS.register_module('reflect', module=nn.ReflectionPad2d)\nPADDING_LAYERS.register_module('replicate', module=nn.ReplicationPad2d)\n\n\ndef build_padding_layer(cfg, *args, **kwargs):\n    \"\"\"Build padding layer.\n\n    Args:\n        cfg (None or dict): The padding layer config, which should contain:\n            - type (str): Layer type.\n            - layer args: Args needed to instantiate a padding layer.\n\n    Returns:\n        nn.Module: Created padding layer.\n    \"\"\"\n    if not isinstance(cfg, dict):\n        raise TypeError('cfg must be a dict')\n    if 'type' not in cfg:\n        raise KeyError('the cfg dict must contain the key \"type\"')\n\n    cfg_ = cfg.copy()\n    padding_type = cfg_.pop('type')\n    if padding_type not in PADDING_LAYERS:\n        raise KeyError(f'Unrecognized padding type {padding_type}.')\n    else:\n        padding_layer = PADDING_LAYERS.get(padding_type)\n\n    layer = padding_layer(*args, **kwargs, **cfg_)\n\n    return layer\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/plugin.py",
    "content": "import inspect\nimport platform\n\nfrom .registry import PLUGIN_LAYERS\n\nif platform.system() == 'Windows':\n    import regex as re\nelse:\n    import re\n\n\ndef infer_abbr(class_type):\n    \"\"\"Infer abbreviation from the class name.\n\n    This method will infer the abbreviation to map class types to\n    abbreviations.\n\n    Rule 1: If the class has the property \"abbr\", return the property.\n    Rule 2: Otherwise, the abbreviation falls back to snake case of class\n    name, e.g. the abbreviation of ``FancyBlock`` will be ``fancy_block``.\n\n    Args:\n        class_type (type): The norm layer type.\n\n    Returns:\n        str: The inferred abbreviation.\n    \"\"\"\n\n    def camel2snack(word):\n        \"\"\"Convert camel case word into snack case.\n\n        Modified from `inflection lib\n        <https://inflection.readthedocs.io/en/latest/#inflection.underscore>`_.\n\n        Example::\n\n            >>> camel2snack(\"FancyBlock\")\n            'fancy_block'\n        \"\"\"\n\n        word = re.sub(r'([A-Z]+)([A-Z][a-z])', r'\\1_\\2', word)\n        word = re.sub(r'([a-z\\d])([A-Z])', r'\\1_\\2', word)\n        word = word.replace('-', '_')\n        return word.lower()\n\n    if not inspect.isclass(class_type):\n        raise TypeError(\n            f'class_type must be a type, but got {type(class_type)}')\n    if hasattr(class_type, '_abbr_'):\n        return class_type._abbr_\n    else:\n        return camel2snack(class_type.__name__)\n\n\ndef build_plugin_layer(cfg, postfix='', **kwargs):\n    \"\"\"Build plugin layer.\n\n    Args:\n        cfg (None or dict): cfg should contain:\n            type (str): identify plugin layer type.\n            layer args: args needed to instantiate a plugin layer.\n        postfix (int, str): appended into norm abbreviation to\n            create named layer. Default: ''.\n\n    Returns:\n        tuple[str, nn.Module]:\n            name (str): abbreviation + postfix\n            layer (nn.Module): created plugin layer\n    \"\"\"\n    if not isinstance(cfg, dict):\n        raise TypeError('cfg must be a dict')\n    if 'type' not in cfg:\n        raise KeyError('the cfg dict must contain the key \"type\"')\n    cfg_ = cfg.copy()\n\n    layer_type = cfg_.pop('type')\n    if layer_type not in PLUGIN_LAYERS:\n        raise KeyError(f'Unrecognized plugin type {layer_type}')\n\n    plugin_layer = PLUGIN_LAYERS.get(layer_type)\n    abbr = infer_abbr(plugin_layer)\n\n    assert isinstance(postfix, (int, str))\n    name = abbr + str(postfix)\n\n    layer = plugin_layer(**kwargs, **cfg_)\n\n    return name, layer\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/registry.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmcv.utils import Registry\n\nCONV_LAYERS = Registry('conv layer')\nNORM_LAYERS = Registry('norm layer')\nACTIVATION_LAYERS = Registry('activation layer')\nPADDING_LAYERS = Registry('padding layer')\nUPSAMPLE_LAYERS = Registry('upsample layer')\nPLUGIN_LAYERS = Registry('plugin layer')\n\nDROPOUT_LAYERS = Registry('drop out layers')\nPOSITIONAL_ENCODING = Registry('position encoding')\nATTENTION = Registry('attention')\nFEEDFORWARD_NETWORK = Registry('feed-forward Network')\nTRANSFORMER_LAYER = Registry('transformerLayer')\nTRANSFORMER_LAYER_SEQUENCE = Registry('transformer-layers sequence')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/transformer.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport warnings\n\nimport torch\nimport torch.nn as nn\nimport torch.utils.checkpoint as cp\nfrom mmcv import ConfigDict, deprecated_api_warning\nfrom .wrappers import Linear\nfrom .activation import build_activation_layer\nfrom .norm import build_norm_layer\n# from mmcv.models.bricks import Linear, build_activation_layer, build_norm_layer\nfrom ..backbones.base_module import BaseModule, ModuleList, Sequential\nfrom mmcv.utils import build_from_cfg\nfrom .drop import build_dropout\nfrom .registry import (ATTENTION, FEEDFORWARD_NETWORK, POSITIONAL_ENCODING,\n                       TRANSFORMER_LAYER, TRANSFORMER_LAYER_SEQUENCE)\n\n# Avoid BC-breaking of importing MultiScaleDeformableAttention from this file\ntry:\n    from mmcv.ops.multi_scale_deform_attn import MultiScaleDeformableAttention  # noqa F401\n    warnings.warn(\n        ImportWarning(\n            '``MultiScaleDeformableAttention`` has been moved to '\n            '``mmcv.ops.multi_scale_deform_attn``, please change original path '  # noqa E501\n            '``from mmcv.cnn.bricks.transformer import MultiScaleDeformableAttention`` '  # noqa E501\n            'to ``from mmcv.ops.multi_scale_deform_attn import MultiScaleDeformableAttention`` '  # noqa E501\n        ))\n\nexcept ImportError:\n    warnings.warn('Fail to import ``MultiScaleDeformableAttention`` from '\n                  '``mmcv.ops.multi_scale_deform_attn``, '\n                  'You should install ``mmcv-full`` if you need this module. ')\n\n\ndef build_positional_encoding(cfg, default_args=None):\n    \"\"\"Builder for Position Encoding.\"\"\"\n    return build_from_cfg(cfg, POSITIONAL_ENCODING, default_args)\n\n\ndef build_attention(cfg, default_args=None):\n    \"\"\"Builder for attention.\"\"\"\n    return build_from_cfg(cfg, ATTENTION, default_args)\n\n\ndef build_feedforward_network(cfg, default_args=None):\n    \"\"\"Builder for feed-forward network (FFN).\"\"\"\n    return build_from_cfg(cfg, FEEDFORWARD_NETWORK, default_args)\n\n\ndef build_transformer_layer(cfg, default_args=None):\n    \"\"\"Builder for transformer layer.\"\"\"\n    return build_from_cfg(cfg, TRANSFORMER_LAYER, default_args)\n\n\ndef build_transformer_layer_sequence(cfg, default_args=None):\n    \"\"\"Builder for transformer encoder and transformer decoder.\"\"\"\n    return build_from_cfg(cfg, TRANSFORMER_LAYER_SEQUENCE, default_args)\n\n\n@ATTENTION.register_module()\nclass MultiheadAttention(BaseModule):\n    \"\"\"A wrapper for ``torch.nn.MultiheadAttention``.\n\n    This module implements MultiheadAttention with identity connection,\n    and positional encoding  is also passed as input.\n\n    Args:\n        embed_dims (int): The embedding dimension.\n        num_heads (int): Parallel attention heads.\n        attn_drop (float): A Dropout layer on attn_output_weights.\n            Default: 0.0.\n        proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.\n            Default: 0.0.\n        dropout_layer (obj:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): When it is True,  Key, Query and Value are shape of\n            (batch, n, embed_dim), otherwise (n, batch, embed_dim).\n             Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims,\n                 num_heads,\n                 attn_drop=0.,\n                 proj_drop=0.,\n                 dropout_layer=dict(type='Dropout', drop_prob=0.),\n                 init_cfg=None,\n                 batch_first=False,\n                 with_cp=False,\n                 **kwargs):\n        super(MultiheadAttention, self).__init__(init_cfg)\n        if 'dropout' in kwargs:\n            warnings.warn('The arguments `dropout` in MultiheadAttention '\n                          'has been deprecated, now you can separately '\n                          'set `attn_drop`(float), proj_drop(float), '\n                          'and `dropout_layer`(dict) ')\n            attn_drop = kwargs['dropout']\n            dropout_layer['drop_prob'] = kwargs.pop('dropout')\n\n        self.embed_dims = embed_dims\n        self.num_heads = num_heads\n        self.batch_first = batch_first\n\n        self.attn = nn.MultiheadAttention(embed_dims, num_heads, attn_drop,\n                                          **kwargs)\n        self.proj_drop = nn.Dropout(proj_drop)\n        self.dropout_layer = build_dropout(\n            dropout_layer) if dropout_layer else nn.Identity()\n        self.with_cp = with_cp\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiheadAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_pos=None,\n                attn_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `MultiheadAttention`.\n\n        **kwargs allow passing a more general data flow when combining\n        with other operations in `transformerlayer`.\n\n        Args:\n            query (Tensor): The input query with shape [num_queries, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n                If None, the ``query`` will be used. Defaults to None.\n            value (Tensor): The value tensor with same shape as `key`.\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n                If None, the `key` will be used.\n            identity (Tensor): This tensor, with the same shape as x,\n                will be used for the identity link.\n                If None, `x` will be used. Defaults to None.\n            query_pos (Tensor): The positional encoding for query, with\n                the same shape as `x`. If not None, it will\n                be added to `x` before forward function. Defaults to None.\n            key_pos (Tensor): The positional encoding for `key`, with the\n                same shape as `key`. Defaults to None. If not None, it will\n                be added to `key` before forward function. If None, and\n                `query_pos` has the same shape as `key`, then `query_pos`\n                will be used for `key_pos`. Defaults to None.\n            attn_mask (Tensor): ByteTensor mask with shape [num_queries,\n                num_keys]. Same in `nn.MultiheadAttention.forward`.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].\n                Defaults to None.\n\n        Returns:\n            Tensor: forwarded results with shape\n                [num_queries, bs, embed_dims]\n                if self.batch_first is False, else\n                [bs, num_queries embed_dims].\n        \"\"\"\n\n        if key is None:\n            key = query\n        if value is None:\n            value = key\n        if identity is None:\n            identity = query\n        if key_pos is None:\n            if query_pos is not None:\n                # use query_pos if key_pos is not available\n                if query_pos.shape == key.shape:\n                    key_pos = query_pos\n                else:\n                    warnings.warn(f'position encoding of key is'\n                                  f'missing in {self.__class__.__name__}.')\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n\n        # Because the dataflow('key', 'query', 'value') of\n        # ``torch.nn.MultiheadAttention`` is (num_query, batch,\n        # embed_dims), We should adjust the shape of dataflow from\n        # batch_first (batch, num_query, embed_dims) to num_query_first\n        # (num_query ,batch, embed_dims), and recover ``attn_output``\n        # from num_query_first to batch_first.\n        if self.batch_first:\n            query = query.transpose(0, 1)\n            key = key.transpose(0, 1)\n            value = value.transpose(0, 1)\n\n        if self.with_cp:\n            out = cp.checkpoint(self.attn, use_reentrant=False, query=query,\n                    key=key,\n                    value=value,\n                    attn_mask=attn_mask,\n                    key_padding_mask=key_padding_mask)[0]\n        else:\n            out = self.attn(\n                    query=query,\n                    key=key,\n                    value=value,\n                    attn_mask=attn_mask,\n                    key_padding_mask=key_padding_mask)[0]\n\n        if self.batch_first:\n            out = out.transpose(0, 1)\n\n        return identity + self.dropout_layer(self.proj_drop(out))\n\n\n@FEEDFORWARD_NETWORK.register_module()\nclass FFN(BaseModule):\n    \"\"\"Implements feed-forward networks (FFNs) with identity connection.\n\n    Args:\n        embed_dims (int): The feature dimension. Same as\n            `MultiheadAttention`. Defaults: 256.\n        feedforward_channels (int): The hidden dimension of FFNs.\n            Defaults: 1024.\n        num_fcs (int, optional): The number of fully-connected layers in\n            FFNs. Default: 2.\n        act_cfg (dict, optional): The activation config for FFNs.\n            Default: dict(type='ReLU')\n        ffn_drop (float, optional): Probability of an element to be\n            zeroed in FFN. Default 0.0.\n        add_identity (bool, optional): Whether to add the\n            identity connection. Default: `True`.\n        dropout_layer (obj:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    @deprecated_api_warning(\n        {\n            'dropout': 'ffn_drop',\n            'add_residual': 'add_identity'\n        },\n        cls_name='FFN')\n    def __init__(self,\n                 embed_dims=256,\n                 feedforward_channels=1024,\n                 num_fcs=2,\n                 act_cfg=dict(type='ReLU', inplace=True),\n                 ffn_drop=0.,\n                 dropout_layer=None,\n                 add_identity=True,\n                 init_cfg=None,\n                 **kwargs):\n        super(FFN, self).__init__(init_cfg)\n        assert num_fcs >= 2, 'num_fcs should be no less ' \\\n            f'than 2. got {num_fcs}.'\n        self.embed_dims = embed_dims\n        self.feedforward_channels = feedforward_channels\n        self.num_fcs = num_fcs\n        self.act_cfg = act_cfg\n        self.activate = build_activation_layer(act_cfg)\n\n        layers = []\n        in_channels = embed_dims\n        for _ in range(num_fcs - 1):\n            layers.append(\n                Sequential(\n                    Linear(in_channels, feedforward_channels), self.activate,\n                    nn.Dropout(ffn_drop)))\n            in_channels = feedforward_channels\n        layers.append(Linear(feedforward_channels, embed_dims))\n        layers.append(nn.Dropout(ffn_drop))\n        self.layers = Sequential(*layers)\n        self.dropout_layer = build_dropout(\n            dropout_layer) if dropout_layer else torch.nn.Identity()\n        self.add_identity = add_identity\n\n    @deprecated_api_warning({'residual': 'identity'}, cls_name='FFN')\n    def forward(self, x, identity=None):\n        \"\"\"Forward function for `FFN`.\n\n        The function would add x to the output tensor if residue is None.\n        \"\"\"\n        out = self.layers(x)\n        if not self.add_identity:\n            return self.dropout_layer(out)\n        if identity is None:\n            identity = x\n        return identity + self.dropout_layer(out)\n\n\n@TRANSFORMER_LAYER.register_module()\nclass BaseTransformerLayer(BaseModule):\n    \"\"\"Base `TransformerLayer` for vision transformer.\n\n    It can be built from `mmcv.ConfigDict` and support more flexible\n    customization, for example, using any number of `FFN or LN ` and\n    use different kinds of `attention` by specifying a list of `ConfigDict`\n    named `attn_cfgs`. It is worth mentioning that it supports `prenorm`\n    when you specifying `norm` as the first element of `operation_order`.\n    More details about the `prenorm`: `On Layer Normalization in the\n    Transformer Architecture <https://arxiv.org/abs/2002.04745>`_ .\n\n    Args:\n        attn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):\n            Configs for `self_attention` or `cross_attention` modules,\n            The order of the configs in the list should be consistent with\n            corresponding attentions in operation_order.\n            If it is a dict, all of the attention modules in operation_order\n            will be built with this config. Default: None.\n        ffn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):\n            Configs for FFN, The order of the configs in the list should be\n            consistent with corresponding ffn in operation_order.\n            If it is a dict, all of the attention modules in operation_order\n            will be built with this config.\n        operation_order (tuple[str]): The execution order of operation\n            in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').\n            Support `prenorm` when you specifying first element as `norm`.\n            Default：None.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: dict(type='LN').\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): Key, Query and Value are shape\n            of (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 attn_cfgs=None,\n                 with_cp=False,\n                 ffn_cfgs=dict(\n                     type='FFN',\n                     embed_dims=256,\n                     feedforward_channels=1024,\n                     num_fcs=2,\n                     ffn_drop=0.,\n                     act_cfg=dict(type='ReLU', inplace=True),\n                 ),\n                 operation_order=None,\n                 norm_cfg=dict(type='LN'),\n                 init_cfg=None,\n                 batch_first=False,\n                 **kwargs):\n\n        deprecated_args = dict(\n            feedforward_channels='feedforward_channels',\n            ffn_dropout='ffn_drop',\n            ffn_num_fcs='num_fcs')\n        for ori_name, new_name in deprecated_args.items():\n            if ori_name in kwargs:\n                warnings.warn(\n                    f'The arguments `{ori_name}` in BaseTransformerLayer '\n                    f'has been deprecated, now you should set `{new_name}` '\n                    f'and other FFN related arguments '\n                    f'to a dict named `ffn_cfgs`. ')\n                ffn_cfgs[new_name] = kwargs[ori_name]\n\n        super(BaseTransformerLayer, self).__init__(init_cfg)\n\n        self.batch_first = batch_first\n\n        assert set(operation_order) & set(\n            ['self_attn', 'norm', 'ffn', 'cross_attn']) == \\\n            set(operation_order), f'The operation_order of' \\\n            f' {self.__class__.__name__} should ' \\\n            f'contains all four operation type ' \\\n            f\"{['self_attn', 'norm', 'ffn', 'cross_attn']}\"\n\n        num_attn = operation_order.count('self_attn') + operation_order.count(\n            'cross_attn')\n        if isinstance(attn_cfgs, dict):\n            attn_cfgs = [copy.deepcopy(attn_cfgs) for _ in range(num_attn)]\n        else:\n            assert num_attn == len(attn_cfgs), f'The length ' \\\n                f'of attn_cfg {num_attn} is ' \\\n                f'not consistent with the number of attention' \\\n                f'in operation_order {operation_order}.'\n\n        self.num_attn = num_attn\n        self.operation_order = operation_order\n        self.norm_cfg = norm_cfg\n        self.pre_norm = operation_order[0] == 'norm'\n        self.attentions = ModuleList()\n\n        index = 0\n        for operation_name in operation_order:\n            if operation_name in ['self_attn', 'cross_attn']:\n                if 'batch_first' in attn_cfgs[index]:\n                    assert self.batch_first == attn_cfgs[index]['batch_first']\n                else:\n                    attn_cfgs[index]['batch_first'] = self.batch_first\n                attention = build_attention(attn_cfgs[index])\n                # Some custom attentions used as `self_attn`\n                # or `cross_attn` can have different behavior.\n                attention.operation_name = operation_name\n                self.attentions.append(attention)\n                index += 1\n\n        self.embed_dims = self.attentions[0].embed_dims\n\n        self.ffns = ModuleList()\n        num_ffns = operation_order.count('ffn')\n        if isinstance(ffn_cfgs, dict):\n            ffn_cfgs = ConfigDict(ffn_cfgs)\n        if isinstance(ffn_cfgs, dict):\n            ffn_cfgs = [copy.deepcopy(ffn_cfgs) for _ in range(num_ffns)]\n        assert len(ffn_cfgs) == num_ffns\n        for ffn_index in range(num_ffns):\n            if 'embed_dims' not in ffn_cfgs[ffn_index]:\n                ffn_cfgs['embed_dims'] = self.embed_dims\n            else:\n                assert ffn_cfgs[ffn_index]['embed_dims'] == self.embed_dims\n            self.ffns.append(\n                build_feedforward_network(ffn_cfgs[ffn_index],\n                                          dict(type='FFN')))\n\n        self.norms = ModuleList()\n        num_norms = operation_order.count('norm')\n        for _ in range(num_norms):\n            self.norms.append(build_norm_layer(norm_cfg, self.embed_dims)[1])\n        self.with_cp = with_cp\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                query_pos=None,\n                key_pos=None,\n                attn_masks=None,\n                query_key_padding_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerDecoderLayer`.\n\n        **kwargs contains some specific arguments of attentions.\n\n        Args:\n            query (Tensor): The input query with shape\n                [num_queries, bs, embed_dims] if\n                self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n            value (Tensor): The value tensor with same shape as `key`.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`.\n                Default: None.\n            attn_masks (List[Tensor] | None): 2D Tensor used in\n                calculation of corresponding attention. The length of\n                it should equal to the number of `attention` in\n                `operation_order`. Default: None.\n            query_key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_queries]. Only used in `self_attn` layer.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_keys]. Default: None.\n\n        Returns:\n            Tensor: forwarded results with shape [num_queries, bs, embed_dims].\n        \"\"\"\n\n        norm_index = 0\n        attn_index = 0\n        ffn_index = 0\n        identity = query\n        if attn_masks is None:\n            attn_masks = [None for _ in range(self.num_attn)]\n        elif isinstance(attn_masks, torch.Tensor):\n            attn_masks = [\n                copy.deepcopy(attn_masks) for _ in range(self.num_attn)\n            ]\n            warnings.warn(f'Use same attn_mask in all attentions in '\n                          f'{self.__class__.__name__} ')\n        else:\n            assert len(attn_masks) == self.num_attn, f'The length of ' \\\n                        f'attn_masks {len(attn_masks)} must be equal ' \\\n                        f'to the number of attention in ' \\\n                        f'operation_order {self.num_attn}'\n\n        for layer in self.operation_order:\n            if layer == 'self_attn':\n                temp_key = temp_value = query\n                query = self.attentions[attn_index](\n                    query,\n                    temp_key,\n                    temp_value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=query_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=query_key_padding_mask,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'norm':\n                query = self.norms[norm_index](query)\n                norm_index += 1\n\n            elif layer == 'cross_attn':\n                query = self.attentions[attn_index](\n                    query,\n                    key,\n                    value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=key_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=key_padding_mask,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'ffn':\n                if self.with_cp:\n                    query = cp.checkpoint(self.ffns[ffn_index], query)\n                else:\n                    query = self.ffns[ffn_index](\n                    query, identity if self.pre_norm else None)\n                ffn_index += 1\n\n        return query\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass TransformerLayerSequence(BaseModule):\n    \"\"\"Base class for TransformerEncoder and TransformerDecoder in vision\n    transformer.\n\n    As base-class of Encoder and Decoder in vision transformer.\n    Support customization such as specifying different kind\n    of `transformer_layer` in `transformer_coder`.\n\n    Args:\n        transformerlayer (list[obj:`mmcv.ConfigDict`] |\n            obj:`mmcv.ConfigDict`): Config of transformerlayer\n            in TransformerCoder. If it is obj:`mmcv.ConfigDict`,\n             it would be repeated `num_layer` times to a\n             list[`mmcv.ConfigDict`]. Default: None.\n        num_layers (int): The number of `TransformerLayer`. Default: None.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    def __init__(self, transformerlayers=None, num_layers=None, init_cfg=None):\n        super(TransformerLayerSequence, self).__init__(init_cfg)\n        if isinstance(transformerlayers, dict):\n            transformerlayers = [\n                copy.deepcopy(transformerlayers) for _ in range(num_layers)\n            ]\n        else:\n            assert isinstance(transformerlayers, list) and \\\n                   len(transformerlayers) == num_layers\n        self.num_layers = num_layers\n        self.layers = ModuleList()\n        for i in range(num_layers):\n            self.layers.append(build_transformer_layer(transformerlayers[i]))\n        self.embed_dims = self.layers[0].embed_dims\n        self.pre_norm = self.layers[0].pre_norm\n\n    def forward(self,\n                query,\n                key,\n                value,\n                query_pos=None,\n                key_pos=None,\n                attn_masks=None,\n                query_key_padding_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerCoder`.\n\n        Args:\n            query (Tensor): Input query with shape\n                `(num_queries, bs, embed_dims)`.\n            key (Tensor): The key tensor with shape\n                `(num_keys, bs, embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(num_keys, bs, embed_dims)`.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`.\n                Default: None.\n            attn_masks (List[Tensor], optional): Each element is 2D Tensor\n                which is used in calculation of corresponding attention in\n                operation_order. Default: None.\n            query_key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_queries]. Only used in self-attention\n                Default: None.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_keys]. Default: None.\n\n        Returns:\n            Tensor:  results with shape [num_queries, bs, embed_dims].\n        \"\"\"\n        for layer in self.layers:\n            query = layer(\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                attn_masks=attn_masks,\n                query_key_padding_mask=query_key_padding_mask,\n                key_padding_mask=key_padding_mask,\n                **kwargs)\n        return query\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/bricks/wrappers.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nr\"\"\"Modified from https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/wrappers.py  # noqa: E501\n\nWrap some nn modules to support empty tensor input. Currently, these wrappers\nare mainly used in mask heads like fcn_mask_head and maskiou_heads since mask\nheads are trained on only positive RoIs.\n\"\"\"\nimport math\n\nimport torch\nimport torch.nn as nn\nfrom torch.nn.modules.utils import _pair, _triple\n\nfrom .registry import CONV_LAYERS, UPSAMPLE_LAYERS\n\nTORCH_VERSION = tuple(int(x) for x in torch.__version__.split('.')[:2])\n\n\ndef obsolete_torch_version(torch_version, version_threshold):\n    return torch_version <= version_threshold\n\n\nclass NewEmptyTensorOp(torch.autograd.Function):\n\n    @staticmethod\n    def forward(ctx, x, new_shape):\n        ctx.shape = x.shape\n        return x.new_empty(new_shape)\n\n    @staticmethod\n    def backward(ctx, grad):\n        shape = ctx.shape\n        return NewEmptyTensorOp.apply(grad, shape), None\n\n\n@CONV_LAYERS.register_module('Conv', force=True)\nclass Conv2d(nn.Conv2d):\n\n    def forward(self, x):\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 4)):\n            out_shape = [x.shape[0], self.out_channels]\n            for i, k, p, s, d in zip(x.shape[-2:], self.kernel_size,\n                                     self.padding, self.stride, self.dilation):\n                o = (i + 2 * p - (d * (k - 1) + 1)) // s + 1\n                out_shape.append(o)\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            if self.training:\n                # produce dummy gradient to avoid DDP warning.\n                dummy = sum(x.view(-1)[0] for x in self.parameters()) * 0.0\n                return empty + dummy\n            else:\n                return empty\n\n        return super().forward(x)\n\n\n@CONV_LAYERS.register_module('Conv3d', force=True)\nclass Conv3d(nn.Conv3d):\n\n    def forward(self, x):\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 4)):\n            out_shape = [x.shape[0], self.out_channels]\n            for i, k, p, s, d in zip(x.shape[-3:], self.kernel_size,\n                                     self.padding, self.stride, self.dilation):\n                o = (i + 2 * p - (d * (k - 1) + 1)) // s + 1\n                out_shape.append(o)\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            if self.training:\n                # produce dummy gradient to avoid DDP warning.\n                dummy = sum(x.view(-1)[0] for x in self.parameters()) * 0.0\n                return empty + dummy\n            else:\n                return empty\n\n        return super().forward(x)\n\n\n@CONV_LAYERS.register_module()\n@CONV_LAYERS.register_module('deconv')\n@UPSAMPLE_LAYERS.register_module('deconv', force=True)\nclass ConvTranspose2d(nn.ConvTranspose2d):\n\n    def forward(self, x):\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 4)):\n            out_shape = [x.shape[0], self.out_channels]\n            for i, k, p, s, d, op in zip(x.shape[-2:], self.kernel_size,\n                                         self.padding, self.stride,\n                                         self.dilation, self.output_padding):\n                out_shape.append((i - 1) * s - 2 * p + (d * (k - 1) + 1) + op)\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            if self.training:\n                # produce dummy gradient to avoid DDP warning.\n                dummy = sum(x.view(-1)[0] for x in self.parameters()) * 0.0\n                return empty + dummy\n            else:\n                return empty\n\n        return super().forward(x)\n\n\n@CONV_LAYERS.register_module()\n@CONV_LAYERS.register_module('deconv3d')\n@UPSAMPLE_LAYERS.register_module('deconv3d', force=True)\nclass ConvTranspose3d(nn.ConvTranspose3d):\n\n    def forward(self, x):\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 4)):\n            out_shape = [x.shape[0], self.out_channels]\n            for i, k, p, s, d, op in zip(x.shape[-3:], self.kernel_size,\n                                         self.padding, self.stride,\n                                         self.dilation, self.output_padding):\n                out_shape.append((i - 1) * s - 2 * p + (d * (k - 1) + 1) + op)\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            if self.training:\n                # produce dummy gradient to avoid DDP warning.\n                dummy = sum(x.view(-1)[0] for x in self.parameters()) * 0.0\n                return empty + dummy\n            else:\n                return empty\n\n        return super().forward(x)\n\n\nclass MaxPool2d(nn.MaxPool2d):\n\n    def forward(self, x):\n        # PyTorch 1.9 does not support empty tensor inference yet\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 9)):\n            out_shape = list(x.shape[:2])\n            for i, k, p, s, d in zip(x.shape[-2:], _pair(self.kernel_size),\n                                     _pair(self.padding), _pair(self.stride),\n                                     _pair(self.dilation)):\n                o = (i + 2 * p - (d * (k - 1) + 1)) / s + 1\n                o = math.ceil(o) if self.ceil_mode else math.floor(o)\n                out_shape.append(o)\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            return empty\n\n        return super().forward(x)\n\n\nclass MaxPool3d(nn.MaxPool3d):\n\n    def forward(self, x):\n        # PyTorch 1.9 does not support empty tensor inference yet\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 9)):\n            out_shape = list(x.shape[:2])\n            for i, k, p, s, d in zip(x.shape[-3:], _triple(self.kernel_size),\n                                     _triple(self.padding),\n                                     _triple(self.stride),\n                                     _triple(self.dilation)):\n                o = (i + 2 * p - (d * (k - 1) + 1)) / s + 1\n                o = math.ceil(o) if self.ceil_mode else math.floor(o)\n                out_shape.append(o)\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            return empty\n\n        return super().forward(x)\n\n\nclass Linear(torch.nn.Linear):\n\n    def forward(self, x):\n        # empty tensor forward of Linear layer is supported in Pytorch 1.6\n        if x.numel() == 0 and obsolete_torch_version(TORCH_VERSION, (1, 5)):\n            out_shape = [x.shape[0], self.out_features]\n            empty = NewEmptyTensorOp.apply(x, out_shape)\n            if self.training:\n                # produce dummy gradient to avoid DDP warning.\n                dummy = sum(x.view(-1)[0] for x in self.parameters()) * 0.0\n                return empty + dummy\n            else:\n                return empty\n\n        return super().forward(x)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/builder.py",
    "content": "import warnings\n\n# from mmcv.cnn import MODELS as MMCV_MODELS\nfrom mmcv.utils import Registry\nfrom .backbones.base_module import Sequential\nfrom ..utils import Registry, build_from_cfg\n\n######### from mmcv.cnn\ndef build_model_from_cfg(cfg, registry, default_args=None):\n    \"\"\"Build a PyTorch model from config dict(s). Different from\n    ``build_from_cfg``, if cfg is a list, a ``nn.Sequential`` will be built.\n\n    Args:\n        cfg (dict, list[dict]): The config of modules, is is either a config\n            dict or a list of config dicts. If cfg is a list, a\n            the built modules will be wrapped with ``nn.Sequential``.\n        registry (:obj:`Registry`): A registry the module belongs to.\n        default_args (dict, optional): Default arguments to build the module.\n            Defaults to None.\n\n    Returns:\n        nn.Module: A built nn module.\n    \"\"\"\n    if isinstance(cfg, list):\n        modules = [\n            build_from_cfg(cfg_, registry, default_args) for cfg_ in cfg\n        ]\n        return Sequential(*modules)\n    else:\n        return build_from_cfg(cfg, registry, default_args)\n\n\nCNN_MODELS = Registry('model', build_func=build_model_from_cfg)\n\n\nMODELS = Registry('models', parent=CNN_MODELS)\n\nBACKBONES = MODELS\nNECKS = MODELS\nROI_EXTRACTORS = MODELS\nSHARED_HEADS = MODELS\nHEADS = MODELS\nLOSSES = MODELS\nDETECTORS = MODELS\nSEGMENTORS = MODELS\n\nVOXEL_ENCODERS = MODELS\nMIDDLE_ENCODERS = MODELS\nFUSION_LAYERS = MODELS\n\n\ndef build_backbone(cfg):\n    \"\"\"Build backbone.\"\"\"\n    return BACKBONES.build(cfg)\n\n\ndef build_neck(cfg):\n    \"\"\"Build neck.\"\"\"\n    return NECKS.build(cfg)\n\n\ndef build_roi_extractor(cfg):\n    \"\"\"Build roi extractor.\"\"\"\n    return ROI_EXTRACTORS.build(cfg)\n\n\ndef build_shared_head(cfg):\n    \"\"\"Build shared head.\"\"\"\n    return SHARED_HEADS.build(cfg)\n\n\ndef build_head(cfg):\n    \"\"\"Build head.\"\"\"\n    return HEADS.build(cfg)\n\n\ndef build_loss(cfg):\n    \"\"\"Build loss.\"\"\"\n    return LOSSES.build(cfg)\n\n\ndef build_detector(cfg, train_cfg=None, test_cfg=None):\n    \"\"\"Build detector.\"\"\"\n    if train_cfg is not None or test_cfg is not None:\n        warnings.warn(\n            'train_cfg and test_cfg is deprecated, '\n            'please specify them in model', UserWarning)\n    assert cfg.get('train_cfg') is None or train_cfg is None, \\\n        'train_cfg specified in both outer field and model field '\n    assert cfg.get('test_cfg') is None or test_cfg is None, \\\n        'test_cfg specified in both outer field and model field '\n    return DETECTORS.build(\n        cfg, default_args=dict(train_cfg=train_cfg, test_cfg=test_cfg))\n    \n    \ndef build_segmentor(cfg, train_cfg=None, test_cfg=None):\n    \"\"\"Build segmentor.\"\"\"\n    if train_cfg is not None or test_cfg is not None:\n        warnings.warn(\n            'train_cfg and test_cfg is deprecated, '\n            'please specify them in model', UserWarning)\n    assert cfg.get('train_cfg') is None or train_cfg is None, \\\n        'train_cfg specified in both outer field and model field '\n    assert cfg.get('test_cfg') is None or test_cfg is None, \\\n        'test_cfg specified in both outer field and model field '\n    return SEGMENTORS.build(\n        cfg, default_args=dict(train_cfg=train_cfg, test_cfg=test_cfg))\n\n\ndef build_model(cfg, train_cfg=None, test_cfg=None):\n    \"\"\"A function warpper for building 3D detector or segmentor according to\n    cfg.\n\n    Should be deprecated in the future.\n    \"\"\"\n    if cfg.type in ['EncoderDecoder3D']:\n        return build_segmentor(cfg, train_cfg=train_cfg, test_cfg=test_cfg)\n    else:\n        return build_detector(cfg, train_cfg=train_cfg, test_cfg=test_cfg)\n\n\ndef build_voxel_encoder(cfg):\n    \"\"\"Build voxel encoder.\"\"\"\n    return VOXEL_ENCODERS.build(cfg)\n\n\ndef build_middle_encoder(cfg):\n    \"\"\"Build middle level encoder.\"\"\"\n    return MIDDLE_ENCODERS.build(cfg)\n\n\ndef build_fusion_layer(cfg):\n    \"\"\"Build fusion layer.\"\"\"\n    return FUSION_LAYERS.build(cfg)\n\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/MomAD_head.py",
    "content": "import copy\nfrom math import pi, cos, sin\n\nimport torch\nimport numpy as np\nimport torch.nn as nn\nimport matplotlib.pyplot as plt\nimport torch.nn.functional as F\nfrom mmcv.models.builder import HEADS, build_loss \nfrom mmcv.models.dense_heads import DETRHead\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom mmcv.core.bbox.builder import build_assigner, build_sampler\nfrom mmcv.core.bbox.coder import build_bbox_coder\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.core.bbox.transforms import bbox_xyxy_to_cxcywh\nfrom mmcv.models.bricks import Linear\nfrom mmcv.models.utils import bias_init_with_prob, xavier_init\nfrom mmcv.core.utils import (multi_apply, multi_apply, reduce_mean)\nfrom mmcv.models.bricks.transformer import build_transformer_layer_sequence\n\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.models.vad_utils.traj_lr_warmup import get_traj_warmup_loss_weight\nfrom mmcv.models.vad_utils.map_utils import (\n    normalize_2d_pts, normalize_2d_bbox, denormalize_2d_pts, denormalize_2d_bbox\n)\n\nclass MLP(nn.Module):\n    def __init__(self, in_channels, hidden_unit, verbose=False):\n        super(MLP, self).__init__()\n        self.mlp = nn.Sequential(\n            nn.Linear(in_channels, hidden_unit),\n            nn.LayerNorm(hidden_unit),\n            nn.ReLU()\n        )\n\n    def forward(self, x):\n        x = self.mlp(x)\n        return x\n\nclass LaneNet(nn.Module):\n    def __init__(self, in_channels, hidden_unit, num_subgraph_layers):\n        super(LaneNet, self).__init__()\n        self.num_subgraph_layers = num_subgraph_layers\n        self.layer_seq = nn.Sequential()\n        for i in range(num_subgraph_layers):\n            self.layer_seq.add_module(\n                f'lmlp_{i}', MLP(in_channels, hidden_unit))\n            in_channels = hidden_unit*2\n\n    def forward(self, pts_lane_feats):\n        '''\n            Extract lane_feature from vectorized lane representation\n\n        Args:\n            pts_lane_feats: [batch size, max_pnum, pts, D]\n\n        Returns:\n            inst_lane_feats: [batch size, max_pnum, D]\n        '''\n        x = pts_lane_feats\n        for name, layer in self.layer_seq.named_modules():\n            if isinstance(layer, MLP):\n                # x [bs,max_lane_num,9,dim]\n                x = layer(x)\n                x_max = torch.max(x, -2)[0]\n                x_max = x_max.unsqueeze(2).repeat(1, 1, x.shape[2], 1)\n                x = torch.cat([x, x_max], dim=-1)\n        x_max = torch.max(x, -2)[0]\n        return x_max\n\n\n@HEADS.register_module()\nclass MomADHead(DETRHead):\n    \"\"\"Head of VAD model.\n    Args:\n        with_box_refine (bool): Whether to refine the reference points\n            in the decoder. Defaults to False.\n        as_two_stage (bool) : Whether to generate the proposal from\n            the outputs of encoder.\n        transformer (obj:`ConfigDict`): ConfigDict is used for building\n            the Encoder and Decoder.\n        bev_h, bev_w (int): spatial shape of BEV queries.\n    \"\"\"\n    def __init__(self,\n                 *args,\n                 with_box_refine=False,\n                 as_two_stage=False,\n                 transformer=None,\n                 bbox_coder=None,\n                 num_cls_fcs=2,\n                 code_weights=None,\n                 bev_h=30,\n                 bev_w=30,\n                 fut_ts=6,\n                 fut_mode=6,\n                 loss_traj=dict(type='L1Loss', loss_weight=0.25),\n                 loss_traj_cls=dict(\n                     type='FocalLoss',\n                     use_sigmoid=True,\n                     gamma=2.0,\n                     alpha=0.25,\n                     loss_weight=0.8),\n                 map_bbox_coder=None,\n                 map_num_query=900,\n                 map_num_classes=3,\n                 map_num_vec=20,\n                 map_num_pts_per_vec=2,\n                 map_num_pts_per_gt_vec=2,\n                 map_query_embed_type='all_pts',\n                 map_transform_method='minmax',\n                 map_gt_shift_pts_pattern='v0',\n                 map_dir_interval=1,\n                 map_code_size=None,\n                 map_code_weights=None,\n                loss_map_cls=dict(\n                     type='CrossEntropyLoss',\n                     bg_cls_weight=0.1,\n                     use_sigmoid=False,\n                     loss_weight=1.0,\n                     class_weight=1.0),\n                 loss_map_bbox=dict(type='L1Loss', loss_weight=5.0),\n                 loss_map_iou=dict(type='GIoULoss', loss_weight=2.0),\n                 loss_map_pts=dict(\n                    type='ChamferDistance',loss_src_weight=1.0,loss_dst_weight=1.0\n                 ),\n                 loss_map_dir=dict(type='PtsDirCosLoss', loss_weight=2.0),\n                 tot_epoch=None,\n                 use_traj_lr_warmup=False,\n                 motion_decoder=None,\n                 motion_map_decoder=None,\n                 use_pe=False,\n                 motion_det_score=None,\n                 map_thresh=0.5,\n                 dis_thresh=0.2,\n                 pe_normalization=True,\n                 ego_his_encoder=None,\n                 ego_fut_mode=3,\n                 loss_plan_reg=dict(type='L1Loss', loss_weight=0.25),\n                 loss_plan_bound=dict(type='PlanMapBoundLoss', loss_weight=0.1),\n                 loss_plan_cls=dict(type='FocalLoss',\n                                    use_sigmoid=True,\n                                    gamma=2.0,\n                                    alpha=0.25,\n                                    loss_weight=1.0),\n                 loss_plan_col=dict(type='PlanAgentDisLoss', loss_weight=0.1),\n                 loss_plan_dir=dict(type='PlanMapThetaLoss', loss_weight=0.1),\n                 ego_agent_decoder=None,\n                 ego_map_decoder=None,\n                 query_thresh=None,\n                 query_use_fix_pad=None,\n                 ego_lcf_feat_idx=None,\n                 valid_fut_ts=6,\n                 **kwargs):\n\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.fp16_enabled = False\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.tot_epoch = tot_epoch\n        self.use_traj_lr_warmup = use_traj_lr_warmup\n        self.motion_decoder = motion_decoder\n        self.motion_map_decoder = motion_map_decoder\n        self.use_pe = use_pe\n        self.motion_det_score = motion_det_score\n        self.map_thresh = map_thresh\n        self.dis_thresh = dis_thresh\n        self.pe_normalization = pe_normalization\n        self.ego_his_encoder = ego_his_encoder\n        self.ego_fut_mode = ego_fut_mode\n        self.ego_fut_inmode_mode = 6\n        self.ego_agent_decoder = ego_agent_decoder\n        self.ego_map_decoder = ego_map_decoder\n        self.query_thresh = query_thresh\n        self.query_use_fix_pad = query_use_fix_pad\n        self.ego_lcf_feat_idx = ego_lcf_feat_idx\n        self.valid_fut_ts = valid_fut_ts\n\n        if loss_traj_cls['use_sigmoid'] == True:\n            self.traj_num_cls = 1\n        else:\n          self.traj_num_cls = 2\n          \n        if loss_plan_cls['use_sigmoid'] == True:\n            self.plan_num_cls = 1\n        else:\n            self.plan_num_cls = 2\n\n        self.with_box_refine = with_box_refine\n        self.as_two_stage = as_two_stage\n        if self.as_two_stage:\n            transformer['as_two_stage'] = self.as_two_stage\n        if 'code_size' in kwargs:\n            self.code_size = kwargs['code_size']\n        else:\n            self.code_size = 10\n        if code_weights is not None:\n            self.code_weights = code_weights\n        else:\n            self.code_weights = [1.0, 1.0, 1.0,\n                                 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]\n        if map_code_size is not None:\n            self.map_code_size = map_code_size\n        else:\n            self.map_code_size = 10\n        if map_code_weights is not None:\n            self.map_code_weights = map_code_weights\n        else:\n            self.map_code_weights = [1.0, 1.0, 1.0,\n                                 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]\n\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n        self.pc_range = self.bbox_coder.pc_range\n        self.real_w = self.pc_range[3] - self.pc_range[0]\n        self.real_h = self.pc_range[4] - self.pc_range[1]\n        self.num_cls_fcs = num_cls_fcs - 1\n\n        self.map_bbox_coder = build_bbox_coder(map_bbox_coder)\n        self.map_query_embed_type = map_query_embed_type\n        self.map_transform_method = map_transform_method\n        self.map_gt_shift_pts_pattern = map_gt_shift_pts_pattern\n        map_num_query = map_num_vec * map_num_pts_per_vec\n        self.map_num_query = map_num_query\n        self.map_num_classes = map_num_classes\n        self.map_num_vec = map_num_vec\n        self.map_num_pts_per_vec = map_num_pts_per_vec\n        self.map_num_pts_per_gt_vec = map_num_pts_per_gt_vec\n        self.map_dir_interval = map_dir_interval\n\n        if loss_map_cls['use_sigmoid'] == True:\n            self.map_cls_out_channels = map_num_classes\n        else:\n            self.map_cls_out_channels = map_num_classes + 1\n\n        self.map_bg_cls_weight = 0\n        map_class_weight = loss_map_cls.get('class_weight', None)\n        if map_class_weight is not None and (self.__class__ is VADHead):\n            assert isinstance(map_class_weight, float), 'Expected ' \\\n                'class_weight to have type float. Found ' \\\n                f'{type(map_class_weight)}.'\n            # NOTE following the official DETR rep0, bg_cls_weight means\n            # relative classification weight of the no-object class.\n            map_bg_cls_weight = loss_map_cls.get('bg_cls_weight', map_class_weight)\n            assert isinstance(map_bg_cls_weight, float), 'Expected ' \\\n                'bg_cls_weight to have type float. Found ' \\\n                f'{type(map_bg_cls_weight)}.'\n            map_class_weight = torch.ones(map_num_classes + 1) * map_class_weight\n            # set background class as the last indice\n            map_class_weight[map_num_classes] = map_bg_cls_weight\n            loss_map_cls.update({'class_weight': map_class_weight})\n            if 'bg_cls_weight' in loss_map_cls:\n                loss_map_cls.pop('bg_cls_weight')\n            self.map_bg_cls_weight = map_bg_cls_weight\n        \n        self.traj_bg_cls_weight = 0\n\n        super(MomADHead, self).__init__(*args, transformer=transformer, **kwargs)\n        self.code_weights = nn.Parameter(torch.tensor(\n            self.code_weights, requires_grad=False), requires_grad=False)\n        self.map_code_weights = nn.Parameter(torch.tensor(\n            self.map_code_weights, requires_grad=False), requires_grad=False)\n        \n        if kwargs['train_cfg'] is not None:\n            assert 'map_assigner' in kwargs['train_cfg'], 'map assigner should be provided '\\\n                'when train_cfg is set.'\n            map_assigner = kwargs['train_cfg']['map_assigner']\n            assert loss_map_cls['loss_weight'] == map_assigner['cls_cost']['weight'], \\\n                'The classification weight for loss and matcher should be' \\\n                'exactly the same.'\n            assert loss_map_bbox['loss_weight'] == map_assigner['reg_cost'][\n                'weight'], 'The regression L1 weight for loss and matcher ' \\\n                'should be exactly the same.'\n            assert loss_map_iou['loss_weight'] == map_assigner['iou_cost']['weight'], \\\n                'The regression iou weight for loss and matcher should be' \\\n                'exactly the same.'\n            assert loss_map_pts['loss_weight'] == map_assigner['pts_cost']['weight'], \\\n                'The regression l1 weight for map pts loss and matcher should be' \\\n                'exactly the same.'\n\n            self.map_assigner = build_assigner(map_assigner)\n            # DETR sampling=False, so use PseudoSampler\n            sampler_cfg = dict(type='PseudoSampler')\n            self.map_sampler = build_sampler(sampler_cfg, context=self)\n        \n        self.loss_traj = build_loss(loss_traj)\n        self.loss_traj_cls = build_loss(loss_traj_cls)\n        self.loss_map_bbox = build_loss(loss_map_bbox)\n        self.loss_map_cls = build_loss(loss_map_cls)\n        self.loss_map_iou = build_loss(loss_map_iou)\n        self.loss_map_pts = build_loss(loss_map_pts)\n        self.loss_map_dir = build_loss(loss_map_dir)\n        self.loss_plan_reg = build_loss(loss_plan_reg)\n        self.loss_plan_cls = build_loss(loss_plan_cls)\n        self.loss_plan_bound = build_loss(loss_plan_bound)\n        self.loss_plan_col = build_loss(loss_plan_col)\n        self.loss_plan_dir = build_loss(loss_plan_dir)\n        self.his_enhance_encoder = nn.Linear(256,512)\n        #self.prev_cmd = None\n        #self.prev_ego_feature = None\n\n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        cls_branch = []\n        #import pdb;pdb.set_trace()\n        for _ in range(self.num_reg_fcs):\n            cls_branch.append(Linear(self.embed_dims, self.embed_dims))\n            cls_branch.append(nn.LayerNorm(self.embed_dims))\n            cls_branch.append(nn.ReLU(inplace=True))\n        cls_branch.append(Linear(self.embed_dims, self.cls_out_channels))\n        cls_branch = nn.Sequential(*cls_branch)\n\n        reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            reg_branch.append(nn.ReLU())\n        reg_branch.append(Linear(self.embed_dims, self.code_size))\n        reg_branch = nn.Sequential(*reg_branch)\n\n        traj_branch = []\n        for _ in range(self.num_reg_fcs):\n            traj_branch.append(Linear(self.embed_dims*2, self.embed_dims*2))\n            traj_branch.append(nn.ReLU())\n        traj_branch.append(Linear(self.embed_dims*2, self.fut_ts*2))\n        traj_branch = nn.Sequential(*traj_branch)\n\n        traj_cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            traj_cls_branch.append(Linear(self.embed_dims*2, self.embed_dims*2))\n            traj_cls_branch.append(nn.LayerNorm(self.embed_dims*2))\n            traj_cls_branch.append(nn.ReLU(inplace=True))\n        traj_cls_branch.append(Linear(self.embed_dims*2, self.traj_num_cls))\n        traj_cls_branch = nn.Sequential(*traj_cls_branch)\n\n        map_cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            map_cls_branch.append(Linear(self.embed_dims, self.embed_dims))\n            map_cls_branch.append(nn.LayerNorm(self.embed_dims))\n            map_cls_branch.append(nn.ReLU(inplace=True))\n        map_cls_branch.append(Linear(self.embed_dims, self.map_cls_out_channels))\n        map_cls_branch = nn.Sequential(*map_cls_branch)\n\n        map_reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            map_reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            map_reg_branch.append(nn.ReLU())\n        map_reg_branch.append(Linear(self.embed_dims, self.map_code_size))\n        map_reg_branch = nn.Sequential(*map_reg_branch)\n\n\n        def _get_clones(module, N):\n            return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n        # last reg_branch is used to generate proposal from\n        # encode feature map when as_two_stage is True.\n        num_decoder_layers = 1\n        num_map_decoder_layers = 1\n        if self.transformer.decoder is not None:\n            num_decoder_layers = self.transformer.decoder.num_layers\n        if self.transformer.map_decoder is not None:\n            num_map_decoder_layers = self.transformer.map_decoder.num_layers\n        num_motion_decoder_layers = 1\n        num_pred = (num_decoder_layers + 1) if \\\n            self.as_two_stage else num_decoder_layers\n        motion_num_pred = (num_motion_decoder_layers + 1) if \\\n            self.as_two_stage else num_motion_decoder_layers\n        map_num_pred = (num_map_decoder_layers + 1) if \\\n            self.as_two_stage else num_map_decoder_layers\n\n        if self.with_box_refine:\n            self.cls_branches = _get_clones(cls_branch, num_pred)\n            self.reg_branches = _get_clones(reg_branch, num_pred)\n            self.traj_branches = _get_clones(traj_branch, motion_num_pred)\n            self.traj_cls_branches = _get_clones(traj_cls_branch, motion_num_pred)\n            self.map_cls_branches = _get_clones(map_cls_branch, map_num_pred)\n            self.map_reg_branches = _get_clones(map_reg_branch, map_num_pred)\n        else:\n            self.cls_branches = nn.ModuleList(\n                [cls_branch for _ in range(num_pred)])\n            self.reg_branches = nn.ModuleList(\n                [reg_branch for _ in range(num_pred)])\n            self.traj_branches = nn.ModuleList(\n                [traj_branch for _ in range(motion_num_pred)])\n            self.traj_cls_branches = nn.ModuleList(\n                [traj_cls_branch for _ in range(motion_num_pred)])\n            self.map_cls_branches = nn.ModuleList(\n                [map_cls_branch for _ in range(map_num_pred)])\n            self.map_reg_branches = nn.ModuleList(\n                [map_reg_branch for _ in range(map_num_pred)])\n\n        if not self.as_two_stage:\n            self.bev_embedding = nn.Embedding(\n                self.bev_h * self.bev_w, self.embed_dims)\n            self.query_embedding = nn.Embedding(self.num_query,\n                                                self.embed_dims * 2)\n            if self.map_query_embed_type == 'all_pts':\n                self.map_query_embedding = nn.Embedding(self.map_num_query,\n                                                    self.embed_dims * 2)\n            elif self.map_query_embed_type == 'instance_pts':\n                self.map_query_embedding = None\n                self.map_instance_embedding = nn.Embedding(self.map_num_vec, self.embed_dims * 2)\n                self.map_pts_embedding = nn.Embedding(self.map_num_pts_per_vec, self.embed_dims * 2)\n        \n        if self.motion_decoder is not None:\n            self.motion_decoder = build_transformer_layer_sequence(self.motion_decoder)\n            self.motion_mode_query = nn.Embedding(self.fut_mode, self.embed_dims)\t\n            self.motion_mode_query.weight.requires_grad = True\n            if self.use_pe:\n                self.pos_mlp_sa = nn.Linear(2, self.embed_dims)\n        else:\n            raise NotImplementedError('Not implement yet')\n\n        if self.motion_map_decoder is not None:\n            self.lane_encoder = LaneNet(256, 128, 3)\n            self.motion_map_decoder = build_transformer_layer_sequence(self.motion_map_decoder)\n            if self.use_pe:\n                self.pos_mlp = nn.Linear(2, self.embed_dims)\n        \n        if self.ego_his_encoder is not None:\n            self.ego_his_encoder = LaneNet(2, self.embed_dims//2, 3)\n        else:\n            self.ego_query = nn.Embedding(1, self.embed_dims)\t\n\n        if self.ego_agent_decoder is not None:\n            self.ego_agent_decoder = build_transformer_layer_sequence(self.ego_agent_decoder)\n            if self.use_pe:\n                self.ego_agent_pos_mlp = nn.Linear(2, self.embed_dims)\n\n        if self.ego_map_decoder is not None:\n            self.ego_map_decoder = build_transformer_layer_sequence(self.ego_map_decoder)\n            if self.use_pe:\n                self.ego_map_pos_mlp = nn.Linear(2, self.embed_dims)\n\n        ego_fut_decoder = []\n        ego_fut_dec_in_dim = self.embed_dims*2 + len(self.ego_lcf_feat_idx) \\\n            if self.ego_lcf_feat_idx is not None else self.embed_dims*2\n        for _ in range(self.num_reg_fcs):\n            ego_fut_decoder.append(Linear(ego_fut_dec_in_dim, ego_fut_dec_in_dim))\n            ego_fut_decoder.append(nn.ReLU())\n        ego_fut_decoder.append(Linear(ego_fut_dec_in_dim, self.fut_ts*2))\n        self.ego_fut_decoder = nn.Sequential(*ego_fut_decoder)\n        # 得分预测分支--liulin add\n        ego_fut_cls_decoder = []\n        for _ in range(self.num_reg_fcs):\n            ego_fut_cls_decoder.append(Linear(ego_fut_dec_in_dim, ego_fut_dec_in_dim))\n            ego_fut_cls_decoder.append(nn.LayerNorm(ego_fut_dec_in_dim))\n            ego_fut_cls_decoder.append(nn.ReLU())\n        ego_fut_cls_decoder.append(Linear(ego_fut_dec_in_dim, 1))\n        self.ego_fut_cls_decoder = nn.Sequential(*ego_fut_cls_decoder)\n        \n\n        self.agent_fus_mlp = nn.Sequential(\n            nn.Linear(self.fut_mode*2*self.embed_dims, self.embed_dims, bias=True),\n            nn.LayerNorm(self.embed_dims),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims, self.embed_dims, bias=True))\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the DeformDETR head.\"\"\"\n        self.transformer.init_weights()\n        if self.loss_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n        if self.loss_map_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.map_cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n        if self.loss_traj_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.traj_cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n        # for m in self.map_reg_branches:\n        #     constant_init(m[-1], 0, bias=0)\n        # nn.init.constant_(self.map_reg_branches[0][-1].bias.data[2:], 0.)\n        if self.motion_decoder is not None:\n            for p in self.motion_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n            nn.init.orthogonal_(self.motion_mode_query.weight)\n            if self.use_pe:\n                xavier_init(self.pos_mlp_sa, distribution='uniform', bias=0.)\n        if self.motion_map_decoder is not None:\n            for p in self.motion_map_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n            for p in self.lane_encoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n            if self.use_pe:\n                xavier_init(self.pos_mlp, distribution='uniform', bias=0.)\n        if self.ego_his_encoder is not None:\n            for p in self.ego_his_encoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n        if self.ego_agent_decoder is not None:\n            for p in self.ego_agent_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n        if self.ego_map_decoder is not None:\n            for p in self.ego_map_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n\n    # @auto_fp16(apply_to=('mlvl_feats'))\n    @force_fp32(apply_to=('mlvl_feats', 'prev_bev'))\n    def forward(self,\n                mlvl_feats,\n                img_metas,\n                prev_bev=None,\n                ego_fut_cmd=None,\n                only_bev=False,\n                ego_his_trajs=None,\n                ego_lcf_feat=None,\n            ):\n        \"\"\"Forward function.\n        Args:\n            mlvl_feats (tuple[Tensor]): Features from the upstream\n                network, each is a 5D-tensor with shape\n                (B, N, C, H, W).\n            prev_bev: previous bev featues\n            only_bev: only compute BEV features with encoder. \n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, theta, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n        \"\"\"\n        \n        #import pdb;pdb.set_trace()\n        bs, num_cam, _, _, _ = mlvl_feats[0].shape\n        dtype = mlvl_feats[0].dtype\n        object_query_embeds = self.query_embedding.weight.to(dtype)\n        \n        if self.map_query_embed_type == 'all_pts':\n            map_query_embeds = self.map_query_embedding.weight.to(dtype)\n        elif self.map_query_embed_type == 'instance_pts':\n            map_pts_embeds = self.map_pts_embedding.weight.unsqueeze(0)\n            map_instance_embeds = self.map_instance_embedding.weight.unsqueeze(1)\n            map_query_embeds = (map_pts_embeds + map_instance_embeds).flatten(0, 1).to(dtype)\n\n        bev_queries = self.bev_embedding.weight.to(dtype)\n\n        bev_mask = torch.zeros((bs, self.bev_h, self.bev_w),\n                               device=bev_queries.device).to(dtype)\n        bev_pos = self.positional_encoding(bev_mask).to(dtype)\n            \n        if only_bev:  # only use encoder to obtain BEV features, TODO: refine the workaround\n            return self.transformer.get_bev_features(\n                mlvl_feats,\n                bev_queries,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                img_metas=img_metas,\n                prev_bev=prev_bev,\n            )\n        else:\n            outputs = self.transformer(\n                mlvl_feats,\n                bev_queries,\n                object_query_embeds,\n                map_query_embeds,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                reg_branches=self.reg_branches if self.with_box_refine else None,  # noqa:E501\n                cls_branches=self.cls_branches if self.as_two_stage else None,\n                map_reg_branches=self.map_reg_branches if self.with_box_refine else None,  # noqa:E501\n                map_cls_branches=self.map_cls_branches if self.as_two_stage else None,\n                img_metas=img_metas,\n                prev_bev=prev_bev\n        )\n\n        bev_embed, hs, init_reference, inter_references, \\\n            map_hs, map_init_reference, map_inter_references = outputs\n\n        hs = hs.permute(0, 2, 1, 3)\n        outputs_classes = []\n        outputs_coords = []\n        outputs_coords_bev = []\n        outputs_trajs = []\n        outputs_trajs_classes = []\n\n        map_hs = map_hs.permute(0, 2, 1, 3)\n        map_outputs_classes = []\n        map_outputs_coords = []\n        map_outputs_pts_coords = []\n        map_outputs_coords_bev = []\n\n        for lvl in range(hs.shape[0]):\n            if lvl == 0:\n                reference = init_reference\n            else:\n                reference = inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            outputs_class = self.cls_branches[lvl](hs[lvl])\n            tmp = self.reg_branches[lvl](hs[lvl])\n\n            # TODO: check the shape of reference\n            assert reference.shape[-1] == 3\n            tmp[..., 0:2] = tmp[..., 0:2] + reference[..., 0:2]\n            tmp[..., 0:2] = tmp[..., 0:2].sigmoid()\n            outputs_coords_bev.append(tmp[..., 0:2].clone().detach())\n            tmp[..., 4:5] = tmp[..., 4:5] + reference[..., 2:3]\n            tmp[..., 4:5] = tmp[..., 4:5].sigmoid()\n            tmp[..., 0:1] = (tmp[..., 0:1] * (self.pc_range[3] -\n                             self.pc_range[0]) + self.pc_range[0])\n            tmp[..., 1:2] = (tmp[..., 1:2] * (self.pc_range[4] -\n                             self.pc_range[1]) + self.pc_range[1])\n            tmp[..., 4:5] = (tmp[..., 4:5] * (self.pc_range[5] -\n                             self.pc_range[2]) + self.pc_range[2])\n\n            # TODO: check if using sigmoid\n            outputs_coord = tmp\n            outputs_classes.append(outputs_class)\n            outputs_coords.append(outputs_coord)\n        \n        for lvl in range(map_hs.shape[0]):\n            if lvl == 0:\n                reference = map_init_reference\n            else:\n                reference = map_inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            map_outputs_class = self.map_cls_branches[lvl](\n                map_hs[lvl].view(bs,self.map_num_vec, self.map_num_pts_per_vec,-1).mean(2)\n            )\n            tmp = self.map_reg_branches[lvl](map_hs[lvl])\n            # TODO: check the shape of reference\n            assert reference.shape[-1] == 2\n            tmp[..., 0:2] += reference[..., 0:2]\n            tmp = tmp.sigmoid() # cx,cy,w,h\n            map_outputs_coord, map_outputs_pts_coord = self.map_transform_box(tmp)\n            map_outputs_coords_bev.append(map_outputs_pts_coord.clone().detach())\n            map_outputs_classes.append(map_outputs_class)\n            map_outputs_coords.append(map_outputs_coord)\n            map_outputs_pts_coords.append(map_outputs_pts_coord)\n        #import pdb;pdb.set_trace() \n        if self.motion_decoder is not None:\n            batch_size, num_agent = outputs_coords_bev[-1].shape[:2] # num_agent = 300\n            # motion_query\n            motion_query = hs[-1].permute(1, 0, 2)  # [A, B, D] # 300,1,256\n            mode_query = self.motion_mode_query.weight  # [fut_mode, D] [6,256]\n            # [M, B, D], M=A*fut_mode\n            motion_query = (motion_query[:, None, :, :] + mode_query[None, :, None, :]).flatten(0, 1)\n            if self.use_pe:\n                motion_coords = outputs_coords_bev[-1]  # [B, A, 2]\n                motion_pos = self.pos_mlp_sa(motion_coords)  # [B, A, D]\n                motion_pos = motion_pos.unsqueeze(2).repeat(1, 1, self.fut_mode, 1).flatten(1, 2)\n                motion_pos = motion_pos.permute(1, 0, 2)  # [M, B, D]\n            else:\n                motion_pos = None\n\n            if self.motion_det_score is not None:\n                motion_score = outputs_classes[-1]\n                max_motion_score = motion_score.max(dim=-1)[0]\n                invalid_motion_idx = max_motion_score < self.motion_det_score  # [B, A]\n                invalid_motion_idx = invalid_motion_idx.unsqueeze(2).repeat(1, 1, self.fut_mode).flatten(1, 2)\n            else:\n                invalid_motion_idx = None\n\n            motion_hs = self.motion_decoder(\n                query=motion_query,\n                key=motion_query,\n                value=motion_query,\n                query_pos=motion_pos,\n                key_pos=motion_pos,\n                key_padding_mask=invalid_motion_idx) # [1800,1,256]\n\n            if self.motion_map_decoder is not None:\n                # map preprocess\n                motion_coords = outputs_coords_bev[-1]  # [B, A, 2]\n                motion_coords = motion_coords.unsqueeze(2).repeat(1, 1, self.fut_mode, 1).flatten(1, 2)\n                map_query = map_hs[-1].view(batch_size, self.map_num_vec, self.map_num_pts_per_vec, -1)\n                map_query = self.lane_encoder(map_query)  # [B, P, pts, D] -> [B, P, D]\n                map_score = map_outputs_classes[-1]\n                map_pos = map_outputs_coords_bev[-1]\n                map_query, map_pos, key_padding_mask = self.select_and_pad_pred_map(\n                    motion_coords, map_query, map_score, map_pos,\n                    map_thresh=self.map_thresh, dis_thresh=self.dis_thresh,\n                    pe_normalization=self.pe_normalization, use_fix_pad=True)\n                map_query = map_query.permute(1, 0, 2)  # [P, B*M, D]\n                ca_motion_query = motion_hs.permute(1, 0, 2).flatten(0, 1).unsqueeze(0)\n\n                # position encoding\n                if self.use_pe:\n                    (num_query, batch) = ca_motion_query.shape[:2] \n                    motion_pos = torch.zeros((num_query, batch, 2), device=motion_hs.device)\n                    motion_pos = self.pos_mlp(motion_pos)\n                    map_pos = map_pos.permute(1, 0, 2)\n                    map_pos = self.pos_mlp(map_pos)\n                else:\n                    motion_pos, map_pos = None, None\n                \n                ca_motion_query = self.motion_map_decoder(\n                    query=ca_motion_query,\n                    key=map_query,\n                    value=map_query,\n                    query_pos=motion_pos,\n                    key_pos=map_pos,\n                    key_padding_mask=key_padding_mask)\n            else:\n                ca_motion_query = motion_hs.permute(1, 0, 2).flatten(0, 1).unsqueeze(0)\n\n            batch_size = outputs_coords_bev[-1].shape[0]\n            motion_hs = motion_hs.permute(1, 0, 2).unflatten(\n                dim=1, sizes=(num_agent, self.fut_mode)\n            )\n            ca_motion_query = ca_motion_query.squeeze(0).unflatten(\n                dim=0, sizes=(batch_size, num_agent, self.fut_mode)\n            )\n            motion_hs = torch.cat([motion_hs, ca_motion_query], dim=-1)  # [B, A, fut_mode, 2D]\n        else:\n            raise NotImplementedError('Not implement yet')\n\n        outputs_traj = self.traj_branches[0](motion_hs)\n        outputs_trajs.append(outputs_traj)\n        #import pdb;pdb.set_trace()\n        outputs_traj_class = self.traj_cls_branches[0](motion_hs)\n        outputs_trajs_classes.append(outputs_traj_class.squeeze(-1))\n        (batch, num_agent) = motion_hs.shape[:2]\n             \n        map_outputs_classes = torch.stack(map_outputs_classes)\n        map_outputs_coords = torch.stack(map_outputs_coords)\n        map_outputs_pts_coords = torch.stack(map_outputs_pts_coords)\n\n        outputs_classes = torch.stack(outputs_classes)\n        outputs_coords = torch.stack(outputs_coords)\n        outputs_trajs = torch.stack(outputs_trajs) # [1,1,300,6,12]\n        outputs_trajs_classes = torch.stack(outputs_trajs_classes) # [1,1,300,6]\n\n        # planning\n        #import pdb;pdb.set_trace()\n        (batch, num_agent) = motion_hs.shape[:2]\n        if self.ego_his_encoder is not None:\n            ego_his_feats = self.ego_his_encoder(ego_his_trajs)  # [B, 1, dim]\n        else:\n            ego_his_feats = self.ego_query.weight.unsqueeze(0).repeat(batch, 1, 1)\n        # Interaction\n        ego_query = ego_his_feats\n        ego_pos = torch.zeros((batch, 1, 2), device=ego_query.device)\n        ego_pos_emb = self.ego_agent_pos_mlp(ego_pos)\n        agent_conf = outputs_classes[-1]\n        agent_query = motion_hs.reshape(batch, num_agent, -1)\n        agent_query = self.agent_fus_mlp(agent_query) # [B, A, fut_mode, 2*D] -> [B, A, D]\n        agent_pos = outputs_coords_bev[-1]\n        agent_query, agent_pos, agent_mask = self.select_and_pad_query(\n            agent_query, agent_pos, agent_conf,\n            score_thresh=self.query_thresh, use_fix_pad=self.query_use_fix_pad\n        )\n        agent_pos_emb = self.ego_agent_pos_mlp(agent_pos)\n        # ego <-> agent interaction\n        ego_agent_query = self.ego_agent_decoder(\n            query=ego_query.permute(1, 0, 2),\n            key=agent_query.permute(1, 0, 2),\n            value=agent_query.permute(1, 0, 2),\n            query_pos=ego_pos_emb.permute(1, 0, 2),\n            key_pos=agent_pos_emb.permute(1, 0, 2),\n            key_padding_mask=agent_mask)\n\n        # ego <-> map interaction\n        ego_pos = torch.zeros((batch, 1, 2), device=agent_query.device)\n        ego_pos_emb = self.ego_map_pos_mlp(ego_pos)\n        map_query = map_hs[-1].view(batch_size, self.map_num_vec, self.map_num_pts_per_vec, -1)\n        map_query = self.lane_encoder(map_query)  # [B, P, pts, D] -> [B, P, D]\n        map_conf = map_outputs_classes[-1]\n        map_pos = map_outputs_coords_bev[-1]\n        # use the most close pts pos in each map inst as the inst's pos\n        batch, num_map = map_pos.shape[:2]\n        map_dis = torch.sqrt(map_pos[..., 0]**2 + map_pos[..., 1]**2)\n        min_map_pos_idx = map_dis.argmin(dim=-1).flatten()  # [B*P]\n        min_map_pos = map_pos.flatten(0, 1)  # [B*P, pts, 2]\n        min_map_pos = min_map_pos[range(min_map_pos.shape[0]), min_map_pos_idx]  # [B*P, 2]\n        min_map_pos = min_map_pos.view(batch, num_map, 2)  # [B, P, 2]\n        map_query, map_pos, map_mask = self.select_and_pad_query(\n            map_query, min_map_pos, map_conf,\n            score_thresh=self.query_thresh, use_fix_pad=self.query_use_fix_pad\n        )\n        map_pos_emb = self.ego_map_pos_mlp(map_pos)\n        ego_map_query = self.ego_map_decoder(\n            query=ego_agent_query,\n            key=map_query.permute(1, 0, 2),\n            value=map_query.permute(1, 0, 2),\n            query_pos=ego_pos_emb.permute(1, 0, 2),\n            key_pos=map_pos_emb.permute(1, 0, 2),\n            key_padding_mask=map_mask)\n\n        if self.ego_his_encoder is not None and self.ego_lcf_feat_idx is not None:\n            ego_feats = torch.cat(\n                [ego_his_feats,\n                 ego_map_query.permute(1, 0, 2),\n                 ego_lcf_feat.squeeze(1)[..., self.ego_lcf_feat_idx]],\n                dim=-1\n            )  # [B, 1, 2D+2]\n        elif self.ego_his_encoder is not None and self.ego_lcf_feat_idx is None:\n            ego_feats = torch.cat(\n                [ego_his_feats,\n                 ego_map_query.permute(1, 0, 2)],\n                dim=-1\n            )  # [B, 1, 2D]\n        elif self.ego_his_encoder is None and self.ego_lcf_feat_idx is not None:                \n            ego_feats = torch.cat(\n                [ego_agent_query.permute(1, 0, 2),\n                 ego_map_query.permute(1, 0, 2),\n                 ego_lcf_feat.squeeze(1)[..., self.ego_lcf_feat_idx]],\n                dim=-1\n            )  # [B, 1, 2D+2]\n        elif self.ego_his_encoder is None and self.ego_lcf_feat_idx is None:                \n            ego_feats = torch.cat(\n                [ego_agent_query.permute(1, 0, 2),\n                 ego_map_query.permute(1, 0, 2)],\n                dim=-1\n            )  # [B, 1, 2D]  \n\n        # Ego prediction\n        #import pdb;pdb.set_trace()\n        \n        ego_feats = ego_feats.repeat(1,self.ego_fut_mode*self.ego_fut_inmode_mode,1)\n        outputs_ego_trajs = self.ego_fut_decoder(ego_feats)\n        outputs_ego_trajs = outputs_ego_trajs.reshape(outputs_ego_trajs.shape[0], \n                                                      self.ego_fut_mode,\n                                                      self.ego_fut_inmode_mode, self.fut_ts, 2)\n        outputs_ego_classifcation = self.ego_fut_cls_decoder(ego_feats)\n        #self.prev_cmd = None\n        #self.prev_ego_feature = None\n        # ego_his_trajs [1,1,6,2] [1,6,6,6,2]\n        #import pdb;pdb.set_trace()\n        if ego_his_trajs != None:\n            selected_idx = self.select_best_reg(outputs_ego_trajs,ego_his_trajs) # [bs,1]\n            ego_his_feats = self.his_enhance_encoder(ego_his_feats) # [1,1,512]\n            ego_his_feats = ego_his_feats.repeat(1, ego_feats.shape[1], 1)\n            # \n            his_mask = torch.zeros_like(ego_his_feats).to(ego_his_feats.device)\n            #his_rows = torch.arange(ego_his_feats.shape[1], device=ego_his_feats.device).unsqueeze(0).expand(ego_his_feats.shape[0], -1)\n            his_mask[torch.arange(ego_his_feats.shape[0]).unsqueeze(1), selected_idx, :] = 1\n            #import pdb;pdb.set_trace()\n            ego_feats = ego_feats + ego_his_feats*his_mask\n        #import pdb;pdb.set_trace()\n        \n        #for i in range(ego_his_feats.shape[0]):\n        #    ego_feats[i][selected_idx[i]] = ego_feats[i][selected_idx[i]] + ego_his_feats[i][0]\n        \n        \n        \n        outputs_ego_trajs_refine = self.ego_fut_decoder(ego_feats)\n        outputs_ego_trajs_refine = outputs_ego_trajs_refine.reshape(outputs_ego_trajs_refine.shape[0], \n                                                      self.ego_fut_mode,\n                                                      self.ego_fut_inmode_mode, self.fut_ts, 2)\n        outputs_ego_classifcation_refine = self.ego_fut_cls_decoder(ego_feats)\n\n        outs = {\n            'bev_embed': bev_embed,\n            'all_cls_scores': outputs_classes,\n            'all_bbox_preds': outputs_coords,\n            'all_traj_preds': outputs_trajs.repeat(outputs_coords.shape[0], 1, 1, 1, 1),\n            'all_traj_cls_scores': outputs_trajs_classes.repeat(outputs_coords.shape[0], 1, 1, 1),\n            'map_all_cls_scores': map_outputs_classes,\n            'map_all_bbox_preds': map_outputs_coords,\n            'map_all_pts_preds': map_outputs_pts_coords,\n            'enc_cls_scores': None,\n            'enc_bbox_preds': None,\n            'map_enc_cls_scores': None,\n            'map_enc_bbox_preds': None,\n            'map_enc_pts_preds': None,\n            'ego_fut_classification': outputs_ego_classifcation,\n            'ego_fut_preds': outputs_ego_trajs,\n            'ego_fut_classification_refine': outputs_ego_classifcation_refine,\n            'ego_fut_preds_refine': outputs_ego_trajs_refine,\n        }\n\n        return outs\n\n    def map_transform_box(self, pts, y_first=False):\n        \"\"\"\n        Converting the points set into bounding box.\n\n        Args:\n            pts: the input points sets (fields), each points\n                set (fields) is represented as 2n scalar.\n            y_first: if y_fisrt=True, the point set is represented as\n                [y1, x1, y2, x2 ... yn, xn], otherwise the point set is\n                represented as [x1, y1, x2, y2 ... xn, yn].\n        Returns:\n            The bbox [cx, cy, w, h] transformed from points.\n        \"\"\"\n        pts_reshape = pts.view(pts.shape[0], self.map_num_vec,\n                                self.map_num_pts_per_vec,2)\n        pts_y = pts_reshape[:, :, :, 0] if y_first else pts_reshape[:, :, :, 1]\n        pts_x = pts_reshape[:, :, :, 1] if y_first else pts_reshape[:, :, :, 0]\n        if self.map_transform_method == 'minmax':\n            # import pdb;pdb.set_trace()\n\n            xmin = pts_x.min(dim=2, keepdim=True)[0]\n            xmax = pts_x.max(dim=2, keepdim=True)[0]\n            ymin = pts_y.min(dim=2, keepdim=True)[0]\n            ymax = pts_y.max(dim=2, keepdim=True)[0]\n            bbox = torch.cat([xmin, ymin, xmax, ymax], dim=2)\n            bbox = bbox_xyxy_to_cxcywh(bbox)\n        else:\n            raise NotImplementedError\n        return bbox, pts_reshape\n\n    def _get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           gt_labels,\n                           gt_bboxes,\n                           gt_attr_labels,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 10].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 9) in [x,y,z,w,l,h,yaw,vx,vy] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        gt_fut_trajs = gt_attr_labels[:, :self.fut_ts*2]\n        gt_fut_masks = gt_attr_labels[:, self.fut_ts*2:self.fut_ts*3]\n        gt_bbox_c = gt_bboxes.shape[-1]\n        num_gt_bbox, gt_traj_c = gt_fut_trajs.shape\n\n        assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,\n                                             gt_labels, gt_bboxes_ignore)\n\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes,),\n                                    self.num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)[..., :gt_bbox_c]\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n\n        # trajs targets\n        traj_targets = torch.zeros((num_bboxes, gt_traj_c), dtype=torch.float32, device=bbox_pred.device)\n        traj_weights = torch.zeros_like(traj_targets)\n        traj_targets[pos_inds] = gt_fut_trajs[sampling_result.pos_assigned_gt_inds]\n        traj_weights[pos_inds] = 1.0\n\n        # Filter out invalid fut trajs\n        traj_masks = torch.zeros_like(traj_targets)  # [num_bboxes, fut_ts*2]\n        gt_fut_masks = gt_fut_masks.unsqueeze(-1).repeat(1, 1, 2).view(num_gt_bbox, -1)  # [num_gt_bbox, fut_ts*2]\n        traj_masks[pos_inds] = gt_fut_masks[sampling_result.pos_assigned_gt_inds]\n        traj_weights = traj_weights * traj_masks\n\n        # Extra future timestamp mask for controlling pred horizon\n        fut_ts_mask = torch.zeros((num_bboxes, self.fut_ts, 2),\n                                   dtype=torch.float32, device=bbox_pred.device)\n        fut_ts_mask[:, :self.valid_fut_ts, :] = 1.0\n        fut_ts_mask = fut_ts_mask.view(num_bboxes, -1)\n        traj_weights = traj_weights * fut_ts_mask\n\n        # DETR\n        bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes\n\n        return (\n            labels, label_weights, bbox_targets, bbox_weights, traj_targets,\n            traj_weights, traj_masks.view(-1, self.fut_ts, 2)[..., 0],\n            pos_inds, neg_inds\n        )\n\n    def _map_get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           pts_pred,\n                           gt_labels,\n                           gt_bboxes,\n                           gt_shifts_pts,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        gt_c = gt_bboxes.shape[-1]\n        assign_result, order_index = self.map_assigner.assign(bbox_pred, cls_score, pts_pred,\n                                             gt_bboxes, gt_labels, gt_shifts_pts,\n                                             gt_bboxes_ignore)\n\n        sampling_result = self.map_sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes,),\n                                    self.map_num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)[..., :gt_c]\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n        # pts targets\n        if order_index is None:\n            assigned_shift = gt_labels[sampling_result.pos_assigned_gt_inds]\n        else:\n            assigned_shift = order_index[sampling_result.pos_inds, sampling_result.pos_assigned_gt_inds]\n        pts_targets = pts_pred.new_zeros((pts_pred.size(0),\n                        pts_pred.size(1), pts_pred.size(2)))\n        pts_weights = torch.zeros_like(pts_targets)\n        pts_weights[pos_inds] = 1.0\n        # DETR\n        bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes\n        pts_targets[pos_inds] = gt_shifts_pts[sampling_result.pos_assigned_gt_inds,assigned_shift,:,:]\n        return (labels, label_weights, bbox_targets, bbox_weights,\n                pts_targets, pts_weights,\n                pos_inds, neg_inds)\n\n    def get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_attr_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            tuple: a tuple containing the following targets.\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, traj_targets_list, traj_weights_list,\n         gt_fut_masks_list, pos_inds_list, neg_inds_list) = multi_apply(\n            self._get_target_single, cls_scores_list, bbox_preds_list,\n            gt_labels_list, gt_bboxes_list, gt_attr_labels_list, gt_bboxes_ignore_list\n         )\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n                traj_targets_list, traj_weights_list, gt_fut_masks_list, num_total_pos, num_total_neg)\n\n    def map_get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    pts_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_shifts_pts_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            tuple: a tuple containing the following targets.\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, pts_targets_list, pts_weights_list,\n         pos_inds_list, neg_inds_list) = multi_apply(\n            self._map_get_target_single, cls_scores_list, bbox_preds_list,pts_preds_list,\n            gt_labels_list, gt_bboxes_list, gt_shifts_pts_list, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, pts_targets_list, pts_weights_list,\n                num_total_pos, num_total_neg)\n\n    def loss_planning_refine(self,\n                      ego_fut_preds,\n                      ego_fut_classification,\n                      ego_fut_gt,\n                      ego_fut_masks,\n                      ego_fut_cmd,\n                      lane_preds,\n                      lane_score_preds,\n                      agent_preds,\n                      agent_fut_preds,\n                      agent_score_preds,\n                      agent_fut_cls_preds):\n        bs = ego_fut_preds.shape[0] # [1,6,6,6,2]\n        bs_indices = torch.arange(bs, device=ego_fut_preds.device)\n        cmd = ego_fut_cmd.argmax(dim=-1)\n        ego_fut_classification = ego_fut_classification.reshape(ego_fut_classification.shape[0], 6, 1, 6) # [1,6,1,6]\n        ego_fut_preds = ego_fut_preds.unsqueeze(2) # [1,6,1,6,6,2]\n        ego_fut_classification = ego_fut_classification[bs_indices, cmd] # [1,1,6]\n        ego_fut_preds = ego_fut_preds[bs_indices, cmd] # [1,1,6,6,2]\n        #import pdb;pdb.set_trace()\n        \n        ego_cls_target = self.get_plan_cls_target(ego_fut_preds, ego_fut_gt, ego_fut_masks.unsqueeze(1)) # [bs,1]\n        ego_cls_weight = ego_fut_masks.unsqueeze(1).any(dim=-1)\n        \n        cls_loss = self.loss_plan_cls(ego_fut_classification.flatten(end_dim=1), \n                                      ego_cls_target.flatten(end_dim=1), \n                                      weight=ego_cls_weight.flatten(end_dim=1))\n        \n        best_reg = self.get_best_reg(ego_fut_preds,ego_fut_gt.unsqueeze(1),ego_fut_masks.unsqueeze(1)) #[1,1]\n        #import pdb;pdb.set_trace()\n        # ego_fut_classification [1,6,6]\n        ego_best_cmd = torch.zeros([ego_fut_cmd.shape[0],6]).to(ego_fut_cmd.device)\n        row_indices = torch.arange(ego_fut_cmd.shape[0]).to(ego_fut_cmd.device)\n        col_indices = best_reg.squeeze(1).to(ego_fut_cmd.device)\n        ego_best_cmd[row_indices, col_indices] = 1\n        \n        ego_fut_gt = ego_fut_gt.unsqueeze(1).repeat(1, self.ego_fut_mode, 1, 1) # [1,6,6,2]\n        # # [6,1,6,6,2], [6,1,6,2], [6,1,6]\n        # best_reg = self.get_best_reg()\n        #ego_cls_target = self.get_plan_cls_target(,ego_fut_masks) # changing\n        #loss_plan_l1_weight = ego_fut_cmd[..., None, None] * ego_fut_masks[:, None, :, None]\n        loss_plan_l1_weight = ego_best_cmd[..., None, None] * ego_fut_masks[:, None, :, None]\n        loss_plan_l1_weight = loss_plan_l1_weight.repeat(1, 1, 1, 2)\n        #import pdb;pdb.set_trace()\n        ego_fut_preds = ego_fut_preds.squeeze(1)\n        loss_plan_l1 = self.loss_plan_reg(\n            ego_fut_preds,\n            ego_fut_gt,\n            loss_plan_l1_weight\n        )\n        \n        #import pdb;pdb.set_trace()\n        loss_plan_bound = self.loss_plan_bound(\n            ego_fut_preds[ego_fut_cmd==1],\n            lane_preds,\n            lane_score_preds,\n            weight=ego_fut_masks\n        )\n\n        loss_plan_col = self.loss_plan_col(\n            ego_fut_preds[ego_fut_cmd==1],\n            agent_preds,\n            agent_fut_preds,\n            agent_score_preds,\n            agent_fut_cls_preds,\n            weight=ego_fut_masks[:, :, None].repeat(1, 1, 2)\n        )\n\n        loss_plan_dir = self.loss_plan_dir(\n            ego_fut_preds[ego_fut_cmd==1],\n            lane_preds,\n            lane_score_preds,\n            weight=ego_fut_masks\n        )\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_plan_l1 = torch.nan_to_num(loss_plan_l1)\n            loss_plan_bound = torch.nan_to_num(loss_plan_bound)\n            loss_plan_col = torch.nan_to_num(loss_plan_col)\n            loss_plan_dir = torch.nan_to_num(loss_plan_dir)\n        \n        loss_plan_dict = dict()\n        loss_plan_dict['loss_plan_reg_refine'] = loss_plan_l1\n        loss_plan_dict['loss_plan_bound_refine'] = loss_plan_bound\n        loss_plan_dict['loss_plan_col_refine'] = loss_plan_col\n        loss_plan_dict['loss_plan_dir_refine'] = loss_plan_dir\n        loss_plan_dict['loss_plan_cls_refine'] = cls_loss\n        \n        return loss_plan_dict\n        \n    def loss_planning(self,\n                      ego_fut_preds,\n                      ego_fut_classification,\n                      ego_fut_gt,\n                      ego_fut_masks,\n                      ego_fut_cmd,\n                      lane_preds,\n                      lane_score_preds,\n                      agent_preds,\n                      agent_fut_preds,\n                      agent_score_preds,\n                      agent_fut_cls_preds):\n        \"\"\"\"Loss function for ego vehicle planning.\n        Args:\n            ego_fut_preds (Tensor): [B, ego_fut_mode, fut_ts, 2]\n            ego_fut_gt (Tensor): [B, fut_ts, 2]\n            ego_fut_masks (Tensor): [B, fut_ts]\n            ego_fut_cmd (Tensor): [B, ego_fut_mode]\n            lane_preds (Tensor): [B, num_vec, num_pts, 2]\n            lane_score_preds (Tensor): [B, num_vec, 3]\n            agent_preds (Tensor): [B, num_agent, 2]\n            agent_fut_preds (Tensor): [B, num_agent, fut_mode, fut_ts, 2]\n            agent_score_preds (Tensor): [B, num_agent, 10]\n            agent_fut_cls_scores (Tensor): [B, num_agent, fut_mode]\n        Returns:\n            loss_plan_reg (Tensor): planning reg loss.\n            loss_plan_bound (Tensor): planning map boundary constraint loss.\n            loss_plan_col (Tensor): planning col constraint loss.\n            loss_plan_dir (Tensor): planning directional constraint loss.\n        \"\"\"\n        #import pdb;pdb.set_trace() # [1,6,2] [batchsize,,]\n        # [1,6,6,2] => [1,1,6,6,2]\n        bs = ego_fut_preds.shape[0] # [1,6,6,6,2]\n        bs_indices = torch.arange(bs, device=ego_fut_preds.device)\n        cmd = ego_fut_cmd.argmax(dim=-1)\n        ego_fut_classification = ego_fut_classification.reshape(ego_fut_classification.shape[0], 6, 1, 6) # [1,6,1,6]\n        ego_fut_preds = ego_fut_preds.unsqueeze(2) # [1,6,1,6,6,2]\n        ego_fut_classification = ego_fut_classification[bs_indices, cmd] # [1,1,6]\n        ego_fut_preds = ego_fut_preds[bs_indices, cmd] # [1,1,6,6,2]\n        #import pdb;pdb.set_trace()\n        \n        ego_cls_target = self.get_plan_cls_target(ego_fut_preds, ego_fut_gt, ego_fut_masks.unsqueeze(1)) # [bs,1]\n        ego_cls_weight = ego_fut_masks.unsqueeze(1).any(dim=-1)\n        \n        cls_loss = self.loss_plan_cls(ego_fut_classification.flatten(end_dim=1), \n                                      ego_cls_target.flatten(end_dim=1), \n                                      weight=ego_cls_weight.flatten(end_dim=1))\n        \n        # [1, 1, 6, 6, 2] [1,1,6,2]\n        best_reg = self.get_best_reg(ego_fut_preds,ego_fut_gt.unsqueeze(1),ego_fut_masks.unsqueeze(1)) #[1,1]\n        #import pdb;pdb.set_trace()\n        # ego_fut_classification [1,6,6]\n        ego_best_cmd = torch.zeros([ego_fut_cmd.shape[0],6]).to(ego_fut_cmd.device)\n        row_indices = torch.arange(ego_fut_cmd.shape[0]).to(ego_fut_cmd.device)\n        col_indices = best_reg.squeeze(1).to(ego_fut_cmd.device)\n        ego_best_cmd[row_indices, col_indices] = 1\n        \n        ego_fut_gt = ego_fut_gt.unsqueeze(1).repeat(1, self.ego_fut_mode, 1, 1) # [1,6,6,2]\n        # # [6,1,6,6,2], [6,1,6,2], [6,1,6]\n        # best_reg = self.get_best_reg()\n        #ego_cls_target = self.get_plan_cls_target(,ego_fut_masks) # changing\n        #loss_plan_l1_weight = ego_fut_cmd[..., None, None] * ego_fut_masks[:, None, :, None]\n        loss_plan_l1_weight = ego_best_cmd[..., None, None] * ego_fut_masks[:, None, :, None]\n        loss_plan_l1_weight = loss_plan_l1_weight.repeat(1, 1, 1, 2)\n        #import pdb;pdb.set_trace()\n        ego_fut_preds = ego_fut_preds.squeeze(1)\n        loss_plan_l1 = self.loss_plan_reg(\n            ego_fut_preds,\n            ego_fut_gt,\n            loss_plan_l1_weight\n        )\n        \n        #import pdb;pdb.set_trace()\n        loss_plan_bound = self.loss_plan_bound(\n            ego_fut_preds[ego_fut_cmd==1],\n            lane_preds,\n            lane_score_preds,\n            weight=ego_fut_masks\n        )\n\n        loss_plan_col = self.loss_plan_col(\n            ego_fut_preds[ego_fut_cmd==1],\n            agent_preds,\n            agent_fut_preds,\n            agent_score_preds,\n            agent_fut_cls_preds,\n            weight=ego_fut_masks[:, :, None].repeat(1, 1, 2)\n        )\n\n        loss_plan_dir = self.loss_plan_dir(\n            ego_fut_preds[ego_fut_cmd==1],\n            lane_preds,\n            lane_score_preds,\n            weight=ego_fut_masks\n        )\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_plan_l1 = torch.nan_to_num(loss_plan_l1)\n            loss_plan_bound = torch.nan_to_num(loss_plan_bound)\n            loss_plan_col = torch.nan_to_num(loss_plan_col)\n            loss_plan_dir = torch.nan_to_num(loss_plan_dir)\n        \n        loss_plan_dict = dict()\n        loss_plan_dict['loss_plan_reg'] = loss_plan_l1\n        loss_plan_dict['loss_plan_bound'] = loss_plan_bound\n        loss_plan_dict['loss_plan_col'] = loss_plan_col\n        loss_plan_dict['loss_plan_dir'] = loss_plan_dir\n        loss_plan_dict['loss_plan_cls'] = cls_loss\n        #import pdb;pdb.set_trace()\n\n        return loss_plan_dict\n    \n    def loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    traj_preds,\n                    traj_cls_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_attr_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,\n                                           gt_bboxes_list, gt_labels_list,\n                                           gt_attr_labels_list, gt_bboxes_ignore_list)\n\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         traj_targets_list, traj_weights_list, gt_fut_masks_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n        traj_targets = torch.cat(traj_targets_list, 0)\n        traj_weights = torch.cat(traj_weights_list, 0)\n        gt_fut_masks = torch.cat(gt_fut_masks_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_cls(cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # regression L1 loss\n        bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))\n        normalized_bbox_targets = normalize_bbox(bbox_targets, self.pc_range)\n        isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)\n        bbox_weights = bbox_weights * self.code_weights\n        loss_bbox = self.loss_bbox(\n            bbox_preds[isnotnan, :10],\n            normalized_bbox_targets[isnotnan, :10],\n            bbox_weights[isnotnan, :10],\n            avg_factor=num_total_pos)\n\n        # traj regression loss\n        best_traj_preds = self.get_best_fut_preds(\n            traj_preds.reshape(-1, self.fut_mode, self.fut_ts, 2),\n            traj_targets.reshape(-1, self.fut_ts, 2), gt_fut_masks)\n\n        neg_inds = (bbox_weights[:, 0] == 0)\n        traj_labels = self.get_traj_cls_target(\n            traj_preds.reshape(-1, self.fut_mode, self.fut_ts, 2),\n            traj_targets.reshape(-1, self.fut_ts, 2),\n            gt_fut_masks, neg_inds)\n\n        loss_traj = self.loss_traj(\n            best_traj_preds[isnotnan],\n            traj_targets[isnotnan],\n            traj_weights[isnotnan],\n            avg_factor=num_total_pos)\n\n        if self.use_traj_lr_warmup:\n            loss_scale_factor = get_traj_warmup_loss_weight(self.epoch, self.tot_epoch)\n            loss_traj = loss_scale_factor * loss_traj\n\n        # traj classification loss\n        traj_cls_scores = traj_cls_preds.reshape(-1, self.fut_mode)\n        # construct weighted avg_factor to match with the official DETR repo\n        traj_cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.traj_bg_cls_weight\n        if self.sync_cls_avg_factor:\n            traj_cls_avg_factor = reduce_mean(\n                traj_cls_scores.new_tensor([traj_cls_avg_factor]))\n\n        traj_cls_avg_factor = max(traj_cls_avg_factor, 1)\n        #import pdb;pdb.set_trace()\n        loss_traj_cls = self.loss_traj_cls(\n            traj_cls_scores, traj_labels, label_weights, avg_factor=traj_cls_avg_factor\n        )\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_cls = torch.nan_to_num(loss_cls)\n            loss_bbox = torch.nan_to_num(loss_bbox)\n            loss_traj = torch.nan_to_num(loss_traj)\n            loss_traj_cls = torch.nan_to_num(loss_traj_cls)\n\n        return loss_cls, loss_bbox, loss_traj, loss_traj_cls\n\n    def get_best_fut_preds(self,\n             traj_preds,\n             traj_targets,\n             gt_fut_masks):\n        \"\"\"\"Choose best preds among all modes.\n        Args:\n            traj_preds (Tensor): MultiModal traj preds with shape (num_box_preds, fut_mode, fut_ts, 2).\n            traj_targets (Tensor): Ground truth traj for each pred box with shape (num_box_preds, fut_ts, 2).\n            gt_fut_masks (Tensor): Ground truth traj mask with shape (num_box_preds, fut_ts).\n            pred_box_centers (Tensor): Pred box centers with shape (num_box_preds, 2).\n            gt_box_centers (Tensor): Ground truth box centers with shape (num_box_preds, 2).\n\n        Returns:\n            best_traj_preds (Tensor): best traj preds (min displacement error with gt)\n                with shape (num_box_preds, fut_ts*2).\n        \"\"\"\n\n        cum_traj_preds = traj_preds.cumsum(dim=-2)\n        cum_traj_targets = traj_targets.cumsum(dim=-2)\n\n        # Get min pred mode indices.\n        # (num_box_preds, fut_mode, fut_ts)\n        dist = torch.linalg.norm(cum_traj_targets[:, None, :, :] - cum_traj_preds, dim=-1)\n        dist = dist * gt_fut_masks[:, None, :]\n        dist = dist[..., -1]\n        dist[torch.isnan(dist)] = dist[torch.isnan(dist)] * 0\n        min_mode_idxs = torch.argmin(dist, dim=-1).tolist()\n        box_idxs = torch.arange(traj_preds.shape[0]).tolist()\n        best_traj_preds = traj_preds[box_idxs, min_mode_idxs, :, :].reshape(-1, self.fut_ts*2)\n\n        return best_traj_preds\n    \n    def get_best_reg(self,\n        reg_preds, \n        reg_target, \n        reg_weight\n    ):  \n        bs, num_pred, mode, ts, d = reg_preds.shape # plan [1,1,6,6,2]\n        reg_preds_cum = reg_preds.cumsum(dim=-2)\n        reg_target_cum = reg_target.cumsum(dim=-2)\n        #import pdb;pdb.set_trace() # [1,1,1,6,2]  [1,1,6,6,2]\n        dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1) # [6,1,6,6]\n        dist = dist * reg_weight.unsqueeze(2) # reg_weight.unsqueeze(2) = [6,1,6,6]\n        dist = dist.mean(dim=-1)\n        mode_idx = torch.argmin(dist, dim=-1) # [6,1] 0,4,1,0,0,1\n        #mode_idx = mode_idx[..., None, None, None].repeat(1, 1, 1, ts, d)\n        #best_reg = torch.gather(reg_preds, 2, mode_idx).squeeze(2) # torch.Size([6, 1, 6, 2])\n        return mode_idx\n    \n    \n    def select_best_reg(self, reg_preds, reg_target):\n        #import pdb;pdb.set_trace()\n        bs, num_pred, mode, ts, d = reg_preds.shape # plan [1,6,6,6,2]\n        reg_preds_cum = reg_preds.cumsum(dim=-2)\n        reg_preds_cum = reg_preds_cum.reshape(bs, num_pred*mode, ts, d) # [1,36,6,2]\n        reg_target_cum = reg_target.cumsum(dim=-2) # [1,1,6,2]\n        reg_preds_cum = reg_preds_cum.unsqueeze(1) # [1,1,36,6,2]\n        #import pdb;pdb.set_trace()\n        dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1) # [6,1,6,6]\n        #dist = dist * reg_weight.unsqueeze(2) # reg_weight.unsqueeze(2) = [6,1,6,6]\n        dist = dist.mean(dim=-1)\n        mode_idx = torch.argmin(dist, dim=-1) # [6,1] 0,4,1,0,0,1\n        return mode_idx\n    \n    def get_traj_cls_target(self,\n             traj_preds,\n             traj_targets,\n             gt_fut_masks,\n             neg_inds):\n        \"\"\"\"Get Trajectory mode classification target.\n        Args:\n            traj_preds (Tensor): MultiModal traj preds with shape (num_box_preds, fut_mode, fut_ts, 2).\n            traj_targets (Tensor): Ground truth traj for each pred box with shape (num_box_preds, fut_ts, 2).\n            gt_fut_masks (Tensor): Ground truth traj mask with shape (num_box_preds, fut_ts).\n            neg_inds (Tensor): Negtive indices with shape (num_box_preds,)\n\n        Returns:\n            traj_labels (Tensor): traj cls labels (num_box_preds,).\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        cum_traj_preds = traj_preds.cumsum(dim=-2)\n        cum_traj_targets = traj_targets.cumsum(dim=-2)\n\n        # Get min pred mode indices.\n        # (num_box_preds, fut_mode, fut_ts)\n        dist = torch.linalg.norm(cum_traj_targets[:, None, :, :] - cum_traj_preds, dim=-1)\n        dist = dist * gt_fut_masks[:, None, :]\n        dist = dist[..., -1]\n        dist[torch.isnan(dist)] = dist[torch.isnan(dist)] * 0\n        traj_labels = torch.argmin(dist, dim=-1)\n        traj_labels[neg_inds] = self.fut_mode\n\n        return traj_labels\n    \n    def get_plan_cls_target(self, reg_preds, \n                       reg_target, \n                       reg_weight\n        ):\n        #import pdb;pdb.set_trace()\n        bs, num_pred, mode, ts, d = reg_preds.shape # [1,1,6,6,2]\n        reg_preds_cum = reg_preds.cumsum(dim=-2)\n        reg_target_cum = reg_target.cumsum(dim=-2)\n        dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1)\n        dist = dist * reg_weight.unsqueeze(2)\n        dist = dist.mean(dim=-1)\n        mode_idx = torch.argmin(dist, dim=-1)\n        return mode_idx\n            \n    def map_loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    pts_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_shifts_pts_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_pts_list (list[Tensor]): Ground truth pts for each image\n                with shape (num_gts, fixed_num, 2) in [x,y] format.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        pts_preds_list = [pts_preds[i] for i in range(num_imgs)]\n\n        cls_reg_targets = self.map_get_targets(cls_scores_list, bbox_preds_list,pts_preds_list,\n                                           gt_bboxes_list, gt_labels_list,gt_shifts_pts_list,\n                                           gt_bboxes_ignore_list)\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         pts_targets_list, pts_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n \n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n        pts_targets = torch.cat(pts_targets_list, 0)\n        pts_weights = torch.cat(pts_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.map_cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.map_bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_map_cls(\n            cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # regression L1 loss\n        bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))\n        normalized_bbox_targets = normalize_2d_bbox(bbox_targets, self.pc_range)\n        # normalized_bbox_targets = bbox_targets\n        isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)\n        bbox_weights = bbox_weights * self.map_code_weights\n\n        loss_bbox = self.loss_map_bbox(\n            bbox_preds[isnotnan, :4],\n            normalized_bbox_targets[isnotnan,:4],\n            bbox_weights[isnotnan, :4],\n            avg_factor=num_total_pos)\n\n        # regression pts CD loss\n        # num_samples, num_order, num_pts, num_coords\n        normalized_pts_targets = normalize_2d_pts(pts_targets, self.pc_range)\n\n        # num_samples, num_pts, num_coords\n        pts_preds = pts_preds.reshape(-1, pts_preds.size(-2), pts_preds.size(-1))\n        if self.map_num_pts_per_vec != self.map_num_pts_per_gt_vec:\n            pts_preds = pts_preds.permute(0,2,1)\n            pts_preds = F.interpolate(pts_preds, size=(self.map_num_pts_per_gt_vec), mode='linear',\n                                    align_corners=True)\n            pts_preds = pts_preds.permute(0,2,1).contiguous()\n\n        loss_pts = self.loss_map_pts(\n            pts_preds[isnotnan,:,:],\n            normalized_pts_targets[isnotnan,:,:], \n            pts_weights[isnotnan,:,:],\n            avg_factor=num_total_pos)\n\n        dir_weights = pts_weights[:, :-self.map_dir_interval,0]\n        denormed_pts_preds = denormalize_2d_pts(pts_preds, self.pc_range)\n        denormed_pts_preds_dir = denormed_pts_preds[:,self.map_dir_interval:,:] - \\\n            denormed_pts_preds[:,:-self.map_dir_interval,:]\n        pts_targets_dir = pts_targets[:, self.map_dir_interval:,:] - pts_targets[:,:-self.map_dir_interval,:]\n\n        loss_dir = self.loss_map_dir(\n            denormed_pts_preds_dir[isnotnan,:,:],\n            pts_targets_dir[isnotnan,:,:],\n            dir_weights[isnotnan,:],\n            avg_factor=num_total_pos)\n\n        bboxes = denormalize_2d_bbox(bbox_preds, self.pc_range)\n        # regression IoU loss, defaultly GIoU loss\n        loss_iou = self.loss_map_iou(\n            bboxes[isnotnan, :4],\n            bbox_targets[isnotnan, :4],\n            bbox_weights[isnotnan, :4], \n            avg_factor=num_total_pos)\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_cls = torch.nan_to_num(loss_cls)\n            loss_bbox = torch.nan_to_num(loss_bbox)\n            loss_iou = torch.nan_to_num(loss_iou)\n            loss_pts = torch.nan_to_num(loss_pts)\n            loss_dir = torch.nan_to_num(loss_dir)\n\n        return loss_cls, loss_bbox, loss_iou, loss_pts, loss_dir\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             map_gt_bboxes_list,\n             map_gt_labels_list,\n             preds_dicts,\n             ego_fut_gt,\n             ego_fut_masks,\n             ego_fut_cmd,\n             gt_attr_labels,\n             gt_bboxes_ignore=None,\n             map_gt_bboxes_ignore=None,\n             img_metas=None):\n        \"\"\"\"Loss function.\n        Args:\n\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            preds_dicts:\n                all_cls_scores (Tensor): Classification score of all\n                    decoder layers, has shape\n                    [nb_dec, bs, num_query, cls_out_channels].\n                all_bbox_preds (Tensor): Sigmoid regression\n                    outputs of all decode layers. Each is a 4D-tensor with\n                    normalized coordinate format (cx, cy, w, h) and shape\n                    [nb_dec, bs, num_query, 4].\n                enc_cls_scores (Tensor): Classification scores of\n                    points on encode feature map , has shape\n                    (N, h*w, num_classes). Only be passed when as_two_stage is\n                    True, otherwise is None.\n                enc_bbox_preds (Tensor): Regression results of each points\n                    on the encode feature map, has shape (N, h*w, 4). Only be\n                    passed when as_two_stage is True, otherwise is None.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            f'{self.__class__.__name__} only supports ' \\\n            f'for gt_bboxes_ignore setting to None.'\n\n        map_gt_vecs_list = copy.deepcopy(map_gt_bboxes_list)\n\n        all_cls_scores = preds_dicts['all_cls_scores']\n        all_bbox_preds = preds_dicts['all_bbox_preds']\n        all_traj_preds = preds_dicts['all_traj_preds']\n        all_traj_cls_scores = preds_dicts['all_traj_cls_scores']\n        enc_cls_scores = preds_dicts['enc_cls_scores']\n        enc_bbox_preds = preds_dicts['enc_bbox_preds']\n        map_all_cls_scores = preds_dicts['map_all_cls_scores']\n        map_all_bbox_preds = preds_dicts['map_all_bbox_preds']\n        map_all_pts_preds = preds_dicts['map_all_pts_preds']\n        map_enc_cls_scores = preds_dicts['map_enc_cls_scores']\n        map_enc_bbox_preds = preds_dicts['map_enc_bbox_preds']\n        map_enc_pts_preds = preds_dicts['map_enc_pts_preds']\n        ego_fut_preds = preds_dicts['ego_fut_preds']\n        ego_fut_classification = preds_dicts['ego_fut_classification'] # 轨迹得分\n        \n        ego_fut_preds_refine = preds_dicts['ego_fut_preds_refine']\n        ego_fut_classification_refine = preds_dicts['ego_fut_classification_refine'] # 轨迹得分\n        #import pdb;pdb.set_trace()\n        num_dec_layers = len(all_cls_scores)\n        device = gt_labels_list[0].device\n\n        gt_bboxes_list = [torch.cat(\n            (gt_bboxes.gravity_center, gt_bboxes.tensor[:, 3:]),\n            dim=1).to(device) for gt_bboxes in gt_bboxes_list]\n\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_attr_labels_list = [gt_attr_labels for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        losses_cls, losses_bbox, loss_traj, loss_traj_cls = multi_apply(\n            self.loss_single, all_cls_scores, all_bbox_preds, all_traj_preds,\n            all_traj_cls_scores, all_gt_bboxes_list, all_gt_labels_list,\n            all_gt_attr_labels_list, all_gt_bboxes_ignore_list)\n        \n\n        num_dec_layers = len(map_all_cls_scores)\n        device = map_gt_labels_list[0].device\n\n        map_gt_bboxes_list = [\n            map_gt_bboxes.bbox.to(device) for map_gt_bboxes in map_gt_vecs_list]\n        map_gt_pts_list = [\n            map_gt_bboxes.fixed_num_sampled_points.to(device) for map_gt_bboxes in map_gt_vecs_list]\n        if self.map_gt_shift_pts_pattern == 'v0':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v1':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v1.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v2':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v2.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v3':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v3.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v4':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v4.to(device) for gt_bboxes in map_gt_vecs_list]\n        else:\n            raise NotImplementedError\n        map_all_gt_bboxes_list = [map_gt_bboxes_list for _ in range(num_dec_layers)]\n        map_all_gt_labels_list = [map_gt_labels_list for _ in range(num_dec_layers)]\n        map_all_gt_pts_list = [map_gt_pts_list for _ in range(num_dec_layers)]\n        map_all_gt_shifts_pts_list = [map_gt_shifts_pts_list for _ in range(num_dec_layers)]\n        map_all_gt_bboxes_ignore_list = [\n            map_gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        map_losses_cls, map_losses_bbox, map_losses_iou, \\\n            map_losses_pts, map_losses_dir = multi_apply(\n            self.map_loss_single, map_all_cls_scores, map_all_bbox_preds,\n            map_all_pts_preds, map_all_gt_bboxes_list, map_all_gt_labels_list,\n            map_all_gt_shifts_pts_list, map_all_gt_bboxes_ignore_list)\n\n        loss_dict = dict()\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls[-1]\n        loss_dict['loss_bbox'] = losses_bbox[-1]\n        loss_dict['loss_traj'] = loss_traj[-1]\n        loss_dict['loss_traj_cls'] = loss_traj_cls[-1]\n        # loss from the last decoder layer\n        loss_dict['loss_map_cls'] = map_losses_cls[-1]\n        loss_dict['loss_map_bbox'] = map_losses_bbox[-1]\n        loss_dict['loss_map_iou'] = map_losses_iou[-1]\n        loss_dict['loss_map_pts'] = map_losses_pts[-1]\n        loss_dict['loss_map_dir'] = map_losses_dir[-1]\n\n        # Planning Loss\n        ego_fut_gt = ego_fut_gt.squeeze(1)\n        ego_fut_masks = ego_fut_masks.squeeze(1).squeeze(1)\n        ego_fut_cmd = ego_fut_cmd.squeeze(1).squeeze(1)\n\n        batch, num_agent = all_traj_preds[-1].shape[:2]\n        agent_fut_preds = all_traj_preds[-1].view(batch, num_agent, self.fut_mode, self.fut_ts, 2)\n        agent_fut_cls_preds = all_traj_cls_scores[-1].view(batch, num_agent, self.fut_mode)\n        loss_plan_input = [ego_fut_preds, ego_fut_classification, ego_fut_gt, ego_fut_masks, ego_fut_cmd,\n                           map_all_pts_preds[-1], map_all_cls_scores[-1].sigmoid(),\n                           all_bbox_preds[-1][..., 0:2], agent_fut_preds,\n                           all_cls_scores[-1].sigmoid(), agent_fut_cls_preds.sigmoid()]\n\n        loss_planning_dict = self.loss_planning(*loss_plan_input)\n        loss_dict['loss_plan_reg'] = loss_planning_dict['loss_plan_reg']\n        loss_dict['loss_plan_cls'] = loss_planning_dict['loss_plan_cls']\n        loss_dict['loss_plan_bound'] = loss_planning_dict['loss_plan_bound']\n        loss_dict['loss_plan_col'] = loss_planning_dict['loss_plan_col']\n        loss_dict['loss_plan_dir'] = loss_planning_dict['loss_plan_dir']\n\n        \n        loss_plan_input_refine = [ego_fut_preds_refine, ego_fut_classification_refine, ego_fut_gt, ego_fut_masks, ego_fut_cmd,\n                           map_all_pts_preds[-1], map_all_cls_scores[-1].sigmoid(),\n                           all_bbox_preds[-1][..., 0:2], agent_fut_preds,\n                           all_cls_scores[-1].sigmoid(), agent_fut_cls_preds.sigmoid()]\n\n        loss_planning_dict_refine = self.loss_planning_refine(*loss_plan_input_refine)\n        loss_dict['loss_plan_reg_refine'] = loss_planning_dict_refine['loss_plan_reg_refine']\n        loss_dict['loss_plan_cls_refine'] = loss_planning_dict_refine['loss_plan_cls_refine']\n        loss_dict['loss_plan_bound_refine'] = loss_planning_dict_refine['loss_plan_bound_refine']\n        loss_dict['loss_plan_col_refine'] = loss_planning_dict_refine['loss_plan_col_refine']\n        loss_dict['loss_plan_dir_refine'] = loss_planning_dict_refine['loss_plan_dir_refine']\n        \n        \n        \n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_cls_i, loss_bbox_i in zip(losses_cls[:-1], losses_bbox[:-1]):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i\n            num_dec_layer += 1\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for map_loss_cls_i, map_loss_bbox_i, map_loss_iou_i, map_loss_pts_i, map_loss_dir_i in zip(\n            map_losses_cls[:-1],\n            map_losses_bbox[:-1],\n            map_losses_iou[:-1],\n            map_losses_pts[:-1],\n            map_losses_dir[:-1]\n        ):\n            loss_dict[f'd{num_dec_layer}.loss_map_cls'] = map_loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_map_bbox'] = map_loss_bbox_i\n            loss_dict[f'd{num_dec_layer}.loss_map_iou'] = map_loss_iou_i\n            loss_dict[f'd{num_dec_layer}.loss_map_pts'] = map_loss_pts_i\n            loss_dict[f'd{num_dec_layer}.loss_map_dir'] = map_loss_dir_i\n            num_dec_layer += 1\n\n        # loss of proposal generated from encode feature map.\n        if enc_cls_scores is not None:\n            binary_labels_list = [\n                torch.zeros_like(gt_labels_list[i])\n                for i in range(len(all_gt_labels_list))\n            ]\n            enc_loss_cls, enc_losses_bbox = \\\n                self.loss_single(enc_cls_scores, enc_bbox_preds,\n                                 gt_bboxes_list, binary_labels_list,\n                                 gt_bboxes_ignore)\n            loss_dict['enc_loss_cls'] = enc_loss_cls\n            loss_dict['enc_loss_bbox'] = enc_losses_bbox\n\n        if map_enc_cls_scores is not None:\n            map_binary_labels_list = [\n                torch.zeros_like(map_gt_labels_list[i])\n                for i in range(len(map_all_gt_labels_list))\n            ]\n            # TODO bug here, but we dont care enc_loss now\n            map_enc_loss_cls, map_enc_loss_bbox, map_enc_loss_iou, \\\n                 map_enc_loss_pts, map_enc_loss_dir = \\\n                self.map_loss_single(\n                    map_enc_cls_scores, map_enc_bbox_preds,\n                    map_enc_pts_preds, map_gt_bboxes_list,\n                    map_binary_labels_list, map_gt_pts_list,\n                    map_gt_bboxes_ignore\n                )\n            loss_dict['enc_loss_map_cls'] = map_enc_loss_cls\n            loss_dict['enc_loss_map_bbox'] = map_enc_loss_bbox\n            loss_dict['enc_loss_map_iou'] = map_enc_loss_iou\n            loss_dict['enc_loss_map_pts'] = map_enc_loss_pts\n            loss_dict['enc_loss_map_dir'] = map_enc_loss_dir\n\n        return loss_dict\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def get_bboxes(self, preds_dicts, img_metas, rescale=False):\n        \"\"\"Generate bboxes from bbox head predictions.\n        Args:\n            preds_dicts (tuple[list[dict]]): Prediction results.\n            img_metas (list[dict]): Point cloud and image's meta info.\n        Returns:\n            list[dict]: Decoded bbox, scores and labels after nms.\n        \"\"\"\n\n        det_preds_dicts = self.bbox_coder.decode(preds_dicts)\n        # map_bboxes: xmin, ymin, xmax, ymax\n        map_preds_dicts = self.map_bbox_coder.decode(preds_dicts)\n\n        num_samples = len(det_preds_dicts)\n        assert len(det_preds_dicts) == len(map_preds_dicts), \\\n             'len(preds_dict) should be equal to len(map_preds_dicts)'\n        ret_list = []\n        for i in range(num_samples):\n            preds = det_preds_dicts[i]\n            bboxes = preds['bboxes']\n            bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5\n            code_size = bboxes.shape[-1]\n            bboxes = img_metas[i]['box_type_3d'](bboxes, code_size)\n            scores = preds['scores']\n            labels = preds['labels']\n            trajs = preds['trajs']\n\n            map_preds = map_preds_dicts[i]\n            map_bboxes = map_preds['map_bboxes']\n            map_scores = map_preds['map_scores']\n            map_labels = map_preds['map_labels']\n            map_pts = map_preds['map_pts']\n\n            ret_list.append([bboxes, scores, labels, trajs, map_bboxes,\n                             map_scores, map_labels, map_pts])\n\n        return ret_list\n\n    def select_and_pad_pred_map(\n        self,\n        motion_pos,\n        map_query,\n        map_score,\n        map_pos,\n        map_thresh=0.5,\n        dis_thresh=None,\n        pe_normalization=True,\n        use_fix_pad=False\n    ):\n        \"\"\"select_and_pad_pred_map.\n        Args:\n            motion_pos: [B, A, 2]\n            map_query: [B, P, D].\n            map_score: [B, P, 3].\n            map_pos: [B, P, pts, 2].\n            map_thresh: map confidence threshold for filtering low-confidence preds\n            dis_thresh: distance threshold for masking far maps for each agent in cross-attn\n            use_fix_pad: always pad one lane instance for each batch\n        Returns:\n            selected_map_query: [B*A, P1(+1), D], P1 is the max inst num after filter and pad.\n            selected_map_pos: [B*A, P1(+1), 2]\n            selected_padding_mask: [B*A, P1(+1)]\n        \"\"\"\n        \n        if dis_thresh is None:\n            raise NotImplementedError('Not implement yet')\n\n        # use the most close pts pos in each map inst as the inst's pos\n        batch, num_map = map_pos.shape[:2]\n        map_dis = torch.sqrt(map_pos[..., 0]**2 + map_pos[..., 1]**2)\n        min_map_pos_idx = map_dis.argmin(dim=-1).flatten()  # [B*P]\n        min_map_pos = map_pos.flatten(0, 1)  # [B*P, pts, 2]\n        min_map_pos = min_map_pos[range(min_map_pos.shape[0]), min_map_pos_idx]  # [B*P, 2]\n        min_map_pos = min_map_pos.view(batch, num_map, 2)  # [B, P, 2]\n\n        # select & pad map vectors for different batch using map_thresh\n        map_score = map_score.sigmoid()\n        map_max_score = map_score.max(dim=-1)[0]\n        map_idx = map_max_score > map_thresh\n        batch_max_pnum = 0\n        for i in range(map_score.shape[0]):\n            pnum = map_idx[i].sum()\n            if pnum > batch_max_pnum:\n                batch_max_pnum = pnum\n\n        selected_map_query, selected_map_pos, selected_padding_mask = [], [], []\n        for i in range(map_score.shape[0]):\n            dim = map_query.shape[-1]\n            valid_pnum = map_idx[i].sum()\n            valid_map_query = map_query[i, map_idx[i]]\n            valid_map_pos = min_map_pos[i, map_idx[i]]\n            pad_pnum = batch_max_pnum - valid_pnum\n            padding_mask = torch.tensor([False], device=map_score.device).repeat(batch_max_pnum)\n            if pad_pnum != 0:\n                valid_map_query = torch.cat([valid_map_query, torch.zeros((pad_pnum, dim), device=map_score.device)], dim=0)\n                valid_map_pos = torch.cat([valid_map_pos, torch.zeros((pad_pnum, 2), device=map_score.device)], dim=0)\n                padding_mask[valid_pnum:] = True\n            selected_map_query.append(valid_map_query)\n            selected_map_pos.append(valid_map_pos)\n            selected_padding_mask.append(padding_mask)\n\n        selected_map_query = torch.stack(selected_map_query, dim=0)\n        selected_map_pos = torch.stack(selected_map_pos, dim=0)\n        selected_padding_mask = torch.stack(selected_padding_mask, dim=0)\n\n        # generate different pe for map vectors for each agent\n        num_agent = motion_pos.shape[1]\n        selected_map_query = selected_map_query.unsqueeze(1).repeat(1, num_agent, 1, 1)  # [B, A, max_P, D]\n        selected_map_pos = selected_map_pos.unsqueeze(1).repeat(1, num_agent, 1, 1)  # [B, A, max_P, 2]\n        selected_padding_mask = selected_padding_mask.unsqueeze(1).repeat(1, num_agent, 1)  # [B, A, max_P]\n        # move lane to per-car coords system\n        selected_map_dist = selected_map_pos - motion_pos[:, :, None, :]  # [B, A, max_P, 2]\n        if pe_normalization:\n            selected_map_pos = selected_map_pos - motion_pos[:, :, None, :]  # [B, A, max_P, 2]\n\n        # filter far map inst for each agent\n        map_dis = torch.sqrt(selected_map_dist[..., 0]**2 + selected_map_dist[..., 1]**2)\n        valid_map_inst = (map_dis <= dis_thresh)  # [B, A, max_P]\n        invalid_map_inst = (valid_map_inst == False)\n        selected_padding_mask = selected_padding_mask + invalid_map_inst\n\n        selected_map_query = selected_map_query.flatten(0, 1)\n        selected_map_pos = selected_map_pos.flatten(0, 1)\n        selected_padding_mask = selected_padding_mask.flatten(0, 1)\n\n        num_batch = selected_padding_mask.shape[0]\n        feat_dim = selected_map_query.shape[-1]\n        if use_fix_pad:\n            pad_map_query = torch.zeros((num_batch, 1, feat_dim), device=selected_map_query.device)\n            pad_map_pos = torch.ones((num_batch, 1, 2), device=selected_map_pos.device)\n            pad_lane_mask = torch.tensor([False], device=selected_padding_mask.device).unsqueeze(0).repeat(num_batch, 1)\n            selected_map_query = torch.cat([selected_map_query, pad_map_query], dim=1)\n            selected_map_pos = torch.cat([selected_map_pos, pad_map_pos], dim=1)\n            selected_padding_mask = torch.cat([selected_padding_mask, pad_lane_mask], dim=1)\n\n        return selected_map_query, selected_map_pos, selected_padding_mask\n\n\n    def select_and_pad_query(\n        self,\n        query,\n        query_pos,\n        query_score,\n        score_thresh=0.5,\n        use_fix_pad=True\n    ):\n        \"\"\"select_and_pad_query.\n        Args:\n            query: [B, Q, D].\n            query_pos: [B, Q, 2]\n            query_score: [B, Q, C].\n            score_thresh: confidence threshold for filtering low-confidence query\n            use_fix_pad: always pad one query instance for each batch\n        Returns:\n            selected_query: [B, Q', D]\n            selected_query_pos: [B, Q', 2]\n            selected_padding_mask: [B, Q']\n        \"\"\"\n\n        # select & pad query for different batch using score_thresh\n        query_score = query_score.sigmoid()\n        query_score = query_score.max(dim=-1)[0]\n        query_idx = query_score > score_thresh\n        batch_max_qnum = 0\n        for i in range(query_score.shape[0]):\n            qnum = query_idx[i].sum()\n            if qnum > batch_max_qnum:\n                batch_max_qnum = qnum\n\n        selected_query, selected_query_pos, selected_padding_mask = [], [], []\n        for i in range(query_score.shape[0]):\n            dim = query.shape[-1]\n            valid_qnum = query_idx[i].sum()\n            valid_query = query[i, query_idx[i]]\n            valid_query_pos = query_pos[i, query_idx[i]]\n            pad_qnum = batch_max_qnum - valid_qnum\n            padding_mask = torch.tensor([False], device=query_score.device).repeat(batch_max_qnum)\n            if pad_qnum != 0:\n                valid_query = torch.cat([valid_query, torch.zeros((pad_qnum, dim), device=query_score.device)], dim=0)\n                valid_query_pos = torch.cat([valid_query_pos, torch.zeros((pad_qnum, 2), device=query_score.device)], dim=0)\n                padding_mask[valid_qnum:] = True\n            selected_query.append(valid_query)\n            selected_query_pos.append(valid_query_pos)\n            selected_padding_mask.append(padding_mask)\n\n        selected_query = torch.stack(selected_query, dim=0)\n        selected_query_pos = torch.stack(selected_query_pos, dim=0)\n        selected_padding_mask = torch.stack(selected_padding_mask, dim=0)\n\n        num_batch = selected_padding_mask.shape[0]\n        feat_dim = selected_query.shape[-1]\n        if use_fix_pad:\n            pad_query = torch.zeros((num_batch, 1, feat_dim), device=selected_query.device)\n            pad_query_pos = torch.ones((num_batch, 1, 2), device=selected_query_pos.device)\n            pad_mask = torch.tensor([False], device=selected_padding_mask.device).unsqueeze(0).repeat(num_batch, 1)\n            selected_query = torch.cat([selected_query, pad_query], dim=1)\n            selected_query_pos = torch.cat([selected_query_pos, pad_query_pos], dim=1)\n            selected_padding_mask = torch.cat([selected_padding_mask, pad_mask], dim=1)\n\n        return selected_query, selected_query_pos, selected_padding_mask\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/VAD_head.py",
    "content": "import copy\nfrom math import pi, cos, sin\n\nimport torch\nimport numpy as np\nimport torch.nn as nn\nimport matplotlib.pyplot as plt\nimport torch.nn.functional as F\nfrom mmcv.models.builder import HEADS, build_loss \nfrom mmcv.models.dense_heads import DETRHead\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom mmcv.core.bbox.builder import build_assigner, build_sampler\nfrom mmcv.core.bbox.coder import build_bbox_coder\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.core.bbox.transforms import bbox_xyxy_to_cxcywh\nfrom mmcv.models.bricks import Linear\nfrom mmcv.models.utils import bias_init_with_prob, xavier_init\nfrom mmcv.core.utils import (multi_apply, multi_apply, reduce_mean)\nfrom mmcv.models.bricks.transformer import build_transformer_layer_sequence\n\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.models.vad_utils.traj_lr_warmup import get_traj_warmup_loss_weight\nfrom mmcv.models.vad_utils.map_utils import (\n    normalize_2d_pts, normalize_2d_bbox, denormalize_2d_pts, denormalize_2d_bbox\n)\n\nclass MLP(nn.Module):\n    def __init__(self, in_channels, hidden_unit, verbose=False):\n        super(MLP, self).__init__()\n        self.mlp = nn.Sequential(\n            nn.Linear(in_channels, hidden_unit),\n            nn.LayerNorm(hidden_unit),\n            nn.ReLU()\n        )\n\n    def forward(self, x):\n        x = self.mlp(x)\n        return x\n\nclass LaneNet(nn.Module):\n    def __init__(self, in_channels, hidden_unit, num_subgraph_layers):\n        super(LaneNet, self).__init__()\n        self.num_subgraph_layers = num_subgraph_layers\n        self.layer_seq = nn.Sequential()\n        for i in range(num_subgraph_layers):\n            self.layer_seq.add_module(\n                f'lmlp_{i}', MLP(in_channels, hidden_unit))\n            in_channels = hidden_unit*2\n\n    def forward(self, pts_lane_feats):\n        '''\n            Extract lane_feature from vectorized lane representation\n\n        Args:\n            pts_lane_feats: [batch size, max_pnum, pts, D]\n\n        Returns:\n            inst_lane_feats: [batch size, max_pnum, D]\n        '''\n        x = pts_lane_feats\n        for name, layer in self.layer_seq.named_modules():\n            if isinstance(layer, MLP):\n                # x [bs,max_lane_num,9,dim]\n                x = layer(x)\n                x_max = torch.max(x, -2)[0]\n                x_max = x_max.unsqueeze(2).repeat(1, 1, x.shape[2], 1)\n                x = torch.cat([x, x_max], dim=-1)\n        x_max = torch.max(x, -2)[0]\n        return x_max\n\n\n@HEADS.register_module()\nclass VADHead(DETRHead):\n    \"\"\"Head of VAD model.\n    Args:\n        with_box_refine (bool): Whether to refine the reference points\n            in the decoder. Defaults to False.\n        as_two_stage (bool) : Whether to generate the proposal from\n            the outputs of encoder.\n        transformer (obj:`ConfigDict`): ConfigDict is used for building\n            the Encoder and Decoder.\n        bev_h, bev_w (int): spatial shape of BEV queries.\n    \"\"\"\n    def __init__(self,\n                 *args,\n                 with_box_refine=False,\n                 as_two_stage=False,\n                 transformer=None,\n                 bbox_coder=None,\n                 num_cls_fcs=2,\n                 code_weights=None,\n                 bev_h=30,\n                 bev_w=30,\n                 fut_ts=6,\n                 fut_mode=6,\n                 loss_traj=dict(type='L1Loss', loss_weight=0.25),\n                 loss_traj_cls=dict(\n                     type='FocalLoss',\n                     use_sigmoid=True,\n                     gamma=2.0,\n                     alpha=0.25,\n                     loss_weight=0.8),\n                 map_bbox_coder=None,\n                 map_num_query=900,\n                 map_num_classes=3,\n                 map_num_vec=20,\n                 map_num_pts_per_vec=2,\n                 map_num_pts_per_gt_vec=2,\n                 map_query_embed_type='all_pts',\n                 map_transform_method='minmax',\n                 map_gt_shift_pts_pattern='v0',\n                 map_dir_interval=1,\n                 map_code_size=None,\n                 map_code_weights=None,\n                loss_map_cls=dict(\n                     type='CrossEntropyLoss',\n                     bg_cls_weight=0.1,\n                     use_sigmoid=False,\n                     loss_weight=1.0,\n                     class_weight=1.0),\n                 loss_map_bbox=dict(type='L1Loss', loss_weight=5.0),\n                 loss_map_iou=dict(type='GIoULoss', loss_weight=2.0),\n                 loss_map_pts=dict(\n                    type='ChamferDistance',loss_src_weight=1.0,loss_dst_weight=1.0\n                 ),\n                 loss_map_dir=dict(type='PtsDirCosLoss', loss_weight=2.0),\n                 tot_epoch=None,\n                 use_traj_lr_warmup=False,\n                 motion_decoder=None,\n                 motion_map_decoder=None,\n                 use_pe=False,\n                 motion_det_score=None,\n                 map_thresh=0.5,\n                 dis_thresh=0.2,\n                 pe_normalization=True,\n                 ego_his_encoder=None,\n                 ego_fut_mode=3,\n                 loss_plan_reg=dict(type='L1Loss', loss_weight=0.25),\n                 loss_plan_bound=dict(type='PlanMapBoundLoss', loss_weight=0.1),\n                 loss_plan_col=dict(type='PlanAgentDisLoss', loss_weight=0.1),\n                 loss_plan_dir=dict(type='PlanMapThetaLoss', loss_weight=0.1),\n                 ego_agent_decoder=None,\n                 ego_map_decoder=None,\n                 query_thresh=None,\n                 query_use_fix_pad=None,\n                 ego_lcf_feat_idx=None,\n                 valid_fut_ts=6,\n                 **kwargs):\n\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.fp16_enabled = False\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.tot_epoch = tot_epoch\n        self.use_traj_lr_warmup = use_traj_lr_warmup\n        self.motion_decoder = motion_decoder\n        self.motion_map_decoder = motion_map_decoder\n        self.use_pe = use_pe\n        self.motion_det_score = motion_det_score\n        self.map_thresh = map_thresh\n        self.dis_thresh = dis_thresh\n        self.pe_normalization = pe_normalization\n        self.ego_his_encoder = ego_his_encoder\n        self.ego_fut_mode = ego_fut_mode\n        self.ego_agent_decoder = ego_agent_decoder\n        self.ego_map_decoder = ego_map_decoder\n        self.query_thresh = query_thresh\n        self.query_use_fix_pad = query_use_fix_pad\n        self.ego_lcf_feat_idx = ego_lcf_feat_idx\n        self.valid_fut_ts = valid_fut_ts\n\n        if loss_traj_cls['use_sigmoid'] == True:\n            self.traj_num_cls = 1\n        else:\n          self.traj_num_cls = 2\n\n        self.with_box_refine = with_box_refine\n        self.as_two_stage = as_two_stage\n        if self.as_two_stage:\n            transformer['as_two_stage'] = self.as_two_stage\n        if 'code_size' in kwargs:\n            self.code_size = kwargs['code_size']\n        else:\n            self.code_size = 10\n        if code_weights is not None:\n            self.code_weights = code_weights\n        else:\n            self.code_weights = [1.0, 1.0, 1.0,\n                                 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]\n        if map_code_size is not None:\n            self.map_code_size = map_code_size\n        else:\n            self.map_code_size = 10\n        if map_code_weights is not None:\n            self.map_code_weights = map_code_weights\n        else:\n            self.map_code_weights = [1.0, 1.0, 1.0,\n                                 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]\n\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n        self.pc_range = self.bbox_coder.pc_range\n        self.real_w = self.pc_range[3] - self.pc_range[0]\n        self.real_h = self.pc_range[4] - self.pc_range[1]\n        self.num_cls_fcs = num_cls_fcs - 1\n\n        self.map_bbox_coder = build_bbox_coder(map_bbox_coder)\n        self.map_query_embed_type = map_query_embed_type\n        self.map_transform_method = map_transform_method\n        self.map_gt_shift_pts_pattern = map_gt_shift_pts_pattern\n        map_num_query = map_num_vec * map_num_pts_per_vec\n        self.map_num_query = map_num_query\n        self.map_num_classes = map_num_classes\n        self.map_num_vec = map_num_vec\n        self.map_num_pts_per_vec = map_num_pts_per_vec\n        self.map_num_pts_per_gt_vec = map_num_pts_per_gt_vec\n        self.map_dir_interval = map_dir_interval\n\n        if loss_map_cls['use_sigmoid'] == True:\n            self.map_cls_out_channels = map_num_classes\n        else:\n            self.map_cls_out_channels = map_num_classes + 1\n\n        self.map_bg_cls_weight = 0\n        map_class_weight = loss_map_cls.get('class_weight', None)\n        if map_class_weight is not None and (self.__class__ is VADHead):\n            assert isinstance(map_class_weight, float), 'Expected ' \\\n                'class_weight to have type float. Found ' \\\n                f'{type(map_class_weight)}.'\n            # NOTE following the official DETR rep0, bg_cls_weight means\n            # relative classification weight of the no-object class.\n            map_bg_cls_weight = loss_map_cls.get('bg_cls_weight', map_class_weight)\n            assert isinstance(map_bg_cls_weight, float), 'Expected ' \\\n                'bg_cls_weight to have type float. Found ' \\\n                f'{type(map_bg_cls_weight)}.'\n            map_class_weight = torch.ones(map_num_classes + 1) * map_class_weight\n            # set background class as the last indice\n            map_class_weight[map_num_classes] = map_bg_cls_weight\n            loss_map_cls.update({'class_weight': map_class_weight})\n            if 'bg_cls_weight' in loss_map_cls:\n                loss_map_cls.pop('bg_cls_weight')\n            self.map_bg_cls_weight = map_bg_cls_weight\n        \n        self.traj_bg_cls_weight = 0\n\n        super(VADHead, self).__init__(*args, transformer=transformer, **kwargs)\n        self.code_weights = nn.Parameter(torch.tensor(\n            self.code_weights, requires_grad=False), requires_grad=False)\n        self.map_code_weights = nn.Parameter(torch.tensor(\n            self.map_code_weights, requires_grad=False), requires_grad=False)\n        \n        if kwargs['train_cfg'] is not None:\n            assert 'map_assigner' in kwargs['train_cfg'], 'map assigner should be provided '\\\n                'when train_cfg is set.'\n            map_assigner = kwargs['train_cfg']['map_assigner']\n            assert loss_map_cls['loss_weight'] == map_assigner['cls_cost']['weight'], \\\n                'The classification weight for loss and matcher should be' \\\n                'exactly the same.'\n            assert loss_map_bbox['loss_weight'] == map_assigner['reg_cost'][\n                'weight'], 'The regression L1 weight for loss and matcher ' \\\n                'should be exactly the same.'\n            assert loss_map_iou['loss_weight'] == map_assigner['iou_cost']['weight'], \\\n                'The regression iou weight for loss and matcher should be' \\\n                'exactly the same.'\n            assert loss_map_pts['loss_weight'] == map_assigner['pts_cost']['weight'], \\\n                'The regression l1 weight for map pts loss and matcher should be' \\\n                'exactly the same.'\n\n            self.map_assigner = build_assigner(map_assigner)\n            # DETR sampling=False, so use PseudoSampler\n            sampler_cfg = dict(type='PseudoSampler')\n            self.map_sampler = build_sampler(sampler_cfg, context=self)\n        \n        self.loss_traj = build_loss(loss_traj)\n        self.loss_traj_cls = build_loss(loss_traj_cls)\n        self.loss_map_bbox = build_loss(loss_map_bbox)\n        self.loss_map_cls = build_loss(loss_map_cls)\n        self.loss_map_iou = build_loss(loss_map_iou)\n        self.loss_map_pts = build_loss(loss_map_pts)\n        self.loss_map_dir = build_loss(loss_map_dir)\n        self.loss_plan_reg = build_loss(loss_plan_reg)\n        self.loss_plan_bound = build_loss(loss_plan_bound)\n        self.loss_plan_col = build_loss(loss_plan_col)\n        self.loss_plan_dir = build_loss(loss_plan_dir)\n\n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            cls_branch.append(Linear(self.embed_dims, self.embed_dims))\n            cls_branch.append(nn.LayerNorm(self.embed_dims))\n            cls_branch.append(nn.ReLU(inplace=True))\n        cls_branch.append(Linear(self.embed_dims, self.cls_out_channels))\n        cls_branch = nn.Sequential(*cls_branch)\n\n        reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            reg_branch.append(nn.ReLU())\n        reg_branch.append(Linear(self.embed_dims, self.code_size))\n        reg_branch = nn.Sequential(*reg_branch)\n\n        traj_branch = []\n        for _ in range(self.num_reg_fcs):\n            traj_branch.append(Linear(self.embed_dims*2, self.embed_dims*2))\n            traj_branch.append(nn.ReLU())\n        traj_branch.append(Linear(self.embed_dims*2, self.fut_ts*2))\n        traj_branch = nn.Sequential(*traj_branch)\n\n        traj_cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            traj_cls_branch.append(Linear(self.embed_dims*2, self.embed_dims*2))\n            traj_cls_branch.append(nn.LayerNorm(self.embed_dims*2))\n            traj_cls_branch.append(nn.ReLU(inplace=True))\n        traj_cls_branch.append(Linear(self.embed_dims*2, self.traj_num_cls))\n        traj_cls_branch = nn.Sequential(*traj_cls_branch)\n\n        map_cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            map_cls_branch.append(Linear(self.embed_dims, self.embed_dims))\n            map_cls_branch.append(nn.LayerNorm(self.embed_dims))\n            map_cls_branch.append(nn.ReLU(inplace=True))\n        map_cls_branch.append(Linear(self.embed_dims, self.map_cls_out_channels))\n        map_cls_branch = nn.Sequential(*map_cls_branch)\n\n        map_reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            map_reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            map_reg_branch.append(nn.ReLU())\n        map_reg_branch.append(Linear(self.embed_dims, self.map_code_size))\n        map_reg_branch = nn.Sequential(*map_reg_branch)\n\n\n        def _get_clones(module, N):\n            return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n        # last reg_branch is used to generate proposal from\n        # encode feature map when as_two_stage is True.\n        num_decoder_layers = 1\n        num_map_decoder_layers = 1\n        if self.transformer.decoder is not None:\n            num_decoder_layers = self.transformer.decoder.num_layers\n        if self.transformer.map_decoder is not None:\n            num_map_decoder_layers = self.transformer.map_decoder.num_layers\n        num_motion_decoder_layers = 1\n        num_pred = (num_decoder_layers + 1) if \\\n            self.as_two_stage else num_decoder_layers\n        motion_num_pred = (num_motion_decoder_layers + 1) if \\\n            self.as_two_stage else num_motion_decoder_layers\n        map_num_pred = (num_map_decoder_layers + 1) if \\\n            self.as_two_stage else num_map_decoder_layers\n\n        if self.with_box_refine:\n            self.cls_branches = _get_clones(cls_branch, num_pred)\n            self.reg_branches = _get_clones(reg_branch, num_pred)\n            self.traj_branches = _get_clones(traj_branch, motion_num_pred)\n            self.traj_cls_branches = _get_clones(traj_cls_branch, motion_num_pred)\n            self.map_cls_branches = _get_clones(map_cls_branch, map_num_pred)\n            self.map_reg_branches = _get_clones(map_reg_branch, map_num_pred)\n        else:\n            self.cls_branches = nn.ModuleList(\n                [cls_branch for _ in range(num_pred)])\n            self.reg_branches = nn.ModuleList(\n                [reg_branch for _ in range(num_pred)])\n            self.traj_branches = nn.ModuleList(\n                [traj_branch for _ in range(motion_num_pred)])\n            self.traj_cls_branches = nn.ModuleList(\n                [traj_cls_branch for _ in range(motion_num_pred)])\n            self.map_cls_branches = nn.ModuleList(\n                [map_cls_branch for _ in range(map_num_pred)])\n            self.map_reg_branches = nn.ModuleList(\n                [map_reg_branch for _ in range(map_num_pred)])\n\n        if not self.as_two_stage:\n            self.bev_embedding = nn.Embedding(\n                self.bev_h * self.bev_w, self.embed_dims)\n            self.query_embedding = nn.Embedding(self.num_query,\n                                                self.embed_dims * 2)\n            if self.map_query_embed_type == 'all_pts':\n                self.map_query_embedding = nn.Embedding(self.map_num_query,\n                                                    self.embed_dims * 2)\n            elif self.map_query_embed_type == 'instance_pts':\n                self.map_query_embedding = None\n                self.map_instance_embedding = nn.Embedding(self.map_num_vec, self.embed_dims * 2)\n                self.map_pts_embedding = nn.Embedding(self.map_num_pts_per_vec, self.embed_dims * 2)\n        \n        if self.motion_decoder is not None:\n            self.motion_decoder = build_transformer_layer_sequence(self.motion_decoder)\n            self.motion_mode_query = nn.Embedding(self.fut_mode, self.embed_dims)\t\n            self.motion_mode_query.weight.requires_grad = True\n            if self.use_pe:\n                self.pos_mlp_sa = nn.Linear(2, self.embed_dims)\n        else:\n            raise NotImplementedError('Not implement yet')\n\n        if self.motion_map_decoder is not None:\n            self.lane_encoder = LaneNet(256, 128, 3)\n            self.motion_map_decoder = build_transformer_layer_sequence(self.motion_map_decoder)\n            if self.use_pe:\n                self.pos_mlp = nn.Linear(2, self.embed_dims)\n        \n        if self.ego_his_encoder is not None:\n            self.ego_his_encoder = LaneNet(2, self.embed_dims//2, 3)\n        else:\n            self.ego_query = nn.Embedding(1, self.embed_dims)\t\n\n        if self.ego_agent_decoder is not None:\n            self.ego_agent_decoder = build_transformer_layer_sequence(self.ego_agent_decoder)\n            if self.use_pe:\n                self.ego_agent_pos_mlp = nn.Linear(2, self.embed_dims)\n\n        if self.ego_map_decoder is not None:\n            self.ego_map_decoder = build_transformer_layer_sequence(self.ego_map_decoder)\n            if self.use_pe:\n                self.ego_map_pos_mlp = nn.Linear(2, self.embed_dims)\n\n        ego_fut_decoder = []\n        ego_fut_dec_in_dim = self.embed_dims*2 + len(self.ego_lcf_feat_idx) \\\n            if self.ego_lcf_feat_idx is not None else self.embed_dims*2\n        for _ in range(self.num_reg_fcs):\n            ego_fut_decoder.append(Linear(ego_fut_dec_in_dim, ego_fut_dec_in_dim))\n            ego_fut_decoder.append(nn.ReLU())\n        ego_fut_decoder.append(Linear(ego_fut_dec_in_dim, self.ego_fut_mode*self.fut_ts*2))\n        self.ego_fut_decoder = nn.Sequential(*ego_fut_decoder)\n\n        self.agent_fus_mlp = nn.Sequential(\n            nn.Linear(self.fut_mode*2*self.embed_dims, self.embed_dims, bias=True),\n            nn.LayerNorm(self.embed_dims),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims, self.embed_dims, bias=True))\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the DeformDETR head.\"\"\"\n        self.transformer.init_weights()\n        if self.loss_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n        if self.loss_map_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.map_cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n        if self.loss_traj_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.traj_cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n        # for m in self.map_reg_branches:\n        #     constant_init(m[-1], 0, bias=0)\n        # nn.init.constant_(self.map_reg_branches[0][-1].bias.data[2:], 0.)\n        if self.motion_decoder is not None:\n            for p in self.motion_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n            nn.init.orthogonal_(self.motion_mode_query.weight)\n            if self.use_pe:\n                xavier_init(self.pos_mlp_sa, distribution='uniform', bias=0.)\n        if self.motion_map_decoder is not None:\n            for p in self.motion_map_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n            for p in self.lane_encoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n            if self.use_pe:\n                xavier_init(self.pos_mlp, distribution='uniform', bias=0.)\n        if self.ego_his_encoder is not None:\n            for p in self.ego_his_encoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n        if self.ego_agent_decoder is not None:\n            for p in self.ego_agent_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n        if self.ego_map_decoder is not None:\n            for p in self.ego_map_decoder.parameters():\n                if p.dim() > 1:\n                    nn.init.xavier_uniform_(p)\n\n    # @auto_fp16(apply_to=('mlvl_feats'))\n    @force_fp32(apply_to=('mlvl_feats', 'prev_bev'))\n    def forward(self,\n                mlvl_feats,\n                img_metas,\n                prev_bev=None,\n                only_bev=False,\n                ego_his_trajs=None,\n                ego_lcf_feat=None,\n            ):\n        \"\"\"Forward function.\n        Args:\n            mlvl_feats (tuple[Tensor]): Features from the upstream\n                network, each is a 5D-tensor with shape\n                (B, N, C, H, W).\n            prev_bev: previous bev featues\n            only_bev: only compute BEV features with encoder. \n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, theta, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n        \"\"\"\n        #import pdb; pdb.set_trace()\n        bs, num_cam, _, _, _ = mlvl_feats[0].shape#1,6\n        dtype = mlvl_feats[0].dtype\n        object_query_embeds = self.query_embedding.weight.to(dtype) #torch.Size([300, 512])\n        \n        if self.map_query_embed_type == 'all_pts':\n            map_query_embeds = self.map_query_embedding.weight.to(dtype)\n        elif self.map_query_embed_type == 'instance_pts':\n            map_pts_embeds = self.map_pts_embedding.weight.unsqueeze(0)#torch.Size([1, 20, 512])\n            map_instance_embeds = self.map_instance_embedding.weight.unsqueeze(1)#torch.Size([100, 1, 512])\n            map_query_embeds = (map_pts_embeds + map_instance_embeds).flatten(0, 1).to(dtype) #torch.Size([2000, 512])\n\n        bev_queries = self.bev_embedding.weight.to(dtype)#torch.Size([40000, 256])\n\n        bev_mask = torch.zeros((bs, self.bev_h, self.bev_w),\n                               device=bev_queries.device).to(dtype)\n        bev_pos = self.positional_encoding(bev_mask).to(dtype)\n            \n        if only_bev:  # only use encoder to obtain BEV features, TODO: refine the workaround\n            return self.transformer.get_bev_features(\n                mlvl_feats,\n                bev_queries,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                img_metas=img_metas,\n                prev_bev=prev_bev,\n            )\n        else:\n            outputs = self.transformer(\n                mlvl_feats,\n                bev_queries,\n                object_query_embeds,\n                map_query_embeds,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                reg_branches=self.reg_branches if self.with_box_refine else None,  # noqa:E501\n                cls_branches=self.cls_branches if self.as_two_stage else None,\n                map_reg_branches=self.map_reg_branches if self.with_box_refine else None,  # noqa:E501\n                map_cls_branches=self.map_cls_branches if self.as_two_stage else None,\n                img_metas=img_metas,\n                prev_bev=prev_bev\n        )\n\n        bev_embed, hs, init_reference, inter_references, \\\n            map_hs, map_init_reference, map_inter_references = outputs\n\n        hs = hs.permute(0, 2, 1, 3)\n        outputs_classes = []\n        outputs_coords = []\n        outputs_coords_bev = []\n        outputs_trajs = []\n        outputs_trajs_classes = []\n\n        map_hs = map_hs.permute(0, 2, 1, 3)\n        map_outputs_classes = []\n        map_outputs_coords = []\n        map_outputs_pts_coords = []\n        map_outputs_coords_bev = []\n\n        for lvl in range(hs.shape[0]):\n            if lvl == 0:\n                reference = init_reference\n            else:\n                reference = inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            outputs_class = self.cls_branches[lvl](hs[lvl])\n            tmp = self.reg_branches[lvl](hs[lvl])\n\n            # TODO: check the shape of reference\n            assert reference.shape[-1] == 3\n            tmp[..., 0:2] = tmp[..., 0:2] + reference[..., 0:2]\n            tmp[..., 0:2] = tmp[..., 0:2].sigmoid()\n            outputs_coords_bev.append(tmp[..., 0:2].clone().detach())\n            tmp[..., 4:5] = tmp[..., 4:5] + reference[..., 2:3]\n            tmp[..., 4:5] = tmp[..., 4:5].sigmoid()\n            tmp[..., 0:1] = (tmp[..., 0:1] * (self.pc_range[3] -\n                             self.pc_range[0]) + self.pc_range[0])\n            tmp[..., 1:2] = (tmp[..., 1:2] * (self.pc_range[4] -\n                             self.pc_range[1]) + self.pc_range[1])\n            tmp[..., 4:5] = (tmp[..., 4:5] * (self.pc_range[5] -\n                             self.pc_range[2]) + self.pc_range[2])\n\n            # TODO: check if using sigmoid\n            outputs_coord = tmp\n            outputs_classes.append(outputs_class)\n            outputs_coords.append(outputs_coord)\n        \n        for lvl in range(map_hs.shape[0]):\n            if lvl == 0:\n                reference = map_init_reference\n            else:\n                reference = map_inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            map_outputs_class = self.map_cls_branches[lvl](\n                map_hs[lvl].view(bs,self.map_num_vec, self.map_num_pts_per_vec,-1).mean(2)\n            )\n            tmp = self.map_reg_branches[lvl](map_hs[lvl])\n            # TODO: check the shape of reference\n            assert reference.shape[-1] == 2\n            tmp[..., 0:2] += reference[..., 0:2]\n            tmp = tmp.sigmoid() # cx,cy,w,h\n            map_outputs_coord, map_outputs_pts_coord = self.map_transform_box(tmp)\n            map_outputs_coords_bev.append(map_outputs_pts_coord.clone().detach())\n            map_outputs_classes.append(map_outputs_class)\n            map_outputs_coords.append(map_outputs_coord)\n            map_outputs_pts_coords.append(map_outputs_pts_coord)\n        #import pdb;pdb.set_trace() \n        if self.motion_decoder is not None:\n            batch_size, num_agent = outputs_coords_bev[-1].shape[:2] # num_agent = 300\n            # motion_query\n            motion_query = hs[-1].permute(1, 0, 2)  # [A, B, D] # 300,1,256\n            mode_query = self.motion_mode_query.weight  # [fut_mode, D] [6,256]\n            # [M, B, D], M=A*fut_mode\n            motion_query = (motion_query[:, None, :, :] + mode_query[None, :, None, :]).flatten(0, 1)\n            if self.use_pe:\n                motion_coords = outputs_coords_bev[-1]  # [B, A, 2]\n                motion_pos = self.pos_mlp_sa(motion_coords)  # [B, A, D]\n                motion_pos = motion_pos.unsqueeze(2).repeat(1, 1, self.fut_mode, 1).flatten(1, 2)\n                motion_pos = motion_pos.permute(1, 0, 2)  # [M, B, D]\n            else:\n                motion_pos = None\n\n            if self.motion_det_score is not None:\n                motion_score = outputs_classes[-1]\n                max_motion_score = motion_score.max(dim=-1)[0]\n                invalid_motion_idx = max_motion_score < self.motion_det_score  # [B, A]\n                invalid_motion_idx = invalid_motion_idx.unsqueeze(2).repeat(1, 1, self.fut_mode).flatten(1, 2)\n            else:\n                invalid_motion_idx = None\n\n            motion_hs = self.motion_decoder(\n                query=motion_query,\n                key=motion_query,\n                value=motion_query,\n                query_pos=motion_pos,\n                key_pos=motion_pos,\n                key_padding_mask=invalid_motion_idx) # [1800,1,256]\n\n            if self.motion_map_decoder is not None:\n                # map preprocess\n                motion_coords = outputs_coords_bev[-1]  # [B, A, 2]\n                motion_coords = motion_coords.unsqueeze(2).repeat(1, 1, self.fut_mode, 1).flatten(1, 2)\n                map_query = map_hs[-1].view(batch_size, self.map_num_vec, self.map_num_pts_per_vec, -1)\n                map_query = self.lane_encoder(map_query)  # [B, P, pts, D] -> [B, P, D]\n                map_score = map_outputs_classes[-1]\n                map_pos = map_outputs_coords_bev[-1]\n                map_query, map_pos, key_padding_mask = self.select_and_pad_pred_map(\n                    motion_coords, map_query, map_score, map_pos,\n                    map_thresh=self.map_thresh, dis_thresh=self.dis_thresh,\n                    pe_normalization=self.pe_normalization, use_fix_pad=True)\n                map_query = map_query.permute(1, 0, 2)  # [P, B*M, D]\n                ca_motion_query = motion_hs.permute(1, 0, 2).flatten(0, 1).unsqueeze(0)\n\n                # position encoding\n                if self.use_pe:\n                    (num_query, batch) = ca_motion_query.shape[:2] \n                    motion_pos = torch.zeros((num_query, batch, 2), device=motion_hs.device)\n                    motion_pos = self.pos_mlp(motion_pos)\n                    map_pos = map_pos.permute(1, 0, 2)\n                    map_pos = self.pos_mlp(map_pos)\n                else:\n                    motion_pos, map_pos = None, None\n                \n                ca_motion_query = self.motion_map_decoder(\n                    query=ca_motion_query,\n                    key=map_query,\n                    value=map_query,\n                    query_pos=motion_pos,\n                    key_pos=map_pos,\n                    key_padding_mask=key_padding_mask)\n            else:\n                ca_motion_query = motion_hs.permute(1, 0, 2).flatten(0, 1).unsqueeze(0)\n\n            batch_size = outputs_coords_bev[-1].shape[0]\n            motion_hs = motion_hs.permute(1, 0, 2).unflatten(\n                dim=1, sizes=(num_agent, self.fut_mode)\n            )\n            ca_motion_query = ca_motion_query.squeeze(0).unflatten(\n                dim=0, sizes=(batch_size, num_agent, self.fut_mode)\n            )\n            motion_hs = torch.cat([motion_hs, ca_motion_query], dim=-1)  # [B, A, fut_mode, 2D]\n        else:\n            raise NotImplementedError('Not implement yet')\n\n        outputs_traj = self.traj_branches[0](motion_hs)\n        outputs_trajs.append(outputs_traj)\n        outputs_traj_class = self.traj_cls_branches[0](motion_hs)\n        outputs_trajs_classes.append(outputs_traj_class.squeeze(-1))\n        (batch, num_agent) = motion_hs.shape[:2]\n             \n        map_outputs_classes = torch.stack(map_outputs_classes)\n        map_outputs_coords = torch.stack(map_outputs_coords)\n        map_outputs_pts_coords = torch.stack(map_outputs_pts_coords)\n\n        outputs_classes = torch.stack(outputs_classes)\n        outputs_coords = torch.stack(outputs_coords)\n        outputs_trajs = torch.stack(outputs_trajs)\n        outputs_trajs_classes = torch.stack(outputs_trajs_classes)\n\n        # planning\n        #import pdb;pdb.set_trace()\n        (batch, num_agent) = motion_hs.shape[:2]\n        if self.ego_his_encoder is not None:\n            ego_his_feats = self.ego_his_encoder(ego_his_trajs)  # [B, 1, dim]\n        else:\n            ego_his_feats = self.ego_query.weight.unsqueeze(0).repeat(batch, 1, 1)\n        # Interaction\n        ego_query = ego_his_feats\n        ego_pos = torch.zeros((batch, 1, 2), device=ego_query.device)\n        ego_pos_emb = self.ego_agent_pos_mlp(ego_pos)\n        agent_conf = outputs_classes[-1]\n        agent_query = motion_hs.reshape(batch, num_agent, -1)\n        agent_query = self.agent_fus_mlp(agent_query) # [B, A, fut_mode, 2*D] -> [B, A, D]\n        agent_pos = outputs_coords_bev[-1]\n        agent_query, agent_pos, agent_mask = self.select_and_pad_query(\n            agent_query, agent_pos, agent_conf,\n            score_thresh=self.query_thresh, use_fix_pad=self.query_use_fix_pad\n        )\n        agent_pos_emb = self.ego_agent_pos_mlp(agent_pos)\n        # ego <-> agent interaction\n        ego_agent_query = self.ego_agent_decoder(\n            query=ego_query.permute(1, 0, 2),\n            key=agent_query.permute(1, 0, 2),\n            value=agent_query.permute(1, 0, 2),\n            query_pos=ego_pos_emb.permute(1, 0, 2),\n            key_pos=agent_pos_emb.permute(1, 0, 2),\n            key_padding_mask=agent_mask)\n\n        # ego <-> map interaction\n        ego_pos = torch.zeros((batch, 1, 2), device=agent_query.device)\n        ego_pos_emb = self.ego_map_pos_mlp(ego_pos)\n        map_query = map_hs[-1].view(batch_size, self.map_num_vec, self.map_num_pts_per_vec, -1)\n        map_query = self.lane_encoder(map_query)  # [B, P, pts, D] -> [B, P, D]\n        map_conf = map_outputs_classes[-1]\n        map_pos = map_outputs_coords_bev[-1]\n        # use the most close pts pos in each map inst as the inst's pos\n        batch, num_map = map_pos.shape[:2]\n        map_dis = torch.sqrt(map_pos[..., 0]**2 + map_pos[..., 1]**2)\n        min_map_pos_idx = map_dis.argmin(dim=-1).flatten()  # [B*P]\n        min_map_pos = map_pos.flatten(0, 1)  # [B*P, pts, 2]\n        min_map_pos = min_map_pos[range(min_map_pos.shape[0]), min_map_pos_idx]  # [B*P, 2]\n        min_map_pos = min_map_pos.view(batch, num_map, 2)  # [B, P, 2]\n        map_query, map_pos, map_mask = self.select_and_pad_query(\n            map_query, min_map_pos, map_conf,\n            score_thresh=self.query_thresh, use_fix_pad=self.query_use_fix_pad\n        )\n        map_pos_emb = self.ego_map_pos_mlp(map_pos)\n        ego_map_query = self.ego_map_decoder(\n            query=ego_agent_query,\n            key=map_query.permute(1, 0, 2),\n            value=map_query.permute(1, 0, 2),\n            query_pos=ego_pos_emb.permute(1, 0, 2),\n            key_pos=map_pos_emb.permute(1, 0, 2),\n            key_padding_mask=map_mask)\n\n        if self.ego_his_encoder is not None and self.ego_lcf_feat_idx is not None:\n            ego_feats = torch.cat(\n                [ego_his_feats,\n                 ego_map_query.permute(1, 0, 2),\n                 ego_lcf_feat.squeeze(1)[..., self.ego_lcf_feat_idx]],\n                dim=-1\n            )  # [B, 1, 2D+2]\n        elif self.ego_his_encoder is not None and self.ego_lcf_feat_idx is None:\n            ego_feats = torch.cat(\n                [ego_his_feats,\n                 ego_map_query.permute(1, 0, 2)],\n                dim=-1\n            )  # [B, 1, 2D]\n        elif self.ego_his_encoder is None and self.ego_lcf_feat_idx is not None:                \n            ego_feats = torch.cat(\n                [ego_agent_query.permute(1, 0, 2),\n                 ego_map_query.permute(1, 0, 2),\n                 ego_lcf_feat.squeeze(1)[..., self.ego_lcf_feat_idx]],\n                dim=-1\n            )  # [B, 1, 2D+2]\n        elif self.ego_his_encoder is None and self.ego_lcf_feat_idx is None:                \n            ego_feats = torch.cat(\n                [ego_agent_query.permute(1, 0, 2),\n                 ego_map_query.permute(1, 0, 2)],\n                dim=-1\n            )  # [B, 1, 2D]  \n\n        # Ego prediction\n        outputs_ego_trajs = self.ego_fut_decoder(ego_feats)\n        outputs_ego_trajs = outputs_ego_trajs.reshape(outputs_ego_trajs.shape[0], \n                                                      self.ego_fut_mode, self.fut_ts, 2)\n        #import pdb;pdb.set_trace()\n        outs = {\n            'bev_embed': bev_embed,\n            'all_cls_scores': outputs_classes,\n            'all_bbox_preds': outputs_coords,\n            'all_traj_preds': outputs_trajs.repeat(outputs_coords.shape[0], 1, 1, 1, 1),\n            'all_traj_cls_scores': outputs_trajs_classes.repeat(outputs_coords.shape[0], 1, 1, 1),\n            'map_all_cls_scores': map_outputs_classes,\n            'map_all_bbox_preds': map_outputs_coords,\n            'map_all_pts_preds': map_outputs_pts_coords,\n            'enc_cls_scores': None,\n            'enc_bbox_preds': None,\n            'map_enc_cls_scores': None,\n            'map_enc_bbox_preds': None,\n            'map_enc_pts_preds': None,\n            'ego_fut_preds': outputs_ego_trajs,\n        }\n\n        return outs\n\n    def map_transform_box(self, pts, y_first=False):\n        \"\"\"\n        Converting the points set into bounding box.\n\n        Args:\n            pts: the input points sets (fields), each points\n                set (fields) is represented as 2n scalar.\n            y_first: if y_fisrt=True, the point set is represented as\n                [y1, x1, y2, x2 ... yn, xn], otherwise the point set is\n                represented as [x1, y1, x2, y2 ... xn, yn].\n        Returns:\n            The bbox [cx, cy, w, h] transformed from points.\n        \"\"\"\n        pts_reshape = pts.view(pts.shape[0], self.map_num_vec,\n                                self.map_num_pts_per_vec,2)\n        pts_y = pts_reshape[:, :, :, 0] if y_first else pts_reshape[:, :, :, 1]\n        pts_x = pts_reshape[:, :, :, 1] if y_first else pts_reshape[:, :, :, 0]\n        if self.map_transform_method == 'minmax':\n            # import pdb;pdb.set_trace()\n\n            xmin = pts_x.min(dim=2, keepdim=True)[0]\n            xmax = pts_x.max(dim=2, keepdim=True)[0]\n            ymin = pts_y.min(dim=2, keepdim=True)[0]\n            ymax = pts_y.max(dim=2, keepdim=True)[0]\n            bbox = torch.cat([xmin, ymin, xmax, ymax], dim=2)\n            bbox = bbox_xyxy_to_cxcywh(bbox)\n        else:\n            raise NotImplementedError\n        return bbox, pts_reshape\n\n    def _get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           gt_labels,\n                           gt_bboxes,\n                           gt_attr_labels,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 10].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 9) in [x,y,z,w,l,h,yaw,vx,vy] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        gt_fut_trajs = gt_attr_labels[:, :self.fut_ts*2]\n        gt_fut_masks = gt_attr_labels[:, self.fut_ts*2:self.fut_ts*3]\n        gt_bbox_c = gt_bboxes.shape[-1]\n        num_gt_bbox, gt_traj_c = gt_fut_trajs.shape\n\n        assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,\n                                             gt_labels, gt_bboxes_ignore)\n\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes,),\n                                    self.num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)[..., :gt_bbox_c]\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n\n        # trajs targets\n        traj_targets = torch.zeros((num_bboxes, gt_traj_c), dtype=torch.float32, device=bbox_pred.device)\n        traj_weights = torch.zeros_like(traj_targets)\n        traj_targets[pos_inds] = gt_fut_trajs[sampling_result.pos_assigned_gt_inds]\n        traj_weights[pos_inds] = 1.0\n\n        # Filter out invalid fut trajs\n        traj_masks = torch.zeros_like(traj_targets)  # [num_bboxes, fut_ts*2]\n        gt_fut_masks = gt_fut_masks.unsqueeze(-1).repeat(1, 1, 2).view(num_gt_bbox, -1)  # [num_gt_bbox, fut_ts*2]\n        traj_masks[pos_inds] = gt_fut_masks[sampling_result.pos_assigned_gt_inds]\n        traj_weights = traj_weights * traj_masks\n\n        # Extra future timestamp mask for controlling pred horizon\n        fut_ts_mask = torch.zeros((num_bboxes, self.fut_ts, 2),\n                                   dtype=torch.float32, device=bbox_pred.device)\n        fut_ts_mask[:, :self.valid_fut_ts, :] = 1.0\n        fut_ts_mask = fut_ts_mask.view(num_bboxes, -1)\n        traj_weights = traj_weights * fut_ts_mask\n\n        # DETR\n        bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes\n\n        return (\n            labels, label_weights, bbox_targets, bbox_weights, traj_targets,\n            traj_weights, traj_masks.view(-1, self.fut_ts, 2)[..., 0],\n            pos_inds, neg_inds\n        )\n\n    def _map_get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           pts_pred,\n                           gt_labels,\n                           gt_bboxes,\n                           gt_shifts_pts,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        gt_c = gt_bboxes.shape[-1]\n        assign_result, order_index = self.map_assigner.assign(bbox_pred, cls_score, pts_pred,\n                                             gt_bboxes, gt_labels, gt_shifts_pts,\n                                             gt_bboxes_ignore)\n\n        sampling_result = self.map_sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes,),\n                                    self.map_num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)[..., :gt_c]\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n        # pts targets\n        if order_index is None:\n            assigned_shift = gt_labels[sampling_result.pos_assigned_gt_inds]\n        else:\n            assigned_shift = order_index[sampling_result.pos_inds, sampling_result.pos_assigned_gt_inds]\n        pts_targets = pts_pred.new_zeros((pts_pred.size(0),\n                        pts_pred.size(1), pts_pred.size(2)))\n        pts_weights = torch.zeros_like(pts_targets)\n        pts_weights[pos_inds] = 1.0\n        # DETR\n        bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes\n        pts_targets[pos_inds] = gt_shifts_pts[sampling_result.pos_assigned_gt_inds,assigned_shift,:,:]\n        return (labels, label_weights, bbox_targets, bbox_weights,\n                pts_targets, pts_weights,\n                pos_inds, neg_inds)\n\n    def get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_attr_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            tuple: a tuple containing the following targets.\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, traj_targets_list, traj_weights_list,\n         gt_fut_masks_list, pos_inds_list, neg_inds_list) = multi_apply(\n            self._get_target_single, cls_scores_list, bbox_preds_list,\n            gt_labels_list, gt_bboxes_list, gt_attr_labels_list, gt_bboxes_ignore_list\n         )\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n                traj_targets_list, traj_weights_list, gt_fut_masks_list, num_total_pos, num_total_neg)\n\n    def map_get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    pts_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_shifts_pts_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            tuple: a tuple containing the following targets.\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, pts_targets_list, pts_weights_list,\n         pos_inds_list, neg_inds_list) = multi_apply(\n            self._map_get_target_single, cls_scores_list, bbox_preds_list,pts_preds_list,\n            gt_labels_list, gt_bboxes_list, gt_shifts_pts_list, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, pts_targets_list, pts_weights_list,\n                num_total_pos, num_total_neg)\n\n    def loss_planning(self,\n                      ego_fut_preds,\n                      ego_fut_gt,\n                      ego_fut_masks,\n                      ego_fut_cmd,\n                      lane_preds,\n                      lane_score_preds,\n                      agent_preds,\n                      agent_fut_preds,\n                      agent_score_preds,\n                      agent_fut_cls_preds):\n        \"\"\"\"Loss function for ego vehicle planning.\n        Args:\n            ego_fut_preds (Tensor): [B, ego_fut_mode, fut_ts, 2]\n            ego_fut_gt (Tensor): [B, fut_ts, 2]\n            ego_fut_masks (Tensor): [B, fut_ts]\n            ego_fut_cmd (Tensor): [B, ego_fut_mode]\n            lane_preds (Tensor): [B, num_vec, num_pts, 2]\n            lane_score_preds (Tensor): [B, num_vec, 3]\n            agent_preds (Tensor): [B, num_agent, 2]\n            agent_fut_preds (Tensor): [B, num_agent, fut_mode, fut_ts, 2]\n            agent_score_preds (Tensor): [B, num_agent, 10]\n            agent_fut_cls_scores (Tensor): [B, num_agent, fut_mode]\n        Returns:\n            loss_plan_reg (Tensor): planning reg loss.\n            loss_plan_bound (Tensor): planning map boundary constraint loss.\n            loss_plan_col (Tensor): planning col constraint loss.\n            loss_plan_dir (Tensor): planning directional constraint loss.\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        ego_fut_gt = ego_fut_gt.unsqueeze(1).repeat(1, self.ego_fut_mode, 1, 1)\n        #import pdb;pdb.set_trace() # [1, 6] => [1, 6, 1, 1]  [1, 6] => [1, 1, 6, 1]\n        loss_plan_l1_weight = ego_fut_cmd[..., None, None] * ego_fut_masks[:, None, :, None]\n        # [1,6,6,1]\n        loss_plan_l1_weight = loss_plan_l1_weight.repeat(1, 1, 1, 2)\n        # [1, 6, 6, 2]\n        #import pdb;pdb.set_trace() # [1,6,6,2] ,[1,6,6,2], # [1, 6, 6, 2]\n        loss_plan_l1 = self.loss_plan_reg(\n            ego_fut_preds,\n            ego_fut_gt,\n            loss_plan_l1_weight\n        )\n\n        loss_plan_bound = self.loss_plan_bound(\n            ego_fut_preds[ego_fut_cmd==1],\n            lane_preds,\n            lane_score_preds,\n            weight=ego_fut_masks\n        )\n\n        loss_plan_col = self.loss_plan_col(\n            ego_fut_preds[ego_fut_cmd==1],\n            agent_preds,\n            agent_fut_preds,\n            agent_score_preds,\n            agent_fut_cls_preds,\n            weight=ego_fut_masks[:, :, None].repeat(1, 1, 2)\n        )\n\n        loss_plan_dir = self.loss_plan_dir(\n            ego_fut_preds[ego_fut_cmd==1],\n            lane_preds,\n            lane_score_preds,\n            weight=ego_fut_masks\n        )\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_plan_l1 = torch.nan_to_num(loss_plan_l1)\n            loss_plan_bound = torch.nan_to_num(loss_plan_bound)\n            loss_plan_col = torch.nan_to_num(loss_plan_col)\n            loss_plan_dir = torch.nan_to_num(loss_plan_dir)\n        \n        loss_plan_dict = dict()\n        loss_plan_dict['loss_plan_reg'] = loss_plan_l1\n        loss_plan_dict['loss_plan_bound'] = loss_plan_bound\n        loss_plan_dict['loss_plan_col'] = loss_plan_col\n        loss_plan_dict['loss_plan_dir'] = loss_plan_dir\n\n        return loss_plan_dict\n    \n    def loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    traj_preds,\n                    traj_cls_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_attr_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,\n                                           gt_bboxes_list, gt_labels_list,\n                                           gt_attr_labels_list, gt_bboxes_ignore_list)\n\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         traj_targets_list, traj_weights_list, gt_fut_masks_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n        traj_targets = torch.cat(traj_targets_list, 0)\n        traj_weights = torch.cat(traj_weights_list, 0)\n        gt_fut_masks = torch.cat(gt_fut_masks_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_cls(cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # regression L1 loss\n        bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))\n        normalized_bbox_targets = normalize_bbox(bbox_targets, self.pc_range)\n        isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)\n        bbox_weights = bbox_weights * self.code_weights\n        loss_bbox = self.loss_bbox(\n            bbox_preds[isnotnan, :10],\n            normalized_bbox_targets[isnotnan, :10],\n            bbox_weights[isnotnan, :10],\n            avg_factor=num_total_pos)\n\n        # traj regression loss\n        best_traj_preds = self.get_best_fut_preds(\n            traj_preds.reshape(-1, self.fut_mode, self.fut_ts, 2),\n            traj_targets.reshape(-1, self.fut_ts, 2), gt_fut_masks)\n\n        neg_inds = (bbox_weights[:, 0] == 0)\n        traj_labels = self.get_traj_cls_target(\n            traj_preds.reshape(-1, self.fut_mode, self.fut_ts, 2),\n            traj_targets.reshape(-1, self.fut_ts, 2),\n            gt_fut_masks, neg_inds)\n\n        loss_traj = self.loss_traj(\n            best_traj_preds[isnotnan],\n            traj_targets[isnotnan],\n            traj_weights[isnotnan],\n            avg_factor=num_total_pos)\n\n        if self.use_traj_lr_warmup:\n            loss_scale_factor = get_traj_warmup_loss_weight(self.epoch, self.tot_epoch)\n            loss_traj = loss_scale_factor * loss_traj\n\n        # traj classification loss\n        traj_cls_scores = traj_cls_preds.reshape(-1, self.fut_mode)\n        # construct weighted avg_factor to match with the official DETR repo\n        traj_cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.traj_bg_cls_weight\n        if self.sync_cls_avg_factor:\n            traj_cls_avg_factor = reduce_mean(\n                traj_cls_scores.new_tensor([traj_cls_avg_factor]))\n\n        traj_cls_avg_factor = max(traj_cls_avg_factor, 1)\n        loss_traj_cls = self.loss_traj_cls(\n            traj_cls_scores, traj_labels, label_weights, avg_factor=traj_cls_avg_factor\n        )\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_cls = torch.nan_to_num(loss_cls)\n            loss_bbox = torch.nan_to_num(loss_bbox)\n            loss_traj = torch.nan_to_num(loss_traj)\n            loss_traj_cls = torch.nan_to_num(loss_traj_cls)\n\n        return loss_cls, loss_bbox, loss_traj, loss_traj_cls\n\n    def get_best_fut_preds(self,\n             traj_preds,\n             traj_targets,\n             gt_fut_masks):\n        \"\"\"\"Choose best preds among all modes.\n        Args:\n            traj_preds (Tensor): MultiModal traj preds with shape (num_box_preds, fut_mode, fut_ts, 2).\n            traj_targets (Tensor): Ground truth traj for each pred box with shape (num_box_preds, fut_ts, 2).\n            gt_fut_masks (Tensor): Ground truth traj mask with shape (num_box_preds, fut_ts).\n            pred_box_centers (Tensor): Pred box centers with shape (num_box_preds, 2).\n            gt_box_centers (Tensor): Ground truth box centers with shape (num_box_preds, 2).\n\n        Returns:\n            best_traj_preds (Tensor): best traj preds (min displacement error with gt)\n                with shape (num_box_preds, fut_ts*2).\n        \"\"\"\n\n        cum_traj_preds = traj_preds.cumsum(dim=-2)\n        cum_traj_targets = traj_targets.cumsum(dim=-2)\n\n        # Get min pred mode indices.\n        # (num_box_preds, fut_mode, fut_ts)\n        dist = torch.linalg.norm(cum_traj_targets[:, None, :, :] - cum_traj_preds, dim=-1)\n        dist = dist * gt_fut_masks[:, None, :]\n        dist = dist[..., -1]\n        dist[torch.isnan(dist)] = dist[torch.isnan(dist)] * 0\n        min_mode_idxs = torch.argmin(dist, dim=-1).tolist()\n        box_idxs = torch.arange(traj_preds.shape[0]).tolist()\n        best_traj_preds = traj_preds[box_idxs, min_mode_idxs, :, :].reshape(-1, self.fut_ts*2)\n\n        return best_traj_preds\n\n    def get_traj_cls_target(self,\n             traj_preds,\n             traj_targets,\n             gt_fut_masks,\n             neg_inds):\n        \"\"\"\"Get Trajectory mode classification target.\n        Args:\n            traj_preds (Tensor): MultiModal traj preds with shape (num_box_preds, fut_mode, fut_ts, 2).\n            traj_targets (Tensor): Ground truth traj for each pred box with shape (num_box_preds, fut_ts, 2).\n            gt_fut_masks (Tensor): Ground truth traj mask with shape (num_box_preds, fut_ts).\n            neg_inds (Tensor): Negtive indices with shape (num_box_preds,)\n\n        Returns:\n            traj_labels (Tensor): traj cls labels (num_box_preds,).\n        \"\"\"\n\n        cum_traj_preds = traj_preds.cumsum(dim=-2)\n        cum_traj_targets = traj_targets.cumsum(dim=-2)\n\n        # Get min pred mode indices.\n        # (num_box_preds, fut_mode, fut_ts)\n        dist = torch.linalg.norm(cum_traj_targets[:, None, :, :] - cum_traj_preds, dim=-1)\n        dist = dist * gt_fut_masks[:, None, :]\n        dist = dist[..., -1]\n        dist[torch.isnan(dist)] = dist[torch.isnan(dist)] * 0\n        traj_labels = torch.argmin(dist, dim=-1)\n        traj_labels[neg_inds] = self.fut_mode\n\n        return traj_labels\n\n    def map_loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    pts_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_shifts_pts_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_pts_list (list[Tensor]): Ground truth pts for each image\n                with shape (num_gts, fixed_num, 2) in [x,y] format.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        pts_preds_list = [pts_preds[i] for i in range(num_imgs)]\n\n        cls_reg_targets = self.map_get_targets(cls_scores_list, bbox_preds_list,pts_preds_list,\n                                           gt_bboxes_list, gt_labels_list,gt_shifts_pts_list,\n                                           gt_bboxes_ignore_list)\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         pts_targets_list, pts_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n \n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n        pts_targets = torch.cat(pts_targets_list, 0)\n        pts_weights = torch.cat(pts_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.map_cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.map_bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_map_cls(\n            cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # regression L1 loss\n        bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))\n        normalized_bbox_targets = normalize_2d_bbox(bbox_targets, self.pc_range)\n        # normalized_bbox_targets = bbox_targets\n        isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)\n        bbox_weights = bbox_weights * self.map_code_weights\n\n        loss_bbox = self.loss_map_bbox(\n            bbox_preds[isnotnan, :4],\n            normalized_bbox_targets[isnotnan,:4],\n            bbox_weights[isnotnan, :4],\n            avg_factor=num_total_pos)\n\n        # regression pts CD loss\n        # num_samples, num_order, num_pts, num_coords\n        normalized_pts_targets = normalize_2d_pts(pts_targets, self.pc_range)\n\n        # num_samples, num_pts, num_coords\n        pts_preds = pts_preds.reshape(-1, pts_preds.size(-2), pts_preds.size(-1))\n        if self.map_num_pts_per_vec != self.map_num_pts_per_gt_vec:\n            pts_preds = pts_preds.permute(0,2,1)\n            pts_preds = F.interpolate(pts_preds, size=(self.map_num_pts_per_gt_vec), mode='linear',\n                                    align_corners=True)\n            pts_preds = pts_preds.permute(0,2,1).contiguous()\n\n        loss_pts = self.loss_map_pts(\n            pts_preds[isnotnan,:,:],\n            normalized_pts_targets[isnotnan,:,:], \n            pts_weights[isnotnan,:,:],\n            avg_factor=num_total_pos)\n\n        dir_weights = pts_weights[:, :-self.map_dir_interval,0]\n        denormed_pts_preds = denormalize_2d_pts(pts_preds, self.pc_range)\n        denormed_pts_preds_dir = denormed_pts_preds[:,self.map_dir_interval:,:] - \\\n            denormed_pts_preds[:,:-self.map_dir_interval,:]\n        pts_targets_dir = pts_targets[:, self.map_dir_interval:,:] - pts_targets[:,:-self.map_dir_interval,:]\n\n        loss_dir = self.loss_map_dir(\n            denormed_pts_preds_dir[isnotnan,:,:],\n            pts_targets_dir[isnotnan,:,:],\n            dir_weights[isnotnan,:],\n            avg_factor=num_total_pos)\n\n        bboxes = denormalize_2d_bbox(bbox_preds, self.pc_range)\n        # regression IoU loss, defaultly GIoU loss\n        loss_iou = self.loss_map_iou(\n            bboxes[isnotnan, :4],\n            bbox_targets[isnotnan, :4],\n            bbox_weights[isnotnan, :4], \n            avg_factor=num_total_pos)\n\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_cls = torch.nan_to_num(loss_cls)\n            loss_bbox = torch.nan_to_num(loss_bbox)\n            loss_iou = torch.nan_to_num(loss_iou)\n            loss_pts = torch.nan_to_num(loss_pts)\n            loss_dir = torch.nan_to_num(loss_dir)\n\n        return loss_cls, loss_bbox, loss_iou, loss_pts, loss_dir\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             map_gt_bboxes_list,\n             map_gt_labels_list,\n             preds_dicts,\n             ego_fut_gt,\n             ego_fut_masks,\n             ego_fut_cmd,\n             gt_attr_labels,\n             gt_bboxes_ignore=None,\n             map_gt_bboxes_ignore=None,\n             img_metas=None):\n        \"\"\"\"Loss function.\n        Args:\n\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            preds_dicts:\n                all_cls_scores (Tensor): Classification score of all\n                    decoder layers, has shape\n                    [nb_dec, bs, num_query, cls_out_channels].\n                all_bbox_preds (Tensor): Sigmoid regression\n                    outputs of all decode layers. Each is a 4D-tensor with\n                    normalized coordinate format (cx, cy, w, h) and shape\n                    [nb_dec, bs, num_query, 4].\n                enc_cls_scores (Tensor): Classification scores of\n                    points on encode feature map , has shape\n                    (N, h*w, num_classes). Only be passed when as_two_stage is\n                    True, otherwise is None.\n                enc_bbox_preds (Tensor): Regression results of each points\n                    on the encode feature map, has shape (N, h*w, 4). Only be\n                    passed when as_two_stage is True, otherwise is None.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            f'{self.__class__.__name__} only supports ' \\\n            f'for gt_bboxes_ignore setting to None.'\n\n        map_gt_vecs_list = copy.deepcopy(map_gt_bboxes_list)\n\n        all_cls_scores = preds_dicts['all_cls_scores']\n        all_bbox_preds = preds_dicts['all_bbox_preds']\n        all_traj_preds = preds_dicts['all_traj_preds']\n        all_traj_cls_scores = preds_dicts['all_traj_cls_scores']\n        enc_cls_scores = preds_dicts['enc_cls_scores']\n        enc_bbox_preds = preds_dicts['enc_bbox_preds']\n        map_all_cls_scores = preds_dicts['map_all_cls_scores']\n        map_all_bbox_preds = preds_dicts['map_all_bbox_preds']\n        map_all_pts_preds = preds_dicts['map_all_pts_preds']\n        map_enc_cls_scores = preds_dicts['map_enc_cls_scores']\n        map_enc_bbox_preds = preds_dicts['map_enc_bbox_preds']\n        map_enc_pts_preds = preds_dicts['map_enc_pts_preds']\n        ego_fut_preds = preds_dicts['ego_fut_preds']\n\n        num_dec_layers = len(all_cls_scores)\n        device = gt_labels_list[0].device\n\n        gt_bboxes_list = [torch.cat(\n            (gt_bboxes.gravity_center, gt_bboxes.tensor[:, 3:]),\n            dim=1).to(device) for gt_bboxes in gt_bboxes_list]\n\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_attr_labels_list = [gt_attr_labels for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        losses_cls, losses_bbox, loss_traj, loss_traj_cls = multi_apply(\n            self.loss_single, all_cls_scores, all_bbox_preds, all_traj_preds,\n            all_traj_cls_scores, all_gt_bboxes_list, all_gt_labels_list,\n            all_gt_attr_labels_list, all_gt_bboxes_ignore_list)\n        \n\n        num_dec_layers = len(map_all_cls_scores)\n        device = map_gt_labels_list[0].device\n\n        map_gt_bboxes_list = [\n            map_gt_bboxes.bbox.to(device) for map_gt_bboxes in map_gt_vecs_list]\n        map_gt_pts_list = [\n            map_gt_bboxes.fixed_num_sampled_points.to(device) for map_gt_bboxes in map_gt_vecs_list]\n        if self.map_gt_shift_pts_pattern == 'v0':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v1':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v1.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v2':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v2.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v3':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v3.to(device) for gt_bboxes in map_gt_vecs_list]\n        elif self.map_gt_shift_pts_pattern == 'v4':\n            map_gt_shifts_pts_list = [\n                gt_bboxes.shift_fixed_num_sampled_points_v4.to(device) for gt_bboxes in map_gt_vecs_list]\n        else:\n            raise NotImplementedError\n        map_all_gt_bboxes_list = [map_gt_bboxes_list for _ in range(num_dec_layers)]\n        map_all_gt_labels_list = [map_gt_labels_list for _ in range(num_dec_layers)]\n        map_all_gt_pts_list = [map_gt_pts_list for _ in range(num_dec_layers)]\n        map_all_gt_shifts_pts_list = [map_gt_shifts_pts_list for _ in range(num_dec_layers)]\n        map_all_gt_bboxes_ignore_list = [\n            map_gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        map_losses_cls, map_losses_bbox, map_losses_iou, \\\n            map_losses_pts, map_losses_dir = multi_apply(\n            self.map_loss_single, map_all_cls_scores, map_all_bbox_preds,\n            map_all_pts_preds, map_all_gt_bboxes_list, map_all_gt_labels_list,\n            map_all_gt_shifts_pts_list, map_all_gt_bboxes_ignore_list)\n\n        loss_dict = dict()\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls[-1]\n        loss_dict['loss_bbox'] = losses_bbox[-1]\n        loss_dict['loss_traj'] = loss_traj[-1]\n        loss_dict['loss_traj_cls'] = loss_traj_cls[-1]\n        # loss from the last decoder layer\n        loss_dict['loss_map_cls'] = map_losses_cls[-1]\n        loss_dict['loss_map_bbox'] = map_losses_bbox[-1]\n        loss_dict['loss_map_iou'] = map_losses_iou[-1]\n        loss_dict['loss_map_pts'] = map_losses_pts[-1]\n        loss_dict['loss_map_dir'] = map_losses_dir[-1]\n\n        # Planning Loss\n        ego_fut_gt = ego_fut_gt.squeeze(1)\n        ego_fut_masks = ego_fut_masks.squeeze(1).squeeze(1)\n        ego_fut_cmd = ego_fut_cmd.squeeze(1).squeeze(1)\n\n        batch, num_agent = all_traj_preds[-1].shape[:2]\n        agent_fut_preds = all_traj_preds[-1].view(batch, num_agent, self.fut_mode, self.fut_ts, 2)\n        agent_fut_cls_preds = all_traj_cls_scores[-1].view(batch, num_agent, self.fut_mode)\n        loss_plan_input = [ego_fut_preds, ego_fut_gt, ego_fut_masks, ego_fut_cmd,\n                           map_all_pts_preds[-1], map_all_cls_scores[-1].sigmoid(),\n                           all_bbox_preds[-1][..., 0:2], agent_fut_preds,\n                           all_cls_scores[-1].sigmoid(), agent_fut_cls_preds.sigmoid()]\n\n        loss_planning_dict = self.loss_planning(*loss_plan_input)\n        loss_dict['loss_plan_reg'] = loss_planning_dict['loss_plan_reg']\n        loss_dict['loss_plan_bound'] = loss_planning_dict['loss_plan_bound']\n        loss_dict['loss_plan_col'] = loss_planning_dict['loss_plan_col']\n        loss_dict['loss_plan_dir'] = loss_planning_dict['loss_plan_dir']\n\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_cls_i, loss_bbox_i in zip(losses_cls[:-1], losses_bbox[:-1]):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i\n            num_dec_layer += 1\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for map_loss_cls_i, map_loss_bbox_i, map_loss_iou_i, map_loss_pts_i, map_loss_dir_i in zip(\n            map_losses_cls[:-1],\n            map_losses_bbox[:-1],\n            map_losses_iou[:-1],\n            map_losses_pts[:-1],\n            map_losses_dir[:-1]\n        ):\n            loss_dict[f'd{num_dec_layer}.loss_map_cls'] = map_loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_map_bbox'] = map_loss_bbox_i\n            loss_dict[f'd{num_dec_layer}.loss_map_iou'] = map_loss_iou_i\n            loss_dict[f'd{num_dec_layer}.loss_map_pts'] = map_loss_pts_i\n            loss_dict[f'd{num_dec_layer}.loss_map_dir'] = map_loss_dir_i\n            num_dec_layer += 1\n\n        # loss of proposal generated from encode feature map.\n        if enc_cls_scores is not None:\n            binary_labels_list = [\n                torch.zeros_like(gt_labels_list[i])\n                for i in range(len(all_gt_labels_list))\n            ]\n            enc_loss_cls, enc_losses_bbox = \\\n                self.loss_single(enc_cls_scores, enc_bbox_preds,\n                                 gt_bboxes_list, binary_labels_list,\n                                 gt_bboxes_ignore)\n            loss_dict['enc_loss_cls'] = enc_loss_cls\n            loss_dict['enc_loss_bbox'] = enc_losses_bbox\n\n        if map_enc_cls_scores is not None:\n            map_binary_labels_list = [\n                torch.zeros_like(map_gt_labels_list[i])\n                for i in range(len(map_all_gt_labels_list))\n            ]\n            # TODO bug here, but we dont care enc_loss now\n            map_enc_loss_cls, map_enc_loss_bbox, map_enc_loss_iou, \\\n                 map_enc_loss_pts, map_enc_loss_dir = \\\n                self.map_loss_single(\n                    map_enc_cls_scores, map_enc_bbox_preds,\n                    map_enc_pts_preds, map_gt_bboxes_list,\n                    map_binary_labels_list, map_gt_pts_list,\n                    map_gt_bboxes_ignore\n                )\n            loss_dict['enc_loss_map_cls'] = map_enc_loss_cls\n            loss_dict['enc_loss_map_bbox'] = map_enc_loss_bbox\n            loss_dict['enc_loss_map_iou'] = map_enc_loss_iou\n            loss_dict['enc_loss_map_pts'] = map_enc_loss_pts\n            loss_dict['enc_loss_map_dir'] = map_enc_loss_dir\n\n        return loss_dict\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def get_bboxes(self, preds_dicts, img_metas, rescale=False):\n        \"\"\"Generate bboxes from bbox head predictions.\n        Args:\n            preds_dicts (tuple[list[dict]]): Prediction results.\n            img_metas (list[dict]): Point cloud and image's meta info.\n        Returns:\n            list[dict]: Decoded bbox, scores and labels after nms.\n        \"\"\"\n\n        det_preds_dicts = self.bbox_coder.decode(preds_dicts)\n        # map_bboxes: xmin, ymin, xmax, ymax\n        map_preds_dicts = self.map_bbox_coder.decode(preds_dicts)\n\n        num_samples = len(det_preds_dicts)\n        assert len(det_preds_dicts) == len(map_preds_dicts), \\\n             'len(preds_dict) should be equal to len(map_preds_dicts)'\n        ret_list = []\n        for i in range(num_samples):\n            preds = det_preds_dicts[i]\n            bboxes = preds['bboxes']\n            bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5\n            code_size = bboxes.shape[-1]\n            bboxes = img_metas[i]['box_type_3d'](bboxes, code_size)\n            scores = preds['scores']\n            labels = preds['labels']\n            trajs = preds['trajs']\n\n            map_preds = map_preds_dicts[i]\n            map_bboxes = map_preds['map_bboxes']\n            map_scores = map_preds['map_scores']\n            map_labels = map_preds['map_labels']\n            map_pts = map_preds['map_pts']\n\n            ret_list.append([bboxes, scores, labels, trajs, map_bboxes,\n                             map_scores, map_labels, map_pts])\n\n        return ret_list\n\n    def select_and_pad_pred_map(\n        self,\n        motion_pos,\n        map_query,\n        map_score,\n        map_pos,\n        map_thresh=0.5,\n        dis_thresh=None,\n        pe_normalization=True,\n        use_fix_pad=False\n    ):\n        \"\"\"select_and_pad_pred_map.\n        Args:\n            motion_pos: [B, A, 2]\n            map_query: [B, P, D].\n            map_score: [B, P, 3].\n            map_pos: [B, P, pts, 2].\n            map_thresh: map confidence threshold for filtering low-confidence preds\n            dis_thresh: distance threshold for masking far maps for each agent in cross-attn\n            use_fix_pad: always pad one lane instance for each batch\n        Returns:\n            selected_map_query: [B*A, P1(+1), D], P1 is the max inst num after filter and pad.\n            selected_map_pos: [B*A, P1(+1), 2]\n            selected_padding_mask: [B*A, P1(+1)]\n        \"\"\"\n        \n        if dis_thresh is None:\n            raise NotImplementedError('Not implement yet')\n\n        # use the most close pts pos in each map inst as the inst's pos\n        batch, num_map = map_pos.shape[:2]\n        map_dis = torch.sqrt(map_pos[..., 0]**2 + map_pos[..., 1]**2)\n        min_map_pos_idx = map_dis.argmin(dim=-1).flatten()  # [B*P]\n        min_map_pos = map_pos.flatten(0, 1)  # [B*P, pts, 2]\n        min_map_pos = min_map_pos[range(min_map_pos.shape[0]), min_map_pos_idx]  # [B*P, 2]\n        min_map_pos = min_map_pos.view(batch, num_map, 2)  # [B, P, 2]\n\n        # select & pad map vectors for different batch using map_thresh\n        map_score = map_score.sigmoid()\n        map_max_score = map_score.max(dim=-1)[0]\n        map_idx = map_max_score > map_thresh\n        batch_max_pnum = 0\n        for i in range(map_score.shape[0]):\n            pnum = map_idx[i].sum()\n            if pnum > batch_max_pnum:\n                batch_max_pnum = pnum\n\n        selected_map_query, selected_map_pos, selected_padding_mask = [], [], []\n        for i in range(map_score.shape[0]):\n            dim = map_query.shape[-1]\n            valid_pnum = map_idx[i].sum()\n            valid_map_query = map_query[i, map_idx[i]]\n            valid_map_pos = min_map_pos[i, map_idx[i]]\n            pad_pnum = batch_max_pnum - valid_pnum\n            padding_mask = torch.tensor([False], device=map_score.device).repeat(batch_max_pnum)\n            if pad_pnum != 0:\n                valid_map_query = torch.cat([valid_map_query, torch.zeros((pad_pnum, dim), device=map_score.device)], dim=0)\n                valid_map_pos = torch.cat([valid_map_pos, torch.zeros((pad_pnum, 2), device=map_score.device)], dim=0)\n                padding_mask[valid_pnum:] = True\n            selected_map_query.append(valid_map_query)\n            selected_map_pos.append(valid_map_pos)\n            selected_padding_mask.append(padding_mask)\n\n        selected_map_query = torch.stack(selected_map_query, dim=0)\n        selected_map_pos = torch.stack(selected_map_pos, dim=0)\n        selected_padding_mask = torch.stack(selected_padding_mask, dim=0)\n\n        # generate different pe for map vectors for each agent\n        num_agent = motion_pos.shape[1]\n        selected_map_query = selected_map_query.unsqueeze(1).repeat(1, num_agent, 1, 1)  # [B, A, max_P, D]\n        selected_map_pos = selected_map_pos.unsqueeze(1).repeat(1, num_agent, 1, 1)  # [B, A, max_P, 2]\n        selected_padding_mask = selected_padding_mask.unsqueeze(1).repeat(1, num_agent, 1)  # [B, A, max_P]\n        # move lane to per-car coords system\n        selected_map_dist = selected_map_pos - motion_pos[:, :, None, :]  # [B, A, max_P, 2]\n        if pe_normalization:\n            selected_map_pos = selected_map_pos - motion_pos[:, :, None, :]  # [B, A, max_P, 2]\n\n        # filter far map inst for each agent\n        map_dis = torch.sqrt(selected_map_dist[..., 0]**2 + selected_map_dist[..., 1]**2)\n        valid_map_inst = (map_dis <= dis_thresh)  # [B, A, max_P]\n        invalid_map_inst = (valid_map_inst == False)\n        selected_padding_mask = selected_padding_mask + invalid_map_inst\n\n        selected_map_query = selected_map_query.flatten(0, 1)\n        selected_map_pos = selected_map_pos.flatten(0, 1)\n        selected_padding_mask = selected_padding_mask.flatten(0, 1)\n\n        num_batch = selected_padding_mask.shape[0]\n        feat_dim = selected_map_query.shape[-1]\n        if use_fix_pad:\n            pad_map_query = torch.zeros((num_batch, 1, feat_dim), device=selected_map_query.device)\n            pad_map_pos = torch.ones((num_batch, 1, 2), device=selected_map_pos.device)\n            pad_lane_mask = torch.tensor([False], device=selected_padding_mask.device).unsqueeze(0).repeat(num_batch, 1)\n            selected_map_query = torch.cat([selected_map_query, pad_map_query], dim=1)\n            selected_map_pos = torch.cat([selected_map_pos, pad_map_pos], dim=1)\n            selected_padding_mask = torch.cat([selected_padding_mask, pad_lane_mask], dim=1)\n\n        return selected_map_query, selected_map_pos, selected_padding_mask\n\n\n    def select_and_pad_query(\n        self,\n        query,\n        query_pos,\n        query_score,\n        score_thresh=0.5,\n        use_fix_pad=True\n    ):\n        \"\"\"select_and_pad_query.\n        Args:\n            query: [B, Q, D].\n            query_pos: [B, Q, 2]\n            query_score: [B, Q, C].\n            score_thresh: confidence threshold for filtering low-confidence query\n            use_fix_pad: always pad one query instance for each batch\n        Returns:\n            selected_query: [B, Q', D]\n            selected_query_pos: [B, Q', 2]\n            selected_padding_mask: [B, Q']\n        \"\"\"\n\n        # select & pad query for different batch using score_thresh\n        query_score = query_score.sigmoid()\n        query_score = query_score.max(dim=-1)[0]\n        query_idx = query_score > score_thresh\n        batch_max_qnum = 0\n        for i in range(query_score.shape[0]):\n            qnum = query_idx[i].sum()\n            if qnum > batch_max_qnum:\n                batch_max_qnum = qnum\n\n        selected_query, selected_query_pos, selected_padding_mask = [], [], []\n        for i in range(query_score.shape[0]):\n            dim = query.shape[-1]\n            valid_qnum = query_idx[i].sum()\n            valid_query = query[i, query_idx[i]]\n            valid_query_pos = query_pos[i, query_idx[i]]\n            pad_qnum = batch_max_qnum - valid_qnum\n            padding_mask = torch.tensor([False], device=query_score.device).repeat(batch_max_qnum)\n            if pad_qnum != 0:\n                valid_query = torch.cat([valid_query, torch.zeros((pad_qnum, dim), device=query_score.device)], dim=0)\n                valid_query_pos = torch.cat([valid_query_pos, torch.zeros((pad_qnum, 2), device=query_score.device)], dim=0)\n                padding_mask[valid_qnum:] = True\n            selected_query.append(valid_query)\n            selected_query_pos.append(valid_query_pos)\n            selected_padding_mask.append(padding_mask)\n\n        selected_query = torch.stack(selected_query, dim=0)\n        selected_query_pos = torch.stack(selected_query_pos, dim=0)\n        selected_padding_mask = torch.stack(selected_padding_mask, dim=0)\n\n        num_batch = selected_padding_mask.shape[0]\n        feat_dim = selected_query.shape[-1]\n        if use_fix_pad:\n            pad_query = torch.zeros((num_batch, 1, feat_dim), device=selected_query.device)\n            pad_query_pos = torch.ones((num_batch, 1, 2), device=selected_query_pos.device)\n            pad_mask = torch.tensor([False], device=selected_padding_mask.device).unsqueeze(0).repeat(num_batch, 1)\n            selected_query = torch.cat([selected_query, pad_query], dim=1)\n            selected_query_pos = torch.cat([selected_query_pos, pad_query_pos], dim=1)\n            selected_padding_mask = torch.cat([selected_padding_mask, pad_mask], dim=1)\n\n        return selected_query, selected_query_pos, selected_padding_mask\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/__init__.py",
    "content": "from .detr_head import DETRHead\nfrom .rpn_head import RPNHead\nfrom .ga_rpn_head import GARPNHead\nfrom .track_head import BEVFormerTrackHead\nfrom .panseg_head import PansegformerHead\nfrom .occ_head import OccHead\nfrom .motion_head import MotionHead\nfrom .planning_head import PlanningHeadSingleMode\nfrom .bevformer_head import BEVFormerHead\nfrom .VAD_head import VADHead\nfrom .MomAD_head import MomADHead"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/anchor3d_head.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom mmcv.utils import force_fp32\nfrom mmcv.models import BaseModule\nfrom torch import nn as nn\n\nfrom mmcv.core import (PseudoSampler, box3d_multiclass_nms, limit_period,\n                          xywhr2xyxyr)\nfrom mmcv.core import (build_assigner, build_bbox_coder,\n                        build_prior_generator, build_sampler, multi_apply)\nfrom mmcv.models import HEADS\nfrom ..builder import build_loss\nfrom .train_mixins import AnchorTrainMixin\n\n@HEADS.register_module()\nclass Anchor3DHead(BaseModule, AnchorTrainMixin):\n    \"\"\"Anchor head for SECOND/PointPillars/MVXNet/PartA2.\n\n    Args:\n        num_classes (int): Number of classes.\n        in_channels (int): Number of channels in the input feature map.\n        train_cfg (dict): Train configs.\n        test_cfg (dict): Test configs.\n        feat_channels (int): Number of channels of the feature map.\n        use_direction_classifier (bool): Whether to add a direction classifier.\n        anchor_generator(dict): Config dict of anchor generator.\n        assigner_per_size (bool): Whether to do assignment for each separate\n            anchor size.\n        assign_per_class (bool): Whether to do assignment for each class.\n        diff_rad_by_sin (bool): Whether to change the difference into sin\n            difference for box regression loss.\n        dir_offset (float | int): The offset of BEV rotation angles.\n            (TODO: may be moved into box coder)\n        dir_limit_offset (float | int): The limited range of BEV\n            rotation angles. (TODO: may be moved into box coder)\n        bbox_coder (dict): Config dict of box coders.\n        loss_cls (dict): Config of classification loss.\n        loss_bbox (dict): Config of localization loss.\n        loss_dir (dict): Config of direction classifier loss.\n    \"\"\"\n\n    def __init__(self,\n                 num_classes,\n                 in_channels,\n                 train_cfg,\n                 test_cfg,\n                 feat_channels=256,\n                 use_direction_classifier=True,\n                 anchor_generator=dict(\n                     type='Anchor3DRangeGenerator',\n                     range=[0, -39.68, -1.78, 69.12, 39.68, -1.78],\n                     strides=[2],\n                     sizes=[[1.6, 3.9, 1.56]],\n                     rotations=[0, 1.57],\n                     custom_values=[],\n                     reshape_out=False),\n                 assigner_per_size=False,\n                 assign_per_class=False,\n                 diff_rad_by_sin=True,\n                 dir_offset=0,\n                 dir_limit_offset=1,\n                 bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),\n                 loss_cls=dict(\n                     type='CrossEntropyLoss',\n                     use_sigmoid=True,\n                     loss_weight=1.0),\n                 loss_bbox=dict(\n                     type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),\n                 loss_dir=dict(type='CrossEntropyLoss', loss_weight=0.2),\n                 init_cfg=None):\n        super().__init__(init_cfg=init_cfg)\n        self.in_channels = in_channels\n        self.num_classes = num_classes\n        self.feat_channels = feat_channels\n        self.diff_rad_by_sin = diff_rad_by_sin\n        self.use_direction_classifier = use_direction_classifier\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n        self.assigner_per_size = assigner_per_size\n        self.assign_per_class = assign_per_class\n        self.dir_offset = dir_offset\n        self.dir_limit_offset = dir_limit_offset\n        self.fp16_enabled = False\n\n        # build anchor generator\n        self.anchor_generator = build_prior_generator(anchor_generator)\n        # In 3D detection, the anchor stride is connected with anchor size\n        self.num_anchors = self.anchor_generator.num_base_anchors\n        # build box coder\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n        self.box_code_size = self.bbox_coder.code_size\n\n        # build loss function\n        self.use_sigmoid_cls = loss_cls.get('use_sigmoid', False)\n        self.sampling = loss_cls['type'] not in ['FocalLoss', 'GHMC']\n        if not self.use_sigmoid_cls:\n            self.num_classes += 1\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bbox = build_loss(loss_bbox)\n        self.loss_dir = build_loss(loss_dir)\n        self.fp16_enabled = False\n\n        self._init_layers()\n        self._init_assigner_sampler()\n\n        if init_cfg is None:\n            self.init_cfg = dict(\n                type='Normal',\n                layer='Conv2d',\n                std=0.01,\n                override=dict(\n                    type='Normal', name='conv_cls', std=0.01, bias_prob=0.01))\n\n    def _init_assigner_sampler(self):\n        \"\"\"Initialize the target assigner and sampler of the head.\"\"\"\n        if self.train_cfg is None:\n            return\n\n        if self.sampling:\n            self.bbox_sampler = build_sampler(self.train_cfg.sampler)\n        else:\n            self.bbox_sampler = PseudoSampler()\n        if isinstance(self.train_cfg.assigner, dict):\n            self.bbox_assigner = build_assigner(self.train_cfg.assigner)\n        elif isinstance(self.train_cfg.assigner, list):\n            self.bbox_assigner = [\n                build_assigner(res) for res in self.train_cfg.assigner\n            ]\n\n    def _init_layers(self):\n        \"\"\"Initialize neural network layers of the head.\"\"\"\n        self.cls_out_channels = self.num_anchors * self.num_classes\n        self.conv_cls = nn.Conv2d(self.feat_channels, self.cls_out_channels, 1)\n        self.conv_reg = nn.Conv2d(self.feat_channels,\n                                  self.num_anchors * self.box_code_size, 1)\n        if self.use_direction_classifier:\n            self.conv_dir_cls = nn.Conv2d(self.feat_channels,\n                                          self.num_anchors * 2, 1)\n\n    def forward_single(self, x):\n        \"\"\"Forward function on a single-scale feature map.\n\n        Args:\n            x (torch.Tensor): Input features.\n\n        Returns:\n            tuple[torch.Tensor]: Contain score of each class, bbox \\\n                regression and direction classification predictions.\n        \"\"\"\n        cls_score = self.conv_cls(x)\n        bbox_pred = self.conv_reg(x)\n        dir_cls_preds = None\n        if self.use_direction_classifier:\n            dir_cls_preds = self.conv_dir_cls(x)\n        return cls_score, bbox_pred, dir_cls_preds\n\n    def forward(self, feats):\n        \"\"\"Forward pass.\n\n        Args:\n            feats (list[torch.Tensor]): Multi-level features, e.g.,\n                features produced by FPN.\n\n        Returns:\n            tuple[list[torch.Tensor]]: Multi-level class score, bbox \\\n                and direction predictions.\n        \"\"\"\n        return multi_apply(self.forward_single, feats)\n\n    def get_anchors(self, featmap_sizes, input_metas, device='cuda'):\n        \"\"\"Get anchors according to feature map sizes.\n\n        Args:\n            featmap_sizes (list[tuple]): Multi-level feature map sizes.\n            input_metas (list[dict]): contain pcd and img's meta info.\n            device (str): device of current module.\n\n        Returns:\n            list[list[torch.Tensor]]: Anchors of each image, valid flags \\\n                of each image.\n        \"\"\"\n        num_imgs = len(input_metas)\n        # since feature map sizes of all images are the same, we only compute\n        # anchors for one time\n        multi_level_anchors = self.anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n        anchor_list = [multi_level_anchors for _ in range(num_imgs)]\n        return anchor_list\n\n    def loss_single(self, cls_score, bbox_pred, dir_cls_preds, labels,\n                    label_weights, bbox_targets, bbox_weights, dir_targets,\n                    dir_weights, num_total_samples):\n        \"\"\"Calculate loss of Single-level results.\n\n        Args:\n            cls_score (torch.Tensor): Class score in single-level.\n            bbox_pred (torch.Tensor): Bbox prediction in single-level.\n            dir_cls_preds (torch.Tensor): Predictions of direction class\n                in single-level.\n            labels (torch.Tensor): Labels of class.\n            label_weights (torch.Tensor): Weights of class loss.\n            bbox_targets (torch.Tensor): Targets of bbox predictions.\n            bbox_weights (torch.Tensor): Weights of bbox loss.\n            dir_targets (torch.Tensor): Targets of direction predictions.\n            dir_weights (torch.Tensor): Weights of direction loss.\n            num_total_samples (int): The number of valid samples.\n\n        Returns:\n            tuple[torch.Tensor]: Losses of class, bbox \\\n                and direction, respectively.\n        \"\"\"\n        # classification loss\n        if num_total_samples is None:\n            num_total_samples = int(cls_score.shape[0])\n        labels = labels.reshape(-1)\n        label_weights = label_weights.reshape(-1)\n        cls_score = cls_score.permute(0, 2, 3, 1).reshape(-1, self.num_classes)\n        assert labels.max().item() <= self.num_classes\n        loss_cls = self.loss_cls(\n            cls_score, labels, label_weights, avg_factor=num_total_samples)\n\n        # regression loss\n        bbox_pred = bbox_pred.permute(0, 2, 3,\n                                      1).reshape(-1, self.box_code_size)\n        bbox_targets = bbox_targets.reshape(-1, self.box_code_size)\n        bbox_weights = bbox_weights.reshape(-1, self.box_code_size)\n\n        bg_class_ind = self.num_classes\n        pos_inds = ((labels >= 0)\n                    & (labels < bg_class_ind)).nonzero(\n                        as_tuple=False).reshape(-1)\n        num_pos = len(pos_inds)\n\n        pos_bbox_pred = bbox_pred[pos_inds]\n        pos_bbox_targets = bbox_targets[pos_inds]\n        pos_bbox_weights = bbox_weights[pos_inds]\n\n        # dir loss\n        if self.use_direction_classifier:\n            dir_cls_preds = dir_cls_preds.permute(0, 2, 3, 1).reshape(-1, 2)\n            dir_targets = dir_targets.reshape(-1)\n            dir_weights = dir_weights.reshape(-1)\n            pos_dir_cls_preds = dir_cls_preds[pos_inds]\n            pos_dir_targets = dir_targets[pos_inds]\n            pos_dir_weights = dir_weights[pos_inds]\n\n        if num_pos > 0:\n            code_weight = self.train_cfg.get('code_weight', None)\n            if code_weight:\n                pos_bbox_weights = pos_bbox_weights * bbox_weights.new_tensor(\n                    code_weight)\n            if self.diff_rad_by_sin:\n                pos_bbox_pred, pos_bbox_targets = self.add_sin_difference(\n                    pos_bbox_pred, pos_bbox_targets)\n            loss_bbox = self.loss_bbox(\n                pos_bbox_pred,\n                pos_bbox_targets,\n                pos_bbox_weights,\n                avg_factor=num_total_samples)\n\n            # direction classification loss\n            loss_dir = None\n            if self.use_direction_classifier:\n                loss_dir = self.loss_dir(\n                    pos_dir_cls_preds,\n                    pos_dir_targets,\n                    pos_dir_weights,\n                    avg_factor=num_total_samples)\n        else:\n            loss_bbox = pos_bbox_pred.sum()\n            if self.use_direction_classifier:\n                loss_dir = pos_dir_cls_preds.sum()\n\n        return loss_cls, loss_bbox, loss_dir\n\n    @staticmethod\n    def add_sin_difference(boxes1, boxes2):\n        \"\"\"Convert the rotation difference to difference in sine function.\n\n        Args:\n            boxes1 (torch.Tensor): Original Boxes in shape (NxC), where C>=7\n                and the 7th dimension is rotation dimension.\n            boxes2 (torch.Tensor): Target boxes in shape (NxC), where C>=7 and\n                the 7th dimension is rotation dimension.\n\n        Returns:\n            tuple[torch.Tensor]: ``boxes1`` and ``boxes2`` whose 7th \\\n                dimensions are changed.\n        \"\"\"\n        rad_pred_encoding = torch.sin(boxes1[..., 6:7]) * torch.cos(\n            boxes2[..., 6:7])\n        rad_tg_encoding = torch.cos(boxes1[..., 6:7]) * torch.sin(boxes2[...,\n                                                                         6:7])\n        boxes1 = torch.cat(\n            [boxes1[..., :6], rad_pred_encoding, boxes1[..., 7:]], dim=-1)\n        boxes2 = torch.cat([boxes2[..., :6], rad_tg_encoding, boxes2[..., 7:]],\n                           dim=-1)\n        return boxes1, boxes2\n\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds', 'dir_cls_preds'))\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             dir_cls_preds,\n             gt_bboxes,\n             gt_labels,\n             input_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"Calculate losses.\n\n        Args:\n            cls_scores (list[torch.Tensor]): Multi-level class scores.\n            bbox_preds (list[torch.Tensor]): Multi-level bbox predictions.\n            dir_cls_preds (list[torch.Tensor]): Multi-level direction\n                class predictions.\n            gt_bboxes (list[:obj:`BaseInstance3DBoxes`]): Gt bboxes\n                of each sample.\n            gt_labels (list[torch.Tensor]): Gt labels of each sample.\n            input_metas (list[dict]): Contain pcd and img's meta info.\n            gt_bboxes_ignore (None | list[torch.Tensor]): Specify\n                which bounding.\n\n        Returns:\n            dict[str, list[torch.Tensor]]: Classification, bbox, and \\\n                direction losses of each level.\n\n                - loss_cls (list[torch.Tensor]): Classification losses.\n                - loss_bbox (list[torch.Tensor]): Box regression losses.\n                - loss_dir (list[torch.Tensor]): Direction classification \\\n                    losses.\n        \"\"\"\n        featmap_sizes = [featmap.size()[-2:] for featmap in cls_scores]\n        assert len(featmap_sizes) == self.anchor_generator.num_levels\n        device = cls_scores[0].device\n        anchor_list = self.get_anchors(\n            featmap_sizes, input_metas, device=device)\n        label_channels = self.cls_out_channels if self.use_sigmoid_cls else 1\n        cls_reg_targets = self.anchor_target_3d(\n            anchor_list,\n            gt_bboxes,\n            input_metas,\n            gt_bboxes_ignore_list=gt_bboxes_ignore,\n            gt_labels_list=gt_labels,\n            num_classes=self.num_classes,\n            label_channels=label_channels,\n            sampling=self.sampling)\n\n        if cls_reg_targets is None:\n            return None\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         dir_targets_list, dir_weights_list, num_total_pos,\n         num_total_neg) = cls_reg_targets\n        num_total_samples = (\n            num_total_pos + num_total_neg if self.sampling else num_total_pos)\n\n        # num_total_samples = None\n        losses_cls, losses_bbox, losses_dir = multi_apply(\n            self.loss_single,\n            cls_scores,\n            bbox_preds,\n            dir_cls_preds,\n            labels_list,\n            label_weights_list,\n            bbox_targets_list,\n            bbox_weights_list,\n            dir_targets_list,\n            dir_weights_list,\n            num_total_samples=num_total_samples)\n        return dict(\n            loss_cls=losses_cls, loss_bbox=losses_bbox, loss_dir=losses_dir)\n\n    def get_bboxes(self,\n                   cls_scores,\n                   bbox_preds,\n                   dir_cls_preds,\n                   input_metas,\n                   cfg=None,\n                   rescale=False):\n        \"\"\"Get bboxes of anchor head.\n\n        Args:\n            cls_scores (list[torch.Tensor]): Multi-level class scores.\n            bbox_preds (list[torch.Tensor]): Multi-level bbox predictions.\n            dir_cls_preds (list[torch.Tensor]): Multi-level direction\n                class predictions.\n            input_metas (list[dict]): Contain pcd and img's meta info.\n            cfg (None | :obj:`ConfigDict`): Training or testing config.\n            rescale (list[torch.Tensor]): Whether th rescale bbox.\n\n        Returns:\n            list[tuple]: Prediction resultes of batches.\n        \"\"\"\n        assert len(cls_scores) == len(bbox_preds)\n        assert len(cls_scores) == len(dir_cls_preds)\n        num_levels = len(cls_scores)\n        featmap_sizes = [cls_scores[i].shape[-2:] for i in range(num_levels)]\n        device = cls_scores[0].device\n        mlvl_anchors = self.anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n        mlvl_anchors = [\n            anchor.reshape(-1, self.box_code_size) for anchor in mlvl_anchors\n        ]\n\n        result_list = []\n        for img_id in range(len(input_metas)):\n            cls_score_list = [\n                cls_scores[i][img_id].detach() for i in range(num_levels)\n            ]\n            bbox_pred_list = [\n                bbox_preds[i][img_id].detach() for i in range(num_levels)\n            ]\n            dir_cls_pred_list = [\n                dir_cls_preds[i][img_id].detach() for i in range(num_levels)\n            ]\n\n            input_meta = input_metas[img_id]\n            proposals = self.get_bboxes_single(cls_score_list, bbox_pred_list,\n                                               dir_cls_pred_list, mlvl_anchors,\n                                               input_meta, cfg, rescale)\n            result_list.append(proposals)\n        return result_list\n\n    def get_bboxes_single(self,\n                          cls_scores,\n                          bbox_preds,\n                          dir_cls_preds,\n                          mlvl_anchors,\n                          input_meta,\n                          cfg=None,\n                          rescale=False):\n        \"\"\"Get bboxes of single branch.\n\n        Args:\n            cls_scores (torch.Tensor): Class score in single batch.\n            bbox_preds (torch.Tensor): Bbox prediction in single batch.\n            dir_cls_preds (torch.Tensor): Predictions of direction class\n                in single batch.\n            mlvl_anchors (List[torch.Tensor]): Multi-level anchors\n                in single batch.\n            input_meta (list[dict]): Contain pcd and img's meta info.\n            cfg (None | :obj:`ConfigDict`): Training or testing config.\n            rescale (list[torch.Tensor]): whether th rescale bbox.\n\n        Returns:\n            tuple: Contain predictions of single batch.\n\n                - bboxes (:obj:`BaseInstance3DBoxes`): Predicted 3d bboxes.\n                - scores (torch.Tensor): Class score of each bbox.\n                - labels (torch.Tensor): Label of each bbox.\n        \"\"\"\n        cfg = self.test_cfg if cfg is None else cfg\n        assert len(cls_scores) == len(bbox_preds) == len(mlvl_anchors)\n        mlvl_bboxes = []\n        mlvl_scores = []\n        mlvl_dir_scores = []\n        for cls_score, bbox_pred, dir_cls_pred, anchors in zip(\n                cls_scores, bbox_preds, dir_cls_preds, mlvl_anchors):\n            assert cls_score.size()[-2:] == bbox_pred.size()[-2:]\n            assert cls_score.size()[-2:] == dir_cls_pred.size()[-2:]\n            dir_cls_pred = dir_cls_pred.permute(1, 2, 0).reshape(-1, 2)\n            dir_cls_score = torch.max(dir_cls_pred, dim=-1)[1]\n\n            cls_score = cls_score.permute(1, 2,\n                                          0).reshape(-1, self.num_classes)\n            if self.use_sigmoid_cls:\n                scores = cls_score.sigmoid()\n            else:\n                scores = cls_score.softmax(-1)\n            bbox_pred = bbox_pred.permute(1, 2,\n                                          0).reshape(-1, self.box_code_size)\n\n            nms_pre = cfg.get('nms_pre', -1)\n            if nms_pre > 0 and scores.shape[0] > nms_pre:\n                if self.use_sigmoid_cls:\n                    max_scores, _ = scores.max(dim=1)\n                else:\n                    max_scores, _ = scores[:, :-1].max(dim=1)\n                _, topk_inds = max_scores.topk(nms_pre)\n                anchors = anchors[topk_inds, :]\n                bbox_pred = bbox_pred[topk_inds, :]\n                scores = scores[topk_inds, :]\n                dir_cls_score = dir_cls_score[topk_inds]\n\n            bboxes = self.bbox_coder.decode(anchors, bbox_pred)\n            mlvl_bboxes.append(bboxes)\n            mlvl_scores.append(scores)\n            mlvl_dir_scores.append(dir_cls_score)\n\n        mlvl_bboxes = torch.cat(mlvl_bboxes)\n        mlvl_bboxes_for_nms = xywhr2xyxyr(input_meta['box_type_3d'](\n            mlvl_bboxes, box_dim=self.box_code_size).bev)\n        mlvl_scores = torch.cat(mlvl_scores)\n        mlvl_dir_scores = torch.cat(mlvl_dir_scores)\n\n        if self.use_sigmoid_cls:\n            # Add a dummy background class to the front when using sigmoid\n            padding = mlvl_scores.new_zeros(mlvl_scores.shape[0], 1)\n            mlvl_scores = torch.cat([mlvl_scores, padding], dim=1)\n\n        score_thr = cfg.get('score_thr', 0)\n        results = box3d_multiclass_nms(mlvl_bboxes, mlvl_bboxes_for_nms,\n                                       mlvl_scores, score_thr, cfg.max_num,\n                                       cfg, mlvl_dir_scores)\n        bboxes, scores, labels, dir_scores = results\n        if bboxes.shape[0] > 0:\n            dir_rot = limit_period(bboxes[..., 6] - self.dir_offset,\n                                   self.dir_limit_offset, np.pi)\n            bboxes[..., 6] = (\n                dir_rot + self.dir_offset +\n                np.pi * dir_scores.to(bboxes.dtype))\n        bboxes = input_meta['box_type_3d'](bboxes, box_dim=self.box_code_size)\n        return bboxes, scores, labels"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/anchor_free_head.py",
    "content": "from abc import abstractmethod\n\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.bricks import ConvModule\nfrom mmcv.utils import force_fp32\n\nfrom ...core.utils import multi_apply\nfrom ..builder import HEADS, build_loss\nfrom .base_dense_head import BaseDenseHead\nfrom .dense_test_mixins import BBoxTestMixin\n\n\n@HEADS.register_module()\nclass AnchorFreeHead(BaseDenseHead, BBoxTestMixin):\n    \"\"\"Anchor-free head (FCOS, Fovea, RepPoints, etc.).\n\n    Args:\n        num_classes (int): Number of categories excluding the background\n            category.\n        in_channels (int): Number of channels in the input feature map.\n        feat_channels (int): Number of hidden channels. Used in child classes.\n        stacked_convs (int): Number of stacking convs of the head.\n        strides (tuple): Downsample factor of each feature map.\n        dcn_on_last_conv (bool): If true, use dcn in the last layer of\n            towers. Default: False.\n        conv_bias (bool | str): If specified as `auto`, it will be decided by\n            the norm_cfg. Bias of conv will be set as True if `norm_cfg` is\n            None, otherwise False. Default: \"auto\".\n        loss_cls (dict): Config of classification loss.\n        loss_bbox (dict): Config of localization loss.\n        conv_cfg (dict): Config dict for convolution layer. Default: None.\n        norm_cfg (dict): Config dict for normalization layer. Default: None.\n        train_cfg (dict): Training config of anchor head.\n        test_cfg (dict): Testing config of anchor head.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n    \"\"\"  # noqa: W605\n\n    _version = 1\n\n    def __init__(self,\n                 num_classes,\n                 in_channels,\n                 feat_channels=256,\n                 stacked_convs=4,\n                 strides=(4, 8, 16, 32, 64),\n                 dcn_on_last_conv=False,\n                 conv_bias='auto',\n                 loss_cls=dict(\n                     type='FocalLoss',\n                     use_sigmoid=True,\n                     gamma=2.0,\n                     alpha=0.25,\n                     loss_weight=1.0),\n                 loss_bbox=dict(type='IoULoss', loss_weight=1.0),\n                 conv_cfg=None,\n                 norm_cfg=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 init_cfg=dict(\n                     type='Normal',\n                     layer='Conv2d',\n                     std=0.01,\n                     override=dict(\n                         type='Normal',\n                         name='conv_cls',\n                         std=0.01,\n                         bias_prob=0.01))):\n        super(AnchorFreeHead, self).__init__(init_cfg)\n        self.num_classes = num_classes\n        self.cls_out_channels = num_classes\n        self.in_channels = in_channels\n        self.feat_channels = feat_channels\n        self.stacked_convs = stacked_convs\n        self.strides = strides\n        self.dcn_on_last_conv = dcn_on_last_conv\n        assert conv_bias == 'auto' or isinstance(conv_bias, bool)\n        self.conv_bias = conv_bias\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bbox = build_loss(loss_bbox)\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n        self.conv_cfg = conv_cfg\n        self.norm_cfg = norm_cfg\n        self.fp16_enabled = False\n\n        self._init_layers()\n\n    def _init_layers(self):\n        \"\"\"Initialize layers of the head.\"\"\"\n        self._init_cls_convs()\n        self._init_reg_convs()\n        self._init_predictor()\n\n    def _init_cls_convs(self):\n        \"\"\"Initialize classification conv layers of the head.\"\"\"\n        self.cls_convs = nn.ModuleList()\n        for i in range(self.stacked_convs):\n            chn = self.in_channels if i == 0 else self.feat_channels\n            if self.dcn_on_last_conv and i == self.stacked_convs - 1:\n                conv_cfg = dict(type='DCNv2')\n            else:\n                conv_cfg = self.conv_cfg\n            self.cls_convs.append(\n                ConvModule(\n                    chn,\n                    self.feat_channels,\n                    3,\n                    stride=1,\n                    padding=1,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=self.norm_cfg,\n                    bias=self.conv_bias))\n\n    def _init_reg_convs(self):\n        \"\"\"Initialize bbox regression conv layers of the head.\"\"\"\n        self.reg_convs = nn.ModuleList()\n        for i in range(self.stacked_convs):\n            chn = self.in_channels if i == 0 else self.feat_channels\n            if self.dcn_on_last_conv and i == self.stacked_convs - 1:\n                conv_cfg = dict(type='DCNv2')\n            else:\n                conv_cfg = self.conv_cfg\n            self.reg_convs.append(\n                ConvModule(\n                    chn,\n                    self.feat_channels,\n                    3,\n                    stride=1,\n                    padding=1,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=self.norm_cfg,\n                    bias=self.conv_bias))\n\n    def _init_predictor(self):\n        \"\"\"Initialize predictor layers of the head.\"\"\"\n        self.conv_cls = nn.Conv2d(\n            self.feat_channels, self.cls_out_channels, 3, padding=1)\n        self.conv_reg = nn.Conv2d(self.feat_channels, 4, 3, padding=1)\n\n    def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,\n                              missing_keys, unexpected_keys, error_msgs):\n        \"\"\"Hack some keys of the model state dict so that can load checkpoints\n        of previous version.\"\"\"\n        version = local_metadata.get('version', None)\n        if version is None:\n            # the key is different in early versions\n            # for example, 'fcos_cls' become 'conv_cls' now\n            bbox_head_keys = [\n                k for k in state_dict.keys() if k.startswith(prefix)\n            ]\n            ori_predictor_keys = []\n            new_predictor_keys = []\n            # e.g. 'fcos_cls' or 'fcos_reg'\n            for key in bbox_head_keys:\n                ori_predictor_keys.append(key)\n                key = key.split('.')\n                conv_name = None\n                if key[1].endswith('cls'):\n                    conv_name = 'conv_cls'\n                elif key[1].endswith('reg'):\n                    conv_name = 'conv_reg'\n                elif key[1].endswith('centerness'):\n                    conv_name = 'conv_centerness'\n                else:\n                    assert NotImplementedError\n                if conv_name is not None:\n                    key[1] = conv_name\n                    new_predictor_keys.append('.'.join(key))\n                else:\n                    ori_predictor_keys.pop(-1)\n            for i in range(len(new_predictor_keys)):\n                state_dict[new_predictor_keys[i]] = state_dict.pop(\n                    ori_predictor_keys[i])\n        super()._load_from_state_dict(state_dict, prefix, local_metadata,\n                                      strict, missing_keys, unexpected_keys,\n                                      error_msgs)\n\n    def forward(self, feats):\n        \"\"\"Forward features from the upstream network.\n\n        Args:\n            feats (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n\n        Returns:\n            tuple: Usually contain classification scores and bbox predictions.\n                cls_scores (list[Tensor]): Box scores for each scale level,\n                    each is a 4D-tensor, the channel number is\n                    num_points * num_classes.\n                bbox_preds (list[Tensor]): Box energies / deltas for each scale\n                    level, each is a 4D-tensor, the channel number is\n                    num_points * 4.\n        \"\"\"\n        return multi_apply(self.forward_single, feats)[:2]\n\n    def forward_single(self, x):\n        \"\"\"Forward features of a single scale level.\n\n        Args:\n            x (Tensor): FPN feature maps of the specified stride.\n\n        Returns:\n            tuple: Scores for each class, bbox predictions, features\n                after classification and regression conv layers, some\n                models needs these features like FCOS.\n        \"\"\"\n        cls_feat = x\n        reg_feat = x\n\n        for cls_layer in self.cls_convs:\n            cls_feat = cls_layer(cls_feat)\n        cls_score = self.conv_cls(cls_feat)\n\n        for reg_layer in self.reg_convs:\n            reg_feat = reg_layer(reg_feat)\n        bbox_pred = self.conv_reg(reg_feat)\n        return cls_score, bbox_pred, cls_feat, reg_feat\n\n    @abstractmethod\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds'))\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             gt_bboxes,\n             gt_labels,\n             img_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"Compute loss of the head.\n\n        Args:\n            cls_scores (list[Tensor]): Box scores for each scale level,\n                each is a 4D-tensor, the channel number is\n                num_points * num_classes.\n            bbox_preds (list[Tensor]): Box energies / deltas for each scale\n                level, each is a 4D-tensor, the channel number is\n                num_points * 4.\n            gt_bboxes (list[Tensor]): Ground truth bboxes for each image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (list[Tensor]): class indices corresponding to each box\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            gt_bboxes_ignore (None | list[Tensor]): specify which bounding\n                boxes can be ignored when computing the loss.\n        \"\"\"\n\n        raise NotImplementedError\n\n    @abstractmethod\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds'))\n    def get_bboxes(self,\n                   cls_scores,\n                   bbox_preds,\n                   img_metas,\n                   cfg=None,\n                   rescale=None):\n        \"\"\"Transform network output for a batch into bbox predictions.\n\n        Args:\n            cls_scores (list[Tensor]): Box scores for each scale level\n                Has shape (N, num_points * num_classes, H, W)\n            bbox_preds (list[Tensor]): Box energies / deltas for each scale\n                level with shape (N, num_points * 4, H, W)\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            cfg (mmcv.Config): Test / postprocessing configuration,\n                if None, test_cfg would be used\n            rescale (bool): If True, return boxes in original image space\n        \"\"\"\n\n        raise NotImplementedError\n\n    @abstractmethod\n    def get_targets(self, points, gt_bboxes_list, gt_labels_list):\n        \"\"\"Compute regression, classification and centerness targets for points\n        in multiple images.\n\n        Args:\n            points (list[Tensor]): Points of each fpn level, each has shape\n                (num_points, 2).\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes of each image,\n                each has shape (num_gt, 4).\n            gt_labels_list (list[Tensor]): Ground truth labels of each box,\n                each has shape (num_gt,).\n        \"\"\"\n        raise NotImplementedError\n\n    def _get_points_single(self,\n                           featmap_size,\n                           stride,\n                           dtype,\n                           device,\n                           flatten=False):\n        \"\"\"Get points of a single scale level.\"\"\"\n        h, w = featmap_size\n        # First create Range with the default dtype, than convert to\n        # target `dtype` for onnx exporting.\n        x_range = torch.arange(w, device=device).to(dtype)\n        y_range = torch.arange(h, device=device).to(dtype)\n        y, x = torch.meshgrid(y_range, x_range)\n        if flatten:\n            y = y.flatten()\n            x = x.flatten()\n        return y, x\n\n    def get_points(self, featmap_sizes, dtype, device, flatten=False):\n        \"\"\"Get points according to feature map sizes.\n\n        Args:\n            featmap_sizes (list[tuple]): Multi-level feature map sizes.\n            dtype (torch.dtype): Type of points.\n            device (torch.device): Device of points.\n\n        Returns:\n            tuple: points of each image.\n        \"\"\"\n        mlvl_points = []\n        for i in range(len(featmap_sizes)):\n            mlvl_points.append(\n                self._get_points_single(featmap_sizes[i], self.strides[i],\n                                        dtype, device, flatten))\n        return mlvl_points\n\n    def aug_test(self, feats, img_metas, rescale=False):\n        \"\"\"Test function with test time augmentation.\n\n        Args:\n            feats (list[Tensor]): the outer list indicates test-time\n                augmentations and inner Tensor should have a shape NxCxHxW,\n                which contains features for all images in the batch.\n            img_metas (list[list[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch. each dict has image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[ndarray]: bbox results of each class\n        \"\"\"\n        return self.aug_test_bboxes(feats, img_metas, rescale=rescale)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/anchor_head.py",
    "content": "import torch\nimport torch.nn as nn\nfrom mmcv.utils import force_fp32\n\nfrom mmcv.core.anchor import (anchor_inside_flags, build_anchor_generator, images_to_levels)\nfrom mmcv.core.bbox.builder import (build_assigner, build_bbox_coder, build_sampler)\nfrom mmcv.core.utils import (multi_apply, unmap)\nfrom mmcv.core.post_processing.bbox_nms import (multiclass_nms)\nfrom ..builder import HEADS, build_loss\nfrom .base_dense_head import BaseDenseHead\nfrom .dense_test_mixins import BBoxTestMixin\n\n\n@HEADS.register_module()\nclass AnchorHead(BaseDenseHead, BBoxTestMixin):\n    \"\"\"Anchor-based head (RPN, RetinaNet, SSD, etc.).\n\n    Args:\n        num_classes (int): Number of categories excluding the background\n            category.\n        in_channels (int): Number of channels in the input feature map.\n        feat_channels (int): Number of hidden channels. Used in child classes.\n        anchor_generator (dict): Config dict for anchor generator\n        bbox_coder (dict): Config of bounding box coder.\n        reg_decoded_bbox (bool): If true, the regression loss would be\n            applied directly on decoded bounding boxes, converting both\n            the predicted boxes and regression targets to absolute\n            coordinates format. Default False. It should be `True` when\n            using `IoULoss`, `GIoULoss`, or `DIoULoss` in the bbox head.\n        loss_cls (dict): Config of classification loss.\n        loss_bbox (dict): Config of localization loss.\n        train_cfg (dict): Training config of anchor head.\n        test_cfg (dict): Testing config of anchor head.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n    \"\"\"  # noqa: W605\n\n    def __init__(self,\n                 num_classes,\n                 in_channels,\n                 feat_channels=256,\n                 anchor_generator=dict(\n                     type='AnchorGenerator',\n                     scales=[8, 16, 32],\n                     ratios=[0.5, 1.0, 2.0],\n                     strides=[4, 8, 16, 32, 64]),\n                 bbox_coder=dict(\n                     type='DeltaXYWHBBoxCoder',\n                     clip_border=True,\n                     target_means=(.0, .0, .0, .0),\n                     target_stds=(1.0, 1.0, 1.0, 1.0)),\n                 reg_decoded_bbox=False,\n                 loss_cls=dict(\n                     type='CrossEntropyLoss',\n                     use_sigmoid=True,\n                     loss_weight=1.0),\n                 loss_bbox=dict(\n                     type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),\n                 train_cfg=None,\n                 test_cfg=None,\n                 init_cfg=dict(type='Normal', layers='Conv2d', std=0.01)):\n        super(AnchorHead, self).__init__(init_cfg)\n        self.in_channels = in_channels\n        self.num_classes = num_classes\n        self.feat_channels = feat_channels\n        self.use_sigmoid_cls = loss_cls.get('use_sigmoid', False)\n        # TODO better way to determine whether sample or not\n        self.sampling = loss_cls['type'] not in [\n            'FocalLoss', 'GHMC', 'QualityFocalLoss'\n        ]\n        if self.use_sigmoid_cls:\n            self.cls_out_channels = num_classes\n        else:\n            self.cls_out_channels = num_classes + 1\n\n        if self.cls_out_channels <= 0:\n            raise ValueError(f'num_classes={num_classes} is too small')\n        self.reg_decoded_bbox = reg_decoded_bbox\n\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bbox = build_loss(loss_bbox)\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n        if self.train_cfg:\n            self.assigner = build_assigner(self.train_cfg.assigner)\n            # use PseudoSampler when sampling is False\n            if self.sampling and hasattr(self.train_cfg, 'sampler'):\n                sampler_cfg = self.train_cfg.sampler\n            else:\n                sampler_cfg = dict(type='PseudoSampler')\n            self.sampler = build_sampler(sampler_cfg, context=self)\n        self.fp16_enabled = False\n\n        self.anchor_generator = build_anchor_generator(anchor_generator)\n        # usually the numbers of anchors for each level are the same\n        # except SSD detectors\n        self.num_anchors = self.anchor_generator.num_base_anchors[0]\n        self._init_layers()\n\n    def _init_layers(self):\n        \"\"\"Initialize layers of the head.\"\"\"\n        self.conv_cls = nn.Conv2d(self.in_channels,\n                                  self.num_anchors * self.cls_out_channels, 1)\n        self.conv_reg = nn.Conv2d(self.in_channels, self.num_anchors * 4, 1)\n\n    def forward_single(self, x):\n        \"\"\"Forward feature of a single scale level.\n\n        Args:\n            x (Tensor): Features of a single scale level.\n\n        Returns:\n            tuple:\n                cls_score (Tensor): Cls scores for a single scale level \\\n                    the channels number is num_anchors * num_classes.\n                bbox_pred (Tensor): Box energies / deltas for a single scale \\\n                    level, the channels number is num_anchors * 4.\n        \"\"\"\n        cls_score = self.conv_cls(x)\n        bbox_pred = self.conv_reg(x)\n        return cls_score, bbox_pred\n\n    def forward(self, feats):\n        \"\"\"Forward features from the upstream network.\n\n        Args:\n            feats (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n\n        Returns:\n            tuple: A tuple of classification scores and bbox prediction.\n\n                - cls_scores (list[Tensor]): Classification scores for all \\\n                    scale levels, each is a 4D-tensor, the channels number \\\n                    is num_anchors * num_classes.\n                - bbox_preds (list[Tensor]): Box energies / deltas for all \\\n                    scale levels, each is a 4D-tensor, the channels number \\\n                    is num_anchors * 4.\n        \"\"\"\n        return multi_apply(self.forward_single, feats)\n\n    def get_anchors(self, featmap_sizes, img_metas, device='cuda'):\n        \"\"\"Get anchors according to feature map sizes.\n\n        Args:\n            featmap_sizes (list[tuple]): Multi-level feature map sizes.\n            img_metas (list[dict]): Image meta info.\n            device (torch.device | str): Device for returned tensors\n\n        Returns:\n            tuple:\n                anchor_list (list[Tensor]): Anchors of each image.\n                valid_flag_list (list[Tensor]): Valid flags of each image.\n        \"\"\"\n        num_imgs = len(img_metas)\n\n        # since feature map sizes of all images are the same, we only compute\n        # anchors for one time\n        multi_level_anchors = self.anchor_generator.grid_anchors(\n            featmap_sizes, device)\n        anchor_list = [multi_level_anchors for _ in range(num_imgs)]\n\n        # for each image, we compute valid flags of multi level anchors\n        valid_flag_list = []\n        for img_id, img_meta in enumerate(img_metas):\n            multi_level_flags = self.anchor_generator.valid_flags(\n                featmap_sizes, img_meta['pad_shape'], device)\n            valid_flag_list.append(multi_level_flags)\n\n        return anchor_list, valid_flag_list\n\n    def _get_targets_single(self,\n                            flat_anchors,\n                            valid_flags,\n                            gt_bboxes,\n                            gt_bboxes_ignore,\n                            gt_labels,\n                            img_meta,\n                            label_channels=1,\n                            unmap_outputs=True):\n        \"\"\"Compute regression and classification targets for anchors in a\n        single image.\n\n        Args:\n            flat_anchors (Tensor): Multi-level anchors of the image, which are\n                concatenated into a single tensor of shape (num_anchors ,4)\n            valid_flags (Tensor): Multi level valid flags of the image,\n                which are concatenated into a single tensor of\n                    shape (num_anchors,).\n            gt_bboxes (Tensor): Ground truth bboxes of the image,\n                shape (num_gts, 4).\n            gt_bboxes_ignore (Tensor): Ground truth bboxes to be\n                ignored, shape (num_ignored_gts, 4).\n            img_meta (dict): Meta info of the image.\n            gt_labels (Tensor): Ground truth labels of each box,\n                shape (num_gts,).\n            label_channels (int): Channel of label.\n            unmap_outputs (bool): Whether to map outputs back to the original\n                set of anchors.\n\n        Returns:\n            tuple:\n                labels_list (list[Tensor]): Labels of each level\n                label_weights_list (list[Tensor]): Label weights of each level\n                bbox_targets_list (list[Tensor]): BBox targets of each level\n                bbox_weights_list (list[Tensor]): BBox weights of each level\n                num_total_pos (int): Number of positive samples in all images\n                num_total_neg (int): Number of negative samples in all images\n        \"\"\"\n        inside_flags = anchor_inside_flags(flat_anchors, valid_flags,\n                                           img_meta['img_shape'][:2],\n                                           self.train_cfg.allowed_border)\n        if not inside_flags.any():\n            return (None, ) * 7\n        # assign gt and sample anchors\n        anchors = flat_anchors[inside_flags, :]\n\n        assign_result = self.assigner.assign(\n            anchors, gt_bboxes, gt_bboxes_ignore,\n            None if self.sampling else gt_labels)\n        sampling_result = self.sampler.sample(assign_result, anchors,\n                                              gt_bboxes)\n\n        num_valid_anchors = anchors.shape[0]\n        bbox_targets = torch.zeros_like(anchors)\n        bbox_weights = torch.zeros_like(anchors)\n        labels = anchors.new_full((num_valid_anchors, ),\n                                  self.num_classes,\n                                  dtype=torch.long)\n        label_weights = anchors.new_zeros(num_valid_anchors, dtype=torch.float)\n\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n        if len(pos_inds) > 0:\n            if not self.reg_decoded_bbox:\n                pos_bbox_targets = self.bbox_coder.encode(\n                    sampling_result.pos_bboxes, sampling_result.pos_gt_bboxes)\n            else:\n                pos_bbox_targets = sampling_result.pos_gt_bboxes\n            bbox_targets[pos_inds, :] = pos_bbox_targets\n            bbox_weights[pos_inds, :] = 1.0\n            if gt_labels is None:\n                # Only rpn gives gt_labels as None\n                # Foreground is the first class since v2.5.0\n                labels[pos_inds] = 0\n            else:\n                labels[pos_inds] = gt_labels[\n                    sampling_result.pos_assigned_gt_inds]\n            if self.train_cfg.pos_weight <= 0:\n                label_weights[pos_inds] = 1.0\n            else:\n                label_weights[pos_inds] = self.train_cfg.pos_weight\n        if len(neg_inds) > 0:\n            label_weights[neg_inds] = 1.0\n\n        # map up to original set of anchors\n        if unmap_outputs:\n            num_total_anchors = flat_anchors.size(0)\n            labels = unmap(\n                labels, num_total_anchors, inside_flags,\n                fill=self.num_classes)  # fill bg label\n            label_weights = unmap(label_weights, num_total_anchors,\n                                  inside_flags)\n            bbox_targets = unmap(bbox_targets, num_total_anchors, inside_flags)\n            bbox_weights = unmap(bbox_weights, num_total_anchors, inside_flags)\n\n        return (labels, label_weights, bbox_targets, bbox_weights, pos_inds,\n                neg_inds, sampling_result)\n\n    def get_targets(self,\n                    anchor_list,\n                    valid_flag_list,\n                    gt_bboxes_list,\n                    img_metas,\n                    gt_bboxes_ignore_list=None,\n                    gt_labels_list=None,\n                    label_channels=1,\n                    unmap_outputs=True,\n                    return_sampling_results=False):\n        \"\"\"Compute regression and classification targets for anchors in\n        multiple images.\n\n        Args:\n            anchor_list (list[list[Tensor]]): Multi level anchors of each\n                image. The outer list indicates images, and the inner list\n                corresponds to feature levels of the image. Each element of\n                the inner list is a tensor of shape (num_anchors, 4).\n            valid_flag_list (list[list[Tensor]]): Multi level valid flags of\n                each image. The outer list indicates images, and the inner list\n                corresponds to feature levels of the image. Each element of\n                the inner list is a tensor of shape (num_anchors, )\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes of each image.\n            img_metas (list[dict]): Meta info of each image.\n            gt_bboxes_ignore_list (list[Tensor]): Ground truth bboxes to be\n                ignored.\n            gt_labels_list (list[Tensor]): Ground truth labels of each box.\n            label_channels (int): Channel of label.\n            unmap_outputs (bool): Whether to map outputs back to the original\n                set of anchors.\n\n        Returns:\n            tuple: Usually returns a tuple containing learning targets.\n\n                - labels_list (list[Tensor]): Labels of each level.\n                - label_weights_list (list[Tensor]): Label weights of each \\\n                    level.\n                - bbox_targets_list (list[Tensor]): BBox targets of each level.\n                - bbox_weights_list (list[Tensor]): BBox weights of each level.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n            additional_returns: This function enables user-defined returns from\n                `self._get_targets_single`. These returns are currently refined\n                to properties at each feature map (i.e. having HxW dimension).\n                The results will be concatenated after the end\n        \"\"\"\n        num_imgs = len(img_metas)\n        assert len(anchor_list) == len(valid_flag_list) == num_imgs\n\n        # anchor number of multi levels\n        num_level_anchors = [anchors.size(0) for anchors in anchor_list[0]]\n        # concat all level anchors to a single tensor\n        concat_anchor_list = []\n        concat_valid_flag_list = []\n        for i in range(num_imgs):\n            assert len(anchor_list[i]) == len(valid_flag_list[i])\n            concat_anchor_list.append(torch.cat(anchor_list[i]))\n            concat_valid_flag_list.append(torch.cat(valid_flag_list[i]))\n\n        # compute targets for each image\n        if gt_bboxes_ignore_list is None:\n            gt_bboxes_ignore_list = [None for _ in range(num_imgs)]\n        if gt_labels_list is None:\n            gt_labels_list = [None for _ in range(num_imgs)]\n        results = multi_apply(\n            self._get_targets_single,\n            concat_anchor_list,\n            concat_valid_flag_list,\n            gt_bboxes_list,\n            gt_bboxes_ignore_list,\n            gt_labels_list,\n            img_metas,\n            label_channels=label_channels,\n            unmap_outputs=unmap_outputs)\n        (all_labels, all_label_weights, all_bbox_targets, all_bbox_weights,\n         pos_inds_list, neg_inds_list, sampling_results_list) = results[:7]\n        rest_results = list(results[7:])  # user-added return values\n        # no valid anchors\n        if any([labels is None for labels in all_labels]):\n            return None\n        # sampled anchors of all images\n        num_total_pos = sum([max(inds.numel(), 1) for inds in pos_inds_list])\n        num_total_neg = sum([max(inds.numel(), 1) for inds in neg_inds_list])\n        # split targets to a list w.r.t. multiple levels\n        labels_list = images_to_levels(all_labels, num_level_anchors)\n        label_weights_list = images_to_levels(all_label_weights,\n                                              num_level_anchors)\n        bbox_targets_list = images_to_levels(all_bbox_targets,\n                                             num_level_anchors)\n        bbox_weights_list = images_to_levels(all_bbox_weights,\n                                             num_level_anchors)\n        res = (labels_list, label_weights_list, bbox_targets_list,\n               bbox_weights_list, num_total_pos, num_total_neg)\n        if return_sampling_results:\n            res = res + (sampling_results_list, )\n        for i, r in enumerate(rest_results):  # user-added return values\n            rest_results[i] = images_to_levels(r, num_level_anchors)\n\n        return res + tuple(rest_results)\n\n    def loss_single(self, cls_score, bbox_pred, anchors, labels, label_weights,\n                    bbox_targets, bbox_weights, num_total_samples):\n        \"\"\"Compute loss of a single scale level.\n\n        Args:\n            cls_score (Tensor): Box scores for each scale level\n                Has shape (N, num_anchors * num_classes, H, W).\n            bbox_pred (Tensor): Box energies / deltas for each scale\n                level with shape (N, num_anchors * 4, H, W).\n            anchors (Tensor): Box reference for each scale level with shape\n                (N, num_total_anchors, 4).\n            labels (Tensor): Labels of each anchors with shape\n                (N, num_total_anchors).\n            label_weights (Tensor): Label weights of each anchor with shape\n                (N, num_total_anchors)\n            bbox_targets (Tensor): BBox regression targets of each anchor wight\n                shape (N, num_total_anchors, 4).\n            bbox_weights (Tensor): BBox regression loss weights of each anchor\n                with shape (N, num_total_anchors, 4).\n            num_total_samples (int): If sampling, num total samples equal to\n                the number of total anchors; Otherwise, it is the number of\n                positive anchors.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        # classification loss\n        labels = labels.reshape(-1)\n        label_weights = label_weights.reshape(-1)\n        cls_score = cls_score.permute(0, 2, 3,\n                                      1).reshape(-1, self.cls_out_channels)\n        loss_cls = self.loss_cls(\n            cls_score, labels, label_weights, avg_factor=num_total_samples)\n        # regression loss\n        bbox_targets = bbox_targets.reshape(-1, 4)\n        bbox_weights = bbox_weights.reshape(-1, 4)\n        bbox_pred = bbox_pred.permute(0, 2, 3, 1).reshape(-1, 4)\n        if self.reg_decoded_bbox:\n            # When the regression loss (e.g. `IouLoss`, `GIouLoss`)\n            # is applied directly on the decoded bounding boxes, it\n            # decodes the already encoded coordinates to absolute format.\n            anchors = anchors.reshape(-1, 4)\n            bbox_pred = self.bbox_coder.decode(anchors, bbox_pred)\n        loss_bbox = self.loss_bbox(\n            bbox_pred,\n            bbox_targets,\n            bbox_weights,\n            avg_factor=num_total_samples)\n        return loss_cls, loss_bbox\n\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds'))\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             gt_bboxes,\n             gt_labels,\n             img_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"Compute losses of the head.\n\n        Args:\n            cls_scores (list[Tensor]): Box scores for each scale level\n                Has shape (N, num_anchors * num_classes, H, W)\n            bbox_preds (list[Tensor]): Box energies / deltas for each scale\n                level with shape (N, num_anchors * 4, H, W)\n            gt_bboxes (list[Tensor]): Ground truth bboxes for each image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (list[Tensor]): class indices corresponding to each box\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            gt_bboxes_ignore (None | list[Tensor]): specify which bounding\n                boxes can be ignored when computing the loss. Default: None\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        featmap_sizes = [featmap.size()[-2:] for featmap in cls_scores]\n        assert len(featmap_sizes) == self.anchor_generator.num_levels\n\n        device = cls_scores[0].device\n\n        anchor_list, valid_flag_list = self.get_anchors(\n            featmap_sizes, img_metas, device=device)\n        label_channels = self.cls_out_channels if self.use_sigmoid_cls else 1\n        cls_reg_targets = self.get_targets(\n            anchor_list,\n            valid_flag_list,\n            gt_bboxes,\n            img_metas,\n            gt_bboxes_ignore_list=gt_bboxes_ignore,\n            gt_labels_list=gt_labels,\n            label_channels=label_channels)\n        if cls_reg_targets is None:\n            return None\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n        num_total_samples = (\n            num_total_pos + num_total_neg if self.sampling else num_total_pos)\n\n        # anchor number of multi levels\n        num_level_anchors = [anchors.size(0) for anchors in anchor_list[0]]\n        # concat all level anchors and flags to a single tensor\n        concat_anchor_list = []\n        for i in range(len(anchor_list)):\n            concat_anchor_list.append(torch.cat(anchor_list[i]))\n        all_anchor_list = images_to_levels(concat_anchor_list,\n                                           num_level_anchors)\n\n        losses_cls, losses_bbox = multi_apply(\n            self.loss_single,\n            cls_scores,\n            bbox_preds,\n            all_anchor_list,\n            labels_list,\n            label_weights_list,\n            bbox_targets_list,\n            bbox_weights_list,\n            num_total_samples=num_total_samples)\n        return dict(loss_cls=losses_cls, loss_bbox=losses_bbox)\n\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds'))\n    def get_bboxes(self,\n                   cls_scores,\n                   bbox_preds,\n                   img_metas,\n                   cfg=None,\n                   rescale=False,\n                   with_nms=True):\n        \"\"\"Transform network output for a batch into bbox predictions.\n\n        Args:\n            cls_scores (list[Tensor]): Box scores for each level in the\n                feature pyramid, has shape\n                (N, num_anchors * num_classes, H, W).\n            bbox_preds (list[Tensor]): Box energies / deltas for each\n                level in the feature pyramid, has shape\n                (N, num_anchors * 4, H, W).\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            cfg (mmcv.Config | None): Test / postprocessing configuration,\n                if None, test_cfg would be used\n            rescale (bool): If True, return boxes in original image space.\n                Default: False.\n            with_nms (bool): If True, do nms before return boxes.\n                Default: True.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is an (n, 5) tensor, where 5 represent\n                (tl_x, tl_y, br_x, br_y, score) and the score between 0 and 1.\n                The shape of the second tensor in the tuple is (n,), and\n                each element represents the class label of the corresponding\n                box.\n\n        Example:\n            >>> import mmcv\n            >>> self = AnchorHead(\n            >>>     num_classes=9,\n            >>>     in_channels=1,\n            >>>     anchor_generator=dict(\n            >>>         type='AnchorGenerator',\n            >>>         scales=[8],\n            >>>         ratios=[0.5, 1.0, 2.0],\n            >>>         strides=[4,]))\n            >>> img_metas = [{'img_shape': (32, 32, 3), 'scale_factor': 1}]\n            >>> cfg = mmcv.Config(dict(\n            >>>     score_thr=0.00,\n            >>>     nms=dict(type='nms', iou_thr=1.0),\n            >>>     max_per_img=10))\n            >>> feat = torch.rand(1, 1, 3, 3)\n            >>> cls_score, bbox_pred = self.forward_single(feat)\n            >>> # note the input lists are over different levels, not images\n            >>> cls_scores, bbox_preds = [cls_score], [bbox_pred]\n            >>> result_list = self.get_bboxes(cls_scores, bbox_preds,\n            >>>                               img_metas, cfg)\n            >>> det_bboxes, det_labels = result_list[0]\n            >>> assert len(result_list) == 1\n            >>> assert det_bboxes.shape[1] == 5\n            >>> assert len(det_bboxes) == len(det_labels) == cfg.max_per_img\n        \"\"\"\n        assert len(cls_scores) == len(bbox_preds)\n        num_levels = len(cls_scores)\n\n        device = cls_scores[0].device\n        featmap_sizes = [cls_scores[i].shape[-2:] for i in range(num_levels)]\n        mlvl_anchors = self.anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n\n        mlvl_cls_scores = [cls_scores[i].detach() for i in range(num_levels)]\n        mlvl_bbox_preds = [bbox_preds[i].detach() for i in range(num_levels)]\n\n        if torch.onnx.is_in_onnx_export():\n            assert len(\n                img_metas\n            ) == 1, 'Only support one input image while in exporting to ONNX'\n            img_shapes = img_metas[0]['img_shape_for_onnx']\n        else:\n            img_shapes = [\n                img_metas[i]['img_shape']\n                for i in range(cls_scores[0].shape[0])\n            ]\n        scale_factors = [\n            img_metas[i]['scale_factor'] for i in range(cls_scores[0].shape[0])\n        ]\n\n        if with_nms:\n            # some heads don't support with_nms argument\n            result_list = self._get_bboxes(mlvl_cls_scores, mlvl_bbox_preds,\n                                           mlvl_anchors, img_shapes,\n                                           scale_factors, cfg, rescale)\n        else:\n            result_list = self._get_bboxes(mlvl_cls_scores, mlvl_bbox_preds,\n                                           mlvl_anchors, img_shapes,\n                                           scale_factors, cfg, rescale,\n                                           with_nms)\n        return result_list\n\n    def _get_bboxes(self,\n                    mlvl_cls_scores,\n                    mlvl_bbox_preds,\n                    mlvl_anchors,\n                    img_shapes,\n                    scale_factors,\n                    cfg,\n                    rescale=False,\n                    with_nms=True):\n        \"\"\"Transform outputs for a batch item into bbox predictions.\n\n        Args:\n            mlvl_cls_scores (list[Tensor]): Each element in the list is\n                the scores of bboxes of single level in the feature pyramid,\n                has shape (N, num_anchors * num_classes, H, W).\n            mlvl_bbox_preds (list[Tensor]):  Each element in the list is the\n                bboxes predictions of single level in the feature pyramid,\n                has shape (N, num_anchors * 4, H, W).\n            mlvl_anchors (list[Tensor]): Each element in the list is\n                the anchors of single level in feature pyramid, has shape\n                (num_anchors, 4).\n            img_shapes (list[tuple[int]]): Each tuple in the list represent\n                the shape(height, width, 3) of single image in the batch.\n            scale_factors (list[ndarray]): Scale factor of the batch\n                image arange as list[(w_scale, h_scale, w_scale, h_scale)].\n            cfg (mmcv.Config): Test / postprocessing configuration,\n                if None, test_cfg would be used.\n            rescale (bool): If True, return boxes in original image space.\n                Default: False.\n            with_nms (bool): If True, do nms before return boxes.\n                Default: True.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is an (n, 5) tensor, where 5 represent\n                (tl_x, tl_y, br_x, br_y, score) and the score between 0 and 1.\n                The shape of the second tensor in the tuple is (n,), and\n                each element represents the class label of the corresponding\n                box.\n        \"\"\"\n        cfg = self.test_cfg if cfg is None else cfg\n        assert len(mlvl_cls_scores) == len(mlvl_bbox_preds) == len(\n            mlvl_anchors)\n        batch_size = mlvl_cls_scores[0].shape[0]\n        # convert to tensor to keep tracing\n        nms_pre_tensor = torch.tensor(\n            cfg.get('nms_pre', -1),\n            device=mlvl_cls_scores[0].device,\n            dtype=torch.long)\n\n        mlvl_bboxes = []\n        mlvl_scores = []\n        for cls_score, bbox_pred, anchors in zip(mlvl_cls_scores,\n                                                 mlvl_bbox_preds,\n                                                 mlvl_anchors):\n            assert cls_score.size()[-2:] == bbox_pred.size()[-2:]\n            cls_score = cls_score.permute(0, 2, 3,\n                                          1).reshape(batch_size, -1,\n                                                     self.cls_out_channels)\n            if self.use_sigmoid_cls:\n                scores = cls_score.sigmoid()\n            else:\n                scores = cls_score.softmax(-1)\n            bbox_pred = bbox_pred.permute(0, 2, 3,\n                                          1).reshape(batch_size, -1, 4)\n            anchors = anchors.expand_as(bbox_pred)\n            # Always keep topk op for dynamic input in onnx\n            from mmcv.core.export import get_k_for_topk\n            nms_pre = get_k_for_topk(nms_pre_tensor, bbox_pred.shape[1])\n            if nms_pre > 0:\n                # Get maximum scores for foreground classes.\n                if self.use_sigmoid_cls:\n                    max_scores, _ = scores.max(-1)\n                else:\n                    # remind that we set FG labels to [0, num_class-1]\n                    # since mmcv v2.0\n                    # BG cat_id: num_class\n                    max_scores, _ = scores[..., :-1].max(-1)\n\n                _, topk_inds = max_scores.topk(nms_pre)\n                batch_inds = torch.arange(batch_size).view(\n                    -1, 1).expand_as(topk_inds)\n                anchors = anchors[batch_inds, topk_inds, :]\n                bbox_pred = bbox_pred[batch_inds, topk_inds, :]\n                scores = scores[batch_inds, topk_inds, :]\n\n            bboxes = self.bbox_coder.decode(\n                anchors, bbox_pred, max_shape=img_shapes)\n            mlvl_bboxes.append(bboxes)\n            mlvl_scores.append(scores)\n\n        batch_mlvl_bboxes = torch.cat(mlvl_bboxes, dim=1)\n        if rescale:\n            batch_mlvl_bboxes /= batch_mlvl_bboxes.new_tensor(\n                scale_factors).unsqueeze(1)\n        batch_mlvl_scores = torch.cat(mlvl_scores, dim=1)\n\n        # Replace multiclass_nms with ONNX::NonMaxSuppression in deployment\n        if torch.onnx.is_in_onnx_export() and with_nms:\n            from mmcv.core.export import add_dummy_nms_for_onnx\n            # ignore background class\n            if not self.use_sigmoid_cls:\n                num_classes = batch_mlvl_scores.shape[2] - 1\n                batch_mlvl_scores = batch_mlvl_scores[..., :num_classes]\n            max_output_boxes_per_class = cfg.nms.get(\n                'max_output_boxes_per_class', 200)\n            iou_threshold = cfg.nms.get('iou_threshold', 0.5)\n            score_threshold = cfg.score_thr\n            nms_pre = cfg.get('deploy_nms_pre', -1)\n            return add_dummy_nms_for_onnx(batch_mlvl_bboxes, batch_mlvl_scores,\n                                          max_output_boxes_per_class,\n                                          iou_threshold, score_threshold,\n                                          nms_pre, cfg.max_per_img)\n        if self.use_sigmoid_cls:\n            # Add a dummy background class to the backend when using sigmoid\n            # remind that we set FG labels to [0, num_class-1] since mmcv v2.0\n            # BG cat_id: num_class\n            padding = batch_mlvl_scores.new_zeros(batch_size,\n                                                  batch_mlvl_scores.shape[1],\n                                                  1)\n            batch_mlvl_scores = torch.cat([batch_mlvl_scores, padding], dim=-1)\n\n        if with_nms:\n            det_results = []\n            for (mlvl_bboxes, mlvl_scores) in zip(batch_mlvl_bboxes,\n                                                  batch_mlvl_scores):\n                det_bbox, det_label = multiclass_nms(mlvl_bboxes, mlvl_scores,\n                                                     cfg.score_thr, cfg.nms,\n                                                     cfg.max_per_img)\n                det_results.append(tuple([det_bbox, det_label]))\n        else:\n            det_results = [\n                tuple(mlvl_bs)\n                for mlvl_bs in zip(batch_mlvl_bboxes, batch_mlvl_scores)\n            ]\n        return det_results\n\n    def aug_test(self, feats, img_metas, rescale=False):\n        \"\"\"Test function with test time augmentation.\n\n        Args:\n            feats (list[Tensor]): the outer list indicates test-time\n                augmentations and inner Tensor should have a shape NxCxHxW,\n                which contains features for all images in the batch.\n            img_metas (list[list[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch. each dict has image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is ``bboxes`` with shape (n, 5), where\n                5 represent (tl_x, tl_y, br_x, br_y, score).\n                The shape of the second tensor in the tuple is ``labels``\n                with shape (n,), The length of list should always be 1.\n        \"\"\"\n        return self.aug_test_bboxes(feats, img_metas, rescale=rescale)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/base_dense_head.py",
    "content": "from abc import ABCMeta, abstractmethod\n\nfrom mmcv.models.backbones import BaseModule\n\n\nclass BaseDenseHead(BaseModule, metaclass=ABCMeta):\n    \"\"\"Base class for DenseHeads.\"\"\"\n\n    def __init__(self, init_cfg=None):\n        super(BaseDenseHead, self).__init__(init_cfg)\n\n    @abstractmethod\n    def loss(self, **kwargs):\n        \"\"\"Compute losses of the head.\"\"\"\n        pass\n\n    @abstractmethod\n    def get_bboxes(self, **kwargs):\n        \"\"\"Transform network output for a batch into bbox predictions.\"\"\"\n        pass\n\n    def forward_train(self,\n                      x,\n                      img_metas,\n                      gt_bboxes,\n                      gt_labels=None,\n                      gt_bboxes_ignore=None,\n                      proposal_cfg=None,\n                      **kwargs):\n        \"\"\"\n        Args:\n            x (list[Tensor]): Features from FPN.\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            gt_bboxes (Tensor): Ground truth bboxes of the image,\n                shape (num_gts, 4).\n            gt_labels (Tensor): Ground truth labels of each box,\n                shape (num_gts,).\n            gt_bboxes_ignore (Tensor): Ground truth bboxes to be\n                ignored, shape (num_ignored_gts, 4).\n            proposal_cfg (mmcv.Config): Test / postprocessing configuration,\n                if None, test_cfg would be used\n\n        Returns:\n            tuple:\n                losses: (dict[str, Tensor]): A dictionary of loss components.\n                proposal_list (list[Tensor]): Proposals of each image.\n        \"\"\"\n        outs = self(x)\n        if gt_labels is None:\n            loss_inputs = outs + (gt_bboxes, img_metas)\n        else:\n            loss_inputs = outs + (gt_bboxes, gt_labels, img_metas)\n        losses = self.loss(*loss_inputs, gt_bboxes_ignore=gt_bboxes_ignore)\n        if proposal_cfg is None:\n            return losses\n        else:\n            proposal_list = self.get_bboxes(*outs, img_metas, cfg=proposal_cfg)\n            return losses, proposal_list\n\n    def simple_test(self, feats, img_metas, rescale=False):\n        \"\"\"Test function without test-time augmentation.\n\n        Args:\n            feats (tuple[torch.Tensor]): Multi-level features from the\n                upstream network, each is a 4D-tensor.\n            img_metas (list[dict]): List of image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is ``bboxes`` with shape (n, 5),\n                where 5 represent (tl_x, tl_y, br_x, br_y, score).\n                The shape of the second tensor in the tuple is ``labels``\n                with shape (n,)\n        \"\"\"\n        return self.simple_test_bboxes(feats, img_metas, rescale=rescale)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/bev_head.py",
    "content": "import copy\nfrom re import I\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models import Linear, bias_init_with_prob\nfrom mmcv.utils import TORCH_VERSION, digit_version\n\nfrom mmcv.core import (multi_apply, multi_apply, reduce_mean)\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.models import HEADS, BaseModule\nfrom mmcv.models.dense_heads import DETRHead\nfrom mmcv.core.bbox.coder import build_bbox_coder\nfrom traitlets import import_item\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.models.bricks import build_positional_encoding\nfrom mmcv.utils import force_fp32\nimport numpy as np\nimport cv2 as cv\nfrom mmcv.models.modules.transformerV2 import PerceptionTransformerBEVEncoder\nfrom mmcv.models.utils import build_transformer\nfrom mmcv.models.builder import build_head\nfrom mmcv.models.dense_heads.free_anchor3d_head import FreeAnchor3DHead\n\n@HEADS.register_module()\nclass BEVHead(BaseModule):\n    def __init__(self, \n                 bev_h,\n                 bev_w,\n                 pc_range,\n                 embed_dims,\n                 transformer, \n                 positional_encoding: dict,\n                 pts_bbox_head_3d: dict, \n                 init_cfg=None,\n                 **kwargs,\n                 ):\n        super(BEVHead, self).__init__(init_cfg=init_cfg)\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.embed_dims = embed_dims\n        self.pc_range = pc_range\n        self.fp16_enabled = False\n        self.transformer :PerceptionTransformerBEVEncoder = build_transformer(transformer)\n        self.positional_encoding = build_positional_encoding(positional_encoding)\n\n        pts_bbox_head_3d.update(kwargs)\n        self.pts_bbox_head_3d = build_head(pts_bbox_head_3d)\n        self.real_w = self.pc_range[3] - self.pc_range[0]\n        self.real_h = self.pc_range[4] - self.pc_range[1]\n        \n        self._init_layers()\n    def init_weights(self):\n        \"\"\"Initialize weights of the Multi View BEV Encoder\"\"\"\n        self.transformer.init_weights()\n\n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        \n        self.bev_embedding = nn.Embedding(self.bev_h * self.bev_w, self.embed_dims)\n\n    @force_fp32(apply_to=('mlvl_feats', 'pred_bev'))\n    def forward(self, mlvl_feats, img_metas, prev_bev=None,  only_bev=False):\n        bs, num_cam, _, _, _ = mlvl_feats[0].shape\n        dtype = mlvl_feats[0].dtype\n        bev_queries = self.bev_embedding.weight.to(dtype)\n\n        bev_mask = torch.zeros((bs, self.bev_h, self.bev_w),\n                               device=bev_queries.device).to(dtype)\n        bev_pos = self.positional_encoding(bev_mask).to(dtype)\n\n        bev_embed = self.transformer(\n                mlvl_feats,\n                bev_queries,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                img_metas=img_metas,\n                prev_bev=prev_bev,\n            )\n\n        if only_bev:\n            return bev_embed\n        \n        bev_feature = bev_embed.permute(0, 2, 1).reshape(bs, self.embed_dims, self.bev_h, self.bev_w)\n        ret = {}\n        ret['pred'] = self.pts_bbox_head_3d([bev_feature,])\n        if not self.training:\n            ret['bev_embed'] = bev_embed\n        return ret \n    \n\n    @force_fp32(apply_to=('ret'))\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             ret,\n             gt_bboxes_ignore=None,\n             img_metas=None):\n        assert gt_bboxes_ignore is None\n        return self.pts_bbox_head_3d.loss(gt_bboxes_list, gt_labels_list, ret['pred'], gt_bboxes_ignore=gt_bboxes_ignore, img_metas=img_metas)\n    \n    @force_fp32(apply_to=('ret'))\n    def get_bboxes(self, ret, img_metas, rescale=False):\n        return self.pts_bbox_head_3d.get_bboxes(ret['pred'], img_metas)\n\n@HEADS.register_module()\nclass FreeAnchor3DHeadV2(FreeAnchor3DHead):\n    @force_fp32(apply_to=('pred'))\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             pred,\n             gt_bboxes_ignore=None,\n             img_metas=None):\n            cls_scores, bbox_preds, dir_cls_preds = pred\n            \n            return super().loss(cls_scores, bbox_preds, dir_cls_preds, gt_bboxes_list, gt_labels_list, img_metas, gt_bboxes_ignore)\n    @force_fp32(apply_to=('pred'))\n    def get_bboxes(self, pred, img_metas, rescale=False):\n        cls_scores, bbox_preds, dir_cls_preds = pred\n        return super().get_bboxes(\n                   cls_scores,\n                   bbox_preds,\n                   dir_cls_preds,\n                   img_metas,\n                   cfg=None,\n                   rescale=rescale)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/bevformer_head.py",
    "content": "import copy\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.models.bricks import Linear\nfrom mmcv.models.utils.weight_init import bias_init_with_prob\n\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom mmcv.core.utils.misc import multi_apply\nfrom mmcv.core.utils.dist_utils import reduce_mean\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.models import HEADS\nfrom mmcv.models.dense_heads import DETRHead\nfrom mmcv.core.bbox.coder import build_bbox_coder\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.utils import force_fp32, auto_fp16\n\n\n@HEADS.register_module()\nclass BEVFormerHead(DETRHead):\n    \"\"\"Head of Detr3D.\n    Args:\n        with_box_refine (bool): Whether to refine the reference points\n            in the decoder. Defaults to False.\n        as_two_stage (bool) : Whether to generate the proposal from\n            the outputs of encoder.\n        transformer (obj:`ConfigDict`): ConfigDict is used for building\n            the Encoder and Decoder.\n        bev_h, bev_w (int): spatial shape of BEV queries.\n    \"\"\"\n\n    def __init__(self,\n                 *args,\n                 with_box_refine=False,\n                 as_two_stage=False,\n                 transformer=None,\n                 bbox_coder=None,\n                 num_cls_fcs=2,\n                 code_weights=None,\n                 bev_h=30,\n                 bev_w=30,\n                 **kwargs):\n\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.fp16_enabled = False\n\n        self.with_box_refine = with_box_refine\n        self.as_two_stage = as_two_stage\n        if self.as_two_stage:\n            transformer['as_two_stage'] = self.as_two_stage\n        if 'code_size' in kwargs:\n            self.code_size = kwargs['code_size']\n        else:\n            self.code_size = 10\n        if code_weights is not None:\n            self.code_weights = code_weights\n        else:\n            self.code_weights = [1.0, 1.0, 1.0,\n                                 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]\n\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n        self.pc_range = self.bbox_coder.pc_range\n        self.real_w = self.pc_range[3] - self.pc_range[0]\n        self.real_h = self.pc_range[4] - self.pc_range[1]\n        self.num_cls_fcs = num_cls_fcs - 1\n        super(BEVFormerHead, self).__init__(\n            *args, transformer=transformer, **kwargs)\n        self.code_weights = nn.Parameter(torch.tensor(\n            self.code_weights, requires_grad=False), requires_grad=False)\n\n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            cls_branch.append(Linear(self.embed_dims, self.embed_dims))\n            cls_branch.append(nn.LayerNorm(self.embed_dims))\n            cls_branch.append(nn.ReLU(inplace=True))\n        cls_branch.append(Linear(self.embed_dims, self.cls_out_channels))\n        fc_cls = nn.Sequential(*cls_branch)\n\n        reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            reg_branch.append(nn.ReLU())\n        reg_branch.append(Linear(self.embed_dims, self.code_size))\n        reg_branch = nn.Sequential(*reg_branch)\n\n        def _get_clones(module, N):\n            return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n        # last reg_branch is used to generate proposal from\n        # encode feature map when as_two_stage is True.\n        num_pred = (self.transformer.decoder.num_layers + 1) if \\\n            self.as_two_stage else self.transformer.decoder.num_layers\n\n        if self.with_box_refine:\n            self.cls_branches = _get_clones(fc_cls, num_pred)\n            self.reg_branches = _get_clones(reg_branch, num_pred)\n        else:\n            self.cls_branches = nn.ModuleList(\n                [fc_cls for _ in range(num_pred)])\n            self.reg_branches = nn.ModuleList(\n                [reg_branch for _ in range(num_pred)])\n\n        if not self.as_two_stage:\n            self.bev_embedding = nn.Embedding(\n                self.bev_h * self.bev_w, self.embed_dims)\n            self.query_embedding = nn.Embedding(self.num_query,\n                                                self.embed_dims * 2)\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the DeformDETR head.\"\"\"\n        self.transformer.init_weights()\n        if self.loss_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n\n    @auto_fp16(apply_to=('mlvl_feats'))\n    def forward(self, mlvl_feats, img_metas, prev_bev=None,  only_bev=False):\n        \"\"\"Forward function.\n        Args:\n            mlvl_feats (tuple[Tensor]): Features from the upstream\n                network, each is a 5D-tensor with shape\n                (B, N, C, H, W).\n            prev_bev: previous bev featues\n            only_bev: only compute BEV features with encoder. \n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, l, cz, h, theta, vx, vy). \\\n                Shape [nb_dec, bs, num_query, 9].\n        \"\"\"\n        bs, num_cam, _, _, _ = mlvl_feats[0].shape\n        dtype = mlvl_feats[0].dtype\n        object_query_embeds = self.query_embedding.weight.to(dtype)\n        bev_queries = self.bev_embedding.weight.to(dtype)\n\n        bev_mask = torch.zeros((bs, self.bev_h, self.bev_w),\n                               device=bev_queries.device).to(dtype)\n        bev_pos = self.positional_encoding(bev_mask).to(dtype)\n\n        if only_bev:  # only use encoder to obtain BEV features, TODO: refine the workaround\n            return self.transformer.get_bev_features(\n                mlvl_feats,\n                bev_queries,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                img_metas=img_metas,\n                prev_bev=prev_bev,\n            )\n        else:\n            outputs = self.transformer(\n                mlvl_feats,\n                bev_queries,\n                object_query_embeds,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                reg_branches=self.reg_branches if self.with_box_refine else None,  # noqa:E501\n                cls_branches=self.cls_branches if self.as_two_stage else None,\n                img_metas=img_metas,\n                prev_bev=prev_bev\n        )\n\n        bev_embed, hs, init_reference, inter_references = outputs\n        hs = hs.permute(0, 2, 1, 3)\n        outputs_classes = []\n        outputs_coords = []\n        for lvl in range(hs.shape[0]):\n            if lvl == 0:\n                reference = init_reference\n            else:\n                reference = inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            outputs_class = self.cls_branches[lvl](hs[lvl])\n            tmp = self.reg_branches[lvl](hs[lvl])\n\n            # TODO: check the shape of reference\n            assert reference.shape[-1] == 3\n            tmp[..., 0:2] += reference[..., 0:2]\n            tmp[..., 0:2] = tmp[..., 0:2].sigmoid()\n            tmp[..., 4:5] += reference[..., 2:3]\n            tmp[..., 4:5] = tmp[..., 4:5].sigmoid()\n            tmp[..., 0:1] = (tmp[..., 0:1] * (self.pc_range[3] -\n                             self.pc_range[0]) + self.pc_range[0])\n            tmp[..., 1:2] = (tmp[..., 1:2] * (self.pc_range[4] -\n                             self.pc_range[1]) + self.pc_range[1])\n            tmp[..., 4:5] = (tmp[..., 4:5] * (self.pc_range[5] -\n                             self.pc_range[2]) + self.pc_range[2])\n\n            # TODO: check if using sigmoid\n            outputs_coord = tmp\n            outputs_classes.append(outputs_class)\n            outputs_coords.append(outputs_coord)\n\n        outputs_classes = torch.stack(outputs_classes)\n        outputs_coords = torch.stack(outputs_coords)\n\n        outs = {\n            'bev_embed': bev_embed,\n            'all_cls_scores': outputs_classes,\n            'all_bbox_preds': outputs_coords,\n            'enc_cls_scores': None,\n            'enc_bbox_preds': None,\n        }\n\n        return outs\n\n    def _get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           gt_labels,\n                           gt_bboxes,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        gt_c = gt_bboxes.shape[-1]\n\n        assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,\n                                             gt_labels, gt_bboxes_ignore)\n\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes,),\n                                    self.num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)[..., :gt_c]\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n\n        # DETR\n        bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes\n        return (labels, label_weights, bbox_targets, bbox_weights,\n                pos_inds, neg_inds)\n\n    def get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            tuple: a tuple containing the following targets.\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, pos_inds_list, neg_inds_list) = multi_apply(\n            self._get_target_single, cls_scores_list, bbox_preds_list,\n            gt_labels_list, gt_bboxes_list, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, num_total_pos, num_total_neg)\n\n    def loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,\n                                           gt_bboxes_list, gt_labels_list,\n                                           gt_bboxes_ignore_list)\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_cls(\n            cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # regression L1 loss\n        bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))\n        normalized_bbox_targets = normalize_bbox(bbox_targets, self.pc_range)\n        isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)\n        bbox_weights = bbox_weights * self.code_weights\n\n        loss_bbox = self.loss_bbox(\n            bbox_preds[isnotnan, :10], normalized_bbox_targets[isnotnan,\n                                                               :10], bbox_weights[isnotnan, :10],\n            avg_factor=num_total_pos)\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            loss_cls = torch.nan_to_num(loss_cls)\n            loss_bbox = torch.nan_to_num(loss_bbox)\n        return loss_cls, loss_bbox\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             preds_dicts,\n             gt_bboxes_ignore=None,\n             img_metas=None):\n        \"\"\"\"Loss function.\n        Args:\n\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            preds_dicts:\n                all_cls_scores (Tensor): Classification score of all\n                    decoder layers, has shape\n                    [nb_dec, bs, num_query, cls_out_channels].\n                all_bbox_preds (Tensor): Sigmoid regression\n                    outputs of all decode layers. Each is a 4D-tensor with\n                    normalized coordinate format (cx, cy, w, h) and shape\n                    [nb_dec, bs, num_query, 4].\n                enc_cls_scores (Tensor): Classification scores of\n                    points on encode feature map , has shape\n                    (N, h*w, num_classes). Only be passed when as_two_stage is\n                    True, otherwise is None.\n                enc_bbox_preds (Tensor): Regression results of each points\n                    on the encode feature map, has shape (N, h*w, 4). Only be\n                    passed when as_two_stage is True, otherwise is None.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            f'{self.__class__.__name__} only supports ' \\\n            f'for gt_bboxes_ignore setting to None.'\n\n        all_cls_scores = preds_dicts['all_cls_scores']\n        all_bbox_preds = preds_dicts['all_bbox_preds']\n        enc_cls_scores = preds_dicts['enc_cls_scores']\n        enc_bbox_preds = preds_dicts['enc_bbox_preds']\n\n        num_dec_layers = len(all_cls_scores)\n        device = gt_labels_list[0].device\n\n        gt_bboxes_list = [torch.cat(\n            (gt_bboxes.gravity_center, gt_bboxes.tensor[:, 3:]),\n            dim=1).to(device) for gt_bboxes in gt_bboxes_list]\n\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        losses_cls, losses_bbox = multi_apply(\n            self.loss_single, all_cls_scores, all_bbox_preds,\n            all_gt_bboxes_list, all_gt_labels_list,\n            all_gt_bboxes_ignore_list)\n\n        loss_dict = dict()\n        # loss of proposal generated from encode feature map.\n        if enc_cls_scores is not None:\n            binary_labels_list = [\n                torch.zeros_like(gt_labels_list[i])\n                for i in range(len(all_gt_labels_list))\n            ]\n            enc_loss_cls, enc_losses_bbox = \\\n                self.loss_single(enc_cls_scores, enc_bbox_preds,\n                                 gt_bboxes_list, binary_labels_list, gt_bboxes_ignore)\n            loss_dict['enc_loss_cls'] = enc_loss_cls\n            loss_dict['enc_loss_bbox'] = enc_losses_bbox\n\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls[-1]\n        loss_dict['loss_bbox'] = losses_bbox[-1]\n\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_cls_i, loss_bbox_i in zip(losses_cls[:-1],\n                                           losses_bbox[:-1]):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i\n            num_dec_layer += 1\n        return loss_dict\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def get_bboxes(self, preds_dicts, img_metas, rescale=False):\n        \"\"\"Generate bboxes from bbox head predictions.\n        Args:\n            preds_dicts (tuple[list[dict]]): Prediction results.\n            img_metas (list[dict]): Point cloud and image's meta info.\n        Returns:\n            list[dict]: Decoded bbox, scores and labels after nms.\n        \"\"\"\n\n        preds_dicts = self.bbox_coder.decode(preds_dicts)\n\n        num_samples = len(preds_dicts)\n        ret_list = []\n        for i in range(num_samples):\n            preds = preds_dicts[i]\n            bboxes = preds['bboxes']\n\n            bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5\n\n            code_size = bboxes.shape[-1]\n            bboxes = img_metas[i]['box_type_3d'](bboxes, code_size)\n            scores = preds['scores']\n            labels = preds['labels']\n\n            ret_list.append([bboxes, scores, labels])\n\n        return ret_list\n\n\n@HEADS.register_module()\nclass BEVFormerHead_GroupDETR(BEVFormerHead):\n    def __init__(self,\n                 *args,\n                 group_detr=1,\n                 **kwargs):\n        self.group_detr = group_detr\n        assert 'num_query' in kwargs\n        kwargs['num_query'] = group_detr * kwargs['num_query']\n        super().__init__(*args, **kwargs)\n\n    def forward(self, mlvl_feats, img_metas, prev_bev=None,  only_bev=False):\n        bs, num_cam, _, _, _ = mlvl_feats[0].shape\n        dtype = mlvl_feats[0].dtype\n        object_query_embeds = self.query_embedding.weight.to(dtype)\n        if not self.training:  # NOTE: Only difference to bevformer head\n            object_query_embeds = object_query_embeds[:self.num_query // self.group_detr]\n        bev_queries = self.bev_embedding.weight.to(dtype)\n\n        bev_mask = torch.zeros((bs, self.bev_h, self.bev_w),\n                               device=bev_queries.device).to(dtype)\n        bev_pos = self.positional_encoding(bev_mask).to(dtype)\n\n        if only_bev:\n            return self.transformer.get_bev_features(\n                mlvl_feats,\n                bev_queries,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                img_metas=img_metas,\n                prev_bev=prev_bev,\n            )\n        else:\n            outputs = self.transformer(\n                mlvl_feats,\n                bev_queries,\n                object_query_embeds,\n                self.bev_h,\n                self.bev_w,\n                grid_length=(self.real_h / self.bev_h,\n                             self.real_w / self.bev_w),\n                bev_pos=bev_pos,\n                reg_branches=self.reg_branches if self.with_box_refine else None,  # noqa:E501\n                cls_branches=self.cls_branches if self.as_two_stage else None,\n                img_metas=img_metas,\n                prev_bev=prev_bev\n        )\n\n        bev_embed, hs, init_reference, inter_references = outputs\n        hs = hs.permute(0, 2, 1, 3)\n        outputs_classes = []\n        outputs_coords = []\n        for lvl in range(hs.shape[0]):\n            if lvl == 0:\n                reference = init_reference\n            else:\n                reference = inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            outputs_class = self.cls_branches[lvl](hs[lvl])\n            tmp = self.reg_branches[lvl](hs[lvl])\n            assert reference.shape[-1] == 3\n            tmp[..., 0:2] += reference[..., 0:2]\n            tmp[..., 0:2] = tmp[..., 0:2].sigmoid()\n            tmp[..., 4:5] += reference[..., 2:3]\n            tmp[..., 4:5] = tmp[..., 4:5].sigmoid()\n            tmp[..., 0:1] = (tmp[..., 0:1] * (self.pc_range[3] -\n                             self.pc_range[0]) + self.pc_range[0])\n            tmp[..., 1:2] = (tmp[..., 1:2] * (self.pc_range[4] -\n                             self.pc_range[1]) + self.pc_range[1])\n            tmp[..., 4:5] = (tmp[..., 4:5] * (self.pc_range[5] -\n                             self.pc_range[2]) + self.pc_range[2])\n            outputs_coord = tmp\n            outputs_classes.append(outputs_class)\n            outputs_coords.append(outputs_coord)\n\n        outputs_classes = torch.stack(outputs_classes)\n        outputs_coords = torch.stack(outputs_coords)\n\n        outs = {\n            'bev_embed': bev_embed,\n            'all_cls_scores': outputs_classes,\n            'all_bbox_preds': outputs_coords,\n            'enc_cls_scores': None,\n            'enc_bbox_preds': None,\n        }\n\n        return outs\n\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             preds_dicts,\n             gt_bboxes_ignore=None,\n             img_metas=None):\n        \"\"\"\"Loss function.\n        Args:\n\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            preds_dicts:\n                all_cls_scores (Tensor): Classification score of all\n                    decoder layers, has shape\n                    [nb_dec, bs, num_query, cls_out_channels].\n                all_bbox_preds (Tensor): Sigmoid regression\n                    outputs of all decode layers. Each is a 4D-tensor with\n                    normalized coordinate format (cx, cy, w, h) and shape\n                    [nb_dec, bs, num_query, 4].\n                enc_cls_scores (Tensor): Classification scores of\n                    points on encode feature map , has shape\n                    (N, h*w, num_classes). Only be passed when as_two_stage is\n                    True, otherwise is None.\n                enc_bbox_preds (Tensor): Regression results of each points\n                    on the encode feature map, has shape (N, h*w, 4). Only be\n                    passed when as_two_stage is True, otherwise is None.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            f'{self.__class__.__name__} only supports ' \\\n            f'for gt_bboxes_ignore setting to None.'\n\n        all_cls_scores = preds_dicts['all_cls_scores']\n        all_bbox_preds = preds_dicts['all_bbox_preds']\n        enc_cls_scores = preds_dicts['enc_cls_scores']\n        enc_bbox_preds = preds_dicts['enc_bbox_preds']\n        assert enc_cls_scores is None and enc_bbox_preds is None \n\n        num_dec_layers = len(all_cls_scores)\n        device = gt_labels_list[0].device\n\n        gt_bboxes_list = [torch.cat(\n            (gt_bboxes.gravity_center, gt_bboxes.tensor[:, 3:]),\n            dim=1).to(device) for gt_bboxes in gt_bboxes_list]\n\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        loss_dict = dict()\n        loss_dict['loss_cls'] = 0\n        loss_dict['loss_bbox'] = 0\n        for num_dec_layer in range(all_cls_scores.shape[0] - 1):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = 0\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = 0\n        num_query_per_group = self.num_query // self.group_detr\n        for group_index in range(self.group_detr):\n            group_query_start = group_index * num_query_per_group\n            group_query_end = (group_index+1) * num_query_per_group\n            group_cls_scores =  all_cls_scores[:, :,group_query_start:group_query_end, :]\n            group_bbox_preds = all_bbox_preds[:, :,group_query_start:group_query_end, :]\n            losses_cls, losses_bbox = multi_apply(\n                self.loss_single, group_cls_scores, group_bbox_preds,\n                all_gt_bboxes_list, all_gt_labels_list,\n                all_gt_bboxes_ignore_list)\n            loss_dict['loss_cls'] += losses_cls[-1] / self.group_detr\n            loss_dict['loss_bbox'] += losses_bbox[-1] / self.group_detr\n            # loss from other decoder layers\n            num_dec_layer = 0\n            for loss_cls_i, loss_bbox_i in zip(losses_cls[:-1], losses_bbox[:-1]):\n                loss_dict[f'd{num_dec_layer}.loss_cls'] += loss_cls_i / self.group_detr\n                loss_dict[f'd{num_dec_layer}.loss_bbox'] += loss_bbox_i / self.group_detr\n                num_dec_layer += 1\n        return loss_dict"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/dense_test_mixins.py",
    "content": "import sys\nfrom inspect import signature\n\nimport torch\n\nfrom mmcv.core.post_processing.merge_augs import merge_aug_proposals\nfrom mmcv.core.post_processing.bbox_nms import multiclass_nms\n# from ...core.post_processing import merge_aug_proposals, multiclass_nms\n\nif sys.version_info >= (3, 7):\n    from mmcv.utils.contextmanagers import completed\n\n\nclass BBoxTestMixin(object):\n    \"\"\"Mixin class for testing det bboxes via DenseHead.\"\"\"\n\n    def simple_test_bboxes(self, feats, img_metas, rescale=False):\n        \"\"\"Test det bboxes without test-time augmentation, can be applied in\n        DenseHead except for ``RPNHead`` and its variants, e.g., ``GARPNHead``,\n        etc.\n\n        Args:\n            feats (tuple[torch.Tensor]): Multi-level features from the\n                upstream network, each is a 4D-tensor.\n            img_metas (list[dict]): List of image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is ``bboxes`` with shape (n, 5),\n                where 5 represent (tl_x, tl_y, br_x, br_y, score).\n                The shape of the second tensor in the tuple is ``labels``\n                with shape (n,)\n        \"\"\"\n        outs = self.forward(feats)\n        results_list = self.get_bboxes(*outs, img_metas, rescale=rescale)\n        return results_list\n\n    def aug_test_bboxes(self, feats, img_metas, rescale=False):\n        \"\"\"Test det bboxes with test time augmentation, can be applied in\n        DenseHead except for ``RPNHead`` and its variants, e.g., ``GARPNHead``,\n        etc.\n\n        Args:\n            feats (list[Tensor]): the outer list indicates test-time\n                augmentations and inner Tensor should have a shape NxCxHxW,\n                which contains features for all images in the batch.\n            img_metas (list[list[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch. each dict has image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is ``bboxes`` with shape (n, 5),\n                where 5 represent (tl_x, tl_y, br_x, br_y, score).\n                The shape of the second tensor in the tuple is ``labels``\n                with shape (n,). The length of list should always be 1.\n        \"\"\"\n        # check with_nms argument\n        gb_sig = signature(self.get_bboxes)\n        gb_args = [p.name for p in gb_sig.parameters.values()]\n        if hasattr(self, '_get_bboxes'):\n            gbs_sig = signature(self._get_bboxes)\n        else:\n            gbs_sig = signature(self._get_bboxes_single)\n        gbs_args = [p.name for p in gbs_sig.parameters.values()]\n        assert ('with_nms' in gb_args) and ('with_nms' in gbs_args), \\\n            f'{self.__class__.__name__}' \\\n            ' does not support test-time augmentation'\n\n        aug_bboxes = []\n        aug_scores = []\n        aug_factors = []  # score_factors for NMS\n        for x, img_meta in zip(feats, img_metas):\n            # only one image in the batch\n            outs = self.forward(x)\n            bbox_inputs = outs + (img_meta, self.test_cfg, False, False)\n            bbox_outputs = self.get_bboxes(*bbox_inputs)[0]\n            aug_bboxes.append(bbox_outputs[0])\n            aug_scores.append(bbox_outputs[1])\n            # bbox_outputs of some detectors (e.g., ATSS, FCOS, YOLOv3)\n            # contains additional element to adjust scores before NMS\n            if len(bbox_outputs) >= 3:\n                aug_factors.append(bbox_outputs[2])\n\n        # after merging, bboxes will be rescaled to the original image size\n        merged_bboxes, merged_scores = self.merge_aug_bboxes(\n            aug_bboxes, aug_scores, img_metas)\n        merged_factors = torch.cat(aug_factors, dim=0) if aug_factors else None\n        det_bboxes, det_labels = multiclass_nms(\n            merged_bboxes,\n            merged_scores,\n            self.test_cfg.score_thr,\n            self.test_cfg.nms,\n            self.test_cfg.max_per_img,\n            score_factors=merged_factors)\n\n        if rescale:\n            _det_bboxes = det_bboxes\n        else:\n            _det_bboxes = det_bboxes.clone()\n            _det_bboxes[:, :4] *= det_bboxes.new_tensor(\n                img_metas[0][0]['scale_factor'])\n\n        return [\n            (_det_bboxes, det_labels),\n        ]\n\n    def simple_test_rpn(self, x, img_metas):\n        \"\"\"Test without augmentation, only for ``RPNHead`` and its variants,\n        e.g., ``GARPNHead``, etc.\n\n        Args:\n            x (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n            img_metas (list[dict]): Meta info of each image.\n\n        Returns:\n            list[Tensor]: Proposals of each image, each item has shape (n, 5),\n                where 5 represent (tl_x, tl_y, br_x, br_y, score).\n        \"\"\"\n        rpn_outs = self(x)\n        proposal_list = self.get_bboxes(*rpn_outs, img_metas)\n        return proposal_list\n\n    def aug_test_rpn(self, feats, img_metas):\n        \"\"\"Test with augmentation for only for ``RPNHead`` and its variants,\n        e.g., ``GARPNHead``, etc.\n\n        Args:\n            feats (tuple[Tensor]): Features from the upstream network, each is\n                        a 4D-tensor.\n            img_metas (list[dict]): Meta info of each image.\n\n        Returns:\n            list[Tensor]: Proposals of each image, each item has shape (n, 5),\n                where 5 represent (tl_x, tl_y, br_x, br_y, score).\n        \"\"\"\n        samples_per_gpu = len(img_metas[0])\n        aug_proposals = [[] for _ in range(samples_per_gpu)]\n        for x, img_meta in zip(feats, img_metas):\n            proposal_list = self.simple_test_rpn(x, img_meta)\n            for i, proposals in enumerate(proposal_list):\n                aug_proposals[i].append(proposals)\n        # reorganize the order of 'img_metas' to match the dimensions\n        # of 'aug_proposals'\n        aug_img_metas = []\n        for i in range(samples_per_gpu):\n            aug_img_meta = []\n            for j in range(len(img_metas)):\n                aug_img_meta.append(img_metas[j][i])\n            aug_img_metas.append(aug_img_meta)\n        # after merging, proposals will be rescaled to the original image size\n        merged_proposals = [\n            merge_aug_proposals(proposals, aug_img_meta, self.test_cfg)\n            for proposals, aug_img_meta in zip(aug_proposals, aug_img_metas)\n        ]\n        return merged_proposals\n\n    if sys.version_info >= (3, 7):\n\n        async def async_simple_test_rpn(self, x, img_metas):\n            sleep_interval = self.test_cfg.pop('async_sleep_interval', 0.025)\n            async with completed(\n                    __name__, 'rpn_head_forward',\n                    sleep_interval=sleep_interval):\n                rpn_outs = self(x)\n\n            proposal_list = self.get_bboxes(*rpn_outs, img_metas)\n            return proposal_list\n\n    def merge_aug_bboxes(self, aug_bboxes, aug_scores, img_metas):\n        \"\"\"Merge augmented detection bboxes and scores.\n\n        Args:\n            aug_bboxes (list[Tensor]): shape (n, 4*#class)\n            aug_scores (list[Tensor] or None): shape (n, #class)\n            img_shapes (list[Tensor]): shape (3, ).\n\n        Returns:\n            tuple[Tensor]: ``bboxes`` with shape (n,4), where\n            4 represent (tl_x, tl_y, br_x, br_y)\n            and ``scores`` with shape (n,).\n        \"\"\"\n        recovered_bboxes = []\n        for bboxes, img_info in zip(aug_bboxes, img_metas):\n            img_shape = img_info[0]['img_shape']\n            scale_factor = img_info[0]['scale_factor']\n            flip = img_info[0]['flip']\n            flip_direction = img_info[0]['flip_direction']\n            bboxes = bbox_mapping_back(bboxes, img_shape, scale_factor, flip,\n                                       flip_direction)\n            recovered_bboxes.append(bboxes)\n        bboxes = torch.cat(recovered_bboxes, dim=0)\n        if aug_scores is None:\n            return bboxes\n        else:\n            scores = torch.cat(aug_scores, dim=0)\n            return bboxes, scores\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/detr_head.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.bricks import Conv2d, Linear, build_activation_layer\nfrom mmcv.models.bricks.transformer import FFN, build_positional_encoding\nfrom mmcv.utils import force_fp32\n\nfrom mmcv.core.utils import multi_apply, reduce_mean\nfrom mmcv.core.bbox.builder import (build_assigner, build_sampler)\nfrom mmcv.core.bbox.transforms import (bbox_cxcywh_to_xyxy, bbox_xyxy_to_cxcywh)\nfrom mmcv.models.utils import build_transformer\nfrom ..builder import HEADS, build_loss\nfrom .anchor_free_head import AnchorFreeHead\n\n\n@HEADS.register_module()\nclass DETRHead(AnchorFreeHead):\n    \"\"\"Implements the DETR transformer head.\n\n    See `paper: End-to-End Object Detection with Transformers\n    <https://arxiv.org/pdf/2005.12872>`_ for details.\n\n    Args:\n        num_classes (int): Number of categories excluding the background.\n        in_channels (int): Number of channels in the input feature map.\n        num_query (int): Number of query in Transformer.\n        num_reg_fcs (int, optional): Number of fully-connected layers used in\n            `FFN`, which is then used for the regression head. Default 2.\n        transformer (obj:`mmcv.ConfigDict`|dict): Config for transformer.\n            Default: None.\n        sync_cls_avg_factor (bool): Whether to sync the avg_factor of\n            all ranks. Default to False.\n        positional_encoding (obj:`mmcv.ConfigDict`|dict):\n            Config for position encoding.\n        loss_cls (obj:`mmcv.ConfigDict`|dict): Config of the\n            classification loss. Default `CrossEntropyLoss`.\n        loss_bbox (obj:`mmcv.ConfigDict`|dict): Config of the\n            regression loss. Default `L1Loss`.\n        loss_iou (obj:`mmcv.ConfigDict`|dict): Config of the\n            regression iou loss. Default `GIoULoss`.\n        tran_cfg (obj:`mmcv.ConfigDict`|dict): Training config of\n            transformer head.\n        test_cfg (obj:`mmcv.ConfigDict`|dict): Testing config of\n            transformer head.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n            Default: None\n    \"\"\"\n\n    _version = 2\n\n    def __init__(self,\n                 num_classes,\n                 in_channels,\n                 num_query=100,\n                 num_reg_fcs=2,\n                 transformer=None,\n                 sync_cls_avg_factor=False,\n                 positional_encoding=dict(\n                     type='SinePositionalEncoding',\n                     num_feats=128,\n                     normalize=True),\n                 loss_cls=dict(\n                     type='CrossEntropyLoss',\n                     bg_cls_weight=0.1,\n                     use_sigmoid=False,\n                     loss_weight=1.0,\n                     class_weight=1.0),\n                 loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n                 loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n                 train_cfg=dict(\n                     assigner=dict(\n                         type='HungarianAssigner',\n                         cls_cost=dict(type='ClassificationCost', weight=1.),\n                         reg_cost=dict(type='BBoxL1Cost', weight=5.0),\n                         iou_cost=dict(\n                             type='IoUCost', iou_mode='giou', weight=2.0))),\n                 test_cfg=dict(max_per_img=100),\n                 init_cfg=None,\n                 **kwargs):\n        # NOTE here use `AnchorFreeHead` instead of `TransformerHead`,\n        # since it brings inconvenience when the initialization of\n        # `AnchorFreeHead` is called.\n        super(AnchorFreeHead, self).__init__(init_cfg)\n        self.bg_cls_weight = 0\n        self.sync_cls_avg_factor = sync_cls_avg_factor\n        class_weight = loss_cls.get('class_weight', None)\n        if class_weight is not None and (self.__class__ is DETRHead):\n            assert isinstance(class_weight, float), 'Expected ' \\\n                'class_weight to have type float. Found ' \\\n                f'{type(class_weight)}.'\n            # NOTE following the official DETR rep0, bg_cls_weight means\n            # relative classification weight of the no-object class.\n            bg_cls_weight = loss_cls.get('bg_cls_weight', class_weight)\n            assert isinstance(bg_cls_weight, float), 'Expected ' \\\n                'bg_cls_weight to have type float. Found ' \\\n                f'{type(bg_cls_weight)}.'\n            class_weight = torch.ones(num_classes + 1) * class_weight\n            # set background class as the last indice\n            class_weight[num_classes] = bg_cls_weight\n            loss_cls.update({'class_weight': class_weight})\n            if 'bg_cls_weight' in loss_cls:\n                loss_cls.pop('bg_cls_weight')\n            self.bg_cls_weight = bg_cls_weight\n\n        if train_cfg:\n            assert 'assigner' in train_cfg, 'assigner should be provided '\\\n                'when train_cfg is set.'\n            assigner = train_cfg['assigner']\n            assert loss_cls['loss_weight'] == assigner['cls_cost']['weight'], \\\n                'The classification weight for loss and matcher should be' \\\n                'exactly the same.'\n            assert loss_bbox['loss_weight'] == assigner['reg_cost'][\n                'weight'], 'The regression L1 weight for loss and matcher ' \\\n                'should be exactly the same.'\n            assert loss_iou['loss_weight'] == assigner['iou_cost']['weight'], \\\n                'The regression iou weight for loss and matcher should be' \\\n                'exactly the same.'\n            self.assigner = build_assigner(assigner)\n            # DETR sampling=False, so use PseudoSampler\n            sampler_cfg = dict(type='PseudoSampler')\n            self.sampler = build_sampler(sampler_cfg, context=self)\n        self.num_query = num_query\n        self.num_classes = num_classes\n        self.in_channels = in_channels\n        self.num_reg_fcs = num_reg_fcs\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n        self.fp16_enabled = False\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bbox = build_loss(loss_bbox)\n        self.loss_iou = build_loss(loss_iou)\n\n        if self.loss_cls.use_sigmoid:\n            self.cls_out_channels = num_classes\n        else:\n            self.cls_out_channels = num_classes + 1\n        self.act_cfg = transformer.get('act_cfg',\n                                       dict(type='ReLU', inplace=True))\n        self.activate = build_activation_layer(self.act_cfg)\n        self.positional_encoding = build_positional_encoding(\n            positional_encoding)\n        self.transformer = build_transformer(transformer)\n        self.embed_dims = self.transformer.embed_dims\n        assert 'num_feats' in positional_encoding\n        num_feats = positional_encoding['num_feats']\n        assert num_feats * 2 == self.embed_dims, 'embed_dims should' \\\n            f' be exactly 2 times of num_feats. Found {self.embed_dims}' \\\n            f' and {num_feats}.'\n        self._init_layers()\n\n    def _init_layers(self):\n        \"\"\"Initialize layers of the transformer head.\"\"\"\n        self.input_proj = Conv2d(\n            self.in_channels, self.embed_dims, kernel_size=1)\n        self.fc_cls = Linear(self.embed_dims, self.cls_out_channels)\n        self.reg_ffn = FFN(\n            self.embed_dims,\n            self.embed_dims,\n            self.num_reg_fcs,\n            self.act_cfg,\n            dropout=0.0,\n            add_residual=False)\n        self.fc_reg = Linear(self.embed_dims, 4)\n        self.query_embedding = nn.Embedding(self.num_query, self.embed_dims)\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the transformer head.\"\"\"\n        # The initialization for transformer is important\n        self.transformer.init_weights()\n\n    def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,\n                              missing_keys, unexpected_keys, error_msgs):\n        \"\"\"load checkpoints.\"\"\"\n        # NOTE here use `AnchorFreeHead` instead of `TransformerHead`,\n        # since `AnchorFreeHead._load_from_state_dict` should not be\n        # called here. Invoking the default `Module._load_from_state_dict`\n        # is enough.\n\n        # Names of some parameters in has been changed.\n        version = local_metadata.get('version', None)\n        if (version is None or version < 2) and self.__class__ is DETRHead:\n            convert_dict = {\n                '.self_attn.': '.attentions.0.',\n                '.ffn.': '.ffns.0.',\n                '.multihead_attn.': '.attentions.1.',\n                '.decoder.norm.': '.decoder.post_norm.'\n            }\n            state_dict_keys = list(state_dict.keys())\n            for k in state_dict_keys:\n                for ori_key, convert_key in convert_dict.items():\n                    if ori_key in k:\n                        convert_key = k.replace(ori_key, convert_key)\n                        state_dict[convert_key] = state_dict[k]\n                        del state_dict[k]\n\n        super(AnchorFreeHead,\n              self)._load_from_state_dict(state_dict, prefix, local_metadata,\n                                          strict, missing_keys,\n                                          unexpected_keys, error_msgs)\n\n    def forward(self, feats, img_metas):\n        \"\"\"Forward function.\n\n        Args:\n            feats (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            tuple[list[Tensor], list[Tensor]]: Outputs for all scale levels.\n\n                - all_cls_scores_list (list[Tensor]): Classification scores \\\n                    for each scale level. Each is a 4D-tensor with shape \\\n                    [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                    `cls_out_channels` should includes background.\n                - all_bbox_preds_list (list[Tensor]): Sigmoid regression \\\n                    outputs for each scale level. Each is a 4D-tensor with \\\n                    normalized coordinate format (cx, cy, w, h) and shape \\\n                    [nb_dec, bs, num_query, 4].\n        \"\"\"\n        num_levels = len(feats)\n        img_metas_list = [img_metas for _ in range(num_levels)]\n        return multi_apply(self.forward_single, feats, img_metas_list)\n\n    def forward_single(self, x, img_metas):\n        \"\"\"\"Forward function for a single feature level.\n\n        Args:\n            x (Tensor): Input feature from backbone's single stage, shape\n                [bs, c, h, w].\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head,\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression\n                head with normalized coordinate format (cx, cy, w, h).\n                Shape [nb_dec, bs, num_query, 4].\n        \"\"\"\n        # construct binary masks which used for the transformer.\n        # NOTE following the official DETR repo, non-zero values representing\n        # ignored positions, while zero values means valid positions.\n        batch_size = x.size(0)\n        input_img_h, input_img_w = img_metas[0]['batch_input_shape']\n        masks = x.new_ones((batch_size, input_img_h, input_img_w))\n        for img_id in range(batch_size):\n            img_h, img_w, _ = img_metas[img_id]['img_shape']\n            masks[img_id, :img_h, :img_w] = 0\n\n        x = self.input_proj(x)\n        # interpolate masks to have the same spatial shape with x\n        masks = F.interpolate(\n            masks.unsqueeze(1), size=x.shape[-2:]).to(torch.bool).squeeze(1)\n        # position encoding\n        pos_embed = self.positional_encoding(masks)  # [bs, embed_dim, h, w]\n        # outs_dec: [nb_dec, bs, num_query, embed_dim]\n        outs_dec, _ = self.transformer(x, masks, self.query_embedding.weight,\n                                       pos_embed)\n\n        all_cls_scores = self.fc_cls(outs_dec)\n        all_bbox_preds = self.fc_reg(self.activate(\n            self.reg_ffn(outs_dec))).sigmoid()\n        return all_cls_scores, all_bbox_preds\n\n    @force_fp32(apply_to=('all_cls_scores_list', 'all_bbox_preds_list'))\n    def loss(self,\n             all_cls_scores_list,\n             all_bbox_preds_list,\n             gt_bboxes_list,\n             gt_labels_list,\n             img_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"\"Loss function.\n\n        Only outputs from the last feature level are used for computing\n        losses by default.\n\n        Args:\n            all_cls_scores_list (list[Tensor]): Classification outputs\n                for each feature level. Each is a 4D-tensor with shape\n                [nb_dec, bs, num_query, cls_out_channels].\n            all_bbox_preds_list (list[Tensor]): Sigmoid regression\n                outputs for each feature level. Each is a 4D-tensor with\n                normalized coordinate format (cx, cy, w, h) and shape\n                [nb_dec, bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        # NOTE defaultly only the outputs from the last feature scale is used.\n        all_cls_scores = all_cls_scores_list[-1]\n        all_bbox_preds = all_bbox_preds_list[-1]\n        assert gt_bboxes_ignore is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n\n        num_dec_layers = len(all_cls_scores)\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n        img_metas_list = [img_metas for _ in range(num_dec_layers)]\n\n        losses_cls, losses_bbox, losses_iou = multi_apply(\n            self.loss_single, all_cls_scores, all_bbox_preds,\n            all_gt_bboxes_list, all_gt_labels_list, img_metas_list,\n            all_gt_bboxes_ignore_list)\n\n        loss_dict = dict()\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls[-1]\n        loss_dict['loss_bbox'] = losses_bbox[-1]\n        loss_dict['loss_iou'] = losses_iou[-1]\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_cls_i, loss_bbox_i, loss_iou_i in zip(losses_cls[:-1],\n                                                       losses_bbox[:-1],\n                                                       losses_iou[:-1]):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i\n            loss_dict[f'd{num_dec_layer}.loss_iou'] = loss_iou_i\n            num_dec_layer += 1\n        return loss_dict\n\n    def loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    img_metas,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,\n                                           gt_bboxes_list, gt_labels_list,\n                                           img_metas, gt_bboxes_ignore_list)\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n        cls_avg_factor = max(cls_avg_factor, 1)\n\n        loss_cls = self.loss_cls(\n            cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # construct factors used for rescale bboxes\n        factors = []\n        for img_meta, bbox_pred in zip(img_metas, bbox_preds):\n            img_h, img_w, _ = img_meta['img_shape']\n            factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                           img_h]).unsqueeze(0).repeat(\n                                               bbox_pred.size(0), 1)\n            factors.append(factor)\n        factors = torch.cat(factors, 0)\n\n        # DETR regress the relative position of boxes (cxcywh) in the image,\n        # thus the learning target is normalized by the image size. So here\n        # we need to re-scale them for calculating IoU loss\n        bbox_preds = bbox_preds.reshape(-1, 4)\n        bboxes = bbox_cxcywh_to_xyxy(bbox_preds) * factors\n        bboxes_gt = bbox_cxcywh_to_xyxy(bbox_targets) * factors\n\n        # regression IoU loss, defaultly GIoU loss\n        loss_iou = self.loss_iou(\n            bboxes, bboxes_gt, bbox_weights, avg_factor=num_total_pos)\n\n        # regression L1 loss\n        loss_bbox = self.loss_bbox(\n            bbox_preds, bbox_targets, bbox_weights, avg_factor=num_total_pos)\n        return loss_cls, loss_bbox, loss_iou\n\n    def get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    img_metas,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n\n        Outputs from a single decoder layer of a single feature level are used.\n\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n\n        Returns:\n            tuple: a tuple containing the following targets.\n\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, pos_inds_list, neg_inds_list) = multi_apply(\n             self._get_target_single, cls_scores_list, bbox_preds_list,\n             gt_bboxes_list, gt_labels_list, img_metas, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, num_total_pos, num_total_neg)\n\n    def _get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           gt_bboxes,\n                           gt_labels,\n                           img_meta,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n\n        Outputs from a single decoder layer of a single feature level are used.\n\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            img_meta (dict): Meta information for one image.\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,\n                                             gt_labels, img_meta,\n                                             gt_bboxes_ignore)\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes, ),\n                                    self.num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n        img_h, img_w, _ = img_meta['img_shape']\n\n        # DETR regress the relative position of boxes (cxcywh) in the image.\n        # Thus the learning target should be normalized by the image size, also\n        # the box format should be converted from defaultly x1y1x2y2 to cxcywh.\n        factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                       img_h]).unsqueeze(0)\n        pos_gt_bboxes_normalized = sampling_result.pos_gt_bboxes / factor\n        pos_gt_bboxes_targets = bbox_xyxy_to_cxcywh(pos_gt_bboxes_normalized)\n        bbox_targets[pos_inds] = pos_gt_bboxes_targets\n        return (labels, label_weights, bbox_targets, bbox_weights, pos_inds,\n                neg_inds)\n\n    # over-write because img_metas are needed as inputs for bbox_head.\n    def forward_train(self,\n                      x,\n                      img_metas,\n                      gt_bboxes,\n                      gt_labels=None,\n                      gt_bboxes_ignore=None,\n                      proposal_cfg=None,\n                      **kwargs):\n        \"\"\"Forward function for training mode.\n\n        Args:\n            x (list[Tensor]): Features from backbone.\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            gt_bboxes (Tensor): Ground truth bboxes of the image,\n                shape (num_gts, 4).\n            gt_labels (Tensor): Ground truth labels of each box,\n                shape (num_gts,).\n            gt_bboxes_ignore (Tensor): Ground truth bboxes to be\n                ignored, shape (num_ignored_gts, 4).\n            proposal_cfg (mmcv.Config): Test / postprocessing configuration,\n                if None, test_cfg would be used.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert proposal_cfg is None, '\"proposal_cfg\" must be None'\n        outs = self(x, img_metas)\n        if gt_labels is None:\n            loss_inputs = outs + (gt_bboxes, img_metas)\n        else:\n            loss_inputs = outs + (gt_bboxes, gt_labels, img_metas)\n        losses = self.loss(*loss_inputs, gt_bboxes_ignore=gt_bboxes_ignore)\n        return losses\n\n    @force_fp32(apply_to=('all_cls_scores_list', 'all_bbox_preds_list'))\n    def get_bboxes(self,\n                   all_cls_scores_list,\n                   all_bbox_preds_list,\n                   img_metas,\n                   rescale=False):\n        \"\"\"Transform network outputs for a batch into bbox predictions.\n\n        Args:\n            all_cls_scores_list (list[Tensor]): Classification outputs\n                for each feature level. Each is a 4D-tensor with shape\n                [nb_dec, bs, num_query, cls_out_channels].\n            all_bbox_preds_list (list[Tensor]): Sigmoid regression\n                outputs for each feature level. Each is a 4D-tensor with\n                normalized coordinate format (cx, cy, w, h) and shape\n                [nb_dec, bs, num_query, 4].\n            img_metas (list[dict]): Meta information of each image.\n            rescale (bool, optional): If True, return boxes in original\n                image space. Default False.\n\n        Returns:\n            list[list[Tensor, Tensor]]: Each item in result_list is 2-tuple. \\\n                The first item is an (n, 5) tensor, where the first 4 columns \\\n                are bounding box positions (tl_x, tl_y, br_x, br_y) and the \\\n                5-th column is a score between 0 and 1. The second item is a \\\n                (n,) tensor where each item is the predicted class label of \\\n                the corresponding box.\n        \"\"\"\n        # NOTE defaultly only using outputs from the last feature level,\n        # and only the outputs from the last decoder layer is used.\n        cls_scores = all_cls_scores_list[-1][-1]\n        bbox_preds = all_bbox_preds_list[-1][-1]\n\n        result_list = []\n        for img_id in range(len(img_metas)):\n            cls_score = cls_scores[img_id]\n            bbox_pred = bbox_preds[img_id]\n            img_shape = img_metas[img_id]['img_shape']\n            scale_factor = img_metas[img_id]['scale_factor']\n            proposals = self._get_bboxes_single(cls_score, bbox_pred,\n                                                img_shape, scale_factor,\n                                                rescale)\n            result_list.append(proposals)\n\n        return result_list\n\n    def _get_bboxes_single(self,\n                           cls_score,\n                           bbox_pred,\n                           img_shape,\n                           scale_factor,\n                           rescale=False):\n        \"\"\"Transform outputs from the last decoder layer into bbox predictions\n        for each image.\n\n        Args:\n            cls_score (Tensor): Box score logits from the last decoder layer\n                for each image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from the last decoder layer\n                for each image, with coordinate format (cx, cy, w, h) and\n                shape [num_query, 4].\n            img_shape (tuple[int]): Shape of input image, (height, width, 3).\n            scale_factor (ndarray, optional): Scale factor of the image arange\n                as (w_scale, h_scale, w_scale, h_scale).\n            rescale (bool, optional): If True, return boxes in original image\n                space. Default False.\n\n        Returns:\n            tuple[Tensor]: Results of detected bboxes and labels.\n\n                - det_bboxes: Predicted bboxes with shape [num_query, 5], \\\n                    where the first 4 columns are bounding box positions \\\n                    (tl_x, tl_y, br_x, br_y) and the 5-th column are scores \\\n                    between 0 and 1.\n                - det_labels: Predicted labels of the corresponding box with \\\n                    shape [num_query].\n        \"\"\"\n        assert len(cls_score) == len(bbox_pred)\n        max_per_img = self.test_cfg.get('max_per_img', self.num_query)\n        # exclude background\n        if self.loss_cls.use_sigmoid:\n            cls_score = cls_score.sigmoid()\n            scores, indexes = cls_score.view(-1).topk(max_per_img)\n            det_labels = indexes % self.num_classes\n            bbox_index = indexes // self.num_classes\n            bbox_pred = bbox_pred[bbox_index]\n        else:\n            scores, det_labels = F.softmax(cls_score, dim=-1)[..., :-1].max(-1)\n            scores, bbox_index = scores.topk(max_per_img)\n            bbox_pred = bbox_pred[bbox_index]\n            det_labels = det_labels[bbox_index]\n\n        det_bboxes = bbox_cxcywh_to_xyxy(bbox_pred)\n        det_bboxes[:, 0::2] = det_bboxes[:, 0::2] * img_shape[1]\n        det_bboxes[:, 1::2] = det_bboxes[:, 1::2] * img_shape[0]\n        det_bboxes[:, 0::2].clamp_(min=0, max=img_shape[1])\n        det_bboxes[:, 1::2].clamp_(min=0, max=img_shape[0])\n        if rescale:\n            det_bboxes /= det_bboxes.new_tensor(scale_factor)\n        det_bboxes = torch.cat((det_bboxes, scores.unsqueeze(1)), -1)\n\n        return det_bboxes, det_labels\n\n    def simple_test_bboxes(self, feats, img_metas, rescale=False):\n        \"\"\"Test det bboxes without test-time augmentation.\n\n        Args:\n            feats (tuple[torch.Tensor]): Multi-level features from the\n                upstream network, each is a 4D-tensor.\n            img_metas (list[dict]): List of image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is ``bboxes`` with shape (n, 5),\n                where 5 represent (tl_x, tl_y, br_x, br_y, score).\n                The shape of the second tensor in the tuple is ``labels``\n                with shape (n,)\n        \"\"\"\n        # forward of this head requires img_metas\n        outs = self.forward(feats, img_metas)\n        results_list = self.get_bboxes(*outs, img_metas, rescale=rescale)\n        return results_list\n\n    def forward_onnx(self, feats, img_metas):\n        \"\"\"Forward function for exporting to ONNX.\n\n        Over-write `forward` because: `masks` is directly created with\n        zero (valid position tag) and has the same spatial size as `x`.\n        Thus the construction of `masks` is different from that in `forward`.\n\n        Args:\n            feats (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            tuple[list[Tensor], list[Tensor]]: Outputs for all scale levels.\n\n                - all_cls_scores_list (list[Tensor]): Classification scores \\\n                    for each scale level. Each is a 4D-tensor with shape \\\n                    [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                    `cls_out_channels` should includes background.\n                - all_bbox_preds_list (list[Tensor]): Sigmoid regression \\\n                    outputs for each scale level. Each is a 4D-tensor with \\\n                    normalized coordinate format (cx, cy, w, h) and shape \\\n                    [nb_dec, bs, num_query, 4].\n        \"\"\"\n        num_levels = len(feats)\n        img_metas_list = [img_metas for _ in range(num_levels)]\n        return multi_apply(self.forward_single_onnx, feats, img_metas_list)\n\n    def forward_single_onnx(self, x, img_metas):\n        \"\"\"\"Forward function for a single feature level with ONNX exportation.\n\n        Args:\n            x (Tensor): Input feature from backbone's single stage, shape\n                [bs, c, h, w].\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head,\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression\n                head with normalized coordinate format (cx, cy, w, h).\n                Shape [nb_dec, bs, num_query, 4].\n        \"\"\"\n        # Note `img_shape` is not dynamically traceable to ONNX,\n        # since the related augmentation was done with numpy under\n        # CPU. Thus `masks` is directly created with zeros (valid tag)\n        # and the same spatial shape as `x`.\n        # The difference between torch and exported ONNX model may be\n        # ignored, since the same performance is achieved (e.g.\n        # 40.1 vs 40.1 for DETR)\n        batch_size = x.size(0)\n        h, w = x.size()[-2:]\n        masks = x.new_zeros((batch_size, h, w))  # [B,h,w]\n\n        x = self.input_proj(x)\n        # interpolate masks to have the same spatial shape with x\n        masks = F.interpolate(\n            masks.unsqueeze(1), size=x.shape[-2:]).to(torch.bool).squeeze(1)\n        pos_embed = self.positional_encoding(masks)\n        outs_dec, _ = self.transformer(x, masks, self.query_embedding.weight,\n                                       pos_embed)\n\n        all_cls_scores = self.fc_cls(outs_dec)\n        all_bbox_preds = self.fc_reg(self.activate(\n            self.reg_ffn(outs_dec))).sigmoid()\n        return all_cls_scores, all_bbox_preds\n\n    def onnx_export(self, all_cls_scores_list, all_bbox_preds_list, img_metas):\n        \"\"\"Transform network outputs into bbox predictions, with ONNX\n        exportation.\n\n        Args:\n            all_cls_scores_list (list[Tensor]): Classification outputs\n                for each feature level. Each is a 4D-tensor with shape\n                [nb_dec, bs, num_query, cls_out_channels].\n            all_bbox_preds_list (list[Tensor]): Sigmoid regression\n                outputs for each feature level. Each is a 4D-tensor with\n                normalized coordinate format (cx, cy, w, h) and shape\n                [nb_dec, bs, num_query, 4].\n            img_metas (list[dict]): Meta information of each image.\n\n        Returns:\n            tuple[Tensor, Tensor]: dets of shape [N, num_det, 5]\n                and class labels of shape [N, num_det].\n        \"\"\"\n        assert len(img_metas) == 1, \\\n            'Only support one input image while in exporting to ONNX'\n\n        cls_scores = all_cls_scores_list[-1][-1]\n        bbox_preds = all_bbox_preds_list[-1][-1]\n\n        # Note `img_shape` is not dynamically traceable to ONNX,\n        # here `img_shape_for_onnx` (padded shape of image tensor)\n        # is used.\n        img_shape = img_metas[0]['img_shape_for_onnx']\n        max_per_img = self.test_cfg.get('max_per_img', self.num_query)\n        batch_size = cls_scores.size(0)\n        # `batch_index_offset` is used for the gather of concatenated tensor\n        batch_index_offset = torch.arange(batch_size).to(\n            cls_scores.device) * max_per_img\n        batch_index_offset = batch_index_offset.unsqueeze(1).expand(\n            batch_size, max_per_img)\n\n        # supports dynamical batch inference\n        if self.loss_cls.use_sigmoid:\n            cls_scores = cls_scores.sigmoid()\n            scores, indexes = cls_scores.view(batch_size, -1).topk(\n                max_per_img, dim=1)\n            det_labels = indexes % self.num_classes\n            bbox_index = indexes // self.num_classes\n            bbox_index = (bbox_index + batch_index_offset).view(-1)\n            bbox_preds = bbox_preds.view(-1, 4)[bbox_index]\n            bbox_preds = bbox_preds.view(batch_size, -1, 4)\n        else:\n            scores, det_labels = F.softmax(\n                cls_scores, dim=-1)[..., :-1].max(-1)\n            scores, bbox_index = scores.topk(max_per_img, dim=1)\n            bbox_index = (bbox_index + batch_index_offset).view(-1)\n            bbox_preds = bbox_preds.view(-1, 4)[bbox_index]\n            det_labels = det_labels.view(-1)[bbox_index]\n            bbox_preds = bbox_preds.view(batch_size, -1, 4)\n            det_labels = det_labels.view(batch_size, -1)\n\n        det_bboxes = bbox_cxcywh_to_xyxy(bbox_preds)\n        # use `img_shape_tensor` for dynamically exporting to ONNX\n        img_shape_tensor = img_shape.flip(0).repeat(2)  # [w,h,w,h]\n        img_shape_tensor = img_shape_tensor.unsqueeze(0).unsqueeze(0).expand(\n            batch_size, det_bboxes.size(1), 4)\n        det_bboxes = det_bboxes * img_shape_tensor\n        # dynamically clip bboxes\n        x1, y1, x2, y2 = det_bboxes.split((1, 1, 1, 1), dim=-1)\n        from mmcv.core.export import dynamic_clip_for_onnx\n        x1, y1, x2, y2 = dynamic_clip_for_onnx(x1, y1, x2, y2, img_shape)\n        det_bboxes = torch.cat([x1, y1, x2, y2], dim=-1)\n        det_bboxes = torch.cat((det_bboxes, scores.unsqueeze(-1)), -1)\n\n        return det_bboxes, det_labels\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/free_anchor3d_head.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nfrom mmcv.runner import force_fp32\nfrom torch.nn import functional as F\n\nfrom mmcv.core.bbox import bbox_overlaps_nearest_3d\nfrom mmcv.models import HEADS\nfrom .anchor3d_head import Anchor3DHead\nfrom .train_mixins import get_direction_target\n\n\n@HEADS.register_module()\nclass FreeAnchor3DHead(Anchor3DHead):\n    r\"\"\"`FreeAnchor <https://arxiv.org/abs/1909.02466>`_ head for 3D detection.\n\n    Note:\n        This implementation is directly modified from the `mmdet implementation\n        <https://github.com/open-mmlab/mmdetection/blob/master/mmdet/models/dense_heads/free_anchor_retina_head.py>`_.\n        We find it also works on 3D detection with minor modification, i.e.,\n        different hyper-parameters and a additional direction classifier.\n\n    Args:\n        pre_anchor_topk (int): Number of boxes that be token in each bag.\n        bbox_thr (float): The threshold of the saturated linear function. It is\n            usually the same with the IoU threshold used in NMS.\n        gamma (float): Gamma parameter in focal loss.\n        alpha (float): Alpha parameter in focal loss.\n        kwargs (dict): Other arguments are the same as those in :class:`Anchor3DHead`.\n    \"\"\"  # noqa: E501\n\n    def __init__(self,\n                 pre_anchor_topk=50,\n                 bbox_thr=0.6,\n                 gamma=2.0,\n                 alpha=0.5,\n                 init_cfg=None,\n                 **kwargs):\n        super().__init__(init_cfg=init_cfg, **kwargs)\n        self.pre_anchor_topk = pre_anchor_topk\n        self.bbox_thr = bbox_thr\n        self.gamma = gamma\n        self.alpha = alpha\n\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds', 'dir_cls_preds'))\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             dir_cls_preds,\n             gt_bboxes,\n             gt_labels,\n             input_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"Calculate loss of FreeAnchor head.\n\n        Args:\n            cls_scores (list[torch.Tensor]): Classification scores of\n                different samples.\n            bbox_preds (list[torch.Tensor]): Box predictions of\n                different samples\n            dir_cls_preds (list[torch.Tensor]): Direction predictions of\n                different samples\n            gt_bboxes (list[:obj:`BaseInstance3DBoxes`]): Ground truth boxes.\n            gt_labels (list[torch.Tensor]): Ground truth labels.\n            input_metas (list[dict]): List of input meta information.\n            gt_bboxes_ignore (list[:obj:`BaseInstance3DBoxes`], optional):\n                Ground truth boxes that should be ignored. Defaults to None.\n\n        Returns:\n            dict[str, torch.Tensor]: Loss items.\n\n                - positive_bag_loss (torch.Tensor): Loss of positive samples.\n                - negative_bag_loss (torch.Tensor): Loss of negative samples.\n        \"\"\"\n        featmap_sizes = [featmap.size()[-2:] for featmap in cls_scores]\n        assert len(featmap_sizes) == self.anchor_generator.num_levels\n\n        anchor_list = self.get_anchors(featmap_sizes, input_metas)\n        anchors = [torch.cat(anchor) for anchor in anchor_list]\n\n        # concatenate each level\n        cls_scores = [\n            cls_score.permute(0, 2, 3, 1).reshape(\n                cls_score.size(0), -1, self.num_classes)\n            for cls_score in cls_scores\n        ]\n        bbox_preds = [\n            bbox_pred.permute(0, 2, 3, 1).reshape(\n                bbox_pred.size(0), -1, self.box_code_size)\n            for bbox_pred in bbox_preds\n        ]\n        dir_cls_preds = [\n            dir_cls_pred.permute(0, 2, 3,\n                                 1).reshape(dir_cls_pred.size(0), -1, 2)\n            for dir_cls_pred in dir_cls_preds\n        ]\n\n        cls_scores = torch.cat(cls_scores, dim=1)\n        bbox_preds = torch.cat(bbox_preds, dim=1)\n        dir_cls_preds = torch.cat(dir_cls_preds, dim=1)\n\n        cls_prob = torch.sigmoid(cls_scores)\n        box_prob = []\n        num_pos = 0\n        positive_losses = []\n        for _, (anchors_, gt_labels_, gt_bboxes_, cls_prob_, bbox_preds_,\n                dir_cls_preds_) in enumerate(\n                    zip(anchors, gt_labels, gt_bboxes, cls_prob, bbox_preds,\n                        dir_cls_preds)):\n\n            gt_bboxes_ = gt_bboxes_.tensor.to(anchors_.device)\n\n            with torch.no_grad():\n                # box_localization: a_{j}^{loc}, shape: [j, 4]\n                pred_boxes = self.bbox_coder.decode(anchors_, bbox_preds_)\n\n                # object_box_iou: IoU_{ij}^{loc}, shape: [i, j]\n                object_box_iou = bbox_overlaps_nearest_3d(\n                    gt_bboxes_, pred_boxes)\n\n                # object_box_prob: P{a_{j} -> b_{i}}, shape: [i, j]\n                t1 = self.bbox_thr\n                t2 = object_box_iou.max(\n                    dim=1, keepdim=True).values.clamp(min=t1 + 1e-6)\n                object_box_prob = ((object_box_iou - t1) / (t2 - t1)).clamp(\n                    min=0, max=1)\n\n                # object_cls_box_prob: P{a_{j} -> b_{i}}, shape: [i, c, j]\n                num_obj = gt_labels_.size(0)\n                indices = torch.stack(\n                    [torch.arange(num_obj).type_as(gt_labels_), gt_labels_],\n                    dim=0)\n\n                object_cls_box_prob = torch.sparse_coo_tensor(\n                    indices, object_box_prob)\n\n                # image_box_iou: P{a_{j} \\in A_{+}}, shape: [c, j]\n                \"\"\"\n                from \"start\" to \"end\" implement:\n                image_box_iou = torch.sparse.max(object_cls_box_prob,\n                                                 dim=0).t()\n\n                \"\"\"\n                # start\n                box_cls_prob = torch.sparse.sum(\n                    object_cls_box_prob, dim=0).to_dense()\n\n                indices = torch.nonzero(box_cls_prob, as_tuple=False).t_()\n                if indices.numel() == 0:\n                    image_box_prob = torch.zeros(\n                        anchors_.size(0),\n                        self.num_classes).type_as(object_box_prob)\n                else:\n                    nonzero_box_prob = torch.where(\n                        (gt_labels_.unsqueeze(dim=-1) == indices[0]),\n                        object_box_prob[:, indices[1]],\n                        torch.tensor(\n                            [0]).type_as(object_box_prob)).max(dim=0).values\n\n                    # upmap to shape [j, c]\n                    image_box_prob = torch.sparse_coo_tensor(\n                        indices.flip([0]),\n                        nonzero_box_prob,\n                        size=(anchors_.size(0), self.num_classes)).to_dense()\n                # end\n\n                box_prob.append(image_box_prob)\n\n            # construct bags for objects\n            match_quality_matrix = bbox_overlaps_nearest_3d(\n                gt_bboxes_, anchors_)\n            _, matched = torch.topk(\n                match_quality_matrix,\n                self.pre_anchor_topk,\n                dim=1,\n                sorted=False)\n            del match_quality_matrix\n\n            # matched_cls_prob: P_{ij}^{cls}\n            matched_cls_prob = torch.gather(\n                cls_prob_[matched], 2,\n                gt_labels_.view(-1, 1, 1).repeat(1, self.pre_anchor_topk,\n                                                 1)).squeeze(2)\n\n            # matched_box_prob: P_{ij}^{loc}\n            matched_anchors = anchors_[matched]\n            matched_object_targets = self.bbox_coder.encode(\n                matched_anchors,\n                gt_bboxes_.unsqueeze(dim=1).expand_as(matched_anchors))\n\n            # direction classification loss\n            loss_dir = None\n            if self.use_direction_classifier:\n                # also calculate direction prob: P_{ij}^{dir}\n                matched_dir_targets = get_direction_target(\n                    matched_anchors,\n                    matched_object_targets,\n                    self.dir_offset,\n                    one_hot=False)\n                loss_dir = self.loss_dir(\n                    dir_cls_preds_[matched].transpose(-2, -1),\n                    matched_dir_targets,\n                    reduction_override='none')\n\n            # generate bbox weights\n            if self.diff_rad_by_sin:\n                bbox_preds_[matched], matched_object_targets = \\\n                    self.add_sin_difference(\n                        bbox_preds_[matched], matched_object_targets)\n            bbox_weights = matched_anchors.new_ones(matched_anchors.size())\n            # Use pop is not right, check performance\n            code_weight = self.train_cfg.get('code_weight', None)\n            if code_weight:\n                bbox_weights = bbox_weights * bbox_weights.new_tensor(\n                    code_weight)\n            loss_bbox = self.loss_bbox(\n                bbox_preds_[matched],\n                matched_object_targets,\n                bbox_weights,\n                reduction_override='none').sum(-1)\n\n            if loss_dir is not None:\n                loss_bbox += loss_dir\n            matched_box_prob = torch.exp(-loss_bbox)\n\n            # positive_losses: {-log( Mean-max(P_{ij}^{cls} * P_{ij}^{loc}) )}\n            num_pos += len(gt_bboxes_)\n            positive_losses.append(\n                self.positive_bag_loss(matched_cls_prob, matched_box_prob))\n\n        positive_loss = torch.cat(positive_losses).sum() / max(1, num_pos)\n\n        # box_prob: P{a_{j} \\in A_{+}}\n        box_prob = torch.stack(box_prob, dim=0)\n\n        # negative_loss:\n        # \\sum_{j}{ FL((1 - P{a_{j} \\in A_{+}}) * (1 - P_{j}^{bg})) } / n||B||\n        negative_loss = self.negative_bag_loss(cls_prob, box_prob).sum() / max(\n            1, num_pos * self.pre_anchor_topk)\n\n        losses = {\n            'positive_bag_loss': positive_loss,\n            'negative_bag_loss': negative_loss\n        }\n        return losses\n\n    def positive_bag_loss(self, matched_cls_prob, matched_box_prob):\n        \"\"\"Generate positive bag loss.\n\n        Args:\n            matched_cls_prob (torch.Tensor): Classification probability\n                of matched positive samples.\n            matched_box_prob (torch.Tensor): Bounding box probability\n                of matched positive samples.\n\n        Returns:\n            torch.Tensor: Loss of positive samples.\n        \"\"\"\n        # bag_prob = Mean-max(matched_prob)\n        matched_prob = matched_cls_prob * matched_box_prob\n        weight = 1 / torch.clamp(1 - matched_prob, 1e-12, None)\n        weight /= weight.sum(dim=1).unsqueeze(dim=-1)\n        bag_prob = (weight * matched_prob).sum(dim=1)\n        # positive_bag_loss = -self.alpha * log(bag_prob)\n        bag_prob = bag_prob.clamp(0, 1)  # to avoid bug of BCE, check\n        return self.alpha * F.binary_cross_entropy(\n            bag_prob, torch.ones_like(bag_prob), reduction='none')\n\n    def negative_bag_loss(self, cls_prob, box_prob):\n        \"\"\"Generate negative bag loss.\n\n        Args:\n            cls_prob (torch.Tensor): Classification probability\n                of negative samples.\n            box_prob (torch.Tensor): Bounding box probability\n                of negative samples.\n\n        Returns:\n            torch.Tensor: Loss of negative samples.\n        \"\"\"\n        prob = cls_prob * (1 - box_prob)\n        prob = prob.clamp(0, 1)  # to avoid bug of BCE, check\n        negative_bag_loss = prob**self.gamma * F.binary_cross_entropy(\n            prob, torch.zeros_like(prob), reduction='none')\n        return (1 - self.alpha) * negative_bag_loss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/ga_rpn_head.py",
    "content": "import copy\nimport warnings\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv import ConfigDict\nfrom mmcv.ops import nms\n\nfrom ..builder import HEADS\nfrom .guided_anchor_head import GuidedAnchorHead\n\n\n@HEADS.register_module()\nclass GARPNHead(GuidedAnchorHead):\n    \"\"\"Guided-Anchor-based RPN head.\"\"\"\n\n    def __init__(self,\n                 in_channels,\n                 init_cfg=dict(\n                     type='Normal',\n                     layer='Conv2d',\n                     std=0.01,\n                     override=dict(\n                         type='Normal',\n                         name='conv_loc',\n                         std=0.01,\n                         bias_prob=0.01)),\n                 **kwargs):\n        super(GARPNHead, self).__init__(\n            1, in_channels, init_cfg=init_cfg, **kwargs)\n\n    def _init_layers(self):\n        \"\"\"Initialize layers of the head.\"\"\"\n        self.rpn_conv = nn.Conv2d(\n            self.in_channels, self.feat_channels, 3, padding=1)\n        super(GARPNHead, self)._init_layers()\n\n    def forward_single(self, x):\n        \"\"\"Forward feature of a single scale level.\"\"\"\n\n        x = self.rpn_conv(x)\n        x = F.relu(x, inplace=True)\n        (cls_score, bbox_pred, shape_pred,\n         loc_pred) = super(GARPNHead, self).forward_single(x)\n        return cls_score, bbox_pred, shape_pred, loc_pred\n\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             shape_preds,\n             loc_preds,\n             gt_bboxes,\n             img_metas,\n             gt_bboxes_ignore=None):\n        losses = super(GARPNHead, self).loss(\n            cls_scores,\n            bbox_preds,\n            shape_preds,\n            loc_preds,\n            gt_bboxes,\n            None,\n            img_metas,\n            gt_bboxes_ignore=gt_bboxes_ignore)\n        return dict(\n            loss_rpn_cls=losses['loss_cls'],\n            loss_rpn_bbox=losses['loss_bbox'],\n            loss_anchor_shape=losses['loss_shape'],\n            loss_anchor_loc=losses['loss_loc'])\n\n    def _get_bboxes_single(self,\n                           cls_scores,\n                           bbox_preds,\n                           mlvl_anchors,\n                           mlvl_masks,\n                           img_shape,\n                           scale_factor,\n                           cfg,\n                           rescale=False):\n        cfg = self.test_cfg if cfg is None else cfg\n\n        cfg = copy.deepcopy(cfg)\n\n        # deprecate arguments warning\n        if 'nms' not in cfg or 'max_num' in cfg or 'nms_thr' in cfg:\n            warnings.warn(\n                'In rpn_proposal or test_cfg, '\n                'nms_thr has been moved to a dict named nms as '\n                'iou_threshold, max_num has been renamed as max_per_img, '\n                'name of original arguments and the way to specify '\n                'iou_threshold of NMS will be deprecated.')\n        if 'nms' not in cfg:\n            cfg.nms = ConfigDict(dict(type='nms', iou_threshold=cfg.nms_thr))\n        if 'max_num' in cfg:\n            if 'max_per_img' in cfg:\n                assert cfg.max_num == cfg.max_per_img, f'You ' \\\n                    f'set max_num and max_per_img at the same time, ' \\\n                    f'but get {cfg.max_num} ' \\\n                    f'and {cfg.max_per_img} respectively' \\\n                    'Please delete max_num which will be deprecated.'\n            else:\n                cfg.max_per_img = cfg.max_num\n        if 'nms_thr' in cfg:\n            assert cfg.nms.iou_threshold == cfg.nms_thr, f'You set ' \\\n                f'iou_threshold in nms and ' \\\n                f'nms_thr at the same time, but get ' \\\n                f'{cfg.nms.iou_threshold} and {cfg.nms_thr}' \\\n                f' respectively. Please delete the ' \\\n                f'nms_thr which will be deprecated.'\n\n        assert cfg.nms.get('type', 'nms') == 'nms', 'GARPNHead only support ' \\\n            'naive nms.'\n\n        mlvl_proposals = []\n        for idx in range(len(cls_scores)):\n            rpn_cls_score = cls_scores[idx]\n            rpn_bbox_pred = bbox_preds[idx]\n            anchors = mlvl_anchors[idx]\n            mask = mlvl_masks[idx]\n            assert rpn_cls_score.size()[-2:] == rpn_bbox_pred.size()[-2:]\n            # if no location is kept, end.\n            if mask.sum() == 0:\n                continue\n            rpn_cls_score = rpn_cls_score.permute(1, 2, 0)\n            if self.use_sigmoid_cls:\n                rpn_cls_score = rpn_cls_score.reshape(-1)\n                scores = rpn_cls_score.sigmoid()\n            else:\n                rpn_cls_score = rpn_cls_score.reshape(-1, 2)\n                # remind that we set FG labels to [0, num_class-1]\n                # since mmdet v2.0\n                # BG cat_id: num_class\n                scores = rpn_cls_score.softmax(dim=1)[:, :-1]\n            # filter scores, bbox_pred w.r.t. mask.\n            # anchors are filtered in get_anchors() beforehand.\n            scores = scores[mask]\n            rpn_bbox_pred = rpn_bbox_pred.permute(1, 2, 0).reshape(-1,\n                                                                   4)[mask, :]\n            if scores.dim() == 0:\n                rpn_bbox_pred = rpn_bbox_pred.unsqueeze(0)\n                anchors = anchors.unsqueeze(0)\n                scores = scores.unsqueeze(0)\n            # filter anchors, bbox_pred, scores w.r.t. scores\n            if cfg.nms_pre > 0 and scores.shape[0] > cfg.nms_pre:\n                _, topk_inds = scores.topk(cfg.nms_pre)\n                rpn_bbox_pred = rpn_bbox_pred[topk_inds, :]\n                anchors = anchors[topk_inds, :]\n                scores = scores[topk_inds]\n            # get proposals w.r.t. anchors and rpn_bbox_pred\n            proposals = self.bbox_coder.decode(\n                anchors, rpn_bbox_pred, max_shape=img_shape)\n            # filter out too small bboxes\n            if cfg.min_bbox_size >= 0:\n                w = proposals[:, 2] - proposals[:, 0]\n                h = proposals[:, 3] - proposals[:, 1]\n                valid_inds = torch.nonzero(\n                    (w > cfg.min_bbox_size) & (h > cfg.min_bbox_size),\n                    as_tuple=False).squeeze()\n                proposals = proposals[valid_inds, :]\n                scores = scores[valid_inds]\n            # NMS in current level\n            proposals, _ = nms(proposals, scores, cfg.nms.iou_threshold)\n            proposals = proposals[:cfg.nms_post, :]\n            mlvl_proposals.append(proposals)\n        proposals = torch.cat(mlvl_proposals, 0)\n        if cfg.get('nms_across_levels', False):\n            # NMS across multi levels\n            proposals, _ = nms(proposals[:, :4], proposals[:, -1],\n                               cfg.nms.iou_threshold)\n            proposals = proposals[:cfg.max_per_img, :]\n        else:\n            scores = proposals[:, 4]\n            num = min(cfg.max_per_img, proposals.shape[0])\n            _, topk_inds = scores.topk(num)\n            proposals = proposals[topk_inds, :]\n        return proposals\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/guided_anchor_head.py",
    "content": "import torch\nimport torch.nn as nn\n# from mmcv.ops import DeformConv2d, MaskedConv2d\nfrom mmcv.ops.deform_conv import DeformConv2d\nfrom mmcv.ops.masked_conv import MaskedConv2d\nfrom mmcv.models.backbones import BaseModule\nfrom mmcv.utils import force_fp32\n\n\nfrom mmcv.core.anchor import anchor_inside_flags, build_anchor_generator, images_to_levels, calc_region\nfrom mmcv.core.utils import multi_apply, reduce_mean, unmap\nfrom mmcv.core.bbox.builder import build_assigner, build_sampler\nfrom mmcv.core.post_processing.bbox_nms import multiclass_nms\nfrom ..builder import HEADS, build_loss\nfrom .anchor_head import AnchorHead\n\n\nclass FeatureAdaption(BaseModule):\n    \"\"\"Feature Adaption Module.\n\n    Feature Adaption Module is implemented based on DCN v1.\n    It uses anchor shape prediction rather than feature map to\n    predict offsets of deform conv layer.\n\n    Args:\n        in_channels (int): Number of channels in the input feature map.\n        out_channels (int): Number of channels in the output feature map.\n        kernel_size (int): Deformable conv kernel size.\n        deform_groups (int): Deformable conv group size.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n    \"\"\"\n\n    def __init__(self,\n                 in_channels,\n                 out_channels,\n                 kernel_size=3,\n                 deform_groups=4,\n                 init_cfg=dict(\n                     type='Normal',\n                     layer='Conv2d',\n                     std=0.1,\n                     override=dict(\n                         type='Normal', name='conv_adaption', std=0.01))):\n        super(FeatureAdaption, self).__init__(init_cfg)\n        offset_channels = kernel_size * kernel_size * 2\n        self.conv_offset = nn.Conv2d(\n            2, deform_groups * offset_channels, 1, bias=False)\n        self.conv_adaption = DeformConv2d(\n            in_channels,\n            out_channels,\n            kernel_size=kernel_size,\n            padding=(kernel_size - 1) // 2,\n            deform_groups=deform_groups)\n        self.relu = nn.ReLU(inplace=True)\n\n    def forward(self, x, shape):\n        offset = self.conv_offset(shape.detach())\n        x = self.relu(self.conv_adaption(x, offset))\n        return x\n\n\n@HEADS.register_module()\nclass GuidedAnchorHead(AnchorHead):\n    \"\"\"Guided-Anchor-based head (GA-RPN, GA-RetinaNet, etc.).\n\n    This GuidedAnchorHead will predict high-quality feature guided\n    anchors and locations where anchors will be kept in inference.\n    There are mainly 3 categories of bounding-boxes.\n\n    - Sampled 9 pairs for target assignment. (approxes)\n    - The square boxes where the predicted anchors are based on. (squares)\n    - Guided anchors.\n\n    Please refer to https://arxiv.org/abs/1901.03278 for more details.\n\n    Args:\n        num_classes (int): Number of classes.\n        in_channels (int): Number of channels in the input feature map.\n        feat_channels (int): Number of hidden channels.\n        approx_anchor_generator (dict): Config dict for approx generator\n        square_anchor_generator (dict): Config dict for square generator\n        anchor_coder (dict): Config dict for anchor coder\n        bbox_coder (dict): Config dict for bbox coder\n        reg_decoded_bbox (bool): If true, the regression loss would be\n            applied directly on decoded bounding boxes, converting both\n            the predicted boxes and regression targets to absolute\n            coordinates format. Default False. It should be `True` when\n            using `IoULoss`, `GIoULoss`, or `DIoULoss` in the bbox head.\n        deform_groups: (int): Group number of DCN in\n            FeatureAdaption module.\n        loc_filter_thr (float): Threshold to filter out unconcerned regions.\n        loss_loc (dict): Config of location loss.\n        loss_shape (dict): Config of anchor shape loss.\n        loss_cls (dict): Config of classification loss.\n        loss_bbox (dict): Config of bbox regression loss.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n    \"\"\"\n\n    def __init__(\n            self,\n            num_classes,\n            in_channels,\n            feat_channels=256,\n            approx_anchor_generator=dict(\n                type='AnchorGenerator',\n                octave_base_scale=8,\n                scales_per_octave=3,\n                ratios=[0.5, 1.0, 2.0],\n                strides=[4, 8, 16, 32, 64]),\n            square_anchor_generator=dict(\n                type='AnchorGenerator',\n                ratios=[1.0],\n                scales=[8],\n                strides=[4, 8, 16, 32, 64]),\n            anchor_coder=dict(\n                type='DeltaXYWHBBoxCoder',\n                target_means=[.0, .0, .0, .0],\n                target_stds=[1.0, 1.0, 1.0, 1.0]\n            ),\n            bbox_coder=dict(\n                type='DeltaXYWHBBoxCoder',\n                target_means=[.0, .0, .0, .0],\n                target_stds=[1.0, 1.0, 1.0, 1.0]\n            ),\n            reg_decoded_bbox=False,\n            deform_groups=4,\n            loc_filter_thr=0.01,\n            train_cfg=None,\n            test_cfg=None,\n            loss_loc=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0),\n            loss_shape=dict(type='BoundedIoULoss', beta=0.2, loss_weight=1.0),\n            loss_cls=dict(\n                type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),\n            loss_bbox=dict(type='SmoothL1Loss', beta=1.0,\n                           loss_weight=1.0),\n            init_cfg=dict(type='Normal', layer='Conv2d', std=0.01,\n                          override=dict(type='Normal',\n                                        name='conv_loc',\n                                        std=0.01,\n                                        bias_prob=0.01))):  # yapf: disable\n        super(AnchorHead, self).__init__(init_cfg)\n        self.in_channels = in_channels\n        self.num_classes = num_classes\n        self.feat_channels = feat_channels\n        self.deform_groups = deform_groups\n        self.loc_filter_thr = loc_filter_thr\n\n        # build approx_anchor_generator and square_anchor_generator\n        assert (approx_anchor_generator['octave_base_scale'] ==\n                square_anchor_generator['scales'][0])\n        assert (approx_anchor_generator['strides'] ==\n                square_anchor_generator['strides'])\n        self.approx_anchor_generator = build_anchor_generator(\n            approx_anchor_generator)\n        self.square_anchor_generator = build_anchor_generator(\n            square_anchor_generator)\n        self.approxs_per_octave = self.approx_anchor_generator \\\n            .num_base_anchors[0]\n\n        self.reg_decoded_bbox = reg_decoded_bbox\n\n        # one anchor per location\n        self.num_anchors = 1\n        self.use_sigmoid_cls = loss_cls.get('use_sigmoid', False)\n        self.loc_focal_loss = loss_loc['type'] in ['FocalLoss']\n        self.sampling = loss_cls['type'] not in ['FocalLoss']\n        self.ga_sampling = train_cfg is not None and hasattr(\n            train_cfg, 'ga_sampler')\n        if self.use_sigmoid_cls:\n            self.cls_out_channels = self.num_classes\n        else:\n            self.cls_out_channels = self.num_classes + 1\n\n        # build bbox_coder\n        self.anchor_coder = build_bbox_coder(anchor_coder)\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n\n        # build losses\n        self.loss_loc = build_loss(loss_loc)\n        self.loss_shape = build_loss(loss_shape)\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bbox = build_loss(loss_bbox)\n\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n\n        if self.train_cfg:\n            self.assigner = build_assigner(self.train_cfg.assigner)\n            # use PseudoSampler when sampling is False\n            if self.sampling and hasattr(self.train_cfg, 'sampler'):\n                sampler_cfg = self.train_cfg.sampler\n            else:\n                sampler_cfg = dict(type='PseudoSampler')\n            self.sampler = build_sampler(sampler_cfg, context=self)\n\n            self.ga_assigner = build_assigner(self.train_cfg.ga_assigner)\n            if self.ga_sampling:\n                ga_sampler_cfg = self.train_cfg.ga_sampler\n            else:\n                ga_sampler_cfg = dict(type='PseudoSampler')\n            self.ga_sampler = build_sampler(ga_sampler_cfg, context=self)\n\n        self.fp16_enabled = False\n\n        self._init_layers()\n\n    def _init_layers(self):\n        self.relu = nn.ReLU(inplace=True)\n        self.conv_loc = nn.Conv2d(self.in_channels, 1, 1)\n        self.conv_shape = nn.Conv2d(self.in_channels, self.num_anchors * 2, 1)\n        self.feature_adaption = FeatureAdaption(\n            self.in_channels,\n            self.feat_channels,\n            kernel_size=3,\n            deform_groups=self.deform_groups)\n        self.conv_cls = MaskedConv2d(self.feat_channels,\n                                     self.num_anchors * self.cls_out_channels,\n                                     1)\n        self.conv_reg = MaskedConv2d(self.feat_channels, self.num_anchors * 4,\n                                     1)\n\n    def forward_single(self, x):\n        loc_pred = self.conv_loc(x)\n        shape_pred = self.conv_shape(x)\n        x = self.feature_adaption(x, shape_pred)\n        # masked conv is only used during inference for speed-up\n        if not self.training:\n            mask = loc_pred.sigmoid()[0] >= self.loc_filter_thr\n        else:\n            mask = None\n        cls_score = self.conv_cls(x, mask)\n        bbox_pred = self.conv_reg(x, mask)\n        return cls_score, bbox_pred, shape_pred, loc_pred\n\n    def forward(self, feats):\n        return multi_apply(self.forward_single, feats)\n\n    def get_sampled_approxs(self, featmap_sizes, img_metas, device='cuda'):\n        \"\"\"Get sampled approxs and inside flags according to feature map sizes.\n\n        Args:\n            featmap_sizes (list[tuple]): Multi-level feature map sizes.\n            img_metas (list[dict]): Image meta info.\n            device (torch.device | str): device for returned tensors\n\n        Returns:\n            tuple: approxes of each image, inside flags of each image\n        \"\"\"\n        num_imgs = len(img_metas)\n\n        # since feature map sizes of all images are the same, we only compute\n        # approxes for one time\n        multi_level_approxs = self.approx_anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n        approxs_list = [multi_level_approxs for _ in range(num_imgs)]\n\n        # for each image, we compute inside flags of multi level approxes\n        inside_flag_list = []\n        for img_id, img_meta in enumerate(img_metas):\n            multi_level_flags = []\n            multi_level_approxs = approxs_list[img_id]\n\n            # obtain valid flags for each approx first\n            multi_level_approx_flags = self.approx_anchor_generator \\\n                .valid_flags(featmap_sizes,\n                             img_meta['pad_shape'],\n                             device=device)\n\n            for i, flags in enumerate(multi_level_approx_flags):\n                approxs = multi_level_approxs[i]\n                inside_flags_list = []\n                for i in range(self.approxs_per_octave):\n                    split_valid_flags = flags[i::self.approxs_per_octave]\n                    split_approxs = approxs[i::self.approxs_per_octave, :]\n                    inside_flags = anchor_inside_flags(\n                        split_approxs, split_valid_flags,\n                        img_meta['img_shape'][:2],\n                        self.train_cfg.allowed_border)\n                    inside_flags_list.append(inside_flags)\n                # inside_flag for a position is true if any anchor in this\n                # position is true\n                inside_flags = (\n                    torch.stack(inside_flags_list, 0).sum(dim=0) > 0)\n                multi_level_flags.append(inside_flags)\n            inside_flag_list.append(multi_level_flags)\n        return approxs_list, inside_flag_list\n\n    def get_anchors(self,\n                    featmap_sizes,\n                    shape_preds,\n                    loc_preds,\n                    img_metas,\n                    use_loc_filter=False,\n                    device='cuda'):\n        \"\"\"Get squares according to feature map sizes and guided anchors.\n\n        Args:\n            featmap_sizes (list[tuple]): Multi-level feature map sizes.\n            shape_preds (list[tensor]): Multi-level shape predictions.\n            loc_preds (list[tensor]): Multi-level location predictions.\n            img_metas (list[dict]): Image meta info.\n            use_loc_filter (bool): Use loc filter or not.\n            device (torch.device | str): device for returned tensors\n\n        Returns:\n            tuple: square approxs of each image, guided anchors of each image,\n                loc masks of each image\n        \"\"\"\n        num_imgs = len(img_metas)\n        num_levels = len(featmap_sizes)\n\n        # since feature map sizes of all images are the same, we only compute\n        # squares for one time\n        multi_level_squares = self.square_anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n        squares_list = [multi_level_squares for _ in range(num_imgs)]\n\n        # for each image, we compute multi level guided anchors\n        guided_anchors_list = []\n        loc_mask_list = []\n        for img_id, img_meta in enumerate(img_metas):\n            multi_level_guided_anchors = []\n            multi_level_loc_mask = []\n            for i in range(num_levels):\n                squares = squares_list[img_id][i]\n                shape_pred = shape_preds[i][img_id]\n                loc_pred = loc_preds[i][img_id]\n                guided_anchors, loc_mask = self._get_guided_anchors_single(\n                    squares,\n                    shape_pred,\n                    loc_pred,\n                    use_loc_filter=use_loc_filter)\n                multi_level_guided_anchors.append(guided_anchors)\n                multi_level_loc_mask.append(loc_mask)\n            guided_anchors_list.append(multi_level_guided_anchors)\n            loc_mask_list.append(multi_level_loc_mask)\n        return squares_list, guided_anchors_list, loc_mask_list\n\n    def _get_guided_anchors_single(self,\n                                   squares,\n                                   shape_pred,\n                                   loc_pred,\n                                   use_loc_filter=False):\n        \"\"\"Get guided anchors and loc masks for a single level.\n\n        Args:\n            square (tensor): Squares of a single level.\n            shape_pred (tensor): Shape predictions of a single level.\n            loc_pred (tensor): Loc predictions of a single level.\n            use_loc_filter (list[tensor]): Use loc filter or not.\n\n        Returns:\n            tuple: guided anchors, location masks\n        \"\"\"\n        # calculate location filtering mask\n        loc_pred = loc_pred.sigmoid().detach()\n        if use_loc_filter:\n            loc_mask = loc_pred >= self.loc_filter_thr\n        else:\n            loc_mask = loc_pred >= 0.0\n        mask = loc_mask.permute(1, 2, 0).expand(-1, -1, self.num_anchors)\n        mask = mask.contiguous().view(-1)\n        # calculate guided anchors\n        squares = squares[mask]\n        anchor_deltas = shape_pred.permute(1, 2, 0).contiguous().view(\n            -1, 2).detach()[mask]\n        bbox_deltas = anchor_deltas.new_full(squares.size(), 0)\n        bbox_deltas[:, 2:] = anchor_deltas\n        guided_anchors = self.anchor_coder.decode(\n            squares, bbox_deltas, wh_ratio_clip=1e-6)\n        return guided_anchors, mask\n\n    def ga_loc_targets(self, gt_bboxes_list, featmap_sizes):\n        \"\"\"Compute location targets for guided anchoring.\n\n        Each feature map is divided into positive, negative and ignore regions.\n        - positive regions: target 1, weight 1\n        - ignore regions: target 0, weight 0\n        - negative regions: target 0, weight 0.1\n\n        Args:\n            gt_bboxes_list (list[Tensor]): Gt bboxes of each image.\n            featmap_sizes (list[tuple]): Multi level sizes of each feature\n                maps.\n\n        Returns:\n            tuple\n        \"\"\"\n        anchor_scale = self.approx_anchor_generator.octave_base_scale\n        anchor_strides = self.approx_anchor_generator.strides\n        # Currently only supports same stride in x and y direction.\n        for stride in anchor_strides:\n            assert (stride[0] == stride[1])\n        anchor_strides = [stride[0] for stride in anchor_strides]\n\n        center_ratio = self.train_cfg.center_ratio\n        ignore_ratio = self.train_cfg.ignore_ratio\n        img_per_gpu = len(gt_bboxes_list)\n        num_lvls = len(featmap_sizes)\n        r1 = (1 - center_ratio) / 2\n        r2 = (1 - ignore_ratio) / 2\n        all_loc_targets = []\n        all_loc_weights = []\n        all_ignore_map = []\n        for lvl_id in range(num_lvls):\n            h, w = featmap_sizes[lvl_id]\n            loc_targets = torch.zeros(\n                img_per_gpu,\n                1,\n                h,\n                w,\n                device=gt_bboxes_list[0].device,\n                dtype=torch.float32)\n            loc_weights = torch.full_like(loc_targets, -1)\n            ignore_map = torch.zeros_like(loc_targets)\n            all_loc_targets.append(loc_targets)\n            all_loc_weights.append(loc_weights)\n            all_ignore_map.append(ignore_map)\n        for img_id in range(img_per_gpu):\n            gt_bboxes = gt_bboxes_list[img_id]\n            scale = torch.sqrt((gt_bboxes[:, 2] - gt_bboxes[:, 0]) *\n                               (gt_bboxes[:, 3] - gt_bboxes[:, 1]))\n            min_anchor_size = scale.new_full(\n                (1, ), float(anchor_scale * anchor_strides[0]))\n            # assign gt bboxes to different feature levels w.r.t. their scales\n            target_lvls = torch.floor(\n                torch.log2(scale) - torch.log2(min_anchor_size) + 0.5)\n            target_lvls = target_lvls.clamp(min=0, max=num_lvls - 1).long()\n            for gt_id in range(gt_bboxes.size(0)):\n                lvl = target_lvls[gt_id].item()\n                # rescaled to corresponding feature map\n                gt_ = gt_bboxes[gt_id, :4] / anchor_strides[lvl]\n                # calculate ignore regions\n                ignore_x1, ignore_y1, ignore_x2, ignore_y2 = calc_region(\n                    gt_, r2, featmap_sizes[lvl])\n                # calculate positive (center) regions\n                ctr_x1, ctr_y1, ctr_x2, ctr_y2 = calc_region(\n                    gt_, r1, featmap_sizes[lvl])\n                all_loc_targets[lvl][img_id, 0, ctr_y1:ctr_y2 + 1,\n                                     ctr_x1:ctr_x2 + 1] = 1\n                all_loc_weights[lvl][img_id, 0, ignore_y1:ignore_y2 + 1,\n                                     ignore_x1:ignore_x2 + 1] = 0\n                all_loc_weights[lvl][img_id, 0, ctr_y1:ctr_y2 + 1,\n                                     ctr_x1:ctr_x2 + 1] = 1\n                # calculate ignore map on nearby low level feature\n                if lvl > 0:\n                    d_lvl = lvl - 1\n                    # rescaled to corresponding feature map\n                    gt_ = gt_bboxes[gt_id, :4] / anchor_strides[d_lvl]\n                    ignore_x1, ignore_y1, ignore_x2, ignore_y2 = calc_region(\n                        gt_, r2, featmap_sizes[d_lvl])\n                    all_ignore_map[d_lvl][img_id, 0, ignore_y1:ignore_y2 + 1,\n                                          ignore_x1:ignore_x2 + 1] = 1\n                # calculate ignore map on nearby high level feature\n                if lvl < num_lvls - 1:\n                    u_lvl = lvl + 1\n                    # rescaled to corresponding feature map\n                    gt_ = gt_bboxes[gt_id, :4] / anchor_strides[u_lvl]\n                    ignore_x1, ignore_y1, ignore_x2, ignore_y2 = calc_region(\n                        gt_, r2, featmap_sizes[u_lvl])\n                    all_ignore_map[u_lvl][img_id, 0, ignore_y1:ignore_y2 + 1,\n                                          ignore_x1:ignore_x2 + 1] = 1\n        for lvl_id in range(num_lvls):\n            # ignore negative regions w.r.t. ignore map\n            all_loc_weights[lvl_id][(all_loc_weights[lvl_id] < 0)\n                                    & (all_ignore_map[lvl_id] > 0)] = 0\n            # set negative regions with weight 0.1\n            all_loc_weights[lvl_id][all_loc_weights[lvl_id] < 0] = 0.1\n        # loc average factor to balance loss\n        loc_avg_factor = sum(\n            [t.size(0) * t.size(-1) * t.size(-2)\n             for t in all_loc_targets]) / 200\n        return all_loc_targets, all_loc_weights, loc_avg_factor\n\n    def _ga_shape_target_single(self,\n                                flat_approxs,\n                                inside_flags,\n                                flat_squares,\n                                gt_bboxes,\n                                gt_bboxes_ignore,\n                                img_meta,\n                                unmap_outputs=True):\n        \"\"\"Compute guided anchoring targets.\n\n        This function returns sampled anchors and gt bboxes directly\n        rather than calculates regression targets.\n\n        Args:\n            flat_approxs (Tensor): flat approxs of a single image,\n                shape (n, 4)\n            inside_flags (Tensor): inside flags of a single image,\n                shape (n, ).\n            flat_squares (Tensor): flat squares of a single image,\n                shape (approxs_per_octave * n, 4)\n            gt_bboxes (Tensor): Ground truth bboxes of a single image.\n            img_meta (dict): Meta info of a single image.\n            approxs_per_octave (int): number of approxs per octave\n            cfg (dict): RPN train configs.\n            unmap_outputs (bool): unmap outputs or not.\n\n        Returns:\n            tuple\n        \"\"\"\n        if not inside_flags.any():\n            return (None, ) * 5\n        # assign gt and sample anchors\n        expand_inside_flags = inside_flags[:, None].expand(\n            -1, self.approxs_per_octave).reshape(-1)\n        approxs = flat_approxs[expand_inside_flags, :]\n        squares = flat_squares[inside_flags, :]\n\n        assign_result = self.ga_assigner.assign(approxs, squares,\n                                                self.approxs_per_octave,\n                                                gt_bboxes, gt_bboxes_ignore)\n        sampling_result = self.ga_sampler.sample(assign_result, squares,\n                                                 gt_bboxes)\n\n        bbox_anchors = torch.zeros_like(squares)\n        bbox_gts = torch.zeros_like(squares)\n        bbox_weights = torch.zeros_like(squares)\n\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n        if len(pos_inds) > 0:\n            bbox_anchors[pos_inds, :] = sampling_result.pos_bboxes\n            bbox_gts[pos_inds, :] = sampling_result.pos_gt_bboxes\n            bbox_weights[pos_inds, :] = 1.0\n\n        # map up to original set of anchors\n        if unmap_outputs:\n            num_total_anchors = flat_squares.size(0)\n            bbox_anchors = unmap(bbox_anchors, num_total_anchors, inside_flags)\n            bbox_gts = unmap(bbox_gts, num_total_anchors, inside_flags)\n            bbox_weights = unmap(bbox_weights, num_total_anchors, inside_flags)\n\n        return (bbox_anchors, bbox_gts, bbox_weights, pos_inds, neg_inds)\n\n    def ga_shape_targets(self,\n                         approx_list,\n                         inside_flag_list,\n                         square_list,\n                         gt_bboxes_list,\n                         img_metas,\n                         gt_bboxes_ignore_list=None,\n                         unmap_outputs=True):\n        \"\"\"Compute guided anchoring targets.\n\n        Args:\n            approx_list (list[list]): Multi level approxs of each image.\n            inside_flag_list (list[list]): Multi level inside flags of each\n                image.\n            square_list (list[list]): Multi level squares of each image.\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes of each image.\n            img_metas (list[dict]): Meta info of each image.\n            gt_bboxes_ignore_list (list[Tensor]): ignore list of gt bboxes.\n            unmap_outputs (bool): unmap outputs or not.\n\n        Returns:\n            tuple\n        \"\"\"\n        num_imgs = len(img_metas)\n        assert len(approx_list) == len(inside_flag_list) == len(\n            square_list) == num_imgs\n        # anchor number of multi levels\n        num_level_squares = [squares.size(0) for squares in square_list[0]]\n        # concat all level anchors and flags to a single tensor\n        inside_flag_flat_list = []\n        approx_flat_list = []\n        square_flat_list = []\n        for i in range(num_imgs):\n            assert len(square_list[i]) == len(inside_flag_list[i])\n            inside_flag_flat_list.append(torch.cat(inside_flag_list[i]))\n            approx_flat_list.append(torch.cat(approx_list[i]))\n            square_flat_list.append(torch.cat(square_list[i]))\n\n        # compute targets for each image\n        if gt_bboxes_ignore_list is None:\n            gt_bboxes_ignore_list = [None for _ in range(num_imgs)]\n        (all_bbox_anchors, all_bbox_gts, all_bbox_weights, pos_inds_list,\n         neg_inds_list) = multi_apply(\n             self._ga_shape_target_single,\n             approx_flat_list,\n             inside_flag_flat_list,\n             square_flat_list,\n             gt_bboxes_list,\n             gt_bboxes_ignore_list,\n             img_metas,\n             unmap_outputs=unmap_outputs)\n        # no valid anchors\n        if any([bbox_anchors is None for bbox_anchors in all_bbox_anchors]):\n            return None\n        # sampled anchors of all images\n        num_total_pos = sum([max(inds.numel(), 1) for inds in pos_inds_list])\n        num_total_neg = sum([max(inds.numel(), 1) for inds in neg_inds_list])\n        # split targets to a list w.r.t. multiple levels\n        bbox_anchors_list = images_to_levels(all_bbox_anchors,\n                                             num_level_squares)\n        bbox_gts_list = images_to_levels(all_bbox_gts, num_level_squares)\n        bbox_weights_list = images_to_levels(all_bbox_weights,\n                                             num_level_squares)\n        return (bbox_anchors_list, bbox_gts_list, bbox_weights_list,\n                num_total_pos, num_total_neg)\n\n    def loss_shape_single(self, shape_pred, bbox_anchors, bbox_gts,\n                          anchor_weights, anchor_total_num):\n        shape_pred = shape_pred.permute(0, 2, 3, 1).contiguous().view(-1, 2)\n        bbox_anchors = bbox_anchors.contiguous().view(-1, 4)\n        bbox_gts = bbox_gts.contiguous().view(-1, 4)\n        anchor_weights = anchor_weights.contiguous().view(-1, 4)\n        bbox_deltas = bbox_anchors.new_full(bbox_anchors.size(), 0)\n        bbox_deltas[:, 2:] += shape_pred\n        # filter out negative samples to speed-up weighted_bounded_iou_loss\n        inds = torch.nonzero(\n            anchor_weights[:, 0] > 0, as_tuple=False).squeeze(1)\n        bbox_deltas_ = bbox_deltas[inds]\n        bbox_anchors_ = bbox_anchors[inds]\n        bbox_gts_ = bbox_gts[inds]\n        anchor_weights_ = anchor_weights[inds]\n        pred_anchors_ = self.anchor_coder.decode(\n            bbox_anchors_, bbox_deltas_, wh_ratio_clip=1e-6)\n        loss_shape = self.loss_shape(\n            pred_anchors_,\n            bbox_gts_,\n            anchor_weights_,\n            avg_factor=anchor_total_num)\n        return loss_shape\n\n    def loss_loc_single(self, loc_pred, loc_target, loc_weight,\n                        loc_avg_factor):\n        loss_loc = self.loss_loc(\n            loc_pred.reshape(-1, 1),\n            loc_target.reshape(-1).long(),\n            loc_weight.reshape(-1),\n            avg_factor=loc_avg_factor)\n        return loss_loc\n\n    @force_fp32(\n        apply_to=('cls_scores', 'bbox_preds', 'shape_preds', 'loc_preds'))\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             shape_preds,\n             loc_preds,\n             gt_bboxes,\n             gt_labels,\n             img_metas,\n             gt_bboxes_ignore=None):\n        featmap_sizes = [featmap.size()[-2:] for featmap in cls_scores]\n        assert len(featmap_sizes) == self.approx_anchor_generator.num_levels\n\n        device = cls_scores[0].device\n\n        # get loc targets\n        loc_targets, loc_weights, loc_avg_factor = self.ga_loc_targets(\n            gt_bboxes, featmap_sizes)\n\n        # get sampled approxes\n        approxs_list, inside_flag_list = self.get_sampled_approxs(\n            featmap_sizes, img_metas, device=device)\n        # get squares and guided anchors\n        squares_list, guided_anchors_list, _ = self.get_anchors(\n            featmap_sizes, shape_preds, loc_preds, img_metas, device=device)\n\n        # get shape targets\n        shape_targets = self.ga_shape_targets(approxs_list, inside_flag_list,\n                                              squares_list, gt_bboxes,\n                                              img_metas)\n        if shape_targets is None:\n            return None\n        (bbox_anchors_list, bbox_gts_list, anchor_weights_list, anchor_fg_num,\n         anchor_bg_num) = shape_targets\n        anchor_total_num = (\n            anchor_fg_num if not self.ga_sampling else anchor_fg_num +\n            anchor_bg_num)\n\n        # get anchor targets\n        label_channels = self.cls_out_channels if self.use_sigmoid_cls else 1\n        cls_reg_targets = self.get_targets(\n            guided_anchors_list,\n            inside_flag_list,\n            gt_bboxes,\n            img_metas,\n            gt_bboxes_ignore_list=gt_bboxes_ignore,\n            gt_labels_list=gt_labels,\n            label_channels=label_channels)\n        if cls_reg_targets is None:\n            return None\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n        num_total_samples = (\n            num_total_pos + num_total_neg if self.sampling else num_total_pos)\n\n        # anchor number of multi levels\n        num_level_anchors = [\n            anchors.size(0) for anchors in guided_anchors_list[0]\n        ]\n        # concat all level anchors to a single tensor\n        concat_anchor_list = []\n        for i in range(len(guided_anchors_list)):\n            concat_anchor_list.append(torch.cat(guided_anchors_list[i]))\n        all_anchor_list = images_to_levels(concat_anchor_list,\n                                           num_level_anchors)\n\n        # get classification and bbox regression losses\n        losses_cls, losses_bbox = multi_apply(\n            self.loss_single,\n            cls_scores,\n            bbox_preds,\n            all_anchor_list,\n            labels_list,\n            label_weights_list,\n            bbox_targets_list,\n            bbox_weights_list,\n            num_total_samples=num_total_samples)\n\n        # get anchor location loss\n        losses_loc = []\n        for i in range(len(loc_preds)):\n            loss_loc = self.loss_loc_single(\n                loc_preds[i],\n                loc_targets[i],\n                loc_weights[i],\n                loc_avg_factor=loc_avg_factor)\n            losses_loc.append(loss_loc)\n\n        # get anchor shape loss\n        losses_shape = []\n        for i in range(len(shape_preds)):\n            loss_shape = self.loss_shape_single(\n                shape_preds[i],\n                bbox_anchors_list[i],\n                bbox_gts_list[i],\n                anchor_weights_list[i],\n                anchor_total_num=anchor_total_num)\n            losses_shape.append(loss_shape)\n\n        return dict(\n            loss_cls=losses_cls,\n            loss_bbox=losses_bbox,\n            loss_shape=losses_shape,\n            loss_loc=losses_loc)\n\n    @force_fp32(\n        apply_to=('cls_scores', 'bbox_preds', 'shape_preds', 'loc_preds'))\n    def get_bboxes(self,\n                   cls_scores,\n                   bbox_preds,\n                   shape_preds,\n                   loc_preds,\n                   img_metas,\n                   cfg=None,\n                   rescale=False):\n        assert len(cls_scores) == len(bbox_preds) == len(shape_preds) == len(\n            loc_preds)\n        num_levels = len(cls_scores)\n        featmap_sizes = [featmap.size()[-2:] for featmap in cls_scores]\n        device = cls_scores[0].device\n        # get guided anchors\n        _, guided_anchors, loc_masks = self.get_anchors(\n            featmap_sizes,\n            shape_preds,\n            loc_preds,\n            img_metas,\n            use_loc_filter=not self.training,\n            device=device)\n        result_list = []\n        for img_id in range(len(img_metas)):\n            cls_score_list = [\n                cls_scores[i][img_id].detach() for i in range(num_levels)\n            ]\n            bbox_pred_list = [\n                bbox_preds[i][img_id].detach() for i in range(num_levels)\n            ]\n            guided_anchor_list = [\n                guided_anchors[img_id][i].detach() for i in range(num_levels)\n            ]\n            loc_mask_list = [\n                loc_masks[img_id][i].detach() for i in range(num_levels)\n            ]\n            img_shape = img_metas[img_id]['img_shape']\n            scale_factor = img_metas[img_id]['scale_factor']\n            proposals = self._get_bboxes_single(cls_score_list, bbox_pred_list,\n                                                guided_anchor_list,\n                                                loc_mask_list, img_shape,\n                                                scale_factor, cfg, rescale)\n            result_list.append(proposals)\n        return result_list\n\n    def _get_bboxes_single(self,\n                           cls_scores,\n                           bbox_preds,\n                           mlvl_anchors,\n                           mlvl_masks,\n                           img_shape,\n                           scale_factor,\n                           cfg,\n                           rescale=False):\n        cfg = self.test_cfg if cfg is None else cfg\n        assert len(cls_scores) == len(bbox_preds) == len(mlvl_anchors)\n        mlvl_bboxes = []\n        mlvl_scores = []\n        for cls_score, bbox_pred, anchors, mask in zip(cls_scores, bbox_preds,\n                                                       mlvl_anchors,\n                                                       mlvl_masks):\n            assert cls_score.size()[-2:] == bbox_pred.size()[-2:]\n            # if no location is kept, end.\n            if mask.sum() == 0:\n                continue\n            # reshape scores and bbox_pred\n            cls_score = cls_score.permute(1, 2,\n                                          0).reshape(-1, self.cls_out_channels)\n            if self.use_sigmoid_cls:\n                scores = cls_score.sigmoid()\n            else:\n                scores = cls_score.softmax(-1)\n            bbox_pred = bbox_pred.permute(1, 2, 0).reshape(-1, 4)\n            # filter scores, bbox_pred w.r.t. mask.\n            # anchors are filtered in get_anchors() beforehand.\n            scores = scores[mask, :]\n            bbox_pred = bbox_pred[mask, :]\n            if scores.dim() == 0:\n                anchors = anchors.unsqueeze(0)\n                scores = scores.unsqueeze(0)\n                bbox_pred = bbox_pred.unsqueeze(0)\n            # filter anchors, bbox_pred, scores w.r.t. scores\n            nms_pre = cfg.get('nms_pre', -1)\n            if nms_pre > 0 and scores.shape[0] > nms_pre:\n                if self.use_sigmoid_cls:\n                    max_scores, _ = scores.max(dim=1)\n                else:\n                    # remind that we set FG labels to [0, num_class-1]\n                    # since mmcv v2.0\n                    # BG cat_id: num_class\n                    max_scores, _ = scores[:, :-1].max(dim=1)\n                _, topk_inds = max_scores.topk(nms_pre)\n                anchors = anchors[topk_inds, :]\n                bbox_pred = bbox_pred[topk_inds, :]\n                scores = scores[topk_inds, :]\n            bboxes = self.bbox_coder.decode(\n                anchors, bbox_pred, max_shape=img_shape)\n            mlvl_bboxes.append(bboxes)\n            mlvl_scores.append(scores)\n        mlvl_bboxes = torch.cat(mlvl_bboxes)\n        if rescale:\n            mlvl_bboxes /= mlvl_bboxes.new_tensor(scale_factor)\n        mlvl_scores = torch.cat(mlvl_scores)\n        if self.use_sigmoid_cls:\n            # Add a dummy background class to the backend when using sigmoid\n            # remind that we set FG labels to [0, num_class-1] since mmcv v2.0\n            # BG cat_id: num_class\n            padding = mlvl_scores.new_zeros(mlvl_scores.shape[0], 1)\n            mlvl_scores = torch.cat([mlvl_scores, padding], dim=1)\n        # multi class NMS\n        det_bboxes, det_labels = multiclass_nms(mlvl_bboxes, mlvl_scores,\n                                                cfg.score_thr, cfg.nms,\n                                                cfg.max_per_img)\n        return det_bboxes, det_labels\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport copy\nfrom mmcv.models import HEADS\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom mmcv.models.utils.functional import (\n    bivariate_gaussian_activation,\n    norm_points,\n    pos2posemb2d,\n    anchor_coordinate_transform\n)\nfrom .motion_head_plugin.motion_utils import nonlinear_smoother\nfrom .motion_head_plugin.base_motion_head import BaseMotionHead\n\n\n@HEADS.register_module()\nclass MotionHead(BaseMotionHead):\n    \"\"\"\n    MotionHead module for a neural network, which predicts motion trajectories and is used in an autonomous driving task.\n\n    Args:\n        *args: Variable length argument list.\n        predict_steps (int): The number of steps to predict motion trajectories.\n        transformerlayers (dict): A dictionary defining the configuration of transformer layers.\n        bbox_coder: An instance of a bbox coder to be used for encoding/decoding boxes.\n        num_cls_fcs (int): The number of fully-connected layers in the classification branch.\n        bev_h (int): The height of the bird's-eye-view map.\n        bev_w (int): The width of the bird's-eye-view map.\n        embed_dims (int): The number of dimensions to use for the query and key vectors in transformer layers.\n        num_anchor (int): The number of anchor points.\n        det_layer_num (int): The number of layers in the transformer model.\n        group_id_list (list): A list of group IDs to use for grouping the classes.\n        pc_range: The range of the point cloud.\n        use_nonlinear_optimizer (bool): A boolean indicating whether to use a non-linear optimizer for training.\n        anchor_info_path (str): The path to the file containing the anchor information.\n        vehicle_id_list(list[int]): class id of vehicle class, used for filtering out non-vehicle objects\n    \"\"\"\n    def __init__(self,\n                 *args,\n                 predict_steps=12,\n                 transformerlayers=None,\n                 bbox_coder=None,\n                 num_cls_fcs=2,\n                 bev_h=30,\n                 bev_w=30,\n                 embed_dims=256,\n                 num_anchor=6,\n                 det_layer_num=6,\n                 group_id_list=[],\n                 pc_range=None,\n                 use_nonlinear_optimizer=False,\n                 anchor_info_path=None,\n                 loss_traj=dict(),\n                 num_classes=0,\n                 vehicle_id_list=[0, 1, 2, 3, 4, 6, 7],\n                 **kwargs):\n        super(MotionHead, self).__init__()\n        \n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.num_cls_fcs = num_cls_fcs - 1\n        self.num_reg_fcs = num_cls_fcs - 1\n        self.embed_dims = embed_dims        \n        self.num_anchor = num_anchor\n        self.num_anchor_group = len(group_id_list)\n        \n        # we merge the classes into groups for anchor assignment\n        self.cls2group = [0 for i in range(num_classes)]\n        for i, grouped_ids in enumerate(group_id_list):\n            for gid in grouped_ids:\n                self.cls2group[gid] = i\n        self.cls2group = torch.tensor(self.cls2group)\n        self.pc_range = pc_range\n        self.predict_steps = predict_steps\n        self.vehicle_id_list = vehicle_id_list\n        \n        self.use_nonlinear_optimizer = use_nonlinear_optimizer\n        self._load_anchors(anchor_info_path)\n        self._build_loss(loss_traj)\n        self._build_layers(transformerlayers, det_layer_num)\n        self._init_layers()\n\n    def forward_train(self,\n                      bev_embed,\n                      gt_bboxes_3d,\n                      gt_labels_3d,\n                      gt_fut_traj=None,\n                      gt_fut_traj_mask=None,\n                      gt_sdc_fut_traj=None, \n                      gt_sdc_fut_traj_mask=None, \n                      outs_track={},\n                      outs_seg={}\n                  ):\n        \"\"\"Forward function\n        Args:\n            bev_embed (Tensor): BEV feature map with the shape of [B, C, H, W].\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`]): Ground truth \\\n                bboxes of each sample.\n            gt_labels_3d (list[torch.Tensor]): Labels of each sample.\n            img_metas (list[dict]): Meta information of each sample.\n            gt_fut_traj (list[torch.Tensor]): Ground truth future trajectory of each sample.\n            gt_fut_traj_mask (list[torch.Tensor]): Ground truth future trajectory mask of each sample.\n            gt_sdc_fut_traj (list[torch.Tensor]): Ground truth future trajectory of each sample.\n            gt_sdc_fut_traj_mask (list[torch.Tensor]): Ground truth future trajectory mask of each sample.\n            outs_track (dict): Outputs of track head.\n            outs_seg (dict): Outputs of seg head.\n            future_states (list[torch.Tensor]): Ground truth future states of each sample.\n        Returns:\n            dict: Losses of each branch.\n        \"\"\"\n        track_query = outs_track['track_query_embeddings'][None, None, ...] # num_dec, B, A_track, D\n        all_matched_idxes = [outs_track['track_query_matched_idxes']] #BxN\n        track_boxes = outs_track['track_bbox_results']\n        \n        # cat sdc query/gt to the last\n        sdc_match_index = torch.zeros((1,), dtype=all_matched_idxes[0].dtype, device=all_matched_idxes[0].device)\n        sdc_match_index[0] = gt_fut_traj[0].shape[0]\n        all_matched_idxes = [torch.cat([all_matched_idxes[0], sdc_match_index], dim=0)]\n        gt_fut_traj[0] = torch.cat([gt_fut_traj[0], gt_sdc_fut_traj[0]], dim=0)\n        gt_fut_traj_mask[0] = torch.cat([gt_fut_traj_mask[0], gt_sdc_fut_traj_mask[0]], dim=0)\n        track_query = torch.cat([track_query, outs_track['sdc_embedding'][None, None, None, :]], dim=2)\n        sdc_track_boxes = outs_track['sdc_track_bbox_results']\n        track_boxes[0][0].tensor = torch.cat([track_boxes[0][0].tensor, sdc_track_boxes[0][0].tensor], dim=0)\n        track_boxes[0][1] = torch.cat([track_boxes[0][1], sdc_track_boxes[0][1]], dim=0)\n        track_boxes[0][2] = torch.cat([track_boxes[0][2], sdc_track_boxes[0][2]], dim=0)\n        track_boxes[0][3] = torch.cat([track_boxes[0][3], sdc_track_boxes[0][3]], dim=0)\n        \n        memory, memory_mask, memory_pos, lane_query, _, lane_query_pos, hw_lvl = outs_seg['args_tuple']\n\n        outs_motion = self(bev_embed, track_query, lane_query, lane_query_pos, track_boxes)\n        loss_inputs = [gt_bboxes_3d, gt_fut_traj, gt_fut_traj_mask, outs_motion, all_matched_idxes, track_boxes]\n        losses = self.loss(*loss_inputs)\n\n        def filter_vehicle_query(outs_motion, all_matched_idxes, gt_labels_3d, vehicle_id_list):\n            query_label = gt_labels_3d[0][-1][all_matched_idxes[0]]\n            # select vehicle query according to vehicle_id_list\n            vehicle_mask = torch.zeros_like(query_label)\n            for veh_id in vehicle_id_list:\n                vehicle_mask |=  query_label == veh_id\n            outs_motion['traj_query'] = outs_motion['traj_query'][:, :, vehicle_mask>0]\n            outs_motion['track_query'] = outs_motion['track_query'][:, vehicle_mask>0]\n            outs_motion['track_query_pos'] = outs_motion['track_query_pos'][:, vehicle_mask>0]\n            all_matched_idxes[0] = all_matched_idxes[0][vehicle_mask>0]\n            return outs_motion, all_matched_idxes\n\n        all_matched_idxes[0] = all_matched_idxes[0][:-1]\n        outs_motion['sdc_traj_query'] = outs_motion['traj_query'][:, :, -1]         # [3, 1, 6, 256]     [n_dec, b, n_mode, d]\n        outs_motion['sdc_track_query'] = outs_motion['track_query'][:, -1]          # [1, 256]           [b, d]\n        outs_motion['sdc_track_query_pos'] = outs_motion['track_query_pos'][:, -1]  # [1, 256]           [b, d]\n        outs_motion['traj_query'] = outs_motion['traj_query'][:, :, :-1]            # [3, 1, 3, 6, 256]  [n_dec, b, nq, n_mode, d]\n        outs_motion['track_query'] = outs_motion['track_query'][:, :-1]             # [1, 3, 256]        [b, nq, d]   \n        outs_motion['track_query_pos'] = outs_motion['track_query_pos'][:, :-1]     # [1, 3, 256]        [b, nq, d]  \n\n        \n        outs_motion, all_matched_idxes = filter_vehicle_query(outs_motion, all_matched_idxes, gt_labels_3d, self.vehicle_id_list)\n        outs_motion['all_matched_idxes'] = all_matched_idxes\n\n        ret_dict = dict(losses=losses, outs_motion=outs_motion, track_boxes=track_boxes)\n        return ret_dict\n\n    def forward_test(self, bev_embed, outs_track={}, outs_seg={}):\n        \"\"\"Test function\"\"\"\n        track_query = outs_track['track_query_embeddings'][None, None, ...]\n        track_boxes = outs_track['track_bbox_results']\n        \n        track_query = torch.cat([track_query, outs_track['sdc_embedding'][None, None, None, :]], dim=2)\n        sdc_track_boxes = outs_track['sdc_track_bbox_results']\n\n        track_boxes[0][0].tensor = torch.cat([track_boxes[0][0].tensor, sdc_track_boxes[0][0].tensor], dim=0)\n        track_boxes[0][1] = torch.cat([track_boxes[0][1], sdc_track_boxes[0][1]], dim=0)\n        track_boxes[0][2] = torch.cat([track_boxes[0][2], sdc_track_boxes[0][2]], dim=0)\n        track_boxes[0][3] = torch.cat([track_boxes[0][3], sdc_track_boxes[0][3]], dim=0)      \n        memory, memory_mask, memory_pos, lane_query, _, lane_query_pos, hw_lvl = outs_seg['args_tuple']\n        outs_motion = self(bev_embed, track_query, lane_query, lane_query_pos, track_boxes)\n        traj_results = self.get_trajs(outs_motion, track_boxes)\n        bboxes, scores, labels, bbox_index, mask = track_boxes[0]\n        outs_motion['track_scores'] = scores[None, :]\n        labels[-1] = 0\n        def filter_vehicle_query(outs_motion, labels, vehicle_id_list):\n            if len(labels) < 1:  # No other obj query except sdc query.\n                return None\n\n            # select vehicle query according to vehicle_id_list\n            vehicle_mask = torch.zeros_like(labels)\n            for veh_id in vehicle_id_list:\n                vehicle_mask |=  labels == veh_id\n            outs_motion['traj_query'] = outs_motion['traj_query'][:, :, vehicle_mask>0]\n            outs_motion['track_query'] = outs_motion['track_query'][:, vehicle_mask>0]\n            outs_motion['track_query_pos'] = outs_motion['track_query_pos'][:, vehicle_mask>0]\n            outs_motion['track_scores'] = outs_motion['track_scores'][:, vehicle_mask>0]\n            return outs_motion\n        \n        outs_motion = filter_vehicle_query(outs_motion, labels, self.vehicle_id_list)\n        \n        # filter sdc query\n        outs_motion['sdc_traj_query'] = outs_motion['traj_query'][:, :, -1]\n        outs_motion['sdc_track_query'] = outs_motion['track_query'][:, -1]\n        outs_motion['sdc_track_query_pos'] = outs_motion['track_query_pos'][:, -1]\n        outs_motion['traj_query'] = outs_motion['traj_query'][:, :, :-1]\n        outs_motion['track_query'] = outs_motion['track_query'][:, :-1]\n        outs_motion['track_query_pos'] = outs_motion['track_query_pos'][:, :-1]\n        outs_motion['track_scores'] = outs_motion['track_scores'][:, :-1]\n\n        return traj_results, outs_motion\n\n    @auto_fp16(apply_to=('bev_embed', 'track_query', 'lane_query', 'lane_query_pos', 'lane_query_embed', 'prev_bev'))\n    def forward(self, \n                bev_embed, \n                track_query, \n                lane_query, \n                lane_query_pos, \n                track_bbox_results):\n        \"\"\"\n        Applies forward pass on the model for motion prediction using bird's eye view (BEV) embedding, track query, lane query, and track bounding box results.\n\n        Args:\n        bev_embed (torch.Tensor): A tensor of shape (h*w, B, D) representing the bird's eye view embedding.\n        track_query (torch.Tensor): A tensor of shape (B, num_dec, A_track, D) representing the track query.\n        lane_query (torch.Tensor): A tensor of shape (N, M_thing, D) representing the lane query.\n        lane_query_pos (torch.Tensor): A tensor of shape (N, M_thing, D) representing the position of the lane query.\n        track_bbox_results (List[torch.Tensor]): A list of tensors containing the tracking bounding box results for each image in the batch.\n\n        Returns:\n        dict: A dictionary containing the following keys and values:\n        - 'all_traj_scores': A tensor of shape (num_levels, B, A_track, num_points) with trajectory scores for each level.\n        - 'all_traj_preds': A tensor of shape (num_levels, B, A_track, num_points, num_future_steps, 2) with predicted trajectories for each level.\n        - 'valid_traj_masks': A tensor of shape (B, A_track) indicating the validity of trajectory masks.\n        - 'traj_query': A tensor containing intermediate states of the trajectory queries.\n        - 'track_query': A tensor containing the input track queries.\n        - 'track_query_pos': A tensor containing the positional embeddings of the track queries.\n        \"\"\"\n        \n        dtype = track_query.dtype\n        device = track_query.device\n        num_groups = self.kmeans_anchors.shape[0]\n\n        # extract the last frame of the track query\n        track_query = track_query[:, -1]\n        \n        # encode the center point of the track query\n        reference_points_track = self._extract_tracking_centers(\n            track_bbox_results, self.pc_range)\n        track_query_pos = self.boxes_query_embedding_layer(pos2posemb2d(reference_points_track.to(device)))  # B, A, D\n        \n        # construct the learnable query positional embedding\n        # split and stack according to groups\n        learnable_query_pos = self.learnable_motion_query_embedding.weight.to(dtype)  # latent anchor (P*G, D)\n        learnable_query_pos = torch.stack(torch.split(learnable_query_pos, self.num_anchor, dim=0))\n\n        # construct the agent level/scene-level query positional embedding \n        # (num_groups, num_anchor, 12, 2)\n        # to incorporate the information of different groups and coordinates, and embed the headding and location information\n        agent_level_anchors = self.kmeans_anchors.to(dtype).to(device).view(num_groups, self.num_anchor, self.predict_steps, 2).detach()\n        scene_level_ego_anchors = anchor_coordinate_transform(agent_level_anchors, track_bbox_results, with_translation_transform=True)  # B, A, G, P ,12 ,2\n        scene_level_offset_anchors = anchor_coordinate_transform(agent_level_anchors, track_bbox_results, with_translation_transform=False)  # B, A, G, P ,12 ,2\n\n        agent_level_norm = norm_points(agent_level_anchors, self.pc_range)\n        scene_level_ego_norm = norm_points(scene_level_ego_anchors, self.pc_range)\n        scene_level_offset_norm = norm_points(scene_level_offset_anchors, self.pc_range)\n\n        # we only use the last point of the anchor\n        agent_level_embedding = self.agent_level_embedding_layer(\n            pos2posemb2d(agent_level_norm[..., -1, :]))  # G, P, D\n        scene_level_ego_embedding = self.scene_level_ego_embedding_layer(\n            pos2posemb2d(scene_level_ego_norm[..., -1, :]))  # B, A, G, P , D\n        scene_level_offset_embedding = self.scene_level_offset_embedding_layer(\n            pos2posemb2d(scene_level_offset_norm[..., -1, :]))  # B, A, G, P , D\n\n        batch_size, num_agents = scene_level_ego_embedding.shape[:2]\n        agent_level_embedding = agent_level_embedding[None,None, ...].expand(batch_size, num_agents, -1, -1, -1)\n        learnable_embed = learnable_query_pos[None, None, ...].expand(batch_size, num_agents, -1, -1, -1)\n\n        \n        # save for latter, anchors\n        # B, A, G, P ,12 ,2 -> B, A, P ,12 ,2\n        scene_level_offset_anchors = self.group_mode_query_pos(track_bbox_results, scene_level_offset_anchors)  \n\n        # select class embedding\n        # B, A, G, P , D-> B, A, P , D\n        agent_level_embedding = self.group_mode_query_pos(\n            track_bbox_results, agent_level_embedding)  \n        scene_level_ego_embedding = self.group_mode_query_pos(\n            track_bbox_results, scene_level_ego_embedding)  # B, A, G, P , D-> B, A, P , D\n        \n        # B, A, G, P , D -> B, A, P , D\n        scene_level_offset_embedding = self.group_mode_query_pos(\n            track_bbox_results, scene_level_offset_embedding)  \n        learnable_embed = self.group_mode_query_pos(\n            track_bbox_results, learnable_embed)  \n\n        init_reference = scene_level_offset_anchors.detach()\n\n        outputs_traj_scores = []\n        outputs_trajs = []\n\n        inter_states, inter_references = self.motionformer(\n            track_query,  # B, A_track, D\n            lane_query,  # B, M, D\n            track_query_pos=track_query_pos,\n            lane_query_pos=lane_query_pos,\n            track_bbox_results=track_bbox_results,\n            bev_embed=bev_embed,\n            reference_trajs=init_reference,\n            traj_reg_branches=self.traj_reg_branches,\n            traj_cls_branches=self.traj_cls_branches,\n            # anchor embeddings \n            agent_level_embedding=agent_level_embedding,\n            scene_level_ego_embedding=scene_level_ego_embedding,\n            scene_level_offset_embedding=scene_level_offset_embedding,\n            learnable_embed=learnable_embed,\n            # anchor positional embeddings layers\n            agent_level_embedding_layer=self.agent_level_embedding_layer,\n            scene_level_ego_embedding_layer=self.scene_level_ego_embedding_layer,\n            scene_level_offset_embedding_layer=self.scene_level_offset_embedding_layer,\n            spatial_shapes=torch.tensor(\n                [[self.bev_h, self.bev_w]], device=device),\n            level_start_index=torch.tensor([0], device=device))\n\n        for lvl in range(inter_states.shape[0]):\n            outputs_class = self.traj_cls_branches[lvl](inter_states[lvl])\n            tmp = self.traj_reg_branches[lvl](inter_states[lvl])\n            tmp = self.unflatten_traj(tmp)\n            \n            # we use cumsum trick here to get the trajectory \n            tmp[..., :2] = torch.cumsum(tmp[..., :2], dim=3)\n\n            outputs_class = self.log_softmax(outputs_class.squeeze(3))\n            outputs_traj_scores.append(outputs_class)\n\n            for bs in range(tmp.shape[0]):\n                tmp[bs] = bivariate_gaussian_activation(tmp[bs])\n            outputs_trajs.append(tmp)\n        outputs_traj_scores = torch.stack(outputs_traj_scores)\n        outputs_trajs = torch.stack(outputs_trajs)\n\n        B, A_track, D = track_query.shape\n        valid_traj_masks = track_query.new_ones((B, A_track)) > 0\n        outs = {\n            'all_traj_scores': outputs_traj_scores,\n            'all_traj_preds': outputs_trajs,\n            'valid_traj_masks': valid_traj_masks,\n            'traj_query': inter_states,\n            'track_query': track_query,\n            'track_query_pos': track_query_pos,\n        }\n\n        return outs\n\n    def group_mode_query_pos(self, bbox_results, mode_query_pos):\n        \"\"\"\n        Group mode query positions based on the input bounding box results.\n        \n        Args:\n            bbox_results (List[Tuple[torch.Tensor]]): A list of tuples containing the bounding box results for each image in the batch.\n            mode_query_pos (torch.Tensor): A tensor of shape (B, A, G, P, D) representing the mode query positions.\n        \n        Returns:\n            torch.Tensor: A tensor of shape (B, A, P, D) representing the classified mode query positions.\n        \"\"\"\n        batch_size = len(bbox_results)\n        agent_num = mode_query_pos.shape[1]\n        batched_mode_query_pos = []\n        self.cls2group = self.cls2group.to(mode_query_pos.device)\n        # TODO: vectorize this\n        # group the embeddings based on the class\n        for i in range(batch_size):\n            bboxes, scores, labels, bbox_index, mask = bbox_results[i]\n            label = labels.to(mode_query_pos.device)\n            grouped_label = self.cls2group[label]\n            grouped_mode_query_pos = []\n            for j in range(agent_num):\n                grouped_mode_query_pos.append(\n                    mode_query_pos[i, j, grouped_label[j]])\n            batched_mode_query_pos.append(torch.stack(grouped_mode_query_pos))\n        return torch.stack(batched_mode_query_pos)\n\n    @force_fp32(apply_to=('preds_dicts_motion'))\n    def loss(self,\n             gt_bboxes_3d,\n             gt_fut_traj,\n             gt_fut_traj_mask,\n             preds_dicts_motion,\n             all_matched_idxes,\n             track_bbox_results):\n        \"\"\"\n        Computes the loss function for the given ground truth and prediction dictionaries.\n        \n        Args:\n            gt_bboxes_3d (List[torch.Tensor]): A list of tensors representing ground truth 3D bounding boxes for each image.\n            gt_fut_traj (torch.Tensor): A tensor representing the ground truth future trajectories.\n            gt_fut_traj_mask (torch.Tensor): A tensor representing the ground truth future trajectory masks.\n            preds_dicts_motion (Dict[str, torch.Tensor]): A dictionary containing motion-related prediction tensors.\n            all_matched_idxes (List[torch.Tensor]): A list of tensors containing the matched ground truth indices for each image in the batch.\n            track_bbox_results (List[Tuple[torch.Tensor]]): A list of tuples containing the tracking bounding box results for each image in the batch.\n\n        Returns:\n            dict[str, torch.Tensor]: A dictionary of loss components.\n        \"\"\"\n\n        # motion related predictions\n        all_traj_scores = preds_dicts_motion['all_traj_scores']\n        all_traj_preds = preds_dicts_motion['all_traj_preds']\n\n        num_dec_layers = len(all_traj_scores)\n\n        all_gt_fut_traj = [gt_fut_traj for _ in range(num_dec_layers)]\n        all_gt_fut_traj_mask = [\n            gt_fut_traj_mask for _ in range(num_dec_layers)]\n\n        losses_traj = []\n        gt_fut_traj_all, gt_fut_traj_mask_all = self.compute_matched_gt_traj(\n            all_gt_fut_traj[0], all_gt_fut_traj_mask[0], all_matched_idxes, track_bbox_results, gt_bboxes_3d)\n        for i in range(num_dec_layers):\n            loss_traj, l_class, l_reg, l_mindae, l_minfde, l_mr = self.compute_loss_traj(all_traj_scores[i], all_traj_preds[i],\n                                                                                         gt_fut_traj_all, gt_fut_traj_mask_all, all_matched_idxes)\n            losses_traj.append(\n                (loss_traj, l_class, l_reg, l_mindae, l_minfde, l_mr))\n\n        loss_dict = dict()\n        loss_dict['loss_traj'] = losses_traj[-1][0]\n        loss_dict['l_class'] = losses_traj[-1][1]\n        loss_dict['l_reg'] = losses_traj[-1][2]\n        loss_dict['min_ade'] = losses_traj[-1][3]\n        loss_dict['min_fde'] = losses_traj[-1][4]\n        loss_dict['mr'] = losses_traj[-1][5]\n\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_traj_i in losses_traj[:-1]:\n            loss_dict[f'd{num_dec_layer}.loss_traj'] = loss_traj_i[0]\n            loss_dict[f'd{num_dec_layer}.l_class'] = loss_traj_i[1]\n            loss_dict[f'd{num_dec_layer}.l_reg'] = loss_traj_i[2]\n            loss_dict[f'd{num_dec_layer}.min_ade'] = loss_traj_i[3]\n            loss_dict[f'd{num_dec_layer}.min_fde'] = loss_traj_i[4]\n            loss_dict[f'd{num_dec_layer}.mr'] = loss_traj_i[5]\n            num_dec_layer += 1\n\n        return loss_dict\n\n    def compute_matched_gt_traj(self,\n                                gt_fut_traj,\n                                gt_fut_traj_mask,\n                                all_matched_idxes,\n                                track_bbox_results,\n                                gt_bboxes_3d):\n        \"\"\"\n        Computes the matched ground truth trajectories for a batch of images based on matched indexes.\n\n        Args:\n        gt_fut_traj (torch.Tensor): Ground truth future trajectories of shape (num_imgs, num_objects, num_future_steps, 2).\n        gt_fut_traj_mask (torch.Tensor): Ground truth future trajectory masks of shape (num_imgs, num_objects, num_future_steps, 2).\n        all_matched_idxes (List[torch.Tensor]): A list of tensors containing the matched indexes for each image in the batch.\n        track_bbox_results (List[torch.Tensor]): A list of tensors containing the tracking bounding box results for each image in the batch.\n        gt_bboxes_3d (List[torch.Tensor]): A list of tensors containing the ground truth 3D bounding boxes for each image in the batch.\n\n        Returns:\n        torch.Tensor: A concatenated tensor of the matched ground truth future trajectories.\n        torch.Tensor: A concatenated tensor of the matched ground truth future trajectory masks.\n        \"\"\"\n        num_imgs = len(all_matched_idxes)\n        gt_fut_traj_all = []\n        gt_fut_traj_mask_all = []\n        for i in range(num_imgs):\n            matched_gt_idx = all_matched_idxes[i]\n            valid_traj_masks = matched_gt_idx >= 0\n            matched_gt_fut_traj = gt_fut_traj[i][matched_gt_idx][valid_traj_masks]\n            matched_gt_fut_traj_mask = gt_fut_traj_mask[i][matched_gt_idx][valid_traj_masks]\n            if self.use_nonlinear_optimizer:\n                # TODO: sdc query is not supported non-linear optimizer\n                bboxes = track_bbox_results[i][0].to(matched_gt_idx.device).tensor[valid_traj_masks]\n                matched_gt_bboxes_3d = gt_bboxes_3d[i][-1].to(matched_gt_idx.device).tensor[matched_gt_idx[:-1]\n                                                                  ][valid_traj_masks[:-1]]\n                sdc_gt_fut_traj = matched_gt_fut_traj[-1:]\n                sdc_gt_fut_traj_mask = matched_gt_fut_traj_mask[-1:]\n                matched_gt_fut_traj = matched_gt_fut_traj[:-1]\n                matched_gt_fut_traj_mask = matched_gt_fut_traj_mask[:-1]\n                bboxes = bboxes[:-1]\n                matched_gt_fut_traj, matched_gt_fut_traj_mask = nonlinear_smoother(\n                    matched_gt_bboxes_3d, matched_gt_fut_traj, matched_gt_fut_traj_mask, bboxes)\n                matched_gt_fut_traj = torch.cat(\n                    [matched_gt_fut_traj, sdc_gt_fut_traj], dim=0)\n                matched_gt_fut_traj_mask = torch.cat(\n                    [matched_gt_fut_traj_mask, sdc_gt_fut_traj_mask], dim=0)\n            matched_gt_fut_traj_mask = torch.all(\n                matched_gt_fut_traj_mask > 0, dim=-1)\n            gt_fut_traj_all.append(matched_gt_fut_traj)\n            gt_fut_traj_mask_all.append(matched_gt_fut_traj_mask)\n        gt_fut_traj_all = torch.cat(gt_fut_traj_all, dim=0)\n        gt_fut_traj_mask_all = torch.cat(gt_fut_traj_mask_all, dim=0)\n        return gt_fut_traj_all, gt_fut_traj_mask_all\n\n    def compute_loss_traj(self,\n                          traj_scores,\n                          traj_preds,\n                          gt_fut_traj_all,\n                          gt_fut_traj_mask_all,\n                          all_matched_idxes):\n        \"\"\"\n        Computes the trajectory loss given the predicted trajectories, ground truth trajectories, and other relevant information.\n        \n        Args:\n            traj_scores (torch.Tensor): A tensor representing the trajectory scores.\n            traj_preds (torch.Tensor): A tensor representing the predicted trajectories.\n            gt_fut_traj_all (torch.Tensor): A tensor representing the ground truth future trajectories.\n            gt_fut_traj_mask_all (torch.Tensor): A tensor representing the ground truth future trajectory masks.\n            all_matched_idxes (List[torch.Tensor]): A list of tensors containing the matched ground truth indices for each image in the batch.\n        \n        Returns:\n            tuple: A tuple containing the total trajectory loss, classification loss, regression loss, minimum average displacement error, minimum final displacement error, and miss rate.\n        \"\"\"\n        num_imgs = traj_scores.size(0)\n        traj_prob_all = []\n        traj_preds_all = []\n        for i in range(num_imgs):\n            matched_gt_idx = all_matched_idxes[i]\n            valid_traj_masks = matched_gt_idx >= 0\n            # select valid and matched\n            batch_traj_prob = traj_scores[i, valid_traj_masks, :]\n            # (n_objs, n_modes, step, 5)\n            batch_traj_preds = traj_preds[i, valid_traj_masks, ...]\n            traj_prob_all.append(batch_traj_prob)\n            traj_preds_all.append(batch_traj_preds)\n        traj_prob_all = torch.cat(traj_prob_all, dim=0)\n        traj_preds_all = torch.cat(traj_preds_all, dim=0)\n        traj_loss, l_class, l_reg, l_minade, l_minfde, l_mr = self.loss_traj(\n            traj_prob_all, traj_preds_all, gt_fut_traj_all, gt_fut_traj_mask_all)\n        return traj_loss, l_class, l_reg, l_minade, l_minfde, l_mr\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def get_trajs(self, preds_dicts, bbox_results):\n        \"\"\"\n        Generates trajectories from the prediction results, bounding box results.\n        \n        Args:\n            preds_dicts (tuple[list[dict]]): A tuple containing lists of dictionaries with prediction results.\n            bbox_results (List[Tuple[torch.Tensor]]): A list of tuples containing the bounding box results for each image in the batch.\n        \n        Returns:\n            List[dict]: A list of dictionaries containing decoded bounding boxes, scores, and labels after non-maximum suppression.\n        \"\"\"\n        num_samples = len(bbox_results)\n        num_layers = preds_dicts['all_traj_preds'].shape[0]\n        ret_list = []\n        for i in range(num_samples):\n            preds = dict()\n            for j in range(num_layers):\n                subfix = '_' + str(j) if j < (num_layers - 1) else ''\n                traj = preds_dicts['all_traj_preds'][j, i]\n                traj_scores = preds_dicts['all_traj_scores'][j, i]\n\n                traj_scores, traj = traj_scores.cpu(), traj.cpu()\n                preds['traj' + subfix] = traj\n                preds['traj_scores' + subfix] = traj_scores\n            ret_list.append(preds)\n        return ret_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head_plugin/__init__.py",
    "content": "from .motion_optimization import MotionNonlinearSmoother\nfrom .modules import MotionTransformerDecoder\nfrom .motion_deformable_attn import MotionTransformerAttentionLayer, MotionDeformableAttention\nfrom .motion_utils import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head_plugin/base_motion_head.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport copy\nimport pickle\nimport torch.nn as nn\nfrom mmcv.models import  build_loss\nfrom mmcv.models.bricks.transformer import build_transformer_layer_sequence\n\nclass BaseMotionHead(nn.Module):\n    def __init__(self, *args, **kwargs):\n        super(BaseMotionHead, self).__init__()\n        pass\n\n    def _build_loss(self, loss_traj):\n        \"\"\"\n        Build the loss function for the motion prediction task.\n\n        Args:\n            loss_traj (dict): A dictionary containing the parameters for the loss function.\n\n        Returns:\n            None\n        \"\"\"\n        self.loss_traj = build_loss(loss_traj)\n        self.unflatten_traj = nn.Unflatten(3, (self.predict_steps, 5))\n        self.log_softmax = nn.LogSoftmax(dim=2)\n\n    def _load_anchors(self, anchor_info_path):\n        \"\"\"\n        Load the anchor information from a file.\n\n        Args:\n            anchor_info_path (str): The path to the file containing the anchor information.\n\n        Returns:\n            None\n        \"\"\"\n        anchor_infos = pickle.load(open(anchor_info_path, 'rb'))\n        self.kmeans_anchors = torch.stack(\n            [torch.from_numpy(a) for a in anchor_infos[\"anchors_all\"]])  # Nc, Pc, steps, 2\n        \n    def _build_layers(self, transformerlayers, det_layer_num):\n        \"\"\"\n        Build the layers of the motion prediction module.\n\n        Args:\n            transformerlayers (dict): A dictionary containing the parameters for the transformer layers.\n            det_layer_num (int): The number of detection layers.\n\n        Returns:\n            None\n        \"\"\"\n        self.learnable_motion_query_embedding = nn.Embedding(\n            self.num_anchor * self.num_anchor_group, self.embed_dims)\n        self.motionformer = build_transformer_layer_sequence(\n            transformerlayers)\n        self.layer_track_query_fuser = nn.Sequential(\n            nn.Linear(self.embed_dims * det_layer_num, self.embed_dims),\n            nn.LayerNorm(self.embed_dims),\n            nn.ReLU(inplace=True)\n        )\n\n        self.agent_level_embedding_layer = nn.Sequential(\n            nn.Linear(self.embed_dims, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n        self.scene_level_ego_embedding_layer = nn.Sequential(\n            nn.Linear(self.embed_dims, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n        self.scene_level_offset_embedding_layer = nn.Sequential(\n            nn.Linear(self.embed_dims, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n        self.boxes_query_embedding_layer = nn.Sequential(\n            nn.Linear(self.embed_dims, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n    \n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        traj_cls_branch = []\n        traj_cls_branch.append(nn.Linear(self.embed_dims, self.embed_dims))\n        traj_cls_branch.append(nn.LayerNorm(self.embed_dims))\n        traj_cls_branch.append(nn.ReLU(inplace=True))\n        for _ in range(self.num_reg_fcs-1):\n            traj_cls_branch.append(nn.Linear(self.embed_dims, self.embed_dims))\n            traj_cls_branch.append(nn.LayerNorm(self.embed_dims))\n            traj_cls_branch.append(nn.ReLU(inplace=True))\n        traj_cls_branch.append(nn.Linear(self.embed_dims, 1))\n        traj_cls_branch = nn.Sequential(*traj_cls_branch)\n\n        traj_reg_branch = []\n        traj_reg_branch.append(nn.Linear(self.embed_dims, self.embed_dims))\n        traj_reg_branch.append(nn.ReLU())\n        for _ in range(self.num_reg_fcs-1):\n            traj_reg_branch.append(nn.Linear(self.embed_dims, self.embed_dims))\n            traj_reg_branch.append(nn.ReLU())\n        traj_reg_branch.append(nn.Linear(self.embed_dims, self.predict_steps * 5))\n        traj_reg_branch = nn.Sequential(*traj_reg_branch)\n\n        def _get_clones(module, N):\n            return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n        num_pred = self.motionformer.num_layers\n        self.traj_cls_branches = _get_clones(traj_cls_branch, num_pred)\n        self.traj_reg_branches = _get_clones(traj_reg_branch, num_pred)\n\n    def _extract_tracking_centers(self, bbox_results, bev_range):\n        \"\"\"\n        extract the bboxes centers and normized according to the bev range\n        \n        Args:\n            bbox_results (List[Tuple[torch.Tensor]]): A list of tuples containing the bounding box results for each image in the batch.\n            bev_range (List[float]): A list of float values representing the bird's eye view range.\n\n        Returns:\n            torch.Tensor: A tensor representing normized centers of the detection bounding boxes.\n        \"\"\"\n        batch_size = len(bbox_results)\n        det_bbox_posembed = []\n        for i in range(batch_size):\n            bboxes, scores, labels, bbox_index, mask = bbox_results[i]\n            xy = bboxes.gravity_center[:, :2]\n            x_norm = (xy[:, 0] - bev_range[0]) / \\\n                (bev_range[3] - bev_range[0])\n            y_norm = (xy[:, 1] - bev_range[1]) / \\\n                (bev_range[4] - bev_range[1])\n            det_bbox_posembed.append(\n                torch.cat([x_norm[:, None], y_norm[:, None]], dim=-1))\n        return torch.stack(det_bbox_posembed)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head_plugin/modules.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.bricks.registry import TRANSFORMER_LAYER_SEQUENCE\nfrom mmcv.models.bricks.transformer import build_transformer_layer\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom mmcv.models.utils.functional import (\n    norm_points,\n    pos2posemb2d,\n    trajectory_coordinate_transform\n)\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass MotionTransformerDecoder(BaseModule):\n    \"\"\"Implements the decoder in DETR3D transformer.\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        coder_norm_cfg (dict): Config of last normalization layer. Default：\n            `LN`.\n    \"\"\"\n\n    def __init__(self, pc_range=None, embed_dims=256, transformerlayers=None, num_layers=3, **kwargs):\n        super(MotionTransformerDecoder, self).__init__()\n        self.pc_range = pc_range\n        self.embed_dims = embed_dims\n        self.num_layers = num_layers\n        self.intention_interaction_layers = IntentionInteraction()\n        self.track_agent_interaction_layers = nn.ModuleList(\n            [TrackAgentInteraction() for i in range(self.num_layers)])\n        self.map_interaction_layers = nn.ModuleList(\n            [MapInteraction() for i in range(self.num_layers)])\n        self.bev_interaction_layers = nn.ModuleList(\n            [build_transformer_layer(transformerlayers) for i in range(self.num_layers)])\n\n        self.static_dynamic_fuser = nn.Sequential(\n            nn.Linear(self.embed_dims*2, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n        self.dynamic_embed_fuser = nn.Sequential(\n            nn.Linear(self.embed_dims*3, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n        self.in_query_fuser = nn.Sequential(\n            nn.Linear(self.embed_dims*2, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n        self.out_query_fuser = nn.Sequential(\n            nn.Linear(self.embed_dims*4, self.embed_dims*2),\n            nn.ReLU(),\n            nn.Linear(self.embed_dims*2, self.embed_dims),\n        )\n\n    def forward(self,\n                track_query,\n                lane_query,\n                track_query_pos=None,\n                lane_query_pos=None,\n                track_bbox_results=None,\n                bev_embed=None,\n                reference_trajs=None,\n                traj_reg_branches=None,\n                agent_level_embedding=None,\n                scene_level_ego_embedding=None,\n                scene_level_offset_embedding=None,\n                learnable_embed=None,\n                agent_level_embedding_layer=None,\n                scene_level_ego_embedding_layer=None,\n                scene_level_offset_embedding_layer=None,\n                **kwargs):\n        \"\"\"Forward function for `MotionTransformerDecoder`.\n        Args:\n            agent_query (B, A, D)\n            map_query (B, M, D) \n            map_query_pos (B, G, D)\n            static_intention_embed (B, A, P, D)\n            offset_query_embed (B, A, P, D)\n            global_intention_embed (B, A, P, D)\n            learnable_intention_embed (B, A, P, D)\n            det_query_pos (B, A, D)\n        Returns:\n            None\n        \"\"\"\n        intermediate = []\n        intermediate_reference_trajs = []\n\n        B, _, P, D = agent_level_embedding.shape\n        track_query_bc = track_query.unsqueeze(2).expand(-1, -1, P, -1)  # (B, A, P, D)\n        track_query_pos_bc = track_query_pos.unsqueeze(2).expand(-1, -1, P, -1)  # (B, A, P, D)\n\n        # static intention embedding, which is imutable throughout all layers\n        agent_level_embedding = self.intention_interaction_layers(agent_level_embedding)\n        static_intention_embed = agent_level_embedding + scene_level_offset_embedding + learnable_embed\n        reference_trajs_input = reference_trajs.unsqueeze(4).detach()\n\n        query_embed = torch.zeros_like(static_intention_embed)\n        for lid in range(self.num_layers):\n            # fuse static and dynamic intention embedding\n            # the dynamic intention embedding is the output of the previous layer, which is initialized with anchor embedding\n            dynamic_query_embed = self.dynamic_embed_fuser(torch.cat(\n                [agent_level_embedding, scene_level_offset_embedding, scene_level_ego_embedding], dim=-1))\n            \n            # fuse static and dynamic intention embedding\n            query_embed_intention = self.static_dynamic_fuser(torch.cat(\n                [static_intention_embed, dynamic_query_embed], dim=-1))  # (B, A, P, D)\n            \n            # fuse intention embedding with query embedding\n            query_embed = self.in_query_fuser(torch.cat([query_embed, query_embed_intention], dim=-1))\n            \n            # interaction between agents\n            track_query_embed = self.track_agent_interaction_layers[lid](\n                query_embed, track_query, query_pos=track_query_pos_bc, key_pos=track_query_pos)\n            \n            # interaction between agents and map\n            map_query_embed = self.map_interaction_layers[lid](\n                query_embed, lane_query, query_pos=track_query_pos_bc, key_pos=lane_query_pos)\n            \n            # interaction between agents and bev, ie. interaction between agents and goals\n            # implemented with deformable transformer\n            bev_query_embed = self.bev_interaction_layers[lid](\n                query_embed,\n                value=bev_embed,\n                query_pos=track_query_pos_bc,\n                bbox_results=track_bbox_results,\n                reference_trajs=reference_trajs_input,\n                **kwargs)\n            \n            # fusing the embeddings from different interaction layers\n            query_embed = [track_query_embed, map_query_embed, bev_query_embed, track_query_bc+track_query_pos_bc]\n            query_embed = torch.cat(query_embed, dim=-1)\n            query_embed = self.out_query_fuser(query_embed)\n\n            if traj_reg_branches is not None:\n                # update reference trajectory\n                tmp = traj_reg_branches[lid](query_embed)\n                bs, n_agent, n_modes, n_steps, _ = reference_trajs.shape\n                tmp = tmp.view(bs, n_agent, n_modes, n_steps, -1)\n                \n                # we predict speed of trajectory and use cumsum trick to get the trajectory\n                tmp[..., :2] = torch.cumsum(tmp[..., :2], dim=3)\n                new_reference_trajs = torch.zeros_like(reference_trajs)\n                new_reference_trajs = tmp[..., :2]\n                reference_trajs = new_reference_trajs.detach()\n                reference_trajs_input = reference_trajs.unsqueeze(4)  # BS NUM_AGENT NUM_MODE 12 NUM_LEVEL  2\n\n                # update embedding, which is used in the next layer\n                # only update the embedding of the last step, i.e. the goal\n                ep_offset_embed = reference_trajs.detach()\n                ep_ego_embed = trajectory_coordinate_transform(reference_trajs.unsqueeze(\n                    2), track_bbox_results, with_translation_transform=True, with_rotation_transform=False).squeeze(2).detach()\n                ep_agent_embed = trajectory_coordinate_transform(reference_trajs.unsqueeze(\n                    2), track_bbox_results, with_translation_transform=False, with_rotation_transform=True).squeeze(2).detach()\n\n                agent_level_embedding = agent_level_embedding_layer(pos2posemb2d(\n                    norm_points(ep_agent_embed[..., -1, :], self.pc_range)))\n                scene_level_ego_embedding = scene_level_ego_embedding_layer(pos2posemb2d(\n                    norm_points(ep_ego_embed[..., -1, :], self.pc_range)))\n                scene_level_offset_embedding = scene_level_offset_embedding_layer(pos2posemb2d(\n                    norm_points(ep_offset_embed[..., -1, :], self.pc_range)))\n\n                intermediate.append(query_embed)\n                intermediate_reference_trajs.append(reference_trajs)\n\n        return torch.stack(intermediate), torch.stack(intermediate_reference_trajs)\n\n\nclass TrackAgentInteraction(BaseModule):\n    \"\"\"\n    Modeling the interaction between the agents\n    \"\"\"\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 dropout=0.1,\n                 batch_first=True,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n\n        self.batch_first = batch_first\n        self.interaction_transformer = nn.TransformerDecoderLayer(d_model=embed_dims,\n                                                                  nhead=num_heads,\n                                                                  dropout=dropout,\n                                                                  dim_feedforward=embed_dims*2,\n                                                                  batch_first=batch_first)\n\n    def forward(self, query, key, query_pos=None, key_pos=None):\n        '''\n        query: context query (B, A, P, D) \n        query_pos: mode pos embedding (B, A, P, D)\n        key: (B, A, D)\n        key_pos: (B, A, D)\n        '''\n        B, A, P, D = query.shape\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n        mem = key.expand(B*A, -1, -1)\n        # N, A, P, D -> N*A, P, D\n        query = torch.flatten(query, start_dim=0, end_dim=1)\n        query = self.interaction_transformer(query, mem)\n        query = query.view(B, A, P, D)\n        return query\n\n\nclass MapInteraction(BaseModule):\n    \"\"\"\n    Modeling the interaction between the agent and the map\n    \"\"\"\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 dropout=0.1,\n                 batch_first=True,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n\n        self.batch_first = batch_first\n        self.interaction_transformer = nn.TransformerDecoderLayer(d_model=embed_dims,\n                                                                  nhead=num_heads,\n                                                                  dropout=dropout,\n                                                                  dim_feedforward=embed_dims*2,\n                                                                  batch_first=batch_first)\n\n    def forward(self, query, key, query_pos=None, key_pos=None):\n        '''\n        x: context query (B, A, P, D) \n        query_pos: mode pos embedding (B, A, P, D)\n        '''\n        B, A, P, D = query.shape\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n\n        # N, A, P, D -> N*A, P, D\n        query = torch.flatten(query, start_dim=0, end_dim=1)\n        mem = key.expand(B*A, -1, -1)\n        query = self.interaction_transformer(query, mem)\n        query = query.view(B, A, P, D)\n        return query\n\n\nclass IntentionInteraction(BaseModule):\n    \"\"\"\n    Modeling the interaction between anchors\n    \"\"\"\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 dropout=0.1,\n                 batch_first=True,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n\n        self.batch_first = batch_first\n        self.interaction_transformer = nn.TransformerEncoderLayer(d_model=embed_dims,\n                                                                  nhead=num_heads,\n                                                                  dropout=dropout,\n                                                                  dim_feedforward=embed_dims*2,\n                                                                  batch_first=batch_first)\n\n    def forward(self, query):\n        B, A, P, D = query.shape\n        # B, A, P, D -> B*A,P, D\n        rebatch_x = torch.flatten(query, start_dim=0, end_dim=1)\n        rebatch_x = self.interaction_transformer(rebatch_x)\n        out = rebatch_x.view(B, A, P, D)\n        return out\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head_plugin/motion_deformable_attn.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport copy\nimport warnings\nimport torch\nimport math\nimport torch.nn as nn\n\nfrom einops import rearrange, repeat\nfrom mmcv.ops.multi_scale_deform_attn import multi_scale_deformable_attn_pytorch\nfrom mmcv.models.utils import xavier_init, constant_init\nfrom mmcv.models.bricks.registry import ATTENTION, TRANSFORMER_LAYER\nfrom mmcv.models.bricks.transformer import build_attention, build_feedforward_network, build_norm_layer\nfrom mmcv.models.bricks.drop import build_dropout\nfrom mmcv.models.backbones.base_module import BaseModule, ModuleList, Sequential\nfrom mmcv.utils import ConfigDict, deprecated_api_warning\nfrom mmcv.models.modules.multi_scale_deformable_attn_function import MultiScaleDeformableAttnFunction_fp32\n\n\n@TRANSFORMER_LAYER.register_module()\nclass MotionTransformerAttentionLayer(BaseModule):\n    \"\"\"Base `TransformerLayer` for vision transformer.\n    It can be built from `mmcv.ConfigDict` and support more flexible\n    customization, for example, using any number of `FFN or LN ` and\n    use different kinds of `attention` by specifying a list of `ConfigDict`\n    named `attn_cfgs`. It is worth mentioning that it supports `prenorm`\n    when you specifying `norm` as the first element of `operation_order`.\n    More details about the `prenorm`: `On Layer Normalization in the\n    Transformer Architecture <https://arxiv.org/abs/2002.04745>`_ .\n    Args:\n        attn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):\n            Configs for `self_attention` or `cross_attention` modules,\n            The order of the configs in the list should be consistent with\n            corresponding attentions in operation_order.\n            If it is a dict, all of the attention modules in operation_order\n            will be built with this config. Default: None.\n        ffn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):\n            Configs for FFN, The order of the configs in the list should be\n            consistent with corresponding ffn in operation_order.\n            If it is a dict, all of the attention modules in operation_order\n            will be built with this config.\n        operation_order (tuple[str]): The execution order of operation\n            in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').\n            Support `prenorm` when you specifying first element as `norm`.\n            Default：None.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: dict(type='LN').\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): Key, Query and Value are shape\n            of (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 attn_cfgs=None,\n                 ffn_cfgs=dict(\n                     type='FFN',\n                     embed_dims=256,\n                     feedforward_channels=1024,\n                     num_fcs=2,\n                     ffn_drop=0.,\n                     act_cfg=dict(type='ReLU', inplace=True),\n                 ),\n                 operation_order=None,\n                 norm_cfg=dict(type='LN'),\n                 init_cfg=None,\n                 batch_first=False,\n                 **kwargs):\n\n        deprecated_args = dict(\n            feedforward_channels='feedforward_channels',\n            ffn_dropout='ffn_drop',\n            ffn_num_fcs='num_fcs')\n        for ori_name, new_name in deprecated_args.items():\n            if ori_name in kwargs:\n                warnings.warn(\n                    f'The arguments `{ori_name}` in BaseTransformerLayer '\n                    f'has been deprecated, now you should set `{new_name}` '\n                    f'and other FFN related arguments '\n                    f'to a dict named `ffn_cfgs`. ', DeprecationWarning)\n                ffn_cfgs[new_name] = kwargs[ori_name]\n\n        super().__init__(init_cfg)\n\n        self.batch_first = batch_first\n\n        num_attn = operation_order.count('self_attn') + operation_order.count(\n            'cross_attn')\n        if isinstance(attn_cfgs, dict):\n            attn_cfgs = [copy.deepcopy(attn_cfgs) for _ in range(num_attn)]\n        else:\n            assert num_attn == len(attn_cfgs), f'The length ' \\\n                f'of attn_cfg {num_attn} is ' \\\n                f'not consistent with the number of attention' \\\n                f'in operation_order {operation_order}.'\n\n        self.num_attn = num_attn\n        self.operation_order = operation_order\n        self.norm_cfg = norm_cfg\n        self.pre_norm = operation_order[0] == 'norm'\n        self.attentions = ModuleList()\n\n        index = 0\n        for operation_name in operation_order:\n            if operation_name in ['self_attn', 'cross_attn']:\n                if 'batch_first' in attn_cfgs[index]:\n                    assert self.batch_first == attn_cfgs[index]['batch_first']\n                else:\n                    attn_cfgs[index]['batch_first'] = self.batch_first\n                attention = build_attention(attn_cfgs[index])\n                # Some custom attentions used as `self_attn`\n                # or `cross_attn` can have different behavior.\n                attention.operation_name = operation_name\n                self.attentions.append(attention)\n                index += 1\n\n        self.embed_dims = self.attentions[0].embed_dims\n\n        self.ffns = ModuleList()\n        num_ffns = operation_order.count('ffn')\n        if isinstance(ffn_cfgs, dict):\n            ffn_cfgs = ConfigDict(ffn_cfgs)\n        if isinstance(ffn_cfgs, dict):\n            ffn_cfgs = [copy.deepcopy(ffn_cfgs) for _ in range(num_ffns)]\n        assert len(ffn_cfgs) == num_ffns\n        for ffn_index in range(num_ffns):\n            if 'embed_dims' not in ffn_cfgs[ffn_index]:\n                ffn_cfgs[ffn_index]['embed_dims'] = self.embed_dims\n            else:\n                assert ffn_cfgs[ffn_index]['embed_dims'] == self.embed_dims\n            self.ffns.append(\n                build_feedforward_network(ffn_cfgs[ffn_index],\n                                          dict(type='FFN')))\n\n        self.norms = ModuleList()\n        num_norms = operation_order.count('norm')\n        for _ in range(num_norms):\n            self.norms.append(build_norm_layer(norm_cfg, self.embed_dims)[1])\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                query_pos=None,\n                key_pos=None,\n                attn_masks=None,\n                query_key_padding_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerDecoderLayer`.\n        **kwargs contains some specific arguments of attentions.\n        Args:\n            query (Tensor): The input query with shape\n                [num_queries, bs, embed_dims] if\n                self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n            value (Tensor): The value tensor with same shape as `key`.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`.\n                Default: None.\n            attn_masks (List[Tensor] | None): 2D Tensor used in\n                calculation of corresponding attention. The length of\n                it should equal to the number of `attention` in\n                `operation_order`. Default: None.\n            query_key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_queries]. Only used in `self_attn` layer.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_keys]. Default: None.\n        Returns:\n            Tensor: forwarded results with shape [num_queries, bs, embed_dims].\n        \"\"\"\n\n        norm_index = 0\n        attn_index = 0\n        ffn_index = 0\n        identity = query\n        if attn_masks is None:\n            attn_masks = [None for _ in range(self.num_attn)]\n        elif isinstance(attn_masks, torch.Tensor):\n            attn_masks = [\n                copy.deepcopy(attn_masks) for _ in range(self.num_attn)\n            ]\n            warnings.warn(f'Use same attn_mask in all attentions in '\n                          f'{self.__class__.__name__} ')\n        else:\n            assert len(attn_masks) == self.num_attn, f'The length of ' \\\n                        f'attn_masks {len(attn_masks)} must be equal ' \\\n                        f'to the number of attention in ' \\\n                        f'operation_order {self.num_attn}'\n\n        for layer in self.operation_order:\n            if layer == 'self_attn':\n                temp_key = temp_value = query\n                query = self.attentions[attn_index](\n                    query,\n                    temp_key,\n                    temp_value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=query_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=query_key_padding_mask,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'norm':\n                query = self.norms[norm_index](query)\n                norm_index += 1\n\n            elif layer == 'cross_attn':\n                query = self.attentions[attn_index](\n                    query,\n                    key,\n                    value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=key_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=key_padding_mask,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'ffn':\n                query = self.ffns[ffn_index](\n                    query, identity if self.pre_norm else None)\n                ffn_index += 1\n\n        return query\n\n@ATTENTION.register_module()\nclass MotionDeformableAttention(BaseModule):\n    \"\"\"An attention module used in Deformable-Detr.\n\n    `Deformable DETR: Deformable Transformers for End-to-End Object Detection.\n    <https://arxiv.org/pdf/2010.04159.pdf>`_.\n\n    Args:\n        embed_dims (int): The embedding dimension of Attention.\n            Default: 256.\n        num_heads (int): Parallel attention heads. Default: 64.\n        num_levels (int): The number of feature map used in\n            Attention. Default: 4.\n        num_points (int): The number of sampling points for\n            each query in each head. Default: 4.\n        im2col_step (int): The step used in image_to_column.\n            Default: 64.\n        dropout (float): A Dropout layer on `inp_identity`.\n            Default: 0.1.\n        batch_first (bool): Key, Query and Value are shape of\n            (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: None.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 num_levels=4,\n                 num_points=4,\n                 num_steps=1,\n                 sample_index=-1,\n                 im2col_step=64,\n                 dropout=0.1,\n                 bev_range=[-51.2, -51.2, -5.0, 51.2, 51.2, 3.0],\n                 voxel_size=[0.2, 0.2, 8],\n                 batch_first=True,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n        if embed_dims % num_heads != 0:\n            raise ValueError(f'embed_dims must be divisible by num_heads, '\n                             f'but got {embed_dims} and {num_heads}')\n        dim_per_head = embed_dims // num_heads\n        self.norm_cfg = norm_cfg\n        self.dropout = nn.Dropout(dropout)\n        self.batch_first = batch_first\n        self.fp16_enabled = False\n        self.bev_range = bev_range\n\n        # you'd better set dim_per_head to a power of 2\n        # which is more efficient in the CUDA implementation\n        def _is_power_of_2(n):\n            if (not isinstance(n, int)) or (n < 0):\n                raise ValueError(\n                    'invalid input for _is_power_of_2: {} (type: {})'.format(\n                        n, type(n)))\n            return (n & (n - 1) == 0) and n != 0\n\n        if not _is_power_of_2(dim_per_head):\n            warnings.warn(\n                \"You'd better set embed_dims in \"\n                'MultiScaleDeformAttention to make '\n                'the dimension of each attention head a power of 2 '\n                'which is more efficient in our CUDA implementation.')\n\n        self.im2col_step = im2col_step\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_heads = num_heads\n        self.num_points = num_points\n        self.num_steps = num_steps\n        self.sample_index = sample_index\n        self.sampling_offsets = nn.Linear(\n            embed_dims, num_heads * num_steps * num_levels * num_points * 2)\n        self.attention_weights = nn.Linear(embed_dims,\n                                           num_heads * num_steps * num_levels * num_points)\n        self.value_proj = nn.Linear(embed_dims, embed_dims)\n        self.output_proj = Sequential(nn.Linear(num_steps*embed_dims, embed_dims),\n                                      nn.LayerNorm(embed_dims),\n                                      nn.ReLU(inplace=True)\n                                     )\n        self.init_weights()\n\n    def init_weights(self):\n        \"\"\"Default initialization for Parameters of Module.\"\"\"\n        constant_init(self.sampling_offsets, 0.)\n        thetas = torch.arange(\n            self.num_heads,\n            dtype=torch.float32) * (2.0 * math.pi / self.num_heads)\n        grid_init = torch.stack([thetas.cos(), thetas.sin()], -1)\n        grid_init = (grid_init /\n                     grid_init.abs().max(-1, keepdim=True)[0]).view(\n            self.num_heads, 1, 1, 1,\n            2).repeat(1, self.num_steps, self.num_levels, self.num_points, 1)\n        for i in range(self.num_points):\n            grid_init[:, :, :, i, :] *= i + 1\n\n        self.sampling_offsets.bias.data = grid_init.view(-1)\n        constant_init(self.attention_weights, val=0., bias=0.)\n        xavier_init(self.value_proj, distribution='uniform', bias=0.)\n        xavier_init(self.output_proj, distribution='uniform', bias=0.)\n        self._is_init = True\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiScaleDeformableAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_padding_mask=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                bbox_results=None,\n                reference_trajs=None,\n                flag='decoder',\n                **kwargs):\n        \"\"\"Forward Function of MultiScaleDeformAttention.\n\n        Args:\n            query (Tensor): Query of Transformer with shape\n                (num_query, bs, embed_dims).\n            key (Tensor): The key tensor with shape\n                `(num_key, bs, embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(num_key, bs, embed_dims)`.\n            identity (Tensor): The tensor used for addition, with the\n                same shape as `query`. Default None. If None,\n                `query` will be used.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`. Default\n                None.\n            reference_points (Tensor):  The normalized reference\n                points with shape (bs, num_query, num_levels, 2),\n                all elements is range in [0, 1], top-left (0,0),\n                bottom-right (1, 1), including padding area.\n                or (N, Length_{query}, num_levels, 4), add\n                additional two dimensions is (w, h) to\n                form reference boxes.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_key].\n            spatial_shapes (Tensor): Spatial shape of features in\n                different levels. With shape (num_levels, 2),\n                last dimension represents (h, w).\n            level_start_index (Tensor): The start index of each level.\n                A tensor has shape ``(num_levels, )`` and can be represented\n                as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...].\n\n        Returns:\n             Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n        bs, num_agent, num_mode, _ = query.shape\n        num_query = num_agent * num_mode\n        if value is None:\n            value = query\n        if identity is None:\n            identity = query\n        if query_pos is not None:\n            query = query + query_pos\n        query = torch.flatten(query, start_dim=1, end_dim=2)\n        \n        value = value.permute(1, 0, 2)\n        bs, num_value, _ = value.shape\n        assert (spatial_shapes[:, 0] * spatial_shapes[:, 1]).sum() == num_value\n\n        value = self.value_proj(value)\n        if key_padding_mask is not None:\n            value = value.masked_fill(key_padding_mask[..., None], 0.0)\n        value = value.view(bs, num_value, self.num_heads, -1)\n        sampling_offsets = self.sampling_offsets(query).view(\n            bs, num_query, self.num_heads, self.num_steps, self.num_levels, self.num_points, 2)\n        attention_weights = self.attention_weights(query).view(\n            bs, num_query, self.num_heads, self.num_steps, self.num_levels * self.num_points)\n        attention_weights = attention_weights.softmax(-1)\n\n        attention_weights = attention_weights.view(bs, num_query,\n                                                   self.num_heads,\n                                                   self.num_steps,\n                                                   self.num_levels,\n                                                   self.num_points)\n        # bs, n_query, n_head, n_steps, N_level, N_points, 2\n        # BS NUM_AGENT NUM_MODE 12 NUM_LEVEL  2\n        if reference_trajs.shape[-1] == 2:\n            reference_trajs = reference_trajs[:, :, :, [self.sample_index], :, :]\n            reference_trajs_ego = self.agent_coords_to_ego_coords(copy.deepcopy(reference_trajs), bbox_results).detach()\n            reference_trajs_ego = torch.flatten(reference_trajs_ego, start_dim=1, end_dim=2)\n            reference_trajs_ego = reference_trajs_ego[:, :, None, :, :, None, :]\n            reference_trajs_ego[..., 0] -= self.bev_range[0]\n            reference_trajs_ego[..., 1] -= self.bev_range[1]\n            reference_trajs_ego[..., 0] /= (self.bev_range[3] - self.bev_range[0])\n            reference_trajs_ego[..., 1] /= (self.bev_range[4] - self.bev_range[1])\n            offset_normalizer = torch.stack(\n                [spatial_shapes[..., 1], spatial_shapes[..., 0]], -1)\n            sampling_locations = reference_trajs_ego \\\n                + sampling_offsets \\\n                / offset_normalizer[None, None, None, None, :, None, :]\n\n            sampling_locations = rearrange(sampling_locations, 'bs nq nh ns nl np c -> bs nq ns nh nl np c') # permute([0,1,3,2,4,5,6])\n            attention_weights = rearrange(attention_weights, 'bs nq nh ns nl np -> bs nq ns nh nl np') #.permute([0,1,3,2,4,5])\n            sampling_locations = sampling_locations.reshape(bs, num_query*self.num_steps, self.num_heads, self.num_levels, self.num_points, 2)\n            attention_weights = attention_weights.reshape(bs, num_query*self.num_steps, self.num_heads, self.num_levels, self.num_points)\n\n        else:\n            raise ValueError(\n                f'Last dim of reference_trajs must be'\n                f' 2 or 4, but get {reference_trajs.shape[-1]} instead.')\n        if torch.cuda.is_available() and value.is_cuda:\n\n            # using fp16 deformable attention is unstable because it performs many sum operations\n            if value.dtype == torch.float16:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            else:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            output = MultiScaleDeformableAttnFunction.apply(\n                value, spatial_shapes, level_start_index, sampling_locations,\n                attention_weights, self.im2col_step)\n        else:\n            output = multi_scale_deformable_attn_pytorch(\n                value, spatial_shapes, sampling_locations, attention_weights)\n        output = output.view(bs, num_query, self.num_steps, -1)\n        output = torch.flatten(output, start_dim=2, end_dim=3)\n        output = self.output_proj(output)\n        output = output.view(bs, num_agent, num_mode, -1)\n        return self.dropout(output) + identity\n\n    def agent_coords_to_ego_coords(self, reference_trajs, bbox_results):\n        batch_size = len(bbox_results)\n        reference_trajs_ego = []\n        for i in range(batch_size):\n            boxes_3d, scores, labels, bbox_index, mask = bbox_results[i]\n            det_centers = boxes_3d.gravity_center.to(reference_trajs.device)\n            batch_reference_trajs = reference_trajs[i]\n            batch_reference_trajs += det_centers[:, None, None, None, :2]\n            reference_trajs_ego.append(batch_reference_trajs)\n        return torch.stack(reference_trajs_ego)\n    \n    def rot_2d(self, yaw):\n        sy, cy = torch.sin(yaw), torch.cos(yaw)\n        out = torch.stack([torch.stack([cy, -sy]), torch.stack([sy, cy])]).permute([2,0,1])\n        return out\n\n@ATTENTION.register_module()\nclass CustomModeMultiheadAttention(BaseModule):\n    \"\"\"A wrapper for ``torch.nn.MultiheadAttention``.\n    This module implements MultiheadAttention with identity connection,\n    and positional encoding  is also passed as input.\n    Args:\n        embed_dims (int): The embedding dimension.\n        num_heads (int): Parallel attention heads.\n        attn_drop (float): A Dropout layer on attn_output_weights.\n            Default: 0.0.\n        proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.\n            Default: 0.0.\n        dropout_layer (obj:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): When it is True,  Key, Query and Value are shape of\n            (batch, n, embed_dim), otherwise (n, batch, embed_dim).\n             Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims,\n                 num_heads,\n                 attn_drop=0.,\n                 proj_drop=0.,\n                 dropout_layer=dict(type='Dropout', drop_prob=0.),\n                 init_cfg=None,\n                 **kwargs):\n        super().__init__(init_cfg)\n        if 'dropout' in kwargs:\n            warnings.warn(\n                'The arguments `dropout` in MultiheadAttention '\n                'has been deprecated, now you can separately '\n                'set `attn_drop`(float), proj_drop(float), '\n                'and `dropout_layer`(dict) ', DeprecationWarning)\n            attn_drop = kwargs['dropout']\n            dropout_layer['drop_prob'] = kwargs.pop('dropout')\n\n        self.embed_dims = embed_dims\n        self.num_heads = num_heads\n\n        self.attn = nn.MultiheadAttention(embed_dims, num_heads, attn_drop, **kwargs)\n\n        self.proj_drop = nn.Dropout(proj_drop)\n        self.dropout_layer = build_dropout(\n            dropout_layer) if dropout_layer else nn.Identity()\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiheadAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_pos=None,\n                attn_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `MultiheadAttention`.\n        **kwargs allow passing a more general data flow when combining\n        with other operations in `transformerlayer`.\n        Args:\n            query (Tensor): The input query with shape [num_queries, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n                If None, the ``query`` will be used. Defaults to None.\n            value (Tensor): The value tensor with same shape as `key`.\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n                If None, the `key` will be used.\n            identity (Tensor): This tensor, with the same shape as x,\n                will be used for the identity link.\n                If None, `x` will be used. Defaults to None.\n            query_pos (Tensor): The positional encoding for query, with\n                the same shape as `x`. If not None, it will\n                be added to `x` before forward function. Defaults to None.\n            key_pos (Tensor): The positional encoding for `key`, with the\n                same shape as `key`. Defaults to None. If not None, it will\n                be added to `key` before forward function. If None, and\n                `query_pos` has the same shape as `key`, then `query_pos`\n                will be used for `key_pos`. Defaults to None.\n            attn_mask (Tensor): ByteTensor mask with shape [num_queries,\n                num_keys]. Same in `nn.MultiheadAttention.forward`.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].\n                Defaults to None.\n        Returns:\n            Tensor: forwarded results with shape\n            [num_queries, bs, embed_dims]\n            if self.batch_first is False, else\n            [bs, num_queries embed_dims].\n        \"\"\"\n        query_pos = query_pos.unsqueeze(1)\n        key_pos = key_pos.unsqueeze(1)\n        bs, n_agent, n_query, D = query.shape\n        if key is None:\n            key = query\n        if value is None:\n            value = key\n        if identity is None:\n            identity = query\n        if key_pos is None:\n            if query_pos is not None:\n                # use query_pos if key_pos is not available\n                if query_pos.shape == key.shape:\n                    key_pos = query_pos\n                else:\n                    warnings.warn(f'position encoding of key is'\n                                  f'missing in {self.__class__.__name__}.')\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n\n        # Because the dataflow('key', 'query', 'value') of\n        # ``torch.nn.MultiheadAttention`` is (num_query, batch,\n        # embed_dims), We should adjust the shape of dataflow from\n        # batch_first (batch, num_query, embed_dims) to num_query_first\n        # (num_query ,batch, embed_dims), and recover ``attn_output``\n        # from num_query_first to batch_first.\n        query = torch.flatten(query, start_dim=0, end_dim=1)\n        key = torch.flatten(key, start_dim=0, end_dim=1)\n        value = torch.flatten(value, start_dim=0, end_dim=1)\n        identity = torch.flatten(identity, start_dim=0, end_dim=1)\n        \n        query = query.transpose(0, 1)\n        key = key.transpose(0, 1)\n        value = value.transpose(0, 1)\n\n        out = self.attn(\n            query=query,\n            key=key,\n            value=value,\n            attn_mask=attn_mask,\n            key_padding_mask=key_padding_mask)[0]\n\n        out = out.transpose(0, 1)\n        out = identity + self.dropout_layer(self.proj_drop(out))\n\n        return out.view(bs, n_agent, n_query, D)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head_plugin/motion_optimization.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nfrom dataclasses import dataclass\nfrom enum import Enum, auto\nfrom typing import Any, Dict, List, Optional, Sequence, Tuple, Union\n\nimport numpy as np\nimport numpy.typing as npt\nfrom casadi import DM, Opti, OptiSol, cos, diff, sin, sumsqr, vertcat\nPose = Tuple[float, float, float]  # (x, y, yaw)\n\n\nclass MotionNonlinearSmoother:\n    \"\"\"\n    Smoothing a set of xy observations with a vehicle dynamics model.\n    Solved with direct multiple-shooting.\n    modified from https://github.com/motional/nuplan-devkit\n    :param trajectory_len: trajectory length\n    :param dt: timestep (sec)\n    \"\"\"\n\n    def __init__(self, trajectory_len: int, dt: float):\n        \"\"\"\n        :param trajectory_len: the length of trajectory to be optimized.\n        :param dt: the time interval between trajectory points.\n        \"\"\"\n        self.dt = dt\n        self.trajectory_len = trajectory_len\n        self.current_index = 0\n        # Use a array of dts to make it compatible to situations with varying dts across different time steps.\n        self._dts: npt.NDArray[np.float32] = np.asarray(\n            [[dt] * trajectory_len])\n        self._init_optimization()\n\n    def _init_optimization(self) -> None:\n        \"\"\"\n        Initialize related variables and constraints for optimization.\n        \"\"\"\n        self.nx = 4  # state dim\n        self.nu = 2  # control dim\n\n        self._optimizer = Opti()  # Optimization problem\n        self._create_decision_variables()\n        self._create_parameters()\n        self._set_dynamic_constraints()\n        self._set_state_constraints()\n        self._set_control_constraints()\n        self._set_objective()\n\n        # Set default solver options (quiet)\n        self._optimizer.solver(\n            \"ipopt\", {\"ipopt.print_level\": 0, \"print_time\": 0, \"ipopt.sb\": \"yes\"})\n\n    def set_reference_trajectory(self, x_curr: Sequence[float], reference_trajectory: Sequence[Pose]) -> None:\n        \"\"\"\n        Set the reference trajectory that the smoother is trying to loosely track.\n        :param x_curr: current state of size nx (x, y, yaw, speed)\n        :param reference_trajectory: N+1 x 3 reference, where the second dim is for (x, y, yaw)\n        \"\"\"\n        self._check_inputs(x_curr, reference_trajectory)\n\n        self._optimizer.set_value(self.x_curr, DM(x_curr))\n        self._optimizer.set_value(self.ref_traj, DM(reference_trajectory).T)\n        self._set_initial_guess(x_curr, reference_trajectory)\n\n    def set_solver_optimizerons(self, options: Dict[str, Any]) -> None:\n        \"\"\"\n        Control solver options including verbosity.\n        :param options: Dictionary containing optimization criterias\n        \"\"\"\n        self._optimizer.solver(\"ipopt\", options)\n\n    def solve(self) -> OptiSol:\n        \"\"\"\n        Solve the optimization problem. Assumes the reference trajectory was already set.\n        :return Casadi optimization class\n        \"\"\"\n        return self._optimizer.solve()\n\n    def _create_decision_variables(self) -> None:\n        \"\"\"\n        Define the decision variables for the trajectory optimization.\n        \"\"\"\n        # State trajectory (x, y, yaw, speed)\n        self.state = self._optimizer.variable(self.nx, self.trajectory_len + 1)\n        self.position_x = self.state[0, :]\n        self.position_y = self.state[1, :]\n        self.yaw = self.state[2, :]\n        self.speed = self.state[3, :]\n\n        # Control trajectory (curvature, accel)\n        self.control = self._optimizer.variable(self.nu, self.trajectory_len)\n        self.curvature = self.control[0, :]\n        self.accel = self.control[1, :]\n\n        # Derived control and state variables, dt[:, 1:] becuases state vector is one step longer than action.\n        self.curvature_rate = diff(self.curvature) / self._dts[:, 1:]\n        self.jerk = diff(self.accel) / self._dts[:, 1:]\n        self.lateral_accel = self.speed[: self.trajectory_len] ** 2 * \\\n            self.curvature\n\n    def _create_parameters(self) -> None:\n        \"\"\"\n        Define the expert trjactory and current position for the trajectory optimizaiton.\n        \"\"\"\n        self.ref_traj = self._optimizer.parameter(\n            3, self.trajectory_len + 1)  # (x, y, yaw)\n        self.x_curr = self._optimizer.parameter(self.nx, 1)\n\n    def _set_dynamic_constraints(self) -> None:\n        r\"\"\"\n        Set the system dynamics constraints as following:\n          dx/dt = f(x,u)\n          \\dot{x} = speed * cos(yaw)\n          \\dot{y} = speed * sin(yaw)\n          \\dot{yaw} = speed * curvature\n          \\dot{speed} = accel\n        \"\"\"\n        state = self.state\n        control = self.control\n        dt = self.dt\n\n        def process(x: Sequence[float], u: Sequence[float]) -> Any:\n            \"\"\"Process for state propagation.\"\"\"\n            return vertcat(x[3] * cos(x[2]), x[3] * sin(x[2]), x[3] * u[0], u[1])\n\n        for k in range(self.trajectory_len):  # loop over control intervals\n            # Runge-Kutta 4 integration\n            k1 = process(state[:, k], control[:, k])\n            k2 = process(state[:, k] + dt / 2 * k1, control[:, k])\n            k3 = process(state[:, k] + dt / 2 * k2, control[:, k])\n            k4 = process(state[:, k] + dt * k3, control[:, k])\n            next_state = state[:, k] + dt / 6 * (k1 + 2 * k2 + 2 * k3 + k4)\n            self._optimizer.subject_to(\n                state[:, k + 1] == next_state)  # close the gaps\n\n    def _set_control_constraints(self) -> None:\n        \"\"\"Set the hard control constraints.\"\"\"\n        curvature_limit = 1.0 / 5.0  # 1/m\n        self._optimizer.subject_to(\n            self._optimizer.bounded(-curvature_limit, self.curvature, curvature_limit))\n        accel_limit = 4.0  # m/s^2\n        self._optimizer.subject_to(\n            self._optimizer.bounded(-accel_limit, self.accel, accel_limit))\n\n    def _set_state_constraints(self) -> None:\n        \"\"\"Set the hard state constraints.\"\"\"\n        # Constrain the current time -- NOT start of history\n        # initial boundary condition\n        self._optimizer.subject_to(\n            self.state[:, self.current_index] == self.x_curr)\n\n        max_speed = 35.0  # m/s\n        self._optimizer.subject_to(self._optimizer.bounded(\n            0.0, self.speed, max_speed))  # only forward\n        max_yaw_rate = 1.75  # rad/s\n        self._optimizer.subject_to(\n            self._optimizer.bounded(-max_yaw_rate, diff(self.yaw) / self._dts, max_yaw_rate))\n        max_lateral_accel = 4.0  # m/s^2, assumes circular motion acc_lat = speed^2 * curvature\n        self._optimizer.subject_to(\n            self._optimizer.bounded(\n                -max_lateral_accel, self.speed[:, : self.trajectory_len] ** 2 *\n                self.curvature, max_lateral_accel\n            )\n        )\n\n    def _set_objective(self) -> None:\n        \"\"\"Set the objective function. Use care when modifying these weights.\"\"\"\n        # Follow reference, minimize control rates and absolute inputs\n        alpha_xy = 1.0\n        alpha_yaw = 0.1\n        alpha_rate = 0.08\n        alpha_abs = 0.08\n        alpha_lat_accel = 0.06\n        cost_stage = (\n            alpha_xy *\n            sumsqr(self.ref_traj[:2, :] -\n                   vertcat(self.position_x, self.position_y))\n            + alpha_yaw * sumsqr(self.ref_traj[2, :] - self.yaw)\n            + alpha_rate * (sumsqr(self.curvature_rate) + sumsqr(self.jerk))\n            + alpha_abs * (sumsqr(self.curvature) + sumsqr(self.accel))\n            + alpha_lat_accel * sumsqr(self.lateral_accel)\n        )\n\n        # Take special care with the final state\n        alpha_terminal_xy = 1.0\n        alpha_terminal_yaw = 40.0  # really care about final heading to help with lane changes\n        cost_terminal = alpha_terminal_xy * sumsqr(\n            self.ref_traj[:2, -1] -\n            vertcat(self.position_x[-1], self.position_y[-1])\n        ) + alpha_terminal_yaw * sumsqr(self.ref_traj[2, -1] - self.yaw[-1])\n\n        self._optimizer.minimize(\n            cost_stage + self.trajectory_len / 4.0 * cost_terminal)\n\n    def _set_initial_guess(self, x_curr: Sequence[float], reference_trajectory: Sequence[Pose]) -> None:\n        \"\"\"Set a warm-start for the solver based on the reference trajectory.\"\"\"\n        self._check_inputs(x_curr, reference_trajectory)\n\n        # Initialize state guess based on reference\n        self._optimizer.set_initial(self.state[:3, :], DM(\n            reference_trajectory).T)  # (x, y, yaw)\n        self._optimizer.set_initial(self.state[3, :], DM(x_curr[3]))  # speed\n\n    def _check_inputs(self, x_curr: Sequence[float], reference_trajectory: Sequence[Pose]) -> None:\n        \"\"\"Raise ValueError if inputs are not of proper size.\"\"\"\n        if len(x_curr) != self.nx:\n            raise ValueError(\n                f\"x_curr length {len(x_curr)} must be equal to state dim {self.nx}\")\n\n        if len(reference_trajectory) != self.trajectory_len + 1:\n            raise ValueError(\n                f\"reference traj length {len(reference_trajectory)} must be equal to {self.trajectory_len + 1}\"\n            )\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/motion_head_plugin/motion_utils.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport random\nimport numpy as np\nfrom .motion_optimization import MotionNonlinearSmoother\n\n\ndef nonlinear_smoother(gt_bboxes_3d, gt_fut_traj, gt_fut_traj_mask, bbox_tensor):\n    \"\"\"\n    This function applies a nonlinear smoother to the ground truth future trajectories of 3D bounding boxes.\n    It takes into account the vehicle's yaw and velocity to generate smooth, realistic trajectories.\n\n    Args:\n    gt_bboxes_3d (torch.Tensor): Ground truth 3D bounding boxes of shape (batch_size, 7).\n    gt_fut_traj (torch.Tensor): Ground truth future trajectories of shape (batch_size, 12, 2).\n    gt_fut_traj_mask (torch.Tensor): A mask indicating valid timesteps in the ground truth future trajectories of shape (batch_size, 12).\n    bbox_tensor (torch.Tensor): A tensor representing the bounding box properties of shape (batch_size, 9).\n\n    Returns:\n    torch.Tensor: The perturbed trajectories of shape (batch_size, 12, 2).\n    torch.Tensor: The updated mask indicating valid timesteps in the perturbed trajectories of the same shape as gt_fut_traj_mask.\n    \"\"\"\n    device = gt_fut_traj.device\n    dtype = gt_fut_traj.dtype\n    gt_bboxes_3d = gt_bboxes_3d.cpu().detach().numpy()\n    gt_fut_traj = gt_fut_traj.cpu().detach().numpy()\n    gt_fut_traj_xy_diff = np.zeros((gt_fut_traj.shape[0], 13, 2))\n    gt_fut_traj_xy_diff[:, 1:, :] = gt_fut_traj\n    gt_fut_traj_xy_diff = np.diff(gt_fut_traj_xy_diff, axis=1)\n    gt_fut_traj_yaw = np.arctan2(\n        gt_fut_traj_xy_diff[:, :, 1], gt_fut_traj_xy_diff[:, :, 0])\n    gt_fut_traj_yaw = np.concatenate(\n        [-np.pi/2 - gt_bboxes_3d[:, None, 6:7], gt_fut_traj_yaw[:, :, None]], axis=1)\n    gt_fut_traj = np.concatenate(\n        [gt_bboxes_3d[:, None, :2], gt_fut_traj], axis=1)\n\n    gt_fut_traj_mask = gt_fut_traj_mask.cpu().detach().numpy()\n    bbox_tensor = bbox_tensor.cpu().detach().numpy()\n    ts_limit = gt_fut_traj_mask.sum(1)[:, 0]\n    yaw_preds = bbox_tensor[:, 6]\n    vel_preds = bbox_tensor[:, -2:]\n    speed_preds = np.sqrt(np.sum(vel_preds**2, axis=-1))\n    traj_perturb_all = []\n\n    # we set some constraints here to avoid perturbing the trajectories that are not dynamic, \n    # or have large differences with the ground truth\n    def _is_dynamic(traj, ts, dist_thres):\n        return np.sqrt(np.sum((traj[ts, :2] - traj[0, :2])**2)) > dist_thres\n\n    def _check_diff(x_curr, ref_traj):\n        if np.sqrt((x_curr[0] - ref_traj[0, 0]) ** 2 + (x_curr[1] - ref_traj[0, 1])**2) > 2:\n            return False\n        a = np.array([np.cos(x_curr[2]), np.sin(x_curr[2])])\n        b = np.array([np.cos(ref_traj[0, 2]), np.sin(ref_traj[0, 2])])\n        diff_theta = np.arccos(\n            np.sum(a*b)/(np.sqrt(np.sum(a**2)) * np.sqrt(np.sum(b**2))))\n        if diff_theta > np.pi/180 * 30:\n            return False\n        return True\n\n    def _check_ade(traj_pert, traj_ref, thres):\n        return np.mean(np.sqrt(np.sum((traj_pert[:, :2] - traj_ref[:, :2])**2, axis=-1))) < thres\n\n    perturb_count = 0\n    perturb_used_count = 0\n    for i in range(gt_fut_traj.shape[0]):\n        ts = ts_limit[i]\n        x_curr = [bbox_tensor[i, 0], bbox_tensor[i, 1], -\n                  np.pi/2 - yaw_preds[i], speed_preds[i]]\n        reference_trajectory = np.concatenate(\n            [gt_fut_traj[i], gt_fut_traj_yaw[i]], axis=-1)\n        if ts > 1 and _is_dynamic(gt_fut_traj[i], int(ts), 2) and _check_diff(x_curr, reference_trajectory):\n            smoother = MotionNonlinearSmoother(\n                trajectory_len=int(ts), dt=0.5)\n            reference_trajectory = reference_trajectory[:int(ts)+1, :]\n            smoother.set_reference_trajectory(x_curr, reference_trajectory)\n            sol = smoother.solve()\n            traj_perturb = np.stack(\n                [sol.value(smoother.position_x), sol.value(smoother.position_y)], axis=-1)\n            perturb_used_count += 1\n            if not _check_ade(traj_perturb, reference_trajectory, thres=1.5):\n                traj_perturb = gt_fut_traj[i, 1:,\n                                           :2] - gt_fut_traj[i, 0:1, :2]\n            else:\n                traj_perturb_tmp = traj_perturb[1:,\n                                                :2] - traj_perturb[0:1, :2]\n                traj_perturb = np.zeros((12, 2))\n                traj_perturb[:traj_perturb_tmp.shape[0],\n                             :] = traj_perturb_tmp[:, :2]\n                perturb_count += 1\n        else:\n            traj_perturb = gt_fut_traj[i, 1:, :2] - gt_fut_traj[i, 0:1, :2]\n        traj_perturb_all.append(traj_perturb)\n    return torch.tensor(traj_perturb_all, device=device, dtype=dtype), torch.tensor(gt_fut_traj_mask > 0, device=device)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/occ_head.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.builder import HEADS, build_loss\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom einops import rearrange\nfrom mmcv.core.utils import reduce_mean\nfrom mmcv.models.bricks.transformer import build_transformer_layer_sequence\nimport copy\nfrom .occ_head_plugin import MLP, BevFeatureSlicer, SimpleConv2d, CVT_Decoder, Bottleneck, UpsamplingAdd, \\\n                             predict_instance_segmentation_and_trajectories\n\ndef _get_clones(module, N):\n    return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n@HEADS.register_module()\nclass OccHead(BaseModule):\n    def __init__(self, \n                 # General\n                 receptive_field=3,\n                 n_future=4,\n                 spatial_extent=(50, 50),\n                 ignore_index=255,\n\n                 # BEV\n                 grid_conf = None,\n\n                 bev_size=(200, 200),\n                 bev_emb_dim=256,\n                 bev_proj_dim=64,\n                 bev_proj_nlayers=1,\n\n                 # Query\n                 query_dim=256,\n                 query_mlp_layers=3,\n                 detach_query_pos=True,\n                 temporal_mlp_layer=2,\n\n                 # Transformer\n                 transformer_decoder=None,\n\n                 attn_mask_thresh=0.5,\n                 # Loss\n                 sample_ignore_mode='all_valid',\n                 aux_loss_weight=1.,\n\n                 loss_mask=None,\n                 loss_dice=None,\n\n                 # Cfgs\n                 init_cfg=None,\n\n                 # Eval\n                 pan_eval=False,\n                 test_seg_thresh:float=0.5,\n                 test_with_track_score=False,\n                 ):\n        assert init_cfg is None, 'To prevent abnormal initialization ' \\\n            'behavior, init_cfg is not allowed to be set'\n        super().__init__(init_cfg)\n        self.receptive_field = receptive_field  # NOTE: Used by prepare_future_labels in E2EPredTransformer\n        self.n_future = n_future\n        self.spatial_extent = spatial_extent\n        self.ignore_index  = ignore_index\n\n        bevformer_bev_conf = {\n            'xbound': [-51.2, 51.2, 0.512],\n            'ybound': [-51.2, 51.2, 0.512],\n            'zbound': [-10.0, 10.0, 20.0],\n        }\n        self.bev_sampler =  BevFeatureSlicer(bevformer_bev_conf, grid_conf)\n        \n        self.bev_size = bev_size\n        self.bev_proj_dim = bev_proj_dim\n\n        if bev_proj_nlayers == 0:\n            self.bev_light_proj = nn.Sequential()\n        else:\n            self.bev_light_proj = SimpleConv2d(\n                in_channels=bev_emb_dim,\n                conv_channels=bev_emb_dim,\n                out_channels=bev_proj_dim,\n                num_conv=bev_proj_nlayers,\n            )\n\n        # Downscale bev_feat -> /4\n        self.base_downscale = nn.Sequential(\n            Bottleneck(in_channels=bev_proj_dim, downsample=True),\n            Bottleneck(in_channels=bev_proj_dim, downsample=True)\n        )\n\n        # Future blocks with transformer\n        self.n_future_blocks = self.n_future + 1\n\n        # - transformer\n        self.attn_mask_thresh = attn_mask_thresh\n        \n        self.num_trans_layers = transformer_decoder.num_layers\n        assert self.num_trans_layers % self.n_future_blocks == 0\n\n        self.num_heads = transformer_decoder.transformerlayers.\\\n            attn_cfgs.num_heads\n        self.transformer_decoder = build_transformer_layer_sequence(\n            transformer_decoder)\n\n        # - temporal-mlps\n        # query_out_dim = bev_proj_dim\n\n        temporal_mlp = MLP(query_dim, query_dim, bev_proj_dim, num_layers=temporal_mlp_layer)\n        self.temporal_mlps = _get_clones(temporal_mlp, self.n_future_blocks)\n            \n        # - downscale-convs\n        downscale_conv = Bottleneck(in_channels=bev_proj_dim, downsample=True)\n        self.downscale_convs = _get_clones(downscale_conv, self.n_future_blocks)\n        \n        # - upsampleAdds\n        upsample_add = UpsamplingAdd(in_channels=bev_proj_dim, out_channels=bev_proj_dim)\n        self.upsample_adds = _get_clones(upsample_add, self.n_future_blocks)\n\n        # Decoder\n        self.dense_decoder = CVT_Decoder(\n            dim=bev_proj_dim,\n            blocks=[bev_proj_dim, bev_proj_dim],\n        )\n\n        # Query\n        self.mode_fuser = nn.Sequential(\n                nn.Linear(query_dim, bev_proj_dim),\n                nn.LayerNorm(bev_proj_dim),\n                nn.ReLU(inplace=True)\n            )\n        self.multi_query_fuser =  nn.Sequential(\n                nn.Linear(query_dim * 3, query_dim * 2),\n                nn.LayerNorm(query_dim * 2),\n                nn.ReLU(inplace=True),\n                nn.Linear(query_dim * 2, bev_proj_dim),\n            )\n\n        self.detach_query_pos = detach_query_pos\n\n        self.query_to_occ_feat = MLP(\n            query_dim, query_dim, bev_proj_dim, num_layers=query_mlp_layers\n        )\n        self.temporal_mlp_for_mask = copy.deepcopy(self.query_to_occ_feat)\n        \n        # Loss\n        # For matching\n        self.sample_ignore_mode = sample_ignore_mode\n        assert self.sample_ignore_mode in ['all_valid', 'past_valid', 'none']\n\n        self.aux_loss_weight = aux_loss_weight\n\n        self.loss_dice = build_loss(loss_dice)\n        self.loss_mask = build_loss(loss_mask)\n\n        self.pan_eval = pan_eval\n        self.test_seg_thresh  = test_seg_thresh\n\n        self.test_with_track_score = test_with_track_score\n        self.init_weights()\n\n    def init_weights(self):\n        for p in self.transformer_decoder.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_normal_(p)\n\n    def get_attn_mask(self, state, ins_query):\n        # state: b, c, h, w\n        # ins_query: b, q, c\n        ins_embed = self.temporal_mlp_for_mask(\n            ins_query \n        )\n        mask_pred = torch.einsum(\"bqc,bchw->bqhw\", ins_embed, state)\n        attn_mask = mask_pred.sigmoid() < self.attn_mask_thresh\n        attn_mask = rearrange(attn_mask, 'b q h w -> b (h w) q').unsqueeze(1).repeat(\n            1, self.num_heads, 1, 1).flatten(0, 1)\n        attn_mask = attn_mask.detach()\n        \n        # if a mask is all True(all background), then set it all False.\n        attn_mask[torch.where(\n            attn_mask.sum(-1) == attn_mask.shape[-1])] = False\n\n        upsampled_mask_pred = F.interpolate(\n            mask_pred,\n            self.bev_size,\n            mode='bilinear',\n            align_corners=False\n        )  # Supervised by gt\n\n        return attn_mask, upsampled_mask_pred, ins_embed\n\n    def forward(self, x, ins_query):\n        base_state = rearrange(x, '(h w) b d -> b d h w', h=self.bev_size[0])\n\n        base_state = self.bev_sampler(base_state)\n        base_state = self.bev_light_proj(base_state)\n        base_state = self.base_downscale(base_state)\n        base_ins_query = ins_query\n\n        last_state = base_state\n        last_ins_query = base_ins_query\n        future_states = []\n        mask_preds = []\n        temporal_query = []\n        temporal_embed_for_mask_attn = []\n        n_trans_layer_each_block = self.num_trans_layers // self.n_future_blocks\n        assert n_trans_layer_each_block >= 1\n        \n        for i in range(self.n_future_blocks):\n            # Downscale\n            cur_state = self.downscale_convs[i](last_state)  # /4 -> /8\n\n            # Attention\n            # temporal_aware ins_query\n            cur_ins_query = self.temporal_mlps[i](last_ins_query)  # [b, q, d]\n            temporal_query.append(cur_ins_query)\n\n            # Generate attn mask \n            attn_mask, mask_pred, cur_ins_emb_for_mask_attn = self.get_attn_mask(cur_state, cur_ins_query)\n            attn_masks = [None, attn_mask] \n\n            mask_preds.append(mask_pred)  # /1\n            temporal_embed_for_mask_attn.append(cur_ins_emb_for_mask_attn)\n\n            cur_state = rearrange(cur_state, 'b c h w -> (h w) b c')\n            cur_ins_query = rearrange(cur_ins_query, 'b q c -> q b c')\n\n            for j in range(n_trans_layer_each_block):\n                trans_layer_ind = i * n_trans_layer_each_block + j\n                trans_layer = self.transformer_decoder.layers[trans_layer_ind]\n                cur_state = trans_layer(\n                    query=cur_state,  # [h'*w', b, c]\n                    key=cur_ins_query,  # [nq, b, c]\n                    value=cur_ins_query,  # [nq, b, c]\n                    query_pos=None,  \n                    key_pos=None,\n                    attn_masks=attn_masks,\n                    query_key_padding_mask=None,\n                    key_padding_mask=None\n                )  # out size: [h'*w', b, c]\n\n            cur_state = rearrange(cur_state, '(h w) b c -> b c h w', h=self.bev_size[0]//8)\n            \n            # Upscale to /4\n            cur_state = self.upsample_adds[i](cur_state, last_state)\n\n            # Out\n            future_states.append(cur_state)  # [b, d, h/4, w/4]\n            last_state = cur_state\n\n        future_states = torch.stack(future_states, dim=1)  # [b, t, d, h/4, w/4]\n        temporal_query = torch.stack(temporal_query, dim=1)  # [b, t, q, d]\n        mask_preds = torch.stack(mask_preds, dim=2)  # [b, q, t, h, w]\n        ins_query = torch.stack(temporal_embed_for_mask_attn, dim=1)  # [b, t, q, d]\n\n        # Decode future states to larger resolution\n        future_states = self.dense_decoder(future_states)\n        ins_occ_query = self.query_to_occ_feat(ins_query)    # [b, t, q, query_out_dim]\n        \n        # Generate final outputs\n        ins_occ_logits = torch.einsum(\"btqc,btchw->bqthw\", ins_occ_query, future_states)\n        \n        return mask_preds, ins_occ_logits\n\n    def merge_queries(self, outs_dict, detach_query_pos=True):\n        ins_query = outs_dict.get('traj_query', None)       # [n_dec, b, nq, n_modes, dim]\n        track_query = outs_dict['track_query']              # [b, nq, d]\n        track_query_pos = outs_dict['track_query_pos']      # [b, nq, d]\n\n        if detach_query_pos:\n            track_query_pos = track_query_pos.detach()\n\n        ins_query = ins_query[-1]\n        ins_query = self.mode_fuser(ins_query).max(2)[0]\n        ins_query = self.multi_query_fuser(torch.cat([ins_query, track_query, track_query_pos], dim=-1))\n        \n        return ins_query\n\n    # With matched queries [a small part of all queries] and matched_gt results\n    def forward_train(\n                    self,\n                    bev_feat,\n                    outs_dict,\n                    gt_inds_list=None,\n                    gt_segmentation=None,\n                    gt_instance=None,\n                    gt_img_is_valid=None,\n                ):\n        # Generate warpped gt and related inputs\n        gt_segmentation, gt_instance, gt_img_is_valid = self.get_occ_labels(gt_segmentation, gt_instance, gt_img_is_valid)\n        \n        all_matched_gt_ids = outs_dict['all_matched_idxes']  # list of tensor, length bs\n\n        ins_query = self.merge_queries(outs_dict, self.detach_query_pos)\n\n        # Forward the occ-flow model\n        mask_preds_batch, ins_seg_preds_batch = self(bev_feat, ins_query=ins_query)\n        \n        # Get pred and gt\n        ins_seg_targets_batch  = gt_instance # [1, 5, 200, 200] [b, t, h, w] # ins targets of a batch\n        \n        # img_valid flag, for filtering out invalid samples in sequence when calculating loss\n        img_is_valid = gt_img_is_valid  # [1, 7]\n        assert img_is_valid.size(1) == self.receptive_field + self.n_future,  \\\n                f\"Img_is_valid can only be 7 as for loss calculation and evaluation!!! Don't change it\"\n        frame_valid_mask = img_is_valid.bool()\n        past_valid_mask  = frame_valid_mask[:, :self.receptive_field]\n        future_frame_mask = frame_valid_mask[:, (self.receptive_field-1):]  # [1, 5]  including current frame\n\n        # only supervise when all 3 past frames are valid\n        past_valid = past_valid_mask.all(dim=1)\n        future_frame_mask[~past_valid] = False\n        \n        # Calculate loss in the batch\n        loss_dict = dict()\n        loss_dice = ins_seg_preds_batch.new_zeros(1)[0].float()\n        loss_mask = ins_seg_preds_batch.new_zeros(1)[0].float()\n        loss_aux_dice = ins_seg_preds_batch.new_zeros(1)[0].float()\n        loss_aux_mask = ins_seg_preds_batch.new_zeros(1)[0].float()\n\n        bs = ins_query.size(0)\n        assert bs == 1\n        for ind in range(bs):\n            # Each gt_bboxes contains 3 frames, we only use the last one\n            cur_gt_inds   = gt_inds_list[ind][-1]\n\n            cur_matched_gt = all_matched_gt_ids[ind]  # [n_gt]\n            \n            # Re-order gt according to matched_gt_inds\n            cur_gt_inds   = cur_gt_inds[cur_matched_gt]\n            \n            # Deal matched_gt: -1, its actually background(unmatched)\n            cur_gt_inds[cur_matched_gt == -1] = -1  # Bugfixed\n            cur_gt_inds[cur_matched_gt == -2] = -2  \n\n            frame_mask = future_frame_mask[ind]  # [t]\n\n            # Prediction\n            ins_seg_preds = ins_seg_preds_batch[ind]   # [q(n_gt for matched), t, h, w]\n            ins_seg_targets = ins_seg_targets_batch[ind]  # [t, h, w]\n            mask_preds = mask_preds_batch[ind]\n            \n            # Assigned-gt\n            ins_seg_targets_ordered = []\n            for ins_id in cur_gt_inds:\n                # -1 for unmatched query\n                # If ins_seg_targets is all 255, ignore (directly append occ-and-flow gt to list)\n                # 255 for special object --> change to -20 (same as in occ_label.py)\n                # -2 for no_query situation\n                if (ins_seg_targets == self.ignore_index).all().item() is True:\n                    ins_tgt = ins_seg_targets.long()\n                elif ins_id.item() in [-1, -2] :  # false positive query (unmatched)\n                    ins_tgt = torch.ones_like(ins_seg_targets).long() * self.ignore_index\n                else:\n                    SPECIAL_INDEX = -20\n                    if ins_id.item() == self.ignore_index:\n                        ins_id = torch.ones_like(ins_id) * SPECIAL_INDEX\n                    ins_tgt = (ins_seg_targets == ins_id).long()  # [t, h, w], 0 or 1\n                \n                ins_seg_targets_ordered.append(ins_tgt)\n            \n            ins_seg_targets_ordered = torch.stack(ins_seg_targets_ordered, dim=0)  # [n_gt, t, h, w]\n            \n            # Sanity check\n            t, h, w = ins_seg_preds.shape[-3:]\n            assert t == 1+self.n_future, f\"{ins_seg_preds.size()}\"\n            assert ins_seg_preds.size() == ins_seg_targets_ordered.size(),   \\\n                            f\"{ins_seg_preds.size()}, {ins_seg_targets_ordered.size()}\"\n            \n            num_total_pos = ins_seg_preds.size(0)  # Check this line \n\n            # loss for a sample in batch\n            num_total_pos = ins_seg_preds.new_tensor([num_total_pos])\n            num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n            \n            cur_dice_loss = self.loss_dice(\n                ins_seg_preds, ins_seg_targets_ordered, avg_factor=num_total_pos, frame_mask=frame_mask)\n\n            cur_mask_loss = self.loss_mask(\n                ins_seg_preds, ins_seg_targets_ordered, frame_mask=frame_mask\n            )\n\n            cur_aux_dice_loss = self.loss_dice(\n                mask_preds, ins_seg_targets_ordered, avg_factor=num_total_pos, frame_mask=frame_mask\n            )\n            cur_aux_mask_loss = self.loss_mask(\n                mask_preds, ins_seg_targets_ordered, frame_mask=frame_mask\n            )\n\n            loss_dice += cur_dice_loss\n            loss_mask += cur_mask_loss\n            loss_aux_dice += cur_aux_dice_loss * self.aux_loss_weight\n            loss_aux_mask += cur_aux_mask_loss * self.aux_loss_weight\n\n        loss_dict['loss_dice'] = loss_dice / bs\n        loss_dict['loss_mask'] = loss_mask / bs\n        loss_dict['loss_aux_dice'] = loss_aux_dice / bs\n        loss_dict['loss_aux_mask'] = loss_aux_mask / bs\n\n        return loss_dict\n\n    def forward_test(\n                    self,\n                    bev_feat,\n                    outs_dict,\n                    no_query=False,\n                    gt_segmentation=None,\n                    gt_instance=None,\n                    gt_img_is_valid=None,\n                ):\n        out_dict = dict()\n\n        #import pdb;pdb.set_trace()\n\n        if gt_segmentation is not None and gt_instance is not None:\n            gt_segmentation, gt_instance, gt_img_is_valid = self.get_occ_labels(gt_segmentation, gt_instance, gt_img_is_valid)\n\n            \n            out_dict['seg_gt']  = gt_segmentation[:, :1+self.n_future]  # [1, 5, 1, 200, 200]\n            out_dict['ins_seg_gt'] = self.get_ins_seg_gt(gt_instance[:, :1+self.n_future])  # [1, 5, 200, 200]\n        if no_query:\n            # output all zero results\n            out_dict['seg_out'] = torch.zeros((1, 5, 1, 200, 200),device=bev_feat.device).long()  # [1, 5, 1, 200, 200]\n            out_dict['ins_seg_out'] = torch.zeros((1, 5, 1, 200, 200),device=bev_feat.device).long()  # [1, 5, 200, 200]\n            return out_dict\n\n\n        ins_query = self.merge_queries(outs_dict, self.detach_query_pos)\n\n        _, pred_ins_logits = self(bev_feat, ins_query=ins_query)\n\n        out_dict['pred_ins_logits'] = pred_ins_logits\n\n        pred_ins_logits = pred_ins_logits[:,:,:1+self.n_future]  # [b, q, t, h, w]\n        pred_ins_sigmoid = pred_ins_logits.sigmoid()  # [b, q, t, h, w]\n\n        if self.test_with_track_score:\n            track_scores = outs_dict['track_scores'].to(pred_ins_sigmoid)  # [b, q]\n            track_scores = track_scores[:, :, None, None, None]\n            pred_ins_sigmoid = pred_ins_sigmoid * track_scores  # [b, q, t, h, w]\n\n        out_dict['pred_ins_sigmoid'] = pred_ins_sigmoid\n        pred_seg_scores = pred_ins_sigmoid.max(1)[0]\n        seg_out = (pred_seg_scores > self.test_seg_thresh).long().unsqueeze(2)  # [b, t, 1, h, w]\n        out_dict['seg_out'] = seg_out\n        if self.pan_eval:\n            # ins_pred\n            pred_consistent_instance_seg =  \\\n                predict_instance_segmentation_and_trajectories(seg_out, pred_ins_sigmoid)  # bg is 0, fg starts with 1, consecutive\n            \n            out_dict['ins_seg_out'] = pred_consistent_instance_seg  # [1, 5, 200, 200]\n\n        return out_dict\n\n    def get_ins_seg_gt(self, gt_instance):\n        ins_gt_old = gt_instance  # Not consecutive, 0 for bg, otherwise ins_ind(start from 1)\n        ins_gt_new = torch.zeros_like(ins_gt_old).to(ins_gt_old)  # Make it consecutive\n        ins_inds_unique = torch.unique(ins_gt_old)\n        new_id = 1\n        for uni_id in ins_inds_unique:\n            if uni_id.item() in [0, self.ignore_index]:  # ignore background_id\n                continue\n            ins_gt_new[ins_gt_old == uni_id] = new_id\n            new_id += 1\n        return ins_gt_new  # Consecutive\n\n    def get_occ_labels(self, gt_segmentation, gt_instance, gt_img_is_valid):\n        if not self.training:\n            gt_segmentation = gt_segmentation[0]\n            gt_instance = gt_instance[0]\n            gt_img_is_valid = gt_img_is_valid[0]\n\n        gt_segmentation = gt_segmentation[:, :self.n_future+1].long().unsqueeze(2)\n        gt_instance = gt_instance[:, :self.n_future+1].long()\n        gt_img_is_valid = gt_img_is_valid[:, :self.receptive_field + self.n_future]\n        return gt_segmentation, gt_instance, gt_img_is_valid\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/occ_head_plugin/__init__.py",
    "content": "from .utils import *\nfrom .metrics import *\nfrom .modules import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/occ_head_plugin/metrics.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nfrom typing import Optional\n\nimport torch\nfrom mmcv.metrics.metric import Metric\nfrom mmcv.metrics.classification import stat_scores_multiple_classes\nfrom mmcv.metrics.reduction import reduce\n\nclass IntersectionOverUnion(Metric):\n    \"\"\"Computes intersection-over-union.\"\"\"\n    def __init__(\n        self,\n        n_classes: int,\n        ignore_index: Optional[int] = None,\n        absent_score: float = 0.0,\n        reduction: str = 'none',\n    ):\n        super().__init__()\n\n        self.n_classes = n_classes\n        self.ignore_index = ignore_index\n        self.absent_score = absent_score\n        self.reduction = reduction\n\n        self.add_state('true_positive', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n        self.add_state('false_positive', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n        self.add_state('false_negative', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n        self.add_state('support', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n\n    def update(self, prediction: torch.Tensor, target: torch.Tensor):\n        tps, fps, _, fns, sups = stat_scores_multiple_classes(prediction, target, self.n_classes)\n\n        self.true_positive += tps\n        self.false_positive += fps\n        self.false_negative += fns\n        self.support += sups\n\n    def compute(self):\n        scores = torch.zeros(self.n_classes, device=self.true_positive.device, dtype=torch.float32)\n\n        for class_idx in range(self.n_classes):\n            if class_idx == self.ignore_index:\n                continue\n\n            tp = self.true_positive[class_idx]\n            fp = self.false_positive[class_idx]\n            fn = self.false_negative[class_idx]\n            sup = self.support[class_idx]\n\n            # If this class is absent in the target (no support) AND absent in the pred (no true or false\n            # positives), then use the absent_score for this class.\n            if sup + tp + fp == 0:\n                scores[class_idx] = self.absent_score\n                continue\n\n            denominator = tp + fp + fn\n            score = tp.to(torch.float) / denominator\n            scores[class_idx] = score\n\n        # Remove the ignored class index from the scores.\n        if (self.ignore_index is not None) and (0 <= self.ignore_index < self.n_classes):\n            scores = torch.cat([scores[:self.ignore_index], scores[self.ignore_index+1:]])\n\n        return reduce(scores, reduction=self.reduction)\n\n\nclass PanopticMetric(Metric):\n    def __init__(\n        self,\n        n_classes: int,\n        temporally_consistent: bool = True,\n        vehicles_id: int = 1,\n    ):\n        super().__init__()\n\n        self.n_classes = n_classes\n        self.temporally_consistent = temporally_consistent\n        self.vehicles_id = vehicles_id\n        self.keys = ['iou', 'true_positive', 'false_positive', 'false_negative']\n\n        self.add_state('iou', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n        self.add_state('true_positive', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n        self.add_state('false_positive', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n        self.add_state('false_negative', default=torch.zeros(n_classes), dist_reduce_fx='sum')\n\n    def update(self, pred_instance, gt_instance):\n        \"\"\"\n        Update state with predictions and targets.\n\n        Parameters\n        ----------\n            pred_instance: (b, s, h, w)\n                Temporally consistent instance segmentation prediction.\n            gt_instance: (b, s, h, w)\n                Ground truth instance segmentation.\n        \"\"\"\n        batch_size, sequence_length = gt_instance.shape[:2]\n        # Process labels\n        assert gt_instance.min() == 0, 'ID 0 of gt_instance must be background'\n        pred_segmentation = (pred_instance > 0).long()\n        gt_segmentation = (gt_instance > 0).long()\n\n        for b in range(batch_size):\n            unique_id_mapping = {}\n            for t in range(sequence_length):\n                result = self.panoptic_metrics(\n                    pred_segmentation[b, t].detach(),\n                    pred_instance[b, t].detach(),\n                    gt_segmentation[b, t],\n                    gt_instance[b, t],\n                    unique_id_mapping,\n                )\n\n                self.iou += result['iou']\n                self.true_positive += result['true_positive']\n                self.false_positive += result['false_positive']\n                self.false_negative += result['false_negative']\n\n    def compute(self):\n        denominator = torch.maximum(\n            (self.true_positive + self.false_positive / 2 + self.false_negative / 2),\n            torch.ones_like(self.true_positive)\n        )\n        pq = self.iou / denominator\n        sq = self.iou / torch.maximum(self.true_positive, torch.ones_like(self.true_positive))\n        rq = self.true_positive / denominator\n\n        return {'pq': pq,\n                'sq': sq,\n                'rq': rq,\n                # If 0, it means there wasn't any detection.\n                'denominator': (self.true_positive + self.false_positive / 2 + self.false_negative / 2),\n                }\n\n    def panoptic_metrics(self, pred_segmentation, pred_instance, gt_segmentation, gt_instance, unique_id_mapping):\n        \"\"\"\n        Computes panoptic quality metric components.\n\n        Parameters\n        ----------\n            pred_segmentation: [H, W] range {0, ..., n_classes-1} (>= n_classes is void)\n            pred_instance: [H, W] range {0, ..., n_instances} (zero means background)\n            gt_segmentation: [H, W] range {0, ..., n_classes-1} (>= n_classes is void)\n            gt_instance: [H, W] range {0, ..., n_instances} (zero means background)\n            unique_id_mapping: instance id mapping to check consistency\n        \"\"\"\n        n_classes = self.n_classes\n\n        result = {key: torch.zeros(n_classes, dtype=torch.float32, device=gt_instance.device) for key in self.keys}\n\n        assert pred_segmentation.dim() == 2\n        assert pred_segmentation.shape == pred_instance.shape == gt_segmentation.shape == gt_instance.shape\n\n        n_instances = int(torch.cat([pred_instance, gt_instance]).max().item())\n        n_all_things = n_instances + n_classes  # Classes + instances.\n        n_things_and_void = n_all_things + 1\n\n        # Now 1 is background; 0 is void (not used). 2 is vehicle semantic class but since it overlaps with\n        # instances, it is not present.\n        # and the rest are instance ids starting from 3\n        prediction, pred_to_cls = self.combine_mask(pred_segmentation, pred_instance, n_classes, n_all_things)\n        target, target_to_cls = self.combine_mask(gt_segmentation, gt_instance, n_classes, n_all_things)\n\n        # Compute ious between all stuff and things\n        # hack for bincounting 2 arrays together\n        x = prediction + n_things_and_void * target\n        bincount_2d = torch.bincount(x.long(), minlength=n_things_and_void ** 2)\n        if bincount_2d.shape[0] != n_things_and_void ** 2:\n            raise ValueError('Incorrect bincount size.')\n        conf = bincount_2d.reshape((n_things_and_void, n_things_and_void))\n        # Drop void class\n        conf = conf[1:, 1:]\n\n        # Confusion matrix contains intersections between all combinations of classes\n        union = conf.sum(0).unsqueeze(0) + conf.sum(1).unsqueeze(1) - conf\n        iou = torch.where(union > 0, (conf.float() + 1e-9) / (union.float() + 1e-9), torch.zeros_like(union).float())\n\n        # In the iou matrix, first dimension is target idx, second dimension is pred idx.\n        # Mapping will contain a tuple that maps prediction idx to target idx for segments matched by iou.\n        mapping = (iou > 0.5).nonzero(as_tuple=False)\n\n        # Check that classes match.\n        is_matching = pred_to_cls[mapping[:, 1]] == target_to_cls[mapping[:, 0]]\n        mapping = mapping[is_matching]\n        tp_mask = torch.zeros_like(conf, dtype=torch.bool)\n        tp_mask[mapping[:, 0], mapping[:, 1]] = True\n\n        # First ids correspond to \"stuff\" i.e. semantic seg.\n        # Instance ids are offset accordingly\n        for target_id, pred_id in mapping:\n            cls_id = pred_to_cls[pred_id]\n\n            if self.temporally_consistent and cls_id == self.vehicles_id:\n                if target_id.item() in unique_id_mapping and unique_id_mapping[target_id.item()] != pred_id.item():\n                    # Not temporally consistent\n                    result['false_negative'][target_to_cls[target_id]] += 1\n                    result['false_positive'][pred_to_cls[pred_id]] += 1\n                    unique_id_mapping[target_id.item()] = pred_id.item()\n                    continue\n\n            result['true_positive'][cls_id] += 1\n            result['iou'][cls_id] += iou[target_id][pred_id]\n            unique_id_mapping[target_id.item()] = pred_id.item()\n\n        for target_id in range(n_classes, n_all_things):\n            # If this is a true positive do nothing.\n            if tp_mask[target_id, n_classes:].any():\n                continue\n            # If this target instance didn't match with any predictions and was present set it as false negative.\n            if target_to_cls[target_id] != -1:\n                result['false_negative'][target_to_cls[target_id]] += 1\n\n        for pred_id in range(n_classes, n_all_things):\n            # If this is a true positive do nothing.\n            if tp_mask[n_classes:, pred_id].any():\n                continue\n            # If this predicted instance didn't match with any prediction, set that predictions as false positive.\n            if pred_to_cls[pred_id] != -1 and (conf[:, pred_id] > 0).any():\n                result['false_positive'][pred_to_cls[pred_id]] += 1\n\n        return result\n\n    def combine_mask(self, segmentation: torch.Tensor, instance: torch.Tensor, n_classes: int, n_all_things: int):\n        \"\"\"Shifts all things ids by num_classes and combines things and stuff into a single mask\n\n        Returns a combined mask + a mapping from id to segmentation class.\n        \"\"\"\n        instance = instance.view(-1)\n        instance_mask = instance > 0\n        instance = instance - 1 + n_classes\n\n        segmentation = segmentation.clone().view(-1)\n        segmentation_mask = segmentation < n_classes  # Remove void pixels.\n\n        # Build an index from instance id to class id.\n        instance_id_to_class_tuples = torch.cat(\n            (\n                instance[instance_mask & segmentation_mask].unsqueeze(1),\n                segmentation[instance_mask & segmentation_mask].unsqueeze(1),\n            ),\n            dim=1,\n        )\n        instance_id_to_class = -instance_id_to_class_tuples.new_ones((n_all_things,))\n        instance_id_to_class[instance_id_to_class_tuples[:, 0]] = instance_id_to_class_tuples[:, 1]\n        instance_id_to_class[torch.arange(n_classes, device=segmentation.device)] = torch.arange(\n            n_classes, device=segmentation.device\n        )\n\n        segmentation[instance_mask] = instance[instance_mask]\n        segmentation += 1  # Shift all legit classes by 1.\n        segmentation[~segmentation_mask] = 0  # Shift void class to zero.\n\n        return segmentation, instance_id_to_class"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/occ_head_plugin/modules.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nfrom torch import nn\nimport torch.utils.checkpoint as checkpoint\nfrom .utils import calculate_birds_eye_view_parameters\nimport torch.nn.functional as F\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom mmcv.models.bricks import ConvModule, build_conv_layer\nfrom einops import rearrange\nfrom collections import OrderedDict\n\n# Grid sampler\n# Sample a smaller receptive-field bev from larger one\nclass BevFeatureSlicer(nn.Module):\n    def __init__(self, grid_conf, map_grid_conf):\n        super().__init__()\n        if grid_conf == map_grid_conf:\n            self.identity_mapping = True\n        else:\n            self.identity_mapping = False\n\n            bev_resolution, bev_start_position, bev_dimension= calculate_birds_eye_view_parameters(\n                grid_conf['xbound'], grid_conf['ybound'], grid_conf['zbound']\n            )\n\n            map_bev_resolution, map_bev_start_position, map_bev_dimension = calculate_birds_eye_view_parameters(\n                map_grid_conf['xbound'], map_grid_conf['ybound'], map_grid_conf['zbound']\n            )\n\n            self.map_x = torch.arange(\n                map_bev_start_position[0], map_grid_conf['xbound'][1], map_bev_resolution[0])\n\n            self.map_y = torch.arange(\n                map_bev_start_position[1], map_grid_conf['ybound'][1], map_bev_resolution[1])\n\n            # convert to normalized coords\n            self.norm_map_x = self.map_x / (- bev_start_position[0])\n            self.norm_map_y = self.map_y / (- bev_start_position[1])\n\n            tmp_m, tmp_n = torch.meshgrid(\n                self.norm_map_x, self.norm_map_y)  # indexing 'ij'\n            tmp_m, tmp_n = tmp_m.T, tmp_n.T  # change it to the 'xy' mode results\n\n            self.map_grid = torch.stack([tmp_m, tmp_n], dim=2)\n\n    def forward(self, x):\n        # x: bev feature map tensor of shape (b, c, h, w)\n        if self.identity_mapping:\n            return x\n        else:\n            grid = self.map_grid.unsqueeze(0).type_as(\n                x).repeat(x.shape[0], 1, 1, 1)  # (b, h, w, 2)\n\n            return F.grid_sample(x, grid=grid, mode='bilinear', align_corners=True)\n\n# General layers\nclass MLP(nn.Module):\n    \"\"\"Very simple multi-layer perceptron (also called FFN)\"\"\"\n\n    def __init__(self, input_dim, hidden_dim, output_dim, num_layers):\n        super().__init__()\n        self.num_layers = num_layers\n        h = [hidden_dim] * (num_layers - 1)\n        self.layers = nn.ModuleList(\n            nn.Linear(n, k) for n, k in zip([input_dim] + h, h + [output_dim])\n        )\n\n    def forward(self, x):\n        for i, layer in enumerate(self.layers):\n            x = F.relu(layer(x)) if i < self.num_layers - 1 else layer(x)\n        return x\n\nclass SimpleConv2d(BaseModule):\n    def __init__(self, in_channels, \n                       out_channels, \n                       \n                       conv_channels=64,\n                       num_conv=1,\n                       conv_cfg=dict(type='Conv2d'),\n                       norm_cfg=dict(type='BN2d'),\n                       bias='auto',\n                       init_cfg=None,\n                       ):\n        assert init_cfg is None, 'To prevent abnormal initialization ' \\\n            'behavior, init_cfg is not allowed to be set'\n        super().__init__(init_cfg=init_cfg)\n        self.out_channels = out_channels\n        if num_conv == 1:\n            conv_channels = in_channels\n\n        conv_layers = []\n        c_in = in_channels\n        for i in range(num_conv-1):\n            conv_layers.append(\n                ConvModule(\n                    c_in,\n                    conv_channels,\n                    kernel_size=3,\n                    stride=1,\n                    padding=1,\n                    bias=bias,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=norm_cfg,\n                )\n            )\n            c_in = conv_channels\n        # No norm and relu in last conv\n        conv_layers.append(\n            build_conv_layer(\n                conv_cfg,\n                conv_channels,\n                out_channels,\n                kernel_size=1,\n                stride=1,\n                padding=0,\n                bias=True\n            )\n        )\n        self.conv_layers = nn.Sequential(*conv_layers)\n\n        if init_cfg is None:\n            self.init_cfg = dict(type='Kaiming', layer='Conv2d')\n\n    def forward(self, x):\n        b, c_in, h_in, w_in = x.size()\n        out = self.conv_layers(x)\n        assert out.size() == (b, self.out_channels, h_in, w_in)  # sanity check\n        return out\n\n# Decoder\nclass CVT_DecoderBlock(nn.Module):\n    def __init__(self, in_channels, out_channels, skip_dim, residual, factor, upsample, with_relu=True):\n        super().__init__()\n\n        dim = out_channels // factor\n\n        if upsample:\n            self.conv = nn.Sequential(\n                nn.Upsample(scale_factor=2, mode='bilinear', align_corners=True),\n                nn.Conv2d(in_channels, dim, 3, padding=1, bias=False),\n                nn.BatchNorm2d(dim),\n                nn.ReLU(inplace=True),\n                nn.Conv2d(dim, out_channels, 1, padding=0, bias=False),\n                nn.BatchNorm2d(out_channels))\n        else:\n            self.conv = nn.Sequential(\n                nn.Conv2d(in_channels, dim, 3, padding=1, bias=False),\n                nn.BatchNorm2d(dim),\n                nn.ReLU(inplace=True),\n                nn.Conv2d(dim, out_channels, 1, padding=0, bias=False),\n                nn.BatchNorm2d(out_channels))\n\n        if residual:\n            self.up = nn.Conv2d(skip_dim, out_channels, 1)\n        else:\n            self.up = None\n        \n        self.with_relu = with_relu\n        if self.with_relu:\n            self.relu = nn.ReLU(inplace=True)\n\n    def forward(self, x, skip):\n        x = self.conv(x)\n\n        if self.up is not None:\n            up = self.up(skip)\n            up = F.interpolate(up, x.shape[-2:])\n\n            x = x + up\n        if self.with_relu:\n            return self.relu(x)\n        return x\n\nclass CVT_Decoder(BaseModule):\n    def __init__(self, dim, blocks, residual=True, factor=2, upsample=True, use_checkpoint=False, init_cfg=None):\n        assert init_cfg is None, 'To prevent abnormal initialization ' \\\n            'behavior, init_cfg is not allowed to be set'\n        super().__init__(init_cfg=init_cfg)\n\n        layers = []\n        channels = dim\n\n        for i, out_channels in enumerate(blocks):\n            with_relu = i < len(blocks) - 1  # if not last block, with relu\n            layer = CVT_DecoderBlock(channels, out_channels, dim, residual, factor, upsample, with_relu=with_relu)\n            layers.append(layer)\n\n            channels = out_channels\n\n        self.layers = nn.Sequential(*layers)\n        self.out_channels = channels\n        self.use_checkpoint = use_checkpoint\n        \n        if init_cfg is None:\n            self.init_cfg = dict(type='Kaiming', layer='Conv2d')\n\n    def forward(self, x):\n        b, t = x.size(0), x.size(1)\n        x = rearrange(x, 'b t c h w -> (b t) c h w')\n        y = x\n        for layer in self.layers:\n            if self.use_checkpoint:\n                y = checkpoint(layer, y, x)\n            else:\n                y = layer(y, x)\n        \n        y = rearrange(y, '(b t) c h w -> b t c h w', b=b, t=t)\n        return y\n\n\n# Conv modules\nclass UpsamplingAdd(nn.Module):\n    def __init__(self, in_channels, out_channels, scale_factor=2):\n        super().__init__()\n        self.upsample_layer = nn.Sequential(\n            nn.Upsample(scale_factor=scale_factor, mode='bilinear', align_corners=False),\n            nn.Conv2d(in_channels, out_channels, kernel_size=1, padding=0, bias=False),\n            nn.BatchNorm2d(out_channels),\n        )\n\n    def forward(self, x, x_skip):\n        x = self.upsample_layer(x)\n        return x + x_skip\n\nclass Interpolate(nn.Module):\n    def __init__(self, scale_factor: int = 2):\n        super().__init__()\n        self._interpolate = nn.functional.interpolate\n        self._scale_factor = scale_factor\n\n    def forward(self, x):\n        return self._interpolate(x, scale_factor=self._scale_factor, mode='bilinear', align_corners=False)\n\nclass Bottleneck(nn.Module):\n    \"\"\"\n    Defines a bottleneck module with a residual connection\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels=None,\n        kernel_size=3,\n        dilation=1,\n        groups=1,\n        upsample=False,\n        downsample=False,\n        dropout=0.0,\n    ):\n        super().__init__()\n        self._downsample = downsample\n        bottleneck_channels = int(in_channels / 2)\n        out_channels = out_channels or in_channels\n        padding_size = ((kernel_size - 1) * dilation + 1) // 2\n\n        # Define the main conv operation\n        assert dilation == 1\n        if upsample:\n            assert not downsample, 'downsample and upsample not possible simultaneously.'\n            bottleneck_conv = nn.ConvTranspose2d(\n                bottleneck_channels,\n                bottleneck_channels,\n                kernel_size=kernel_size,\n                bias=False,\n                dilation=1,\n                stride=2,\n                output_padding=padding_size,\n                padding=padding_size,\n                groups=groups,\n            )\n        elif downsample:\n            bottleneck_conv = nn.Conv2d(\n                bottleneck_channels,\n                bottleneck_channels,\n                kernel_size=kernel_size,\n                bias=False,\n                dilation=dilation,\n                stride=2,\n                padding=padding_size,\n                groups=groups,\n            )\n        else:\n            bottleneck_conv = nn.Conv2d(\n                bottleneck_channels,\n                bottleneck_channels,\n                kernel_size=kernel_size,\n                bias=False,\n                dilation=dilation,\n                padding=padding_size,\n                groups=groups,\n            )\n\n        self.layers = nn.Sequential(\n            OrderedDict(\n                [\n                    # First projection with 1x1 kernel\n                    ('conv_down_project', nn.Conv2d(in_channels, bottleneck_channels, kernel_size=1, bias=False)),\n                    ('abn_down_project', nn.Sequential(nn.BatchNorm2d(bottleneck_channels),\n                                                       nn.ReLU(inplace=True))),\n                    # Second conv block\n                    ('conv', bottleneck_conv),\n                    ('abn', nn.Sequential(nn.BatchNorm2d(bottleneck_channels), nn.ReLU(inplace=True))),\n                    # Final projection with 1x1 kernel\n                    ('conv_up_project', nn.Conv2d(bottleneck_channels, out_channels, kernel_size=1, bias=False)),\n                    ('abn_up_project', nn.Sequential(nn.BatchNorm2d(out_channels),\n                                                     nn.ReLU(inplace=True))),\n                    # Regulariser\n                    ('dropout', nn.Dropout2d(p=dropout)),\n                ]\n            )\n        )\n\n        if out_channels == in_channels and not downsample and not upsample:\n            self.projection = None\n        else:\n            projection = OrderedDict()\n            if upsample:\n                projection.update({'upsample_skip_proj': Interpolate(scale_factor=2)})\n            elif downsample:\n                projection.update({'upsample_skip_proj': nn.MaxPool2d(kernel_size=2, stride=2)})\n            projection.update(\n                {\n                    'conv_skip_proj': nn.Conv2d(in_channels, out_channels, kernel_size=1, bias=False),\n                    'bn_skip_proj': nn.BatchNorm2d(out_channels),\n                }\n            )\n            self.projection = nn.Sequential(projection)\n\n    def forward(self, *args):\n        (x,) = args\n        x_residual = self.layers(x)\n        if self.projection is not None:\n            if self._downsample:\n                # pad h/w dimensions if they are odd to prevent shape mismatch with residual layer\n                x = nn.functional.pad(x, (0, x.shape[-1] % 2, 0, x.shape[-2] % 2), value=0)\n            return x_residual + self.projection(x)\n        return x_residual + x\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/occ_head_plugin/utils.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nimport numpy as np\n\n\ndef calculate_birds_eye_view_parameters(x_bounds, y_bounds, z_bounds):\n    \"\"\"\n    Parameters\n    ----------\n        x_bounds: Forward direction in the ego-car.\n        y_bounds: Sides\n        z_bounds: Height\n\n    Returns\n    -------\n        bev_resolution: Bird's-eye view bev_resolution\n        bev_start_position Bird's-eye view first element\n        bev_dimension Bird's-eye view tensor spatial dimension\n    \"\"\"\n    bev_resolution = torch.tensor(\n        [row[2] for row in [x_bounds, y_bounds, z_bounds]])\n    bev_start_position = torch.tensor(\n        [row[0] + row[2] / 2.0 for row in [x_bounds, y_bounds, z_bounds]])\n    bev_dimension = torch.tensor([(row[1] - row[0]) / row[2]\n                                 for row in [x_bounds, y_bounds, z_bounds]], dtype=torch.long)\n\n    return bev_resolution, bev_start_position, bev_dimension\n\n\ndef gen_dx_bx(xbound, ybound, zbound):\n    dx = torch.Tensor([row[2] for row in [xbound, ybound, zbound]])\n    bx = torch.Tensor([row[0] + row[2]/2.0 for row in [xbound, ybound, zbound]])\n    nx = torch.LongTensor([(row[1] - row[0]) / row[2] for row in [xbound, ybound, zbound]])\n\n    return dx, bx, nx\n\n# Instance utils\ndef update_instance_ids(instance_seg, old_ids, new_ids):\n    \"\"\"\n    Parameters\n    ----------\n        instance_seg: torch.Tensor arbitrary shape\n        old_ids: 1D tensor containing the list of old ids, must be all present in instance_seg.\n        new_ids: 1D tensor with the new ids, aligned with old_ids\n\n    Returns\n        new_instance_seg: torch.Tensor same shape as instance_seg with new ids\n    \"\"\"\n    indices = torch.arange(old_ids.max() + 1, device=instance_seg.device)\n    for old_id, new_id in zip(old_ids, new_ids):\n        indices[old_id] = new_id\n\n    return indices[instance_seg].long()\n\n\ndef make_instance_seg_consecutive(instance_seg):\n    # Make the indices of instance_seg consecutive\n    unique_ids = torch.unique(instance_seg)  # include background\n    new_ids = torch.arange(len(unique_ids), device=instance_seg.device)\n    instance_seg = update_instance_ids(instance_seg, unique_ids, new_ids)\n    return instance_seg\n\n\ndef predict_instance_segmentation_and_trajectories(\n                                    foreground_masks,\n                                    ins_sigmoid,\n                                    vehicles_id=1,\n                                    ):\n    if foreground_masks.dim() == 5 and foreground_masks.shape[2] == 1:\n        foreground_masks = foreground_masks.squeeze(2)  # [b, t, h, w]\n    foreground_masks = foreground_masks == vehicles_id  # [b, t, h, w]  Only these places have foreground id\n    \n    argmax_ins = ins_sigmoid.argmax(dim=1)  # long, [b, t, h, w], ins_id starts from 0\n    argmax_ins = argmax_ins + 1 # [b, t, h, w], ins_id starts from 1\n    instance_seg = (argmax_ins * foreground_masks.float()).long()  # bg is 0, fg starts with 1\n\n    # Make the indices of instance_seg consecutive\n    instance_seg = make_instance_seg_consecutive(instance_seg).long()\n\n    return instance_seg\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/panseg_head.py",
    "content": "#----------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)   #\n# Source code: https://github.com/OpenDriveLab/UniAD                               #\n# Copyright (c) OpenDriveLab. All rights reserved.                                 #\n# Modified from panoptic_segformer (https://github.com/zhiqi-li/Panoptic-SegFormer)#\n#--------------------------------------------------------------------------------- #\n\nimport copy\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.bricks import Linear\nfrom mmcv.models.utils import bias_init_with_prob, constant_init\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.models.builder import HEADS, build_loss\nfrom mmcv.core.bbox.transforms import bbox_cxcywh_to_xyxy, bbox_xyxy_to_cxcywh\nfrom mmcv.core.bbox.builder import build_assigner, build_sampler\nfrom mmcv.core.utils import multi_apply, reduce_mean\nfrom mmcv.models.utils import build_transformer\nfrom .seg_head_plugin import SegDETRHead, IOU\n\n@HEADS.register_module()\nclass PansegformerHead(SegDETRHead):\n    \"\"\"\n    Head of Panoptic SegFormer\n\n    Code is modified from the `official github repo\n    <https://github.com/open-mmlab/mmcvection>`_.\n\n    Args:\n        with_box_refine (bool): Whether to refine the reference points\n            in the decoder. Defaults to False.\n        as_two_stage (bool) : Whether to generate the proposal from\n            the outputs of encoder.\n        transformer (obj:`ConfigDict`): ConfigDict is used for building\n            the Encoder and Decoder.\n    \"\"\"\n\n    def __init__(\n            self,\n            *args,\n            bev_h,\n            bev_w,\n            canvas_size,\n            pc_range,\n            with_box_refine=False,\n            as_two_stage=False,\n            transformer=None,\n            quality_threshold_things=0.25,\n            quality_threshold_stuff=0.25,\n            overlap_threshold_things=0.4,\n            overlap_threshold_stuff=0.2,\n            thing_transformer_head=dict(\n                type='TransformerHead',  # mask decoder for things\n                d_model=256,\n                nhead=8,\n                num_decoder_layers=6),\n            stuff_transformer_head=dict(\n                type='TransformerHead',  # mask decoder for stuff\n                d_model=256,\n                nhead=8,\n                num_decoder_layers=6),\n            loss_mask=dict(type='DiceLoss', weight=2.0),\n            train_cfg=dict(\n                assigner=dict(type='HungarianAssigner',\n                              cls_cost=dict(type='ClassificationCost',\n                                            weight=1.),\n                              reg_cost=dict(type='BBoxL1Cost', weight=5.0),\n                              iou_cost=dict(type='IoUCost',\n                                            iou_mode='giou',\n                                            weight=2.0)),\n                sampler=dict(type='PseudoSampler'),\n            ),\n            **kwargs):\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.canvas_size = canvas_size\n        self.pc_range = pc_range\n        self.real_w = self.pc_range[3] - self.pc_range[0]\n        self.real_h = self.pc_range[4] - self.pc_range[1]\n\n        self.with_box_refine = with_box_refine\n        self.as_two_stage = as_two_stage\n        self.quality_threshold_things = 0.1\n        self.quality_threshold_stuff = quality_threshold_stuff\n        self.overlap_threshold_things = overlap_threshold_things\n        self.overlap_threshold_stuff = overlap_threshold_stuff\n        self.fp16_enabled = False\n\n        if self.as_two_stage:\n            transformer['as_two_stage'] = self.as_two_stage\n        self.num_dec_things = thing_transformer_head['num_decoder_layers']\n        self.num_dec_stuff = stuff_transformer_head['num_decoder_layers']\n        super(PansegformerHead, self).__init__(*args,\n                                            transformer=transformer,\n                                            train_cfg=train_cfg,\n                                            **kwargs)\n        if train_cfg:\n            sampler_cfg = train_cfg['sampler_with_mask']\n            self.sampler_with_mask = build_sampler(sampler_cfg, context=self)\n            assigner_cfg = train_cfg['assigner_with_mask']\n            self.assigner_with_mask = build_assigner(assigner_cfg)\n            self.assigner_filter = build_assigner(\n                dict(\n                    type='HungarianAssigner_filter',\n                    cls_cost=dict(type='FocalLossCost', weight=2.0),\n                    reg_cost=dict(type='BBoxL1Cost',\n                                  weight=5.0,\n                                  box_format='xywh'),\n                    iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0),\n                    max_pos=\n                    3  # Depends on GPU memory, setting it to 1, model can be trained on 1080Ti\n                ), )\n\n        self.loss_mask = build_loss(loss_mask)\n        self.things_mask_head = build_transformer(thing_transformer_head)\n        self.stuff_mask_head = build_transformer(stuff_transformer_head)\n        self.count = 0\n\n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        if not self.as_two_stage:\n            self.bev_embedding = nn.Embedding(self.bev_h * self.bev_w, self.embed_dims)\n\n        fc_cls = Linear(self.embed_dims, self.cls_out_channels)\n        fc_cls_stuff = Linear(self.embed_dims, 1)\n        reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            reg_branch.append(nn.ReLU())\n        reg_branch.append(Linear(self.embed_dims, 4))\n        reg_branch = nn.Sequential(*reg_branch)\n\n        def _get_clones(module, N):\n            return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n        # last reg_branch is used to generate proposal from\n        # encode feature map when as_two_stage is True.\n        num_pred = (self.transformer.decoder.num_layers + 1) if \\\n            self.as_two_stage else self.transformer.decoder.num_layers\n\n        if self.with_box_refine:\n            self.cls_branches = _get_clones(fc_cls, num_pred)\n            self.reg_branches = _get_clones(reg_branch, num_pred)\n        else:\n            self.cls_branches = nn.ModuleList(\n                [fc_cls for _ in range(num_pred)])\n            self.reg_branches = nn.ModuleList(\n                [reg_branch for _ in range(num_pred)])\n        if not self.as_two_stage:\n            self.query_embedding = nn.Embedding(self.num_query,\n                                                self.embed_dims * 2)\n        self.stuff_query = nn.Embedding(self.num_stuff_classes,\n                                        self.embed_dims * 2)\n        self.reg_branches2 = _get_clones(reg_branch, self.num_dec_things) # used in mask decoder\n        self.cls_thing_branches = _get_clones(fc_cls, self.num_dec_things) # used in mask decoder\n        self.cls_stuff_branches = _get_clones(fc_cls_stuff, self.num_dec_stuff) # used in mask deocder\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the DeformDETR head.\"\"\"\n        self.transformer.init_weights()\n        if self.loss_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.cls_branches:\n                nn.init.constant_(m.bias, bias_init)\n            for m in self.cls_thing_branches:\n                nn.init.constant_(m.bias, bias_init)\n            for m in self.cls_stuff_branches:\n                nn.init.constant_(m.bias, bias_init)\n        for m in self.reg_branches:\n            constant_init(m[-1], 0, bias=0)\n        for m in self.reg_branches2:\n            constant_init(m[-1], 0, bias=0)\n        nn.init.constant_(self.reg_branches[0][-1].bias.data[2:], -2.0)\n\n        if self.as_two_stage:\n            for m in self.reg_branches:\n                nn.init.constant_(m[-1].bias.data[2:], 0.0)\n\n    @force_fp32(apply_to=('bev_embed', ))\n    def forward(self, bev_embed):\n        \"\"\"Forward function.\n\n        Args:\n            bev_embed (tuple[Tensor]): Features from the upstream\n                network, each is a 4D-tensor with shape\n                (N, C, H, W).\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head, \\\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression \\\n                head with normalized coordinate format (cx, cy, w, h). \\\n                Shape [nb_dec, bs, num_query, 4].\n            enc_outputs_class (Tensor): The score of each point on encode \\\n                feature map, has shape (N, h*w, num_class). Only when \\\n                as_two_stage is True it would be returned, otherwise \\\n                `None` would be returned.\n            enc_outputs_coord (Tensor): The proposal generate from the \\\n                encode feature map, has shape (N, h*w, 4). Only when \\\n                as_two_stage is True it would be returned, otherwise \\\n                `None` would be returned.\n        \"\"\"\n        _, bs, _ = bev_embed.shape\n\n        mlvl_feats = [torch.reshape(bev_embed, (bs, self.bev_h, self.bev_w ,-1)).permute(0, 3, 1, 2)]\n        img_masks = mlvl_feats[0].new_zeros((bs, self.bev_h, self.bev_w))\n\n        hw_lvl = [feat_lvl.shape[-2:] for feat_lvl in mlvl_feats]\n        mlvl_masks = []\n        mlvl_positional_encodings = []\n        for feat in mlvl_feats:\n            mlvl_masks.append(\n                F.interpolate(img_masks[None],\n                              size=feat.shape[-2:]).to(torch.bool).squeeze(0))\n            mlvl_positional_encodings.append(\n                self.positional_encoding(mlvl_masks[-1]))\n\n        query_embeds = None\n        if not self.as_two_stage:\n            query_embeds = self.query_embedding.weight\n        (memory, memory_pos, memory_mask, query_pos), hs, init_reference, inter_references, \\\n        enc_outputs_class, enc_outputs_coord = self.transformer(\n            mlvl_feats,\n            mlvl_masks,\n            query_embeds,\n            mlvl_positional_encodings,\n            reg_branches=self.reg_branches if self.with_box_refine else None,  # noqa:E501\n            cls_branches=self.cls_branches if self.as_two_stage else None  # noqa:E501\n        )\n\n        memory = memory.permute(1, 0, 2)\n        query = hs[-1].permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        memory_pos = memory_pos.permute(1, 0, 2)\n\n        # we should feed these to mask deocder.\n        args_tuple = [memory, memory_mask, memory_pos, query, None, query_pos, hw_lvl]\n\n        hs = hs.permute(0, 2, 1, 3)\n        outputs_classes = []\n        outputs_coords = []\n        for lvl in range(hs.shape[0]):\n            if lvl == 0:\n                reference = init_reference\n            else:\n                reference = inter_references[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            outputs_class = self.cls_branches[lvl](hs[lvl])\n            tmp = self.reg_branches[lvl](hs[lvl])\n\n            if reference.shape[-1] == 4:\n                tmp += reference\n            else:\n                assert reference.shape[-1] == 2\n                tmp[..., :2] += reference\n            outputs_coord = tmp.sigmoid()\n            outputs_classes.append(outputs_class)\n            outputs_coords.append(outputs_coord)\n\n        outputs_classes = torch.stack(outputs_classes)\n        outputs_coords = torch.stack(outputs_coords)\n\n        outs = {\n                'bev_embed': None if self.as_two_stage else bev_embed,\n                'outputs_classes': outputs_classes,\n                'outputs_coords': outputs_coords,\n                'enc_outputs_class': enc_outputs_class if self.as_two_stage else None,\n                'enc_outputs_coord': enc_outputs_coord.sigmoid() if self.as_two_stage else None,\n                'args_tuple': args_tuple,\n                'reference': reference,\n            }\n        \n        return outs\n\n    @force_fp32(apply_to=('all_cls_scores_list', 'all_bbox_preds_list',\n                          'args_tuple', 'reference'))\n    def loss(\n        self,\n        all_cls_scores,\n        all_bbox_preds,\n        enc_cls_scores,\n        enc_bbox_preds,\n        args_tuple,\n        reference,\n        gt_labels_list,\n        gt_bboxes_list,\n        gt_masks_list,\n        img_metas=None,\n        gt_bboxes_ignore=None,\n    ):\n        \"\"\"\"Loss function.\n\n        Args:\n            all_cls_scores (Tensor): Classification score of all\n                decoder layers, has shape\n                [nb_dec, bs, num_query, cls_out_channels].\n            all_bbox_preds (Tensor): Sigmoid regression\n                outputs of all decode layers. Each is a 4D-tensor with\n                normalized coordinate format (cx, cy, w, h) and shape\n                [nb_dec, bs, num_query, 4].\n            enc_cls_scores (Tensor): Classification scores of\n                points on encode feature map , has shape\n                (N, h*w, num_classes). Only be passed when as_two_stage is\n                True, otherwise is None.\n            enc_bbox_preds (Tensor): Regression results of each points\n                on the encode feature map, has shape (N, h*w, 4). Only be\n                passed when as_two_stage is True, otherwise is None.\n            args_tuple (Tuple) several args\n            reference (Tensor) reference from location decoder\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        img_metas[0]['img_shape'] = (self.canvas_size[0], self.canvas_size[1], 3)\n\n        assert gt_bboxes_ignore is None, \\\n            f'{self.__class__.__name__} only supports ' \\\n            f'for gt_bboxes_ignore setting to None.'\n\n        ### seprate things and stuff\n        gt_things_lables_list = []\n        gt_things_bboxes_list = []\n        gt_things_masks_list = []\n        gt_stuff_labels_list = []\n        gt_stuff_masks_list = []\n        for i, each in enumerate(gt_labels_list):   \n            # MDS: for coco, id<80 (Continuous id) is things. This is not true for other data sets\n            things_selected = each < self.num_things_classes\n\n            stuff_selected = things_selected == False\n\n            gt_things_lables_list.append(gt_labels_list[i][things_selected])\n            gt_things_bboxes_list.append(gt_bboxes_list[i][things_selected])\n            gt_things_masks_list.append(gt_masks_list[i][things_selected])\n\n            gt_stuff_labels_list.append(gt_labels_list[i][stuff_selected])\n            gt_stuff_masks_list.append(gt_masks_list[i][stuff_selected])\n\n        num_dec_layers = len(all_cls_scores)\n        all_gt_bboxes_list = [\n            gt_things_bboxes_list for _ in range(num_dec_layers - 1)\n        ]\n        all_gt_labels_list = [\n            gt_things_lables_list for _ in range(num_dec_layers - 1)\n        ]\n        # all_gt_masks_list = [gt_masks_list for _ in range(num_dec_layers-1)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers - 1)\n        ]\n        img_metas_list = [img_metas for _ in range(num_dec_layers - 1)]\n\n        # if the location decoder codntains L layers, we compute the losses of the first L-1 layers\n        losses_cls, losses_bbox, losses_iou = multi_apply(\n            self.loss_single, all_cls_scores[:-1], all_bbox_preds[:-1],\n            all_gt_bboxes_list, all_gt_labels_list, img_metas_list,\n            all_gt_bboxes_ignore_list)\n\n        losses_cls_f, losses_bbox_f, losses_iou_f, losses_masks_things_f, losses_masks_stuff_f, loss_mask_things_list_f, loss_mask_stuff_list_f, loss_iou_list_f, loss_bbox_list_f, loss_cls_list_f, loss_cls_stuff_list_f, things_ratio, stuff_ratio = self.loss_single_panoptic(\n            all_cls_scores[-1], all_bbox_preds[-1], args_tuple, reference,\n            gt_things_bboxes_list, gt_things_lables_list, gt_things_masks_list,\n            (gt_stuff_labels_list, gt_stuff_masks_list), img_metas,\n            gt_bboxes_ignore)\n\n        loss_dict = dict()\n        # loss of proposal generated from encode feature map.\n        if enc_cls_scores is not None:\n            binary_labels_list = [\n                torch.zeros_like(gt_things_lables_list[i])\n                for i in range(len(img_metas))\n            ]\n            enc_loss_cls, enc_losses_bbox, enc_losses_iou = \\\n                self.loss_single(enc_cls_scores, enc_bbox_preds,\n                                 gt_things_bboxes_list, binary_labels_list,\n                                 img_metas, gt_bboxes_ignore)\n            loss_dict['enc_loss_cls'] = enc_loss_cls * things_ratio\n            loss_dict['enc_loss_bbox'] = enc_losses_bbox * things_ratio\n            loss_dict['enc_loss_iou'] = enc_losses_iou * things_ratio\n            # loss_dict['enc_loss_mask'] = enc_losses_mask\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls_f * things_ratio\n        loss_dict['loss_bbox'] = losses_bbox_f * things_ratio\n        loss_dict['loss_iou'] = losses_iou_f * things_ratio\n        loss_dict['loss_mask_things'] = losses_masks_things_f * things_ratio\n        loss_dict['loss_mask_stuff'] = losses_masks_stuff_f * stuff_ratio\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for i in range(len(loss_mask_things_list_f)):\n            loss_dict[f'd{i}.loss_mask_things_f'] = loss_mask_things_list_f[\n                i] * things_ratio\n            loss_dict[f'd{i}.loss_iou_f'] = loss_iou_list_f[i] * things_ratio\n            loss_dict[f'd{i}.loss_bbox_f'] = loss_bbox_list_f[i] * things_ratio\n            loss_dict[f'd{i}.loss_cls_f'] = loss_cls_list_f[i] * things_ratio\n        for i in range(len(loss_mask_stuff_list_f)):\n            loss_dict[f'd{i}.loss_mask_stuff_f'] = loss_mask_stuff_list_f[\n                i] * stuff_ratio\n            loss_dict[f'd{i}.loss_cls_stuff_f'] = loss_cls_stuff_list_f[\n                i] * stuff_ratio\n        for loss_cls_i, loss_bbox_i, loss_iou_i in zip(\n                losses_cls,\n                losses_bbox,\n                losses_iou,\n        ):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i * things_ratio\n            loss_dict[\n                f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i * things_ratio\n            loss_dict[f'd{num_dec_layer}.loss_iou'] = loss_iou_i * things_ratio\n\n            num_dec_layer += 1\n        # print(loss_dict)\n        return loss_dict\n\n    def filter_query(self,\n                     cls_scores_list,\n                     bbox_preds_list,\n                     gt_bboxes_list,\n                     gt_labels_list,\n                     img_metas,\n                     gt_bboxes_ignore_list=None):\n        '''\n        This function aims to using the cost from the location decoder to filter out low-quality queries.\n        '''\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (pos_inds_mask_list, neg_inds_mask_list, labels_list,\n         label_weights_list, bbox_targets_list,\n         bbox_weights_list, pos_inds_list, neg_inds_list) = multi_apply(\n             self._filter_query_single, cls_scores_list, bbox_preds_list,\n             gt_bboxes_list, gt_labels_list, img_metas, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n\n        return pos_inds_mask_list, neg_inds_mask_list, labels_list, label_weights_list, bbox_targets_list, \\\n               bbox_weights_list, num_total_pos, num_total_neg, pos_inds_list, neg_inds_list\n\n    def _filter_query_single(self,\n                             cls_score,\n                             bbox_pred,\n                             gt_bboxes,\n                             gt_labels,\n                             img_meta,\n                             gt_bboxes_ignore=None):\n        num_bboxes = bbox_pred.size(0)\n        pos_ind_mask, neg_ind_mask, assign_result = self.assigner_filter.assign(\n            bbox_pred, cls_score, gt_bboxes, gt_labels, img_meta,\n            gt_bboxes_ignore)\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes, ),\n                                    self.num_things_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n        img_h, img_w, _ = img_meta['img_shape']\n\n        # DETR regress the relative position of boxes (cxcywh) in the image.\n        # Thus the learning target should be normalized by the image size, also\n        # the box format should be converted from defaultly x1y1x2y2 to cxcywh.\n        factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                       img_h]).unsqueeze(0)\n        pos_gt_bboxes_normalized = sampling_result.pos_gt_bboxes / factor\n        pos_gt_bboxes_targets = bbox_xyxy_to_cxcywh(pos_gt_bboxes_normalized)\n        bbox_targets[pos_inds] = pos_gt_bboxes_targets\n\n        return (pos_ind_mask, neg_ind_mask, labels, label_weights,\n                bbox_targets, bbox_weights, pos_inds, neg_inds)\n\n    def get_targets_with_mask(self,\n                              cls_scores_list,\n                              bbox_preds_list,\n                              masks_preds_list_thing,\n                              gt_bboxes_list,\n                              gt_labels_list,\n                              gt_masks_list,\n                              img_metas,\n                              gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n\n        Outputs from a single decoder layer of a single feature level are used.\n\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            masks_preds_list_thing  (list[Tensor]):\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         mask_targets_list, mask_weights_list, pos_inds_list,\n         neg_inds_list) = multi_apply(self._get_target_single_with_mask,\n                                      cls_scores_list, bbox_preds_list,\n                                      masks_preds_list_thing, gt_bboxes_list,\n                                      gt_labels_list, gt_masks_list, img_metas,\n                                      gt_bboxes_ignore_list)\n        num_total_pos_thing = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg_thing = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, mask_targets_list, mask_weights_list,\n                num_total_pos_thing, num_total_neg_thing, pos_inds_list)\n\n    def _get_target_single_with_mask(self,\n                                     cls_score,\n                                     bbox_pred,\n                                     masks_preds_things,\n                                     gt_bboxes,\n                                     gt_labels,\n                                     gt_masks,\n                                     img_meta,\n                                     gt_bboxes_ignore=None):\n        \"\"\"\n        \"\"\"\n\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n\n        gt_masks = gt_masks.float()\n\n        assign_result = self.assigner_with_mask.assign(bbox_pred, cls_score,\n                                                       masks_preds_things,\n                                                       gt_bboxes, gt_labels,\n                                                       gt_masks, img_meta,\n                                                       gt_bboxes_ignore)\n        sampling_result = self.sampler_with_mask.sample(\n            assign_result, bbox_pred, gt_bboxes, gt_masks)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes, ),\n                                    self.num_things_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n        img_h, img_w, _ = img_meta['img_shape']\n\n        # DETR regress the relative position of boxes (cxcywh) in the image.\n        # Thus the learning target should be normalized by the image size, also\n        # the box format should be converted from defaultly x1y1x2y2 to cxcywh.\n        factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                       img_h]).unsqueeze(0)\n        pos_gt_bboxes_normalized = sampling_result.pos_gt_bboxes / factor\n        pos_gt_bboxes_targets = bbox_xyxy_to_cxcywh(pos_gt_bboxes_normalized)\n        bbox_targets[pos_inds] = pos_gt_bboxes_targets\n\n        mask_weights = masks_preds_things.new_zeros(num_bboxes)\n        mask_weights[pos_inds] = 1.0\n        pos_gt_masks = sampling_result.pos_gt_masks\n        _, w, h = pos_gt_masks.shape\n        mask_target = masks_preds_things.new_zeros([num_bboxes, w, h])\n        mask_target[pos_inds] = pos_gt_masks\n\n        return (labels, label_weights, bbox_targets, bbox_weights, mask_target,\n                mask_weights, pos_inds, neg_inds)\n\n    def get_filter_results_and_loss(self, cls_scores, bbox_preds,\n                                    cls_scores_list, bbox_preds_list,\n                                    gt_bboxes_list, gt_labels_list, img_metas,\n                                    gt_bboxes_ignore_list):\n\n\n        pos_inds_mask_list, neg_inds_mask_list, labels_list, label_weights_list, bbox_targets_list, \\\n        bbox_weights_list, num_total_pos_thing, num_total_neg_thing, pos_inds_list, neg_inds_list = self.filter_query(\n            cls_scores_list, bbox_preds_list,\n            gt_bboxes_list, gt_labels_list,\n            img_metas, gt_bboxes_ignore_list)\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos_thing * 1.0 + \\\n                         num_total_neg_thing * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n        cls_avg_factor = max(cls_avg_factor, 1)\n\n        loss_cls = self.loss_cls(cls_scores,\n                                 labels,\n                                 label_weights,\n                                 avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n\n        num_total_pos_thing = loss_cls.new_tensor([num_total_pos_thing])\n        num_total_pos_thing = torch.clamp(reduce_mean(num_total_pos_thing),\n                                          min=1).item()\n\n        # construct factors used for rescale bboxes\n        factors = []\n        for img_meta, bbox_pred in zip(img_metas, bbox_preds):\n            img_h, img_w, _ = img_meta['img_shape']\n            factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                           img_h]).unsqueeze(0).repeat(\n                                               bbox_pred.size(0), 1)\n            factors.append(factor)\n        factors = torch.cat(factors, 0)\n\n        # DETR regress the relative position of boxes (cxcywh) in the image,\n        # thus the learning target is normalized by the image size. So here\n        # we need to re-scale them for calculating IoU loss\n        \n        bbox_preds = bbox_preds.reshape(-1, 4)\n        bboxes = bbox_cxcywh_to_xyxy(bbox_preds) * factors\n        bboxes_gt = bbox_cxcywh_to_xyxy(bbox_targets) * factors\n\n        # regression IoU loss, defaultly GIoU loss\n        loss_iou = self.loss_iou(bboxes,\n                                 bboxes_gt,\n                                 bbox_weights,\n                                 avg_factor=num_total_pos_thing)\n\n        # regression L1 loss\n        loss_bbox = self.loss_bbox(bbox_preds,\n                                   bbox_targets,\n                                   bbox_weights,\n                                   avg_factor=num_total_pos_thing)\n        return loss_cls, loss_iou, loss_bbox,\\\n            pos_inds_mask_list, num_total_pos_thing\n\n    def loss_single_panoptic(self,\n                             cls_scores,\n                             bbox_preds,\n                             args_tuple,\n                             reference,\n                             gt_bboxes_list,\n                             gt_labels_list,\n                             gt_masks_list,\n                             gt_panoptic_list,\n                             img_metas,\n                             gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            args_tuple:\n            reference:\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        gt_stuff_labels_list, gt_stuff_masks_list = gt_panoptic_list\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        loss_cls, loss_iou, loss_bbox, pos_inds_mask_list, num_total_pos_thing = self.get_filter_results_and_loss(\n            cls_scores, bbox_preds, cls_scores_list, bbox_preds_list, gt_bboxes_list, gt_labels_list, img_metas, gt_bboxes_ignore_list)\n\n        memory, memory_mask, memory_pos, query, _, query_pos, hw_lvl = args_tuple\n\n        BS, _, dim_query = query.shape[0], query.shape[1], query.shape[-1]\n\n        len_query = max([len(pos_ind) for pos_ind in pos_inds_mask_list])\n        thing_query = torch.zeros([BS, len_query, dim_query],\n                                  device=query.device)\n\n        stuff_query, stuff_query_pos = torch.split(self.stuff_query.weight,\n                                                   self.embed_dims,\n                                                   dim=1)\n        stuff_query_pos = stuff_query_pos.unsqueeze(0).expand(BS, -1, -1)\n        stuff_query = stuff_query.unsqueeze(0).expand(BS, -1, -1)\n\n        for i in range(BS):\n            thing_query[i, :len(pos_inds_mask_list[i])] = query[\n                i, pos_inds_mask_list[i]]\n\n        mask_preds_things = []\n        mask_preds_stuff = []\n        # mask_preds_inter = [[],[],[]]\n        mask_preds_inter_things = [[] for _ in range(self.num_dec_things)]\n        mask_preds_inter_stuff = [[] for _ in range(self.num_dec_stuff)]\n        cls_thing_preds = [[] for _ in range(self.num_dec_things)]\n        cls_stuff_preds = [[] for _ in range(self.num_dec_stuff)]\n        BS, NQ, L = bbox_preds.shape\n        new_bbox_preds = [\n            torch.zeros([BS, len_query, L]).to(bbox_preds.device)\n            for _ in range(self.num_dec_things)\n        ]\n\n        mask_things, mask_inter_things, query_inter_things = self.things_mask_head(\n            memory, memory_mask, None, thing_query, None, None, hw_lvl=hw_lvl)\n\n        mask_stuff, mask_inter_stuff, query_inter_stuff = self.stuff_mask_head(\n            memory,\n            memory_mask,\n            None,\n            stuff_query,\n            None,\n            stuff_query_pos,\n            hw_lvl=hw_lvl)\n\n        mask_things = mask_things.squeeze(-1)\n        mask_inter_things = torch.stack(mask_inter_things, 0).squeeze(-1)\n\n        mask_stuff = mask_stuff.squeeze(-1)\n        mask_inter_stuff = torch.stack(mask_inter_stuff, 0).squeeze(-1)\n\n        for i in range(BS):\n            tmp_i = mask_things[i][:len(pos_inds_mask_list[i])].reshape(\n                -1, *hw_lvl[0])\n            mask_preds_things.append(tmp_i)\n            pos_ind = pos_inds_mask_list[i]\n            reference_i = reference[i:i + 1, pos_ind, :]\n\n            for j in range(self.num_dec_things):\n                tmp_i_j = mask_inter_things[j][i][:len(pos_inds_mask_list[i]\n                                                       )].reshape(\n                                                           -1, *hw_lvl[0])\n                mask_preds_inter_things[j].append(tmp_i_j)\n\n                # mask_preds_inter_things[j].append(mask_inter_things[j].reshape(-1, *hw_lvl[0]))\n                query_things = query_inter_things[j]\n                t1, t2, t3 = query_things.shape\n                tmp = self.reg_branches2[j](query_things.reshape(t1 * t2, t3)).reshape(t1, t2, 4)\n                if len(pos_ind) == 0:\n                    tmp = tmp.sum(\n                    ) + reference_i  # for reply bug of pytorch broadcast\n                elif reference_i.shape[-1] == 4:\n                    tmp += reference_i\n                else:\n                    assert reference_i.shape[-1] == 2\n                    tmp[..., :2] += reference_i\n\n                outputs_coord = tmp.sigmoid()\n\n                new_bbox_preds[j][i][:len(pos_inds_mask_list[i])] = outputs_coord\n                cls_thing_preds[j].append(self.cls_thing_branches[j](\n                    query_things.reshape(t1 * t2, t3)))\n\n            # stuff\n            tmp_i = mask_stuff[i].reshape(-1, *hw_lvl[0])\n            mask_preds_stuff.append(tmp_i)\n            for j in range(self.num_dec_stuff):\n                tmp_i_j = mask_inter_stuff[j][i].reshape(-1, *hw_lvl[0])\n                mask_preds_inter_stuff[j].append(tmp_i_j)\n\n                query_stuff = query_inter_stuff[j]\n                s1, s2, s3 = query_stuff.shape\n                cls_stuff_preds[j].append(self.cls_stuff_branches[j](\n                    query_stuff.reshape(s1 * s2, s3)))\n\n        masks_preds_list_thing = [\n            mask_preds_things[i] for i in range(num_imgs)\n        ]\n        mask_preds_things = torch.cat(mask_preds_things, 0)\n        mask_preds_inter_things = [\n            torch.cat(each, 0) for each in mask_preds_inter_things\n        ]\n        cls_thing_preds = [torch.cat(each, 0) for each in cls_thing_preds]\n        cls_stuff_preds = [torch.cat(each, 0) for each in cls_stuff_preds]\n        mask_preds_stuff = torch.cat(mask_preds_stuff, 0)\n        mask_preds_inter_stuff = [\n            torch.cat(each, 0) for each in mask_preds_inter_stuff\n        ]\n        cls_scores_list = [\n            cls_scores_list[i][pos_inds_mask_list[i]] for i in range(num_imgs)\n        ]\n\n        bbox_preds_list = [\n            bbox_preds_list[i][pos_inds_mask_list[i]] for i in range(num_imgs)\n        ]\n\n        gt_targets = self.get_targets_with_mask(cls_scores_list,\n                                                bbox_preds_list,\n                                                masks_preds_list_thing,\n                                                gt_bboxes_list, gt_labels_list,\n                                                gt_masks_list, img_metas,\n                                                gt_bboxes_ignore_list)\n\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         mask_targets_list, mask_weights_list, _, _,\n         pos_inds_list) = gt_targets\n\n        thing_labels = torch.cat(labels_list, 0)\n        things_weights = torch.cat(label_weights_list, 0)\n\n        bboxes_taget = torch.cat(bbox_targets_list)\n        bboxes_weights = torch.cat(bbox_weights_list)\n\n        factors = []\n        for img_meta, bbox_pred in zip(img_metas, bbox_preds_list):\n            img_h, img_w, _ = img_meta['img_shape']\n            factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                           img_h]).unsqueeze(0).repeat(\n                                               bbox_pred.size(0), 1)\n            factors.append(factor)\n        factors = torch.cat(factors, 0)\n\n        bboxes_gt = bbox_cxcywh_to_xyxy(bboxes_taget) * factors\n\n        mask_things_gt = torch.cat(mask_targets_list, 0).to(torch.float)\n\n        mask_weight_things = torch.cat(mask_weights_list,\n                                       0).to(thing_labels.device)\n\n        mask_stuff_gt = []\n        mask_weight_stuff = []\n        stuff_labels = []\n        num_total_pos_stuff = 0\n        for i in range(BS):\n            num_total_pos_stuff += len(gt_stuff_labels_list[i])  ## all stuff\n\n            select_stuff_index = gt_stuff_labels_list[\n                i] - self.num_things_classes\n            mask_weight_i_stuff = torch.zeros([self.num_stuff_classes])\n            mask_weight_i_stuff[select_stuff_index] = 1\n            stuff_masks = torch.zeros(\n                (self.num_stuff_classes, *mask_targets_list[i].shape[-2:]),\n                device=mask_targets_list[i].device).to(torch.bool)\n            stuff_masks[select_stuff_index] = gt_stuff_masks_list[i].to(\n                torch.bool)\n            mask_stuff_gt.append(stuff_masks)\n            select_stuff_index = torch.cat([\n                select_stuff_index,\n                torch.tensor([self.num_stuff_classes],\n                             device=select_stuff_index.device)\n            ])\n\n            stuff_labels.append(1 - mask_weight_i_stuff)\n            mask_weight_stuff.append(mask_weight_i_stuff)\n\n        mask_weight_stuff = torch.cat(mask_weight_stuff,\n                                      0).to(thing_labels.device)\n        stuff_labels = torch.cat(stuff_labels, 0).to(thing_labels.device)\n        mask_stuff_gt = torch.cat(mask_stuff_gt, 0).to(torch.float)\n\n        num_total_pos_stuff = loss_cls.new_tensor([num_total_pos_stuff])\n        num_total_pos_stuff = torch.clamp(reduce_mean(num_total_pos_stuff),\n                                          min=1).item()\n        if mask_preds_things.shape[0] == 0:\n            loss_mask_things = (0 * mask_preds_things).sum()\n        else:\n            mask_preds = F.interpolate(mask_preds_things.unsqueeze(0),\n                                       scale_factor=2.0,\n                                       mode='bilinear').squeeze(0)\n            mask_targets_things = F.interpolate(mask_things_gt.unsqueeze(0),\n                                                size=mask_preds.shape[-2:],\n                                                mode='bilinear').squeeze(0)\n            loss_mask_things = self.loss_mask(mask_preds,\n                                              mask_targets_things,\n                                              mask_weight_things,\n                                              avg_factor=num_total_pos_thing)\n        if mask_preds_stuff.shape[0] == 0:\n            loss_mask_stuff = (0 * mask_preds_stuff).sum()\n        else:\n            mask_preds = F.interpolate(mask_preds_stuff.unsqueeze(0),\n                                       scale_factor=2.0,\n                                       mode='bilinear').squeeze(0)\n            mask_targets_stuff = F.interpolate(mask_stuff_gt.unsqueeze(0),\n                                               size=mask_preds.shape[-2:],\n                                               mode='bilinear').squeeze(0)\n\n            loss_mask_stuff = self.loss_mask(mask_preds,\n                                             mask_targets_stuff,\n                                             mask_weight_stuff,\n                                             avg_factor=num_total_pos_stuff)\n\n        loss_mask_things_list = []\n        loss_mask_stuff_list = []\n        loss_iou_list = []\n        loss_bbox_list = []\n        for j in range(len(mask_preds_inter_things)):\n            mask_preds_this_level = mask_preds_inter_things[j]\n            if mask_preds_this_level.shape[0] == 0:\n                loss_mask_j = (0 * mask_preds_this_level).sum()\n            else:\n                mask_preds_this_level = F.interpolate(\n                    mask_preds_this_level.unsqueeze(0),\n                    scale_factor=2.0,\n                    mode='bilinear').squeeze(0)\n                loss_mask_j = self.loss_mask(mask_preds_this_level,\n                                             mask_targets_things,\n                                             mask_weight_things,\n                                             avg_factor=num_total_pos_thing)\n            loss_mask_things_list.append(loss_mask_j)\n            bbox_preds_this_level = new_bbox_preds[j].reshape(-1, 4)\n            bboxes_this_level = bbox_cxcywh_to_xyxy(\n                bbox_preds_this_level) * factors\n            # We let this loss be 0. We didn't predict bbox in our mask decoder. Predicting bbox in the mask decoder is basically useless\n            loss_iou_j = self.loss_iou(bboxes_this_level,\n                                       bboxes_gt,\n                                       bboxes_weights,\n                                       avg_factor=num_total_pos_thing) * 0\n            if bboxes_taget.shape[0] != 0:\n                loss_bbox_j = self.loss_bbox(\n                    bbox_preds_this_level,\n                    bboxes_taget,\n                    bboxes_weights,\n                    avg_factor=num_total_pos_thing) * 0\n            else:\n                loss_bbox_j = bbox_preds_this_level.sum() * 0\n            loss_iou_list.append(loss_iou_j)\n            loss_bbox_list.append(loss_bbox_j)\n        for j in range(len(mask_preds_inter_stuff)):\n            mask_preds_this_level = mask_preds_inter_stuff[j]\n            if mask_preds_this_level.shape[0] == 0:\n                loss_mask_j = (0 * mask_preds_this_level).sum()\n            else:\n                mask_preds_this_level = F.interpolate(\n                    mask_preds_this_level.unsqueeze(0),\n                    scale_factor=2.0,\n                    mode='bilinear').squeeze(0)\n                loss_mask_j = self.loss_mask(mask_preds_this_level,\n                                             mask_targets_stuff,\n                                             mask_weight_stuff,\n                                             avg_factor=num_total_pos_stuff)\n            loss_mask_stuff_list.append(loss_mask_j)\n\n        loss_cls_thing_list = []\n        loss_cls_stuff_list = []\n        thing_labels = thing_labels.reshape(-1)\n        for j in range(len(mask_preds_inter_things)):\n            # We let this loss be 0. When using \"query-filter\", only partial thing queries are feed to the mask decoder. This will cause imbalance when supervising these queries.\n            cls_scores = cls_thing_preds[j]\n\n            if cls_scores.shape[0] == 0:\n                loss_cls_thing_j = cls_scores.sum() * 0\n            else:\n                loss_cls_thing_j = self.loss_cls(\n                    cls_scores,\n                    thing_labels,\n                    things_weights,\n                    avg_factor=num_total_pos_thing) * 2 * 0\n            loss_cls_thing_list.append(loss_cls_thing_j)\n\n        for j in range(len(mask_preds_inter_stuff)):\n            cls_scores = cls_stuff_preds[j]\n            if cls_scores.shape[0] == 0:\n                loss_cls_stuff_j = cls_stuff_preds[j].sum() * 0\n            else:\n                loss_cls_stuff_j = self.loss_cls(\n                    cls_stuff_preds[j],\n                    stuff_labels.to(torch.long),\n                    avg_factor=num_total_pos_stuff) * 2\n            loss_cls_stuff_list.append(loss_cls_stuff_j)\n\n        ## dynamic adjusting the weights\n        things_ratio, stuff_ratio = num_total_pos_thing / (\n            num_total_pos_stuff + num_total_pos_thing), num_total_pos_stuff / (\n                num_total_pos_stuff + num_total_pos_thing)\n\n        return loss_cls, loss_bbox, loss_iou, loss_mask_things, loss_mask_stuff, loss_mask_things_list, loss_mask_stuff_list, loss_iou_list, loss_bbox_list, loss_cls_thing_list, loss_cls_stuff_list, things_ratio, stuff_ratio\n    \n    def forward_test(self,\n                    pts_feats=None,\n                    gt_lane_labels=None,\n                    gt_lane_masks=None,\n                    img_metas=None,\n                    rescale=False):\n        bbox_list = [dict() for i in range(len(img_metas))]\n\n        pred_seg_dict = self(pts_feats)\n        results = self.get_bboxes(pred_seg_dict['outputs_classes'],\n                                           pred_seg_dict['outputs_coords'],\n                                           pred_seg_dict['enc_outputs_class'],\n                                           pred_seg_dict['enc_outputs_coord'],\n                                           pred_seg_dict['args_tuple'],\n                                           pred_seg_dict['reference'],\n                                           img_metas,\n                                           rescale=rescale)\n\n        if gt_lane_labels is None or gt_lane_masks is None:\n            for result_dict, pts_bbox in zip(bbox_list, results):\n                result_dict['pts_bbox'] = pts_bbox\n                result_dict['args_tuple'] = pred_seg_dict['args_tuple']\n            return bbox_list\n\n        with torch.no_grad():\n            drivable_pred = results[0]['drivable']\n            drivable_gt = gt_lane_masks[0][0, -1]\n            drivable_iou, drivable_intersection, drivable_union = IOU(drivable_pred.view(1, -1), drivable_gt.view(1, -1))\n\n            lane_pred = results[0]['lane']\n            lanes_pred = (results[0]['lane'].sum(0) > 0).int()\n            lanes_gt = (gt_lane_masks[0][0][:-1].sum(0) > 0).int()\n            lanes_iou, lanes_intersection, lanes_union = IOU(lanes_pred.view(1, -1), lanes_gt.view(1, -1))\n\n            divider_gt = (gt_lane_masks[0][0][gt_lane_labels[0][0] == 0].sum(0) > 0).int()\n            crossing_gt = (gt_lane_masks[0][0][gt_lane_labels[0][0] == 1].sum(0) > 0).int()\n            contour_gt = (gt_lane_masks[0][0][gt_lane_labels[0][0] == 2].sum(0) > 0).int()\n            divider_iou, divider_intersection, divider_union = IOU(lane_pred[0].view(1, -1), divider_gt.view(1, -1))\n            crossing_iou, crossing_intersection, crossing_union = IOU(lane_pred[1].view(1, -1), crossing_gt.view(1, -1))\n            contour_iou, contour_intersection, contour_union = IOU(lane_pred[2].view(1, -1), contour_gt.view(1, -1))\n\n\n            ret_iou = {'drivable_intersection': drivable_intersection,\n                       'drivable_union': drivable_union,\n                       'lanes_intersection': lanes_intersection,\n                       'lanes_union': lanes_union,\n                       'divider_intersection': divider_intersection,\n                       'divider_union': divider_union,\n                       'crossing_intersection': crossing_intersection,\n                       'crossing_union': crossing_union,\n                       'contour_intersection': contour_intersection,\n                       'contour_union': contour_union,\n                       'drivable_iou': drivable_iou,\n                       'lanes_iou': lanes_iou,\n                       'divider_iou': divider_iou,\n                       'crossing_iou': crossing_iou,\n                       'contour_iou': contour_iou}\n        for result_dict, pts_bbox in zip(bbox_list, results):\n            result_dict['pts_bbox'] = pts_bbox\n            result_dict['ret_iou'] = ret_iou\n            result_dict['args_tuple'] = pred_seg_dict['args_tuple']\n        return bbox_list\n\n\n    @auto_fp16(apply_to=(\"bev_feat\", \"prev_bev\"))\n    def forward_train(self,\n                          bev_feat=None,\n                          img_metas=None,\n                          gt_lane_labels=None,\n                          gt_lane_bboxes=None,\n                          gt_lane_masks=None,\n                         ):\n        \"\"\"\n        Forward pass of the segmentation model during training.\n\n        Args:\n            bev_feat (torch.Tensor): Bird's eye view feature maps. Shape [batch_size, channels, height, width].\n            img_metas (list[dict]): List of image meta information dictionaries.\n            gt_lane_labels (list[torch.Tensor]): Ground-truth lane class labels. Shape [batch_size, num_lanes, max_lanes].\n            gt_lane_bboxes (list[torch.Tensor]): Ground-truth lane bounding boxes. Shape [batch_size, num_lanes, 4].\n            gt_lane_masks (list[torch.Tensor]): Ground-truth lane masks. Shape [batch_size, num_lanes, height, width].\n            prev_bev (torch.Tensor): Previous bird's eye view feature map. Shape [batch_size, channels, height, width].\n\n        Returns:\n            tuple:\n                - losses_seg (torch.Tensor): Total segmentation loss.\n                - pred_seg_dict (dict): Dictionary of predicted segmentation outputs.\n        \"\"\"\n        pred_seg_dict = self(bev_feat)\n        loss_inputs = [\n            pred_seg_dict['outputs_classes'],\n            pred_seg_dict['outputs_coords'],\n            pred_seg_dict['enc_outputs_class'],\n            pred_seg_dict['enc_outputs_coord'],\n            pred_seg_dict['args_tuple'],\n            pred_seg_dict['reference'],\n            gt_lane_labels,\n            gt_lane_bboxes,\n            gt_lane_masks\n        ]\n        losses_seg = self.loss(*loss_inputs, img_metas=img_metas)\n        return losses_seg, pred_seg_dict\n\n    def _get_bboxes_single(self,\n                           cls_score,\n                           bbox_pred,\n                           img_shape,\n                           scale_factor,\n                           rescale=False):\n        \"\"\"\n        \"\"\"\n        assert len(cls_score) == len(bbox_pred)\n        max_per_img = self.test_cfg.get('max_per_img', self.num_query)\n\n        # exclude background\n        if self.loss_cls.use_sigmoid:\n            cls_score = cls_score.sigmoid()\n            scores, indexes = cls_score.view(-1).topk(max_per_img)\n            det_labels = indexes % self.num_things_classes\n            bbox_index = indexes // self.num_things_classes\n            bbox_pred = bbox_pred[bbox_index]\n        else:\n            scores, det_labels = F.softmax(cls_score, dim=-1)[..., :-1].max(-1)\n            scores, bbox_index = scores.topk(max_per_img)\n            bbox_pred = bbox_pred[bbox_index]\n            det_labels = det_labels[bbox_index]\n\n        det_bboxes = bbox_cxcywh_to_xyxy(bbox_pred)\n        det_bboxes[:, 0::2] = det_bboxes[:, 0::2] * img_shape[1]\n        det_bboxes[:, 1::2] = det_bboxes[:, 1::2] * img_shape[0]\n        det_bboxes[:, 0::2].clamp_(min=0, max=img_shape[1])\n        det_bboxes[:, 1::2].clamp_(min=0, max=img_shape[0])\n        if rescale:\n            det_bboxes /= det_bboxes.new_tensor(scale_factor)\n        det_bboxes = torch.cat((det_bboxes, scores.unsqueeze(1)), -1)\n\n        return bbox_index, det_bboxes, det_labels\n\n    @force_fp32(apply_to=('all_cls_scores_list', 'all_bbox_preds_list',\n                          'args_tuple'))\n    def get_bboxes(\n        self,\n        all_cls_scores,\n        all_bbox_preds,\n        enc_cls_scores,\n        enc_bbox_preds,\n        args_tuple,\n        reference,\n        img_metas,\n        rescale=False,\n    ):\n        \"\"\"\n        \"\"\"\n        cls_scores = all_cls_scores[-1]\n        bbox_preds = all_bbox_preds[-1]\n        memory, memory_mask, memory_pos, query, _, query_pos, hw_lvl = args_tuple\n\n        seg_list = []\n        stuff_score_list = []\n        panoptic_list = []\n        bbox_list = []\n        labels_list = []\n        drivable_list = []\n        lane_list = []\n        lane_score_list = []\n        score_list = []\n        for img_id in range(len(img_metas)):\n            cls_score = cls_scores[img_id]\n            bbox_pred = bbox_preds[img_id]\n            # img_shape = img_metas[img_id]['img_shape']\n            # ori_shape = img_metas[img_id]['ori_shape']\n            # scale_factor = img_metas[img_id]['scale_factor']\n            img_shape = (self.canvas_size[0], self.canvas_size[1], 3)\n            ori_shape = (self.canvas_size[0], self.canvas_size[1], 3)\n            scale_factor = 1\n\n            index, bbox, labels = self._get_bboxes_single(\n                cls_score, bbox_pred, img_shape, scale_factor, rescale)\n\n            i = img_id\n            thing_query = query[i:i + 1, index, :]\n            thing_query_pos = query_pos[i:i + 1, index, :]\n            joint_query = torch.cat([\n                thing_query, self.stuff_query.weight[None, :, :self.embed_dims]\n            ], 1)\n\n            stuff_query_pos = self.stuff_query.weight[None, :,\n                                                      self.embed_dims:]\n\n            if self.num_stuff_classes>0:\n                joint_query = joint_query[:, :-self.num_stuff_classes]\n                \n            #import pdb;pdb.set_trace()\n\n            mask_things, mask_inter_things, query_inter_things = self.things_mask_head(\n                memory[i:i + 1],\n                memory_mask[i:i + 1],\n                None,\n                joint_query,\n                None,\n                None,\n                hw_lvl=hw_lvl)\n            # mask_stuff, mask_inter_stuff, query_inter_stuff = self.stuff_mask_head(\n            #     memory[i:i + 1],\n            #     memory_mask[i:i + 1],\n            #     None,\n            #     joint_query,\n            #     None,\n            #     stuff_query_pos,\n            #     hw_lvl=hw_lvl)\n\n            #attn_map = torch.cat([mask_things, mask_stuff], 1) \n            attn_map = mask_things\n\n            attn_map = attn_map.squeeze(-1)  # BS, NQ, N_head,LEN\n\n            # stuff_query = query_inter_stuff[-1]\n            # scores_stuff = self.cls_stuff_branches[-1](\n            #     stuff_query).sigmoid().reshape(-1)\n\n            mask_pred = attn_map.reshape(-1, *hw_lvl[0])\n\n            mask_pred = F.interpolate(mask_pred.unsqueeze(0),\n                                      size=ori_shape[:2],\n                                      mode='bilinear').squeeze(0)\n\n            masks_all = mask_pred\n            score_list.append(masks_all)\n            drivable_list.append(masks_all[-1] > 0.5)\n            if self.num_stuff_classes>0:\n                masks_all = masks_all[:-self.num_stuff_classes]\n            seg_all = masks_all > 0.5\n            sum_seg_all = seg_all.sum((1, 2)).float() + 1\n            # scores_all = torch.cat([bbox[:, -1], scores_stuff], 0)\n            # bboxes_all = torch.cat([bbox, torch.zeros([self.num_stuff_classes, 5], device=labels.device)], 0)\n            # labels_all = torch.cat([labels, torch.arange(self.num_things_classes, self.num_things_classes+self.num_stuff_classes).to(labels.device)], 0)\n            scores_all = bbox[:, -1]\n            bboxes_all = bbox\n            labels_all = labels\n\n            ## mask wise merging\n            seg_scores = (masks_all * seg_all.float()).sum(\n                (1, 2)) / sum_seg_all\n            scores_all *= (seg_scores**2)\n\n            scores_all, index = torch.sort(scores_all, descending=True)\n\n            masks_all = masks_all[index]\n            labels_all = labels_all[index]\n            bboxes_all = bboxes_all[index]\n            seg_all = seg_all[index]\n\n            bboxes_all[:, -1] = scores_all\n\n            # MDS: select things for instance segmeantion\n            things_selected = labels_all < self.num_things_classes\n            stuff_selected = labels_all >= self.num_things_classes\n            bbox_th = bboxes_all[things_selected][:100]\n            labels_th = labels_all[things_selected][:100]\n            seg_th = seg_all[things_selected][:100]\n            labels_st = labels_all[stuff_selected]\n            scores_st = scores_all[stuff_selected]\n            masks_st = masks_all[stuff_selected]\n            \n            stuff_score_list.append(scores_st)\n\n            results = torch.zeros((2, *mask_pred.shape[-2:]),\n                                  device=mask_pred.device).to(torch.long)\n            id_unique = 1\n            lane = torch.zeros((self.num_things_classes, *mask_pred.shape[-2:]), device=mask_pred.device).to(torch.long)\n            lane_score =  torch.zeros((self.num_things_classes, *mask_pred.shape[-2:]), device=mask_pred.device).to(mask_pred.dtype)\n            for i, scores in enumerate(scores_all):\n                # MDS: things and sutff have different threholds may perform a little bit better\n                if labels_all[i] < self.num_things_classes and scores < self.quality_threshold_things:\n                    continue\n                elif labels_all[i] >= self.num_things_classes and scores < self.quality_threshold_stuff:\n                    continue\n                _mask = masks_all[i] > 0.5\n                mask_area = _mask.sum().item()\n                intersect = _mask & (results[0] > 0)\n                intersect_area = intersect.sum().item()\n                if labels_all[i] < self.num_things_classes:\n                    if mask_area == 0 or (intersect_area * 1.0 / mask_area\n                                          ) > self.overlap_threshold_things:\n                        continue\n                else:\n                    if mask_area == 0 or (intersect_area * 1.0 / mask_area\n                                          ) > self.overlap_threshold_stuff:\n                        continue\n                if intersect_area > 0:\n                    _mask = _mask & (results[0] == 0)\n                results[0, _mask] = labels_all[i]\n                if labels_all[i] < self.num_things_classes:\n                    lane[labels_all[i], _mask] = 1\n                    lane_score[labels_all[i], _mask] = masks_all[i][_mask]\n                    results[1, _mask] = id_unique\n                    id_unique += 1\n\n            # file_name = img_metas[img_id]['pts_filename'].split('/')[-1].split('.')[0]\n            # panoptic_list.append(\n            #     (results.permute(1, 2, 0).cpu().numpy(), file_name, ori_shape))\n            panoptic_list.append((results.permute(1, 2, 0).cpu().numpy(),ori_shape))            \n            \n\n            bbox_list.append(bbox_th)\n            labels_list.append(labels_th)\n            seg_list.append(seg_th)\n            lane_list.append(lane)\n            lane_score_list.append(lane_score)\n        results = []\n        for i in range(len(img_metas)):\n            results.append({\n                'bbox': bbox_list[i],\n                'segm': seg_list[i],\n                'labels': labels_list[i],\n                'panoptic': panoptic_list[i],\n                'drivable': drivable_list[i],\n                'score_list': score_list[i],\n                'lane': lane_list[i],\n                'lane_score': lane_score_list[i],\n                'stuff_score_list' : stuff_score_list[i],\n            })\n        return results\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/planning_head.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.builder import HEADS, build_loss\nfrom einops import rearrange\nfrom mmcv.models.utils.functional import bivariate_gaussian_activation\nfrom .planning_head_plugin import CollisionNonlinearOptimizer\nimport numpy as np\nimport copy\n\n@HEADS.register_module()\nclass PlanningHeadSingleMode(nn.Module):\n    def __init__(self,\n                 bev_h=200,\n                 bev_w=200,\n                 embed_dims=256,\n                 planning_steps=6,\n                 command_dim=3,\n                 loss_planning=None,\n                 loss_collision=None,\n                 planning_eval=False,\n                 use_col_optim=False,\n                 col_optim_args=dict(\n                    occ_filter_range=5.0,\n                    sigma=1.0, \n                    alpha_collision=5.0,\n                 ),\n                 with_adapter=False,\n                ):\n        \"\"\"\n        Single Mode Planning Head for Autonomous Driving.\n\n        Args:\n            embed_dims (int): Embedding dimensions. Default: 256.\n            planning_steps (int): Number of steps for motion planning. Default: 6.\n            loss_planning (dict): Configuration for planning loss. Default: None.\n            loss_collision (dict): Configuration for collision loss. Default: None.\n            planning_eval (bool): Whether to use planning for evaluation. Default: False.\n            use_col_optim (bool): Whether to use collision optimization. Default: False.\n            col_optim_args (dict): Collision optimization arguments. Default: dict(occ_filter_range=5.0, sigma=1.0, alpha_collision=5.0).\n        \"\"\"\n        super(PlanningHeadSingleMode, self).__init__()\n\n        # Nuscenes\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.navi_embed = nn.Embedding(command_dim, embed_dims)\n        self.reg_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, planning_steps * 2),\n        )\n        self.loss_planning = build_loss(loss_planning)\n        self.planning_steps = planning_steps\n        self.planning_eval = planning_eval\n        \n        #### planning head\n        fuser_dim = 3\n        attn_module_layer = nn.TransformerDecoderLayer(embed_dims, 8, dim_feedforward=embed_dims*2, dropout=0.1, batch_first=False)\n        self.attn_module = nn.TransformerDecoder(attn_module_layer, 3)\n        \n        self.mlp_fuser = nn.Sequential(\n                nn.Linear(embed_dims*fuser_dim, embed_dims),\n                nn.LayerNorm(embed_dims),\n                nn.ReLU(inplace=True),\n            )\n        \n        self.pos_embed = nn.Embedding(1, embed_dims)\n        self.loss_collision = []\n        for cfg in loss_collision:\n            self.loss_collision.append(build_loss(cfg))\n        self.loss_collision = nn.ModuleList(self.loss_collision)\n        \n        self.use_col_optim = use_col_optim\n        self.occ_filter_range = col_optim_args['occ_filter_range']\n        self.sigma = col_optim_args['sigma']\n        self.alpha_collision = col_optim_args['alpha_collision']\n\n        # TODO: reimplement it with down-scaled feature_map\n        self.with_adapter = with_adapter\n        if with_adapter:\n            bev_adapter_block = nn.Sequential(\n                nn.Conv2d(embed_dims, embed_dims // 2, kernel_size=3, padding=1),\n                nn.ReLU(),\n                nn.Conv2d(embed_dims // 2, embed_dims, kernel_size=1),\n            )\n            N_Blocks = 3\n            bev_adapter = [copy.deepcopy(bev_adapter_block) for _ in range(N_Blocks)]\n            self.bev_adapter = nn.Sequential(*bev_adapter)\n           \n    def forward_train(self,\n                      bev_embed, \n                      outs_motion={}, \n                      sdc_planning=None, \n                      sdc_planning_mask=None,\n                      command=None,\n                      gt_future_boxes=None,\n                      ):\n        \"\"\"\n        Perform forward planning training with the given inputs.\n        Args:\n            bev_embed (torch.Tensor): The input bird's eye view feature map.\n            outs_motion (dict): A dictionary containing the motion outputs.\n            outs_occflow (dict): A dictionary containing the occupancy flow outputs.\n            sdc_planning (torch.Tensor, optional): The self-driving car's planned trajectory.\n            sdc_planning_mask (torch.Tensor, optional): The mask for the self-driving car's planning.\n            command (torch.Tensor, optional): The driving command issued to the self-driving car.\n            gt_future_boxes (torch.Tensor, optional): The ground truth future bounding boxes.\n            img_metas (list[dict], optional): A list of metadata information about the input images.\n\n        Returns:\n            ret_dict (dict): A dictionary containing the losses and planning outputs.\n        \"\"\"\n        sdc_traj_query = outs_motion['sdc_traj_query']\n        sdc_track_query = outs_motion['sdc_track_query']\n        bev_pos = outs_motion['bev_pos']\n\n        occ_mask = None\n        \n        outs_planning = self(bev_embed, occ_mask, bev_pos, sdc_traj_query, sdc_track_query, command)\n        loss_inputs = [sdc_planning, sdc_planning_mask, outs_planning, gt_future_boxes]\n        losses = self.loss(*loss_inputs)\n        ret_dict = dict(losses=losses, outs_motion=outs_planning)\n        return ret_dict\n\n    def forward_test(self, bev_embed, outs_motion={}, outs_occflow={}, command=None):\n        sdc_traj_query = outs_motion['sdc_traj_query']\n        sdc_track_query = outs_motion['sdc_track_query']\n        bev_pos = outs_motion['bev_pos']\n        occ_mask = outs_occflow['seg_out']\n        \n        outs_planning = self(bev_embed, occ_mask, bev_pos, sdc_traj_query, sdc_track_query, command)\n        return outs_planning\n\n    def forward(self, \n                bev_embed, \n                occ_mask, \n                bev_pos, \n                sdc_traj_query, \n                sdc_track_query, \n                command):\n        \"\"\"\n        Forward pass for PlanningHeadSingleMode.\n\n        Args:\n            bev_embed (torch.Tensor): Bird's eye view feature embedding.\n            occ_mask (torch.Tensor): Instance mask for occupancy.\n            bev_pos (torch.Tensor): BEV position.\n            sdc_traj_query (torch.Tensor): SDC trajectory query.\n            sdc_track_query (torch.Tensor): SDC track query.\n            command (int): Driving command.\n\n        Returns:\n            dict: A dictionary containing SDC trajectory and all SDC trajectories.\n        \"\"\"\n        sdc_track_query = sdc_track_query.detach()\n        sdc_traj_query = sdc_traj_query[-1]\n        P = sdc_traj_query.shape[1]\n        sdc_track_query = sdc_track_query[:, None].expand(-1,P,-1)\n        \n        #import pdb;pdb.set_trace()\n        navi_embed = self.navi_embed.weight[command]\n        navi_embed = navi_embed[None].expand(-1,P,-1)\n        plan_query = torch.cat([sdc_traj_query, sdc_track_query, navi_embed], dim=-1)\n\n        plan_query = self.mlp_fuser(plan_query).max(1, keepdim=True)[0]   # expand, then fuse  # [1, 6, 768] -> [1, 1, 256]\n        plan_query = rearrange(plan_query, 'b p c -> p b c')\n        \n        bev_pos = rearrange(bev_pos, 'b c h w -> (h w) b c')\n        bev_feat = bev_embed +  bev_pos\n        \n        ##### Plugin adapter #####\n        if self.with_adapter:\n            bev_feat = rearrange(bev_feat, '(h w) b c -> b c h w', h=self.bev_h, w=self.bev_w)\n            \n            bev_feat = bev_feat + self.bev_adapter(bev_feat)  # residual connection\n            bev_feat = rearrange(bev_feat, 'b c h w -> (h w) b c')\n        ##########################\n      \n        pos_embed = self.pos_embed.weight\n        plan_query = plan_query + pos_embed[None]  # [1, 1, 256]\n        \n        # plan_query: [1, 1, 256]\n        # bev_feat: [40000, 1, 256]\n        plan_query = self.attn_module(plan_query, bev_feat)   # [1, 1, 256]\n        \n        sdc_traj_all = self.reg_branch(plan_query).view((-1, self.planning_steps, 2))\n        sdc_traj_all[...,:2] = torch.cumsum(sdc_traj_all[...,:2], dim=1)\n        sdc_traj_all[0] = bivariate_gaussian_activation(sdc_traj_all[0])\n        if self.use_col_optim and not self.training:\n            # post process, only used when testing\n            assert occ_mask is not None\n            sdc_traj_all = self.collision_optimization(sdc_traj_all, occ_mask)\n        \n        return dict(\n            sdc_traj=sdc_traj_all,\n            sdc_traj_all=sdc_traj_all,\n        )\n\n    def collision_optimization(self, sdc_traj_all, occ_mask):\n        \"\"\"\n        Optimize SDC trajectory with occupancy instance mask.\n\n        Args:\n            sdc_traj_all (torch.Tensor): SDC trajectory tensor.\n            occ_mask (torch.Tensor): Occupancy flow instance mask. \n        Returns:\n            torch.Tensor: Optimized SDC trajectory tensor.\n        \"\"\"\n        pos_xy_t = []\n        valid_occupancy_num = 0\n        \n        if occ_mask.shape[2] == 1:\n            occ_mask = occ_mask.squeeze(2)\n        occ_horizon = occ_mask.shape[1]\n        assert occ_horizon == 5\n\n        for t in range(self.planning_steps):\n            cur_t = min(t+1, occ_horizon-1)\n            pos_xy = torch.nonzero(occ_mask[0][cur_t], as_tuple=False)\n            pos_xy = pos_xy[:, [1, 0]]\n            pos_xy[:, 0] = (pos_xy[:, 0] - self.bev_h//2) * 0.5 + 0.25\n            pos_xy[:, 1] = (pos_xy[:, 1] - self.bev_w//2) * 0.5 + 0.25\n\n            # filter the occupancy in range\n            keep_index = torch.sum((sdc_traj_all[0, t, :2][None, :] - pos_xy[:, :2])**2, axis=-1) < self.occ_filter_range**2\n            pos_xy_t.append(pos_xy[keep_index].cpu().detach().numpy())\n            valid_occupancy_num += torch.sum(keep_index>0)\n        if valid_occupancy_num == 0:\n            return sdc_traj_all\n        \n        col_optimizer = CollisionNonlinearOptimizer(self.planning_steps, 0.5, self.sigma, self.alpha_collision, pos_xy_t)\n        col_optimizer.set_reference_trajectory(sdc_traj_all[0].cpu().detach().numpy())\n        sol = col_optimizer.solve()\n        sdc_traj_optim = np.stack([sol.value(col_optimizer.position_x), sol.value(col_optimizer.position_y)], axis=-1)\n        return torch.tensor(sdc_traj_optim[None], device=sdc_traj_all.device, dtype=sdc_traj_all.dtype)\n    \n    def loss(self, sdc_planning, sdc_planning_mask, outs_planning, future_gt_bbox=None):\n        sdc_traj_all = outs_planning['sdc_traj_all'] # b, p, t, 5\n        loss_dict = dict()\n        for i in range(len(self.loss_collision)):\n            loss_collision = self.loss_collision[i](sdc_traj_all, sdc_planning[0, :, :self.planning_steps, :3], torch.any(sdc_planning_mask[0, :, :self.planning_steps], dim=-1), future_gt_bbox[0][1:self.planning_steps+1])\n            loss_dict[f'loss_collision_{i}'] = loss_collision          \n        loss_ade = self.loss_planning(sdc_traj_all, sdc_planning[0, :, :self.planning_steps, :2], torch.any(sdc_planning_mask[0, :, :self.planning_steps], dim=-1))\n        loss_dict.update(dict(loss_ade=loss_ade))\n        return loss_dict"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/planning_head_plugin/__init__.py",
    "content": "# from .collision_optimization import *\nfrom .planning_metrics import *\nfrom .collision_optimization import *\nfrom .metric_stp3 import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/planning_head_plugin/collision_optimization.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nfrom typing import Any, Dict, List, Optional, Sequence, Tuple, Union\n\nimport numpy as np\nimport numpy.typing as npt\nfrom casadi import DM, Opti, OptiSol, cos, diff, sin, sumsqr, vertcat, exp\n\nPose = Tuple[float, float, float]  # (x, y, yaw)\n\n\nclass CollisionNonlinearOptimizer:\n    \"\"\"\n    Optimize planned trajectory with predicted occupancy\n    Solved with direct multiple-shooting.\n    modified from https://github.com/motional/nuplan-devkit\n    :param trajectory_len: trajectory length\n    :param dt: timestep (sec)\n    \"\"\"\n\n    def __init__(self, trajectory_len: int, dt: float, sigma, alpha_collision, obj_pixel_pos):\n        \"\"\"\n        :param trajectory_len: the length of trajectory to be optimized.\n        :param dt: the time interval between trajectory points.\n        \"\"\"\n        self.dt = dt\n        self.trajectory_len = trajectory_len\n        self.current_index = 0\n        self.sigma = sigma\n        self.alpha_collision = alpha_collision\n        self.obj_pixel_pos = obj_pixel_pos\n        # Use a array of dts to make it compatible to situations with varying dts across different time steps.\n        self._dts: npt.NDArray[np.float32] = np.asarray([[dt] * trajectory_len])\n        self._init_optimization()\n\n    def _init_optimization(self) -> None:\n        \"\"\"\n        Initialize related variables and constraints for optimization.\n        \"\"\"\n        self.nx = 2  # state dim\n\n        self._optimizer = Opti()  # Optimization problem\n        self._create_decision_variables()\n        self._create_parameters()\n        self._set_objective()\n\n        # Set default solver options (quiet)\n        self._optimizer.solver(\"ipopt\", {\"ipopt.print_level\": 0, \"print_time\": 0, \"ipopt.sb\": \"yes\"})\n\n    def set_reference_trajectory(self, reference_trajectory: Sequence[Pose]) -> None:\n        \"\"\"\n        Set the reference trajectory that the smoother is trying to loosely track.\n        :param x_curr: current state of size nx (x, y)\n        :param reference_trajectory: N x 3 reference, where the second dim is for (x, y)\n        \"\"\"\n        self._optimizer.set_value(self.ref_traj, DM(reference_trajectory).T)\n        self._set_initial_guess(reference_trajectory)\n\n    def set_solver_optimizerons(self, options: Dict[str, Any]) -> None:\n        \"\"\"\n        Control solver options including verbosity.\n        :param options: Dictionary containing optimization criterias\n        \"\"\"\n        self._optimizer.solver(\"ipopt\", options)\n\n    def solve(self) -> OptiSol:\n        \"\"\"\n        Solve the optimization problem. Assumes the reference trajectory was already set.\n        :return Casadi optimization class\n        \"\"\"\n        return self._optimizer.solve()\n\n    def _create_decision_variables(self) -> None:\n        \"\"\"\n        Define the decision variables for the trajectory optimization.\n        \"\"\"\n        # State trajectory (x, y)\n        self.state = self._optimizer.variable(self.nx, self.trajectory_len)\n        self.position_x = self.state[0, :]\n        self.position_y = self.state[1, :]\n\n    def _create_parameters(self) -> None:\n        \"\"\"\n        Define the expert trjactory and current position for the trajectory optimizaiton.\n        \"\"\"\n        self.ref_traj = self._optimizer.parameter(2, self.trajectory_len)  # (x, y)\n\n    def _set_objective(self) -> None:\n        \"\"\"Set the objective function. Use care when modifying these weights.\"\"\"\n        # Follow reference, minimize control rates and absolute inputs\n        alpha_xy = 1.0\n        cost_stage = (\n            alpha_xy * sumsqr(self.ref_traj[:2, :] - vertcat(self.position_x, self.position_y))\n        )\n\n        alpha_collision = self.alpha_collision\n        \n        cost_collision = 0\n        normalizer = 1/(2.507*self.sigma)\n        # TODO: vectorize this\n        for t in range(len(self.obj_pixel_pos)):\n            x, y = self.position_x[t], self.position_y[t]\n            for i in range(len(self.obj_pixel_pos[t])):\n                col_x, col_y = self.obj_pixel_pos[t][i]\n                cost_collision += alpha_collision * normalizer * exp(-((x - col_x)**2 + (y - col_y)**2)/2/self.sigma**2)\n        self._optimizer.minimize(cost_stage + cost_collision)\n\n    def _set_initial_guess(self, reference_trajectory: Sequence[Pose]) -> None:\n        \"\"\"Set a warm-start for the solver based on the reference trajectory.\"\"\"\n        # Initialize state guess based on reference\n        self._optimizer.set_initial(self.state[:2, :], DM(reference_trajectory).T)  # (x, y, yaw)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/planning_head_plugin/metric_stp3.py",
    "content": "'''\ncalculate planner metric same as stp3\n'''\nimport numpy as np\nimport torch\nimport cv2\nimport copy\nimport matplotlib.pyplot as plt\nfrom skimage.draw import polygon\nfrom nuscenes.utils.data_classes import Box\nfrom scipy.spatial.transform import Rotation as R\n\nego_width, ego_length = 1.85, 4.084\n\nclass PlanningMetric():\n    def __init__(self):\n        super().__init__()\n        self.X_BOUND = [-50.0, 50.0, 0.5]  # Forward\n        self.Y_BOUND = [-50.0, 50.0, 0.5]  # Sides\n        self.Z_BOUND = [-10.0, 10.0, 20.0]  # Height\n        dx, bx, _ = self.gen_dx_bx(self.X_BOUND, self.Y_BOUND, self.Z_BOUND)\n        self.dx, self.bx = dx[:2], bx[:2]\n\n        bev_resolution, bev_start_position, bev_dimension = self.calculate_birds_eye_view_parameters(\n            self.X_BOUND, self.Y_BOUND, self.Z_BOUND\n        )\n        self.bev_resolution = bev_resolution.numpy()\n        self.bev_start_position = bev_start_position.numpy()\n        self.bev_dimension = bev_dimension.numpy()\n\n        self.W = ego_width\n        self.H = ego_length\n\n        self.category_index = {\n            'human':[2,3,4,5,6,7,8],\n            'vehicle':[14,15,16,17,18,19,20,21,22,23]\n        }\n\n        # self.n_future = n_future\n\n        # self.add_state(\"obj_col\", default=torch.zeros(self.n_future), dist_reduce_fx=\"sum\")\n        # self.add_state(\"obj_box_col\", default=torch.zeros(self.n_future), dist_reduce_fx=\"sum\")\n        # self.add_state(\"L2\", default=torch.zeros(self.n_future),dist_reduce_fx=\"sum\")\n        # self.add_state(\"total\", default=torch.tensor(0), dist_reduce_fx=\"sum\")\n\n    def gen_dx_bx(self, xbound, ybound, zbound):\n        dx = torch.Tensor([row[2] for row in [xbound, ybound, zbound]])\n        bx = torch.Tensor([row[0] + row[2]/2.0 for row in [xbound, ybound, zbound]])\n        nx = torch.LongTensor([(row[1] - row[0]) / row[2] for row in [xbound, ybound, zbound]])\n\n        return dx, bx, nx\n    \n    def calculate_birds_eye_view_parameters(self, x_bounds, y_bounds, z_bounds):\n        \"\"\"\n        Parameters\n        ----------\n            x_bounds: Forward direction in the ego-car.\n            y_bounds: Sides\n            z_bounds: Height\n\n        Returns\n        -------\n            bev_resolution: Bird's-eye view bev_resolution\n            bev_start_position Bird's-eye view first element\n            bev_dimension Bird's-eye view tensor spatial dimension\n        \"\"\"\n        bev_resolution = torch.tensor([row[2] for row in [x_bounds, y_bounds, z_bounds]])\n        bev_start_position = torch.tensor([row[0] + row[2] / 2.0 for row in [x_bounds, y_bounds, z_bounds]])\n        bev_dimension = torch.tensor([(row[1] - row[0]) / row[2] for row in [x_bounds, y_bounds, z_bounds]],\n                                    dtype=torch.long)\n\n        return bev_resolution, bev_start_position, bev_dimension\n    \n    def get_label(\n            self,\n            gt_agent_boxes,\n            gt_agent_feats\n        ):\n        segmentation_np, pedestrian_np = self.get_birds_eye_view_label(gt_agent_boxes,gt_agent_feats)\n        segmentation = torch.from_numpy(segmentation_np).long().unsqueeze(0)\n        pedestrian = torch.from_numpy(pedestrian_np).long().unsqueeze(0)\n\n        return segmentation, pedestrian\n    \n    def get_birds_eye_view_label(\n            self,\n            gt_agent_boxes,\n            gt_agent_feats\n        ):\n        '''\n        gt_agent_boxes (LiDARInstance3DBoxes): list of GT Bboxs.\n            dim 9 = (x,y,z)+(w,l,h)+yaw+(vx,vy)\n        gt_agent_feats: (B, A, 34)\n            dim 34 = fut_traj(6*2) + fut_mask(6) + goal(1) + lcf_feat(9) + fut_yaw(6)\n            lcf_feat (x, y, yaw, vx, vy, width, length, height, type)\n        ego_lcf_feats: (B, 9) \n            dim 8 = (vx, vy, ax, ay, w, length, width, vel, steer)\n        '''\n        T = 6\n        segmentation = np.zeros((T,self.bev_dimension[0], self.bev_dimension[1]))\n        pedestrian = np.zeros((T,self.bev_dimension[0], self.bev_dimension[1]))\n        agent_num = gt_agent_feats.shape[1]\n\n        gt_agent_boxes = gt_agent_boxes.tensor.cpu().numpy()  #(N, 9)\n        gt_agent_feats = gt_agent_feats.cpu().numpy()\n\n        gt_agent_fut_trajs = gt_agent_feats[..., :T*2].reshape(-1, 6, 2)\n        gt_agent_fut_mask = gt_agent_feats[..., T*2:T*3].reshape(-1, 6)\n        # gt_agent_lcf_feat = gt_agent_feats[..., T*3+1:T*3+10].reshape(-1, 9)\n        gt_agent_fut_yaw = gt_agent_feats[..., T*3+10:T*4+10].reshape(-1, 6, 1)\n        gt_agent_fut_trajs = np.cumsum(gt_agent_fut_trajs, axis=1)\n        gt_agent_fut_yaw = np.cumsum(gt_agent_fut_yaw, axis=1)\n\n        gt_agent_boxes[:,6:7] = -1*(gt_agent_boxes[:,6:7] + np.pi/2) # NOTE: convert yaw to lidar frame\n        gt_agent_fut_trajs = gt_agent_fut_trajs + gt_agent_boxes[:, np.newaxis, 0:2]\n        gt_agent_fut_yaw = gt_agent_fut_yaw + gt_agent_boxes[:, np.newaxis, 6:7]\n        \n        for t in range(T):\n            for i in range(agent_num):\n                if gt_agent_fut_mask[i][t] == 1:\n                    # Filter out all non vehicle instances\n                    category_index = int(gt_agent_feats[0,i][27])\n                    agent_length, agent_width = gt_agent_boxes[i][4], gt_agent_boxes[i][3]\n                    x_a = gt_agent_fut_trajs[i, t, 0]\n                    y_a = gt_agent_fut_trajs[i, t, 1]\n                    yaw_a = gt_agent_fut_yaw[i, t, 0]\n                    param = [x_a,y_a,yaw_a,agent_length, agent_width]\n                    if (category_index in self.category_index['vehicle']):\n                        poly_region = self._get_poly_region_in_image(param)\n                        cv2.fillPoly(segmentation[t], [poly_region], 1.0)\n                    if (category_index in self.category_index['human']):\n                        poly_region = self._get_poly_region_in_image(param)\n                        cv2.fillPoly(pedestrian[t], [poly_region], 1.0)\n        \n        # vis for debug\n        # plt.figure('debug')\n        # for i in range(T):\n        #     plt.subplot(2,T,i+1)\n        #     plt.imshow(segmentation[i])\n        #     plt.subplot(2,T,i+1+T)\n        #     plt.imshow(pedestrian[i])\n        # plt.savefig('/home/users/qing01.xu/bevformer/debug_figs/car_ped_occ.jpg')\n        # plt.close()\n\n        return segmentation, pedestrian\n    \n    def _get_poly_region_in_image(self,param):\n        lidar2cv_rot = np.array([[1,0], [0,-1]])\n        x_a,y_a,yaw_a,agent_length, agent_width = param\n        trans_a = np.array([[x_a,y_a]]).T\n        rot_mat_a = np.array([[np.cos(yaw_a), -np.sin(yaw_a)],\n                                [np.sin(yaw_a), np.cos(yaw_a)]])\n        agent_corner = np.array([\n            [agent_length/2, -agent_length/2, -agent_length/2, agent_length/2],\n            [agent_width/2, agent_width/2, -agent_width/2, -agent_width/2]]) #(2,4)\n        agent_corner_lidar = np.matmul(rot_mat_a, agent_corner) + trans_a #(2,4)\n        # convert to cv frame\n        agent_corner_cv2 = (np.matmul(lidar2cv_rot, agent_corner_lidar) \\\n            - self.bev_start_position[:2,None] + self.bev_resolution[:2,None] / 2.0).T / self.bev_resolution[:2] #(4,2)\n        agent_corner_cv2 = np.round(agent_corner_cv2).astype(np.int32)\n\n        return agent_corner_cv2\n\n\n    def evaluate_single_coll(self, traj, segmentation, input_gt):\n        '''\n        traj: torch.Tensor (n_future, 2)\n            自车lidar系为轨迹参考系\n                ^ y\n                |\n                | \n                0------->\n                        x\n        segmentation: torch.Tensor (n_future, 200, 200)\n        '''\n        pts = np.array([\n            [-self.H / 2. + 0.5, self.W / 2.],\n            [self.H / 2. + 0.5, self.W / 2.],\n            [self.H / 2. + 0.5, -self.W / 2.],\n            [-self.H / 2. + 0.5, -self.W / 2.],\n        ])\n        pts = (pts - self.bx.cpu().numpy()) / (self.dx.cpu().numpy())\n        pts[:, [0, 1]] = pts[:, [1, 0]]\n        rr, cc = polygon(pts[:,1], pts[:,0])\n        rc = np.concatenate([rr[:,None], cc[:,None]], axis=-1)\n\n        n_future, _ = traj.shape\n        trajs = traj.view(n_future, 1, 2)\n        # 轨迹坐标系转换为:\n        #  ^ x\n        #  |\n        #  | \n        #  0-------> y\n        trajs_ = copy.deepcopy(trajs)\n        trajs_[:,:,[0,1]] = trajs_[:,:,[1,0]] # can also change original tensor\n        trajs_ = trajs_ / self.dx.to(trajs.device)\n        trajs_ = trajs_.cpu().numpy() + rc # (n_future, 32, 2)\n\n        r = (self.bev_dimension[0] - trajs_[:,:,0]).astype(np.int32)\n        r = np.clip(r, 0, self.bev_dimension[0] - 1)\n\n        c = trajs_[:,:,1].astype(np.int32)\n        c = np.clip(c, 0, self.bev_dimension[1] - 1)\n\n        collision = np.full(n_future, False)\n        for t in range(n_future):\n            rr = r[t]\n            cc = c[t]\n            I = np.logical_and(\n                np.logical_and(rr >= 0, rr < self.bev_dimension[0]),\n                np.logical_and(cc >= 0, cc < self.bev_dimension[1]),\n            )\n            collision[t] = np.any(segmentation[t, rr[I], cc[I]].cpu().numpy())\n        \n        # vis for debug\n        # obs_occ = copy.deepcopy(segmentation)\n        # ego_occ = torch.zeros_like(obs_occ)\n        # for t in range(n_future):\n        #     rr = r[t]\n        #     cc = c[t]\n        #     I = np.logical_and(\n        #         np.logical_and(rr >= 0, rr < self.bev_dimension[0]),\n        #         np.logical_and(cc >= 0, cc < self.bev_dimension[1]),\n        #     )\n        #     ego_occ[t, rr[I], cc[I]]=1\n        \n        # plt.figure()\n        # for i in range(6):\n        #     plt.subplot(2,6,i+1)\n        #     plt.imshow(obs_occ[i])\n        #     plt.subplot(2,6,i+7)\n        #     plt.imshow(ego_occ[i])\n        # if input_gt:\n        #     plt.savefig('/home/users/qing01.xu/bevformer/debug_figs/occ_metric_stp3_gt.jpg')\n        # else:\n        #     plt.savefig('/home/users/qing01.xu/bevformer/debug_figs/occ_metric_stp3_pred.jpg')\n        # plt.close()\n\n        return torch.from_numpy(collision).to(device=traj.device)\n\n    def evaluate_coll(\n            self, \n            trajs, \n            gt_trajs, \n            segmentation\n        ):\n        '''\n        trajs: torch.Tensor (B, n_future, 2)\n            自车lidar系为轨迹参考系\n            ^ y\n            |\n            | \n            0------->\n                    x\n        gt_trajs: torch.Tensor (B, n_future, 2)\n        segmentation: torch.Tensor (B, n_future, 200, 200)\n\n        '''\n        gt_trajs = gt_trajs.to(device=trajs.device)\n        B, n_future, _ = trajs.shape\n        # trajs = trajs * torch.tensor([-1, 1], device=trajs.device)\n        # gt_trajs = gt_trajs * torch.tensor([-1, 1], device=gt_trajs.device)\n\n        obj_coll_sum = torch.zeros(n_future, device=segmentation.device)\n        obj_box_coll_sum = torch.zeros(n_future, device=segmentation.device)\n\n        for i in range(B):\n            gt_box_coll = self.evaluate_single_coll(gt_trajs[i], segmentation[i], input_gt=True)\n\n            xx, yy = trajs[i,:,0], trajs[i, :, 1]\n            # lidar系下的轨迹转换到图片坐标系下\n            xi = ((-self.bx[0]/2 - yy) / self.dx[0]).long()\n            yi = ((-self.bx[1]/2 + xx) / self.dx[1]).long()\n\n            m1 = torch.logical_and(\n                torch.logical_and(xi >= 0, xi < self.bev_dimension[0]),\n                torch.logical_and(yi >= 0, yi < self.bev_dimension[1]),\n            ).to(gt_box_coll.device)\n            m1 = torch.logical_and(m1, torch.logical_not(gt_box_coll))\n            #import pdb;pdb.set_trace()\n\n            ti = torch.arange(n_future)\n            obj_coll_sum[ti[m1]] += segmentation[i, ti[m1], xi[m1], yi[m1]].long()\n\n            m2 = torch.logical_not(gt_box_coll)\n            box_coll = self.evaluate_single_coll(trajs[i], segmentation[i], input_gt=False).to(ti.device)\n            obj_box_coll_sum[ti[m2]] += (box_coll[ti[m2]]).long()\n\n        return obj_coll_sum, obj_box_coll_sum\n\n    def compute_L2(self, trajs, gt_trajs):\n        '''\n        trajs: torch.Tensor (n_future, 2)\n        gt_trajs: torch.Tensor (n_future, 2)\n        '''\n        # return torch.sqrt(((trajs[:, :, :2] - gt_trajs[:, :, :2]) ** 2).sum(dim=-1))\n        pred_len = trajs.shape[0]\n        ade = float(\n            sum(\n                torch.sqrt(\n                    (trajs[i, 0] - gt_trajs[i, 0]) ** 2\n                    + (trajs[i, 1] - gt_trajs[i, 1]) ** 2\n                )\n                for i in range(pred_len)\n            )\n            / pred_len\n        )\n        \n        return ade\n\n    # def update(self, trajs, gt_trajs, segmentation):\n    #     '''\n    #     trajs: torch.Tensor (B, n_future, 3)\n    #     gt_trajs: torch.Tensor (B, n_future, 3)\n    #     segmentation: torch.Tensor (B, n_future, 200, 200)\n    #     '''\n    #     assert trajs.shape == gt_trajs.shape\n    #     L2 = self.compute_L2(trajs, gt_trajs)\n    #     obj_coll_sum, obj_box_coll_sum = self.evaluate_coll(trajs[:,:,:2], gt_trajs[:,:,:2], segmentation)\n\n    #     if torch.isnan(L2).max().item():\n    #         debug = 1\n    #     else:\n    #         self.obj_col += obj_coll_sum\n    #         self.obj_box_col += obj_box_coll_sum\n    #         self.L2 += L2.sum(dim=0)\n    #         if torch.isnan(self.L2).max().item():\n    #             debug=1\n    #         self.total +=len(trajs)\n\n\n    # def compute(self):\n    #     return {\n    #         'obj_col': self.obj_col / self.total,\n    #         'obj_box_col': self.obj_box_col / self.total,\n    #         'L2' : self.L2 / self.total\n    #     }"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/planning_head_plugin/planning_metrics.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nimport numpy as np\nfrom skimage.draw import polygon\nfrom mmcv.metrics.metric import Metric\nfrom ..occ_head_plugin import calculate_birds_eye_view_parameters, gen_dx_bx\n\n\nclass UniADPlanningMetric(Metric):\n    def __init__(\n        self,\n        n_future=6,\n    ):\n        super().__init__()\n        dx, bx, _ = gen_dx_bx([-50.0, 50.0, 0.5], [-50.0, 50.0, 0.5], [-10.0, 10.0, 20.0])\n        dx, bx = dx[:2], bx[:2]\n        self.dx = nn.Parameter(dx, requires_grad=False)\n        self.bx = nn.Parameter(bx, requires_grad=False)\n\n        _, _, self.bev_dimension = calculate_birds_eye_view_parameters(\n            [-50.0, 50.0, 0.5], [-50.0, 50.0, 0.5], [-10.0, 10.0, 20.0]\n        )\n        self.bev_dimension = self.bev_dimension.numpy()\n\n        self.W = 1.85\n        self.H = 4.084\n\n        self.n_future = n_future\n\n        self.add_state(\"obj_col\", default=torch.zeros(self.n_future), dist_reduce_fx=\"sum\")\n        self.add_state(\"obj_box_col\", default=torch.zeros(self.n_future), dist_reduce_fx=\"sum\")\n        self.add_state(\"L2\", default=torch.zeros(self.n_future),dist_reduce_fx=\"sum\")\n        self.add_state(\"total\", default=torch.tensor(0), dist_reduce_fx=\"sum\")\n\n\n    def evaluate_single_coll(self, traj, segmentation):\n        '''\n        gt_segmentation\n        traj: torch.Tensor (n_future, 2)\n        segmentation: torch.Tensor (n_future, 200, 200)\n        '''\n        pts = np.array([\n            [-self.H / 2. + 0.5, self.W / 2.],\n            [self.H / 2. + 0.5, self.W / 2.],\n            [self.H / 2. + 0.5, -self.W / 2.],\n            [-self.H / 2. + 0.5, -self.W / 2.],\n        ])\n        pts = (pts - self.bx.cpu().numpy()) / (self.dx.cpu().numpy())\n        pts[:, [0, 1]] = pts[:, [1, 0]]\n        rr, cc = polygon(pts[:,1], pts[:,0])\n        rc = np.concatenate([rr[:,None], cc[:,None]], axis=-1)\n\n        n_future, _ = traj.shape\n        trajs = traj.view(n_future, 1, 2)\n        trajs[:,:,[0,1]] = trajs[:,:,[1,0]] # can also change original tensor\n        trajs = trajs / self.dx\n        trajs = trajs.cpu().numpy() + rc # (n_future, 32, 2)\n\n        r = trajs[:,:,0].astype(np.int32)\n        r = np.clip(r, 0, self.bev_dimension[0] - 1)\n\n        c = trajs[:,:,1].astype(np.int32)\n        c = np.clip(c, 0, self.bev_dimension[1] - 1)\n\n        collision = np.full(n_future, False)\n        for t in range(n_future):\n            rr = r[t]\n            cc = c[t]\n            I = np.logical_and(\n                np.logical_and(rr >= 0, rr < self.bev_dimension[0]),\n                np.logical_and(cc >= 0, cc < self.bev_dimension[1]),\n            )\n            collision[t] = np.any(segmentation[t, rr[I], cc[I]].cpu().numpy())\n\n        return torch.from_numpy(collision).to(device=traj.device)\n\n    def evaluate_coll(self, trajs, gt_trajs, segmentation):\n        '''\n        trajs: torch.Tensor (B, n_future, 2)\n        gt_trajs: torch.Tensor (B, n_future, 2)\n        segmentation: torch.Tensor (B, n_future, 200, 200)\n        '''\n        B, n_future, _ = trajs.shape\n        trajs = trajs * torch.tensor([-1, 1], device=trajs.device)\n        gt_trajs = gt_trajs * torch.tensor([-1, 1], device=gt_trajs.device)\n\n        obj_coll_sum = torch.zeros(n_future, device=segmentation.device)\n        obj_box_coll_sum = torch.zeros(n_future, device=segmentation.device)\n\n        for i in range(B):\n            gt_box_coll = self.evaluate_single_coll(gt_trajs[i], segmentation[i])\n\n            xx, yy = trajs[i,:,0], trajs[i, :, 1]\n            yi = ((yy - self.bx[0]) / self.dx[0]).long()\n            xi = ((xx - self.bx[1]) / self.dx[1]).long()\n\n            m1 = torch.logical_and(\n                torch.logical_and(yi >= 0, yi < self.bev_dimension[0]),\n                torch.logical_and(xi >= 0, xi < self.bev_dimension[1]),\n            )\n            m1 = torch.logical_and(m1, torch.logical_not(gt_box_coll))\n\n            ti = torch.arange(n_future, device=m1.device)\n            obj_coll_sum[ti[m1]] += segmentation[i, ti[m1], yi[m1], xi[m1]].long()\n\n            m2 = torch.logical_not(gt_box_coll)\n            box_coll = self.evaluate_single_coll(trajs[i], segmentation[i])\n            obj_box_coll_sum[ti[m2]] += (box_coll[ti[m2]]).long()\n\n        return obj_coll_sum, obj_box_coll_sum\n\n    def compute_L2(self, trajs, gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n        return torch.sqrt((((trajs[:, :, :2] - gt_trajs[:, :, :2]) ** 2) * gt_trajs_mask).sum(dim=-1)) \n\n    def update(self, trajs, gt_trajs, gt_trajs_mask, segmentation):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        segmentation: torch.Tensor (B, n_future, 200, 200)\n        '''\n        assert trajs.shape == gt_trajs.shape\n        trajs[..., 0] = - trajs[..., 0]\n        gt_trajs[..., 0] = - gt_trajs[..., 0]\n        L2 = self.compute_L2(trajs, gt_trajs, gt_trajs_mask)\n        obj_coll_sum, obj_box_coll_sum = self.evaluate_coll(trajs[:,:,:2], gt_trajs[:,:,:2], segmentation)\n\n        self.obj_col += obj_coll_sum\n        self.obj_box_col += obj_box_coll_sum\n        self.L2 += L2.sum(dim=0)\n        self.total +=len(trajs)\n\n    def compute(self):\n        return {\n            'obj_col': self.obj_col / self.total,\n            'obj_box_col': self.obj_box_col / self.total,\n            'L2' : self.L2 / self.total\n        }"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/rpn_head.py",
    "content": "import copy\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.ops.nms import batched_nms\nfrom mmcv.utils import force_fp32\n\nfrom ..builder import HEADS\nfrom .anchor_head import AnchorHead\n\n\n@HEADS.register_module()\nclass RPNHead(AnchorHead):\n    \"\"\"RPN head.\n\n    Args:\n        in_channels (int): Number of channels in the input feature map.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n    \"\"\"  # noqa: W605\n\n    def __init__(self,\n                 in_channels,\n                 init_cfg=dict(type='Normal', layer='Conv2d', std=0.01),\n                 **kwargs):\n        super(RPNHead, self).__init__(\n            1, in_channels, init_cfg=init_cfg, **kwargs)\n\n    def _init_layers(self):\n        \"\"\"Initialize layers of the head.\"\"\"\n        self.rpn_conv = nn.Conv2d(\n            self.in_channels, self.feat_channels, 3, padding=1)\n        self.rpn_cls = nn.Conv2d(self.feat_channels,\n                                 self.num_anchors * self.cls_out_channels, 1)\n        self.rpn_reg = nn.Conv2d(self.feat_channels, self.num_anchors * 4, 1)\n\n    def forward_single(self, x):\n        \"\"\"Forward feature map of a single scale level.\"\"\"\n        x = self.rpn_conv(x)\n        x = F.relu(x, inplace=True)\n        rpn_cls_score = self.rpn_cls(x)\n        rpn_bbox_pred = self.rpn_reg(x)\n        return rpn_cls_score, rpn_bbox_pred\n\n    def loss(self,\n             cls_scores,\n             bbox_preds,\n             gt_bboxes,\n             img_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"Compute losses of the head.\n\n        Args:\n            cls_scores (list[Tensor]): Box scores for each scale level\n                Has shape (N, num_anchors * num_classes, H, W)\n            bbox_preds (list[Tensor]): Box energies / deltas for each scale\n                level with shape (N, num_anchors * 4, H, W)\n            gt_bboxes (list[Tensor]): Ground truth bboxes for each image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            gt_bboxes_ignore (None | list[Tensor]): specify which bounding\n                boxes can be ignored when computing the loss.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        losses = super(RPNHead, self).loss(\n            cls_scores,\n            bbox_preds,\n            gt_bboxes,\n            None,\n            img_metas,\n            gt_bboxes_ignore=gt_bboxes_ignore)\n        return dict(\n            loss_rpn_cls=losses['loss_cls'], loss_rpn_bbox=losses['loss_bbox'])\n\n    @force_fp32(apply_to=('cls_scores', 'bbox_preds'))\n    def get_bboxes(self,\n                   cls_scores,\n                   bbox_preds,\n                   img_metas,\n                   cfg=None,\n                   rescale=False,\n                   with_nms=True):\n        \"\"\"Transform network output for a batch into bbox predictions.\n\n        Args:\n            cls_scores (list[Tensor]): Box scores for each scale level\n                Has shape (N, num_anchors * num_classes, H, W)\n            bbox_preds (list[Tensor]): Box energies / deltas for each scale\n                level with shape (N, num_anchors * 4, H, W)\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            cfg (mmcv.Config | None): Test / postprocessing configuration,\n                if None, test_cfg would be used\n            rescale (bool): If True, return boxes in original image space.\n                Default: False.\n            with_nms (bool): If True, do nms before return boxes.\n                Default: True.\n\n        Returns:\n            list[tuple[Tensor, Tensor]]: Each item in result_list is 2-tuple.\n                The first item is an (n, 5) tensor, where the first 4 columns\n                are bounding box positions (tl_x, tl_y, br_x, br_y) and the\n                5-th column is a score between 0 and 1. The second item is a\n                (n,) tensor where each item is the predicted class label of the\n                corresponding box.\n        \"\"\"\n        assert with_nms, '``with_nms`` in RPNHead should always True'\n        assert len(cls_scores) == len(bbox_preds)\n        num_levels = len(cls_scores)\n        device = cls_scores[0].device\n        featmap_sizes = [cls_scores[i].shape[-2:] for i in range(num_levels)]\n        mlvl_anchors = self.anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n\n        result_list = []\n        for img_id in range(len(img_metas)):\n            cls_score_list = [\n                cls_scores[i][img_id].detach() for i in range(num_levels)\n            ]\n            bbox_pred_list = [\n                bbox_preds[i][img_id].detach() for i in range(num_levels)\n            ]\n            img_shape = img_metas[img_id]['img_shape']\n            scale_factor = img_metas[img_id]['scale_factor']\n            proposals = self._get_bboxes_single(cls_score_list, bbox_pred_list,\n                                                mlvl_anchors, img_shape,\n                                                scale_factor, cfg, rescale)\n            result_list.append(proposals)\n        return result_list\n\n    def _get_bboxes_single(self,\n                           cls_scores,\n                           bbox_preds,\n                           mlvl_anchors,\n                           img_shape,\n                           scale_factor,\n                           cfg,\n                           rescale=False):\n        \"\"\"Transform outputs for a single batch item into bbox predictions.\n\n          Args:\n            cls_scores (list[Tensor]): Box scores of all scale level\n                each item has shape (num_anchors * num_classes, H, W).\n            bbox_preds (list[Tensor]): Box energies / deltas of all\n                scale level, each item has shape (num_anchors * 4, H, W).\n            mlvl_anchors (list[Tensor]): Anchors of all scale level\n                each item has shape (num_total_anchors, 4).\n            img_shape (tuple[int]): Shape of the input image,\n                (height, width, 3).\n            scale_factor (ndarray): Scale factor of the image arrange as\n                (w_scale, h_scale, w_scale, h_scale).\n            cfg (mmcv.Config): Test / postprocessing configuration,\n                if None, test_cfg would be used.\n            rescale (bool): If True, return boxes in original image space.\n                Default: False.\n\n        Returns:\n            Tensor: Labeled boxes in shape (n, 5), where the first 4 columns\n                are bounding box positions (tl_x, tl_y, br_x, br_y) and the\n                5-th column is a score between 0 and 1.\n        \"\"\"\n        cfg = self.test_cfg if cfg is None else cfg\n        cfg = copy.deepcopy(cfg)\n        # bboxes from different level should be independent during NMS,\n        # level_ids are used as labels for batched NMS to separate them\n        level_ids = []\n        mlvl_scores = []\n        mlvl_bbox_preds = []\n        mlvl_valid_anchors = []\n        for idx in range(len(cls_scores)):\n            rpn_cls_score = cls_scores[idx]\n            rpn_bbox_pred = bbox_preds[idx]\n            assert rpn_cls_score.size()[-2:] == rpn_bbox_pred.size()[-2:]\n            rpn_cls_score = rpn_cls_score.permute(1, 2, 0)\n            if self.use_sigmoid_cls:\n                rpn_cls_score = rpn_cls_score.reshape(-1)\n                scores = rpn_cls_score.sigmoid()\n            else:\n                rpn_cls_score = rpn_cls_score.reshape(-1, 2)\n                # We set FG labels to [0, num_class-1] and BG label to\n                # num_class in RPN head since mmdet v2.5, which is unified to\n                # be consistent with other head since mmdet v2.0. In mmdet v2.0\n                # to v2.4 we keep BG label as 0 and FG label as 1 in rpn head.\n                scores = rpn_cls_score.softmax(dim=1)[:, 0]\n            rpn_bbox_pred = rpn_bbox_pred.permute(1, 2, 0).reshape(-1, 4)\n            anchors = mlvl_anchors[idx]\n            if cfg.nms_pre > 0 and scores.shape[0] > cfg.nms_pre:\n                # sort is faster than topk\n                # _, topk_inds = scores.topk(cfg.nms_pre)\n                ranked_scores, rank_inds = scores.sort(descending=True)\n                topk_inds = rank_inds[:cfg.nms_pre]\n                scores = ranked_scores[:cfg.nms_pre]\n                rpn_bbox_pred = rpn_bbox_pred[topk_inds, :]\n                anchors = anchors[topk_inds, :]\n            mlvl_scores.append(scores)\n            mlvl_bbox_preds.append(rpn_bbox_pred)\n            mlvl_valid_anchors.append(anchors)\n            level_ids.append(\n                scores.new_full((scores.size(0), ), idx, dtype=torch.long))\n\n        scores = torch.cat(mlvl_scores)\n        anchors = torch.cat(mlvl_valid_anchors)\n        rpn_bbox_pred = torch.cat(mlvl_bbox_preds)\n        proposals = self.bbox_coder.decode(\n            anchors, rpn_bbox_pred, max_shape=img_shape)\n        ids = torch.cat(level_ids)\n\n        if cfg.min_bbox_size > 0:\n            w = proposals[:, 2] - proposals[:, 0]\n            h = proposals[:, 3] - proposals[:, 1]\n            valid_mask = (w >= cfg.min_bbox_size) & (h >= cfg.min_bbox_size)\n            if not valid_mask.all():\n                proposals = proposals[valid_mask]\n                scores = scores[valid_mask]\n                ids = ids[valid_mask]\n        if proposals.numel() > 0:\n            dets, keep = batched_nms(proposals, scores, ids, cfg.nms)\n        else:\n            return proposals.new_zeros(0, 5)\n\n        return dets[:cfg.max_per_img]\n\n    def onnx_export(self, x, img_metas):\n        \"\"\"Test without augmentation.\n\n        Args:\n            x (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n            img_metas (list[dict]): Meta info of each image.\n\n        Returns:\n            tuple[Tensor, Tensor]: dets of shape [N, num_det, 5]\n                and class labels of shape [N, num_det].\n        \"\"\"\n        cls_scores, bbox_preds = self(x)\n\n        assert len(cls_scores) == len(bbox_preds)\n        num_levels = len(cls_scores)\n\n        device = cls_scores[0].device\n        featmap_sizes = [cls_scores[i].shape[-2:] for i in range(num_levels)]\n        mlvl_anchors = self.anchor_generator.grid_anchors(\n            featmap_sizes, device=device)\n\n        cls_scores = [cls_scores[i].detach() for i in range(num_levels)]\n        bbox_preds = [bbox_preds[i].detach() for i in range(num_levels)]\n\n        assert len(\n            img_metas\n        ) == 1, 'Only support one input image while in exporting to ONNX'\n        img_shapes = img_metas[0]['img_shape_for_onnx']\n\n        cfg = copy.deepcopy(self.test_cfg)\n\n        mlvl_scores = []\n        mlvl_bbox_preds = []\n        mlvl_valid_anchors = []\n        batch_size = cls_scores[0].shape[0]\n        nms_pre_tensor = torch.tensor(\n            cfg.nms_pre, device=cls_scores[0].device, dtype=torch.long)\n        for idx in range(len(cls_scores)):\n            rpn_cls_score = cls_scores[idx]\n            rpn_bbox_pred = bbox_preds[idx]\n            assert rpn_cls_score.size()[-2:] == rpn_bbox_pred.size()[-2:]\n            rpn_cls_score = rpn_cls_score.permute(0, 2, 3, 1)\n            if self.use_sigmoid_cls:\n                rpn_cls_score = rpn_cls_score.reshape(batch_size, -1)\n                scores = rpn_cls_score.sigmoid()\n            else:\n                rpn_cls_score = rpn_cls_score.reshape(batch_size, -1, 2)\n                # We set FG labels to [0, num_class-1] and BG label to\n                # num_class in RPN head since mmdet v2.5, which is unified to\n                # be consistent with other head since mmdet v2.0. In mmdet v2.0\n                # to v2.4 we keep BG label as 0 and FG label as 1 in rpn head.\n                scores = rpn_cls_score.softmax(-1)[..., 0]\n            rpn_bbox_pred = rpn_bbox_pred.permute(0, 2, 3, 1).reshape(\n                batch_size, -1, 4)\n            anchors = mlvl_anchors[idx]\n            anchors = anchors.expand_as(rpn_bbox_pred)\n            # Get top-k prediction\n            from mmcv.core.export import get_k_for_topk\n            nms_pre = get_k_for_topk(nms_pre_tensor, rpn_bbox_pred.shape[1])\n            if nms_pre > 0:\n                _, topk_inds = scores.topk(nms_pre)\n                batch_inds = torch.arange(batch_size).view(\n                    -1, 1).expand_as(topk_inds)\n                # Avoid onnx2tensorrt issue in https://github.com/NVIDIA/TensorRT/issues/1134 # noqa: E501\n                # Mind k<=3480 in TensorRT for TopK\n                transformed_inds = scores.shape[1] * batch_inds + topk_inds\n                scores = scores.reshape(-1, 1)[transformed_inds].reshape(\n                    batch_size, -1)\n                rpn_bbox_pred = rpn_bbox_pred.reshape(\n                    -1, 4)[transformed_inds, :].reshape(batch_size, -1, 4)\n                anchors = anchors.reshape(-1, 4)[transformed_inds, :].reshape(\n                    batch_size, -1, 4)\n            mlvl_scores.append(scores)\n            mlvl_bbox_preds.append(rpn_bbox_pred)\n            mlvl_valid_anchors.append(anchors)\n\n        batch_mlvl_scores = torch.cat(mlvl_scores, dim=1)\n        batch_mlvl_anchors = torch.cat(mlvl_valid_anchors, dim=1)\n        batch_mlvl_rpn_bbox_pred = torch.cat(mlvl_bbox_preds, dim=1)\n        batch_mlvl_proposals = self.bbox_coder.decode(\n            batch_mlvl_anchors, batch_mlvl_rpn_bbox_pred, max_shape=img_shapes)\n\n        # Use ONNX::NonMaxSuppression in deployment\n        from mmcv.core.export import add_dummy_nms_for_onnx\n        batch_mlvl_scores = batch_mlvl_scores.unsqueeze(2)\n        score_threshold = cfg.nms.get('score_thr', 0.0)\n        nms_pre = cfg.get('deploy_nms_pre', -1)\n        dets, _ = add_dummy_nms_for_onnx(batch_mlvl_proposals,\n                                         batch_mlvl_scores, cfg.max_per_img,\n                                         cfg.nms.iou_threshold,\n                                         score_threshold, nms_pre,\n                                         cfg.max_per_img)\n        return dets\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/seg_head_plugin/__init__.py",
    "content": "from .seg_detr_head import SegDETRHead\nfrom .seg_mask_head import SegMaskHead\nfrom .seg_deformable_transformer import SegDeformableTransformer\nfrom .seg_assigner import *\nfrom .seg_utils import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/seg_head_plugin/seg_assigner.py",
    "content": "from mmcv.core import mask\nimport torch\nfrom mmcv.core.bbox.assigners.base_assigner import BaseAssigner\n\nfrom mmcv.core.bbox.assigners.assign_result import AssignResult\nfrom mmcv.core.bbox.transforms import bbox_cxcywh_to_xyxy\nfrom mmcv.core.bbox.match_costs import build_match_cost\nfrom mmcv.core.bbox.builder import BBOX_ASSIGNERS\ntry:\n    from scipy.optimize import linear_sum_assignment\nexcept ImportError:\n    linear_sum_assignment = None\n\nfrom mmcv.core.bbox.samplers.base_sampler import BaseSampler\nfrom mmcv.core.bbox.builder import BBOX_SAMPLERS\nfrom mmcv.core import mask\nimport torch\n\nfrom mmcv.utils import util_mixins\n\n\nINF = 10000000\n\n\nclass SamplingResult_segformer(util_mixins.NiceRepr):\n    \"\"\"\n    \"\"\"\n\n    def __init__(self, pos_inds, neg_inds, bboxes, gt_bboxes, gt_masks,assign_result,\n                 gt_flags):\n        self.pos_inds = pos_inds\n        self.neg_inds = neg_inds\n        self.pos_bboxes = bboxes[pos_inds]\n        self.neg_bboxes = bboxes[neg_inds]\n        self.pos_is_gt = gt_flags[pos_inds]\n\n        self.num_gts = gt_bboxes.shape[0]\n        self.pos_assigned_gt_inds = assign_result.gt_inds[pos_inds] - 1\n       \n\n        if gt_bboxes.numel() == 0:\n            # hack for index error case\n            assert self.pos_assigned_gt_inds.numel() == 0\n            self.pos_gt_bboxes = torch.empty_like(gt_bboxes).view(-1, 4)\n            \n            #print('pos_gt_bboxes',self.pos_gt_bboxes.shape)\n            #print('gt_mask',gt_masks.shape)\n            n,h,w = gt_masks.shape\n            #n = self.pos_gt_bboxes.shape[0]\n            self.pos_gt_masks = torch.empty_like(gt_masks).view(-1, h,w)\n        else:\n            if len(gt_bboxes.shape) < 2:\n                gt_bboxes = gt_bboxes.view(-1, 4)\n            \n            self.pos_gt_bboxes = gt_bboxes[self.pos_assigned_gt_inds, :]\n            self.pos_gt_masks = gt_masks[self.pos_assigned_gt_inds, :]\n\n        if assign_result.labels is not None:\n            self.pos_gt_labels = assign_result.labels[pos_inds]\n        else:\n            self.pos_gt_labels = None\n\n    @property\n    def bboxes(self):\n        \"\"\"torch.Tensor: concatenated positive and negative boxes\"\"\"\n        return torch.cat([self.pos_bboxes, self.neg_bboxes])\n  \n\n    def to(self, device):\n        \"\"\"Change the device of the data inplace.\n\n        Example:\n            >>> self = SamplingResult.random()\n            >>> print(f'self = {self.to(None)}')\n            >>> # xdoctest: +REQUIRES(--gpu)\n            >>> print(f'self = {self.to(0)}')\n        \"\"\"\n        _dict = self.__dict__\n        for key, value in _dict.items():\n            if isinstance(value, torch.Tensor):\n                _dict[key] = value.to(device)\n        return self\n\n    def __nice__(self):\n        data = self.info.copy()\n        data['pos_bboxes'] = data.pop('pos_bboxes').shape\n        data['neg_bboxes'] = data.pop('neg_bboxes').shape\n        parts = [f\"'{k}': {v!r}\" for k, v in sorted(data.items())]\n        body = '    ' + ',\\n    '.join(parts)\n        return '{\\n' + body + '\\n}'\n\n    @property\n    def info(self):\n        \"\"\"Returns a dictionary of info about the object.\"\"\"\n        return {\n            'pos_inds': self.pos_inds,\n            'neg_inds': self.neg_inds,\n            'pos_bboxes': self.pos_bboxes,\n            'neg_bboxes': self.neg_bboxes,\n            'pos_is_gt': self.pos_is_gt,\n            'num_gts': self.num_gts,\n            'pos_assigned_gt_inds': self.pos_assigned_gt_inds,\n        }\n\n    @classmethod\n    def random(cls, rng=None, **kwargs):\n        \"\"\"\n        Args:\n            rng (None | int | numpy.random.RandomState): seed or state.\n            kwargs (keyword arguments):\n                - num_preds: number of predicted boxes\n                - num_gts: number of true boxes\n                - p_ignore (float): probability of a predicted box assigned to \\\n                    an ignored truth.\n                - p_assigned (float): probability of a predicted box not being \\\n                    assigned.\n                - p_use_label (float | bool): with labels or not.\n\n        Returns:\n            :obj:`SamplingResult`: Randomly generated sampling result.\n\n        Example:\n            >>> from mmcv.core.bbox.samplers.sampling_result import *  # NOQA\n            >>> self = SamplingResult.random()\n            >>> print(self.__dict__)\n        \"\"\"\n        from mmcv.core.bbox.samplers.random_sampler import RandomSampler\n        from mmcv.core.bbox.assigners.assign_result import AssignResult\n        from mmcv.core.bbox import demodata\n        rng = demodata.ensure_rng(rng)\n\n        # make probabalistic?\n        num = 32\n        pos_fraction = 0.5\n        neg_pos_ub = -1\n\n        assign_result = AssignResult.random(rng=rng, **kwargs)\n\n        # Note we could just compute an assignment\n        bboxes = demodata.random_boxes(assign_result.num_preds, rng=rng)\n        gt_bboxes = demodata.random_boxes(assign_result.num_gts, rng=rng)\n\n        if rng.rand() > 0.2:\n            # sometimes algorithms squeeze their data, be robust to that\n            gt_bboxes = gt_bboxes.squeeze()\n            bboxes = bboxes.squeeze()\n\n        if assign_result.labels is None:\n            gt_labels = None\n        else:\n            gt_labels = None  # todo\n\n        if gt_labels is None:\n            add_gt_as_proposals = False\n        else:\n            add_gt_as_proposals = True  # make probabalistic?\n\n        sampler = RandomSampler(\n            num,\n            pos_fraction,\n            neg_pos_ub=neg_pos_ub,\n            add_gt_as_proposals=add_gt_as_proposals,\n            rng=rng)\n        self = sampler.sample(assign_result, bboxes, gt_bboxes, gt_labels)\n        return self\n\n\n@BBOX_SAMPLERS.register_module()\nclass PseudoSampler_segformer(BaseSampler):\n    \"\"\"A pseudo sampler that does not do sampling actually.\"\"\"\n\n    def __init__(self, **kwargs):\n        pass\n\n    def _sample_pos(self, **kwargs):\n        \"\"\"Sample positive samples.\"\"\"\n        raise NotImplementedError\n\n    def _sample_neg(self, **kwargs):\n        \"\"\"Sample negative samples.\"\"\"\n        raise NotImplementedError\n\n    def sample(self, assign_result, bboxes, gt_bboxes,gt_masks, **kwargs):\n        \"\"\"Directly returns the positive and negative indices  of samples.\n\n        Args:\n            assign_result (:obj:`AssignResult`): Assigned results\n            bboxes (torch.Tensor): Bounding boxes\n            gt_bboxes (torch.Tensor): Ground truth boxes\n\n        Returns:\n            :obj:`SamplingResult`: sampler results\n        \"\"\"\n        pos_inds = torch.nonzero(\n            assign_result.gt_inds > 0, as_tuple=False).squeeze(-1).unique()\n        neg_inds = torch.nonzero(\n            assign_result.gt_inds == 0, as_tuple=False).squeeze(-1).unique()\n        gt_flags = bboxes.new_zeros(bboxes.shape[0], dtype=torch.uint8)\n        sampling_result = SamplingResult_segformer(pos_inds, neg_inds, bboxes, gt_bboxes,gt_masks,\n                                         assign_result, gt_flags,**kwargs)\n        return sampling_result\n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianAssigner_filter(BaseAssigner):\n    \"\"\"\n    \"\"\"\n\n    def __init__(self,\n                 cls_cost=dict(type='ClassificationCost', weight=1.),\n                 reg_cost=dict(type='BBoxL1Cost', weight=1.0),\n                 iou_cost=dict(type='IoUCost', iou_mode='giou', weight=1.0),\n                 max_pos = 3\n                 ):\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n        self.iou_cost = build_match_cost(iou_cost)\n        self.max_pos = max_pos\n    def assign(self,\n               bbox_pred,\n               cls_pred,\n               gt_bboxes,\n               gt_labels,\n               img_meta,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)\n\n        # 1. assign -1 by default\n        assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),\n                                              -1,\n                                              dtype=torch.long)\n        \n        assigned_labels = bbox_pred.new_full((num_bboxes, ),-1,dtype=torch.long)\n\n        if num_gts == 0 or num_bboxes == 0:\n            # No ground truth or boxes, return empty assignment\n            if num_gts == 0:\n                assigned_gt_inds[:] = 0\n                # No ground truth, assign all to background\n                pos_ind = assigned_gt_inds.gt(0).nonzero().squeeze(1)\n                neg_ind = assigned_gt_inds.eq(0).nonzero().squeeze(1)\n                # No ground truth, assign all to background\n            return pos_ind, neg_ind,  AssignResult(\n                num_gts, assigned_gt_inds, None, labels=assigned_labels)\n        img_h, img_w, _ = img_meta['img_shape']\n        factor = gt_bboxes.new_tensor([img_w, img_h, img_w,\n                                       img_h]).unsqueeze(0)\n\n        # 2. compute the weighted costs\n        # classification and bboxcost.\n        \n        cls_cost = self.cls_cost(cls_pred, gt_labels)\n        # regression L1 cost\n        normalize_gt_bboxes = gt_bboxes / factor\n        reg_cost = self.reg_cost(bbox_pred, normalize_gt_bboxes)\n        # regression iou cost, defaultly giou is used in official DETR.\n        bboxes = bbox_cxcywh_to_xyxy(bbox_pred) * factor\n        iou_cost = self.iou_cost(bboxes, gt_bboxes)\n        # weighted sum of above three cost\n        \n        cost = cls_cost + reg_cost + iou_cost \n        \n        # 3. do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu()\n\n        assigned_gt_inds[:] = 0\n        #index_set = []\n        \n        if linear_sum_assignment is None:\n            raise ImportError('Please run \"pip install scipy\" '\n                              'to install scipy first.')\n        result=None\n        for i in range(max(min(self.max_pos, 300//num_gts),1)):\n            matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n            \n            matched_row_inds = torch.from_numpy(matched_row_inds).to(\n                bbox_pred.device)\n            matched_col_inds = torch.from_numpy(matched_col_inds).to(\n                bbox_pred.device)     \n            #print(matched_row_inds)\n                \n            cost[matched_row_inds,:] = INF   \n            #index_set.(matched_row_inds)\n            #print('this mathed row inds ', len(matched_row_inds), i)\n            assigned_gt_inds[matched_row_inds] = matched_col_inds + 1\n            assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]\n            if i == 0:\n                result = AssignResult(num_gts, assigned_gt_inds.clone(), None, labels=assigned_labels.clone())\n            if cost[matched_row_inds.cpu(), matched_col_inds.cpu()].max()>=INF:\n                break\n        pos_ind = assigned_gt_inds.gt(0).nonzero().squeeze(1)\n        neg_ind = assigned_gt_inds.eq(0).nonzero().squeeze(1)\n        \n        return pos_ind, neg_ind, result\n            \n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianAssigner_multi_info(BaseAssigner):\n    \"\"\"Computes one-to-one matching between predictions and ground truth.\n\n    This class computes an assignment between the targets and the predictions\n    based on the costs. The costs are weighted sum of three components:\n    classification cost, regression L1 cost and regression iou cost. The\n    targets don't include the no_object, so generally there are more\n    predictions than targets. After the one-to-one matching, the un-matched\n    are treated as backgrounds. Thus each query prediction will be assigned\n    with `0` or a positive integer indicating the ground truth index:\n\n    - 0: negative sample, no assigned gt\n    - positive integer: positive sample, index (1-based) of assigned gt\n\n    Args:\n        cls_weight (int | float, optional): The scale factor for classification\n            cost. Default 1.0.\n        bbox_weight (int | float, optional): The scale factor for regression\n            L1 cost. Default 1.0.\n        iou_weight (int | float, optional): The scale factor for regression\n            iou cost. Default 1.0.\n        iou_calculator (dict | optional): The config for the iou calculation.\n            Default type `BboxOverlaps2D`.\n        iou_mode (str | optional): \"iou\" (intersection over union), \"iof\"\n                (intersection over foreground), or \"giou\" (generalized\n                intersection over union). Default \"giou\".\n    \"\"\"\n\n    def __init__(self,\n                 cls_cost=dict(type='ClassificationCost', weight=1.),\n                 reg_cost=dict(type='BBoxL1Cost', weight=1.0),\n                 iou_cost=dict(type='IoUCost', iou_mode='giou', weight=1.0),\n                 mask_cost=dict(type='DiceCost', weight=1.0)\n                \n                 ):\n        cls_cost['weight'] *= 2\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n        self.iou_cost = build_match_cost(iou_cost)\n        self.mask_cost = build_match_cost(mask_cost)\n     \n\n    def assign(self,\n               bbox_pred,\n               cls_pred,\n               mask_pred,\n               gt_bboxes,\n               gt_labels,\n               gt_mask,\n               img_meta,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"Computes one-to-one matching based on the weighted costs.\n\n        This method assign each query prediction to a ground truth or\n        background. The `assigned_gt_inds` with -1 means don't care,\n        0 means negative sample, and positive number is the index (1-based)\n        of assigned gt.\n        The assignment is done in the following steps, the order matters.\n\n        1. assign every prediction to -1\n        2. compute the weighted costs\n        3. do Hungarian matching on CPU based on the costs\n        4. assign all to 0 (background) first, then for each matched pair\n           between predictions and gts, treat this prediction as foreground\n           and assign the corresponding gt index (plus 1) to it.\n\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (cx, cy, w, h), which are all in range [0, 1]. Shape\n                [num_query, 4].\n            cls_pred (Tensor): Predicted classification logits, shape\n                [num_query, num_class].\n            gt_bboxes (Tensor): Ground truth boxes with unnormalized\n                coordinates (x1, y1, x2, y2). Shape [num_gt, 4].\n            gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n            img_meta (dict): Meta information for current image.\n            gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                labelled as `ignored`. Default None.\n            eps (int | float, optional): A value added to the denominator for\n                numerical stability. Default 1e-7.\n\n        Returns:\n            :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        #print(bbox_pred.shape, cls_pred.shape,mask_pred.shape,gt_bboxes.shape,gt_labels.shape,gt_mask.shape)\n        num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)\n\n        # 1. assign -1 by default\n        assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),\n                                              -1,\n                                              dtype=torch.long)\n\n        assigned_labels = bbox_pred.new_full((num_bboxes, ),\n                                             -1,\n                                             dtype=torch.long)\n\n        if num_gts == 0 or num_bboxes == 0:\n            # No ground truth or boxes, return empty assignment\n            if num_gts == 0:\n                # No ground truth, assign all to background\n                assigned_gt_inds[:] = 0\n            return AssignResult(\n                num_gts, assigned_gt_inds, None, labels=assigned_labels)\n        img_h, img_w, _ = img_meta['img_shape']\n        \n        factor = bbox_pred.new_tensor([img_w, img_h, img_w,img_h]).unsqueeze(0)\n\n      \n        # classification and bboxcost.\n        cls_cost = self.cls_cost(cls_pred, gt_labels)\n        # regression L1 cost\n        normalize_gt_bboxes = gt_bboxes / factor\n        reg_cost = self.reg_cost(bbox_pred, normalize_gt_bboxes)\n        # regression iou cost, defaultly giou is used in official DETR.\n        bboxes = bbox_cxcywh_to_xyxy(bbox_pred) * factor\n        iou_cost = self.iou_cost(bboxes, gt_bboxes)\n        # weighted sum of above three costs\n        mask_cost = self.mask_cost(mask_pred,gt_mask)\n        #\n        cost = cls_cost + reg_cost + iou_cost + mask_cost\n\n        # 3. do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu()\n        if linear_sum_assignment is None:\n            raise ImportError('Please run \"pip install scipy\" '\n                              'to install scipy first.')\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        matched_row_inds = torch.from_numpy(matched_row_inds).to(\n            bbox_pred.device)\n        matched_col_inds = torch.from_numpy(matched_col_inds).to(\n            bbox_pred.device)\n        # 4. assign backgrounds and foregrounds\n        # assign all indices to backgrounds first\n        assigned_gt_inds[:] = 0\n        # assign foregrounds based on matching results\n     \n        assigned_gt_inds[matched_row_inds] = matched_col_inds + 1\n        assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]\n        return AssignResult(\n            num_gts, assigned_gt_inds, None, labels=assigned_labels)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/seg_head_plugin/seg_deformable_transformer.py",
    "content": "from mmcv.utils import force_fp32\nfrom mmcv.models.utils.builder import TRANSFORMER\nfrom mmcv.models.utils import Transformer\nimport warnings\nimport math\nimport copy\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.bricks import build_activation_layer, build_norm_layer\nfrom mmcv.models.utils import xavier_init\nfrom mmcv.models.bricks.registry import (TRANSFORMER_LAYER,\n                                      TRANSFORMER_LAYER_SEQUENCE)\nfrom mmcv.models.bricks.transformer import (BaseTransformerLayer,\n                                         MultiScaleDeformableAttention,\n                                         TransformerLayerSequence,\n                                         build_transformer_layer_sequence)\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom torch.nn.init import normal_\n\nfrom mmcv.models.utils.builder import TRANSFORMER\nfrom mmcv.models.bricks.registry import ATTENTION\nfrom torch import einsum\n\nfrom einops import rearrange, repeat\nfrom einops.layers.torch import Rearrange\n\n# Copy-paste from defromable detr in mmcv.\n@TRANSFORMER.register_module()\nclass SegDeformableTransformer(Transformer):\n    \"\"\"Implements the DeformableDETR transformer.\n\n    Args:\n        as_two_stage (bool): Generate query from encoder features.\n            Default: False.\n        num_feature_levels (int): Number of feature maps from FPN:\n            Default: 4.\n        two_stage_num_proposals (int): Number of proposals when set\n            `as_two_stage` as True. Default: 300.\n    \"\"\"\n    def __init__(self,\n                 as_two_stage=False,\n                 num_feature_levels=4,\n                 two_stage_num_proposals=300,\n                 **kwargs):\n        super(SegDeformableTransformer, self).__init__(**kwargs)\n        self.fp16_enabled = False\n        self.as_two_stage = as_two_stage\n        self.num_feature_levels = num_feature_levels\n        self.two_stage_num_proposals = two_stage_num_proposals\n        self.embed_dims = self.encoder.embed_dims\n        self.init_layers()\n\n    def init_layers(self):\n        \"\"\"Initialize layers of the DeformableDetrTransformer.\"\"\"\n        self.level_embeds = nn.Parameter(\n            torch.Tensor(self.num_feature_levels, self.embed_dims))\n\n        if self.as_two_stage:\n            self.enc_output = nn.Linear(self.embed_dims, self.embed_dims)\n            self.enc_output_norm = nn.LayerNorm(self.embed_dims)\n            self.pos_trans = nn.Linear(self.embed_dims * 2,\n                                       self.embed_dims * 2)\n            self.pos_trans_norm = nn.LayerNorm(self.embed_dims * 2)\n        else:\n            self.reference_points = nn.Linear(self.embed_dims, 2)\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MultiScaleDeformableAttention):\n                try:\n                    m.init_weight()\n                except:\n                    m.init_weights()\n        if not self.as_two_stage:\n            xavier_init(self.reference_points, distribution='uniform', bias=0.)\n        normal_(self.level_embeds)\n\n    def gen_encoder_output_proposals(self, memory, memory_padding_mask,\n                                     spatial_shapes):\n        \"\"\"Generate proposals from encoded memory.\n\n        Args:\n            memory (Tensor) : The output of encoder,\n                has shape (bs, num_key, embed_dim).  num_key is\n                equal the number of points on feature map from\n                all level.\n            memory_padding_mask (Tensor): Padding mask for memory.\n                has shape (bs, num_key).\n            spatial_shapes (Tensor): The shape of all feature maps.\n                has shape (num_level, 2).\n\n        Returns:\n            tuple: A tuple of feature map and bbox prediction.\n\n                - output_memory (Tensor): The input of decoder,  \\\n                    has shape (bs, num_key, embed_dim).  num_key is \\\n                    equal the number of points on feature map from \\\n                    all levels.\n                - output_proposals (Tensor): The normalized proposal \\\n                    after a inverse sigmoid, has shape \\\n                    (bs, num_keys, 4).\n        \"\"\"\n\n        N, S, C = memory.shape\n        proposals = []\n        _cur = 0\n        for lvl, (H, W) in enumerate(spatial_shapes):\n            mask_flatten_ = memory_padding_mask[:, _cur:(_cur + H * W)].view(\n                N, H, W, 1)\n            valid_H = torch.sum(~mask_flatten_[:, :, 0, 0], 1)\n            valid_W = torch.sum(~mask_flatten_[:, 0, :, 0], 1)\n\n            grid_y, grid_x = torch.meshgrid(\n                torch.linspace(0,\n                               H - 1,\n                               H,\n                               dtype=torch.float32,\n                               device=memory.device),\n                torch.linspace(0,\n                               W - 1,\n                               W,\n                               dtype=torch.float32,\n                               device=memory.device))\n            grid = torch.cat([grid_x.unsqueeze(-1), grid_y.unsqueeze(-1)], -1)\n\n            scale = torch.cat([valid_W.unsqueeze(-1),\n                               valid_H.unsqueeze(-1)], 1).view(N, 1, 1, 2)\n            grid = (grid.unsqueeze(0).expand(N, -1, -1, -1) + 0.5) / scale\n            wh = torch.ones_like(grid) * 0.05 * (2.0**lvl)\n            proposal = torch.cat((grid, wh), -1).view(N, -1, 4)\n            proposals.append(proposal)\n            _cur += (H * W)\n        output_proposals = torch.cat(proposals, 1)\n        output_proposals_valid = ((output_proposals > 0.01) &\n                                  (output_proposals < 0.99)).all(-1,\n                                                                 keepdim=True)\n        output_proposals = torch.log(output_proposals / (1 - output_proposals))\n        output_proposals = output_proposals.masked_fill(\n            memory_padding_mask.unsqueeze(-1), float('inf'))\n        output_proposals = output_proposals.masked_fill(\n            ~output_proposals_valid, float('inf'))\n\n        output_memory = memory\n        output_memory = output_memory.masked_fill(\n            memory_padding_mask.unsqueeze(-1), float(0))\n        output_memory = output_memory.masked_fill(~output_proposals_valid,\n                                                  float(0))\n        output_memory = self.enc_output_norm(self.enc_output(output_memory))\n        return output_memory, output_proposals\n\n    @staticmethod\n    def get_reference_points(spatial_shapes, valid_ratios, device):\n        \"\"\"Get the reference points used in decoder.\n\n        Args:\n            spatial_shapes (Tensor): The shape of all\n                feature maps, has shape (num_level, 2).\n            valid_ratios (Tensor): The radios of valid\n                points on the feature map, has shape\n                (bs, num_levels, 2)\n            device (obj:`device`): The device where\n                reference_points should be.\n\n        Returns:\n            Tensor: reference points used in decoder, has \\\n                shape (bs, num_keys, num_levels, 2).\n        \"\"\"\n        reference_points_list = []\n        for lvl, (H, W) in enumerate(spatial_shapes):\n            #  TODO  check this 0.5\n            ref_y, ref_x = torch.meshgrid(\n                torch.linspace(0.5,\n                               H - 0.5,\n                               H,\n                               dtype=torch.float32,\n                               device=device),\n                torch.linspace(0.5,\n                               W - 0.5,\n                               W,\n                               dtype=torch.float32,\n                               device=device))\n            ref_y = ref_y.reshape(-1)[None] / (valid_ratios[:, None, lvl, 1] *\n                                               H)\n            ref_x = ref_x.reshape(-1)[None] / (valid_ratios[:, None, lvl, 0] *\n                                               W)\n            ref = torch.stack((ref_x, ref_y), -1)\n            reference_points_list.append(ref)\n        reference_points = torch.cat(reference_points_list, 1)\n        reference_points = reference_points[:, :, None] * valid_ratios[:, None]\n        return reference_points\n\n    def get_valid_ratio(self, mask):\n        \"\"\"Get the valid radios of feature maps of all  level.\"\"\"\n        _, H, W = mask.shape\n        valid_H = torch.sum(~mask[:, :, 0], 1)\n        valid_W = torch.sum(~mask[:, 0, :], 1)\n        valid_ratio_h = valid_H.float() / H\n        valid_ratio_w = valid_W.float() / W\n        valid_ratio = torch.stack([valid_ratio_w, valid_ratio_h], -1)\n        return valid_ratio\n\n    def get_proposal_pos_embed(self,\n                               proposals,\n                               num_pos_feats=128,\n                               temperature=10000):\n        \"\"\"Get the position embedding of proposal.\"\"\"\n        scale = 2 * math.pi\n        dim_t = torch.arange(num_pos_feats,\n                             dtype=torch.float32,\n                             device=proposals.device)\n        dim_t = temperature**(2 * (dim_t // 2) / num_pos_feats)\n        # N, L, 4\n        proposals = proposals.sigmoid() * scale\n        # N, L, 4, 128\n        pos = proposals[:, :, :, None] / dim_t\n        # N, L, 4, 64, 2\n        pos = torch.stack((pos[:, :, :, 0::2].sin(), pos[:, :, :, 1::2].cos()),\n                          dim=4).flatten(2)\n        return pos\n\n    @force_fp32(apply_to=('mlvl_feats', 'query_embed', 'mlvl_pos_embeds'))\n    def forward(self,\n                mlvl_feats,\n                mlvl_masks,\n                query_embed,\n                mlvl_pos_embeds,\n                reg_branches=None,\n                cls_branches=None,\n                **kwargs):\n        \"\"\"Forward function for `Transformer`.\n\n        Args:\n            mlvl_feats (list(Tensor)): Input queries from\n                different level. Each element has shape\n                [bs, embed_dims, h, w].\n            mlvl_masks (list(Tensor)): The key_padding_mask from\n                different level used for encoder and decoder,\n                each element has shape  [bs, h, w].\n            query_embed (Tensor): The query embedding for decoder,\n                with shape [num_query, c].\n            mlvl_pos_embeds (list(Tensor)): The positional encoding\n                of feats from different level, has the shape\n                 [bs, embed_dims, h, w].\n            reg_branches (obj:`nn.ModuleList`): Regression heads for\n                feature maps from each decoder layer. Only would\n                be passed when\n                `with_box_refine` is True. Default to None.\n            cls_branches (obj:`nn.ModuleList`): Classification heads\n                for feature maps from each decoder layer. Only would\n                 be passed when `as_two_stage`\n                 is True. Default to None.\n\n\n        Returns:\n            tuple[Tensor]: results of decoder containing the following tensor.\n\n                - inter_states: Outputs from decoder. If\n                    return_intermediate_dec is True output has shape \\\n                      (num_dec_layers, bs, num_query, embed_dims), else has \\\n                      shape (1, bs, num_query, embed_dims).\n                - init_reference_out: The initial value of reference \\\n                    points, has shape (bs, num_queries, 4).\n                - inter_references_out: The internal value of reference \\\n                    points in decoder, has shape \\\n                    (num_dec_layers, bs,num_query, embed_dims)\n                - enc_outputs_class: The classification score of \\\n                    proposals generated from \\\n                    encoder's feature maps, has shape \\\n                    (batch, h*w, num_classes). \\\n                    Only would be returned when `as_two_stage` is True, \\\n                    otherwise None.\n                - enc_outputs_coord_unact: The regression results \\\n                    generated from encoder's feature maps., has shape \\\n                    (batch, h*w, 4). Only would \\\n                    be returned when `as_two_stage` is True, \\\n                    otherwise None.\n        \"\"\"\n\n        assert self.as_two_stage or query_embed is not None\n        feat_flatten = []\n        mask_flatten = []\n        lvl_pos_embed_flatten = []\n        spatial_shapes = []\n        for lvl, (feat, mask, pos_embed) in enumerate(\n                zip(mlvl_feats, mlvl_masks, mlvl_pos_embeds)):\n            bs, c, h, w = feat.shape\n            spatial_shape = (h, w)\n            spatial_shapes.append(spatial_shape)\n            feat = feat.flatten(2).transpose(1, 2)\n            mask = mask.flatten(1)\n            pos_embed = pos_embed.flatten(2).transpose(1, 2)\n            lvl_pos_embed = pos_embed + self.level_embeds[lvl].view(1, 1, -1)\n            lvl_pos_embed_flatten.append(lvl_pos_embed)\n            feat_flatten.append(feat)\n            mask_flatten.append(mask)\n        feat_flatten = torch.cat(feat_flatten, 1)\n        mask_flatten = torch.cat(mask_flatten, 1)\n        lvl_pos_embed_flatten = torch.cat(lvl_pos_embed_flatten, 1)\n        spatial_shapes = torch.as_tensor(spatial_shapes,\n                                         dtype=torch.long,\n                                         device=feat_flatten.device)\n        level_start_index = torch.cat((spatial_shapes.new_zeros(\n            (1, )), spatial_shapes.prod(1).cumsum(0)[:-1]))\n        valid_ratios = torch.stack(\n            [self.get_valid_ratio(m) for m in mlvl_masks], 1)\n\n        reference_points = \\\n            self.get_reference_points(spatial_shapes,\n                                      valid_ratios,\n                                      device=feat.device)\n\n        feat_flatten = feat_flatten.permute(1, 0, 2)  # (H*W, bs, embed_dims)\n        lvl_pos_embed_flatten = lvl_pos_embed_flatten.permute(\n            1, 0, 2)  # (H*W, bs, embed_dims)\n        memory = self.encoder(query=feat_flatten,\n                              key=None,\n                              value=None,\n                              query_pos=lvl_pos_embed_flatten,\n                              query_key_padding_mask=mask_flatten,\n                              spatial_shapes=spatial_shapes,\n                              reference_points=reference_points,\n                              level_start_index=level_start_index,\n                              valid_ratios=valid_ratios,\n                              **kwargs)\n\n        memory = memory.permute(1, 0, 2)\n        bs, _, c = memory.shape\n        if self.as_two_stage:\n            output_memory, output_proposals = \\\n                self.gen_encoder_output_proposals(\n                    memory, mask_flatten, spatial_shapes)\n            enc_outputs_class = cls_branches[self.decoder.num_layers](\n                output_memory)\n            enc_outputs_coord_unact = \\\n                reg_branches[\n                    self.decoder.num_layers](output_memory) + output_proposals\n\n            topk = self.two_stage_num_proposals\n            topk_proposals = torch.topk(enc_outputs_class[..., 0], topk,\n                                        dim=1)[1]\n            topk_coords_unact = torch.gather(\n                enc_outputs_coord_unact, 1,\n                topk_proposals.unsqueeze(-1).repeat(1, 1, 4))\n            topk_coords_unact = topk_coords_unact.detach()\n            reference_points = topk_coords_unact.sigmoid()\n            init_reference_out = reference_points\n            pos_trans_out = self.pos_trans_norm(\n                self.pos_trans(self.get_proposal_pos_embed(topk_coords_unact)))\n            query_pos, query = torch.split(pos_trans_out, c, dim=2)\n        else:\n            #print('query_embd',query_embed.shape, c)\n            # query_embed N *(2C)\n            query_pos, query = torch.split(query_embed, c, dim=1)\n            query_pos = query_pos.unsqueeze(0).expand(bs, -1, -1)\n            query = query.unsqueeze(0).expand(bs, -1, -1)\n            reference_points = self.reference_points(query_pos).sigmoid()\n            init_reference_out = reference_points\n\n        # decoder\n        query = query.permute(1, 0, 2)\n        memory = memory.permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        inter_states, inter_references = self.decoder(\n            query=query,\n            key=None,\n            value=memory,\n            query_pos=query_pos,\n            key_padding_mask=mask_flatten,\n            reference_points=reference_points,\n            spatial_shapes=spatial_shapes,\n            level_start_index=level_start_index,\n            valid_ratios=valid_ratios,\n            reg_branches=reg_branches,\n            **kwargs)\n        inter_references_out = inter_references\n        if self.as_two_stage:\n            return (memory,lvl_pos_embed_flatten,mask_flatten,query_pos), inter_states, init_reference_out,\\\n                inter_references_out, enc_outputs_class,\\\n                enc_outputs_coord_unact\n        return (memory,lvl_pos_embed_flatten,mask_flatten,query_pos), inter_states, init_reference_out, \\\n            inter_references_out, None, None"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/seg_head_plugin/seg_detr_head.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.bricks import Conv2d, Linear, build_activation_layer\nfrom mmcv.models.bricks.transformer import FFN, build_positional_encoding\nfrom mmcv.utils import force_fp32\n\nfrom mmcv.core.bbox.transforms import bbox_cxcywh_to_xyxy, bbox_xyxy_to_cxcywh\nfrom mmcv.core.bbox.builder import build_assigner, build_sampler\nfrom mmcv.core.utils import multi_apply, reduce_mean\nfrom mmcv.models.utils import build_transformer\n\nfrom mmcv.models.dense_heads.anchor_free_head import AnchorFreeHead\nfrom mmcv.models.builder import HEADS, build_loss\n\n\n@HEADS.register_module()\nclass SegDETRHead(\n        AnchorFreeHead\n):  # I modify DETRHead to make it to support panoptic segmentation\n    \"\"\"Implements the DETR transformer head.\n\n    See `paper: End-to-End Object Detection with Transformers\n    <https://arxiv.org/pdf/2005.12872>`_ for details.\n\n    Args:\n        num_classes (int): Number of categories excluding the background.\n        in_channels (int): Number of channels in the input feature map.\n        num_query (int): Number of query in Transformer.\n        num_reg_fcs (int, optional): Number of fully-connected layers used in\n            `FFN`, which is then used for the regression head. Default 2.\n        transformer (obj:`mmcv.ConfigDict`|dict): Config for transformer.\n            Default: None.\n        sync_cls_avg_factor (bool): Whether to sync the avg_factor of\n            all ranks. Default to False.\n        positional_encoding (obj:`mmcv.ConfigDict`|dict):\n            Config for position encoding.\n        loss_cls (obj:`mmcv.ConfigDict`|dict): Config of the\n            classification loss. Default `CrossEntropyLoss`.\n        loss_bbox (obj:`mmcv.ConfigDict`|dict): Config of the\n            regression loss. Default `L1Loss`.\n        loss_iou (obj:`mmcv.ConfigDict`|dict): Config of the\n            regression iou loss. Default `GIoULoss`.\n        tran_cfg (obj:`mmcv.ConfigDict`|dict): Training config of\n            transformer head.\n        test_cfg (obj:`mmcv.ConfigDict`|dict): Testing config of\n            transformer head.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n            Default: None\n    \"\"\"\n\n    _version = 2\n\n    def __init__(\n            self,\n            num_classes,\n            num_things_classes,\n            num_stuff_classes,\n            in_channels,\n            num_query=100,\n            num_reg_fcs=2,\n            transformer=None,\n            sync_cls_avg_factor=False,\n            positional_encoding=dict(type='SinePositionalEncoding',\n                                     num_feats=128,\n                                     normalize=True),\n            loss_cls=dict(type='CrossEntropyLoss',\n                          bg_cls_weight=0.1,\n                          use_sigmoid=False,\n                          loss_weight=1.0,\n                          class_weight=1.0),\n            loss_bbox=dict(type='L1Loss', loss_weight=5.0),\n            loss_iou=dict(type='GIoULoss', loss_weight=2.0),\n            train_cfg=dict(assigner=dict(\n                type='HungarianAssigner',\n                cls_cost=dict(type='ClassificationCost', weight=1.),\n                reg_cost=dict(type='BBoxL1Cost', weight=5.0),\n                iou_cost=dict(type='IoUCost', iou_mode='giou', weight=2.0))),\n            test_cfg=dict(max_per_img=100),\n            init_cfg=None,\n            **kwargs):\n        # NOTE here use `AnchorFreeHead` instead of `TransformerHead`,\n        # since it brings inconvenience when the initialization of\n        # `AnchorFreeHead` is called.\n        super(AnchorFreeHead, self).__init__(init_cfg)\n        self.bg_cls_weight = 0\n        self.sync_cls_avg_factor = sync_cls_avg_factor\n        class_weight = loss_cls.get('class_weight', None)\n        if class_weight is not None and (self.__class__ is SegDETRHead):\n            assert isinstance(class_weight, float), 'Expected ' \\\n                'class_weight to have type float. Found ' \\\n                f'{type(class_weight)}.'\n            # NOTE following the official DETR rep0, bg_cls_weight means\n            # relative classification weight of the no-object class.\n            bg_cls_weight = loss_cls.get('bg_cls_weight', class_weight)\n            assert isinstance(bg_cls_weight, float), 'Expected ' \\\n                'bg_cls_weight to have type float. Found ' \\\n                f'{type(bg_cls_weight)}.'\n            class_weight = torch.ones(num_things_classes + 1) * class_weight\n            # set background class as the last indice\n            class_weight[num_things_classes] = bg_cls_weight\n            loss_cls.update({'class_weight': class_weight})\n            if 'bg_cls_weight' in loss_cls:\n                loss_cls.pop('bg_cls_weight')\n            self.bg_cls_weight = bg_cls_weight\n\n        if train_cfg:\n            assert 'assigner' in train_cfg, 'assigner should be provided '\\\n                'when train_cfg is set.'\n            assigner = train_cfg['assigner']\n            # assert loss_cls['loss_weight'] == assigner['cls_cost']['weight'], \\\n            #     'The classification weight for loss and matcher should be' \\\n            #     'exactly the same.'\n            # assert loss_bbox['loss_weight'] == assigner['reg_cost'][\n            #     'weight'], 'The regression L1 weight for loss and matcher ' \\\n            #     'should be exactly the same.'\n            # assert loss_iou['loss_weight'] == assigner['iou_cost']['weight'], \\\n            #     'The regression iou weight for loss and matcher should be' \\\n            #     'exactly the same.'\n            self.assigner = build_assigner(assigner)\n            # DETR sampling=False, so use PseudoSampler\n            sampler_cfg = dict(type='PseudoSampler')\n            self.sampler = build_sampler(sampler_cfg, context=self)\n        self.num_query = num_query\n        self.num_classes = num_classes\n        self.num_things_classes = num_things_classes\n        self.num_stuff_classes = num_stuff_classes\n        self.in_channels = in_channels\n        self.num_reg_fcs = num_reg_fcs\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n        self.fp16_enabled = False\n        self.loss_cls = build_loss(loss_cls)\n        self.loss_bbox = build_loss(loss_bbox)\n        self.loss_iou = build_loss(loss_iou)\n\n        if self.loss_cls.use_sigmoid:\n            self.cls_out_channels = num_things_classes\n        else:\n            self.cls_out_channels = num_things_classes + 1\n        self.act_cfg = transformer.get('act_cfg',\n                                       dict(type='ReLU', inplace=True))\n        self.activate = build_activation_layer(self.act_cfg)\n        self.positional_encoding = build_positional_encoding(\n            positional_encoding)\n        self.transformer = build_transformer(transformer)\n        self.embed_dims = self.transformer.embed_dims\n        assert 'num_feats' in positional_encoding\n        num_feats = positional_encoding['num_feats']\n        assert num_feats * 2 == self.embed_dims, 'embed_dims should' \\\n            f' be exactly 2 times of num_feats. Found {self.embed_dims}' \\\n            f' and {num_feats}.'\n        self._init_layers()\n\n    def _init_layers(self):\n        \"\"\"Initialize layers of the transformer head.\"\"\"\n        self.input_proj = Conv2d(self.in_channels,\n                                 self.embed_dims,\n                                 kernel_size=1)\n        self.fc_cls = Linear(self.embed_dims, self.cls_out_channels)\n        self.reg_ffn = FFN(self.embed_dims,\n                           self.embed_dims,\n                           self.num_reg_fcs,\n                           self.act_cfg,\n                           dropout=0.0,\n                           add_residual=False)\n        self.fc_reg = Linear(self.embed_dims, 4)\n        self.query_embedding = nn.Embedding(self.num_query, self.embed_dims)\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the transformer head.\"\"\"\n        # The initialization for transformer is important\n        self.transformer.init_weights()\n\n    def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,\n                              missing_keys, unexpected_keys, error_msgs):\n        \"\"\"load checkpoints.\"\"\"\n        # NOTE here use `AnchorFreeHead` instead of `TransformerHead`,\n        # since `AnchorFreeHead._load_from_state_dict` should not be\n        # called here. Invoking the default `Module._load_from_state_dict`\n        # is enough.\n\n        # Names of some parameters in has been changed.\n        version = local_metadata.get('version', None)\n        if (version is None or version < 2) and self.__class__ is SegDETRHead:\n            convert_dict = {\n                '.self_attn.': '.attentions.0.',\n                '.ffn.': '.ffns.0.',\n                '.multihead_attn.': '.attentions.1.',\n                '.decoder.norm.': '.decoder.post_norm.'\n            }\n            for k in state_dict.keys():\n                for ori_key, convert_key in convert_dict.items():\n                    if ori_key in k:\n                        convert_key = k.replace(ori_key, convert_key)\n                        state_dict[convert_key] = state_dict[k]\n                        del state_dict[k]\n\n        super(AnchorFreeHead,\n              self)._load_from_state_dict(state_dict, prefix, local_metadata,\n                                          strict, missing_keys,\n                                          unexpected_keys, error_msgs)\n\n    def forward(self, feats, img_metas):\n        \"\"\"Forward function.\n\n        Args:\n            feats (tuple[Tensor]): Features from the upstream network, each is\n                a 4D-tensor.\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            tuple[list[Tensor], list[Tensor]]: Outputs for all scale levels.\n\n                - all_cls_scores_list (list[Tensor]): Classification scores \\\n                    for each scale level. Each is a 4D-tensor with shape \\\n                    [nb_dec, bs, num_query, cls_out_channels]. Note \\\n                    `cls_out_channels` should includes background.\n                - all_bbox_preds_list (list[Tensor]): Sigmoid regression \\\n                    outputs for each scale level. Each is a 4D-tensor with \\\n                    normalized coordinate format (cx, cy, w, h) and shape \\\n                    [nb_dec, bs, num_query, 4].\n        \"\"\"\n        num_levels = len(feats)\n        img_metas_list = [img_metas for _ in range(num_levels)]\n        return multi_apply(self.forward_single, feats, img_metas_list)\n\n    def forward_single(self, x, img_metas):\n        \"\"\"\"Forward function for a single feature level.\n\n        Args:\n            x (Tensor): Input feature from backbone's single stage, shape\n                [bs, c, h, w].\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            all_cls_scores (Tensor): Outputs from the classification head,\n                shape [nb_dec, bs, num_query, cls_out_channels]. Note\n                cls_out_channels should includes background.\n            all_bbox_preds (Tensor): Sigmoid outputs from the regression\n                head with normalized coordinate format (cx, cy, w, h).\n                Shape [nb_dec, bs, num_query, 4].\n        \"\"\"\n        # construct binary masks which used for the transformer.\n        # NOTE following the official DETR repo, non-zero values representing\n        # ignored positions, while zero values means valid positions.\n        batch_size = x.size(0)\n        input_img_h, input_img_w = img_metas[0]['batch_input_shape']\n        masks = x.new_ones((batch_size, input_img_h, input_img_w))\n        for img_id in range(batch_size):\n            img_h, img_w, _ = img_metas[img_id]['img_shape']\n            masks[img_id, :img_h, :img_w] = 0\n\n        x = self.input_proj(x)\n        # interpolate masks to have the same spatial shape with x\n        masks = F.interpolate(masks.unsqueeze(1),\n                              size=x.shape[-2:]).to(torch.bool).squeeze(1)\n        # position encoding\n        pos_embed = self.positional_encoding(masks)  # [bs, embed_dim, h, w]\n        # outs_dec: [nb_dec, bs, num_query, embed_dim]\n        outs_dec, _ = self.transformer(x, masks, self.query_embedding.weight,\n                                       pos_embed)\n\n        all_cls_scores = self.fc_cls(outs_dec)\n        all_bbox_preds = self.fc_reg(self.activate(\n            self.reg_ffn(outs_dec))).sigmoid()\n        return all_cls_scores, all_bbox_preds\n\n    @force_fp32(apply_to=('all_cls_scores_list', 'all_bbox_preds_list'))\n    def loss(self,\n             all_cls_scores_list,\n             all_bbox_preds_list,\n             gt_bboxes_list,\n             gt_labels_list,\n             img_metas,\n             gt_bboxes_ignore=None):\n        \"\"\"\"Loss function.\n\n        Only outputs from the last feature level are used for computing\n        losses by default.\n\n        Args:\n            all_cls_scores_list (list[Tensor]): Classification outputs\n                for each feature level. Each is a 4D-tensor with shape\n                [nb_dec, bs, num_query, cls_out_channels].\n            all_bbox_preds_list (list[Tensor]): Sigmoid regression\n                outputs for each feature level. Each is a 4D-tensor with\n                normalized coordinate format (cx, cy, w, h) and shape\n                [nb_dec, bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        # NOTE defaultly only the outputs from the last feature scale is used.\n        all_cls_scores = all_cls_scores_list[-1]\n        all_bbox_preds = all_bbox_preds_list[-1]\n        assert gt_bboxes_ignore is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n\n        num_dec_layers = len(all_cls_scores)\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n        img_metas_list = [img_metas for _ in range(num_dec_layers)]\n\n        losses_cls, losses_bbox, losses_iou = multi_apply(\n            self.loss_single, all_cls_scores, all_bbox_preds,\n            all_gt_bboxes_list, all_gt_labels_list, img_metas_list,\n            all_gt_bboxes_ignore_list)\n\n        loss_dict = dict()\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls[-1]\n        loss_dict['loss_bbox'] = losses_bbox[-1]\n        loss_dict['loss_iou'] = losses_iou[-1]\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_cls_i, loss_bbox_i, loss_iou_i in zip(losses_cls[:-1],\n                                                       losses_bbox[:-1],\n                                                       losses_iou[:-1]):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i\n            loss_dict[f'd{num_dec_layer}.loss_iou'] = loss_iou_i\n            num_dec_layer += 1\n        return loss_dict\n\n    def loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    img_metas,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,\n                                           gt_bboxes_list, gt_labels_list,\n                                           img_metas, gt_bboxes_ignore_list)\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_cls(cls_scores,\n                                 labels,\n                                 label_weights,\n                                 avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # construct factors used for rescale bboxes\n        factors = []\n        for img_meta, bbox_pred in zip(img_metas, bbox_preds):\n            img_h, img_w, _ = img_meta['img_shape']\n            factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                           img_h]).unsqueeze(0).repeat(\n                                               bbox_pred.size(0), 1)\n            factors.append(factor)\n        factors = torch.cat(factors, 0)\n\n        # DETR regress the relative position of boxes (cxcywh) in the image,\n        # thus the learning target is normalized by the image size. So here\n        # we need to re-scale them for calculating IoU loss\n        bbox_preds = bbox_preds.reshape(-1, 4)\n        bboxes = bbox_cxcywh_to_xyxy(bbox_preds) * factors\n        bboxes_gt = bbox_cxcywh_to_xyxy(bbox_targets) * factors\n\n        # regression IoU loss, defaultly GIoU loss\n        loss_iou = self.loss_iou(bboxes,\n                                 bboxes_gt,\n                                 bbox_weights,\n                                 avg_factor=num_total_pos)\n\n        # regression L1 loss\n        loss_bbox = self.loss_bbox(bbox_preds,\n                                   bbox_targets,\n                                   bbox_weights,\n                                   avg_factor=num_total_pos)\n        return loss_cls, loss_bbox, loss_iou\n\n    def get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    img_metas,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n\n        Outputs from a single decoder layer of a single feature level are used.\n\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            img_metas (list[dict]): List of image meta information.\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n\n        Returns:\n            tuple: a tuple containing the following targets.\n\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, pos_inds_list, neg_inds_list) = multi_apply(\n             self._get_target_single, cls_scores_list, bbox_preds_list,\n             gt_bboxes_list, gt_labels_list, img_metas, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, num_total_pos, num_total_neg)\n\n    def _get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           gt_bboxes,\n                           gt_labels,\n                           img_meta,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n\n        Outputs from a single decoder layer of a single feature level are used.\n\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            img_meta (dict): Meta information for one image.\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,\n                                            gt_labels, img_meta,\n                                            gt_bboxes_ignore)\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes, ),\n                                    self.num_things_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n        img_h, img_w, _ = img_meta['img_shape']\n\n        # DETR regress the relative position of boxes (cxcywh) in the image.\n        # Thus the learning target should be normalized by the image size, also\n        # the box format should be converted from defaultly x1y1x2y2 to cxcywh.\n        factor = bbox_pred.new_tensor([img_w, img_h, img_w,\n                                       img_h]).unsqueeze(0)\n        pos_gt_bboxes_normalized = sampling_result.pos_gt_bboxes / factor\n        pos_gt_bboxes_targets = bbox_xyxy_to_cxcywh(pos_gt_bboxes_normalized)\n        bbox_targets[pos_inds] = pos_gt_bboxes_targets\n        return (labels, label_weights, bbox_targets, bbox_weights, pos_inds,\n                neg_inds)\n\n    # over-write because img_metas are needed as inputs for bbox_head.\n    def forward_train(self,\n                      x,\n                      img_metas,\n                      gt_bboxes,\n                      gt_labels=None,\n                      gt_bboxes_ignore=None,\n                      proposal_cfg=None,\n                      **kwargs):\n        \"\"\"Forward function for training mode.\n\n        Args:\n            x (list[Tensor]): Features from backbone.\n            img_metas (list[dict]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n            gt_bboxes (Tensor): Ground truth bboxes of the image,\n                shape (num_gts, 4).\n            gt_labels (Tensor): Ground truth labels of each box,\n                shape (num_gts,).\n            gt_bboxes_ignore (Tensor): Ground truth bboxes to be\n                ignored, shape (num_ignored_gts, 4).\n            proposal_cfg (mmcv.Config): Test / postprocessing configuration,\n                if None, test_cfg would be used.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert proposal_cfg is None, '\"proposal_cfg\" must be None'\n        outs = self(x, img_metas)\n        if gt_labels is None:\n            loss_inputs = outs + (gt_bboxes, img_metas)\n        else:\n            loss_inputs = outs + (gt_bboxes, gt_labels, img_metas)\n        losses = self.loss(*loss_inputs, gt_bboxes_ignore=gt_bboxes_ignore)\n        return losses\n\n    @force_fp32(apply_to=('all_cls_scores_list', 'all_bbox_preds_list'))\n    def get_bboxes(self,\n                   all_cls_scores_list,\n                   all_bbox_preds_list,\n                   img_metas,\n                   rescale=False):\n        \"\"\"Transform network outputs for a batch into bbox predictions.\n\n        Args:\n            all_cls_scores_list (list[Tensor]): Classification outputs\n                for each feature level. Each is a 4D-tensor with shape\n                [nb_dec, bs, num_query, cls_out_channels].\n            all_bbox_preds_list (list[Tensor]): Sigmoid regression\n                outputs for each feature level. Each is a 4D-tensor with\n                normalized coordinate format (cx, cy, w, h) and shape\n                [nb_dec, bs, num_query, 4].\n            img_metas (list[dict]): Meta information of each image.\n            rescale (bool, optional): If True, return boxes in original\n                image space. Default False.\n\n        Returns:\n            list[list[Tensor, Tensor]]: Each item in result_list is 2-tuple. \\\n                The first item is an (n, 5) tensor, where the first 4 columns \\\n                are bounding box positions (tl_x, tl_y, br_x, br_y) and the \\\n                5-th column is a score between 0 and 1. The second item is a \\\n                (n,) tensor where each item is the predicted class label of \\\n                the corresponding box.\n        \"\"\"\n        # NOTE defaultly only using outputs from the last feature level,\n        # and only the outputs from the last decoder layer is used.\n        cls_scores = all_cls_scores_list[-1][-1]\n        bbox_preds = all_bbox_preds_list[-1][-1]\n\n        result_list = []\n        for img_id in range(len(img_metas)):\n            cls_score = cls_scores[img_id]\n            bbox_pred = bbox_preds[img_id]\n            img_shape = img_metas[img_id]['img_shape']\n            scale_factor = img_metas[img_id]['scale_factor']\n            proposals = self._get_bboxes_single(cls_score, bbox_pred,\n                                                img_shape, scale_factor,\n                                                rescale)\n            result_list.append(proposals)\n\n        return result_list\n\n    def _get_bboxes_single(self,\n                           cls_score,\n                           bbox_pred,\n                           img_shape,\n                           scale_factor,\n                           rescale=False):\n        \"\"\"Transform outputs from the last decoder layer into bbox predictions\n        for each image.\n\n        Args:\n            cls_score (Tensor): Box score logits from the last decoder layer\n                for each image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from the last decoder layer\n                for each image, with coordinate format (cx, cy, w, h) and\n                shape [num_query, 4].\n            img_shape (tuple[int]): Shape of input image, (height, width, 3).\n            scale_factor (ndarray, optional): Scale factor of the image arange\n                as (w_scale, h_scale, w_scale, h_scale).\n            rescale (bool, optional): If True, return boxes in original image\n                space. Default False.\n\n        Returns:\n            tuple[Tensor]: Results of detected bboxes and labels.\n\n                - det_bboxes: Predicted bboxes with shape [num_query, 5], \\\n                    where the first 4 columns are bounding box positions \\\n                    (tl_x, tl_y, br_x, br_y) and the 5-th column are scores \\\n                    between 0 and 1.\n                - det_labels: Predicted labels of the corresponding box with \\\n                    shape [num_query].\n        \"\"\"\n        assert len(cls_score) == len(bbox_pred)\n        max_per_img = self.test_cfg.get('max_per_img', self.num_query)\n        # exclude background\n        if self.loss_cls.use_sigmoid:\n            cls_score = cls_score.sigmoid()\n            scores, indexes = cls_score.view(-1).topk(max_per_img)\n            det_labels = indexes % self.num_things_classes\n            bbox_index = indexes // self.num_things_classes\n            bbox_pred = bbox_pred[bbox_index]\n        else:\n            scores, det_labels = F.softmax(cls_score, dim=-1)[..., :-1].max(-1)\n            scores, bbox_index = scores.topk(max_per_img)\n            bbox_pred = bbox_pred[bbox_index]\n            det_labels = det_labels[bbox_index]\n\n        det_bboxes = bbox_cxcywh_to_xyxy(bbox_pred)\n        det_bboxes[:, 0::2] = det_bboxes[:, 0::2] * img_shape[1]\n        det_bboxes[:, 1::2] = det_bboxes[:, 1::2] * img_shape[0]\n        det_bboxes[:, 0::2].clamp_(min=0, max=img_shape[1])\n        det_bboxes[:, 1::2].clamp_(min=0, max=img_shape[0])\n        if rescale:\n            det_bboxes /= det_bboxes.new_tensor(scale_factor)\n        det_bboxes = torch.cat((det_bboxes, scores.unsqueeze(1)), -1)\n\n        return det_bboxes, det_labels\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/seg_head_plugin/seg_mask_head.py",
    "content": "\"\"\"\nCopy-paste from torch.nn.Transformer, timm, with modifications:\n\"\"\"\nimport copy\nfrom typing import Optional, List\n\nimport torch\nimport torch.nn.functional as F\nfrom torch import nn, Tensor\nfrom functools import partial\nfrom mmcv.models.utils.builder import TRANSFORMER\nimport math\nfrom mmcv.utils import force_fp32\n\ncount = 0\n\n\nclass Mlp(nn.Module):\n    def __init__(self,\n                 in_features,\n                 hidden_features=None,\n                 out_features=None,\n                 act_layer=nn.GELU,\n                 drop=0.):\n        super().__init__()\n        self.fp16_enabled = False\n        out_features = out_features or in_features\n        hidden_features = hidden_features or in_features\n        self.fc1 = nn.Linear(in_features, hidden_features)\n\n        self.act = act_layer()\n        self.fc2 = nn.Linear(hidden_features, out_features)\n        self.drop = nn.Dropout(drop)\n\n    @force_fp32(apply_to=('x', ))\n    def forward(self, x):\n        x = self.fc1(x)\n        x = self.act(x)\n        x = self.drop(x)\n        x = self.fc2(x)\n        x = self.drop(x)\n        return x\n\n\nclass SelfAttention(nn.Module):\n    def __init__(self,\n                 cfg,\n                 dim,\n                 num_heads=2,\n                 qkv_bias=False,\n                 qk_scale=None,\n                 attn_drop=0.,\n                 proj_drop=0.):\n        super().__init__()\n        self.num_heads = num_heads\n        head_dim = dim // num_heads\n        self.fp16_enabled = False\n        self.scale = qk_scale or head_dim**-0.5\n\n        self.qkv = nn.Linear(dim, dim * 3, bias=qkv_bias)\n        self.attn_drop = nn.Dropout(attn_drop)\n        self.proj = nn.Linear(dim, dim)\n        self.proj_drop = nn.Dropout(proj_drop)\n\n    @force_fp32(apply_to=('x', ))\n    def forward(self, x):\n        B, N, C = x.shape\n\n        qkv = self.qkv(x).reshape(B, N, 3, self.num_heads,\n                                  C // self.num_heads).permute(2, 0, 3, 1,\n                                                               4).contiguous()\n        q, k, v = qkv[0], qkv[1], qkv[\n            2]  # make torchscript happy (cannot use tensor as tuple)\n\n        attn = (q @ k.transpose(-2, -1)) * self.scale\n\n        attn = attn.softmax(dim=-1)\n        attn = self.attn_drop(attn)\n        x = (attn @ v).transpose(1, 2).reshape(B, N, C)\n        x = self.proj(x)\n        x = self.proj_drop(x)\n\n        return x\n\n\nclass Attention(nn.Module):\n    def __init__(self,\n                 cfg,\n                 dim,\n                 num_heads=2,\n                 qkv_bias=False,\n                 qk_scale=None,\n                 attn_drop=0.,\n                 proj_drop=0.):\n        super().__init__()\n        self.fp16_enabled = False\n        self.num_heads = num_heads\n        head_dim = dim // num_heads\n        self.scale = qk_scale or head_dim**-0.5\n        self.q = nn.Linear(dim, dim, bias=qkv_bias)\n        self.k = nn.Linear(dim, dim, bias=qkv_bias)\n        self.v = nn.Linear(dim, dim, bias=qkv_bias)\n        self.attn_drop = nn.Dropout(attn_drop)\n        self.proj = nn.Linear(dim, dim)\n        self.proj_drop = nn.Dropout(proj_drop)\n        self.linear_l1 = nn.Sequential(\n            nn.Linear(self.num_heads, self.num_heads),\n            nn.ReLU(),\n        )\n        self.linear = nn.Sequential(\n            nn.Linear(self.num_heads, 1),\n            nn.ReLU(),\n        )\n        self._reset_parameters()\n\n    def _reset_parameters(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n\n    @force_fp32(apply_to=('query', 'key', 'value'))\n    def forward(self, query, key, value, key_padding_mask, hw_lvl):\n        B, N, C = query.shape\n        _, L, _ = key.shape\n        #print('query, key, value', query.shape, value.shape, key.shape)\n        q = self.q(query).reshape(B, N,\n                                  self.num_heads, C // self.num_heads).permute(\n                                      0, 2, 1,\n                                      3).contiguous()  #.permute(2, 0, 3, 1, 4)\n        k = self.k(key).reshape(B, L,\n                                self.num_heads, C // self.num_heads).permute(\n                                    0, 2, 1,\n                                    3).contiguous()  #.permute(2, 0, 3, 1, 4)\n\n        v = self.v(value).reshape(B, L,\n                                  self.num_heads, C // self.num_heads).permute(\n                                      0, 2, 1,\n                                      3).contiguous()  #.permute(2, 0, 3, 1, 4)\n\n        attn = (q @ k.transpose(-2, -1).contiguous()) * self.scale\n\n        attn = attn.permute(0, 2, 3, 1)\n\n        new_feats = self.linear_l1(attn)\n        mask = self.linear(new_feats)\n\n        attn = attn.permute(0, 3, 1, 2)\n        attn = attn.softmax(dim=-1)\n        attn = self.attn_drop(attn)\n\n        x = (attn @ v).transpose(1, 2).contiguous().reshape(B, N, C)\n        x = self.proj(x)\n        x = self.proj_drop(x)\n\n        return x, mask\n\n# AttentionTail is a cheap implementation that can make mask decoder 1 layer deeper.\nclass AttentionTail(nn.Module): \n    def __init__(self,\n                 cfg,\n                 dim,\n                 num_heads=2,\n                 qkv_bias=False,\n                 qk_scale=None,\n                 attn_drop=0.,\n                 proj_drop=0.):\n        super().__init__()\n        self.fp16_enabled = False\n        self.num_heads = num_heads\n        head_dim = dim // num_heads\n        self.scale = qk_scale or head_dim**-0.5\n        self.q = nn.Linear(dim, dim, bias=qkv_bias)\n        self.k = nn.Linear(dim, dim, bias=qkv_bias)\n\n        self.linear_l1 = nn.Sequential(\n            nn.Linear(self.num_heads, self.num_heads),\n            nn.ReLU(),\n        )\n        \n        self.linear = nn.Sequential(\n            nn.Linear(self.num_heads, 1),\n            nn.ReLU(),\n        )\n        self._reset_parameters()\n\n    def _reset_parameters(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n\n    @force_fp32(apply_to=('query', 'key'))\n    def forward(self, query, key, key_padding_mask, hw_lvl=None):\n        B, N, C = query.shape\n        _, L, _ = key.shape\n        #print('query, key, value', query.shape, value.shape, key.shape)\n        q = self.q(query).reshape(B, N,\n                                  self.num_heads, C // self.num_heads).permute(\n                                      0, 2, 1,\n                                      3).contiguous()  #.permute(2, 0, 3, 1, 4)\n        k = self.k(key).reshape(B, L,\n                                self.num_heads, C // self.num_heads).permute(\n                                    0, 2, 1,\n                                    3).contiguous()  #.permute(2, 0, 3, 1, 4)\n        attn = (q @ k.transpose(-2, -1).contiguous()) * self.scale\n\n        attn = attn.permute(0, 2, 3, 1)\n        \n        new_feats = self.linear_l1(attn)\n        mask = self.linear(new_feats)\n\n        return mask\n\n\nclass Block(nn.Module):\n    def __init__(self,\n                 cfg,\n                 dim,\n                 num_heads,\n                 mlp_ratio=4.,\n                 qkv_bias=False,\n                 qk_scale=None,\n                 drop=0.,\n                 attn_drop=0.,\n                 drop_path=0.,\n                 act_layer=nn.GELU,\n                 norm_layer=nn.LayerNorm,\n                 self_attn=False):\n        super().__init__()\n        self.fp16_enabled = False\n        self.head_norm1 = norm_layer(dim)\n        self.self_attn = self_attn\n        self.attn = Attention(cfg,\n                              dim,\n                              num_heads=num_heads,\n                              qkv_bias=qkv_bias,\n                              qk_scale=qk_scale,\n                              attn_drop=attn_drop,\n                              proj_drop=drop)\n        # NOTE: drop path for stochastic depth, we shall see if this is better than dropout here\n\n        self.drop_path = DropPath(\n            drop_path) if drop_path > 0. else nn.Identity()\n        self.head_norm2 = norm_layer(dim)\n        mlp_hidden_dim = int(dim * mlp_ratio)\n        self.mlp = Mlp(in_features=dim,\n                       hidden_features=mlp_hidden_dim,\n                       act_layer=act_layer,\n                       drop=drop)\n        if self.self_attn:\n            self.self_attention = SelfAttention(cfg,\n                                                dim,\n                                                num_heads=num_heads,\n                                                qkv_bias=qkv_bias,\n                                                qk_scale=qk_scale,\n                                                attn_drop=attn_drop,\n                                                proj_drop=drop)\n            self.norm3 = norm_layer(dim)\n\n    @force_fp32(apply_to=('query', 'key', 'value'))\n    def forward(self, query, key, value, key_padding_mask=None, hw_lvl=None):\n        if self.self_attn:\n            query = query + self.drop_path(self.self_attention(query))\n            query = self.norm3(query)\n        x, mask = self.attn(query, key, value, key_padding_mask, hw_lvl=hw_lvl)\n        query = query + self.drop_path(x)\n        query = self.head_norm1(query)\n\n        query = query + self.drop_path(self.mlp(query))\n        query = self.head_norm2(query)\n        return query, mask\n\n\ndef drop_path(x, drop_prob: float = 0., training: bool = False):\n    \"\"\"Drop paths (Stochastic Depth) per sample (when applied in main path of residual blocks).\n    This is the same as the DropConnect impl I created for EfficientNet, etc networks, however,\n    the original name is misleading as 'Drop Connect' is a different form of dropout in a separate paper...\n    See discussion: https://github.com/tensorflow/tpu/issues/494#issuecomment-53296self.num_heads956 ... I've opted for\n    changing the layer and argument names to 'drop path' rather than mix DropConnect as a layer name and use\n    'survival rate' as the argument.\n    \"\"\"\n    if drop_prob == 0. or not training:\n        return x\n    keep_prob = 1 - drop_prob\n    shape = (x.shape[0], ) + (1, ) * (\n        x.ndim - 1)  # work with diff dim tensors, not just 2D ConvNets\n    random_tensor = keep_prob + torch.rand(\n        shape, dtype=x.dtype, device=x.device)\n    random_tensor.floor_()  # binarize\n    output = x.div(keep_prob) * random_tensor\n    return output\n\n\ndef _get_clones(module, N):\n    return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n\nclass DropPath(nn.Module):\n    \"\"\"Drop paths (Stochastic Depth) per sample  (when applied in main path of residual blocks).\n    \"\"\"\n    def __init__(self, drop_prob=None):\n        super(DropPath, self).__init__()\n        self.drop_prob = drop_prob\n\n    @force_fp32(apply_to=('x', ))\n    def forward(self, x):\n        return drop_path(x, self.drop_prob, self.training)\n\n\n@TRANSFORMER.register_module()\nclass SegMaskHead(nn.Module):\n    def __init__(self,\n                 cfg=None,\n                 d_model=16,\n                 nhead=2,\n                 num_encoder_layers=6,\n                 num_decoder_layers=1,\n                 dim_feedforward=64,\n                 dropout=0.1,\n                 activation=\"relu\",\n                 normalize_before=False,\n                 return_intermediate_dec=False,\n                 self_attn=False):\n        super().__init__()\n\n        self.fp16_enabled = False\n        mlp_ratio = 4\n        qkv_bias = True\n        qk_scale = None\n        drop_rate = 0\n        attn_drop_rate = 0\n\n        norm_layer = None\n        norm_layer = norm_layer or partial(nn.LayerNorm, eps=1e-6)\n        act_layer = None\n        act_layer = act_layer or nn.GELU\n        block = Block(cfg,\n                      dim=d_model,\n                      num_heads=nhead,\n                      mlp_ratio=mlp_ratio,\n                      qkv_bias=qkv_bias,\n                      qk_scale=qk_scale,\n                      drop=drop_rate,\n                      attn_drop=attn_drop_rate,\n                      drop_path=0,\n                      norm_layer=norm_layer,\n                      act_layer=act_layer,\n                      self_attn=self_attn)\n        self.blocks = _get_clones(block, num_decoder_layers)\n        self.attnen = AttentionTail(cfg,\n                                    d_model,\n                                    num_heads=nhead,\n                                    qkv_bias=qkv_bias,\n                                    qk_scale=qk_scale,\n                                    attn_drop=attn_drop_rate,\n                                    proj_drop=0)\n\n        self._reset_parameters()\n\n    def _reset_parameters(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n\n    def with_pos_embed(self, tensor, pos: Optional[Tensor]):\n        if pos is None:\n            return tensor\n        else:\n            return tensor + pos\n        #return tensor if pos is None else tensor + pos\n    @force_fp32(apply_to=('memory', 'mask_memory', 'pos_memory', 'query_embed',\n                          'mask_query', 'pos_query'))\n    def forward(self, memory, mask_memory, pos_memory, query_embed, mask_query,\n                pos_query, hw_lvl):\n        if mask_memory is not None and isinstance(mask_memory, torch.Tensor):\n            mask_memory = mask_memory.to(torch.bool)\n        masks = []\n        inter_query = []\n        for i, block in enumerate(self.blocks):\n            query_embed, mask = block(self.with_pos_embed(\n                query_embed, pos_query),\n                                      self.with_pos_embed(memory, pos_memory),\n                                      memory,\n                                      key_padding_mask=mask_memory,\n                                      hw_lvl=hw_lvl)\n            masks.append(mask)\n            inter_query.append(query_embed)\n            #if i == 1:\n            #    return mask, masks, inter_query\n        attn = self.attnen(self.with_pos_embed(query_embed, pos_query),\n                           self.with_pos_embed(memory, pos_memory),\n                           key_padding_mask=mask_memory,\n                           hw_lvl=hw_lvl)\n        return attn, masks, inter_query\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/seg_head_plugin/seg_utils.py",
    "content": "\n\ndef IOU(intputs, targets):\n    numerator = (intputs * targets).sum(dim=1)\n    denominator = intputs.sum(dim=1) + targets.sum(dim=1) - numerator\n    loss = numerator / (denominator + 0.0000000000001)\n    return loss.cpu(), numerator.cpu(), denominator.cpu()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/track_head.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n# Modified from bevformer (https://github.com/fundamentalvision/BEVFormer)        #\n#---------------------------------------------------------------------------------#\n\nimport copy\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.bricks import Linear\nfrom mmcv.models.utils import bias_init_with_prob\nfrom mmcv.utils import TORCH_VERSION, digit_version\n\nfrom mmcv.core.utils import (multi_apply, reduce_mean)\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom mmcv.models import HEADS\nfrom mmcv.models.dense_heads import DETRHead\nfrom mmcv.core.bbox.coder import build_bbox_coder\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.utils import force_fp32, auto_fp16\n\n\n@HEADS.register_module()\nclass BEVFormerTrackHead(DETRHead):\n    \"\"\"Head of Detr3D.\n    Args:\n        with_box_refine (bool): Whether to refine the reference points\n            in the decoder. Defaults to False.\n        as_two_stage (bool) : Whether to generate the proposal from\n            the outputs of encoder.\n        transformer (obj:`ConfigDict`): ConfigDict is used for building\n            the Encoder and Decoder.\n        bev_h, bev_w (int): spatial shape of BEV queries.\n    \"\"\"\n\n    def __init__(self,\n                 *args,\n                 with_box_refine=False,\n                 as_two_stage=False,\n                 transformer=None,\n                 bbox_coder=None,\n                 num_cls_fcs=2,\n                 code_weights=None,\n                 bev_h=30,\n                 bev_w=30,\n                 past_steps=4,\n                 fut_steps=4,\n                 **kwargs):\n\n        self.bev_h = bev_h\n        self.bev_w = bev_w\n        self.fp16_enabled = False\n\n        self.with_box_refine = with_box_refine\n\n        assert as_two_stage is False, 'as_two_stage is not supported yet.'\n        self.as_two_stage = as_two_stage\n        if self.as_two_stage:\n            transformer['as_two_stage'] = self.as_two_stage\n        if 'code_size' in kwargs:\n            self.code_size = kwargs['code_size']\n        else:\n            self.code_size = 10\n        if code_weights is not None:\n            self.code_weights = code_weights\n        else:\n            self.code_weights = [1.0, 1.0, 1.0,\n                                 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]\n\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n        self.pc_range = self.bbox_coder.pc_range\n        self.real_w = self.pc_range[3] - self.pc_range[0]\n        self.real_h = self.pc_range[4] - self.pc_range[1]\n        self.num_cls_fcs = num_cls_fcs - 1\n        self.past_steps = past_steps\n        self.fut_steps = fut_steps\n        super(BEVFormerTrackHead, self).__init__(\n            *args, transformer=transformer, **kwargs)\n        self.code_weights = nn.Parameter(torch.tensor(\n            self.code_weights, requires_grad=False), requires_grad=False)\n\n    def _init_layers(self):\n        \"\"\"Initialize classification branch and regression branch of head.\"\"\"\n        cls_branch = []\n        for _ in range(self.num_reg_fcs):\n            cls_branch.append(Linear(self.embed_dims, self.embed_dims))\n            cls_branch.append(nn.LayerNorm(self.embed_dims))\n            cls_branch.append(nn.ReLU(inplace=True))\n        cls_branch.append(Linear(self.embed_dims, self.cls_out_channels))\n        fc_cls = nn.Sequential(*cls_branch)\n\n        reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            reg_branch.append(Linear(self.embed_dims, self.embed_dims))\n            reg_branch.append(nn.ReLU())\n        reg_branch.append(Linear(self.embed_dims, self.code_size))\n        reg_branch = nn.Sequential(*reg_branch)\n\n        past_traj_reg_branch = []\n        for _ in range(self.num_reg_fcs):\n            past_traj_reg_branch.append(\n                Linear(self.embed_dims, self.embed_dims))\n            past_traj_reg_branch.append(nn.ReLU())\n        past_traj_reg_branch.append(\n            Linear(self.embed_dims, (self.past_steps + self.fut_steps)*2))\n        past_traj_reg_branch = nn.Sequential(*past_traj_reg_branch)\n\n        def _get_clones(module, N):\n            return nn.ModuleList([copy.deepcopy(module) for i in range(N)])\n\n        # last reg_branch is used to generate proposal from\n        # encode feature map when as_two_stage is True.\n        num_pred = (self.transformer.decoder.num_layers + 1) if \\\n            self.as_two_stage else self.transformer.decoder.num_layers\n\n        if self.with_box_refine:\n            self.cls_branches = _get_clones(fc_cls, num_pred)\n            self.reg_branches = _get_clones(reg_branch, num_pred)\n            self.past_traj_reg_branches = _get_clones(\n                past_traj_reg_branch, num_pred)\n        else:\n            self.cls_branches = nn.ModuleList(\n                [fc_cls for _ in range(num_pred)])\n            self.reg_branches = nn.ModuleList(\n                [reg_branch for _ in range(num_pred)])\n            self.past_traj_reg_branches = nn.ModuleList(\n                [past_traj_reg_branch for _ in range(num_pred)])\n        if not self.as_two_stage:\n            self.bev_embedding = nn.Embedding(\n                self.bev_h * self.bev_w, self.embed_dims)\n\n    def init_weights(self):\n        \"\"\"Initialize weights of the DeformDETR head.\"\"\"\n        self.transformer.init_weights()\n        if self.loss_cls.use_sigmoid:\n            bias_init = bias_init_with_prob(0.01)\n            for m in self.cls_branches:\n                nn.init.constant_(m[-1].bias, bias_init)\n    \n    def get_bev_features(self, mlvl_feats, img_metas, prev_bev=None):\n        bs, num_cam, _, _, _ = mlvl_feats[0].shape\n        dtype = mlvl_feats[0].dtype\n        bev_queries = self.bev_embedding.weight.to(dtype)\n\n        bev_mask = torch.zeros((bs, self.bev_h, self.bev_w),\n                               device=bev_queries.device).to(dtype)\n        bev_pos = self.positional_encoding(bev_mask).to(dtype)\n        bev_embed = self.transformer.get_bev_features(\n            mlvl_feats,\n            bev_queries,\n            self.bev_h,\n            self.bev_w,\n            grid_length=(self.real_h / self.bev_h,\n                         self.real_w / self.bev_w),\n            bev_pos=bev_pos,\n            prev_bev=prev_bev,\n            img_metas=img_metas,\n        )\n        return bev_embed, bev_pos\n\n    def get_detections(\n        self, \n        bev_embed,\n        object_query_embeds=None,\n        ref_points=None,\n        img_metas=None,\n    ):\n        assert bev_embed.shape[0] == self.bev_h * self.bev_w\n        hs, init_reference, inter_references = self.transformer.get_states_and_refs(\n            bev_embed,\n            object_query_embeds,\n            self.bev_h,\n            self.bev_w,\n            reference_points=ref_points,\n            reg_branches=self.reg_branches if self.with_box_refine else None,\n            cls_branches=self.cls_branches if self.as_two_stage else None,\n            img_metas=img_metas,\n        )\n        hs = hs.permute(0, 2, 1, 3)\n        outputs_classes = []\n        outputs_coords = []\n        outputs_trajs = []\n        for lvl in range(hs.shape[0]):\n            if lvl == 0:\n                # reference = init_reference\n                reference = ref_points.sigmoid()\n            else:\n                reference = inter_references[lvl - 1]\n                # ref_size_base = inter_box_sizes[lvl - 1]\n            reference = inverse_sigmoid(reference)\n            outputs_class = self.cls_branches[lvl](hs[lvl])\n            tmp = self.reg_branches[lvl](hs[lvl])  # xydxdyxdz\n            outputs_past_traj = self.past_traj_reg_branches[lvl](hs[lvl]).view(\n                tmp.shape[0], -1, self.past_steps + self.fut_steps, 2)\n            # TODO: check the shape of reference\n            assert reference.shape[-1] == 3\n            tmp[..., 0:2] += reference[..., 0:2]\n            tmp[..., 0:2] = tmp[..., 0:2].sigmoid()\n            tmp[..., 4:5] += reference[..., 2:3]\n            tmp[..., 4:5] = tmp[..., 4:5].sigmoid()\n\n            last_ref_points = torch.cat(\n                [tmp[..., 0:2], tmp[..., 4:5]], dim=-1,\n            )\n\n            tmp[..., 0:1] = (tmp[..., 0:1] * (self.pc_range[3] -\n                             self.pc_range[0]) + self.pc_range[0])\n            tmp[..., 1:2] = (tmp[..., 1:2] * (self.pc_range[4] -\n                             self.pc_range[1]) + self.pc_range[1])\n            tmp[..., 4:5] = (tmp[..., 4:5] * (self.pc_range[5] -\n                             self.pc_range[2]) + self.pc_range[2])\n\n            # tmp[..., 2:4] = tmp[..., 2:4] + ref_size_basse[..., 0:2]\n            # tmp[..., 5:6] = tmp[..., 5:6] + ref_size_basse[..., 2:3]\n\n            # TODO: check if using sigmoid\n            outputs_coord = tmp\n            outputs_classes.append(outputs_class)\n            outputs_coords.append(outputs_coord)\n            outputs_trajs.append(outputs_past_traj)\n        outputs_classes = torch.stack(outputs_classes)\n        outputs_coords = torch.stack(outputs_coords)\n        outputs_trajs = torch.stack(outputs_trajs)\n        last_ref_points = inverse_sigmoid(last_ref_points)\n        outs = {\n            'all_cls_scores': outputs_classes,\n            'all_bbox_preds': outputs_coords,\n            'all_past_traj_preds': outputs_trajs,\n            'enc_cls_scores': None,\n            'enc_bbox_preds': None,\n            'last_ref_points': last_ref_points,\n            'query_feats': hs,\n        }\n        return outs\n        \n    def _get_target_single(self,\n                           cls_score,\n                           bbox_pred,\n                           gt_labels,\n                           gt_bboxes,\n                           gt_bboxes_ignore=None):\n        \"\"\"\"Compute regression and classification targets for one image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_score (Tensor): Box score logits from a single decoder layer\n                for one image. Shape [num_query, cls_out_channels].\n            bbox_pred (Tensor): Sigmoid outputs from a single decoder layer\n                for one image, with normalized coordinate (cx, cy, w, h) and\n                shape [num_query, 4].\n            gt_bboxes (Tensor): Ground truth bboxes for one image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (Tensor): Ground truth class indices for one image\n                with shape (num_gts, ).\n            gt_bboxes_ignore (Tensor, optional): Bounding boxes\n                which can be ignored. Default None.\n        Returns:\n            tuple[Tensor]: a tuple containing the following for one image.\n                - labels (Tensor): Labels of each image.\n                - label_weights (Tensor]): Label weights of each image.\n                - bbox_targets (Tensor): BBox targets of each image.\n                - bbox_weights (Tensor): BBox weights of each image.\n                - pos_inds (Tensor): Sampled positive indices for each image.\n                - neg_inds (Tensor): Sampled negative indices for each image.\n        \"\"\"\n\n        num_bboxes = bbox_pred.size(0)\n        # assigner and sampler\n        gt_c = gt_bboxes.shape[-1]\n\n        assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,\n                                             gt_labels, gt_bboxes_ignore)\n\n        sampling_result = self.sampler.sample(assign_result, bbox_pred,\n                                              gt_bboxes)\n        pos_inds = sampling_result.pos_inds\n        neg_inds = sampling_result.neg_inds\n\n        # label targets\n        labels = gt_bboxes.new_full((num_bboxes,),\n                                    self.num_classes,\n                                    dtype=torch.long)\n        labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]\n        label_weights = gt_bboxes.new_ones(num_bboxes)\n\n        # bbox targets\n        bbox_targets = torch.zeros_like(bbox_pred)[..., :gt_c]\n        bbox_weights = torch.zeros_like(bbox_pred)\n        bbox_weights[pos_inds] = 1.0\n\n        # DETR\n        bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes\n        return (labels, label_weights, bbox_targets, bbox_weights,\n                pos_inds, neg_inds)\n\n    def get_targets(self,\n                    cls_scores_list,\n                    bbox_preds_list,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Compute regression and classification targets for a batch image.\n        Outputs from a single decoder layer of a single feature level are used.\n        Args:\n            cls_scores_list (list[Tensor]): Box score logits from a single\n                decoder layer for each image with shape [num_query,\n                cls_out_channels].\n            bbox_preds_list (list[Tensor]): Sigmoid outputs from a single\n                decoder layer for each image, with normalized coordinate\n                (cx, cy, w, h) and shape [num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            tuple: a tuple containing the following targets.\n                - labels_list (list[Tensor]): Labels for all images.\n                - label_weights_list (list[Tensor]): Label weights for all \\\n                    images.\n                - bbox_targets_list (list[Tensor]): BBox targets for all \\\n                    images.\n                - bbox_weights_list (list[Tensor]): BBox weights for all \\\n                    images.\n                - num_total_pos (int): Number of positive samples in all \\\n                    images.\n                - num_total_neg (int): Number of negative samples in all \\\n                    images.\n        \"\"\"\n        assert gt_bboxes_ignore_list is None, \\\n            'Only supports for gt_bboxes_ignore setting to None.'\n        num_imgs = len(cls_scores_list)\n        gt_bboxes_ignore_list = [\n            gt_bboxes_ignore_list for _ in range(num_imgs)\n        ]\n\n        (labels_list, label_weights_list, bbox_targets_list,\n         bbox_weights_list, pos_inds_list, neg_inds_list) = multi_apply(\n            self._get_target_single, cls_scores_list, bbox_preds_list,\n            gt_labels_list, gt_bboxes_list, gt_bboxes_ignore_list)\n        num_total_pos = sum((inds.numel() for inds in pos_inds_list))\n        num_total_neg = sum((inds.numel() for inds in neg_inds_list))\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, num_total_pos, num_total_neg)\n\n    def loss_single(self,\n                    cls_scores,\n                    bbox_preds,\n                    gt_bboxes_list,\n                    gt_labels_list,\n                    gt_bboxes_ignore_list=None):\n        \"\"\"\"Loss function for outputs from a single decoder layer of a single\n        feature level.\n        Args:\n            cls_scores (Tensor): Box score logits from a single decoder layer\n                for all images. Shape [bs, num_query, cls_out_channels].\n            bbox_preds (Tensor): Sigmoid outputs from a single decoder layer\n                for all images, with normalized coordinate (cx, cy, w, h) and\n                shape [bs, num_query, 4].\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            gt_bboxes_ignore_list (list[Tensor], optional): Bounding\n                boxes which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components for outputs from\n                a single decoder layer.\n        \"\"\"\n        num_imgs = cls_scores.size(0)\n        cls_scores_list = [cls_scores[i] for i in range(num_imgs)]\n        bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]\n        cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,\n                                           gt_bboxes_list, gt_labels_list,\n                                           gt_bboxes_ignore_list)\n        (labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,\n         num_total_pos, num_total_neg) = cls_reg_targets\n        labels = torch.cat(labels_list, 0)\n        label_weights = torch.cat(label_weights_list, 0)\n        bbox_targets = torch.cat(bbox_targets_list, 0)\n        bbox_weights = torch.cat(bbox_weights_list, 0)\n\n        # classification loss\n        cls_scores = cls_scores.reshape(-1, self.cls_out_channels)\n        # construct weighted avg_factor to match with the official DETR repo\n        cls_avg_factor = num_total_pos * 1.0 + \\\n            num_total_neg * self.bg_cls_weight\n        if self.sync_cls_avg_factor:\n            cls_avg_factor = reduce_mean(\n                cls_scores.new_tensor([cls_avg_factor]))\n\n        cls_avg_factor = max(cls_avg_factor, 1)\n        loss_cls = self.loss_cls(\n            cls_scores, labels, label_weights, avg_factor=cls_avg_factor)\n\n        # Compute the average number of gt boxes accross all gpus, for\n        # normalization purposes\n        num_total_pos = loss_cls.new_tensor([num_total_pos])\n        num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()\n\n        # regression L1 loss\n        bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))\n        normalized_bbox_targets = normalize_bbox(bbox_targets, self.pc_range)\n        isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)\n        bbox_weights = bbox_weights * self.code_weights\n\n        loss_bbox = self.loss_bbox(\n            bbox_preds[isnotnan, :10], normalized_bbox_targets[isnotnan,\n                                                               :10], bbox_weights[isnotnan, :10],\n            avg_factor=num_total_pos)\n        loss_cls = torch.nan_to_num(loss_cls)\n        loss_bbox = torch.nan_to_num(loss_bbox)\n        return loss_cls, loss_bbox\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def loss(self,\n             gt_bboxes_list,\n             gt_labels_list,\n             preds_dicts,\n             gt_bboxes_ignore=None,\n             img_metas=None):\n        \"\"\"\"Loss function.\n        Args:\n\n            gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image\n                with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels_list (list[Tensor]): Ground truth class indices for each\n                image with shape (num_gts, ).\n            preds_dicts:\n                all_cls_scores (Tensor): Classification score of all\n                    decoder layers, has shape\n                    [nb_dec, bs, num_query, cls_out_channels].\n                all_bbox_preds (Tensor): Sigmoid regression\n                    outputs of all decode layers. Each is a 4D-tensor with\n                    normalized coordinate format (cx, cy, w, h) and shape\n                    [nb_dec, bs, num_query, 4].\n                enc_cls_scores (Tensor): Classification scores of\n                    points on encode feature map , has shape\n                    (N, h*w, num_classes). Only be passed when as_two_stage is\n                    True, otherwise is None.\n                enc_bbox_preds (Tensor): Regression results of each points\n                    on the encode feature map, has shape (N, h*w, 4). Only be\n                    passed when as_two_stage is True, otherwise is None.\n            gt_bboxes_ignore (list[Tensor], optional): Bounding boxes\n                which can be ignored for each image. Default None.\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            f'{self.__class__.__name__} only supports ' \\\n            f'for gt_bboxes_ignore setting to None.'\n\n        all_cls_scores = preds_dicts['all_cls_scores']\n        all_bbox_preds = preds_dicts['all_bbox_preds']\n        enc_cls_scores = preds_dicts['enc_cls_scores']\n        enc_bbox_preds = preds_dicts['enc_bbox_preds']\n\n        num_dec_layers = len(all_cls_scores)\n        device = gt_labels_list[0].device\n\n        gt_bboxes_list = [torch.cat(\n            (gt_bboxes.gravity_center, gt_bboxes.tensor[:, 3:]),\n            dim=1).to(device) for gt_bboxes in gt_bboxes_list]\n\n        all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]\n        all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]\n        all_gt_bboxes_ignore_list = [\n            gt_bboxes_ignore for _ in range(num_dec_layers)\n        ]\n\n        losses_cls, losses_bbox = multi_apply(\n            self.loss_single, all_cls_scores, all_bbox_preds,\n            all_gt_bboxes_list, all_gt_labels_list,\n            all_gt_bboxes_ignore_list)\n\n        loss_dict = dict()\n        # loss of proposal generated from encode feature map.\n        if enc_cls_scores is not None:\n            binary_labels_list = [\n                torch.zeros_like(gt_labels_list[i])\n                for i in range(len(all_gt_labels_list))\n            ]\n            enc_loss_cls, enc_losses_bbox = \\\n                self.loss_single(enc_cls_scores, enc_bbox_preds,\n                                 gt_bboxes_list, binary_labels_list, gt_bboxes_ignore)\n            loss_dict['enc_loss_cls'] = enc_loss_cls\n            loss_dict['enc_loss_bbox'] = enc_losses_bbox\n\n        # loss from the last decoder layer\n        loss_dict['loss_cls'] = losses_cls[-1]\n        loss_dict['loss_bbox'] = losses_bbox[-1]\n\n        # loss from other decoder layers\n        num_dec_layer = 0\n        for loss_cls_i, loss_bbox_i in zip(losses_cls[:-1],\n                                           losses_bbox[:-1]):\n            loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i\n            loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i\n            num_dec_layer += 1\n        return loss_dict\n\n    @force_fp32(apply_to=('preds_dicts'))\n    def get_bboxes(self, preds_dicts, img_metas, rescale=False):\n        \"\"\"Generate bboxes from bbox head predictions.\n        Args:\n            preds_dicts (tuple[list[dict]]): Prediction results.\n            img_metas (list[dict]): Point cloud and image's meta info.\n        Returns:\n            list[dict]: Decoded bbox, scores and labels after nms.\n        \"\"\"\n\n        preds_dicts = self.bbox_coder.decode(preds_dicts)\n\n        num_samples = len(preds_dicts)\n        ret_list = []\n        for i in range(num_samples):\n            preds = preds_dicts[i]\n            bboxes = preds['bboxes']\n\n            bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5\n\n            code_size = bboxes.shape[-1]\n            bboxes = img_metas[i]['box_type_3d'](bboxes, code_size)\n            scores = preds['scores']\n            labels = preds['labels']\n            bbox_index = preds['bbox_index']\n            mask = preds['mask']\n\n            ret_list.append([bboxes, scores, labels, bbox_index, mask])\n\n        return ret_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/track_head_plugin/__init__.py",
    "content": "from .modules import MemoryBank, QueryInteractionModule\nfrom .track_instance import Instances\nfrom .tracker import RuntimeTrackerBase"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/track_head_plugin/modules.py",
    "content": "import torch\nimport torch.nn.functional as F\nfrom torch import nn\nfrom .track_instance import Instances\n\n# MemoryBank\nclass MemoryBank(nn.Module):\n\n    def __init__(self,\n                 args,\n                 dim_in, hidden_dim, dim_out,\n                 ):\n        super().__init__()\n        self._build_layers(args, dim_in, hidden_dim, dim_out)\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n\n    def _build_layers(self, args, dim_in, hidden_dim, dim_out):\n        self.save_thresh = args['memory_bank_score_thresh']\n        self.save_period = 3\n        self.max_his_length = args['memory_bank_len']\n\n        self.save_proj = nn.Linear(dim_in, dim_in)\n\n        self.temporal_attn = nn.MultiheadAttention(dim_in, 8, dropout=0)\n        self.temporal_fc1 = nn.Linear(dim_in, hidden_dim)\n        self.temporal_fc2 = nn.Linear(hidden_dim, dim_in)\n        self.temporal_norm1 = nn.LayerNorm(dim_in)\n        self.temporal_norm2 = nn.LayerNorm(dim_in)\n\n    def update(self, track_instances):\n        embed = track_instances.output_embedding[:, None]  #( N, 1, 256)\n        scores = track_instances.scores\n        mem_padding_mask = track_instances.mem_padding_mask\n        device = embed.device\n\n        save_period = track_instances.save_period\n        if self.training:\n            saved_idxes = scores > 0\n        else:\n            saved_idxes = (save_period == 0) & (scores > self.save_thresh)\n            # saved_idxes = (save_period == 0)\n            save_period[save_period > 0] -= 1\n            save_period[saved_idxes] = self.save_period\n\n        saved_embed = embed[saved_idxes]\n        if len(saved_embed) > 0:\n            prev_embed = track_instances.mem_bank[saved_idxes]\n            save_embed = self.save_proj(saved_embed)\n            mem_padding_mask[saved_idxes] = torch.cat([mem_padding_mask[saved_idxes, 1:], torch.zeros((len(saved_embed), 1), dtype=torch.bool, device=device)], dim=1)\n            track_instances.mem_bank = track_instances.mem_bank.clone()\n            track_instances.mem_bank[saved_idxes] = torch.cat([prev_embed[:, 1:], save_embed], dim=1)\n\n    def _forward_temporal_attn(self, track_instances):\n        if len(track_instances) == 0:\n            return track_instances\n\n        key_padding_mask = track_instances.mem_padding_mask  # [n_, memory_bank_len]\n\n        valid_idxes = key_padding_mask[:, -1] == 0\n        embed = track_instances.output_embedding[valid_idxes]  # (n, 256)\n\n        if len(embed) > 0:\n            prev_embed = track_instances.mem_bank[valid_idxes]\n            key_padding_mask = key_padding_mask[valid_idxes]\n            embed2 = self.temporal_attn(\n                embed[None],                  # (num_track, dim) to (1, num_track, dim)\n                prev_embed.transpose(0, 1),   # (num_track, mem_len, dim) to (mem_len, num_track, dim)\n                prev_embed.transpose(0, 1),\n                key_padding_mask=key_padding_mask,\n            )[0][0]\n\n            embed = self.temporal_norm1(embed + embed2)\n            embed2 = self.temporal_fc2(F.relu(self.temporal_fc1(embed)))\n            embed = self.temporal_norm2(embed + embed2)\n            track_instances.output_embedding = track_instances.output_embedding.clone()\n            track_instances.output_embedding[valid_idxes] = embed\n\n        return track_instances\n\n    def forward_temporal_attn(self, track_instances):\n        return self._forward_temporal_attn(track_instances)\n\n    def forward(self, track_instances: Instances, update_bank=True) -> Instances:\n        track_instances = self._forward_temporal_attn(track_instances)\n        if update_bank:\n            self.update(track_instances)\n        return track_instances\n\n\n# QIM\nclass QueryInteractionBase(nn.Module):\n\n    def __init__(self, args, dim_in, hidden_dim, dim_out):\n        super().__init__()\n        self.args = args\n        self._build_layers(args, dim_in, hidden_dim, dim_out)\n        self._reset_parameters()\n\n    def _build_layers(self, args, dim_in, hidden_dim, dim_out):\n        raise NotImplementedError()\n\n    def _reset_parameters(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n\n    def _select_active_tracks(self, data: dict) -> Instances:\n        raise NotImplementedError()\n\n    def _update_track_embedding(self, track_instances):\n        raise NotImplementedError()\n\nclass QueryInteractionModule(QueryInteractionBase):\n\n    def __init__(self, args, dim_in, hidden_dim, dim_out):\n        super().__init__(args, dim_in, hidden_dim, dim_out)\n        self.random_drop = args[\"random_drop\"]\n        self.fp_ratio = args[\"fp_ratio\"]\n        self.update_query_pos = args[\"update_query_pos\"]\n\n    def _build_layers(self, args, dim_in, hidden_dim, dim_out):\n        dropout = args[\"merger_dropout\"]\n\n        self.self_attn = nn.MultiheadAttention(dim_in, 8, dropout)\n        self.linear1 = nn.Linear(dim_in, hidden_dim)\n        self.dropout = nn.Dropout(dropout)\n        self.linear2 = nn.Linear(hidden_dim, dim_in)\n\n        if args[\"update_query_pos\"]:\n            self.linear_pos1 = nn.Linear(dim_in, hidden_dim)\n            self.linear_pos2 = nn.Linear(hidden_dim, dim_in)\n            self.dropout_pos1 = nn.Dropout(dropout)\n            self.dropout_pos2 = nn.Dropout(dropout)\n            self.norm_pos = nn.LayerNorm(dim_in)\n\n        self.linear_feat1 = nn.Linear(dim_in, hidden_dim)\n        self.linear_feat2 = nn.Linear(hidden_dim, dim_in)\n        self.dropout_feat1 = nn.Dropout(dropout)\n        self.dropout_feat2 = nn.Dropout(dropout)\n        self.norm_feat = nn.LayerNorm(dim_in)\n\n        self.norm1 = nn.LayerNorm(dim_in)\n        self.norm2 = nn.LayerNorm(dim_in)\n\n        self.dropout1 = nn.Dropout(dropout)\n        self.dropout2 = nn.Dropout(dropout)\n        self.activation = F.relu\n\n    def _update_track_embedding(self, track_instances: Instances) -> Instances:\n        if len(track_instances) == 0:\n            return track_instances\n        dim = track_instances.query.shape[1]\n        out_embed = track_instances.output_embedding\n        query_pos = track_instances.query[:, :dim // 2]\n        query_feat = track_instances.query[:, dim // 2:]\n        q = k = query_pos + out_embed\n\n        # attention\n        tgt = out_embed\n        tgt2 = self.self_attn(q[:, None], k[:, None], value=tgt[:, None])[0][:,\n                                                                             0]\n        tgt = tgt + self.dropout1(tgt2)\n        tgt = self.norm1(tgt)\n\n        # ffn\n        tgt2 = self.linear2(self.dropout(self.activation(self.linear1(tgt))))\n        tgt = tgt + self.dropout2(tgt2)\n        tgt = self.norm2(tgt)\n\n        if self.update_query_pos:\n            # ffn: linear_pos2\n            query_pos2 = self.linear_pos2(\n                self.dropout_pos1(self.activation(self.linear_pos1(tgt))))\n            query_pos = query_pos + self.dropout_pos2(query_pos2)\n            query_pos = self.norm_pos(query_pos)\n            track_instances.query[:, :dim // 2] = query_pos\n\n        query_feat2 = self.linear_feat2(\n            self.dropout_feat1(self.activation(self.linear_feat1(tgt))))\n        query_feat = query_feat + self.dropout_feat2(query_feat2)\n        query_feat = self.norm_feat(query_feat)\n        track_instances.query[:, dim // 2:] = query_feat\n        # track_instances.ref_pts = inverse_sigmoid(track_instances.pred_boxes[:, :2].detach().clone())\n        # update ref_pts using track_instances.pred_boxes\n        return track_instances\n\n    def _random_drop_tracks(self, track_instances: Instances) -> Instances:\n        drop_probability = self.random_drop\n        if drop_probability > 0 and len(track_instances) > 0:\n            keep_idxes = torch.rand_like(track_instances.scores) > drop_probability\n            track_instances = track_instances[keep_idxes]\n        return track_instances\n\n    def _add_fp_tracks(self, track_instances: Instances,\n                       active_track_instances: Instances) -> Instances:\n        \"\"\"\n        self.fp_ratio is used to control num(add_fp) / num(active)\n        \"\"\"\n        inactive_instances = track_instances[track_instances.obj_idxes < 0]\n\n        # add fp for each active track in a specific probability.\n        fp_prob = torch.ones_like(\n            active_track_instances.scores) * self.fp_ratio\n        selected_active_track_instances = active_track_instances[\n            torch.bernoulli(fp_prob).bool()]\n        num_fp = len(selected_active_track_instances)\n\n        if len(inactive_instances) > 0 and num_fp > 0:\n            if num_fp >= len(inactive_instances):\n                fp_track_instances = inactive_instances\n            else:\n                # randomly select num_fp from inactive_instances\n                # fp_indexes = np.random.permutation(len(inactive_instances))\n                # fp_indexes = fp_indexes[:num_fp]\n                # fp_track_instances = inactive_instances[fp_indexes]\n\n                # v2: select the fps with top scores rather than random selection\n                fp_indexes = torch.argsort(inactive_instances.scores)[-num_fp:]\n                fp_track_instances = inactive_instances[fp_indexes]\n\n            merged_track_instances = Instances.cat(\n                [active_track_instances, fp_track_instances])\n            return merged_track_instances\n\n        return active_track_instances\n\n    def _select_active_tracks(self, data: dict) -> Instances:\n        track_instances: Instances = data[\"track_instances\"]\n        if self.training:\n            active_idxes = (track_instances.obj_idxes >=\n                            0) & (track_instances.iou > 0.5)\n            active_track_instances = track_instances[active_idxes]\n            # set -2 instead of -1 to ensure that these tracks will not be selected in matching.\n            active_track_instances = self._random_drop_tracks(\n                active_track_instances)\n            if self.fp_ratio > 0:\n                active_track_instances = self._add_fp_tracks(\n                    track_instances, active_track_instances)\n        else:\n            active_track_instances = track_instances[\n                track_instances.obj_idxes >= 0]\n\n        return active_track_instances\n\n    def forward(self, data) -> Instances:\n        active_track_instances = self._select_active_tracks(data)\n        active_track_instances = self._update_track_embedding(\n            active_track_instances)\n        init_track_instances: Instances = data[\"init_track_instances\"]\n        merged_track_instances = Instances.cat(\n            [init_track_instances, active_track_instances])\n        return merged_track_instances\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/track_head_plugin/track_instance.py",
    "content": "import itertools\nfrom typing import Any, Dict, List, Tuple, Union\nimport torch\n\n\nclass Instances:\n    \"\"\"\n    This class represents a list of instances in an image.\n    It stores the attributes of instances (e.g., boxes, masks, labels, scores) as \"fields\".\n    All fields must have the same ``__len__`` which is the number of instances.\n    All other (non-field) attributes of this class are considered private:\n    they must start with '_' and are not modifiable by a user.\n    Some basic usage:\n    1. Set/get/check a field:\n       .. code-block:: python\n          instances.gt_boxes = Boxes(...)\n          print(instances.pred_masks)  # a tensor of shape (N, H, W)\n          print('gt_masks' in instances)\n    2. ``len(instances)`` returns the number of instances\n    3. Indexing: ``instances[indices]`` will apply the indexing on all the fields\n       and returns a new :class:`Instances`.\n       Typically, ``indices`` is a integer vector of indices,\n       or a binary mask of length ``num_instances``\n       .. code-block:: python\n          category_3_detections = instances[instances.pred_classes == 3]\n          confident_detections = instances[instances.scores > 0.9]\n    \"\"\"\n\n    def __init__(self, image_size: Tuple[int, int], **kwargs: Any):\n        \"\"\"\n        Args:\n            image_size (height, width): the spatial size of the image.\n            kwargs: fields to add to this `Instances`.\n        \"\"\"\n        self._image_size = image_size\n        self._fields: Dict[str, Any] = {}\n        for k, v in kwargs.items():\n            self.set(k, v)\n\n    @property\n    def image_size(self) -> Tuple[int, int]:\n        \"\"\"\n        Returns:\n            tuple: height, width\n        \"\"\"\n        return self._image_size\n\n    def __setattr__(self, name: str, val: Any) -> None:\n        if name.startswith(\"_\"):\n            super().__setattr__(name, val)\n        else:\n            self.set(name, val)\n\n    def __getattr__(self, name: str) -> Any:\n        if name == \"_fields\" or name not in self._fields:\n            raise AttributeError(\"Cannot find field '{}' in the given Instances!\".format(name))\n        return self._fields[name]\n\n    def set(self, name: str, value: Any) -> None:\n        \"\"\"\n        Set the field named `name` to `value`.\n        The length of `value` must be the number of instances,\n        and must agree with other existing fields in this object.\n        \"\"\"\n        data_len = len(value)\n        if len(self._fields):\n            assert (\n                len(self) == data_len\n            ), \"Adding a field of length {} to a Instances of length {}\".format(data_len, len(self))\n        self._fields[name] = value\n\n    def has(self, name: str) -> bool:\n        \"\"\"\n        Returns:\n            bool: whether the field called `name` exists.\n        \"\"\"\n        return name in self._fields\n\n    def remove(self, name: str) -> None:\n        \"\"\"\n        Remove the field called `name`.\n        \"\"\"\n        del self._fields[name]\n\n    def get(self, name: str) -> Any:\n        \"\"\"\n        Returns the field called `name`.\n        \"\"\"\n        return self._fields[name]\n\n    def get_fields(self) -> Dict[str, Any]:\n        \"\"\"\n        Returns:\n            dict: a dict which maps names (str) to data of the fields\n        Modifying the returned dict will modify this instance.\n        \"\"\"\n        return self._fields\n\n    # Tensor-like methods\n    def to(self, *args: Any, **kwargs: Any) -> \"Instances\":\n        \"\"\"\n        Returns:\n            Instances: all fields are called with a `to(device)`, if the field has this method.\n        \"\"\"\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            if hasattr(v, \"to\"):\n                v = v.to(*args, **kwargs)\n            ret.set(k, v)\n        return ret\n\n    def numpy(self):\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            if hasattr(v, \"numpy\"):\n                v = v.numpy()\n            ret.set(k, v)\n        return ret\n\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"Instances\":\n        \"\"\"\n        Args:\n            item: an index-like object and will be used to index all the fields.\n        Returns:\n            If `item` is a string, return the data in the corresponding field.\n            Otherwise, returns an `Instances` where all fields are indexed by `item`.\n        \"\"\"\n        if type(item) == int:\n            if item >= len(self) or item < -len(self):\n                raise IndexError(\"Instances index out of range!\")\n            else:\n                item = slice(item, None, len(self))\n\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            # print(k, type(item), 'getitem', item.type(), item.dtype)\n            # if index by torch.BoolTensor\n            if k == 'kalman_models' and isinstance(item, torch.Tensor):\n                # print(item.shape, 'in get item')\n                ret_list = []\n                for i, if_true in enumerate(item):\n                    if if_true:\n                        ret_list.append(self.kalman_models[i])\n                ret.set(k, ret_list)\n\n            else:\n                ret.set(k, v[item])\n        return ret\n\n    def __len__(self) -> int:\n        for v in self._fields.values():\n            # use __len__ because len() has to be int and is not friendly to tracing\n            return v.__len__()\n        raise NotImplementedError(\"Empty Instances does not support __len__!\")\n\n    def __iter__(self):\n        raise NotImplementedError(\"`Instances` object is not iterable!\")\n\n    @staticmethod\n    def cat(instance_lists: List[\"Instances\"]) -> \"Instances\":\n        \"\"\"\n        Args:\n            instance_lists (list[Instances])\n        Returns:\n            Instances\n        \"\"\"\n        assert all(isinstance(i, Instances) for i in instance_lists)\n        assert len(instance_lists) > 0\n        if len(instance_lists) == 1:\n            return instance_lists[0]\n\n        image_size = instance_lists[0].image_size\n        for i in instance_lists[1:]:\n            assert i.image_size == image_size\n        ret = Instances(image_size)\n        for k in instance_lists[0]._fields.keys():\n            values = [i.get(k) for i in instance_lists]\n            v0 = values[0]\n            if isinstance(v0, torch.Tensor):\n                values = torch.cat(values, dim=0)\n            elif isinstance(v0, list):\n                values = list(itertools.chain(*values))\n            elif hasattr(type(v0), \"cat\"):\n                values = type(v0).cat(values)\n            else:\n                raise ValueError(\"Unsupported type {} for concatenation\".format(type(v0)))\n            ret.set(k, values)\n        return ret\n\n    def __str__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={}, \".format(len(self))\n        s += \"image_height={}, \".format(self._image_size[0])\n        s += \"image_width={}, \".format(self._image_size[1])\n        s += \"fields=[{}])\".format(\", \".join((f\"{k}: {v}\" for k, v in self._fields.items())))\n        return s\n\n    __repr__ = __str__"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/track_head_plugin/tracker.py",
    "content": "from .track_instance import Instances\nfrom mmcv.core.bbox.iou_calculators.iou3d_calculator import (\n    bbox_overlaps_nearest_3d as iou_3d, )\nfrom mmcv.core.bbox.util import denormalize_bbox\n\nclass RuntimeTrackerBase(object):\n    def __init__(self, score_thresh=0.5, filter_score_thresh=0.4,  miss_tolerance=5):\n        self.score_thresh = score_thresh\n        self.filter_score_thresh = filter_score_thresh\n        self.miss_tolerance = miss_tolerance\n        self.max_obj_id = 0\n\n    def clear(self):\n        self.max_obj_id = 0\n\n    def update(self, track_instances: Instances, iou_thre=None):\n        track_instances.disappear_time[track_instances.scores >= self.score_thresh] = 0\n        for i in range(len(track_instances)):\n            if (\n                track_instances.obj_idxes[i] == -1\n                and track_instances.scores[i] >= self.score_thresh\n            ):  \n                if iou_thre is not None and track_instances.pred_boxes[track_instances.obj_idxes>=0].shape[0]!=0:\n                    iou3ds = iou_3d(denormalize_bbox(track_instances.pred_boxes[i].unsqueeze(0), None)[...,:7], denormalize_bbox(track_instances.pred_boxes[track_instances.obj_idxes>=0], None)[...,:7])\n                    if iou3ds.max()>iou_thre:\n                        continue\n                # new track\n                # print(\"track {} has score {}, assign obj_id {}\".format(i, track_instances.scores[i], self.max_obj_id))\n                track_instances.obj_idxes[i] = self.max_obj_id\n                self.max_obj_id += 1\n            elif (\n                track_instances.obj_idxes[i] >= 0\n                and track_instances.scores[i] < self.filter_score_thresh\n            ):\n                # sleep time ++\n                track_instances.disappear_time[i] += 1\n                if track_instances.disappear_time[i] >= self.miss_tolerance:\n                    # mark deaded tracklets: Set the obj_id to -1.\n                    # TODO: remove it by following functions\n                    # Then this track will be removed by TrackEmbeddingLayer.\n                    track_instances.obj_idxes[i] = -1\n                    "
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/dense_heads/train_mixins.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmcv.core import limit_period\nfrom mmcv.core import images_to_levels, multi_apply\n\n\nclass AnchorTrainMixin(object):\n    \"\"\"Mixin class for target assigning of dense heads.\"\"\"\n\n    def anchor_target_3d(self,\n                         anchor_list,\n                         gt_bboxes_list,\n                         input_metas,\n                         gt_bboxes_ignore_list=None,\n                         gt_labels_list=None,\n                         label_channels=1,\n                         num_classes=1,\n                         sampling=True):\n        \"\"\"Compute regression and classification targets for anchors.\n\n        Args:\n            anchor_list (list[list]): Multi level anchors of each image.\n            gt_bboxes_list (list[:obj:`BaseInstance3DBoxes`]): Ground truth\n                bboxes of each image.\n            input_metas (list[dict]): Meta info of each image.\n            gt_bboxes_ignore_list (None | list): Ignore list of gt bboxes.\n            gt_labels_list (list[torch.Tensor]): Gt labels of batches.\n            label_channels (int): The channel of labels.\n            num_classes (int): The number of classes.\n            sampling (bool): Whether to sample anchors.\n\n        Returns:\n            tuple (list, list, list, list, list, list, int, int):\n                Anchor targets, including labels, label weights,\n                bbox targets, bbox weights, direction targets,\n                direction weights, number of postive anchors and\n                number of negative anchors.\n        \"\"\"\n        num_imgs = len(input_metas)\n        assert len(anchor_list) == num_imgs\n\n        if isinstance(anchor_list[0][0], list):\n            # sizes of anchors are different\n            # anchor number of a single level\n            num_level_anchors = [\n                sum([anchor.size(0) for anchor in anchors])\n                for anchors in anchor_list[0]\n            ]\n            for i in range(num_imgs):\n                anchor_list[i] = anchor_list[i][0]\n        else:\n            # anchor number of multi levels\n            num_level_anchors = [\n                anchors.view(-1, self.box_code_size).size(0)\n                for anchors in anchor_list[0]\n            ]\n            # concat all level anchors and flags to a single tensor\n            for i in range(num_imgs):\n                anchor_list[i] = torch.cat(anchor_list[i])\n\n        # compute targets for each image\n        if gt_bboxes_ignore_list is None:\n            gt_bboxes_ignore_list = [None for _ in range(num_imgs)]\n        if gt_labels_list is None:\n            gt_labels_list = [None for _ in range(num_imgs)]\n\n        (all_labels, all_label_weights, all_bbox_targets, all_bbox_weights,\n         all_dir_targets, all_dir_weights, pos_inds_list,\n         neg_inds_list) = multi_apply(\n             self.anchor_target_3d_single,\n             anchor_list,\n             gt_bboxes_list,\n             gt_bboxes_ignore_list,\n             gt_labels_list,\n             input_metas,\n             label_channels=label_channels,\n             num_classes=num_classes,\n             sampling=sampling)\n\n        # no valid anchors\n        if any([labels is None for labels in all_labels]):\n            return None\n        # sampled anchors of all images\n        num_total_pos = sum([max(inds.numel(), 1) for inds in pos_inds_list])\n        num_total_neg = sum([max(inds.numel(), 1) for inds in neg_inds_list])\n        # split targets to a list w.r.t. multiple levels\n        labels_list = images_to_levels(all_labels, num_level_anchors)\n        label_weights_list = images_to_levels(all_label_weights,\n                                              num_level_anchors)\n        bbox_targets_list = images_to_levels(all_bbox_targets,\n                                             num_level_anchors)\n        bbox_weights_list = images_to_levels(all_bbox_weights,\n                                             num_level_anchors)\n        dir_targets_list = images_to_levels(all_dir_targets, num_level_anchors)\n        dir_weights_list = images_to_levels(all_dir_weights, num_level_anchors)\n        return (labels_list, label_weights_list, bbox_targets_list,\n                bbox_weights_list, dir_targets_list, dir_weights_list,\n                num_total_pos, num_total_neg)\n\n    def anchor_target_3d_single(self,\n                                anchors,\n                                gt_bboxes,\n                                gt_bboxes_ignore,\n                                gt_labels,\n                                input_meta,\n                                label_channels=1,\n                                num_classes=1,\n                                sampling=True):\n        \"\"\"Compute targets of anchors in single batch.\n\n        Args:\n            anchors (torch.Tensor): Concatenated multi-level anchor.\n            gt_bboxes (:obj:`BaseInstance3DBoxes`): Gt bboxes.\n            gt_bboxes_ignore (torch.Tensor): Ignored gt bboxes.\n            gt_labels (torch.Tensor): Gt class labels.\n            input_meta (dict): Meta info of each image.\n            label_channels (int): The channel of labels.\n            num_classes (int): The number of classes.\n            sampling (bool): Whether to sample anchors.\n\n        Returns:\n            tuple[torch.Tensor]: Anchor targets.\n        \"\"\"\n        if isinstance(self.bbox_assigner,\n                      list) and (not isinstance(anchors, list)):\n            feat_size = anchors.size(0) * anchors.size(1) * anchors.size(2)\n            rot_angles = anchors.size(-2)\n            assert len(self.bbox_assigner) == anchors.size(-3)\n            (total_labels, total_label_weights, total_bbox_targets,\n             total_bbox_weights, total_dir_targets, total_dir_weights,\n             total_pos_inds, total_neg_inds) = [], [], [], [], [], [], [], []\n            current_anchor_num = 0\n            for i, assigner in enumerate(self.bbox_assigner):\n                current_anchors = anchors[..., i, :, :].reshape(\n                    -1, self.box_code_size)\n                current_anchor_num += current_anchors.size(0)\n                if self.assign_per_class:\n                    gt_per_cls = (gt_labels == i)\n                    anchor_targets = self.anchor_target_single_assigner(\n                        assigner, current_anchors, gt_bboxes[gt_per_cls, :],\n                        gt_bboxes_ignore, gt_labels[gt_per_cls], input_meta,\n                        num_classes, sampling)\n                else:\n                    anchor_targets = self.anchor_target_single_assigner(\n                        assigner, current_anchors, gt_bboxes, gt_bboxes_ignore,\n                        gt_labels, input_meta, num_classes, sampling)\n\n                (labels, label_weights, bbox_targets, bbox_weights,\n                 dir_targets, dir_weights, pos_inds, neg_inds) = anchor_targets\n                total_labels.append(labels.reshape(feat_size, 1, rot_angles))\n                total_label_weights.append(\n                    label_weights.reshape(feat_size, 1, rot_angles))\n                total_bbox_targets.append(\n                    bbox_targets.reshape(feat_size, 1, rot_angles,\n                                         anchors.size(-1)))\n                total_bbox_weights.append(\n                    bbox_weights.reshape(feat_size, 1, rot_angles,\n                                         anchors.size(-1)))\n                total_dir_targets.append(\n                    dir_targets.reshape(feat_size, 1, rot_angles))\n                total_dir_weights.append(\n                    dir_weights.reshape(feat_size, 1, rot_angles))\n                total_pos_inds.append(pos_inds)\n                total_neg_inds.append(neg_inds)\n\n            total_labels = torch.cat(total_labels, dim=-2).reshape(-1)\n            total_label_weights = torch.cat(\n                total_label_weights, dim=-2).reshape(-1)\n            total_bbox_targets = torch.cat(\n                total_bbox_targets, dim=-3).reshape(-1, anchors.size(-1))\n            total_bbox_weights = torch.cat(\n                total_bbox_weights, dim=-3).reshape(-1, anchors.size(-1))\n            total_dir_targets = torch.cat(\n                total_dir_targets, dim=-2).reshape(-1)\n            total_dir_weights = torch.cat(\n                total_dir_weights, dim=-2).reshape(-1)\n            total_pos_inds = torch.cat(total_pos_inds, dim=0).reshape(-1)\n            total_neg_inds = torch.cat(total_neg_inds, dim=0).reshape(-1)\n            return (total_labels, total_label_weights, total_bbox_targets,\n                    total_bbox_weights, total_dir_targets, total_dir_weights,\n                    total_pos_inds, total_neg_inds)\n        elif isinstance(self.bbox_assigner, list) and isinstance(\n                anchors, list):\n            # class-aware anchors with different feature map sizes\n            assert len(self.bbox_assigner) == len(anchors), \\\n                'The number of bbox assigners and anchors should be the same.'\n            (total_labels, total_label_weights, total_bbox_targets,\n             total_bbox_weights, total_dir_targets, total_dir_weights,\n             total_pos_inds, total_neg_inds) = [], [], [], [], [], [], [], []\n            current_anchor_num = 0\n            for i, assigner in enumerate(self.bbox_assigner):\n                current_anchors = anchors[i]\n                current_anchor_num += current_anchors.size(0)\n                if self.assign_per_class:\n                    gt_per_cls = (gt_labels == i)\n                    anchor_targets = self.anchor_target_single_assigner(\n                        assigner, current_anchors, gt_bboxes[gt_per_cls, :],\n                        gt_bboxes_ignore, gt_labels[gt_per_cls], input_meta,\n                        num_classes, sampling)\n                else:\n                    anchor_targets = self.anchor_target_single_assigner(\n                        assigner, current_anchors, gt_bboxes, gt_bboxes_ignore,\n                        gt_labels, input_meta, num_classes, sampling)\n\n                (labels, label_weights, bbox_targets, bbox_weights,\n                 dir_targets, dir_weights, pos_inds, neg_inds) = anchor_targets\n                total_labels.append(labels)\n                total_label_weights.append(label_weights)\n                total_bbox_targets.append(\n                    bbox_targets.reshape(-1, anchors[i].size(-1)))\n                total_bbox_weights.append(\n                    bbox_weights.reshape(-1, anchors[i].size(-1)))\n                total_dir_targets.append(dir_targets)\n                total_dir_weights.append(dir_weights)\n                total_pos_inds.append(pos_inds)\n                total_neg_inds.append(neg_inds)\n\n            total_labels = torch.cat(total_labels, dim=0)\n            total_label_weights = torch.cat(total_label_weights, dim=0)\n            total_bbox_targets = torch.cat(total_bbox_targets, dim=0)\n            total_bbox_weights = torch.cat(total_bbox_weights, dim=0)\n            total_dir_targets = torch.cat(total_dir_targets, dim=0)\n            total_dir_weights = torch.cat(total_dir_weights, dim=0)\n            total_pos_inds = torch.cat(total_pos_inds, dim=0)\n            total_neg_inds = torch.cat(total_neg_inds, dim=0)\n            return (total_labels, total_label_weights, total_bbox_targets,\n                    total_bbox_weights, total_dir_targets, total_dir_weights,\n                    total_pos_inds, total_neg_inds)\n        else:\n            return self.anchor_target_single_assigner(self.bbox_assigner,\n                                                      anchors, gt_bboxes,\n                                                      gt_bboxes_ignore,\n                                                      gt_labels, input_meta,\n                                                      num_classes, sampling)\n\n    def anchor_target_single_assigner(self,\n                                      bbox_assigner,\n                                      anchors,\n                                      gt_bboxes,\n                                      gt_bboxes_ignore,\n                                      gt_labels,\n                                      input_meta,\n                                      num_classes=1,\n                                      sampling=True):\n        \"\"\"Assign anchors and encode positive anchors.\n\n        Args:\n            bbox_assigner (BaseAssigner): assign positive and negative boxes.\n            anchors (torch.Tensor): Concatenated multi-level anchor.\n            gt_bboxes (:obj:`BaseInstance3DBoxes`): Gt bboxes.\n            gt_bboxes_ignore (torch.Tensor): Ignored gt bboxes.\n            gt_labels (torch.Tensor): Gt class labels.\n            input_meta (dict): Meta info of each image.\n            num_classes (int): The number of classes.\n            sampling (bool): Whether to sample anchors.\n\n        Returns:\n            tuple[torch.Tensor]: Anchor targets.\n        \"\"\"\n        anchors = anchors.reshape(-1, anchors.size(-1))\n        num_valid_anchors = anchors.shape[0]\n        bbox_targets = torch.zeros_like(anchors)\n        bbox_weights = torch.zeros_like(anchors)\n        dir_targets = anchors.new_zeros((anchors.shape[0]), dtype=torch.long)\n        dir_weights = anchors.new_zeros((anchors.shape[0]), dtype=torch.float)\n        labels = anchors.new_zeros(num_valid_anchors, dtype=torch.long)\n        label_weights = anchors.new_zeros(num_valid_anchors, dtype=torch.float)\n        if len(gt_bboxes) > 0:\n            if not isinstance(gt_bboxes, torch.Tensor):\n                gt_bboxes = gt_bboxes.tensor.to(anchors.device)\n            assign_result = bbox_assigner.assign(anchors, gt_bboxes,\n                                                 gt_bboxes_ignore, gt_labels)\n            sampling_result = self.bbox_sampler.sample(assign_result, anchors,\n                                                       gt_bboxes)\n            pos_inds = sampling_result.pos_inds\n            neg_inds = sampling_result.neg_inds\n        else:\n            pos_inds = torch.nonzero(\n                anchors.new_zeros((anchors.shape[0], ), dtype=torch.bool) > 0,\n                as_tuple=False).squeeze(-1).unique()\n            neg_inds = torch.nonzero(\n                anchors.new_zeros((anchors.shape[0], ), dtype=torch.bool) == 0,\n                as_tuple=False).squeeze(-1).unique()\n\n        if gt_labels is not None:\n            labels += num_classes\n        if len(pos_inds) > 0:\n            pos_bbox_targets = self.bbox_coder.encode(\n                sampling_result.pos_bboxes, sampling_result.pos_gt_bboxes)\n            pos_dir_targets = get_direction_target(\n                sampling_result.pos_bboxes,\n                pos_bbox_targets,\n                self.dir_offset,\n                one_hot=False)\n            bbox_targets[pos_inds, :] = pos_bbox_targets\n            bbox_weights[pos_inds, :] = 1.0\n            dir_targets[pos_inds] = pos_dir_targets\n            dir_weights[pos_inds] = 1.0\n\n            if gt_labels is None:\n                labels[pos_inds] = 1\n            else:\n                labels[pos_inds] = gt_labels[\n                    sampling_result.pos_assigned_gt_inds]\n            if self.train_cfg.pos_weight <= 0:\n                label_weights[pos_inds] = 1.0\n            else:\n                label_weights[pos_inds] = self.train_cfg.pos_weight\n\n        if len(neg_inds) > 0:\n            label_weights[neg_inds] = 1.0\n        return (labels, label_weights, bbox_targets, bbox_weights, dir_targets,\n                dir_weights, pos_inds, neg_inds)\n\n\ndef get_direction_target(anchors,\n                         reg_targets,\n                         dir_offset=0,\n                         num_bins=2,\n                         one_hot=True):\n    \"\"\"Encode direction to 0 ~ num_bins-1.\n\n    Args:\n        anchors (torch.Tensor): Concatenated multi-level anchor.\n        reg_targets (torch.Tensor): Bbox regression targets.\n        dir_offset (int): Direction offset.\n        num_bins (int): Number of bins to divide 2*PI.\n        one_hot (bool): Whether to encode as one hot.\n\n    Returns:\n        torch.Tensor: Encoded direction targets.\n    \"\"\"\n    rot_gt = reg_targets[..., 6] + anchors[..., 6]\n    offset_rot = limit_period(rot_gt - dir_offset, 0, 2 * np.pi)\n    dir_cls_targets = torch.floor(offset_rot / (2 * np.pi / num_bins)).long()\n    dir_cls_targets = torch.clamp(dir_cls_targets, min=0, max=num_bins - 1)\n    if one_hot:\n        dir_targets = torch.zeros(\n            *list(dir_cls_targets.shape),\n            num_bins,\n            dtype=anchors.dtype,\n            device=dir_cls_targets.device)\n        dir_targets.scatter_(dir_cls_targets.unsqueeze(dim=-1).long(), 1.0)\n        dir_cls_targets = dir_targets\n    return dir_cls_targets"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/MomAD.py",
    "content": "import time\nimport copy\n\nimport torch\nfrom mmcv.models import DETECTORS\nfrom mmcv.core.bbox.transforms import bbox3d2result\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom scipy.optimize import linear_sum_assignment\nfrom mmcv.models.detectors.mvx_two_stage import MVXTwoStageDetector\n\nfrom mmcv.models.utils.grid_mask import GridMask\nfrom mmcv.models.dense_heads.planning_head_plugin.metric_stp3 import PlanningMetric\n\n\n@DETECTORS.register_module()\nclass MomAD(MVXTwoStageDetector):\n    \"\"\"VAD model.\n    \"\"\"\n    def __init__(self,\n                 use_grid_mask=False,\n                 pts_voxel_layer=None,\n                 pts_voxel_encoder=None,\n                 pts_middle_encoder=None,\n                 pts_fusion_layer=None,\n                 img_backbone=None,\n                 pts_backbone=None,\n                 img_neck=None,\n                 pts_neck=None,\n                 pts_bbox_head=None,\n                 img_roi_head=None,\n                 img_rpn_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 pretrained=None,\n                 video_test_mode=False,\n                 prev_frame_num=0,\n                 fut_ts=6,\n                 fut_mode=6\n                 ):\n\n        super(MomAD,\n              self).__init__(pts_voxel_layer, pts_voxel_encoder,\n                             pts_middle_encoder, pts_fusion_layer,\n                             img_backbone, pts_backbone, img_neck, pts_neck,\n                             pts_bbox_head, img_roi_head, img_rpn_head,\n                             train_cfg, test_cfg, pretrained)\n        self.grid_mask = GridMask(\n            True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7)\n        #import pdb;pdb.set_trace()\n        self.use_grid_mask = use_grid_mask\n        self.fp16_enabled = False\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.valid_fut_ts = pts_bbox_head['valid_fut_ts']\n        self.prev_frame_num = prev_frame_num\n        self.prev_frame_infos = []\n\n        # temporal\n        self.video_test_mode = video_test_mode\n        self.prev_frame_info = {\n            'prev_bev': None,\n            'scene_token': None,\n            'prev_pos': 0,\n            'prev_angle': 0,\n        }\n\n        self.planning_metric = None\n\n    def extract_img_feat(self, img, img_metas, len_queue=None):\n        \"\"\"Extract features of images.\"\"\"\n        #import pdb;pdb.set_trace()\n        B = img.size(0)\n        if img is not None:\n            \n            # input_shape = img.shape[-2:]\n            # # update real input shape of each single img\n            # for img_meta in img_metas:\n            #     img_meta.update(input_shape=input_shape)\n\n            if img.dim() == 5 and img.size(0) == 1:\n                img.squeeze_()\n            elif img.dim() == 5 and img.size(0) > 1:\n                B, N, C, H, W = img.size()\n                img = img.reshape(B * N, C, H, W)\n            if self.use_grid_mask:\n                img = self.grid_mask(img)\n\n            img_feats = self.img_backbone(img)\n            if isinstance(img_feats, dict):\n                img_feats = list(img_feats.values())\n        else:\n            return None\n        if self.with_img_neck:\n            img_feats = self.img_neck(img_feats)\n\n        img_feats_reshaped = []\n        for img_feat in img_feats:\n            BN, C, H, W = img_feat.size()\n            if len_queue is not None:\n                img_feats_reshaped.append(img_feat.view(int(B/len_queue), len_queue, int(BN / B), C, H, W))\n            else:\n                img_feats_reshaped.append(img_feat.view(B, int(BN / B), C, H, W))\n        return img_feats_reshaped\n\n    @auto_fp16(apply_to=('img'), out_fp32=True)\n    def extract_feat(self, img, img_metas=None, len_queue=None):\n        #import pdb;pdb.set_trace()\n        \"\"\"Extract features from images and points.\"\"\"\n\n        img_feats = self.extract_img_feat(img, img_metas, len_queue=len_queue)\n        \n        return img_feats\n\n    def forward_pts_train(self,\n                          pts_feats,\n                          gt_bboxes_3d,\n                          gt_labels_3d,\n                          map_gt_bboxes_3d,\n                          map_gt_labels_3d,                          \n                          img_metas,\n                          gt_bboxes_ignore=None,\n                          map_gt_bboxes_ignore=None,\n                          prev_bev=None,\n                          ego_his_trajs=None,\n                          ego_fut_trajs=None,\n                          ego_fut_masks=None,\n                          ego_fut_cmd=None,\n                          ego_lcf_feat=None,\n                          gt_attr_labels=None):\n        \"\"\"Forward function'\n        Args:\n            pts_feats (list[torch.Tensor]): Features of point cloud branch\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`]): Ground truth\n                boxes for each sample.\n            gt_labels_3d (list[torch.Tensor]): Ground truth labels for\n                boxes of each sampole\n            img_metas (list[dict]): Meta information of samples.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                boxes to be ignored. Defaults to None.\n            prev_bev (torch.Tensor, optional): BEV features of previous frame.\n        Returns:\n            dict: Losses of each branch.\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        outs = self.pts_bbox_head(pts_feats, img_metas, prev_bev, ego_fut_cmd,\n                                  ego_his_trajs=ego_his_trajs, ego_lcf_feat=ego_lcf_feat)\n        loss_inputs = [\n            gt_bboxes_3d, gt_labels_3d, map_gt_bboxes_3d, map_gt_labels_3d,\n            outs, ego_fut_trajs, ego_fut_masks, ego_fut_cmd, gt_attr_labels\n        ]\n        losses = self.pts_bbox_head.loss(*loss_inputs, img_metas=img_metas)\n        return losses\n\n    def forward_dummy(self, img):\n        #import pdb;pdb.set_trace()\n        dummy_metas = None\n        return self.forward_test(img=img, img_metas=[[dummy_metas]])\n\n    def forward(self, inputs,return_loss=True,rescale=False):\n        \"\"\"Calls either forward_train or forward_test depending on whether\n        return_loss=True.\n        Note this setting will change the expected inputs. When\n        `return_loss=True`, img and img_metas are single-nested (i.e.\n        torch.Tensor and list[dict]), and when `resturn_loss=False`, img and\n        img_metas should be double nested (i.e.  list[torch.Tensor],\n        list[list[dict]]), with the outer list indicating test time\n        augmentations.\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        if return_loss:\n            losses = self.forward_train(**inputs)\n            loss, log_vars = self._parse_losses(losses)\n            outputs = dict(\n                loss=loss, log_vars=log_vars, num_samples=len(inputs['img_metas']))\n            return outputs\n        else:\n            outputs = self.forward_test(**inputs,rescale=rescale)            \n            return outputs\n    \n    def obtain_history_bev(self, imgs_queue, img_metas_list):\n        \"\"\"Obtain history BEV features iteratively. To save GPU memory, gradients are not calculated.\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        self.eval()\n\n        with torch.no_grad():\n            prev_bev = None\n            bs, len_queue, num_cams, C, H, W = imgs_queue.shape\n            imgs_queue = imgs_queue.reshape(bs*len_queue, num_cams, C, H, W)\n            img_feats_list = self.extract_feat(img=imgs_queue, len_queue=len_queue)\n            for i in range(len_queue):\n                img_metas = [each[i] for each in img_metas_list]\n                # img_feats = self.extract_feat(img=img, img_metas=img_metas)\n                img_feats = [each_scale[:, i] for each_scale in img_feats_list]\n                prev_bev = self.pts_bbox_head(\n                    img_feats, img_metas, prev_bev, only_bev=True)\n            self.train()\n            return prev_bev\n\n    # @auto_fp16(apply_to=('img', 'points'))\n    @force_fp32(apply_to=('img','points','prev_bev'))\n    def forward_train(self,\n                      points=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      map_gt_bboxes_3d=None,\n                      map_gt_labels_3d=None,\n                      gt_labels=None,\n                      gt_bboxes=None,\n                      img=None,\n                      proposals=None,\n                      gt_bboxes_ignore=None,\n                      map_gt_bboxes_ignore=None,\n                      img_depth=None,\n                      img_mask=None,\n                      ego_his_trajs=None,\n                      ego_fut_trajs=None,\n                      ego_fut_masks=None,\n                      ego_fut_cmd=None,\n                      ego_lcf_feat=None,\n                      gt_attr_labels=None,\n                      **kwargs\n                      ):\n        \"\"\"Forward training function.\n        Args:\n            points (list[torch.Tensor], optional): Points of each sample.\n                Defaults to None.\n            img_metas (list[dict], optional): Meta information of each sample.\n                Defaults to None.\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`], optional):\n                Ground truth 3D boxes. Defaults to None.\n            gt_labels_3d (list[torch.Tensor], optional): Ground truth labels\n                of 3D boxes. Defaults to None.\n            gt_labels (list[torch.Tensor], optional): Ground truth labels\n                of 2D boxes in images. Defaults to None.\n            gt_bboxes (list[torch.Tensor], optional): Ground truth 2D boxes in\n                images. Defaults to None.\n            img (torch.Tensor optional): Images of each sample with shape\n                (N, C, H, W). Defaults to None.\n            proposals ([list[torch.Tensor], optional): Predicted proposals\n                used for training Fast RCNN. Defaults to None.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                2D boxes in images to be ignored. Defaults to None.\n        Returns:\n            dict: Losses of different branches.\n        \"\"\"\n        #import pdb;pdb.set_trace()\n        len_queue = img.size(1)\n        prev_img = img[:, :-1, ...]\n        img = img[:, -1, ...]\n\n        prev_img_metas = copy.deepcopy(img_metas)\n        # prev_bev = self.obtain_history_bev(prev_img, prev_img_metas)\n        \n        prev_bev = self.obtain_history_bev(prev_img, prev_img_metas) if len_queue > 1 else None\n\n        img_metas = [each[len_queue-1] for each in img_metas]\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        losses = dict()\n        losses_pts = self.forward_pts_train(img_feats, gt_bboxes_3d, gt_labels_3d,\n                                            map_gt_bboxes_3d, map_gt_labels_3d, img_metas,\n                                            gt_bboxes_ignore, map_gt_bboxes_ignore, prev_bev,\n                                            ego_his_trajs=ego_his_trajs, ego_fut_trajs=ego_fut_trajs,\n                                            ego_fut_masks=ego_fut_masks, ego_fut_cmd=ego_fut_cmd,\n                                            ego_lcf_feat=ego_lcf_feat, gt_attr_labels=gt_attr_labels)\n\n        losses.update(losses_pts)\n        return losses\n\n    def forward_test(\n        self,\n        img_metas,\n        gt_bboxes_3d=None,\n        gt_labels_3d=None,\n        img=None,\n        ego_his_trajs=None,\n        ego_fut_trajs=None,\n        ego_fut_cmd=None,\n        ego_lcf_feat=None,\n        gt_attr_labels=None,\n        **kwargs\n    ):\n        #import pdb;pdb.set_trace()\n        for var, name in [(img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError('{} must be a list, but got {}'.format(\n                    name, type(var)))\n        img = [img] if img is None else img\n\n        if self.prev_frame_num > 0:\n            if len(self.prev_frame_infos) < self.prev_frame_num:\n                self.prev_frame_info = {\n                \"prev_bev\": None,\n                \"scene_token\": None,\n                \"prev_pos\": 0,\n                \"prev_angle\": 0,\n            }\n            else:\n                self.prev_frame_info = self.prev_frame_infos.pop(0)\n\n\n\n\n        if img_metas[0][0]['scene_token'] != self.prev_frame_info['scene_token']:\n            # the first sample of each scene is truncated\n            self.prev_frame_info['prev_bev'] = None\n        # update idx\n        self.prev_frame_info['scene_token'] = img_metas[0][0]['scene_token']\n\n        # do not use temporal information\n        if not self.video_test_mode:\n            self.prev_frame_info['prev_bev'] = None\n\n        # Get the delta of ego position and angle between two timestamps.\n        tmp_pos = copy.deepcopy(img_metas[0][0]['can_bus'][:3])\n        tmp_angle = copy.deepcopy(img_metas[0][0]['can_bus'][-1])\n        if self.prev_frame_info['prev_bev'] is not None:\n            img_metas[0][0]['can_bus'][:3] -= self.prev_frame_info['prev_pos']\n            img_metas[0][0]['can_bus'][-1] -= self.prev_frame_info['prev_angle']\n        else:\n            img_metas[0][0]['can_bus'][-1] = 0\n            img_metas[0][0]['can_bus'][:3] = 0\n\n\n        if ego_his_trajs is not None:\n            ego_his_trajs=ego_his_trajs[0]\n        if ego_fut_trajs is not None:\n            ego_fut_trajs=ego_fut_trajs[0]\n        if ego_fut_cmd is not None:\n            ego_fut_cmd=ego_fut_cmd[0]\n        if ego_lcf_feat is not None:\n            ego_lcf_feat=ego_lcf_feat[0]\n\n        new_prev_bev, bbox_results = self.simple_test(\n            img_metas=img_metas[0],\n            img=img[0],\n            prev_bev=self.prev_frame_info['prev_bev'],\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            ego_his_trajs=ego_his_trajs,\n            ego_fut_trajs=ego_fut_trajs,\n            ego_fut_cmd=ego_fut_cmd,\n            ego_lcf_feat=ego_lcf_feat,\n            gt_attr_labels=gt_attr_labels,\n            **kwargs\n        )\n        # During inference, we save the BEV features and ego motion of each timestamp.\n        self.prev_frame_info['prev_pos'] = tmp_pos\n        self.prev_frame_info['prev_angle'] = tmp_angle\n        self.prev_frame_info['prev_bev'] = new_prev_bev\n        if self.prev_frame_num > 0:        \n            self.prev_frame_infos.append(self.prev_frame_info)        \n\n        return bbox_results\n\n    def simple_test(\n        self,\n        img_metas,\n        gt_bboxes_3d,\n        gt_labels_3d,\n        img=None,\n        prev_bev=None,\n        points=None,\n        fut_valid_flag=None,\n        rescale=False,\n        ego_his_trajs=None,\n        ego_fut_trajs=None,\n        ego_fut_cmd=None,\n        ego_lcf_feat=None,\n        gt_attr_labels=None,\n        **kwargs\n    ):\n        \"\"\"Test function without augmentaiton.\"\"\"\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        bbox_list = [dict() for i in range(len(img_metas))]\n        new_prev_bev, bbox_pts, metric_dict = self.simple_test_pts(\n            img_feats,\n            img_metas,\n            gt_bboxes_3d,\n            gt_labels_3d,\n            prev_bev,\n            fut_valid_flag=fut_valid_flag,\n            rescale=rescale,\n            start=None,\n            ego_his_trajs=ego_his_trajs,\n            ego_fut_trajs=ego_fut_trajs,\n            ego_fut_cmd=ego_fut_cmd,\n            ego_lcf_feat=ego_lcf_feat,\n            gt_attr_labels=gt_attr_labels,\n        )\n        for result_dict, pts_bbox in zip(bbox_list, bbox_pts):\n            result_dict['pts_bbox'] = pts_bbox\n            result_dict['metric_results'] = metric_dict\n\n        return new_prev_bev, bbox_list\n\n    def simple_test_pts(\n        self,\n        x,\n        img_metas,\n        gt_bboxes_3d,\n        gt_labels_3d,\n        prev_bev=None,\n        fut_valid_flag=None,\n        rescale=False,\n        start=None,\n        ego_his_trajs=None,\n        ego_fut_trajs=None,\n        ego_fut_cmd=None,\n        ego_lcf_feat=None,\n        gt_attr_labels=None,\n    ):\n        \"\"\"Test function\"\"\"\n        mapped_class_names = [\n            'car', 'truck', 'construction_vehicle', 'bus',\n            'trailer', 'barrier', 'motorcycle', 'bicycle', \n            'pedestrian', 'traffic_cone'\n        ]\n\n        outs = self.pts_bbox_head(x, img_metas, prev_bev=prev_bev,\n                                  ego_his_trajs=ego_his_trajs, ego_lcf_feat=ego_lcf_feat)\n        #import pdb;pdb.set_trace()\n        bbox_list = self.pts_bbox_head.get_bboxes(outs, img_metas, rescale=rescale)\n        #import pdb;pdb.set_trace()\n        bbox_results = []\n        for i, (bboxes, scores, labels, trajs, map_bboxes, map_scores, map_labels, map_pts) in enumerate(bbox_list):\n            bbox_result = bbox3d2result(bboxes, scores, labels)\n            bbox_result['trajs_3d'] = trajs.cpu()\n            map_bbox_result = self.map_pred2result(map_bboxes, map_scores, map_labels, map_pts)\n            bbox_result.update(map_bbox_result)\n            bbox_result['ego_fut_preds_refine'] = outs['ego_fut_preds_refine'][i].cpu()\n            bbox_result['ego_fut_classification_refine'] = outs['ego_fut_classification_refine'][i].cpu()\n            bbox_result['ego_fut_cmd'] = ego_fut_cmd.cpu()\n            bbox_results.append(bbox_result)\n\n        metric_dict = None\n\n        if gt_attr_labels is not None:\n\n\n            assert len(bbox_results) == 1, 'only support batch_size=1 now'\n            score_threshold = 0.6\n            with torch.no_grad():\n                c_bbox_results = copy.deepcopy(bbox_results)\n\n                bbox_result = c_bbox_results[0]\n                gt_bbox = gt_bboxes_3d[0][0]\n                gt_label = gt_labels_3d[0][0].to('cpu')\n                gt_attr_label = gt_attr_labels[0][0].to('cpu')\n                fut_valid_flag = bool(fut_valid_flag[0][0])\n                # filter pred bbox by score_threshold\n                mask = bbox_result['scores_3d'] > score_threshold\n                bbox_result['boxes_3d'] = bbox_result['boxes_3d'][mask]\n                bbox_result['scores_3d'] = bbox_result['scores_3d'][mask]\n                bbox_result['labels_3d'] = bbox_result['labels_3d'][mask]\n                bbox_result['trajs_3d'] = bbox_result['trajs_3d'][mask]\n\n                matched_bbox_result = self.assign_pred_to_gt_vip3d(\n                    bbox_result, gt_bbox, gt_label)\n\n                metric_dict = self.compute_motion_metric_vip3d(\n                    gt_bbox, gt_label, gt_attr_label, bbox_result,\n                    matched_bbox_result, mapped_class_names)\n\n                # ego planning metric\n                assert ego_fut_trajs.shape[0] == 1, 'only support batch_size=1 for testing'\n                ego_fut_preds = bbox_result['ego_fut_preds_refine']\n                #import pdb;pdb.set_trace()\n                ego_fut_trajs = ego_fut_trajs[0, 0] # [6,2]\n                ego_fut_cmd = ego_fut_cmd[0, 0, 0] # [6]\n                ego_fut_cmd_idx = torch.nonzero(ego_fut_cmd)[0, 0]\n                #import pdb;pdb.set_trace()\n                ego_fut_pred = ego_fut_preds[ego_fut_cmd_idx] # [6,6,2]\n                #import pdb;pdb.set_trace()\n                ego_classification = bbox_result['ego_fut_classification_refine'].reshape(6,6,-1)\n                ego_classification = ego_classification.sum(dim=-1)\n                ego_classification = ego_classification[ego_fut_cmd_idx]\n                ego_fut_pred = ego_fut_pred[ego_classification.argmax()]\n                #import pdb;pdb.set_trace()\n                ego_fut_pred = ego_fut_pred.cumsum(dim=-2)\n                ego_fut_trajs = ego_fut_trajs.cumsum(dim=-2)\n\n                metric_dict_planner_stp3 = self.compute_planner_metric_stp3(\n                    pred_ego_fut_trajs = ego_fut_pred[None],\n                    gt_ego_fut_trajs = ego_fut_trajs[None],\n                    gt_agent_boxes = gt_bbox,\n                    gt_agent_feats = gt_attr_label.unsqueeze(0),\n                    fut_valid_flag = fut_valid_flag\n                )\n                metric_dict.update(metric_dict_planner_stp3)\n\n        return outs['bev_embed'], bbox_results, metric_dict\n\n    def map_pred2result(self, bboxes, scores, labels, pts, attrs=None):\n        \"\"\"Convert detection results to a list of numpy arrays.\n\n        Args:\n            bboxes (torch.Tensor): Bounding boxes with shape of (n, 5).\n            labels (torch.Tensor): Labels with shape of (n, ).\n            scores (torch.Tensor): Scores with shape of (n, ).\n            attrs (torch.Tensor, optional): Attributes with shape of (n, ). \\\n                Defaults to None.\n\n        Returns:\n            dict[str, torch.Tensor]: Bounding box results in cpu mode.\n\n                - boxes_3d (torch.Tensor): 3D boxes.\n                - scores (torch.Tensor): Prediction scores.\n                - labels_3d (torch.Tensor): Box labels.\n                - attrs_3d (torch.Tensor, optional): Box attributes.\n        \"\"\"\n        result_dict = dict(\n            map_boxes_3d=bboxes.to('cpu'),\n            map_scores_3d=scores.cpu(),\n            map_labels_3d=labels.cpu(),\n            map_pts_3d=pts.to('cpu'))\n\n        if attrs is not None:\n            result_dict['map_attrs_3d'] = attrs.cpu()\n\n        return result_dict\n\n    def assign_pred_to_gt_vip3d(\n        self,\n        bbox_result,\n        gt_bbox,\n        gt_label,\n        match_dis_thresh=2.0\n    ):\n        \"\"\"Assign pred boxs to gt boxs according to object center preds in lcf.\n        Args:\n            bbox_result (dict): Predictions.\n                'boxes_3d': (LiDARInstance3DBoxes)\n                'scores_3d': (Tensor), [num_pred_bbox]\n                'labels_3d': (Tensor), [num_pred_bbox]\n                'trajs_3d': (Tensor), [fut_ts*2]\n            gt_bboxs (LiDARInstance3DBoxes): GT Bboxs.\n            gt_label (Tensor): GT labels for gt_bbox, [num_gt_bbox].\n            match_dis_thresh (float): dis thresh for determine a positive sample for a gt bbox.\n\n        Returns:\n            matched_bbox_result (np.array): assigned pred index for each gt box [num_gt_bbox].\n        \"\"\"     \n        dynamic_list = [0,1,3,4,6,7,8]\n        matched_bbox_result = torch.ones(\n            (len(gt_bbox)), dtype=torch.long) * -1  # -1: not assigned\n        gt_centers = gt_bbox.center[:, :2]\n        pred_centers = bbox_result['boxes_3d'].center[:, :2]\n        dist = torch.linalg.norm(pred_centers[:, None, :] - gt_centers[None, :, :], dim=-1)\n        pred_not_dyn = [label not in dynamic_list for label in bbox_result['labels_3d']]\n        gt_not_dyn = [label not in dynamic_list for label in gt_label]\n        dist[pred_not_dyn] = 1e6\n        dist[:, gt_not_dyn] = 1e6\n        dist[dist > match_dis_thresh] = 1e6\n\n        r_list, c_list = linear_sum_assignment(dist)\n\n        for i in range(len(r_list)):\n            if dist[r_list[i], c_list[i]] <= match_dis_thresh:\n                matched_bbox_result[c_list[i]] = r_list[i]\n\n        return matched_bbox_result\n\n    def compute_motion_metric_vip3d(\n        self,\n        gt_bbox,\n        gt_label,\n        gt_attr_label,\n        pred_bbox,\n        matched_bbox_result,\n        mapped_class_names,\n        match_dis_thresh=2.0,\n    ):\n        \"\"\"Compute EPA metric for one sample.\n        Args:\n            gt_bboxs (LiDARInstance3DBoxes): GT Bboxs.\n            gt_label (Tensor): GT labels for gt_bbox, [num_gt_bbox].\n            pred_bbox (dict): Predictions.\n                'boxes_3d': (LiDARInstance3DBoxes)\n                'scores_3d': (Tensor), [num_pred_bbox]\n                'labels_3d': (Tensor), [num_pred_bbox]\n                'trajs_3d': (Tensor), [fut_ts*2]\n            matched_bbox_result (np.array): assigned pred index for each gt box [num_gt_bbox].\n            match_dis_thresh (float): dis thresh for determine a positive sample for a gt bbox.\n\n        Returns:\n            EPA_dict (dict): EPA metric dict of each cared class.\n        \"\"\"\n        motion_cls_names = ['car', 'pedestrian']\n        motion_metric_names = ['gt', 'cnt_ade', 'cnt_fde', 'hit',\n                               'fp', 'ADE', 'FDE', 'MR']\n        \n        metric_dict = {}\n        for met in motion_metric_names:\n            for cls in motion_cls_names:\n                metric_dict[met+'_'+cls] = 0.0\n\n        veh_list = [0,1,3,4]\n        ignore_list = ['construction_vehicle', 'barrier',\n                       'traffic_cone', 'motorcycle', 'bicycle']\n\n        for i in range(pred_bbox['labels_3d'].shape[0]):\n            pred_bbox['labels_3d'][i] = 0 if pred_bbox['labels_3d'][i] in veh_list else pred_bbox['labels_3d'][i]\n            box_name = mapped_class_names[pred_bbox['labels_3d'][i]]\n            if box_name in ignore_list:\n                continue\n            if i not in matched_bbox_result:\n                metric_dict['fp_'+box_name] += 1\n\n        for i in range(gt_label.shape[0]):\n            gt_label[i] = 0 if gt_label[i] in veh_list else gt_label[i]\n            box_name = mapped_class_names[gt_label[i]]\n            if box_name in ignore_list:\n                continue\n            gt_fut_masks = gt_attr_label[i][self.fut_ts*2:self.fut_ts*3]\n            num_valid_ts = sum(gt_fut_masks==1)\n            if num_valid_ts == self.fut_ts:\n                metric_dict['gt_'+box_name] += 1\n            if matched_bbox_result[i] >= 0 and num_valid_ts > 0:\n                metric_dict['cnt_ade_'+box_name] += 1\n                m_pred_idx = matched_bbox_result[i]\n                gt_fut_trajs = gt_attr_label[i][:self.fut_ts*2].reshape(-1, 2)\n                gt_fut_trajs = gt_fut_trajs[:num_valid_ts]\n                pred_fut_trajs = pred_bbox['trajs_3d'][m_pred_idx].reshape(self.fut_mode, self.fut_ts, 2)\n                pred_fut_trajs = pred_fut_trajs[:, :num_valid_ts, :]\n                gt_fut_trajs = gt_fut_trajs.cumsum(dim=-2)\n                pred_fut_trajs = pred_fut_trajs.cumsum(dim=-2)\n                gt_fut_trajs = gt_fut_trajs + gt_bbox[i].center[0, :2]\n                pred_fut_trajs = pred_fut_trajs + pred_bbox['boxes_3d'][int(m_pred_idx)].center[0, :2]\n\n                dist = torch.linalg.norm(gt_fut_trajs[None, :, :] - pred_fut_trajs, dim=-1)\n                ade = dist.sum(-1) / num_valid_ts\n                ade = ade.min()\n\n                metric_dict['ADE_'+box_name] += ade\n                if num_valid_ts == self.fut_ts:\n                    fde = dist[:, -1].min()\n                    metric_dict['cnt_fde_'+box_name] += 1\n                    metric_dict['FDE_'+box_name] += fde\n                    if fde <= match_dis_thresh:\n                        metric_dict['hit_'+box_name] += 1\n                    else:\n                        metric_dict['MR_'+box_name] += 1\n\n        return metric_dict\n\n    ### same planning metric as stp3\n    def compute_planner_metric_stp3(\n        self,\n        pred_ego_fut_trajs,\n        gt_ego_fut_trajs,\n        gt_agent_boxes,\n        gt_agent_feats,\n        fut_valid_flag\n    ):\n        \"\"\"Compute planner metric for one sample same as stp3.\"\"\"\n        metric_dict = {\n            'plan_L2_1s':0,\n            'plan_L2_2s':0,\n            'plan_L2_3s':0,\n            'plan_obj_col_1s':0,\n            'plan_obj_col_2s':0,\n            'plan_obj_col_3s':0,\n            'plan_obj_box_col_1s':0,\n            'plan_obj_box_col_2s':0,\n            'plan_obj_box_col_3s':0,\n        }\n        metric_dict['fut_valid_flag'] = fut_valid_flag\n        future_second = 3\n        assert pred_ego_fut_trajs.shape[0] == 1, 'only support bs=1'\n        if self.planning_metric is None:\n            self.planning_metric = PlanningMetric()\n        segmentation, pedestrian = self.planning_metric.get_label(\n            gt_agent_boxes, gt_agent_feats)\n        occupancy = torch.logical_or(segmentation, pedestrian)\n\n        for i in range(future_second):\n            if fut_valid_flag:\n                cur_time = (i+1)*2\n                traj_L2 = self.planning_metric.compute_L2(\n                    pred_ego_fut_trajs[0, :cur_time].detach().to(gt_ego_fut_trajs.device),\n                    gt_ego_fut_trajs[0, :cur_time]\n                )\n                obj_coll, obj_box_coll = self.planning_metric.evaluate_coll(\n                    pred_ego_fut_trajs[:, :cur_time].detach(),\n                    gt_ego_fut_trajs[:, :cur_time],\n                    occupancy)\n                metric_dict['plan_L2_{}s'.format(i+1)] = traj_L2\n                metric_dict['plan_obj_col_{}s'.format(i+1)] = obj_coll.mean().item()\n                metric_dict['plan_obj_box_col_{}s'.format(i+1)] = obj_box_coll.mean().item()\n            else:\n                metric_dict['plan_L2_{}s'.format(i+1)] = 0.0\n                metric_dict['plan_obj_col_{}s'.format(i+1)] = 0.0\n                metric_dict['plan_obj_box_col_{}s'.format(i+1)] = 0.0\n            \n        return metric_dict\n\n    def set_epoch(self, epoch): \n        self.pts_bbox_head.epoch = epoch"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/SpMomAD.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/VAD.py",
    "content": "import time\nimport copy\n\nimport torch\nfrom mmcv.models import DETECTORS\nfrom mmcv.core.bbox.transforms import bbox3d2result\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom scipy.optimize import linear_sum_assignment\nfrom mmcv.models.detectors.mvx_two_stage import MVXTwoStageDetector\n\nfrom mmcv.models.utils.grid_mask import GridMask\nfrom mmcv.models.dense_heads.planning_head_plugin.metric_stp3 import PlanningMetric\n\n\n@DETECTORS.register_module()\nclass VAD(MVXTwoStageDetector):\n    \"\"\"VAD model.\n    \"\"\"\n    def __init__(self,\n                 use_grid_mask=False,\n                 pts_voxel_layer=None,\n                 pts_voxel_encoder=None,\n                 pts_middle_encoder=None,\n                 pts_fusion_layer=None,\n                 img_backbone=None,\n                 pts_backbone=None,\n                 img_neck=None,\n                 pts_neck=None,\n                 pts_bbox_head=None,\n                 img_roi_head=None,\n                 img_rpn_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 pretrained=None,\n                 video_test_mode=False,\n                 prev_frame_num=0,\n                 fut_ts=6,\n                 fut_mode=6\n                 ):\n\n        super(VAD,\n              self).__init__(pts_voxel_layer, pts_voxel_encoder,\n                             pts_middle_encoder, pts_fusion_layer,\n                             img_backbone, pts_backbone, img_neck, pts_neck,\n                             pts_bbox_head, img_roi_head, img_rpn_head,\n                             train_cfg, test_cfg, pretrained)\n        self.grid_mask = GridMask(\n            True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7)\n        #import pdb;pdb.set_trace()\n        self.use_grid_mask = use_grid_mask\n        self.fp16_enabled = False\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.valid_fut_ts = pts_bbox_head['valid_fut_ts']\n        self.prev_frame_num = prev_frame_num\n        self.prev_frame_infos = []\n\n        # temporal\n        self.video_test_mode = video_test_mode\n        self.prev_frame_info = {\n            'prev_bev': None,\n            'scene_token': None,\n            'prev_pos': 0,\n            'prev_angle': 0,\n        }\n\n        self.planning_metric = None\n\n    def extract_img_feat(self, img, img_metas, len_queue=None):\n        \"\"\"Extract features of images.\"\"\"\n        B = img.size(0)\n        if img is not None:\n            \n            # input_shape = img.shape[-2:]\n            # # update real input shape of each single img\n            # for img_meta in img_metas:\n            #     img_meta.update(input_shape=input_shape)\n\n            if img.dim() == 5 and img.size(0) == 1:\n                img.squeeze_()\n            elif img.dim() == 5 and img.size(0) > 1:\n                B, N, C, H, W = img.size()\n                img = img.reshape(B * N, C, H, W)\n            if self.use_grid_mask:\n                img = self.grid_mask(img)\n\n            img_feats = self.img_backbone(img)\n            if isinstance(img_feats, dict):\n                img_feats = list(img_feats.values())\n        else:\n            return None\n        if self.with_img_neck:\n            img_feats = self.img_neck(img_feats)\n\n        img_feats_reshaped = []\n        for img_feat in img_feats:\n            BN, C, H, W = img_feat.size()\n            if len_queue is not None:\n                img_feats_reshaped.append(img_feat.view(int(B/len_queue), len_queue, int(BN / B), C, H, W))\n            else:\n                img_feats_reshaped.append(img_feat.view(B, int(BN / B), C, H, W))\n        return img_feats_reshaped\n\n    @auto_fp16(apply_to=('img'), out_fp32=True)\n    def extract_feat(self, img, img_metas=None, len_queue=None):\n        \"\"\"Extract features from images and points.\"\"\"\n\n        img_feats = self.extract_img_feat(img, img_metas, len_queue=len_queue)\n        \n        return img_feats\n\n    def forward_pts_train(self,\n                          pts_feats,\n                          gt_bboxes_3d,\n                          gt_labels_3d,\n                          map_gt_bboxes_3d,\n                          map_gt_labels_3d,                          \n                          img_metas,\n                          gt_bboxes_ignore=None,\n                          map_gt_bboxes_ignore=None,\n                          prev_bev=None,\n                          ego_his_trajs=None,\n                          ego_fut_trajs=None,\n                          ego_fut_masks=None,\n                          ego_fut_cmd=None,\n                          ego_lcf_feat=None,\n                          gt_attr_labels=None):\n        \"\"\"Forward function'\n        Args:\n            pts_feats (list[torch.Tensor]): Features of point cloud branch\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`]): Ground truth\n                boxes for each sample.\n            gt_labels_3d (list[torch.Tensor]): Ground truth labels for\n                boxes of each sampole\n            img_metas (list[dict]): Meta information of samples.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                boxes to be ignored. Defaults to None.\n            prev_bev (torch.Tensor, optional): BEV features of previous frame.\n        Returns:\n            dict: Losses of each branch.\n        \"\"\"\n\n        outs = self.pts_bbox_head(pts_feats, img_metas, prev_bev,\n                                  ego_his_trajs=ego_his_trajs, ego_lcf_feat=ego_lcf_feat)\n        loss_inputs = [\n            gt_bboxes_3d, gt_labels_3d, map_gt_bboxes_3d, map_gt_labels_3d,\n            outs, ego_fut_trajs, ego_fut_masks, ego_fut_cmd, gt_attr_labels\n        ]\n        losses = self.pts_bbox_head.loss(*loss_inputs, img_metas=img_metas)\n        return losses\n\n    def forward_dummy(self, img):\n        dummy_metas = None\n        return self.forward_test(img=img, img_metas=[[dummy_metas]])\n\n    def forward(self, inputs,return_loss=True,rescale=False):\n        \"\"\"Calls either forward_train or forward_test depending on whether\n        return_loss=True.\n        Note this setting will change the expected inputs. When\n        `return_loss=True`, img and img_metas are single-nested (i.e.\n        torch.Tensor and list[dict]), and when `resturn_loss=False`, img and\n        img_metas should be double nested (i.e.  list[torch.Tensor],\n        list[list[dict]]), with the outer list indicating test time\n        augmentations.\n        \"\"\"\n        if return_loss:\n            losses = self.forward_train(**inputs)\n            loss, log_vars = self._parse_losses(losses)\n            outputs = dict(\n                loss=loss, log_vars=log_vars, num_samples=len(inputs['img_metas']))\n            return outputs\n        else:\n            outputs = self.forward_test(**inputs,rescale=rescale)            \n            return outputs\n    \n    def obtain_history_bev(self, imgs_queue, img_metas_list):\n        \"\"\"Obtain history BEV features iteratively. To save GPU memory, gradients are not calculated.\n        \"\"\"\n        self.eval()\n\n        with torch.no_grad():\n            prev_bev = None\n            bs, len_queue, num_cams, C, H, W = imgs_queue.shape\n            imgs_queue = imgs_queue.reshape(bs*len_queue, num_cams, C, H, W)\n            img_feats_list = self.extract_feat(img=imgs_queue, len_queue=len_queue)\n            for i in range(len_queue):\n                img_metas = [each[i] for each in img_metas_list]\n                # img_feats = self.extract_feat(img=img, img_metas=img_metas)\n                img_feats = [each_scale[:, i] for each_scale in img_feats_list]\n                prev_bev = self.pts_bbox_head(\n                    img_feats, img_metas, prev_bev, only_bev=True)\n            self.train()\n            return prev_bev\n\n    # @auto_fp16(apply_to=('img', 'points'))\n    @force_fp32(apply_to=('img','points','prev_bev'))\n    def forward_train(self,\n                      points=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      map_gt_bboxes_3d=None,\n                      map_gt_labels_3d=None,\n                      gt_labels=None,\n                      gt_bboxes=None,\n                      img=None,\n                      proposals=None,\n                      gt_bboxes_ignore=None,\n                      map_gt_bboxes_ignore=None,\n                      img_depth=None,\n                      img_mask=None,\n                      ego_his_trajs=None,\n                      ego_fut_trajs=None,\n                      ego_fut_masks=None,\n                      ego_fut_cmd=None,\n                      ego_lcf_feat=None,\n                      gt_attr_labels=None,\n                      **kwargs\n                      ):\n        \"\"\"Forward training function.\n        Args:\n            points (list[torch.Tensor], optional): Points of each sample.\n                Defaults to None.\n            img_metas (list[dict], optional): Meta information of each sample.\n                Defaults to None.\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`], optional):\n                Ground truth 3D boxes. Defaults to None.\n            gt_labels_3d (list[torch.Tensor], optional): Ground truth labels\n                of 3D boxes. Defaults to None.\n            gt_labels (list[torch.Tensor], optional): Ground truth labels\n                of 2D boxes in images. Defaults to None.\n            gt_bboxes (list[torch.Tensor], optional): Ground truth 2D boxes in\n                images. Defaults to None.\n            img (torch.Tensor optional): Images of each sample with shape\n                (N, C, H, W). Defaults to None.\n            proposals ([list[torch.Tensor], optional): Predicted proposals\n                used for training Fast RCNN. Defaults to None.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                2D boxes in images to be ignored. Defaults to None.\n        Returns:\n            dict: Losses of different branches.\n        \"\"\"\n        \n        len_queue = img.size(1)\n        prev_img = img[:, :-1, ...]\n        img = img[:, -1, ...]\n\n        prev_img_metas = copy.deepcopy(img_metas)\n        # prev_bev = self.obtain_history_bev(prev_img, prev_img_metas)\n        # import pdb;pdb.set_trace()\n        prev_bev = self.obtain_history_bev(prev_img, prev_img_metas) if len_queue > 1 else None\n\n        img_metas = [each[len_queue-1] for each in img_metas]\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        losses = dict()\n        losses_pts = self.forward_pts_train(img_feats, gt_bboxes_3d, gt_labels_3d,\n                                            map_gt_bboxes_3d, map_gt_labels_3d, img_metas,\n                                            gt_bboxes_ignore, map_gt_bboxes_ignore, prev_bev,\n                                            ego_his_trajs=ego_his_trajs, ego_fut_trajs=ego_fut_trajs,\n                                            ego_fut_masks=ego_fut_masks, ego_fut_cmd=ego_fut_cmd,\n                                            ego_lcf_feat=ego_lcf_feat, gt_attr_labels=gt_attr_labels)\n\n        losses.update(losses_pts)\n        return losses\n\n    def forward_test(\n        self,\n        img_metas,\n        gt_bboxes_3d=None,\n        gt_labels_3d=None,\n        img=None,\n        ego_his_trajs=None,\n        ego_fut_trajs=None,\n        ego_fut_cmd=None,\n        ego_lcf_feat=None,\n        gt_attr_labels=None,\n        **kwargs\n    ):\n        for var, name in [(img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError('{} must be a list, but got {}'.format(\n                    name, type(var)))\n        img = [img] if img is None else img\n\n        if self.prev_frame_num > 0:\n            if len(self.prev_frame_infos) < self.prev_frame_num:\n                self.prev_frame_info = {\n                \"prev_bev\": None,\n                \"scene_token\": None,\n                \"prev_pos\": 0,\n                \"prev_angle\": 0,\n            }\n            else:\n                self.prev_frame_info = self.prev_frame_infos.pop(0)\n\n\n\n\n        if img_metas[0][0]['scene_token'] != self.prev_frame_info['scene_token']:\n            # the first sample of each scene is truncated\n            self.prev_frame_info['prev_bev'] = None\n        # update idx\n        self.prev_frame_info['scene_token'] = img_metas[0][0]['scene_token']\n\n        # do not use temporal information\n        if not self.video_test_mode:\n            self.prev_frame_info['prev_bev'] = None\n\n        # Get the delta of ego position and angle between two timestamps.\n        tmp_pos = copy.deepcopy(img_metas[0][0]['can_bus'][:3])\n        tmp_angle = copy.deepcopy(img_metas[0][0]['can_bus'][-1])\n        if self.prev_frame_info['prev_bev'] is not None:\n            img_metas[0][0]['can_bus'][:3] -= self.prev_frame_info['prev_pos']\n            img_metas[0][0]['can_bus'][-1] -= self.prev_frame_info['prev_angle']\n        else:\n            img_metas[0][0]['can_bus'][-1] = 0\n            img_metas[0][0]['can_bus'][:3] = 0\n\n\n        if ego_his_trajs is not None:\n            ego_his_trajs=ego_his_trajs[0]\n        if ego_fut_trajs is not None:\n            ego_fut_trajs=ego_fut_trajs[0]\n        if ego_fut_cmd is not None:\n            ego_fut_cmd=ego_fut_cmd[0]\n        if ego_lcf_feat is not None:\n            ego_lcf_feat=ego_lcf_feat[0]\n\n        new_prev_bev, bbox_results = self.simple_test(\n            img_metas=img_metas[0],\n            img=img[0],\n            prev_bev=self.prev_frame_info['prev_bev'],\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            ego_his_trajs=ego_his_trajs,\n            ego_fut_trajs=ego_fut_trajs,\n            ego_fut_cmd=ego_fut_cmd,\n            ego_lcf_feat=ego_lcf_feat,\n            gt_attr_labels=gt_attr_labels,\n            **kwargs\n        )\n        # During inference, we save the BEV features and ego motion of each timestamp.\n        self.prev_frame_info['prev_pos'] = tmp_pos\n        self.prev_frame_info['prev_angle'] = tmp_angle\n        self.prev_frame_info['prev_bev'] = new_prev_bev\n        if self.prev_frame_num > 0:        \n            self.prev_frame_infos.append(self.prev_frame_info)        \n\n        return bbox_results\n\n    def simple_test(\n        self,\n        img_metas,\n        gt_bboxes_3d,\n        gt_labels_3d,\n        img=None,\n        prev_bev=None,\n        points=None,\n        fut_valid_flag=None,\n        rescale=False,\n        ego_his_trajs=None,\n        ego_fut_trajs=None,\n        ego_fut_cmd=None,\n        ego_lcf_feat=None,\n        gt_attr_labels=None,\n        **kwargs\n    ):\n        \"\"\"Test function without augmentaiton.\"\"\"\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        bbox_list = [dict() for i in range(len(img_metas))]\n        new_prev_bev, bbox_pts, metric_dict = self.simple_test_pts(\n            img_feats,\n            img_metas,\n            gt_bboxes_3d,\n            gt_labels_3d,\n            prev_bev,\n            fut_valid_flag=fut_valid_flag,\n            rescale=rescale,\n            start=None,\n            ego_his_trajs=ego_his_trajs,\n            ego_fut_trajs=ego_fut_trajs,\n            ego_fut_cmd=ego_fut_cmd,\n            ego_lcf_feat=ego_lcf_feat,\n            gt_attr_labels=gt_attr_labels,\n        )\n        for result_dict, pts_bbox in zip(bbox_list, bbox_pts):\n            result_dict['pts_bbox'] = pts_bbox\n            result_dict['metric_results'] = metric_dict\n\n        return new_prev_bev, bbox_list\n\n    def simple_test_pts(\n        self,\n        x,\n        img_metas,\n        gt_bboxes_3d,\n        gt_labels_3d,\n        prev_bev=None,\n        fut_valid_flag=None,\n        rescale=False,\n        start=None,\n        ego_his_trajs=None,\n        ego_fut_trajs=None,\n        ego_fut_cmd=None,\n        ego_lcf_feat=None,\n        gt_attr_labels=None,\n    ):\n        \"\"\"Test function\"\"\"\n        mapped_class_names = [\n            'car', 'truck', 'construction_vehicle', 'bus',\n            'trailer', 'barrier', 'motorcycle', 'bicycle', \n            'pedestrian', 'traffic_cone'\n        ]\n\n        outs = self.pts_bbox_head(x, img_metas, prev_bev=prev_bev,\n                                  ego_his_trajs=ego_his_trajs, ego_lcf_feat=ego_lcf_feat)\n        bbox_list = self.pts_bbox_head.get_bboxes(outs, img_metas, rescale=rescale)\n\n        bbox_results = []\n        for i, (bboxes, scores, labels, trajs, map_bboxes, \\\n                map_scores, map_labels, map_pts) in enumerate(bbox_list):\n            bbox_result = bbox3d2result(bboxes, scores, labels)\n            bbox_result['trajs_3d'] = trajs.cpu()\n            map_bbox_result = self.map_pred2result(map_bboxes, map_scores, map_labels, map_pts)\n            bbox_result.update(map_bbox_result)\n            bbox_result['ego_fut_preds'] = outs['ego_fut_preds'][i].cpu()\n            bbox_result['ego_fut_cmd'] = ego_fut_cmd.cpu()\n            bbox_results.append(bbox_result)\n\n        metric_dict = None\n\n        if gt_attr_labels is not None:\n\n\n            assert len(bbox_results) == 1, 'only support batch_size=1 now'\n            score_threshold = 0.6\n            with torch.no_grad():\n                c_bbox_results = copy.deepcopy(bbox_results)\n\n                bbox_result = c_bbox_results[0]\n                gt_bbox = gt_bboxes_3d[0][0]\n                gt_label = gt_labels_3d[0][0].to('cpu')\n                gt_attr_label = gt_attr_labels[0][0].to('cpu')\n                fut_valid_flag = bool(fut_valid_flag[0][0])\n                # filter pred bbox by score_threshold\n                mask = bbox_result['scores_3d'] > score_threshold\n                bbox_result['boxes_3d'] = bbox_result['boxes_3d'][mask]\n                bbox_result['scores_3d'] = bbox_result['scores_3d'][mask]\n                bbox_result['labels_3d'] = bbox_result['labels_3d'][mask]\n                bbox_result['trajs_3d'] = bbox_result['trajs_3d'][mask]\n\n                matched_bbox_result = self.assign_pred_to_gt_vip3d(\n                    bbox_result, gt_bbox, gt_label)\n\n                metric_dict = self.compute_motion_metric_vip3d(\n                    gt_bbox, gt_label, gt_attr_label, bbox_result,\n                    matched_bbox_result, mapped_class_names)\n\n                # ego planning metric\n                assert ego_fut_trajs.shape[0] == 1, 'only support batch_size=1 for testing'\n                ego_fut_preds = bbox_result['ego_fut_preds']\n                ego_fut_trajs = ego_fut_trajs[0, 0]\n                ego_fut_cmd = ego_fut_cmd[0, 0, 0]\n                ego_fut_cmd_idx = torch.nonzero(ego_fut_cmd)[0, 0]\n                ego_fut_pred = ego_fut_preds[ego_fut_cmd_idx]\n                ego_fut_pred = ego_fut_pred.cumsum(dim=-2)\n                ego_fut_trajs = ego_fut_trajs.cumsum(dim=-2)\n\n                metric_dict_planner_stp3 = self.compute_planner_metric_stp3(\n                    pred_ego_fut_trajs = ego_fut_pred[None],\n                    gt_ego_fut_trajs = ego_fut_trajs[None],\n                    gt_agent_boxes = gt_bbox,\n                    gt_agent_feats = gt_attr_label.unsqueeze(0),\n                    fut_valid_flag = fut_valid_flag\n                )\n                metric_dict.update(metric_dict_planner_stp3)\n\n        return outs['bev_embed'], bbox_results, metric_dict\n\n    def map_pred2result(self, bboxes, scores, labels, pts, attrs=None):\n        \"\"\"Convert detection results to a list of numpy arrays.\n\n        Args:\n            bboxes (torch.Tensor): Bounding boxes with shape of (n, 5).\n            labels (torch.Tensor): Labels with shape of (n, ).\n            scores (torch.Tensor): Scores with shape of (n, ).\n            attrs (torch.Tensor, optional): Attributes with shape of (n, ). \\\n                Defaults to None.\n\n        Returns:\n            dict[str, torch.Tensor]: Bounding box results in cpu mode.\n\n                - boxes_3d (torch.Tensor): 3D boxes.\n                - scores (torch.Tensor): Prediction scores.\n                - labels_3d (torch.Tensor): Box labels.\n                - attrs_3d (torch.Tensor, optional): Box attributes.\n        \"\"\"\n        result_dict = dict(\n            map_boxes_3d=bboxes.to('cpu'),\n            map_scores_3d=scores.cpu(),\n            map_labels_3d=labels.cpu(),\n            map_pts_3d=pts.to('cpu'))\n\n        if attrs is not None:\n            result_dict['map_attrs_3d'] = attrs.cpu()\n\n        return result_dict\n\n    def assign_pred_to_gt_vip3d(\n        self,\n        bbox_result,\n        gt_bbox,\n        gt_label,\n        match_dis_thresh=2.0\n    ):\n        \"\"\"Assign pred boxs to gt boxs according to object center preds in lcf.\n        Args:\n            bbox_result (dict): Predictions.\n                'boxes_3d': (LiDARInstance3DBoxes)\n                'scores_3d': (Tensor), [num_pred_bbox]\n                'labels_3d': (Tensor), [num_pred_bbox]\n                'trajs_3d': (Tensor), [fut_ts*2]\n            gt_bboxs (LiDARInstance3DBoxes): GT Bboxs.\n            gt_label (Tensor): GT labels for gt_bbox, [num_gt_bbox].\n            match_dis_thresh (float): dis thresh for determine a positive sample for a gt bbox.\n\n        Returns:\n            matched_bbox_result (np.array): assigned pred index for each gt box [num_gt_bbox].\n        \"\"\"     \n        dynamic_list = [0,1,3,4,6,7,8]\n        matched_bbox_result = torch.ones(\n            (len(gt_bbox)), dtype=torch.long) * -1  # -1: not assigned\n        gt_centers = gt_bbox.center[:, :2]\n        pred_centers = bbox_result['boxes_3d'].center[:, :2]\n        dist = torch.linalg.norm(pred_centers[:, None, :] - gt_centers[None, :, :], dim=-1)\n        pred_not_dyn = [label not in dynamic_list for label in bbox_result['labels_3d']]\n        gt_not_dyn = [label not in dynamic_list for label in gt_label]\n        dist[pred_not_dyn] = 1e6\n        dist[:, gt_not_dyn] = 1e6\n        dist[dist > match_dis_thresh] = 1e6\n\n        r_list, c_list = linear_sum_assignment(dist)\n\n        for i in range(len(r_list)):\n            if dist[r_list[i], c_list[i]] <= match_dis_thresh:\n                matched_bbox_result[c_list[i]] = r_list[i]\n\n        return matched_bbox_result\n\n    def compute_motion_metric_vip3d(\n        self,\n        gt_bbox,\n        gt_label,\n        gt_attr_label,\n        pred_bbox,\n        matched_bbox_result,\n        mapped_class_names,\n        match_dis_thresh=2.0,\n    ):\n        \"\"\"Compute EPA metric for one sample.\n        Args:\n            gt_bboxs (LiDARInstance3DBoxes): GT Bboxs.\n            gt_label (Tensor): GT labels for gt_bbox, [num_gt_bbox].\n            pred_bbox (dict): Predictions.\n                'boxes_3d': (LiDARInstance3DBoxes)\n                'scores_3d': (Tensor), [num_pred_bbox]\n                'labels_3d': (Tensor), [num_pred_bbox]\n                'trajs_3d': (Tensor), [fut_ts*2]\n            matched_bbox_result (np.array): assigned pred index for each gt box [num_gt_bbox].\n            match_dis_thresh (float): dis thresh for determine a positive sample for a gt bbox.\n\n        Returns:\n            EPA_dict (dict): EPA metric dict of each cared class.\n        \"\"\"\n        motion_cls_names = ['car', 'pedestrian']\n        motion_metric_names = ['gt', 'cnt_ade', 'cnt_fde', 'hit',\n                               'fp', 'ADE', 'FDE', 'MR']\n        \n        metric_dict = {}\n        for met in motion_metric_names:\n            for cls in motion_cls_names:\n                metric_dict[met+'_'+cls] = 0.0\n\n        veh_list = [0,1,3,4]\n        ignore_list = ['construction_vehicle', 'barrier',\n                       'traffic_cone', 'motorcycle', 'bicycle']\n\n        for i in range(pred_bbox['labels_3d'].shape[0]):\n            pred_bbox['labels_3d'][i] = 0 if pred_bbox['labels_3d'][i] in veh_list else pred_bbox['labels_3d'][i]\n            box_name = mapped_class_names[pred_bbox['labels_3d'][i]]\n            if box_name in ignore_list:\n                continue\n            if i not in matched_bbox_result:\n                metric_dict['fp_'+box_name] += 1\n\n        for i in range(gt_label.shape[0]):\n            gt_label[i] = 0 if gt_label[i] in veh_list else gt_label[i]\n            box_name = mapped_class_names[gt_label[i]]\n            if box_name in ignore_list:\n                continue\n            gt_fut_masks = gt_attr_label[i][self.fut_ts*2:self.fut_ts*3]\n            num_valid_ts = sum(gt_fut_masks==1)\n            if num_valid_ts == self.fut_ts:\n                metric_dict['gt_'+box_name] += 1\n            if matched_bbox_result[i] >= 0 and num_valid_ts > 0:\n                metric_dict['cnt_ade_'+box_name] += 1\n                m_pred_idx = matched_bbox_result[i]\n                gt_fut_trajs = gt_attr_label[i][:self.fut_ts*2].reshape(-1, 2)\n                gt_fut_trajs = gt_fut_trajs[:num_valid_ts]\n                pred_fut_trajs = pred_bbox['trajs_3d'][m_pred_idx].reshape(self.fut_mode, self.fut_ts, 2)\n                pred_fut_trajs = pred_fut_trajs[:, :num_valid_ts, :]\n                gt_fut_trajs = gt_fut_trajs.cumsum(dim=-2)\n                pred_fut_trajs = pred_fut_trajs.cumsum(dim=-2)\n                gt_fut_trajs = gt_fut_trajs + gt_bbox[i].center[0, :2]\n                pred_fut_trajs = pred_fut_trajs + pred_bbox['boxes_3d'][int(m_pred_idx)].center[0, :2]\n\n                dist = torch.linalg.norm(gt_fut_trajs[None, :, :] - pred_fut_trajs, dim=-1)\n                ade = dist.sum(-1) / num_valid_ts\n                ade = ade.min()\n\n                metric_dict['ADE_'+box_name] += ade\n                if num_valid_ts == self.fut_ts:\n                    fde = dist[:, -1].min()\n                    metric_dict['cnt_fde_'+box_name] += 1\n                    metric_dict['FDE_'+box_name] += fde\n                    if fde <= match_dis_thresh:\n                        metric_dict['hit_'+box_name] += 1\n                    else:\n                        metric_dict['MR_'+box_name] += 1\n\n        return metric_dict\n\n    ### same planning metric as stp3\n    def compute_planner_metric_stp3(\n        self,\n        pred_ego_fut_trajs,\n        gt_ego_fut_trajs,\n        gt_agent_boxes,\n        gt_agent_feats,\n        fut_valid_flag\n    ):\n        \"\"\"Compute planner metric for one sample same as stp3.\"\"\"\n        metric_dict = {\n            'plan_L2_1s':0,\n            'plan_L2_2s':0,\n            'plan_L2_3s':0,\n            'plan_obj_col_1s':0,\n            'plan_obj_col_2s':0,\n            'plan_obj_col_3s':0,\n            'plan_obj_box_col_1s':0,\n            'plan_obj_box_col_2s':0,\n            'plan_obj_box_col_3s':0,\n        }\n        metric_dict['fut_valid_flag'] = fut_valid_flag\n        future_second = 3\n        assert pred_ego_fut_trajs.shape[0] == 1, 'only support bs=1'\n        if self.planning_metric is None:\n            self.planning_metric = PlanningMetric()\n        segmentation, pedestrian = self.planning_metric.get_label(\n            gt_agent_boxes, gt_agent_feats)\n        occupancy = torch.logical_or(segmentation, pedestrian)\n\n        for i in range(future_second):\n            if fut_valid_flag:\n                cur_time = (i+1)*2\n                traj_L2 = self.planning_metric.compute_L2(\n                    pred_ego_fut_trajs[0, :cur_time].detach().to(gt_ego_fut_trajs.device),\n                    gt_ego_fut_trajs[0, :cur_time]\n                )\n                obj_coll, obj_box_coll = self.planning_metric.evaluate_coll(\n                    pred_ego_fut_trajs[:, :cur_time].detach(),\n                    gt_ego_fut_trajs[:, :cur_time],\n                    occupancy)\n                metric_dict['plan_L2_{}s'.format(i+1)] = traj_L2\n                metric_dict['plan_obj_col_{}s'.format(i+1)] = obj_coll.mean().item()\n                metric_dict['plan_obj_box_col_{}s'.format(i+1)] = obj_box_coll.mean().item()\n            else:\n                metric_dict['plan_L2_{}s'.format(i+1)] = 0.0\n                metric_dict['plan_obj_col_{}s'.format(i+1)] = 0.0\n                metric_dict['plan_obj_box_col_{}s'.format(i+1)] = 0.0\n            \n        return metric_dict\n\n    def set_epoch(self, epoch): \n        self.pts_bbox_head.epoch = epoch"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/__init__.py",
    "content": "from .base import BaseDetector, Base3DDetector\nfrom .single_stage_mono3d import SingleStageMono3DDetector\nfrom .uniad_e2e import UniAD\nfrom .bevformer import BEVFormer\nfrom .VAD import VAD\nfrom .MomAD import MomAD"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/base.py",
    "content": "from abc import ABCMeta, abstractmethod\nfrom collections import OrderedDict\n\nfrom os import path as osp\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.models.backbones import BaseModule\nfrom mmcv.utils import auto_fp16\n\nfrom mmcv.core.bbox.structures.box_3d_mode import Box3DMode\nfrom mmcv.core.bbox.structures.coord_3d_mode import Coord3DMode\nfrom mmcv.core.visualizer import show_result\nfrom mmcv.core.visualization import imshow_det_bboxes\nfrom mmcv.utils import concat_list, is_list_of\nfrom mmcv.image import imread\n\n\nclass BaseDetector(BaseModule, metaclass=ABCMeta):\n    \"\"\"Base class for detectors.\"\"\"\n\n    def __init__(self, init_cfg=None):\n        super(BaseDetector, self).__init__(init_cfg)\n        self.fp16_enabled = False\n\n    @property\n    def with_neck(self):\n        \"\"\"bool: whether the detector has a neck\"\"\"\n        return hasattr(self, 'neck') and self.neck is not None\n\n    # TODO: these properties need to be carefully handled\n    # for both single stage & two stage detectors\n    @property\n    def with_shared_head(self):\n        \"\"\"bool: whether the detector has a shared head in the RoI Head\"\"\"\n        return hasattr(self, 'roi_head') and self.roi_head.with_shared_head\n\n    @property\n    def with_bbox(self):\n        \"\"\"bool: whether the detector has a bbox head\"\"\"\n        return ((hasattr(self, 'roi_head') and self.roi_head.with_bbox)\n                or (hasattr(self, 'bbox_head') and self.bbox_head is not None))\n\n    @property\n    def with_mask(self):\n        \"\"\"bool: whether the detector has a mask head\"\"\"\n        return ((hasattr(self, 'roi_head') and self.roi_head.with_mask)\n                or (hasattr(self, 'mask_head') and self.mask_head is not None))\n\n    @abstractmethod\n    def extract_feat(self, imgs):\n        \"\"\"Extract features from images.\"\"\"\n        pass\n\n    def extract_feats(self, imgs):\n        \"\"\"Extract features from multiple images.\n\n        Args:\n            imgs (list[torch.Tensor]): A list of images. The images are\n                augmented from the same image but in different ways.\n\n        Returns:\n            list[torch.Tensor]: Features of different images\n        \"\"\"\n        assert isinstance(imgs, list)\n        return [self.extract_feat(img) for img in imgs]\n\n    def forward_train(self, imgs, img_metas, **kwargs):\n        \"\"\"\n        Args:\n            img (list[Tensor]): List of tensors of shape (1, C, H, W).\n                Typically these should be mean centered and std scaled.\n            img_metas (list[dict]): List of image info dict where each dict\n                has: 'img_shape', 'scale_factor', 'flip', and may also contain\n                'filename', 'ori_shape', 'pad_shape', and 'img_norm_cfg'.\n                For details on the values of these keys, see\n                :class:`mmcv.datasets.pipelines.Collect`.\n            kwargs (keyword arguments): Specific to concrete implementation.\n        \"\"\"\n        # NOTE the batched image size information may be useful, e.g.\n        # in DETR, this is needed for the construction of masks, which is\n        # then used for the transformer_head.\n        batch_input_shape = tuple(imgs[0].size()[-2:])\n        for img_meta in img_metas:\n            img_meta['batch_input_shape'] = batch_input_shape\n\n    async def async_simple_test(self, img, img_metas, **kwargs):\n        raise NotImplementedError\n\n    @abstractmethod\n    def simple_test(self, img, img_metas, **kwargs):\n        pass\n\n    @abstractmethod\n    def aug_test(self, imgs, img_metas, **kwargs):\n        \"\"\"Test function with test time augmentation.\"\"\"\n        pass\n\n    async def aforward_test(self, *, img, img_metas, **kwargs):\n        for var, name in [(img, 'img'), (img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError(f'{name} must be a list, but got {type(var)}')\n\n        num_augs = len(img)\n        if num_augs != len(img_metas):\n            raise ValueError(f'num of augmentations ({len(img)}) '\n                             f'!= num of image metas ({len(img_metas)})')\n        # TODO: remove the restriction of samples_per_gpu == 1 when prepared\n        samples_per_gpu = img[0].size(0)\n        assert samples_per_gpu == 1\n\n        if num_augs == 1:\n            return await self.async_simple_test(img[0], img_metas[0], **kwargs)\n        else:\n            raise NotImplementedError\n\n    def forward_test(self, imgs, img_metas, **kwargs):\n        \"\"\"\n        Args:\n            imgs (List[Tensor]): the outer list indicates test-time\n                augmentations and inner Tensor should have a shape NxCxHxW,\n                which contains all images in the batch.\n            img_metas (List[List[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch.\n        \"\"\"\n        for var, name in [(imgs, 'imgs'), (img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError(f'{name} must be a list, but got {type(var)}')\n\n        num_augs = len(imgs)\n        if num_augs != len(img_metas):\n            raise ValueError(f'num of augmentations ({len(imgs)}) '\n                             f'!= num of image meta ({len(img_metas)})')\n\n        # NOTE the batched image size information may be useful, e.g.\n        # in DETR, this is needed for the construction of masks, which is\n        # then used for the transformer_head.\n        for img, img_meta in zip(imgs, img_metas):\n            batch_size = len(img_meta)\n            for img_id in range(batch_size):\n                img_meta[img_id]['batch_input_shape'] = tuple(img.size()[-2:])\n\n        if num_augs == 1:\n            # proposals (List[List[Tensor]]): the outer list indicates\n            # test-time augs (multiscale, flip, etc.) and the inner list\n            # indicates images in a batch.\n            # The Tensor should have a shape Px4, where P is the number of\n            # proposals.\n            if 'proposals' in kwargs:\n                kwargs['proposals'] = kwargs['proposals'][0]\n            return self.simple_test(imgs[0], img_metas[0], **kwargs)\n        else:\n            assert imgs[0].size(0) == 1, 'aug test does not support ' \\\n                                         'inference with batch size ' \\\n                                         f'{imgs[0].size(0)}'\n            # TODO: support test augmentation for predefined proposals\n            assert 'proposals' not in kwargs\n            return self.aug_test(imgs, img_metas, **kwargs)\n\n    @auto_fp16(apply_to=('img', ))\n    def forward(self, img, img_metas, return_loss=True, **kwargs):\n        \"\"\"Calls either :func:`forward_train` or :func:`forward_test` depending\n        on whether ``return_loss`` is ``True``.\n\n        Note this setting will change the expected inputs. When\n        ``return_loss=True``, img and img_meta are single-nested (i.e. Tensor\n        and List[dict]), and when ``resturn_loss=False``, img and img_meta\n        should be double nested (i.e.  List[Tensor], List[List[dict]]), with\n        the outer list indicating test time augmentations.\n        \"\"\"\n        if torch.onnx.is_in_onnx_export():\n            assert len(img_metas) == 1\n            return self.onnx_export(img[0], img_metas[0])\n\n        if return_loss:\n            return self.forward_train(img, img_metas, **kwargs)\n        else:\n            return self.forward_test(img, img_metas, **kwargs)\n\n    def _parse_losses(self, losses):\n        \"\"\"Parse the raw outputs (losses) of the network.\n\n        Args:\n            losses (dict): Raw output of the network, which usually contain\n                losses and other necessary infomation.\n\n        Returns:\n            tuple[Tensor, dict]: (loss, log_vars), loss is the loss tensor \\\n                which may be a weighted sum of all losses, log_vars contains \\\n                all the variables to be sent to the logger.\n        \"\"\"\n        log_vars = OrderedDict()\n        for loss_name, loss_value in losses.items():\n            if isinstance(loss_value, torch.Tensor):\n                log_vars[loss_name] = loss_value.mean()\n            elif isinstance(loss_value, list):\n                log_vars[loss_name] = sum(_loss.mean() for _loss in loss_value)\n            else:\n                raise TypeError(\n                    f'{loss_name} is not a tensor or list of tensors')\n\n        loss = sum(_value for _key, _value in log_vars.items()\n                   if 'loss' in _key)\n\n        log_vars['loss'] = loss\n        for loss_name, loss_value in log_vars.items():\n            # reduce loss when distributed training\n            if dist.is_available() and dist.is_initialized():\n                loss_value = loss_value.data.clone()\n                dist.all_reduce(loss_value.div_(dist.get_world_size()))\n            log_vars[loss_name] = loss_value.item()\n\n        return loss, log_vars\n\n\n    def show_result(self,\n                    img,\n                    result,\n                    score_thr=0.3,\n                    bbox_color=(72, 101, 241),\n                    text_color=(72, 101, 241),\n                    mask_color=None,\n                    thickness=2,\n                    font_size=13,\n                    win_name='',\n                    show=False,\n                    wait_time=0,\n                    out_file=None):\n        \"\"\"Draw `result` over `img`.\n\n        Args:\n            img (str or Tensor): The image to be displayed.\n            result (Tensor or tuple): The results to draw over `img`\n                bbox_result or (bbox_result, segm_result).\n            score_thr (float, optional): Minimum score of bboxes to be shown.\n                Default: 0.3.\n            bbox_color (str or tuple(int) or :obj:`Color`):Color of bbox lines.\n               The tuple of color should be in BGR order. Default: 'green'\n            text_color (str or tuple(int) or :obj:`Color`):Color of texts.\n               The tuple of color should be in BGR order. Default: 'green'\n            mask_color (None or str or tuple(int) or :obj:`Color`):\n               Color of masks. The tuple of color should be in BGR order.\n               Default: None\n            thickness (int): Thickness of lines. Default: 2\n            font_size (int): Font size of texts. Default: 13\n            win_name (str): The window name. Default: ''\n            wait_time (float): Value of waitKey param.\n                Default: 0.\n            show (bool): Whether to show the image.\n                Default: False.\n            out_file (str or None): The filename to write the image.\n                Default: None.\n\n        Returns:\n            img (Tensor): Only if not `show` or `out_file`\n        \"\"\"\n        img = imread(img)\n        img = img.copy()\n        if isinstance(result, tuple):\n            bbox_result, segm_result = result\n            if isinstance(segm_result, tuple):\n                segm_result = segm_result[0]  # ms rcnn\n        else:\n            bbox_result, segm_result = result, None\n        bboxes = np.vstack(bbox_result)\n        labels = [\n            np.full(bbox.shape[0], i, dtype=np.int32)\n            for i, bbox in enumerate(bbox_result)\n        ]\n        labels = np.concatenate(labels)\n        # draw segmentation masks\n        segms = None\n        if segm_result is not None and len(labels) > 0:  # non empty\n            segms = concat_list(segm_result)\n            if isinstance(segms[0], torch.Tensor):\n                segms = torch.stack(segms, dim=0).detach().cpu().numpy()\n            else:\n                segms = np.stack(segms, axis=0)\n        # if out_file specified, do not show image in window\n        if out_file is not None:\n            show = False\n        # draw bounding boxes\n        img = imshow_det_bboxes(\n            img,\n            bboxes,\n            labels,\n            segms,\n            class_names=self.CLASSES,\n            score_thr=score_thr,\n            bbox_color=bbox_color,\n            text_color=text_color,\n            mask_color=mask_color,\n            thickness=thickness,\n            font_size=font_size,\n            win_name=win_name,\n            show=show,\n            wait_time=wait_time,\n            out_file=out_file)\n\n        if not (show or out_file):\n            return img\n\n    def onnx_export(self, img, img_metas):\n        raise NotImplementedError(f'{self.__class__.__name__} does '\n                                  f'not support ONNX EXPORT')\n\n\nclass Base3DDetector(BaseDetector):\n    \"\"\"Base class for detectors.\"\"\"\n\n    def forward_test(self, points, img_metas, img=None, **kwargs):\n        \"\"\"\n        Args:\n            points (list[torch.Tensor]): the outer list indicates test-time\n                augmentations and inner torch.Tensor should have a shape NxC,\n                which contains all points in the batch.\n            img_metas (list[list[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch\n            img (list[torch.Tensor], optional): the outer\n                list indicates test-time augmentations and inner\n                torch.Tensor should have a shape NxCxHxW, which contains\n                all images in the batch. Defaults to None.\n        \"\"\"\n        for var, name in [(points, 'points'), (img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError('{} must be a list, but got {}'.format(\n                    name, type(var)))\n\n        num_augs = len(points)\n        if num_augs != len(img_metas):\n            raise ValueError(\n                'num of augmentations ({}) != num of image meta ({})'.format(\n                    len(points), len(img_metas)))\n\n        if num_augs == 1:\n            img = [img] if img is None else img\n            return self.simple_test(points[0], img_metas[0], img[0], **kwargs)\n        else:\n            return self.aug_test(points, img_metas, img, **kwargs)\n\n    @auto_fp16(apply_to=('img', 'points'))\n    def forward(self, return_loss=True, **kwargs):\n        \"\"\"Calls either forward_train or forward_test depending on whether\n        return_loss=True.\n\n        Note this setting will change the expected inputs. When\n        `return_loss=True`, img and img_metas are single-nested (i.e.\n        torch.Tensor and list[dict]), and when `resturn_loss=False`, img and\n        img_metas should be double nested (i.e.  list[torch.Tensor],\n        list[list[dict]]), with the outer list indicating test time\n        augmentations.\n        \"\"\"\n        if return_loss:\n            return self.forward_train(**kwargs)\n        else:\n            return self.forward_test(**kwargs)\n\n    def show_results(self, data, result, out_dir):\n        \"\"\"Results visualization.\n\n        Args:\n            data (list[dict]): Input points and the information of the sample.\n            result (list[dict]): Prediction results.\n            out_dir (str): Output directory of visualization result.\n        \"\"\"\n        for batch_id in range(len(result)):\n            if isinstance(data['points'][0], DC):\n                points = data['points'][0]._data[0][batch_id].numpy()\n            elif is_list_of(data['points'][0], torch.Tensor):\n                points = data['points'][0][batch_id]\n            else:\n                ValueError(f\"Unsupported data type {type(data['points'][0])} \"\n                           f'for visualization!')\n            if isinstance(data['img_metas'][0], DC):\n                pts_filename = data['img_metas'][0]._data[0][batch_id][\n                    'pts_filename']\n                box_mode_3d = data['img_metas'][0]._data[0][batch_id][\n                    'box_mode_3d']\n            elif is_list_of(data['img_metas'][0], dict):\n                pts_filename = data['img_metas'][0][batch_id]['pts_filename']\n                box_mode_3d = data['img_metas'][0][batch_id]['box_mode_3d']\n            else:\n                ValueError(\n                    f\"Unsupported data type {type(data['img_metas'][0])} \"\n                    f'for visualization!')\n            file_name = osp.split(pts_filename)[-1].split('.')[0]\n\n            assert out_dir is not None, 'Expect out_dir, got none.'\n\n            pred_bboxes = result[batch_id]['boxes_3d']\n\n            # for now we convert points and bbox into depth mode\n            if (box_mode_3d == Box3DMode.CAM) or (box_mode_3d\n                                                  == Box3DMode.LIDAR):\n                points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,\n                                                   Coord3DMode.DEPTH)\n                pred_bboxes = Box3DMode.convert(pred_bboxes, box_mode_3d,\n                                                Box3DMode.DEPTH)\n            elif box_mode_3d != Box3DMode.DEPTH:\n                ValueError(\n                    f'Unsupported box_mode_3d {box_mode_3d} for convertion!')\n            pred_bboxes = pred_bboxes.tensor.cpu().numpy()\n            show_result(points, None, pred_bboxes, out_dir, file_name)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/bevformer.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nimport torch\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom mmcv.models import DETECTORS\nfrom mmcv.core import bbox3d2result\nfrom mmcv.models.detectors.mvx_two_stage import MVXTwoStageDetector\nfrom mmcv.models.utils.grid_mask import GridMask\nimport time\nimport copy\nimport numpy as np\nfrom mmcv.utils.bricks import run_time\n\n\n@DETECTORS.register_module()\nclass BEVFormer(MVXTwoStageDetector):\n    \"\"\"BEVFormer.\n    Args:\n        video_test_mode (bool): Decide whether to use temporal information during inference.\n    \"\"\"\n\n    def __init__(self,\n                 use_grid_mask=False,\n                 pts_voxel_layer=None,\n                 pts_voxel_encoder=None,\n                 pts_middle_encoder=None,\n                 pts_fusion_layer=None,\n                 img_backbone=None,\n                 pts_backbone=None,\n                 img_neck=None,\n                 pts_neck=None,\n                 pts_bbox_head=None,\n                 img_roi_head=None,\n                 img_rpn_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 pretrained=None,\n                 video_test_mode=False\n                 ):\n\n        super(BEVFormer,\n              self).__init__(pts_voxel_layer, pts_voxel_encoder,\n                             pts_middle_encoder, pts_fusion_layer,\n                             img_backbone, pts_backbone, img_neck, pts_neck,\n                             pts_bbox_head, img_roi_head, img_rpn_head,\n                             train_cfg, test_cfg, pretrained)\n        self.grid_mask = GridMask(\n            True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7)\n        self.use_grid_mask = use_grid_mask\n        self.fp16_enabled = False\n\n        # temporal\n        self.video_test_mode = video_test_mode\n        self.prev_frame_info = {\n            'prev_bev': None,\n            'scene_token': None,\n            'prev_pos': 0,\n            'prev_angle': 0,\n        }\n\n\n    def extract_img_feat(self, img, img_metas, len_queue=None):\n        \"\"\"Extract features of images.\"\"\"\n        B = img.size(0)\n        if img is not None:\n            \n            # input_shape = img.shape[-2:]\n            # # update real input shape of each single img\n            # for img_meta in img_metas:\n            #     img_meta.update(input_shape=input_shape)\n\n            if img.dim() == 5 and img.size(0) == 1:\n                img.squeeze_()\n            elif img.dim() == 5 and img.size(0) > 1:\n                B, N, C, H, W = img.size()\n                img = img.reshape(B * N, C, H, W)\n            if self.use_grid_mask:\n                img = self.grid_mask(img)\n\n            img_feats = self.img_backbone(img)\n            if isinstance(img_feats, dict):\n                img_feats = list(img_feats.values())\n        else:\n            return None\n        if self.with_img_neck:\n            img_feats = self.img_neck(img_feats)\n\n        img_feats_reshaped = []\n        for img_feat in img_feats:\n            BN, C, H, W = img_feat.size()\n            if len_queue is not None:\n                img_feats_reshaped.append(img_feat.view(int(B/len_queue), len_queue, int(BN / B), C, H, W))\n            else:\n                img_feats_reshaped.append(img_feat.view(B, int(BN / B), C, H, W))\n        return img_feats_reshaped\n\n    @auto_fp16(apply_to=('img'))\n    def extract_feat(self, img, img_metas=None, len_queue=None):\n        \"\"\"Extract features from images and points.\"\"\"\n\n        img_feats = self.extract_img_feat(img, img_metas, len_queue=len_queue)\n        \n        return img_feats\n\n\n    def forward_pts_train(self,\n                          pts_feats,\n                          gt_bboxes_3d,\n                          gt_labels_3d,\n                          img_metas,\n                          gt_bboxes_ignore=None,\n                          prev_bev=None):\n        \"\"\"Forward function'\n        Args:\n            pts_feats (list[torch.Tensor]): Features of point cloud branch\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`]): Ground truth\n                boxes for each sample.\n            gt_labels_3d (list[torch.Tensor]): Ground truth labels for\n                boxes of each sampole\n            img_metas (list[dict]): Meta information of samples.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                boxes to be ignored. Defaults to None.\n            prev_bev (torch.Tensor, optional): BEV features of previous frame.\n        Returns:\n            dict: Losses of each branch.\n        \"\"\"\n\n        outs = self.pts_bbox_head(\n            pts_feats, img_metas, prev_bev)\n        loss_inputs = [gt_bboxes_3d, gt_labels_3d, outs]\n        losses = self.pts_bbox_head.loss(*loss_inputs, img_metas=img_metas)\n        return losses\n\n    def forward_dummy(self, img):\n        dummy_metas = None\n        return self.forward_test(img=img, img_metas=[[dummy_metas]])\n\n    def forward(self, inputs, return_loss=True, rescale=False):\n        \"\"\"Calls either forward_train or forward_test depending on whether\n        return_loss=True.\n        Note this setting will change the expected inputs. When\n        `return_loss=True`, img and img_metas are single-nested (i.e.\n        torch.Tensor and list[dict]), and when `resturn_loss=False`, img and\n        img_metas should be double nested (i.e.  list[torch.Tensor],\n        list[list[dict]]), with the outer list indicating test time\n        augmentations.\n        \"\"\"\n        if return_loss:\n            losses = self.forward_train(**inputs)\n            loss, log_vars = self._parse_losses(losses)\n            outputs = dict(\n                loss=loss, log_vars=log_vars, num_samples=len(inputs['img_metas']))\n            return outputs\n        else:\n            outputs = self.forward_test(**inputs, rescale=rescale)\n            return outputs\n    \n    def obtain_history_bev(self, imgs_queue, img_metas_list):\n        \"\"\"Obtain history BEV features iteratively. To save GPU memory, gradients are not calculated.\n        \"\"\"\n        self.eval()\n\n        with torch.no_grad():\n            prev_bev = None\n            bs, len_queue, num_cams, C, H, W = imgs_queue.shape\n            imgs_queue = imgs_queue.reshape(bs*len_queue, num_cams, C, H, W)\n            img_feats_list = self.extract_feat(img=imgs_queue, len_queue=len_queue)\n            for i in range(len_queue):\n                img_metas = [each[i] for each in img_metas_list]\n                if not img_metas[0]['prev_bev_exists']:\n                    prev_bev = None\n                # img_feats = self.extract_feat(img=img, img_metas=img_metas)\n                img_feats = [each_scale[:, i] for each_scale in img_feats_list]\n                prev_bev = self.pts_bbox_head(\n                    img_feats, img_metas, prev_bev, only_bev=True)\n            self.train()\n            return prev_bev\n\n    @auto_fp16(apply_to=('img', 'points'))\n    def forward_train(self,\n                      points=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      gt_labels=None,\n                      gt_bboxes=None,\n                      img=None,\n                      proposals=None,\n                      gt_bboxes_ignore=None,\n                      img_depth=None,\n                      img_mask=None,\n                      ):\n        \"\"\"Forward training function.\n        Args:\n            points (list[torch.Tensor], optional): Points of each sample.\n                Defaults to None.\n            img_metas (list[dict], optional): Meta information of each sample.\n                Defaults to None.\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`], optional):\n                Ground truth 3D boxes. Defaults to None.\n            gt_labels_3d (list[torch.Tensor], optional): Ground truth labels\n                of 3D boxes. Defaults to None.\n            gt_labels (list[torch.Tensor], optional): Ground truth labels\n                of 2D boxes in images. Defaults to None.\n            gt_bboxes (list[torch.Tensor], optional): Ground truth 2D boxes in\n                images. Defaults to None.\n            img (torch.Tensor optional): Images of each sample with shape\n                (N, C, H, W). Defaults to None.\n            proposals ([list[torch.Tensor], optional): Predicted proposals\n                used for training Fast RCNN. Defaults to None.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                2D boxes in images to be ignored. Defaults to None.\n        Returns:\n            dict: Losses of different branches.\n        \"\"\"\n        len_queue = img.size(1)\n        prev_img = img[:, :-1, ...]\n        img = img[:, -1, ...]\n\n        prev_img_metas = copy.deepcopy(img_metas)\n        prev_bev = self.obtain_history_bev(prev_img, prev_img_metas)\n\n        img_metas = [each[len_queue-1] for each in img_metas]\n        if not img_metas[0]['prev_bev_exists']:\n            prev_bev = None\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        losses = dict()\n        losses_pts = self.forward_pts_train(img_feats, gt_bboxes_3d,\n                                            gt_labels_3d, img_metas,\n                                            gt_bboxes_ignore, prev_bev)\n\n        losses.update(losses_pts)\n        return losses\n\n    def forward_test(self, img_metas, img=None, rescale=None):\n        for var, name in [(img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError('{} must be a list, but got {}'.format(\n                    name, type(var)))\n        img = [img] if img is None else img\n\n        if img_metas[0][0]['scene_token'] != self.prev_frame_info['scene_token']:\n            # the first sample of each scene is truncated\n            self.prev_frame_info['prev_bev'] = None\n        # update idx\n        self.prev_frame_info['scene_token'] = img_metas[0][0]['scene_token']\n\n        # do not use temporal information\n        if not self.video_test_mode:\n            self.prev_frame_info['prev_bev'] = None\n\n        # Get the delta of ego position and angle between two timestamps.\n        tmp_pos = copy.deepcopy(img_metas[0][0]['can_bus'][:3])\n        tmp_angle = copy.deepcopy(img_metas[0][0]['can_bus'][-1])\n        if self.prev_frame_info['prev_bev'] is not None:\n            img_metas[0][0]['can_bus'][:3] -= self.prev_frame_info['prev_pos']\n            img_metas[0][0]['can_bus'][-1] -= self.prev_frame_info['prev_angle']\n        else:\n            img_metas[0][0]['can_bus'][-1] = 0\n            img_metas[0][0]['can_bus'][:3] = 0\n\n        new_prev_bev, bbox_results = self.simple_test(\n            img_metas[0], img[0], prev_bev=self.prev_frame_info['prev_bev'], rescale=rescale)\n        # During inference, we save the BEV features and ego motion of each timestamp.\n        self.prev_frame_info['prev_pos'] = tmp_pos\n        self.prev_frame_info['prev_angle'] = tmp_angle\n        self.prev_frame_info['prev_bev'] = new_prev_bev\n        return bbox_results\n\n    def simple_test_pts(self, x, img_metas, prev_bev=None, rescale=False):\n        \"\"\"Test function\"\"\"\n        outs = self.pts_bbox_head(x, img_metas, prev_bev=prev_bev)\n\n        bbox_list = self.pts_bbox_head.get_bboxes(\n            outs, img_metas, rescale=rescale)\n        bbox_results = [\n            bbox3d2result(bboxes, scores, labels)\n            for bboxes, scores, labels in bbox_list\n        ]\n        return outs['bev_embed'], bbox_results\n\n    def simple_test(self, img_metas, img=None, prev_bev=None, rescale=False):\n        \"\"\"Test function without augmentaiton.\"\"\"\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n\n        bbox_list = [dict() for i in range(len(img_metas))]\n        new_prev_bev, bbox_pts = self.simple_test_pts(\n            img_feats, img_metas, prev_bev, rescale=rescale)\n        for result_dict, pts_bbox in zip(bbox_list, bbox_pts):\n            result_dict['pts_bbox'] = pts_bbox\n        return new_prev_bev, bbox_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/bevformerV2.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nimport copy\nfrom collections import OrderedDict\nimport torch\nfrom mmdet.models import DETECTORS\nfrom mmdet3d.core import bbox3d2result\nfrom mmdet3d.models.detectors.mvx_two_stage import MVXTwoStageDetector\nfrom mmdet3d.models.builder import build_head\nfrom projects.mmdet3d_plugin.models.utils.grid_mask import GridMask\n\n\n@DETECTORS.register_module()\nclass BEVFormerV2(MVXTwoStageDetector):\n    \"\"\"BEVFormer.\n    Args:\n        video_test_mode (bool): Decide whether to use temporal information during inference.\n    \"\"\"\n\n    def __init__(self,\n                 use_grid_mask=False,\n                 pts_voxel_layer=None,\n                 pts_voxel_encoder=None,\n                 pts_middle_encoder=None,\n                 pts_fusion_layer=None,\n                 img_backbone=None,\n                 pts_backbone=None,\n                 img_neck=None,\n                 pts_neck=None,\n                 pts_bbox_head=None,\n                 fcos3d_bbox_head=None,\n                 img_roi_head=None,\n                 img_rpn_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 pretrained=None,\n                 video_test_mode=False,\n                 num_levels=None,\n                 num_mono_levels=None,\n                 mono_loss_weight=1.0,\n                 frames=(0,),\n                 ):\n\n        super(BEVFormerV2,\n              self).__init__(pts_voxel_layer, pts_voxel_encoder,\n                             pts_middle_encoder, pts_fusion_layer,\n                             img_backbone, pts_backbone, img_neck, pts_neck,\n                             pts_bbox_head, img_roi_head, img_rpn_head,\n                             train_cfg, test_cfg, pretrained)\n        self.grid_mask = GridMask(\n            True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7)\n        self.use_grid_mask = use_grid_mask\n        self.fp16_enabled = False\n        assert not self.fp16_enabled  # not support fp16 yet\n        # temporal\n        self.video_test_mode = video_test_mode\n        assert not self.video_test_mode  # not support video_test_mode yet\n\n        # fcos3d head\n        self.fcos3d_bbox_head = build_head(fcos3d_bbox_head) if fcos3d_bbox_head else None\n        # loss weight\n        self.mono_loss_weight = mono_loss_weight\n\n        # levels of features\n        self.num_levels = num_levels\n        self.num_mono_levels = num_mono_levels\n        self.frames = frames\n    def extract_img_feat(self, img):\n        \"\"\"Extract features of images.\"\"\"\n        B = img.size(0)\n        if img is not None:\n            if img.dim() == 5 and img.size(0) == 1:\n                img.squeeze_()\n            elif img.dim() == 5 and img.size(0) > 1:\n                B, N, C, H, W = img.size()\n                img = img.reshape(B * N, C, H, W)\n            if self.use_grid_mask:\n                img = self.grid_mask(img)\n\n            img_feats = self.img_backbone(img)\n            if isinstance(img_feats, dict):\n                img_feats = list(img_feats.values())\n        else:\n            return None\n        if self.with_img_neck:\n            img_feats = self.img_neck(img_feats)\n\n        img_feats_reshaped = []\n        for img_feat in img_feats:\n            BN, C, H, W = img_feat.size()\n            img_feats_reshaped.append(img_feat.view(B, int(BN / B), C, H, W))\n        return img_feats_reshaped\n\n    def extract_feat(self, img, img_metas, len_queue=None):\n        \"\"\"Extract features from images and points.\"\"\"\n\n        img_feats = self.extract_img_feat(img)\n        if 'aug_param' in img_metas[0] and img_metas[0]['aug_param']['CropResizeFlipImage_param'][-1] is True:\n            # flip feature \n            img_feats = [torch.flip(x, dims=[-1, ]) for x in img_feats]\n        return img_feats\n\n    def forward_pts_train(self,\n                          pts_feats,\n                          gt_bboxes_3d,\n                          gt_labels_3d,\n                          img_metas,\n                          gt_bboxes_ignore=None,\n                          prev_bev=None):\n        outs = self.pts_bbox_head(\n            pts_feats, img_metas, prev_bev)\n        loss_inputs = [gt_bboxes_3d, gt_labels_3d, outs]\n        losses = self.pts_bbox_head.loss(*loss_inputs, img_metas=img_metas)\n        return losses\n\n    def forward_mono_train(self, img_feats, mono_input_dict):\n        \"\"\"\n        img_feats (list[Tensor]): 5-D tensor for each level, (B, N, C, H, W)\n        gt_bboxes (list[list[Tensor]]): Ground truth bboxes for each image with\n                shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.\n        gt_labels (list[list[Tensor]]): class indices corresponding to each box\n        gt_bboxes_3d (list[list[[Tensor]]): 3D boxes ground truth with shape of\n                (num_gts, code_size).\n        gt_labels_3d (list[list[Tensor]]): same as gt_labels\n        centers2d (list[list[Tensor]]): 2D centers on the image with shape of\n                (num_gts, 2).\n        depths (list[list[Tensor]]): Depth ground truth with shape of\n                (num_gts, ).\n        attr_labels (list[list[Tensor]]): Attributes indices of each box.\n        img_metas (list[list[dict]]): Meta information of each image, e.g.,\n                image size, scaling factor, etc.\n        ann_idx (list[list[idx]]): indicate which image has mono annotation.\n        \"\"\"\n        bsz = img_feats[0].shape[0];\n        num_lvls = len(img_feats)\n\n        img_feats_select = [[] for lvl in range(num_lvls)]\n        for lvl, img_feat in enumerate(img_feats):\n            for i in range(bsz):\n                img_feats_select[lvl].append(img_feat[i, mono_input_dict['mono_ann_idx'][i]])\n            img_feats_select[lvl] = torch.cat(img_feats_select[lvl], dim=0)\n        bsz_new = img_feats_select[0].shape[0]\n        assert bsz == len(mono_input_dict['mono_input_dict'])\n        input_dict = []\n        for i in range(bsz):\n            input_dict.extend(mono_input_dict['mono_input_dict'][i])\n        assert bsz_new == len(input_dict)\n        losses = self.fcos3d_bbox_head.forward_train(img_feats_select, input_dict)\n        return losses\n\n    def forward_dummy(self, img):\n        dummy_metas = None\n        return self.forward_test(img=img, img_metas=[[dummy_metas]])\n\n    def forward(self, return_loss=True, **kwargs):\n        if return_loss:\n            return self.forward_train(**kwargs)\n        else:\n            return self.forward_test(**kwargs)\n\n    def obtain_history_bev(self, img_dict, img_metas_dict):\n        \"\"\"Obtain history BEV features iteratively. To save GPU memory, gradients are not calculated.\n        \"\"\"\n        # Modify: roll back to previous version for single frame\n        is_training = self.training\n        self.eval()\n        prev_bev = OrderedDict({i: None for i in self.frames})\n        with torch.no_grad():\n            for t in img_dict.keys():\n                img = img_dict[t]\n                img_metas = [img_metas_dict[t], ]\n                img_feats = self.extract_feat(img=img, img_metas=img_metas)\n                if self.num_levels:\n                    img_feats = img_feats[:self.num_levels]\n                bev = self.pts_bbox_head(\n                    img_feats, img_metas, None, only_bev=True)\n                prev_bev[t] = bev.detach()\n        if is_training:\n            self.train()\n        return list(prev_bev.values())\n\n    def forward_train(self,\n                      points=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      img=None,\n                      gt_bboxes_ignore=None,\n                      **mono_input_dict,\n                      ):\n        img_metas = OrderedDict(sorted(img_metas[0].items()))\n        img_dict = {}\n        for ind, t in enumerate(img_metas.keys()):\n            img_dict[t] = img[:, ind, ...]\n\n        img = img_dict[0]\n        img_dict.pop(0)\n\n        prev_img_metas = copy.deepcopy(img_metas)\n        prev_img_metas.pop(0)\n        prev_bev = self.obtain_history_bev(img_dict, prev_img_metas)\n\n        img_metas = [img_metas[0], ]\n\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        losses = dict()\n        losses_pts = self.forward_pts_train(img_feats if self.num_levels is None\n                                            else img_feats[:self.num_levels], gt_bboxes_3d,\n                                            gt_labels_3d, img_metas,\n                                            gt_bboxes_ignore, prev_bev)\n        losses.update(losses_pts)\n\n        if self.fcos3d_bbox_head:\n            losses_mono = self.forward_mono_train(img_feats=img_feats if self.num_mono_levels is None\n            else img_feats[:self.num_mono_levels],\n                                                  mono_input_dict=mono_input_dict)\n            for k, v in losses_mono.items():\n                losses[f'{k}_mono'] = v * self.mono_loss_weight\n\n        return losses\n\n    def forward_test(self, img_metas, img=None, **kwargs):\n        for var, name in [(img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError('{} must be a list, but got {}'.format(\n                    name, type(var)))\n        img = [img] if img is None else img\n        new_prev_bev, bbox_results = self.simple_test(img_metas[0], img[0], prev_bev=None, **kwargs)\n        return bbox_results\n\n    def simple_test_pts(self, x, img_metas, prev_bev=None, rescale=False):\n        \"\"\"Test function\"\"\"\n        outs = self.pts_bbox_head(x, img_metas, prev_bev=prev_bev)\n\n        bbox_list = self.pts_bbox_head.get_bboxes(\n            outs, img_metas, rescale=rescale)\n        bbox_results = [\n            bbox3d2result(bboxes, scores, labels)\n            for bboxes, scores, labels in bbox_list\n        ]\n        return outs['bev_embed'], bbox_results\n\n    def simple_test(self, img_metas, img=None, prev_bev=None, rescale=False, **kwargs):\n        \"\"\"Test function without augmentaiton.\"\"\"\n        img_metas = OrderedDict(sorted(img_metas[0].items()))\n        img_dict = {}\n        for ind, t in enumerate(img_metas.keys()):\n            img_dict[t] = img[:, ind, ...]\n        img = img_dict[0]\n        img_dict.pop(0)\n\n        prev_img_metas = copy.deepcopy(img_metas)\n        prev_bev = self.obtain_history_bev(img_dict, prev_img_metas)\n\n        img_metas = [img_metas[0], ]\n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n        if self.num_levels:\n            img_feats = img_feats[:self.num_levels]\n\n        bbox_list = [dict() for i in range(len(img_metas))]\n        new_prev_bev, bbox_pts = self.simple_test_pts(\n            img_feats, img_metas, prev_bev, rescale=rescale)\n        for result_dict, pts_bbox in zip(bbox_list, bbox_pts):\n            result_dict['pts_bbox'] = pts_bbox\n        return new_prev_bev, bbox_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/bevformer_fp16.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom tkinter.messagebox import NO\nimport torch\nfrom mmcv.runner import force_fp32, auto_fp16\nfrom mmdet.models import DETECTORS\nfrom mmdet3d.core import bbox3d2result\nfrom mmdet3d.models.detectors.mvx_two_stage import MVXTwoStageDetector\nfrom projects.mmdet3d_plugin.models.utils.grid_mask import GridMask\nfrom projects.mmdet3d_plugin.bevformer.detectors.bevformer import BEVFormer\nimport time\nimport copy\nimport numpy as np\nimport mmdet3d\nfrom projects.mmdet3d_plugin.models.utils.bricks import run_time\n\n\n@DETECTORS.register_module()\nclass BEVFormer_fp16(BEVFormer):\n    \"\"\"\n    The default version BEVFormer currently can not support FP16. \n    We provide this version to resolve this issue.\n    \"\"\"\n    \n    @auto_fp16(apply_to=('img', 'prev_bev', 'points'))\n    def forward_train(self,\n                      points=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      gt_labels=None,\n                      gt_bboxes=None,\n                      img=None,\n                      proposals=None,\n                      gt_bboxes_ignore=None,\n                      img_depth=None,\n                      img_mask=None,\n                      prev_bev=None,\n                      ):\n        \"\"\"Forward training function.\n        Args:\n            points (list[torch.Tensor], optional): Points of each sample.\n                Defaults to None.\n            img_metas (list[dict], optional): Meta information of each sample.\n                Defaults to None.\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`], optional):\n                Ground truth 3D boxes. Defaults to None.\n            gt_labels_3d (list[torch.Tensor], optional): Ground truth labels\n                of 3D boxes. Defaults to None.\n            gt_labels (list[torch.Tensor], optional): Ground truth labels\n                of 2D boxes in images. Defaults to None.\n            gt_bboxes (list[torch.Tensor], optional): Ground truth 2D boxes in\n                images. Defaults to None.\n            img (torch.Tensor optional): Images of each sample with shape\n                (N, C, H, W). Defaults to None.\n            proposals ([list[torch.Tensor], optional): Predicted proposals\n                used for training Fast RCNN. Defaults to None.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                2D boxes in images to be ignored. Defaults to None.\n        Returns:\n            dict: Losses of different branches.\n        \"\"\"\n        \n        img_feats = self.extract_feat(img=img, img_metas=img_metas)\n\n        losses = dict()\n        losses_pts = self.forward_pts_train(img_feats, gt_bboxes_3d,\n                                            gt_labels_3d, img_metas,\n                                            gt_bboxes_ignore, prev_bev=prev_bev)\n        losses.update(losses_pts)\n        return losses\n\n\n    def val_step(self, data, optimizer):\n        \"\"\"\n        In BEVFormer_fp16, we use this `val_step` function to inference the `prev_pev`.\n        This is not the standard function of `val_step`.\n        \"\"\"\n\n        img = data['img']\n        img_metas = data['img_metas']\n        img_feats = self.extract_feat(img=img,  img_metas=img_metas)\n        prev_bev = data.get('prev_bev', None)\n        prev_bev = self.pts_bbox_head(img_feats, img_metas, prev_bev=prev_bev, only_bev=True)\n        return prev_bev"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/mvx_two_stage.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nimport warnings\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.utils import force_fp32\nfrom os import path as osp\nfrom torch.nn import functional as F\n\nfrom mmcv.core.bbox.structures.box_3d_mode import Box3DMode\nfrom mmcv.core.bbox.structures.coord_3d_mode import Coord3DMode\nfrom mmcv.core.bbox.transforms import bbox3d2result\nfrom mmcv.core.post_processing.merge_augs import merge_aug_bboxes_3d\nfrom mmcv.core.visualizer import show_result\nfrom mmcv.ops.voxelize import Voxelization\nfrom mmcv.core.utils import multi_apply\nfrom mmcv.models import DETECTORS\nfrom mmcv.utils import is_list_of\nfrom .. import builder\nfrom .base import Base3DDetector\n\n\n@DETECTORS.register_module()\nclass MVXTwoStageDetector(Base3DDetector):\n    \"\"\"Base class of Multi-modality VoxelNet.\"\"\"\n\n    def __init__(self,\n                 pts_voxel_layer=None,\n                 pts_voxel_encoder=None,\n                 pts_middle_encoder=None,\n                 pts_fusion_layer=None,\n                 img_backbone=None,\n                 pts_backbone=None,\n                 img_neck=None,\n                 pts_neck=None,\n                 pts_bbox_head=None,\n                 img_roi_head=None,\n                 img_rpn_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 pretrained=None,\n                 init_cfg=None):\n        super(MVXTwoStageDetector, self).__init__(init_cfg=init_cfg)\n\n        if pts_voxel_layer:\n            self.pts_voxel_layer = Voxelization(**pts_voxel_layer)\n        if pts_voxel_encoder:\n            self.pts_voxel_encoder = builder.build_voxel_encoder(\n                pts_voxel_encoder)\n        if pts_middle_encoder:\n            self.pts_middle_encoder = builder.build_middle_encoder(\n                pts_middle_encoder)\n        if pts_backbone:\n            self.pts_backbone = builder.build_backbone(pts_backbone)\n        if pts_fusion_layer:\n            self.pts_fusion_layer = builder.build_fusion_layer(\n                pts_fusion_layer)\n        if pts_neck is not None:\n            self.pts_neck = builder.build_neck(pts_neck)\n        if pts_bbox_head:\n            pts_train_cfg = train_cfg.pts if train_cfg else None\n            pts_bbox_head.update(train_cfg=pts_train_cfg)\n            pts_test_cfg = test_cfg.pts if test_cfg else None\n            pts_bbox_head.update(test_cfg=pts_test_cfg)\n            self.pts_bbox_head = builder.build_head(pts_bbox_head)\n\n        if img_backbone:\n            self.img_backbone = builder.build_backbone(img_backbone)\n        if img_neck is not None:\n            self.img_neck = builder.build_neck(img_neck)\n        if img_rpn_head is not None:\n            self.img_rpn_head = builder.build_head(img_rpn_head)\n        if img_roi_head is not None:\n            self.img_roi_head = builder.build_head(img_roi_head)\n\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n\n        if pretrained is None:\n            img_pretrained = None\n            pts_pretrained = None\n        elif isinstance(pretrained, dict):\n            img_pretrained = pretrained.get('img', None)\n            pts_pretrained = pretrained.get('pts', None)\n        else:\n            raise ValueError(\n                f'pretrained should be a dict, got {type(pretrained)}')\n\n        if self.with_img_backbone:\n            if img_pretrained is not None:\n                warnings.warn('DeprecationWarning: pretrained is a deprecated \\\n                    key, please consider using init_cfg')\n                self.img_backbone.init_cfg = dict(\n                    type='Pretrained', checkpoint=img_pretrained)\n        if self.with_img_roi_head:\n            if img_pretrained is not None:\n                warnings.warn('DeprecationWarning: pretrained is a deprecated \\\n                    key, please consider using init_cfg')\n                self.img_roi_head.init_cfg = dict(\n                    type='Pretrained', checkpoint=img_pretrained)\n\n        if self.with_pts_backbone:\n            if pts_pretrained is not None:\n                warnings.warn('DeprecationWarning: pretrained is a deprecated \\\n                    key, please consider using init_cfg')\n                self.pts_backbone.init_cfg = dict(\n                    type='Pretrained', checkpoint=pts_pretrained)\n\n    @property\n    def with_img_shared_head(self):\n        \"\"\"bool: Whether the detector has a shared head in image branch.\"\"\"\n        return hasattr(self,\n                       'img_shared_head') and self.img_shared_head is not None\n\n    @property\n    def with_pts_bbox(self):\n        \"\"\"bool: Whether the detector has a 3D box head.\"\"\"\n        return hasattr(self,\n                       'pts_bbox_head') and self.pts_bbox_head is not None\n\n    @property\n    def with_img_bbox(self):\n        \"\"\"bool: Whether the detector has a 2D image box head.\"\"\"\n        return hasattr(self,\n                       'img_bbox_head') and self.img_bbox_head is not None\n\n    @property\n    def with_img_backbone(self):\n        \"\"\"bool: Whether the detector has a 2D image backbone.\"\"\"\n        return hasattr(self, 'img_backbone') and self.img_backbone is not None\n\n    @property\n    def with_pts_backbone(self):\n        \"\"\"bool: Whether the detector has a 3D backbone.\"\"\"\n        return hasattr(self, 'pts_backbone') and self.pts_backbone is not None\n\n    @property\n    def with_fusion(self):\n        \"\"\"bool: Whether the detector has a fusion layer.\"\"\"\n        return hasattr(self,\n                       'pts_fusion_layer') and self.fusion_layer is not None\n\n    @property\n    def with_img_neck(self):\n        \"\"\"bool: Whether the detector has a neck in image branch.\"\"\"\n        return hasattr(self, 'img_neck') and self.img_neck is not None\n\n    @property\n    def with_pts_neck(self):\n        \"\"\"bool: Whether the detector has a neck in 3D detector branch.\"\"\"\n        return hasattr(self, 'pts_neck') and self.pts_neck is not None\n\n    @property\n    def with_img_rpn(self):\n        \"\"\"bool: Whether the detector has a 2D RPN in image detector branch.\"\"\"\n        return hasattr(self, 'img_rpn_head') and self.img_rpn_head is not None\n\n    @property\n    def with_img_roi_head(self):\n        \"\"\"bool: Whether the detector has a RoI Head in image branch.\"\"\"\n        return hasattr(self, 'img_roi_head') and self.img_roi_head is not None\n\n    @property\n    def with_voxel_encoder(self):\n        \"\"\"bool: Whether the detector has a voxel encoder.\"\"\"\n        return hasattr(self,\n                       'voxel_encoder') and self.voxel_encoder is not None\n\n    @property\n    def with_middle_encoder(self):\n        \"\"\"bool: Whether the detector has a middle encoder.\"\"\"\n        return hasattr(self,\n                       'middle_encoder') and self.middle_encoder is not None\n\n    def extract_img_feat(self, img, img_metas):\n        \"\"\"Extract features of images.\"\"\"\n        if self.with_img_backbone and img is not None:\n            input_shape = img.shape[-2:]\n            # update real input shape of each single img\n            for img_meta in img_metas:\n                img_meta.update(input_shape=input_shape)\n\n            if img.dim() == 5 and img.size(0) == 1:\n                img.squeeze_()\n            elif img.dim() == 5 and img.size(0) > 1:\n                B, N, C, H, W = img.size()\n                img = img.view(B * N, C, H, W)\n            img_feats = self.img_backbone(img)\n        else:\n            return None\n        if self.with_img_neck:\n            img_feats = self.img_neck(img_feats)\n        return img_feats\n\n    def extract_pts_feat(self, pts, img_feats, img_metas):\n        \"\"\"Extract features of points.\"\"\"\n        if not self.with_pts_bbox:\n            return None\n        voxels, num_points, coors = self.voxelize(pts)\n        voxel_features = self.pts_voxel_encoder(voxels, num_points, coors,\n                                                img_feats, img_metas)\n        batch_size = coors[-1, 0] + 1\n        x = self.pts_middle_encoder(voxel_features, coors, batch_size)\n        x = self.pts_backbone(x)\n        if self.with_pts_neck:\n            x = self.pts_neck(x)\n        return x\n\n    def extract_feat(self, points, img, img_metas):\n        \"\"\"Extract features from images and points.\"\"\"\n        img_feats = self.extract_img_feat(img, img_metas)\n        pts_feats = self.extract_pts_feat(points, img_feats, img_metas)\n        return (img_feats, pts_feats)\n\n    @torch.no_grad()\n    @force_fp32()\n    def voxelize(self, points):\n        \"\"\"Apply dynamic voxelization to points.\n\n        Args:\n            points (list[torch.Tensor]): Points of each sample.\n\n        Returns:\n            tuple[torch.Tensor]: Concatenated points, number of points\n                per voxel, and coordinates.\n        \"\"\"\n        voxels, coors, num_points = [], [], []\n        for res in points:\n            res_voxels, res_coors, res_num_points = self.pts_voxel_layer(res)\n            voxels.append(res_voxels)\n            coors.append(res_coors)\n            num_points.append(res_num_points)\n        voxels = torch.cat(voxels, dim=0)\n        num_points = torch.cat(num_points, dim=0)\n        coors_batch = []\n        for i, coor in enumerate(coors):\n            coor_pad = F.pad(coor, (1, 0), mode='constant', value=i)\n            coors_batch.append(coor_pad)\n        coors_batch = torch.cat(coors_batch, dim=0)\n        return voxels, num_points, coors_batch\n\n    def forward_train(self,\n                      points=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      gt_labels=None,\n                      gt_bboxes=None,\n                      img=None,\n                      proposals=None,\n                      gt_bboxes_ignore=None):\n        \"\"\"Forward training function.\n\n        Args:\n            points (list[torch.Tensor], optional): Points of each sample.\n                Defaults to None.\n            img_metas (list[dict], optional): Meta information of each sample.\n                Defaults to None.\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`], optional):\n                Ground truth 3D boxes. Defaults to None.\n            gt_labels_3d (list[torch.Tensor], optional): Ground truth labels\n                of 3D boxes. Defaults to None.\n            gt_labels (list[torch.Tensor], optional): Ground truth labels\n                of 2D boxes in images. Defaults to None.\n            gt_bboxes (list[torch.Tensor], optional): Ground truth 2D boxes in\n                images. Defaults to None.\n            img (torch.Tensor optional): Images of each sample with shape\n                (N, C, H, W). Defaults to None.\n            proposals ([list[torch.Tensor], optional): Predicted proposals\n                used for training Fast RCNN. Defaults to None.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                2D boxes in images to be ignored. Defaults to None.\n\n        Returns:\n            dict: Losses of different branches.\n        \"\"\"\n        img_feats, pts_feats = self.extract_feat(\n            points, img=img, img_metas=img_metas)\n        losses = dict()\n        if pts_feats:\n            losses_pts = self.forward_pts_train(pts_feats, gt_bboxes_3d,\n                                                gt_labels_3d, img_metas,\n                                                gt_bboxes_ignore)\n            losses.update(losses_pts)\n        if img_feats:\n            losses_img = self.forward_img_train(\n                img_feats,\n                img_metas=img_metas,\n                gt_bboxes=gt_bboxes,\n                gt_labels=gt_labels,\n                gt_bboxes_ignore=gt_bboxes_ignore,\n                proposals=proposals)\n            losses.update(losses_img)\n        return losses\n\n    def forward_pts_train(self,\n                          pts_feats,\n                          gt_bboxes_3d,\n                          gt_labels_3d,\n                          img_metas,\n                          gt_bboxes_ignore=None):\n        \"\"\"Forward function for point cloud branch.\n\n        Args:\n            pts_feats (list[torch.Tensor]): Features of point cloud branch\n            gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`]): Ground truth\n                boxes for each sample.\n            gt_labels_3d (list[torch.Tensor]): Ground truth labels for\n                boxes of each sampole\n            img_metas (list[dict]): Meta information of samples.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                boxes to be ignored. Defaults to None.\n\n        Returns:\n            dict: Losses of each branch.\n        \"\"\"\n        outs = self.pts_bbox_head(pts_feats)\n        loss_inputs = outs + (gt_bboxes_3d, gt_labels_3d, img_metas)\n        losses = self.pts_bbox_head.loss(\n            *loss_inputs, gt_bboxes_ignore=gt_bboxes_ignore)\n        return losses\n\n    def forward_img_train(self,\n                          x,\n                          img_metas,\n                          gt_bboxes,\n                          gt_labels,\n                          gt_bboxes_ignore=None,\n                          proposals=None,\n                          **kwargs):\n        \"\"\"Forward function for image branch.\n\n        This function works similar to the forward function of Faster R-CNN.\n\n        Args:\n            x (list[torch.Tensor]): Image features of shape (B, C, H, W)\n                of multiple levels.\n            img_metas (list[dict]): Meta information of images.\n            gt_bboxes (list[torch.Tensor]): Ground truth boxes of each image\n                sample.\n            gt_labels (list[torch.Tensor]): Ground truth labels of boxes.\n            gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth\n                boxes to be ignored. Defaults to None.\n            proposals (list[torch.Tensor], optional): Proposals of each sample.\n                Defaults to None.\n\n        Returns:\n            dict: Losses of each branch.\n        \"\"\"\n        losses = dict()\n        # RPN forward and loss\n        if self.with_img_rpn:\n            rpn_outs = self.img_rpn_head(x)\n            rpn_loss_inputs = rpn_outs + (gt_bboxes, img_metas,\n                                          self.train_cfg.img_rpn)\n            rpn_losses = self.img_rpn_head.loss(\n                *rpn_loss_inputs, gt_bboxes_ignore=gt_bboxes_ignore)\n            losses.update(rpn_losses)\n\n            proposal_cfg = self.train_cfg.get('img_rpn_proposal',\n                                              self.test_cfg.img_rpn)\n            proposal_inputs = rpn_outs + (img_metas, proposal_cfg)\n            proposal_list = self.img_rpn_head.get_bboxes(*proposal_inputs)\n        else:\n            proposal_list = proposals\n\n        # bbox head forward and loss\n        if self.with_img_bbox:\n            # bbox head forward and loss\n            img_roi_losses = self.img_roi_head.forward_train(\n                x, img_metas, proposal_list, gt_bboxes, gt_labels,\n                gt_bboxes_ignore, **kwargs)\n            losses.update(img_roi_losses)\n\n        return losses\n\n    def simple_test_img(self, x, img_metas, proposals=None, rescale=False):\n        \"\"\"Test without augmentation.\"\"\"\n        if proposals is None:\n            proposal_list = self.simple_test_rpn(x, img_metas,\n                                                 self.test_cfg.img_rpn)\n        else:\n            proposal_list = proposals\n\n        return self.img_roi_head.simple_test(\n            x, proposal_list, img_metas, rescale=rescale)\n\n    def simple_test_rpn(self, x, img_metas, rpn_test_cfg):\n        \"\"\"RPN test function.\"\"\"\n        rpn_outs = self.img_rpn_head(x)\n        proposal_inputs = rpn_outs + (img_metas, rpn_test_cfg)\n        proposal_list = self.img_rpn_head.get_bboxes(*proposal_inputs)\n        return proposal_list\n\n    def simple_test_pts(self, x, img_metas, rescale=False):\n        \"\"\"Test function of point cloud branch.\"\"\"\n        outs = self.pts_bbox_head(x)\n        bbox_list = self.pts_bbox_head.get_bboxes(\n            *outs, img_metas, rescale=rescale)\n        bbox_results = [\n            bbox3d2result(bboxes, scores, labels)\n            for bboxes, scores, labels in bbox_list\n        ]\n        return bbox_results\n\n    def simple_test(self, points, img_metas, img=None, rescale=False):\n        \"\"\"Test function without augmentaiton.\"\"\"\n        img_feats, pts_feats = self.extract_feat(\n            points, img=img, img_metas=img_metas)\n\n        bbox_list = [dict() for i in range(len(img_metas))]\n        if pts_feats and self.with_pts_bbox:\n            bbox_pts = self.simple_test_pts(\n                pts_feats, img_metas, rescale=rescale)\n            for result_dict, pts_bbox in zip(bbox_list, bbox_pts):\n                result_dict['pts_bbox'] = pts_bbox\n        if img_feats and self.with_img_bbox:\n            bbox_img = self.simple_test_img(\n                img_feats, img_metas, rescale=rescale)\n            for result_dict, img_bbox in zip(bbox_list, bbox_img):\n                result_dict['img_bbox'] = img_bbox\n        return bbox_list\n\n    def aug_test(self, points, img_metas, imgs=None, rescale=False):\n        \"\"\"Test function with augmentaiton.\"\"\"\n        img_feats, pts_feats = self.extract_feats(points, img_metas, imgs)\n\n        bbox_list = dict()\n        if pts_feats and self.with_pts_bbox:\n            bbox_pts = self.aug_test_pts(pts_feats, img_metas, rescale)\n            bbox_list.update(pts_bbox=bbox_pts)\n        return [bbox_list]\n\n    def extract_feats(self, points, img_metas, imgs=None):\n        \"\"\"Extract point and image features of multiple samples.\"\"\"\n        if imgs is None:\n            imgs = [None] * len(img_metas)\n        img_feats, pts_feats = multi_apply(self.extract_feat, points, imgs,\n                                           img_metas)\n        return img_feats, pts_feats\n\n    def aug_test_pts(self, feats, img_metas, rescale=False):\n        \"\"\"Test function of point cloud branch with augmentaiton.\"\"\"\n        # only support aug_test for one sample\n        aug_bboxes = []\n        for x, img_meta in zip(feats, img_metas):\n            outs = self.pts_bbox_head(x)\n            bbox_list = self.pts_bbox_head.get_bboxes(\n                *outs, img_meta, rescale=rescale)\n            bbox_list = [\n                dict(boxes_3d=bboxes, scores_3d=scores, labels_3d=labels)\n                for bboxes, scores, labels in bbox_list\n            ]\n            aug_bboxes.append(bbox_list[0])\n\n        # after merging, bboxes will be rescaled to the original image size\n        merged_bboxes = merge_aug_bboxes_3d(aug_bboxes, img_metas,\n                                            self.pts_bbox_head.test_cfg)\n        return merged_bboxes\n\n    def show_results(self, data, result, out_dir):\n        \"\"\"Results visualization.\n\n        Args:\n            data (dict): Input points and the information of the sample.\n            result (dict): Prediction results.\n            out_dir (str): Output directory of visualization result.\n        \"\"\"\n        for batch_id in range(len(result)):\n            if isinstance(data['points'][0], DC):\n                points = data['points'][0]._data[0][batch_id].numpy()\n            elif is_list_of(data['points'][0], torch.Tensor):\n                points = data['points'][0][batch_id]\n            else:\n                ValueError(f\"Unsupported data type {type(data['points'][0])} \"\n                           f'for visualization!')\n            if isinstance(data['img_metas'][0], DC):\n                pts_filename = data['img_metas'][0]._data[0][batch_id][\n                    'pts_filename']\n                box_mode_3d = data['img_metas'][0]._data[0][batch_id][\n                    'box_mode_3d']\n            elif is_list_of(data['img_metas'][0], dict):\n                pts_filename = data['img_metas'][0][batch_id]['pts_filename']\n                box_mode_3d = data['img_metas'][0][batch_id]['box_mode_3d']\n            else:\n                ValueError(\n                    f\"Unsupported data type {type(data['img_metas'][0])} \"\n                    f'for visualization!')\n            file_name = osp.split(pts_filename)[-1].split('.')[0]\n\n            assert out_dir is not None, 'Expect out_dir, got none.'\n            inds = result[batch_id]['pts_bbox']['scores_3d'] > 0.1\n            pred_bboxes = result[batch_id]['pts_bbox']['boxes_3d'][inds]\n\n            # for now we convert points and bbox into depth mode\n            if (box_mode_3d == Box3DMode.CAM) or (box_mode_3d\n                                                  == Box3DMode.LIDAR):\n                points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,\n                                                   Coord3DMode.DEPTH)\n                pred_bboxes = Box3DMode.convert(pred_bboxes, box_mode_3d,\n                                                Box3DMode.DEPTH)\n            elif box_mode_3d != Box3DMode.DEPTH:\n                ValueError(\n                    f'Unsupported box_mode_3d {box_mode_3d} for convertion!')\n\n            pred_bboxes = pred_bboxes.tensor.cpu().numpy()\n            show_result(points, None, pred_bboxes, out_dir, file_name)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/single_stage.py",
    "content": "import warnings\n\nimport torch\n\nfrom mmcv.core.bbox.transforms import bbox2result\nfrom mmcv.models import DETECTORS, build_backbone, build_head, build_neck\nfrom ..builder import DETECTORS, build_backbone, build_head, build_neck\nfrom .base import BaseDetector, Base3DDetector\n\n\n@DETECTORS.register_module()\nclass SingleStageDetector(BaseDetector):\n    \"\"\"Base class for single-stage detectors.\n\n    Single-stage detectors directly and densely predict bounding boxes on the\n    output features of the backbone+neck.\n    \"\"\"\n\n    def __init__(self,\n                 backbone,\n                 neck=None,\n                 bbox_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 pretrained=None,\n                 init_cfg=None):\n        super(SingleStageDetector, self).__init__(init_cfg)\n        if pretrained:\n            warnings.warn('DeprecationWarning: pretrained is deprecated, '\n                          'please use \"init_cfg\" instead')\n            backbone.pretrained = pretrained\n        self.backbone = build_backbone(backbone)\n        if neck is not None:\n            self.neck = build_neck(neck)\n        bbox_head.update(train_cfg=train_cfg)\n        bbox_head.update(test_cfg=test_cfg)\n        self.bbox_head = build_head(bbox_head)\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n\n    def extract_feat(self, img):\n        \"\"\"Directly extract features from the backbone+neck.\"\"\"\n        x = self.backbone(img)\n        if self.with_neck:\n            x = self.neck(x)\n        return x\n\n    def forward_dummy(self, img):\n        \"\"\"Used for computing network flops.\n\n        See `mmcvection/tools/analysis_tools/get_flops.py`\n        \"\"\"\n        x = self.extract_feat(img)\n        outs = self.bbox_head(x)\n        return outs\n\n    def forward_train(self,\n                      img,\n                      img_metas,\n                      gt_bboxes,\n                      gt_labels,\n                      gt_bboxes_ignore=None):\n        \"\"\"\n        Args:\n            img (Tensor): Input images of shape (N, C, H, W).\n                Typically these should be mean centered and std scaled.\n            img_metas (list[dict]): A List of image info dict where each dict\n                has: 'img_shape', 'scale_factor', 'flip', and may also contain\n                'filename', 'ori_shape', 'pad_shape', and 'img_norm_cfg'.\n                For details on the values of these keys see\n                :class:`mmcv.datasets.pipelines.Collect`.\n            gt_bboxes (list[Tensor]): Each item are the truth boxes for each\n                image in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (list[Tensor]): Class indices corresponding to each box\n            gt_bboxes_ignore (None | list[Tensor]): Specify which bounding\n                boxes can be ignored when computing the loss.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        super(SingleStageDetector, self).forward_train(img, img_metas)\n        x = self.extract_feat(img)\n        losses = self.bbox_head.forward_train(x, img_metas, gt_bboxes,\n                                              gt_labels, gt_bboxes_ignore)\n        return losses\n\n    def simple_test(self, img, img_metas, rescale=False):\n        \"\"\"Test function without test-time augmentation.\n\n        Args:\n            img (torch.Tensor): Images with shape (N, C, H, W).\n            img_metas (list[dict]): List of image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[list[np.ndarray]]: BBox results of each image and classes.\n                The outer list corresponds to each image. The inner list\n                corresponds to each class.\n        \"\"\"\n        feat = self.extract_feat(img)\n        results_list = self.bbox_head.simple_test(\n            feat, img_metas, rescale=rescale)\n        bbox_results = [\n            bbox2result(det_bboxes, det_labels, self.bbox_head.num_classes)\n            for det_bboxes, det_labels in results_list\n        ]\n        return bbox_results\n\n    def aug_test(self, imgs, img_metas, rescale=False):\n        \"\"\"Test function with test time augmentation.\n\n        Args:\n            imgs (list[Tensor]): the outer list indicates test-time\n                augmentations and inner Tensor should have a shape NxCxHxW,\n                which contains all images in the batch.\n            img_metas (list[list[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch. each dict has image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[list[np.ndarray]]: BBox results of each image and classes.\n                The outer list corresponds to each image. The inner list\n                corresponds to each class.\n        \"\"\"\n        assert hasattr(self.bbox_head, 'aug_test'), \\\n            f'{self.bbox_head.__class__.__name__}' \\\n            ' does not support test-time augmentation'\n\n        feats = self.extract_feats(imgs)\n        results_list = self.bbox_head.aug_test(\n            feats, img_metas, rescale=rescale)\n        bbox_results = [\n            bbox2result(det_bboxes, det_labels, self.bbox_head.num_classes)\n            for det_bboxes, det_labels in results_list\n        ]\n        return bbox_results\n\n    def onnx_export(self, img, img_metas):\n        \"\"\"Test function without test time augmentation.\n\n        Args:\n            img (torch.Tensor): input images.\n            img_metas (list[dict]): List of image information.\n\n        Returns:\n            tuple[Tensor, Tensor]: dets of shape [N, num_det, 5]\n                and class labels of shape [N, num_det].\n        \"\"\"\n        x = self.extract_feat(img)\n        outs = self.bbox_head(x)\n        # get origin input shape to support onnx dynamic shape\n\n        # get shape as tensor\n        img_shape = torch._shape_as_tensor(img)[2:]\n        img_metas[0]['img_shape_for_onnx'] = img_shape\n        # get pad input shape to support onnx dynamic shape for exporting\n        # `CornerNet` and `CentripetalNet`, which 'pad_shape' is used\n        # for inference\n        img_metas[0]['pad_shape_for_onnx'] = img_shape\n        # TODO:move all onnx related code in bbox_head to onnx_export function\n        det_bboxes, det_labels = self.bbox_head.get_bboxes(*outs, img_metas)\n\n        return det_bboxes, det_labels\n    \n@DETECTORS.register_module()\nclass SingleStage3DDetector(Base3DDetector):\n    \"\"\"SingleStage3DDetector.\n\n    This class serves as a base class for single-stage 3D detectors.\n\n    Args:\n        backbone (dict): Config dict of detector's backbone.\n        neck (dict, optional): Config dict of neck. Defaults to None.\n        bbox_head (dict, optional): Config dict of box head. Defaults to None.\n        train_cfg (dict, optional): Config dict of training hyper-parameters.\n            Defaults to None.\n        test_cfg (dict, optional): Config dict of test hyper-parameters.\n            Defaults to None.\n        pretrained (str, optional): Path of pretrained models.\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self,\n                 backbone,\n                 neck=None,\n                 bbox_head=None,\n                 train_cfg=None,\n                 test_cfg=None,\n                 init_cfg=None,\n                 pretrained=None):\n        super(SingleStage3DDetector, self).__init__(init_cfg)\n        self.backbone = build_backbone(backbone)\n        if neck is not None:\n            self.neck = build_neck(neck)\n        bbox_head.update(train_cfg=train_cfg)\n        bbox_head.update(test_cfg=test_cfg)\n        self.bbox_head = build_head(bbox_head)\n        self.train_cfg = train_cfg\n        self.test_cfg = test_cfg\n\n    def forward_dummy(self, points):\n        \"\"\"Used for computing network flops.\n\n        See `mmcvection/tools/analysis_tools/get_flops.py`\n        \"\"\"\n        x = self.extract_feat(points)\n        try:\n            sample_mod = self.train_cfg.sample_mod\n            outs = self.bbox_head(x, sample_mod)\n        except AttributeError:\n            outs = self.bbox_head(x)\n        return outs\n\n    def extract_feat(self, points, img_metas=None):\n        \"\"\"Directly extract features from the backbone+neck.\n\n        Args:\n            points (torch.Tensor): Input points.\n        \"\"\"\n        x = self.backbone(points)\n        if self.with_neck:\n            x = self.neck(x)\n        return x\n\n    def extract_feats(self, points, img_metas):\n        \"\"\"Extract features of multiple samples.\"\"\"\n        return [\n            self.extract_feat(pts, img_meta)\n            for pts, img_meta in zip(points, img_metas)\n        ]\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/single_stage_mono3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom mmcv.parallel import DataContainer as DC\nfrom os import path as osp\n\nfrom mmcv.core.bbox.structures.cam_box3d import CameraInstance3DBoxes\nfrom mmcv.core.bbox.transforms import bbox3d2result\nfrom mmcv.core.visualizer import show_multi_modality_result\n\n\n# from mmcv.core import (CameraInstance3DBoxes, bbox3d2result,\n#                           show_multi_modality_result)\nfrom mmcv.models.builder import DETECTORS\nfrom mmcv.models.detectors.single_stage import SingleStageDetector\nfrom mmcv.utils import is_list_of\nfrom mmcv.image import imread\n\n\n@DETECTORS.register_module()\nclass SingleStageMono3DDetector(SingleStageDetector):\n    \"\"\"Base class for monocular 3D single-stage detectors.\n\n    Single-stage detectors directly and densely predict bounding boxes on the\n    output features of the backbone+neck.\n    \"\"\"\n\n    def extract_feats(self, imgs):\n        \"\"\"Directly extract features from the backbone+neck.\"\"\"\n        assert isinstance(imgs, list)\n        return [self.extract_feat(img) for img in imgs]\n\n    def forward_train(self,\n                      img,\n                      img_metas,\n                      gt_bboxes,\n                      gt_labels,\n                      gt_bboxes_3d,\n                      gt_labels_3d,\n                      centers2d,\n                      depths,\n                      attr_labels=None,\n                      gt_bboxes_ignore=None):\n        \"\"\"\n        Args:\n            img (Tensor): Input images of shape (N, C, H, W).\n                Typically these should be mean centered and std scaled.\n            img_metas (list[dict]): A List of image info dict where each dict\n                has: 'img_shape', 'scale_factor', 'flip', and may also contain\n                'filename', 'ori_shape', 'pad_shape', and 'img_norm_cfg'.\n                For details on the values of these keys see\n                :class:`mmcv.datasets.pipelines.Collect`.\n            gt_bboxes (list[Tensor]): Each item are the truth boxes for each\n                image in [tl_x, tl_y, br_x, br_y] format.\n            gt_labels (list[Tensor]): Class indices corresponding to each box\n            gt_bboxes_3d (list[Tensor]): Each item are the 3D truth boxes for\n                each image in [x, y, z, w, l, h, theta, vx, vy] format.\n            gt_labels_3d (list[Tensor]): 3D class indices corresponding to\n                each box.\n            centers2d (list[Tensor]): Projected 3D centers onto 2D images.\n            depths (list[Tensor]): Depth of projected centers on 2D images.\n            attr_labels (list[Tensor], optional): Attribute indices\n                corresponding to each box\n            gt_bboxes_ignore (None | list[Tensor]): Specify which bounding\n                boxes can be ignored when computing the loss.\n\n        Returns:\n            dict[str, Tensor]: A dictionary of loss components.\n        \"\"\"\n        x = self.extract_feat(img)\n        losses = self.bbox_head.forward_train(x, img_metas, gt_bboxes,\n                                              gt_labels, gt_bboxes_3d,\n                                              gt_labels_3d, centers2d, depths,\n                                              attr_labels, gt_bboxes_ignore)\n        return losses\n\n    def simple_test(self, img, img_metas, rescale=False):\n        \"\"\"Test function without test time augmentation.\n\n        Args:\n            imgs (list[torch.Tensor]): List of multiple images\n            img_metas (list[dict]): List of image information.\n            rescale (bool, optional): Whether to rescale the results.\n                Defaults to False.\n\n        Returns:\n            list[list[np.ndarray]]: BBox results of each image and classes.\n                The outer list corresponds to each image. The inner list\n                corresponds to each class.\n        \"\"\"\n        x = self.extract_feat(img)\n        outs = self.bbox_head(x)\n        bbox_outputs = self.bbox_head.get_bboxes(\n            *outs, img_metas, rescale=rescale)\n\n        if self.bbox_head.pred_bbox2d:\n            from mmcv.core import bbox2result\n            bbox2d_img = [\n                bbox2result(bboxes2d, labels, self.bbox_head.num_classes)\n                for bboxes, scores, labels, attrs, bboxes2d in bbox_outputs\n            ]\n            bbox_outputs = [bbox_outputs[0][:-1]]\n\n        bbox_img = [\n            bbox3d2result(bboxes, scores, labels, attrs)\n            for bboxes, scores, labels, attrs in bbox_outputs\n        ]\n\n        bbox_list = [dict() for i in range(len(img_metas))]\n        for result_dict, img_bbox in zip(bbox_list, bbox_img):\n            result_dict['img_bbox'] = img_bbox\n        if self.bbox_head.pred_bbox2d:\n            for result_dict, img_bbox2d in zip(bbox_list, bbox2d_img):\n                result_dict['img_bbox2d'] = img_bbox2d\n        return bbox_list\n\n    def aug_test(self, imgs, img_metas, rescale=False):\n        \"\"\"Test function with test time augmentation.\"\"\"\n        feats = self.extract_feats(imgs)\n\n        # only support aug_test for one sample\n        outs_list = [self.bbox_head(x) for x in feats]\n        for i, img_meta in enumerate(img_metas):\n            if img_meta[0]['pcd_horizontal_flip']:\n                for j in range(len(outs_list[i])):  # for each prediction\n                    if outs_list[i][j][0] is None:\n                        continue\n                    for k in range(len(outs_list[i][j])):\n                        # every stride of featmap\n                        outs_list[i][j][k] = torch.flip(\n                            outs_list[i][j][k], dims=[3])\n                reg = outs_list[i][1]\n                for reg_feat in reg:\n                    # offset_x\n                    reg_feat[:, 0, :, :] = 1 - reg_feat[:, 0, :, :]\n                    # velo_x\n                    if self.bbox_head.pred_velo:\n                        reg_feat[:, 7, :, :] = -reg_feat[:, 7, :, :]\n                    # rotation\n                    reg_feat[:, 6, :, :] = -reg_feat[:, 6, :, :] + np.pi\n\n        merged_outs = []\n        for i in range(len(outs_list[0])):  # for each prediction\n            merged_feats = []\n            for j in range(len(outs_list[0][i])):\n                if outs_list[0][i][0] is None:\n                    merged_feats.append(None)\n                    continue\n                # for each stride of featmap\n                avg_feats = torch.mean(\n                    torch.cat([x[i][j] for x in outs_list]),\n                    dim=0,\n                    keepdim=True)\n                if i == 1:  # regression predictions\n                    # rot/velo/2d det keeps the original\n                    avg_feats[:, 6:, :, :] = \\\n                        outs_list[0][i][j][:, 6:, :, :]\n                if i == 2:\n                    # dir_cls keeps the original\n                    avg_feats = outs_list[0][i][j]\n                merged_feats.append(avg_feats)\n            merged_outs.append(merged_feats)\n        merged_outs = tuple(merged_outs)\n\n        bbox_outputs = self.bbox_head.get_bboxes(\n            *merged_outs, img_metas[0], rescale=rescale)\n        if self.bbox_head.pred_bbox2d:\n            from mmcv.core import bbox2result\n            bbox2d_img = [\n                bbox2result(bboxes2d, labels, self.bbox_head.num_classes)\n                for bboxes, scores, labels, attrs, bboxes2d in bbox_outputs\n            ]\n            bbox_outputs = [bbox_outputs[0][:-1]]\n\n        bbox_img = [\n            bbox3d2result(bboxes, scores, labels, attrs)\n            for bboxes, scores, labels, attrs in bbox_outputs\n        ]\n\n        bbox_list = dict()\n        bbox_list.update(img_bbox=bbox_img[0])\n        if self.bbox_head.pred_bbox2d:\n            bbox_list.update(img_bbox2d=bbox2d_img[0])\n\n        return [bbox_list]\n\n    def show_results(self, data, result, out_dir):\n        \"\"\"Results visualization.\n\n        Args:\n            data (list[dict]): Input images and the information of the sample.\n            result (list[dict]): Prediction results.\n            out_dir (str): Output directory of visualization result.\n        \"\"\"\n        for batch_id in range(len(result)):\n            if isinstance(data['img_metas'][0], DC):\n                img_filename = data['img_metas'][0]._data[0][batch_id][\n                    'filename']\n                cam2img = data['img_metas'][0]._data[0][batch_id]['cam2img']\n            elif is_list_of(data['img_metas'][0], dict):\n                img_filename = data['img_metas'][0][batch_id]['filename']\n                cam2img = data['img_metas'][0][batch_id]['cam2img']\n            else:\n                ValueError(\n                    f\"Unsupported data type {type(data['img_metas'][0])} \"\n                    f'for visualization!')\n            img = imread(img_filename)\n            file_name = osp.split(img_filename)[-1].split('.')[0]\n\n            assert out_dir is not None, 'Expect out_dir, got none.'\n\n            pred_bboxes = result[batch_id]['img_bbox']['boxes_3d']\n            assert isinstance(pred_bboxes, CameraInstance3DBoxes), \\\n                f'unsupported predicted bbox type {type(pred_bboxes)}'\n\n            show_multi_modality_result(\n                img,\n                None,\n                pred_bboxes,\n                cam2img,\n                out_dir,\n                file_name,\n                'camera',\n                show=True)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/sparsedrive.py",
    "content": "from inspect import signature\n\nimport torch\n\nfrom mmcv.runner import force_fp32, auto_fp16\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\nfrom mmdet.models import (\n    DETECTORS,\n    BaseDetector,\n    build_backbone,\n    build_head,\n    build_neck,\n)\nfrom .grid_mask import GridMask\n\ntry:\n    from ..ops import feature_maps_format\n    DAF_VALID = True\nexcept:\n    DAF_VALID = False\n\n__all__ = [\"SparseDrive\"]\n\n\n@DETECTORS.register_module()\nclass SparseDrive(BaseDetector):\n    def __init__(\n        self,\n        img_backbone,\n        head,\n        img_neck=None,\n        init_cfg=None,\n        train_cfg=None,\n        test_cfg=None,\n        pretrained=None,\n        use_grid_mask=True,\n        use_deformable_func=False,\n        depth_branch=None,\n    ):\n        super(SparseDrive, self).__init__(init_cfg=init_cfg)\n        if pretrained is not None:\n            backbone.pretrained = pretrained\n        self.img_backbone = build_backbone(img_backbone)\n        if img_neck is not None:\n            self.img_neck = build_neck(img_neck)\n        self.head = build_head(head)\n        self.use_grid_mask = use_grid_mask\n        if use_deformable_func:\n            assert DAF_VALID, \"deformable_aggregation needs to be set up.\"\n        self.use_deformable_func = use_deformable_func\n        if depth_branch is not None:\n            self.depth_branch = build_from_cfg(depth_branch, PLUGIN_LAYERS)\n        else:\n            self.depth_branch = None\n        if use_grid_mask:\n            self.grid_mask = GridMask(\n                True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7\n            ) \n\n    @auto_fp16(apply_to=(\"img\",), out_fp32=True)\n    def extract_feat(self, img, return_depth=False, metas=None):\n        bs = img.shape[0]\n        if img.dim() == 5:  # multi-view\n            num_cams = img.shape[1]\n            img = img.flatten(end_dim=1)\n        else:\n            num_cams = 1\n        if self.use_grid_mask:\n            img = self.grid_mask(img)\n        if \"metas\" in signature(self.img_backbone.forward).parameters:\n            feature_maps = self.img_backbone(img, num_cams, metas=metas)\n        else:\n            feature_maps = self.img_backbone(img)\n        if self.img_neck is not None:\n            feature_maps = list(self.img_neck(feature_maps))\n        for i, feat in enumerate(feature_maps):\n            feature_maps[i] = torch.reshape(\n                feat, (bs, num_cams) + feat.shape[1:]\n            )\n        if return_depth and self.depth_branch is not None:\n            depths = self.depth_branch(feature_maps, metas.get(\"focal\"))\n        else:\n            depths = None\n        if self.use_deformable_func:\n            feature_maps = feature_maps_format(feature_maps)\n        if return_depth:\n            return feature_maps, depths\n        return feature_maps\n\n    @force_fp32(apply_to=(\"img\",))\n    def forward(self, img, **data):\n        if self.training:\n            return self.forward_train(img, **data)\n        else:\n            return self.forward_test(img, **data)\n\n    def forward_train(self, img, **data):\n        feature_maps, depths = self.extract_feat(img, True, data)\n        model_outs = self.head(feature_maps, data)\n        output = self.head.loss(model_outs, data)\n        if depths is not None and \"gt_depth\" in data:\n            output[\"loss_dense_depth\"] = self.depth_branch.loss(\n                depths, data[\"gt_depth\"]\n            )\n        return output\n\n    def forward_test(self, img, **data):\n        if isinstance(img, list):\n            return self.aug_test(img, **data)\n        else:\n            return self.simple_test(img, **data)\n\n    def simple_test(self, img, **data):\n        feature_maps = self.extract_feat(img)\n\n        model_outs = self.head(feature_maps, data)\n        results = self.head.post_process(model_outs, data)\n        output = [{\"img_bbox\": result} for result in results]\n        return output\n\n    def aug_test(self, img, **data):\n        # fake test time augmentation\n        for key in data.keys():\n            if isinstance(data[key], list):\n                data[key] = data[key][0]\n        return self.simple_test(img[0], **data)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/uniad_e2e.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nfrom mmcv.utils import auto_fp16\nfrom mmcv.models import DETECTORS\nimport copy\nimport os\nfrom ..dense_heads.seg_head_plugin import IOU\nfrom .uniad_track import UniADTrack\nfrom mmcv.models.builder import build_head\n\n@DETECTORS.register_module()\nclass UniAD(UniADTrack):\n    \"\"\"\n    UniAD: Unifying Detection, Tracking, Segmentation, Motion Forecasting, Occupancy Prediction and Planning for Autonomous Driving\n    \"\"\"\n    def __init__(\n        self,\n        seg_head=None,\n        motion_head=None,\n        occ_head=None,\n        planning_head=None,\n        task_loss_weight=dict(\n            track=1.0,\n            map=1.0,\n            motion=1.0,\n            occ=1.0,\n            planning=1.0\n        ),\n        **kwargs,\n    ):\n        super(UniAD, self).__init__(**kwargs)\n        if seg_head:\n            self.seg_head = build_head(seg_head)\n        if occ_head:\n            self.occ_head = build_head(occ_head)\n        if motion_head:\n            self.motion_head = build_head(motion_head)\n        if planning_head:\n            self.planning_head = build_head(planning_head)\n        \n        self.task_loss_weight = task_loss_weight\n        assert set(task_loss_weight.keys()) == \\\n               {'track', 'occ', 'motion', 'map', 'planning'}\n\n    @property\n    def with_planning_head(self):\n        return hasattr(self, 'planning_head') and self.planning_head is not None\n    \n    @property\n    def with_occ_head(self):\n        return hasattr(self, 'occ_head') and self.occ_head is not None\n\n    @property\n    def with_motion_head(self):\n        return hasattr(self, 'motion_head') and self.motion_head is not None\n\n    @property\n    def with_seg_head(self):\n        return hasattr(self, 'seg_head') and self.seg_head is not None\n\n    def forward_dummy(self, img):\n        dummy_metas = None\n        return self.forward_test(img=img, img_metas=[[dummy_metas]])\n\n    def forward(self, inputs, return_loss=True, rescale=False):\n        \"\"\"Calls either forward_train or forward_test depending on whether\n        return_loss=True.\n        Note this setting will change the expected inputs. When\n        `return_loss=True`, img and img_metas are single-nested (i.e.\n        torch.Tensor and list[dict]), and when `resturn_loss=False`, img and\n        img_metas should be double nested (i.e.  list[torch.Tensor],\n        list[list[dict]]), with the outer list indicating test time\n        augmentations.\n        \"\"\"\n        if return_loss:\n            losses = self.forward_train(**inputs)\n            loss, log_vars = self._parse_losses(losses)\n            outputs = dict(\n                loss=loss, log_vars=log_vars, num_samples=len(inputs['img_metas']))\n            return outputs\n        else:\n            outputs = self.forward_test(**inputs, rescale=rescale)\n            return outputs\n\n    # Add the subtask loss to the whole model loss\n    @auto_fp16(apply_to=('img', 'points'))\n    def forward_train(self,\n                      img=None,\n                      img_metas=None,\n                      gt_bboxes_3d=None,\n                      gt_labels_3d=None,\n                      gt_inds=None,\n                      l2g_t=None,\n                      l2g_r_mat=None,\n                      timestamp=None,\n                      gt_lane_labels=None,\n                      gt_lane_bboxes=None,\n                      gt_lane_masks=None,\n                      gt_fut_traj=None,\n                      gt_fut_traj_mask=None,\n                      gt_past_traj=None,\n                      gt_past_traj_mask=None,\n                      gt_sdc_bbox=None,\n                      gt_sdc_label=None,\n                      gt_sdc_fut_traj=None,\n                      gt_sdc_fut_traj_mask=None,\n                      \n                      # Occ_gt\n                      gt_segmentation=None,\n                      gt_instance=None, \n                      gt_occ_img_is_valid=None,\n                      \n                      #planning\n                      sdc_planning=None,\n                      sdc_planning_mask=None,\n                      command=None,\n                      \n                      # fut gt for planning\n                      gt_future_boxes=None,\n                      **kwargs,  # [1, 9]\n                      ):\n        \"\"\"Forward training function for the model that includes multiple tasks, such as tracking, segmentation, motion prediction, occupancy prediction, and planning.\n\n            Args:\n            img (torch.Tensor, optional): Tensor containing images of each sample with shape (N, C, H, W). Defaults to None.\n            img_metas (list[dict], optional): List of dictionaries containing meta information for each sample. Defaults to None.\n            gt_bboxes_3d (list[:obj:BaseInstance3DBoxes], optional): List of ground truth 3D bounding boxes for each sample. Defaults to None.\n            gt_labels_3d (list[torch.Tensor], optional): List of tensors containing ground truth labels for 3D bounding boxes. Defaults to None.\n            gt_inds (list[torch.Tensor], optional): List of tensors containing indices of ground truth objects. Defaults to None.\n            l2g_t (list[torch.Tensor], optional): List of tensors containing translation vectors from local to global coordinates. Defaults to None.\n            l2g_r_mat (list[torch.Tensor], optional): List of tensors containing rotation matrices from local to global coordinates. Defaults to None.\n            timestamp (list[float], optional): List of timestamps for each sample. Defaults to None.\n            gt_bboxes_ignore (list[torch.Tensor], optional): List of tensors containing ground truth 2D bounding boxes in images to be ignored. Defaults to None.\n            gt_lane_labels (list[torch.Tensor], optional): List of tensors containing ground truth lane labels. Defaults to None.\n            gt_lane_bboxes (list[torch.Tensor], optional): List of tensors containing ground truth lane bounding boxes. Defaults to None.\n            gt_lane_masks (list[torch.Tensor], optional): List of tensors containing ground truth lane masks. Defaults to None.\n            gt_fut_traj (list[torch.Tensor], optional): List of tensors containing ground truth future trajectories. Defaults to None.\n            gt_fut_traj_mask (list[torch.Tensor], optional): List of tensors containing ground truth future trajectory masks. Defaults to None.\n            gt_past_traj (list[torch.Tensor], optional): List of tensors containing ground truth past trajectories. Defaults to None.\n            gt_past_traj_mask (list[torch.Tensor], optional): List of tensors containing ground truth past trajectory masks. Defaults to None.\n            gt_sdc_bbox (list[torch.Tensor], optional): List of tensors containing ground truth self-driving car bounding boxes. Defaults to None.\n            gt_sdc_label (list[torch.Tensor], optional): List of tensors containing ground truth self-driving car labels. Defaults to None.\n            gt_sdc_fut_traj (list[torch.Tensor], optional): List of tensors containing ground truth self-driving car future trajectories. Defaults to None.\n            gt_sdc_fut_traj_mask (list[torch.Tensor], optional): List of tensors containing ground truth self-driving car future trajectory masks. Defaults to None.\n            gt_segmentation (list[torch.Tensor], optional): List of tensors containing ground truth segmentation masks. Defaults to\n            gt_instance (list[torch.Tensor], optional): List of tensors containing ground truth instance segmentation masks. Defaults to None.\n            gt_occ_img_is_valid (list[torch.Tensor], optional): List of tensors containing binary flags indicating whether an image is valid for occupancy prediction. Defaults to None.\n            sdc_planning (list[torch.Tensor], optional): List of tensors containing self-driving car planning information. Defaults to None.\n            sdc_planning_mask (list[torch.Tensor], optional): List of tensors containing self-driving car planning masks. Defaults to None.\n            command (list[torch.Tensor], optional): List of tensors containing high-level command information for planning. Defaults to None.\n            gt_future_boxes (list[torch.Tensor], optional): List of tensors containing ground truth future bounding boxes for planning. Defaults to None.\n            gt_future_labels (list[torch.Tensor], optional): List of tensors containing ground truth future labels for planning. Defaults to None.\n            \n            Returns:\n                dict: Dictionary containing losses of different tasks, such as tracking, segmentation, motion prediction, occupancy prediction, and planning. Each key in the dictionary \n                    is prefixed with the corresponding task name, e.g., 'track', 'map', 'motion', 'occ', and 'planning'. The values are the calculated losses for each task.\n        \"\"\"\n        losses = dict()\n        len_queue = img.size(1)\n        \n\n        losses_track, outs_track = self.forward_track_train(img, gt_bboxes_3d, gt_labels_3d, gt_past_traj, gt_past_traj_mask, gt_inds, gt_sdc_bbox, gt_sdc_label,\n                                                        l2g_t, l2g_r_mat, img_metas, timestamp)\n        losses_track = self.loss_weighted_and_prefixed(losses_track, prefix='track')\n        losses.update(losses_track)\n        \n        # Upsample bev for tiny version\n        outs_track = self.upsample_bev_if_tiny(outs_track)\n\n        bev_embed = outs_track[\"bev_embed\"]\n        bev_pos  = outs_track[\"bev_pos\"]\n\n        img_metas = [each[len_queue-1] for each in img_metas]\n\n        outs_seg = dict()\n        if self.with_seg_head:          \n            losses_seg, outs_seg = self.seg_head.forward_train(bev_embed, img_metas,\n                                                          gt_lane_labels, gt_lane_bboxes, gt_lane_masks)\n            \n            losses_seg = self.loss_weighted_and_prefixed(losses_seg, prefix='map')\n            losses.update(losses_seg)\n\n        outs_motion = dict()\n        # Forward Motion Head\n        if self.with_motion_head:\n            ret_dict_motion = self.motion_head.forward_train(bev_embed,\n                                                        gt_bboxes_3d, gt_labels_3d, \n                                                        gt_fut_traj, gt_fut_traj_mask, \n                                                        gt_sdc_fut_traj, gt_sdc_fut_traj_mask, \n                                                        outs_track=outs_track, outs_seg=outs_seg\n                                                    )\n            losses_motion = ret_dict_motion[\"losses\"]\n            outs_motion = ret_dict_motion[\"outs_motion\"]\n            outs_motion['bev_pos'] = bev_pos\n            losses_motion = self.loss_weighted_and_prefixed(losses_motion, prefix='motion')\n            losses.update(losses_motion)\n\n        # Forward Occ Head\n        if self.with_occ_head:\n            if outs_motion['track_query'].shape[1] == 0:\n                # TODO: rm hard code\n                outs_motion['track_query'] = torch.zeros((1, 1, 256)).to(bev_embed)\n                outs_motion['track_query_pos'] = torch.zeros((1,1, 256)).to(bev_embed)\n                outs_motion['traj_query'] = torch.zeros((3, 1, 1, 6, 256)).to(bev_embed)\n                outs_motion['all_matched_idxes'] = [[-1]]\n            losses_occ = self.occ_head.forward_train(\n                            bev_embed, \n                            outs_motion, \n                            gt_inds_list=gt_inds,\n                            gt_segmentation=gt_segmentation,\n                            gt_instance=gt_instance,\n                            gt_img_is_valid=gt_occ_img_is_valid,\n                        )\n            losses_occ = self.loss_weighted_and_prefixed(losses_occ, prefix='occ')\n            losses.update(losses_occ)\n        \n\n        # Forward Plan Head\n        if self.with_planning_head:\n            outs_planning = self.planning_head.forward_train(bev_embed, outs_motion, sdc_planning, sdc_planning_mask, command, gt_future_boxes)\n            losses_planning = outs_planning['losses']\n            losses_planning = self.loss_weighted_and_prefixed(losses_planning, prefix='planning')\n            losses.update(losses_planning)\n        \n        for k,v in losses.items():\n            losses[k] = torch.nan_to_num(v)\n        return losses\n    \n    def loss_weighted_and_prefixed(self, loss_dict, prefix=''):\n        loss_factor = self.task_loss_weight[prefix]\n        loss_dict = {f\"{prefix}.{k}\" : v*loss_factor for k, v in loss_dict.items()}\n        return loss_dict\n\n    def forward_test(self,\n                     img=None,\n                     img_metas=None,\n                     l2g_t=None,\n                     l2g_r_mat=None,\n                     timestamp=None,\n                     gt_lane_labels=None,\n                     gt_lane_masks=None,\n                     rescale=False,\n                     # planning gt(for evaluation only)\n                     sdc_planning=None,\n                     sdc_planning_mask=None,\n                     command=None,\n \n                     # Occ_gt (for evaluation only)\n                     gt_segmentation=None,\n                     gt_instance=None, \n                     gt_occ_img_is_valid=None,\n                     **kwargs,\n                    ):\n        \"\"\"Test function\n        \"\"\"\n        for var, name in [(img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError('{} must be a list, but got {}'.format(\n                    name, type(var)))\n        img = [img] if img is None else img\n        \n        if self.prev_frame_num > 0:\n            if len(self.prev_frame_infos) < self.prev_frame_num:\n                self.prev_frame_info = {\n                \"prev_bev\": None,\n                \"scene_token\": None,\n                \"prev_pos\": 0,\n                \"prev_angle\": 0,\n            }\n            else:\n                self.prev_frame_info = self.prev_frame_infos.pop(0)\n\n        if img_metas[0][0]['scene_token'] != self.prev_frame_info['scene_token']:\n            # the first sample of each scene is truncated\n            self.prev_frame_info['prev_bev'] = None\n        # update idx\n        self.prev_frame_info['scene_token'] = img_metas[0][0]['scene_token']\n\n        # do not use temporal information\n        if not self.video_test_mode:\n            self.prev_frame_info['prev_bev'] = None\n\n        # Get the delta of ego position and angle between two timestamps.\n        tmp_pos = copy.deepcopy(img_metas[0][0]['can_bus'][:3])\n        tmp_angle = copy.deepcopy(img_metas[0][0]['can_bus'][-1])\n        # first frame\n        if self.prev_frame_info['scene_token'] is None:\n            img_metas[0][0]['can_bus'][:3] = 0\n            img_metas[0][0]['can_bus'][-1] = 0\n        # following frames\n        else:\n            img_metas[0][0]['can_bus'][:3] -= self.prev_frame_info['prev_pos']\n            img_metas[0][0]['can_bus'][-1] -= self.prev_frame_info['prev_angle']\n        self.prev_frame_info['prev_pos'] = tmp_pos\n        self.prev_frame_info['prev_angle'] = tmp_angle\n        \n\n\n        img = img[0]\n        img_metas = img_metas[0]\n        timestamp = timestamp[0] if timestamp is not None else None\n\n        result = [dict() for i in range(len(img_metas))]\n        result_track = self.simple_test_track(img, l2g_t, l2g_r_mat, img_metas, timestamp)\n\n        # Upsample bev for tiny model        \n        result_track[0] = self.upsample_bev_if_tiny(result_track[0])\n        \n        bev_embed = result_track[0][\"bev_embed\"]\n        \n        if self.prev_frame_num > 0:        \n            self.prev_frame_infos.append(self.prev_frame_info)        \n        \n        \n\n        if self.with_seg_head:\n            result_seg =  self.seg_head.forward_test(bev_embed, gt_lane_labels, gt_lane_masks, img_metas, rescale)\n\n        if self.with_motion_head:\n            result_motion, outs_motion = self.motion_head.forward_test(bev_embed, outs_track=result_track[0], outs_seg=result_seg[0])\n            outs_motion['bev_pos'] = result_track[0]['bev_pos']\n\n        outs_occ = dict()\n        if self.with_occ_head:\n            occ_no_query = outs_motion['track_query'].shape[1] == 0\n            outs_occ = self.occ_head.forward_test(\n                bev_embed, \n                outs_motion,\n                no_query = occ_no_query,\n                gt_segmentation=gt_segmentation,\n                gt_instance=gt_instance,\n                gt_img_is_valid=gt_occ_img_is_valid,\n            )\n            result[0]['occ'] = outs_occ\n        \n        if self.with_planning_head:\n            planning_gt=dict(\n                segmentation=gt_segmentation,\n                sdc_planning=sdc_planning,\n                sdc_planning_mask=sdc_planning_mask,\n                command=command\n            )\n            result_planning = self.planning_head.forward_test(bev_embed, outs_motion, outs_occ, command)\n            result[0]['planning'] = dict(\n                planning_gt=planning_gt,\n                result_planning=result_planning,\n            )\n\n        pop_track_list = ['prev_bev', 'bev_pos', 'bev_embed', 'track_query_embeddings', 'sdc_embedding']\n        result_track[0] = pop_elem_in_result(result_track[0], pop_track_list)\n\n        if self.with_seg_head:\n            result_seg[0] = pop_elem_in_result(result_seg[0], pop_list=['pts_bbox', 'args_tuple'])\n        if self.with_motion_head:\n            result_motion[0] = pop_elem_in_result(result_motion[0])\n        if self.with_occ_head:\n            result[0]['occ'] = pop_elem_in_result(result[0]['occ'],  \\\n                pop_list=['seg_out_mask', 'flow_out', 'future_states_occ', 'pred_ins_masks', 'pred_raw_occ', 'pred_ins_logits', 'pred_ins_sigmoid'])\n        \n        for i, res in enumerate(result):\n            #res['token'] = img_metas[i]['sample_idx']\n            res.update(result_track[i])\n            if self.with_motion_head:\n                res.update(result_motion[i])\n            if self.with_seg_head:\n                res.update(result_seg[i])\n\n        return result\n\n\ndef pop_elem_in_result(task_result:dict, pop_list:list=None):\n    all_keys = list(task_result.keys())\n    for k in all_keys:\n        if k.endswith('query') or k.endswith('query_pos') or k.endswith('embedding'):\n            task_result.pop(k)\n    \n    if pop_list is not None:\n        for pop_k in pop_list:\n            task_result.pop(pop_k, None)\n    return task_result\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/detectors/uniad_track.py",
    "content": "#---------------------------------------------------------------------------------#\n# UniAD: Planning-oriented Autonomous Driving (https://arxiv.org/abs/2212.10156)  #\n# Source code: https://github.com/OpenDriveLab/UniAD                              #\n# Copyright (c) OpenDriveLab. All rights reserved.                                #\n#---------------------------------------------------------------------------------#\n\nimport torch\nimport torch.nn as nn\nfrom mmcv.utils import auto_fp16\nfrom mmcv.models import DETECTORS\nfrom mmcv.core.bbox.coder import build_bbox_coder\nfrom mmcv.models.detectors.mvx_two_stage import MVXTwoStageDetector\nfrom mmcv.models.utils.grid_mask import GridMask\nimport copy\nimport math\nfrom mmcv.core.bbox.util import normalize_bbox\nfrom mmcv.models import build_loss\nfrom einops import rearrange\nfrom mmcv.models.utils.transformer import inverse_sigmoid\nfrom ..dense_heads.track_head_plugin import MemoryBank, QueryInteractionModule, Instances, RuntimeTrackerBase\n\n@DETECTORS.register_module()\nclass UniADTrack(MVXTwoStageDetector):\n    \"\"\"UniAD tracking part\n    \"\"\"\n    def __init__(\n        self, \n        use_grid_mask=False,\n        img_backbone=None,\n        img_neck=None,\n        pts_bbox_head=None,\n        train_cfg=None,\n        test_cfg=None,\n        pretrained=None,\n        video_test_mode=False,\n        loss_cfg=None,\n        prev_frame_num=0,\n        qim_args=dict(\n            qim_type=\"QIMBase\",\n            merger_dropout=0,\n            update_query_pos=False,\n            fp_ratio=0.3,\n            random_drop=0.1,\n        ),\n        mem_args=dict(\n            memory_bank_type=\"MemoryBank\",\n            memory_bank_score_thresh=0.0,\n            memory_bank_len=4,\n        ),\n        bbox_coder=dict(\n            type=\"DETRTrack3DCoder\",\n            post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],\n            pc_range=[-51.2, -51.2, -5.0, 51.2, 51.2, 3.0],\n            max_num=300,\n            num_classes=10,\n            score_threshold=0.0,\n            with_nms=False,\n            iou_thres=0.3,\n        ),\n        pc_range=None,\n        embed_dims=256,\n        num_query=900,\n        num_classes=10,\n        vehicle_id_list=None,\n        score_thresh=0.2,\n        filter_score_thresh=0.1,\n        miss_tolerance=5,\n        gt_iou_threshold=0.0,\n        freeze_img_backbone=False,\n        freeze_img_neck=False,\n        freeze_bn=False,\n        freeze_bev_encoder=False,\n        queue_length=3,\n    ):\n        super(UniADTrack, self).__init__(\n            img_backbone=img_backbone,\n            img_neck=img_neck,\n            pts_bbox_head=pts_bbox_head,\n            train_cfg=train_cfg,\n            test_cfg=test_cfg,\n            pretrained=pretrained,\n        )\n\n        self.grid_mask = GridMask(\n            True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7\n        )\n        self.use_grid_mask = use_grid_mask\n        self.fp16_enabled = False\n        self.embed_dims = embed_dims\n        self.num_query = num_query\n        self.num_classes = num_classes\n        self.vehicle_id_list = vehicle_id_list\n        self.pc_range = pc_range\n        self.queue_length = queue_length\n        if freeze_img_backbone:\n            if freeze_bn:\n                self.img_backbone.eval()\n            for param in self.img_backbone.parameters():\n                param.requires_grad = False\n        \n        if freeze_img_neck:\n            if freeze_bn:\n                self.img_neck.eval()\n            for param in self.img_neck.parameters():\n                param.requires_grad = False\n\n        # temporal\n        self.video_test_mode = video_test_mode\n        assert self.video_test_mode\n        self.prev_frame_num = prev_frame_num\n        self.prev_frame_infos = []\n        self.prev_frame_info = {\n            \"prev_bev\": None,\n            \"scene_token\": None,\n            \"prev_pos\": 0,\n            \"prev_angle\": 0,\n        }\n        self.query_embedding = nn.Embedding(self.num_query+1, self.embed_dims * 2)   # the final one is ego query, which constantly models ego-vehicle\n        self.reference_points = nn.Linear(self.embed_dims, 3)\n\n        self.mem_bank_len = mem_args[\"memory_bank_len\"]\n        self.track_base = RuntimeTrackerBase(\n            score_thresh=score_thresh,\n            filter_score_thresh=filter_score_thresh,\n            miss_tolerance=miss_tolerance,\n        )  # hyper-param for removing inactive queries\n\n        self.query_interact = QueryInteractionModule(\n            qim_args,\n            dim_in=embed_dims,\n            hidden_dim=embed_dims,\n            dim_out=embed_dims,\n        )\n\n        self.bbox_coder = build_bbox_coder(bbox_coder)\n\n        self.memory_bank = MemoryBank(\n            mem_args,\n            dim_in=embed_dims,\n            hidden_dim=embed_dims,\n            dim_out=embed_dims,\n        )\n        self.mem_bank_len = (\n            0 if self.memory_bank is None else self.memory_bank.max_his_length\n        )\n        self.criterion = build_loss(loss_cfg)\n        self.test_track_instances = None\n        self.l2g_r_mat = None\n        self.l2g_t = None\n        self.gt_iou_threshold = gt_iou_threshold\n        self.bev_h, self.bev_w = self.pts_bbox_head.bev_h, self.pts_bbox_head.bev_w\n        self.freeze_bev_encoder = freeze_bev_encoder\n\n    def extract_img_feat(self, img, len_queue=None):\n        \"\"\"Extract features of images.\"\"\"\n        if img is None:\n            return None\n        assert img.dim() == 5\n        B, N, C, H, W = img.size()\n        img = img.reshape(B * N, C, H, W)\n        if self.use_grid_mask:\n            img = self.grid_mask(img)\n        img_feats = self.img_backbone(img)\n        if isinstance(img_feats, dict):\n            img_feats = list(img_feats.values())\n        if self.with_img_neck:\n            img_feats = self.img_neck(img_feats)\n\n        img_feats_reshaped = []\n        for img_feat in img_feats:\n            _, c, h, w = img_feat.size()\n            if len_queue is not None:\n                img_feat_reshaped = img_feat.view(B//len_queue, len_queue, N, c, h, w)\n            else:\n                img_feat_reshaped = img_feat.view(B, N, c, h, w)\n            img_feats_reshaped.append(img_feat_reshaped)\n        return img_feats_reshaped\n\n    def _generate_empty_tracks(self):\n        track_instances = Instances((1, 1))\n        num_queries, dim = self.query_embedding.weight.shape  # (300, 256 * 2)\n        device = self.query_embedding.weight.device\n        query = self.query_embedding.weight\n        track_instances.ref_pts = self.reference_points(query[..., : dim // 2])\n\n        # init boxes: xy, wl, z, h, sin, cos, vx, vy, vz\n        pred_boxes_init = torch.zeros(\n            (len(track_instances), 10), dtype=torch.float, device=device\n        )\n        track_instances.query = query\n\n        track_instances.output_embedding = torch.zeros(\n            (num_queries, dim >> 1), device=device\n        )\n\n        track_instances.obj_idxes = torch.full(\n            (len(track_instances),), -1, dtype=torch.long, device=device\n        )\n        track_instances.matched_gt_idxes = torch.full(\n            (len(track_instances),), -1, dtype=torch.long, device=device\n        )\n        track_instances.disappear_time = torch.zeros(\n            (len(track_instances),), dtype=torch.long, device=device\n        )\n\n        track_instances.iou = torch.zeros(\n            (len(track_instances),), dtype=torch.float, device=device\n        )\n        track_instances.scores = torch.zeros(\n            (len(track_instances),), dtype=torch.float, device=device\n        )\n        track_instances.track_scores = torch.zeros(\n            (len(track_instances),), dtype=torch.float, device=device\n        )\n        # xy, wl, z, h, sin, cos, vx, vy, vz\n        track_instances.pred_boxes = pred_boxes_init\n\n        track_instances.pred_logits = torch.zeros(\n            (len(track_instances), self.num_classes), dtype=torch.float, device=device\n        )\n\n        mem_bank_len = self.mem_bank_len\n        track_instances.mem_bank = torch.zeros(\n            (len(track_instances), mem_bank_len, dim // 2),\n            dtype=torch.float32,\n            device=device,\n        )\n        track_instances.mem_padding_mask = torch.ones(\n            (len(track_instances), mem_bank_len), dtype=torch.bool, device=device\n        )\n        track_instances.save_period = torch.zeros(\n            (len(track_instances),), dtype=torch.float32, device=device\n        )\n\n        return track_instances.to(self.query_embedding.weight.device)\n\n    def velo_update(\n        self, ref_pts, velocity, l2g_r1, l2g_t1, l2g_r2, l2g_t2, time_delta\n    ):\n        \"\"\"\n        Args:\n            ref_pts (Tensor): (num_query, 3).  in inevrse sigmoid space\n            velocity (Tensor): (num_query, 2). m/s\n                in lidar frame. vx, vy\n            global2lidar (np.Array) [4,4].\n        Outs:\n            ref_pts (Tensor): (num_query, 3).  in inevrse sigmoid space\n        \"\"\"\n        # print(l2g_r1.type(), l2g_t1.type(), ref_pts.type())\n        \n        if isinstance(l2g_r1,list):\n            l2g_r1 = l2g_r1[0]\n        if isinstance(l2g_t1,list):\n            l2g_t1 = l2g_t1[0]\n        if isinstance(l2g_r2,list):\n            l2g_r2 = l2g_r2[0]\n        if isinstance(l2g_t2,list):\n            l2g_t2 = l2g_t2[0]          \n        \n        l2g_r1 = l2g_r1.type(torch.float)\n        l2g_t1 = l2g_t1.type(torch.float)\n        l2g_t2 = l2g_t2.type(torch.float)\n        time_delta = time_delta.type(torch.float)\n        \n        num_query = ref_pts.size(0)\n        velo_pad_ = velocity.new_zeros((num_query, 1))\n        velo_pad = torch.cat((velocity, velo_pad_), dim=-1)\n\n        reference_points = ref_pts.sigmoid().clone()\n        pc_range = self.pc_range\n        reference_points[..., 0:1] = (\n            reference_points[..., 0:1] * (pc_range[3] - pc_range[0]) + pc_range[0]\n        )\n        reference_points[..., 1:2] = (\n            reference_points[..., 1:2] * (pc_range[4] - pc_range[1]) + pc_range[1]\n        )\n        reference_points[..., 2:3] = (\n            reference_points[..., 2:3] * (pc_range[5] - pc_range[2]) + pc_range[2]\n        )\n\n        reference_points = reference_points + velo_pad * time_delta\n\n        ref_pts = reference_points @ l2g_r1 + l2g_t1 - l2g_t2\n\n        g2l_r = torch.linalg.inv(l2g_r2).type(torch.float)\n\n        ref_pts = ref_pts @ g2l_r\n\n        ref_pts[..., 0:1] = (ref_pts[..., 0:1] - pc_range[0]) / (\n            pc_range[3] - pc_range[0]\n        )\n        ref_pts[..., 1:2] = (ref_pts[..., 1:2] - pc_range[1]) / (\n            pc_range[4] - pc_range[1]\n        )\n        ref_pts[..., 2:3] = (ref_pts[..., 2:3] - pc_range[2]) / (\n            pc_range[5] - pc_range[2]\n        )\n\n        ref_pts = inverse_sigmoid(ref_pts)\n\n        return ref_pts\n\n    def _copy_tracks_for_loss(self, tgt_instances):\n        device = self.query_embedding.weight.device\n        track_instances = Instances((1, 1))\n\n        track_instances.obj_idxes = copy.deepcopy(tgt_instances.obj_idxes)\n\n        track_instances.matched_gt_idxes = copy.deepcopy(tgt_instances.matched_gt_idxes)\n        track_instances.disappear_time = copy.deepcopy(tgt_instances.disappear_time)\n\n        track_instances.scores = torch.zeros(\n            (len(track_instances),), dtype=torch.float, device=device\n        )\n        track_instances.track_scores = torch.zeros(\n            (len(track_instances),), dtype=torch.float, device=device\n        )\n        track_instances.pred_boxes = torch.zeros(\n            (len(track_instances), 10), dtype=torch.float, device=device\n        )\n        track_instances.iou = torch.zeros(\n            (len(track_instances),), dtype=torch.float, device=device\n        )\n        track_instances.pred_logits = torch.zeros(\n            (len(track_instances), self.num_classes), dtype=torch.float, device=device\n        )\n\n        track_instances.save_period = copy.deepcopy(tgt_instances.save_period)\n        return track_instances.to(device)\n\n    def get_history_bev(self, imgs_queue, img_metas_list):\n        \"\"\"\n        Get history BEV features iteratively. To save GPU memory, gradients are not calculated.\n        \"\"\"\n        self.eval()\n        with torch.no_grad():\n            prev_bev = None\n            bs, len_queue, num_cams, C, H, W = imgs_queue.shape\n            imgs_queue = imgs_queue.reshape(bs * len_queue, num_cams, C, H, W)\n            img_feats_list = self.extract_img_feat(img=imgs_queue, len_queue=len_queue)\n            for i in range(len_queue):\n                img_metas = [each[i] for each in img_metas_list]\n                img_feats = [each_scale[:, i] for each_scale in img_feats_list]\n                prev_bev, _ = self.pts_bbox_head.get_bev_features(\n                    mlvl_feats=img_feats, \n                    img_metas=img_metas, \n                    prev_bev=prev_bev)\n        self.train()\n        return prev_bev\n\n    # Generate bev using bev_encoder in BEVFormer\n    def get_bevs(self, imgs, img_metas, prev_img=None, prev_img_metas=None, prev_bev=None):\n        if prev_img is not None and prev_img_metas is not None:\n            assert prev_bev is None\n            prev_bev = self.get_history_bev(prev_img, prev_img_metas)\n\n        img_feats = self.extract_img_feat(img=imgs)\n        if self.freeze_bev_encoder:\n            with torch.no_grad():\n                bev_embed, bev_pos = self.pts_bbox_head.get_bev_features(\n                    mlvl_feats=img_feats, img_metas=img_metas, prev_bev=prev_bev)\n        else:\n            bev_embed, bev_pos = self.pts_bbox_head.get_bev_features(\n                    mlvl_feats=img_feats, img_metas=img_metas, prev_bev=prev_bev)\n        \n        if bev_embed.shape[1] == self.bev_h * self.bev_w:\n            bev_embed = bev_embed.permute(1, 0, 2)\n        \n        assert bev_embed.shape[0] == self.bev_h * self.bev_w\n        return bev_embed, bev_pos\n\n    @auto_fp16(apply_to=(\"img\", \"prev_bev\"))\n    def _forward_single_frame_train(\n        self,\n        img,\n        img_metas,\n        track_instances,\n        prev_img,\n        prev_img_metas,\n        l2g_r1=None,\n        l2g_t1=None,\n        l2g_r2=None,\n        l2g_t2=None,\n        time_delta=None,\n        all_query_embeddings=None,\n        all_matched_indices=None,\n        all_instances_pred_logits=None,\n        all_instances_pred_boxes=None,\n    ):\n        \"\"\"\n        Perform forward only on one frame. Called in  forward_train\n        Warnning: Only Support BS=1\n        Args:\n            img: shape [B, num_cam, 3, H, W]\n            if l2g_r2 is None or l2g_t2 is None:\n                it means this frame is the end of the training clip,\n                so no need to call velocity update\n        \"\"\"\n        # NOTE: You can replace BEVFormer with other BEV encoder and provide bev_embed here\n        bev_embed, bev_pos = self.get_bevs(\n            img, img_metas,\n            prev_img=prev_img, prev_img_metas=prev_img_metas,\n        )\n\n        det_output = self.pts_bbox_head.get_detections(\n            bev_embed,\n            object_query_embeds=track_instances.query,\n            ref_points=track_instances.ref_pts,\n            img_metas=img_metas,\n        )\n\n        output_classes = det_output[\"all_cls_scores\"]\n        output_coords = det_output[\"all_bbox_preds\"]\n        output_past_trajs = det_output[\"all_past_traj_preds\"]\n        last_ref_pts = det_output[\"last_ref_points\"]\n        query_feats = det_output[\"query_feats\"]\n\n        out = {\n            \"pred_logits\": output_classes[-1],\n            \"pred_boxes\": output_coords[-1],\n            \"pred_past_trajs\": output_past_trajs[-1],\n            \"ref_pts\": last_ref_pts,\n            \"bev_embed\": bev_embed,\n            \"bev_pos\": bev_pos\n        }\n        with torch.no_grad():\n            track_scores = output_classes[-1, 0, :].sigmoid().max(dim=-1).values\n\n        # Step-1 Update track instances with current prediction\n        # [nb_dec, bs, num_query, xxx]\n        nb_dec = output_classes.size(0)\n\n        # the track id will be assigned by the matcher.\n        track_instances_list = [\n            self._copy_tracks_for_loss(track_instances) for i in range(nb_dec - 1)\n        ]\n        track_instances.output_embedding = query_feats[-1][0]  # [300, feat_dim]\n        velo = output_coords[-1, 0, :, -2:]  # [num_query, 3]\n        if l2g_r2 is not None:\n            # Update ref_pts for next frame considering each agent's velocity\n            ref_pts = self.velo_update(\n                last_ref_pts[0],\n                velo,\n                l2g_r1,\n                l2g_t1,\n                l2g_r2,\n                l2g_t2,\n                time_delta=time_delta,\n            )\n        else:\n            ref_pts = last_ref_pts[0]\n\n        dim = track_instances.query.shape[-1]\n        track_instances.ref_pts = self.reference_points(track_instances.query[..., :dim//2])\n        track_instances.ref_pts[...,:2] = ref_pts[...,:2]\n\n        track_instances_list.append(track_instances)\n        \n        for i in range(nb_dec):\n            track_instances = track_instances_list[i]\n\n            track_instances.scores = track_scores\n            track_instances.pred_logits = output_classes[i, 0]  # [300, num_cls]\n            track_instances.pred_boxes = output_coords[i, 0]  # [300, box_dim]\n            track_instances.pred_past_trajs = output_past_trajs[i, 0]  # [300,past_steps, 2]\n\n            out[\"track_instances\"] = track_instances\n            track_instances, matched_indices = self.criterion.match_for_single_frame(\n                out, i, if_step=(i == (nb_dec - 1))\n            )\n            all_query_embeddings.append(query_feats[i][0])\n            all_matched_indices.append(matched_indices)\n            all_instances_pred_logits.append(output_classes[i, 0])\n            all_instances_pred_boxes.append(output_coords[i, 0])   # Not used\n        \n        active_index = (track_instances.obj_idxes>=0) & (track_instances.iou >= self.gt_iou_threshold) & (track_instances.matched_gt_idxes >=0)\n        out.update(self.select_active_track_query(track_instances, active_index, img_metas))\n        out.update(self.select_sdc_track_query(track_instances[900], img_metas))\n        \n        # memory bank \n        if self.memory_bank is not None:\n            track_instances = self.memory_bank(track_instances)\n        # Step-2 Update track instances using matcher\n\n        tmp = {}\n        tmp[\"init_track_instances\"] = self._generate_empty_tracks()\n        tmp[\"track_instances\"] = track_instances\n        out_track_instances = self.query_interact(tmp)\n        out[\"track_instances\"] = out_track_instances\n        return out\n\n    def select_active_track_query(self, track_instances, active_index, img_metas, with_mask=True):\n        result_dict = self._track_instances2results(track_instances[active_index], img_metas, with_mask=with_mask)\n        result_dict[\"track_query_embeddings\"] = track_instances.output_embedding[active_index][result_dict['bbox_index']][result_dict['mask']]\n        result_dict[\"track_query_matched_idxes\"] = track_instances.matched_gt_idxes[active_index][result_dict['bbox_index']][result_dict['mask']]\n        return result_dict\n    \n    def select_sdc_track_query(self, sdc_instance, img_metas):\n        out = dict()\n        result_dict = self._track_instances2results(sdc_instance, img_metas, with_mask=False)\n        out[\"sdc_boxes_3d\"] = result_dict['boxes_3d']\n        out[\"sdc_scores_3d\"] = result_dict['scores_3d']\n        out[\"sdc_track_scores\"] = result_dict['track_scores']\n        out[\"sdc_track_bbox_results\"] = result_dict['track_bbox_results']\n        out[\"sdc_embedding\"] = sdc_instance.output_embedding[0]\n        return out\n\n    @auto_fp16(apply_to=(\"img\", \"points\"))\n    def forward_track_train(self,\n                            img,\n                            gt_bboxes_3d,\n                            gt_labels_3d,\n                            gt_past_traj,\n                            gt_past_traj_mask,\n                            gt_inds,\n                            gt_sdc_bbox,\n                            gt_sdc_label,\n                            l2g_t,\n                            l2g_r_mat,\n                            img_metas,\n                            timestamp):\n        \"\"\"Forward funciton\n        Args:\n        Returns:\n        \"\"\"\n        track_instances = self._generate_empty_tracks()\n        num_frame = img.size(1)\n        # init gt instances!\n        gt_instances_list = []\n\n        for i in range(num_frame):\n            gt_instances = Instances((1, 1))\n            boxes = gt_bboxes_3d[0][i].tensor.to(img.device)\n            # normalize gt bboxes here!\n            boxes = normalize_bbox(boxes, self.pc_range)\n            sd_boxes = gt_sdc_bbox[0][i].tensor.to(img.device)\n            sd_boxes = normalize_bbox(sd_boxes, self.pc_range)\n            gt_instances.boxes = boxes\n            gt_instances.labels = gt_labels_3d[0][i]\n            gt_instances.obj_ids = gt_inds[0][i]\n            gt_instances.past_traj = gt_past_traj[0][i].float()\n            gt_instances.past_traj_mask = gt_past_traj_mask[0][i].float()\n            gt_instances.sdc_boxes = torch.cat([sd_boxes for _ in range(boxes.shape[0])], dim=0)  # boxes.shape[0] sometimes 0\n            gt_instances.sdc_labels = torch.cat([gt_sdc_label[0][i] for _ in range(gt_labels_3d[0][i].shape[0])], dim=0)\n            gt_instances_list.append(gt_instances)\n\n        self.criterion.initialize_for_single_clip(gt_instances_list)\n\n        out = dict()\n\n        for i in range(num_frame):\n            prev_img = img[:, :i, ...] if i != 0 else img[:, :1, ...]\n            prev_img_metas = copy.deepcopy(img_metas)\n            # TODO: Generate prev_bev in an RNN way.\n\n            img_single = torch.stack([img_[i] for img_ in img], dim=0)\n            img_metas_single = [copy.deepcopy(img_metas[0][i])]\n            if i == num_frame - 1:\n                l2g_r2 = None\n                l2g_t2 = None\n                time_delta = None\n            else:\n                l2g_r2 = l2g_r_mat[0][i + 1]\n                l2g_t2 = l2g_t[0][i + 1]\n                time_delta = timestamp[0][i + 1] - timestamp[0][i]\n            all_query_embeddings = []\n            all_matched_idxes = []\n            all_instances_pred_logits = []\n            all_instances_pred_boxes = []\n            frame_res = self._forward_single_frame_train(\n                img_single,\n                img_metas_single,\n                track_instances,\n                prev_img,\n                prev_img_metas,\n                l2g_r_mat[0][i],\n                l2g_t[0][i],\n                l2g_r2,\n                l2g_t2,\n                time_delta,\n                all_query_embeddings,\n                all_matched_idxes,\n                all_instances_pred_logits,\n                all_instances_pred_boxes,\n            )\n            # all_query_embeddings: len=dec nums, N*256\n            # all_matched_idxes: len=dec nums, N*2\n            track_instances = frame_res[\"track_instances\"]\n        \n        get_keys = [\"bev_embed\", \"bev_pos\",\n                    \"track_query_embeddings\", \"track_query_matched_idxes\", \"track_bbox_results\",\n                    \"sdc_boxes_3d\", \"sdc_scores_3d\", \"sdc_track_scores\", \"sdc_track_bbox_results\", \"sdc_embedding\"]\n        out.update({k: frame_res[k] for k in get_keys})\n        \n        losses = self.criterion.losses_dict\n        return losses, out\n\n    def upsample_bev_if_tiny(self, outs_track):\n        if outs_track[\"bev_embed\"].size(0) == 100 * 100:\n            # For tiny model\n            # bev_emb\n            bev_embed = outs_track[\"bev_embed\"] # [10000, 1, 256]\n            dim, _, _ = bev_embed.size()\n            w = h = int(math.sqrt(dim))\n            assert h == w == 100\n\n            bev_embed = rearrange(bev_embed, '(h w) b c -> b c h w', h=h, w=w)  # [1, 256, 100, 100]\n            bev_embed = nn.Upsample(scale_factor=2)(bev_embed)  # [1, 256, 200, 200]\n            bev_embed = rearrange(bev_embed, 'b c h w -> (h w) b c')\n            outs_track[\"bev_embed\"] = bev_embed\n\n            # prev_bev\n            prev_bev = outs_track.get(\"prev_bev\", None)\n            if prev_bev is not None:\n                if self.training:\n                    #  [1, 10000, 256]\n                    prev_bev = rearrange(prev_bev, 'b (h w) c -> b c h w', h=h, w=w)\n                    prev_bev = nn.Upsample(scale_factor=2)(prev_bev)  # [1, 256, 200, 200]\n                    prev_bev = rearrange(prev_bev, 'b c h w -> b (h w) c')\n                    outs_track[\"prev_bev\"] = prev_bev\n                else:\n                    #  [10000, 1, 256]\n                    prev_bev = rearrange(prev_bev, '(h w) b c -> b c h w', h=h, w=w)\n                    prev_bev = nn.Upsample(scale_factor=2)(prev_bev)  # [1, 256, 200, 200]\n                    prev_bev = rearrange(prev_bev, 'b c h w -> (h w) b c')\n                    outs_track[\"prev_bev\"] = prev_bev\n\n            # bev_pos\n            bev_pos  = outs_track[\"bev_pos\"]  # [1, 256, 100, 100]\n            bev_pos = nn.Upsample(scale_factor=2)(bev_pos)  # [1, 256, 200, 200]\n            outs_track[\"bev_pos\"] = bev_pos\n        return outs_track\n\n\n    def _forward_single_frame_inference(\n        self,\n        img,\n        img_metas,\n        track_instances,\n        prev_bev=None,\n        l2g_r1=None,\n        l2g_t1=None,\n        l2g_r2=None,\n        l2g_t2=None,\n        time_delta=None,\n    ):\n        \"\"\"\n        img: B, num_cam, C, H, W = img.shape\n        \"\"\"\n\n        \"\"\" velo update \"\"\"\n        active_inst = track_instances[track_instances.obj_idxes >= 0]\n        other_inst = track_instances[track_instances.obj_idxes < 0]\n\n        if l2g_r2 is not None and len(active_inst) > 0 and l2g_r1 is not None:\n            ref_pts = active_inst.ref_pts\n            velo = active_inst.pred_boxes[:, -2:]\n            ref_pts = self.velo_update(\n                ref_pts, velo, l2g_r1, l2g_t1, l2g_r2, l2g_t2, time_delta=time_delta\n            )\n            ref_pts = ref_pts.squeeze(0)\n            dim = active_inst.query.shape[-1]\n            active_inst.ref_pts = self.reference_points(active_inst.query[..., :dim//2])\n            active_inst.ref_pts[...,:2] = ref_pts[...,:2]\n\n        track_instances = Instances.cat([other_inst, active_inst])\n\n        # NOTE: You can replace BEVFormer with other BEV encoder and provide bev_embed here\n        bev_embed, bev_pos = self.get_bevs(img, img_metas, prev_bev=prev_bev)\n        det_output = self.pts_bbox_head.get_detections(\n            bev_embed, \n            object_query_embeds=track_instances.query,\n            ref_points=track_instances.ref_pts,\n            img_metas=img_metas,\n        )\n        output_classes = det_output[\"all_cls_scores\"]\n        output_coords = det_output[\"all_bbox_preds\"]\n        last_ref_pts = det_output[\"last_ref_points\"]\n        query_feats = det_output[\"query_feats\"]\n\n        out = {\n            \"pred_logits\": output_classes,\n            \"pred_boxes\": output_coords,\n            \"ref_pts\": last_ref_pts,\n            \"bev_embed\": bev_embed,\n            \"query_embeddings\": query_feats,\n            \"all_past_traj_preds\": det_output[\"all_past_traj_preds\"],\n            \"bev_pos\": bev_pos,\n        }\n\n        \"\"\" update track instances with predict results \"\"\"\n        track_scores = output_classes[-1, 0, :].sigmoid().max(dim=-1).values\n        # each track will be assigned an unique global id by the track base.\n        track_instances.scores = track_scores\n        # track_instances.track_scores = track_scores  # [300]\n        track_instances.pred_logits = output_classes[-1, 0]  # [300, num_cls]\n        track_instances.pred_boxes = output_coords[-1, 0]  # [300, box_dim]\n        track_instances.output_embedding = query_feats[-1][0]  # [300, feat_dim]\n        track_instances.ref_pts = last_ref_pts[0]\n        # hard_code: assume the 901 query is sdc query \n        track_instances.obj_idxes[900] = -2\n        \"\"\" update track base \"\"\"\n        self.track_base.update(track_instances, None)\n       \n        active_index = (track_instances.obj_idxes>=0) & (track_instances.scores >= self.track_base.filter_score_thresh)    # filter out sleep objects\n        out.update(self.select_active_track_query(track_instances, active_index, img_metas))\n        out.update(self.select_sdc_track_query(track_instances[track_instances.obj_idxes==-2], img_metas))\n\n        \"\"\" update with memory_bank \"\"\"\n        if self.memory_bank is not None:\n            track_instances = self.memory_bank(track_instances)\n\n        \"\"\"  Update track instances using matcher \"\"\"\n        tmp = {}\n        tmp[\"init_track_instances\"] = self._generate_empty_tracks()\n        tmp[\"track_instances\"] = track_instances\n        out_track_instances = self.query_interact(tmp)\n        out[\"track_instances_fordet\"] = track_instances\n        out[\"track_instances\"] = out_track_instances\n        out[\"track_obj_idxes\"] = track_instances.obj_idxes\n        return out\n\n    def simple_test_track(\n        self,\n        img=None,\n        l2g_t=None,\n        l2g_r_mat=None,\n        img_metas=None,\n        timestamp=None,\n    ):\n        \"\"\"only support bs=1 and sequential input\"\"\"\n\n        bs = img.size(0)\n        # img_metas = img_metas[0]\n\n        \"\"\" init track instances for first frame \"\"\"\n        if (\n            self.test_track_instances is None\n            or img_metas[0][\"scene_token\"] != self.scene_token\n        ):\n            self.timestamp = timestamp\n            self.scene_token = img_metas[0][\"scene_token\"]\n            self.prev_bev = None\n            track_instances = self._generate_empty_tracks()\n            time_delta, l2g_r1, l2g_t1, l2g_r2, l2g_t2 = None, None, None, None, None\n            \n        else:\n            track_instances = self.test_track_instances\n            time_delta = timestamp - self.timestamp\n            l2g_r1 = self.l2g_r_mat\n            l2g_t1 = self.l2g_t\n            l2g_r2 = l2g_r_mat\n            l2g_t2 = l2g_t\n            self.prev_bev = self.prev_frame_info['prev_bev']\n        \n        \"\"\" get time_delta and l2g r/t infos \"\"\"\n        \"\"\" update frame info for next frame\"\"\"\n        self.timestamp = timestamp\n        self.l2g_t = l2g_t\n        self.l2g_r_mat = l2g_r_mat\n\n        \"\"\" predict and update \"\"\"\n        \n        prev_bev = self.prev_bev\n        frame_res = self._forward_single_frame_inference(\n            img,\n            img_metas,\n            track_instances,\n            prev_bev,\n            l2g_r1,\n            l2g_t1,\n            l2g_r2,\n            l2g_t2,\n            time_delta,\n        )\n\n        self.prev_bev = frame_res[\"bev_embed\"]\n        self.prev_frame_info['prev_bev'] = self.prev_bev\n        track_instances = frame_res[\"track_instances\"]\n        track_instances_fordet = frame_res[\"track_instances_fordet\"]\n\n        self.test_track_instances = track_instances\n        results = [dict()]\n        get_keys = [\"bev_embed\", \"bev_pos\", \n                    \"track_query_embeddings\", \"track_bbox_results\", \n                    \"boxes_3d\", \"scores_3d\", \"labels_3d\", \"track_scores\", \"track_ids\"]\n        if self.with_motion_head:\n            get_keys += [\"sdc_boxes_3d\", \"sdc_scores_3d\", \"sdc_track_scores\", \"sdc_track_bbox_results\", \"sdc_embedding\"]\n        results[0].update({k: frame_res[k] for k in get_keys})\n        results = self._det_instances2results(track_instances_fordet, results, img_metas)\n        return results\n    \n    def _track_instances2results(self, track_instances, img_metas, with_mask=True):\n        bbox_dict = dict(\n            cls_scores=track_instances.pred_logits,\n            bbox_preds=track_instances.pred_boxes,\n            track_scores=track_instances.scores,\n            obj_idxes=track_instances.obj_idxes,\n        )\n        # bboxes_dict = self.bbox_coder.decode(bbox_dict, with_mask=with_mask)[0]\n        bboxes_dict = self.bbox_coder.decode(bbox_dict, with_mask=with_mask, img_metas=img_metas)[0]\n        bboxes = bboxes_dict[\"bboxes\"]\n        # bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5\n        bboxes = img_metas[0][\"box_type_3d\"](bboxes, 9)\n        labels = bboxes_dict[\"labels\"]\n        scores = bboxes_dict[\"scores\"]\n        bbox_index = bboxes_dict[\"bbox_index\"]\n\n        track_scores = bboxes_dict[\"track_scores\"]\n        obj_idxes = bboxes_dict[\"obj_idxes\"]\n        result_dict = dict(\n            boxes_3d=bboxes.to(\"cpu\"),\n            scores_3d=scores.cpu(),\n            labels_3d=labels.cpu(),\n            track_scores=track_scores.cpu(),\n            bbox_index=bbox_index.cpu(),\n            track_ids=obj_idxes.cpu(),\n            mask=bboxes_dict[\"mask\"].cpu(),\n            track_bbox_results=[[bboxes.to(\"cpu\"), scores.cpu(), labels.cpu(), bbox_index.cpu(), bboxes_dict[\"mask\"].cpu()]]\n        )\n        return result_dict\n\n    def _det_instances2results(self, instances, results, img_metas):\n        \"\"\"\n        Outs:\n        active_instances. keys:\n        - 'pred_logits':\n        - 'pred_boxes': normalized bboxes\n        - 'scores'\n        - 'obj_idxes'\n        out_dict. keys:\n            - boxes_3d (torch.Tensor): 3D boxes.\n            - scores (torch.Tensor): Prediction scores.\n            - labels_3d (torch.Tensor): Box labels.\n            - attrs_3d (torch.Tensor, optional): Box attributes.\n            - track_ids\n            - tracking_score\n        \"\"\"\n        # filter out sleep querys\n        if instances.pred_logits.numel() == 0:\n            return [None]\n        bbox_dict = dict(\n            cls_scores=instances.pred_logits,\n            bbox_preds=instances.pred_boxes,\n            track_scores=instances.scores,\n            obj_idxes=instances.obj_idxes,\n        )\n        bboxes_dict = self.bbox_coder.decode(bbox_dict, img_metas=img_metas)[0]\n        bboxes = bboxes_dict[\"bboxes\"]\n        # import pdb;pdb.set_trace()\n        bboxes = img_metas[0][\"box_type_3d\"](bboxes, 9)\n        labels = bboxes_dict[\"labels\"]\n        scores = bboxes_dict[\"scores\"]\n\n        track_scores = bboxes_dict[\"track_scores\"]\n        obj_idxes = bboxes_dict[\"obj_idxes\"]\n        result_dict = results[0]\n        result_dict_det = dict(\n            boxes_3d_det=bboxes.to(\"cpu\"),\n            scores_3d_det=scores.cpu(),\n            labels_3d_det=labels.cpu(),\n        )\n        if result_dict is not None:\n            result_dict.update(result_dict_det)\n        else:\n            result_dict = None\n\n        return [result_dict]\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/losses/__init__.py",
    "content": "from .focal_loss import FocalLoss, sigmoid_focal_loss\nfrom .iou_loss import (BoundedIoULoss, CIoULoss, DIoULoss, GIoULoss, IoULoss,\n                       bounded_iou_loss, iou_loss)\nfrom .smooth_l1_loss import L1Loss, SmoothL1Loss, l1_loss, smooth_l1_loss\n\n\n# __all__ = [\n#     'accuracy', 'Accuracy', 'cross_entropy', 'binary_cross_entropy',\n#     'mask_cross_entropy', 'CrossEntropyLoss', 'sigmoid_focal_loss',\n#     'FocalLoss', 'smooth_l1_loss', 'SmoothL1Loss', 'balanced_l1_loss',\n#     'BalancedL1Loss', 'mse_loss', 'MSELoss', 'iou_loss', 'bounded_iou_loss',\n#     'IoULoss', 'BoundedIoULoss', 'GIoULoss', 'DIoULoss', 'CIoULoss', 'GHMC',\n#     'GHMR', 'reduce_loss', 'weight_reduce_loss', 'weighted_loss', 'L1Loss',\n#     'l1_loss', 'isr_p', 'carl_loss', 'AssociativeEmbeddingLoss',\n#     'GaussianFocalLoss', 'QualityFocalLoss', 'DistributionFocalLoss',\n#     'VarifocalLoss', 'KnowledgeDistillationKLDivLoss', 'SeesawLoss',\n#     'ChamferDistance', 'chamfer_distance', 'axis_aligned_iou_loss', \n#     'AxisAlignedIoULoss', 'PAConvRegularizationLoss',\n#     'LovaszLoss'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/losses/focal_loss.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.ops.focal_loss import sigmoid_focal_loss as _sigmoid_focal_loss\n\nfrom ..builder import LOSSES\nfrom .utils import weight_reduce_loss\n\n\n# This method is only for debugging\ndef py_sigmoid_focal_loss(pred,\n                          target,\n                          weight=None,\n                          gamma=2.0,\n                          alpha=0.25,\n                          reduction='mean',\n                          avg_factor=None):\n    \"\"\"PyTorch version of `Focal Loss <https://arxiv.org/abs/1708.02002>`_.\n\n    Args:\n        pred (torch.Tensor): The prediction with shape (N, C), C is the\n            number of classes\n        target (torch.Tensor): The learning label of the prediction.\n        weight (torch.Tensor, optional): Sample-wise loss weight.\n        gamma (float, optional): The gamma for calculating the modulating\n            factor. Defaults to 2.0.\n        alpha (float, optional): A balanced form for Focal Loss.\n            Defaults to 0.25.\n        reduction (str, optional): The method used to reduce the loss into\n            a scalar. Defaults to 'mean'.\n        avg_factor (int, optional): Average factor that is used to average\n            the loss. Defaults to None.\n    \"\"\"\n    pred_sigmoid = pred.sigmoid()\n    target = target.type_as(pred)\n    pt = (1 - pred_sigmoid) * target + pred_sigmoid * (1 - target)\n    focal_weight = (alpha * target + (1 - alpha) *\n                    (1 - target)) * pt.pow(gamma)\n    loss = F.binary_cross_entropy_with_logits(\n        pred, target, reduction='none') * focal_weight\n    if weight is not None:\n        if weight.shape != loss.shape:\n            if weight.size(0) == loss.size(0):\n                # For most cases, weight is of shape (num_priors, ),\n                #  which means it does not have the second axis num_class\n                weight = weight.view(-1, 1)\n            else:\n                # Sometimes, weight per anchor per class is also needed. e.g.\n                #  in FSAF. But it may be flattened of shape\n                #  (num_priors x num_class, ), while loss is still of shape\n                #  (num_priors, num_class).\n                assert weight.numel() == loss.numel()\n                weight = weight.view(loss.size(0), -1)\n        assert weight.ndim == loss.ndim\n    loss = weight_reduce_loss(loss, weight, reduction, avg_factor)\n    return loss\n\n\ndef sigmoid_focal_loss(pred,\n                       target,\n                       weight=None,\n                       gamma=2.0,\n                       alpha=0.25,\n                       reduction='mean',\n                       avg_factor=None):\n    r\"\"\"A warpper of cuda version `Focal Loss\n    <https://arxiv.org/abs/1708.02002>`_.\n\n    Args:\n        pred (torch.Tensor): The prediction with shape (N, C), C is the number\n            of classes.\n        target (torch.Tensor): The learning label of the prediction.\n        weight (torch.Tensor, optional): Sample-wise loss weight.\n        gamma (float, optional): The gamma for calculating the modulating\n            factor. Defaults to 2.0.\n        alpha (float, optional): A balanced form for Focal Loss.\n            Defaults to 0.25.\n        reduction (str, optional): The method used to reduce the loss into\n            a scalar. Defaults to 'mean'. Options are \"none\", \"mean\" and \"sum\".\n        avg_factor (int, optional): Average factor that is used to average\n            the loss. Defaults to None.\n    \"\"\"\n    # Function.apply does not accept keyword arguments, so the decorator\n    # \"weighted_loss\" is not applicable\n    loss = _sigmoid_focal_loss(pred.contiguous(), target, gamma, alpha, None,\n                               'none')\n    if weight is not None:\n        if weight.shape != loss.shape:\n            if weight.size(0) == loss.size(0):\n                # For most cases, weight is of shape (num_priors, ),\n                #  which means it does not have the second axis num_class\n                weight = weight.view(-1, 1)\n            else:\n                # Sometimes, weight per anchor per class is also needed. e.g.\n                #  in FSAF. But it may be flattened of shape\n                #  (num_priors x num_class, ), while loss is still of shape\n                #  (num_priors, num_class).\n                assert weight.numel() == loss.numel()\n                weight = weight.view(loss.size(0), -1)\n        assert weight.ndim == loss.ndim\n    loss = weight_reduce_loss(loss, weight, reduction, avg_factor)\n    return loss\n\n\n@LOSSES.register_module()\nclass FocalLoss(nn.Module):\n\n    def __init__(self,\n                 use_sigmoid=True,\n                 gamma=2.0,\n                 alpha=0.25,\n                 reduction='mean',\n                 loss_weight=1.0):\n        \"\"\"`Focal Loss <https://arxiv.org/abs/1708.02002>`_\n\n        Args:\n            use_sigmoid (bool, optional): Whether to the prediction is\n                used for sigmoid or softmax. Defaults to True.\n            gamma (float, optional): The gamma for calculating the modulating\n                factor. Defaults to 2.0.\n            alpha (float, optional): A balanced form for Focal Loss.\n                Defaults to 0.25.\n            reduction (str, optional): The method used to reduce the loss into\n                a scalar. Defaults to 'mean'. Options are \"none\", \"mean\" and\n                \"sum\".\n            loss_weight (float, optional): Weight of loss. Defaults to 1.0.\n        \"\"\"\n        super(FocalLoss, self).__init__()\n        assert use_sigmoid is True, 'Only sigmoid focal loss supported now.'\n        self.use_sigmoid = use_sigmoid\n        self.gamma = gamma\n        self.alpha = alpha\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning label of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Options are \"none\", \"mean\" and \"sum\".\n\n        Returns:\n            torch.Tensor: The calculated loss\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        if self.use_sigmoid:\n            if torch.cuda.is_available() and pred.is_cuda:\n                calculate_loss_func = sigmoid_focal_loss\n            else:\n                num_classes = pred.size(1)\n                target = F.one_hot(target, num_classes=num_classes + 1)\n                target = target[:, :num_classes]\n                calculate_loss_func = py_sigmoid_focal_loss\n\n            loss_cls = self.loss_weight * calculate_loss_func(\n                pred,\n                target,\n                weight,\n                gamma=self.gamma,\n                alpha=self.alpha,\n                reduction=reduction,\n                avg_factor=avg_factor)\n\n        else:\n            raise NotImplementedError\n        return loss_cls\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/losses/iou_loss.py",
    "content": "import math\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.core.bbox.iou_calculators.iou3d_calculator import bbox_overlaps\nfrom ..builder import LOSSES\nfrom .utils import weighted_loss\n\n\n\n@weighted_loss\ndef iou_loss(pred, target, linear=False, eps=1e-6):\n    \"\"\"IoU loss.\n\n    Computing the IoU loss between a set of predicted bboxes and target bboxes.\n    The loss is calculated as negative log of IoU.\n\n    Args:\n        pred (torch.Tensor): Predicted bboxes of format (x1, y1, x2, y2),\n            shape (n, 4).\n        target (torch.Tensor): Corresponding gt bboxes, shape (n, 4).\n        linear (bool, optional): If True, use linear scale of loss instead of\n            log scale. Default: False.\n        eps (float): Eps to avoid log(0).\n\n    Return:\n        torch.Tensor: Loss tensor.\n    \"\"\"\n    ious = bbox_overlaps(pred, target, is_aligned=True).clamp(min=eps)\n    if linear:\n        loss = 1 - ious\n    else:\n        loss = -ious.log()\n    return loss\n\n\n@weighted_loss\ndef bounded_iou_loss(pred, target, beta=0.2, eps=1e-3):\n    \"\"\"BIoULoss.\n\n    This is an implementation of paper\n    `Improving Object Localization with Fitness NMS and Bounded IoU Loss.\n    <https://arxiv.org/abs/1711.00164>`_.\n\n    Args:\n        pred (torch.Tensor): Predicted bboxes.\n        target (torch.Tensor): Target bboxes.\n        beta (float): beta parameter in smoothl1.\n        eps (float): eps to avoid NaN.\n    \"\"\"\n    pred_ctrx = (pred[:, 0] + pred[:, 2]) * 0.5\n    pred_ctry = (pred[:, 1] + pred[:, 3]) * 0.5\n    pred_w = pred[:, 2] - pred[:, 0]\n    pred_h = pred[:, 3] - pred[:, 1]\n    with torch.no_grad():\n        target_ctrx = (target[:, 0] + target[:, 2]) * 0.5\n        target_ctry = (target[:, 1] + target[:, 3]) * 0.5\n        target_w = target[:, 2] - target[:, 0]\n        target_h = target[:, 3] - target[:, 1]\n\n    dx = target_ctrx - pred_ctrx\n    dy = target_ctry - pred_ctry\n\n    loss_dx = 1 - torch.max(\n        (target_w - 2 * dx.abs()) /\n        (target_w + 2 * dx.abs() + eps), torch.zeros_like(dx))\n    loss_dy = 1 - torch.max(\n        (target_h - 2 * dy.abs()) /\n        (target_h + 2 * dy.abs() + eps), torch.zeros_like(dy))\n    loss_dw = 1 - torch.min(target_w / (pred_w + eps), pred_w /\n                            (target_w + eps))\n    loss_dh = 1 - torch.min(target_h / (pred_h + eps), pred_h /\n                            (target_h + eps))\n    loss_comb = torch.stack([loss_dx, loss_dy, loss_dw, loss_dh],\n                            dim=-1).view(loss_dx.size(0), -1)\n\n    loss = torch.where(loss_comb < beta, 0.5 * loss_comb * loss_comb / beta,\n                       loss_comb - 0.5 * beta)\n    return loss\n\n\n\n@weighted_loss\ndef giou_loss(pred, target, eps=1e-7):\n    r\"\"\"`Generalized Intersection over Union: A Metric and A Loss for Bounding\n    Box Regression <https://arxiv.org/abs/1902.09630>`_.\n\n    Args:\n        pred (torch.Tensor): Predicted bboxes of format (x1, y1, x2, y2),\n            shape (n, 4).\n        target (torch.Tensor): Corresponding gt bboxes, shape (n, 4).\n        eps (float): Eps to avoid log(0).\n\n    Return:\n        Tensor: Loss tensor.\n    \"\"\"\n    gious = bbox_overlaps(pred, target, mode='giou', is_aligned=True, eps=eps)\n    loss = 1 - gious\n    return loss\n\n\n@weighted_loss\ndef diou_loss(pred, target, eps=1e-7):\n    r\"\"\"`Implementation of Distance-IoU Loss: Faster and Better\n    Learning for Bounding Box Regression, https://arxiv.org/abs/1911.08287`_.\n\n    Code is modified from https://github.com/Zzh-tju/DIoU.\n\n    Args:\n        pred (Tensor): Predicted bboxes of format (x1, y1, x2, y2),\n            shape (n, 4).\n        target (Tensor): Corresponding gt bboxes, shape (n, 4).\n        eps (float): Eps to avoid log(0).\n    Return:\n        Tensor: Loss tensor.\n    \"\"\"\n    # overlap\n    lt = torch.max(pred[:, :2], target[:, :2])\n    rb = torch.min(pred[:, 2:], target[:, 2:])\n    wh = (rb - lt).clamp(min=0)\n    overlap = wh[:, 0] * wh[:, 1]\n\n    # union\n    ap = (pred[:, 2] - pred[:, 0]) * (pred[:, 3] - pred[:, 1])\n    ag = (target[:, 2] - target[:, 0]) * (target[:, 3] - target[:, 1])\n    union = ap + ag - overlap + eps\n\n    # IoU\n    ious = overlap / union\n\n    # enclose area\n    enclose_x1y1 = torch.min(pred[:, :2], target[:, :2])\n    enclose_x2y2 = torch.max(pred[:, 2:], target[:, 2:])\n    enclose_wh = (enclose_x2y2 - enclose_x1y1).clamp(min=0)\n\n    cw = enclose_wh[:, 0]\n    ch = enclose_wh[:, 1]\n\n    c2 = cw**2 + ch**2 + eps\n\n    b1_x1, b1_y1 = pred[:, 0], pred[:, 1]\n    b1_x2, b1_y2 = pred[:, 2], pred[:, 3]\n    b2_x1, b2_y1 = target[:, 0], target[:, 1]\n    b2_x2, b2_y2 = target[:, 2], target[:, 3]\n\n    left = ((b2_x1 + b2_x2) - (b1_x1 + b1_x2))**2 / 4\n    right = ((b2_y1 + b2_y2) - (b1_y1 + b1_y2))**2 / 4\n    rho2 = left + right\n\n    # DIoU\n    dious = ious - rho2 / c2\n    loss = 1 - dious\n    return loss\n\n\n@weighted_loss\ndef ciou_loss(pred, target, eps=1e-7):\n    r\"\"\"`Implementation of paper `Enhancing Geometric Factors into\n    Model Learning and Inference for Object Detection and Instance\n    Segmentation <https://arxiv.org/abs/2005.03572>`_.\n\n    Code is modified from https://github.com/Zzh-tju/CIoU.\n\n    Args:\n        pred (Tensor): Predicted bboxes of format (x1, y1, x2, y2),\n            shape (n, 4).\n        target (Tensor): Corresponding gt bboxes, shape (n, 4).\n        eps (float): Eps to avoid log(0).\n    Return:\n        Tensor: Loss tensor.\n    \"\"\"\n    # overlap\n    lt = torch.max(pred[:, :2], target[:, :2])\n    rb = torch.min(pred[:, 2:], target[:, 2:])\n    wh = (rb - lt).clamp(min=0)\n    overlap = wh[:, 0] * wh[:, 1]\n\n    # union\n    ap = (pred[:, 2] - pred[:, 0]) * (pred[:, 3] - pred[:, 1])\n    ag = (target[:, 2] - target[:, 0]) * (target[:, 3] - target[:, 1])\n    union = ap + ag - overlap + eps\n\n    # IoU\n    ious = overlap / union\n\n    # enclose area\n    enclose_x1y1 = torch.min(pred[:, :2], target[:, :2])\n    enclose_x2y2 = torch.max(pred[:, 2:], target[:, 2:])\n    enclose_wh = (enclose_x2y2 - enclose_x1y1).clamp(min=0)\n\n    cw = enclose_wh[:, 0]\n    ch = enclose_wh[:, 1]\n\n    c2 = cw**2 + ch**2 + eps\n\n    b1_x1, b1_y1 = pred[:, 0], pred[:, 1]\n    b1_x2, b1_y2 = pred[:, 2], pred[:, 3]\n    b2_x1, b2_y1 = target[:, 0], target[:, 1]\n    b2_x2, b2_y2 = target[:, 2], target[:, 3]\n\n    w1, h1 = b1_x2 - b1_x1, b1_y2 - b1_y1 + eps\n    w2, h2 = b2_x2 - b2_x1, b2_y2 - b2_y1 + eps\n\n    left = ((b2_x1 + b2_x2) - (b1_x1 + b1_x2))**2 / 4\n    right = ((b2_y1 + b2_y2) - (b1_y1 + b1_y2))**2 / 4\n    rho2 = left + right\n\n    factor = 4 / math.pi**2\n    v = factor * torch.pow(torch.atan(w2 / h2) - torch.atan(w1 / h1), 2)\n\n    # CIoU\n    cious = ious - (rho2 / c2 + v**2 / (1 - ious + v))\n    loss = 1 - cious\n    return loss\n\n\nclass IoULoss(nn.Module):\n    \"\"\"IoULoss.\n\n    Computing the IoU loss between a set of predicted bboxes and target bboxes.\n\n    Args:\n        linear (bool): If True, use linear scale of loss instead of log scale.\n            Default: False.\n        eps (float): Eps to avoid log(0).\n        reduction (str): Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float): Weight of loss.\n    \"\"\"\n\n    def __init__(self,\n                 linear=False,\n                 eps=1e-6,\n                 reduction='mean',\n                 loss_weight=1.0):\n        super(IoULoss, self).__init__()\n        self.linear = linear\n        self.eps = eps\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None. Options are \"none\", \"mean\" and \"sum\".\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        if (weight is not None) and (not torch.any(weight > 0)) and (\n                reduction != 'none'):\n            if pred.dim() == weight.dim() + 1:\n                weight = weight.unsqueeze(1)\n            return (pred * weight).sum()  # 0\n        if weight is not None and weight.dim() > 1:\n            # TODO: remove this in the future\n            # reduce the weight of shape (n, 4) to (n,) to match the\n            # iou_loss of shape (n,)\n            assert weight.shape == pred.shape\n            weight = weight.mean(-1)\n        loss = self.loss_weight * iou_loss(\n            pred,\n            target,\n            weight,\n            linear=self.linear,\n            eps=self.eps,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        return loss\n\n\n@LOSSES.register_module()\nclass BoundedIoULoss(nn.Module):\n\n    def __init__(self, beta=0.2, eps=1e-3, reduction='mean', loss_weight=1.0):\n        super(BoundedIoULoss, self).__init__()\n        self.beta = beta\n        self.eps = eps\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n        if weight is not None and not torch.any(weight > 0):\n            if pred.dim() == weight.dim() + 1:\n                weight = weight.unsqueeze(1)\n            return (pred * weight).sum()  # 0\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        loss = self.loss_weight * bounded_iou_loss(\n            pred,\n            target,\n            weight,\n            beta=self.beta,\n            eps=self.eps,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        return loss\n\n\n@LOSSES.register_module()\nclass GIoULoss(nn.Module):\n\n    def __init__(self, eps=1e-6, reduction='mean', loss_weight=1.0):\n        super(GIoULoss, self).__init__()\n        self.eps = eps\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n        if weight is not None and not torch.any(weight > 0):\n            if pred.dim() == weight.dim() + 1:\n                weight = weight.unsqueeze(1)\n            return (pred * weight).sum()  # 0\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        if weight is not None and weight.dim() > 1:\n            # TODO: remove this in the future\n            # reduce the weight of shape (n, 4) to (n,) to match the\n            # giou_loss of shape (n,)\n            assert weight.shape == pred.shape\n            weight = weight.mean(-1)\n        loss = self.loss_weight * giou_loss(\n            pred,\n            target,\n            weight,\n            eps=self.eps,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        return loss\n\n\n@LOSSES.register_module()\nclass DIoULoss(nn.Module):\n\n    def __init__(self, eps=1e-6, reduction='mean', loss_weight=1.0):\n        super(DIoULoss, self).__init__()\n        self.eps = eps\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n        if weight is not None and not torch.any(weight > 0):\n            if pred.dim() == weight.dim() + 1:\n                weight = weight.unsqueeze(1)\n            return (pred * weight).sum()  # 0\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        if weight is not None and weight.dim() > 1:\n            # TODO: remove this in the future\n            # reduce the weight of shape (n, 4) to (n,) to match the\n            # giou_loss of shape (n,)\n            assert weight.shape == pred.shape\n            weight = weight.mean(-1)\n        loss = self.loss_weight * diou_loss(\n            pred,\n            target,\n            weight,\n            eps=self.eps,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        return loss\n\n\n@LOSSES.register_module()\nclass CIoULoss(nn.Module):\n\n    def __init__(self, eps=1e-6, reduction='mean', loss_weight=1.0):\n        super(CIoULoss, self).__init__()\n        self.eps = eps\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n        if weight is not None and not torch.any(weight > 0):\n            if pred.dim() == weight.dim() + 1:\n                weight = weight.unsqueeze(1)\n            return (pred * weight).sum()  # 0\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        if weight is not None and weight.dim() > 1:\n            # TODO: remove this in the future\n            # reduce the weight of shape (n, 4) to (n,) to match the\n            # giou_loss of shape (n,)\n            assert weight.shape == pred.shape\n            weight = weight.mean(-1)\n        loss = self.loss_weight * ciou_loss(\n            pred,\n            target,\n            weight,\n            eps=self.eps,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        return loss\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/losses/smooth_l1_loss.py",
    "content": "import torch\nimport torch.nn as nn\n\nfrom ..builder import LOSSES\nfrom .utils import weighted_loss\n\n\n@weighted_loss\ndef smooth_l1_loss(pred, target, beta=1.0):\n    \"\"\"Smooth L1 loss.\n\n    Args:\n        pred (torch.Tensor): The prediction.\n        target (torch.Tensor): The learning target of the prediction.\n        beta (float, optional): The threshold in the piecewise function.\n            Defaults to 1.0.\n\n    Returns:\n        torch.Tensor: Calculated loss\n    \"\"\"\n    assert beta > 0\n    assert pred.size() == target.size() and target.numel() > 0\n    diff = torch.abs(pred - target)\n    loss = torch.where(diff < beta, 0.5 * diff * diff / beta,\n                       diff - 0.5 * beta)\n    return loss\n\n\n@weighted_loss\ndef l1_loss(pred, target):\n    \"\"\"L1 loss.\n\n    Args:\n        pred (torch.Tensor): The prediction.\n        target (torch.Tensor): The learning target of the prediction.\n\n    Returns:\n        torch.Tensor: Calculated loss\n    \"\"\"\n    assert pred.size() == target.size() and target.numel() > 0\n    loss = torch.abs(pred - target)\n    return loss\n\n\n@LOSSES.register_module()\nclass SmoothL1Loss(nn.Module):\n    \"\"\"Smooth L1 loss.\n\n    Args:\n        beta (float, optional): The threshold in the piecewise function.\n            Defaults to 1.0.\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\". Defaults to \"mean\".\n        loss_weight (float, optional): The weight of loss.\n    \"\"\"\n\n    def __init__(self, beta=1.0, reduction='mean', loss_weight=1.0):\n        super(SmoothL1Loss, self).__init__()\n        self.beta = beta\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None,\n                **kwargs):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        loss_bbox = self.loss_weight * smooth_l1_loss(\n            pred,\n            target,\n            weight,\n            beta=self.beta,\n            reduction=reduction,\n            avg_factor=avg_factor,\n            **kwargs)\n        return loss_bbox\n\n\n@LOSSES.register_module()\nclass L1Loss(nn.Module):\n    \"\"\"L1 loss.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n    \"\"\"\n\n    def __init__(self, reduction='mean', loss_weight=1.0):\n        super(L1Loss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        loss_bbox = self.loss_weight * l1_loss(\n            pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/losses/utils.py",
    "content": "import functools\n\nfrom mmcv.fileio.io import load\nimport numpy as np\nimport torch.nn.functional as F\n\ndef get_class_weight(class_weight):\n    \"\"\"Get class weight for loss function.\n\n    Args:\n        class_weight (list[float] | str | None): If class_weight is a str,\n            take it as a file name and read from it.\n    \"\"\"\n    if isinstance(class_weight, str):\n        # take it as a file path\n        if class_weight.endswith('.npy'):\n            class_weight = np.load(class_weight)\n        else:\n            # pkl, json or yaml\n            class_weight = load(class_weight)\n\n    return class_weight\n\ndef reduce_loss(loss, reduction):\n    \"\"\"Reduce loss as specified.\n\n    Args:\n        loss (Tensor): Elementwise loss tensor.\n        reduction (str): Options are \"none\", \"mean\" and \"sum\".\n\n    Return:\n        Tensor: Reduced loss tensor.\n    \"\"\"\n    reduction_enum = F._Reduction.get_enum(reduction)\n    # none: 0, elementwise_mean:1, sum: 2\n    if reduction_enum == 0:\n        return loss\n    elif reduction_enum == 1:\n        return loss.mean()\n    elif reduction_enum == 2:\n        return loss.sum()\n\ndef weight_reduce_loss(loss, weight=None, reduction='mean', avg_factor=None):\n    \"\"\"Apply element-wise weight and reduce loss.\n\n    Args:\n        loss (Tensor): Element-wise loss.\n        weight (Tensor): Element-wise weights.\n        reduction (str): Same as built-in losses of PyTorch.\n        avg_factor (float): Avarage factor when computing the mean of losses.\n\n    Returns:\n        Tensor: Processed loss values.\n    \"\"\"\n    # if weight is specified, apply element-wise weight\n    if weight is not None:\n        loss = loss * weight\n\n    # if avg_factor is not specified, just reduce the loss\n    if avg_factor is None:\n        loss = reduce_loss(loss, reduction)\n    else:\n        # if reduction is mean, then average the loss by avg_factor\n        if reduction == 'mean':\n            loss = loss.sum() / avg_factor\n        # if reduction is 'none', then do nothing, otherwise raise an error\n        elif reduction != 'none':\n            raise ValueError('avg_factor can not be used with reduction=\"sum\"')\n    return loss\n\n\ndef weighted_loss(loss_func):\n    \"\"\"Create a weighted version of a given loss function.\n\n    To use this decorator, the loss function must have the signature like\n    `loss_func(pred, target, **kwargs)`. The function only needs to compute\n    element-wise loss without any reduction. This decorator will add weight\n    and reduction arguments to the function. The decorated function will have\n    the signature like `loss_func(pred, target, weight=None, reduction='mean',\n    avg_factor=None, **kwargs)`.\n\n    :Example:\n\n    >>> import torch\n    >>> @weighted_loss\n    >>> def l1_loss(pred, target):\n    >>>     return (pred - target).abs()\n\n    >>> pred = torch.Tensor([0, 2, 3])\n    >>> target = torch.Tensor([1, 1, 1])\n    >>> weight = torch.Tensor([1, 0, 1])\n\n    >>> l1_loss(pred, target)\n    tensor(1.3333)\n    >>> l1_loss(pred, target, weight)\n    tensor(1.)\n    >>> l1_loss(pred, target, reduction='none')\n    tensor([1., 1., 2.])\n    >>> l1_loss(pred, target, weight, avg_factor=2)\n    tensor(1.5000)\n    \"\"\"\n\n    @functools.wraps(loss_func)\n    def wrapper(pred,\n                target,\n                weight=None,\n                reduction='mean',\n                avg_factor=None,\n                **kwargs):\n        # get element-wise loss\n        loss = loss_func(pred, target, **kwargs)\n        loss = weight_reduce_loss(loss, weight, reduction, avg_factor)\n        return loss\n\n    return wrapper\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/VAD_transformer.py",
    "content": "import torch\nimport numpy as np\nimport torch.nn as nn\nfrom mmcv.models.utils import xavier_init\nfrom mmcv.utils import ext_loader\nfrom torch.nn.init import normal_\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom mmcv.models.utils.builder import TRANSFORMER\nfrom torchvision.transforms.functional import rotate\nfrom mmcv.models.bricks.registry import TRANSFORMER_LAYER_SEQUENCE\nfrom mmcv.models.bricks.transformer import TransformerLayerSequence\nfrom mmcv.models.bricks.transformer import build_transformer_layer_sequence\n\nfrom mmcv.models.modules.decoder import CustomMSDeformableAttention\nfrom mmcv.models.modules.temporal_self_attention import TemporalSelfAttention\nfrom mmcv.models.modules.spatial_cross_attention import MSDeformableAttention3D\n\n\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\ndef inverse_sigmoid(x, eps=1e-5):\n    \"\"\"Inverse function of sigmoid.\n    Args:\n        x (Tensor): The tensor to do the\n            inverse.\n        eps (float): EPS avoid numerical\n            overflow. Defaults 1e-5.\n    Returns:\n        Tensor: The x has passed the inverse\n            function of sigmoid, has same\n            shape with input.\n    \"\"\"\n    x = x.clamp(min=0, max=1)\n    x1 = x.clamp(min=eps)\n    x2 = (1 - x).clamp(min=eps)\n    return torch.log(x1 / x2)\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass MapDetectionTransformerDecoder(TransformerLayerSequence):\n    \"\"\"Implements the decoder in DETR3D transformer.\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        coder_norm_cfg (dict): Config of last normalization layer. Default:\n            `LN`.\n    \"\"\"\n\n    def __init__(self, *args, return_intermediate=False, **kwargs):\n        super(MapDetectionTransformerDecoder, self).__init__(*args, **kwargs)\n        self.return_intermediate = return_intermediate\n        self.fp16_enabled = False\n\n    def forward(self,\n                query,\n                *args,\n                reference_points=None,\n                reg_branches=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `Detr3DTransformerDecoder`.\n        Args:\n            query (Tensor): Input query with shape\n                `(num_query, bs, embed_dims)`.\n            reference_points (Tensor): The reference\n                points of offset. has shape\n                (bs, num_query, 4) when as_two_stage,\n                otherwise has shape ((bs, num_query, 2).\n            reg_branch: (obj:`nn.ModuleList`): Used for\n                refining the regression results. Only would\n                be passed when with_box_refine is True,\n                otherwise would be passed a `None`.\n        Returns:\n            Tensor: Results with shape [1, num_query, bs, embed_dims] when\n                return_intermediate is `False`, otherwise it has shape\n                [num_layers, num_query, bs, embed_dims].\n        \"\"\"\n        output = query\n        intermediate = []\n        intermediate_reference_points = []\n        for lid, layer in enumerate(self.layers):\n\n            reference_points_input = reference_points[..., :2].unsqueeze(\n                2)  # BS NUM_QUERY NUM_LEVEL 2\n            output = layer(\n                output,\n                *args,\n                reference_points=reference_points_input,\n                key_padding_mask=key_padding_mask,\n                **kwargs)\n            output = output.permute(1, 0, 2)\n\n            if reg_branches is not None:\n                tmp = reg_branches[lid](output)\n\n                assert reference_points.shape[-1] == 2\n\n                new_reference_points = torch.zeros_like(reference_points)\n                new_reference_points[..., :2] = tmp[\n                    ..., :2] + inverse_sigmoid(reference_points[..., :2])\n                # new_reference_points[..., 2:3] = tmp[\n                #     ..., 4:5] + inverse_sigmoid(reference_points[..., 2:3])\n\n                new_reference_points = new_reference_points.sigmoid()\n\n                reference_points = new_reference_points.detach()\n\n            output = output.permute(1, 0, 2)\n            if self.return_intermediate:\n                intermediate.append(output)\n                intermediate_reference_points.append(reference_points)\n\n        if self.return_intermediate:\n            return torch.stack(intermediate), torch.stack(\n                intermediate_reference_points)\n\n        return output, reference_points\n\n\n@TRANSFORMER.register_module()\nclass VADPerceptionTransformer(BaseModule):\n    \"\"\"Implements the Detr3D transformer.\n    Args:\n        as_two_stage (bool): Generate query from encoder features.\n            Default: False.\n        num_feature_levels (int): Number of feature maps from FPN:\n            Default: 4.\n        two_stage_num_proposals (int): Number of proposals when set\n            `as_two_stage` as True. Default: 300.\n    \"\"\"\n\n    def __init__(self,\n                 num_feature_levels=4,\n                 num_cams=6,\n                 two_stage_num_proposals=300,\n                 encoder=None,\n                 decoder=None,\n                 map_decoder=None,\n                 embed_dims=256,\n                 rotate_prev_bev=True,\n                 use_shift=True,\n                 use_can_bus=True,\n                 can_bus_norm=True,\n                 use_cams_embeds=True,\n                 rotate_center=[100, 100],\n                 map_num_vec=50,\n                 map_num_pts_per_vec=10,\n                 **kwargs):\n        super(VADPerceptionTransformer, self).__init__(**kwargs)\n        self.encoder = build_transformer_layer_sequence(encoder)\n        if decoder is not None:\n            self.decoder = build_transformer_layer_sequence(decoder)\n        else:\n            self.decoder = None\n        if map_decoder is not None:\n            self.map_decoder = build_transformer_layer_sequence(map_decoder)\n        else:\n            self.map_decoder = None\n\n        self.embed_dims = embed_dims\n        self.num_feature_levels = num_feature_levels\n        self.num_cams = num_cams\n        self.fp16_enabled = False\n        self.rotate_prev_bev = rotate_prev_bev\n        self.use_shift = use_shift\n        self.use_can_bus = use_can_bus\n        self.can_bus_norm = can_bus_norm\n        self.use_cams_embeds = use_cams_embeds\n        self.two_stage_num_proposals = two_stage_num_proposals\n        self.rotate_center = rotate_center\n        self.map_num_vec = map_num_vec\n        self.map_num_pts_per_vec = map_num_pts_per_vec\n        self.init_layers()\n\n    def init_layers(self):\n        \"\"\"Initialize layers of the Detr3DTransformer.\"\"\"\n        self.level_embeds = nn.Parameter(torch.Tensor(\n            self.num_feature_levels, self.embed_dims))\n        self.cams_embeds = nn.Parameter(\n            torch.Tensor(self.num_cams, self.embed_dims))\n        self.reference_points = nn.Linear(self.embed_dims, 3)\n        self.map_reference_points = nn.Linear(self.embed_dims, 2)\n        self.can_bus_mlp = nn.Sequential(\n            nn.Linear(18, self.embed_dims // 2),\n            nn.ReLU(inplace=True),\n            nn.Linear(self.embed_dims // 2, self.embed_dims),\n            nn.ReLU(inplace=True),\n        )\n        if self.can_bus_norm:\n            self.can_bus_mlp.add_module('norm', nn.LayerNorm(self.embed_dims))\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MSDeformableAttention3D) or isinstance(m, TemporalSelfAttention) \\\n                    or isinstance(m, CustomMSDeformableAttention):\n                try:\n                    m.init_weight()\n                except AttributeError:\n                    m.init_weights()\n        normal_(self.level_embeds)\n        normal_(self.cams_embeds)\n        xavier_init(self.reference_points, distribution='uniform', bias=0.)\n        xavier_init(self.map_reference_points, distribution='uniform', bias=0.)\n        xavier_init(self.can_bus_mlp, distribution='uniform', bias=0.)\n\n    # TODO apply fp16 to this module cause grad_norm NAN\n    # @auto_fp16(apply_to=('mlvl_feats', 'bev_queries', 'prev_bev', 'bev_pos'))\n    def get_bev_features(\n            self,\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=[0.512, 0.512],\n            bev_pos=None,\n            prev_bev=None,\n            **kwargs):\n        \"\"\"\n        obtain bev features.\n        \"\"\"\n\n        bs = mlvl_feats[0].size(0)\n        bev_queries = bev_queries.unsqueeze(1).repeat(1, bs, 1)\n        bev_pos = bev_pos.flatten(2).permute(2, 0, 1)\n\n        # obtain rotation angle and shift with ego motion\n        delta_x = np.array([each['can_bus'][0]\n                           for each in kwargs['img_metas']])\n        delta_y = np.array([each['can_bus'][1]\n                           for each in kwargs['img_metas']])\n        ego_angle = np.array(\n            [each['can_bus'][-2] / np.pi * 180 for each in kwargs['img_metas']])\n        grid_length_y = grid_length[0]\n        grid_length_x = grid_length[1]\n        translation_length = np.sqrt(delta_x ** 2 + delta_y ** 2)\n        translation_angle = np.arctan2(delta_y, delta_x) / np.pi * 180\n        bev_angle = ego_angle - translation_angle\n        shift_y = translation_length * \\\n            np.cos(bev_angle / 180 * np.pi) / grid_length_y / bev_h\n        shift_x = translation_length * \\\n            np.sin(bev_angle / 180 * np.pi) / grid_length_x / bev_w\n        shift_y = shift_y * self.use_shift\n        shift_x = shift_x * self.use_shift\n        shift = bev_queries.new_tensor(\n            [shift_x, shift_y]).permute(1, 0)  # xy, bs -> bs, xy\n\n        if prev_bev is not None:\n            if prev_bev.shape[1] == bev_h * bev_w:\n                prev_bev = prev_bev.permute(1, 0, 2)\n            if self.rotate_prev_bev:\n                for i in range(bs):\n                    # num_prev_bev = prev_bev.size(1)\n                    rotation_angle = kwargs['img_metas'][i]['can_bus'][-1]\n                    tmp_prev_bev = prev_bev[:, i].reshape(\n                        bev_h, bev_w, -1).permute(2, 0, 1)\n                    tmp_prev_bev = rotate(tmp_prev_bev, rotation_angle,\n                                          center=self.rotate_center)\n                    tmp_prev_bev = tmp_prev_bev.permute(1, 2, 0).reshape(\n                        bev_h * bev_w, 1, -1)\n                    prev_bev[:, i] = tmp_prev_bev[:, 0]\n\n        # add can bus signals\n        can_bus = bev_queries.new_tensor(\n            [each['can_bus'] for each in kwargs['img_metas']])  # [:, :]\n        can_bus = self.can_bus_mlp(can_bus)[None, :, :]\n        bev_queries = bev_queries + can_bus * self.use_can_bus\n\n        feat_flatten = []\n        spatial_shapes = []\n        for lvl, feat in enumerate(mlvl_feats):\n            bs, num_cam, c, h, w = feat.shape\n            spatial_shape = (h, w)\n            feat = feat.flatten(3).permute(1, 0, 3, 2)\n            if self.use_cams_embeds:\n                feat = feat + self.cams_embeds[:, None, None, :].to(feat.dtype)\n            feat = feat + self.level_embeds[None,\n                                            None, lvl:lvl + 1, :].to(feat.dtype)\n            spatial_shapes.append(spatial_shape)\n            feat_flatten.append(feat)\n\n        feat_flatten = torch.cat(feat_flatten, 2)\n        spatial_shapes = torch.as_tensor(\n            spatial_shapes, dtype=torch.long, device=bev_pos.device)\n        level_start_index = torch.cat((spatial_shapes.new_zeros(\n            (1,)), spatial_shapes.prod(1).cumsum(0)[:-1]))\n\n        feat_flatten = feat_flatten.permute(\n            0, 2, 1, 3)  # (num_cam, H*W, bs, embed_dims)\n\n        bev_embed = self.encoder(\n            bev_queries,\n            feat_flatten,\n            feat_flatten,\n            bev_h=bev_h,\n            bev_w=bev_w,\n            bev_pos=bev_pos,\n            spatial_shapes=spatial_shapes,\n            level_start_index=level_start_index,\n            prev_bev=prev_bev,\n            shift=shift,\n            **kwargs\n        )\n\n        return bev_embed\n\n    # TODO apply fp16 to this module cause grad_norm NAN\n    # @auto_fp16(apply_to=('mlvl_feats', 'bev_queries', 'object_query_embed', 'prev_bev', 'bev_pos'))\n    def forward(self,\n                mlvl_feats,\n                bev_queries,\n                object_query_embed,\n                map_query_embed,\n                bev_h,\n                bev_w,\n                grid_length=[0.512, 0.512],\n                bev_pos=None,\n                reg_branches=None,\n                cls_branches=None,\n                map_reg_branches=None,\n                map_cls_branches=None,                \n                prev_bev=None,            \n                **kwargs):\n        \"\"\"Forward function for `Detr3DTransformer`.\n        Args:\n            mlvl_feats (list(Tensor)): Input queries from\n                different level. Each element has shape\n                [bs, num_cams, embed_dims, h, w].\n            bev_queries (Tensor): (bev_h*bev_w, c)\n            bev_pos (Tensor): (bs, embed_dims, bev_h, bev_w)\n            object_query_embed (Tensor): The query embedding for decoder,\n                with shape [num_query, c].\n            reg_branches (obj:`nn.ModuleList`): Regression heads for\n                feature maps from each decoder layer. Only would\n                be passed when `with_box_refine` is True. Default to None.\n        Returns:\n            tuple[Tensor]: results of decoder containing the following tensor.\n                - bev_embed: BEV features\n                - inter_states: Outputs from decoder. If\n                    return_intermediate_dec is True output has shape \\\n                      (num_dec_layers, bs, num_query, embed_dims), else has \\\n                      shape (1, bs, num_query, embed_dims).\n                - init_reference_out: The initial value of reference \\\n                    points, has shape (bs, num_queries, 4).\n                - inter_references_out: The internal value of reference \\\n                    points in decoder, has shape \\\n                    (num_dec_layers, bs,num_query, embed_dims)\n                - enc_outputs_class: The classification score of \\\n                    proposals generated from \\\n                    encoder's feature maps, has shape \\\n                    (batch, h*w, num_classes). \\\n                    Only would be returned when `as_two_stage` is True, \\\n                    otherwise None.\n                - enc_outputs_coord_unact: The regression results \\\n                    generated from encoder's feature maps., has shape \\\n                    (batch, h*w, 4). Only would \\\n                    be returned when `as_two_stage` is True, \\\n                    otherwise None.\n        \"\"\"\n\n        bev_embed = self.get_bev_features(\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=grid_length,\n            bev_pos=bev_pos,\n            prev_bev=prev_bev,\n            **kwargs)  # bev_embed shape: bs, bev_h*bev_w, embed_dims\n\n        bs = mlvl_feats[0].size(0)\n        query_pos, query = torch.split(\n            object_query_embed, self.embed_dims, dim=1)\n        query_pos = query_pos.unsqueeze(0).expand(bs, -1, -1)\n        query = query.unsqueeze(0).expand(bs, -1, -1)\n        reference_points = self.reference_points(query_pos)\n        reference_points = reference_points.sigmoid()\n        init_reference_out = reference_points\n\n        map_query_pos, map_query = torch.split(\n            map_query_embed, self.embed_dims, dim=1)\n        map_query_pos = map_query_pos.unsqueeze(0).expand(bs, -1, -1)\n        map_query = map_query.unsqueeze(0).expand(bs, -1, -1)\n        map_reference_points = self.map_reference_points(map_query_pos)\n        map_reference_points = map_reference_points.sigmoid()\n        map_init_reference_out = map_reference_points        \n\n        query = query.permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        map_query = map_query.permute(1, 0, 2)\n        map_query_pos = map_query_pos.permute(1, 0, 2)\n        bev_embed = bev_embed.permute(1, 0, 2)\n\n        if self.decoder is not None:\n            # [L, Q, B, D], [L, B, Q, D]\n            inter_states, inter_references = self.decoder(\n                query=query,\n                key=None,\n                value=bev_embed,\n                query_pos=query_pos,\n                reference_points=reference_points,\n                reg_branches=reg_branches,\n                cls_branches=cls_branches,\n                spatial_shapes=torch.tensor([[bev_h, bev_w]], device=query.device),\n                level_start_index=torch.tensor([0], device=query.device),\n                **kwargs)\n            inter_references_out = inter_references\n        else:\n            inter_states = query.unsqueeze(0)\n            inter_references_out = reference_points.unsqueeze(0)\n\n        if self.map_decoder is not None:\n            # [L, Q, B, D], [L, B, Q, D]\n            map_inter_states, map_inter_references = self.map_decoder(\n                query=map_query,\n                key=None,\n                value=bev_embed,\n                query_pos=map_query_pos,\n                reference_points=map_reference_points,\n                reg_branches=map_reg_branches,\n                cls_branches=map_cls_branches,\n                spatial_shapes=torch.tensor([[bev_h, bev_w]], device=map_query.device),\n                level_start_index=torch.tensor([0], device=map_query.device),\n                **kwargs)\n            map_inter_references_out = map_inter_references\n        else:\n            map_inter_states = map_query.unsqueeze(0)\n            map_inter_references_out = map_reference_points.unsqueeze(0)\n\n        return (\n            bev_embed, inter_states, init_reference_out, inter_references_out,\n            map_inter_states, map_init_reference_out, map_inter_references_out)\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass CustomTransformerDecoder(TransformerLayerSequence):\n    \"\"\"Implements the decoder in DETR3D transformer.\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        coder_norm_cfg (dict): Config of last normalization layer. Default: `LN`.\n    \"\"\"\n\n    def __init__(self, *args, return_intermediate=False, **kwargs):\n        super(CustomTransformerDecoder, self).__init__(*args, **kwargs)\n        self.return_intermediate = return_intermediate\n        self.fp16_enabled = False\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                query_pos=None,\n                key_pos=None,\n                attn_masks=None,\n                key_padding_mask=None,\n                *args,\n                **kwargs):\n        \"\"\"Forward function for `Detr3DTransformerDecoder`.\n        Args:\n            query (Tensor): Input query with shape\n                `(num_query, bs, embed_dims)`.\n        Returns:\n            Tensor: Results with shape [1, num_query, bs, embed_dims] when\n                return_intermediate is `False`, otherwise it has shape\n                [num_layers, num_query, bs, embed_dims].\n        \"\"\"\n        intermediate = []\n        for lid, layer in enumerate(self.layers):\n            query = layer(\n                query=query,\n                key=key,\n                value=value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                attn_masks=attn_masks,\n                key_padding_mask=key_padding_mask,\n                *args,\n                **kwargs)\n\n            if self.return_intermediate:\n                intermediate.append(query)\n\n        if self.return_intermediate:\n            return torch.stack(intermediate)\n\n        return query"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/__init__.py",
    "content": "from .transformer import BEVFormerPerceptionTransformer, UniADPerceptionTransformer, GroupFree3DMHA\nfrom .spatial_cross_attention import SpatialCrossAttention, MSDeformableAttention3D\nfrom .temporal_self_attention import TemporalSelfAttention\nfrom .encoder import BEVFormerEncoder, BEVFormerLayer\nfrom .decoder import DetectionTransformerDecoder\nfrom .vote_module import VoteModule\nfrom .VAD_transformer import VADPerceptionTransformer\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/custom_base_transformer_layer.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nimport copy\nimport warnings\n\nimport torch\n\nfrom mmcv import ConfigDict\nfrom mmcv.models.bricks import build_norm_layer\nfrom mmcv.models.backbones.base_module import BaseModule, ModuleList\n\nfrom mmcv.models.bricks.registry import TRANSFORMER_LAYER\nfrom mmcv.models.bricks.transformer import build_feedforward_network, build_attention\n\n\n@TRANSFORMER_LAYER.register_module()\nclass MyCustomBaseTransformerLayer(BaseModule):\n    \"\"\"Base `TransformerLayer` for vision transformer.\n    It can be built from `mmcv.ConfigDict` and support more flexible\n    customization, for example, using any number of `FFN or LN ` and\n    use different kinds of `attention` by specifying a list of `ConfigDict`\n    named `attn_cfgs`. It is worth mentioning that it supports `prenorm`\n    when you specifying `norm` as the first element of `operation_order`.\n    More details about the `prenorm`: `On Layer Normalization in the\n    Transformer Architecture <https://arxiv.org/abs/2002.04745>`_ .\n    Args:\n        attn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):\n            Configs for `self_attention` or `cross_attention` modules,\n            The order of the configs in the list should be consistent with\n            corresponding attentions in operation_order.\n            If it is a dict, all of the attention modules in operation_order\n            will be built with this config. Default: None.\n        ffn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):\n            Configs for FFN, The order of the configs in the list should be\n            consistent with corresponding ffn in operation_order.\n            If it is a dict, all of the attention modules in operation_order\n            will be built with this config.\n        operation_order (tuple[str]): The execution order of operation\n            in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').\n            Support `prenorm` when you specifying first element as `norm`.\n            Default：None.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: dict(type='LN').\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): Key, Query and Value are shape\n            of (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 attn_cfgs=None,\n                 ffn_cfgs=dict(\n                     type='FFN',\n                     embed_dims=256,\n                     feedforward_channels=1024,\n                     num_fcs=2,\n                     ffn_drop=0.,\n                     act_cfg=dict(type='ReLU', inplace=True),\n                 ),\n                 operation_order=None,\n                 norm_cfg=dict(type='LN'),\n                 init_cfg=None,\n                 batch_first=True,\n                 **kwargs):\n\n        deprecated_args = dict(\n            feedforward_channels='feedforward_channels',\n            ffn_dropout='ffn_drop',\n            ffn_num_fcs='num_fcs')\n        for ori_name, new_name in deprecated_args.items():\n            if ori_name in kwargs:\n                warnings.warn(\n                    f'The arguments `{ori_name}` in BaseTransformerLayer '\n                    f'has been deprecated, now you should set `{new_name}` '\n                    f'and other FFN related arguments '\n                    f'to a dict named `ffn_cfgs`. ')\n                ffn_cfgs[new_name] = kwargs[ori_name]\n\n        super(MyCustomBaseTransformerLayer, self).__init__(init_cfg)\n\n        self.batch_first = batch_first\n\n        assert set(operation_order) & set(\n            ['self_attn', 'norm', 'ffn', 'cross_attn']) == \\\n            set(operation_order), f'The operation_order of' \\\n            f' {self.__class__.__name__} should ' \\\n            f'contains all four operation type ' \\\n            f\"{['self_attn', 'norm', 'ffn', 'cross_attn']}\"\n\n        num_attn = operation_order.count('self_attn') + operation_order.count(\n            'cross_attn')\n        if isinstance(attn_cfgs, dict):\n            attn_cfgs = [copy.deepcopy(attn_cfgs) for _ in range(num_attn)]\n        else:\n            assert num_attn == len(attn_cfgs), f'The length ' \\\n                f'of attn_cfg {num_attn} is ' \\\n                f'not consistent with the number of attention' \\\n                f'in operation_order {operation_order}.'\n\n        self.num_attn = num_attn\n        self.operation_order = operation_order\n        self.norm_cfg = norm_cfg\n        self.pre_norm = operation_order[0] == 'norm'\n        self.attentions = ModuleList()\n\n        index = 0\n        for operation_name in operation_order:\n            if operation_name in ['self_attn', 'cross_attn']:\n                if 'batch_first' in attn_cfgs[index]:\n                    assert self.batch_first == attn_cfgs[index]['batch_first']\n                else:\n                    attn_cfgs[index]['batch_first'] = self.batch_first\n                attention = build_attention(attn_cfgs[index])\n                # Some custom attentions used as `self_attn`\n                # or `cross_attn` can have different behavior.\n                attention.operation_name = operation_name\n                self.attentions.append(attention)\n                index += 1\n\n        self.embed_dims = self.attentions[0].embed_dims\n\n        self.ffns = ModuleList()\n        num_ffns = operation_order.count('ffn')\n        if isinstance(ffn_cfgs, dict):\n            ffn_cfgs = ConfigDict(ffn_cfgs)\n        if isinstance(ffn_cfgs, dict):\n            ffn_cfgs = [copy.deepcopy(ffn_cfgs) for _ in range(num_ffns)]\n        assert len(ffn_cfgs) == num_ffns\n        for ffn_index in range(num_ffns):\n            if 'embed_dims' not in ffn_cfgs[ffn_index]:\n                ffn_cfgs['embed_dims'] = self.embed_dims\n            else:\n                assert ffn_cfgs[ffn_index]['embed_dims'] == self.embed_dims\n\n            self.ffns.append(\n                build_feedforward_network(ffn_cfgs[ffn_index]))\n\n        self.norms = ModuleList()\n        num_norms = operation_order.count('norm')\n        for _ in range(num_norms):\n            self.norms.append(build_norm_layer(norm_cfg, self.embed_dims)[1])\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                query_pos=None,\n                key_pos=None,\n                attn_masks=None,\n                query_key_padding_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerDecoderLayer`.\n        **kwargs contains some specific arguments of attentions.\n        Args:\n            query (Tensor): The input query with shape\n                [num_queries, bs, embed_dims] if\n                self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n            value (Tensor): The value tensor with same shape as `key`.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`.\n                Default: None.\n            attn_masks (List[Tensor] | None): 2D Tensor used in\n                calculation of corresponding attention. The length of\n                it should equal to the number of `attention` in\n                `operation_order`. Default: None.\n            query_key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_queries]. Only used in `self_attn` layer.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_keys]. Default: None.\n        Returns:\n            Tensor: forwarded results with shape [num_queries, bs, embed_dims].\n        \"\"\"\n\n        norm_index = 0\n        attn_index = 0\n        ffn_index = 0\n        identity = query\n        if attn_masks is None:\n            attn_masks = [None for _ in range(self.num_attn)]\n        elif isinstance(attn_masks, torch.Tensor):\n            attn_masks = [\n                copy.deepcopy(attn_masks) for _ in range(self.num_attn)\n            ]\n            warnings.warn(f'Use same attn_mask in all attentions in '\n                          f'{self.__class__.__name__} ')\n        else:\n            assert len(attn_masks) == self.num_attn, f'The length of ' \\\n                f'attn_masks {len(attn_masks)} must be equal ' \\\n                f'to the number of attention in ' \\\n                f'operation_order {self.num_attn}'\n\n        for layer in self.operation_order:\n            if layer == 'self_attn':\n                temp_key = temp_value = query\n                query = self.attentions[attn_index](\n                    query,\n                    temp_key,\n                    temp_value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=query_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=query_key_padding_mask,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'norm':\n                query = self.norms[norm_index](query)\n                norm_index += 1\n\n            elif layer == 'cross_attn':\n                query = self.attentions[attn_index](\n                    query,\n                    key,\n                    value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=key_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=key_padding_mask,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'ffn':\n                query = self.ffns[ffn_index](\n                    query, identity if self.pre_norm else None)\n                ffn_index += 1\n\n        return query\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/decoder.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom mmcv.ops.multi_scale_deform_attn import multi_scale_deformable_attn_pytorch\nimport cv2 as cv\nimport copy\nimport warnings\nfrom matplotlib import pyplot as plt\nimport numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.utils import xavier_init, constant_init\nfrom mmcv.models.bricks.registry import (ATTENTION,\n                                      TRANSFORMER_LAYER_SEQUENCE)\nfrom mmcv.models.bricks.transformer import TransformerLayerSequence\nimport math\nfrom mmcv.models.backbones.base_module import BaseModule, ModuleList, Sequential\nfrom mmcv.utils import (ConfigDict, build_from_cfg, deprecated_api_warning,\n                        to_2tuple)\n\nfrom mmcv.utils import ext_loader\nfrom .multi_scale_deformable_attn_function import MultiScaleDeformableAttnFunction_fp32, \\\n    MultiScaleDeformableAttnFunction_fp16\n\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\n\ndef inverse_sigmoid(x, eps=1e-5):\n    \"\"\"Inverse function of sigmoid.\n    Args:\n        x (Tensor): The tensor to do the\n            inverse.\n        eps (float): EPS avoid numerical\n            overflow. Defaults 1e-5.\n    Returns:\n        Tensor: The x has passed the inverse\n            function of sigmoid, has same\n            shape with input.\n    \"\"\"\n    x = x.clamp(min=0, max=1)\n    x1 = x.clamp(min=eps)\n    x2 = (1 - x).clamp(min=eps)\n    return torch.log(x1 / x2)\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass DetectionTransformerDecoder(TransformerLayerSequence):\n    \"\"\"Implements the decoder in DETR3D transformer.\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        coder_norm_cfg (dict): Config of last normalization layer. Default：\n            `LN`.\n    \"\"\"\n\n    def __init__(self, *args, return_intermediate=False, **kwargs):\n        super(DetectionTransformerDecoder, self).__init__(*args, **kwargs)\n        self.return_intermediate = return_intermediate\n        self.fp16_enabled = False\n\n    def forward(self,\n                query,\n                *args,\n                reference_points=None,\n                reg_branches=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `Detr3DTransformerDecoder`.\n        Args:\n            query (Tensor): Input query with shape\n                `(num_query, bs, embed_dims)`.\n            reference_points (Tensor): The reference\n                points of offset. has shape\n                (bs, num_query, 4) when as_two_stage,\n                otherwise has shape ((bs, num_query, 2).\n            reg_branch: (obj:`nn.ModuleList`): Used for\n                refining the regression results. Only would\n                be passed when with_box_refine is True,\n                otherwise would be passed a `None`.\n        Returns:\n            Tensor: Results with shape [1, num_query, bs, embed_dims] when\n                return_intermediate is `False`, otherwise it has shape\n                [num_layers, num_query, bs, embed_dims].\n        \"\"\"\n        output = query\n        intermediate = []\n        intermediate_reference_points = []\n        for lid, layer in enumerate(self.layers):\n\n            reference_points_input = reference_points[..., :2].unsqueeze(\n                2)  # BS NUM_QUERY NUM_LEVEL 2\n            output = layer(\n                output,\n                *args,\n                reference_points=reference_points_input,\n                key_padding_mask=key_padding_mask,\n                **kwargs)\n            output = output.permute(1, 0, 2)\n\n            if reg_branches is not None:\n                tmp = reg_branches[lid](output)\n\n                assert reference_points.shape[-1] == 3\n\n                new_reference_points = torch.zeros_like(reference_points)\n                new_reference_points[..., :2] = tmp[\n                    ..., :2] + inverse_sigmoid(reference_points[..., :2])\n                new_reference_points[..., 2:3] = tmp[\n                    ..., 4:5] + inverse_sigmoid(reference_points[..., 2:3])\n\n                new_reference_points = new_reference_points.sigmoid()\n\n                reference_points = new_reference_points.detach()\n\n            output = output.permute(1, 0, 2)\n            if self.return_intermediate:\n                intermediate.append(output)\n                intermediate_reference_points.append(reference_points)\n\n        if self.return_intermediate:\n            return torch.stack(intermediate), torch.stack(\n                intermediate_reference_points)\n\n        return output, reference_points\n\n\n@ATTENTION.register_module()\nclass CustomMSDeformableAttention(BaseModule):\n    \"\"\"An attention module used in Deformable-Detr.\n\n    `Deformable DETR: Deformable Transformers for End-to-End Object Detection.\n    <https://arxiv.org/pdf/2010.04159.pdf>`_.\n\n    Args:\n        embed_dims (int): The embedding dimension of Attention.\n            Default: 256.\n        num_heads (int): Parallel attention heads. Default: 64.\n        num_levels (int): The number of feature map used in\n            Attention. Default: 4.\n        num_points (int): The number of sampling points for\n            each query in each head. Default: 4.\n        im2col_step (int): The step used in image_to_column.\n            Default: 64.\n        dropout (float): A Dropout layer on `inp_identity`.\n            Default: 0.1.\n        batch_first (bool): Key, Query and Value are shape of\n            (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: None.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 num_levels=4,\n                 num_points=4,\n                 im2col_step=64,\n                 dropout=0.1,\n                 batch_first=False,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n        if embed_dims % num_heads != 0:\n            raise ValueError(f'embed_dims must be divisible by num_heads, '\n                             f'but got {embed_dims} and {num_heads}')\n        dim_per_head = embed_dims // num_heads\n        self.norm_cfg = norm_cfg\n        self.dropout = nn.Dropout(dropout)\n        self.batch_first = batch_first\n        self.fp16_enabled = False\n\n        # you'd better set dim_per_head to a power of 2\n        # which is more efficient in the CUDA implementation\n        def _is_power_of_2(n):\n            if (not isinstance(n, int)) or (n < 0):\n                raise ValueError(\n                    'invalid input for _is_power_of_2: {} (type: {})'.format(\n                        n, type(n)))\n            return (n & (n - 1) == 0) and n != 0\n\n        if not _is_power_of_2(dim_per_head):\n            warnings.warn(\n                \"You'd better set embed_dims in \"\n                'MultiScaleDeformAttention to make '\n                'the dimension of each attention head a power of 2 '\n                'which is more efficient in our CUDA implementation.')\n\n        self.im2col_step = im2col_step\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_heads = num_heads\n        self.num_points = num_points\n        self.sampling_offsets = nn.Linear(\n            embed_dims, num_heads * num_levels * num_points * 2)\n        self.attention_weights = nn.Linear(embed_dims,\n                                           num_heads * num_levels * num_points)\n        self.value_proj = nn.Linear(embed_dims, embed_dims)\n        self.output_proj = nn.Linear(embed_dims, embed_dims)\n        self.init_weights()\n\n    def init_weights(self):\n        \"\"\"Default initialization for Parameters of Module.\"\"\"\n        constant_init(self.sampling_offsets, 0.)\n        thetas = torch.arange(\n            self.num_heads,\n            dtype=torch.float32) * (2.0 * math.pi / self.num_heads)\n        grid_init = torch.stack([thetas.cos(), thetas.sin()], -1)\n        grid_init = (grid_init /\n                     grid_init.abs().max(-1, keepdim=True)[0]).view(\n            self.num_heads, 1, 1,\n            2).repeat(1, self.num_levels, self.num_points, 1)\n        for i in range(self.num_points):\n            grid_init[:, :, i, :] *= i + 1\n\n        self.sampling_offsets.bias.data = grid_init.view(-1)\n        constant_init(self.attention_weights, val=0., bias=0.)\n        xavier_init(self.value_proj, distribution='uniform', bias=0.)\n        xavier_init(self.output_proj, distribution='uniform', bias=0.)\n        self._is_init = True\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiScaleDeformableAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_padding_mask=None,\n                reference_points=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                flag='decoder',\n                **kwargs):\n        \"\"\"Forward Function of MultiScaleDeformAttention.\n\n        Args:\n            query (Tensor): Query of Transformer with shape\n                (num_query, bs, embed_dims).\n            key (Tensor): The key tensor with shape\n                `(num_key, bs, embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(num_key, bs, embed_dims)`.\n            identity (Tensor): The tensor used for addition, with the\n                same shape as `query`. Default None. If None,\n                `query` will be used.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`. Default\n                None.\n            reference_points (Tensor):  The normalized reference\n                points with shape (bs, num_query, num_levels, 2),\n                all elements is range in [0, 1], top-left (0,0),\n                bottom-right (1, 1), including padding area.\n                or (N, Length_{query}, num_levels, 4), add\n                additional two dimensions is (w, h) to\n                form reference boxes.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_key].\n            spatial_shapes (Tensor): Spatial shape of features in\n                different levels. With shape (num_levels, 2),\n                last dimension represents (h, w).\n            level_start_index (Tensor): The start index of each level.\n                A tensor has shape ``(num_levels, )`` and can be represented\n                as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...].\n\n        Returns:\n             Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n\n        if value is None:\n            value = query\n\n        if identity is None:\n            identity = query\n        if query_pos is not None:\n            query = query + query_pos\n        if not self.batch_first:\n            # change to (bs, num_query ,embed_dims)\n            query = query.permute(1, 0, 2)\n            value = value.permute(1, 0, 2)\n\n        bs, num_query, _ = query.shape\n        bs, num_value, _ = value.shape\n        assert (spatial_shapes[:, 0] * spatial_shapes[:, 1]).sum() == num_value\n\n        value = self.value_proj(value)\n        if key_padding_mask is not None:\n            value = value.masked_fill(key_padding_mask[..., None], 0.0)\n        value = value.view(bs, num_value, self.num_heads, -1)\n\n        sampling_offsets = self.sampling_offsets(query).view(\n            bs, num_query, self.num_heads, self.num_levels, self.num_points, 2)\n        attention_weights = self.attention_weights(query).view(\n            bs, num_query, self.num_heads, self.num_levels * self.num_points)\n        attention_weights = attention_weights.softmax(-1)\n\n        attention_weights = attention_weights.view(bs, num_query,\n                                                   self.num_heads,\n                                                   self.num_levels,\n                                                   self.num_points)\n        if reference_points.shape[-1] == 2:\n            offset_normalizer = torch.stack(\n                [spatial_shapes[..., 1], spatial_shapes[..., 0]], -1)\n            sampling_locations = reference_points[:, :, None, :, None, :] \\\n                + sampling_offsets \\\n                / offset_normalizer[None, None, None, :, None, :]\n        elif reference_points.shape[-1] == 4:\n            sampling_locations = reference_points[:, :, None, :, None, :2] \\\n                + sampling_offsets / self.num_points \\\n                * reference_points[:, :, None, :, None, 2:] \\\n                * 0.5\n        else:\n            raise ValueError(\n                f'Last dim of reference_points must be'\n                f' 2 or 4, but get {reference_points.shape[-1]} instead.')\n        if torch.cuda.is_available() and value.is_cuda:\n\n            # using fp16 deformable attention is unstable because it performs many sum operations\n            if value.dtype == torch.float16:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            else:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            output = MultiScaleDeformableAttnFunction.apply(\n                value, spatial_shapes, level_start_index, sampling_locations,\n                attention_weights, self.im2col_step)\n        else:\n            output = multi_scale_deformable_attn_pytorch(\n                value, spatial_shapes, sampling_locations, attention_weights)\n\n        output = self.output_proj(output)\n\n        if not self.batch_first:\n            # (num_query, bs ,embed_dims)\n            output = output.permute(1, 0, 2)\n\n        return self.dropout(output) + identity\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/encoder.py",
    "content": "\n# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom .custom_base_transformer_layer import MyCustomBaseTransformerLayer\nimport copy\nimport warnings\nfrom mmcv.models.bricks.registry import (ATTENTION,\n                                      TRANSFORMER_LAYER,\n                                      TRANSFORMER_LAYER_SEQUENCE)\nfrom mmcv.models.bricks.transformer import TransformerLayerSequence\nfrom mmcv.utils import force_fp32, auto_fp16\nimport numpy as np\nimport torch\nimport cv2 as cv\nfrom mmcv.utils import TORCH_VERSION, digit_version\nfrom mmcv.utils import ext_loader\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass BEVFormerEncoder(TransformerLayerSequence):\n\n    \"\"\"\n    Attention with both self and cross\n    Implements the decoder in DETR transformer.\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        coder_norm_cfg (dict): Config of last normalization layer. Default：\n            `LN`.\n    \"\"\"\n\n    def __init__(self, *args, pc_range=None, num_points_in_pillar=4, return_intermediate=False, dataset_type='nuscenes',\n                 **kwargs):\n\n        super(BEVFormerEncoder, self).__init__(*args, **kwargs)\n        self.return_intermediate = return_intermediate\n\n        self.num_points_in_pillar = num_points_in_pillar\n        self.pc_range = pc_range\n        self.fp16_enabled = False\n\n    @staticmethod\n    def get_reference_points(H, W, Z=8, num_points_in_pillar=4, dim='3d', bs=1, device='cuda', dtype=torch.float):\n        \"\"\"Get the reference points used in SCA and TSA.\n        Args:\n            H, W: spatial shape of bev.\n            Z: hight of pillar.\n            D: sample D points uniformly from each pillar.\n            device (obj:`device`): The device where\n                reference_points should be.\n        Returns:\n            Tensor: reference points used in decoder, has \\\n                shape (bs, num_keys, num_levels, 2).\n        \"\"\"\n\n        # reference points in 3D space, used in spatial cross-attention (SCA)\n        if dim == '3d':\n            zs = torch.linspace(0.5, Z - 0.5, num_points_in_pillar, dtype=dtype,\n                                device=device).view(-1, 1, 1).expand(num_points_in_pillar, H, W) / Z\n            xs = torch.linspace(0.5, W - 0.5, W, dtype=dtype,\n                                device=device).view(1, 1, W).expand(num_points_in_pillar, H, W) / W\n            ys = torch.linspace(0.5, H - 0.5, H, dtype=dtype,\n                                device=device).view(1, H, 1).expand(num_points_in_pillar, H, W) / H\n            ref_3d = torch.stack((xs, ys, zs), -1)\n            ref_3d = ref_3d.permute(0, 3, 1, 2).flatten(2).permute(0, 2, 1)\n            ref_3d = ref_3d[None].repeat(bs, 1, 1, 1)\n            return ref_3d\n\n        # reference points on 2D bev plane, used in temporal self-attention (TSA).\n        elif dim == '2d':\n            ref_y, ref_x = torch.meshgrid(\n                torch.linspace(\n                    0.5, H - 0.5, H, dtype=dtype, device=device),\n                torch.linspace(\n                    0.5, W - 0.5, W, dtype=dtype, device=device)\n            )\n            ref_y = ref_y.reshape(-1)[None] / H\n            ref_x = ref_x.reshape(-1)[None] / W\n            ref_2d = torch.stack((ref_x, ref_y), -1)\n            ref_2d = ref_2d.repeat(bs, 1, 1).unsqueeze(2)\n            return ref_2d\n\n    # This function must use fp32!!!\n    @force_fp32(apply_to=('reference_points', 'img_metas'))\n    def point_sampling(self, reference_points, pc_range,  img_metas):\n        # NOTE: close tf32 here. TODO(yzj): used in bevformer\n        # allow_tf32 = torch.backends.cuda.matmul.allow_tf32\n        # torch.backends.cuda.matmul.allow_tf32 = False\n        # torch.backends.cudnn.allow_tf32 = False\n\n        lidar2img = []\n        for img_meta in img_metas:\n            lidar2img.append(img_meta['lidar2img'])\n        lidar2img = np.asarray(lidar2img)\n        lidar2img = reference_points.new_tensor(lidar2img)  # (B, N, 4, 4)\n        reference_points = reference_points.clone()\n\n        reference_points[..., 0:1] = reference_points[..., 0:1] * \\\n            (pc_range[3] - pc_range[0]) + pc_range[0]\n        reference_points[..., 1:2] = reference_points[..., 1:2] * \\\n            (pc_range[4] - pc_range[1]) + pc_range[1]\n        reference_points[..., 2:3] = reference_points[..., 2:3] * \\\n            (pc_range[5] - pc_range[2]) + pc_range[2]\n\n        reference_points = torch.cat(\n            (reference_points, torch.ones_like(reference_points[..., :1])), -1)\n\n        reference_points = reference_points.permute(1, 0, 2, 3)\n        D, B, num_query = reference_points.size()[:3]\n        num_cam = lidar2img.size(1)\n\n        reference_points = reference_points.view(\n            D, B, 1, num_query, 4).repeat(1, 1, num_cam, 1, 1).unsqueeze(-1)\n\n        lidar2img = lidar2img.view(\n            1, B, num_cam, 1, 4, 4).repeat(D, 1, 1, num_query, 1, 1)\n\n        reference_points_cam = torch.matmul(lidar2img.to(torch.float32),\n                                            reference_points.to(torch.float32)).squeeze(-1)\n        eps = 1e-5\n\n        bev_mask = (reference_points_cam[..., 2:3] > eps)\n        reference_points_cam = reference_points_cam[..., 0:2] / torch.maximum(\n            reference_points_cam[..., 2:3], torch.ones_like(reference_points_cam[..., 2:3]) * eps)\n\n        reference_points_cam[..., 0] /= img_metas[0]['img_shape'][0][1]\n        reference_points_cam[..., 1] /= img_metas[0]['img_shape'][0][0]\n\n        bev_mask = (bev_mask & (reference_points_cam[..., 1:2] > 0.0)\n                    & (reference_points_cam[..., 1:2] < 1.0)\n                    & (reference_points_cam[..., 0:1] < 1.0)\n                    & (reference_points_cam[..., 0:1] > 0.0))\n        if digit_version(TORCH_VERSION) >= digit_version('1.8'):\n            bev_mask = torch.nan_to_num(bev_mask)\n        else:\n            bev_mask = bev_mask.new_tensor(\n                np.nan_to_num(bev_mask.cpu().numpy()))\n\n        reference_points_cam = reference_points_cam.permute(2, 1, 3, 0, 4)\n        bev_mask = bev_mask.permute(2, 1, 3, 0, 4).squeeze(-1)\n\n        return reference_points_cam, bev_mask\n\n    @auto_fp16()\n    def forward(self,\n                bev_query,\n                key,\n                value,\n                *args,\n                bev_h=None,\n                bev_w=None,\n                bev_pos=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                valid_ratios=None,\n                prev_bev=None,\n                shift=0.,\n                img_metas=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerDecoder`.\n        Args:\n            bev_query (Tensor): Input BEV query with shape\n                `(num_query, bs, embed_dims)`.\n            key & value (Tensor): Input multi-cameta features with shape\n                (num_cam, num_value, bs, embed_dims)\n            reference_points (Tensor): The reference\n                points of offset. has shape\n                (bs, num_query, 4) when as_two_stage,\n                otherwise has shape ((bs, num_query, 2).\n            valid_ratios (Tensor): The radios of valid\n                points on the feature map, has shape\n                (bs, num_levels, 2)\n        Returns:\n            Tensor: Results with shape [1, num_query, bs, embed_dims] when\n                return_intermediate is `False`, otherwise it has shape\n                [num_layers, num_query, bs, embed_dims].\n        \"\"\"\n\n        output = bev_query\n        intermediate = []\n\n        ref_3d = self.get_reference_points(\n            bev_h, bev_w, self.pc_range[5]-self.pc_range[2], self.num_points_in_pillar, dim='3d', bs=bev_query.size(1),  device=bev_query.device, dtype=bev_query.dtype)\n        ref_2d = self.get_reference_points(\n            bev_h, bev_w, dim='2d', bs=bev_query.size(1), device=bev_query.device, dtype=bev_query.dtype)\n\n        reference_points_cam, bev_mask = self.point_sampling(\n            ref_3d, self.pc_range, img_metas)\n\n        # bug: this code should be 'shift_ref_2d = ref_2d.clone()', we keep this bug for reproducing our results in paper.\n        shift_ref_2d = ref_2d  # .clone()\n        shift_ref_2d += shift[:, None, None, :]\n\n        # (num_query, bs, embed_dims) -> (bs, num_query, embed_dims)\n        bev_query = bev_query.permute(1, 0, 2)\n        bev_pos = bev_pos.permute(1, 0, 2)\n        bs, len_bev, num_bev_level, _ = ref_2d.shape\n        if prev_bev is not None:\n            prev_bev = prev_bev.permute(1, 0, 2)\n            prev_bev = torch.stack(\n                [prev_bev, bev_query], 1).reshape(bs*2, len_bev, -1)\n            hybird_ref_2d = torch.stack([shift_ref_2d, ref_2d], 1).reshape(\n                bs*2, len_bev, num_bev_level, 2)\n        else:\n            hybird_ref_2d = torch.stack([ref_2d, ref_2d], 1).reshape(\n                bs*2, len_bev, num_bev_level, 2)\n\n        for lid, layer in enumerate(self.layers):\n            output = layer(\n                bev_query,\n                key,\n                value,\n                *args,\n                bev_pos=bev_pos,\n                ref_2d=hybird_ref_2d,\n                ref_3d=ref_3d,\n                bev_h=bev_h,\n                bev_w=bev_w,\n                spatial_shapes=spatial_shapes,\n                level_start_index=level_start_index,\n                reference_points_cam=reference_points_cam,\n                bev_mask=bev_mask,\n                prev_bev=prev_bev,\n                **kwargs)\n\n            bev_query = output\n            if self.return_intermediate:\n                intermediate.append(output)\n\n        if self.return_intermediate:\n            return torch.stack(intermediate)\n\n        return output\n\n\n@TRANSFORMER_LAYER.register_module()\nclass BEVFormerLayer(MyCustomBaseTransformerLayer):\n    \"\"\"Implements decoder layer in DETR transformer.\n    Args:\n        attn_cfgs (list[`mmcv.ConfigDict`] | list[dict] | dict )):\n            Configs for self_attention or cross_attention, the order\n            should be consistent with it in `operation_order`. If it is\n            a dict, it would be expand to the number of attention in\n            `operation_order`.\n        feedforward_channels (int): The hidden dimension for FFNs.\n        ffn_dropout (float): Probability of an element to be zeroed\n            in ffn. Default 0.0.\n        operation_order (tuple[str]): The execution order of operation\n            in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').\n            Default: None\n        act_cfg (dict): The activation config for FFNs. Default: `LN`\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: `LN`.\n        ffn_num_fcs (int): The number of fully-connected layers in FFNs.\n            Default: 2.\n    \"\"\"\n\n    def __init__(self,\n                 attn_cfgs,\n                 feedforward_channels,\n                 ffn_dropout=0.0,\n                 operation_order=None,\n                 act_cfg=dict(type='ReLU', inplace=True),\n                 norm_cfg=dict(type='LN'),\n                 ffn_num_fcs=2,\n                 **kwargs):\n        super(BEVFormerLayer, self).__init__(\n            attn_cfgs=attn_cfgs,\n            feedforward_channels=feedforward_channels,\n            ffn_dropout=ffn_dropout,\n            operation_order=operation_order,\n            act_cfg=act_cfg,\n            norm_cfg=norm_cfg,\n            ffn_num_fcs=ffn_num_fcs,\n            **kwargs)\n        self.fp16_enabled = False\n        assert len(operation_order) == 6\n        assert set(operation_order) == set(\n            ['self_attn', 'norm', 'cross_attn', 'ffn'])\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                bev_pos=None,\n                query_pos=None,\n                key_pos=None,\n                attn_masks=None,\n                query_key_padding_mask=None,\n                key_padding_mask=None,\n                ref_2d=None,\n                ref_3d=None,\n                bev_h=None,\n                bev_w=None,\n                reference_points_cam=None,\n                mask=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                prev_bev=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerDecoderLayer`.\n\n        **kwargs contains some specific arguments of attentions.\n\n        Args:\n            query (Tensor): The input query with shape\n                [num_queries, bs, embed_dims] if\n                self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n            value (Tensor): The value tensor with same shape as `key`.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`.\n                Default: None.\n            attn_masks (List[Tensor] | None): 2D Tensor used in\n                calculation of corresponding attention. The length of\n                it should equal to the number of `attention` in\n                `operation_order`. Default: None.\n            query_key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_queries]. Only used in `self_attn` layer.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_keys]. Default: None.\n\n        Returns:\n            Tensor: forwarded results with shape [num_queries, bs, embed_dims].\n        \"\"\"\n\n        norm_index = 0\n        attn_index = 0\n        ffn_index = 0\n        identity = query\n        if attn_masks is None:\n            attn_masks = [None for _ in range(self.num_attn)]\n        elif isinstance(attn_masks, torch.Tensor):\n            attn_masks = [\n                copy.deepcopy(attn_masks) for _ in range(self.num_attn)\n            ]\n            warnings.warn(f'Use same attn_mask in all attentions in '\n                          f'{self.__class__.__name__} ')\n        else:\n            assert len(attn_masks) == self.num_attn, f'The length of ' \\\n                                                     f'attn_masks {len(attn_masks)} must be equal ' \\\n                                                     f'to the number of attention in ' \\\n                f'operation_order {self.num_attn}'\n\n        for layer in self.operation_order:\n            # temporal self attention\n            if layer == 'self_attn':\n\n                query = self.attentions[attn_index](\n                    query,\n                    prev_bev,\n                    prev_bev,\n                    identity if self.pre_norm else None,\n                    query_pos=bev_pos,\n                    key_pos=bev_pos,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=query_key_padding_mask,\n                    reference_points=ref_2d,\n                    spatial_shapes=torch.tensor(\n                        [[bev_h, bev_w]], device=query.device),\n                    level_start_index=torch.tensor([0], device=query.device),\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'norm':\n                query = self.norms[norm_index](query)\n                norm_index += 1\n\n            # spaital cross attention\n            elif layer == 'cross_attn':\n                query = self.attentions[attn_index](\n                    query,\n                    key,\n                    value,\n                    identity if self.pre_norm else None,\n                    query_pos=query_pos,\n                    key_pos=key_pos,\n                    reference_points=ref_3d,\n                    reference_points_cam=reference_points_cam,\n                    mask=mask,\n                    attn_mask=attn_masks[attn_index],\n                    key_padding_mask=key_padding_mask,\n                    spatial_shapes=spatial_shapes,\n                    level_start_index=level_start_index,\n                    **kwargs)\n                attn_index += 1\n                identity = query\n\n            elif layer == 'ffn':\n                query = self.ffns[ffn_index](\n                    query, identity if self.pre_norm else None)\n                ffn_index += 1\n\n        return query\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/group_attention.py",
    "content": "import copy\nimport math\nimport warnings\nfrom typing import Sequence\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nfrom mmcv.cnn import (Linear, build_activation_layer, build_conv_layer, build_norm_layer)\nfrom mmcv.runner.base_module import BaseModule, ModuleList, Sequential\nfrom mmcv.utils import (ConfigDict, build_from_cfg, deprecated_api_warning, to_2tuple)\nfrom mmcv.cnn.bricks.drop import build_dropout\nfrom mmcv.cnn.bricks.registry import (ATTENTION, FEEDFORWARD_NETWORK, POSITIONAL_ENCODING, TRANSFORMER_LAYER,\n                                      TRANSFORMER_LAYER_SEQUENCE)\n\n\n@ATTENTION.register_module()\nclass GroupMultiheadAttention(BaseModule):\n    \"\"\"A wrapper for ``torch.nn.MultiheadAttention``.\n    This module implements MultiheadAttention with identity connection,\n    and positional encoding  is also passed as input.\n    Args:\n        embed_dims (int): The embedding dimension.\n        num_heads (int): Parallel attention heads.\n        attn_drop (float): A Dropout layer on attn_output_weights.\n            Default: 0.0.\n        proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.\n            Default: 0.0.\n        dropout_layer (obj:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): When it is True,  Key, Query and Value are shape of\n            (batch, n, embed_dim), otherwise (n, batch, embed_dim).\n             Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims,\n                 num_heads,\n                 attn_drop=0.,\n                 proj_drop=0.,\n                 group=1,\n                 dropout_layer=dict(type='Dropout', drop_prob=0.),\n                 init_cfg=None,\n                 batch_first=False,\n                 **kwargs):\n        super().__init__(init_cfg)\n        if 'dropout' in kwargs:\n            warnings.warn(\n                'The arguments `dropout` in MultiheadAttention '\n                'has been deprecated, now you can separately '\n                'set `attn_drop`(float), proj_drop(float), '\n                'and `dropout_layer`(dict) ', DeprecationWarning)\n            attn_drop = kwargs['dropout']\n            dropout_layer['drop_prob'] = kwargs.pop('dropout')\n\n        self.embed_dims = embed_dims\n        self.num_heads = num_heads\n        self.group = group\n        self.batch_first = batch_first\n\n        self.attn = nn.MultiheadAttention(embed_dims, num_heads, attn_drop, **kwargs)\n\n        self.proj_drop = nn.Dropout(proj_drop)\n        self.dropout_layer = build_dropout(dropout_layer) if dropout_layer else nn.Identity()\n\n    @deprecated_api_warning({'residual': 'identity'}, cls_name='MultiheadAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_pos=None,\n                attn_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `MultiheadAttention`.\n        **kwargs allow passing a more general data flow when combining\n        with other operations in `transformerlayer`.\n        Args:\n            query (Tensor): The input query with shape [num_queries, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n                If None, the ``query`` will be used. Defaults to None.\n            value (Tensor): The value tensor with same shape as `key`.\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n                If None, the `key` will be used.\n            identity (Tensor): This tensor, with the same shape as x,\n                will be used for the identity link.\n                If None, `x` will be used. Defaults to None.\n            query_pos (Tensor): The positional encoding for query, with\n                the same shape as `x`. If not None, it will\n                be added to `x` before forward function. Defaults to None.\n            key_pos (Tensor): The positional encoding for `key`, with the\n                same shape as `key`. Defaults to None. If not None, it will\n                be added to `key` before forward function. If None, and\n                `query_pos` has the same shape as `key`, then `query_pos`\n                will be used for `key_pos`. Defaults to None.\n            attn_mask (Tensor): ByteTensor mask with shape [num_queries,\n                num_keys]. Same in `nn.MultiheadAttention.forward`.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].\n                Defaults to None.\n        Returns:\n            Tensor: forwarded results with shape\n            [num_queries, bs, embed_dims]\n            if self.batch_first is False, else\n            [bs, num_queries embed_dims].\n        \"\"\"\n\n        if key is None:\n            key = query\n        if value is None:\n            value = key\n        if identity is None:\n            identity = query\n        if key_pos is None:\n            if query_pos is not None:\n                # use query_pos if key_pos is not available\n                if query_pos.shape == key.shape:\n                    key_pos = query_pos\n                else:\n                    warnings.warn(f'position encoding of key is'\n                                  f'missing in {self.__class__.__name__}.')\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n\n        # Because the dataflow('key', 'query', 'value') of\n        # ``torch.nn.MultiheadAttention`` is (num_query, batch,\n        # embed_dims), We should adjust the shape of dataflow from\n        # batch_first (batch, num_query, embed_dims) to num_query_first\n        # (num_query ,batch, embed_dims), and recover ``attn_output``\n        # from num_query_first to batch_first.\n        if self.batch_first:\n            query = query.transpose(0, 1)\n            key = key.transpose(0, 1)\n            value = value.transpose(0, 1)\n\n        num_queries = query.shape[0]\n        bs = query.shape[1]\n        if self.training:\n            query = torch.cat(query.split(num_queries // self.group, dim=0), dim=1)\n            key = torch.cat(key.split(num_queries // self.group, dim=0), dim=1)\n            value = torch.cat(value.split(num_queries // self.group, dim=0), dim=1)\n\n        out = self.attn(query=query, key=key, value=value, attn_mask=attn_mask, key_padding_mask=key_padding_mask)[0]\n\n        if self.training:\n            out = torch.cat(out.split(bs, dim=1), dim=0)  # shape\n\n        if self.batch_first:\n            out = out.transpose(0, 1)\n\n        return identity + self.dropout_layer(self.proj_drop(out))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/multi_scale_deformable_attn_function.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nimport torch\nfrom torch.cuda.amp import custom_bwd, custom_fwd\nfrom torch.autograd.function import Function, once_differentiable\nfrom mmcv.utils import ext_loader\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\n\nclass MultiScaleDeformableAttnFunction_fp16(Function):\n\n    @staticmethod\n    @custom_fwd(cast_inputs=torch.float16)\n    def forward(ctx, value, value_spatial_shapes, value_level_start_index,\n                sampling_locations, attention_weights, im2col_step):\n        \"\"\"GPU version of multi-scale deformable attention.\n\n        Args:\n            value (Tensor): The value has shape\n                (bs, num_keys, mum_heads, embed_dims//num_heads)\n            value_spatial_shapes (Tensor): Spatial shape of\n                each feature map, has shape (num_levels, 2),\n                last dimension 2 represent (h, w)\n            sampling_locations (Tensor): The location of sampling points,\n                has shape\n                (bs ,num_queries, num_heads, num_levels, num_points, 2),\n                the last dimension 2 represent (x, y).\n            attention_weights (Tensor): The weight of sampling points used\n                when calculate the attention, has shape\n                (bs ,num_queries, num_heads, num_levels, num_points),\n            im2col_step (Tensor): The step used in image to column.\n\n        Returns:\n            Tensor: has shape (bs, num_queries, embed_dims)\n        \"\"\"\n        ctx.im2col_step = im2col_step\n        output = ext_module.ms_deform_attn_forward(\n            value,\n            value_spatial_shapes,\n            value_level_start_index,\n            sampling_locations,\n            attention_weights,\n            im2col_step=ctx.im2col_step)\n        ctx.save_for_backward(value, value_spatial_shapes,\n                              value_level_start_index, sampling_locations,\n                              attention_weights)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    @custom_bwd\n    def backward(ctx, grad_output):\n        \"\"\"GPU version of backward function.\n\n        Args:\n            grad_output (Tensor): Gradient\n                of output tensor of forward.\n\n        Returns:\n             Tuple[Tensor]: Gradient\n                of input tensors in forward.\n        \"\"\"\n        value, value_spatial_shapes, value_level_start_index, \\\n            sampling_locations, attention_weights = ctx.saved_tensors\n        grad_value = torch.zeros_like(value)\n        grad_sampling_loc = torch.zeros_like(sampling_locations)\n        grad_attn_weight = torch.zeros_like(attention_weights)\n\n        ext_module.ms_deform_attn_backward(\n            value,\n            value_spatial_shapes,\n            value_level_start_index,\n            sampling_locations,\n            attention_weights,\n            grad_output.contiguous(),\n            grad_value,\n            grad_sampling_loc,\n            grad_attn_weight,\n            im2col_step=ctx.im2col_step)\n\n        return grad_value, None, None, \\\n            grad_sampling_loc, grad_attn_weight, None\n\n\nclass MultiScaleDeformableAttnFunction_fp32(Function):\n\n    @staticmethod\n    @custom_fwd(cast_inputs=torch.float32)\n    def forward(ctx, value, value_spatial_shapes, value_level_start_index,\n                sampling_locations, attention_weights, im2col_step):\n        \"\"\"GPU version of multi-scale deformable attention.\n\n        Args:\n            value (Tensor): The value has shape\n                (bs, num_keys, mum_heads, embed_dims//num_heads)\n            value_spatial_shapes (Tensor): Spatial shape of\n                each feature map, has shape (num_levels, 2),\n                last dimension 2 represent (h, w)\n            sampling_locations (Tensor): The location of sampling points,\n                has shape\n                (bs ,num_queries, num_heads, num_levels, num_points, 2),\n                the last dimension 2 represent (x, y).\n            attention_weights (Tensor): The weight of sampling points used\n                when calculate the attention, has shape\n                (bs ,num_queries, num_heads, num_levels, num_points),\n            im2col_step (Tensor): The step used in image to column.\n\n        Returns:\n            Tensor: has shape (bs, num_queries, embed_dims)\n        \"\"\"\n\n        ctx.im2col_step = im2col_step\n        output = ext_module.ms_deform_attn_forward(\n            value,\n            value_spatial_shapes,\n            value_level_start_index,\n            sampling_locations,\n            attention_weights,\n            im2col_step=ctx.im2col_step)\n        ctx.save_for_backward(value, value_spatial_shapes,\n                              value_level_start_index, sampling_locations,\n                              attention_weights)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    @custom_bwd\n    def backward(ctx, grad_output):\n        \"\"\"GPU version of backward function.\n\n        Args:\n            grad_output (Tensor): Gradient\n                of output tensor of forward.\n\n        Returns:\n             Tuple[Tensor]: Gradient\n                of input tensors in forward.\n        \"\"\"\n        value, value_spatial_shapes, value_level_start_index, \\\n            sampling_locations, attention_weights = ctx.saved_tensors\n        grad_value = torch.zeros_like(value)\n        grad_sampling_loc = torch.zeros_like(sampling_locations)\n        grad_attn_weight = torch.zeros_like(attention_weights)\n\n        ext_module.ms_deform_attn_backward(\n            value,\n            value_spatial_shapes,\n            value_level_start_index,\n            sampling_locations,\n            attention_weights,\n            grad_output.contiguous(),\n            grad_value,\n            grad_sampling_loc,\n            grad_attn_weight,\n            im2col_step=ctx.im2col_step)\n\n        return grad_value, None, None, \\\n            grad_sampling_loc, grad_attn_weight, None\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/spatial_cross_attention.py",
    "content": "\n# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom mmcv.ops.multi_scale_deform_attn import multi_scale_deformable_attn_pytorch\nimport warnings\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.utils import xavier_init, constant_init\nfrom mmcv.models.bricks.registry import (ATTENTION,\n                                      TRANSFORMER_LAYER,\n                                      TRANSFORMER_LAYER_SEQUENCE)\nfrom mmcv.models.bricks.transformer import build_attention\nimport math\nfrom mmcv.utils import force_fp32, auto_fp16\n\nfrom mmcv.models.backbones.base_module import BaseModule, ModuleList, Sequential\n\nfrom mmcv.utils import ext_loader\nfrom .multi_scale_deformable_attn_function import MultiScaleDeformableAttnFunction_fp32, \\\n    MultiScaleDeformableAttnFunction_fp16\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\n\n@ATTENTION.register_module()\nclass SpatialCrossAttention(BaseModule):\n    \"\"\"An attention module used in BEVFormer.\n    Args:\n        embed_dims (int): The embedding dimension of Attention.\n            Default: 256.\n        num_cams (int): The number of cameras\n        dropout (float): A Dropout layer on `inp_residual`.\n            Default: 0..\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        deformable_attention: (dict): The config for the deformable attention used in SCA.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims=256,\n                 num_cams=6,\n                 pc_range=None,\n                 dropout=0.1,\n                 init_cfg=None,\n                 batch_first=False,\n                 deformable_attention=dict(\n                     type='MSDeformableAttention3D',\n                     embed_dims=256,\n                     num_levels=4),\n                 **kwargs\n                 ):\n        super(SpatialCrossAttention, self).__init__(init_cfg)\n\n        self.init_cfg = init_cfg\n        self.dropout = nn.Dropout(dropout)\n        self.pc_range = pc_range\n        self.fp16_enabled = False\n        self.deformable_attention = build_attention(deformable_attention)\n        self.embed_dims = embed_dims\n        self.num_cams = num_cams\n        self.output_proj = nn.Linear(embed_dims, embed_dims)\n        self.batch_first = batch_first\n        self.init_weight()\n\n    def init_weight(self):\n        \"\"\"Default initialization for Parameters of Module.\"\"\"\n        xavier_init(self.output_proj, distribution='uniform', bias=0.)\n    \n    @force_fp32(apply_to=('query', 'key', 'value', 'query_pos', 'reference_points_cam'))\n    def forward(self,\n                query,\n                key,\n                value,\n                residual=None,\n                query_pos=None,\n                key_padding_mask=None,\n                reference_points=None,\n                spatial_shapes=None,\n                reference_points_cam=None,\n                bev_mask=None,\n                level_start_index=None,\n                flag='encoder',\n                **kwargs):\n        \"\"\"Forward Function of Detr3DCrossAtten.\n        Args:\n            query (Tensor): Query of Transformer with shape\n                (num_query, bs, embed_dims).\n            key (Tensor): The key tensor with shape\n                `(num_key, bs, embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(num_key, bs, embed_dims)`. (B, N, C, H, W)\n            residual (Tensor): The tensor used for addition, with the\n                same shape as `x`. Default None. If None, `x` will be used.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for  `key`. Default\n                None.\n            reference_points (Tensor):  The normalized reference\n                points with shape (bs, num_query, 4),\n                all elements is range in [0, 1], top-left (0,0),\n                bottom-right (1, 1), including padding area.\n                or (N, Length_{query}, num_levels, 4), add\n                additional two dimensions is (w, h) to\n                form reference boxes.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_key].\n            spatial_shapes (Tensor): Spatial shape of features in\n                different level. With shape  (num_levels, 2),\n                last dimension represent (h, w).\n            level_start_index (Tensor): The start index of each level.\n                A tensor has shape (num_levels) and can be represented\n                as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...].\n        Returns:\n             Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n\n        if key is None:\n            key = query\n        if value is None:\n            value = key\n\n        if residual is None:\n            inp_residual = query\n            slots = torch.zeros_like(query)\n        if query_pos is not None:\n            query = query + query_pos\n\n        bs, num_query, _ = query.size()\n\n        D = reference_points_cam.size(3)\n        indexes = []\n        for i, mask_per_img in enumerate(bev_mask):\n            index_query_per_img = mask_per_img[0].sum(-1).nonzero().squeeze(-1)\n            indexes.append(index_query_per_img)\n        max_len = max([len(each) for each in indexes])\n\n        # each camera only interacts with its corresponding BEV queries. This step can  greatly save GPU memory.\n        queries_rebatch = query.new_zeros(\n            [bs, self.num_cams, max_len, self.embed_dims])\n        reference_points_rebatch = reference_points_cam.new_zeros(\n            [bs, self.num_cams, max_len, D, 2])\n        \n        for j in range(bs):\n            for i, reference_points_per_img in enumerate(reference_points_cam):   \n                index_query_per_img = indexes[i]\n                queries_rebatch[j, i, :len(index_query_per_img)] = query[j, index_query_per_img]\n                reference_points_rebatch[j, i, :len(index_query_per_img)] = reference_points_per_img[j, index_query_per_img]\n\n        num_cams, l, bs, embed_dims = key.shape\n\n        key = key.permute(2, 0, 1, 3).reshape(\n            bs * self.num_cams, l, self.embed_dims)\n        value = value.permute(2, 0, 1, 3).reshape(\n            bs * self.num_cams, l, self.embed_dims)\n\n        queries = self.deformable_attention(query=queries_rebatch.view(bs*self.num_cams, max_len, self.embed_dims), key=key, value=value,\n                                            reference_points=reference_points_rebatch.view(bs*self.num_cams, max_len, D, 2), spatial_shapes=spatial_shapes,\n                                            level_start_index=level_start_index).view(bs, self.num_cams, max_len, self.embed_dims)\n        for j in range(bs):\n            for i, index_query_per_img in enumerate(indexes):\n                slots[j, index_query_per_img] += queries[j, i, :len(index_query_per_img)]\n\n        count = bev_mask.sum(-1) > 0\n        count = count.permute(1, 2, 0).sum(-1)\n        count = torch.clamp(count, min=1.0)\n        slots = slots / count[..., None]\n        slots = self.output_proj(slots)\n\n        return self.dropout(slots) + inp_residual\n\n\n@ATTENTION.register_module()\nclass MSDeformableAttention3D(BaseModule):\n    \"\"\"An attention module used in BEVFormer based on Deformable-Detr.\n    `Deformable DETR: Deformable Transformers for End-to-End Object Detection.\n    <https://arxiv.org/pdf/2010.04159.pdf>`_.\n    Args:\n        embed_dims (int): The embedding dimension of Attention.\n            Default: 256.\n        num_heads (int): Parallel attention heads. Default: 64.\n        num_levels (int): The number of feature map used in\n            Attention. Default: 4.\n        num_points (int): The number of sampling points for\n            each query in each head. Default: 4.\n        im2col_step (int): The step used in image_to_column.\n            Default: 64.\n        dropout (float): A Dropout layer on `inp_identity`.\n            Default: 0.1.\n        batch_first (bool): Key, Query and Value are shape of\n            (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: None.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 num_levels=4,\n                 num_points=8,\n                 im2col_step=64,\n                 dropout=0.1,\n                 batch_first=True,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n        if embed_dims % num_heads != 0:\n            raise ValueError(f'embed_dims must be divisible by num_heads, '\n                             f'but got {embed_dims} and {num_heads}')\n        dim_per_head = embed_dims // num_heads\n        self.norm_cfg = norm_cfg\n        self.batch_first = batch_first\n        self.output_proj = None\n        self.fp16_enabled = False\n\n        # you'd better set dim_per_head to a power of 2\n        # which is more efficient in the CUDA implementation\n        def _is_power_of_2(n):\n            if (not isinstance(n, int)) or (n < 0):\n                raise ValueError(\n                    'invalid input for _is_power_of_2: {} (type: {})'.format(\n                        n, type(n)))\n            return (n & (n - 1) == 0) and n != 0\n\n        if not _is_power_of_2(dim_per_head):\n            warnings.warn(\n                \"You'd better set embed_dims in \"\n                'MultiScaleDeformAttention to make '\n                'the dimension of each attention head a power of 2 '\n                'which is more efficient in our CUDA implementation.')\n\n        self.im2col_step = im2col_step\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_heads = num_heads\n        self.num_points = num_points\n        self.sampling_offsets = nn.Linear(\n            embed_dims, num_heads * num_levels * num_points * 2)\n        self.attention_weights = nn.Linear(embed_dims,\n                                           num_heads * num_levels * num_points)\n        self.value_proj = nn.Linear(embed_dims, embed_dims)\n\n        self.init_weights()\n\n    def init_weights(self):\n        \"\"\"Default initialization for Parameters of Module.\"\"\"\n        constant_init(self.sampling_offsets, 0.)\n        thetas = torch.arange(\n            self.num_heads,\n            dtype=torch.float32) * (2.0 * math.pi / self.num_heads)\n        grid_init = torch.stack([thetas.cos(), thetas.sin()], -1)\n        grid_init = (grid_init /\n                     grid_init.abs().max(-1, keepdim=True)[0]).view(\n            self.num_heads, 1, 1,\n            2).repeat(1, self.num_levels, self.num_points, 1)\n        for i in range(self.num_points):\n            grid_init[:, :, i, :] *= i + 1\n\n        self.sampling_offsets.bias.data = grid_init.view(-1)\n        constant_init(self.attention_weights, val=0., bias=0.)\n        xavier_init(self.value_proj, distribution='uniform', bias=0.)\n        xavier_init(self.output_proj, distribution='uniform', bias=0.)\n        self._is_init = True\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_padding_mask=None,\n                reference_points=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                **kwargs):\n        \"\"\"Forward Function of MultiScaleDeformAttention.\n        Args:\n            query (Tensor): Query of Transformer with shape\n                ( bs, num_query, embed_dims).\n            key (Tensor): The key tensor with shape\n                `(bs, num_key,  embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(bs, num_key,  embed_dims)`.\n            identity (Tensor): The tensor used for addition, with the\n                same shape as `query`. Default None. If None,\n                `query` will be used.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`. Default\n                None.\n            reference_points (Tensor):  The normalized reference\n                points with shape (bs, num_query, num_levels, 2),\n                all elements is range in [0, 1], top-left (0,0),\n                bottom-right (1, 1), including padding area.\n                or (N, Length_{query}, num_levels, 4), add\n                additional two dimensions is (w, h) to\n                form reference boxes.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_key].\n            spatial_shapes (Tensor): Spatial shape of features in\n                different levels. With shape (num_levels, 2),\n                last dimension represents (h, w).\n            level_start_index (Tensor): The start index of each level.\n                A tensor has shape ``(num_levels, )`` and can be represented\n                as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...].\n        Returns:\n             Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n\n        if value is None:\n            value = query\n        if identity is None:\n            identity = query\n        if query_pos is not None:\n            query = query + query_pos\n\n        if not self.batch_first:\n            # change to (bs, num_query ,embed_dims)\n            query = query.permute(1, 0, 2)\n            value = value.permute(1, 0, 2)\n\n        bs, num_query, _ = query.shape\n        bs, num_value, _ = value.shape\n        assert (spatial_shapes[:, 0] * spatial_shapes[:, 1]).sum() == num_value\n\n        value = self.value_proj(value)\n        if key_padding_mask is not None:\n            value = value.masked_fill(key_padding_mask[..., None], 0.0)\n        value = value.view(bs, num_value, self.num_heads, -1)\n        sampling_offsets = self.sampling_offsets(query).view(\n            bs, num_query, self.num_heads, self.num_levels, self.num_points, 2)\n        attention_weights = self.attention_weights(query).view(\n            bs, num_query, self.num_heads, self.num_levels * self.num_points)\n\n        attention_weights = attention_weights.softmax(-1)\n\n        attention_weights = attention_weights.view(bs, num_query,\n                                                   self.num_heads,\n                                                   self.num_levels,\n                                                   self.num_points)\n\n        if reference_points.shape[-1] == 2:\n            \"\"\"\n            For each BEV query, it owns `num_Z_anchors` in 3D space that having different heights.\n            After proejcting, each BEV query has `num_Z_anchors` reference points in each 2D image.\n            For each referent point, we sample `num_points` sampling points.\n            For `num_Z_anchors` reference points,  it has overall `num_points * num_Z_anchors` sampling points.\n            \"\"\"\n            offset_normalizer = torch.stack(\n                [spatial_shapes[..., 1], spatial_shapes[..., 0]], -1)\n\n            bs, num_query, num_Z_anchors, xy = reference_points.shape\n            reference_points = reference_points[:, :, None, None, None, :, :]\n            sampling_offsets = sampling_offsets / \\\n                offset_normalizer[None, None, None, :, None, :]\n            bs, num_query, num_heads, num_levels, num_all_points, xy = sampling_offsets.shape\n            sampling_offsets = sampling_offsets.view(\n                bs, num_query, num_heads, num_levels, num_all_points // num_Z_anchors, num_Z_anchors, xy)\n            sampling_locations = reference_points + sampling_offsets\n            bs, num_query, num_heads, num_levels, num_points, num_Z_anchors, xy = sampling_locations.shape\n            assert num_all_points == num_points * num_Z_anchors\n\n            sampling_locations = sampling_locations.view(\n                bs, num_query, num_heads, num_levels, num_all_points, xy)\n\n        elif reference_points.shape[-1] == 4:\n            assert False\n        else:\n            raise ValueError(\n                f'Last dim of reference_points must be'\n                f' 2 or 4, but get {reference_points.shape[-1]} instead.')\n\n        #  sampling_locations.shape: bs, num_query, num_heads, num_levels, num_all_points, 2\n        #  attention_weights.shape: bs, num_query, num_heads, num_levels, num_all_points\n        #\n\n        if torch.cuda.is_available() and value.is_cuda:\n            if value.dtype == torch.float16:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            else:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            output = MultiScaleDeformableAttnFunction.apply(\n                value, spatial_shapes, level_start_index, sampling_locations,\n                attention_weights, self.im2col_step)\n        else:\n            output = multi_scale_deformable_attn_pytorch(\n                value, spatial_shapes, sampling_locations, attention_weights)\n        if not self.batch_first:\n            output = output.permute(1, 0, 2)\n\n        return output\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/temporal_self_attention.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom .multi_scale_deformable_attn_function import MultiScaleDeformableAttnFunction_fp32\nfrom mmcv.ops.multi_scale_deform_attn import multi_scale_deformable_attn_pytorch\nimport warnings\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.utils import xavier_init, constant_init\nfrom mmcv.models.bricks.registry import ATTENTION\nimport math\nfrom mmcv.models.backbones.base_module import BaseModule, ModuleList, Sequential\nfrom mmcv.utils import (ConfigDict, build_from_cfg, deprecated_api_warning,\n                        to_2tuple)\n\nfrom mmcv.utils import ext_loader\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\n\n@ATTENTION.register_module()\nclass TemporalSelfAttention(BaseModule):\n    \"\"\"An attention module used in BEVFormer based on Deformable-Detr.\n\n    `Deformable DETR: Deformable Transformers for End-to-End Object Detection.\n    <https://arxiv.org/pdf/2010.04159.pdf>`_.\n\n    Args:\n        embed_dims (int): The embedding dimension of Attention.\n            Default: 256.\n        num_heads (int): Parallel attention heads. Default: 64.\n        num_levels (int): The number of feature map used in\n            Attention. Default: 4.\n        num_points (int): The number of sampling points for\n            each query in each head. Default: 4.\n        im2col_step (int): The step used in image_to_column.\n            Default: 64.\n        dropout (float): A Dropout layer on `inp_identity`.\n            Default: 0.1.\n        batch_first (bool): Key, Query and Value are shape of\n            (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to True.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: None.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        num_bev_queue (int): In this version, we only use one history BEV and one currenct BEV.\n         the length of BEV queue is 2.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 num_levels=4,\n                 num_points=4,\n                 num_bev_queue=2,\n                 im2col_step=64,\n                 dropout=0.1,\n                 batch_first=True,\n                 norm_cfg=None,\n                 init_cfg=None):\n\n        super().__init__(init_cfg)\n        if embed_dims % num_heads != 0:\n            raise ValueError(f'embed_dims must be divisible by num_heads, '\n                             f'but got {embed_dims} and {num_heads}')\n        dim_per_head = embed_dims // num_heads\n        self.norm_cfg = norm_cfg\n        self.dropout = nn.Dropout(dropout)\n        self.batch_first = batch_first\n        self.fp16_enabled = False\n\n        # you'd better set dim_per_head to a power of 2\n        # which is more efficient in the CUDA implementation\n        def _is_power_of_2(n):\n            if (not isinstance(n, int)) or (n < 0):\n                raise ValueError(\n                    'invalid input for _is_power_of_2: {} (type: {})'.format(\n                        n, type(n)))\n            return (n & (n - 1) == 0) and n != 0\n\n        if not _is_power_of_2(dim_per_head):\n            warnings.warn(\n                \"You'd better set embed_dims in \"\n                'MultiScaleDeformAttention to make '\n                'the dimension of each attention head a power of 2 '\n                'which is more efficient in our CUDA implementation.')\n\n        self.im2col_step = im2col_step\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_heads = num_heads\n        self.num_points = num_points\n        self.num_bev_queue = num_bev_queue\n        self.sampling_offsets = nn.Linear(\n            embed_dims*self.num_bev_queue, num_bev_queue*num_heads * num_levels * num_points * 2)\n        self.attention_weights = nn.Linear(embed_dims*self.num_bev_queue,\n                                           num_bev_queue*num_heads * num_levels * num_points)\n        self.value_proj = nn.Linear(embed_dims, embed_dims)\n        self.output_proj = nn.Linear(embed_dims, embed_dims)\n        self.init_weights()\n\n    def init_weights(self):\n        \"\"\"Default initialization for Parameters of Module.\"\"\"\n        constant_init(self.sampling_offsets, 0.)\n        thetas = torch.arange(\n            self.num_heads,\n            dtype=torch.float32) * (2.0 * math.pi / self.num_heads)\n        grid_init = torch.stack([thetas.cos(), thetas.sin()], -1)\n        grid_init = (grid_init /\n                     grid_init.abs().max(-1, keepdim=True)[0]).view(\n            self.num_heads, 1, 1,\n            2).repeat(1, self.num_levels*self.num_bev_queue, self.num_points, 1)\n\n        for i in range(self.num_points):\n            grid_init[:, :, i, :] *= i + 1\n\n        self.sampling_offsets.bias.data = grid_init.view(-1)\n        constant_init(self.attention_weights, val=0., bias=0.)\n        xavier_init(self.value_proj, distribution='uniform', bias=0.)\n        xavier_init(self.output_proj, distribution='uniform', bias=0.)\n        self._is_init = True\n\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_padding_mask=None,\n                reference_points=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                flag='decoder',\n\n                **kwargs):\n        \"\"\"Forward Function of MultiScaleDeformAttention.\n\n        Args:\n            query (Tensor): Query of Transformer with shape\n                (num_query, bs, embed_dims).\n            key (Tensor): The key tensor with shape\n                `(num_key, bs, embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(num_key, bs, embed_dims)`.\n            identity (Tensor): The tensor used for addition, with the\n                same shape as `query`. Default None. If None,\n                `query` will be used.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`. Default\n                None.\n            reference_points (Tensor):  The normalized reference\n                points with shape (bs, num_query, num_levels, 2),\n                all elements is range in [0, 1], top-left (0,0),\n                bottom-right (1, 1), including padding area.\n                or (N, Length_{query}, num_levels, 4), add\n                additional two dimensions is (w, h) to\n                form reference boxes.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_key].\n            spatial_shapes (Tensor): Spatial shape of features in\n                different levels. With shape (num_levels, 2),\n                last dimension represents (h, w).\n            level_start_index (Tensor): The start index of each level.\n                A tensor has shape ``(num_levels, )`` and can be represented\n                as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...].\n\n        Returns:\n             Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n\n        if value is None:\n            assert self.batch_first\n            bs, len_bev, c = query.shape\n            value = torch.stack([query, query], 1).reshape(bs*2, len_bev, c)\n\n        if identity is None:\n            identity = query\n        if query_pos is not None:\n            query = query + query_pos\n        if not self.batch_first:\n            # change to (bs, num_query ,embed_dims)\n            query = query.permute(1, 0, 2)\n            value = value.permute(1, 0, 2)\n        bs,  num_query, embed_dims = query.shape\n        _, num_value, _ = value.shape\n        assert (spatial_shapes[:, 0] * spatial_shapes[:, 1]).sum() == num_value\n        assert self.num_bev_queue == 2\n\n        query = torch.cat([value[:bs], query], -1)\n        value = self.value_proj(value)\n\n        if key_padding_mask is not None:\n            value = value.masked_fill(key_padding_mask[..., None], 0.0)\n\n        value = value.reshape(bs*self.num_bev_queue,\n                              num_value, self.num_heads, -1)\n\n        sampling_offsets = self.sampling_offsets(query)\n        sampling_offsets = sampling_offsets.view(\n            bs, num_query, self.num_heads,  self.num_bev_queue, self.num_levels, self.num_points, 2)\n        attention_weights = self.attention_weights(query).view(\n            bs, num_query,  self.num_heads, self.num_bev_queue, self.num_levels * self.num_points)\n        attention_weights = attention_weights.softmax(-1)\n\n        attention_weights = attention_weights.view(bs, num_query,\n                                                   self.num_heads,\n                                                   self.num_bev_queue,\n                                                   self.num_levels,\n                                                   self.num_points)\n\n        attention_weights = attention_weights.permute(0, 3, 1, 2, 4, 5)\\\n            .reshape(bs*self.num_bev_queue, num_query, self.num_heads, self.num_levels, self.num_points).contiguous()\n        sampling_offsets = sampling_offsets.permute(0, 3, 1, 2, 4, 5, 6)\\\n            .reshape(bs*self.num_bev_queue, num_query, self.num_heads, self.num_levels, self.num_points, 2)\n\n        if reference_points.shape[-1] == 2:\n            offset_normalizer = torch.stack(\n                [spatial_shapes[..., 1], spatial_shapes[..., 0]], -1)\n            sampling_locations = reference_points[:, :, None, :, None, :] \\\n                + sampling_offsets \\\n                / offset_normalizer[None, None, None, :, None, :]\n\n        elif reference_points.shape[-1] == 4:\n            sampling_locations = reference_points[:, :, None, :, None, :2] \\\n                + sampling_offsets / self.num_points \\\n                * reference_points[:, :, None, :, None, 2:] \\\n                * 0.5\n        else:\n            raise ValueError(\n                f'Last dim of reference_points must be'\n                f' 2 or 4, but get {reference_points.shape[-1]} instead.')\n        if torch.cuda.is_available() and value.is_cuda:\n\n            # using fp16 deformable attention is unstable because it performs many sum operations\n            if value.dtype == torch.float16:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            else:\n                MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32\n            output = MultiScaleDeformableAttnFunction.apply(\n                value, spatial_shapes, level_start_index, sampling_locations,\n                attention_weights, self.im2col_step)\n        else:\n\n            output = multi_scale_deformable_attn_pytorch(\n                value, spatial_shapes, sampling_locations, attention_weights)\n\n        # output shape (bs*num_bev_queue, num_query, embed_dims)\n        # (bs*num_bev_queue, num_query, embed_dims)-> (num_query, embed_dims, bs*num_bev_queue)\n        output = output.permute(1, 2, 0)\n\n        # fuse history value and current value\n        # (num_query, embed_dims, bs*num_bev_queue)-> (num_query, embed_dims, bs, num_bev_queue)\n        output = output.view(num_query, embed_dims, bs, self.num_bev_queue)\n        output = output.mean(-1)\n\n        # (num_query, embed_dims, bs)-> (bs, num_query, embed_dims)\n        output = output.permute(2, 0, 1)\n\n        output = self.output_proj(output)\n\n        if not self.batch_first:\n            output = output.permute(1, 0, 2)\n\n        return self.dropout(output) + identity\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/transformer.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.utils import xavier_init\nfrom mmcv.models.bricks.transformer import build_transformer_layer_sequence\nfrom mmcv.models.backbones.base_module import BaseModule\n\nfrom mmcv.models.utils.builder import TRANSFORMER\nfrom torch.nn.init import normal_\nfrom torchvision.transforms.functional import rotate\nfrom .temporal_self_attention import TemporalSelfAttention\nfrom .spatial_cross_attention import MSDeformableAttention3D\nfrom .decoder import CustomMSDeformableAttention\nfrom mmcv.utils import force_fp32, auto_fp16\nfrom mmcv.models.bricks.registry import ATTENTION\nfrom mmcv.models.bricks.transformer import POSITIONAL_ENCODING, MultiheadAttention\n\n@TRANSFORMER.register_module()\nclass UniADPerceptionTransformer(BaseModule):\n    \"\"\"Implements the Detr3D transformer.\n    Args:\n        as_two_stage (bool): Generate query from encoder features.\n            Default: False.\n        num_feature_levels (int): Number of feature maps from FPN:\n            Default: 4.\n        two_stage_num_proposals (int): Number of proposals when set\n            `as_two_stage` as True. Default: 300.\n    \"\"\"\n\n    def __init__(self,\n                 num_feature_levels=4,\n                 num_cams=6,\n                 two_stage_num_proposals=300,\n                 encoder=None,\n                 decoder=None,\n                 embed_dims=256,\n                 rotate_prev_bev=True,\n                 use_shift=True,\n                 use_can_bus=True,\n                 can_bus_norm=True,\n                 use_cams_embeds=True,\n                 rotate_center=[100, 100],\n                 **kwargs):\n        super(UniADPerceptionTransformer, self).__init__(**kwargs)\n        self.encoder = build_transformer_layer_sequence(encoder)\n        self.decoder = build_transformer_layer_sequence(decoder)\n        self.embed_dims = embed_dims\n        self.num_feature_levels = num_feature_levels\n        self.num_cams = num_cams\n        self.fp16_enabled = False\n\n        self.rotate_prev_bev = rotate_prev_bev\n        self.use_shift = use_shift\n        self.use_can_bus = use_can_bus\n        self.can_bus_norm = can_bus_norm\n        self.use_cams_embeds = use_cams_embeds\n\n        self.two_stage_num_proposals = two_stage_num_proposals\n        self.init_layers()\n        self.rotate_center = rotate_center\n\n    def init_layers(self):\n        \"\"\"Initialize layers of the Detr3DTransformer.\"\"\"\n        self.level_embeds = nn.Parameter(torch.Tensor(\n            self.num_feature_levels, self.embed_dims))\n        self.cams_embeds = nn.Parameter(\n            torch.Tensor(self.num_cams, self.embed_dims))\n        self.can_bus_mlp = nn.Sequential(\n            nn.Linear(18, self.embed_dims // 2),\n            nn.ReLU(inplace=True),\n            nn.Linear(self.embed_dims // 2, self.embed_dims),\n            nn.ReLU(inplace=True),\n        )\n        if self.can_bus_norm:\n            self.can_bus_mlp.add_module('norm', nn.LayerNorm(self.embed_dims))\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MSDeformableAttention3D) or isinstance(m, TemporalSelfAttention) \\\n                    or isinstance(m, CustomMSDeformableAttention):\n                try:\n                    m.init_weight()\n                except AttributeError:\n                    m.init_weights()\n        normal_(self.level_embeds)\n        normal_(self.cams_embeds)\n        xavier_init(self.can_bus_mlp, distribution='uniform', bias=0.)\n\n    @auto_fp16(apply_to=('mlvl_feats', 'bev_queries', 'prev_bev', 'bev_pos'))\n    def get_bev_features(\n            self,\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=[0.512, 0.512],\n            bev_pos=None,\n            prev_bev=None,\n            img_metas=None):\n        \"\"\"\n        obtain bev features.\n        \"\"\"\n\n        bs = mlvl_feats[0].size(0)\n        bev_queries = bev_queries.unsqueeze(1).repeat(1, bs, 1)\n        bev_pos = bev_pos.flatten(2).permute(2, 0, 1)\n        # obtain rotation angle and shift with ego motion\n        delta_x = np.array([each['can_bus'][0]\n                           for each in img_metas])\n        delta_y = np.array([each['can_bus'][1]\n                           for each in img_metas])\n        ego_angle = np.array(\n            [each['can_bus'][-2] / np.pi * 180 for each in img_metas])\n        grid_length_y = grid_length[0]\n        grid_length_x = grid_length[1]\n        translation_length = np.sqrt(delta_x ** 2 + delta_y ** 2)\n        translation_angle = np.arctan2(delta_y, delta_x) / np.pi * 180\n        bev_angle = ego_angle - translation_angle\n        shift_y = translation_length * \\\n            np.cos(bev_angle / 180 * np.pi) / grid_length_y / bev_h\n        shift_x = translation_length * \\\n            np.sin(bev_angle / 180 * np.pi) / grid_length_x / bev_w\n        shift_y = shift_y * self.use_shift\n        shift_x = shift_x * self.use_shift\n        shift = bev_queries.new_tensor(\n            [shift_x, shift_y]).permute(1, 0)  # xy, bs -> bs, xy\n\n        if prev_bev is not None:\n            if prev_bev.shape[1] == bev_h * bev_w:\n                prev_bev = prev_bev.permute(1, 0, 2)\n            if self.rotate_prev_bev:\n                for i in range(bs):\n                    rotation_angle = img_metas[i]['can_bus'][-1]\n                    tmp_prev_bev = prev_bev[:, i].reshape(\n                        bev_h, bev_w, -1).permute(2, 0, 1)\n                    tmp_prev_bev = rotate(tmp_prev_bev, rotation_angle,\n                                          center=self.rotate_center)\n                    tmp_prev_bev = tmp_prev_bev.permute(1, 2, 0).reshape(\n                        bev_h * bev_w, 1, -1)\n                    prev_bev[:, i] = tmp_prev_bev[:, 0]\n\n        # add can bus signals\n        can_bus = bev_queries.new_tensor(\n            [each['can_bus'] for each in img_metas])  # [:, :]\n        can_bus = self.can_bus_mlp(can_bus)[None, :, :]\n        bev_queries = bev_queries + can_bus * self.use_can_bus\n\n        feat_flatten = []\n        spatial_shapes = []\n        for lvl, feat in enumerate(mlvl_feats):\n            bs, num_cam, c, h, w = feat.shape\n            spatial_shape = (h, w)\n            feat = feat.flatten(3).permute(1, 0, 3, 2)\n            if self.use_cams_embeds:\n                feat = feat + self.cams_embeds[:, None, None, :].to(feat.dtype)\n            feat = feat + self.level_embeds[None,\n                                            None, lvl:lvl + 1, :].to(feat.dtype)\n            spatial_shapes.append(spatial_shape)\n            feat_flatten.append(feat)\n\n        feat_flatten = torch.cat(feat_flatten, 2)\n        spatial_shapes = torch.as_tensor(\n            spatial_shapes, dtype=torch.long, device=bev_pos.device)\n        level_start_index = torch.cat((spatial_shapes.new_zeros(\n            (1,)), spatial_shapes.prod(1).cumsum(0)[:-1]))\n\n        feat_flatten = feat_flatten.permute(\n            0, 2, 1, 3)  # (num_cam, H*W, bs, embed_dims)\n\n        bev_embed = self.encoder(\n            bev_queries,\n            feat_flatten,\n            feat_flatten,\n            bev_h=bev_h,\n            bev_w=bev_w,\n            bev_pos=bev_pos,\n            spatial_shapes=spatial_shapes,\n            level_start_index=level_start_index,\n            prev_bev=prev_bev,\n            shift=shift,\n            img_metas=img_metas,\n        )\n\n        return bev_embed\n    \n    def get_states_and_refs(\n        self,\n        bev_embed,\n        object_query_embed,\n        bev_h,\n        bev_w,\n        reference_points,\n        reg_branches=None,\n        cls_branches=None,\n        img_metas=None\n    ):\n        bs = bev_embed.shape[1]\n        query_pos, query = torch.split(\n            object_query_embed, self.embed_dims, dim=1)\n        query_pos = query_pos.unsqueeze(0).expand(bs, -1, -1)\n        query = query.unsqueeze(0).expand(bs, -1, -1)\n\n        reference_points = reference_points.unsqueeze(0).expand(bs, -1, -1)\n        reference_points = reference_points.sigmoid()\n\n        init_reference_out = reference_points\n        query = query.permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        inter_states, inter_references = self.decoder(\n            query=query,\n            key=None,\n            value=bev_embed,\n            query_pos=query_pos,\n            reference_points=reference_points,\n            reg_branches=reg_branches,\n            cls_branches=cls_branches,\n            spatial_shapes=torch.tensor([[bev_h, bev_w]], device=query.device),\n            level_start_index=torch.tensor([0], device=query.device),\n            img_metas=img_metas\n        )\n        inter_references_out = inter_references\n\n        return inter_states, init_reference_out, inter_references_out\n\n\n@ATTENTION.register_module()\nclass GroupFree3DMHA(MultiheadAttention):\n    \"\"\"A warpper for torch.nn.MultiheadAttention for GroupFree3D.\n\n    This module implements MultiheadAttention with identity connection,\n    and positional encoding used in DETR is also passed as input.\n\n    Args:\n        embed_dims (int): The embedding dimension.\n        num_heads (int): Parallel attention heads. Same as\n            `nn.MultiheadAttention`.\n        attn_drop (float): A Dropout layer on attn_output_weights. Default 0.0.\n        proj_drop (float): A Dropout layer. Default 0.0.\n        dropout_layer (obj:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): Key, Query and Value are shape of\n            (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims,\n                 num_heads,\n                 attn_drop=0.,\n                 proj_drop=0.,\n                 dropout_layer=dict(type='DropOut', drop_prob=0.),\n                 init_cfg=None,\n                 batch_first=False,\n                 **kwargs):\n        super().__init__(embed_dims, num_heads, attn_drop, proj_drop,\n                         dropout_layer, init_cfg, batch_first, **kwargs)\n\n    def forward(self,\n                query,\n                key,\n                value,\n                identity,\n                query_pos=None,\n                key_pos=None,\n                attn_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `GroupFree3DMHA`.\n\n        **kwargs allow passing a more general data flow when combining\n        with other operations in `transformerlayer`.\n\n        Args:\n            query (Tensor): The input query with shape [num_queries, bs,\n                embed_dims]. Same in `nn.MultiheadAttention.forward`.\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims]. Same in `nn.MultiheadAttention.forward`.\n                If None, the ``query`` will be used. Defaults to None.\n            value (Tensor): The value tensor with same shape as `key`.\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n                If None, the `key` will be used.\n            identity (Tensor): This tensor, with the same shape as x,\n                will be used for the identity link.\n                If None, `x` will be used. Defaults to None.\n            query_pos (Tensor): The positional encoding for query, with\n                the same shape as `x`. If not None, it will\n                be added to `x` before forward function. Defaults to None.\n            key_pos (Tensor): The positional encoding for `key`, with the\n                same shape as `key`. Defaults to None. If not None, it will\n                be added to `key` before forward function. If None, and\n                `query_pos` has the same shape as `key`, then `query_pos`\n                will be used for `key_pos`. Defaults to None.\n            attn_mask (Tensor): ByteTensor mask with shape [num_queries,\n                num_keys]. Same in `nn.MultiheadAttention.forward`.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n\n        Returns:\n            Tensor: forwarded results with shape [num_queries, bs, embed_dims].\n        \"\"\"\n\n        if hasattr(self, 'operation_name'):\n            if self.operation_name == 'self_attn':\n                value = value + query_pos\n            elif self.operation_name == 'cross_attn':\n                value = value + key_pos\n            else:\n                raise NotImplementedError(\n                    f'{self.__class__.name} '\n                    f\"can't be used as {self.operation_name}\")\n        else:\n            value = value + query_pos\n\n        return super(GroupFree3DMHA, self).forward(\n            query=query,\n            key=key,\n            value=value,\n            identity=identity,\n            query_pos=query_pos,\n            key_pos=key_pos,\n            attn_mask=attn_mask,\n            key_padding_mask=key_padding_mask,\n            **kwargs)\n\n\n@POSITIONAL_ENCODING.register_module()\nclass ConvBNPositionalEncoding(nn.Module):\n    \"\"\"Absolute position embedding with Conv learning.\n\n    Args:\n        input_channel (int): input features dim.\n        num_pos_feats (int): output position features dim.\n            Defaults to 288 to be consistent with seed features dim.\n    \"\"\"\n\n    def __init__(self, input_channel, num_pos_feats=288):\n        super().__init__()\n        self.position_embedding_head = nn.Sequential(\n            nn.Conv1d(input_channel, num_pos_feats, kernel_size=1),\n            nn.BatchNorm1d(num_pos_feats), nn.ReLU(inplace=True),\n            nn.Conv1d(num_pos_feats, num_pos_feats, kernel_size=1))\n\n    def forward(self, xyz):\n        \"\"\"Forward pass.\n\n        Args:\n            xyz (Tensor)： (B, N, 3) the coordinates to embed.\n\n        Returns:\n            Tensor: (B, num_pos_feats, N) the embeded position features.\n        \"\"\"\n        xyz = xyz.permute(0, 2, 1)\n        position_embedding = self.position_embedding_head(xyz)\n        return position_embedding\n\n@TRANSFORMER.register_module()\nclass BEVFormerPerceptionTransformer(BaseModule):\n    \"\"\"Implements the Detr3D transformer.\n    Args:\n        as_two_stage (bool): Generate query from encoder features.\n            Default: False.\n        num_feature_levels (int): Number of feature maps from FPN:\n            Default: 4.\n        two_stage_num_proposals (int): Number of proposals when set\n            `as_two_stage` as True. Default: 300.\n    \"\"\"\n\n    def __init__(self,\n                 num_feature_levels=4,\n                 num_cams=6,\n                 two_stage_num_proposals=300,\n                 encoder=None,\n                 decoder=None,\n                 embed_dims=256,\n                 rotate_prev_bev=True,\n                 use_shift=True,\n                 use_can_bus=True,\n                 can_bus_norm=True,\n                 use_cams_embeds=True,\n                 rotate_center=[100, 100],\n                 **kwargs):\n        super(BEVFormerPerceptionTransformer, self).__init__(**kwargs)\n        self.encoder = build_transformer_layer_sequence(encoder)\n        self.decoder = build_transformer_layer_sequence(decoder)\n        self.embed_dims = embed_dims\n        self.num_feature_levels = num_feature_levels\n        self.num_cams = num_cams\n        self.fp16_enabled = False\n\n        self.rotate_prev_bev = rotate_prev_bev\n        self.use_shift = use_shift\n        self.use_can_bus = use_can_bus\n        self.can_bus_norm = can_bus_norm\n        self.use_cams_embeds = use_cams_embeds\n\n        self.two_stage_num_proposals = two_stage_num_proposals\n        self.init_layers()\n        self.rotate_center = rotate_center\n\n    def init_layers(self):\n        \"\"\"Initialize layers of the Detr3DTransformer.\"\"\"\n        self.level_embeds = nn.Parameter(torch.Tensor(\n            self.num_feature_levels, self.embed_dims))\n        self.cams_embeds = nn.Parameter(\n            torch.Tensor(self.num_cams, self.embed_dims))\n        self.reference_points = nn.Linear(self.embed_dims, 3)\n        self.can_bus_mlp = nn.Sequential(\n            nn.Linear(18, self.embed_dims // 2),\n            nn.ReLU(inplace=True),\n            nn.Linear(self.embed_dims // 2, self.embed_dims),\n            nn.ReLU(inplace=True),\n        )\n        if self.can_bus_norm:\n            self.can_bus_mlp.add_module('norm', nn.LayerNorm(self.embed_dims))\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MSDeformableAttention3D) or isinstance(m, TemporalSelfAttention) \\\n                    or isinstance(m, CustomMSDeformableAttention):\n                try:\n                    m.init_weight()\n                except AttributeError:\n                    m.init_weights()\n        normal_(self.level_embeds)\n        normal_(self.cams_embeds)\n        xavier_init(self.reference_points, distribution='uniform', bias=0.)\n        xavier_init(self.can_bus_mlp, distribution='uniform', bias=0.)\n\n    @auto_fp16(apply_to=('mlvl_feats', 'bev_queries', 'prev_bev', 'bev_pos'))\n    def get_bev_features(\n            self,\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=[0.512, 0.512],\n            bev_pos=None,\n            prev_bev=None,\n            **kwargs):\n        \"\"\"\n        obtain bev features.\n        \"\"\"\n\n        bs = mlvl_feats[0].size(0)\n        bev_queries = bev_queries.unsqueeze(1).repeat(1, bs, 1)\n        bev_pos = bev_pos.flatten(2).permute(2, 0, 1)\n\n        # obtain rotation angle and shift with ego motion\n        delta_x = np.array([each['can_bus'][0]\n                           for each in kwargs['img_metas']])\n        delta_y = np.array([each['can_bus'][1]\n                           for each in kwargs['img_metas']])\n        ego_angle = np.array(\n            [each['can_bus'][-2] / np.pi * 180 for each in kwargs['img_metas']])\n        grid_length_y = grid_length[0]\n        grid_length_x = grid_length[1]\n        translation_length = np.sqrt(delta_x ** 2 + delta_y ** 2)\n        translation_angle = np.arctan2(delta_y, delta_x) / np.pi * 180\n        bev_angle = ego_angle - translation_angle\n        shift_y = translation_length * \\\n            np.cos(bev_angle / 180 * np.pi) / grid_length_y / bev_h\n        shift_x = translation_length * \\\n            np.sin(bev_angle / 180 * np.pi) / grid_length_x / bev_w\n        shift_y = shift_y * self.use_shift\n        shift_x = shift_x * self.use_shift\n        shift = bev_queries.new_tensor(\n            [shift_x, shift_y]).permute(1, 0)  # xy, bs -> bs, xy\n\n        if prev_bev is not None:\n            if prev_bev.shape[1] == bev_h * bev_w:\n                prev_bev = prev_bev.permute(1, 0, 2)\n            if self.rotate_prev_bev:\n                for i in range(bs):\n                    # num_prev_bev = prev_bev.size(1)\n                    rotation_angle = kwargs['img_metas'][i]['can_bus'][-1]\n                    tmp_prev_bev = prev_bev[:, i].reshape(\n                        bev_h, bev_w, -1).permute(2, 0, 1)\n                    tmp_prev_bev = rotate(tmp_prev_bev, rotation_angle,\n                                          center=self.rotate_center)\n                    tmp_prev_bev = tmp_prev_bev.permute(1, 2, 0).reshape(\n                        bev_h * bev_w, 1, -1)\n                    prev_bev[:, i] = tmp_prev_bev[:, 0]\n\n        # add can bus signals\n        can_bus = bev_queries.new_tensor(\n            [each['can_bus'] for each in kwargs['img_metas']])  # [:, :]\n        can_bus = self.can_bus_mlp(can_bus)[None, :, :]\n        bev_queries = bev_queries + can_bus * self.use_can_bus\n\n        feat_flatten = []\n        spatial_shapes = []\n        for lvl, feat in enumerate(mlvl_feats):\n            bs, num_cam, c, h, w = feat.shape\n            spatial_shape = (h, w)\n            feat = feat.flatten(3).permute(1, 0, 3, 2)\n            if self.use_cams_embeds:\n                feat = feat + self.cams_embeds[:, None, None, :].to(feat.dtype)\n            feat = feat + self.level_embeds[None,\n                                            None, lvl:lvl + 1, :].to(feat.dtype)\n            spatial_shapes.append(spatial_shape)\n            feat_flatten.append(feat)\n\n        feat_flatten = torch.cat(feat_flatten, 2)\n        spatial_shapes = torch.as_tensor(\n            spatial_shapes, dtype=torch.long, device=bev_pos.device)\n        level_start_index = torch.cat((spatial_shapes.new_zeros(\n            (1,)), spatial_shapes.prod(1).cumsum(0)[:-1]))\n\n        feat_flatten = feat_flatten.permute(\n            0, 2, 1, 3)  # (num_cam, H*W, bs, embed_dims)\n\n        bev_embed = self.encoder(\n            bev_queries,\n            feat_flatten,\n            feat_flatten,\n            bev_h=bev_h,\n            bev_w=bev_w,\n            bev_pos=bev_pos,\n            spatial_shapes=spatial_shapes,\n            level_start_index=level_start_index,\n            prev_bev=prev_bev,\n            shift=shift,\n            **kwargs\n        )\n\n        return bev_embed\n\n    @auto_fp16(apply_to=('mlvl_feats', 'bev_queries', 'object_query_embed', 'prev_bev', 'bev_pos'))\n    def forward(self,\n                mlvl_feats,\n                bev_queries,\n                object_query_embed,\n                bev_h,\n                bev_w,\n                grid_length=[0.512, 0.512],\n                bev_pos=None,\n                reg_branches=None,\n                cls_branches=None,\n                prev_bev=None,\n                **kwargs):\n        \"\"\"Forward function for `Detr3DTransformer`.\n        Args:\n            mlvl_feats (list(Tensor)): Input queries from\n                different level. Each element has shape\n                [bs, num_cams, embed_dims, h, w].\n            bev_queries (Tensor): (bev_h*bev_w, c)\n            bev_pos (Tensor): (bs, embed_dims, bev_h, bev_w)\n            object_query_embed (Tensor): The query embedding for decoder,\n                with shape [num_query, c].\n            reg_branches (obj:`nn.ModuleList`): Regression heads for\n                feature maps from each decoder layer. Only would\n                be passed when `with_box_refine` is True. Default to None.\n        Returns:\n            tuple[Tensor]: results of decoder containing the following tensor.\n                - bev_embed: BEV features\n                - inter_states: Outputs from decoder. If\n                    return_intermediate_dec is True output has shape \\\n                      (num_dec_layers, bs, num_query, embed_dims), else has \\\n                      shape (1, bs, num_query, embed_dims).\n                - init_reference_out: The initial value of reference \\\n                    points, has shape (bs, num_queries, 4).\n                - inter_references_out: The internal value of reference \\\n                    points in decoder, has shape \\\n                    (num_dec_layers, bs,num_query, embed_dims)\n                - enc_outputs_class: The classification score of \\\n                    proposals generated from \\\n                    encoder's feature maps, has shape \\\n                    (batch, h*w, num_classes). \\\n                    Only would be returned when `as_two_stage` is True, \\\n                    otherwise None.\n                - enc_outputs_coord_unact: The regression results \\\n                    generated from encoder's feature maps., has shape \\\n                    (batch, h*w, 4). Only would \\\n                    be returned when `as_two_stage` is True, \\\n                    otherwise None.\n        \"\"\"\n\n        bev_embed = self.get_bev_features(\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=grid_length,\n            bev_pos=bev_pos,\n            prev_bev=prev_bev,\n            **kwargs)  # bev_embed shape: bs, bev_h*bev_w, embed_dims\n\n        bs = mlvl_feats[0].size(0)\n        query_pos, query = torch.split(\n            object_query_embed, self.embed_dims, dim=1)\n        query_pos = query_pos.unsqueeze(0).expand(bs, -1, -1)\n        query = query.unsqueeze(0).expand(bs, -1, -1)\n        reference_points = self.reference_points(query_pos)\n        reference_points = reference_points.sigmoid()\n        init_reference_out = reference_points\n\n        query = query.permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        bev_embed = bev_embed.permute(1, 0, 2)\n\n        inter_states, inter_references = self.decoder(\n            query=query,\n            key=None,\n            value=bev_embed,\n            query_pos=query_pos,\n            reference_points=reference_points,\n            reg_branches=reg_branches,\n            cls_branches=cls_branches,\n            spatial_shapes=torch.tensor([[bev_h, bev_w]], device=query.device),\n            level_start_index=torch.tensor([0], device=query.device),\n            **kwargs)\n\n        inter_references_out = inter_references\n\n        return bev_embed, inter_states, init_reference_out, inter_references_out\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/transformerV2.py",
    "content": "import torch\nimport torch.nn as nn\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.transformer import build_transformer_layer_sequence\nfrom mmdet.models.utils.builder import TRANSFORMER\nfrom torch.nn.init import normal_\nfrom mmcv.runner.base_module import BaseModule\nfrom .temporal_self_attention import TemporalSelfAttention\nfrom .spatial_cross_attention import MSDeformableAttention3D\nfrom .decoder import CustomMSDeformableAttention\nfrom mmcv.cnn import build_norm_layer, build_conv_layer\nimport torch.utils.checkpoint as checkpoint\nfrom mmdet.models.backbones.resnet import Bottleneck, BasicBlock\n\n\nclass ResNetFusion(BaseModule):\n    def __init__(self, in_channels, out_channels, inter_channels, num_layer, norm_cfg=dict(type='SyncBN'),\n                 with_cp=False):\n        super(ResNetFusion, self).__init__()\n        layers = []\n        self.inter_channels = inter_channels\n        for i in range(num_layer):\n            if i == 0:\n                if inter_channels == in_channels:\n                    layers.append(BasicBlock(in_channels, inter_channels, stride=1, norm_cfg=norm_cfg))\n                else:\n                    downsample = nn.Sequential(\n                        build_conv_layer(None, in_channels, inter_channels, 3, stride=1, padding=1, dilation=1,\n                                         bias=False),\n                        build_norm_layer(norm_cfg, inter_channels)[1])\n                    layers.append(\n                        BasicBlock(in_channels, inter_channels, stride=1, norm_cfg=norm_cfg, downsample=downsample))\n            else:\n                layers.append(BasicBlock(inter_channels, inter_channels, stride=1, norm_cfg=norm_cfg))\n        self.layers = nn.Sequential(*layers)\n        self.layer_norm = nn.Sequential(\n                nn.Linear(inter_channels, out_channels),\n                nn.LayerNorm(out_channels))\n        self.with_cp = with_cp\n\n    def forward(self, x):\n        x = torch.cat(x, 1).contiguous()\n        # x should be [1, in_channels, bev_h, bev_w]\n        for lid, layer in enumerate(self.layers):\n            if self.with_cp and x.requires_grad:\n                x = checkpoint.checkpoint(layer, x)\n            else:\n                x = layer(x)\n        x = x.reshape(x.shape[0], x.shape[1], -1).permute(0, 2, 1)  # nchw -> n(hw)c\n        x = self.layer_norm(x)\n        return x\n\n\n@TRANSFORMER.register_module()\nclass PerceptionTransformerBEVEncoder(BaseModule):\n    def __init__(self,\n                 num_feature_levels=4,\n                 num_cams=6,\n                 two_stage_num_proposals=300,\n                 encoder=None,\n                 embed_dims=256,\n                 use_cams_embeds=True,\n                 rotate_center=[100, 100],\n                 **kwargs):\n        super(PerceptionTransformerBEVEncoder, self).__init__(**kwargs)\n        self.encoder = build_transformer_layer_sequence(encoder)\n        self.embed_dims = embed_dims\n        self.num_feature_levels = num_feature_levels\n        self.num_cams = num_cams\n        self.fp16_enabled = False\n\n        self.use_cams_embeds = use_cams_embeds\n\n        self.two_stage_num_proposals = two_stage_num_proposals\n        self.rotate_center = rotate_center\n        \"\"\"Initialize layers of the Detr3DTransformer.\"\"\"\n        self.level_embeds = nn.Parameter(torch.Tensor(self.num_feature_levels, self.embed_dims))\n        if self.use_cams_embeds:\n            self.cams_embeds = nn.Parameter(torch.Tensor(self.num_cams, self.embed_dims))\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MSDeformableAttention3D) or isinstance(m, TemporalSelfAttention) \\\n                    or isinstance(m, CustomMSDeformableAttention):\n                try:\n                    m.init_weight()\n                except AttributeError:\n                    m.init_weights()\n        normal_(self.level_embeds)\n        if self.use_cams_embeds:\n            normal_(self.cams_embeds)\n\n    def forward(self,\n                mlvl_feats,\n                bev_queries,\n                bev_h,\n                bev_w,\n                grid_length=[0.512, 0.512],\n                bev_pos=None,\n                prev_bev=None,\n                **kwargs):\n        \"\"\"\n        obtain bev features.\n        \"\"\"\n        bs = mlvl_feats[0].size(0)\n        bev_queries = bev_queries.unsqueeze(1).repeat(1, bs, 1)\n        bev_pos = bev_pos.flatten(2).permute(2, 0, 1)\n\n        feat_flatten = []\n        spatial_shapes = []\n        for lvl, feat in enumerate(mlvl_feats):\n            bs, num_cam, c, h, w = feat.shape\n            spatial_shape = (h, w)\n            feat = feat.flatten(3).permute(1, 0, 3, 2)\n            if self.use_cams_embeds:\n                feat = feat + self.cams_embeds[:, None, None, :].to(feat.dtype)\n            feat = feat + self.level_embeds[None, None, lvl:lvl + 1, :].to(feat.dtype)\n            spatial_shapes.append(spatial_shape)\n            feat_flatten.append(feat)\n\n        feat_flatten = torch.cat(feat_flatten, 2)\n        spatial_shapes = torch.as_tensor(spatial_shapes, dtype=torch.long, device=bev_pos.device)\n        level_start_index = torch.cat((spatial_shapes.new_zeros((1,)), spatial_shapes.prod(1).cumsum(0)[:-1]))\n\n        feat_flatten = feat_flatten.permute(0, 2, 1, 3)  # (num_cam, H*W, bs, embed_dims)\n\n        bev_embed = self.encoder(bev_queries,\n                                 feat_flatten,\n                                 feat_flatten,\n                                 bev_h=bev_h,\n                                 bev_w=bev_w,\n                                 bev_pos=bev_pos,\n                                 spatial_shapes=spatial_shapes,\n                                 level_start_index=level_start_index,\n                                 prev_bev=None,\n                                 shift=bev_queries.new_tensor([0, 0]).unsqueeze(0),\n                                 **kwargs)\n        # rotate current bev to final aligned\n        prev_bev = bev_embed\n        if 'aug_param' in kwargs['img_metas'][0] and 'GlobalRotScaleTransImage_param' in kwargs['img_metas'][0][\n            'aug_param']:\n            rot_angle, scale_ratio, flip_dx, flip_dy, bda_mat, only_gt = kwargs['img_metas'][0]['aug_param'][\n                'GlobalRotScaleTransImage_param']\n            prev_bev = prev_bev.reshape(bs, bev_h, bev_w, -1).permute(0, 3, 1, 2)  # bchw\n            if only_gt:\n                # rot angle\n                # prev_bev = torchvision.transforms.functional.rotate(prev_bev, -30, InterpolationMode.BILINEAR)\n                ref_y, ref_x = torch.meshgrid(\n                    torch.linspace(0.5, bev_h - 0.5, bev_h, dtype=bev_queries.dtype, device=bev_queries.device),\n                    torch.linspace(0.5, bev_w - 0.5, bev_w, dtype=bev_queries.dtype, device=bev_queries.device))\n                ref_y = (ref_y / bev_h)\n                ref_x = (ref_x / bev_w)\n                grid = torch.stack((ref_x, ref_y), -1)\n                grid_shift = grid * 2.0 - 1.0\n                grid_shift = grid_shift.unsqueeze(0).unsqueeze(-1)\n                # bda_mat = ( bda_mat[:2, :2] / scale_ratio).to(grid_shift).view(1, 1, 1, 2,2).repeat(grid_shift.shape[0], grid_shift.shape[1], grid_shift.shape[2], 1, 1)\n                bda_mat = bda_mat[:2, :2].to(grid_shift).view(1, 1, 1, 2, 2).repeat(grid_shift.shape[0],\n                                                                                    grid_shift.shape[1],\n                                                                                    grid_shift.shape[2], 1, 1)\n                grid_shift = torch.matmul(bda_mat, grid_shift).squeeze(-1)\n                # grid_shift = grid_shift / scale_ratio\n                prev_bev = torch.nn.functional.grid_sample(prev_bev, grid_shift, align_corners=False)\n                # if flip_dx:\n                #     prev_bev = torch.flip(prev_bev, dims=[-1])\n                # if flip_dy:\n                #     prev_bev = torch.flip(prev_bev, dims=[-2])\n            prev_bev = prev_bev.reshape(bs, -1, bev_h * bev_w)\n            prev_bev = prev_bev.permute(0, 2, 1)\n        return prev_bev\n\n\n@TRANSFORMER.register_module()\nclass PerceptionTransformerV2(PerceptionTransformerBEVEncoder):\n    \"\"\"Implements the Detr3D transformer.\n    Args:\n        as_two_stage (bool): Generate query from encoder features.\n            Default: False.\n        num_feature_levels (int): Number of feature maps from FPN:\n            Default: 4.\n        two_stage_num_proposals (int): Number of proposals when set\n            `as_two_stage` as True. Default: 300.\n    \"\"\"\n\n    def __init__(self,\n                 num_feature_levels=4,\n                 num_cams=6,\n                 two_stage_num_proposals=300,\n                 encoder=None,\n                 embed_dims=256,\n                 use_cams_embeds=True,\n                 rotate_center=[100, 100],\n                 frames=(0,),\n                 decoder=None,\n                 num_fusion=3,\n                 inter_channels=None,\n                 **kwargs):\n        super(PerceptionTransformerV2, self).__init__(num_feature_levels, num_cams, two_stage_num_proposals, encoder,\n                                                      embed_dims, use_cams_embeds, rotate_center,\n                                                      **kwargs)\n        self.decoder = build_transformer_layer_sequence(decoder)\n        \"\"\"Initialize layers of the Detr3DTransformer.\"\"\"\n        self.reference_points = nn.Linear(self.embed_dims, 3)\n        self.frames = frames\n        if len(self.frames) > 1:\n            self.fusion = ResNetFusion(len(self.frames) * self.embed_dims, self.embed_dims,\n                                       inter_channels if inter_channels is not None else len(\n                                           self.frames) * self.embed_dims,\n                                       num_fusion)\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        super().init_weights()\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MSDeformableAttention3D) or isinstance(m, TemporalSelfAttention) \\\n                    or isinstance(m, CustomMSDeformableAttention):\n                try:\n                    m.init_weight()\n                except AttributeError:\n                    m.init_weights()\n        xavier_init(self.reference_points, distribution='uniform', bias=0.)\n\n    def get_bev_features(\n            self,\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=[0.512, 0.512],\n            bev_pos=None,\n            prev_bev=None,\n            **kwargs):\n        return super().forward(\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length,\n            bev_pos,\n            prev_bev,\n            **kwargs\n        )\n\n    def forward(self,\n                mlvl_feats,\n                bev_queries,\n                object_query_embed,\n                bev_h,\n                bev_w,\n                grid_length=[0.512, 0.512],\n                bev_pos=None,\n                reg_branches=None,\n                cls_branches=None,\n                prev_bev=None,\n                **kwargs):\n        \"\"\"Forward function for `Detr3DTransformer`.\n        Args:\n            mlvl_feats (list(Tensor)): Input queries from\n                different level. Each element has shape\n                [bs, num_cams, embed_dims, h, w].\n            bev_queries (Tensor): (bev_h*bev_w, c)\n            bev_pos (Tensor): (bs, embed_dims, bev_h, bev_w)\n            object_query_embed (Tensor): The query embedding for decoder,\n                with shape [num_query, c].\n            reg_branches (obj:`nn.ModuleList`): Regression heads for\n                feature maps from each decoder layer. Only would\n                be passed when `with_box_refine` is True. Default to None.\n        Returns:\n            tuple[Tensor]: results of decoder containing the following tensor.\n                - bev_embed: BEV features\n                - inter_states: Outputs from decoder. If\n                    return_intermediate_dec is True output has shape \\\n                      (num_dec_layers, bs, num_query, embed_dims), else has \\\n                      shape (1, bs, num_query, embed_dims).\n                - init_reference_out: The initial value of reference \\\n                    points, has shape (bs, num_queries, 4).\n                - inter_references_out: The internal value of reference \\\n                    points in decoder, has shape \\\n                    (num_dec_layers, bs,num_query, embed_dims)\n                - enc_outputs_class: The classification score of \\\n                    proposals generated from \\\n                    encoder's feature maps, has shape \\\n                    (batch, h*w, num_classes). \\\n                    Only would be returned when `as_two_stage` is True, \\\n                    otherwise None.\n                - enc_outputs_coord_unact: The regression results \\\n                    generated from encoder's feature maps., has shape \\\n                    (batch, h*w, 4). Only would \\\n                    be returned when `as_two_stage` is True, \\\n                    otherwise None.\n        \"\"\"\n        bev_embed = self.get_bev_features(\n            mlvl_feats,\n            bev_queries,\n            bev_h,\n            bev_w,\n            grid_length=grid_length,\n            bev_pos=bev_pos,\n            prev_bev=None,\n            **kwargs)  # bev_embed shape: bs, bev_h*bev_w, embed_dims\n\n        if len(self.frames) > 1:\n            cur_ind = list(self.frames).index(0)\n            assert prev_bev[cur_ind] is None and len(prev_bev) == len(self.frames)\n            prev_bev[cur_ind] = bev_embed\n\n            # fill prev frame feature \n            for i in range(1, cur_ind + 1):\n                if prev_bev[cur_ind - i] is None:\n                    prev_bev[cur_ind - i] = prev_bev[cur_ind - i + 1].detach()\n\n            # fill next frame feature \n            for i in range(cur_ind + 1, len(self.frames)):\n                if prev_bev[i] is None:\n                    prev_bev[i] = prev_bev[i - 1].detach()\n            bev_embed = [x.reshape(x.shape[0], bev_h, bev_w, x.shape[-1]).permute(0, 3, 1, 2).contiguous() for x in\n                         prev_bev]\n            bev_embed = self.fusion(bev_embed)\n\n        bs = mlvl_feats[0].size(0)\n        query_pos, query = torch.split(\n            object_query_embed, self.embed_dims, dim=1)\n        query_pos = query_pos.unsqueeze(0).expand(bs, -1, -1)\n        query = query.unsqueeze(0).expand(bs, -1, -1)\n        reference_points = self.reference_points(query_pos)\n        reference_points = reference_points.sigmoid()\n        init_reference_out = reference_points\n\n        query = query.permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        bev_embed = bev_embed.permute(1, 0, 2)\n\n        inter_states, inter_references = self.decoder(\n            query=query,\n            key=None,\n            value=bev_embed,\n            query_pos=query_pos,\n            reference_points=reference_points,\n            reg_branches=reg_branches,\n            cls_branches=cls_branches,\n            spatial_shapes=torch.tensor([[bev_h, bev_w]], device=query.device),\n            level_start_index=torch.tensor([0], device=query.device),\n            **kwargs)\n\n        inter_references_out = inter_references\n\n        return bev_embed, inter_states, init_reference_out, inter_references_out\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/modules/vote_module.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nfrom mmcv import is_tuple_of\nfrom mmcv.models.bricks import ConvModule\nfrom torch import nn as nn\n\nfrom mmcv.models.builder import build_loss\n\n\nclass VoteModule(nn.Module):\n    \"\"\"Vote module.\n\n    Generate votes from seed point features.\n\n    Args:\n        in_channels (int): Number of channels of seed point features.\n        vote_per_seed (int): Number of votes generated from each seed point.\n        gt_per_seed (int): Number of ground truth votes generated\n            from each seed point.\n        num_points (int): Number of points to be used for voting.\n        conv_channels (tuple[int]): Out channels of vote\n            generating convolution.\n        conv_cfg (dict): Config of convolution.\n            Default: dict(type='Conv1d').\n        norm_cfg (dict): Config of normalization.\n            Default: dict(type='BN1d').\n        norm_feats (bool): Whether to normalize features.\n            Default: True.\n        with_res_feat (bool): Whether to predict residual features.\n            Default: True.\n        vote_xyz_range (list[float], None): The range of points translation.\n        vote_loss (dict): Config of vote loss.\n    \"\"\"\n\n    def __init__(self,\n                 in_channels,\n                 vote_per_seed=1,\n                 gt_per_seed=3,\n                 num_points=-1,\n                 conv_channels=(16, 16),\n                 conv_cfg=dict(type='Conv1d'),\n                 norm_cfg=dict(type='BN1d'),\n                 act_cfg=dict(type='ReLU'),\n                 norm_feats=True,\n                 with_res_feat=True,\n                 vote_xyz_range=None,\n                 vote_loss=None):\n        super().__init__()\n        self.in_channels = in_channels\n        self.vote_per_seed = vote_per_seed\n        self.gt_per_seed = gt_per_seed\n        self.num_points = num_points\n        self.norm_feats = norm_feats\n        self.with_res_feat = with_res_feat\n\n        assert vote_xyz_range is None or is_tuple_of(vote_xyz_range, float)\n        self.vote_xyz_range = vote_xyz_range\n\n        if vote_loss is not None:\n            self.vote_loss = build_loss(vote_loss)\n\n        prev_channels = in_channels\n        vote_conv_list = list()\n        for k in range(len(conv_channels)):\n            vote_conv_list.append(\n                ConvModule(\n                    prev_channels,\n                    conv_channels[k],\n                    1,\n                    padding=0,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=norm_cfg,\n                    act_cfg=act_cfg,\n                    bias=True,\n                    inplace=True))\n            prev_channels = conv_channels[k]\n        self.vote_conv = nn.Sequential(*vote_conv_list)\n\n        # conv_out predicts coordinate and residual features\n        if with_res_feat:\n            out_channel = (3 + in_channels) * self.vote_per_seed\n        else:\n            out_channel = 3 * self.vote_per_seed\n        self.conv_out = nn.Conv1d(prev_channels, out_channel, 1)\n\n    def forward(self, seed_points, seed_feats):\n        \"\"\"forward.\n\n        Args:\n            seed_points (torch.Tensor): Coordinate of the seed\n                points in shape (B, N, 3).\n            seed_feats (torch.Tensor): Features of the seed points in shape\n                (B, C, N).\n\n        Returns:\n            tuple[torch.Tensor]:\n\n                - vote_points: Voted xyz based on the seed points \\\n                    with shape (B, M, 3), ``M=num_seed*vote_per_seed``.\n                - vote_features: Voted features based on the seed points with \\\n                    shape (B, C, M) where ``M=num_seed*vote_per_seed``, \\\n                    ``C=vote_feature_dim``.\n        \"\"\"\n        if self.num_points != -1:\n            assert self.num_points < seed_points.shape[1], \\\n                f'Number of vote points ({self.num_points}) should be '\\\n                f'smaller than seed points size ({seed_points.shape[1]})'\n            seed_points = seed_points[:, :self.num_points]\n            seed_feats = seed_feats[..., :self.num_points]\n\n        batch_size, feat_channels, num_seed = seed_feats.shape\n        num_vote = num_seed * self.vote_per_seed\n        x = self.vote_conv(seed_feats)\n        # (batch_size, (3+out_dim)*vote_per_seed, num_seed)\n        votes = self.conv_out(x)\n\n        votes = votes.transpose(2, 1).view(batch_size, num_seed,\n                                           self.vote_per_seed, -1)\n\n        offset = votes[:, :, :, 0:3]\n        if self.vote_xyz_range is not None:\n            limited_offset_list = []\n            for axis in range(len(self.vote_xyz_range)):\n                limited_offset_list.append(offset[..., axis].clamp(\n                    min=-self.vote_xyz_range[axis],\n                    max=self.vote_xyz_range[axis]))\n            limited_offset = torch.stack(limited_offset_list, -1)\n            vote_points = (seed_points.unsqueeze(2) +\n                           limited_offset).contiguous()\n        else:\n            vote_points = (seed_points.unsqueeze(2) + offset).contiguous()\n        vote_points = vote_points.view(batch_size, num_vote, 3)\n        offset = offset.reshape(batch_size, num_vote, 3).transpose(2, 1)\n\n        if self.with_res_feat:\n            res_feats = votes[:, :, :, 3:]\n            vote_feats = (seed_feats.transpose(2, 1).unsqueeze(2) +\n                          res_feats).contiguous()\n            vote_feats = vote_feats.view(batch_size,\n                                         num_vote, feat_channels).transpose(\n                                             2, 1).contiguous()\n\n            if self.norm_feats:\n                features_norm = torch.norm(vote_feats, p=2, dim=1)\n                vote_feats = vote_feats.div(features_norm.unsqueeze(1))\n        else:\n            vote_feats = seed_feats\n        return vote_points, vote_feats, offset\n\n    def get_loss(self, seed_points, vote_points, seed_indices,\n                 vote_targets_mask, vote_targets):\n        \"\"\"Calculate loss of voting module.\n\n        Args:\n            seed_points (torch.Tensor): Coordinate of the seed points.\n            vote_points (torch.Tensor): Coordinate of the vote points.\n            seed_indices (torch.Tensor): Indices of seed points in raw points.\n            vote_targets_mask (torch.Tensor): Mask of valid vote targets.\n            vote_targets (torch.Tensor): Targets of votes.\n\n        Returns:\n            torch.Tensor: Weighted vote loss.\n        \"\"\"\n        batch_size, num_seed = seed_points.shape[:2]\n\n        seed_gt_votes_mask = torch.gather(vote_targets_mask, 1,\n                                          seed_indices).float()\n\n        seed_indices_expand = seed_indices.unsqueeze(-1).repeat(\n            1, 1, 3 * self.gt_per_seed)\n        seed_gt_votes = torch.gather(vote_targets, 1, seed_indices_expand)\n        seed_gt_votes += seed_points.repeat(1, 1, self.gt_per_seed)\n\n        weight = seed_gt_votes_mask / (torch.sum(seed_gt_votes_mask) + 1e-6)\n        distance = self.vote_loss(\n            vote_points.view(batch_size * num_seed, -1, 3),\n            seed_gt_votes.view(batch_size * num_seed, -1, 3),\n            dst_weight=weight.view(batch_size * num_seed, 1))[1]\n        vote_loss = torch.sum(torch.min(distance, dim=1)[0])\n\n        return vote_loss\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/necks/__init__.py",
    "content": "# from .bfp import BFP\n# from .channel_mapper import ChannelMapper\n# from .ct_resnet_neck import CTResNetNeck\n# from .dilated_encoder import DilatedEncoder\n# from .fpg import FPG\nfrom .fpn import FPN\n# from .fpn_carafe import FPN_CARAFE\n# from .multilevel_neck import MultiLevelNeck\n# from .hrfpn import HRFPN\n# from .nas_fpn import NASFPN\n# from .nasfcos_fpn import NASFCOS_FPN\n# from .pafpn import PAFPN\n# from .rfp import RFP\n# from .ssd_neck import SSDNeck\n# from .yolo_neck import YOLOV3Neck\n# from .imvoxel_neck import OutdoorImVoxelNeck\n# from .second_fpn import SECONDFPN\n\n# __all__ = [\n#     'FPN', 'BFP', 'ChannelMapper', 'HRFPN', 'NASFPN', 'FPN_CARAFE', 'PAFPN',\n#     'NASFCOS_FPN', 'RFP', 'YOLOV3Neck', 'FPG', 'DilatedEncoder',\n#     'CTResNetNeck', 'SSDNeck', 'SECONDFPN', 'OutdoorImVoxelNeck',\n#     'MultiLevelNeck'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/necks/fpn.py",
    "content": "import torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models.bricks import ConvModule\nfrom mmcv.models.backbones import BaseModule\nfrom mmcv.utils import auto_fp16\n\nfrom ..builder import NECKS\n\n\n@NECKS.register_module()\nclass FPN(BaseModule):\n    r\"\"\"Feature Pyramid Network.\n\n    This is an implementation of paper `Feature Pyramid Networks for Object\n    Detection <https://arxiv.org/abs/1612.03144>`_.\n\n    Args:\n        in_channels (List[int]): Number of input channels per scale.\n        out_channels (int): Number of output channels (used at each scale)\n        num_outs (int): Number of output scales.\n        start_level (int): Index of the start input backbone level used to\n            build the feature pyramid. Default: 0.\n        end_level (int): Index of the end input backbone level (exclusive) to\n            build the feature pyramid. Default: -1, which means the last level.\n        add_extra_convs (bool | str): If bool, it decides whether to add conv\n            layers on top of the original feature maps. Default to False.\n            If True, it is equivalent to `add_extra_convs='on_input'`.\n            If str, it specifies the source feature map of the extra convs.\n            Only the following options are allowed\n\n            - 'on_input': Last feat map of neck inputs (i.e. backbone feature).\n            - 'on_lateral':  Last feature map after lateral convs.\n            - 'on_output': The last output feature map after fpn convs.\n        relu_before_extra_convs (bool): Whether to apply relu before the extra\n            conv. Default: False.\n        no_norm_on_lateral (bool): Whether to apply norm on lateral.\n            Default: False.\n        conv_cfg (dict): Config dict for convolution layer. Default: None.\n        norm_cfg (dict): Config dict for normalization layer. Default: None.\n        act_cfg (str): Config dict for activation layer in ConvModule.\n            Default: None.\n        upsample_cfg (dict): Config dict for interpolate layer.\n            Default: `dict(mode='nearest')`\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n\n    Example:\n        >>> import torch\n        >>> in_channels = [2, 3, 5, 7]\n        >>> scales = [340, 170, 84, 43]\n        >>> inputs = [torch.rand(1, c, s, s)\n        ...           for c, s in zip(in_channels, scales)]\n        >>> self = FPN(in_channels, 11, len(in_channels)).eval()\n        >>> outputs = self.forward(inputs)\n        >>> for i in range(len(outputs)):\n        ...     print(f'outputs[{i}].shape = {outputs[i].shape}')\n        outputs[0].shape = torch.Size([1, 11, 340, 340])\n        outputs[1].shape = torch.Size([1, 11, 170, 170])\n        outputs[2].shape = torch.Size([1, 11, 84, 84])\n        outputs[3].shape = torch.Size([1, 11, 43, 43])\n    \"\"\"\n\n    def __init__(self,\n                 in_channels,\n                 out_channels,\n                 num_outs,\n                 start_level=0,\n                 end_level=-1,\n                 add_extra_convs=False,\n                 relu_before_extra_convs=False,\n                 no_norm_on_lateral=False,\n                 conv_cfg=None,\n                 norm_cfg=None,\n                 act_cfg=None,\n                 upsample_cfg=dict(mode='nearest'),\n                 init_cfg=dict(\n                     type='Xavier', layer='Conv2d', distribution='uniform')):\n        super(FPN, self).__init__(init_cfg)\n        assert isinstance(in_channels, list)\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.num_ins = len(in_channels)\n        self.num_outs = num_outs\n        self.relu_before_extra_convs = relu_before_extra_convs\n        self.no_norm_on_lateral = no_norm_on_lateral\n        self.fp16_enabled = False\n        self.upsample_cfg = upsample_cfg.copy()\n\n        if end_level == -1:\n            self.backbone_end_level = self.num_ins\n            assert num_outs >= self.num_ins - start_level\n        else:\n            # if end_level < inputs, no extra level is allowed\n            self.backbone_end_level = end_level\n            assert end_level <= len(in_channels)\n            assert num_outs == end_level - start_level\n        self.start_level = start_level\n        self.end_level = end_level\n        self.add_extra_convs = add_extra_convs\n        assert isinstance(add_extra_convs, (str, bool))\n        if isinstance(add_extra_convs, str):\n            # Extra_convs_source choices: 'on_input', 'on_lateral', 'on_output'\n            assert add_extra_convs in ('on_input', 'on_lateral', 'on_output')\n        elif add_extra_convs:  # True\n            self.add_extra_convs = 'on_input'\n\n        self.lateral_convs = nn.ModuleList()\n        self.fpn_convs = nn.ModuleList()\n\n        for i in range(self.start_level, self.backbone_end_level):\n            l_conv = ConvModule(\n                in_channels[i],\n                out_channels,\n                1,\n                conv_cfg=conv_cfg,\n                norm_cfg=norm_cfg if not self.no_norm_on_lateral else None,\n                act_cfg=act_cfg,\n                inplace=False)\n            fpn_conv = ConvModule(\n                out_channels,\n                out_channels,\n                3,\n                padding=1,\n                conv_cfg=conv_cfg,\n                norm_cfg=norm_cfg,\n                act_cfg=act_cfg,\n                inplace=False)\n\n            self.lateral_convs.append(l_conv)\n            self.fpn_convs.append(fpn_conv)\n\n        # add extra conv layers (e.g., RetinaNet)\n        extra_levels = num_outs - self.backbone_end_level + self.start_level\n        if self.add_extra_convs and extra_levels >= 1:\n            for i in range(extra_levels):\n                if i == 0 and self.add_extra_convs == 'on_input':\n                    in_channels = self.in_channels[self.backbone_end_level - 1]\n                else:\n                    in_channels = out_channels\n                extra_fpn_conv = ConvModule(\n                    in_channels,\n                    out_channels,\n                    3,\n                    stride=2,\n                    padding=1,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=norm_cfg,\n                    act_cfg=act_cfg,\n                    inplace=False)\n                self.fpn_convs.append(extra_fpn_conv)\n\n    @auto_fp16()\n    def forward(self, inputs):\n        \"\"\"Forward function.\"\"\"\n        assert len(inputs) == len(self.in_channels)\n\n        # build laterals\n        laterals = [\n            lateral_conv(inputs[i + self.start_level])\n            for i, lateral_conv in enumerate(self.lateral_convs)\n        ]\n\n        # build top-down path\n        used_backbone_levels = len(laterals)\n        for i in range(used_backbone_levels - 1, 0, -1):\n            # In some cases, fixing `scale factor` (e.g. 2) is preferred, but\n            #  it cannot co-exist with `size` in `F.interpolate`.\n            if 'scale_factor' in self.upsample_cfg:\n                laterals[i - 1] += F.interpolate(laterals[i],\n                                                 **self.upsample_cfg)\n            else:\n                prev_shape = laterals[i - 1].shape[2:]\n                laterals[i - 1] += F.interpolate(\n                    laterals[i], size=prev_shape, **self.upsample_cfg)\n\n        # build outputs\n        # part 1: from original levels\n        outs = [\n            self.fpn_convs[i](laterals[i]) for i in range(used_backbone_levels)\n        ]\n        # part 2: add extra levels\n        if self.num_outs > len(outs):\n            # use max pool to get more levels on top of outputs\n            # (e.g., Faster R-CNN, Mask R-CNN)\n            if not self.add_extra_convs:\n                for i in range(self.num_outs - used_backbone_levels):\n                    outs.append(F.max_pool2d(outs[-1], 1, stride=2))\n            # add conv layers on top of original feature maps (RetinaNet)\n            else:\n                if self.add_extra_convs == 'on_input':\n                    extra_source = inputs[self.backbone_end_level - 1]\n                elif self.add_extra_convs == 'on_lateral':\n                    extra_source = laterals[-1]\n                elif self.add_extra_convs == 'on_output':\n                    extra_source = outs[-1]\n                else:\n                    raise NotImplementedError\n                outs.append(self.fpn_convs[used_backbone_levels](extra_source))\n                for i in range(used_backbone_levels + 1, self.num_outs):\n                    if self.relu_before_extra_convs:\n                        outs.append(self.fpn_convs[i](F.relu(outs[-1])))\n                    else:\n                        outs.append(self.fpn_convs[i](outs[-1]))\n        return tuple(outs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/opt/__init__.py",
    "content": "from .adamw import AdamW2"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/opt/adamw.py",
    "content": "try:\n    from torch.optim import _functional as F\nexcept:\n    print('WARNING!!!, I recommend using torch>=1.8')\n\nimport torch\nfrom torch.optim.optimizer import Optimizer\nfrom mmcv.optims import OPTIMIZERS\n\n@OPTIMIZERS.register_module()\nclass AdamW2(Optimizer):\n    r\"\"\"Implements AdamW algorithm. Solve the bug of torch 1.8\n\n    The original Adam algorithm was proposed in `Adam: A Method for Stochastic Optimization`_.\n    The AdamW variant was proposed in `Decoupled Weight Decay Regularization`_.\n\n    Args:\n        params (iterable): iterable of parameters to optimize or dicts defining\n            parameter groups\n        lr (float, optional): learning rate (default: 1e-3)\n        betas (Tuple[float, float], optional): coefficients used for computing\n            running averages of gradient and its square (default: (0.9, 0.999))\n        eps (float, optional): term added to the denominator to improve\n            numerical stability (default: 1e-8)\n        weight_decay (float, optional): weight decay coefficient (default: 1e-2)\n        amsgrad (boolean, optional): whether to use the AMSGrad variant of this\n            algorithm from the paper `On the Convergence of Adam and Beyond`_\n            (default: False)\n\n    .. _Adam\\: A Method for Stochastic Optimization:\n        https://arxiv.org/abs/1412.6980\n    .. _Decoupled Weight Decay Regularization:\n        https://arxiv.org/abs/1711.05101\n    .. _On the Convergence of Adam and Beyond:\n        https://openreview.net/forum?id=ryQu7f-RZ\n    \"\"\"\n\n    def __init__(self, params, lr=1e-3, betas=(0.9, 0.999), eps=1e-8,\n                 weight_decay=1e-2, amsgrad=False):\n        if not 0.0 <= lr:\n            raise ValueError(\"Invalid learning rate: {}\".format(lr))\n        if not 0.0 <= eps:\n            raise ValueError(\"Invalid epsilon value: {}\".format(eps))\n        if not 0.0 <= betas[0] < 1.0:\n            raise ValueError(\"Invalid beta parameter at index 0: {}\".format(betas[0]))\n        if not 0.0 <= betas[1] < 1.0:\n            raise ValueError(\"Invalid beta parameter at index 1: {}\".format(betas[1]))\n        if not 0.0 <= weight_decay:\n            raise ValueError(\"Invalid weight_decay value: {}\".format(weight_decay))\n        defaults = dict(lr=lr, betas=betas, eps=eps,\n                        weight_decay=weight_decay, amsgrad=amsgrad)\n        super(AdamW2, self).__init__(params, defaults)\n\n    def __setstate__(self, state):\n        super(AdamW2, self).__setstate__(state)\n        for group in self.param_groups:\n            group.setdefault('amsgrad', False)\n\n    @torch.no_grad()\n    def step(self, closure=None):\n        \"\"\"Performs a single optimization step.\n\n        Args:\n            closure (callable, optional): A closure that reevaluates the model\n                and returns the loss.\n        \"\"\"\n        loss = None\n        if closure is not None:\n            with torch.enable_grad():\n                loss = closure()\n\n        for group in self.param_groups:\n            params_with_grad = []\n            grads = []\n            exp_avgs = []\n            exp_avg_sqs = []\n            state_sums = []\n            max_exp_avg_sqs = []\n            state_steps = []\n            amsgrad = group['amsgrad']\n\n            # put this line here for solving bug\n            beta1, beta2 = group['betas']\n\n            for p in group['params']:\n                if p.grad is None:\n                    continue\n                params_with_grad.append(p)\n                if p.grad.is_sparse:\n                    raise RuntimeError('AdamW does not support sparse gradients')\n                grads.append(p.grad)\n\n                state = self.state[p]\n\n                # State initialization\n                if len(state) == 0:\n                    state['step'] = 0\n                    # Exponential moving average of gradient values\n                    state['exp_avg'] = torch.zeros_like(p, memory_format=torch.preserve_format)\n                    # Exponential moving average of squared gradient values\n                    state['exp_avg_sq'] = torch.zeros_like(p, memory_format=torch.preserve_format)\n                    if amsgrad:\n                        # Maintains max of all exp. moving avg. of sq. grad. values\n                        state['max_exp_avg_sq'] = torch.zeros_like(p, memory_format=torch.preserve_format)\n\n                exp_avgs.append(state['exp_avg'])\n                exp_avg_sqs.append(state['exp_avg_sq'])\n\n                if amsgrad:\n                    max_exp_avg_sqs.append(state['max_exp_avg_sq'])\n\n\n                # update the steps for each param group update\n                state['step'] += 1\n                # record the step after step update\n                state_steps.append(state['step'])\n\n            F.adamw(params_with_grad,\n                    grads,\n                    exp_avgs,\n                    exp_avg_sqs,\n                    max_exp_avg_sqs,\n                    state_steps,\n                    amsgrad,\n                    beta1,\n                    beta2,\n                    group['lr'],\n                    group['weight_decay'],\n                    group['eps'])\n\n        return loss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/roi_heads/mask_heads/__init__.py",
    "content": "from .fused_semantic_head import FusedSemanticHead"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/roi_heads/mask_heads/fused_semantic_head.py",
    "content": "import torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.models import ConvModule\nfrom mmcv.models.backbones import BaseModule\nfrom mmcv.utils import auto_fp16, force_fp32\n\nfrom mmcv.models.builder import HEADS\n\n\n@HEADS.register_module()\nclass FusedSemanticHead(BaseModule):\n    r\"\"\"Multi-level fused semantic segmentation head.\n\n    .. code-block:: none\n\n        in_1 -> 1x1 conv ---\n                            |\n        in_2 -> 1x1 conv -- |\n                           ||\n        in_3 -> 1x1 conv - ||\n                          |||                  /-> 1x1 conv (mask prediction)\n        in_4 -> 1x1 conv -----> 3x3 convs (*4)\n                            |                  \\-> 1x1 conv (feature)\n        in_5 -> 1x1 conv ---\n    \"\"\"  # noqa: W605\n\n    def __init__(self,\n                 num_ins,\n                 fusion_level,\n                 num_convs=4,\n                 in_channels=256,\n                 conv_out_channels=256,\n                 num_classes=183,\n                 ignore_label=255,\n                 loss_weight=0.2,\n                 conv_cfg=None,\n                 norm_cfg=None,\n                 init_cfg=dict(\n                     type='Kaiming', override=dict(name='conv_logits'))):\n        super(FusedSemanticHead, self).__init__(init_cfg)\n        self.num_ins = num_ins\n        self.fusion_level = fusion_level\n        self.num_convs = num_convs\n        self.in_channels = in_channels\n        self.conv_out_channels = conv_out_channels\n        self.num_classes = num_classes\n        self.ignore_label = ignore_label\n        self.loss_weight = loss_weight\n        self.conv_cfg = conv_cfg\n        self.norm_cfg = norm_cfg\n        self.fp16_enabled = False\n\n        self.lateral_convs = nn.ModuleList()\n        for i in range(self.num_ins):\n            self.lateral_convs.append(\n                ConvModule(\n                    self.in_channels,\n                    self.in_channels,\n                    1,\n                    conv_cfg=self.conv_cfg,\n                    norm_cfg=self.norm_cfg,\n                    inplace=False))\n\n        self.convs = nn.ModuleList()\n        for i in range(self.num_convs):\n            in_channels = self.in_channels if i == 0 else conv_out_channels\n            self.convs.append(\n                ConvModule(\n                    in_channels,\n                    conv_out_channels,\n                    3,\n                    padding=1,\n                    conv_cfg=self.conv_cfg,\n                    norm_cfg=self.norm_cfg))\n        self.conv_embedding = ConvModule(\n            conv_out_channels,\n            conv_out_channels,\n            1,\n            conv_cfg=self.conv_cfg,\n            norm_cfg=self.norm_cfg)\n        self.conv_logits = nn.Conv2d(conv_out_channels, self.num_classes, 1)\n\n        self.criterion = nn.CrossEntropyLoss(ignore_index=ignore_label)\n\n    @auto_fp16()\n    def forward(self, feats):\n        x = self.lateral_convs[self.fusion_level](feats[self.fusion_level])\n        fused_size = tuple(x.shape[-2:])\n        for i, feat in enumerate(feats):\n            if i != self.fusion_level:\n                feat = F.interpolate(\n                    feat, size=fused_size, mode='bilinear', align_corners=True)\n                x += self.lateral_convs[i](feat)\n\n        for i in range(self.num_convs):\n            x = self.convs[i](x)\n\n        mask_pred = self.conv_logits(x)\n        x = self.conv_embedding(x)\n        return mask_pred, x\n\n    @force_fp32(apply_to=('mask_pred', ))\n    def loss(self, mask_pred, labels):\n        labels = labels.squeeze(1).long()\n        loss_semantic_seg = self.criterion(mask_pred, labels)\n        loss_semantic_seg *= self.loss_weight\n        return loss_semantic_seg\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/segmentors/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base import Base3DSegmentor, BaseSegmentor\n# from .cascade_encoder_decoder import CascadeEncoderDecoder\n# from .encoder_decoder import EncoderDecoder3D, EncoderDecoder\n\n# __all__ = ['Base3DSegmentor', 'EncoderDecoder3D',\n#            'BaseSegmentor', 'EncoderDecoder', 'CascadeEncoderDecoder']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/segmentors/base.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.parallel import DataContainer as DC\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom mmcv.utils import auto_fp16\nfrom os import path as osp\nfrom abc import ABCMeta, abstractmethod\nfrom collections import OrderedDict\nfrom mmcv.image import imread, imwrite\nfrom mmcv.utils import is_list_of\nfrom mmcv.core.visualizer import show_seg_result\nfrom mmcv.core.visualization import imshow\n\n\nclass BaseSegmentor(BaseModule, metaclass=ABCMeta):\n    \"\"\"Base class for segmentors.\"\"\"\n\n    def __init__(self, init_cfg=None):\n        super(BaseSegmentor, self).__init__(init_cfg)\n        self.fp16_enabled = False\n\n    @property\n    def with_neck(self):\n        \"\"\"bool: whether the segmentor has neck\"\"\"\n        return hasattr(self, 'neck') and self.neck is not None\n\n    @property\n    def with_auxiliary_head(self):\n        \"\"\"bool: whether the segmentor has auxiliary head\"\"\"\n        return hasattr(self,\n                       'auxiliary_head') and self.auxiliary_head is not None\n\n    @property\n    def with_decode_head(self):\n        \"\"\"bool: whether the segmentor has decode head\"\"\"\n        return hasattr(self, 'decode_head') and self.decode_head is not None\n\n    @abstractmethod\n    def extract_feat(self, imgs):\n        \"\"\"Placeholder for extract features from images.\"\"\"\n        pass\n\n    @abstractmethod\n    def encode_decode(self, img, img_metas):\n        \"\"\"Placeholder for encode images with backbone and decode into a\n        semantic segmentation map of the same size as input.\"\"\"\n        pass\n\n    @abstractmethod\n    def forward_train(self, imgs, img_metas, **kwargs):\n        \"\"\"Placeholder for Forward function for training.\"\"\"\n        pass\n\n    @abstractmethod\n    def simple_test(self, img, img_meta, **kwargs):\n        \"\"\"Placeholder for single image test.\"\"\"\n        pass\n\n    @abstractmethod\n    def aug_test(self, imgs, img_metas, **kwargs):\n        \"\"\"Placeholder for augmentation test.\"\"\"\n        pass\n\n    def forward_test(self, imgs, img_metas, **kwargs):\n        \"\"\"\n        Args:\n            imgs (List[Tensor]): the outer list indicates test-time\n                augmentations and inner Tensor should have a shape NxCxHxW,\n                which contains all images in the batch.\n            img_metas (List[List[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch.\n        \"\"\"\n        for var, name in [(imgs, 'imgs'), (img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError(f'{name} must be a list, but got '\n                                f'{type(var)}')\n\n        num_augs = len(imgs)\n        if num_augs != len(img_metas):\n            raise ValueError(f'num of augmentations ({len(imgs)}) != '\n                             f'num of image meta ({len(img_metas)})')\n        # all images in the same aug batch all of the same ori_shape and pad\n        # shape\n        for img_meta in img_metas:\n            ori_shapes = [_['ori_shape'] for _ in img_meta]\n            assert all(shape == ori_shapes[0] for shape in ori_shapes)\n            img_shapes = [_['img_shape'] for _ in img_meta]\n            assert all(shape == img_shapes[0] for shape in img_shapes)\n            pad_shapes = [_['pad_shape'] for _ in img_meta]\n            assert all(shape == pad_shapes[0] for shape in pad_shapes)\n\n        if num_augs == 1:\n            return self.simple_test(imgs[0], img_metas[0], **kwargs)\n        else:\n            return self.aug_test(imgs, img_metas, **kwargs)\n\n    @auto_fp16(apply_to=('img', ))\n    def forward(self, img, img_metas, return_loss=True, **kwargs):\n        \"\"\"Calls either :func:`forward_train` or :func:`forward_test` depending\n        on whether ``return_loss`` is ``True``.\n\n        Note this setting will change the expected inputs. When\n        ``return_loss=True``, img and img_meta are single-nested (i.e. Tensor\n        and List[dict]), and when ``resturn_loss=False``, img and img_meta\n        should be double nested (i.e.  List[Tensor], List[List[dict]]), with\n        the outer list indicating test time augmentations.\n        \"\"\"\n        if return_loss:\n            return self.forward_train(img, img_metas, **kwargs)\n        else:\n            return self.forward_test(img, img_metas, **kwargs)\n\n    def train_step(self, data_batch, optimizer, **kwargs):\n        \"\"\"The iteration step during training.\n\n        This method defines an iteration step during training, except for the\n        back propagation and optimizer updating, which are done in an optimizer\n        hook. Note that in some complicated cases or models, the whole process\n        including back propagation and optimizer updating is also defined in\n        this method, such as GAN.\n\n        Args:\n            data (dict): The output of dataloader.\n            optimizer (:obj:`torch.optim.Optimizer` | dict): The optimizer of\n                runner is passed to ``train_step()``. This argument is unused\n                and reserved.\n\n        Returns:\n            dict: It should contain at least 3 keys: ``loss``, ``log_vars``,\n                ``num_samples``.\n                ``loss`` is a tensor for back propagation, which can be a\n                weighted sum of multiple losses.\n                ``log_vars`` contains all the variables to be sent to the\n                logger.\n                ``num_samples`` indicates the batch size (when the model is\n                DDP, it means the batch size on each GPU), which is used for\n                averaging the logs.\n        \"\"\"\n        losses = self(**data_batch)\n        loss, log_vars = self._parse_losses(losses)\n\n        outputs = dict(\n            loss=loss,\n            log_vars=log_vars,\n            num_samples=len(data_batch['img_metas']))\n\n        return outputs\n\n    def val_step(self, data_batch, **kwargs):\n        \"\"\"The iteration step during validation.\n\n        This method shares the same signature as :func:`train_step`, but used\n        during val epochs. Note that the evaluation after training epochs is\n        not implemented with this method, but an evaluation hook.\n        \"\"\"\n        output = self(**data_batch, **kwargs)\n        return output\n\n    @staticmethod\n    def _parse_losses(losses):\n        \"\"\"Parse the raw outputs (losses) of the network.\n\n        Args:\n            losses (dict): Raw output of the network, which usually contain\n                losses and other necessary information.\n\n        Returns:\n            tuple[Tensor, dict]: (loss, log_vars), loss is the loss tensor\n                which may be a weighted sum of all losses, log_vars contains\n                all the variables to be sent to the logger.\n        \"\"\"\n        log_vars = OrderedDict()\n        for loss_name, loss_value in losses.items():\n            if isinstance(loss_value, torch.Tensor):\n                log_vars[loss_name] = loss_value.mean()\n            elif isinstance(loss_value, list):\n                log_vars[loss_name] = sum(_loss.mean() for _loss in loss_value)\n            else:\n                raise TypeError(\n                    f'{loss_name} is not a tensor or list of tensors')\n\n        loss = sum(_value for _key, _value in log_vars.items()\n                   if 'loss' in _key)\n\n        log_vars['loss'] = loss\n        for loss_name, loss_value in log_vars.items():\n            # reduce loss when distributed training\n            if dist.is_available() and dist.is_initialized():\n                loss_value = loss_value.data.clone()\n                dist.all_reduce(loss_value.div_(dist.get_world_size()))\n            log_vars[loss_name] = loss_value.item()\n\n        return loss, log_vars\n\n    def show_result(self,\n                    img,\n                    result,\n                    palette=None,\n                    win_name='',\n                    show=False,\n                    wait_time=0,\n                    out_file=None,\n                    opacity=0.5):\n        \"\"\"Draw `result` over `img`.\n\n        Args:\n            img (str or Tensor): The image to be displayed.\n            result (Tensor): The semantic segmentation results to draw over\n                `img`.\n            palette (list[list[int]]] | np.ndarray | None): The palette of\n                segmentation map. If None is given, random palette will be\n                generated. Default: None\n            win_name (str): The window name.\n            wait_time (int): Value of waitKey param.\n                Default: 0.\n            show (bool): Whether to show the image.\n                Default: False.\n            out_file (str or None): The filename to write the image.\n                Default: None.\n            opacity(float): Opacity of painted segmentation map.\n                Default 0.5.\n                Must be in (0, 1] range.\n        Returns:\n            img (Tensor): Only if not `show` or `out_file`\n        \"\"\"\n        img = imread(img)\n        img = img.copy()\n        seg = result[0]\n        if palette is None:\n            if self.PALETTE is None:\n                palette = np.random.randint(\n                    0, 255, size=(len(self.CLASSES), 3))\n            else:\n                palette = self.PALETTE\n        palette = np.array(palette)\n        assert palette.shape[0] == len(self.CLASSES)\n        assert palette.shape[1] == 3\n        assert len(palette.shape) == 2\n        assert 0 < opacity <= 1.0\n        color_seg = np.zeros((seg.shape[0], seg.shape[1], 3), dtype=np.uint8)\n        for label, color in enumerate(palette):\n            color_seg[seg == label, :] = color\n        # convert to BGR\n        color_seg = color_seg[..., ::-1]\n\n        img = img * (1 - opacity) + color_seg * opacity\n        img = img.astype(np.uint8)\n        # if out_file specified, do not show image in window\n        if out_file is not None:\n            show = False\n\n        if show:\n            imshow(img, win_name, wait_time)\n        if out_file is not None:\n            imwrite(img, out_file)\n\n        if not (show or out_file):\n            warnings.warn('show==False and out_file is not specified, only '\n                          'result image will be returned')\n            return img\n\nclass Base3DSegmentor(BaseSegmentor):\n    \"\"\"Base class for 3D segmentors.\n\n    The main difference with `BaseSegmentor` is that we modify the keys in\n    data_dict and use a 3D seg specific visualization function.\n    \"\"\"\n\n    @property\n    def with_regularization_loss(self):\n        \"\"\"bool: whether the segmentor has regularization loss for weight\"\"\"\n        return hasattr(self, 'loss_regularization') and \\\n            self.loss_regularization is not None\n\n    def forward_test(self, points, img_metas, **kwargs):\n        \"\"\"Calls either simple_test or aug_test depending on the length of\n        outer list of points. If len(points) == 1, call simple_test. Otherwise\n        call aug_test to aggregate the test results by e.g. voting.\n\n        Args:\n            points (list[list[torch.Tensor]]): the outer list indicates\n                test-time augmentations and inner torch.Tensor should have a\n                shape BXNxC, which contains all points in the batch.\n            img_metas (list[list[dict]]): the outer list indicates test-time\n                augs (multiscale, flip, etc.) and the inner list indicates\n                images in a batch.\n        \"\"\"\n        for var, name in [(points, 'points'), (img_metas, 'img_metas')]:\n            if not isinstance(var, list):\n                raise TypeError(f'{name} must be a list, but got {type(var)}')\n\n        num_augs = len(points)\n        if num_augs != len(img_metas):\n            raise ValueError(f'num of augmentations ({len(points)}) != '\n                             f'num of image meta ({len(img_metas)})')\n\n        if num_augs == 1:\n            return self.simple_test(points[0], img_metas[0], **kwargs)\n        else:\n            return self.aug_test(points, img_metas, **kwargs)\n\n    @auto_fp16(apply_to=('points'))\n    def forward(self, return_loss=True, **kwargs):\n        \"\"\"Calls either forward_train or forward_test depending on whether\n        return_loss=True.\n\n        Note this setting will change the expected inputs. When\n        `return_loss=True`, point and img_metas are single-nested (i.e.\n        torch.Tensor and list[dict]), and when `resturn_loss=False`, point and\n        img_metas should be double nested (i.e.  list[torch.Tensor],\n        list[list[dict]]), with the outer list indicating test time\n        augmentations.\n        \"\"\"\n        if return_loss:\n            return self.forward_train(**kwargs)\n        else:\n            return self.forward_test(**kwargs)\n\n    def show_results(self,\n                     data,\n                     result,\n                     palette=None,\n                     out_dir=None,\n                     ignore_index=None):\n        \"\"\"Results visualization.\n\n        Args:\n            data (list[dict]): Input points and the information of the sample.\n            result (list[dict]): Prediction results.\n            palette (list[list[int]]] | np.ndarray | None): The palette of\n                segmentation map. If None is given, random palette will be\n                generated. Default: None\n            out_dir (str): Output directory of visualization result.\n            ignore_index (int, optional): The label index to be ignored, e.g.\n                unannotated points. If None is given, set to len(self.CLASSES).\n                Defaults to None.\n        \"\"\"\n        assert out_dir is not None, 'Expect out_dir, got none.'\n        if palette is None:\n            if self.PALETTE is None:\n                palette = np.random.randint(\n                    0, 255, size=(len(self.CLASSES), 3))\n            else:\n                palette = self.PALETTE\n        palette = np.array(palette)\n        for batch_id in range(len(result)):\n            if isinstance(data['points'][0], DC):\n                points = data['points'][0]._data[0][batch_id].numpy()\n            elif is_list_of(data['points'][0], torch.Tensor):\n                points = data['points'][0][batch_id]\n            else:\n                ValueError(f\"Unsupported data type {type(data['points'][0])} \"\n                           f'for visualization!')\n            if isinstance(data['img_metas'][0], DC):\n                pts_filename = data['img_metas'][0]._data[0][batch_id][\n                    'pts_filename']\n            elif is_list_of(data['img_metas'][0], dict):\n                pts_filename = data['img_metas'][0][batch_id]['pts_filename']\n            else:\n                ValueError(\n                    f\"Unsupported data type {type(data['img_metas'][0])} \"\n                    f'for visualization!')\n            file_name = osp.split(pts_filename)[-1].split('.')[0]\n\n            pred_sem_mask = result[batch_id]['semantic_mask'].cpu().numpy()\n\n            show_seg_result(\n                points,\n                None,\n                pred_sem_mask,\n                out_dir,\n                file_name,\n                palette,\n                ignore_index,\n                show=True)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/__init__.py",
    "content": "from .builder import build_linear_layer, build_transformer\nfrom .positional_encoding import (LearnedPositionalEncoding,\n                                  SinePositionalEncoding)\nfrom .res_layer import ResLayer, SimplifiedBasicBlock\nfrom .transformer import (DetrTransformerDecoder, DetrTransformerDecoderLayer,\n                          DynamicConv, Transformer)\nfrom .grid_mask import GridMask\nfrom .weight_init import (INITIALIZERS, Caffe2XavierInit, ConstantInit,\n                          KaimingInit, NormalInit, PretrainedInit,\n                          TruncNormalInit, UniformInit, XavierInit,\n                          bias_init_with_prob, caffe2_xavier_init,\n                          constant_init, initialize, kaiming_init, normal_init,\n                          trunc_normal_init, uniform_init, xavier_init)\nfrom .fuse_conv_bn import fuse_conv_bn\n\n\n# __all__ = [\n#     'ResLayer', 'gaussian_radius', 'gen_gaussian_target',\n#     'DetrTransformerDecoderLayer', 'DetrTransformerDecoder', 'Transformer',\n#     'build_transformer', 'build_linear_layer', 'SinePositionalEncoding',\n#     'LearnedPositionalEncoding', 'DynamicConv', 'SimplifiedBasicBlock',\n#     'NormedLinear', 'NormedConv2d', 'make_divisible', 'InvertedResidual',\n#     'SELayer','clip_sigmoid', 'MLP', 'run_time', 'GridMask', 'SelfAttentionBlock',\n#     'UpConvBlock', 'InvertedResidualV3', 'DropPath', 'trunc_normal_'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/builder.py",
    "content": "import torch.nn as nn\nfrom mmcv.utils import Registry, build_from_cfg\n\nTRANSFORMER = Registry('Transformer')\nLINEAR_LAYERS = Registry('linear layers')\n\n\ndef build_transformer(cfg, default_args=None):\n    \"\"\"Builder for Transformer.\"\"\"\n    return build_from_cfg(cfg, TRANSFORMER, default_args)\n\n\nLINEAR_LAYERS.register_module('Linear', module=nn.Linear)\n\n\ndef build_linear_layer(cfg, *args, **kwargs):\n    \"\"\"Build linear layer.\n    Args:\n        cfg (None or dict): The linear layer config, which should contain:\n            - type (str): Layer type.\n            - layer args: Args needed to instantiate an linear layer.\n        args (argument list): Arguments passed to the `__init__`\n            method of the corresponding linear layer.\n        kwargs (keyword arguments): Keyword arguments passed to the `__init__`\n            method of the corresponding linear layer.\n    Returns:\n        nn.Module: Created linear layer.\n    \"\"\"\n    if cfg is None:\n        cfg_ = dict(type='Linear')\n    else:\n        if not isinstance(cfg, dict):\n            raise TypeError('cfg must be a dict')\n        if 'type' not in cfg:\n            raise KeyError('the cfg dict must contain the key \"type\"')\n        cfg_ = cfg.copy()\n\n    layer_type = cfg_.pop('type')\n    if layer_type not in LINEAR_LAYERS:\n        raise KeyError(f'Unrecognized linear type {layer_type}')\n    else:\n        linear_layer = LINEAR_LAYERS.get(layer_type)\n\n    layer = linear_layer(*args, **kwargs, **cfg_)\n\n    return layer\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/functional.py",
    "content": "import math\nimport torch\nfrom einops import rearrange, repeat\n\ndef bivariate_gaussian_activation(ip):\n    \"\"\"\n    Activation function to output parameters of bivariate Gaussian distribution.\n\n    Args:\n        ip (torch.Tensor): Input tensor.\n\n    Returns:\n        torch.Tensor: Output tensor containing the parameters of the bivariate Gaussian distribution.\n    \"\"\"\n    mu_x = ip[..., 0:1]\n    mu_y = ip[..., 1:2]\n    sig_x = ip[..., 2:3]\n    sig_y = ip[..., 3:4]\n    rho = ip[..., 4:5]\n    sig_x = torch.exp(sig_x)\n    sig_y = torch.exp(sig_y)\n    rho = torch.tanh(rho)\n    out = torch.cat([mu_x, mu_y, sig_x, sig_y, rho], dim=-1)\n    return out\n\ndef norm_points(pos, pc_range):\n    \"\"\"\n    Normalize the end points of a given position tensor.\n\n    Args:\n        pos (torch.Tensor): Input position tensor.\n        pc_range (List[float]): Point cloud range.\n\n    Returns:\n        torch.Tensor: Normalized end points tensor.\n    \"\"\"\n    x_norm = (pos[..., 0] - pc_range[0]) / (pc_range[3] - pc_range[0])\n    y_norm = (pos[..., 1] - pc_range[1]) / (pc_range[4] - pc_range[1]) \n    return torch.stack([x_norm, y_norm], dim=-1)\n\ndef pos2posemb2d(pos, num_pos_feats=128, temperature=10000):\n    \"\"\"\n    Convert 2D position into positional embeddings.\n\n    Args:\n        pos (torch.Tensor): Input 2D position tensor.\n        num_pos_feats (int, optional): Number of positional features. Default is 128.\n        temperature (int, optional): Temperature factor for positional embeddings. Default is 10000.\n\n    Returns:\n        torch.Tensor: Positional embeddings tensor.\n    \"\"\"\n    scale = 2 * math.pi\n    pos = pos * scale\n    dim_t = torch.arange(num_pos_feats, dtype=torch.float32, device=pos.device)\n    dim_t = temperature ** (2 * (dim_t // 2) / num_pos_feats)\n    pos_x = pos[..., 0, None] / dim_t\n    pos_y = pos[..., 1, None] / dim_t\n    pos_x = torch.stack((pos_x[..., 0::2].sin(), pos_x[..., 1::2].cos()), dim=-1).flatten(-2)\n    pos_y = torch.stack((pos_y[..., 0::2].sin(), pos_y[..., 1::2].cos()), dim=-1).flatten(-2)\n    posemb = torch.cat((pos_y, pos_x), dim=-1)\n    return posemb\n\ndef rot_2d(yaw):\n    \"\"\"\n    Compute 2D rotation matrix for a given yaw angle tensor.\n\n    Args:\n        yaw (torch.Tensor): Input yaw angle tensor.\n\n    Returns:\n        torch.Tensor: 2D rotation matrix tensor.\n    \"\"\"\n    sy, cy = torch.sin(yaw), torch.cos(yaw)\n    out = torch.stack([torch.stack([cy, -sy]), torch.stack([sy, cy])]).permute([2,0,1])\n    return out\n\ndef anchor_coordinate_transform(anchors, bbox_results, with_translation_transform=True, with_rotation_transform=True):\n    \"\"\"\n    Transform anchor coordinates with respect to detected bounding boxes in the batch.\n\n    Args:\n        anchors (torch.Tensor): A tensor containing the k-means anchor values.\n        bbox_results (List[Tuple[torch.Tensor]]): A list of tuples containing the bounding box results for each image in the batch.\n        with_translate (bool, optional): Whether to perform translation transformation. Defaults to True.\n        with_rot (bool, optional): Whether to perform rotation transformation. Defaults to True.\n\n    Returns:\n        torch.Tensor: A tensor containing the transformed anchor coordinates.\n    \"\"\"\n    batch_size = len(bbox_results)\n    batched_anchors = []\n    transformed_anchors = anchors[None, ...] # expand num agents: num_groups, num_modes, 12, 2 -> 1, ...\n    for i in range(batch_size):\n        bboxes, scores, labels, bbox_index, mask = bbox_results[i]\n        yaw = bboxes.yaw.to(transformed_anchors.device)\n        bbox_centers = bboxes.gravity_center.to(transformed_anchors.device)\n        if with_rotation_transform: \n            angle = yaw - 3.1415953 # num_agents, 1\n            rot_yaw = rot_2d(angle) # num_agents, 2, 2\n            rot_yaw = rot_yaw[:, None, None,:, :] # num_agents, 1, 1, 2, 2\n            transformed_anchors = rearrange(transformed_anchors, 'b g m t c -> b g m c t')  # 1, num_groups, num_modes, 12, 2 -> 1, num_groups, num_modes, 2, 12\n            transformed_anchors = torch.matmul(rot_yaw, transformed_anchors)# -> num_agents, num_groups, num_modes, 12, 2\n            transformed_anchors = rearrange(transformed_anchors, 'b g m c t -> b g m t c')\n        if with_translation_transform:\n            transformed_anchors = bbox_centers[:, None, None, None, :2] + transformed_anchors\n        batched_anchors.append(transformed_anchors)\n    return torch.stack(batched_anchors)\n\n\ndef trajectory_coordinate_transform(trajectory, bbox_results, with_translation_transform=True, with_rotation_transform=True):\n    \"\"\"\n    Transform trajectory coordinates with respect to detected bounding boxes in the batch.\n    Args:\n        trajectory (torch.Tensor): predicted trajectory.\n        bbox_results (List[Tuple[torch.Tensor]]): A list of tuples containing the bounding box results for each image in the batch.\n        with_translate (bool, optional): Whether to perform translation transformation. Defaults to True.\n        with_rot (bool, optional): Whether to perform rotation transformation. Defaults to True.\n\n    Returns:\n        torch.Tensor: A tensor containing the transformed trajectory coordinates.\n    \"\"\"\n    batch_size = len(bbox_results)\n    batched_trajectories = []\n    for i in range(batch_size):\n        bboxes, scores, labels, bbox_index, mask = bbox_results[i]\n        yaw = bboxes.yaw.to(trajectory.device)\n        bbox_centers = bboxes.gravity_center.to(trajectory.device)\n        transformed_trajectory = trajectory[i,...]\n        if with_rotation_transform:\n            # we take negtive here, to reverse the trajectory back to ego centric coordinate\n            angle = -(yaw - 3.1415953) \n            rot_yaw = rot_2d(angle)\n            rot_yaw = rot_yaw[:,None, None,:, :] # A, 1, 1, 2, 2\n            transformed_trajectory = rearrange(transformed_trajectory, 'a g p t c -> a g p c t') # A, G, P, 12 ,2 -> # A, G, P, 2, 12\n            transformed_trajectory = torch.matmul(rot_yaw, transformed_trajectory)# -> A, G, P, 12, 2\n            transformed_trajectory = rearrange(transformed_trajectory, 'a g p c t -> a g p t c')\n        if with_translation_transform:\n            transformed_trajectory = bbox_centers[:, None, None, None, :2] + transformed_trajectory\n        batched_trajectories.append(transformed_trajectory)\n    return torch.stack(batched_trajectories)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/fuse_conv_bn.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nimport torch.nn as nn\n\n\ndef _fuse_conv_bn(conv, bn):\n    \"\"\"Fuse conv and bn into one module.\n\n    Args:\n        conv (nn.Module): Conv to be fused.\n        bn (nn.Module): BN to be fused.\n\n    Returns:\n        nn.Module: Fused module.\n    \"\"\"\n    conv_w = conv.weight\n    conv_b = conv.bias if conv.bias is not None else torch.zeros_like(\n        bn.running_mean)\n\n    factor = bn.weight / torch.sqrt(bn.running_var + bn.eps)\n    conv.weight = nn.Parameter(conv_w *\n                               factor.reshape([conv.out_channels, 1, 1, 1]))\n    conv.bias = nn.Parameter((conv_b - bn.running_mean) * factor + bn.bias)\n    return conv\n\n\ndef fuse_conv_bn(module):\n    \"\"\"Recursively fuse conv and bn in a module.\n\n    During inference, the functionary of batch norm layers is turned off\n    but only the mean and var alone channels are used, which exposes the\n    chance to fuse it with the preceding conv layers to save computations and\n    simplify network structures.\n\n    Args:\n        module (nn.Module): Module to be fused.\n\n    Returns:\n        nn.Module: Fused module.\n    \"\"\"\n    last_conv = None\n    last_conv_name = None\n\n    for name, child in module.named_children():\n        if isinstance(child,\n                      (nn.modules.batchnorm._BatchNorm, nn.SyncBatchNorm)):\n            if last_conv is None:  # only fuse BN that is after Conv\n                continue\n            fused_conv = _fuse_conv_bn(last_conv, child)\n            module._modules[last_conv_name] = fused_conv\n            # To reduce changes, set BN as Identity instead of deleting it.\n            module._modules[name] = nn.Identity()\n            last_conv = None\n        elif isinstance(child, nn.Conv2d):\n            last_conv = child\n            last_conv_name = name\n        else:\n            fuse_conv_bn(child)\n    return module\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/grid_mask.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\nfrom PIL import Image\nfrom mmcv.utils import force_fp32, auto_fp16\n\nclass Grid(object):\n    def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5, mode=0, prob = 1.):\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode=mode\n        self.st_prob = prob\n        self.prob = prob\n\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch\n\n    def __call__(self, img, label):\n        if np.random.rand() > self.prob:\n            return img, label\n        h = img.size(1)\n        w = img.size(2)\n        self.d1 = 2\n        self.d2 = min(h, w)\n        hh = int(1.5*h)\n        ww = int(1.5*w)\n        d = np.random.randint(self.d1, self.d2)\n        if self.ratio == 1:\n            self.l = np.random.randint(1, d)\n        else:\n            self.l = min(max(int(d*self.ratio+0.5),1),d-1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh//d):\n                s = d*i + st_h\n                t = min(s+self.l, hh)\n                mask[s:t,:] *= 0\n        if self.use_w:\n            for i in range(ww//d):\n                s = d*i + st_w\n                t = min(s+self.l, ww)\n                mask[:,s:t] *= 0\n       \n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[(hh-h)//2:(hh-h)//2+h, (ww-w)//2:(ww-w)//2+w]\n\n        mask = torch.from_numpy(mask).float()\n        if self.mode == 1:\n            mask = 1-mask\n\n        mask = mask.expand_as(img)\n        if self.offset:\n            offset = torch.from_numpy(2 * (np.random.rand(h,w) - 0.5)).float()\n            offset = (1 - mask) * offset\n            img = img * mask + offset\n        else:\n            img = img * mask \n\n        return img, label\n\n\nclass GridMask(nn.Module):\n    def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5, mode=0, prob = 1.):\n        super(GridMask, self).__init__()\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode = mode\n        self.st_prob = prob\n        self.prob = prob\n        self.fp16_enable = False\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch #+ 1.#0.5\n    @auto_fp16()\n    def forward(self, x):\n        if np.random.rand() > self.prob or not self.training:\n            return x\n        n,c,h,w = x.size()\n        x = x.view(-1,h,w)\n        hh = int(1.5*h)\n        ww = int(1.5*w)\n        d = np.random.randint(2, h)\n        self.l = min(max(int(d*self.ratio+0.5),1),d-1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh//d):\n                s = d*i + st_h\n                t = min(s+self.l, hh)\n                mask[s:t,:] *= 0\n        if self.use_w:\n            for i in range(ww//d):\n                s = d*i + st_w\n                t = min(s+self.l, ww)\n                mask[:,s:t] *= 0\n       \n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[(hh-h)//2:(hh-h)//2+h, (ww-w)//2:(ww-w)//2+w]\n\n        mask = torch.from_numpy(mask).to(x.dtype).cuda()\n        if self.mode == 1:\n            mask = 1-mask\n        mask = mask.expand_as(x)\n        if self.offset:\n            offset = torch.from_numpy(2 * (np.random.rand(h,w) - 0.5)).to(x.dtype).cuda()\n            x = x * mask + offset * (1 - mask)\n        else:\n            x = x * mask \n        \n        return x.view(n,c,h,w)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/positional_encoding.py",
    "content": "import math\n\nimport torch\nimport torch.nn as nn\nfrom mmcv.models.bricks.transformer import POSITIONAL_ENCODING\nfrom mmcv.models.backbones.base_module import BaseModule\n\n\n@POSITIONAL_ENCODING.register_module()\nclass SinePositionalEncoding(BaseModule):\n    \"\"\"Position encoding with sine and cosine functions.\n\n    See `End-to-End Object Detection with Transformers\n    <https://arxiv.org/pdf/2005.12872>`_ for details.\n\n    Args:\n        num_feats (int): The feature dimension for each position\n            along x-axis or y-axis. Note the final returned dimension\n            for each position is 2 times of this value.\n        temperature (int, optional): The temperature used for scaling\n            the position embedding. Defaults to 10000.\n        normalize (bool, optional): Whether to normalize the position\n            embedding. Defaults to False.\n        scale (float, optional): A scale factor that scales the position\n            embedding. The scale will be used only when `normalize` is True.\n            Defaults to 2*pi.\n        eps (float, optional): A value added to the denominator for\n            numerical stability. Defaults to 1e-6.\n        offset (float): offset add to embed when do the normalization.\n            Defaults to 0.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n            Default: None\n    \"\"\"\n\n    def __init__(self,\n                 num_feats,\n                 temperature=10000,\n                 normalize=False,\n                 scale=2 * math.pi,\n                 eps=1e-6,\n                 offset=0.,\n                 init_cfg=None):\n        super(SinePositionalEncoding, self).__init__(init_cfg)\n        if normalize:\n            assert isinstance(scale, (float, int)), 'when normalize is set,' \\\n                'scale should be provided and in float or int type, ' \\\n                f'found {type(scale)}'\n        self.num_feats = num_feats\n        self.temperature = temperature\n        self.normalize = normalize\n        self.scale = scale\n        self.eps = eps\n        self.offset = offset\n\n    def forward(self, mask):\n        \"\"\"Forward function for `SinePositionalEncoding`.\n\n        Args:\n            mask (Tensor): ByteTensor mask. Non-zero values representing\n                ignored positions, while zero values means valid positions\n                for this image. Shape [bs, h, w].\n\n        Returns:\n            pos (Tensor): Returned position embedding with shape\n                [bs, num_feats*2, h, w].\n        \"\"\"\n        # For convenience of exporting to ONNX, it's required to convert\n        # `masks` from bool to int.\n        mask = mask.to(torch.int)\n        not_mask = 1 - mask  # logical_not\n        y_embed = not_mask.cumsum(1, dtype=torch.float32)\n        x_embed = not_mask.cumsum(2, dtype=torch.float32)\n        if self.normalize:\n            y_embed = (y_embed + self.offset) / \\\n                      (y_embed[:, -1:, :] + self.eps) * self.scale\n            x_embed = (x_embed + self.offset) / \\\n                      (x_embed[:, :, -1:] + self.eps) * self.scale\n        dim_t = torch.arange(\n            self.num_feats, dtype=torch.float32, device=mask.device)\n        dim_t = self.temperature**(2 * (dim_t // 2) / self.num_feats)\n        pos_x = x_embed[:, :, :, None] / dim_t\n        pos_y = y_embed[:, :, :, None] / dim_t\n        # use `view` instead of `flatten` for dynamically exporting to ONNX\n        B, H, W = mask.size()\n        pos_x = torch.stack(\n            (pos_x[:, :, :, 0::2].sin(), pos_x[:, :, :, 1::2].cos()),\n            dim=4).view(B, H, W, -1)\n        pos_y = torch.stack(\n            (pos_y[:, :, :, 0::2].sin(), pos_y[:, :, :, 1::2].cos()),\n            dim=4).view(B, H, W, -1)\n        pos = torch.cat((pos_y, pos_x), dim=3).permute(0, 3, 1, 2)\n        return pos\n\n    def __repr__(self):\n        \"\"\"str: a string that describes the module\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(num_feats={self.num_feats}, '\n        repr_str += f'temperature={self.temperature}, '\n        repr_str += f'normalize={self.normalize}, '\n        repr_str += f'scale={self.scale}, '\n        repr_str += f'eps={self.eps})'\n        return repr_str\n\n\n@POSITIONAL_ENCODING.register_module()\nclass LearnedPositionalEncoding(BaseModule):\n    \"\"\"Position embedding with learnable embedding weights.\n\n    Args:\n        num_feats (int): The feature dimension for each position\n            along x-axis or y-axis. The final returned dimension for\n            each position is 2 times of this value.\n        row_num_embed (int, optional): The dictionary size of row embeddings.\n            Default 50.\n        col_num_embed (int, optional): The dictionary size of col embeddings.\n            Default 50.\n        init_cfg (dict or list[dict], optional): Initialization config dict.\n    \"\"\"\n\n    def __init__(self,\n                 num_feats,\n                 row_num_embed=50,\n                 col_num_embed=50,\n                 init_cfg=dict(type='Uniform', layer='Embedding')):\n        super(LearnedPositionalEncoding, self).__init__(init_cfg)\n        self.row_embed = nn.Embedding(row_num_embed, num_feats)\n        self.col_embed = nn.Embedding(col_num_embed, num_feats)\n        self.num_feats = num_feats\n        self.row_num_embed = row_num_embed\n        self.col_num_embed = col_num_embed\n\n    def forward(self, mask):\n        \"\"\"Forward function for `LearnedPositionalEncoding`.\n\n        Args:\n            mask (Tensor): ByteTensor mask. Non-zero values representing\n                ignored positions, while zero values means valid positions\n                for this image. Shape [bs, h, w].\n\n        Returns:\n            pos (Tensor): Returned position embedding with shape\n                [bs, num_feats*2, h, w].\n        \"\"\"\n        h, w = mask.shape[-2:]\n        x = torch.arange(w, device=mask.device)\n        y = torch.arange(h, device=mask.device)\n        x_embed = self.col_embed(x)\n        y_embed = self.row_embed(y)\n        pos = torch.cat(\n            (x_embed.unsqueeze(0).repeat(h, 1, 1), y_embed.unsqueeze(1).repeat(\n                1, w, 1)),\n            dim=-1).permute(2, 0,\n                            1).unsqueeze(0).repeat(mask.shape[0], 1, 1, 1)\n        return pos\n\n    def __repr__(self):\n        \"\"\"str: a string that describes the module\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f'(num_feats={self.num_feats}, '\n        repr_str += f'row_num_embed={self.row_num_embed}, '\n        repr_str += f'col_num_embed={self.col_num_embed})'\n        return repr_str\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/res_layer.py",
    "content": "from ..bricks.conv import build_conv_layer\nfrom ..bricks.norm import build_norm_layer\n# from ..bricks import build_conv_layer, build_norm_layer\nfrom mmcv.models.backbones.base_module import BaseModule, Sequential\nfrom torch import nn as nn\n\n\nclass ResLayer(Sequential):\n    \"\"\"ResLayer to build ResNet style backbone.\n\n    Args:\n        block (nn.Module): block used to build ResLayer.\n        inplanes (int): inplanes of block.\n        planes (int): planes of block.\n        num_blocks (int): number of blocks.\n        stride (int): stride of the first block. Default: 1\n        avg_down (bool): Use AvgPool instead of stride conv when\n            downsampling in the bottleneck. Default: False\n        conv_cfg (dict): dictionary to construct and config conv layer.\n            Default: None\n        norm_cfg (dict): dictionary to construct and config norm layer.\n            Default: dict(type='BN')\n        downsample_first (bool): Downsample at the first block or last block.\n            False for Hourglass, True for ResNet. Default: True\n    \"\"\"\n\n    def __init__(self,\n                 block,\n                 inplanes,\n                 planes,\n                 num_blocks,\n                 stride=1,\n                 avg_down=False,\n                 conv_cfg=None,\n                 norm_cfg=dict(type='BN'),\n                 downsample_first=True,\n                 **kwargs):\n        self.block = block\n\n        downsample = None\n        if stride != 1 or inplanes != planes * block.expansion:\n            downsample = []\n            conv_stride = stride\n            if avg_down:\n                conv_stride = 1\n                downsample.append(\n                    nn.AvgPool2d(\n                        kernel_size=stride,\n                        stride=stride,\n                        ceil_mode=True,\n                        count_include_pad=False))\n            downsample.extend([\n                build_conv_layer(\n                    conv_cfg,\n                    inplanes,\n                    planes * block.expansion,\n                    kernel_size=1,\n                    stride=conv_stride,\n                    bias=False),\n                build_norm_layer(norm_cfg, planes * block.expansion)[1]\n            ])\n            downsample = nn.Sequential(*downsample)\n\n        layers = []\n        if downsample_first:\n            layers.append(\n                block(\n                    inplanes=inplanes,\n                    planes=planes,\n                    stride=stride,\n                    downsample=downsample,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=norm_cfg,\n                    **kwargs))\n            inplanes = planes * block.expansion\n            for _ in range(1, num_blocks):\n                layers.append(\n                    block(\n                        inplanes=inplanes,\n                        planes=planes,\n                        stride=1,\n                        conv_cfg=conv_cfg,\n                        norm_cfg=norm_cfg,\n                        **kwargs))\n\n        else:  # downsample_first=False is for HourglassModule\n            for _ in range(num_blocks - 1):\n                layers.append(\n                    block(\n                        inplanes=inplanes,\n                        planes=inplanes,\n                        stride=1,\n                        conv_cfg=conv_cfg,\n                        norm_cfg=norm_cfg,\n                        **kwargs))\n            layers.append(\n                block(\n                    inplanes=inplanes,\n                    planes=planes,\n                    stride=stride,\n                    downsample=downsample,\n                    conv_cfg=conv_cfg,\n                    norm_cfg=norm_cfg,\n                    **kwargs))\n        super(ResLayer, self).__init__(*layers)\n\n\nclass SimplifiedBasicBlock(BaseModule):\n    \"\"\"Simplified version of original basic residual block. This is used in\n    `SCNet <https://arxiv.org/abs/2012.10150>`_.\n\n    - Norm layer is now optional\n    - Last ReLU in forward function is removed\n    \"\"\"\n    expansion = 1\n\n    def __init__(self,\n                 inplanes,\n                 planes,\n                 stride=1,\n                 dilation=1,\n                 downsample=None,\n                 style='pytorch',\n                 with_cp=False,\n                 conv_cfg=None,\n                 norm_cfg=dict(type='BN'),\n                 dcn=None,\n                 plugins=None,\n                 init_fg=None):\n        super(SimplifiedBasicBlock, self).__init__(init_fg)\n        assert dcn is None, 'Not implemented yet.'\n        assert plugins is None, 'Not implemented yet.'\n        assert not with_cp, 'Not implemented yet.'\n        self.with_norm = norm_cfg is not None\n        with_bias = True if norm_cfg is None else False\n        self.conv1 = build_conv_layer(\n            conv_cfg,\n            inplanes,\n            planes,\n            3,\n            stride=stride,\n            padding=dilation,\n            dilation=dilation,\n            bias=with_bias)\n        if self.with_norm:\n            self.norm1_name, norm1 = build_norm_layer(\n                norm_cfg, planes, postfix=1)\n            self.add_module(self.norm1_name, norm1)\n        self.conv2 = build_conv_layer(\n            conv_cfg, planes, planes, 3, padding=1, bias=with_bias)\n        if self.with_norm:\n            self.norm2_name, norm2 = build_norm_layer(\n                norm_cfg, planes, postfix=2)\n            self.add_module(self.norm2_name, norm2)\n\n        self.relu = nn.ReLU(inplace=True)\n        self.downsample = downsample\n        self.stride = stride\n        self.dilation = dilation\n        self.with_cp = with_cp\n\n    @property\n    def norm1(self):\n        \"\"\"nn.Module: normalization layer after the first convolution layer\"\"\"\n        return getattr(self, self.norm1_name) if self.with_norm else None\n\n    @property\n    def norm2(self):\n        \"\"\"nn.Module: normalization layer after the second convolution layer\"\"\"\n        return getattr(self, self.norm2_name) if self.with_norm else None\n\n    def forward(self, x):\n        \"\"\"Forward function.\"\"\"\n\n        identity = x\n\n        out = self.conv1(x)\n        if self.with_norm:\n            out = self.norm1(out)\n        out = self.relu(out)\n\n        out = self.conv2(out)\n        if self.with_norm:\n            out = self.norm2(out)\n\n        if self.downsample is not None:\n            identity = self.downsample(x)\n\n        out += identity\n\n        return out\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/transformer.py",
    "content": "import math\nimport warnings\n\nimport torch\nimport torch.nn as nn\nfrom ..bricks.activation import build_activation_layer\nfrom ..bricks.norm import build_norm_layer\nfrom .weight_init import xavier_init\n# from mmcv.models import build_activation_layer, build_norm_layer, xavier_init\nfrom mmcv.models.bricks.registry import (TRANSFORMER_LAYER,\n                                      TRANSFORMER_LAYER_SEQUENCE)\nfrom mmcv.models.bricks.transformer import (BaseTransformerLayer,\n                                         TransformerLayerSequence,\n                                         build_transformer_layer_sequence)\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom torch.nn.init import normal_\n\nfrom mmcv.models.utils.builder import TRANSFORMER\n\nfrom mmcv.ops.multi_scale_deform_attn import MultiScaleDeformableAttention\n\ntry:\n    from mmcv.ops.multi_scale_deform_attn import MultiScaleDeformableAttention\n\nexcept ImportError:\n    warnings.warn(\n        '`MultiScaleDeformableAttention` in MMCV has been moved to '\n        '`mmcv.ops.multi_scale_deform_attn`, please update your MMCV')\n    from ..bricks.transformer import MultiScaleDeformableAttention\n\n\ndef inverse_sigmoid(x, eps=1e-5):\n    \"\"\"Inverse function of sigmoid.\n\n    Args:\n        x (Tensor): The tensor to do the\n            inverse.\n        eps (float): EPS avoid numerical\n            overflow. Defaults 1e-5.\n    Returns:\n        Tensor: The x has passed the inverse\n            function of sigmoid, has same\n            shape with input.\n    \"\"\"\n    x = x.clamp(min=0, max=1)\n    x1 = x.clamp(min=eps)\n    x2 = (1 - x).clamp(min=eps)\n    return torch.log(x1 / x2)\n\n\n@TRANSFORMER_LAYER.register_module()\nclass DetrTransformerDecoderLayer(BaseTransformerLayer):\n    \"\"\"Implements decoder layer in DETR transformer.\n\n    Args:\n        attn_cfgs (list[`mmcv.ConfigDict`] | list[dict] | dict )):\n            Configs for self_attention or cross_attention, the order\n            should be consistent with it in `operation_order`. If it is\n            a dict, it would be expand to the number of attention in\n            `operation_order`.\n        feedforward_channels (int): The hidden dimension for FFNs.\n        ffn_dropout (float): Probability of an element to be zeroed\n            in ffn. Default 0.0.\n        operation_order (tuple[str]): The execution order of operation\n            in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').\n            Default：None\n        act_cfg (dict): The activation config for FFNs. Default: `LN`\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: `LN`.\n        ffn_num_fcs (int): The number of fully-connected layers in FFNs.\n            Default：2.\n    \"\"\"\n\n    def __init__(self,\n                 attn_cfgs,\n                 feedforward_channels,\n                 ffn_dropout=0.0,\n                 operation_order=None,\n                 act_cfg=dict(type='ReLU', inplace=True),\n                 norm_cfg=dict(type='LN'),\n                 ffn_num_fcs=2,\n                 with_cp=True,\n                 **kwargs):\n        super(DetrTransformerDecoderLayer, self).__init__(\n            attn_cfgs=attn_cfgs,\n            feedforward_channels=feedforward_channels,\n            ffn_dropout=ffn_dropout,\n            operation_order=operation_order,\n            act_cfg=act_cfg,\n            norm_cfg=norm_cfg,\n            ffn_num_fcs=ffn_num_fcs,\n            **kwargs)\n        assert len(operation_order) == 6\n        assert set(operation_order) == set(\n            ['self_attn', 'norm', 'cross_attn', 'ffn'])\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass DetrTransformerEncoder(TransformerLayerSequence):\n    \"\"\"TransformerEncoder of DETR.\n\n    Args:\n        post_norm_cfg (dict): Config of last normalization layer. Default：\n            `LN`. Only used when `self.pre_norm` is `True`\n    \"\"\"\n\n    def __init__(self, *args, post_norm_cfg=dict(type='LN'), **kwargs):\n        super(DetrTransformerEncoder, self).__init__(*args, **kwargs)\n        if post_norm_cfg is not None:\n            self.post_norm = build_norm_layer(\n                post_norm_cfg, self.embed_dims)[1] if self.pre_norm else None\n        else:\n            assert not self.pre_norm, f'Use prenorm in ' \\\n                                      f'{self.__class__.__name__},' \\\n                                      f'Please specify post_norm_cfg'\n            self.post_norm = None\n\n    def forward(self, *args, **kwargs):\n        \"\"\"Forward function for `TransformerCoder`.\n\n        Returns:\n            Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n        x = super(DetrTransformerEncoder, self).forward(*args, **kwargs)\n        if self.post_norm is not None:\n            x = self.post_norm(x)\n        return x\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass DetrTransformerDecoder(TransformerLayerSequence):\n    \"\"\"Implements the decoder in DETR transformer.\n\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        post_norm_cfg (dict): Config of last normalization layer. Default：\n            `LN`.\n    \"\"\"\n\n    def __init__(self,\n                 *args,\n                 post_norm_cfg=dict(type='LN'),\n                 return_intermediate=False,\n                 **kwargs):\n\n        super(DetrTransformerDecoder, self).__init__(*args, **kwargs)\n        self.return_intermediate = return_intermediate\n        if post_norm_cfg is not None:\n            self.post_norm = build_norm_layer(post_norm_cfg,\n                                              self.embed_dims)[1]\n        else:\n            self.post_norm = None\n\n    def forward(self, query, *args, **kwargs):\n        \"\"\"Forward function for `TransformerDecoder`.\n\n        Args:\n            query (Tensor): Input query with shape\n                `(num_query, bs, embed_dims)`.\n\n        Returns:\n            Tensor: Results with shape [1, num_query, bs, embed_dims] when\n                return_intermediate is `False`, otherwise it has shape\n                [num_layers, num_query, bs, embed_dims].\n        \"\"\"\n        if not self.return_intermediate:\n            x = super().forward(query, *args, **kwargs)\n            if self.post_norm:\n                x = self.post_norm(x)[None]\n            return x\n\n        intermediate = []\n        for layer in self.layers:\n            query = layer(query, *args, **kwargs)\n            if self.return_intermediate:\n                if self.post_norm is not None:\n                    intermediate.append(self.post_norm(query))\n                else:\n                    intermediate.append(query)\n        return torch.stack(intermediate)\n\n\n@TRANSFORMER.register_module()\nclass Transformer(BaseModule):\n    \"\"\"Implements the DETR transformer.\n\n    Following the official DETR implementation, this module copy-paste\n    from torch.nn.Transformer with modifications:\n\n        * positional encodings are passed in MultiheadAttention\n        * extra LN at the end of encoder is removed\n        * decoder returns a stack of activations from all decoding layers\n\n    See `paper: End-to-End Object Detection with Transformers\n    <https://arxiv.org/pdf/2005.12872>`_ for details.\n\n    Args:\n        encoder (`mmcv.ConfigDict` | Dict): Config of\n            TransformerEncoder. Defaults to None.\n        decoder ((`mmcv.ConfigDict` | Dict)): Config of\n            TransformerDecoder. Defaults to None\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, encoder=None, decoder=None, init_cfg=None):\n        super(Transformer, self).__init__(init_cfg=init_cfg)\n        self.encoder = build_transformer_layer_sequence(encoder)\n        self.decoder = build_transformer_layer_sequence(decoder)\n        self.embed_dims = self.encoder.embed_dims\n\n    def init_weights(self):\n        # follow the official DETR to init parameters\n        for m in self.modules():\n            if hasattr(m, 'weight') and m.weight.dim() > 1:\n                xavier_init(m, distribution='uniform')\n        self._is_init = True\n\n    def forward(self, x, mask, query_embed, pos_embed):\n        \"\"\"Forward function for `Transformer`.\n\n        Args:\n            x (Tensor): Input query with shape [bs, c, h, w] where\n                c = embed_dims.\n            mask (Tensor): The key_padding_mask used for encoder and decoder,\n                with shape [bs, h, w].\n            query_embed (Tensor): The query embedding for decoder, with shape\n                [num_query, c].\n            pos_embed (Tensor): The positional encoding for encoder and\n                decoder, with the same shape as `x`.\n\n        Returns:\n            tuple[Tensor]: results of decoder containing the following tensor.\n\n                - out_dec: Output from decoder. If return_intermediate_dec \\\n                      is True output has shape [num_dec_layers, bs,\n                      num_query, embed_dims], else has shape [1, bs, \\\n                      num_query, embed_dims].\n                - memory: Output results from encoder, with shape \\\n                      [bs, embed_dims, h, w].\n        \"\"\"\n        bs, c, h, w = x.shape\n        # use `view` instead of `flatten` for dynamically exporting to ONNX\n        x = x.view(bs, c, -1).permute(2, 0, 1)  # [bs, c, h, w] -> [h*w, bs, c]\n        pos_embed = pos_embed.view(bs, c, -1).permute(2, 0, 1)\n        query_embed = query_embed.unsqueeze(1).repeat(\n            1, bs, 1)  # [num_query, dim] -> [num_query, bs, dim]\n        mask = mask.view(bs, -1)  # [bs, h, w] -> [bs, h*w]\n        memory = self.encoder(\n            query=x,\n            key=None,\n            value=None,\n            query_pos=pos_embed,\n            query_key_padding_mask=mask)\n        target = torch.zeros_like(query_embed)\n        # out_dec: [num_layers, num_query, bs, dim]\n        out_dec = self.decoder(\n            query=target,\n            key=memory,\n            value=memory,\n            key_pos=pos_embed,\n            query_pos=query_embed,\n            key_padding_mask=mask)\n        out_dec = out_dec.transpose(1, 2)\n        memory = memory.permute(1, 2, 0).reshape(bs, c, h, w)\n        return out_dec, memory\n\n\n@TRANSFORMER_LAYER_SEQUENCE.register_module()\nclass DeformableDetrTransformerDecoder(TransformerLayerSequence):\n    \"\"\"Implements the decoder in DETR transformer.\n\n    Args:\n        return_intermediate (bool): Whether to return intermediate outputs.\n        coder_norm_cfg (dict): Config of last normalization layer. Default：\n            `LN`.\n    \"\"\"\n\n    def __init__(self, *args, return_intermediate=False, **kwargs):\n\n        super(DeformableDetrTransformerDecoder, self).__init__(*args, **kwargs)\n        self.return_intermediate = return_intermediate\n\n    def forward(self,\n                query,\n                *args,\n                reference_points=None,\n                valid_ratios=None,\n                reg_branches=None,\n                **kwargs):\n        \"\"\"Forward function for `TransformerDecoder`.\n\n        Args:\n            query (Tensor): Input query with shape\n                `(num_query, bs, embed_dims)`.\n            reference_points (Tensor): The reference\n                points of offset. has shape\n                (bs, num_query, 4) when as_two_stage,\n                otherwise has shape ((bs, num_query, 2).\n            valid_ratios (Tensor): The radios of valid\n                points on the feature map, has shape\n                (bs, num_levels, 2)\n            reg_branch: (obj:`nn.ModuleList`): Used for\n                refining the regression results. Only would\n                be passed when with_box_refine is True,\n                otherwise would be passed a `None`.\n\n        Returns:\n            Tensor: Results with shape [1, num_query, bs, embed_dims] when\n                return_intermediate is `False`, otherwise it has shape\n                [num_layers, num_query, bs, embed_dims].\n        \"\"\"\n        output = query\n        intermediate = []\n        intermediate_reference_points = []\n        for lid, layer in enumerate(self.layers):\n            if reference_points.shape[-1] == 4:\n                reference_points_input = reference_points[:, :, None] * \\\n                    torch.cat([valid_ratios, valid_ratios], -1)[:, None]\n            else:\n                assert reference_points.shape[-1] == 2\n                reference_points_input = reference_points[:, :, None] * \\\n                    valid_ratios[:, None]\n            output = layer(\n                output,\n                *args,\n                reference_points=reference_points_input,\n                **kwargs)\n            output = output.permute(1, 0, 2)\n\n            if reg_branches is not None:\n                tmp = reg_branches[lid](output)\n                if reference_points.shape[-1] == 4:\n                    new_reference_points = tmp + inverse_sigmoid(\n                        reference_points)\n                    new_reference_points = new_reference_points.sigmoid()\n                else:\n                    assert reference_points.shape[-1] == 2\n                    new_reference_points = tmp\n                    new_reference_points[..., :2] = tmp[\n                        ..., :2] + inverse_sigmoid(reference_points)\n                    new_reference_points = new_reference_points.sigmoid()\n                reference_points = new_reference_points.detach()\n\n            output = output.permute(1, 0, 2)\n            if self.return_intermediate:\n                intermediate.append(output)\n                intermediate_reference_points.append(reference_points)\n\n        if self.return_intermediate:\n            return torch.stack(intermediate), torch.stack(\n                intermediate_reference_points)\n\n        return output, reference_points\n\n\n@TRANSFORMER.register_module()\nclass DeformableDetrTransformer(Transformer):\n    \"\"\"Implements the DeformableDETR transformer.\n\n    Args:\n        as_two_stage (bool): Generate query from encoder features.\n            Default: False.\n        num_feature_levels (int): Number of feature maps from FPN:\n            Default: 4.\n        two_stage_num_proposals (int): Number of proposals when set\n            `as_two_stage` as True. Default: 300.\n    \"\"\"\n\n    def __init__(self,\n                 as_two_stage=False,\n                 num_feature_levels=4,\n                 two_stage_num_proposals=300,\n                 **kwargs):\n        super(DeformableDetrTransformer, self).__init__(**kwargs)\n        self.as_two_stage = as_two_stage\n        self.num_feature_levels = num_feature_levels\n        self.two_stage_num_proposals = two_stage_num_proposals\n        self.embed_dims = self.encoder.embed_dims\n        self.init_layers()\n\n    def init_layers(self):\n        \"\"\"Initialize layers of the DeformableDetrTransformer.\"\"\"\n        self.level_embeds = nn.Parameter(\n            torch.Tensor(self.num_feature_levels, self.embed_dims))\n\n        if self.as_two_stage:\n            self.enc_output = nn.Linear(self.embed_dims, self.embed_dims)\n            self.enc_output_norm = nn.LayerNorm(self.embed_dims)\n            self.pos_trans = nn.Linear(self.embed_dims * 2,\n                                       self.embed_dims * 2)\n            self.pos_trans_norm = nn.LayerNorm(self.embed_dims * 2)\n        else:\n            self.reference_points = nn.Linear(self.embed_dims, 2)\n\n    def init_weights(self):\n        \"\"\"Initialize the transformer weights.\"\"\"\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if isinstance(m, MultiScaleDeformableAttention):\n                m.init_weights()\n        if not self.as_two_stage:\n            xavier_init(self.reference_points, distribution='uniform', bias=0.)\n        normal_(self.level_embeds)\n\n    def gen_encoder_output_proposals(self, memory, memory_padding_mask,\n                                     spatial_shapes):\n        \"\"\"Generate proposals from encoded memory.\n\n        Args:\n            memory (Tensor) : The output of encoder,\n                has shape (bs, num_key, embed_dim).  num_key is\n                equal the number of points on feature map from\n                all level.\n            memory_padding_mask (Tensor): Padding mask for memory.\n                has shape (bs, num_key).\n            spatial_shapes (Tensor): The shape of all feature maps.\n                has shape (num_level, 2).\n\n        Returns:\n            tuple: A tuple of feature map and bbox prediction.\n\n                - output_memory (Tensor): The input of decoder,  \\\n                    has shape (bs, num_key, embed_dim).  num_key is \\\n                    equal the number of points on feature map from \\\n                    all levels.\n                - output_proposals (Tensor): The normalized proposal \\\n                    after a inverse sigmoid, has shape \\\n                    (bs, num_keys, 4).\n        \"\"\"\n\n        N, S, C = memory.shape\n        proposals = []\n        _cur = 0\n        for lvl, (H, W) in enumerate(spatial_shapes):\n            mask_flatten_ = memory_padding_mask[:, _cur:(_cur + H * W)].view(\n                N, H, W, 1)\n            valid_H = torch.sum(~mask_flatten_[:, :, 0, 0], 1)\n            valid_W = torch.sum(~mask_flatten_[:, 0, :, 0], 1)\n\n            grid_y, grid_x = torch.meshgrid(\n                torch.linspace(\n                    0, H - 1, H, dtype=torch.float32, device=memory.device),\n                torch.linspace(\n                    0, W - 1, W, dtype=torch.float32, device=memory.device))\n            grid = torch.cat([grid_x.unsqueeze(-1), grid_y.unsqueeze(-1)], -1)\n\n            scale = torch.cat([valid_W.unsqueeze(-1),\n                               valid_H.unsqueeze(-1)], 1).view(N, 1, 1, 2)\n            grid = (grid.unsqueeze(0).expand(N, -1, -1, -1) + 0.5) / scale\n            wh = torch.ones_like(grid) * 0.05 * (2.0**lvl)\n            proposal = torch.cat((grid, wh), -1).view(N, -1, 4)\n            proposals.append(proposal)\n            _cur += (H * W)\n        output_proposals = torch.cat(proposals, 1)\n        output_proposals_valid = ((output_proposals > 0.01) &\n                                  (output_proposals < 0.99)).all(\n                                      -1, keepdim=True)\n        output_proposals = torch.log(output_proposals / (1 - output_proposals))\n        output_proposals = output_proposals.masked_fill(\n            memory_padding_mask.unsqueeze(-1), float('inf'))\n        output_proposals = output_proposals.masked_fill(\n            ~output_proposals_valid, float('inf'))\n\n        output_memory = memory\n        output_memory = output_memory.masked_fill(\n            memory_padding_mask.unsqueeze(-1), float(0))\n        output_memory = output_memory.masked_fill(~output_proposals_valid,\n                                                  float(0))\n        output_memory = self.enc_output_norm(self.enc_output(output_memory))\n        return output_memory, output_proposals\n\n    @staticmethod\n    def get_reference_points(spatial_shapes, valid_ratios, device):\n        \"\"\"Get the reference points used in decoder.\n\n        Args:\n            spatial_shapes (Tensor): The shape of all\n                feature maps, has shape (num_level, 2).\n            valid_ratios (Tensor): The radios of valid\n                points on the feature map, has shape\n                (bs, num_levels, 2)\n            device (obj:`device`): The device where\n                reference_points should be.\n\n        Returns:\n            Tensor: reference points used in decoder, has \\\n                shape (bs, num_keys, num_levels, 2).\n        \"\"\"\n        reference_points_list = []\n        for lvl, (H, W) in enumerate(spatial_shapes):\n            #  TODO  check this 0.5\n            ref_y, ref_x = torch.meshgrid(\n                torch.linspace(\n                    0.5, H - 0.5, H, dtype=torch.float32, device=device),\n                torch.linspace(\n                    0.5, W - 0.5, W, dtype=torch.float32, device=device))\n            ref_y = ref_y.reshape(-1)[None] / (\n                valid_ratios[:, None, lvl, 1] * H)\n            ref_x = ref_x.reshape(-1)[None] / (\n                valid_ratios[:, None, lvl, 0] * W)\n            ref = torch.stack((ref_x, ref_y), -1)\n            reference_points_list.append(ref)\n        reference_points = torch.cat(reference_points_list, 1)\n        reference_points = reference_points[:, :, None] * valid_ratios[:, None]\n        return reference_points\n\n    def get_valid_ratio(self, mask):\n        \"\"\"Get the valid radios of feature maps of all  level.\"\"\"\n        _, H, W = mask.shape\n        valid_H = torch.sum(~mask[:, :, 0], 1)\n        valid_W = torch.sum(~mask[:, 0, :], 1)\n        valid_ratio_h = valid_H.float() / H\n        valid_ratio_w = valid_W.float() / W\n        valid_ratio = torch.stack([valid_ratio_w, valid_ratio_h], -1)\n        return valid_ratio\n\n    def get_proposal_pos_embed(self,\n                               proposals,\n                               num_pos_feats=128,\n                               temperature=10000):\n        \"\"\"Get the position embedding of proposal.\"\"\"\n        scale = 2 * math.pi\n        dim_t = torch.arange(\n            num_pos_feats, dtype=torch.float32, device=proposals.device)\n        dim_t = temperature**(2 * (dim_t // 2) / num_pos_feats)\n        # N, L, 4\n        proposals = proposals.sigmoid() * scale\n        # N, L, 4, 128\n        pos = proposals[:, :, :, None] / dim_t\n        # N, L, 4, 64, 2\n        pos = torch.stack((pos[:, :, :, 0::2].sin(), pos[:, :, :, 1::2].cos()),\n                          dim=4).flatten(2)\n        return pos\n\n    def forward(self,\n                mlvl_feats,\n                mlvl_masks,\n                query_embed,\n                mlvl_pos_embeds,\n                reg_branches=None,\n                cls_branches=None,\n                **kwargs):\n        \"\"\"Forward function for `Transformer`.\n\n        Args:\n            mlvl_feats (list(Tensor)): Input queries from\n                different level. Each element has shape\n                [bs, embed_dims, h, w].\n            mlvl_masks (list(Tensor)): The key_padding_mask from\n                different level used for encoder and decoder,\n                each element has shape  [bs, h, w].\n            query_embed (Tensor): The query embedding for decoder,\n                with shape [num_query, c].\n            mlvl_pos_embeds (list(Tensor)): The positional encoding\n                of feats from different level, has the shape\n                 [bs, embed_dims, h, w].\n            reg_branches (obj:`nn.ModuleList`): Regression heads for\n                feature maps from each decoder layer. Only would\n                be passed when\n                `with_box_refine` is True. Default to None.\n            cls_branches (obj:`nn.ModuleList`): Classification heads\n                for feature maps from each decoder layer. Only would\n                 be passed when `as_two_stage`\n                 is True. Default to None.\n\n\n        Returns:\n            tuple[Tensor]: results of decoder containing the following tensor.\n\n                - inter_states: Outputs from decoder. If\n                    return_intermediate_dec is True output has shape \\\n                      (num_dec_layers, bs, num_query, embed_dims), else has \\\n                      shape (1, bs, num_query, embed_dims).\n                - init_reference_out: The initial value of reference \\\n                    points, has shape (bs, num_queries, 4).\n                - inter_references_out: The internal value of reference \\\n                    points in decoder, has shape \\\n                    (num_dec_layers, bs,num_query, embed_dims)\n                - enc_outputs_class: The classification score of \\\n                    proposals generated from \\\n                    encoder's feature maps, has shape \\\n                    (batch, h*w, num_classes). \\\n                    Only would be returned when `as_two_stage` is True, \\\n                    otherwise None.\n                - enc_outputs_coord_unact: The regression results \\\n                    generated from encoder's feature maps., has shape \\\n                    (batch, h*w, 4). Only would \\\n                    be returned when `as_two_stage` is True, \\\n                    otherwise None.\n        \"\"\"\n        assert self.as_two_stage or query_embed is not None\n\n        feat_flatten = []\n        mask_flatten = []\n        lvl_pos_embed_flatten = []\n        spatial_shapes = []\n        for lvl, (feat, mask, pos_embed) in enumerate(\n                zip(mlvl_feats, mlvl_masks, mlvl_pos_embeds)):\n            bs, c, h, w = feat.shape\n            spatial_shape = (h, w)\n            spatial_shapes.append(spatial_shape)\n            feat = feat.flatten(2).transpose(1, 2)\n            mask = mask.flatten(1)\n            pos_embed = pos_embed.flatten(2).transpose(1, 2)\n            lvl_pos_embed = pos_embed + self.level_embeds[lvl].view(1, 1, -1)\n            lvl_pos_embed_flatten.append(lvl_pos_embed)\n            feat_flatten.append(feat)\n            mask_flatten.append(mask)\n        feat_flatten = torch.cat(feat_flatten, 1)\n        mask_flatten = torch.cat(mask_flatten, 1)\n        lvl_pos_embed_flatten = torch.cat(lvl_pos_embed_flatten, 1)\n        spatial_shapes = torch.as_tensor(\n            spatial_shapes, dtype=torch.long, device=feat_flatten.device)\n        level_start_index = torch.cat((spatial_shapes.new_zeros(\n            (1, )), spatial_shapes.prod(1).cumsum(0)[:-1]))\n        valid_ratios = torch.stack(\n            [self.get_valid_ratio(m) for m in mlvl_masks], 1)\n\n        reference_points = \\\n            self.get_reference_points(spatial_shapes,\n                                      valid_ratios,\n                                      device=feat.device)\n\n        feat_flatten = feat_flatten.permute(1, 0, 2)  # (H*W, bs, embed_dims)\n        lvl_pos_embed_flatten = lvl_pos_embed_flatten.permute(\n            1, 0, 2)  # (H*W, bs, embed_dims)\n        memory = self.encoder(\n            query=feat_flatten,\n            key=None,\n            value=None,\n            query_pos=lvl_pos_embed_flatten,\n            query_key_padding_mask=mask_flatten,\n            spatial_shapes=spatial_shapes,\n            reference_points=reference_points,\n            level_start_index=level_start_index,\n            valid_ratios=valid_ratios,\n            **kwargs)\n\n        memory = memory.permute(1, 0, 2)\n        bs, _, c = memory.shape\n        if self.as_two_stage:\n            output_memory, output_proposals = \\\n                self.gen_encoder_output_proposals(\n                    memory, mask_flatten, spatial_shapes)\n            enc_outputs_class = cls_branches[self.decoder.num_layers](\n                output_memory)\n            enc_outputs_coord_unact = \\\n                reg_branches[\n                    self.decoder.num_layers](output_memory) + output_proposals\n\n            topk = self.two_stage_num_proposals\n            topk_proposals = torch.topk(\n                enc_outputs_class[..., 0], topk, dim=1)[1]\n            topk_coords_unact = torch.gather(\n                enc_outputs_coord_unact, 1,\n                topk_proposals.unsqueeze(-1).repeat(1, 1, 4))\n            topk_coords_unact = topk_coords_unact.detach()\n            reference_points = topk_coords_unact.sigmoid()\n            init_reference_out = reference_points\n            pos_trans_out = self.pos_trans_norm(\n                self.pos_trans(self.get_proposal_pos_embed(topk_coords_unact)))\n            query_pos, query = torch.split(pos_trans_out, c, dim=2)\n        else:\n            query_pos, query = torch.split(query_embed, c, dim=1)\n            query_pos = query_pos.unsqueeze(0).expand(bs, -1, -1)\n            query = query.unsqueeze(0).expand(bs, -1, -1)\n            reference_points = self.reference_points(query_pos).sigmoid()\n            init_reference_out = reference_points\n\n        # decoder\n        query = query.permute(1, 0, 2)\n        memory = memory.permute(1, 0, 2)\n        query_pos = query_pos.permute(1, 0, 2)\n        inter_states, inter_references = self.decoder(\n            query=query,\n            key=None,\n            value=memory,\n            query_pos=query_pos,\n            key_padding_mask=mask_flatten,\n            reference_points=reference_points,\n            spatial_shapes=spatial_shapes,\n            level_start_index=level_start_index,\n            valid_ratios=valid_ratios,\n            reg_branches=reg_branches,\n            **kwargs)\n\n        inter_references_out = inter_references\n        if self.as_two_stage:\n            return inter_states, init_reference_out,\\\n                inter_references_out, enc_outputs_class,\\\n                enc_outputs_coord_unact\n        return inter_states, init_reference_out, \\\n            inter_references_out, None, None\n\n\n@TRANSFORMER.register_module()\nclass DynamicConv(BaseModule):\n    \"\"\"Implements Dynamic Convolution.\n\n    This module generate parameters for each sample and\n    use bmm to implement 1*1 convolution. Code is modified\n    from the `official github repo <https://github.com/PeizeSun/\n    SparseR-CNN/blob/main/projects/SparseRCNN/sparsercnn/head.py#L258>`_ .\n\n    Args:\n        in_channels (int): The input feature channel.\n            Defaults to 256.\n        feat_channels (int): The inner feature channel.\n            Defaults to 64.\n        out_channels (int, optional): The output feature channel.\n            When not specified, it will be set to `in_channels`\n            by default\n        input_feat_shape (int): The shape of input feature.\n            Defaults to 7.\n        act_cfg (dict): The activation config for DynamicConv.\n        norm_cfg (dict): Config dict for normalization layer. Default\n            layer normalization.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 in_channels=256,\n                 feat_channels=64,\n                 out_channels=None,\n                 input_feat_shape=7,\n                 act_cfg=dict(type='ReLU', inplace=True),\n                 norm_cfg=dict(type='LN'),\n                 init_cfg=None):\n        super(DynamicConv, self).__init__(init_cfg)\n        self.in_channels = in_channels\n        self.feat_channels = feat_channels\n        self.out_channels_raw = out_channels\n        self.input_feat_shape = input_feat_shape\n        self.act_cfg = act_cfg\n        self.norm_cfg = norm_cfg\n        self.out_channels = out_channels if out_channels else in_channels\n\n        self.num_params_in = self.in_channels * self.feat_channels\n        self.num_params_out = self.out_channels * self.feat_channels\n        self.dynamic_layer = nn.Linear(\n            self.in_channels, self.num_params_in + self.num_params_out)\n\n        self.norm_in = build_norm_layer(norm_cfg, self.feat_channels)[1]\n        self.norm_out = build_norm_layer(norm_cfg, self.out_channels)[1]\n\n        self.activation = build_activation_layer(act_cfg)\n\n        num_output = self.out_channels * input_feat_shape**2\n        self.fc_layer = nn.Linear(num_output, self.out_channels)\n        self.fc_norm = build_norm_layer(norm_cfg, self.out_channels)[1]\n\n    def forward(self, param_feature, input_feature):\n        \"\"\"Forward function for `DynamicConv`.\n\n        Args:\n            param_feature (Tensor): The feature can be used\n                to generate the parameter, has shape\n                (num_all_proposals, in_channels).\n            input_feature (Tensor): Feature that\n                interact with parameters, has shape\n                (num_all_proposals, in_channels, H, W).\n\n        Returns:\n            Tensor: The output feature has shape\n            (num_all_proposals, out_channels).\n        \"\"\"\n        num_proposals = param_feature.size(0)\n        input_feature = input_feature.view(num_proposals, self.in_channels,\n                                           -1).permute(2, 0, 1)\n\n        input_feature = input_feature.permute(1, 0, 2)\n        parameters = self.dynamic_layer(param_feature)\n\n        param_in = parameters[:, :self.num_params_in].view(\n            -1, self.in_channels, self.feat_channels)\n        param_out = parameters[:, -self.num_params_out:].view(\n            -1, self.feat_channels, self.out_channels)\n\n        # input_feature has shape (num_all_proposals, H*W, in_channels)\n        # param_in has shape (num_all_proposals, in_channels, feat_channels)\n        # feature has shape (num_all_proposals, H*W, feat_channels)\n        features = torch.bmm(input_feature, param_in)\n        features = self.norm_in(features)\n        features = self.activation(features)\n\n        # param_out has shape (batch_size, feat_channels, out_channels)\n        features = torch.bmm(features, param_out)\n        features = self.norm_out(features)\n        features = self.activation(features)\n\n        features = features.flatten(1)\n        features = self.fc_layer(features)\n        features = self.fc_norm(features)\n        features = self.activation(features)\n\n        return features\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/utils/weight_init.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport math\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nfrom torch import Tensor\n\nfrom mmcv.utils import Registry, build_from_cfg, get_logger, print_log\n\nINITIALIZERS = Registry('initializer')\n\n\ndef update_init_info(module, init_info):\n    \"\"\"Update the `_params_init_info` in the module if the value of parameters\n    are changed.\n\n    Args:\n        module (obj:`nn.Module`): The module of PyTorch with a user-defined\n            attribute `_params_init_info` which records the initialization\n            information.\n        init_info (str): The string that describes the initialization.\n    \"\"\"\n    assert hasattr(\n        module,\n        '_params_init_info'), f'Can not find `_params_init_info` in {module}'\n    for name, param in module.named_parameters():\n\n        assert param in module._params_init_info, (\n            f'Find a new :obj:`Parameter` '\n            f'named `{name}` during executing the '\n            f'`init_weights` of '\n            f'`{module.__class__.__name__}`. '\n            f'Please do not add or '\n            f'replace parameters during executing '\n            f'the `init_weights`. ')\n\n        # The parameter has been changed during executing the\n        # `init_weights` of module\n        mean_value = param.data.mean()\n        if module._params_init_info[param]['tmp_mean_value'] != mean_value:\n            module._params_init_info[param]['init_info'] = init_info\n            module._params_init_info[param]['tmp_mean_value'] = mean_value\n\n\ndef constant_init(module, val, bias=0):\n    if hasattr(module, 'weight') and module.weight is not None:\n        nn.init.constant_(module.weight, val)\n    if hasattr(module, 'bias') and module.bias is not None:\n        nn.init.constant_(module.bias, bias)\n\n\ndef xavier_init(module, gain=1, bias=0, distribution='normal'):\n    assert distribution in ['uniform', 'normal']\n    if hasattr(module, 'weight') and module.weight is not None:\n        if distribution == 'uniform':\n            nn.init.xavier_uniform_(module.weight, gain=gain)\n        else:\n            nn.init.xavier_normal_(module.weight, gain=gain)\n    if hasattr(module, 'bias') and module.bias is not None:\n        nn.init.constant_(module.bias, bias)\n\n\ndef normal_init(module, mean=0, std=1, bias=0):\n    if hasattr(module, 'weight') and module.weight is not None:\n        nn.init.normal_(module.weight, mean, std)\n    if hasattr(module, 'bias') and module.bias is not None:\n        nn.init.constant_(module.bias, bias)\n\n\ndef trunc_normal_init(module: nn.Module,\n                      mean: float = 0,\n                      std: float = 1,\n                      a: float = -2,\n                      b: float = 2,\n                      bias: float = 0) -> None:\n    if hasattr(module, 'weight') and module.weight is not None:\n        trunc_normal_(module.weight, mean, std, a, b)  # type: ignore\n    if hasattr(module, 'bias') and module.bias is not None:\n        nn.init.constant_(module.bias, bias)  # type: ignore\n\n\ndef uniform_init(module, a=0, b=1, bias=0):\n    if hasattr(module, 'weight') and module.weight is not None:\n        nn.init.uniform_(module.weight, a, b)\n    if hasattr(module, 'bias') and module.bias is not None:\n        nn.init.constant_(module.bias, bias)\n\n\ndef kaiming_init(module,\n                 a=0,\n                 mode='fan_out',\n                 nonlinearity='relu',\n                 bias=0,\n                 distribution='normal'):\n    assert distribution in ['uniform', 'normal']\n    if hasattr(module, 'weight') and module.weight is not None:\n        if distribution == 'uniform':\n            nn.init.kaiming_uniform_(\n                module.weight, a=a, mode=mode, nonlinearity=nonlinearity)\n        else:\n            nn.init.kaiming_normal_(\n                module.weight, a=a, mode=mode, nonlinearity=nonlinearity)\n    if hasattr(module, 'bias') and module.bias is not None:\n        nn.init.constant_(module.bias, bias)\n\n\ndef caffe2_xavier_init(module, bias=0):\n    # `XavierFill` in Caffe2 corresponds to `kaiming_uniform_` in PyTorch\n    # Acknowledgment to FAIR's internal code\n    kaiming_init(\n        module,\n        a=1,\n        mode='fan_in',\n        nonlinearity='leaky_relu',\n        bias=bias,\n        distribution='uniform')\n\n\ndef bias_init_with_prob(prior_prob):\n    \"\"\"initialize conv/fc bias value according to a given probability value.\"\"\"\n    bias_init = float(-np.log((1 - prior_prob) / prior_prob))\n    return bias_init\n\n\ndef _get_bases_name(m):\n    return [b.__name__ for b in m.__class__.__bases__]\n\n\nclass BaseInit(object):\n\n    def __init__(self, *, bias=0, bias_prob=None, layer=None):\n        self.wholemodule = False\n        if not isinstance(bias, (int, float)):\n            raise TypeError(f'bias must be a number, but got a {type(bias)}')\n\n        if bias_prob is not None:\n            if not isinstance(bias_prob, float):\n                raise TypeError(f'bias_prob type must be float, \\\n                    but got {type(bias_prob)}')\n\n        if layer is not None:\n            if not isinstance(layer, (str, list)):\n                raise TypeError(f'layer must be a str or a list of str, \\\n                    but got a {type(layer)}')\n        else:\n            layer = []\n\n        if bias_prob is not None:\n            self.bias = bias_init_with_prob(bias_prob)\n        else:\n            self.bias = bias\n        self.layer = [layer] if isinstance(layer, str) else layer\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='Constant')\nclass ConstantInit(BaseInit):\n    \"\"\"Initialize module parameters with constant values.\n\n    Args:\n        val (int | float): the value to fill the weights in the module with\n        bias (int | float): the value to fill the bias. Defaults to 0.\n        bias_prob (float, optional): the probability for bias initialization.\n            Defaults to None.\n        layer (str | list[str], optional): the layer will be initialized.\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, val, **kwargs):\n        super().__init__(**kwargs)\n        self.val = val\n\n    def __call__(self, module):\n\n        def init(m):\n            if self.wholemodule:\n                constant_init(m, self.val, self.bias)\n            else:\n                layername = m.__class__.__name__\n                basesname = _get_bases_name(m)\n                if len(set(self.layer) & set([layername] + basesname)):\n                    constant_init(m, self.val, self.bias)\n\n        module.apply(init)\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: val={self.val}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='Xavier')\nclass XavierInit(BaseInit):\n    r\"\"\"Initialize module parameters with values according to the method\n    described in `Understanding the difficulty of training deep feedforward\n    neural networks - Glorot, X. & Bengio, Y. (2010).\n    <http://proceedings.mlr.press/v9/glorot10a/glorot10a.pdf>`_\n\n    Args:\n        gain (int | float): an optional scaling factor. Defaults to 1.\n        bias (int | float): the value to fill the bias. Defaults to 0.\n        bias_prob (float, optional): the probability for bias initialization.\n            Defaults to None.\n        distribution (str): distribution either be ``'normal'``\n            or ``'uniform'``. Defaults to ``'normal'``.\n        layer (str | list[str], optional): the layer will be initialized.\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, gain=1, distribution='normal', **kwargs):\n        super().__init__(**kwargs)\n        self.gain = gain\n        self.distribution = distribution\n\n    def __call__(self, module):\n\n        def init(m):\n            if self.wholemodule:\n                xavier_init(m, self.gain, self.bias, self.distribution)\n            else:\n                layername = m.__class__.__name__\n                basesname = _get_bases_name(m)\n                if len(set(self.layer) & set([layername] + basesname)):\n                    xavier_init(m, self.gain, self.bias, self.distribution)\n\n        module.apply(init)\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: gain={self.gain}, ' \\\n               f'distribution={self.distribution}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='Normal')\nclass NormalInit(BaseInit):\n    r\"\"\"Initialize module parameters with the values drawn from the normal\n    distribution :math:`\\mathcal{N}(\\text{mean}, \\text{std}^2)`.\n\n    Args:\n        mean (int | float):the mean of the normal distribution. Defaults to 0.\n        std (int | float): the standard deviation of the normal distribution.\n            Defaults to 1.\n        bias (int | float): the value to fill the bias. Defaults to 0.\n        bias_prob (float, optional): the probability for bias initialization.\n            Defaults to None.\n        layer (str | list[str], optional): the layer will be initialized.\n            Defaults to None.\n\n    \"\"\"\n\n    def __init__(self, mean=0, std=1, **kwargs):\n        super().__init__(**kwargs)\n        self.mean = mean\n        self.std = std\n\n    def __call__(self, module):\n\n        def init(m):\n            if self.wholemodule:\n                normal_init(m, self.mean, self.std, self.bias)\n            else:\n                layername = m.__class__.__name__\n                basesname = _get_bases_name(m)\n                if len(set(self.layer) & set([layername] + basesname)):\n                    normal_init(m, self.mean, self.std, self.bias)\n\n        module.apply(init)\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: mean={self.mean},' \\\n               f' std={self.std}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='TruncNormal')\nclass TruncNormalInit(BaseInit):\n    r\"\"\"Initialize module parameters with the values drawn from the normal\n    distribution :math:`\\mathcal{N}(\\text{mean}, \\text{std}^2)` with values\n    outside :math:`[a, b]`.\n\n    Args:\n        mean (float): the mean of the normal distribution. Defaults to 0.\n        std (float):  the standard deviation of the normal distribution.\n            Defaults to 1.\n        a (float): The minimum cutoff value.\n        b ( float): The maximum cutoff value.\n        bias (float): the value to fill the bias. Defaults to 0.\n        bias_prob (float, optional): the probability for bias initialization.\n            Defaults to None.\n        layer (str | list[str], optional): the layer will be initialized.\n            Defaults to None.\n\n    \"\"\"\n\n    def __init__(self,\n                 mean: float = 0,\n                 std: float = 1,\n                 a: float = -2,\n                 b: float = 2,\n                 **kwargs) -> None:\n        super().__init__(**kwargs)\n        self.mean = mean\n        self.std = std\n        self.a = a\n        self.b = b\n\n    def __call__(self, module: nn.Module) -> None:\n\n        def init(m):\n            if self.wholemodule:\n                trunc_normal_init(m, self.mean, self.std, self.a, self.b,\n                                  self.bias)\n            else:\n                layername = m.__class__.__name__\n                basesname = _get_bases_name(m)\n                if len(set(self.layer) & set([layername] + basesname)):\n                    trunc_normal_init(m, self.mean, self.std, self.a, self.b,\n                                      self.bias)\n\n        module.apply(init)\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: a={self.a}, b={self.b},' \\\n               f' mean={self.mean}, std={self.std}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='Uniform')\nclass UniformInit(BaseInit):\n    r\"\"\"Initialize module parameters with values drawn from the uniform\n    distribution :math:`\\mathcal{U}(a, b)`.\n\n    Args:\n        a (int | float): the lower bound of the uniform distribution.\n            Defaults to 0.\n        b (int | float): the upper bound of the uniform distribution.\n            Defaults to 1.\n        bias (int | float): the value to fill the bias. Defaults to 0.\n        bias_prob (float, optional): the probability for bias initialization.\n            Defaults to None.\n        layer (str | list[str], optional): the layer will be initialized.\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, a=0, b=1, **kwargs):\n        super().__init__(**kwargs)\n        self.a = a\n        self.b = b\n\n    def __call__(self, module):\n\n        def init(m):\n            if self.wholemodule:\n                uniform_init(m, self.a, self.b, self.bias)\n            else:\n                layername = m.__class__.__name__\n                basesname = _get_bases_name(m)\n                if len(set(self.layer) & set([layername] + basesname)):\n                    uniform_init(m, self.a, self.b, self.bias)\n\n        module.apply(init)\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: a={self.a},' \\\n               f' b={self.b}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='Kaiming')\nclass KaimingInit(BaseInit):\n    r\"\"\"Initialize module parameters with the values according to the method\n    described in `Delving deep into rectifiers: Surpassing human-level\n    performance on ImageNet classification - He, K. et al. (2015).\n    <https://www.cv-foundation.org/openaccess/content_iccv_2015/\n    papers/He_Delving_Deep_into_ICCV_2015_paper.pdf>`_\n\n    Args:\n        a (int | float): the negative slope of the rectifier used after this\n            layer (only used with ``'leaky_relu'``). Defaults to 0.\n        mode (str):  either ``'fan_in'`` or ``'fan_out'``. Choosing\n            ``'fan_in'`` preserves the magnitude of the variance of the weights\n            in the forward pass. Choosing ``'fan_out'`` preserves the\n            magnitudes in the backwards pass. Defaults to ``'fan_out'``.\n        nonlinearity (str): the non-linear function (`nn.functional` name),\n            recommended to use only with ``'relu'`` or ``'leaky_relu'`` .\n            Defaults to 'relu'.\n        bias (int | float): the value to fill the bias. Defaults to 0.\n        bias_prob (float, optional): the probability for bias initialization.\n            Defaults to None.\n        distribution (str): distribution either be ``'normal'`` or\n            ``'uniform'``. Defaults to ``'normal'``.\n        layer (str | list[str], optional): the layer will be initialized.\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self,\n                 a=0,\n                 mode='fan_out',\n                 nonlinearity='relu',\n                 distribution='normal',\n                 **kwargs):\n        super().__init__(**kwargs)\n        self.a = a\n        self.mode = mode\n        self.nonlinearity = nonlinearity\n        self.distribution = distribution\n\n    def __call__(self, module):\n\n        def init(m):\n            if self.wholemodule:\n                kaiming_init(m, self.a, self.mode, self.nonlinearity,\n                             self.bias, self.distribution)\n            else:\n                layername = m.__class__.__name__\n                basesname = _get_bases_name(m)\n                if len(set(self.layer) & set([layername] + basesname)):\n                    kaiming_init(m, self.a, self.mode, self.nonlinearity,\n                                 self.bias, self.distribution)\n\n        module.apply(init)\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: a={self.a}, mode={self.mode}, ' \\\n               f'nonlinearity={self.nonlinearity}, ' \\\n               f'distribution ={self.distribution}, bias={self.bias}'\n        return info\n\n\n@INITIALIZERS.register_module(name='Caffe2Xavier')\nclass Caffe2XavierInit(KaimingInit):\n    # `XavierFill` in Caffe2 corresponds to `kaiming_uniform_` in PyTorch\n    # Acknowledgment to FAIR's internal code\n    def __init__(self, **kwargs):\n        super().__init__(\n            a=1,\n            mode='fan_in',\n            nonlinearity='leaky_relu',\n            distribution='uniform',\n            **kwargs)\n\n    def __call__(self, module):\n        super().__call__(module)\n\n\n@INITIALIZERS.register_module(name='Pretrained')\nclass PretrainedInit(object):\n    \"\"\"Initialize module by loading a pretrained model.\n\n    Args:\n        checkpoint (str): the checkpoint file of the pretrained model should\n            be load.\n        prefix (str, optional): the prefix of a sub-module in the pretrained\n            model. it is for loading a part of the pretrained model to\n            initialize. For example, if we would like to only load the\n            backbone of a detector model, we can set ``prefix='backbone.'``.\n            Defaults to None.\n        map_location (str): map tensors into proper locations.\n    \"\"\"\n\n    def __init__(self, checkpoint, prefix=None, map_location=None):\n        self.checkpoint = checkpoint\n        self.prefix = prefix\n        self.map_location = map_location\n\n    def __call__(self, module):\n        from mmcv.utils import load_checkpoint\n        logger = get_logger('mmcv')\n        if self.prefix is None:\n            print_log(f'load model from: {self.checkpoint}', logger=logger)\n            load_checkpoint(\n                module,\n                self.checkpoint,\n                map_location=self.map_location,\n                strict=False,\n                logger=logger)\n        else:\n            print_log(\n                f'load {self.prefix} in model from: {self.checkpoint}',\n                logger=logger)\n            state_dict = _load_checkpoint_with_prefix(\n                self.prefix, self.checkpoint, map_location=self.map_location)\n            load_state_dict(module, state_dict, strict=False, logger=logger)\n\n        if hasattr(module, '_params_init_info'):\n            update_init_info(module, init_info=self._get_init_info())\n\n    def _get_init_info(self):\n        info = f'{self.__class__.__name__}: load from {self.checkpoint}'\n        return info\n\n\ndef _initialize(module, cfg, wholemodule=False):\n    func = build_from_cfg(cfg, INITIALIZERS)\n    # wholemodule flag is for override mode, there is no layer key in override\n    # and initializer will give init values for the whole module with the name\n    # in override.\n    func.wholemodule = wholemodule\n    func(module)\n\n\ndef _initialize_override(module, override, cfg):\n    if not isinstance(override, (dict, list)):\n        raise TypeError(f'override must be a dict or a list of dict, \\\n                but got {type(override)}')\n\n    override = [override] if isinstance(override, dict) else override\n\n    for override_ in override:\n\n        cp_override = copy.deepcopy(override_)\n        name = cp_override.pop('name', None)\n        if name is None:\n            raise ValueError('`override` must contain the key \"name\",'\n                             f'but got {cp_override}')\n        # if override only has name key, it means use args in init_cfg\n        if not cp_override:\n            cp_override.update(cfg)\n        # if override has name key and other args except type key, it will\n        # raise error\n        elif 'type' not in cp_override.keys():\n            raise ValueError(\n                f'`override` need \"type\" key, but got {cp_override}')\n\n        if hasattr(module, name):\n            _initialize(getattr(module, name), cp_override, wholemodule=True)\n        else:\n            raise RuntimeError(f'module did not have attribute {name}, '\n                               f'but init_cfg is {cp_override}.')\n\n\ndef initialize(module, init_cfg):\n    \"\"\"Initialize a module.\n\n    Args:\n        module (``torch.nn.Module``): the module will be initialized.\n        init_cfg (dict | list[dict]): initialization configuration dict to\n            define initializer. OpenMMLab has implemented 6 initializers\n            including ``Constant``, ``Xavier``, ``Normal``, ``Uniform``,\n            ``Kaiming``, and ``Pretrained``.\n    Example:\n        >>> module = nn.Linear(2, 3, bias=True)\n        >>> init_cfg = dict(type='Constant', layer='Linear', val =1 , bias =2)\n        >>> initialize(module, init_cfg)\n\n        >>> module = nn.Sequential(nn.Conv1d(3, 1, 3), nn.Linear(1,2))\n        >>> # define key ``'layer'`` for initializing layer with different\n        >>> # configuration\n        >>> init_cfg = [dict(type='Constant', layer='Conv1d', val=1),\n                dict(type='Constant', layer='Linear', val=2)]\n        >>> initialize(module, init_cfg)\n\n        >>> # define key``'override'`` to initialize some specific part in\n        >>> # module\n        >>> class FooNet(nn.Module):\n        >>>     def __init__(self):\n        >>>         super().__init__()\n        >>>         self.feat = nn.Conv2d(3, 16, 3)\n        >>>         self.reg = nn.Conv2d(16, 10, 3)\n        >>>         self.cls = nn.Conv2d(16, 5, 3)\n        >>> model = FooNet()\n        >>> init_cfg = dict(type='Constant', val=1, bias=2, layer='Conv2d',\n        >>>     override=dict(type='Constant', name='reg', val=3, bias=4))\n        >>> initialize(model, init_cfg)\n\n        >>> model = ResNet(depth=50)\n        >>> # Initialize weights with the pretrained model.\n        >>> init_cfg = dict(type='Pretrained',\n                checkpoint='torchvision://resnet50')\n        >>> initialize(model, init_cfg)\n\n        >>> # Initialize weights of a sub-module with the specific part of\n        >>> # a pretrained model by using \"prefix\".\n        >>> url = 'http://download.openmmlab.com/mmdetection/v2.0/retinanet/'\\\n        >>>     'retinanet_r50_fpn_1x_coco/'\\\n        >>>     'retinanet_r50_fpn_1x_coco_20200130-c2398f9e.pth'\n        >>> init_cfg = dict(type='Pretrained',\n                checkpoint=url, prefix='backbone.')\n    \"\"\"\n    if not isinstance(init_cfg, (dict, list)):\n        raise TypeError(f'init_cfg must be a dict or a list of dict, \\\n                but got {type(init_cfg)}')\n\n    if isinstance(init_cfg, dict):\n        init_cfg = [init_cfg]\n\n    for cfg in init_cfg:\n        # should deeply copy the original config because cfg may be used by\n        # other modules, e.g., one init_cfg shared by multiple bottleneck\n        # blocks, the expected cfg will be changed after pop and will change\n        # the initialization behavior of other modules\n        cp_cfg = copy.deepcopy(cfg)\n        override = cp_cfg.pop('override', None)\n        _initialize(module, cp_cfg)\n\n        if override is not None:\n            cp_cfg.pop('layer', None)\n            _initialize_override(module, override, cp_cfg)\n        else:\n            # All attributes in module have same initialization.\n            pass\n\n\ndef _no_grad_trunc_normal_(tensor: Tensor, mean: float, std: float, a: float,\n                           b: float) -> Tensor:\n    # Method based on\n    # https://people.sc.fsu.edu/~jburkardt/presentations/truncated_normal.pdf\n    # Modified from\n    # https://github.com/pytorch/pytorch/blob/master/torch/nn/init.py\n    def norm_cdf(x):\n        # Computes standard normal cumulative distribution function\n        return (1. + math.erf(x / math.sqrt(2.))) / 2.\n\n    if (mean < a - 2 * std) or (mean > b + 2 * std):\n        warnings.warn(\n            'mean is more than 2 std from [a, b] in nn.init.trunc_normal_. '\n            'The distribution of values may be incorrect.',\n            stacklevel=2)\n\n    with torch.no_grad():\n        # Values are generated by using a truncated uniform distribution and\n        # then using the inverse CDF for the normal distribution.\n        # Get upper and lower cdf values\n        lower = norm_cdf((a - mean) / std)\n        upper = norm_cdf((b - mean) / std)\n\n        # Uniformly fill tensor with values from [lower, upper], then translate\n        # to [2lower-1, 2upper-1].\n        tensor.uniform_(2 * lower - 1, 2 * upper - 1)\n\n        # Use inverse cdf transform for normal distribution to get truncated\n        # standard normal\n        tensor.erfinv_()\n\n        # Transform to proper mean, std\n        tensor.mul_(std * math.sqrt(2.))\n        tensor.add_(mean)\n\n        # Clamp to ensure it's in the proper range\n        tensor.clamp_(min=a, max=b)\n        return tensor\n\n\ndef trunc_normal_(tensor: Tensor,\n                  mean: float = 0.,\n                  std: float = 1.,\n                  a: float = -2.,\n                  b: float = 2.) -> Tensor:\n    r\"\"\"Fills the input Tensor with values drawn from a truncated\n    normal distribution. The values are effectively drawn from the\n    normal distribution :math:`\\mathcal{N}(\\text{mean}, \\text{std}^2)`\n    with values outside :math:`[a, b]` redrawn until they are within\n    the bounds. The method used for generating the random values works\n    best when :math:`a \\leq \\text{mean} \\leq b`.\n\n    Modified from\n    https://github.com/pytorch/pytorch/blob/master/torch/nn/init.py\n\n    Args:\n        tensor (``torch.Tensor``): an n-dimensional `torch.Tensor`.\n        mean (float): the mean of the normal distribution.\n        std (float): the standard deviation of the normal distribution.\n        a (float): the minimum cutoff value.\n        b (float): the maximum cutoff value.\n    \"\"\"\n    return _no_grad_trunc_normal_(tensor, mean, std, a, b)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/vad_utils/CD_loss.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nfrom torch import nn as nn\nfrom torch.nn.functional import l1_loss, mse_loss, smooth_l1_loss\n\nfrom mmcv.models.builder import LOSSES\nfrom mmcv.models.losses.utils import weighted_loss\nimport torch.nn.functional as F\nfrom mmcv.core.bbox.match_costs.builder import MATCH_COST\nimport functools\n\n\ndef reduce_loss(loss, reduction):\n    \"\"\"Reduce loss as specified.\n\n    Args:\n        loss (Tensor): Elementwise loss tensor.\n        reduction (str): Options are \"none\", \"mean\" and \"sum\".\n\n    Return:\n        Tensor: Reduced loss tensor.\n    \"\"\"\n    reduction_enum = F._Reduction.get_enum(reduction)\n    # none: 0, elementwise_mean:1, sum: 2\n    if reduction_enum == 0:\n        return loss\n    elif reduction_enum == 1:\n        return loss.mean()\n    elif reduction_enum == 2:\n        return loss.sum()\n\ndef custom_weight_dir_reduce_loss(loss, weight=None, reduction='mean', avg_factor=None):\n    \"\"\"Apply element-wise weight and reduce loss.\n\n    Args:\n        loss (Tensor): num_sample, num_dir\n        weight (Tensor): Element-wise weights.\n        reduction (str): Same as built-in losses of PyTorch.\n        avg_factor (float): Average factor when computing the mean of losses.\n\n    Returns:\n        Tensor: Processed loss values.\n    \"\"\"\n    # if weight is specified, apply element-wise weight\n    if weight is not None:\n        loss = loss * weight\n\n    # if avg_factor is not specified, just reduce the loss\n    if avg_factor is None:\n        raise ValueError('avg_factor should not be none for OrderedPtsL1Loss')\n        # loss = reduce_loss(loss, reduction)\n    else:\n        # if reduction is mean, then average the loss by avg_factor\n        if reduction == 'mean':\n            # import pdb;pdb.set_trace()\n            # loss = loss.permute(1,0,2,3).contiguous()\n            loss = loss.sum()\n            loss = loss / avg_factor\n        # if reduction is 'none', then do nothing, otherwise raise an error\n        elif reduction != 'none':\n            raise ValueError('avg_factor can not be used with reduction=\"sum\"')\n    return loss\n\ndef custom_weight_reduce_loss(loss, weight=None, reduction='mean', avg_factor=None):\n    \"\"\"Apply element-wise weight and reduce loss.\n\n    Args:\n        loss (Tensor): num_sample, num_order, num_pts, num_coords\n        weight (Tensor): Element-wise weights.\n        reduction (str): Same as built-in losses of PyTorch.\n        avg_factor (float): Average factor when computing the mean of losses.\n\n    Returns:\n        Tensor: Processed loss values.\n    \"\"\"\n    # if weight is specified, apply element-wise weight\n    if weight is not None:\n        loss = loss * weight\n\n    # if avg_factor is not specified, just reduce the loss\n    if avg_factor is None:\n        raise ValueError('avg_factor should not be none for OrderedPtsL1Loss')\n        # loss = reduce_loss(loss, reduction)\n    else:\n        # if reduction is mean, then average the loss by avg_factor\n        if reduction == 'mean':\n            # import pdb;pdb.set_trace()\n            loss = loss.permute(1,0,2,3).contiguous()\n            loss = loss.sum((1,2,3))\n            loss = loss / avg_factor\n        # if reduction is 'none', then do nothing, otherwise raise an error\n        elif reduction != 'none':\n            raise ValueError('avg_factor can not be used with reduction=\"sum\"')\n    return loss\n\ndef custom_weighted_loss(loss_func):\n    \"\"\"Create a weighted version of a given loss function.\n\n    To use this decorator, the loss function must have the signature like\n    `loss_func(pred, target, **kwargs)`. The function only needs to compute\n    element-wise loss without any reduction. This decorator will add weight\n    and reduction arguments to the function. The decorated function will have\n    the signature like `loss_func(pred, target, weight=None, reduction='mean',\n    avg_factor=None, **kwargs)`.\n\n    :Example:\n\n    >>> import torch\n    >>> @weighted_loss\n    >>> def l1_loss(pred, target):\n    >>>     return (pred - target).abs()\n\n    >>> pred = torch.Tensor([0, 2, 3])\n    >>> target = torch.Tensor([1, 1, 1])\n    >>> weight = torch.Tensor([1, 0, 1])\n\n    >>> l1_loss(pred, target)\n    tensor(1.3333)\n    >>> l1_loss(pred, target, weight)\n    tensor(1.)\n    >>> l1_loss(pred, target, reduction='none')\n    tensor([1., 1., 2.])\n    >>> l1_loss(pred, target, weight, avg_factor=2)\n    tensor(1.5000)\n    \"\"\"\n\n    @functools.wraps(loss_func)\n    def wrapper(pred,\n                target,\n                weight=None,\n                reduction='mean',\n                avg_factor=None,\n                **kwargs):\n        # get element-wise loss\n        loss = loss_func(pred, target, **kwargs)\n        loss = custom_weight_reduce_loss(loss, weight, reduction, avg_factor)\n        return loss\n\n    return wrapper\n\n\ndef custom_weighted_dir_loss(loss_func):\n    \"\"\"Create a weighted version of a given loss function.\n\n    To use this decorator, the loss function must have the signature like\n    `loss_func(pred, target, **kwargs)`. The function only needs to compute\n    element-wise loss without any reduction. This decorator will add weight\n    and reduction arguments to the function. The decorated function will have\n    the signature like `loss_func(pred, target, weight=None, reduction='mean',\n    avg_factor=None, **kwargs)`.\n\n    :Example:\n\n    >>> import torch\n    >>> @weighted_loss\n    >>> def l1_loss(pred, target):\n    >>>     return (pred - target).abs()\n\n    >>> pred = torch.Tensor([0, 2, 3])\n    >>> target = torch.Tensor([1, 1, 1])\n    >>> weight = torch.Tensor([1, 0, 1])\n\n    >>> l1_loss(pred, target)\n    tensor(1.3333)\n    >>> l1_loss(pred, target, weight)\n    tensor(1.)\n    >>> l1_loss(pred, target, reduction='none')\n    tensor([1., 1., 2.])\n    >>> l1_loss(pred, target, weight, avg_factor=2)\n    tensor(1.5000)\n    \"\"\"\n\n    @functools.wraps(loss_func)\n    def wrapper(pred,\n                target,\n                weight=None,\n                reduction='mean',\n                avg_factor=None,\n                **kwargs):\n        # get element-wise loss\n        loss = loss_func(pred, target, **kwargs)\n        loss = custom_weight_dir_reduce_loss(loss, weight, reduction, avg_factor)\n        return loss\n\n    return wrapper\n\n@custom_weighted_loss\ndef ordered_pts_smooth_l1_loss(pred, target):\n    \"\"\"L1 loss.\n\n    Args:\n        pred (torch.Tensor): shape [num_samples, num_pts, num_coords]\n        target (torch.Tensor): shape [num_samples, num_order, num_pts, num_coords]\n\n    Returns:\n        torch.Tensor: Calculated loss\n    \"\"\"\n    if target.numel() == 0:\n        return pred.sum() * 0\n    pred = pred.unsqueeze(1).repeat(1, target.size(1),1,1)\n    assert pred.size() == target.size()\n    loss =smooth_l1_loss(pred,target, reduction='none')\n    # import pdb;pdb.set_trace()\n    return loss\n\n@weighted_loss\ndef pts_l1_loss(pred, target):\n    \"\"\"L1 loss.\n\n    Args:\n        pred (torch.Tensor): shape [num_samples, num_pts, num_coords]\n        target (torch.Tensor): shape [num_samples, num_pts, num_coords]\n\n    Returns:\n        torch.Tensor: Calculated loss\n    \"\"\"\n    if target.numel() == 0:\n        return pred.sum() * 0\n    assert pred.size() == target.size()\n    loss = torch.abs(pred - target)\n    return loss\n\n@custom_weighted_loss\ndef ordered_pts_l1_loss(pred, target):\n    \"\"\"L1 loss.\n\n    Args:\n        pred (torch.Tensor): shape [num_samples, num_pts, num_coords]\n        target (torch.Tensor): shape [num_samples, num_order, num_pts, num_coords]\n\n    Returns:\n        torch.Tensor: Calculated loss\n    \"\"\"\n    if target.numel() == 0:\n        return pred.sum() * 0\n    pred = pred.unsqueeze(1).repeat(1, target.size(1),1,1)\n    assert pred.size() == target.size()\n    loss = torch.abs(pred - target)\n    return loss\n\n@custom_weighted_dir_loss\ndef pts_dir_cos_loss(pred, target):\n    \"\"\" Dir cosine similiarity loss\n    pred (torch.Tensor): shape [num_samples, num_dir, num_coords]\n    target (torch.Tensor): shape [num_samples, num_dir, num_coords]\n\n    \"\"\"\n    if target.numel() == 0:\n        return pred.sum() * 0\n    # import pdb;pdb.set_trace()\n    num_samples, num_dir, num_coords = pred.shape\n    loss_func = torch.nn.CosineEmbeddingLoss(reduction='none')\n    tgt_param = target.new_ones((num_samples, num_dir))\n    tgt_param = tgt_param.flatten(0)\n    loss = loss_func(pred.flatten(0,1), target.flatten(0,1), tgt_param)\n    loss = loss.view(num_samples, num_dir)\n    return loss\n\n@LOSSES.register_module()\nclass OrderedPtsSmoothL1Loss(nn.Module):\n    \"\"\"L1 loss.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n    \"\"\"\n\n    def __init__(self, reduction='mean', loss_weight=1.0):\n        super(OrderedPtsSmoothL1Loss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        # import pdb;pdb.set_trace()\n        loss_bbox = self.loss_weight * ordered_pts_smooth_l1_loss(\n            pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n\n\n@LOSSES.register_module()\nclass PtsDirCosLoss(nn.Module):\n    \"\"\"L1 loss.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n    \"\"\"\n\n    def __init__(self, reduction='mean', loss_weight=1.0):\n        super(PtsDirCosLoss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        # import pdb;pdb.set_trace()\n        loss_dir = self.loss_weight * pts_dir_cos_loss(\n            pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        return loss_dir\n\n\n\n@LOSSES.register_module()\nclass PtsL1Loss(nn.Module):\n    \"\"\"L1 loss.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n    \"\"\"\n\n    def __init__(self, reduction='mean', loss_weight=1.0):\n        super(PtsL1Loss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        # import pdb;pdb.set_trace()\n        loss_bbox = self.loss_weight * pts_l1_loss(\n            pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n\n@LOSSES.register_module()\nclass OrderedPtsL1Loss(nn.Module):\n    \"\"\"L1 loss.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n    \"\"\"\n\n    def __init__(self, reduction='mean', loss_weight=1.0):\n        super(OrderedPtsL1Loss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            pred (torch.Tensor): The prediction.\n            target (torch.Tensor): The learning target of the prediction.\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n        # import pdb;pdb.set_trace()\n        loss_bbox = self.loss_weight * ordered_pts_l1_loss(\n            pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n\n\n\n\n@MATCH_COST.register_module()\nclass OrderedPtsSmoothL1Cost(object):\n    \"\"\"OrderedPtsL1Cost.\n     Args:\n         weight (int | float, optional): loss_weight\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n\n    def __call__(self, bbox_pred, gt_bboxes):\n        \"\"\"\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (x, y), which are all in range [0, 1]. Shape\n                [num_query, num_pts, 2].\n            gt_bboxes (Tensor): Ground truth boxes with normalized\n                coordinates (x,y). \n                Shape [num_gt, num_ordered, num_pts, 2].\n        Returns:\n            torch.Tensor: bbox_cost value with weight\n        \"\"\"\n        num_gts, num_orders, num_pts, num_coords = gt_bboxes.shape\n        # import pdb;pdb.set_trace()\n        bbox_pred = bbox_pred.view(bbox_pred.size(0),-1).unsqueeze(1).repeat(1,num_gts*num_orders,1)\n        gt_bboxes = gt_bboxes.flatten(2).view(num_gts*num_orders,-1).unsqueeze(0).repeat(bbox_pred.size(0),1,1)\n        # import pdb;pdb.set_trace()\n        bbox_cost = smooth_l1_loss(bbox_pred, gt_bboxes, reduction='none').sum(-1)\n        # bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)\n        return bbox_cost * self.weight\n\n@MATCH_COST.register_module()\nclass PtsL1Cost(object):\n    \"\"\"OrderedPtsL1Cost.\n     Args:\n         weight (int | float, optional): loss_weight\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n\n    def __call__(self, bbox_pred, gt_bboxes):\n        \"\"\"\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (x, y), which are all in range [0, 1]. Shape\n                [num_query, num_pts, 2].\n            gt_bboxes (Tensor): Ground truth boxes with normalized\n                coordinates (x,y). \n                Shape [num_gt, num_ordered, num_pts, 2].\n        Returns:\n            torch.Tensor: bbox_cost value with weight\n        \"\"\"\n        num_gts, num_pts, num_coords = gt_bboxes.shape\n        # import pdb;pdb.set_trace()\n        bbox_pred = bbox_pred.view(bbox_pred.size(0),-1)\n        gt_bboxes = gt_bboxes.view(num_gts,-1)\n        bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)\n        return bbox_cost * self.weight\n\n@MATCH_COST.register_module()\nclass OrderedPtsL1Cost(object):\n    \"\"\"OrderedPtsL1Cost.\n     Args:\n         weight (int | float, optional): loss_weight\n    \"\"\"\n\n    def __init__(self, weight=1.):\n        self.weight = weight\n\n    def __call__(self, bbox_pred, gt_bboxes):\n        \"\"\"\n        Args:\n            bbox_pred (Tensor): Predicted boxes with normalized coordinates\n                (x, y), which are all in range [0, 1]. Shape\n                [num_query, num_pts, 2].\n            gt_bboxes (Tensor): Ground truth boxes with normalized\n                coordinates (x,y). \n                Shape [num_gt, num_ordered, num_pts, 2].\n        Returns:\n            torch.Tensor: bbox_cost value with weight\n        \"\"\"\n        num_gts, num_orders, num_pts, num_coords = gt_bboxes.shape\n        # import pdb;pdb.set_trace()\n        bbox_pred = bbox_pred.view(bbox_pred.size(0),-1)\n        gt_bboxes = gt_bboxes.flatten(2).view(num_gts*num_orders,-1)\n        bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)\n        return bbox_cost * self.weight\n\n@MATCH_COST.register_module()\nclass MyChamferDistanceCost:\n    def __init__(self, loss_src_weight=1., loss_dst_weight=1.):\n        # assert mode in ['smooth_l1', 'l1', 'l2']\n        # self.mode = mode\n        self.loss_src_weight = loss_src_weight\n        self.loss_dst_weight = loss_dst_weight\n\n    def __call__(self, src, dst,src_weight=1.0,dst_weight=1.0,):\n        \"\"\"\n        pred_pts (Tensor): normed coordinate(x,y), shape (num_q, num_pts_M, 2)\n        gt_pts (Tensor): normed coordinate(x,y), shape (num_gt, num_pts_N, 2)\n        \"\"\"\n        # criterion_mode = self.mode\n        # if criterion_mode == 'smooth_l1':\n        #     criterion = smooth_l1_loss\n        # elif criterion_mode == 'l1':\n        #     criterion = l1_loss\n        # elif criterion_mode == 'l2':\n        #     criterion = mse_loss\n        # else:\n        #     raise NotImplementedError\n        # import pdb;pdb.set_trace()\n        src_expand = src.unsqueeze(1).repeat(1,dst.shape[0],1,1)\n        dst_expand = dst.unsqueeze(0).repeat(src.shape[0],1,1,1)\n        # src_expand = src.unsqueeze(2).unsqueeze(1).repeat(1,dst.shape[0], 1, dst.shape[1], 1)\n        # dst_expand = dst.unsqueeze(1).unsqueeze(0).repeat(src.shape[0],1, src.shape[1], 1, 1)\n        distance = torch.cdist(src_expand, dst_expand)\n        src2dst_distance = torch.min(distance, dim=3)[0]  # (num_q, num_gt, num_pts_N)\n        dst2src_distance = torch.min(distance, dim=2)[0]  # (num_q, num_gt, num_pts_M)\n        loss_src = (src2dst_distance * src_weight).mean(-1)\n        loss_dst = (dst2src_distance * dst_weight).mean(-1)\n        loss = loss_src*self.loss_src_weight + loss_dst * self.loss_dst_weight\n        return loss\n\ndef chamfer_distance(src,\n                     dst,\n                     src_weight=1.0,\n                     dst_weight=1.0,\n                    #  criterion_mode='l1',\n                     reduction='mean',\n                     avg_factor=None):\n    \"\"\"Calculate Chamfer Distance of two sets.\n\n    Args:\n        src (torch.Tensor): Source set with shape [B, N, C] to\n            calculate Chamfer Distance.\n        dst (torch.Tensor): Destination set with shape [B, M, C] to\n            calculate Chamfer Distance.\n        src_weight (torch.Tensor or float): Weight of source loss.\n        dst_weight (torch.Tensor or float): Weight of destination loss.\n        criterion_mode (str): Criterion mode to calculate distance.\n            The valid modes are smooth_l1, l1 or l2.\n        reduction (str): Method to reduce losses.\n            The valid reduction method are 'none', 'sum' or 'mean'.\n\n    Returns:\n        tuple: Source and Destination loss with the corresponding indices.\n\n            - loss_src (torch.Tensor): The min distance \\\n                from source to destination.\n            - loss_dst (torch.Tensor): The min distance \\\n                from destination to source.\n            - indices1 (torch.Tensor): Index the min distance point \\\n                for each point in source to destination.\n            - indices2 (torch.Tensor): Index the min distance point \\\n                for each point in destination to source.\n    \"\"\"\n\n    # if criterion_mode == 'smooth_l1':\n    #     criterion = smooth_l1_loss\n    # elif criterion_mode == 'l1':\n    #     criterion = l1_loss\n    # elif criterion_mode == 'l2':\n    #     criterion = mse_loss\n    # else:\n    #     raise NotImplementedError\n\n    # src_expand = src.unsqueeze(2).repeat(1, 1, dst.shape[1], 1)\n    # dst_expand = dst.unsqueeze(1).repeat(1, src.shape[1], 1, 1)\n    # import pdb;pdb.set_trace()\n    distance = torch.cdist(src, dst)\n    src2dst_distance, indices1 = torch.min(distance, dim=2)  # (B,N)\n    dst2src_distance, indices2 = torch.min(distance, dim=1)  # (B,M)\n    # import pdb;pdb.set_trace()\n    #TODO this may be wrong for misaligned src_weight, now[N,fixed_num]\n    # should be [N], then view\n    loss_src = (src2dst_distance * src_weight)\n    loss_dst = (dst2src_distance * dst_weight)\n    if avg_factor is None:\n        reduction_enum = F._Reduction.get_enum(reduction)\n        if reduction_enum == 0:\n            raise ValueError('MyCDLoss can not be used with reduction=`none`')\n        elif reduction_enum == 1:\n            loss_src = loss_src.mean(-1).mean()\n            loss_dst = loss_dst.mean(-1).mean()\n        elif reduction_enum == 2:\n            loss_src = loss_src.mean(-1).sum()\n            loss_dst = loss_dst.mean(-1).sum()\n        else:\n            raise NotImplementedError\n    else:\n        if reduction == 'mean':\n            eps = torch.finfo(torch.float32).eps\n            loss_src = loss_src.mean(-1).sum() / (avg_factor + eps)\n            loss_dst = loss_dst.mean(-1).sum() / (avg_factor + eps)\n        elif reduction != 'none':\n            raise ValueError('avg_factor can not be used with reduction=\"sum\"')\n\n    return loss_src, loss_dst, indices1, indices2\n\n\n@LOSSES.register_module()\nclass MyChamferDistance(nn.Module):\n    \"\"\"Calculate Chamfer Distance of two sets.\n\n    Args:\n        mode (str): Criterion mode to calculate distance.\n            The valid modes are smooth_l1, l1 or l2.\n        reduction (str): Method to reduce losses.\n            The valid reduction method are none, sum or mean.\n        loss_src_weight (float): Weight of loss_source.\n        loss_dst_weight (float): Weight of loss_target.\n    \"\"\"\n\n    def __init__(self,\n                #  mode='l1',\n                 reduction='mean',\n                 loss_src_weight=1.0,\n                 loss_dst_weight=1.0):\n        super(MyChamferDistance, self).__init__()\n\n        # assert mode in ['smooth_l1', 'l1', 'l2']\n        assert reduction in ['none', 'sum', 'mean']\n        # self.mode = mode\n        self.reduction = reduction\n        self.loss_src_weight = loss_src_weight\n        self.loss_dst_weight = loss_dst_weight\n\n    def forward(self,\n                source,\n                target,\n                src_weight=1.0,\n                dst_weight=1.0,\n                avg_factor=None,\n                reduction_override=None,\n                return_indices=False,\n                **kwargs):\n        \"\"\"Forward function of loss calculation.\n\n        Args:\n            source (torch.Tensor): Source set with shape [B, N, C] to\n                calculate Chamfer Distance.\n            target (torch.Tensor): Destination set with shape [B, M, C] to\n                calculate Chamfer Distance.\n            src_weight (torch.Tensor | float, optional):\n                Weight of source loss. Defaults to 1.0.\n            dst_weight (torch.Tensor | float, optional):\n                Weight of destination loss. Defaults to 1.0.\n            reduction_override (str, optional): Method to reduce losses.\n                The valid reduction method are 'none', 'sum' or 'mean'.\n                Defaults to None.\n            return_indices (bool, optional): Whether to return indices.\n                Defaults to False.\n\n        Returns:\n            tuple[torch.Tensor]: If ``return_indices=True``, return losses of \\\n                source and target with their corresponding indices in the \\\n                order of ``(loss_source, loss_target, indices1, indices2)``. \\\n                If ``return_indices=False``, return \\\n                ``(loss_source, loss_target)``.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        loss_source, loss_target, indices1, indices2 = chamfer_distance(\n            source, target, src_weight, dst_weight, reduction,\n            avg_factor=avg_factor)\n\n        loss_source *= self.loss_src_weight\n        loss_target *= self.loss_dst_weight\n\n        loss_pts = loss_source + loss_target\n\n        if return_indices:\n            return loss_pts, indices1, indices2\n        else:\n            return loss_pts\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/vad_utils/__init__.py",
    "content": "from .map_utils import normalize_2d_bbox, normalize_2d_pts, denormalize_2d_bbox, denormalize_2d_pts\nfrom .CD_loss import (\n    MyChamferDistance, MyChamferDistanceCost,\n    OrderedPtsL1Cost, PtsL1Cost, OrderedPtsSmoothL1Cost,\n    OrderedPtsL1Loss, PtsL1Loss, PtsDirCosLoss\n)\nfrom .plan_loss import PlanMapBoundLoss, PlanCollisionLoss, PlanMapDirectionLoss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/vad_utils/map_utils.py",
    "content": "from mmcv.core.bbox.transforms import bbox_xyxy_to_cxcywh, bbox_cxcywh_to_xyxy\n\ndef normalize_2d_bbox(bboxes, pc_range):\n\n    patch_h = pc_range[4]-pc_range[1]\n    patch_w = pc_range[3]-pc_range[0]\n    cxcywh_bboxes = bbox_xyxy_to_cxcywh(bboxes)\n    cxcywh_bboxes[...,0:1] = cxcywh_bboxes[..., 0:1] - pc_range[0]\n    cxcywh_bboxes[...,1:2] = cxcywh_bboxes[...,1:2] - pc_range[1]\n    factor = bboxes.new_tensor([patch_w, patch_h,patch_w,patch_h])\n\n    normalized_bboxes = cxcywh_bboxes / factor\n    return normalized_bboxes\n\ndef normalize_2d_pts(pts, pc_range):\n    patch_h = pc_range[4]-pc_range[1]\n    patch_w = pc_range[3]-pc_range[0]\n    new_pts = pts.clone()\n    new_pts[...,0:1] = pts[..., 0:1] - pc_range[0]\n    new_pts[...,1:2] = pts[...,1:2] - pc_range[1]\n    factor = pts.new_tensor([patch_w, patch_h])\n    normalized_pts = new_pts / factor\n    return normalized_pts\n\ndef denormalize_2d_bbox(bboxes, pc_range):\n\n    bboxes = bbox_cxcywh_to_xyxy(bboxes)\n    bboxes[..., 0::2] = (bboxes[..., 0::2]*(pc_range[3] -\n                            pc_range[0]) + pc_range[0])\n    bboxes[..., 1::2] = (bboxes[..., 1::2]*(pc_range[4] -\n                            pc_range[1]) + pc_range[1])\n\n    return bboxes\n\ndef denormalize_2d_pts(pts, pc_range):\n    new_pts = pts.clone()\n    new_pts[...,0:1] = (pts[..., 0:1]*(pc_range[3] -\n                            pc_range[0]) + pc_range[0])\n    new_pts[...,1:2] = (pts[...,1:2]*(pc_range[4] -\n                            pc_range[1]) + pc_range[1])\n    return new_pts"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/vad_utils/plan_loss.py",
    "content": "import math\nimport torch\nfrom torch import nn as nn\nfrom mmcv.models.losses.utils import weighted_loss\nfrom mmcv.models.builder import LOSSES\n\n\n@LOSSES.register_module()\nclass PlanMapBoundLoss(nn.Module):\n    \"\"\"Planning constraint to push ego vehicle away from the lane boundary.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n        map_thresh (float, optional): confidence threshold to filter map predictions.\n        lane_bound_cls_idx (float, optional): lane_boundary class index.\n        dis_thresh (float, optional): distance threshold between ego vehicle and lane bound.\n        point_cloud_range (list, optional): point cloud range.\n    \"\"\"\n\n    def __init__(\n        self,\n        reduction='mean',\n        loss_weight=1.0,\n        map_thresh=0.5,\n        lane_bound_cls_idx=2,\n        dis_thresh=1.0,\n        point_cloud_range=[-15.0, -30.0, -2.0, 15.0, 30.0, 2.0],\n        perception_detach=False\n    ):\n        super(PlanMapBoundLoss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n        self.map_thresh = map_thresh\n        self.lane_bound_cls_idx = lane_bound_cls_idx\n        self.dis_thresh = dis_thresh\n        self.pc_range = point_cloud_range\n        self.perception_detach = perception_detach\n\n    def forward(self,\n                ego_fut_preds,\n                lane_preds,\n                lane_score_preds,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            ego_fut_preds (Tensor): [B, fut_ts, 2]\n            lane_preds (Tensor): [B, num_vec, num_pts, 2]\n            lane_score_preds (Tensor): [B, num_vec, 3]\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        if self.perception_detach:\n            lane_preds = lane_preds.detach()\n            lane_score_preds = lane_score_preds.detach()\n\n        # filter lane element according to confidence score and class\n        not_lane_bound_mask = lane_score_preds[..., self.lane_bound_cls_idx] < self.map_thresh\n        # denormalize map pts\n        lane_bound_preds = lane_preds.clone()\n        lane_bound_preds[...,0:1] = (lane_bound_preds[..., 0:1] * (self.pc_range[3] -\n                                self.pc_range[0]) + self.pc_range[0])\n        lane_bound_preds[...,1:2] = (lane_bound_preds[..., 1:2] * (self.pc_range[4] -\n                                self.pc_range[1]) + self.pc_range[1])\n        # pad not-lane-boundary cls and low confidence preds\n        lane_bound_preds[not_lane_bound_mask] = 1e6\n\n        loss_bbox = self.loss_weight * plan_map_bound_loss(ego_fut_preds, lane_bound_preds,\n                                                           weight=weight, dis_thresh=self.dis_thresh,\n                                                           reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n\n@weighted_loss\ndef plan_map_bound_loss(pred, target, dis_thresh=1.0):\n    \"\"\"Planning map bound constraint (L1 distance).\n\n    Args:\n        pred (torch.Tensor): ego_fut_preds, [B, fut_ts, 2].\n        target (torch.Tensor): lane_bound_preds, [B, num_vec, num_pts, 2].\n        weight (torch.Tensor): [B, fut_ts]\n\n    Returns:\n        torch.Tensor: Calculated loss [B, fut_ts]\n    \"\"\"\n    pred = pred.cumsum(dim=-2)\n    ego_traj_starts = pred[:, :-1, :]\n    ego_traj_ends = pred\n    B, T, _ = ego_traj_ends.size()\n    padding_zeros = torch.zeros((B, 1, 2), dtype=pred.dtype, device=pred.device)  # initial position\n    ego_traj_starts = torch.cat((padding_zeros, ego_traj_starts), dim=1)\n    _, V, P, _ = target.size()\n    ego_traj_expanded = ego_traj_ends.unsqueeze(2).unsqueeze(3)  # [B, T, 1, 1, 2]\n    maps_expanded = target.unsqueeze(1)  # [1, 1, M, P, 2]\n    dist = torch.linalg.norm(ego_traj_expanded - maps_expanded, dim=-1)  # [B, T, M, P]\n    dist = dist.min(dim=-1, keepdim=False)[0]\n    min_inst_idxs = torch.argmin(dist, dim=-1).tolist()\n    batch_idxs = [[i] for i in range(dist.shape[0])]\n    ts_idxs = [[i for i in range(dist.shape[1])] for j in range(dist.shape[0])]\n    bd_target = target.unsqueeze(1).repeat(1, pred.shape[1], 1, 1, 1)\n    min_bd_insts = bd_target[batch_idxs, ts_idxs, min_inst_idxs]  # [B, T, P, 2]\n    bd_inst_starts = min_bd_insts[:, :, :-1, :].flatten(0, 2)\n    bd_inst_ends = min_bd_insts[:, :, 1:, :].flatten(0, 2)\n    ego_traj_starts = ego_traj_starts.unsqueeze(2).repeat(1, 1, P-1, 1).flatten(0, 2)\n    ego_traj_ends = ego_traj_ends.unsqueeze(2).repeat(1, 1, P-1, 1).flatten(0, 2)\n\n    intersect_mask = segments_intersect(ego_traj_starts, ego_traj_ends,\n                                        bd_inst_starts, bd_inst_ends)\n    intersect_mask = intersect_mask.reshape(B, T, P-1)\n    intersect_mask = intersect_mask.any(dim=-1)\n    intersect_idx = (intersect_mask == True).nonzero()\n\n    target = target.view(target.shape[0], -1, target.shape[-1])\n    # [B, fut_ts, num_vec*num_pts]\n    dist = torch.linalg.norm(pred[:, :, None, :] - target[:, None, :, :], dim=-1)\n    min_idxs = torch.argmin(dist, dim=-1).tolist()\n    batch_idxs = [[i] for i in range(dist.shape[0])]\n    ts_idxs = [[i for i in range(dist.shape[1])] for j in range(dist.shape[0])]\n    min_dist = dist[batch_idxs, ts_idxs, min_idxs]\n    loss = min_dist\n    safe_idx = loss > dis_thresh\n    unsafe_idx = loss <= dis_thresh\n    loss[safe_idx] = 0\n    loss[unsafe_idx] = dis_thresh - loss[unsafe_idx]\n\n    for i in range(len(intersect_idx)):\n        loss[intersect_idx[i, 0], intersect_idx[i, 1]:] = 0\n\n    return loss\n\n\ndef segments_intersect(line1_start, line1_end, line2_start, line2_end):\n    # Calculating the differences\n    dx1 = line1_end[:, 0] - line1_start[:, 0]\n    dy1 = line1_end[:, 1] - line1_start[:, 1]\n    dx2 = line2_end[:, 0] - line2_start[:, 0]\n    dy2 = line2_end[:, 1] - line2_start[:, 1]\n\n    # Calculating determinants\n    det = dx1 * dy2 - dx2 * dy1\n    det_mask = det != 0\n\n    # Checking if lines are parallel or coincident\n    parallel_mask = torch.logical_not(det_mask)\n\n    # Calculating intersection parameters\n    t1 = ((line2_start[:, 0] - line1_start[:, 0]) * dy2 \n          - (line2_start[:, 1] - line1_start[:, 1]) * dx2) / det\n    t2 = ((line2_start[:, 0] - line1_start[:, 0]) * dy1 \n          - (line2_start[:, 1] - line1_start[:, 1]) * dx1) / det\n\n    # Checking intersection conditions\n    intersect_mask = torch.logical_and(\n        torch.logical_and(t1 >= 0, t1 <= 1),\n        torch.logical_and(t2 >= 0, t2 <= 1)\n    )\n\n    # Handling parallel or coincident lines\n    intersect_mask[parallel_mask] = False\n\n    return intersect_mask\n\n\n@LOSSES.register_module()\nclass PlanCollisionLoss(nn.Module):\n    \"\"\"Planning constraint to push ego vehicle away from other agents.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n        agent_thresh (float, optional): confidence threshold to filter agent predictions.\n        x_dis_thresh (float, optional): distance threshold between ego and other agents in x-axis.\n        y_dis_thresh (float, optional): distance threshold between ego and other agents in y-axis.\n        point_cloud_range (list, optional): point cloud range.\n    \"\"\"\n\n    def __init__(\n        self,\n        reduction='mean',\n        loss_weight=1.0,\n        agent_thresh=0.5,\n        x_dis_thresh=1.5,\n        y_dis_thresh=3.0,\n        point_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\n    ):\n        super(PlanCollisionLoss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n        self.agent_thresh = agent_thresh\n        self.x_dis_thresh = x_dis_thresh\n        self.y_dis_thresh = y_dis_thresh\n        self.pc_range = point_cloud_range\n\n    def forward(self,\n                ego_fut_preds,\n                agent_preds,\n                agent_fut_preds,\n                agent_score_preds,\n                agent_fut_cls_preds,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            ego_fut_preds (Tensor): [B, fut_ts, 2]\n            agent_preds (Tensor): [B, num_agent, 2]\n            agent_fut_preds (Tensor): [B, num_agent, fut_mode, fut_ts, 2]\n            agent_fut_cls_preds (Tensor): [B, num_agent, fut_mode]\n            agent_score_preds (Tensor): [B, num_agent, 10]\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        # filter agent element according to confidence score\n        agent_max_score_preds, agent_max_score_idxs = agent_score_preds.max(dim=-1)\n        not_valid_agent_mask = agent_max_score_preds < self.agent_thresh\n        # filter low confidence preds\n        agent_fut_preds[not_valid_agent_mask] = 1e6\n        # filter not vehicle preds\n        not_veh_pred_mask = agent_max_score_idxs > 4  # veh idxs are 0-4\n        agent_fut_preds[not_veh_pred_mask] = 1e6\n        # only use best mode pred\n        best_mode_idxs = torch.argmax(agent_fut_cls_preds, dim=-1).tolist()\n        batch_idxs = [[i] for i in range(agent_fut_cls_preds.shape[0])]\n        agent_num_idxs = [[i for i in range(agent_fut_cls_preds.shape[1])] for j in range(agent_fut_cls_preds.shape[0])]\n        agent_fut_preds = agent_fut_preds[batch_idxs, agent_num_idxs, best_mode_idxs]\n\n        loss_bbox = self.loss_weight * plan_col_loss(ego_fut_preds, agent_preds,\n                                                           agent_fut_preds=agent_fut_preds, weight=weight,\n                                                           x_dis_thresh=self.x_dis_thresh,\n                                                           y_dis_thresh=self.y_dis_thresh,\n                                                           reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n\n@weighted_loss\ndef plan_col_loss(\n    pred,\n    target,\n    agent_fut_preds,\n    x_dis_thresh=1.5,\n    y_dis_thresh=3.0,\n    dis_thresh=3.0\n):\n    \"\"\"Planning ego-agent collsion constraint.\n\n    Args:\n        pred (torch.Tensor): ego_fut_preds, [B, fut_ts, 2].\n        target (torch.Tensor): agent_preds, [B, num_agent, 2].\n        agent_fut_preds (Tensor): [B, num_agent, fut_ts, 2].\n        weight (torch.Tensor): [B, fut_ts, 2].\n        x_dis_thresh (float, optional): distance threshold between ego and other agents in x-axis.\n        y_dis_thresh (float, optional): distance threshold between ego and other agents in y-axis.\n        dis_thresh (float, optional): distance threshold to filter distant agents.\n\n    Returns:\n        torch.Tensor: Calculated loss [B, fut_mode, fut_ts, 2]\n    \"\"\"\n    pred = pred.cumsum(dim=-2)\n    agent_fut_preds = agent_fut_preds.cumsum(dim=-2)\n    target = target[:, :, None, :] + agent_fut_preds\n    # filter distant agents from ego vehicle\n    dist = torch.linalg.norm(pred[:, None, :, :] - target, dim=-1)\n    dist_mask = dist > dis_thresh\n    target[dist_mask] = 1e6\n\n    # [B, num_agent, fut_ts]\n    x_dist = torch.abs(pred[:, None, :, 0] - target[..., 0])\n    y_dist = torch.abs(pred[:, None, :, 1] - target[..., 1])\n    x_min_idxs = torch.argmin(x_dist, dim=1).tolist()\n    y_min_idxs = torch.argmin(y_dist, dim=1).tolist()\n    batch_idxs = [[i] for i in range(y_dist.shape[0])]\n    ts_idxs = [[i for i in range(y_dist.shape[-1])] for j in range(y_dist.shape[0])]\n\n    # [B, fut_ts]\n    x_min_dist = x_dist[batch_idxs, x_min_idxs, ts_idxs]\n    y_min_dist = y_dist[batch_idxs, y_min_idxs, ts_idxs]\n    x_loss = x_min_dist\n    safe_idx = x_loss > x_dis_thresh\n    unsafe_idx = x_loss <= x_dis_thresh\n    x_loss[safe_idx] = 0\n    x_loss[unsafe_idx] = x_dis_thresh - x_loss[unsafe_idx]\n    y_loss = y_min_dist\n    safe_idx = y_loss > y_dis_thresh\n    unsafe_idx = y_loss <= y_dis_thresh\n    y_loss[safe_idx] = 0\n    y_loss[unsafe_idx] = y_dis_thresh - y_loss[unsafe_idx]\n    loss = torch.cat([x_loss.unsqueeze(-1), y_loss.unsqueeze(-1)], dim=-1)\n\n    return loss\n\n\n@LOSSES.register_module()\nclass PlanMapDirectionLoss(nn.Module):\n    \"\"\"Planning loss to force the ego heading angle consistent with lane direction.\n\n    Args:\n        reduction (str, optional): The method to reduce the loss.\n            Options are \"none\", \"mean\" and \"sum\".\n        loss_weight (float, optional): The weight of loss.\n        theta_thresh (float, optional): angle diff thresh between ego and lane.\n        point_cloud_range (list, optional): point cloud range.\n    \"\"\"\n\n    def __init__(\n        self,\n        reduction='mean',\n        loss_weight=1.0,\n        map_thresh=0.5,\n        dis_thresh=2.0,\n        lane_div_cls_idx=0,\n        point_cloud_range = [-15.0, -30.0, -2.0, 15.0, 30.0, 2.0]\n    ):\n        super(PlanMapDirectionLoss, self).__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n        self.map_thresh = map_thresh\n        self.dis_thresh = dis_thresh\n        self.lane_div_cls_idx = lane_div_cls_idx\n        self.pc_range = point_cloud_range\n\n    def forward(self,\n                ego_fut_preds,\n                lane_preds,\n                lane_score_preds,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n\n        Args:\n            ego_fut_preds (Tensor): [B, fut_ts, 2]\n            lane_preds (Tensor): [B, num_vec, num_pts, 2]\n            lane_score_preds (Tensor): [B, num_vec, 3]\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        # filter lane element according to confidence score and class\n        not_lane_div_mask = lane_score_preds[..., self.lane_div_cls_idx] < self.map_thresh\n        # denormalize map pts\n        lane_div_preds = lane_preds.clone()\n        lane_div_preds[...,0:1] = (lane_div_preds[..., 0:1] * (self.pc_range[3] -\n                                self.pc_range[0]) + self.pc_range[0])\n        lane_div_preds[...,1:2] = (lane_div_preds[..., 1:2] * (self.pc_range[4] -\n                                self.pc_range[1]) + self.pc_range[1])\n        # pad not-lane-divider cls and low confidence preds\n        lane_div_preds[not_lane_div_mask] = 1e6\n\n        loss_bbox = self.loss_weight * plan_map_dir_loss(ego_fut_preds, lane_div_preds,\n                                                           weight=weight, dis_thresh=self.dis_thresh,\n                                                           reduction=reduction, avg_factor=avg_factor)\n        return loss_bbox\n\n@weighted_loss\ndef plan_map_dir_loss(pred, target, dis_thresh=2.0):\n    \"\"\"Planning ego-map directional loss.\n\n    Args:\n        pred (torch.Tensor): ego_fut_preds, [B, fut_ts, 2].\n        target (torch.Tensor): lane_div_preds, [B, num_vec, num_pts, 2].\n        weight (torch.Tensor): [B, fut_ts]\n\n    Returns:\n        torch.Tensor: Calculated loss [B, fut_ts]\n    \"\"\"\n    num_map_pts = target.shape[2]\n    pred = pred.cumsum(dim=-2)\n    traj_dis = torch.linalg.norm(pred[:, -1, :] - pred[:, 0, :], dim=-1)\n    static_mask = traj_dis < 1.0\n    target = target.unsqueeze(1).repeat(1, pred.shape[1], 1, 1, 1)\n\n    # find the closest map instance for ego at each timestamp\n    dist = torch.linalg.norm(pred[:, :, None, None, :] - target, dim=-1)\n    dist = dist.min(dim=-1, keepdim=False)[0]\n    min_inst_idxs = torch.argmin(dist, dim=-1).tolist()\n    batch_idxs = [[i] for i in range(dist.shape[0])]\n    ts_idxs = [[i for i in range(dist.shape[1])] for j in range(dist.shape[0])]\n    target_map_inst = target[batch_idxs, ts_idxs, min_inst_idxs]  # [B, fut_ts, num_pts, 2]\n\n    # calculate distance\n    dist = torch.linalg.norm(pred[:, :, None, :] - target_map_inst, dim=-1)\n    min_pts_idxs = torch.argmin(dist, dim=-1)\n    min_pts_next_idxs = min_pts_idxs.clone()\n    is_end_point = (min_pts_next_idxs == num_map_pts-1)\n    not_end_point = (min_pts_next_idxs != num_map_pts-1)\n    min_pts_next_idxs[is_end_point] = num_map_pts - 2\n    min_pts_next_idxs[not_end_point] = min_pts_next_idxs[not_end_point] + 1\n    min_pts_idxs = min_pts_idxs.tolist()\n    min_pts_next_idxs = min_pts_next_idxs.tolist()\n    traj_yaw = torch.atan2(torch.diff(pred[..., 1]), torch.diff(pred[..., 0]))  # [B, fut_ts-1]\n    # last ts yaw assume same as previous\n    traj_yaw = torch.cat([traj_yaw, traj_yaw[:, [-1]]], dim=-1)  # [B, fut_ts]\n    min_pts = target_map_inst[batch_idxs, ts_idxs, min_pts_idxs]\n    dist = torch.linalg.norm(min_pts - pred, dim=-1)\n    dist_mask = dist > dis_thresh\n    min_pts = min_pts.unsqueeze(2)\n    min_pts_next = target_map_inst[batch_idxs, ts_idxs, min_pts_next_idxs].unsqueeze(2)\n    map_pts = torch.cat([min_pts, min_pts_next], dim=2)\n    lane_yaw = torch.atan2(torch.diff(map_pts[..., 1]).squeeze(-1), torch.diff(map_pts[..., 0]).squeeze(-1))  # [B, fut_ts]\n    yaw_diff = traj_yaw - lane_yaw\n    yaw_diff[yaw_diff > math.pi] =  yaw_diff[yaw_diff > math.pi] - math.pi\n    yaw_diff[yaw_diff > math.pi/2] = yaw_diff[yaw_diff > math.pi/2] - math.pi\n    yaw_diff[yaw_diff < -math.pi] = yaw_diff[yaw_diff < -math.pi] + math.pi\n    yaw_diff[yaw_diff < -math.pi/2] = yaw_diff[yaw_diff < -math.pi/2] + math.pi\n    yaw_diff[dist_mask] = 0  # loss = 0 if no lane around ego\n    yaw_diff[static_mask] = 0  # loss = 0 if ego is static\n\n    loss = torch.abs(yaw_diff)\n\n    return loss  # [B, fut_ts]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/models/vad_utils/traj_lr_warmup.py",
    "content": "import torch\n\ndef get_traj_warmup_loss_weight(\n    cur_epoch,\n    tot_epoch,\n    start_pos=0.3,\n    end_pos=0.35,\n    scale_weight=1.1\n):\n    epoch_percentage = cur_epoch / tot_epoch\n    sigmoid_input = 5 / (end_pos-start_pos) * epoch_percentage - 2.5 * (end_pos+start_pos) / (end_pos - start_pos)\n\n    return scale_weight * torch.sigmoid(torch.tensor(sigmoid_input))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .modulated_deform_conv import (ModulatedDeformConv2d,\n                                    ModulatedDeformConv2dPack,\n                                    modulated_deform_conv2d)\nfrom .multi_scale_deform_attn import MultiScaleDeformableAttention\nfrom .roiaware_pool3d import (RoIAwarePool3d, points_in_boxes_batch,\n                              points_in_boxes_cpu, points_in_boxes_gpu)\nfrom .roi_align import RoIAlign, roi_align\nfrom .iou3d import boxes_iou_bev, nms_bev, nms_normal_bev\nfrom .focal_loss import (SigmoidFocalLoss, SoftmaxFocalLoss,\n                         sigmoid_focal_loss, softmax_focal_loss)\nfrom .voxelize import Voxelization, voxelization\nfrom .nms import batched_nms, nms, nms_match, nms_rotated, soft_nms\nfrom .masked_conv import MaskedConv2d, masked_conv2d\nfrom .deform_conv import DeformConv2d, DeformConv2dPack, deform_conv2d\n\n\n# __all__ = [\n#     'bbox_overlaps', 'CARAFE', 'CARAFENaive', 'CARAFEPack', 'carafe',\n#     'carafe_naive', 'CornerPool', 'DeformConv2d', 'DeformConv2dPack',\n#     'deform_conv2d', 'DeformRoIPool', 'DeformRoIPoolPack',\n#     'ModulatedDeformRoIPoolPack', 'deform_roi_pool', 'SigmoidFocalLoss',\n#     'SoftmaxFocalLoss', 'sigmoid_focal_loss', 'softmax_focal_loss',\n#     'get_compiler_version', 'get_compiling_cuda_version',\n#     'get_onnxruntime_op_path', 'MaskedConv2d', 'masked_conv2d',\n#     'ModulatedDeformConv2d', 'ModulatedDeformConv2dPack',\n#     'modulated_deform_conv2d', 'batched_nms', 'nms', 'soft_nms', 'nms_match',\n#     'RoIAlign', 'roi_align', 'RoIPool', 'roi_pool', 'SyncBatchNorm', 'Conv2d',\n#     'ConvTranspose2d', 'Linear', 'MaxPool2d', 'CrissCrossAttention', 'PSAMask',\n#     'point_sample', 'rel_roi_point_to_rel_img_point', 'SimpleRoIAlign',\n#     'SAConv2d', 'TINShift', 'tin_shift', 'assign_score_withk',\n#     'box_iou_rotated', 'RoIPointPool3d', 'nms_rotated', 'knn', 'ball_query',\n#     'upfirdn2d', 'FusedBiasLeakyReLU', 'fused_bias_leakyrelu',\n#     'RoIAlignRotated', 'roi_align_rotated', 'pixel_group', 'QueryAndGroup',\n#     'GroupAll', 'grouping_operation', 'contour_expand', 'three_nn',\n#     'three_interpolate', 'MultiScaleDeformableAttention', 'BorderAlign',\n#     'border_align', 'gather_points', 'furthest_point_sample',\n#     'furthest_point_sample_with_dist', 'PointsSampler', 'Correlation',\n#     'boxes_iou_bev', 'nms_bev', 'nms_normal_bev', 'Voxelization',\n#     'voxelization', 'dynamic_scatter', 'DynamicScatter', 'RoIAwarePool3d',\n#     'points_in_boxes_part', 'points_in_boxes_cpu', 'points_in_boxes_all',\n#     'soft_nms', 'get_compiler_version',\n#     'get_compiling_cuda_version', 'NaiveSyncBatchNorm1d',\n#     'NaiveSyncBatchNorm2d', 'batched_nms', 'Voxelization', 'voxelization',\n#     'dynamic_scatter', 'DynamicScatter',\n#     'SparseBasicBlock', 'SparseBottleneck',\n#     'RoIAwarePool3d', 'points_in_boxes_gpu', 'points_in_boxes_cpu',\n#     'make_sparse_convmodule', 'ball_query', 'knn', 'furthest_point_sample',\n#     'furthest_point_sample_with_dist', 'three_interpolate', 'three_nn',\n#     'gather_points', 'grouping_operation', 'group_points', 'GroupAll',\n#     'QueryAndGroup', 'PointSAModule', 'PointSAModuleMSG', 'PointFPModule',\n#     'points_in_boxes_batch', 'assign_score_withk',\n#     'Points_Sampler', 'build_sa_module',\n#     'PAConv', 'PAConvCUDA', 'PAConvSAModuleMSG', 'PAConvSAModule',\n#     'PAConvCUDASAModule', 'PAConvCUDASAModuleMSG',\n#     'Upsample', 'resize', 'Encoding'\n# ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/box_iou_rotated_utils.hpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_utils.h\n#pragma once\n#include <cassert>\n#include <cmath>\n\n#ifdef __CUDACC__\n// Designates functions callable from the host (CPU) and the device (GPU)\n#define HOST_DEVICE __host__ __device__\n#define HOST_DEVICE_INLINE HOST_DEVICE __forceinline__\n#else\n#include <algorithm>\n#define HOST_DEVICE\n#define HOST_DEVICE_INLINE HOST_DEVICE inline\n#endif\n\nnamespace {\n\ntemplate <typename T>\nstruct RotatedBox {\n  T x_ctr, y_ctr, w, h, a;\n};\n\ntemplate <typename T>\nstruct Point {\n  T x, y;\n  HOST_DEVICE_INLINE Point(const T& px = 0, const T& py = 0) : x(px), y(py) {}\n  HOST_DEVICE_INLINE Point operator+(const Point& p) const {\n    return Point(x + p.x, y + p.y);\n  }\n  HOST_DEVICE_INLINE Point& operator+=(const Point& p) {\n    x += p.x;\n    y += p.y;\n    return *this;\n  }\n  HOST_DEVICE_INLINE Point operator-(const Point& p) const {\n    return Point(x - p.x, y - p.y);\n  }\n  HOST_DEVICE_INLINE Point operator*(const T coeff) const {\n    return Point(x * coeff, y * coeff);\n  }\n};\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T dot_2d(const Point<T>& A, const Point<T>& B) {\n  return A.x * B.x + A.y * B.y;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T cross_2d(const Point<T>& A, const Point<T>& B) {\n  return A.x * B.y - B.x * A.y;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE void get_rotated_vertices(const RotatedBox<T>& box,\n                                             Point<T> (&pts)[4]) {\n  // M_PI / 180. == 0.01745329251\n  // double theta = box.a * 0.01745329251;\n  // MODIFIED\n  double theta = box.a;\n  T cosTheta2 = (T)cos(theta) * 0.5f;\n  T sinTheta2 = (T)sin(theta) * 0.5f;\n\n  // y: top --> down; x: left --> right\n  pts[0].x = box.x_ctr - sinTheta2 * box.h - cosTheta2 * box.w;\n  pts[0].y = box.y_ctr + cosTheta2 * box.h - sinTheta2 * box.w;\n  pts[1].x = box.x_ctr + sinTheta2 * box.h - cosTheta2 * box.w;\n  pts[1].y = box.y_ctr - cosTheta2 * box.h - sinTheta2 * box.w;\n  pts[2].x = 2 * box.x_ctr - pts[0].x;\n  pts[2].y = 2 * box.y_ctr - pts[0].y;\n  pts[3].x = 2 * box.x_ctr - pts[1].x;\n  pts[3].y = 2 * box.y_ctr - pts[1].y;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE int get_intersection_points(const Point<T> (&pts1)[4],\n                                               const Point<T> (&pts2)[4],\n                                               Point<T> (&intersections)[24]) {\n  // Line vector\n  // A line from p1 to p2 is: p1 + (p2-p1)*t, t=[0,1]\n  Point<T> vec1[4], vec2[4];\n  for (int i = 0; i < 4; i++) {\n    vec1[i] = pts1[(i + 1) % 4] - pts1[i];\n    vec2[i] = pts2[(i + 1) % 4] - pts2[i];\n  }\n\n  // Line test - test all line combos for intersection\n  int num = 0;  // number of intersections\n  for (int i = 0; i < 4; i++) {\n    for (int j = 0; j < 4; j++) {\n      // Solve for 2x2 Ax=b\n      T det = cross_2d<T>(vec2[j], vec1[i]);\n\n      // This takes care of parallel lines\n      if (fabs(det) <= 1e-14) {\n        continue;\n      }\n\n      auto vec12 = pts2[j] - pts1[i];\n\n      T t1 = cross_2d<T>(vec2[j], vec12) / det;\n      T t2 = cross_2d<T>(vec1[i], vec12) / det;\n\n      if (t1 >= 0.0f && t1 <= 1.0f && t2 >= 0.0f && t2 <= 1.0f) {\n        intersections[num++] = pts1[i] + vec1[i] * t1;\n      }\n    }\n  }\n\n  // Check for vertices of rect1 inside rect2\n  {\n    const auto& AB = vec2[0];\n    const auto& DA = vec2[3];\n    auto ABdotAB = dot_2d<T>(AB, AB);\n    auto ADdotAD = dot_2d<T>(DA, DA);\n    for (int i = 0; i < 4; i++) {\n      // assume ABCD is the rectangle, and P is the point to be judged\n      // P is inside ABCD iff. P's projection on AB lies within AB\n      // and P's projection on AD lies within AD\n\n      auto AP = pts1[i] - pts2[0];\n\n      auto APdotAB = dot_2d<T>(AP, AB);\n      auto APdotAD = -dot_2d<T>(AP, DA);\n\n      if ((APdotAB >= 0) && (APdotAD >= 0) && (APdotAB <= ABdotAB) &&\n          (APdotAD <= ADdotAD)) {\n        intersections[num++] = pts1[i];\n      }\n    }\n  }\n\n  // Reverse the check - check for vertices of rect2 inside rect1\n  {\n    const auto& AB = vec1[0];\n    const auto& DA = vec1[3];\n    auto ABdotAB = dot_2d<T>(AB, AB);\n    auto ADdotAD = dot_2d<T>(DA, DA);\n    for (int i = 0; i < 4; i++) {\n      auto AP = pts2[i] - pts1[0];\n\n      auto APdotAB = dot_2d<T>(AP, AB);\n      auto APdotAD = -dot_2d<T>(AP, DA);\n\n      if ((APdotAB >= 0) && (APdotAD >= 0) && (APdotAB <= ABdotAB) &&\n          (APdotAD <= ADdotAD)) {\n        intersections[num++] = pts2[i];\n      }\n    }\n  }\n\n  return num;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE int convex_hull_graham(const Point<T> (&p)[24],\n                                          const int& num_in, Point<T> (&q)[24],\n                                          bool shift_to_zero = false) {\n  assert(num_in >= 2);\n\n  // Step 1:\n  // Find point with minimum y\n  // if more than 1 points have the same minimum y,\n  // pick the one with the minimum x.\n  int t = 0;\n  for (int i = 1; i < num_in; i++) {\n    if (p[i].y < p[t].y || (p[i].y == p[t].y && p[i].x < p[t].x)) {\n      t = i;\n    }\n  }\n  auto& start = p[t];  // starting point\n\n  // Step 2:\n  // Subtract starting point from every points (for sorting in the next step)\n  for (int i = 0; i < num_in; i++) {\n    q[i] = p[i] - start;\n  }\n\n  // Swap the starting point to position 0\n  auto tmp = q[0];\n  q[0] = q[t];\n  q[t] = tmp;\n\n  // Step 3:\n  // Sort point 1 ~ num_in according to their relative cross-product values\n  // (essentially sorting according to angles)\n  // If the angles are the same, sort according to their distance to origin\n  T dist[24];\n  for (int i = 0; i < num_in; i++) {\n    dist[i] = dot_2d<T>(q[i], q[i]);\n  }\n\n#ifdef __CUDACC__\n  // CUDA version\n  // In the future, we can potentially use thrust\n  // for sorting here to improve speed (though not guaranteed)\n  for (int i = 1; i < num_in - 1; i++) {\n    for (int j = i + 1; j < num_in; j++) {\n      T crossProduct = cross_2d<T>(q[i], q[j]);\n      if ((crossProduct < -1e-6) ||\n          (fabs(crossProduct) < 1e-6 && dist[i] > dist[j])) {\n        auto q_tmp = q[i];\n        q[i] = q[j];\n        q[j] = q_tmp;\n        auto dist_tmp = dist[i];\n        dist[i] = dist[j];\n        dist[j] = dist_tmp;\n      }\n    }\n  }\n#else\n  // CPU version\n  std::sort(q + 1, q + num_in,\n            [](const Point<T>& A, const Point<T>& B) -> bool {\n              T temp = cross_2d<T>(A, B);\n              if (fabs(temp) < 1e-6) {\n                return dot_2d<T>(A, A) < dot_2d<T>(B, B);\n              } else {\n                return temp > 0;\n              }\n            });\n#endif\n\n  // Step 4:\n  // Make sure there are at least 2 points (that don't overlap with each other)\n  // in the stack\n  int k;  // index of the non-overlapped second point\n  for (k = 1; k < num_in; k++) {\n    if (dist[k] > 1e-8) {\n      break;\n    }\n  }\n  if (k == num_in) {\n    // We reach the end, which means the convex hull is just one point\n    q[0] = p[t];\n    return 1;\n  }\n  q[1] = q[k];\n  int m = 2;  // 2 points in the stack\n  // Step 5:\n  // Finally we can start the scanning process.\n  // When a non-convex relationship between the 3 points is found\n  // (either concave shape or duplicated points),\n  // we pop the previous point from the stack\n  // until the 3-point relationship is convex again, or\n  // until the stack only contains two points\n  for (int i = k + 1; i < num_in; i++) {\n    while (m > 1 && cross_2d<T>(q[i] - q[m - 2], q[m - 1] - q[m - 2]) >= 0) {\n      m--;\n    }\n    q[m++] = q[i];\n  }\n\n  // Step 6 (Optional):\n  // In general sense we need the original coordinates, so we\n  // need to shift the points back (reverting Step 2)\n  // But if we're only interested in getting the area/perimeter of the shape\n  // We can simply return.\n  if (!shift_to_zero) {\n    for (int i = 0; i < m; i++) {\n      q[i] += start;\n    }\n  }\n\n  return m;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T polygon_area(const Point<T> (&q)[24], const int& m) {\n  if (m <= 2) {\n    return 0;\n  }\n\n  T area = 0;\n  for (int i = 1; i < m - 1; i++) {\n    area += fabs(cross_2d<T>(q[i] - q[0], q[i + 1] - q[0]));\n  }\n\n  return area / 2.0;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T rotated_boxes_intersection(const RotatedBox<T>& box1,\n                                                const RotatedBox<T>& box2) {\n  // There are up to 4 x 4 + 4 + 4 = 24 intersections (including dups) returned\n  // from rotated_rect_intersection_pts\n  Point<T> intersectPts[24], orderedPts[24];\n\n  Point<T> pts1[4];\n  Point<T> pts2[4];\n  get_rotated_vertices<T>(box1, pts1);\n  get_rotated_vertices<T>(box2, pts2);\n\n  int num = get_intersection_points<T>(pts1, pts2, intersectPts);\n\n  if (num <= 2) {\n    return 0.0;\n  }\n\n  // Convex Hull to order the intersection points in clockwise order and find\n  // the contour area.\n  int num_convex = convex_hull_graham<T>(intersectPts, num, orderedPts, true);\n  return polygon_area<T>(orderedPts, num_convex);\n}\n\n}  // namespace\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T single_box_iou_rotated(T const* const box1_raw,\n                                            T const* const box2_raw,\n                                            const int mode_flag) {\n  // shift center to the middle point to achieve higher precision in result\n  RotatedBox<T> box1, box2;\n  auto center_shift_x = (box1_raw[0] + box2_raw[0]) / 2.0;\n  auto center_shift_y = (box1_raw[1] + box2_raw[1]) / 2.0;\n  box1.x_ctr = box1_raw[0] - center_shift_x;\n  box1.y_ctr = box1_raw[1] - center_shift_y;\n  box1.w = box1_raw[2];\n  box1.h = box1_raw[3];\n  box1.a = box1_raw[4];\n  box2.x_ctr = box2_raw[0] - center_shift_x;\n  box2.y_ctr = box2_raw[1] - center_shift_y;\n  box2.w = box2_raw[2];\n  box2.h = box2_raw[3];\n  box2.a = box2_raw[4];\n\n  const T area1 = box1.w * box1.h;\n  const T area2 = box2.w * box2.h;\n  if (area1 < 1e-14 || area2 < 1e-14) {\n    return 0.f;\n  }\n\n  const T intersection = rotated_boxes_intersection<T>(box1, box2);\n  T baseS = 1.0;\n  if (mode_flag == 0) {\n    baseS = (area1 + area2 - intersection);\n  } else if (mode_flag == 1) {\n    baseS = area1;\n  }\n  const T iou = intersection / baseS;\n  return iou;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/assign_score_withk_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef ASSIGN_SCORE_WITHK_CUDA_KERNEL_CUH\n#define ASSIGN_SCORE_WITHK_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\n// input: points(B,N0,M,O), centers(B,N0,M,O), scores(B,N1,K,M), knn_idx(B,N1,K)\n// output: fout(B,O,N)\n// algo: fout(b,i,k,j) = s(b,i,k,m)*p(b,c(i),k,m,j) =  s(b,i,k,m)*p(b,i(k),m,j)\n//       i(k) = idx(b,i,k)\n//      sum: fout(b,i,j) = fout(b,i,j) + s(b,i,k,m)*p(b,i,k,m,j)\n//      avg: fout(b,i,j) = sum(fout(b,i,k,j)) / k\n//      max: fout(b,i,j) = max(fout(b,i,k,j), sum(s(b,i,k,m)*p(b,i,k,m,j)))\n\ntemplate <typename T>\n__global__ void assign_score_withk_forward_cuda_kernel(\n    const int B, const int N0, const int N1, const int M, const int K,\n    const int O, const int aggregate, const T* points, const T* centers,\n    const T* scores, const int64_t* knn_idx, T* output) {\n  // ----- parallel loop for B, N1, K and O ---------\n  long i = blockIdx.x * blockDim.x + threadIdx.x;\n  if (i >= B * N1 * K * O) return;\n  // ------- loop for M ----------\n  const int b = (int)(i / (O * N1 * K));\n  const int o = (int)(i % (O * N1 * K) / (N1 * K));\n  const int n = (int)(i % (N1 * K) / K);\n  const int k = (int)(i % K);\n  const int cn = (int)knn_idx[b * K * N1 + n * K +\n                              0];  // The first neighbor is the center point\n  const int kn = (int)knn_idx[b * K * N1 + n * K + k];\n  if (kn >= N0 ||\n      kn < 0) {  // if index overflows, it is out of the neighborhood range\n    return;\n  }\n  assert(b < B);\n  assert(kn < N0);\n  assert(cn < N0);\n  assert(o < O);\n  assert(n < N1);\n  const int out_idx = b * N1 * O * K + o * N1 * K + n * K + k;\n  T val = output[out_idx];\n  for (int m = 0; m < M; m++) {\n    val += points[b * N0 * M * O + kn * M * O + m * O + o] *\n               scores[b * N1 * K * M + n * K * M + k * M + m] -\n           centers[b * N0 * M * O + cn * M * O + m * O + o] *\n               scores[b * N1 * K * M + n * K * M + k * M + m];\n  }\n  output[out_idx] = val;\n}\n\ntemplate <typename T>\n__global__ void assign_score_withk_points_backward_cuda_kernel(\n    const int B, const int N0, const int N, const int M, const int K,\n    const int O, const int aggregate, const T* grad_out, const T* scores,\n    const int64_t* knn_idx, T* grad_points, T* grad_centers) {\n  // ----- parallel loop for B, M, O ---------\n  long i = blockIdx.x * blockDim.x + threadIdx.x;\n  if (i >= B * M * O) return;\n  int b = (int)(i / (M * O));\n  int m = (int)(i % (M * O) / O);\n  int o = (int)(i % O);\n\n  // ----- loop for N,K ---------\n  for (int n = 0; n < N; n++) {\n    for (int k = 0; k < K; k++) {\n      int kn = knn_idx[b * N * K + n * K + k];\n      int cn = knn_idx[b * N * K + n * K + 0];\n      if (kn >= N0 ||\n          kn < 0) {  // if index overflows, it is out of the neighborhood range\n        continue;\n      }\n      atomicAdd(grad_points + b * N0 * M * O + kn * M * O + m * O + o,\n                scores[b * N * K * M + n * K * M + k * M + m] *\n                    grad_out[b * O * N * K + o * N * K + n * K + k]);\n      atomicAdd(grad_centers + b * N0 * M * O + cn * M * O + m * O + o,\n                -scores[b * N * K * M + n * K * M + k * M + m] *\n                    grad_out[b * O * N * K + o * N * K + n * K + k]);\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void assign_score_withk_scores_backward_cuda_kernel(\n    const int B, const int N0, const int N, const int M, const int K,\n    const int O, const int aggregate, const T* grad_out, const T* points,\n    const T* centers, const int64_t* knn_idx, T* grad_scores) {\n  // ----- parallel loop for B, N, K, M ---------\n  long i = blockIdx.x * blockDim.x + threadIdx.x;\n  if (i >= B * N * K * M) return;\n  const int b = (int)(i / (N * M * K));\n  const int n = (int)(i % (N * M * K) / M / K);\n  const int k = (int)(i % (M * K) / M);\n  const int m = (int)(i % M);\n  const int cn = knn_idx[b * N * K + n * K + 0];\n  const int kn = knn_idx[b * N * K + n * K + k];\n  if (kn >= N0 ||\n      kn < 0) {  // if index overflows, it is out of the neighborhood range\n    return;\n  }\n\n  // -------------- loop for O ------------------------\n  const int out_idx = b * N * K * M + n * K * M + k * M + m;\n  T val = grad_scores[out_idx];\n  for (int o = 0; o < O; o++) {\n    val += (points[b * N0 * M * O + kn * M * O + m * O + o] -\n            centers[b * N0 * M * O + cn * M * O + m * O + o]) *\n           grad_out[b * O * N * K + o * N * K + n * K + k];\n  }\n  grad_scores[out_idx] = val;\n}\n\n#endif  // ASSIGN_SCORE_WITHK_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/ball_query_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/ball_query_gpu.cu\n#ifndef BALL_QUERY_CUDA_KERNEL_CUH\n#define BALL_QUERY_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void ball_query_forward_cuda_kernel(int b, int n, int m,\n                                               float min_radius,\n                                               float max_radius, int nsample,\n                                               const T* new_xyz, const T* xyz,\n                                               int* idx) {\n  // new_xyz: (B, M, 3)\n  // xyz: (B, N, 3)\n  // output:\n  //      idx: (B, M, nsample)\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= b || pt_idx >= m) return;\n\n  new_xyz += bs_idx * m * 3 + pt_idx * 3;\n  xyz += bs_idx * n * 3;\n  idx += bs_idx * m * nsample + pt_idx * nsample;\n\n  float max_radius2 = max_radius * max_radius;\n  float min_radius2 = min_radius * min_radius;\n  T new_x = new_xyz[0];\n  T new_y = new_xyz[1];\n  T new_z = new_xyz[2];\n\n  int cnt = 0;\n  for (int k = 0; k < n; ++k) {\n    T x = xyz[k * 3 + 0];\n    T y = xyz[k * 3 + 1];\n    T z = xyz[k * 3 + 2];\n    T d2 = (new_x - x) * (new_x - x) + (new_y - y) * (new_y - y) +\n           (new_z - z) * (new_z - z);\n    if (d2 == 0 || (d2 >= min_radius2 && d2 < max_radius2)) {\n      if (cnt == 0) {\n        for (int l = 0; l < nsample; ++l) {\n          idx[l] = k;\n        }\n      }\n      idx[cnt] = k;\n      ++cnt;\n      if (cnt >= nsample) break;\n    }\n  }\n}\n\n#endif  // BALL_QUERY_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/bbox_overlaps_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef BBOX_OVERLAPS_CUDA_KERNEL_CUH\n#define BBOX_OVERLAPS_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void bbox_overlaps_cuda_kernel(const T* bbox1, const T* bbox2,\n                                          T* ious, const int num_bbox1,\n                                          const int num_bbox2, const int mode,\n                                          const bool aligned,\n                                          const int offset) {\n  if (aligned) {\n    CUDA_1D_KERNEL_LOOP(index, num_bbox1) {\n      int b1 = index;\n      int b2 = index;\n\n      int base1 = b1 * 4;\n      T b1_x1 = bbox1[base1];\n      T b1_y1 = bbox1[base1 + 1];\n      T b1_x2 = bbox1[base1 + 2];\n      T b1_y2 = bbox1[base1 + 3];\n      T b1_area = (b1_x2 - b1_x1 + offset) * (b1_y2 - b1_y1 + offset);\n\n      int base2 = b2 * 4;\n      T b2_x1 = bbox2[base2];\n      T b2_y1 = bbox2[base2 + 1];\n      T b2_x2 = bbox2[base2 + 2];\n      T b2_y2 = bbox2[base2 + 3];\n      T b2_area = (b2_x2 - b2_x1 + offset) * (b2_y2 - b2_y1 + offset);\n\n      T left = fmaxf(b1_x1, b2_x1), right = fminf(b1_x2, b2_x2);\n      T top = fmaxf(b1_y1, b2_y1), bottom = fminf(b1_y2, b2_y2);\n      T width = fmaxf(right - left + offset, 0.f);\n      T height = fmaxf(bottom - top + offset, 0.f);\n      T interS = width * height;\n      T baseS = 1.0;\n      if (mode == 0) {\n        baseS = fmaxf(b1_area + b2_area - interS, T(offset));\n      } else if (mode == 1) {\n        baseS = fmaxf(b1_area, T(offset));\n      }\n      ious[index] = interS / baseS;\n    }\n  } else {\n    CUDA_1D_KERNEL_LOOP(index, num_bbox1 * num_bbox2) {\n      int b1 = index / num_bbox2;\n      int b2 = index % num_bbox2;\n\n      int base1 = b1 * 4;\n      T b1_x1 = bbox1[base1];\n      T b1_y1 = bbox1[base1 + 1];\n      T b1_x2 = bbox1[base1 + 2];\n      T b1_y2 = bbox1[base1 + 3];\n      T b1_area = (b1_x2 - b1_x1 + offset) * (b1_y2 - b1_y1 + offset);\n\n      int base2 = b2 * 4;\n      T b2_x1 = bbox2[base2];\n      T b2_y1 = bbox2[base2 + 1];\n      T b2_x2 = bbox2[base2 + 2];\n      T b2_y2 = bbox2[base2 + 3];\n      T b2_area = (b2_x2 - b2_x1 + offset) * (b2_y2 - b2_y1 + offset);\n\n      T left = fmaxf(b1_x1, b2_x1), right = fminf(b1_x2, b2_x2);\n      T top = fmaxf(b1_y1, b2_y1), bottom = fminf(b1_y2, b2_y2);\n      T width = fmaxf(right - left + offset, 0.f);\n      T height = fmaxf(bottom - top + offset, 0.f);\n      T interS = width * height;\n      T baseS = 1.0;\n      if (mode == 0) {\n        baseS = fmaxf(b1_area + b2_area - interS, T(offset));\n      } else if (mode == 1) {\n        baseS = fmaxf(b1_area, T(offset));\n      }\n      ious[index] = interS / baseS;\n    }\n  }\n}\n\n#endif  // BBOX_OVERLAPS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/border_align_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// modified from\n// https://github.com/Megvii-BaseDetection/cvpods/blob/master/cvpods/layers/csrc/border_align/border_align_kernel.cu.\n// the main difference: (1) use `argmax_idx` for fast computing of gradient\n// during the backward. (2) `wh` is directly computed by `boxes`, rather than\n// passing it as argument to forward or backward functions.\n\n#ifndef BORDER_ALIGN_CUDA_KERNEL_CUH\n#define BORDER_ALIGN_CUDA_KERNEL_CUH\n\n#include <float.h>\n#ifdef MMCV_WITH_TRT\n#include \"common_cuda_helper.hpp\"\n#else  // MMCV_WITH_TRT\n#include \"pytorch_cuda_helper.hpp\"\n#endif  // MMCV_WITH_TRT\n\nenum BorderMode { Top = 0, Left = 1, Bottom = 2, Right = 3 };\n\n/*** Forward ***/\ntemplate <typename T>\n__global__ void border_align_forward_cuda_kernel(\n    const int nthreads, const T* input, const T* boxes, T* output,\n    int* argmax_idx, const int channels, const int box_size, const int height,\n    const int width, const int pool_size) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (batch_idx, c_idx, box_idx) is an element paralleled for computing\n    // output, and `extreme_idx` is in range [0,3]\n    int batch_idx, c_idx, box_idx, extreme_idx, maxidx, *offset_argmax_idx;\n    const T *offset_box, *offset_input, *offset_box_x;\n    T *offset_output, box_width, box_height, stride, x_stride, y_stride, x, y,\n        val, maxval;\n\n    extreme_idx = threadIdx.y;\n    // shape (N, C, box_size, 4) for output\n    batch_idx = index / channels / box_size;\n    // shape (N, box_size, 4) for boxes\n    box_idx = index % box_size + batch_idx * box_size;\n    c_idx = (index / box_size) % channels;\n\n    offset_box = boxes + box_idx * 4;\n    box_width = *(offset_box + 2) - *offset_box;\n    box_height = *(offset_box + 3) - *(offset_box + 1);\n    offset_output = output + index * 4 + extreme_idx;\n    offset_argmax_idx = argmax_idx + index * 4 + extreme_idx;\n    // shape (N, 4C, h, w) for input.\n    // [0,C) for top feature, [C,2C) for left feature,\n    // [2C,3C) for bottom feature, [3C,4C) for right feature\n    offset_input =\n        input + (batch_idx * channels * 4 + extreme_idx * channels + c_idx) *\n                    height * width;\n\n    // extreme_idx in [0,1] -> offset_box_x indexed at x1\n    // extreme_idx in [2,3] -> offset_box_x indexed at x2\n    offset_box_x = offset_box + extreme_idx / 2 * 2;\n\n    // (x1,y1) or (x2,y2) for (x,y)\n    x = *offset_box_x;\n    y = *(offset_box_x + 1);\n\n    switch (extreme_idx) {\n      // top\n      case BorderMode::Top:\n        stride = box_width / pool_size;\n        x_stride = stride;\n        y_stride = 0;\n        break;\n      // left\n      case BorderMode::Left:\n        stride = box_height / pool_size;\n        x_stride = 0;\n        y_stride = stride;\n        break;\n      // bottom\n      case BorderMode::Bottom:\n        stride = box_width / pool_size;\n        x_stride = -stride;\n        y_stride = 0;\n        break;\n      // right\n      case BorderMode::Right:\n        stride = box_height / pool_size;\n        x_stride = 0;\n        y_stride = -stride;\n        break;\n    }\n\n    // initialize maxval and maxidx with the start position (e.g. (x1,y1) or\n    // (x2,y2))\n    maxval = bilinear_interpolate(offset_input, height, width, y, x, index);\n    maxidx = 0;\n\n    // do max_pool along the border\n    for (int i = 1; i <= pool_size; i++) {\n      x += x_stride;\n      y += y_stride;\n      val = bilinear_interpolate(offset_input, height, width, y, x, index);\n      if (val > maxval) {\n        maxval = val;\n        maxidx = i;\n      }\n    }\n\n    // update output and argmax_idx\n    *offset_output = maxval;\n    *offset_argmax_idx = maxidx;\n  }\n}\n\n/*** Backward ***/\ntemplate <typename T>\n__global__ void border_align_backward_cuda_kernel(\n    const int nthreads, const T* grad_output, const T* boxes,\n    const int* argmax_idx, T* grad_input, const int channels,\n    const int box_size, const int height, const int width,\n    const int pool_size) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (batch_idx, c_idx, box_idx) is an element paralleled for computing\n    // output, and `extreme_idx` is in range [0,3]\n    int batch_idx, c_idx, box_idx, extreme_idx;\n    const int* offset_argmax_idx;\n    const T *offset_grad_output, *offset_box, *offset_box_x;\n    T *offset_grad_input, box_width, box_height, stride, x_stride, y_stride, x,\n        y;\n\n    extreme_idx = threadIdx.y;\n    batch_idx = index / channels / box_size;\n    box_idx = index % box_size + batch_idx * box_size;\n    c_idx = (index / box_size) % channels;\n\n    offset_box = boxes + box_idx * 4;\n    box_width = *(offset_box + 2) - *offset_box;\n    box_height = *(offset_box + 3) - *(offset_box + 1);\n    offset_grad_output = grad_output + index * 4 + extreme_idx;\n    offset_argmax_idx = argmax_idx + index * 4 + extreme_idx;\n    // [0,C) for top feature grad, [C,2C) for left feature grad,\n    // [2C,3C) for bottom feature grad, [3C,4C) for right feature grad\n    offset_grad_input = grad_input + (batch_idx * channels * 4 +\n                                      extreme_idx * channels + c_idx) *\n                                         height * width;\n\n    // extreme_idx in [0,1] -> offset_box_x indexed at x1\n    // extreme_idx in [2,3] -> offset_box_x indexed at x2\n    offset_box_x = offset_box + extreme_idx / 2 * 2;\n\n    switch (extreme_idx) {\n      // top\n      case BorderMode::Top:\n        stride = box_width / pool_size;\n        x_stride = stride;\n        y_stride = 0;\n        break;\n      // left\n      case BorderMode::Left:\n        stride = box_height / pool_size;\n        x_stride = 0;\n        y_stride = stride;\n        break;\n      // bottom\n      case BorderMode::Bottom:\n        stride = box_width / pool_size;\n        x_stride = -stride;\n        y_stride = 0;\n        break;\n      // right\n      case BorderMode::Right:\n        stride = box_height / pool_size;\n        x_stride = 0;\n        y_stride = -stride;\n        break;\n    }\n\n    // get position (x,y) which has maximum value during forward\n    x = *offset_box_x;\n    y = *(offset_box_x + 1);\n    x += x_stride * (T)(*offset_argmax_idx);\n    y += y_stride * (T)(*offset_argmax_idx);\n\n    T w1, w2, w3, w4;\n    int x_low, x_high, y_low, y_high;\n    bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4, x_low,\n                                  x_high, y_low, y_high, index);\n\n    // update grad_output\n    atomicAdd(offset_grad_input + y_low * width + x_low,\n              *offset_grad_output * w1);\n    atomicAdd(offset_grad_input + y_low * width + x_high,\n              *offset_grad_output * w2);\n    atomicAdd(offset_grad_input + y_high * width + x_low,\n              *offset_grad_output * w3);\n    atomicAdd(offset_grad_input + y_high * width + x_high,\n              *offset_grad_output * w4);\n  }\n}\n\n#endif  // BORDER_ALIGN_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/box_iou_rotated_cuda.cuh",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_cuda.cu\n#ifndef BOX_IOU_ROTATED_CUDA_CUH\n#define BOX_IOU_ROTATED_CUDA_CUH\n\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"box_iou_rotated_utils.hpp\"\n\n// 2D block with 32 * 16 = 512 threads per block\nconst int BLOCK_DIM_X = 32;\nconst int BLOCK_DIM_Y = 16;\n\ninline int divideUP(const int x, const int y) { return (((x) + (y)-1) / (y)); }\n\ntemplate <typename T>\n__global__ void box_iou_rotated_cuda_kernel(\n    const int n_boxes1, const int n_boxes2, const T* dev_boxes1,\n    const T* dev_boxes2, T* dev_ious, const int mode_flag, const bool aligned) {\n  if (aligned) {\n    CUDA_1D_KERNEL_LOOP(index, n_boxes1) {\n      int b1 = index;\n      int b2 = index;\n\n      int base1 = b1 * 5;\n\n      float block_boxes1[5];\n      float block_boxes2[5];\n\n      block_boxes1[0] = dev_boxes1[base1 + 0];\n      block_boxes1[1] = dev_boxes1[base1 + 1];\n      block_boxes1[2] = dev_boxes1[base1 + 2];\n      block_boxes1[3] = dev_boxes1[base1 + 3];\n      block_boxes1[4] = dev_boxes1[base1 + 4];\n\n      int base2 = b2 * 5;\n\n      block_boxes2[0] = dev_boxes2[base2 + 0];\n      block_boxes2[1] = dev_boxes2[base2 + 1];\n      block_boxes2[2] = dev_boxes2[base2 + 2];\n      block_boxes2[3] = dev_boxes2[base2 + 3];\n      block_boxes2[4] = dev_boxes2[base2 + 4];\n\n      dev_ious[index] =\n          single_box_iou_rotated<T>(block_boxes1, block_boxes2, mode_flag);\n    }\n  } else {\n    CUDA_1D_KERNEL_LOOP(index, n_boxes1 * n_boxes2) {\n      int b1 = index / n_boxes2;\n      int b2 = index % n_boxes2;\n\n      int base1 = b1 * 5;\n\n      float block_boxes1[5];\n      float block_boxes2[5];\n\n      block_boxes1[0] = dev_boxes1[base1 + 0];\n      block_boxes1[1] = dev_boxes1[base1 + 1];\n      block_boxes1[2] = dev_boxes1[base1 + 2];\n      block_boxes1[3] = dev_boxes1[base1 + 3];\n      block_boxes1[4] = dev_boxes1[base1 + 4];\n\n      int base2 = b2 * 5;\n\n      block_boxes2[0] = dev_boxes2[base2 + 0];\n      block_boxes2[1] = dev_boxes2[base2 + 1];\n      block_boxes2[2] = dev_boxes2[base2 + 2];\n      block_boxes2[3] = dev_boxes2[base2 + 3];\n      block_boxes2[4] = dev_boxes2[base2 + 4];\n\n      dev_ious[index] =\n          single_box_iou_rotated<T>(block_boxes1, block_boxes2, mode_flag);\n    }\n  }\n}\n\n#endif\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/carafe_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef CARAFE_CUDA_KERNEL_CUH\n#define CARAFE_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\n#ifdef HIP_DIFF\n#define WARP_SIZE 64\n#else\n#define WARP_SIZE 32\n#endif\n#define THREADS_PER_PIXEL 32\n#define MAX_SHARED_MEMORY 49152\n#define MAX_SHARED_SCALAR_T 6144  // 49152 / 8 = 6144\n#define MAXIMIZE_KERNEL_SIZE true\n#define kTileDim 32\n#define kBlockRows 8\n#define FULL_MASK 0xffffffff\n\ninline int divideUP(const int x, const int y) { return (((x) + (y)-1) / (y)); }\n\n__device__ inline int Loc2Index(const int n, const int c, const int h,\n                                const int w, const int channel_num,\n                                const int height, const int width) {\n  int index = w + (h + (c + n * channel_num) * height) * width;\n  return index;\n}\n#ifndef HIP_DIFF\n/* TODO: move this to a common place */\ntemplate <typename scalar_t>\n__device__ inline scalar_t min(scalar_t a, scalar_t b) {\n  return a < b ? a : b;\n}\n\ntemplate <typename scalar_t>\n__device__ inline scalar_t max(scalar_t a, scalar_t b) {\n  return a > b ? a : b;\n}\n#endif\ntemplate <typename scalar_t>\n__device__ __forceinline__ scalar_t warpReduceSum(scalar_t val) {\n  for (int offset = WARP_SIZE / 2; offset > 0; offset /= 2)\n#ifdef HIP_DIFF\n    val += __shfl_down(val, offset);\n#else\n    val += __shfl_down_sync(FULL_MASK, val, offset);\n#endif\n  return val;\n}\n\ntemplate <>\n__device__ __forceinline__ phalf warpReduceSum(phalf val) {\n  for (int offset = WARP_SIZE / 2; offset > 0; offset /= 2)\n#ifdef HIP_DIFF\n    __PHALF(val) += __shfl_down(FULL_MASK, val, offset);\n#else\n    __PHALF(val) +=\n        __shfl_down_sync(FULL_MASK, static_cast<__half>(__PHALF(val)), offset);\n#endif\n  return val;\n}\n\n// Splits the original matrix into submatrices with size 32 * 32.\n// Each block transposes one submatrix by loading it into shared memory.\n// Reference https://devblogs.nvidia.com/efficient-matrix-transpose-cuda-cc/\ntemplate <typename scalar_t>\n__global__ void BatchTranspose2DCUDAKernel(const int N, const int H,\n                                           const int W, const int dh,\n                                           const int dw,\n                                           const scalar_t *__restrict__ X,\n                                           scalar_t *__restrict__ Y) {\n  __shared__ scalar_t tile[kTileDim][kTileDim + 1];\n  const int n = blockIdx.x / (dh * dw);\n  const int k = blockIdx.x % (dh * dw);\n  const int r = k / dw;\n  const int c = k % dw;\n  const int offset = n * H * W;\n  int x = c * kTileDim + threadIdx.x;\n  int y = r * kTileDim + threadIdx.y;\n  if (x < W) {\n    for (int i = 0; threadIdx.y + i < kTileDim && y + i < H; i += kBlockRows) {\n      tile[threadIdx.y + i][threadIdx.x] = X[offset + (y + i) * W + x];\n    }\n  }\n  __syncthreads();\n  x = r * kTileDim + threadIdx.x;\n  y = c * kTileDim + threadIdx.y;\n  if (x < H) {\n    for (int i = 0; threadIdx.y + i < kTileDim && y + i < W; i += kBlockRows) {\n      Y[offset + (y + i) * H + x] = tile[threadIdx.x][threadIdx.y + i];\n    }\n  }\n}\ntemplate <typename scalar_t>\n__global__ void CARAFEForward(\n    const int num_kernels, const scalar_t *__restrict__ bottom_data,\n    const scalar_t *__restrict__ bottom_masks, const int kernel_size,\n    const int group_size, const int scale_factor, const int channels,\n    const int down_height, const int down_width, const int height,\n    const int width, const int mask_channels, scalar_t *__restrict__ top_data) {\n#if MAXIMIZE_KERNEL_SIZE\n  __shared__ float shared_mask[MAX_SHARED_SCALAR_T * 2];\n#else\n  __shared__ scalar_t shared_mask[MAX_SHARED_SCALAR_T];\n#endif\n\n  int index = threadIdx.x + blockIdx.x * blockDim.x;\n  if (index > num_kernels - 1) {\n    return;\n  }\n  const int pixel_id = threadIdx.x / THREADS_PER_PIXEL;\n  const int split_id = threadIdx.x % THREADS_PER_PIXEL;\n  index = index / THREADS_PER_PIXEL;\n  const int pw = index % width;\n  const int ph = (index / width) % height;\n  const int n = index / width / height;\n\n  const int down_pw = pw / scale_factor;\n  const int down_ph = ph / scale_factor;\n\n  const int start_w = down_pw - (kernel_size - 1) / 2;\n  const int end_w = down_pw + (kernel_size - 1) / 2 + 1;\n  const int start_h = down_ph - (kernel_size - 1) / 2;\n  const int end_h = down_ph + (kernel_size - 1) / 2 + 1;\n  for (int c = split_id; c < mask_channels; c += THREADS_PER_PIXEL) {\n    int mask_index = Loc2Index(n, ph, pw, c, height, width, mask_channels);\n    shared_mask[c * WARP_SIZE + pixel_id] = bottom_masks[mask_index];\n  }\n  __syncthreads();\n\n  const int channels_per_group = ceilf(channels / (float)group_size);\n#pragma unroll\n  for (int c = split_id; c < channels; c += THREADS_PER_PIXEL) {\n    int mask_group = c / channels_per_group;\n    scalar_t output_val = 0;\n#pragma unroll\n    for (int iy = start_h; iy < end_h; iy++) {\n#pragma unroll\n      for (int ix = start_w; ix < end_w; ix++) {\n        if (iy < 0 || iy > down_height - 1 || ix < 0 || ix > down_width - 1) {\n          continue;\n        }\n        int mask_iy = iy - down_ph + (kernel_size - 1) / 2;\n        int mask_ix = ix - down_pw + (kernel_size - 1) / 2;\n        int mask_c =\n            (mask_group * kernel_size + mask_iy) * kernel_size + mask_ix;\n        int feat_index =\n            Loc2Index(n, iy, ix, c, down_height, down_width, channels);\n\n        output_val += bottom_data[feat_index] *\n                      shared_mask[mask_c * WARP_SIZE + pixel_id];\n      }\n    }\n\n    int top_index = Loc2Index(n, ph, pw, c, height, width, channels);\n    top_data[top_index] = output_val;\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void CARAFEBackward_Feature(\n    const int num_kernels, const scalar_t *__restrict__ top_diff,\n    const scalar_t *__restrict__ bottom_masks, const int kernel_size,\n    const int group_size, const int scale_factor, const int channels,\n    const int down_height, const int down_width, const int height,\n    const int width, const int mask_channels,\n    scalar_t *__restrict__ bottom_diff) {\n#if MAXIMIZE_KERNEL_SIZE\n  __shared__ float shared_mask[MAX_SHARED_SCALAR_T * 2];\n#else\n  __shared__ scalar_t shared_mask[MAX_SHARED_SCALAR_T];\n#endif\n\n  int index = threadIdx.x + blockIdx.x * blockDim.x;\n  if (index > num_kernels - 1) {\n    return;\n  }\n\n  const int pixel_id = threadIdx.x / THREADS_PER_PIXEL;\n  const int split_id = threadIdx.x % THREADS_PER_PIXEL;\n  // (n, c, ph, pw) is an element in the bottom_data\n  index = index / THREADS_PER_PIXEL;\n  const int pw = index % width;\n  const int ph = (index / width) % height;\n  const int n = index / width / height;\n\n  const int start_w = pw - (kernel_size - 1) * scale_factor / 2;\n  const int end_w = pw + (kernel_size - 1) * scale_factor / 2 + 1;\n  const int start_h = ph - (kernel_size - 1) * scale_factor / 2;\n  const int end_h = ph + (kernel_size - 1) * scale_factor / 2 + 1;\n  for (int c = split_id; c < mask_channels; c += THREADS_PER_PIXEL) {\n    const int mask_w = (c % kernel_size) * scale_factor;\n    const int mask_h = (c / kernel_size % kernel_size) * scale_factor;\n    const int mask_x = start_w + mask_w;\n    const int mask_y = start_h + mask_h;\n    if (mask_y < 0 || mask_y > height - 1 || mask_x < 0 || mask_x > width - 1) {\n      shared_mask[c * WARP_SIZE + pixel_id] = 0;\n      continue;\n    }\n    const int mask_group = c / (kernel_size * kernel_size);\n    const int mask_c = (2 * mask_group + 1) * kernel_size * kernel_size - c - 1;\n    int mask_index =\n        Loc2Index(n, mask_c, mask_y, mask_x, mask_channels, height, width);\n    shared_mask[c * WARP_SIZE + pixel_id] = bottom_masks[mask_index];\n  }\n  __syncthreads();\n  const int channels_per_group = ceilf(channels / (float)group_size);\n#pragma unroll\n  for (int c = split_id; c < channels; c += THREADS_PER_PIXEL) {\n    int mask_group = c / channels_per_group;\n    int top_index = Loc2Index(n, ph, pw, c, height, width, channels);\n    scalar_t output_val = 0;\n#pragma unroll\n    for (int iy = start_h; iy < end_h; iy += scale_factor) {\n#pragma unroll\n      for (int ix = start_w; ix < end_w; ix += scale_factor) {\n        if (iy < 0 || iy > height - 1 || ix < 0 || ix > width - 1) {\n          continue;\n        }\n        int mask_iy =\n            (iy - ph + (kernel_size - 1) * scale_factor / 2) / scale_factor;\n        int mask_ix =\n            (ix - pw + (kernel_size - 1) * scale_factor / 2) / scale_factor;\n        int mask_c =\n            (mask_group * kernel_size + mask_iy) * kernel_size + mask_ix;\n        int feat_index = Loc2Index(n, iy, ix, c, height, width, channels);\n        output_val +=\n            shared_mask[mask_c * WARP_SIZE + pixel_id] * top_diff[feat_index];\n      }\n    }\n    bottom_diff[top_index] = output_val;\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void FeatureSum(const int num_kernels,\n                           const scalar_t *__restrict__ input_data,\n                           const int scale_factor, const int channels,\n                           const int height, const int width,\n                           scalar_t *__restrict__ output_data) {\n  int index = threadIdx.x + blockIdx.x * blockDim.x;\n  if (index > num_kernels - 1) {\n    return;\n  }\n  const int split_id = threadIdx.x % THREADS_PER_PIXEL;\n  index = index / THREADS_PER_PIXEL;\n  const int pw = index % width;\n  const int ph = (index / width) % height;\n  const int n = index / width / height;\n  for (int c = split_id; c < channels; c += THREADS_PER_PIXEL) {\n    scalar_t output_val = 0;\n    for (int iy = ph * scale_factor; iy < (ph + 1) * scale_factor; iy++) {\n      for (int ix = pw * scale_factor; ix < (pw + 1) * scale_factor; ix++) {\n        int input_id = Loc2Index(n, iy, ix, c, height * scale_factor,\n                                 width * scale_factor, channels);\n        output_val += input_data[input_id];\n      }\n    }\n    const int output_id = Loc2Index(n, ph, pw, c, height, width, channels);\n    output_data[output_id] = output_val;\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void CARAFEBackward_Mask(const int num_kernels,\n                                    const scalar_t *__restrict__ top_diff,\n                                    const scalar_t *__restrict__ bottom_data,\n                                    const int kernel_size, const int group_size,\n                                    const int scale_factor, const int channels,\n                                    const int down_height, const int down_width,\n                                    const int height, const int width,\n                                    const int mask_channels,\n                                    scalar_t *__restrict__ mask_diff) {\n  int index = threadIdx.x + blockIdx.x * blockDim.x;\n  if (index > num_kernels - 1) {\n    return;\n  }\n\n  const int lane_id = index % WARP_SIZE;\n  index = index / WARP_SIZE;\n  const int mask_c = index % mask_channels;\n  // (n, c, ph, pw) is an element in the bottom_data\n  index = index / mask_channels;\n  const int pw = index % width;\n  const int ph = (index / width) % height;\n  const int n = index / width / height;\n\n  const int down_pw = pw / scale_factor;\n  const int down_ph = ph / scale_factor;\n\n  const int mask_group = mask_c / (kernel_size * kernel_size);\n  const int mask_loc = mask_c % (kernel_size * kernel_size);\n\n  const int offset_x = mask_loc % kernel_size - (kernel_size - 1) / 2;\n  const int offset_y =\n      mask_loc / kernel_size % kernel_size - (kernel_size - 1) / 2;\n\n  const int down_x = down_pw + offset_x;\n  const int down_y = down_ph + offset_y;\n\n  scalar_t output_val = 0;\n\n  if (down_y >= 0 && down_y <= down_height - 1 && down_x >= 0 &&\n      down_x <= down_width - 1) {\n    const int channels_per_mask = ceilf(channels / (float)group_size);\n    const int start = channels_per_mask * mask_group;\n    const int end = min(channels_per_mask * (mask_group + 1), channels);\n    for (int c = start + lane_id; c < end; c += WARP_SIZE) {\n      int bottom_id =\n          Loc2Index(n, down_y, down_x, c, down_height, down_width, channels);\n      int top_id = Loc2Index(n, ph, pw, c, height, width, channels);\n      output_val += top_diff[top_id] * bottom_data[bottom_id];\n    }\n  }\n#ifdef HIP_DIFF\n  __syncthreads();\n#else\n  __syncwarp();\n#endif\n  output_val = warpReduceSum(output_val);\n  if (lane_id == 0) {\n    const int mask_id =\n        Loc2Index(n, ph, pw, mask_c, height, width, mask_channels);\n    mask_diff[mask_id] = output_val;\n  }\n}\n\n#endif  // CARAFE_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/carafe_naive_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef CARAFE_NAIVE_CUDA_KERNEL_CUH\n#define CARAFE_NAIVE_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\n__device__ inline int Loc2Index(const int n, const int c, const int h,\n                                const int w, const int channel_num,\n                                const int height, const int width) {\n  int index = w + (h + (c + n * channel_num) * height) * width;\n  return index;\n}\n\ntemplate <typename scalar_t>\n__global__ void carafe_naive_forward_cuda_kernel(\n    const int nthreads, const scalar_t *bottom_data,\n    const scalar_t *bottom_masks, scalar_t *top_data, const int kernel_size,\n    const int group_size, const int scale_factor, const int channels,\n    const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the bottom_data\n    int pw = index % width;\n    int ph = (index / width) % height;\n    int c = (index / width / height) % channels;\n    int n = index / width / height / channels;\n\n    int mask_channels = kernel_size * kernel_size * group_size;\n    int mask_group = c / (channels / group_size);\n\n    int down_pw = pw / scale_factor;\n    int down_ph = ph / scale_factor;\n    int down_width = width / scale_factor;\n    int down_height = height / scale_factor;\n    int start_w = down_pw - (kernel_size - 1) / 2;\n    int end_w = down_pw + (kernel_size - 1) / 2 + 1;\n    int start_h = down_ph - (kernel_size - 1) / 2;\n    int end_h = down_ph + (kernel_size - 1) / 2 + 1;\n\n    scalar_t output_val = 0;\n    for (int iy = start_h; iy < end_h; iy++) {\n      for (int ix = start_w; ix < end_w; ix++) {\n        if (iy < 0 || iy > down_height - 1 || ix < 0 || ix > down_width - 1) {\n          continue;\n        }\n        int mask_iy = iy - down_ph + (kernel_size - 1) / 2;\n        int mask_ix = ix - down_pw + (kernel_size - 1) / 2;\n        int mask_c =\n            (mask_group * kernel_size + mask_iy) * kernel_size + mask_ix;\n        int feat_index =\n            Loc2Index(n, c, iy, ix, channels, down_height, down_width);\n        int mask_index =\n            Loc2Index(n, mask_c, ph, pw, mask_channels, height, width);\n        output_val += bottom_data[feat_index] * bottom_masks[mask_index];\n      }\n    }\n    top_data[index] = output_val;\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void carafe_naive_backward_cuda_kernel(\n    const int nthreads, const scalar_t *top_diff, const scalar_t *bottom_data,\n    const scalar_t *bottom_masks, scalar_t *bottom_diff, scalar_t *mask_diff,\n    const int kernel_size, const int group_size, const int scale_factor,\n    const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the bottom_data\n    int pw = index % width;\n    int ph = (index / width) % height;\n    int c = (index / width / height) % channels;\n    int n = index / width / height / channels;\n\n    int mask_channels = kernel_size * kernel_size * group_size;\n    int mask_group = c / (channels / group_size);\n\n    int down_pw = pw / scale_factor;\n    int down_ph = ph / scale_factor;\n    int down_width = width / scale_factor;\n    int down_height = height / scale_factor;\n    int start_w = down_pw - (kernel_size - 1) / 2;\n    int end_w = down_pw + (kernel_size - 1) / 2 + 1;\n    int start_h = down_ph - (kernel_size - 1) / 2;\n    int end_h = down_ph + (kernel_size - 1) / 2 + 1;\n\n    for (int iy = start_h; iy < end_h; iy++) {\n      for (int ix = start_w; ix < end_w; ix++) {\n        if (iy < 0 || iy > down_height - 1 || ix < 0 || ix > down_width - 1) {\n          continue;\n        }\n        int mask_iy = iy - down_ph + (kernel_size - 1) / 2;\n        int mask_ix = ix - down_pw + (kernel_size - 1) / 2;\n        int mask_c =\n            (mask_group * kernel_size + mask_iy) * kernel_size + mask_ix;\n        int feat_index =\n            Loc2Index(n, c, iy, ix, channels, down_height, down_width);\n        int mask_index =\n            Loc2Index(n, mask_c, ph, pw, mask_channels, height, width);\n        atomicAdd(bottom_diff + feat_index,\n                  bottom_masks[mask_index] * top_diff[index]);\n        atomicAdd(mask_diff + mask_index,\n                  bottom_data[feat_index] * top_diff[index]);\n      }\n    }\n  }\n}\n\n#endif  // CARAFE_NAIVE_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/common_cuda_helper.hpp",
    "content": "#ifndef COMMON_CUDA_HELPER\n#define COMMON_CUDA_HELPER\n\n#include <cuda.h>\n\n#define CUDA_1D_KERNEL_LOOP(i, n)                              \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < (n); \\\n       i += blockDim.x * gridDim.x)\n\n#define THREADS_PER_BLOCK 512\n\n#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))\n\ninline int GET_BLOCKS(const int N) {\n  int optimal_block_num = (N + THREADS_PER_BLOCK - 1) / THREADS_PER_BLOCK;\n  int max_block_num = 4096;\n  return min(optimal_block_num, max_block_num);\n}\n\ntemplate <typename T>\n__device__ T bilinear_interpolate(const T* input, const int height,\n                                  const int width, T y, T x,\n                                  const int index /* index for debug only*/) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) return 0;\n\n  if (y <= 0) y = 0;\n  if (x <= 0) x = 0;\n\n  int y_low = (int)y;\n  int x_low = (int)x;\n  int y_high;\n  int x_high;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n  // do bilinear interpolation\n  T v1 = input[y_low * width + x_low];\n  T v2 = input[y_low * width + x_high];\n  T v3 = input[y_high * width + x_low];\n  T v4 = input[y_high * width + x_high];\n  T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  return val;\n}\n\ntemplate <typename T>\n__device__ void bilinear_interpolate_gradient(\n    const int height, const int width, T y, T x, T& w1, T& w2, T& w3, T& w4,\n    int& x_low, int& x_high, int& y_low, int& y_high,\n    const int index /* index for debug only*/) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y <= 0) y = 0;\n  if (x <= 0) x = 0;\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n#endif  // COMMON_CUDA_HELPER\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/correlation_cuda.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n// Modified from\n// https://github.com/ClementPinard/Pytorch-Correlation-extension/blob/master/Correlation_Module/correlation_cuda_kernel.cu\n// Original licence: Under MIT License\n\n#ifndef CORRELATION_CUDA\n#define CORRELATION_CUDA\n\n#include \"pytorch_cuda_helper.hpp\"\n\n#include <cuda.h>\n#include <cuda_runtime.h>\n// Using <torch/extension.h> is recommended in the official documentation in\n// https://pytorch.org/tutorials/advanced/cpp_extension.html#writing-the-c-op.\n// However, we use <torch/types.h> for compatibility with CUDA 9.0\n// Read https://github.com/pytorch/extension-cpp/issues/35 for more details.\n#include <torch/types.h>\n\n#include <iostream>\n#include <vector>\n\nusing namespace torch;\n\n#define TensorAcc4R PackedTensorAccessor32<scalar_t, 4, RestrictPtrTraits>\n#define TensorAcc5R PackedTensorAccessor32<scalar_t, 5, RestrictPtrTraits>\n#define WITHIN_BOUNDS(x, y, H, W) (x >= 0 && x < H && y >= 0 && y < W)\n\n#define THREADS_FORWARD 32\n#define THREADS_BACKWARD 16\n\ntemplate <typename scalar_t>\n__global__ void correlation_forward_cuda_kernel(\n    const TensorAcc4R rInput1, const TensorAcc4R rInput2, TensorAcc5R output,\n    int kH, int kW, int patchH, int patchW, int padH, int padW, int dilationH,\n    int dilationW, int dilation_patchH, int dilation_patchW, int dH, int dW) {\n  const int iH = rInput1.size(1);\n  const int iW = rInput1.size(2);\n  const int C = rInput1.size(3);\n\n  const int n = blockIdx.x;\n  const int h = blockIdx.y;\n  const int w = blockIdx.z;\n  const int thread = threadIdx.x;\n\n  const int start_i = -padH + h * dH;\n  const int start_j = -padW + w * dW;\n\n  const int patchRadH = dilation_patchH * (patchH - 1) / 2;\n  const int patchRadW = dilation_patchW * (patchW - 1) / 2;\n\n  __shared__ scalar_t prod_sum[THREADS_FORWARD];\n\n  for (int ph = 0; ph < patchH; ++ph) {\n    int ph_dilated = ph * dilation_patchH - patchRadH;\n    for (int pw = 0; pw < patchW; ++pw) {\n      int pw_dilated = pw * dilation_patchW - patchRadW;\n      prod_sum[thread] = 0;\n      for (int i = 0; i < kH; ++i) {\n        int i1 = start_i + i * dilationH;\n        int i2 = i1 + ph_dilated;\n        if\n          WITHIN_BOUNDS(i1, i2, iH, iH) {\n            for (int j = 0; j < kW; ++j) {\n              int j1 = start_j + j * dilationW;\n              int j2 = j1 + pw_dilated;\n              if\n                WITHIN_BOUNDS(j1, j2, iW, iW) {\n                  for (int c = thread; c < C; c += THREADS_FORWARD) {\n                    scalar_t v1 = rInput1[n][i1][j1][c];\n                    scalar_t v2 = rInput2[n][i2][j2][c];\n                    prod_sum[thread] += v1 * v2;\n                  }\n                }\n            }\n          }\n      }\n      // accumulate\n      __syncthreads();\n      if (thread == 0) {\n        scalar_t reduce_sum = 0;\n        for (int index = 0; index < THREADS_FORWARD; ++index) {\n          reduce_sum += prod_sum[index];\n        }\n        output[n][ph][pw][h][w] = reduce_sum;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void correlation_backward_cuda_kernel_input1(\n    const TensorAcc5R grad_output, const TensorAcc4R input2,\n    TensorAcc4R grad_input1, const int kH, const int kW, const int patchH,\n    const int patchW, const int padH, const int padW, const int dilationH,\n    const int dilationW, const int dilation_patchH, const int dilation_patchW,\n    const int dH, const int dW, const int batch) {\n  const int iH = input2.size(2);\n  const int iW = input2.size(3);\n\n  const int H = grad_output.size(3);\n  const int W = grad_output.size(4);\n\n  const int patchRadH = (patchH - 1) / 2;\n  const int patchRadW = (patchW - 1) / 2;\n\n  const int n = batch;\n  const int c = blockIdx.x;\n  const int h = blockIdx.y;\n  const int w = blockIdx.z;\n  const int ph_off = threadIdx.x;\n  const int pw_off = threadIdx.y;\n\n  const int h_2 = h + padH;\n  const int w_2 = w + padW;\n  const int min_h = h_2 - kH * dilationH;\n  const int min_w = w_2 - kW * dilationW;\n\n  __shared__ scalar_t prod_sum[THREADS_BACKWARD][THREADS_BACKWARD];\n  prod_sum[ph_off][pw_off] = 0;\n\n  for (int ph = ph_off; ph < patchH; ph += THREADS_BACKWARD) {\n    int i1 = h + dilation_patchH * (ph - patchRadH);\n    for (int pw = pw_off; pw < patchW; pw += THREADS_BACKWARD) {\n      int j1 = w + dilation_patchW * (pw - patchRadW);\n      if (WITHIN_BOUNDS(i1, j1, iH, iW)) {\n        scalar_t val = input2[n][c][i1][j1];\n        for (int h_3 = h_2; h_3 > min_h; h_3 -= dilationH) {\n          int i2 = (h_3) / dH;\n          if (i2 * dH != h_3) continue;\n          for (int w_3 = w_2; w_3 > min_w; w_3 -= dilationW) {\n            int j2 = (w_3) / dW;\n            if (j2 * dW != w_3) continue;\n            if\n              WITHIN_BOUNDS(i2, j2, H, W) {\n                prod_sum[ph_off][pw_off] +=\n                    grad_output[n][ph][pw][i2][j2] * val;\n              }\n          }\n        }\n      }\n    }\n  }\n\n  __syncthreads();\n\n  if (ph_off == 0 && pw_off == 0) {\n    scalar_t reduce_sum = 0;\n    for (int ph = 0; ph < THREADS_BACKWARD; ++ph) {\n      for (int pw = 0; pw < THREADS_BACKWARD; ++pw) {\n        reduce_sum += prod_sum[ph][pw];\n      }\n    }\n    grad_input1[n][c][h][w] = reduce_sum;\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void correlation_backward_cuda_kernel_input2(\n    const TensorAcc5R grad_output, const TensorAcc4R input1,\n    TensorAcc4R grad_input2, int kH, int kW, int patchH, int patchW, int padH,\n    int padW, int dilationH, int dilationW, int dilation_patchH,\n    int dilation_patchW, int dH, int dW, int batch) {\n  const int iH = input1.size(2);\n  const int iW = input1.size(3);\n\n  const int patchRadH = (patchH - 1) / 2;\n  const int patchRadW = (patchW - 1) / 2;\n\n  const int H = grad_output.size(3);\n  const int W = grad_output.size(4);\n\n  const int dilatedKH = kH * dilationH;\n  const int dilatedKW = kW * dilationW;\n\n  const int n = batch;\n  const int c = blockIdx.x;\n  const int h = blockIdx.y;\n  const int w = blockIdx.z;\n  const int ph_off = threadIdx.x;\n  const int pw_off = threadIdx.y;\n\n  __shared__ scalar_t prod_sum[THREADS_BACKWARD][THREADS_BACKWARD];\n  prod_sum[ph_off][pw_off] = 0;\n\n  for (int ph = ph_off; ph < patchH; ph += THREADS_BACKWARD) {\n    int i1 = h - dilation_patchH * (ph - patchRadH);\n    for (int pw = pw_off; pw < patchW; pw += THREADS_BACKWARD) {\n      int j1 = w - dilation_patchW * (pw - patchRadW);\n      if\n        WITHIN_BOUNDS(i1, j1, iH, iW) {\n          scalar_t val = input1[n][c][i1][j1];\n\n          const int h_2 = i1 + padH;\n          const int w_2 = j1 + padW;\n          const int min_h = h_2 - dilatedKH;\n          const int min_w = w_2 - dilatedKW;\n\n          for (int h_3 = h_2; h_3 > min_h; h_3 -= dilationH) {\n            int i2 = (h_3) / dH;\n            if (i2 * dH != h_3) continue;\n            for (int w_3 = w_2; w_3 > min_w; w_3 -= dilationW) {\n              int j2 = (w_3) / dW;\n              if (j2 * dW != w_3) continue;\n              if\n                WITHIN_BOUNDS(i2, j2, H, W) {\n                  prod_sum[ph_off][pw_off] +=\n                      grad_output[n][ph][pw][i2][j2] * val;\n                }\n            }\n          }\n        }\n    }\n  }\n\n  __syncthreads();\n\n  if (ph_off == 0 && pw_off == 0) {\n    scalar_t reduce_sum = 0;\n    for (int ph = 0; ph < THREADS_BACKWARD; ++ph) {\n      for (int pw = 0; pw < THREADS_BACKWARD; ++pw) {\n        reduce_sum += prod_sum[ph][pw];\n      }\n    }\n    grad_input2[n][c][h][w] = reduce_sum;\n  }\n}\n#endif\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/deform_conv_cuda_kernel.cuh",
    "content": "/*!\n ******************* BEGIN Caffe Copyright Notice and Disclaimer\n *****************\n *\n * COPYRIGHT\n *\n * All contributions by the University of California:\n * Copyright (c) 2014-2017 The Regents of the University of California (Regents)\n * All rights reserved.\n *\n * All other contributions:\n * Copyright (c) 2014-2017, the respective contributors\n * All rights reserved.\n *\n * Caffe uses a shared copyright model: each contributor holds copyright over\n * their contributions to Caffe. The project versioning records all such\n * contribution and copyright details. If a contributor wants to further mark\n * their specific copyright on a particular contribution, they should indicate\n * their copyright solely in the commit message of the change when it is\n * committed.\n *\n * LICENSE\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n * 1. Redistributions of source code must retain the above copyright notice,\n *this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above copyright notice,\n * this list of conditions and the following disclaimer in the documentation\n * and/or other materials provided with the distribution.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n *AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n *IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE\n *FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\n *DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\n *SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\n *OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\n *OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n *\n * CONTRIBUTION AGREEMENT\n *\n * By contributing to the BVLC/caffe repository through pull-request, comment,\n * or otherwise, the contributor releases their content to the\n * license and copyright terms herein.\n *\n ***************** END Caffe Copyright Notice and Disclaimer\n *********************\n *\n * Copyright (c) 2018 Microsoft\n * Licensed under The MIT License [see LICENSE for details]\n * \\file modulated_deformable_im2col.cuh\n * \\brief Function definitions of converting an image to\n * column matrix based on kernel, padding, dilation, and offset.\n * These functions are mainly used in deformable convolution operators.\n * \\ref: https://arxiv.org/abs/1703.06211\n * \\author Yuwen Xiong, Haozhi Qi, Jifeng Dai, Xizhou Zhu, Han Hu, Dazhi Cheng\n */\n\n// modified from\n// https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/blob/mmdetection/mmdet/ops/dcn/src/deform_conv_cuda_kernel.cu\n\n#ifndef DEFORM_CONV_CUDA_KERNEL_CUH\n#define DEFORM_CONV_CUDA_KERNEL_CUH\n\n#include <float.h>\n#ifdef MMCV_WITH_TRT\n#include \"common_cuda_helper.hpp\"\n#else  // MMCV_WITH_TRT\n#include \"pytorch_cuda_helper.hpp\"\n#endif  // MMCV_WITH_TRT\n\ntemplate <typename T>\n__device__ T deformable_im2col_bilinear(const T *input, const int data_width,\n                                        const int height, const int width, T h,\n                                        T w) {\n  if (h <= -1 || height <= h || w <= -1 || width <= w) {\n    return 0;\n  }\n\n  int h_low = floorf(h);\n  int w_low = floorf(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  T lh = h - h_low;\n  T lw = w - w_low;\n  T hh = 1 - lh, hw = 1 - lw;\n\n  T v1 = 0;\n  if (h_low >= 0 && w_low >= 0) v1 = input[h_low * data_width + w_low];\n  T v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = input[h_low * data_width + w_high];\n  T v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = input[h_high * data_width + w_low];\n  T v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = input[h_high * data_width + w_high];\n\n  T w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename T>\n__device__ T get_gradient_weight(T argmax_h, T argmax_w, const int h,\n                                 const int w, const int height,\n                                 const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floorf(argmax_h);\n  int argmax_w_low = floorf(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename T>\n__device__ T get_coordinate_weight(T argmax_h, T argmax_w, const int height,\n                                   const int width, const T *im_data,\n                                   const int data_width, const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floorf(argmax_h);\n  int argmax_w_low = floorf(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename T>\n__global__ void deformable_im2col_gpu_kernel(\n    const int n, const T *data_im, const T *data_offset, const int height,\n    const int width, const int kernel_h, const int kernel_w, const int pad_h,\n    const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int num_channels, const int deformable_group, const int height_col,\n    const int width_col, T *data_col) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n    T *data_col_ptr =\n        data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    const T *data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const T *data_offset_ptr =\n        data_offset + (b_col * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const T offset_h = data_offset_ptr[data_offset_h_ptr];\n        const T offset_w = data_offset_ptr[data_offset_w_ptr];\n        T val = static_cast<T>(0);\n        const T h_im = h_in + i * dilation_h + offset_h;\n        const T w_im = w_in + j * dilation_w + offset_w;\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width)\n          val = deformable_im2col_bilinear(data_im_ptr, width, height, width,\n                                           h_im, w_im);\n        *data_col_ptr = val;\n        data_col_ptr += batch_size * height_col * width_col;\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void deformable_col2im_gpu_kernel(\n    const int n, const T *data_col, const T *data_offset, const int channels,\n    const int height, const int width, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int deformable_group, const int height_col, const int width_col,\n    T *grad_im) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const T offset_h = data_offset_ptr[data_offset_h_ptr];\n    const T offset_w = data_offset_ptr[data_offset_w_ptr];\n    const T cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const T cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const T cur_top_grad = data_col[index];\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          T weight = get_gradient_weight(cur_inv_h_data, cur_inv_w_data,\n                                         cur_h + dy, cur_w + dx, height, width);\n          atomicAdd(grad_im + cur_bottom_grad_pos, weight * cur_top_grad);\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void deformable_col2im_coord_gpu_kernel(\n    const int n, const T *data_col, const T *data_im, const T *data_offset,\n    const int channels, const int height, const int width, const int kernel_h,\n    const int kernel_w, const int pad_h, const int pad_w, const int stride_h,\n    const int stride_w, const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int offset_channels, const int deformable_group, const int height_col,\n    const int width_col, T *grad_offset) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    T val = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const T *data_col_ptr = data_col + deformable_group_index *\n                                           channel_per_deformable_group *\n                                           batch_size * width_col * height_col;\n    const T *data_im_ptr =\n        data_im + (b * deformable_group + deformable_group_index) *\n                      channel_per_deformable_group / kernel_h / kernel_w *\n                      height * width;\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const T offset_h = data_offset_ptr[data_offset_h_ptr];\n      const T offset_w = data_offset_ptr[data_offset_w_ptr];\n      T inv_h = h_in + i * dilation_h + offset_h;\n      T inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width)\n        inv_h = inv_w = -2;\n      const T weight = get_coordinate_weight(inv_h, inv_w, height, width,\n                                             data_im_ptr + cnt * height * width,\n                                             width, bp_dir);\n      val += weight * data_col_ptr[col_pos];\n      cnt += 1;\n    }\n\n    grad_offset[index] = val;\n  }\n}\n\n#endif  // DEFORM_CONV_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/deform_roi_pool_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef DEFORM_ROI_POOL_CUDA_KERNEL_CUH\n#define DEFORM_ROI_POOL_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void deform_roi_pool_forward_cuda_kernel(\n    const int nthreads, const T* input, const T* rois, const T* offset,\n    T* output, const int pooled_height, const int pooled_width,\n    const T spatial_scale, const int sampling_ratio, const T gamma,\n    const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n\n    // Do not using rounding; this implementation detail is critical\n    T roi_start_w = offset_rois[1] * spatial_scale - 0.5;\n    T roi_start_h = offset_rois[2] * spatial_scale - 0.5;\n    T roi_end_w = offset_rois[3] * spatial_scale - 0.5;\n    T roi_end_h = offset_rois[4] * spatial_scale - 0.5;\n\n    T roi_width = roi_end_w - roi_start_w;\n    T roi_height = roi_end_h - roi_start_h;\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    const T* offset_input =\n        input + (roi_batch_ind * channels + c) * height * width;\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h =\n        (sampling_ratio > 0)\n            ? sampling_ratio\n            : static_cast<int>(ceilf(roi_height / pooled_height));\n    int roi_bin_grid_w =\n        (sampling_ratio > 0)\n            ? sampling_ratio\n            : static_cast<int>(ceilf(roi_width / pooled_width));\n\n    // Compute roi offset\n    if (offset != NULL) {\n      const T* offset_cur_w = offset + n * pooled_width * pooled_height * 2 +\n                              ph * pooled_width + pw;\n      T offset_roi_w = gamma * roi_width * offset_cur_w[0];\n      T offset_roi_h =\n          gamma * roi_height * offset_cur_w[pooled_width * pooled_height];\n      roi_start_w += offset_roi_w;\n      roi_start_h += offset_roi_h;\n    }\n\n    // We do average pooling inside a bin\n    const T count = max(roi_bin_grid_h * roi_bin_grid_w, 1);\n    T output_val = 0.;\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n      const T y = roi_start_h + ph * bin_size_h +\n                  static_cast<T>(iy + .5f) * bin_size_h /\n                      static_cast<T>(roi_bin_grid_h);\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T x = roi_start_w + pw * bin_size_w +\n                    static_cast<T>(ix + .5f) * bin_size_w /\n                        static_cast<T>(roi_bin_grid_w);\n        T val = bilinear_interpolate(offset_input, height, width, y, x, index);\n        output_val += val;\n      }\n    }\n    output[index] = output_val / count;\n  }\n}\n\ntemplate <typename T>\n__global__ void deform_roi_pool_backward_cuda_kernel(\n    const int nthreads, const T* grad_output, const T* input, const T* rois,\n    const T* offset, T* grad_input, T* grad_offset, const int pooled_height,\n    const int pooled_width, const T spatial_scale, const int sampling_ratio,\n    const T gamma, const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n    const T* offset_input =\n        input + ((roi_batch_ind * channels + c) * height * width);\n    T* offset_grad_input =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n\n    // Do not using rounding; this implementation detail is critical\n    T roi_start_w = offset_rois[1] * spatial_scale - 0.5;\n    T roi_start_h = offset_rois[2] * spatial_scale - 0.5;\n    T roi_end_w = offset_rois[3] * spatial_scale - 0.5;\n    T roi_end_h = offset_rois[4] * spatial_scale - 0.5;\n\n    T roi_width = roi_end_w - roi_start_w;\n    T roi_height = roi_end_h - roi_start_h;\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h =\n        (sampling_ratio > 0)\n            ? sampling_ratio\n            : static_cast<int>(ceilf(roi_height / pooled_height));\n    int roi_bin_grid_w =\n        (sampling_ratio > 0)\n            ? sampling_ratio\n            : static_cast<int>(ceilf(roi_width / pooled_width));\n\n    // Compute roi offset\n    if (offset != NULL) {\n      const T* offset_cur_w = offset + n * pooled_width * pooled_height * 2 +\n                              ph * pooled_width + pw;\n      T offset_roi_w = gamma * roi_width * offset_cur_w[0];\n      T offset_roi_h =\n          gamma * roi_height * offset_cur_w[pooled_width * pooled_height];\n      roi_start_w += offset_roi_w;\n      roi_start_h += offset_roi_h;\n    }\n\n    // We do average (integral) pooling inside a bin\n    const T count = roi_bin_grid_h * roi_bin_grid_w;  // e.g. = 4\n    const T grad_output_this_bin = grad_output[index] / count;\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n      const T y = roi_start_h + ph * bin_size_h +\n                  static_cast<T>(iy + .5f) * bin_size_h /\n                      static_cast<T>(roi_bin_grid_h);\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T x = roi_start_w + pw * bin_size_w +\n                    static_cast<T>(ix + .5f) * bin_size_w /\n                        static_cast<T>(roi_bin_grid_w);\n\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n        bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4,\n                                      x_low, x_high, y_low, y_high, index);\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          atomicAdd(offset_grad_input + y_low * width + x_low,\n                    grad_output_this_bin * w1);\n          atomicAdd(offset_grad_input + y_low * width + x_high,\n                    grad_output_this_bin * w2);\n          atomicAdd(offset_grad_input + y_high * width + x_low,\n                    grad_output_this_bin * w3);\n          atomicAdd(offset_grad_input + y_high * width + x_high,\n                    grad_output_this_bin * w4);\n          if (offset != NULL) {\n            T input_00 = offset_input[y_low * width + x_low];\n            T input_10 = offset_input[y_low * width + x_high];\n            T input_01 = offset_input[y_high * width + x_low];\n            T input_11 = offset_input[y_high * width + x_high];\n            T ogx = gamma * roi_width * grad_output_this_bin *\n                    (input_11 * (y - y_low) + input_10 * (y_high - y) +\n                     input_01 * (y_low - y) + input_00 * (y - y_high));\n            T ogy = gamma * roi_height * grad_output_this_bin *\n                    (input_11 * (x - x_low) + input_01 * (x_high - x) +\n                     input_10 * (x_low - x) + input_00 * (x - x_high));\n            atomicAdd(grad_offset + n * pooled_width * pooled_height * 2 +\n                          ph * pooled_width + pw,\n                      ogx);\n            atomicAdd(grad_offset + n * pooled_width * pooled_height * 2 +\n                          pooled_width * pooled_height + ph * pooled_width + pw,\n                      ogy);\n          }\n        }\n      }\n    }\n  }\n}\n\n#endif  // DEFORM_ROI_POOL_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/furthest_point_sample_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef FURTHEST_POINT_SAMPLE_CUDA_KERNEL_CUH\n#define FURTHEST_POINT_SAMPLE_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\n__device__ void __update(float *__restrict__ dists, int *__restrict__ dists_i,\n                         int idx1, int idx2) {\n  const float v1 = dists[idx1], v2 = dists[idx2];\n  const int i1 = dists_i[idx1], i2 = dists_i[idx2];\n  dists[idx1] = max(v1, v2);\n  dists_i[idx1] = v2 > v1 ? i2 : i1;\n}\n\ntemplate <unsigned int block_size>\n__global__ void furthest_point_sampling_forward_cuda_kernel(\n    int b, int n, int m, const float *__restrict__ dataset,\n    float *__restrict__ temp, int *__restrict__ idxs) {\n  // dataset: (B, N, 3)\n  // tmp: (B, N)\n  // output:\n  //      idx: (B, M)\n\n  if (m <= 0) return;\n  __shared__ float dists[block_size];\n  __shared__ int dists_i[block_size];\n\n  int batch_index = blockIdx.x;\n  dataset += batch_index * n * 3;\n  temp += batch_index * n;\n  idxs += batch_index * m;\n\n  int tid = threadIdx.x;\n  const int stride = block_size;\n\n  int old = 0;\n  if (threadIdx.x == 0) idxs[0] = old;\n\n  __syncthreads();\n  for (int j = 1; j < m; j++) {\n    int besti = 0;\n    float best = -1;\n    float x1 = dataset[old * 3 + 0];\n    float y1 = dataset[old * 3 + 1];\n    float z1 = dataset[old * 3 + 2];\n    for (int k = tid; k < n; k += stride) {\n      float x2, y2, z2;\n      x2 = dataset[k * 3 + 0];\n      y2 = dataset[k * 3 + 1];\n      z2 = dataset[k * 3 + 2];\n      // float mag = (x2 * x2) + (y2 * y2) + (z2 * z2);\n      // if (mag <= 1e-3)\n      // continue;\n\n      float d =\n          (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1) + (z2 - z1) * (z2 - z1);\n      float d2 = min(d, temp[k]);\n      temp[k] = d2;\n      besti = d2 > best ? k : besti;\n      best = d2 > best ? d2 : best;\n    }\n    dists[tid] = best;\n    dists_i[tid] = besti;\n    __syncthreads();\n\n#pragma unroll\n    for (int block_size_thres = 1024; block_size_thres >= 2;\n         block_size_thres >>= 1) {\n      const int tid_thres = block_size_thres / 2;\n      if (block_size >= block_size_thres && tid < tid_thres) {\n        __update(dists, dists_i, tid, tid + tid_thres);\n      }\n      __syncthreads();\n    }\n\n    old = dists_i[0];\n    if (tid == 0) idxs[j] = old;\n  }\n}\n\n// Modified from\n// https://github.com/qiqihaer/3DSSD-pytorch/blob/master/lib/pointnet2/src/sampling_gpu.cu\ntemplate <unsigned int block_size>\n__global__ void furthest_point_sampling_with_dist_forward_cuda_kernel(\n    int b, int n, int m, const float *__restrict__ dataset,\n    float *__restrict__ temp, int *__restrict__ idxs) {\n  // dataset: (B, N, N)\n  // tmp: (B, N)\n  // output:\n  //      idx: (B, M)\n\n  if (m <= 0) return;\n  __shared__ float dists[block_size];\n  __shared__ int dists_i[block_size];\n\n  int batch_index = blockIdx.x;\n  dataset += batch_index * n * n;\n  temp += batch_index * n;\n  idxs += batch_index * m;\n\n  int tid = threadIdx.x;\n  const int stride = block_size;\n\n  int old = 0;\n  if (threadIdx.x == 0) idxs[0] = old;\n\n  __syncthreads();\n  for (int j = 1; j < m; j++) {\n    int besti = 0;\n    float best = -1;\n    // float x1 = dataset[old * 3 + 0];\n    // float y1 = dataset[old * 3 + 1];\n    // float z1 = dataset[old * 3 + 2];\n    for (int k = tid; k < n; k += stride) {\n      // float x2, y2, z2;\n      // x2 = dataset[k * 3 + 0];\n      // y2 = dataset[k * 3 + 1];\n      // z2 = dataset[k * 3 + 2];\n\n      // float d = (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1) + (z2 - z1) *\n      // (z2 - z1);\n      float d = dataset[old * n + k];\n\n      float d2 = min(d, temp[k]);\n      temp[k] = d2;\n      besti = d2 > best ? k : besti;\n      best = d2 > best ? d2 : best;\n    }\n    dists[tid] = best;\n    dists_i[tid] = besti;\n    __syncthreads();\n\n#pragma unroll\n    for (int block_size_thres = 1024; block_size_thres >= 2;\n         block_size_thres >>= 1) {\n      const int tid_thres = block_size_thres / 2;\n      if (block_size >= block_size_thres && tid < tid_thres) {\n        __update(dists, dists_i, tid, tid + tid_thres);\n      }\n      __syncthreads();\n    }\n\n    old = dists_i[0];\n    if (tid == 0) idxs[j] = old;\n  }\n}\n\n#endif  // FURTHEST_POINT_SAMPLE_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/gather_points_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef GATHER_POINTS_CUDA_KERNEL_CUH\n#define GATHER_POINTS_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\n#define TOTAL_THREADS 1024\n\ntemplate <typename T>\n__global__ void gather_points_forward_cuda_kernel(int b, int c, int n, int m,\n                                                  const T *points,\n                                                  const int *__restrict__ idx,\n                                                  T *out) {\n  // points: (B, C, N)\n  // idx: (B, M)\n  // output:\n  //      out: (B, C, M)\n\n  int bs_idx = blockIdx.z;\n  int c_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= b || c_idx >= c || pt_idx >= m) return;\n\n  out += bs_idx * c * m + c_idx * m + pt_idx;\n  idx += bs_idx * m + pt_idx;\n  points += bs_idx * c * n + c_idx * n;\n  out[0] = points[idx[0]];\n}\n\ntemplate <typename T>\n__global__ void gather_points_backward_cuda_kernel(int b, int c, int n, int m,\n                                                   const T *grad_out,\n                                                   const int *__restrict__ idx,\n                                                   T *grad_points) {\n  // grad_out: (B, C, M)\n  // idx: (B, M)\n  // output:\n  //      grad_points: (B, C, N)\n\n  int bs_idx = blockIdx.z;\n  int c_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= b || c_idx >= c || pt_idx >= m) return;\n\n  grad_out += bs_idx * c * m + c_idx * m + pt_idx;\n  idx += bs_idx * m + pt_idx;\n  grad_points += bs_idx * c * n + c_idx * n;\n\n  atomicAdd(grad_points + idx[0], grad_out[0]);\n}\n\n#endif  // GATHER_POINTS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/group_points_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/group_points_gpu.cu\n#ifndef GROUP_POINTS_CUDA_KERNEL_CUH\n#define GROUP_POINTS_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void group_points_forward_cuda_kernel(int b, int c, int n,\n                                                 int npoints, int nsample,\n                                                 const T *points,\n                                                 const int *__restrict__ idx,\n                                                 T *out) {\n  // points: (B, C, N)\n  // idx: (B, npoints, nsample)\n  // output:\n  //      out: (B, C, npoints, nsample)\n  int bs_idx = blockIdx.z;\n  int c_idx = blockIdx.y;\n  int index = blockIdx.x * blockDim.x + threadIdx.x;\n  int pt_idx = index / nsample;\n  if (bs_idx >= b || c_idx >= c || pt_idx >= npoints) return;\n\n  int sample_idx = index % nsample;\n\n  idx += bs_idx * npoints * nsample + pt_idx * nsample + sample_idx;\n  int in_idx = bs_idx * c * n + c_idx * n + idx[0];\n  int out_idx = bs_idx * c * npoints * nsample + c_idx * npoints * nsample +\n                pt_idx * nsample + sample_idx;\n\n  out[out_idx] = points[in_idx];\n}\n\ntemplate <typename T>\n__global__ void group_points_backward_cuda_kernel(int b, int c, int n,\n                                                  int npoints, int nsample,\n                                                  const T *grad_out,\n                                                  const int *__restrict__ idx,\n                                                  T *grad_points) {\n  // grad_out: (B, C, npoints, nsample)\n  // idx: (B, npoints, nsample)\n  // output:\n  //      grad_points: (B, C, N)\n  int bs_idx = blockIdx.z;\n  int c_idx = blockIdx.y;\n  int index = blockIdx.x * blockDim.x + threadIdx.x;\n  int pt_idx = index / nsample;\n  if (bs_idx >= b || c_idx >= c || pt_idx >= npoints) return;\n\n  int sample_idx = index % nsample;\n  grad_out += bs_idx * c * npoints * nsample + c_idx * npoints * nsample +\n              pt_idx * nsample + sample_idx;\n  idx += bs_idx * npoints * nsample + pt_idx * nsample + sample_idx;\n\n  atomicAdd(grad_points + bs_idx * c * n + c_idx * n + idx[0], grad_out[0]);\n}\n\n#endif  // GROUP_POINTS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/iou3d_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef IOU3D_CUDA_KERNEL_CUH\n#define IOU3D_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\nconst int THREADS_PER_BLOCK_IOU3D = 16;\nconst int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;\n__device__ const float EPS = 1e-8;\n\nstruct Point {\n  float x, y;\n  __device__ Point() {}\n  __device__ Point(double _x, double _y) { x = _x, y = _y; }\n\n  __device__ void set(float _x, float _y) {\n    x = _x;\n    y = _y;\n  }\n\n  __device__ Point operator+(const Point &b) const {\n    return Point(x + b.x, y + b.y);\n  }\n\n  __device__ Point operator-(const Point &b) const {\n    return Point(x - b.x, y - b.y);\n  }\n};\n\n__device__ inline float cross(const Point &a, const Point &b) {\n  return a.x * b.y - a.y * b.x;\n}\n\n__device__ inline float cross(const Point &p1, const Point &p2,\n                              const Point &p0) {\n  return (p1.x - p0.x) * (p2.y - p0.y) - (p2.x - p0.x) * (p1.y - p0.y);\n}\n\n__device__ int check_rect_cross(const Point &p1, const Point &p2,\n                                const Point &q1, const Point &q2) {\n  int ret = min(p1.x, p2.x) <= max(q1.x, q2.x) &&\n            min(q1.x, q2.x) <= max(p1.x, p2.x) &&\n            min(p1.y, p2.y) <= max(q1.y, q2.y) &&\n            min(q1.y, q2.y) <= max(p1.y, p2.y);\n  return ret;\n}\n\n__device__ inline int check_in_box2d(const float *box, const Point &p) {\n  // params: box (5) [x1, y1, x2, y2, angle]\n  const float MARGIN = 1e-5;\n\n  float center_x = (box[0] + box[2]) / 2;\n  float center_y = (box[1] + box[3]) / 2;\n  float angle_cos = cos(-box[4]),\n        angle_sin =\n            sin(-box[4]);  // rotate the point in the opposite direction of box\n  float rot_x =\n      (p.x - center_x) * angle_cos - (p.y - center_y) * angle_sin + center_x;\n  float rot_y =\n      (p.x - center_x) * angle_sin + (p.y - center_y) * angle_cos + center_y;\n\n  return (rot_x > box[0] - MARGIN && rot_x < box[2] + MARGIN &&\n          rot_y > box[1] - MARGIN && rot_y < box[3] + MARGIN);\n}\n\n__device__ inline int intersection(const Point &p1, const Point &p0,\n                                   const Point &q1, const Point &q0,\n                                   Point &ans_point) {\n  // fast exclusion\n  if (check_rect_cross(p0, p1, q0, q1) == 0) return 0;\n\n  // check cross standing\n  float s1 = cross(q0, p1, p0);\n  float s2 = cross(p1, q1, p0);\n  float s3 = cross(p0, q1, q0);\n  float s4 = cross(q1, p1, q0);\n\n  if (!(s1 * s2 > 0 && s3 * s4 > 0)) return 0;\n\n  // calculate intersection of two lines\n  float s5 = cross(q1, p1, p0);\n  if (fabs(s5 - s1) > EPS) {\n    ans_point.x = (s5 * q0.x - s1 * q1.x) / (s5 - s1);\n    ans_point.y = (s5 * q0.y - s1 * q1.y) / (s5 - s1);\n\n  } else {\n    float a0 = p0.y - p1.y, b0 = p1.x - p0.x, c0 = p0.x * p1.y - p1.x * p0.y;\n    float a1 = q0.y - q1.y, b1 = q1.x - q0.x, c1 = q0.x * q1.y - q1.x * q0.y;\n    float D = a0 * b1 - a1 * b0;\n\n    ans_point.x = (b0 * c1 - b1 * c0) / D;\n    ans_point.y = (a1 * c0 - a0 * c1) / D;\n  }\n\n  return 1;\n}\n\n__device__ inline void rotate_around_center(const Point &center,\n                                            const float angle_cos,\n                                            const float angle_sin, Point &p) {\n  float new_x =\n      (p.x - center.x) * angle_cos - (p.y - center.y) * angle_sin + center.x;\n  float new_y =\n      (p.x - center.x) * angle_sin + (p.y - center.y) * angle_cos + center.y;\n  p.set(new_x, new_y);\n}\n\n__device__ inline int point_cmp(const Point &a, const Point &b,\n                                const Point &center) {\n  return atan2(a.y - center.y, a.x - center.x) >\n         atan2(b.y - center.y, b.x - center.x);\n}\n\n__device__ inline float box_overlap(const float *box_a, const float *box_b) {\n  // params: box_a (5) [x1, y1, x2, y2, angle]\n  // params: box_b (5) [x1, y1, x2, y2, angle]\n\n  float a_x1 = box_a[0], a_y1 = box_a[1], a_x2 = box_a[2], a_y2 = box_a[3],\n        a_angle = box_a[4];\n  float b_x1 = box_b[0], b_y1 = box_b[1], b_x2 = box_b[2], b_y2 = box_b[3],\n        b_angle = box_b[4];\n\n  Point center_a((a_x1 + a_x2) / 2, (a_y1 + a_y2) / 2);\n  Point center_b((b_x1 + b_x2) / 2, (b_y1 + b_y2) / 2);\n\n  Point box_a_corners[5];\n  box_a_corners[0].set(a_x1, a_y1);\n  box_a_corners[1].set(a_x2, a_y1);\n  box_a_corners[2].set(a_x2, a_y2);\n  box_a_corners[3].set(a_x1, a_y2);\n\n  Point box_b_corners[5];\n  box_b_corners[0].set(b_x1, b_y1);\n  box_b_corners[1].set(b_x2, b_y1);\n  box_b_corners[2].set(b_x2, b_y2);\n  box_b_corners[3].set(b_x1, b_y2);\n\n  // get oriented corners\n  float a_angle_cos = cos(a_angle), a_angle_sin = sin(a_angle);\n  float b_angle_cos = cos(b_angle), b_angle_sin = sin(b_angle);\n\n  for (int k = 0; k < 4; k++) {\n    rotate_around_center(center_a, a_angle_cos, a_angle_sin, box_a_corners[k]);\n    rotate_around_center(center_b, b_angle_cos, b_angle_sin, box_b_corners[k]);\n  }\n\n  box_a_corners[4] = box_a_corners[0];\n  box_b_corners[4] = box_b_corners[0];\n\n  // get intersection of lines\n  Point cross_points[16];\n  Point poly_center;\n  int cnt = 0, flag = 0;\n\n  poly_center.set(0, 0);\n  for (int i = 0; i < 4; i++) {\n    for (int j = 0; j < 4; j++) {\n      flag = intersection(box_a_corners[i + 1], box_a_corners[i],\n                          box_b_corners[j + 1], box_b_corners[j],\n                          cross_points[cnt]);\n      if (flag) {\n        poly_center = poly_center + cross_points[cnt];\n        cnt++;\n      }\n    }\n  }\n\n  // check corners\n  for (int k = 0; k < 4; k++) {\n    if (check_in_box2d(box_a, box_b_corners[k])) {\n      poly_center = poly_center + box_b_corners[k];\n      cross_points[cnt] = box_b_corners[k];\n      cnt++;\n    }\n    if (check_in_box2d(box_b, box_a_corners[k])) {\n      poly_center = poly_center + box_a_corners[k];\n      cross_points[cnt] = box_a_corners[k];\n      cnt++;\n    }\n  }\n\n  poly_center.x /= cnt;\n  poly_center.y /= cnt;\n\n  // sort the points of polygon\n  Point temp;\n  for (int j = 0; j < cnt - 1; j++) {\n    for (int i = 0; i < cnt - j - 1; i++) {\n      if (point_cmp(cross_points[i], cross_points[i + 1], poly_center)) {\n        temp = cross_points[i];\n        cross_points[i] = cross_points[i + 1];\n        cross_points[i + 1] = temp;\n      }\n    }\n  }\n\n  // get the overlap areas\n  float area = 0;\n  for (int k = 0; k < cnt - 1; k++) {\n    area += cross(cross_points[k] - cross_points[0],\n                  cross_points[k + 1] - cross_points[0]);\n  }\n\n  return fabs(area) / 2.0;\n}\n\n__device__ inline float iou_bev(const float *box_a, const float *box_b) {\n  // params: box_a (5) [x1, y1, x2, y2, angle]\n  // params: box_b (5) [x1, y1, x2, y2, angle]\n  float sa = (box_a[2] - box_a[0]) * (box_a[3] - box_a[1]);\n  float sb = (box_b[2] - box_b[0]) * (box_b[3] - box_b[1]);\n  float s_overlap = box_overlap(box_a, box_b);\n  return s_overlap / fmaxf(sa + sb - s_overlap, EPS);\n}\n\n__global__ void iou3d_boxes_overlap_bev_forward_cuda_kernel(\n    const int num_a, const float *boxes_a, const int num_b,\n    const float *boxes_b, float *ans_overlap) {\n  const int a_idx = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y;\n  const int b_idx = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x;\n\n  if (a_idx >= num_a || b_idx >= num_b) {\n    return;\n  }\n  const float *cur_box_a = boxes_a + a_idx * 5;\n  const float *cur_box_b = boxes_b + b_idx * 5;\n  float s_overlap = box_overlap(cur_box_a, cur_box_b);\n  ans_overlap[a_idx * num_b + b_idx] = s_overlap;\n}\n\n__global__ void iou3d_boxes_iou_bev_forward_cuda_kernel(const int num_a,\n                                                        const float *boxes_a,\n                                                        const int num_b,\n                                                        const float *boxes_b,\n                                                        float *ans_iou) {\n  const int a_idx = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y;\n  const int b_idx = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x;\n\n  if (a_idx >= num_a || b_idx >= num_b) {\n    return;\n  }\n\n  const float *cur_box_a = boxes_a + a_idx * 5;\n  const float *cur_box_b = boxes_b + b_idx * 5;\n  float cur_iou_bev = iou_bev(cur_box_a, cur_box_b);\n  ans_iou[a_idx * num_b + b_idx] = cur_iou_bev;\n}\n\n__global__ void nms_forward_cuda_kernel(const int boxes_num,\n                                        const float nms_overlap_thresh,\n                                        const float *boxes,\n                                        unsigned long long *mask) {\n  // params: boxes (N, 5) [x1, y1, x2, y2, ry]\n  // params: mask (N, N/THREADS_PER_BLOCK_NMS)\n\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n\n  // if (row_start > col_start) return;\n\n  const int row_size = fminf(boxes_num - row_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n  const int col_size = fminf(boxes_num - col_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n\n  __shared__ float block_boxes[THREADS_PER_BLOCK_NMS * 5];\n\n  if (threadIdx.x < col_size) {\n    block_boxes[threadIdx.x * 5 + 0] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 0];\n    block_boxes[threadIdx.x * 5 + 1] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 1];\n    block_boxes[threadIdx.x * 5 + 2] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 2];\n    block_boxes[threadIdx.x * 5 + 3] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 3];\n    block_boxes[threadIdx.x * 5 + 4] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size) {\n    const int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x;\n    const float *cur_box = boxes + cur_box_idx * 5;\n\n    int i = 0;\n    unsigned long long t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = threadIdx.x + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      if (iou_bev(cur_box, block_boxes + i * 5) > nms_overlap_thresh) {\n        t |= 1ULL << i;\n      }\n    }\n    const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n    mask[cur_box_idx * col_blocks + col_start] = t;\n  }\n}\n\n__device__ inline float iou_normal(float const *const a, float const *const b) {\n  float left = fmaxf(a[0], b[0]), right = fminf(a[2], b[2]);\n  float top = fmaxf(a[1], b[1]), bottom = fminf(a[3], b[3]);\n  float width = fmaxf(right - left, 0.f), height = fmaxf(bottom - top, 0.f);\n  float interS = width * height;\n  float Sa = (a[2] - a[0]) * (a[3] - a[1]);\n  float Sb = (b[2] - b[0]) * (b[3] - b[1]);\n  return interS / fmaxf(Sa + Sb - interS, EPS);\n}\n\n__global__ void nms_normal_forward_cuda_kernel(const int boxes_num,\n                                               const float nms_overlap_thresh,\n                                               const float *boxes,\n                                               unsigned long long *mask) {\n  // params: boxes (N, 5) [x1, y1, x2, y2, ry]\n  // params: mask (N, N/THREADS_PER_BLOCK_NMS)\n\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n\n  // if (row_start > col_start) return;\n\n  const int row_size = fminf(boxes_num - row_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n  const int col_size = fminf(boxes_num - col_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n\n  __shared__ float block_boxes[THREADS_PER_BLOCK_NMS * 5];\n\n  if (threadIdx.x < col_size) {\n    block_boxes[threadIdx.x * 5 + 0] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 0];\n    block_boxes[threadIdx.x * 5 + 1] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 1];\n    block_boxes[threadIdx.x * 5 + 2] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 2];\n    block_boxes[threadIdx.x * 5 + 3] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 3];\n    block_boxes[threadIdx.x * 5 + 4] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size) {\n    const int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x;\n    const float *cur_box = boxes + cur_box_idx * 5;\n\n    int i = 0;\n    unsigned long long t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = threadIdx.x + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      if (iou_normal(cur_box, block_boxes + i * 5) > nms_overlap_thresh) {\n        t |= 1ULL << i;\n      }\n    }\n    const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n    mask[cur_box_idx * col_blocks + col_start] = t;\n  }\n}\n\n#endif  // IOU3D_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/knn_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/CVMI-Lab/PAConv/tree/main/scene_seg/lib/pointops/src/knnquery_heap\n#ifndef KNN_CUDA_KERNEL_CUH\n#define KNN_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ninline __device__ void swap_float(float *x, float *y) {\n  float tmp = *x;\n  *x = *y;\n  *y = tmp;\n}\n\ninline __device__ void swap_int(int *x, int *y) {\n  int tmp = *x;\n  *x = *y;\n  *y = tmp;\n}\n\n__device__ void reheap(float *dist, int *idx, int k) {\n  int root = 0;\n  int child = root * 2 + 1;\n  while (child < k) {\n    if (child + 1 < k && dist[child + 1] > dist[child]) child++;\n    if (dist[root] > dist[child]) return;\n    swap_float(&dist[root], &dist[child]);\n    swap_int(&idx[root], &idx[child]);\n    root = child;\n    child = root * 2 + 1;\n  }\n}\n\n__device__ void heap_sort(float *dist, int *idx, int k) {\n  int i;\n  for (i = k - 1; i > 0; i--) {\n    swap_float(&dist[0], &dist[i]);\n    swap_int(&idx[0], &idx[i]);\n    reheap(dist, idx, i);\n  }\n}\n\n// input: xyz (b, n, 3) new_xyz (b, m, 3)\n// output: idx (b, m, nsample) dist2 (b, m, nsample)\ntemplate <typename T>\n__global__ void knn_forward_cuda_kernel(int b, int n, int m, int nsample,\n                                        const T *xyz, const T *new_xyz,\n                                        int *__restrict__ idx, T *dist2) {\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= b || pt_idx >= m) return;\n\n  new_xyz += bs_idx * m * 3 + pt_idx * 3;\n  xyz += bs_idx * n * 3;\n  idx += bs_idx * m * nsample + pt_idx * nsample;\n  dist2 += bs_idx * m * nsample + pt_idx * nsample;\n\n  T new_x = new_xyz[0];\n  T new_y = new_xyz[1];\n  T new_z = new_xyz[2];\n\n  float best_dist[100];\n  int best_idx[100];\n  for (int i = 0; i < nsample; i++) {\n    best_dist[i] = 1e10;\n    best_idx[i] = 0;\n  }\n  for (int i = 0; i < n; i++) {\n    T x = xyz[i * 3 + 0];\n    T y = xyz[i * 3 + 1];\n    T z = xyz[i * 3 + 2];\n    T d2 = (new_x - x) * (new_x - x) + (new_y - y) * (new_y - y) +\n           (new_z - z) * (new_z - z);\n    if (d2 < best_dist[0]) {\n      best_dist[0] = d2;\n      best_idx[0] = i;\n      reheap(best_dist, best_idx, nsample);\n    }\n  }\n  heap_sort(best_dist, best_idx, nsample);\n  for (int i = 0; i < nsample; i++) {\n    idx[i] = best_idx[i];\n    dist2[i] = best_dist[i];\n  }\n}\n\n#endif  // KNN_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/masked_conv2d_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef MASKED_CONV2D_CUDA_KERNEL_CUH\n#define MASKED_CONV2D_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename scalar_t>\n__global__ void MaskedIm2colForward(const int n, const scalar_t *data_im,\n                                    const int height, const int width,\n                                    const int kernel_h, const int kernel_w,\n                                    const int pad_h, const int pad_w,\n                                    const int64_t *mask_h_idx,\n                                    const int64_t *mask_w_idx,\n                                    const int mask_cnt, scalar_t *data_col) {\n  // mask_cnt * channels\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    const int m_index = index % mask_cnt;\n    const int h_col = mask_h_idx[m_index];\n    const int w_col = mask_w_idx[m_index];\n    const int c_im = index / mask_cnt;\n    const int c_col = c_im * kernel_h * kernel_w;\n    const int h_offset = h_col - pad_h;\n    const int w_offset = w_col - pad_w;\n    scalar_t *data_col_ptr = data_col + c_col * mask_cnt + m_index;\n    for (int i = 0; i < kernel_h; ++i) {\n      int h_im = h_offset + i;\n      for (int j = 0; j < kernel_w; ++j) {\n        int w_im = w_offset + j;\n        if (h_im >= 0 && w_im >= 0 && h_im < height && w_im < width) {\n          *data_col_ptr =\n              (scalar_t)data_im[(c_im * height + h_im) * width + w_im];\n        } else {\n          *data_col_ptr = 0.0;\n        }\n        data_col_ptr += mask_cnt;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void MaskedCol2imForward(const int n, const scalar_t *data_col,\n                                    const int height, const int width,\n                                    const int channels,\n                                    const int64_t *mask_h_idx,\n                                    const int64_t *mask_w_idx,\n                                    const int mask_cnt, scalar_t *data_im) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    const int m_index = index % mask_cnt;\n    const int h_im = mask_h_idx[m_index];\n    const int w_im = mask_w_idx[m_index];\n    const int c_im = index / mask_cnt;\n    // compute the start and end of the output\n    data_im[(c_im * height + h_im) * width + w_im] = data_col[index];\n  }\n}\n\n#endif  // MASKED_CONV2D_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/modulated_deform_conv_cuda_kernel.cuh",
    "content": "/*!\n ******************* BEGIN Caffe Copyright Notice and Disclaimer\n *****************\n *\n * COPYRIGHT\n *\n * All contributions by the University of California:\n * Copyright (c) 2014-2017 The Regents of the University of California (Regents)\n * All rights reserved.\n *\n * All other contributions:\n * Copyright (c) 2014-2017, the respective contributors\n * All rights reserved.\n *\n * Caffe uses a shared copyright model: each contributor holds copyright over\n * their contributions to Caffe. The project versioning records all such\n * contribution and copyright details. If a contributor wants to further mark\n * their specific copyright on a particular contribution, they should indicate\n * their copyright solely in the commit message of the change when it is\n * committed.\n *\n * LICENSE\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n * 1. Redistributions of source code must retain the above copyright notice,\n *this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above copyright notice,\n * this list of conditions and the following disclaimer in the documentation\n * and/or other materials provided with the distribution.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n *AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n *IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE\n *FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\n *DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\n *SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\n *OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\n *OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n *\n * CONTRIBUTION AGREEMENT\n *\n * By contributing to the BVLC/caffe repository through pull-request, comment,\n * or otherwise, the contributor releases their content to the\n * license and copyright terms herein.\n *\n ***************** END Caffe Copyright Notice and Disclaimer\n *********************\n *\n * Copyright (c) 2018 Microsoft\n * Licensed under The MIT License [see LICENSE for details]\n * \\file modulated_deformable_im2col.cuh\n * \\brief Function definitions of converting an image to\n * column matrix based on kernel, padding, dilation, and offset.\n * These functions are mainly used in deformable convolution operators.\n * \\ref: https://arxiv.org/abs/1703.06211\n * \\author Yuwen Xiong, Haozhi Qi, Jifeng Dai, Xizhou Zhu, Han Hu, Dazhi Cheng\n */\n\n// modified from\n// https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/blob/mmdetection/mmdet/ops/dcn/src/deform_conv_cuda_kernel.cu\n\n#ifndef MODULATED_DEFORM_CONV_CUDA_KERNEL_CUH\n#define MODULATED_DEFORM_CONV_CUDA_KERNEL_CUH\n\n#include <float.h>\n#ifdef MMCV_WITH_TRT\n#include \"common_cuda_helper.hpp\"\n#else  // MMCV_WITH_TRT\n#include \"pytorch_cuda_helper.hpp\"\n#endif  // MMCV_WITH_TRT\n\ntemplate <typename T>\n__device__ T dmcn_im2col_bilinear(const T *input, const int data_width,\n                                  const int height, const int width, T h, T w) {\n  int h_low = floorf(h);\n  int w_low = floorf(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  T lh = h - h_low;\n  T lw = w - w_low;\n  T hh = 1 - lh, hw = 1 - lw;\n\n  T v1 = 0;\n  if (h_low >= 0 && w_low >= 0) v1 = input[h_low * data_width + w_low];\n  T v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = input[h_low * data_width + w_high];\n  T v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = input[h_high * data_width + w_low];\n  T v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = input[h_high * data_width + w_high];\n\n  T w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename T>\n__device__ T dmcn_get_gradient_weight(T argmax_h, T argmax_w, const int h,\n                                      const int w, const int height,\n                                      const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floorf(argmax_h);\n  int argmax_w_low = floorf(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename T>\n__device__ T dmcn_get_coordinate_weight(T argmax_h, T argmax_w,\n                                        const int height, const int width,\n                                        const T *im_data, const int data_width,\n                                        const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floorf(argmax_h);\n  int argmax_w_low = floorf(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename T>\n__global__ void modulated_deformable_im2col_gpu_kernel(\n    const int n, const T *data_im, const T *data_offset, const T *data_mask,\n    const int height, const int width, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int num_channels, const int deformable_group, const int height_col,\n    const int width_col, T *data_col) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n\n    T *data_col_ptr =\n        data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    const T *data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const T *data_offset_ptr =\n        data_offset + (b_col * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n\n    const T *data_mask_ptr =\n        data_mask + (b_col * deformable_group + deformable_group_index) *\n                        kernel_h * kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const int data_mask_hw_ptr =\n            ((i * kernel_w + j) * height_col + h_col) * width_col + w_col;\n        const T offset_h = data_offset_ptr[data_offset_h_ptr];\n        const T offset_w = data_offset_ptr[data_offset_w_ptr];\n        const T mask = data_mask_ptr[data_mask_hw_ptr];\n        T val = static_cast<T>(0);\n        const T h_im = h_in + i * dilation_h + offset_h;\n        const T w_im = w_in + j * dilation_w + offset_w;\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width)\n          val = dmcn_im2col_bilinear(data_im_ptr, width, height, width, h_im,\n                                     w_im);\n        *data_col_ptr = val * mask;\n        data_col_ptr += batch_size * height_col * width_col;\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void modulated_deformable_col2im_gpu_kernel(\n    const int n, const T *data_col, const T *data_offset, const T *data_mask,\n    const int channels, const int height, const int width, const int kernel_h,\n    const int kernel_w, const int pad_h, const int pad_w, const int stride_h,\n    const int stride_w, const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int deformable_group, const int height_col, const int width_col,\n    T *grad_im) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n    const T *data_mask_ptr =\n        data_mask + (b * deformable_group + deformable_group_index) * kernel_h *\n                        kernel_w * height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const int data_mask_hw_ptr =\n        ((i * kernel_w + j) * height_col + h_out) * width_col + w_out;\n    const T offset_h = data_offset_ptr[data_offset_h_ptr];\n    const T offset_w = data_offset_ptr[data_offset_w_ptr];\n    const T mask = data_mask_ptr[data_mask_hw_ptr];\n    const T cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const T cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const T cur_top_grad = data_col[index] * mask;\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          T weight =\n              dmcn_get_gradient_weight(cur_inv_h_data, cur_inv_w_data,\n                                       cur_h + dy, cur_w + dx, height, width);\n          atomicAdd(grad_im + cur_bottom_grad_pos, weight * cur_top_grad);\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void modulated_deformable_col2im_coord_gpu_kernel(\n    const int n, const T *data_col, const T *data_im, const T *data_offset,\n    const T *data_mask, const int channels, const int height, const int width,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int channel_per_deformable_group,\n    const int batch_size, const int offset_channels, const int deformable_group,\n    const int height_col, const int width_col, T *grad_offset, T *grad_mask) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    T val = 0, mval = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const T *data_col_ptr = data_col + deformable_group_index *\n                                           channel_per_deformable_group *\n                                           batch_size * width_col * height_col;\n    const T *data_im_ptr =\n        data_im + (b * deformable_group + deformable_group_index) *\n                      channel_per_deformable_group / kernel_h / kernel_w *\n                      height * width;\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n    const T *data_mask_ptr =\n        data_mask + (b * deformable_group + deformable_group_index) * kernel_h *\n                        kernel_w * height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const int data_mask_hw_ptr =\n          (((i * kernel_w + j) * height_col + h_out) * width_col + w_out);\n      const T offset_h = data_offset_ptr[data_offset_h_ptr];\n      const T offset_w = data_offset_ptr[data_offset_w_ptr];\n      const T mask = data_mask_ptr[data_mask_hw_ptr];\n      T inv_h = h_in + i * dilation_h + offset_h;\n      T inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width)\n        inv_h = inv_w = -2;\n      else\n        mval += data_col_ptr[col_pos] *\n                dmcn_im2col_bilinear(data_im_ptr + cnt * height * width, width,\n                                     height, width, inv_h, inv_w);\n      const T weight = dmcn_get_coordinate_weight(\n          inv_h, inv_w, height, width, data_im_ptr + cnt * height * width,\n          width, bp_dir);\n      val += weight * data_col_ptr[col_pos] * mask;\n      cnt += 1;\n    }\n    // KERNEL_ASSIGN(grad_offset[index], offset_req, val);\n    grad_offset[index] = val;\n    if (offset_c % 2 == 0)\n      // KERNEL_ASSIGN(grad_mask[(((b * deformable_group +\n      // deformable_group_index) * kernel_h * kernel_w + offset_c / 2) *\n      // height_col + h) * width_col + w], mask_req, mval);\n      grad_mask[(((b * deformable_group + deformable_group_index) * kernel_h *\n                      kernel_w +\n                  offset_c / 2) *\n                     height_col +\n                 h) *\n                    width_col +\n                w] = mval;\n  }\n}\n\n#endif  // MODULATED_DEFORM_CONV_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/ms_deform_attn_cuda_kernel.cuh",
    "content": "/*!\n**************************************************************************************************\n* Deformable DETR\n* Copyright (c) 2020 SenseTime. All Rights Reserved.\n* Licensed under the Apache License, Version 2.0 [see LICENSE for details]\n**************************************************************************************************\n* Modified from\n*https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/tree/pytorch_1.0.0\n**************************************************************************************************\n*/\n#ifndef DEFORM_ATTN_CUDA_KERNEL\n#define DEFORM_ATTN_CUDA_KERNEL\n\n#include \"common_cuda_helper.hpp\"\n#include \"pytorch_cuda_helper.hpp\"\n\nconst int CUDA_NUM_THREADS = 1024;\ninline int GET_BLOCKS(const int N, const int num_threads) {\n  return (N + num_threads - 1) / num_threads;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t ms_deform_attn_im2col_bilinear(\n    const scalar_t *&bottom_data, const int &height, const int &width,\n    const int &nheads, const int &channels, const scalar_t &h,\n    const scalar_t &w, const int &m, const int &c) {\n  const int h_low = floorf(h);\n  const int w_low = floorf(w);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const scalar_t lh = h - h_low;\n  const scalar_t lw = w - w_low;\n  const scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = nheads * channels;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n  const int base_ptr = m * channels + c;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n  }\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n  }\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n  }\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n  }\n\n  const scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  const scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename scalar_t>\n__device__ void ms_deform_attn_col2im_bilinear(\n    const scalar_t *&bottom_data, const int &height, const int &width,\n    const int &nheads, const int &channels, const scalar_t &h,\n    const scalar_t &w, const int &m, const int &c, const scalar_t &top_grad,\n    const scalar_t &attn_weight, scalar_t *&grad_value,\n    scalar_t *grad_sampling_loc, scalar_t *grad_attn_weight) {\n  const int h_low = floorf(h);\n  const int w_low = floorf(w);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const scalar_t lh = h - h_low;\n  const scalar_t lw = w - w_low;\n  const scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = nheads * channels;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n  const int base_ptr = m * channels + c;\n\n  const scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n  const scalar_t top_grad_value = top_grad * attn_weight;\n  scalar_t grad_h_weight = 0, grad_w_weight = 0;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n    grad_h_weight -= hw * v1;\n    grad_w_weight -= hh * v1;\n    atomicAdd(grad_value + ptr1, w1 * top_grad_value);\n  }\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n    grad_h_weight -= lw * v2;\n    grad_w_weight += hh * v2;\n    atomicAdd(grad_value + ptr2, w2 * top_grad_value);\n  }\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n    grad_h_weight += hw * v3;\n    grad_w_weight -= lh * v3;\n    atomicAdd(grad_value + ptr3, w3 * top_grad_value);\n  }\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n    grad_h_weight += lw * v4;\n    grad_w_weight += lh * v4;\n    atomicAdd(grad_value + ptr4, w4 * top_grad_value);\n  }\n\n  const scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  *grad_attn_weight = top_grad * val;\n  *grad_sampling_loc = width * grad_w_weight * top_grad_value;\n  *(grad_sampling_loc + 1) = height * grad_h_weight * top_grad_value;\n}\n\ntemplate <typename scalar_t>\n__device__ void ms_deform_attn_col2im_bilinear_gm(\n    const scalar_t *&bottom_data, const int &height, const int &width,\n    const int &nheads, const int &channels, const scalar_t &h,\n    const scalar_t &w, const int &m, const int &c, const scalar_t &top_grad,\n    const scalar_t &attn_weight, scalar_t *&grad_value,\n    scalar_t *grad_sampling_loc, scalar_t *grad_attn_weight) {\n  const int h_low = floorf(h);\n  const int w_low = floorf(w);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const scalar_t lh = h - h_low;\n  const scalar_t lw = w - w_low;\n  const scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = nheads * channels;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n  const int base_ptr = m * channels + c;\n\n  const scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n  const scalar_t top_grad_value = top_grad * attn_weight;\n  scalar_t grad_h_weight = 0, grad_w_weight = 0;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n    grad_h_weight -= hw * v1;\n    grad_w_weight -= hh * v1;\n    atomicAdd(grad_value + ptr1, w1 * top_grad_value);\n  }\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n    grad_h_weight -= lw * v2;\n    grad_w_weight += hh * v2;\n    atomicAdd(grad_value + ptr2, w2 * top_grad_value);\n  }\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n    grad_h_weight += hw * v3;\n    grad_w_weight -= lh * v3;\n    atomicAdd(grad_value + ptr3, w3 * top_grad_value);\n  }\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n    grad_h_weight += lw * v4;\n    grad_w_weight += lh * v4;\n    atomicAdd(grad_value + ptr4, w4 * top_grad_value);\n  }\n\n  const scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  atomicAdd(grad_attn_weight, top_grad * val);\n  atomicAdd(grad_sampling_loc, width * grad_w_weight * top_grad_value);\n  atomicAdd(grad_sampling_loc + 1, height * grad_h_weight * top_grad_value);\n}\n\ntemplate <typename scalar_t>\n__global__ void ms_deformable_im2col_gpu_kernel(\n    const int n, const scalar_t *data_value, const int64_t *data_spatial_shapes,\n    const int64_t *data_level_start_index, const scalar_t *data_sampling_loc,\n    const scalar_t *data_attn_weight, const int batch_size,\n    const int spatial_size, const int num_heads, const int channels,\n    const int num_levels, const int num_query, const int num_point,\n    scalar_t *data_col) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    scalar_t *data_col_ptr = data_col + index;\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n    scalar_t col = 0;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const scalar_t *data_value_ptr =\n          data_value +\n          (data_value_ptr_init_offset + level_start_id * qid_stride);\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          col += ms_deform_attn_im2col_bilinear(data_value_ptr, spatial_h,\n                                                spatial_w, num_heads, channels,\n                                                h_im, w_im, m_col, c_col) *\n                 weight;\n        }\n\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n      }\n    }\n    *data_col_ptr = col;\n  }\n}\n\ntemplate <typename scalar_t, unsigned int blockSize>\n__global__ void ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1(\n    const int n, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    __shared__ scalar_t cache_grad_sampling_loc[blockSize * 2];\n    __shared__ scalar_t cache_grad_attn_weight[blockSize];\n    unsigned int tid = threadIdx.x;\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    const scalar_t top_grad = grad_col[index];\n\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int grad_sampling_ptr = data_weight_ptr;\n    grad_sampling_loc += grad_sampling_ptr << 1;\n    grad_attn_weight += grad_sampling_ptr;\n    const int grad_weight_stride = 1;\n    const int grad_loc_stride = 2;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const int value_ptr_offset =\n          data_value_ptr_init_offset + level_start_id * qid_stride;\n      const scalar_t *data_value_ptr = data_value + value_ptr_offset;\n      scalar_t *grad_value_ptr = grad_value + value_ptr_offset;\n\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n        *(cache_grad_sampling_loc + (threadIdx.x << 1)) = 0;\n        *(cache_grad_sampling_loc + ((threadIdx.x << 1) + 1)) = 0;\n        *(cache_grad_attn_weight + threadIdx.x) = 0;\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          ms_deform_attn_col2im_bilinear(\n              data_value_ptr, spatial_h, spatial_w, num_heads, channels, h_im,\n              w_im, m_col, c_col, top_grad, weight, grad_value_ptr,\n              cache_grad_sampling_loc + (threadIdx.x << 1),\n              cache_grad_attn_weight + threadIdx.x);\n        }\n\n        __syncthreads();\n        if (tid == 0) {\n          scalar_t _grad_w = cache_grad_sampling_loc[0],\n                   _grad_h = cache_grad_sampling_loc[1],\n                   _grad_a = cache_grad_attn_weight[0];\n          int sid = 2;\n          for (unsigned int tid = 1; tid < blockSize; ++tid) {\n            _grad_w += cache_grad_sampling_loc[sid];\n            _grad_h += cache_grad_sampling_loc[sid + 1];\n            _grad_a += cache_grad_attn_weight[tid];\n            sid += 2;\n          }\n\n          *grad_sampling_loc = _grad_w;\n          *(grad_sampling_loc + 1) = _grad_h;\n          *grad_attn_weight = _grad_a;\n        }\n        __syncthreads();\n\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n        grad_attn_weight += grad_weight_stride;\n        grad_sampling_loc += grad_loc_stride;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t, unsigned int blockSize>\n__global__ void ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v2(\n    const int n, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    __shared__ scalar_t cache_grad_sampling_loc[blockSize * 2];\n    __shared__ scalar_t cache_grad_attn_weight[blockSize];\n    unsigned int tid = threadIdx.x;\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    const scalar_t top_grad = grad_col[index];\n\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int grad_sampling_ptr = data_weight_ptr;\n    grad_sampling_loc += grad_sampling_ptr << 1;\n    grad_attn_weight += grad_sampling_ptr;\n    const int grad_weight_stride = 1;\n    const int grad_loc_stride = 2;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const int value_ptr_offset =\n          data_value_ptr_init_offset + level_start_id * qid_stride;\n      const scalar_t *data_value_ptr = data_value + value_ptr_offset;\n      scalar_t *grad_value_ptr = grad_value + value_ptr_offset;\n\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n        *(cache_grad_sampling_loc + (threadIdx.x << 1)) = 0;\n        *(cache_grad_sampling_loc + ((threadIdx.x << 1) + 1)) = 0;\n        *(cache_grad_attn_weight + threadIdx.x) = 0;\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          ms_deform_attn_col2im_bilinear(\n              data_value_ptr, spatial_h, spatial_w, num_heads, channels, h_im,\n              w_im, m_col, c_col, top_grad, weight, grad_value_ptr,\n              cache_grad_sampling_loc + (threadIdx.x << 1),\n              cache_grad_attn_weight + threadIdx.x);\n        }\n\n        __syncthreads();\n\n        for (unsigned int s = blockSize / 2; s > 0; s >>= 1) {\n          if (tid < s) {\n            const unsigned int xid1 = tid << 1;\n            const unsigned int xid2 = (tid + s) << 1;\n            cache_grad_attn_weight[tid] += cache_grad_attn_weight[tid + s];\n            cache_grad_sampling_loc[xid1] += cache_grad_sampling_loc[xid2];\n            cache_grad_sampling_loc[xid1 + 1] +=\n                cache_grad_sampling_loc[xid2 + 1];\n          }\n          __syncthreads();\n        }\n\n        if (tid == 0) {\n          *grad_sampling_loc = cache_grad_sampling_loc[0];\n          *(grad_sampling_loc + 1) = cache_grad_sampling_loc[1];\n          *grad_attn_weight = cache_grad_attn_weight[0];\n        }\n        __syncthreads();\n\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n        grad_attn_weight += grad_weight_stride;\n        grad_sampling_loc += grad_loc_stride;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void ms_deformable_col2im_gpu_kernel_shm_reduce_v1(\n    const int n, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    extern __shared__ int _s[];\n    scalar_t *cache_grad_sampling_loc = reinterpret_cast<scalar_t *>(_s);\n    scalar_t *cache_grad_attn_weight = cache_grad_sampling_loc + 2 * blockDim.x;\n    unsigned int tid = threadIdx.x;\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    const scalar_t top_grad = grad_col[index];\n\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int grad_sampling_ptr = data_weight_ptr;\n    grad_sampling_loc += grad_sampling_ptr << 1;\n    grad_attn_weight += grad_sampling_ptr;\n    const int grad_weight_stride = 1;\n    const int grad_loc_stride = 2;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const int value_ptr_offset =\n          data_value_ptr_init_offset + level_start_id * qid_stride;\n      const scalar_t *data_value_ptr = data_value + value_ptr_offset;\n      scalar_t *grad_value_ptr = grad_value + value_ptr_offset;\n\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n        *(cache_grad_sampling_loc + (threadIdx.x << 1)) = 0;\n        *(cache_grad_sampling_loc + ((threadIdx.x << 1) + 1)) = 0;\n        *(cache_grad_attn_weight + threadIdx.x) = 0;\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          ms_deform_attn_col2im_bilinear(\n              data_value_ptr, spatial_h, spatial_w, num_heads, channels, h_im,\n              w_im, m_col, c_col, top_grad, weight, grad_value_ptr,\n              cache_grad_sampling_loc + (threadIdx.x << 1),\n              cache_grad_attn_weight + threadIdx.x);\n        }\n\n        __syncthreads();\n        if (tid == 0) {\n          scalar_t _grad_w = cache_grad_sampling_loc[0],\n                   _grad_h = cache_grad_sampling_loc[1],\n                   _grad_a = cache_grad_attn_weight[0];\n          int sid = 2;\n          for (unsigned int tid = 1; tid < blockDim.x; ++tid) {\n            _grad_w += cache_grad_sampling_loc[sid];\n            _grad_h += cache_grad_sampling_loc[sid + 1];\n            _grad_a += cache_grad_attn_weight[tid];\n            sid += 2;\n          }\n\n          *grad_sampling_loc = _grad_w;\n          *(grad_sampling_loc + 1) = _grad_h;\n          *grad_attn_weight = _grad_a;\n        }\n        __syncthreads();\n\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n        grad_attn_weight += grad_weight_stride;\n        grad_sampling_loc += grad_loc_stride;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void ms_deformable_col2im_gpu_kernel_shm_reduce_v2(\n    const int n, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    extern __shared__ int _s[];\n    scalar_t *cache_grad_sampling_loc = reinterpret_cast<scalar_t *>(_s);\n    scalar_t *cache_grad_attn_weight = cache_grad_sampling_loc + 2 * blockDim.x;\n    unsigned int tid = threadIdx.x;\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    const scalar_t top_grad = grad_col[index];\n\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int grad_sampling_ptr = data_weight_ptr;\n    grad_sampling_loc += grad_sampling_ptr << 1;\n    grad_attn_weight += grad_sampling_ptr;\n    const int grad_weight_stride = 1;\n    const int grad_loc_stride = 2;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const int value_ptr_offset =\n          data_value_ptr_init_offset + level_start_id * qid_stride;\n      const scalar_t *data_value_ptr = data_value + value_ptr_offset;\n      scalar_t *grad_value_ptr = grad_value + value_ptr_offset;\n\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n        *(cache_grad_sampling_loc + (threadIdx.x << 1)) = 0;\n        *(cache_grad_sampling_loc + ((threadIdx.x << 1) + 1)) = 0;\n        *(cache_grad_attn_weight + threadIdx.x) = 0;\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          ms_deform_attn_col2im_bilinear(\n              data_value_ptr, spatial_h, spatial_w, num_heads, channels, h_im,\n              w_im, m_col, c_col, top_grad, weight, grad_value_ptr,\n              cache_grad_sampling_loc + (threadIdx.x << 1),\n              cache_grad_attn_weight + threadIdx.x);\n        }\n\n        __syncthreads();\n\n        for (unsigned int s = blockDim.x / 2, spre = blockDim.x; s > 0;\n             s >>= 1, spre >>= 1) {\n          if (tid < s) {\n            const unsigned int xid1 = tid << 1;\n            const unsigned int xid2 = (tid + s) << 1;\n            cache_grad_attn_weight[tid] += cache_grad_attn_weight[tid + s];\n            cache_grad_sampling_loc[xid1] += cache_grad_sampling_loc[xid2];\n            cache_grad_sampling_loc[xid1 + 1] +=\n                cache_grad_sampling_loc[xid2 + 1];\n            if (tid + (s << 1) < spre) {\n              cache_grad_attn_weight[tid] +=\n                  cache_grad_attn_weight[tid + (s << 1)];\n              cache_grad_sampling_loc[xid1] +=\n                  cache_grad_sampling_loc[xid2 + (s << 1)];\n              cache_grad_sampling_loc[xid1 + 1] +=\n                  cache_grad_sampling_loc[xid2 + 1 + (s << 1)];\n            }\n          }\n          __syncthreads();\n        }\n\n        if (tid == 0) {\n          *grad_sampling_loc = cache_grad_sampling_loc[0];\n          *(grad_sampling_loc + 1) = cache_grad_sampling_loc[1];\n          *grad_attn_weight = cache_grad_attn_weight[0];\n        }\n        __syncthreads();\n\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n        grad_attn_weight += grad_weight_stride;\n        grad_sampling_loc += grad_loc_stride;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void ms_deformable_col2im_gpu_kernel_shm_reduce_v2_multi_blocks(\n    const int n, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    extern __shared__ int _s[];\n    scalar_t *cache_grad_sampling_loc = reinterpret_cast<scalar_t *>(_s);\n    scalar_t *cache_grad_attn_weight = cache_grad_sampling_loc + 2 * blockDim.x;\n    unsigned int tid = threadIdx.x;\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    const scalar_t top_grad = grad_col[index];\n\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int grad_sampling_ptr = data_weight_ptr;\n    grad_sampling_loc += grad_sampling_ptr << 1;\n    grad_attn_weight += grad_sampling_ptr;\n    const int grad_weight_stride = 1;\n    const int grad_loc_stride = 2;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const int value_ptr_offset =\n          data_value_ptr_init_offset + level_start_id * qid_stride;\n      const scalar_t *data_value_ptr = data_value + value_ptr_offset;\n      scalar_t *grad_value_ptr = grad_value + value_ptr_offset;\n\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n        *(cache_grad_sampling_loc + (threadIdx.x << 1)) = 0;\n        *(cache_grad_sampling_loc + ((threadIdx.x << 1) + 1)) = 0;\n        *(cache_grad_attn_weight + threadIdx.x) = 0;\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          ms_deform_attn_col2im_bilinear(\n              data_value_ptr, spatial_h, spatial_w, num_heads, channels, h_im,\n              w_im, m_col, c_col, top_grad, weight, grad_value_ptr,\n              cache_grad_sampling_loc + (threadIdx.x << 1),\n              cache_grad_attn_weight + threadIdx.x);\n        }\n\n        __syncthreads();\n\n        for (unsigned int s = blockDim.x / 2, spre = blockDim.x; s > 0;\n             s >>= 1, spre >>= 1) {\n          if (tid < s) {\n            const unsigned int xid1 = tid << 1;\n            const unsigned int xid2 = (tid + s) << 1;\n            cache_grad_attn_weight[tid] += cache_grad_attn_weight[tid + s];\n            cache_grad_sampling_loc[xid1] += cache_grad_sampling_loc[xid2];\n            cache_grad_sampling_loc[xid1 + 1] +=\n                cache_grad_sampling_loc[xid2 + 1];\n            if (tid + (s << 1) < spre) {\n              cache_grad_attn_weight[tid] +=\n                  cache_grad_attn_weight[tid + (s << 1)];\n              cache_grad_sampling_loc[xid1] +=\n                  cache_grad_sampling_loc[xid2 + (s << 1)];\n              cache_grad_sampling_loc[xid1 + 1] +=\n                  cache_grad_sampling_loc[xid2 + 1 + (s << 1)];\n            }\n          }\n          __syncthreads();\n        }\n\n        if (tid == 0) {\n          atomicAdd(grad_sampling_loc, cache_grad_sampling_loc[0]);\n          atomicAdd(grad_sampling_loc + 1, cache_grad_sampling_loc[1]);\n          atomicAdd(grad_attn_weight, cache_grad_attn_weight[0]);\n        }\n        __syncthreads();\n\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n        grad_attn_weight += grad_weight_stride;\n        grad_sampling_loc += grad_loc_stride;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void ms_deformable_col2im_gpu_kernel_gm(\n    const int n, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  CUDA_1D_KERNEL_LOOP(index, n) {\n    int _temp = index;\n    const int c_col = _temp % channels;\n    _temp /= channels;\n    const int sampling_index = _temp;\n    const int m_col = _temp % num_heads;\n    _temp /= num_heads;\n    _temp /= num_query;\n    const int b_col = _temp;\n\n    const scalar_t top_grad = grad_col[index];\n\n    int data_weight_ptr = sampling_index * num_levels * num_point;\n    int data_loc_w_ptr = data_weight_ptr << 1;\n    const int grad_sampling_ptr = data_weight_ptr;\n    grad_sampling_loc += grad_sampling_ptr << 1;\n    grad_attn_weight += grad_sampling_ptr;\n    const int grad_weight_stride = 1;\n    const int grad_loc_stride = 2;\n    const int qid_stride = num_heads * channels;\n    const int data_value_ptr_init_offset = b_col * spatial_size * qid_stride;\n\n    for (int l_col = 0; l_col < num_levels; ++l_col) {\n      const int level_start_id = data_level_start_index[l_col];\n      const int spatial_h_ptr = l_col << 1;\n      const int spatial_h = data_spatial_shapes[spatial_h_ptr];\n      const int spatial_w = data_spatial_shapes[spatial_h_ptr + 1];\n      const int value_ptr_offset =\n          data_value_ptr_init_offset + level_start_id * qid_stride;\n      const scalar_t *data_value_ptr = data_value + value_ptr_offset;\n      scalar_t *grad_value_ptr = grad_value + value_ptr_offset;\n\n      for (int p_col = 0; p_col < num_point; ++p_col) {\n        const scalar_t loc_w = data_sampling_loc[data_loc_w_ptr];\n        const scalar_t loc_h = data_sampling_loc[data_loc_w_ptr + 1];\n        const scalar_t weight = data_attn_weight[data_weight_ptr];\n\n        const scalar_t h_im = loc_h * spatial_h - 0.5;\n        const scalar_t w_im = loc_w * spatial_w - 0.5;\n        if (h_im > -1 && w_im > -1 && h_im < spatial_h && w_im < spatial_w) {\n          ms_deform_attn_col2im_bilinear_gm(\n              data_value_ptr, spatial_h, spatial_w, num_heads, channels, h_im,\n              w_im, m_col, c_col, top_grad, weight, grad_value_ptr,\n              grad_sampling_loc, grad_attn_weight);\n        }\n        data_weight_ptr += 1;\n        data_loc_w_ptr += 2;\n        grad_attn_weight += grad_weight_stride;\n        grad_sampling_loc += grad_loc_stride;\n      }\n    }\n  }\n}\n#endif  // DEFORM_ATTN_CUDA_KERNEL\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/nms_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef NMS_CUDA_KERNEL_CUH\n#define NMS_CUDA_KERNEL_CUH\n\n#include <float.h>\n#ifdef MMCV_WITH_TRT\n#include \"common_cuda_helper.hpp\"\n#else  // MMCV_WITH_TRT\n#include \"pytorch_cuda_helper.hpp\"\n#endif  // MMCV_WITH_TRT\n\nint const threadsPerBlock = sizeof(unsigned long long int) * 8;\n\n__device__ inline bool devIoU(float const *const a, float const *const b,\n                              const int offset, const float threshold) {\n  float left = fmaxf(a[0], b[0]), right = fminf(a[2], b[2]);\n  float top = fmaxf(a[1], b[1]), bottom = fminf(a[3], b[3]);\n  float width = fmaxf(right - left + offset, 0.f),\n        height = fmaxf(bottom - top + offset, 0.f);\n  float interS = width * height;\n  float Sa = (a[2] - a[0] + offset) * (a[3] - a[1] + offset);\n  float Sb = (b[2] - b[0] + offset) * (b[3] - b[1] + offset);\n  return interS > threshold * (Sa + Sb - interS);\n}\n\n__global__ void nms_cuda(const int n_boxes, const float iou_threshold,\n                         const int offset, const float *dev_boxes,\n                         unsigned long long *dev_mask) {\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n  const int tid = threadIdx.x;\n\n  if (row_start > col_start) return;\n\n  const int row_size =\n      fminf(n_boxes - row_start * threadsPerBlock, threadsPerBlock);\n  const int col_size =\n      fminf(n_boxes - col_start * threadsPerBlock, threadsPerBlock);\n\n  __shared__ float block_boxes[threadsPerBlock * 4];\n  if (tid < col_size) {\n    block_boxes[tid * 4 + 0] =\n        dev_boxes[(threadsPerBlock * col_start + tid) * 4 + 0];\n    block_boxes[tid * 4 + 1] =\n        dev_boxes[(threadsPerBlock * col_start + tid) * 4 + 1];\n    block_boxes[tid * 4 + 2] =\n        dev_boxes[(threadsPerBlock * col_start + tid) * 4 + 2];\n    block_boxes[tid * 4 + 3] =\n        dev_boxes[(threadsPerBlock * col_start + tid) * 4 + 3];\n  }\n  __syncthreads();\n\n  if (tid < row_size) {\n    const int cur_box_idx = threadsPerBlock * row_start + tid;\n    const float *cur_box = dev_boxes + cur_box_idx * 4;\n    int i = 0;\n    unsigned long long int t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = tid + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      if (devIoU(cur_box, block_boxes + i * 4, offset, iou_threshold)) {\n        t |= 1ULL << i;\n      }\n    }\n    dev_mask[cur_box_idx * gridDim.y + col_start] = t;\n  }\n}\n#endif  // NMS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/nms_rotated_cuda.cuh",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/nms_rotated/nms_rotated_cuda.cu\n#ifndef NMS_ROTATED_CUDA_CUH\n#define NMS_ROTATED_CUDA_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"box_iou_rotated_utils.hpp\"\n\n__host__ __device__ inline int divideUP(const int x, const int y) {\n  return (((x) + (y)-1) / (y));\n}\n\nnamespace {\nint const threadsPerBlock = sizeof(unsigned long long) * 8;\n}\n\ntemplate <typename T>\n__global__ void nms_rotated_cuda_kernel(const int n_boxes,\n                                        const float iou_threshold,\n                                        const T* dev_boxes,\n                                        unsigned long long* dev_mask,\n                                        const int multi_label) {\n  // nms_rotated_cuda_kernel is modified from torchvision's nms_cuda_kernel\n\n  if (multi_label == 1) {\n    const int row_start = blockIdx.y;\n    const int col_start = blockIdx.x;\n\n    // if (row_start > col_start) return;\n\n    const int row_size =\n        min(n_boxes - row_start * threadsPerBlock, threadsPerBlock);\n    const int col_size =\n        min(n_boxes - col_start * threadsPerBlock, threadsPerBlock);\n\n    // Compared to nms_cuda_kernel, where each box is represented with 4 values\n    // (x1, y1, x2, y2), each rotated box is represented with 5 values\n    // (x_center, y_center, width, height, angle_degrees) here.\n    __shared__ T block_boxes[threadsPerBlock * 5];\n    if (threadIdx.x < col_size) {\n      block_boxes[threadIdx.x * 6 + 0] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 6 + 0];\n      block_boxes[threadIdx.x * 6 + 1] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 6 + 1];\n      block_boxes[threadIdx.x * 6 + 2] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 6 + 2];\n      block_boxes[threadIdx.x * 6 + 3] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 6 + 3];\n      block_boxes[threadIdx.x * 6 + 4] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 6 + 4];\n      block_boxes[threadIdx.x * 6 + 5] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 6 + 5];\n    }\n    __syncthreads();\n\n    if (threadIdx.x < row_size) {\n      const int cur_box_idx = threadsPerBlock * row_start + threadIdx.x;\n      const T* cur_box = dev_boxes + cur_box_idx * 6;\n      int i = 0;\n      unsigned long long t = 0;\n      int start = 0;\n      if (row_start == col_start) {\n        start = threadIdx.x + 1;\n      }\n      for (i = start; i < col_size; i++) {\n        // Instead of devIoU used by original horizontal nms, here\n        // we use the single_box_iou_rotated function from\n        // box_iou_rotated_utils.h\n        if (single_box_iou_rotated<T>(cur_box, block_boxes + i * 6, 0) >\n            iou_threshold) {\n          t |= 1ULL << i;\n        }\n      }\n      const int col_blocks = divideUP(n_boxes, threadsPerBlock);\n      dev_mask[cur_box_idx * col_blocks + col_start] = t;\n    }\n  } else {\n    const int row_start = blockIdx.y;\n    const int col_start = blockIdx.x;\n\n    // if (row_start > col_start) return;\n\n    const int row_size =\n        min(n_boxes - row_start * threadsPerBlock, threadsPerBlock);\n    const int col_size =\n        min(n_boxes - col_start * threadsPerBlock, threadsPerBlock);\n\n    // Compared to nms_cuda_kernel, where each box is represented with 4 values\n    // (x1, y1, x2, y2), each rotated box is represented with 5 values\n    // (x_center, y_center, width, height, angle_degrees) here.\n    __shared__ T block_boxes[threadsPerBlock * 5];\n    if (threadIdx.x < col_size) {\n      block_boxes[threadIdx.x * 5 + 0] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 0];\n      block_boxes[threadIdx.x * 5 + 1] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 1];\n      block_boxes[threadIdx.x * 5 + 2] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 2];\n      block_boxes[threadIdx.x * 5 + 3] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 3];\n      block_boxes[threadIdx.x * 5 + 4] =\n          dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 4];\n    }\n    __syncthreads();\n\n    if (threadIdx.x < row_size) {\n      const int cur_box_idx = threadsPerBlock * row_start + threadIdx.x;\n      const T* cur_box = dev_boxes + cur_box_idx * 5;\n      int i = 0;\n      unsigned long long t = 0;\n      int start = 0;\n      if (row_start == col_start) {\n        start = threadIdx.x + 1;\n      }\n      for (i = start; i < col_size; i++) {\n        // Instead of devIoU used by original horizontal nms, here\n        // we use the single_box_iou_rotated function from\n        // box_iou_rotated_utils.h\n        if (single_box_iou_rotated<T>(cur_box, block_boxes + i * 5, 0) >\n            iou_threshold) {\n          t |= 1ULL << i;\n        }\n      }\n      const int col_blocks = divideUP(n_boxes, threadsPerBlock);\n      dev_mask[cur_box_idx * col_blocks + col_start] = t;\n    }\n  }\n}\n\n#endif\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/points_in_boxes_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef POINT_IN_BOXES_CUDA_KERNEL_CUH\n#define POINT_IN_BOXES_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__device__ inline void lidar_to_local_coords(T shift_x, T shift_y, T rz,\n                                             T &local_x, T &local_y) {\n  T cosa = cos(-rz), sina = sin(-rz);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\ntemplate <typename T>\n__device__ inline int check_pt_in_box3d(const T *pt, const T *box3d, T &local_x,\n                                        T &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, x_size, y_size, z_size, rz) in LiDAR coordinate,\n  // cz in the bottom center\n  T x = pt[0], y = pt[1], z = pt[2];\n  T cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  T x_size = box3d[3], y_size = box3d[4], z_size = box3d[5], rz = box3d[6];\n  cz += z_size /\n        2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > z_size / 2.0) return 0;\n  lidar_to_local_coords(x - cx, y - cy, rz, local_x, local_y);\n  float in_flag = (local_x > -x_size / 2.0) & (local_x < x_size / 2.0) &\n                  (local_y > -y_size / 2.0) & (local_y < y_size / 2.0);\n  return in_flag;\n}\n\ntemplate <typename T>\n__global__ void points_in_boxes_part_forward_cuda_kernel(\n    int batch_size, int boxes_num, int pts_num, const T *boxes, const T *pts,\n    int *box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is the bottom center, each box DO NOT overlaps params pts:\n  // (B, npoints, 3) [x, y, z] in LiDAR coordinate params boxes_idx_of_points:\n  // (B, npoints), default -1\n\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= batch_size || pt_idx >= pts_num) return;\n\n  boxes += bs_idx * boxes_num * 7;\n  pts += bs_idx * pts_num * 3 + pt_idx * 3;\n  box_idx_of_points += bs_idx * pts_num + pt_idx;\n\n  T local_x = 0, local_y = 0;\n  int cur_in_flag = 0;\n  for (int k = 0; k < boxes_num; k++) {\n    cur_in_flag = check_pt_in_box3d(pts, boxes + k * 7, local_x, local_y);\n    if (cur_in_flag) {\n      box_idx_of_points[0] = k;\n      break;\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void points_in_boxes_all_forward_cuda_kernel(\n    int batch_size, int boxes_num, int pts_num, const T *boxes, const T *pts,\n    int *box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is the bottom center, each box DO NOT overlaps params pts:\n  // (B, npoints, 3) [x, y, z] in LiDAR coordinate params boxes_idx_of_points:\n  // (B, npoints), default -1\n\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= batch_size || pt_idx >= pts_num) return;\n\n  boxes += bs_idx * boxes_num * 7;\n  pts += bs_idx * pts_num * 3 + pt_idx * 3;\n  box_idx_of_points += bs_idx * pts_num * boxes_num + pt_idx * boxes_num;\n\n  T local_x = 0, local_y = 0;\n  for (int k = 0; k < boxes_num; k++) {\n    const int cur_in_flag =\n        check_pt_in_box3d(pts, boxes + k * 7, local_x, local_y);\n    if (cur_in_flag) {\n      box_idx_of_points[k] = 1;\n    }\n  }\n}\n\n#endif  // POINT_IN_BOXES_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/psamask_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef PSAMASK_CUDA_KERNEL_CUH\n#define PSAMASK_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\n// CUDA: grid stride looping\n#ifndef CUDA_KERNEL_LOOP\n#define CUDA_KERNEL_LOOP(i, n)                                 \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < (n); \\\n       i += blockDim.x * gridDim.x)\n#endif\n\ntemplate <typename T>\n__global__ void psamask_collect_forward_cuda(\n    const int nthreads, const int h_feature, const int w_feature,\n    const int h_mask, const int w_mask, const int half_h_mask,\n    const int half_w_mask, const T* mask_data, T* buffer_data) {\n  CUDA_KERNEL_LOOP(index, nthreads) {\n    const int w = index % w_feature;\n    const int h = (index / w_feature) % h_feature;\n    const int n = index / w_feature / h_feature;\n    // effective mask region : [hstart, hend) x [wstart, wend) with mask-indexed\n    const int hstart = max(0, half_h_mask - h);\n    const int hend = min(h_mask, h_feature + half_h_mask - h);\n    const int wstart = max(0, half_w_mask - w);\n    const int wend = min(w_mask, w_feature + half_w_mask - w);\n    // (hidx,                    widx                   ) with mask-indexed\n    // (hidx + h - half_h_mask, widx + w - half_w_mask) with feature-indexed\n    for (int hidx = hstart; hidx < hend; hidx++) {\n      for (int widx = wstart; widx < wend; widx++) {\n        buffer_data[(n * h_feature * w_feature +\n                     (hidx + h - half_h_mask) * w_feature +\n                     (widx + w - half_w_mask)) *\n                        h_feature * w_feature +\n                    h * w_feature + w] = mask_data\n            [((n * h_mask * w_mask + hidx * w_mask + widx) * h_feature + h) *\n                 w_feature +\n             w];\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void psamask_distribute_forward_cuda(\n    const int nthreads, const int h_feature, const int w_feature,\n    const int h_mask, const int w_mask, const int half_h_mask,\n    const int half_w_mask, const T* mask_data, T* buffer_data) {\n  CUDA_KERNEL_LOOP(index, nthreads) {\n    const int w = index % w_feature;\n    const int h = (index / w_feature) % h_feature;\n    const int n = index / w_feature / h_feature;\n    // effective mask region : [hstart, hend) x [wstart, wend) with mask-indexed\n    const int hstart = max(0, half_h_mask - h);\n    const int hend = min(h_mask, h_feature + half_h_mask - h);\n    const int wstart = max(0, half_w_mask - w);\n    const int wend = min(w_mask, w_feature + half_w_mask - w);\n    // (hidx,                    widx                   ) with mask-indexed\n    // (hidx + h - half_h_mask, widx + w - half_w_mask) with feature-indexed\n    for (int hidx = hstart; hidx < hend; hidx++) {\n      for (int widx = wstart; widx < wend; widx++) {\n        buffer_data[(n * h_feature * w_feature + h * w_feature + w) *\n                        h_feature * w_feature +\n                    (hidx + h - half_h_mask) * w_feature +\n                    (widx + w - half_w_mask)] = mask_data\n            [((n * h_mask * w_mask + hidx * w_mask + widx) * h_feature + h) *\n                 w_feature +\n             w];\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void psamask_collect_backward_cuda(\n    const int nthreads, const int h_feature, const int w_feature,\n    const int h_mask, const int w_mask, const int half_h_mask,\n    const int half_w_mask, const T* buffer_diff, T* mask_diff) {\n  CUDA_KERNEL_LOOP(index, nthreads) {\n    const int w = index % w_feature;\n    const int h = (index / w_feature) % h_feature;\n    const int n = index / w_feature / h_feature;\n    // effective mask region : [hstart, hend) x [wstart, wend) with mask-indexed\n    const int hstart = max(0, half_h_mask - h);\n    const int hend = min(h_mask, h_feature + half_h_mask - h);\n    const int wstart = max(0, half_w_mask - w);\n    const int wend = min(w_mask, w_feature + half_w_mask - w);\n    // (hidx,                    widx                   ) with mask-indexed\n    // (hidx + h - half_h_mask, widx + w - half_w_mask) with feature-indexed\n    for (int hidx = hstart; hidx < hend; hidx++) {\n      for (int widx = wstart; widx < wend; widx++) {\n        mask_diff[((n * h_mask * w_mask + hidx * w_mask + widx) * h_feature +\n                   h) *\n                      w_feature +\n                  w] = buffer_diff[(n * h_feature * w_feature +\n                                    (hidx + h - half_h_mask) * w_feature +\n                                    (widx + w - half_w_mask)) *\n                                       h_feature * w_feature +\n                                   h * w_feature + w];\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void psamask_distribute_backward_cuda(\n    const int nthreads, const int h_feature, const int w_feature,\n    const int h_mask, const int w_mask, const int half_h_mask,\n    const int half_w_mask, const T* buffer_diff, T* mask_diff) {\n  CUDA_KERNEL_LOOP(index, nthreads) {\n    const int w = index % w_feature;\n    const int h = (index / w_feature) % h_feature;\n    const int n = index / w_feature / h_feature;\n    // effective mask region : [hstart, hend) x [wstart, wend) with mask-indexed\n    const int hstart = max(0, half_h_mask - h);\n    const int hend = min(h_mask, h_feature + half_h_mask - h);\n    const int wstart = max(0, half_w_mask - w);\n    const int wend = min(w_mask, w_feature + half_w_mask - w);\n    // (hidx,                    widx                   ) with mask-indexed\n    // (hidx + h - half_h_mask, widx + w - half_w_mask) with feature-indexed\n    for (int hidx = hstart; hidx < hend; hidx++) {\n      for (int widx = wstart; widx < wend; widx++) {\n        mask_diff[((n * h_mask * w_mask + hidx * w_mask + widx) * h_feature +\n                   h) *\n                      w_feature +\n                  w] =\n            buffer_diff[(n * h_feature * w_feature + h * w_feature + w) *\n                            h_feature * w_feature +\n                        (hidx + h - half_h_mask) * w_feature +\n                        (widx + w - half_w_mask)];\n      }\n    }\n  }\n}\n\n#endif  // PSAMASK_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/roi_align_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef ROI_ALIGN_CUDA_KERNEL_CUH\n#define ROI_ALIGN_CUDA_KERNEL_CUH\n\n#include <float.h>\n#ifdef MMCV_WITH_TRT\n#include \"common_cuda_helper.hpp\"\n#else  // MMCV_WITH_TRT\n#include \"pytorch_cuda_helper.hpp\"\n#endif  // MMCV_WITH_TRT\n\n/*** Forward ***/\ntemplate <typename T>\n__global__ void roi_align_forward_cuda_kernel(\n    const int nthreads, const T* input, const T* rois, T* output, T* argmax_y,\n    T* argmax_x, const int pooled_height, const int pooled_width,\n    const T spatial_scale, const int sampling_ratio,\n    const int pool_mode,  // 0 - max pool, 1 - avg pool\n    const bool aligned, const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n\n    // Do not using rounding; this implementation detail is critical\n    T offset = aligned ? (T)0.5 : (T)0.0;\n    T roi_start_w = offset_rois[1] * spatial_scale - offset;\n    T roi_start_h = offset_rois[2] * spatial_scale - offset;\n    T roi_end_w = offset_rois[3] * spatial_scale - offset;\n    T roi_end_h = offset_rois[4] * spatial_scale - offset;\n\n    T roi_width = roi_end_w - roi_start_w;\n    T roi_height = roi_end_h - roi_start_h;\n    if (!aligned) {  // for backward-compatibility only\n      roi_width = max(roi_width, (T)1.);\n      roi_height = max(roi_height, (T)1.);\n    }\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    const T* offset_input =\n        input + (roi_batch_ind * channels + c) * height * width;\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h =\n        (sampling_ratio > 0)\n            ? sampling_ratio\n            : static_cast<int>(ceilf(roi_height / pooled_height));\n    int roi_bin_grid_w =\n        (sampling_ratio > 0)\n            ? sampling_ratio\n            : static_cast<int>(ceilf(roi_width / pooled_width));\n\n    if (pool_mode == 0) {\n      // We do max pooling inside a bin\n      T maxval = -FLT_MAX;\n      T maxidx_y = -1.f, maxidx_x = -1.f;\n      for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n        const T y = roi_start_h + ph * bin_size_h +\n                    static_cast<T>(iy + .5f) * bin_size_h /\n                        static_cast<T>(roi_bin_grid_h);\n        for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n          const T x = roi_start_w + pw * bin_size_w +\n                      static_cast<T>(ix + .5f) * bin_size_w /\n                          static_cast<T>(roi_bin_grid_w);\n          T val =\n              bilinear_interpolate(offset_input, height, width, y, x, index);\n          if (val > maxval) {\n            maxval = val;\n            maxidx_y = y;\n            maxidx_x = x;\n          }\n        }\n      }\n      output[index] = maxval;\n      argmax_y[index] = maxidx_y;\n      argmax_x[index] = maxidx_x;\n    } else if (pool_mode == 1) {\n      // We do average pooling inside a bin\n      const T count = max(roi_bin_grid_h * roi_bin_grid_w, 1);\n      T output_val = 0.;\n      for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n        const T y = roi_start_h + ph * bin_size_h +\n                    static_cast<T>(iy + .5f) * bin_size_h /\n                        static_cast<T>(roi_bin_grid_h);\n        for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n          const T x = roi_start_w + pw * bin_size_w +\n                      static_cast<T>(ix + .5f) * bin_size_w /\n                          static_cast<T>(roi_bin_grid_w);\n          T val =\n              bilinear_interpolate(offset_input, height, width, y, x, index);\n          output_val += val;\n        }\n      }\n      output[index] = output_val / count;\n    }\n  }\n}\n\n/*** Backward ***/\ntemplate <typename T>\n__global__ void roi_align_backward_cuda_kernel(\n    const int nthreads, const T* grad_output, const T* rois, const T* argmax_y,\n    const T* argmax_x, T* grad_input, const int pooled_height,\n    const int pooled_width, const T spatial_scale, const int sampling_ratio,\n    const int pool_mode,  // 0 - max pool, 1 - avg pool\n    const bool aligned, const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T grad_output_this_bin = grad_output[index];\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n    T* offset_grad_input =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n\n    if (pool_mode == 0) {\n      T y = argmax_y[index], x = argmax_x[index];\n      if (y != -1.f) {\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n        bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4,\n                                      x_low, x_high, y_low, y_high, index);\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          atomicAdd(offset_grad_input + y_low * width + x_low,\n                    grad_output_this_bin * w1);\n          atomicAdd(offset_grad_input + y_low * width + x_high,\n                    grad_output_this_bin * w2);\n          atomicAdd(offset_grad_input + y_high * width + x_low,\n                    grad_output_this_bin * w3);\n          atomicAdd(offset_grad_input + y_high * width + x_high,\n                    grad_output_this_bin * w4);\n        }\n      }\n    } else if (pool_mode == 1) {\n      // Do not using rounding; this implementation detail is critical\n      T offset = aligned ? (T)0.5 : (T)0.0;\n      T roi_start_w = offset_rois[1] * spatial_scale - offset;\n      T roi_start_h = offset_rois[2] * spatial_scale - offset;\n      T roi_end_w = offset_rois[3] * spatial_scale - offset;\n      T roi_end_h = offset_rois[4] * spatial_scale - offset;\n\n      T roi_width = roi_end_w - roi_start_w;\n      T roi_height = roi_end_h - roi_start_h;\n      if (!aligned) {  // for backward-compatibility only\n        roi_width = max(roi_width, (T)1.);\n        roi_height = max(roi_height, (T)1.);\n      }\n\n      T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n      T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n      // We use roi_bin_grid to sample the grid and mimic integral\n      int roi_bin_grid_h =\n          (sampling_ratio > 0)\n              ? sampling_ratio\n              : static_cast<int>(ceilf(roi_height / pooled_height));\n      int roi_bin_grid_w =\n          (sampling_ratio > 0)\n              ? sampling_ratio\n              : static_cast<int>(ceilf(roi_width / pooled_width));\n\n      // We do average (integral) pooling inside a bin\n      const T count = roi_bin_grid_h * roi_bin_grid_w;  // e.g. = 4\n\n      for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n        const T y = roi_start_h + ph * bin_size_h +\n                    static_cast<T>(iy + .5f) * bin_size_h /\n                        static_cast<T>(roi_bin_grid_h);\n        for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n          const T x = roi_start_w + pw * bin_size_w +\n                      static_cast<T>(ix + .5f) * bin_size_w /\n                          static_cast<T>(roi_bin_grid_w);\n\n          T w1, w2, w3, w4;\n          int x_low, x_high, y_low, y_high;\n          bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4,\n                                        x_low, x_high, y_low, y_high, index);\n\n          if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n            atomicAdd(offset_grad_input + y_low * width + x_low,\n                      grad_output_this_bin * w1 / count);\n            atomicAdd(offset_grad_input + y_low * width + x_high,\n                      grad_output_this_bin * w2 / count);\n            atomicAdd(offset_grad_input + y_high * width + x_low,\n                      grad_output_this_bin * w3 / count);\n            atomicAdd(offset_grad_input + y_high * width + x_high,\n                      grad_output_this_bin * w4 / count);\n          }\n        }\n      }\n    }\n  }\n}\n\n#endif  // ROI_ALIGN_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/roi_align_rotated_cuda_kernel.cuh",
    "content": "// Modified from\n// https://github.com/facebookresearch/detectron2/tree/master/detectron2/layers/csrc/ROIAlignRotated\n// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n#ifndef ROI_ALIGN_ROTATED_CUDA_KERNEL_CUH\n#define ROI_ALIGN_ROTATED_CUDA_KERNEL_CUH\n\n#include <float.h>\n#ifdef MMCV_WITH_TRT\n#include \"common_cuda_helper.hpp\"\n#else  // MMCV_WITH_TRT\n#include \"pytorch_cuda_helper.hpp\"\n#endif  // MMCV_WITH_TRT\n\n/*** Forward ***/\ntemplate <typename scalar_t>\n__global__ void roi_align_rotated_forward_cuda_kernel(\n    const int nthreads, const scalar_t *bottom_data,\n    const scalar_t *bottom_rois, const scalar_t spatial_scale,\n    const int sample_num, const bool aligned, const bool clockwise,\n    const int channels, const int height, const int width,\n    const int pooled_height, const int pooled_width, scalar_t *top_data) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const scalar_t *offset_bottom_rois = bottom_rois + n * 6;\n    int roi_batch_ind = offset_bottom_rois[0];\n\n    // Do not using rounding; this implementation detail is critical\n    scalar_t offset = aligned ? (scalar_t)0.5 : (scalar_t)0.0;\n    scalar_t roi_center_w = offset_bottom_rois[1] * spatial_scale - offset;\n    scalar_t roi_center_h = offset_bottom_rois[2] * spatial_scale - offset;\n    scalar_t roi_width = offset_bottom_rois[3] * spatial_scale;\n    scalar_t roi_height = offset_bottom_rois[4] * spatial_scale;\n    // scalar_t theta = offset_bottom_rois[5] * M_PI / 180.0;\n    scalar_t theta = offset_bottom_rois[5];\n    if (clockwise) {\n      theta = -theta;  // If clockwise, the angle needs to be reversed.\n    }\n    if (!aligned) {  // for backward-compatibility only\n      // Force malformed ROIs to be 1x1\n      roi_width = max(roi_width, (scalar_t)1.);\n      roi_height = max(roi_height, (scalar_t)1.);\n    }\n    scalar_t bin_size_h = static_cast<scalar_t>(roi_height) /\n                          static_cast<scalar_t>(pooled_height);\n    scalar_t bin_size_w =\n        static_cast<scalar_t>(roi_width) / static_cast<scalar_t>(pooled_width);\n\n    const scalar_t *offset_bottom_data =\n        bottom_data + (roi_batch_ind * channels + c) * height * width;\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sample_num > 0)\n                             ? sample_num\n                             : ceilf(roi_height / pooled_height);  // e.g., = 2\n    int roi_bin_grid_w =\n        (sample_num > 0) ? sample_num : ceilf(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    scalar_t roi_start_h = -roi_height / 2.0;\n    scalar_t roi_start_w = -roi_width / 2.0;\n    scalar_t cosscalar_theta = cos(theta);\n    scalar_t sinscalar_theta = sin(theta);\n\n    // We do average (integral) pooling inside a bin\n    const scalar_t count = max(roi_bin_grid_h * roi_bin_grid_w, 1);  // e.g. = 4\n\n    scalar_t output_val = 0.;\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {  // e.g., iy = 0, 1\n      const scalar_t yy =\n          roi_start_h + ph * bin_size_h +\n          static_cast<scalar_t>(iy + .5f) * bin_size_h /\n              static_cast<scalar_t>(roi_bin_grid_h);  // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const scalar_t xx = roi_start_w + pw * bin_size_w +\n                            static_cast<scalar_t>(ix + .5f) * bin_size_w /\n                                static_cast<scalar_t>(roi_bin_grid_w);\n\n        // Rotate by theta (counterclockwise) around the center and translate\n        scalar_t y = yy * cosscalar_theta - xx * sinscalar_theta + roi_center_h;\n        scalar_t x = yy * sinscalar_theta + xx * cosscalar_theta + roi_center_w;\n\n        scalar_t val = bilinear_interpolate<scalar_t>(\n            offset_bottom_data, height, width, y, x, index);\n        output_val += val;\n      }\n    }\n    output_val /= count;\n\n    top_data[index] = output_val;\n  }\n}\n\n/*** Backward ***/\ntemplate <typename scalar_t>\n__global__ void roi_align_rotated_backward_cuda_kernel(\n    const int nthreads, const scalar_t *top_diff, const scalar_t *bottom_rois,\n    const scalar_t spatial_scale, const int sample_num, const bool aligned,\n    const bool clockwise, const int channels, const int height, const int width,\n    const int pooled_height, const int pooled_width, scalar_t *bottom_diff) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const scalar_t *offset_bottom_rois = bottom_rois + n * 6;\n    int roi_batch_ind = offset_bottom_rois[0];\n\n    // Do not round\n    scalar_t offset = aligned ? (scalar_t)0.5 : (scalar_t)0.0;\n    scalar_t roi_center_w = offset_bottom_rois[1] * spatial_scale - offset;\n    scalar_t roi_center_h = offset_bottom_rois[2] * spatial_scale - offset;\n    scalar_t roi_width = offset_bottom_rois[3] * spatial_scale;\n    scalar_t roi_height = offset_bottom_rois[4] * spatial_scale;\n    // scalar_t theta = offset_bottom_rois[5] * M_PI / 180.0;\n    scalar_t theta = offset_bottom_rois[5];\n    if (clockwise) {\n      theta = -theta;  // If clockwise, the angle needs to be reversed.\n    }\n    if (!aligned) {  // for backward-compatibility only\n      // Force malformed ROIs to be 1x1\n      roi_width = max(roi_width, (scalar_t)1.);\n      roi_height = max(roi_height, (scalar_t)1.);\n    }\n    scalar_t bin_size_h = static_cast<scalar_t>(roi_height) /\n                          static_cast<scalar_t>(pooled_height);\n    scalar_t bin_size_w =\n        static_cast<scalar_t>(roi_width) / static_cast<scalar_t>(pooled_width);\n\n    scalar_t *offset_bottom_diff =\n        bottom_diff + (roi_batch_ind * channels + c) * height * width;\n\n    int top_offset = (n * channels + c) * pooled_height * pooled_width;\n    const scalar_t *offset_top_diff = top_diff + top_offset;\n    const scalar_t top_diff_this_bin = offset_top_diff[ph * pooled_width + pw];\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sample_num > 0)\n                             ? sample_num\n                             : ceilf(roi_height / pooled_height);  // e.g., = 2\n    int roi_bin_grid_w =\n        (sample_num > 0) ? sample_num : ceilf(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    scalar_t roi_start_h = -roi_height / 2.0;\n    scalar_t roi_start_w = -roi_width / 2.0;\n    scalar_t cosTheta = cos(theta);\n    scalar_t sinTheta = sin(theta);\n\n    // We do average (integral) pooling inside a bin\n    const scalar_t count = roi_bin_grid_h * roi_bin_grid_w;  // e.g. = 4\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {  // e.g., iy = 0, 1\n      const scalar_t yy =\n          roi_start_h + ph * bin_size_h +\n          static_cast<scalar_t>(iy + .5f) * bin_size_h /\n              static_cast<scalar_t>(roi_bin_grid_h);  // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const scalar_t xx = roi_start_w + pw * bin_size_w +\n                            static_cast<scalar_t>(ix + .5f) * bin_size_w /\n                                static_cast<scalar_t>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        scalar_t y = yy * cosTheta - xx * sinTheta + roi_center_h;\n        scalar_t x = yy * sinTheta + xx * cosTheta + roi_center_w;\n\n        scalar_t w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n\n        bilinear_interpolate_gradient<scalar_t>(height, width, y, x, w1, w2, w3,\n                                                w4, x_low, x_high, y_low,\n                                                y_high, index);\n\n        scalar_t g1 = top_diff_this_bin * w1 / count;\n        scalar_t g2 = top_diff_this_bin * w2 / count;\n        scalar_t g3 = top_diff_this_bin * w3 / count;\n        scalar_t g4 = top_diff_this_bin * w4 / count;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          atomicAdd(offset_bottom_diff + y_low * width + x_low, g1);\n          atomicAdd(offset_bottom_diff + y_low * width + x_high, g2);\n          atomicAdd(offset_bottom_diff + y_high * width + x_low, g3);\n          atomicAdd(offset_bottom_diff + y_high * width + x_high, g4);\n        }  // if\n      }    // ix\n    }      // iy\n  }        // CUDA_1D_KERNEL_LOOP\n}  // RoIAlignBackward\n\n#endif  // ROI_ALIGN_ROTATED_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/roi_pool_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef ROI_POOL_CUDA_KERNEL_CUH\n#define ROI_POOL_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void roi_pool_forward_cuda_kernel(\n    const int nthreads, const T* input, const T* rois, T* output, int* argmax,\n    const int pooled_height, const int pooled_width, const T spatial_scale,\n    const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n    // calculate the roi region on feature maps\n    T roi_x1 = offset_rois[1] * spatial_scale;\n    T roi_y1 = offset_rois[2] * spatial_scale;\n    T roi_x2 = (offset_rois[3] + 1) * spatial_scale;\n    T roi_y2 = (offset_rois[4] + 1) * spatial_scale;\n\n    // force malformed rois to be 1x1\n    T roi_w = roi_x2 - roi_x1;\n    T roi_h = roi_y2 - roi_y1;\n    if (roi_w <= 0 || roi_h <= 0) continue;\n\n    T bin_size_w = roi_w / static_cast<T>(pooled_width);\n    T bin_size_h = roi_h / static_cast<T>(pooled_height);\n\n    // the corresponding bin region\n    int bin_x1 = floorf(static_cast<T>(pw) * bin_size_w + roi_x1);\n    int bin_y1 = floorf(static_cast<T>(ph) * bin_size_h + roi_y1);\n    int bin_x2 = ceilf(static_cast<T>(pw + 1) * bin_size_w + roi_x1);\n    int bin_y2 = ceilf(static_cast<T>(ph + 1) * bin_size_h + roi_y1);\n\n    // add roi offsets and clip to input boundaries\n    bin_x1 = min(max(bin_x1, 0), width);\n    bin_y1 = min(max(bin_y1, 0), height);\n    bin_x2 = min(max(bin_x2, 0), width);\n    bin_y2 = min(max(bin_y2, 0), height);\n    bool is_empty = (bin_y2 <= bin_y1) || (bin_x2 <= bin_x1);\n\n    const T* offset_input =\n        input + (roi_batch_ind * channels + c) * height * width;\n    // Define an empty pooling region to be zero\n    // If nothing is pooled, argmax = -1 causes nothing to be backprop'd\n    T max_val = is_empty ? 0 : -FLT_MAX;\n    int max_idx = -1;\n    for (int h = bin_y1; h < bin_y2; ++h) {\n      for (int w = bin_x1; w < bin_x2; ++w) {\n        int offset = h * width + w;\n        if (offset_input[offset] > max_val) {\n          max_val = offset_input[offset];\n          max_idx = offset;\n        }\n      }\n    }\n    output[index] = max_val;\n    if (argmax != NULL) argmax[index] = max_idx;\n  }\n}\n\ntemplate <typename T>\n__global__ void roi_pool_backward_cuda_kernel(\n    const int nthreads, const T* grad_output, const T* rois, const int* argmax,\n    T* grad_input, const int pooled_height, const int pooled_width,\n    const int channels, const int height, const int width) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c) is an element in the pooled output\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    int roi_batch_ind = rois[n * 5];\n    T* grad_input_offset =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n    int argmax_index = argmax[index];\n\n    if (argmax_index != -1) {\n      atomicAdd(grad_input_offset + argmax_index, grad_output[index]);\n    }\n  }\n}\n\n#endif  // ROI_POOL_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/roiaware_pool3d_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef ROIAWARE_POOL3D_CUDA_KERNEL_CUH\n#define ROIAWARE_POOL3D_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__device__ inline void lidar_to_local_coords(T shift_x, T shift_y, T rz,\n                                             T &local_x, T &local_y) {\n  T cosa = cos(-rz), sina = sin(-rz);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\ntemplate <typename T>\n__device__ inline int check_pt_in_box3d(const T *pt, const T *box3d, T &local_x,\n                                        T &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, x_size, y_size, z_size, rz) in LiDAR coordinate,\n  // cz in the bottom center\n  T x = pt[0], y = pt[1], z = pt[2];\n  T cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  T x_size = box3d[3], y_size = box3d[4], z_size = box3d[5], rz = box3d[6];\n  cz += z_size /\n        2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > z_size / 2.0) return 0;\n  lidar_to_local_coords(x - cx, y - cy, rz, local_x, local_y);\n  float in_flag = (local_x > -x_size / 2.0) & (local_x < x_size / 2.0) &\n                  (local_y > -y_size / 2.0) & (local_y < y_size / 2.0);\n  return in_flag;\n}\n\ntemplate <typename T>\n__global__ void generate_pts_mask_for_box3d(int boxes_num, int pts_num,\n                                            int out_x, int out_y, int out_z,\n                                            const T *rois, const T *pts,\n                                            int *pts_mask) {\n  // params rois: (N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate params pts: (npoints, 3) [x, y, z] params pts_mask: (N,\n  // npoints): -1 means point does not in this box, otherwise: encode (x_idxs,\n  // y_idxs, z_idxs) by binary bit\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  int box_idx = blockIdx.y;\n  if (pt_idx >= pts_num || box_idx >= boxes_num) return;\n\n  pts += pt_idx * 3;\n  rois += box_idx * 7;\n  pts_mask += box_idx * pts_num + pt_idx;\n\n  T local_x = 0, local_y = 0;\n  int cur_in_flag = check_pt_in_box3d(pts, rois, local_x, local_y);\n\n  pts_mask[0] = -1;\n  if (cur_in_flag > 0) {\n    T local_z = pts[2] - rois[2];\n    T x_size = rois[3], y_size = rois[4], z_size = rois[5];\n\n    T x_res = x_size / out_x;\n    T y_res = y_size / out_y;\n    T z_res = z_size / out_z;\n\n    unsigned int x_idx = int((local_x + x_size / 2) / x_res);\n    unsigned int y_idx = int((local_y + y_size / 2) / y_res);\n    unsigned int z_idx = int(local_z / z_res);\n\n    x_idx = min(max(x_idx, 0), out_x - 1);\n    y_idx = min(max(y_idx, 0), out_y - 1);\n    z_idx = min(max(z_idx, 0), out_z - 1);\n\n    unsigned int idx_encoding = (x_idx << 16) + (y_idx << 8) + z_idx;\n\n    pts_mask[0] = idx_encoding;\n  }\n}\n\ntemplate <typename T>\n__global__ void collect_inside_pts_for_box3d(int boxes_num, int pts_num,\n                                             int max_pts_each_voxel, int out_x,\n                                             int out_y, int out_z,\n                                             const int *pts_mask,\n                                             T *pts_idx_of_voxels) {\n  // params pts_mask: (N, npoints)  0 or 1\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n\n  int box_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (box_idx >= boxes_num) return;\n\n  int max_num_pts = max_pts_each_voxel - 1;  // index 0 is the counter\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel;\n\n  for (int k = 0; k < pts_num; k++) {\n    if (pts_mask[box_idx * pts_num + k] != -1) {\n      unsigned int idx_encoding = pts_mask[box_idx * pts_num + k];\n      unsigned int x_idx = (idx_encoding >> 16) & 0xFF;\n      unsigned int y_idx = (idx_encoding >> 8) & 0xFF;\n      unsigned int z_idx = idx_encoding & 0xFF;\n      unsigned int base_offset = x_idx * out_y * out_z * max_pts_each_voxel +\n                                 y_idx * out_z * max_pts_each_voxel +\n                                 z_idx * max_pts_each_voxel;\n      unsigned int cnt = pts_idx_of_voxels[base_offset];\n      if (cnt < max_num_pts) {\n        pts_idx_of_voxels[base_offset + cnt + 1] = k;\n        pts_idx_of_voxels[base_offset]++;\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void roiaware_maxpool3d(int boxes_num, int pts_num, int channels,\n                                   int max_pts_each_voxel, int out_x, int out_y,\n                                   int out_z, const T *pts_feature,\n                                   const int *pts_idx_of_voxels,\n                                   T *pooled_features, int *argmax) {\n  // params pts_feature: (npoints, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel),\n  // index 0 is the counter params pooled_features: (N, out_x, out_y, out_z, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel +\n                       offset_base * max_pts_each_voxel;\n  pooled_features += box_idx * out_x * out_y * out_z * channels +\n                     offset_base * channels + channel_idx;\n  argmax += box_idx * out_x * out_y * out_z * channels +\n            offset_base * channels + channel_idx;\n\n  int argmax_idx = -1;\n  float max_val = -1e50;\n\n  int total_pts = pts_idx_of_voxels[0];\n\n  for (int k = 1; k <= total_pts; k++) {\n    if (pts_feature[pts_idx_of_voxels[k] * channels + channel_idx] > max_val) {\n      max_val = pts_feature[pts_idx_of_voxels[k] * channels + channel_idx];\n      argmax_idx = pts_idx_of_voxels[k];\n    }\n  }\n\n  if (argmax_idx != -1) {\n    pooled_features[0] = max_val;\n  }\n  argmax[0] = argmax_idx;\n}\n\ntemplate <typename T>\n__global__ void roiaware_avgpool3d(int boxes_num, int pts_num, int channels,\n                                   int max_pts_each_voxel, int out_x, int out_y,\n                                   int out_z, const T *pts_feature,\n                                   const int *pts_idx_of_voxels,\n                                   T *pooled_features) {\n  // params pts_feature: (npoints, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel),\n  // index 0 is the counter params pooled_features: (N, out_x, out_y, out_z, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel +\n                       offset_base * max_pts_each_voxel;\n  pooled_features += box_idx * out_x * out_y * out_z * channels +\n                     offset_base * channels + channel_idx;\n\n  float sum_val = 0;\n  int total_pts = pts_idx_of_voxels[0];\n\n  for (int k = 1; k <= total_pts; k++) {\n    sum_val += pts_feature[pts_idx_of_voxels[k] * channels + channel_idx];\n  }\n\n  if (total_pts > 0) {\n    pooled_features[0] = sum_val / total_pts;\n  }\n}\n\ntemplate <typename T>\n__global__ void roiaware_maxpool3d_backward(int boxes_num, int channels,\n                                            int out_x, int out_y, int out_z,\n                                            const int *argmax,\n                                            const T *grad_out, T *grad_in) {\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  argmax += box_idx * out_x * out_y * out_z * channels +\n            offset_base * channels + channel_idx;\n  grad_out += box_idx * out_x * out_y * out_z * channels +\n              offset_base * channels + channel_idx;\n\n  if (argmax[0] == -1) return;\n\n  atomicAdd(grad_in + argmax[0] * channels + channel_idx, grad_out[0] * 1);\n}\n\ntemplate <typename T>\n__global__ void roiaware_avgpool3d_backward(int boxes_num, int channels,\n                                            int out_x, int out_y, int out_z,\n                                            int max_pts_each_voxel,\n                                            const int *pts_idx_of_voxels,\n                                            const T *grad_out, T *grad_in) {\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel +\n                       offset_base * max_pts_each_voxel;\n  grad_out += box_idx * out_x * out_y * out_z * channels +\n              offset_base * channels + channel_idx;\n\n  int total_pts = pts_idx_of_voxels[0];\n  float cur_grad = 1 / fmaxf(float(total_pts), 1.0);\n  for (int k = 1; k <= total_pts; k++) {\n    atomicAdd(grad_in + pts_idx_of_voxels[k] * channels + channel_idx,\n              grad_out[0] * cur_grad);\n  }\n}\n\n#endif  // ROIAWARE_POOL3D_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/roipoint_pool3d_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef ROIPOINT_POOL3D_CUDA_KERNEL_CUH\n#define ROIPOINT_POOL3D_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__device__ inline void lidar_to_local_coords(T shift_x, T shift_y, T rz,\n                                             T &local_x, T &local_y) {\n  T cosa = cos(-rz), sina = sin(-rz);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\ntemplate <typename T>\n__device__ inline int check_pt_in_box3d(const T *pt, const T *box3d, T &local_x,\n                                        T &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, dx, dy, dz, rz) in LiDAR coordinate, cz in the\n  // bottom center\n  T x = pt[0], y = pt[1], z = pt[2];\n  T cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  T dx = box3d[3], dy = box3d[4], dz = box3d[5], rz = box3d[6];\n  cz += dz / 2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > dz / 2.0) return 0;\n  lidar_to_local_coords(x - cx, y - cy, rz, local_x, local_y);\n  T in_flag = (local_x > -dx / 2.0) & (local_x < dx / 2.0) &\n              (local_y > -dy / 2.0) & (local_y < dy / 2.0);\n  return in_flag;\n}\n\ntemplate <typename T>\n__global__ void assign_pts_to_box3d(int batch_size, int pts_num, int boxes_num,\n                                    const T *xyz, const T *boxes3d,\n                                    int *pts_assign) {\n  // params xyz: (B, N, 3)\n  // params boxes3d: (B, M, 7)\n  // params pts_assign: (B, N, M): idx of the corresponding box3d, -1 means\n  // background points\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  int box_idx = blockIdx.y;\n  int bs_idx = blockIdx.z;\n\n  if (pt_idx >= pts_num || box_idx >= boxes_num || bs_idx >= batch_size) {\n    return;\n  }\n  int assign_idx = bs_idx * pts_num * boxes_num + pt_idx * boxes_num + box_idx;\n  pts_assign[assign_idx] = 0;\n\n  int box_offset = bs_idx * boxes_num * 7 + box_idx * 7;\n  int pt_offset = bs_idx * pts_num * 3 + pt_idx * 3;\n\n  T local_x = 0, local_y = 0;\n  int cur_in_flag = check_pt_in_box3d(xyz + pt_offset, boxes3d + box_offset,\n                                      local_x, local_y);\n  pts_assign[assign_idx] = cur_in_flag;\n}\n\n__global__ void get_pooled_idx(int batch_size, int pts_num, int boxes_num,\n                               int sampled_pts_num, const int *pts_assign,\n                               int *pts_idx, int *pooled_empty_flag) {\n  // params xyz: (B, N, 3)\n  // params pts_feature: (B, N, C)\n  // params pts_assign: (B, N)\n  // params pts_idx: (B, M, 512)\n  // params pooled_empty_flag: (B, M)\n\n  int boxes_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (boxes_idx >= boxes_num) {\n    return;\n  }\n\n  int bs_idx = blockIdx.y;\n\n  int cnt = 0;\n  for (int k = 0; k < pts_num; k++) {\n    if (pts_assign[bs_idx * pts_num * boxes_num + k * boxes_num + boxes_idx]) {\n      if (cnt < sampled_pts_num) {\n        pts_idx[bs_idx * boxes_num * sampled_pts_num +\n                boxes_idx * sampled_pts_num + cnt] = k;\n        cnt++;\n      } else\n        break;\n    }\n  }\n\n  if (cnt == 0) {\n    pooled_empty_flag[bs_idx * boxes_num + boxes_idx] = 1;\n  } else if (cnt < sampled_pts_num) {\n    // duplicate same points for sampling\n    for (int k = cnt; k < sampled_pts_num; k++) {\n      int duplicate_idx = k % cnt;\n      int base_offset =\n          bs_idx * boxes_num * sampled_pts_num + boxes_idx * sampled_pts_num;\n      pts_idx[base_offset + k] = pts_idx[base_offset + duplicate_idx];\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void roipoint_pool3d_forward(\n    int batch_size, int pts_num, int boxes_num, int feature_in_len,\n    int sampled_pts_num, const T *xyz, const int *pts_idx, const T *pts_feature,\n    T *pooled_features, int *pooled_empty_flag) {\n  // params xyz: (B, N, 3)\n  // params pts_idx: (B, M, 512)\n  // params pts_feature: (B, N, C)\n  // params pooled_features: (B, M, 512, 3+C)\n  // params pooled_empty_flag: (B, M)\n\n  int sample_pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  int box_idx = blockIdx.y;\n  int bs_idx = blockIdx.z;\n\n  if (sample_pt_idx >= sampled_pts_num || box_idx >= boxes_num ||\n      bs_idx >= batch_size) {\n    return;\n  }\n\n  if (pooled_empty_flag[bs_idx * boxes_num + box_idx]) {\n    return;\n  }\n\n  int temp_idx = bs_idx * boxes_num * sampled_pts_num +\n                 box_idx * sampled_pts_num + sample_pt_idx;\n  int src_pt_idx = pts_idx[temp_idx];\n  int dst_feature_offset = temp_idx * (3 + feature_in_len);\n\n  for (int j = 0; j < 3; j++)\n    pooled_features[dst_feature_offset + j] =\n        xyz[bs_idx * pts_num * 3 + src_pt_idx * 3 + j];\n\n  int src_feature_offset =\n      bs_idx * pts_num * feature_in_len + src_pt_idx * feature_in_len;\n  memcpy(pooled_features + dst_feature_offset + 3,\n         pts_feature + src_feature_offset, feature_in_len * sizeof(T));\n}\n\n#endif  // ROIPOINT_POOL3D_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/scatter_points_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef SCATTER_POINTS_CUDA_KERNEL_CUH\n#define SCATTER_POINTS_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntypedef enum { SUM = 0, MEAN = 1, MAX = 2 } reduce_t;\nint const maxGridDim = 50000;\n\n__device__ __forceinline__ static void reduceMax(float *address, float val) {\n  int *address_as_i = reinterpret_cast<int *>(address);\n  int old = *address_as_i, assumed;\n  do {\n    assumed = old;\n    old = atomicCAS(address_as_i, assumed,\n                    __float_as_int(fmaxf(val, __int_as_float(assumed))));\n  } while (assumed != old || __int_as_float(old) < val);\n}\n\n__device__ __forceinline__ static void reduceMax(double *address, double val) {\n  unsigned long long *address_as_ull =\n      reinterpret_cast<unsigned long long *>(address);\n  unsigned long long old = *address_as_ull, assumed;\n  do {\n    assumed = old;\n    old = atomicCAS(\n        address_as_ull, assumed,\n        __double_as_longlong(fmax(val, __longlong_as_double(assumed))));\n  } while (assumed != old || __longlong_as_double(old) < val);\n}\n\n// get rid of meaningless warnings when compiling host code\n#ifdef HIP_DIFF\n__device__ __forceinline__ static void reduceAdd(float *address, float val) {\n  atomicAdd(address, val);\n}\n__device__ __forceinline__ static void reduceAdd(double *address, double val) {\n  atomicAdd(address, val);\n}\n#else\n#ifdef __CUDA_ARCH__\n__device__ __forceinline__ static void reduceAdd(float *address, float val) {\n#if (__CUDA_ARCH__ < 200)\n#ifdef _MSC_VER\n#pragma message( \\\n    \"compute capability lower than 2.x. fall back to use CAS version of atomicAdd for float32\")\n#else\n#warning \\\n    \"compute capability lower than 2.x. fall back to use CAS version of atomicAdd for float32\"\n#endif\n  int *address_as_i = reinterpret_cast<int *>(address);\n  int old = *address_as_i, assumed;\n  do {\n    assumed = old;\n    old = atomicCAS(address_as_i, assumed,\n                    __float_as_int(val + __int_as_float(assumed)));\n  } while (assumed != old);\n#else\n  atomicAdd(address, val);\n#endif\n}\n\n__device__ __forceinline__ static void reduceAdd(double *address, double val) {\n#if (__CUDA_ARCH__ < 600)\n#ifdef _MSC_VER\n#pragma message( \\\n    \"compute capability lower than 6.x. fall back to use CAS version of atomicAdd for float64\")\n#else\n#warning \\\n    \"compute capability lower than 6.x. fall back to use CAS version of atomicAdd for float64\"\n#endif\n  unsigned long long *address_as_ull =\n      reinterpret_cast<unsigned long long *>(address);\n  unsigned long long old = *address_as_ull, assumed;\n  do {\n    assumed = old;\n    old = atomicCAS(address_as_ull, assumed,\n                    __double_as_longlong(val + __longlong_as_double(assumed)));\n  } while (assumed != old);\n#else\n  atomicAdd(address, val);\n#endif\n}\n#endif  // __CUDA_ARCH__\n#endif  // HIP_DIFF\n\ntemplate <typename T>\n__global__ void feats_reduce_kernel(\n    const T *feats, const int32_t *coors_map,\n    T *reduced_feats,  // shall be 0 at initialization\n    const int num_input, const int num_feats, const reduce_t reduce_type) {\n  CUDA_1D_KERNEL_LOOP(x, num_input) {\n    int32_t reduce_to = coors_map[x];\n    if (reduce_to == -1) continue;\n\n    const T *feats_offset = feats + x * num_feats;\n    T *reduced_feats_offset = reduced_feats + reduce_to * num_feats;\n    if (reduce_type == reduce_t::MAX) {\n      for (int i = 0; i < num_feats; i++) {\n        reduceMax(&reduced_feats_offset[i], feats_offset[i]);\n      }\n    } else {\n      for (int i = 0; i < num_feats; i++) {\n        reduceAdd(&reduced_feats_offset[i], feats_offset[i]);\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void add_reduce_traceback_grad_kernel(\n    T *grad_feats, const T *grad_reduced_feats, const int32_t *coors_map,\n    const int32_t *reduce_count, const int num_input, const int num_feats,\n    const reduce_t reduce_type) {\n  CUDA_1D_KERNEL_LOOP(x, num_input) {\n    int32_t reduce_to = coors_map[x];\n    if (reduce_to == -1) {\n      continue;\n    }\n\n    const int input_offset = x * num_feats;\n    T *grad_feats_offset = grad_feats + input_offset;\n    const int reduced_offset = reduce_to * num_feats;\n    const T *grad_reduced_feats_offset = grad_reduced_feats + reduced_offset;\n\n    if (reduce_type == reduce_t::SUM) {\n      for (int i = 0; i < num_feats; i++) {\n        grad_feats_offset[i] = grad_reduced_feats_offset[i];\n      }\n    } else if (reduce_type == reduce_t::MEAN) {\n      for (int i = 0; i < num_feats; i++) {\n        grad_feats_offset[i] = grad_reduced_feats_offset[i] /\n                               static_cast<T>(reduce_count[reduce_to]);\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void max_reduce_traceback_scatter_idx_kernel(\n    const T *feats, const T *reduced_feats, int32_t *reduce_from,\n    const int32_t *coors_map, const int num_input, const int num_feats) {\n  CUDA_1D_KERNEL_LOOP(x, num_input) {\n    int32_t reduce_to = coors_map[x];\n\n    const int input_offset = x * num_feats;\n    const T *feats_offset = feats + input_offset;\n\n    if (reduce_to == -1) {\n      continue;\n    }\n\n    const int reduced_offset = reduce_to * num_feats;\n    const T *reduced_feats_offset = reduced_feats + reduced_offset;\n    int32_t *reduce_from_offset = reduce_from + reduced_offset;\n\n    for (int i = 0; i < num_feats; i++) {\n      if (feats_offset[i] == reduced_feats_offset[i]) {\n        atomicMin(&reduce_from_offset[i], static_cast<int32_t>(x));\n      }\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void max_reduce_scatter_grad_kernel(T *grad_feats,\n                                               const T *grad_reduced_feats,\n                                               const int32_t *reduce_from,\n                                               const int num_reduced,\n                                               const int num_feats) {\n  CUDA_1D_KERNEL_LOOP(x, num_reduced) {\n    const int reduced_offset = x * num_feats;\n    const int32_t *scatter_to_offset = reduce_from + reduced_offset;\n    const T *grad_reduced_feats_offset = grad_reduced_feats + reduced_offset;\n\n    for (int i = 0; i < num_feats; i++) {\n      grad_feats[scatter_to_offset[i] * num_feats + i] =\n          grad_reduced_feats_offset[i];\n    }\n  }\n}\n\n#endif  // SCATTER_POINTS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/sigmoid_focal_loss_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef SIGMOID_FOCAL_LOSS_CUDA_KERNEL_CUH\n#define SIGMOID_FOCAL_LOSS_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void sigmoid_focal_loss_forward_cuda_kernel(\n    const int nthreads, const T* input, const int64_t* target, const T* weight,\n    T* output, const T gamma, const T alpha, const int num_classes) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int n = index / num_classes;\n    int c = index % num_classes;\n\n    int64_t t = target[n];\n    T flag_p = (t == c);\n    T flag_n = (t != c);\n\n    // p = sigmoid(x) = 1. / 1. + expf(-x)\n    T p = (T)1. / ((T)1. + expf(-input[index]));\n\n    // (1 - p)**gamma * log(p)\n    T term_p = pow(((T)1. - p), gamma) * log(max(p, (T)FLT_MIN));\n    // p**gamma * log(1 - p)\n    T term_n = pow(p, gamma) * log(max((T)1. - p, (T)FLT_MIN));\n\n    output[index] = (T)0.;\n    output[index] += -flag_p * alpha * term_p;\n    output[index] += -flag_n * ((T)1. - alpha) * term_n;\n    if (weight != NULL) {\n      output[index] *= weight[t];\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void sigmoid_focal_loss_backward_cuda_kernel(\n    const int nthreads, const T* input, const int64_t* target, const T* weight,\n    T* grad_input, const T gamma, const T alpha, const int num_classes) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int n = index / num_classes;\n    int c = index % num_classes;\n\n    int64_t t = target[n];\n    T flag_p = (t == c);\n    T flag_n = (t != c);\n\n    // p = sigmoid(x) = 1. / 1. + expf(-x)\n    T p = (T)1. / ((T)1. + exp(-input[index]));\n\n    // (1 - p)**gamma * (1 - p - gamma*p*log(p))\n    T term_p = pow(((T)1. - p), gamma) *\n               ((T)1. - p - (gamma * p * log(max(p, (T)FLT_MIN))));\n    // p**gamma * (gamma * (1 - p) * log(1 - p) - p)\n    T term_n = pow(p, gamma) *\n               (gamma * ((T)1. - p) * log(max((T)1. - p, (T)FLT_MIN)) - p);\n\n    grad_input[index] = (T)0.;\n    grad_input[index] += -flag_p * alpha * term_p;\n    grad_input[index] += -flag_n * ((T)1. - alpha) * term_n;\n    if (weight != NULL) {\n      grad_input[index] *= weight[t];\n    }\n  }\n}\n\n#endif  // SIGMOID_FOCAL_LOSS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/softmax_focal_loss_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef SOFTMAX_FOCAL_LOSS_CUDA_KERNEL_CUH\n#define SOFTMAX_FOCAL_LOSS_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void softmax_focal_loss_forward_cuda_kernel(\n    const int nthreads, const T* softmax, const int64_t* target,\n    const T* weight, T* output, const T gamma, const T alpha,\n    const int num_classes) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int64_t label = target[index];\n    T pred = softmax[index * num_classes + label];\n\n    if (label >= 0) {\n      output[index] =\n          -alpha * pow((T)1. - pred, gamma) * log(max(pred, (T)FLT_MIN));\n    } else {\n      output[index] = 0;\n    }\n    if (weight != NULL) {\n      output[index] *= weight[label];\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void softmax_focal_loss_backward_cuda1_kernel(\n    const int nthreads, const T* softmax, const int64_t* target,\n    const T* weight, T* buff, const T gamma, const T alpha,\n    const int num_classes) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int64_t label = target[index];\n    T pred = softmax[index * num_classes + label];\n\n    if (label >= 0) {\n      buff[index] = alpha * (-pow((T)1. - pred, gamma) +\n                             gamma * pow((T)1. - pred, gamma - 1) * pred *\n                                 log(max(pred, (T)FLT_MIN)));\n    } else {\n      buff[index] = 0;\n    }\n    if (weight != NULL) {\n      buff[index] *= weight[label];\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void softmax_focal_loss_backward_cuda2_kernel(\n    const int nthreads, const T* softmax, const int64_t* target, const T* buff,\n    T* grad_input, const int num_classes) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int n = index / num_classes;\n    int c = index % num_classes;\n    int64_t label = target[n];\n\n    if (label >= 0) {\n      T flag = (label == c ? (T)1. : (T)0.);\n      grad_input[index] = buff[n] * (flag - softmax[index]);\n    } else {\n      grad_input[index] = 0;\n    }\n  }\n}\n\n#endif  // SOFTMAX_FOCAL_LOSS_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/sync_bn_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef SYNCBN_CUDA_KERNEL_CUH\n#define SYNCBN_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void sync_bn_forward_mean_cuda_kernel(const T *input, float *mean,\n                                                 int num, int channels,\n                                                 int spatial) {\n  __shared__ float buffer[THREADS_PER_BLOCK];\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  buffer[tid] = 0;\n  for (int i = tid; i < num * spatial; i += blockDim.x) {\n    int index = (i / spatial) * channels * spatial + c * spatial + i % spatial;\n    buffer[tid] += input[index];\n  }\n  __syncthreads();\n\n  for (int s = blockDim.x / 2; s > 0; s >>= 1) {\n    if (tid < s) {\n      buffer[tid] += buffer[tid + s];\n    }\n    __syncthreads();\n  }\n  int total = num * spatial;\n  if (tid == 0) {\n    mean[c] = buffer[0] / total;\n  }\n}\n\ntemplate <>\n__global__ void sync_bn_forward_mean_cuda_kernel(const phalf *input,\n                                                 float *mean, int num,\n                                                 int channels, int spatial) {\n  __shared__ float buffer[THREADS_PER_BLOCK];\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  buffer[tid] = 0;\n  for (int i = tid; i < num * spatial; i += blockDim.x) {\n    int index = (i / spatial) * channels * spatial + c * spatial + i % spatial;\n    buffer[tid] += static_cast<float>(input[index]);\n  }\n  __syncthreads();\n\n  for (int s = blockDim.x / 2; s > 0; s >>= 1) {\n    if (tid < s) {\n      buffer[tid] += buffer[tid + s];\n    }\n    __syncthreads();\n  }\n  int total = num * spatial;\n  if (tid == 0) {\n    mean[c] = buffer[0] / total;\n  }\n}\n\ntemplate <typename T>\n__global__ void sync_bn_forward_var_cuda_kernel(const T *input,\n                                                const float *mean, float *var,\n                                                int num, int channels,\n                                                int spatial) {\n  __shared__ float buffer[THREADS_PER_BLOCK];\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  buffer[tid] = 0;\n  for (int i = tid; i < num * spatial; i += blockDim.x) {\n    int index = (i / spatial) * channels * spatial + c * spatial + i % spatial;\n    float td = input[index] - mean[c];\n    buffer[tid] += td * td;\n  }\n  __syncthreads();\n  for (int s = blockDim.x / 2; s > 0; s >>= 1) {\n    if (tid < s) {\n      buffer[tid] += buffer[tid + s];\n    }\n    __syncthreads();\n  }\n  int total = num * spatial;\n  if (tid == 0) {\n    var[c] = buffer[0] / total;\n  }\n}\n\ntemplate <>\n__global__ void sync_bn_forward_var_cuda_kernel(const phalf *input,\n                                                const float *mean, float *var,\n                                                int num, int channels,\n                                                int spatial) {\n  __shared__ float buffer[THREADS_PER_BLOCK];\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  buffer[tid] = 0;\n  for (int i = tid; i < num * spatial; i += blockDim.x) {\n    int index = (i / spatial) * channels * spatial + c * spatial + i % spatial;\n    float td = static_cast<float>(input[index]) - mean[c];\n    buffer[tid] += td * td;\n  }\n  __syncthreads();\n  for (int s = blockDim.x / 2; s > 0; s >>= 1) {\n    if (tid < s) {\n      buffer[tid] += buffer[tid + s];\n    }\n    __syncthreads();\n  }\n  int total = num * spatial;\n  if (tid == 0) {\n    var[c] = buffer[0] / total;\n  }\n}\n\ntemplate <typename T>\n__global__ void sync_bn_forward_output_cuda_kernel(\n    const T *input, const float *mean, const float *var, float *running_mean,\n    float *running_var, const float *weight, const float *bias, float *norm,\n    float *std, T *output, int num, int channels, int spatial, float eps,\n    float momentum, int group_size) {\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  float mean_value = mean[c];\n  float std_value = sqrt(var[c] + eps);\n\n  if (weight != nullptr) {\n    float weight_value = weight[c];\n    float bias_value = bias[c];\n    if (norm != nullptr) {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        norm[index] = (input[index] - mean_value) / std_value;\n        output[index] = norm[index] * weight_value + bias_value;\n      }\n    } else {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        output[index] =\n            (input[index] - mean_value) / std_value * weight_value + bias_value;\n      }\n    }\n  } else {\n    if (norm != nullptr) {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        output[index] = norm[index] = (input[index] - mean_value) / std_value;\n      }\n    } else {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        output[index] = (input[index] - mean_value) / std_value;\n      }\n    }\n  }\n  if (tid == 0) {\n    if (std != nullptr) std[c] = std_value;\n    if (running_mean != nullptr) {\n      running_mean[c] =\n          momentum * mean_value + (1 - momentum) * running_mean[c];\n      int count = num * spatial * group_size;\n      float var_unbias = count > 1 ? var[c] * count / (count - 1) : var[c];\n      running_var[c] = momentum * var_unbias + (1 - momentum) * running_var[c];\n    }\n  }\n}\n\ntemplate <>\n__global__ void sync_bn_forward_output_cuda_kernel(\n    const phalf *input, const float *mean, const float *var,\n    float *running_mean, float *running_var, const float *weight,\n    const float *bias, float *norm, float *std, phalf *output, int num,\n    int channels, int spatial, float eps, float momentum, int group_size) {\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  float mean_value = mean[c];\n  float std_value = sqrt(var[c] + eps);\n  if (weight != nullptr) {\n    float weight_value = weight[c];\n    float bias_value = bias[c];\n    if (norm != nullptr) {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        norm[index] =\n            (static_cast<float>(input[index]) - mean_value) / std_value;\n        output[index] =\n            static_cast<phalf>(norm[index] * weight_value + bias_value);\n      }\n    } else {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        output[index] =\n            static_cast<phalf>((static_cast<float>(input[index]) - mean_value) /\n                                   std_value * weight_value +\n                               bias_value);\n      }\n    }\n  } else {\n    if (norm != nullptr) {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        norm[index] =\n            (static_cast<float>(input[index]) - mean_value) / std_value;\n        output[index] = static_cast<phalf>(norm[index]);\n      }\n    } else {\n      for (int i = tid; i < num * spatial; i += blockDim.x) {\n        int index =\n            (i / spatial) * channels * spatial + c * spatial + i % spatial;\n        output[index] = static_cast<phalf>(\n            (static_cast<float>(input[index]) - mean_value) / std_value);\n      }\n    }\n  }\n  if (tid == 0) {\n    if (std != nullptr) std[c] = std_value;\n    if (running_mean != nullptr) {\n      running_mean[c] =\n          momentum * mean_value + (1 - momentum) * running_mean[c];\n      int count = num * spatial * group_size;\n      float var_unbias = count > 1 ? var[c] * count / (count - 1) : var[c];\n      running_var[c] = momentum * var_unbias + (1 - momentum) * running_var[c];\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void sync_bn_backward_param_cuda_kernel(const T *grad_output,\n                                                   const float *norm,\n                                                   float *grad_weight,\n                                                   float *grad_bias, int num,\n                                                   int channels, int spatial) {\n  __shared__ float buffer1[THREADS_PER_BLOCK];\n  __shared__ float buffer2[THREADS_PER_BLOCK];\n\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  buffer1[tid] = buffer2[tid] = 0;\n  for (int i = tid; i < num * spatial; i += blockDim.x) {\n    int index = (i / spatial) * channels * spatial + c * spatial + i % spatial;\n    buffer1[tid] += grad_output[index] * norm[index];\n    buffer2[tid] += grad_output[index];\n  }\n  __syncthreads();\n\n  for (int s = blockDim.x / 2; s > 0; s >>= 1) {\n    if (tid < s) {\n      buffer1[tid] += buffer1[tid + s];\n      buffer2[tid] += buffer2[tid + s];\n    }\n    __syncthreads();\n  }\n  if (tid == 0) {\n    grad_weight[c] = buffer1[0];\n    grad_bias[c] = buffer2[0];\n  }\n}\n\ntemplate <>\n__global__ void sync_bn_backward_param_cuda_kernel(const phalf *grad_output,\n                                                   const float *norm,\n                                                   float *grad_weight,\n                                                   float *grad_bias, int num,\n                                                   int channels, int spatial) {\n  __shared__ float buffer1[THREADS_PER_BLOCK];\n  __shared__ float buffer2[THREADS_PER_BLOCK];\n\n  int tid = threadIdx.x;\n  int c = blockIdx.x;\n  buffer1[tid] = buffer2[tid] = 0;\n  for (int i = tid; i < num * spatial; i += blockDim.x) {\n    int index = (i / spatial) * channels * spatial + c * spatial + i % spatial;\n    buffer1[tid] += static_cast<float>(grad_output[index]) * norm[index];\n    buffer2[tid] += static_cast<float>(grad_output[index]);\n  }\n  __syncthreads();\n\n  for (int s = blockDim.x / 2; s > 0; s >>= 1) {\n    if (tid < s) {\n      buffer1[tid] += buffer1[tid + s];\n      buffer2[tid] += buffer2[tid + s];\n    }\n    __syncthreads();\n  }\n  if (tid == 0) {\n    grad_weight[c] = buffer1[0];\n    grad_bias[c] = buffer2[0];\n  }\n}\n\ntemplate <typename T>\n__global__ void sync_bn_backward_data_cuda_kernel(\n    int output_size, const T *grad_output, const float *weight,\n    const float *grad_weight, const float *grad_bias, const float *norm,\n    const float *std, T *grad_input, int num, int channels, int spatial) {\n  int factor = num * spatial;\n  CUDA_1D_KERNEL_LOOP(index, output_size) {\n    int c = (index / spatial) % channels;\n    grad_input[index] =\n        weight[c] *\n        (grad_output[index] -\n         (grad_weight[c] * norm[index] + grad_bias[c]) / factor) /\n        std[c];\n  }\n}\n\ntemplate <>\n__global__ void sync_bn_backward_data_cuda_kernel(\n    int output_size, const phalf *grad_output, const float *weight,\n    const float *grad_weight, const float *grad_bias, const float *norm,\n    const float *std, phalf *grad_input, int num, int channels, int spatial) {\n  int factor = num * spatial;\n  CUDA_1D_KERNEL_LOOP(index, output_size) {\n    int c = (index / spatial) % channels;\n    grad_input[index] = static_cast<phalf>(\n        weight[c] *\n        (static_cast<float>(grad_output[index]) -\n         (grad_weight[c] * norm[index] + grad_bias[c]) / factor) /\n        std[c]);\n  }\n}\n\n#endif  // SYNCBN_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/three_interpolate_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef THREE_INTERPOLATE_CUDA_KERNEL_CUH\n#define THREE_INTERPOLATE_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void three_interpolate_forward_cuda_kernel(\n    int b, int c, int m, int n, const T *points, const int *__restrict__ idx,\n    const T *weight, T *out) {\n  // points: (B, C, M)\n  // idx: (B, N, 3)\n  // weight: (B, N, 3)\n  // output:\n  //      out: (B, C, N)\n\n  int bs_idx = blockIdx.z;\n  int c_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n\n  if (bs_idx >= b || c_idx >= c || pt_idx >= n) return;\n\n  weight += bs_idx * n * 3 + pt_idx * 3;\n  points += bs_idx * c * m + c_idx * m;\n  idx += bs_idx * n * 3 + pt_idx * 3;\n  out += bs_idx * c * n + c_idx * n;\n\n  out[pt_idx] = weight[0] * points[idx[0]] + weight[1] * points[idx[1]] +\n                weight[2] * points[idx[2]];\n}\n\ntemplate <typename T>\n__global__ void three_interpolate_backward_cuda_kernel(\n    int b, int c, int n, int m, const T *grad_out, const int *__restrict__ idx,\n    const T *weight, T *grad_points) {\n  // grad_out: (B, C, N)\n  // weight: (B, N, 3)\n  // output:\n  //      grad_points: (B, C, M)\n\n  int bs_idx = blockIdx.z;\n  int c_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n\n  if (bs_idx >= b || c_idx >= c || pt_idx >= n) return;\n\n  grad_out += bs_idx * c * n + c_idx * n + pt_idx;\n  weight += bs_idx * n * 3 + pt_idx * 3;\n  grad_points += bs_idx * c * m + c_idx * m;\n  idx += bs_idx * n * 3 + pt_idx * 3;\n\n  atomicAdd(grad_points + idx[0], grad_out[0] * weight[0]);\n  atomicAdd(grad_points + idx[1], grad_out[0] * weight[1]);\n  atomicAdd(grad_points + idx[2], grad_out[0] * weight[2]);\n}\n\n#endif  // THREE_INTERPOLATE_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/three_nn_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef THREE_NN_CUDA_KERNEL_CUH\n#define THREE_NN_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void three_nn_forward_cuda_kernel(int b, int n, int m,\n                                             const T *unknown, const T *known,\n                                             T *dist2, int *__restrict__ idx) {\n  // unknown: (B, N, 3)\n  // known: (B, M, 3)\n  // output:\n  //      dist2: (B, N, 3)\n  //      idx: (B, N, 3)\n\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= b || pt_idx >= n) return;\n\n  unknown += bs_idx * n * 3 + pt_idx * 3;\n  known += bs_idx * m * 3;\n  dist2 += bs_idx * n * 3 + pt_idx * 3;\n  idx += bs_idx * n * 3 + pt_idx * 3;\n\n  T ux = unknown[0];\n  T uy = unknown[1];\n  T uz = unknown[2];\n\n  double best1 = 1e40, best2 = 1e40, best3 = 1e40;\n  int besti1 = 0, besti2 = 0, besti3 = 0;\n  for (int k = 0; k < m; ++k) {\n    T x = known[k * 3 + 0];\n    T y = known[k * 3 + 1];\n    T z = known[k * 3 + 2];\n    T d = (ux - x) * (ux - x) + (uy - y) * (uy - y) + (uz - z) * (uz - z);\n    if (d < best1) {\n      best3 = best2;\n      besti3 = besti2;\n      best2 = best1;\n      besti2 = besti1;\n      best1 = d;\n      besti1 = k;\n    } else if (d < best2) {\n      best3 = best2;\n      besti3 = besti2;\n      best2 = d;\n      besti2 = k;\n    } else if (d < best3) {\n      best3 = d;\n      besti3 = k;\n    }\n  }\n  dist2[0] = best1;\n  dist2[1] = best2;\n  dist2[2] = best3;\n  idx[0] = besti1;\n  idx[1] = besti2;\n  idx[2] = besti3;\n}\n\n#endif  // THREE_NN_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/tin_shift_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#ifndef TIN_SHIFT_CUDA_KERNEL_CUH\n#define TIN_SHIFT_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntemplate <typename T>\n__global__ void tin_shift_forward_cuda_kernel(\n    const int nthreads, const T* input, const int* shift, T* output,\n    const int batch_size, const int channels, const int t_size,\n    const int hw_size, const int group_size, const int group_channel) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    const int hw_index = index % hw_size;\n    const int j = (index / hw_size) % channels;\n\n    const int n_index = (index / hw_size / channels) % batch_size;\n    int group_id = j / group_channel;\n    int t_shift = shift[n_index * group_size + group_id];\n    int offset = n_index * t_size * hw_size * channels + hw_size * j + hw_index;\n    for (int i = 0; i < t_size; i++) {\n      int now_t = i + t_shift;\n      int data_id = i * hw_size * channels + offset;\n      if (now_t < 0 || now_t >= t_size) {\n        continue;\n      }\n      int out_id = now_t * hw_size * channels + offset;\n      output[out_id] = input[data_id];\n    }\n  }\n}\n\ntemplate <typename T>\n__global__ void tin_shift_backward_cuda_kernel(\n    const int nthreads, const T* input, const int* shift, T* output,\n    const int batch_size, const int channels, const int t_size,\n    const int hw_size, const int group_size, const int group_channel) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    const int hw_index = index % hw_size;\n    const int j = (index / hw_size) % channels;\n\n    const int n_index = (index / hw_size / channels) % batch_size;\n    int group_id = j / group_channel;\n    int t_shift = shift[n_index * group_size + group_id];\n    int offset = n_index * t_size * hw_size * channels + hw_size * j + hw_index;\n    for (int i = 0; i < t_size; i++) {\n      int now_t = i + t_shift;\n      int data_id = i * hw_size * channels + offset;\n      if (now_t < 0 || now_t >= t_size) {\n        continue;\n      }\n      int out_id = now_t * hw_size * channels + offset;\n      output[out_id] = input[data_id];\n    }\n  }\n}\n\n#endif  // TIN_SHIFT_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/cuda/voxelization_cuda_kernel.cuh",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#ifndef VOXELIZATION_CUDA_KERNEL_CUH\n#define VOXELIZATION_CUDA_KERNEL_CUH\n\n#include \"pytorch_cuda_helper.hpp\"\n\ntypedef enum { SUM = 0, MEAN = 1, MAX = 2 } reduce_t;\n\ntemplate <typename T, typename T_int>\n__global__ void dynamic_voxelize_kernel(\n    const T* points, T_int* coors, const float voxel_x, const float voxel_y,\n    const float voxel_z, const float coors_x_min, const float coors_y_min,\n    const float coors_z_min, const float coors_x_max, const float coors_y_max,\n    const float coors_z_max, const int grid_x, const int grid_y,\n    const int grid_z, const int num_points, const int num_features,\n    const int NDim) {\n  //   const int index = blockIdx.x * threadsPerBlock + threadIdx.x;\n  CUDA_1D_KERNEL_LOOP(index, num_points) {\n    // To save some computation\n    auto points_offset = points + index * num_features;\n    auto coors_offset = coors + index * NDim;\n    int c_x = floor((points_offset[0] - coors_x_min) / voxel_x);\n    if (c_x < 0 || c_x >= grid_x) {\n      coors_offset[0] = -1;\n      continue;\n    }\n\n    int c_y = floor((points_offset[1] - coors_y_min) / voxel_y);\n    if (c_y < 0 || c_y >= grid_y) {\n      coors_offset[0] = -1;\n      coors_offset[1] = -1;\n      continue;\n    }\n\n    int c_z = floor((points_offset[2] - coors_z_min) / voxel_z);\n    if (c_z < 0 || c_z >= grid_z) {\n      coors_offset[0] = -1;\n      coors_offset[1] = -1;\n      coors_offset[2] = -1;\n    } else {\n      coors_offset[0] = c_z;\n      coors_offset[1] = c_y;\n      coors_offset[2] = c_x;\n    }\n  }\n}\n\ntemplate <typename T, typename T_int>\n__global__ void assign_point_to_voxel(const int nthreads, const T* points,\n                                      T_int* point_to_voxelidx,\n                                      T_int* coor_to_voxelidx, T* voxels,\n                                      const int max_points,\n                                      const int num_features,\n                                      const int num_points, const int NDim) {\n  CUDA_1D_KERNEL_LOOP(thread_idx, nthreads) {\n    // const int index = blockIdx.x * threadsPerBlock + threadIdx.x;\n    int index = thread_idx / num_features;\n\n    int num = point_to_voxelidx[index];\n    int voxelidx = coor_to_voxelidx[index];\n    if (num > -1 && voxelidx > -1) {\n      auto voxels_offset =\n          voxels + voxelidx * max_points * num_features + num * num_features;\n\n      int k = thread_idx % num_features;\n      voxels_offset[k] = points[thread_idx];\n    }\n  }\n}\n\ntemplate <typename T, typename T_int>\n__global__ void assign_voxel_coors(const int nthreads, T_int* coor,\n                                   T_int* point_to_voxelidx,\n                                   T_int* coor_to_voxelidx, T_int* voxel_coors,\n                                   const int num_points, const int NDim) {\n  CUDA_1D_KERNEL_LOOP(thread_idx, nthreads) {\n    // const int index = blockIdx.x * threadsPerBlock + threadIdx.x;\n    // if (index >= num_points) return;\n    int index = thread_idx / NDim;\n    int num = point_to_voxelidx[index];\n    int voxelidx = coor_to_voxelidx[index];\n    if (num == 0 && voxelidx > -1) {\n      auto coors_offset = voxel_coors + voxelidx * NDim;\n      int k = thread_idx % NDim;\n      coors_offset[k] = coor[thread_idx];\n    }\n  }\n}\n\ntemplate <typename T_int>\n__global__ void point_to_voxelidx_kernel(const T_int* coor,\n                                         T_int* point_to_voxelidx,\n                                         T_int* point_to_pointidx,\n                                         const int max_points,\n                                         const int max_voxels,\n                                         const int num_points, const int NDim) {\n  CUDA_1D_KERNEL_LOOP(index, num_points) {\n    auto coor_offset = coor + index * NDim;\n    // skip invalid points\n    if ((index >= num_points) || (coor_offset[0] == -1)) return;\n\n    int num = 0;\n    int coor_x = coor_offset[0];\n    int coor_y = coor_offset[1];\n    int coor_z = coor_offset[2];\n    // only calculate the coors before this coor[index]\n    for (int i = 0; i < index; ++i) {\n      auto prev_coor = coor + i * NDim;\n      if (prev_coor[0] == -1) continue;\n\n      // Find all previous points that have the same coors\n      // if find the same coor, record it\n      if ((prev_coor[0] == coor_x) && (prev_coor[1] == coor_y) &&\n          (prev_coor[2] == coor_z)) {\n        num++;\n        if (num == 1) {\n          // point to the same coor that first show up\n          point_to_pointidx[index] = i;\n        } else if (num >= max_points) {\n          // out of boundary\n          return;\n        }\n      }\n    }\n    if (num == 0) {\n      point_to_pointidx[index] = index;\n    }\n    if (num < max_points) {\n      point_to_voxelidx[index] = num;\n    }\n  }\n}\n\ntemplate <typename T_int>\n__global__ void determin_voxel_num(\n    // const T_int* coor,\n    T_int* num_points_per_voxel, T_int* point_to_voxelidx,\n    T_int* point_to_pointidx, T_int* coor_to_voxelidx, T_int* voxel_num,\n    const int max_points, const int max_voxels, const int num_points) {\n  // only calculate the coors before this coor[index]\n  for (int i = 0; i < num_points; ++i) {\n    int point_pos_in_voxel = point_to_voxelidx[i];\n    // record voxel\n    if (point_pos_in_voxel == -1) {\n      // out of max_points or invalid point\n      continue;\n    } else if (point_pos_in_voxel == 0) {\n      // record new voxel\n      int voxelidx = voxel_num[0];\n      if (voxel_num[0] >= max_voxels) continue;\n      voxel_num[0] += 1;\n      coor_to_voxelidx[i] = voxelidx;\n      num_points_per_voxel[voxelidx] = 1;\n    } else {\n      int point_idx = point_to_pointidx[i];\n      int voxelidx = coor_to_voxelidx[point_idx];\n      if (voxelidx != -1) {\n        coor_to_voxelidx[i] = voxelidx;\n        num_points_per_voxel[voxelidx] += 1;\n      }\n    }\n  }\n}\n\n#endif  // VOXELIZATION_CUDA_KERNEL_CUH\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/pytorch_cpp_helper.hpp",
    "content": "#ifndef PYTORCH_CPP_HELPER\n#define PYTORCH_CPP_HELPER\n#include <torch/extension.h>\n\n#include <vector>\n\nusing namespace at;\n\n#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))\n\n#define CHECK_CUDA(x) \\\n  TORCH_CHECK(x.device().is_cuda(), #x \" must be a CUDA tensor\")\n#define CHECK_CPU(x) \\\n  TORCH_CHECK(!x.device().is_cuda(), #x \" must be a CPU tensor\")\n#define CHECK_CONTIGUOUS(x) \\\n  TORCH_CHECK(x.is_contiguous(), #x \" must be contiguous\")\n#define CHECK_CUDA_INPUT(x) \\\n  CHECK_CUDA(x);            \\\n  CHECK_CONTIGUOUS(x)\n#define CHECK_CPU_INPUT(x) \\\n  CHECK_CPU(x);            \\\n  CHECK_CONTIGUOUS(x)\n\n#endif  // PYTORCH_CPP_HELPER\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/pytorch_cuda_helper.hpp",
    "content": "#ifndef PYTORCH_CUDA_HELPER\n#define PYTORCH_CUDA_HELPER\n\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n#include <THC/THCAtomics.cuh>\n\n#include \"common_cuda_helper.hpp\"\n\nusing at::Half;\nusing at::Tensor;\nusing phalf = at::Half;\n\n#define __PHALF(x) (x)\n\n#endif  // PYTORCH_CUDA_HELPER\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/common/pytorch_device_registry.hpp",
    "content": "#ifndef PYTORCH_DEVICE_REGISTRY_H\n#define PYTORCH_DEVICE_REGISTRY_H\n\n// Using <torch/extension.h> is recommended in the official documentation in\n// https://pytorch.org/tutorials/advanced/cpp_extension.html#writing-the-c-op.\n// However, we use <torch/types.h> for compatibility with CUDA 9.0\n// Read https://github.com/pytorch/extension-cpp/issues/35 for more details.\n#include <torch/types.h>\n\n#include <cassert>\n#include <functional>\n#include <map>\n#include <type_traits>\n\ninline std::string GetDeviceStr(const at::Device& device) {\n  std::string str = DeviceTypeName(device.type(), true);\n  if (device.has_index()) {\n    str.push_back(':');\n    str.append(std::to_string(device.index()));\n  }\n  return str;\n}\n\n// Registry\ntemplate <typename F, F f>\nclass DeviceRegistry;\n\ntemplate <typename Ret, typename... Args, Ret (*f)(Args...)>\nclass DeviceRegistry<Ret (*)(Args...), f> {\n public:\n  using FunctionType = Ret (*)(Args...);\n  static const int MAX_DEVICE_TYPES =\n      int8_t(at::DeviceType::COMPILE_TIME_MAX_DEVICE_TYPES);\n\n  void Register(at::DeviceType device, FunctionType function) {\n    funcs_[int8_t(device)] = function;\n  }\n\n  FunctionType Find(at::DeviceType device) const {\n    return funcs_[int8_t(device)];\n  }\n\n  static DeviceRegistry& instance() {\n    static DeviceRegistry inst;\n    return inst;\n  }\n\n private:\n  DeviceRegistry() {\n    for (size_t i = 0; i < MAX_DEVICE_TYPES; ++i) {\n      funcs_[i] = nullptr;\n    }\n  };\n  FunctionType funcs_[MAX_DEVICE_TYPES];\n};\n\n// get device of first tensor param\n\ntemplate <typename T, typename... Args,\n          std::enable_if_t<std::is_same<std::decay_t<T>, at::Tensor>::value,\n                           bool> = true>\nat::Device GetFirstTensorDevice(T&& t, Args&&... args) {\n  return std::forward<T>(t).device();\n}\ntemplate <typename T, typename... Args,\n          std::enable_if_t<!std::is_same<std::decay_t<T>, at::Tensor>::value,\n                           bool> = true>\nat::Device GetFirstTensorDevice(T&& t, Args&&... args) {\n  return GetFirstTensorDevice(std::forward<Args>(args)...);\n}\n\n// check device consistency\n\ninline std::pair<int, at::Device> CheckDeviceConsistency(\n    const at::Device& device, int index) {\n  return {index, device};\n}\n\ntemplate <typename T, typename... Args,\n          std::enable_if_t<!std::is_same<std::decay_t<T>, at::Tensor>::value,\n                           bool> = true>\nstd::pair<int, at::Device> CheckDeviceConsistency(const at::Device& device,\n                                                  int index, T&& t,\n                                                  Args&&... args);\n\ntemplate <typename T, typename... Args,\n          std::enable_if_t<std::is_same<std::decay_t<T>, at::Tensor>::value,\n                           bool> = true>\nstd::pair<int, at::Device> CheckDeviceConsistency(const at::Device& device,\n                                                  int index, T&& t,\n                                                  Args&&... args) {\n  auto new_device = std::forward<T>(t).device();\n  if (new_device.type() != device.type() ||\n      new_device.index() != device.index()) {\n    return {index, new_device};\n  }\n  return CheckDeviceConsistency(device, index + 1, std::forward<Args>(args)...);\n}\n\ntemplate <\n    typename T, typename... Args,\n    std::enable_if_t<!std::is_same<std::decay_t<T>, at::Tensor>::value, bool>>\nstd::pair<int, at::Device> CheckDeviceConsistency(const at::Device& device,\n                                                  int index, T&& t,\n                                                  Args&&... args) {\n  return CheckDeviceConsistency(device, index + 1, std::forward<Args>(args)...);\n}\n\n// dispatch\n\ntemplate <typename R, typename... Args>\nauto Dispatch(const R& registry, const char* name, Args&&... args) {\n  auto device = GetFirstTensorDevice(std::forward<Args>(args)...);\n  auto inconsist =\n      CheckDeviceConsistency(device, 0, std::forward<Args>(args)...);\n  TORCH_CHECK(inconsist.first >= int(sizeof...(Args)), name, \": at param \",\n              inconsist.first,\n              \", inconsistent device: \", GetDeviceStr(inconsist.second).c_str(),\n              \" vs \", GetDeviceStr(device).c_str(), \"\\n\")\n  auto f_ptr = registry.Find(device.type());\n  TORCH_CHECK(f_ptr != nullptr, name, \": implementation for device \",\n              GetDeviceStr(device).c_str(), \" not found.\\n\")\n  return f_ptr(std::forward<Args>(args)...);\n}\n\n// helper macro\n\n#define DEVICE_REGISTRY(key) DeviceRegistry<decltype(&(key)), key>::instance()\n\n#define REGISTER_DEVICE_IMPL(key, device, value)           \\\n  struct key##_##device##_registerer {                     \\\n    key##_##device##_registerer() {                        \\\n      DEVICE_REGISTRY(key).Register(at::k##device, value); \\\n    }                                                      \\\n  };                                                       \\\n  static key##_##device##_registerer _##key##_##device##_registerer;\n\n#define DISPATCH_DEVICE_IMPL(key, ...) \\\n  Dispatch(DEVICE_REGISTRY(key), #key, __VA_ARGS__)\n\n#endif  // PYTORCH_DEVICE_REGISTRY\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/assign_score_withk.cpp",
    "content": "// Modified from\n// https://github.com/CVMI-Lab/PAConv/tree/main/scene_seg/lib/paconv_lib/src/gpu\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid assign_score_withk_forward_impl(int B, int N0, int N1, int M, int K, int O,\n                                     int aggregate, const Tensor& points,\n                                     const Tensor& centers,\n                                     const Tensor& scores,\n                                     const Tensor& knn_idx, Tensor& output) {\n  DISPATCH_DEVICE_IMPL(assign_score_withk_forward_impl, B, N0, N1, M, K, O,\n                       aggregate, points, centers, scores, knn_idx, output);\n}\n\nvoid assign_score_withk_backward_impl(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& grad_out, const Tensor& points, const Tensor& centers,\n    const Tensor& scores, const Tensor& knn_idx, Tensor& grad_points,\n    Tensor& grad_centers, Tensor& grad_scores) {\n  DISPATCH_DEVICE_IMPL(assign_score_withk_backward_impl, B, N0, N1, M, K, O,\n                       aggregate, grad_out, points, centers, scores, knn_idx,\n                       grad_points, grad_centers, grad_scores);\n}\n\nvoid assign_score_withk_forward(const Tensor& points, const Tensor& centers,\n                                const Tensor& scores, const Tensor& knn_idx,\n                                Tensor& output, int B, int N0, int N1, int M,\n                                int K, int O, int aggregate) {\n  assign_score_withk_forward_impl(B, N0, N1, M, K, O, aggregate, points,\n                                  centers, scores, knn_idx, output);\n}\n\nvoid assign_score_withk_backward(const Tensor& grad_out, const Tensor& points,\n                                 const Tensor& centers, const Tensor& scores,\n                                 const Tensor& knn_idx, Tensor& grad_points,\n                                 Tensor& grad_centers, Tensor& grad_scores,\n                                 int B, int N0, int N1, int M, int K, int O,\n                                 int aggregate) {\n  assign_score_withk_backward_impl(B, N0, N1, M, K, O, aggregate, grad_out,\n                                   points, centers, scores, knn_idx,\n                                   grad_points, grad_centers, grad_scores);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/ball_query.cpp",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/ball_query.cpp\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid ball_query_forward_impl(int b, int n, int m, float min_radius,\n                             float max_radius, int nsample,\n                             const Tensor new_xyz, const Tensor xyz,\n                             Tensor idx) {\n  DISPATCH_DEVICE_IMPL(ball_query_forward_impl, b, n, m, min_radius, max_radius,\n                       nsample, new_xyz, xyz, idx);\n}\n\nvoid ball_query_forward(Tensor new_xyz_tensor, Tensor xyz_tensor,\n                        Tensor idx_tensor, int b, int n, int m,\n                        float min_radius, float max_radius, int nsample) {\n  ball_query_forward_impl(b, n, m, min_radius, max_radius, nsample,\n                          new_xyz_tensor, xyz_tensor, idx_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/bbox_overlaps.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid bbox_overlaps_impl(const Tensor bboxes1, const Tensor bboxes2, Tensor ious,\n                        const int mode, const bool aligned, const int offset) {\n  DISPATCH_DEVICE_IMPL(bbox_overlaps_impl, bboxes1, bboxes2, ious, mode,\n                       aligned, offset);\n}\n\nvoid bbox_overlaps(const Tensor bboxes1, const Tensor bboxes2, Tensor ious,\n                   const int mode, const bool aligned, const int offset) {\n  bbox_overlaps_impl(bboxes1, bboxes2, ious, mode, aligned, offset);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/border_align.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid border_align_forward_impl(const Tensor &input, const Tensor &boxes,\n                               Tensor output, Tensor argmax_idx,\n                               const int pool_size) {\n  DISPATCH_DEVICE_IMPL(border_align_forward_impl, input, boxes, output,\n                       argmax_idx, pool_size);\n}\n\nvoid border_align_backward_impl(const Tensor &grad_output, const Tensor &boxes,\n                                const Tensor &argmax_idx, Tensor grad_input,\n                                const int pool_size) {\n  DISPATCH_DEVICE_IMPL(border_align_backward_impl, grad_output, boxes,\n                       argmax_idx, grad_input, pool_size);\n}\n\nvoid border_align_forward(const Tensor &input, const Tensor &boxes,\n                          Tensor output, Tensor argmax_idx,\n                          const int pool_size) {\n  border_align_forward_impl(input, boxes, output, argmax_idx, pool_size);\n}\n\nvoid border_align_backward(const Tensor &grad_output, const Tensor &boxes,\n                           const Tensor &argmax_idx, Tensor grad_input,\n                           const int pool_size) {\n  border_align_backward_impl(grad_output, boxes, argmax_idx, grad_input,\n                             pool_size);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/box_iou_rotated.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated.h\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid box_iou_rotated_impl(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                          const int mode_flag, const bool aligned) {\n  DISPATCH_DEVICE_IMPL(box_iou_rotated_impl, boxes1, boxes2, ious, mode_flag,\n                       aligned);\n}\n\n// Interface for Python\n// inline is needed to prevent multiple function definitions when this header is\n// included by different cpps\nvoid box_iou_rotated(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                     const int mode_flag, const bool aligned) {\n  box_iou_rotated_impl(boxes1, boxes2, ious, mode_flag, aligned);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/carafe.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid carafe_forward_impl(Tensor features, Tensor masks, Tensor rfeatures,\n                         Tensor routput, Tensor rmasks, Tensor output,\n                         int kernel_size, int group_size, int scale_factor) {\n  DISPATCH_DEVICE_IMPL(carafe_forward_impl, features, masks, rfeatures, routput,\n                       rmasks, output, kernel_size, group_size, scale_factor);\n}\n\nvoid carafe_backward_impl(Tensor top_grad, Tensor rfeatures, Tensor masks,\n                          Tensor rtop_grad, Tensor rbottom_grad_hs,\n                          Tensor rbottom_grad, Tensor rmask_grad,\n                          Tensor bottom_grad, Tensor mask_grad, int kernel_size,\n                          int group_size, int scale_factor) {\n  DISPATCH_DEVICE_IMPL(carafe_backward_impl, top_grad, rfeatures, masks,\n                       rtop_grad, rbottom_grad_hs, rbottom_grad, rmask_grad,\n                       bottom_grad, mask_grad, kernel_size, group_size,\n                       scale_factor);\n}\n\nvoid carafe_forward(Tensor features, Tensor masks, Tensor rfeatures,\n                    Tensor routput, Tensor rmasks, Tensor output,\n                    int kernel_size, int group_size, int scale_factor) {\n  carafe_forward_impl(features, masks, rfeatures, routput, rmasks, output,\n                      kernel_size, group_size, scale_factor);\n}\n\nvoid carafe_backward(Tensor top_grad, Tensor rfeatures, Tensor masks,\n                     Tensor rtop_grad, Tensor rbottom_grad_hs,\n                     Tensor rbottom_grad, Tensor rmask_grad, Tensor bottom_grad,\n                     Tensor mask_grad, int kernel_size, int group_size,\n                     int scale_factor) {\n  carafe_backward_impl(top_grad, rfeatures, masks, rtop_grad, rbottom_grad_hs,\n                       rbottom_grad, rmask_grad, bottom_grad, mask_grad,\n                       kernel_size, group_size, scale_factor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/carafe_naive.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid carafe_naive_forward_impl(Tensor features, Tensor masks, Tensor output,\n                               int kernel_size, int group_size,\n                               int scale_factor) {\n  DISPATCH_DEVICE_IMPL(carafe_naive_forward_impl, features, masks, output,\n                       kernel_size, group_size, scale_factor);\n}\n\nvoid carafe_naive_backward_impl(Tensor top_grad, Tensor features, Tensor masks,\n                                Tensor bottom_grad, Tensor mask_grad,\n                                int kernel_size, int group_size,\n                                int scale_factor) {\n  DISPATCH_DEVICE_IMPL(carafe_naive_backward_impl, top_grad, features, masks,\n                       bottom_grad, mask_grad, kernel_size, group_size,\n                       scale_factor);\n}\n\nvoid carafe_naive_forward(Tensor features, Tensor masks, Tensor output,\n                          int kernel_size, int group_size, int scale_factor) {\n  carafe_naive_forward_impl(features, masks, output, kernel_size, group_size,\n                            scale_factor);\n}\n\nvoid carafe_naive_backward(Tensor top_grad, Tensor features, Tensor masks,\n                           Tensor bottom_grad, Tensor mask_grad,\n                           int kernel_size, int group_size, int scale_factor) {\n  carafe_naive_backward_impl(top_grad, features, masks, bottom_grad, mask_grad,\n                             kernel_size, group_size, scale_factor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/contour_expand.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// It is modified from https://github.com/whai362/PSENet\n#include <iostream>\n#include <queue>\n\n#include \"pytorch_cpp_helper.hpp\"\n\nusing namespace std;\n\nclass Point2d {\n public:\n  int x;\n  int y;\n\n  Point2d() : x(0), y(0) {}\n  Point2d(int _x, int _y) : x(_x), y(_y) {}\n};\n\nvoid kernel_dilate(const uint8_t *data, IntArrayRef data_shape,\n                   const int *label_map, int &label_num, int &min_area,\n                   vector<vector<int>> &text_line) {\n  std::vector<int> area(label_num + 1);\n  int kernel_num = data_shape[0];\n  int height = data_shape[1];\n  int width = data_shape[2];\n\n  for (int x = 0; x < height; ++x) {\n    for (int y = 0; y < width; ++y) {\n      int label = label_map[x * width + y];\n      if (label == 0) continue;\n      area[label] += 1;\n    }\n  }\n\n  queue<Point2d> queue, next_queue;\n  for (int x = 0; x < height; ++x) {\n    vector<int> row(width);\n    for (int y = 0; y < width; ++y) {\n      int label = label_map[x * width + y];\n      if (label == 0) continue;\n      if (area[label] < min_area) continue;\n\n      Point2d point(x, y);\n      queue.push(point);\n      row[y] = label;\n    }\n    text_line.emplace_back(row);\n  }\n\n  int dx[] = {-1, 1, 0, 0};\n  int dy[] = {0, 0, -1, 1};\n  vector<int> kernel_step(kernel_num);\n  std::for_each(kernel_step.begin(), kernel_step.end(),\n                [=](int &k) { return k * height * width; });\n\n  for (int kernel_id = kernel_num - 2; kernel_id >= 0; --kernel_id) {\n    while (!queue.empty()) {\n      Point2d point = queue.front();\n      queue.pop();\n      int x = point.x;\n      int y = point.y;\n      int label = text_line[x][y];\n\n      bool is_edge = true;\n      for (int d = 0; d < 4; ++d) {\n        int tmp_x = x + dx[d];\n        int tmp_y = y + dy[d];\n\n        if (tmp_x < 0 || tmp_x >= height) continue;\n        if (tmp_y < 0 || tmp_y >= width) continue;\n        int kernel_value = data[kernel_step[kernel_id] + tmp_x * width + tmp_y];\n        if (kernel_value == 0) continue;\n        if (text_line[tmp_x][tmp_y] > 0) continue;\n\n        Point2d point(tmp_x, tmp_y);\n        queue.push(point);\n        text_line[tmp_x][tmp_y] = label;\n        is_edge = false;\n      }\n\n      if (is_edge) {\n        next_queue.push(point);\n      }\n    }\n    swap(queue, next_queue);\n  }\n}\n\nstd::vector<std::vector<int>> contour_expand(Tensor kernel_mask,\n                                             Tensor internal_kernel_label,\n                                             int min_kernel_area,\n                                             int kernel_num) {\n  kernel_mask = kernel_mask.contiguous();\n  internal_kernel_label = internal_kernel_label.contiguous();\n  assert(kernel_mask.dim() == 3);\n  assert(internal_kernel_label.dim() == 2);\n  assert(kernel_mask.size(1) == internal_kernel_label.size(0));\n  assert(kernel_mask.size(2) == internal_kernel_label.size(1));\n  CHECK_CPU_INPUT(kernel_mask);\n  CHECK_CPU_INPUT(internal_kernel_label);\n  auto ptr_data = kernel_mask.data_ptr<uint8_t>();\n  IntArrayRef data_shape = kernel_mask.sizes();\n\n  auto data_label_map = internal_kernel_label.data_ptr<int32_t>();\n  IntArrayRef label_map_shape = internal_kernel_label.sizes();\n  vector<vector<int>> text_line;\n\n  kernel_dilate(ptr_data, data_shape, data_label_map, kernel_num,\n                min_kernel_area, text_line);\n\n  return text_line;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/corner_pool.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/princeton-vl/CornerNet-Lite/tree/master/core/models/py_utils/_cpools/src\n#include \"pytorch_cpp_helper.hpp\"\n\nTensor bottom_pool_forward(Tensor input) {\n  // Initialize output\n  Tensor output = at::zeros_like(input);\n  // Get height\n  int64_t height = input.size(2);\n  output.copy_(input);\n\n  for (int64_t ind = 1; ind < height; ind <<= 1) {\n    Tensor max_temp = at::slice(output, 2, ind, height);\n    Tensor cur_temp = at::slice(output, 2, ind, height).clone();\n    Tensor next_temp = at::slice(output, 2, 0, height - ind).clone();\n    at::max_out(max_temp, cur_temp, next_temp);\n  }\n\n  return output;\n}\n\nTensor bottom_pool_backward(Tensor input, Tensor grad_output) {\n  auto output = at::zeros_like(input);\n\n  int32_t batch = input.size(0);\n  int32_t channel = input.size(1);\n  int32_t height = input.size(2);\n  int32_t width = input.size(3);\n\n  auto max_val = torch::zeros({batch, channel, width},\n                              at::device(at::kCUDA).dtype(at::kFloat));\n  auto max_ind = torch::zeros({batch, channel, width},\n                              at::device(at::kCUDA).dtype(at::kLong));\n\n  auto input_temp = input.select(2, 0);\n  max_val.copy_(input_temp);\n\n  max_ind.fill_(0);\n\n  auto output_temp = output.select(2, 0);\n  auto grad_output_temp = grad_output.select(2, 0);\n  output_temp.copy_(grad_output_temp);\n\n  auto un_max_ind = max_ind.unsqueeze(2);\n  auto gt_mask = torch::zeros({batch, channel, width},\n                              at::device(at::kCUDA).dtype(at::kBool));\n  auto max_temp = torch::zeros({batch, channel, width},\n                               at::device(at::kCUDA).dtype(at::kFloat));\n  for (int32_t ind = 0; ind < height - 1; ++ind) {\n    input_temp = input.select(2, ind + 1);\n    at::gt_out(gt_mask, input_temp, max_val);\n\n    at::masked_select_out(max_temp, input_temp, gt_mask);\n    max_val.masked_scatter_(gt_mask, max_temp);\n    max_ind.masked_fill_(gt_mask, ind + 1);\n\n    grad_output_temp = grad_output.select(2, ind + 1).unsqueeze(2);\n    output.scatter_add_(2, un_max_ind, grad_output_temp);\n  }\n\n  return output;\n}\n\nTensor left_pool_forward(Tensor input) {\n  // Initialize output\n  Tensor output = at::zeros_like(input);\n  // Get width\n  int64_t width = input.size(3);\n  output.copy_(input);\n\n  for (int64_t ind = 1; ind < width; ind <<= 1) {\n    Tensor max_temp = at::slice(output, 3, 0, width - ind);\n    Tensor cur_temp = at::slice(output, 3, 0, width - ind).clone();\n    Tensor next_temp = at::slice(output, 3, ind, width).clone();\n    at::max_out(max_temp, cur_temp, next_temp);\n  }\n\n  return output;\n}\n\nTensor left_pool_backward(Tensor input, Tensor grad_output) {\n  auto output = at::zeros_like(input);\n\n  int32_t batch = input.size(0);\n  int32_t channel = input.size(1);\n  int32_t height = input.size(2);\n  int32_t width = input.size(3);\n\n  auto max_val = torch::zeros({batch, channel, height},\n                              at::device(at::kCUDA).dtype(at::kFloat));\n  auto max_ind = torch::zeros({batch, channel, height},\n                              at::device(at::kCUDA).dtype(at::kLong));\n\n  auto input_temp = input.select(3, width - 1);\n  max_val.copy_(input_temp);\n\n  max_ind.fill_(width - 1);\n\n  auto output_temp = output.select(3, width - 1);\n  auto grad_output_temp = grad_output.select(3, width - 1);\n  output_temp.copy_(grad_output_temp);\n\n  auto un_max_ind = max_ind.unsqueeze(3);\n  auto gt_mask = torch::zeros({batch, channel, height},\n                              at::device(at::kCUDA).dtype(at::kBool));\n  auto max_temp = torch::zeros({batch, channel, height},\n                               at::device(at::kCUDA).dtype(at::kFloat));\n  for (int32_t ind = 1; ind < width; ++ind) {\n    input_temp = input.select(3, width - ind - 1);\n    at::gt_out(gt_mask, input_temp, max_val);\n\n    at::masked_select_out(max_temp, input_temp, gt_mask);\n    max_val.masked_scatter_(gt_mask, max_temp);\n    max_ind.masked_fill_(gt_mask, width - ind - 1);\n\n    grad_output_temp = grad_output.select(3, width - ind - 1).unsqueeze(3);\n    output.scatter_add_(3, un_max_ind, grad_output_temp);\n  }\n\n  return output;\n}\n\nTensor right_pool_forward(Tensor input) {\n  // Initialize output\n  Tensor output = at::zeros_like(input);\n  // Get width\n  int64_t width = input.size(3);\n  output.copy_(input);\n\n  for (int64_t ind = 1; ind < width; ind <<= 1) {\n    Tensor max_temp = at::slice(output, 3, ind, width);\n    Tensor cur_temp = at::slice(output, 3, ind, width).clone();\n    Tensor next_temp = at::slice(output, 3, 0, width - ind).clone();\n    at::max_out(max_temp, cur_temp, next_temp);\n  }\n\n  return output;\n}\n\nTensor right_pool_backward(Tensor input, Tensor grad_output) {\n  Tensor output = at::zeros_like(input);\n\n  int32_t batch = input.size(0);\n  int32_t channel = input.size(1);\n  int32_t height = input.size(2);\n  int32_t width = input.size(3);\n\n  auto max_val = torch::zeros({batch, channel, height},\n                              at::device(at::kCUDA).dtype(at::kFloat));\n  auto max_ind = torch::zeros({batch, channel, height},\n                              at::device(at::kCUDA).dtype(at::kLong));\n\n  auto input_temp = input.select(3, 0);\n  max_val.copy_(input_temp);\n\n  max_ind.fill_(0);\n\n  auto output_temp = output.select(3, 0);\n  auto grad_output_temp = grad_output.select(3, 0);\n  output_temp.copy_(grad_output_temp);\n\n  auto un_max_ind = max_ind.unsqueeze(3);\n  auto gt_mask = torch::zeros({batch, channel, height},\n                              at::device(at::kCUDA).dtype(at::kBool));\n  auto max_temp = torch::zeros({batch, channel, height},\n                               at::device(at::kCUDA).dtype(at::kFloat));\n  for (int32_t ind = 0; ind < width - 1; ++ind) {\n    input_temp = input.select(3, ind + 1);\n    at::gt_out(gt_mask, input_temp, max_val);\n\n    at::masked_select_out(max_temp, input_temp, gt_mask);\n    max_val.masked_scatter_(gt_mask, max_temp);\n    max_ind.masked_fill_(gt_mask, ind + 1);\n\n    grad_output_temp = grad_output.select(3, ind + 1).unsqueeze(3);\n    output.scatter_add_(3, un_max_ind, grad_output_temp);\n  }\n\n  return output;\n}\n\nTensor top_pool_forward(Tensor input) {\n  // Initialize output\n  Tensor output = at::zeros_like(input);\n  // Get height\n  int64_t height = input.size(2);\n  output.copy_(input);\n\n  for (int64_t ind = 1; ind < height; ind <<= 1) {\n    Tensor max_temp = at::slice(output, 2, 0, height - ind);\n    Tensor cur_temp = at::slice(output, 2, 0, height - ind).clone();\n    Tensor next_temp = at::slice(output, 2, ind, height).clone();\n    at::max_out(max_temp, cur_temp, next_temp);\n  }\n\n  return output;\n}\n\nTensor top_pool_backward(Tensor input, Tensor grad_output) {\n  auto output = at::zeros_like(input);\n\n  int32_t batch = input.size(0);\n  int32_t channel = input.size(1);\n  int32_t height = input.size(2);\n  int32_t width = input.size(3);\n\n  auto max_val = torch::zeros({batch, channel, width},\n                              at::device(at::kCUDA).dtype(at::kFloat));\n  auto max_ind = torch::zeros({batch, channel, width},\n                              at::device(at::kCUDA).dtype(at::kLong));\n\n  auto input_temp = input.select(2, height - 1);\n  max_val.copy_(input_temp);\n\n  max_ind.fill_(height - 1);\n\n  auto output_temp = output.select(2, height - 1);\n  auto grad_output_temp = grad_output.select(2, height - 1);\n  output_temp.copy_(grad_output_temp);\n\n  auto un_max_ind = max_ind.unsqueeze(2);\n  auto gt_mask = torch::zeros({batch, channel, width},\n                              at::device(at::kCUDA).dtype(at::kBool));\n  auto max_temp = torch::zeros({batch, channel, width},\n                               at::device(at::kCUDA).dtype(at::kFloat));\n  for (int32_t ind = 1; ind < height; ++ind) {\n    input_temp = input.select(2, height - ind - 1);\n    at::gt_out(gt_mask, input_temp, max_val);\n\n    at::masked_select_out(max_temp, input_temp, gt_mask);\n    max_val.masked_scatter_(gt_mask, max_temp);\n    max_ind.masked_fill_(gt_mask, height - ind - 1);\n\n    grad_output_temp = grad_output.select(2, height - ind - 1).unsqueeze(2);\n    output.scatter_add_(2, un_max_ind, grad_output_temp);\n  }\n\n  return output;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/correlation.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#include <iostream>\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid correlation_forward_impl(Tensor input1, Tensor input2, Tensor output,\n                              int kH, int kW, int patchH, int patchW, int padH,\n                              int padW, int dilationH, int dilationW,\n                              int dilation_patchH, int dilation_patchW, int dH,\n                              int dW) {\n  DISPATCH_DEVICE_IMPL(correlation_forward_impl, input1, input2, output, kH, kW,\n                       patchH, patchW, padH, padW, dilationH, dilationW,\n                       dilation_patchH, dilation_patchW, dH, dW);\n}\n\nvoid correlation_backward_impl(Tensor grad_output, Tensor input1, Tensor input2,\n                               Tensor grad_input1, Tensor grad_input2, int kH,\n                               int kW, int patchH, int patchW, int padH,\n                               int padW, int dilationH, int dilationW,\n                               int dilation_patchH, int dilation_patchW, int dH,\n                               int dW) {\n  DISPATCH_DEVICE_IMPL(correlation_backward_impl, grad_output, input1, input2,\n                       grad_input1, grad_input2, kH, kW, patchH, patchW, padH,\n                       padW, dilationH, dilationW, dilation_patchH,\n                       dilation_patchW, dH, dW);\n}\n\nvoid correlation_forward(Tensor input1, Tensor input2, Tensor output, int kH,\n                         int kW, int patchH, int patchW, int padH, int padW,\n                         int dilationH, int dilationW, int dilation_patchH,\n                         int dilation_patchW, int dH, int dW) {\n  correlation_forward_impl(input1, input2, output, kH, kW, patchH, patchW, padH,\n                           padW, dilationH, dilationW, dilation_patchH,\n                           dilation_patchW, dH, dW);\n}\n\nvoid correlation_backward(Tensor grad_output, Tensor input1, Tensor input2,\n                          Tensor grad_input1, Tensor grad_input2, int kH,\n                          int kW, int patchH, int patchW, int padH, int padW,\n                          int dilationH, int dilationW, int dilation_patchH,\n                          int dilation_patchW, int dH, int dW) {\n  correlation_backward_impl(grad_output, input1, input2, grad_input1,\n                            grad_input2, kH, kW, patchH, patchW, padH, padW,\n                            dilationH, dilationW, dilation_patchH,\n                            dilation_patchW, dH, dW);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/box_iou_rotated.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_cpu.cpp\n#include \"box_iou_rotated_utils.hpp\"\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntemplate <typename T>\nvoid box_iou_rotated_cpu_kernel(const Tensor boxes1, const Tensor boxes2,\n                                Tensor ious, const int mode_flag,\n                                const bool aligned) {\n  int output_size = ious.numel();\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n\n  if (aligned) {\n    for (int i = 0; i < output_size; i++) {\n      ious[i] = single_box_iou_rotated<T>(boxes1[i].data_ptr<T>(),\n                                          boxes2[i].data_ptr<T>(), mode_flag);\n    }\n  } else {\n    for (int i = 0; i < num_boxes1; i++) {\n      for (int j = 0; j < num_boxes2; j++) {\n        ious[i * num_boxes2 + j] = single_box_iou_rotated<T>(\n            boxes1[i].data_ptr<T>(), boxes2[j].data_ptr<T>(), mode_flag);\n      }\n    }\n  }\n}\n\nvoid box_iou_rotated_cpu(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                         const int mode_flag, const bool aligned) {\n  box_iou_rotated_cpu_kernel<float>(boxes1, boxes2, ious, mode_flag, aligned);\n}\n\nvoid box_iou_rotated_impl(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                          const int mode_flag, const bool aligned);\nREGISTER_DEVICE_IMPL(box_iou_rotated_impl, CPU, box_iou_rotated_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/deform_conv.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntemplate <typename T>\nT deformable_im2col_bilinear_cpu(const T *input, const int data_width,\n                                 const int height, const int width, T h, T w) {\n  if (h <= -1 || height <= h || w <= -1 || width <= w) {\n    return 0;\n  }\n\n  int h_low = floor(h);\n  int w_low = floor(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  T lh = h - h_low;\n  T lw = w - w_low;\n  T hh = 1 - lh, hw = 1 - lw;\n\n  T v1 = 0;\n  if (h_low >= 0 && w_low >= 0) v1 = input[h_low * data_width + w_low];\n  T v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = input[h_low * data_width + w_high];\n  T v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = input[h_high * data_width + w_low];\n  T v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = input[h_high * data_width + w_high];\n\n  T w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename T>\nT get_gradient_weight_cpu(T argmax_h, T argmax_w, const int h, const int w,\n                          const int height, const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename T>\nT get_coordinate_weight_cpu(T argmax_h, T argmax_w, const int height,\n                            const int width, const T *im_data,\n                            const int data_width, const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename T>\nvoid deformable_im2col_cpu_kernel(\n    const int n, const T *data_im, const T *data_offset, const int height,\n    const int width, const int kernel_h, const int kernel_w, const int pad_h,\n    const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int num_channels, const int deformable_group, const int height_col,\n    const int width_col, T *data_col) {\n  for (int index = 0; index < n; index++) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n    T *data_col_ptr =\n        data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    const T *data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const T *data_offset_ptr =\n        data_offset + (b_col * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const T offset_h = data_offset_ptr[data_offset_h_ptr];\n        const T offset_w = data_offset_ptr[data_offset_w_ptr];\n        T val = static_cast<T>(0);\n        const T h_im = h_in + i * dilation_h + offset_h;\n        const T w_im = w_in + j * dilation_w + offset_w;\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width)\n          val = deformable_im2col_bilinear_cpu(data_im_ptr, width, height,\n                                               width, h_im, w_im);\n        *data_col_ptr = val;\n        data_col_ptr += batch_size * height_col * width_col;\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid deformable_col2im_cpu_kernel(\n    const int n, const T *data_col, const T *data_offset, const int channels,\n    const int height, const int width, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int deformable_group, const int height_col, const int width_col,\n    T *grad_im) {\n  for (int index = 0; index < n; index++) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const T offset_h = data_offset_ptr[data_offset_h_ptr];\n    const T offset_w = data_offset_ptr[data_offset_w_ptr];\n    const T cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const T cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const T cur_top_grad = data_col[index];\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          T weight =\n              get_gradient_weight_cpu(cur_inv_h_data, cur_inv_w_data,\n                                      cur_h + dy, cur_w + dx, height, width);\n          *(grad_im + cur_bottom_grad_pos) += weight * cur_top_grad;\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid deformable_col2im_coord_cpu_kernel(\n    const int n, const T *data_col, const T *data_im, const T *data_offset,\n    const int channels, const int height, const int width, const int kernel_h,\n    const int kernel_w, const int pad_h, const int pad_w, const int stride_h,\n    const int stride_w, const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int offset_channels, const int deformable_group, const int height_col,\n    const int width_col, T *grad_offset) {\n  for (int index = 0; index < n; index++) {\n    T val = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const T *data_col_ptr = data_col + deformable_group_index *\n                                           channel_per_deformable_group *\n                                           batch_size * width_col * height_col;\n    const T *data_im_ptr =\n        data_im + (b * deformable_group + deformable_group_index) *\n                      channel_per_deformable_group / kernel_h / kernel_w *\n                      height * width;\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const T offset_h = data_offset_ptr[data_offset_h_ptr];\n      const T offset_w = data_offset_ptr[data_offset_w_ptr];\n      T inv_h = h_in + i * dilation_h + offset_h;\n      T inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width)\n        inv_h = inv_w = -2;\n      const T weight = get_coordinate_weight_cpu(\n          inv_h, inv_w, height, width, data_im_ptr + cnt * height * width,\n          width, bp_dir);\n      val += weight * data_col_ptr[col_pos];\n      cnt += 1;\n    }\n\n    grad_offset[index] = val;\n  }\n}\n\nvoid deformable_im2col_cpu(Tensor data_im, Tensor data_offset,\n                           const int channels, const int height,\n                           const int width, const int ksize_h,\n                           const int ksize_w, const int pad_h, const int pad_w,\n                           const int stride_h, const int stride_w,\n                           const int dilation_h, const int dilation_w,\n                           const int parallel_imgs, const int deformable_group,\n                           Tensor data_col) {\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = channels * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"deformable_im2col_cpu\", [&] {\n        deformable_im2col_cpu_kernel<scalar_t>(\n            num_kernels, data_im.data_ptr<scalar_t>(),\n            data_offset.data_ptr<scalar_t>(), height, width, ksize_h, ksize_w,\n            pad_h, pad_w, stride_h, stride_w, dilation_h, dilation_w,\n            channel_per_deformable_group, parallel_imgs, channels,\n            deformable_group, height_col, width_col,\n            data_col.data_ptr<scalar_t>());\n      });\n}\n\nvoid deformable_col2im_cpu(Tensor data_col, Tensor data_offset,\n                           const int channels, const int height,\n                           const int width, const int ksize_h,\n                           const int ksize_w, const int pad_h, const int pad_w,\n                           const int stride_h, const int stride_w,\n                           const int dilation_h, const int dilation_w,\n                           const int parallel_imgs, const int deformable_group,\n                           Tensor grad_im) {\n  // todo: make sure parallel_imgs is passed in correctly\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels =\n      channels * ksize_h * ksize_w * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_gpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t *grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        deformable_col2im_cpu_kernel<scalar_t>(\n            num_kernels, data_col_, data_offset_, channels, height, width,\n            ksize_h, ksize_w, pad_h, pad_w, stride_h, stride_w, dilation_h,\n            dilation_w, channel_per_deformable_group, parallel_imgs,\n            deformable_group, height_col, width_col, grad_im_);\n      }));\n}\n\nvoid deformable_col2im_coord_cpu(\n    Tensor data_col, Tensor data_im, Tensor data_offset, const int channels,\n    const int height, const int width, const int ksize_h, const int ksize_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int parallel_imgs,\n    const int deformable_group, Tensor grad_offset) {\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = height_col * width_col * 2 * ksize_h * ksize_w *\n                    deformable_group * parallel_imgs;\n  int channel_per_deformable_group =\n      channels * ksize_h * ksize_w / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_coord_cpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t *grad_offset_ = grad_offset.data_ptr<scalar_t>();\n\n        deformable_col2im_coord_cpu_kernel<scalar_t>(\n            num_kernels, data_col_, data_im_, data_offset_, channels, height,\n            width, ksize_h, ksize_w, pad_h, pad_w, stride_h, stride_w,\n            dilation_h, dilation_w, channel_per_deformable_group, parallel_imgs,\n            2 * ksize_h * ksize_w * deformable_group, deformable_group,\n            height_col, width_col, grad_offset_);\n      }));\n}\n\nvoid deformable_im2col_impl(Tensor data_im, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor data_col);\n\nvoid deformable_col2im_impl(Tensor data_col, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor grad_im);\n\nvoid deformable_col2im_coord_impl(\n    Tensor data_col, Tensor data_im, Tensor data_offset, const int channels,\n    const int height, const int width, const int ksize_h, const int ksize_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int parallel_imgs,\n    const int deformable_group, Tensor grad_offset);\n\nREGISTER_DEVICE_IMPL(deformable_im2col_impl, CPU, deformable_im2col_cpu);\nREGISTER_DEVICE_IMPL(deformable_col2im_impl, CPU, deformable_col2im_cpu);\nREGISTER_DEVICE_IMPL(deformable_col2im_coord_impl, CPU,\n                     deformable_col2im_coord_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/modulated_deform_conv.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntemplate <typename T>\nT dmcn_im2col_bilinear_cpu(const T *input, const int data_width,\n                           const int height, const int width, T h, T w) {\n  int h_low = floorf(h);\n  int w_low = floorf(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  T lh = h - h_low;\n  T lw = w - w_low;\n  T hh = 1 - lh, hw = 1 - lw;\n\n  T v1 = 0;\n  if (h_low >= 0 && w_low >= 0) v1 = input[h_low * data_width + w_low];\n  T v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = input[h_low * data_width + w_high];\n  T v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = input[h_high * data_width + w_low];\n  T v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = input[h_high * data_width + w_high];\n\n  T w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename T>\nT dmcn_get_gradient_weight_cpu(T argmax_h, T argmax_w, const int h, const int w,\n                               const int height, const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floorf(argmax_h);\n  int argmax_w_low = floorf(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename T>\nT dmcn_get_coordinate_weight_cpu(T argmax_h, T argmax_w, const int height,\n                                 const int width, const T *im_data,\n                                 const int data_width, const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floorf(argmax_h);\n  int argmax_w_low = floorf(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  T weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n                im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n                im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename T>\nvoid modulated_deformable_im2col_cpu_kernel(\n    const int n, const T *data_im, const T *data_offset, const T *data_mask,\n    const int height, const int width, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int num_channels, const int deformable_group, const int height_col,\n    const int width_col, T *data_col) {\n  for (int index = 0; index < n; index++) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n\n    T *data_col_ptr =\n        data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    const T *data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const T *data_offset_ptr =\n        data_offset + (b_col * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n\n    const T *data_mask_ptr =\n        data_mask + (b_col * deformable_group + deformable_group_index) *\n                        kernel_h * kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const int data_mask_hw_ptr =\n            ((i * kernel_w + j) * height_col + h_col) * width_col + w_col;\n        const T offset_h = data_offset_ptr[data_offset_h_ptr];\n        const T offset_w = data_offset_ptr[data_offset_w_ptr];\n        const T mask = data_mask_ptr[data_mask_hw_ptr];\n        T val = static_cast<T>(0);\n        const T h_im = h_in + i * dilation_h + offset_h;\n        const T w_im = w_in + j * dilation_w + offset_w;\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width)\n          val = dmcn_im2col_bilinear_cpu(data_im_ptr, width, height, width,\n                                         h_im, w_im);\n        *data_col_ptr = val * mask;\n        data_col_ptr += batch_size * height_col * width_col;\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid modulated_deformable_col2im_cpu_kernel(\n    const int n, const T *data_col, const T *data_offset, const T *data_mask,\n    const int channels, const int height, const int width, const int kernel_h,\n    const int kernel_w, const int pad_h, const int pad_w, const int stride_h,\n    const int stride_w, const int dilation_h, const int dilation_w,\n    const int channel_per_deformable_group, const int batch_size,\n    const int deformable_group, const int height_col, const int width_col,\n    T *grad_im) {\n  for (int index = 0; index < n; index++) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n    const T *data_mask_ptr =\n        data_mask + (b * deformable_group + deformable_group_index) * kernel_h *\n                        kernel_w * height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const int data_mask_hw_ptr =\n        ((i * kernel_w + j) * height_col + h_out) * width_col + w_out;\n    const T offset_h = data_offset_ptr[data_offset_h_ptr];\n    const T offset_w = data_offset_ptr[data_offset_w_ptr];\n    const T mask = data_mask_ptr[data_mask_hw_ptr];\n    const T cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const T cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const T cur_top_grad = data_col[index] * mask;\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          T weight = dmcn_get_gradient_weight_cpu(cur_inv_h_data,\n                                                  cur_inv_w_data, cur_h + dy,\n                                                  cur_w + dx, height, width);\n          *(grad_im + cur_bottom_grad_pos) += weight * cur_top_grad;\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid modulated_deformable_col2im_coord_cpu_kernel(\n    const int n, const T *data_col, const T *data_im, const T *data_offset,\n    const T *data_mask, const int channels, const int height, const int width,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int channel_per_deformable_group,\n    const int batch_size, const int offset_channels, const int deformable_group,\n    const int height_col, const int width_col, T *grad_offset, T *grad_mask) {\n  for (int index = 0; index < n; index++) {\n    T val = 0, mval = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const T *data_col_ptr = data_col + deformable_group_index *\n                                           channel_per_deformable_group *\n                                           batch_size * width_col * height_col;\n    const T *data_im_ptr =\n        data_im + (b * deformable_group + deformable_group_index) *\n                      channel_per_deformable_group / kernel_h / kernel_w *\n                      height * width;\n    const T *data_offset_ptr =\n        data_offset + (b * deformable_group + deformable_group_index) * 2 *\n                          kernel_h * kernel_w * height_col * width_col;\n    const T *data_mask_ptr =\n        data_mask + (b * deformable_group + deformable_group_index) * kernel_h *\n                        kernel_w * height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const int data_mask_hw_ptr =\n          (((i * kernel_w + j) * height_col + h_out) * width_col + w_out);\n      const T offset_h = data_offset_ptr[data_offset_h_ptr];\n      const T offset_w = data_offset_ptr[data_offset_w_ptr];\n      const T mask = data_mask_ptr[data_mask_hw_ptr];\n      T inv_h = h_in + i * dilation_h + offset_h;\n      T inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width)\n        inv_h = inv_w = -2;\n      else\n        mval += data_col_ptr[col_pos] *\n                dmcn_im2col_bilinear_cpu(data_im_ptr + cnt * height * width,\n                                         width, height, width, inv_h, inv_w);\n      const T weight = dmcn_get_coordinate_weight_cpu(\n          inv_h, inv_w, height, width, data_im_ptr + cnt * height * width,\n          width, bp_dir);\n      val += weight * data_col_ptr[col_pos] * mask;\n      cnt += 1;\n    }\n    // KERNEL_ASSIGN(grad_offset[index], offset_req, val);\n    grad_offset[index] = val;\n    if (offset_c % 2 == 0)\n      // KERNEL_ASSIGN(grad_mask[(((b * deformable_group +\n      // deformable_group_index) * kernel_h * kernel_w + offset_c / 2) *\n      // height_col + h) * width_col + w], mask_req, mval);\n      grad_mask[(((b * deformable_group + deformable_group_index) * kernel_h *\n                      kernel_w +\n                  offset_c / 2) *\n                     height_col +\n                 h) *\n                    width_col +\n                w] = mval;\n  }\n}\n\nvoid modulated_deformable_im2col_cpu(\n    const Tensor data_im, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor data_col) {\n  // num_axes should be smaller than block size\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels = channels * batch_size * height_col * width_col;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"modulated_deformable_im2col_cpu\", ([&] {\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t *data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n\n        modulated_deformable_im2col_cpu_kernel(\n            num_kernels, data_im_, data_offset_, data_mask_, height_im,\n            width_im, kernel_h, kernel_w, pad_h, pad_w, stride_h, stride_w,\n            dilation_h, dilation_w, channel_per_deformable_group, batch_size,\n            channels, deformable_group, height_col, width_col, data_col_);\n      }));\n}\n\nvoid modulated_deformable_col2im_cpu(\n    const Tensor data_col, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor grad_im) {\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels =\n      channels * kernel_h * kernel_w * batch_size * height_col * width_col;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_cpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t *data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t *grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_cpu_kernel(\n            num_kernels, data_col_, data_offset_, data_mask_, channels,\n            height_im, width_im, kernel_h, kernel_w, pad_h, pad_w, stride_h,\n            stride_w, dilation_h, dilation_w, channel_per_deformable_group,\n            batch_size, deformable_group, height_col, width_col, grad_im_);\n      }));\n}\n\nvoid modulated_deformable_col2im_coord_cpu(\n    const Tensor data_col, const Tensor data_im, const Tensor data_offset,\n    const Tensor data_mask, const int batch_size, const int channels,\n    const int height_im, const int width_im, const int height_col,\n    const int width_col, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int deformable_group,\n    Tensor grad_offset, Tensor grad_mask) {\n  const int num_kernels = batch_size * height_col * width_col * 2 * kernel_h *\n                          kernel_w * deformable_group;\n  const int channel_per_deformable_group =\n      channels * kernel_h * kernel_w / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_coord_cpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t *data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t *grad_offset_ = grad_offset.data_ptr<scalar_t>();\n        scalar_t *grad_mask_ = grad_mask.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_coord_cpu_kernel(\n            num_kernels, data_col_, data_im_, data_offset_, data_mask_,\n            channels, height_im, width_im, kernel_h, kernel_w, pad_h, pad_w,\n            stride_h, stride_w, dilation_h, dilation_w,\n            channel_per_deformable_group, batch_size,\n            2 * kernel_h * kernel_w * deformable_group, deformable_group,\n            height_col, width_col, grad_offset_, grad_mask_);\n      }));\n}\n\nvoid modulated_deformable_im2col_impl(\n    const Tensor data_im, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor data_col);\n\nvoid modulated_deformable_col2im_impl(\n    const Tensor data_col, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor grad_im);\n\nvoid modulated_deformable_col2im_coord_impl(\n    const Tensor data_col, const Tensor data_im, const Tensor data_offset,\n    const Tensor data_mask, const int batch_size, const int channels,\n    const int height_im, const int width_im, const int height_col,\n    const int width_col, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int deformable_group,\n    Tensor grad_offset, Tensor grad_mask);\n\nREGISTER_DEVICE_IMPL(modulated_deformable_im2col_impl, CPU,\n                     modulated_deformable_im2col_cpu);\nREGISTER_DEVICE_IMPL(modulated_deformable_col2im_impl, CPU,\n                     modulated_deformable_col2im_cpu);\nREGISTER_DEVICE_IMPL(modulated_deformable_col2im_coord_impl, CPU,\n                     modulated_deformable_col2im_coord_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/nms.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nTensor nms_cpu(Tensor boxes, Tensor scores, float iou_threshold, int offset) {\n  if (boxes.numel() == 0) {\n    return at::empty({0}, boxes.options().dtype(at::kLong));\n  }\n  auto x1_t = boxes.select(1, 0).contiguous();\n  auto y1_t = boxes.select(1, 1).contiguous();\n  auto x2_t = boxes.select(1, 2).contiguous();\n  auto y2_t = boxes.select(1, 3).contiguous();\n\n  Tensor areas_t = (x2_t - x1_t + offset) * (y2_t - y1_t + offset);\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n\n  auto nboxes = boxes.size(0);\n  Tensor select_t = at::ones({nboxes}, boxes.options().dtype(at::kBool));\n\n  auto select = select_t.data_ptr<bool>();\n  auto order = order_t.data_ptr<int64_t>();\n  auto x1 = x1_t.data_ptr<float>();\n  auto y1 = y1_t.data_ptr<float>();\n  auto x2 = x2_t.data_ptr<float>();\n  auto y2 = y2_t.data_ptr<float>();\n  auto areas = areas_t.data_ptr<float>();\n\n  for (int64_t _i = 0; _i < nboxes; _i++) {\n    if (select[_i] == false) continue;\n    auto i = order[_i];\n    auto ix1 = x1[i];\n    auto iy1 = y1[i];\n    auto ix2 = x2[i];\n    auto iy2 = y2[i];\n    auto iarea = areas[i];\n\n    for (int64_t _j = _i + 1; _j < nboxes; _j++) {\n      if (select[_j] == false) continue;\n      auto j = order[_j];\n      auto xx1 = std::max(ix1, x1[j]);\n      auto yy1 = std::max(iy1, y1[j]);\n      auto xx2 = std::min(ix2, x2[j]);\n      auto yy2 = std::min(iy2, y2[j]);\n\n      auto w = std::max(0.f, xx2 - xx1 + offset);\n      auto h = std::max(0.f, yy2 - yy1 + offset);\n      auto inter = w * h;\n      auto ovr = inter / (iarea + areas[j] - inter);\n      if (ovr > iou_threshold) select[_j] = false;\n    }\n  }\n  return order_t.masked_select(select_t);\n}\n\nTensor nms_impl(Tensor boxes, Tensor scores, float iou_threshold, int offset);\nREGISTER_DEVICE_IMPL(nms_impl, CPU, nms_cpu);\n\nTensor softnms_cpu(Tensor boxes, Tensor scores, Tensor dets,\n                   float iou_threshold, float sigma, float min_score,\n                   int method, int offset) {\n  if (boxes.numel() == 0) {\n    return at::empty({0}, boxes.options().dtype(at::kLong));\n  }\n\n  auto x1_t = boxes.select(1, 0).contiguous();\n  auto y1_t = boxes.select(1, 1).contiguous();\n  auto x2_t = boxes.select(1, 2).contiguous();\n  auto y2_t = boxes.select(1, 3).contiguous();\n  auto scores_t = scores.clone();\n\n  Tensor areas_t = (x2_t - x1_t + offset) * (y2_t - y1_t + offset);\n\n  auto nboxes = boxes.size(0);\n  auto x1 = x1_t.data_ptr<float>();\n  auto y1 = y1_t.data_ptr<float>();\n  auto x2 = x2_t.data_ptr<float>();\n  auto y2 = y2_t.data_ptr<float>();\n  auto sc = scores_t.data_ptr<float>();\n  auto areas = areas_t.data_ptr<float>();\n  auto de = dets.data_ptr<float>();\n\n  int64_t pos = 0;\n  Tensor inds_t = at::arange(nboxes, boxes.options().dtype(at::kLong));\n  auto inds = inds_t.data_ptr<int64_t>();\n\n  for (int64_t i = 0; i < nboxes; i++) {\n    auto max_score = sc[i];\n    auto max_pos = i;\n\n    pos = i + 1;\n    // get max box\n    while (pos < nboxes) {\n      if (max_score < sc[pos]) {\n        max_score = sc[pos];\n        max_pos = pos;\n      }\n      pos = pos + 1;\n    }\n    // swap\n    auto ix1 = de[i * 5 + 0] = x1[max_pos];\n    auto iy1 = de[i * 5 + 1] = y1[max_pos];\n    auto ix2 = de[i * 5 + 2] = x2[max_pos];\n    auto iy2 = de[i * 5 + 3] = y2[max_pos];\n    auto iscore = de[i * 5 + 4] = sc[max_pos];\n    auto iarea = areas[max_pos];\n    auto iind = inds[max_pos];\n    x1[max_pos] = x1[i];\n    y1[max_pos] = y1[i];\n    x2[max_pos] = x2[i];\n    y2[max_pos] = y2[i];\n    sc[max_pos] = sc[i];\n    areas[max_pos] = areas[i];\n    inds[max_pos] = inds[i];\n    x1[i] = ix1;\n    y1[i] = iy1;\n    x2[i] = ix2;\n    y2[i] = iy2;\n    sc[i] = iscore;\n    areas[i] = iarea;\n    inds[i] = iind;\n\n    pos = i + 1;\n    while (pos < nboxes) {\n      auto xx1 = std::max(ix1, x1[pos]);\n      auto yy1 = std::max(iy1, y1[pos]);\n      auto xx2 = std::min(ix2, x2[pos]);\n      auto yy2 = std::min(iy2, y2[pos]);\n\n      auto w = std::max(0.f, xx2 - xx1 + offset);\n      auto h = std::max(0.f, yy2 - yy1 + offset);\n      auto inter = w * h;\n      auto ovr = inter / (iarea + areas[pos] - inter);\n\n      float weight = 1.;\n      if (method == 0) {\n        if (ovr >= iou_threshold) weight = 0;\n      } else if (method == 1) {\n        if (ovr >= iou_threshold) weight = 1 - ovr;\n      } else if (method == 2) {\n        weight = std::exp(-(ovr * ovr) / sigma);\n      }\n      sc[pos] *= weight;\n      // if box score falls below threshold, discard the box by\n      // swapping with last box update N\n      if (sc[pos] < min_score) {\n        x1[pos] = x1[nboxes - 1];\n        y1[pos] = y1[nboxes - 1];\n        x2[pos] = x2[nboxes - 1];\n        y2[pos] = y2[nboxes - 1];\n        sc[pos] = sc[nboxes - 1];\n        areas[pos] = areas[nboxes - 1];\n        inds[pos] = inds[nboxes - 1];\n        nboxes = nboxes - 1;\n        pos = pos - 1;\n      }\n      pos = pos + 1;\n    }\n  }\n  return inds_t.slice(0, 0, nboxes);\n}\n\nTensor softnms_impl(Tensor boxes, Tensor scores, Tensor dets,\n                    float iou_threshold, float sigma, float min_score,\n                    int method, int offset);\nREGISTER_DEVICE_IMPL(softnms_impl, CPU, softnms_cpu);\n\nstd::vector<std::vector<int> > nms_match_cpu(Tensor dets, float iou_threshold) {\n  auto x1_t = dets.select(1, 0).contiguous();\n  auto y1_t = dets.select(1, 1).contiguous();\n  auto x2_t = dets.select(1, 2).contiguous();\n  auto y2_t = dets.select(1, 3).contiguous();\n  auto scores = dets.select(1, 4).contiguous();\n\n  at::Tensor areas_t = (x2_t - x1_t) * (y2_t - y1_t);\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n\n  auto ndets = dets.size(0);\n  at::Tensor suppressed_t =\n      at::zeros({ndets}, dets.options().dtype(at::kByte).device(at::kCPU));\n\n  auto suppressed = suppressed_t.data_ptr<uint8_t>();\n  auto order = order_t.data_ptr<int64_t>();\n  auto x1 = x1_t.data_ptr<float>();\n  auto y1 = y1_t.data_ptr<float>();\n  auto x2 = x2_t.data_ptr<float>();\n  auto y2 = y2_t.data_ptr<float>();\n  auto areas = areas_t.data_ptr<float>();\n\n  std::vector<int> keep;\n  std::vector<std::vector<int> > matched;\n\n  for (int64_t _i = 0; _i < ndets; _i++) {\n    auto i = order[_i];\n    if (suppressed[i] == 1) continue;\n    keep.push_back(i);\n    std::vector<int> v_i;\n    auto ix1 = x1[i];\n    auto iy1 = y1[i];\n    auto ix2 = x2[i];\n    auto iy2 = y2[i];\n    auto iarea = areas[i];\n\n    for (int64_t _j = _i + 1; _j < ndets; _j++) {\n      auto j = order[_j];\n      if (suppressed[j] == 1) continue;\n      auto xx1 = std::max(ix1, x1[j]);\n      auto yy1 = std::max(iy1, y1[j]);\n      auto xx2 = std::min(ix2, x2[j]);\n      auto yy2 = std::min(iy2, y2[j]);\n\n      auto w = std::max(static_cast<float>(0), xx2 - xx1);\n      auto h = std::max(static_cast<float>(0), yy2 - yy1);\n      auto inter = w * h;\n      auto ovr = inter / (iarea + areas[j] - inter);\n      if (ovr >= iou_threshold) {\n        suppressed[j] = 1;\n        v_i.push_back(j);\n      }\n    }\n    matched.push_back(v_i);\n  }\n  for (size_t i = 0; i < keep.size(); i++)\n    matched[i].insert(matched[i].begin(), keep[i]);\n  return matched;\n}\n\nstd::vector<std::vector<int> > nms_match_impl(Tensor dets, float iou_threshold);\nREGISTER_DEVICE_IMPL(nms_match_impl, CPU, nms_match_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/nms_rotated.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/nms_rotated/nms_rotated_cpu.cpp\n#include \"box_iou_rotated_utils.hpp\"\n#include \"pytorch_cpp_helper.hpp\"\n\ntemplate <typename scalar_t>\nTensor nms_rotated_cpu_kernel(const Tensor dets, const Tensor scores,\n                              const float iou_threshold) {\n  // nms_rotated_cpu_kernel is modified from torchvision's nms_cpu_kernel,\n  // however, the code in this function is much shorter because\n  // we delegate the IoU computation for rotated boxes to\n  // the single_box_iou_rotated function in box_iou_rotated_utils.h\n  AT_ASSERTM(!dets.is_cuda(), \"dets must be a CPU tensor\");\n  AT_ASSERTM(!scores.is_cuda(), \"scores must be a CPU tensor\");\n  AT_ASSERTM(dets.scalar_type() == scores.scalar_type(),\n             \"dets should have the same type as scores\");\n\n  if (dets.numel() == 0) {\n    return at::empty({0}, dets.options().dtype(at::kLong));\n  }\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n\n  auto ndets = dets.size(0);\n  Tensor suppressed_t = at::zeros({ndets}, dets.options().dtype(at::kByte));\n  Tensor keep_t = at::zeros({ndets}, dets.options().dtype(at::kLong));\n\n  auto suppressed = suppressed_t.data_ptr<uint8_t>();\n  auto keep = keep_t.data_ptr<int64_t>();\n  auto order = order_t.data_ptr<int64_t>();\n\n  int64_t num_to_keep = 0;\n\n  for (int64_t _i = 0; _i < ndets; _i++) {\n    auto i = order[_i];\n    if (suppressed[i] == 1) {\n      continue;\n    }\n\n    keep[num_to_keep++] = i;\n\n    for (int64_t _j = _i + 1; _j < ndets; _j++) {\n      auto j = order[_j];\n      if (suppressed[j] == 1) {\n        continue;\n      }\n\n      auto ovr = single_box_iou_rotated<scalar_t>(\n          dets[i].data_ptr<scalar_t>(), dets[j].data_ptr<scalar_t>(), 0);\n      if (ovr >= iou_threshold) {\n        suppressed[j] = 1;\n      }\n    }\n  }\n  return keep_t.narrow(/*dim=*/0, /*start=*/0, /*length=*/num_to_keep);\n}\n\nTensor nms_rotated_cpu(const Tensor dets, const Tensor scores,\n                       const float iou_threshold) {\n  auto result = at::empty({0}, dets.options());\n  AT_DISPATCH_FLOATING_TYPES(dets.type(), \"nms_rotated\", [&] {\n    result = nms_rotated_cpu_kernel<scalar_t>(dets, scores, iou_threshold);\n  });\n  return result;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/pixel_group.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// It is modified from https://github.com/WenmuZhou/PAN.pytorch\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nstd::vector<std::vector<float>> estimate_confidence(int32_t* label,\n                                                    float* score, int label_num,\n                                                    int height, int width) {\n  std::vector<std::vector<float>> point_vector;\n  for (int i = 0; i < label_num; i++) {\n    std::vector<float> point;\n    point.push_back(0);\n    point.push_back(0);\n    point_vector.push_back(point);\n  }\n  for (int y = 0; y < height; y++) {\n    auto label_tmp = label + y * width;\n    auto score_tmp = score + y * width;\n    for (int x = 0; x < width; x++) {\n      auto l = label_tmp[x];\n      if (l > 0) {\n        float confidence = score_tmp[x];\n        point_vector[l].push_back(x);\n        point_vector[l].push_back(y);\n        point_vector[l][0] += confidence;\n        point_vector[l][1] += 1;\n      }\n    }\n  }\n  for (size_t l = 0; l < point_vector.size(); l++)\n    if (point_vector[l][1] > 0) {\n      point_vector[l][0] /= point_vector[l][1];\n    }\n  return point_vector;\n}\nstd::vector<std::vector<float>> pixel_group_cpu(\n    Tensor score, Tensor mask, Tensor embedding, Tensor kernel_label,\n    Tensor kernel_contour, int kernel_region_num, float dis_threshold) {\n  assert(score.dim() == 2);\n  assert(mask.dim() == 2);\n  assert(embedding_dim.dim() == 3);\n  int height = score.size(0);\n  int width = score.size(1);\n  assert(height == mask.size(0) == embedding.size(1) == kernel_label.size(1));\n  assert(width == mask.size(1) == embedding.size(2) == kernel_label.size(2));\n\n  auto threshold_square = dis_threshold * dis_threshold;\n  auto ptr_score = score.data_ptr<float>();\n  auto ptr_mask = mask.data_ptr<bool>();\n  auto ptr_kernel_contour = kernel_contour.data_ptr<uint8_t>();\n  auto ptr_embedding = embedding.data_ptr<float>();\n  auto ptr_kernel_label = kernel_label.data_ptr<int32_t>();\n  std::queue<std::tuple<int, int, int32_t>> contour_pixels;\n  auto embedding_dim = embedding.size(2);\n  std::vector<std::vector<float>> kernel_vector(\n      kernel_region_num, std::vector<float>(embedding_dim + 1, 0));\n\n  Tensor text_label;\n  text_label = kernel_label.clone();\n  auto ptr_text_label = text_label.data_ptr<int32_t>();\n\n  for (int i = 0; i < height; i++) {\n    auto ptr_embedding_tmp = ptr_embedding + i * width * embedding_dim;\n    auto ptr_kernel_label_tmp = ptr_kernel_label + i * width;\n    auto ptr_kernel_contour_tmp = ptr_kernel_contour + i * width;\n\n    for (int j = 0, k = 0; j < width && k < width * embedding_dim;\n         j++, k += embedding_dim) {\n      int32_t label = ptr_kernel_label_tmp[j];\n      if (label > 0) {\n        for (int d = 0; d < embedding_dim; d++)\n          kernel_vector[label][d] += ptr_embedding_tmp[k + d];\n        kernel_vector[label][embedding_dim] += 1;\n        // kernel pixel number\n        if (ptr_kernel_contour_tmp[j]) {\n          contour_pixels.push(std::make_tuple(i, j, label));\n        }\n      }\n    }\n  }\n  for (int i = 0; i < kernel_region_num; i++) {\n    for (int j = 0; j < embedding_dim; j++) {\n      kernel_vector[i][j] /= kernel_vector[i][embedding_dim];\n    }\n  }\n  int dx[4] = {-1, 1, 0, 0};\n  int dy[4] = {0, 0, -1, 1};\n  while (!contour_pixels.empty()) {\n    auto query_pixel = contour_pixels.front();\n    contour_pixels.pop();\n    int y = std::get<0>(query_pixel);\n    int x = std::get<1>(query_pixel);\n    int32_t l = std::get<2>(query_pixel);\n    auto kernel_cv = kernel_vector[l];\n    for (int idx = 0; idx < 4; idx++) {\n      int tmpy = y + dy[idx];\n      int tmpx = x + dx[idx];\n      auto ptr_text_label_tmp = ptr_text_label + tmpy * width;\n      if (tmpy < 0 || tmpy >= height || tmpx < 0 || tmpx >= width) continue;\n      if (!ptr_mask[tmpy * width + tmpx] || ptr_text_label_tmp[tmpx] > 0)\n        continue;\n\n      float dis = 0;\n      auto ptr_embedding_tmp = ptr_embedding + tmpy * width * embedding_dim;\n      for (size_t i = 0; i < embedding_dim; i++) {\n        dis +=\n            pow(kernel_cv[i] - ptr_embedding_tmp[tmpx * embedding_dim + i], 2);\n        // ignore further computing if dis is big enough\n        if (dis >= threshold_square) break;\n      }\n      if (dis >= threshold_square) continue;\n      contour_pixels.push(std::make_tuple(tmpy, tmpx, l));\n      ptr_text_label_tmp[tmpx] = l;\n    }\n  }\n\n  return estimate_confidence(ptr_text_label, ptr_score, kernel_region_num,\n                             height, width);\n}\nstd::vector<std::vector<float>> pixel_group_impl(\n    Tensor score, Tensor mask, Tensor embedding, Tensor kernel_label,\n    Tensor kernel_contour, int kernel_region_num, float dis_threshold);\nREGISTER_DEVICE_IMPL(pixel_group_impl, CPU, pixel_group_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/points_in_boxes.cpp",
    "content": "#include \"pytorch_cpp_helper.hpp\"\n\ninline void lidar_to_local_coords_cpu(float shift_x, float shift_y, float rz,\n                                      float &local_x, float &local_y) {\n  float cosa = cos(-rz), sina = sin(-rz);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\ninline int check_pt_in_box3d_cpu(const float *pt, const float *box3d,\n                                 float &local_x, float &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, x_size, y_size, z_size, rz) in LiDAR coordinate,\n  // cz in the bottom center\n  float x = pt[0], y = pt[1], z = pt[2];\n  float cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  float x_size = box3d[3], y_size = box3d[4], z_size = box3d[5], rz = box3d[6];\n  cz += z_size /\n        2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > z_size / 2.0) return 0;\n  lidar_to_local_coords_cpu(x - cx, y - cy, rz, local_x, local_y);\n  float in_flag = (local_x > -x_size / 2.0) & (local_x < x_size / 2.0) &\n                  (local_y > -y_size / 2.0) & (local_y < y_size / 2.0);\n  return in_flag;\n}\n\nvoid points_in_boxes_cpu_forward(Tensor boxes_tensor, Tensor pts_tensor,\n                                 Tensor pts_indices_tensor) {\n  // params boxes: (N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is the bottom center, each box DO NOT overlaps params pts:\n  // (npoints, 3) [x, y, z] in LiDAR coordinate params pts_indices: (N, npoints)\n\n  CHECK_CONTIGUOUS(boxes_tensor);\n  CHECK_CONTIGUOUS(pts_tensor);\n  CHECK_CONTIGUOUS(pts_indices_tensor);\n\n  int boxes_num = boxes_tensor.size(0);\n  int pts_num = pts_tensor.size(0);\n\n  const float *boxes = boxes_tensor.data_ptr<float>();\n  const float *pts = pts_tensor.data_ptr<float>();\n  int *pts_indices = pts_indices_tensor.data_ptr<int>();\n\n  float local_x = 0, local_y = 0;\n  for (int i = 0; i < boxes_num; i++) {\n    for (int j = 0; j < pts_num; j++) {\n      int cur_in_flag =\n          check_pt_in_box3d_cpu(pts + j * 3, boxes + i * 7, local_x, local_y);\n      pts_indices[i * pts_num + j] = cur_in_flag;\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/psamask.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/hszhao/semseg/blob/master/lib/psa/src\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\n#ifndef min\n#define min(a, b) (((a) < (b)) ? (a) : (b))\n#endif\n#ifndef max\n#define max(a, b) (((a) > (b)) ? (a) : (b))\n#endif\n\nvoid psamask_collect_forward(const int num_, const int h_feature,\n                             const int w_feature, const int h_mask,\n                             const int w_mask, const int half_h_mask,\n                             const int half_w_mask, const Tensor mask_data,\n                             Tensor buffer_data) {\n  for (int n = 0; n < num_; n++) {\n    for (int h = 0; h < h_feature; h++) {\n      for (int w = 0; w < w_feature; w++) {\n        // effective mask region : [hstart, hend) x [wstart, wend) with\n        // mask-indexed\n        const int hstart = max(0, half_h_mask - h);\n        const int hend = min(h_mask, h_feature + half_h_mask - h);\n        const int wstart = max(0, half_w_mask - w);\n        const int wend = min(w_mask, w_feature + half_w_mask - w);\n        // (hidx,                    widx                   ) with mask-indexed\n        // (hidx + h - half_h_mask, widx + w - half_w_mask) with\n        // feature-indexed\n        for (int hidx = hstart; hidx < hend; hidx++) {\n          for (int widx = wstart; widx < wend; widx++) {\n            buffer_data.view({-1})[(n * h_feature * w_feature +\n                                    (hidx + h - half_h_mask) * w_feature +\n                                    (widx + w - half_w_mask)) *\n                                       h_feature * w_feature +\n                                   h * w_feature + w] =\n                mask_data.view(\n                    {-1})[((n * h_mask * w_mask + hidx * w_mask + widx) *\n                               h_feature +\n                           h) *\n                              w_feature +\n                          w];\n          }\n        }\n      }\n    }\n  }\n}\n\nvoid psamask_distribute_forward(const int num_, const int h_feature,\n                                const int w_feature, const int h_mask,\n                                const int w_mask, const int half_h_mask,\n                                const int half_w_mask, const Tensor mask_data,\n                                Tensor buffer_data) {\n  for (int n = 0; n < num_; n++) {\n    for (int h = 0; h < h_feature; h++) {\n      for (int w = 0; w < w_feature; w++) {\n        // effective mask region : [hstart, hend) x [wstart, wend) with\n        // mask-indexed\n        const int hstart = max(0, half_h_mask - h);\n        const int hend = min(h_mask, h_feature + half_h_mask - h);\n        const int wstart = max(0, half_w_mask - w);\n        const int wend = min(w_mask, w_feature + half_w_mask - w);\n        // (hidx,                    widx                   ) with mask-indexed\n        // (hidx + h - half_h_mask, widx + w - half_w_mask) with\n        // feature-indexed\n        for (int hidx = hstart; hidx < hend; hidx++) {\n          for (int widx = wstart; widx < wend; widx++) {\n            buffer_data.view(\n                {-1})[(n * h_feature * w_feature + h * w_feature + w) *\n                          h_feature * w_feature +\n                      (hidx + h - half_h_mask) * w_feature +\n                      (widx + w - half_w_mask)] =\n                mask_data.view(\n                    {-1})[((n * h_mask * w_mask + hidx * w_mask + widx) *\n                               h_feature +\n                           h) *\n                              w_feature +\n                          w];\n          }\n        }\n      }\n    }\n  }\n}\n\nvoid psamask_collect_backward(const int num_, const int h_feature,\n                              const int w_feature, const int h_mask,\n                              const int w_mask, const int half_h_mask,\n                              const int half_w_mask, const Tensor buffer_diff,\n                              Tensor mask_diff) {\n  for (int n = 0; n < num_; n++) {\n    for (int h = 0; h < h_feature; h++) {\n      for (int w = 0; w < w_feature; w++) {\n        // effective mask region : [hstart, hend) x [wstart, wend) with\n        // mask-indexed\n        const int hstart = max(0, half_h_mask - h);\n        const int hend = min(h_mask, h_feature + half_h_mask - h);\n        const int wstart = max(0, half_w_mask - w);\n        const int wend = min(w_mask, w_feature + half_w_mask - w);\n        // (hidx,                    widx                   ) with mask-indexed\n        // (hidx + h - half_h_mask, widx + w - half_w_mask) with\n        // feature-indexed\n        for (int hidx = hstart; hidx < hend; hidx++) {\n          for (int widx = wstart; widx < wend; widx++) {\n            mask_diff.view({-1})[((n * h_mask * w_mask + hidx * w_mask + widx) *\n                                      h_feature +\n                                  h) *\n                                     w_feature +\n                                 w] =\n                buffer_diff.view({-1})[(n * h_feature * w_feature +\n                                        (hidx + h - half_h_mask) * w_feature +\n                                        (widx + w - half_w_mask)) *\n                                           h_feature * w_feature +\n                                       h * w_feature + w];\n          }\n        }\n      }\n    }\n  }\n}\n\nvoid psamask_distribute_backward(const int num_, const int h_feature,\n                                 const int w_feature, const int h_mask,\n                                 const int w_mask, const int half_h_mask,\n                                 const int half_w_mask,\n                                 const Tensor buffer_diff, Tensor mask_diff) {\n  for (int n = 0; n < num_; n++) {\n    for (int h = 0; h < h_feature; h++) {\n      for (int w = 0; w < w_feature; w++) {\n        // effective mask region : [hstart, hend) x [wstart, wend) with\n        // mask-indexed\n        const int hstart = max(0, half_h_mask - h);\n        const int hend = min(h_mask, h_feature + half_h_mask - h);\n        const int wstart = max(0, half_w_mask - w);\n        const int wend = min(w_mask, w_feature + half_w_mask - w);\n        // (hidx,                    widx                   ) with mask-indexed\n        // (hidx + h - half_h_mask, widx + w - half_w_mask) with\n        // feature-indexed\n        for (int hidx = hstart; hidx < hend; hidx++) {\n          for (int widx = wstart; widx < wend; widx++) {\n            mask_diff.view({-1})[((n * h_mask * w_mask + hidx * w_mask + widx) *\n                                      h_feature +\n                                  h) *\n                                     w_feature +\n                                 w] =\n                buffer_diff.view(\n                    {-1})[(n * h_feature * w_feature + h * w_feature + w) *\n                              h_feature * w_feature +\n                          (hidx + h - half_h_mask) * w_feature +\n                          (widx + w - half_w_mask)];\n          }\n        }\n      }\n    }\n  }\n}\n\nvoid psamask_forward_cpu(const int psa_type, const Tensor input, Tensor output,\n                         const int num_, const int h_feature,\n                         const int w_feature, const int h_mask,\n                         const int w_mask, const int half_h_mask,\n                         const int half_w_mask) {\n  if (psa_type == 0)\n    psamask_collect_forward(num_, h_feature, w_feature, h_mask, w_mask,\n                            half_h_mask, half_w_mask, input, output);\n  else\n    psamask_distribute_forward(num_, h_feature, w_feature, h_mask, w_mask,\n                               half_h_mask, half_w_mask, input, output);\n}\n\nvoid psamask_backward_cpu(const int psa_type, const Tensor grad_output,\n                          Tensor grad_input, const int num_,\n                          const int h_feature, const int w_feature,\n                          const int h_mask, const int w_mask,\n                          const int half_h_mask, const int half_w_mask) {\n  if (psa_type == 0)\n    psamask_collect_backward(num_, h_feature, w_feature, h_mask, w_mask,\n                             half_h_mask, half_w_mask, grad_output, grad_input);\n  else\n    psamask_distribute_backward(num_, h_feature, w_feature, h_mask, w_mask,\n                                half_h_mask, half_w_mask, grad_output,\n                                grad_input);\n}\n\nvoid psamask_forward_impl(const int psa_type, const Tensor input, Tensor output,\n                          const int num_, const int h_feature,\n                          const int w_feature, const int h_mask,\n                          const int w_mask, const int half_h_mask,\n                          const int half_w_mask);\n\nvoid psamask_backward_impl(const int psa_type, const Tensor grad_output,\n                           Tensor grad_input, const int num_,\n                           const int h_feature, const int w_feature,\n                           const int h_mask, const int w_mask,\n                           const int half_h_mask, const int half_w_mask);\nREGISTER_DEVICE_IMPL(psamask_forward_impl, CPU, psamask_forward_cpu);\nREGISTER_DEVICE_IMPL(psamask_backward_impl, CPU, psamask_backward_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/roi_align.cpp",
    "content": "// Modified from\n// https://github.com/facebookresearch/detectron2/tree/master/detectron2/layers/csrc/ROIAlign\n// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n#include <ATen/ATen.h>\n#include <ATen/TensorUtils.h>\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\n// implementation taken from Caffe2\ntemplate <typename T>\nstruct PreCalc {\n  int pos1;\n  int pos2;\n  int pos3;\n  int pos4;\n  T w1;\n  T w2;\n  T w3;\n  T w4;\n};\n\ntemplate <typename T>\nvoid pre_calc_for_bilinear_interpolate(\n    const int height, const int width, const int pooled_height,\n    const int pooled_width, const int iy_upper, const int ix_upper,\n    T roi_start_h, T roi_start_w, T bin_size_h, T bin_size_w,\n    int roi_bin_grid_h, int roi_bin_grid_w, std::vector<PreCalc<T>>& pre_calc) {\n  int pre_calc_index = 0;\n  for (int ph = 0; ph < pooled_height; ph++) {\n    for (int pw = 0; pw < pooled_width; pw++) {\n      for (int iy = 0; iy < iy_upper; iy++) {\n        const T yy = roi_start_h + ph * bin_size_h +\n                     static_cast<T>(iy + .5f) * bin_size_h /\n                         static_cast<T>(roi_bin_grid_h);  // e.g., 0.5, 1.5\n        for (int ix = 0; ix < ix_upper; ix++) {\n          const T xx = roi_start_w + pw * bin_size_w +\n                       static_cast<T>(ix + .5f) * bin_size_w /\n                           static_cast<T>(roi_bin_grid_w);\n\n          T x = xx;\n          T y = yy;\n          // deal with: inverse elements are out of feature map boundary\n          if (y < -1.0 || y > height || x < -1.0 || x > width) {\n            // empty\n            PreCalc<T> pc;\n            pc.pos1 = 0;\n            pc.pos2 = 0;\n            pc.pos3 = 0;\n            pc.pos4 = 0;\n            pc.w1 = 0;\n            pc.w2 = 0;\n            pc.w3 = 0;\n            pc.w4 = 0;\n            pre_calc[pre_calc_index] = pc;\n            pre_calc_index += 1;\n            continue;\n          }\n\n          if (y <= 0) {\n            y = 0;\n          }\n          if (x <= 0) {\n            x = 0;\n          }\n\n          int y_low = (int)y;\n          int x_low = (int)x;\n          int y_high;\n          int x_high;\n\n          if (y_low >= height - 1) {\n            y_high = y_low = height - 1;\n            y = (T)y_low;\n          } else {\n            y_high = y_low + 1;\n          }\n\n          if (x_low >= width - 1) {\n            x_high = x_low = width - 1;\n            x = (T)x_low;\n          } else {\n            x_high = x_low + 1;\n          }\n\n          T ly = y - y_low;\n          T lx = x - x_low;\n          T hy = 1. - ly, hx = 1. - lx;\n          T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n          // save weights and indices\n          PreCalc<T> pc;\n          pc.pos1 = y_low * width + x_low;\n          pc.pos2 = y_low * width + x_high;\n          pc.pos3 = y_high * width + x_low;\n          pc.pos4 = y_high * width + x_high;\n          pc.w1 = w1;\n          pc.w2 = w2;\n          pc.w3 = w3;\n          pc.w4 = w4;\n          pre_calc[pre_calc_index] = pc;\n\n          pre_calc_index += 1;\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid ROIAlignForward(const int nthreads, const T* input, const T* rois,\n                     T* output, T* argmax_y, T* argmax_x,\n                     const int pooled_height, const int pooled_width,\n                     const T spatial_scale, const int sampling_ratio,\n                     const int pool_mode,  // 0 - max pool, 1 - avg pool\n                     const bool aligned, const int channels, const int height,\n                     const int width) {\n  int n_rois = nthreads / channels / pooled_width / pooled_height;\n  // (n, c, ph, pw) is an element in the pooled output\n  // can be parallelized using omp\n  // #pragma omp parallel for num_threads(32)\n  for (int n = 0; n < n_rois; n++) {\n    int index_n = n * channels * pooled_width * pooled_height;\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n\n    // Do not use rounding; this implementation detail is critical\n    T offset = aligned ? (T)0.5 : (T)0.0;\n    T roi_start_w = offset_rois[1] * spatial_scale - offset;\n    T roi_start_h = offset_rois[2] * spatial_scale - offset;\n    T roi_end_w = offset_rois[3] * spatial_scale - offset;\n    T roi_end_h = offset_rois[4] * spatial_scale - offset;\n\n    T roi_width = roi_end_w - roi_start_w;\n    T roi_height = roi_end_h - roi_start_h;\n    if (aligned) {\n      AT_ASSERTM(roi_width >= 0 && roi_height >= 0,\n                 \"ROIs in ROIAlign cannot have non-negative size!\");\n    } else {  // for backward-compatibility only\n      roi_width = std::max(roi_width, (T)1.);\n      roi_height = std::max(roi_height, (T)1.);\n    }\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n                             ? sampling_ratio\n                             : ceilf(roi_height / pooled_height);  // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceilf(roi_width / pooled_width);\n\n    // When the grid is empty, output zeros == 0/1, instead of NaN.\n    const T count = std::max(roi_bin_grid_h * roi_bin_grid_w, 1);  // e.g. = 4\n\n    // we want to precalculate indices and weights shared by all channels,\n    // this is the key point of optimization\n    std::vector<PreCalc<T>> pre_calc(roi_bin_grid_h * roi_bin_grid_w *\n                                     pooled_width * pooled_height);\n    pre_calc_for_bilinear_interpolate(\n        height, width, pooled_height, pooled_width, roi_bin_grid_h,\n        roi_bin_grid_w, roi_start_h, roi_start_w, bin_size_h, bin_size_w,\n        roi_bin_grid_h, roi_bin_grid_w, pre_calc);\n\n    for (int c = 0; c < channels; c++) {\n      int index_n_c = index_n + c * pooled_width * pooled_height;\n      const T* offset_input =\n          input + (roi_batch_ind * channels + c) * height * width;\n      int pre_calc_index = 0;\n\n      for (int ph = 0; ph < pooled_height; ph++) {\n        for (int pw = 0; pw < pooled_width; pw++) {\n          int index = index_n_c + ph * pooled_width + pw;\n\n          T output_val = 0.;\n          T maxval = -10000;\n          T maxidx_y = -1.f, maxidx_x = -1.f;\n          for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n            const T y = roi_start_h + ph * bin_size_h +\n                        static_cast<T>(iy + .5f) * bin_size_h /\n                            static_cast<T>(roi_bin_grid_h);\n            for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n              const T x = roi_start_w + pw * bin_size_w +\n                          static_cast<T>(ix + .5f) * bin_size_w /\n                              static_cast<T>(roi_bin_grid_w);\n              PreCalc<T> pc = pre_calc[pre_calc_index];\n              T val = pc.w1 * offset_input[pc.pos1] +\n                      pc.w2 * offset_input[pc.pos2] +\n                      pc.w3 * offset_input[pc.pos3] +\n                      pc.w4 * offset_input[pc.pos4];\n              if (val > maxval) {\n                maxval = val;\n                maxidx_y = y;\n                maxidx_x = x;\n              }\n              output_val += val;\n              pre_calc_index += 1;\n            }\n          }\n          if (pool_mode == 0) {\n            // We do max pooling inside a bin\n            output[index] = maxval;\n            argmax_y[index] = maxidx_y;\n            argmax_x[index] = maxidx_x;\n          } else if (pool_mode == 1) {\n            // We do average (integral) pooling inside a bin\n            output[index] = output_val / count;\n          }  // if\n        }    // for pw\n      }      // for ph\n    }        // for c\n  }          // for n\n}\n\ntemplate <typename T>\nvoid bilinear_interpolate_gradient(const int height, const int width, T y, T x,\n                                   T& w1, T& w2, T& w3, T& w4, int& x_low,\n                                   int& x_high, int& y_low, int& y_high,\n                                   const int index /* index for debug only*/) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y <= 0) y = 0;\n  if (x <= 0) x = 0;\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n\ntemplate <class T>\ninline void add(T* address, const T& val) {\n  *address += val;\n}\n\ntemplate <typename T>\nvoid ROIAlignBackward(const int nthreads, const T* grad_output, const T* rois,\n                      const T* argmax_y, const T* argmax_x, T* grad_input,\n                      const int pooled_height, const int pooled_width,\n                      const T spatial_scale, const int sampling_ratio,\n                      const int pool_mode,  // 0 - max pool, 1 - avg pool\n                      const bool aligned, const int channels, const int height,\n                      const int width, const int n_stride, const int c_stride,\n                      const int h_stride, const int w_stride) {\n  for (int index = 0; index < nthreads; index++) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* offset_rois = rois + n * 5;\n    int roi_batch_ind = offset_rois[0];\n\n    // Do not use rounding; this implementation detail is critical\n    T offset = aligned ? (T)0.5 : (T)0.0;\n    T roi_start_w = offset_rois[1] * spatial_scale - offset;\n    T roi_start_h = offset_rois[2] * spatial_scale - offset;\n    T roi_end_w = offset_rois[3] * spatial_scale - offset;\n    T roi_end_h = offset_rois[4] * spatial_scale - offset;\n\n    T roi_width = roi_end_w - roi_start_w;\n    T roi_height = roi_end_h - roi_start_h;\n    if (aligned) {\n      AT_ASSERTM(roi_width >= 0 && roi_height >= 0,\n                 \"ROIs in ROIAlign do not have non-negative size!\");\n    } else {  // for backward-compatibility only\n      roi_width = std::max(roi_width, (T)1.);\n      roi_height = std::max(roi_height, (T)1.);\n    }\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    T* offset_grad_input =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n\n    int output_offset = n * n_stride + c * c_stride;\n    const T* offset_grad_output = grad_output + output_offset;\n    const T grad_output_this_bin =\n        offset_grad_output[ph * h_stride + pw * w_stride];\n\n    if (pool_mode == 0) {\n      // We do max pooling inside a bin\n      T y = argmax_y[index], x = argmax_x[index];\n      if (y != -1.f) {\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n        bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4,\n                                      x_low, x_high, y_low, y_high, index);\n\n        T g1 = grad_output_this_bin * w1;\n        T g2 = grad_output_this_bin * w2;\n        T g3 = grad_output_this_bin * w3;\n        T g4 = grad_output_this_bin * w4;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          // atomic add is not needed for now since it is single threaded\n          add(offset_grad_input + y_low * width + x_low, static_cast<T>(g1));\n          add(offset_grad_input + y_low * width + x_high, static_cast<T>(g2));\n          add(offset_grad_input + y_high * width + x_low, static_cast<T>(g3));\n          add(offset_grad_input + y_high * width + x_high, static_cast<T>(g4));\n        }  // if\n      }    // mode\n    } else if (pool_mode == 1) {\n      // We do average (integral) pooling inside a bin\n      // We use roi_bin_grid to sample the grid and mimic integral\n      int roi_bin_grid_h =\n          (sampling_ratio > 0)\n              ? sampling_ratio\n              : ceilf(roi_height / pooled_height);  // e.g., = 2\n      int roi_bin_grid_w = (sampling_ratio > 0)\n                               ? sampling_ratio\n                               : ceilf(roi_width / pooled_width);\n\n      const T count = roi_bin_grid_h * roi_bin_grid_w;  // e.g. = 4\n      for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n        const T y = roi_start_h + ph * bin_size_h +\n                    static_cast<T>(iy + .5f) * bin_size_h /\n                        static_cast<T>(roi_bin_grid_h);  // e.g., 0.5, 1.5\n        for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n          const T x = roi_start_w + pw * bin_size_w +\n                      static_cast<T>(ix + .5f) * bin_size_w /\n                          static_cast<T>(roi_bin_grid_w);\n\n          T w1, w2, w3, w4;\n          int x_low, x_high, y_low, y_high;\n\n          bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4,\n                                        x_low, x_high, y_low, y_high, index);\n\n          T g1 = grad_output_this_bin * w1 / count;\n          T g2 = grad_output_this_bin * w2 / count;\n          T g3 = grad_output_this_bin * w3 / count;\n          T g4 = grad_output_this_bin * w4 / count;\n\n          if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n            // atomic add is not needed for now since it is single threaded\n            add(offset_grad_input + y_low * width + x_low, static_cast<T>(g1));\n            add(offset_grad_input + y_low * width + x_high, static_cast<T>(g2));\n            add(offset_grad_input + y_high * width + x_low, static_cast<T>(g3));\n            add(offset_grad_input + y_high * width + x_high,\n                static_cast<T>(g4));\n          }  // if\n        }    // ix\n      }      // iy\n    }        // mode\n  }          // for\n}  // ROIAlignBackward\n\nvoid ROIAlignForwardCPULauncher(Tensor input, Tensor rois, Tensor output,\n                                Tensor argmax_y, Tensor argmax_x,\n                                int aligned_height, int aligned_width,\n                                float spatial_scale, int sampling_ratio,\n                                int pool_mode, bool aligned) {\n  int output_size = output.numel();\n  int channels = input.size(1);\n  int height = input.size(2);\n  int width = input.size(3);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"ROIAlign_forward\", [&] {\n        ROIAlignForward<scalar_t>(\n            output_size, input.data_ptr<scalar_t>(), rois.data_ptr<scalar_t>(),\n            output.data_ptr<scalar_t>(), argmax_y.data_ptr<scalar_t>(),\n            argmax_x.data_ptr<scalar_t>(), aligned_height, aligned_width,\n            static_cast<scalar_t>(spatial_scale), sampling_ratio, pool_mode,\n            aligned, channels, height, width);\n      });\n}\n\nvoid ROIAlignBackwardCPULauncher(Tensor grad_output, Tensor rois,\n                                 Tensor argmax_y, Tensor argmax_x,\n                                 Tensor grad_input, int aligned_height,\n                                 int aligned_width, float spatial_scale,\n                                 int sampling_ratio, int pool_mode,\n                                 bool aligned) {\n  int output_size = grad_output.numel();\n  int channels = grad_input.size(1);\n  int height = grad_input.size(2);\n  int width = grad_input.size(3);\n\n  // get stride values to ensure indexing into gradients is correct.\n  int n_stride = grad_output.stride(0);\n  int c_stride = grad_output.stride(1);\n  int h_stride = grad_output.stride(2);\n  int w_stride = grad_output.stride(3);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"ROIAlign_backward\", [&] {\n        ROIAlignBackward<scalar_t>(\n            output_size, grad_output.data_ptr<scalar_t>(),\n            rois.data_ptr<scalar_t>(), argmax_y.data_ptr<scalar_t>(),\n            argmax_x.data_ptr<scalar_t>(), grad_input.data_ptr<scalar_t>(),\n            aligned_height, aligned_width, static_cast<scalar_t>(spatial_scale),\n            sampling_ratio, pool_mode, aligned, channels, height, width,\n            n_stride, c_stride, h_stride, w_stride);\n      });\n}\n\nvoid roi_align_forward_cpu(Tensor input, Tensor rois, Tensor output,\n                           Tensor argmax_y, Tensor argmax_x, int aligned_height,\n                           int aligned_width, float spatial_scale,\n                           int sampling_ratio, int pool_mode, bool aligned) {\n  ROIAlignForwardCPULauncher(input, rois, output, argmax_y, argmax_x,\n                             aligned_height, aligned_width, spatial_scale,\n                             sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_backward_cpu(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                            Tensor argmax_x, Tensor grad_input,\n                            int aligned_height, int aligned_width,\n                            float spatial_scale, int sampling_ratio,\n                            int pool_mode, bool aligned) {\n  ROIAlignBackwardCPULauncher(grad_output, rois, argmax_y, argmax_x, grad_input,\n                              aligned_height, aligned_width, spatial_scale,\n                              sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_forward_impl(Tensor input, Tensor rois, Tensor output,\n                            Tensor argmax_y, Tensor argmax_x,\n                            int aligned_height, int aligned_width,\n                            float spatial_scale, int sampling_ratio,\n                            int pool_mode, bool aligned);\n\nvoid roi_align_backward_impl(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                             Tensor argmax_x, Tensor grad_input,\n                             int aligned_height, int aligned_width,\n                             float spatial_scale, int sampling_ratio,\n                             int pool_mode, bool aligned);\n\nREGISTER_DEVICE_IMPL(roi_align_forward_impl, CPU, roi_align_forward_cpu);\nREGISTER_DEVICE_IMPL(roi_align_backward_impl, CPU, roi_align_backward_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/roi_align_rotated.cpp",
    "content": "// Modified from\n// https://github.com/facebookresearch/detectron2/tree/master/detectron2/layers/csrc/ROIAlignRotated\n// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n#include <ATen/ATen.h>\n#include <ATen/TensorUtils.h>\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\n// implementation taken from Caffe2\ntemplate <typename T>\nstruct PreCalc {\n  int pos1;\n  int pos2;\n  int pos3;\n  int pos4;\n  T w1;\n  T w2;\n  T w3;\n  T w4;\n};\n\ntemplate <typename T>\nvoid pre_calc_for_bilinear_interpolate(\n    const int height, const int width, const int pooled_height,\n    const int pooled_width, const int iy_upper, const int ix_upper,\n    T roi_start_h, T roi_start_w, T bin_size_h, T bin_size_w,\n    int roi_bin_grid_h, int roi_bin_grid_w, T roi_center_h, T roi_center_w,\n    T cos_theta, T sin_theta, std::vector<PreCalc<T>>& pre_calc) {\n  int pre_calc_index = 0;\n  for (int ph = 0; ph < pooled_height; ph++) {\n    for (int pw = 0; pw < pooled_width; pw++) {\n      for (int iy = 0; iy < iy_upper; iy++) {\n        const T yy = roi_start_h + ph * bin_size_h +\n                     static_cast<T>(iy + .5f) * bin_size_h /\n                         static_cast<T>(roi_bin_grid_h);  // e.g., 0.5, 1.5\n        for (int ix = 0; ix < ix_upper; ix++) {\n          const T xx = roi_start_w + pw * bin_size_w +\n                       static_cast<T>(ix + .5f) * bin_size_w /\n                           static_cast<T>(roi_bin_grid_w);\n\n          // Rotate by theta around the center and translate\n          // In image space, (y, x) is the order for Right Handed System,\n          // and this is essentially multiplying the point by a rotation matrix\n          // to rotate it counterclockwise through angle theta.\n          T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n          T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n          // deal with: inverse elements are out of feature map boundary\n          if (y < -1.0 || y > height || x < -1.0 || x > width) {\n            // empty\n            PreCalc<T> pc;\n            pc.pos1 = 0;\n            pc.pos2 = 0;\n            pc.pos3 = 0;\n            pc.pos4 = 0;\n            pc.w1 = 0;\n            pc.w2 = 0;\n            pc.w3 = 0;\n            pc.w4 = 0;\n            pre_calc[pre_calc_index] = pc;\n            pre_calc_index += 1;\n            continue;\n          }\n\n          if (y < 0) {\n            y = 0;\n          }\n          if (x < 0) {\n            x = 0;\n          }\n\n          int y_low = (int)y;\n          int x_low = (int)x;\n          int y_high;\n          int x_high;\n\n          if (y_low >= height - 1) {\n            y_high = y_low = height - 1;\n            y = (T)y_low;\n          } else {\n            y_high = y_low + 1;\n          }\n\n          if (x_low >= width - 1) {\n            x_high = x_low = width - 1;\n            x = (T)x_low;\n          } else {\n            x_high = x_low + 1;\n          }\n\n          T ly = y - y_low;\n          T lx = x - x_low;\n          T hy = 1. - ly, hx = 1. - lx;\n          T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n          // save weights and indices\n          PreCalc<T> pc;\n          pc.pos1 = y_low * width + x_low;\n          pc.pos2 = y_low * width + x_high;\n          pc.pos3 = y_high * width + x_low;\n          pc.pos4 = y_high * width + x_high;\n          pc.w1 = w1;\n          pc.w2 = w2;\n          pc.w3 = w3;\n          pc.w4 = w4;\n          pre_calc[pre_calc_index] = pc;\n\n          pre_calc_index += 1;\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid ROIAlignRotatedForward(const int nthreads, const T* input,\n                            const T& spatial_scale, const bool aligned,\n                            const bool clockwise, const int channels,\n                            const int height, const int width,\n                            const int pooled_height, const int pooled_width,\n                            const int sampling_ratio, const T* rois,\n                            T* output) {\n  int n_rois = nthreads / channels / pooled_width / pooled_height;\n  // (n, c, ph, pw) is an element in the pooled output\n  // can be parallelized using omp\n  // #pragma omp parallel for num_threads(32)\n  for (int n = 0; n < n_rois; n++) {\n    int index_n = n * channels * pooled_width * pooled_height;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    T offset = aligned ? (T)0.5 : (T)0.0;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5];\n    if (clockwise) {\n      theta = -theta;  // If clockwise, the angle needs to be reversed.\n    }\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    if (aligned) {\n      AT_ASSERTM(roi_width >= 0 && roi_height >= 0,\n                 \"ROIs in ROIAlignRotated do not have non-negative size!\");\n    } else {  // for backward-compatibility only\n      roi_width = std::max(roi_width, (T)1.);\n      roi_height = std::max(roi_height, (T)1.);\n    }\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n                             ? sampling_ratio\n                             : ceilf(roi_height / pooled_height);  // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceilf(roi_width / pooled_width);\n\n    // We do average (integral) pooling inside a bin\n    const T count = std::max(roi_bin_grid_h * roi_bin_grid_w, 1);  // e.g. = 4\n\n    // we want to precalculate indices and weights shared by all channels,\n    // this is the key point of optimization\n    std::vector<PreCalc<T>> pre_calc(roi_bin_grid_h * roi_bin_grid_w *\n                                     pooled_width * pooled_height);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    pre_calc_for_bilinear_interpolate(\n        height, width, pooled_height, pooled_width, roi_bin_grid_h,\n        roi_bin_grid_w, roi_start_h, roi_start_w, bin_size_h, bin_size_w,\n        roi_bin_grid_h, roi_bin_grid_w, roi_center_h, roi_center_w, cos_theta,\n        sin_theta, pre_calc);\n\n    for (int c = 0; c < channels; c++) {\n      int index_n_c = index_n + c * pooled_width * pooled_height;\n      const T* offset_input =\n          input + (roi_batch_ind * channels + c) * height * width;\n      int pre_calc_index = 0;\n\n      for (int ph = 0; ph < pooled_height; ph++) {\n        for (int pw = 0; pw < pooled_width; pw++) {\n          int index = index_n_c + ph * pooled_width + pw;\n\n          T output_val = 0.;\n          for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n            for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n              PreCalc<T> pc = pre_calc[pre_calc_index];\n              output_val += pc.w1 * offset_input[pc.pos1] +\n                            pc.w2 * offset_input[pc.pos2] +\n                            pc.w3 * offset_input[pc.pos3] +\n                            pc.w4 * offset_input[pc.pos4];\n\n              pre_calc_index += 1;\n            }\n          }\n          output_val /= count;\n\n          output[index] = output_val;\n        }  // for pw\n      }    // for ph\n    }      // for c\n  }        // for n\n}\n\ntemplate <typename T>\nvoid bilinear_interpolate_gradient(const int height, const int width, T y, T x,\n                                   T& w1, T& w2, T& w3, T& w4, int& x_low,\n                                   int& x_high, int& y_low, int& y_high) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n\ntemplate <class T>\ninline void add(T* address, const T& val) {\n  *address += val;\n}\n\ntemplate <typename T>\nvoid ROIAlignRotatedBackward(\n    const int nthreads,\n    // may not be contiguous. should index using n_stride, etc\n    const T* grad_output, const T& spatial_scale, const bool aligned,\n    const bool clockwise, const int channels, const int height, const int width,\n    const int pooled_height, const int pooled_width, const int sampling_ratio,\n    T* grad_input, const T* rois, const int n_stride, const int c_stride,\n    const int h_stride, const int w_stride) {\n  for (int index = 0; index < nthreads; index++) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    T offset = aligned ? (T)0.5 : (T)0.0;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5];\n    if (clockwise) {\n      theta = -theta;  // If clockwise, the angle needs to be reversed.\n    }\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    if (aligned) {\n      AT_ASSERTM(roi_width >= 0 && roi_height >= 0,\n                 \"ROIs in ROIAlignRotated do not have non-negative size!\");\n    } else {  // for backward-compatibility only\n      roi_width = std::max(roi_width, (T)1.);\n      roi_height = std::max(roi_height, (T)1.);\n    }\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    T* offset_grad_input =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n\n    int output_offset = n * n_stride + c * c_stride;\n    const T* offset_grad_output = grad_output + output_offset;\n    const T grad_output_this_bin =\n        offset_grad_output[ph * h_stride + pw * w_stride];\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n                             ? sampling_ratio\n                             : ceilf(roi_height / pooled_height);  // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceilf(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (integral) pooling inside a bin\n    const T count = roi_bin_grid_h * roi_bin_grid_w;  // e.g. = 4\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n      const T yy = roi_start_h + ph * bin_size_h +\n                   static_cast<T>(iy + .5f) * bin_size_h /\n                       static_cast<T>(roi_bin_grid_h);  // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n                     static_cast<T>(ix + .5f) * bin_size_w /\n                         static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n\n        bilinear_interpolate_gradient(height, width, y, x, w1, w2, w3, w4,\n                                      x_low, x_high, y_low, y_high);\n\n        T g1 = grad_output_this_bin * w1 / count;\n        T g2 = grad_output_this_bin * w2 / count;\n        T g3 = grad_output_this_bin * w3 / count;\n        T g4 = grad_output_this_bin * w4 / count;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          // atomic add is not needed for now since it is single threaded\n          add(offset_grad_input + y_low * width + x_low, static_cast<T>(g1));\n          add(offset_grad_input + y_low * width + x_high, static_cast<T>(g2));\n          add(offset_grad_input + y_high * width + x_low, static_cast<T>(g3));\n          add(offset_grad_input + y_high * width + x_high, static_cast<T>(g4));\n        }  // if\n      }    // ix\n    }      // iy\n  }        // for\n}  // ROIAlignRotatedBackward\n\nvoid ROIAlignRotatedForwardCPULauncher(Tensor input, Tensor rois, Tensor output,\n                                       int aligned_height, int aligned_width,\n                                       float spatial_scale, int sampling_ratio,\n                                       bool aligned, bool clockwise) {\n  int output_size = output.numel();\n  int channels = input.size(1);\n  int height = input.size(2);\n  int width = input.size(3);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        ROIAlignRotatedForward<scalar_t>(\n            output_size, input.data_ptr<scalar_t>(),\n            static_cast<scalar_t>(spatial_scale), aligned, clockwise, channels,\n            height, width, aligned_height, aligned_width, sampling_ratio,\n            rois.data_ptr<scalar_t>(), output.data_ptr<scalar_t>());\n      });\n}\n\nvoid ROIAlignRotatedBackwardCPULauncher(Tensor grad_output, Tensor rois,\n                                        Tensor grad_input, int aligned_height,\n                                        int aligned_width, float spatial_scale,\n                                        int sampling_ratio, bool aligned,\n                                        bool clockwise) {\n  int output_size = grad_output.numel();\n  int channels = grad_input.size(1);\n  int height = grad_input.size(2);\n  int width = grad_input.size(3);\n\n  // get stride values to ensure indexing into gradients is correct.\n  int n_stride = grad_output.stride(0);\n  int c_stride = grad_output.stride(1);\n  int h_stride = grad_output.stride(2);\n  int w_stride = grad_output.stride(3);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"ROIAlignRotated_backward\", [&] {\n        ROIAlignRotatedBackward<scalar_t>(\n            grad_output.numel(), grad_output.data_ptr<scalar_t>(),\n            static_cast<scalar_t>(spatial_scale), aligned, clockwise, channels,\n            height, width, aligned_height, aligned_width, sampling_ratio,\n            grad_input.data_ptr<scalar_t>(), rois.data_ptr<scalar_t>(),\n            n_stride, c_stride, h_stride, w_stride);\n      });\n}\n\nvoid roi_align_rotated_forward_cpu(Tensor input, Tensor rois, Tensor output,\n                                   int aligned_height, int aligned_width,\n                                   float spatial_scale, int sampling_ratio,\n                                   bool aligned, bool clockwise) {\n  ROIAlignRotatedForwardCPULauncher(input, rois, output, aligned_height,\n                                    aligned_width, spatial_scale,\n                                    sampling_ratio, aligned, clockwise);\n}\n\nvoid roi_align_rotated_backward_cpu(Tensor top_grad, Tensor rois,\n                                    Tensor bottom_grad, int aligned_height,\n                                    int aligned_width, float spatial_scale,\n                                    int sampling_ratio, bool aligned,\n                                    bool clockwise) {\n  // Number of ROIs\n  int num_rois = rois.size(0);\n  int size_rois = rois.size(1);\n  if (size_rois != 6) {\n    AT_ERROR(\"wrong roi size\");\n  }\n  ROIAlignRotatedBackwardCPULauncher(\n      top_grad, rois, bottom_grad, aligned_height, aligned_width, spatial_scale,\n      sampling_ratio, aligned, clockwise);\n}\n\nvoid roi_align_rotated_forward_impl(Tensor features, Tensor rois, Tensor output,\n                                    int aligned_height, int aligned_width,\n                                    float spatial_scale, int sample_ratio,\n                                    bool aligned, bool clockwise);\n\nvoid roi_align_rotated_backward_impl(Tensor top_grad, Tensor rois,\n                                     Tensor bottom_grad, int aligned_height,\n                                     int aligned_width, float spatial_scale,\n                                     int sample_ratio, bool aligned,\n                                     bool clockwise);\nREGISTER_DEVICE_IMPL(roi_align_rotated_forward_impl, CPU,\n                     roi_align_rotated_forward_cpu);\nREGISTER_DEVICE_IMPL(roi_align_rotated_backward_impl, CPU,\n                     roi_align_rotated_backward_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cpu/voxelization.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntemplate <typename T, typename T_int>\nvoid dynamic_voxelize_forward_cpu_kernel(\n    const torch::TensorAccessor<T, 2> points,\n    torch::TensorAccessor<T_int, 2> coors, const std::vector<float> voxel_size,\n    const std::vector<float> coors_range, const std::vector<int> grid_size,\n    const int num_points, const int num_features, const int NDim) {\n  const int ndim_minus_1 = NDim - 1;\n  bool failed = false;\n  // int coor[NDim];\n  int* coor = new int[NDim]();\n  int c;\n\n  for (int i = 0; i < num_points; ++i) {\n    failed = false;\n    for (int j = 0; j < NDim; ++j) {\n      c = floor((points[i][j] - coors_range[j]) / voxel_size[j]);\n      // necessary to rm points out of range\n      if ((c < 0 || c >= grid_size[j])) {\n        failed = true;\n        break;\n      }\n      coor[ndim_minus_1 - j] = c;\n    }\n\n    if (failed)\n      memset(&coors[i][0], -1, NDim * sizeof(T_int));\n    else\n      memcpy(&coors[i][0], &coor[0], NDim * sizeof(T_int));\n  }\n\n  delete[] coor;\n}\n\ntemplate <typename T, typename T_int>\nvoid hard_voxelize_forward_cpu_kernel(\n    const torch::TensorAccessor<T, 2> points,\n    torch::TensorAccessor<T, 3> voxels, torch::TensorAccessor<T_int, 2> coors,\n    torch::TensorAccessor<T_int, 1> num_points_per_voxel,\n    torch::TensorAccessor<T_int, 3> coor_to_voxelidx, int& voxel_num,\n    const std::vector<float> voxel_size, const std::vector<float> coors_range,\n    const std::vector<int> grid_size, const int max_points,\n    const int max_voxels, const int num_points, const int num_features,\n    const int NDim) {\n  // declare a temp coors\n  at::Tensor temp_coors = at::zeros(\n      {num_points, NDim}, at::TensorOptions().dtype(at::kInt).device(at::kCPU));\n\n  // First use dynamic voxelization to get coors,\n  // then check max points/voxels constraints\n  dynamic_voxelize_forward_cpu_kernel<T, int>(\n      points, temp_coors.accessor<int, 2>(), voxel_size, coors_range, grid_size,\n      num_points, num_features, NDim);\n\n  int voxelidx, num;\n  auto coor = temp_coors.accessor<int, 2>();\n\n  for (int i = 0; i < num_points; ++i) {\n    // T_int* coor = temp_coors.data_ptr<int>() + i * NDim;\n\n    if (coor[i][0] == -1) continue;\n\n    voxelidx = coor_to_voxelidx[coor[i][0]][coor[i][1]][coor[i][2]];\n\n    // record voxel\n    if (voxelidx == -1) {\n      voxelidx = voxel_num;\n      if (max_voxels != -1 && voxel_num >= max_voxels) continue;\n      voxel_num += 1;\n\n      coor_to_voxelidx[coor[i][0]][coor[i][1]][coor[i][2]] = voxelidx;\n      memcpy(&coors[voxelidx][0], &coor[i][0], NDim * sizeof(T_int));\n    }\n\n    // put points into voxel\n    num = num_points_per_voxel[voxelidx];\n    if (max_points == -1 || num < max_points) {\n      memcpy(&voxels[voxelidx][num][0], &points[i][0],\n             num_features * sizeof(T));\n      num_points_per_voxel[voxelidx] += 1;\n    }\n  }\n\n  return;\n}\n\nvoid dynamic_voxelize_forward_cpu(const at::Tensor& points, at::Tensor& coors,\n                                  const std::vector<float> voxel_size,\n                                  const std::vector<float> coors_range,\n                                  const int NDim = 3) {\n  // check device\n  AT_ASSERTM(points.device().is_cpu(), \"points must be a CPU tensor\");\n\n  std::vector<int> grid_size(NDim);\n  const int num_points = points.size(0);\n  const int num_features = points.size(1);\n\n  for (int i = 0; i < NDim; ++i) {\n    grid_size[i] =\n        round((coors_range[NDim + i] - coors_range[i]) / voxel_size[i]);\n  }\n\n  // coors, num_points_per_voxel, coor_to_voxelidx are int Tensor\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      points.scalar_type(), \"dynamic_voxelize_forward_cpu_kernel\", [&] {\n        dynamic_voxelize_forward_cpu_kernel<scalar_t, int>(\n            points.accessor<scalar_t, 2>(), coors.accessor<int, 2>(),\n            voxel_size, coors_range, grid_size, num_points, num_features, NDim);\n      });\n}\n\nint hard_voxelize_forward_cpu(const at::Tensor& points, at::Tensor& voxels,\n                              at::Tensor& coors,\n                              at::Tensor& num_points_per_voxel,\n                              const std::vector<float> voxel_size,\n                              const std::vector<float> coors_range,\n                              const int max_points, const int max_voxels,\n                              const int NDim = 3) {\n  // current version tooks about 0.02s_0.03s for one frame on cpu\n  // check device\n  AT_ASSERTM(points.device().is_cpu(), \"points must be a CPU tensor\");\n\n  std::vector<int> grid_size(NDim);\n  const int num_points = points.size(0);\n  const int num_features = points.size(1);\n\n  for (int i = 0; i < NDim; ++i) {\n    grid_size[i] =\n        round((coors_range[NDim + i] - coors_range[i]) / voxel_size[i]);\n  }\n\n  // coors, num_points_per_voxel, coor_to_voxelidx are int Tensor\n  // printf(\"cpu coor_to_voxelidx size: [%d, %d, %d]\\n\", grid_size[2],\n  // grid_size[1], grid_size[0]);\n  at::Tensor coor_to_voxelidx =\n      -at::ones({grid_size[2], grid_size[1], grid_size[0]}, coors.options());\n\n  int voxel_num = 0;\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      points.scalar_type(), \"hard_voxelize_forward_cpu_kernel\", [&] {\n        hard_voxelize_forward_cpu_kernel<scalar_t, int>(\n            points.accessor<scalar_t, 2>(), voxels.accessor<scalar_t, 3>(),\n            coors.accessor<int, 2>(), num_points_per_voxel.accessor<int, 1>(),\n            coor_to_voxelidx.accessor<int, 3>(), voxel_num, voxel_size,\n            coors_range, grid_size, max_points, max_voxels, num_points,\n            num_features, NDim);\n      });\n\n  return voxel_num;\n}\n\nint hard_voxelize_forward_impl(const at::Tensor& points, at::Tensor& voxels,\n                               at::Tensor& coors,\n                               at::Tensor& num_points_per_voxel,\n                               const std::vector<float> voxel_size,\n                               const std::vector<float> coors_range,\n                               const int max_points, const int max_voxels,\n                               const int NDim);\n\nvoid dynamic_voxelize_forward_impl(const at::Tensor& points, at::Tensor& coors,\n                                   const std::vector<float> voxel_size,\n                                   const std::vector<float> coors_range,\n                                   const int NDim);\nREGISTER_DEVICE_IMPL(hard_voxelize_forward_impl, CPU,\n                     hard_voxelize_forward_cpu);\nREGISTER_DEVICE_IMPL(dynamic_voxelize_forward_impl, CPU,\n                     dynamic_voxelize_forward_cpu);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/assign_score_withk_cuda.cu",
    "content": "// Modified from\n// https://github.com/CVMI-Lab/PAConv/tree/main/scene_seg/lib/paconv_lib/src/gpu\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"assign_score_withk_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid AssignScoreWithKForwardCUDAKernelLauncher(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& points, const Tensor& centers, const Tensor& scores,\n    const Tensor& knn_idx, Tensor& output) {\n  at::cuda::CUDAGuard device_guard(points.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks(DIVUP(B * O * N1 * K, THREADS_PER_BLOCK));\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      points.scalar_type(), \"assign_score_withk_forward_cuda_kernel\", [&] {\n        assign_score_withk_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                B, N0, N1, M, K, O, aggregate, points.data_ptr<scalar_t>(),\n                centers.data_ptr<scalar_t>(), scores.data_ptr<scalar_t>(),\n                knn_idx.data_ptr<int64_t>(), output.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid AssignScoreWithKBackwardCUDAKernelLauncher(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& grad_out, const Tensor& points, const Tensor& centers,\n    const Tensor& scores, const Tensor& knn_idx, Tensor& grad_points,\n    Tensor& grad_centers, Tensor& grad_scores) {\n  at::cuda::CUDAGuard device_guard(grad_out.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks1(DIVUP(B * M * O, THREADS_PER_BLOCK));\n  dim3 threads1(THREADS_PER_BLOCK);\n  dim3 blocks2(DIVUP(B * N1 * K * M, THREADS_PER_BLOCK));\n  dim3 threads2(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_out.scalar_type(), \"assign_score_withk_points_backward_cuda_kernel\",\n      [&] {\n        assign_score_withk_points_backward_cuda_kernel<scalar_t>\n            <<<blocks1, threads1, 0, stream>>>(\n                B, N0, N1, M, K, O, aggregate, grad_out.data_ptr<scalar_t>(),\n                scores.data_ptr<scalar_t>(), knn_idx.data_ptr<int64_t>(),\n                grad_points.data_ptr<scalar_t>(),\n                grad_centers.data_ptr<scalar_t>());\n      });\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_out.scalar_type(), \"assign_score_withk_scores_backward_cuda_kernel\",\n      [&] {\n        assign_score_withk_scores_backward_cuda_kernel<scalar_t>\n            <<<blocks2, threads2, 0, stream>>>(\n                B, N0, N1, M, K, O, aggregate, grad_out.data_ptr<scalar_t>(),\n                points.data_ptr<scalar_t>(), centers.data_ptr<scalar_t>(),\n                knn_idx.data_ptr<int64_t>(), grad_scores.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/ball_query_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/ball_query_gpu.cu\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"ball_query_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid BallQueryForwardCUDAKernelLauncher(int b, int n, int m, float min_radius,\n                                        float max_radius, int nsample,\n                                        const Tensor new_xyz, const Tensor xyz,\n                                        Tensor idx) {\n  // new_xyz: (B, M, 3)\n  // xyz: (B, N, 3)\n  // output:\n  //      idx: (B, M, nsample)\n\n  at::cuda::CUDAGuard device_guard(new_xyz.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(m, THREADS_PER_BLOCK), b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      new_xyz.scalar_type(), \"ball_query_forward_cuda_kernel\", [&] {\n        ball_query_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, n, m, min_radius, max_radius, nsample,\n                new_xyz.data_ptr<scalar_t>(), xyz.data_ptr<scalar_t>(),\n                idx.data_ptr<int>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/bbox_overlaps_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"bbox_overlaps_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid BBoxOverlapsCUDAKernelLauncher(const Tensor bboxes1, const Tensor bboxes2,\n                                    Tensor ious, const int mode,\n                                    const bool aligned, const int offset) {\n  int output_size = ious.numel();\n  int num_bbox1 = bboxes1.size(0);\n  int num_bbox2 = bboxes2.size(0);\n\n  at::cuda::CUDAGuard device_guard(bboxes1.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      bboxes1.scalar_type(), \"bbox_overlaps_cuda_kernel\", ([&] {\n        bbox_overlaps_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                bboxes1.data_ptr<scalar_t>(), bboxes2.data_ptr<scalar_t>(),\n                ious.data_ptr<scalar_t>(), num_bbox1, num_bbox2, mode, aligned,\n                offset);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/border_align_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"border_align_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid BorderAlignForwardCUDAKernelLauncher(const Tensor &input,\n                                          const Tensor &boxes, Tensor output,\n                                          Tensor argmax_idx,\n                                          const int pool_size) {\n  // shape assertion\n  AT_ASSERTM(input.ndimension() == 4,\n             \"non-empty 4D(batch mode) tensor expected for input feature\");\n  AT_ASSERTM(boxes.ndimension() == 3,\n             \"boxes must be 3D tensor with size of [B, H*W, 4]\");\n\n  int batch_size = input.size(0);\n  int feat_channels = input.size(1);\n  int channels = feat_channels / 4;\n  int height = input.size(2);\n  int width = input.size(3);\n  // shape [N, box_size, 4] for boxes. (x1, y1, x2, y2) format\n  int box_size = boxes.size(1);\n  // shape [N, channels, box_size, 4] for output\n  int nthreads = batch_size * channels * box_size;\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  dim3 block(128, 4);\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"border_align_forward_cuda_kernel\", [&] {\n        border_align_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(nthreads), block, 0, stream>>>(\n                nthreads, input.data_ptr<scalar_t>(),\n                boxes.data_ptr<scalar_t>(), output.data_ptr<scalar_t>(),\n                argmax_idx.data_ptr<int>(), channels, box_size, height, width,\n                pool_size);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid BorderAlignBackwardCUDAKernelLauncher(const Tensor &grad_output,\n                                           const Tensor &boxes,\n                                           const Tensor &argmax_idx,\n                                           Tensor grad_input,\n                                           const int pool_size) {\n  int batch_size = grad_input.size(0);\n  int feat_channels = grad_input.size(1);\n  int channels = feat_channels / 4;\n  int height = grad_input.size(2);\n  int width = grad_input.size(3);\n  int box_size = boxes.size(1);\n  int nthreads = batch_size * channels * box_size;\n\n  at::cuda::CUDAGuard device_guard(grad_output.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  dim3 block(128, 4);\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"border_align_backward_cuda_kernel\", [&] {\n        border_align_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(nthreads), block, 0, stream>>>(\n                nthreads, grad_output.data_ptr<scalar_t>(),\n                boxes.data_ptr<scalar_t>(), argmax_idx.data_ptr<int>(),\n                grad_input.data_ptr<scalar_t>(), channels, box_size, height,\n                width, pool_size);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/box_iou_rotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_cuda.cu\n#include \"box_iou_rotated_cuda.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid box_iou_rotated_cuda(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                          const int mode_flag, const bool aligned) {\n  using scalar_t = float;\n  AT_ASSERTM(boxes1.is_cuda(), \"boxes1 must be a CUDA tensor\");\n  AT_ASSERTM(boxes2.is_cuda(), \"boxes2 must be a CUDA tensor\");\n\n  int output_size = ious.numel();\n  int num_boxes1 = boxes1.size(0);\n  int num_boxes2 = boxes2.size(0);\n\n  at::cuda::CUDAGuard device_guard(boxes1.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  box_iou_rotated_cuda_kernel<scalar_t>\n      <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n          num_boxes1, num_boxes2, boxes1.data_ptr<scalar_t>(),\n          boxes2.data_ptr<scalar_t>(), (scalar_t*)ious.data_ptr<scalar_t>(),\n          mode_flag, aligned);\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/carafe_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"carafe_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid CARAFEForwardCUDAKernelLauncher(const Tensor features, const Tensor masks,\n                                     Tensor rfeatures, Tensor routput,\n                                     Tensor rmasks, Tensor output,\n                                     const int kernel_size,\n                                     const int group_size,\n                                     const int scale_factor) {\n  const int batch_size = output.size(0);\n  const int channels = output.size(1);\n  const int output_height = output.size(2);\n  const int output_width = output.size(3);\n\n  const int input_height = features.size(2);\n  const int input_width = features.size(3);\n\n  const int mask_channels = masks.size(1);\n\n  rfeatures.resize_({batch_size, input_height, input_width, channels});\n  routput.resize_({batch_size, output_height, output_width, channels});\n  rmasks.resize_({batch_size, output_height, output_width, mask_channels});\n\n  // one warp per pixel\n  at::cuda::CUDAGuard device_guard(features.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      features.scalar_type(), \"NCHW2NHWC_Feature\", ([&] {\n        const scalar_t *bottom_data = features.data_ptr<scalar_t>();\n        scalar_t *top_data = rfeatures.data_ptr<scalar_t>();\n        const int dh = divideUP(channels, kTileDim);\n        const int dw = divideUP(input_height * input_width, kTileDim);\n        BatchTranspose2DCUDAKernel<scalar_t>\n            <<<batch_size * dh * dw, dim3(kTileDim, kBlockRows), 0, stream>>>(\n                batch_size, channels, input_height * input_width, dh, dw,\n                bottom_data, top_data);\n      }));\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      features.scalar_type(), \"NCHW2NHWC_Masks\", ([&] {\n        const scalar_t *bottom_data = masks.data_ptr<scalar_t>();\n        scalar_t *top_data = rmasks.data_ptr<scalar_t>();\n        const int dh = divideUP(mask_channels, kTileDim);\n        const int dw = divideUP(output_height * output_width, kTileDim);\n        BatchTranspose2DCUDAKernel<scalar_t>\n            <<<batch_size * dh * dw, dim3(kTileDim, kBlockRows), 0, stream>>>(\n                batch_size, mask_channels, output_height * output_width, dh, dw,\n                bottom_data, top_data);\n      }));\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      features.scalar_type(), \"CARAFELaucherForward\", ([&] {\n        const int num_kernels =\n            batch_size * output_height * output_width * THREADS_PER_PIXEL;\n        const scalar_t *bottom_data = rfeatures.data_ptr<scalar_t>();\n        const scalar_t *bottom_masks = rmasks.data_ptr<scalar_t>();\n        scalar_t *top_data = routput.data_ptr<scalar_t>();\n\n        CARAFEForward<scalar_t><<<divideUP(num_kernels, THREADS_PER_BLOCK),\n                                  THREADS_PER_BLOCK, 0, stream>>>(\n            num_kernels, bottom_data, bottom_masks, kernel_size, group_size,\n            scale_factor, channels, input_height, input_width, output_height,\n            output_width, mask_channels, top_data);\n      }));\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      features.scalar_type(), \"NHWC2NCHW\", ([&] {\n        const scalar_t *bottom_data = routput.data_ptr<scalar_t>();\n        scalar_t *top_data = output.data_ptr<scalar_t>();\n        const int dh = divideUP(output_height * output_width, kTileDim);\n        const int dw = divideUP(channels, kTileDim);\n        BatchTranspose2DCUDAKernel<scalar_t>\n            <<<batch_size * dh * dw, dim3(kTileDim, kBlockRows), 0, stream>>>(\n                batch_size, output_height * output_width, channels, dh, dw,\n                bottom_data, top_data);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid CARAFEBackwardCUDAKernelLauncher(\n    const Tensor top_grad, const Tensor rfeatures, const Tensor masks,\n    Tensor rtop_grad, Tensor rbottom_grad_hs, Tensor rbottom_grad,\n    Tensor rmask_grad, Tensor bottom_grad, Tensor mask_grad,\n    const int kernel_size, const int group_size, const int scale_factor) {\n  const int batch_size = top_grad.size(0);\n  const int channels = top_grad.size(1);\n  const int output_height = top_grad.size(2);\n  const int output_width = top_grad.size(3);\n\n  const int input_height = bottom_grad.size(2);\n  const int input_width = bottom_grad.size(3);\n\n  const int mask_channels = masks.size(1);\n\n  rtop_grad.resize_({batch_size, output_height, output_width, channels});\n  rbottom_grad.resize_({batch_size, input_height, input_width, channels});\n  rbottom_grad_hs.resize_({batch_size, output_height, output_width, channels});\n  rmask_grad.resize_({batch_size, output_height, output_width, mask_channels});\n\n  at::cuda::CUDAGuard device_guard(top_grad.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"NCHW2NHWC_Top_Grad\", ([&] {\n        const scalar_t *bottom_data = top_grad.data_ptr<scalar_t>();\n        scalar_t *top_data = rtop_grad.data_ptr<scalar_t>();\n        const int dh = divideUP(channels, kTileDim);\n        const int dw = divideUP(output_height * output_width, kTileDim);\n        BatchTranspose2DCUDAKernel<scalar_t>\n            <<<batch_size * dh * dw, dim3(kTileDim, kBlockRows), 0, stream>>>(\n                batch_size, channels, output_height * output_width, dh, dw,\n                bottom_data, top_data);\n      }));\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"CARAFELaucherBackward_Feature\", ([&] {\n        const int num_kernels =\n            batch_size * output_height * output_width * THREADS_PER_PIXEL;\n        const scalar_t *top_diff = rtop_grad.data_ptr<scalar_t>();\n        const scalar_t *bottom_masks = masks.data_ptr<scalar_t>();\n        scalar_t *bottom_diff = rbottom_grad_hs.data_ptr<scalar_t>();\n\n        CARAFEBackward_Feature<scalar_t>\n            <<<divideUP(num_kernels, THREADS_PER_BLOCK), THREADS_PER_BLOCK, 0,\n               stream>>>(num_kernels, top_diff, bottom_masks, kernel_size,\n                         group_size, scale_factor, channels, input_height,\n                         input_width, output_height, output_width,\n                         mask_channels, bottom_diff);\n      }));\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"FeatureSum\", ([&] {\n        const int num_kernels =\n            batch_size * input_height * input_width * THREADS_PER_PIXEL;\n        const scalar_t *bottom_diff_hs = rbottom_grad_hs.data_ptr<scalar_t>();\n        scalar_t *bottom_diff = rbottom_grad.data_ptr<scalar_t>();\n\n        FeatureSum<scalar_t>\n            <<<divideUP(num_kernels, THREADS_PER_BLOCK), THREADS_PER_BLOCK, 0,\n               stream>>>(num_kernels, bottom_diff_hs, scale_factor, channels,\n                         input_height, input_width, bottom_diff);\n      }));\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"NHWC2NCHW_Bottom_Grad\", ([&] {\n        const scalar_t *bottom_data = rbottom_grad.data_ptr<scalar_t>();\n        scalar_t *top_data = bottom_grad.data_ptr<scalar_t>();\n        const int dh = divideUP(input_height * input_width, kTileDim);\n        const int dw = divideUP(channels, kTileDim);\n        BatchTranspose2DCUDAKernel<scalar_t>\n            <<<batch_size * dh * dw, dim3(kTileDim, kBlockRows), 0, stream>>>(\n                batch_size, input_height * input_width, channels, dh, dw,\n                bottom_data, top_data);\n      }));\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"CARAFELaucherBackward_Mask\", ([&] {\n        const int num_kernels = batch_size * output_height * output_width *\n                                mask_channels * WARP_SIZE;\n        const scalar_t *top_diff = rtop_grad.data_ptr<scalar_t>();\n        const scalar_t *bottom_data = rfeatures.data_ptr<scalar_t>();\n        scalar_t *mask_diff = rmask_grad.data_ptr<scalar_t>();\n\n        CARAFEBackward_Mask<scalar_t>\n            <<<divideUP(num_kernels, THREADS_PER_BLOCK), THREADS_PER_BLOCK, 0,\n               stream>>>(num_kernels, top_diff, bottom_data, kernel_size,\n                         group_size, scale_factor, channels, input_height,\n                         input_width, output_height, output_width,\n                         mask_channels, mask_diff);\n      }));\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"NHWC2NCHW_Mask_Grad\", ([&] {\n        const scalar_t *bottom_data = rmask_grad.data_ptr<scalar_t>();\n        scalar_t *top_data = mask_grad.data_ptr<scalar_t>();\n        const int dh = divideUP(output_height * output_width, kTileDim);\n        const int dw = divideUP(mask_channels, kTileDim);\n        BatchTranspose2DCUDAKernel<scalar_t>\n            <<<batch_size * dh * dw, dim3(kTileDim, kBlockRows), 0, stream>>>(\n                batch_size, output_height * output_width, mask_channels, dh, dw,\n                bottom_data, top_data);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/carafe_naive_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"carafe_naive_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid CARAFENAIVEForwardCUDAKernelLauncher(const Tensor features,\n                                          const Tensor masks, Tensor output,\n                                          const int kernel_size,\n                                          const int group_size,\n                                          const int scale_factor) {\n  int output_size = output.numel();\n  int channels = output.size(1);\n  int height = output.size(2);\n  int width = output.size(3);\n\n  at::cuda::CUDAGuard device_guard(features.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      features.scalar_type(), \"CARAFENAIVEForward\", ([&] {\n        carafe_naive_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, features.data_ptr<scalar_t>(),\n                masks.data_ptr<scalar_t>(), output.data_ptr<scalar_t>(),\n                kernel_size, group_size, scale_factor, channels, height, width);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid CARAFENAIVEBackwardCUDAKernelLauncher(\n    const Tensor top_grad, const Tensor features, const Tensor masks,\n    Tensor bottom_grad, Tensor mask_grad, const int kernel_size,\n    const int group_size, const int scale_factor) {\n  int output_size = top_grad.numel();\n  int channels = top_grad.size(1);\n  int height = top_grad.size(2);\n  int width = top_grad.size(3);\n\n  at::cuda::CUDAGuard device_guard(top_grad.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"CARAFENAIVEBackward\", ([&] {\n        carafe_naive_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, top_grad.data_ptr<scalar_t>(),\n                features.data_ptr<scalar_t>(), masks.data_ptr<scalar_t>(),\n                bottom_grad.data_ptr<scalar_t>(),\n                mask_grad.data_ptr<scalar_t>(), kernel_size, group_size,\n                scale_factor, channels, height, width);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/correlation_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n// Modified from\n// https://github.com/ClementPinard/Pytorch-Correlation-extension/blob/master/Correlation_Module/correlation_cuda_kernel.cu\n// Original licence: Under MIT License\n\n#include \"correlation_cuda.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid CorrelationForwardCUDAKernelLauncher(Tensor input1, Tensor input2,\n                                          Tensor output, int kH, int kW,\n                                          int patchH, int patchW, int padH,\n                                          int padW, int dilationH,\n                                          int dilationW, int dilation_patchH,\n                                          int dilation_patchW, int dH, int dW) {\n  const int batch_size = input1.size(0);\n  const int iH = input1.size(2);\n  const int iW = input1.size(3);\n  const int dilatedKH = (kH - 1) * dilationH + 1;\n  const int dilatedKW = (kW - 1) * dilationW + 1;\n\n  const auto oH = (iH + 2 * padH - dilatedKH) / dH + 1;\n  const auto oW = (iW + 2 * padW - dilatedKW) / dW + 1;\n\n  auto trInput1 = input1.permute({0, 2, 3, 1}).contiguous();\n  auto trInput2 = input2.permute({0, 2, 3, 1}).contiguous();\n\n  const int threads = THREADS_FORWARD;\n  const dim3 blocks(batch_size, oH, oW);\n\n  at::cuda::CUDAGuard device_guard(input1.device());\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input1.scalar_type(), \"correlation_forward_cuda\", ([&] {\n        TensorAcc4R trInput1_acc =\n            trInput1.packed_accessor32<scalar_t, 4, RestrictPtrTraits>();\n        TensorAcc4R trInput2_acc =\n            trInput2.packed_accessor32<scalar_t, 4, RestrictPtrTraits>();\n        TensorAcc5R output_acc =\n            output.packed_accessor32<scalar_t, 5, RestrictPtrTraits>();\n\n        correlation_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, at::cuda::getCurrentCUDAStream()>>>(\n                trInput1_acc, trInput2_acc, output_acc, kH, kW, patchH, patchW,\n                padH, padW, dilationH, dilationW, dilation_patchH,\n                dilation_patchW, dH, dW);\n      }));\n}\n\nvoid CorrelationBackwardCUDAKernelLauncher(\n    Tensor grad_output, Tensor input1, Tensor input2, Tensor grad_input1,\n    Tensor grad_input2, int kH, int kW, int patchH, int patchW, int padH,\n    int padW, int dilationH, int dilationW, int dilation_patchH,\n    int dilation_patchW, int dH, int dW) {\n  const int batch_size = input1.size(0);\n  const int iH = input1.size(2);\n  const int iW = input1.size(3);\n  const int C = input1.size(1);\n\n  const dim3 blocks(C, iH, iW);\n  const dim3 threads(THREADS_BACKWARD, THREADS_BACKWARD);\n\n  at::cuda::CUDAGuard device_guard(input1.device());\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input1.scalar_type(), \"correlation_backward_cuda\", ([&] {\n        TensorAcc4R input1_acc =\n            input1.packed_accessor32<scalar_t, 4, RestrictPtrTraits>();\n        TensorAcc4R input2_acc =\n            input2.packed_accessor32<scalar_t, 4, RestrictPtrTraits>();\n        TensorAcc4R grad_input1_acc =\n            grad_input1.packed_accessor32<scalar_t, 4, RestrictPtrTraits>();\n        TensorAcc4R grad_input2_acc =\n            grad_input2.packed_accessor32<scalar_t, 4, RestrictPtrTraits>();\n        TensorAcc5R grad_output_acc =\n            grad_output.packed_accessor32<scalar_t, 5, RestrictPtrTraits>();\n\n        for (int n = 0; n < batch_size; ++n) {\n          correlation_backward_cuda_kernel_input1<scalar_t>\n              <<<blocks, threads, 0, at::cuda::getCurrentCUDAStream()>>>(\n                  grad_output_acc, input2_acc, grad_input1_acc, kH, kW, patchH,\n                  patchW, padH, padW, dilationH, dilationW, dilation_patchH,\n                  dilation_patchW, dH, dW, n);\n        }\n\n        for (int n = 0; n < batch_size; ++n) {\n          correlation_backward_cuda_kernel_input2<scalar_t>\n              <<<blocks, threads, 0, at::cuda::getCurrentCUDAStream()>>>(\n                  grad_output_acc, input1_acc, grad_input2_acc, kH, kW, patchH,\n                  patchW, padH, padW, dilationH, dilationW, dilation_patchH,\n                  dilation_patchW, dH, dW, n);\n        }\n      }));\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/cudabind.cpp",
    "content": "#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid AssignScoreWithKForwardCUDAKernelLauncher(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& points, const Tensor& centers, const Tensor& scores,\n    const Tensor& knn_idx, Tensor& output);\n\nvoid AssignScoreWithKBackwardCUDAKernelLauncher(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& grad_out, const Tensor& points, const Tensor& centers,\n    const Tensor& scores, const Tensor& knn_idx, Tensor& grad_points,\n    Tensor& grad_centers, Tensor& grad_scores);\n\nvoid assign_score_withk_forward_cuda(int B, int N0, int N1, int M, int K, int O,\n                                     int aggregate, const Tensor& points,\n                                     const Tensor& centers,\n                                     const Tensor& scores,\n                                     const Tensor& knn_idx, Tensor& output) {\n  AssignScoreWithKForwardCUDAKernelLauncher(\n      B, N0, N1, M, K, O, aggregate, points, centers, scores, knn_idx, output);\n};\n\nvoid assign_score_withk_backward_cuda(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& grad_out, const Tensor& points, const Tensor& centers,\n    const Tensor& scores, const Tensor& knn_idx, Tensor& grad_points,\n    Tensor& grad_centers, Tensor& grad_scores) {\n  AssignScoreWithKBackwardCUDAKernelLauncher(\n      B, N0, N1, M, K, O, aggregate, grad_out, points, centers, scores, knn_idx,\n      grad_points, grad_centers, grad_scores);\n};\n\nvoid assign_score_withk_forward_impl(int B, int N0, int N1, int M, int K, int O,\n                                     int aggregate, const Tensor& points,\n                                     const Tensor& centers,\n                                     const Tensor& scores,\n                                     const Tensor& knn_idx, Tensor& output);\n\nvoid assign_score_withk_backward_impl(\n    int B, int N0, int N1, int M, int K, int O, int aggregate,\n    const Tensor& grad_out, const Tensor& points, const Tensor& centers,\n    const Tensor& scores, const Tensor& knn_idx, Tensor& grad_points,\n    Tensor& grad_centers, Tensor& grad_scores);\n\nREGISTER_DEVICE_IMPL(assign_score_withk_forward_impl, CUDA,\n                     assign_score_withk_forward_cuda);\nREGISTER_DEVICE_IMPL(assign_score_withk_backward_impl, CUDA,\n                     assign_score_withk_backward_cuda);\n\nvoid BallQueryForwardCUDAKernelLauncher(int b, int n, int m, float min_radius,\n                                        float max_radius, int nsample,\n                                        const Tensor new_xyz, const Tensor xyz,\n                                        Tensor idx);\n\nvoid ball_query_forward_cuda(int b, int n, int m, float min_radius,\n                             float max_radius, int nsample,\n                             const Tensor new_xyz, const Tensor xyz,\n                             Tensor idx) {\n  BallQueryForwardCUDAKernelLauncher(b, n, m, min_radius, max_radius, nsample,\n                                     new_xyz, xyz, idx);\n};\n\nvoid ball_query_forward_impl(int b, int n, int m, float min_radius,\n                             float max_radius, int nsample,\n                             const Tensor new_xyz, const Tensor xyz,\n                             Tensor idx);\nREGISTER_DEVICE_IMPL(ball_query_forward_impl, CUDA, ball_query_forward_cuda);\n\nvoid BBoxOverlapsCUDAKernelLauncher(const Tensor bboxes1, const Tensor bboxes2,\n                                    Tensor ious, const int mode,\n                                    const bool aligned, const int offset);\n\nvoid bbox_overlaps_cuda(const Tensor bboxes1, const Tensor bboxes2, Tensor ious,\n                        const int mode, const bool aligned, const int offset) {\n  BBoxOverlapsCUDAKernelLauncher(bboxes1, bboxes2, ious, mode, aligned, offset);\n}\n\nvoid bbox_overlaps_impl(const Tensor bboxes1, const Tensor bboxes2, Tensor ious,\n                        const int mode, const bool aligned, const int offset);\nREGISTER_DEVICE_IMPL(bbox_overlaps_impl, CUDA, bbox_overlaps_cuda);\n\nvoid BorderAlignForwardCUDAKernelLauncher(const Tensor& input,\n                                          const Tensor& boxes, Tensor output,\n                                          Tensor argmax_idx,\n                                          const int pool_size);\n\nvoid BorderAlignBackwardCUDAKernelLauncher(const Tensor& grad_output,\n                                           const Tensor& boxes,\n                                           const Tensor& argmax_idx,\n                                           Tensor grad_input,\n                                           const int pool_size);\n\nvoid border_align_forward_cuda(const Tensor& input, const Tensor& boxes,\n                               Tensor output, Tensor argmax_idx,\n                               const int pool_size) {\n  BorderAlignForwardCUDAKernelLauncher(input, boxes, output, argmax_idx,\n                                       pool_size);\n}\n\nvoid border_align_backward_cuda(const Tensor& grad_output, const Tensor& boxes,\n                                const Tensor& argmax_idx, Tensor grad_input,\n                                const int pool_size) {\n  BorderAlignBackwardCUDAKernelLauncher(grad_output, boxes, argmax_idx,\n                                        grad_input, pool_size);\n}\n\nvoid border_align_forward_impl(const Tensor& input, const Tensor& boxes,\n                               Tensor output, Tensor argmax_idx,\n                               const int pool_size);\n\nvoid border_align_backward_impl(const Tensor& grad_output, const Tensor& boxes,\n                                const Tensor& argmax_idx, Tensor grad_input,\n                                const int pool_size);\n\nREGISTER_DEVICE_IMPL(border_align_forward_impl, CUDA,\n                     border_align_forward_cuda);\nREGISTER_DEVICE_IMPL(border_align_backward_impl, CUDA,\n                     border_align_backward_cuda);\n\nvoid box_iou_rotated_cuda(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                          const int mode_flag, const bool aligned);\n\nvoid box_iou_rotated_impl(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                          const int mode_flag, const bool aligned);\nREGISTER_DEVICE_IMPL(box_iou_rotated_impl, CUDA, box_iou_rotated_cuda);\n\nvoid CARAFEForwardCUDAKernelLauncher(const Tensor features, const Tensor masks,\n                                     Tensor rfeatures, Tensor routput,\n                                     Tensor rmasks, Tensor output,\n                                     const int kernel_size,\n                                     const int group_size,\n                                     const int scale_factor);\n\nvoid CARAFEBackwardCUDAKernelLauncher(\n    const Tensor top_grad, const Tensor rfeatures, const Tensor masks,\n    Tensor rtop_grad, Tensor rbottom_grad_hs, Tensor rbottom_grad,\n    Tensor rmask_grad, Tensor bottom_grad, Tensor mask_grad,\n    const int kernel_size, const int group_size, const int scale_factor);\n\nvoid carafe_forward_cuda(Tensor features, Tensor masks, Tensor rfeatures,\n                         Tensor routput, Tensor rmasks, Tensor output,\n                         int kernel_size, int group_size, int scale_factor) {\n  CARAFEForwardCUDAKernelLauncher(features, masks, rfeatures, routput, rmasks,\n                                  output, kernel_size, group_size,\n                                  scale_factor);\n}\n\nvoid carafe_backward_cuda(Tensor top_grad, Tensor rfeatures, Tensor masks,\n                          Tensor rtop_grad, Tensor rbottom_grad_hs,\n                          Tensor rbottom_grad, Tensor rmask_grad,\n                          Tensor bottom_grad, Tensor mask_grad, int kernel_size,\n                          int group_size, int scale_factor) {\n  CARAFEBackwardCUDAKernelLauncher(top_grad, rfeatures, masks, rtop_grad,\n                                   rbottom_grad_hs, rbottom_grad, rmask_grad,\n                                   bottom_grad, mask_grad, kernel_size,\n                                   group_size, scale_factor);\n}\n\nvoid carafe_forward_impl(Tensor features, Tensor masks, Tensor rfeatures,\n                         Tensor routput, Tensor rmasks, Tensor output,\n                         int kernel_size, int group_size, int scale_factor);\n\nvoid carafe_backward_impl(Tensor top_grad, Tensor rfeatures, Tensor masks,\n                          Tensor rtop_grad, Tensor rbottom_grad_hs,\n                          Tensor rbottom_grad, Tensor rmask_grad,\n                          Tensor bottom_grad, Tensor mask_grad, int kernel_size,\n                          int group_size, int scale_factor);\n\nREGISTER_DEVICE_IMPL(carafe_forward_impl, CUDA, carafe_forward_cuda);\nREGISTER_DEVICE_IMPL(carafe_backward_impl, CUDA, carafe_backward_cuda);\n\nvoid CARAFENAIVEForwardCUDAKernelLauncher(const Tensor features,\n                                          const Tensor masks, Tensor output,\n                                          const int kernel_size,\n                                          const int group_size,\n                                          const int scale_factor);\n\nvoid CARAFENAIVEBackwardCUDAKernelLauncher(\n    const Tensor top_grad, const Tensor features, const Tensor masks,\n    Tensor bottom_grad, Tensor mask_grad, const int kernel_size,\n    const int group_size, const int scale_factor);\n\nvoid carafe_naive_forward_cuda(Tensor features, Tensor masks, Tensor output,\n                               int kernel_size, int group_size,\n                               int scale_factor) {\n  CARAFENAIVEForwardCUDAKernelLauncher(features, masks, output, kernel_size,\n                                       group_size, scale_factor);\n}\n\nvoid carafe_naive_backward_cuda(Tensor top_grad, Tensor features, Tensor masks,\n                                Tensor bottom_grad, Tensor mask_grad,\n                                int kernel_size, int group_size,\n                                int scale_factor) {\n  CARAFENAIVEBackwardCUDAKernelLauncher(top_grad, features, masks, bottom_grad,\n                                        mask_grad, kernel_size, group_size,\n                                        scale_factor);\n}\nvoid carafe_naive_forward_impl(Tensor features, Tensor masks, Tensor output,\n                               int kernel_size, int group_size,\n                               int scale_factor);\n\nvoid carafe_naive_backward_impl(Tensor top_grad, Tensor features, Tensor masks,\n                                Tensor bottom_grad, Tensor mask_grad,\n                                int kernel_size, int group_size,\n                                int scale_factor);\n\nREGISTER_DEVICE_IMPL(carafe_naive_forward_impl, CUDA,\n                     carafe_naive_forward_cuda);\nREGISTER_DEVICE_IMPL(carafe_naive_backward_impl, CUDA,\n                     carafe_naive_backward_cuda);\n\nvoid CorrelationForwardCUDAKernelLauncher(Tensor input1, Tensor input2,\n                                          Tensor output, int kH, int kW,\n                                          int patchH, int patchW, int padH,\n                                          int padW, int dilationH,\n                                          int dilationW, int dilation_patchH,\n                                          int dilation_patchW, int dH, int dW);\n\nvoid CorrelationBackwardCUDAKernelLauncher(Tensor grad_output, Tensor input1,\n                                           Tensor input2, Tensor grad_input1,\n                                           Tensor grad_input2, int kH, int kW,\n                                           int patchH, int patchW, int padH,\n                                           int padW, int dilationH,\n                                           int dilationW, int dilation_patchH,\n                                           int dilation_patchW, int dH, int dW);\n\nvoid correlation_forward_cuda(Tensor input1, Tensor input2, Tensor output,\n                              int kH, int kW, int patchH, int patchW, int padH,\n                              int padW, int dilationH, int dilationW,\n                              int dilation_patchH, int dilation_patchW, int dH,\n                              int dW) {\n  CorrelationForwardCUDAKernelLauncher(\n      input1, input2, output, kH, kW, patchH, patchW, padH, padW, dilationH,\n      dilationW, dilation_patchH, dilation_patchW, dH, dW);\n}\n\nvoid correlation_backward_cuda(Tensor grad_output, Tensor input1, Tensor input2,\n                               Tensor grad_input1, Tensor grad_input2, int kH,\n                               int kW, int patchH, int patchW, int padH,\n                               int padW, int dilationH, int dilationW,\n                               int dilation_patchH, int dilation_patchW, int dH,\n                               int dW) {\n  CorrelationBackwardCUDAKernelLauncher(\n      grad_output, input1, input2, grad_input1, grad_input2, kH, kW, patchH,\n      patchW, padH, padW, dilationH, dilationW, dilation_patchH,\n      dilation_patchW, dH, dW);\n}\n\nvoid correlation_forward_impl(Tensor input1, Tensor input2, Tensor output,\n                              int kH, int kW, int patchH, int patchW, int padH,\n                              int padW, int dilationH, int dilationW,\n                              int dilation_patchH, int dilation_patchW, int dH,\n                              int dW);\n\nvoid correlation_backward_impl(Tensor grad_output, Tensor input1, Tensor input2,\n                               Tensor grad_input1, Tensor grad_input2, int kH,\n                               int kW, int patchH, int patchW, int padH,\n                               int padW, int dilationH, int dilationW,\n                               int dilation_patchH, int dilation_patchW, int dH,\n                               int dW);\n\nREGISTER_DEVICE_IMPL(correlation_forward_impl, CUDA, correlation_forward_cuda);\nREGISTER_DEVICE_IMPL(correlation_backward_impl, CUDA,\n                     correlation_backward_cuda);\n\nvoid deformable_im2col_cuda(Tensor data_im, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor data_col);\n\nvoid deformable_col2im_cuda(Tensor data_col, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor grad_im);\n\nvoid deformable_col2im_coord_cuda(\n    Tensor data_col, Tensor data_im, Tensor data_offset, const int channels,\n    const int height, const int width, const int ksize_h, const int ksize_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int parallel_imgs,\n    const int deformable_group, Tensor grad_offset);\n\nvoid deformable_im2col_impl(Tensor data_im, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor data_col);\n\nvoid deformable_col2im_impl(Tensor data_col, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor grad_im);\n\nvoid deformable_col2im_coord_impl(\n    Tensor data_col, Tensor data_im, Tensor data_offset, const int channels,\n    const int height, const int width, const int ksize_h, const int ksize_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int parallel_imgs,\n    const int deformable_group, Tensor grad_offset);\n\nREGISTER_DEVICE_IMPL(deformable_im2col_impl, CUDA, deformable_im2col_cuda);\nREGISTER_DEVICE_IMPL(deformable_col2im_impl, CUDA, deformable_col2im_cuda);\nREGISTER_DEVICE_IMPL(deformable_col2im_coord_impl, CUDA,\n                     deformable_col2im_coord_cuda);\n\nvoid DeformRoIPoolForwardCUDAKernelLauncher(Tensor input, Tensor rois,\n                                            Tensor offset, Tensor output,\n                                            int pooled_height, int pooled_width,\n                                            float spatial_scale,\n                                            int sampling_ratio, float gamma);\n\nvoid DeformRoIPoolBackwardCUDAKernelLauncher(\n    Tensor grad_output, Tensor input, Tensor rois, Tensor offset,\n    Tensor grad_input, Tensor grad_offset, int pooled_height, int pooled_width,\n    float spatial_scale, int sampling_ratio, float gamma);\n\nvoid deform_roi_pool_forward_cuda(Tensor input, Tensor rois, Tensor offset,\n                                  Tensor output, int pooled_height,\n                                  int pooled_width, float spatial_scale,\n                                  int sampling_ratio, float gamma) {\n  DeformRoIPoolForwardCUDAKernelLauncher(input, rois, offset, output,\n                                         pooled_height, pooled_width,\n                                         spatial_scale, sampling_ratio, gamma);\n}\n\nvoid deform_roi_pool_backward_cuda(Tensor grad_output, Tensor input,\n                                   Tensor rois, Tensor offset,\n                                   Tensor grad_input, Tensor grad_offset,\n                                   int pooled_height, int pooled_width,\n                                   float spatial_scale, int sampling_ratio,\n                                   float gamma) {\n  DeformRoIPoolBackwardCUDAKernelLauncher(\n      grad_output, input, rois, offset, grad_input, grad_offset, pooled_height,\n      pooled_width, spatial_scale, sampling_ratio, gamma);\n}\n\nvoid deform_roi_pool_forward_impl(Tensor input, Tensor rois, Tensor offset,\n                                  Tensor output, int pooled_height,\n                                  int pooled_width, float spatial_scale,\n                                  int sampling_ratio, float gamma);\n\nvoid deform_roi_pool_backward_impl(Tensor grad_output, Tensor input,\n                                   Tensor rois, Tensor offset,\n                                   Tensor grad_input, Tensor grad_offset,\n                                   int pooled_height, int pooled_width,\n                                   float spatial_scale, int sampling_ratio,\n                                   float gamma);\n\nREGISTER_DEVICE_IMPL(deform_roi_pool_forward_impl, CUDA,\n                     deform_roi_pool_forward_cuda);\nREGISTER_DEVICE_IMPL(deform_roi_pool_backward_impl, CUDA,\n                     deform_roi_pool_backward_cuda);\n\nvoid SigmoidFocalLossForwardCUDAKernelLauncher(Tensor input, Tensor target,\n                                               Tensor weight, Tensor output,\n                                               const float gamma,\n                                               const float alpha);\n\nvoid SigmoidFocalLossBackwardCUDAKernelLauncher(Tensor input, Tensor target,\n                                                Tensor weight,\n                                                Tensor grad_input,\n                                                const float gamma,\n                                                const float alpha);\n\nvoid SoftmaxFocalLossForwardCUDAKernelLauncher(Tensor softmax, Tensor target,\n                                               Tensor weight, Tensor output,\n                                               const float gamma,\n                                               const float alpha);\n\nvoid SoftmaxFocalLossBackwardCUDAKernelLauncher(Tensor softmax, Tensor target,\n                                                Tensor weight, Tensor buff,\n                                                Tensor grad_input,\n                                                const float gamma,\n                                                const float alpha);\n\nvoid sigmoid_focal_loss_forward_cuda(Tensor input, Tensor target, Tensor weight,\n                                     Tensor output, float gamma, float alpha) {\n  SigmoidFocalLossForwardCUDAKernelLauncher(input, target, weight, output,\n                                            gamma, alpha);\n}\n\nvoid sigmoid_focal_loss_backward_cuda(Tensor input, Tensor target,\n                                      Tensor weight, Tensor grad_input,\n                                      float gamma, float alpha) {\n  SigmoidFocalLossBackwardCUDAKernelLauncher(input, target, weight, grad_input,\n                                             gamma, alpha);\n}\n\nvoid softmax_focal_loss_forward_cuda(Tensor input, Tensor target, Tensor weight,\n                                     Tensor output, float gamma, float alpha) {\n  SoftmaxFocalLossForwardCUDAKernelLauncher(input, target, weight, output,\n                                            gamma, alpha);\n}\n\nvoid softmax_focal_loss_backward_cuda(Tensor input, Tensor target,\n                                      Tensor weight, Tensor buff,\n                                      Tensor grad_input, float gamma,\n                                      float alpha) {\n  SoftmaxFocalLossBackwardCUDAKernelLauncher(input, target, weight, buff,\n                                             grad_input, gamma, alpha);\n}\n\nvoid sigmoid_focal_loss_forward_impl(Tensor input, Tensor target, Tensor weight,\n                                     Tensor output, float gamma, float alpha);\n\nvoid sigmoid_focal_loss_backward_impl(Tensor input, Tensor target,\n                                      Tensor weight, Tensor grad_input,\n                                      float gamma, float alpha);\n\nvoid softmax_focal_loss_forward_impl(Tensor input, Tensor target, Tensor weight,\n                                     Tensor output, float gamma, float alpha);\n\nvoid softmax_focal_loss_backward_impl(Tensor input, Tensor target,\n                                      Tensor weight, Tensor buff,\n                                      Tensor grad_input, float gamma,\n                                      float alpha);\n\nREGISTER_DEVICE_IMPL(sigmoid_focal_loss_forward_impl, CUDA,\n                     sigmoid_focal_loss_forward_cuda);\nREGISTER_DEVICE_IMPL(sigmoid_focal_loss_backward_impl, CUDA,\n                     sigmoid_focal_loss_backward_cuda);\nREGISTER_DEVICE_IMPL(softmax_focal_loss_forward_impl, CUDA,\n                     softmax_focal_loss_forward_cuda);\nREGISTER_DEVICE_IMPL(softmax_focal_loss_backward_impl, CUDA,\n                     softmax_focal_loss_backward_cuda);\n\nvoid FurthestPointSamplingForwardCUDAKernelLauncher(int b, int n, int m,\n                                                    const float* dataset,\n                                                    float* temp, int* idxs);\n\nvoid FurthestPointSamplingWithDistForwardCUDAKernelLauncher(\n    int b, int n, int m, const float* dataset, float* temp, int* idxs);\n\nvoid furthest_point_sampling_forward_cuda(Tensor points_tensor,\n                                          Tensor temp_tensor, Tensor idx_tensor,\n                                          int b, int n, int m) {\n  const float* dataset = points_tensor.data_ptr<float>();\n  float* temp = temp_tensor.data_ptr<float>();\n  int* idxs = idx_tensor.data_ptr<int>();\n  FurthestPointSamplingForwardCUDAKernelLauncher(b, n, m, dataset, temp, idxs);\n}\n\nvoid furthest_point_sampling_with_dist_forward_cuda(Tensor points_tensor,\n                                                    Tensor temp_tensor,\n                                                    Tensor idx_tensor, int b,\n                                                    int n, int m) {\n  const float* dataset = points_tensor.data_ptr<float>();\n  float* temp = temp_tensor.data_ptr<float>();\n  int* idxs = idx_tensor.data_ptr<int>();\n  FurthestPointSamplingWithDistForwardCUDAKernelLauncher(b, n, m, dataset, temp,\n                                                         idxs);\n}\n\nvoid furthest_point_sampling_forward_impl(Tensor points_tensor,\n                                          Tensor temp_tensor, Tensor idx_tensor,\n                                          int b, int n, int m);\n\nvoid furthest_point_sampling_with_dist_forward_impl(Tensor points_tensor,\n                                                    Tensor temp_tensor,\n                                                    Tensor idx_tensor, int b,\n                                                    int n, int m);\n\nREGISTER_DEVICE_IMPL(furthest_point_sampling_forward_impl, CUDA,\n                     furthest_point_sampling_forward_cuda);\nREGISTER_DEVICE_IMPL(furthest_point_sampling_with_dist_forward_impl, CUDA,\n                     furthest_point_sampling_with_dist_forward_cuda);\n\ntorch::Tensor fused_bias_leakyrelu_op(const torch::Tensor& input,\n                                      const torch::Tensor& bias,\n                                      const torch::Tensor& refer, int act,\n                                      int grad, float alpha, float scale);\n\ntorch::Tensor fused_bias_leakyrelu_op_impl(const torch::Tensor& input,\n                                           const torch::Tensor& bias,\n                                           const torch::Tensor& refer, int act,\n                                           int grad, float alpha, float scale);\nREGISTER_DEVICE_IMPL(fused_bias_leakyrelu_op_impl, CUDA,\n                     fused_bias_leakyrelu_op);\n\nvoid GatherPointsForwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                           const Tensor points,\n                                           const Tensor idx, Tensor out);\n\nvoid GatherPointsBackwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                            const Tensor grad_out,\n                                            const Tensor idx,\n                                            Tensor grad_points);\n\nvoid gather_points_forward_cuda(int b, int c, int n, int npoints,\n                                const Tensor points, const Tensor idx,\n                                Tensor out) {\n  GatherPointsForwardCUDAKernelLauncher(b, c, n, npoints, points, idx, out);\n};\n\nvoid gather_points_backward_cuda(int b, int c, int n, int npoints,\n                                 const Tensor grad_out, const Tensor idx,\n                                 Tensor grad_points) {\n  GatherPointsBackwardCUDAKernelLauncher(b, c, n, npoints, grad_out, idx,\n                                         grad_points);\n};\n\nvoid gather_points_forward_impl(int b, int c, int n, int npoints,\n                                const Tensor points, const Tensor idx,\n                                Tensor out);\n\nvoid gather_points_backward_impl(int b, int c, int n, int npoints,\n                                 const Tensor grad_out, const Tensor idx,\n                                 Tensor grad_points);\n\nREGISTER_DEVICE_IMPL(gather_points_forward_impl, CUDA,\n                     gather_points_forward_cuda);\nREGISTER_DEVICE_IMPL(gather_points_backward_impl, CUDA,\n                     gather_points_backward_cuda);\n\nvoid GroupPointsForwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                          int nsample, const Tensor points,\n                                          const Tensor idx, Tensor out);\n\nvoid GroupPointsBackwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                           int nsample, const Tensor grad_out,\n                                           const Tensor idx,\n                                           Tensor grad_points);\n\nvoid group_points_forward_cuda(int b, int c, int n, int npoints, int nsample,\n                               const Tensor points, const Tensor idx,\n                               Tensor out) {\n  GroupPointsForwardCUDAKernelLauncher(b, c, n, npoints, nsample, points, idx,\n                                       out);\n};\n\nvoid group_points_backward_cuda(int b, int c, int n, int npoints, int nsample,\n                                const Tensor grad_out, const Tensor idx,\n                                Tensor grad_points) {\n  GroupPointsBackwardCUDAKernelLauncher(b, c, n, npoints, nsample, grad_out,\n                                        idx, grad_points);\n};\n\nvoid group_points_forward_impl(int b, int c, int n, int npoints, int nsample,\n                               const Tensor points, const Tensor idx,\n                               Tensor out);\n\nvoid group_points_backward_impl(int b, int c, int n, int npoints, int nsample,\n                                const Tensor grad_out, const Tensor idx,\n                                Tensor grad_points);\n\nREGISTER_DEVICE_IMPL(group_points_forward_impl, CUDA,\n                     group_points_forward_cuda);\nREGISTER_DEVICE_IMPL(group_points_backward_impl, CUDA,\n                     group_points_backward_cuda);\n\nvoid IoU3DBoxesOverlapBevForwardCUDAKernelLauncher(const int num_a,\n                                                   const Tensor boxes_a,\n                                                   const int num_b,\n                                                   const Tensor boxes_b,\n                                                   Tensor ans_overlap);\n\nvoid IoU3DBoxesIoUBevForwardCUDAKernelLauncher(const int num_a,\n                                               const Tensor boxes_a,\n                                               const int num_b,\n                                               const Tensor boxes_b,\n                                               Tensor ans_iou);\n\nvoid IoU3DNMSForwardCUDAKernelLauncher(const Tensor boxes,\n                                       unsigned long long* mask, int boxes_num,\n                                       float nms_overlap_thresh);\n\nvoid IoU3DNMSNormalForwardCUDAKernelLauncher(const Tensor boxes,\n                                             unsigned long long* mask,\n                                             int boxes_num,\n                                             float nms_overlap_thresh);\n\nvoid iou3d_boxes_overlap_bev_forward_cuda(const int num_a, const Tensor boxes_a,\n                                          const int num_b, const Tensor boxes_b,\n                                          Tensor ans_overlap) {\n  IoU3DBoxesOverlapBevForwardCUDAKernelLauncher(num_a, boxes_a, num_b, boxes_b,\n                                                ans_overlap);\n};\n\nvoid iou3d_boxes_iou_bev_forward_cuda(const int num_a, const Tensor boxes_a,\n                                      const int num_b, const Tensor boxes_b,\n                                      Tensor ans_iou) {\n  IoU3DBoxesIoUBevForwardCUDAKernelLauncher(num_a, boxes_a, num_b, boxes_b,\n                                            ans_iou);\n};\n\nvoid iou3d_nms_forward_cuda(const Tensor boxes, unsigned long long* mask,\n                            int boxes_num, float nms_overlap_thresh) {\n  IoU3DNMSForwardCUDAKernelLauncher(boxes, mask, boxes_num, nms_overlap_thresh);\n};\n\nvoid iou3d_nms_normal_forward_cuda(const Tensor boxes, unsigned long long* mask,\n                                   int boxes_num, float nms_overlap_thresh) {\n  IoU3DNMSNormalForwardCUDAKernelLauncher(boxes, mask, boxes_num,\n                                          nms_overlap_thresh);\n};\n\nvoid iou3d_boxes_overlap_bev_forward_impl(const int num_a, const Tensor boxes_a,\n                                          const int num_b, const Tensor boxes_b,\n                                          Tensor ans_overlap);\n\nvoid iou3d_boxes_iou_bev_forward_impl(const int num_a, const Tensor boxes_a,\n                                      const int num_b, const Tensor boxes_b,\n                                      Tensor ans_iou);\n\nvoid iou3d_nms_forward_impl(const Tensor boxes, unsigned long long* mask,\n                            int boxes_num, float nms_overlap_thresh);\n\nvoid iou3d_nms_normal_forward_impl(const Tensor boxes, unsigned long long* mask,\n                                   int boxes_num, float nms_overlap_thresh);\n\nREGISTER_DEVICE_IMPL(iou3d_boxes_overlap_bev_forward_impl, CUDA,\n                     iou3d_boxes_overlap_bev_forward_cuda);\nREGISTER_DEVICE_IMPL(iou3d_boxes_iou_bev_forward_impl, CUDA,\n                     iou3d_boxes_iou_bev_forward_cuda);\nREGISTER_DEVICE_IMPL(iou3d_nms_forward_impl, CUDA, iou3d_nms_forward_cuda);\nREGISTER_DEVICE_IMPL(iou3d_nms_normal_forward_impl, CUDA,\n                     iou3d_nms_normal_forward_cuda);\n\nvoid KNNForwardCUDAKernelLauncher(int b, int n, int m, int nsample,\n                                  const Tensor xyz, const Tensor new_xyz,\n                                  Tensor idx, Tensor dist2);\n\nvoid knn_forward_cuda(int b, int n, int m, int nsample, const Tensor xyz,\n                      const Tensor new_xyz, Tensor idx, Tensor dist2) {\n  KNNForwardCUDAKernelLauncher(b, n, m, nsample, xyz, new_xyz, idx, dist2);\n}\n\nvoid knn_forward_impl(int b, int n, int m, int nsample, const Tensor xyz,\n                      const Tensor new_xyz, Tensor idx, Tensor dist2);\nREGISTER_DEVICE_IMPL(knn_forward_impl, CUDA, knn_forward_cuda);\n\nvoid MaskedIm2colForwardCUDAKernelLauncher(const Tensor bottom_data,\n                                           const Tensor mask_h_idx,\n                                           const Tensor mask_w_idx,\n                                           Tensor top_data, const int kernel_h,\n                                           const int kernel_w, const int pad_h,\n                                           const int pad_w);\n\nvoid MaskedCol2imForwardCUDAKernelLauncher(const Tensor bottom_data,\n                                           const Tensor mask_h_idx,\n                                           const Tensor mask_w_idx,\n                                           Tensor top_data, const int height,\n                                           const int width, const int channels);\n\nvoid masked_im2col_forward_cuda(const Tensor im, const Tensor mask_h_idx,\n                                const Tensor mask_w_idx, Tensor col,\n                                const int kernel_h, const int kernel_w,\n                                const int pad_h, const int pad_w) {\n  // im: (n, ic, h, w), kernel size (kh, kw)\n  // kernel: (oc, ic * kh * kw), col: (kh * kw * ic, ow * oh)\n  MaskedIm2colForwardCUDAKernelLauncher(im, mask_h_idx, mask_w_idx, col,\n                                        kernel_h, kernel_w, pad_h, pad_w);\n}\n\nvoid masked_col2im_forward_cuda(const Tensor col, const Tensor mask_h_idx,\n                                const Tensor mask_w_idx, Tensor im, int height,\n                                int width, int channels) {\n  // im: (n, ic, h, w), kernel size (kh, kw)\n  // kernel: (oc, ic * kh * kh), col: (kh * kw * ic, ow * oh)\n  MaskedCol2imForwardCUDAKernelLauncher(col, mask_h_idx, mask_w_idx, im, height,\n                                        width, channels);\n}\n\nvoid masked_im2col_forward_impl(const Tensor im, const Tensor mask_h_idx,\n                                const Tensor mask_w_idx, Tensor col,\n                                const int kernel_h, const int kernel_w,\n                                const int pad_h, const int pad_w);\n\nvoid masked_col2im_forward_impl(const Tensor col, const Tensor mask_h_idx,\n                                const Tensor mask_w_idx, Tensor im, int height,\n                                int width, int channels);\n\nREGISTER_DEVICE_IMPL(masked_im2col_forward_impl, CUDA,\n                     masked_im2col_forward_cuda);\nREGISTER_DEVICE_IMPL(masked_col2im_forward_impl, CUDA,\n                     masked_col2im_forward_cuda);\n\nvoid modulated_deformable_im2col_cuda(\n    const Tensor data_im, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor data_col);\n\nvoid modulated_deformable_col2im_cuda(\n    const Tensor data_col, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor grad_im);\n\nvoid modulated_deformable_col2im_coord_cuda(\n    const Tensor data_col, const Tensor data_im, const Tensor data_offset,\n    const Tensor data_mask, const int batch_size, const int channels,\n    const int height_im, const int width_im, const int height_col,\n    const int width_col, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int deformable_group,\n    Tensor grad_offset, Tensor grad_mask);\n\nvoid modulated_deformable_im2col_impl(\n    const Tensor data_im, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor data_col);\n\nvoid modulated_deformable_col2im_impl(\n    const Tensor data_col, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor grad_im);\n\nvoid modulated_deformable_col2im_coord_impl(\n    const Tensor data_col, const Tensor data_im, const Tensor data_offset,\n    const Tensor data_mask, const int batch_size, const int channels,\n    const int height_im, const int width_im, const int height_col,\n    const int width_col, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int deformable_group,\n    Tensor grad_offset, Tensor grad_mask);\n\nREGISTER_DEVICE_IMPL(modulated_deformable_im2col_impl, CUDA,\n                     modulated_deformable_im2col_cuda);\nREGISTER_DEVICE_IMPL(modulated_deformable_col2im_impl, CUDA,\n                     modulated_deformable_col2im_cuda);\nREGISTER_DEVICE_IMPL(modulated_deformable_col2im_coord_impl, CUDA,\n                     modulated_deformable_col2im_coord_cuda);\n\nTensor ms_deform_attn_cuda_forward(const Tensor& value,\n                                   const Tensor& spatial_shapes,\n                                   const Tensor& level_start_index,\n                                   const Tensor& sampling_loc,\n                                   const Tensor& attn_weight,\n                                   const int im2col_step);\n\nvoid ms_deform_attn_cuda_backward(\n    const Tensor& value, const Tensor& spatial_shapes,\n    const Tensor& level_start_index, const Tensor& sampling_loc,\n    const Tensor& attn_weight, const Tensor& grad_output, Tensor& grad_value,\n    Tensor& grad_sampling_loc, Tensor& grad_attn_weight, const int im2col_step);\n\nTensor ms_deform_attn_impl_forward(const Tensor& value,\n                                   const Tensor& spatial_shapes,\n                                   const Tensor& level_start_index,\n                                   const Tensor& sampling_loc,\n                                   const Tensor& attn_weight,\n                                   const int im2col_step);\n\nvoid ms_deform_attn_impl_backward(\n    const Tensor& value, const Tensor& spatial_shapes,\n    const Tensor& level_start_index, const Tensor& sampling_loc,\n    const Tensor& attn_weight, const Tensor& grad_output, Tensor& grad_value,\n    Tensor& grad_sampling_loc, Tensor& grad_attn_weight, const int im2col_step);\n\nREGISTER_DEVICE_IMPL(ms_deform_attn_impl_forward, CUDA,\n                     ms_deform_attn_cuda_forward);\nREGISTER_DEVICE_IMPL(ms_deform_attn_impl_backward, CUDA,\n                     ms_deform_attn_cuda_backward);\n\nTensor NMSCUDAKernelLauncher(Tensor boxes, Tensor scores, float iou_threshold,\n                             int offset);\n\nTensor nms_cuda(Tensor boxes, Tensor scores, float iou_threshold, int offset) {\n  return NMSCUDAKernelLauncher(boxes, scores, iou_threshold, offset);\n}\n\nTensor nms_impl(Tensor boxes, Tensor scores, float iou_threshold, int offset);\nREGISTER_DEVICE_IMPL(nms_impl, CUDA, nms_cuda);\n\nvoid PointsInBoxesPartForwardCUDAKernelLauncher(int batch_size, int boxes_num,\n                                                int pts_num, const Tensor boxes,\n                                                const Tensor pts,\n                                                Tensor box_idx_of_points);\n\nvoid PointsInBoxesAllForwardCUDAKernelLauncher(int batch_size, int boxes_num,\n                                               int pts_num, const Tensor boxes,\n                                               const Tensor pts,\n                                               Tensor box_idx_of_points);\n\nvoid points_in_boxes_part_forward_cuda(int batch_size, int boxes_num,\n                                       int pts_num, const Tensor boxes,\n                                       const Tensor pts,\n                                       Tensor box_idx_of_points) {\n  PointsInBoxesPartForwardCUDAKernelLauncher(batch_size, boxes_num, pts_num,\n                                             boxes, pts, box_idx_of_points);\n};\n\nvoid points_in_boxes_all_forward_cuda(int batch_size, int boxes_num,\n                                      int pts_num, const Tensor boxes,\n                                      const Tensor pts,\n                                      Tensor box_idx_of_points) {\n  PointsInBoxesAllForwardCUDAKernelLauncher(batch_size, boxes_num, pts_num,\n                                            boxes, pts, box_idx_of_points);\n};\n\nvoid points_in_boxes_part_forward_impl(int batch_size, int boxes_num,\n                                       int pts_num, const Tensor boxes,\n                                       const Tensor pts,\n                                       Tensor box_idx_of_points);\n\nvoid points_in_boxes_all_forward_impl(int batch_size, int boxes_num,\n                                      int pts_num, const Tensor boxes,\n                                      const Tensor pts,\n                                      Tensor box_idx_of_points);\nREGISTER_DEVICE_IMPL(points_in_boxes_part_forward_impl, CUDA,\n                     points_in_boxes_part_forward_cuda);\nREGISTER_DEVICE_IMPL(points_in_boxes_all_forward_impl, CUDA,\n                     points_in_boxes_all_forward_cuda);\n\nvoid PSAMaskForwardCUDAKernelLauncher(const int psa_type, const Tensor input,\n                                      Tensor output, const int num_,\n                                      const int h_feature, const int w_feature,\n                                      const int h_mask, const int w_mask,\n                                      const int half_h_mask,\n                                      const int half_w_mask);\n\nvoid PSAMaskBackwardCUDAKernelLauncher(\n    const int psa_type, const Tensor grad_output, Tensor grad_input,\n    const int num_, const int h_feature, const int w_feature, const int h_mask,\n    const int w_mask, const int half_h_mask, const int half_w_mask);\n\nvoid psamask_forward_cuda(const int psa_type, const Tensor input, Tensor output,\n                          const int num_, const int h_feature,\n                          const int w_feature, const int h_mask,\n                          const int w_mask, const int half_h_mask,\n                          const int half_w_mask) {\n  PSAMaskForwardCUDAKernelLauncher(psa_type, input, output, num_, h_feature,\n                                   w_feature, h_mask, w_mask, half_h_mask,\n                                   half_w_mask);\n}\n\nvoid psamask_backward_cuda(const int psa_type, const Tensor grad_output,\n                           Tensor grad_input, const int num_,\n                           const int h_feature, const int w_feature,\n                           const int h_mask, const int w_mask,\n                           const int half_h_mask, const int half_w_mask) {\n  PSAMaskBackwardCUDAKernelLauncher(psa_type, grad_output, grad_input, num_,\n                                    h_feature, w_feature, h_mask, w_mask,\n                                    half_h_mask, half_w_mask);\n}\n\nvoid psamask_forward_impl(const int psa_type, const Tensor input, Tensor output,\n                          const int num_, const int h_feature,\n                          const int w_feature, const int h_mask,\n                          const int w_mask, const int half_h_mask,\n                          const int half_w_mask);\n\nvoid psamask_backward_impl(const int psa_type, const Tensor grad_output,\n                           Tensor grad_input, const int num_,\n                           const int h_feature, const int w_feature,\n                           const int h_mask, const int w_mask,\n                           const int half_h_mask, const int half_w_mask);\nREGISTER_DEVICE_IMPL(psamask_forward_impl, CUDA, psamask_forward_cuda);\nREGISTER_DEVICE_IMPL(psamask_backward_impl, CUDA, psamask_backward_cuda);\n\nvoid ROIAlignForwardCUDAKernelLauncher(Tensor input, Tensor rois, Tensor output,\n                                       Tensor argmax_y, Tensor argmax_x,\n                                       int aligned_height, int aligned_width,\n                                       float spatial_scale, int sampling_ratio,\n                                       int pool_mode, bool aligned);\n\nvoid ROIAlignBackwardCUDAKernelLauncher(Tensor grad_output, Tensor rois,\n                                        Tensor argmax_y, Tensor argmax_x,\n                                        Tensor grad_input, int aligned_height,\n                                        int aligned_width, float spatial_scale,\n                                        int sampling_ratio, int pool_mode,\n                                        bool aligned);\n\nvoid roi_align_forward_cuda(Tensor input, Tensor rois, Tensor output,\n                            Tensor argmax_y, Tensor argmax_x,\n                            int aligned_height, int aligned_width,\n                            float spatial_scale, int sampling_ratio,\n                            int pool_mode, bool aligned) {\n  ROIAlignForwardCUDAKernelLauncher(\n      input, rois, output, argmax_y, argmax_x, aligned_height, aligned_width,\n      spatial_scale, sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_backward_cuda(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                             Tensor argmax_x, Tensor grad_input,\n                             int aligned_height, int aligned_width,\n                             float spatial_scale, int sampling_ratio,\n                             int pool_mode, bool aligned) {\n  ROIAlignBackwardCUDAKernelLauncher(\n      grad_output, rois, argmax_y, argmax_x, grad_input, aligned_height,\n      aligned_width, spatial_scale, sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_forward_impl(Tensor input, Tensor rois, Tensor output,\n                            Tensor argmax_y, Tensor argmax_x,\n                            int aligned_height, int aligned_width,\n                            float spatial_scale, int sampling_ratio,\n                            int pool_mode, bool aligned);\n\nvoid roi_align_backward_impl(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                             Tensor argmax_x, Tensor grad_input,\n                             int aligned_height, int aligned_width,\n                             float spatial_scale, int sampling_ratio,\n                             int pool_mode, bool aligned);\n\nREGISTER_DEVICE_IMPL(roi_align_forward_impl, CUDA, roi_align_forward_cuda);\nREGISTER_DEVICE_IMPL(roi_align_backward_impl, CUDA, roi_align_backward_cuda);\n\nvoid ROIAlignRotatedForwardCUDAKernelLauncher(\n    const at::Tensor features, const at::Tensor rois, const float spatial_scale,\n    const int sample_num, const bool aligned, const bool clockwise,\n    const int channels, const int height, const int width, const int num_rois,\n    const int pooled_height, const int pooled_width, at::Tensor output);\n\nvoid ROIAlignRotatedBackwardCUDAKernelLauncher(\n    const at::Tensor top_grad, const at::Tensor rois, const float spatial_scale,\n    const int sample_num, const bool aligned, const bool clockwise,\n    const int channels, const int height, const int width, const int num_rois,\n    const int pooled_height, const int pooled_width, at::Tensor bottom_grad);\n\nvoid roi_align_rotated_forward_cuda(Tensor features, Tensor rois, Tensor output,\n                                    int aligned_height, int aligned_width,\n                                    float spatial_scale, int sample_ratio,\n                                    bool aligned, bool clockwise) {\n  // Number of ROIs\n  int num_rois = rois.size(0);\n  int size_rois = rois.size(1);\n\n  if (size_rois != 6) {\n    AT_ERROR(\"wrong roi size\");\n  }\n\n  int num_channels = features.size(1);\n  int data_height = features.size(2);\n  int data_width = features.size(3);\n  ROIAlignRotatedForwardCUDAKernelLauncher(\n      features, rois, spatial_scale, sample_ratio, aligned, clockwise,\n      num_channels, data_height, data_width, num_rois, aligned_height,\n      aligned_width, output);\n}\n\nvoid roi_align_rotated_backward_cuda(Tensor top_grad, Tensor rois,\n                                     Tensor bottom_grad, int aligned_height,\n                                     int aligned_width, float spatial_scale,\n                                     int sample_ratio, bool aligned,\n                                     bool clockwise) {\n  // Number of ROIs\n  int num_rois = rois.size(0);\n  int size_rois = rois.size(1);\n  if (size_rois != 6) {\n    AT_ERROR(\"wrong roi size\");\n  }\n\n  int num_channels = bottom_grad.size(1);\n  int data_height = bottom_grad.size(2);\n  int data_width = bottom_grad.size(3);\n  ROIAlignRotatedBackwardCUDAKernelLauncher(\n      top_grad, rois, spatial_scale, sample_ratio, aligned, clockwise,\n      num_channels, data_height, data_width, num_rois, aligned_height,\n      aligned_width, bottom_grad);\n}\n\nvoid roi_align_rotated_forward_impl(Tensor features, Tensor rois, Tensor output,\n                                    int aligned_height, int aligned_width,\n                                    float spatial_scale, int sample_ratio,\n                                    bool aligned, bool clockwise);\n\nvoid roi_align_rotated_backward_impl(Tensor top_grad, Tensor rois,\n                                     Tensor bottom_grad, int aligned_height,\n                                     int aligned_width, float spatial_scale,\n                                     int sample_ratio, bool aligned,\n                                     bool clockwise);\nREGISTER_DEVICE_IMPL(roi_align_rotated_forward_impl, CUDA,\n                     roi_align_rotated_forward_cuda);\nREGISTER_DEVICE_IMPL(roi_align_rotated_backward_impl, CUDA,\n                     roi_align_rotated_backward_cuda);\n\nvoid RoiawarePool3dForwardCUDAKernelLauncher(\n    int boxes_num, int pts_num, int channels, int max_pts_each_voxel, int out_x,\n    int out_y, int out_z, const Tensor rois, const Tensor pts,\n    const Tensor pts_feature, Tensor argmax, Tensor pts_idx_of_voxels,\n    Tensor pooled_features, int pool_method);\n\nvoid RoiawarePool3dBackwardCUDAKernelLauncher(\n    int boxes_num, int out_x, int out_y, int out_z, int channels,\n    int max_pts_each_voxel, const Tensor pts_idx_of_voxels, const Tensor argmax,\n    const Tensor grad_out, Tensor grad_in, int pool_method);\n\nvoid roiaware_pool3d_forward_cuda(int boxes_num, int pts_num, int channels,\n                                  int max_pts_each_voxel, int out_x, int out_y,\n                                  int out_z, const Tensor rois,\n                                  const Tensor pts, const Tensor pts_feature,\n                                  Tensor argmax, Tensor pts_idx_of_voxels,\n                                  Tensor pooled_features, int pool_method) {\n  RoiawarePool3dForwardCUDAKernelLauncher(\n      boxes_num, pts_num, channels, max_pts_each_voxel, out_x, out_y, out_z,\n      rois, pts, pts_feature, argmax, pts_idx_of_voxels, pooled_features,\n      pool_method);\n};\n\nvoid roiaware_pool3d_backward_cuda(int boxes_num, int out_x, int out_y,\n                                   int out_z, int channels,\n                                   int max_pts_each_voxel,\n                                   const Tensor pts_idx_of_voxels,\n                                   const Tensor argmax, const Tensor grad_out,\n                                   Tensor grad_in, int pool_method) {\n  RoiawarePool3dBackwardCUDAKernelLauncher(\n      boxes_num, out_x, out_y, out_z, channels, max_pts_each_voxel,\n      pts_idx_of_voxels, argmax, grad_out, grad_in, pool_method);\n};\n\nvoid roiaware_pool3d_forward_impl(int boxes_num, int pts_num, int channels,\n                                  int max_pts_each_voxel, int out_x, int out_y,\n                                  int out_z, const Tensor rois,\n                                  const Tensor pts, const Tensor pts_feature,\n                                  Tensor argmax, Tensor pts_idx_of_voxels,\n                                  Tensor pooled_features, int pool_method);\n\nvoid roiaware_pool3d_backward_impl(int boxes_num, int out_x, int out_y,\n                                   int out_z, int channels,\n                                   int max_pts_each_voxel,\n                                   const Tensor pts_idx_of_voxels,\n                                   const Tensor argmax, const Tensor grad_out,\n                                   Tensor grad_in, int pool_method);\n\nREGISTER_DEVICE_IMPL(roiaware_pool3d_forward_impl, CUDA,\n                     roiaware_pool3d_forward_cuda);\nREGISTER_DEVICE_IMPL(roiaware_pool3d_backward_impl, CUDA,\n                     roiaware_pool3d_backward_cuda);\n\nvoid RoIPointPool3dForwardCUDAKernelLauncher(\n    int batch_size, int pts_num, int boxes_num, int feature_in_len,\n    int sampled_pts_num, const Tensor xyz, const Tensor boxes3d,\n    const Tensor pts_feature, Tensor pooled_features, Tensor pooled_empty_flag);\n\nvoid roipoint_pool3d_forward_cuda(int batch_size, int pts_num, int boxes_num,\n                                  int feature_in_len, int sampled_pts_num,\n                                  const Tensor xyz, const Tensor boxes3d,\n                                  const Tensor pts_feature,\n                                  Tensor pooled_features,\n                                  Tensor pooled_empty_flag) {\n  RoIPointPool3dForwardCUDAKernelLauncher(\n      batch_size, pts_num, boxes_num, feature_in_len, sampled_pts_num, xyz,\n      boxes3d, pts_feature, pooled_features, pooled_empty_flag);\n};\n\nvoid roipoint_pool3d_forward_impl(int batch_size, int pts_num, int boxes_num,\n                                  int feature_in_len, int sampled_pts_num,\n                                  const Tensor xyz, const Tensor boxes3d,\n                                  const Tensor pts_feature,\n                                  Tensor pooled_features,\n                                  Tensor pooled_empty_flag);\nREGISTER_DEVICE_IMPL(roipoint_pool3d_forward_impl, CUDA,\n                     roipoint_pool3d_forward_cuda);\n\nvoid ROIPoolForwardCUDAKernelLauncher(Tensor input, Tensor rois, Tensor output,\n                                      Tensor argmax, int pooled_height,\n                                      int pooled_width, float spatial_scale);\n\nvoid ROIPoolBackwardCUDAKernelLauncher(Tensor grad_output, Tensor rois,\n                                       Tensor argmax, Tensor grad_input,\n                                       int pooled_height, int pooled_width,\n                                       float spatial_scale);\n\nvoid roi_pool_forward_cuda(Tensor input, Tensor rois, Tensor output,\n                           Tensor argmax, int pooled_height, int pooled_width,\n                           float spatial_scale) {\n  ROIPoolForwardCUDAKernelLauncher(input, rois, output, argmax, pooled_height,\n                                   pooled_width, spatial_scale);\n}\n\nvoid roi_pool_backward_cuda(Tensor grad_output, Tensor rois, Tensor argmax,\n                            Tensor grad_input, int pooled_height,\n                            int pooled_width, float spatial_scale) {\n  ROIPoolBackwardCUDAKernelLauncher(grad_output, rois, argmax, grad_input,\n                                    pooled_height, pooled_width, spatial_scale);\n}\n\nvoid roi_pool_forward_impl(Tensor input, Tensor rois, Tensor output,\n                           Tensor argmax, int pooled_height, int pooled_width,\n                           float spatial_scale);\nvoid roi_pool_backward_impl(Tensor grad_output, Tensor rois, Tensor argmax,\n                            Tensor grad_input, int pooled_height,\n                            int pooled_width, float spatial_scale);\nREGISTER_DEVICE_IMPL(roi_pool_forward_impl, CUDA, roi_pool_forward_cuda);\nREGISTER_DEVICE_IMPL(roi_pool_backward_impl, CUDA, roi_pool_backward_cuda);\n\ntypedef enum { SUM = 0, MEAN = 1, MAX = 2 } reduce_t;\n\nstd::vector<at::Tensor> DynamicPointToVoxelForwardCUDAKernelLauncher(\n    const at::Tensor& feats, const at::Tensor& coors,\n    const reduce_t reduce_type);\n\nvoid DynamicPointToVoxelBackwardCUDAKernelLauncher(\n    at::Tensor& grad_feats, const at::Tensor& grad_reduced_feats,\n    const at::Tensor& feats, const at::Tensor& reduced_feats,\n    const at::Tensor& coors_map, const at::Tensor& reduce_count,\n    const reduce_t reduce_type);\n\nstd::vector<torch::Tensor> dynamic_point_to_voxel_forward_cuda(\n    const torch::Tensor& feats, const torch::Tensor& coors,\n    const reduce_t reduce_type) {\n  return DynamicPointToVoxelForwardCUDAKernelLauncher(feats, coors,\n                                                      reduce_type);\n};\n\nvoid dynamic_point_to_voxel_backward_cuda(\n    torch::Tensor& grad_feats, const torch::Tensor& grad_reduced_feats,\n    const torch::Tensor& feats, const torch::Tensor& reduced_feats,\n    const torch::Tensor& coors_idx, const torch::Tensor& reduce_count,\n    const reduce_t reduce_type) {\n  DynamicPointToVoxelBackwardCUDAKernelLauncher(grad_feats, grad_reduced_feats,\n                                                feats, reduced_feats, coors_idx,\n                                                reduce_count, reduce_type);\n};\n\nstd::vector<torch::Tensor> dynamic_point_to_voxel_forward_impl(\n    const torch::Tensor& feats, const torch::Tensor& coors,\n    const reduce_t reduce_type);\n\nvoid dynamic_point_to_voxel_backward_impl(\n    torch::Tensor& grad_feats, const torch::Tensor& grad_reduced_feats,\n    const torch::Tensor& feats, const torch::Tensor& reduced_feats,\n    const torch::Tensor& coors_idx, const torch::Tensor& reduce_count,\n    const reduce_t reduce_type);\n\nREGISTER_DEVICE_IMPL(dynamic_point_to_voxel_forward_impl, CUDA,\n                     dynamic_point_to_voxel_forward_cuda);\nREGISTER_DEVICE_IMPL(dynamic_point_to_voxel_backward_impl, CUDA,\n                     dynamic_point_to_voxel_backward_cuda);\n\nvoid SyncBNForwardMeanCUDAKernelLauncher(const Tensor input, Tensor mean);\n\nvoid SyncBNForwardVarCUDAKernelLauncher(const Tensor input, const Tensor mean,\n                                        Tensor var);\n\nvoid SyncBNForwardOutputCUDAKernelLauncher(\n    const Tensor input, const Tensor mean, const Tensor var,\n    Tensor running_mean, Tensor running_var, const Tensor weight,\n    const Tensor bias, Tensor norm, Tensor std, Tensor output, float eps,\n    float momentum, int group_size);\n\nvoid SyncBNBackwardParamCUDAKernelLauncher(const Tensor grad_output,\n                                           const Tensor norm,\n                                           Tensor grad_weight,\n                                           Tensor grad_bias);\n\nvoid SyncBNBackwardDataCUDAKernelLauncher(const Tensor grad_output,\n                                          const Tensor weight,\n                                          const Tensor grad_weight,\n                                          const Tensor grad_bias,\n                                          const Tensor norm, const Tensor std,\n                                          Tensor grad_input);\n\nvoid sync_bn_forward_mean_cuda(const Tensor input, Tensor mean) {\n  SyncBNForwardMeanCUDAKernelLauncher(input, mean);\n}\n\nvoid sync_bn_forward_var_cuda(const Tensor input, const Tensor mean,\n                              Tensor var) {\n  SyncBNForwardVarCUDAKernelLauncher(input, mean, var);\n}\n\nvoid sync_bn_forward_output_cuda(const Tensor input, const Tensor mean,\n                                 const Tensor var, Tensor running_mean,\n                                 Tensor running_var, const Tensor weight,\n                                 const Tensor bias, Tensor norm, Tensor std,\n                                 Tensor output, float eps, float momentum,\n                                 int group_size) {\n  SyncBNForwardOutputCUDAKernelLauncher(input, mean, var, running_mean,\n                                        running_var, weight, bias, norm, std,\n                                        output, eps, momentum, group_size);\n}\n\nvoid sync_bn_backward_param_cuda(const Tensor grad_output, const Tensor norm,\n                                 Tensor grad_weight, Tensor grad_bias) {\n  SyncBNBackwardParamCUDAKernelLauncher(grad_output, norm, grad_weight,\n                                        grad_bias);\n}\n\nvoid sync_bn_backward_data_cuda(const Tensor grad_output, const Tensor weight,\n                                const Tensor grad_weight,\n                                const Tensor grad_bias, const Tensor norm,\n                                const Tensor std, Tensor grad_input) {\n  SyncBNBackwardDataCUDAKernelLauncher(grad_output, weight, grad_weight,\n                                       grad_bias, norm, std, grad_input);\n}\n\nvoid sync_bn_forward_mean_impl(const Tensor input, Tensor mean);\n\nvoid sync_bn_forward_var_impl(const Tensor input, const Tensor mean,\n                              Tensor var);\n\nvoid sync_bn_forward_output_impl(const Tensor input, const Tensor mean,\n                                 const Tensor var, Tensor running_mean,\n                                 Tensor running_var, const Tensor weight,\n                                 const Tensor bias, Tensor norm, Tensor std,\n                                 Tensor output, float eps, float momentum,\n                                 int group_size);\n\nvoid sync_bn_backward_param_impl(const Tensor grad_output, const Tensor norm,\n                                 Tensor grad_weight, Tensor grad_bias);\n\nvoid sync_bn_backward_data_impl(const Tensor grad_output, const Tensor weight,\n                                const Tensor grad_weight,\n                                const Tensor grad_bias, const Tensor norm,\n                                const Tensor std, Tensor grad_input);\n\nREGISTER_DEVICE_IMPL(sync_bn_forward_mean_impl, CUDA,\n                     sync_bn_forward_mean_cuda);\nREGISTER_DEVICE_IMPL(sync_bn_forward_var_impl, CUDA, sync_bn_forward_var_cuda);\nREGISTER_DEVICE_IMPL(sync_bn_forward_output_impl, CUDA,\n                     sync_bn_forward_output_cuda);\nREGISTER_DEVICE_IMPL(sync_bn_backward_param_impl, CUDA,\n                     sync_bn_backward_param_cuda);\nREGISTER_DEVICE_IMPL(sync_bn_backward_data_impl, CUDA,\n                     sync_bn_backward_data_cuda);\n\nvoid ThreeInterpolateForwardCUDAKernelLauncher(int b, int c, int m, int n,\n                                               const Tensor points,\n                                               const Tensor idx,\n                                               const Tensor weight, Tensor out);\n\nvoid ThreeInterpolateBackwardCUDAKernelLauncher(int b, int c, int n, int m,\n                                                const Tensor grad_out,\n                                                const Tensor idx,\n                                                const Tensor weight,\n                                                Tensor grad_points);\n\nvoid three_interpolate_forward_cuda(int b, int c, int m, int n,\n                                    const Tensor points, const Tensor idx,\n                                    const Tensor weight, Tensor out) {\n  ThreeInterpolateForwardCUDAKernelLauncher(b, c, m, n, points, idx, weight,\n                                            out);\n};\n\nvoid three_interpolate_backward_cuda(int b, int c, int n, int m,\n                                     const Tensor grad_out, const Tensor idx,\n                                     const Tensor weight, Tensor grad_points) {\n  ThreeInterpolateBackwardCUDAKernelLauncher(b, c, n, m, grad_out, idx, weight,\n                                             grad_points);\n};\n\nvoid three_interpolate_forward_impl(int b, int c, int m, int n,\n                                    const Tensor points, const Tensor idx,\n                                    const Tensor weight, Tensor out);\n\nvoid three_interpolate_backward_impl(int b, int c, int n, int m,\n                                     const Tensor grad_out, const Tensor idx,\n                                     const Tensor weight, Tensor grad_points);\nREGISTER_DEVICE_IMPL(three_interpolate_forward_impl, CUDA,\n                     three_interpolate_forward_cuda);\nREGISTER_DEVICE_IMPL(three_interpolate_backward_impl, CUDA,\n                     three_interpolate_backward_cuda);\n\nvoid ThreeNNForwardCUDAKernelLauncher(int b, int n, int m, const Tensor unknown,\n                                      const Tensor known, Tensor dist2,\n                                      Tensor idx);\n\nvoid three_nn_forward_cuda(int b, int n, int m, const Tensor unknown,\n                           const Tensor known, Tensor dist2, Tensor idx) {\n  ThreeNNForwardCUDAKernelLauncher(b, n, m, unknown, known, dist2, idx);\n};\n\nvoid three_nn_forward_impl(int b, int n, int m, const Tensor unknown,\n                           const Tensor known, Tensor dist2, Tensor idx);\nREGISTER_DEVICE_IMPL(three_nn_forward_impl, CUDA, three_nn_forward_cuda);\n\nvoid TINShiftForwardCUDAKernelLauncher(Tensor input, Tensor shift,\n                                       Tensor output);\n\nvoid TINShiftBackwardCUDAKernelLauncher(Tensor grad_output, Tensor shift,\n                                        Tensor grad_input);\n\nvoid tin_shift_forward_cuda(Tensor input, Tensor shift, Tensor output) {\n  TINShiftForwardCUDAKernelLauncher(input, shift, output);\n}\n\nvoid tin_shift_backward_cuda(Tensor grad_output, Tensor shift,\n                             Tensor grad_input) {\n  TINShiftBackwardCUDAKernelLauncher(grad_output, shift, grad_input);\n}\n\nvoid tin_shift_forward_impl(Tensor input, Tensor shift, Tensor output);\nvoid tin_shift_backward_impl(Tensor grad_output, Tensor shift,\n                             Tensor grad_input);\nREGISTER_DEVICE_IMPL(tin_shift_forward_impl, CUDA, tin_shift_forward_cuda);\nREGISTER_DEVICE_IMPL(tin_shift_backward_impl, CUDA, tin_shift_backward_cuda);\n\ntorch::Tensor upfirdn2d_op(const torch::Tensor& input,\n                           const torch::Tensor& kernel, int up_x, int up_y,\n                           int down_x, int down_y, int pad_x0, int pad_x1,\n                           int pad_y0, int pad_y1);\n\ntorch::Tensor upfirdn2d_op_impl(const torch::Tensor& input,\n                                const torch::Tensor& kernel, int up_x, int up_y,\n                                int down_x, int down_y, int pad_x0, int pad_x1,\n                                int pad_y0, int pad_y1);\nREGISTER_DEVICE_IMPL(upfirdn2d_op_impl, CUDA, upfirdn2d_op);\n\nint HardVoxelizeForwardCUDAKernelLauncher(\n    const at::Tensor& points, at::Tensor& voxels, at::Tensor& coors,\n    at::Tensor& num_points_per_voxel, const std::vector<float> voxel_size,\n    const std::vector<float> coors_range, const int max_points,\n    const int max_voxels, const int NDim = 3);\n\nvoid DynamicVoxelizeForwardCUDAKernelLauncher(\n    const at::Tensor& points, at::Tensor& coors,\n    const std::vector<float> voxel_size, const std::vector<float> coors_range,\n    const int NDim = 3);\n\nint hard_voxelize_forward_cuda(const at::Tensor& points, at::Tensor& voxels,\n                               at::Tensor& coors,\n                               at::Tensor& num_points_per_voxel,\n                               const std::vector<float> voxel_size,\n                               const std::vector<float> coors_range,\n                               const int max_points, const int max_voxels,\n                               const int NDim) {\n  return HardVoxelizeForwardCUDAKernelLauncher(\n      points, voxels, coors, num_points_per_voxel, voxel_size, coors_range,\n      max_points, max_voxels, NDim);\n};\n\nvoid dynamic_voxelize_forward_cuda(const at::Tensor& points, at::Tensor& coors,\n                                   const std::vector<float> voxel_size,\n                                   const std::vector<float> coors_range,\n                                   const int NDim) {\n  DynamicVoxelizeForwardCUDAKernelLauncher(points, coors, voxel_size,\n                                           coors_range, NDim);\n};\n\nint hard_voxelize_forward_impl(const at::Tensor& points, at::Tensor& voxels,\n                               at::Tensor& coors,\n                               at::Tensor& num_points_per_voxel,\n                               const std::vector<float> voxel_size,\n                               const std::vector<float> coors_range,\n                               const int max_points, const int max_voxels,\n                               const int NDim);\n\nvoid dynamic_voxelize_forward_impl(const at::Tensor& points, at::Tensor& coors,\n                                   const std::vector<float> voxel_size,\n                                   const std::vector<float> coors_range,\n                                   const int NDim);\nREGISTER_DEVICE_IMPL(hard_voxelize_forward_impl, CUDA,\n                     hard_voxelize_forward_cuda);\nREGISTER_DEVICE_IMPL(dynamic_voxelize_forward_impl, CUDA,\n                     dynamic_voxelize_forward_cuda);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/deform_conv_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"deform_conv_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid deformable_im2col_cuda(Tensor data_im, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor data_col) {\n  // num_axes should be smaller than block size\n  // todo: check parallel_imgs is correctly passed in\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = channels * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"deformable_im2col_gpu\", ([&] {\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n\n        deformable_im2col_gpu_kernel<<<GET_BLOCKS(num_kernels),\n                                       THREADS_PER_BLOCK, 0,\n                                       at::cuda::getCurrentCUDAStream()>>>(\n            num_kernels, data_im_, data_offset_, height, width, ksize_h,\n            ksize_w, pad_h, pad_w, stride_h, stride_w, dilation_h, dilation_w,\n            channel_per_deformable_group, parallel_imgs, channels,\n            deformable_group, height_col, width_col, data_col_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid deformable_col2im_cuda(Tensor data_col, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor grad_im) {\n  // todo: make sure parallel_imgs is passed in correctly\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels =\n      channels * ksize_h * ksize_w * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_gpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t *grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        deformable_col2im_gpu_kernel<<<GET_BLOCKS(num_kernels),\n                                       THREADS_PER_BLOCK, 0,\n                                       at::cuda::getCurrentCUDAStream()>>>(\n            num_kernels, data_col_, data_offset_, channels, height, width,\n            ksize_h, ksize_w, pad_h, pad_w, stride_h, stride_w, dilation_h,\n            dilation_w, channel_per_deformable_group, parallel_imgs,\n            deformable_group, height_col, width_col, grad_im_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid deformable_col2im_coord_cuda(\n    Tensor data_col, Tensor data_im, Tensor data_offset, const int channels,\n    const int height, const int width, const int ksize_h, const int ksize_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int parallel_imgs,\n    const int deformable_group, Tensor grad_offset) {\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = height_col * width_col * 2 * ksize_h * ksize_w *\n                    deformable_group * parallel_imgs;\n  int channel_per_deformable_group =\n      channels * ksize_h * ksize_w / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_coord_gpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t *grad_offset_ = grad_offset.data_ptr<scalar_t>();\n\n        deformable_col2im_coord_gpu_kernel<<<\n            GET_BLOCKS(num_kernels), THREADS_PER_BLOCK, 0,\n            at::cuda::getCurrentCUDAStream()>>>(\n            num_kernels, data_col_, data_im_, data_offset_, channels, height,\n            width, ksize_h, ksize_w, pad_h, pad_w, stride_h, stride_w,\n            dilation_h, dilation_w, channel_per_deformable_group, parallel_imgs,\n            2 * ksize_h * ksize_w * deformable_group, deformable_group,\n            height_col, width_col, grad_offset_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/deform_roi_pool_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"deform_roi_pool_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid DeformRoIPoolForwardCUDAKernelLauncher(Tensor input, Tensor rois,\n                                            Tensor offset, Tensor output,\n                                            int pooled_height, int pooled_width,\n                                            float spatial_scale,\n                                            int sampling_ratio, float gamma) {\n  int output_size = output.numel();\n  int channels = input.size(1);\n  int height = input.size(2);\n  int width = input.size(3);\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"deform_roi_pool_forward_cuda_kernel\", [&] {\n        deform_roi_pool_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, input.data_ptr<scalar_t>(),\n                rois.data_ptr<scalar_t>(), offset.data_ptr<scalar_t>(),\n                output.data_ptr<scalar_t>(), pooled_height, pooled_width,\n                static_cast<scalar_t>(spatial_scale), sampling_ratio,\n                static_cast<scalar_t>(gamma), channels, height, width);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid DeformRoIPoolBackwardCUDAKernelLauncher(\n    Tensor grad_output, Tensor input, Tensor rois, Tensor offset,\n    Tensor grad_input, Tensor grad_offset, int pooled_height, int pooled_width,\n    float spatial_scale, int sampling_ratio, float gamma) {\n  int output_size = grad_output.numel();\n  int channels = grad_input.size(1);\n  int height = grad_input.size(2);\n  int width = grad_input.size(3);\n\n  at::cuda::CUDAGuard device_guard(grad_output.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"deform_roi_pool_backward_cuda_kernel\", [&] {\n        deform_roi_pool_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, grad_output.data_ptr<scalar_t>(),\n                input.data_ptr<scalar_t>(), rois.data_ptr<scalar_t>(),\n                offset.data_ptr<scalar_t>(), grad_input.data_ptr<scalar_t>(),\n                grad_offset.data_ptr<scalar_t>(), pooled_height, pooled_width,\n                static_cast<scalar_t>(spatial_scale), sampling_ratio,\n                static_cast<scalar_t>(gamma), channels, height, width);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/focal_loss_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cuda_helper.hpp\"\n#include \"sigmoid_focal_loss_cuda_kernel.cuh\"\n#include \"softmax_focal_loss_cuda_kernel.cuh\"\n\nvoid SigmoidFocalLossForwardCUDAKernelLauncher(Tensor input, Tensor target,\n                                               Tensor weight, Tensor output,\n                                               const float gamma,\n                                               const float alpha) {\n  int output_size = output.numel();\n  int num_classes = input.size(1);\n  AT_ASSERTM(target.max().item<int64_t>() <= (int64_t)num_classes,\n             \"target label should smaller or equal than num classes\");\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"sigmoid_focal_loss_forward_cuda_kernel\", [&] {\n        sigmoid_focal_loss_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, input.data_ptr<scalar_t>(),\n                target.data_ptr<int64_t>(), weight.data_ptr<scalar_t>(),\n                output.data_ptr<scalar_t>(), gamma, alpha, num_classes);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SigmoidFocalLossBackwardCUDAKernelLauncher(Tensor input, Tensor target,\n                                                Tensor weight,\n                                                Tensor grad_input,\n                                                const float gamma,\n                                                const float alpha) {\n  int output_size = grad_input.numel();\n  int num_classes = input.size(1);\n\n  at::cuda::CUDAGuard device_guard(grad_input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"sigmoid_focal_loss_backward_cuda_kernel\", [&] {\n        sigmoid_focal_loss_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, input.data_ptr<scalar_t>(),\n                target.data_ptr<int64_t>(), weight.data_ptr<scalar_t>(),\n                grad_input.data_ptr<scalar_t>(), gamma, alpha, num_classes);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SoftmaxFocalLossForwardCUDAKernelLauncher(Tensor softmax, Tensor target,\n                                               Tensor weight, Tensor output,\n                                               const float gamma,\n                                               const float alpha) {\n  int output_size = output.numel();\n  int num_classes = softmax.size(1);\n\n  AT_ASSERTM(target.max().item<int64_t>() <= (int64_t)num_classes,\n             \"target label should smaller or equal than num classes\");\n  at::cuda::CUDAGuard device_guard(softmax.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      softmax.scalar_type(), \"softmax_focal_loss_forward_cuda_kernel\", [&] {\n        softmax_focal_loss_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, softmax.data_ptr<scalar_t>(),\n                target.data_ptr<int64_t>(), weight.data_ptr<scalar_t>(),\n                output.data_ptr<scalar_t>(), gamma, alpha, num_classes);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SoftmaxFocalLossBackwardCUDAKernelLauncher(Tensor softmax, Tensor target,\n                                                Tensor weight, Tensor buff,\n                                                Tensor grad_input,\n                                                const float gamma,\n                                                const float alpha) {\n  int num_classes = softmax.size(1);\n\n  int output_size = buff.numel();\n  at::cuda::CUDAGuard device_guard(grad_input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_input.scalar_type(),\n      \"softmax_focal_loss_backward_cuda1_\"\n      \"kernel\",\n      [&] {\n        softmax_focal_loss_backward_cuda1_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, softmax.data_ptr<scalar_t>(),\n                target.data_ptr<int64_t>(), weight.data_ptr<scalar_t>(),\n                buff.data_ptr<scalar_t>(), gamma, alpha, num_classes);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  output_size = grad_input.numel();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_input.scalar_type(),\n      \"softmax_focal_loss_backward_cuda2_\"\n      \"kernel\",\n      [&] {\n        softmax_focal_loss_backward_cuda2_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, softmax.data_ptr<scalar_t>(),\n                target.data_ptr<int64_t>(), buff.data_ptr<scalar_t>(),\n                grad_input.data_ptr<scalar_t>(), num_classes);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/furthest_point_sample_cuda.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/sampling_gpu.cu\n\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"furthest_point_sample_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\ninline int opt_n_threads(int work_size) {\n  const int pow_2 = std::log(static_cast<double>(work_size)) / std::log(2.0);\n\n  return max(min(1 << pow_2, 1024), 1);\n}\n\nvoid FurthestPointSamplingForwardCUDAKernelLauncher(int b, int n, int m,\n                                                    const float* dataset,\n                                                    float* temp, int* idxs) {\n  // dataset: (B, N, 3)\n  // tmp: (B, N)\n  // output:\n  //      idx: (B, M)\n\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  unsigned int n_threads = opt_n_threads(n);\n\n  switch (n_threads) {\n    case 1024:\n      furthest_point_sampling_forward_cuda_kernel<1024>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 512:\n      furthest_point_sampling_forward_cuda_kernel<512>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 256:\n      furthest_point_sampling_forward_cuda_kernel<256>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 128:\n      furthest_point_sampling_forward_cuda_kernel<128>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 64:\n      furthest_point_sampling_forward_cuda_kernel<64>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 32:\n      furthest_point_sampling_forward_cuda_kernel<32>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 16:\n      furthest_point_sampling_forward_cuda_kernel<16>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 8:\n      furthest_point_sampling_forward_cuda_kernel<8>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 4:\n      furthest_point_sampling_forward_cuda_kernel<4>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 2:\n      furthest_point_sampling_forward_cuda_kernel<2>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 1:\n      furthest_point_sampling_forward_cuda_kernel<1>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    default:\n      furthest_point_sampling_forward_cuda_kernel<512>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid FurthestPointSamplingWithDistForwardCUDAKernelLauncher(\n    int b, int n, int m, const float* dataset, float* temp, int* idxs) {\n  // dataset: (B, N, N)\n  // temp: (B, N)\n  // output:\n  //      idx: (B, M)\n\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  unsigned int n_threads = opt_n_threads(n);\n\n  switch (n_threads) {\n    case 1024:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<1024>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 512:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<512>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 256:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<256>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 128:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<128>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 64:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<64>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 32:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<32>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 16:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<16>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 8:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<8>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 4:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<4>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 2:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<2>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    case 1:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<1>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n      break;\n    default:\n      furthest_point_sampling_with_dist_forward_cuda_kernel<512>\n          <<<b, n_threads, 0, stream>>>(b, n, m, dataset, temp, idxs);\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/fused_bias_leakyrelu_cuda.cu",
    "content": "// Modified from\n// https://github.com/rosinality/stylegan2-pytorch/blob/master/op/fused_bias_act_kernel.cu\n// Copyright (c) 2019, NVIDIA Corporation. All rights reserved.\n//\n// This work is made available under the Nvidia Source Code License-NC.\n// To view a copy of this license, visit\n// https://nvlabs.github.io/stylegan2/license.html\n\n#include <ATen/ATen.h>\n#include <ATen/AccumulateType.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <torch/types.h>\n\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n\ntemplate <typename scalar_t>\nstatic __global__ void fused_bias_act_kernel(\n    scalar_t* out, const scalar_t* p_x, const scalar_t* p_b,\n    const scalar_t* p_ref, int act, int grad, scalar_t alpha, scalar_t scale,\n    int loop_x, int size_x, int step_b, int size_b, int use_bias, int use_ref) {\n  int xi = blockIdx.x * loop_x * blockDim.x + threadIdx.x;\n\n  scalar_t zero = 0.0;\n\n  for (int loop_idx = 0; loop_idx < loop_x && xi < size_x;\n       loop_idx++, xi += blockDim.x) {\n    scalar_t x = p_x[xi];\n\n    if (use_bias) {\n      x += p_b[(xi / step_b) % size_b];\n    }\n\n    scalar_t ref = use_ref ? p_ref[xi] : zero;\n\n    scalar_t y;\n\n    // act = 1: linear layer\n    // act = 3: leaky relu layer\n    // grad = 0: direct forward path\n    // grad = 1: first order deviation\n    // grad = 2: second order deviation\n    switch (act * 10 + grad) {\n      default:\n      case 10:\n        y = x;\n        break;\n      case 11:\n        y = x;\n        break;\n      case 12:\n        y = 0.0;\n        break;\n\n      case 30:\n        y = (x > 0.0) ? x : x * alpha;\n        break;\n      case 31:\n        y = (ref > 0.0) ? x : x * alpha;\n        break;\n      case 32:\n        y = 0.0;\n        break;\n    }\n\n    out[xi] = y * scale;\n  }\n}\n\ntorch::Tensor fused_bias_leakyrelu_op(const torch::Tensor& input,\n                                      const torch::Tensor& bias,\n                                      const torch::Tensor& refer, int act,\n                                      int grad, float alpha, float scale) {\n  int curDevice = -1;\n  cudaGetDevice(&curDevice);\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream(curDevice);\n\n  auto x = input.contiguous();\n  auto b = bias.contiguous();\n  auto ref = refer.contiguous();\n\n  int use_bias = b.numel() ? 1 : 0;\n  int use_ref = ref.numel() ? 1 : 0;\n\n  int size_x = x.numel();\n  int size_b = b.numel();\n  int step_b = 1;\n\n  for (int i = 1 + 1; i < x.dim(); i++) {\n    step_b *= x.size(i);\n  }\n\n  int loop_x = 4;\n  int block_size = 4 * 32;\n  int grid_size = (size_x - 1) / (loop_x * block_size) + 1;\n\n  auto y = torch::empty_like(x);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      x.scalar_type(), \"fused_bias_act_kernel\", [&] {\n        fused_bias_act_kernel<scalar_t><<<grid_size, block_size, 0, stream>>>(\n            y.data_ptr<scalar_t>(), x.data_ptr<scalar_t>(),\n            b.data_ptr<scalar_t>(), ref.data_ptr<scalar_t>(), act, grad, alpha,\n            scale, loop_x, size_x, step_b, size_b, use_bias, use_ref);\n      });\n\n  return y;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/gather_points_cuda.cu",
    "content": "#include <stdio.h>\n#include <stdlib.h>\n\n#include \"gather_points_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid GatherPointsForwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                           const Tensor points,\n                                           const Tensor idx, Tensor out) {\n  // points: (B, C, N)\n  // idx: (B, npoints)\n  // output:\n  //      out: (B, C, npoints)\n\n  at::cuda::CUDAGuard device_guard(points.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(npoints, THREADS_PER_BLOCK), c, b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      points.scalar_type(), \"gather_points_forward_cuda_kernel\", [&] {\n        gather_points_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, c, n, npoints, points.data_ptr<scalar_t>(),\n                idx.data_ptr<int>(), out.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid GatherPointsBackwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                            const Tensor grad_out,\n                                            const Tensor idx,\n                                            Tensor grad_points) {\n  // grad_out: (B, C, npoints)\n  // idx: (B, npoints)\n  // output:\n  //      grad_points: (B, C, N)\n\n  at::cuda::CUDAGuard device_guard(grad_out.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(npoints, THREADS_PER_BLOCK), c, b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_out.scalar_type(), \"gather_points_backward_cuda_kernel\", [&] {\n        gather_points_backward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, c, n, npoints, grad_out.data_ptr<scalar_t>(),\n                idx.data_ptr<int>(), grad_points.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/group_points_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/group_points_gpu.cu\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"group_points_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid GroupPointsForwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                          int nsample, const Tensor points,\n                                          const Tensor idx, Tensor out) {\n  // points: (B, C, N)\n  // idx: (B, npoints, nsample)\n  // output:\n  //      out: (B, C, npoints, nsample)\n\n  at::cuda::CUDAGuard device_guard(points.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(npoints * nsample, THREADS_PER_BLOCK), c, b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      points.scalar_type(), \"group_points_forward_cuda_kernel\", [&] {\n        group_points_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, c, n, npoints, nsample, points.data_ptr<scalar_t>(),\n                idx.data_ptr<int>(), out.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid GroupPointsBackwardCUDAKernelLauncher(int b, int c, int n, int npoints,\n                                           int nsample, const Tensor grad_out,\n                                           const Tensor idx,\n                                           Tensor grad_points) {\n  // grad_out: (B, C, npoints, nsample)\n  // idx: (B, npoints, nsample)\n  // output:\n  //      grad_points: (B, C, N)\n\n  at::cuda::CUDAGuard device_guard(grad_out.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(npoints * nsample, THREADS_PER_BLOCK), c, b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_out.scalar_type(), \"group_points_backward_cuda_kernel\", [&] {\n        group_points_backward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, c, n, npoints, nsample, grad_out.data_ptr<scalar_t>(),\n                idx.data_ptr<int>(), grad_points.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/iou3d_cuda.cu",
    "content": "// Modified from\n// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms_kernel.cu\n\n/*\n3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)\nWritten by Shaoshuai Shi\nAll Rights Reserved 2019-2020.\n*/\n\n#include <stdio.h>\n\n#include \"iou3d_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid IoU3DBoxesOverlapBevForwardCUDAKernelLauncher(const int num_a,\n                                                   const Tensor boxes_a,\n                                                   const int num_b,\n                                                   const Tensor boxes_b,\n                                                   Tensor ans_overlap) {\n  at::cuda::CUDAGuard device_guard(boxes_a.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(num_b, THREADS_PER_BLOCK_IOU3D),\n              DIVUP(num_a, THREADS_PER_BLOCK_IOU3D));\n  dim3 threads(THREADS_PER_BLOCK_IOU3D, THREADS_PER_BLOCK_IOU3D);\n\n  iou3d_boxes_overlap_bev_forward_cuda_kernel<<<blocks, threads, 0, stream>>>(\n      num_a, boxes_a.data_ptr<float>(), num_b, boxes_b.data_ptr<float>(),\n      ans_overlap.data_ptr<float>());\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid IoU3DBoxesIoUBevForwardCUDAKernelLauncher(const int num_a,\n                                               const Tensor boxes_a,\n                                               const int num_b,\n                                               const Tensor boxes_b,\n                                               Tensor ans_iou) {\n  at::cuda::CUDAGuard device_guard(boxes_a.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(num_b, THREADS_PER_BLOCK_IOU3D),\n              DIVUP(num_a, THREADS_PER_BLOCK_IOU3D));\n  dim3 threads(THREADS_PER_BLOCK_IOU3D, THREADS_PER_BLOCK_IOU3D);\n\n  iou3d_boxes_iou_bev_forward_cuda_kernel<<<blocks, threads, 0, stream>>>(\n      num_a, boxes_a.data_ptr<float>(), num_b, boxes_b.data_ptr<float>(),\n      ans_iou.data_ptr<float>());\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid IoU3DNMSForwardCUDAKernelLauncher(const Tensor boxes,\n                                       unsigned long long *mask, int boxes_num,\n                                       float nms_overlap_thresh) {\n  at::cuda::CUDAGuard device_guard(boxes.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks(DIVUP(boxes_num, THREADS_PER_BLOCK_NMS),\n              DIVUP(boxes_num, THREADS_PER_BLOCK_NMS));\n  dim3 threads(THREADS_PER_BLOCK_NMS);\n\n  nms_forward_cuda_kernel<<<blocks, threads, 0, stream>>>(\n      boxes_num, nms_overlap_thresh, boxes.data_ptr<float>(), mask);\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid IoU3DNMSNormalForwardCUDAKernelLauncher(const Tensor boxes,\n                                             unsigned long long *mask,\n                                             int boxes_num,\n                                             float nms_overlap_thresh) {\n  at::cuda::CUDAGuard device_guard(boxes.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks(DIVUP(boxes_num, THREADS_PER_BLOCK_NMS),\n              DIVUP(boxes_num, THREADS_PER_BLOCK_NMS));\n  dim3 threads(THREADS_PER_BLOCK_NMS);\n\n  nms_normal_forward_cuda_kernel<<<blocks, threads, 0, stream>>>(\n      boxes_num, nms_overlap_thresh, boxes.data_ptr<float>(), mask);\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/knn_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/CVMI-Lab/PAConv/tree/main/scene_seg/lib/pointops/src/knnquery_heap\n\n#include <cmath>\n#include <cstdio>\n\n#include \"knn_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid KNNForwardCUDAKernelLauncher(int b, int n, int m, int nsample,\n                                  const Tensor xyz, const Tensor new_xyz,\n                                  Tensor idx, Tensor dist2) {\n  // param new_xyz: (B, m, 3)\n  // param xyz: (B, n, 3)\n  // param idx: (B, m, nsample)\n\n  at::cuda::CUDAGuard device_guard(new_xyz.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(m, THREADS_PER_BLOCK), b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      new_xyz.scalar_type(), \"knn_forward_cuda_kernel\", [&] {\n        knn_forward_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n            b, n, m, nsample, xyz.data_ptr<scalar_t>(),\n            new_xyz.data_ptr<scalar_t>(), idx.data_ptr<int>(),\n            dist2.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/masked_conv2d_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"masked_conv2d_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid MaskedIm2colForwardCUDAKernelLauncher(const Tensor bottom_data,\n                                           const Tensor mask_h_idx,\n                                           const Tensor mask_w_idx,\n                                           Tensor top_data, const int kernel_h,\n                                           const int kernel_w, const int pad_h,\n                                           const int pad_w) {\n  int channels = bottom_data.size(1);\n  int height = bottom_data.size(2);\n  int width = bottom_data.size(3);\n  int mask_cnt = mask_h_idx.size(0);\n  int output_size = mask_cnt * channels;\n\n  at::cuda::CUDAGuard device_guard(bottom_data.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      bottom_data.scalar_type(), \"MaskedIm2colLaucherForward\", ([&] {\n        const scalar_t *bottom_data_ = bottom_data.data_ptr<scalar_t>();\n        const int64_t *mask_h_idx_ = mask_h_idx.data_ptr<int64_t>();\n        const int64_t *mask_w_idx_ = mask_w_idx.data_ptr<int64_t>();\n        scalar_t *top_data_ = top_data.data_ptr<scalar_t>();\n        MaskedIm2colForward<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, bottom_data_, height, width, kernel_h, kernel_w,\n                pad_h, pad_w, mask_h_idx_, mask_w_idx_, mask_cnt, top_data_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid MaskedCol2imForwardCUDAKernelLauncher(\n    const Tensor bottom_data, const Tensor mask_h_idx, const Tensor mask_w_idx,\n    Tensor top_data, const int height, const int width, const int channels) {\n  int mask_cnt = mask_h_idx.size(0);\n  int output_size = mask_cnt * channels;\n\n  at::cuda::CUDAGuard device_guard(bottom_data.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      bottom_data.scalar_type(), \"MaskedCol2imLaucherForward\", ([&] {\n        const scalar_t *bottom_data_ = bottom_data.data_ptr<scalar_t>();\n        const int64_t *mask_h_idx_ = mask_h_idx.data_ptr<int64_t>();\n        const int64_t *mask_w_idx_ = mask_w_idx.data_ptr<int64_t>();\n        scalar_t *top_data_ = top_data.data_ptr<scalar_t>();\n\n        MaskedCol2imForward<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, bottom_data_, height, width, channels, mask_h_idx_,\n                mask_w_idx_, mask_cnt, top_data_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/modulated_deform_conv_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"modulated_deform_conv_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid modulated_deformable_im2col_cuda(\n    const Tensor data_im, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor data_col) {\n  // num_axes should be smaller than block size\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels = channels * batch_size * height_col * width_col;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"modulated_deformable_im2col_gpu\", ([&] {\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t *data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n\n        modulated_deformable_im2col_gpu_kernel<<<\n            GET_BLOCKS(num_kernels), THREADS_PER_BLOCK, 0,\n            at::cuda::getCurrentCUDAStream()>>>(\n            num_kernels, data_im_, data_offset_, data_mask_, height_im,\n            width_im, kernel_h, kernel_w, pad_h, pad_w, stride_h, stride_w,\n            dilation_h, dilation_w, channel_per_deformable_group, batch_size,\n            channels, deformable_group, height_col, width_col, data_col_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid modulated_deformable_col2im_cuda(\n    const Tensor data_col, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor grad_im) {\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels =\n      channels * kernel_h * kernel_w * batch_size * height_col * width_col;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_gpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t *data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t *grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_gpu_kernel<<<\n            GET_BLOCKS(num_kernels), THREADS_PER_BLOCK, 0,\n            at::cuda::getCurrentCUDAStream()>>>(\n            num_kernels, data_col_, data_offset_, data_mask_, channels,\n            height_im, width_im, kernel_h, kernel_w, pad_h, pad_w, stride_h,\n            stride_w, dilation_h, dilation_w, channel_per_deformable_group,\n            batch_size, deformable_group, height_col, width_col, grad_im_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid modulated_deformable_col2im_coord_cuda(\n    const Tensor data_col, const Tensor data_im, const Tensor data_offset,\n    const Tensor data_mask, const int batch_size, const int channels,\n    const int height_im, const int width_im, const int height_col,\n    const int width_col, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int deformable_group,\n    Tensor grad_offset, Tensor grad_mask) {\n  const int num_kernels = batch_size * height_col * width_col * 2 * kernel_h *\n                          kernel_w * deformable_group;\n  const int channel_per_deformable_group =\n      channels * kernel_h * kernel_w / deformable_group;\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_coord_gpu\", ([&] {\n        const scalar_t *data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t *data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t *data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t *data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t *grad_offset_ = grad_offset.data_ptr<scalar_t>();\n        scalar_t *grad_mask_ = grad_mask.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_coord_gpu_kernel<<<\n            GET_BLOCKS(num_kernels), THREADS_PER_BLOCK, 0,\n            at::cuda::getCurrentCUDAStream()>>>(\n            num_kernels, data_col_, data_im_, data_offset_, data_mask_,\n            channels, height_im, width_im, kernel_h, kernel_w, pad_h, pad_w,\n            stride_h, stride_w, dilation_h, dilation_w,\n            channel_per_deformable_group, batch_size,\n            2 * kernel_h * kernel_w * deformable_group, deformable_group,\n            height_col, width_col, grad_offset_, grad_mask_);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/ms_deform_attn_cuda.cu",
    "content": "/*!\n**************************************************************************************************\n* Deformable DETR\n* Copyright (c) 2020 SenseTime. All Rights Reserved.\n* Licensed under the Apache License, Version 2.0 [see LICENSE for details]\n**************************************************************************************************\n* Modified from\n*https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/tree/pytorch_1.0.0\n**************************************************************************************************\n*/\n\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n\n#include <THC/THCAtomics.cuh>\n#include <vector>\n\n#include \"ms_deform_attn_cuda_kernel.cuh\"\n\ntemplate <typename scalar_t>\nvoid ms_deformable_im2col_cuda(cudaStream_t stream, const scalar_t *data_value,\n                               const int64_t *data_spatial_shapes,\n                               const int64_t *data_level_start_index,\n                               const scalar_t *data_sampling_loc,\n                               const scalar_t *data_attn_weight,\n                               const int batch_size, const int spatial_size,\n                               const int num_heads, const int channels,\n                               const int num_levels, const int num_query,\n                               const int num_point, scalar_t *data_col) {\n  const int num_kernels = batch_size * num_query * num_heads * channels;\n  const int num_actual_kernels = batch_size * num_query * num_heads * channels;\n  const int num_threads = CUDA_NUM_THREADS;\n  ms_deformable_im2col_gpu_kernel<scalar_t>\n      <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0, stream>>>(\n          num_kernels, data_value, data_spatial_shapes, data_level_start_index,\n          data_sampling_loc, data_attn_weight, batch_size, spatial_size,\n          num_heads, channels, num_levels, num_query, num_point, data_col);\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\"error in ms_deformable_im2col_cuda: %s\\n\", cudaGetErrorString(err));\n  }\n}\n\ntemplate <typename scalar_t>\nvoid ms_deformable_col2im_cuda(\n    cudaStream_t stream, const scalar_t *grad_col, const scalar_t *data_value,\n    const int64_t *data_spatial_shapes, const int64_t *data_level_start_index,\n    const scalar_t *data_sampling_loc, const scalar_t *data_attn_weight,\n    const int batch_size, const int spatial_size, const int num_heads,\n    const int channels, const int num_levels, const int num_query,\n    const int num_point, scalar_t *grad_value, scalar_t *grad_sampling_loc,\n    scalar_t *grad_attn_weight) {\n  const int num_threads =\n      (channels > CUDA_NUM_THREADS) ? CUDA_NUM_THREADS : channels;\n  const int num_kernels = batch_size * num_query * num_heads * channels;\n  const int num_actual_kernels = batch_size * num_query * num_heads * channels;\n  if (channels > 1024) {\n    if ((channels & 1023) == 0) {\n      ms_deformable_col2im_gpu_kernel_shm_reduce_v2_multi_blocks<scalar_t>\n          <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads,\n             num_threads * 3 * sizeof(scalar_t), stream>>>(\n              num_kernels, grad_col, data_value, data_spatial_shapes,\n              data_level_start_index, data_sampling_loc, data_attn_weight,\n              batch_size, spatial_size, num_heads, channels, num_levels,\n              num_query, num_point, grad_value, grad_sampling_loc,\n              grad_attn_weight);\n    } else {\n      ms_deformable_col2im_gpu_kernel_gm<scalar_t>\n          <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n             stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                       data_level_start_index, data_sampling_loc,\n                       data_attn_weight, batch_size, spatial_size, num_heads,\n                       channels, num_levels, num_query, num_point, grad_value,\n                       grad_sampling_loc, grad_attn_weight);\n    }\n  } else {\n    switch (channels) {\n      case 1:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1<scalar_t,\n                                                                      1>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 2:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1<scalar_t,\n                                                                      2>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 4:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1<scalar_t,\n                                                                      4>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 8:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1<scalar_t,\n                                                                      8>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 16:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1<scalar_t,\n                                                                      16>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 32:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v1<scalar_t,\n                                                                      32>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 64:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v2<scalar_t,\n                                                                      64>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 128:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v2<scalar_t,\n                                                                      128>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 256:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v2<scalar_t,\n                                                                      256>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 512:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v2<scalar_t,\n                                                                      512>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      case 1024:\n        ms_deformable_col2im_gpu_kernel_shm_blocksize_aware_reduce_v2<scalar_t,\n                                                                      1024>\n            <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads, 0,\n               stream>>>(num_kernels, grad_col, data_value, data_spatial_shapes,\n                         data_level_start_index, data_sampling_loc,\n                         data_attn_weight, batch_size, spatial_size, num_heads,\n                         channels, num_levels, num_query, num_point, grad_value,\n                         grad_sampling_loc, grad_attn_weight);\n        break;\n      default:\n        if (channels < 64) {\n          ms_deformable_col2im_gpu_kernel_shm_reduce_v1<scalar_t>\n              <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads,\n                 num_threads * 3 * sizeof(scalar_t), stream>>>(\n                  num_kernels, grad_col, data_value, data_spatial_shapes,\n                  data_level_start_index, data_sampling_loc, data_attn_weight,\n                  batch_size, spatial_size, num_heads, channels, num_levels,\n                  num_query, num_point, grad_value, grad_sampling_loc,\n                  grad_attn_weight);\n        } else {\n          ms_deformable_col2im_gpu_kernel_shm_reduce_v2<scalar_t>\n              <<<GET_BLOCKS(num_actual_kernels, num_threads), num_threads,\n                 num_threads * 3 * sizeof(scalar_t), stream>>>(\n                  num_kernels, grad_col, data_value, data_spatial_shapes,\n                  data_level_start_index, data_sampling_loc, data_attn_weight,\n                  batch_size, spatial_size, num_heads, channels, num_levels,\n                  num_query, num_point, grad_value, grad_sampling_loc,\n                  grad_attn_weight);\n        }\n    }\n  }\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\"error in ms_deformable_col2im_cuda: %s\\n\", cudaGetErrorString(err));\n  }\n}\n\nat::Tensor ms_deform_attn_cuda_forward(const at::Tensor &value,\n                                       const at::Tensor &spatial_shapes,\n                                       const at::Tensor &level_start_index,\n                                       const at::Tensor &sampling_loc,\n                                       const at::Tensor &attn_weight,\n                                       const int im2col_step) {\n  AT_ASSERTM(value.is_contiguous(), \"value tensor has to be contiguous\");\n  AT_ASSERTM(spatial_shapes.is_contiguous(),\n             \"spatial_shapes tensor has to be contiguous\");\n  AT_ASSERTM(level_start_index.is_contiguous(),\n             \"level_start_index tensor has to be contiguous\");\n  AT_ASSERTM(sampling_loc.is_contiguous(),\n             \"sampling_loc tensor has to be contiguous\");\n  AT_ASSERTM(attn_weight.is_contiguous(),\n             \"attn_weight tensor has to be contiguous\");\n\n  AT_ASSERTM(value.is_cuda(), \"value must be a CUDA tensor\");\n  AT_ASSERTM(spatial_shapes.is_cuda(), \"spatial_shapes must be a CUDA tensor\");\n  AT_ASSERTM(level_start_index.is_cuda(),\n             \"level_start_index must be a CUDA tensor\");\n  AT_ASSERTM(sampling_loc.is_cuda(), \"sampling_loc must be a CUDA tensor\");\n  AT_ASSERTM(attn_weight.is_cuda(), \"attn_weight must be a CUDA tensor\");\n\n  const int batch = value.size(0);\n  const int spatial_size = value.size(1);\n  const int num_heads = value.size(2);\n  const int channels = value.size(3);\n\n  const int num_levels = spatial_shapes.size(0);\n\n  const int num_query = sampling_loc.size(1);\n  const int num_point = sampling_loc.size(4);\n\n  const int im2col_step_ = std::min(batch, im2col_step);\n\n  AT_ASSERTM(batch % im2col_step_ == 0, \"batch(%d) must divide im2col_step(%d)\",\n             batch, im2col_step_);\n\n  auto output =\n      at::zeros({batch, num_query, num_heads, channels}, value.options());\n\n  const int batch_n = im2col_step_;\n  auto output_n = output.view(\n      {batch / im2col_step_, batch_n, num_query, num_heads, channels});\n  auto per_value_size = spatial_size * num_heads * channels;\n  auto per_sample_loc_size = num_query * num_heads * num_levels * num_point * 2;\n  auto per_attn_weight_size = num_query * num_heads * num_levels * num_point;\n  for (int n = 0; n < batch / im2col_step_; ++n) {\n    auto columns = output_n.select(0, n);\n    AT_DISPATCH_FLOATING_TYPES(\n        value.scalar_type(), \"ms_deform_attn_forward_cuda\", ([&] {\n          ms_deformable_im2col_cuda(\n              at::cuda::getCurrentCUDAStream(),\n              value.data_ptr<scalar_t>() + n * im2col_step_ * per_value_size,\n              spatial_shapes.data_ptr<int64_t>(),\n              level_start_index.data_ptr<int64_t>(),\n              sampling_loc.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_sample_loc_size,\n              attn_weight.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_attn_weight_size,\n              batch_n, spatial_size, num_heads, channels, num_levels, num_query,\n              num_point, columns.data_ptr<scalar_t>());\n        }));\n  }\n\n  output = output.view({batch, num_query, num_heads * channels});\n\n  return output;\n}\n\nvoid ms_deform_attn_cuda_backward(\n    const at::Tensor &value, const at::Tensor &spatial_shapes,\n    const at::Tensor &level_start_index, const at::Tensor &sampling_loc,\n    const at::Tensor &attn_weight, const at::Tensor &grad_output,\n    at::Tensor &grad_value, at::Tensor &grad_sampling_loc,\n    at::Tensor &grad_attn_weight, const int im2col_step) {\n  AT_ASSERTM(value.is_contiguous(), \"value tensor has to be contiguous\");\n  AT_ASSERTM(spatial_shapes.is_contiguous(),\n             \"spatial_shapes tensor has to be contiguous\");\n  AT_ASSERTM(level_start_index.is_contiguous(),\n             \"level_start_index tensor has to be contiguous\");\n  AT_ASSERTM(sampling_loc.is_contiguous(),\n             \"sampling_loc tensor has to be contiguous\");\n  AT_ASSERTM(attn_weight.is_contiguous(),\n             \"attn_weight tensor has to be contiguous\");\n  AT_ASSERTM(grad_output.is_contiguous(),\n             \"grad_output tensor has to be contiguous\");\n\n  AT_ASSERTM(value.is_cuda(), \"value must be a CUDA tensor\");\n  AT_ASSERTM(spatial_shapes.is_cuda(), \"spatial_shapes must be a CUDA tensor\");\n  AT_ASSERTM(level_start_index.is_cuda(),\n             \"level_start_index must be a CUDA tensor\");\n  AT_ASSERTM(sampling_loc.is_cuda(), \"sampling_loc must be a CUDA tensor\");\n  AT_ASSERTM(attn_weight.is_cuda(), \"attn_weight must be a CUDA tensor\");\n  AT_ASSERTM(grad_output.is_cuda(), \"grad_output must be a CUDA tensor\");\n\n  const int batch = value.size(0);\n  const int spatial_size = value.size(1);\n  const int num_heads = value.size(2);\n  const int channels = value.size(3);\n\n  const int num_levels = spatial_shapes.size(0);\n\n  const int num_query = sampling_loc.size(1);\n  const int num_point = sampling_loc.size(4);\n\n  const int im2col_step_ = std::min(batch, im2col_step);\n\n  AT_ASSERTM(batch % im2col_step_ == 0, \"batch(%d) must divide im2col_step(%d)\",\n             batch, im2col_step_);\n\n  const int batch_n = im2col_step_;\n  auto per_value_size = spatial_size * num_heads * channels;\n  auto per_sample_loc_size = num_query * num_heads * num_levels * num_point * 2;\n  auto per_attn_weight_size = num_query * num_heads * num_levels * num_point;\n  auto grad_output_n = grad_output.view(\n      {batch / im2col_step_, batch_n, num_query, num_heads, channels});\n\n  for (int n = 0; n < batch / im2col_step_; ++n) {\n    auto grad_output_g = grad_output_n.select(0, n);\n    AT_DISPATCH_FLOATING_TYPES(\n        value.scalar_type(), \"ms_deform_attn_backward_cuda\", ([&] {\n          ms_deformable_col2im_cuda(\n              at::cuda::getCurrentCUDAStream(),\n              grad_output_g.data_ptr<scalar_t>(),\n              value.data_ptr<scalar_t>() + n * im2col_step_ * per_value_size,\n              spatial_shapes.data_ptr<int64_t>(),\n              level_start_index.data_ptr<int64_t>(),\n              sampling_loc.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_sample_loc_size,\n              attn_weight.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_attn_weight_size,\n              batch_n, spatial_size, num_heads, channels, num_levels, num_query,\n              num_point,\n              grad_value.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_value_size,\n              grad_sampling_loc.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_sample_loc_size,\n              grad_attn_weight.data_ptr<scalar_t>() +\n                  n * im2col_step_ * per_attn_weight_size);\n        }));\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/nms_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"nms_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nTensor NMSCUDAKernelLauncher(Tensor boxes, Tensor scores, float iou_threshold,\n                             int offset) {\n  at::cuda::CUDAGuard device_guard(boxes.device());\n\n  if (boxes.numel() == 0) {\n    return at::empty({0}, boxes.options().dtype(at::kLong));\n  }\n  auto order_t = std::get<1>(scores.sort(0, /*descending=*/true));\n  auto boxes_sorted = boxes.index_select(0, order_t);\n\n  int boxes_num = boxes.size(0);\n  const int col_blocks = DIVUP(boxes_num, threadsPerBlock);\n  Tensor mask =\n      at::empty({boxes_num, col_blocks}, boxes.options().dtype(at::kLong));\n  dim3 blocks(col_blocks, col_blocks);\n  dim3 threads(threadsPerBlock);\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  nms_cuda<<<blocks, threads, 0, stream>>>(\n      boxes_num, iou_threshold, offset, boxes_sorted.data_ptr<float>(),\n      (unsigned long long*)mask.data_ptr<int64_t>());\n\n  at::Tensor mask_cpu = mask.to(at::kCPU);\n  unsigned long long* mask_host =\n      (unsigned long long*)mask_cpu.data_ptr<int64_t>();\n\n  std::vector<unsigned long long> remv(col_blocks);\n  memset(&remv[0], 0, sizeof(unsigned long long) * col_blocks);\n\n  at::Tensor keep_t =\n      at::zeros({boxes_num}, boxes.options().dtype(at::kBool).device(at::kCPU));\n  bool* keep = keep_t.data_ptr<bool>();\n\n  for (int i = 0; i < boxes_num; i++) {\n    int nblock = i / threadsPerBlock;\n    int inblock = i % threadsPerBlock;\n\n    if (!(remv[nblock] & (1ULL << inblock))) {\n      keep[i] = true;\n      // set every overlap box with bit 1 in remv\n      unsigned long long* p = mask_host + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv[j] |= p[j];\n      }\n    }\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n  return order_t.masked_select(keep_t.to(at::kCUDA));\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/nms_rotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/nms_rotated/nms_rotated_cuda.cu\n#include \"nms_rotated_cuda.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nTensor nms_rotated_cuda(const Tensor dets, const Tensor scores,\n                        const Tensor order_t, const Tensor dets_sorted,\n                        float iou_threshold, const int multi_label) {\n  // using scalar_t = float;\n  AT_ASSERTM(dets.is_cuda(), \"dets must be a CUDA tensor\");\n  AT_ASSERTM(scores.is_cuda(), \"scores must be a CUDA tensor\");\n  at::cuda::CUDAGuard device_guard(dets.device());\n\n  int dets_num = dets.size(0);\n\n  const int col_blocks = at::cuda::ATenCeilDiv(dets_num, threadsPerBlock);\n\n  Tensor mask =\n      at::empty({dets_num * col_blocks}, dets.options().dtype(at::kLong));\n\n  dim3 blocks(col_blocks, col_blocks);\n  dim3 threads(threadsPerBlock);\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      dets_sorted.scalar_type(), \"nms_rotated_kernel_cuda\", [&] {\n        nms_rotated_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n            dets_num, iou_threshold, dets_sorted.data_ptr<scalar_t>(),\n            (unsigned long long*)mask.data_ptr<int64_t>(), multi_label);\n      });\n\n  Tensor mask_cpu = mask.to(at::kCPU);\n  unsigned long long* mask_host =\n      (unsigned long long*)mask_cpu.data_ptr<int64_t>();\n\n  std::vector<unsigned long long> remv(col_blocks);\n  memset(&remv[0], 0, sizeof(unsigned long long) * col_blocks);\n\n  Tensor keep =\n      at::empty({dets_num}, dets.options().dtype(at::kLong).device(at::kCPU));\n  int64_t* keep_out = keep.data_ptr<int64_t>();\n\n  int num_to_keep = 0;\n  for (int i = 0; i < dets_num; i++) {\n    int nblock = i / threadsPerBlock;\n    int inblock = i % threadsPerBlock;\n\n    if (!(remv[nblock] & (1ULL << inblock))) {\n      keep_out[num_to_keep++] = i;\n      unsigned long long* p = mask_host + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv[j] |= p[j];\n      }\n    }\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n  return order_t.index(\n      {keep.narrow(/*dim=*/0, /*start=*/0, /*length=*/num_to_keep)\n           .to(order_t.device(), keep.scalar_type())});\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/points_in_boxes_cuda.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/PCDet/blob/master/pcdet/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu\n// Written by Shaoshuai Shi\n// All Rights Reserved 2019.\n\n#include <stdio.h>\n\n#include \"points_in_boxes_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid PointsInBoxesPartForwardCUDAKernelLauncher(int batch_size, int boxes_num,\n                                                int pts_num, const Tensor boxes,\n                                                const Tensor pts,\n                                                Tensor box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is\n  // the bottom center, each box DO NOT overlaps params pts: (B, npoints, 3) [x,\n  // y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints), default\n  // -1\n\n  at::cuda::CUDAGuard device_guard(boxes.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks(DIVUP(pts_num, THREADS_PER_BLOCK), batch_size);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      boxes.scalar_type(), \"points_in_boxes_part_forward_cuda_kernel\", [&] {\n        points_in_boxes_part_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                batch_size, boxes_num, pts_num, boxes.data_ptr<scalar_t>(),\n                pts.data_ptr<scalar_t>(), box_idx_of_points.data_ptr<int>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid PointsInBoxesAllForwardCUDAKernelLauncher(int batch_size, int boxes_num,\n                                               int pts_num, const Tensor boxes,\n                                               const Tensor pts,\n                                               Tensor box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is the bottom center, each box params pts: (B, npoints, 3)\n  // [x, y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints),\n  // default -1\n\n  at::cuda::CUDAGuard device_guard(boxes.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks(DIVUP(pts_num, THREADS_PER_BLOCK), batch_size);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      boxes.scalar_type(), \"points_in_boxes_all_forward_cuda_kernel\", [&] {\n        points_in_boxes_all_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                batch_size, boxes_num, pts_num, boxes.data_ptr<scalar_t>(),\n                pts.data_ptr<scalar_t>(), box_idx_of_points.data_ptr<int>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/psamask_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/hszhao/semseg/blob/master/lib/psa/src\n\n#include <torch/serialize/tensor.h>\n#include \"psamask_cuda_kernel.cuh\"\n#include \"pytorch_cuda_helper.hpp\"\n\nvoid PSAMaskForwardCUDAKernelLauncher(const int psa_type, const Tensor input,\n                                      Tensor output, const int num_,\n                                      const int h_feature, const int w_feature,\n                                      const int h_mask, const int w_mask,\n                                      const int half_h_mask,\n                                      const int half_w_mask) {\n  int nthreads = num_ * h_feature * w_feature;\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  if (psa_type == 0)\n    AT_DISPATCH_FLOATING_TYPES(\n        input.scalar_type(), \"psamask_collect_forward_cuda\", [&] {\n          psamask_collect_forward_cuda<scalar_t><<<nthreads, 512, 0, stream>>>(\n              nthreads, h_feature, w_feature, h_mask, w_mask, half_h_mask,\n              half_w_mask, input.data_ptr<scalar_t>(),\n              output.data_ptr<scalar_t>());\n        });\n  else\n    AT_DISPATCH_FLOATING_TYPES(\n        input.scalar_type(), \"psamask_distribute_forward_cuda\", [&] {\n          psamask_distribute_forward_cuda<scalar_t>\n              <<<nthreads, 512, 0, stream>>>(\n                  nthreads, h_feature, w_feature, h_mask, w_mask, half_h_mask,\n                  half_w_mask, input.data_ptr<scalar_t>(),\n                  output.data_ptr<scalar_t>());\n        });\n}\n\nvoid PSAMaskBackwardCUDAKernelLauncher(\n    const int psa_type, const Tensor grad_output, Tensor grad_input,\n    const int num_, const int h_feature, const int w_feature, const int h_mask,\n    const int w_mask, const int half_h_mask, const int half_w_mask) {\n  int nthreads = num_ * h_feature * w_feature;\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  if (psa_type == 0)\n    AT_DISPATCH_FLOATING_TYPES(\n        grad_input.scalar_type(), \"psamask_collect_backward_cuda\", [&] {\n          psamask_collect_backward_cuda<scalar_t><<<nthreads, 512, 0, stream>>>(\n              nthreads, h_feature, w_feature, h_mask, w_mask, half_h_mask,\n              half_w_mask, grad_output.data_ptr<scalar_t>(),\n              grad_input.data_ptr<scalar_t>());\n        });\n  else\n    AT_DISPATCH_FLOATING_TYPES(\n        grad_input.scalar_type(), \"psamask_distribute_backward_cuda\", [&] {\n          psamask_distribute_backward_cuda<scalar_t>\n              <<<nthreads, 512, 0, stream>>>(\n                  nthreads, h_feature, w_feature, h_mask, w_mask, half_h_mask,\n                  half_w_mask, grad_output.data_ptr<scalar_t>(),\n                  grad_input.data_ptr<scalar_t>());\n        });\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/roi_align_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cuda_helper.hpp\"\n#include \"roi_align_cuda_kernel.cuh\"\n\nvoid ROIAlignForwardCUDAKernelLauncher(Tensor input, Tensor rois, Tensor output,\n                                       Tensor argmax_y, Tensor argmax_x,\n                                       int aligned_height, int aligned_width,\n                                       float spatial_scale, int sampling_ratio,\n                                       int pool_mode, bool aligned) {\n  int output_size = output.numel();\n  int channels = input.size(1);\n  int height = input.size(2);\n  int width = input.size(3);\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"roi_align_forward_cuda_kernel\", [&] {\n        roi_align_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, input.data_ptr<scalar_t>(),\n                rois.data_ptr<scalar_t>(), output.data_ptr<scalar_t>(),\n                argmax_y.data_ptr<scalar_t>(), argmax_x.data_ptr<scalar_t>(),\n                aligned_height, aligned_width,\n                static_cast<scalar_t>(spatial_scale), sampling_ratio, pool_mode,\n                aligned, channels, height, width);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid ROIAlignBackwardCUDAKernelLauncher(Tensor grad_output, Tensor rois,\n                                        Tensor argmax_y, Tensor argmax_x,\n                                        Tensor grad_input, int aligned_height,\n                                        int aligned_width, float spatial_scale,\n                                        int sampling_ratio, int pool_mode,\n                                        bool aligned) {\n  int output_size = grad_output.numel();\n  int channels = grad_input.size(1);\n  int height = grad_input.size(2);\n  int width = grad_input.size(3);\n\n  at::cuda::CUDAGuard device_guard(grad_output.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"roi_align_backward_cuda_kernel\", [&] {\n        roi_align_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, grad_output.data_ptr<scalar_t>(),\n                rois.data_ptr<scalar_t>(), argmax_y.data_ptr<scalar_t>(),\n                argmax_x.data_ptr<scalar_t>(), grad_input.data_ptr<scalar_t>(),\n                aligned_height, aligned_width,\n                static_cast<scalar_t>(spatial_scale), sampling_ratio, pool_mode,\n                aligned, channels, height, width);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/roi_align_rotated_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cuda_helper.hpp\"\n#include \"roi_align_rotated_cuda_kernel.cuh\"\n\nvoid ROIAlignRotatedForwardCUDAKernelLauncher(\n    const at::Tensor features, const at::Tensor rois, const float spatial_scale,\n    const int sample_num, const bool aligned, const bool clockwise,\n    const int channels, const int height, const int width, const int num_rois,\n    const int pooled_height, const int pooled_width, at::Tensor output) {\n  const int output_size = num_rois * pooled_height * pooled_width * channels;\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      features.scalar_type(), \"ROIAlignRotatedLaucherForward\", ([&] {\n        const scalar_t *bottom_data = features.data_ptr<scalar_t>();\n        const scalar_t *rois_data = rois.data_ptr<scalar_t>();\n        scalar_t *top_data = output.data_ptr<scalar_t>();\n\n        roi_align_rotated_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK>>>(\n                output_size, bottom_data, rois_data, scalar_t(spatial_scale),\n                sample_num, aligned, clockwise, channels, height, width,\n                pooled_height, pooled_width, top_data);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid ROIAlignRotatedBackwardCUDAKernelLauncher(\n    const at::Tensor top_grad, const at::Tensor rois, const float spatial_scale,\n    const int sample_num, const bool aligned, const bool clockwise,\n    const int channels, const int height, const int width, const int num_rois,\n    const int pooled_height, const int pooled_width, at::Tensor bottom_grad) {\n  const int output_size = num_rois * pooled_height * pooled_width * channels;\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      top_grad.scalar_type(), \"ROIAlignLaucherBackward\", ([&] {\n        const scalar_t *top_diff = top_grad.data_ptr<scalar_t>();\n        const scalar_t *rois_data = rois.data_ptr<scalar_t>();\n        scalar_t *bottom_diff = bottom_grad.data_ptr<scalar_t>();\n        roi_align_rotated_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK>>>(\n                output_size, top_diff, rois_data, spatial_scale, sample_num,\n                aligned, clockwise, channels, height, width, pooled_height,\n                pooled_width, bottom_diff);\n      }));\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/roi_pool_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cuda_helper.hpp\"\n#include \"roi_pool_cuda_kernel.cuh\"\n\nvoid ROIPoolForwardCUDAKernelLauncher(Tensor input, Tensor rois, Tensor output,\n                                      Tensor argmax, int pooled_height,\n                                      int pooled_width, float spatial_scale) {\n  int output_size = output.numel();\n  int channels = input.size(1);\n  int height = input.size(2);\n  int width = input.size(3);\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"roi_pool_forward_cuda_kernel\", [&] {\n        roi_pool_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, input.data_ptr<scalar_t>(),\n                rois.data_ptr<scalar_t>(), output.data_ptr<scalar_t>(),\n                argmax.data_ptr<int>(), pooled_height, pooled_width,\n                static_cast<scalar_t>(spatial_scale), channels, height, width);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid ROIPoolBackwardCUDAKernelLauncher(Tensor grad_output, Tensor rois,\n                                       Tensor argmax, Tensor grad_input,\n                                       int pooled_height, int pooled_width,\n                                       float spatial_scale) {\n  int output_size = grad_output.numel();\n  int channels = grad_input.size(1);\n  int height = grad_input.size(2);\n  int width = grad_input.size(3);\n\n  at::cuda::CUDAGuard device_guard(grad_output.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"roi_pool_backward_cuda_kernel\", [&] {\n        roi_pool_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, grad_output.data_ptr<scalar_t>(),\n                rois.data_ptr<scalar_t>(), argmax.data_ptr<int>(),\n                grad_input.data_ptr<scalar_t>(), pooled_height, pooled_width,\n                channels, height, width);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/roiaware_pool3d_cuda.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/PCDet/blob/master/pcdet/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu\n// Written by Shaoshuai Shi\n// All Rights Reserved 2019.\n\n#include <stdio.h>\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"roiaware_pool3d_cuda_kernel.cuh\"\n\nvoid RoiawarePool3dForwardCUDAKernelLauncher(\n    int boxes_num, int pts_num, int channels, int max_pts_each_voxel, int out_x,\n    int out_y, int out_z, const Tensor rois, const Tensor pts,\n    const Tensor pts_feature, Tensor argmax, Tensor pts_idx_of_voxels,\n    Tensor pooled_features, int pool_method) {\n  // params rois: (N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate params pts: (npoints, 3) [x, y, z] in LiDAR coordinate params\n  // pts_feature: (npoints, C) params argmax: (N, out_x, out_y, out_z, C) params\n  // pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel) params\n  // pooled_features: (N, out_x, out_y, out_z, C) params pool_method: 0:\n  // max_pool 1: avg_pool\n\n  at::cuda::CUDAGuard device_guard(pts_feature.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  Tensor pts_mask =\n      -at::ones({boxes_num, pts_num}, pts_feature.options().dtype(at::kInt));\n\n  dim3 blocks_mask(DIVUP(pts_num, THREADS_PER_BLOCK), boxes_num);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      rois.scalar_type(), \"generate_pts_mask_for_box3d\", [&] {\n        generate_pts_mask_for_box3d<scalar_t>\n            <<<blocks_mask, threads, 0, stream>>>(\n                boxes_num, pts_num, out_x, out_y, out_z,\n                rois.data_ptr<scalar_t>(), pts.data_ptr<scalar_t>(),\n                pts_mask.data_ptr<int>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  // TODO: Merge the collect and pool functions, SS\n\n  dim3 blocks_collect(DIVUP(boxes_num, THREADS_PER_BLOCK));\n\n  AT_DISPATCH_INTEGRAL_TYPES(\n      pts_idx_of_voxels.scalar_type(), \"collect_inside_pts_for_box3d\", [&] {\n        collect_inside_pts_for_box3d<scalar_t>\n            <<<blocks_collect, threads, 0, stream>>>(\n                boxes_num, pts_num, max_pts_each_voxel, out_x, out_y, out_z,\n                pts_mask.data_ptr<int>(),\n                pts_idx_of_voxels.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  dim3 blocks_pool(DIVUP(out_x * out_y * out_z, THREADS_PER_BLOCK), channels,\n                   boxes_num);\n  if (pool_method == 0) {\n    AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n        pts_feature.scalar_type(), \"roiaware_maxpool3d\", [&] {\n          roiaware_maxpool3d<scalar_t><<<blocks_pool, threads, 0, stream>>>(\n              boxes_num, pts_num, channels, max_pts_each_voxel, out_x, out_y,\n              out_z, pts_feature.data_ptr<scalar_t>(),\n              pts_idx_of_voxels.data_ptr<int>(),\n              pooled_features.data_ptr<scalar_t>(), argmax.data_ptr<int>());\n        });\n  } else if (pool_method == 1) {\n    AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n        pts_feature.scalar_type(), \"roiaware_avgpool3d\", [&] {\n          roiaware_avgpool3d<scalar_t><<<blocks_pool, threads, 0, stream>>>(\n              boxes_num, pts_num, channels, max_pts_each_voxel, out_x, out_y,\n              out_z, pts_feature.data_ptr<scalar_t>(),\n              pts_idx_of_voxels.data_ptr<int>(),\n              pooled_features.data_ptr<scalar_t>());\n        });\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid RoiawarePool3dBackwardCUDAKernelLauncher(\n    int boxes_num, int out_x, int out_y, int out_z, int channels,\n    int max_pts_each_voxel, const Tensor pts_idx_of_voxels, const Tensor argmax,\n    const Tensor grad_out, Tensor grad_in, int pool_method) {\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n  // params pool_method: 0: max_pool, 1: avg_pool\n\n  at::cuda::CUDAGuard device_guard(grad_out.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 blocks(DIVUP(out_x * out_y * out_z, THREADS_PER_BLOCK), channels,\n              boxes_num);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  if (pool_method == 0) {\n    AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n        grad_in.scalar_type(), \"roiaware_maxpool3d_backward\", [&] {\n          roiaware_maxpool3d_backward<scalar_t><<<blocks, threads, 0, stream>>>(\n              boxes_num, channels, out_x, out_y, out_z, argmax.data_ptr<int>(),\n              grad_out.data_ptr<scalar_t>(), grad_in.data_ptr<scalar_t>());\n        });\n  } else if (pool_method == 1) {\n    AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n        grad_in.scalar_type(), \"roiaware_avgpool3d_backward\", [&] {\n          roiaware_avgpool3d_backward<scalar_t><<<blocks, threads, 0, stream>>>(\n              boxes_num, channels, out_x, out_y, out_z, max_pts_each_voxel,\n              pts_idx_of_voxels.data_ptr<int>(), grad_out.data_ptr<scalar_t>(),\n              grad_in.data_ptr<scalar_t>());\n        });\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/roipoint_pool3d_cuda.cu",
    "content": "/*\nModified from\nhttps://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/roipoint_pool3d/src/roipoint_pool3d_kernel.cu\nPoint cloud feature pooling\nWritten by Shaoshuai Shi\nAll Rights Reserved 2018.\n*/\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"roipoint_pool3d_cuda_kernel.cuh\"\n\nvoid RoIPointPool3dForwardCUDAKernelLauncher(\n    int batch_size, int pts_num, int boxes_num, int feature_in_len,\n    int sampled_pts_num, const Tensor xyz, const Tensor boxes3d,\n    const Tensor pts_feature, Tensor pooled_features,\n    Tensor pooled_empty_flag) {\n  Tensor pts_assign = at::empty({batch_size, pts_num, boxes_num},\n                                boxes3d.options().dtype(at::kInt));\n\n  at::cuda::CUDAGuard device_guard(xyz.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(pts_num, THREADS_PER_BLOCK), boxes_num, batch_size);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      xyz.scalar_type(), \"assign_pts_to_box3d\", [&] {\n        assign_pts_to_box3d<scalar_t><<<blocks, threads, 0, stream>>>(\n            batch_size, pts_num, boxes_num, xyz.data_ptr<scalar_t>(),\n            boxes3d.data_ptr<scalar_t>(), pts_assign.data_ptr<int>());\n      });\n\n  Tensor pts_idx = at::empty({batch_size, boxes_num, sampled_pts_num},\n                             boxes3d.options().dtype(at::kInt));\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks2(DIVUP(boxes_num, THREADS_PER_BLOCK), batch_size);\n\n  get_pooled_idx<<<blocks2, threads, 0, stream>>>(\n      batch_size, pts_num, boxes_num, sampled_pts_num,\n      pts_assign.data_ptr<int>(), pts_idx.data_ptr<int>(),\n      pooled_empty_flag.data_ptr<int>());\n\n  dim3 blocks_pool(DIVUP(sampled_pts_num, THREADS_PER_BLOCK), boxes_num,\n                   batch_size);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      xyz.scalar_type(), \"roipoint_pool3d_forward\", [&] {\n        roipoint_pool3d_forward<scalar_t><<<blocks_pool, threads, 0, stream>>>(\n            batch_size, pts_num, boxes_num, feature_in_len, sampled_pts_num,\n            xyz.data_ptr<scalar_t>(), pts_idx.data_ptr<int>(),\n            pts_feature.data_ptr<scalar_t>(),\n            pooled_features.data_ptr<scalar_t>(),\n            pooled_empty_flag.data_ptr<int>());\n      });\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/scatter_points_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#include <stdio.h>\n#include <stdlib.h>\n#include <torch/types.h>\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"scatter_points_cuda_kernel.cuh\"\n\nstd::vector<at::Tensor> DynamicPointToVoxelForwardCUDAKernelLauncher(\n    const at::Tensor &feats, const at::Tensor &coors,\n    const reduce_t reduce_type) {\n  const int num_input = feats.size(0);\n  const int num_feats = feats.size(1);\n\n  if (num_input == 0)\n    return {feats.clone().detach(), coors.clone().detach(),\n            coors.new_empty({0}, torch::kInt32),\n            coors.new_empty({0}, torch::kInt32)};\n\n  at::Tensor out_coors;\n  at::Tensor coors_map;\n  at::Tensor reduce_count;\n\n  auto coors_clean = coors.masked_fill(coors.lt(0).any(-1, true), -1);\n\n  std::tie(out_coors, coors_map, reduce_count) =\n      at::unique_dim(coors_clean, 0, true, true, true);\n\n  // the first element of out_coors is always (-1,-1,-1) and should be removed\n  out_coors = out_coors.slice(0, 1);\n  reduce_count = reduce_count.slice(0, 1).to(torch::kInt32);\n  coors_map = coors_map.to(torch::kInt32) - 1;\n\n  auto reduced_feats =\n      at::empty({out_coors.size(0), num_feats}, feats.options());\n\n  at::cuda::CUDAGuard device_guard(feats.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES(\n      feats.scalar_type(), \"feats_reduce_kernel\", ([&] {\n        if (reduce_type == reduce_t::MAX)\n          reduced_feats.fill_(-std::numeric_limits<scalar_t>::infinity());\n        else\n          reduced_feats.fill_(static_cast<scalar_t>(0));\n\n        dim3 blocks(std::min(\n            at::cuda::ATenCeilDiv(num_input, THREADS_PER_BLOCK), maxGridDim));\n        dim3 threads(THREADS_PER_BLOCK);\n        feats_reduce_kernel<<<blocks, threads, 0, stream>>>(\n            feats.data_ptr<scalar_t>(), coors_map.data_ptr<int32_t>(),\n            reduced_feats.data_ptr<scalar_t>(), num_input, num_feats,\n            reduce_type);\n        if (reduce_type == reduce_t::MEAN)\n          reduced_feats /= reduce_count.unsqueeze(-1).to(reduced_feats.dtype());\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  return {reduced_feats, out_coors, coors_map, reduce_count};\n}\n\nvoid DynamicPointToVoxelBackwardCUDAKernelLauncher(\n    at::Tensor &grad_feats, const at::Tensor &grad_reduced_feats,\n    const at::Tensor &feats, const at::Tensor &reduced_feats,\n    const at::Tensor &coors_map, const at::Tensor &reduce_count,\n    const reduce_t reduce_type) {\n  const int num_input = feats.size(0);\n  const int num_reduced = reduced_feats.size(0);\n  const int num_feats = feats.size(1);\n\n  grad_feats.fill_(0);\n  // copy voxel grad to points\n\n  if (num_input == 0 || num_reduced == 0) return;\n  at::cuda::CUDAGuard device_guard(feats.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  if (reduce_type == reduce_t::MEAN || reduce_type == reduce_t::SUM) {\n    AT_DISPATCH_FLOATING_TYPES(\n        grad_reduced_feats.scalar_type(), \"add_reduce_traceback_grad_kernel\",\n        ([&] {\n          dim3 blocks(std::min(\n              at::cuda::ATenCeilDiv(num_input, THREADS_PER_BLOCK), maxGridDim));\n          dim3 threads(THREADS_PER_BLOCK);\n          add_reduce_traceback_grad_kernel<<<blocks, threads, 0, stream>>>(\n              grad_feats.data_ptr<scalar_t>(),\n              grad_reduced_feats.data_ptr<scalar_t>(),\n              coors_map.data_ptr<int32_t>(), reduce_count.data_ptr<int32_t>(),\n              num_input, num_feats, reduce_type);\n        }));\n\n    AT_CUDA_CHECK(cudaGetLastError());\n  } else {\n    auto reduce_from = at::full({num_reduced, num_feats}, num_input,\n                                coors_map.options().dtype(torch::kInt32));\n    AT_DISPATCH_FLOATING_TYPES(\n        grad_reduced_feats.scalar_type(),\n        \"max_reduce_traceback_scatter_idx_kernel\", ([&] {\n          dim3 blocks(std::min(\n              at::cuda::ATenCeilDiv(num_input, THREADS_PER_BLOCK), maxGridDim));\n          dim3 threads(THREADS_PER_BLOCK);\n          max_reduce_traceback_scatter_idx_kernel<<<blocks, threads, 0,\n                                                    stream>>>(\n              feats.data_ptr<scalar_t>(), reduced_feats.data_ptr<scalar_t>(),\n              reduce_from.data_ptr<int32_t>(), coors_map.data_ptr<int32_t>(),\n              num_input, num_feats);\n        }));\n\n    AT_CUDA_CHECK(cudaGetLastError());\n\n    AT_DISPATCH_FLOATING_TYPES(\n        grad_reduced_feats.scalar_type(),\n        \"max_reduce_traceback_scatter_idx_kernel\", ([&] {\n          dim3 blocks(\n              std::min(at::cuda::ATenCeilDiv(num_reduced, THREADS_PER_BLOCK),\n                       maxGridDim));\n          dim3 threads(THREADS_PER_BLOCK);\n          max_reduce_scatter_grad_kernel<<<blocks, threads, 0, stream>>>(\n              grad_feats.data_ptr<scalar_t>(),\n              grad_reduced_feats.data_ptr<scalar_t>(),\n              reduce_from.data_ptr<int32_t>(), num_reduced, num_feats);\n        }));\n\n    AT_CUDA_CHECK(cudaGetLastError());\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/sync_bn_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cuda_helper.hpp\"\n#include \"sync_bn_cuda_kernel.cuh\"\n\nvoid SyncBNForwardMeanCUDAKernelLauncher(const Tensor input, Tensor mean) {\n  int num = input.size(0);\n  int channels = input.size(1);\n  int spatial = input.size(2);\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"sync_bn_forward_mean_cuda_kernel\", [&] {\n        sync_bn_forward_mean_cuda_kernel<scalar_t>\n            <<<channels, THREADS_PER_BLOCK, 0, stream>>>(\n                input.data_ptr<scalar_t>(), mean.data_ptr<float>(), num,\n                channels, spatial);\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SyncBNForwardVarCUDAKernelLauncher(const Tensor input, const Tensor mean,\n                                        Tensor var) {\n  int num = input.size(0);\n  int channels = input.size(1);\n  int spatial = input.size(2);\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"sync_bn_forward_mean_cuda_kernel\", [&] {\n        sync_bn_forward_var_cuda_kernel<scalar_t>\n            <<<channels, THREADS_PER_BLOCK, 0, stream>>>(\n                input.data_ptr<scalar_t>(), mean.data_ptr<float>(),\n                var.data_ptr<float>(), num, channels, spatial);\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SyncBNForwardOutputCUDAKernelLauncher(\n    const Tensor input, const Tensor mean, const Tensor var,\n    Tensor running_mean, Tensor running_var, const Tensor weight,\n    const Tensor bias, Tensor norm, Tensor std, Tensor output, float eps,\n    float momentum, int group_size) {\n  int num = input.size(0);\n  int channels = input.size(1);\n  int spatial = input.size(2);\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"sync_bn_forward_mean_cuda_kernel\", [&] {\n        sync_bn_forward_output_cuda_kernel<scalar_t>\n            <<<channels, THREADS_PER_BLOCK, 0, stream>>>(\n                input.data_ptr<scalar_t>(), mean.data_ptr<float>(),\n                var.data_ptr<float>(), running_mean.data_ptr<float>(),\n                running_var.data_ptr<float>(), weight.data_ptr<float>(),\n                bias.data_ptr<float>(), norm.data_ptr<float>(),\n                std.data_ptr<float>(), output.data_ptr<scalar_t>(), num,\n                channels, spatial, eps, momentum, group_size);\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SyncBNBackwardParamCUDAKernelLauncher(const Tensor grad_output,\n                                           const Tensor norm,\n                                           Tensor grad_weight,\n                                           Tensor grad_bias) {\n  int num = grad_output.size(0);\n  int channels = grad_output.size(1);\n  int spatial = grad_output.size(2);\n\n  at::cuda::CUDAGuard device_guard(grad_output.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"sync_bn_backward_param_cuda_kernel\", [&] {\n        sync_bn_backward_param_cuda_kernel<scalar_t>\n            <<<channels, THREADS_PER_BLOCK, 0, stream>>>(\n                grad_output.data_ptr<scalar_t>(), norm.data_ptr<float>(),\n                grad_weight.data_ptr<float>(), grad_bias.data_ptr<float>(), num,\n                channels, spatial);\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid SyncBNBackwardDataCUDAKernelLauncher(const Tensor grad_output,\n                                          const Tensor weight,\n                                          const Tensor grad_weight,\n                                          const Tensor grad_bias,\n                                          const Tensor norm, const Tensor std,\n                                          Tensor grad_input) {\n  int output_size = grad_input.numel();\n  int num = grad_input.size(0);\n  int channels = grad_input.size(1);\n  int spatial = grad_input.size(2);\n\n  at::cuda::CUDAGuard device_guard(grad_input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"sync_bn_backward_data_cuda_kernel\", [&] {\n        sync_bn_backward_data_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(output_size), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, grad_output.data_ptr<scalar_t>(),\n                weight.data_ptr<float>(), grad_weight.data_ptr<float>(),\n                grad_bias.data_ptr<float>(), norm.data_ptr<float>(),\n                std.data_ptr<float>(), grad_input.data_ptr<scalar_t>(), num,\n                channels, spatial);\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/three_interpolate_cuda.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/interpolate_gpu.cu\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"three_interpolate_cuda_kernel.cuh\"\n\nvoid ThreeInterpolateForwardCUDAKernelLauncher(int b, int c, int m, int n,\n                                               const Tensor points,\n                                               const Tensor idx,\n                                               const Tensor weight,\n                                               Tensor out) {\n  // points: (B, C, M)\n  // idx: (B, N, 3)\n  // weight: (B, N, 3)\n  // output:\n  //      out: (B, C, N)\n\n  at::cuda::CUDAGuard device_guard(points.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(n, THREADS_PER_BLOCK), c, b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      points.scalar_type(), \"three_interpolate_forward_cuda_kernel\", [&] {\n        three_interpolate_forward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, c, m, n, points.data_ptr<scalar_t>(), idx.data_ptr<int>(),\n                weight.data_ptr<scalar_t>(), out.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid ThreeInterpolateBackwardCUDAKernelLauncher(int b, int c, int n, int m,\n                                                const Tensor grad_out,\n                                                const Tensor idx,\n                                                const Tensor weight,\n                                                Tensor grad_points) {\n  // grad_out: (B, C, N)\n  // weight: (B, N, 3)\n  // output:\n  //      grad_points: (B, C, M)\n\n  at::cuda::CUDAGuard device_guard(grad_out.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(n, THREADS_PER_BLOCK), c, b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_out.scalar_type(), \"three_interpolate_backward_cuda_kernel\", [&] {\n        three_interpolate_backward_cuda_kernel<scalar_t>\n            <<<blocks, threads, 0, stream>>>(\n                b, c, n, m, grad_out.data_ptr<scalar_t>(), idx.data_ptr<int>(),\n                weight.data_ptr<scalar_t>(), grad_points.data_ptr<scalar_t>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/three_nn_cuda.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/interpolate_gpu.cu\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"three_nn_cuda_kernel.cuh\"\n\nvoid ThreeNNForwardCUDAKernelLauncher(int b, int n, int m, const Tensor unknown,\n                                      const Tensor known, Tensor dist2,\n                                      Tensor idx) {\n  // unknown: (B, N, 3)\n  // known: (B, M, 3)\n  // output:\n  //      dist2: (B, N, 3)\n  //      idx: (B, N, 3)\n\n  at::cuda::CUDAGuard device_guard(unknown.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  // blockIdx.x(col), blockIdx.y(row)\n  dim3 blocks(DIVUP(n, THREADS_PER_BLOCK), b);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      unknown.scalar_type(), \"three_nn_forward_cuda_kernel\", [&] {\n        three_nn_forward_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n            b, n, m, unknown.data_ptr<scalar_t>(), known.data_ptr<scalar_t>(),\n            dist2.data_ptr<scalar_t>(), idx.data_ptr<int>());\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/tin_shift_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cuda_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n#include \"tin_shift_cuda_kernel.cuh\"\n\nvoid TINShiftForwardCUDAKernelLauncher(Tensor input, Tensor shift,\n                                       Tensor output) {\n  int output_size = output.numel();\n  int batch_size = input.size(0);\n  int t_size = input.size(1);\n  int channels = input.size(2);\n  int hw_size = input.size(3);\n  int group_size = shift.size(1);\n  int group_channel = channels / group_size;\n  int num_kernels = batch_size * hw_size * channels;\n\n  at::cuda::CUDAGuard device_guard(input.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"tin_shift_forward_cuda_kernel\", [&] {\n        tin_shift_forward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(num_kernels), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, input.data_ptr<scalar_t>(), shift.data_ptr<int>(),\n                output.data_ptr<scalar_t>(), batch_size, channels, t_size,\n                hw_size, group_size, group_channel);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n\nvoid TINShiftBackwardCUDAKernelLauncher(Tensor grad_output, Tensor shift,\n                                        Tensor grad_input) {\n  int output_size = grad_output.numel();\n  int batch_size = grad_output.size(0);\n  int t_size = grad_output.size(1);\n  int channels = grad_output.size(2);\n  int hw_size = grad_output.size(3);\n  int group_size = shift.size(1);\n  int group_channel = channels / group_size;\n  int num_kernels = batch_size * hw_size * channels;\n\n  at::cuda::CUDAGuard device_guard(grad_output.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad_output.scalar_type(), \"tin_shift_backward_cuda_kernel\", [&] {\n        tin_shift_backward_cuda_kernel<scalar_t>\n            <<<GET_BLOCKS(num_kernels), THREADS_PER_BLOCK, 0, stream>>>(\n                output_size, grad_output.data_ptr<scalar_t>(),\n                shift.data_ptr<int>(), grad_input.data_ptr<scalar_t>(),\n                batch_size, channels, t_size, hw_size, group_size,\n                group_channel);\n      });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/upfirdn2d_kernel.cu",
    "content": "// Modified from\n// https://github.com/rosinality/stylegan2-pytorch/blob/master/op/upfirdn2d_kernel.cu\n// Copyright (c) 2019, NVIDIA Corporation. All rights reserved.\n//\n// This work is made available under the Nvidia Source Code License-NC.\n// To view a copy of this license, visit\n// https://nvlabs.github.io/stylegan2/license.html\n\n#include <ATen/ATen.h>\n#include <ATen/AccumulateType.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <torch/types.h>\n\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n\nstatic __host__ __device__ __forceinline__ int floor_div(int a, int b) {\n  int c = a / b;\n\n  if (c * b > a) {\n    c--;\n  }\n\n  return c;\n}\n\nstruct UpFirDn2DKernelParams {\n  int up_x;\n  int up_y;\n  int down_x;\n  int down_y;\n  int pad_x0;\n  int pad_x1;\n  int pad_y0;\n  int pad_y1;\n\n  int major_dim;\n  int in_h;\n  int in_w;\n  int minor_dim;\n  int kernel_h;\n  int kernel_w;\n  int out_h;\n  int out_w;\n  int loop_major;\n  int loop_x;\n};\n\ntemplate <typename scalar_t>\n__global__ void upfirdn2d_kernel_large(scalar_t *out, const scalar_t *input,\n                                       const scalar_t *kernel,\n                                       const UpFirDn2DKernelParams p) {\n  int minor_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  int out_y = minor_idx / p.minor_dim;\n  minor_idx -= out_y * p.minor_dim;\n  int out_x_base = blockIdx.y * p.loop_x * blockDim.y + threadIdx.y;\n  int major_idx_base = blockIdx.z * p.loop_major;\n\n  if (out_x_base >= p.out_w || out_y >= p.out_h ||\n      major_idx_base >= p.major_dim) {\n    return;\n  }\n\n  int mid_y = out_y * p.down_y + p.up_y - 1 - p.pad_y0;\n  int in_y = min(max(floor_div(mid_y, p.up_y), 0), p.in_h);\n  int h = min(max(floor_div(mid_y + p.kernel_h, p.up_y), 0), p.in_h) - in_y;\n  int kernel_y = mid_y + p.kernel_h - (in_y + 1) * p.up_y;\n\n  for (int loop_major = 0, major_idx = major_idx_base;\n       loop_major < p.loop_major && major_idx < p.major_dim;\n       loop_major++, major_idx++) {\n    for (int loop_x = 0, out_x = out_x_base;\n         loop_x < p.loop_x && out_x < p.out_w; loop_x++, out_x += blockDim.y) {\n      int mid_x = out_x * p.down_x + p.up_x - 1 - p.pad_x0;\n      int in_x = min(max(floor_div(mid_x, p.up_x), 0), p.in_w);\n      int w = min(max(floor_div(mid_x + p.kernel_w, p.up_x), 0), p.in_w) - in_x;\n      int kernel_x = mid_x + p.kernel_w - (in_x + 1) * p.up_x;\n\n      const scalar_t *x_p =\n          &input[((major_idx * p.in_h + in_y) * p.in_w + in_x) * p.minor_dim +\n                 minor_idx];\n      const scalar_t *k_p = &kernel[kernel_y * p.kernel_w + kernel_x];\n      int x_px = p.minor_dim;\n      int k_px = -p.up_x;\n      int x_py = p.in_w * p.minor_dim;\n      int k_py = -p.up_y * p.kernel_w;\n\n      scalar_t v = 0.0f;\n\n      for (int y = 0; y < h; y++) {\n        for (int x = 0; x < w; x++) {\n          v += static_cast<scalar_t>(*x_p) * static_cast<scalar_t>(*k_p);\n          x_p += x_px;\n          k_p += k_px;\n        }\n\n        x_p += x_py - w * x_px;\n        k_p += k_py - w * k_px;\n      }\n\n      out[((major_idx * p.out_h + out_y) * p.out_w + out_x) * p.minor_dim +\n          minor_idx] = v;\n    }\n  }\n}\n\ntemplate <typename scalar_t, int up_x, int up_y, int down_x, int down_y,\n          int kernel_h, int kernel_w, int tile_out_h, int tile_out_w>\n__global__ void upfirdn2d_kernel(scalar_t *out, const scalar_t *input,\n                                 const scalar_t *kernel,\n                                 const UpFirDn2DKernelParams p) {\n  const int tile_in_h = ((tile_out_h - 1) * down_y + kernel_h - 1) / up_y + 1;\n  const int tile_in_w = ((tile_out_w - 1) * down_x + kernel_w - 1) / up_x + 1;\n\n  __shared__ volatile float sk[kernel_h][kernel_w];\n  __shared__ volatile float sx[tile_in_h][tile_in_w];\n\n  int minor_idx = blockIdx.x;\n  int tile_out_y = minor_idx / p.minor_dim;\n  minor_idx -= tile_out_y * p.minor_dim;\n  tile_out_y *= tile_out_h;\n  int tile_out_x_base = blockIdx.y * p.loop_x * tile_out_w;\n  int major_idx_base = blockIdx.z * p.loop_major;\n\n  if (tile_out_x_base >= p.out_w | tile_out_y >= p.out_h |\n      major_idx_base >= p.major_dim) {\n    return;\n  }\n\n  for (int tap_idx = threadIdx.x; tap_idx < kernel_h * kernel_w;\n       tap_idx += blockDim.x) {\n    int ky = tap_idx / kernel_w;\n    int kx = tap_idx - ky * kernel_w;\n    scalar_t v = 0.0;\n\n    if (kx < p.kernel_w & ky < p.kernel_h) {\n      v = kernel[(p.kernel_h - 1 - ky) * p.kernel_w + (p.kernel_w - 1 - kx)];\n    }\n\n    sk[ky][kx] = v;\n  }\n\n  for (int loop_major = 0, major_idx = major_idx_base;\n       loop_major < p.loop_major & major_idx < p.major_dim;\n       loop_major++, major_idx++) {\n    for (int loop_x = 0, tile_out_x = tile_out_x_base;\n         loop_x < p.loop_x & tile_out_x < p.out_w;\n         loop_x++, tile_out_x += tile_out_w) {\n      int tile_mid_x = tile_out_x * down_x + up_x - 1 - p.pad_x0;\n      int tile_mid_y = tile_out_y * down_y + up_y - 1 - p.pad_y0;\n      int tile_in_x = floor_div(tile_mid_x, up_x);\n      int tile_in_y = floor_div(tile_mid_y, up_y);\n\n      __syncthreads();\n\n      for (int in_idx = threadIdx.x; in_idx < tile_in_h * tile_in_w;\n           in_idx += blockDim.x) {\n        int rel_in_y = in_idx / tile_in_w;\n        int rel_in_x = in_idx - rel_in_y * tile_in_w;\n        int in_x = rel_in_x + tile_in_x;\n        int in_y = rel_in_y + tile_in_y;\n\n        scalar_t v = 0.0;\n\n        if (in_x >= 0 & in_y >= 0 & in_x < p.in_w & in_y < p.in_h) {\n          v = input[((major_idx * p.in_h + in_y) * p.in_w + in_x) *\n                        p.minor_dim +\n                    minor_idx];\n        }\n\n        sx[rel_in_y][rel_in_x] = v;\n      }\n\n      __syncthreads();\n      for (int out_idx = threadIdx.x; out_idx < tile_out_h * tile_out_w;\n           out_idx += blockDim.x) {\n        int rel_out_y = out_idx / tile_out_w;\n        int rel_out_x = out_idx - rel_out_y * tile_out_w;\n        int out_x = rel_out_x + tile_out_x;\n        int out_y = rel_out_y + tile_out_y;\n\n        int mid_x = tile_mid_x + rel_out_x * down_x;\n        int mid_y = tile_mid_y + rel_out_y * down_y;\n        int in_x = floor_div(mid_x, up_x);\n        int in_y = floor_div(mid_y, up_y);\n        int rel_in_x = in_x - tile_in_x;\n        int rel_in_y = in_y - tile_in_y;\n        int kernel_x = (in_x + 1) * up_x - mid_x - 1;\n        int kernel_y = (in_y + 1) * up_y - mid_y - 1;\n\n        scalar_t v = 0.0;\n\n#pragma unroll\n        for (int y = 0; y < kernel_h / up_y; y++)\n#pragma unroll\n          for (int x = 0; x < kernel_w / up_x; x++)\n            v += sx[rel_in_y + y][rel_in_x + x] *\n                 sk[kernel_y + y * up_y][kernel_x + x * up_x];\n\n        if (out_x < p.out_w & out_y < p.out_h) {\n          out[((major_idx * p.out_h + out_y) * p.out_w + out_x) * p.minor_dim +\n              minor_idx] = v;\n        }\n      }\n    }\n  }\n}\n\ntorch::Tensor upfirdn2d_op(const torch::Tensor &input,\n                           const torch::Tensor &kernel, int up_x, int up_y,\n                           int down_x, int down_y, int pad_x0, int pad_x1,\n                           int pad_y0, int pad_y1) {\n  int curDevice = -1;\n  cudaGetDevice(&curDevice);\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream(curDevice);\n\n  UpFirDn2DKernelParams p;\n\n  auto x = input.contiguous();\n  auto k = kernel.contiguous();\n\n  p.major_dim = x.size(0);\n  p.in_h = x.size(1);\n  p.in_w = x.size(2);\n  p.minor_dim = x.size(3);\n  p.kernel_h = k.size(0);\n  p.kernel_w = k.size(1);\n  p.up_x = up_x;\n  p.up_y = up_y;\n  p.down_x = down_x;\n  p.down_y = down_y;\n  p.pad_x0 = pad_x0;\n  p.pad_x1 = pad_x1;\n  p.pad_y0 = pad_y0;\n  p.pad_y1 = pad_y1;\n\n  p.out_h = (p.in_h * p.up_y + p.pad_y0 + p.pad_y1 - p.kernel_h + p.down_y) /\n            p.down_y;\n  p.out_w = (p.in_w * p.up_x + p.pad_x0 + p.pad_x1 - p.kernel_w + p.down_x) /\n            p.down_x;\n\n  auto out =\n      at::empty({p.major_dim, p.out_h, p.out_w, p.minor_dim}, x.options());\n\n  int mode = -1;\n\n  int tile_out_h = -1;\n  int tile_out_w = -1;\n\n  if (p.up_x == 1 && p.up_y == 1 && p.down_x == 1 && p.down_y == 1 &&\n      p.kernel_h <= 4 && p.kernel_w <= 4) {\n    mode = 1;\n    tile_out_h = 16;\n    tile_out_w = 64;\n  }\n\n  if (p.up_x == 1 && p.up_y == 1 && p.down_x == 1 && p.down_y == 1 &&\n      p.kernel_h <= 3 && p.kernel_w <= 3) {\n    mode = 2;\n    tile_out_h = 16;\n    tile_out_w = 64;\n  }\n\n  if (p.up_x == 2 && p.up_y == 2 && p.down_x == 1 && p.down_y == 1 &&\n      p.kernel_h <= 4 && p.kernel_w <= 4) {\n    mode = 3;\n    tile_out_h = 16;\n    tile_out_w = 64;\n  }\n\n  if (p.up_x == 2 && p.up_y == 2 && p.down_x == 1 && p.down_y == 1 &&\n      p.kernel_h <= 2 && p.kernel_w <= 2) {\n    mode = 4;\n    tile_out_h = 16;\n    tile_out_w = 64;\n  }\n\n  if (p.up_x == 1 && p.up_y == 1 && p.down_x == 2 && p.down_y == 2 &&\n      p.kernel_h <= 4 && p.kernel_w <= 4) {\n    mode = 5;\n    tile_out_h = 8;\n    tile_out_w = 32;\n  }\n\n  if (p.up_x == 1 && p.up_y == 1 && p.down_x == 2 && p.down_y == 2 &&\n      p.kernel_h <= 2 && p.kernel_w <= 2) {\n    mode = 6;\n    tile_out_h = 8;\n    tile_out_w = 32;\n  }\n\n  dim3 block_size;\n  dim3 grid_size;\n\n  if (tile_out_h > 0 && tile_out_w > 0) {\n    p.loop_major = (p.major_dim - 1) / 16384 + 1;\n    p.loop_x = 1;\n    block_size = dim3(32 * 8, 1, 1);\n    grid_size = dim3(((p.out_h - 1) / tile_out_h + 1) * p.minor_dim,\n                     (p.out_w - 1) / (p.loop_x * tile_out_w) + 1,\n                     (p.major_dim - 1) / p.loop_major + 1);\n  } else {\n    p.loop_major = (p.major_dim - 1) / 16384 + 1;\n    p.loop_x = 4;\n    block_size = dim3(4, 32, 1);\n    grid_size = dim3((p.out_h * p.minor_dim - 1) / block_size.x + 1,\n                     (p.out_w - 1) / (p.loop_x * block_size.y) + 1,\n                     (p.major_dim - 1) / p.loop_major + 1);\n  }\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(x.scalar_type(), \"upfirdn2d_cuda\", [&] {\n    switch (mode) {\n      case 1:\n        upfirdn2d_kernel<scalar_t, 1, 1, 1, 1, 4, 4, 16, 64>\n            <<<grid_size, block_size, 0, stream>>>(out.data_ptr<scalar_t>(),\n                                                   x.data_ptr<scalar_t>(),\n                                                   k.data_ptr<scalar_t>(), p);\n\n        break;\n\n      case 2:\n        upfirdn2d_kernel<scalar_t, 1, 1, 1, 1, 3, 3, 16, 64>\n            <<<grid_size, block_size, 0, stream>>>(out.data_ptr<scalar_t>(),\n                                                   x.data_ptr<scalar_t>(),\n                                                   k.data_ptr<scalar_t>(), p);\n\n        break;\n\n      case 3:\n        upfirdn2d_kernel<scalar_t, 2, 2, 1, 1, 4, 4, 16, 64>\n            <<<grid_size, block_size, 0, stream>>>(out.data_ptr<scalar_t>(),\n                                                   x.data_ptr<scalar_t>(),\n                                                   k.data_ptr<scalar_t>(), p);\n\n        break;\n\n      case 4:\n        upfirdn2d_kernel<scalar_t, 2, 2, 1, 1, 2, 2, 16, 64>\n            <<<grid_size, block_size, 0, stream>>>(out.data_ptr<scalar_t>(),\n                                                   x.data_ptr<scalar_t>(),\n                                                   k.data_ptr<scalar_t>(), p);\n\n        break;\n\n      case 5:\n        upfirdn2d_kernel<scalar_t, 1, 1, 2, 2, 4, 4, 8, 32>\n            <<<grid_size, block_size, 0, stream>>>(out.data_ptr<scalar_t>(),\n                                                   x.data_ptr<scalar_t>(),\n                                                   k.data_ptr<scalar_t>(), p);\n\n        break;\n\n      case 6:\n        upfirdn2d_kernel<scalar_t, 1, 1, 2, 2, 4, 4, 8, 32>\n            <<<grid_size, block_size, 0, stream>>>(out.data_ptr<scalar_t>(),\n                                                   x.data_ptr<scalar_t>(),\n                                                   k.data_ptr<scalar_t>(), p);\n\n        break;\n\n      default:\n        upfirdn2d_kernel_large<scalar_t><<<grid_size, block_size, 0, stream>>>(\n            out.data_ptr<scalar_t>(), x.data_ptr<scalar_t>(),\n            k.data_ptr<scalar_t>(), p);\n    }\n  });\n\n  return out;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/cuda/voxelization_cuda.cu",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"pytorch_cuda_helper.hpp\"\n#include \"voxelization_cuda_kernel.cuh\"\n\nint HardVoxelizeForwardCUDAKernelLauncher(\n    const at::Tensor &points, at::Tensor &voxels, at::Tensor &coors,\n    at::Tensor &num_points_per_voxel, const std::vector<float> voxel_size,\n    const std::vector<float> coors_range, const int max_points,\n    const int max_voxels, const int NDim = 3) {\n  // current version tooks about 0.04s for one frame on cpu\n  // check device\n\n  at::cuda::CUDAGuard device_guard(points.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  const int num_points = points.size(0);\n  const int num_features = points.size(1);\n\n  const float voxel_x = voxel_size[0];\n  const float voxel_y = voxel_size[1];\n  const float voxel_z = voxel_size[2];\n  const float coors_x_min = coors_range[0];\n  const float coors_y_min = coors_range[1];\n  const float coors_z_min = coors_range[2];\n  const float coors_x_max = coors_range[3];\n  const float coors_y_max = coors_range[4];\n  const float coors_z_max = coors_range[5];\n\n  const int grid_x = round((coors_x_max - coors_x_min) / voxel_x);\n  const int grid_y = round((coors_y_max - coors_y_min) / voxel_y);\n  const int grid_z = round((coors_z_max - coors_z_min) / voxel_z);\n\n  // map points to voxel coors\n  at::Tensor temp_coors =\n      at::zeros({num_points, NDim}, points.options().dtype(at::kInt));\n\n  dim3 grid(std::min(at::cuda::ATenCeilDiv(num_points, 512), 4096));\n  dim3 block(512);\n\n  // 1. link point to corresponding voxel coors\n  AT_DISPATCH_ALL_TYPES(\n      points.scalar_type(), \"hard_voxelize_kernel\", ([&] {\n        dynamic_voxelize_kernel<scalar_t, int><<<grid, block, 0, stream>>>(\n            points.contiguous().data_ptr<scalar_t>(),\n            temp_coors.contiguous().data_ptr<int>(), voxel_x, voxel_y, voxel_z,\n            coors_x_min, coors_y_min, coors_z_min, coors_x_max, coors_y_max,\n            coors_z_max, grid_x, grid_y, grid_z, num_points, num_features,\n            NDim);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  // 2. map point to the idx of the corresponding voxel, find duplicate coor\n  // create some temporary variables\n  auto point_to_pointidx = -at::ones(\n      {\n          num_points,\n      },\n      points.options().dtype(at::kInt));\n  auto point_to_voxelidx = -at::ones(\n      {\n          num_points,\n      },\n      points.options().dtype(at::kInt));\n\n  dim3 map_grid(std::min(at::cuda::ATenCeilDiv(num_points, 512), 4096));\n  dim3 map_block(512);\n\n  AT_DISPATCH_ALL_TYPES(\n      temp_coors.scalar_type(), \"determin_duplicate\", ([&] {\n        point_to_voxelidx_kernel<int><<<map_grid, map_block, 0, stream>>>(\n            temp_coors.contiguous().data_ptr<int>(),\n            point_to_voxelidx.contiguous().data_ptr<int>(),\n            point_to_pointidx.contiguous().data_ptr<int>(), max_points,\n            max_voxels, num_points, NDim);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  // 3. determine voxel num and voxel's coor index\n  // make the logic in the CUDA device could accelerate about 10 times\n  auto coor_to_voxelidx = -at::ones(\n      {\n          num_points,\n      },\n      points.options().dtype(at::kInt));\n  auto voxel_num = at::zeros(\n      {\n          1,\n      },\n      points.options().dtype(at::kInt));  // must be zero from the beginning\n\n  AT_DISPATCH_ALL_TYPES(temp_coors.scalar_type(), \"determin_duplicate\", ([&] {\n                          determin_voxel_num<int><<<1, 1, 0, stream>>>(\n                              num_points_per_voxel.contiguous().data_ptr<int>(),\n                              point_to_voxelidx.contiguous().data_ptr<int>(),\n                              point_to_pointidx.contiguous().data_ptr<int>(),\n                              coor_to_voxelidx.contiguous().data_ptr<int>(),\n                              voxel_num.contiguous().data_ptr<int>(),\n                              max_points, max_voxels, num_points);\n                        }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  // 4. copy point features to voxels\n  // Step 4 & 5 could be parallel\n  auto pts_output_size = num_points * num_features;\n  dim3 cp_grid(std::min(at::cuda::ATenCeilDiv(pts_output_size, 512), 4096));\n  dim3 cp_block(512);\n  AT_DISPATCH_ALL_TYPES(\n      points.scalar_type(), \"assign_point_to_voxel\", ([&] {\n        assign_point_to_voxel<float, int><<<cp_grid, cp_block, 0, stream>>>(\n            pts_output_size, points.contiguous().data_ptr<float>(),\n            point_to_voxelidx.contiguous().data_ptr<int>(),\n            coor_to_voxelidx.contiguous().data_ptr<int>(),\n            voxels.contiguous().data_ptr<float>(), max_points, num_features,\n            num_points, NDim);\n      }));\n  //   cudaDeviceSynchronize();\n  //   AT_CUDA_CHECK(cudaGetLastError());\n\n  // 5. copy coors of each voxels\n  auto coors_output_size = num_points * NDim;\n  dim3 coors_cp_grid(\n      std::min(at::cuda::ATenCeilDiv(coors_output_size, 512), 4096));\n  dim3 coors_cp_block(512);\n  AT_DISPATCH_ALL_TYPES(\n      points.scalar_type(), \"assign_point_to_voxel\", ([&] {\n        assign_voxel_coors<float, int>\n            <<<coors_cp_grid, coors_cp_block, 0, stream>>>(\n                coors_output_size, temp_coors.contiguous().data_ptr<int>(),\n                point_to_voxelidx.contiguous().data_ptr<int>(),\n                coor_to_voxelidx.contiguous().data_ptr<int>(),\n                coors.contiguous().data_ptr<int>(), num_points, NDim);\n      }));\n\n  AT_CUDA_CHECK(cudaGetLastError());\n\n  auto voxel_num_cpu = voxel_num.to(at::kCPU);\n  int voxel_num_int = voxel_num_cpu.data_ptr<int>()[0];\n\n  return voxel_num_int;\n}\n\nvoid DynamicVoxelizeForwardCUDAKernelLauncher(\n    const at::Tensor &points, at::Tensor &coors,\n    const std::vector<float> voxel_size, const std::vector<float> coors_range,\n    const int NDim = 3) {\n  // current version tooks about 0.04s for one frame on cpu\n  // check device\n\n  at::cuda::CUDAGuard device_guard(points.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  const int num_points = points.size(0);\n  const int num_features = points.size(1);\n\n  const float voxel_x = voxel_size[0];\n  const float voxel_y = voxel_size[1];\n  const float voxel_z = voxel_size[2];\n  const float coors_x_min = coors_range[0];\n  const float coors_y_min = coors_range[1];\n  const float coors_z_min = coors_range[2];\n  const float coors_x_max = coors_range[3];\n  const float coors_y_max = coors_range[4];\n  const float coors_z_max = coors_range[5];\n\n  const int grid_x = round((coors_x_max - coors_x_min) / voxel_x);\n  const int grid_y = round((coors_y_max - coors_y_min) / voxel_y);\n  const int grid_z = round((coors_z_max - coors_z_min) / voxel_z);\n\n  const int col_blocks = at::cuda::ATenCeilDiv(num_points, THREADS_PER_BLOCK);\n  dim3 blocks(col_blocks);\n  dim3 threads(THREADS_PER_BLOCK);\n\n  AT_DISPATCH_ALL_TYPES(points.scalar_type(), \"dynamic_voxelize_kernel\", [&] {\n    dynamic_voxelize_kernel<scalar_t, int><<<blocks, threads, 0, stream>>>(\n        points.contiguous().data_ptr<scalar_t>(),\n        coors.contiguous().data_ptr<int>(), voxel_x, voxel_y, voxel_z,\n        coors_x_min, coors_y_min, coors_z_min, coors_x_max, coors_y_max,\n        coors_z_max, grid_x, grid_y, grid_z, num_points, num_features, NDim);\n  });\n\n  AT_CUDA_CHECK(cudaGetLastError());\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/deform_conv.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid deformable_im2col_impl(Tensor data_im, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor data_col) {\n  DISPATCH_DEVICE_IMPL(deformable_im2col_impl, data_im, data_offset, channels,\n                       height, width, ksize_h, ksize_w, pad_h, pad_w, stride_h,\n                       stride_w, dilation_h, dilation_w, parallel_imgs,\n                       deformable_group, data_col);\n}\n\nvoid deformable_col2im_impl(Tensor data_col, Tensor data_offset,\n                            const int channels, const int height,\n                            const int width, const int ksize_h,\n                            const int ksize_w, const int pad_h, const int pad_w,\n                            const int stride_h, const int stride_w,\n                            const int dilation_h, const int dilation_w,\n                            const int parallel_imgs, const int deformable_group,\n                            Tensor grad_im) {\n  DISPATCH_DEVICE_IMPL(deformable_col2im_impl, data_col, data_offset, channels,\n                       height, width, ksize_h, ksize_w, pad_h, pad_w, stride_h,\n                       stride_w, dilation_h, dilation_w, parallel_imgs,\n                       deformable_group, grad_im);\n}\n\nvoid deformable_col2im_coord_impl(\n    Tensor data_col, Tensor data_im, Tensor data_offset, const int channels,\n    const int height, const int width, const int ksize_h, const int ksize_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int parallel_imgs,\n    const int deformable_group, Tensor grad_offset) {\n  DISPATCH_DEVICE_IMPL(deformable_col2im_coord_impl, data_col, data_im,\n                       data_offset, channels, height, width, ksize_h, ksize_w,\n                       pad_h, pad_w, stride_h, stride_w, dilation_h, dilation_w,\n                       parallel_imgs, deformable_group, grad_offset);\n}\n\nvoid deform_conv_shape_check(at::Tensor input, at::Tensor offset,\n                             at::Tensor *gradOutput, at::Tensor weight, int kH,\n                             int kW, int dH, int dW, int padH, int padW,\n                             int dilationH, int dilationW, int group,\n                             int deformable_group) {\n  TORCH_CHECK(\n      weight.ndimension() == 4,\n      \"4D weight tensor (nOutputPlane,nInputPlane,kH,kW) expected, but got: %s\",\n      weight.ndimension());\n\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  TORCH_CHECK(kW > 0 && kH > 0,\n              \"kernel size should be greater than zero, but got kH: %d kW: %d\",\n              kH, kW);\n\n  TORCH_CHECK((weight.size(2) == kH && weight.size(3) == kW),\n              \"kernel size should be consistent with weight, \",\n              \"but got kH: %d kW: %d weight.size(2): %d, weight.size(3): %d\",\n              kH, kW, weight.size(2), weight.size(3));\n\n  TORCH_CHECK(dW > 0 && dH > 0,\n              \"stride should be greater than zero, but got dH: %d dW: %d\", dH,\n              dW);\n\n  TORCH_CHECK(\n      dilationW > 0 && dilationH > 0,\n      \"dilation should be greater than 0, but got dilationH: %d dilationW: %d\",\n      dilationH, dilationW);\n\n  int ndim = input.ndimension();\n  int dimf = 0;\n  int dimh = 1;\n  int dimw = 2;\n\n  if (ndim == 4) {\n    dimf++;\n    dimh++;\n    dimw++;\n  }\n\n  TORCH_CHECK(ndim == 3 || ndim == 4,\n              \"3D or 4D input tensor expected but got: %s\", ndim);\n\n  long nInputPlane = weight.size(1) * group;\n  long inputHeight = input.size(dimh);\n  long inputWidth = input.size(dimw);\n  long nOutputPlane = weight.size(0);\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n\n  TORCH_CHECK(nInputPlane % deformable_group == 0,\n              \"input channels must divide deformable group size\");\n\n  if (outputWidth < 1 || outputHeight < 1)\n    AT_ERROR(\n        \"Given input size: (%ld x %ld x %ld). \"\n        \"Calculated output size: (%ld x %ld x %ld). Output size is too small\",\n        nInputPlane, inputHeight, inputWidth, nOutputPlane, outputHeight,\n        outputWidth);\n\n  TORCH_CHECK(input.size(1) == nInputPlane,\n              \"invalid number of input planes, expected: %d, but got: %d\",\n              nInputPlane, input.size(1));\n\n  TORCH_CHECK((inputHeight >= kH && inputWidth >= kW),\n              \"input image is smaller than kernel\");\n\n  TORCH_CHECK(\n      (offset.size(2) == outputHeight && offset.size(3) == outputWidth),\n      \"invalid spatial size of offset, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      outputHeight, outputWidth, offset.size(2), offset.size(3));\n\n  TORCH_CHECK((offset.size(1) == deformable_group * 2 * kH * kW),\n              \"invalid number of channels of offset\");\n\n  if (gradOutput != NULL) {\n    TORCH_CHECK(\n        gradOutput->size(dimf) == nOutputPlane,\n        \"invalid number of gradOutput planes, expected: %d, but got: %d\",\n        nOutputPlane, gradOutput->size(dimf));\n\n    TORCH_CHECK(\n        (gradOutput->size(dimh) == outputHeight &&\n         gradOutput->size(dimw) == outputWidth),\n        \"invalid size of gradOutput, expected height: %d width: %d , but \"\n        \"got height: %d width: %d\",\n        outputHeight, outputWidth, gradOutput->size(dimh),\n        gradOutput->size(dimw));\n  }\n}\n\nvoid deform_conv_forward(Tensor input, Tensor weight, Tensor offset,\n                         Tensor output, Tensor columns, Tensor ones, int kW,\n                         int kH, int dW, int dH, int padW, int padH,\n                         int dilationW, int dilationH, int group,\n                         int deformable_group, int im2col_step) {\n  if (input.device().is_cuda()) {\n#ifdef MMCV_WITH_CUDA\n    CHECK_CUDA_INPUT(input);\n    CHECK_CUDA_INPUT(offset);\n    CHECK_CUDA_INPUT(weight);\n    CHECK_CUDA_INPUT(output);\n    CHECK_CUDA_INPUT(columns);\n    CHECK_CUDA_INPUT(ones);\n#else\n    AT_ERROR(\"DeformConv is not compiled with GPU support\");\n#endif\n  } else {\n    CHECK_CPU_INPUT(input);\n    CHECK_CPU_INPUT(offset);\n    CHECK_CPU_INPUT(weight);\n    CHECK_CPU_INPUT(output);\n    CHECK_CPU_INPUT(columns);\n    CHECK_CPU_INPUT(ones);\n  }\n\n  deform_conv_shape_check(input, offset, NULL, weight, kH, kW, dH, dW, padH,\n                          padW, dilationH, dilationW, group, deformable_group);\n  at::DeviceGuard guard(input.device());\n\n  int batch = 1;\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input.unsqueeze_(0);\n    offset.unsqueeze_(0);\n  }\n\n  // todo: assert batchsize dividable by im2col_step\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = weight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), \"invalid batch size of offset\");\n\n  output = output.view({batchSize / im2col_step, im2col_step, nOutputPlane,\n                        outputHeight, outputWidth});\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < outputHeight * outputWidth) {\n    ones = at::ones({outputHeight, outputWidth}, input.options());\n  }\n\n  input = input.view({batchSize / im2col_step, im2col_step, nInputPlane,\n                      inputHeight, inputWidth});\n  offset =\n      offset.view({batchSize / im2col_step, im2col_step,\n                   deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  Tensor output_buffer = at::zeros({batchSize / im2col_step, nOutputPlane,\n                                    im2col_step * outputHeight, outputWidth},\n                                   output.options());\n\n  output_buffer = output_buffer.view(\n      {output_buffer.size(0), group, output_buffer.size(1) / group,\n       output_buffer.size(2), output_buffer.size(3)});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    deformable_im2col_impl(input[elt], offset[elt], nInputPlane, inputHeight,\n                           inputWidth, kH, kW, padH, padW, dH, dW, dilationH,\n                           dilationW, im2col_step, deformable_group, columns);\n\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view({group, weight.size(0) / group, weight.size(1),\n                          weight.size(2), weight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      output_buffer[elt][g] = output_buffer[elt][g]\n                                  .flatten(1)\n                                  .addmm_(weight[g].flatten(1), columns[g])\n                                  .view_as(output_buffer[elt][g]);\n    }\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    weight = weight.view({weight.size(0) * weight.size(1), weight.size(2),\n                          weight.size(3), weight.size(4)});\n  }\n\n  output_buffer = output_buffer.view(\n      {output_buffer.size(0), output_buffer.size(1) * output_buffer.size(2),\n       output_buffer.size(3), output_buffer.size(4)});\n\n  output_buffer = output_buffer.view({batchSize / im2col_step, nOutputPlane,\n                                      im2col_step, outputHeight, outputWidth});\n  output_buffer.transpose_(1, 2);\n  output.copy_(output_buffer);\n  output = output.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    output = output.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n    offset = offset.view({offset.size(1), offset.size(2), offset.size(3)});\n  }\n}\n\nvoid deform_conv_backward_input(Tensor input, Tensor offset, Tensor gradOutput,\n                                Tensor gradInput, Tensor gradOffset,\n                                Tensor weight, Tensor columns, int kW, int kH,\n                                int dW, int dH, int padW, int padH,\n                                int dilationW, int dilationH, int group,\n                                int deformable_group, int im2col_step) {\n  if (input.device().is_cuda()) {\n#ifdef MMCV_WITH_CUDA\n    CHECK_CUDA_INPUT(input);\n    CHECK_CUDA_INPUT(offset);\n    CHECK_CUDA_INPUT(gradOutput);\n    CHECK_CUDA_INPUT(gradInput);\n    CHECK_CUDA_INPUT(gradOffset);\n    CHECK_CUDA_INPUT(weight);\n    CHECK_CUDA_INPUT(columns);\n#else\n    AT_ERROR(\"DeformConv is not compiled with GPU support\");\n#endif\n  } else {\n    CHECK_CPU_INPUT(input);\n    CHECK_CPU_INPUT(offset);\n    CHECK_CPU_INPUT(gradOutput);\n    CHECK_CPU_INPUT(gradInput);\n    CHECK_CPU_INPUT(gradOffset);\n    CHECK_CPU_INPUT(weight);\n    CHECK_CPU_INPUT(columns);\n  }\n  deform_conv_shape_check(input, offset, &gradOutput, weight, kH, kW, dH, dW,\n                          padH, padW, dilationH, dilationW, group,\n                          deformable_group);\n\n  at::DeviceGuard guard(input.device());\n\n  int batch = 1;\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input = input.view({1, input.size(0), input.size(1), input.size(2)});\n    offset = offset.view({1, offset.size(0), offset.size(1), offset.size(2)});\n    gradOutput = gradOutput.view(\n        {1, gradOutput.size(0), gradOutput.size(1), gradOutput.size(2)});\n  }\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = weight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), 3, \"invalid batch size of offset\");\n  gradInput = gradInput.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  // change order of grad output\n  gradOutput = gradOutput.view({batchSize / im2col_step, im2col_step,\n                                nOutputPlane, outputHeight, outputWidth});\n  gradOutput.transpose_(1, 2);\n\n  gradInput = gradInput.view({batchSize / im2col_step, im2col_step, nInputPlane,\n                              inputHeight, inputWidth});\n  input = input.view({batchSize / im2col_step, im2col_step, nInputPlane,\n                      inputHeight, inputWidth});\n  gradOffset = gradOffset.view({batchSize / im2col_step, im2col_step,\n                                deformable_group * 2 * kH * kW, outputHeight,\n                                outputWidth});\n  offset =\n      offset.view({batchSize / im2col_step, im2col_step,\n                   deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    // divide into groups\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view({group, weight.size(0) / group, weight.size(1),\n                          weight.size(2), weight.size(3)});\n    gradOutput = gradOutput.view(\n        {gradOutput.size(0), group, gradOutput.size(1) / group,\n         gradOutput.size(2), gradOutput.size(3), gradOutput.size(4)});\n\n    for (int g = 0; g < group; g++) {\n      columns[g] = columns[g].addmm_(weight[g].flatten(1).transpose(0, 1),\n                                     gradOutput[elt][g].flatten(1), 0.0f, 1.0f);\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    gradOutput = gradOutput.view(\n        {gradOutput.size(0), gradOutput.size(1) * gradOutput.size(2),\n         gradOutput.size(3), gradOutput.size(4), gradOutput.size(5)});\n\n    deformable_col2im_coord_impl(columns, input[elt], offset[elt], nInputPlane,\n                                 inputHeight, inputWidth, kH, kW, padH, padW,\n                                 dH, dW, dilationH, dilationW, im2col_step,\n                                 deformable_group, gradOffset[elt]);\n\n    deformable_col2im_impl(columns, offset[elt], nInputPlane, inputHeight,\n                           inputWidth, kH, kW, padH, padW, dH, dW, dilationH,\n                           dilationW, im2col_step, deformable_group,\n                           gradInput[elt]);\n\n    weight = weight.view({weight.size(0) * weight.size(1), weight.size(2),\n                          weight.size(3), weight.size(4)});\n  }\n\n  gradOutput.transpose_(1, 2);\n  gradOutput =\n      gradOutput.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  gradInput = gradInput.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  gradOffset = gradOffset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    gradOutput = gradOutput.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n    gradInput = gradInput.view({nInputPlane, inputHeight, inputWidth});\n    offset = offset.view({offset.size(1), offset.size(2), offset.size(3)});\n    gradOffset =\n        gradOffset.view({offset.size(1), offset.size(2), offset.size(3)});\n  }\n}\n\nvoid deform_conv_backward_parameters(Tensor input, Tensor offset,\n                                     Tensor gradOutput, Tensor gradWeight,\n                                     Tensor columns, Tensor ones, int kW,\n                                     int kH, int dW, int dH, int padW, int padH,\n                                     int dilationW, int dilationH, int group,\n                                     int deformable_group, float scale,\n                                     int im2col_step) {\n  if (input.device().is_cuda()) {\n#ifdef MMCV_WITH_CUDA\n    CHECK_CUDA_INPUT(input);\n    CHECK_CUDA_INPUT(offset);\n    CHECK_CUDA_INPUT(gradOutput);\n    CHECK_CUDA_INPUT(gradWeight);\n    CHECK_CUDA_INPUT(columns);\n    CHECK_CUDA_INPUT(ones);\n#else\n    AT_ERROR(\"DeformConv is not compiled with GPU support\");\n#endif\n  } else {\n    CHECK_CPU_INPUT(input);\n    CHECK_CPU_INPUT(offset);\n    CHECK_CPU_INPUT(gradOutput);\n    CHECK_CPU_INPUT(gradWeight);\n    CHECK_CPU_INPUT(columns);\n    CHECK_CPU_INPUT(ones);\n  }\n\n  deform_conv_shape_check(input, offset, &gradOutput, gradWeight, kH, kW, dH,\n                          dW, padH, padW, dilationH, dilationW, group,\n                          deformable_group);\n  at::DeviceGuard guard(input.device());\n\n  int batch = 1;\n\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input = input.view(\n        at::IntList({1, input.size(0), input.size(1), input.size(2)}));\n    gradOutput = gradOutput.view(\n        {1, gradOutput.size(0), gradOutput.size(1), gradOutput.size(2)});\n  }\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = gradWeight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), \"invalid batch size of offset\");\n\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  gradOutput = gradOutput.view({batchSize / im2col_step, im2col_step,\n                                nOutputPlane, outputHeight, outputWidth});\n  gradOutput.transpose_(1, 2);\n\n  Tensor gradOutputBuffer = at::zeros_like(gradOutput);\n  gradOutputBuffer =\n      gradOutputBuffer.view({batchSize / im2col_step, nOutputPlane, im2col_step,\n                             outputHeight, outputWidth});\n  gradOutputBuffer = gradOutputBuffer.contiguous();\n  gradOutputBuffer.copy_(gradOutput);\n  gradOutputBuffer =\n      gradOutputBuffer.view({batchSize / im2col_step, nOutputPlane,\n                             im2col_step * outputHeight, outputWidth});\n\n  gradOutput.transpose_(1, 2);\n  gradOutput =\n      gradOutput.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  input = input.view({batchSize / im2col_step, im2col_step, nInputPlane,\n                      inputHeight, inputWidth});\n  offset =\n      offset.view({batchSize / im2col_step, im2col_step,\n                   deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    deformable_im2col_impl(input[elt], offset[elt], nInputPlane, inputHeight,\n                           inputWidth, kH, kW, padH, padW, dH, dW, dilationH,\n                           dilationW, im2col_step, deformable_group, columns);\n\n    // divide into group\n    gradOutputBuffer = gradOutputBuffer.view(\n        {gradOutputBuffer.size(0), group, gradOutputBuffer.size(1) / group,\n         gradOutputBuffer.size(2), gradOutputBuffer.size(3)});\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    gradWeight =\n        gradWeight.view({group, gradWeight.size(0) / group, gradWeight.size(1),\n                         gradWeight.size(2), gradWeight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      gradWeight[g] = gradWeight[g]\n                          .flatten(1)\n                          .addmm_(gradOutputBuffer[elt][g].flatten(1),\n                                  columns[g].transpose(1, 0), 1.0, scale)\n                          .view_as(gradWeight[g]);\n    }\n    gradOutputBuffer = gradOutputBuffer.view(\n        {gradOutputBuffer.size(0),\n         gradOutputBuffer.size(1) * gradOutputBuffer.size(2),\n         gradOutputBuffer.size(3), gradOutputBuffer.size(4)});\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    gradWeight = gradWeight.view({gradWeight.size(0) * gradWeight.size(1),\n                                  gradWeight.size(2), gradWeight.size(3),\n                                  gradWeight.size(4)});\n  }\n\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    gradOutput = gradOutput.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/deform_roi_pool.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid deform_roi_pool_forward_impl(Tensor input, Tensor rois, Tensor offset,\n                                  Tensor output, int pooled_height,\n                                  int pooled_width, float spatial_scale,\n                                  int sampling_ratio, float gamma) {\n  DISPATCH_DEVICE_IMPL(deform_roi_pool_forward_impl, input, rois, offset,\n                       output, pooled_height, pooled_width, spatial_scale,\n                       sampling_ratio, gamma);\n}\n\nvoid deform_roi_pool_backward_impl(Tensor grad_output, Tensor input,\n                                   Tensor rois, Tensor offset,\n                                   Tensor grad_input, Tensor grad_offset,\n                                   int pooled_height, int pooled_width,\n                                   float spatial_scale, int sampling_ratio,\n                                   float gamma) {\n  DISPATCH_DEVICE_IMPL(deform_roi_pool_backward_impl, grad_output, input, rois,\n                       offset, grad_input, grad_offset, pooled_height,\n                       pooled_width, spatial_scale, sampling_ratio, gamma);\n}\n\nvoid deform_roi_pool_forward(Tensor input, Tensor rois, Tensor offset,\n                             Tensor output, int pooled_height, int pooled_width,\n                             float spatial_scale, int sampling_ratio,\n                             float gamma) {\n  deform_roi_pool_forward_impl(input, rois, offset, output, pooled_height,\n                               pooled_width, spatial_scale, sampling_ratio,\n                               gamma);\n}\n\nvoid deform_roi_pool_backward(Tensor grad_output, Tensor input, Tensor rois,\n                              Tensor offset, Tensor grad_input,\n                              Tensor grad_offset, int pooled_height,\n                              int pooled_width, float spatial_scale,\n                              int sampling_ratio, float gamma) {\n  deform_roi_pool_backward_impl(grad_output, input, rois, offset, grad_input,\n                                grad_offset, pooled_height, pooled_width,\n                                spatial_scale, sampling_ratio, gamma);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/focal_loss.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid sigmoid_focal_loss_forward_impl(Tensor input, Tensor target, Tensor weight,\n                                     Tensor output, float gamma, float alpha) {\n  DISPATCH_DEVICE_IMPL(sigmoid_focal_loss_forward_impl, input, target, weight,\n                       output, gamma, alpha);\n}\n\nvoid sigmoid_focal_loss_backward_impl(Tensor input, Tensor target,\n                                      Tensor weight, Tensor grad_input,\n                                      float gamma, float alpha) {\n  DISPATCH_DEVICE_IMPL(sigmoid_focal_loss_backward_impl, input, target, weight,\n                       grad_input, gamma, alpha);\n}\n\nvoid softmax_focal_loss_forward_impl(Tensor input, Tensor target, Tensor weight,\n                                     Tensor output, float gamma, float alpha) {\n  DISPATCH_DEVICE_IMPL(softmax_focal_loss_forward_impl, input, target, weight,\n                       output, gamma, alpha);\n}\n\nvoid softmax_focal_loss_backward_impl(Tensor input, Tensor target,\n                                      Tensor weight, Tensor buff,\n                                      Tensor grad_input, float gamma,\n                                      float alpha) {\n  DISPATCH_DEVICE_IMPL(softmax_focal_loss_backward_impl, input, target, weight,\n                       buff, grad_input, gamma, alpha);\n}\n\nvoid sigmoid_focal_loss_forward(Tensor input, Tensor target, Tensor weight,\n                                Tensor output, float gamma, float alpha) {\n  sigmoid_focal_loss_forward_impl(input, target, weight, output, gamma, alpha);\n}\n\nvoid sigmoid_focal_loss_backward(Tensor input, Tensor target, Tensor weight,\n                                 Tensor grad_input, float gamma, float alpha) {\n  sigmoid_focal_loss_backward_impl(input, target, weight, grad_input, gamma,\n                                   alpha);\n}\n\nvoid softmax_focal_loss_forward(Tensor input, Tensor target, Tensor weight,\n                                Tensor output, float gamma, float alpha) {\n  softmax_focal_loss_forward_impl(input, target, weight, output, gamma, alpha);\n}\n\nvoid softmax_focal_loss_backward(Tensor input, Tensor target, Tensor weight,\n                                 Tensor buff, Tensor grad_input, float gamma,\n                                 float alpha) {\n  softmax_focal_loss_backward_impl(input, target, weight, buff, grad_input,\n                                   gamma, alpha);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/furthest_point_sample.cpp",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/sampling.cpp\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid furthest_point_sampling_forward_impl(Tensor points_tensor,\n                                          Tensor temp_tensor, Tensor idx_tensor,\n                                          int b, int n, int m) {\n  DISPATCH_DEVICE_IMPL(furthest_point_sampling_forward_impl, points_tensor,\n                       temp_tensor, idx_tensor, b, n, m);\n}\n\nvoid furthest_point_sampling_with_dist_forward_impl(Tensor points_tensor,\n                                                    Tensor temp_tensor,\n                                                    Tensor idx_tensor, int b,\n                                                    int n, int m) {\n  DISPATCH_DEVICE_IMPL(furthest_point_sampling_with_dist_forward_impl,\n                       points_tensor, temp_tensor, idx_tensor, b, n, m);\n}\n\nvoid furthest_point_sampling_forward(Tensor points_tensor, Tensor temp_tensor,\n                                     Tensor idx_tensor, int b, int n, int m) {\n  furthest_point_sampling_forward_impl(points_tensor, temp_tensor, idx_tensor,\n                                       b, n, m);\n}\n\nvoid furthest_point_sampling_with_dist_forward(Tensor points_tensor,\n                                               Tensor temp_tensor,\n                                               Tensor idx_tensor, int b, int n,\n                                               int m) {\n  furthest_point_sampling_with_dist_forward_impl(points_tensor, temp_tensor,\n                                                 idx_tensor, b, n, m);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/fused_bias_leakyrelu.cpp",
    "content": "// Modified from\n// https://github.com/rosinality/stylegan2-pytorch/blob/master/op/fused_bias_act.cpp\n\n/*\nCopyright (c) 2021, NVIDIA Corporation. All rights reserved.\n\nNVIDIA Source Code License for StyleGAN2 with Adaptive Discriminator\nAugmentation (ADA)\n=======================================================================\n\n1. Definitions\n\n\"Licensor\" means any person or entity that distributes its Work.\n\n\"Software\" means the original work of authorship made available under\nthis License.\n\n\"Work\" means the Software and any additions to or derivative works of\nthe Software that are made available under this License.\n\nThe terms \"reproduce,\" \"reproduction,\" \"derivative works,\" and\n\"distribution\" have the meaning as provided under U.S. copyright law;\nprovided, however, that for the purposes of this License, derivative\nworks shall not include works that remain separable from, or merely\nlink (or bind by name) to the interfaces of, the Work.\n\nWorks, including the Software, are \"made available\" under this License\nby including in or with the Work either (a) a copyright notice\nreferencing the applicability of this License to the Work, or (b) a\ncopy of this License.\n\n2. License Grants\n\n    2.1 Copyright Grant. Subject to the terms and conditions of this\n    License, each Licensor grants to you a perpetual, worldwide,\n    non-exclusive, royalty-free, copyright license to reproduce,\n    prepare derivative works of, publicly display, publicly perform,\n    sublicense and distribute its Work and any resulting derivative\n    works in any form.\n\n3. Limitations\n\n    3.1 Redistribution. You may reproduce or distribute the Work only\n    if (a) you do so under this License, (b) you include a complete\n    copy of this License with your distribution, and (c) you retain\n    without modification any copyright, patent, trademark, or\n    attribution notices that are present in the Work.\n\n    3.2 Derivative Works. You may specify that additional or different\n    terms apply to the use, reproduction, and distribution of your\n    derivative works of the Work (\"Your Terms\") only if (a) Your Terms\n    provide that the use limitation in Section 3.3 applies to your\n    derivative works, and (b) you identify the specific derivative\n    works that are subject to Your Terms. Notwithstanding Your Terms,\n    this License (including the redistribution requirements in Section\n    3.1) will continue to apply to the Work itself.\n\n    3.3 Use Limitation. The Work and any derivative works thereof only\n    may be used or intended for use non-commercially. Notwithstanding\n    the foregoing, NVIDIA and its affiliates may use the Work and any\n    derivative works commercially. As used herein, \"non-commercially\"\n    means for research or evaluation purposes only.\n\n    3.4 Patent Claims. If you bring or threaten to bring a patent claim\n    against any Licensor (including any claim, cross-claim or\n    counterclaim in a lawsuit) to enforce any patents that you allege\n    are infringed by any Work, then your rights under this License from\n    such Licensor (including the grant in Section 2.1) will terminate\n    immediately.\n\n    3.5 Trademarks. This License does not grant any rights to use any\n    Licensor’s or its affiliates’ names, logos, or trademarks, except\n    as necessary to reproduce the notices described in this License.\n\n    3.6 Termination. If you violate any term of this License, then your\n    rights under this License (including the grant in Section 2.1) will\n    terminate immediately.\n\n4. Disclaimer of Warranty.\n\nTHE WORK IS PROVIDED \"AS IS\" WITHOUT WARRANTIES OR CONDITIONS OF ANY\nKIND, EITHER EXPRESS OR IMPLIED, INCLUDING WARRANTIES OR CONDITIONS OF\nMERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE OR\nNON-INFRINGEMENT. YOU BEAR THE RISK OF UNDERTAKING ANY ACTIVITIES UNDER\nTHIS LICENSE.\n\n5. Limitation of Liability.\n\nEXCEPT AS PROHIBITED BY APPLICABLE LAW, IN NO EVENT AND UNDER NO LEGAL\nTHEORY, WHETHER IN TORT (INCLUDING NEGLIGENCE), CONTRACT, OR OTHERWISE\nSHALL ANY LICENSOR BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY DIRECT,\nINDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT OF\nOR RELATED TO THIS LICENSE, THE USE OR INABILITY TO USE THE WORK\n(INCLUDING BUT NOT LIMITED TO LOSS OF GOODWILL, BUSINESS INTERRUPTION,\nLOST PROFITS OR DATA, COMPUTER FAILURE OR MALFUNCTION, OR ANY OTHER\nCOMMERCIAL DAMAGES OR LOSSES), EVEN IF THE LICENSOR HAS BEEN ADVISED OF\nTHE POSSIBILITY OF SUCH DAMAGES.\n\n=======================================================================\n*/\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntorch::Tensor fused_bias_leakyrelu_op_impl(const torch::Tensor& input,\n                                           const torch::Tensor& bias,\n                                           const torch::Tensor& refer, int act,\n                                           int grad, float alpha, float scale) {\n  return DISPATCH_DEVICE_IMPL(fused_bias_leakyrelu_op_impl, input, bias, refer,\n                              act, grad, alpha, scale);\n}\n\ntorch::Tensor fused_bias_leakyrelu(const torch::Tensor& input,\n                                   const torch::Tensor& bias,\n                                   const torch::Tensor& refer, int act,\n                                   int grad, float alpha, float scale) {\n  return fused_bias_leakyrelu_op_impl(input, bias, refer, act, grad, alpha,\n                                      scale);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/gather_points.cpp",
    "content": "#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid gather_points_forward_impl(int b, int c, int n, int npoints,\n                                const Tensor points, const Tensor idx,\n                                Tensor out) {\n  DISPATCH_DEVICE_IMPL(gather_points_forward_impl, b, c, n, npoints, points,\n                       idx, out);\n}\n\nvoid gather_points_backward_impl(int b, int c, int n, int npoints,\n                                 const Tensor grad_out, const Tensor idx,\n                                 Tensor grad_points) {\n  DISPATCH_DEVICE_IMPL(gather_points_backward_impl, b, c, n, npoints, grad_out,\n                       idx, grad_points);\n}\n\nvoid gather_points_forward(Tensor points_tensor, Tensor idx_tensor,\n                           Tensor out_tensor, int b, int c, int n,\n                           int npoints) {\n  gather_points_forward_impl(b, c, n, npoints, points_tensor, idx_tensor,\n                             out_tensor);\n}\n\nvoid gather_points_backward(Tensor grad_out_tensor, Tensor idx_tensor,\n                            Tensor grad_points_tensor, int b, int c, int n,\n                            int npoints) {\n  gather_points_backward_impl(b, c, n, npoints, grad_out_tensor, idx_tensor,\n                              grad_points_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/group_points.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/group_points.cpp\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid group_points_forward_impl(int b, int c, int n, int npoints, int nsample,\n                               const Tensor points, const Tensor idx,\n                               Tensor out) {\n  DISPATCH_DEVICE_IMPL(group_points_forward_impl, b, c, n, npoints, nsample,\n                       points, idx, out);\n}\n\nvoid group_points_backward_impl(int b, int c, int n, int npoints, int nsample,\n                                const Tensor grad_out, const Tensor idx,\n                                Tensor grad_points) {\n  DISPATCH_DEVICE_IMPL(group_points_backward_impl, b, c, n, npoints, nsample,\n                       grad_out, idx, grad_points);\n}\n\nvoid group_points_forward(Tensor points_tensor, Tensor idx_tensor,\n                          Tensor out_tensor, int b, int c, int n, int npoints,\n                          int nsample) {\n  DISPATCH_DEVICE_IMPL(group_points_forward_impl, b, c, n, npoints, nsample,\n                       points_tensor, idx_tensor, out_tensor);\n}\n\nvoid group_points_backward(Tensor grad_out_tensor, Tensor idx_tensor,\n                           Tensor grad_points_tensor, int b, int c, int n,\n                           int npoints, int nsample) {\n  group_points_backward_impl(b, c, n, npoints, nsample, grad_out_tensor,\n                             idx_tensor, grad_points_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/info.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/vision.cpp\n#include \"pytorch_cpp_helper.hpp\"\n\n#ifdef MMCV_WITH_CUDA\n#ifndef HIP_DIFF\n#include <cuda_runtime_api.h>\nint get_cudart_version() { return CUDART_VERSION; }\n#endif\n#endif\n\nstd::string get_compiling_cuda_version() {\n#ifdef MMCV_WITH_CUDA\n#ifndef HIP_DIFF\n  std::ostringstream oss;\n  // copied from\n  // https://github.com/pytorch/pytorch/blob/master/aten/src/ATen/cuda/detail/CUDAHooks.cpp#L231\n  auto printCudaStyleVersion = [&](int v) {\n    oss << (v / 1000) << \".\" << (v / 10 % 100);\n    if (v % 10 != 0) {\n      oss << \".\" << (v % 10);\n    }\n  };\n  printCudaStyleVersion(get_cudart_version());\n  return oss.str();\n#else\n  return std::string(\"rocm not available\");\n#endif\n#else\n  return std::string(\"not available\");\n#endif\n}\n\n// similar to\n// https://github.com/pytorch/pytorch/blob/master/aten/src/ATen/Version.cpp\nstd::string get_compiler_version() {\n  std::ostringstream ss;\n#if defined(__GNUC__)\n#ifndef __clang__\n  { ss << \"GCC \" << __GNUC__ << \".\" << __GNUC_MINOR__; }\n#endif\n#endif\n\n#if defined(__clang_major__)\n  {\n    ss << \"clang \" << __clang_major__ << \".\" << __clang_minor__ << \".\"\n       << __clang_patchlevel__;\n  }\n#endif\n\n#if defined(_MSC_VER)\n  { ss << \"MSVC \" << _MSC_FULL_VER; }\n#endif\n  return ss.str();\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/iou3d.cpp",
    "content": "// Modified from\n// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms.cpp\n\n/*\n3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)\nWritten by Shaoshuai Shi\nAll Rights Reserved 2019-2020.\n*/\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nconst int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;\n\nvoid iou3d_boxes_overlap_bev_forward_impl(const int num_a, const Tensor boxes_a,\n                                          const int num_b, const Tensor boxes_b,\n                                          Tensor ans_overlap) {\n  DISPATCH_DEVICE_IMPL(iou3d_boxes_overlap_bev_forward_impl, num_a, boxes_a,\n                       num_b, boxes_b, ans_overlap);\n}\n\nvoid iou3d_boxes_iou_bev_forward_impl(const int num_a, const Tensor boxes_a,\n                                      const int num_b, const Tensor boxes_b,\n                                      Tensor ans_iou) {\n  DISPATCH_DEVICE_IMPL(iou3d_boxes_iou_bev_forward_impl, num_a, boxes_a, num_b,\n                       boxes_b, ans_iou);\n}\n\nvoid iou3d_nms_forward_impl(const Tensor boxes, unsigned long long *mask,\n                            int boxes_num, float nms_overlap_thresh) {\n  DISPATCH_DEVICE_IMPL(iou3d_nms_forward_impl, boxes, mask, boxes_num,\n                       nms_overlap_thresh);\n}\n\nvoid iou3d_nms_normal_forward_impl(const Tensor boxes, unsigned long long *mask,\n                                   int boxes_num, float nms_overlap_thresh) {\n  DISPATCH_DEVICE_IMPL(iou3d_nms_normal_forward_impl, boxes, mask, boxes_num,\n                       nms_overlap_thresh);\n}\n\nvoid iou3d_boxes_overlap_bev_forward(Tensor boxes_a, Tensor boxes_b,\n                                     Tensor ans_overlap) {\n  // params boxes_a: (N, 5) [x1, y1, x2, y2, ry]\n  // params boxes_b: (M, 5)\n  // params ans_overlap: (N, M)\n\n  int num_a = boxes_a.size(0);\n  int num_b = boxes_b.size(0);\n\n  iou3d_boxes_overlap_bev_forward_impl(num_a, boxes_a, num_b, boxes_b,\n                                       ans_overlap);\n}\n\nvoid iou3d_boxes_iou_bev_forward(Tensor boxes_a, Tensor boxes_b,\n                                 Tensor ans_iou) {\n  // params boxes_a: (N, 5) [x1, y1, x2, y2, ry]\n  // params boxes_b: (M, 5)\n  // params ans_overlap: (N, M)\n  int num_a = boxes_a.size(0);\n  int num_b = boxes_b.size(0);\n\n  iou3d_boxes_iou_bev_forward_impl(num_a, boxes_a, num_b, boxes_b, ans_iou);\n}\n\nvoid iou3d_nms_forward(Tensor boxes, Tensor keep, Tensor keep_num,\n                       float nms_overlap_thresh) {\n  // params boxes: (N, 5) [x1, y1, x2, y2, ry]\n  // params keep: (N)\n  CHECK_CONTIGUOUS(boxes);\n  CHECK_CONTIGUOUS(keep);\n\n  int boxes_num = boxes.size(0);\n  int64_t *keep_data = keep.data_ptr<int64_t>();\n  int64_t *keep_num_data = keep_num.data_ptr<int64_t>();\n\n  const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n\n  Tensor mask =\n      at::empty({boxes_num, col_blocks}, boxes.options().dtype(at::kLong));\n  unsigned long long *mask_data =\n      (unsigned long long *)mask.data_ptr<int64_t>();\n  iou3d_nms_forward_impl(boxes, mask_data, boxes_num, nms_overlap_thresh);\n\n  at::Tensor mask_cpu = mask.to(at::kCPU);\n  unsigned long long *mask_host =\n      (unsigned long long *)mask_cpu.data_ptr<int64_t>();\n\n  std::vector<unsigned long long> remv_cpu(col_blocks);\n  memset(&remv_cpu[0], 0, sizeof(unsigned long long) * col_blocks);\n\n  int num_to_keep = 0;\n\n  for (int i = 0; i < boxes_num; i++) {\n    int nblock = i / THREADS_PER_BLOCK_NMS;\n    int inblock = i % THREADS_PER_BLOCK_NMS;\n\n    if (!(remv_cpu[nblock] & (1ULL << inblock))) {\n      keep_data[num_to_keep++] = i;\n      unsigned long long *p = &mask_host[0] + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv_cpu[j] |= p[j];\n      }\n    }\n    *keep_num_data = num_to_keep;\n  }\n}\n\nvoid iou3d_nms_normal_forward(Tensor boxes, Tensor keep, Tensor keep_num,\n                              float nms_overlap_thresh) {\n  // params boxes: (N, 5) [x1, y1, x2, y2, ry]\n  // params keep: (N)\n\n  CHECK_CONTIGUOUS(boxes);\n  CHECK_CONTIGUOUS(keep);\n\n  int boxes_num = boxes.size(0);\n  int64_t *keep_data = keep.data_ptr<int64_t>();\n  int64_t *keep_num_data = keep_num.data_ptr<int64_t>();\n\n  const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n\n  Tensor mask =\n      at::empty({boxes_num, col_blocks}, boxes.options().dtype(at::kLong));\n  unsigned long long *mask_data =\n      (unsigned long long *)mask.data_ptr<int64_t>();\n  iou3d_nms_normal_forward_impl(boxes, mask_data, boxes_num,\n                                nms_overlap_thresh);\n\n  at::Tensor mask_cpu = mask.to(at::kCPU);\n  unsigned long long *mask_host =\n      (unsigned long long *)mask_cpu.data_ptr<int64_t>();\n\n  std::vector<unsigned long long> remv_cpu(col_blocks);\n  memset(&remv_cpu[0], 0, sizeof(unsigned long long) * col_blocks);\n  int num_to_keep = 0;\n\n  for (int i = 0; i < boxes_num; i++) {\n    int nblock = i / THREADS_PER_BLOCK_NMS;\n    int inblock = i % THREADS_PER_BLOCK_NMS;\n\n    if (!(remv_cpu[nblock] & (1ULL << inblock))) {\n      keep_data[num_to_keep++] = i;\n      unsigned long long *p = &mask_host[0] + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv_cpu[j] |= p[j];\n      }\n    }\n  }\n\n  *keep_num_data = num_to_keep;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/knn.cpp",
    "content": "// Modified from\n// https://github.com/CVMI-Lab/PAConv/tree/main/scene_seg/lib/pointops/src/knnquery_heap\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid knn_forward_impl(int b, int n, int m, int nsample, const Tensor xyz,\n                      const Tensor new_xyz, Tensor idx, Tensor dist2) {\n  DISPATCH_DEVICE_IMPL(knn_forward_impl, b, n, m, nsample, xyz, new_xyz, idx,\n                       dist2);\n}\n\nvoid knn_forward(Tensor xyz_tensor, Tensor new_xyz_tensor, Tensor idx_tensor,\n                 Tensor dist2_tensor, int b, int n, int m, int nsample) {\n  knn_forward_impl(b, n, m, nsample, xyz_tensor, new_xyz_tensor, idx_tensor,\n                   dist2_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/masked_conv2d.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid masked_im2col_forward_impl(const Tensor im, const Tensor mask_h_idx,\n                                const Tensor mask_w_idx, Tensor col,\n                                const int kernel_h, const int kernel_w,\n                                const int pad_h, const int pad_w) {\n  DISPATCH_DEVICE_IMPL(masked_im2col_forward_impl, im, mask_h_idx, mask_w_idx,\n                       col, kernel_h, kernel_w, pad_h, pad_w);\n}\n\nvoid masked_col2im_forward_impl(const Tensor col, const Tensor mask_h_idx,\n                                const Tensor mask_w_idx, Tensor im, int height,\n                                int width, int channels) {\n  DISPATCH_DEVICE_IMPL(masked_col2im_forward_impl, col, mask_h_idx, mask_w_idx,\n                       im, height, width, channels);\n}\n\nvoid masked_im2col_forward(const Tensor im, const Tensor mask_h_idx,\n                           const Tensor mask_w_idx, Tensor col,\n                           const int kernel_h, const int kernel_w,\n                           const int pad_h, const int pad_w) {\n  masked_im2col_forward_impl(im, mask_h_idx, mask_w_idx, col, kernel_h,\n                             kernel_w, pad_h, pad_w);\n}\n\nvoid masked_col2im_forward(const Tensor col, const Tensor mask_h_idx,\n                           const Tensor mask_w_idx, Tensor im, int height,\n                           int width, int channels) {\n  masked_col2im_forward_impl(col, mask_h_idx, mask_w_idx, im, height, width,\n                             channels);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/modulated_deform_conv.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid modulated_deformable_im2col_impl(\n    const Tensor data_im, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor data_col) {\n  DISPATCH_DEVICE_IMPL(modulated_deformable_im2col_impl, data_im, data_offset,\n                       data_mask, batch_size, channels, height_im, width_im,\n                       height_col, width_col, kernel_h, kernel_w, pad_h, pad_w,\n                       stride_h, stride_w, dilation_h, dilation_w,\n                       deformable_group, data_col);\n}\n\nvoid modulated_deformable_col2im_impl(\n    const Tensor data_col, const Tensor data_offset, const Tensor data_mask,\n    const int batch_size, const int channels, const int height_im,\n    const int width_im, const int height_col, const int width_col,\n    const int kernel_h, const int kernel_w, const int pad_h, const int pad_w,\n    const int stride_h, const int stride_w, const int dilation_h,\n    const int dilation_w, const int deformable_group, Tensor grad_im) {\n  DISPATCH_DEVICE_IMPL(modulated_deformable_col2im_impl, data_col, data_offset,\n                       data_mask, batch_size, channels, height_im, width_im,\n                       height_col, width_col, kernel_h, kernel_w, pad_h, pad_w,\n                       stride_h, stride_w, dilation_h, dilation_w,\n                       deformable_group, grad_im);\n}\n\nvoid modulated_deformable_col2im_coord_impl(\n    const Tensor data_col, const Tensor data_im, const Tensor data_offset,\n    const Tensor data_mask, const int batch_size, const int channels,\n    const int height_im, const int width_im, const int height_col,\n    const int width_col, const int kernel_h, const int kernel_w,\n    const int pad_h, const int pad_w, const int stride_h, const int stride_w,\n    const int dilation_h, const int dilation_w, const int deformable_group,\n    Tensor grad_offset, Tensor grad_mask) {\n  DISPATCH_DEVICE_IMPL(modulated_deformable_col2im_coord_impl, data_col,\n                       data_im, data_offset, data_mask, batch_size, channels,\n                       height_im, width_im, height_col, width_col, kernel_h,\n                       kernel_w, pad_h, pad_w, stride_h, stride_w, dilation_h,\n                       dilation_w, deformable_group, grad_offset, grad_mask);\n}\n\nvoid modulated_deform_conv_forward(\n    Tensor input, Tensor weight, Tensor bias, Tensor ones, Tensor offset,\n    Tensor mask, Tensor output, Tensor columns, int kernel_h, int kernel_w,\n    const int stride_h, const int stride_w, const int pad_h, const int pad_w,\n    const int dilation_h, const int dilation_w, const int group,\n    const int deformable_group, const bool with_bias) {\n  at::DeviceGuard guard(input.device());\n\n  const int batch = input.size(0);\n  const int channels = input.size(1);\n  const int height = input.size(2);\n  const int width = input.size(3);\n\n  const int channels_out = weight.size(0);\n  const int channels_kernel = weight.size(1);\n  const int kernel_h_ = weight.size(2);\n  const int kernel_w_ = weight.size(3);\n\n  if (kernel_h_ != kernel_h || kernel_w_ != kernel_w)\n    AT_ERROR(\"Input shape and kernel shape won't match: (%d x %d vs %d x %d).\",\n             kernel_h_, kernel_w, kernel_h_, kernel_w_);\n  if (channels != channels_kernel * group)\n    AT_ERROR(\"Input shape and kernel channels won't match: (%d vs %d).\",\n             channels, channels_kernel * group);\n\n  const int height_out =\n      (height + 2 * pad_h - (dilation_h * (kernel_h - 1) + 1)) / stride_h + 1;\n  const int width_out =\n      (width + 2 * pad_w - (dilation_w * (kernel_w - 1) + 1)) / stride_w + 1;\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < height_out * width_out) {\n    // Resize plane and fill with ones...\n    ones = at::ones({height_out, width_out}, input.options());\n  }\n\n  // resize output\n  output = output.view({batch, channels_out, height_out, width_out}).zero_();\n  // resize temporary columns\n  columns =\n      at::zeros({channels * kernel_h * kernel_w, 1 * height_out * width_out},\n                input.options());\n\n  output = output.view({output.size(0), group, output.size(1) / group,\n                        output.size(2), output.size(3)});\n\n  for (int b = 0; b < batch; b++) {\n    modulated_deformable_im2col_impl(\n        input[b], offset[b], mask[b], 1, channels, height, width, height_out,\n        width_out, kernel_h, kernel_w, pad_h, pad_w, stride_h, stride_w,\n        dilation_h, dilation_w, deformable_group, columns);\n\n    // divide into group\n    weight = weight.view({group, weight.size(0) / group, weight.size(1),\n                          weight.size(2), weight.size(3)});\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n\n    for (int g = 0; g < group; g++) {\n      output[b][g] = output[b][g]\n                         .flatten(1)\n                         .addmm_(weight[g].flatten(1), columns[g])\n                         .view_as(output[b][g]);\n    }\n\n    weight = weight.view({weight.size(0) * weight.size(1), weight.size(2),\n                          weight.size(3), weight.size(4)});\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n  }\n\n  output = output.view({output.size(0), output.size(1) * output.size(2),\n                        output.size(3), output.size(4)});\n\n  if (with_bias) {\n    output += bias.view({1, bias.size(0), 1, 1});\n  }\n}\n\nvoid modulated_deform_conv_backward(\n    Tensor input, Tensor weight, Tensor bias, Tensor ones, Tensor offset,\n    Tensor mask, Tensor columns, Tensor grad_input, Tensor grad_weight,\n    Tensor grad_bias, Tensor grad_offset, Tensor grad_mask, Tensor grad_output,\n    int kernel_h, int kernel_w, int stride_h, int stride_w, int pad_h,\n    int pad_w, int dilation_h, int dilation_w, int group, int deformable_group,\n    const bool with_bias) {\n  at::DeviceGuard guard(input.device());\n\n  const int batch = input.size(0);\n  const int channels = input.size(1);\n  const int height = input.size(2);\n  const int width = input.size(3);\n\n  const int channels_kernel = weight.size(1);\n  const int kernel_h_ = weight.size(2);\n  const int kernel_w_ = weight.size(3);\n  if (kernel_h_ != kernel_h || kernel_w_ != kernel_w)\n    AT_ERROR(\"Input shape and kernel shape won't match: (%d x %d vs %d x %d).\",\n             kernel_h_, kernel_w, kernel_h_, kernel_w_);\n  if (channels != channels_kernel * group)\n    AT_ERROR(\"Input shape and kernel channels won't match: (%d vs %d).\",\n             channels, channels_kernel * group);\n\n  const int height_out =\n      (height + 2 * pad_h - (dilation_h * (kernel_h - 1) + 1)) / stride_h + 1;\n  const int width_out =\n      (width + 2 * pad_w - (dilation_w * (kernel_w - 1) + 1)) / stride_w + 1;\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < height_out * width_out) {\n    // Resize plane and fill with ones...\n    ones = at::ones({height_out, width_out}, input.options());\n  }\n\n  grad_input = grad_input.view({batch, channels, height, width});\n  columns = at::zeros({channels * kernel_h * kernel_w, height_out * width_out},\n                      input.options());\n\n  grad_output =\n      grad_output.view({grad_output.size(0), group, grad_output.size(1) / group,\n                        grad_output.size(2), grad_output.size(3)});\n\n  for (int b = 0; b < batch; b++) {\n    // divide int group\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view({group, weight.size(0) / group, weight.size(1),\n                          weight.size(2), weight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      columns[g].addmm_(weight[g].flatten(1).transpose(0, 1),\n                        grad_output[b][g].flatten(1), 0.0f, 1.0f);\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    weight = weight.view({weight.size(0) * weight.size(1), weight.size(2),\n                          weight.size(3), weight.size(4)});\n\n    // gradient w.r.t. input coordinate data\n    modulated_deformable_col2im_coord_impl(\n        columns, input[b], offset[b], mask[b], 1, channels, height, width,\n        height_out, width_out, kernel_h, kernel_w, pad_h, pad_w, stride_h,\n        stride_w, dilation_h, dilation_w, deformable_group, grad_offset[b],\n        grad_mask[b]);\n    // gradient w.r.t. input data\n    modulated_deformable_col2im_impl(\n        columns, offset[b], mask[b], 1, channels, height, width, height_out,\n        width_out, kernel_h, kernel_w, pad_h, pad_w, stride_h, stride_w,\n        dilation_h, dilation_w, deformable_group, grad_input[b]);\n\n    // gradient w.r.t. weight, dWeight should accumulate across the batch and\n    // group\n    modulated_deformable_im2col_impl(\n        input[b], offset[b], mask[b], 1, channels, height, width, height_out,\n        width_out, kernel_h, kernel_w, pad_h, pad_w, stride_h, stride_w,\n        dilation_h, dilation_w, deformable_group, columns);\n\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    grad_weight = grad_weight.view({group, grad_weight.size(0) / group,\n                                    grad_weight.size(1), grad_weight.size(2),\n                                    grad_weight.size(3)});\n    if (with_bias)\n      grad_bias = grad_bias.view({group, grad_bias.size(0) / group});\n\n    for (int g = 0; g < group; g++) {\n      grad_weight[g] =\n          grad_weight[g]\n              .flatten(1)\n              .addmm_(grad_output[b][g].flatten(1), columns[g].transpose(0, 1))\n              .view_as(grad_weight[g]);\n      if (with_bias) {\n        grad_bias[g] =\n            grad_bias[g]\n                .view({-1, 1})\n                .addmm_(grad_output[b][g].flatten(1), ones.view({-1, 1}))\n                .view(-1);\n      }\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    grad_weight = grad_weight.view({grad_weight.size(0) * grad_weight.size(1),\n                                    grad_weight.size(2), grad_weight.size(3),\n                                    grad_weight.size(4)});\n    if (with_bias)\n      grad_bias = grad_bias.view({grad_bias.size(0) * grad_bias.size(1)});\n  }\n  grad_output = grad_output.view({grad_output.size(0) * grad_output.size(1),\n                                  grad_output.size(2), grad_output.size(3),\n                                  grad_output.size(4)});\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/ms_deform_attn.cpp",
    "content": "/*!\n**************************************************************************************************\n* Deformable DETR\n* Copyright (c) 2020 SenseTime. All Rights Reserved.\n* Licensed under the Apache License, Version 2.0 [see LICENSE for details]\n**************************************************************************************************\n* Modified from\n*https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/tree/pytorch_1.0.0\n**************************************************************************************************\n*/\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nTensor ms_deform_attn_impl_forward(const Tensor &value,\n                                   const Tensor &spatial_shapes,\n                                   const Tensor &level_start_index,\n                                   const Tensor &sampling_loc,\n                                   const Tensor &attn_weight,\n                                   const int im2col_step) {\n  return DISPATCH_DEVICE_IMPL(ms_deform_attn_impl_forward, value,\n                              spatial_shapes, level_start_index, sampling_loc,\n                              attn_weight, im2col_step);\n}\n\nvoid ms_deform_attn_impl_backward(\n    const Tensor &value, const Tensor &spatial_shapes,\n    const Tensor &level_start_index, const Tensor &sampling_loc,\n    const Tensor &attn_weight, const Tensor &grad_output, Tensor &grad_value,\n    Tensor &grad_sampling_loc, Tensor &grad_attn_weight,\n    const int im2col_step) {\n  DISPATCH_DEVICE_IMPL(ms_deform_attn_impl_backward, value, spatial_shapes,\n                       level_start_index, sampling_loc, attn_weight,\n                       grad_output, grad_value, grad_sampling_loc,\n                       grad_attn_weight, im2col_step);\n}\n\nTensor ms_deform_attn_forward(const Tensor &value, const Tensor &spatial_shapes,\n                              const Tensor &level_start_index,\n                              const Tensor &sampling_loc,\n                              const Tensor &attn_weight,\n                              const int im2col_step) {\n  at::DeviceGuard guard(value.device());\n  return ms_deform_attn_impl_forward(value, spatial_shapes, level_start_index,\n                                     sampling_loc, attn_weight, im2col_step);\n}\n\nvoid ms_deform_attn_backward(const Tensor &value, const Tensor &spatial_shapes,\n                             const Tensor &level_start_index,\n                             const Tensor &sampling_loc,\n                             const Tensor &attn_weight,\n                             const Tensor &grad_output, Tensor &grad_value,\n                             Tensor &grad_sampling_loc,\n                             Tensor &grad_attn_weight, const int im2col_step) {\n  at::DeviceGuard guard(value.device());\n  ms_deform_attn_impl_backward(value, spatial_shapes, level_start_index,\n                               sampling_loc, attn_weight, grad_output,\n                               grad_value, grad_sampling_loc, grad_attn_weight,\n                               im2col_step);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/nms.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nTensor nms_impl(Tensor boxes, Tensor scores, float iou_threshold, int offset) {\n  return DISPATCH_DEVICE_IMPL(nms_impl, boxes, scores, iou_threshold, offset);\n}\n\nTensor softnms_impl(Tensor boxes, Tensor scores, Tensor dets,\n                    float iou_threshold, float sigma, float min_score,\n                    int method, int offset) {\n  return DISPATCH_DEVICE_IMPL(softnms_impl, boxes, scores, dets, iou_threshold,\n                              sigma, min_score, method, offset);\n}\n\nstd::vector<std::vector<int> > nms_match_impl(Tensor dets,\n                                              float iou_threshold) {\n  return DISPATCH_DEVICE_IMPL(nms_match_impl, dets, iou_threshold);\n}\n\nTensor nms(Tensor boxes, Tensor scores, float iou_threshold, int offset) {\n  return nms_impl(boxes, scores, iou_threshold, offset);\n}\n\nTensor softnms(Tensor boxes, Tensor scores, Tensor dets, float iou_threshold,\n               float sigma, float min_score, int method, int offset) {\n  return softnms_impl(boxes, scores, dets, iou_threshold, sigma, min_score,\n                      method, offset);\n}\n\nstd::vector<std::vector<int> > nms_match(Tensor dets, float iou_threshold) {\n  return nms_match_impl(dets, iou_threshold);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/nms_rotated.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n// modified from\n// https://github.com/facebookresearch/detectron2/blob/master/detectron2/layers/csrc/nms_rotated/nms_rotated.h\n#include \"pytorch_cpp_helper.hpp\"\n\nTensor nms_rotated_cpu(const Tensor dets, const Tensor scores,\n                       const float iou_threshold);\n\n#ifdef MMCV_WITH_CUDA\nTensor nms_rotated_cuda(const Tensor dets, const Tensor scores,\n                        const Tensor order, const Tensor dets_sorted,\n                        const float iou_threshold, const int multi_label);\n#endif\n\n// Interface for Python\n// inline is needed to prevent multiple function definitions when this header is\n// included by different cpps\nTensor nms_rotated(const Tensor dets, const Tensor scores, const Tensor order,\n                   const Tensor dets_sorted, const float iou_threshold,\n                   const int multi_label) {\n  assert(dets.device().is_cuda() == scores.device().is_cuda());\n  if (dets.device().is_cuda()) {\n#ifdef MMCV_WITH_CUDA\n    return nms_rotated_cuda(dets, scores, order, dets_sorted, iou_threshold,\n                            multi_label);\n#else\n    AT_ERROR(\"Not compiled with GPU support\");\n#endif\n  }\n\n  return nms_rotated_cpu(dets, scores, iou_threshold);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/pixel_group.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// It is modified from https://github.com/WenmuZhou/PAN.pytorch\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nstd::vector<std::vector<float>> pixel_group_impl(\n    Tensor score, Tensor mask, Tensor embedding, Tensor kernel_label,\n    Tensor kernel_contour, int kernel_region_num, float dis_threshold) {\n  return DISPATCH_DEVICE_IMPL(pixel_group_impl, score, mask, embedding,\n                              kernel_label, kernel_contour, kernel_region_num,\n                              dis_threshold);\n}\n\nstd::vector<std::vector<float>> pixel_group(\n    Tensor score, Tensor mask, Tensor embedding, Tensor kernel_label,\n    Tensor kernel_contour, int kernel_region_num, float distance_threshold) {\n  score = score.contiguous();\n  mask = mask.contiguous();\n  embedding = embedding.contiguous();\n  kernel_label = kernel_label.contiguous();\n  kernel_contour = kernel_contour.contiguous();\n\n  return pixel_group_impl(score, mask, embedding, kernel_label, kernel_contour,\n                          kernel_region_num, distance_threshold);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/points_in_boxes.cpp",
    "content": "#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid points_in_boxes_part_forward_impl(int batch_size, int boxes_num,\n                                       int pts_num, const Tensor boxes,\n                                       const Tensor pts,\n                                       Tensor box_idx_of_points) {\n  DISPATCH_DEVICE_IMPL(points_in_boxes_part_forward_impl, batch_size, boxes_num,\n                       pts_num, boxes, pts, box_idx_of_points);\n}\n\nvoid points_in_boxes_all_forward_impl(int batch_size, int boxes_num,\n                                      int pts_num, const Tensor boxes,\n                                      const Tensor pts,\n                                      Tensor box_idx_of_points) {\n  DISPATCH_DEVICE_IMPL(points_in_boxes_all_forward_impl, batch_size, boxes_num,\n                       pts_num, boxes, pts, box_idx_of_points);\n}\n\nvoid points_in_boxes_part_forward(Tensor boxes_tensor, Tensor pts_tensor,\n                                  Tensor box_idx_of_points_tensor) {\n  // params boxes: (B, N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is the bottom center, each box params pts: (B, npoints, 3)\n  // [x, y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints),\n  // default -1\n  int batch_size = boxes_tensor.size(0);\n  int boxes_num = boxes_tensor.size(1);\n  int pts_num = pts_tensor.size(1);\n  points_in_boxes_part_forward_impl(batch_size, boxes_num, pts_num,\n                                    boxes_tensor, pts_tensor,\n                                    box_idx_of_points_tensor);\n}\n\nvoid points_in_boxes_all_forward(Tensor boxes_tensor, Tensor pts_tensor,\n                                 Tensor box_idx_of_points_tensor) {\n  // params boxes: (B, N, 7) [x, y, z, x_size, y_size, z_size, rz] in LiDAR\n  // coordinate, z is the bottom center. params pts: (B, npoints, 3) [x, y, z]\n  // in LiDAR coordinate params boxes_idx_of_points: (B, npoints), default -1\n  int batch_size = boxes_tensor.size(0);\n  int boxes_num = boxes_tensor.size(1);\n  int pts_num = pts_tensor.size(1);\n  points_in_boxes_all_forward_impl(batch_size, boxes_num, pts_num, boxes_tensor,\n                                   pts_tensor, box_idx_of_points_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/psamask.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n// Modified from\n// https://github.com/hszhao/semseg/blob/master/lib/psa/src\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid psamask_forward_impl(const int psa_type, const Tensor input, Tensor output,\n                          const int num_, const int h_feature,\n                          const int w_feature, const int h_mask,\n                          const int w_mask, const int half_h_mask,\n                          const int half_w_mask) {\n  DISPATCH_DEVICE_IMPL(psamask_forward_impl, psa_type, input, output, num_,\n                       h_feature, w_feature, h_mask, w_mask, half_h_mask,\n                       half_w_mask);\n}\n\nvoid psamask_backward_impl(const int psa_type, const Tensor grad_output,\n                           Tensor grad_input, const int num_,\n                           const int h_feature, const int w_feature,\n                           const int h_mask, const int w_mask,\n                           const int half_h_mask, const int half_w_mask) {\n  DISPATCH_DEVICE_IMPL(psamask_backward_impl, psa_type, grad_output, grad_input,\n                       num_, h_feature, w_feature, h_mask, w_mask, half_h_mask,\n                       half_w_mask);\n}\n\nvoid psamask_forward(const Tensor input, Tensor output, const int psa_type,\n                     const int num_, const int h_feature, const int w_feature,\n                     const int h_mask, const int w_mask, const int half_h_mask,\n                     const int half_w_mask) {\n  psamask_forward_impl(psa_type, input, output, num_, h_feature, w_feature,\n                       h_mask, w_mask, half_h_mask, half_w_mask);\n}\n\nvoid psamask_backward(Tensor grad_output, const Tensor grad_input,\n                      const int psa_type, const int num_, const int h_feature,\n                      const int w_feature, const int h_mask, const int w_mask,\n                      const int half_h_mask, const int half_w_mask) {\n  psamask_backward_impl(psa_type, grad_output, grad_input, num_, h_feature,\n                        w_feature, h_mask, w_mask, half_h_mask, half_w_mask);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/pybind.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n\nstd::string get_compiler_version();\nstd::string get_compiling_cuda_version();\n\nvoid assign_score_withk_forward(const Tensor &points, const Tensor &centers,\n                                const Tensor &scores, const Tensor &knn_idx,\n                                Tensor &output, int B, int N0, int N1, int M,\n                                int K, int O, int aggregate);\n\nvoid assign_score_withk_backward(const Tensor &grad_out, const Tensor &points,\n                                 const Tensor &centers, const Tensor &scores,\n                                 const Tensor &knn_idx, Tensor &grad_points,\n                                 Tensor &grad_centers, Tensor &grad_scores,\n                                 int B, int N0, int N1, int M, int K, int O,\n                                 int aggregate);\n\nvoid carafe_naive_forward(Tensor features, Tensor masks, Tensor output,\n                          int kernel_size, int group_size, int scale_factor);\n\nvoid carafe_naive_backward(Tensor top_grad, Tensor features, Tensor masks,\n                           Tensor bottom_grad, Tensor mask_grad,\n                           int kernel_size, int group_size, int scale_factor);\n\nvoid carafe_forward(Tensor features, Tensor masks, Tensor rfeatures,\n                    Tensor routput, Tensor rmasks, Tensor output,\n                    int kernel_size, int group_size, int scale_factor);\n\nvoid carafe_backward(Tensor top_grad, Tensor rfeatures, Tensor masks,\n                     Tensor rtop_grad, Tensor rbottom_grad_hs,\n                     Tensor rbottom_grad, Tensor rmask_grad, Tensor bottom_grad,\n                     Tensor mask_grad, int kernel_size, int group_size,\n                     int scale_factor);\n\nvoid deform_conv_forward(Tensor input, Tensor weight, Tensor offset,\n                         Tensor output, Tensor columns, Tensor ones, int kW,\n                         int kH, int dW, int dH, int padW, int padH,\n                         int dilationW, int dilationH, int group,\n                         int deformable_group, int im2col_step);\n\nvoid deform_conv_backward_input(Tensor input, Tensor offset, Tensor gradOutput,\n                                Tensor gradInput, Tensor gradOffset,\n                                Tensor weight, Tensor columns, int kW, int kH,\n                                int dW, int dH, int padW, int padH,\n                                int dilationW, int dilationH, int group,\n                                int deformable_group, int im2col_step);\n\nvoid deform_conv_backward_parameters(Tensor input, Tensor offset,\n                                     Tensor gradOutput, Tensor gradWeight,\n                                     Tensor columns, Tensor ones, int kW,\n                                     int kH, int dW, int dH, int padW, int padH,\n                                     int dilationW, int dilationH, int group,\n                                     int deformable_group, float scale,\n                                     int im2col_step);\n\nvoid deform_roi_pool_forward(Tensor input, Tensor rois, Tensor offset,\n                             Tensor output, int pooled_height, int pooled_width,\n                             float spatial_scale, int sampling_ratio,\n                             float gamma);\n\nvoid deform_roi_pool_backward(Tensor grad_output, Tensor input, Tensor rois,\n                              Tensor offset, Tensor grad_input,\n                              Tensor grad_offset, int pooled_height,\n                              int pooled_width, float spatial_scale,\n                              int sampling_ratio, float gamma);\n\nvoid group_points_forward(Tensor points_tensor, Tensor idx_tensor,\n                          Tensor out_tensor, int b, int c, int n, int npoints,\n                          int nsample);\n\nvoid group_points_backward(Tensor grad_out_tensor, Tensor idx_tensor,\n                           Tensor grad_points_tensor, int b, int c, int n,\n                           int npoints, int nsample);\n\nvoid roipoint_pool3d_forward(Tensor xyz, Tensor boxes3d, Tensor pts_feature,\n                             Tensor pooled_features, Tensor pooled_empty_flag);\n\nvoid gather_points_forward(Tensor points_tensor, Tensor idx_tensor,\n                           Tensor out_tensor, int b, int c, int n, int npoints);\n\nvoid gather_points_backward(Tensor grad_out_tensor, Tensor idx_tensor,\n                            Tensor grad_points_tensor, int b, int c, int n,\n                            int npoints);\n\nvoid sigmoid_focal_loss_forward(Tensor input, Tensor target, Tensor weight,\n                                Tensor output, float gamma, float alpha);\n\nvoid sigmoid_focal_loss_backward(Tensor input, Tensor target, Tensor weight,\n                                 Tensor grad_input, float gamma, float alpha);\n\nvoid softmax_focal_loss_forward(Tensor input, Tensor target, Tensor weight,\n                                Tensor output, float gamma, float alpha);\n\nvoid softmax_focal_loss_backward(Tensor input, Tensor target, Tensor weight,\n                                 Tensor buff, Tensor grad_input, float gamma,\n                                 float alpha);\n\nvoid three_interpolate_forward(Tensor points_tensor, Tensor idx_tensor,\n                               Tensor weight_tensor, Tensor out_tensor, int b,\n                               int c, int m, int n);\n\nvoid three_interpolate_backward(Tensor grad_out_tensor, Tensor idx_tensor,\n                                Tensor weight_tensor, Tensor grad_points_tensor,\n                                int b, int c, int n, int m);\n\nvoid three_nn_forward(Tensor unknown_tensor, Tensor known_tensor,\n                      Tensor dist2_tensor, Tensor idx_tensor, int b, int n,\n                      int m);\n\nvoid bbox_overlaps(const Tensor bboxes1, const Tensor bboxes2, Tensor ious,\n                   const int mode, const bool aligned, const int offset);\n\nvoid knn_forward(Tensor xyz_tensor, Tensor new_xyz_tensor, Tensor idx_tensor,\n                 Tensor dist2_tensor, int b, int n, int m, int nsample);\nvoid iou3d_boxes_overlap_bev_forward(Tensor boxes_a, Tensor boxes_b,\n                                     Tensor ans_overlap);\n\nvoid iou3d_boxes_iou_bev_forward(Tensor boxes_a, Tensor boxes_b,\n                                 Tensor ans_iou);\n\nvoid iou3d_nms_forward(Tensor boxes, Tensor keep, Tensor keep_num,\n                       float nms_overlap_thresh);\n\nvoid iou3d_nms_normal_forward(Tensor boxes, Tensor keep, Tensor keep_num,\n                              float nms_overlap_thresh);\n\nvoid furthest_point_sampling_forward(Tensor points_tensor, Tensor temp_tensor,\n                                     Tensor idx_tensor, int b, int n, int m);\n\nvoid furthest_point_sampling_with_dist_forward(Tensor points_tensor,\n                                               Tensor temp_tensor,\n                                               Tensor idx_tensor, int b, int n,\n                                               int m);\n\nvoid masked_im2col_forward(const Tensor im, const Tensor mask_h_idx,\n                           const Tensor mask_w_idx, Tensor col,\n                           const int kernel_h, const int kernel_w,\n                           const int pad_h, const int pad_w);\n\nvoid masked_col2im_forward(const Tensor col, const Tensor mask_h_idx,\n                           const Tensor mask_w_idx, Tensor im, int height,\n                           int width, int channels);\n\nvoid modulated_deform_conv_forward(\n    Tensor input, Tensor weight, Tensor bias, Tensor ones, Tensor offset,\n    Tensor mask, Tensor output, Tensor columns, int kernel_h, int kernel_w,\n    const int stride_h, const int stride_w, const int pad_h, const int pad_w,\n    const int dilation_h, const int dilation_w, const int group,\n    const int deformable_group, const bool with_bias);\n\nvoid modulated_deform_conv_backward(\n    Tensor input, Tensor weight, Tensor bias, Tensor ones, Tensor offset,\n    Tensor mask, Tensor columns, Tensor grad_input, Tensor grad_weight,\n    Tensor grad_bias, Tensor grad_offset, Tensor grad_mask, Tensor grad_output,\n    int kernel_h, int kernel_w, int stride_h, int stride_w, int pad_h,\n    int pad_w, int dilation_h, int dilation_w, int group, int deformable_group,\n    const bool with_bias);\n\nTensor ms_deform_attn_forward(const Tensor &value, const Tensor &spatial_shapes,\n                              const Tensor &level_start_index,\n                              const Tensor &sampling_loc,\n                              const Tensor &attn_weight, const int im2col_step);\n\nvoid ms_deform_attn_backward(const Tensor &value, const Tensor &spatial_shapes,\n                             const Tensor &level_start_index,\n                             const Tensor &sampling_loc,\n                             const Tensor &attn_weight,\n                             const Tensor &grad_output, Tensor &grad_value,\n                             Tensor &grad_sampling_loc,\n                             Tensor &grad_attn_weight, const int im2col_step);\n\nTensor nms(Tensor boxes, Tensor scores, float iou_threshold, int offset);\n\nTensor softnms(Tensor boxes, Tensor scores, Tensor dets, float iou_threshold,\n               float sigma, float min_score, int method, int offset);\n\nstd::vector<std::vector<int>> nms_match(Tensor dets, float iou_threshold);\n\nstd::vector<std::vector<float>> pixel_group(\n    Tensor score, Tensor mask, Tensor embedding, Tensor kernel_label,\n    Tensor kernel_contour, int kernel_region_num, float distance_threshold);\n\nstd::vector<std::vector<int>> contour_expand(Tensor kernel_mask,\n                                             Tensor internal_kernel_label,\n                                             int min_kernel_area,\n                                             int kernel_num);\n\nvoid roi_align_forward(Tensor input, Tensor rois, Tensor output,\n                       Tensor argmax_y, Tensor argmax_x, int aligned_height,\n                       int aligned_width, float spatial_scale,\n                       int sampling_ratio, int pool_mode, bool aligned);\n\nvoid roi_align_backward(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                        Tensor argmax_x, Tensor grad_input, int aligned_height,\n                        int aligned_width, float spatial_scale,\n                        int sampling_ratio, int pool_mode, bool aligned);\n\nvoid roi_pool_forward(Tensor input, Tensor rois, Tensor output, Tensor argmax,\n                      int pooled_height, int pooled_width, float spatial_scale);\n\nvoid roi_pool_backward(Tensor grad_output, Tensor rois, Tensor argmax,\n                       Tensor grad_input, int pooled_height, int pooled_width,\n                       float spatial_scale);\n\nvoid sync_bn_forward_mean(const Tensor input, Tensor mean);\n\nvoid sync_bn_forward_var(const Tensor input, const Tensor mean, Tensor var);\n\nvoid sync_bn_forward_output(const Tensor input, const Tensor mean,\n                            const Tensor var, const Tensor weight,\n                            const Tensor bias, Tensor running_mean,\n                            Tensor running_var, Tensor norm, Tensor std,\n                            Tensor output, float eps, float momentum,\n                            int group_size);\n\nvoid sync_bn_backward_param(const Tensor grad_output, const Tensor norm,\n                            Tensor grad_weight, Tensor grad_bias);\n\nvoid sync_bn_backward_data(const Tensor grad_output, const Tensor weight,\n                           const Tensor grad_weight, const Tensor grad_bias,\n                           const Tensor norm, const Tensor std,\n                           Tensor grad_input);\n\nvoid psamask_forward(const Tensor input, Tensor output, const int psa_type,\n                     const int num_, const int h_feature, const int w_feature,\n                     const int h_mask, const int w_mask, const int half_h_mask,\n                     const int half_w_mask);\n\nvoid psamask_backward(Tensor grad_output, const Tensor grad_input,\n                      const int psa_type, const int num_, const int h_feature,\n                      const int w_feature, const int h_mask, const int w_mask,\n                      const int half_h_mask, const int half_w_mask);\n\nvoid tin_shift_forward(Tensor input, Tensor shift, Tensor output);\n\nvoid tin_shift_backward(Tensor grad_output, Tensor shift, Tensor grad_input);\n\nvoid ball_query_forward(Tensor new_xyz_tensor, Tensor xyz_tensor,\n                        Tensor idx_tensor, int b, int n, int m,\n                        float min_radius, float max_radius, int nsample);\n\nTensor bottom_pool_forward(Tensor input);\n\nTensor bottom_pool_backward(Tensor input, Tensor grad_output);\n\nTensor left_pool_forward(Tensor input);\n\nTensor left_pool_backward(Tensor input, Tensor grad_output);\n\nTensor right_pool_forward(Tensor input);\n\nTensor right_pool_backward(Tensor input, Tensor grad_output);\n\nTensor top_pool_forward(Tensor input);\n\nTensor top_pool_backward(Tensor input, Tensor grad_output);\n\nvoid box_iou_rotated(const Tensor boxes1, const Tensor boxes2, Tensor ious,\n                     const int mode_flag, const bool aligned);\n\nTensor nms_rotated(const Tensor dets, const Tensor scores, const Tensor order,\n                   const Tensor dets_sorted, const float iou_threshold,\n                   const int multi_label);\n\nTensor upfirdn2d(const Tensor &input, const Tensor &kernel, int up_x, int up_y,\n                 int down_x, int down_y, int pad_x0, int pad_x1, int pad_y0,\n                 int pad_y1);\n\nTensor fused_bias_leakyrelu(const Tensor &input, const Tensor &bias,\n                            const Tensor &refer, int act, int grad, float alpha,\n                            float scale);\n\nvoid roi_align_rotated_forward(Tensor input, Tensor rois, Tensor output,\n                               int pooled_height, int pooled_width,\n                               float spatial_scale, int sample_num,\n                               bool aligned, bool clockwise);\n\nvoid roi_align_rotated_backward(Tensor grad_output, Tensor rois,\n                                Tensor grad_input, int pooled_height,\n                                int pooled_width, float spatial_scale,\n                                int sample_num, bool aligned, bool clockwise);\n\nstd::vector<torch::Tensor> dynamic_point_to_voxel_forward(\n    const torch::Tensor &feats, const torch::Tensor &coors,\n    const std::string &reduce_type);\n\nvoid dynamic_point_to_voxel_backward(torch::Tensor &grad_feats,\n                                     const torch::Tensor &grad_reduced_feats,\n                                     const torch::Tensor &feats,\n                                     const torch::Tensor &reduced_feats,\n                                     const torch::Tensor &coors_idx,\n                                     const torch::Tensor &reduce_count,\n                                     const std::string &reduce_type);\n\nvoid hard_voxelize_forward(const at::Tensor &points,\n                           const at::Tensor &voxel_size,\n                           const at::Tensor &coors_range, at::Tensor &voxels,\n                           at::Tensor &coors, at::Tensor &num_points_per_voxel,\n                           at::Tensor &voxel_num, const int max_points,\n                           const int max_voxels, const int NDim);\n\nvoid dynamic_voxelize_forward(const at::Tensor &points,\n                              const at::Tensor &voxel_size,\n                              const at::Tensor &coors_range, at::Tensor &coors,\n                              const int NDim);\n\nvoid border_align_forward(const Tensor &input, const Tensor &boxes,\n                          Tensor output, Tensor argmax_idx,\n                          const int pool_size);\n\nvoid border_align_backward(const Tensor &grad_output, const Tensor &boxes,\n                           const Tensor &argmax_idx, Tensor grad_input,\n                           const int pool_size);\n\nvoid points_in_boxes_cpu_forward(Tensor boxes_tensor, Tensor pts_tensor,\n                                 Tensor pts_indices_tensor);\n\nvoid points_in_boxes_part_forward(Tensor boxes_tensor, Tensor pts_tensor,\n                                  Tensor box_idx_of_points_tensor);\n\nvoid points_in_boxes_all_forward(Tensor boxes_tensor, Tensor pts_tensor,\n                                 Tensor box_idx_of_points_tensor);\n\nvoid roiaware_pool3d_forward(Tensor rois, Tensor pts, Tensor pts_feature,\n                             Tensor argmax, Tensor pts_idx_of_voxels,\n                             Tensor pooled_features, int pool_method);\n\nvoid roiaware_pool3d_backward(Tensor pts_idx_of_voxels, Tensor argmax,\n                              Tensor grad_out, Tensor grad_in, int pool_method);\n\nvoid correlation_forward(Tensor input1, Tensor input2, Tensor output, int kH,\n                         int kW, int patchH, int patchW, int padH, int padW,\n                         int dilationH, int dilationW, int dilation_patchH,\n                         int dilation_patchW, int dH, int dW);\n\nvoid correlation_backward(Tensor grad_output, Tensor input1, Tensor input2,\n                          Tensor grad_input1, Tensor grad_input2, int kH,\n                          int kW, int patchH, int patchW, int padH, int padW,\n                          int dilationH, int dilationW, int dilation_patchH,\n                          int dilation_patchW, int dH, int dW);\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"upfirdn2d\", &upfirdn2d, \"upfirdn2d (CUDA)\", py::arg(\"input\"),\n        py::arg(\"kernel\"), py::arg(\"up_x\"), py::arg(\"up_y\"), py::arg(\"down_x\"),\n        py::arg(\"down_y\"), py::arg(\"pad_x0\"), py::arg(\"pad_x1\"),\n        py::arg(\"pad_y0\"), py::arg(\"pad_y1\"));\n  m.def(\"fused_bias_leakyrelu\", &fused_bias_leakyrelu,\n        \"fused_bias_leakyrelu (CUDA)\", py::arg(\"input\"), py::arg(\"bias\"),\n        py::arg(\"empty\"), py::arg(\"act\"), py::arg(\"grad\"), py::arg(\"alpha\"),\n        py::arg(\"scale\"));\n  m.def(\"gather_points_forward\", &gather_points_forward,\n        \"gather_points_forward\", py::arg(\"points_tensor\"),\n        py::arg(\"idx_tensor\"), py::arg(\"out_tensor\"), py::arg(\"b\"),\n        py::arg(\"c\"), py::arg(\"n\"), py::arg(\"npoints\"));\n  m.def(\"gather_points_backward\", &gather_points_backward,\n        \"gather_points_backward\", py::arg(\"grad_out_tensor\"),\n        py::arg(\"idx_tensor\"), py::arg(\"grad_points_tensor\"), py::arg(\"b\"),\n        py::arg(\"c\"), py::arg(\"n\"), py::arg(\"npoints\"));\n  m.def(\"get_compiler_version\", &get_compiler_version, \"get_compiler_version\");\n  m.def(\"get_compiling_cuda_version\", &get_compiling_cuda_version,\n        \"get_compiling_cuda_version\");\n  m.def(\"assign_score_withk_forward\", &assign_score_withk_forward,\n        \"assign_score_withk_forward\", py::arg(\"points\"), py::arg(\"centers\"),\n        py::arg(\"scores\"), py::arg(\"knn_idx\"), py::arg(\"output\"), py::arg(\"B\"),\n        py::arg(\"N0\"), py::arg(\"N1\"), py::arg(\"M\"), py::arg(\"K\"), py::arg(\"O\"),\n        py::arg(\"aggregate\"));\n  m.def(\"assign_score_withk_backward\", &assign_score_withk_backward,\n        \"assign_score_withk_backward\", py::arg(\"grad_out\"), py::arg(\"points\"),\n        py::arg(\"centers\"), py::arg(\"scores\"), py::arg(\"knn_idx\"),\n        py::arg(\"grad_points\"), py::arg(\"grad_centers\"), py::arg(\"grad_scores\"),\n        py::arg(\"B\"), py::arg(\"N0\"), py::arg(\"N1\"), py::arg(\"M\"), py::arg(\"K\"),\n        py::arg(\"O\"), py::arg(\"aggregate\"));\n  m.def(\"knn_forward\", &knn_forward, \"knn_forward\", py::arg(\"xyz_tensor\"),\n        py::arg(\"new_xyz_tensor\"), py::arg(\"idx_tensor\"),\n        py::arg(\"dist2_tensor\"), py::arg(\"b\"), py::arg(\"n\"), py::arg(\"m\"),\n        py::arg(\"nsample\"));\n  m.def(\"carafe_naive_forward\", &carafe_naive_forward, \"carafe_naive_forward\",\n        py::arg(\"features\"), py::arg(\"masks\"), py::arg(\"output\"),\n        py::arg(\"kernel_size\"), py::arg(\"group_size\"), py::arg(\"scale_factor\"));\n  m.def(\"carafe_naive_backward\", &carafe_naive_backward,\n        \"carafe_naive_backward\", py::arg(\"top_grad\"), py::arg(\"features\"),\n        py::arg(\"masks\"), py::arg(\"bottom_grad\"), py::arg(\"mask_grad\"),\n        py::arg(\"kernel_size\"), py::arg(\"group_size\"), py::arg(\"scale_factor\"));\n  m.def(\"carafe_forward\", &carafe_forward, \"carafe_forward\",\n        py::arg(\"features\"), py::arg(\"masks\"), py::arg(\"rfeatures\"),\n        py::arg(\"routput\"), py::arg(\"rmasks\"), py::arg(\"output\"),\n        py::arg(\"kernel_size\"), py::arg(\"group_size\"), py::arg(\"scale_factor\"));\n  m.def(\"carafe_backward\", &carafe_backward, \"carafe_backward\",\n        py::arg(\"top_grad\"), py::arg(\"rfeatures\"), py::arg(\"masks\"),\n        py::arg(\"rtop_grad\"), py::arg(\"rbottom_grad_hs\"),\n        py::arg(\"rbottom_grad\"), py::arg(\"rmask_grad\"), py::arg(\"bottom_grad\"),\n        py::arg(\"mask_grad\"), py::arg(\"kernel_size\"), py::arg(\"group_size\"),\n        py::arg(\"scale_factor\"));\n  m.def(\"deform_conv_forward\", &deform_conv_forward, \"deform_conv_forward\",\n        py::arg(\"input\"), py::arg(\"weight\"), py::arg(\"offset\"),\n        py::arg(\"output\"), py::arg(\"columns\"), py::arg(\"ones\"), py::arg(\"kW\"),\n        py::arg(\"kH\"), py::arg(\"dW\"), py::arg(\"dH\"), py::arg(\"padH\"),\n        py::arg(\"padW\"), py::arg(\"dilationW\"), py::arg(\"dilationH\"),\n        py::arg(\"group\"), py::arg(\"deformable_group\"), py::arg(\"im2col_step\"));\n  m.def(\"deform_conv_backward_input\", &deform_conv_backward_input,\n        \"deform_conv_backward_input\", py::arg(\"input\"), py::arg(\"offset\"),\n        py::arg(\"gradOutput\"), py::arg(\"gradInput\"), py::arg(\"gradOffset\"),\n        py::arg(\"weight\"), py::arg(\"columns\"), py::arg(\"kW\"), py::arg(\"kH\"),\n        py::arg(\"dW\"), py::arg(\"dH\"), py::arg(\"padH\"), py::arg(\"padW\"),\n        py::arg(\"dilationW\"), py::arg(\"dilationH\"), py::arg(\"group\"),\n        py::arg(\"deformable_group\"), py::arg(\"im2col_step\"));\n  m.def(\"deform_conv_backward_parameters\", &deform_conv_backward_parameters,\n        \"deform_conv_backward_parameters\", py::arg(\"input\"), py::arg(\"offset\"),\n        py::arg(\"gradOutput\"), py::arg(\"gradWeight\"), py::arg(\"columns\"),\n        py::arg(\"ones\"), py::arg(\"kW\"), py::arg(\"kH\"), py::arg(\"dW\"),\n        py::arg(\"dH\"), py::arg(\"padH\"), py::arg(\"padW\"), py::arg(\"dilationW\"),\n        py::arg(\"dilationH\"), py::arg(\"group\"), py::arg(\"deformable_group\"),\n        py::arg(\"scale\"), py::arg(\"im2col_step\"));\n  m.def(\"deform_roi_pool_forward\", &deform_roi_pool_forward,\n        \"deform roi pool forward\", py::arg(\"input\"), py::arg(\"rois\"),\n        py::arg(\"offset\"), py::arg(\"output\"), py::arg(\"pooled_height\"),\n        py::arg(\"pooled_width\"), py::arg(\"spatial_scale\"),\n        py::arg(\"sampling_ratio\"), py::arg(\"gamma\"));\n  m.def(\"deform_roi_pool_backward\", &deform_roi_pool_backward,\n        \"deform roi pool backward\", py::arg(\"grad_output\"), py::arg(\"input\"),\n        py::arg(\"rois\"), py::arg(\"offset\"), py::arg(\"grad_input\"),\n        py::arg(\"grad_offset\"), py::arg(\"pooled_height\"),\n        py::arg(\"pooled_width\"), py::arg(\"spatial_scale\"),\n        py::arg(\"sampling_ratio\"), py::arg(\"gamma\"));\n  m.def(\"roipoint_pool3d_forward\", &roipoint_pool3d_forward,\n        \"roipoint_pool3d_forward\", py::arg(\"xyz\"), py::arg(\"boxes3d\"),\n        py::arg(\"pts_feature\"), py::arg(\"pooled_features\"),\n        py::arg(\"pooled_empty_flag\"));\n  m.def(\"sigmoid_focal_loss_forward\", &sigmoid_focal_loss_forward,\n        \"sigmoid_focal_loss_forward \", py::arg(\"input\"), py::arg(\"target\"),\n        py::arg(\"weight\"), py::arg(\"output\"), py::arg(\"gamma\"),\n        py::arg(\"alpha\"));\n  m.def(\"sigmoid_focal_loss_backward\", &sigmoid_focal_loss_backward,\n        \"sigmoid_focal_loss_backward\", py::arg(\"input\"), py::arg(\"target\"),\n        py::arg(\"weight\"), py::arg(\"grad_input\"), py::arg(\"gamma\"),\n        py::arg(\"alpha\"));\n  m.def(\"softmax_focal_loss_forward\", &softmax_focal_loss_forward,\n        \"softmax_focal_loss_forward\", py::arg(\"input\"), py::arg(\"target\"),\n        py::arg(\"weight\"), py::arg(\"output\"), py::arg(\"gamma\"),\n        py::arg(\"alpha\"));\n  m.def(\"softmax_focal_loss_backward\", &softmax_focal_loss_backward,\n        \"softmax_focal_loss_backward\", py::arg(\"input\"), py::arg(\"target\"),\n        py::arg(\"weight\"), py::arg(\"buff\"), py::arg(\"grad_input\"),\n        py::arg(\"gamma\"), py::arg(\"alpha\"));\n  m.def(\"three_interpolate_forward\", &three_interpolate_forward,\n        \"three_interpolate_forward\", py::arg(\"points_tensor\"),\n        py::arg(\"idx_tensor\"), py::arg(\"weight_tensor\"), py::arg(\"out_tensor\"),\n        py::arg(\"b\"), py::arg(\"c\"), py::arg(\"m\"), py::arg(\"n\"));\n  m.def(\"three_interpolate_backward\", &three_interpolate_backward,\n        \"three_interpolate_backward\", py::arg(\"grad_out_tensor\"),\n        py::arg(\"idx_tensor\"), py::arg(\"weight_tensor\"),\n        py::arg(\"grad_points_tensor\"), py::arg(\"b\"), py::arg(\"c\"), py::arg(\"n\"),\n        py::arg(\"m\"));\n  m.def(\"three_nn_forward\", &three_nn_forward, \"three_nn_forward\",\n        py::arg(\"unknown_tensor\"), py::arg(\"known_tensor\"),\n        py::arg(\"dist2_tensor\"), py::arg(\"idx_tensor\"), py::arg(\"b\"),\n        py::arg(\"n\"), py::arg(\"m\"));\n  m.def(\"bbox_overlaps\", &bbox_overlaps, \"bbox_overlaps\", py::arg(\"bboxes1\"),\n        py::arg(\"bboxes2\"), py::arg(\"ious\"), py::arg(\"mode\"),\n        py::arg(\"aligned\"), py::arg(\"offset\"));\n  m.def(\"group_points_forward\", &group_points_forward, \"group_points_forward\",\n        py::arg(\"points_tensor\"), py::arg(\"idx_tensor\"), py::arg(\"out_tensor\"),\n        py::arg(\"b\"), py::arg(\"c\"), py::arg(\"n\"), py::arg(\"npoints\"),\n        py::arg(\"nsample\"));\n  m.def(\"group_points_backward\", &group_points_backward,\n        \"group_points_backward\", py::arg(\"grad_out_tensor\"),\n        py::arg(\"idx_tensor\"), py::arg(\"grad_points_tensor\"), py::arg(\"b\"),\n        py::arg(\"c\"), py::arg(\"n\"), py::arg(\"npoints\"), py::arg(\"nsample\"));\n  m.def(\"knn_forward\", &knn_forward, \"knn_forward\", py::arg(\"b\"), py::arg(\"n\"),\n        py::arg(\"m\"), py::arg(\"nsample\"), py::arg(\"xyz_tensor\"),\n        py::arg(\"new_xyz_tensor\"), py::arg(\"idx_tensor\"),\n        py::arg(\"dist2_tensor\"));\n  m.def(\"iou3d_boxes_overlap_bev_forward\", &iou3d_boxes_overlap_bev_forward,\n        \"iou3d_boxes_overlap_bev_forward\", py::arg(\"boxes_a\"),\n        py::arg(\"boxes_b\"), py::arg(\"ans_overlap\"));\n  m.def(\"iou3d_boxes_iou_bev_forward\", &iou3d_boxes_iou_bev_forward,\n        \"iou3d_boxes_iou_bev_forward\", py::arg(\"boxes_a\"), py::arg(\"boxes_b\"),\n        py::arg(\"ans_iou\"));\n  m.def(\"iou3d_nms_forward\", &iou3d_nms_forward, \"iou3d_nms_forward\",\n        py::arg(\"boxes\"), py::arg(\"keep\"), py::arg(\"num_out\"),\n        py::arg(\"nms_overlap_thresh\"));\n  m.def(\"iou3d_nms_normal_forward\", &iou3d_nms_normal_forward,\n        \"iou3d_nms_normal_forward\", py::arg(\"boxes\"), py::arg(\"keep\"),\n        py::arg(\"num_out\"), py::arg(\"nms_overlap_thresh\"));\n  m.def(\"furthest_point_sampling_forward\", &furthest_point_sampling_forward,\n        \"furthest_point_sampling_forward\", py::arg(\"points_tensor\"),\n        py::arg(\"temp_tensor\"), py::arg(\"idx_tensor\"), py::arg(\"b\"),\n        py::arg(\"n\"), py::arg(\"m\"));\n  m.def(\"furthest_point_sampling_with_dist_forward\",\n        &furthest_point_sampling_with_dist_forward,\n        \"furthest_point_sampling_with_dist_forward\", py::arg(\"points_tensor\"),\n        py::arg(\"temp_tensor\"), py::arg(\"idx_tensor\"), py::arg(\"b\"),\n        py::arg(\"n\"), py::arg(\"m\"));\n  m.def(\"masked_im2col_forward\", &masked_im2col_forward,\n        \"masked_im2col_forward\", py::arg(\"im\"), py::arg(\"mask_h_idx\"),\n        py::arg(\"mask_w_idx\"), py::arg(\"col\"), py::arg(\"kernel_h\"),\n        py::arg(\"kernel_w\"), py::arg(\"pad_h\"), py::arg(\"pad_w\"));\n  m.def(\"masked_col2im_forward\", &masked_col2im_forward,\n        \"masked_col2im_forward\", py::arg(\"col\"), py::arg(\"mask_h_idx\"),\n        py::arg(\"mask_w_idx\"), py::arg(\"im\"), py::arg(\"height\"),\n        py::arg(\"width\"), py::arg(\"channels\"));\n  m.def(\"modulated_deform_conv_forward\", &modulated_deform_conv_forward,\n        \"modulated deform conv forward\", py::arg(\"input\"), py::arg(\"weight\"),\n        py::arg(\"bias\"), py::arg(\"ones\"), py::arg(\"offset\"), py::arg(\"mask\"),\n        py::arg(\"output\"), py::arg(\"columns\"), py::arg(\"kernel_h\"),\n        py::arg(\"kernel_w\"), py::arg(\"stride_h\"), py::arg(\"stride_w\"),\n        py::arg(\"pad_h\"), py::arg(\"pad_w\"), py::arg(\"dilation_h\"),\n        py::arg(\"dilation_w\"), py::arg(\"group\"), py::arg(\"deformable_group\"),\n        py::arg(\"with_bias\"));\n  m.def(\"modulated_deform_conv_backward\", &modulated_deform_conv_backward,\n        \"modulated deform conv backward\", py::arg(\"input\"), py::arg(\"weight\"),\n        py::arg(\"bias\"), py::arg(\"ones\"), py::arg(\"offset\"), py::arg(\"mask\"),\n        py::arg(\"columns\"), py::arg(\"grad_input\"), py::arg(\"grad_weight\"),\n        py::arg(\"grad_bias\"), py::arg(\"grad_offset\"), py::arg(\"grad_mask\"),\n        py::arg(\"grad_output\"), py::arg(\"kernel_h\"), py::arg(\"kernel_w\"),\n        py::arg(\"stride_h\"), py::arg(\"stride_w\"), py::arg(\"pad_h\"),\n        py::arg(\"pad_w\"), py::arg(\"dilation_h\"), py::arg(\"dilation_w\"),\n        py::arg(\"group\"), py::arg(\"deformable_group\"), py::arg(\"with_bias\"));\n  m.def(\"nms\", &nms, \"nms (CPU/CUDA) \", py::arg(\"boxes\"), py::arg(\"scores\"),\n        py::arg(\"iou_threshold\"), py::arg(\"offset\"));\n  m.def(\"softnms\", &softnms, \"softnms (CPU) \", py::arg(\"boxes\"),\n        py::arg(\"scores\"), py::arg(\"dets\"), py::arg(\"iou_threshold\"),\n        py::arg(\"sigma\"), py::arg(\"min_score\"), py::arg(\"method\"),\n        py::arg(\"offset\"));\n  m.def(\"nms_match\", &nms_match, \"nms_match (CPU) \", py::arg(\"dets\"),\n        py::arg(\"iou_threshold\"));\n  m.def(\"pixel_group\", &pixel_group, \"pixel group (CPU) \", py::arg(\"score\"),\n        py::arg(\"mask\"), py::arg(\"embedding\"), py::arg(\"kernel_label\"),\n        py::arg(\"kernel_contour\"), py::arg(\"kernel_region_label\"),\n        py::arg(\"distance_threshold\"));\n  m.def(\"contour_expand\", &contour_expand, \"contour exapnd (CPU) \",\n        py::arg(\"kernel_mask\"), py::arg(\"internal_kernel_label\"),\n        py::arg(\"min_kernel_area\"), py::arg(\"kernel_num\"));\n  m.def(\"roi_align_forward\", &roi_align_forward, \"roi_align forward\",\n        py::arg(\"input\"), py::arg(\"rois\"), py::arg(\"output\"),\n        py::arg(\"argmax_y\"), py::arg(\"argmax_x\"), py::arg(\"aligned_height\"),\n        py::arg(\"aligned_width\"), py::arg(\"spatial_scale\"),\n        py::arg(\"sampling_ratio\"), py::arg(\"pool_mode\"), py::arg(\"aligned\"));\n  m.def(\"roi_align_backward\", &roi_align_backward, \"roi_align backward\",\n        py::arg(\"grad_output\"), py::arg(\"rois\"), py::arg(\"argmax_y\"),\n        py::arg(\"argmax_x\"), py::arg(\"grad_input\"), py::arg(\"aligned_height\"),\n        py::arg(\"aligned_width\"), py::arg(\"spatial_scale\"),\n        py::arg(\"sampling_ratio\"), py::arg(\"pool_mode\"), py::arg(\"aligned\"));\n  m.def(\"roi_pool_forward\", &roi_pool_forward, \"roi_pool forward\",\n        py::arg(\"input\"), py::arg(\"rois\"), py::arg(\"output\"), py::arg(\"argmax\"),\n        py::arg(\"pooled_height\"), py::arg(\"pooled_width\"),\n        py::arg(\"spatial_scale\"));\n  m.def(\"roi_pool_backward\", &roi_pool_backward, \"roi_pool backward\",\n        py::arg(\"grad_output\"), py::arg(\"rois\"), py::arg(\"argmax\"),\n        py::arg(\"grad_input\"), py::arg(\"pooled_height\"),\n        py::arg(\"pooled_width\"), py::arg(\"spatial_scale\"));\n  m.def(\"sync_bn_forward_mean\", &sync_bn_forward_mean, \"sync_bn forward_mean\",\n        py::arg(\"input\"), py::arg(\"mean\"));\n  m.def(\"sync_bn_forward_var\", &sync_bn_forward_var, \"sync_bn forward_var\",\n        py::arg(\"input\"), py::arg(\"mean\"), py::arg(\"var\"));\n  m.def(\"sync_bn_forward_output\", &sync_bn_forward_output,\n        \"sync_bn forward_output\", py::arg(\"input\"), py::arg(\"mean\"),\n        py::arg(\"var\"), py::arg(\"weight\"), py::arg(\"bias\"),\n        py::arg(\"running_mean\"), py::arg(\"running_var\"), py::arg(\"norm\"),\n        py::arg(\"std\"), py::arg(\"output\"), py::arg(\"eps\"), py::arg(\"momentum\"),\n        py::arg(\"group_size\"));\n  m.def(\"sync_bn_backward_param\", &sync_bn_backward_param,\n        \"sync_bn backward_param\", py::arg(\"grad_output\"), py::arg(\"norm\"),\n        py::arg(\"grad_weight\"), py::arg(\"grad_bias\"));\n  m.def(\"sync_bn_backward_data\", &sync_bn_backward_data,\n        \"sync_bn backward_data\", py::arg(\"grad_output\"), py::arg(\"weight\"),\n        py::arg(\"grad_weight\"), py::arg(\"grad_bias\"), py::arg(\"norm\"),\n        py::arg(\"std\"), py::arg(\"grad_input\"));\n  m.def(\"psamask_forward\", &psamask_forward, \"PSAMASK forward (CPU/CUDA)\",\n        py::arg(\"input\"), py::arg(\"output\"), py::arg(\"psa_type\"),\n        py::arg(\"num_\"), py::arg(\"h_feature\"), py::arg(\"w_feature\"),\n        py::arg(\"h_mask\"), py::arg(\"w_mask\"), py::arg(\"half_h_mask\"),\n        py::arg(\"half_w_mask\"));\n  m.def(\"psamask_backward\", &psamask_backward, \"PSAMASK backward (CPU/CUDA)\",\n        py::arg(\"grad_output\"), py::arg(\"grad_input\"), py::arg(\"psa_type\"),\n        py::arg(\"num_\"), py::arg(\"h_feature\"), py::arg(\"w_feature\"),\n        py::arg(\"h_mask\"), py::arg(\"w_mask\"), py::arg(\"half_h_mask\"),\n        py::arg(\"half_w_mask\"));\n  m.def(\"tin_shift_forward\", &tin_shift_forward, \"tin_shift forward\",\n        py::arg(\"input\"), py::arg(\"shift\"), py::arg(\"output\"));\n  m.def(\"tin_shift_backward\", &tin_shift_backward, \"tin_shift backward\",\n        py::arg(\"grad_output\"), py::arg(\"shift\"), py::arg(\"grad_input\"));\n  m.def(\"bottom_pool_forward\", &bottom_pool_forward, \"Bottom Pool Forward\",\n        py::arg(\"input\"), py::call_guard<py::gil_scoped_release>());\n  m.def(\"bottom_pool_backward\", &bottom_pool_backward, \"Bottom Pool Backward\",\n        py::arg(\"input\"), py::arg(\"grad_output\"),\n        py::call_guard<py::gil_scoped_release>());\n  m.def(\"left_pool_forward\", &left_pool_forward, \"Left Pool Forward\",\n        py::arg(\"input\"), py::call_guard<py::gil_scoped_release>());\n  m.def(\"left_pool_backward\", &left_pool_backward, \"Left Pool Backward\",\n        py::arg(\"input\"), py::arg(\"grad_output\"),\n        py::call_guard<py::gil_scoped_release>());\n  m.def(\"right_pool_forward\", &right_pool_forward, \"Right Pool Forward\",\n        py::arg(\"input\"), py::call_guard<py::gil_scoped_release>());\n  m.def(\"right_pool_backward\", &right_pool_backward, \"Right Pool Backward\",\n        py::arg(\"input\"), py::arg(\"grad_output\"),\n        py::call_guard<py::gil_scoped_release>());\n  m.def(\"top_pool_forward\", &top_pool_forward, \"Top Pool Forward\",\n        py::arg(\"input\"), py::call_guard<py::gil_scoped_release>());\n  m.def(\"top_pool_backward\", &top_pool_backward, \"Top Pool Backward\",\n        py::arg(\"input\"), py::arg(\"grad_output\"),\n        py::call_guard<py::gil_scoped_release>());\n  m.def(\"box_iou_rotated\", &box_iou_rotated, \"IoU for rotated boxes\",\n        py::arg(\"boxes1\"), py::arg(\"boxes2\"), py::arg(\"ious\"),\n        py::arg(\"mode_flag\"), py::arg(\"aligned\"));\n  m.def(\"nms_rotated\", &nms_rotated, \"NMS for rotated boxes\", py::arg(\"dets\"),\n        py::arg(\"scores\"), py::arg(\"order\"), py::arg(\"dets_sorted\"),\n        py::arg(\"iou_threshold\"), py::arg(\"multi_label\"));\n  m.def(\"ball_query_forward\", &ball_query_forward, \"ball_query_forward\",\n        py::arg(\"new_xyz_tensor\"), py::arg(\"xyz_tensor\"), py::arg(\"idx_tensor\"),\n        py::arg(\"b\"), py::arg(\"n\"), py::arg(\"m\"), py::arg(\"min_radius\"),\n        py::arg(\"max_radius\"), py::arg(\"nsample\"));\n  m.def(\"roi_align_rotated_forward\", &roi_align_rotated_forward,\n        \"roi_align_rotated forward\", py::arg(\"input\"), py::arg(\"rois\"),\n        py::arg(\"output\"), py::arg(\"pooled_height\"), py::arg(\"pooled_width\"),\n        py::arg(\"spatial_scale\"), py::arg(\"sample_num\"), py::arg(\"aligned\"),\n        py::arg(\"clockwise\"));\n  m.def(\"roi_align_rotated_backward\", &roi_align_rotated_backward,\n        \"roi_align_rotated backward\", py::arg(\"rois\"), py::arg(\"grad_input\"),\n        py::arg(\"grad_output\"), py::arg(\"pooled_height\"),\n        py::arg(\"pooled_width\"), py::arg(\"spatial_scale\"),\n        py::arg(\"sample_num\"), py::arg(\"aligned\"), py::arg(\"clockwise\"));\n  m.def(\"dynamic_point_to_voxel_forward\", &dynamic_point_to_voxel_forward,\n        \"dynamic_point_to_voxel_forward\", py::arg(\"feats\"), py::arg(\"coors\"),\n        py::arg(\"reduce_type\"));\n  m.def(\"dynamic_point_to_voxel_backward\", &dynamic_point_to_voxel_backward,\n        \"dynamic_point_to_voxel_backward\", py::arg(\"grad_feats\"),\n        py::arg(\"grad_reduced_feats\"), py::arg(\"feats\"),\n        py::arg(\"reduced_feats\"), py::arg(\"coors_idx\"), py::arg(\"reduce_count\"),\n        py::arg(\"reduce_type\"));\n  m.def(\"hard_voxelize_forward\", &hard_voxelize_forward,\n        \"hard_voxelize_forward\", py::arg(\"points\"), py::arg(\"voxel_size\"),\n        py::arg(\"coors_range\"), py::arg(\"voxels\"), py::arg(\"coors\"),\n        py::arg(\"num_points_per_voxel\"), py::arg(\"voxel_num\"),\n        py::arg(\"max_points\"), py::arg(\"max_voxels\"), py::arg(\"NDim\"));\n  m.def(\"dynamic_voxelize_forward\", &dynamic_voxelize_forward,\n        \"dynamic_voxelize_forward\", py::arg(\"points\"), py::arg(\"voxel_size\"),\n        py::arg(\"coors_range\"), py::arg(\"coors\"), py::arg(\"NDim\"));\n  m.def(\"ms_deform_attn_forward\", &ms_deform_attn_forward,\n        \"forward function of multi-scale deformable attention\",\n        py::arg(\"value\"), py::arg(\"value_spatial_shapes\"),\n        py::arg(\"value_level_start_index\"), py::arg(\"sampling_locations\"),\n        py::arg(\"attention_weights\"), py::arg(\"im2col_step\"));\n  m.def(\"ms_deform_attn_backward\", &ms_deform_attn_backward,\n        \"backward function of multi-scale deformable attention\",\n        py::arg(\"value\"), py::arg(\"value_spatial_shapes\"),\n        py::arg(\"value_level_start_index\"), py::arg(\"sampling_locations\"),\n        py::arg(\"attention_weights\"), py::arg(\"grad_output\"),\n        py::arg(\"grad_value\"), py::arg(\"grad_sampling_loc\"),\n        py::arg(\"grad_attn_weight\"), py::arg(\"im2col_step\"));\n  m.def(\"border_align_forward\", &border_align_forward,\n        \"forward function of border_align\", py::arg(\"input\"), py::arg(\"boxes\"),\n        py::arg(\"output\"), py::arg(\"argmax_idx\"), py::arg(\"pool_size\"));\n  m.def(\"border_align_backward\", &border_align_backward,\n        \"backward function of border_align\", py::arg(\"grad_output\"),\n        py::arg(\"boxes\"), py::arg(\"argmax_idx\"), py::arg(\"grad_input\"),\n        py::arg(\"pool_size\"));\n  m.def(\"correlation_forward\", &correlation_forward, \"Correlation forward\",\n        py::arg(\"input1\"), py::arg(\"input2\"), py::arg(\"output\"), py::arg(\"kH\"),\n        py::arg(\"kW\"), py::arg(\"patchH\"), py::arg(\"patchW\"), py::arg(\"padH\"),\n        py::arg(\"padW\"), py::arg(\"dilationH\"), py::arg(\"dilationW\"),\n        py::arg(\"dilation_patchH\"), py::arg(\"dilation_patchW\"), py::arg(\"dH\"),\n        py::arg(\"dW\"));\n  m.def(\"correlation_backward\", &correlation_backward, \"Correlation backward\",\n        py::arg(\"grad_output\"), py::arg(\"input1\"), py::arg(\"input2\"),\n        py::arg(\"grad_input1\"), py::arg(\"grad_input2\"), py::arg(\"kH\"),\n        py::arg(\"kW\"), py::arg(\"patchH\"), py::arg(\"patchW\"), py::arg(\"padH\"),\n        py::arg(\"padW\"), py::arg(\"dilationH\"), py::arg(\"dilationW\"),\n        py::arg(\"dilation_patchH\"), py::arg(\"dilation_patchW\"), py::arg(\"dH\"),\n        py::arg(\"dW\"));\n  m.def(\"points_in_boxes_cpu_forward\", &points_in_boxes_cpu_forward,\n        \"points_in_boxes_cpu_forward\", py::arg(\"boxes_tensor\"),\n        py::arg(\"pts_tensor\"), py::arg(\"pts_indices_tensor\"));\n  m.def(\"points_in_boxes_part_forward\", &points_in_boxes_part_forward,\n        \"points_in_boxes_part_forward\", py::arg(\"boxes_tensor\"),\n        py::arg(\"pts_tensor\"), py::arg(\"box_idx_of_points_tensor\"));\n  m.def(\"points_in_boxes_all_forward\", &points_in_boxes_all_forward,\n        \"points_in_boxes_all_forward\", py::arg(\"boxes_tensor\"),\n        py::arg(\"pts_tensor\"), py::arg(\"box_idx_of_points_tensor\"));\n  m.def(\"roiaware_pool3d_forward\", &roiaware_pool3d_forward,\n        \"roiaware_pool3d_forward\", py::arg(\"rois\"), py::arg(\"pts\"),\n        py::arg(\"pts_feature\"), py::arg(\"argmax\"), py::arg(\"pts_idx_of_voxels\"),\n        py::arg(\"pooled_features\"), py::arg(\"pool_method\"));\n  m.def(\"roiaware_pool3d_backward\", &roiaware_pool3d_backward,\n        \"roiaware_pool3d_backward\", py::arg(\"pts_idx_of_voxels\"),\n        py::arg(\"argmax\"), py::arg(\"grad_out\"), py::arg(\"grad_in\"),\n        py::arg(\"pool_method\"));\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/roi_align.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid roi_align_forward_impl(Tensor input, Tensor rois, Tensor output,\n                            Tensor argmax_y, Tensor argmax_x,\n                            int aligned_height, int aligned_width,\n                            float spatial_scale, int sampling_ratio,\n                            int pool_mode, bool aligned) {\n  DISPATCH_DEVICE_IMPL(roi_align_forward_impl, input, rois, output, argmax_y,\n                       argmax_x, aligned_height, aligned_width, spatial_scale,\n                       sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_backward_impl(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                             Tensor argmax_x, Tensor grad_input,\n                             int aligned_height, int aligned_width,\n                             float spatial_scale, int sampling_ratio,\n                             int pool_mode, bool aligned) {\n  DISPATCH_DEVICE_IMPL(roi_align_backward_impl, grad_output, rois, argmax_y,\n                       argmax_x, grad_input, aligned_height, aligned_width,\n                       spatial_scale, sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_forward(Tensor input, Tensor rois, Tensor output,\n                       Tensor argmax_y, Tensor argmax_x, int aligned_height,\n                       int aligned_width, float spatial_scale,\n                       int sampling_ratio, int pool_mode, bool aligned) {\n  roi_align_forward_impl(input, rois, output, argmax_y, argmax_x,\n                         aligned_height, aligned_width, spatial_scale,\n                         sampling_ratio, pool_mode, aligned);\n}\n\nvoid roi_align_backward(Tensor grad_output, Tensor rois, Tensor argmax_y,\n                        Tensor argmax_x, Tensor grad_input, int aligned_height,\n                        int aligned_width, float spatial_scale,\n                        int sampling_ratio, int pool_mode, bool aligned) {\n  roi_align_backward_impl(grad_output, rois, argmax_y, argmax_x, grad_input,\n                          aligned_height, aligned_width, spatial_scale,\n                          sampling_ratio, pool_mode, aligned);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/roi_align_rotated.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid roi_align_rotated_forward_impl(Tensor features, Tensor rois, Tensor output,\n                                    int aligned_height, int aligned_width,\n                                    float spatial_scale, int sample_ratio,\n                                    bool aligned, bool clockwise) {\n  DISPATCH_DEVICE_IMPL(roi_align_rotated_forward_impl, features, rois, output,\n                       aligned_height, aligned_width, spatial_scale,\n                       sample_ratio, aligned, clockwise);\n}\n\nvoid roi_align_rotated_backward_impl(Tensor top_grad, Tensor rois,\n                                     Tensor bottom_grad, int aligned_height,\n                                     int aligned_width, float spatial_scale,\n                                     int sample_ratio, bool aligned,\n                                     bool clockwise) {\n  DISPATCH_DEVICE_IMPL(roi_align_rotated_backward_impl, top_grad, rois,\n                       bottom_grad, aligned_height, aligned_width,\n                       spatial_scale, sample_ratio, aligned, clockwise);\n}\n\nvoid roi_align_rotated_forward(Tensor input, Tensor rois, Tensor output,\n                               int aligned_height, int aligned_width,\n                               float spatial_scale, int sampling_ratio,\n                               bool aligned, bool clockwise) {\n  roi_align_rotated_forward_impl(input, rois, output, aligned_height,\n                                 aligned_width, spatial_scale, sampling_ratio,\n                                 aligned, clockwise);\n}\n\nvoid roi_align_rotated_backward(Tensor top_grad, Tensor rois,\n                                Tensor bottom_grad, int aligned_height,\n                                int aligned_width, float spatial_scale,\n                                int sampling_ratio, bool aligned,\n                                bool clockwise) {\n  roi_align_rotated_backward_impl(top_grad, rois, bottom_grad, aligned_height,\n                                  aligned_width, spatial_scale, sampling_ratio,\n                                  aligned, clockwise);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/roi_pool.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid roi_pool_forward_impl(Tensor input, Tensor rois, Tensor output,\n                           Tensor argmax, int pooled_height, int pooled_width,\n                           float spatial_scale) {\n  DISPATCH_DEVICE_IMPL(roi_pool_forward_impl, input, rois, output, argmax,\n                       pooled_height, pooled_width, spatial_scale);\n}\n\nvoid roi_pool_backward_impl(Tensor grad_output, Tensor rois, Tensor argmax,\n                            Tensor grad_input, int pooled_height,\n                            int pooled_width, float spatial_scale) {\n  DISPATCH_DEVICE_IMPL(roi_pool_backward_impl, grad_output, rois, argmax,\n                       grad_input, pooled_height, pooled_width, spatial_scale);\n}\n\nvoid roi_pool_forward(Tensor input, Tensor rois, Tensor output, Tensor argmax,\n                      int pooled_height, int pooled_width,\n                      float spatial_scale) {\n  roi_pool_forward_impl(input, rois, output, argmax, pooled_height,\n                        pooled_width, spatial_scale);\n}\n\nvoid roi_pool_backward(Tensor grad_output, Tensor rois, Tensor argmax,\n                       Tensor grad_input, int pooled_height, int pooled_width,\n                       float spatial_scale) {\n  roi_pool_backward_impl(grad_output, rois, argmax, grad_input, pooled_height,\n                         pooled_width, spatial_scale);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/roiaware_pool3d.cpp",
    "content": "#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid roiaware_pool3d_forward_impl(int boxes_num, int pts_num, int channels,\n                                  int max_pts_each_voxel, int out_x, int out_y,\n                                  int out_z, const Tensor rois,\n                                  const Tensor pts, const Tensor pts_feature,\n                                  Tensor argmax, Tensor pts_idx_of_voxels,\n                                  Tensor pooled_features, int pool_method) {\n  DISPATCH_DEVICE_IMPL(roiaware_pool3d_forward_impl, boxes_num, pts_num,\n                       channels, max_pts_each_voxel, out_x, out_y, out_z, rois,\n                       pts, pts_feature, argmax, pts_idx_of_voxels,\n                       pooled_features, pool_method);\n}\n\nvoid roiaware_pool3d_backward_impl(int boxes_num, int out_x, int out_y,\n                                   int out_z, int channels,\n                                   int max_pts_each_voxel,\n                                   const Tensor pts_idx_of_voxels,\n                                   const Tensor argmax, const Tensor grad_out,\n                                   Tensor grad_in, int pool_method) {\n  DISPATCH_DEVICE_IMPL(roiaware_pool3d_backward_impl, boxes_num, out_x, out_y,\n                       out_z, channels, max_pts_each_voxel, pts_idx_of_voxels,\n                       argmax, grad_out, grad_in, pool_method);\n}\n\nvoid roiaware_pool3d_forward(Tensor rois, Tensor pts, Tensor pts_feature,\n                             Tensor argmax, Tensor pts_idx_of_voxels,\n                             Tensor pooled_features, int pool_method) {\n  // params rois: (N, 7) [x, y, z, x_size, y_size, z_size, ry] in LiDAR\n  // coordinate\n  // params pts: (npoints, 3) [x, y, z] in LiDAR coordinate\n  // params pts_feature: (npoints, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params pooled_features: (N, out_x, out_y, out_z, C)\n  // params pool_method: 0: max_pool 1: avg_pool\n  int boxes_num = rois.size(0);\n  int pts_num = pts.size(0);\n  int channels = pts_feature.size(1);\n  int max_pts_each_voxel = pts_idx_of_voxels.size(4);  // index 0 is the counter\n  int out_x = pts_idx_of_voxels.size(1);\n  int out_y = pts_idx_of_voxels.size(2);\n  int out_z = pts_idx_of_voxels.size(3);\n  assert((out_x < 256) && (out_y < 256) &&\n         (out_z < 256));  // we encode index with 8bit\n\n  roiaware_pool3d_forward_impl(boxes_num, pts_num, channels, max_pts_each_voxel,\n                               out_x, out_y, out_z, rois, pts, pts_feature,\n                               argmax, pts_idx_of_voxels, pooled_features,\n                               pool_method);\n}\n\nvoid roiaware_pool3d_backward(Tensor pts_idx_of_voxels, Tensor argmax,\n                              Tensor grad_out, Tensor grad_in,\n                              int pool_method) {\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n  // params pool_method: 0: max_pool 1: avg_pool\n  int boxes_num = pts_idx_of_voxels.size(0);\n  int out_x = pts_idx_of_voxels.size(1);\n  int out_y = pts_idx_of_voxels.size(2);\n  int out_z = pts_idx_of_voxels.size(3);\n  int max_pts_each_voxel = pts_idx_of_voxels.size(4);  // index 0 is the counter\n  int channels = grad_out.size(4);\n\n  roiaware_pool3d_backward_impl(boxes_num, out_x, out_y, out_z, channels,\n                                max_pts_each_voxel, pts_idx_of_voxels, argmax,\n                                grad_out, grad_in, pool_method);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/roipoint_pool3d.cpp",
    "content": "/*\nModified from\nhttps://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/roipoint_pool3d/src/roipoint_pool3d.cpp\nPoint cloud feature pooling\nWritten by Shaoshuai Shi\nAll Rights Reserved 2018.\n*/\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid roipoint_pool3d_forward_impl(int batch_size, int pts_num, int boxes_num,\n                                  int feature_in_len, int sampled_pts_num,\n                                  const Tensor xyz, const Tensor boxes3d,\n                                  const Tensor pts_feature,\n                                  Tensor pooled_features,\n                                  Tensor pooled_empty_flag) {\n  DISPATCH_DEVICE_IMPL(roipoint_pool3d_forward_impl, batch_size, pts_num,\n                       boxes_num, feature_in_len, sampled_pts_num, xyz, boxes3d,\n                       pts_feature, pooled_features, pooled_empty_flag);\n}\n\nvoid roipoint_pool3d_forward(Tensor xyz, Tensor boxes3d, Tensor pts_feature,\n                             Tensor pooled_features, Tensor pooled_empty_flag) {\n  // params xyz: (B, N, 3)\n  // params boxes3d: (B, M, 7)\n  // params pts_feature: (B, N, C)\n  // params pooled_features: (B, M, 512, 3+C)\n  // params pooled_empty_flag: (B, M)\n  int batch_size = xyz.size(0);\n  int pts_num = xyz.size(1);\n  int boxes_num = boxes3d.size(1);\n  int feature_in_len = pts_feature.size(2);\n  int sampled_pts_num = pooled_features.size(2);\n\n  roipoint_pool3d_forward_impl(batch_size, pts_num, boxes_num, feature_in_len,\n                               sampled_pts_num, xyz, boxes3d, pts_feature,\n                               pooled_features, pooled_empty_flag);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/scatter_points.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntypedef enum { SUM = 0, MEAN = 1, MAX = 2 } reduce_t;\n\nstd::vector<torch::Tensor> dynamic_point_to_voxel_forward_impl(\n    const torch::Tensor &feats, const torch::Tensor &coors,\n    const reduce_t reduce_type) {\n  return DISPATCH_DEVICE_IMPL(dynamic_point_to_voxel_forward_impl, feats, coors,\n                              reduce_type);\n}\n\nvoid dynamic_point_to_voxel_backward_impl(\n    torch::Tensor &grad_feats, const torch::Tensor &grad_reduced_feats,\n    const torch::Tensor &feats, const torch::Tensor &reduced_feats,\n    const torch::Tensor &coors_idx, const torch::Tensor &reduce_count,\n    const reduce_t reduce_type) {\n  DISPATCH_DEVICE_IMPL(dynamic_point_to_voxel_backward_impl, grad_feats,\n                       grad_reduced_feats, feats, reduced_feats, coors_idx,\n                       reduce_count, reduce_type);\n}\n\ninline reduce_t convert_reduce_type(const std::string &reduce_type) {\n  if (reduce_type == \"max\")\n    return reduce_t::MAX;\n  else if (reduce_type == \"sum\")\n    return reduce_t::SUM;\n  else if (reduce_type == \"mean\")\n    return reduce_t::MEAN;\n  else\n    TORCH_CHECK(false, \"do not support reduce type \" + reduce_type)\n  return reduce_t::SUM;\n}\n\nstd::vector<torch::Tensor> dynamic_point_to_voxel_forward(\n    const torch::Tensor &feats, const torch::Tensor &coors,\n    const std::string &reduce_type) {\n  return dynamic_point_to_voxel_forward_impl(feats, coors,\n                                             convert_reduce_type(reduce_type));\n}\n\nvoid dynamic_point_to_voxel_backward(torch::Tensor &grad_feats,\n                                     const torch::Tensor &grad_reduced_feats,\n                                     const torch::Tensor &feats,\n                                     const torch::Tensor &reduced_feats,\n                                     const torch::Tensor &coors_idx,\n                                     const torch::Tensor &reduce_count,\n                                     const std::string &reduce_type) {\n  dynamic_point_to_voxel_backward_impl(grad_feats, grad_reduced_feats, feats,\n                                       reduced_feats, coors_idx, reduce_count,\n                                       convert_reduce_type(reduce_type));\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/sync_bn.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid sync_bn_forward_mean_impl(const Tensor input, Tensor mean) {\n  DISPATCH_DEVICE_IMPL(sync_bn_forward_mean_impl, input, mean);\n}\n\nvoid sync_bn_forward_var_impl(const Tensor input, const Tensor mean,\n                              Tensor var) {\n  DISPATCH_DEVICE_IMPL(sync_bn_forward_var_impl, input, mean, var);\n}\n\nvoid sync_bn_forward_output_impl(const Tensor input, const Tensor mean,\n                                 const Tensor var, Tensor running_mean,\n                                 Tensor running_var, const Tensor weight,\n                                 const Tensor bias, Tensor norm, Tensor std,\n                                 Tensor output, float eps, float momentum,\n                                 int group_size) {\n  DISPATCH_DEVICE_IMPL(sync_bn_forward_output_impl, input, mean, var,\n                       running_mean, running_var, weight, bias, norm, std,\n                       output, eps, momentum, group_size);\n}\n\nvoid sync_bn_backward_param_impl(const Tensor grad_output, const Tensor norm,\n                                 Tensor grad_weight, Tensor grad_bias) {\n  DISPATCH_DEVICE_IMPL(sync_bn_backward_param_impl, grad_output, norm,\n                       grad_weight, grad_bias);\n}\n\nvoid sync_bn_backward_data_impl(const Tensor grad_output, const Tensor weight,\n                                const Tensor grad_weight,\n                                const Tensor grad_bias, const Tensor norm,\n                                const Tensor std, Tensor grad_input) {\n  DISPATCH_DEVICE_IMPL(sync_bn_backward_data_impl, grad_output, weight,\n                       grad_weight, grad_bias, norm, std, grad_input);\n}\n\nvoid sync_bn_forward_mean(const Tensor input, Tensor mean) {\n  sync_bn_forward_mean_impl(input, mean);\n}\n\nvoid sync_bn_forward_var(const Tensor input, const Tensor mean, Tensor var) {\n  sync_bn_forward_var_impl(input, mean, var);\n}\n\nvoid sync_bn_forward_output(const Tensor input, const Tensor mean,\n                            const Tensor var, const Tensor weight,\n                            const Tensor bias, Tensor running_mean,\n                            Tensor running_var, Tensor norm, Tensor std,\n                            Tensor output, float eps, float momentum,\n                            int group_size) {\n  sync_bn_forward_output_impl(input, mean, var, running_mean, running_var,\n                              weight, bias, norm, std, output, eps, momentum,\n                              group_size);\n}\n\nvoid sync_bn_backward_param(const Tensor grad_output, const Tensor norm,\n                            Tensor grad_weight, Tensor grad_bias) {\n  sync_bn_backward_param_impl(grad_output, norm, grad_weight, grad_bias);\n}\n\nvoid sync_bn_backward_data(const Tensor grad_output, const Tensor weight,\n                           const Tensor grad_weight, const Tensor grad_bias,\n                           const Tensor norm, const Tensor std,\n                           Tensor grad_input) {\n  sync_bn_backward_data_impl(grad_output, weight, grad_weight, grad_bias, norm,\n                             std, grad_input);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/three_interpolate.cpp",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/interpolate.cpp\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid three_interpolate_forward_impl(int b, int c, int m, int n,\n                                    const Tensor points, const Tensor idx,\n                                    const Tensor weight, Tensor out) {\n  DISPATCH_DEVICE_IMPL(three_interpolate_forward_impl, b, c, m, n, points, idx,\n                       weight, out);\n}\n\nvoid three_interpolate_backward_impl(int b, int c, int n, int m,\n                                     const Tensor grad_out, const Tensor idx,\n                                     const Tensor weight, Tensor grad_points) {\n  DISPATCH_DEVICE_IMPL(three_interpolate_backward_impl, b, c, n, m, grad_out,\n                       idx, weight, grad_points);\n}\n\nvoid three_interpolate_forward(Tensor points_tensor, Tensor idx_tensor,\n                               Tensor weight_tensor, Tensor out_tensor, int b,\n                               int c, int m, int n) {\n  three_interpolate_forward_impl(b, c, m, n, points_tensor, idx_tensor,\n                                 weight_tensor, out_tensor);\n}\n\nvoid three_interpolate_backward(Tensor grad_out_tensor, Tensor idx_tensor,\n                                Tensor weight_tensor, Tensor grad_points_tensor,\n                                int b, int c, int n, int m) {\n  three_interpolate_backward_impl(b, c, n, m, grad_out_tensor, idx_tensor,\n                                  weight_tensor, grad_points_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/three_nn.cpp",
    "content": "// Modified from\n// https://github.com/sshaoshuai/Pointnet2.PyTorch/tree/master/pointnet2/src/interpolate.cpp\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid three_nn_forward_impl(int b, int n, int m, const Tensor unknown,\n                           const Tensor known, Tensor dist2, Tensor idx) {\n  DISPATCH_DEVICE_IMPL(three_nn_forward_impl, b, n, m, unknown, known, dist2,\n                       idx);\n}\n\nvoid three_nn_forward(Tensor unknown_tensor, Tensor known_tensor,\n                      Tensor dist2_tensor, Tensor idx_tensor, int b, int n,\n                      int m) {\n  three_nn_forward_impl(b, n, m, unknown_tensor, known_tensor, dist2_tensor,\n                        idx_tensor);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/tin_shift.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nvoid tin_shift_forward_impl(Tensor input, Tensor shift, Tensor output) {\n  DISPATCH_DEVICE_IMPL(tin_shift_forward_impl, input, shift, output);\n}\n\nvoid tin_shift_backward_impl(Tensor grad_output, Tensor shift,\n                             Tensor grad_input) {\n  DISPATCH_DEVICE_IMPL(tin_shift_backward_impl, grad_output, shift, grad_input);\n}\n\nvoid tin_shift_forward(Tensor input, Tensor shift, Tensor output) {\n  tin_shift_forward_impl(input, shift, output);\n}\n\nvoid tin_shift_backward(Tensor grad_output, Tensor shift, Tensor grad_input) {\n  tin_shift_backward_impl(grad_output, shift, grad_input);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/upfirdn2d.cpp",
    "content": "// Modified from\n// https://github.com/rosinality/stylegan2-pytorch/blob/master/op/upfirdn2d.cpp\n\n/*\nCopyright (c) 2021, NVIDIA Corporation. All rights reserved.\n\nNVIDIA Source Code License for StyleGAN2 with Adaptive Discriminator\nAugmentation (ADA)\n=======================================================================\n\n1. Definitions\n\n\"Licensor\" means any person or entity that distributes its Work.\n\n\"Software\" means the original work of authorship made available under\nthis License.\n\n\"Work\" means the Software and any additions to or derivative works of\nthe Software that are made available under this License.\n\nThe terms \"reproduce,\" \"reproduction,\" \"derivative works,\" and\n\"distribution\" have the meaning as provided under U.S. copyright law;\nprovided, however, that for the purposes of this License, derivative\nworks shall not include works that remain separable from, or merely\nlink (or bind by name) to the interfaces of, the Work.\n\nWorks, including the Software, are \"made available\" under this License\nby including in or with the Work either (a) a copyright notice\nreferencing the applicability of this License to the Work, or (b) a\ncopy of this License.\n\n2. License Grants\n\n    2.1 Copyright Grant. Subject to the terms and conditions of this\n    License, each Licensor grants to you a perpetual, worldwide,\n    non-exclusive, royalty-free, copyright license to reproduce,\n    prepare derivative works of, publicly display, publicly perform,\n    sublicense and distribute its Work and any resulting derivative\n    works in any form.\n\n3. Limitations\n\n    3.1 Redistribution. You may reproduce or distribute the Work only\n    if (a) you do so under this License, (b) you include a complete\n    copy of this License with your distribution, and (c) you retain\n    without modification any copyright, patent, trademark, or\n    attribution notices that are present in the Work.\n\n    3.2 Derivative Works. You may specify that additional or different\n    terms apply to the use, reproduction, and distribution of your\n    derivative works of the Work (\"Your Terms\") only if (a) Your Terms\n    provide that the use limitation in Section 3.3 applies to your\n    derivative works, and (b) you identify the specific derivative\n    works that are subject to Your Terms. Notwithstanding Your Terms,\n    this License (including the redistribution requirements in Section\n    3.1) will continue to apply to the Work itself.\n\n    3.3 Use Limitation. The Work and any derivative works thereof only\n    may be used or intended for use non-commercially. Notwithstanding\n    the foregoing, NVIDIA and its affiliates may use the Work and any\n    derivative works commercially. As used herein, \"non-commercially\"\n    means for research or evaluation purposes only.\n\n    3.4 Patent Claims. If you bring or threaten to bring a patent claim\n    against any Licensor (including any claim, cross-claim or\n    counterclaim in a lawsuit) to enforce any patents that you allege\n    are infringed by any Work, then your rights under this License from\n    such Licensor (including the grant in Section 2.1) will terminate\n    immediately.\n\n    3.5 Trademarks. This License does not grant any rights to use any\n    Licensor’s or its affiliates’ names, logos, or trademarks, except\n    as necessary to reproduce the notices described in this License.\n\n    3.6 Termination. If you violate any term of this License, then your\n    rights under this License (including the grant in Section 2.1) will\n    terminate immediately.\n\n4. Disclaimer of Warranty.\n\nTHE WORK IS PROVIDED \"AS IS\" WITHOUT WARRANTIES OR CONDITIONS OF ANY\nKIND, EITHER EXPRESS OR IMPLIED, INCLUDING WARRANTIES OR CONDITIONS OF\nMERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE OR\nNON-INFRINGEMENT. YOU BEAR THE RISK OF UNDERTAKING ANY ACTIVITIES UNDER\nTHIS LICENSE.\n\n5. Limitation of Liability.\n\nEXCEPT AS PROHIBITED BY APPLICABLE LAW, IN NO EVENT AND UNDER NO LEGAL\nTHEORY, WHETHER IN TORT (INCLUDING NEGLIGENCE), CONTRACT, OR OTHERWISE\nSHALL ANY LICENSOR BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY DIRECT,\nINDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT OF\nOR RELATED TO THIS LICENSE, THE USE OR INABILITY TO USE THE WORK\n(INCLUDING BUT NOT LIMITED TO LOSS OF GOODWILL, BUSINESS INTERRUPTION,\nLOST PROFITS OR DATA, COMPUTER FAILURE OR MALFUNCTION, OR ANY OTHER\nCOMMERCIAL DAMAGES OR LOSSES), EVEN IF THE LICENSOR HAS BEEN ADVISED OF\nTHE POSSIBILITY OF SUCH DAMAGES.\n\n=======================================================================\n*/\n\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\ntorch::Tensor upfirdn2d_op_impl(const torch::Tensor& input,\n                                const torch::Tensor& kernel, int up_x, int up_y,\n                                int down_x, int down_y, int pad_x0, int pad_x1,\n                                int pad_y0, int pad_y1) {\n  return DISPATCH_DEVICE_IMPL(upfirdn2d_op_impl, input, kernel, up_x, up_y,\n                              down_x, down_y, pad_x0, pad_x1, pad_y0, pad_y1);\n}\n\ntorch::Tensor upfirdn2d(const torch::Tensor& input, const torch::Tensor& kernel,\n                        int up_x, int up_y, int down_x, int down_y, int pad_x0,\n                        int pad_x1, int pad_y0, int pad_y1) {\n  return upfirdn2d_op_impl(input, kernel, up_x, up_y, down_x, down_y, pad_x0,\n                           pad_x1, pad_y0, pad_y1);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/csrc/pytorch/voxelization.cpp",
    "content": "// Copyright (c) OpenMMLab. All rights reserved.\n#include \"pytorch_cpp_helper.hpp\"\n#include \"pytorch_device_registry.hpp\"\n\nint hard_voxelize_forward_impl(const at::Tensor &points, at::Tensor &voxels,\n                               at::Tensor &coors,\n                               at::Tensor &num_points_per_voxel,\n                               const std::vector<float> voxel_size,\n                               const std::vector<float> coors_range,\n                               const int max_points, const int max_voxels,\n                               const int NDim = 3) {\n  return DISPATCH_DEVICE_IMPL(hard_voxelize_forward_impl, points, voxels, coors,\n                              num_points_per_voxel, voxel_size, coors_range,\n                              max_points, max_voxels, NDim);\n}\n\nvoid dynamic_voxelize_forward_impl(const at::Tensor &points, at::Tensor &coors,\n                                   const std::vector<float> voxel_size,\n                                   const std::vector<float> coors_range,\n                                   const int NDim = 3) {\n  DISPATCH_DEVICE_IMPL(dynamic_voxelize_forward_impl, points, coors, voxel_size,\n                       coors_range, NDim);\n}\n\nvoid hard_voxelize_forward(const at::Tensor &points,\n                           const at::Tensor &voxel_size,\n                           const at::Tensor &coors_range, at::Tensor &voxels,\n                           at::Tensor &coors, at::Tensor &num_points_per_voxel,\n                           at::Tensor &voxel_num, const int max_points,\n                           const int max_voxels, const int NDim = 3) {\n  int64_t *voxel_num_data = voxel_num.data_ptr<int64_t>();\n  std::vector<float> voxel_size_v(\n      voxel_size.data_ptr<float>(),\n      voxel_size.data_ptr<float>() + voxel_size.numel());\n  std::vector<float> coors_range_v(\n      coors_range.data_ptr<float>(),\n      coors_range.data_ptr<float>() + coors_range.numel());\n\n  *voxel_num_data = hard_voxelize_forward_impl(\n      points, voxels, coors, num_points_per_voxel, voxel_size_v, coors_range_v,\n      max_points, max_voxels, NDim);\n}\n\nvoid dynamic_voxelize_forward(const at::Tensor &points,\n                              const at::Tensor &voxel_size,\n                              const at::Tensor &coors_range, at::Tensor &coors,\n                              const int NDim = 3) {\n  std::vector<float> voxel_size_v(\n      voxel_size.data_ptr<float>(),\n      voxel_size.data_ptr<float>() + voxel_size.numel());\n  std::vector<float> coors_range_v(\n      coors_range.data_ptr<float>(),\n      coors_range.data_ptr<float>() + coors_range.numel());\n  dynamic_voxelize_forward_impl(points, coors, voxel_size_v, coors_range_v,\n                                NDim);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/deform_conv.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom typing import Tuple, Union\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom torch import Tensor\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair, _single\n\nfrom mmcv.utils import deprecated_api_warning\nfrom ..models.bricks import CONV_LAYERS\nfrom ..utils import ext_loader, print_log\n\next_module = ext_loader.load_ext('_ext', [\n    'deform_conv_forward', 'deform_conv_backward_input',\n    'deform_conv_backward_parameters'\n])\n\n\nclass DeformConv2dFunction(Function):\n\n    @staticmethod\n    def symbolic(g,\n                 input,\n                 offset,\n                 weight,\n                 stride,\n                 padding,\n                 dilation,\n                 groups,\n                 deform_groups,\n                 bias=False,\n                 im2col_step=32):\n        return g.op(\n            'mmcv::MMCVDeformConv2d',\n            input,\n            offset,\n            weight,\n            stride_i=stride,\n            padding_i=padding,\n            dilation_i=dilation,\n            groups_i=groups,\n            deform_groups_i=deform_groups,\n            bias_i=bias,\n            im2col_step_i=im2col_step)\n\n    @staticmethod\n    def forward(ctx,\n                input,\n                offset,\n                weight,\n                stride=1,\n                padding=0,\n                dilation=1,\n                groups=1,\n                deform_groups=1,\n                bias=False,\n                im2col_step=32):\n        if input is not None and input.dim() != 4:\n            raise ValueError(\n                f'Expected 4D tensor as input, got {input.dim()}D tensor \\\n                  instead.')\n        assert bias is False, 'Only support bias is False.'\n        ctx.stride = _pair(stride)\n        ctx.padding = _pair(padding)\n        ctx.dilation = _pair(dilation)\n        ctx.groups = groups\n        ctx.deform_groups = deform_groups\n        ctx.im2col_step = im2col_step\n\n        # When pytorch version >= 1.6.0, amp is adopted for fp16 mode;\n        # amp won't cast the type of model (float32), but \"offset\" is cast\n        # to float16 by nn.Conv2d automatically, leading to the type\n        # mismatch with input (when it is float32) or weight.\n        # The flag for whether to use fp16 or amp is the type of \"offset\",\n        # we cast weight and input to temporarily support fp16 and amp\n        # whatever the pytorch version is.\n        input = input.type_as(offset)\n        weight = weight.type_as(input)\n        ctx.save_for_backward(input, offset, weight)\n\n        output = input.new_empty(\n            DeformConv2dFunction._output_size(ctx, input, weight))\n\n        ctx.bufs_ = [input.new_empty(0), input.new_empty(0)]  # columns, ones\n\n        cur_im2col_step = min(ctx.im2col_step, input.size(0))\n        assert (input.size(0) % cur_im2col_step\n                ) == 0, 'batch size must be divisible by im2col_step'\n        ext_module.deform_conv_forward(\n            input,\n            weight,\n            offset,\n            output,\n            ctx.bufs_[0],\n            ctx.bufs_[1],\n            kW=weight.size(3),\n            kH=weight.size(2),\n            dW=ctx.stride[1],\n            dH=ctx.stride[0],\n            padW=ctx.padding[1],\n            padH=ctx.padding[0],\n            dilationW=ctx.dilation[1],\n            dilationH=ctx.dilation[0],\n            group=ctx.groups,\n            deformable_group=ctx.deform_groups,\n            im2col_step=cur_im2col_step)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        input, offset, weight = ctx.saved_tensors\n\n        grad_input = grad_offset = grad_weight = None\n\n        cur_im2col_step = min(ctx.im2col_step, input.size(0))\n        assert (input.size(0) % cur_im2col_step\n                ) == 0, 'batch size must be divisible by im2col_step'\n\n        grad_output = grad_output.contiguous()\n        if ctx.needs_input_grad[0] or ctx.needs_input_grad[1]:\n            grad_input = torch.zeros_like(input)\n            grad_offset = torch.zeros_like(offset)\n            ext_module.deform_conv_backward_input(\n                input,\n                offset,\n                grad_output,\n                grad_input,\n                grad_offset,\n                weight,\n                ctx.bufs_[0],\n                kW=weight.size(3),\n                kH=weight.size(2),\n                dW=ctx.stride[1],\n                dH=ctx.stride[0],\n                padW=ctx.padding[1],\n                padH=ctx.padding[0],\n                dilationW=ctx.dilation[1],\n                dilationH=ctx.dilation[0],\n                group=ctx.groups,\n                deformable_group=ctx.deform_groups,\n                im2col_step=cur_im2col_step)\n\n        if ctx.needs_input_grad[2]:\n            grad_weight = torch.zeros_like(weight)\n            ext_module.deform_conv_backward_parameters(\n                input,\n                offset,\n                grad_output,\n                grad_weight,\n                ctx.bufs_[0],\n                ctx.bufs_[1],\n                kW=weight.size(3),\n                kH=weight.size(2),\n                dW=ctx.stride[1],\n                dH=ctx.stride[0],\n                padW=ctx.padding[1],\n                padH=ctx.padding[0],\n                dilationW=ctx.dilation[1],\n                dilationH=ctx.dilation[0],\n                group=ctx.groups,\n                deformable_group=ctx.deform_groups,\n                scale=1,\n                im2col_step=cur_im2col_step)\n\n        return grad_input, grad_offset, grad_weight, \\\n            None, None, None, None, None, None, None\n\n    @staticmethod\n    def _output_size(ctx, input, weight):\n        channels = weight.size(0)\n        output_size = (input.size(0), channels)\n        for d in range(input.dim() - 2):\n            in_size = input.size(d + 2)\n            pad = ctx.padding[d]\n            kernel = ctx.dilation[d] * (weight.size(d + 2) - 1) + 1\n            stride_ = ctx.stride[d]\n            output_size += ((in_size + (2 * pad) - kernel) // stride_ + 1, )\n        if not all(map(lambda s: s > 0, output_size)):\n            raise ValueError(\n                'convolution input is too small (output would be ' +\n                'x'.join(map(str, output_size)) + ')')\n        return output_size\n\n\ndeform_conv2d = DeformConv2dFunction.apply\n\n\nclass DeformConv2d(nn.Module):\n    r\"\"\"Deformable 2D convolution.\n\n    Applies a deformable 2D convolution over an input signal composed of\n    several input planes. DeformConv2d was described in the paper\n    `Deformable Convolutional Networks\n    <https://arxiv.org/pdf/1703.06211.pdf>`_\n\n    Note:\n        The argument ``im2col_step`` was added in version 1.3.17, which means\n        number of samples processed by the ``im2col_cuda_kernel`` per call.\n        It enables users to define ``batch_size`` and ``im2col_step`` more\n        flexibly and solved `issue mmcv#1440\n        <https://github.com/open-mmlab/mmcv/issues/1440>`_.\n\n    Args:\n        in_channels (int): Number of channels in the input image.\n        out_channels (int): Number of channels produced by the convolution.\n        kernel_size(int, tuple): Size of the convolving kernel.\n        stride(int, tuple): Stride of the convolution. Default: 1.\n        padding (int or tuple): Zero-padding added to both sides of the input.\n            Default: 0.\n        dilation (int or tuple): Spacing between kernel elements. Default: 1.\n        groups (int): Number of blocked connections from input.\n            channels to output channels. Default: 1.\n        deform_groups (int): Number of deformable group partitions.\n        bias (bool): If True, adds a learnable bias to the output.\n            Default: False.\n        im2col_step (int): Number of samples processed by im2col_cuda_kernel\n            per call. It will work when ``batch_size`` > ``im2col_step``, but\n            ``batch_size`` must be divisible by ``im2col_step``. Default: 32.\n            `New in version 1.3.17.`\n    \"\"\"\n\n    @deprecated_api_warning({'deformable_groups': 'deform_groups'},\n                            cls_name='DeformConv2d')\n    def __init__(self,\n                 in_channels: int,\n                 out_channels: int,\n                 kernel_size: Union[int, Tuple[int, ...]],\n                 stride: Union[int, Tuple[int, ...]] = 1,\n                 padding: Union[int, Tuple[int, ...]] = 0,\n                 dilation: Union[int, Tuple[int, ...]] = 1,\n                 groups: int = 1,\n                 deform_groups: int = 1,\n                 bias: bool = False,\n                 im2col_step: int = 32) -> None:\n        super(DeformConv2d, self).__init__()\n\n        assert not bias, \\\n            f'bias={bias} is not supported in DeformConv2d.'\n        assert in_channels % groups == 0, \\\n            f'in_channels {in_channels} cannot be divisible by groups {groups}'\n        assert out_channels % groups == 0, \\\n            f'out_channels {out_channels} cannot be divisible by groups \\\n              {groups}'\n\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.stride = _pair(stride)\n        self.padding = _pair(padding)\n        self.dilation = _pair(dilation)\n        self.groups = groups\n        self.deform_groups = deform_groups\n        self.im2col_step = im2col_step\n        # enable compatibility with nn.Conv2d\n        self.transposed = False\n        self.output_padding = _single(0)\n\n        # only weight, no bias\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // self.groups,\n                         *self.kernel_size))\n\n        self.reset_parameters()\n\n    def reset_parameters(self):\n        # switch the initialization of `self.weight` to the standard kaiming\n        # method described in `Delving deep into rectifiers: Surpassing\n        # human-level performance on ImageNet classification` - He, K. et al.\n        # (2015), using a uniform distribution\n        nn.init.kaiming_uniform_(self.weight, nonlinearity='relu')\n\n    def forward(self, x: Tensor, offset: Tensor) -> Tensor:\n        \"\"\"Deformable Convolutional forward function.\n\n        Args:\n            x (Tensor): Input feature, shape (B, C_in, H_in, W_in)\n            offset (Tensor): Offset for deformable convolution, shape\n                (B, deform_groups*kernel_size[0]*kernel_size[1]*2,\n                H_out, W_out), H_out, W_out are equal to the output's.\n\n                An offset is like `[y0, x0, y1, x1, y2, x2, ..., y8, x8]`.\n                The spatial arrangement is like:\n\n                .. code:: text\n\n                    (x0, y0) (x1, y1) (x2, y2)\n                    (x3, y3) (x4, y4) (x5, y5)\n                    (x6, y6) (x7, y7) (x8, y8)\n\n        Returns:\n            Tensor: Output of the layer.\n        \"\"\"\n        # To fix an assert error in deform_conv_cuda.cpp:128\n        # input image is smaller than kernel\n        input_pad = (x.size(2) < self.kernel_size[0]) or (x.size(3) <\n                                                          self.kernel_size[1])\n        if input_pad:\n            pad_h = max(self.kernel_size[0] - x.size(2), 0)\n            pad_w = max(self.kernel_size[1] - x.size(3), 0)\n            x = F.pad(x, (0, pad_w, 0, pad_h), 'constant', 0).contiguous()\n            offset = F.pad(offset, (0, pad_w, 0, pad_h), 'constant', 0)\n            offset = offset.contiguous()\n        out = deform_conv2d(x, offset, self.weight, self.stride, self.padding,\n                            self.dilation, self.groups, self.deform_groups,\n                            False, self.im2col_step)\n        if input_pad:\n            out = out[:, :, :out.size(2) - pad_h, :out.size(3) -\n                      pad_w].contiguous()\n        return out\n\n    def __repr__(self):\n        s = self.__class__.__name__\n        s += f'(in_channels={self.in_channels},\\n'\n        s += f'out_channels={self.out_channels},\\n'\n        s += f'kernel_size={self.kernel_size},\\n'\n        s += f'stride={self.stride},\\n'\n        s += f'padding={self.padding},\\n'\n        s += f'dilation={self.dilation},\\n'\n        s += f'groups={self.groups},\\n'\n        s += f'deform_groups={self.deform_groups},\\n'\n        # bias is not supported in DeformConv2d.\n        s += 'bias=False)'\n        return s\n\n\n@CONV_LAYERS.register_module('DCN')\nclass DeformConv2dPack(DeformConv2d):\n    \"\"\"A Deformable Conv Encapsulation that acts as normal Conv layers.\n\n    The offset tensor is like `[y0, x0, y1, x1, y2, x2, ..., y8, x8]`.\n    The spatial arrangement is like:\n\n    .. code:: text\n\n        (x0, y0) (x1, y1) (x2, y2)\n        (x3, y3) (x4, y4) (x5, y5)\n        (x6, y6) (x7, y7) (x8, y8)\n\n    Args:\n        in_channels (int): Same as nn.Conv2d.\n        out_channels (int): Same as nn.Conv2d.\n        kernel_size (int or tuple[int]): Same as nn.Conv2d.\n        stride (int or tuple[int]): Same as nn.Conv2d.\n        padding (int or tuple[int]): Same as nn.Conv2d.\n        dilation (int or tuple[int]): Same as nn.Conv2d.\n        groups (int): Same as nn.Conv2d.\n        bias (bool or str): If specified as `auto`, it will be decided by the\n            norm_cfg. Bias will be set as True if norm_cfg is None, otherwise\n            False.\n    \"\"\"\n\n    _version = 2\n\n    def __init__(self, *args, **kwargs):\n        super(DeformConv2dPack, self).__init__(*args, **kwargs)\n        self.conv_offset = nn.Conv2d(\n            self.in_channels,\n            self.deform_groups * 2 * self.kernel_size[0] * self.kernel_size[1],\n            kernel_size=self.kernel_size,\n            stride=_pair(self.stride),\n            padding=_pair(self.padding),\n            dilation=_pair(self.dilation),\n            bias=True)\n        self.init_offset()\n\n    def init_offset(self):\n        self.conv_offset.weight.data.zero_()\n        self.conv_offset.bias.data.zero_()\n\n    def forward(self, x):\n        offset = self.conv_offset(x)\n        return deform_conv2d(x, offset, self.weight, self.stride, self.padding,\n                             self.dilation, self.groups, self.deform_groups,\n                             False, self.im2col_step)\n\n    def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,\n                              missing_keys, unexpected_keys, error_msgs):\n        version = local_metadata.get('version', None)\n\n        if version is None or version < 2:\n            # the key is different in early versions\n            # In version < 2, DeformConvPack loads previous benchmark models.\n            if (prefix + 'conv_offset.weight' not in state_dict\n                    and prefix[:-1] + '_offset.weight' in state_dict):\n                state_dict[prefix + 'conv_offset.weight'] = state_dict.pop(\n                    prefix[:-1] + '_offset.weight')\n            if (prefix + 'conv_offset.bias' not in state_dict\n                    and prefix[:-1] + '_offset.bias' in state_dict):\n                state_dict[prefix +\n                           'conv_offset.bias'] = state_dict.pop(prefix[:-1] +\n                                                                '_offset.bias')\n\n        if version is not None and version > 1:\n            print_log(\n                f'DeformConv2dPack {prefix.rstrip(\".\")} is upgraded to '\n                'version 2.',\n                logger='root')\n\n        super()._load_from_state_dict(state_dict, prefix, local_metadata,\n                                      strict, missing_keys, unexpected_keys,\n                                      error_msgs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/focal_loss.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nimport torch.nn as nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\n\nfrom ..utils import ext_loader\n\next_module = ext_loader.load_ext('_ext', [\n    'sigmoid_focal_loss_forward', 'sigmoid_focal_loss_backward',\n    'softmax_focal_loss_forward', 'softmax_focal_loss_backward'\n])\n\n\nclass SigmoidFocalLossFunction(Function):\n\n    @staticmethod\n    def symbolic(g, input, target, gamma, alpha, weight, reduction):\n        return g.op(\n            'mmcv::MMCVSigmoidFocalLoss',\n            input,\n            target,\n            gamma_f=gamma,\n            alpha_f=alpha,\n            weight_f=weight,\n            reduction_s=reduction)\n\n    @staticmethod\n    def forward(ctx,\n                input,\n                target,\n                gamma=2.0,\n                alpha=0.25,\n                weight=None,\n                reduction='mean'):\n\n        assert isinstance(target, (torch.LongTensor, torch.cuda.LongTensor))\n        assert input.dim() == 2\n        assert target.dim() == 1\n        assert input.size(0) == target.size(0)\n        if weight is None:\n            weight = input.new_empty(0)\n        else:\n            assert weight.dim() == 1\n            assert input.size(1) == weight.size(0)\n        ctx.reduction_dict = {'none': 0, 'mean': 1, 'sum': 2}\n        assert reduction in ctx.reduction_dict.keys()\n\n        ctx.gamma = float(gamma)\n        ctx.alpha = float(alpha)\n        ctx.reduction = ctx.reduction_dict[reduction]\n\n        output = input.new_zeros(input.size())\n\n        ext_module.sigmoid_focal_loss_forward(\n            input, target, weight, output, gamma=ctx.gamma, alpha=ctx.alpha)\n        if ctx.reduction == ctx.reduction_dict['mean']:\n            output = output.sum() / input.size(0)\n        elif ctx.reduction == ctx.reduction_dict['sum']:\n            output = output.sum()\n        ctx.save_for_backward(input, target, weight)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        input, target, weight = ctx.saved_tensors\n\n        grad_input = input.new_zeros(input.size())\n\n        ext_module.sigmoid_focal_loss_backward(\n            input,\n            target,\n            weight,\n            grad_input,\n            gamma=ctx.gamma,\n            alpha=ctx.alpha)\n\n        grad_input *= grad_output\n        if ctx.reduction == ctx.reduction_dict['mean']:\n            grad_input /= input.size(0)\n        return grad_input, None, None, None, None, None\n\n\nsigmoid_focal_loss = SigmoidFocalLossFunction.apply\n\n\nclass SigmoidFocalLoss(nn.Module):\n\n    def __init__(self, gamma, alpha, weight=None, reduction='mean'):\n        super(SigmoidFocalLoss, self).__init__()\n        self.gamma = gamma\n        self.alpha = alpha\n        self.register_buffer('weight', weight)\n        self.reduction = reduction\n\n    def forward(self, input, target):\n        return sigmoid_focal_loss(input, target, self.gamma, self.alpha,\n                                  self.weight, self.reduction)\n\n    def __repr__(self):\n        s = self.__class__.__name__\n        s += f'(gamma={self.gamma}, '\n        s += f'alpha={self.alpha}, '\n        s += f'reduction={self.reduction})'\n        return s\n\n\nclass SoftmaxFocalLossFunction(Function):\n\n    @staticmethod\n    def symbolic(g, input, target, gamma, alpha, weight, reduction):\n        return g.op(\n            'mmcv::MMCVSoftmaxFocalLoss',\n            input,\n            target,\n            gamma_f=gamma,\n            alpha_f=alpha,\n            weight_f=weight,\n            reduction_s=reduction)\n\n    @staticmethod\n    def forward(ctx,\n                input,\n                target,\n                gamma=2.0,\n                alpha=0.25,\n                weight=None,\n                reduction='mean'):\n\n        assert isinstance(target, (torch.LongTensor, torch.cuda.LongTensor))\n        assert input.dim() == 2\n        assert target.dim() == 1\n        assert input.size(0) == target.size(0)\n        if weight is None:\n            weight = input.new_empty(0)\n        else:\n            assert weight.dim() == 1\n            assert input.size(1) == weight.size(0)\n        ctx.reduction_dict = {'none': 0, 'mean': 1, 'sum': 2}\n        assert reduction in ctx.reduction_dict.keys()\n\n        ctx.gamma = float(gamma)\n        ctx.alpha = float(alpha)\n        ctx.reduction = ctx.reduction_dict[reduction]\n\n        channel_stats, _ = torch.max(input, dim=1)\n        input_softmax = input - channel_stats.unsqueeze(1).expand_as(input)\n        input_softmax.exp_()\n\n        channel_stats = input_softmax.sum(dim=1)\n        input_softmax /= channel_stats.unsqueeze(1).expand_as(input)\n\n        output = input.new_zeros(input.size(0))\n        ext_module.softmax_focal_loss_forward(\n            input_softmax,\n            target,\n            weight,\n            output,\n            gamma=ctx.gamma,\n            alpha=ctx.alpha)\n\n        if ctx.reduction == ctx.reduction_dict['mean']:\n            output = output.sum() / input.size(0)\n        elif ctx.reduction == ctx.reduction_dict['sum']:\n            output = output.sum()\n        ctx.save_for_backward(input_softmax, target, weight)\n        return output\n\n    @staticmethod\n    def backward(ctx, grad_output):\n        input_softmax, target, weight = ctx.saved_tensors\n        buff = input_softmax.new_zeros(input_softmax.size(0))\n        grad_input = input_softmax.new_zeros(input_softmax.size())\n\n        ext_module.softmax_focal_loss_backward(\n            input_softmax,\n            target,\n            weight,\n            buff,\n            grad_input,\n            gamma=ctx.gamma,\n            alpha=ctx.alpha)\n\n        grad_input *= grad_output\n        if ctx.reduction == ctx.reduction_dict['mean']:\n            grad_input /= input_softmax.size(0)\n        return grad_input, None, None, None, None, None\n\n\nsoftmax_focal_loss = SoftmaxFocalLossFunction.apply\n\n\nclass SoftmaxFocalLoss(nn.Module):\n\n    def __init__(self, gamma, alpha, weight=None, reduction='mean'):\n        super(SoftmaxFocalLoss, self).__init__()\n        self.gamma = gamma\n        self.alpha = alpha\n        self.register_buffer('weight', weight)\n        self.reduction = reduction\n\n    def forward(self, input, target):\n        return softmax_focal_loss(input, target, self.gamma, self.alpha,\n                                  self.weight, self.reduction)\n\n    def __repr__(self):\n        s = self.__class__.__name__\n        s += f'(gamma={self.gamma}, '\n        s += f'alpha={self.alpha}, '\n        s += f'reduction={self.reduction})'\n        return s\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/iou3d.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom ..utils import ext_loader\n\next_module = ext_loader.load_ext('_ext', [\n    'iou3d_boxes_iou_bev_forward', 'iou3d_nms_forward',\n    'iou3d_nms_normal_forward'\n])\n\n\ndef boxes_iou_bev(boxes_a, boxes_b):\n    \"\"\"Calculate boxes IoU in the Bird's Eye View.\n\n    Args:\n        boxes_a (torch.Tensor): Input boxes a with shape (M, 5).\n        boxes_b (torch.Tensor): Input boxes b with shape (N, 5).\n\n    Returns:\n        ans_iou (torch.Tensor): IoU result with shape (M, N).\n    \"\"\"\n    ans_iou = boxes_a.new_zeros(\n        torch.Size((boxes_a.shape[0], boxes_b.shape[0])))\n\n    ext_module.iou3d_boxes_iou_bev_forward(boxes_a.contiguous(),\n                                           boxes_b.contiguous(), ans_iou)\n\n    return ans_iou\n\n\ndef nms_bev(boxes, scores, thresh, pre_max_size=None, post_max_size=None):\n    \"\"\"NMS function GPU implementation (for BEV boxes). The overlap of two\n    boxes for IoU calculation is defined as the exact overlapping area of the\n    two boxes. In this function, one can also set ``pre_max_size`` and\n    ``post_max_size``.\n\n    Args:\n        boxes (torch.Tensor): Input boxes with the shape of [N, 5]\n            ([x1, y1, x2, y2, ry]).\n        scores (torch.Tensor): Scores of boxes with the shape of [N].\n        thresh (float): Overlap threshold of NMS.\n        pre_max_size (int, optional): Max size of boxes before NMS.\n            Default: None.\n        post_max_size (int, optional): Max size of boxes after NMS.\n            Default: None.\n\n    Returns:\n        torch.Tensor: Indexes after NMS.\n    \"\"\"\n    assert boxes.size(1) == 5, 'Input boxes shape should be [N, 5]'\n    order = scores.sort(0, descending=True)[1]\n\n    if pre_max_size is not None:\n        order = order[:pre_max_size]\n    boxes = boxes[order].contiguous()\n\n    keep = torch.zeros(boxes.size(0), dtype=torch.long)\n    num_out = torch.zeros(size=(), dtype=torch.long)\n    ext_module.iou3d_nms_forward(\n        boxes, keep, num_out, nms_overlap_thresh=thresh)\n    keep = order[keep[:num_out].cuda(boxes.device)].contiguous()\n    if post_max_size is not None:\n        keep = keep[:post_max_size]\n    return keep\n\n\ndef nms_normal_bev(boxes, scores, thresh):\n    \"\"\"Normal NMS function GPU implementation (for BEV boxes). The overlap of\n    two boxes for IoU calculation is defined as the exact overlapping area of\n    the two boxes WITH their yaw angle set to 0.\n\n    Args:\n        boxes (torch.Tensor): Input boxes with shape (N, 5).\n        scores (torch.Tensor): Scores of predicted boxes with shape (N).\n        thresh (float): Overlap threshold of NMS.\n\n    Returns:\n        torch.Tensor: Remaining indices with scores in descending order.\n    \"\"\"\n    assert boxes.shape[1] == 5, 'Input boxes shape should be [N, 5]'\n    order = scores.sort(0, descending=True)[1]\n\n    boxes = boxes[order].contiguous()\n\n    keep = torch.zeros(boxes.size(0), dtype=torch.long)\n    num_out = torch.zeros(size=(), dtype=torch.long)\n    ext_module.iou3d_nms_normal_forward(\n        boxes, keep, num_out, nms_overlap_thresh=thresh)\n    return order[keep[:num_out].cuda(boxes.device)].contiguous()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/iou3d_det/__init__.py",
    "content": "from .iou3d_utils import boxes_iou_bev, nms_gpu, nms_normal_gpu\n\n__all__ = ['boxes_iou_bev', 'nms_gpu', 'nms_normal_gpu']\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/iou3d_det/iou3d_utils.py",
    "content": "import torch\n\nfrom . import iou3d_cuda\n\n\ndef boxes_iou_bev(boxes_a, boxes_b):\n    \"\"\"Calculate boxes IoU in the bird view.\n\n    Args:\n        boxes_a (torch.Tensor): Input boxes a with shape (M, 5).\n        boxes_b (torch.Tensor): Input boxes b with shape (N, 5).\n\n    Returns:\n        ans_iou (torch.Tensor): IoU result with shape (M, N).\n    \"\"\"\n    ans_iou = boxes_a.new_zeros(\n        torch.Size((boxes_a.shape[0], boxes_b.shape[0])))\n\n    iou3d_cuda.boxes_iou_bev_gpu(boxes_a.contiguous(), boxes_b.contiguous(),\n                                 ans_iou)\n\n    return ans_iou\n\n\ndef nms_gpu(boxes, scores, thresh, pre_maxsize=None, post_max_size=None):\n    \"\"\"Nms function with gpu implementation.\n\n    Args:\n        boxes (torch.Tensor): Input boxes with the shape of [N, 5]\n            ([x1, y1, x2, y2, ry]).\n        scores (torch.Tensor): Scores of boxes with the shape of [N].\n        thresh (int): Threshold.\n        pre_maxsize (int): Max size of boxes before nms. Default: None.\n        post_maxsize (int): Max size of boxes after nms. Default: None.\n\n    Returns:\n        torch.Tensor: Indexes after nms.\n    \"\"\"\n    order = scores.sort(0, descending=True)[1]\n\n    if pre_maxsize is not None:\n        order = order[:pre_maxsize]\n    boxes = boxes[order].contiguous()\n\n    keep = torch.zeros(boxes.size(0), dtype=torch.long)\n    num_out = iou3d_cuda.nms_gpu(boxes, keep, thresh, boxes.device.index)\n    keep = order[keep[:num_out].cuda(boxes.device)].contiguous()\n    if post_max_size is not None:\n        keep = keep[:post_max_size]\n    return keep\n\n\ndef nms_normal_gpu(boxes, scores, thresh):\n    \"\"\"Normal non maximum suppression on GPU.\n\n    Args:\n        boxes (torch.Tensor): Input boxes with shape (N, 5).\n        scores (torch.Tensor): Scores of predicted boxes with shape (N).\n        thresh (torch.Tensor): Threshold of non maximum suppression.\n\n    Returns:\n        torch.Tensor: Remaining indices with scores in descending order.\n    \"\"\"\n    order = scores.sort(0, descending=True)[1]\n\n    boxes = boxes[order].contiguous()\n\n    keep = torch.zeros(boxes.size(0), dtype=torch.long)\n    num_out = iou3d_cuda.nms_normal_gpu(boxes, keep, thresh,\n                                        boxes.device.index)\n    return order[keep[:num_out].cuda(boxes.device)].contiguous()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/iou3d_det/src/iou3d.cpp",
    "content": "// Modified from\n// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms.cpp\n\n/*\n3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)\nWritten by Shaoshuai Shi\nAll Rights Reserved 2019-2020.\n*/\n\n#include <cuda.h>\n#include <cuda_runtime_api.h>\n#include <torch/extension.h>\n#include <torch/serialize/tensor.h>\n\n#include <cstdint>\n#include <vector>\n\n#define CHECK_CUDA(x) \\\n  TORCH_CHECK(x.device().is_cuda(), #x, \" must be a CUDAtensor \")\n#define CHECK_CONTIGUOUS(x) \\\n  TORCH_CHECK(x.is_contiguous(), #x, \" must be contiguous \")\n#define CHECK_INPUT(x) \\\n  CHECK_CUDA(x);       \\\n  CHECK_CONTIGUOUS(x)\n\n#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))\n\n#define CHECK_ERROR(ans) \\\n  { gpuAssert((ans), __FILE__, __LINE__); }\ninline void gpuAssert(cudaError_t code, const char *file, int line,\n                      bool abort = true) {\n  if (code != cudaSuccess) {\n    fprintf(stderr, \"GPUassert: %s %s %d\\n\", cudaGetErrorString(code), file,\n            line);\n    if (abort) exit(code);\n  }\n}\n\nconst int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;\n\nvoid boxesoverlapLauncher(const int num_a, const float *boxes_a,\n                          const int num_b, const float *boxes_b,\n                          float *ans_overlap);\nvoid boxesioubevLauncher(const int num_a, const float *boxes_a, const int num_b,\n                         const float *boxes_b, float *ans_iou);\nvoid nmsLauncher(const float *boxes, unsigned long long *mask, int boxes_num,\n                 float nms_overlap_thresh);\nvoid nmsNormalLauncher(const float *boxes, unsigned long long *mask,\n                       int boxes_num, float nms_overlap_thresh);\n\nint boxes_overlap_bev_gpu(at::Tensor boxes_a, at::Tensor boxes_b,\n                          at::Tensor ans_overlap) {\n  // params boxes_a: (N, 5) [x1, y1, x2, y2, ry]\n  // params boxes_b: (M, 5)\n  // params ans_overlap: (N, M)\n\n  CHECK_INPUT(boxes_a);\n  CHECK_INPUT(boxes_b);\n  CHECK_INPUT(ans_overlap);\n\n  int num_a = boxes_a.size(0);\n  int num_b = boxes_b.size(0);\n\n  const float *boxes_a_data = boxes_a.data_ptr<float>();\n  const float *boxes_b_data = boxes_b.data_ptr<float>();\n  float *ans_overlap_data = ans_overlap.data_ptr<float>();\n\n  boxesoverlapLauncher(num_a, boxes_a_data, num_b, boxes_b_data,\n                       ans_overlap_data);\n\n  return 1;\n}\n\nint boxes_iou_bev_gpu(at::Tensor boxes_a, at::Tensor boxes_b,\n                      at::Tensor ans_iou) {\n  // params boxes_a: (N, 5) [x1, y1, x2, y2, ry]\n  // params boxes_b: (M, 5)\n  // params ans_overlap: (N, M)\n\n  CHECK_INPUT(boxes_a);\n  CHECK_INPUT(boxes_b);\n  CHECK_INPUT(ans_iou);\n\n  int num_a = boxes_a.size(0);\n  int num_b = boxes_b.size(0);\n\n  const float *boxes_a_data = boxes_a.data_ptr<float>();\n  const float *boxes_b_data = boxes_b.data_ptr<float>();\n  float *ans_iou_data = ans_iou.data_ptr<float>();\n\n  boxesioubevLauncher(num_a, boxes_a_data, num_b, boxes_b_data, ans_iou_data);\n\n  return 1;\n}\n\nint nms_gpu(at::Tensor boxes, at::Tensor keep,\n\t    float nms_overlap_thresh, int device_id) {\n  // params boxes: (N, 5) [x1, y1, x2, y2, ry]\n  // params keep: (N)\n\n  CHECK_INPUT(boxes);\n  CHECK_CONTIGUOUS(keep);\n  cudaSetDevice(device_id);\n\n  int boxes_num = boxes.size(0);\n  const float *boxes_data = boxes.data_ptr<float>();\n  int64_t *keep_data = keep.data_ptr<int64_t>();\n\n  const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n\n  unsigned long long *mask_data = NULL;\n  CHECK_ERROR(cudaMalloc((void **)&mask_data,\n                         boxes_num * col_blocks * sizeof(unsigned long long)));\n  nmsLauncher(boxes_data, mask_data, boxes_num, nms_overlap_thresh);\n\n  // unsigned long long mask_cpu[boxes_num * col_blocks];\n  // unsigned long long *mask_cpu = new unsigned long long [boxes_num *\n  // col_blocks];\n  std::vector<unsigned long long> mask_cpu(boxes_num * col_blocks);\n\n  //    printf(\"boxes_num=%d, col_blocks=%d\\n\", boxes_num, col_blocks);\n  CHECK_ERROR(cudaMemcpy(&mask_cpu[0], mask_data,\n                         boxes_num * col_blocks * sizeof(unsigned long long),\n                         cudaMemcpyDeviceToHost));\n\n  cudaFree(mask_data);\n\n  unsigned long long *remv_cpu = new unsigned long long[col_blocks]();\n\n  int num_to_keep = 0;\n\n  for (int i = 0; i < boxes_num; i++) {\n    int nblock = i / THREADS_PER_BLOCK_NMS;\n    int inblock = i % THREADS_PER_BLOCK_NMS;\n\n    if (!(remv_cpu[nblock] & (1ULL << inblock))) {\n      keep_data[num_to_keep++] = i;\n      unsigned long long *p = &mask_cpu[0] + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv_cpu[j] |= p[j];\n      }\n    }\n  }\n  delete[] remv_cpu;\n  if (cudaSuccess != cudaGetLastError()) printf(\"Error!\\n\");\n\n  return num_to_keep;\n}\n\nint nms_normal_gpu(at::Tensor boxes, at::Tensor keep,\n                   float nms_overlap_thresh, int device_id) {\n  // params boxes: (N, 5) [x1, y1, x2, y2, ry]\n  // params keep: (N)\n\n  CHECK_INPUT(boxes);\n  CHECK_CONTIGUOUS(keep);\n  cudaSetDevice(device_id);\n\n  int boxes_num = boxes.size(0);\n  const float *boxes_data = boxes.data_ptr<float>();\n  int64_t *keep_data = keep.data_ptr<int64_t>();\n\n  const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n\n  unsigned long long *mask_data = NULL;\n  CHECK_ERROR(cudaMalloc((void **)&mask_data,\n                         boxes_num * col_blocks * sizeof(unsigned long long)));\n  nmsNormalLauncher(boxes_data, mask_data, boxes_num, nms_overlap_thresh);\n\n  // unsigned long long mask_cpu[boxes_num * col_blocks];\n  // unsigned long long *mask_cpu = new unsigned long long [boxes_num *\n  // col_blocks];\n  std::vector<unsigned long long> mask_cpu(boxes_num * col_blocks);\n\n  //    printf(\"boxes_num=%d, col_blocks=%d\\n\", boxes_num, col_blocks);\n  CHECK_ERROR(cudaMemcpy(&mask_cpu[0], mask_data,\n                         boxes_num * col_blocks * sizeof(unsigned long long),\n                         cudaMemcpyDeviceToHost));\n\n  cudaFree(mask_data);\n\n  unsigned long long *remv_cpu = new unsigned long long[col_blocks]();\n\n  int num_to_keep = 0;\n\n  for (int i = 0; i < boxes_num; i++) {\n    int nblock = i / THREADS_PER_BLOCK_NMS;\n    int inblock = i % THREADS_PER_BLOCK_NMS;\n\n    if (!(remv_cpu[nblock] & (1ULL << inblock))) {\n      keep_data[num_to_keep++] = i;\n      unsigned long long *p = &mask_cpu[0] + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv_cpu[j] |= p[j];\n      }\n    }\n  }\n  delete[] remv_cpu;\n  if (cudaSuccess != cudaGetLastError()) printf(\"Error!\\n\");\n\n  return num_to_keep;\n}\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"boxes_overlap_bev_gpu\", &boxes_overlap_bev_gpu,\n        \"oriented boxes overlap\");\n  m.def(\"boxes_iou_bev_gpu\", &boxes_iou_bev_gpu, \"oriented boxes iou\");\n  m.def(\"nms_gpu\", &nms_gpu, \"oriented nms gpu\");\n  m.def(\"nms_normal_gpu\", &nms_normal_gpu, \"nms gpu\");\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/iou3d_det/src/iou3d_kernel.cu",
    "content": "// Modified from\n// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms_kernel.cu\n\n/*\n3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)\nWritten by Shaoshuai Shi\nAll Rights Reserved 2019-2020.\n*/\n\n#include <stdio.h>\n#define THREADS_PER_BLOCK 16\n#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))\n\n//#define DEBUG\nconst int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;\n__device__ const float EPS = 1e-8;\nstruct Point {\n  float x, y;\n  __device__ Point() {}\n  __device__ Point(double _x, double _y) { x = _x, y = _y; }\n\n  __device__ void set(float _x, float _y) {\n    x = _x;\n    y = _y;\n  }\n\n  __device__ Point operator+(const Point &b) const {\n    return Point(x + b.x, y + b.y);\n  }\n\n  __device__ Point operator-(const Point &b) const {\n    return Point(x - b.x, y - b.y);\n  }\n};\n\n__device__ inline float cross(const Point &a, const Point &b) {\n  return a.x * b.y - a.y * b.x;\n}\n\n__device__ inline float cross(const Point &p1, const Point &p2,\n                              const Point &p0) {\n  return (p1.x - p0.x) * (p2.y - p0.y) - (p2.x - p0.x) * (p1.y - p0.y);\n}\n\n__device__ int check_rect_cross(const Point &p1, const Point &p2,\n                                const Point &q1, const Point &q2) {\n  int ret = min(p1.x, p2.x) <= max(q1.x, q2.x) &&\n            min(q1.x, q2.x) <= max(p1.x, p2.x) &&\n            min(p1.y, p2.y) <= max(q1.y, q2.y) &&\n            min(q1.y, q2.y) <= max(p1.y, p2.y);\n  return ret;\n}\n\n__device__ inline int check_in_box2d(const float *box, const Point &p) {\n  // params: box (5) [x1, y1, x2, y2, angle]\n  const float MARGIN = 1e-5;\n\n  float center_x = (box[0] + box[2]) / 2;\n  float center_y = (box[1] + box[3]) / 2;\n  float angle_cos = cos(-box[4]),\n        angle_sin =\n            sin(-box[4]);  // rotate the point in the opposite direction of box\n  float rot_x =\n      (p.x - center_x) * angle_cos + (p.y - center_y) * angle_sin + center_x;\n  float rot_y =\n      -(p.x - center_x) * angle_sin + (p.y - center_y) * angle_cos + center_y;\n#ifdef DEBUG\n  printf(\"box: (%.3f, %.3f, %.3f, %.3f, %.3f)\\n\", box[0], box[1], box[2],\n         box[3], box[4]);\n  printf(\n      \"center: (%.3f, %.3f), cossin(%.3f, %.3f), src(%.3f, %.3f), rot(%.3f, \"\n      \"%.3f)\\n\",\n      center_x, center_y, angle_cos, angle_sin, p.x, p.y, rot_x, rot_y);\n#endif\n  return (rot_x > box[0] - MARGIN && rot_x < box[2] + MARGIN &&\n          rot_y > box[1] - MARGIN && rot_y < box[3] + MARGIN);\n}\n\n__device__ inline int intersection(const Point &p1, const Point &p0,\n                                   const Point &q1, const Point &q0,\n                                   Point &ans) {\n  // fast exclusion\n  if (check_rect_cross(p0, p1, q0, q1) == 0) return 0;\n\n  // check cross standing\n  float s1 = cross(q0, p1, p0);\n  float s2 = cross(p1, q1, p0);\n  float s3 = cross(p0, q1, q0);\n  float s4 = cross(q1, p1, q0);\n\n  if (!(s1 * s2 > 0 && s3 * s4 > 0)) return 0;\n\n  // calculate intersection of two lines\n  float s5 = cross(q1, p1, p0);\n  if (fabs(s5 - s1) > EPS) {\n    ans.x = (s5 * q0.x - s1 * q1.x) / (s5 - s1);\n    ans.y = (s5 * q0.y - s1 * q1.y) / (s5 - s1);\n\n  } else {\n    float a0 = p0.y - p1.y, b0 = p1.x - p0.x, c0 = p0.x * p1.y - p1.x * p0.y;\n    float a1 = q0.y - q1.y, b1 = q1.x - q0.x, c1 = q0.x * q1.y - q1.x * q0.y;\n    float D = a0 * b1 - a1 * b0;\n\n    ans.x = (b0 * c1 - b1 * c0) / D;\n    ans.y = (a1 * c0 - a0 * c1) / D;\n  }\n\n  return 1;\n}\n\n__device__ inline void rotate_around_center(const Point &center,\n                                            const float angle_cos,\n                                            const float angle_sin, Point &p) {\n  float new_x =\n      (p.x - center.x) * angle_cos + (p.y - center.y) * angle_sin + center.x;\n  float new_y =\n      -(p.x - center.x) * angle_sin + (p.y - center.y) * angle_cos + center.y;\n  p.set(new_x, new_y);\n}\n\n__device__ inline int point_cmp(const Point &a, const Point &b,\n                                const Point &center) {\n  return atan2(a.y - center.y, a.x - center.x) >\n         atan2(b.y - center.y, b.x - center.x);\n}\n\n__device__ inline float box_overlap(const float *box_a, const float *box_b) {\n  // params: box_a (5) [x1, y1, x2, y2, angle]\n  // params: box_b (5) [x1, y1, x2, y2, angle]\n\n  float a_x1 = box_a[0], a_y1 = box_a[1], a_x2 = box_a[2], a_y2 = box_a[3],\n        a_angle = box_a[4];\n  float b_x1 = box_b[0], b_y1 = box_b[1], b_x2 = box_b[2], b_y2 = box_b[3],\n        b_angle = box_b[4];\n\n  Point center_a((a_x1 + a_x2) / 2, (a_y1 + a_y2) / 2);\n  Point center_b((b_x1 + b_x2) / 2, (b_y1 + b_y2) / 2);\n#ifdef DEBUG\n  printf(\n      \"a: (%.3f, %.3f, %.3f, %.3f, %.3f), b: (%.3f, %.3f, %.3f, %.3f, %.3f)\\n\",\n      a_x1, a_y1, a_x2, a_y2, a_angle, b_x1, b_y1, b_x2, b_y2, b_angle);\n  printf(\"center a: (%.3f, %.3f), b: (%.3f, %.3f)\\n\", center_a.x, center_a.y,\n         center_b.x, center_b.y);\n#endif\n\n  Point box_a_corners[5];\n  box_a_corners[0].set(a_x1, a_y1);\n  box_a_corners[1].set(a_x2, a_y1);\n  box_a_corners[2].set(a_x2, a_y2);\n  box_a_corners[3].set(a_x1, a_y2);\n\n  Point box_b_corners[5];\n  box_b_corners[0].set(b_x1, b_y1);\n  box_b_corners[1].set(b_x2, b_y1);\n  box_b_corners[2].set(b_x2, b_y2);\n  box_b_corners[3].set(b_x1, b_y2);\n\n  // get oriented corners\n  float a_angle_cos = cos(a_angle), a_angle_sin = sin(a_angle);\n  float b_angle_cos = cos(b_angle), b_angle_sin = sin(b_angle);\n\n  for (int k = 0; k < 4; k++) {\n#ifdef DEBUG\n    printf(\"before corner %d: a(%.3f, %.3f), b(%.3f, %.3f) \\n\", k,\n           box_a_corners[k].x, box_a_corners[k].y, box_b_corners[k].x,\n           box_b_corners[k].y);\n#endif\n    rotate_around_center(center_a, a_angle_cos, a_angle_sin, box_a_corners[k]);\n    rotate_around_center(center_b, b_angle_cos, b_angle_sin, box_b_corners[k]);\n#ifdef DEBUG\n    printf(\"corner %d: a(%.3f, %.3f), b(%.3f, %.3f) \\n\", k, box_a_corners[k].x,\n           box_a_corners[k].y, box_b_corners[k].x, box_b_corners[k].y);\n#endif\n  }\n\n  box_a_corners[4] = box_a_corners[0];\n  box_b_corners[4] = box_b_corners[0];\n\n  // get intersection of lines\n  Point cross_points[16];\n  Point poly_center;\n  int cnt = 0, flag = 0;\n\n  poly_center.set(0, 0);\n  for (int i = 0; i < 4; i++) {\n    for (int j = 0; j < 4; j++) {\n      flag = intersection(box_a_corners[i + 1], box_a_corners[i],\n                          box_b_corners[j + 1], box_b_corners[j],\n                          cross_points[cnt]);\n      if (flag) {\n        poly_center = poly_center + cross_points[cnt];\n        cnt++;\n      }\n    }\n  }\n\n  // check corners\n  for (int k = 0; k < 4; k++) {\n    if (check_in_box2d(box_a, box_b_corners[k])) {\n      poly_center = poly_center + box_b_corners[k];\n      cross_points[cnt] = box_b_corners[k];\n      cnt++;\n    }\n    if (check_in_box2d(box_b, box_a_corners[k])) {\n      poly_center = poly_center + box_a_corners[k];\n      cross_points[cnt] = box_a_corners[k];\n      cnt++;\n    }\n  }\n\n  poly_center.x /= cnt;\n  poly_center.y /= cnt;\n\n  // sort the points of polygon\n  Point temp;\n  for (int j = 0; j < cnt - 1; j++) {\n    for (int i = 0; i < cnt - j - 1; i++) {\n      if (point_cmp(cross_points[i], cross_points[i + 1], poly_center)) {\n        temp = cross_points[i];\n        cross_points[i] = cross_points[i + 1];\n        cross_points[i + 1] = temp;\n      }\n    }\n  }\n\n#ifdef DEBUG\n  printf(\"cnt=%d\\n\", cnt);\n  for (int i = 0; i < cnt; i++) {\n    printf(\"All cross point %d: (%.3f, %.3f)\\n\", i, cross_points[i].x,\n           cross_points[i].y);\n  }\n#endif\n\n  // get the overlap areas\n  float area = 0;\n  for (int k = 0; k < cnt - 1; k++) {\n    area += cross(cross_points[k] - cross_points[0],\n                  cross_points[k + 1] - cross_points[0]);\n  }\n\n  return fabs(area) / 2.0;\n}\n\n__device__ inline float iou_bev(const float *box_a, const float *box_b) {\n  // params: box_a (5) [x1, y1, x2, y2, angle]\n  // params: box_b (5) [x1, y1, x2, y2, angle]\n  float sa = (box_a[2] - box_a[0]) * (box_a[3] - box_a[1]);\n  float sb = (box_b[2] - box_b[0]) * (box_b[3] - box_b[1]);\n  float s_overlap = box_overlap(box_a, box_b);\n  return s_overlap / fmaxf(sa + sb - s_overlap, EPS);\n}\n\n__global__ void boxes_overlap_kernel(const int num_a, const float *boxes_a,\n                                     const int num_b, const float *boxes_b,\n                                     float *ans_overlap) {\n  const int a_idx = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y;\n  const int b_idx = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x;\n\n  if (a_idx >= num_a || b_idx >= num_b) {\n    return;\n  }\n  const float *cur_box_a = boxes_a + a_idx * 5;\n  const float *cur_box_b = boxes_b + b_idx * 5;\n  float s_overlap = box_overlap(cur_box_a, cur_box_b);\n  ans_overlap[a_idx * num_b + b_idx] = s_overlap;\n}\n\n__global__ void boxes_iou_bev_kernel(const int num_a, const float *boxes_a,\n                                     const int num_b, const float *boxes_b,\n                                     float *ans_iou) {\n  const int a_idx = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y;\n  const int b_idx = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x;\n\n  if (a_idx >= num_a || b_idx >= num_b) {\n    return;\n  }\n\n  const float *cur_box_a = boxes_a + a_idx * 5;\n  const float *cur_box_b = boxes_b + b_idx * 5;\n  float cur_iou_bev = iou_bev(cur_box_a, cur_box_b);\n  ans_iou[a_idx * num_b + b_idx] = cur_iou_bev;\n}\n\n__global__ void nms_kernel(const int boxes_num, const float nms_overlap_thresh,\n                           const float *boxes, unsigned long long *mask) {\n  // params: boxes (N, 5) [x1, y1, x2, y2, ry]\n  // params: mask (N, N/THREADS_PER_BLOCK_NMS)\n\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n\n  // if (row_start > col_start) return;\n\n  const int row_size = fminf(boxes_num - row_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n  const int col_size = fminf(boxes_num - col_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n\n  __shared__ float block_boxes[THREADS_PER_BLOCK_NMS * 5];\n\n  if (threadIdx.x < col_size) {\n    block_boxes[threadIdx.x * 5 + 0] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 0];\n    block_boxes[threadIdx.x * 5 + 1] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 1];\n    block_boxes[threadIdx.x * 5 + 2] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 2];\n    block_boxes[threadIdx.x * 5 + 3] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 3];\n    block_boxes[threadIdx.x * 5 + 4] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size) {\n    const int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x;\n    const float *cur_box = boxes + cur_box_idx * 5;\n\n    int i = 0;\n    unsigned long long t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = threadIdx.x + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      if (iou_bev(cur_box, block_boxes + i * 5) > nms_overlap_thresh) {\n        t |= 1ULL << i;\n      }\n    }\n    const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n    mask[cur_box_idx * col_blocks + col_start] = t;\n  }\n}\n\n__device__ inline float iou_normal(float const *const a, float const *const b) {\n  float left = fmaxf(a[0], b[0]), right = fminf(a[2], b[2]);\n  float top = fmaxf(a[1], b[1]), bottom = fminf(a[3], b[3]);\n  float width = fmaxf(right - left, 0.f), height = fmaxf(bottom - top, 0.f);\n  float interS = width * height;\n  float Sa = (a[2] - a[0]) * (a[3] - a[1]);\n  float Sb = (b[2] - b[0]) * (b[3] - b[1]);\n  return interS / fmaxf(Sa + Sb - interS, EPS);\n}\n\n__global__ void nms_normal_kernel(const int boxes_num,\n                                  const float nms_overlap_thresh,\n                                  const float *boxes,\n                                  unsigned long long *mask) {\n  // params: boxes (N, 5) [x1, y1, x2, y2, ry]\n  // params: mask (N, N/THREADS_PER_BLOCK_NMS)\n\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n\n  // if (row_start > col_start) return;\n\n  const int row_size = fminf(boxes_num - row_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n  const int col_size = fminf(boxes_num - col_start * THREADS_PER_BLOCK_NMS,\n                             THREADS_PER_BLOCK_NMS);\n\n  __shared__ float block_boxes[THREADS_PER_BLOCK_NMS * 5];\n\n  if (threadIdx.x < col_size) {\n    block_boxes[threadIdx.x * 5 + 0] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 0];\n    block_boxes[threadIdx.x * 5 + 1] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 1];\n    block_boxes[threadIdx.x * 5 + 2] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 2];\n    block_boxes[threadIdx.x * 5 + 3] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 3];\n    block_boxes[threadIdx.x * 5 + 4] =\n        boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size) {\n    const int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x;\n    const float *cur_box = boxes + cur_box_idx * 5;\n\n    int i = 0;\n    unsigned long long t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = threadIdx.x + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      if (iou_normal(cur_box, block_boxes + i * 5) > nms_overlap_thresh) {\n        t |= 1ULL << i;\n      }\n    }\n    const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);\n    mask[cur_box_idx * col_blocks + col_start] = t;\n  }\n}\n\nvoid boxesoverlapLauncher(const int num_a, const float *boxes_a,\n                          const int num_b, const float *boxes_b,\n                          float *ans_overlap) {\n  dim3 blocks(\n      DIVUP(num_b, THREADS_PER_BLOCK),\n      DIVUP(num_a, THREADS_PER_BLOCK));  // blockIdx.x(col), blockIdx.y(row)\n  dim3 threads(THREADS_PER_BLOCK, THREADS_PER_BLOCK);\n\n  boxes_overlap_kernel<<<blocks, threads>>>(num_a, boxes_a, num_b, boxes_b,\n                                            ans_overlap);\n#ifdef DEBUG\n  cudaDeviceSynchronize();  // for using printf in kernel function\n#endif\n}\n\nvoid boxesioubevLauncher(const int num_a, const float *boxes_a, const int num_b,\n                         const float *boxes_b, float *ans_iou) {\n  dim3 blocks(\n      DIVUP(num_b, THREADS_PER_BLOCK),\n      DIVUP(num_a, THREADS_PER_BLOCK));  // blockIdx.x(col), blockIdx.y(row)\n  dim3 threads(THREADS_PER_BLOCK, THREADS_PER_BLOCK);\n\n  boxes_iou_bev_kernel<<<blocks, threads>>>(num_a, boxes_a, num_b, boxes_b,\n                                            ans_iou);\n}\n\nvoid nmsLauncher(const float *boxes, unsigned long long *mask, int boxes_num,\n                 float nms_overlap_thresh) {\n  dim3 blocks(DIVUP(boxes_num, THREADS_PER_BLOCK_NMS),\n              DIVUP(boxes_num, THREADS_PER_BLOCK_NMS));\n  dim3 threads(THREADS_PER_BLOCK_NMS);\n  nms_kernel<<<blocks, threads>>>(boxes_num, nms_overlap_thresh, boxes, mask);\n}\n\nvoid nmsNormalLauncher(const float *boxes, unsigned long long *mask,\n                       int boxes_num, float nms_overlap_thresh) {\n  dim3 blocks(DIVUP(boxes_num, THREADS_PER_BLOCK_NMS),\n              DIVUP(boxes_num, THREADS_PER_BLOCK_NMS));\n  dim3 threads(THREADS_PER_BLOCK_NMS);\n  nms_normal_kernel<<<blocks, threads>>>(boxes_num, nms_overlap_thresh, boxes,\n                                         mask);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/masked_conv.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport math\n\nimport torch\nimport torch.nn as nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair\n\nfrom ..utils import ext_loader\n\next_module = ext_loader.load_ext(\n    '_ext', ['masked_im2col_forward', 'masked_col2im_forward'])\n\n\nclass MaskedConv2dFunction(Function):\n\n    @staticmethod\n    def symbolic(g, features, mask, weight, bias, padding, stride):\n        return g.op(\n            'mmcv::MMCVMaskedConv2d',\n            features,\n            mask,\n            weight,\n            bias,\n            padding_i=padding,\n            stride_i=stride)\n\n    @staticmethod\n    def forward(ctx, features, mask, weight, bias, padding=0, stride=1):\n        assert mask.dim() == 3 and mask.size(0) == 1\n        assert features.dim() == 4 and features.size(0) == 1\n        assert features.size()[2:] == mask.size()[1:]\n        pad_h, pad_w = _pair(padding)\n        stride_h, stride_w = _pair(stride)\n        if stride_h != 1 or stride_w != 1:\n            raise ValueError(\n                'Stride could not only be 1 in masked_conv2d currently.')\n        out_channel, in_channel, kernel_h, kernel_w = weight.size()\n\n        batch_size = features.size(0)\n        out_h = int(\n            math.floor((features.size(2) + 2 * pad_h -\n                        (kernel_h - 1) - 1) / stride_h + 1))\n        out_w = int(\n            math.floor((features.size(3) + 2 * pad_w -\n                        (kernel_h - 1) - 1) / stride_w + 1))\n        mask_inds = torch.nonzero(mask[0] > 0, as_tuple=False)\n        output = features.new_zeros(batch_size, out_channel, out_h, out_w)\n        if mask_inds.numel() > 0:\n            mask_h_idx = mask_inds[:, 0].contiguous()\n            mask_w_idx = mask_inds[:, 1].contiguous()\n            data_col = features.new_zeros(in_channel * kernel_h * kernel_w,\n                                          mask_inds.size(0))\n            ext_module.masked_im2col_forward(\n                features,\n                mask_h_idx,\n                mask_w_idx,\n                data_col,\n                kernel_h=kernel_h,\n                kernel_w=kernel_w,\n                pad_h=pad_h,\n                pad_w=pad_w)\n\n            masked_output = torch.addmm(1, bias[:, None], 1,\n                                        weight.view(out_channel, -1), data_col)\n            ext_module.masked_col2im_forward(\n                masked_output,\n                mask_h_idx,\n                mask_w_idx,\n                output,\n                height=out_h,\n                width=out_w,\n                channels=out_channel)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        return (None, ) * 5\n\n\nmasked_conv2d = MaskedConv2dFunction.apply\n\n\nclass MaskedConv2d(nn.Conv2d):\n    \"\"\"A MaskedConv2d which inherits the official Conv2d.\n\n    The masked forward doesn't implement the backward function and only\n    supports the stride parameter to be 1 currently.\n    \"\"\"\n\n    def __init__(self,\n                 in_channels,\n                 out_channels,\n                 kernel_size,\n                 stride=1,\n                 padding=0,\n                 dilation=1,\n                 groups=1,\n                 bias=True):\n        super(MaskedConv2d,\n              self).__init__(in_channels, out_channels, kernel_size, stride,\n                             padding, dilation, groups, bias)\n\n    def forward(self, input, mask=None):\n        if mask is None:  # fallback to the normal Conv2d\n            return super(MaskedConv2d, self).forward(input)\n        else:\n            return masked_conv2d(input, mask, self.weight, self.bias,\n                                 self.padding)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/modulated_deform_conv.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport math\n\nimport torch\nimport torch.nn as nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair, _single\n\nfrom mmcv.utils import deprecated_api_warning\nfrom ..models import CONV_LAYERS\nfrom ..utils import ext_loader, print_log\n\next_module = ext_loader.load_ext(\n    '_ext',\n    ['modulated_deform_conv_forward', 'modulated_deform_conv_backward'])\n\n\nclass ModulatedDeformConv2dFunction(Function):\n\n    @staticmethod\n    def symbolic(g, input, offset, mask, weight, bias, stride, padding,\n                 dilation, groups, deform_groups):\n        input_tensors = [input, offset, mask, weight]\n        if bias is not None:\n            input_tensors.append(bias)\n        return g.op(\n            'mmcv::MMCVModulatedDeformConv2d',\n            *input_tensors,\n            stride_i=stride,\n            padding_i=padding,\n            dilation_i=dilation,\n            groups_i=groups,\n            deform_groups_i=deform_groups)\n\n    @staticmethod\n    def forward(ctx,\n                input,\n                offset,\n                mask,\n                weight,\n                bias=None,\n                stride=1,\n                padding=0,\n                dilation=1,\n                groups=1,\n                deform_groups=1):\n        if input is not None and input.dim() != 4:\n            raise ValueError(\n                f'Expected 4D tensor as input, got {input.dim()}D tensor \\\n                  instead.')\n        ctx.stride = _pair(stride)\n        ctx.padding = _pair(padding)\n        ctx.dilation = _pair(dilation)\n        ctx.groups = groups\n        ctx.deform_groups = deform_groups\n        ctx.with_bias = bias is not None\n        if not ctx.with_bias:\n            bias = input.new_empty(0)  # fake tensor\n        # When pytorch version >= 1.6.0, amp is adopted for fp16 mode;\n        # amp won't cast the type of model (float32), but \"offset\" is cast\n        # to float16 by nn.Conv2d automatically, leading to the type\n        # mismatch with input (when it is float32) or weight.\n        # The flag for whether to use fp16 or amp is the type of \"offset\",\n        # we cast weight and input to temporarily support fp16 and amp\n        # whatever the pytorch version is.\n        input = input.type_as(offset)\n        weight = weight.type_as(input)\n        ctx.save_for_backward(input, offset, mask, weight, bias)\n        output = input.new_empty(\n            ModulatedDeformConv2dFunction._output_size(ctx, input, weight))\n        ctx._bufs = [input.new_empty(0), input.new_empty(0)]\n        ext_module.modulated_deform_conv_forward(\n            input,\n            weight,\n            bias,\n            ctx._bufs[0],\n            offset,\n            mask,\n            output,\n            ctx._bufs[1],\n            kernel_h=weight.size(2),\n            kernel_w=weight.size(3),\n            stride_h=ctx.stride[0],\n            stride_w=ctx.stride[1],\n            pad_h=ctx.padding[0],\n            pad_w=ctx.padding[1],\n            dilation_h=ctx.dilation[0],\n            dilation_w=ctx.dilation[1],\n            group=ctx.groups,\n            deformable_group=ctx.deform_groups,\n            with_bias=ctx.with_bias)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        input, offset, mask, weight, bias = ctx.saved_tensors\n        grad_input = torch.zeros_like(input)\n        grad_offset = torch.zeros_like(offset)\n        grad_mask = torch.zeros_like(mask)\n        grad_weight = torch.zeros_like(weight)\n        grad_bias = torch.zeros_like(bias)\n        grad_output = grad_output.contiguous()\n        ext_module.modulated_deform_conv_backward(\n            input,\n            weight,\n            bias,\n            ctx._bufs[0],\n            offset,\n            mask,\n            ctx._bufs[1],\n            grad_input,\n            grad_weight,\n            grad_bias,\n            grad_offset,\n            grad_mask,\n            grad_output,\n            kernel_h=weight.size(2),\n            kernel_w=weight.size(3),\n            stride_h=ctx.stride[0],\n            stride_w=ctx.stride[1],\n            pad_h=ctx.padding[0],\n            pad_w=ctx.padding[1],\n            dilation_h=ctx.dilation[0],\n            dilation_w=ctx.dilation[1],\n            group=ctx.groups,\n            deformable_group=ctx.deform_groups,\n            with_bias=ctx.with_bias)\n        if not ctx.with_bias:\n            grad_bias = None\n\n        return (grad_input, grad_offset, grad_mask, grad_weight, grad_bias,\n                None, None, None, None, None)\n\n    @staticmethod\n    def _output_size(ctx, input, weight):\n        channels = weight.size(0)\n        output_size = (input.size(0), channels)\n        for d in range(input.dim() - 2):\n            in_size = input.size(d + 2)\n            pad = ctx.padding[d]\n            kernel = ctx.dilation[d] * (weight.size(d + 2) - 1) + 1\n            stride_ = ctx.stride[d]\n            output_size += ((in_size + (2 * pad) - kernel) // stride_ + 1, )\n        if not all(map(lambda s: s > 0, output_size)):\n            raise ValueError(\n                'convolution input is too small (output would be ' +\n                'x'.join(map(str, output_size)) + ')')\n        return output_size\n\n\nmodulated_deform_conv2d = ModulatedDeformConv2dFunction.apply\n\n\nclass ModulatedDeformConv2d(nn.Module):\n\n    @deprecated_api_warning({'deformable_groups': 'deform_groups'},\n                            cls_name='ModulatedDeformConv2d')\n    def __init__(self,\n                 in_channels,\n                 out_channels,\n                 kernel_size,\n                 stride=1,\n                 padding=0,\n                 dilation=1,\n                 groups=1,\n                 deform_groups=1,\n                 bias=True):\n        super(ModulatedDeformConv2d, self).__init__()\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.stride = _pair(stride)\n        self.padding = _pair(padding)\n        self.dilation = _pair(dilation)\n        self.groups = groups\n        self.deform_groups = deform_groups\n        # enable compatibility with nn.Conv2d\n        self.transposed = False\n        self.output_padding = _single(0)\n\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // groups,\n                         *self.kernel_size))\n        if bias:\n            self.bias = nn.Parameter(torch.Tensor(out_channels))\n        else:\n            self.register_parameter('bias', None)\n        self.init_weights()\n\n    def init_weights(self):\n        n = self.in_channels\n        for k in self.kernel_size:\n            n *= k\n        stdv = 1. / math.sqrt(n)\n        self.weight.data.uniform_(-stdv, stdv)\n        if self.bias is not None:\n            self.bias.data.zero_()\n\n    def forward(self, x, offset, mask):\n        return modulated_deform_conv2d(x, offset, mask, self.weight, self.bias,\n                                       self.stride, self.padding,\n                                       self.dilation, self.groups,\n                                       self.deform_groups)\n\n\n@CONV_LAYERS.register_module('DCNv2')\nclass ModulatedDeformConv2dPack(ModulatedDeformConv2d):\n    \"\"\"A ModulatedDeformable Conv Encapsulation that acts as normal Conv\n    layers.\n\n    Args:\n        in_channels (int): Same as nn.Conv2d.\n        out_channels (int): Same as nn.Conv2d.\n        kernel_size (int or tuple[int]): Same as nn.Conv2d.\n        stride (int): Same as nn.Conv2d, while tuple is not supported.\n        padding (int): Same as nn.Conv2d, while tuple is not supported.\n        dilation (int): Same as nn.Conv2d, while tuple is not supported.\n        groups (int): Same as nn.Conv2d.\n        bias (bool or str): If specified as `auto`, it will be decided by the\n            norm_cfg. Bias will be set as True if norm_cfg is None, otherwise\n            False.\n    \"\"\"\n\n    _version = 2\n\n    def __init__(self, *args, **kwargs):\n        super(ModulatedDeformConv2dPack, self).__init__(*args, **kwargs)\n        self.conv_offset = nn.Conv2d(\n            self.in_channels,\n            self.deform_groups * 3 * self.kernel_size[0] * self.kernel_size[1],\n            kernel_size=self.kernel_size,\n            stride=self.stride,\n            padding=self.padding,\n            dilation=self.dilation,\n            bias=True)\n        self.init_weights()\n\n    def init_weights(self):\n        super(ModulatedDeformConv2dPack, self).init_weights()\n        if hasattr(self, 'conv_offset'):\n            self.conv_offset.weight.data.zero_()\n            self.conv_offset.bias.data.zero_()\n\n    def forward(self, x):\n        out = self.conv_offset(x)\n        o1, o2, mask = torch.chunk(out, 3, dim=1)\n        offset = torch.cat((o1, o2), dim=1)\n        mask = torch.sigmoid(mask)\n        return modulated_deform_conv2d(x, offset, mask, self.weight, self.bias,\n                                       self.stride, self.padding,\n                                       self.dilation, self.groups,\n                                       self.deform_groups)\n\n    def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,\n                              missing_keys, unexpected_keys, error_msgs):\n        version = local_metadata.get('version', None)\n\n        if version is None or version < 2:\n            # the key is different in early versions\n            # In version < 2, ModulatedDeformConvPack\n            # loads previous benchmark models.\n            if (prefix + 'conv_offset.weight' not in state_dict\n                    and prefix[:-1] + '_offset.weight' in state_dict):\n                state_dict[prefix + 'conv_offset.weight'] = state_dict.pop(\n                    prefix[:-1] + '_offset.weight')\n            if (prefix + 'conv_offset.bias' not in state_dict\n                    and prefix[:-1] + '_offset.bias' in state_dict):\n                state_dict[prefix +\n                           'conv_offset.bias'] = state_dict.pop(prefix[:-1] +\n                                                                '_offset.bias')\n\n        if version is not None and version > 1:\n            print_log(\n                f'ModulatedDeformConvPack {prefix.rstrip(\".\")} is upgraded to '\n                'version 2.',\n                logger='root')\n\n        super()._load_from_state_dict(state_dict, prefix, local_metadata,\n                                      strict, missing_keys, unexpected_keys,\n                                      error_msgs)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/multi_scale_deform_attn.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport math\nimport warnings\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom torch.autograd.function import Function, once_differentiable\n\nfrom mmcv import deprecated_api_warning\nfrom mmcv.models.utils.weight_init import constant_init, xavier_init\nfrom mmcv.models.bricks.registry import ATTENTION\nfrom mmcv.models.backbones.base_module import BaseModule\nfrom ..utils import ext_loader\n\next_module = ext_loader.load_ext(\n    '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward'])\n\n\nclass MultiScaleDeformableAttnFunction(Function):\n\n    @staticmethod\n    def forward(ctx, value, value_spatial_shapes, value_level_start_index,\n                sampling_locations, attention_weights, im2col_step):\n        \"\"\"GPU version of multi-scale deformable attention.\n\n        Args:\n            value (Tensor): The value has shape\n                (bs, num_keys, mum_heads, embed_dims//num_heads)\n            value_spatial_shapes (Tensor): Spatial shape of\n                each feature map, has shape (num_levels, 2),\n                last dimension 2 represent (h, w)\n            sampling_locations (Tensor): The location of sampling points,\n                has shape\n                (bs ,num_queries, num_heads, num_levels, num_points, 2),\n                the last dimension 2 represent (x, y).\n            attention_weights (Tensor): The weight of sampling points used\n                when calculate the attention, has shape\n                (bs ,num_queries, num_heads, num_levels, num_points),\n            im2col_step (Tensor): The step used in image to column.\n\n        Returns:\n            Tensor: has shape (bs, num_queries, embed_dims)\n        \"\"\"\n\n        ctx.im2col_step = im2col_step\n        output = ext_module.ms_deform_attn_forward(\n            value,\n            value_spatial_shapes,\n            value_level_start_index,\n            sampling_locations,\n            attention_weights,\n            im2col_step=ctx.im2col_step)\n        ctx.save_for_backward(value, value_spatial_shapes,\n                              value_level_start_index, sampling_locations,\n                              attention_weights)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        \"\"\"GPU version of backward function.\n\n        Args:\n            grad_output (Tensor): Gradient\n                of output tensor of forward.\n\n        Returns:\n             Tuple[Tensor]: Gradient\n                of input tensors in forward.\n        \"\"\"\n        value, value_spatial_shapes, value_level_start_index,\\\n            sampling_locations, attention_weights = ctx.saved_tensors\n        grad_value = torch.zeros_like(value)\n        grad_sampling_loc = torch.zeros_like(sampling_locations)\n        grad_attn_weight = torch.zeros_like(attention_weights)\n\n        ext_module.ms_deform_attn_backward(\n            value,\n            value_spatial_shapes,\n            value_level_start_index,\n            sampling_locations,\n            attention_weights,\n            grad_output.contiguous(),\n            grad_value,\n            grad_sampling_loc,\n            grad_attn_weight,\n            im2col_step=ctx.im2col_step)\n\n        return grad_value, None, None, \\\n            grad_sampling_loc, grad_attn_weight, None\n\n\ndef multi_scale_deformable_attn_pytorch(value, value_spatial_shapes,\n                                        sampling_locations, attention_weights):\n    \"\"\"CPU version of multi-scale deformable attention.\n\n    Args:\n        value (Tensor): The value has shape\n            (bs, num_keys, mum_heads, embed_dims//num_heads)\n        value_spatial_shapes (Tensor): Spatial shape of\n            each feature map, has shape (num_levels, 2),\n            last dimension 2 represent (h, w)\n        sampling_locations (Tensor): The location of sampling points,\n            has shape\n            (bs ,num_queries, num_heads, num_levels, num_points, 2),\n            the last dimension 2 represent (x, y).\n        attention_weights (Tensor): The weight of sampling points used\n            when calculate the attention, has shape\n            (bs ,num_queries, num_heads, num_levels, num_points),\n\n    Returns:\n        Tensor: has shape (bs, num_queries, embed_dims)\n    \"\"\"\n\n    bs, _, num_heads, embed_dims = value.shape\n    _, num_queries, num_heads, num_levels, num_points, _ =\\\n        sampling_locations.shape\n    value_list = value.split([H_ * W_ for H_, W_ in value_spatial_shapes],\n                             dim=1)\n    sampling_grids = 2 * sampling_locations - 1\n    sampling_value_list = []\n    for level, (H_, W_) in enumerate(value_spatial_shapes):\n        # bs, H_*W_, num_heads, embed_dims ->\n        # bs, H_*W_, num_heads*embed_dims ->\n        # bs, num_heads*embed_dims, H_*W_ ->\n        # bs*num_heads, embed_dims, H_, W_\n        value_l_ = value_list[level].flatten(2).transpose(1, 2).reshape(\n            bs * num_heads, embed_dims, H_, W_)\n        # bs, num_queries, num_heads, num_points, 2 ->\n        # bs, num_heads, num_queries, num_points, 2 ->\n        # bs*num_heads, num_queries, num_points, 2\n        sampling_grid_l_ = sampling_grids[:, :, :,\n                                          level].transpose(1, 2).flatten(0, 1)\n        # bs*num_heads, embed_dims, num_queries, num_points\n        sampling_value_l_ = F.grid_sample(\n            value_l_,\n            sampling_grid_l_,\n            mode='bilinear',\n            padding_mode='zeros',\n            align_corners=False)\n        sampling_value_list.append(sampling_value_l_)\n    # (bs, num_queries, num_heads, num_levels, num_points) ->\n    # (bs, num_heads, num_queries, num_levels, num_points) ->\n    # (bs, num_heads, 1, num_queries, num_levels*num_points)\n    attention_weights = attention_weights.transpose(1, 2).reshape(\n        bs * num_heads, 1, num_queries, num_levels * num_points)\n    output = (torch.stack(sampling_value_list, dim=-2).flatten(-2) *\n              attention_weights).sum(-1).view(bs, num_heads * embed_dims,\n                                              num_queries)\n    return output.transpose(1, 2).contiguous()\n\n\n@ATTENTION.register_module()\nclass MultiScaleDeformableAttention(BaseModule):\n    \"\"\"An attention module used in Deformable-Detr.\n\n    `Deformable DETR: Deformable Transformers for End-to-End Object Detection.\n    <https://arxiv.org/pdf/2010.04159.pdf>`_.\n\n    Args:\n        embed_dims (int): The embedding dimension of Attention.\n            Default: 256.\n        num_heads (int): Parallel attention heads. Default: 64.\n        num_levels (int): The number of feature map used in\n            Attention. Default: 4.\n        num_points (int): The number of sampling points for\n            each query in each head. Default: 4.\n        im2col_step (int): The step used in image_to_column.\n            Default: 64.\n        dropout (float): A Dropout layer on `inp_identity`.\n            Default: 0.1.\n        batch_first (bool): Key, Query and Value are shape of\n            (batch, n, embed_dim)\n            or (n, batch, embed_dim). Default to False.\n        norm_cfg (dict): Config dict for normalization layer.\n            Default: None.\n        init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims=256,\n                 num_heads=8,\n                 num_levels=4,\n                 num_points=4,\n                 im2col_step=64,\n                 dropout=0.1,\n                 batch_first=False,\n                 norm_cfg=None,\n                 init_cfg=None):\n        super().__init__(init_cfg)\n        if embed_dims % num_heads != 0:\n            raise ValueError(f'embed_dims must be divisible by num_heads, '\n                             f'but got {embed_dims} and {num_heads}')\n        dim_per_head = embed_dims // num_heads\n        self.norm_cfg = norm_cfg\n        self.dropout = nn.Dropout(dropout)\n        self.batch_first = batch_first\n\n        # you'd better set dim_per_head to a power of 2\n        # which is more efficient in the CUDA implementation\n        def _is_power_of_2(n):\n            if (not isinstance(n, int)) or (n < 0):\n                raise ValueError(\n                    'invalid input for _is_power_of_2: {} (type: {})'.format(\n                        n, type(n)))\n            return (n & (n - 1) == 0) and n != 0\n\n        if not _is_power_of_2(dim_per_head):\n            warnings.warn(\n                \"You'd better set embed_dims in \"\n                'MultiScaleDeformAttention to make '\n                'the dimension of each attention head a power of 2 '\n                'which is more efficient in our CUDA implementation.')\n\n        self.im2col_step = im2col_step\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_heads = num_heads\n        self.num_points = num_points\n        self.sampling_offsets = nn.Linear(\n            embed_dims, num_heads * num_levels * num_points * 2)\n        self.attention_weights = nn.Linear(embed_dims,\n                                           num_heads * num_levels * num_points)\n        self.value_proj = nn.Linear(embed_dims, embed_dims)\n        self.output_proj = nn.Linear(embed_dims, embed_dims)\n        self.init_weights()\n\n    def init_weights(self):\n        \"\"\"Default initialization for Parameters of Module.\"\"\"\n        constant_init(self.sampling_offsets, 0.)\n        thetas = torch.arange(\n            self.num_heads,\n            dtype=torch.float32) * (2.0 * math.pi / self.num_heads)\n        grid_init = torch.stack([thetas.cos(), thetas.sin()], -1)\n        grid_init = (grid_init /\n                     grid_init.abs().max(-1, keepdim=True)[0]).view(\n                         self.num_heads, 1, 1,\n                         2).repeat(1, self.num_levels, self.num_points, 1)\n        for i in range(self.num_points):\n            grid_init[:, :, i, :] *= i + 1\n\n        self.sampling_offsets.bias.data = grid_init.view(-1)\n        constant_init(self.attention_weights, val=0., bias=0.)\n        xavier_init(self.value_proj, distribution='uniform', bias=0.)\n        xavier_init(self.output_proj, distribution='uniform', bias=0.)\n        self._is_init = True\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiScaleDeformableAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_padding_mask=None,\n                reference_points=None,\n                spatial_shapes=None,\n                level_start_index=None,\n                **kwargs):\n        \"\"\"Forward Function of MultiScaleDeformAttention.\n\n        Args:\n            query (Tensor): Query of Transformer with shape\n                (num_query, bs, embed_dims).\n            key (Tensor): The key tensor with shape\n                `(num_key, bs, embed_dims)`.\n            value (Tensor): The value tensor with shape\n                `(num_key, bs, embed_dims)`.\n            identity (Tensor): The tensor used for addition, with the\n                same shape as `query`. Default None. If None,\n                `query` will be used.\n            query_pos (Tensor): The positional encoding for `query`.\n                Default: None.\n            key_pos (Tensor): The positional encoding for `key`. Default\n                None.\n            reference_points (Tensor):  The normalized reference\n                points with shape (bs, num_query, num_levels, 2),\n                all elements is range in [0, 1], top-left (0,0),\n                bottom-right (1, 1), including padding area.\n                or (N, Length_{query}, num_levels, 4), add\n                additional two dimensions is (w, h) to\n                form reference boxes.\n            key_padding_mask (Tensor): ByteTensor for `query`, with\n                shape [bs, num_key].\n            spatial_shapes (Tensor): Spatial shape of features in\n                different levels. With shape (num_levels, 2),\n                last dimension represents (h, w).\n            level_start_index (Tensor): The start index of each level.\n                A tensor has shape ``(num_levels, )`` and can be represented\n                as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...].\n\n        Returns:\n             Tensor: forwarded results with shape [num_query, bs, embed_dims].\n        \"\"\"\n\n        if value is None:\n            value = query\n\n        if identity is None:\n            identity = query\n        if query_pos is not None:\n            query = query + query_pos\n        if not self.batch_first:\n            # change to (bs, num_query ,embed_dims)\n            query = query.permute(1, 0, 2)\n            value = value.permute(1, 0, 2)\n\n        bs, num_query, _ = query.shape\n        bs, num_value, _ = value.shape\n        assert (spatial_shapes[:, 0] * spatial_shapes[:, 1]).sum() == num_value\n\n        value = self.value_proj(value)\n        if key_padding_mask is not None:\n            value = value.masked_fill(key_padding_mask[..., None], 0.0)\n        value = value.view(bs, num_value, self.num_heads, -1)\n        sampling_offsets = self.sampling_offsets(query).view(\n            bs, num_query, self.num_heads, self.num_levels, self.num_points, 2)\n        attention_weights = self.attention_weights(query).view(\n            bs, num_query, self.num_heads, self.num_levels * self.num_points)\n        attention_weights = attention_weights.softmax(-1)\n\n        attention_weights = attention_weights.view(bs, num_query,\n                                                   self.num_heads,\n                                                   self.num_levels,\n                                                   self.num_points)\n        if reference_points.shape[-1] == 2:\n            offset_normalizer = torch.stack(\n                [spatial_shapes[..., 1], spatial_shapes[..., 0]], -1)\n            sampling_locations = reference_points[:, :, None, :, None, :] \\\n                + sampling_offsets \\\n                / offset_normalizer[None, None, None, :, None, :]\n        elif reference_points.shape[-1] == 4:\n            sampling_locations = reference_points[:, :, None, :, None, :2] \\\n                + sampling_offsets / self.num_points \\\n                * reference_points[:, :, None, :, None, 2:] \\\n                * 0.5\n        else:\n            raise ValueError(\n                f'Last dim of reference_points must be'\n                f' 2 or 4, but get {reference_points.shape[-1]} instead.')\n        if torch.cuda.is_available() and value.is_cuda:\n            output = MultiScaleDeformableAttnFunction.apply(\n                value, spatial_shapes, level_start_index, sampling_locations,\n                attention_weights, self.im2col_step)\n        else:\n            output = multi_scale_deformable_attn_pytorch(\n                value, spatial_shapes, sampling_locations, attention_weights)\n\n        output = self.output_proj(output)\n\n        if not self.batch_first:\n            # (num_query, bs ,embed_dims)\n            output = output.permute(1, 0, 2)\n\n        return self.dropout(output) + identity\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/nms.py",
    "content": "import os\n\nimport numpy as np\nimport torch\n\nfrom mmcv.utils import deprecated_api_warning\nfrom ..utils import ext_loader\n\next_module = ext_loader.load_ext(\n    '_ext', ['nms', 'softnms', 'nms_match', 'nms_rotated'])\n\n\n# This function is modified from: https://github.com/pytorch/vision/\nclass NMSop(torch.autograd.Function):\n\n    @staticmethod\n    def forward(ctx, bboxes, scores, iou_threshold, offset, score_threshold,\n                max_num):\n        is_filtering_by_score = score_threshold > 0\n        if is_filtering_by_score:\n            valid_mask = scores > score_threshold\n            bboxes, scores = bboxes[valid_mask], scores[valid_mask]\n            valid_inds = torch.nonzero(\n                valid_mask, as_tuple=False).squeeze(dim=1)\n\n        inds = ext_module.nms(\n            bboxes, scores, iou_threshold=float(iou_threshold), offset=offset)\n\n        if max_num > 0:\n            inds = inds[:max_num]\n        if is_filtering_by_score:\n            inds = valid_inds[inds]\n        return inds\n\n    @staticmethod\n    def symbolic(g, bboxes, scores, iou_threshold, offset, score_threshold,\n                 max_num):\n        from ..onnx import is_custom_op_loaded\n        has_custom_op = is_custom_op_loaded()\n        # TensorRT nms plugin is aligned with original nms in ONNXRuntime\n        is_trt_backend = os.environ.get('ONNX_BACKEND') == 'MMCVTensorRT'\n        if has_custom_op and (not is_trt_backend):\n            return g.op(\n                'mmcv::NonMaxSuppression',\n                bboxes,\n                scores,\n                iou_threshold_f=float(iou_threshold),\n                offset_i=int(offset))\n        else:\n            from torch.onnx.symbolic_opset9 import select, squeeze, unsqueeze\n            from ..onnx.onnx_utils.symbolic_helper import _size_helper\n\n            boxes = unsqueeze(g, bboxes, 0)\n            scores = unsqueeze(g, unsqueeze(g, scores, 0), 0)\n\n            if max_num > 0:\n                max_num = g.op(\n                    'Constant',\n                    value_t=torch.tensor(max_num, dtype=torch.long))\n            else:\n                dim = g.op('Constant', value_t=torch.tensor(0))\n                max_num = _size_helper(g, bboxes, dim)\n            max_output_per_class = max_num\n            iou_threshold = g.op(\n                'Constant',\n                value_t=torch.tensor([iou_threshold], dtype=torch.float))\n            score_threshold = g.op(\n                'Constant',\n                value_t=torch.tensor([score_threshold], dtype=torch.float))\n            nms_out = g.op('NonMaxSuppression', boxes, scores,\n                           max_output_per_class, iou_threshold,\n                           score_threshold)\n            return squeeze(\n                g,\n                select(\n                    g, nms_out, 1,\n                    g.op(\n                        'Constant',\n                        value_t=torch.tensor([2], dtype=torch.long))), 1)\n\n\nclass SoftNMSop(torch.autograd.Function):\n\n    @staticmethod\n    def forward(ctx, boxes, scores, iou_threshold, sigma, min_score, method,\n                offset):\n        dets = boxes.new_empty((boxes.size(0), 5), device='cpu')\n        inds = ext_module.softnms(\n            boxes.cpu(),\n            scores.cpu(),\n            dets.cpu(),\n            iou_threshold=float(iou_threshold),\n            sigma=float(sigma),\n            min_score=float(min_score),\n            method=int(method),\n            offset=int(offset))\n        return dets, inds\n\n    @staticmethod\n    def symbolic(g, boxes, scores, iou_threshold, sigma, min_score, method,\n                 offset):\n        from packaging import version\n        assert version.parse(torch.__version__) >= version.parse('1.7.0')\n        nms_out = g.op(\n            'mmcv::SoftNonMaxSuppression',\n            boxes,\n            scores,\n            iou_threshold_f=float(iou_threshold),\n            sigma_f=float(sigma),\n            min_score_f=float(min_score),\n            method_i=int(method),\n            offset_i=int(offset),\n            outputs=2)\n        return nms_out\n\n\n@deprecated_api_warning({'iou_thr': 'iou_threshold'})\ndef nms(boxes, scores, iou_threshold, offset=0, score_threshold=0, max_num=-1):\n    \"\"\"Dispatch to either CPU or GPU NMS implementations.\n\n    The input can be either torch tensor or numpy array. GPU NMS will be used\n    if the input is gpu tensor, otherwise CPU NMS\n    will be used. The returned type will always be the same as inputs.\n\n    Arguments:\n        boxes (torch.Tensor or np.ndarray): boxes in shape (N, 4).\n        scores (torch.Tensor or np.ndarray): scores in shape (N, ).\n        iou_threshold (float): IoU threshold for NMS.\n        offset (int, 0 or 1): boxes' width or height is (x2 - x1 + offset).\n        score_threshold (float): score threshold for NMS.\n        max_num (int): maximum number of boxes after NMS.\n\n    Returns:\n        tuple: kept dets(boxes and scores) and indice, which is always the \\\n            same data type as the input.\n\n    Example:\n        >>> boxes = np.array([[49.1, 32.4, 51.0, 35.9],\n        >>>                   [49.3, 32.9, 51.0, 35.3],\n        >>>                   [49.2, 31.8, 51.0, 35.4],\n        >>>                   [35.1, 11.5, 39.1, 15.7],\n        >>>                   [35.6, 11.8, 39.3, 14.2],\n        >>>                   [35.3, 11.5, 39.9, 14.5],\n        >>>                   [35.2, 11.7, 39.7, 15.7]], dtype=np.float32)\n        >>> scores = np.array([0.9, 0.9, 0.5, 0.5, 0.5, 0.4, 0.3],\\\n               dtype=np.float32)\n        >>> iou_threshold = 0.6\n        >>> dets, inds = nms(boxes, scores, iou_threshold)\n        >>> assert len(inds) == len(dets) == 3\n    \"\"\"\n    assert isinstance(boxes, (torch.Tensor, np.ndarray))\n    assert isinstance(scores, (torch.Tensor, np.ndarray))\n    is_numpy = False\n    if isinstance(boxes, np.ndarray):\n        is_numpy = True\n        boxes = torch.from_numpy(boxes)\n    if isinstance(scores, np.ndarray):\n        scores = torch.from_numpy(scores)\n    assert boxes.size(1) == 4\n    assert boxes.size(0) == scores.size(0)\n    assert offset in (0, 1)\n\n\n    inds = NMSop.apply(boxes, scores, iou_threshold, offset,\n                        score_threshold, max_num)\n    dets = torch.cat((boxes[inds], scores[inds].reshape(-1, 1)), dim=1)\n    if is_numpy:\n        dets = dets.cpu().numpy()\n        inds = inds.cpu().numpy()\n    return dets, inds\n\n\n@deprecated_api_warning({'iou_thr': 'iou_threshold'})\ndef soft_nms(boxes,\n             scores,\n             iou_threshold=0.3,\n             sigma=0.5,\n             min_score=1e-3,\n             method='linear',\n             offset=0):\n    \"\"\"Dispatch to only CPU Soft NMS implementations.\n\n    The input can be either a torch tensor or numpy array.\n    The returned type will always be the same as inputs.\n\n    Arguments:\n        boxes (torch.Tensor or np.ndarray): boxes in shape (N, 4).\n        scores (torch.Tensor or np.ndarray): scores in shape (N, ).\n        iou_threshold (float): IoU threshold for NMS.\n        sigma (float): hyperparameter for gaussian method\n        min_score (float): score filter threshold\n        method (str): either 'linear' or 'gaussian'\n        offset (int, 0 or 1): boxes' width or height is (x2 - x1 + offset).\n\n    Returns:\n        tuple: kept dets(boxes and scores) and indice, which is always the \\\n            same data type as the input.\n\n    Example:\n        >>> boxes = np.array([[4., 3., 5., 3.],\n        >>>                   [4., 3., 5., 4.],\n        >>>                   [3., 1., 3., 1.],\n        >>>                   [3., 1., 3., 1.],\n        >>>                   [3., 1., 3., 1.],\n        >>>                   [3., 1., 3., 1.]], dtype=np.float32)\n        >>> scores = np.array([0.9, 0.9, 0.5, 0.5, 0.4, 0.0], dtype=np.float32)\n        >>> iou_threshold = 0.6\n        >>> dets, inds = soft_nms(boxes, scores, iou_threshold, sigma=0.5)\n        >>> assert len(inds) == len(dets) == 5\n    \"\"\"\n\n    assert isinstance(boxes, (torch.Tensor, np.ndarray))\n    assert isinstance(scores, (torch.Tensor, np.ndarray))\n    is_numpy = False\n    if isinstance(boxes, np.ndarray):\n        is_numpy = True\n        boxes = torch.from_numpy(boxes)\n    if isinstance(scores, np.ndarray):\n        scores = torch.from_numpy(scores)\n    assert boxes.size(1) == 4\n    assert boxes.size(0) == scores.size(0)\n    assert offset in (0, 1)\n    method_dict = {'naive': 0, 'linear': 1, 'gaussian': 2}\n    assert method in method_dict.keys()\n\n\n    dets, inds = SoftNMSop.apply(boxes.cpu(), scores.cpu(),\n                                    float(iou_threshold), float(sigma),\n                                    float(min_score), method_dict[method],\n                                    int(offset))\n\n    dets = dets[:inds.size(0)]\n\n    if is_numpy:\n        dets = dets.cpu().numpy()\n        inds = inds.cpu().numpy()\n        return dets, inds\n    else:\n        return dets.to(device=boxes.device), inds.to(device=boxes.device)\n\n\ndef batched_nms(boxes, scores, idxs, nms_cfg, class_agnostic=False):\n    \"\"\"Performs non-maximum suppression in a batched fashion.\n\n    Modified from https://github.com/pytorch/vision/blob\n    /505cd6957711af790211896d32b40291bea1bc21/torchvision/ops/boxes.py#L39.\n    In order to perform NMS independently per class, we add an offset to all\n    the boxes. The offset is dependent only on the class idx, and is large\n    enough so that boxes from different classes do not overlap.\n\n    Arguments:\n        boxes (torch.Tensor): boxes in shape (N, 4).\n        scores (torch.Tensor): scores in shape (N, ).\n        idxs (torch.Tensor): each index value correspond to a bbox cluster,\n            and NMS will not be applied between elements of different idxs,\n            shape (N, ).\n        nms_cfg (dict): specify nms type and other parameters like iou_thr.\n            Possible keys includes the following.\n\n            - iou_thr (float): IoU threshold used for NMS.\n            - split_thr (float): threshold number of boxes. In some cases the\n                number of boxes is large (e.g., 200k). To avoid OOM during\n                training, the users could set `split_thr` to a small value.\n                If the number of boxes is greater than the threshold, it will\n                perform NMS on each group of boxes separately and sequentially.\n                Defaults to 10000.\n        class_agnostic (bool): if true, nms is class agnostic,\n            i.e. IoU thresholding happens over all boxes,\n            regardless of the predicted class.\n\n    Returns:\n        tuple: kept dets and indice.\n    \"\"\"\n    nms_cfg_ = nms_cfg.copy()\n    class_agnostic = nms_cfg_.pop('class_agnostic', class_agnostic)\n    if class_agnostic:\n        boxes_for_nms = boxes\n    else:\n        max_coordinate = boxes.max()\n        offsets = idxs.to(boxes) * (max_coordinate + torch.tensor(1).to(boxes))\n        boxes_for_nms = boxes + offsets[:, None]\n\n    nms_type = nms_cfg_.pop('type', 'nms')\n    nms_op = eval(nms_type)\n\n    split_thr = nms_cfg_.pop('split_thr', 10000)\n    # Won't split to multiple nms nodes when exporting to onnx\n    if boxes_for_nms.shape[0] < split_thr or torch.onnx.is_in_onnx_export():\n        dets, keep = nms_op(boxes_for_nms, scores, **nms_cfg_)\n        boxes = boxes[keep]\n        # -1 indexing works abnormal in TensorRT\n        # This assumes `dets` has 5 dimensions where\n        # the last dimension is score.\n        # TODO: more elegant way to handle the dimension issue.\n        # Some type of nms would reweight the score, such as SoftNMS\n        scores = dets[:, 4]\n    else:\n        max_num = nms_cfg_.pop('max_num', -1)\n        total_mask = scores.new_zeros(scores.size(), dtype=torch.bool)\n        # Some type of nms would reweight the score, such as SoftNMS\n        scores_after_nms = scores.new_zeros(scores.size())\n        for id in torch.unique(idxs):\n            mask = (idxs == id).nonzero(as_tuple=False).view(-1)\n            dets, keep = nms_op(boxes_for_nms[mask], scores[mask], **nms_cfg_)\n            total_mask[mask[keep]] = True\n            scores_after_nms[mask[keep]] = dets[:, -1]\n        keep = total_mask.nonzero(as_tuple=False).view(-1)\n\n        scores, inds = scores_after_nms[keep].sort(descending=True)\n        keep = keep[inds]\n        boxes = boxes[keep]\n\n        if max_num > 0:\n            keep = keep[:max_num]\n            boxes = boxes[:max_num]\n            scores = scores[:max_num]\n\n    return torch.cat([boxes, scores[:, None]], -1), keep\n\n\ndef nms_match(dets, iou_threshold):\n    \"\"\"Matched dets into different groups by NMS.\n\n    NMS match is Similar to NMS but when a bbox is suppressed, nms match will\n    record the indice of suppressed bbox and form a group with the indice of\n    kept bbox. In each group, indice is sorted as score order.\n\n    Arguments:\n        dets (torch.Tensor | np.ndarray): Det boxes with scores, shape (N, 5).\n        iou_thr (float): IoU thresh for NMS.\n\n    Returns:\n        List[torch.Tensor | np.ndarray]: The outer list corresponds different\n            matched group, the inner Tensor corresponds the indices for a group\n            in score order.\n    \"\"\"\n    if dets.shape[0] == 0:\n        matched = []\n    else:\n        assert dets.shape[-1] == 5, 'inputs dets.shape should be (N, 5), ' \\\n                                    f'but get {dets.shape}'\n        if isinstance(dets, torch.Tensor):\n            dets_t = dets.detach().cpu()\n        else:\n            dets_t = torch.from_numpy(dets)\n        indata_list = [dets_t]\n        indata_dict = {'iou_threshold': float(iou_threshold)}\n        matched = ext_module.nms_match(*indata_list, **indata_dict)\n\n    if isinstance(dets, torch.Tensor):\n        return [dets.new_tensor(m, dtype=torch.long) for m in matched]\n    else:\n        return [np.array(m, dtype=np.int) for m in matched]\n\n\ndef nms_rotated(dets, scores, iou_threshold, labels=None):\n    \"\"\"Performs non-maximum suppression (NMS) on the rotated boxes according to\n    their intersection-over-union (IoU).\n\n    Rotated NMS iteratively removes lower scoring rotated boxes which have an\n    IoU greater than iou_threshold with another (higher scoring) rotated box.\n\n    Args:\n        boxes (Tensor):  Rotated boxes in shape (N, 5). They are expected to \\\n            be in (x_ctr, y_ctr, width, height, angle_radian) format.\n        scores (Tensor): scores in shape (N, ).\n        iou_threshold (float): IoU thresh for NMS.\n        labels (Tensor): boxes' label in shape (N,).\n\n    Returns:\n        tuple: kept dets(boxes and scores) and indice, which is always the \\\n            same data type as the input.\n    \"\"\"\n    if dets.shape[0] == 0:\n        return dets, None\n    multi_label = labels is not None\n    if multi_label:\n        dets_wl = torch.cat((dets, labels.unsqueeze(1)), 1)\n    else:\n        dets_wl = dets\n    _, order = scores.sort(0, descending=True)\n    dets_sorted = dets_wl.index_select(0, order)\n\n    keep_inds = ext_module.nms_rotated(dets_wl, scores, order, dets_sorted,\n                                        iou_threshold, multi_label)\n    dets = torch.cat((dets[keep_inds], scores[keep_inds].reshape(-1, 1)),\n                     dim=1)\n    return dets, keep_inds\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roi_align.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nimport torch.nn as nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair\n\nfrom ..utils import deprecated_api_warning, ext_loader\n\next_module = ext_loader.load_ext('_ext',\n                                 ['roi_align_forward', 'roi_align_backward'])\n\n\nclass RoIAlignFunction(Function):\n\n    @staticmethod\n    def symbolic(g, input, rois, output_size, spatial_scale, sampling_ratio,\n                 pool_mode, aligned):\n        from ..onnx import is_custom_op_loaded\n        has_custom_op = is_custom_op_loaded()\n        if has_custom_op:\n            return g.op(\n                'mmcv::MMCVRoiAlign',\n                input,\n                rois,\n                output_height_i=output_size[0],\n                output_width_i=output_size[1],\n                spatial_scale_f=spatial_scale,\n                sampling_ratio_i=sampling_ratio,\n                mode_s=pool_mode,\n                aligned_i=aligned)\n        else:\n            from torch.onnx.symbolic_opset9 import sub, squeeze\n            from torch.onnx.symbolic_helper import _slice_helper\n            from torch.onnx import TensorProtoDataType\n            # batch_indices = rois[:, 0].long()\n            batch_indices = _slice_helper(\n                g, rois, axes=[1], starts=[0], ends=[1])\n            batch_indices = squeeze(g, batch_indices, 1)\n            batch_indices = g.op(\n                'Cast', batch_indices, to_i=TensorProtoDataType.INT64)\n            # rois = rois[:, 1:]\n            rois = _slice_helper(g, rois, axes=[1], starts=[1], ends=[5])\n            if aligned:\n                # rois -= 0.5/spatial_scale\n                aligned_offset = g.op(\n                    'Constant',\n                    value_t=torch.tensor([0.5 / spatial_scale],\n                                         dtype=torch.float32))\n                rois = sub(g, rois, aligned_offset)\n            # roi align\n            return g.op(\n                'RoiAlign',\n                input,\n                rois,\n                batch_indices,\n                output_height_i=output_size[0],\n                output_width_i=output_size[1],\n                spatial_scale_f=spatial_scale,\n                sampling_ratio_i=max(0, sampling_ratio),\n                mode_s=pool_mode)\n\n    @staticmethod\n    def forward(ctx,\n                input,\n                rois,\n                output_size,\n                spatial_scale=1.0,\n                sampling_ratio=0,\n                pool_mode='avg',\n                aligned=True):\n        ctx.output_size = _pair(output_size)\n        ctx.spatial_scale = spatial_scale\n        ctx.sampling_ratio = sampling_ratio\n        assert pool_mode in ('max', 'avg')\n        ctx.pool_mode = 0 if pool_mode == 'max' else 1\n        ctx.aligned = aligned\n        ctx.input_shape = input.size()\n\n        assert rois.size(1) == 5, 'RoI must be (idx, x1, y1, x2, y2)!'\n\n        output_shape = (rois.size(0), input.size(1), ctx.output_size[0],\n                        ctx.output_size[1])\n        output = input.new_zeros(output_shape)\n        if ctx.pool_mode == 0:\n            argmax_y = input.new_zeros(output_shape)\n            argmax_x = input.new_zeros(output_shape)\n        else:\n            argmax_y = input.new_zeros(0)\n            argmax_x = input.new_zeros(0)\n\n        ext_module.roi_align_forward(\n            input,\n            rois,\n            output,\n            argmax_y,\n            argmax_x,\n            aligned_height=ctx.output_size[0],\n            aligned_width=ctx.output_size[1],\n            spatial_scale=ctx.spatial_scale,\n            sampling_ratio=ctx.sampling_ratio,\n            pool_mode=ctx.pool_mode,\n            aligned=ctx.aligned)\n\n        ctx.save_for_backward(rois, argmax_y, argmax_x)\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        rois, argmax_y, argmax_x = ctx.saved_tensors\n        grad_input = grad_output.new_zeros(ctx.input_shape)\n        # complex head architecture may cause grad_output uncontiguous.\n        grad_output = grad_output.contiguous()\n        ext_module.roi_align_backward(\n            grad_output,\n            rois,\n            argmax_y,\n            argmax_x,\n            grad_input,\n            aligned_height=ctx.output_size[0],\n            aligned_width=ctx.output_size[1],\n            spatial_scale=ctx.spatial_scale,\n            sampling_ratio=ctx.sampling_ratio,\n            pool_mode=ctx.pool_mode,\n            aligned=ctx.aligned)\n        return grad_input, None, None, None, None, None, None\n\n\nroi_align = RoIAlignFunction.apply\n\n\nclass RoIAlign(nn.Module):\n    \"\"\"RoI align pooling layer.\n\n    Args:\n        output_size (tuple): h, w\n        spatial_scale (float): scale the input boxes by this number\n        sampling_ratio (int): number of inputs samples to take for each\n            output sample. 0 to take samples densely for current models.\n        pool_mode (str, 'avg' or 'max'): pooling mode in each bin.\n        aligned (bool): if False, use the legacy implementation in\n            MMDetection. If True, align the results more perfectly.\n        use_torchvision (bool): whether to use roi_align from torchvision.\n\n    Note:\n        The implementation of RoIAlign when aligned=True is modified from\n        https://github.com/facebookresearch/detectron2/\n\n        The meaning of aligned=True:\n\n        Given a continuous coordinate c, its two neighboring pixel\n        indices (in our pixel model) are computed by floor(c - 0.5) and\n        ceil(c - 0.5). For example, c=1.3 has pixel neighbors with discrete\n        indices [0] and [1] (which are sampled from the underlying signal\n        at continuous coordinates 0.5 and 1.5). But the original roi_align\n        (aligned=False) does not subtract the 0.5 when computing\n        neighboring pixel indices and therefore it uses pixels with a\n        slightly incorrect alignment (relative to our pixel model) when\n        performing bilinear interpolation.\n\n        With `aligned=True`,\n        we first appropriately scale the ROI and then shift it by -0.5\n        prior to calling roi_align. This produces the correct neighbors;\n\n        The difference does not make a difference to the model's\n        performance if ROIAlign is used together with conv layers.\n    \"\"\"\n\n    @deprecated_api_warning(\n        {\n            'out_size': 'output_size',\n            'sample_num': 'sampling_ratio'\n        },\n        cls_name='RoIAlign')\n    def __init__(self,\n                 output_size,\n                 spatial_scale=1.0,\n                 sampling_ratio=0,\n                 pool_mode='avg',\n                 aligned=True,\n                 use_torchvision=False):\n        super(RoIAlign, self).__init__()\n\n        self.output_size = _pair(output_size)\n        self.spatial_scale = float(spatial_scale)\n        self.sampling_ratio = int(sampling_ratio)\n        self.pool_mode = pool_mode\n        self.aligned = aligned\n        self.use_torchvision = use_torchvision\n\n    def forward(self, input, rois):\n        \"\"\"\n        Args:\n            input: NCHW images\n            rois: Bx5 boxes. First column is the index into N.\\\n                The other 4 columns are xyxy.\n        \"\"\"\n        if self.use_torchvision:\n            from torchvision.ops import roi_align as tv_roi_align\n            if 'aligned' in tv_roi_align.__code__.co_varnames:\n                return tv_roi_align(input, rois, self.output_size,\n                                    self.spatial_scale, self.sampling_ratio,\n                                    self.aligned)\n            else:\n                if self.aligned:\n                    rois -= rois.new_tensor([0.] +\n                                            [0.5 / self.spatial_scale] * 4)\n                return tv_roi_align(input, rois, self.output_size,\n                                    self.spatial_scale, self.sampling_ratio)\n        else:\n            return roi_align(input, rois, self.output_size, self.spatial_scale,\n                             self.sampling_ratio, self.pool_mode, self.aligned)\n\n    def __repr__(self):\n        s = self.__class__.__name__\n        s += f'(output_size={self.output_size}, '\n        s += f'spatial_scale={self.spatial_scale}, '\n        s += f'sampling_ratio={self.sampling_ratio}, '\n        s += f'pool_mode={self.pool_mode}, '\n        s += f'aligned={self.aligned}, '\n        s += f'use_torchvision={self.use_torchvision})'\n        return s\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/__init__.py",
    "content": "from .points_in_boxes import (points_in_boxes_batch, points_in_boxes_cpu,\n                              points_in_boxes_gpu)\nfrom .roiaware_pool3d import RoIAwarePool3d\n\n__all__ = [\n    'RoIAwarePool3d', 'points_in_boxes_gpu', 'points_in_boxes_cpu',\n    'points_in_boxes_batch'\n]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/points_in_boxes.py",
    "content": "import torch\n\nfrom . import roiaware_pool3d_ext\n\n\ndef points_in_boxes_gpu(points, boxes):\n    \"\"\"Find points that are in boxes (CUDA)\n\n    Args:\n        points (torch.Tensor): [B, M, 3], [x, y, z] in LiDAR coordinate\n        boxes (torch.Tensor): [B, T, 7],\n            num_valid_boxes <= T, [x, y, z, w, l, h, ry] in LiDAR coordinate,\n            (x, y, z) is the bottom center\n\n    Returns:\n        box_idxs_of_pts (torch.Tensor): (B, M), default background = -1\n    \"\"\"\n    assert boxes.shape[0] == points.shape[0], \\\n        f'Points and boxes should have the same batch size, ' \\\n        f'got {boxes.shape[0]} and {boxes.shape[0]}'\n    assert boxes.shape[2] == 7, \\\n        f'boxes dimension should be 7, ' \\\n        f'got unexpected shape {boxes.shape[2]}'\n    assert points.shape[2] == 3, \\\n        f'points dimension should be 3, ' \\\n        f'got unexpected shape {points.shape[2]}'\n    batch_size, num_points, _ = points.shape\n\n    box_idxs_of_pts = points.new_zeros((batch_size, num_points),\n                                       dtype=torch.int).fill_(-1)\n\n    # If manually put the tensor 'points' or 'boxes' on a device\n    # which is not the current device, some temporary variables\n    # will be created on the current device in the cuda op,\n    # and the output will be incorrect.\n    # Therefore, we force the current device to be the same\n    # as the device of the tensors if it was not.\n    # Please refer to https://github.com/open-mmlab/mmdetection3d/issues/305\n    # for the incorrect output before the fix.\n    points_device = points.get_device()\n    assert points_device == boxes.get_device(), \\\n        'Points and boxes should be put on the same device'\n    if torch.cuda.current_device() != points_device:\n        torch.cuda.set_device(points_device)\n\n    roiaware_pool3d_ext.points_in_boxes_gpu(boxes.contiguous(),\n                                            points.contiguous(),\n                                            box_idxs_of_pts)\n\n    return box_idxs_of_pts\n\n\ndef points_in_boxes_cpu(points, boxes):\n    \"\"\"Find points that are in boxes (CPU)\n\n    Note:\n        Currently, the output of this function is different from that of\n        points_in_boxes_gpu.\n\n    Args:\n        points (torch.Tensor): [npoints, 3]\n        boxes (torch.Tensor): [N, 7], in LiDAR coordinate,\n            (x, y, z) is the bottom center\n\n    Returns:\n        point_indices (torch.Tensor): (N, npoints)\n    \"\"\"\n    # TODO: Refactor this function as a CPU version of points_in_boxes_gpu\n    assert boxes.shape[1] == 7, \\\n        f'boxes dimension should be 7, ' \\\n        f'got unexpected shape {boxes.shape[2]}'\n    assert points.shape[1] == 3, \\\n        f'points dimension should be 3, ' \\\n        f'got unexpected shape {points.shape[2]}'\n\n    point_indices = points.new_zeros((boxes.shape[0], points.shape[0]),\n                                     dtype=torch.int)\n    roiaware_pool3d_ext.points_in_boxes_cpu(boxes.float().contiguous(),\n                                            points.float().contiguous(),\n                                            point_indices)\n\n    return point_indices\n\n\ndef points_in_boxes_batch(points, boxes):\n    \"\"\"Find points that are in boxes (CUDA)\n\n    Args:\n        points (torch.Tensor): [B, M, 3], [x, y, z] in LiDAR coordinate\n        boxes (torch.Tensor): [B, T, 7],\n            num_valid_boxes <= T, [x, y, z, w, l, h, ry] in LiDAR coordinate,\n            (x, y, z) is the bottom center.\n\n    Returns:\n        box_idxs_of_pts (torch.Tensor): (B, M, T), default background = 0\n    \"\"\"\n    assert boxes.shape[0] == points.shape[0], \\\n        f'Points and boxes should have the same batch size, ' \\\n        f'got {boxes.shape[0]} and {boxes.shape[0]}'\n    assert boxes.shape[2] == 7, \\\n        f'boxes dimension should be 7, ' \\\n        f'got unexpected shape {boxes.shape[2]}'\n    assert points.shape[2] == 3, \\\n        f'points dimension should be 3, ' \\\n        f'got unexpected shape {points.shape[2]}'\n    batch_size, num_points, _ = points.shape\n    num_boxes = boxes.shape[1]\n\n    box_idxs_of_pts = points.new_zeros((batch_size, num_points, num_boxes),\n                                       dtype=torch.int).fill_(0)\n\n    # Same reason as line 25-32\n    points_device = points.get_device()\n    assert points_device == boxes.get_device(), \\\n        'Points and boxes should be put on the same device'\n    if torch.cuda.current_device() != points_device:\n        torch.cuda.set_device(points_device)\n\n    roiaware_pool3d_ext.points_in_boxes_batch(boxes.contiguous(),\n                                              points.contiguous(),\n                                              box_idxs_of_pts)\n\n    return box_idxs_of_pts\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/roiaware_pool3d.py",
    "content": "from mmcv.utils import is_tuple_of\nimport torch\nfrom torch import nn as nn\nfrom torch.autograd import Function\n\nfrom . import roiaware_pool3d_ext\n\n\nclass RoIAwarePool3d(nn.Module):\n\n    def __init__(self, out_size, max_pts_per_voxel=128, mode='max'):\n        super().__init__()\n        \"\"\"RoIAwarePool3d module\n\n        Args:\n            out_size (int or tuple): n or [n1, n2, n3]\n            max_pts_per_voxel (int): m\n            mode (str): 'max' or 'avg'\n        \"\"\"\n        self.out_size = out_size\n        self.max_pts_per_voxel = max_pts_per_voxel\n        assert mode in ['max', 'avg']\n        pool_method_map = {'max': 0, 'avg': 1}\n        self.mode = pool_method_map[mode]\n\n    def forward(self, rois, pts, pts_feature):\n        \"\"\"RoIAwarePool3d module forward.\n\n        Args:\n            rois (torch.Tensor): [N, 7],in LiDAR coordinate,\n                (x, y, z) is the bottom center of rois\n            pts (torch.Tensor): [npoints, 3]\n            pts_feature (torch.Tensor): [npoints, C]\n\n        Returns:\n            pooled_features (torch.Tensor): [N, out_x, out_y, out_z, C]\n        \"\"\"\n\n        return RoIAwarePool3dFunction.apply(rois, pts, pts_feature,\n                                            self.out_size,\n                                            self.max_pts_per_voxel, self.mode)\n\n\nclass RoIAwarePool3dFunction(Function):\n\n    @staticmethod\n    def forward(ctx, rois, pts, pts_feature, out_size, max_pts_per_voxel,\n                mode):\n        \"\"\"RoIAwarePool3d function forward.\n\n        Args:\n            rois (torch.Tensor): [N, 7], in LiDAR coordinate,\n                (x, y, z) is the bottom center of rois\n            pts (torch.Tensor): [npoints, 3]\n            pts_feature (torch.Tensor): [npoints, C]\n            out_size (int or tuple): n or [n1, n2, n3]\n            max_pts_per_voxel (int): m\n            mode (int): 0 (max pool) or 1 (average pool)\n\n        Returns:\n            pooled_features (torch.Tensor): [N, out_x, out_y, out_z, C]\n        \"\"\"\n\n        if isinstance(out_size, int):\n            out_x = out_y = out_z = out_size\n        else:\n            assert len(out_size) == 3\n            assert is_tuple_of(out_size, int)\n            out_x, out_y, out_z = out_size\n\n        num_rois = rois.shape[0]\n        num_channels = pts_feature.shape[-1]\n        num_pts = pts.shape[0]\n\n        pooled_features = pts_feature.new_zeros(\n            (num_rois, out_x, out_y, out_z, num_channels))\n        argmax = pts_feature.new_zeros(\n            (num_rois, out_x, out_y, out_z, num_channels), dtype=torch.int)\n        pts_idx_of_voxels = pts_feature.new_zeros(\n            (num_rois, out_x, out_y, out_z, max_pts_per_voxel),\n            dtype=torch.int)\n\n        roiaware_pool3d_ext.forward(rois, pts, pts_feature, argmax,\n                                    pts_idx_of_voxels, pooled_features, mode)\n\n        ctx.roiaware_pool3d_for_backward = (pts_idx_of_voxels, argmax, mode,\n                                            num_pts, num_channels)\n        return pooled_features\n\n    @staticmethod\n    def backward(ctx, grad_out):\n        \"\"\"RoIAwarePool3d function forward.\n\n        Args:\n            grad_out (torch.Tensor): [N, out_x, out_y, out_z, C]\n        Returns:\n            grad_in (torch.Tensor): [npoints, C]\n        \"\"\"\n        ret = ctx.roiaware_pool3d_for_backward\n        pts_idx_of_voxels, argmax, mode, num_pts, num_channels = ret\n\n        grad_in = grad_out.new_zeros((num_pts, num_channels))\n        roiaware_pool3d_ext.backward(pts_idx_of_voxels, argmax,\n                                     grad_out.contiguous(), grad_in, mode)\n\n        return None, None, grad_in, None, None, None\n\n\nif __name__ == '__main__':\n    pass\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/src/points_in_boxes_cpu.cpp",
    "content": "// Modified from\n// https://github.com/sshaoshuai/PCDet/blob/master/pcdet/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu\n// Written by Shaoshuai Shi\n// All Rights Reserved 2019.\n\n#include <assert.h>\n#include <math.h>\n#include <stdio.h>\n#include <torch/extension.h>\n#include <torch/serialize/tensor.h>\n\n#define CHECK_CONTIGUOUS(x) \\\n  TORCH_CHECK(x.is_contiguous(), #x, \" must be contiguous \")\n// #define DEBUG\n\ninline void lidar_to_local_coords_cpu(float shift_x, float shift_y, float rz,\n                                      float &local_x, float &local_y) {\n  // should rotate pi/2 + alpha to translate LiDAR to local\n  float rot_angle = rz + M_PI / 2;\n  float cosa = cos(rot_angle), sina = sin(rot_angle);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\ninline int check_pt_in_box3d_cpu(const float *pt, const float *box3d,\n                                 float &local_x, float &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, w, l, h, rz) in LiDAR coordinate, cz in the\n  // bottom center\n  float x = pt[0], y = pt[1], z = pt[2];\n  float cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  float w = box3d[3], l = box3d[4], h = box3d[5], rz = box3d[6];\n  cz += h / 2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > h / 2.0) return 0;\n  lidar_to_local_coords_cpu(x - cx, y - cy, rz, local_x, local_y);\n  float in_flag = (local_x > -l / 2.0) & (local_x < l / 2.0) &\n                  (local_y > -w / 2.0) & (local_y < w / 2.0);\n  return in_flag;\n}\n\nint points_in_boxes_cpu(at::Tensor boxes_tensor, at::Tensor pts_tensor,\n                        at::Tensor pts_indices_tensor) {\n  // params boxes: (N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is the\n  // bottom center, each box DO NOT overlaps params pts: (npoints, 3) [x, y, z]\n  // in LiDAR coordinate params pts_indices: (N, npoints)\n\n  CHECK_CONTIGUOUS(boxes_tensor);\n  CHECK_CONTIGUOUS(pts_tensor);\n  CHECK_CONTIGUOUS(pts_indices_tensor);\n\n  int boxes_num = boxes_tensor.size(0);\n  int pts_num = pts_tensor.size(0);\n\n  const float *boxes = boxes_tensor.data_ptr<float>();\n  const float *pts = pts_tensor.data_ptr<float>();\n  int *pts_indices = pts_indices_tensor.data_ptr<int>();\n\n  float local_x = 0, local_y = 0;\n  for (int i = 0; i < boxes_num; i++) {\n    for (int j = 0; j < pts_num; j++) {\n      int cur_in_flag =\n          check_pt_in_box3d_cpu(pts + j * 3, boxes + i * 7, local_x, local_y);\n      pts_indices[i * pts_num + j] = cur_in_flag;\n    }\n  }\n\n  return 1;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/src/points_in_boxes_cuda.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/PCDet/blob/master/pcdet/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu\n// Written by Shaoshuai Shi\n// All Rights Reserved 2019.\n\n#include <assert.h>\n#include <math.h>\n#include <stdio.h>\n#include <torch/serialize/tensor.h>\n#include <torch/types.h>\n\n#define THREADS_PER_BLOCK 256\n#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))\n\n#define CHECK_CUDA(x) \\\n  TORCH_CHECK(x.device().is_cuda(), #x, \" must be a CUDAtensor \")\n#define CHECK_CONTIGUOUS(x) \\\n  TORCH_CHECK(x.is_contiguous(), #x, \" must be contiguous \")\n#define CHECK_INPUT(x) \\\n  CHECK_CUDA(x);       \\\n  CHECK_CONTIGUOUS(x)\n// #define DEBUG\n\n__device__ inline void lidar_to_local_coords(float shift_x, float shift_y,\n                                             float rz, float &local_x,\n                                             float &local_y) {\n  // should rotate pi/2 + alpha to translate LiDAR to local\n  float rot_angle = rz + M_PI / 2;\n  float cosa = cos(rot_angle), sina = sin(rot_angle);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\n__device__ inline int check_pt_in_box3d(const float *pt, const float *box3d,\n                                        float &local_x, float &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, w, l, h, rz) in LiDAR coordinate, cz in the\n  // bottom center\n  float x = pt[0], y = pt[1], z = pt[2];\n  float cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  float w = box3d[3], l = box3d[4], h = box3d[5], rz = box3d[6];\n  cz += h / 2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > h / 2.0) return 0;\n  lidar_to_local_coords(x - cx, y - cy, rz, local_x, local_y);\n  float in_flag = (local_x > -l / 2.0) & (local_x < l / 2.0) &\n                  (local_y > -w / 2.0) & (local_y < w / 2.0);\n  return in_flag;\n}\n\n__global__ void points_in_boxes_kernel(int batch_size, int boxes_num,\n                                       int pts_num, const float *boxes,\n                                       const float *pts,\n                                       int *box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is\n  // the bottom center, each box DO NOT overlaps params pts: (B, npoints, 3) [x,\n  // y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints), default\n  // -1\n\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= batch_size || pt_idx >= pts_num) return;\n\n  boxes += bs_idx * boxes_num * 7;\n  pts += bs_idx * pts_num * 3 + pt_idx * 3;\n  box_idx_of_points += bs_idx * pts_num + pt_idx;\n\n  float local_x = 0, local_y = 0;\n  int cur_in_flag = 0;\n  for (int k = 0; k < boxes_num; k++) {\n    cur_in_flag = check_pt_in_box3d(pts, boxes + k * 7, local_x, local_y);\n    if (cur_in_flag) {\n      box_idx_of_points[0] = k;\n      break;\n    }\n  }\n}\n\n__global__ void points_in_boxes_batch_kernel(int batch_size, int boxes_num,\n                                             int pts_num, const float *boxes,\n                                             const float *pts,\n                                             int *box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is\n  // the bottom center, each box DO NOT overlaps params pts: (B, npoints, 3) [x,\n  // y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints), default\n  // -1\n\n  int bs_idx = blockIdx.y;\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (bs_idx >= batch_size || pt_idx >= pts_num) return;\n\n  boxes += bs_idx * boxes_num * 7;\n  pts += bs_idx * pts_num * 3 + pt_idx * 3;\n  box_idx_of_points += bs_idx * pts_num * boxes_num + pt_idx * boxes_num;\n\n  float local_x = 0, local_y = 0;\n  int cur_in_flag = 0;\n  for (int k = 0; k < boxes_num; k++) {\n    cur_in_flag = check_pt_in_box3d(pts, boxes + k * 7, local_x, local_y);\n    if (cur_in_flag) {\n      box_idx_of_points[k] = 1;\n    }\n    cur_in_flag = 0;\n  }\n}\n\nvoid points_in_boxes_launcher(int batch_size, int boxes_num, int pts_num,\n                              const float *boxes, const float *pts,\n                              int *box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is\n  // the bottom center, each box DO NOT overlaps params pts: (B, npoints, 3) [x,\n  // y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints), default\n  // -1\n  cudaError_t err;\n\n  dim3 blocks(DIVUP(pts_num, THREADS_PER_BLOCK), batch_size);\n  dim3 threads(THREADS_PER_BLOCK);\n  points_in_boxes_kernel<<<blocks, threads>>>(batch_size, boxes_num, pts_num,\n                                              boxes, pts, box_idx_of_points);\n\n  err = cudaGetLastError();\n  if (cudaSuccess != err) {\n    fprintf(stderr, \"CUDA kernel failed : %s\\n\", cudaGetErrorString(err));\n    exit(-1);\n  }\n\n#ifdef DEBUG\n  cudaDeviceSynchronize();  // for using printf in kernel function\n#endif\n}\n\nvoid points_in_boxes_batch_launcher(int batch_size, int boxes_num, int pts_num,\n                                    const float *boxes, const float *pts,\n                                    int *box_idx_of_points) {\n  // params boxes: (B, N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is\n  // the bottom center, each box params pts: (B, npoints, 3) [x, y, z] in\n  // LiDAR coordinate params boxes_idx_of_points: (B, npoints), default -1\n  cudaError_t err;\n\n  dim3 blocks(DIVUP(pts_num, THREADS_PER_BLOCK), batch_size);\n  dim3 threads(THREADS_PER_BLOCK);\n  points_in_boxes_batch_kernel<<<blocks, threads>>>(\n      batch_size, boxes_num, pts_num, boxes, pts, box_idx_of_points);\n\n  err = cudaGetLastError();\n  if (cudaSuccess != err) {\n    fprintf(stderr, \"CUDA kernel failed : %s\\n\", cudaGetErrorString(err));\n    exit(-1);\n  }\n\n#ifdef DEBUG\n  cudaDeviceSynchronize();  // for using printf in kernel function\n#endif\n}\n\nint points_in_boxes_gpu(at::Tensor boxes_tensor, at::Tensor pts_tensor,\n                        at::Tensor box_idx_of_points_tensor) {\n  // params boxes: (B, N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is\n  // the bottom center, each box DO NOT overlaps params pts: (B, npoints, 3) [x,\n  // y, z] in LiDAR coordinate params boxes_idx_of_points: (B, npoints), default\n  // -1\n\n  CHECK_INPUT(boxes_tensor);\n  CHECK_INPUT(pts_tensor);\n  CHECK_INPUT(box_idx_of_points_tensor);\n\n  int batch_size = boxes_tensor.size(0);\n  int boxes_num = boxes_tensor.size(1);\n  int pts_num = pts_tensor.size(1);\n\n  const float *boxes = boxes_tensor.data_ptr<float>();\n  const float *pts = pts_tensor.data_ptr<float>();\n  int *box_idx_of_points = box_idx_of_points_tensor.data_ptr<int>();\n\n  points_in_boxes_launcher(batch_size, boxes_num, pts_num, boxes, pts,\n                           box_idx_of_points);\n\n  return 1;\n}\n\nint points_in_boxes_batch(at::Tensor boxes_tensor, at::Tensor pts_tensor,\n                          at::Tensor box_idx_of_points_tensor) {\n  // params boxes: (B, N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate, z is\n  // the bottom center. params pts: (B, npoints, 3) [x, y, z] in LiDAR\n  // coordinate params boxes_idx_of_points: (B, npoints), default -1\n\n  CHECK_INPUT(boxes_tensor);\n  CHECK_INPUT(pts_tensor);\n  CHECK_INPUT(box_idx_of_points_tensor);\n\n  int batch_size = boxes_tensor.size(0);\n  int boxes_num = boxes_tensor.size(1);\n  int pts_num = pts_tensor.size(1);\n\n  const float *boxes = boxes_tensor.data_ptr<float>();\n  const float *pts = pts_tensor.data_ptr<float>();\n  int *box_idx_of_points = box_idx_of_points_tensor.data_ptr<int>();\n\n  points_in_boxes_batch_launcher(batch_size, boxes_num, pts_num, boxes, pts,\n                                 box_idx_of_points);\n\n  return 1;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/src/roiaware_pool3d.cpp",
    "content": "// Modified from\n// https://github.com/sshaoshuai/PCDet/blob/master/pcdet/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu\n// Written by Shaoshuai Shi\n// All Rights Reserved 2019.\n\n#include <assert.h>\n#include <torch/extension.h>\n#include <torch/serialize/tensor.h>\n\n#define CHECK_CUDA(x) \\\n  TORCH_CHECK(x.device().is_cuda(), #x, \" must be a CUDAtensor \")\n#define CHECK_CONTIGUOUS(x) \\\n  TORCH_CHECK(x.is_contiguous(), #x, \" must be contiguous \")\n#define CHECK_INPUT(x) \\\n  CHECK_CUDA(x);       \\\n  CHECK_CONTIGUOUS(x)\n\nvoid roiaware_pool3d_launcher(int boxes_num, int pts_num, int channels,\n                              int max_pts_each_voxel, int out_x, int out_y,\n                              int out_z, const float *rois, const float *pts,\n                              const float *pts_feature, int *argmax,\n                              int *pts_idx_of_voxels, float *pooled_features,\n                              int pool_method);\n\nvoid roiaware_pool3d_backward_launcher(int boxes_num, int out_x, int out_y,\n                                       int out_z, int channels,\n                                       int max_pts_each_voxel,\n                                       const int *pts_idx_of_voxels,\n                                       const int *argmax, const float *grad_out,\n                                       float *grad_in, int pool_method);\n\nint roiaware_pool3d_gpu(at::Tensor rois, at::Tensor pts, at::Tensor pts_feature,\n                        at::Tensor argmax, at::Tensor pts_idx_of_voxels,\n                        at::Tensor pooled_features, int pool_method);\n\nint roiaware_pool3d_gpu_backward(at::Tensor pts_idx_of_voxels,\n                                 at::Tensor argmax, at::Tensor grad_out,\n                                 at::Tensor grad_in, int pool_method);\n\nint points_in_boxes_cpu(at::Tensor boxes_tensor, at::Tensor pts_tensor,\n                        at::Tensor pts_indices_tensor);\n\nint points_in_boxes_gpu(at::Tensor boxes_tensor, at::Tensor pts_tensor,\n                        at::Tensor box_idx_of_points_tensor);\n\nint points_in_boxes_batch(at::Tensor boxes_tensor, at::Tensor pts_tensor,\n                          at::Tensor box_idx_of_points_tensor);\n\nint roiaware_pool3d_gpu(at::Tensor rois, at::Tensor pts, at::Tensor pts_feature,\n                        at::Tensor argmax, at::Tensor pts_idx_of_voxels,\n                        at::Tensor pooled_features, int pool_method) {\n  // params rois: (N, 7) [x, y, z, w, l, h, ry] in LiDAR coordinate\n  // params pts: (npoints, 3) [x, y, z] in LiDAR coordinate\n  // params pts_feature: (npoints, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params pooled_features: (N, out_x, out_y, out_z, C)\n  // params pool_method: 0: max_pool 1: avg_pool\n\n  CHECK_INPUT(rois);\n  CHECK_INPUT(pts);\n  CHECK_INPUT(pts_feature);\n  CHECK_INPUT(argmax);\n  CHECK_INPUT(pts_idx_of_voxels);\n  CHECK_INPUT(pooled_features);\n\n  int boxes_num = rois.size(0);\n  int pts_num = pts.size(0);\n  int channels = pts_feature.size(1);\n  int max_pts_each_voxel = pts_idx_of_voxels.size(4);  // index 0 is the counter\n  int out_x = pts_idx_of_voxels.size(1);\n  int out_y = pts_idx_of_voxels.size(2);\n  int out_z = pts_idx_of_voxels.size(3);\n  assert((out_x < 256) && (out_y < 256) &&\n         (out_z < 256));  // we encode index with 8bit\n\n  const float *rois_data = rois.data_ptr<float>();\n  const float *pts_data = pts.data_ptr<float>();\n  const float *pts_feature_data = pts_feature.data_ptr<float>();\n  int *argmax_data = argmax.data_ptr<int>();\n  int *pts_idx_of_voxels_data = pts_idx_of_voxels.data_ptr<int>();\n  float *pooled_features_data = pooled_features.data_ptr<float>();\n\n  roiaware_pool3d_launcher(\n      boxes_num, pts_num, channels, max_pts_each_voxel, out_x, out_y, out_z,\n      rois_data, pts_data, pts_feature_data, argmax_data,\n      pts_idx_of_voxels_data, pooled_features_data, pool_method);\n\n  return 1;\n}\n\nint roiaware_pool3d_gpu_backward(at::Tensor pts_idx_of_voxels,\n                                 at::Tensor argmax, at::Tensor grad_out,\n                                 at::Tensor grad_in, int pool_method) {\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n  // params pool_method: 0: max_pool 1: avg_pool\n\n  CHECK_INPUT(pts_idx_of_voxels);\n  CHECK_INPUT(argmax);\n  CHECK_INPUT(grad_out);\n  CHECK_INPUT(grad_in);\n\n  int boxes_num = pts_idx_of_voxels.size(0);\n  int out_x = pts_idx_of_voxels.size(1);\n  int out_y = pts_idx_of_voxels.size(2);\n  int out_z = pts_idx_of_voxels.size(3);\n  int max_pts_each_voxel = pts_idx_of_voxels.size(4);  // index 0 is the counter\n  int channels = grad_out.size(4);\n\n  const int *pts_idx_of_voxels_data = pts_idx_of_voxels.data_ptr<int>();\n  const int *argmax_data = argmax.data_ptr<int>();\n  const float *grad_out_data = grad_out.data_ptr<float>();\n  float *grad_in_data = grad_in.data_ptr<float>();\n\n  roiaware_pool3d_backward_launcher(boxes_num, out_x, out_y, out_z, channels,\n                                    max_pts_each_voxel, pts_idx_of_voxels_data,\n                                    argmax_data, grad_out_data, grad_in_data,\n                                    pool_method);\n\n  return 1;\n}\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"forward\", &roiaware_pool3d_gpu, \"roiaware pool3d forward (CUDA)\");\n  m.def(\"backward\", &roiaware_pool3d_gpu_backward,\n        \"roiaware pool3d backward (CUDA)\");\n  m.def(\"points_in_boxes_gpu\", &points_in_boxes_gpu,\n        \"points_in_boxes_gpu forward (CUDA)\");\n  m.def(\"points_in_boxes_batch\", &points_in_boxes_batch,\n        \"points_in_boxes_batch forward (CUDA)\");\n  m.def(\"points_in_boxes_cpu\", &points_in_boxes_cpu,\n        \"points_in_boxes_cpu forward (CPU)\");\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu",
    "content": "// Modified from\n// https://github.com/sshaoshuai/PCDet/blob/master/pcdet/ops/roiaware_pool3d/src/roiaware_pool3d_kernel.cu\n// Written by Shaoshuai Shi\n// All Rights Reserved 2019.\n\n#include <assert.h>\n#include <math.h>\n#include <stdio.h>\n#include <torch/serialize/tensor.h>\n#include <torch/types.h>\n\n#define THREADS_PER_BLOCK 256\n#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))\n\n// #define DEBUG\n\n__device__ inline void lidar_to_local_coords(float shift_x, float shift_y,\n                                             float rz, float &local_x,\n                                             float &local_y) {\n  // should rotate pi/2 + alpha to translate LiDAR to local\n  float rot_angle = rz + M_PI / 2;\n  float cosa = cos(rot_angle), sina = sin(rot_angle);\n  local_x = shift_x * cosa + shift_y * (-sina);\n  local_y = shift_x * sina + shift_y * cosa;\n}\n\n__device__ inline int check_pt_in_box3d(const float *pt, const float *box3d,\n                                        float &local_x, float &local_y) {\n  // param pt: (x, y, z)\n  // param box3d: (cx, cy, cz, w, l, h, rz) in LiDAR coordinate, cz in the\n  // bottom center\n  float x = pt[0], y = pt[1], z = pt[2];\n  float cx = box3d[0], cy = box3d[1], cz = box3d[2];\n  float w = box3d[3], l = box3d[4], h = box3d[5], rz = box3d[6];\n  cz += h / 2.0;  // shift to the center since cz in box3d is the bottom center\n\n  if (fabsf(z - cz) > h / 2.0) return 0;\n  lidar_to_local_coords(x - cx, y - cy, rz, local_x, local_y);\n  float in_flag = (local_x > -l / 2.0) & (local_x < l / 2.0) &\n                  (local_y > -w / 2.0) & (local_y < w / 2.0);\n  return in_flag;\n}\n\n__global__ void generate_pts_mask_for_box3d(int boxes_num, int pts_num,\n                                            int out_x, int out_y, int out_z,\n                                            const float *rois, const float *pts,\n                                            int *pts_mask) {\n  // params rois: (N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate\n  // params pts: (npoints, 3) [x, y, z]\n  // params pts_mask: (N, npoints): -1 means point doesnot in this box,\n  // otherwise: encode (x_idxs, y_idxs, z_idxs) by binary bit\n  int pt_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  int box_idx = blockIdx.y;\n  if (pt_idx >= pts_num || box_idx >= boxes_num) return;\n\n  pts += pt_idx * 3;\n  rois += box_idx * 7;\n  pts_mask += box_idx * pts_num + pt_idx;\n\n  float local_x = 0, local_y = 0;\n  int cur_in_flag = check_pt_in_box3d(pts, rois, local_x, local_y);\n\n  pts_mask[0] = -1;\n  if (cur_in_flag > 0) {\n    float local_z = pts[2] - rois[2];\n    float w = rois[3], l = rois[4], h = rois[5];\n\n    float x_res = l / out_x;\n    float y_res = w / out_y;\n    float z_res = h / out_z;\n\n    unsigned int x_idx = int((local_x + l / 2) / x_res);\n    unsigned int y_idx = int((local_y + w / 2) / y_res);\n    unsigned int z_idx = int(local_z / z_res);\n\n    x_idx = min(max(x_idx, 0), out_x - 1);\n    y_idx = min(max(y_idx, 0), out_y - 1);\n    z_idx = min(max(z_idx, 0), out_z - 1);\n\n    unsigned int idx_encoding = (x_idx << 16) + (y_idx << 8) + z_idx;\n#ifdef DEBUG\n    printf(\n        \"mask: pts_%d(%.3f, %.3f, %.3f), local(%.3f, %.3f, %.3f), idx(%d, %d, \"\n        \"%d), res(%.3f, %.3f, %.3f), idx_encoding=%x\\n\",\n        pt_idx, pts[0], pts[1], pts[2], local_x, local_y, local_z, x_idx, y_idx,\n        z_idx, x_res, y_res, z_res, idx_encoding);\n#endif\n\n    pts_mask[0] = idx_encoding;\n  }\n}\n\n__global__ void collect_inside_pts_for_box3d(int boxes_num, int pts_num,\n                                             int max_pts_each_voxel, int out_x,\n                                             int out_y, int out_z,\n                                             const int *pts_mask,\n                                             int *pts_idx_of_voxels) {\n  // params pts_mask: (N, npoints)  0 or 1\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n\n  int box_idx = blockIdx.x * blockDim.x + threadIdx.x;\n  if (box_idx >= boxes_num) return;\n\n  int max_num_pts = max_pts_each_voxel - 1;  // index 0 is the counter\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel;\n\n  for (int k = 0; k < pts_num; k++) {\n    if (pts_mask[box_idx * pts_num + k] != -1) {\n      unsigned int idx_encoding = pts_mask[box_idx * pts_num + k];\n      unsigned int x_idx = (idx_encoding >> 16) & 0xFF;\n      unsigned int y_idx = (idx_encoding >> 8) & 0xFF;\n      unsigned int z_idx = idx_encoding & 0xFF;\n      unsigned int base_offset = x_idx * out_y * out_z * max_pts_each_voxel +\n                                 y_idx * out_z * max_pts_each_voxel +\n                                 z_idx * max_pts_each_voxel;\n      unsigned int cnt = pts_idx_of_voxels[base_offset];\n      if (cnt < max_num_pts) {\n        pts_idx_of_voxels[base_offset + cnt + 1] = k;\n        pts_idx_of_voxels[base_offset]++;\n      }\n#ifdef DEBUG\n      printf(\"collect: pts_%d, idx(%d, %d, %d), idx_encoding=%x\\n\", k, x_idx,\n             y_idx, z_idx, idx_encoding);\n#endif\n    }\n  }\n}\n\n__global__ void roiaware_maxpool3d(int boxes_num, int pts_num, int channels,\n                                   int max_pts_each_voxel, int out_x, int out_y,\n                                   int out_z, const float *pts_feature,\n                                   const int *pts_idx_of_voxels,\n                                   float *pooled_features, int *argmax) {\n  // params pts_feature: (npoints, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel),\n  // index 0 is the counter params pooled_features: (N, out_x, out_y, out_z, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n#ifdef DEBUG\n  printf(\"src pts_idx_of_voxels: (%p, ), argmax: %p\\n\", pts_idx_of_voxels,\n         argmax);\n#endif\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel +\n                       offset_base * max_pts_each_voxel;\n  pooled_features += box_idx * out_x * out_y * out_z * channels +\n                     offset_base * channels + channel_idx;\n  argmax += box_idx * out_x * out_y * out_z * channels +\n            offset_base * channels + channel_idx;\n\n  int argmax_idx = -1;\n  float max_val = -1e50;\n\n  int total_pts = pts_idx_of_voxels[0];\n\n  for (int k = 1; k <= total_pts; k++) {\n    if (pts_feature[pts_idx_of_voxels[k] * channels + channel_idx] > max_val) {\n      max_val = pts_feature[pts_idx_of_voxels[k] * channels + channel_idx];\n      argmax_idx = pts_idx_of_voxels[k];\n    }\n  }\n\n  if (argmax_idx != -1) {\n    pooled_features[0] = max_val;\n  }\n  argmax[0] = argmax_idx;\n\n#ifdef DEBUG\n  printf(\n      \"channel_%d idx(%d, %d, %d), argmax_idx=(%d, %.3f), total=%d, after \"\n      \"pts_idx: %p, argmax: (%p, %d)\\n\",\n      channel_idx, x_idx, y_idx, z_idx, argmax_idx, max_val, total_pts,\n      pts_idx_of_voxels, argmax, argmax_idx);\n#endif\n}\n\n__global__ void roiaware_avgpool3d(int boxes_num, int pts_num, int channels,\n                                   int max_pts_each_voxel, int out_x, int out_y,\n                                   int out_z, const float *pts_feature,\n                                   const int *pts_idx_of_voxels,\n                                   float *pooled_features) {\n  // params pts_feature: (npoints, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel),\n  // index 0 is the counter params pooled_features: (N, out_x, out_y, out_z, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel +\n                       offset_base * max_pts_each_voxel;\n  pooled_features += box_idx * out_x * out_y * out_z * channels +\n                     offset_base * channels + channel_idx;\n\n  float sum_val = 0;\n  int total_pts = pts_idx_of_voxels[0];\n\n  for (int k = 1; k <= total_pts; k++) {\n    sum_val += pts_feature[pts_idx_of_voxels[k] * channels + channel_idx];\n  }\n\n  if (total_pts > 0) {\n    pooled_features[0] = sum_val / total_pts;\n  }\n}\n\nvoid roiaware_pool3d_launcher(int boxes_num, int pts_num, int channels,\n                              int max_pts_each_voxel, int out_x, int out_y,\n                              int out_z, const float *rois, const float *pts,\n                              const float *pts_feature, int *argmax,\n                              int *pts_idx_of_voxels, float *pooled_features,\n                              int pool_method) {\n  // params rois: (N, 7) [x, y, z, w, l, h, rz] in LiDAR coordinate\n  // params pts: (npoints, 3) [x, y, z] in LiDAR coordinate\n  // params pts_feature: (npoints, C)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params pooled_features: (N, out_x, out_y, out_z, C)\n  // params pool_method: 0: max_pool 1: avg_pool\n\n  int *pts_mask = NULL;\n  cudaMalloc(&pts_mask, boxes_num * pts_num * sizeof(int));  // (N, M)\n  cudaMemset(pts_mask, -1, boxes_num * pts_num * sizeof(int));\n\n  dim3 blocks_mask(DIVUP(pts_num, THREADS_PER_BLOCK), boxes_num);\n  dim3 threads(THREADS_PER_BLOCK);\n  generate_pts_mask_for_box3d<<<blocks_mask, threads>>>(\n      boxes_num, pts_num, out_x, out_y, out_z, rois, pts, pts_mask);\n\n  // TODO: Merge the collect and pool functions, SS\n\n  dim3 blocks_collect(DIVUP(boxes_num, THREADS_PER_BLOCK));\n  collect_inside_pts_for_box3d<<<blocks_collect, threads>>>(\n      boxes_num, pts_num, max_pts_each_voxel, out_x, out_y, out_z, pts_mask,\n      pts_idx_of_voxels);\n\n  dim3 blocks_pool(DIVUP(out_x * out_y * out_z, THREADS_PER_BLOCK), channels,\n                   boxes_num);\n  if (pool_method == 0) {\n    roiaware_maxpool3d<<<blocks_pool, threads>>>(\n        boxes_num, pts_num, channels, max_pts_each_voxel, out_x, out_y, out_z,\n        pts_feature, pts_idx_of_voxels, pooled_features, argmax);\n  } else if (pool_method == 1) {\n    roiaware_avgpool3d<<<blocks_pool, threads>>>(\n        boxes_num, pts_num, channels, max_pts_each_voxel, out_x, out_y, out_z,\n        pts_feature, pts_idx_of_voxels, pooled_features);\n  }\n\n  cudaFree(pts_mask);\n\n#ifdef DEBUG\n  cudaDeviceSynchronize();  // for using printf in kernel function\n#endif\n}\n\n__global__ void roiaware_maxpool3d_backward(int boxes_num, int channels,\n                                            int out_x, int out_y, int out_z,\n                                            const int *argmax,\n                                            const float *grad_out,\n                                            float *grad_in) {\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  argmax += box_idx * out_x * out_y * out_z * channels +\n            offset_base * channels + channel_idx;\n  grad_out += box_idx * out_x * out_y * out_z * channels +\n              offset_base * channels + channel_idx;\n\n  if (argmax[0] == -1) return;\n\n  atomicAdd(grad_in + argmax[0] * channels + channel_idx, grad_out[0] * 1);\n}\n\n__global__ void roiaware_avgpool3d_backward(int boxes_num, int channels,\n                                            int out_x, int out_y, int out_z,\n                                            int max_pts_each_voxel,\n                                            const int *pts_idx_of_voxels,\n                                            const float *grad_out,\n                                            float *grad_in) {\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n\n  int box_idx = blockIdx.z;\n  int channel_idx = blockIdx.y;\n  int voxel_idx_flat = blockIdx.x * blockDim.x + threadIdx.x;\n\n  int x_idx = voxel_idx_flat / (out_y * out_z);\n  int y_idx = (voxel_idx_flat - x_idx * (out_y * out_z)) / out_z;\n  int z_idx = voxel_idx_flat % out_z;\n  if (box_idx >= boxes_num || channel_idx >= channels || x_idx >= out_x ||\n      y_idx >= out_y || z_idx >= out_z)\n    return;\n\n  int offset_base = x_idx * out_y * out_z + y_idx * out_z + z_idx;\n  pts_idx_of_voxels += box_idx * out_x * out_y * out_z * max_pts_each_voxel +\n                       offset_base * max_pts_each_voxel;\n  grad_out += box_idx * out_x * out_y * out_z * channels +\n              offset_base * channels + channel_idx;\n\n  int total_pts = pts_idx_of_voxels[0];\n  float cur_grad = 1 / fmaxf(float(total_pts), 1.0);\n  for (int k = 1; k <= total_pts; k++) {\n    atomicAdd(grad_in + pts_idx_of_voxels[k] * channels + channel_idx,\n              grad_out[0] * cur_grad);\n  }\n}\n\nvoid roiaware_pool3d_backward_launcher(int boxes_num, int out_x, int out_y,\n                                       int out_z, int channels,\n                                       int max_pts_each_voxel,\n                                       const int *pts_idx_of_voxels,\n                                       const int *argmax, const float *grad_out,\n                                       float *grad_in, int pool_method) {\n  // params pts_idx_of_voxels: (N, out_x, out_y, out_z, max_pts_each_voxel)\n  // params argmax: (N, out_x, out_y, out_z, C)\n  // params grad_out: (N, out_x, out_y, out_z, C)\n  // params grad_in: (npoints, C), return value\n  // params pool_method: 0: max_pool, 1: avg_pool\n\n  dim3 blocks(DIVUP(out_x * out_y * out_z, THREADS_PER_BLOCK), channels,\n              boxes_num);\n  dim3 threads(THREADS_PER_BLOCK);\n  if (pool_method == 0) {\n    roiaware_maxpool3d_backward<<<blocks, threads>>>(\n        boxes_num, channels, out_x, out_y, out_z, argmax, grad_out, grad_in);\n  } else if (pool_method == 1) {\n    roiaware_avgpool3d_backward<<<blocks, threads>>>(\n        boxes_num, channels, out_x, out_y, out_z, max_pts_each_voxel,\n        pts_idx_of_voxels, grad_out, grad_in);\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/ops/voxelize.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nfrom torch import nn\nfrom torch.autograd import Function\nfrom torch.nn.modules.utils import _pair\n\nfrom ..utils import ext_loader\n\next_module = ext_loader.load_ext(\n    '_ext', ['dynamic_voxelize_forward', 'hard_voxelize_forward'])\n\n\nclass _Voxelization(Function):\n\n    @staticmethod\n    def forward(ctx,\n                points,\n                voxel_size,\n                coors_range,\n                max_points=35,\n                max_voxels=20000):\n        \"\"\"Convert kitti points(N, >=3) to voxels.\n\n        Args:\n            points (torch.Tensor): [N, ndim]. Points[:, :3] contain xyz points\n                and points[:, 3:] contain other information like reflectivity.\n            voxel_size (tuple or float): The size of voxel with the shape of\n                [3].\n            coors_range (tuple or float): The coordinate range of voxel with\n                the shape of [6].\n            max_points (int, optional): maximum points contained in a voxel. if\n                max_points=-1, it means using dynamic_voxelize. Default: 35.\n            max_voxels (int, optional): maximum voxels this function create.\n                for second, 20000 is a good choice. Users should shuffle points\n                before call this function because max_voxels may drop points.\n                Default: 20000.\n\n        Returns:\n            voxels_out (torch.Tensor): Output voxels with the shape of [M,\n                max_points, ndim]. Only contain points and returned when\n                max_points != -1.\n            coors_out (torch.Tensor): Output coordinates with the shape of\n                [M, 3].\n            num_points_per_voxel_out (torch.Tensor): Num points per voxel with\n                the shape of [M]. Only returned when max_points != -1.\n        \"\"\"\n        if max_points == -1 or max_voxels == -1:\n            coors = points.new_zeros(size=(points.size(0), 3), dtype=torch.int)\n            ext_module.dynamic_voxelize_forward(\n                points,\n                torch.tensor(voxel_size, dtype=torch.float),\n                torch.tensor(coors_range, dtype=torch.float),\n                coors,\n                NDim=3)\n            return coors\n        else:\n            voxels = points.new_zeros(\n                size=(max_voxels, max_points, points.size(1)))\n            coors = points.new_zeros(size=(max_voxels, 3), dtype=torch.int)\n            num_points_per_voxel = points.new_zeros(\n                size=(max_voxels, ), dtype=torch.int)\n            voxel_num = torch.zeros(size=(), dtype=torch.long)\n            ext_module.hard_voxelize_forward(\n                points,\n                torch.tensor(voxel_size, dtype=torch.float),\n                torch.tensor(coors_range, dtype=torch.float),\n                voxels,\n                coors,\n                num_points_per_voxel,\n                voxel_num,\n                max_points=max_points,\n                max_voxels=max_voxels,\n                NDim=3)\n            # select the valid voxels\n            voxels_out = voxels[:voxel_num]\n            coors_out = coors[:voxel_num]\n            num_points_per_voxel_out = num_points_per_voxel[:voxel_num]\n            return voxels_out, coors_out, num_points_per_voxel_out\n\n\nvoxelization = _Voxelization.apply\n\n\nclass Voxelization(nn.Module):\n    \"\"\"Convert kitti points(N, >=3) to voxels.\n\n    Please refer to `PVCNN <https://arxiv.org/abs/1907.03739>`_ for more\n    details.\n\n    Args:\n        voxel_size (tuple or float): The size of voxel with the shape of [3].\n        point_cloud_range (tuple or float): The coordinate range of voxel with\n            the shape of [6].\n        max_num_points (int): maximum points contained in a voxel. if\n            max_points=-1, it means using dynamic_voxelize.\n        max_voxels (int, optional): maximum voxels this function create.\n            for second, 20000 is a good choice. Users should shuffle points\n            before call this function because max_voxels may drop points.\n            Default: 20000.\n    \"\"\"\n\n    def __init__(self,\n                 voxel_size,\n                 point_cloud_range,\n                 max_num_points,\n                 max_voxels=20000):\n        super().__init__()\n\n        self.voxel_size = voxel_size\n        self.point_cloud_range = point_cloud_range\n        self.max_num_points = max_num_points\n        if isinstance(max_voxels, tuple):\n            self.max_voxels = max_voxels\n        else:\n            self.max_voxels = _pair(max_voxels)\n\n        point_cloud_range = torch.tensor(\n            point_cloud_range, dtype=torch.float32)\n        voxel_size = torch.tensor(voxel_size, dtype=torch.float32)\n        grid_size = (point_cloud_range[3:] -\n                     point_cloud_range[:3]) / voxel_size\n        grid_size = torch.round(grid_size).long()\n        input_feat_shape = grid_size[:2]\n        self.grid_size = grid_size\n        # the origin shape is as [x-len, y-len, z-len]\n        # [w, h, d] -> [d, h, w]\n        self.pcd_shape = [*input_feat_shape, 1][::-1]\n\n    def forward(self, input):\n        if self.training:\n            max_voxels = self.max_voxels[0]\n        else:\n            max_voxels = self.max_voxels[1]\n\n        return voxelization(input, self.voxel_size, self.point_cloud_range,\n                            self.max_num_points, max_voxels)\n\n    def __repr__(self):\n        s = self.__class__.__name__ + '('\n        s += 'voxel_size=' + str(self.voxel_size)\n        s += ', point_cloud_range=' + str(self.point_cloud_range)\n        s += ', max_num_points=' + str(self.max_num_points)\n        s += ', max_voxels=' + str(self.max_voxels)\n        s += ')'\n        return s\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/optims/__init__.py",
    "content": "from .optimizer import build_optimizer, OPTIMIZERS"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/optims/adamw.py",
    "content": "try:\n    from torch.optim import _functional as F\nexcept:\n    print('WARNING!!!, I recommend using torch>=1.8')\n\nimport torch\nfrom torch.optim.optimizer import Optimizer\nfrom mmcv.runner.optimizer.builder import OPTIMIZERS\n\n@OPTIMIZERS.register_module()\nclass AdamW2(Optimizer):\n    r\"\"\"Implements AdamW algorithm. Solve the bug of torch 1.8\n\n    The original Adam algorithm was proposed in `Adam: A Method for Stochastic Optimization`_.\n    The AdamW variant was proposed in `Decoupled Weight Decay Regularization`_.\n\n    Args:\n        params (iterable): iterable of parameters to optimize or dicts defining\n            parameter groups\n        lr (float, optional): learning rate (default: 1e-3)\n        betas (Tuple[float, float], optional): coefficients used for computing\n            running averages of gradient and its square (default: (0.9, 0.999))\n        eps (float, optional): term added to the denominator to improve\n            numerical stability (default: 1e-8)\n        weight_decay (float, optional): weight decay coefficient (default: 1e-2)\n        amsgrad (boolean, optional): whether to use the AMSGrad variant of this\n            algorithm from the paper `On the Convergence of Adam and Beyond`_\n            (default: False)\n\n    .. _Adam\\: A Method for Stochastic Optimization:\n        https://arxiv.org/abs/1412.6980\n    .. _Decoupled Weight Decay Regularization:\n        https://arxiv.org/abs/1711.05101\n    .. _On the Convergence of Adam and Beyond:\n        https://openreview.net/forum?id=ryQu7f-RZ\n    \"\"\"\n\n    def __init__(self, params, lr=1e-3, betas=(0.9, 0.999), eps=1e-8,\n                 weight_decay=1e-2, amsgrad=False):\n        if not 0.0 <= lr:\n            raise ValueError(\"Invalid learning rate: {}\".format(lr))\n        if not 0.0 <= eps:\n            raise ValueError(\"Invalid epsilon value: {}\".format(eps))\n        if not 0.0 <= betas[0] < 1.0:\n            raise ValueError(\"Invalid beta parameter at index 0: {}\".format(betas[0]))\n        if not 0.0 <= betas[1] < 1.0:\n            raise ValueError(\"Invalid beta parameter at index 1: {}\".format(betas[1]))\n        if not 0.0 <= weight_decay:\n            raise ValueError(\"Invalid weight_decay value: {}\".format(weight_decay))\n        defaults = dict(lr=lr, betas=betas, eps=eps,\n                        weight_decay=weight_decay, amsgrad=amsgrad)\n        super(AdamW2, self).__init__(params, defaults)\n\n    def __setstate__(self, state):\n        super(AdamW2, self).__setstate__(state)\n        for group in self.param_groups:\n            group.setdefault('amsgrad', False)\n\n    @torch.no_grad()\n    def step(self, closure=None):\n        \"\"\"Performs a single optimization step.\n\n        Args:\n            closure (callable, optional): A closure that reevaluates the model\n                and returns the loss.\n        \"\"\"\n        loss = None\n        if closure is not None:\n            with torch.enable_grad():\n                loss = closure()\n\n        for group in self.param_groups:\n            params_with_grad = []\n            grads = []\n            exp_avgs = []\n            exp_avg_sqs = []\n            state_sums = []\n            max_exp_avg_sqs = []\n            state_steps = []\n            amsgrad = group['amsgrad']\n\n            # put this line here for solving bug\n            beta1, beta2 = group['betas']\n\n            for p in group['params']:\n                if p.grad is None:\n                    continue\n                params_with_grad.append(p)\n                if p.grad.is_sparse:\n                    raise RuntimeError('AdamW does not support sparse gradients')\n                grads.append(p.grad)\n\n                state = self.state[p]\n\n                # State initialization\n                if len(state) == 0:\n                    state['step'] = 0\n                    # Exponential moving average of gradient values\n                    state['exp_avg'] = torch.zeros_like(p, memory_format=torch.preserve_format)\n                    # Exponential moving average of squared gradient values\n                    state['exp_avg_sq'] = torch.zeros_like(p, memory_format=torch.preserve_format)\n                    if amsgrad:\n                        # Maintains max of all exp. moving avg. of sq. grad. values\n                        state['max_exp_avg_sq'] = torch.zeros_like(p, memory_format=torch.preserve_format)\n\n                exp_avgs.append(state['exp_avg'])\n                exp_avg_sqs.append(state['exp_avg_sq'])\n\n                if amsgrad:\n                    max_exp_avg_sqs.append(state['max_exp_avg_sq'])\n\n\n                # update the steps for each param group update\n                state['step'] += 1\n                # record the step after step update\n                state_steps.append(state['step'])\n\n            F.adamw(params_with_grad,\n                    grads,\n                    exp_avgs,\n                    exp_avg_sqs,\n                    max_exp_avg_sqs,\n                    state_steps,\n                    amsgrad,\n                    beta1,\n                    beta2,\n                    group['lr'],\n                    group['weight_decay'],\n                    group['eps'])\n\n        return loss"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/optims/optimizer.py",
    "content": "import torch\nfrom torch.nn import GroupNorm, LayerNorm\nfrom mmcv.utils import build_from_cfg, is_list_of, Registry\nfrom torch.nn.modules.instancenorm import _InstanceNorm\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom mmcv.utils.ext_loader import check_ops_exist\nfrom mmcv.utils import Registry\nimport inspect\nimport copy\n\nOPTIMIZERS = Registry('optimizer')\n\ndef build_optimizer(model, cfg):\n    optimizer_cfg = copy.deepcopy(cfg)\n    paramwise_cfg = optimizer_cfg.pop('paramwise_cfg', None)\n    return DefaultOptimizerConstructor(optimizer_cfg, paramwise_cfg)(model)\n\ndef register_torch_optimizers():\n    torch_optimizers = []\n    for module_name in dir(torch.optim):\n        if module_name.startswith('__'):\n            continue\n        _optim = getattr(torch.optim, module_name)\n        if inspect.isclass(_optim) and issubclass(_optim,\n                                                  torch.optim.Optimizer):\n            OPTIMIZERS.register_module()(_optim)\n            torch_optimizers.append(module_name)\n    return torch_optimizers\n\nTORCH_OPTIMIZERS = register_torch_optimizers()\n\nclass DefaultOptimizerConstructor:\n    \"\"\"Default constructor for optimizers.\n\n    By default each parameter share the same optimizer settings, and we\n    provide an argument ``paramwise_cfg`` to specify parameter-wise settings.\n    It is a dict and may contain the following fields:\n\n    - ``custom_keys`` (dict): Specified parameters-wise settings by keys. If\n      one of the keys in ``custom_keys`` is a substring of the name of one\n      parameter, then the setting of the parameter will be specified by\n      ``custom_keys[key]`` and other setting like ``bias_lr_mult`` etc. will\n      be ignored. It should be noted that the aforementioned ``key`` is the\n      longest key that is a substring of the name of the parameter. If there\n      are multiple matched keys with the same length, then the key with lower\n      alphabet order will be chosen.\n      ``custom_keys[key]`` should be a dict and may contain fields ``lr_mult``\n      and ``decay_mult``. See Example 2 below.\n    - ``bias_lr_mult`` (float): It will be multiplied to the learning\n      rate for all bias parameters (except for those in normalization\n      layers and offset layers of DCN).\n    - ``bias_decay_mult`` (float): It will be multiplied to the weight\n      decay for all bias parameters (except for those in\n      normalization layers, depthwise conv layers, offset layers of DCN).\n    - ``norm_decay_mult`` (float): It will be multiplied to the weight\n      decay for all weight and bias parameters of normalization\n      layers.\n    - ``dwconv_decay_mult`` (float): It will be multiplied to the weight\n      decay for all weight and bias parameters of depthwise conv\n      layers.\n    - ``dcn_offset_lr_mult`` (float): It will be multiplied to the learning\n      rate for parameters of offset layer in the deformable convs\n      of a model.\n    - ``bypass_duplicate`` (bool): If true, the duplicate parameters\n      would not be added into optimizer. Default: False.\n\n    Note:\n        1. If the option ``dcn_offset_lr_mult`` is used, the constructor will\n            override the effect of ``bias_lr_mult`` in the bias of offset\n            layer. So be careful when using both ``bias_lr_mult`` and\n            ``dcn_offset_lr_mult``. If you wish to apply both of them to the\n            offset layer in deformable convs, set ``dcn_offset_lr_mult``\n            to the original ``dcn_offset_lr_mult`` * ``bias_lr_mult``.\n        2. If the option ``dcn_offset_lr_mult`` is used, the constructor will\n            apply it to all the DCN layers in the model. So be careful when\n            the model contains multiple DCN layers in places other than\n            backbone.\n\n    Args:\n        model (:obj:`nn.Module`): The model with parameters to be optimized.\n        optimizer_cfg (dict): The config dict of the optimizer.\n            Positional fields are\n\n                - `type`: class name of the optimizer.\n\n            Optional fields are\n\n                - any arguments of the corresponding optimizer type, e.g.,\n                  lr, weight_decay, momentum, etc.\n        paramwise_cfg (dict, optional): Parameter-wise options.\n\n    Example 1:\n        >>> model = torch.nn.modules.Conv1d(1, 1, 1)\n        >>> optimizer_cfg = dict(type='SGD', lr=0.01, momentum=0.9,\n        >>>                      weight_decay=0.0001)\n        >>> paramwise_cfg = dict(norm_decay_mult=0.)\n        >>> optim_builder = DefaultOptimizerConstructor(\n        >>>     optimizer_cfg, paramwise_cfg)\n        >>> optimizer = optim_builder(model)\n\n    Example 2:\n        >>> # assume model have attribute model.backbone and model.cls_head\n        >>> optimizer_cfg = dict(type='SGD', lr=0.01, weight_decay=0.95)\n        >>> paramwise_cfg = dict(custom_keys={\n                '.backbone': dict(lr_mult=0.1, decay_mult=0.9)})\n        >>> optim_builder = DefaultOptimizerConstructor(\n        >>>     optimizer_cfg, paramwise_cfg)\n        >>> optimizer = optim_builder(model)\n        >>> # Then the `lr` and `weight_decay` for model.backbone is\n        >>> # (0.01 * 0.1, 0.95 * 0.9). `lr` and `weight_decay` for\n        >>> # model.cls_head is (0.01, 0.95).\n    \"\"\"\n\n    def __init__(self, optimizer_cfg, paramwise_cfg=None):\n        if not isinstance(optimizer_cfg, dict):\n            raise TypeError('optimizer_cfg should be a dict',\n                            f'but got {type(optimizer_cfg)}')\n        self.optimizer_cfg = optimizer_cfg\n        self.paramwise_cfg = {} if paramwise_cfg is None else paramwise_cfg\n        self.base_lr = optimizer_cfg.get('lr', None)\n        self.base_wd = optimizer_cfg.get('weight_decay', None)\n        self._validate_cfg()\n\n    def _validate_cfg(self):\n        if not isinstance(self.paramwise_cfg, dict):\n            raise TypeError('paramwise_cfg should be None or a dict, '\n                            f'but got {type(self.paramwise_cfg)}')\n\n        if 'custom_keys' in self.paramwise_cfg:\n            if not isinstance(self.paramwise_cfg['custom_keys'], dict):\n                raise TypeError(\n                    'If specified, custom_keys must be a dict, '\n                    f'but got {type(self.paramwise_cfg[\"custom_keys\"])}')\n            if self.base_wd is None:\n                for key in self.paramwise_cfg['custom_keys']:\n                    if 'decay_mult' in self.paramwise_cfg['custom_keys'][key]:\n                        raise ValueError('base_wd should not be None')\n\n        # get base lr and weight decay\n        # weight_decay must be explicitly specified if mult is specified\n        if ('bias_decay_mult' in self.paramwise_cfg\n                or 'norm_decay_mult' in self.paramwise_cfg\n                or 'dwconv_decay_mult' in self.paramwise_cfg):\n            if self.base_wd is None:\n                raise ValueError('base_wd should not be None')\n\n    def _is_in(self, param_group, param_group_list):\n        assert is_list_of(param_group_list, dict)\n        param = set(param_group['params'])\n        param_set = set()\n        for group in param_group_list:\n            param_set.update(set(group['params']))\n\n        return not param.isdisjoint(param_set)\n\n    def add_params(self, params, module, prefix='', is_dcn_module=None):\n        \"\"\"Add all parameters of module to the params list.\n\n        The parameters of the given module will be added to the list of param\n        groups, with specific rules defined by paramwise_cfg.\n\n        Args:\n            params (list[dict]): A list of param groups, it will be modified\n                in place.\n            module (nn.Module): The module to be added.\n            prefix (str): The prefix of the module\n            is_dcn_module (int|float|None): If the current module is a\n                submodule of DCN, `is_dcn_module` will be passed to\n                control conv_offset layer's learning rate. Defaults to None.\n        \"\"\"\n        # get param-wise options\n        custom_keys = self.paramwise_cfg.get('custom_keys', {})\n        # first sort with alphabet order and then sort with reversed len of str\n        sorted_keys = sorted(sorted(custom_keys.keys()), key=len, reverse=True)\n\n        bias_lr_mult = self.paramwise_cfg.get('bias_lr_mult', 1.)\n        bias_decay_mult = self.paramwise_cfg.get('bias_decay_mult', 1.)\n        norm_decay_mult = self.paramwise_cfg.get('norm_decay_mult', 1.)\n        dwconv_decay_mult = self.paramwise_cfg.get('dwconv_decay_mult', 1.)\n        bypass_duplicate = self.paramwise_cfg.get('bypass_duplicate', False)\n        dcn_offset_lr_mult = self.paramwise_cfg.get('dcn_offset_lr_mult', 1.)\n\n        # special rules for norm layers and depth-wise conv layers\n        is_norm = isinstance(module,\n                             (_BatchNorm, _InstanceNorm, GroupNorm, LayerNorm))\n        is_dwconv = (\n            isinstance(module, torch.nn.Conv2d)\n            and module.in_channels == module.groups)\n\n        for name, param in module.named_parameters(recurse=False):\n            param_group = {'params': [param]}\n            if not param.requires_grad:\n                params.append(param_group)\n                continue\n            if bypass_duplicate and self._is_in(param_group, params):\n                warnings.warn(f'{prefix} is duplicate. It is skipped since '\n                              f'bypass_duplicate={bypass_duplicate}')\n                continue\n            # if the parameter match one of the custom keys, ignore other rules\n            is_custom = False\n            for key in sorted_keys:\n                if key in f'{prefix}.{name}':\n                    is_custom = True\n                    lr_mult = custom_keys[key].get('lr_mult', 1.)\n                    param_group['lr'] = self.base_lr * lr_mult\n                    if self.base_wd is not None:\n                        decay_mult = custom_keys[key].get('decay_mult', 1.)\n                        param_group['weight_decay'] = self.base_wd * decay_mult\n                    break\n\n            if not is_custom:\n                # bias_lr_mult affects all bias parameters\n                # except for norm.bias dcn.conv_offset.bias\n                if name == 'bias' and not (is_norm or is_dcn_module):\n                    param_group['lr'] = self.base_lr * bias_lr_mult\n\n                if (prefix.find('conv_offset') != -1 and is_dcn_module\n                        and isinstance(module, torch.nn.Conv2d)):\n                    # deal with both dcn_offset's bias & weight\n                    param_group['lr'] = self.base_lr * dcn_offset_lr_mult\n\n                # apply weight decay policies\n                if self.base_wd is not None:\n                    # norm decay\n                    if is_norm:\n                        param_group[\n                            'weight_decay'] = self.base_wd * norm_decay_mult\n                    # depth-wise conv\n                    elif is_dwconv:\n                        param_group[\n                            'weight_decay'] = self.base_wd * dwconv_decay_mult\n                    # bias lr and decay\n                    elif name == 'bias' and not is_dcn_module:\n                        # TODO: current bias_decay_mult will have affect on DCN\n                        param_group[\n                            'weight_decay'] = self.base_wd * bias_decay_mult\n            params.append(param_group)\n\n        if check_ops_exist():\n            from mmcv.ops import DeformConv2d, ModulatedDeformConv2d\n            is_dcn_module = isinstance(module,\n                                       (DeformConv2d, ModulatedDeformConv2d))\n        else:\n            is_dcn_module = False\n        for child_name, child_mod in module.named_children():\n            child_prefix = f'{prefix}.{child_name}' if prefix else child_name\n            self.add_params(\n                params,\n                child_mod,\n                prefix=child_prefix,\n                is_dcn_module=is_dcn_module)\n\n    def __call__(self, model):\n        if hasattr(model, 'module'):\n            model = model.module\n\n        optimizer_cfg = self.optimizer_cfg.copy()\n        # if no paramwise option is specified, just use the global setting\n        if not self.paramwise_cfg:\n            optimizer_cfg['params'] = model.parameters()\n            return build_from_cfg(optimizer_cfg, OPTIMIZERS)\n\n        # set param-wise lr and weight decay recursively\n        params = []\n        self.add_params(params, model)\n        optimizer_cfg['params'] = params\n\n        return build_from_cfg(optimizer_cfg, OPTIMIZERS)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/parallel/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .collate import collate\nfrom .data_container import DataContainer\nfrom .utils import is_module_wrapper"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/parallel/collate.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom collections.abc import Mapping, Sequence\n\nimport torch\nimport torch.nn.functional as F\nfrom torch.utils.data.dataloader import default_collate\n\nfrom .data_container import DataContainer\n\ndef collate(batch, samples_per_gpu=1):\n    batch = collate_dc(batch, samples_per_gpu)\n    data_dict = {}\n    for key, value in batch.items():\n        if isinstance(value, DataContainer):\n            data_dict[key] = value.data[0]\n        elif isinstance(value[0], DataContainer):\n            data_dict[key] = value[0].data\n        else:\n            data_dict[key] = value\n    return data_dict\n\ndef collate_dc(batch, samples_per_gpu=1):\n    \"\"\"Puts each data field into a tensor/DataContainer with outer dimension\n    batch size.\n\n    Extend default_collate to add support for\n    :type:`~mmcv.parallel.DataContainer`. There are 3 cases.\n\n    1. cpu_only = True, e.g., meta data\n    2. cpu_only = False, stack = True, e.g., images tensors\n    3. cpu_only = False, stack = False, e.g., gt bboxes\n    \"\"\"\n\n    if not isinstance(batch, Sequence):\n        raise TypeError(f'{batch.dtype} is not supported.')\n\n    if isinstance(batch[0], DataContainer):\n        stacked = []\n        if batch[0].cpu_only:\n            for i in range(0, len(batch), samples_per_gpu):\n                stacked.append(\n                    [sample.data for sample in batch[i:i + samples_per_gpu]])\n            return DataContainer(\n                stacked, batch[0].stack, batch[0].padding_value, cpu_only=True)\n        elif batch[0].stack:\n            for i in range(0, len(batch), samples_per_gpu):\n                assert isinstance(batch[i].data, torch.Tensor)\n\n                if batch[i].pad_dims is not None:\n                    ndim = batch[i].dim()\n                    assert ndim > batch[i].pad_dims\n                    max_shape = [0 for _ in range(batch[i].pad_dims)]\n                    for dim in range(1, batch[i].pad_dims + 1):\n                        max_shape[dim - 1] = batch[i].size(-dim)\n                    for sample in batch[i:i + samples_per_gpu]:\n                        for dim in range(0, ndim - batch[i].pad_dims):\n                            assert batch[i].size(dim) == sample.size(dim)\n                        for dim in range(1, batch[i].pad_dims + 1):\n                            max_shape[dim - 1] = max(max_shape[dim - 1],\n                                                     sample.size(-dim))\n                    padded_samples = []\n                    for sample in batch[i:i + samples_per_gpu]:\n                        pad = [0 for _ in range(batch[i].pad_dims * 2)]\n                        for dim in range(1, batch[i].pad_dims + 1):\n                            pad[2 * dim -\n                                1] = max_shape[dim - 1] - sample.size(-dim)\n                        padded_samples.append(\n                            F.pad(\n                                sample.data, pad, value=sample.padding_value))\n                    stacked.append(default_collate(padded_samples))\n                elif batch[i].pad_dims is None:\n                    stacked.append(\n                        default_collate([\n                            sample.data\n                            for sample in batch[i:i + samples_per_gpu]\n                        ]))\n                else:\n                    raise ValueError(\n                        'pad_dims should be either None or integers (1-3)')\n\n        else:\n            for i in range(0, len(batch), samples_per_gpu):\n                stacked.append(\n                    [sample.data for sample in batch[i:i + samples_per_gpu]])\n        return DataContainer(stacked, batch[0].stack, batch[0].padding_value)\n    elif isinstance(batch[0], Sequence):\n        transposed = zip(*batch)\n        return [collate_dc(samples, samples_per_gpu) for samples in transposed]\n    elif isinstance(batch[0], Mapping):\n        return {\n            key: collate_dc([d[key] for d in batch], samples_per_gpu)\n            for key in batch[0]\n        }\n    else:\n        return default_collate(batch)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/parallel/data_container.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport functools\nimport torch\n\n\ndef assert_tensor_type(func):\n\n    @functools.wraps(func)\n    def wrapper(*args, **kwargs):\n        if not isinstance(args[0].data, torch.Tensor):\n            raise AttributeError(\n                f'{args[0].__class__.__name__} has no attribute '\n                f'{func.__name__} for type {args[0].datatype}')\n        return func(*args, **kwargs)\n\n    return wrapper\n\n\nclass DataContainer:\n    \"\"\"A container for any type of objects.\n\n    Typically tensors will be stacked in the collate function and sliced along\n    some dimension in the scatter function. This behavior has some limitations.\n    1. All tensors have to be the same size.\n    2. Types are limited (numpy array or Tensor).\n\n    We design `DataContainer` and `MMDataParallel` to overcome these\n    limitations. The behavior can be either of the following.\n\n    - copy to GPU, pad all tensors to the same size and stack them\n    - copy to GPU without stacking\n    - leave the objects as is and pass it to the model\n    - pad_dims specifies the number of last few dimensions to do padding\n    \"\"\"\n\n    def __init__(self,\n                 data,\n                 stack=False,\n                 padding_value=0,\n                 cpu_only=False,\n                 pad_dims=2):\n        self._data = data\n        self._cpu_only = cpu_only\n        self._stack = stack\n        self._padding_value = padding_value\n        assert pad_dims in [None, 1, 2, 3]\n        self._pad_dims = pad_dims\n\n    def __repr__(self):\n        return f'{self.__class__.__name__}({repr(self.data)})'\n\n    def __len__(self):\n        return len(self._data)\n\n    @property\n    def data(self):\n        return self._data\n\n    @property\n    def datatype(self):\n        if isinstance(self.data, torch.Tensor):\n            return self.data.type()\n        else:\n            return type(self.data)\n\n    @property\n    def cpu_only(self):\n        return self._cpu_only\n\n    @property\n    def stack(self):\n        return self._stack\n\n    @property\n    def padding_value(self):\n        return self._padding_value\n\n    @property\n    def pad_dims(self):\n        return self._pad_dims\n\n    @assert_tensor_type\n    def size(self, *args, **kwargs):\n        return self.data.size(*args, **kwargs)\n\n    @assert_tensor_type\n    def dim(self):\n        return self.data.dim()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/parallel/registry.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom torch.nn.parallel import DataParallel, DistributedDataParallel\n\nfrom mmcv.utils import Registry\n\nMODULE_WRAPPERS = Registry('module wrapper')\nMODULE_WRAPPERS.register_module(module=DataParallel)\nMODULE_WRAPPERS.register_module(module=DistributedDataParallel)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/parallel/utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .registry import MODULE_WRAPPERS\n\n\ndef is_module_wrapper(module):\n    \"\"\"Check if a module is a module wrapper.\n\n    The following 3 modules in MMCV (and their subclasses) are regarded as\n    module wrappers: DataParallel, DistributedDataParallel,\n    MMDistributedDataParallel (the deprecated version). You may add you own\n    module wrapper by registering it to mmcv.parallel.MODULE_WRAPPERS.\n\n    Args:\n        module (nn.Module): The module to be checked.\n\n    Returns:\n        bool: True if the input module is a module wrapper.\n    \"\"\"\n    module_wrappers = tuple(MODULE_WRAPPERS.module_dict.values())\n    return isinstance(module, module_wrappers)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/__init__.py",
    "content": "from .hooks import DistEvalHook, EvalHook, OptimizerHook, HOOKS, DistSamplerSeedHook, Fp16OptimizerHook\nfrom .epoch_based_runner import EpochBasedRunner\nfrom .builder import build_runner"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/base_runner.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport logging\nimport os.path as osp\nimport warnings\nfrom abc import ABCMeta, abstractmethod\n\nimport torch\nfrom torch.optim import Optimizer\n\nfrom .hooks import HOOKS, Hook\nfrom ..parallel import is_module_wrapper\nfrom ..utils import load_checkpoint, LogBuffer, is_str, mkdir_or_exist, build_from_cfg, \\\n                    Config, get_dist_info, get_time_str, Priority, get_priority\n\n\nclass BaseRunner(metaclass=ABCMeta):\n    \"\"\"The base class of Runner, a training helper for PyTorch.\n\n    All subclasses should implement the following APIs:\n\n    - ``run()``\n    - ``train()``\n    - ``val()``\n    - ``save_checkpoint()``\n\n    Args:\n        model (:obj:`torch.nn.Module`): The model to be run.\n        batch_processor (callable): A callable method that process a data\n            batch. The interface of this method should be\n            `batch_processor(model, data, train_mode) -> dict`\n        optimizer (dict or :obj:`torch.optim.Optimizer`): It can be either an\n            optimizer (in most cases) or a dict of optimizers (in models that\n            requires more than one optimizer, e.g., GAN).\n        work_dir (str, optional): The working directory to save checkpoints\n            and logs. Defaults to None.\n        logger (:obj:`logging.Logger`): Logger used during training.\n             Defaults to None. (The default value is just for backward\n             compatibility)\n        meta (dict | None): A dict records some import information such as\n            environment info and seed, which will be logged in logger hook.\n            Defaults to None.\n        max_epochs (int, optional): Total training epochs.\n        max_iters (int, optional): Total training iterations.\n    \"\"\"\n\n    def __init__(self,\n                 model,\n                 batch_processor=None,\n                 optimizer=None,\n                 work_dir=None,\n                 logger=None,\n                 meta=None,\n                 max_iters=None,\n                 max_epochs=None):\n        if batch_processor is not None:\n            if not callable(batch_processor):\n                raise TypeError('batch_processor must be callable, '\n                                f'but got {type(batch_processor)}')\n            warnings.warn('batch_processor is deprecated, please implement '\n                          'train_step() and val_step() in the model instead.')\n            # raise an error is `batch_processor` is not None and\n            # `model.train_step()` exists.\n            if is_module_wrapper(model):\n                _model = model.module\n            else:\n                _model = model\n\n        # check the type of `optimizer`\n        if isinstance(optimizer, dict):\n            for name, optim in optimizer.items():\n                if not isinstance(optim, Optimizer):\n                    raise TypeError(\n                        f'optimizer must be a dict of torch.optim.Optimizers, '\n                        f'but optimizer[\"{name}\"] is a {type(optim)}')\n        elif not isinstance(optimizer, Optimizer) and optimizer is not None:\n            raise TypeError(\n                f'optimizer must be a torch.optim.Optimizer object '\n                f'or dict or None, but got {type(optimizer)}')\n\n        # check the type of `logger`\n        if not isinstance(logger, logging.Logger):\n            raise TypeError(f'logger must be a logging.Logger object, '\n                            f'but got {type(logger)}')\n\n        # check the type of `meta`\n        if meta is not None and not isinstance(meta, dict):\n            raise TypeError(\n                f'meta must be a dict or None, but got {type(meta)}')\n\n        self.model = model\n        self.batch_processor = batch_processor\n        self.optimizer = optimizer\n        self.logger = logger\n        self.meta = meta\n        # create work_dir\n        if is_str(work_dir):\n            self.work_dir = osp.abspath(work_dir)\n            mkdir_or_exist(self.work_dir)\n        elif work_dir is None:\n            self.work_dir = None\n        else:\n            raise TypeError('\"work_dir\" must be a str or None')\n\n        # get model name from the model class\n        if hasattr(self.model, 'module'):\n            self._model_name = self.model.module.__class__.__name__\n        else:\n            self._model_name = self.model.__class__.__name__\n\n        self._rank, self._world_size = get_dist_info()\n        self.timestamp = get_time_str()\n        self.mode = None\n        self._hooks = []\n        self._epoch = 0\n        self._iter = 0\n        self._inner_iter = 0\n\n        if max_epochs is not None and max_iters is not None:\n            raise ValueError(\n                'Only one of `max_epochs` or `max_iters` can be set.')\n\n        self._max_epochs = max_epochs\n        self._max_iters = max_iters\n        # TODO: Redesign LogBuffer, it is not flexible and elegant enough\n        self.log_buffer = LogBuffer()\n\n    @property\n    def model_name(self):\n        \"\"\"str: Name of the model, usually the module class name.\"\"\"\n        return self._model_name\n\n    @property\n    def rank(self):\n        \"\"\"int: Rank of current process. (distributed training)\"\"\"\n        return self._rank\n\n    @property\n    def world_size(self):\n        \"\"\"int: Number of processes participating in the job.\n        (distributed training)\"\"\"\n        return self._world_size\n\n    @property\n    def hooks(self):\n        \"\"\"list[:obj:`Hook`]: A list of registered hooks.\"\"\"\n        return self._hooks\n\n    @property\n    def epoch(self):\n        \"\"\"int: Current epoch.\"\"\"\n        return self._epoch\n\n    @property\n    def iter(self):\n        \"\"\"int: Current iteration.\"\"\"\n        return self._iter\n\n    @property\n    def inner_iter(self):\n        \"\"\"int: Iteration in an epoch.\"\"\"\n        return self._inner_iter\n\n    @property\n    def max_epochs(self):\n        \"\"\"int: Maximum training epochs.\"\"\"\n        return self._max_epochs\n\n    @property\n    def max_iters(self):\n        \"\"\"int: Maximum training iterations.\"\"\"\n        return self._max_iters\n\n    @abstractmethod\n    def train(self):\n        pass\n\n    @abstractmethod\n    def val(self):\n        pass\n\n    @abstractmethod\n    def run(self, data_loaders, workflow, **kwargs):\n        pass\n\n    @abstractmethod\n    def save_checkpoint(self,\n                        out_dir,\n                        filename_tmpl,\n                        save_optimizer=True,\n                        meta=None,\n                        create_symlink=True):\n        pass\n\n    def current_lr(self):\n        \"\"\"Get current learning rates.\n\n        Returns:\n            list[float] | dict[str, list[float]]: Current learning rates of all\n                param groups. If the runner has a dict of optimizers, this\n                method will return a dict.\n        \"\"\"\n        if isinstance(self.optimizer, torch.optim.Optimizer):\n            lr = [group['lr'] for group in self.optimizer.param_groups]\n        elif isinstance(self.optimizer, dict):\n            lr = dict()\n            for name, optim in self.optimizer.items():\n                lr[name] = [group['lr'] for group in optim.param_groups]\n        else:\n            raise RuntimeError(\n                'lr is not applicable because optimizer does not exist.')\n        return lr\n\n    def current_momentum(self):\n        \"\"\"Get current momentums.\n\n        Returns:\n            list[float] | dict[str, list[float]]: Current momentums of all\n                param groups. If the runner has a dict of optimizers, this\n                method will return a dict.\n        \"\"\"\n\n        def _get_momentum(optimizer):\n            momentums = []\n            for group in optimizer.param_groups:\n                if 'momentum' in group.keys():\n                    momentums.append(group['momentum'])\n                elif 'betas' in group.keys():\n                    momentums.append(group['betas'][0])\n                else:\n                    momentums.append(0)\n            return momentums\n\n        if self.optimizer is None:\n            raise RuntimeError(\n                'momentum is not applicable because optimizer does not exist.')\n        elif isinstance(self.optimizer, torch.optim.Optimizer):\n            momentums = _get_momentum(self.optimizer)\n        elif isinstance(self.optimizer, dict):\n            momentums = dict()\n            for name, optim in self.optimizer.items():\n                momentums[name] = _get_momentum(optim)\n        return momentums\n\n    def register_hook(self, hook, priority='NORMAL'):\n        \"\"\"Register a hook into the hook list.\n\n        The hook will be inserted into a priority queue, with the specified\n        priority (See :class:`Priority` for details of priorities).\n        For hooks with the same priority, they will be triggered in the same\n        order as they are registered.\n\n        Args:\n            hook (:obj:`Hook`): The hook to be registered.\n            priority (int or str or :obj:`Priority`): Hook priority.\n                Lower value means higher priority.\n        \"\"\"\n        assert isinstance(hook, Hook)\n        if hasattr(hook, 'priority'):\n            raise ValueError('\"priority\" is a reserved attribute for hooks')\n        priority = get_priority(priority)\n        hook.priority = priority\n        # insert the hook to a sorted list\n        inserted = False\n        for i in range(len(self._hooks) - 1, -1, -1):\n            if priority >= self._hooks[i].priority:\n                self._hooks.insert(i + 1, hook)\n                inserted = True\n                break\n        if not inserted:\n            self._hooks.insert(0, hook)\n\n    def register_hook_from_cfg(self, hook_cfg):\n        \"\"\"Register a hook from its cfg.\n\n        Args:\n            hook_cfg (dict): Hook config. It should have at least keys 'type'\n              and 'priority' indicating its type and priority.\n\n        Notes:\n            The specific hook class to register should not use 'type' and\n            'priority' arguments during initialization.\n        \"\"\"\n        hook_cfg = hook_cfg.copy()\n        priority = hook_cfg.pop('priority', 'NORMAL')\n        hook = build_from_cfg(hook_cfg, HOOKS)\n        self.register_hook(hook, priority=priority)\n\n    def call_hook(self, fn_name):\n        \"\"\"Call all hooks.\n\n        Args:\n            fn_name (str): The function name in each hook to be called, such as\n                \"before_train_epoch\".\n        \"\"\"\n        for hook in self._hooks:\n            getattr(hook, fn_name)(self)\n\n    def get_hook_info(self):\n        # Get hooks info in each stage\n        stage_hook_map = {stage: [] for stage in Hook.stages}\n        for hook in self.hooks:\n            try:\n                priority = Priority(hook.priority).name\n            except ValueError:\n                priority = hook.priority\n            classname = hook.__class__.__name__\n            hook_info = f'({priority:<12}) {classname:<35}'\n            for trigger_stage in hook.get_triggered_stages():\n                stage_hook_map[trigger_stage].append(hook_info)\n\n        stage_hook_infos = []\n        for stage in Hook.stages:\n            hook_infos = stage_hook_map[stage]\n            if len(hook_infos) > 0:\n                info = f'{stage}:\\n'\n                info += '\\n'.join(hook_infos)\n                info += '\\n -------------------- '\n                stage_hook_infos.append(info)\n        return '\\n'.join(stage_hook_infos)\n\n    def load_checkpoint(self,\n                        filename,\n                        map_location='cpu',\n                        strict=False,\n                        revise_keys=[(r'^module.', '')]):\n        return load_checkpoint(\n            self.model,\n            filename,\n            map_location,\n            strict,\n            self.logger,\n            revise_keys=revise_keys)\n\n    def resume(self,\n               checkpoint,\n               resume_optimizer=True,\n               map_location='default'):\n        if map_location == 'default':\n            if torch.cuda.is_available():\n                device_id = torch.cuda.current_device()\n                checkpoint = self.load_checkpoint(\n                    checkpoint,\n                    map_location=lambda storage, loc: storage.cuda(device_id))\n            else:\n                checkpoint = self.load_checkpoint(checkpoint)\n        else:\n            checkpoint = self.load_checkpoint(\n                checkpoint, map_location=map_location)\n\n        self._epoch = checkpoint['meta']['epoch']\n        self._iter = checkpoint['meta']['iter']\n        if self.meta is None:\n            self.meta = {}\n        self.meta.setdefault('hook_msgs', {})\n        # load `last_ckpt`, `best_score`, `best_ckpt`, etc. for hook messages\n        self.meta['hook_msgs'].update(checkpoint['meta'].get('hook_msgs', {}))\n\n        # Re-calculate the number of iterations when resuming\n        # models with different number of GPUs\n        if 'config' in checkpoint['meta']:\n            config = Config.fromstring(\n                checkpoint['meta']['config'], file_format='.py')\n            previous_gpu_ids = config.get('gpu_ids', None)\n            if previous_gpu_ids and len(previous_gpu_ids) > 0 and len(\n                    previous_gpu_ids) != self.world_size:\n                self._iter = int(self._iter * len(previous_gpu_ids) /\n                                 self.world_size)\n                self.logger.info('the iteration number is changed due to '\n                                 'change of GPU number')\n\n        # resume meta information meta\n        self.meta = checkpoint['meta']\n\n        if 'optimizer' in checkpoint and resume_optimizer:\n            if isinstance(self.optimizer, Optimizer):\n                self.optimizer.load_state_dict(checkpoint['optimizer'])\n            elif isinstance(self.optimizer, dict):\n                for k in self.optimizer.keys():\n                    self.optimizer[k].load_state_dict(\n                        checkpoint['optimizer'][k])\n            else:\n                raise TypeError(\n                    'Optimizer should be dict or torch.optim.Optimizer '\n                    f'but got {type(self.optimizer)}')\n\n        self.logger.info('resumed epoch %d, iter %d', self.epoch, self.iter)\n\n    def register_lr_hook(self, lr_config):\n        if lr_config is None:\n            return\n        elif isinstance(lr_config, dict):\n            assert 'policy' in lr_config\n            policy_type = lr_config.pop('policy')\n            # If the type of policy is all in lower case, e.g., 'cyclic',\n            # then its first letter will be capitalized, e.g., to be 'Cyclic'.\n            # This is for the convenient usage of Lr updater.\n            # Since this is not applicable for `\n            # CosineAnnealingLrUpdater`,\n            # the string will not be changed if it contains capital letters.\n            if policy_type == policy_type.lower():\n                policy_type = policy_type.title()\n            hook_type = policy_type + 'LrUpdaterHook'\n            lr_config['type'] = hook_type\n            hook = build_from_cfg(lr_config, HOOKS)\n        else:\n            hook = lr_config\n        self.register_hook(hook, priority='VERY_HIGH')\n\n    def register_momentum_hook(self, momentum_config):\n        if momentum_config is None:\n            return\n        if isinstance(momentum_config, dict):\n            assert 'policy' in momentum_config\n            policy_type = momentum_config.pop('policy')\n            # If the type of policy is all in lower case, e.g., 'cyclic',\n            # then its first letter will be capitalized, e.g., to be 'Cyclic'.\n            # This is for the convenient usage of momentum updater.\n            # Since this is not applicable for\n            # `CosineAnnealingMomentumUpdater`,\n            # the string will not be changed if it contains capital letters.\n            if policy_type == policy_type.lower():\n                policy_type = policy_type.title()\n            hook_type = policy_type + 'MomentumUpdaterHook'\n            momentum_config['type'] = hook_type\n            hook = build_from_cfg(momentum_config, HOOKS)\n        else:\n            hook = momentum_config\n        self.register_hook(hook, priority='HIGH')\n\n    def register_optimizer_hook(self, optimizer_config):\n        if optimizer_config is None:\n            return\n        if isinstance(optimizer_config, dict):\n            optimizer_config.setdefault('type', 'OptimizerHook')\n            hook = build_from_cfg(optimizer_config, HOOKS)\n        else:\n            hook = optimizer_config\n        self.register_hook(hook, priority='ABOVE_NORMAL')\n\n    def register_checkpoint_hook(self, checkpoint_config):\n        if checkpoint_config is None:\n            return\n        if isinstance(checkpoint_config, dict):\n            checkpoint_config.setdefault('type', 'CheckpointHook')\n            hook = build_from_cfg(checkpoint_config, HOOKS)\n        else:\n            hook = checkpoint_config\n        self.register_hook(hook, priority='NORMAL')\n\n    def register_logger_hooks(self, log_config):\n        if log_config is None:\n            return\n        log_interval = log_config['interval']\n        for info in log_config['hooks']:\n            logger_hook = build_from_cfg(\n                info, HOOKS, default_args=dict(interval=log_interval))\n            self.register_hook(logger_hook, priority='VERY_LOW')\n\n    def register_timer_hook(self, timer_config):\n        if timer_config is None:\n            return\n        if isinstance(timer_config, dict):\n            timer_config_ = copy.deepcopy(timer_config)\n            hook = build_from_cfg(timer_config_, HOOKS)\n        else:\n            hook = timer_config\n        self.register_hook(hook, priority='LOW')\n\n    def register_custom_hooks(self, custom_config):\n        if custom_config is None:\n            return\n\n        if not isinstance(custom_config, list):\n            custom_config = [custom_config]\n\n        for item in custom_config:\n            if isinstance(item, dict):\n                self.register_hook_from_cfg(item)\n            else:\n                self.register_hook(item, priority='NORMAL')\n\n    def register_profiler_hook(self, profiler_config):\n        if profiler_config is None:\n            return\n        if isinstance(profiler_config, dict):\n            profiler_config.setdefault('type', 'ProfilerHook')\n            hook = build_from_cfg(profiler_config, HOOKS)\n        else:\n            hook = profiler_config\n        self.register_hook(hook)\n\n    def register_training_hooks(self,\n                                lr_config,\n                                optimizer_config=None,\n                                checkpoint_config=None,\n                                log_config=None,\n                                momentum_config=None,\n                                timer_config=dict(type='IterTimerHook'),\n                                custom_hooks_config=None):\n        \"\"\"Register default and custom hooks for training.\n\n        Default and custom hooks include:\n\n        +----------------------+-------------------------+\n        | Hooks                | Priority                |\n        +======================+=========================+\n        | LrUpdaterHook        | VERY_HIGH (10)          |\n        +----------------------+-------------------------+\n        | MomentumUpdaterHook  | HIGH (30)               |\n        +----------------------+-------------------------+\n        | OptimizerStepperHook | ABOVE_NORMAL (40)       |\n        +----------------------+-------------------------+\n        | CheckpointSaverHook  | NORMAL (50)             |\n        +----------------------+-------------------------+\n        | IterTimerHook        | LOW (70)                |\n        +----------------------+-------------------------+\n        | LoggerHook(s)        | VERY_LOW (90)           |\n        +----------------------+-------------------------+\n        | CustomHook(s)        | defaults to NORMAL (50) |\n        +----------------------+-------------------------+\n\n        If custom hooks have same priority with default hooks, custom hooks\n        will be triggered after default hooks.\n        \"\"\"\n        self.register_lr_hook(lr_config)\n        self.register_momentum_hook(momentum_config)\n        self.register_optimizer_hook(optimizer_config)\n        self.register_checkpoint_hook(checkpoint_config)\n        self.register_timer_hook(timer_config)\n        self.register_logger_hooks(log_config)\n        self.register_custom_hooks(custom_hooks_config)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/builder.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nfrom mmcv.utils import Registry\n\nRUNNERS = Registry('runner')\n\ndef build_runner(cfg, default_args=None):\n    runner_cfg = copy.deepcopy(cfg)\n    runner = RUNNERS.build(runner_cfg, default_args=default_args)\n    return runner"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/epoch_based_runner.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os.path as osp\nimport platform\nimport shutil\nimport time\nimport warnings\n\nimport torch\n\nfrom .base_runner import BaseRunner\nfrom .builder import RUNNERS\nfrom ..utils import save_checkpoint, is_list_of, symlink, get_host_info\n\n\n\n\n\n\n@RUNNERS.register_module()\nclass EpochBasedRunner(BaseRunner):\n    \"\"\"Epoch-based Runner.\n\n    This runner train models epoch by epoch.\n    \"\"\"\n\n    def run_iter(self, data_batch, train_mode, **kwargs):\n        if self.batch_processor is not None:\n            outputs = self.batch_processor(\n                self.model, data_batch, train_mode=train_mode, **kwargs)\n        elif train_mode:\n            outputs = self.model(data_batch, return_loss=train_mode, **kwargs)\n        else:\n            outputs = self.model.val_step(data_batch, self.optimizer, **kwargs)\n        if not isinstance(outputs, dict):\n            raise TypeError('\"batch_processor()\" or \"model.train_step()\"'\n                            'and \"model.val_step()\" must return a dict')\n        if 'log_vars' in outputs:\n            self.log_buffer.update(outputs['log_vars'], outputs['num_samples'])\n        self.outputs = outputs\n\n    def train(self, data_loader, **kwargs):\n        self.model.train()\n        self.mode = 'train'\n        self.data_loader = data_loader\n        self._max_iters = self._max_epochs * len(self.data_loader)\n        self.call_hook('before_train_epoch')\n        time.sleep(2)  # Prevent possible deadlock during epoch transition\n        for i, data_batch in enumerate(self.data_loader):\n            self._inner_iter = i\n            self.call_hook('before_train_iter')\n            self.run_iter(data_batch, train_mode=True, **kwargs)\n            self.call_hook('after_train_iter')\n            self._iter += 1\n\n        self.call_hook('after_train_epoch')\n        self._epoch += 1\n\n    @torch.no_grad()\n    def val(self, data_loader, **kwargs):\n        self.model.eval()\n        self.mode = 'val'\n        self.data_loader = data_loader\n        self.call_hook('before_val_epoch')\n        time.sleep(2)  # Prevent possible deadlock during epoch transition\n        for i, data_batch in enumerate(self.data_loader):\n            self._inner_iter = i\n            self.call_hook('before_val_iter')\n            self.run_iter(data_batch, train_mode=False)\n            self.call_hook('after_val_iter')\n            \n\n        self.call_hook('after_val_epoch')\n\n    def run(self, data_loaders, workflow, max_epochs=None, **kwargs):\n        \"\"\"Start running.\n\n        Args:\n            data_loaders (list[:obj:`DataLoader`]): Dataloaders for training\n                and validation.\n            workflow (list[tuple]): A list of (phase, epochs) to specify the\n                running order and epochs. E.g, [('train', 2), ('val', 1)] means\n                running 2 epochs for training and 1 epoch for validation,\n                iteratively.\n        \"\"\"\n        assert isinstance(data_loaders, list)\n        assert is_list_of(workflow, tuple)\n        assert len(data_loaders) == len(workflow)\n        if max_epochs is not None:\n            warnings.warn(\n                'setting max_epochs in run is deprecated, '\n                'please set max_epochs in runner_config', DeprecationWarning)\n            self._max_epochs = max_epochs\n\n        assert self._max_epochs is not None, (\n            'max_epochs must be specified during instantiation')\n\n        for i, flow in enumerate(workflow):\n            mode, epochs = flow\n            if mode == 'train':\n                self._max_iters = self._max_epochs * len(data_loaders[i])\n                break\n\n        work_dir = self.work_dir if self.work_dir is not None else 'NONE'\n        self.logger.info('Start running, host: %s, work_dir: %s',\n                         get_host_info(), work_dir)\n        self.logger.info('Hooks will be executed in the following order:\\n%s',\n                         self.get_hook_info())\n        self.logger.info('workflow: %s, max: %d epochs', workflow,\n                         self._max_epochs)\n        self.call_hook('before_run')\n\n        while self.epoch < self._max_epochs:\n            for i, flow in enumerate(workflow):\n                mode, epochs = flow\n                if isinstance(mode, str):  # self.train()\n                    if not hasattr(self, mode):\n                        raise ValueError(\n                            f'runner has no method named \"{mode}\" to run an '\n                            'epoch')\n                    epoch_runner = getattr(self, mode)\n                else:\n                    raise TypeError(\n                        'mode in workflow must be a str, but got {}'.format(\n                            type(mode)))\n\n                for _ in range(epochs):\n                    if mode == 'train' and self.epoch >= self._max_epochs:\n                        break\n                    epoch_runner(data_loaders[i], **kwargs)\n\n        time.sleep(1)  # wait for some hooks like loggers to finish\n        self.call_hook('after_run')\n\n    def save_checkpoint(self,\n                        out_dir,\n                        filename_tmpl='epoch_{}.pth',\n                        save_optimizer=True,\n                        meta=None,\n                        create_symlink=True):\n        \"\"\"Save the checkpoint.\n\n        Args:\n            out_dir (str): The directory that checkpoints are saved.\n            filename_tmpl (str, optional): The checkpoint filename template,\n                which contains a placeholder for the epoch number.\n                Defaults to 'epoch_{}.pth'.\n            save_optimizer (bool, optional): Whether to save the optimizer to\n                the checkpoint. Defaults to True.\n            meta (dict, optional): The meta information to be saved in the\n                checkpoint. Defaults to None.\n            create_symlink (bool, optional): Whether to create a symlink\n                \"latest.pth\" to point to the latest checkpoint.\n                Defaults to True.\n        \"\"\"\n        if meta is None:\n            meta = {}\n        elif not isinstance(meta, dict):\n            raise TypeError(\n                f'meta should be a dict or None, but got {type(meta)}')\n        if self.meta is not None:\n            meta.update(self.meta)\n            # Note: meta.update(self.meta) should be done before\n            # meta.update(epoch=self.epoch + 1, iter=self.iter) otherwise\n            # there will be problems with resumed checkpoints.\n            # More details in https://github.com/open-mmlab/mmcv/pull/1108\n        meta.update(epoch=self.epoch + 1, iter=self.iter)\n\n        filename = filename_tmpl.format(self.epoch + 1)\n        filepath = osp.join(out_dir, filename)\n        optimizer = self.optimizer if save_optimizer else None\n        save_checkpoint(self.model, filepath, optimizer=optimizer, meta=meta)\n        # in some environments, `os.symlink` is not supported, you may need to\n        # set `create_symlink` to False\n        if create_symlink:\n            dst_file = osp.join(out_dir, 'latest.pth')\n            if platform.system() != 'Windows':\n                symlink(filename, dst_file)\n            else:\n                shutil.copy(filepath, dst_file)\n\n\n\n@RUNNERS.register_module()\nclass EpochBasedRunner_video(EpochBasedRunner):\n    \n    ''' \n    # basic logic\n    \n    input_sequence = [a, b, c] # given a sequence of samples\n    \n    prev_bev = None\n    for each in input_sequcene[:-1]\n        prev_bev = eval_model(each, prev_bev)) # inference only.\n    \n    model(input_sequcene[-1], prev_bev) # train the last sample.\n    '''\n    \n    def __init__(self,\n                 model,\n                 eval_model=None,\n                 batch_processor=None,\n                 optimizer=None,\n                 work_dir=None,\n                 logger=None,\n                 meta=None,\n                 keys=['gt_bboxes_3d', 'gt_labels_3d', 'img'],\n                 max_iters=None,\n                 max_epochs=None):\n        super().__init__(model,\n                 batch_processor,\n                 optimizer,\n                 work_dir,\n                 logger,\n                 meta,\n                 max_iters,\n                 max_epochs)\n        keys.append('img_metas')\n        self.keys = keys\n        self.eval_model = eval_model\n        self.eval_model.eval()\n    \n    def run_iter(self, data_batch, train_mode, **kwargs):\n        if self.batch_processor is not None:\n            assert False\n            # outputs = self.batch_processor(\n            #     self.model, data_batch, train_mode=train_mode, **kwargs)\n        elif train_mode:\n\n            num_samples = data_batch['img'].data[0].size(1)\n            data_list = []\n            prev_bev = None\n            for i in range(num_samples):\n                data = {}\n                for key in self.keys:\n                    if key not in ['img_metas', 'img', 'points']:\n                        data[key] = data_batch[key]\n                    else:\n                        if key == 'img':\n                            data['img'] = DataContainer(data=[data_batch['img'].data[0][:, i]], cpu_only=data_batch['img'].cpu_only, stack=True)\n                        elif key == 'img_metas':\n                            data['img_metas'] = DataContainer(data=[[each[i] for each in data_batch['img_metas'].data[0]]], cpu_only=data_batch['img_metas'].cpu_only)\n                        else:\n                            assert False\n                data_list.append(data)\n            with torch.no_grad():\n                for i in range(num_samples-1):\n                    if i>0: data_list[i]['prev_bev'] = DataContainer(data=[prev_bev], cpu_only=False)\n                    prev_bev = self.eval_model.val_step(data_list[i], self.optimizer, **kwargs)\n            \n            data_list[-1]['prev_bev'] = DataContainer(data=[prev_bev], cpu_only=False)\n            outputs = self.model.train_step(data_list[-1], self.optimizer, **kwargs)\n        else:\n            assert False\n            # outputs = self.model.val_step(data_batch, self.optimizer, **kwargs)\n\n        if not isinstance(outputs, dict):\n            raise TypeError('\"batch_processor()\" or \"model.train_step()\"'\n                            'and \"model.val_step()\" must return a dict')\n        if 'log_vars' in outputs:\n            self.log_buffer.update(outputs['log_vars'], outputs['num_samples'])\n        self.outputs = outputs\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/__init__.py",
    "content": "from .evaluation import DistEvalHook, EvalHook\nfrom .optimizer import OptimizerHook, Fp16OptimizerHook\nfrom .sampler_seed import DistSamplerSeedHook\nfrom .hook import HOOKS, Hook\nfrom .lr_updater import LrUpdaterHook\nfrom .checkpoint import CheckpointHook\nfrom .iter_timer import IterTimerHook\nfrom .logger import *\nfrom .vad_hooks import *"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/checkpoint.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os.path as osp\nimport warnings\n\nfrom mmcv.fileio.file_client import FileClient\nfrom mmcv.utils import allreduce_params, master_only\nfrom .hook import HOOKS, Hook\n\n\n@HOOKS.register_module()\nclass CheckpointHook(Hook):\n    \"\"\"Save checkpoints periodically.\n\n    Args:\n        interval (int): The saving period. If ``by_epoch=True``, interval\n            indicates epochs, otherwise it indicates iterations.\n            Default: -1, which means \"never\".\n        by_epoch (bool): Saving checkpoints by epoch or by iteration.\n            Default: True.\n        save_optimizer (bool): Whether to save optimizer state_dict in the\n            checkpoint. It is usually used for resuming experiments.\n            Default: True.\n        out_dir (str, optional): The root directory to save checkpoints. If not\n            specified, ``runner.work_dir`` will be used by default. If\n            specified, the ``out_dir`` will be the concatenation of ``out_dir``\n            and the last level directory of ``runner.work_dir``.\n            `Changed in version 1.3.16.`\n        max_keep_ckpts (int, optional): The maximum checkpoints to keep.\n            In some cases we want only the latest few checkpoints and would\n            like to delete old ones to save the disk space.\n            Default: -1, which means unlimited.\n        save_last (bool, optional): Whether to force the last checkpoint to be\n            saved regardless of interval. Default: True.\n        sync_buffer (bool, optional): Whether to synchronize buffers in\n            different gpus. Default: False.\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n            `New in version 1.3.16.`\n\n    .. warning::\n        Before v1.3.16, the ``out_dir`` argument indicates the path where the\n        checkpoint is stored. However, since v1.3.16, ``out_dir`` indicates the\n        root directory and the final path to save checkpoint is the\n        concatenation of ``out_dir`` and the last level directory of\n        ``runner.work_dir``. Suppose the value of ``out_dir`` is \"/path/of/A\"\n        and the value of ``runner.work_dir`` is \"/path/of/B\", then the final\n        path will be \"/path/of/A/B\".\n    \"\"\"\n\n    def __init__(self,\n                 interval=-1,\n                 by_epoch=True,\n                 save_optimizer=True,\n                 out_dir=None,\n                 max_keep_ckpts=-1,\n                 save_last=True,\n                 sync_buffer=False,\n                 file_client_args=None,\n                 **kwargs):\n        self.interval = interval\n        self.by_epoch = by_epoch\n        self.save_optimizer = save_optimizer\n        self.out_dir = out_dir\n        self.max_keep_ckpts = max_keep_ckpts\n        self.save_last = save_last\n        self.args = kwargs\n        self.sync_buffer = sync_buffer\n        self.file_client_args = file_client_args\n\n    def before_run(self, runner):\n        if not self.out_dir:\n            self.out_dir = runner.work_dir\n\n        self.file_client = FileClient.infer_client(self.file_client_args,\n                                                   self.out_dir)\n\n        # if `self.out_dir` is not equal to `runner.work_dir`, it means that\n        # `self.out_dir` is set so the final `self.out_dir` is the\n        # concatenation of `self.out_dir` and the last level directory of\n        # `runner.work_dir`\n        if self.out_dir != runner.work_dir:\n            basename = osp.basename(runner.work_dir.rstrip(osp.sep))\n            self.out_dir = self.file_client.join_path(self.out_dir, basename)\n\n        runner.logger.info((f'Checkpoints will be saved to {self.out_dir} by '\n                            f'{self.file_client.name}.'))\n\n        # disable the create_symlink option because some file backends do not\n        # allow to create a symlink\n        if 'create_symlink' in self.args:\n            if self.args[\n                    'create_symlink'] and not self.file_client.allow_symlink:\n                self.args['create_symlink'] = False\n                warnings.warn(\n                    ('create_symlink is set as True by the user but is changed'\n                     'to be False because creating symbolic link is not '\n                     f'allowed in {self.file_client.name}'))\n        else:\n            self.args['create_symlink'] = self.file_client.allow_symlink\n\n    def after_train_epoch(self, runner):\n        if not self.by_epoch:\n            return\n\n        # save checkpoint for following cases:\n        # 1. every ``self.interval`` epochs\n        # 2. reach the last epoch of training\n        if self.every_n_epochs(\n                runner, self.interval) or (self.save_last\n                                           and self.is_last_epoch(runner)):\n            runner.logger.info(\n                f'Saving checkpoint at {runner.epoch + 1} epochs')\n            if self.sync_buffer:\n                allreduce_params(runner.model.buffers())\n            self._save_checkpoint(runner)\n\n    @master_only\n    def _save_checkpoint(self, runner):\n        \"\"\"Save the current checkpoint and delete unwanted checkpoint.\"\"\"\n        runner.save_checkpoint(\n            self.out_dir, save_optimizer=self.save_optimizer, **self.args)\n        if runner.meta is not None:\n            if self.by_epoch:\n                cur_ckpt_filename = self.args.get(\n                    'filename_tmpl', 'epoch_{}.pth').format(runner.epoch + 1)\n            else:\n                cur_ckpt_filename = self.args.get(\n                    'filename_tmpl', 'iter_{}.pth').format(runner.iter + 1)\n            runner.meta.setdefault('hook_msgs', dict())\n            runner.meta['hook_msgs']['last_ckpt'] = self.file_client.join_path(\n                self.out_dir, cur_ckpt_filename)\n        # remove other checkpoints\n        if self.max_keep_ckpts > 0:\n            if self.by_epoch:\n                name = 'epoch_{}.pth'\n                current_ckpt = runner.epoch + 1\n            else:\n                name = 'iter_{}.pth'\n                current_ckpt = runner.iter + 1\n            redundant_ckpts = range(\n                current_ckpt - self.max_keep_ckpts * self.interval, 0,\n                -self.interval)\n            filename_tmpl = self.args.get('filename_tmpl', name)\n            for _step in redundant_ckpts:\n                ckpt_path = self.file_client.join_path(\n                    self.out_dir, filename_tmpl.format(_step))\n                if self.file_client.isfile(ckpt_path):\n                    self.file_client.remove(ckpt_path)\n                else:\n                    break\n\n    def after_train_iter(self, runner):\n        if self.by_epoch:\n            return\n\n        # save checkpoint for following cases:\n        # 1. every ``self.interval`` iterations\n        # 2. reach the last iteration of training\n        if self.every_n_iters(\n                runner, self.interval) or (self.save_last\n                                           and self.is_last_iter(runner)):\n            runner.logger.info(\n                f'Saving checkpoint at {runner.iter + 1} iterations')\n            if self.sync_buffer:\n                allreduce_params(runner.model.buffers())\n            self._save_checkpoint(runner)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/evaluation.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os.path as osp\nimport warnings\nfrom math import inf\n\nimport torch.distributed as dist\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom torch.utils.data import DataLoader\n\nfrom mmcv.fileio.file_client import FileClient\nfrom mmcv.utils import is_seq_of\nfrom .hook import Hook\nfrom .logger import LoggerHook\n\n\nclass EvalHook(Hook):\n    \"\"\"Non-Distributed evaluation hook.\n\n    This hook will regularly perform evaluation in a given interval when\n    performing in non-distributed environment.\n\n    Args:\n        dataloader (DataLoader): A PyTorch dataloader, whose dataset has\n            implemented ``evaluate`` function.\n        start (int | None, optional): Evaluation starting epoch. It enables\n            evaluation before the training starts if ``start`` <= the resuming\n            epoch. If None, whether to evaluate is merely decided by\n            ``interval``. Default: None.\n        interval (int): Evaluation interval. Default: 1.\n        by_epoch (bool): Determine perform evaluation by epoch or by iteration.\n            If set to True, it will perform by epoch. Otherwise, by iteration.\n            Default: True.\n        save_best (str, optional): If a metric is specified, it would measure\n            the best checkpoint during evaluation. The information about best\n            checkpoint would be saved in ``runner.meta['hook_msgs']`` to keep\n            best score value and best checkpoint path, which will be also\n            loaded when resume checkpoint. Options are the evaluation metrics\n            on the test dataset. e.g., ``bbox_mAP``, ``segm_mAP`` for bbox\n            detection and instance segmentation. ``AR@100`` for proposal\n            recall. If ``save_best`` is ``auto``, the first key of the returned\n            ``OrderedDict`` result will be used. Default: None.\n        rule (str | None, optional): Comparison rule for best score. If set to\n            None, it will infer a reasonable rule. Keys such as 'acc', 'top'\n            .etc will be inferred by 'greater' rule. Keys contain 'loss' will\n            be inferred by 'less' rule. Options are 'greater', 'less', None.\n            Default: None.\n        test_fn (callable, optional): test a model with samples from a\n            dataloader, and return the test results. If ``None``, the default\n            test function ``mmcv.engine.single_gpu_test`` will be used.\n            (default: ``None``)\n        greater_keys (List[str] | None, optional): Metric keys that will be\n            inferred by 'greater' comparison rule. If ``None``,\n            _default_greater_keys will be used. (default: ``None``)\n        less_keys (List[str] | None, optional): Metric keys that will be\n            inferred by 'less' comparison rule. If ``None``, _default_less_keys\n            will be used. (default: ``None``)\n        out_dir (str, optional): The root directory to save checkpoints. If not\n            specified, `runner.work_dir` will be used by default. If specified,\n            the `out_dir` will be the concatenation of `out_dir` and the last\n            level directory of `runner.work_dir`.\n            `New in version 1.3.16.`\n        file_client_args (dict): Arguments to instantiate a FileClient.\n            See :class:`mmcv.fileio.FileClient` for details. Default: None.\n            `New in version 1.3.16.`\n        **eval_kwargs: Evaluation arguments fed into the evaluate function of\n            the dataset.\n\n    Notes:\n        If new arguments are added for EvalHook, tools/test.py,\n        tools/eval_metric.py may be affected.\n    \"\"\"\n\n    # Since the key for determine greater or less is related to the downstream\n    # tasks, downstream repos may need to overwrite the following inner\n    # variable accordingly.\n\n    rule_map = {'greater': lambda x, y: x > y, 'less': lambda x, y: x < y}\n    init_value_map = {'greater': -inf, 'less': inf}\n    _default_greater_keys = [\n        'acc', 'top', 'AR@', 'auc', 'precision', 'mAP', 'mDice', 'mIoU',\n        'mAcc', 'aAcc'\n    ]\n    _default_less_keys = ['loss']\n\n    def __init__(self,\n                 dataloader,\n                 start=None,\n                 interval=1,\n                 by_epoch=True,\n                 save_best=None,\n                 rule=None,\n                 test_fn=None,\n                 greater_keys=None,\n                 less_keys=None,\n                 out_dir=None,\n                 file_client_args=None,\n                 **eval_kwargs):\n        if not isinstance(dataloader, DataLoader):\n            raise TypeError(f'dataloader must be a pytorch DataLoader, '\n                            f'but got {type(dataloader)}')\n\n        if interval <= 0:\n            raise ValueError(f'interval must be a positive number, '\n                             f'but got {interval}')\n\n        assert isinstance(by_epoch, bool), '``by_epoch`` should be a boolean'\n\n        if start is not None and start < 0:\n            raise ValueError(f'The evaluation start epoch {start} is smaller '\n                             f'than 0')\n\n        self.dataloader = dataloader\n        self.interval = interval\n        self.start = start\n        self.by_epoch = by_epoch\n\n        assert isinstance(save_best, str) or save_best is None, \\\n            '\"\"save_best\"\" should be a str or None ' \\\n            f'rather than {type(save_best)}'\n        self.save_best = save_best\n        self.eval_kwargs = eval_kwargs\n        self.initial_flag = True\n\n        if test_fn is None:\n            raise 'not implement single_gpu_test test_gn'        \n        else:\n            self.test_fn = test_fn\n\n        if greater_keys is None:\n            self.greater_keys = self._default_greater_keys\n        else:\n            if not isinstance(greater_keys, (list, tuple)):\n                greater_keys = (greater_keys, )\n            assert is_seq_of(greater_keys, str)\n            self.greater_keys = greater_keys\n\n        if less_keys is None:\n            self.less_keys = self._default_less_keys\n        else:\n            if not isinstance(less_keys, (list, tuple)):\n                less_keys = (less_keys, )\n            assert is_seq_of(less_keys, str)\n            self.less_keys = less_keys\n\n        if self.save_best is not None:\n            self.best_ckpt_path = None\n            self._init_rule(rule, self.save_best)\n\n        self.out_dir = out_dir\n        self.file_client_args = file_client_args\n\n    def _init_rule(self, rule, key_indicator):\n        \"\"\"Initialize rule, key_indicator, comparison_func, and best score.\n\n        Here is the rule to determine which rule is used for key indicator\n        when the rule is not specific (note that the key indicator matching\n        is case-insensitive):\n        1. If the key indicator is in ``self.greater_keys``, the rule will be\n           specified as 'greater'.\n        2. Or if the key indicator is in ``self.less_keys``, the rule will be\n           specified as 'less'.\n        3. Or if the key indicator is equal to the substring in any one item\n           in ``self.greater_keys``, the rule will be specified as 'greater'.\n        4. Or if the key indicator is equal to the substring in any one item\n           in ``self.less_keys``, the rule will be specified as 'less'.\n\n        Args:\n            rule (str | None): Comparison rule for best score.\n            key_indicator (str | None): Key indicator to determine the\n                comparison rule.\n        \"\"\"\n        if rule not in self.rule_map and rule is not None:\n            raise KeyError(f'rule must be greater, less or None, '\n                           f'but got {rule}.')\n\n        if rule is None:\n            if key_indicator != 'auto':\n                # `_lc` here means we use the lower case of keys for\n                # case-insensitive matching\n                key_indicator_lc = key_indicator.lower()\n                greater_keys = [key.lower() for key in self.greater_keys]\n                less_keys = [key.lower() for key in self.less_keys]\n\n                if key_indicator_lc in greater_keys:\n                    rule = 'greater'\n                elif key_indicator_lc in less_keys:\n                    rule = 'less'\n                elif any(key in key_indicator_lc for key in greater_keys):\n                    rule = 'greater'\n                elif any(key in key_indicator_lc for key in less_keys):\n                    rule = 'less'\n                else:\n                    raise ValueError(f'Cannot infer the rule for key '\n                                     f'{key_indicator}, thus a specific rule '\n                                     f'must be specified.')\n        self.rule = rule\n        self.key_indicator = key_indicator\n        if self.rule is not None:\n            self.compare_func = self.rule_map[self.rule]\n\n    def before_run(self, runner):\n        if not self.out_dir:\n            self.out_dir = runner.work_dir\n\n        self.file_client = FileClient.infer_client(self.file_client_args,\n                                                   self.out_dir)\n\n        # if `self.out_dir` is not equal to `runner.work_dir`, it means that\n        # `self.out_dir` is set so the final `self.out_dir` is the\n        # concatenation of `self.out_dir` and the last level directory of\n        # `runner.work_dir`\n        if self.out_dir != runner.work_dir:\n            basename = osp.basename(runner.work_dir.rstrip(osp.sep))\n            self.out_dir = self.file_client.join_path(self.out_dir, basename)\n            runner.logger.info(\n                (f'The best checkpoint will be saved to {self.out_dir} by '\n                 f'{self.file_client.name}'))\n\n        if self.save_best is not None:\n            if runner.meta is None:\n                warnings.warn('runner.meta is None. Creating an empty one.')\n                runner.meta = dict()\n            runner.meta.setdefault('hook_msgs', dict())\n            self.best_ckpt_path = runner.meta['hook_msgs'].get(\n                'best_ckpt', None)\n\n    def before_train_iter(self, runner):\n        \"\"\"Evaluate the model only at the start of training by iteration.\"\"\"\n        if self.by_epoch or not self.initial_flag:\n            return\n        if self.start is not None and runner.iter >= self.start:\n            self.after_train_iter(runner)\n        self.initial_flag = False\n\n    def before_train_epoch(self, runner):\n        \"\"\"Evaluate the model only at the start of training by epoch.\"\"\"\n        if not (self.by_epoch and self.initial_flag):\n            return\n        if self.start is not None and runner.epoch >= self.start:\n            self.after_train_epoch(runner)\n        self.initial_flag = False\n\n    def after_train_iter(self, runner):\n        \"\"\"Called after every training iter to evaluate the results.\"\"\"\n        if not self.by_epoch and self._should_evaluate(runner):\n            # Because the priority of EvalHook is higher than LoggerHook, the\n            # training log and the evaluating log are mixed. Therefore,\n            # we need to dump the training log and clear it before evaluating\n            # log is generated. In addition, this problem will only appear in\n            # `IterBasedRunner` whose `self.by_epoch` is False, because\n            # `EpochBasedRunner` whose `self.by_epoch` is True calls\n            # `_do_evaluate` in `after_train_epoch` stage, and at this stage\n            # the training log has been printed, so it will not cause any\n            # problem. more details at\n            # https://github.com/open-mmlab/mmsegmentation/issues/694\n            for hook in runner._hooks:\n                if isinstance(hook, LoggerHook):\n                    hook.after_train_iter(runner)\n            runner.log_buffer.clear()\n\n            self._do_evaluate(runner)\n\n    def after_train_epoch(self, runner):\n        \"\"\"Called after every training epoch to evaluate the results.\"\"\"\n        if self.by_epoch and self._should_evaluate(runner):\n            self._do_evaluate(runner)\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        results = self.test_fn(runner.model, self.dataloader)\n        runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)\n        key_score = self.evaluate(runner, results)\n        # the key_score may be `None` so it needs to skip the action to save\n        # the best checkpoint\n        if self.save_best and key_score:\n            self._save_ckpt(runner, key_score)\n\n    def _should_evaluate(self, runner):\n        \"\"\"Judge whether to perform evaluation.\n\n        Here is the rule to judge whether to perform evaluation:\n        1. It will not perform evaluation during the epoch/iteration interval,\n           which is determined by ``self.interval``.\n        2. It will not perform evaluation if the start time is larger than\n           current time.\n        3. It will not perform evaluation when current time is larger than\n           the start time but during epoch/iteration interval.\n\n        Returns:\n            bool: The flag indicating whether to perform evaluation.\n        \"\"\"\n        if self.by_epoch:\n            current = runner.epoch\n            check_time = self.every_n_epochs\n        else:\n            current = runner.iter\n            check_time = self.every_n_iters\n\n        if self.start is None:\n            if not check_time(runner, self.interval):\n                # No evaluation during the interval.\n                return False\n        elif (current + 1) < self.start:\n            # No evaluation if start is larger than the current time.\n            return False\n        else:\n            # Evaluation only at epochs/iters 3, 5, 7...\n            # if start==3 and interval==2\n            if (current + 1 - self.start) % self.interval:\n                return False\n        return True\n\n    def _save_ckpt(self, runner, key_score):\n        \"\"\"Save the best checkpoint.\n\n        It will compare the score according to the compare function, write\n        related information (best score, best checkpoint path) and save the\n        best checkpoint into ``work_dir``.\n        \"\"\"\n        if self.by_epoch:\n            current = f'epoch_{runner.epoch + 1}'\n            cur_type, cur_time = 'epoch', runner.epoch + 1\n        else:\n            current = f'iter_{runner.iter + 1}'\n            cur_type, cur_time = 'iter', runner.iter + 1\n\n        best_score = runner.meta['hook_msgs'].get(\n            'best_score', self.init_value_map[self.rule])\n        if self.compare_func(key_score, best_score):\n            best_score = key_score\n            runner.meta['hook_msgs']['best_score'] = best_score\n\n            if self.best_ckpt_path and self.file_client.isfile(\n                    self.best_ckpt_path):\n                self.file_client.remove(self.best_ckpt_path)\n                runner.logger.info(\n                    (f'The previous best checkpoint {self.best_ckpt_path} was '\n                     'removed'))\n\n            best_ckpt_name = f'best_{self.key_indicator}_{current}.pth'\n            self.best_ckpt_path = self.file_client.join_path(\n                self.out_dir, best_ckpt_name)\n            runner.meta['hook_msgs']['best_ckpt'] = self.best_ckpt_path\n\n            runner.save_checkpoint(\n                self.out_dir, best_ckpt_name, create_symlink=False)\n            runner.logger.info(\n                f'Now best checkpoint is saved as {best_ckpt_name}.')\n            runner.logger.info(\n                f'Best {self.key_indicator} is {best_score:0.4f} '\n                f'at {cur_time} {cur_type}.')\n\n    def evaluate(self, runner, results):\n        \"\"\"Evaluate the results.\n\n        Args:\n            runner (:obj:`mmcv.Runner`): The underlined training runner.\n            results (list): Output results.\n        \"\"\"\n        eval_res = self.dataloader.dataset.evaluate(\n            results, logger=runner.logger, **self.eval_kwargs)\n\n        for name, val in eval_res.items():\n            runner.log_buffer.output[name] = val\n        runner.log_buffer.ready = True\n\n        if self.save_best is not None:\n            # If the performance of model is pool, the `eval_res` may be an\n            # empty dict and it will raise exception when `self.save_best` is\n            # not None. More details at\n            # https://github.com/open-mmlab/mmdetection/issues/6265.\n            if not eval_res:\n                warnings.warn(\n                    'Since `eval_res` is an empty dict, the behavior to save '\n                    'the best checkpoint will be skipped in this evaluation.')\n                return None\n\n            if self.key_indicator == 'auto':\n                # infer from eval_results\n                self._init_rule(self.rule, list(eval_res.keys())[0])\n            return eval_res[self.key_indicator]\n\n        return None\n\n\nclass DistEvalHook(EvalHook):\n    \"\"\"Distributed evaluation hook.\n\n    This hook will regularly perform evaluation in a given interval when\n    performing in distributed environment.\n\n    Args:\n        dataloader (DataLoader): A PyTorch dataloader, whose dataset has\n            implemented ``evaluate`` function.\n        start (int | None, optional): Evaluation starting epoch. It enables\n            evaluation before the training starts if ``start`` <= the resuming\n            epoch. If None, whether to evaluate is merely decided by\n            ``interval``. Default: None.\n        interval (int): Evaluation interval. Default: 1.\n        by_epoch (bool): Determine perform evaluation by epoch or by iteration.\n            If set to True, it will perform by epoch. Otherwise, by iteration.\n            default: True.\n        save_best (str, optional): If a metric is specified, it would measure\n            the best checkpoint during evaluation. The information about best\n            checkpoint would be saved in ``runner.meta['hook_msgs']`` to keep\n            best score value and best checkpoint path, which will be also\n            loaded when resume checkpoint. Options are the evaluation metrics\n            on the test dataset. e.g., ``bbox_mAP``, ``segm_mAP`` for bbox\n            detection and instance segmentation. ``AR@100`` for proposal\n            recall. If ``save_best`` is ``auto``, the first key of the returned\n            ``OrderedDict`` result will be used. Default: None.\n        rule (str | None, optional): Comparison rule for best score. If set to\n            None, it will infer a reasonable rule. Keys such as 'acc', 'top'\n            .etc will be inferred by 'greater' rule. Keys contain 'loss' will\n            be inferred by 'less' rule. Options are 'greater', 'less', None.\n            Default: None.\n        test_fn (callable, optional): test a model with samples from a\n            dataloader in a multi-gpu manner, and return the test results. If\n            ``None``, the default test function ``mmcv.engine.multi_gpu_test``\n            will be used. (default: ``None``)\n        tmpdir (str | None): Temporary directory to save the results of all\n            processes. Default: None.\n        gpu_collect (bool): Whether to use gpu or cpu to collect results.\n            Default: False.\n        broadcast_bn_buffer (bool): Whether to broadcast the\n            buffer(running_mean and running_var) of rank 0 to other rank\n            before evaluation. Default: True.\n        out_dir (str, optional): The root directory to save checkpoints. If not\n            specified, `runner.work_dir` will be used by default. If specified,\n            the `out_dir` will be the concatenation of `out_dir` and the last\n            level directory of `runner.work_dir`.\n        file_client_args (dict): Arguments to instantiate a FileClient.\n            See :class:`mmcv.fileio.FileClient` for details. Default: None.\n        **eval_kwargs: Evaluation arguments fed into the evaluate function of\n            the dataset.\n    \"\"\"\n\n    def __init__(self,\n                 dataloader,\n                 start=None,\n                 interval=1,\n                 by_epoch=True,\n                 save_best=None,\n                 rule=None,\n                 test_fn=None,\n                 greater_keys=None,\n                 less_keys=None,\n                 broadcast_bn_buffer=True,\n                 tmpdir=None,\n                 gpu_collect=False,\n                 out_dir=None,\n                 file_client_args=None,\n                 **eval_kwargs):\n\n        if test_fn is None:\n            raise 'not implement multi_gpu_test test_fn'\n\n        super().__init__(\n            dataloader,\n            start=start,\n            interval=interval,\n            by_epoch=by_epoch,\n            save_best=save_best,\n            rule=rule,\n            test_fn=test_fn,\n            greater_keys=greater_keys,\n            less_keys=less_keys,\n            out_dir=out_dir,\n            file_client_args=file_client_args,\n            **eval_kwargs)\n\n        self.broadcast_bn_buffer = broadcast_bn_buffer\n        self.tmpdir = tmpdir\n        self.gpu_collect = gpu_collect\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        # Synchronization of BatchNorm's buffer (running_mean\n        # and running_var) is not supported in the DDP of pytorch,\n        # which may cause the inconsistent performance of models in\n        # different ranks, so we broadcast BatchNorm's buffers\n        # of rank 0 to other ranks to avoid this.\n        if self.broadcast_bn_buffer:\n            model = runner.model\n            for name, module in model.named_modules():\n                if isinstance(module,\n                              _BatchNorm) and module.track_running_stats:\n                    dist.broadcast(module.running_var, 0)\n                    dist.broadcast(module.running_mean, 0)\n\n        tmpdir = self.tmpdir\n        if tmpdir is None:\n            tmpdir = osp.join(runner.work_dir, '.eval_hook')\n\n        results = self.test_fn(\n            runner.model,\n            self.dataloader,\n            tmpdir=tmpdir,\n            gpu_collect=self.gpu_collect)\n        if runner.rank == 0:\n            print('\\n')\n            runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)\n            key_score = self.evaluate(runner, results)\n            # the key_score may be `None` so it needs to skip the action to\n            # save the best checkpoint\n            if self.save_best and key_score:\n                self._save_ckpt(runner, key_score)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/hook.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmcv.utils import Registry, is_method_overridden\n\nHOOKS = Registry('hook')\n\n\nclass Hook:\n    stages = ('before_run', 'before_train_epoch', 'before_train_iter',\n              'after_train_iter', 'after_train_epoch', 'before_val_epoch',\n              'before_val_iter', 'after_val_iter', 'after_val_epoch',\n              'after_run')\n\n    def before_run(self, runner):\n        pass\n\n    def after_run(self, runner):\n        pass\n\n    def before_epoch(self, runner):\n        pass\n\n    def after_epoch(self, runner):\n        pass\n\n    def before_iter(self, runner):\n        pass\n\n    def after_iter(self, runner):\n        pass\n\n    def before_train_epoch(self, runner):\n        self.before_epoch(runner)\n\n    def before_val_epoch(self, runner):\n        self.before_epoch(runner)\n\n    def after_train_epoch(self, runner):\n        self.after_epoch(runner)\n\n    def after_val_epoch(self, runner):\n        self.after_epoch(runner)\n\n    def before_train_iter(self, runner):\n        self.before_iter(runner)\n\n    def before_val_iter(self, runner):\n        self.before_iter(runner)\n\n    def after_train_iter(self, runner):\n        self.after_iter(runner)\n\n    def after_val_iter(self, runner):\n        self.after_iter(runner)\n\n    def every_n_epochs(self, runner, n):\n        return (runner.epoch + 1) % n == 0 if n > 0 else False\n\n    def every_n_inner_iters(self, runner, n):\n        return (runner.inner_iter + 1) % n == 0 if n > 0 else False\n\n    def every_n_iters(self, runner, n):\n        return (runner.iter + 1) % n == 0 if n > 0 else False\n\n    def end_of_epoch(self, runner):\n        return runner.inner_iter + 1 == len(runner.data_loader)\n\n    def is_last_epoch(self, runner):\n        return runner.epoch + 1 == runner._max_epochs\n\n    def is_last_iter(self, runner):\n        return runner.iter + 1 == runner._max_iters\n\n    def get_triggered_stages(self):\n        trigger_stages = set()\n        for stage in Hook.stages:\n            if is_method_overridden(stage, Hook, self):\n                trigger_stages.add(stage)\n\n        # some methods will be triggered in multi stages\n        # use this dict to map method to stages.\n        method_stages_map = {\n            'before_epoch': ['before_train_epoch', 'before_val_epoch'],\n            'after_epoch': ['after_train_epoch', 'after_val_epoch'],\n            'before_iter': ['before_train_iter', 'before_val_iter'],\n            'after_iter': ['after_train_iter', 'after_val_iter'],\n        }\n\n        for method, map_stages in method_stages_map.items():\n            if is_method_overridden(method, Hook, self):\n                trigger_stages.update(map_stages)\n\n        return [stage for stage in Hook.stages if stage in trigger_stages]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/iter_timer.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport time\n\nfrom .hook import HOOKS, Hook\n\n\n@HOOKS.register_module()\nclass IterTimerHook(Hook):\n\n    def before_epoch(self, runner):\n        self.t = time.time()\n\n    def before_iter(self, runner):\n        runner.log_buffer.update({'data_time': time.time() - self.t})\n\n    def after_iter(self, runner):\n        runner.log_buffer.update({'time': time.time() - self.t})\n        self.t = time.time()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/logger/__init__.py",
    "content": "from .base import LoggerHook\nfrom .text import TextLoggerHook\nfrom .tensorboard import TensorboardLoggerHook"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/logger/base.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numbers\nfrom abc import ABCMeta, abstractmethod\n\nimport numpy as np\nimport torch\n\nfrom ..hook import Hook\n\n\nclass LoggerHook(Hook):\n    \"\"\"Base class for logger hooks.\n\n    Args:\n        interval (int): Logging interval (every k iterations).\n        ignore_last (bool): Ignore the log of last iterations in each epoch\n            if less than `interval`.\n        reset_flag (bool): Whether to clear the output buffer after logging.\n        by_epoch (bool): Whether EpochBasedRunner is used.\n    \"\"\"\n\n    __metaclass__ = ABCMeta\n\n    def __init__(self,\n                 interval=10,\n                 ignore_last=True,\n                 reset_flag=False,\n                 by_epoch=True):\n        self.interval = interval\n        self.ignore_last = ignore_last\n        self.reset_flag = reset_flag\n        self.by_epoch = by_epoch\n\n    @abstractmethod\n    def log(self, runner):\n        pass\n\n    @staticmethod\n    def is_scalar(val, include_np=True, include_torch=True):\n        \"\"\"Tell the input variable is a scalar or not.\n\n        Args:\n            val: Input variable.\n            include_np (bool): Whether include 0-d np.ndarray as a scalar.\n            include_torch (bool): Whether include 0-d torch.Tensor as a scalar.\n\n        Returns:\n            bool: True or False.\n        \"\"\"\n        if isinstance(val, numbers.Number):\n            return True\n        elif include_np and isinstance(val, np.ndarray) and val.ndim == 0:\n            return True\n        elif include_torch and isinstance(val, torch.Tensor) and len(val) == 1:\n            return True\n        else:\n            return False\n\n    def get_mode(self, runner):\n        if runner.mode == 'train':\n            if 'time' in runner.log_buffer.output:\n                mode = 'train'\n            else:\n                mode = 'val'\n        elif runner.mode == 'val':\n            mode = 'val'\n        else:\n            raise ValueError(f\"runner mode should be 'train' or 'val', \"\n                             f'but got {runner.mode}')\n        return mode\n\n    def get_epoch(self, runner):\n        if runner.mode == 'train':\n            epoch = runner.epoch + 1\n        elif runner.mode == 'val':\n            # normal val mode\n            # runner.epoch += 1 has been done before val workflow\n            epoch = runner.epoch\n        else:\n            raise ValueError(f\"runner mode should be 'train' or 'val', \"\n                             f'but got {runner.mode}')\n        return epoch\n\n    def get_iter(self, runner, inner_iter=False):\n        \"\"\"Get the current training iteration step.\"\"\"\n        if self.by_epoch and inner_iter:\n            current_iter = runner.inner_iter + 1\n        else:\n            current_iter = runner.iter + 1\n        return current_iter\n\n    def get_lr_tags(self, runner):\n        tags = {}\n        lrs = runner.current_lr()\n        if isinstance(lrs, dict):\n            for name, value in lrs.items():\n                tags[f'learning_rate/{name}'] = value[0]\n        else:\n            tags['learning_rate'] = lrs[0]\n        return tags\n\n    def get_momentum_tags(self, runner):\n        tags = {}\n        momentums = runner.current_momentum()\n        if isinstance(momentums, dict):\n            for name, value in momentums.items():\n                tags[f'momentum/{name}'] = value[0]\n        else:\n            tags['momentum'] = momentums[0]\n        return tags\n\n    def get_loggable_tags(self,\n                          runner,\n                          allow_scalar=True,\n                          allow_text=False,\n                          add_mode=True,\n                          tags_to_skip=('time', 'data_time')):\n        tags = {}\n        for var, val in runner.log_buffer.output.items():\n            if var in tags_to_skip:\n                continue\n            if self.is_scalar(val) and not allow_scalar:\n                continue\n            if isinstance(val, str) and not allow_text:\n                continue\n            if add_mode:\n                var = f'{self.get_mode(runner)}/{var}'\n            tags[var] = val\n        tags.update(self.get_lr_tags(runner))\n        tags.update(self.get_momentum_tags(runner))\n        return tags\n\n    def before_run(self, runner):\n        for hook in runner.hooks[::-1]:\n            if isinstance(hook, LoggerHook):\n                hook.reset_flag = True\n                break\n\n    def before_epoch(self, runner):\n        runner.log_buffer.clear()  # clear logs of last epoch\n\n    def after_train_iter(self, runner):\n        if self.by_epoch and self.every_n_inner_iters(runner, self.interval):\n            runner.log_buffer.average(self.interval)\n        elif not self.by_epoch and self.every_n_iters(runner, self.interval):\n            runner.log_buffer.average(self.interval)\n        elif self.end_of_epoch(runner) and not self.ignore_last:\n            # not precise but more stable\n            runner.log_buffer.average(self.interval)\n\n        if runner.log_buffer.ready:\n            self.log(runner)\n            if self.reset_flag:\n                runner.log_buffer.clear_output()\n\n    def after_train_epoch(self, runner):\n        if runner.log_buffer.ready:\n            self.log(runner)\n            if self.reset_flag:\n                runner.log_buffer.clear_output()\n\n    def after_val_epoch(self, runner):\n        runner.log_buffer.average()\n        self.log(runner)\n        if self.reset_flag:\n            runner.log_buffer.clear_output()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/logger/tensorboard.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os.path as osp\n\nfrom mmcv.utils import TORCH_VERSION, digit_version, master_only\nfrom ..hook import HOOKS\nfrom .base import LoggerHook\n\n\n@HOOKS.register_module()\nclass TensorboardLoggerHook(LoggerHook):\n\n    def __init__(self,\n                 log_dir=None,\n                 interval=10,\n                 ignore_last=True,\n                 reset_flag=False,\n                 by_epoch=True):\n        super(TensorboardLoggerHook, self).__init__(interval, ignore_last,\n                                                    reset_flag, by_epoch)\n        self.log_dir = log_dir\n\n    @master_only\n    def before_run(self, runner):\n        super(TensorboardLoggerHook, self).before_run(runner)\n        if (digit_version(TORCH_VERSION) < digit_version('1.1')):\n            try:\n                from tensorboardX import SummaryWriter\n            except ImportError:\n                raise ImportError('Please install tensorboardX to use '\n                                  'TensorboardLoggerHook.')\n        else:\n            try:\n                from torch.utils.tensorboard import SummaryWriter\n            except ImportError:\n                raise ImportError(\n                    'Please run \"pip install future tensorboard\" to install '\n                    'the dependencies to use torch.utils.tensorboard '\n                    '(applicable to PyTorch 1.1 or higher)')\n\n        if self.log_dir is None:\n            self.log_dir = osp.join(runner.work_dir, 'tf_logs')\n        self.writer = SummaryWriter(self.log_dir)\n\n    @master_only\n    def log(self, runner):\n        tags = self.get_loggable_tags(runner, allow_text=True)\n        for tag, val in tags.items():\n            if isinstance(val, str):\n                self.writer.add_text(tag, val, self.get_iter(runner))\n            else:\n                self.writer.add_scalar(tag, val, self.get_iter(runner))\n\n    @master_only\n    def after_run(self, runner):\n        self.writer.close()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/logger/text.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport datetime\nimport os\nimport os.path as osp\nfrom collections import OrderedDict\n\nimport torch\nimport torch.distributed as dist\n\nfrom mmcv.fileio.file_client import FileClient\nfrom mmcv.utils import is_tuple_of, scandir\nfrom mmcv.fileio.io import dump\nfrom ..hook import HOOKS\nfrom .base import LoggerHook\n\n\n@HOOKS.register_module()\nclass TextLoggerHook(LoggerHook):\n    \"\"\"Logger hook in text.\n\n    In this logger hook, the information will be printed on terminal and\n    saved in json file.\n\n    Args:\n        by_epoch (bool, optional): Whether EpochBasedRunner is used.\n            Default: True.\n        interval (int, optional): Logging interval (every k iterations).\n            Default: 10.\n        ignore_last (bool, optional): Ignore the log of last iterations in each\n            epoch if less than :attr:`interval`. Default: True.\n        reset_flag (bool, optional): Whether to clear the output buffer after\n            logging. Default: False.\n        interval_exp_name (int, optional): Logging interval for experiment\n            name. This feature is to help users conveniently get the experiment\n            information from screen or log file. Default: 1000.\n        out_dir (str, optional): Logs are saved in ``runner.work_dir`` default.\n            If ``out_dir`` is specified, logs will be copied to a new directory\n            which is the concatenation of ``out_dir`` and the last level\n            directory of ``runner.work_dir``. Default: None.\n            `New in version 1.3.16.`\n        out_suffix (str or tuple[str], optional): Those filenames ending with\n            ``out_suffix`` will be copied to ``out_dir``.\n            Default: ('.log.json', '.log', '.py').\n            `New in version 1.3.16.`\n        keep_local (bool, optional): Whether to keep local log when\n            :attr:`out_dir` is specified. If False, the local log will be\n            removed. Default: True.\n            `New in version 1.3.16.`\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n            `New in version 1.3.16.`\n    \"\"\"\n\n    def __init__(self,\n                 by_epoch=True,\n                 interval=10,\n                 ignore_last=True,\n                 reset_flag=False,\n                 interval_exp_name=1000,\n                 out_dir=None,\n                 out_suffix=('.log.json', '.log', '.py'),\n                 keep_local=True,\n                 file_client_args=None):\n        super(TextLoggerHook, self).__init__(interval, ignore_last, reset_flag,\n                                             by_epoch)\n        self.by_epoch = by_epoch\n        self.time_sec_tot = 0\n        self.interval_exp_name = interval_exp_name\n\n        if out_dir is None and file_client_args is not None:\n            raise ValueError(\n                'file_client_args should be \"None\" when `out_dir` is not'\n                'specified.')\n        self.out_dir = out_dir\n\n        if not (out_dir is None or isinstance(out_dir, str)\n                or is_tuple_of(out_dir, str)):\n            raise TypeError('out_dir should be  \"None\" or string or tuple of '\n                            'string, but got {out_dir}')\n        self.out_suffix = out_suffix\n\n        self.keep_local = keep_local\n        self.file_client_args = file_client_args\n        if self.out_dir is not None:\n            self.file_client = FileClient.infer_client(file_client_args,\n                                                       self.out_dir)\n\n    def before_run(self, runner):\n        super(TextLoggerHook, self).before_run(runner)\n\n        if self.out_dir is not None:\n            self.file_client = FileClient.infer_client(self.file_client_args,\n                                                       self.out_dir)\n            # The final `self.out_dir` is the concatenation of `self.out_dir`\n            # and the last level directory of `runner.work_dir`\n            basename = osp.basename(runner.work_dir.rstrip(osp.sep))\n            self.out_dir = self.file_client.join_path(self.out_dir, basename)\n            runner.logger.info(\n                (f'Text logs will be saved to {self.out_dir} by '\n                 f'{self.file_client.name} after the training process.'))\n\n        self.start_iter = runner.iter\n        self.json_log_path = osp.join(runner.work_dir,\n                                      f'{runner.timestamp}.log.json')\n        if runner.meta is not None:\n            self._dump_log(runner.meta, runner)\n\n    def _get_max_memory(self, runner):\n        device = getattr(runner.model, 'output_device', None)\n        mem = torch.cuda.max_memory_allocated(device=device)\n        mem_mb = torch.tensor([mem / (1024 * 1024)],\n                              dtype=torch.int,\n                              device=device)\n        if runner.world_size > 1:\n            dist.reduce(mem_mb, 0, op=dist.ReduceOp.MAX)\n        return mem_mb.item()\n\n    def _log_info(self, log_dict, runner):\n        # print exp name for users to distinguish experiments\n        # at every ``interval_exp_name`` iterations and the end of each epoch\n        if runner.meta is not None and 'exp_name' in runner.meta:\n            if (self.every_n_iters(runner, self.interval_exp_name)) or (\n                    self.by_epoch and self.end_of_epoch(runner)):\n                exp_info = f'Exp name: {runner.meta[\"exp_name\"]}'\n                runner.logger.info(exp_info)\n\n        if log_dict['mode'] == 'train':\n            if isinstance(log_dict['lr'], dict):\n                lr_str = []\n                for k, val in log_dict['lr'].items():\n                    lr_str.append(f'lr_{k}: {val:.3e}')\n                lr_str = ' '.join(lr_str)\n            else:\n                lr_str = f'lr: {log_dict[\"lr\"]:.3e}'\n\n            # by epoch: Epoch [4][100/1000]\n            # by iter:  Iter [100/100000]\n            if self.by_epoch:\n                log_str = f'Epoch [{log_dict[\"epoch\"]}]' \\\n                          f'[{log_dict[\"iter\"]}/{len(runner.data_loader)}]\\t'\n            else:\n                log_str = f'Iter [{log_dict[\"iter\"]}/{runner.max_iters}]\\t'\n            log_str += f'{lr_str}, '\n\n            if 'time' in log_dict.keys():\n                self.time_sec_tot += (log_dict['time'] * self.interval)\n                time_sec_avg = self.time_sec_tot / (\n                    runner.iter - self.start_iter + 1)\n                eta_sec = time_sec_avg * (runner.max_iters - runner.iter - 1)\n                eta_str = str(datetime.timedelta(seconds=int(eta_sec)))\n                log_str += f'eta: {eta_str}, '\n                log_str += f'time: {log_dict[\"time\"]:.3f}, ' \\\n                           f'data_time: {log_dict[\"data_time\"]:.3f}, '\n                # statistic memory\n                if torch.cuda.is_available():\n                    log_str += f'memory: {log_dict[\"memory\"]}, '\n        else:\n            # val/test time\n            # here 1000 is the length of the val dataloader\n            # by epoch: Epoch[val] [4][1000]\n            # by iter: Iter[val] [1000]\n            if self.by_epoch:\n                log_str = f'Epoch({log_dict[\"mode\"]}) ' \\\n                    f'[{log_dict[\"epoch\"]}][{log_dict[\"iter\"]}]\\t'\n            else:\n                log_str = f'Iter({log_dict[\"mode\"]}) [{log_dict[\"iter\"]}]\\t'\n\n        log_items = []\n        for name, val in log_dict.items():\n            # TODO: resolve this hack\n            # these items have been in log_str\n            if name in [\n                    'mode', 'Epoch', 'iter', 'lr', 'time', 'data_time',\n                    'memory', 'epoch'\n            ]:\n                continue\n            if isinstance(val, float):\n                val = f'{val:.4f}'\n            log_items.append(f'{name}: {val}')\n        log_str += ', '.join(log_items)\n\n        runner.logger.info(log_str)\n\n    def _dump_log(self, log_dict, runner):\n        # dump log in json format\n        json_log = OrderedDict()\n        for k, v in log_dict.items():\n            json_log[k] = self._round_float(v)\n        # only append log at last line\n        if runner.rank == 0:\n            with open(self.json_log_path, 'a+') as f:\n                dump(json_log, f, file_format='json')\n                f.write('\\n')\n\n    def _round_float(self, items):\n        if isinstance(items, list):\n            return [self._round_float(item) for item in items]\n        elif isinstance(items, float):\n            return round(items, 5)\n        else:\n            return items\n\n    def log(self, runner):\n        if 'eval_iter_num' in runner.log_buffer.output:\n            # this doesn't modify runner.iter and is regardless of by_epoch\n            cur_iter = runner.log_buffer.output.pop('eval_iter_num')\n        else:\n            cur_iter = self.get_iter(runner, inner_iter=True)\n\n        log_dict = OrderedDict(\n            mode=self.get_mode(runner),\n            epoch=self.get_epoch(runner),\n            iter=cur_iter)\n\n        # only record lr of the first param group\n        cur_lr = runner.current_lr()\n        if isinstance(cur_lr, list):\n            log_dict['lr'] = cur_lr[0]\n        else:\n            assert isinstance(cur_lr, dict)\n            log_dict['lr'] = {}\n            for k, lr_ in cur_lr.items():\n                assert isinstance(lr_, list)\n                log_dict['lr'].update({k: lr_[0]})\n\n        if 'time' in runner.log_buffer.output:\n            # statistic memory\n            if torch.cuda.is_available():\n                log_dict['memory'] = self._get_max_memory(runner)\n\n        log_dict = dict(log_dict, **runner.log_buffer.output)\n\n        self._log_info(log_dict, runner)\n        self._dump_log(log_dict, runner)\n        return log_dict\n\n    def after_run(self, runner):\n        # copy or upload logs to self.out_dir\n        if self.out_dir is not None:\n            for filename in scandir(runner.work_dir, self.out_suffix, True):\n                local_filepath = osp.join(runner.work_dir, filename)\n                out_filepath = self.file_client.join_path(\n                    self.out_dir, filename)\n                with open(local_filepath, 'r') as f:\n                    self.file_client.put_text(f.read(), out_filepath)\n\n                runner.logger.info(\n                    (f'The file {local_filepath} has been uploaded to '\n                     f'{out_filepath}.'))\n\n                if not self.keep_local:\n                    os.remove(local_filepath)\n                    runner.logger.info(\n                        (f'{local_filepath} was removed due to the '\n                         '`self.keep_local=False`'))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/lr_updater.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numbers\nfrom math import cos, pi\n\nfrom mmcv.utils import is_list_of\nfrom .hook import HOOKS, Hook\n\n\nclass LrUpdaterHook(Hook):\n    \"\"\"LR Scheduler in MMCV.\n\n    Args:\n        by_epoch (bool): LR changes epoch by epoch\n        warmup (string): Type of warmup used. It can be None(use no warmup),\n            'constant', 'linear' or 'exp'\n        warmup_iters (int): The number of iterations or epochs that warmup\n            lasts\n        warmup_ratio (float): LR used at the beginning of warmup equals to\n            warmup_ratio * initial_lr\n        warmup_by_epoch (bool): When warmup_by_epoch == True, warmup_iters\n            means the number of epochs that warmup lasts, otherwise means the\n            number of iteration that warmup lasts\n    \"\"\"\n\n    def __init__(self,\n                 by_epoch=True,\n                 warmup=None,\n                 warmup_iters=0,\n                 warmup_ratio=0.1,\n                 warmup_by_epoch=False):\n        # validate the \"warmup\" argument\n        if warmup is not None:\n            if warmup not in ['constant', 'linear', 'exp']:\n                raise ValueError(\n                    f'\"{warmup}\" is not a supported type for warming up, valid'\n                    ' types are \"constant\" and \"linear\"')\n        if warmup is not None:\n            assert warmup_iters > 0, \\\n                '\"warmup_iters\" must be a positive integer'\n            assert 0 < warmup_ratio <= 1.0, \\\n                '\"warmup_ratio\" must be in range (0,1]'\n\n        self.by_epoch = by_epoch\n        self.warmup = warmup\n        self.warmup_iters = warmup_iters\n        self.warmup_ratio = warmup_ratio\n        self.warmup_by_epoch = warmup_by_epoch\n\n        if self.warmup_by_epoch:\n            self.warmup_epochs = self.warmup_iters\n            self.warmup_iters = None\n        else:\n            self.warmup_epochs = None\n\n        self.base_lr = []  # initial lr for all param groups\n        self.regular_lr = []  # expected lr if no warming up is performed\n\n    def _set_lr(self, runner, lr_groups):\n        if isinstance(runner.optimizer, dict):\n            for k, optim in runner.optimizer.items():\n                for param_group, lr in zip(optim.param_groups, lr_groups[k]):\n                    param_group['lr'] = lr\n        else:\n            for param_group, lr in zip(runner.optimizer.param_groups,\n                                       lr_groups):\n                param_group['lr'] = lr\n\n    def get_lr(self, runner, base_lr):\n        raise NotImplementedError\n\n    def get_regular_lr(self, runner):\n        if isinstance(runner.optimizer, dict):\n            lr_groups = {}\n            for k in runner.optimizer.keys():\n                _lr_group = [\n                    self.get_lr(runner, _base_lr)\n                    for _base_lr in self.base_lr[k]\n                ]\n                lr_groups.update({k: _lr_group})\n\n            return lr_groups\n        else:\n            return [self.get_lr(runner, _base_lr) for _base_lr in self.base_lr]\n\n    def get_warmup_lr(self, cur_iters):\n\n        def _get_warmup_lr(cur_iters, regular_lr):\n            if self.warmup == 'constant':\n                warmup_lr = [_lr * self.warmup_ratio for _lr in regular_lr]\n            elif self.warmup == 'linear':\n                k = (1 - cur_iters / self.warmup_iters) * (1 -\n                                                           self.warmup_ratio)\n                warmup_lr = [_lr * (1 - k) for _lr in regular_lr]\n            elif self.warmup == 'exp':\n                k = self.warmup_ratio**(1 - cur_iters / self.warmup_iters)\n                warmup_lr = [_lr * k for _lr in regular_lr]\n            return warmup_lr\n\n        if isinstance(self.regular_lr, dict):\n            lr_groups = {}\n            for key, regular_lr in self.regular_lr.items():\n                lr_groups[key] = _get_warmup_lr(cur_iters, regular_lr)\n            return lr_groups\n        else:\n            return _get_warmup_lr(cur_iters, self.regular_lr)\n\n    def before_run(self, runner):\n        # NOTE: when resuming from a checkpoint, if 'initial_lr' is not saved,\n        # it will be set according to the optimizer params\n        if isinstance(runner.optimizer, dict):\n            self.base_lr = {}\n            for k, optim in runner.optimizer.items():\n                for group in optim.param_groups:\n                    group.setdefault('initial_lr', group['lr'])\n                _base_lr = [\n                    group['initial_lr'] for group in optim.param_groups\n                ]\n                self.base_lr.update({k: _base_lr})\n        else:\n            for group in runner.optimizer.param_groups:\n                group.setdefault('initial_lr', group['lr'])\n            self.base_lr = [\n                group['initial_lr'] for group in runner.optimizer.param_groups\n            ]\n\n    def before_train_epoch(self, runner):\n        if self.warmup_iters is None:\n            epoch_len = len(runner.data_loader)\n            self.warmup_iters = self.warmup_epochs * epoch_len\n\n        if not self.by_epoch:\n            return\n\n        self.regular_lr = self.get_regular_lr(runner)\n        self._set_lr(runner, self.regular_lr)\n\n    def before_train_iter(self, runner):\n        cur_iter = runner.iter\n        if not self.by_epoch:\n            self.regular_lr = self.get_regular_lr(runner)\n            if self.warmup is None or cur_iter >= self.warmup_iters:\n                self._set_lr(runner, self.regular_lr)\n            else:\n                warmup_lr = self.get_warmup_lr(cur_iter)\n                self._set_lr(runner, warmup_lr)\n        elif self.by_epoch:\n            if self.warmup is None or cur_iter > self.warmup_iters:\n                return\n            elif cur_iter == self.warmup_iters:\n                self._set_lr(runner, self.regular_lr)\n            else:\n                warmup_lr = self.get_warmup_lr(cur_iter)\n                self._set_lr(runner, warmup_lr)\n\n\n@HOOKS.register_module()\nclass FixedLrUpdaterHook(LrUpdaterHook):\n\n    def __init__(self, **kwargs):\n        super(FixedLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        return base_lr\n\n\n@HOOKS.register_module()\nclass StepLrUpdaterHook(LrUpdaterHook):\n    \"\"\"Step LR scheduler with min_lr clipping.\n\n    Args:\n        step (int | list[int]): Step to decay the LR. If an int value is given,\n            regard it as the decay interval. If a list is given, decay LR at\n            these steps.\n        gamma (float, optional): Decay LR ratio. Default: 0.1.\n        min_lr (float, optional): Minimum LR value to keep. If LR after decay\n            is lower than `min_lr`, it will be clipped to this value. If None\n            is given, we don't perform lr clipping. Default: None.\n    \"\"\"\n\n    def __init__(self, step, gamma=0.1, min_lr=None, **kwargs):\n        if isinstance(step, list):\n            assert is_list_of(step, int)\n            assert all([s > 0 for s in step])\n        elif isinstance(step, int):\n            assert step > 0\n        else:\n            raise TypeError('\"step\" must be a list or integer')\n        self.step = step\n        self.gamma = gamma\n        self.min_lr = min_lr\n        super(StepLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        progress = runner.epoch if self.by_epoch else runner.iter\n\n        # calculate exponential term\n        if isinstance(self.step, int):\n            exp = progress // self.step\n        else:\n            exp = len(self.step)\n            for i, s in enumerate(self.step):\n                if progress < s:\n                    exp = i\n                    break\n\n        lr = base_lr * (self.gamma**exp)\n        if self.min_lr is not None:\n            # clip to a minimum value\n            lr = max(lr, self.min_lr)\n        return lr\n\n\n@HOOKS.register_module()\nclass ExpLrUpdaterHook(LrUpdaterHook):\n\n    def __init__(self, gamma, **kwargs):\n        self.gamma = gamma\n        super(ExpLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        progress = runner.epoch if self.by_epoch else runner.iter\n        return base_lr * self.gamma**progress\n\n\n@HOOKS.register_module()\nclass PolyLrUpdaterHook(LrUpdaterHook):\n\n    def __init__(self, power=1., min_lr=0., **kwargs):\n        self.power = power\n        self.min_lr = min_lr\n        super(PolyLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        if self.by_epoch:\n            progress = runner.epoch\n            max_progress = runner.max_epochs\n        else:\n            progress = runner.iter\n            max_progress = runner.max_iters\n        coeff = (1 - progress / max_progress)**self.power\n        return (base_lr - self.min_lr) * coeff + self.min_lr\n\n\n@HOOKS.register_module()\nclass InvLrUpdaterHook(LrUpdaterHook):\n\n    def __init__(self, gamma, power=1., **kwargs):\n        self.gamma = gamma\n        self.power = power\n        super(InvLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        progress = runner.epoch if self.by_epoch else runner.iter\n        return base_lr * (1 + self.gamma * progress)**(-self.power)\n\n\n@HOOKS.register_module()\nclass CosineAnnealingLrUpdaterHook(LrUpdaterHook):\n\n    def __init__(self, min_lr=None, min_lr_ratio=None, **kwargs):\n        assert (min_lr is None) ^ (min_lr_ratio is None)\n        self.min_lr = min_lr\n        self.min_lr_ratio = min_lr_ratio\n        super(CosineAnnealingLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        if self.by_epoch:\n            progress = runner.epoch\n            max_progress = runner.max_epochs\n        else:\n            progress = runner.iter\n            max_progress = runner.max_iters\n\n        if self.min_lr_ratio is not None:\n            target_lr = base_lr * self.min_lr_ratio\n        else:\n            target_lr = self.min_lr\n        return annealing_cos(base_lr, target_lr, progress / max_progress)\n\n\n@HOOKS.register_module()\nclass FlatCosineAnnealingLrUpdaterHook(LrUpdaterHook):\n    \"\"\"Flat + Cosine lr schedule.\n\n    Modified from https://github.com/fastai/fastai/blob/master/fastai/callback/schedule.py#L128 # noqa: E501\n\n    Args:\n        start_percent (float): When to start annealing the learning rate\n            after the percentage of the total training steps.\n            The value should be in range [0, 1).\n            Default: 0.75\n        min_lr (float, optional): The minimum lr. Default: None.\n        min_lr_ratio (float, optional): The ratio of minimum lr to the base lr.\n            Either `min_lr` or `min_lr_ratio` should be specified.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 start_percent=0.75,\n                 min_lr=None,\n                 min_lr_ratio=None,\n                 **kwargs):\n        assert (min_lr is None) ^ (min_lr_ratio is None)\n        if start_percent < 0 or start_percent > 1 or not isinstance(\n                start_percent, float):\n            raise ValueError(\n                'expected float between 0 and 1 start_percent, but '\n                f'got {start_percent}')\n        self.start_percent = start_percent\n        self.min_lr = min_lr\n        self.min_lr_ratio = min_lr_ratio\n        super(FlatCosineAnnealingLrUpdaterHook, self).__init__(**kwargs)\n\n    def get_lr(self, runner, base_lr):\n        if self.by_epoch:\n            start = round(runner.max_epochs * self.start_percent)\n            progress = runner.epoch - start\n            max_progress = runner.max_epochs - start\n        else:\n            start = round(runner.max_iters * self.start_percent)\n            progress = runner.iter - start\n            max_progress = runner.max_iters - start\n\n        if self.min_lr_ratio is not None:\n            target_lr = base_lr * self.min_lr_ratio\n        else:\n            target_lr = self.min_lr\n\n        if progress < 0:\n            return base_lr\n        else:\n            return annealing_cos(base_lr, target_lr, progress / max_progress)\n\n\n@HOOKS.register_module()\nclass CosineRestartLrUpdaterHook(LrUpdaterHook):\n    \"\"\"Cosine annealing with restarts learning rate scheme.\n\n    Args:\n        periods (list[int]): Periods for each cosine anneling cycle.\n        restart_weights (list[float], optional): Restart weights at each\n            restart iteration. Default: [1].\n        min_lr (float, optional): The minimum lr. Default: None.\n        min_lr_ratio (float, optional): The ratio of minimum lr to the base lr.\n            Either `min_lr` or `min_lr_ratio` should be specified.\n            Default: None.\n    \"\"\"\n\n    def __init__(self,\n                 periods,\n                 restart_weights=[1],\n                 min_lr=None,\n                 min_lr_ratio=None,\n                 **kwargs):\n        assert (min_lr is None) ^ (min_lr_ratio is None)\n        self.periods = periods\n        self.min_lr = min_lr\n        self.min_lr_ratio = min_lr_ratio\n        self.restart_weights = restart_weights\n        assert (len(self.periods) == len(self.restart_weights)\n                ), 'periods and restart_weights should have the same length.'\n        super(CosineRestartLrUpdaterHook, self).__init__(**kwargs)\n\n        self.cumulative_periods = [\n            sum(self.periods[0:i + 1]) for i in range(0, len(self.periods))\n        ]\n\n    def get_lr(self, runner, base_lr):\n        if self.by_epoch:\n            progress = runner.epoch\n        else:\n            progress = runner.iter\n\n        if self.min_lr_ratio is not None:\n            target_lr = base_lr * self.min_lr_ratio\n        else:\n            target_lr = self.min_lr\n\n        idx = get_position_from_periods(progress, self.cumulative_periods)\n        current_weight = self.restart_weights[idx]\n        nearest_restart = 0 if idx == 0 else self.cumulative_periods[idx - 1]\n        current_periods = self.periods[idx]\n\n        alpha = min((progress - nearest_restart) / current_periods, 1)\n        return annealing_cos(base_lr, target_lr, alpha, current_weight)\n\n\ndef get_position_from_periods(iteration, cumulative_periods):\n    \"\"\"Get the position from a period list.\n\n    It will return the index of the right-closest number in the period list.\n    For example, the cumulative_periods = [100, 200, 300, 400],\n    if iteration == 50, return 0;\n    if iteration == 210, return 2;\n    if iteration == 300, return 3.\n\n    Args:\n        iteration (int): Current iteration.\n        cumulative_periods (list[int]): Cumulative period list.\n\n    Returns:\n        int: The position of the right-closest number in the period list.\n    \"\"\"\n    for i, period in enumerate(cumulative_periods):\n        if iteration < period:\n            return i\n    raise ValueError(f'Current iteration {iteration} exceeds '\n                     f'cumulative_periods {cumulative_periods}')\n\n\n@HOOKS.register_module()\nclass CyclicLrUpdaterHook(LrUpdaterHook):\n    \"\"\"Cyclic LR Scheduler.\n\n    Implement the cyclical learning rate policy (CLR) described in\n    https://arxiv.org/pdf/1506.01186.pdf\n\n    Different from the original paper, we use cosine annealing rather than\n    triangular policy inside a cycle. This improves the performance in the\n    3D detection area.\n\n    Args:\n        by_epoch (bool): Whether to update LR by epoch.\n        target_ratio (tuple[float]): Relative ratio of the highest LR and the\n            lowest LR to the initial LR.\n        cyclic_times (int): Number of cycles during training\n        step_ratio_up (float): The ratio of the increasing process of LR in\n            the total cycle.\n        anneal_strategy (str): {'cos', 'linear'}\n            Specifies the annealing strategy: 'cos' for cosine annealing,\n            'linear' for linear annealing. Default: 'cos'.\n    \"\"\"\n\n    def __init__(self,\n                 by_epoch=False,\n                 target_ratio=(10, 1e-4),\n                 cyclic_times=1,\n                 step_ratio_up=0.4,\n                 anneal_strategy='cos',\n                 **kwargs):\n        if isinstance(target_ratio, float):\n            target_ratio = (target_ratio, target_ratio / 1e5)\n        elif isinstance(target_ratio, tuple):\n            target_ratio = (target_ratio[0], target_ratio[0] / 1e5) \\\n                if len(target_ratio) == 1 else target_ratio\n        else:\n            raise ValueError('target_ratio should be either float '\n                             f'or tuple, got {type(target_ratio)}')\n\n        assert len(target_ratio) == 2, \\\n            '\"target_ratio\" must be list or tuple of two floats'\n        assert 0 <= step_ratio_up < 1.0, \\\n            '\"step_ratio_up\" must be in range [0,1)'\n\n        self.target_ratio = target_ratio\n        self.cyclic_times = cyclic_times\n        self.step_ratio_up = step_ratio_up\n        self.lr_phases = []  # init lr_phases\n        # validate anneal_strategy\n        if anneal_strategy not in ['cos', 'linear']:\n            raise ValueError('anneal_strategy must be one of \"cos\" or '\n                             f'\"linear\", instead got {anneal_strategy}')\n        elif anneal_strategy == 'cos':\n            self.anneal_func = annealing_cos\n        elif anneal_strategy == 'linear':\n            self.anneal_func = annealing_linear\n\n        assert not by_epoch, \\\n            'currently only support \"by_epoch\" = False'\n        super(CyclicLrUpdaterHook, self).__init__(by_epoch, **kwargs)\n\n    def before_run(self, runner):\n        super(CyclicLrUpdaterHook, self).before_run(runner)\n        # initiate lr_phases\n        # total lr_phases are separated as up and down\n        max_iter_per_phase = runner.max_iters // self.cyclic_times\n        iter_up_phase = int(self.step_ratio_up * max_iter_per_phase)\n        self.lr_phases.append(\n            [0, iter_up_phase, max_iter_per_phase, 1, self.target_ratio[0]])\n        self.lr_phases.append([\n            iter_up_phase, max_iter_per_phase, max_iter_per_phase,\n            self.target_ratio[0], self.target_ratio[1]\n        ])\n\n    def get_lr(self, runner, base_lr):\n        curr_iter = runner.iter\n        for (start_iter, end_iter, max_iter_per_phase, start_ratio,\n             end_ratio) in self.lr_phases:\n            curr_iter %= max_iter_per_phase\n            if start_iter <= curr_iter < end_iter:\n                progress = curr_iter - start_iter\n                return self.anneal_func(base_lr * start_ratio,\n                                        base_lr * end_ratio,\n                                        progress / (end_iter - start_iter))\n\n\n@HOOKS.register_module()\nclass OneCycleLrUpdaterHook(LrUpdaterHook):\n    \"\"\"One Cycle LR Scheduler.\n\n    The 1cycle learning rate policy changes the learning rate after every\n    batch. The one cycle learning rate policy is described in\n    https://arxiv.org/pdf/1708.07120.pdf\n\n    Args:\n        max_lr (float or list): Upper learning rate boundaries in the cycle\n            for each parameter group.\n        total_steps (int, optional): The total number of steps in the cycle.\n            Note that if a value is not provided here, it will be the max_iter\n            of runner. Default: None.\n        pct_start (float): The percentage of the cycle (in number of steps)\n            spent increasing the learning rate.\n            Default: 0.3\n        anneal_strategy (str): {'cos', 'linear'}\n            Specifies the annealing strategy: 'cos' for cosine annealing,\n            'linear' for linear annealing.\n            Default: 'cos'\n        div_factor (float): Determines the initial learning rate via\n            initial_lr = max_lr/div_factor\n            Default: 25\n        final_div_factor (float): Determines the minimum learning rate via\n            min_lr = initial_lr/final_div_factor\n            Default: 1e4\n        three_phase (bool): If three_phase is True, use a third phase of the\n            schedule to annihilate the learning rate according to\n            final_div_factor instead of modifying the second phase (the first\n            two phases will be symmetrical about the step indicated by\n            pct_start).\n            Default: False\n    \"\"\"\n\n    def __init__(self,\n                 max_lr,\n                 total_steps=None,\n                 pct_start=0.3,\n                 anneal_strategy='cos',\n                 div_factor=25,\n                 final_div_factor=1e4,\n                 three_phase=False,\n                 **kwargs):\n        # validate by_epoch, currently only support by_epoch = False\n        if 'by_epoch' not in kwargs:\n            kwargs['by_epoch'] = False\n        else:\n            assert not kwargs['by_epoch'], \\\n                'currently only support \"by_epoch\" = False'\n        if not isinstance(max_lr, (numbers.Number, list, dict)):\n            raise ValueError('the type of max_lr must be the one of list or '\n                             f'dict, but got {type(max_lr)}')\n        self._max_lr = max_lr\n        if total_steps is not None:\n            if not isinstance(total_steps, int):\n                raise ValueError('the type of total_steps must be int, but'\n                                 f'got {type(total_steps)}')\n            self.total_steps = total_steps\n        # validate pct_start\n        if pct_start < 0 or pct_start > 1 or not isinstance(pct_start, float):\n            raise ValueError('expected float between 0 and 1 pct_start, but '\n                             f'got {pct_start}')\n        self.pct_start = pct_start\n        # validate anneal_strategy\n        if anneal_strategy not in ['cos', 'linear']:\n            raise ValueError('anneal_strategy must be one of \"cos\" or '\n                             f'\"linear\", instead got {anneal_strategy}')\n        elif anneal_strategy == 'cos':\n            self.anneal_func = annealing_cos\n        elif anneal_strategy == 'linear':\n            self.anneal_func = annealing_linear\n        self.div_factor = div_factor\n        self.final_div_factor = final_div_factor\n        self.three_phase = three_phase\n        self.lr_phases = []  # init lr_phases\n        super(OneCycleLrUpdaterHook, self).__init__(**kwargs)\n\n    def before_run(self, runner):\n        if hasattr(self, 'total_steps'):\n            total_steps = self.total_steps\n        else:\n            total_steps = runner.max_iters\n        if total_steps < runner.max_iters:\n            raise ValueError(\n                'The total steps must be greater than or equal to max '\n                f'iterations {runner.max_iters} of runner, but total steps '\n                f'is {total_steps}.')\n\n        if isinstance(runner.optimizer, dict):\n            self.base_lr = {}\n            for k, optim in runner.optimizer.items():\n                _max_lr = format_param(k, optim, self._max_lr)\n                self.base_lr[k] = [lr / self.div_factor for lr in _max_lr]\n                for group, lr in zip(optim.param_groups, self.base_lr[k]):\n                    group.setdefault('initial_lr', lr)\n        else:\n            k = type(runner.optimizer).__name__\n            _max_lr = format_param(k, runner.optimizer, self._max_lr)\n            self.base_lr = [lr / self.div_factor for lr in _max_lr]\n            for group, lr in zip(runner.optimizer.param_groups, self.base_lr):\n                group.setdefault('initial_lr', lr)\n\n        if self.three_phase:\n            self.lr_phases.append(\n                [float(self.pct_start * total_steps) - 1, 1, self.div_factor])\n            self.lr_phases.append([\n                float(2 * self.pct_start * total_steps) - 2, self.div_factor, 1\n            ])\n            self.lr_phases.append(\n                [total_steps - 1, 1, 1 / self.final_div_factor])\n        else:\n            self.lr_phases.append(\n                [float(self.pct_start * total_steps) - 1, 1, self.div_factor])\n            self.lr_phases.append(\n                [total_steps - 1, self.div_factor, 1 / self.final_div_factor])\n\n    def get_lr(self, runner, base_lr):\n        curr_iter = runner.iter\n        start_iter = 0\n        for i, (end_iter, start_lr, end_lr) in enumerate(self.lr_phases):\n            if curr_iter <= end_iter:\n                pct = (curr_iter - start_iter) / (end_iter - start_iter)\n                lr = self.anneal_func(base_lr * start_lr, base_lr * end_lr,\n                                      pct)\n                break\n            start_iter = end_iter\n        return lr\n\n\ndef annealing_cos(start, end, factor, weight=1):\n    \"\"\"Calculate annealing cos learning rate.\n\n    Cosine anneal from `weight * start + (1 - weight) * end` to `end` as\n    percentage goes from 0.0 to 1.0.\n\n    Args:\n        start (float): The starting learning rate of the cosine annealing.\n        end (float): The ending learing rate of the cosine annealing.\n        factor (float): The coefficient of `pi` when calculating the current\n            percentage. Range from 0.0 to 1.0.\n        weight (float, optional): The combination factor of `start` and `end`\n            when calculating the actual starting learning rate. Default to 1.\n    \"\"\"\n    cos_out = cos(pi * factor) + 1\n    return end + 0.5 * weight * (start - end) * cos_out\n\n\ndef annealing_linear(start, end, factor):\n    \"\"\"Calculate annealing linear learning rate.\n\n    Linear anneal from `start` to `end` as percentage goes from 0.0 to 1.0.\n\n    Args:\n        start (float): The starting learning rate of the linear annealing.\n        end (float): The ending learing rate of the linear annealing.\n        factor (float): The coefficient of `pi` when calculating the current\n            percentage. Range from 0.0 to 1.0.\n    \"\"\"\n    return start + (end - start) * factor\n\n\ndef format_param(name, optim, param):\n    if isinstance(param, numbers.Number):\n        return [param] * len(optim.param_groups)\n    elif isinstance(param, (list, tuple)):  # multi param groups\n        if len(param) != len(optim.param_groups):\n            raise ValueError(f'expected {len(optim.param_groups)} '\n                             f'values for {name}, got {len(param)}')\n        return param\n    else:  # multi optimizers\n        if name not in param:\n            raise KeyError(f'{name} is not found in {param.keys()}')\n        return param[name]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/optimizer.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nfrom collections import defaultdict\nfrom itertools import chain\n\nfrom torch.nn.utils import clip_grad\n\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom mmcv.utils import LossScaler, wrap_fp16_model, TORCH_VERSION, digit_version, allreduce_grads\nfrom .hook import HOOKS, Hook\n\ntry:\n    # If PyTorch version >= 1.6.0, torch.cuda.amp.GradScaler would be imported\n    # and used; otherwise, auto fp16 will adopt mmcv's implementation.\n    from torch.cuda.amp import GradScaler\nexcept ImportError:\n    pass\n\n\n@HOOKS.register_module()\nclass OptimizerHook(Hook):\n\n    def __init__(self, grad_clip=None):\n        self.grad_clip = grad_clip\n\n    def clip_grads(self, params):\n        params = list(\n            filter(lambda p: p.requires_grad and p.grad is not None, params))\n        if len(params) > 0:\n            return clip_grad.clip_grad_norm_(params, **self.grad_clip)\n\n    def after_train_iter(self, runner):\n        runner.optimizer.zero_grad()\n        runner.outputs['loss'].backward()\n        if self.grad_clip is not None:\n            grad_norm = self.clip_grads(runner.model.parameters())\n            if grad_norm is not None:\n                # Add grad norm to the logger\n                runner.log_buffer.update({'grad_norm': float(grad_norm)},\n                                         runner.outputs['num_samples'])\n        runner.optimizer.step()\n\n\n@HOOKS.register_module()\nclass GradientCumulativeOptimizerHook(OptimizerHook):\n    \"\"\"Optimizer Hook implements multi-iters gradient cumulating.\n\n    Args:\n        cumulative_iters (int, optional): Num of gradient cumulative iters.\n            The optimizer will step every `cumulative_iters` iters.\n            Defaults to 1.\n\n    Examples:\n        >>> # Use cumulative_iters to simulate a large batch size\n        >>> # It is helpful when the hardware cannot handle a large batch size.\n        >>> loader = DataLoader(data, batch_size=64)\n        >>> optim_hook = GradientCumulativeOptimizerHook(cumulative_iters=4)\n        >>> # almost equals to\n        >>> loader = DataLoader(data, batch_size=256)\n        >>> optim_hook = OptimizerHook()\n    \"\"\"\n\n    def __init__(self, cumulative_iters=1, **kwargs):\n        super(GradientCumulativeOptimizerHook, self).__init__(**kwargs)\n\n        assert isinstance(cumulative_iters, int) and cumulative_iters > 0, \\\n            f'cumulative_iters only accepts positive int, but got ' \\\n            f'{type(cumulative_iters)} instead.'\n\n        self.cumulative_iters = cumulative_iters\n        self.divisible_iters = 0\n        self.remainder_iters = 0\n        self.initialized = False\n\n    def has_batch_norm(self, module):\n        if isinstance(module, _BatchNorm):\n            return True\n        for m in module.children():\n            if self.has_batch_norm(m):\n                return True\n        return False\n\n    def _init(self, runner):\n        if runner.iter % self.cumulative_iters != 0:\n            runner.logger.warning(\n                'Resume iter number is not divisible by cumulative_iters in '\n                'GradientCumulativeOptimizerHook, which means the gradient of '\n                'some iters is lost and the result may be influenced slightly.'\n            )\n\n        if self.has_batch_norm(runner.model) and self.cumulative_iters > 1:\n            runner.logger.warning(\n                'GradientCumulativeOptimizerHook may slightly decrease '\n                'performance if the model has BatchNorm layers.')\n\n        residual_iters = runner.max_iters - runner.iter\n\n        self.divisible_iters = (\n            residual_iters // self.cumulative_iters * self.cumulative_iters)\n        self.remainder_iters = residual_iters - self.divisible_iters\n\n        self.initialized = True\n\n    def after_train_iter(self, runner):\n        if not self.initialized:\n            self._init(runner)\n\n        if runner.iter < self.divisible_iters:\n            loss_factor = self.cumulative_iters\n        else:\n            loss_factor = self.remainder_iters\n        loss = runner.outputs['loss']\n        loss = loss / loss_factor\n        loss.backward()\n\n        if (self.every_n_iters(runner, self.cumulative_iters)\n                or self.is_last_iter(runner)):\n\n            if self.grad_clip is not None:\n                grad_norm = self.clip_grads(runner.model.parameters())\n                if grad_norm is not None:\n                    # Add grad norm to the logger\n                    runner.log_buffer.update({'grad_norm': float(grad_norm)},\n                                             runner.outputs['num_samples'])\n            runner.optimizer.step()\n            runner.optimizer.zero_grad()\n\n\nif (digit_version(TORCH_VERSION) >= digit_version('1.6.0')):\n\n    @HOOKS.register_module()\n    class Fp16OptimizerHook(OptimizerHook):\n        \"\"\"FP16 optimizer hook (using PyTorch's implementation).\n\n        If you are using PyTorch >= 1.6, torch.cuda.amp is used as the backend,\n        to take care of the optimization procedure.\n\n        Args:\n            loss_scale (float | str | dict): Scale factor configuration.\n                If loss_scale is a float, static loss scaling will be used with\n                the specified scale. If loss_scale is a string, it must be\n                'dynamic', then dynamic loss scaling will be used.\n                It can also be a dict containing arguments of GradScalar.\n                Defaults to 512. For Pytorch >= 1.6, mmcv uses official\n                implementation of GradScaler. If you use a dict version of\n                loss_scale to create GradScaler, please refer to:\n                https://pytorch.org/docs/stable/amp.html#torch.cuda.amp.GradScaler\n                for the parameters.\n\n        Examples:\n            >>> loss_scale = dict(\n            ...     init_scale=65536.0,\n            ...     growth_factor=2.0,\n            ...     backoff_factor=0.5,\n            ...     growth_interval=2000\n            ... )\n            >>> optimizer_hook = Fp16OptimizerHook(loss_scale=loss_scale)\n        \"\"\"\n\n        def __init__(self,\n                     grad_clip=None,\n                     coalesce=True,\n                     bucket_size_mb=-1,\n                     loss_scale=512.,\n                     distributed=True):\n            self.grad_clip = grad_clip\n            self.coalesce = coalesce\n            self.bucket_size_mb = bucket_size_mb\n            self.distributed = distributed\n            self._scale_update_param = None\n            if loss_scale == 'dynamic':\n                self.loss_scaler = GradScaler()\n            elif isinstance(loss_scale, float):\n                self._scale_update_param = loss_scale\n                self.loss_scaler = GradScaler(init_scale=loss_scale)\n            elif isinstance(loss_scale, dict):\n                self.loss_scaler = GradScaler(**loss_scale)\n            else:\n                raise ValueError('loss_scale must be of type float, dict, or '\n                                 f'\"dynamic\", got {loss_scale}')\n\n        def before_run(self, runner):\n            \"\"\"Preparing steps before Mixed Precision Training.\"\"\"\n            # wrap model mode to fp16\n            wrap_fp16_model(runner.model)\n            # resume from state dict\n            if 'fp16' in runner.meta and 'loss_scaler' in runner.meta['fp16']:\n                scaler_state_dict = runner.meta['fp16']['loss_scaler']\n                self.loss_scaler.load_state_dict(scaler_state_dict)\n\n        def copy_grads_to_fp32(self, fp16_net, fp32_weights):\n            \"\"\"Copy gradients from fp16 model to fp32 weight copy.\"\"\"\n            for fp32_param, fp16_param in zip(fp32_weights,\n                                              fp16_net.parameters()):\n                if fp16_param.grad is not None:\n                    if fp32_param.grad is None:\n                        fp32_param.grad = fp32_param.data.new(\n                            fp32_param.size())\n                    fp32_param.grad.copy_(fp16_param.grad)\n\n        def copy_params_to_fp16(self, fp16_net, fp32_weights):\n            \"\"\"Copy updated params from fp32 weight copy to fp16 model.\"\"\"\n            for fp16_param, fp32_param in zip(fp16_net.parameters(),\n                                              fp32_weights):\n                fp16_param.data.copy_(fp32_param.data)\n\n        def after_train_iter(self, runner):\n            \"\"\"Backward optimization steps for Mixed Precision Training. For\n            dynamic loss scaling, please refer to\n            https://pytorch.org/docs/stable/amp.html#torch.cuda.amp.GradScaler.\n\n            1. Scale the loss by a scale factor.\n            2. Backward the loss to obtain the gradients.\n            3. Unscale the optimizer’s gradient tensors.\n            4. Call optimizer.step() and update scale factor.\n            5. Save loss_scaler state_dict for resume purpose.\n            \"\"\"\n            # clear grads of last iteration\n            runner.model.zero_grad()\n            runner.optimizer.zero_grad()\n\n            self.loss_scaler.scale(runner.outputs['loss']).backward()\n            self.loss_scaler.unscale_(runner.optimizer)\n            # grad clip\n            if self.grad_clip is not None:\n                grad_norm = self.clip_grads(runner.model.parameters())\n                if grad_norm is not None:\n                    # Add grad norm to the logger\n                    runner.log_buffer.update({'grad_norm': float(grad_norm)},\n                                             runner.outputs['num_samples'])\n            # backward and update scaler\n            self.loss_scaler.step(runner.optimizer)\n            self.loss_scaler.update(self._scale_update_param)\n\n            # save state_dict of loss_scaler\n            runner.meta.setdefault(\n                'fp16', {})['loss_scaler'] = self.loss_scaler.state_dict()\n\n    @HOOKS.register_module()\n    class GradientCumulativeFp16OptimizerHook(GradientCumulativeOptimizerHook,\n                                              Fp16OptimizerHook):\n        \"\"\"Fp16 optimizer Hook (using PyTorch's implementation) implements\n        multi-iters gradient cumulating.\n\n        If you are using PyTorch >= 1.6, torch.cuda.amp is used as the backend,\n        to take care of the optimization procedure.\n        \"\"\"\n\n        def __init__(self, *args, **kwargs):\n            super(GradientCumulativeFp16OptimizerHook,\n                  self).__init__(*args, **kwargs)\n\n        def after_train_iter(self, runner):\n            if not self.initialized:\n                self._init(runner)\n\n            if runner.iter < self.divisible_iters:\n                loss_factor = self.cumulative_iters\n            else:\n                loss_factor = self.remainder_iters\n            loss = runner.outputs['loss']\n            loss = loss / loss_factor\n\n            self.loss_scaler.scale(loss).backward()\n\n            if (self.every_n_iters(runner, self.cumulative_iters)\n                    or self.is_last_iter(runner)):\n\n                # copy fp16 grads in the model to fp32 params in the optimizer\n                self.loss_scaler.unscale_(runner.optimizer)\n\n                if self.grad_clip is not None:\n                    grad_norm = self.clip_grads(runner.model.parameters())\n                    if grad_norm is not None:\n                        # Add grad norm to the logger\n                        runner.log_buffer.update(\n                            {'grad_norm': float(grad_norm)},\n                            runner.outputs['num_samples'])\n\n                # backward and update scaler\n                self.loss_scaler.step(runner.optimizer)\n                self.loss_scaler.update(self._scale_update_param)\n\n                # save state_dict of loss_scaler\n                runner.meta.setdefault(\n                    'fp16', {})['loss_scaler'] = self.loss_scaler.state_dict()\n\n                # clear grads\n                runner.model.zero_grad()\n                runner.optimizer.zero_grad()\n\nelse:\n\n    @HOOKS.register_module()\n    class Fp16OptimizerHook(OptimizerHook):\n        \"\"\"FP16 optimizer hook (mmcv's implementation).\n\n        The steps of fp16 optimizer is as follows.\n        1. Scale the loss value.\n        2. BP in the fp16 model.\n        2. Copy gradients from fp16 model to fp32 weights.\n        3. Update fp32 weights.\n        4. Copy updated parameters from fp32 weights to fp16 model.\n\n        Refer to https://arxiv.org/abs/1710.03740 for more details.\n\n        Args:\n            loss_scale (float | str | dict): Scale factor configuration.\n                If loss_scale is a float, static loss scaling will be used with\n                the specified scale. If loss_scale is a string, it must be\n                'dynamic', then dynamic loss scaling will be used.\n                It can also be a dict containing arguments of LossScaler.\n                Defaults to 512.\n        \"\"\"\n\n        def __init__(self,\n                     grad_clip=None,\n                     coalesce=True,\n                     bucket_size_mb=-1,\n                     loss_scale=512.,\n                     distributed=True):\n            self.grad_clip = grad_clip\n            self.coalesce = coalesce\n            self.bucket_size_mb = bucket_size_mb\n            self.distributed = distributed\n            if loss_scale == 'dynamic':\n                self.loss_scaler = LossScaler(mode='dynamic')\n            elif isinstance(loss_scale, float):\n                self.loss_scaler = LossScaler(\n                    init_scale=loss_scale, mode='static')\n            elif isinstance(loss_scale, dict):\n                self.loss_scaler = LossScaler(**loss_scale)\n            else:\n                raise ValueError('loss_scale must be of type float, dict, or '\n                                 f'\"dynamic\", got {loss_scale}')\n\n        def before_run(self, runner):\n            \"\"\"Preparing steps before Mixed Precision Training.\n\n            1. Make a master copy of fp32 weights for optimization.\n            2. Convert the main model from fp32 to fp16.\n            \"\"\"\n            # keep a copy of fp32 weights\n            old_groups = runner.optimizer.param_groups\n            runner.optimizer.param_groups = copy.deepcopy(\n                runner.optimizer.param_groups)\n            state = defaultdict(dict)\n            p_map = {\n                old_p: p\n                for old_p, p in zip(\n                    chain(*(g['params'] for g in old_groups)),\n                    chain(*(g['params']\n                            for g in runner.optimizer.param_groups)))\n            }\n            for k, v in runner.optimizer.state.items():\n                state[p_map[k]] = v\n            runner.optimizer.state = state\n            # convert model to fp16\n            wrap_fp16_model(runner.model)\n            # resume from state dict\n            if 'fp16' in runner.meta and 'loss_scaler' in runner.meta['fp16']:\n                scaler_state_dict = runner.meta['fp16']['loss_scaler']\n                self.loss_scaler.load_state_dict(scaler_state_dict)\n\n        def copy_grads_to_fp32(self, fp16_net, fp32_weights):\n            \"\"\"Copy gradients from fp16 model to fp32 weight copy.\"\"\"\n            for fp32_param, fp16_param in zip(fp32_weights,\n                                              fp16_net.parameters()):\n                if fp16_param.grad is not None:\n                    if fp32_param.grad is None:\n                        fp32_param.grad = fp32_param.data.new(\n                            fp32_param.size())\n                    fp32_param.grad.copy_(fp16_param.grad)\n\n        def copy_params_to_fp16(self, fp16_net, fp32_weights):\n            \"\"\"Copy updated params from fp32 weight copy to fp16 model.\"\"\"\n            for fp16_param, fp32_param in zip(fp16_net.parameters(),\n                                              fp32_weights):\n                fp16_param.data.copy_(fp32_param.data)\n\n        def after_train_iter(self, runner):\n            \"\"\"Backward optimization steps for Mixed Precision Training. For\n            dynamic loss scaling, please refer `loss_scalar.py`\n\n            1. Scale the loss by a scale factor.\n            2. Backward the loss to obtain the gradients (fp16).\n            3. Copy gradients from the model to the fp32 weight copy.\n            4. Scale the gradients back and update the fp32 weight copy.\n            5. Copy back the params from fp32 weight copy to the fp16 model.\n            6. Save loss_scaler state_dict for resume purpose.\n            \"\"\"\n            # clear grads of last iteration\n            runner.model.zero_grad()\n            runner.optimizer.zero_grad()\n            # scale the loss value\n            scaled_loss = runner.outputs['loss'] * self.loss_scaler.loss_scale\n            scaled_loss.backward()\n            # copy fp16 grads in the model to fp32 params in the optimizer\n\n            fp32_weights = []\n            for param_group in runner.optimizer.param_groups:\n                fp32_weights += param_group['params']\n            self.copy_grads_to_fp32(runner.model, fp32_weights)\n            # allreduce grads\n            if self.distributed:\n                allreduce_grads(fp32_weights, self.coalesce,\n                                self.bucket_size_mb)\n\n            has_overflow = self.loss_scaler.has_overflow(fp32_weights)\n            # if has overflow, skip this iteration\n            if not has_overflow:\n                # scale the gradients back\n                for param in fp32_weights:\n                    if param.grad is not None:\n                        param.grad.div_(self.loss_scaler.loss_scale)\n                if self.grad_clip is not None:\n                    grad_norm = self.clip_grads(fp32_weights)\n                    if grad_norm is not None:\n                        # Add grad norm to the logger\n                        runner.log_buffer.update(\n                            {'grad_norm': float(grad_norm)},\n                            runner.outputs['num_samples'])\n                # update fp32 params\n                runner.optimizer.step()\n                # copy fp32 params to the fp16 model\n                self.copy_params_to_fp16(runner.model, fp32_weights)\n            self.loss_scaler.update_scale(has_overflow)\n            if has_overflow:\n                runner.logger.warning('Check overflow, downscale loss scale '\n                                      f'to {self.loss_scaler.cur_scale}')\n\n            # save state_dict of loss_scaler\n            runner.meta.setdefault(\n                'fp16', {})['loss_scaler'] = self.loss_scaler.state_dict()\n\n    @HOOKS.register_module()\n    class GradientCumulativeFp16OptimizerHook(GradientCumulativeOptimizerHook,\n                                              Fp16OptimizerHook):\n        \"\"\"Fp16 optimizer Hook (using mmcv implementation) implements multi-\n        iters gradient cumulating.\"\"\"\n\n        def __init__(self, *args, **kwargs):\n            super(GradientCumulativeFp16OptimizerHook,\n                  self).__init__(*args, **kwargs)\n\n        def after_train_iter(self, runner):\n            if not self.initialized:\n                self._init(runner)\n\n            if runner.iter < self.divisible_iters:\n                loss_factor = self.cumulative_iters\n            else:\n                loss_factor = self.remainder_iters\n\n            loss = runner.outputs['loss']\n            loss = loss / loss_factor\n\n            # scale the loss value\n            scaled_loss = loss * self.loss_scaler.loss_scale\n            scaled_loss.backward()\n\n            if (self.every_n_iters(runner, self.cumulative_iters)\n                    or self.is_last_iter(runner)):\n\n                # copy fp16 grads in the model to fp32 params in the optimizer\n                fp32_weights = []\n                for param_group in runner.optimizer.param_groups:\n                    fp32_weights += param_group['params']\n                self.copy_grads_to_fp32(runner.model, fp32_weights)\n                # allreduce grads\n                if self.distributed:\n                    allreduce_grads(fp32_weights, self.coalesce,\n                                    self.bucket_size_mb)\n\n                has_overflow = self.loss_scaler.has_overflow(fp32_weights)\n                # if has overflow, skip this iteration\n                if not has_overflow:\n                    # scale the gradients back\n                    for param in fp32_weights:\n                        if param.grad is not None:\n                            param.grad.div_(self.loss_scaler.loss_scale)\n                    if self.grad_clip is not None:\n                        grad_norm = self.clip_grads(fp32_weights)\n                        if grad_norm is not None:\n                            # Add grad norm to the logger\n                            runner.log_buffer.update(\n                                {'grad_norm': float(grad_norm)},\n                                runner.outputs['num_samples'])\n                    # update fp32 params\n                    runner.optimizer.step()\n                    # copy fp32 params to the fp16 model\n                    self.copy_params_to_fp16(runner.model, fp32_weights)\n                else:\n                    runner.logger.warning(\n                        'Check overflow, downscale loss scale '\n                        f'to {self.loss_scaler.cur_scale}')\n\n                self.loss_scaler.update_scale(has_overflow)\n\n                # save state_dict of loss_scaler\n                runner.meta.setdefault(\n                    'fp16', {})['loss_scaler'] = self.loss_scaler.state_dict()\n\n                # clear grads\n                runner.model.zero_grad()\n                runner.optimizer.zero_grad()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/sampler_seed.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .hook import HOOKS, Hook\n\n\n@HOOKS.register_module()\nclass DistSamplerSeedHook(Hook):\n    \"\"\"Data-loading sampler for distributed training.\n\n    When distributed training, it is only useful in conjunction with\n    :obj:`EpochBasedRunner`, while :obj:`IterBasedRunner` achieves the same\n    purpose with :obj:`IterLoader`.\n    \"\"\"\n\n    def before_epoch(self, runner):\n        if hasattr(runner.data_loader.sampler, 'set_epoch'):\n            # in case the data loader uses `SequentialSampler` in Pytorch\n            runner.data_loader.sampler.set_epoch(runner.epoch)\n        elif hasattr(runner.data_loader.batch_sampler.sampler, 'set_epoch'):\n            # batch sampler in pytorch warps the sampler as its attributes.\n            runner.data_loader.batch_sampler.sampler.set_epoch(runner.epoch)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/runner/hooks/vad_hooks.py",
    "content": "from mmcv.runner.hooks.hook import HOOKS, Hook\nfrom mmcv.parallel import is_module_wrapper\n\n\n\n\n@HOOKS.register_module()\nclass CustomSetEpochInfoHook(Hook):\n    \"\"\"Set runner's epoch information to the model.\"\"\"\n\n    def before_train_epoch(self, runner):\n        epoch = runner.epoch\n        model = runner.model\n        if is_module_wrapper(model):\n            model = model.module\n        model.set_epoch(epoch)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .boxes import BoxMode, Boxes\nfrom .instances import Instances\n# from .keypoints import Keypoints, heatmaps_to_keypoints\nfrom .masks import ROIMasks\n# from .masks import BitMasks, PolygonMasks, polygons_to_bitmask, ROIMasks\n# from .rotated_boxes import RotatedBoxes\n# from .rotated_boxes import pairwise_iou as pairwise_iou_rotated\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/boxes.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nimport numpy as np\nfrom enum import IntEnum, unique\nfrom typing import List, Tuple, Union\nimport torch\nfrom torch import device\n\n_RawBoxType = Union[List[float], Tuple[float, ...], torch.Tensor, np.ndarray]\n\n\n@unique\nclass BoxMode(IntEnum):\n    \"\"\"\n    Enum of different ways to represent a box.\n    \"\"\"\n\n    XYXY_ABS = 0\n    \"\"\"\n    (x0, y0, x1, y1) in absolute floating points coordinates.\n    The coordinates in range [0, width or height].\n    \"\"\"\n    XYWH_ABS = 1\n    \"\"\"\n    (x0, y0, w, h) in absolute floating points coordinates.\n    \"\"\"\n    XYXY_REL = 2\n    \"\"\"\n    Not yet supported!\n    (x0, y0, x1, y1) in range [0, 1]. They are relative to the size of the image.\n    \"\"\"\n    XYWH_REL = 3\n    \"\"\"\n    Not yet supported!\n    (x0, y0, w, h) in range [0, 1]. They are relative to the size of the image.\n    \"\"\"\n    XYWHA_ABS = 4\n    \"\"\"\n    (xc, yc, w, h, a) in absolute floating points coordinates.\n    (xc, yc) is the center of the rotated box, and the angle a is in degrees ccw.\n    \"\"\"\n\n    @staticmethod\n    def convert(box: _RawBoxType, from_mode: \"BoxMode\", to_mode: \"BoxMode\") -> _RawBoxType:\n        \"\"\"\n        Args:\n            box: can be a k-tuple, k-list or an Nxk array/tensor, where k = 4 or 5\n            from_mode, to_mode (BoxMode)\n\n        Returns:\n            The converted box of the same type.\n        \"\"\"\n        if from_mode == to_mode:\n            return box\n\n        original_type = type(box)\n        is_numpy = isinstance(box, np.ndarray)\n        single_box = isinstance(box, (list, tuple))\n        if single_box:\n            assert len(box) == 4 or len(box) == 5, (\n                \"BoxMode.convert takes either a k-tuple/list or an Nxk array/tensor,\"\n                \" where k == 4 or 5\"\n            )\n            arr = torch.tensor(box)[None, :]\n        else:\n            # avoid modifying the input box\n            if is_numpy:\n                arr = torch.from_numpy(np.asarray(box)).clone()\n            else:\n                arr = box.clone()\n\n        assert to_mode not in [BoxMode.XYXY_REL, BoxMode.XYWH_REL] and from_mode not in [\n            BoxMode.XYXY_REL,\n            BoxMode.XYWH_REL,\n        ], \"Relative mode not yet supported!\"\n\n        if from_mode == BoxMode.XYWHA_ABS and to_mode == BoxMode.XYXY_ABS:\n            assert (\n                arr.shape[-1] == 5\n            ), \"The last dimension of input shape must be 5 for XYWHA format\"\n            original_dtype = arr.dtype\n            arr = arr.double()\n\n            w = arr[:, 2]\n            h = arr[:, 3]\n            a = arr[:, 4]\n            c = torch.abs(torch.cos(a * math.pi / 180.0))\n            s = torch.abs(torch.sin(a * math.pi / 180.0))\n            # This basically computes the horizontal bounding rectangle of the rotated box\n            new_w = c * w + s * h\n            new_h = c * h + s * w\n\n            # convert center to top-left corner\n            arr[:, 0] -= new_w / 2.0\n            arr[:, 1] -= new_h / 2.0\n            # bottom-right corner\n            arr[:, 2] = arr[:, 0] + new_w\n            arr[:, 3] = arr[:, 1] + new_h\n\n            arr = arr[:, :4].to(dtype=original_dtype)\n        elif from_mode == BoxMode.XYWH_ABS and to_mode == BoxMode.XYWHA_ABS:\n            original_dtype = arr.dtype\n            arr = arr.double()\n            arr[:, 0] += arr[:, 2] / 2.0\n            arr[:, 1] += arr[:, 3] / 2.0\n            angles = torch.zeros((arr.shape[0], 1), dtype=arr.dtype)\n            arr = torch.cat((arr, angles), axis=1).to(dtype=original_dtype)\n        else:\n            if to_mode == BoxMode.XYXY_ABS and from_mode == BoxMode.XYWH_ABS:\n                arr[:, 2] += arr[:, 0]\n                arr[:, 3] += arr[:, 1]\n            elif from_mode == BoxMode.XYXY_ABS and to_mode == BoxMode.XYWH_ABS:\n                arr[:, 2] -= arr[:, 0]\n                arr[:, 3] -= arr[:, 1]\n            else:\n                raise NotImplementedError(\n                    \"Conversion from BoxMode {} to {} is not supported yet\".format(\n                        from_mode, to_mode\n                    )\n                )\n\n        if single_box:\n            return original_type(arr.flatten().tolist())\n        if is_numpy:\n            return arr.numpy()\n        else:\n            return arr\n\n\nclass Boxes:\n    \"\"\"\n    This structure stores a list of boxes as a Nx4 torch.Tensor.\n    It supports some common methods about boxes\n    (`area`, `clip`, `nonempty`, etc),\n    and also behaves like a Tensor\n    (support indexing, `to(device)`, `.device`, and iteration over all boxes)\n\n    Attributes:\n        tensor (torch.Tensor): float matrix of Nx4. Each row is (x1, y1, x2, y2).\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor):\n        \"\"\"\n        Args:\n            tensor (Tensor[float]): a Nx4 matrix.  Each row is (x1, y1, x2, y2).\n        \"\"\"\n        if not isinstance(tensor, torch.Tensor):\n            tensor = torch.as_tensor(tensor, dtype=torch.float32, device=torch.device(\"cpu\"))\n        else:\n            tensor = tensor.to(torch.float32)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that does not depend on\n            # the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((-1, 4)).to(dtype=torch.float32)\n        assert tensor.dim() == 2 and tensor.size(-1) == 4, tensor.size()\n\n        self.tensor = tensor\n\n    def clone(self) -> \"Boxes\":\n        \"\"\"\n        Clone the Boxes.\n\n        Returns:\n            Boxes\n        \"\"\"\n        return Boxes(self.tensor.clone())\n\n    def to(self, device: torch.device):\n        # Boxes are assumed float32 and does not support to(dtype)\n        return Boxes(self.tensor.to(device=device))\n\n    def area(self) -> torch.Tensor:\n        \"\"\"\n        Computes the area of all the boxes.\n\n        Returns:\n            torch.Tensor: a vector with areas of each box.\n        \"\"\"\n        box = self.tensor\n        area = (box[:, 2] - box[:, 0]) * (box[:, 3] - box[:, 1])\n        return area\n\n    def clip(self, box_size: Tuple[int, int]) -> None:\n        \"\"\"\n        Clip (in place) the boxes by limiting x coordinates to the range [0, width]\n        and y coordinates to the range [0, height].\n\n        Args:\n            box_size (height, width): The clipping box's size.\n        \"\"\"\n        assert torch.isfinite(self.tensor).all(), \"Box tensor contains infinite or NaN!\"\n        h, w = box_size\n        x1 = self.tensor[:, 0].clamp(min=0, max=w)\n        y1 = self.tensor[:, 1].clamp(min=0, max=h)\n        x2 = self.tensor[:, 2].clamp(min=0, max=w)\n        y2 = self.tensor[:, 3].clamp(min=0, max=h)\n        self.tensor = torch.stack((x1, y1, x2, y2), dim=-1)\n\n    def nonempty(self, threshold: float = 0.0) -> torch.Tensor:\n        \"\"\"\n        Find boxes that are non-empty.\n        A box is considered empty, if either of its side is no larger than threshold.\n\n        Returns:\n            Tensor:\n                a binary vector which represents whether each box is empty\n                (False) or non-empty (True).\n        \"\"\"\n        box = self.tensor\n        widths = box[:, 2] - box[:, 0]\n        heights = box[:, 3] - box[:, 1]\n        keep = (widths > threshold) & (heights > threshold)\n        return keep\n\n    def __getitem__(self, item) -> \"Boxes\":\n        \"\"\"\n        Args:\n            item: int, slice, or a BoolTensor\n\n        Returns:\n            Boxes: Create a new :class:`Boxes` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_boxes = boxes[3]`: return a `Boxes` which contains only one box.\n        2. `new_boxes = boxes[2:10]`: return a slice of boxes.\n        3. `new_boxes = boxes[vector]`, where vector is a torch.BoolTensor\n           with `length = len(boxes)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned Boxes might share storage with this Boxes,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return Boxes(self.tensor[item].view(1, -1))\n        b = self.tensor[item]\n        assert b.dim() == 2, \"Indexing on Boxes with {} failed to return a matrix!\".format(item)\n        return Boxes(b)\n\n    def __len__(self) -> int:\n        return self.tensor.shape[0]\n\n    def __repr__(self) -> str:\n        return \"Boxes(\" + str(self.tensor) + \")\"\n\n    def inside_box(self, box_size: Tuple[int, int], boundary_threshold: int = 0) -> torch.Tensor:\n        \"\"\"\n        Args:\n            box_size (height, width): Size of the reference box.\n            boundary_threshold (int): Boxes that extend beyond the reference box\n                boundary by more than boundary_threshold are considered \"outside\".\n\n        Returns:\n            a binary vector, indicating whether each box is inside the reference box.\n        \"\"\"\n        height, width = box_size\n        inds_inside = (\n            (self.tensor[..., 0] >= -boundary_threshold)\n            & (self.tensor[..., 1] >= -boundary_threshold)\n            & (self.tensor[..., 2] < width + boundary_threshold)\n            & (self.tensor[..., 3] < height + boundary_threshold)\n        )\n        return inds_inside\n\n    def get_centers(self) -> torch.Tensor:\n        \"\"\"\n        Returns:\n            The box centers in a Nx2 array of (x, y).\n        \"\"\"\n        return (self.tensor[:, :2] + self.tensor[:, 2:]) / 2\n\n    def scale(self, scale_x: float, scale_y: float) -> None:\n        \"\"\"\n        Scale the box with horizontal and vertical scaling factors\n        \"\"\"\n        self.tensor[:, 0::2] *= scale_x\n        self.tensor[:, 1::2] *= scale_y\n\n    @classmethod\n    def cat(cls, boxes_list: List[\"Boxes\"]) -> \"Boxes\":\n        \"\"\"\n        Concatenates a list of Boxes into a single Boxes\n\n        Arguments:\n            boxes_list (list[Boxes])\n\n        Returns:\n            Boxes: the concatenated Boxes\n        \"\"\"\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0))\n        assert all([isinstance(box, Boxes) for box in boxes_list])\n\n        # use torch.cat (v.s. layers.cat) so the returned boxes never share storage with input\n        cat_boxes = cls(torch.cat([b.tensor for b in boxes_list], dim=0))\n        return cat_boxes\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    # type \"Iterator[torch.Tensor]\", yield, and iter() not supported by torchscript\n    # https://github.com/pytorch/pytorch/issues/18627\n    @torch.jit.unused\n    def __iter__(self):\n        \"\"\"\n        Yield a box as a Tensor of shape (4,) at a time.\n        \"\"\"\n        yield from self.tensor\n\n\ndef pairwise_intersection(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Given two lists of boxes of size N and M,\n    compute the intersection area between __all__ N x M pairs of boxes.\n    The box order must be (xmin, ymin, xmax, ymax)\n\n    Args:\n        boxes1,boxes2 (Boxes): two `Boxes`. Contains N & M boxes, respectively.\n\n    Returns:\n        Tensor: intersection, sized [N,M].\n    \"\"\"\n    boxes1, boxes2 = boxes1.tensor, boxes2.tensor\n    width_height = torch.min(boxes1[:, None, 2:], boxes2[:, 2:]) - torch.max(\n        boxes1[:, None, :2], boxes2[:, :2]\n    )  # [N,M,2]\n\n    width_height.clamp_(min=0)  # [N,M,2]\n    intersection = width_height.prod(dim=2)  # [N,M]\n    return intersection\n\n\n# implementation from https://github.com/kuangliu/torchcv/blob/master/torchcv/utils/box.py\n# with slight modifications\ndef pairwise_iou(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Given two lists of boxes of size N and M, compute the IoU\n    (intersection over union) between **all** N x M pairs of boxes.\n    The box order must be (xmin, ymin, xmax, ymax).\n\n    Args:\n        boxes1,boxes2 (Boxes): two `Boxes`. Contains N & M boxes, respectively.\n\n    Returns:\n        Tensor: IoU, sized [N,M].\n    \"\"\"\n    area1 = boxes1.area()  # [N]\n    area2 = boxes2.area()  # [M]\n    inter = pairwise_intersection(boxes1, boxes2)\n\n    # handle empty boxes\n    iou = torch.where(\n        inter > 0,\n        inter / (area1[:, None] + area2 - inter),\n        torch.zeros(1, dtype=inter.dtype, device=inter.device),\n    )\n    return iou\n\n\ndef pairwise_ioa(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Similar to :func:`pariwise_iou` but compute the IoA (intersection over boxes2 area).\n\n    Args:\n        boxes1,boxes2 (Boxes): two `Boxes`. Contains N & M boxes, respectively.\n\n    Returns:\n        Tensor: IoA, sized [N,M].\n    \"\"\"\n    area2 = boxes2.area()  # [M]\n    inter = pairwise_intersection(boxes1, boxes2)\n\n    # handle empty boxes\n    ioa = torch.where(\n        inter > 0, inter / area2, torch.zeros(1, dtype=inter.dtype, device=inter.device)\n    )\n    return ioa\n\n\ndef pairwise_point_box_distance(points: torch.Tensor, boxes: Boxes):\n    \"\"\"\n    Pairwise distance between N points and M boxes. The distance between a\n    point and a box is represented by the distance from the point to 4 edges\n    of the box. Distances are all positive when the point is inside the box.\n\n    Args:\n        points: Nx2 coordinates. Each row is (x, y)\n        boxes: M boxes\n\n    Returns:\n        Tensor: distances of size (N, M, 4). The 4 values are distances from\n            the point to the left, top, right, bottom of the box.\n    \"\"\"\n    x, y = points.unsqueeze(dim=2).unbind(dim=1)  # (N, 1)\n    x0, y0, x1, y1 = boxes.tensor.unsqueeze(dim=0).unbind(dim=2)  # (1, M)\n    return torch.stack([x - x0, y - y0, x1 - x, y1 - y], dim=2)\n\n\ndef matched_pairwise_iou(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Compute pairwise intersection over union (IOU) of two sets of matched\n    boxes that have the same number of boxes.\n    Similar to :func:`pairwise_iou`, but computes only diagonal elements of the matrix.\n\n    Args:\n        boxes1 (Boxes): bounding boxes, sized [N,4].\n        boxes2 (Boxes): same length as boxes1\n    Returns:\n        Tensor: iou, sized [N].\n    \"\"\"\n    assert len(boxes1) == len(\n        boxes2\n    ), \"boxlists should have the same\" \"number of entries, got {}, {}\".format(\n        len(boxes1), len(boxes2)\n    )\n    area1 = boxes1.area()  # [N]\n    area2 = boxes2.area()  # [N]\n    box1, box2 = boxes1.tensor, boxes2.tensor\n    lt = torch.max(box1[:, :2], box2[:, :2])  # [N,2]\n    rb = torch.min(box1[:, 2:], box2[:, 2:])  # [N,2]\n    wh = (rb - lt).clamp(min=0)  # [N,2]\n    inter = wh[:, 0] * wh[:, 1]  # [N]\n    iou = inter / (area1 + area2 - inter)  # [N]\n    return iou\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/image_list.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom __future__ import division\nfrom typing import Any, Dict, List, Optional, Tuple\nimport torch\nfrom torch import device\nfrom torch.nn import functional as F\n\nfrom detectron2.layers.wrappers import move_device_like, shapes_to_tensor\n\n\nclass ImageList:\n    \"\"\"\n    Structure that holds a list of images (of possibly\n    varying sizes) as a single tensor.\n    This works by padding the images to the same size.\n    The original sizes of each image is stored in `image_sizes`.\n\n    Attributes:\n        image_sizes (list[tuple[int, int]]): each tuple is (h, w).\n            During tracing, it becomes list[Tensor] instead.\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor, image_sizes: List[Tuple[int, int]]):\n        \"\"\"\n        Arguments:\n            tensor (Tensor): of shape (N, H, W) or (N, C_1, ..., C_K, H, W) where K >= 1\n            image_sizes (list[tuple[int, int]]): Each tuple is (h, w). It can\n                be smaller than (H, W) due to padding.\n        \"\"\"\n        self.tensor = tensor\n        self.image_sizes = image_sizes\n\n    def __len__(self) -> int:\n        return len(self.image_sizes)\n\n    def __getitem__(self, idx) -> torch.Tensor:\n        \"\"\"\n        Access the individual image in its original size.\n\n        Args:\n            idx: int or slice\n\n        Returns:\n            Tensor: an image of shape (H, W) or (C_1, ..., C_K, H, W) where K >= 1\n        \"\"\"\n        size = self.image_sizes[idx]\n        return self.tensor[idx, ..., : size[0], : size[1]]\n\n    @torch.jit.unused\n    def to(self, *args: Any, **kwargs: Any) -> \"ImageList\":\n        cast_tensor = self.tensor.to(*args, **kwargs)\n        return ImageList(cast_tensor, self.image_sizes)\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    @staticmethod\n    def from_tensors(\n        tensors: List[torch.Tensor],\n        size_divisibility: int = 0,\n        pad_value: float = 0.0,\n        padding_constraints: Optional[Dict[str, int]] = None,\n    ) -> \"ImageList\":\n        \"\"\"\n        Args:\n            tensors: a tuple or list of `torch.Tensor`, each of shape (Hi, Wi) or\n                (C_1, ..., C_K, Hi, Wi) where K >= 1. The Tensors will be padded\n                to the same shape with `pad_value`.\n            size_divisibility (int): If `size_divisibility > 0`, add padding to ensure\n                the common height and width is divisible by `size_divisibility`.\n                This depends on the model and many models need a divisibility of 32.\n            pad_value (float): value to pad.\n            padding_constraints (optional[Dict]): If given, it would follow the format as\n                {\"size_divisibility\": int, \"square_size\": int}, where `size_divisibility` will\n                overwrite the above one if presented and `square_size` indicates the\n                square padding size if `square_size` > 0.\n        Returns:\n            an `ImageList`.\n        \"\"\"\n        assert len(tensors) > 0\n        assert isinstance(tensors, (tuple, list))\n        for t in tensors:\n            assert isinstance(t, torch.Tensor), type(t)\n            assert t.shape[:-2] == tensors[0].shape[:-2], t.shape\n\n        image_sizes = [(im.shape[-2], im.shape[-1]) for im in tensors]\n        image_sizes_tensor = [shapes_to_tensor(x) for x in image_sizes]\n        max_size = torch.stack(image_sizes_tensor).max(0).values\n\n        if padding_constraints is not None:\n            square_size = padding_constraints.get(\"square_size\", 0)\n            if square_size > 0:\n                # pad to square.\n                max_size[0] = max_size[1] = square_size\n            if \"size_divisibility\" in padding_constraints:\n                size_divisibility = padding_constraints[\"size_divisibility\"]\n        if size_divisibility > 1:\n            stride = size_divisibility\n            # the last two dims are H,W, both subject to divisibility requirement\n            max_size = (max_size + (stride - 1)).div(stride, rounding_mode=\"floor\") * stride\n\n        # handle weirdness of scripting and tracing ...\n        if torch.jit.is_scripting():\n            max_size: List[int] = max_size.to(dtype=torch.long).tolist()\n        else:\n            if torch.jit.is_tracing():\n                image_sizes = image_sizes_tensor\n\n        if len(tensors) == 1:\n            # This seems slightly (2%) faster.\n            # TODO: check whether it's faster for multiple images as well\n            image_size = image_sizes[0]\n            padding_size = [0, max_size[-1] - image_size[1], 0, max_size[-2] - image_size[0]]\n            batched_imgs = F.pad(tensors[0], padding_size, value=pad_value).unsqueeze_(0)\n        else:\n            # max_size can be a tensor in tracing mode, therefore convert to list\n            batch_shape = [len(tensors)] + list(tensors[0].shape[:-2]) + list(max_size)\n            device = (\n                None if torch.jit.is_scripting() else (\"cpu\" if torch.jit.is_tracing() else None)\n            )\n            batched_imgs = tensors[0].new_full(batch_shape, pad_value, device=device)\n            batched_imgs = move_device_like(batched_imgs, tensors[0])\n            for i, img in enumerate(tensors):\n                # Use `batched_imgs` directly instead of `img, pad_img = zip(tensors, batched_imgs)`\n                # Tracing mode cannot capture `copy_()` of temporary locals\n                batched_imgs[i, ..., : img.shape[-2], : img.shape[-1]].copy_(img)\n\n        return ImageList(batched_imgs.contiguous(), image_sizes)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/instances.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport itertools\nimport warnings\nfrom typing import Any, Dict, List, Tuple, Union\nimport torch\n\n\nclass Instances:\n    \"\"\"\n    This class represents a list of instances in an image.\n    It stores the attributes of instances (e.g., boxes, masks, labels, scores) as \"fields\".\n    All fields must have the same ``__len__`` which is the number of instances.\n\n    All other (non-field) attributes of this class are considered private:\n    they must start with '_' and are not modifiable by a user.\n\n    Some basic usage:\n\n    1. Set/get/check a field:\n\n       .. code-block:: python\n\n          instances.gt_boxes = Boxes(...)\n          print(instances.pred_masks)  # a tensor of shape (N, H, W)\n          print('gt_masks' in instances)\n\n    2. ``len(instances)`` returns the number of instances\n    3. Indexing: ``instances[indices]`` will apply the indexing on all the fields\n       and returns a new :class:`Instances`.\n       Typically, ``indices`` is a integer vector of indices,\n       or a binary mask of length ``num_instances``\n\n       .. code-block:: python\n\n          category_3_detections = instances[instances.pred_classes == 3]\n          confident_detections = instances[instances.scores > 0.9]\n    \"\"\"\n\n    def __init__(self, image_size: Tuple[int, int], **kwargs: Any):\n        \"\"\"\n        Args:\n            image_size (height, width): the spatial size of the image.\n            kwargs: fields to add to this `Instances`.\n        \"\"\"\n        self._image_size = image_size\n        self._fields: Dict[str, Any] = {}\n        for k, v in kwargs.items():\n            self.set(k, v)\n\n    @property\n    def image_size(self) -> Tuple[int, int]:\n        \"\"\"\n        Returns:\n            tuple: height, width\n        \"\"\"\n        return self._image_size\n\n    def __setattr__(self, name: str, val: Any) -> None:\n        if name.startswith(\"_\"):\n            super().__setattr__(name, val)\n        else:\n            self.set(name, val)\n\n    def __getattr__(self, name: str) -> Any:\n        if name == \"_fields\" or name not in self._fields:\n            raise AttributeError(\"Cannot find field '{}' in the given Instances!\".format(name))\n        return self._fields[name]\n\n    def set(self, name: str, value: Any) -> None:\n        \"\"\"\n        Set the field named `name` to `value`.\n        The length of `value` must be the number of instances,\n        and must agree with other existing fields in this object.\n        \"\"\"\n        with warnings.catch_warnings(record=True):\n            data_len = len(value)\n        if len(self._fields):\n            assert (\n                len(self) == data_len\n            ), \"Adding a field of length {} to a Instances of length {}\".format(data_len, len(self))\n        self._fields[name] = value\n\n    def has(self, name: str) -> bool:\n        \"\"\"\n        Returns:\n            bool: whether the field called `name` exists.\n        \"\"\"\n        return name in self._fields\n\n    def remove(self, name: str) -> None:\n        \"\"\"\n        Remove the field called `name`.\n        \"\"\"\n        del self._fields[name]\n\n    def get(self, name: str) -> Any:\n        \"\"\"\n        Returns the field called `name`.\n        \"\"\"\n        return self._fields[name]\n\n    def get_fields(self) -> Dict[str, Any]:\n        \"\"\"\n        Returns:\n            dict: a dict which maps names (str) to data of the fields\n\n        Modifying the returned dict will modify this instance.\n        \"\"\"\n        return self._fields\n\n    # Tensor-like methods\n    def to(self, *args: Any, **kwargs: Any) -> \"Instances\":\n        \"\"\"\n        Returns:\n            Instances: all fields are called with a `to(device)`, if the field has this method.\n        \"\"\"\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            if hasattr(v, \"to\"):\n                v = v.to(*args, **kwargs)\n            ret.set(k, v)\n        return ret\n\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"Instances\":\n        \"\"\"\n        Args:\n            item: an index-like object and will be used to index all the fields.\n\n        Returns:\n            If `item` is a string, return the data in the corresponding field.\n            Otherwise, returns an `Instances` where all fields are indexed by `item`.\n        \"\"\"\n        if type(item) == int:\n            if item >= len(self) or item < -len(self):\n                raise IndexError(\"Instances index out of range!\")\n            else:\n                item = slice(item, None, len(self))\n\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            ret.set(k, v[item])\n        return ret\n\n    def __len__(self) -> int:\n        for v in self._fields.values():\n            # use __len__ because len() has to be int and is not friendly to tracing\n            return v.__len__()\n        raise NotImplementedError(\"Empty Instances does not support __len__!\")\n\n    def __iter__(self):\n        raise NotImplementedError(\"`Instances` object is not iterable!\")\n\n    @staticmethod\n    def cat(instance_lists: List[\"Instances\"]) -> \"Instances\":\n        \"\"\"\n        Args:\n            instance_lists (list[Instances])\n\n        Returns:\n            Instances\n        \"\"\"\n        assert all(isinstance(i, Instances) for i in instance_lists)\n        assert len(instance_lists) > 0\n        if len(instance_lists) == 1:\n            return instance_lists[0]\n\n        image_size = instance_lists[0].image_size\n        if not isinstance(image_size, torch.Tensor):  # could be a tensor in tracing\n            for i in instance_lists[1:]:\n                assert i.image_size == image_size\n        ret = Instances(image_size)\n        for k in instance_lists[0]._fields.keys():\n            values = [i.get(k) for i in instance_lists]\n            v0 = values[0]\n            if isinstance(v0, torch.Tensor):\n                values = torch.cat(values, dim=0)\n            elif isinstance(v0, list):\n                values = list(itertools.chain(*values))\n            elif hasattr(type(v0), \"cat\"):\n                values = type(v0).cat(values)\n            else:\n                raise ValueError(\"Unsupported type {} for concatenation\".format(type(v0)))\n            ret.set(k, values)\n        return ret\n\n    def __str__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={}, \".format(len(self))\n        s += \"image_height={}, \".format(self._image_size[0])\n        s += \"image_width={}, \".format(self._image_size[1])\n        s += \"fields=[{}])\".format(\", \".join((f\"{k}: {v}\" for k, v in self._fields.items())))\n        return s\n\n    __repr__ = __str__\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/keypoints.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Any, List, Tuple, Union\nimport torch\nfrom torch.nn import functional as F\n\n\nclass Keypoints:\n    \"\"\"\n    Stores keypoint **annotation** data. GT Instances have a `gt_keypoints` property\n    containing the x,y location and visibility flag of each keypoint. This tensor has shape\n    (N, K, 3) where N is the number of instances and K is the number of keypoints per instance.\n\n    The visibility flag follows the COCO format and must be one of three integers:\n\n    * v=0: not labeled (in which case x=y=0)\n    * v=1: labeled but not visible\n    * v=2: labeled and visible\n    \"\"\"\n\n    def __init__(self, keypoints: Union[torch.Tensor, np.ndarray, List[List[float]]]):\n        \"\"\"\n        Arguments:\n            keypoints: A Tensor, numpy array, or list of the x, y, and visibility of each keypoint.\n                The shape should be (N, K, 3) where N is the number of\n                instances, and K is the number of keypoints per instance.\n        \"\"\"\n        device = keypoints.device if isinstance(keypoints, torch.Tensor) else torch.device(\"cpu\")\n        keypoints = torch.as_tensor(keypoints, dtype=torch.float32, device=device)\n        assert keypoints.dim() == 3 and keypoints.shape[2] == 3, keypoints.shape\n        self.tensor = keypoints\n\n    def __len__(self) -> int:\n        return self.tensor.size(0)\n\n    def to(self, *args: Any, **kwargs: Any) -> \"Keypoints\":\n        return type(self)(self.tensor.to(*args, **kwargs))\n\n    @property\n    def device(self) -> torch.device:\n        return self.tensor.device\n\n    def to_heatmap(self, boxes: torch.Tensor, heatmap_size: int) -> torch.Tensor:\n        \"\"\"\n        Convert keypoint annotations to a heatmap of one-hot labels for training,\n        as described in :paper:`Mask R-CNN`.\n\n        Arguments:\n            boxes: Nx4 tensor, the boxes to draw the keypoints to\n\n        Returns:\n            heatmaps:\n                A tensor of shape (N, K), each element is integer spatial label\n                in the range [0, heatmap_size**2 - 1] for each keypoint in the input.\n            valid:\n                A tensor of shape (N, K) containing whether each keypoint is in the roi or not.\n        \"\"\"\n        return _keypoints_to_heatmap(self.tensor, boxes, heatmap_size)\n\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"Keypoints\":\n        \"\"\"\n        Create a new `Keypoints` by indexing on this `Keypoints`.\n\n        The following usage are allowed:\n\n        1. `new_kpts = kpts[3]`: return a `Keypoints` which contains only one instance.\n        2. `new_kpts = kpts[2:10]`: return a slice of key points.\n        3. `new_kpts = kpts[vector]`, where vector is a torch.ByteTensor\n           with `length = len(kpts)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned Keypoints might share storage with this Keypoints,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return Keypoints([self.tensor[item]])\n        return Keypoints(self.tensor[item])\n\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.tensor))\n        return s\n\n    @staticmethod\n    def cat(keypoints_list: List[\"Keypoints\"]) -> \"Keypoints\":\n        \"\"\"\n        Concatenates a list of Keypoints into a single Keypoints\n\n        Arguments:\n            keypoints_list (list[Keypoints])\n\n        Returns:\n            Keypoints: the concatenated Keypoints\n        \"\"\"\n        assert isinstance(keypoints_list, (list, tuple))\n        assert len(keypoints_list) > 0\n        assert all(isinstance(keypoints, Keypoints) for keypoints in keypoints_list)\n\n        cat_kpts = type(keypoints_list[0])(\n            torch.cat([kpts.tensor for kpts in keypoints_list], dim=0)\n        )\n        return cat_kpts\n\n\n# TODO make this nicer, this is a direct translation from C2 (but removing the inner loop)\ndef _keypoints_to_heatmap(\n    keypoints: torch.Tensor, rois: torch.Tensor, heatmap_size: int\n) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Encode keypoint locations into a target heatmap for use in SoftmaxWithLoss across space.\n\n    Maps keypoints from the half-open interval [x1, x2) on continuous image coordinates to the\n    closed interval [0, heatmap_size - 1] on discrete image coordinates. We use the\n    continuous-discrete conversion from Heckbert 1990 (\"What is the coordinate of a pixel?\"):\n    d = floor(c) and c = d + 0.5, where d is a discrete coordinate and c is a continuous coordinate.\n\n    Arguments:\n        keypoints: tensor of keypoint locations in of shape (N, K, 3).\n        rois: Nx4 tensor of rois in xyxy format\n        heatmap_size: integer side length of square heatmap.\n\n    Returns:\n        heatmaps: A tensor of shape (N, K) containing an integer spatial label\n            in the range [0, heatmap_size**2 - 1] for each keypoint in the input.\n        valid: A tensor of shape (N, K) containing whether each keypoint is in\n            the roi or not.\n    \"\"\"\n\n    if rois.numel() == 0:\n        return rois.new().long(), rois.new().long()\n    offset_x = rois[:, 0]\n    offset_y = rois[:, 1]\n    scale_x = heatmap_size / (rois[:, 2] - rois[:, 0])\n    scale_y = heatmap_size / (rois[:, 3] - rois[:, 1])\n\n    offset_x = offset_x[:, None]\n    offset_y = offset_y[:, None]\n    scale_x = scale_x[:, None]\n    scale_y = scale_y[:, None]\n\n    x = keypoints[..., 0]\n    y = keypoints[..., 1]\n\n    x_boundary_inds = x == rois[:, 2][:, None]\n    y_boundary_inds = y == rois[:, 3][:, None]\n\n    x = (x - offset_x) * scale_x\n    x = x.floor().long()\n    y = (y - offset_y) * scale_y\n    y = y.floor().long()\n\n    x[x_boundary_inds] = heatmap_size - 1\n    y[y_boundary_inds] = heatmap_size - 1\n\n    valid_loc = (x >= 0) & (y >= 0) & (x < heatmap_size) & (y < heatmap_size)\n    vis = keypoints[..., 2] > 0\n    valid = (valid_loc & vis).long()\n\n    lin_ind = y * heatmap_size + x\n    heatmaps = lin_ind * valid\n\n    return heatmaps, valid\n\n\n@torch.jit.script_if_tracing\ndef heatmaps_to_keypoints(maps: torch.Tensor, rois: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Extract predicted keypoint locations from heatmaps.\n\n    Args:\n        maps (Tensor): (#ROIs, #keypoints, POOL_H, POOL_W). The predicted heatmap of logits for\n            each ROI and each keypoint.\n        rois (Tensor): (#ROIs, 4). The box of each ROI.\n\n    Returns:\n        Tensor of shape (#ROIs, #keypoints, 4) with the last dimension corresponding to\n        (x, y, logit, score) for each keypoint.\n\n    When converting discrete pixel indices in an NxN image to a continuous keypoint coordinate,\n    we maintain consistency with :meth:`Keypoints.to_heatmap` by using the conversion from\n    Heckbert 1990: c = d + 0.5, where d is a discrete coordinate and c is a continuous coordinate.\n    \"\"\"\n\n    offset_x = rois[:, 0]\n    offset_y = rois[:, 1]\n\n    widths = (rois[:, 2] - rois[:, 0]).clamp(min=1)\n    heights = (rois[:, 3] - rois[:, 1]).clamp(min=1)\n    widths_ceil = widths.ceil()\n    heights_ceil = heights.ceil()\n\n    num_rois, num_keypoints = maps.shape[:2]\n    xy_preds = maps.new_zeros(rois.shape[0], num_keypoints, 4)\n\n    width_corrections = widths / widths_ceil\n    height_corrections = heights / heights_ceil\n\n    keypoints_idx = torch.arange(num_keypoints, device=maps.device)\n\n    for i in range(num_rois):\n        outsize = (int(heights_ceil[i]), int(widths_ceil[i]))\n        roi_map = F.interpolate(maps[[i]], size=outsize, mode=\"bicubic\", align_corners=False)\n\n        # Although semantically equivalent, `reshape` is used instead of `squeeze` due\n        # to limitation during ONNX export of `squeeze` in scripting mode\n        roi_map = roi_map.reshape(roi_map.shape[1:])  # keypoints x H x W\n\n        # softmax over the spatial region\n        max_score, _ = roi_map.view(num_keypoints, -1).max(1)\n        max_score = max_score.view(num_keypoints, 1, 1)\n        tmp_full_resolution = (roi_map - max_score).exp_()\n        tmp_pool_resolution = (maps[i] - max_score).exp_()\n        # Produce scores over the region H x W, but normalize with POOL_H x POOL_W,\n        # so that the scores of objects of different absolute sizes will be more comparable\n        roi_map_scores = tmp_full_resolution / tmp_pool_resolution.sum((1, 2), keepdim=True)\n\n        w = roi_map.shape[2]\n        pos = roi_map.view(num_keypoints, -1).argmax(1)\n\n        x_int = pos % w\n        y_int = (pos - x_int) // w\n\n        assert (\n            roi_map_scores[keypoints_idx, y_int, x_int]\n            == roi_map_scores.view(num_keypoints, -1).max(1)[0]\n        ).all()\n\n        x = (x_int.float() + 0.5) * width_corrections[i]\n        y = (y_int.float() + 0.5) * height_corrections[i]\n\n        xy_preds[i, :, 0] = x + offset_x[i]\n        xy_preds[i, :, 1] = y + offset_y[i]\n        xy_preds[i, :, 2] = roi_map[keypoints_idx, y_int, x_int]\n        xy_preds[i, :, 3] = roi_map_scores[keypoints_idx, y_int, x_int]\n\n    return xy_preds\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/masks.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport itertools\nimport numpy as np\nfrom typing import Any, Iterator, List, Union\nimport pycocotools.mask as mask_util\nimport torch\nfrom torch import device\n\nfrom mmcv.layers.roi_align import ROIAlign\nfrom mmcv.utils import retry_if_cuda_oom\n\nfrom .boxes import Boxes\n\n\ndef polygon_area(x, y):\n    # Using the shoelace formula\n    # https://stackoverflow.com/questions/24467972/calculate-area-of-polygon-given-x-y-coordinates\n    return 0.5 * np.abs(np.dot(x, np.roll(y, 1)) - np.dot(y, np.roll(x, 1)))\n\n\ndef polygons_to_bitmask(polygons: List[np.ndarray], height: int, width: int) -> np.ndarray:\n    \"\"\"\n    Args:\n        polygons (list[ndarray]): each array has shape (Nx2,)\n        height, width (int)\n\n    Returns:\n        ndarray: a bool mask of shape (height, width)\n    \"\"\"\n    if len(polygons) == 0:\n        # COCOAPI does not support empty polygons\n        return np.zeros((height, width)).astype(bool)\n    rles = mask_util.frPyObjects(polygons, height, width)\n    rle = mask_util.merge(rles)\n    return mask_util.decode(rle).astype(bool)\n\n\ndef rasterize_polygons_within_box(\n    polygons: List[np.ndarray], box: np.ndarray, mask_size: int\n) -> torch.Tensor:\n    \"\"\"\n    Rasterize the polygons into a mask image and\n    crop the mask content in the given box.\n    The cropped mask is resized to (mask_size, mask_size).\n\n    This function is used when generating training targets for mask head in Mask R-CNN.\n    Given original ground-truth masks for an image, new ground-truth mask\n    training targets in the size of `mask_size x mask_size`\n    must be provided for each predicted box. This function will be called to\n    produce such targets.\n\n    Args:\n        polygons (list[ndarray[float]]): a list of polygons, which represents an instance.\n        box: 4-element numpy array\n        mask_size (int):\n\n    Returns:\n        Tensor: BoolTensor of shape (mask_size, mask_size)\n    \"\"\"\n    # 1. Shift the polygons w.r.t the boxes\n    w, h = box[2] - box[0], box[3] - box[1]\n\n    polygons = copy.deepcopy(polygons)\n    for p in polygons:\n        p[0::2] = p[0::2] - box[0]\n        p[1::2] = p[1::2] - box[1]\n\n    # 2. Rescale the polygons to the new box size\n    # max() to avoid division by small number\n    ratio_h = mask_size / max(h, 0.1)\n    ratio_w = mask_size / max(w, 0.1)\n\n    if ratio_h == ratio_w:\n        for p in polygons:\n            p *= ratio_h\n    else:\n        for p in polygons:\n            p[0::2] *= ratio_w\n            p[1::2] *= ratio_h\n\n    # 3. Rasterize the polygons with coco api\n    mask = polygons_to_bitmask(polygons, mask_size, mask_size)\n    mask = torch.from_numpy(mask)\n    return mask\n\n\nclass BitMasks:\n    \"\"\"\n    This class stores the segmentation masks for all objects in one image, in\n    the form of bitmaps.\n\n    Attributes:\n        tensor: bool Tensor of N,H,W, representing N instances in the image.\n    \"\"\"\n\n    def __init__(self, tensor: Union[torch.Tensor, np.ndarray]):\n        \"\"\"\n        Args:\n            tensor: bool Tensor of N,H,W, representing N instances in the image.\n        \"\"\"\n        if isinstance(tensor, torch.Tensor):\n            tensor = tensor.to(torch.bool)\n        else:\n            tensor = torch.as_tensor(tensor, dtype=torch.bool, device=torch.device(\"cpu\"))\n        assert tensor.dim() == 3, tensor.size()\n        self.image_size = tensor.shape[1:]\n        self.tensor = tensor\n\n    @torch.jit.unused\n    def to(self, *args: Any, **kwargs: Any) -> \"BitMasks\":\n        return BitMasks(self.tensor.to(*args, **kwargs))\n\n    @property\n    def device(self) -> torch.device:\n        return self.tensor.device\n\n    @torch.jit.unused\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"BitMasks\":\n        \"\"\"\n        Returns:\n            BitMasks: Create a new :class:`BitMasks` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_masks = masks[3]`: return a `BitMasks` which contains only one mask.\n        2. `new_masks = masks[2:10]`: return a slice of masks.\n        3. `new_masks = masks[vector]`, where vector is a torch.BoolTensor\n           with `length = len(masks)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned object might share storage with this object,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return BitMasks(self.tensor[item].unsqueeze(0))\n        m = self.tensor[item]\n        assert m.dim() == 3, \"Indexing on BitMasks with {} returns a tensor with shape {}!\".format(\n            item, m.shape\n        )\n        return BitMasks(m)\n\n    @torch.jit.unused\n    def __iter__(self) -> torch.Tensor:\n        yield from self.tensor\n\n    @torch.jit.unused\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.tensor))\n        return s\n\n    def __len__(self) -> int:\n        return self.tensor.shape[0]\n\n    def nonempty(self) -> torch.Tensor:\n        \"\"\"\n        Find masks that are non-empty.\n\n        Returns:\n            Tensor: a BoolTensor which represents\n                whether each mask is empty (False) or non-empty (True).\n        \"\"\"\n        return self.tensor.flatten(1).any(dim=1)\n\n    @staticmethod\n    def from_polygon_masks(\n        polygon_masks: Union[\"PolygonMasks\", List[List[np.ndarray]]], height: int, width: int\n    ) -> \"BitMasks\":\n        \"\"\"\n        Args:\n            polygon_masks (list[list[ndarray]] or PolygonMasks)\n            height, width (int)\n        \"\"\"\n        if isinstance(polygon_masks, PolygonMasks):\n            polygon_masks = polygon_masks.polygons\n        masks = [polygons_to_bitmask(p, height, width) for p in polygon_masks]\n        if len(masks):\n            return BitMasks(torch.stack([torch.from_numpy(x) for x in masks]))\n        else:\n            return BitMasks(torch.empty(0, height, width, dtype=torch.bool))\n\n    @staticmethod\n    def from_roi_masks(roi_masks: \"ROIMasks\", height: int, width: int) -> \"BitMasks\":\n        \"\"\"\n        Args:\n            roi_masks:\n            height, width (int):\n        \"\"\"\n        return roi_masks.to_bitmasks(height, width)\n\n    def crop_and_resize(self, boxes: torch.Tensor, mask_size: int) -> torch.Tensor:\n        \"\"\"\n        Crop each bitmask by the given box, and resize results to (mask_size, mask_size).\n        This can be used to prepare training targets for Mask R-CNN.\n        It has less reconstruction error compared to rasterization with polygons.\n        However we observe no difference in accuracy,\n        but BitMasks requires more memory to store all the masks.\n\n        Args:\n            boxes (Tensor): Nx4 tensor storing the boxes for each mask\n            mask_size (int): the size of the rasterized mask.\n\n        Returns:\n            Tensor:\n                A bool tensor of shape (N, mask_size, mask_size), where\n                N is the number of predicted boxes for this image.\n        \"\"\"\n        assert len(boxes) == len(self), \"{} != {}\".format(len(boxes), len(self))\n        device = self.tensor.device\n\n        batch_inds = torch.arange(len(boxes), device=device).to(dtype=boxes.dtype)[:, None]\n        rois = torch.cat([batch_inds, boxes], dim=1)  # Nx5\n\n        bit_masks = self.tensor.to(dtype=torch.float32)\n        rois = rois.to(device=device)\n        output = (\n            ROIAlign((mask_size, mask_size), 1.0, 0, aligned=True)\n            .forward(bit_masks[:, None, :, :], rois)\n            .squeeze(1)\n        )\n        output = output >= 0.5\n        return output\n\n    def get_bounding_boxes(self) -> Boxes:\n        \"\"\"\n        Returns:\n            Boxes: tight bounding boxes around bitmasks.\n            If a mask is empty, it's bounding box will be all zero.\n        \"\"\"\n        boxes = torch.zeros(self.tensor.shape[0], 4, dtype=torch.float32)\n        x_any = torch.any(self.tensor, dim=1)\n        y_any = torch.any(self.tensor, dim=2)\n        for idx in range(self.tensor.shape[0]):\n            x = torch.where(x_any[idx, :])[0]\n            y = torch.where(y_any[idx, :])[0]\n            if len(x) > 0 and len(y) > 0:\n                boxes[idx, :] = torch.as_tensor(\n                    [x[0], y[0], x[-1] + 1, y[-1] + 1], dtype=torch.float32\n                )\n        return Boxes(boxes)\n\n    @staticmethod\n    def cat(bitmasks_list: List[\"BitMasks\"]) -> \"BitMasks\":\n        \"\"\"\n        Concatenates a list of BitMasks into a single BitMasks\n\n        Arguments:\n            bitmasks_list (list[BitMasks])\n\n        Returns:\n            BitMasks: the concatenated BitMasks\n        \"\"\"\n        assert isinstance(bitmasks_list, (list, tuple))\n        assert len(bitmasks_list) > 0\n        assert all(isinstance(bitmask, BitMasks) for bitmask in bitmasks_list)\n\n        cat_bitmasks = type(bitmasks_list[0])(torch.cat([bm.tensor for bm in bitmasks_list], dim=0))\n        return cat_bitmasks\n\n\nclass PolygonMasks:\n    \"\"\"\n    This class stores the segmentation masks for all objects in one image, in the form of polygons.\n\n    Attributes:\n        polygons: list[list[ndarray]]. Each ndarray is a float64 vector representing a polygon.\n    \"\"\"\n\n    def __init__(self, polygons: List[List[Union[torch.Tensor, np.ndarray]]]):\n        \"\"\"\n        Arguments:\n            polygons (list[list[np.ndarray]]): The first\n                level of the list correspond to individual instances,\n                the second level to all the polygons that compose the\n                instance, and the third level to the polygon coordinates.\n                The third level array should have the format of\n                [x0, y0, x1, y1, ..., xn, yn] (n >= 3).\n        \"\"\"\n        if not isinstance(polygons, list):\n            raise ValueError(\n                \"Cannot create PolygonMasks: Expect a list of list of polygons per image. \"\n                \"Got '{}' instead.\".format(type(polygons))\n            )\n\n        def _make_array(t: Union[torch.Tensor, np.ndarray]) -> np.ndarray:\n            # Use float64 for higher precision, because why not?\n            # Always put polygons on CPU (self.to is a no-op) since they\n            # are supposed to be small tensors.\n            # May need to change this assumption if GPU placement becomes useful\n            if isinstance(t, torch.Tensor):\n                t = t.cpu().numpy()\n            return np.asarray(t).astype(\"float64\")\n\n        def process_polygons(\n            polygons_per_instance: List[Union[torch.Tensor, np.ndarray]]\n        ) -> List[np.ndarray]:\n            if not isinstance(polygons_per_instance, list):\n                raise ValueError(\n                    \"Cannot create polygons: Expect a list of polygons per instance. \"\n                    \"Got '{}' instead.\".format(type(polygons_per_instance))\n                )\n            # transform each polygon to a numpy array\n            polygons_per_instance = [_make_array(p) for p in polygons_per_instance]\n            for polygon in polygons_per_instance:\n                if len(polygon) % 2 != 0 or len(polygon) < 6:\n                    raise ValueError(f\"Cannot create a polygon from {len(polygon)} coordinates.\")\n            return polygons_per_instance\n\n        self.polygons: List[List[np.ndarray]] = [\n            process_polygons(polygons_per_instance) for polygons_per_instance in polygons\n        ]\n\n    def to(self, *args: Any, **kwargs: Any) -> \"PolygonMasks\":\n        return self\n\n    @property\n    def device(self) -> torch.device:\n        return torch.device(\"cpu\")\n\n    def get_bounding_boxes(self) -> Boxes:\n        \"\"\"\n        Returns:\n            Boxes: tight bounding boxes around polygon masks.\n        \"\"\"\n        boxes = torch.zeros(len(self.polygons), 4, dtype=torch.float32)\n        for idx, polygons_per_instance in enumerate(self.polygons):\n            minxy = torch.as_tensor([float(\"inf\"), float(\"inf\")], dtype=torch.float32)\n            maxxy = torch.zeros(2, dtype=torch.float32)\n            for polygon in polygons_per_instance:\n                coords = torch.from_numpy(polygon).view(-1, 2).to(dtype=torch.float32)\n                minxy = torch.min(minxy, torch.min(coords, dim=0).values)\n                maxxy = torch.max(maxxy, torch.max(coords, dim=0).values)\n            boxes[idx, :2] = minxy\n            boxes[idx, 2:] = maxxy\n        return Boxes(boxes)\n\n    def nonempty(self) -> torch.Tensor:\n        \"\"\"\n        Find masks that are non-empty.\n\n        Returns:\n            Tensor:\n                a BoolTensor which represents whether each mask is empty (False) or not (True).\n        \"\"\"\n        keep = [1 if len(polygon) > 0 else 0 for polygon in self.polygons]\n        return torch.from_numpy(np.asarray(keep, dtype=bool))\n\n    def __getitem__(self, item: Union[int, slice, List[int], torch.BoolTensor]) -> \"PolygonMasks\":\n        \"\"\"\n        Support indexing over the instances and return a `PolygonMasks` object.\n        `item` can be:\n\n        1. An integer. It will return an object with only one instance.\n        2. A slice. It will return an object with the selected instances.\n        3. A list[int]. It will return an object with the selected instances,\n           correpsonding to the indices in the list.\n        4. A vector mask of type BoolTensor, whose length is num_instances.\n           It will return an object with the instances whose mask is nonzero.\n        \"\"\"\n        if isinstance(item, int):\n            selected_polygons = [self.polygons[item]]\n        elif isinstance(item, slice):\n            selected_polygons = self.polygons[item]\n        elif isinstance(item, list):\n            selected_polygons = [self.polygons[i] for i in item]\n        elif isinstance(item, torch.Tensor):\n            # Polygons is a list, so we have to move the indices back to CPU.\n            if item.dtype == torch.bool:\n                assert item.dim() == 1, item.shape\n                item = item.nonzero().squeeze(1).cpu().numpy().tolist()\n            elif item.dtype in [torch.int32, torch.int64]:\n                item = item.cpu().numpy().tolist()\n            else:\n                raise ValueError(\"Unsupported tensor dtype={} for indexing!\".format(item.dtype))\n            selected_polygons = [self.polygons[i] for i in item]\n        return PolygonMasks(selected_polygons)\n\n    def __iter__(self) -> Iterator[List[np.ndarray]]:\n        \"\"\"\n        Yields:\n            list[ndarray]: the polygons for one instance.\n            Each Tensor is a float64 vector representing a polygon.\n        \"\"\"\n        return iter(self.polygons)\n\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.polygons))\n        return s\n\n    def __len__(self) -> int:\n        return len(self.polygons)\n\n    def crop_and_resize(self, boxes: torch.Tensor, mask_size: int) -> torch.Tensor:\n        \"\"\"\n        Crop each mask by the given box, and resize results to (mask_size, mask_size).\n        This can be used to prepare training targets for Mask R-CNN.\n\n        Args:\n            boxes (Tensor): Nx4 tensor storing the boxes for each mask\n            mask_size (int): the size of the rasterized mask.\n\n        Returns:\n            Tensor: A bool tensor of shape (N, mask_size, mask_size), where\n            N is the number of predicted boxes for this image.\n        \"\"\"\n        assert len(boxes) == len(self), \"{} != {}\".format(len(boxes), len(self))\n\n        device = boxes.device\n        # Put boxes on the CPU, as the polygon representation is not efficient GPU-wise\n        # (several small tensors for representing a single instance mask)\n        boxes = boxes.to(torch.device(\"cpu\"))\n\n        results = [\n            rasterize_polygons_within_box(poly, box.numpy(), mask_size)\n            for poly, box in zip(self.polygons, boxes)\n        ]\n        \"\"\"\n        poly: list[list[float]], the polygons for one instance\n        box: a tensor of shape (4,)\n        \"\"\"\n        if len(results) == 0:\n            return torch.empty(0, mask_size, mask_size, dtype=torch.bool, device=device)\n        return torch.stack(results, dim=0).to(device=device)\n\n    def area(self):\n        \"\"\"\n        Computes area of the mask.\n        Only works with Polygons, using the shoelace formula:\n        https://stackoverflow.com/questions/24467972/calculate-area-of-polygon-given-x-y-coordinates\n\n        Returns:\n            Tensor: a vector, area for each instance\n        \"\"\"\n\n        area = []\n        for polygons_per_instance in self.polygons:\n            area_per_instance = 0\n            for p in polygons_per_instance:\n                area_per_instance += polygon_area(p[0::2], p[1::2])\n            area.append(area_per_instance)\n\n        return torch.tensor(area)\n\n    @staticmethod\n    def cat(polymasks_list: List[\"PolygonMasks\"]) -> \"PolygonMasks\":\n        \"\"\"\n        Concatenates a list of PolygonMasks into a single PolygonMasks\n\n        Arguments:\n            polymasks_list (list[PolygonMasks])\n\n        Returns:\n            PolygonMasks: the concatenated PolygonMasks\n        \"\"\"\n        assert isinstance(polymasks_list, (list, tuple))\n        assert len(polymasks_list) > 0\n        assert all(isinstance(polymask, PolygonMasks) for polymask in polymasks_list)\n\n        cat_polymasks = type(polymasks_list[0])(\n            list(itertools.chain.from_iterable(pm.polygons for pm in polymasks_list))\n        )\n        return cat_polymasks\n\n\nclass ROIMasks:\n    \"\"\"\n    Represent masks by N smaller masks defined in some ROIs. Once ROI boxes are given,\n    full-image bitmask can be obtained by \"pasting\" the mask on the region defined\n    by the corresponding ROI box.\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor):\n        \"\"\"\n        Args:\n            tensor: (N, M, M) mask tensor that defines the mask within each ROI.\n        \"\"\"\n        if tensor.dim() != 3:\n            raise ValueError(\"ROIMasks must take a masks of 3 dimension.\")\n        self.tensor = tensor\n\n    def to(self, device: torch.device) -> \"ROIMasks\":\n        return ROIMasks(self.tensor.to(device))\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    def __len__(self):\n        return self.tensor.shape[0]\n\n    def __getitem__(self, item) -> \"ROIMasks\":\n        \"\"\"\n        Returns:\n            ROIMasks: Create a new :class:`ROIMasks` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_masks = masks[2:10]`: return a slice of masks.\n        2. `new_masks = masks[vector]`, where vector is a torch.BoolTensor\n           with `length = len(masks)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned object might share storage with this object,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        t = self.tensor[item]\n        if t.dim() != 3:\n            raise ValueError(\n                f\"Indexing on ROIMasks with {item} returns a tensor with shape {t.shape}!\"\n            )\n        return ROIMasks(t)\n\n    @torch.jit.unused\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.tensor))\n        return s\n\n    @torch.jit.unused\n    def to_bitmasks(self, boxes: torch.Tensor, height, width, threshold=0.5):\n        \"\"\"\n        Args: see documentation of :func:`paste_masks_in_image`.\n        \"\"\"\n        from detectron2.layers.mask_ops import paste_masks_in_image, _paste_masks_tensor_shape\n\n        if torch.jit.is_tracing():\n            if isinstance(height, torch.Tensor):\n                paste_func = _paste_masks_tensor_shape\n            else:\n                paste_func = paste_masks_in_image\n        else:\n            paste_func = retry_if_cuda_oom(paste_masks_in_image)\n        bitmasks = paste_func(self.tensor, boxes.tensor, (height, width), threshold=threshold)\n        return BitMasks(bitmasks)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/structures/rotated_boxes.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom typing import List, Tuple\nimport torch\n\nfrom detectron2.layers.rotated_boxes import pairwise_iou_rotated\n\nfrom .boxes import Boxes\n\n\nclass RotatedBoxes(Boxes):\n    \"\"\"\n    This structure stores a list of rotated boxes as a Nx5 torch.Tensor.\n    It supports some common methods about boxes\n    (`area`, `clip`, `nonempty`, etc),\n    and also behaves like a Tensor\n    (support indexing, `to(device)`, `.device`, and iteration over all boxes)\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor):\n        \"\"\"\n        Args:\n            tensor (Tensor[float]): a Nx5 matrix.  Each row is\n                (x_center, y_center, width, height, angle),\n                in which angle is represented in degrees.\n                While there's no strict range restriction for it,\n                the recommended principal range is between [-180, 180) degrees.\n\n        Assume we have a horizontal box B = (x_center, y_center, width, height),\n        where width is along the x-axis and height is along the y-axis.\n        The rotated box B_rot (x_center, y_center, width, height, angle)\n        can be seen as:\n\n        1. When angle == 0:\n           B_rot == B\n        2. When angle > 0:\n           B_rot is obtained by rotating B w.r.t its center by :math:`|angle|` degrees CCW;\n        3. When angle < 0:\n           B_rot is obtained by rotating B w.r.t its center by :math:`|angle|` degrees CW.\n\n        Mathematically, since the right-handed coordinate system for image space\n        is (y, x), where y is top->down and x is left->right, the 4 vertices of the\n        rotated rectangle :math:`(yr_i, xr_i)` (i = 1, 2, 3, 4) can be obtained from\n        the vertices of the horizontal rectangle :math:`(y_i, x_i)` (i = 1, 2, 3, 4)\n        in the following way (:math:`\\\\theta = angle*\\\\pi/180` is the angle in radians,\n        :math:`(y_c, x_c)` is the center of the rectangle):\n\n        .. math::\n\n            yr_i = \\\\cos(\\\\theta) (y_i - y_c) - \\\\sin(\\\\theta) (x_i - x_c) + y_c,\n\n            xr_i = \\\\sin(\\\\theta) (y_i - y_c) + \\\\cos(\\\\theta) (x_i - x_c) + x_c,\n\n        which is the standard rigid-body rotation transformation.\n\n        Intuitively, the angle is\n        (1) the rotation angle from y-axis in image space\n        to the height vector (top->down in the box's local coordinate system)\n        of the box in CCW, and\n        (2) the rotation angle from x-axis in image space\n        to the width vector (left->right in the box's local coordinate system)\n        of the box in CCW.\n\n        More intuitively, consider the following horizontal box ABCD represented\n        in (x1, y1, x2, y2): (3, 2, 7, 4),\n        covering the [3, 7] x [2, 4] region of the continuous coordinate system\n        which looks like this:\n\n        .. code:: none\n\n            O--------> x\n            |\n            |  A---B\n            |  |   |\n            |  D---C\n            |\n            v y\n\n        Note that each capital letter represents one 0-dimensional geometric point\n        instead of a 'square pixel' here.\n\n        In the example above, using (x, y) to represent a point we have:\n\n        .. math::\n\n            O = (0, 0), A = (3, 2), B = (7, 2), C = (7, 4), D = (3, 4)\n\n        We name vector AB = vector DC as the width vector in box's local coordinate system, and\n        vector AD = vector BC as the height vector in box's local coordinate system. Initially,\n        when angle = 0 degree, they're aligned with the positive directions of x-axis and y-axis\n        in the image space, respectively.\n\n        For better illustration, we denote the center of the box as E,\n\n        .. code:: none\n\n            O--------> x\n            |\n            |  A---B\n            |  | E |\n            |  D---C\n            |\n            v y\n\n        where the center E = ((3+7)/2, (2+4)/2) = (5, 3).\n\n        Also,\n\n        .. math::\n\n            width = |AB| = |CD| = 7 - 3 = 4,\n            height = |AD| = |BC| = 4 - 2 = 2.\n\n        Therefore, the corresponding representation for the same shape in rotated box in\n        (x_center, y_center, width, height, angle) format is:\n\n        (5, 3, 4, 2, 0),\n\n        Now, let's consider (5, 3, 4, 2, 90), which is rotated by 90 degrees\n        CCW (counter-clockwise) by definition. It looks like this:\n\n        .. code:: none\n\n            O--------> x\n            |   B-C\n            |   | |\n            |   |E|\n            |   | |\n            |   A-D\n            v y\n\n        The center E is still located at the same point (5, 3), while the vertices\n        ABCD are rotated by 90 degrees CCW with regard to E:\n        A = (4, 5), B = (4, 1), C = (6, 1), D = (6, 5)\n\n        Here, 90 degrees can be seen as the CCW angle to rotate from y-axis to\n        vector AD or vector BC (the top->down height vector in box's local coordinate system),\n        or the CCW angle to rotate from x-axis to vector AB or vector DC (the left->right\n        width vector in box's local coordinate system).\n\n        .. math::\n\n            width = |AB| = |CD| = 5 - 1 = 4,\n            height = |AD| = |BC| = 6 - 4 = 2.\n\n        Next, how about (5, 3, 4, 2, -90), which is rotated by 90 degrees CW (clockwise)\n        by definition? It looks like this:\n\n        .. code:: none\n\n            O--------> x\n            |   D-A\n            |   | |\n            |   |E|\n            |   | |\n            |   C-B\n            v y\n\n        The center E is still located at the same point (5, 3), while the vertices\n        ABCD are rotated by 90 degrees CW with regard to E:\n        A = (6, 1), B = (6, 5), C = (4, 5), D = (4, 1)\n\n        .. math::\n\n            width = |AB| = |CD| = 5 - 1 = 4,\n            height = |AD| = |BC| = 6 - 4 = 2.\n\n        This covers exactly the same region as (5, 3, 4, 2, 90) does, and their IoU\n        will be 1. However, these two will generate different RoI Pooling results and\n        should not be treated as an identical box.\n\n        On the other hand, it's easy to see that (X, Y, W, H, A) is identical to\n        (X, Y, W, H, A+360N), for any integer N. For example (5, 3, 4, 2, 270) would be\n        identical to (5, 3, 4, 2, -90), because rotating the shape 270 degrees CCW is\n        equivalent to rotating the same shape 90 degrees CW.\n\n        We could rotate further to get (5, 3, 4, 2, 180), or (5, 3, 4, 2, -180):\n\n        .. code:: none\n\n            O--------> x\n            |\n            |  C---D\n            |  | E |\n            |  B---A\n            |\n            v y\n\n        .. math::\n\n            A = (7, 4), B = (3, 4), C = (3, 2), D = (7, 2),\n\n            width = |AB| = |CD| = 7 - 3 = 4,\n            height = |AD| = |BC| = 4 - 2 = 2.\n\n        Finally, this is a very inaccurate (heavily quantized) illustration of\n        how (5, 3, 4, 2, 60) looks like in case anyone wonders:\n\n        .. code:: none\n\n            O--------> x\n            |     B\\\n            |    /  C\n            |   /E /\n            |  A  /\n            |   `D\n            v y\n\n        It's still a rectangle with center of (5, 3), width of 4 and height of 2,\n        but its angle (and thus orientation) is somewhere between\n        (5, 3, 4, 2, 0) and (5, 3, 4, 2, 90).\n        \"\"\"\n        device = tensor.device if isinstance(tensor, torch.Tensor) else torch.device(\"cpu\")\n        tensor = torch.as_tensor(tensor, dtype=torch.float32, device=device)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that does not depend on\n            # the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((0, 5)).to(dtype=torch.float32, device=device)\n        assert tensor.dim() == 2 and tensor.size(-1) == 5, tensor.size()\n\n        self.tensor = tensor\n\n    def clone(self) -> \"RotatedBoxes\":\n        \"\"\"\n        Clone the RotatedBoxes.\n\n        Returns:\n            RotatedBoxes\n        \"\"\"\n        return RotatedBoxes(self.tensor.clone())\n\n    def to(self, device: torch.device):\n        # Boxes are assumed float32 and does not support to(dtype)\n        return RotatedBoxes(self.tensor.to(device=device))\n\n    def area(self) -> torch.Tensor:\n        \"\"\"\n        Computes the area of all the boxes.\n\n        Returns:\n            torch.Tensor: a vector with areas of each box.\n        \"\"\"\n        box = self.tensor\n        area = box[:, 2] * box[:, 3]\n        return area\n\n    # Avoid in-place operations so that we can torchscript; NOTE: this creates a new tensor\n    def normalize_angles(self) -> None:\n        \"\"\"\n        Restrict angles to the range of [-180, 180) degrees\n        \"\"\"\n        angle_tensor = (self.tensor[:, 4] + 180.0) % 360.0 - 180.0\n        self.tensor = torch.cat((self.tensor[:, :4], angle_tensor[:, None]), dim=1)\n\n    def clip(self, box_size: Tuple[int, int], clip_angle_threshold: float = 1.0) -> None:\n        \"\"\"\n        Clip (in place) the boxes by limiting x coordinates to the range [0, width]\n        and y coordinates to the range [0, height].\n\n        For RRPN:\n        Only clip boxes that are almost horizontal with a tolerance of\n        clip_angle_threshold to maintain backward compatibility.\n\n        Rotated boxes beyond this threshold are not clipped for two reasons:\n\n        1. There are potentially multiple ways to clip a rotated box to make it\n           fit within the image.\n        2. It's tricky to make the entire rectangular box fit within the image\n           and still be able to not leave out pixels of interest.\n\n        Therefore we rely on ops like RoIAlignRotated to safely handle this.\n\n        Args:\n            box_size (height, width): The clipping box's size.\n            clip_angle_threshold:\n                Iff. abs(normalized(angle)) <= clip_angle_threshold (in degrees),\n                we do the clipping as horizontal boxes.\n        \"\"\"\n        h, w = box_size\n\n        # normalize angles to be within (-180, 180] degrees\n        self.normalize_angles()\n\n        idx = torch.where(torch.abs(self.tensor[:, 4]) <= clip_angle_threshold)[0]\n\n        # convert to (x1, y1, x2, y2)\n        x1 = self.tensor[idx, 0] - self.tensor[idx, 2] / 2.0\n        y1 = self.tensor[idx, 1] - self.tensor[idx, 3] / 2.0\n        x2 = self.tensor[idx, 0] + self.tensor[idx, 2] / 2.0\n        y2 = self.tensor[idx, 1] + self.tensor[idx, 3] / 2.0\n\n        # clip\n        x1.clamp_(min=0, max=w)\n        y1.clamp_(min=0, max=h)\n        x2.clamp_(min=0, max=w)\n        y2.clamp_(min=0, max=h)\n\n        # convert back to (xc, yc, w, h)\n        self.tensor[idx, 0] = (x1 + x2) / 2.0\n        self.tensor[idx, 1] = (y1 + y2) / 2.0\n        # make sure widths and heights do not increase due to numerical errors\n        self.tensor[idx, 2] = torch.min(self.tensor[idx, 2], x2 - x1)\n        self.tensor[idx, 3] = torch.min(self.tensor[idx, 3], y2 - y1)\n\n    def nonempty(self, threshold: float = 0.0) -> torch.Tensor:\n        \"\"\"\n        Find boxes that are non-empty.\n        A box is considered empty, if either of its side is no larger than threshold.\n\n        Returns:\n            Tensor: a binary vector which represents\n            whether each box is empty (False) or non-empty (True).\n        \"\"\"\n        box = self.tensor\n        widths = box[:, 2]\n        heights = box[:, 3]\n        keep = (widths > threshold) & (heights > threshold)\n        return keep\n\n    def __getitem__(self, item) -> \"RotatedBoxes\":\n        \"\"\"\n        Returns:\n            RotatedBoxes: Create a new :class:`RotatedBoxes` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_boxes = boxes[3]`: return a `RotatedBoxes` which contains only one box.\n        2. `new_boxes = boxes[2:10]`: return a slice of boxes.\n        3. `new_boxes = boxes[vector]`, where vector is a torch.ByteTensor\n           with `length = len(boxes)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned RotatedBoxes might share storage with this RotatedBoxes,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return RotatedBoxes(self.tensor[item].view(1, -1))\n        b = self.tensor[item]\n        assert b.dim() == 2, \"Indexing on RotatedBoxes with {} failed to return a matrix!\".format(\n            item\n        )\n        return RotatedBoxes(b)\n\n    def __len__(self) -> int:\n        return self.tensor.shape[0]\n\n    def __repr__(self) -> str:\n        return \"RotatedBoxes(\" + str(self.tensor) + \")\"\n\n    def inside_box(self, box_size: Tuple[int, int], boundary_threshold: int = 0) -> torch.Tensor:\n        \"\"\"\n        Args:\n            box_size (height, width): Size of the reference box covering\n                [0, width] x [0, height]\n            boundary_threshold (int): Boxes that extend beyond the reference box\n                boundary by more than boundary_threshold are considered \"outside\".\n\n        For RRPN, it might not be necessary to call this function since it's common\n        for rotated box to extend to outside of the image boundaries\n        (the clip function only clips the near-horizontal boxes)\n\n        Returns:\n            a binary vector, indicating whether each box is inside the reference box.\n        \"\"\"\n        height, width = box_size\n\n        cnt_x = self.tensor[..., 0]\n        cnt_y = self.tensor[..., 1]\n        half_w = self.tensor[..., 2] / 2.0\n        half_h = self.tensor[..., 3] / 2.0\n        a = self.tensor[..., 4]\n        c = torch.abs(torch.cos(a * math.pi / 180.0))\n        s = torch.abs(torch.sin(a * math.pi / 180.0))\n        # This basically computes the horizontal bounding rectangle of the rotated box\n        max_rect_dx = c * half_w + s * half_h\n        max_rect_dy = c * half_h + s * half_w\n\n        inds_inside = (\n            (cnt_x - max_rect_dx >= -boundary_threshold)\n            & (cnt_y - max_rect_dy >= -boundary_threshold)\n            & (cnt_x + max_rect_dx < width + boundary_threshold)\n            & (cnt_y + max_rect_dy < height + boundary_threshold)\n        )\n\n        return inds_inside\n\n    def get_centers(self) -> torch.Tensor:\n        \"\"\"\n        Returns:\n            The box centers in a Nx2 array of (x, y).\n        \"\"\"\n        return self.tensor[:, :2]\n\n    def scale(self, scale_x: float, scale_y: float) -> None:\n        \"\"\"\n        Scale the rotated box with horizontal and vertical scaling factors\n        Note: when scale_factor_x != scale_factor_y,\n        the rotated box does not preserve the rectangular shape when the angle\n        is not a multiple of 90 degrees under resize transformation.\n        Instead, the shape is a parallelogram (that has skew)\n        Here we make an approximation by fitting a rotated rectangle to the parallelogram.\n        \"\"\"\n        self.tensor[:, 0] *= scale_x\n        self.tensor[:, 1] *= scale_y\n        theta = self.tensor[:, 4] * math.pi / 180.0\n        c = torch.cos(theta)\n        s = torch.sin(theta)\n\n        # In image space, y is top->down and x is left->right\n        # Consider the local coordintate system for the rotated box,\n        # where the box center is located at (0, 0), and the four vertices ABCD are\n        # A(-w / 2, -h / 2), B(w / 2, -h / 2), C(w / 2, h / 2), D(-w / 2, h / 2)\n        # the midpoint of the left edge AD of the rotated box E is:\n        # E = (A+D)/2 = (-w / 2, 0)\n        # the midpoint of the top edge AB of the rotated box F is:\n        # F(0, -h / 2)\n        # To get the old coordinates in the global system, apply the rotation transformation\n        # (Note: the right-handed coordinate system for image space is yOx):\n        # (old_x, old_y) = (s * y + c * x, c * y - s * x)\n        # E(old) = (s * 0 + c * (-w/2), c * 0 - s * (-w/2)) = (-c * w / 2, s * w / 2)\n        # F(old) = (s * (-h / 2) + c * 0, c * (-h / 2) - s * 0) = (-s * h / 2, -c * h / 2)\n        # After applying the scaling factor (sfx, sfy):\n        # E(new) = (-sfx * c * w / 2, sfy * s * w / 2)\n        # F(new) = (-sfx * s * h / 2, -sfy * c * h / 2)\n        # The new width after scaling tranformation becomes:\n\n        # w(new) = |E(new) - O| * 2\n        #        = sqrt[(sfx * c * w / 2)^2 + (sfy * s * w / 2)^2] * 2\n        #        = sqrt[(sfx * c)^2 + (sfy * s)^2] * w\n        # i.e., scale_factor_w = sqrt[(sfx * c)^2 + (sfy * s)^2]\n        #\n        # For example,\n        # when angle = 0 or 180, |c| = 1, s = 0, scale_factor_w == scale_factor_x;\n        # when |angle| = 90, c = 0, |s| = 1, scale_factor_w == scale_factor_y\n        self.tensor[:, 2] *= torch.sqrt((scale_x * c) ** 2 + (scale_y * s) ** 2)\n\n        # h(new) = |F(new) - O| * 2\n        #        = sqrt[(sfx * s * h / 2)^2 + (sfy * c * h / 2)^2] * 2\n        #        = sqrt[(sfx * s)^2 + (sfy * c)^2] * h\n        # i.e., scale_factor_h = sqrt[(sfx * s)^2 + (sfy * c)^2]\n        #\n        # For example,\n        # when angle = 0 or 180, |c| = 1, s = 0, scale_factor_h == scale_factor_y;\n        # when |angle| = 90, c = 0, |s| = 1, scale_factor_h == scale_factor_x\n        self.tensor[:, 3] *= torch.sqrt((scale_x * s) ** 2 + (scale_y * c) ** 2)\n\n        # The angle is the rotation angle from y-axis in image space to the height\n        # vector (top->down in the box's local coordinate system) of the box in CCW.\n        #\n        # angle(new) = angle_yOx(O - F(new))\n        #            = angle_yOx( (sfx * s * h / 2, sfy * c * h / 2) )\n        #            = atan2(sfx * s * h / 2, sfy * c * h / 2)\n        #            = atan2(sfx * s, sfy * c)\n        #\n        # For example,\n        # when sfx == sfy, angle(new) == atan2(s, c) == angle(old)\n        self.tensor[:, 4] = torch.atan2(scale_x * s, scale_y * c) * 180 / math.pi\n\n    @classmethod\n    def cat(cls, boxes_list: List[\"RotatedBoxes\"]) -> \"RotatedBoxes\":\n        \"\"\"\n        Concatenates a list of RotatedBoxes into a single RotatedBoxes\n\n        Arguments:\n            boxes_list (list[RotatedBoxes])\n\n        Returns:\n            RotatedBoxes: the concatenated RotatedBoxes\n        \"\"\"\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0))\n        assert all([isinstance(box, RotatedBoxes) for box in boxes_list])\n\n        # use torch.cat (v.s. layers.cat) so the returned boxes never share storage with input\n        cat_boxes = cls(torch.cat([b.tensor for b in boxes_list], dim=0))\n        return cat_boxes\n\n    @property\n    def device(self) -> torch.device:\n        return self.tensor.device\n\n    @torch.jit.unused\n    def __iter__(self):\n        \"\"\"\n        Yield a box as a Tensor of shape (5,) at a time.\n        \"\"\"\n        yield from self.tensor\n\n\ndef pairwise_iou(boxes1: RotatedBoxes, boxes2: RotatedBoxes) -> None:\n    \"\"\"\n    Given two lists of rotated boxes of size N and M,\n    compute the IoU (intersection over union)\n    between **all** N x M pairs of boxes.\n    The box order must be (x_center, y_center, width, height, angle).\n\n    Args:\n        boxes1, boxes2 (RotatedBoxes):\n            two `RotatedBoxes`. Contains N & M rotated boxes, respectively.\n\n    Returns:\n        Tensor: IoU, sized [N,M].\n    \"\"\"\n\n    return pairwise_iou_rotated(boxes1.tensor, boxes2.tensor)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/__init__.py",
    "content": "# flake8: noqa\n# Copyright (c) OpenMMLab. All rights reserved.\nfrom .config import Config, ConfigDict, DictAction\nfrom .misc import (check_prerequisites, concat_list, deprecated_api_warning,\n                   has_method, import_modules_from_strings, is_list_of,\n                   is_method_overridden, is_seq_of, is_str, is_tuple_of,\n                   iter_cast, list_cast, requires_executable, requires_package,\n                   slice_list, to_1tuple, to_2tuple, to_3tuple, to_4tuple,\n                   to_ntuple, tuple_cast)\nfrom .path import (check_file_exist, fopen, is_filepath, mkdir_or_exist,\n                   scandir, symlink)\nfrom .progressbar import (ProgressBar, track_iter_progress,\n                          track_parallel_progress, track_progress)\nfrom .timer import Timer, TimerError, check_time\nfrom .version_utils import digit_version, get_git_hash\nimport torch\nfrom .logging import get_logger, print_log\nfrom .registry import Registry, build_from_cfg\nfrom .hub import load_url\nfrom .logging import get_logger, print_log\nfrom .logger import get_root_logger\nfrom .collect_env import collect_env\nfrom .runner_utils import *\nfrom .fp16_utils import LossScaler, auto_fp16, force_fp32, wrap_fp16_model, TORCH_VERSION\nfrom .checkpoint import load_checkpoint, save_checkpoint\nfrom .log_buffer import LogBuffer\nfrom .priority import Priority, get_priority\nfrom .memory import retry_if_cuda_oom\nfrom .visual import convert_color, save_tensor"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/bricks.py",
    "content": "import functools\nimport time\nfrom collections import defaultdict\nimport torch\ntime_maps = defaultdict(lambda :0.)\ncount_maps = defaultdict(lambda :0.)\ndef run_time(name):\n    def middle(fn):\n        def wrapper(*args, **kwargs):\n            torch.cuda.synchronize()\n            start = time.time()\n            res = fn(*args, **kwargs)\n            torch.cuda.synchronize()\n            time_maps['%s : %s'%(name, fn.__name__) ] += time.time()-start\n            count_maps['%s : %s'%(name, fn.__name__) ] +=1\n            print(\"%s : %s takes up %f \"% (name, fn.__name__,time_maps['%s : %s'%(name, fn.__name__) ] /count_maps['%s : %s'%(name, fn.__name__) ] ))\n            return res\n        return wrapper\n    return middle\n    "
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/checkpoint.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport io\nimport os\nimport os.path as osp\nimport pkgutil\nimport re\nimport time\nimport warnings\nfrom collections import OrderedDict\nimport torch\nfrom torch.optim import Optimizer\nfrom .logging import print_log\nfrom .runner_utils import get_dist_info\nfrom ..parallel import is_module_wrapper\nfrom mmcv.fileio.file_client import FileClient\n\ndef load_checkpoint(model,\n                    filename,\n                    map_location=None,\n                    strict=False,\n                    logger=None,\n                    revise_keys=[(r'^module\\.', '')]):\n    \"\"\"Load checkpoint from a file or URI.\n\n    Args:\n        model (Module): Module to load checkpoint.\n        filename (str): Accept local filepath\n        map_location (str): Same as :func:`torch.load`.\n        strict (bool): Whether to allow different params for the model and\n            checkpoint.\n        logger (:mod:`logging.Logger` or None): The logger for error message.\n        revise_keys (list): A list of customized keywords to modify the\n            state_dict in checkpoint. Each item is a (pattern, replacement)\n            pair of the regular expression operations. Default: strip\n            the prefix 'module.' by [(r'^module\\\\.', '')].\n\n    Returns:\n        dict or OrderedDict: The loaded checkpoint.\n    \"\"\"\n    print_log(\n        f'load checkpoint from path: {filename}', logger)\n    if not osp.isfile(filename):\n        raise IOError(f'{filename} is not a checkpoint file')\n    checkpoint = torch.load(filename, map_location=map_location)\n    # OrderedDict is a subclass of dict\n    if not isinstance(checkpoint, dict):\n        raise RuntimeError(\n            f'No state_dict found in checkpoint file {filename}')\n    # get state_dict from checkpoint\n    if 'state_dict' in checkpoint:\n        state_dict = checkpoint['state_dict']\n    else:\n        state_dict = checkpoint\n\n    # strip prefix of state_dict\n    metadata = getattr(state_dict, '_metadata', OrderedDict())\n    for p, r in revise_keys:\n        state_dict = OrderedDict(\n            {re.sub(p, r, k): v\n             for k, v in state_dict.items()})\n    # Keep metadata in state_dict\n    state_dict._metadata = metadata\n\n    # load state_dict\n    if is_module_wrapper(model):\n        model = model.module\n    missing_keys, unexpected_keys = model.load_state_dict(state_dict, strict)\n    # ignore \"num_batches_tracked\" of BN layers\n    err_msg = []\n    if unexpected_keys:\n        err_msg.append('unexpected key in source '\n                       f'state_dict: {\", \".join(unexpected_keys)}\\n')\n    if missing_keys:\n        err_msg.append(\n            f'missing keys in source state_dict: {\", \".join(missing_keys)}\\n')\n\n    rank, _ = get_dist_info()\n    if len(err_msg) > 0 and rank == 0:\n        err_msg.insert(\n            0, 'The model and loaded state dict do not match exactly\\n')\n        err_msg = '\\n'.join(err_msg)\n        if strict:\n            raise RuntimeError(err_msg)\n        elif logger is not None:\n            logger.warning(err_msg)\n        else:\n            print(err_msg)\n    return checkpoint\n\ndef weights_to_cpu(state_dict):\n    \"\"\"Copy a model state_dict to cpu.\n\n    Args:\n        state_dict (OrderedDict): Model weights on GPU.\n\n    Returns:\n        OrderedDict: Model weights on GPU.\n    \"\"\"\n    state_dict_cpu = OrderedDict()\n    for key, val in state_dict.items():\n        state_dict_cpu[key] = val.cpu()\n    # Keep metadata in state_dict\n    state_dict_cpu._metadata = getattr(state_dict, '_metadata', OrderedDict())\n    return state_dict_cpu\n\ndef save_checkpoint(model,\n                    filename,\n                    optimizer=None,\n                    meta=None,\n                    file_client_args=None):\n    \"\"\"Save checkpoint to file.\n\n    The checkpoint will have 3 fields: ``meta``, ``state_dict`` and\n    ``optimizer``. By default ``meta`` will contain version and time info.\n\n    Args:\n        model (Module): Module whose params are to be saved.\n        filename (str): Checkpoint filename.\n        optimizer (:obj:`Optimizer`, optional): Optimizer to be saved.\n        meta (dict, optional): Metadata to be saved in checkpoint.\n        file_client_args (dict, optional): Arguments to instantiate a\n            FileClient. See :class:`mmcv.fileio.FileClient` for details.\n            Default: None.\n            `New in version 1.3.16.`\n    \"\"\"\n    if meta is None:\n        meta = {}\n    elif not isinstance(meta, dict):\n        raise TypeError(f'meta must be a dict or None, but got {type(meta)}')\n    meta.update(time=time.asctime())\n\n    if is_module_wrapper(model):\n        model = model.module\n\n    if hasattr(model, 'CLASSES') and model.CLASSES is not None:\n        # save class name to the meta\n        meta.update(CLASSES=model.CLASSES)\n    checkpoint = {\n        'meta': meta,\n        'state_dict': weights_to_cpu(model.state_dict()),\n    }\n    # save optimizer state dict in the checkpoint\n    if isinstance(optimizer, Optimizer):\n        checkpoint['optimizer'] = optimizer.state_dict()\n    elif isinstance(optimizer, dict):\n        checkpoint['optimizer'] = {}\n        for name, optim in optimizer.items():\n            checkpoint['optimizer'][name] = optim.state_dict()\n\n    file_client = FileClient.infer_client(file_client_args, filename)\n    with io.BytesIO() as f:\n        torch.save(checkpoint, f)\n        file_client.put(f.getvalue(), filename)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/collect_env.py",
    "content": "from mmcv.utils import get_git_hash\nfrom mmcv import __version__\n\ndef collect_env():\n    \"\"\"Collect the information of the running environments.\"\"\"\n    env_info = {}\n    env_info['MMCV'] = __version__\n    return env_info\n\n\nif __name__ == '__main__':\n    for name, val in collect_env().items():\n        print(f'{name}: {val}')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/config.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport ast\nimport copy\nimport os\nimport os.path as osp\nimport platform\nimport shutil\nimport sys\nimport tempfile\nimport uuid\nimport warnings\nfrom argparse import Action, ArgumentParser\nfrom collections import abc\nfrom importlib import import_module\nfrom mmcv.fileio.io import load, dump\n\nfrom addict import Dict\nfrom yapf.yapflib.yapf_api import FormatCode\n\nfrom .misc import import_modules_from_strings\nfrom .path import check_file_exist\n\nif platform.system() == 'Windows':\n    import regex as re\nelse:\n    import re\n\nBASE_KEY = '_base_'\nDELETE_KEY = '_delete_'\nDEPRECATION_KEY = '_deprecation_'\nRESERVED_KEYS = ['filename', 'text', 'pretty_text']\n\n\nclass ConfigDict(Dict):\n\n    def __missing__(self, name):\n        raise KeyError(name)\n\n    def __getattr__(self, name):\n        try:\n            value = super(ConfigDict, self).__getattr__(name)\n        except KeyError:\n            ex = AttributeError(f\"'{self.__class__.__name__}' object has no \"\n                                f\"attribute '{name}'\")\n        except Exception as e:\n            ex = e\n        else:\n            return value\n        raise ex\n\n\ndef add_args(parser, cfg, prefix=''):\n    for k, v in cfg.items():\n        if isinstance(v, str):\n            parser.add_argument('--' + prefix + k)\n        elif isinstance(v, int):\n            parser.add_argument('--' + prefix + k, type=int)\n        elif isinstance(v, float):\n            parser.add_argument('--' + prefix + k, type=float)\n        elif isinstance(v, bool):\n            parser.add_argument('--' + prefix + k, action='store_true')\n        elif isinstance(v, dict):\n            add_args(parser, v, prefix + k + '.')\n        elif isinstance(v, abc.Iterable):\n            parser.add_argument('--' + prefix + k, type=type(v[0]), nargs='+')\n        else:\n            print(f'cannot parse key {prefix + k} of type {type(v)}')\n    return parser\n\n\nclass Config:\n    \"\"\"A facility for config and config files.\n\n    It supports common file formats as configs: python/json/yaml. The interface\n    is the same as a dict object and also allows access config values as\n    attributes.\n\n    Example:\n        >>> cfg = Config(dict(a=1, b=dict(b1=[0, 1])))\n        >>> cfg.a\n        1\n        >>> cfg.b\n        {'b1': [0, 1]}\n        >>> cfg.b.b1\n        [0, 1]\n        >>> cfg = Config.fromfile('tests/data/config/a.py')\n        >>> cfg.filename\n        \"/home/kchen/projects/mmcv/tests/data/config/a.py\"\n        >>> cfg.item4\n        'test'\n        >>> cfg\n        \"Config [path: /home/kchen/projects/mmcv/tests/data/config/a.py]: \"\n        \"{'item1': [1, 2], 'item2': {'a': 0}, 'item3': True, 'item4': 'test'}\"\n    \"\"\"\n\n    @staticmethod\n    def _validate_py_syntax(filename):\n        with open(filename, 'r', encoding='utf-8') as f:\n            # Setting encoding explicitly to resolve coding issue on windows\n            content = f.read()\n        try:\n            ast.parse(content)\n        except SyntaxError as e:\n            raise SyntaxError('There are syntax errors in config '\n                              f'file {filename}: {e}')\n\n    @staticmethod\n    def _substitute_predefined_vars(filename, temp_config_name):\n        file_dirname = osp.dirname(filename)\n        file_basename = osp.basename(filename)\n        file_basename_no_extension = osp.splitext(file_basename)[0]\n        file_extname = osp.splitext(filename)[1]\n        support_templates = dict(\n            fileDirname=file_dirname,\n            fileBasename=file_basename,\n            fileBasenameNoExtension=file_basename_no_extension,\n            fileExtname=file_extname)\n        with open(filename, 'r', encoding='utf-8') as f:\n            # Setting encoding explicitly to resolve coding issue on windows\n            config_file = f.read()\n        for key, value in support_templates.items():\n            regexp = r'\\{\\{\\s*' + str(key) + r'\\s*\\}\\}'\n            value = value.replace('\\\\', '/')\n            config_file = re.sub(regexp, value, config_file)\n        with open(temp_config_name, 'w', encoding='utf-8') as tmp_config_file:\n            tmp_config_file.write(config_file)\n\n    @staticmethod\n    def _pre_substitute_base_vars(filename, temp_config_name):\n        \"\"\"Substitute base variable placehoders to string, so that parsing\n        would work.\"\"\"\n        with open(filename, 'r', encoding='utf-8') as f:\n            # Setting encoding explicitly to resolve coding issue on windows\n            config_file = f.read()\n        base_var_dict = {}\n        regexp = r'\\{\\{\\s*' + BASE_KEY + r'\\.([\\w\\.]+)\\s*\\}\\}'\n        base_vars = set(re.findall(regexp, config_file))\n        for base_var in base_vars:\n            randstr = f'_{base_var}_{uuid.uuid4().hex.lower()[:6]}'\n            base_var_dict[randstr] = base_var\n            regexp = r'\\{\\{\\s*' + BASE_KEY + r'\\.' + base_var + r'\\s*\\}\\}'\n            config_file = re.sub(regexp, f'\"{randstr}\"', config_file)\n        with open(temp_config_name, 'w', encoding='utf-8') as tmp_config_file:\n            tmp_config_file.write(config_file)\n        return base_var_dict\n\n    @staticmethod\n    def _substitute_base_vars(cfg, base_var_dict, base_cfg):\n        \"\"\"Substitute variable strings to their actual values.\"\"\"\n        cfg = copy.deepcopy(cfg)\n\n        if isinstance(cfg, dict):\n            for k, v in cfg.items():\n                if isinstance(v, str) and v in base_var_dict:\n                    new_v = base_cfg\n                    for new_k in base_var_dict[v].split('.'):\n                        new_v = new_v[new_k]\n                    cfg[k] = new_v\n                elif isinstance(v, (list, tuple, dict)):\n                    cfg[k] = Config._substitute_base_vars(\n                        v, base_var_dict, base_cfg)\n        elif isinstance(cfg, tuple):\n            cfg = tuple(\n                Config._substitute_base_vars(c, base_var_dict, base_cfg)\n                for c in cfg)\n        elif isinstance(cfg, list):\n            cfg = [\n                Config._substitute_base_vars(c, base_var_dict, base_cfg)\n                for c in cfg\n            ]\n        elif isinstance(cfg, str) and cfg in base_var_dict:\n            new_v = base_cfg\n            for new_k in base_var_dict[cfg].split('.'):\n                new_v = new_v[new_k]\n            cfg = new_v\n\n        return cfg\n\n    @staticmethod\n    def _file2dict(filename, use_predefined_variables=True):\n        filename = osp.abspath(osp.expanduser(filename))\n        check_file_exist(filename)\n        fileExtname = osp.splitext(filename)[1]\n        if fileExtname not in ['.py', '.json', '.yaml', '.yml']:\n            raise IOError('Only py/yml/yaml/json type are supported now!')\n\n        with tempfile.TemporaryDirectory() as temp_config_dir:\n            temp_config_file = tempfile.NamedTemporaryFile(\n                dir=temp_config_dir, suffix=fileExtname)\n            if platform.system() == 'Windows':\n                temp_config_file.close()\n            temp_config_name = osp.basename(temp_config_file.name)\n            # Substitute predefined variables\n            if use_predefined_variables:\n                Config._substitute_predefined_vars(filename,\n                                                   temp_config_file.name)\n            else:\n                shutil.copyfile(filename, temp_config_file.name)\n            # Substitute base variables from placeholders to strings\n            base_var_dict = Config._pre_substitute_base_vars(\n                temp_config_file.name, temp_config_file.name)\n\n            if filename.endswith('.py'):\n                temp_module_name = osp.splitext(temp_config_name)[0]\n                sys.path.insert(0, temp_config_dir)\n                Config._validate_py_syntax(filename)\n                mod = import_module(temp_module_name)\n                sys.path.pop(0)\n                cfg_dict = {\n                    name: value\n                    for name, value in mod.__dict__.items()\n                    if not name.startswith('__')\n                }\n                # delete imported module\n                del sys.modules[temp_module_name]\n            elif filename.endswith(('.yml', '.yaml', '.json')):\n                cfg_dict = load(temp_config_file.name)\n            # close temp file\n            temp_config_file.close()\n\n        # check deprecation information\n        if DEPRECATION_KEY in cfg_dict:\n            deprecation_info = cfg_dict.pop(DEPRECATION_KEY)\n            warning_msg = f'The config file {filename} will be deprecated ' \\\n                'in the future.'\n            if 'expected' in deprecation_info:\n                warning_msg += f' Please use {deprecation_info[\"expected\"]} ' \\\n                    'instead.'\n            if 'reference' in deprecation_info:\n                warning_msg += ' More information can be found at ' \\\n                    f'{deprecation_info[\"reference\"]}'\n            warnings.warn(warning_msg)\n\n        cfg_text = filename + '\\n'\n        with open(filename, 'r', encoding='utf-8') as f:\n            # Setting encoding explicitly to resolve coding issue on windows\n            cfg_text += f.read()\n\n        if BASE_KEY in cfg_dict:\n            cfg_dir = osp.dirname(filename)\n            base_filename = cfg_dict.pop(BASE_KEY)\n            base_filename = base_filename if isinstance(\n                base_filename, list) else [base_filename]\n\n            cfg_dict_list = list()\n            cfg_text_list = list()\n            for f in base_filename:\n                _cfg_dict, _cfg_text = Config._file2dict(osp.join(cfg_dir, f))\n                cfg_dict_list.append(_cfg_dict)\n                cfg_text_list.append(_cfg_text)\n\n            base_cfg_dict = dict()\n            for c in cfg_dict_list:\n                duplicate_keys = base_cfg_dict.keys() & c.keys()\n                if len(duplicate_keys) > 0:\n                    raise KeyError('Duplicate key is not allowed among bases. '\n                                   f'Duplicate keys: {duplicate_keys}')\n                base_cfg_dict.update(c)\n\n            # Substitute base variables from strings to their actual values\n            cfg_dict = Config._substitute_base_vars(cfg_dict, base_var_dict,\n                                                    base_cfg_dict)\n\n            base_cfg_dict = Config._merge_a_into_b(cfg_dict, base_cfg_dict)\n            cfg_dict = base_cfg_dict\n\n            # merge cfg_text\n            cfg_text_list.append(cfg_text)\n            cfg_text = '\\n'.join(cfg_text_list)\n\n        return cfg_dict, cfg_text\n\n    @staticmethod\n    def _merge_a_into_b(a, b, allow_list_keys=False):\n        \"\"\"merge dict ``a`` into dict ``b`` (non-inplace).\n\n        Values in ``a`` will overwrite ``b``. ``b`` is copied first to avoid\n        in-place modifications.\n\n        Args:\n            a (dict): The source dict to be merged into ``b``.\n            b (dict): The origin dict to be fetch keys from ``a``.\n            allow_list_keys (bool): If True, int string keys (e.g. '0', '1')\n              are allowed in source ``a`` and will replace the element of the\n              corresponding index in b if b is a list. Default: False.\n\n        Returns:\n            dict: The modified dict of ``b`` using ``a``.\n\n        Examples:\n            # Normally merge a into b.\n            >>> Config._merge_a_into_b(\n            ...     dict(obj=dict(a=2)), dict(obj=dict(a=1)))\n            {'obj': {'a': 2}}\n\n            # Delete b first and merge a into b.\n            >>> Config._merge_a_into_b(\n            ...     dict(obj=dict(_delete_=True, a=2)), dict(obj=dict(a=1)))\n            {'obj': {'a': 2}}\n\n            # b is a list\n            >>> Config._merge_a_into_b(\n            ...     {'0': dict(a=2)}, [dict(a=1), dict(b=2)], True)\n            [{'a': 2}, {'b': 2}]\n        \"\"\"\n        b = b.copy()\n        for k, v in a.items():\n            if allow_list_keys and k.isdigit() and isinstance(b, list):\n                k = int(k)\n                if len(b) <= k:\n                    raise KeyError(f'Index {k} exceeds the length of list {b}')\n                b[k] = Config._merge_a_into_b(v, b[k], allow_list_keys)\n            elif isinstance(v,\n                            dict) and k in b and not v.pop(DELETE_KEY, False):\n                allowed_types = (dict, list) if allow_list_keys else dict\n                if not isinstance(b[k], allowed_types):\n                    raise TypeError(\n                        f'{k}={v} in child config cannot inherit from base '\n                        f'because {k} is a dict in the child config but is of '\n                        f'type {type(b[k])} in base config. You may set '\n                        f'`{DELETE_KEY}=True` to ignore the base config')\n                b[k] = Config._merge_a_into_b(v, b[k], allow_list_keys)\n            else:\n                b[k] = v\n        return b\n\n    @staticmethod\n    def fromfile(filename,\n                 use_predefined_variables=True,\n                 import_custom_modules=True):\n        cfg_dict, cfg_text = Config._file2dict(filename,\n                                               use_predefined_variables)\n        if import_custom_modules and cfg_dict.get('custom_imports', None):\n            import_modules_from_strings(**cfg_dict['custom_imports'])\n        return Config(cfg_dict, cfg_text=cfg_text, filename=filename)\n\n    @staticmethod\n    def fromstring(cfg_str, file_format):\n        \"\"\"Generate config from config str.\n\n        Args:\n            cfg_str (str): Config str.\n            file_format (str): Config file format corresponding to the\n               config str. Only py/yml/yaml/json type are supported now!\n\n        Returns:\n            obj:`Config`: Config obj.\n        \"\"\"\n        if file_format not in ['.py', '.json', '.yaml', '.yml']:\n            raise IOError('Only py/yml/yaml/json type are supported now!')\n        if file_format != '.py' and 'dict(' in cfg_str:\n            # check if users specify a wrong suffix for python\n            warnings.warn(\n                'Please check \"file_format\", the file format may be .py')\n        with tempfile.NamedTemporaryFile(\n                'w', encoding='utf-8', suffix=file_format,\n                delete=False) as temp_file:\n            temp_file.write(cfg_str)\n            # on windows, previous implementation cause error\n            # see PR 1077 for details\n        cfg = Config.fromfile(temp_file.name)\n        os.remove(temp_file.name)\n        return cfg\n\n    @staticmethod\n    def auto_argparser(description=None):\n        \"\"\"Generate argparser from config file automatically (experimental)\"\"\"\n        partial_parser = ArgumentParser(description=description)\n        partial_parser.add_argument('config', help='config file path')\n        cfg_file = partial_parser.parse_known_args()[0].config\n        cfg = Config.fromfile(cfg_file)\n        parser = ArgumentParser(description=description)\n        parser.add_argument('config', help='config file path')\n        add_args(parser, cfg)\n        return parser, cfg\n\n    def __init__(self, cfg_dict=None, cfg_text=None, filename=None):\n        if cfg_dict is None:\n            cfg_dict = dict()\n        elif not isinstance(cfg_dict, dict):\n            raise TypeError('cfg_dict must be a dict, but '\n                            f'got {type(cfg_dict)}')\n        for key in cfg_dict:\n            if key in RESERVED_KEYS:\n                raise KeyError(f'{key} is reserved for config file')\n\n        super(Config, self).__setattr__('_cfg_dict', ConfigDict(cfg_dict))\n        super(Config, self).__setattr__('_filename', filename)\n        if cfg_text:\n            text = cfg_text\n        elif filename:\n            with open(filename, 'r') as f:\n                text = f.read()\n        else:\n            text = ''\n        super(Config, self).__setattr__('_text', text)\n\n    @property\n    def filename(self):\n        return self._filename\n\n    @property\n    def text(self):\n        return self._text\n\n    @property\n    def pretty_text(self):\n\n        indent = 4\n\n        def _indent(s_, num_spaces):\n            s = s_.split('\\n')\n            if len(s) == 1:\n                return s_\n            first = s.pop(0)\n            s = [(num_spaces * ' ') + line for line in s]\n            s = '\\n'.join(s)\n            s = first + '\\n' + s\n            return s\n\n        def _format_basic_types(k, v, use_mapping=False):\n            if isinstance(v, str):\n                v_str = f\"'{v}'\"\n            else:\n                v_str = str(v)\n\n            if use_mapping:\n                k_str = f\"'{k}'\" if isinstance(k, str) else str(k)\n                attr_str = f'{k_str}: {v_str}'\n            else:\n                attr_str = f'{str(k)}={v_str}'\n            attr_str = _indent(attr_str, indent)\n\n            return attr_str\n\n        def _format_list(k, v, use_mapping=False):\n            # check if all items in the list are dict\n            if all(isinstance(_, dict) for _ in v):\n                v_str = '[\\n'\n                v_str += '\\n'.join(\n                    f'dict({_indent(_format_dict(v_), indent)}),'\n                    for v_ in v).rstrip(',')\n                if use_mapping:\n                    k_str = f\"'{k}'\" if isinstance(k, str) else str(k)\n                    attr_str = f'{k_str}: {v_str}'\n                else:\n                    attr_str = f'{str(k)}={v_str}'\n                attr_str = _indent(attr_str, indent) + ']'\n            else:\n                attr_str = _format_basic_types(k, v, use_mapping)\n            return attr_str\n\n        def _contain_invalid_identifier(dict_str):\n            contain_invalid_identifier = False\n            for key_name in dict_str:\n                contain_invalid_identifier |= \\\n                    (not str(key_name).isidentifier())\n            return contain_invalid_identifier\n\n        def _format_dict(input_dict, outest_level=False):\n            r = ''\n            s = []\n\n            use_mapping = _contain_invalid_identifier(input_dict)\n            if use_mapping:\n                r += '{'\n            for idx, (k, v) in enumerate(input_dict.items()):\n                is_last = idx >= len(input_dict) - 1\n                end = '' if outest_level or is_last else ','\n                if isinstance(v, dict):\n                    v_str = '\\n' + _format_dict(v)\n                    if use_mapping:\n                        k_str = f\"'{k}'\" if isinstance(k, str) else str(k)\n                        attr_str = f'{k_str}: dict({v_str}'\n                    else:\n                        attr_str = f'{str(k)}=dict({v_str}'\n                    attr_str = _indent(attr_str, indent) + ')' + end\n                elif isinstance(v, list):\n                    attr_str = _format_list(k, v, use_mapping) + end\n                else:\n                    attr_str = _format_basic_types(k, v, use_mapping) + end\n\n                s.append(attr_str)\n            r += '\\n'.join(s)\n            if use_mapping:\n                r += '}'\n            return r\n\n        cfg_dict = self._cfg_dict.to_dict()\n        text = _format_dict(cfg_dict, outest_level=True)\n        # copied from setup.cfg\n        yapf_style = dict(\n            based_on_style='pep8',\n            blank_line_before_nested_class_or_def=True,\n            split_before_expression_after_opening_paren=True)\n        text, _ = FormatCode(text, style_config=yapf_style, verify=True)\n\n        return text\n\n    def __repr__(self):\n        return f'Config (path: {self.filename}): {self._cfg_dict.__repr__()}'\n\n    def __len__(self):\n        return len(self._cfg_dict)\n\n    def __getattr__(self, name):\n        return getattr(self._cfg_dict, name)\n\n    def __getitem__(self, name):\n        return self._cfg_dict.__getitem__(name)\n\n    def __setattr__(self, name, value):\n        if isinstance(value, dict):\n            value = ConfigDict(value)\n        self._cfg_dict.__setattr__(name, value)\n\n    def __setitem__(self, name, value):\n        if isinstance(value, dict):\n            value = ConfigDict(value)\n        self._cfg_dict.__setitem__(name, value)\n\n    def __iter__(self):\n        return iter(self._cfg_dict)\n\n    def __getstate__(self):\n        return (self._cfg_dict, self._filename, self._text)\n\n    def __setstate__(self, state):\n        _cfg_dict, _filename, _text = state\n        super(Config, self).__setattr__('_cfg_dict', _cfg_dict)\n        super(Config, self).__setattr__('_filename', _filename)\n        super(Config, self).__setattr__('_text', _text)\n\n    def dump(self, file=None):\n        cfg_dict = super(Config, self).__getattribute__('_cfg_dict').to_dict()\n        if self.filename.endswith('.py'):\n            if file is None:\n                return self.pretty_text\n            else:\n                with open(file, 'w', encoding='utf-8') as f:\n                    f.write(self.pretty_text)\n        else:\n            if file is None:\n                file_format = self.filename.split('.')[-1]\n                return dump(cfg_dict, file_format=file_format)\n            else:\n                dump(cfg_dict, file)\n\n    def merge_from_dict(self, options, allow_list_keys=True):\n        \"\"\"Merge list into cfg_dict.\n\n        Merge the dict parsed by MultipleKVAction into this cfg.\n\n        Examples:\n            >>> options = {'model.backbone.depth': 50,\n            ...            'model.backbone.with_cp':True}\n            >>> cfg = Config(dict(model=dict(backbone=dict(type='ResNet'))))\n            >>> cfg.merge_from_dict(options)\n            >>> cfg_dict = super(Config, self).__getattribute__('_cfg_dict')\n            >>> assert cfg_dict == dict(\n            ...     model=dict(backbone=dict(depth=50, with_cp=True)))\n\n            # Merge list element\n            >>> cfg = Config(dict(pipeline=[\n            ...     dict(type='LoadImage'), dict(type='LoadAnnotations')]))\n            >>> options = dict(pipeline={'0': dict(type='SelfLoadImage')})\n            >>> cfg.merge_from_dict(options, allow_list_keys=True)\n            >>> cfg_dict = super(Config, self).__getattribute__('_cfg_dict')\n            >>> assert cfg_dict == dict(pipeline=[\n            ...     dict(type='SelfLoadImage'), dict(type='LoadAnnotations')])\n\n        Args:\n            options (dict): dict of configs to merge from.\n            allow_list_keys (bool): If True, int string keys (e.g. '0', '1')\n              are allowed in ``options`` and will replace the element of the\n              corresponding index in the config if the config is a list.\n              Default: True.\n        \"\"\"\n        option_cfg_dict = {}\n        for full_key, v in options.items():\n            d = option_cfg_dict\n            key_list = full_key.split('.')\n            for subkey in key_list[:-1]:\n                d.setdefault(subkey, ConfigDict())\n                d = d[subkey]\n            subkey = key_list[-1]\n            d[subkey] = v\n\n        cfg_dict = super(Config, self).__getattribute__('_cfg_dict')\n        super(Config, self).__setattr__(\n            '_cfg_dict',\n            Config._merge_a_into_b(\n                option_cfg_dict, cfg_dict, allow_list_keys=allow_list_keys))\n\n\nclass DictAction(Action):\n    \"\"\"\n    argparse action to split an argument into KEY=VALUE form\n    on the first = and append to a dictionary. List options can\n    be passed as comma separated values, i.e 'KEY=V1,V2,V3', or with explicit\n    brackets, i.e. 'KEY=[V1,V2,V3]'. It also support nested brackets to build\n    list/tuple values. e.g. 'KEY=[(V1,V2),(V3,V4)]'\n    \"\"\"\n\n    @staticmethod\n    def _parse_int_float_bool(val):\n        try:\n            return int(val)\n        except ValueError:\n            pass\n        try:\n            return float(val)\n        except ValueError:\n            pass\n        if val.lower() in ['true', 'false']:\n            return True if val.lower() == 'true' else False\n        return val\n\n    @staticmethod\n    def _parse_iterable(val):\n        \"\"\"Parse iterable values in the string.\n\n        All elements inside '()' or '[]' are treated as iterable values.\n\n        Args:\n            val (str): Value string.\n\n        Returns:\n            list | tuple: The expanded list or tuple from the string.\n\n        Examples:\n            >>> DictAction._parse_iterable('1,2,3')\n            [1, 2, 3]\n            >>> DictAction._parse_iterable('[a, b, c]')\n            ['a', 'b', 'c']\n            >>> DictAction._parse_iterable('[(1, 2, 3), [a, b], c]')\n            [(1, 2, 3), ['a', 'b'], 'c']\n        \"\"\"\n\n        def find_next_comma(string):\n            \"\"\"Find the position of next comma in the string.\n\n            If no ',' is found in the string, return the string length. All\n            chars inside '()' and '[]' are treated as one element and thus ','\n            inside these brackets are ignored.\n            \"\"\"\n            assert (string.count('(') == string.count(')')) and (\n                    string.count('[') == string.count(']')), \\\n                f'Imbalanced brackets exist in {string}'\n            end = len(string)\n            for idx, char in enumerate(string):\n                pre = string[:idx]\n                # The string before this ',' is balanced\n                if ((char == ',') and (pre.count('(') == pre.count(')'))\n                        and (pre.count('[') == pre.count(']'))):\n                    end = idx\n                    break\n            return end\n\n        # Strip ' and \" characters and replace whitespace.\n        val = val.strip('\\'\\\"').replace(' ', '')\n        is_tuple = False\n        if val.startswith('(') and val.endswith(')'):\n            is_tuple = True\n            val = val[1:-1]\n        elif val.startswith('[') and val.endswith(']'):\n            val = val[1:-1]\n        elif ',' not in val:\n            # val is a single value\n            return DictAction._parse_int_float_bool(val)\n\n        values = []\n        while len(val) > 0:\n            comma_idx = find_next_comma(val)\n            element = DictAction._parse_iterable(val[:comma_idx])\n            values.append(element)\n            val = val[comma_idx + 1:]\n        if is_tuple:\n            values = tuple(values)\n        return values\n\n    def __call__(self, parser, namespace, values, option_string=None):\n        options = {}\n        for kv in values:\n            key, val = kv.split('=', maxsplit=1)\n            options[key] = self._parse_iterable(val)\n        setattr(namespace, self.dest, options)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/contextmanagers.py",
    "content": "import asyncio\nimport contextlib\nimport logging\nimport os\nimport time\nfrom typing import List\n\nimport torch\n\nlogger = logging.getLogger(__name__)\n\nDEBUG_COMPLETED_TIME = bool(os.environ.get('DEBUG_COMPLETED_TIME', False))\n\n\n@contextlib.asynccontextmanager\nasync def completed(trace_name='',\n                    name='',\n                    sleep_interval=0.05,\n                    streams: List[torch.cuda.Stream] = None):\n    \"\"\"Async context manager that waits for work to complete on given CUDA\n    streams.\"\"\"\n    if not torch.cuda.is_available():\n        yield\n        return\n\n    stream_before_context_switch = torch.cuda.current_stream()\n    if not streams:\n        streams = [stream_before_context_switch]\n    else:\n        streams = [s if s else stream_before_context_switch for s in streams]\n\n    end_events = [\n        torch.cuda.Event(enable_timing=DEBUG_COMPLETED_TIME) for _ in streams\n    ]\n\n    if DEBUG_COMPLETED_TIME:\n        start = torch.cuda.Event(enable_timing=True)\n        stream_before_context_switch.record_event(start)\n\n        cpu_start = time.monotonic()\n    logger.debug('%s %s starting, streams: %s', trace_name, name, streams)\n    grad_enabled_before = torch.is_grad_enabled()\n    try:\n        yield\n    finally:\n        current_stream = torch.cuda.current_stream()\n        assert current_stream == stream_before_context_switch\n\n        if DEBUG_COMPLETED_TIME:\n            cpu_end = time.monotonic()\n        for i, stream in enumerate(streams):\n            event = end_events[i]\n            stream.record_event(event)\n\n        grad_enabled_after = torch.is_grad_enabled()\n\n        # observed change of torch.is_grad_enabled() during concurrent run of\n        # async_test_bboxes code\n        assert (grad_enabled_before == grad_enabled_after\n                ), 'Unexpected is_grad_enabled() value change'\n\n        are_done = [e.query() for e in end_events]\n        logger.debug('%s %s completed: %s streams: %s', trace_name, name,\n                     are_done, streams)\n        with torch.cuda.stream(stream_before_context_switch):\n            while not all(are_done):\n                await asyncio.sleep(sleep_interval)\n                are_done = [e.query() for e in end_events]\n                logger.debug(\n                    '%s %s completed: %s streams: %s',\n                    trace_name,\n                    name,\n                    are_done,\n                    streams,\n                )\n\n        current_stream = torch.cuda.current_stream()\n        assert current_stream == stream_before_context_switch\n\n        if DEBUG_COMPLETED_TIME:\n            cpu_time = (cpu_end - cpu_start) * 1000\n            stream_times_ms = ''\n            for i, stream in enumerate(streams):\n                elapsed_time = start.elapsed_time(end_events[i])\n                stream_times_ms += f' {stream} {elapsed_time:.2f} ms'\n            logger.info('%s %s %.2f ms %s', trace_name, name, cpu_time,\n                        stream_times_ms)\n\n\n@contextlib.asynccontextmanager\nasync def concurrent(streamqueue: asyncio.Queue,\n                     trace_name='concurrent',\n                     name='stream'):\n    \"\"\"Run code concurrently in different streams.\n\n    :param streamqueue: asyncio.Queue instance.\n\n    Queue tasks define the pool of streams used for concurrent execution.\n    \"\"\"\n    if not torch.cuda.is_available():\n        yield\n        return\n\n    initial_stream = torch.cuda.current_stream()\n\n    with torch.cuda.stream(initial_stream):\n        stream = await streamqueue.get()\n        assert isinstance(stream, torch.cuda.Stream)\n\n        try:\n            with torch.cuda.stream(stream):\n                logger.debug('%s %s is starting, stream: %s', trace_name, name,\n                             stream)\n                yield\n                current = torch.cuda.current_stream()\n                assert current == stream\n                logger.debug('%s %s has finished, stream: %s', trace_name,\n                             name, stream)\n        finally:\n            streamqueue.task_done()\n            streamqueue.put_nowait(stream)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/ext_loader.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport importlib\nimport os\nimport pkgutil\nimport warnings\nfrom collections import namedtuple\n\nimport torch\n\ndef load_ext(name, funcs):\n    ext = importlib.import_module('mmcv.' + name)\n    for fun in funcs:\n        assert hasattr(ext, fun), f'{fun} miss in module {name}'\n    return ext\n\ndef check_ops_exist():\n    ext_loader = pkgutil.find_loader('mmcv._ext')\n    return ext_loader is not None\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/fp16_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport functools\nimport warnings\nfrom collections import abc\nfrom inspect import getfullargspec\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nTORCH_VERSION = torch.__version__\nfrom .version_utils import digit_version\nfrom .runner_utils import allreduce_grads as _allreduce_grads\n\ntry:\n    # If PyTorch version >= 1.6.0, torch.cuda.amp.autocast would be imported\n    # and used; otherwise, auto fp16 will adopt mmcv's implementation.\n    # Note that when PyTorch >= 1.6.0, we still cast tensor types to fp16\n    # manually, so the behavior may not be consistent with real amp.\n    from torch.cuda.amp import autocast\nexcept ImportError:\n    pass\n\n\ndef cast_tensor_type(inputs, src_type, dst_type):\n    \"\"\"Recursively convert Tensor in inputs from src_type to dst_type.\n\n    Args:\n        inputs: Inputs that to be casted.\n        src_type (torch.dtype): Source type..\n        dst_type (torch.dtype): Destination type.\n\n    Returns:\n        The same type with inputs, but all contained Tensors have been cast.\n    \"\"\"\n    if isinstance(inputs, nn.Module):\n        return inputs\n    elif isinstance(inputs, torch.Tensor):\n        return inputs.to(dst_type)\n    elif isinstance(inputs, str):\n        return inputs\n    elif isinstance(inputs, np.ndarray):\n        return inputs\n    elif isinstance(inputs, abc.Mapping):\n        return type(inputs)({\n            k: cast_tensor_type(v, src_type, dst_type)\n            for k, v in inputs.items()\n        })\n    elif isinstance(inputs, abc.Iterable):\n        return type(inputs)(\n            cast_tensor_type(item, src_type, dst_type) for item in inputs)\n    else:\n        return inputs\n\n\ndef auto_fp16(apply_to=None, out_fp32=False):\n    \"\"\"Decorator to enable fp16 training automatically.\n\n    This decorator is useful when you write custom modules and want to support\n    mixed precision training. If inputs arguments are fp32 tensors, they will\n    be converted to fp16 automatically. Arguments other than fp32 tensors are\n    ignored. If you are using PyTorch >= 1.6, torch.cuda.amp is used as the\n    backend, otherwise, original mmcv implementation will be adopted.\n\n    Args:\n        apply_to (Iterable, optional): The argument names to be converted.\n            `None` indicates all arguments.\n        out_fp32 (bool): Whether to convert the output back to fp32.\n\n    Example:\n\n        >>> import torch.nn as nn\n        >>> class MyModule1(nn.Module):\n        >>>\n        >>>     # Convert x and y to fp16\n        >>>     @auto_fp16()\n        >>>     def forward(self, x, y):\n        >>>         pass\n\n        >>> import torch.nn as nn\n        >>> class MyModule2(nn.Module):\n        >>>\n        >>>     # convert pred to fp16\n        >>>     @auto_fp16(apply_to=('pred', ))\n        >>>     def do_something(self, pred, others):\n        >>>         pass\n    \"\"\"\n\n    def auto_fp16_wrapper(old_func):\n\n        @functools.wraps(old_func)\n        def new_func(*args, **kwargs):\n            # check if the module has set the attribute `fp16_enabled`, if not,\n            # just fallback to the original method.\n            if not isinstance(args[0], torch.nn.Module):\n                raise TypeError('@auto_fp16 can only be used to decorate the '\n                                'method of nn.Module')\n            if not (hasattr(args[0], 'fp16_enabled') and args[0].fp16_enabled):\n                return old_func(*args, **kwargs)\n\n            # get the arg spec of the decorated method\n            args_info = getfullargspec(old_func)\n            # get the argument names to be casted\n            args_to_cast = args_info.args if apply_to is None else apply_to\n            # convert the args that need to be processed\n            new_args = []\n            # NOTE: default args are not taken into consideration\n            if args:\n                arg_names = args_info.args[:len(args)]\n                for i, arg_name in enumerate(arg_names):\n                    if arg_name in args_to_cast:\n                        new_args.append(\n                            cast_tensor_type(args[i], torch.float, torch.half))\n                    else:\n                        new_args.append(args[i])\n            # convert the kwargs that need to be processed\n            new_kwargs = {}\n            if kwargs:\n                for arg_name, arg_value in kwargs.items():\n                    if arg_name in args_to_cast:\n                        new_kwargs[arg_name] = cast_tensor_type(\n                            arg_value, torch.float, torch.half)\n                    else:\n                        new_kwargs[arg_name] = arg_value\n            # apply converted arguments to the decorated method\n            if (digit_version(TORCH_VERSION) >= digit_version('1.6.0')):\n                with autocast(enabled=True):\n                    output = old_func(*new_args, **new_kwargs)\n            else:\n                output = old_func(*new_args, **new_kwargs)\n            # cast the results back to fp32 if necessary\n            if out_fp32:\n                output = cast_tensor_type(output, torch.half, torch.float)\n            return output\n\n        return new_func\n\n    return auto_fp16_wrapper\n\n\ndef force_fp32(apply_to=None, out_fp16=False):\n    \"\"\"Decorator to convert input arguments to fp32 in force.\n\n    This decorator is useful when you write custom modules and want to support\n    mixed precision training. If there are some inputs that must be processed\n    in fp32 mode, then this decorator can handle it. If inputs arguments are\n    fp16 tensors, they will be converted to fp32 automatically. Arguments other\n    than fp16 tensors are ignored. If you are using PyTorch >= 1.6,\n    torch.cuda.amp is used as the backend, otherwise, original mmcv\n    implementation will be adopted.\n\n    Args:\n        apply_to (Iterable, optional): The argument names to be converted.\n            `None` indicates all arguments.\n        out_fp16 (bool): Whether to convert the output back to fp16.\n\n    Example:\n\n        >>> import torch.nn as nn\n        >>> class MyModule1(nn.Module):\n        >>>\n        >>>     # Convert x and y to fp32\n        >>>     @force_fp32()\n        >>>     def loss(self, x, y):\n        >>>         pass\n\n        >>> import torch.nn as nn\n        >>> class MyModule2(nn.Module):\n        >>>\n        >>>     # convert pred to fp32\n        >>>     @force_fp32(apply_to=('pred', ))\n        >>>     def post_process(self, pred, others):\n        >>>         pass\n    \"\"\"\n\n    def force_fp32_wrapper(old_func):\n\n        @functools.wraps(old_func)\n        def new_func(*args, **kwargs):\n            # check if the module has set the attribute `fp16_enabled`, if not,\n            # just fallback to the original method.\n            if not isinstance(args[0], torch.nn.Module):\n                raise TypeError('@force_fp32 can only be used to decorate the '\n                                'method of nn.Module')\n            if not (hasattr(args[0], 'fp16_enabled') and args[0].fp16_enabled):\n                return old_func(*args, **kwargs)\n            # get the arg spec of the decorated method\n            args_info = getfullargspec(old_func)\n            # get the argument names to be casted\n            args_to_cast = args_info.args if apply_to is None else apply_to\n            # convert the args that need to be processed\n            new_args = []\n            if args:\n                arg_names = args_info.args[:len(args)]\n                for i, arg_name in enumerate(arg_names):\n                    if arg_name in args_to_cast:\n                        new_args.append(\n                            cast_tensor_type(args[i], torch.half, torch.float))\n                    else:\n                        new_args.append(args[i])\n            # convert the kwargs that need to be processed\n            new_kwargs = dict()\n            if kwargs:\n                for arg_name, arg_value in kwargs.items():\n                    if arg_name in args_to_cast:\n                        new_kwargs[arg_name] = cast_tensor_type(\n                            arg_value, torch.half, torch.float)\n                    else:\n                        new_kwargs[arg_name] = arg_value\n            # apply converted arguments to the decorated method\n            if (digit_version(TORCH_VERSION) >= digit_version('1.6.0')):\n                with autocast(enabled=False):\n                    output = old_func(*new_args, **new_kwargs)\n            else:\n                output = old_func(*new_args, **new_kwargs)\n            # cast the results back to fp32 if necessary\n            if out_fp16:\n                output = cast_tensor_type(output, torch.float, torch.half)\n            return output\n\n        return new_func\n\n    return force_fp32_wrapper\n\n\ndef allreduce_grads(params, coalesce=True, bucket_size_mb=-1):\n    warnings.warning(\n        '\"mmcv.runner.fp16_utils.allreduce_grads\" is deprecated, and will be '\n        'removed in v2.8. Please switch to \"mmcv.runner.allreduce_grads')\n    _allreduce_grads(params, coalesce=coalesce, bucket_size_mb=bucket_size_mb)\n\n\ndef wrap_fp16_model(model):\n    \"\"\"Wrap the FP32 model to FP16.\n\n    If you are using PyTorch >= 1.6, torch.cuda.amp is used as the\n    backend, otherwise, original mmcv implementation will be adopted.\n\n    For PyTorch >= 1.6, this function will\n    1. Set fp16 flag inside the model to True.\n\n    Otherwise:\n    1. Convert FP32 model to FP16.\n    2. Remain some necessary layers to be FP32, e.g., normalization layers.\n    3. Set `fp16_enabled` flag inside the model to True.\n\n    Args:\n        model (nn.Module): Model in FP32.\n    \"\"\"\n    if (digit_version(TORCH_VERSION) < digit_version('1.6.0')):\n        # convert model to fp16\n        model.half()\n        # patch the normalization layers to make it work in fp32 mode\n        patch_norm_fp32(model)\n    # set `fp16_enabled` flag\n    for m in model.modules():\n        if hasattr(m, 'fp16_enabled'):\n            m.fp16_enabled = True\n\n\ndef patch_norm_fp32(module):\n    \"\"\"Recursively convert normalization layers from FP16 to FP32.\n\n    Args:\n        module (nn.Module): The modules to be converted in FP16.\n\n    Returns:\n        nn.Module: The converted module, the normalization layers have been\n            converted to FP32.\n    \"\"\"\n    if isinstance(module, (nn.modules.batchnorm._BatchNorm, nn.GroupNorm)):\n        module.float()\n        if isinstance(module, nn.GroupNorm) or torch.__version__ < '1.3':\n            module.forward = patch_forward_method(module.forward, torch.half,\n                                                  torch.float)\n    for child in module.children():\n        patch_norm_fp32(child)\n    return module\n\n\ndef patch_forward_method(func, src_type, dst_type, convert_output=True):\n    \"\"\"Patch the forward method of a module.\n\n    Args:\n        func (callable): The original forward method.\n        src_type (torch.dtype): Type of input arguments to be converted from.\n        dst_type (torch.dtype): Type of input arguments to be converted to.\n        convert_output (bool): Whether to convert the output back to src_type.\n\n    Returns:\n        callable: The patched forward method.\n    \"\"\"\n\n    def new_forward(*args, **kwargs):\n        output = func(*cast_tensor_type(args, src_type, dst_type),\n                      **cast_tensor_type(kwargs, src_type, dst_type))\n        if convert_output:\n            output = cast_tensor_type(output, dst_type, src_type)\n        return output\n\n    return new_forward\n\n\nclass LossScaler:\n    \"\"\"Class that manages loss scaling in mixed precision training which\n    supports both dynamic or static mode.\n\n    The implementation refers to\n    https://github.com/NVIDIA/apex/blob/master/apex/fp16_utils/loss_scaler.py.\n    Indirectly, by supplying ``mode='dynamic'`` for dynamic loss scaling.\n    It's important to understand how :class:`LossScaler` operates.\n    Loss scaling is designed to combat the problem of underflowing\n    gradients encountered at long times when training fp16 networks.\n    Dynamic loss scaling begins by attempting a very high loss\n    scale.  Ironically, this may result in OVERflowing gradients.\n    If overflowing gradients are encountered, :class:`FP16_Optimizer` then\n    skips the update step for this particular iteration/minibatch,\n    and :class:`LossScaler` adjusts the loss scale to a lower value.\n    If a certain number of iterations occur without overflowing gradients\n    detected,:class:`LossScaler` increases the loss scale once more.\n    In this way :class:`LossScaler` attempts to \"ride the edge\" of always\n    using the highest loss scale possible without incurring overflow.\n\n    Args:\n        init_scale (float): Initial loss scale value, default: 2**32.\n        scale_factor (float): Factor used when adjusting the loss scale.\n            Default: 2.\n        mode (str): Loss scaling mode. 'dynamic' or 'static'\n        scale_window (int): Number of consecutive iterations without an\n            overflow to wait before increasing the loss scale. Default: 1000.\n    \"\"\"\n\n    def __init__(self,\n                 init_scale=2**32,\n                 mode='dynamic',\n                 scale_factor=2.,\n                 scale_window=1000):\n        self.cur_scale = init_scale\n        self.cur_iter = 0\n        assert mode in ('dynamic',\n                        'static'), 'mode can only be dynamic or static'\n        self.mode = mode\n        self.last_overflow_iter = -1\n        self.scale_factor = scale_factor\n        self.scale_window = scale_window\n\n    def has_overflow(self, params):\n        \"\"\"Check if params contain overflow.\"\"\"\n        if self.mode != 'dynamic':\n            return False\n        for p in params:\n            if p.grad is not None and LossScaler._has_inf_or_nan(p.grad.data):\n                return True\n        return False\n\n    def _has_inf_or_nan(x):\n        \"\"\"Check if params contain NaN.\"\"\"\n        try:\n            cpu_sum = float(x.float().sum())\n        except RuntimeError as instance:\n            if 'value cannot be converted' not in instance.args[0]:\n                raise\n            return True\n        else:\n            if cpu_sum == float('inf') or cpu_sum == -float('inf') \\\n                    or cpu_sum != cpu_sum:\n                return True\n            return False\n\n    def update_scale(self, overflow):\n        \"\"\"update the current loss scale value when overflow happens.\"\"\"\n        if self.mode != 'dynamic':\n            return\n        if overflow:\n            self.cur_scale = max(self.cur_scale / self.scale_factor, 1)\n            self.last_overflow_iter = self.cur_iter\n        else:\n            if (self.cur_iter - self.last_overflow_iter) % \\\n                    self.scale_window == 0:\n                self.cur_scale *= self.scale_factor\n        self.cur_iter += 1\n\n    def state_dict(self):\n        \"\"\"Returns the state of the scaler as a :class:`dict`.\"\"\"\n        return dict(\n            cur_scale=self.cur_scale,\n            cur_iter=self.cur_iter,\n            mode=self.mode,\n            last_overflow_iter=self.last_overflow_iter,\n            scale_factor=self.scale_factor,\n            scale_window=self.scale_window)\n\n    def load_state_dict(self, state_dict):\n        \"\"\"Loads the loss_scaler state dict.\n\n        Args:\n           state_dict (dict): scaler state.\n        \"\"\"\n        self.cur_scale = state_dict['cur_scale']\n        self.cur_iter = state_dict['cur_iter']\n        self.mode = state_dict['mode']\n        self.last_overflow_iter = state_dict['last_overflow_iter']\n        self.scale_factor = state_dict['scale_factor']\n        self.scale_window = state_dict['scale_window']\n\n    @property\n    def loss_scale(self):\n        return self.cur_scale\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/grid_mask.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\nfrom PIL import Image\nfrom mmcv.runner import force_fp32, auto_fp16\n\nclass Grid(object):\n    def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5, mode=0, prob = 1.):\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode=mode\n        self.st_prob = prob\n        self.prob = prob\n\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch\n\n    def __call__(self, img, label):\n        if np.random.rand() > self.prob:\n            return img, label\n        h = img.size(1)\n        w = img.size(2)\n        self.d1 = 2\n        self.d2 = min(h, w)\n        hh = int(1.5*h)\n        ww = int(1.5*w)\n        d = np.random.randint(self.d1, self.d2)\n        if self.ratio == 1:\n            self.l = np.random.randint(1, d)\n        else:\n            self.l = min(max(int(d*self.ratio+0.5),1),d-1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh//d):\n                s = d*i + st_h\n                t = min(s+self.l, hh)\n                mask[s:t,:] *= 0\n        if self.use_w:\n            for i in range(ww//d):\n                s = d*i + st_w\n                t = min(s+self.l, ww)\n                mask[:,s:t] *= 0\n       \n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[(hh-h)//2:(hh-h)//2+h, (ww-w)//2:(ww-w)//2+w]\n\n        mask = torch.from_numpy(mask).float()\n        if self.mode == 1:\n            mask = 1-mask\n\n        mask = mask.expand_as(img)\n        if self.offset:\n            offset = torch.from_numpy(2 * (np.random.rand(h,w) - 0.5)).float()\n            offset = (1 - mask) * offset\n            img = img * mask + offset\n        else:\n            img = img * mask \n\n        return img, label\n\n\nclass GridMask(nn.Module):\n    def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5, mode=0, prob = 1.):\n        super(GridMask, self).__init__()\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode = mode\n        self.st_prob = prob\n        self.prob = prob\n        self.fp16_enable = False\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch #+ 1.#0.5\n    @auto_fp16()\n    def forward(self, x):\n        if np.random.rand() > self.prob or not self.training:\n            return x\n        n,c,h,w = x.size()\n        x = x.view(-1,h,w)\n        hh = int(1.5*h)\n        ww = int(1.5*w)\n        d = np.random.randint(2, h)\n        self.l = min(max(int(d*self.ratio+0.5),1),d-1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh//d):\n                s = d*i + st_h\n                t = min(s+self.l, hh)\n                mask[s:t,:] *= 0\n        if self.use_w:\n            for i in range(ww//d):\n                s = d*i + st_w\n                t = min(s+self.l, ww)\n                mask[:,s:t] *= 0\n       \n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[(hh-h)//2:(hh-h)//2+h, (ww-w)//2:(ww-w)//2+w]\n\n        mask = torch.from_numpy(mask).to(x.dtype).cuda()\n        if self.mode == 1:\n            mask = 1-mask\n        mask = mask.expand_as(x)\n        if self.offset:\n            offset = torch.from_numpy(2 * (np.random.rand(h,w) - 0.5)).to(x.dtype).cuda()\n            x = x * mask + offset * (1 - mask)\n        else:\n            x = x * mask \n        \n        return x.view(n,c,h,w)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/hub.py",
    "content": "# The 1.6 release of PyTorch switched torch.save to use a new zipfile-based\n# file format. It will cause RuntimeError when a checkpoint was saved in\n# torch >= 1.6.0 but loaded in torch < 1.7.0.\n# More details at https://github.com/open-mmlab/mmpose/issues/904\nfrom .path import mkdir_or_exist\nfrom .version_utils import digit_version\nimport torch\n\nTORCH_VERSION = torch.__version__\n\nif digit_version(TORCH_VERSION) < digit_version('1.7.0'):\n    # Modified from https://github.com/pytorch/pytorch/blob/master/torch/hub.py\n    import os\n    import torch\n    import warnings\n    from urllib.parse import urlparse\n    import sys\n    import zipfile\n    from torch.hub import download_url_to_file, _get_torch_home, HASH_REGEX\n\n    # Hub used to support automatically extracts from zipfile manually\n    # compressed by users. The legacy zip format expects only one file from\n    # torch.save() < 1.6 in the zip. We should remove this support since\n    # zipfile is now default zipfile format for torch.save().\n    def _is_legacy_zip_format(filename):\n        if zipfile.is_zipfile(filename):\n            infolist = zipfile.ZipFile(filename).infolist()\n            return len(infolist) == 1 and not infolist[0].is_dir()\n        return False\n\n    def _legacy_zip_load(filename, model_dir, map_location):\n        warnings.warn('Falling back to the old format < 1.6. This support will'\n                      ' be deprecated in favor of default zipfile format '\n                      'introduced in 1.6. Please redo torch.save() to save it '\n                      'in the new zipfile format.')\n        # Note: extractall() defaults to overwrite file if exists. No need to\n        #       clean up beforehand. We deliberately don't handle tarfile here\n        #       since our legacy serialization format was in tar.\n        #       E.g. resnet18-5c106cde.pth which is widely used.\n        with zipfile.ZipFile(filename) as f:\n            members = f.infolist()\n            if len(members) != 1:\n                raise RuntimeError(\n                    'Only one file(not dir) is allowed in the zipfile')\n            f.extractall(model_dir)\n            extraced_name = members[0].filename\n            extracted_file = os.path.join(model_dir, extraced_name)\n        return torch.load(extracted_file, map_location=map_location)\n\n    def load_url(url,\n                 model_dir=None,\n                 map_location=None,\n                 progress=True,\n                 check_hash=False,\n                 file_name=None):\n        r\"\"\"Loads the Torch serialized object at the given URL.\n\n        If downloaded file is a zip file, it will be automatically decompressed\n\n        If the object is already present in `model_dir`, it's deserialized and\n        returned.\n        The default value of ``model_dir`` is ``<hub_dir>/checkpoints`` where\n        ``hub_dir`` is the directory returned by :func:`~torch.hub.get_dir`.\n\n        Args:\n            url (str): URL of the object to download\n            model_dir (str, optional): directory in which to save the object\n            map_location (optional): a function or a dict specifying how to\n                remap storage locations (see torch.load)\n            progress (bool, optional): whether or not to display a progress bar\n                to stderr. Default: True\n            check_hash(bool, optional): If True, the filename part of the URL\n                should follow the naming convention ``filename-<sha256>.ext``\n                where ``<sha256>`` is the first eight or more digits of the\n                SHA256 hash of the contents of the file. The hash is used to\n                ensure unique names and to verify the contents of the file.\n                Default: False\n            file_name (str, optional): name for the downloaded file. Filename\n                from ``url`` will be used if not set. Default: None.\n\n        Example:\n            >>> url = ('https://s3.amazonaws.com/pytorch/models/resnet18-5c106'\n            ...        'cde.pth')\n            >>> state_dict = torch.hub.load_state_dict_from_url(url)\n        \"\"\"\n        # Issue warning to move data if old env is set\n        if os.getenv('TORCH_MODEL_ZOO'):\n            warnings.warn('TORCH_MODEL_ZOO is deprecated, please use env '\n                          'TORCH_HOME instead')\n\n        if model_dir is None:\n            torch_home = _get_torch_home()\n            model_dir = os.path.join(torch_home, 'checkpoints')\n\n        mkdir_or_exist(model_dir)\n\n        parts = urlparse(url)\n        filename = os.path.basename(parts.path)\n        if file_name is not None:\n            filename = file_name\n        cached_file = os.path.join(model_dir, filename)\n        if not os.path.exists(cached_file):\n            sys.stderr.write('Downloading: \"{}\" to {}\\n'.format(\n                url, cached_file))\n            hash_prefix = None\n            if check_hash:\n                r = HASH_REGEX.search(filename)  # r is Optional[Match[str]]\n                hash_prefix = r.group(1) if r else None\n            download_url_to_file(\n                url, cached_file, hash_prefix, progress=progress)\n\n        if _is_legacy_zip_format(cached_file):\n            return _legacy_zip_load(cached_file, model_dir, map_location)\n\n        try:\n            return torch.load(cached_file, map_location=map_location)\n        except RuntimeError as error:\n            if digit_version(TORCH_VERSION) < digit_version('1.5.0'):\n                warnings.warn(\n                    f'If the error is the same as \"{cached_file} is a zip '\n                    'archive (did you mean to use torch.jit.load()?)\", you can'\n                    ' upgrade your torch to 1.5.0 or higher (current torch '\n                    f'version is {TORCH_VERSION}). The error was raised '\n                    ' because the checkpoint was saved in torch>=1.6.0 but '\n                    'loaded in torch<1.5.')\n            raise error\nelse:\n    from torch.utils.model_zoo import load_url  # noqa: F401\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/log_buffer.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom collections import OrderedDict\n\nimport numpy as np\n\n\nclass LogBuffer:\n\n    def __init__(self):\n        self.val_history = OrderedDict()\n        self.n_history = OrderedDict()\n        self.output = OrderedDict()\n        self.ready = False\n\n    def clear(self):\n        self.val_history.clear()\n        self.n_history.clear()\n        self.clear_output()\n\n    def clear_output(self):\n        self.output.clear()\n        self.ready = False\n\n    def update(self, vars, count=1):\n        assert isinstance(vars, dict)\n        for key, var in vars.items():\n            if key not in self.val_history:\n                self.val_history[key] = []\n                self.n_history[key] = []\n            self.val_history[key].append(var)\n            self.n_history[key].append(count)\n\n    def average(self, n=0):\n        \"\"\"Average latest n values or all values.\"\"\"\n        assert n >= 0\n        for key in self.val_history:\n            values = np.array(self.val_history[key][-n:])\n            nums = np.array(self.n_history[key][-n:])\n            avg = np.sum(values * nums) / np.sum(nums)\n            self.output[key] = avg\n        self.ready = True\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/logger.py",
    "content": "import logging\nfrom .logging import get_logger\nfrom mmcv import __version__\n\ndef get_root_logger(log_file=None, log_level=logging.INFO, name = __version__):\n    \"\"\"Get root logger.\n\n    Args:\n        log_file (str, optional): File path of log. Defaults to None.\n        log_level (int, optional): The level of logger.\n            Defaults to logging.INFO.\n\n    Returns:\n        :obj:`logging.Logger`: The obtained logger\n    \"\"\"\n    logger = get_logger(name=name, log_file=log_file, log_level=log_level)\n    \n    logging_filter = logging.Filter(name)\n    logging_filter.filter = lambda record: record.find(name) != -1\n\n    return logger\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/logging.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport logging\n\nimport torch.distributed as dist\n\nlogger_initialized = {}\n\n\ndef get_logger(name, log_file=None, log_level=logging.INFO, file_mode='w'):\n    \"\"\"Initialize and get a logger by name.\n\n    If the logger has not been initialized, this method will initialize the\n    logger by adding one or two handlers, otherwise the initialized logger will\n    be directly returned. During initialization, a StreamHandler will always be\n    added. If `log_file` is specified and the process rank is 0, a FileHandler\n    will also be added.\n\n    Args:\n        name (str): Logger name.\n        log_file (str | None): The log filename. If specified, a FileHandler\n            will be added to the logger.\n        log_level (int): The logger level. Note that only the process of\n            rank 0 is affected, and other processes will set the level to\n            \"Error\" thus be silent most of the time.\n        file_mode (str): The file mode used in opening log file.\n            Defaults to 'w'.\n\n    Returns:\n        logging.Logger: The expected logger.\n    \"\"\"\n    logger = logging.getLogger(name)\n    if name in logger_initialized:\n        return logger\n    # handle hierarchical names\n    # e.g., logger \"a\" is initialized, then logger \"a.b\" will skip the\n    # initialization since it is a child of \"a\".\n    for logger_name in logger_initialized:\n        if name.startswith(logger_name):\n            return logger\n\n    # handle duplicate logs to the console\n    # Starting in 1.8.0, PyTorch DDP attaches a StreamHandler <stderr> (NOTSET)\n    # to the root logger. As logger.propagate is True by default, this root\n    # level handler causes logging messages from rank>0 processes to\n    # unexpectedly show up on the console, creating much unwanted clutter.\n    # To fix this issue, we set the root logger's StreamHandler, if any, to log\n    # at the ERROR level.\n    for handler in logger.root.handlers:\n        if type(handler) is logging.StreamHandler:\n            handler.setLevel(logging.ERROR)\n\n    stream_handler = logging.StreamHandler()\n    handlers = [stream_handler]\n\n    if dist.is_available() and dist.is_initialized():\n        rank = dist.get_rank()\n    else:\n        rank = 0\n\n    # only rank 0 will add a FileHandler\n    if rank == 0 and log_file is not None:\n        # Here, the default behaviour of the official logger is 'a'. Thus, we\n        # provide an interface to change the file mode to the default\n        # behaviour.\n        file_handler = logging.FileHandler(log_file, file_mode)\n        handlers.append(file_handler)\n\n    formatter = logging.Formatter(\n        '%(asctime)s - %(name)s - %(levelname)s - %(message)s')\n    for handler in handlers:\n        handler.setFormatter(formatter)\n        handler.setLevel(log_level)\n        logger.addHandler(handler)\n\n    if rank == 0:\n        logger.setLevel(log_level)\n    else:\n        logger.setLevel(logging.ERROR)\n\n    logger_initialized[name] = True\n\n    return logger\n\n\ndef print_log(msg, logger=None, level=logging.INFO):\n    \"\"\"Print a log message.\n\n    Args:\n        msg (str): The message to be logged.\n        logger (logging.Logger | str | None): The logger to be used.\n            Some special loggers are:\n            - \"silent\": no message will be printed.\n            - other str: the logger obtained with `get_root_logger(logger)`.\n            - None: The `print()` method will be used to print log messages.\n        level (int): Logging level. Only available when `logger` is a Logger\n            object or \"root\".\n    \"\"\"\n    if logger is None:\n        print(msg)\n    elif isinstance(logger, logging.Logger):\n        logger.log(level, msg)\n    elif logger == 'silent':\n        pass\n    elif isinstance(logger, str):\n        _logger = get_logger(logger)\n        _logger.log(level, msg)\n    else:\n        raise TypeError(\n            'logger should be either a logging.Logger object, str, '\n            f'\"silent\" or None, but got {type(logger)}')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/memory.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nfrom contextlib import contextmanager\nfrom functools import wraps\nimport torch\n\n__all__ = [\"retry_if_cuda_oom\"]\n\n\n@contextmanager\ndef _ignore_torch_cuda_oom():\n    \"\"\"\n    A context which ignores CUDA OOM exception from pytorch.\n    \"\"\"\n    try:\n        yield\n    except RuntimeError as e:\n        # NOTE: the string may change?\n        if \"CUDA out of memory. \" in str(e):\n            pass\n        else:\n            raise\n\n\ndef retry_if_cuda_oom(func):\n    \"\"\"\n    Makes a function retry itself after encountering\n    pytorch's CUDA OOM error.\n    It will first retry after calling `torch.cuda.empty_cache()`.\n\n    If that still fails, it will then retry by trying to convert inputs to CPUs.\n    In this case, it expects the function to dispatch to CPU implementation.\n    The return values may become CPU tensors as well and it's user's\n    responsibility to convert it back to CUDA tensor if needed.\n\n    Args:\n        func: a stateless callable that takes tensor-like objects as arguments\n\n    Returns:\n        a callable which retries `func` if OOM is encountered.\n\n    Examples:\n    ::\n        output = retry_if_cuda_oom(some_torch_function)(input1, input2)\n        # output may be on CPU even if inputs are on GPU\n\n    Note:\n        1. When converting inputs to CPU, it will only look at each argument and check\n           if it has `.device` and `.to` for conversion. Nested structures of tensors\n           are not supported.\n\n        2. Since the function might be called more than once, it has to be\n           stateless.\n    \"\"\"\n\n    def maybe_to_cpu(x):\n        try:\n            like_gpu_tensor = x.device.type == \"cuda\" and hasattr(x, \"to\")\n        except AttributeError:\n            like_gpu_tensor = False\n        if like_gpu_tensor:\n            return x.to(device=\"cpu\")\n        else:\n            return x\n\n    @wraps(func)\n    def wrapped(*args, **kwargs):\n        with _ignore_torch_cuda_oom():\n            return func(*args, **kwargs)\n\n        # Clear cache and retry\n        torch.cuda.empty_cache()\n        with _ignore_torch_cuda_oom():\n            return func(*args, **kwargs)\n\n        # Try on CPU. This slows down the code significantly, therefore print a notice.\n        logger = logging.getLogger(__name__)\n        logger.info(\"Attempting to copy inputs of {} to CPU due to CUDA OOM\".format(str(func)))\n        new_args = (maybe_to_cpu(x) for x in args)\n        new_kwargs = {k: maybe_to_cpu(v) for k, v in kwargs.items()}\n        return func(*new_args, **new_kwargs)\n\n    return wrapped"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/misc.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport collections.abc\nimport functools\nimport itertools\nimport subprocess\nimport warnings\nfrom collections import abc\nfrom importlib import import_module\nfrom inspect import getfullargspec\nfrom itertools import repeat\n\n\n# From PyTorch internals\ndef _ntuple(n):\n\n    def parse(x):\n        if isinstance(x, collections.abc.Iterable):\n            return x\n        return tuple(repeat(x, n))\n\n    return parse\n\n\nto_1tuple = _ntuple(1)\nto_2tuple = _ntuple(2)\nto_3tuple = _ntuple(3)\nto_4tuple = _ntuple(4)\nto_ntuple = _ntuple\n\n\ndef is_str(x):\n    \"\"\"Whether the input is an string instance.\n\n    Note: This method is deprecated since python 2 is no longer supported.\n    \"\"\"\n    return isinstance(x, str)\n\n\ndef import_modules_from_strings(imports, allow_failed_imports=False):\n    \"\"\"Import modules from the given list of strings.\n\n    Args:\n        imports (list | str | None): The given module names to be imported.\n        allow_failed_imports (bool): If True, the failed imports will return\n            None. Otherwise, an ImportError is raise. Default: False.\n\n    Returns:\n        list[module] | module | None: The imported modules.\n\n    Examples:\n        >>> osp, sys = import_modules_from_strings(\n        ...     ['os.path', 'sys'])\n        >>> import os.path as osp_\n        >>> import sys as sys_\n        >>> assert osp == osp_\n        >>> assert sys == sys_\n    \"\"\"\n    if not imports:\n        return\n    single_import = False\n    if isinstance(imports, str):\n        single_import = True\n        imports = [imports]\n    if not isinstance(imports, list):\n        raise TypeError(\n            f'custom_imports must be a list but got type {type(imports)}')\n    imported = []\n    for imp in imports:\n        if not isinstance(imp, str):\n            raise TypeError(\n                f'{imp} is of type {type(imp)} and cannot be imported.')\n        try:\n            imported_tmp = import_module(imp)\n        except ImportError:\n            if allow_failed_imports:\n                warnings.warn(f'{imp} failed to import and is ignored.',\n                              UserWarning)\n                imported_tmp = None\n            else:\n                raise ImportError\n        imported.append(imported_tmp)\n    if single_import:\n        imported = imported[0]\n    return imported\n\n\ndef iter_cast(inputs, dst_type, return_type=None):\n    \"\"\"Cast elements of an iterable object into some type.\n\n    Args:\n        inputs (Iterable): The input object.\n        dst_type (type): Destination type.\n        return_type (type, optional): If specified, the output object will be\n            converted to this type, otherwise an iterator.\n\n    Returns:\n        iterator or specified type: The converted object.\n    \"\"\"\n    if not isinstance(inputs, abc.Iterable):\n        raise TypeError('inputs must be an iterable object')\n    if not isinstance(dst_type, type):\n        raise TypeError('\"dst_type\" must be a valid type')\n\n    out_iterable = map(dst_type, inputs)\n\n    if return_type is None:\n        return out_iterable\n    else:\n        return return_type(out_iterable)\n\n\ndef list_cast(inputs, dst_type):\n    \"\"\"Cast elements of an iterable object into a list of some type.\n\n    A partial method of :func:`iter_cast`.\n    \"\"\"\n    return iter_cast(inputs, dst_type, return_type=list)\n\n\ndef tuple_cast(inputs, dst_type):\n    \"\"\"Cast elements of an iterable object into a tuple of some type.\n\n    A partial method of :func:`iter_cast`.\n    \"\"\"\n    return iter_cast(inputs, dst_type, return_type=tuple)\n\n\ndef is_seq_of(seq, expected_type, seq_type=None):\n    \"\"\"Check whether it is a sequence of some type.\n\n    Args:\n        seq (Sequence): The sequence to be checked.\n        expected_type (type): Expected type of sequence items.\n        seq_type (type, optional): Expected sequence type.\n\n    Returns:\n        bool: Whether the sequence is valid.\n    \"\"\"\n    if seq_type is None:\n        exp_seq_type = abc.Sequence\n    else:\n        assert isinstance(seq_type, type)\n        exp_seq_type = seq_type\n    if not isinstance(seq, exp_seq_type):\n        return False\n    for item in seq:\n        if not isinstance(item, expected_type):\n            return False\n    return True\n\n\ndef is_list_of(seq, expected_type):\n    \"\"\"Check whether it is a list of some type.\n\n    A partial method of :func:`is_seq_of`.\n    \"\"\"\n    return is_seq_of(seq, expected_type, seq_type=list)\n\n\ndef is_tuple_of(seq, expected_type):\n    \"\"\"Check whether it is a tuple of some type.\n\n    A partial method of :func:`is_seq_of`.\n    \"\"\"\n    return is_seq_of(seq, expected_type, seq_type=tuple)\n\n\ndef slice_list(in_list, lens):\n    \"\"\"Slice a list into several sub lists by a list of given length.\n\n    Args:\n        in_list (list): The list to be sliced.\n        lens(int or list): The expected length of each out list.\n\n    Returns:\n        list: A list of sliced list.\n    \"\"\"\n    if isinstance(lens, int):\n        assert len(in_list) % lens == 0\n        lens = [lens] * int(len(in_list) / lens)\n    if not isinstance(lens, list):\n        raise TypeError('\"indices\" must be an integer or a list of integers')\n    elif sum(lens) != len(in_list):\n        raise ValueError('sum of lens and list length does not '\n                         f'match: {sum(lens)} != {len(in_list)}')\n    out_list = []\n    idx = 0\n    for i in range(len(lens)):\n        out_list.append(in_list[idx:idx + lens[i]])\n        idx += lens[i]\n    return out_list\n\n\ndef concat_list(in_list):\n    \"\"\"Concatenate a list of list into a single list.\n\n    Args:\n        in_list (list): The list of list to be merged.\n\n    Returns:\n        list: The concatenated flat list.\n    \"\"\"\n    return list(itertools.chain(*in_list))\n\n\ndef check_prerequisites(\n        prerequisites,\n        checker,\n        msg_tmpl='Prerequisites \"{}\" are required in method \"{}\" but not '\n        'found, please install them first.'):  # yapf: disable\n    \"\"\"A decorator factory to check if prerequisites are satisfied.\n\n    Args:\n        prerequisites (str of list[str]): Prerequisites to be checked.\n        checker (callable): The checker method that returns True if a\n            prerequisite is meet, False otherwise.\n        msg_tmpl (str): The message template with two variables.\n\n    Returns:\n        decorator: A specific decorator.\n    \"\"\"\n\n    def wrap(func):\n\n        @functools.wraps(func)\n        def wrapped_func(*args, **kwargs):\n            requirements = [prerequisites] if isinstance(\n                prerequisites, str) else prerequisites\n            missing = []\n            for item in requirements:\n                if not checker(item):\n                    missing.append(item)\n            if missing:\n                print(msg_tmpl.format(', '.join(missing), func.__name__))\n                raise RuntimeError('Prerequisites not meet.')\n            else:\n                return func(*args, **kwargs)\n\n        return wrapped_func\n\n    return wrap\n\n\ndef _check_py_package(package):\n    try:\n        import_module(package)\n    except ImportError:\n        return False\n    else:\n        return True\n\n\ndef _check_executable(cmd):\n    if subprocess.call(f'which {cmd}', shell=True) != 0:\n        return False\n    else:\n        return True\n\n\ndef requires_package(prerequisites):\n    \"\"\"A decorator to check if some python packages are installed.\n\n    Example:\n        >>> @requires_package('numpy')\n        >>> func(arg1, args):\n        >>>     return numpy.zeros(1)\n        array([0.])\n        >>> @requires_package(['numpy', 'non_package'])\n        >>> func(arg1, args):\n        >>>     return numpy.zeros(1)\n        ImportError\n    \"\"\"\n    return check_prerequisites(prerequisites, checker=_check_py_package)\n\n\ndef requires_executable(prerequisites):\n    \"\"\"A decorator to check if some executable files are installed.\n\n    Example:\n        >>> @requires_executable('ffmpeg')\n        >>> func(arg1, args):\n        >>>     print(1)\n        1\n    \"\"\"\n    return check_prerequisites(prerequisites, checker=_check_executable)\n\n\ndef deprecated_api_warning(name_dict, cls_name=None):\n    \"\"\"A decorator to check if some arguments are deprecate and try to replace\n    deprecate src_arg_name to dst_arg_name.\n\n    Args:\n        name_dict(dict):\n            key (str): Deprecate argument names.\n            val (str): Expected argument names.\n\n    Returns:\n        func: New function.\n    \"\"\"\n\n    def api_warning_wrapper(old_func):\n\n        @functools.wraps(old_func)\n        def new_func(*args, **kwargs):\n            # get the arg spec of the decorated method\n            args_info = getfullargspec(old_func)\n            # get name of the function\n            func_name = old_func.__name__\n            if cls_name is not None:\n                func_name = f'{cls_name}.{func_name}'\n            if args:\n                arg_names = args_info.args[:len(args)]\n                for src_arg_name, dst_arg_name in name_dict.items():\n                    if src_arg_name in arg_names:\n                        warnings.warn(\n                            f'\"{src_arg_name}\" is deprecated in '\n                            f'`{func_name}`, please use \"{dst_arg_name}\" '\n                            'instead')\n                        arg_names[arg_names.index(src_arg_name)] = dst_arg_name\n            if kwargs:\n                for src_arg_name, dst_arg_name in name_dict.items():\n                    if src_arg_name in kwargs:\n\n                        assert dst_arg_name not in kwargs, (\n                            f'The expected behavior is to replace '\n                            f'the deprecated key `{src_arg_name}` to '\n                            f'new key `{dst_arg_name}`, but got them '\n                            f'in the arguments at the same time, which '\n                            f'is confusing. `{src_arg_name} will be '\n                            f'deprecated in the future, please '\n                            f'use `{dst_arg_name}` instead.')\n\n                        warnings.warn(\n                            f'\"{src_arg_name}\" is deprecated in '\n                            f'`{func_name}`, please use \"{dst_arg_name}\" '\n                            'instead')\n                        kwargs[dst_arg_name] = kwargs.pop(src_arg_name)\n\n            # apply converted arguments to the decorated method\n            output = old_func(*args, **kwargs)\n            return output\n\n        return new_func\n\n    return api_warning_wrapper\n\n\ndef is_method_overridden(method, base_class, derived_class):\n    \"\"\"Check if a method of base class is overridden in derived class.\n\n    Args:\n        method (str): the method name to check.\n        base_class (type): the class of the base class.\n        derived_class (type | Any): the class or instance of the derived class.\n    \"\"\"\n    assert isinstance(base_class, type), \\\n        \"base_class doesn't accept instance, Please pass class instead.\"\n\n    if not isinstance(derived_class, type):\n        derived_class = derived_class.__class__\n\n    base_method = getattr(base_class, method)\n    derived_method = getattr(derived_class, method)\n    return derived_method != base_method\n\n\ndef has_method(obj: object, method: str) -> bool:\n    \"\"\"Check whether the object has a method.\n\n    Args:\n        method (str): The method name to check.\n        obj (object): The object to check.\n\n    Returns:\n        bool: True if the object has the method else False.\n    \"\"\"\n    return hasattr(obj, method) and callable(getattr(obj, method))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/path.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nimport os.path as osp\nfrom pathlib import Path\n\nfrom .misc import is_str\n\n\ndef is_filepath(x):\n    return is_str(x) or isinstance(x, Path)\n\n\ndef fopen(filepath, *args, **kwargs):\n    if is_str(filepath):\n        return open(filepath, *args, **kwargs)\n    elif isinstance(filepath, Path):\n        return filepath.open(*args, **kwargs)\n    raise ValueError('`filepath` should be a string or a Path')\n\n\ndef check_file_exist(filename, msg_tmpl='file \"{}\" does not exist'):\n    if not osp.isfile(filename):\n        raise FileNotFoundError(msg_tmpl.format(filename))\n\n\ndef mkdir_or_exist(dir_name, mode=0o777):\n    if dir_name == '':\n        return\n    dir_name = osp.expanduser(dir_name)\n    os.makedirs(dir_name, mode=mode, exist_ok=True)\n\n\ndef symlink(src, dst, overwrite=True, **kwargs):\n    if os.path.lexists(dst) and overwrite:\n        os.remove(dst)\n    os.symlink(src, dst, **kwargs)\n\n\ndef scandir(dir_path, suffix=None, recursive=False, case_sensitive=True):\n    \"\"\"Scan a directory to find the interested files.\n\n    Args:\n        dir_path (str | obj:`Path`): Path of the directory.\n        suffix (str | tuple(str), optional): File suffix that we are\n            interested in. Default: None.\n        recursive (bool, optional): If set to True, recursively scan the\n            directory. Default: False.\n        case_sensitive (bool, optional) : If set to False, ignore the case of\n            suffix. Default: True.\n\n    Returns:\n        A generator for all the interested files with relative paths.\n    \"\"\"\n    if isinstance(dir_path, (str, Path)):\n        dir_path = str(dir_path)\n    else:\n        raise TypeError('\"dir_path\" must be a string or Path object')\n\n    if (suffix is not None) and not isinstance(suffix, (str, tuple)):\n        raise TypeError('\"suffix\" must be a string or tuple of strings')\n\n    if suffix is not None and not case_sensitive:\n        suffix = suffix.lower() if isinstance(suffix, str) else tuple(\n            item.lower() for item in suffix)\n\n    root = dir_path\n\n    def _scandir(dir_path, suffix, recursive, case_sensitive):\n        for entry in os.scandir(dir_path):\n            if not entry.name.startswith('.') and entry.is_file():\n                rel_path = osp.relpath(entry.path, root)\n                _rel_path = rel_path if case_sensitive else rel_path.lower()\n                if suffix is None or _rel_path.endswith(suffix):\n                    yield rel_path\n            elif recursive and os.path.isdir(entry.path):\n                # scan recursively if entry.path is a directory\n                yield from _scandir(entry.path, suffix, recursive,\n                                    case_sensitive)\n\n    return _scandir(dir_path, suffix, recursive, case_sensitive)\n\n\ndef find_vcs_root(path, markers=('.git', )):\n    \"\"\"Finds the root directory (including itself) of specified markers.\n\n    Args:\n        path (str): Path of directory or file.\n        markers (list[str], optional): List of file or directory names.\n\n    Returns:\n        The directory contained one of the markers or None if not found.\n    \"\"\"\n    if osp.isfile(path):\n        path = osp.dirname(path)\n\n    prev, cur = None, osp.abspath(osp.expanduser(path))\n    while cur != prev:\n        if any(osp.exists(osp.join(cur, marker)) for marker in markers):\n            return cur\n        prev, cur = cur, osp.split(cur)[0]\n    return None\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/position_embedding.py",
    "content": "import torch\nimport torch.nn as nn\nimport math\n\nclass RelPositionEmbedding(nn.Module):\n    def __init__(self, num_pos_feats=64, pos_norm=True):\n        super().__init__()\n        self.num_pos_feats = num_pos_feats\n        self.fc = nn.Linear(4, self.num_pos_feats,bias=False)\n        #nn.init.orthogonal_(self.fc.weight)\n        #self.fc.weight.requires_grad = False\n        self.pos_norm = pos_norm\n        if self.pos_norm:\n            self.norm = nn.LayerNorm(self.num_pos_feats)\n    def forward(self, tensor):\n        #mask = nesttensor.mask\n        B,C,H,W = tensor.shape\n        #print('tensor.shape',  tensor.shape)\n        y_range = (torch.arange(H) / float(H - 1)).to(tensor.device)\n        #y_axis = torch.stack((y_range, 1-y_range),dim=1)\n        y_axis = torch.stack((torch.cos(y_range * math.pi), torch.sin(y_range * math.pi)), dim=1)\n        y_axis = y_axis.reshape(H, 1, 2).repeat(1, W, 1).reshape(H * W, 2)\n\n        x_range = (torch.arange(W) / float(W - 1)).to(tensor.device)\n        #x_axis =torch.stack((x_range,1-x_range),dim=1)\n        x_axis = torch.stack((torch.cos(x_range * math.pi), torch.sin(x_range * math.pi)), dim=1)\n        x_axis = x_axis.reshape(1, W, 2).repeat(H, 1, 1).reshape(H * W, 2)\n        x_pos = torch.cat((y_axis, x_axis), dim=1)\n        x_pos = self.fc(x_pos)\n\n        if self.pos_norm:\n            x_pos = self.norm(x_pos)\n        #print('xpos,', x_pos.max(),x_pos.min())\n        return x_pos"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/priority.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom enum import Enum\n\n\nclass Priority(Enum):\n    \"\"\"Hook priority levels.\n\n    +--------------+------------+\n    | Level        | Value      |\n    +==============+============+\n    | HIGHEST      | 0          |\n    +--------------+------------+\n    | VERY_HIGH    | 10         |\n    +--------------+------------+\n    | HIGH         | 30         |\n    +--------------+------------+\n    | ABOVE_NORMAL | 40         |\n    +--------------+------------+\n    | NORMAL       | 50         |\n    +--------------+------------+\n    | BELOW_NORMAL | 60         |\n    +--------------+------------+\n    | LOW          | 70         |\n    +--------------+------------+\n    | VERY_LOW     | 90         |\n    +--------------+------------+\n    | LOWEST       | 100        |\n    +--------------+------------+\n    \"\"\"\n\n    HIGHEST = 0\n    VERY_HIGH = 10\n    HIGH = 30\n    ABOVE_NORMAL = 40\n    NORMAL = 50\n    BELOW_NORMAL = 60\n    LOW = 70\n    VERY_LOW = 90\n    LOWEST = 100\n\n\ndef get_priority(priority):\n    \"\"\"Get priority value.\n\n    Args:\n        priority (int or str or :obj:`Priority`): Priority.\n\n    Returns:\n        int: The priority value.\n    \"\"\"\n    if isinstance(priority, int):\n        if priority < 0 or priority > 100:\n            raise ValueError('priority must be between 0 and 100')\n        return priority\n    elif isinstance(priority, Priority):\n        return priority.value\n    elif isinstance(priority, str):\n        return Priority[priority.upper()].value\n    else:\n        raise TypeError('priority must be an integer or Priority enum value')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/progressbar.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport sys\nfrom collections.abc import Iterable\nfrom multiprocessing import Pool\nfrom shutil import get_terminal_size\n\nfrom .timer import Timer\n\n\nclass ProgressBar:\n    \"\"\"A progress bar which can print the progress.\"\"\"\n\n    def __init__(self, task_num=0, bar_width=50, start=True, file=sys.stdout):\n        self.task_num = task_num\n        self.bar_width = bar_width\n        self.completed = 0\n        self.file = file\n        if start:\n            self.start()\n\n    @property\n    def terminal_width(self):\n        width, _ = get_terminal_size()\n        return width\n\n    def start(self):\n        if self.task_num > 0:\n            self.file.write(f'[{\" \" * self.bar_width}] 0/{self.task_num}, '\n                            'elapsed: 0s, ETA:')\n        else:\n            self.file.write('completed: 0, elapsed: 0s')\n        self.file.flush()\n        self.timer = Timer()\n\n    def update(self, num_tasks=1):\n        assert num_tasks > 0\n        self.completed += num_tasks\n        elapsed = self.timer.since_start()\n        if elapsed > 0:\n            fps = self.completed / elapsed\n        else:\n            fps = float('inf')\n        if self.task_num > 0:\n            percentage = self.completed / float(self.task_num)\n            eta = int(elapsed * (1 - percentage) / percentage + 0.5)\n            msg = f'\\r[{{}}] {self.completed}/{self.task_num}, ' \\\n                  f'{fps:.1f} task/s, elapsed: {int(elapsed + 0.5)}s, ' \\\n                  f'ETA: {eta:5}s'\n\n            bar_width = min(self.bar_width,\n                            int(self.terminal_width - len(msg)) + 2,\n                            int(self.terminal_width * 0.6))\n            bar_width = max(2, bar_width)\n            mark_width = int(bar_width * percentage)\n            bar_chars = '>' * mark_width + ' ' * (bar_width - mark_width)\n            self.file.write(msg.format(bar_chars))\n        else:\n            self.file.write(\n                f'completed: {self.completed}, elapsed: {int(elapsed + 0.5)}s,'\n                f' {fps:.1f} tasks/s')\n        self.file.flush()\n\n\ndef track_progress(func, tasks, bar_width=50, file=sys.stdout, **kwargs):\n    \"\"\"Track the progress of tasks execution with a progress bar.\n\n    Tasks are done with a simple for-loop.\n\n    Args:\n        func (callable): The function to be applied to each task.\n        tasks (list or tuple[Iterable, int]): A list of tasks or\n            (tasks, total num).\n        bar_width (int): Width of progress bar.\n\n    Returns:\n        list: The task results.\n    \"\"\"\n    if isinstance(tasks, tuple):\n        assert len(tasks) == 2\n        assert isinstance(tasks[0], Iterable)\n        assert isinstance(tasks[1], int)\n        task_num = tasks[1]\n        tasks = tasks[0]\n    elif isinstance(tasks, Iterable):\n        task_num = len(tasks)\n    else:\n        raise TypeError(\n            '\"tasks\" must be an iterable object or a (iterator, int) tuple')\n    prog_bar = ProgressBar(task_num, bar_width, file=file)\n    results = []\n    for task in tasks:\n        results.append(func(task, **kwargs))\n        prog_bar.update()\n    prog_bar.file.write('\\n')\n    return results\n\n\ndef init_pool(process_num, initializer=None, initargs=None):\n    if initializer is None:\n        return Pool(process_num)\n    elif initargs is None:\n        return Pool(process_num, initializer)\n    else:\n        if not isinstance(initargs, tuple):\n            raise TypeError('\"initargs\" must be a tuple')\n        return Pool(process_num, initializer, initargs)\n\n\ndef track_parallel_progress(func,\n                            tasks,\n                            nproc,\n                            initializer=None,\n                            initargs=None,\n                            bar_width=50,\n                            chunksize=1,\n                            skip_first=False,\n                            keep_order=True,\n                            file=sys.stdout):\n    \"\"\"Track the progress of parallel task execution with a progress bar.\n\n    The built-in :mod:`multiprocessing` module is used for process pools and\n    tasks are done with :func:`Pool.map` or :func:`Pool.imap_unordered`.\n\n    Args:\n        func (callable): The function to be applied to each task.\n        tasks (list or tuple[Iterable, int]): A list of tasks or\n            (tasks, total num).\n        nproc (int): Process (worker) number.\n        initializer (None or callable): Refer to :class:`multiprocessing.Pool`\n            for details.\n        initargs (None or tuple): Refer to :class:`multiprocessing.Pool` for\n            details.\n        chunksize (int): Refer to :class:`multiprocessing.Pool` for details.\n        bar_width (int): Width of progress bar.\n        skip_first (bool): Whether to skip the first sample for each worker\n            when estimating fps, since the initialization step may takes\n            longer.\n        keep_order (bool): If True, :func:`Pool.imap` is used, otherwise\n            :func:`Pool.imap_unordered` is used.\n\n    Returns:\n        list: The task results.\n    \"\"\"\n    if isinstance(tasks, tuple):\n        assert len(tasks) == 2\n        assert isinstance(tasks[0], Iterable)\n        assert isinstance(tasks[1], int)\n        task_num = tasks[1]\n        tasks = tasks[0]\n    elif isinstance(tasks, Iterable):\n        task_num = len(tasks)\n    else:\n        raise TypeError(\n            '\"tasks\" must be an iterable object or a (iterator, int) tuple')\n    pool = init_pool(nproc, initializer, initargs)\n    start = not skip_first\n    task_num -= nproc * chunksize * int(skip_first)\n    prog_bar = ProgressBar(task_num, bar_width, start, file=file)\n    results = []\n    if keep_order:\n        gen = pool.imap(func, tasks, chunksize)\n    else:\n        gen = pool.imap_unordered(func, tasks, chunksize)\n    for result in gen:\n        results.append(result)\n        if skip_first:\n            if len(results) < nproc * chunksize:\n                continue\n            elif len(results) == nproc * chunksize:\n                prog_bar.start()\n                continue\n        prog_bar.update()\n    prog_bar.file.write('\\n')\n    pool.close()\n    pool.join()\n    return results\n\n\ndef track_iter_progress(tasks, bar_width=50, file=sys.stdout):\n    \"\"\"Track the progress of tasks iteration or enumeration with a progress\n    bar.\n\n    Tasks are yielded with a simple for-loop.\n\n    Args:\n        tasks (list or tuple[Iterable, int]): A list of tasks or\n            (tasks, total num).\n        bar_width (int): Width of progress bar.\n\n    Yields:\n        list: The task results.\n    \"\"\"\n    if isinstance(tasks, tuple):\n        assert len(tasks) == 2\n        assert isinstance(tasks[0], Iterable)\n        assert isinstance(tasks[1], int)\n        task_num = tasks[1]\n        tasks = tasks[0]\n    elif isinstance(tasks, Iterable):\n        task_num = len(tasks)\n    else:\n        raise TypeError(\n            '\"tasks\" must be an iterable object or a (iterator, int) tuple')\n    prog_bar = ProgressBar(task_num, bar_width, file=file)\n    for task in tasks:\n        yield task\n        prog_bar.update()\n    prog_bar.file.write('\\n')\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/registry.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport inspect\nimport warnings\nfrom functools import partial\n\nfrom .misc import is_seq_of\n\n\ndef build_from_cfg(cfg, registry, default_args=None):\n    \"\"\"Build a module from config dict.\n\n    Args:\n        cfg (dict): Config dict. It should at least contain the key \"type\".\n        registry (:obj:`Registry`): The registry to search the type from.\n        default_args (dict, optional): Default initialization arguments.\n\n    Returns:\n        object: The constructed object.\n    \"\"\"\n    if not isinstance(cfg, dict):\n        raise TypeError(f'cfg must be a dict, but got {type(cfg)}')\n    if 'type' not in cfg:\n        if default_args is None or 'type' not in default_args:\n            raise KeyError(\n                '`cfg` or `default_args` must contain the key \"type\", '\n                f'but got {cfg}\\n{default_args}')\n    if not isinstance(registry, Registry):\n        raise TypeError('registry must be an mmcv.Registry object, '\n                        f'but got {type(registry)}')\n    if not (isinstance(default_args, dict) or default_args is None):\n        raise TypeError('default_args must be a dict or None, '\n                        f'but got {type(default_args)}')\n\n    args = cfg.copy()\n\n    if default_args is not None:\n        for name, value in default_args.items():\n            args.setdefault(name, value)\n\n    obj_type = args.pop('type')\n    if isinstance(obj_type, str):\n        obj_cls = registry.get(obj_type)\n        if obj_cls is None:\n            raise KeyError(\n                f'{obj_type} is not in the {registry.name} registry')\n    elif inspect.isclass(obj_type):\n        obj_cls = obj_type\n    else:\n        raise TypeError(\n            f'type must be a str or valid type, but got {type(obj_type)}')\n    try:\n        return obj_cls(**args)\n    except Exception as e:\n        # Normal TypeError does not print class name.\n        raise type(e)(f'{obj_cls.__name__}: {e}')\n\n\nclass Registry:\n    \"\"\"A registry to map strings to classes.\n\n    Registered object could be built from registry.\n    Example:\n        >>> MODELS = Registry('models')\n        >>> @MODELS.register_module()\n        >>> class ResNet:\n        >>>     pass\n        >>> resnet = MODELS.build(dict(type='ResNet'))\n\n    Please refer to\n    https://mmcv.readthedocs.io/en/latest/understand_mmcv/registry.html for\n    advanced usage.\n\n    Args:\n        name (str): Registry name.\n        build_func(func, optional): Build function to construct instance from\n            Registry, func:`build_from_cfg` is used if neither ``parent`` or\n            ``build_func`` is specified. If ``parent`` is specified and\n            ``build_func`` is not given,  ``build_func`` will be inherited\n            from ``parent``. Default: None.\n        parent (Registry, optional): Parent registry. The class registered in\n            children registry could be built from parent. Default: None.\n        scope (str, optional): The scope of registry. It is the key to search\n            for children registry. If not specified, scope will be the name of\n            the package where class is defined, e.g. mmdet, mmcls, mmseg.\n            Default: None.\n    \"\"\"\n\n    def __init__(self, name, build_func=None, parent=None, scope=None):\n        self._name = name\n        self._module_dict = dict()\n        self._children = dict()\n        self._scope = self.infer_scope() if scope is None else scope\n\n        # self.build_func will be set with the following priority:\n        # 1. build_func\n        # 2. parent.build_func\n        # 3. build_from_cfg\n        if build_func is None:\n            if parent is not None:\n                self.build_func = parent.build_func\n            else:\n                self.build_func = build_from_cfg\n        else:\n            self.build_func = build_func\n        if parent is not None:\n            assert isinstance(parent, Registry)\n            parent._add_children(self)\n            self.parent = parent\n        else:\n            self.parent = None\n\n    def __len__(self):\n        return len(self._module_dict)\n\n    def __contains__(self, key):\n        return self.get(key) is not None\n\n    def __repr__(self):\n        format_str = self.__class__.__name__ + \\\n                     f'(name={self._name}, ' \\\n                     f'items={self._module_dict})'\n        return format_str\n\n    @staticmethod\n    def infer_scope():\n        \"\"\"Infer the scope of registry.\n\n        The name of the package where registry is defined will be returned.\n\n        Example:\n            # in mmdet/models/backbone/resnet.py\n            >>> MODELS = Registry('models')\n            >>> @MODELS.register_module()\n            >>> class ResNet:\n            >>>     pass\n            The scope of ``ResNet`` will be ``mmdet``.\n\n\n        Returns:\n            scope (str): The inferred scope name.\n        \"\"\"\n        # inspect.stack() trace where this function is called, the index-2\n        # indicates the frame where `infer_scope()` is called\n        filename = inspect.getmodule(inspect.stack()[2][0]).__name__\n        split_filename = filename.split('.')\n        return split_filename[0]\n\n    @staticmethod\n    def split_scope_key(key):\n        \"\"\"Split scope and key.\n\n        The first scope will be split from key.\n\n        Examples:\n            >>> Registry.split_scope_key('mmcv.ResNet')\n            'mmdet', 'ResNet'\n            >>> Registry.split_scope_key('ResNet')\n            None, 'ResNet'\n\n        Return:\n            scope (str, None): The first scope.\n            key (str): The remaining key.\n        \"\"\"\n        split_index = key.find('.')\n        if split_index != -1:\n            return key[:split_index], key[split_index + 1:]\n        else:\n            return None, key\n\n    @property\n    def name(self):\n        return self._name\n\n    @property\n    def scope(self):\n        return self._scope\n\n    @property\n    def module_dict(self):\n        return self._module_dict\n\n    @property\n    def children(self):\n        return self._children\n\n    def get(self, key):\n        \"\"\"Get the registry record.\n\n        Args:\n            key (str): The class name in string format.\n\n        Returns:\n            class: The corresponding class.\n        \"\"\"\n        scope, real_key = self.split_scope_key(key)\n        if scope is None or scope == self._scope:\n            # get from self\n            if real_key in self._module_dict:\n                return self._module_dict[real_key]\n        else:\n            # get from self._children\n            if scope in self._children:\n                return self._children[scope].get(real_key)\n            else:\n                # goto root\n                parent = self.parent\n                while parent.parent is not None:\n                    parent = parent.parent\n                return parent.get(key)\n\n    def build(self, *args, **kwargs):\n        return self.build_func(*args, **kwargs, registry=self)\n\n    def _add_children(self, registry):\n        \"\"\"Add children for a registry.\n\n        The ``registry`` will be added as children based on its scope.\n        The parent registry could build objects from children registry.\n\n        Example:\n            >>> models = Registry('models')\n            >>> mmdet_models = Registry('models', parent=models)\n            >>> @mmdet_models.register_module()\n            >>> class ResNet:\n            >>>     pass\n            >>> resnet = models.build(dict(type='mmcv.ResNet'))\n        \"\"\"\n\n        assert isinstance(registry, Registry)\n        assert registry.scope is not None\n        assert registry.scope not in self.children, \\\n            f'scope {registry.scope} exists in {self.name} registry'\n        self.children[registry.scope] = registry\n\n    def _register_module(self, module_class, module_name=None, force=False):\n        if not inspect.isclass(module_class):\n            raise TypeError('module must be a class, '\n                            f'but got {type(module_class)}')\n\n        if module_name is None:\n            module_name = module_class.__name__\n        if isinstance(module_name, str):\n            module_name = [module_name]\n        for name in module_name:\n            if not force and name in self._module_dict:\n                raise KeyError(f'{name} is already registered '\n                               f'in {self.name}')\n            self._module_dict[name] = module_class\n\n    def deprecated_register_module(self, cls=None, force=False):\n        warnings.warn(\n            'The old API of register_module(module, force=False) '\n            'is deprecated and will be removed, please use the new API '\n            'register_module(name=None, force=False, module=None) instead.')\n        if cls is None:\n            return partial(self.deprecated_register_module, force=force)\n        self._register_module(cls, force=force)\n        return cls\n\n    def register_module(self, name=None, force=False, module=None):\n        \"\"\"Register a module.\n\n        A record will be added to `self._module_dict`, whose key is the class\n        name or the specified name, and value is the class itself.\n        It can be used as a decorator or a normal function.\n\n        Example:\n            >>> backbones = Registry('backbone')\n            >>> @backbones.register_module()\n            >>> class ResNet:\n            >>>     pass\n\n            >>> backbones = Registry('backbone')\n            >>> @backbones.register_module(name='mnet')\n            >>> class MobileNet:\n            >>>     pass\n\n            >>> backbones = Registry('backbone')\n            >>> class ResNet:\n            >>>     pass\n            >>> backbones.register_module(ResNet)\n\n        Args:\n            name (str | None): The module name to be registered. If not\n                specified, the class name will be used.\n            force (bool, optional): Whether to override an existing class with\n                the same name. Default: False.\n            module (type): Module class to be registered.\n        \"\"\"\n        if not isinstance(force, bool):\n            raise TypeError(f'force must be a boolean, but got {type(force)}')\n        # NOTE: This is a walkaround to be compatible with the old api,\n        # while it may introduce unexpected bugs.\n        if isinstance(name, type):\n            return self.deprecated_register_module(name, force=force)\n\n        # raise the error ahead of time\n        if not (name is None or isinstance(name, str) or is_seq_of(name, str)):\n            raise TypeError(\n                'name must be either of None, an instance of str or a sequence'\n                f'  of str, but got {type(name)}')\n\n        # use it as a normal method: x.register_module(module=SomeClass)\n        if module is not None:\n            self._register_module(\n                module_class=module, module_name=name, force=force)\n            return module\n\n        # use it as a decorator: @x.register_module()\n        def _register(cls):\n            self._register_module(\n                module_class=cls, module_name=name, force=force)\n            return cls\n\n        return _register\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/runner_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nimport random\nimport sys\nimport time\nimport warnings\nfrom getpass import getuser\nfrom socket import gethostname\n\nimport numpy as np\nfrom mmcv.utils import is_str\nimport functools\nimport os\nimport subprocess\nfrom collections import OrderedDict\n\nimport torch\nimport torch.multiprocessing as mp\nfrom torch import distributed as dist\nfrom torch._utils import (_flatten_dense_tensors, _take_tensors,\n                          _unflatten_dense_tensors)\n\n\ndef get_host_info():\n    \"\"\"Get hostname and username.\n\n    Return empty string if exception raised, e.g. ``getpass.getuser()`` will\n    lead to error in docker container\n    \"\"\"\n    host = ''\n    try:\n        host = f'{getuser()}@{gethostname()}'\n    except Exception as e:\n        warnings.warn(f'Host or user not found: {str(e)}')\n    finally:\n        return host\n\n\ndef get_time_str():\n    return time.strftime('%Y%m%d_%H%M%S', time.localtime())\n\n\ndef obj_from_dict(info, parent=None, default_args=None):\n    \"\"\"Initialize an object from dict.\n\n    The dict must contain the key \"type\", which indicates the object type, it\n    can be either a string or type, such as \"list\" or ``list``. Remaining\n    fields are treated as the arguments for constructing the object.\n\n    Args:\n        info (dict): Object types and arguments.\n        parent (:class:`module`): Module which may containing expected object\n            classes.\n        default_args (dict, optional): Default arguments for initializing the\n            object.\n\n    Returns:\n        any type: Object built from the dict.\n    \"\"\"\n    assert isinstance(info, dict) and 'type' in info\n    assert isinstance(default_args, dict) or default_args is None\n    args = info.copy()\n    obj_type = args.pop('type')\n    if is_str(obj_type):\n        if parent is not None:\n            obj_type = getattr(parent, obj_type)\n        else:\n            obj_type = sys.modules[obj_type]\n    elif not isinstance(obj_type, type):\n        raise TypeError('type must be a str or valid type, but '\n                        f'got {type(obj_type)}')\n    if default_args is not None:\n        for name, value in default_args.items():\n            args.setdefault(name, value)\n    return obj_type(**args)\n\n\ndef set_random_seed(seed, deterministic=False, use_rank_shift=False):\n    \"\"\"Set random seed.\n\n    Args:\n        seed (int): Seed to be used.\n        deterministic (bool): Whether to set the deterministic option for\n            CUDNN backend, i.e., set `torch.backends.cudnn.deterministic`\n            to True and `torch.backends.cudnn.benchmark` to False.\n            Default: False.\n        rank_shift (bool): Whether to add rank number to the random seed to\n            have different random seed in different threads. Default: False.\n    \"\"\"\n    if use_rank_shift:\n        rank, _ = get_dist_info()\n        seed += rank\n    random.seed(seed)\n    np.random.seed(seed)\n    torch.manual_seed(seed)\n    torch.cuda.manual_seed(seed)\n    torch.cuda.manual_seed_all(seed)\n    os.environ['PYTHONHASHSEED'] = str(seed)\n    if deterministic:\n        torch.backends.cudnn.deterministic = True\n        torch.backends.cudnn.benchmark = False\n\n\ndef init_dist(launcher, backend='nccl', **kwargs):\n    if mp.get_start_method(allow_none=True) is None:\n        mp.set_start_method('spawn')\n    if launcher == 'pytorch':\n        _init_dist_pytorch(backend, **kwargs)\n    elif launcher == 'mpi':\n        _init_dist_mpi(backend, **kwargs)\n    elif launcher == 'slurm':\n        _init_dist_slurm(backend, **kwargs)\n    else:\n        raise ValueError(f'Invalid launcher type: {launcher}')\n\n\ndef _init_dist_pytorch(backend, **kwargs):\n    # TODO: use local_rank instead of rank % num_gpus\n    rank = int(os.environ['RANK'])\n    num_gpus = torch.cuda.device_count()\n    torch.cuda.set_device(rank % num_gpus)\n    dist.init_process_group(backend=backend, **kwargs)\n\n\ndef _init_dist_mpi(backend, **kwargs):\n    # TODO: use local_rank instead of rank % num_gpus\n    rank = int(os.environ['OMPI_COMM_WORLD_RANK'])\n    num_gpus = torch.cuda.device_count()\n    torch.cuda.set_device(rank % num_gpus)\n    dist.init_process_group(backend=backend, **kwargs)\n\n\ndef _init_dist_slurm(backend, port=None):\n    \"\"\"Initialize slurm distributed training environment.\n\n    If argument ``port`` is not specified, then the master port will be system\n    environment variable ``MASTER_PORT``. If ``MASTER_PORT`` is not in system\n    environment variable, then a default port ``29500`` will be used.\n\n    Args:\n        backend (str): Backend of torch.distributed.\n        port (int, optional): Master port. Defaults to None.\n    \"\"\"\n    proc_id = int(os.environ['SLURM_PROCID'])\n    ntasks = int(os.environ['SLURM_NTASKS'])\n    node_list = os.environ['SLURM_NODELIST']\n    num_gpus = torch.cuda.device_count()\n    torch.cuda.set_device(proc_id % num_gpus)\n    addr = subprocess.getoutput(\n        f'scontrol show hostname {node_list} | head -n1')\n    # specify master port\n    if port is not None:\n        os.environ['MASTER_PORT'] = str(port)\n    elif 'MASTER_PORT' in os.environ:\n        pass  # use MASTER_PORT in the environment variable\n    else:\n        # 29500 is torch.distributed default port\n        os.environ['MASTER_PORT'] = '29500'\n    # use MASTER_ADDR in the environment variable if it already exists\n    if 'MASTER_ADDR' not in os.environ:\n        os.environ['MASTER_ADDR'] = addr\n    os.environ['WORLD_SIZE'] = str(ntasks)\n    os.environ['LOCAL_RANK'] = str(proc_id % num_gpus)\n    os.environ['RANK'] = str(proc_id)\n    dist.init_process_group(backend=backend)\n\n\ndef get_dist_info():\n    if dist.is_available() and dist.is_initialized():\n        rank = dist.get_rank()\n        world_size = dist.get_world_size()\n    else:\n        rank = 0\n        world_size = 1\n    return rank, world_size\n\n\ndef master_only(func):\n\n    @functools.wraps(func)\n    def wrapper(*args, **kwargs):\n        rank, _ = get_dist_info()\n        if rank == 0:\n            return func(*args, **kwargs)\n\n    return wrapper\n\n\ndef allreduce_params(params, coalesce=True, bucket_size_mb=-1):\n    \"\"\"Allreduce parameters.\n\n    Args:\n        params (list[torch.Parameters]): List of parameters or buffers of a\n            model.\n        coalesce (bool, optional): Whether allreduce parameters as a whole.\n            Defaults to True.\n        bucket_size_mb (int, optional): Size of bucket, the unit is MB.\n            Defaults to -1.\n    \"\"\"\n    _, world_size = get_dist_info()\n    if world_size == 1:\n        return\n    params = [param.data for param in params]\n    if coalesce:\n        _allreduce_coalesced(params, world_size, bucket_size_mb)\n    else:\n        for tensor in params:\n            dist.all_reduce(tensor.div_(world_size))\n\n\ndef allreduce_grads(params, coalesce=True, bucket_size_mb=-1):\n    \"\"\"Allreduce gradients.\n\n    Args:\n        params (list[torch.Parameters]): List of parameters of a model\n        coalesce (bool, optional): Whether allreduce parameters as a whole.\n            Defaults to True.\n        bucket_size_mb (int, optional): Size of bucket, the unit is MB.\n            Defaults to -1.\n    \"\"\"\n    grads = [\n        param.grad.data for param in params\n        if param.requires_grad and param.grad is not None\n    ]\n    _, world_size = get_dist_info()\n    if world_size == 1:\n        return\n    if coalesce:\n        _allreduce_coalesced(grads, world_size, bucket_size_mb)\n    else:\n        for tensor in grads:\n            dist.all_reduce(tensor.div_(world_size))\n\n\ndef _allreduce_coalesced(tensors, world_size, bucket_size_mb=-1):\n    if bucket_size_mb > 0:\n        bucket_size_bytes = bucket_size_mb * 1024 * 1024\n        buckets = _take_tensors(tensors, bucket_size_bytes)\n    else:\n        buckets = OrderedDict()\n        for tensor in tensors:\n            tp = tensor.type()\n            if tp not in buckets:\n                buckets[tp] = []\n            buckets[tp].append(tensor)\n        buckets = buckets.values()\n\n    for bucket in buckets:\n        flat_tensors = _flatten_dense_tensors(bucket)\n        dist.all_reduce(flat_tensors)\n        flat_tensors.div_(world_size)\n        for tensor, synced in zip(\n                bucket, _unflatten_dense_tensors(flat_tensors, bucket)):\n            tensor.copy_(synced)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/timer.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom time import time\n\n\nclass TimerError(Exception):\n\n    def __init__(self, message):\n        self.message = message\n        super(TimerError, self).__init__(message)\n\n\nclass Timer:\n    \"\"\"A flexible Timer class.\n\n    :Example:\n\n    >>> import time\n    >>> import mmcv\n    >>> with mmcv.Timer():\n    >>>     # simulate a code block that will run for 1s\n    >>>     time.sleep(1)\n    1.000\n    >>> with mmcv.Timer(print_tmpl='it takes {:.1f} seconds'):\n    >>>     # simulate a code block that will run for 1s\n    >>>     time.sleep(1)\n    it takes 1.0 seconds\n    >>> timer = mmcv.Timer()\n    >>> time.sleep(0.5)\n    >>> print(timer.since_start())\n    0.500\n    >>> time.sleep(0.5)\n    >>> print(timer.since_last_check())\n    0.500\n    >>> print(timer.since_start())\n    1.000\n    \"\"\"\n\n    def __init__(self, start=True, print_tmpl=None):\n        self._is_running = False\n        self.print_tmpl = print_tmpl if print_tmpl else '{:.3f}'\n        if start:\n            self.start()\n\n    @property\n    def is_running(self):\n        \"\"\"bool: indicate whether the timer is running\"\"\"\n        return self._is_running\n\n    def __enter__(self):\n        self.start()\n        return self\n\n    def __exit__(self, type, value, traceback):\n        print(self.print_tmpl.format(self.since_last_check()))\n        self._is_running = False\n\n    def start(self):\n        \"\"\"Start the timer.\"\"\"\n        if not self._is_running:\n            self._t_start = time()\n            self._is_running = True\n        self._t_last = time()\n\n    def since_start(self):\n        \"\"\"Total time since the timer is started.\n\n        Returns (float): Time in seconds.\n        \"\"\"\n        if not self._is_running:\n            raise TimerError('timer is not running')\n        self._t_last = time()\n        return self._t_last - self._t_start\n\n    def since_last_check(self):\n        \"\"\"Time since the last checking.\n\n        Either :func:`since_start` or :func:`since_last_check` is a checking\n        operation.\n\n        Returns (float): Time in seconds.\n        \"\"\"\n        if not self._is_running:\n            raise TimerError('timer is not running')\n        dur = time() - self._t_last\n        self._t_last = time()\n        return dur\n\n\n_g_timers = {}  # global timers\n\n\ndef check_time(timer_id):\n    \"\"\"Add check points in a single line.\n\n    This method is suitable for running a task on a list of items. A timer will\n    be registered when the method is called for the first time.\n\n    :Example:\n\n    >>> import time\n    >>> import mmcv\n    >>> for i in range(1, 6):\n    >>>     # simulate a code block\n    >>>     time.sleep(i)\n    >>>     mmcv.check_time('task1')\n    2.000\n    3.000\n    4.000\n    5.000\n\n    Args:\n        timer_id (str): Timer identifier.\n    \"\"\"\n    if timer_id not in _g_timers:\n        _g_timers[timer_id] = Timer()\n        return 0\n    else:\n        return _g_timers[timer_id].since_last_check()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/util_mixins.py",
    "content": "\"\"\"This module defines the :class:`NiceRepr` mixin class, which defines a\n``__repr__`` and ``__str__`` method that only depend on a custom ``__nice__``\nmethod, which you must define. This means you only have to overload one\nfunction instead of two.  Furthermore, if the object defines a ``__len__``\nmethod, then the ``__nice__`` method defaults to something sensible, otherwise\nit is treated as abstract and raises ``NotImplementedError``.\n\nTo use simply have your object inherit from :class:`NiceRepr`\n(multi-inheritance should be ok).\n\nThis code was copied from the ubelt library: https://github.com/Erotemic/ubelt\n\nExample:\n    >>> # Objects that define __nice__ have a default __str__ and __repr__\n    >>> class Student(NiceRepr):\n    ...    def __init__(self, name):\n    ...        self.name = name\n    ...    def __nice__(self):\n    ...        return self.name\n    >>> s1 = Student('Alice')\n    >>> s2 = Student('Bob')\n    >>> print(f's1 = {s1}')\n    >>> print(f's2 = {s2}')\n    s1 = <Student(Alice)>\n    s2 = <Student(Bob)>\n\nExample:\n    >>> # Objects that define __len__ have a default __nice__\n    >>> class Group(NiceRepr):\n    ...    def __init__(self, data):\n    ...        self.data = data\n    ...    def __len__(self):\n    ...        return len(self.data)\n    >>> g = Group([1, 2, 3])\n    >>> print(f'g = {g}')\n    g = <Group(3)>\n\"\"\"\nimport warnings\n\n\nclass NiceRepr:\n    \"\"\"Inherit from this class and define ``__nice__`` to \"nicely\" print your\n    objects.\n\n    Defines ``__str__`` and ``__repr__`` in terms of ``__nice__`` function\n    Classes that inherit from :class:`NiceRepr` should redefine ``__nice__``.\n    If the inheriting class has a ``__len__``, method then the default\n    ``__nice__`` method will return its length.\n\n    Example:\n        >>> class Foo(NiceRepr):\n        ...    def __nice__(self):\n        ...        return 'info'\n        >>> foo = Foo()\n        >>> assert str(foo) == '<Foo(info)>'\n        >>> assert repr(foo).startswith('<Foo(info) at ')\n\n    Example:\n        >>> class Bar(NiceRepr):\n        ...    pass\n        >>> bar = Bar()\n        >>> import pytest\n        >>> with pytest.warns(None) as record:\n        >>>     assert 'object at' in str(bar)\n        >>>     assert 'object at' in repr(bar)\n\n    Example:\n        >>> class Baz(NiceRepr):\n        ...    def __len__(self):\n        ...        return 5\n        >>> baz = Baz()\n        >>> assert str(baz) == '<Baz(5)>'\n    \"\"\"\n\n    def __nice__(self):\n        \"\"\"str: a \"nice\" summary string describing this module\"\"\"\n        if hasattr(self, '__len__'):\n            # It is a common pattern for objects to use __len__ in __nice__\n            # As a convenience we define a default __nice__ for these objects\n            return str(len(self))\n        else:\n            # In all other cases force the subclass to overload __nice__\n            raise NotImplementedError(\n                f'Define the __nice__ method for {self.__class__!r}')\n\n    def __repr__(self):\n        \"\"\"str: the string of the module\"\"\"\n        try:\n            nice = self.__nice__()\n            classname = self.__class__.__name__\n            return f'<{classname}({nice}) at {hex(id(self))}>'\n        except NotImplementedError as ex:\n            warnings.warn(str(ex), category=RuntimeWarning)\n            return object.__repr__(self)\n\n    def __str__(self):\n        \"\"\"str: the string of the module\"\"\"\n        try:\n            classname = self.__class__.__name__\n            nice = self.__nice__()\n            return f'<{classname}({nice})>'\n        except NotImplementedError as ex:\n            warnings.warn(str(ex), category=RuntimeWarning)\n            return object.__repr__(self)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/version_utils.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nimport subprocess\nimport warnings\n\nfrom packaging.version import parse\n\ndef digit_version(version_str: str, length: int = 4):\n    \"\"\"Convert a version string into a tuple of integers.\n\n    This method is usually used for comparing two versions. For pre-release\n    versions: alpha < beta < rc.\n\n    Args:\n        version_str (str): The version string.\n        length (int): The maximum number of version levels. Default: 4.\n\n    Returns:\n        tuple[int]: The version info in digits (integers).\n    \"\"\"\n    version = parse(version_str)\n    assert version.release, f'failed to parse version {version_str}'\n    release = list(version.release)\n    release = release[:length]\n    if len(release) < length:\n        release = release + [0] * (length - len(release))\n    if version.is_prerelease:\n        mapping = {'a': -3, 'b': -2, 'rc': -1}\n        val = -4\n        # version.pre can be None\n        if version.pre:\n            if version.pre[0] not in mapping:\n                warnings.warn(f'unknown prerelease version {version.pre[0]}, '\n                              'version checking may go wrong')\n            else:\n                val = mapping[version.pre[0]]\n            release.extend([val, version.pre[-1]])\n        else:\n            release.extend([val, 0])\n\n    elif version.is_postrelease:\n        release.extend([1, version.post])\n    else:\n        release.extend([0, 0])\n    return tuple(release)\n\n\ndef _minimal_ext_cmd(cmd):\n    # construct minimal environment\n    env = {}\n    for k in ['SYSTEMROOT', 'PATH', 'HOME']:\n        v = os.environ.get(k)\n        if v is not None:\n            env[k] = v\n    # LANGUAGE is used on win32\n    env['LANGUAGE'] = 'C'\n    env['LANG'] = 'C'\n    env['LC_ALL'] = 'C'\n    out = subprocess.Popen(\n        cmd, stdout=subprocess.PIPE, env=env).communicate()[0]\n    return out\n\n\ndef get_git_hash(fallback='unknown', digits=None):\n    \"\"\"Get the git hash of the current repo.\n\n    Args:\n        fallback (str, optional): The fallback string when git hash is\n            unavailable. Defaults to 'unknown'.\n        digits (int, optional): kept digits of the hash. Defaults to None,\n            meaning all digits are kept.\n\n    Returns:\n        str: Git commit hash.\n    \"\"\"\n\n    if digits is not None and not isinstance(digits, int):\n        raise TypeError('digits must be None or an integer')\n\n    try:\n        out = _minimal_ext_cmd(['git', 'rev-parse', 'HEAD'])\n        sha = out.strip().decode('ascii')\n        if digits is not None:\n            sha = sha[:digits]\n    except OSError:\n        sha = fallback\n\n    return sha\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/mmcv/utils/visual.py",
    "content": "import torch\nfrom torchvision.utils import make_grid\nimport torchvision\nimport matplotlib.pyplot as plt\nimport cv2\n\n\ndef convert_color(img_path):\n    plt.figure()\n    img = cv2.imread(img_path, cv2.IMREAD_GRAYSCALE)\n    plt.imsave(img_path, img, cmap=plt.get_cmap('viridis'))\n    plt.close()\n\n\ndef save_tensor(tensor, path, pad_value=254.0,):\n    print('save_tensor', path)\n    tensor = tensor.to(torch.float).detach().cpu()\n    if tensor.type() == 'torch.BoolTensor':\n        tensor = tensor*255\n    if len(tensor.shape) == 3:\n        tensor = tensor.unsqueeze(1)\n    tensor = make_grid(tensor, pad_value=pad_value, normalize=False).permute(1, 2, 0).numpy().copy()\n    torchvision.utils.save_image(torch.tensor(tensor).permute(2, 0, 1), path)\n    convert_color(path)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/requirements.txt",
    "content": "cython\nnumba==0.48.0 # In order to speed up\naddict\npackaging\nPillow\nmatplotlib\nregex;sys_platform=='win32'\npycocotools; platform_system == \"Linux\"\npycocotools-windows; platform_system == \"Windows\"\nprettytable\nsix\nterminaltables\nlyft_dataset_sdk\nnuscenes-devkit\nscikit-image\ntensorboard\ncityscapesscripts\nimagecorruptions\nscipy\nscikit-learn\nopen3d\nnetworkx\nipython\nopencv-python\nseaborn\nnumpy==1.20.0 # In order to adapt numba\n# metric related\neinops\ncasadi\ntorchmetrics\nmotmetrics==1.1.3 # Fixed\ntrimesh\n# pytest related\npytest\npytest-cov\npytest-runner\nyapf==0.40.1\nflake8\ntrimesh==2.35.39\nsimilaritymeasures\nlaspy==2.5.0\nlazrs==0.5.3\npy-trees==0.8.3\nsimple_watchdog_timer\ntransforms3d\ntabulate\nephem\ndictor"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/team_code/pid_controller.py",
    "content": "from collections import deque\nimport numpy as np\n\nclass PID(object):\n\tdef __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20):\n\t\tself._K_P = K_P\n\t\tself._K_I = K_I\n\t\tself._K_D = K_D\n\n\t\tself._window = deque([0 for _ in range(n)], maxlen=n)\n\t\tself._max = 0.0\n\t\tself._min = 0.0\n\n\tdef step(self, error):\n\t\tself._window.append(error)\n\t\tself._max = max(self._max, abs(error))\n\t\tself._min = -abs(self._max)\n\n\t\tif len(self._window) >= 2:\n\t\t\tintegral = np.mean(self._window)\n\t\t\tderivative = (self._window[-1] - self._window[-2])\n\t\telse:\n\t\t\tintegral = 0.0\n\t\t\tderivative = 0.0\n\n\t\treturn self._K_P * error + self._K_I * integral + self._K_D * derivative\n\n\n\nclass PIDController(object):\n    \n    def __init__(self, turn_KP=0.75, turn_KI=0.75, turn_KD=0.3, turn_n=40, speed_KP=5.0, speed_KI=0.5,speed_KD=1.0, speed_n = 40,max_throttle=0.75, brake_speed=0.4,brake_ratio=1.1, clip_delta=0.25, aim_dist=4.0, angle_thresh=0.3, dist_thresh=10):\n        \n        self.turn_controller = PID(K_P=turn_KP, K_I=turn_KI, K_D=turn_KD, n=turn_n)\n        self.speed_controller = PID(K_P=speed_KP, K_I=speed_KI, K_D=speed_KD, n=speed_n)\n        self.max_throttle = max_throttle\n        self.brake_speed = brake_speed\n        self.brake_ratio = brake_ratio\n        self.clip_delta = clip_delta\n        self.aim_dist = aim_dist\n        self.angle_thresh = angle_thresh\n        self.dist_thresh = dist_thresh\n\n    def control_pid(self, waypoints, speed, target):\n        ''' Predicts vehicle control with a PID controller.\n        Args:\n            waypoints (tensor): output of self.plan()\n            speed (tensor): speedometer input\n        '''\n\n        # iterate over vectors between predicted waypoints\n        num_pairs = len(waypoints) - 1\n        best_norm = 1e5\n        desired_speed = 0\n        aim = waypoints[0]\n        for i in range(num_pairs):\n            # magnitude of vectors, used for speed\n            desired_speed += np.linalg.norm(\n                    waypoints[i+1] - waypoints[i]) * 2.0 / num_pairs\n\n            # norm of vector midpoints, used for steering\n            norm = np.linalg.norm((waypoints[i+1] + waypoints[i]) / 2.0)\n            if abs(self.aim_dist-best_norm) > abs(self.aim_dist-norm):\n                aim = waypoints[i]\n                best_norm = norm\n\n        aim_last = waypoints[-1] - waypoints[-2]\n\n        angle = np.degrees(np.pi / 2 - np.arctan2(aim[1], aim[0])) / 90\n        angle_last = np.degrees(np.pi / 2 - np.arctan2(aim_last[1], aim_last[0])) / 90\n        angle_target = np.degrees(np.pi / 2 - np.arctan2(target[1], target[0])) / 90\n\n        # choice of point to aim for steering, removing outlier predictions\n        # use target point if it has a smaller angle or if error is large\n        # predicted point otherwise\n        # (reduces noise in eg. straight roads, helps with sudden turn commands)\n        use_target_to_aim = np.abs(angle_target) < np.abs(angle)\n        use_target_to_aim = use_target_to_aim or (np.abs(angle_target-angle_last) > self.angle_thresh and target[1] < self.dist_thresh)\n        if use_target_to_aim:\n            angle_final = angle_target\n        else:\n            angle_final = angle\n\n        steer = self.turn_controller.step(angle_final)\n        steer = np.clip(steer, -1.0, 1.0)\n\n        brake = desired_speed < self.brake_speed or (speed / desired_speed) > self.brake_ratio\n\n        delta = np.clip(desired_speed - speed, 0.0, self.clip_delta)\n        throttle = self.speed_controller.step(delta)\n        throttle = np.clip(throttle, 0.0, self.max_throttle)\n        throttle = throttle if not brake else 0.0\n\n        metadata = {\n            'speed': float(speed.astype(np.float64)),\n            'steer': float(steer),\n            'throttle': float(throttle),\n            'brake': float(brake),\n            'wp_4': tuple(waypoints[3].astype(np.float64)),\n            'wp_3': tuple(waypoints[2].astype(np.float64)),\n            'wp_2': tuple(waypoints[1].astype(np.float64)),\n            'wp_1': tuple(waypoints[0].astype(np.float64)),\n            'aim': tuple(aim.astype(np.float64)),\n            'target': tuple(target.astype(np.float64)),\n            'desired_speed': float(desired_speed.astype(np.float64)),\n            'angle': float(angle.astype(np.float64)),\n            'angle_last': float(angle_last.astype(np.float64)),\n            'angle_target': float(angle_target.astype(np.float64)),\n            'angle_final': float(angle_final.astype(np.float64)),\n            'delta': float(delta.astype(np.float64)),\n        }\n\n        return steer, throttle, brake, metadata"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/team_code/planner.py",
    "content": "import os\nfrom collections import deque\n\nimport numpy as np\nimport math\nEARTH_RADIUS_EQUA = 6378137.0\n\n\nDEBUG = int(os.environ.get('HAS_DISPLAY', 0))\n\n\nclass Plotter(object):\n    def __init__(self, size):\n        self.size = size\n        self.clear()\n        self.title = str(self.size)\n\n    def clear(self):\n        from PIL import Image, ImageDraw\n\n        self.img = Image.fromarray(np.zeros((self.size, self.size, 3), dtype=np.uint8))\n        self.draw = ImageDraw.Draw(self.img)\n\n    def dot(self, pos, node, color=(255, 255, 255), r=2):\n        x, y = 5.5 * (pos - node)\n        x += self.size / 2\n        y += self.size / 2\n\n        self.draw.ellipse((x-r, y-r, x+r, y+r), color)\n\n    def show(self):\n        if not DEBUG:\n            return\n\n        import cv2\n\n        cv2.imshow(self.title, cv2.cvtColor(np.array(self.img), cv2.COLOR_BGR2RGB))\n        cv2.waitKey(1)\n\n\nclass RoutePlanner(object):\n    def __init__(self, min_distance, max_distance, debug_size=256, lat_ref=42.0, lon_ref=2.0):\n        self.route = deque()\n        self.min_distance = min_distance\n        self.max_distance = max_distance\n\n        # self.mean = np.array([49.0, 8.0]) # for carla 9.9\n        # self.scale = np.array([111324.60662786, 73032.1570362]) # for carla 9.9\n        self.mean = np.array([0.0, 0.0]) # for carla 9.10\n        self.scale = np.array([111324.60662786, 111319.490945]) # for carla 9.10\n\n        self.debug = Plotter(debug_size)\n        # self.lat_ref, self.lon_ref = self._get_latlon_ref()\n        self.lat_ref = lat_ref\n        self.lon_ref = lon_ref\n\n    def set_route(self, global_plan, gps=False, global_plan_world = None):\n        self.route.clear()\n\n        if global_plan_world:\n            for (pos, cmd), (pos_word, _ )in zip(global_plan, global_plan_world):\n                if gps:\n                    pos = self.gps_to_location(np.array([pos['lat'], pos['lon']]))\n                    # pos -= self.mean\n                    # pos *= self.scale\n                else:\n                    pos = np.array([pos.location.x, pos.location.y])\n                    # pos -= self.mean\n                \n                self.route.append((pos, cmd, pos_word))\n        else:\n            for pos, cmd in global_plan:\n                if gps:\n                    pos = self.gps_to_location(np.array([pos['lat'], pos['lon']]))\n                    # pos -= self.mean\n                    # pos *= self.scale\n                else:\n                    pos = np.array([pos.location.x, pos.location.y])\n                    # pos -= self.mean\n\n                self.route.append((pos, cmd))\n\n    def run_step(self, gps):\n        self.debug.clear()\n\n        if len(self.route) == 1:\n            return self.route[0]\n\n        to_pop = 0\n        farthest_in_range = -np.inf\n        cumulative_distance = 0.0\n\n        for i in range(1, len(self.route)):\n            if cumulative_distance > self.max_distance:\n                break\n\n            cumulative_distance += np.linalg.norm(self.route[i][0] - self.route[i-1][0])\n            distance = np.linalg.norm(self.route[i][0] - gps)\n\n            if distance <= self.min_distance and distance > farthest_in_range:\n                farthest_in_range = distance\n                to_pop = i\n\n            r = 255 * int(distance > self.min_distance)\n            g = 255 * int(self.route[i][1].value == 4)\n            b = 255\n            self.debug.dot(gps, self.route[i][0], (r, g, b))\n\n        for _ in range(to_pop):\n            if len(self.route) > 2:\n                self.route.popleft()\n\n        self.debug.dot(gps, self.route[0][0], (0, 255, 0))\n        self.debug.dot(gps, self.route[1][0], (255, 0, 0))\n        self.debug.dot(gps, gps, (0, 0, 255))\n        self.debug.show()\n\n        return self.route[1]\n    \n    def gps_to_location(self, gps):\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/team_code/sparsedrive_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\n\nimport math\nfrom scipy.optimize import fsolve\nfrom pyquaternion import Quaternion\n\nfrom PIL import Image\nimport cv2\nimport numpy as np\nimport torch\nimport pickle\n\nimport carla\nfrom close_loop.leaderboard.team_code.pid_controller import PIDController\nfrom close_loop.leaderboard.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom mmcv import Config\nfrom mmcv.runner import load_checkpoint\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmdet.models import build_detector\nfrom mmdet.datasets.pipelines import Compose\n\n\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\nCAMERAS = ['CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_FRONT_LEFT', 'CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']\nframe_rate = 10\nresize_scale = 1\nsave_interval = 1\n\n\nlefthand_ego_to_lidar = np.array([[ 0, 1, 0, 0],\n                                  [ 1, 0, 0, 0],\n                                  [ 0, 0, 1, 0],\n                                  [ 0, 0, 0, 1]])\n\nleft2right = np.eye(4)\nleft2right[1,1] = -1\n\n\ndef get_entry_point():\n    return 'SparseDriveAgent'\n\nclass Clock():\n    def __init__(self):\n        self.time =  time.time()\n        self.verbose = False\n\n    def count(self, tag):\n        if self.verbose:\n            prev_time = self.time\n            self.time = time.time()\n            print(tag, self.time - prev_time)\n        else:\n            pass\n    \n\nclass SparseDriveAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file, gpu_rank, save_name):\n        self.save_name = save_name\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        self.cfg = cfg\n        if hasattr(cfg, \"plugin\"):\n            if cfg.plugin:\n                import importlib\n\n                if hasattr(cfg, \"plugin_dir\"):\n                    plugin_dir = cfg.plugin_dir\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split(\"/\")\n                    _module_path = _module_dir[0]\n\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + \".\" + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)\n                else:\n                    # import dir is the dirpath for the config file\n                    _module_dir = os.path.dirname(args.config)\n                    _module_dir = _module_dir.split(\"/\")\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + \".\" + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)\n  \n        self.gpu_rank = gpu_rank\n        model = build_detector(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model = MMDataParallel(model, device_ids=[gpu_rank])\n        self.device = next(self.model.module.parameters()).device\n        self.model.eval()\n        self.test_pipeline = []\n        for test_pipeline in cfg.test_pipeline:\n            if test_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.test_pipeline.append(test_pipeline)\n        self.test_pipeline = Compose(self.test_pipeline)\n        self.data_aug_conf = cfg.data_aug_conf\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n\n        self.save_path = pathlib.Path(f'close_loop_log/save/{save_name}')\n        self.save_path.mkdir(parents=True, exist_ok=True)\n        (self.save_path / 'rgb_front' ).mkdir(exist_ok=True)\n        (self.save_path / 'rgb_front_right').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_front_left').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_back').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_back_right').mkdir(exist_ok=True)\n        (self.save_path / 'rgb_back_left').mkdir(exist_ok=True)\n        (self.save_path / 'meta').mkdir(exist_ok=True)\n        (self.save_path / 'bev').mkdir(exist_ok=True)\n   \n        # self.lidar2img = {\n        # 'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n        #                       [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n        #                       [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n        #                       [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        # 'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n        #                             [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n        #                             [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n        #                             [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        # 'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n        #                            [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n        #                            [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n        #                            [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        # 'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n        #                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n        #                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, 1.61000000e+00],\n        #                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,1.00000000e+00]]),\n        # 'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n        #                           [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n        #                           [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n        #                           [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        # 'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n        #                             [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n        #                             [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n        #                             [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        # }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                                [ 0.  ,  0.  ,  1.  ,  0.  ],\n                                [ 0.  , -1.  ,  0.  ,  0.  ],\n                                [ 0.  , -0.24, -1.19,  1.  ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644,  0.        ,  0.81915204,  0.        ],\n                                    [-0.81915204,  0.        ,  0.57357644,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [ 0.22517331, -0.24      , -0.82909407,  1.        ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.        , -0.81915204,  0.        ],\n                                    [ 0.81915204,  0.        ,  0.57357644,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [-0.22517331, -0.24      , -0.82909407,  1.        ]]),\n        'CAM_BACK':np.array([[-1.00000000e+00,  0.00000000e+00,  1.22464680e-16, 0.00000000e+00],\n                            [-1.22464680e-16,  0.00000000e+00, -1.00000000e+00, 0.00000000e+00],\n                            [ 0.00000000e+00, -1.00000000e+00,  0.00000000e+00, 0.00000000e+00],\n                            [-1.97168135e-16, -2.40000000e-01, -1.61000000e+00, 1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.        , -0.93969262,  0.        ],\n                                    [ 0.93969262,  0.        , -0.34202014,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [-0.25388956, -0.24      , -0.49288953,  1.        ]]),\n        'CAM_BACK_RIGHT':np.array([[-0.34202014,  0.        ,  0.93969262,  0.        ],\n                                    [-0.93969262,  0.        , -0.34202014,  0.        ],\n                                    [ 0.        , -1.        ,  0.        ,  0.        ],\n                                    [ 0.25388956, -0.24      , -0.49288953,  1.        ]])\n        }\n        self.cam_intrinsic = {\n        'CAM_FRONT': np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                            [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                            [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_FRONT_RIGHT': np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_FRONT_LEFT': np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[560.16603057,   0.        , 800.        ],\n                            [  0.        , 560.16603057, 450.        ],\n                            [  0.        ,   0.        ,   1.        ]]),\n        'CAM_BACK_LEFT':np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK_RIGHT':np.array([[1.14251841e+03, 0.00000000e+00, 8.00000000e+02],\n                                    [0.00000000e+00, 1.14251841e+03, 4.50000000e+02],\n                                    [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]),\n        }\n\n        self.lidar2img = {}\n        for key, value in self.cam_intrinsic.items():\n            intrinsic = value * resize_scale\n            self.cam_intrinsic[key] = intrinsic\n\n            viewpad = np.eye(4)\n            viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n            lidar2cam = self.lidar2cam[key]\n            self.lidar2img[key] = viewpad @ lidar2cam.T\n\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n        self.clock = Clock() \n\n        self.stuck_detector = 0\n        self.forced_move = 0\n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n\n    def sensors(self):\n        W = 1600 * resize_scale\n        H = 900 * resize_scale\n\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': W, 'height': H, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': W, 'height': H, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n                # lidar\n                {   'type': 'sensor.lidar.ray_cast',\n                    'x': -0.39, 'y': 0.0, 'z': 1.84,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 85,\n                    'rotation_frequency': 10,\n                    'channels': 64,\n                    'points_per_second': 600000,\n                    'dropoff_general_rate': 0.0,\n                    'dropoff_intensity_limit': 0.0,\n                    'dropoff_zero_intensity': 0.0,\n                    'id': 'LIDAR_TOP'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in CAMERAS:\n            img = input_data[cam][1][:, :, :3]\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n\n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        self.clock.count(\"start\")\n        tick_data = self.tick(input_data)\n        self.clock.count(\"tick\")\n\n        results = {}\n        results['timestamp'] = self.step / frame_rate\n        results['img'] = []\n        results['lidar2img'] = []\n  \n        for cam in CAMERAS:\n            results['img'].append(tick_data['imgs'][cam])\n            results['lidar2img'].append(self.lidar2img[cam])\n        \n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        \n        lidar = CarlaDataProvider.get_world().get_actors().filter('*sensor.lidar.ray_cast*')[0]\n        world2lidar = lidar.get_transform().get_inverse_matrix()\n        world2lidar = lefthand_ego_to_lidar @ world2lidar @ left2right\n        lidar2global =  self.invert_pose(world2lidar)\n        results['lidar2global'] = lidar2global\n\n        ego_status = np.zeros(10, dtype=np.float32)\n        ego_status[:3] = np.array([tick_data['acceleration'][0],-tick_data['acceleration'][1],tick_data['acceleration'][2]])\n        ego_status[3:6] = -np.array(tick_data['angular_velocity'])\n        ego_status[6:9] = np.array([tick_data['speed'],0,0])\n        results[\"ego_status\"] = ego_status\n        \n        if self.cfg.num_cmd > 1:\n            command = tick_data['command_near']\n            if command < 0:\n                command = 4\n            command -= 1\n            command_onehot = np.zeros(6)\n            command_onehot[command] = 1\n        else:\n            command = 0\n            command_onehot = np.array([0, ])\n        # import ipdb; ipdb.set_trace()\n        results['gt_ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n        results['tp_near'] = local_command_xy\n        results['tp_far'] = local_command_xy\n\n        # ego2world = np.eye(4)\n        # ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        # ego2world[0:2,3] = can_bus[0:2]\n        # lidar2global = ego2world @ self.lidar2ego\n        # results['lidar2global'] = lidar2global\n\n        stacked_img = np.stack(results['img'], axis=-1)\n        results['img_shape'] = stacked_img.shape\n        results['ori_shape'] = stacked_img.shape\n        results['pad_shape'] = stacked_img.shape\n\n        aug_config = self.get_augmentation()\n        results[\"aug_config\"] = aug_config\n        results = self.test_pipeline(results)\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data):\n                    data = data.to(self.device)\n        self.clock.count(\"data\")\n        output_data_batch = self.model(**input_data_batch)\n        self.clock.count(\"model\")\n        out_truck = output_data_batch[0]['img_bbox']['final_planning'].numpy()\n        \n        ## creep\n        is_stuck = False\n        if(self.stuck_detector > 150 and self.forced_move < 15):\n            print(\"Detected agent being stuck. Move for frame: \", self.forced_move)\n            is_stuck = True\n            self.forced_move += 1\n\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy, is_stuck)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        if is_stuck:\n            steer_traj *= 0.5\n\n        if(tick_data['speed'] < 0.1): # 0.1 is just an arbitrary low number to threshhold when the car is stopped\n            self.stuck_detector += 1\n\n        elif(tick_data['speed'] > 0.1 and is_stuck == False):\n            self.stuck_detector = 0\n            self.forced_move    = 0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['local_command_xy'] = local_command_xy\n        self.pid_metadata['result'] = output_data_batch[0]['img_bbox']\n\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n\n        if self.step % save_interval == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n\n        return control\n\n    def save(self, tick_data):\n        frame = self.step // save_interval\n\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n\n        data = {}\n\n        cmd = np.zeros(6)\n        cmd[self.pid_metadata[\"command\"]] = 1\n        data[\"gt_ego_fut_cmd\"] = cmd\n        data[\"tp_near\"] = self.pid_metadata[\"local_command_xy\"]\n\n        data[\"img_filename\"] = [\n            self.save_path / 'rgb_front' / ('%04d.png' % frame),\n            self.save_path / 'rgb_front_right' / ('%04d.png' % frame),\n            self.save_path / 'rgb_front_left' / ('%04d.png' % frame),\n            self.save_path / 'rgb_back' / ('%04d.png' % frame),\n            self.save_path / 'rgb_back_left' / ('%04d.png' % frame),\n            self.save_path / 'rgb_back_right' / ('%04d.png' % frame),\n        ]\n\n        data['lidar2cam'] = []\n        data['cam_intrinsic'] = []\n        for cam in CAMERAS:\n            data['lidar2cam'].append(self.lidar2cam[cam])\n            data['cam_intrinsic'].append(self.cam_intrinsic[cam])\n        \n        self.pid_metadata[\"data\"] = data\n            \n        outfile = open(self.save_path / 'meta' / ('%04d.pkl' % frame), 'wb')\n        pickle.dump(self.pid_metadata, outfile)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n\n    def get_augmentation(self):\n        H = 900 * resize_scale\n        W = 1600 * resize_scale\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        resize = max(fH / H, fW / W)\n        resize_dims = (int(W * resize), int(H * resize))\n        newW, newH = resize_dims\n        crop_h = (\n            int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n            - fH\n        )\n        crop_w = int(max(0, newW - fW) / 2)\n        crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n        flip = False\n        rotate = 0\n        rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def invert_pose(self, pose):\n        inv_pose = np.eye(4)\n        inv_pose[:3, :3] = np.transpose(pose[:3, :3])\n        inv_pose[:3, -1] = - inv_pose[:3, :3] @ pose[:3, -1]\n        return inv_pose\n\ndef draw(input, step, cfg):\n    img = input['img'].data[0][0, 0]\n    projection_mat = input['projection_mat'].data[0, 0]\n    key_points = torch.tensor([0, 10, -1.8])\n    pts_extend = torch.cat(\n        [key_points, torch.ones_like(key_points[..., :1])], dim=-1\n    )\n    points_2d = torch.matmul(\n        projection_mat, pts_extend[..., None]\n    ).squeeze(-1)\n    points_2d = points_2d[..., :2] / torch.clamp(\n        points_2d[..., 2:3], min=1e-5\n    )\n    print(points_2d[0]/img.shape[2], points_2d[1]/img.shape[1])\n    points_2d = points_2d.numpy()\n    img = img.numpy().transpose(1, 2, 0).astype(np.uint8)\n    img = img.copy()\n    cv2.circle(img, (int(points_2d[0]), int(points_2d[1])), 5, (0, 0, 255))\n    cv2.imwrite(f'vis3/{resize_scale}_{cfg.data_aug_conf[\"final_dim\"]}{step}.jpg', img)"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/team_code/uniad_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom Bench2DriveZoo.team_code.pid_controller import PIDController\nfrom Bench2DriveZoo.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\nfrom scipy.optimize import fsolve\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\ndef get_entry_point():\n    return 'UniadAgent'\n\nclass UniadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steers = deque()\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        cfg.model['motion_head']['anchor_info_path'] = os.path.join('Bench2DriveZoo',cfg.model['motion_head']['anchor_info_path'])\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.last_steers = deque()\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            # string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string = self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        # write extrinsics directly\n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                                  [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                                  [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                                 [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n          'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n          'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                       [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n         'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                                 [ 0.  ,  0.  , -1.  , -0.24],\n                                 [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                      [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n          'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n    def _init(self):\n        \n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0        \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n                \n            ]\n        \n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n    \n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n  \n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n  \n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n  \n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        out_truck =  output_data_batch[0]['planning']['result_planning']['sdc_traj'][0].cpu().numpy()\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n        if tick_data['speed']>5:\n            throttle_traj = 0\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)\n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n        if SAVE_PATH is not None and self.step % 1 == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        return control\n\n    def save(self, tick_data):\n        frame = self.step // 10\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/team_code/vad_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nfrom scipy.optimize import fsolve\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom team_code.pid_controller import PIDController\nfrom team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,\n                        wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\n\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\n\ndef get_entry_point():\n    return 'VadAgent'\n\n\nclass VadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string += self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                              [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                              [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                              [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                    [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                              [ 0.  ,  0.  , -1.  , -0.24],\n                              [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n  \n  \n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n  \n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        \n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = can_bus[0:2].copy()\n        ego_lcf_feat[2:4] = can_bus[10:12].copy()\n        ego_lcf_feat[4] = rotation[-1]\n        ego_lcf_feat[5] = 4.89238167\n        ego_lcf_feat[6] = 1.83671331\n        ego_lcf_feat[7] = np.sqrt(can_bus[0]**2+can_bus[1]**2)\n\n        if len(self.prev_control_cache)<10:\n            ego_lcf_feat[8] = 0\n        else:\n            ego_lcf_feat[8] = self.prev_control_cache[0].steer\n\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n        command_onehot = np.zeros(6)\n        command_onehot[command] = 1\n        results['ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        #import pdb;pdb.set_trace()\n        #all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds_refine'].cpu().numpy()\n        all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds_refine'].cpu().numpy() # [6,6,2]\n        all_cls = output_data_batch[0]['pts_bbox']['ego_fut_classification_refine'].reshape(6,6,-1).sum(dim=-1)\n        all_cls = all_cls.cpu().numpy()\n        nnums = np.arange(all_out_truck_d1.shape[0])\n        all_out_truck_d1 = all_out_truck_d1[nnums,all_cls.argmax(-1), :, :]\n        #all_cls = all_cls.reshape(6,6,-1).sum(dim=-1)\n        #import pdb;pdb.set_trace()\n        all_out_truck =  np.cumsum(all_out_truck_d1,axis=1)\n        out_truck = all_out_truck[command]\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['all_plan'] = all_out_truck.tolist()\n\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n        if SAVE_PATH is not None and self.step % 1 == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n        return control\n\n\n    def save(self, tick_data):\n        frame = self.step // 10\n\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n\n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/Bench2DriveZoo/team_code/vad_b2d_agent_visualize.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nfrom scipy.optimize import fsolve\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom Bench2DriveZoo.team_code.pid_controller import PIDController\nfrom Bench2DriveZoo.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,\n                        wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\nfrom scipy.interpolate import splprep, splev\nimport copy\nimport seaborn as sns\n\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\ndef float_to_uint8_color(float_clr):\n    assert all([c >= 0. for c in float_clr])\n    assert all([c <= 1. for c in float_clr])\n    return [int(c * 255.) for c in float_clr]\n\n\nCOLORS = [float_to_uint8_color(clr) for clr in sns.color_palette(\"bright\", n_colors=10)]\nCOLORMAP = OrderedDict({\n    6: COLORS[8],  # yellow\n    4: COLORS[8],\n    3: COLORS[0],  # blue\n    1: COLORS[6],  # pink\n    0: COLORS[2],  # green\n    8: COLORS[7],  # gray\n    7: COLORS[1],  # orange\n    5: COLORS[3],  # red\n    2: COLORS[5],  # brown\n})\n\ndef get_entry_point():\n    return 'VadAgent'\n\n\nclass VadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string += self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                              [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                              [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                              [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                    [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                              [ 0.  ,  0.  , -1.  , -0.24],\n                              [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        # topdown_extrinsics =  np.array([[0.0, -0.0, -1.0, 50.0], \n        #                                 [0.0,  1.0, -0.0,  0.0], \n        #                                 [1.0, -0.0,  0.0, -0.0], \n        #                                 [0.0,  0.0,  0.0,  1.0]])\n        # unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        #unreal2cam @ topdown_extrinsics\n        self.coor2topdown = np.array([[1.0,  0.0,  0.0,  0.0], \n                                      [0.0, -1.0,  0.0,  0.0], \n                                      [0.0,  0.0, -1.0, 50.0], \n                                      [0.0,  0.0,  0.0,  1.0]])\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown         \n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n  \n  \n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n  \n        if math.isnan(compass): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = can_bus[0:2].copy()\n        ego_lcf_feat[2:4] = can_bus[10:12].copy()\n        ego_lcf_feat[4] = rotation[-1]\n        ego_lcf_feat[5] = 4.89238167\n        ego_lcf_feat[6] = 1.83671331\n        ego_lcf_feat[7] = np.sqrt(can_bus[0]**2+can_bus[1]**2)\n\n        if len(self.prev_control_cache)<10:\n            ego_lcf_feat[8] = 0\n        else:\n            ego_lcf_feat[8] = self.prev_control_cache[0].steer\n\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n        command_onehot = np.zeros(6)\n        command_onehot[command] = 1\n        results['ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds'].cpu().numpy()\n        all_out_truck =  np.cumsum(all_out_truck_d1,axis=1)\n        out_truck = all_out_truck[command]\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['all_plan'] = all_out_truck.tolist()\n\n        #if SAVE_PATH is not None and self.step % 10 == 0:\n        self.save(tick_data,out_truck,output_data_batch)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n        return control\n\n\n    def save(self, tick_data,ego_traj,result=None):\n        frame = self.step\n        imgs_with_box = {}\n        for cam, img in tick_data['imgs'].items():\n            imgs_with_box[cam] = self.draw_lidar_bbox3d_on_img(result[0]['pts_bbox']['boxes_3d'], tick_data['imgs'][cam], self.lidar2img[cam], scores=result[0]['pts_bbox']['scores_3d'],labels=result[0]['pts_bbox']['labels_3d'],canvas_size=(900,1600))\n        imgs_with_box['bev'] = self.draw_lidar_bbox3d_on_img(result[0]['pts_bbox']['boxes_3d'], tick_data['bev'], self.coor2topdown, scores=result[0]['pts_bbox']['scores_3d'],labels=result[0]['pts_bbox']['labels_3d'],trajs=result[0]['pts_bbox']['trajs_3d'],canvas_size=(512,512))\n        imgs_with_box['bev'] = self.draw_traj_bev(ego_traj, imgs_with_box['bev'],is_ego=True)\n        imgs_with_box['CAM_FRONT'] = self.draw_traj(ego_traj, imgs_with_box['CAM_FRONT'])\n        for cam, img in imgs_with_box.items():\n            Image.fromarray(img).save(self.save_path / str.lower(cam).replace('cam','rgb') / ('%04d.png' % frame))   \n                \n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n        \n    def draw_traj(self, traj, raw_img,canvas_size=(900,1600),thickness=3,is_ego=True,hue_start=120,hue_end=80):\n        line = traj\n        lidar2img_rt = self.lidar2img['CAM_FRONT']\n        img = raw_img.copy()\n        pts_4d = np.stack([line[:,0],line[:,1],np.ones((line.shape[0]))*(-1.84),np.ones((line.shape[0]))])\n        pts_2d = ((lidar2img_rt @ pts_4d).T)\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        mask = (pts_2d[:, 0]>0) & (pts_2d[:, 0]<canvas_size[1]) & (pts_2d[:, 1]>0) & (pts_2d[:, 1]<canvas_size[0])\n        if not mask.any():\n            return img\n        pts_2d = pts_2d[mask,0:2]\n        if is_ego:\n            pts_2d = np.concatenate([np.array([[800,900]]),pts_2d],axis=0)\n        try:\n            tck, u = splprep([pts_2d[:, 0], pts_2d[:, 1]], s=0)\n        except:\n            return img\n        unew = np.linspace(0, 1, 100)\n        smoothed_pts = np.stack(splev(unew, tck)).astype(int).T\n        \n        num_points = len(smoothed_pts)\n        for i in range(num_points-1):\n            hue = hue_start + (hue_end - hue_start) * (i / num_points)\n            hsv_color = np.array([hue, 255, 255], dtype=np.uint8)\n            rgb_color = cv2.cvtColor(hsv_color[np.newaxis, np.newaxis, :], cv2.COLOR_HSV2RGB).reshape(-1)\n            rgb_color_tuple = (float(rgb_color[0]),float(rgb_color[1]),float(rgb_color[2]))\n            cv2.line(img,(smoothed_pts[i,0],smoothed_pts[i,1]),(smoothed_pts[i+1,0],smoothed_pts[i+1,1]),color=rgb_color_tuple, thickness=thickness)  \n      \n        return img\n\n\n\n    def draw_traj_bev(self, traj, raw_img,canvas_size=(512,512),thickness=3,is_ego=False,hue_start=120,hue_end=80):\n        if is_ego:\n            line = np.concatenate([np.zeros((1,2)),traj],axis=0)\n        else:\n            line = traj\n        img = raw_img.copy()        \n        pts_4d = np.stack([line[:,0],line[:,1],np.zeros((line.shape[0])),np.ones((line.shape[0]))])\n        pts_2d = (self.coor2topdown @ pts_4d).T\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        mask = (pts_2d[:, 0]>0) & (pts_2d[:, 0]<canvas_size[1]) & (pts_2d[:, 1]>0) & (pts_2d[:, 1]<canvas_size[0])\n        if not mask.any():\n            return img\n        pts_2d = pts_2d[mask,0:2]\n        try:\n            tck, u = splprep([pts_2d[:, 0], pts_2d[:, 1]], s=0)\n        except:\n            return img\n        unew = np.linspace(0, 1, 100)\n        smoothed_pts = np.stack(splev(unew, tck)).astype(int).T\n\n        num_points = len(smoothed_pts)\n        for i in range(num_points-1):\n            hue = hue_start + (hue_end - hue_start) * (i / num_points)\n            hsv_color = np.array([hue, 255, 255], dtype=np.uint8)\n            rgb_color = cv2.cvtColor(hsv_color[np.newaxis, np.newaxis, :], cv2.COLOR_HSV2RGB).reshape(-1)\n            rgb_color_tuple = (float(rgb_color[0]),float(rgb_color[1]),float(rgb_color[2]))\n            if smoothed_pts[i,0]>0 and smoothed_pts[i,0]<canvas_size[1] and smoothed_pts[i,1]>0 and smoothed_pts[i,1]<canvas_size[0]:\n                cv2.line(img,(smoothed_pts[i,0],smoothed_pts[i,1]),(smoothed_pts[i+1,0],smoothed_pts[i+1,1]),color=rgb_color_tuple, thickness=thickness)   \n            elif i==0:\n                break\n        return img\n    \n    def draw_lidar_bbox3d_on_img(self,bboxes3d,raw_img,lidar2img_rt,canvas_size=(900,1600),img_metas=None,scores=None,labels=None,trajs=None,color=(0, 255, 0),thickness=1):\n        img = raw_img.copy()\n        bboxes3d_numpy = bboxes3d.tensor.cpu().numpy()\n        if len(bboxes3d_numpy) == 0:\n            return img\n        corners_3d = bboxes3d.corners\n        num_bbox = corners_3d.shape[0]\n        pts_4d = np.concatenate(\n            [corners_3d.reshape(-1, 3),\n            np.ones((num_bbox * 8, 1))], axis=-1)\n        lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n        if isinstance(lidar2img_rt, torch.Tensor):\n            lidar2img_rt = lidar2img_rt.cpu().numpy()\n        if isinstance(scores, torch.Tensor):\n            scores = scores.cpu().numpy()            \n        if isinstance(labels, torch.Tensor):\n            labels = labels.cpu().numpy()            \n            \n        pts_2d = (lidar2img_rt @ pts_4d.T).T\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)\n        depth = pts_2d[..., 2].reshape(num_bbox, 8)\n        mask1 = ((imgfov_pts_2d[:,:,0]>-1e5) & (imgfov_pts_2d[:,:,0]<1e5)&(imgfov_pts_2d[:,:,1]>-1e5) & (imgfov_pts_2d[:,:,1]<1e5) & (depth > -1) ).all(-1)\n        mask2 = (imgfov_pts_2d.reshape(num_bbox,16).max(axis=-1) - imgfov_pts_2d.reshape(num_bbox,16).min(axis=-1))< 2000\n        mask = mask1 & mask2\n        if scores is not None:\n            mask3 = (scores>=0.3)\n            mask = mask & mask3\n            \n        if not mask.any():\n            return img\n\n        scores = scores[mask] if scores is not None else None\n        labels = labels[mask] if labels is not None else None\n        \n        imgfov_pts_2d = imgfov_pts_2d[mask]\n        num_bbox = mask.sum()\n        if trajs is not None:\n            \n            trajs = trajs[mask]\n            agent_boxes = bboxes3d_numpy[mask]\n            for traj,agent_box,label in zip(trajs,agent_boxes,labels):\n                if label in [0,1,2,3,7]:\n                    for i in range(6):\n                        traj1 = np.concatenate([np.zeros((1,2)),traj[i].reshape(6,2)],axis=0)\n                        traj1 = np.cumsum(traj1,axis=0) + agent_box[None,0:2]\n                        #traj1 = (r_m @ traj1.T).T + agent_box[None,0:2]\n                        if canvas_size==(900,1600):\n                            img = self.draw_traj(traj1,img,hue_start=0,hue_end=20)\n                        else:\n                            img = self.draw_traj_bev(traj1,img,hue_start=0,hue_end=20)\n\n        return self.plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, scores, labels, color, thickness,bev=(canvas_size!=(900,1600))) \n    \n    \n\n    \n    def plot_rect3d_on_img(self,img,num_rects,rect_corners,scores=None,labels=None,color=(0, 255, 0),thickness=1,bev=False):\n        line_indices = ((0, 1), (0, 3), (0, 4), (1, 2), (1, 5), (3, 2), (3, 7),\n                        (4, 5), (4, 7), (2, 6), (5, 6), (6, 7))\n        if bev:\n            line_indices = ((0, 3), (3, 7),(4, 7), (0, 4))\n        for i in range(num_rects):\n            c = COLORMAP[labels[i]]\n            thinck = 2\n            corners = rect_corners[i].astype(np.int)\n            # if scores is not None:\n            #     cv2.putText(img, \"{:.2f}\".format(scores[i]), corners[0], cv2.FONT_HERSHEY_SIMPLEX, 0.3, (0,0,0), 1)\n            if scores[i] < 0.3:\n                continue\n                #     c=(255,255,255)\n                #     thinck=1\n            for start, end in line_indices:\n                cv2.line(img, (corners[start, 0], corners[start, 1]),\n                        (corners[end, 0], corners[end, 1]), c, thinck,\n                        cv2.LINE_AA)\n        return img.astype(np.uint8)\n    \n\n        \n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/docs/anno.md",
    "content": "\n# Detailed explanation of annotation information and visualization of datasets.\n\n## Get Started\n- Most of recorded data is **directly from CARLA API** to avoid information loss. The data collection code is in [tools/data_collect.py](../tools/data_collect.py). We suggest reading it aided by [CARLA official Python API docs](https://carla.readthedocs.io/en/latest/python_api/).\n- Keep in mind that the recorded data might be **in different coordinate systems** (World, Ego, LiDAR, Compass). We provide a [visualization code](../tools/visualize.py) for you to get familiar with these coordinate systems. You might refer to [this explanations](https://github.com/autonomousvision/carla_garage/blob/main/docs/coordinate_systems.md) (awsome codebase!).\n- For fair/legal comparision, make sure your model only use the information from [**allowed sensors**](https://leaderboard.carla.org/#sensors-track) + high level command as input. Other information is only allowed to use during training.\n- Note that sometimes **CARLA API could be buggy**, we record some known issues below:\n  - The speed value of all pedestrians are 0. You might want to calculate by youself.\n  - The returned value of the sensor Speedometer might be None. The yaw value could be None as well. You might want to deal with it by setting all None to 0.\n  - Some stop signs in CARLA are on the ground and thus there is no bounding box. However, we record all stop signs in the *anno* file with rectangles to denote their [trigger volume](https://carla.readthedocs.io/en/latest/python_api/#carla.TrafficSign.trigger_volume).\n  - All trigger volumes' *rotation* attribute is relative to the parent actor (traffic lights or stop signs). Thus, **you need to add the parent actors' rotation to it** to obtain the global *rotation*.  \n  - Static vehicles' (state==\"static\") rotation and location is wrong due to CARLA API bugs. Thus, we suggest only use attribute **center** and **extent** to obtain the local 3D bounding boxes. Use the inverse of **world2vehicle** to obtain the vehicle's bounding box in the world coordinate system. \n  - The extent in CARLA means **half** of the Height, Width, Length!\n  - The HD-Map of each town is in https://hf-mirror.com/datasets/rethinklab/Bench2Drive-Map. The data structure is in the following section.\n\n## Data\n[CARLAs docs about sensors](https://carla.readthedocs.io/en/latest/ref_sensors/)\n- RGB image * 6:\n    - JPG compressed. Quality 20.\n    - [Related code](https://github.com/Thinklab-SJTU/Bench2Drive/blob/main/tools/data_collect.py#L743-L749)\n    - The position and FoV is similar to [nuScenes](https://www.nuscenes.org/).\n    - **Since JPG is lossy compression, you might need to compress the image from sensors during inference to avoid train-val gap!**\n- anno:\n    - Use GZIP to compress json file.\n    - [Related code](https://github.com/Thinklab-SJTU/Bench2Drive/blob/main/tools/data_collect.py#L820-L821)\n- LiDAR*1\n    - Use a specialized algorithm called laszip to compress LiDAR point clouds.\n    - [Related code](https://github.com/Thinklab-SJTU/Bench2Drive/blob/main/tools/data_collect.py#L779-L790)\n- Radar*5\n    - Use h5py format and use GZIP to compress.\n    - The position is similar to [nuScenes](https://www.nuscenes.org/).\n    - [Related code](https://github.com/Thinklab-SJTU/Bench2Drive/blob/main/tools/data_collect.py#L772-L777)\n- Depth, Semantic, Instance\n    - Please refer to CARLA official docs about sensors about obtaining the labels.\n    - Their sensors' position is exactly the same as RGB Cameras'.\n- HD-Map\n    - Data is generated by [code](https://github.com/Thinklab-SJTU/Bench2Drive/blob/main/tools/gen_hdmap.py)\n\n## How to Visualize?\n\n``` bash\ncd tools\npython visualize.py -f FILE_PATH -m LANEMARK_PATH\n# for example, \n# FILE_PATH is NonSignalizedJunctionLeftTurnEnterFlow/Town13_723\n# LANEMARK_PATH is maps/Town13_lanemarkings.npz\n```\n\n## Data structure\n\n``` python\n- scenario_name/\n    - Town[id]_weather[id]_route[id]/\n        - anno\n            - 00000.json.gz\n        - camera\n            - depth_back\n                - 00000.png\n            - depth_back\n                - 00000.png\n            - depth_back_left\n                - 00000.png\n            - depth_back_right\n                - 00000.png\n            - depth_front\n                - 00000.png\n            - depth_front_left\n                - 00000.png\n            - depth_front_right\n                - 00000.png\n            - instance_back\n                - 00000.png\n            - instance_back_left\n                - 00000.png\n            - instance_back_right\n                - 00000.png\n            - instance_front\n                - 00000.png\n            - instance_front_left\n                - 00000.png\n            - instance_front_right\n                - 00000.png\n            - rgb_back\n                - 00000.jpg\n            - rgb_back_left\n                - 00000.jpg\n            - rgb_back_right\n                - 00000.jpg\n            - rgb_front\n                - 00000.jpg\n            - rgb_front_left\n                - 00000.jpg\n            - rgb_front_right\n                - 00000.jpg\n            - rgb_top_down\n                - 00000.jpg\n            - semantic_back\n                - 00000.png\n            - semantic_back_left\n                - 00000.png\n            - semantic_back_right\n                - 00000.png\n            - semantic_front\n            - semantic_front_left\n                - 00000.png\n            - semantic_front_right\n                - 00000.png\n        - expert_assessment\n            - 00000.npz\n        - lidar\n            - 00000.laz\n        - radar\n            - 00000.h5\n```\n\n## Anno Structure\n**TODO: For all items, tell which sensors/CARLA API it is from and which lines of code in the sensor agent!!! Especially for those from sensors to make sure people can make legal agent.**\n``` shell\n    - x # current position in world coordinates.\n    - y # current position in world coordinates.\n    - throttle\n    - steer\n    - brake\n    - reverse\n    - theta\n    - speed\n    - x_command_far # farther waypoint x in world coordinates.\n    - y_command_far # farther waypoint y in world coordinates.\n    - command_far #  the command to farther waypoint.\n    - x_command_near # nearby waypoint x in world coordinates.\n    - y_command_near # nearby waypoint y in world coordinates.\n    - command_near # the command to nearby waypoint.\n    - should_brake # inherit from TCP\n    - only_ap_brake # inherit from TCP\n    - x_target # target waypoint \n    - y_target # target waypoint \n    - next_command # next command\n    - weather\n    - acceleration\n    - angular_velocity\n    - sensors\n        - CAM_XXXX\n            - location # Location coordinates of the CAM_XXXX(x,y,z in world coordinates)\n            - rotation # Orientation of the CAM_XXXX in world coordinates.\n            - intrinsic # The intrinsic of camera.\n            - world2cam # Transformation from world coordinates to camera coordinates\n            - cam2ego # Transformation from camera coordinates to ego_vehicle coordinates\n            - fov\n            - image_size_x # 1600\n            - image_size_y # 900\n        - RADAR_XXXX\n            - location # Location coordinates of the RADAR_XXXX(x,y,z in world coordinates)\n            - rotation # Orientation of the RADAR_XXXX in world coordinates.\n            - world2radar # Transformation from world coordinates to radar coordinates\n            - radar2ego # Transformation from radar coordinates to ego_vehicle coordinates\n        - LIDAR_TOP\n            - location # Location coordinates of the LIDAR_TOP(x,y,z in world coordinates)\n            - rotation  # Orientation of the LIDAR_TOP in world coordinates.\n            - world2lidar # Transformation from world coordinates to lidar coordinates\n            - lidar2ego # Transformation from lidar coordinates to ego_vehicle coordinates\n    - bounding_boxes\n        - ego_vehicle \n            - class: 'vehicle'\n            - id # unique actor id\n            - type_id # Type name for the ego_vehicle\n            - base_type # The ego_vehicle's base type in CARLA.\n            - location # Location coordinates of the ego_vehicle(x,y,z in world coordinates)\n            - rotation # Orientation of the ego_vehicle in world coordinates.\n            - bbx_loc # Bounding box location(x,y,z in ego coordinates)\n            - center # Center point of the ego_vehicle in world coordinates.\n            - extent # Extension length of ego_vehicle in world coordinates.\n            - world_cord # Bounding box verts coordinates in world coordinates.\n            - semantic_tags # Descriptive tags related to the vehicle.\n            - color # The color of ego_vehicle.\n            - speed\n            - brake\n            - road_id # Road identifier where the ego_vehicle is located\n            - lane_id # Lane identifier for the lane affected by the ego_vehicle\n            - section_id # Section of the road where the ego_vehicle is located\n            - world2ego # Transformation from world coordinates to ego_vehicle coordinates\n        - vehicle\n            - class: 'vehicle'\n            - state # dynamic or static\n            - id # Unique identifier for the vehicle\n            - location # Location coordinates of the vehicle(x,y,z in world coordinates)\n            - rotation # Orientation of the vehicle in world coordinates.\n            - bbx_loc # Bounding box location(x,y,z in ego coordinates)\n            - center # Center point of the vehicle in world coordinates.\n            - extent # Extension length of vehicle in world coordinates.\n            - world_cord # Bounding box verts coordinates in world coordinates.\n            - semantic_tags # Descriptive tags related to the vehicle.\n            - type_id # Type name for the vehicle.\n            - color # The color of vehicle.\n            - base_type # The vehicle's base type in CARLA.\n            - num_points # num of LiDAR point cloud.\n            - distance # Distance of the vehicle from the ego vehicle.\n            - speed\n            - brake\n            - light_state # The state of vehicle.\n            - road_id # Road identifier where the vehicle is located\n            - lane_id # Lane identifier for the lane affected by the vehicle\n            - section_id # Section of the road where the vehicle is located\n            - world2vehicle # Transformation from world coordinates to vehicle coordinates\n\n        - traffic_light\n            - class: 'traffic_light'\n            - id # Unique identifier for the traffic light\n            - location # Location coordinates of the traffic light(x,y,z in world coordinates)\n            - rotation # Orientation of the traffic light in world coordinates.\n            - center # Center point of the traffic light in world coordinates.\n            - extent # Extension length of traffic light in world coordinates.\n            - semantic_tags # Descriptive tags related to the traffic light.\n            - type_id # Type name for the traffic light\n            - distance # Distance of the traffic light from the ego vehicle\n            - state # The state(color) of traffic light.\n            - affects_ego # Whether the traffic light affects the ego vehicle\n            - trigger_volume_location # Location for the trigger area for specific light\n            - trigger_volume_rotation # Orientation of the trigger volume for specific light\n            - trigger_volume_extent # Extension length of the trigger volume for specific light\n            - road_id # Road identifier where the traffic light is located\n            - lane_id # Lane identifier for the lane affected by the traffic light\n            - section_id # Section of the road where the traffic light is located\n\n        - traffic_sign\n            - class: 'traffic_sign'\n            - id # Unique identifier for the traffic sign\n            - location # Location coordinates of the traffic sign(x,y,z in world coordinates)\n            - rotation # Orientation of the traffic sign in world coordinates.\n            - center # Center point of the traffic sign in world coordinates.\n            - extent # Extension length of traffic sign in world coordinates.\n            - semantic_tags # Descriptive tags related to the traffic sign.\n            - type_id # Type name for the traffic sign\n            - distance # Distance of the traffic sign from the ego vehicle\n            - affects_ego # Whether the traffic sign affects the ego vehicle\n            - road_id # Road identifier where the traffic sign is located\n            - lane_id # Lane identifier for the lane affected by the traffic sign\n            - section_id # Section of the road where the traffic sign is located\n            - world2sign # Transformation from world coordinates to sign coordinates\n\n            # for stop sign/ speed_limit sign specified\n            - trigger_volume_location # Location for the trigger area for specific signs like stop or speed limit\n            - trigger_volume_rotation # Orientation of the trigger volume for specific signs\n            - trigger_volume_extent # Extension length of the trigger volume for specific signs\n\n            # for others sign specified, because CARLA API get incorrect coordinates, so we need to adjust it.\n            - bbx_loc # Bounding box location(x,y,z in ego coordinates)\n            - world_cord # Bounding box verts coordinates in world coordinates.\n\n        - pedestrian\n            - class: 'walker'\n            - id # Unique identifier for the pedestrian\n            - location # Location coordinates of the pedestrian(x,y,z in world coordinates)\n            - rotation # Orientation of pedestrian in world coordinates\n            - bbx_loc # Bounding box location(x,y,z in ego coordinates)\n            - center # Center point of the pedestrian in world coordinates.\n            - extent # Extension length of pedestrian in world coordinates.\n            - world_cord  # Bounding box verts coordinates in world coordinates.\n            - semantic_tags  # Descriptive tags related to the pedestrian.\n            - type_id # Type name for the pedestrian.\n            - gender\n            - age\n            - num_points # num of LiDAR point cloud.\n            - distance # Distance of the pedestrian from the ego vehicle\n            - speed # Speed of pedestrian.\n            - bone # Bone of pedestrian.\n            - road_id # Road identifier where the pedestrian is located\n            - lane_id # Lane identifier for the lane affected by the pedestrian\n            - section_id # Section of the road where the pedestrian is located\n            - world2ped # Transformation from world coordinates to pedestrian coordinates\n```\n## HD-Map Data Structure\n``` shell\n  # Each HD-Map file contains road information of a certain town\n  - road_id  # CARLA road id\n    # Each road_id corresponds to a dict, where each element formed as:\n    -lane_id\n        # Each lane_id corresponds to a list, where each element is a dict formed as:\n        - Points  # Location-rotation array formed as ((location_x, location_y, location_z), (roll, pitch, yaw), Flag_variable(If the 'Type==Center', a flag variable will exist to indicate whether the current waypoint is in a junction; otherwise, it will not exist.))\n        - Type # String, can be 'Broken', 'Solid', 'SolidSolid', 'Other', 'NONE', 'Center'\n        - Color # Color, can be 'Blue', 'White', 'Yellow'. (color of Type-'Center' is 'White') \n        - Topology # String array contains the 'road_id' and 'lane_id' of the current road adjacent to, formed as ((road_id, lane_id), ..)\n        # If the Type == 'Center', there will be other three keys named 'TopologyType', 'Left' and 'Right'\n        - TopologyType # The current lane's topology status, can be 'Junction', 'Normal', 'EnterNormal', 'EnterJunction', 'PassNormal', 'PassJunction', 'StartJunctionMultiChange', or 'StartNormalMultiChange'\n        - Left # The road_id and lane_id of the left lane of the current lane，formed as (road_id, lane_id), None if the left lane does not exist\n        - Right # The road_id and lane_id of the right lane of the current lane，formed as (road_id, lane_id), None if the right lane does not exist\n    # If current 'road_id' contains trigger volumes, there will be a special dict with 'TriggerVolumes' as key:\n    - 'TriggerVolumes'\n        # Each 'TriggerVolumes' corresponds to a list, where each element is a dict formed as:\n        - 'Points' # Vertexs location array of current trigger volume\n        - 'Type' # The parent actor type of current trigger volume, can be 'StopSign' or 'TrafficLight'\n        - 'ParentActor_Location' # The parent actor's location of current trigger volume, formed as (location.x, location.y, location.z)\n```\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/docs/bench2drive_base_1000.json",
    "content": "{\n    \"AccidentTwoWays_Town12_Route1102_Weather10.tar.gz\": {\n        \"sha256\": \"f3e06c3086d75dfa1f3741cfb8f56861c0e1303404ea2cb0cf7e38b07930865f\",\n        \"size\": 431879587\n    },\n    \"AccidentTwoWays_Town12_Route1103_Weather11.tar.gz\": {\n        \"sha256\": \"14d4f79281c1c7adce5803197d8b646cd7452f847ac427a77be8205df6231990\",\n        \"size\": 279443560\n    },\n    \"AccidentTwoWays_Town12_Route1104_Weather12.tar.gz\": {\n        \"sha256\": \"3696744bbd8eb681414c66cf8418ee75f4c4187d68009625a5a376135de0f8b3\",\n        \"size\": 268023816\n    },\n    \"AccidentTwoWays_Town12_Route1105_Weather13.tar.gz\": {\n        \"sha256\": \"56b837a072085b55dd1b58377454b1af22383c4d31c24484b44b40691e94e70c\",\n        \"size\": 146208246\n    },\n    \"AccidentTwoWays_Town12_Route1106_Weather14.tar.gz\": {\n        \"sha256\": \"f023f1ee1ba5ba056a54be01915b634b64587ca0330ff7c652148f73b42c402a\",\n        \"size\": 296301415\n    },\n    \"AccidentTwoWays_Town12_Route1107_Weather15.tar.gz\": {\n        \"sha256\": \"857b9bf76063b47631affd180c43e45ce1c52c494ad74e5d4487e34bba9e8936\",\n        \"size\": 487429369\n    },\n    \"AccidentTwoWays_Town12_Route1109_Weather9.tar.gz\": {\n        \"sha256\": \"dc24f42a45e1a9ce2a2de82c50ababfc7c5f6bb476b7d047396d7e5cb364c6d3\",\n        \"size\": 259856278\n    },\n    \"AccidentTwoWays_Town12_Route1110_Weather18.tar.gz\": {\n        \"sha256\": \"4d573ed9fa80f7a57449b7d00ea441a56d0b24fa5543d444fb4607ee817df966\",\n        \"size\": 805422958\n    },\n    \"AccidentTwoWays_Town12_Route1111_Weather19.tar.gz\": {\n        \"sha256\": \"4f7266fb2bf2e6bdbe78dea21ce5f32a085626b247f14759e9ccad108ff553db\",\n        \"size\": 483146320\n    },\n    \"AccidentTwoWays_Town12_Route1112_Weather20.tar.gz\": {\n        \"sha256\": \"3768f01bea7c69ca8c841e4d0960f2dc4e5fb833dbcdb20702508d5d3891f8ad\",\n        \"size\": 305195309\n    },\n    \"AccidentTwoWays_Town12_Route1113_Weather21.tar.gz\": {\n        \"sha256\": \"ca595390f422490a779cd0f3d9581837fe40e9536ab9b1664986831b760bba88\",\n        \"size\": 252507680\n    },\n    \"AccidentTwoWays_Town12_Route1114_Weather22.tar.gz\": {\n        \"sha256\": \"7152f13dbd35e97a1f03a1bb395c91469bc07ad503cfc75e949d2a1e8d5e0a48\",\n        \"size\": 385267137\n    },\n    \"AccidentTwoWays_Town12_Route1115_Weather23.tar.gz\": {\n        \"sha256\": \"2ebb88739db86ec8c4292f6f6b3a55ae588f670e784650e5a9c34cea15dcff87\",\n        \"size\": 378045977\n    },\n    \"AccidentTwoWays_Town12_Route1116_Weather23.tar.gz\": {\n        \"sha256\": \"e2d382921cfa5e7b8a0abbab2eff986cb620ba436e618742ec9b780086cdcb51\",\n        \"size\": 325781760\n    },\n    \"AccidentTwoWays_Town12_Route1117_Weather25.tar.gz\": {\n        \"sha256\": \"9924d4e60e7341004270d3da9a8b303569cb9d1739f24fb33db1e6a1bcd65b17\",\n        \"size\": 411153955\n    },\n    \"AccidentTwoWays_Town12_Route1119_Weather1.tar.gz\": {\n        \"sha256\": \"729d3bfc258f8b6af9581278f8d8784f0651af0aee48319db363f6ac9c252f20\",\n        \"size\": 983866449\n    },\n    \"AccidentTwoWays_Town12_Route1120_Weather2.tar.gz\": {\n        \"sha256\": \"0804aa235bbf783b3f07eb7acc3655e2be8768a307297809eacb0756277b245e\",\n        \"size\": 296100580\n    },\n    \"AccidentTwoWays_Town12_Route1121_Weather3.tar.gz\": {\n        \"sha256\": \"1411b131749bf5eeda0af1dc56cdff79e27b18c71196be52810478c01001442b\",\n        \"size\": 181759292\n    },\n    \"AccidentTwoWays_Town12_Route1124_Weather18.tar.gz\": {\n        \"sha256\": \"25edece7f693aa6dc8052b5171b97d67fd006238b6661aef1e1c33a6cd091a62\",\n        \"size\": 1240922644\n    },\n    \"AccidentTwoWays_Town12_Route1126_Weather8.tar.gz\": {\n        \"sha256\": \"d3c1aa4380e918a96a1b1f2c67d94a13ea759dbe9c1e121c91595df511453259\",\n        \"size\": 312852145\n    },\n    \"AccidentTwoWays_Town12_Route1127_Weather9.tar.gz\": {\n        \"sha256\": \"a8f821f0f4de784c8fc2eddc59eb1d0d36ec8bedcbcd38f46bf29e1a4b5d12e1\",\n        \"size\": 302025157\n    },\n    \"AccidentTwoWays_Town12_Route1444_Weather0.tar.gz\": {\n        \"sha256\": \"2690cb0053a2e9208f50f9d48c4a1c5befae4179c07e6fb8f06dc4434fb82178\",\n        \"size\": 341845960\n    },\n    \"AccidentTwoWays_Town12_Route1445_Weather1.tar.gz\": {\n        \"sha256\": \"008957cf0b1cd14cee9f4354341d201d734bbf316f0f94a02ecf8582b066dd41\",\n        \"size\": 421161539\n    },\n    \"AccidentTwoWays_Town12_Route1446_Weather2.tar.gz\": {\n        \"sha256\": \"4af0c2b3c9b2088532707ded560b0f2a5df0bb995e7f8f2e662d97737a624344\",\n        \"size\": 325838936\n    },\n    \"AccidentTwoWays_Town12_Route1448_Weather5.tar.gz\": {\n        \"sha256\": \"d317357e6071d6d373f7a5ea6c2a477f7e56d9d9094049c4787d41a0c54e050d\",\n        \"size\": 307719445\n    },\n    \"AccidentTwoWays_Town12_Route1453_Weather12.tar.gz\": {\n        \"sha256\": \"0e5cfdb2903f01ab6d96f876add12293e44d0ead82b6cd5fe5fb6f633d2c81cb\",\n        \"size\": 321739513\n    },\n    \"AccidentTwoWays_Town12_Route1454_Weather13.tar.gz\": {\n        \"sha256\": \"29922ca7bf519af629a78125dfd96cb03b14139d15ecd21ba53fba7f13245828\",\n        \"size\": 241022808\n    },\n    \"AccidentTwoWays_Town12_Route1455_Weather14.tar.gz\": {\n        \"sha256\": \"4159f8bdc1ac9742c61cc92a06f0079f6be4b3b557f1ea44a82e4a283c8c1400\",\n        \"size\": 268420165\n    },\n    \"AccidentTwoWays_Town12_Route1456_Weather15.tar.gz\": {\n        \"sha256\": \"2e0359e23dcd0b4fd20b5c89e59ea85982355c3bcc6c0b59bed87bae1d34b4e6\",\n        \"size\": 307288254\n    },\n    \"AccidentTwoWays_Town12_Route1458_Weather9.tar.gz\": {\n        \"sha256\": \"76447c5eef451e0cd955b6dda84215e30e9a0faaa433788421af5b24359b7b53\",\n        \"size\": 235261670\n    },\n    \"AccidentTwoWays_Town12_Route1459_Weather18.tar.gz\": {\n        \"sha256\": \"e751251caa5e6184c0b2cfe06fe1470f2aa1a30753faa703c3445a1a3d548f65\",\n        \"size\": 309292436\n    },\n    \"AccidentTwoWays_Town12_Route1461_Weather20.tar.gz\": {\n        \"sha256\": \"124510be926a6cfae76fd1e67ac0813bd6ff36b945e7ce2b9556ef2a034666cc\",\n        \"size\": 400187739\n    },\n    \"AccidentTwoWays_Town12_Route1463_Weather22.tar.gz\": {\n        \"sha256\": \"ca35a46a342c5cfc97b852e66b4704948050e5fdbfc2355ce7d312a4e5add24a\",\n        \"size\": 276586405\n    },\n    \"AccidentTwoWays_Town12_Route1468_Weather2.tar.gz\": {\n        \"sha256\": \"8b8d443e7d3249e7310a77db12b3984df3fe751ac0ad1f43393782f8e6ef110d\",\n        \"size\": 412947975\n    },\n    \"AccidentTwoWays_Town12_Route1469_Weather3.tar.gz\": {\n        \"sha256\": \"553738a667bd409b809fed94b9a781c5c42c2560aa7bfb59a110399db223c35b\",\n        \"size\": 318815267\n    },\n    \"Accident_Town03_Route101_Weather23.tar.gz\": {\n        \"sha256\": \"bc8a6dd3e4f5887c29f4f99b1ead01ddc505295ff240fe9449006719f334bdbb\",\n        \"size\": 174853755\n    },\n    \"Accident_Town03_Route102_Weather20.tar.gz\": {\n        \"sha256\": \"aa821b9fa1adf46b299b890d0c0e13e80d1851c66b1800594d40483afc6b3be5\",\n        \"size\": 194025708\n    },\n    \"Accident_Town03_Route146_Weather8.tar.gz\": {\n        \"sha256\": \"397dce793df6a7c0c2eb6e56e4b6e4889adaa6a855ecbe25c5fb85aaa3eb45ad\",\n        \"size\": 242654284\n    },\n    \"Accident_Town03_Route156_Weather0.tar.gz\": {\n        \"sha256\": \"09780cfaae07b13f65f11addfffbda8dea7723a6dfbbe0b49f493303805d24fa\",\n        \"size\": 264497958\n    },\n    \"Accident_Town04_Route159_Weather3.tar.gz\": {\n        \"sha256\": \"92b77f8bdb930a74fd78e59d27e19e3a4d171f3f81e830c5c86f627a51ed84f7\",\n        \"size\": 312299119\n    },\n    \"Accident_Town04_Route160_Weather3.tar.gz\": {\n        \"sha256\": \"6f22087304f093df9a2981955cf77e6ef996ba2d7d0ab89d9b567fdae6105792\",\n        \"size\": 301736807\n    },\n    \"Accident_Town04_Route205_Weather23.tar.gz\": {\n        \"sha256\": \"8f1dba46a15da6636176b9f884b63cc77d0eb73501e36b876c05e692dd61d70a\",\n        \"size\": 257542485\n    },\n    \"Accident_Town05_Route218_Weather10.tar.gz\": {\n        \"sha256\": \"451e06782b857ec572bf92e847ff08104cf7fcfa50627cbad0844babe6e54e02\",\n        \"size\": 246433697\n    },\n    \"Accident_Town05_Route219_Weather11.tar.gz\": {\n        \"sha256\": \"cfda56df54d7f48e9642fd33020147aa96c2b72642818e8eb49c525661010073\",\n        \"size\": 283002864\n    },\n    \"Accident_Town06_Route279_Weather19.tar.gz\": {\n        \"sha256\": \"8faca9466b6027d02ade050d548de3273aaac5cc02ec652770e1bbbe52f4a990\",\n        \"size\": 203646607\n    },\n    \"Accident_Town06_Route280_Weather11.tar.gz\": {\n        \"sha256\": \"cd4978006f2b5deb792a44abe9e7ba2349ae668bc710b3468b824399bcead6e6\",\n        \"size\": 244529006\n    },\n    \"Accident_Town06_Route308_Weather22.tar.gz\": {\n        \"sha256\": \"def4b3e8e593e07558cc7271902160ee1e875fe3557fd5f559c10415f3e134fb\",\n        \"size\": 212361840\n    },\n    \"Accident_Town06_Route327_Weather15.tar.gz\": {\n        \"sha256\": \"a41c25bdd2e3a2b6e42e040b5b04ce8438bcb6c2e0aab8fad991972417cbfdb2\",\n        \"size\": 247663969\n    },\n    \"Accident_Town12_Route1108_Weather8.tar.gz\": {\n        \"sha256\": \"5385616707992a89aa4653262731114ca4cad36fc005e3d967657686499836b7\",\n        \"size\": 149203258\n    },\n    \"Accident_Town12_Route1122_Weather3.tar.gz\": {\n        \"sha256\": \"480cb56b46d30153d914d4c36efd3f6dc4eb84007cd759684d4d6c39ba848aed\",\n        \"size\": 266836027\n    },\n    \"Accident_Town12_Route766_Weather12.tar.gz\": {\n        \"sha256\": \"8b9ea0e3436fc50352d85be96776cd88cf2428c8432e6915d9baca99ae586ee3\",\n        \"size\": 240962064\n    },\n    \"Accident_Town12_Route767_Weather13.tar.gz\": {\n        \"sha256\": \"efce63e4ce952bdbebf411fedb5e0bd1bb89958783018896935fa82a9487a4ff\",\n        \"size\": 237451352\n    },\n    \"Accident_Town12_Route768_Weather14.tar.gz\": {\n        \"sha256\": \"6ff51c8913731255fd22c9b36ea8ca9ad6d2f05b16f92f4a6a337c3ac0ba8592\",\n        \"size\": 250285692\n    },\n    \"Accident_Town12_Route769_Weather15.tar.gz\": {\n        \"sha256\": \"f9be0322fbe9dee3b1764dc0595521d0a956a734bfae58a02261bd3fc0da2c95\",\n        \"size\": 293533515\n    },\n    \"Accident_Town12_Route956_Weather20.tar.gz\": {\n        \"sha256\": \"2465f472cb17bcf26eca16ba0c41899d0fe1b85d55cae0ba2fb750da2cdc505a\",\n        \"size\": 799057991\n    },\n    \"Accident_Town12_Route957_Weather21.tar.gz\": {\n        \"sha256\": \"23c7b861b9de7301d882c6013db90c46ed359c8e1622f6f6661f18c8ef487351\",\n        \"size\": 365035493\n    },\n    \"Accident_Town13_Route550_Weather3.tar.gz\": {\n        \"sha256\": \"c28a24bd4dc593cec47be3b09288e5cce11720537448c5d203183446f73ae9c6\",\n        \"size\": 493024693\n    },\n    \"Accident_Town13_Route551_Weather5.tar.gz\": {\n        \"sha256\": \"c86ab3dfde33f9ac75afbd6ba4cf20d11bb6c25734a52e64c5daa4d63b1e93d4\",\n        \"size\": 648538952\n    },\n    \"Accident_Town13_Route552_Weather6.tar.gz\": {\n        \"sha256\": \"ef6a7849d723def7a105568bd038f8516a22792b583cc699d101664ea4154ee0\",\n        \"size\": 352188421\n    },\n    \"Accident_Town15_Route411_Weather21.tar.gz\": {\n        \"sha256\": \"fdbdefbc7c522a57ee7c798e55d549b98663416a85ff208456a5131fd90df85c\",\n        \"size\": 345218591\n    },\n    \"Accident_Town15_Route412_Weather22.tar.gz\": {\n        \"sha256\": \"ec323294e8605dbfaadfc7ac177df112e8f423e452f2569d4a93ff642626af4a\",\n        \"size\": 887687471\n    },\n    \"Accident_Town15_Route413_Weather23.tar.gz\": {\n        \"sha256\": \"9a07fb416c5cbb0551560d72fbe14dec3a257139a57573f9b2f6b1574dedb921\",\n        \"size\": 562723878\n    },\n    \"Accident_Town15_Route414_Weather23.tar.gz\": {\n        \"sha256\": \"1d51ac921b45dcb44bd827e6869c1a660d6e41bfa7069fb6d50bbcde62254d96\",\n        \"size\": 661437491\n    },\n    \"BlockedIntersection_Town03_Route134_Weather3.tar.gz\": {\n        \"sha256\": \"883fbed36b4266e4aff2686c9e6e2f143302fdceb0d631ea07949f547b85f6ec\",\n        \"size\": 481369531\n    },\n    \"BlockedIntersection_Town03_Route135_Weather5.tar.gz\": {\n        \"sha256\": \"5ad3d52c2bd8f9cacef988d0e70ccb9b2c61dfb6afad77adfd67d83f47714326\",\n        \"size\": 652151028\n    },\n    \"BlockedIntersection_Town03_Route136_Weather6.tar.gz\": {\n        \"sha256\": \"094614ce081a8feaa7cb3f3f9a9b5ff7989acdd7da018d9502f2f3e27a7bbcdb\",\n        \"size\": 244235614\n    },\n    \"BlockedIntersection_Town04_Route193_Weather11.tar.gz\": {\n        \"sha256\": \"1a3f52c961eaaed14ae01cf1ca2d87fc51501c4559fa0e90de2aaa5177e0d307\",\n        \"size\": 409128574\n    },\n    \"BlockedIntersection_Town04_Route194_Weather12.tar.gz\": {\n        \"sha256\": \"38736f237ee86ef5d61d6c8d6fe190c46d1f6b8859189a058e9b51d35ef6ef82\",\n        \"size\": 305276272\n    },\n    \"BlockedIntersection_Town04_Route195_Weather13.tar.gz\": {\n        \"sha256\": \"7fbde2e76e3605d772de3ab2b2e8ac7d018b008d8ed5975fa9a949cb4348ce68\",\n        \"size\": 414226256\n    },\n    \"BlockedIntersection_Town05_Route247_Weather19.tar.gz\": {\n        \"sha256\": \"39faaf7b0dc88ad1dc15c858922941d51e82c5be2ef5491cf537535d301d5f85\",\n        \"size\": 359698927\n    },\n    \"BlockedIntersection_Town05_Route248_Weather14.tar.gz\": {\n        \"sha256\": \"c9a0be6d4a39c4b8ddc965228b42e982f607d1ba0574106f9abf75cf676c0c5c\",\n        \"size\": 297625633\n    },\n    \"BlockedIntersection_Town05_Route272_Weather12.tar.gz\": {\n        \"sha256\": \"a157a2dc5efa0c00d4333efd64e3c808cd8d266fb7641a9e63b480357122989b\",\n        \"size\": 660231980\n    },\n    \"BlockedIntersection_Town07_Route351_Weather13.tar.gz\": {\n        \"sha256\": \"3656d93f45638860f8284bde9846861fd1f8500dc27d64e6a32a209a8e109e97\",\n        \"size\": 381908882\n    },\n    \"BlockedIntersection_Town07_Route352_Weather14.tar.gz\": {\n        \"sha256\": \"784bf0062acad8694a2651cb097901eac49ee74723dd3c3f80b3d11fff82b95d\",\n        \"size\": 358510616\n    },\n    \"BlockedIntersection_Town07_Route353_Weather15.tar.gz\": {\n        \"sha256\": \"46eee7beeb20a44f21d1c8ea09f87ee8441b400e57cbd5c40bc0db68973ee585\",\n        \"size\": 302209816\n    },\n    \"BlockedIntersection_Town10HD_Route391_Weather1.tar.gz\": {\n        \"sha256\": \"f1fe402e4d69d8cbcde99b9029fd18b3efad3a8471116fca61d187ac1d2dda0c\",\n        \"size\": 600995368\n    },\n    \"BlockedIntersection_Town12_Route834_Weather2.tar.gz\": {\n        \"sha256\": \"bcdf2742864482e0d5294ea13dfb3deb92869ab0f0d4d2d04ee5f293bc49b629\",\n        \"size\": 317415439\n    },\n    \"BlockedIntersection_Town12_Route835_Weather3.tar.gz\": {\n        \"sha256\": \"af422b30ad197cc2919a57769abe2807fb7908111d8d0cfc9ea32a0b7c5d93f7\",\n        \"size\": 289873027\n    },\n    \"BlockedIntersection_Town12_Route836_Weather3.tar.gz\": {\n        \"sha256\": \"a0d07a4dda654d348d03de49d627dffdd9e7efb0ae409b84c36a6c9927b2bc7e\",\n        \"size\": 1046553390\n    },\n    \"BlockedIntersection_Town12_Route936_Weather0.tar.gz\": {\n        \"sha256\": \"127690f961e984e9ef62f2a955dc90d248eec4f205224f2237c617b9d3ac9bfc\",\n        \"size\": 610053596\n    },\n    \"BlockedIntersection_Town13_Route615_Weather9.tar.gz\": {\n        \"sha256\": \"c5c048ee1d8db286dd94a3c6bbbf03b53714770629e01c98de47c4d389e3e1b5\",\n        \"size\": 453689897\n    },\n    \"BlockedIntersection_Town13_Route616_Weather18.tar.gz\": {\n        \"sha256\": \"8bc0e327a77289704ea1f1857dd693a9e3c3207ff84ab53751b9134c23a72db3\",\n        \"size\": 683948671\n    },\n    \"BlockedIntersection_Town13_Route617_Weather19.tar.gz\": {\n        \"sha256\": \"d498b79d56b9fd78c36dbc24d556e9263392994919e6656f9d091a9621643259\",\n        \"size\": 436163992\n    },\n    \"BlockedIntersection_Town13_Route618_Weather20.tar.gz\": {\n        \"sha256\": \"008d2b421ccaee6d0b36d8a36d244ca305c69797098a5112e99d0ffd4d40cba3\",\n        \"size\": 273102207\n    },\n    \"BlockedIntersection_Town15_Route485_Weather9.tar.gz\": {\n        \"sha256\": \"36c11d690961c2859df8dc39ceed3a4355e66551944cd2d1ff51a6b0d7439415\",\n        \"size\": 578951153\n    },\n    \"BlockedIntersection_Town15_Route486_Weather18.tar.gz\": {\n        \"sha256\": \"b904d51eed3241306e4d352a11e9360920131a1479f6f98815bfbfbe0d0b8027\",\n        \"size\": 919999680\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1080_Weather14.tar.gz\": {\n        \"sha256\": \"91b6e179ea5f738930634850b8a9d01f864f129dd1f9901784487f1db3889147\",\n        \"size\": 253940881\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1083_Weather9.tar.gz\": {\n        \"sha256\": \"8bb53384d17a27051b96f74d0215521edd451f88046ba1d856c7c653ccd9ee2e\",\n        \"size\": 229462137\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1084_Weather5.tar.gz\": {\n        \"sha256\": \"cded6742bdc9ca808df01fbb165542ed3c2f1d8b1d3f86a88922dabec9ed6d35\",\n        \"size\": 477305303\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1085_Weather6.tar.gz\": {\n        \"sha256\": \"64b492429fb82e20693b7d2847af94b5293c424d931e9f2179a08ffdf8fca320\",\n        \"size\": 264949484\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1086_Weather20.tar.gz\": {\n        \"sha256\": \"e99e87390a23705fb51fc63d1a813da2f7cd72492cd194cf1f9861c0e1946b99\",\n        \"size\": 253318591\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1089_Weather23.tar.gz\": {\n        \"sha256\": \"e64d7cb114ed420746eff66dd0f9884a771e964867f3c6ba3ae935da42ad2394\",\n        \"size\": 257293507\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1091_Weather12.tar.gz\": {\n        \"sha256\": \"81d22adc33978431ec816f9d9bc11e785b17fe19359cc8df339d75b13c6ae711\",\n        \"size\": 247928155\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1093_Weather1.tar.gz\": {\n        \"sha256\": \"bd197cbaefa36b430fe7c5addf77d723531c5a100e691cd48aed878ea6c7215e\",\n        \"size\": 344327293\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1094_Weather2.tar.gz\": {\n        \"sha256\": \"e1befb0788410bdb332c3316e834e10ff9fc845e2840d100dbc32481f7aef913\",\n        \"size\": 443320581\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1095_Weather3.tar.gz\": {\n        \"sha256\": \"f07ce98b096d768e338eb8f689e9c178ad32c81aed15eb4e21d71ec7fe494834\",\n        \"size\": 303682962\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1096_Weather3.tar.gz\": {\n        \"sha256\": \"add016644ea577df8143b107f5dc9c8a3f2d0c67301d8a6c36dba229a1fa848c\",\n        \"size\": 311856070\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1097_Weather5.tar.gz\": {\n        \"sha256\": \"d1e7c5a02298741248bab366413d16541d32e96704bb87c234ad80156ac78091\",\n        \"size\": 354544741\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1098_Weather6.tar.gz\": {\n        \"sha256\": \"3d24198ee965a0fd4ee65b0504774082f1b1b11a6fc30be28acfb04ffbcc03aa\",\n        \"size\": 333545230\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1099_Weather7.tar.gz\": {\n        \"sha256\": \"162ce1fd3c886f6f46c75c2ef5b6a918b0d2a60f15397fcba5f1b160c090b8b2\",\n        \"size\": 355038530\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1100_Weather14.tar.gz\": {\n        \"sha256\": \"abc4df340ca2d1879bb4fd4b56e87ee8cf2d30c928c2af885a27d0f5f4544129\",\n        \"size\": 707528400\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1404_Weather26.tar.gz\": {\n        \"sha256\": \"44ab0ed739e96488010f734b9e8e2326ee44c8e607ce13f4b46772c043877ccd\",\n        \"size\": 380727070\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1406_Weather26.tar.gz\": {\n        \"sha256\": \"83a5a5d01c52797d669b1934310a371bf73b476abdcf9f501bd546c88d251434\",\n        \"size\": 359022318\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1410_Weather26.tar.gz\": {\n        \"sha256\": \"04c3d6abde2f5ca11b3b2cf77298dc789a5a99e114eabb2e7d169aa298fb3e07\",\n        \"size\": 361357063\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1413_Weather26.tar.gz\": {\n        \"sha256\": \"e33184d9fb821afb1a8d57975a27e924eee4d1dab7238df1693d550731848e30\",\n        \"size\": 341440809\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1414_Weather26.tar.gz\": {\n        \"sha256\": \"14e9b56e30779711533865d60999a5b82c4ed04bdf9a1a4e5a12ec264a66c949\",\n        \"size\": 372128998\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1415_Weather26.tar.gz\": {\n        \"sha256\": \"a9643c507c2ff7ea6dc2551d166f6c4f6ca0723eff0a661afe0aae435e7898b6\",\n        \"size\": 362560911\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1418_Weather26.tar.gz\": {\n        \"sha256\": \"e2185c06154d82f5830e028ee391a24ef77b88cacd0b4aca1e164331464f3396\",\n        \"size\": 393442859\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1419_Weather26.tar.gz\": {\n        \"sha256\": \"d7f98d12be16eb681e791669d4548da9891cf5797df727b15a33bc3309f6bc88\",\n        \"size\": 384819045\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1421_Weather26.tar.gz\": {\n        \"sha256\": \"0cf3ce35821eafbd39d51d0e426d4202a18980c4c819508de2d6083c30ab4711\",\n        \"size\": 384804277\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1422_Weather26.tar.gz\": {\n        \"sha256\": \"3d9b51fac6848f692363bcbf5f7965d64d8dd28d4b69a9eb8ea95d96fabf3f70\",\n        \"size\": 361347931\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1424_Weather26.tar.gz\": {\n        \"sha256\": \"6caf6a8f583f31662a09aeca348ecb766b76bd7001fc632189f1bcf430a8be6f\",\n        \"size\": 408502814\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1425_Weather26.tar.gz\": {\n        \"sha256\": \"e7ce510398b66d4bc63ad6c4109e8ab53c53fd486379e40e000ce9201e8c391e\",\n        \"size\": 418454399\n    },\n    \"ConstructionObstacle_Town03_Route60_Weather8.tar.gz\": {\n        \"sha256\": \"ecfe6e7cd8343761bf78c8ee6a1104f9d36a04c29a633547b947d78abb239a1a\",\n        \"size\": 148863523\n    },\n    \"ConstructionObstacle_Town03_Route61_Weather9.tar.gz\": {\n        \"sha256\": \"be2e4a0e1423b9accb2fc19025d422fa9f42b5245789e8eca51442d398a00ea4\",\n        \"size\": 191885610\n    },\n    \"ConstructionObstacle_Town03_Route62_Weather10.tar.gz\": {\n        \"sha256\": \"c945c4afd833aadc00a37fd2142a2ac94c82a3ed3ba8ae7edde4c20737a32083\",\n        \"size\": 183568087\n    },\n    \"ConstructionObstacle_Town03_Route63_Weather11.tar.gz\": {\n        \"sha256\": \"75bfb48fead1b664b643468a64fd62a646ab968b4ae0a7b1721d87936135d1c3\",\n        \"size\": 129055189\n    },\n    \"ConstructionObstacle_Town04_Route64_Weather12.tar.gz\": {\n        \"sha256\": \"2b7363c61ff0f9b5b5f0fc8e48fb67ab7c102c6c5ddb58d08ae96d3a5b34e37e\",\n        \"size\": 231452251\n    },\n    \"ConstructionObstacle_Town04_Route65_Weather13.tar.gz\": {\n        \"sha256\": \"fcb9d284e0d5c5961966149be102773aa95e59f045fae6a4cd74dcbdef4e514c\",\n        \"size\": 216145499\n    },\n    \"ConstructionObstacle_Town04_Route66_Weather14.tar.gz\": {\n        \"sha256\": \"9e6f4323523bf62d03c632f4ffaa84ed792e8f30338c95fa1ecac818f6218bb9\",\n        \"size\": 217961417\n    },\n    \"ConstructionObstacle_Town04_Route67_Weather15.tar.gz\": {\n        \"sha256\": \"db16668d9efffde1e7249871d9ef66633013e66362dabeee2fa64905934afcd8\",\n        \"size\": 219926136\n    },\n    \"ConstructionObstacle_Town05_Route68_Weather8.tar.gz\": {\n        \"sha256\": \"7a1e93168780f5dc4d38b6b5b357e74a62736c935adc3fa74b1ed35028c61e76\",\n        \"size\": 287017092\n    },\n    \"ConstructionObstacle_Town05_Route69_Weather9.tar.gz\": {\n        \"sha256\": \"622b08e44276561b3943002f1ce66b7508b94ae0210d694818b8b6ba5499e7e0\",\n        \"size\": 242368119\n    },\n    \"ConstructionObstacle_Town05_Route70_Weather18.tar.gz\": {\n        \"sha256\": \"87a45a586729a55fefedfb5af7fa0c36c1aaf720c14ab7f3f8c0602d2978a4e5\",\n        \"size\": 323684357\n    },\n    \"ConstructionObstacle_Town05_Route71_Weather19.tar.gz\": {\n        \"sha256\": \"65916f52194d611f3e68321827c316c08393b850103d2db5d24421e33c045a9f\",\n        \"size\": 224768446\n    },\n    \"ConstructionObstacle_Town06_Route72_Weather20.tar.gz\": {\n        \"sha256\": \"82bae89ef3279c55cd774a78682c40c811663f5cf59b1c2338acf89c7e399df8\",\n        \"size\": 235630982\n    },\n    \"ConstructionObstacle_Town06_Route73_Weather21.tar.gz\": {\n        \"sha256\": \"e09f8d22c5f12bac31f6fda3629800eda118556223d2a63aea387d711391ec97\",\n        \"size\": 129785887\n    },\n    \"ConstructionObstacle_Town10HD_Route74_Weather22.tar.gz\": {\n        \"sha256\": \"c553b45ccd07319b2a620af2cb17a88e74c75be406c50559f8f819ddd1030ebb\",\n        \"size\": 235784985\n    },\n    \"ConstructionObstacle_Town12_Route75_Weather23.tar.gz\": {\n        \"sha256\": \"3399b457cea08f4758684c2f8e868e600bca4de79d517249bef5c11ad3dded56\",\n        \"size\": 345212222\n    },\n    \"ConstructionObstacle_Town12_Route76_Weather23.tar.gz\": {\n        \"sha256\": \"febd5ab9b0d712dabc417a50a90137fef817c89f94c622474aed5ca42604e9bc\",\n        \"size\": 248482655\n    },\n    \"ConstructionObstacle_Town12_Route77_Weather25.tar.gz\": {\n        \"sha256\": \"ce255902fb5d4377850cf6e9668029ba8d32373df6fd6de11dd44dd7d9bd01cf\",\n        \"size\": 149586435\n    },\n    \"ConstructionObstacle_Town12_Route78_Weather0.tar.gz\": {\n        \"sha256\": \"d487121ad522f6c6c0cf158036c1ccf0f426bdfc41af8a4a39a3eb88818b0fd2\",\n        \"size\": 182273154\n    },\n    \"ConstructionObstacle_Town12_Route79_Weather1.tar.gz\": {\n        \"sha256\": \"bf6926a270d9dbb29ecb07afae2cee0db7de469d55c13a19e2d9548a7b102e86\",\n        \"size\": 273042524\n    },\n    \"ConstructionObstacle_Town13_Route80_Weather2.tar.gz\": {\n        \"sha256\": \"cdb080fa4174d73d0e672674938669c6e4c0898f7448fe7805f17f78ac1124bc\",\n        \"size\": 363659201\n    },\n    \"ConstructionObstacle_Town13_Route81_Weather3.tar.gz\": {\n        \"sha256\": \"a13ba610a8cada5621e3c9ce58740c7c5a775a64c295562b6a79170b03c947a1\",\n        \"size\": 469022128\n    },\n    \"ConstructionObstacle_Town13_Route82_Weather3.tar.gz\": {\n        \"sha256\": \"f6c5bc08d04cd0eda7c443b8ee1b89f3b8fd3a5e782f012071f515d5b6095ebf\",\n        \"size\": 353761464\n    },\n    \"ConstructionObstacle_Town13_Route83_Weather5.tar.gz\": {\n        \"sha256\": \"0c981ad389f8525e70959da5b536665e0154444806c77fcb4f20afdcf2e4bb24\",\n        \"size\": 506541569\n    },\n    \"ConstructionObstacle_Town15_Route84_Weather6.tar.gz\": {\n        \"sha256\": \"e9446a50a6ca022b86cd5c8b5d945931d636fd8041ce7b6eda16af10a9f97233\",\n        \"size\": 456799112\n    },\n    \"ConstructionObstacle_Town15_Route85_Weather7.tar.gz\": {\n        \"sha256\": \"ad32ac8181da95f86a65b223bd8f78715b31a59c68d711b77e5793a056df6eaf\",\n        \"size\": 568546367\n    },\n    \"ConstructionObstacle_Town15_Route87_Weather9.tar.gz\": {\n        \"sha256\": \"2dc6e97d4ef84a5bc1ed5e089cc7e1b1f685e15d4ae912bdac1eb7abfa3d6248\",\n        \"size\": 169725164\n    },\n    \"ControlLoss_Town04_Route169_Weather13.tar.gz\": {\n        \"sha256\": \"475ccd4c57f5de8fe38aaaba5334526612c1f1cc6405987bf8ed010b08250ea9\",\n        \"size\": 413814300\n    },\n    \"ControlLoss_Town04_Route170_Weather14.tar.gz\": {\n        \"sha256\": \"0ec76d93259d045503a8d95bab011f803e73dc5f8fc6ca4bc2810c3189c0e139\",\n        \"size\": 354467906\n    },\n    \"ControlLoss_Town07_Route332_Weather20.tar.gz\": {\n        \"sha256\": \"ea6be4a0dfc1e931288802393f2e9cc6f50b6446159ec52eb3471a20e58c20c6\",\n        \"size\": 525532824\n    },\n    \"ControlLoss_Town07_Route333_Weather21.tar.gz\": {\n        \"sha256\": \"b8694a60d44f4165b83ef0251c70235fc9bfedbb896e72d586d65a93a4f4ace3\",\n        \"size\": 363767594\n    },\n    \"ControlLoss_Town10HD_Route377_Weather13.tar.gz\": {\n        \"sha256\": \"029e1e1ca8edfd792ae230b0a80dec1456a805a39e55b4f1bcb48ce14808feac\",\n        \"size\": 210696563\n    },\n    \"ControlLoss_Town10HD_Route378_Weather14.tar.gz\": {\n        \"sha256\": \"1e004431cc3dd2d483a246228d7c6d2f959fc4ffc32dec7f4c4584b1f95f07c5\",\n        \"size\": 286046217\n    },\n    \"ControlLoss_Town11_Route401_Weather11.tar.gz\": {\n        \"sha256\": \"9e3abe0c9b25f0e50e597ac0f62a5cf681acd9631e439b23cabac77b85355043\",\n        \"size\": 99078817\n    },\n    \"ControlLoss_Town11_Route402_Weather12.tar.gz\": {\n        \"sha256\": \"4059fdbe8663b8a4d5d38f19b4d361ca64ad58bfecca357ff6f8c7dd6d0011e1\",\n        \"size\": 69532663\n    },\n    \"ControlLoss_Town13_Route574_Weather19.tar.gz\": {\n        \"sha256\": \"b5942530323404b139693461fd0b25f6005f8e417e8ee327a99bb4cf7f1df5ee\",\n        \"size\": 492282676\n    },\n    \"ControlLoss_Town15_Route430_Weather14.tar.gz\": {\n        \"sha256\": \"b82805d5cbc5ae148db9974a12bf0a8f35446bc248bf1bb5a05b7968d6b5b475\",\n        \"size\": 688837715\n    },\n    \"ControlLoss_Town15_Route431_Weather15.tar.gz\": {\n        \"sha256\": \"45ba84f627f3bbc8b693c65c5b2ae1111b213028a1837ce426502a7545b6bc5c\",\n        \"size\": 548666503\n    },\n    \"ControlLoss_Town15_Route432_Weather8.tar.gz\": {\n        \"sha256\": \"0d9a140f35cdca17f74a406a55afe4586b9368a63da186b8c45aec276a259656\",\n        \"size\": 431639375\n    },\n    \"ControlLoss_Town15_Route433_Weather9.tar.gz\": {\n        \"sha256\": \"f1b7eb5c785e304ad7082c1cd2438454608616c685841da091ec9e2c7927fab5\",\n        \"size\": 463186634\n    },\n    \"CrossingBicycleFlow_Town12_Route1011_Weather23.tar.gz\": {\n        \"sha256\": \"7d542038b6e18d26be4f6d314a8e558fb01976789e588b71ebdf7d2c9e31c4cb\",\n        \"size\": 401621672\n    },\n    \"CrossingBicycleFlow_Town12_Route1012_Weather23.tar.gz\": {\n        \"sha256\": \"3f6d6349aa8044ce4767d7feb3cf411f68716399179469ce655d544d5340afe2\",\n        \"size\": 839194598\n    },\n    \"CrossingBicycleFlow_Town12_Route1032_Weather18.tar.gz\": {\n        \"sha256\": \"3dbf6c364177fac5927c68c915506bea859a646ccef8a5c525cc638a3fc598a3\",\n        \"size\": 377496481\n    },\n    \"CrossingBicycleFlow_Town12_Route1044_Weather3.tar.gz\": {\n        \"sha256\": \"410ebc927154c3e00cf5f7ace7acc0e2e7b9feedc9e18c65729e528b18fc8bb5\",\n        \"size\": 469708098\n    },\n    \"CrossingBicycleFlow_Town12_Route1050_Weather10.tar.gz\": {\n        \"sha256\": \"6c3630dd421bf52ec5bfe64fe17927af21c3bc3ba32013e30913588c9738445a\",\n        \"size\": 493155757\n    },\n    \"CrossingBicycleFlow_Town12_Route1061_Weather21.tar.gz\": {\n        \"sha256\": \"50096f04f7ce013241cbcccfa72701ff9f45b00d87772275abca3eece3c8ec56\",\n        \"size\": 436671527\n    },\n    \"CrossingBicycleFlow_Town12_Route1062_Weather22.tar.gz\": {\n        \"sha256\": \"c3a40aef32a1612603f11425ad60ac6227a05d78107c5f295bb99192e4d170c8\",\n        \"size\": 471402030\n    },\n    \"CrossingBicycleFlow_Town12_Route1063_Weather23.tar.gz\": {\n        \"sha256\": \"abaee33bf2e33872e5e663493803940e919f35d1152ff6bf36f051d30ccf39a0\",\n        \"size\": 422176592\n    },\n    \"CrossingBicycleFlow_Town12_Route1064_Weather23.tar.gz\": {\n        \"sha256\": \"b7825c63b06265c4fb4180326ed70a2f325b5ee1b26ec887d160478da11bd622\",\n        \"size\": 379289929\n    },\n    \"CrossingBicycleFlow_Town12_Route1065_Weather25.tar.gz\": {\n        \"sha256\": \"bce15db79de979d3e736f694fba412a240cccd68b2972629a8bd9f1b2ed7e8c6\",\n        \"size\": 311661774\n    },\n    \"CrossingBicycleFlow_Town12_Route1066_Weather0.tar.gz\": {\n        \"sha256\": \"a2a024693384fe223d609eef7ba901191d9eb23d3e2cd7553dbc23b42d35cc03\",\n        \"size\": 507973097\n    },\n    \"CrossingBicycleFlow_Town12_Route1067_Weather1.tar.gz\": {\n        \"sha256\": \"95939849b8e4a39be237c3567b6b8eb5bd41cf305d67c052b87c94d94ce3e551\",\n        \"size\": 167996518\n    },\n    \"CrossingBicycleFlow_Town12_Route1068_Weather2.tar.gz\": {\n        \"sha256\": \"a0f326e4af73a1f80948c259fcab80f27d958c6e5158a9353aa4f1ecd0631ce0\",\n        \"size\": 462889503\n    },\n    \"CrossingBicycleFlow_Town12_Route1070_Weather3.tar.gz\": {\n        \"sha256\": \"f8201f6da07308c49c1a383d977e36ce1656a84b4ef7438cfff1d1c2eb331899\",\n        \"size\": 1012245809\n    },\n    \"CrossingBicycleFlow_Town12_Route1071_Weather0.tar.gz\": {\n        \"sha256\": \"31f41d35c8090b7b5494b4ce0de5fff094f937d0c14424790c5eb46d9a70440d\",\n        \"size\": 507161597\n    },\n    \"CrossingBicycleFlow_Town12_Route1072_Weather6.tar.gz\": {\n        \"sha256\": \"3038891520b01169a01a9b03829b515d84c01a8be735bde0f7218c73560c33f3\",\n        \"size\": 485753024\n    },\n    \"CrossingBicycleFlow_Town12_Route1073_Weather7.tar.gz\": {\n        \"sha256\": \"1e1c411b8c2035d66d153e642672313d698c54fd4f670ef03df060fa706221b1\",\n        \"size\": 814378436\n    },\n    \"CrossingBicycleFlow_Town12_Route1074_Weather8.tar.gz\": {\n        \"sha256\": \"d541a39dde3995f35900aaa32a8f10f65ca5e0f90dadecb2cff231e2aabd5fb9\",\n        \"size\": 679854628\n    },\n    \"CrossingBicycleFlow_Town12_Route1075_Weather9.tar.gz\": {\n        \"sha256\": \"4abf1725b82ead9efb1329f24696e04589723f987a2e9d9e7417ff7586b8c292\",\n        \"size\": 576222279\n    },\n    \"CrossingBicycleFlow_Town12_Route1076_Weather10.tar.gz\": {\n        \"sha256\": \"b601f1739286887b8eb342b49cbd94c5607914540b8514c3d3ff96f1b346e9d8\",\n        \"size\": 494868200\n    },\n    \"CrossingBicycleFlow_Town12_Route1077_Weather11.tar.gz\": {\n        \"sha256\": \"dceebbda200ff90a23f4f9217e9b3a74c4f8a6c1ca31b47ce028eea93e97c361\",\n        \"size\": 358981207\n    },\n    \"CrossingBicycleFlow_Town12_Route1078_Weather12.tar.gz\": {\n        \"sha256\": \"48f6766cc3baf1b9eb0e84f1f0d8b6f4dfd03c9d7b8f874651c0185c41d84b6a\",\n        \"size\": 886450197\n    },\n    \"CrossingBicycleFlow_Town12_Route860_Weather2.tar.gz\": {\n        \"sha256\": \"f7ea407c7e3d343a16bffd26a244f557d00ce61c902b006c87c6cfeeaea80643\",\n        \"size\": 536140647\n    },\n    \"CrossingBicycleFlow_Town12_Route862_Weather3.tar.gz\": {\n        \"sha256\": \"eb8af755f141d09ec96753d2fafc05a13a7e6983d734f1b99020c19c56fb1c53\",\n        \"size\": 536556540\n    },\n    \"CrossingBicycleFlow_Town12_Route863_Weather5.tar.gz\": {\n        \"sha256\": \"9c4e44c2011bc1f0c51aa530d08250cc5f605e0575da2884b8ccf0e5c936cd59\",\n        \"size\": 475465833\n    },\n    \"CrossingBicycleFlow_Town12_Route977_Weather15.tar.gz\": {\n        \"sha256\": \"3037230b36a9e5d576dbfa95a9924da66011c064339bea5706a9b9f485d40860\",\n        \"size\": 364346930\n    },\n    \"DynamicObjectCrossing_Town01_Route1_Weather1.tar.gz\": {\n        \"sha256\": \"f2c7cd5f50164a99cc9179c168ac8af9b318670f4ef850de7e5f08e499848969\",\n        \"size\": 323155259\n    },\n    \"DynamicObjectCrossing_Town01_Route2_Weather2.tar.gz\": {\n        \"sha256\": \"346824bf8f8695f97d303a013fc58cc8289b97b1956d8155432877a99de7c7be\",\n        \"size\": 879914987\n    },\n    \"DynamicObjectCrossing_Town01_Route3_Weather3.tar.gz\": {\n        \"sha256\": \"f76f2b255983ff9838bda9907c364ec0e012b3974915aac4a36bee99a60e9d98\",\n        \"size\": 279952165\n    },\n    \"DynamicObjectCrossing_Town01_Route4_Weather3.tar.gz\": {\n        \"sha256\": \"f8f7737bf762693560e422760383ba7bbc1060617e045f4cd20b2c359817003d\",\n        \"size\": 287214189\n    },\n    \"DynamicObjectCrossing_Town01_Route5_Weather2.tar.gz\": {\n        \"sha256\": \"709df5f844dd1600293631f2f1de147cd879f782f4c8f0386d2442d0d573e062\",\n        \"size\": 278760625\n    },\n    \"DynamicObjectCrossing_Town01_Route6_Weather6.tar.gz\": {\n        \"sha256\": \"e448174f97d6806813d827a85af7461c66d60ffacfc2f90c1ee1e21282af6d51\",\n        \"size\": 241933364\n    },\n    \"DynamicObjectCrossing_Town01_Route7_Weather7.tar.gz\": {\n        \"sha256\": \"4ed6da5b900077ec7ccfaaf63ee4e08976a02efbd01ea1cb0e3259f4ad431617\",\n        \"size\": 257576087\n    },\n    \"DynamicObjectCrossing_Town01_Route8_Weather3.tar.gz\": {\n        \"sha256\": \"2f8835ed66e4ba04ed07f2f7ffcf7735185de75849b731fff1f2f6c4c5c1d128\",\n        \"size\": 281651674\n    },\n    \"DynamicObjectCrossing_Town02_Route11_Weather11.tar.gz\": {\n        \"sha256\": \"37ed01c2f10da24b52af3bdc285f79144d5e43c5502dbefa8a821574b39feb0b\",\n        \"size\": 224203134\n    },\n    \"DynamicObjectCrossing_Town02_Route12_Weather12.tar.gz\": {\n        \"sha256\": \"115adb2adfd3bf17e64ff86c734f8ef4c4d51c8d14eddaf541d2ce089155f9f5\",\n        \"size\": 216906406\n    },\n    \"DynamicObjectCrossing_Town02_Route13_Weather6.tar.gz\": {\n        \"sha256\": \"b040f5993726dfb3a1dc1aaf5e2e4f93404a0124272d6f47f2469fca53ca25f2\",\n        \"size\": 280176944\n    },\n    \"DynamicObjectCrossing_Town02_Route14_Weather14.tar.gz\": {\n        \"sha256\": \"076e2efcca52f2add5f4c8ae0c71733cfe4b3e329a3052593d3fb512389ce778\",\n        \"size\": 258929584\n    },\n    \"DynamicObjectCrossing_Town02_Route15_Weather15.tar.gz\": {\n        \"sha256\": \"338793740fa738eb5b6723ecdb67f8a49c0900765ff158014f062f0e877d1687\",\n        \"size\": 258690228\n    },\n    \"DynamicObjectCrossing_Town02_Route9_Weather9.tar.gz\": {\n        \"sha256\": \"738939d20df4e1a245e873034f449bbe36e642f27e40aa4fe7b01f2b1d59c6be\",\n        \"size\": 226983293\n    },\n    \"DynamicObjectCrossing_Town10HD_Route18_Weather18.tar.gz\": {\n        \"sha256\": \"5a31e048122182ba3b56d8e811457c03c1396624173c07b51e22b77497237f30\",\n        \"size\": 203557817\n    },\n    \"DynamicObjectCrossing_Town10HD_Route19_Weather19.tar.gz\": {\n        \"sha256\": \"7d28469920444c1b6f8518aae3785340544e98e9f0dba3120eef4c89bfd58e2d\",\n        \"size\": 194851173\n    },\n    \"DynamicObjectCrossing_Town11_Route20_Weather20.tar.gz\": {\n        \"sha256\": \"3051701a2115094d208d1b6090f6cd336d51d0122612ef92b5859b50477cfade\",\n        \"size\": 53176605\n    },\n    \"DynamicObjectCrossing_Town12_Route21_Weather21.tar.gz\": {\n        \"sha256\": \"565e0b9a47088f27a7aba9894523230e825f66e65f16f65015af0bbb1b1058fc\",\n        \"size\": 267342607\n    },\n    \"DynamicObjectCrossing_Town12_Route22_Weather22.tar.gz\": {\n        \"sha256\": \"49f5519ee8f53cdfc8fbe0bd9f47531f41fc58874385e673909899edc25c036e\",\n        \"size\": 108718255\n    },\n    \"DynamicObjectCrossing_Town12_Route23_Weather23.tar.gz\": {\n        \"sha256\": \"35c41df06eb7a564b1f12df20c09628452fb591a01f2dde5633ebd4416d4b936\",\n        \"size\": 255484401\n    },\n    \"DynamicObjectCrossing_Town13_Route24_Weather23.tar.gz\": {\n        \"sha256\": \"1e4088cf79ddb81aa12fc0c087458e944b1e2d0fee27533a6fdb10ba189e72bc\",\n        \"size\": 143503611\n    },\n    \"DynamicObjectCrossing_Town13_Route25_Weather25.tar.gz\": {\n        \"sha256\": \"e27bf2b42f62c1543b731f59361046d71cfec1d281bd600f7bd8ab581efad4f3\",\n        \"size\": 284459303\n    },\n    \"DynamicObjectCrossing_Town13_Route26_Weather0.tar.gz\": {\n        \"sha256\": \"9b3729eb5b218ad5e74a353b65d151c42e87f4f6ac1884378f4cfc862c185170\",\n        \"size\": 270421722\n    },\n    \"DynamicObjectCrossing_Town15_Route27_Weather1.tar.gz\": {\n        \"sha256\": \"4018bb06db0dd37587c8c892bdcfc8c1d6cd3a4b965bc63c1a5214b72123d7ed\",\n        \"size\": 257970893\n    },\n    \"DynamicObjectCrossing_Town15_Route28_Weather2.tar.gz\": {\n        \"sha256\": \"88ad18ccadf4a3520891c93b8c5c0d765780702f55f1a4d814f92626b6444a22\",\n        \"size\": 308198385\n    },\n    \"DynamicObjectCrossing_Town15_Route29_Weather3.tar.gz\": {\n        \"sha256\": \"dfe5531ef461260b26d6d06e1fda26d2a105af233980944f88edee3a7a2e5867\",\n        \"size\": 251768702\n    },\n    \"EnterActorFlow_Town03_Route132_Weather2.tar.gz\": {\n        \"sha256\": \"50348d4ec638cf2dc3a05d7e83946a97b902cc3fbd5f319d6ca821cc2a46eaa0\",\n        \"size\": 462923906\n    },\n    \"EnterActorFlow_Town04_Route192_Weather10.tar.gz\": {\n        \"sha256\": \"da91e09f4e8bca8423ff16e0ab6e34e7c40d9b09f165a86e1270662f7b395fdb\",\n        \"size\": 215034847\n    },\n    \"EnterActorFlow_Town05_Route245_Weather9.tar.gz\": {\n        \"sha256\": \"e804109a053ed2160bc7a57004248635586d073ef86f51e189820c8b0e4b490c\",\n        \"size\": 361173359\n    },\n    \"EnterActorFlow_Town05_Route271_Weather11.tar.gz\": {\n        \"sha256\": \"da7f109f669fe9d08cba15a765edc662d47a09a9a5398ce0bdd4e694fc9a2f71\",\n        \"size\": 678355546\n    },\n    \"EnterActorFlow_Town07_Route348_Weather10.tar.gz\": {\n        \"sha256\": \"c7a4e43b165097f1e56fe837ee0a28456b23df221d3dd88c0530ed51e07323fe\",\n        \"size\": 195498004\n    },\n    \"EnterActorFlow_Town07_Route349_Weather11.tar.gz\": {\n        \"sha256\": \"3b75d7603316a6c155495e443439743ebc081f2793f574e8fa7be066d54e809c\",\n        \"size\": 161068354\n    },\n    \"EnterActorFlow_Town07_Route350_Weather12.tar.gz\": {\n        \"sha256\": \"0b878a50a10d8d57e52d48077d517a5d3344dffc6d15eec7fe468b08ba2fa00a\",\n        \"size\": 815011471\n    },\n    \"EnterActorFlow_Town12_Route830_Weather23.tar.gz\": {\n        \"sha256\": \"e9b7c74e59dfa235619b4d11956172980aac099512254841c37d983014b0e42d\",\n        \"size\": 93976589\n    },\n    \"EnterActorFlow_Town12_Route831_Weather25.tar.gz\": {\n        \"sha256\": \"80f6a756f95f90c82d55510a4740a69915e5ebad9a23cf08431edc3c70c839d3\",\n        \"size\": 145856660\n    },\n    \"EnterActorFlow_Town12_Route832_Weather0.tar.gz\": {\n        \"sha256\": \"a9f67121d71c336a8d9d0f382983a2cca3e1b2008c2c96c1a20d4485ea985289\",\n        \"size\": 635637526\n    },\n    \"EnterActorFlow_Town13_Route611_Weather13.tar.gz\": {\n        \"sha256\": \"8df2ade60cca1845012be286c2c0b511d2f07fff8f008c36f6f5051638262eed\",\n        \"size\": 142556865\n    },\n    \"EnterActorFlow_Town13_Route612_Weather14.tar.gz\": {\n        \"sha256\": \"6b2b42a89b9b18637d0832489b96e3b68ebeb4b0a3a62552362f7935abce6b4a\",\n        \"size\": 453593675\n    },\n    \"EnterActorFlow_Town13_Route613_Weather15.tar.gz\": {\n        \"sha256\": \"182ccc376d1c22cc7abc50f4163d4548af0b731d23bd8c5f8d391dcf5cf2d6a3\",\n        \"size\": 110003793\n    },\n    \"EnterActorFlow_Town13_Route614_Weather8.tar.gz\": {\n        \"sha256\": \"0aaed4ce3f43c0392dbfcb69ce573c1b412fca82b16b2fcb778db5cd09cf8eab\",\n        \"size\": 247701625\n    },\n    \"EnterActorFlow_Town13_Route681_Weather5.tar.gz\": {\n        \"sha256\": \"04a98039cb15899095822a850c98bcb38a38b32db9488c14f9f16fee55a2dede\",\n        \"size\": 495973968\n    },\n    \"HardBreakRoute_Town01_Route30_Weather3.tar.gz\": {\n        \"sha256\": \"2f6593d05e288a88cf37d8043d1e448842a4b1ceaed5544fe13100c174a4cb04\",\n        \"size\": 426576889\n    },\n    \"HardBreakRoute_Town01_Route31_Weather5.tar.gz\": {\n        \"sha256\": \"2aed910952ecd37df4f3ab4bb24e73194cae99117657ba263869a46a94c6181c\",\n        \"size\": 401177647\n    },\n    \"HardBreakRoute_Town01_Route32_Weather6.tar.gz\": {\n        \"sha256\": \"5ece530c85506e96b517ba7452ff9e626c542c18fbc65328b4c291e466cb94af\",\n        \"size\": 376360156\n    },\n    \"HardBreakRoute_Town02_Route33_Weather7.tar.gz\": {\n        \"sha256\": \"a179c2fd08a8b1d40dd15b3d069b0033c080ecedd06ad6f8ada1b79c8ea353d7\",\n        \"size\": 261815491\n    },\n    \"HardBreakRoute_Town02_Route34_Weather8.tar.gz\": {\n        \"sha256\": \"807764868812d01cdc9a6101da944ac9ceb64c64510a198a1bf4281520e61669\",\n        \"size\": 199958468\n    },\n    \"HardBreakRoute_Town02_Route35_Weather9.tar.gz\": {\n        \"sha256\": \"254b474c17664b42ace05abc8302e18acf92c62edd1e0ce0e43a730ecad5e687\",\n        \"size\": 177504376\n    },\n    \"HardBreakRoute_Town03_Route36_Weather10.tar.gz\": {\n        \"sha256\": \"dd5389f8a33fb790cfa11ffe59b14960d90fab21d8351f9ffc0cc1157ee1090a\",\n        \"size\": 419818184\n    },\n    \"HardBreakRoute_Town03_Route37_Weather11.tar.gz\": {\n        \"sha256\": \"c54fed30fbbed63feb645c1c7af2e8d5ad574983134c0010321b4520fbb7a0cc\",\n        \"size\": 152762660\n    },\n    \"HardBreakRoute_Town03_Route38_Weather12.tar.gz\": {\n        \"sha256\": \"25e6bd4e90e927452cdaad2c92727bce27967d0e18c240959ef6659690891a4d\",\n        \"size\": 515689383\n    },\n    \"HardBreakRoute_Town04_Route39_Weather13.tar.gz\": {\n        \"sha256\": \"71fa80210a9634ccc58f4bc13a4fbf863144a80c3130f21c8b6fe24fd872f221\",\n        \"size\": 300681407\n    },\n    \"HardBreakRoute_Town04_Route40_Weather14.tar.gz\": {\n        \"sha256\": \"bde6ea69ea858459bbaf038428ede02ec006bfc4481ecad320937b06873c761b\",\n        \"size\": 341353021\n    },\n    \"HardBreakRoute_Town04_Route41_Weather15.tar.gz\": {\n        \"sha256\": \"413e30c6bee8bf83e8d61f0fea2db29ddf21abba1b03b65100c9de369118d38a\",\n        \"size\": 308379371\n    },\n    \"HardBreakRoute_Town05_Route42_Weather8.tar.gz\": {\n        \"sha256\": \"ac4b370288690cff9bcbe7d865cfe5132287e5d85a5e8b1e59718c213291f10f\",\n        \"size\": 832662119\n    },\n    \"HardBreakRoute_Town05_Route43_Weather9.tar.gz\": {\n        \"sha256\": \"74197b957aaf0b63705f56bbb5742deac821c1901397f1b3cf81a8fcfe2aee00\",\n        \"size\": 307973685\n    },\n    \"HardBreakRoute_Town05_Route44_Weather18.tar.gz\": {\n        \"sha256\": \"a6778b30987c8ecffe0e0d14f14cc20a5d4b94fbed029c2075f57e9179062cd0\",\n        \"size\": 415438043\n    },\n    \"HardBreakRoute_Town06_Route45_Weather19.tar.gz\": {\n        \"sha256\": \"56c69a3544e9037f60d272f75b641223b40a446b0aa06fbea5f1349c248a425a\",\n        \"size\": 288096662\n    },\n    \"HardBreakRoute_Town06_Route46_Weather20.tar.gz\": {\n        \"sha256\": \"1049ee6bfd2c3b9b07fdf2ec86ba8b608551ccf87eca5392674c189e31915500\",\n        \"size\": 376398720\n    },\n    \"HardBreakRoute_Town07_Route47_Weather21.tar.gz\": {\n        \"sha256\": \"9722bdfeb6aa596a43d318ec918e65715bd0d2489cd5f84663ccee9feea424a4\",\n        \"size\": 466413936\n    },\n    \"HardBreakRoute_Town07_Route48_Weather22.tar.gz\": {\n        \"sha256\": \"6bfa30e317cf36e7255b7528a367537d0b3d0ce4c6051d5acb03a3926ba0d78e\",\n        \"size\": 508273219\n    },\n    \"HardBreakRoute_Town10HD_Route49_Weather23.tar.gz\": {\n        \"sha256\": \"c113220c5c318eafa027d1ec5c31e22b85e3038466dd3da7e1e6d9f33eaf2a94\",\n        \"size\": 296640328\n    },\n    \"HardBreakRoute_Town11_Route50_Weather23.tar.gz\": {\n        \"sha256\": \"b86886309a1deb3926d3050451eccd1d2d021c501b87f8a9b6c5b8571ea481ec\",\n        \"size\": 73424788\n    },\n    \"HardBreakRoute_Town12_Route51_Weather25.tar.gz\": {\n        \"sha256\": \"e57fdbfc59696e64d0b35e1b2dbf720c219e311f644fe22886510e3ba7871c8e\",\n        \"size\": 208795577\n    },\n    \"HardBreakRoute_Town12_Route52_Weather0.tar.gz\": {\n        \"sha256\": \"151fcd40cb31a1775162654e55fc953a4e261585b92ad1b419e0613232c2ac47\",\n        \"size\": 244441203\n    },\n    \"HardBreakRoute_Town12_Route53_Weather1.tar.gz\": {\n        \"sha256\": \"c456373dac8774f8cf18d9d49382bb1642a9ec9ce1b9ff571a56c4c45e6401a2\",\n        \"size\": 248506847\n    },\n    \"HardBreakRoute_Town13_Route1337_Weather26.tar.gz\": {\n        \"sha256\": \"82cf4c0d376409119e8819740363eb444c1e4508330f29128aeae8c3cde15a08\",\n        \"size\": 876427546\n    },\n    \"HardBreakRoute_Town13_Route1338_Weather26.tar.gz\": {\n        \"sha256\": \"3ab5bb988949c2cfb6258b4ac89f96af78e3c0b6d271bbed8017b89035c314b0\",\n        \"size\": 864328697\n    },\n    \"HardBreakRoute_Town13_Route1339_Weather26.tar.gz\": {\n        \"sha256\": \"65adf467d6b291061e803361b23139066c7569a0a15be67973201f888c10a3ce\",\n        \"size\": 850970855\n    },\n    \"HardBreakRoute_Town13_Route1340_Weather26.tar.gz\": {\n        \"sha256\": \"1b341dade11d0b509e18f3e9043e49ca5838ce64b072024e4af73f7acd3f5e79\",\n        \"size\": 347234021\n    },\n    \"HardBreakRoute_Town13_Route1341_Weather26.tar.gz\": {\n        \"sha256\": \"6660d72f918d4c91ef568b73ee3832827d9798712fe432bbaa1f49eddaa60718\",\n        \"size\": 1247146940\n    },\n    \"HardBreakRoute_Town13_Route54_Weather2.tar.gz\": {\n        \"sha256\": \"894101d8eb24d77c62c2fe53a38158f52b6712b95fc5fb15fddf055c10fe12e5\",\n        \"size\": 473644750\n    },\n    \"HardBreakRoute_Town13_Route55_Weather3.tar.gz\": {\n        \"sha256\": \"b4f9fe5a1d59a89aeff60c27eaa065e37e531a91fb0e710929ebbd7991f2a71e\",\n        \"size\": 515994279\n    },\n    \"HardBreakRoute_Town13_Route56_Weather3.tar.gz\": {\n        \"sha256\": \"0a42e021f4895c8d3ca578c74ec6d715aabd0dbc96c27171c765f6fe4520363b\",\n        \"size\": 463089266\n    },\n    \"HardBreakRoute_Town15_Route57_Weather5.tar.gz\": {\n        \"sha256\": \"0dfab2d87eba5538d7200952ddf14a1fa3224b68cff5cd4369bc09b665dcb3b9\",\n        \"size\": 924983641\n    },\n    \"HardBreakRoute_Town15_Route58_Weather6.tar.gz\": {\n        \"sha256\": \"f2d75918f8928785afb834fc17867aeaddaa856eeefb06da3dbad20369943487\",\n        \"size\": 578407693\n    },\n    \"HardBreakRoute_Town15_Route59_Weather7.tar.gz\": {\n        \"sha256\": \"e4796db18c1afeadd141c4141516c18bf815e1d9c2440f27d46ebf6ef8eb8e65\",\n        \"size\": 3010262100\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1128_Weather10.tar.gz\": {\n        \"sha256\": \"a8c2c8d0d51e97f41849c7b6c61fd1c697f7413e9612291bf9c8591fec16ead1\",\n        \"size\": 425816580\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1129_Weather11.tar.gz\": {\n        \"sha256\": \"8661eb7cd39944cb8fcdaa5e5d38f541ce392c960c02daace056891ad2b68548\",\n        \"size\": 350329598\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1130_Weather12.tar.gz\": {\n        \"sha256\": \"447d12c4396d846e6170b49f3bcbe7c4d60e41f0da5b36044b8f86315b43de7b\",\n        \"size\": 449329760\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1131_Weather13.tar.gz\": {\n        \"sha256\": \"6e08487ec8c55e277a2fb5cbf1ce7b353491a43d77bd1088fe9184d091edd601\",\n        \"size\": 410631063\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1132_Weather14.tar.gz\": {\n        \"sha256\": \"e59439c4ba8ac41355dc2fe1c35074e589f356867f81b09578217c827f05f08a\",\n        \"size\": 443730002\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1133_Weather15.tar.gz\": {\n        \"sha256\": \"9d2effd8b0790b6537a26a7eb081f5cb8e63a92a31efb499136979a2d138e20f\",\n        \"size\": 419049952\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1134_Weather8.tar.gz\": {\n        \"sha256\": \"dfb88d713854ef3bff30bfe08cac4eccf458b58bcca8b2dfb01a3e5c26bcc638\",\n        \"size\": 521969129\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1135_Weather9.tar.gz\": {\n        \"sha256\": \"9aab5d6bb3ca9161a2447f2c7941dd8419536767533810cc97774f855c027a83\",\n        \"size\": 492960174\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1136_Weather18.tar.gz\": {\n        \"sha256\": \"25ec6411830f62713fe15c9d5e4e8d1a649db70a0a3b2232bf191b7cc7e8e1cf\",\n        \"size\": 427688466\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1137_Weather19.tar.gz\": {\n        \"sha256\": \"b67b3fcc89d0fe80f9e10b6c34eb2098f29447c6e09b2b5595e435ee47ce91aa\",\n        \"size\": 239755082\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1138_Weather20.tar.gz\": {\n        \"sha256\": \"ea7822760f5685674701c198cdcd4fec58b550cb37798708d135e4a968f5e8fb\",\n        \"size\": 192261842\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1139_Weather21.tar.gz\": {\n        \"sha256\": \"c828b6f685279d77024f918f63a328fec8bb3b7fcb4d292426ef69f403d93a4b\",\n        \"size\": 288781374\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1140_Weather22.tar.gz\": {\n        \"sha256\": \"47f23b5d9011934545d54f599fcdf7ca9f5187dfd9a497ac7be04a69e7b62e7c\",\n        \"size\": 380509810\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1141_Weather23.tar.gz\": {\n        \"sha256\": \"d053c286b40dbf93b8873557491f8433f46a1a9db61682c17ba222411429feb6\",\n        \"size\": 431591635\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1142_Weather23.tar.gz\": {\n        \"sha256\": \"a6d8ba12e99420d7714cb6639b9fc3603f0e2dc93cf7a5c52dcfd47c6e95dc4e\",\n        \"size\": 342418533\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1143_Weather25.tar.gz\": {\n        \"sha256\": \"f813dc3c158562151f6645ca5173d48cafaca9bbfa0294d957a1dd6056a02d4e\",\n        \"size\": 163288807\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1144_Weather0.tar.gz\": {\n        \"sha256\": \"9f8e92a41e360ba2a133e2e1a87a293d82cd6b49a66eda89fbb4e68d696cb58a\",\n        \"size\": 406530516\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1145_Weather1.tar.gz\": {\n        \"sha256\": \"fb98c2cced547d0617936d1b23ca7fbf2d6417d3c9a407e0120a307d06b9c760\",\n        \"size\": 653206340\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1146_Weather2.tar.gz\": {\n        \"sha256\": \"9e78a50ae33a5ff0cc00859a64b64d68aac55aa6c44b5ec45f009b332c11c7db\",\n        \"size\": 611959081\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1147_Weather3.tar.gz\": {\n        \"sha256\": \"e216ec4ff33f7dcebd1a032ddcf29ed977e494bdd676e53bb78f57e23b91ce9b\",\n        \"size\": 592577667\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1151_Weather7.tar.gz\": {\n        \"sha256\": \"117d938e563fc25df97b9b5408c9fb05b53ad9f231697a99c5c99660314a06a9\",\n        \"size\": 584021303\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1152_Weather8.tar.gz\": {\n        \"sha256\": \"ddacdbf3707c75bb7c5f78bc679ff28b1d0b0f6e5d8a6ef4a61d697e56ecd90c\",\n        \"size\": 346135203\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1153_Weather9.tar.gz\": {\n        \"sha256\": \"55fed76506e3656205d2570f000b86908b49c5b07a1ec5810dcfc711051ec070\",\n        \"size\": 343429218\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1154_Weather10.tar.gz\": {\n        \"sha256\": \"0085a25b93b82b26457b103902f5f478ade33059a4c782c363ed47e7c83051e5\",\n        \"size\": 370819790\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1155_Weather11.tar.gz\": {\n        \"sha256\": \"dda873652d36f9e49fce1112bd67a4675e52e68c5d64786e037993a29a33370e\",\n        \"size\": 449368590\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1156_Weather12.tar.gz\": {\n        \"sha256\": \"ff51ba2312c57713f068fd23c781def7c3edcb6ad9fc43514ea5f886e6c06112\",\n        \"size\": 139208951\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1157_Weather13.tar.gz\": {\n        \"sha256\": \"0e8d29e3290d33fb4e2fbe5f1f9d1db9885b4c8a7bf6bcd4cc890adc49141056\",\n        \"size\": 167057772\n    },\n    \"HazardAtSideLane_Town03_Route105_Weather22.tar.gz\": {\n        \"sha256\": \"e3314913aa5b9e8372720a2d0a350d109acffb9d2713d5609f3a2eeb150d382c\",\n        \"size\": 91200165\n    },\n    \"HazardAtSideLane_Town03_Route106_Weather23.tar.gz\": {\n        \"sha256\": \"5c4d08f7e59c158232366d46fb05f86b36ada71f0ba7fabe6081ec408cbe3287\",\n        \"size\": 175342898\n    },\n    \"HazardAtSideLane_Town04_Route164_Weather8.tar.gz\": {\n        \"sha256\": \"25142dbcdb17a4969fdc844c45d14b6372141f7985bdc82cd6eb4c11e6f6a242\",\n        \"size\": 226620307\n    },\n    \"HazardAtSideLane_Town05_Route222_Weather0.tar.gz\": {\n        \"sha256\": \"a034ddbef5c3d12a53a065b372f34b2b2b4026fb23f4091abe01bddd9598a9ff\",\n        \"size\": 284488502\n    },\n    \"HazardAtSideLane_Town05_Route223_Weather15.tar.gz\": {\n        \"sha256\": \"2fb3ea8862bc2d1a4d064828deb65b8513edafa7b57988b2ac2c7d7fa1d86015\",\n        \"size\": 284760379\n    },\n    \"HazardAtSideLane_Town05_Route263_Weather3.tar.gz\": {\n        \"sha256\": \"9e744f26f20bc29531c947b1ffc84d47049d27e4d6c433a67b364bc91da827e1\",\n        \"size\": 264883778\n    },\n    \"HazardAtSideLane_Town06_Route283_Weather23.tar.gz\": {\n        \"sha256\": \"96c3fedc802d72113d103501f5a6680238c4d1f86ca86702df6d6ffa9290ef75\",\n        \"size\": 207194553\n    },\n    \"HazardAtSideLane_Town06_Route329_Weather9.tar.gz\": {\n        \"sha256\": \"e2f3dedd9ca8d2a785c7afbf7ac7406488f191bda98e175ce4fa00cffaaf9891\",\n        \"size\": 210842578\n    },\n    \"HazardAtSideLane_Town10HD_Route373_Weather9.tar.gz\": {\n        \"sha256\": \"ec5f0053fb77e909a71740e761088976fe9a3afab0b4117b7c6f1583bcf79d2c\",\n        \"size\": 217312677\n    },\n    \"HazardAtSideLane_Town12_Route1506_Weather0.tar.gz\": {\n        \"sha256\": \"d1d6b540d23bbeb84e151a3bd66fa2c7c18b2b0e255e3738cb3d1d7f10e58128\",\n        \"size\": 396237938\n    },\n    \"HazardAtSideLane_Town12_Route1507_Weather1.tar.gz\": {\n        \"sha256\": \"a374133780220809c19f77aedf5f80796a381e326055111e95adb6cd7d87912b\",\n        \"size\": 544755357\n    },\n    \"HazardAtSideLane_Town12_Route1508_Weather2.tar.gz\": {\n        \"sha256\": \"f2278d092fd0db9a6468dfed713269496f6c027041aaea2fd4a51d77c2c07ecb\",\n        \"size\": 521535007\n    },\n    \"HazardAtSideLane_Town12_Route1512_Weather7.tar.gz\": {\n        \"sha256\": \"789a46bb0c0d54406c61ee96dfa0b5281e060482aee3b518e6028d7806ab6a64\",\n        \"size\": 338689368\n    },\n    \"HazardAtSideLane_Town12_Route1515_Weather12.tar.gz\": {\n        \"sha256\": \"e744fdd1047b5f4c3ed8f833c52516b45b89203d63a9846e05c05cc15bc09c64\",\n        \"size\": 390757691\n    },\n    \"HazardAtSideLane_Town12_Route1516_Weather13.tar.gz\": {\n        \"sha256\": \"a00eceb9f0085e044fb6965cb4900676a6f2be39c7232275b26e15daab7c037f\",\n        \"size\": 403911498\n    },\n    \"HazardAtSideLane_Town12_Route1517_Weather14.tar.gz\": {\n        \"sha256\": \"37f6e4bcdb51e0f05b076f55873f60649eb8dd0bbdd98a524a41d7bece0d8270\",\n        \"size\": 456694330\n    },\n    \"HazardAtSideLane_Town12_Route1518_Weather15.tar.gz\": {\n        \"sha256\": \"d8d63717f25a22f0ac80daffd20a7d1455a13f8ba1d8f09f257eadf98b831ecd\",\n        \"size\": 260719936\n    },\n    \"HazardAtSideLane_Town12_Route1519_Weather8.tar.gz\": {\n        \"sha256\": \"1b843e567f17c595effc3008c4e4cd1a53334064d741a8216c3fc9482055fbc2\",\n        \"size\": 223474540\n    },\n    \"HazardAtSideLane_Town12_Route1520_Weather9.tar.gz\": {\n        \"sha256\": \"3e595fa1139ea4714d494885a7b5e5a8c13bdaa5dab36fde1bd0857c7d1843e2\",\n        \"size\": 150569458\n    },\n    \"HazardAtSideLane_Town12_Route1521_Weather18.tar.gz\": {\n        \"sha256\": \"2b60a9e072fb362da2fce90de08287335edafc3f471efc64ca4c9e3bc8b21e19\",\n        \"size\": 438379994\n    },\n    \"HazardAtSideLane_Town12_Route1523_Weather20.tar.gz\": {\n        \"sha256\": \"f5893cc367ef48dba179ef8e4d30e556289cf83a2cd75c13253a17f1f2ff3673\",\n        \"size\": 548086984\n    },\n    \"HazardAtSideLane_Town12_Route1524_Weather21.tar.gz\": {\n        \"sha256\": \"bdff5317f19aca58ddef6bf829019541d3faa05d36b20e3323f28546ab652cf8\",\n        \"size\": 466784189\n    },\n    \"HazardAtSideLane_Town12_Route1525_Weather22.tar.gz\": {\n        \"sha256\": \"4fdfe415b451f6ff7ad4b0a429a4d00c0afb1dd37af992b07e5dd41e77f3d05b\",\n        \"size\": 417041584\n    },\n    \"HazardAtSideLane_Town12_Route1526_Weather23.tar.gz\": {\n        \"sha256\": \"a0fb0d8f0ed8a07835da365b51575915c4625726c06a597f032adb93879e9721\",\n        \"size\": 178301097\n    },\n    \"HazardAtSideLane_Town12_Route1527_Weather25.tar.gz\": {\n        \"sha256\": \"4e59eb69f09b87fb7b282dac7efffaf316a379663a0050c46dcee1b289b27c5e\",\n        \"size\": 145113992\n    },\n    \"HazardAtSideLane_Town12_Route1528_Weather0.tar.gz\": {\n        \"sha256\": \"32fdfc2dd903e13372b592879d5f8ad7f3b498e34d6728c658ba729f3d68934b\",\n        \"size\": 200329720\n    },\n    \"HazardAtSideLane_Town12_Route1530_Weather2.tar.gz\": {\n        \"sha256\": \"f9a33645bd47bda7fde236a9ffb085e963edf666db6fbb7f0558ba003b146915\",\n        \"size\": 356818778\n    },\n    \"HazardAtSideLane_Town12_Route1532_Weather5.tar.gz\": {\n        \"sha256\": \"aee7c9bbcf8eed8027a98db5e2935a5dcc1faf5f7fa41a5a5eec6870d58b3078\",\n        \"size\": 461063902\n    },\n    \"HazardAtSideLane_Town12_Route1533_Weather6.tar.gz\": {\n        \"sha256\": \"6dc54cfc9f2861351649a0665c39c717466f6a4348bddfe834b719a57fac9116\",\n        \"size\": 262624979\n    },\n    \"HazardAtSideLane_Town12_Route1534_Weather7.tar.gz\": {\n        \"sha256\": \"0892dcdff24050656e34a98204b0515828565a4e04431e864b6e9308fa0ea625\",\n        \"size\": 222050817\n    },\n    \"HazardAtSideLane_Town12_Route1535_Weather10.tar.gz\": {\n        \"sha256\": \"7ba6f2fccfa617b8ead6311831d5be4426c25a7d3eee4550dcd2579e21f36220\",\n        \"size\": 512897769\n    },\n    \"HazardAtSideLane_Town12_Route1536_Weather11.tar.gz\": {\n        \"sha256\": \"fa088b816dfcd010b26b1997948540161344b772dff39dfb44e785f527a59f17\",\n        \"size\": 340589178\n    },\n    \"HazardAtSideLane_Town12_Route1537_Weather12.tar.gz\": {\n        \"sha256\": \"2255a2b689b495dc9f667fa8b12f70cb1ad2cafaa2f858fa56fa94260dba4749\",\n        \"size\": 385653352\n    },\n    \"HazardAtSideLane_Town12_Route1538_Weather13.tar.gz\": {\n        \"sha256\": \"9d35503d61374046991b9484c1eb6148bd98204c7e4089b2f6df4437ef5ff1c6\",\n        \"size\": 189348665\n    },\n    \"HazardAtSideLane_Town12_Route774_Weather20.tar.gz\": {\n        \"sha256\": \"7594fc879794caec6f5ae06a9c5d1072d9f716d241c9f266ac0475678d7ab3f9\",\n        \"size\": 195065723\n    },\n    \"HazardAtSideLane_Town12_Route775_Weather12.tar.gz\": {\n        \"sha256\": \"8a7d429b9db5f0ead543c9494719e3f0d44f7986a6ac9a2e0e19176321eb834f\",\n        \"size\": 136248619\n    },\n    \"HazardAtSideLane_Town12_Route777_Weather23.tar.gz\": {\n        \"sha256\": \"f7dfa2ca888b082051212b1d361729d722e1166b2e331318852e336f62be364c\",\n        \"size\": 217794450\n    },\n    \"HazardAtSideLane_Town12_Route915_Weather7.tar.gz\": {\n        \"sha256\": \"22cdf22c4c27e52f18038642bf1898f9758590f801afe25c69762372724addec\",\n        \"size\": 453141626\n    },\n    \"HazardAtSideLane_Town12_Route960_Weather20.tar.gz\": {\n        \"sha256\": \"3b6404b636d9356944aabb9dad7c59185d1fa92d9bc8d0141bbcd14929acdea0\",\n        \"size\": 185057089\n    },\n    \"HazardAtSideLane_Town12_Route961_Weather25.tar.gz\": {\n        \"sha256\": \"e2677146238d2ea90c361dc35581e8a1fbb6464c5b5fa1b92e5eb2ccf85d0f5d\",\n        \"size\": 391797619\n    },\n    \"HazardAtSideLane_Town13_Route558_Weather12.tar.gz\": {\n        \"sha256\": \"fa80431c4dcc48bf1a00d5b588a809439b91ac828de2ac5c951e77a005d0dd25\",\n        \"size\": 569779798\n    },\n    \"HazardAtSideLane_Town15_Route420_Weather3.tar.gz\": {\n        \"sha256\": \"19767b93980a0ff4b88448afb0e1e86781e6ab4b3160ba808a4b0a4a875decf6\",\n        \"size\": 415545207\n    },\n    \"HazardAtSideLane_Town15_Route421_Weather5.tar.gz\": {\n        \"sha256\": \"ec8bec5d900e310eabeded1e2308b90bac32fc4bf9b33b943158de57ab1fd9e1\",\n        \"size\": 216398878\n    },\n    \"HighwayCutIn_Town06_Route298_Weather20.tar.gz\": {\n        \"sha256\": \"53dfc41cf3a8cb052bf708344a4e5b7f80ee6ca26f3773acb8eb75c0313d4a54\",\n        \"size\": 151733498\n    },\n    \"HighwayCutIn_Town06_Route299_Weather13.tar.gz\": {\n        \"sha256\": \"95db330d5ee826d60afb80e034aefcf84a0f8e84ecb4ddb10c90277b986d8e3b\",\n        \"size\": 158819801\n    },\n    \"HighwayCutIn_Town06_Route300_Weather14.tar.gz\": {\n        \"sha256\": \"1e2528285647cdfcb01f73d177ccc2968507e81875139a4437860c812876afb2\",\n        \"size\": 151149491\n    },\n    \"HighwayCutIn_Town06_Route320_Weather8.tar.gz\": {\n        \"sha256\": \"0007fb5e7e0a82aca974124e5da7ce0e7d277f8439e0a18a62bebb8e5b2b10e8\",\n        \"size\": 186373828\n    },\n    \"HighwayCutIn_Town06_Route321_Weather9.tar.gz\": {\n        \"sha256\": \"c865d83e2ba6c38bdd2749100222edf6b2b019130e5337f8d1de0db2ed3ee468\",\n        \"size\": 161123191\n    },\n    \"HighwayCutIn_Town06_Route322_Weather10.tar.gz\": {\n        \"sha256\": \"9c1c9efe44f1b7c4045b5fb68b753961e4f04a22ee63330f114c924b360569f7\",\n        \"size\": 158556260\n    },\n    \"HighwayCutIn_Town12_Route1005_Weather9.tar.gz\": {\n        \"sha256\": \"2c82b35e0cc79a37aea2614d9c3b6721c87a3d896974532c8984de1cfb14fadb\",\n        \"size\": 195691936\n    },\n    \"HighwayCutIn_Town12_Route1006_Weather18.tar.gz\": {\n        \"sha256\": \"3f3f93f31c25ec6386800c5e2e9b66a1841c414eb5127987b16bad2d19cdd456\",\n        \"size\": 257587611\n    },\n    \"HighwayCutIn_Town12_Route1029_Weather15.tar.gz\": {\n        \"sha256\": \"52dace5ac23f4c77ec1ab9ecf4e4ba45aadc11ee2b4789dc1c5c73c1cdf9b990\",\n        \"size\": 190060406\n    },\n    \"HighwayCutIn_Town12_Route1042_Weather2.tar.gz\": {\n        \"sha256\": \"1a8463c90532bf7837a6848604ee868cdf2eb6abc89441025a21be34ebd00299\",\n        \"size\": 270215566\n    },\n    \"HighwayCutIn_Town12_Route1047_Weather7.tar.gz\": {\n        \"sha256\": \"940fdfeafc7d9c2e24c2c2b0b8cafe8146a46c60771be97792825a6b629da365\",\n        \"size\": 274957240\n    },\n    \"HighwayCutIn_Town12_Route1052_Weather12.tar.gz\": {\n        \"sha256\": \"6c93805559c28d88b0f1ccf075b9a715b6da3df2ae0a5776d7d29da92a962ad1\",\n        \"size\": 215805302\n    },\n    \"HighwayCutIn_Town12_Route849_Weather9.tar.gz\": {\n        \"sha256\": \"e74a836b3cea0b030691d295f781608838e05af4a8af0f22dd9a53b4159b1d0b\",\n        \"size\": 211207181\n    },\n    \"HighwayCutIn_Town12_Route850_Weather18.tar.gz\": {\n        \"sha256\": \"9062cb853d81faeb518ba01816e608bff4260e20cae05d93ffcd5c6ff65195e5\",\n        \"size\": 250885294\n    },\n    \"HighwayCutIn_Town12_Route851_Weather19.tar.gz\": {\n        \"sha256\": \"413845d54d6dc3581d3185d5a020df9041d4cf5e37154404d0435cfa75a8865d\",\n        \"size\": 163839691\n    },\n    \"HighwayCutIn_Town12_Route940_Weather3.tar.gz\": {\n        \"sha256\": \"71442c7cf787b5b681b768208a741fdb8a0903b0601651477faa5ece4694b0b8\",\n        \"size\": 280477833\n    },\n    \"HighwayCutIn_Town12_Route974_Weather12.tar.gz\": {\n        \"sha256\": \"8a5ee03adaffb80e9f7fb4891e8f6b322cd0559e50872c675f7a11ffeefd8708\",\n        \"size\": 235771270\n    },\n    \"HighwayCutIn_Town13_Route628_Weather3.tar.gz\": {\n        \"sha256\": \"31d381e1025e9416bc3c1f44fe3167f1514c949fbecd236b7b562761d902e7cc\",\n        \"size\": 518388280\n    },\n    \"HighwayCutIn_Town13_Route629_Weather5.tar.gz\": {\n        \"sha256\": \"6590438bda4f0b359ac411fdae540298e0cae39961923ea73f00fc4e9d76f57c\",\n        \"size\": 593847289\n    },\n    \"HighwayCutIn_Town13_Route630_Weather6.tar.gz\": {\n        \"sha256\": \"528fc6fdb199b0496af2a6cd65e7a3e26f99a678ad8c1bca401435266db89587\",\n        \"size\": 267973198\n    },\n    \"HighwayCutIn_Town13_Route631_Weather7.tar.gz\": {\n        \"sha256\": \"a7c380618399222f81238a88a932a5b32ef1e05b48ace75fb0f18a8e2eee35f6\",\n        \"size\": 567260227\n    },\n    \"HighwayCutIn_Town13_Route685_Weather9.tar.gz\": {\n        \"sha256\": \"7bc0b3551cc33fe4ac3b606ce3edc9edcf1c4f9a722d068c2d1c295a7276d2e4\",\n        \"size\": 481916100\n    },\n    \"HighwayCutIn_Town13_Route713_Weather11.tar.gz\": {\n        \"sha256\": \"e64920c44f847bb99236e443c85c036be3d2da84f685ba4bc07bf1e09a791529\",\n        \"size\": 462573401\n    },\n    \"HighwayCutIn_Town13_Route734_Weather6.tar.gz\": {\n        \"sha256\": \"9c4b0d590a7e9cfade5622c3ec9c19e1ac5ed550d727c577c4726d35b54b4b91\",\n        \"size\": 467018812\n    },\n    \"HighwayCutIn_Town13_Route745_Weather9.tar.gz\": {\n        \"sha256\": \"bf87f68bfa73262548d39ca0d3984e4a814da516a059a1c435135ab2354ddd72\",\n        \"size\": 200269292\n    },\n    \"HighwayCutIn_Town13_Route750_Weather22.tar.gz\": {\n        \"sha256\": \"0893436271d2469260a4ad616bf462faf08036a3b9cf377b91814f04d604967d\",\n        \"size\": 427593910\n    },\n    \"HighwayCutIn_Town13_Route751_Weather23.tar.gz\": {\n        \"sha256\": \"19a7796fd7774f7d65aa3803a816cb1d14894ee040856ad26eed76e3911cbecb\",\n        \"size\": 481171405\n    },\n    \"HighwayExit_Town06_Route291_Weather5.tar.gz\": {\n        \"sha256\": \"6de775b8ef13f2623477a256312f8bf60ab63bdb9714332883b856de81874517\",\n        \"size\": 164158235\n    },\n    \"HighwayExit_Town06_Route292_Weather14.tar.gz\": {\n        \"sha256\": \"a23e914453cf1de7ef32589018810114cb7429f15f0fc91b24a6d5d68e83185d\",\n        \"size\": 153066143\n    },\n    \"HighwayExit_Town06_Route293_Weather15.tar.gz\": {\n        \"sha256\": \"4a704cc95a67bf602c98867b3ef4f119c8e9796ef1076b183b981b47e2b6f9d4\",\n        \"size\": 165293726\n    },\n    \"HighwayExit_Town06_Route311_Weather25.tar.gz\": {\n        \"sha256\": \"c4b68226ff3d01a898542df23e88a247088ed280baaffb8108fb0c147be0f2de\",\n        \"size\": 169724168\n    },\n    \"HighwayExit_Town06_Route312_Weather0.tar.gz\": {\n        \"sha256\": \"15b7cd174377631558000b65ae20c05a2baa571fbdc11a51789b75e3752d3e92\",\n        \"size\": 194572909\n    },\n    \"HighwayExit_Town06_Route313_Weather1.tar.gz\": {\n        \"sha256\": \"b7bb7b89b7bcb984b96e14ae61cbbb11573e00f9e60cd2c72881fba923e0a6d2\",\n        \"size\": 218599862\n    },\n    \"HighwayExit_Town12_Route1000_Weather12.tar.gz\": {\n        \"sha256\": \"381934aa12530697cd30f1f6e2161e3c695ee7870e56b0ea0092bb232e39e481\",\n        \"size\": 302026823\n    },\n    \"HighwayExit_Town12_Route1028_Weather14.tar.gz\": {\n        \"sha256\": \"4e825e23fc774df3d0f58040e8a156231d400842c12ebf87aac3deef569519f5\",\n        \"size\": 326825269\n    },\n    \"HighwayExit_Town12_Route1041_Weather1.tar.gz\": {\n        \"sha256\": \"e7cba0ebc33c0e358610b4d8895cbecf8804fcac7455ac11890ea5e41f00baed\",\n        \"size\": 380503753\n    },\n    \"HighwayExit_Town12_Route1046_Weather6.tar.gz\": {\n        \"sha256\": \"0bc7597fae1d86a15740e065b3edecf3c43afb537caf196ad4882e5fb0e92c9c\",\n        \"size\": 282308514\n    },\n    \"HighwayExit_Town12_Route1051_Weather11.tar.gz\": {\n        \"sha256\": \"374faea6b3d14c4f9d06f78929fa633b4176a6273c081cbd948f6522bbb01fb7\",\n        \"size\": 206635940\n    },\n    \"HighwayExit_Town12_Route1324_Weather0.tar.gz\": {\n        \"sha256\": \"24d0b447c846bf323d40add015e11ed8be5ba268305d32095d4debd809cc9de9\",\n        \"size\": 280882766\n    },\n    \"HighwayExit_Town12_Route1326_Weather2.tar.gz\": {\n        \"sha256\": \"cb33c92a7c5139a331d0cec0600a838c4efdf5c4aa103b9033166e2fd39dd9e6\",\n        \"size\": 236611991\n    },\n    \"HighwayExit_Town12_Route1327_Weather3.tar.gz\": {\n        \"sha256\": \"283ad87d17f32f72267c711328deaf6046804ae34685db4c7aa6aaeb447077ce\",\n        \"size\": 321910963\n    },\n    \"HighwayExit_Town12_Route1331_Weather10.tar.gz\": {\n        \"sha256\": \"a950e71e875f01849494446221d8dbf856b1fc32b98203d5db662cdc78728419\",\n        \"size\": 299347172\n    },\n    \"HighwayExit_Town12_Route838_Weather6.tar.gz\": {\n        \"sha256\": \"750a0d1039c7a541b859c2ed067feb2f1d8e2b43d98e980f3957ee9bc4195b17\",\n        \"size\": 276948575\n    },\n    \"HighwayExit_Town12_Route841_Weather9.tar.gz\": {\n        \"sha256\": \"c2adbd750f7d831081d1e751b6fdd8df28cff27ae4a9b7bd6c4460d2e95ee62f\",\n        \"size\": 212020378\n    },\n    \"HighwayExit_Town12_Route937_Weather1.tar.gz\": {\n        \"sha256\": \"7b987b8d887855ace86495079dde76261ea4d4678a0e463265b086c687f2fb2b\",\n        \"size\": 252017031\n    },\n    \"HighwayExit_Town13_Route619_Weather21.tar.gz\": {\n        \"sha256\": \"9f61563f6207ab97188029764cb6817f4e53e116ddbfcb744a4b42b097fe6d09\",\n        \"size\": 564855216\n    },\n    \"HighwayExit_Town13_Route620_Weather22.tar.gz\": {\n        \"sha256\": \"981023a3cd45d9a96f761def5108c7d15a1f1ab8be1cc1061cd1b0d8090bfa68\",\n        \"size\": 555746704\n    },\n    \"HighwayExit_Town13_Route621_Weather23.tar.gz\": {\n        \"sha256\": \"ab2e8183228660562d36c3afae2dcd663cf29c7df612b1c6542d3a91ded3e489\",\n        \"size\": 539088118\n    },\n    \"HighwayExit_Town13_Route622_Weather23.tar.gz\": {\n        \"sha256\": \"96692eaa79ce967e27978d3b180d44384165f3d9fc71e7704490ef89a1a1e8a0\",\n        \"size\": 505837776\n    },\n    \"HighwayExit_Town13_Route683_Weather7.tar.gz\": {\n        \"sha256\": \"4867c7666a163aa26601a1c8c7719ec8e4f2d51aba19c6e00774ffde8afce849\",\n        \"size\": 640055057\n    },\n    \"HighwayExit_Town13_Route704_Weather2.tar.gz\": {\n        \"sha256\": \"93dcfa4f998411b1ba6da600942ebddf14855859bec654979ea970a4ae8c9a78\",\n        \"size\": 622456041\n    },\n    \"HighwayExit_Town13_Route705_Weather3.tar.gz\": {\n        \"sha256\": \"b45cc034c4ee286e7b80714ac1568e90f537f5d094365afc2b4d1f85732a2b0a\",\n        \"size\": 598470606\n    },\n    \"HighwayExit_Town13_Route706_Weather3.tar.gz\": {\n        \"sha256\": \"9a84830ca0dd2af27b6d8888f7e2479099a3720111fdd8b0b3500526fc5ae9b2\",\n        \"size\": 613606602\n    },\n    \"HighwayExit_Town13_Route744_Weather8.tar.gz\": {\n        \"sha256\": \"e33b46fd3afe06ba61bdf7b31e9ce408a1a2b66741bcdebb8867e652ba5a182a\",\n        \"size\": 581093636\n    },\n    \"HighwayExit_Town13_Route748_Weather20.tar.gz\": {\n        \"sha256\": \"2800b592d1fe1443f3158305a4ccb13b30d32546ea59e1c611e1048e9321f970\",\n        \"size\": 522237104\n    },\n    \"HighwayExit_Town13_Route749_Weather21.tar.gz\": {\n        \"sha256\": \"7b36fd3ca7167b9516ee20913607876914989e7b237898efbfdb448482c967e6\",\n        \"size\": 532024157\n    },\n    \"InterurbanActorFlow_Town06_Route294_Weather8.tar.gz\": {\n        \"sha256\": \"bd795fb3a0a9f1a46bfc1f0b2895b00d146497eddec9c728951b5966ac134dd0\",\n        \"size\": 157577277\n    },\n    \"InterurbanActorFlow_Town06_Route314_Weather2.tar.gz\": {\n        \"sha256\": \"6374b322b74f623131b2908f48ac2ba7ceaa1a87a41a302b2326f48fc7429356\",\n        \"size\": 182303493\n    },\n    \"InterurbanActorFlow_Town06_Route315_Weather3.tar.gz\": {\n        \"sha256\": \"e41e2d75c7a988b4739cc70c637b4bedcff95dcefc7a63f791157b32192ee27a\",\n        \"size\": 201981663\n    },\n    \"InterurbanActorFlow_Town06_Route316_Weather3.tar.gz\": {\n        \"sha256\": \"33e786805f7e0a8b7c22b084274f2010b6ebff19f17197f89b12e0402322283a\",\n        \"size\": 205647882\n    },\n    \"InterurbanActorFlow_Town12_Route1291_Weather1.tar.gz\": {\n        \"sha256\": \"67dc1a811a9ea683ed4abbb6f41acf601af32aeb44cc204ae58203bca708e981\",\n        \"size\": 172837480\n    },\n    \"InterurbanActorFlow_Town12_Route1292_Weather2.tar.gz\": {\n        \"sha256\": \"d2f1ce7efb2656d5c8773bc824988e3d1a6ea426e18f3bd0c957dd01b1e2550e\",\n        \"size\": 308904217\n    },\n    \"InterurbanActorFlow_Town12_Route1296_Weather7.tar.gz\": {\n        \"sha256\": \"534eccbe65b1da1c8a0e34fcba1c2f78f2c0c99624b17cb49ae48a326cd8be5b\",\n        \"size\": 241568780\n    },\n    \"InterurbanActorFlow_Town12_Route842_Weather10.tar.gz\": {\n        \"sha256\": \"275aedbfff5f7e9a21b0a776915fb9694b9f3b10e9421c9e498e320c097083a4\",\n        \"size\": 201093840\n    },\n    \"InterurbanActorFlow_Town12_Route843_Weather11.tar.gz\": {\n        \"sha256\": \"9e1dbd80397b91bac971cdbee512e93dcb333744e2f6d9c2366e1b67a295b781\",\n        \"size\": 190442832\n    },\n    \"InterurbanActorFlow_Town12_Route938_Weather2.tar.gz\": {\n        \"sha256\": \"985374f0522d2c4b370870cc9c9eeba5ef0ad3be7a2c271a53f611874df8626e\",\n        \"size\": 369301527\n    },\n    \"InterurbanActorFlow_Town13_Route623_Weather25.tar.gz\": {\n        \"sha256\": \"7cdf50f2be82d80409f696afeecbad10942182d6cc86c4056b2ee1b742dbd2bb\",\n        \"size\": 471936666\n    },\n    \"InterurbanActorFlow_Town13_Route707_Weather5.tar.gz\": {\n        \"sha256\": \"24951d3035229e3c9a3971db8983bf35f65bf17451a00497b9401cf3d593dd7e\",\n        \"size\": 240698662\n    },\n    \"InterurbanActorFlow_Town13_Route708_Weather6.tar.gz\": {\n        \"sha256\": \"36f93a38d3145b2c71016a95c7028ef573335b89b706367d46ab5e20d90fb046\",\n        \"size\": 231856399\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route301_Weather15.tar.gz\": {\n        \"sha256\": \"30eacbe14263fe60dd6d4b5125dfcef962b3047d218b0411424226168a6eb6f8\",\n        \"size\": 174702489\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route302_Weather21.tar.gz\": {\n        \"sha256\": \"c9f70427903d45444102ecf4a1af15198093aabd480e3c48d69720ab4d1bfb18\",\n        \"size\": 164693161\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route303_Weather22.tar.gz\": {\n        \"sha256\": \"3ed32f46487d2bbdea8df46c8ec0457bd0f20243ef431d30ac9f8df62d42cdd6\",\n        \"size\": 150997605\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route324_Weather2.tar.gz\": {\n        \"sha256\": \"b6059886c9bcc8d0717217041ba45698fc0a35a28075b153028ddd1d7222bf1a\",\n        \"size\": 203089829\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route325_Weather13.tar.gz\": {\n        \"sha256\": \"de58f8a81070747dc1e394f717c98f5b46da1e3ce861bb6074f9fc5c576b10f9\",\n        \"size\": 116510342\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route330_Weather18.tar.gz\": {\n        \"sha256\": \"1f0671726efafd675a0547ddfe10a5c6b50c385f0b072f5ea72993b154482dc7\",\n        \"size\": 173657365\n    },\n    \"InterurbanAdvancedActorFlow_Town06_Route331_Weather19.tar.gz\": {\n        \"sha256\": \"cf91506fb06549e52d15a56526103a6f1be14aaeb0c14639662c7137f7f0d6ab\",\n        \"size\": 113758993\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route1030_Weather8.tar.gz\": {\n        \"sha256\": \"891103fba4374089226192642573603763c53db2edc6c203f60bcf3babe161f6\",\n        \"size\": 251559541\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route1048_Weather8.tar.gz\": {\n        \"sha256\": \"b08501eb4db1ae1c0ab2e3a0ffa3dd2f81c601b6826d578bf2334dcdf9e92415\",\n        \"size\": 263912425\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route854_Weather22.tar.gz\": {\n        \"sha256\": \"30e9b2bb109d081883cef77db5a3a8d032caf89af4c4e394022c1ad9ad6bcb9a\",\n        \"size\": 217906205\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route634_Weather10.tar.gz\": {\n        \"sha256\": \"4bcb39877fe113c29b1f37b3a70e6a50694f11d6978caa445c5c59169bc5fa09\",\n        \"size\": 564406350\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route686_Weather10.tar.gz\": {\n        \"sha256\": \"fdd174e94313758ac720873370e470e35fae1013db65936757aa70f8a6180c96\",\n        \"size\": 597324406\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route715_Weather13.tar.gz\": {\n        \"sha256\": \"1bfd3e6c62a472b70267da495f5db8d3e3e17c5752ca2afb6a4790e41f602b7a\",\n        \"size\": 483936169\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route735_Weather7.tar.gz\": {\n        \"sha256\": \"7ab71cbbc562f9f6b52be980fccce49965a593e7e4bdc43e7775c900fa4837c4\",\n        \"size\": 573437846\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route753_Weather25.tar.gz\": {\n        \"sha256\": \"c2c5b89a3df71be8f606d644f04378fa81da6e748636c38890a16d845ad57748\",\n        \"size\": 481468083\n    },\n    \"InvadingTurn_Town02_Route95_Weather9.tar.gz\": {\n        \"sha256\": \"9011a0f41b008d4cc424e1fdc589d6cd482a2451cd30b1716a954cca2953be4b\",\n        \"size\": 78613306\n    },\n    \"InvadingTurn_Town02_Route99_Weather21.tar.gz\": {\n        \"sha256\": \"8a19225ee8b08d94d00c83a6e221b289cea48e78002edf7bbda3b7473f059e2d\",\n        \"size\": 74680692\n    },\n    \"InvadingTurn_Town04_Route217_Weather9.tar.gz\": {\n        \"sha256\": \"4825fef15cbd3a11229353ed3163c0eac8fec4a6efe0b27e8013bf2927f67287\",\n        \"size\": 172052489\n    },\n    \"InvadingTurn_Town05_Route230_Weather22.tar.gz\": {\n        \"sha256\": \"7bef6dd76fdea13fba7fedf79b9987d5b32da0c50e690caf9baabd935e7a00f9\",\n        \"size\": 152238928\n    },\n    \"InvadingTurn_Town05_Route231_Weather23.tar.gz\": {\n        \"sha256\": \"e5c3ec2dc7ee3d27dff862277c762312978a99701513b5aeed21dc88b6c33def\",\n        \"size\": 266824051\n    },\n    \"InvadingTurn_Town05_Route266_Weather6.tar.gz\": {\n        \"sha256\": \"ec74472570767e3b83b4538e165286c6d5900208bab792c81cc08c748134221e\",\n        \"size\": 204001087\n    },\n    \"InvadingTurn_Town12_Route796_Weather8.tar.gz\": {\n        \"sha256\": \"75348481b73549875ec9ba74849c82ef32e90fd909cf757b51f6a6b280f763af\",\n        \"size\": 364352186\n    },\n    \"InvadingTurn_Town12_Route924_Weather14.tar.gz\": {\n        \"sha256\": \"a7c13923272cc6d35508ade3e582956ff4af9d0489e1d54a27e3f0a7d3a8e7fb\",\n        \"size\": 262412245\n    },\n    \"InvadingTurn_Town12_Route925_Weather15.tar.gz\": {\n        \"sha256\": \"14fc6341f012fd1618dd3925bf527326917dfe0c8728c0cff8587fb9650b738b\",\n        \"size\": 265723429\n    },\n    \"InvadingTurn_Town13_Route575_Weather3.tar.gz\": {\n        \"sha256\": \"f8d2a45a76faf508109da5b2f1cc85ff090665ee8e0ba0f6eebd2086baac1881\",\n        \"size\": 437078350\n    },\n    \"InvadingTurn_Town13_Route578_Weather6.tar.gz\": {\n        \"sha256\": \"31362b4a1ac5ab29e8cccfdf569f088a49939196ad0b13e2e217e31bb411ab9f\",\n        \"size\": 219799888\n    },\n    \"InvadingTurn_Town15_Route434_Weather18.tar.gz\": {\n        \"sha256\": \"7ca4636a8346e7098c56a7681a97f6fad369f24b1df628cf1b5aa1464c180714\",\n        \"size\": 566872603\n    },\n    \"InvadingTurn_Town15_Route436_Weather20.tar.gz\": {\n        \"sha256\": \"997c457fb5a10657bfaaa80b2d7e3da458e9d9727fc9cee4bcdad46eb7dffba8\",\n        \"size\": 344452575\n    },\n    \"LaneChange_Town06_Route277_Weather9.tar.gz\": {\n        \"sha256\": \"d2008772dbd0bcf1b72c9cdd13ded83f18ed0271697be2efb7e6ba075ad3e27f\",\n        \"size\": 154428739\n    },\n    \"LaneChange_Town06_Route307_Weather21.tar.gz\": {\n        \"sha256\": \"8d62546eb29d8f0b8dc423ea41932241a92f0637f124b6591423f6a38df42aad\",\n        \"size\": 132357666\n    },\n    \"LaneChange_Town06_Route326_Weather3.tar.gz\": {\n        \"sha256\": \"bf474b84c0f9e192684a1056fab10d40b4630c3565fdd5aab4b8cb4cfd34ae28\",\n        \"size\": 185065636\n    },\n    \"LaneChange_Town12_Route756_Weather2.tar.gz\": {\n        \"sha256\": \"696fd57201e645ab40510f8787190fec6cb61320e5a3e362debe933707fd9a11\",\n        \"size\": 276947678\n    },\n    \"LaneChange_Town12_Route757_Weather10.tar.gz\": {\n        \"sha256\": \"eb51c5ff727554b3d26e4637b7b5397153e8095e8e88e2b178f28634344b82d1\",\n        \"size\": 267701316\n    },\n    \"LaneChange_Town12_Route892_Weather8.tar.gz\": {\n        \"sha256\": \"b4da35e3bf27c894ae1f7c5e33c18c6ff27c4672edd9baf3f4fb8060ab5428e4\",\n        \"size\": 306833289\n    },\n    \"LaneChange_Town12_Route894_Weather10.tar.gz\": {\n        \"sha256\": \"197694b47ad05319f06c6f6a5bc1e4970c9858f80df6eab4c0bdf654602fba2a\",\n        \"size\": 288321868\n    },\n    \"LaneChange_Town12_Route983_Weather5.tar.gz\": {\n        \"sha256\": \"345ad5c5be09aaccf650c1090c1edf1f6335d926794652772b12e4126ea5fe3f\",\n        \"size\": 287680743\n    },\n    \"LaneChange_Town12_Route984_Weather22.tar.gz\": {\n        \"sha256\": \"8100eb23a22b4676e1c7bd3aefa1b0ebcde75b0fba1c78ce6b8d0bd28ef35643\",\n        \"size\": 188265662\n    },\n    \"LaneChange_Town13_Route664_Weather14.tar.gz\": {\n        \"sha256\": \"b1b0e9409a98b44806c12e486fcb5ec330efbec50a38175e878349bb62f60603\",\n        \"size\": 192822156\n    },\n    \"LaneChange_Town13_Route725_Weather23.tar.gz\": {\n        \"sha256\": \"dda77b066aaeedbd047bb1e027b926857f5dc737d1d49af475c63893692b592b\",\n        \"size\": 636665567\n    },\n    \"LaneChange_Town13_Route726_Weather21.tar.gz\": {\n        \"sha256\": \"d1f41425a22d613013e4475b15307b71d4bacf0a90a14cc90a879f97faaa05ea\",\n        \"size\": 508714740\n    },\n    \"LaneChange_Town13_Route739_Weather25.tar.gz\": {\n        \"sha256\": \"15d6a1b52b7eae8f9434027f55987c9c613d301260e3bf52d4254a4a54151aeb\",\n        \"size\": 104946465\n    },\n    \"LaneChange_Town13_Route740_Weather0.tar.gz\": {\n        \"sha256\": \"102a6cf2d0a6fe1b45e57270f1f10b7dc0bd20956257090afafc9553f5c6a68b\",\n        \"size\": 127526816\n    },\n    \"LaneChange_Town13_Route743_Weather3.tar.gz\": {\n        \"sha256\": \"41589c44e74e729c7e58c2dd969d2eb077c9fb3c8b0d0c1ca39d01b4f91558f5\",\n        \"size\": 551507186\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1009_Weather21.tar.gz\": {\n        \"sha256\": \"a4f71b418d195865f4a18b7413d72adae56b7fd716e37b4e67e2141a952f9dc5\",\n        \"size\": 177065408\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1010_Weather22.tar.gz\": {\n        \"sha256\": \"ee2f7088e58077d061867b64eb35bb453991ddd362eb85e00e232e0a39150570\",\n        \"size\": 181762946\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1031_Weather9.tar.gz\": {\n        \"sha256\": \"f3b34a52824b8b4d87ee0737677a04c8442de7431fb2168eef058a865f6cf432\",\n        \"size\": 172061273\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1043_Weather3.tar.gz\": {\n        \"sha256\": \"a949ab12fd2ad8e07f2edbe024512b2b6daf0c13d347709b337b0b2d83d8659f\",\n        \"size\": 194731006\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1053_Weather13.tar.gz\": {\n        \"sha256\": \"77d09de242d4b0121c39221ba17a757fa8080ae3e15d5fc113bc6b3270e680d7\",\n        \"size\": 149100042\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1055_Weather15.tar.gz\": {\n        \"sha256\": \"1638c8c7f508bb6a7a3897713bb7d6b4976a1590ae06d3e08181d23eab3073c2\",\n        \"size\": 167566156\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1056_Weather8.tar.gz\": {\n        \"sha256\": \"ed283833aa7bb38254da73e259d1335feea8a4dbf6a6f70d8023a6654cb41277\",\n        \"size\": 176197073\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1057_Weather9.tar.gz\": {\n        \"sha256\": \"21a24f0f564e09444ce26184c543b5057080a5c8541414682ec1a99191cb102d\",\n        \"size\": 161360740\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1058_Weather18.tar.gz\": {\n        \"sha256\": \"2aaadb221f02a1ea5a2c112b022b96be2eb0ed113bbd340d84d45efde4aaf2bb\",\n        \"size\": 222302036\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1059_Weather19.tar.gz\": {\n        \"sha256\": \"2050a9f9c1364fed502c693790de1dc7a63c28ee03f4de6b4aeed28c7c1b4217\",\n        \"size\": 169671453\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route1060_Weather20.tar.gz\": {\n        \"sha256\": \"8ce792009a2f6f43fd371923982f500f7a1f76151639610a5fcd4fc3e480ec8a\",\n        \"size\": 173282984\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route856_Weather23.tar.gz\": {\n        \"sha256\": \"4ca5818f9b51afb5f480a231dcc4d76c785d0bd698f311b0463f8fdb68abfa35\",\n        \"size\": 180138822\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route857_Weather25.tar.gz\": {\n        \"sha256\": \"63a3083021b2b124b3a30c28ccdb7cc2581c1ce10934222a48bbd537713d9671\",\n        \"size\": 167911447\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route858_Weather0.tar.gz\": {\n        \"sha256\": \"d53cf4c027e42077b7f247424b55655818985c8845eea497a36f327b6f207c6a\",\n        \"size\": 231372706\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route859_Weather1.tar.gz\": {\n        \"sha256\": \"8a15a3513cb64b04ae056d888085f91d69ac59f35b73d392e0f7831ae2de48a4\",\n        \"size\": 225358341\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route941_Weather5.tar.gz\": {\n        \"sha256\": \"97271feebc94f934ea49d28f68fd41238e54f8358f1057dc1da170f6de92ace0\",\n        \"size\": 212523550\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route976_Weather14.tar.gz\": {\n        \"sha256\": \"7d3d79a4a14348050248c17b674edfa245212835bdabb2f1eac705e770cb57be\",\n        \"size\": 169759195\n    },\n    \"MergerIntoSlowTrafficV2_Town15_Route525_Weather5.tar.gz\": {\n        \"sha256\": \"546aca31520f4584fa95409ced6b7f43b468a9af9eb40891ead99a6c6e877030\",\n        \"size\": 476215896\n    },\n    \"MergerIntoSlowTraffic_Town06_Route317_Weather5.tar.gz\": {\n        \"sha256\": \"a8a2c52720a51eb071233a8c0d739dcee20826a3d55226a20e5ae545b5730481\",\n        \"size\": 217223866\n    },\n    \"MergerIntoSlowTraffic_Town12_Route1003_Weather8.tar.gz\": {\n        \"sha256\": \"2588662dac89e964e907d01d61d92d4db9537c3e773bb79f71e7f07ca8e8f888\",\n        \"size\": 351126413\n    },\n    \"MergerIntoSlowTraffic_Town12_Route1004_Weather8.tar.gz\": {\n        \"sha256\": \"536a3fc1350d417ac8a1c61c5445cfe07c7eac18d39b4c84d098abd173344367\",\n        \"size\": 307529384\n    },\n    \"MergerIntoSlowTraffic_Town12_Route844_Weather12.tar.gz\": {\n        \"sha256\": \"9ded261e3601d5e914c3dae1928036880db14612d3b65f71027de594857c3a49\",\n        \"size\": 288350127\n    },\n    \"MergerIntoSlowTraffic_Town12_Route845_Weather13.tar.gz\": {\n        \"sha256\": \"a30f54a114dc1b6c3e6a2c5c93563c641ee8b95f8bda19874a2f8f49f73eff48\",\n        \"size\": 244064838\n    },\n    \"MergerIntoSlowTraffic_Town12_Route973_Weather11.tar.gz\": {\n        \"sha256\": \"c1e02e4c9adf665b640d3db30539c3136c8e127c0bd1bb081162a750ba41f3a4\",\n        \"size\": 264881477\n    },\n    \"MergerIntoSlowTraffic_Town13_Route626_Weather2.tar.gz\": {\n        \"sha256\": \"c8bfd44852d03a8e962b9f7557a84a9f496cfc700efb475f87c76836038f303e\",\n        \"size\": 677692834\n    },\n    \"MergerIntoSlowTraffic_Town13_Route627_Weather3.tar.gz\": {\n        \"sha256\": \"4156f9ce54f9e8c600f34353605f1c0b0a335ca51e8330a612a1fa21843be77a\",\n        \"size\": 224479014\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route1022_Weather8.tar.gz\": {\n        \"sha256\": \"cd9c4aba8070ea91af956572c87c2b43cfc5efc5b328fded4daa140b480f82e0\",\n        \"size\": 183191914\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route1035_Weather21.tar.gz\": {\n        \"sha256\": \"80b0bfb1e1162f23290fd9a49bef1eb08d92a37d48f855b28a9ac0fbf548579a\",\n        \"size\": 171294962\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route888_Weather3.tar.gz\": {\n        \"sha256\": \"ad46eee70f3d2e80607fa8c9df3f474edbc288edf666952b1d1aad3af8424fa7\",\n        \"size\": 156738569\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route891_Weather7.tar.gz\": {\n        \"sha256\": \"1b0873aa068fb780d36560d3ccbaa42e9785709f212ff78e8ff8e090c4c18d7a\",\n        \"size\": 188090035\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route949_Weather13.tar.gz\": {\n        \"sha256\": \"d1f656e33d792983b6ef17ad2f2a4cfcbeb04ed14f8c7adf1868cb5929087379\",\n        \"size\": 76104449\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route982_Weather20.tar.gz\": {\n        \"sha256\": \"483654092014d6fecbbccf5fe5aa8e49e994e86486c406f2fa65366969ff8fae\",\n        \"size\": 181464485\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route660_Weather10.tar.gz\": {\n        \"sha256\": \"323991bed6147dcdde46248bc051e7f57c84f2c4b79eaf5d75b4bf09580eb181\",\n        \"size\": 123739662\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route661_Weather11.tar.gz\": {\n        \"sha256\": \"a9f4be00e695830873f9fb864b7449886273ec355d56d56ccad7d7f85de78c7b\",\n        \"size\": 196161756\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route722_Weather20.tar.gz\": {\n        \"sha256\": \"5f4b8a37fe404d43785a77057723f518285c96809493ebf98f72968d7ab8f1e4\",\n        \"size\": 127843299\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route723_Weather21.tar.gz\": {\n        \"sha256\": \"e35df0efb140ab6160d7e6d6bbe790aee4d9c88ce21c9968e6bcb73cf6800839\",\n        \"size\": 116663934\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route724_Weather22.tar.gz\": {\n        \"sha256\": \"c6c7f99474ac56c66e6c8656fdc2ed4121ac11fa2bb161d17cf02e001263ac01\",\n        \"size\": 116558252\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route738_Weather10.tar.gz\": {\n        \"sha256\": \"3897f23038bbb4780531bc1b5bedf504bbfc61c9a05e8e9967857587be28dd36\",\n        \"size\": 148447593\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town15_Route460_Weather18.tar.gz\": {\n        \"sha256\": \"33ace789985926e92e83295e4b6fe24fa67421a178add19f74013619f0b92916\",\n        \"size\": 130671742\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town15_Route499_Weather5.tar.gz\": {\n        \"sha256\": \"d48283973698587d96b3176e3aa06384bac62030ca9b186f699caa691dbebb6c\",\n        \"size\": 271586408\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town15_Route512_Weather18.tar.gz\": {\n        \"sha256\": \"c1bf4ae07359889887dfa555dab7abafaad2f10e7c699ec26365ce4f9501d7ff\",\n        \"size\": 116536811\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town15_Route532_Weather12.tar.gz\": {\n        \"sha256\": \"1ff5f037816f5603b5447b847448cfa8b48604d1fb47083e8831b7b53adc7226\",\n        \"size\": 257856199\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town15_Route533_Weather13.tar.gz\": {\n        \"sha256\": \"b2821e28f4f3fb30cb2d40c9123e9ffeb3e2295b6bcd6ed22044581feb787f69\",\n        \"size\": 255615682\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town15_Route537_Weather9.tar.gz\": {\n        \"sha256\": \"ae9b33df9ab73ea13c3b1e2634621b5988cf62dce25097f99d1664c3666021ab\",\n        \"size\": 82749024\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route122_Weather26.tar.gz\": {\n        \"sha256\": \"170e923defdef8e853cee03f77513b8903a3988988686f1e2fb35f2ea1a09091\",\n        \"size\": 157600405\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route123_Weather26.tar.gz\": {\n        \"sha256\": \"3060f583d29cbdb5bf2bbb8e5683bf6ff7eba50e0c943dddda674abfb69793ef\",\n        \"size\": 155598718\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route124_Weather26.tar.gz\": {\n        \"sha256\": \"a142bdab1320457a5ff8e624c8ce9b13179b2ef3babe5d5e10f0d1ace2b81bce\",\n        \"size\": 160666483\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route153_Weather26.tar.gz\": {\n        \"sha256\": \"df14e068d11b90908469cc15414374fd6dde83081041a77a637e7320c05a75f8\",\n        \"size\": 222202585\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route181_Weather15.tar.gz\": {\n        \"sha256\": \"c6c438f4d05ecea75617efd98baf4eb4cf02cb756dcfe8de00c5b93cbe1fc24e\",\n        \"size\": 1332988659\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route182_Weather26.tar.gz\": {\n        \"sha256\": \"180cbb09f98367ca703d691857de1c087c9584b4088cb5b301c831a2a32ab766\",\n        \"size\": 451746570\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route183_Weather1.tar.gz\": {\n        \"sha256\": \"99bf0aa82dc05d5355b1ce002a10a33e2383cfbbe5f2ff27f7ae9f401888989b\",\n        \"size\": 730148153\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route212_Weather26.tar.gz\": {\n        \"sha256\": \"addccabf39484e7cf3af470f15b311e92a04a407d4b8b65bfe28d072c2cf3897\",\n        \"size\": 319100778\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route238_Weather26.tar.gz\": {\n        \"sha256\": \"985d07b3669e8ec5fb0fb1182b3ab77019f1eff436de41b9c297c8fa1825daad\",\n        \"size\": 235576903\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route239_Weather26.tar.gz\": {\n        \"sha256\": \"5dc14728b5fb75c03ac207a290387b49b345c2ca4614ef72f6eea883aebf2c5d\",\n        \"size\": 645568686\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route240_Weather26.tar.gz\": {\n        \"sha256\": \"e3b50f92bc20629905b3562027025f4fc7f680f2fb670ea4fb7edce6226c320c\",\n        \"size\": 365141513\n    },\n    \"NonSignalizedJunctionLeftTurn_Town07_Route342_Weather3.tar.gz\": {\n        \"sha256\": \"5b1189d91933c681b243fe5516f383858bbe8531921342b86c47e6029c212a20\",\n        \"size\": 166172004\n    },\n    \"NonSignalizedJunctionLeftTurn_Town07_Route344_Weather6.tar.gz\": {\n        \"sha256\": \"213ba7c4c5f7f005ec7943a975eda3ac4448a503766e19a644874ba68721bec5\",\n        \"size\": 228514843\n    },\n    \"NonSignalizedJunctionLeftTurn_Town07_Route369_Weather18.tar.gz\": {\n        \"sha256\": \"42323e4105292d40c09d6841b8f894583e7915019af2836f22268afecabd8aef\",\n        \"size\": 370149774\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1350_Weather0.tar.gz\": {\n        \"sha256\": \"65402910129862e3b9f41a103b97185d2b56e3b4532f23a6179989602aeb7920\",\n        \"size\": 215128126\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1351_Weather1.tar.gz\": {\n        \"sha256\": \"bf5b1c3c6f59e189b2a2b70be2517223570da49258ba61f29d736527364b1775\",\n        \"size\": 239797759\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1352_Weather2.tar.gz\": {\n        \"sha256\": \"4d78242d637e0516bea5649a3c0731f4391535974d732e2fb4bd211f5eca4aa8\",\n        \"size\": 249285408\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1353_Weather3.tar.gz\": {\n        \"sha256\": \"a250748523fcb1b2aedd0d54c01fbffc5ca0037c7a4583853b0875f4aebf5db5\",\n        \"size\": 641498771\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1355_Weather6.tar.gz\": {\n        \"sha256\": \"b40b01924d328589ab2da6019531aacdaaae4c1da216d630bdae9eae7af3b27f\",\n        \"size\": 228349002\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1356_Weather7.tar.gz\": {\n        \"sha256\": \"04025997aa7fd52dd64e3968a3625a335c582b7eb62c4057f5af9b8f791e7e8e\",\n        \"size\": 225692722\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1357_Weather10.tar.gz\": {\n        \"sha256\": \"672b20591d3286490701c109afc4e31ba8a0cd278c290ce07f82abeb81915c26\",\n        \"size\": 209821452\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1358_Weather11.tar.gz\": {\n        \"sha256\": \"9a03c0b4bbe2d6cb0877ac0e38740233c0ca46814b054e1133a7c6be76a21df0\",\n        \"size\": 186722219\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1359_Weather12.tar.gz\": {\n        \"sha256\": \"571611fdb864a12e83ff95d2069879dae748147831b020cba0dc4fd8ea46c1e3\",\n        \"size\": 222402769\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1361_Weather14.tar.gz\": {\n        \"sha256\": \"8ba5a8ab15952cf2be852383a0b9f7d642239ffa478e5d9b83f9633e6588670b\",\n        \"size\": 221995532\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1362_Weather15.tar.gz\": {\n        \"sha256\": \"bfce2893b91cfed1567557bd09e533ab33f0e390cab22643a4b3d56f12f4dcbf\",\n        \"size\": 341181173\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route1363_Weather8.tar.gz\": {\n        \"sha256\": \"490bdd2ed0665700e46bba9f4a96882c4788a1f6ac6ac26125341ee917c92d8c\",\n        \"size\": 236828031\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route810_Weather10.tar.gz\": {\n        \"sha256\": \"63101044d67dbc7adaa497eeaba957c620a39b62b7f5000315e9b7a36ee4d0ca\",\n        \"size\": 226423311\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route812_Weather12.tar.gz\": {\n        \"sha256\": \"2bf89259609c89417662c0bd0bb911d815a7c97fb6b60e3a2b37f4922d495933\",\n        \"size\": 149562035\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route813_Weather26.tar.gz\": {\n        \"sha256\": \"7b7b9059951eb0fc37f4d9f491b85b9576be1d9ac20fbd1c1b332ddc11eddd7e\",\n        \"size\": 182312287\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route930_Weather20.tar.gz\": {\n        \"sha256\": \"cb9bd13c3c8f6fa37ade9515c95f685f2c8df58d0cf67fd76ab9f8cf16812b51\",\n        \"size\": 163210550\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route966_Weather3.tar.gz\": {\n        \"sha256\": \"a9c89e0e111ebcb8db9946fd12caccd14aff29be036417250682f50f3abafd07\",\n        \"size\": 157907409\n    },\n    \"NonSignalizedJunctionLeftTurn_Town13_Route592_Weather26.tar.gz\": {\n        \"sha256\": \"9d58f558c3277b52e30790cd4bb9f0781bf3df3d4dc198330d65336b877be9c0\",\n        \"size\": 150199193\n    },\n    \"NonSignalizedJunctionLeftTurn_Town13_Route593_Weather26.tar.gz\": {\n        \"sha256\": \"141c786fc99ab5e8dde5b5081bd1a5951ba0aca2d499f9e2348113af236b5016\",\n        \"size\": 270489805\n    },\n    \"NonSignalizedJunctionLeftTurn_Town13_Route594_Weather26.tar.gz\": {\n        \"sha256\": \"83222ed83d8b22208ba6f310aecef8f118dc9f8810094e49034b8f60fade8327\",\n        \"size\": 158228018\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route126_Weather18.tar.gz\": {\n        \"sha256\": \"e68420ff5cdfe7e29788eb44d1397f6307ffe4d03222c88cade68fad406254c9\",\n        \"size\": 173919693\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route184_Weather2.tar.gz\": {\n        \"sha256\": \"1b26d99c4d6d964dcf1081dab37dbbc946c37bbe8d0cfb99a88595d60b5ef52a\",\n        \"size\": 239752927\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route185_Weather9.tar.gz\": {\n        \"sha256\": \"299f058c1c20dab4e9ca3d1ffb7a8f5d694d3b6c28793610dd908b296865c5bf\",\n        \"size\": 269145176\n    },\n    \"NonSignalizedJunctionRightTurn_Town07_Route345_Weather14.tar.gz\": {\n        \"sha256\": \"51f705eca7d51887e32205626b2643b552849def68b4bac3f7a67afa297caf8c\",\n        \"size\": 223414665\n    },\n    \"NonSignalizedJunctionRightTurn_Town07_Route346_Weather15.tar.gz\": {\n        \"sha256\": \"df0e298294e2d98ed181a3e9c594f7dc35f767e00efe7c327e51b6139e5a13f4\",\n        \"size\": 309031402\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route1024_Weather10.tar.gz\": {\n        \"sha256\": \"63f0490b7cf225ccbff15d9769ef9cc672b91c6a6a927ed005360af30df742ed\",\n        \"size\": 123501634\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route815_Weather9.tar.gz\": {\n        \"sha256\": \"f425314417ca3d41c3fffa73303dbda944690399d343ef57c75bec42ca4f1af6\",\n        \"size\": 136537611\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route816_Weather15.tar.gz\": {\n        \"sha256\": \"0b2833dcf6b2a827f601dd317f49a770a889e3e8249bbd6f5d1e479a0969e374\",\n        \"size\": 358542153\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route817_Weather11.tar.gz\": {\n        \"sha256\": \"8da867b83cb827e51861f6a0042733e1f0694b6c260b837ae5b47def66160509\",\n        \"size\": 161948260\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route931_Weather21.tar.gz\": {\n        \"sha256\": \"1debb99ffc33817dec2f1c66e79f9c0e6ef3506695e2dcd1c4c7e4d47fe9611a\",\n        \"size\": 94436926\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route967_Weather25.tar.gz\": {\n        \"sha256\": \"f24367ecec6c0ccccc5f7777fe305d2ea8aa6fa81680066cb3f0ed19edd3bbbb\",\n        \"size\": 166272344\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route595_Weather11.tar.gz\": {\n        \"sha256\": \"3904a9a81f99d6afd4965ae5af21f92c9f23a2823f09e205e95f890ac181e594\",\n        \"size\": 171240191\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route596_Weather23.tar.gz\": {\n        \"sha256\": \"85c4ccbffedca7c7d4d6bd54643b9809c787ea96327a6617d06712e1f53f106b\",\n        \"size\": 95721522\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route598_Weather0.tar.gz\": {\n        \"sha256\": \"b686a0bdd77e2a6e8f7e28a388fbf10d4a321e13940404ca2a0076d3718ef323\",\n        \"size\": 108594308\n    },\n    \"OppositeVehicleRunningRedLight_Town03_Route119_Weather12.tar.gz\": {\n        \"sha256\": \"af3cb96a304eb27cfc663b1995457ed512929457e711fc2e13420c58a8c22675\",\n        \"size\": 97686170\n    },\n    \"OppositeVehicleRunningRedLight_Town03_Route120_Weather8.tar.gz\": {\n        \"sha256\": \"86c8b3556de29b7ec6e1f8499990733b9542a1076991a2e3a8cfcc207da44e8b\",\n        \"size\": 113901898\n    },\n    \"OppositeVehicleRunningRedLight_Town03_Route121_Weather13.tar.gz\": {\n        \"sha256\": \"3e8d4a48bffdd29a1b662cd2d3df8c27125f6477c0b87dafe76d9f7090cf0e8b\",\n        \"size\": 218194933\n    },\n    \"OppositeVehicleRunningRedLight_Town03_Route152_Weather22.tar.gz\": {\n        \"sha256\": \"284e0ad441c832fa29f827ca41484674f2bb3d4177e601a00957fab53e6b9f1d\",\n        \"size\": 103199684\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route178_Weather22.tar.gz\": {\n        \"sha256\": \"483446005c82580563479ab0d9a20f4fc70b5ed7714d1c8c91b4be9c578f5633\",\n        \"size\": 159377987\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route179_Weather14.tar.gz\": {\n        \"sha256\": \"cf1932acd0c3eb857e16aa5d4dcecda57cf70b5cde825a679713c53b50578470\",\n        \"size\": 154512523\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route180_Weather23.tar.gz\": {\n        \"sha256\": \"c2de54d2c404b0f8c9357b4d43edf5eda7a539270d8c46ca6f30b4b1a12ec1be\",\n        \"size\": 128624000\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route235_Weather1.tar.gz\": {\n        \"sha256\": \"ea31d450c6222ba249926a4f20d76ea650abe9dfecde3fea1459c0d21acb25b1\",\n        \"size\": 391759415\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route236_Weather10.tar.gz\": {\n        \"sha256\": \"0ee82eec0943a330f32d343baec6933038b98c2049738e0b0f51f64b4d8078aa\",\n        \"size\": 162937340\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route268_Weather8.tar.gz\": {\n        \"sha256\": \"56ea8a69dbb008c65b62b952c7330bd386625de107a6a176296f73f75176dea3\",\n        \"size\": 175380385\n    },\n    \"OppositeVehicleRunningRedLight_Town07_Route368_Weather3.tar.gz\": {\n        \"sha256\": \"fc5e76628da2b34f3976153a742c192402c838668af57af74dbf32c73170ed1a\",\n        \"size\": 213296837\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route807_Weather1.tar.gz\": {\n        \"sha256\": \"0af43794e9863cfacedd0df3867c00933e74acdfab4c2a9186222ccda0169153\",\n        \"size\": 120507715\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route809_Weather3.tar.gz\": {\n        \"sha256\": \"2815d9ec91548303bfefe0d210b284ebd7682eea229ff19271e9f524be340484\",\n        \"size\": 148724268\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route929_Weather19.tar.gz\": {\n        \"sha256\": \"cad093e8cbc4661473c579ad12c781b68740b3a0adb4d7ea9da9d628d0d81d98\",\n        \"size\": 144007435\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route990_Weather2.tar.gz\": {\n        \"sha256\": \"2b8d442a4b53e2468776b1f9078c1ee740560efc1149d08a523a86f6c0ebfd89\",\n        \"size\": 156889229\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route991_Weather3.tar.gz\": {\n        \"sha256\": \"c1f50ad4a99cd9d2927457f778d408d0ed48767e0648586c22dea94b00033481\",\n        \"size\": 225847400\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route587_Weather15.tar.gz\": {\n        \"sha256\": \"5cdb20b2765a174b4b1f31ac654c2f410d37acb5aadc37afd16917fd1b81e014\",\n        \"size\": 142880901\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route588_Weather8.tar.gz\": {\n        \"sha256\": \"70a28fc885bca13cdde306101bcffde6d0c89ebf93d32a511adfcc506095fdd4\",\n        \"size\": 155103226\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route590_Weather18.tar.gz\": {\n        \"sha256\": \"176c7419be5ae6f64b98736c6d3523e168131acb5ea03b581aea8e8c1f3e91b2\",\n        \"size\": 161694959\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route440_Weather23.tar.gz\": {\n        \"sha256\": \"baa86d146dde0aea6e19694499bd955d9ea58488afd6432da7a945b7e476f565\",\n        \"size\": 401563026\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route475_Weather7.tar.gz\": {\n        \"sha256\": \"93820986dd3acc6742de818a82358be8585577eb0fb78feb69698e45d0ec645c\",\n        \"size\": 413084044\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route128_Weather23.tar.gz\": {\n        \"sha256\": \"652951b3993c76d47c63a3053e93d8c8129c1309f0cace0b887506390955df6f\",\n        \"size\": 106129668\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route155_Weather25.tar.gz\": {\n        \"sha256\": \"02cb0751eb1082b33d95d7f36b835135b3a9c16369d50d3fa78bfb4e0073c56f\",\n        \"size\": 138210779\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route187_Weather5.tar.gz\": {\n        \"sha256\": \"eeabd9644f36fe62cc79868af7d21c021430d8eee67c8242e23624515cd3e4d0\",\n        \"size\": 794576550\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route188_Weather6.tar.gz\": {\n        \"sha256\": \"2b4fc6eb96a0fc352a66ecbb23d6b9f73392c89c36eba68293100d19296f88e7\",\n        \"size\": 764855087\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route189_Weather7.tar.gz\": {\n        \"sha256\": \"99d76f9244d0cba986ad599073556078bb23e5d97352686e8ca233b704f41632\",\n        \"size\": 231491277\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route214_Weather6.tar.gz\": {\n        \"sha256\": \"365ee55d62ffca565c5366240d1a889f714ef834bdae42d357d8de5f86288c9b\",\n        \"size\": 202060383\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route241_Weather7.tar.gz\": {\n        \"sha256\": \"93bc8bf34eacbde025173a63fe0bfaf50760a8ecc8843462c049e0e2aa53086f\",\n        \"size\": 274410640\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route242_Weather15.tar.gz\": {\n        \"sha256\": \"9e704995a330804f894b113dcf0b1b26f0c5893c38cb0c8d8e8310a44c6c1db5\",\n        \"size\": 205637120\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route243_Weather9.tar.gz\": {\n        \"sha256\": \"979bce4dbcd4227e791a95b4361de230cac5d22f65d7cdddbcc16a368bd22d38\",\n        \"size\": 189916897\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route270_Weather6.tar.gz\": {\n        \"sha256\": \"99071ad8f00a4721d2738d4c09618f81ccf0524b217b67900ad85b6d602f29bf\",\n        \"size\": 240282150\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route1025_Weather11.tar.gz\": {\n        \"sha256\": \"811937620dd6e386d2768379ba0f8ce1e14d87a006b775bb524f0ba842209f61\",\n        \"size\": 224958021\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route1038_Weather23.tar.gz\": {\n        \"sha256\": \"53d5e41dbb44af1730dfd7fe7677a6192dba452fea70c00ceff83e8d99354cb6\",\n        \"size\": 182314425\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route818_Weather12.tar.gz\": {\n        \"sha256\": \"33a2c030d1810cd42d8f54a077575e115500a00907c6e57ed26a8914d9f670d9\",\n        \"size\": 232821407\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route820_Weather14.tar.gz\": {\n        \"sha256\": \"e393681b8ab0292fb152c4f2a7b5a2db2663910c459c9c82cbf3e847a39abbc8\",\n        \"size\": 288515040\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route932_Weather22.tar.gz\": {\n        \"sha256\": \"2e64c21acd6eeb3c202fcd67b670c2cb69fe3f32a75466e339fc79423ba1a133\",\n        \"size\": 180993644\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route968_Weather6.tar.gz\": {\n        \"sha256\": \"47ab935dd3c235305c30be54e1614249d3f223df50d445ea9a88ad5413f4983e\",\n        \"size\": 226299482\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route994_Weather6.tar.gz\": {\n        \"sha256\": \"07ca8aa7c586764e77f75bd7cc66c530366d5f56308828077cb376d22bd0e902\",\n        \"size\": 219016269\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route995_Weather7.tar.gz\": {\n        \"sha256\": \"79d0a1a14dcbdb1d80e2f2dc868b49f665a9fef9993fe0ab5d9ad4fef0db46d9\",\n        \"size\": 237453197\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route600_Weather2.tar.gz\": {\n        \"sha256\": \"757a8e7415081447c2d172592723de194b05ad3fb9416e9fc215844e1dac58dc\",\n        \"size\": 177697783\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route601_Weather3.tar.gz\": {\n        \"sha256\": \"c3d6020043149dc183309b4abf85857d408eb6f2655cb403da98e0cc1e555f43\",\n        \"size\": 180447632\n    },\n    \"OppositeVehicleTakingPriority_Town15_Route477_Weather9.tar.gz\": {\n        \"sha256\": \"56e1bc9960734a44f38698921a128d6f4c401b0561d085484391ad7d00c0cb3c\",\n        \"size\": 318530800\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1158_Weather14.tar.gz\": {\n        \"sha256\": \"cd427aac3123d3531cd0d8bac586dc7ef33c8819e7829008a95d97348c245cd9\",\n        \"size\": 482530535\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1159_Weather23.tar.gz\": {\n        \"sha256\": \"9c07006c9cca2430fd1c3b20d0c81c654317e7e2ce3ac7b0df796cdfc2ff272c\",\n        \"size\": 393535967\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1161_Weather9.tar.gz\": {\n        \"sha256\": \"bb7dab4b662c2bf1f3a2f51921234be9f42be5c6c4f4d0146cbd2201d33a6b0f\",\n        \"size\": 223935830\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1163_Weather19.tar.gz\": {\n        \"sha256\": \"42ecbad7f7f3c91c6ba2a3d0b0bc704b9fdfbe49d1ea973dcfb4543da0962992\",\n        \"size\": 486446316\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1164_Weather20.tar.gz\": {\n        \"sha256\": \"0e8a521631aac411be24d7e5b436efeb1620175e2d3a6d69c02b224da4082c7c\",\n        \"size\": 259542565\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1165_Weather21.tar.gz\": {\n        \"sha256\": \"f1f7d13d9ba80c4c5734322afebba19ba16005a78176317677420edd27b9829c\",\n        \"size\": 248442683\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1166_Weather22.tar.gz\": {\n        \"sha256\": \"187e7b277053a9ecf8f06c2f7c323b98f3435838e527eb5e79a43fb487476607\",\n        \"size\": 275252053\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1167_Weather23.tar.gz\": {\n        \"sha256\": \"ad51fff98612387fdce8a1c24629cd52ffaab2926a5e6b39e4c5265bb5d52c41\",\n        \"size\": 575338142\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1168_Weather23.tar.gz\": {\n        \"sha256\": \"e5fdc922c1252dd9b99a791052f2d33c45a6d4db7e1a9ee11f2d8390d737c42f\",\n        \"size\": 234588500\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1169_Weather25.tar.gz\": {\n        \"sha256\": \"aea1cd8899542dc43e65a8177efd15eedc50994ebfa4eafa658e019ddac16c6a\",\n        \"size\": 293136258\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1171_Weather1.tar.gz\": {\n        \"sha256\": \"a156c6989c9f401508fb3def16032e1f234a646961307c60dbafe5f994c0492d\",\n        \"size\": 1002010949\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1172_Weather2.tar.gz\": {\n        \"sha256\": \"b1d842a8835670d09c359034b4bad30303648baca9d6af6d8f31673ef8afdf30\",\n        \"size\": 347207406\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1173_Weather3.tar.gz\": {\n        \"sha256\": \"71e6acffb5bb7e5e9bdf2b12986e4482733f773ab7ce8dff15b8cd5f6ad073cb\",\n        \"size\": 319307491\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1174_Weather3.tar.gz\": {\n        \"sha256\": \"d7e48fcfb1e18ed2fe1e89bd538a951f1cf7ab303cca84eda72f0e96fb2cc9c3\",\n        \"size\": 334388234\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1175_Weather5.tar.gz\": {\n        \"sha256\": \"87dba764c42cb0eb5ce6ee0e888e9083ce5471c2f19df4b6d5b7361ae4d16e58\",\n        \"size\": 743983813\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1178_Weather8.tar.gz\": {\n        \"sha256\": \"ae84b84158e6d579ad7585506f0bb9974cd02e08b1d0b6a4a57504f41c44c5d7\",\n        \"size\": 586363520\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1181_Weather11.tar.gz\": {\n        \"sha256\": \"51340fd1a65bf48d83414f5e64f1812b4e157eeab6c47a2a83784eac1f6a776e\",\n        \"size\": 721667751\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1182_Weather12.tar.gz\": {\n        \"sha256\": \"a2809fe95a03cbed463ac1c2ace574da114bc1eebbbddf2a44aa49359bbfa283\",\n        \"size\": 275180435\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1183_Weather7.tar.gz\": {\n        \"sha256\": \"6be36c23108e28e804aff2ab1a330948cd900339c3c845df1c7b578d7ca5491a\",\n        \"size\": 1168722927\n    },\n    \"ParkedObstacleTwoWays_Town13_Route1333_Weather26.tar.gz\": {\n        \"sha256\": \"45b8da367741b43f10bb440eb5569542c319ba03d16c0a51a10d5d8360699857\",\n        \"size\": 460310894\n    },\n    \"ParkedObstacleTwoWays_Town13_Route1334_Weather26.tar.gz\": {\n        \"sha256\": \"c62480dc25f6158e6f4ea748016b8f905cc255365d012146f1eb0f32a57ffd01\",\n        \"size\": 807145291\n    },\n    \"ParkedObstacleTwoWays_Town13_Route1335_Weather26.tar.gz\": {\n        \"sha256\": \"4000b0d27f1306bdf336e0539088d4c5508e4dfcb1e5af07aa9df5a7617e7694\",\n        \"size\": 447357779\n    },\n    \"ParkedObstacleTwoWays_Town13_Route1336_Weather26.tar.gz\": {\n        \"sha256\": \"688c6915d5323a45cc838fa202a8bd31a44e966e66599f805f531de5992cdfdc\",\n        \"size\": 616478401\n    },\n    \"ParkedObstacle_Town03_Route103_Weather25.tar.gz\": {\n        \"sha256\": \"d472e4dd6c8f19a01c965bb8871878ae1e263bfe8b5c95e31379c11ba8861557\",\n        \"size\": 95515824\n    },\n    \"ParkedObstacle_Town03_Route147_Weather0.tar.gz\": {\n        \"sha256\": \"e84cbe5f1c7cfafc26aad111a55f3c816773e46fa5c73a6696a4d198bd7d79b1\",\n        \"size\": 131815830\n    },\n    \"ParkedObstacle_Town03_Route157_Weather1.tar.gz\": {\n        \"sha256\": \"9e687d40a0a7e3990ddf1f58df7160abca006b7d65480b7d1f0f3c6fbb433ce2\",\n        \"size\": 141347413\n    },\n    \"ParkedObstacle_Town04_Route162_Weather6.tar.gz\": {\n        \"sha256\": \"858125180aa21468aec5697049ca629355e1a04829142041aa672cbeda798e56\",\n        \"size\": 317370488\n    },\n    \"ParkedObstacle_Town05_Route220_Weather12.tar.gz\": {\n        \"sha256\": \"c78f923d45325b0c2ceac60d3efe8efa6140d2c638e95e2f5da3a5c8ab697fc4\",\n        \"size\": 587632134\n    },\n    \"ParkedObstacle_Town05_Route221_Weather13.tar.gz\": {\n        \"sha256\": \"54f6b930f12c3beb9cd3bb7a2f6549227fc866d3b1725c1e7383c848dcd2f652\",\n        \"size\": 282506156\n    },\n    \"ParkedObstacle_Town05_Route262_Weather1.tar.gz\": {\n        \"sha256\": \"2167f418986b0ddfa79fafdb60e3872940d77d77e0d1940e890f78461fec0ab9\",\n        \"size\": 309129874\n    },\n    \"ParkedObstacle_Town05_Route273_Weather7.tar.gz\": {\n        \"sha256\": \"2134121041a77208a2ec1199ce5c2e097cac08e347a0ce3cd67909d7f40f03c7\",\n        \"size\": 311641955\n    },\n    \"ParkedObstacle_Town06_Route281_Weather21.tar.gz\": {\n        \"sha256\": \"f95844bdcd0b62ee3c984834dcb8052a3053c8f6dba6764e84b0b235c189b59e\",\n        \"size\": 241771866\n    },\n    \"ParkedObstacle_Town06_Route282_Weather22.tar.gz\": {\n        \"sha256\": \"d06fea63ead863561af4cd99016c07ddef270d6d85aacea07e4a565071bd14e2\",\n        \"size\": 174350658\n    },\n    \"ParkedObstacle_Town06_Route309_Weather23.tar.gz\": {\n        \"sha256\": \"c32f526b70c42edebc01b55ed578de07e9496f9830f8593411e63bce0520a4a0\",\n        \"size\": 213668943\n    },\n    \"ParkedObstacle_Town06_Route328_Weather8.tar.gz\": {\n        \"sha256\": \"6cf6bf06d30d7dfcc8dd7f5496fa4c7daaf92af1b517699af37b230606d88788\",\n        \"size\": 224218241\n    },\n    \"ParkedObstacle_Town10HD_Route371_Weather7.tar.gz\": {\n        \"sha256\": \"78464d659875f8b2bc5901c763bc9ba154c3eaf021196f4d6077d9ef17c705e4\",\n        \"size\": 264725091\n    },\n    \"ParkedObstacle_Town10HD_Route372_Weather8.tar.gz\": {\n        \"sha256\": \"b99e3f9ea5a8925435438feb074ee35a040f7bfc8de6a9f52f59899634f7b732\",\n        \"size\": 241697687\n    },\n    \"ParkedObstacle_Town11_Route395_Weather5.tar.gz\": {\n        \"sha256\": \"3e966dfd56aa999f5850f0e9fb552347bea6dc46898b64f6deaa76e491f240f6\",\n        \"size\": 99662965\n    },\n    \"ParkedObstacle_Town12_Route770_Weather8.tar.gz\": {\n        \"sha256\": \"2b63b3bb2124dcca3370c84886ce4f5390fbaec9976cc5b83ddb73e009b02eff\",\n        \"size\": 225259718\n    },\n    \"ParkedObstacle_Town12_Route771_Weather9.tar.gz\": {\n        \"sha256\": \"f3ff321975fe88e765dc2d80614c6758b939967dc907136c82edb39f18eddd2c\",\n        \"size\": 143272357\n    },\n    \"ParkedObstacle_Town12_Route772_Weather11.tar.gz\": {\n        \"sha256\": \"425064e8a2dee5126ac2f12a03547206e7a8212b4a9efc48d3a70da813dd82e4\",\n        \"size\": 131307783\n    },\n    \"ParkedObstacle_Town12_Route773_Weather19.tar.gz\": {\n        \"sha256\": \"7e672603850456b96c9906ddc7c59294089077abb368daa1524cab703bca1267\",\n        \"size\": 330329941\n    },\n    \"ParkedObstacle_Town12_Route958_Weather22.tar.gz\": {\n        \"sha256\": \"8e0b01dbe8e67780d1d66f0d359bceb612e61e4c3adb1edc270122cf73ac97dc\",\n        \"size\": 269022668\n    },\n    \"ParkedObstacle_Town12_Route959_Weather23.tar.gz\": {\n        \"sha256\": \"b5c297aecab1310a1cae0eaa120280199e1ce967feba1aa44bafc15d581d7eb0\",\n        \"size\": 153037259\n    },\n    \"ParkedObstacle_Town13_Route553_Weather11.tar.gz\": {\n        \"sha256\": \"085a0b97927cd2c6678c577500fdda30129e098977b346ba739e951484f15b9f\",\n        \"size\": 501598203\n    },\n    \"ParkedObstacle_Town13_Route554_Weather12.tar.gz\": {\n        \"sha256\": \"2401803605a5c6db600a6010eb2a8ca9cb7da4ec929c638193dfcffc3fdd0d6d\",\n        \"size\": 164003255\n    },\n    \"ParkedObstacle_Town13_Route555_Weather9.tar.gz\": {\n        \"sha256\": \"b583606e56bea23708b4ff2ac4e9fc0c0eabeff6a6f4885a1f3fb70ca5515c95\",\n        \"size\": 583501922\n    },\n    \"ParkedObstacle_Town13_Route556_Weather10.tar.gz\": {\n        \"sha256\": \"745a4583a3cb5d5811c5f63a6e6876bf1473ca60ca043c8975c584fd2b48b39b\",\n        \"size\": 238884711\n    },\n    \"ParkedObstacle_Town15_Route415_Weather25.tar.gz\": {\n        \"sha256\": \"8e5070cece9260f0a9d5a645ce9a3914eafcf2b373380dd1a658c0c974ae772a\",\n        \"size\": 615396231\n    },\n    \"ParkedObstacle_Town15_Route417_Weather1.tar.gz\": {\n        \"sha256\": \"231e50e43bc7dd9a2e4b0007abe7264a152d8fdd0d829c37862977420e467699\",\n        \"size\": 701231429\n    },\n    \"ParkedObstacle_Town15_Route418_Weather2.tar.gz\": {\n        \"sha256\": \"953567d3367748d0dd657b42e6e99e8ebc27a683154650e4f02ed0432e27608a\",\n        \"size\": 429190268\n    },\n    \"ParkingCrossingPedestrian_Town12_Route758_Weather3.tar.gz\": {\n        \"sha256\": \"7ad0e03656e450871f5ccc51d8c7db6a9df33332800e7a2c779db9498a8b16cb\",\n        \"size\": 905366099\n    },\n    \"ParkingCrossingPedestrian_Town12_Route759_Weather5.tar.gz\": {\n        \"sha256\": \"925385e0acf1d4aa798d93798a4fd329b25df88acc9e790f2dfe6d7be252fcfe\",\n        \"size\": 213481964\n    },\n    \"ParkingCrossingPedestrian_Town12_Route760_Weather6.tar.gz\": {\n        \"sha256\": \"2b85dc673c8f8c1280b4f26169a23cc1950754fd5e375c6dc5e698d8dbc647d3\",\n        \"size\": 156242354\n    },\n    \"ParkingCrossingPedestrian_Town12_Route761_Weather7.tar.gz\": {\n        \"sha256\": \"dbb61f8cf2bd131f8ad0adfae3d01598777d70186a2f63add1e36a0bfafb3d7f\",\n        \"size\": 220522651\n    },\n    \"ParkingCrossingPedestrian_Town12_Route896_Weather12.tar.gz\": {\n        \"sha256\": \"108531a92e4324d56d1b94d1a103ec5c7e5f64aa50350574581fa863810b9f13\",\n        \"size\": 156894753\n    },\n    \"ParkingCrossingPedestrian_Town12_Route897_Weather13.tar.gz\": {\n        \"sha256\": \"3811bdb5c9efdc84ff0e0a38723f5841e6ede5d6d844f7e7b4e4d3327661fc2e\",\n        \"size\": 435875764\n    },\n    \"ParkingCrossingPedestrian_Town12_Route898_Weather14.tar.gz\": {\n        \"sha256\": \"c07d7483e3d4ec8d246c7a49105d7228c68fba7ff503d1c89ba6551b6d1a71f9\",\n        \"size\": 162362089\n    },\n    \"ParkingCrossingPedestrian_Town12_Route899_Weather15.tar.gz\": {\n        \"sha256\": \"d3e07c505a5db5dc02375464b63aa8765422baaf69e716bff1665bfafe9b1d76\",\n        \"size\": 195665848\n    },\n    \"ParkingCrossingPedestrian_Town12_Route952_Weather8.tar.gz\": {\n        \"sha256\": \"688c664910adca54235e406f57afadd350b724fd6c24388789b6c465fe41cb57\",\n        \"size\": 190679683\n    },\n    \"ParkingCrossingPedestrian_Town12_Route953_Weather9.tar.gz\": {\n        \"sha256\": \"bd271093ff4031f8082e3a404412191e527aa7fffe1f0cda4bcbdc2dcb98cb94\",\n        \"size\": 131188732\n    },\n    \"ParkingCrossingPedestrian_Town13_Route545_Weather25.tar.gz\": {\n        \"sha256\": \"10db9ea1c4abf1f40767a3faa140780802ac578312bb182d0dd977098102d70d\",\n        \"size\": 176560829\n    },\n    \"ParkingCrossingPedestrian_Town13_Route668_Weather18.tar.gz\": {\n        \"sha256\": \"a64d622c253cfd78cb66513bc06e71332411bf8b5225760479937a7a46b8a558\",\n        \"size\": 408175419\n    },\n    \"ParkingCrossingPedestrian_Town13_Route669_Weather19.tar.gz\": {\n        \"sha256\": \"33873d3edbbc7999771ee8056ac726fb636dcff4e812879d13a6f873a8ab950a\",\n        \"size\": 527770501\n    },\n    \"ParkingCrossingPedestrian_Town13_Route727_Weather25.tar.gz\": {\n        \"sha256\": \"abd25608bf9846f36beabdbc013027477c00060d582b20bb5229f5c1ee9f9b1d\",\n        \"size\": 180325591\n    },\n    \"ParkingCrossingPedestrian_Town13_Route728_Weather0.tar.gz\": {\n        \"sha256\": \"eebe2f2a20b4c1a18a1b390c11bc58133638c572cfc337145bf54349e5593b9f\",\n        \"size\": 249052115\n    },\n    \"ParkingCrossingPedestrian_Town15_Route403_Weather13.tar.gz\": {\n        \"sha256\": \"53c951d9a8927e8c3e4f0efd6cfaf0cf3110e6debd297119933f2763f50e4cb1\",\n        \"size\": 253822166\n    },\n    \"ParkingCrossingPedestrian_Town15_Route405_Weather15.tar.gz\": {\n        \"sha256\": \"bf32a0e9217c029673dc9bf1622b000ab8ef6c0e7383bd62e716cc74a177510a\",\n        \"size\": 370797636\n    },\n    \"ParkingCrossingPedestrian_Town15_Route462_Weather20.tar.gz\": {\n        \"sha256\": \"518d523ed8a29056c2164b488228c904810024cc135804ae419b1e3a4e98aff0\",\n        \"size\": 393328697\n    },\n    \"ParkingCrossingPedestrian_Town15_Route513_Weather19.tar.gz\": {\n        \"sha256\": \"ac3e9e690e645e619961588c3f0912dcd21a631b0bdecef58c0b1e3f27f69496\",\n        \"size\": 1547087124\n    },\n    \"ParkingCrossingPedestrian_Town15_Route514_Weather0.tar.gz\": {\n        \"sha256\": \"a79e11caf067fcee41341e3f58ca2c688519226a308d6acd8b2dd8a8a01ca387\",\n        \"size\": 491668646\n    },\n    \"ParkingCutIn_Town12_Route1300_Weather13.tar.gz\": {\n        \"sha256\": \"3acd2b02318783b1aed345859845e716e8e93a3150f75c4dfbb64570f3189a14\",\n        \"size\": 163973527\n    },\n    \"ParkingCutIn_Town12_Route1301_Weather14.tar.gz\": {\n        \"sha256\": \"90bc4db9254be2654f32c054a4a7c09ceeba7c1686c0bf1377828885802cba5d\",\n        \"size\": 179297363\n    },\n    \"ParkingCutIn_Town12_Route1302_Weather15.tar.gz\": {\n        \"sha256\": \"2b78dc2c253231db2761fffd8a6ec76de12c822085491a019cedc2bbe2b1280f\",\n        \"size\": 196525634\n    },\n    \"ParkingCutIn_Town12_Route1303_Weather8.tar.gz\": {\n        \"sha256\": \"6decfbcc673a192703f2dc2ade4ddc99217832749a508ec597f452ccede7fe20\",\n        \"size\": 162860447\n    },\n    \"ParkingCutIn_Town12_Route1304_Weather9.tar.gz\": {\n        \"sha256\": \"107c34344ea8f3eabf342a62954e20ebe509a194b6dc40dcf88734f3f6267d9d\",\n        \"size\": 152204658\n    },\n    \"ParkingCutIn_Town12_Route1310_Weather0.tar.gz\": {\n        \"sha256\": \"c2f02b139e55a97d4193f29583d1ba7b8a03fa30327430299b460d6dd426c34c\",\n        \"size\": 225139382\n    },\n    \"ParkingCutIn_Town12_Route1311_Weather1.tar.gz\": {\n        \"sha256\": \"bab7effb6ec3e5afaeeea230fe2ff92628fe576658d963b963699090b6236b3a\",\n        \"size\": 217929599\n    },\n    \"ParkingCutIn_Town12_Route1312_Weather2.tar.gz\": {\n        \"sha256\": \"be65b43d98db0b0017ad5c66ab867c5b01253e4f6743dffb6bae33a7fbcfcc85\",\n        \"size\": 212398410\n    },\n    \"ParkingCutIn_Town12_Route1313_Weather3.tar.gz\": {\n        \"sha256\": \"99ceec02c1037f1242994a323b6a886943a45f3bbcdb0ee82a640f0ec3cf86a9\",\n        \"size\": 170967903\n    },\n    \"ParkingCutIn_Town12_Route1314_Weather5.tar.gz\": {\n        \"sha256\": \"5fc6174b0902bb66b92f852a905f057cbae7b1b69c9f84136376cd31d31e095c\",\n        \"size\": 210343782\n    },\n    \"ParkingCutIn_Town12_Route1315_Weather6.tar.gz\": {\n        \"sha256\": \"f2da487a00e67ebc777386230a3761856320ff915198690291d461227cbd1bd4\",\n        \"size\": 187914234\n    },\n    \"ParkingCutIn_Town12_Route762_Weather8.tar.gz\": {\n        \"sha256\": \"74da5b0370d4edf6d50e05e96654553540aa9da2076b4c0db2b29b1d8373ec9b\",\n        \"size\": 211725259\n    },\n    \"ParkingCutIn_Town12_Route763_Weather9.tar.gz\": {\n        \"sha256\": \"06c36861bf17de48cc6a2e9ed1e049f7f0c539b0fffff48271600682a73beab2\",\n        \"size\": 331830740\n    },\n    \"ParkingCutIn_Town12_Route764_Weather10.tar.gz\": {\n        \"sha256\": \"bc2f62a343f54c78914663b36027eea43e64e3d4c1381836e4bec1920a13bd63\",\n        \"size\": 214134854\n    },\n    \"ParkingCutIn_Town12_Route765_Weather11.tar.gz\": {\n        \"sha256\": \"c440b6538e7e187a446013843001312ecc930d774a52385faf94b7f566802bdb\",\n        \"size\": 148771721\n    },\n    \"ParkingCutIn_Town12_Route900_Weather19.tar.gz\": {\n        \"sha256\": \"0ea604f0fc71fa7df7b9ad3e9f14c27a2d673ca4c058eed7a896d5cef6aa524c\",\n        \"size\": 471787638\n    },\n    \"ParkingCutIn_Town12_Route901_Weather9.tar.gz\": {\n        \"sha256\": \"cd159bbc2182bf38f35b05ea6a38ee1cd760fc96cb3fd5b9ff09158f9d4185a3\",\n        \"size\": 154915854\n    },\n    \"ParkingCutIn_Town12_Route902_Weather18.tar.gz\": {\n        \"sha256\": \"3f4daf945897938dfb63348f7596bda6bc1f1818090321baf44823c825459851\",\n        \"size\": 192033306\n    },\n    \"ParkingCutIn_Town12_Route903_Weather20.tar.gz\": {\n        \"sha256\": \"50611e6b2b3e665c98b84980ca2d49e7c41c14cf8e01f8ffed8a880f9fa8809a\",\n        \"size\": 194043424\n    },\n    \"ParkingCutIn_Town12_Route954_Weather18.tar.gz\": {\n        \"sha256\": \"2afd9a2cd4ddad31928fed35baa1ad932975e5ce64d4b0f09a6fe1d67a09823c\",\n        \"size\": 454054301\n    },\n    \"ParkingCutIn_Town12_Route955_Weather19.tar.gz\": {\n        \"sha256\": \"64de6a7d82b1785a256b0467b1004986e9b35554d144e6ba0c0522bf83105c61\",\n        \"size\": 220751743\n    },\n    \"ParkingCutIn_Town13_Route1342_Weather0.tar.gz\": {\n        \"sha256\": \"0995b929bb2d3a8f70e9b4619a433256b00b89271bdb3170cd460f55b11673a0\",\n        \"size\": 207092429\n    },\n    \"ParkingCutIn_Town13_Route1343_Weather1.tar.gz\": {\n        \"sha256\": \"98ec376f27890f4dc11ff2dd3787f7784f2b7588a37a7876c12ec359edef1bde\",\n        \"size\": 204824312\n    },\n    \"ParkingCutIn_Town13_Route1344_Weather2.tar.gz\": {\n        \"sha256\": \"060706ef50a3509b6d98c449e4087b348c58eb482fb833f72b2afdfc5f44ec1d\",\n        \"size\": 238463650\n    },\n    \"ParkingCutIn_Town13_Route1345_Weather3.tar.gz\": {\n        \"sha256\": \"df0940b205582ac23b30d0f9c68fef2b285a9de7046a111c529d288cae37125e\",\n        \"size\": 229828432\n    },\n    \"ParkingCutIn_Town13_Route1346_Weather5.tar.gz\": {\n        \"sha256\": \"6aabfec0d10d317d3b57eb161ff3cb13c87edfba55a0151b2762b425c4c7ea4d\",\n        \"size\": 345154292\n    },\n    \"ParkingCutIn_Town13_Route1347_Weather6.tar.gz\": {\n        \"sha256\": \"6d171944e927cc01691f15729ccdd2cb7b21d6fe09daaacbc9a339d2dbd1db22\",\n        \"size\": 209099363\n    },\n    \"ParkingCutIn_Town13_Route1348_Weather7.tar.gz\": {\n        \"sha256\": \"c387c9d1fd0fffc39778d271f7dac6a434944f69e16df2f9d5f9e3e7903e6839\",\n        \"size\": 253436684\n    },\n    \"ParkingCutIn_Town13_Route1349_Weather10.tar.gz\": {\n        \"sha256\": \"db8d2b648069171c56f694edf6511aa046379b305e082c02dc2df58ce8b64a92\",\n        \"size\": 325114249\n    },\n    \"ParkingCutIn_Town13_Route546_Weather0.tar.gz\": {\n        \"sha256\": \"f6dcb3b5c1101c9dd161c03a51fc60e68a120217e04e090eb7c2fde06319cc7d\",\n        \"size\": 244097919\n    },\n    \"ParkingCutIn_Town13_Route547_Weather1.tar.gz\": {\n        \"sha256\": \"3e40fd8841d5a6897abea94a17b2ae6f6dbcd0a47d7efdf73761f13be57f0958\",\n        \"size\": 207590563\n    },\n    \"ParkingCutIn_Town13_Route548_Weather2.tar.gz\": {\n        \"sha256\": \"b123cdb34e4dc1de34b764d02fae54c45f7e20757afdf6a0083f82da5dc8fbf1\",\n        \"size\": 328242714\n    },\n    \"ParkingCutIn_Town13_Route549_Weather3.tar.gz\": {\n        \"sha256\": \"08291d28196b95602f98ee77590a1b8a4bd9f469ea5c890c75228b232eb34bd4\",\n        \"size\": 711423576\n    },\n    \"ParkingCutIn_Town13_Route670_Weather20.tar.gz\": {\n        \"sha256\": \"9a82f807bb5992d4d5f6a83078180d7074ab987a33189b74934a0051cc019c22\",\n        \"size\": 179059695\n    },\n    \"ParkingCutIn_Town13_Route671_Weather21.tar.gz\": {\n        \"sha256\": \"3e2bdcf29aa02f6f072fd548a420a090d2b191b346edb2956c4eb52ea0fe1580\",\n        \"size\": 300704290\n    },\n    \"ParkingCutIn_Town13_Route672_Weather22.tar.gz\": {\n        \"sha256\": \"bb39d11661a16d2b8ea4f1b23bbc8205c8356f4f93823e99deb785cb3a42726f\",\n        \"size\": 169871866\n    },\n    \"ParkingCutIn_Town13_Route696_Weather20.tar.gz\": {\n        \"sha256\": \"5720773eb921d93e0f8068cfe91c8d2f55125c537bca196bd0bd37ee0fa76334\",\n        \"size\": 187498023\n    },\n    \"ParkingCutIn_Town13_Route729_Weather1.tar.gz\": {\n        \"sha256\": \"2c331465f4affc97785e8f2ba0067e292d688ec8233a02c679aefd81d5ce5006\",\n        \"size\": 233007995\n    },\n    \"ParkingExit_Town12_Route1305_Weather18.tar.gz\": {\n        \"sha256\": \"36bf5b218ace2cd63c96b62f76c886476dbd962de5cb041f596df2739d6e054b\",\n        \"size\": 192536846\n    },\n    \"ParkingExit_Town12_Route1307_Weather20.tar.gz\": {\n        \"sha256\": \"a181a445079ae81d75165fb708650e64e15c896b578a4b8754885c1408cc26d7\",\n        \"size\": 149981334\n    },\n    \"ParkingExit_Town12_Route1308_Weather21.tar.gz\": {\n        \"sha256\": \"1c59345bc0cfcf0cbebd5f2a08d66e4c513d0660322138d4e93d77a72580e981\",\n        \"size\": 428773424\n    },\n    \"ParkingExit_Town12_Route1309_Weather22.tar.gz\": {\n        \"sha256\": \"5a3b6deddc648090540b584f9e353cf7d089bae868b836bd35ebd838029711f5\",\n        \"size\": 178313263\n    },\n    \"ParkingExit_Town12_Route1316_Weather0.tar.gz\": {\n        \"sha256\": \"fe2742ea5664b70ac8139c7774edca683e10567e3603620093453cea88c6e84a\",\n        \"size\": 200663665\n    },\n    \"ParkingExit_Town12_Route1318_Weather2.tar.gz\": {\n        \"sha256\": \"d2633798d962e241a1f3dbb9ace3ba6680dab51a7072a6bd7167cbcb98566972\",\n        \"size\": 178185934\n    },\n    \"ParkingExit_Town12_Route1319_Weather3.tar.gz\": {\n        \"sha256\": \"81e6335c0775e2b616689db2c57fc109311b5060f984d657ce5fe2995437b5d2\",\n        \"size\": 438910627\n    },\n    \"ParkingExit_Town12_Route1320_Weather5.tar.gz\": {\n        \"sha256\": \"563f2306a479e6b46013a21c7c80e74c26db15dbab9bee7ace14b1e9b28583b2\",\n        \"size\": 197803110\n    },\n    \"ParkingExit_Town12_Route1321_Weather6.tar.gz\": {\n        \"sha256\": \"42723d5c05c4f659990f5d75ce092e1135180a2b1b67d52239a63b720ee88f96\",\n        \"size\": 174604343\n    },\n    \"ParkingExit_Town12_Route1322_Weather7.tar.gz\": {\n        \"sha256\": \"3dc479ff220299eb380ea5c877339b09e5e3d626327eaf2d6c16e36905496041\",\n        \"size\": 193686163\n    },\n    \"ParkingExit_Town12_Route786_Weather6.tar.gz\": {\n        \"sha256\": \"79c3ca0e973746e825b78b907dbaf7f7dd29d5356b1447546d13410731867e12\",\n        \"size\": 192373313\n    },\n    \"ParkingExit_Town12_Route787_Weather7.tar.gz\": {\n        \"sha256\": \"5be91fb8a70379f94b01cee10dbe5b0af4723012562568a9e487b183b38d9b56\",\n        \"size\": 231059862\n    },\n    \"ParkingExit_Town12_Route788_Weather8.tar.gz\": {\n        \"sha256\": \"d1bc43122bb2726ce8f7ce81d65a9d03fd1bd9ee2ba1b89ec39edb793f226ecb\",\n        \"size\": 435462312\n    },\n    \"ParkingExit_Town12_Route789_Weather9.tar.gz\": {\n        \"sha256\": \"c1820e0fb14a636ff91c24a999927f2ce70d9ce9a24caa67489a3711a37a761d\",\n        \"size\": 136413212\n    },\n    \"ParkingExit_Town12_Route920_Weather10.tar.gz\": {\n        \"sha256\": \"b1eb2e15ce0f6cefc75fab58a887e1ec7c4b434a5893dce68ce7352362b0ef4e\",\n        \"size\": 175370496\n    },\n    \"ParkingExit_Town12_Route922_Weather12.tar.gz\": {\n        \"sha256\": \"1d70a167a904bb3e2e6129f937cb740d2cf67f0ecf96968fd864f3447b19302f\",\n        \"size\": 153840673\n    },\n    \"ParkingExit_Town12_Route923_Weather13.tar.gz\": {\n        \"sha256\": \"73bac14043ac05bfbfac746cc990f70601b508313164de1241fccb7ae8a1da48\",\n        \"size\": 157475379\n    },\n    \"ParkingExit_Town13_Route567_Weather21.tar.gz\": {\n        \"sha256\": \"2d07d5baa713ef762426df850b2208a55a12597fbe2e249aa86cc1ed318a604f\",\n        \"size\": 229308443\n    },\n    \"ParkingExit_Town13_Route568_Weather22.tar.gz\": {\n        \"sha256\": \"e296b2b834652588645f75bab4415e805ddd0342172beda9b3d186fc5a019446\",\n        \"size\": 178381928\n    },\n    \"ParkingExit_Town13_Route569_Weather23.tar.gz\": {\n        \"sha256\": \"787b39d59faf7320e8a358423993040ea1c1f58476a3ef49000c3ec791247b38\",\n        \"size\": 184506542\n    },\n    \"ParkingExit_Town13_Route570_Weather23.tar.gz\": {\n        \"sha256\": \"3fcbd824eb3de30230678c0b6c0c6b93f7cb1b67c65ed5c136be55ad0dc66662\",\n        \"size\": 195977159\n    },\n    \"ParkingExit_Town13_Route676_Weather0.tar.gz\": {\n        \"sha256\": \"3643cc12dfbcf4a67e524ace06a1e79e68d0e4849cc80092dc60cdb377b12133\",\n        \"size\": 259877946\n    },\n    \"ParkingExit_Town13_Route677_Weather1.tar.gz\": {\n        \"sha256\": \"bf1a2309a3422a1643ed978ee462f0c2395a577041711763aaa40d64a3cd2cbf\",\n        \"size\": 752522503\n    },\n    \"ParkingExit_Town13_Route678_Weather2.tar.gz\": {\n        \"sha256\": \"3868919aa910260714e3b57a04c533e1c2c111cd2fdf5fe02efd1966e79324c2\",\n        \"size\": 396649603\n    },\n    \"ParkingExit_Town13_Route697_Weather21.tar.gz\": {\n        \"sha256\": \"48013c1b7c4a394b0d3e3f5ef8b59b94bdc5ab9883f78f15e178ea5291cf0542\",\n        \"size\": 173965377\n    },\n    \"ParkingExit_Town13_Route731_Weather3.tar.gz\": {\n        \"sha256\": \"cf256f5524c18d2dc6ef661cc988b28ecdc68d19d6aafd4b6d6247b683c9e4e7\",\n        \"size\": 484916912\n    },\n    \"ParkingExit_Town13_Route732_Weather3.tar.gz\": {\n        \"sha256\": \"5811aede99ea5537a3e581ad67c4ebf6e358e39f34e5e66edb49ffd286e0a881\",\n        \"size\": 638103650\n    },\n    \"PedestrianCrossing_Town12_Route1013_Weather25.tar.gz\": {\n        \"sha256\": \"49960a9fb123ba6bd9ea69c1435285c5f255b9021a91c0907e05d56e61308b74\",\n        \"size\": 160068740\n    },\n    \"PedestrianCrossing_Town12_Route1014_Weather0.tar.gz\": {\n        \"sha256\": \"40826a8a1faece0073d7851cd73b84742faa833b4e1bde3585d1e1c64a3eb1b8\",\n        \"size\": 303478056\n    },\n    \"PedestrianCrossing_Town12_Route1033_Weather20.tar.gz\": {\n        \"sha256\": \"67dedd346791282414e397d1edafd5c847d6fd8a9627ca6d8d533007105e81cf\",\n        \"size\": 165266426\n    },\n    \"PedestrianCrossing_Town12_Route1045_Weather5.tar.gz\": {\n        \"sha256\": \"9cd68bc83dc141327472b05db697350f21e414bca872abe87334d54bf4c9dd28\",\n        \"size\": 382044587\n    },\n    \"PedestrianCrossing_Town12_Route864_Weather6.tar.gz\": {\n        \"sha256\": \"d2b679e96507c4f9485a44225fcb8d1ecd73be4b7331d816788b5432eb654990\",\n        \"size\": 704986654\n    },\n    \"PedestrianCrossing_Town12_Route865_Weather7.tar.gz\": {\n        \"sha256\": \"4bd51e0b4fa7f6d9c1b49e4aceb5f9715aa87a9c6078ff7e837be0d47b60685b\",\n        \"size\": 432250053\n    },\n    \"PedestrianCrossing_Town12_Route866_Weather8.tar.gz\": {\n        \"sha256\": \"a1388fef96e6bbd25bd180b328ebaa73b5186a50b82a05f8b9000f67ef70f68e\",\n        \"size\": 551493230\n    },\n    \"PedestrianCrossing_Town12_Route867_Weather9.tar.gz\": {\n        \"sha256\": \"58a726401dc7f27ef1999ecc0ef5a18e853cbb5893ee817eb26df774a13c81df\",\n        \"size\": 85890287\n    },\n    \"PedestrianCrossing_Town12_Route943_Weather7.tar.gz\": {\n        \"sha256\": \"ba8d4f6d3183476f7015ce4198093984ed29f7af204ec0a63463b23bb249cf4c\",\n        \"size\": 422692397\n    },\n    \"PedestrianCrossing_Town13_Route636_Weather12.tar.gz\": {\n        \"sha256\": \"0212c5038ea6a96033f48c57df316108b24746b7ac18196440a3a7d914217430\",\n        \"size\": 548961492\n    },\n    \"PedestrianCrossing_Town13_Route637_Weather13.tar.gz\": {\n        \"sha256\": \"d89a4ebf8e813957275317295b4fbc995a30b329779535305d41b2641d878f6b\",\n        \"size\": 173129285\n    },\n    \"PedestrianCrossing_Town13_Route638_Weather14.tar.gz\": {\n        \"sha256\": \"7a9507c3e9e5adf3d18e2e8ee2d98f8776309158ce9a32e63902e87f5c174046\",\n        \"size\": 469050270\n    },\n    \"PedestrianCrossing_Town13_Route687_Weather11.tar.gz\": {\n        \"sha256\": \"45c85b1fa3796e2395a7a0addef42b017201bb38c0c9277880b6ecf4ae1e2a31\",\n        \"size\": 95993933\n    },\n    \"PedestrianCrossing_Town13_Route716_Weather14.tar.gz\": {\n        \"sha256\": \"ff533dfc1159d0f3b5c2404f1c597801220bfe200607eb9bad859d60dfe568ba\",\n        \"size\": 528659607\n    },\n    \"PedestrianCrossing_Town13_Route718_Weather8.tar.gz\": {\n        \"sha256\": \"8fe8d1ec73e5b68cbd451d267d9d8a4434577019bdfa082871183b316ccce3a2\",\n        \"size\": 620818658\n    },\n    \"PedestrianCrossing_Town13_Route736_Weather8.tar.gz\": {\n        \"sha256\": \"e160e46b571199f6c4e00b138675bb8198b6fcdd738e174fbdd6288748486055\",\n        \"size\": 634072221\n    },\n    \"PedestrianCrossing_Town13_Route747_Weather19.tar.gz\": {\n        \"sha256\": \"00601dbd6b8838f7ab0de878b138a995bd7f0e30f23efddc063aad63818b0ddd\",\n        \"size\": 809131844\n    },\n    \"PedestrianCrossing_Town15_Route448_Weather6.tar.gz\": {\n        \"sha256\": \"6f547f5fc787dde79da087808579f48f47bb6ef4de2fca6a2e48e369d18d2760\",\n        \"size\": 1014723314\n    },\n    \"PedestrianCrossing_Town15_Route506_Weather12.tar.gz\": {\n        \"sha256\": \"2b3266336b4e580c1c1306d9f0cbbd951d959fd2e4d00c133c7223a87a15a665\",\n        \"size\": 1113447581\n    },\n    \"PedestrianCrossing_Town15_Route526_Weather6.tar.gz\": {\n        \"sha256\": \"9a2c33a8d338160462ef237e2b6a1faea1f868d87e94ae2ccd3bc929d4d72982\",\n        \"size\": 1033439353\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route1019_Weather5.tar.gz\": {\n        \"sha256\": \"c320cad4c4e24ed315aff1b70348bcf66b318a24b1be0f273e25949705dfcdf8\",\n        \"size\": 218224282\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route1020_Weather6.tar.gz\": {\n        \"sha256\": \"bcf516c81c0ffe652ebcaa337dc67d48ea47d9e83b70f1208f0b52a476007721\",\n        \"size\": 188616741\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route1034_Weather20.tar.gz\": {\n        \"sha256\": \"0b20a7b8b8518676c2f94076bdc6df31561467b6084b961d69622fc393be745d\",\n        \"size\": 138158440\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route884_Weather0.tar.gz\": {\n        \"sha256\": \"0127c662e8c8259c493690d0fca0e536e7a768f3fb1d52310eda9f09eeefdf63\",\n        \"size\": 251642768\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route885_Weather14.tar.gz\": {\n        \"sha256\": \"e505e84cd628ca5e1d8205e148a7d49afbe8cf0df26b3bf5e8fdb608b2fed360\",\n        \"size\": 100976038\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route887_Weather3.tar.gz\": {\n        \"sha256\": \"0ec20e04353a02e6bdbb9b9b66d4d2b4548c3264561d62767d94fd4ccc8ee902\",\n        \"size\": 184305182\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route948_Weather9.tar.gz\": {\n        \"sha256\": \"f14413b93d035aba0814737dceff7ec305b07ec3120a3f6e981f548f9d433a71\",\n        \"size\": 131559012\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route981_Weather19.tar.gz\": {\n        \"sha256\": \"a4206fb0e0a655630f2eb135f4f02fb30fad74646243942ef064d58475149878\",\n        \"size\": 184646790\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route1627_Weather3.tar.gz\": {\n        \"sha256\": \"e35e665ce7bd4e29fef12df044038ebc2f4eae5eb9a0477936ccf2b1debc5f9d\",\n        \"size\": 354407865\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route1629_Weather6.tar.gz\": {\n        \"sha256\": \"a91d2b79587bfc1055410e47c81af89e4ea5b8a170794854947180abd8816b27\",\n        \"size\": 259443776\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route1630_Weather7.tar.gz\": {\n        \"sha256\": \"0b2493c22de92f41895328f008ddfc5779fbc612521b2a59dc48bce4aae205bc\",\n        \"size\": 169214567\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route1631_Weather10.tar.gz\": {\n        \"sha256\": \"d1d76d6611b4f35a95d509b19e6870be4a232f435c869931f3b430c82f3bb792\",\n        \"size\": 120876892\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route1633_Weather12.tar.gz\": {\n        \"sha256\": \"0d747950c395b9143f99963c4044f430b752166fdac0edc5b3fb662732b9fe4f\",\n        \"size\": 118794979\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route1636_Weather15.tar.gz\": {\n        \"sha256\": \"54606f65d664730550d98f2ebddd637ecf9394a53304515f02c43bf8c80bec0c\",\n        \"size\": 255387627\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route657_Weather2.tar.gz\": {\n        \"sha256\": \"6a74e29a530c2cc952bfcdfffc6ebb7b2c0903e803582c8870ae5cd387946381\",\n        \"size\": 169878219\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route658_Weather8.tar.gz\": {\n        \"sha256\": \"9c0fe5ee096033117594e7e40f924a4bc2bc410b1a6a3698fe1eabd4afd1f7c6\",\n        \"size\": 153609789\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route659_Weather3.tar.gz\": {\n        \"sha256\": \"255b3b368abaf27a74e6d3556e8ec30783545979b494d0d8b07121c3c8358608\",\n        \"size\": 137411396\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route692_Weather8.tar.gz\": {\n        \"sha256\": \"44a8345859f49cd91346cc21189114095a75f92eb13b51f71a49f31a828a4cfb\",\n        \"size\": 140488832\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route719_Weather18.tar.gz\": {\n        \"sha256\": \"4671d287948827b63ced315293fa8254b4c47483bd853a9dc9f8ae668bf54cf4\",\n        \"size\": 153616431\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route720_Weather19.tar.gz\": {\n        \"sha256\": \"6b2e7cbac1354186e510f6aac03b6120815dc98559b8029990389fce5387eb8a\",\n        \"size\": 286032344\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route721_Weather19.tar.gz\": {\n        \"sha256\": \"3348d1c52e42ce7d7905d8028b1372c1a38f7ebf9a83f0329778aa37328d3442\",\n        \"size\": 232674679\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route737_Weather23.tar.gz\": {\n        \"sha256\": \"40a3867ac7bc972602f092a77fe88accb0fe3e55de6404a1695cc44df766419a\",\n        \"size\": 196914202\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route498_Weather23.tar.gz\": {\n        \"sha256\": \"6ba5e9e16a37c3dcd71150a9631cf79c4f0182b64498fbf627e8fc50333ad13d\",\n        \"size\": 426738358\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route511_Weather9.tar.gz\": {\n        \"sha256\": \"1d0578fceb5fddc0a946316c58648d2e30e5408d4b0acdec17e26033a5a2879b\",\n        \"size\": 447744563\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route529_Weather9.tar.gz\": {\n        \"sha256\": \"0e28471b5ccaee272d97d355a36ddacb0fdc02d5f6c3e608065d4bdaad8d67a2\",\n        \"size\": 396723633\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route531_Weather11.tar.gz\": {\n        \"sha256\": \"0519a4a36442e8d5e7f28602067a12ff3c8884fe0cc7dde5b6a4c9e45c4a65f8\",\n        \"size\": 449011100\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route536_Weather8.tar.gz\": {\n        \"sha256\": \"0a08633aed3b6d0f94a72535233ea57c8474c183788c7173963d3a1fd60b49de\",\n        \"size\": 479957251\n    },\n    \"SignalizedJunctionLeftTurn_Town03_Route113_Weather26.tar.gz\": {\n        \"sha256\": \"307f74647acd3a7a51772006104b02c2b32abcbaa10f8886f98c1b9fe1ddfddb\",\n        \"size\": 162910901\n    },\n    \"SignalizedJunctionLeftTurn_Town03_Route114_Weather6.tar.gz\": {\n        \"sha256\": \"816ae9deb32aa591b5535eb5d5e85b2a928e9e085c9be4e9cdea7b0d3baa338a\",\n        \"size\": 125330450\n    },\n    \"SignalizedJunctionLeftTurn_Town03_Route150_Weather26.tar.gz\": {\n        \"sha256\": \"5c76895ae3eb231d5794cff147cc6962238123ea54c334e5ef5e6389dc934971\",\n        \"size\": 145562214\n    },\n    \"SignalizedJunctionLeftTurn_Town04_Route172_Weather8.tar.gz\": {\n        \"sha256\": \"ff3a3deb25b202aad294448418bece3b1d2ab99a5f2a58379aa541a2eb27bb1f\",\n        \"size\": 231721139\n    },\n    \"SignalizedJunctionLeftTurn_Town04_Route173_Weather26.tar.gz\": {\n        \"sha256\": \"23b897dfac6c199ce85b5ac1f2368cc4db8ec1212ea673081bd983aba3f09444\",\n        \"size\": 833035773\n    },\n    \"SignalizedJunctionLeftTurn_Town04_Route174_Weather18.tar.gz\": {\n        \"sha256\": \"564cf6ec4a3d13dfd2b345a81bdf514a06db68a0ca8ab2817cbcbe6d3bb4fa9a\",\n        \"size\": 205333137\n    },\n    \"SignalizedJunctionLeftTurn_Town05_Route232_Weather23.tar.gz\": {\n        \"sha256\": \"b49ab07f82c99803452f75426e8bc0b394ba23d9d6b9b0b3764c77c4c655c4a0\",\n        \"size\": 156070829\n    },\n    \"SignalizedJunctionLeftTurn_Town05_Route233_Weather6.tar.gz\": {\n        \"sha256\": \"b200f9494c8ce641bf6467af845a9644c6f5a50017ba9a035337f11837241116\",\n        \"size\": 155075144\n    },\n    \"SignalizedJunctionLeftTurn_Town05_Route234_Weather7.tar.gz\": {\n        \"sha256\": \"5c78fe42621aa1b1d44f07baf3f598975e7ff52787cf2afdd4a6828cb8b6e081\",\n        \"size\": 175445418\n    },\n    \"SignalizedJunctionLeftTurn_Town05_Route267_Weather3.tar.gz\": {\n        \"sha256\": \"67a46cf685a8ea5d0fa7dc212fa970686c2f0385ff2ecb2359bf94371cbb84df\",\n        \"size\": 178594513\n    },\n    \"SignalizedJunctionLeftTurn_Town07_Route334_Weather26.tar.gz\": {\n        \"sha256\": \"2931b22c4424f8d62f387e81a2535be97b41b1546b3246f50c4a0c72ab7d4d39\",\n        \"size\": 276351823\n    },\n    \"SignalizedJunctionLeftTurn_Town07_Route336_Weather23.tar.gz\": {\n        \"sha256\": \"47b7ab30d540085ccdd7206ff221d3f77e32effce92d517f53e4749a20473e6c\",\n        \"size\": 220806763\n    },\n    \"SignalizedJunctionLeftTurn_Town07_Route366_Weather2.tar.gz\": {\n        \"sha256\": \"7469302e8ec876882a5aaf5065969f9d6163642d533ade260833747a2fad71c2\",\n        \"size\": 272675358\n    },\n    \"SignalizedJunctionLeftTurn_Town10HD_Route380_Weather21.tar.gz\": {\n        \"sha256\": \"5f80bac91b9a59cbf7b903be0c69cd3e9b817665b55a90e9c9ed80aa07828938\",\n        \"size\": 242935184\n    },\n    \"SignalizedJunctionLeftTurn_Town10HD_Route381_Weather22.tar.gz\": {\n        \"sha256\": \"6dee206eafdaeb5889ccd0e0c112bcd6cb0359086e141e478fcf88480cd3b404\",\n        \"size\": 258131195\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route1470_Weather5.tar.gz\": {\n        \"sha256\": \"1a8ac4fd6bf364d2c99dacdda4e5fb89abc76c6597b1d3f8f4caa4d1bec0e4cf\",\n        \"size\": 404877154\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route799_Weather0.tar.gz\": {\n        \"sha256\": \"048503c9a28fb8a1e5bc79ff88b755c5d6337038ee739ea011cf35db84e27d1e\",\n        \"size\": 373939890\n    },\n    \"SignalizedJunctionLeftTurn_Town13_Route580_Weather26.tar.gz\": {\n        \"sha256\": \"5d4ca4a4b91f17696842acbca76ce24afef6abbedfbb1e886b08d25f28566375\",\n        \"size\": 155632527\n    },\n    \"SignalizedJunctionLeftTurn_Town13_Route581_Weather26.tar.gz\": {\n        \"sha256\": \"c6fab232dfaff9114b217bea4be4d45042fdb2afa50f5ef9e030f9e5c56458d4\",\n        \"size\": 169868642\n    },\n    \"SignalizedJunctionLeftTurn_Town15_Route437_Weather26.tar.gz\": {\n        \"sha256\": \"da74ca962987aad56eb582f62601657233592a7863ac404f2e96182a7da63cf4\",\n        \"size\": 435870480\n    },\n    \"SignalizedJunctionLeftTurn_Town15_Route471_Weather26.tar.gz\": {\n        \"sha256\": \"4e2176d85eb72d09518f2df488959d361bfa8d90071c9a8e13b110f44641068d\",\n        \"size\": 463018682\n    },\n    \"SignalizedJunctionRightTurn_Town03_Route118_Weather14.tar.gz\": {\n        \"sha256\": \"9102a888cc13f8fac4f0f8e8acca3a2a53439190045e1e9c7e41d051897765fd\",\n        \"size\": 124093368\n    },\n    \"SignalizedJunctionRightTurn_Town03_Route151_Weather2.tar.gz\": {\n        \"sha256\": \"eb05f5dd036e25dba9c2eb8946b0f7c82c1ca35efe0517c0d4ffed488d12b1be\",\n        \"size\": 213195578\n    },\n    \"SignalizedJunctionRightTurn_Town04_Route176_Weather20.tar.gz\": {\n        \"sha256\": \"109210c7888191623f0ed32c76e68072740380a406098d9a82f58b15a06721fd\",\n        \"size\": 138702249\n    },\n    \"SignalizedJunctionRightTurn_Town04_Route177_Weather13.tar.gz\": {\n        \"sha256\": \"aa4516bfee04a5f38d8a54fdc725d70ff19ed5ea3e99ebc55f702a8fe4e74373\",\n        \"size\": 317376295\n    },\n    \"SignalizedJunctionRightTurn_Town04_Route211_Weather3.tar.gz\": {\n        \"sha256\": \"7b530737766a6cbd6dece9308d28fad09e9caf17f348ab4ab09b54d8b8270531\",\n        \"size\": 216855894\n    },\n    \"SignalizedJunctionRightTurn_Town07_Route338_Weather10.tar.gz\": {\n        \"sha256\": \"899798047e2fcde965d5dd45d7305152d0ecc4c575bfc05cff0e3944ad0bfa2f\",\n        \"size\": 214016166\n    },\n    \"SignalizedJunctionRightTurn_Town07_Route339_Weather1.tar.gz\": {\n        \"sha256\": \"e46161972dccaf2fe426946ca6b766ad748b53422022fc79f620753e0df150d8\",\n        \"size\": 294723696\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route803_Weather23.tar.gz\": {\n        \"sha256\": \"3a1f142f61f016cce0c1d7f5682bc64a7571ea2c9f40fd712033f59357a940a9\",\n        \"size\": 139010164\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route804_Weather5.tar.gz\": {\n        \"sha256\": \"e57f51ea95c5c4a4437b39f75cc2cb7ed7a978e6b210a53af7cc5d775d8bb6e4\",\n        \"size\": 151455663\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route805_Weather25.tar.gz\": {\n        \"sha256\": \"6f8484169f069debfaf817d6d3af424257087708eceadd2a63260dca7bc14cd9\",\n        \"size\": 127020458\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route964_Weather2.tar.gz\": {\n        \"sha256\": \"fd6d0bb8153c47685d38f8890adf45df50e7bb0fc474ba2895ffa623adf8b78d\",\n        \"size\": 122252674\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route988_Weather0.tar.gz\": {\n        \"sha256\": \"ee73a66b67b6f5cd4cea9bf6c51a170e71932f00162066454a1b04dbdbcc1498\",\n        \"size\": 145014735\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route583_Weather11.tar.gz\": {\n        \"sha256\": \"eb4cf5b4fe21bf6f6ab3160126052163e841358b8b99904a0be605d00b363c8d\",\n        \"size\": 179461654\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route438_Weather7.tar.gz\": {\n        \"sha256\": \"aba6e99e20d6a58727599eff2470c421c547289c9a24c2ae6fd9e5bfe4db0ad4\",\n        \"size\": 407447318\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route473_Weather5.tar.gz\": {\n        \"sha256\": \"7b4886197bd1372c7f6f709542fac4cc42d10d5a97502c1027bd96db9200e76b\",\n        \"size\": 449912384\n    },\n    \"StaticCutIn_Town03_Route109_Weather1.tar.gz\": {\n        \"sha256\": \"ca086d2f0f4347ea4b5ea9163940791298084cfcc898e22c206e55f6c7c94f50\",\n        \"size\": 132896437\n    },\n    \"StaticCutIn_Town03_Route110_Weather6.tar.gz\": {\n        \"sha256\": \"59e0e02d8735a26da34121fdee6d8e851f1899267da84d45f6b5d220d187714a\",\n        \"size\": 240442659\n    },\n    \"StaticCutIn_Town03_Route149_Weather19.tar.gz\": {\n        \"sha256\": \"da2f45e540d6ce72b0ad96b062e33bc978b1a7e205173c9d532457d2b38725af\",\n        \"size\": 75043129\n    },\n    \"StaticCutIn_Town03_Route158_Weather2.tar.gz\": {\n        \"sha256\": \"6a78c3541d8ed714e6981ba527055ad1354f27f41ed4983f413971f53dec1555\",\n        \"size\": 268878476\n    },\n    \"StaticCutIn_Town04_Route168_Weather12.tar.gz\": {\n        \"sha256\": \"2a520d2b2d42442f2216bf77c97aaf1100f1565314b9298a4a1c01c3da6f8636\",\n        \"size\": 219229076\n    },\n    \"StaticCutIn_Town04_Route208_Weather0.tar.gz\": {\n        \"sha256\": \"957af6e1d0f5a31d983ea7afc0765155f7b425b58a861159a906262f500f4c76\",\n        \"size\": 244136027\n    },\n    \"StaticCutIn_Town04_Route216_Weather8.tar.gz\": {\n        \"sha256\": \"b11e46f7777a8e3f42ff778239a9f8d2a465097b9af53accd7a215dc52600bd8\",\n        \"size\": 196847195\n    },\n    \"StaticCutIn_Town05_Route226_Weather18.tar.gz\": {\n        \"sha256\": \"7c1ba09c63f5e2d19434422266e08c9c22ba6931f1fa7b1e0c3cd7fd971867ea\",\n        \"size\": 351706953\n    },\n    \"StaticCutIn_Town05_Route227_Weather2.tar.gz\": {\n        \"sha256\": \"744aa966e03eae75fb5936e5552f591d43b13b8ca8ea8f3f94aaa2410755de32\",\n        \"size\": 278897358\n    },\n    \"StaticCutIn_Town05_Route265_Weather5.tar.gz\": {\n        \"sha256\": \"4fe8aa55c1f0d48377c15ac93a2f9c791810aaadcc5729d5c81f60c693d51d25\",\n        \"size\": 437808855\n    },\n    \"StaticCutIn_Town05_Route275_Weather15.tar.gz\": {\n        \"sha256\": \"08da220299283ebc28d5ee8796a97fc44520f09ec09c0c1a241e4949c1870f5a\",\n        \"size\": 283289118\n    },\n    \"StaticCutIn_Town06_Route287_Weather1.tar.gz\": {\n        \"sha256\": \"0980c2496e5b2141d6ada465246f5846a04740741cca483840c686101be36988\",\n        \"size\": 267411106\n    },\n    \"StaticCutIn_Town06_Route288_Weather2.tar.gz\": {\n        \"sha256\": \"6b9c25cb2e242d7f00509466e0e229bcd95b3d2bb49d9b462a27a9b244244239\",\n        \"size\": 253514436\n    },\n    \"StaticCutIn_Town12_Route782_Weather2.tar.gz\": {\n        \"sha256\": \"1991ffcea1952d4e4da4f808ec8e3cf77aa98b709f987ade2e0f939b9cc65ff7\",\n        \"size\": 189294890\n    },\n    \"StaticCutIn_Town12_Route783_Weather3.tar.gz\": {\n        \"sha256\": \"2e0dd8ba008a3bc69e8f93f5194692a9c4f5b07896e6c76b57a0e670845fe6c5\",\n        \"size\": 198003265\n    },\n    \"StaticCutIn_Town12_Route785_Weather5.tar.gz\": {\n        \"sha256\": \"81b0b77572e68c183357c67166cc1dc60fef69f367dc6f801e246fbb73db2274\",\n        \"size\": 414568857\n    },\n    \"StaticCutIn_Town13_Route563_Weather9.tar.gz\": {\n        \"sha256\": \"12304faf9f4ea83eefe37cb3346175d8c6eebafc2219f15f897c96ee7ff66ed3\",\n        \"size\": 266080463\n    },\n    \"StaticCutIn_Town13_Route564_Weather18.tar.gz\": {\n        \"sha256\": \"3fd15fd584fa1f3dc255e1ba0a05aec9c512950491255fa6c015479504959950\",\n        \"size\": 449116958\n    },\n    \"StaticCutIn_Town13_Route565_Weather8.tar.gz\": {\n        \"sha256\": \"2dc59c5f402f1574d15672439bf36732b594b436544669f49431ad6269aec1b6\",\n        \"size\": 123814612\n    },\n    \"StaticCutIn_Town13_Route566_Weather20.tar.gz\": {\n        \"sha256\": \"732a93906db1a38be75938925a1375bd7cd33ebdabffb36069946e54ff0c94a7\",\n        \"size\": 141863782\n    },\n    \"StaticCutIn_Town15_Route426_Weather10.tar.gz\": {\n        \"sha256\": \"d5304071077bc5d55cb409f037e62a4c70c0c735205141e5c55adbfb8400cca5\",\n        \"size\": 359264845\n    },\n    \"StaticCutIn_Town15_Route427_Weather11.tar.gz\": {\n        \"sha256\": \"66f217ecbbc2137acc1bdf9515c6896f379ab14f76d70be57402703b247cf20b\",\n        \"size\": 334100761\n    },\n    \"StaticCutIn_Town15_Route428_Weather12.tar.gz\": {\n        \"sha256\": \"694c6fd76289aa275ef785c2c63d1fd57b1e0f6b8cd90c70b5789cf0c3b9ac22\",\n        \"size\": 383313944\n    },\n    \"StaticCutIn_Town15_Route429_Weather13.tar.gz\": {\n        \"sha256\": \"3727e0bc683cea5be7fcbb1728a434a4e882243e26ac7d2a403c41baa014a6a3\",\n        \"size\": 142446409\n    },\n    \"TJunction_Town01_Route90_Weather12.tar.gz\": {\n        \"sha256\": \"f0ca1727537cffb2d3b47eca581172941cf1346b37e201551d02bfeddd4ca907\",\n        \"size\": 786008469\n    },\n    \"TJunction_Town01_Route91_Weather13.tar.gz\": {\n        \"sha256\": \"a4a7c6c4a997f05a66cfa594158132e52d4495da72f227c5dac9dd2a52ffb7e4\",\n        \"size\": 157092708\n    },\n    \"TJunction_Town02_Route97_Weather19.tar.gz\": {\n        \"sha256\": \"acf9bc9aade7451056bc83e8d2ff1cac695105fbb3abcc7742b58bfc1897647e\",\n        \"size\": 265051346\n    },\n    \"TJunction_Town05_Route259_Weather0.tar.gz\": {\n        \"sha256\": \"82d456c3aad2d23933f3de3f2e6e534e1229cf906aede18a9e14b60fd6b59355\",\n        \"size\": 923002146\n    },\n    \"TJunction_Town05_Route260_Weather0.tar.gz\": {\n        \"sha256\": \"578024b7fae88fa157bf49712a4e364511765f6148949323945ea61dde61a4c6\",\n        \"size\": 873535637\n    },\n    \"TJunction_Town05_Route261_Weather1.tar.gz\": {\n        \"sha256\": \"d8b9c50489b011fb04dc6e4813a791a8cb7993703607337fbca166d616836dff\",\n        \"size\": 417017934\n    },\n    \"TJunction_Town06_Route304_Weather18.tar.gz\": {\n        \"sha256\": \"12ca5938cec64cbb705aaede94afdba7a78d793576c17e90f0759d82d7be775d\",\n        \"size\": 808918090\n    },\n    \"TJunction_Town06_Route305_Weather19.tar.gz\": {\n        \"sha256\": \"f575c814dccbc0532e058621138413ef311fcdf5f87e5013d6b09959efab8b32\",\n        \"size\": 570775039\n    },\n    \"TJunction_Town06_Route306_Weather20.tar.gz\": {\n        \"sha256\": \"8fa7570114eebc22ea3f48c56d994fbe8e43d743287b02262ecf976d7c319579\",\n        \"size\": 605867541\n    },\n    \"TJunction_Town07_Route363_Weather25.tar.gz\": {\n        \"sha256\": \"f401755dcd20abd2646024da494368c1b48322a2408e0702bc3ab26e2b637bd0\",\n        \"size\": 470403884\n    },\n    \"TJunction_Town07_Route364_Weather0.tar.gz\": {\n        \"sha256\": \"ccd261ae0f9887c270fd3d6ea5389be674011b90ea91166f98842590c4aa9d17\",\n        \"size\": 228334347\n    },\n    \"TJunction_Town07_Route365_Weather1.tar.gz\": {\n        \"sha256\": \"faa287a223e2b2d2363a7dce1e6576c61bec7fe89d12c3eb51e61860ca9a4566\",\n        \"size\": 947724286\n    },\n    \"TJunction_Town12_Route1017_Weather3.tar.gz\": {\n        \"sha256\": \"33596c0be1b7eefb0125e0b86696e67b6b141eccca0e8c454c97e91b407e2356\",\n        \"size\": 314260836\n    },\n    \"TJunction_Town12_Route1018_Weather3.tar.gz\": {\n        \"sha256\": \"dd1f3f377d4a76ea9fff5b3bdad90b781eb166eedc5fd81bb3286ea4cef3c321\",\n        \"size\": 621528755\n    },\n    \"TJunction_Town12_Route1201_Weather5.tar.gz\": {\n        \"sha256\": \"6eb281f0d103d50cd4114c5d07d9e4dfb7ed01d7bfdcc7c6f48ff44d4b3cb881\",\n        \"size\": 552885794\n    },\n    \"TJunction_Town12_Route880_Weather22.tar.gz\": {\n        \"sha256\": \"289c9c94876d4f75c6c2099c7566117498046f4decbd49b712fd4a4ac0938701\",\n        \"size\": 503091053\n    },\n    \"TJunction_Town12_Route881_Weather23.tar.gz\": {\n        \"sha256\": \"643b5776197515a25e862e83f2708a5bf6ee64822c6d48fc0b7e3ed3a7f6683f\",\n        \"size\": 212391115\n    },\n    \"TJunction_Town12_Route882_Weather23.tar.gz\": {\n        \"sha256\": \"df4afced1416c3f9a1c5d7e72f74f61c2b70a4485d78d28f0c1cd6c1091c2a73\",\n        \"size\": 413557323\n    },\n    \"TJunction_Town12_Route883_Weather25.tar.gz\": {\n        \"sha256\": \"1bb6290e33aa8ded7f2636a4149777da0777e670fd7d99d994261f35bba7855e\",\n        \"size\": 413605161\n    },\n    \"TJunction_Town12_Route926_Weather8.tar.gz\": {\n        \"sha256\": \"6b3017eaa2d436aaf3b2ea0f0fc3b75454a221093ed7bbf23fb95e3bbeac6d1e\",\n        \"size\": 558219496\n    },\n    \"TJunction_Town12_Route927_Weather9.tar.gz\": {\n        \"sha256\": \"ae31746c80b8cfde1f35f189b23e56306b4c5f082d4b0457e4ca1a494295eef7\",\n        \"size\": 481369883\n    },\n    \"TJunction_Town12_Route947_Weather11.tar.gz\": {\n        \"sha256\": \"37d7422e89e16a7902b36aad5ff4d0f1d1ea281ec71df40f108e6a8706021f9b\",\n        \"size\": 390423152\n    },\n    \"TJunction_Town12_Route980_Weather18.tar.gz\": {\n        \"sha256\": \"9052db68a37b85d72f973c0f99532a4544dbff169941c12f298124a50a1e0273\",\n        \"size\": 588679777\n    },\n    \"TJunction_Town13_Route652_Weather2.tar.gz\": {\n        \"sha256\": \"f3c798276ff148470b556cb10c25fd56e7ddf5413c8b4fedca9b3cc11ef4585f\",\n        \"size\": 813282733\n    },\n    \"TJunction_Town13_Route654_Weather3.tar.gz\": {\n        \"sha256\": \"e9576ae6c0a7c036afdb26ea593fc61cd5724051f7f7c1802c4bc216914d7c5d\",\n        \"size\": 486876743\n    },\n    \"TJunction_Town13_Route655_Weather5.tar.gz\": {\n        \"sha256\": \"bc4e4502e9601810eea45be49766478d839680c8fe55084ce5471a58a09e233c\",\n        \"size\": 724086134\n    },\n    \"TJunction_Town13_Route691_Weather15.tar.gz\": {\n        \"sha256\": \"aea5c28ff5d07d0b5f1a4b84aae996c76434673912461fb19daa5b948ed2393c\",\n        \"size\": 323664419\n    },\n    \"TJunction_Town15_Route456_Weather14.tar.gz\": {\n        \"sha256\": \"7efc773c30b3c72414a4a8f8570038937c4033b99d3e817abf808789edc99832\",\n        \"size\": 1591072119\n    },\n    \"TJunction_Town15_Route457_Weather15.tar.gz\": {\n        \"sha256\": \"b70af4a90fbf6df0e51ce354b936755672be43ec182eaff49decd2b5dab4f014\",\n        \"size\": 440147208\n    },\n    \"TJunction_Town15_Route495_Weather1.tar.gz\": {\n        \"sha256\": \"8552a6403837fa58efed1a7f67316e51ac839da1a6e3b4daf4600771307cda6a\",\n        \"size\": 2181805980\n    },\n    \"TJunction_Town15_Route496_Weather2.tar.gz\": {\n        \"sha256\": \"135dc494f1350335dba079d1d4ba2fa161ea302eaf0385fa0ea116c563a8fa24\",\n        \"size\": 940877841\n    },\n    \"TJunction_Town15_Route510_Weather8.tar.gz\": {\n        \"sha256\": \"342a130d35d8d7cc19a84fbf697f88ed6cae6ee05b925cf7aaaaafa532dff39f\",\n        \"size\": 456479032\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town03_Route143_Weather13.tar.gz\": {\n        \"sha256\": \"e314e7588c1b5cf5153642c4870898071c890974fb388ba904a60cfdf173321d\",\n        \"size\": 272032974\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town03_Route144_Weather14.tar.gz\": {\n        \"sha256\": \"6f474d4d05d3115fceaf4ec63145f8058593a57d250a838d633a96a5080adad9\",\n        \"size\": 232054659\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town03_Route145_Weather15.tar.gz\": {\n        \"sha256\": \"dec2ddb07870fde36a2be506910091c7298274f69b96766ccf79184694653367\",\n        \"size\": 111113126\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town04_Route202_Weather20.tar.gz\": {\n        \"sha256\": \"5de8b26c559e0c622e19bdfcf27f03efdbb569f598ea8136c88981a3568f02e8\",\n        \"size\": 377546253\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town04_Route203_Weather21.tar.gz\": {\n        \"sha256\": \"9a5d654a57653fdd3bca86f95c52519532d7424d496ac5340c21cef7e555b45c\",\n        \"size\": 127883702\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town05_Route256_Weather22.tar.gz\": {\n        \"sha256\": \"94a0492f29b8cee1d1a62e5b741aea9f9355fd1ed3e36fd134303a530f397760\",\n        \"size\": 126234252\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town05_Route257_Weather23.tar.gz\": {\n        \"sha256\": \"45651822e55c49e83c0a47abe5749c7a82999c4938290d99811b17e83e4f28fb\",\n        \"size\": 171061933\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town05_Route258_Weather25.tar.gz\": {\n        \"sha256\": \"5435b11ff0477556020953d40269560f1560b040a3b474275a5609bf82a32842\",\n        \"size\": 133217178\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town07_Route360_Weather22.tar.gz\": {\n        \"sha256\": \"08e5abc20ff31ebfa825e4e51c66b5764557fa42376e337dd78ce3648189478f\",\n        \"size\": 154437628\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town07_Route361_Weather23.tar.gz\": {\n        \"sha256\": \"52babb2313f05fe5526cb40eaea393ae950e1d68e77c77712de178dbb3510909\",\n        \"size\": 126248334\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town07_Route362_Weather23.tar.gz\": {\n        \"sha256\": \"a108851f431961245a8f8609cd3217088f477d981497efb19c3f1dec2b47ded9\",\n        \"size\": 150879629\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route1015_Weather1.tar.gz\": {\n        \"sha256\": \"7eb65f5aa0723ed12b81bb154c7da53f8996c2926ca1243c6f6cc6b239fb5155\",\n        \"size\": 104823097\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route1016_Weather2.tar.gz\": {\n        \"sha256\": \"ac543fcda502e8e4f8e0b6a8bb1fe3052e1eb97e80149c5e7cc07ff63e404de0\",\n        \"size\": 202296097\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route876_Weather18.tar.gz\": {\n        \"sha256\": \"42d4c8c26dcc18037ff776d3762638cf90cfb3c58ae078b816b2488fdd33b49b\",\n        \"size\": 180680546\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route877_Weather19.tar.gz\": {\n        \"sha256\": \"4e097cfb1e0abb8b46a77d3ca939e1af6c90cd54cd22c2808209905dd043b09b\",\n        \"size\": 149253551\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route878_Weather20.tar.gz\": {\n        \"sha256\": \"f3478d9d408306aeed076f5963796bcca18d530b0280b321de5afeb939027ad0\",\n        \"size\": 128740499\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route879_Weather21.tar.gz\": {\n        \"sha256\": \"1d95f492adf826cb79f7f2093bfb2bec7e868b25833af6700244dc1d19a247da\",\n        \"size\": 140683523\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route946_Weather10.tar.gz\": {\n        \"sha256\": \"6149f82bacc50e93979e420d68d2f140b31d2d34fac3c5ed2a9b7adaca3dc770\",\n        \"size\": 113774579\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route979_Weather9.tar.gz\": {\n        \"sha256\": \"20a86df657e47dbe277ffbd04ac82ed6728748a24feb1ff39afb81263b272b69\",\n        \"size\": 100988023\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route648_Weather23.tar.gz\": {\n        \"sha256\": \"c7fa481b6bba0c0029a0f1ab0be8aac5af50aaa62073f540aacd2de72b114ed7\",\n        \"size\": 98495071\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route650_Weather0.tar.gz\": {\n        \"sha256\": \"ad53840cd5c555dc21f8d66c1e4a63201d75cf5e8afc7bed886ea15d214d2ee9\",\n        \"size\": 112036615\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route651_Weather1.tar.gz\": {\n        \"sha256\": \"92a8f0bcec2bea7e73ebf9a88d3993a651f69fccbfa5c668411be506dc2d265f\",\n        \"size\": 118571242\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route690_Weather14.tar.gz\": {\n        \"sha256\": \"ab8dcd95734aafe1d0c8c1c2a3d7e13f6823ecb4c7e4b47606c0c2c098caf334\",\n        \"size\": 96572873\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route454_Weather12.tar.gz\": {\n        \"sha256\": \"11c0281650ede6a18adaf9fdc5c1c6b65eb423337030d033768a2f0dc53ef74d\",\n        \"size\": 72407775\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route455_Weather13.tar.gz\": {\n        \"sha256\": \"5b07753c90e1f7454587c648cef4ab83a3fd0f27ab3696ad81ce0104400cb4a9\",\n        \"size\": 212712569\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route493_Weather25.tar.gz\": {\n        \"sha256\": \"8b95afe9e1cc61812b9cf1302ff6bef8d011fce64b3dd4d411493559e35efcf3\",\n        \"size\": 199417101\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route494_Weather0.tar.gz\": {\n        \"sha256\": \"30e253468ba2dcb7d1c930b1f58b79d0e59e902e5afd559e84dcff0017440ebf\",\n        \"size\": 245140959\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route509_Weather15.tar.gz\": {\n        \"sha256\": \"62df5f6caf01a7f9f2bc8accc43581b01078b0e0b522a32a6dd19e8ad24255ff\",\n        \"size\": 230754756\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route530_Weather10.tar.gz\": {\n        \"sha256\": \"bd1062cf9ece45f93d9c49937815bd25441f61a05a456a7fc34f14dc60fe138a\",\n        \"size\": 221719175\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town15_Route535_Weather15.tar.gz\": {\n        \"sha256\": \"8c7118472e70eff75ce1e87df15ac342e20b8ea770a930a7c295a44916280c08\",\n        \"size\": 232735839\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town03_Route137_Weather7.tar.gz\": {\n        \"sha256\": \"4bd1651c5401cb551f2a90d3fdaf8d2a92788f0b3e539f279546be6589f396af\",\n        \"size\": 378181990\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town03_Route139_Weather9.tar.gz\": {\n        \"sha256\": \"0202eef34c2ef5ccc044ab5c3a586411178372ce7b2c502c26cdf05ad3ff185c\",\n        \"size\": 289815871\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town04_Route196_Weather14.tar.gz\": {\n        \"sha256\": \"1812df35da5991fc3cdea86f2bb23cfaddb19cae64a26584194128da94861168\",\n        \"size\": 209742468\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town04_Route197_Weather15.tar.gz\": {\n        \"sha256\": \"8cc7e173a7b47f0120107feaaea962b1c78dbab1e02e1a137ef4fe19e53507a8\",\n        \"size\": 628129389\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town04_Route198_Weather8.tar.gz\": {\n        \"sha256\": \"c0296cc93ab2e9ef4750775bd7252996c25984e56781d64da2b01ae8910ca61e\",\n        \"size\": 218589876\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town05_Route250_Weather8.tar.gz\": {\n        \"sha256\": \"f217569e7a8b0f219fa9304cb6ae80d04d905b95342b5fb4b0b2942007b2a4e3\",\n        \"size\": 148945382\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town05_Route251_Weather9.tar.gz\": {\n        \"sha256\": \"9baecc8b81b402064f828cac66bd7cb79f6161140bf50095cac599b7130e0f35\",\n        \"size\": 95496965\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town05_Route252_Weather21.tar.gz\": {\n        \"sha256\": \"37c4179bab4119a817faed216403fb44e7ec35d30523b4ff09ab60b508026978\",\n        \"size\": 107918192\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route354_Weather8.tar.gz\": {\n        \"sha256\": \"dec452d5db1828b05b45f211f8536d235f4efb8f23cd3a29153320cc6ce16eb8\",\n        \"size\": 427204496\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route355_Weather9.tar.gz\": {\n        \"sha256\": \"707f23539aaefda89bfdb720cb8b9736fa00294b6920e8ca03001e3f1f8b0cf2\",\n        \"size\": 375880080\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route356_Weather18.tar.gz\": {\n        \"sha256\": \"85ec7908756304e295af06c7f7ba9c662967a9088047e0e1584f822012c129ee\",\n        \"size\": 159967293\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town10HD_Route386_Weather22.tar.gz\": {\n        \"sha256\": \"a3135ef5a6bf7df94ebb0381c48a16674ffb9328bdd4929546f9dc97797409e5\",\n        \"size\": 322101083\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town10HD_Route387_Weather23.tar.gz\": {\n        \"sha256\": \"1b513b9dd8748f7b6325ee759500bb96b54ff25570b5789abbad221af4457d70\",\n        \"size\": 332924879\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town10HD_Route392_Weather2.tar.gz\": {\n        \"sha256\": \"d9875adb11a84106c32e243bafd948c97e26d5323fa2e6495b9c0749d721091b\",\n        \"size\": 398159526\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route868_Weather10.tar.gz\": {\n        \"sha256\": \"5d70a8f6c9121c6c91e7a1bee340797ff91c724f3c0dd7000b2b6b26164f245a\",\n        \"size\": 510520864\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route869_Weather11.tar.gz\": {\n        \"sha256\": \"2a5c885da0ec6f741c159064aebda934f21afa91d14d02cd43857a194a1e88f2\",\n        \"size\": 82331323\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route870_Weather12.tar.gz\": {\n        \"sha256\": \"7274418980cdd7c8a0ca6d5b8eaca4d155fead1772fa0ece165b38bc3e052048\",\n        \"size\": 258805335\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route871_Weather13.tar.gz\": {\n        \"sha256\": \"47ce51da07451b4c9a1196164afcaee68128303942eb13c028e52e8748ea11b7\",\n        \"size\": 351080524\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route944_Weather8.tar.gz\": {\n        \"sha256\": \"77e49a278e8dc9495dec8f26121b5b3e929fb0309fa77d53364e16398b30fc42\",\n        \"size\": 435359860\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route640_Weather8.tar.gz\": {\n        \"sha256\": \"f616bc3387bb0eaaf1a8972bfa78c0cd64d65dca3ac2bd1f41a469e1b66d268a\",\n        \"size\": 355968568\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route641_Weather9.tar.gz\": {\n        \"sha256\": \"bef6a9e1fe9c52bc8add585c62ffffd4a9857d89ef91b35fd1bfdc0883819ea2\",\n        \"size\": 296790858\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route642_Weather18.tar.gz\": {\n        \"sha256\": \"459a5ac3b634538dd96876bb364041d2c40cef21b54318ba8d28a99c86aa1d25\",\n        \"size\": 100100710\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route643_Weather19.tar.gz\": {\n        \"sha256\": \"03c73ccccf6300817ea078d532bb6d58e3b19d5225343981babe9cb2506254eb\",\n        \"size\": 324443255\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town15_Route451_Weather9.tar.gz\": {\n        \"sha256\": \"ca95d81749785a062c6be66cad14471f6e0d9a35de2aeafea215a3e4d27f0c4f\",\n        \"size\": 588831063\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town15_Route489_Weather21.tar.gz\": {\n        \"sha256\": \"a9c34039dc4a84a79e48a3aebceb7ed65b55919e85c79951fcb220be71ec9512\",\n        \"size\": 247793940\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town15_Route490_Weather22.tar.gz\": {\n        \"sha256\": \"05defc78ea619d711635f66a09ff1395ad6175611a404621c6ea85f1bf7cde09\",\n        \"size\": 1683081325\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town15_Route507_Weather13.tar.gz\": {\n        \"sha256\": \"c073579261b1cec4fe3f9b7980241c9e4ec948f7dfdbdc99fbd81ef641477292\",\n        \"size\": 704844551\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town03_Route140_Weather10.tar.gz\": {\n        \"sha256\": \"bbcada9ee00ed71da2dc10cb5506f746c4971c4d221ede798c8c58aef72106fe\",\n        \"size\": 173155928\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town03_Route141_Weather11.tar.gz\": {\n        \"sha256\": \"30d76da53eb7f8672746fdf4ff6db88d38212305fec6bb57daf8d951dea64efe\",\n        \"size\": 202351813\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town03_Route142_Weather12.tar.gz\": {\n        \"sha256\": \"d18759e9160c32d68ad843d8ca4208bb26fe5f871b1d6e9e2e69dc55936ed6d4\",\n        \"size\": 205460671\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town04_Route199_Weather9.tar.gz\": {\n        \"sha256\": \"7e7dba34ee5f72abc5fbe1bca5cf4f91e76c3bae4b164b82820ae30859168481\",\n        \"size\": 352196033\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town04_Route200_Weather18.tar.gz\": {\n        \"sha256\": \"da37964ae50c1bb314ae08a5e016df6a276aa797e01be5795ae22d10c38abecb\",\n        \"size\": 350724291\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town04_Route201_Weather19.tar.gz\": {\n        \"sha256\": \"c3797e7ea2522efdd381641369b620168a3857666f0282d19d87b8660f95feb5\",\n        \"size\": 315943192\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town05_Route253_Weather19.tar.gz\": {\n        \"sha256\": \"95f5d2859d19a4fea159ddd7560d59d9d8d0ec077235f946053805876f620cd3\",\n        \"size\": 215984762\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town05_Route254_Weather20.tar.gz\": {\n        \"sha256\": \"6c370d75e8716db9b260b931c0d3e63468105278b19003fc970feaa95718498d\",\n        \"size\": 546501052\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town05_Route255_Weather21.tar.gz\": {\n        \"sha256\": \"25daaf4d67f9b46f2e220757b4ae06a43df15265696a3ff329d11a299d78823a\",\n        \"size\": 158008959\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town07_Route357_Weather19.tar.gz\": {\n        \"sha256\": \"4e0a5e1488e81f7d75982e6a65b2703145741a9ace027383abb040ded30c7a40\",\n        \"size\": 461374424\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town07_Route358_Weather20.tar.gz\": {\n        \"sha256\": \"3c8e4b9a38452a96e69fb8837dc5b30ac1de99096a1e0c07446b083063fae167\",\n        \"size\": 452559764\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town07_Route359_Weather21.tar.gz\": {\n        \"sha256\": \"45934154e2c0892346da1f92bc13d0e005b3e4487c5740cf8c1a2f34940fb20d\",\n        \"size\": 435389862\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town10HD_Route388_Weather23.tar.gz\": {\n        \"sha256\": \"5b76b70b091bd8ba93f20a555e978941f11276127a96ca610550d740f7029cca\",\n        \"size\": 380074897\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town10HD_Route389_Weather25.tar.gz\": {\n        \"sha256\": \"e612847647230ebf9e2e007e2512442ab9fb2a080cf2350a48f21e70e035225a\",\n        \"size\": 244068300\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town10HD_Route393_Weather3.tar.gz\": {\n        \"sha256\": \"d13836ed1b2decfb148b7d6f2341ae7378e28c22fd7a76c5483412bfa36560a6\",\n        \"size\": 450265273\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route1054_Weather14.tar.gz\": {\n        \"sha256\": \"315544de562b937310959065f0ad8cf407e67b884e794e73772d79c4b74ee1d4\",\n        \"size\": 107360227\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route872_Weather14.tar.gz\": {\n        \"sha256\": \"50a3bcbb6e39f0d83bc66b1db77aa202d6377d41b3c0ce14ea227c6352f21eed\",\n        \"size\": 747862099\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route874_Weather8.tar.gz\": {\n        \"sha256\": \"9e26f8049a4213220950b7d3db9ab8237bed627409adda4656de0ff23a982575\",\n        \"size\": 502644382\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route875_Weather9.tar.gz\": {\n        \"sha256\": \"1eeeefdfe81594f1ebec7f4cfafd50e81a021910ffea04af124cd1dfbb367d82\",\n        \"size\": 446535066\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route945_Weather9.tar.gz\": {\n        \"sha256\": \"40a9c3bb1ad18d1293bfdaa9e354e26ec99a08787ff1648c51671387968fa29b\",\n        \"size\": 759763981\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route969_Weather7.tar.gz\": {\n        \"sha256\": \"b7a7edc3cfc58335f19beae95654a00214b77d1a0d0e57f2da02c458f91776d6\",\n        \"size\": 894701668\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route603_Weather15.tar.gz\": {\n        \"sha256\": \"777a4c2b7b87c06e33a96346d43112ba3cd6fb78291d25564e6f255f8f40a875\",\n        \"size\": 1028852978\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route644_Weather20.tar.gz\": {\n        \"sha256\": \"b813132bec85ab67339367abe7df5f38567a458d1fb517d89062bfbcb44200eb\",\n        \"size\": 190041755\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route645_Weather21.tar.gz\": {\n        \"sha256\": \"663d701c28106d08b8f42941030a85ba3995e14b5aaef9e28293e5b4250a5c4b\",\n        \"size\": 602105976\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route646_Weather22.tar.gz\": {\n        \"sha256\": \"0f0a97406b9310a04e2193c7f15db73d844111b36f77d5d9057129792b3856e7\",\n        \"size\": 143152548\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route647_Weather23.tar.gz\": {\n        \"sha256\": \"35b7851d467a4ccb4670348317e035d592cfbac11544c57951b6203c26047ec6\",\n        \"size\": 619856233\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route689_Weather13.tar.gz\": {\n        \"sha256\": \"e9329c46fea1faff01156de6325374d30cc713fca8d47b0b6b45ee06da5409a7\",\n        \"size\": 128927380\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town15_Route452_Weather10.tar.gz\": {\n        \"sha256\": \"89879eda8d3c10455fd0ea39e53a6951e1d85b5f84d5b35c01747f009ccd67fc\",\n        \"size\": 487012199\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town15_Route491_Weather23.tar.gz\": {\n        \"sha256\": \"fb3c2e53594a49561226979f5e74d15dade11fe08ff0992357ab95ed2da9418f\",\n        \"size\": 1800939722\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town15_Route492_Weather23.tar.gz\": {\n        \"sha256\": \"f796504fae99f5d122e4ba239f41110e3c111e4009d5bd0a11ee00f34a1963c7\",\n        \"size\": 518948990\n    },\n    \"VehicleOpensDoorTwoWays_Town12_Route1196_Weather0.tar.gz\": {\n        \"sha256\": \"049d6bbbdc4d4889f6f2479e16326837e5efb7300bca9cc1b1ede463fb37e403\",\n        \"size\": 484536696\n    },\n    \"VehicleOpensDoorTwoWays_Town12_Route1197_Weather1.tar.gz\": {\n        \"sha256\": \"09f94a9bd8c188087329bbbc4dd2ad34c0c3908bcedfad9f9098fe921c83ce45\",\n        \"size\": 833068860\n    },\n    \"VehicleOpensDoorTwoWays_Town12_Route1203_Weather7.tar.gz\": {\n        \"sha256\": \"7aa68386706418e1de41b9fd9504ce735b574cdd7ec5ae95f1b6c91c7a332b6b\",\n        \"size\": 1124540424\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route1027_Weather13.tar.gz\": {\n        \"sha256\": \"1d96a3b6940fd4ed2387b835f0e8034f2b51bf18eb5863e6ae66780bce62f0ae\",\n        \"size\": 177632894\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route1040_Weather0.tar.gz\": {\n        \"sha256\": \"5773d8fc10b5cf7ef178253d6eb89d314e4777c0a76d4f60a8174215672837ea\",\n        \"size\": 691989898\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route826_Weather20.tar.gz\": {\n        \"sha256\": \"ae35fac6f1da73e6323e02dc225f820b2aedb90818fcb536460455c92bf855ca\",\n        \"size\": 179002922\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route827_Weather22.tar.gz\": {\n        \"sha256\": \"36aa5ed9fabd0c9bcc7b34b818d6937863fb66d6359252277cd1475541cfe2af\",\n        \"size\": 229318698\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route829_Weather25.tar.gz\": {\n        \"sha256\": \"8c20806e90f9c32a649c50aac46120c456b8fc206386468ad0fd5b91aadbb87a\",\n        \"size\": 461662735\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route970_Weather8.tar.gz\": {\n        \"sha256\": \"b739868dcc8f5260c4d21f5658dd5620ce5ec5b89fc0062f0ee09398b9b84ef2\",\n        \"size\": 817384606\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route999_Weather11.tar.gz\": {\n        \"sha256\": \"19ef70f2881851d133d6b02a010140614bae5ddd2e6ac6a2a0515e878e79cfb1\",\n        \"size\": 276278987\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route607_Weather19.tar.gz\": {\n        \"sha256\": \"d17bf4e0b41e56a92e9f4724dd81d40d4d2a8fa9c5392d0f14c36b34e1edfcb5\",\n        \"size\": 174157353\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route609_Weather21.tar.gz\": {\n        \"sha256\": \"2c49be11d0b1e2dad22973ffaabdb6c4e640dd701e801db087220c935f1a24f6\",\n        \"size\": 433136427\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route610_Weather12.tar.gz\": {\n        \"sha256\": \"6c4b1480af14c2121a749330deff3591308f57eea2a97496929ae74462a77c5b\",\n        \"size\": 116782311\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route680_Weather10.tar.gz\": {\n        \"sha256\": \"204264f4f7de3013f867183018a661ec6e30eb072f1751653d01dba3958689f5\",\n        \"size\": 193367743\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route702_Weather14.tar.gz\": {\n        \"sha256\": \"b4b1a68ef0c150702c21d9b3952e601e3e6b8e4f281ea3fcbe9abd138ea200ec\",\n        \"size\": 204533029\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route703_Weather1.tar.gz\": {\n        \"sha256\": \"268b05873a61c77487a5bac29dac28fc346665b7d535de617c7af6905d146527\",\n        \"size\": 190955026\n    },\n    \"VehicleTurningRoutePedestrian_Town15_Route1387_Weather1.tar.gz\": {\n        \"sha256\": \"e7eeb84b06885146028dd01e1c34df18381566fbf3ab5d159737909297cf7d6c\",\n        \"size\": 142262239\n    },\n    \"VehicleTurningRoutePedestrian_Town15_Route445_Weather11.tar.gz\": {\n        \"sha256\": \"b7ed661f81111be7f63946e219b5f454592bd8941867e5410dada96db86b9c7a\",\n        \"size\": 330617001\n    },\n    \"VehicleTurningRoutePedestrian_Town15_Route481_Weather19.tar.gz\": {\n        \"sha256\": \"1129ef803a43bbaa4d884400b3da6e9c0af2afac83f809afaca65a2b721386e4\",\n        \"size\": 234243765\n    },\n    \"VehicleTurningRoutePedestrian_Town15_Route482_Weather20.tar.gz\": {\n        \"sha256\": \"b7190ab189925c0cdb51bcff614e4ee1130981253bdeca1a389191b44c78415b\",\n        \"size\": 318086239\n    },\n    \"VehicleTurningRoutePedestrian_Town15_Route523_Weathe.tar.gz\": {\n        \"sha256\": \"3863318aeefac7dcddc06a6bd5c4ef277f59c4e4e532678e72a76c2934de09d0\",\n        \"size\": 360371905\n    },\n    \"VehicleTurningRoute_Town12_Route1026_Weather12.tar.gz\": {\n        \"sha256\": \"ac093bb77a049fae7d358420a58589792ad29dc741d6ef87c1c3571c690d06f6\",\n        \"size\": 158534487\n    },\n    \"VehicleTurningRoute_Town12_Route822_Weather18.tar.gz\": {\n        \"sha256\": \"a6a12d4814a337c95d4bf08d1a1d1b763e6eef36cce25723a9dc118fd397d478\",\n        \"size\": 429718393\n    },\n    \"VehicleTurningRoute_Town12_Route824_Weather20.tar.gz\": {\n        \"sha256\": \"b1160febf6b71d82281e1c0a401087bfbe7e3411b33861878cf9505710e0e8b1\",\n        \"size\": 136678128\n    },\n    \"VehicleTurningRoute_Town12_Route825_Weather21.tar.gz\": {\n        \"sha256\": \"855472eebfc106c503eeba921420d61b7a4145ef170802bda5614a1b9913116a\",\n        \"size\": 322192849\n    },\n    \"VehicleTurningRoute_Town12_Route933_Weather23.tar.gz\": {\n        \"sha256\": \"87f3e968b5ae99929368b0d45ba17a7d17484181e2fc0da2f2d9cf4c85bd38a6\",\n        \"size\": 164128081\n    },\n    \"VehicleTurningRoute_Town12_Route997_Weather9.tar.gz\": {\n        \"sha256\": \"0a67f4c47f550c8439d24b3ba35dd5713e98d7c6b27cf5f7bf0f3f3dbfc181c0\",\n        \"size\": 434001195\n    },\n    \"VehicleTurningRoute_Town13_Route605_Weather9.tar.gz\": {\n        \"sha256\": \"1f71fb1f07b741ad9b97a50bd590624e5ba78f07dc1bb14cd4d8641667bde008\",\n        \"size\": 352553801\n    },\n    \"VehicleTurningRoute_Town13_Route606_Weather18.tar.gz\": {\n        \"sha256\": \"43b74a8029917e9f2368acde8e58520c7d7fb9d78e95e18a8659d1dbce18685e\",\n        \"size\": 500760797\n    },\n    \"VehicleTurningRoute_Town13_Route679_Weather3.tar.gz\": {\n        \"sha256\": \"39d24e3d1ca664eecc78a58549117d5769ba1ca396870c7e36ffbf1fce0744eb\",\n        \"size\": 195012475\n    },\n    \"VehicleTurningRoute_Town13_Route698_Weather22.tar.gz\": {\n        \"sha256\": \"4ed9e3f3908970a8cef1409d807a5ea787ba6b4f2db3fe25d72d40899921e350\",\n        \"size\": 205106000\n    },\n    \"VehicleTurningRoute_Town13_Route699_Weather23.tar.gz\": {\n        \"sha256\": \"0d8d3a4f91922da2d75b7b0e5783a135a095a3871601e5ca44136f58b9b81283\",\n        \"size\": 200808587\n    },\n    \"VehicleTurningRoute_Town13_Route700_Weather23.tar.gz\": {\n        \"sha256\": \"9eb2afce9a176407861161059f1ee34ab0260679b29ad9a1b7be4743bf4b3297\",\n        \"size\": 234636000\n    },\n    \"VehicleTurningRoute_Town15_Route1367_Weather3.tar.gz\": {\n        \"sha256\": \"a805c191adbe45f567251d10a417a62c91d8b7925473dd885657e653bfaefef5\",\n        \"size\": 352512733\n    },\n    \"VehicleTurningRoute_Town15_Route1368_Weather5.tar.gz\": {\n        \"sha256\": \"95ea719749b2677127c4e2f38598655a83d26c9b352de3edbd2aa19a7baa4992\",\n        \"size\": 366522208\n    },\n    \"VehicleTurningRoute_Town15_Route1369_Weather6.tar.gz\": {\n        \"sha256\": \"cb45fcc2b45baa07884c01ffe5110dd24d726f7d712c2dbde9cba7f2b16392c0\",\n        \"size\": 251428724\n    },\n    \"VehicleTurningRoute_Town15_Route1370_Weather7.tar.gz\": {\n        \"sha256\": \"235f7979906c8306d82a9c2c5555115a3fed866f8468cb4abe0c1c475caf54ac\",\n        \"size\": 343523800\n    },\n    \"VehicleTurningRoute_Town15_Route1374_Weather13.tar.gz\": {\n        \"sha256\": \"5d2dddccce34cdf833f7d13d7c27de0dd5be3d0f50d7946b5e4eac754b4d84c4\",\n        \"size\": 315159752\n    },\n    \"VehicleTurningRoute_Town15_Route1376_Weather15.tar.gz\": {\n        \"sha256\": \"355b5856362060c3c5fa256b46a1db2cd2bf34d50e1f5bbceedaaf5ebc57c6e8\",\n        \"size\": 306093213\n    },\n    \"VehicleTurningRoute_Town15_Route1377_Weather8.tar.gz\": {\n        \"sha256\": \"bcedcfd95e08976d45d9d6dfea5d817d732e346731cb42e69e183fb63b5d4424\",\n        \"size\": 231038024\n    },\n    \"VehicleTurningRoute_Town15_Route1378_Weather9.tar.gz\": {\n        \"sha256\": \"bffd74a60637a5854494ab1233aa288bc6677c08b3ad34e6079beaf4fc3a0e42\",\n        \"size\": 254040737\n    },\n    \"VehicleTurningRoute_Town15_Route1379_Weather18.tar.gz\": {\n        \"sha256\": \"edea54a71be761e3b59ae4bd319a81e62e33132fea761aebca5c1bce49875a14\",\n        \"size\": 278122038\n    },\n    \"VehicleTurningRoute_Town15_Route1380_Weather19.tar.gz\": {\n        \"sha256\": \"6d7fefe01e38da9422b8e0be37103579a02948ce33c181b21f6e4d60eb0236f4\",\n        \"size\": 250685466\n    },\n    \"VehicleTurningRoute_Town15_Route443_Weather1.tar.gz\": {\n        \"sha256\": \"97a066963571c10fd91ec0ee45bd5fc598e79ea2f1cf153e8617887ad83b2b5a\",\n        \"size\": 487312838\n    },\n    \"VehicleTurningRoute_Town15_Route479_Weather11.tar.gz\": {\n        \"sha256\": \"cfbbf7d74ac8ef60b005df7bea5606c1e8c4cea88bb5244eb31771eeac883eb5\",\n        \"size\": 234759870\n    },\n    \"VehicleTurningRoute_Town15_Route480_Weather18.tar.gz\": {\n        \"sha256\": \"d94f6dea12de21146f7a25ba3f8036baa28f1567af1ead48f90f4a6301763c00\",\n        \"size\": 248397689\n    },\n    \"VehicleTurningRoute_Town15_Route504_Weather10.tar.gz\": {\n        \"sha256\": \"5557528e51db301cf0eed521bdad1d04427dc544f78817f938b35e803ef14182\",\n        \"size\": 311701616\n    },\n    \"VehicleTurningRoute_Town15_Route519_Weather25.tar.gz\": {\n        \"sha256\": \"70af91ea872f02de585cf1584a8cf3f0113772d70c59bdaddc0ce947f20742cd\",\n        \"size\": 264756036\n    },\n    \"YieldToEmergencyVehicle_Town03_Route148_Weather18.tar.gz\": {\n        \"sha256\": \"e2194bd3c9983ec76347585f2472cab4d93258e70115ca26b706fa6dd66f73b0\",\n        \"size\": 114626256\n    },\n    \"YieldToEmergencyVehicle_Town04_Route165_Weather7.tar.gz\": {\n        \"sha256\": \"feb52345f09a5358728dd2ed32db93cf64a5d2b0d04d4719a38d408c60c212df\",\n        \"size\": 183804370\n    },\n    \"YieldToEmergencyVehicle_Town04_Route166_Weather10.tar.gz\": {\n        \"sha256\": \"c1939ac3cfe69f4ffca865904244b7ef0c52016daa1eb317685151893ecab010\",\n        \"size\": 337303222\n    },\n    \"YieldToEmergencyVehicle_Town04_Route207_Weather25.tar.gz\": {\n        \"sha256\": \"08f530647fe6c649236a14c22e6d461ab0b0684f694b8479a8430229c992fdf8\",\n        \"size\": 141954055\n    },\n    \"YieldToEmergencyVehicle_Town05_Route225_Weather9.tar.gz\": {\n        \"sha256\": \"6bf78cef0ea3292a8766651618059b0767b22eef356312dd01203c742549b491\",\n        \"size\": 311757367\n    },\n    \"YieldToEmergencyVehicle_Town12_Route778_Weather14.tar.gz\": {\n        \"sha256\": \"4d3079d3e15046d050f031f607f52279479bb5c5ba8f64149411cea8c98cae6a\",\n        \"size\": 129791102\n    },\n    \"YieldToEmergencyVehicle_Town12_Route779_Weather25.tar.gz\": {\n        \"sha256\": \"b7d3599c2d9bf3eead134e6c4fda3d8cac13849e042fbc18d81e895bf4bd32cd\",\n        \"size\": 346567434\n    },\n    \"YieldToEmergencyVehicle_Town12_Route781_Weather8.tar.gz\": {\n        \"sha256\": \"f79f36377060c9ed67be6d9598a9478888010496364f3da4ff6c2b1d955d1465\",\n        \"size\": 366525037\n    },\n    \"YieldToEmergencyVehicle_Town12_Route917_Weather7.tar.gz\": {\n        \"sha256\": \"2e8137dd3f8ef5343a6116f96e3213b12fd9e13621cfdeb8477491721dadae46\",\n        \"size\": 156581534\n    },\n    \"YieldToEmergencyVehicle_Town12_Route918_Weather8.tar.gz\": {\n        \"sha256\": \"6d7a04157a55b19e36d8c4571c4a3fe61183aa70d80ca5dae971a646e5e8169f\",\n        \"size\": 152258286\n    },\n    \"YieldToEmergencyVehicle_Town12_Route919_Weather11.tar.gz\": {\n        \"sha256\": \"b523f7ca0e763a1510630ead2c3a08733309e0e4fcb4e7ff37d8d267459d249a\",\n        \"size\": 270793773\n    },\n    \"YieldToEmergencyVehicle_Town13_Route560_Weather14.tar.gz\": {\n        \"sha256\": \"e8a2266e4faa7dd0c3a1e742e13dadd3512ef22259f7a7e42ad9d8ec98e4e755\",\n        \"size\": 561808864\n    },\n    \"YieldToEmergencyVehicle_Town13_Route561_Weather14.tar.gz\": {\n        \"sha256\": \"4d316eeea53badeea078266382832843f58050f1c7cc2f5b0a08fea4cb4fc434\",\n        \"size\": 216266711\n    },\n    \"YieldToEmergencyVehicle_Town13_Route562_Weather15.tar.gz\": {\n        \"sha256\": \"74f6e66dd979ab5434bf92a1930ead22d0a038c35dcfd648cab606ee40f4f0eb\",\n        \"size\": 494214024\n    },\n    \"YieldToEmergencyVehicle_Town13_Route673_Weather23.tar.gz\": {\n        \"sha256\": \"112605413c14fd3a4922cb8bd89fe50923a331cd3d47dcd637aa3e8ea3bb0351\",\n        \"size\": 293601671\n    },\n    \"YieldToEmergencyVehicle_Town13_Route675_Weather25.tar.gz\": {\n        \"sha256\": \"922a7bf18a4042b5d8e931d2f5df0c42fb518d771a830668c3f00c792911ea44\",\n        \"size\": 355324884\n    },\n    \"YieldToEmergencyVehicle_Town15_Route423_Weather7.tar.gz\": {\n        \"sha256\": \"2e4fe3138e6d2813e903f7692181740092c61462573ebe3ed5e43065131650ac\",\n        \"size\": 325792761\n    },\n    \"YieldToEmergencyVehicle_Town15_Route424_Weather8.tar.gz\": {\n        \"sha256\": \"aab95418ab5ce6801af4bd442244583542f6220fa72e4e7ceb42e46e50a7def1\",\n        \"size\": 281237114\n    },\n    \"YieldToEmergencyVehicle_Town15_Route425_Weather9.tar.gz\": {\n        \"sha256\": \"a9e2bab4889cf738537b4f2ce6ccccdf8cb3b554d04beba71ddf829e26524606\",\n        \"size\": 271277312\n    }\n}"
  },
  {
    "path": "close_loop/VAD_MomAD/docs/bench2drive_full+sup_13638.json",
    "content": "{\n    \"AccidentTwoWays_Town05_Route25857_Weather5.tar.gz\": {\n        \"sha256\": \"e00609aa51624aeadf6f5969f82f5ed1c1adb2aa3eb134972a9c58d00083e0cb\",\n        \"size\": 435387626\n    },\n    \"AccidentTwoWays_Town05_Route25864_Weather12.tar.gz\": {\n        \"sha256\": \"9cae769e9844b6ae84e59438bb86cab3e1a8be76eb0d5591962137a921815c1b\",\n        \"size\": 312867683\n    },\n    \"AccidentTwoWays_Town05_Route25871_Weather21.tar.gz\": {\n        \"sha256\": \"39d51ef025da97797f0a4d1d13c54cdff062929e70a418ce5125a3eb7917add7\",\n        \"size\": 236054190\n    },\n    \"AccidentTwoWays_Town05_Route25885_Weather10.tar.gz\": {\n        \"sha256\": \"abcd9a082f66d2aef9c219399c5bb179f802e697f58df5055c003e618381c707\",\n        \"size\": 295763112\n    },\n    \"AccidentTwoWays_Town05_Route25906_Weather8.tar.gz\": {\n        \"sha256\": \"8dd89c965b6c3587e856abaa0943e476e104f0d02bacb980dbd423ef02e5c178\",\n        \"size\": 423815413\n    },\n    \"AccidentTwoWays_Town05_Route25913_Weather15.tar.gz\": {\n        \"sha256\": \"d3acaa1550e37cac1a7a1626ad3e8bc3096d7da992d338369051492890600f6a\",\n        \"size\": 269828229\n    },\n    \"AccidentTwoWays_Town05_Route25920_Weather25.tar.gz\": {\n        \"sha256\": \"039bb358787b4beff0f76d8cc13a745da5da8e89f6bce9003a3e23d816790b49\",\n        \"size\": 243903957\n    },\n    \"AccidentTwoWays_Town12_Route1845_Weather19.tar.gz\": {\n        \"sha256\": \"53a1dca09e3fcb9b761f71207170a668fd445ec06b070a2778f9c3e40639587c\",\n        \"size\": 1305555478\n    },\n    \"AccidentTwoWays_Town12_Route1848_Weather22.tar.gz\": {\n        \"sha256\": \"1d4b49f761c52938d677d75423f9df57b807d8febd9f26650319bfa1b7d63a26\",\n        \"size\": 532171244\n    },\n    \"AccidentTwoWays_Town12_Route1851_Weather25.tar.gz\": {\n        \"sha256\": \"a5c5fe71388f6423ae28f0c2d417d05c196c08169d6309be26faaa8efe7b3d31\",\n        \"size\": 587597260\n    },\n    \"AccidentTwoWays_Town12_Route1852_Weather0.tar.gz\": {\n        \"sha256\": \"3b23da8c89b6a670eef02544e8b6ddde7d75f7ac94fb5abab5e2482c95f51c90\",\n        \"size\": 226004876\n    },\n    \"AccidentTwoWays_Town12_Route1853_Weather1.tar.gz\": {\n        \"sha256\": \"c1aeec93a5c1ac74ebbea65060e9886710001ef78e7a27fc83d1a664ebf2383e\",\n        \"size\": 297417168\n    },\n    \"AccidentTwoWays_Town12_Route1854_Weather2.tar.gz\": {\n        \"sha256\": \"97d5f16b738b57dbb5d0bfe0ad4eaf00280648b1175e2c43b7f86cd863f60db1\",\n        \"size\": 320459602\n    },\n    \"AccidentTwoWays_Town12_Route1857_Weather5.tar.gz\": {\n        \"sha256\": \"b8b103cb0f72c9f8d4514e6182925815d55cfa4e79d45cc32183bc0f5b26fc0e\",\n        \"size\": 305450061\n    },\n    \"AccidentTwoWays_Town12_Route1859_Weather7.tar.gz\": {\n        \"sha256\": \"c47a47433abf0825f52d267d1e247dcad71a44e8ee447c58a5dfeac329499776\",\n        \"size\": 365360972\n    },\n    \"AccidentTwoWays_Town12_Route1860_Weather8.tar.gz\": {\n        \"sha256\": \"caec148b80fd2c530c2531601b4601f193aaed0d2e282fa425deb347394b1b39\",\n        \"size\": 334861946\n    },\n    \"AccidentTwoWays_Town12_Route1861_Weather9.tar.gz\": {\n        \"sha256\": \"f37764aa496814711f49834c7a701588430bfde2978b6af219f1b7a8830f1f1c\",\n        \"size\": 246841811\n    },\n    \"AccidentTwoWays_Town12_Route1863_Weather11.tar.gz\": {\n        \"sha256\": \"b3acea2e0c4397e9c28790337ce8c857877f8664dda7fba5fca9e036a192e10c\",\n        \"size\": 701105025\n    },\n    \"AccidentTwoWays_Town12_Route20934_Weather3.tar.gz\": {\n        \"sha256\": \"de7e21c199cb6d99ec2c0d62195bff7f7666c5e702718aeac48cde733e4976e5\",\n        \"size\": 303517030\n    },\n    \"AccidentTwoWays_Town12_Route20937_Weather6.tar.gz\": {\n        \"sha256\": \"e24c6d3b28cdc54741fac209f08c195c333ab0bb3a4930c403a8c8d7a1289dbc\",\n        \"size\": 266895399\n    },\n    \"AccidentTwoWays_Town12_Route20938_Weather7.tar.gz\": {\n        \"sha256\": \"b77ebf281f7d34b82644feda59e96b5e281537edb9d0a1581f275f244dfb58ff\",\n        \"size\": 300091118\n    },\n    \"AccidentTwoWays_Town12_Route20942_Weather11.tar.gz\": {\n        \"sha256\": \"b4cc5cd47242ae6a87239a6010e67bbd7e16f8842276df6d954a2f782b4f93fc\",\n        \"size\": 251840695\n    },\n    \"AccidentTwoWays_Town12_Route20943_Weather12.tar.gz\": {\n        \"sha256\": \"77d4a06dc55184f1dd21cd52dcf70181eb17f41f2ef8efd78b0f7bca022d263f\",\n        \"size\": 234380104\n    },\n    \"AccidentTwoWays_Town12_Route20944_Weather13.tar.gz\": {\n        \"sha256\": \"8cbbe6587911483f75b1dd2c92b10087452017f6137e843fcf7442613aa0fe3a\",\n        \"size\": 242466239\n    },\n    \"AccidentTwoWays_Town12_Route20945_Weather14.tar.gz\": {\n        \"sha256\": \"ecb2a94dc59ddbe90b29faeb16ac54c4b7c1a15f712f85c7a04227ad94b7ccaa\",\n        \"size\": 267804759\n    },\n    \"AccidentTwoWays_Town12_Route20949_Weather18.tar.gz\": {\n        \"sha256\": \"7f3e6782e0cfbebe9d4a7f46f08fe4e93fb004d52543de859d4ed44bd351eb13\",\n        \"size\": 320233239\n    },\n    \"AccidentTwoWays_Town12_Route20950_Weather19.tar.gz\": {\n        \"sha256\": \"c36d37b8cb04e78fcaabd282ce2f514c8ccb38818b7c28009974ad5e16335d37\",\n        \"size\": 303894859\n    },\n    \"AccidentTwoWays_Town12_Route20951_Weather20.tar.gz\": {\n        \"sha256\": \"a3af2c554b03776b2fc501f2cf3e6660582e96b247f448308ec818d0a8a6c071\",\n        \"size\": 274581664\n    },\n    \"AccidentTwoWays_Town12_Route20953_Weather22.tar.gz\": {\n        \"sha256\": \"5f1c4342264db5ae9f34e57774a8a69a2590ff8b4579090e00d84e0e4a3b5dc8\",\n        \"size\": 258694942\n    },\n    \"AccidentTwoWays_Town12_Route20955_Weather23.tar.gz\": {\n        \"sha256\": \"2729f54cff5d29bfcf035828452f8f51c2c242f53d57b95f40af6a5235f27a62\",\n        \"size\": 248606210\n    },\n    \"AccidentTwoWays_Town12_Route20957_Weather0.tar.gz\": {\n        \"sha256\": \"9a1d7f11fef3ef49fc1d28425f46c634d0bf564f14841b2c15a2613c0c5567d8\",\n        \"size\": 339961857\n    },\n    \"AccidentTwoWays_Town12_Route20960_Weather3.tar.gz\": {\n        \"sha256\": \"956b23e3724464a09445b2ad422ade5283e63f443e07d27b690054ad3e6e4b02\",\n        \"size\": 291505138\n    },\n    \"AccidentTwoWays_Town12_Route20961_Weather3.tar.gz\": {\n        \"sha256\": \"e89abbfda315e11d989f2435b82ac399880b6c396264a6a59135cc943d73886a\",\n        \"size\": 289598036\n    },\n    \"AccidentTwoWays_Town12_Route20963_Weather6.tar.gz\": {\n        \"sha256\": \"7401ed9358dbefd6258d3149ec416eb43987141f9deb9313628880e5344cc5f5\",\n        \"size\": 275830186\n    },\n    \"AccidentTwoWays_Town12_Route20965_Weather8.tar.gz\": {\n        \"sha256\": \"8e856b97381518d215242dc2b91b2c6f9eb3b7b10176dea2f0e423770c7c2a9e\",\n        \"size\": 280687193\n    },\n    \"AccidentTwoWays_Town12_Route20966_Weather9.tar.gz\": {\n        \"sha256\": \"f163483347042d0a8af9ad020dd170a473139206ce4dd86364a33ac3fbdb6812\",\n        \"size\": 227223493\n    },\n    \"AccidentTwoWays_Town12_Route20967_Weather10.tar.gz\": {\n        \"sha256\": \"c23d153be8b8448dd36665204e05b66e150843d9300b82b3aaedb291597c7c68\",\n        \"size\": 296704139\n    },\n    \"AccidentTwoWays_Town12_Route20968_Weather11.tar.gz\": {\n        \"sha256\": \"5743720b04c07d4858bdbd37ce0dea0d8701862c2f620f4c42dc0285d2990e90\",\n        \"size\": 230201231\n    },\n    \"AccidentTwoWays_Town12_Route20970_Weather13.tar.gz\": {\n        \"sha256\": \"7b683df40e9e0b923332f2895798585cc772afe127572cd0bcfdb6d0e4ff0018\",\n        \"size\": 235413566\n    },\n    \"AccidentTwoWays_Town12_Route20971_Weather14.tar.gz\": {\n        \"sha256\": \"34e067fe43a59628d6b3078e190af5c231683a5bfd40dd14e8ea08c9cf5bde8a\",\n        \"size\": 259859120\n    },\n    \"AccidentTwoWays_Town12_Route20972_Weather15.tar.gz\": {\n        \"sha256\": \"abc3d3dc1c8a886b6fc6035f7c3fa95f895d63bbfc5c82f6bdf708cdb0f82dce\",\n        \"size\": 271787581\n    },\n    \"AccidentTwoWays_Town12_Route20973_Weather8.tar.gz\": {\n        \"sha256\": \"0584ee6e6fc2981c141eaa64f9efb235d7af1227e1ada50fde1a908b7be30a59\",\n        \"size\": 290260092\n    },\n    \"AccidentTwoWays_Town12_Route20975_Weather18.tar.gz\": {\n        \"sha256\": \"291b13b11ef9441342fa3ad0ef00f91bb00bf2a38354c84980f04df9fb3b5063\",\n        \"size\": 294280138\n    },\n    \"AccidentTwoWays_Town12_Route20976_Weather19.tar.gz\": {\n        \"sha256\": \"cb8d5d56835e303e3db077575f21f6a19761131757cca606a6bc82f73bcbbada\",\n        \"size\": 287694642\n    },\n    \"AccidentTwoWays_Town12_Route20977_Weather20.tar.gz\": {\n        \"sha256\": \"c8d97ad49bc519541517b4358d8a98d6cf9e7b87508c2f7feaa169ec6c23cd1e\",\n        \"size\": 277619973\n    },\n    \"AccidentTwoWays_Town12_Route20978_Weather21.tar.gz\": {\n        \"sha256\": \"f1c2d4cec545415d9a4fba386a3cb4fd9d49992bbb85262c9c8e9d4e8c36beca\",\n        \"size\": 247629862\n    },\n    \"AccidentTwoWays_Town12_Route20979_Weather22.tar.gz\": {\n        \"sha256\": \"4c800f22542842b20e4542ef29a2c27a1b25071fb7c82279142c2c370c9e2886\",\n        \"size\": 273028306\n    },\n    \"AccidentTwoWays_Town12_Route20981_Weather23.tar.gz\": {\n        \"sha256\": \"8e4624f630a838f16972c3a51f2c88932064712d227048e05d5cde5419edd571\",\n        \"size\": 254759094\n    },\n    \"AccidentTwoWays_Town12_Route20984_Weather1.tar.gz\": {\n        \"sha256\": \"336c85aa2ab8192972d03a8c3a362bb217402b1c0cd632f783201cd9cd611eb5\",\n        \"size\": 307408895\n    },\n    \"AccidentTwoWays_Town12_Route20985_Weather2.tar.gz\": {\n        \"sha256\": \"75e1ace851ac08d126528a0d6bb5b63c6bc903ac4aa26a8762d7b37a72741602\",\n        \"size\": 306105961\n    },\n    \"AccidentTwoWays_Town12_Route20986_Weather3.tar.gz\": {\n        \"sha256\": \"c1628cc0c287cbdbb74eff695cd9c81501d909000b1388eafe4cd7f2607e02dc\",\n        \"size\": 324081107\n    },\n    \"AccidentTwoWays_Town12_Route20990_Weather7.tar.gz\": {\n        \"sha256\": \"921d3ba26fe9e53fbbf9f1621ab2e1535d2b418dad0c1de66b6f8e2af006b41e\",\n        \"size\": 311361232\n    },\n    \"AccidentTwoWays_Town12_Route20991_Weather8.tar.gz\": {\n        \"sha256\": \"54c7805f910d0a673d75acca54bee42e6f959d7ed132854372375220e90b937e\",\n        \"size\": 276737650\n    },\n    \"AccidentTwoWays_Town12_Route20992_Weather9.tar.gz\": {\n        \"sha256\": \"6b304af7db479c79ecdefce872fb24a2c296465d09cddb1e4be11a709d274241\",\n        \"size\": 255018700\n    },\n    \"AccidentTwoWays_Town12_Route2624_Weather18.tar.gz\": {\n        \"sha256\": \"51facaa8a1ed25db5f9d7f53b8453d30320861d0afdc4e5445cdc7b1036f0c4e\",\n        \"size\": 638130834\n    },\n    \"AccidentTwoWays_Town12_Route2629_Weather23.tar.gz\": {\n        \"sha256\": \"c892ebb5369696bc8b80ebe9e61e77562ef5806c9fa4b72bfac8d4a1aed5aa7c\",\n        \"size\": 266172535\n    },\n    \"AccidentTwoWays_Town12_Route2632_Weather0.tar.gz\": {\n        \"sha256\": \"7cd237c40c2068d0bf123e5cb7b78a9fb040d5e7695115be6390734a1eb6e822\",\n        \"size\": 293828285\n    },\n    \"AccidentTwoWays_Town12_Route2635_Weather3.tar.gz\": {\n        \"sha256\": \"522c5cf39815c51c4621b8d027a53be69bd2add290334a424a1002698da09340\",\n        \"size\": 393889538\n    },\n    \"AccidentTwoWays_Town12_Route2637_Weather5.tar.gz\": {\n        \"sha256\": \"7e7847f75ebebf62b44c1847da02699a0b15c8d23ef679311c14e4fa40bab3dc\",\n        \"size\": 493634889\n    },\n    \"AccidentTwoWays_Town12_Route2641_Weather9.tar.gz\": {\n        \"sha256\": \"edce53461848f08939df63be707f8153addaa280677c38a5e59ce2912ef7a90a\",\n        \"size\": 237853814\n    },\n    \"AccidentTwoWays_Town12_Route2642_Weather10.tar.gz\": {\n        \"sha256\": \"5c9c86b421f5414e8f269774fd4706313df33b695ff5b01de5f38e7c0ed1dece\",\n        \"size\": 316245992\n    },\n    \"AccidentTwoWays_Town12_Route2643_Weather11.tar.gz\": {\n        \"sha256\": \"a9d63e9a465df7c58c5f1ad659c3369f66450e516dc171bccf9d589fe3897afe\",\n        \"size\": 303190633\n    },\n    \"AccidentTwoWays_Town13_Route1007_Weather21.tar.gz\": {\n        \"sha256\": \"43cec4c85f6324cc139b6cfc4b77058b23fc9290a7e131707be8f3c7c30d6c86\",\n        \"size\": 303142155\n    },\n    \"AccidentTwoWays_Town13_Route1037_Weather2.tar.gz\": {\n        \"sha256\": \"06fc25290fe49e35c6fbabff6f62dfa3acfbb4b53ab7f46597f1bf35316a7e9a\",\n        \"size\": 338559896\n    },\n    \"AccidentTwoWays_Town13_Route1090_Weather10.tar.gz\": {\n        \"sha256\": \"ebc4fcede0e4eabf042cc9d75b539b6a7681ee22a995e10e59ef62ce398c1ad0\",\n        \"size\": 338971759\n    },\n    \"AccidentTwoWays_Town13_Route1150_Weather0.tar.gz\": {\n        \"sha256\": \"7f7f755cd1bb99f4646d061f0f1f50d81be70534d81a2c19fdf76fd95c2584e1\",\n        \"size\": 432822461\n    },\n    \"AccidentTwoWays_Town13_Route1210_Weather15.tar.gz\": {\n        \"sha256\": \"9557774d53978e8f6b1fba68d9bb5ae7c263214cb9f84025c19554bef1385cdd\",\n        \"size\": 227599365\n    },\n    \"AccidentTwoWays_Town13_Route1224_Weather6.tar.gz\": {\n        \"sha256\": \"e3ca361a1f6b2b9ddbeecd8b4ba7550d58415737ea6e73487d7b1072197872c8\",\n        \"size\": 593369299\n    },\n    \"AccidentTwoWays_Town13_Route1244_Weather2.tar.gz\": {\n        \"sha256\": \"894ed70218f3329c86954bd9fd5d4850f307fdb86352ee7128ff14887cbe2a56\",\n        \"size\": 376665853\n    },\n    \"AccidentTwoWays_Town13_Route1271_Weather7.tar.gz\": {\n        \"sha256\": \"37cfaa086062928d7a37c1cf5e97a8d0539ba89752df2da8b061d907ea4c974a\",\n        \"size\": 397461263\n    },\n    \"AccidentTwoWays_Town13_Route1277_Weather13.tar.gz\": {\n        \"sha256\": \"d71df29368cabcff3e46676c1815ff5ae9fc4284ed3aead8fbfc858c551e2b60\",\n        \"size\": 237585302\n    },\n    \"AccidentTwoWays_Town13_Route1317_Weather7.tar.gz\": {\n        \"sha256\": \"56464ce81b18da658c9339504c80a4077cc2d81716cb2e8eb7de9d1c7542506d\",\n        \"size\": 414991980\n    },\n    \"AccidentTwoWays_Town13_Route30360_Weather10.tar.gz\": {\n        \"sha256\": \"33a431d9825b62402921791d2094b10b7d6b76b944f3067a3624526d1c507cd0\",\n        \"size\": 569001720\n    },\n    \"AccidentTwoWays_Town13_Route30362_Weather12.tar.gz\": {\n        \"sha256\": \"956958110528cfe407fa48c44bc2121de3c8fc852e4e194da0a7cdb377b58309\",\n        \"size\": 280688362\n    },\n    \"AccidentTwoWays_Town13_Route30369_Weather21.tar.gz\": {\n        \"sha256\": \"7b6125b7982f9eeb264209ead4707373de083e2c4b6825e33fcd6b562d8e9db2\",\n        \"size\": 395639603\n    },\n    \"AccidentTwoWays_Town13_Route30378_Weather5.tar.gz\": {\n        \"sha256\": \"bcc79f89b7d7329c52c4affc5d0b9560bdc435fd9276c301b58034175e2907f6\",\n        \"size\": 351106376\n    },\n    \"AccidentTwoWays_Town13_Route30384_Weather11.tar.gz\": {\n        \"sha256\": \"5267a7e4877945eaaaa765257b638158ef1bb6365614f6d255a3102b669486f4\",\n        \"size\": 238111487\n    },\n    \"AccidentTwoWays_Town13_Route30408_Weather12.tar.gz\": {\n        \"sha256\": \"ea31fb5ae0e4810d0a3b25e936eb5c2e8b9dd07ced3a7cdd95b85772d1f143e3\",\n        \"size\": 258674140\n    },\n    \"AccidentTwoWays_Town13_Route30440_Weather23.tar.gz\": {\n        \"sha256\": \"cfa4cfb88cfefb4791477e60a532ebce30b77055756edaa3d7ae3811eef59030\",\n        \"size\": 334415520\n    },\n    \"AccidentTwoWays_Town13_Route30458_Weather18.tar.gz\": {\n        \"sha256\": \"1e9e8910907719c9a4be17231009691dc12205336c4c0b492307f7694f44e54a\",\n        \"size\": 485859436\n    },\n    \"AccidentTwoWays_Town13_Route30459_Weather19.tar.gz\": {\n        \"sha256\": \"973aa58d861a7759ef07da6a026158f4afa76a6790e324f482239bb11dedd46b\",\n        \"size\": 815284127\n    },\n    \"AccidentTwoWays_Town13_Route30491_Weather2.tar.gz\": {\n        \"sha256\": \"04c6051a2e03f64f7905667abbeb0149542e80aaf25dd89cce84808fd394d792\",\n        \"size\": 365036171\n    },\n    \"AccidentTwoWays_Town13_Route30508_Weather22.tar.gz\": {\n        \"sha256\": \"e8cd66c103b577e8a7748d8b5169381dd1e0b30ea8bac598272836505d5e298a\",\n        \"size\": 301815433\n    },\n    \"AccidentTwoWays_Town13_Route30510_Weather25.tar.gz\": {\n        \"sha256\": \"ec88ceb7997e82a40b36bf3e4943ea567cf6fa8cce6de5c3b92fc5355ecdc462\",\n        \"size\": 270098698\n    },\n    \"AccidentTwoWays_Town13_Route3405_Weather20.tar.gz\": {\n        \"sha256\": \"45c74f34ddd7b78a60cbcf878a5917b131771e9f5054922002a73ea63b1a2da4\",\n        \"size\": 413266245\n    },\n    \"AccidentTwoWays_Town13_Route3410_Weather25.tar.gz\": {\n        \"sha256\": \"70f5be4bae821e218c8785fc8275c3ce0fe24cef8d3e26add50c4664c12214fe\",\n        \"size\": 513108053\n    },\n    \"AccidentTwoWays_Town13_Route3411_Weather0.tar.gz\": {\n        \"sha256\": \"de0f13b6b4500193c518889a5b2a9d6dad93b0c56a74e2b74b694e14ba1e6aeb\",\n        \"size\": 487386333\n    },\n    \"AccidentTwoWays_Town13_Route3413_Weather2.tar.gz\": {\n        \"sha256\": \"123d12bb3ce7e07aaf8fbf08372ed19605c8b30edbaaabf3f369a5c588569294\",\n        \"size\": 376630543\n    },\n    \"AccidentTwoWays_Town13_Route3414_Weather3.tar.gz\": {\n        \"sha256\": \"969042d9f6778f35030270be17552c5237e8574e3698887fb1715192de0aa6d4\",\n        \"size\": 753399450\n    },\n    \"AccidentTwoWays_Town13_Route3417_Weather6.tar.gz\": {\n        \"sha256\": \"7b4e00842f2785bcf5397567e111fc44df96178c41d7de1d57b0ed761cb16c45\",\n        \"size\": 379217952\n    },\n    \"AccidentTwoWays_Town13_Route3419_Weather8.tar.gz\": {\n        \"sha256\": \"56f8e5f27e3935decb2c320696127b25dc07768f87e72a6e81ce0129ea2e691e\",\n        \"size\": 705224706\n    },\n    \"AccidentTwoWays_Town13_Route3422_Weather11.tar.gz\": {\n        \"sha256\": \"13fac80ffc7e0400a1eeab14615b21d258390a773579f909bf8bda9b6f9998f0\",\n        \"size\": 332847812\n    },\n    \"AccidentTwoWays_Town15_Route25845_Weather18.tar.gz\": {\n        \"sha256\": \"45f9ab2d1056ef5c175c97cc37acfc318f4ec5aae0c7831f5b5075909bfd8dd9\",\n        \"size\": 672990662\n    },\n    \"AccidentTwoWays_Town15_Route25894_Weather21.tar.gz\": {\n        \"sha256\": \"8e821d2243933419578ca9e2a0bf889bd7e89113fbdb94d26644277cbd569e1e\",\n        \"size\": 941224281\n    },\n    \"AccidentTwoWays_Town15_Route25943_Weather25.tar.gz\": {\n        \"sha256\": \"2d6f74f48eaefee02102ba7e6b6762f9aa602d9848d039335a82582f39a111b4\",\n        \"size\": 365786076\n    },\n    \"AccidentTwoWays_Town15_Route25957_Weather13.tar.gz\": {\n        \"sha256\": \"6af36bf594cc2b04e5a6aabec6342d67ce008543cb22abb9f87b80f824bc5601\",\n        \"size\": 612453234\n    },\n    \"Accident_Town03_Route24816_Weather25.tar.gz\": {\n        \"sha256\": \"365196b0b3c581b56f08b6f255b1fc92e27679d3821e9c1e4ed734523b2ebb39\",\n        \"size\": 185727459\n    },\n    \"Accident_Town10HD_Route24240_Weather23.tar.gz\": {\n        \"sha256\": \"00cc1b1902f4ff2dfec92011512dd61bb8fa01ad267ac32e5b9f7bdf488e4a38\",\n        \"size\": 248618161\n    },\n    \"Accident_Town12_Route1744_Weather22.tar.gz\": {\n        \"sha256\": \"ec7c03adcc8a07068d674b60517d92f4b035b3cbc953cabdce6ab214e7d6c4cb\",\n        \"size\": 366129099\n    },\n    \"Accident_Town12_Route1745_Weather23.tar.gz\": {\n        \"sha256\": \"ad3cfd42e8ced451bb854a9862b29907fce5fa00cf2f163a1e0aa3d349517d9a\",\n        \"size\": 305248598\n    },\n    \"Accident_Town12_Route1747_Weather25.tar.gz\": {\n        \"sha256\": \"54c28c0de0c7b840aa20394983c4bc5c11b5b37c40c696e44cc31aa3bfd300ea\",\n        \"size\": 265106233\n    },\n    \"Accident_Town12_Route1748_Weather0.tar.gz\": {\n        \"sha256\": \"ba26cf21f8b31b24d99db320dd7d0e518e66de72e0d85226633a704d60ef7944\",\n        \"size\": 418288015\n    },\n    \"Accident_Town12_Route1749_Weather1.tar.gz\": {\n        \"sha256\": \"39273fc234e2c47d77cb9e491fdbeeca571f28119a67c8265260d9fd5764ee37\",\n        \"size\": 487572195\n    },\n    \"Accident_Town12_Route1751_Weather3.tar.gz\": {\n        \"sha256\": \"d035ddde01f944ee1ece05d8653450bdfdd5a377f455060ddb9e62bcc33c5759\",\n        \"size\": 474515987\n    },\n    \"Accident_Town12_Route1756_Weather8.tar.gz\": {\n        \"sha256\": \"7128f797b1d7d87c059ad05396a7a342ebfadf4b33d8040daeccf8cdf570dc3e\",\n        \"size\": 172407118\n    },\n    \"Accident_Town12_Route1757_Weather9.tar.gz\": {\n        \"sha256\": \"ec638ad43efcff4c8c284965528041963e3b0dd1742f5de1aa1c30d6120c4866\",\n        \"size\": 404058304\n    },\n    \"Accident_Town12_Route1759_Weather11.tar.gz\": {\n        \"sha256\": \"f34e80127f1a60861f30b28f6a84261900f0ebe9998c9286fae2fe5ab374372d\",\n        \"size\": 299689597\n    },\n    \"Accident_Town12_Route1760_Weather12.tar.gz\": {\n        \"sha256\": \"cf1e799fb28d6cc49a9e1a7b13633bbc0944cf6a57b392f97eb38a1dd858144c\",\n        \"size\": 386780436\n    },\n    \"Accident_Town12_Route19072_Weather13.tar.gz\": {\n        \"sha256\": \"eaec8061fab2a54df7204df9dcccfed10890e75a52d9a371c5267655b305d47c\",\n        \"size\": 149656399\n    },\n    \"Accident_Town12_Route19073_Weather14.tar.gz\": {\n        \"sha256\": \"4dd36ca547ba4083e77d6f872a4375a69e6675811f462a83cc6eedcca3ab17ae\",\n        \"size\": 132670857\n    },\n    \"Accident_Town12_Route19074_Weather15.tar.gz\": {\n        \"sha256\": \"1d77c237ecc47aa8ec3a6ce737f5c0bef4ec4c2d37c07b14072157a59bc3cd61\",\n        \"size\": 227861955\n    },\n    \"Accident_Town12_Route19075_Weather8.tar.gz\": {\n        \"sha256\": \"fde36fedaad3fbfdecced0b05becbabc90f107d3f0012b4f0e03528380ae3ae7\",\n        \"size\": 422395813\n    },\n    \"Accident_Town12_Route19077_Weather18.tar.gz\": {\n        \"sha256\": \"f10b8d128702daa51151d1f31a835d147fb5e7462c788ae9dd499562c1fbc264\",\n        \"size\": 314756754\n    },\n    \"Accident_Town12_Route19078_Weather19.tar.gz\": {\n        \"sha256\": \"d23636f79b91b566e3cc92ae61de1f7902434a895d6328b4fab40f3b4aab94cb\",\n        \"size\": 436298222\n    },\n    \"Accident_Town12_Route19081_Weather22.tar.gz\": {\n        \"sha256\": \"5ade54db929e6b9364816f8b1d12d5a0a5558c199bb02ed21069439d3c569fca\",\n        \"size\": 484382593\n    },\n    \"Accident_Town12_Route19082_Weather23.tar.gz\": {\n        \"sha256\": \"cad3abcaf33a12accba51023e8aac0ae3d63fb2c83041b2cb57a8eb62e20fc33\",\n        \"size\": 409730660\n    },\n    \"Accident_Town12_Route19086_Weather1.tar.gz\": {\n        \"sha256\": \"d55be96aece4adf5fcb59020d28e0b56a6956d3e93ede5e3fe2f13ef7d97d961\",\n        \"size\": 166651124\n    },\n    \"Accident_Town12_Route19087_Weather2.tar.gz\": {\n        \"sha256\": \"ab61ec9ae1f2c3ea019405d76e099c4dab31136534ce21a013af78560dd9f09c\",\n        \"size\": 454683929\n    },\n    \"Accident_Town12_Route19088_Weather3.tar.gz\": {\n        \"sha256\": \"47426ff3433ec8a45c0fc1c385078dcdcdf19def740e42ee19413492ea6821c1\",\n        \"size\": 423227129\n    },\n    \"Accident_Town12_Route19089_Weather3.tar.gz\": {\n        \"sha256\": \"3bbeffd122f4e520c3826ec00bb9473ce52b734fd78574b2c9e66d3c90de94cf\",\n        \"size\": 334417165\n    },\n    \"Accident_Town12_Route19092_Weather7.tar.gz\": {\n        \"sha256\": \"d45a021c057ef73146d028e33eb82cb5f56886bf7819cca23cb5be865725d45b\",\n        \"size\": 415917672\n    },\n    \"Accident_Town12_Route19094_Weather9.tar.gz\": {\n        \"sha256\": \"9f346bd0a0f4031f4eaa54bf8da3eb15b6102e37c013280eff5b01f084049f29\",\n        \"size\": 612891543\n    },\n    \"Accident_Town12_Route19097_Weather12.tar.gz\": {\n        \"sha256\": \"cb367e665ce44ecce5e8321f15e59d38f2f1ff8e2dd2116dcc4c3a784209ef12\",\n        \"size\": 140478193\n    },\n    \"Accident_Town12_Route19101_Weather8.tar.gz\": {\n        \"sha256\": \"82fc20a14aba047260be622a6e8cf9866a1cbb9e45f3542fbc846cc513aa77c4\",\n        \"size\": 163299911\n    },\n    \"Accident_Town12_Route19102_Weather9.tar.gz\": {\n        \"sha256\": \"3e2cec4eee555649c1dc4651c2cefedce15da64b84a48542b2119d419e04f907\",\n        \"size\": 149101035\n    },\n    \"Accident_Town12_Route19103_Weather18.tar.gz\": {\n        \"sha256\": \"7fcd0a20b53b111a7fcc53341c40bd440b86e0a28b506e804b600917faf3ad41\",\n        \"size\": 182721647\n    },\n    \"Accident_Town12_Route19106_Weather21.tar.gz\": {\n        \"sha256\": \"6f3a38e3fec86fc6082f29095c7cbc2ec7b3f0fedcb184d6c62ba1fbf96cf476\",\n        \"size\": 389901074\n    },\n    \"Accident_Town12_Route19107_Weather22.tar.gz\": {\n        \"sha256\": \"76f30695e069ce06235c2a043a049f2c4a3da864ab57b3247c09dd2077e55765\",\n        \"size\": 189216625\n    },\n    \"Accident_Town12_Route19108_Weather23.tar.gz\": {\n        \"sha256\": \"a64a7f670858b0e3086a5224ac8e3a5df7ff8f3958bf479fdb5f444116a7189a\",\n        \"size\": 301945684\n    },\n    \"Accident_Town12_Route19111_Weather0.tar.gz\": {\n        \"sha256\": \"5d648c3d0ddf90375656bcd40123ab8b48f4bded0480bc77e0359af49fafc0b0\",\n        \"size\": 328377211\n    },\n    \"Accident_Town12_Route19112_Weather1.tar.gz\": {\n        \"sha256\": \"7d5507e2f9f5ac380f5ddca9f99183dcec3a1be74c28f12770c88ac3632516c2\",\n        \"size\": 162430940\n    },\n    \"Accident_Town12_Route19113_Weather2.tar.gz\": {\n        \"sha256\": \"8a1f72a2efb18837defccaec6b6406d4f8426c3ef9af05d42ea622c9ab1190b3\",\n        \"size\": 529084349\n    },\n    \"Accident_Town12_Route19114_Weather3.tar.gz\": {\n        \"sha256\": \"7d66a45c573729e8ae5123bd00c19bad99fabcc598b70706ddbab8ccaba14854\",\n        \"size\": 465948519\n    },\n    \"Accident_Town12_Route19115_Weather3.tar.gz\": {\n        \"sha256\": \"67a08007ba0d1e03090f4e16cb364b15cbc53a977df0a894cd793dc40a123271\",\n        \"size\": 506357162\n    },\n    \"Accident_Town12_Route19117_Weather6.tar.gz\": {\n        \"sha256\": \"154aad25fde3aae489d951ecfe503d12cb77b061b519bb12609915600eebe1e9\",\n        \"size\": 175061657\n    },\n    \"Accident_Town12_Route19118_Weather7.tar.gz\": {\n        \"sha256\": \"393133fc55768e28d785c06209019bf9e430383c4275596ebfeaf4e0ff2a3c66\",\n        \"size\": 182281499\n    },\n    \"Accident_Town12_Route19121_Weather10.tar.gz\": {\n        \"sha256\": \"6e2c7f2f8afc5d3eee0226099371492bb0dfdf618592cdc8e7729538df974c7b\",\n        \"size\": 249814731\n    },\n    \"Accident_Town12_Route19122_Weather11.tar.gz\": {\n        \"sha256\": \"5e5b6861ea1dbe2305beda68e9583cd4caefcffa428832cf5c5d0b9f91154505\",\n        \"size\": 125198830\n    },\n    \"Accident_Town12_Route19123_Weather12.tar.gz\": {\n        \"sha256\": \"ef3967b0a474da0eaca5f27fb96d780012523f253910c654252a75985959c1a8\",\n        \"size\": 425839367\n    },\n    \"Accident_Town12_Route19124_Weather13.tar.gz\": {\n        \"sha256\": \"35427db0f5223447fc2908ef93e9a4be7749f2131dc7552a97589f2b74f60400\",\n        \"size\": 140115374\n    },\n    \"Accident_Town12_Route19126_Weather15.tar.gz\": {\n        \"sha256\": \"6b1d35676c764ecda952ad492bb93d2d5835cab3e57129b0ee34716246073f9a\",\n        \"size\": 161389582\n    },\n    \"Accident_Town12_Route19127_Weather8.tar.gz\": {\n        \"sha256\": \"e371aea130526e0b3ae4605e23ae6b94ae77597ab72f7c8f20e9f9c24a3587b6\",\n        \"size\": 403882827\n    },\n    \"Accident_Town12_Route19128_Weather9.tar.gz\": {\n        \"sha256\": \"eaba2bdc01ae6ff72fe0d237090ef2d35ecc3a1749cde04bb6b096059272f338\",\n        \"size\": 379151619\n    },\n    \"Accident_Town12_Route19136_Weather25.tar.gz\": {\n        \"sha256\": \"3e7beb68acdb6ff09aa29710fa7560834d16f99c1446ca8c48998ec76571d857\",\n        \"size\": 427156905\n    },\n    \"Accident_Town12_Route19137_Weather0.tar.gz\": {\n        \"sha256\": \"ac8e76295bd7c913ffb78bdd19981d0b3deba676568268ae26f394b50fb22786\",\n        \"size\": 536934876\n    },\n    \"Accident_Town12_Route19139_Weather2.tar.gz\": {\n        \"sha256\": \"edfe2dfe9c9a88327e8b74766f462c0b8e9d18560cd9d0f775d4f5aafc8df5e1\",\n        \"size\": 537826514\n    },\n    \"Accident_Town12_Route19141_Weather3.tar.gz\": {\n        \"sha256\": \"25e548abd558b7977e5591e1e07c5fb9ed925c5a7cf979b1e813b80e010bb4bb\",\n        \"size\": 351398656\n    },\n    \"Accident_Town12_Route19142_Weather5.tar.gz\": {\n        \"sha256\": \"32a1be229cac31698a13567fc6e2568966f593d60f09e74bd853dd9184137472\",\n        \"size\": 160229347\n    },\n    \"Accident_Town12_Route19143_Weather6.tar.gz\": {\n        \"sha256\": \"39f77aeacae74b57ec6507032bcef4d98a69f8fcbe315d891017d5a352b3e558\",\n        \"size\": 163861985\n    },\n    \"Accident_Town12_Route19145_Weather8.tar.gz\": {\n        \"sha256\": \"b5de971cf5b931e63e8cb80a71d2f5e43079c277d844ad2c592d47e793b03f7a\",\n        \"size\": 224371101\n    },\n    \"Accident_Town12_Route19148_Weather11.tar.gz\": {\n        \"sha256\": \"09d5415dea0a65255f93fd9fffe56ad41a10390b6521df722df9e35df16907b5\",\n        \"size\": 473222053\n    },\n    \"Accident_Town12_Route19151_Weather14.tar.gz\": {\n        \"sha256\": \"665baea742f3aef9c8e7a55b211961672f55fade483ebb0394356ed9d61b7f25\",\n        \"size\": 155184721\n    },\n    \"Accident_Town12_Route19152_Weather15.tar.gz\": {\n        \"sha256\": \"c1f3a0abf097aeec818c78d35c0f6dcf378a1a8cb3bbe29386a37d14931177fe\",\n        \"size\": 332925261\n    },\n    \"Accident_Town12_Route19153_Weather8.tar.gz\": {\n        \"sha256\": \"fdbfbb3c35427f00cda5266be543e1d7bbd40a9d4ee4a4834bf74fda52241da6\",\n        \"size\": 307924057\n    },\n    \"Accident_Town12_Route19154_Weather9.tar.gz\": {\n        \"sha256\": \"8de053525f4d776dfc8f5201480b535ce8a16bef2bd25c5578b035b70f80d4ed\",\n        \"size\": 140108341\n    },\n    \"Accident_Town12_Route19155_Weather18.tar.gz\": {\n        \"sha256\": \"768a533bae5f3d4f8bd7ff05523999963f83bc41334030677e0af2c51997e916\",\n        \"size\": 428233018\n    },\n    \"Accident_Town12_Route19159_Weather22.tar.gz\": {\n        \"sha256\": \"7066a1e352bcefb49dae1edf5f652994d102b13b90ebd0a75a7ed55fd750632a\",\n        \"size\": 374257683\n    },\n    \"Accident_Town12_Route19160_Weather23.tar.gz\": {\n        \"sha256\": \"740db612524b7d20ad6bf2a6eea723b3e32f19f22d5cc75d790a538f11b96e09\",\n        \"size\": 367223407\n    },\n    \"Accident_Town12_Route19162_Weather25.tar.gz\": {\n        \"sha256\": \"0af95ed87765cc14106b9c5b9a1d0179423ec548eabe0850e1730d1384518f44\",\n        \"size\": 329800110\n    },\n    \"Accident_Town12_Route19163_Weather0.tar.gz\": {\n        \"sha256\": \"ba48c33c21a2ff3697ebe906ff2d00d4872a2515da44e52348d1b316938da583\",\n        \"size\": 469037361\n    },\n    \"Accident_Town12_Route19164_Weather1.tar.gz\": {\n        \"sha256\": \"9c6b90922b7f9d928a8c4de96d83b82e2a69f6fbf695f324ad9957e61a1e8641\",\n        \"size\": 314219114\n    },\n    \"Accident_Town12_Route19165_Weather2.tar.gz\": {\n        \"sha256\": \"5d2c838e543ee639c7e9ef48c6e547dc47d5f76796fae4985717c234d99b1f6c\",\n        \"size\": 319450958\n    },\n    \"Accident_Town12_Route19166_Weather3.tar.gz\": {\n        \"sha256\": \"6d270feff4ff80445fa6e9c0c30a18f43d45523fa97733ca30b1b23b2ea40073\",\n        \"size\": 295051354\n    },\n    \"Accident_Town12_Route19167_Weather3.tar.gz\": {\n        \"sha256\": \"9e96a53c10e3415705e192defdda4e5ebda63d74da7b4e718050199290e16eaa\",\n        \"size\": 350290414\n    },\n    \"Accident_Town12_Route19169_Weather6.tar.gz\": {\n        \"sha256\": \"d0ffc1e08aba30f1091cecef3eae6868566d593b1a751fcd70a03c61bb2291d4\",\n        \"size\": 306931329\n    },\n    \"Accident_Town12_Route19170_Weather7.tar.gz\": {\n        \"sha256\": \"bf1871cd494fe35c69ee50558dbab5a356c141df5760e78ad880428a5adf6330\",\n        \"size\": 355095659\n    },\n    \"Accident_Town12_Route19171_Weather8.tar.gz\": {\n        \"sha256\": \"5ef3bc4b7bde2da140b2b5cb71febca56dd378dc308bf097bdf346fc3ab939a2\",\n        \"size\": 279633342\n    },\n    \"Accident_Town12_Route19172_Weather9.tar.gz\": {\n        \"sha256\": \"38251964f10c93ce91729292a3fd382478071075bac301ffab55843169e392a3\",\n        \"size\": 274873541\n    },\n    \"Accident_Town12_Route19173_Weather10.tar.gz\": {\n        \"sha256\": \"dd6231e6891d15ed61d48776173b2d3fd2b5b59de85a41a9a5a863391dfb9976\",\n        \"size\": 276149305\n    },\n    \"Accident_Town12_Route19174_Weather11.tar.gz\": {\n        \"sha256\": \"512f2801d79eeb3adbe67577c5dcd8a71bc9fb3bd6fb18c8aefe58aa49a3799a\",\n        \"size\": 277351387\n    },\n    \"Accident_Town12_Route19175_Weather12.tar.gz\": {\n        \"sha256\": \"14afefb93ab6243d20a805e3b8413c952a40588e4d92dfdb3d976e456898e154\",\n        \"size\": 430059836\n    },\n    \"Accident_Town12_Route19177_Weather14.tar.gz\": {\n        \"sha256\": \"ab3412d1162b0d8e644306a66f762cb0fbd92bd08eae483287a5ae358d11c7d1\",\n        \"size\": 189839181\n    },\n    \"Accident_Town12_Route19178_Weather15.tar.gz\": {\n        \"sha256\": \"c2fc7d91813a63f29e797f26202ddf4faa33afcf4dc80fed16b9a38b0a09043d\",\n        \"size\": 278462851\n    },\n    \"Accident_Town12_Route19179_Weather8.tar.gz\": {\n        \"sha256\": \"651ce41a29701a3ecea0e3815584a54d93aa6234423242b6976a054500b8a552\",\n        \"size\": 259431994\n    },\n    \"Accident_Town12_Route19180_Weather9.tar.gz\": {\n        \"sha256\": \"34b2ca8d2e25188e8f43b2091c93aed4b3bda071e402696f7c8f3defe9a2b8df\",\n        \"size\": 262217070\n    },\n    \"Accident_Town12_Route19181_Weather18.tar.gz\": {\n        \"sha256\": \"1e76a2d2567026f592661be60a01110dacfb423c8918a31a80881f451628d9ac\",\n        \"size\": 326468171\n    },\n    \"Accident_Town12_Route19182_Weather19.tar.gz\": {\n        \"sha256\": \"7c1b2bd52fa7b5f6033eceb229561f3e935f802d3f2b82ed71a7ff40a10f4d50\",\n        \"size\": 296021253\n    },\n    \"Accident_Town12_Route19183_Weather20.tar.gz\": {\n        \"sha256\": \"24aa246753db9e99e1ad2e740a92190255e63fcc27faa723cf08c1f0d39dba13\",\n        \"size\": 289625955\n    },\n    \"Accident_Town12_Route19184_Weather21.tar.gz\": {\n        \"sha256\": \"22adc6c6459157e354d48dc46357b30e7476440246ab84eaf575ab8460a63436\",\n        \"size\": 293422278\n    },\n    \"Accident_Town12_Route19185_Weather22.tar.gz\": {\n        \"sha256\": \"2c9378840b56e9119e93414be19e2d2837212e6af2feb76bc82abc84d02ee989\",\n        \"size\": 315380716\n    },\n    \"Accident_Town12_Route19186_Weather23.tar.gz\": {\n        \"sha256\": \"eaefc31a8830ae1af72f42af57059e8e3c8e7b506d4fa5fbb41f4ffab40a53bf\",\n        \"size\": 320788016\n    },\n    \"Accident_Town12_Route19187_Weather23.tar.gz\": {\n        \"sha256\": \"d360ee4a7733a10287692d8eef6afe0f96654ea37522d9a2daf8da6ab8d8bb11\",\n        \"size\": 343307933\n    },\n    \"Accident_Town12_Route19189_Weather0.tar.gz\": {\n        \"sha256\": \"1c0fba15786053287429974f6958226b8dcbd022b24250347d4141f10dce3f90\",\n        \"size\": 392064216\n    },\n    \"Accident_Town12_Route19190_Weather1.tar.gz\": {\n        \"sha256\": \"607f36986910007fa6c0f2982575140249c0c719f65c72c372081605ad8859b1\",\n        \"size\": 426118506\n    },\n    \"Accident_Town12_Route19191_Weather2.tar.gz\": {\n        \"sha256\": \"6dd8e5cf7795e22ebd79037030c01c880b804741a65e6d94b9eaa58e8c8e01bb\",\n        \"size\": 454188634\n    },\n    \"Accident_Town12_Route19194_Weather5.tar.gz\": {\n        \"sha256\": \"84b0e5e927f7effa82b010a1971dd16ff405111d2fbc54eb1a5dc7591efe2efb\",\n        \"size\": 373279856\n    },\n    \"Accident_Town12_Route19197_Weather8.tar.gz\": {\n        \"sha256\": \"0dde8006c3157e44391e436f03f70da3c7f16199349abac3e564a1bdd04ef9ec\",\n        \"size\": 167518204\n    },\n    \"Accident_Town12_Route19199_Weather10.tar.gz\": {\n        \"sha256\": \"7c2cada1ec60429bb96b1984df55613f2bbff701d54581a3fc6a4ec3cc238fb1\",\n        \"size\": 318024860\n    },\n    \"Accident_Town12_Route19200_Weather11.tar.gz\": {\n        \"sha256\": \"bec2cecb8863ba1c38aacb31ee6577aef97aed4fc0afadc2ea37fda51f39c8a3\",\n        \"size\": 285413172\n    },\n    \"Accident_Town12_Route19201_Weather12.tar.gz\": {\n        \"sha256\": \"e849b95d90edf1c1e5b3f324f450e999fa7af1b2e9ffd695cdc0fe8fb3d2e737\",\n        \"size\": 288126014\n    },\n    \"Accident_Town12_Route19202_Weather13.tar.gz\": {\n        \"sha256\": \"26948a97aabbb93ec67f291003d8a99fb20b41ddc57194c192eff2ed371074aa\",\n        \"size\": 281491497\n    },\n    \"Accident_Town12_Route19203_Weather14.tar.gz\": {\n        \"sha256\": \"33561e76ead42730f157ca7bd0aeab33532efcd3c2ffcdeff3e373c30c68ac8e\",\n        \"size\": 279718227\n    },\n    \"Accident_Town12_Route19204_Weather15.tar.gz\": {\n        \"sha256\": \"a6f69ecee4eba5d5ec4ede0bd964ab800b061f479df9f3101f847e6ecdbeb0ae\",\n        \"size\": 426167650\n    },\n    \"Accident_Town12_Route19206_Weather9.tar.gz\": {\n        \"sha256\": \"e50a925aba997a39ded8d694747a8e9a85d069cb469a5b7be662459de45dcba3\",\n        \"size\": 448568718\n    },\n    \"Accident_Town12_Route19208_Weather19.tar.gz\": {\n        \"sha256\": \"79961fc54c8b4854da0dbda5e06d241d3dcd488c0d81be45c1cca719a739d4c1\",\n        \"size\": 153323035\n    },\n    \"Accident_Town12_Route19211_Weather22.tar.gz\": {\n        \"sha256\": \"c11862e60185d1c8b168709ae7bb7d207d386a576222b025b67df657b2a18e37\",\n        \"size\": 349856763\n    },\n    \"Accident_Town12_Route19212_Weather23.tar.gz\": {\n        \"sha256\": \"a80e0392ef799d7183d24a028341202fd5b289510ca8c29b2f296149cfe8e71e\",\n        \"size\": 150602800\n    },\n    \"Accident_Town12_Route19213_Weather23.tar.gz\": {\n        \"sha256\": \"36db8319e78420b0060be641651b4e88f4b6aad3daf2ddf2d57b9709f7860717\",\n        \"size\": 132431587\n    },\n    \"Accident_Town12_Route19215_Weather0.tar.gz\": {\n        \"sha256\": \"77d6bb67c95c4a8df33802a59def58c542482d99f2c32d930f821a9482cf6d85\",\n        \"size\": 183809745\n    },\n    \"Accident_Town12_Route19218_Weather3.tar.gz\": {\n        \"sha256\": \"11ad94edf58e57af4a398b2c2ec4bc4f72e7d2a864155fd73acdb213ea179381\",\n        \"size\": 182936176\n    },\n    \"Accident_Town12_Route19219_Weather3.tar.gz\": {\n        \"sha256\": \"2515a75b32ce399157d063ae9defba38aaecfe65c9c8cc9fdb218a7ad04490f5\",\n        \"size\": 182297086\n    },\n    \"Accident_Town12_Route19220_Weather5.tar.gz\": {\n        \"sha256\": \"fda272e1542a2566c87c2694791fa88f2f7e0839d6901a49ac5ebba2055f6c4d\",\n        \"size\": 212957959\n    },\n    \"Accident_Town12_Route19222_Weather7.tar.gz\": {\n        \"sha256\": \"9627c6ae97ae0b7e3cca2a26a615b3c7756e95e3de8e7b2740f0b1a9ed8889e3\",\n        \"size\": 387807714\n    },\n    \"Accident_Town12_Route19225_Weather10.tar.gz\": {\n        \"sha256\": \"d4186f5564b31019eb7114cec3085ee4eee2fa61d6594ea973bd469c3725dcde\",\n        \"size\": 330248774\n    },\n    \"Accident_Town12_Route19226_Weather11.tar.gz\": {\n        \"sha256\": \"f3d48d2eb8d457484660d512a4abc888a11eecf668f83f43119da860b34092c7\",\n        \"size\": 132210387\n    },\n    \"Accident_Town12_Route19227_Weather12.tar.gz\": {\n        \"sha256\": \"6cd376ff73435bd3ebb44a96c27b80e5390b7377495e7a3d57f6f9334a95d162\",\n        \"size\": 411915055\n    },\n    \"Accident_Town12_Route19228_Weather13.tar.gz\": {\n        \"sha256\": \"afb2f18385c5975d162e2eef523f45187721d53a23206b0b0f22cae7674d9455\",\n        \"size\": 127969344\n    },\n    \"Accident_Town12_Route19229_Weather14.tar.gz\": {\n        \"sha256\": \"ec6dc344dcf1e81cce7b8e6972a3d40b701f3a76214d6759c9d332626380adc9\",\n        \"size\": 155895858\n    },\n    \"Accident_Town12_Route19230_Weather15.tar.gz\": {\n        \"sha256\": \"efcab293282467cc57941684613df0784f6a77ab407197db5490ae929a50ed2e\",\n        \"size\": 156726516\n    },\n    \"Accident_Town12_Route19231_Weather8.tar.gz\": {\n        \"sha256\": \"ecc6fe9e1c31b19e37f33154d24e37ba2cbd9e0db4075126a5b62017236e895e\",\n        \"size\": 176356028\n    },\n    \"Accident_Town12_Route19232_Weather9.tar.gz\": {\n        \"sha256\": \"15dfbf22f12c6ca5bed3b31388d4164a2acd571f78711c3cb06bab7b59a824fe\",\n        \"size\": 132474802\n    },\n    \"Accident_Town12_Route19234_Weather19.tar.gz\": {\n        \"sha256\": \"3c3bbd2123b7dfcaf37abf43a81221d596ca68da336ed134fed7ad0c6b30dfea\",\n        \"size\": 354759743\n    },\n    \"Accident_Town12_Route19235_Weather20.tar.gz\": {\n        \"sha256\": \"24abebe664d66acde202029faa10ddf505d3fbd05903c2f65ac4146e7404b611\",\n        \"size\": 166956565\n    },\n    \"Accident_Town12_Route19236_Weather21.tar.gz\": {\n        \"sha256\": \"ab11ba47b9ddc8e735b30c05cbf4ebb6ca7c3c98515624f327d7e6ab07c3c240\",\n        \"size\": 158241577\n    },\n    \"Accident_Town12_Route19238_Weather23.tar.gz\": {\n        \"sha256\": \"3a0935605ef17019d073795ae9fc804338b6f4b909df24307a68a3a827662e2e\",\n        \"size\": 150154114\n    },\n    \"Accident_Town12_Route19239_Weather23.tar.gz\": {\n        \"sha256\": \"b40d7ac458e6411c57c13f1f578066a3296e941aba58d92606a755fe0e54933f\",\n        \"size\": 143490720\n    },\n    \"Accident_Town12_Route19241_Weather0.tar.gz\": {\n        \"sha256\": \"71c3d3f2b33571f8317f6a68f5ccfca14eacb89065ada8dfde02f16123b40bb2\",\n        \"size\": 327474349\n    },\n    \"Accident_Town12_Route19244_Weather3.tar.gz\": {\n        \"sha256\": \"1a7d33cb41e8e1550dafaf0e36a0c16dddb33db2edb98db7b97b6e98e8baefc6\",\n        \"size\": 189234160\n    },\n    \"Accident_Town12_Route19246_Weather5.tar.gz\": {\n        \"sha256\": \"53ae081fc151fee8087e83be831407a88b4c2046d0b92023935afc2572095117\",\n        \"size\": 193857219\n    },\n    \"Accident_Town12_Route19247_Weather6.tar.gz\": {\n        \"sha256\": \"0d3a85cee8bd02fbeb91341eed54fb5565b8b70458a4b7b9d1327eca8196a35a\",\n        \"size\": 192947796\n    },\n    \"Accident_Town12_Route19248_Weather7.tar.gz\": {\n        \"sha256\": \"0bd1694ca14dad89deec143828373df4c32448a500b1449187179d807962a531\",\n        \"size\": 220762747\n    },\n    \"Accident_Town12_Route19249_Weather8.tar.gz\": {\n        \"sha256\": \"b2b4b32fc78982fb44ddf3f952e7f91811bfbc5dd77d1688b2768fee2036f80d\",\n        \"size\": 321960798\n    },\n    \"Accident_Town12_Route19250_Weather9.tar.gz\": {\n        \"sha256\": \"e85097cfd592017e0c29787073a4304682d58e7d5174b648469f9e087f10741f\",\n        \"size\": 348016358\n    },\n    \"Accident_Town12_Route19252_Weather11.tar.gz\": {\n        \"sha256\": \"74dc3d4c36d3774965a91b21ec212ac35bdeb0bb12d67189dea5385c1e200b03\",\n        \"size\": 204276014\n    },\n    \"Accident_Town12_Route19255_Weather14.tar.gz\": {\n        \"sha256\": \"fe2128c46ba2ed6fc512571a2b29b71b5e91a118c434f33a6bfbd6a26a1c8dcf\",\n        \"size\": 413760593\n    },\n    \"Accident_Town12_Route19257_Weather8.tar.gz\": {\n        \"sha256\": \"024cbe2010bb3e9b4f7571bcb669c5d1e5795e44280d9e46d810703bde914c8a\",\n        \"size\": 170056891\n    },\n    \"Accident_Town12_Route19259_Weather18.tar.gz\": {\n        \"sha256\": \"83d00ed38c09e86396b6f1d1cf88833fc63a85c82056588837b1e7272a71d71a\",\n        \"size\": 310330348\n    },\n    \"Accident_Town12_Route19260_Weather19.tar.gz\": {\n        \"sha256\": \"aa8dbfb75b1411ac3127028a85625271963b686d8679cff7052c2c70129d267b\",\n        \"size\": 411083566\n    },\n    \"Accident_Town12_Route19261_Weather20.tar.gz\": {\n        \"sha256\": \"9f7c9d5d6a8277dda875cc734e4ffe7834a1fa5a57f5cb341fd190842047343e\",\n        \"size\": 416726074\n    },\n    \"Accident_Town12_Route19262_Weather21.tar.gz\": {\n        \"sha256\": \"c2af8c440ce80574bea7d845ab9988eaf29a492eeb6cf8e799ec2e95ece2c9bb\",\n        \"size\": 419256635\n    },\n    \"Accident_Town12_Route19263_Weather22.tar.gz\": {\n        \"sha256\": \"ca8bc44cdf2a71971ab8a108c5223367ab5e28202e62102b61b86c552806960f\",\n        \"size\": 399831331\n    },\n    \"Accident_Town12_Route19265_Weather23.tar.gz\": {\n        \"sha256\": \"ddc66527130e3dfe52a6de18991154b3ca704f35a9ddcba97b1d4e8651196f1a\",\n        \"size\": 398611696\n    },\n    \"Accident_Town12_Route19266_Weather25.tar.gz\": {\n        \"sha256\": \"db62055d22b2210df755fe69dd475c93a2afcf54bc74b86784f599778ae3e410\",\n        \"size\": 432125455\n    },\n    \"Accident_Town12_Route19267_Weather0.tar.gz\": {\n        \"sha256\": \"8258376734cce69282a12fa1f424559ce7666ec281b09557eb4130fcb00564a9\",\n        \"size\": 456395982\n    },\n    \"Accident_Town12_Route19269_Weather2.tar.gz\": {\n        \"sha256\": \"8d63fd2083befd206931469ec34fe8bd88e232707c1c2caad6823efa03a3368c\",\n        \"size\": 243046519\n    },\n    \"Accident_Town12_Route19270_Weather3.tar.gz\": {\n        \"sha256\": \"bcfc4e5d041a81c9a4586bea570e06e5e7699ea121709b5974e941e694ce7fb8\",\n        \"size\": 228526469\n    },\n    \"Accident_Town12_Route19272_Weather5.tar.gz\": {\n        \"sha256\": \"04de6f537166a65a25e6b8b41ba26981fa6eb0ff8b7a4664119b7b38abf9e812\",\n        \"size\": 323409078\n    },\n    \"Accident_Town12_Route19274_Weather7.tar.gz\": {\n        \"sha256\": \"b08ab352afdc08b7784bb08a550ba7dcbd73b2047bec218029000a383ddbfe82\",\n        \"size\": 185441619\n    },\n    \"Accident_Town12_Route19277_Weather10.tar.gz\": {\n        \"sha256\": \"1a6802cc3b57d8d13edfd06937007c7ad22c8ab1791cebb1d2b22aa7ce340f7d\",\n        \"size\": 172932977\n    },\n    \"Accident_Town12_Route19281_Weather14.tar.gz\": {\n        \"sha256\": \"f5cc41bf3da9c3e18873976366905e3a32796e49f325dc1d173ec37f7ed2c7a3\",\n        \"size\": 398962070\n    },\n    \"Accident_Town12_Route19282_Weather15.tar.gz\": {\n        \"sha256\": \"d2876b151eb40bafd9ca6b29b4651177f73d2fd20701fdf9987547c385037cca\",\n        \"size\": 378928742\n    },\n    \"Accident_Town12_Route19283_Weather8.tar.gz\": {\n        \"sha256\": \"4044f3d5730307b3093344ff14d7e592e4ba76ce4aac411082bd265a9cb98ae6\",\n        \"size\": 170529339\n    },\n    \"Accident_Town12_Route19295_Weather2.tar.gz\": {\n        \"sha256\": \"ae70d6e0db0ffa931e32ea29802c4f93e0b3876dfeb3fab6a124fbcd99cdc4c4\",\n        \"size\": 307089166\n    },\n    \"Accident_Town12_Route19297_Weather3.tar.gz\": {\n        \"sha256\": \"0393bd7d64ac4d3d31f9f3414eca88a15b11798199e17f261c2a590be43f400c\",\n        \"size\": 1991569149\n    },\n    \"Accident_Town12_Route19298_Weather5.tar.gz\": {\n        \"sha256\": \"7d1da753e92b1300297afacc0152fabb3d5a69b03e176cc848e9c17a6d336e2a\",\n        \"size\": 183226624\n    },\n    \"Accident_Town12_Route19299_Weather6.tar.gz\": {\n        \"sha256\": \"d9ea931813d2286f4c2223d7be46f7b85152fb848138a7d1e6d1f01a7d6b205b\",\n        \"size\": 174877306\n    },\n    \"Accident_Town12_Route19300_Weather7.tar.gz\": {\n        \"sha256\": \"60357374551e2843a58589b0033222face383b93d4a1f649c3d595d48fe84151\",\n        \"size\": 363293811\n    },\n    \"Accident_Town12_Route19301_Weather8.tar.gz\": {\n        \"sha256\": \"7d9019e1f095c502f0c253481ff5976b8b7c7475accccbd2720cdad9c3c1400b\",\n        \"size\": 173480283\n    },\n    \"Accident_Town12_Route19303_Weather10.tar.gz\": {\n        \"sha256\": \"2316779af238c656f2706a87987eba2e7ecdcad2a501f97671d179d762217a37\",\n        \"size\": 476769738\n    },\n    \"Accident_Town12_Route19304_Weather11.tar.gz\": {\n        \"sha256\": \"36dc30ee3d24ac493b199f1be34379bb14a444ad74f544bf5888863938d78440\",\n        \"size\": 271769761\n    },\n    \"Accident_Town12_Route19306_Weather13.tar.gz\": {\n        \"sha256\": \"04820eb791242781368aef403993f6760d4df72ba158ff6f626a26a4b681aab5\",\n        \"size\": 384054233\n    },\n    \"Accident_Town12_Route19307_Weather14.tar.gz\": {\n        \"sha256\": \"bd1c61c04f961fa83cb0847d836408bc070e628f77462b49fd1b98ffbec04a7d\",\n        \"size\": 293344244\n    },\n    \"Accident_Town12_Route19310_Weather9.tar.gz\": {\n        \"sha256\": \"c09d25d2f4f57f490e6cc0878779e1cd3e14934fa8fb1b7c564c27e929b9aeb2\",\n        \"size\": 309757610\n    },\n    \"Accident_Town12_Route19312_Weather19.tar.gz\": {\n        \"sha256\": \"d544f7c617b25cb8d249e2341d76d35bdfe9d9bb44f072343a582254e0161c73\",\n        \"size\": 164311111\n    },\n    \"Accident_Town12_Route19313_Weather20.tar.gz\": {\n        \"sha256\": \"10a89c66414352ffddc9554ce3725aabce7cdfdcd5e7a657a9e73189c3f11a87\",\n        \"size\": 417913759\n    },\n    \"Accident_Town12_Route19314_Weather21.tar.gz\": {\n        \"sha256\": \"fe77ac3a48657e59cf1f480e5ca0e9f677b6e502d45d95abfdb5ad8ad5546835\",\n        \"size\": 378622008\n    },\n    \"Accident_Town12_Route19316_Weather23.tar.gz\": {\n        \"sha256\": \"ba51b58607eb2390bb352bfafbf5322c8799f76e485786c2f879ac87ceec0f57\",\n        \"size\": 355263146\n    },\n    \"Accident_Town12_Route19317_Weather23.tar.gz\": {\n        \"sha256\": \"113bff10c483b3f7a15e385e1e9a2751de6b36e06869a2e1b5a176dcff360194\",\n        \"size\": 1322330902\n    },\n    \"Accident_Town12_Route19319_Weather0.tar.gz\": {\n        \"sha256\": \"9dfb287d9759e445e4ad9b4cc0c09d2d70c0fba427d1a1bddced99b524a92b69\",\n        \"size\": 176655481\n    },\n    \"Accident_Town12_Route19321_Weather2.tar.gz\": {\n        \"sha256\": \"3ee7b0a09d00f2b6ef283028822c7f3b26b425741ffc033b0a9922315b2fb1e2\",\n        \"size\": 244593548\n    },\n    \"Accident_Town12_Route19322_Weather3.tar.gz\": {\n        \"sha256\": \"85188e0c26f82c4b2b16e27fdb45041854443cefbaed0a34da0b966c675c806f\",\n        \"size\": 522866495\n    },\n    \"Accident_Town12_Route19325_Weather6.tar.gz\": {\n        \"sha256\": \"e552331035b94da61fa4d36d4cb5201f4735de6285b25634d0d7d986812f6906\",\n        \"size\": 169657046\n    },\n    \"Accident_Town12_Route19327_Weather8.tar.gz\": {\n        \"sha256\": \"e7178291157620dae18d65c2af1781f661d0245fd050eab84a86533e5f569c4e\",\n        \"size\": 177675898\n    },\n    \"Accident_Town12_Route19328_Weather9.tar.gz\": {\n        \"sha256\": \"3fd0beefcfa5676d9923745be58b205659b8c3430e86cc0353e3ad5dd8b646db\",\n        \"size\": 225380106\n    },\n    \"Accident_Town12_Route19329_Weather10.tar.gz\": {\n        \"sha256\": \"b4c8eaf23f44407167dccef18dadc092e870817a7316b515b8fde683487454a6\",\n        \"size\": 165659972\n    },\n    \"Accident_Town12_Route19330_Weather11.tar.gz\": {\n        \"sha256\": \"dfc03d54e1799c05f0d66063814fd094cc4df0f32c4b8270ba4a502aa7b6e347\",\n        \"size\": 332425066\n    },\n    \"Accident_Town12_Route19331_Weather12.tar.gz\": {\n        \"sha256\": \"b3a5e731dbd3dfd57b30b3d0e43628f53536ee8f3f7e0b3da21518fa55062921\",\n        \"size\": 331744004\n    },\n    \"Accident_Town12_Route19332_Weather13.tar.gz\": {\n        \"sha256\": \"77c9ee7c3a4912cbdcbbea0b8c81a775fab53e9c11708d4bc1dd8b50be72b3d3\",\n        \"size\": 134305961\n    },\n    \"Accident_Town12_Route19334_Weather15.tar.gz\": {\n        \"sha256\": \"506f601c0191bba0ff840d5c0458fd2511f47f8dfe723555ac88558425bed3be\",\n        \"size\": 155851755\n    },\n    \"Accident_Town12_Route19335_Weather8.tar.gz\": {\n        \"sha256\": \"c59dde1cf4f2f9777ffc960c0014b6b0a6b6a18dad121d3a4c6516ee7571baf6\",\n        \"size\": 192075986\n    },\n    \"Accident_Town12_Route19336_Weather9.tar.gz\": {\n        \"sha256\": \"f7448cf1f35156472759c8c51e041fc13fcc54a7b5a429075455d40a2ead351c\",\n        \"size\": 145603798\n    },\n    \"Accident_Town12_Route19337_Weather18.tar.gz\": {\n        \"sha256\": \"ed0b7b8402dad6d8a355239f882edf0c6017a846dcb6991caf3c5c724b258470\",\n        \"size\": 308033185\n    },\n    \"Accident_Town12_Route19338_Weather19.tar.gz\": {\n        \"sha256\": \"c9c669bd166b5115d0296d014c40c2d7c750e37fc492aab7965e8c1be96d0ada\",\n        \"size\": 238419515\n    },\n    \"Accident_Town12_Route19339_Weather20.tar.gz\": {\n        \"sha256\": \"e81b26f5af5e709e12e034c2e0d9b6a90003b7b00df995eaa39203ca5a1f44d2\",\n        \"size\": 255672432\n    },\n    \"Accident_Town12_Route19340_Weather21.tar.gz\": {\n        \"sha256\": \"388bff3a5a2920005a1db77c1d6769b01357ab02f89a7e096d864422935d8342\",\n        \"size\": 252297724\n    },\n    \"Accident_Town12_Route19341_Weather22.tar.gz\": {\n        \"sha256\": \"0db050d4a92d760c2136eecd295f7ddd543661aea7348bdcbf191ddb5cbd9588\",\n        \"size\": 167100926\n    },\n    \"Accident_Town12_Route19342_Weather23.tar.gz\": {\n        \"sha256\": \"9f74e71d1cd33403bc2926cbd7d730b1e2a1f11be67568eaf35dce0f7fc6b443\",\n        \"size\": 145146542\n    },\n    \"Accident_Town12_Route19343_Weather23.tar.gz\": {\n        \"sha256\": \"e3974913f09c5e9a63c58576c0a9cd820a4efc66b04ea77c4b41ff8a688ac7bc\",\n        \"size\": 227367118\n    },\n    \"Accident_Town12_Route19345_Weather0.tar.gz\": {\n        \"sha256\": \"16dfa438760b7b8b467c430547fb1e2cfe39916d9dc4bb165fff69303ff30924\",\n        \"size\": 447534475\n    },\n    \"Accident_Town12_Route19347_Weather2.tar.gz\": {\n        \"sha256\": \"071037549c0919ce7864a370ea5167ba691d321251908d719fcdca2e54857a53\",\n        \"size\": 440965756\n    },\n    \"Accident_Town12_Route19349_Weather3.tar.gz\": {\n        \"sha256\": \"c4fb91bd34b87e6d85e8aa1bcd1032be33ed298b33867f8a672e86ba3ff7c709\",\n        \"size\": 421951924\n    },\n    \"Accident_Town12_Route19350_Weather5.tar.gz\": {\n        \"sha256\": \"17d1afcbd7e2ae01e135e102e5ccc8ba587d9b90e3a6ce27deb3d24de20aef57\",\n        \"size\": 324533308\n    },\n    \"Accident_Town12_Route19351_Weather6.tar.gz\": {\n        \"sha256\": \"0a19fbf8056a1bf6dcd91e26fb0f6f3daf9f9528eb90ebafadfaf91dca0bdd07\",\n        \"size\": 320705085\n    },\n    \"Accident_Town12_Route19352_Weather7.tar.gz\": {\n        \"sha256\": \"ccd67eb4a3224a49bb1a55bd3a9c029dac83f53fddbe89f187fb3003867c3ba5\",\n        \"size\": 326621365\n    },\n    \"Accident_Town12_Route19353_Weather8.tar.gz\": {\n        \"sha256\": \"62aa13422ecf71e3e2eb67aca8fd39d6594e95a9e0d327c147b0b1ba4ee7fde5\",\n        \"size\": 294557046\n    },\n    \"Accident_Town12_Route19354_Weather9.tar.gz\": {\n        \"sha256\": \"121c58763e8bb3d3e8ffeb49a6fe064f6845195eb78dc379362c92313739f741\",\n        \"size\": 304157834\n    },\n    \"Accident_Town12_Route19355_Weather10.tar.gz\": {\n        \"sha256\": \"699657243229089bdf46289dbbd469af71630945521e08b3f08c2b29fb082778\",\n        \"size\": 284210233\n    },\n    \"Accident_Town12_Route19356_Weather11.tar.gz\": {\n        \"sha256\": \"527b61186825df7132806b50e7b1aa26eee0f72deab439ecf8cc4eabd93b7dd6\",\n        \"size\": 261454329\n    },\n    \"Accident_Town12_Route19357_Weather12.tar.gz\": {\n        \"sha256\": \"fcea081d7c6e95c60d3442709cfeaec921872c7a4b7716b9e01aa0245ab0edfa\",\n        \"size\": 263371784\n    },\n    \"Accident_Town12_Route19358_Weather13.tar.gz\": {\n        \"sha256\": \"834dbb2ab751bba98380c1a1db654baf4f5ee05371b02dde40d905913b31b3f1\",\n        \"size\": 142147786\n    },\n    \"Accident_Town12_Route19359_Weather14.tar.gz\": {\n        \"sha256\": \"a13629ea1bfc3e1c0b5d5223b2d71f3f2058a96af25c34add0b55c2d102ada6a\",\n        \"size\": 437816984\n    },\n    \"Accident_Town12_Route19360_Weather15.tar.gz\": {\n        \"sha256\": \"26559d1817715b2c3944550152e5bfc675fcd730ab01a3804570e86130cf8e23\",\n        \"size\": 379124465\n    },\n    \"Accident_Town12_Route19361_Weather8.tar.gz\": {\n        \"sha256\": \"d8048d5d910ff0449a485804d0f8b6737b40d6ae41982f07ad47735ca4059e20\",\n        \"size\": 437485736\n    },\n    \"Accident_Town12_Route19365_Weather20.tar.gz\": {\n        \"sha256\": \"ccef65e16ba0732bfeaf8583c6e38ea2b343cf332a4f4a230428a47102ece2a7\",\n        \"size\": 165916563\n    },\n    \"Accident_Town12_Route19369_Weather23.tar.gz\": {\n        \"sha256\": \"6fbea8f22d74c763be8c28711f63eac7c49f8151d4aba342f183d8a6db34d3b2\",\n        \"size\": 246588750\n    },\n    \"Accident_Town12_Route19370_Weather25.tar.gz\": {\n        \"sha256\": \"2c175edd67779baa5f3459dc30821c9ec83fd5265db682281bdce68b538bd059\",\n        \"size\": 142339032\n    },\n    \"Accident_Town12_Route19372_Weather1.tar.gz\": {\n        \"sha256\": \"f22cb0b2117b129eb0cc4d4d00c2b854524cf5d47c2d507f93c1fee61820a8f0\",\n        \"size\": 366399509\n    },\n    \"Accident_Town12_Route2528_Weather0.tar.gz\": {\n        \"sha256\": \"216f0167f3a2f2fad10d87ac9d73dfdc362bf2682f48314bb5a3e3454d15cadf\",\n        \"size\": 324289208\n    },\n    \"Accident_Town12_Route2529_Weather1.tar.gz\": {\n        \"sha256\": \"4d228649bf82e4e51646d2d394c93f6143f4a1e0c8e596eef849e286ba4d869e\",\n        \"size\": 194757958\n    },\n    \"Accident_Town12_Route2531_Weather3.tar.gz\": {\n        \"sha256\": \"0605bc40f211b266d84eacb880c88e83232a1c02b30306325e694175813e3706\",\n        \"size\": 467497863\n    },\n    \"Accident_Town12_Route2533_Weather5.tar.gz\": {\n        \"sha256\": \"e3f0acc3bce123c4263248deb38a0daf3dc1b21b933280705acc99ddb03c8321\",\n        \"size\": 380367581\n    },\n    \"Accident_Town12_Route2534_Weather6.tar.gz\": {\n        \"sha256\": \"330b683cb1fb7fdc22dba83eb21e5a298cea8432911666825ba7b79098e1963c\",\n        \"size\": 347258460\n    },\n    \"Accident_Town12_Route2535_Weather7.tar.gz\": {\n        \"sha256\": \"5559a4666efa58c62d7af0b0c836754824fd3c98daf5d7236d2d7f0889d3cfd4\",\n        \"size\": 375615906\n    },\n    \"Accident_Town12_Route2539_Weather11.tar.gz\": {\n        \"sha256\": \"d978fe39130037b947577ef61dab758cc0394c7f2e569b2b9e3c33dba5e016de\",\n        \"size\": 342568718\n    },\n    \"Accident_Town12_Route2541_Weather13.tar.gz\": {\n        \"sha256\": \"ae57434a7487d1247121b3166de8d70ecddff29ca2a19a35f449e22e94a02210\",\n        \"size\": 147001893\n    },\n    \"Accident_Town12_Route2542_Weather14.tar.gz\": {\n        \"sha256\": \"255a14fedeac56310348d74cf6c6b432c5081277b8f04a18d5ec8fc3df6603b3\",\n        \"size\": 158306783\n    },\n    \"Accident_Town13_Route3304_Weather23.tar.gz\": {\n        \"sha256\": \"12ca84aa77ae21f6112d2db8dd8e9bf566a893f4b80d31287ee72c8fe9335a36\",\n        \"size\": 413877044\n    },\n    \"Accident_Town13_Route3305_Weather23.tar.gz\": {\n        \"sha256\": \"a2cc019503adb1310dcb20dcb400d2b22cd5bf083de53d1975cba8953a8edf01\",\n        \"size\": 322695253\n    },\n    \"Accident_Town13_Route3306_Weather25.tar.gz\": {\n        \"sha256\": \"4984eb8571f24b6fea938959835df68fd87988d592adc522ea116ea81f0fc382\",\n        \"size\": 620790718\n    },\n    \"Accident_Town13_Route3307_Weather0.tar.gz\": {\n        \"sha256\": \"15fd9e1210a9eb95b224784e9c7a8ce59d5f959a7e1a8309873722bb9cdbd6dd\",\n        \"size\": 876744475\n    },\n    \"Accident_Town13_Route3309_Weather2.tar.gz\": {\n        \"sha256\": \"b3726914cdcf8312f786d42b31a710560d9891b18b08f3e26fe122ace5316117\",\n        \"size\": 775172844\n    },\n    \"Accident_Town13_Route3312_Weather5.tar.gz\": {\n        \"sha256\": \"0ed1194776960010fa06b466656b00b7eb60d5ebd01f32a56ca9a3905052ba01\",\n        \"size\": 476142477\n    },\n    \"Accident_Town13_Route3314_Weather7.tar.gz\": {\n        \"sha256\": \"330986853e77e03dd72c019f171684a3686c836c1af168bea26b308494d09f6c\",\n        \"size\": 462328999\n    },\n    \"Accident_Town13_Route3315_Weather8.tar.gz\": {\n        \"sha256\": \"0e0c7528a151bd8f1edbead47531782c340abe537bbbf8fe2e4ec4b2dbe3d040\",\n        \"size\": 463934536\n    },\n    \"Accident_Town13_Route3316_Weather9.tar.gz\": {\n        \"sha256\": \"0da4bef5cfc6ae30962ca35fe6414174a01f655fbb09be1a92370f0e60f24699\",\n        \"size\": 664863270\n    },\n    \"Accident_Town13_Route3320_Weather13.tar.gz\": {\n        \"sha256\": \"68edfaa830d6121d13e738a114b7a89c9178df7516648294c5204074e1c17022\",\n        \"size\": 384121627\n    },\n    \"Accident_Town13_Route3322_Weather15.tar.gz\": {\n        \"sha256\": \"bf84d3413310e0da7d61288302fb132ae22e29fd5c0d29a84dcaf2b0a423894a\",\n        \"size\": 229959725\n    },\n    \"BlockedIntersection_Town03_Route27330_Weather6.tar.gz\": {\n        \"sha256\": \"1b2b598b93d6c8e324725baac23d3d2c3dd661342175349830c1fc7de3f87ca4\",\n        \"size\": 281182694\n    },\n    \"BlockedIntersection_Town03_Route27335_Weather11.tar.gz\": {\n        \"sha256\": \"33b2590ff8db100f30d5fe4a39006f5a7c02d4bad6c27a130cb2e0ef933b6da0\",\n        \"size\": 761891203\n    },\n    \"BlockedIntersection_Town03_Route27340_Weather18.tar.gz\": {\n        \"sha256\": \"8987d0183adf4327e201b394c05c41e9c6a4166768bad6c4bfbd1e1eaf859147\",\n        \"size\": 234551647\n    },\n    \"BlockedIntersection_Town03_Route27345_Weather23.tar.gz\": {\n        \"sha256\": \"584966ec8e85aa85f7fc1ec1b6f3145a7cea1c4a7b3ff44dc81471aa03849182\",\n        \"size\": 233069169\n    },\n    \"BlockedIntersection_Town03_Route27350_Weather2.tar.gz\": {\n        \"sha256\": \"9548c87f8eeaff86154524065551e72c377dcf6c2b9b91e429ba9230b32c8410\",\n        \"size\": 393725713\n    },\n    \"BlockedIntersection_Town03_Route27355_Weather8.tar.gz\": {\n        \"sha256\": \"03d538793b2e7f23587973d2b782c58bbe92646b217f93e5e672d37f6769e1c5\",\n        \"size\": 287332296\n    },\n    \"BlockedIntersection_Town03_Route27360_Weather13.tar.gz\": {\n        \"sha256\": \"92884769f329dbf48ef3fade1159a68dbd98628d3620c282cbf3d1f1d602a67c\",\n        \"size\": 258917717\n    },\n    \"BlockedIntersection_Town03_Route27370_Weather26.tar.gz\": {\n        \"sha256\": \"305d27ed97c2dcec99325c441a0708fe8dfd2ac9bcc25f84e28f97f933c331db\",\n        \"size\": 722943487\n    },\n    \"BlockedIntersection_Town03_Route27375_Weather5.tar.gz\": {\n        \"sha256\": \"e9c3ce701803e7f39671adc241d98981e63b02c69a4f53fc803727486d9e956f\",\n        \"size\": 252852225\n    },\n    \"BlockedIntersection_Town03_Route27380_Weather10.tar.gz\": {\n        \"sha256\": \"dfb2669342f428f8742536f701109d4a05c5798cccd2022550ae2be8f71e66af\",\n        \"size\": 176739358\n    },\n    \"BlockedIntersection_Town03_Route27390_Weather22.tar.gz\": {\n        \"sha256\": \"d7c3c9b80901f17ed87935e4ebb93aae2301b27b29287b14bf7db2d05d850d29\",\n        \"size\": 198796676\n    },\n    \"BlockedIntersection_Town03_Route27395_Weather1.tar.gz\": {\n        \"sha256\": \"c9f4a69a87913fed556aa04733e8ead04cd41bc7ad223f3d064850dd23cfc545\",\n        \"size\": 490832507\n    },\n    \"BlockedIntersection_Town03_Route27400_Weather7.tar.gz\": {\n        \"sha256\": \"aa63681fe1e13431d8166437d575ca62ffe9e4c564513f82e78a899ec1c560e2\",\n        \"size\": 263888629\n    },\n    \"BlockedIntersection_Town03_Route27410_Weather19.tar.gz\": {\n        \"sha256\": \"e89c5c134110f7e604c58859858e6f3310ee91d29c6755b52c4f890414730c6c\",\n        \"size\": 526756180\n    },\n    \"BlockedIntersection_Town03_Route27415_Weather25.tar.gz\": {\n        \"sha256\": \"443579ded38a15f1c6df48df77d845270a40b4940603c8a4eb270779156f64ca\",\n        \"size\": 233632769\n    },\n    \"BlockedIntersection_Town03_Route27420_Weather3.tar.gz\": {\n        \"sha256\": \"52043a2c0aabe29ad99266305c9cac6db94ac3565948f89c4d8be448be1efbce\",\n        \"size\": 288119453\n    },\n    \"BlockedIntersection_Town04_Route27409_Weather18.tar.gz\": {\n        \"sha256\": \"a1104478f3c0d6aeba2a2517d6efed9de161ab7e06cff81b7e73b21e267e3608\",\n        \"size\": 271089438\n    },\n    \"BlockedIntersection_Town04_Route27414_Weather23.tar.gz\": {\n        \"sha256\": \"89dd48247ef019affb7ecbfad77a44753e36598c5b55b6cd83d78d842c3759b7\",\n        \"size\": 311596375\n    },\n    \"BlockedIntersection_Town04_Route27419_Weather2.tar.gz\": {\n        \"sha256\": \"ec63e1f418a41f7bbc583d708f8638859bed81f8f5386ee84ce295d7ed5b041f\",\n        \"size\": 620567735\n    },\n    \"BlockedIntersection_Town04_Route27424_Weather8.tar.gz\": {\n        \"sha256\": \"1117c2525b1e32e6d43e0c0c536266483498b9575a740b2783accb3e1cbc873e\",\n        \"size\": 573232137\n    },\n    \"BlockedIntersection_Town04_Route27429_Weather13.tar.gz\": {\n        \"sha256\": \"c0981d61eb23036f4d6f3ff70870387ee008cf103482541e496329cd71f5f503\",\n        \"size\": 391670267\n    },\n    \"BlockedIntersection_Town04_Route27434_Weather20.tar.gz\": {\n        \"sha256\": \"d60c2aea01aa454e651039426885f6d17d8f9577e9e05378bf94774400451f9d\",\n        \"size\": 275248852\n    },\n    \"BlockedIntersection_Town04_Route27439_Weather26.tar.gz\": {\n        \"sha256\": \"a32b9660be91aa26818967807dcb751031a7cd1e731222dd614087e59dddcedb\",\n        \"size\": 325934522\n    },\n    \"BlockedIntersection_Town04_Route27444_Weather5.tar.gz\": {\n        \"sha256\": \"8a65b4d303612a2d24db7e9e6bcbff486d5057be08447f511d0444b4fc317269\",\n        \"size\": 266998960\n    },\n    \"BlockedIntersection_Town04_Route27464_Weather1.tar.gz\": {\n        \"sha256\": \"bde92e8279fbf00ea64e5f4b14a015ca12519b531f1551f982a502a099ab4cb7\",\n        \"size\": 424437556\n    },\n    \"BlockedIntersection_Town04_Route27469_Weather7.tar.gz\": {\n        \"sha256\": \"6c984700372eb1f79f979264b803042f253de169c720de7c97d77b37b4815f1c\",\n        \"size\": 460263541\n    },\n    \"BlockedIntersection_Town04_Route27474_Weather12.tar.gz\": {\n        \"sha256\": \"1f9d0328af536a4cc5aaafa8bc81d647276cd44f953c862e225d3db3b597f150\",\n        \"size\": 514846411\n    },\n    \"BlockedIntersection_Town04_Route27484_Weather25.tar.gz\": {\n        \"sha256\": \"c7cbc0415053ebf88d6040d13897b352155307d50f4b22977445ba3aa4f50b98\",\n        \"size\": 249961291\n    },\n    \"BlockedIntersection_Town04_Route27489_Weather3.tar.gz\": {\n        \"sha256\": \"1742c9b159b2aa64113bcaf0a6b98be91f768f9e45051acce5b8eafa89a199b5\",\n        \"size\": 434463754\n    },\n    \"BlockedIntersection_Town04_Route27494_Weather9.tar.gz\": {\n        \"sha256\": \"3632e815597f31f2e8c847d607bc26015d1fe5d32125ab34758c1126edeff858\",\n        \"size\": 297027548\n    },\n    \"BlockedIntersection_Town04_Route27499_Weather14.tar.gz\": {\n        \"sha256\": \"3bb4d2bee7049b4a71d261842dfcf00775f7bbc08f4cf09b1e9229ecb79473b0\",\n        \"size\": 641008292\n    },\n    \"BlockedIntersection_Town04_Route27504_Weather21.tar.gz\": {\n        \"sha256\": \"34d5750bf6b36ac73c86cf39f6c84a934677be59597082fd89f35893446361a0\",\n        \"size\": 352096445\n    },\n    \"BlockedIntersection_Town05_Route27516_Weather8.tar.gz\": {\n        \"sha256\": \"35a03202a1c74f9c9196ff3a7efef528a792ec70317f9d0c6f6dc4f274088953\",\n        \"size\": 716779485\n    },\n    \"BlockedIntersection_Town05_Route27521_Weather13.tar.gz\": {\n        \"sha256\": \"8cc26346b81a17495cc67d7cddfa0e436084616932f482b31507f0a3a7c64985\",\n        \"size\": 220801755\n    },\n    \"BlockedIntersection_Town05_Route27526_Weather20.tar.gz\": {\n        \"sha256\": \"4af6500bf702fad7aa79d4574581a9123766b62f2950852824f0eb4a7f6f96d0\",\n        \"size\": 606312910\n    },\n    \"BlockedIntersection_Town05_Route27531_Weather26.tar.gz\": {\n        \"sha256\": \"8dd91c9e772788d22c1da93ee0badeca61c62bd8bf8546ee6d5778721989f061\",\n        \"size\": 573977549\n    },\n    \"BlockedIntersection_Town05_Route27536_Weather5.tar.gz\": {\n        \"sha256\": \"aa5c3fe9704a5882ab8dc79b3b4130c9ad518a7ff05db587d6764d94aa1008f2\",\n        \"size\": 411169174\n    },\n    \"BlockedIntersection_Town05_Route27541_Weather10.tar.gz\": {\n        \"sha256\": \"2325461b3084964bb3065848ebcdb77eda6af943e72c7d2f31f0a679f8465e9e\",\n        \"size\": 744204744\n    },\n    \"BlockedIntersection_Town05_Route27551_Weather22.tar.gz\": {\n        \"sha256\": \"519abbad6236710590c1436ddd15b83d4115a26a1b46fa75f630f7842b6a3736\",\n        \"size\": 868687776\n    },\n    \"BlockedIntersection_Town05_Route27556_Weather1.tar.gz\": {\n        \"sha256\": \"368e75e5bccaa8af83e1481e601dccea0289639136ed4609e61ecbda35791ed4\",\n        \"size\": 766439648\n    },\n    \"BlockedIntersection_Town05_Route27566_Weather12.tar.gz\": {\n        \"sha256\": \"1acfb73fc76b4bcf1f14350af53f05b40abd50860ae88d27f46409baffa2dc63\",\n        \"size\": 1002601455\n    },\n    \"BlockedIntersection_Town05_Route27571_Weather19.tar.gz\": {\n        \"sha256\": \"6e7ee61ecd15fdae05a0dff9c1c028c469f716e7ae6b9c630af3699cadab1e9c\",\n        \"size\": 381143582\n    },\n    \"BlockedIntersection_Town05_Route27576_Weather25.tar.gz\": {\n        \"sha256\": \"5abb90ce923fa9e874fc2181550c8049523446e53d0e331c8972b2ba2efe506a\",\n        \"size\": 445654423\n    },\n    \"BlockedIntersection_Town05_Route27581_Weather3.tar.gz\": {\n        \"sha256\": \"89cdb96f0f6502834d1dbb3d4df2255b7fda0eb8d185076c57917b8696e8f7b8\",\n        \"size\": 694003230\n    },\n    \"BlockedIntersection_Town05_Route27586_Weather9.tar.gz\": {\n        \"sha256\": \"b7667d0a158466414dcc884028116a59ded46280760a036c3c809eac7a642fd5\",\n        \"size\": 534001724\n    },\n    \"BlockedIntersection_Town05_Route27591_Weather14.tar.gz\": {\n        \"sha256\": \"96e4dd069a35439311e0fe8ae1a9571d827ee3c6ffb6806a7f023ef7dbaee539\",\n        \"size\": 243388839\n    },\n    \"BlockedIntersection_Town05_Route27596_Weather21.tar.gz\": {\n        \"sha256\": \"b8593585ef44cda6e4cf7a82276254ae005d8a0d0cd719b1f819476d41033671\",\n        \"size\": 649610114\n    },\n    \"BlockedIntersection_Town05_Route27601_Weather0.tar.gz\": {\n        \"sha256\": \"638caa938c1d1bd8d1398ade5ed5b5cdc87a432d3e319da78a5d01b112d29844\",\n        \"size\": 364429776\n    },\n    \"BlockedIntersection_Town05_Route27606_Weather6.tar.gz\": {\n        \"sha256\": \"e91b290a586f4c5fc899ed0328ad012b9547d33dd36d98c17e08e6455a1b2ae5\",\n        \"size\": 500088879\n    },\n    \"BlockedIntersection_Town05_Route27611_Weather11.tar.gz\": {\n        \"sha256\": \"1ef5eba58a5dfee044e687263acfab3844305c4ec53d848e0d45e784337318d1\",\n        \"size\": 749577069\n    },\n    \"BlockedIntersection_Town11_Route27467_Weather5.tar.gz\": {\n        \"sha256\": \"5c214f92b4f04bb06c5d49670718b2932b9d2bfbdc0d2dbf91c54cdac0186114\",\n        \"size\": 108397403\n    },\n    \"BlockedIntersection_Town11_Route27472_Weather10.tar.gz\": {\n        \"sha256\": \"ece208cc40bb7d3843a68dc48f7dc9107f5664068ccdc934cc401552f83d9e9f\",\n        \"size\": 83766598\n    },\n    \"BlockedIntersection_Town11_Route27477_Weather15.tar.gz\": {\n        \"sha256\": \"7159c0332d770f0a9e92dd1ad4aa963aa50f1d9dc12e9d001a0ba214fcb8ca24\",\n        \"size\": 119603241\n    },\n    \"BlockedIntersection_Town11_Route27482_Weather22.tar.gz\": {\n        \"sha256\": \"8b3678ceffab70d55f7f5d090c83b38b8f7f47835997076db7b7f0d25f211c0a\",\n        \"size\": 97733641\n    },\n    \"BlockedIntersection_Town11_Route27487_Weather1.tar.gz\": {\n        \"sha256\": \"cca99f6528f69117884ac715e4c77994b907b8ca57869a3a1cca2f02fcebb0f6\",\n        \"size\": 121726145\n    },\n    \"BlockedIntersection_Town11_Route27492_Weather7.tar.gz\": {\n        \"sha256\": \"7828540a86e082340636e16687531ad9c4cdb13a1094992c395a2bf60175945a\",\n        \"size\": 121744963\n    },\n    \"BlockedIntersection_Town11_Route27497_Weather12.tar.gz\": {\n        \"sha256\": \"6bfd09715c51f5902bb429eb3ca21b4653cdf8ff795372751450521f6d4e374f\",\n        \"size\": 85269273\n    },\n    \"BlockedIntersection_Town11_Route27502_Weather19.tar.gz\": {\n        \"sha256\": \"d0558a47da50b07570381a6df4e65ab5546ca2dc76a71caded2ffaf27bf10215\",\n        \"size\": 65797406\n    },\n    \"BlockedIntersection_Town11_Route27507_Weather25.tar.gz\": {\n        \"sha256\": \"9b284fb63c211e8af047038f660da447d9874dd2982d60daba78cb2489dc7117\",\n        \"size\": 56931488\n    },\n    \"BlockedIntersection_Town11_Route27512_Weather3.tar.gz\": {\n        \"sha256\": \"f05e6f05d43ed21a5001e20ccf52fdbc6ed8d0e6b26c8f90e3762d6bc3f8bc12\",\n        \"size\": 162277466\n    },\n    \"BlockedIntersection_Town11_Route27517_Weather9.tar.gz\": {\n        \"sha256\": \"a3cc5acd97f74eeede5a7e5be3f7c675ec3c40a8d0a90a4402e89f984f797a16\",\n        \"size\": 120009508\n    },\n    \"BlockedIntersection_Town11_Route27522_Weather14.tar.gz\": {\n        \"sha256\": \"d8b16d68dd77aa2fe1fefc6668a8707e3a675cebf9a1c81a84681981854f8ba3\",\n        \"size\": 135366300\n    },\n    \"BlockedIntersection_Town11_Route27527_Weather21.tar.gz\": {\n        \"sha256\": \"cf222c7c7f05cf81ba7e89bc40b6abc386b36495efb8738cf850eda4a0c76465\",\n        \"size\": 91284997\n    },\n    \"BlockedIntersection_Town11_Route27532_Weather0.tar.gz\": {\n        \"sha256\": \"e722fa6b41022e7112ebd4e21339baff934a6bd3fd47357aa9427a9daff91032\",\n        \"size\": 100208528\n    },\n    \"BlockedIntersection_Town11_Route27537_Weather6.tar.gz\": {\n        \"sha256\": \"45a64d7392070732bafd0683919bfcccabed48c4c176480d2db3c57b8a8a34b2\",\n        \"size\": 159108568\n    },\n    \"BlockedIntersection_Town11_Route27542_Weather11.tar.gz\": {\n        \"sha256\": \"cc69c8f43add69d021182331c16bcb66feb50324a8fa7e4078bb5d38c0c4503d\",\n        \"size\": 72196424\n    },\n    \"BlockedIntersection_Town11_Route27547_Weather18.tar.gz\": {\n        \"sha256\": \"116eeb3081f8023b92500553bd4a30ff63a6fb119ca240319356b403e893e8de\",\n        \"size\": 175780272\n    },\n    \"BlockedIntersection_Town11_Route27552_Weather23.tar.gz\": {\n        \"sha256\": \"bab7a02a95504bf43af00956c68ddb8fc2f539670c39a7ae6edd2af28f5010eb\",\n        \"size\": 154922556\n    },\n    \"BlockedIntersection_Town11_Route27557_Weather2.tar.gz\": {\n        \"sha256\": \"f2a07ffead50c6e1af164251e55939d1e2e29cffe21d8a5eb01f86263aea0d5c\",\n        \"size\": 133939606\n    },\n    \"BlockedIntersection_Town11_Route27562_Weather8.tar.gz\": {\n        \"sha256\": \"aed1b48640f9fa9829124944f7389bdbd964b4fbc826396a70861a3fb8b6b41b\",\n        \"size\": 88001162\n    },\n    \"BlockedIntersection_Town12_Route12437_Weather12.tar.gz\": {\n        \"sha256\": \"b42ded9f81486f05e9a147e471f78e15d37869250eb8e3b3c47536a64c2aaa6f\",\n        \"size\": 567482905\n    },\n    \"BlockedIntersection_Town12_Route12438_Weather13.tar.gz\": {\n        \"sha256\": \"2e1837faeaefcc5bf2d992e6baaeb9b37b1269ceda54cf0f31b3a3b85a9497b4\",\n        \"size\": 362345983\n    },\n    \"BlockedIntersection_Town12_Route12439_Weather14.tar.gz\": {\n        \"sha256\": \"0f00f31704e47db4a7a457aaef5e3005960434592988f8063b4452b6f8604dd2\",\n        \"size\": 518309861\n    },\n    \"BlockedIntersection_Town12_Route12440_Weather15.tar.gz\": {\n        \"sha256\": \"17c35c62a4adad604dd1ddc12ac930e2a696b2a97e2d1f0d1bca82d700287a74\",\n        \"size\": 600823248\n    },\n    \"BlockedIntersection_Town12_Route12441_Weather8.tar.gz\": {\n        \"sha256\": \"3235f0f607231436ca709f5e347ba41815b53036f2a857d8b9b3dae8a0418157\",\n        \"size\": 348898572\n    },\n    \"BlockedIntersection_Town12_Route12443_Weather18.tar.gz\": {\n        \"sha256\": \"158e69f143d48c91ae2265913eb7c3985bf026c8009e9d59ec8be4a894c7f613\",\n        \"size\": 320326234\n    },\n    \"BlockedIntersection_Town12_Route12444_Weather19.tar.gz\": {\n        \"sha256\": \"d503ba42ccfddbeadea60b8b44109565603f50ea3d9940efc093812f7cd20b31\",\n        \"size\": 249058021\n    },\n    \"BlockedIntersection_Town12_Route12445_Weather20.tar.gz\": {\n        \"sha256\": \"3c71007c5ca49db43e6d1c6fc734278afb9a451bc35c344f0a33e49c94a4c045\",\n        \"size\": 323089265\n    },\n    \"BlockedIntersection_Town12_Route12446_Weather21.tar.gz\": {\n        \"sha256\": \"210dbc583881de4dae485c4e841f3cd796028763c18d6ef48605bb5af08d86c9\",\n        \"size\": 326453760\n    },\n    \"BlockedIntersection_Town12_Route12448_Weather23.tar.gz\": {\n        \"sha256\": \"8ed3c1ff43f6eeb61d33300dd88ae9074f0eadadf74b0f690ed82a4401961bd3\",\n        \"size\": 321448404\n    },\n    \"BlockedIntersection_Town12_Route12450_Weather25.tar.gz\": {\n        \"sha256\": \"6cca7294cd007ac1ea22622e7c8445f9561ed900becfb8d7ca23c8dbeffd9ba5\",\n        \"size\": 479379924\n    },\n    \"BlockedIntersection_Town12_Route12451_Weather0.tar.gz\": {\n        \"sha256\": \"6346b615b9635d74f62519ca2725a05ea3ed1dd6ad84b7990e969aa3cca4bc45\",\n        \"size\": 818909079\n    },\n    \"BlockedIntersection_Town12_Route12454_Weather3.tar.gz\": {\n        \"sha256\": \"69a4e76375c98ab61b11278523446174088484b08b3bbf26ea5eeb3355669d31\",\n        \"size\": 379858284\n    },\n    \"BlockedIntersection_Town12_Route12455_Weather3.tar.gz\": {\n        \"sha256\": \"197c392b3955921c4788277e9632c4b555ac6ba639dc1bac6b79518356f64353\",\n        \"size\": 294059118\n    },\n    \"BlockedIntersection_Town12_Route12460_Weather9.tar.gz\": {\n        \"sha256\": \"5a837fd046434b3da093cdffd2b6b213c4d29e84fa268c4ba1fb81edbc8dd62d\",\n        \"size\": 270024665\n    },\n    \"BlockedIntersection_Town12_Route12461_Weather10.tar.gz\": {\n        \"sha256\": \"1192ede01341241316cd7af1cacb183e15810f7e7f1d0ae42da32431ed860fe2\",\n        \"size\": 327525015\n    },\n    \"BlockedIntersection_Town12_Route12462_Weather11.tar.gz\": {\n        \"sha256\": \"66ef679860c0d4faaf6767daa76c34e82c93e5c7156eeba47344d1ac393f5d38\",\n        \"size\": 391903908\n    },\n    \"BlockedIntersection_Town12_Route12463_Weather12.tar.gz\": {\n        \"sha256\": \"e96a5ce2a1c75f6be51836923e9f936f57963edb39bcccc168982709c8ef4a19\",\n        \"size\": 355975009\n    },\n    \"BlockedIntersection_Town12_Route12464_Weather13.tar.gz\": {\n        \"sha256\": \"f552acfb06bb80ae7e97facbc04f619354553bc4a166e227b8c5c8b55de53211\",\n        \"size\": 308156432\n    },\n    \"BlockedIntersection_Town12_Route12465_Weather14.tar.gz\": {\n        \"sha256\": \"b3527bffc06bd17f1f7e2f3c48f024224ee739cb9c43128767bf848e36d47138\",\n        \"size\": 537324783\n    },\n    \"BlockedIntersection_Town12_Route12466_Weather15.tar.gz\": {\n        \"sha256\": \"dec152342a4138d2019c4ec2dfc4797c08e12ab50cbff46767afc790f7acbce0\",\n        \"size\": 406367256\n    },\n    \"BlockedIntersection_Town12_Route12468_Weather9.tar.gz\": {\n        \"sha256\": \"828ebf5c5a50fb5a600851e3f65fe482f96e38efdf3c16450d461b8ee8bfc89c\",\n        \"size\": 262389305\n    },\n    \"BlockedIntersection_Town12_Route12469_Weather18.tar.gz\": {\n        \"sha256\": \"a4e35e95bd55110740f49484e560a62e34fea756ec6caa3837d8040f92afed09\",\n        \"size\": 261402092\n    },\n    \"BlockedIntersection_Town12_Route12470_Weather19.tar.gz\": {\n        \"sha256\": \"4d4f77e87b1160323a6a04a1e01830ee5b780e55d7e5eeed3f6cc921a1f5e723\",\n        \"size\": 328697927\n    },\n    \"BlockedIntersection_Town12_Route12471_Weather20.tar.gz\": {\n        \"sha256\": \"d0c9b9692453548454f6fa1a0f587242b41c83850baac496aa58df948f7498c1\",\n        \"size\": 408598039\n    },\n    \"BlockedIntersection_Town12_Route12472_Weather21.tar.gz\": {\n        \"sha256\": \"534d460e7b911b4defb4214a57a74e83e5fde3d714ad69f0763797f298fa751e\",\n        \"size\": 338931869\n    },\n    \"BlockedIntersection_Town12_Route12473_Weather22.tar.gz\": {\n        \"sha256\": \"83a700845d5d7fd1cf978ddcd3ee8b58b0b1fb19beaaf1f7304f64cefcdce887\",\n        \"size\": 290245483\n    },\n    \"BlockedIntersection_Town12_Route12474_Weather23.tar.gz\": {\n        \"sha256\": \"cb7ec2bfeaa5adfb962866865f0ade0161e31e4ad6516627719f8492768f292a\",\n        \"size\": 389114544\n    },\n    \"BlockedIntersection_Town12_Route12475_Weather23.tar.gz\": {\n        \"sha256\": \"92b76da15cfec012a0661492e4ec66a2cd63a759a92ac03b2e9c99910c528ce0\",\n        \"size\": 241383410\n    },\n    \"BlockedIntersection_Town12_Route12476_Weather25.tar.gz\": {\n        \"sha256\": \"f9d3ffe9b59a11716ef94b29e1d1e60ea33d4251cf22a051124b9530674da069\",\n        \"size\": 313754108\n    },\n    \"BlockedIntersection_Town12_Route12477_Weather0.tar.gz\": {\n        \"sha256\": \"f0fcd73ae9ecc88e2d3f72474dc8b7d3a878c091b87dc140bd6b0f41637a78e5\",\n        \"size\": 421287913\n    },\n    \"BlockedIntersection_Town12_Route12478_Weather1.tar.gz\": {\n        \"sha256\": \"b27b4596bad807a09d6854403a845bfa68ae7b176640b8d2672e12496749a1dd\",\n        \"size\": 302494758\n    },\n    \"BlockedIntersection_Town12_Route12479_Weather2.tar.gz\": {\n        \"sha256\": \"08c000c479d6d2eeaef62fd52e479db74c842834ee5e508794b585fe13b774e8\",\n        \"size\": 524559558\n    },\n    \"BlockedIntersection_Town12_Route12480_Weather3.tar.gz\": {\n        \"sha256\": \"a1ae4032bb908024bddf6b28a6e12c6bd5a0be8c9d424afbad1db5c29740c523\",\n        \"size\": 339612492\n    },\n    \"BlockedIntersection_Town12_Route12481_Weather3.tar.gz\": {\n        \"sha256\": \"ba9e31bca71f97475bf65f1121ecb1d5c3dbdb470427a8f203938fc5c56a0096\",\n        \"size\": 422275962\n    },\n    \"BlockedIntersection_Town12_Route12482_Weather5.tar.gz\": {\n        \"sha256\": \"ca84c5dd80273b1cfc97b409797cf2fc6ab5bbcfcb6a9c64af71c34b509478f5\",\n        \"size\": 282959524\n    },\n    \"BlockedIntersection_Town12_Route12483_Weather6.tar.gz\": {\n        \"sha256\": \"32240f020fca01a863b56ac9ce4be8515c7873e4717111b6b681affce3e6fdb1\",\n        \"size\": 286691402\n    },\n    \"BlockedIntersection_Town12_Route12485_Weather8.tar.gz\": {\n        \"sha256\": \"5087dd2331bb26dd0203592eb49c4da26529252faf6c79efb68eafa0016e7b59\",\n        \"size\": 306518342\n    },\n    \"BlockedIntersection_Town12_Route12486_Weather9.tar.gz\": {\n        \"sha256\": \"5cec65376a7ad9ac8750f2a5a9cd9da5e94d285d6630842fdb0a7ad808c5ef1f\",\n        \"size\": 254623626\n    },\n    \"BlockedIntersection_Town12_Route12487_Weather10.tar.gz\": {\n        \"sha256\": \"275f4b513ee0fd8ccbe1b4b532688b1332d38f3e5f5d7717c6bb92183a8f62c8\",\n        \"size\": 122880371\n    },\n    \"BlockedIntersection_Town12_Route12488_Weather11.tar.gz\": {\n        \"sha256\": \"3ad91b0571fc1022743d045771f5afc8c92dffecc45e918859d9591701b29276\",\n        \"size\": 338600199\n    },\n    \"BlockedIntersection_Town12_Route12489_Weather12.tar.gz\": {\n        \"sha256\": \"ca0b3bdbc26513d7d9650be27be0613919194980f75cca09e9a1422f175787f5\",\n        \"size\": 529435350\n    },\n    \"BlockedIntersection_Town12_Route12490_Weather13.tar.gz\": {\n        \"sha256\": \"928da6c7646eed1f9f2dbe3e61b05b079144940b362c49f270badff60acc2099\",\n        \"size\": 369434158\n    },\n    \"BlockedIntersection_Town12_Route12492_Weather15.tar.gz\": {\n        \"sha256\": \"6dca7e9a8a013954dfa84e86f8b6b1680433573812fb26b6b242935072ad4757\",\n        \"size\": 426911785\n    },\n    \"BlockedIntersection_Town12_Route12493_Weather8.tar.gz\": {\n        \"sha256\": \"7a0128f50a5cb09e9d9cc1b9d12ae57dd677d8916002eabb8c6ddc817bcd6683\",\n        \"size\": 477834619\n    },\n    \"BlockedIntersection_Town12_Route12496_Weather19.tar.gz\": {\n        \"sha256\": \"5b0c70aaa1331b26c12df6952982cc89cd419344521e88f6b99b84ae587c8a71\",\n        \"size\": 227439019\n    },\n    \"BlockedIntersection_Town12_Route12497_Weather20.tar.gz\": {\n        \"sha256\": \"d96fe301915f9b847553bc386d2125d69ff3c9c786cf411df561e4324f452962\",\n        \"size\": 376408132\n    },\n    \"BlockedIntersection_Town12_Route12498_Weather21.tar.gz\": {\n        \"sha256\": \"f3dc38fd473371e82b918cabbebb93001edeafb2aa113219f7e872a0f35544a5\",\n        \"size\": 773101207\n    },\n    \"BlockedIntersection_Town12_Route12499_Weather22.tar.gz\": {\n        \"sha256\": \"64c93c6ba1b96cf26ae988ea080ce0d84ad03541947420249864960337613d18\",\n        \"size\": 798050453\n    },\n    \"BlockedIntersection_Town12_Route12501_Weather23.tar.gz\": {\n        \"sha256\": \"785a1ff49f08e050cf623352eeadc6c66b974289a86b632c29e5d7dae422eb5c\",\n        \"size\": 292907606\n    },\n    \"BlockedIntersection_Town12_Route12502_Weather25.tar.gz\": {\n        \"sha256\": \"fae62af02088eeac0ef944c0e5bdcd74e67c3d338a9d7f315e7e841633da17c5\",\n        \"size\": 200273009\n    },\n    \"BlockedIntersection_Town12_Route12504_Weather1.tar.gz\": {\n        \"sha256\": \"40c6b1f5acb09209346aff0c2f63b962dbb0ae206e2966f79dc84bcf2238d414\",\n        \"size\": 648426446\n    },\n    \"BlockedIntersection_Town12_Route12505_Weather2.tar.gz\": {\n        \"sha256\": \"2129e9cb3c09cb008b56aee57658d3fa92684a7d001c99573194ce451125d7d4\",\n        \"size\": 307227013\n    },\n    \"BlockedIntersection_Town12_Route12506_Weather3.tar.gz\": {\n        \"sha256\": \"a9ceab1f18cebd6dec11c0dbd6e0e01a6079156fafb62c3d1a4788656bd590f2\",\n        \"size\": 727822962\n    },\n    \"BlockedIntersection_Town12_Route12507_Weather3.tar.gz\": {\n        \"sha256\": \"5b7725987c72e58286608b23ed87527c73e09cf8ef59fc1d76e6be0d35eb9b4f\",\n        \"size\": 342731787\n    },\n    \"BlockedIntersection_Town12_Route12508_Weather5.tar.gz\": {\n        \"sha256\": \"273066fa2771d5911c3661946d4155bac33c4d5af976894334fdaf7695bc0b38\",\n        \"size\": 622633731\n    },\n    \"BlockedIntersection_Town12_Route12509_Weather6.tar.gz\": {\n        \"sha256\": \"d36b06661c42092a3fdc1188a091325d833ce0d33a7d7f67db81e21c2248be7e\",\n        \"size\": 707768183\n    },\n    \"BlockedIntersection_Town12_Route12510_Weather7.tar.gz\": {\n        \"sha256\": \"c122ff3a81846bd44e8befda41dc7001477e07b406e6f7e8947613c09007eac8\",\n        \"size\": 236227538\n    },\n    \"BlockedIntersection_Town12_Route12511_Weather8.tar.gz\": {\n        \"sha256\": \"de7acd93886cd2dfa7c281d653c6deeceee51516c174b76b9fe203faf173493f\",\n        \"size\": 240264911\n    },\n    \"BlockedIntersection_Town12_Route12513_Weather10.tar.gz\": {\n        \"sha256\": \"25797c76cc6c3abbd113b1937d77dd203851c9ad96e612e1942285e5ef7434c4\",\n        \"size\": 256961664\n    },\n    \"BlockedIntersection_Town12_Route12514_Weather11.tar.gz\": {\n        \"sha256\": \"a4848520974b1c9882cd3be1573971556b830bb86deaac84369b23006a8a9e9e\",\n        \"size\": 254678961\n    },\n    \"BlockedIntersection_Town12_Route12515_Weather12.tar.gz\": {\n        \"sha256\": \"d49f5b67eabacdc5cde0d2a3f33480c36890fb909184faf57c8ee2773e5581bc\",\n        \"size\": 253326446\n    },\n    \"BlockedIntersection_Town12_Route12516_Weather13.tar.gz\": {\n        \"sha256\": \"b7f6d731101468c37191a1e21a7d990179babca16176aa06933291745b69699d\",\n        \"size\": 189425730\n    },\n    \"BlockedIntersection_Town12_Route12517_Weather14.tar.gz\": {\n        \"sha256\": \"54237959a43e285ad6f86cdcce068fcb16671c076dbfece20a971de46f254b61\",\n        \"size\": 519687609\n    },\n    \"BlockedIntersection_Town12_Route12518_Weather15.tar.gz\": {\n        \"sha256\": \"7eb396a0934bc86f5b364b37e93802d73c6e0c6dedb6269f5229d28297580a2f\",\n        \"size\": 339657820\n    },\n    \"BlockedIntersection_Town12_Route12519_Weather8.tar.gz\": {\n        \"sha256\": \"ca5d56de0d96ccfa20068e4946971d7e8ae5b7110d219fdf52e7b61f2a2cbfdf\",\n        \"size\": 303760146\n    },\n    \"BlockedIntersection_Town12_Route12520_Weather9.tar.gz\": {\n        \"sha256\": \"8713bbd41e0e83df115bdf229f57eb8246b8d6bfe113e201c0974acbce4f94a5\",\n        \"size\": 191604877\n    },\n    \"BlockedIntersection_Town12_Route12522_Weather19.tar.gz\": {\n        \"sha256\": \"67eded6930215e960f0555af24efa2defe1742ee9be97e25acb6bdf0b113ec50\",\n        \"size\": 192545404\n    },\n    \"BlockedIntersection_Town12_Route12523_Weather20.tar.gz\": {\n        \"sha256\": \"a7c665df01d60ecb2b71e5cfff2cdecf6c303d4833140a9fda6f89e306a7e586\",\n        \"size\": 597025392\n    },\n    \"BlockedIntersection_Town12_Route12524_Weather21.tar.gz\": {\n        \"sha256\": \"18f93ce1c86eea594cff34c0c463dce054f6ede2f8999d5a4f8b7a99665c5335\",\n        \"size\": 254460679\n    },\n    \"BlockedIntersection_Town12_Route12525_Weather22.tar.gz\": {\n        \"sha256\": \"eb76a7ac32b771bc7f71396d6abb5b9e69ce3b9f62d5dce71483d4c98ba19dcb\",\n        \"size\": 326719027\n    },\n    \"BlockedIntersection_Town12_Route12527_Weather23.tar.gz\": {\n        \"sha256\": \"2a2311a5a63e4a399144ac748897b921bb9816ae9f72a5ff2ba7e91431b19cba\",\n        \"size\": 709665007\n    },\n    \"BlockedIntersection_Town12_Route12528_Weather25.tar.gz\": {\n        \"sha256\": \"ec355f16ab1566061aadf4de575baba20bb3813a1cd1894e29a84581f8cbc72f\",\n        \"size\": 279444614\n    },\n    \"BlockedIntersection_Town12_Route12529_Weather0.tar.gz\": {\n        \"sha256\": \"d0ebbeea1910bcf72f88c1ccdd3efdd605835491b49b493cd398202d8a4968e8\",\n        \"size\": 844827761\n    },\n    \"BlockedIntersection_Town12_Route12530_Weather1.tar.gz\": {\n        \"sha256\": \"1b342264b815065e512bc6063e330cf04804f4114175509b847e61ee3775f087\",\n        \"size\": 346502527\n    },\n    \"BlockedIntersection_Town12_Route12531_Weather2.tar.gz\": {\n        \"sha256\": \"3a0f511760155ee2830e440284cc248400c426a2152113d1c110fbfbab2755a1\",\n        \"size\": 231425887\n    },\n    \"BlockedIntersection_Town12_Route12532_Weather3.tar.gz\": {\n        \"sha256\": \"d4a38e8829449728ec1a3d74a4a705fb64a07f1e172b4225a02dfc9afebc95dd\",\n        \"size\": 283723687\n    },\n    \"BlockedIntersection_Town12_Route12535_Weather6.tar.gz\": {\n        \"sha256\": \"043a68076984d6d4298205f4fb01cc92a57227dfdfc0fd2c2c2e43968fd9da46\",\n        \"size\": 593858449\n    },\n    \"BlockedIntersection_Town12_Route12536_Weather7.tar.gz\": {\n        \"sha256\": \"d6cacf37ea93c2be21ff69d8c7424c7659abaef4dce75bb1dc95c1d5577c72de\",\n        \"size\": 360560250\n    },\n    \"BlockedIntersection_Town12_Route12538_Weather9.tar.gz\": {\n        \"sha256\": \"1747fbc98558466f8697f5bb3891aa7d775f01377abb813f381c9a6c397e3567\",\n        \"size\": 398847174\n    },\n    \"BlockedIntersection_Town12_Route12539_Weather10.tar.gz\": {\n        \"sha256\": \"86ba039c344e6b4121af4ab04ce3fea94c3f4b960ba91111749261c5dff709de\",\n        \"size\": 335520673\n    },\n    \"BlockedIntersection_Town12_Route12540_Weather11.tar.gz\": {\n        \"sha256\": \"8a13c38d5e29a3ff8843ee6955fb2a215b145196cfa991fd1b47d8ad107d623a\",\n        \"size\": 212423979\n    },\n    \"BlockedIntersection_Town12_Route12541_Weather12.tar.gz\": {\n        \"sha256\": \"0302aead9a9030a87ecc457f4bc3f8e445f5ecb1d6d1f89778415e64ae2cb797\",\n        \"size\": 376126530\n    },\n    \"BlockedIntersection_Town12_Route12542_Weather13.tar.gz\": {\n        \"sha256\": \"5327de579877353ecbcea871d8b7b51f7ca08b0abde59141c7697fdd534b92ae\",\n        \"size\": 129728077\n    },\n    \"BlockedIntersection_Town12_Route12543_Weather14.tar.gz\": {\n        \"sha256\": \"6f96abf163d9babca4be39af730a8737ce65eb4f14fc1f55944b1942aa8fd213\",\n        \"size\": 556478318\n    },\n    \"BlockedIntersection_Town12_Route12544_Weather15.tar.gz\": {\n        \"sha256\": \"1ec52cae74e562567c3680a236d40568ff09ef8b0f3fd0907e625946a259f5d0\",\n        \"size\": 561220868\n    },\n    \"BlockedIntersection_Town12_Route12545_Weather8.tar.gz\": {\n        \"sha256\": \"89c0a4cb410f5cf907d7db3946a96b704a5ca1e4d0c03d17b48614f36381cd27\",\n        \"size\": 168678612\n    },\n    \"BlockedIntersection_Town12_Route12546_Weather9.tar.gz\": {\n        \"sha256\": \"05547462714f95af7b21b71c38c8bd0e40215cc607c39ceb71d38e83ada2fb78\",\n        \"size\": 400910409\n    },\n    \"BlockedIntersection_Town12_Route12547_Weather18.tar.gz\": {\n        \"sha256\": \"ed792301dba5e08c4214c7e7f3bcebb143b0fef69e5ebb398d5a6d3c282e3c1a\",\n        \"size\": 470137875\n    },\n    \"BlockedIntersection_Town12_Route12549_Weather20.tar.gz\": {\n        \"sha256\": \"6d47e9f381c295ac9d4c62aa07d88522527d313ee46e3c18322b1c1944d820cf\",\n        \"size\": 362961298\n    },\n    \"BlockedIntersection_Town12_Route12550_Weather21.tar.gz\": {\n        \"sha256\": \"2fe954cb09b26a30533e00cf5a5c2972d31794b0ae8fcf5f36a9da0add274f7c\",\n        \"size\": 261731757\n    },\n    \"BlockedIntersection_Town12_Route12551_Weather22.tar.gz\": {\n        \"sha256\": \"e73d00023b360e2d677caebf28677afc73ae17b633fc45b9782dcc443b5e7b2a\",\n        \"size\": 262949846\n    },\n    \"BlockedIntersection_Town12_Route12553_Weather23.tar.gz\": {\n        \"sha256\": \"8808830b21fdbb4017211ab7d865d2399f4ac788b39fcb8a3d19c9c0cdec0b3b\",\n        \"size\": 337698096\n    },\n    \"BlockedIntersection_Town12_Route12554_Weather25.tar.gz\": {\n        \"sha256\": \"8eaed1e8b93ce0c4170367cd80441960564cf38a20d67e525556060b85067aa7\",\n        \"size\": 226154678\n    },\n    \"BlockedIntersection_Town12_Route12555_Weather0.tar.gz\": {\n        \"sha256\": \"85dfa3805546c1d2b304c3b2087e1675367be2020a33dee6ef3b292239d55daa\",\n        \"size\": 609263761\n    },\n    \"BlockedIntersection_Town12_Route12556_Weather1.tar.gz\": {\n        \"sha256\": \"2e251779cefdc8f3538aa5daf8756b199231170c4075ac0d2837063640679dc0\",\n        \"size\": 633574788\n    },\n    \"BlockedIntersection_Town12_Route12557_Weather2.tar.gz\": {\n        \"sha256\": \"62bf3dabaa81729eb75506aa62d7f54620376f59116446e50587821b9d4eac7e\",\n        \"size\": 307170149\n    },\n    \"BlockedIntersection_Town12_Route12558_Weather3.tar.gz\": {\n        \"sha256\": \"511224814a55f4162116927cc313fc800895fd086035586659598703e03df935\",\n        \"size\": 430303797\n    },\n    \"BlockedIntersection_Town12_Route12559_Weather3.tar.gz\": {\n        \"sha256\": \"0f9ef686410d2fd316001bd4f80cdc9ff5c29d226118e41a5e437e7dbf1fa620\",\n        \"size\": 560902129\n    },\n    \"BlockedIntersection_Town12_Route12562_Weather7.tar.gz\": {\n        \"sha256\": \"043669096dca2ae7cfb0fbe315d996548956f27f8b88f587dfceaeb416fdcc3d\",\n        \"size\": 515104747\n    },\n    \"BlockedIntersection_Town12_Route12563_Weather8.tar.gz\": {\n        \"sha256\": \"67b180826763c8add886e773e033a1235380cc694ec239959f71aeea48b20686\",\n        \"size\": 253285161\n    },\n    \"BlockedIntersection_Town12_Route12564_Weather9.tar.gz\": {\n        \"sha256\": \"5740d785e9fd1b30306c706027c1adff59f6472bb29cd86a141edf3559278e4c\",\n        \"size\": 340081775\n    },\n    \"BlockedIntersection_Town12_Route12565_Weather10.tar.gz\": {\n        \"sha256\": \"b205f0dc67403876fd240296e0bac7c682163fd6f7c4f4b6795ab7924b8778fa\",\n        \"size\": 432667104\n    },\n    \"BlockedIntersection_Town12_Route12566_Weather11.tar.gz\": {\n        \"sha256\": \"c055e3e094d513771317d9269dba0311b682a37addf4490fb09feabdc6bdbd2d\",\n        \"size\": 663200454\n    },\n    \"BlockedIntersection_Town12_Route12567_Weather12.tar.gz\": {\n        \"sha256\": \"a08ea5a54cff755a05970386a9647ed1b336c7b82e2b4f18e2f7578a3258a91f\",\n        \"size\": 293838625\n    },\n    \"BlockedIntersection_Town12_Route12568_Weather13.tar.gz\": {\n        \"sha256\": \"d5b64a4d738e4706426b3305bcdeb67dc90189f38b6edb5ed09cbd30be7db5ba\",\n        \"size\": 494723553\n    },\n    \"BlockedIntersection_Town12_Route12569_Weather14.tar.gz\": {\n        \"sha256\": \"1f6c477a641575408168c60831bda881f410fa5b5279eaccda94bfe9b69cbca9\",\n        \"size\": 414913543\n    },\n    \"BlockedIntersection_Town12_Route12572_Weather9.tar.gz\": {\n        \"sha256\": \"3c11f1a76bd7389e606c26d54fe2fbaa245ef6a06510bdd32683d493e6c87ff4\",\n        \"size\": 253138700\n    },\n    \"BlockedIntersection_Town12_Route12573_Weather18.tar.gz\": {\n        \"sha256\": \"561e89992d6a12860b12604659870592fc9878260ccaceb5a46a89f87a75eb7d\",\n        \"size\": 523920718\n    },\n    \"BlockedIntersection_Town12_Route12574_Weather19.tar.gz\": {\n        \"sha256\": \"c0928bbfedde5c1e7dbeeeb5e650c2abefcb680c97d5e23b25a540ac6e69444c\",\n        \"size\": 327088819\n    },\n    \"BlockedIntersection_Town12_Route12575_Weather20.tar.gz\": {\n        \"sha256\": \"af14bcec89aea3d3e68ad145ced1da2450b7d399b2a7b4258143bec77c18bae8\",\n        \"size\": 303009230\n    },\n    \"BlockedIntersection_Town12_Route12576_Weather21.tar.gz\": {\n        \"sha256\": \"916a35ee7d85ad24d0e54e475aa97ae6f8804ee1585ff8a52a45d4f48db85e1e\",\n        \"size\": 225910580\n    },\n    \"BlockedIntersection_Town12_Route12577_Weather22.tar.gz\": {\n        \"sha256\": \"88940c45e540144090e34572ce1bd46e0d1ca413a697b10aed01839c130737d0\",\n        \"size\": 343597171\n    },\n    \"BlockedIntersection_Town12_Route12578_Weather23.tar.gz\": {\n        \"sha256\": \"27a7060f8307fb881c3c22bf3319f8915aac60d1e240ab3173a4cc521ec5a6cb\",\n        \"size\": 205979023\n    },\n    \"BlockedIntersection_Town12_Route12579_Weather23.tar.gz\": {\n        \"sha256\": \"2532bf89e31b7b28a63b054c693e98089bcbc93c8cd97b9623e01b872962db19\",\n        \"size\": 426605919\n    },\n    \"BlockedIntersection_Town12_Route12580_Weather25.tar.gz\": {\n        \"sha256\": \"db4b03442b4ddac3bc36b990549d5ac4c0ba3baf5b40722b9426db131667726b\",\n        \"size\": 280733991\n    },\n    \"BlockedIntersection_Town12_Route12581_Weather0.tar.gz\": {\n        \"sha256\": \"782e7ef6fced4b4d421dafc3fdffc68d72c4278324d48df5a3af9f06e877dd5e\",\n        \"size\": 510798196\n    },\n    \"BlockedIntersection_Town12_Route12582_Weather1.tar.gz\": {\n        \"sha256\": \"be5221c44a5b5ceb3c2141b7650c3960cbad716914d3345a7a6f3430f4f81d94\",\n        \"size\": 1140784425\n    },\n    \"BlockedIntersection_Town12_Route12583_Weather2.tar.gz\": {\n        \"sha256\": \"f62fa87e42373ec08d1b77bad09f4e659502a799b783bf6982d6c655c472ec4c\",\n        \"size\": 453672125\n    },\n    \"BlockedIntersection_Town12_Route12585_Weather3.tar.gz\": {\n        \"sha256\": \"c65d1e668d9b9a3d98a4ad301760368ec1fc62cf41ae34ccc563ab78bb94aaa3\",\n        \"size\": 564963273\n    },\n    \"BlockedIntersection_Town12_Route12586_Weather5.tar.gz\": {\n        \"sha256\": \"4cd0af73a4d20668b936324918470b21c1db727a937b1861a38feca021d87021\",\n        \"size\": 336036121\n    },\n    \"BlockedIntersection_Town12_Route12587_Weather6.tar.gz\": {\n        \"sha256\": \"290ebff17036d4df4cec89660d8a30ed1f84059f03534137c7d6c20225726de5\",\n        \"size\": 1110829952\n    },\n    \"BlockedIntersection_Town12_Route12588_Weather7.tar.gz\": {\n        \"sha256\": \"17c28fda6b757d0d66921dba5607c6b7ee190f74b2307329bf54ea9bb468e70e\",\n        \"size\": 752456191\n    },\n    \"BlockedIntersection_Town12_Route12589_Weather8.tar.gz\": {\n        \"sha256\": \"20c248328a2e7ca029df67461300ac7a6c607d8c83d6588e4da76a2518d29f52\",\n        \"size\": 379752683\n    },\n    \"BlockedIntersection_Town12_Route12590_Weather9.tar.gz\": {\n        \"sha256\": \"2c01c8c80c53d23270f079cb88a342cfc0b6f788165096a4b753414c4fa61abf\",\n        \"size\": 341224184\n    },\n    \"BlockedIntersection_Town12_Route12592_Weather11.tar.gz\": {\n        \"sha256\": \"c786a21327077f70a12fe8d6cd18a1438b568e38708d1af879bb94c51c0cbc88\",\n        \"size\": 386634927\n    },\n    \"BlockedIntersection_Town12_Route12594_Weather13.tar.gz\": {\n        \"sha256\": \"ab02db83dc5d13777652cc859b3a2d4e9f81f385311d624fc26a08671a4783b4\",\n        \"size\": 1098145790\n    },\n    \"BlockedIntersection_Town12_Route12595_Weather14.tar.gz\": {\n        \"sha256\": \"afbf64ede6c21de38671eb7efd7ebb9ad9f8c5e65598edab83966a4ae46a9692\",\n        \"size\": 245916745\n    },\n    \"BlockedIntersection_Town12_Route12596_Weather15.tar.gz\": {\n        \"sha256\": \"d8e27cb7d1f73d8ae3215502b5f35af6d642e25a0cbf0dc89466c8efbd8c41c2\",\n        \"size\": 443492319\n    },\n    \"BlockedIntersection_Town12_Route12597_Weather8.tar.gz\": {\n        \"sha256\": \"f58396c0c6f4b097a5fd0faa7d4bb96c24b384279bc3e141a159df9fb0fc689a\",\n        \"size\": 232906596\n    },\n    \"BlockedIntersection_Town12_Route12599_Weather18.tar.gz\": {\n        \"sha256\": \"83dee83d96f47f92a8ba6041c4a2dd519a091f04155cf42dfad940c9d468e73b\",\n        \"size\": 342315006\n    },\n    \"BlockedIntersection_Town12_Route12600_Weather19.tar.gz\": {\n        \"sha256\": \"da242ca9e52aaf0a26008b04171398a09a0c5e514e53ebfc894e5cc94d593ce1\",\n        \"size\": 389384925\n    },\n    \"BlockedIntersection_Town12_Route12601_Weather20.tar.gz\": {\n        \"sha256\": \"a6bac12f718b92f059fc433b89729a603410630c044b3ab777a35c1070fdba64\",\n        \"size\": 300894647\n    },\n    \"BlockedIntersection_Town12_Route12602_Weather21.tar.gz\": {\n        \"sha256\": \"28c63f25aed489f00552d1255115384637449d683800b28f8b1ff0a8a1dfcced\",\n        \"size\": 343907681\n    },\n    \"BlockedIntersection_Town12_Route12603_Weather22.tar.gz\": {\n        \"sha256\": \"486e89d4a3d54f62609cfc20046a3e981528ebdaf8f1de01efb7cc361051ce96\",\n        \"size\": 249681454\n    },\n    \"BlockedIntersection_Town12_Route12605_Weather23.tar.gz\": {\n        \"sha256\": \"ca84b964d3765b2408129e29ed723df234ad36d03adce58d0b5d167f7b727a80\",\n        \"size\": 358180324\n    },\n    \"BlockedIntersection_Town12_Route12606_Weather25.tar.gz\": {\n        \"sha256\": \"459f7ca252942969bedb7c9cd6c5e407ac8b6af9b4dcc4e3544473dd5eed9fcf\",\n        \"size\": 448042900\n    },\n    \"BlockedIntersection_Town12_Route12607_Weather0.tar.gz\": {\n        \"sha256\": \"c0bc9f37f6ac74addc6077b31001a606941f067d61c4bcc0dbed92686d425c32\",\n        \"size\": 303933616\n    },\n    \"BlockedIntersection_Town12_Route12608_Weather1.tar.gz\": {\n        \"sha256\": \"f1cb3c423f5e33b508ba88b49826aa1558e5662b146b7f68b25f79966407b972\",\n        \"size\": 365272112\n    },\n    \"BlockedIntersection_Town12_Route12609_Weather2.tar.gz\": {\n        \"sha256\": \"2e1f52c4e94a8e9760379bddc27f56cf68a6adb274d4fd29eba5f04735d39ab3\",\n        \"size\": 716173294\n    },\n    \"BlockedIntersection_Town12_Route12611_Weather3.tar.gz\": {\n        \"sha256\": \"76039269a264c1d041220924de4e611392d865f948cd48048a2a5cd32aa625b7\",\n        \"size\": 282950760\n    },\n    \"BlockedIntersection_Town12_Route12612_Weather5.tar.gz\": {\n        \"sha256\": \"3ed8a85d57271273c33b01a7847c726717c4e978ecf1da7bd7b10b676c18b4ba\",\n        \"size\": 324937918\n    },\n    \"BlockedIntersection_Town12_Route12613_Weather6.tar.gz\": {\n        \"sha256\": \"178a5055556040948dcd24836d94bd3dfc5b64d35123f62790299101c86c2526\",\n        \"size\": 553831967\n    },\n    \"BlockedIntersection_Town12_Route12614_Weather7.tar.gz\": {\n        \"sha256\": \"5cb8a13d34246189d94e64ce358c54bad9f54d1c08ec4b8021903e0b7f529d4b\",\n        \"size\": 955086260\n    },\n    \"BlockedIntersection_Town12_Route12615_Weather8.tar.gz\": {\n        \"sha256\": \"d9b8044e18f793a3fe55095b7a775c35ce5fe2dd32040367fe0dfeb02b8bb341\",\n        \"size\": 518353616\n    },\n    \"BlockedIntersection_Town12_Route12617_Weather10.tar.gz\": {\n        \"sha256\": \"b51fb7fb6239c8b7fde7dc7d1a84562a8fe2689b553b5a51c209c6c85768573b\",\n        \"size\": 546877332\n    },\n    \"BlockedIntersection_Town12_Route12618_Weather11.tar.gz\": {\n        \"sha256\": \"0346c5be75cc517549019cf9a38977f8518af2aa56e26b77dfc29648efc30274\",\n        \"size\": 371037039\n    },\n    \"BlockedIntersection_Town12_Route12619_Weather12.tar.gz\": {\n        \"sha256\": \"8245a4395ec3668456e90c314773a22854871f67289c77841ebc51915e8b4e68\",\n        \"size\": 308884671\n    },\n    \"BlockedIntersection_Town12_Route12621_Weather14.tar.gz\": {\n        \"sha256\": \"a46fe2de8b915a1215e6dd450c08326f27cf5c0c4cb17173ed8e0ced45a1eaac\",\n        \"size\": 320181516\n    },\n    \"BlockedIntersection_Town12_Route12622_Weather15.tar.gz\": {\n        \"sha256\": \"7b242ac8ca653f73f77a298bb5d914eeafe3c61814d4d3559898e9a0f5adbdb7\",\n        \"size\": 448949507\n    },\n    \"BlockedIntersection_Town12_Route12623_Weather8.tar.gz\": {\n        \"sha256\": \"f8d09247d1f23a83d4465639d006496573a5bd33f6f8269e9b9969260685b30c\",\n        \"size\": 420355457\n    },\n    \"BlockedIntersection_Town12_Route12624_Weather9.tar.gz\": {\n        \"sha256\": \"66095853719599cc1ad2986801c3ae3e6e3078a8c2e034ac95cf98c193edca2f\",\n        \"size\": 365771318\n    },\n    \"BlockedIntersection_Town12_Route12625_Weather18.tar.gz\": {\n        \"sha256\": \"38a71350a7030602063ffaa592bc0a7416e99f2c8d52f522b812cd226da817a3\",\n        \"size\": 171416094\n    },\n    \"BlockedIntersection_Town12_Route12626_Weather19.tar.gz\": {\n        \"sha256\": \"1188e8656b20a86c62d57aa6d775e7b4642075de9e60cbc7630e6df8589c0b06\",\n        \"size\": 760622087\n    },\n    \"BlockedIntersection_Town12_Route12627_Weather20.tar.gz\": {\n        \"sha256\": \"aa84a98579818103fb4164509cdaa9ac153144ed6fb5703914b54f3b02b4029e\",\n        \"size\": 765939181\n    },\n    \"BlockedIntersection_Town12_Route12628_Weather21.tar.gz\": {\n        \"sha256\": \"29a2abd445df44317df395892f6dd4891b3ea4c0773c5ffdb844d7dfb2fb93f9\",\n        \"size\": 646828820\n    },\n    \"BlockedIntersection_Town12_Route12629_Weather22.tar.gz\": {\n        \"sha256\": \"7f67f1a57adb3fef8c4f1ede20281c2d5d0a0abc4139173681233f0df3c582c1\",\n        \"size\": 277424620\n    },\n    \"BlockedIntersection_Town12_Route12630_Weather23.tar.gz\": {\n        \"sha256\": \"024195ce789c30198632066cc6c46a2bf5b57c4a9d593337fe427e8f8deb4ef3\",\n        \"size\": 849626273\n    },\n    \"BlockedIntersection_Town12_Route12632_Weather25.tar.gz\": {\n        \"sha256\": \"2563e4ed1da60826c150b3e082151a4541845705c708bd8935136b480e3d1233\",\n        \"size\": 217054001\n    },\n    \"BlockedIntersection_Town12_Route12633_Weather0.tar.gz\": {\n        \"sha256\": \"65a140cb759560b55734aece06ade389043f2b04b93782464c9e865680e391cd\",\n        \"size\": 490713310\n    },\n    \"BlockedIntersection_Town12_Route12634_Weather1.tar.gz\": {\n        \"sha256\": \"70e9b69e1d90ff332dbf15360ce2c7ad0182410efba0ec54a2cb96923bf881fd\",\n        \"size\": 311103437\n    },\n    \"BlockedIntersection_Town12_Route12636_Weather3.tar.gz\": {\n        \"sha256\": \"d5615e765a48baf53c35638f45be7d63c40fee8fea8770021984fc5861a3ae95\",\n        \"size\": 386305937\n    },\n    \"BlockedIntersection_Town12_Route12637_Weather3.tar.gz\": {\n        \"sha256\": \"980b6e09b89e79cd47e68dcab14ddd09f83c6b8160631b0f1afb41ccc7c7deb2\",\n        \"size\": 371664696\n    },\n    \"BlockedIntersection_Town12_Route12638_Weather5.tar.gz\": {\n        \"sha256\": \"3505923b292c85328c0459bab935015d14cec5e70c3da235780d5fdbc4e35638\",\n        \"size\": 248060341\n    },\n    \"BlockedIntersection_Town12_Route12639_Weather6.tar.gz\": {\n        \"sha256\": \"fabb7d14eed4862f11b8dd732cfa9ce047a2208b66ef8f509111df439853cb80\",\n        \"size\": 587274013\n    },\n    \"BlockedIntersection_Town12_Route12640_Weather7.tar.gz\": {\n        \"sha256\": \"d517306b3f366e5b84469626291a37a91a9271f848212e247645b70ecb2d5afc\",\n        \"size\": 322024570\n    },\n    \"BlockedIntersection_Town12_Route12641_Weather8.tar.gz\": {\n        \"sha256\": \"57dc0b75b3963b8e4fd0bc54f903dda0807721f7059f6159c916317195660d18\",\n        \"size\": 256524227\n    },\n    \"BlockedIntersection_Town12_Route12644_Weather11.tar.gz\": {\n        \"sha256\": \"b46ec96db8018018253229c6b5e9f2c3556a48f7fe6cb73b1845b38b9bbee694\",\n        \"size\": 274748503\n    },\n    \"BlockedIntersection_Town12_Route12646_Weather13.tar.gz\": {\n        \"sha256\": \"4a3921dda1ebc2fa4b30dde1c5f1d0a15ca5ece779e865ed80c7a0e561918084\",\n        \"size\": 324174258\n    },\n    \"BlockedIntersection_Town12_Route12647_Weather14.tar.gz\": {\n        \"sha256\": \"fee543bd15a5e2e5336e02fa310dbf77802bc3f4c02813a9304729f6d17eddbd\",\n        \"size\": 224318026\n    },\n    \"BlockedIntersection_Town12_Route12648_Weather15.tar.gz\": {\n        \"sha256\": \"2228937bdba0615ac5d692655bb5f382cf9f10bc207abd01601e717fdd90302b\",\n        \"size\": 285350493\n    },\n    \"BlockedIntersection_Town12_Route12649_Weather8.tar.gz\": {\n        \"sha256\": \"b41b52a6ef85e881cace5eaa5bff1a832ca5ad21b686dbdf96141d64ea41a935\",\n        \"size\": 340019655\n    },\n    \"BlockedIntersection_Town12_Route12650_Weather9.tar.gz\": {\n        \"sha256\": \"8f67b538a0e8c599e90672670e04d5221468b0e20bfe976fe04f9e082f5e88da\",\n        \"size\": 274399209\n    },\n    \"BlockedIntersection_Town12_Route12651_Weather18.tar.gz\": {\n        \"sha256\": \"bec6676b1cffc15d12147c58d76b505f4c52af78b252a3034507fc93a6a9f44a\",\n        \"size\": 497175648\n    },\n    \"BlockedIntersection_Town12_Route12653_Weather20.tar.gz\": {\n        \"sha256\": \"27543f458f9f80247b594f4467472e21f551921afed28cdd8e5fe8064053989f\",\n        \"size\": 594233396\n    },\n    \"BlockedIntersection_Town12_Route12655_Weather22.tar.gz\": {\n        \"sha256\": \"3e16ba6a376e8291b6a7af8b8a732aff0d266f260f5613a8c818f5bd448946c6\",\n        \"size\": 260407272\n    },\n    \"BlockedIntersection_Town12_Route12656_Weather23.tar.gz\": {\n        \"sha256\": \"5048a7c33da607555473170fd9fa364b4abf68d7e1ac0ab3a64e2bfb09833293\",\n        \"size\": 363552190\n    },\n    \"BlockedIntersection_Town12_Route12657_Weather23.tar.gz\": {\n        \"sha256\": \"d1378f456b9dad5fa74e9b296a776976420d6f9feef33364f0487d7cfe229827\",\n        \"size\": 294914393\n    },\n    \"BlockedIntersection_Town12_Route12658_Weather25.tar.gz\": {\n        \"sha256\": \"b26bbb7588a55784eb860dba0e722b6201d77e977be0372ef0a682c530d6ab5c\",\n        \"size\": 271539257\n    },\n    \"BlockedIntersection_Town12_Route12660_Weather1.tar.gz\": {\n        \"sha256\": \"ead35ba95d4016393e5c280ac1916f25e5e84c0685c4876c0727c733a447f500\",\n        \"size\": 626499668\n    },\n    \"BlockedIntersection_Town12_Route12661_Weather2.tar.gz\": {\n        \"sha256\": \"adce89ed22f5b4df70c4de287f8effb92985074a3f58d46174ec705b4906c60e\",\n        \"size\": 729206044\n    },\n    \"BlockedIntersection_Town12_Route12663_Weather3.tar.gz\": {\n        \"sha256\": \"8a0b8b4946ea3b2364f29060efe6d7847a8a71625db0a0f5406a3359bf656bac\",\n        \"size\": 277567351\n    },\n    \"BlockedIntersection_Town12_Route12664_Weather5.tar.gz\": {\n        \"sha256\": \"2c2aadaf378af82922fbd80bbba6f244b3bea2e786dbc4fc26f9f82843d92773\",\n        \"size\": 403310304\n    },\n    \"BlockedIntersection_Town12_Route12665_Weather6.tar.gz\": {\n        \"sha256\": \"c0657b3b0b90be53a0e56e9efb00f109adcc8ecf1494cea219620c1b3b7973af\",\n        \"size\": 574754180\n    },\n    \"BlockedIntersection_Town12_Route12666_Weather7.tar.gz\": {\n        \"sha256\": \"7dc735fdd6fc85b61183c7b9663c015a4dc869c88eb4d883cc8b2e10e4f9e536\",\n        \"size\": 594547172\n    },\n    \"BlockedIntersection_Town12_Route12667_Weather8.tar.gz\": {\n        \"sha256\": \"ac5465468485501dc636b1049ae33c46c5187d52cf979564b77975c2c254d75d\",\n        \"size\": 223481369\n    },\n    \"BlockedIntersection_Town12_Route12668_Weather9.tar.gz\": {\n        \"sha256\": \"476c36f9e3b85d0dedf45cb96e9a9cf4a263de8988cdce1a5dc01159bcafcb82\",\n        \"size\": 241485265\n    },\n    \"BlockedIntersection_Town12_Route12669_Weather10.tar.gz\": {\n        \"sha256\": \"881a10b5804c0d13028b976ceedc43ee4f574a82b3ab5d7faed36683d103b13f\",\n        \"size\": 351684231\n    },\n    \"BlockedIntersection_Town12_Route12672_Weather13.tar.gz\": {\n        \"sha256\": \"f1a14fba1e03b299996cd6b15c5474109d5afd24ac2499e84e5c7df1eb76ed4e\",\n        \"size\": 309678630\n    },\n    \"BlockedIntersection_Town12_Route12673_Weather14.tar.gz\": {\n        \"sha256\": \"11dcf9a67fc691caf3268d0cd3466831527cc7cbb0c668c9fa438fff10a5015f\",\n        \"size\": 434743787\n    },\n    \"BlockedIntersection_Town12_Route12675_Weather8.tar.gz\": {\n        \"sha256\": \"5aed6b2b28ab1e1a08981351faa1d2204719e2950f901bcc8ece8c421cb458c1\",\n        \"size\": 325813223\n    },\n    \"BlockedIntersection_Town12_Route12686_Weather1.tar.gz\": {\n        \"sha256\": \"62786b08d3f2e04029e046a12d99105759525502e05bc9b2a4add6eae335ffc7\",\n        \"size\": 261165258\n    },\n    \"BlockedIntersection_Town12_Route12749_Weather12.tar.gz\": {\n        \"sha256\": \"cb102000ac22b281aacbc1e0205c4337ca9a3c24e525779cdb219079838b9a4b\",\n        \"size\": 276755634\n    },\n    \"BlockedIntersection_Town12_Route12774_Weather11.tar.gz\": {\n        \"sha256\": \"f03816019a684f26764665ba8009af7b1ac30b92277ecb3baf1f12be827b5453\",\n        \"size\": 243076164\n    },\n    \"BlockedIntersection_Town12_Route12787_Weather23.tar.gz\": {\n        \"sha256\": \"55043e6bd25aac6efa947fded0fa6ffdd7679235fb5d277f81fefe978b1ee3ac\",\n        \"size\": 224230503\n    },\n    \"BlockedIntersection_Town12_Route12788_Weather25.tar.gz\": {\n        \"sha256\": \"38d91518f9aecab694a69c3939bf949b1a819887669c7407a599a446102aae97\",\n        \"size\": 311804572\n    },\n    \"BlockedIntersection_Town12_Route12803_Weather14.tar.gz\": {\n        \"sha256\": \"9411053813972bbdeb6c03b094db00fe3ab237ab68cd36737bc8913623c01d84\",\n        \"size\": 361509792\n    },\n    \"BlockedIntersection_Town12_Route12825_Weather10.tar.gz\": {\n        \"sha256\": \"96fe6bafb330470b077ca5916c2432d52752aa1e6018f0b2a9482c9807b61837\",\n        \"size\": 664156014\n    },\n    \"BlockedIntersection_Town12_Route12829_Weather14.tar.gz\": {\n        \"sha256\": \"7d63e2d1ffabfe8d86489f1ca20ed93499f37a105b2dc0b8eaa088656bbf544b\",\n        \"size\": 431971636\n    },\n    \"BlockedIntersection_Town12_Route12836_Weather21.tar.gz\": {\n        \"sha256\": \"a8a322ea1d41961afff575c3607c1cf366f5375f76f17ea3779b41fbc8bcecba\",\n        \"size\": 303916411\n    },\n    \"BlockedIntersection_Town12_Route12837_Weather22.tar.gz\": {\n        \"sha256\": \"dc99c62ab2785d9ea56231faf0a17f90ffd91f1036ed1caae2baadf9fa042dd9\",\n        \"size\": 512513145\n    },\n    \"BlockedIntersection_Town12_Route12838_Weather23.tar.gz\": {\n        \"sha256\": \"bb5b5b46389ad42c265d23d832edd67d4b518016c517d94fa7133104bc496036\",\n        \"size\": 294956718\n    },\n    \"BlockedIntersection_Town12_Route12839_Weather23.tar.gz\": {\n        \"sha256\": \"6d594a266e4cd570cb93d86245f7412023de709cedfe43f08e68e9c4a226989c\",\n        \"size\": 718050622\n    },\n    \"BlockedIntersection_Town12_Route12845_Weather3.tar.gz\": {\n        \"sha256\": \"1acc0e63ebf833f0c5b49b11119f68a7902a5b81166db429ef18b5eee9109786\",\n        \"size\": 329211551\n    },\n    \"BlockedIntersection_Town12_Route12873_Weather6.tar.gz\": {\n        \"sha256\": \"d67ab94f37219ddced6c0290b16373ed42a29485c853300e0326eecb62daca79\",\n        \"size\": 295087468\n    },\n    \"BlockedIntersection_Town12_Route12880_Weather13.tar.gz\": {\n        \"sha256\": \"1a3bf8db2b1fa0194dd444d7b177342835c08912f689539cc1f8bf92d0cb49c3\",\n        \"size\": 323377732\n    },\n    \"BlockedIntersection_Town12_Route12883_Weather8.tar.gz\": {\n        \"sha256\": \"39a3d232799d5866c7a76707f3640163bb028be3b129792264157fa848c10d05\",\n        \"size\": 345733501\n    },\n    \"BlockedIntersection_Town12_Route12919_Weather0.tar.gz\": {\n        \"sha256\": \"798a2e53b1c31eb68a94033c9f3f7ab0a31cb200316dfea7845b07c0e0ab7733\",\n        \"size\": 297454067\n    },\n    \"BlockedIntersection_Town12_Route12941_Weather22.tar.gz\": {\n        \"sha256\": \"35d093243a65b63cc419c2a3e9b3b31ba876838e967e0902384e6b816cc6dc12\",\n        \"size\": 232655679\n    },\n    \"BlockedIntersection_Town12_Route12943_Weather23.tar.gz\": {\n        \"sha256\": \"5e5419f353a54a5d75f8d6d9615716406cb07a2b971d376356a431f3177f0fd8\",\n        \"size\": 448265675\n    },\n    \"BlockedIntersection_Town12_Route12944_Weather25.tar.gz\": {\n        \"sha256\": \"4743be06df5dd9addded660b41fe664f0e4942be5931da01f03e853737e302e1\",\n        \"size\": 192625909\n    },\n    \"BlockedIntersection_Town12_Route12959_Weather14.tar.gz\": {\n        \"sha256\": \"8081297128dd30b9803efef5dc98e9a987034754dbf119ce89a9e00e735106f7\",\n        \"size\": 470673675\n    },\n    \"BlockedIntersection_Town12_Route12968_Weather23.tar.gz\": {\n        \"sha256\": \"c02b3b482e0fac8e525d45fb42f05b233051cdb956bb176b76dac50642f54311\",\n        \"size\": 643330061\n    },\n    \"BlockedIntersection_Town12_Route12970_Weather25.tar.gz\": {\n        \"sha256\": \"36c6f066f174bf67be3a2746ad452769be1e7d959b0af21bdf4fbd69ed1a6edd\",\n        \"size\": 506254756\n    },\n    \"BlockedIntersection_Town12_Route12977_Weather6.tar.gz\": {\n        \"sha256\": \"67fde7a17d848f47d8f90ba040df7825aec8795f7f32732595ec15d772e6fbc9\",\n        \"size\": 287437892\n    },\n    \"BlockedIntersection_Town12_Route12985_Weather14.tar.gz\": {\n        \"sha256\": \"aeb63b9ffa1f89135a2df1d7e794bb12477f6be9b4b6f2f3adff8ed2cff29523\",\n        \"size\": 426067891\n    },\n    \"BlockedIntersection_Town12_Route12988_Weather9.tar.gz\": {\n        \"sha256\": \"01ab9125bb7971816096062ba72fb1fd219aa26effb6ccd454c4781078fea04d\",\n        \"size\": 260551644\n    },\n    \"BlockedIntersection_Town12_Route12991_Weather20.tar.gz\": {\n        \"sha256\": \"03c527629985d844fe94307ac5b97a2467e769e5f3bd65a65e9a2972cfa82319\",\n        \"size\": 248687985\n    },\n    \"BlockedIntersection_Town12_Route13002_Weather5.tar.gz\": {\n        \"sha256\": \"33f784b6037ef1ed8015811b6e6b6e4adbb7c13a30efabda4a36db3d6054c3ce\",\n        \"size\": 452338611\n    },\n    \"BlockedIntersection_Town12_Route13009_Weather12.tar.gz\": {\n        \"sha256\": \"6168807201f75aefbfdc4f61e2bebd04f915ede044c3d9e9510babf088b94a46\",\n        \"size\": 265581769\n    },\n    \"BlockedIntersection_Town12_Route13015_Weather18.tar.gz\": {\n        \"sha256\": \"b6aa42e11977ffe12561346e980480709fbae798e47d28e3f501a8558240773d\",\n        \"size\": 829185545\n    },\n    \"BlockedIntersection_Town12_Route13016_Weather19.tar.gz\": {\n        \"sha256\": \"15dc41584f8332d729a9e4c28cad743fa5e99b1f28dae9424b031956b9f3d19f\",\n        \"size\": 638088351\n    },\n    \"BlockedIntersection_Town12_Route13020_Weather23.tar.gz\": {\n        \"sha256\": \"7cbc4a611e83e72ebff99b0bf82af82ae8b9cc048d9ce1f798af42882b7af37a\",\n        \"size\": 514133125\n    },\n    \"BlockedIntersection_Town12_Route13038_Weather15.tar.gz\": {\n        \"sha256\": \"72ec4ee99877b19c000f082b69b6fd5bddd0487acb293c890fc7b08de0268497\",\n        \"size\": 422437792\n    },\n    \"BlockedIntersection_Town12_Route13076_Weather1.tar.gz\": {\n        \"sha256\": \"acc92c3961b06e045d501e36cd2b4749da0f78aefe353b4b65230413ee3d9f15\",\n        \"size\": 363606794\n    },\n    \"BlockedIntersection_Town12_Route13079_Weather3.tar.gz\": {\n        \"sha256\": \"a51a77f70ac46f4ffa066ca6b31c6d8260978ccf8b468714ebc1f67478806de0\",\n        \"size\": 455989063\n    },\n    \"BlockedIntersection_Town12_Route13083_Weather8.tar.gz\": {\n        \"sha256\": \"692eca1882117287c2334452ee08726fc1d6e783b20f7738eb638efa3e1e0d19\",\n        \"size\": 414253192\n    },\n    \"BlockedIntersection_Town12_Route13112_Weather11.tar.gz\": {\n        \"sha256\": \"b454da0003985892a41518507e77f301d1ad565c4de2e9d801d335000fc8888d\",\n        \"size\": 252561967\n    },\n    \"BlockedIntersection_Town12_Route13129_Weather2.tar.gz\": {\n        \"sha256\": \"c13c2d50ccb5073ba1a63eedf378c0e75c7dcf0600fba6e016a0b7c43564edf5\",\n        \"size\": 327750114\n    },\n    \"BlockedIntersection_Town12_Route13154_Weather1.tar.gz\": {\n        \"sha256\": \"2c453aca5fe6563b59d6371b141438eda01f39495ab783bf5ff1eff12bfb9f82\",\n        \"size\": 355181536\n    },\n    \"BlockedIntersection_Town12_Route13158_Weather5.tar.gz\": {\n        \"sha256\": \"a82457b8625d8d762e572cf9058cb22687e45dcb0b49a7751de6729caf0f906b\",\n        \"size\": 403698836\n    },\n    \"BlockedIntersection_Town12_Route13170_Weather9.tar.gz\": {\n        \"sha256\": \"9e2b76f0df36e6f1602e066c4115289d3ac79af961c8dee5d51a116c889f8d03\",\n        \"size\": 150012675\n    },\n    \"BlockedIntersection_Town12_Route13193_Weather14.tar.gz\": {\n        \"sha256\": \"eb1154caa0bee9b161196d0f4f56532e7d97c3ea887e692969b39a4891fc4519\",\n        \"size\": 485631170\n    },\n    \"BlockedIntersection_Town12_Route13218_Weather13.tar.gz\": {\n        \"sha256\": \"e5be370f86ea305d4deebc60cd1b4105e52c21696595cd96855bf7fdbda39f0a\",\n        \"size\": 436206584\n    },\n    \"BlockedIntersection_Town12_Route13223_Weather18.tar.gz\": {\n        \"sha256\": \"803e8f60a7b3955bb1faf5081f13ab6a54cdd6f1626b2192e1ba9a48bf1f3e56\",\n        \"size\": 336331554\n    },\n    \"BlockedIntersection_Town12_Route13225_Weather20.tar.gz\": {\n        \"sha256\": \"5138ab1fe55bf520aab0c5212ef351a5983afdb6107271f146b09cfddb83a337\",\n        \"size\": 305000156\n    },\n    \"BlockedIntersection_Town12_Route13227_Weather22.tar.gz\": {\n        \"sha256\": \"2b72b03d625d21830636ee13ab89fa2beffcc14db109144557aff71361ccfc17\",\n        \"size\": 273928955\n    },\n    \"BlockedIntersection_Town12_Route13235_Weather3.tar.gz\": {\n        \"sha256\": \"51f725974954ebf3715c3bc85961edf94b9962806e5bd803373019302c4efce0\",\n        \"size\": 260486738\n    },\n    \"BlockedIntersection_Town12_Route13237_Weather6.tar.gz\": {\n        \"sha256\": \"4c68b2542561f93afd4715547db9400de6db1e30a81f38cbaa907674990f80b7\",\n        \"size\": 220565237\n    },\n    \"BlockedIntersection_Town12_Route13250_Weather19.tar.gz\": {\n        \"sha256\": \"29addf2f5259ff2b0d38f249079d1ac41e4acf38b67968815198e8cd1a469cdf\",\n        \"size\": 391502494\n    },\n    \"BlockedIntersection_Town12_Route13265_Weather8.tar.gz\": {\n        \"sha256\": \"fb67e07452cca42ecb6c304c470feb0274e2d5774bcf6e9b3e3e627c9341be29\",\n        \"size\": 225315374\n    },\n    \"BlockedIntersection_Town12_Route13273_Weather8.tar.gz\": {\n        \"sha256\": \"eb4aad24604840db7488b71e57b5041c24502ddc938e46b90be7c1283ae24888\",\n        \"size\": 508846656\n    },\n    \"BlockedIntersection_Town12_Route13274_Weather9.tar.gz\": {\n        \"sha256\": \"8c2f7becc171fbc1b4e2940996b022aabe570ea4ba5fac8c21c41f80b1c28838\",\n        \"size\": 408438935\n    },\n    \"BlockedIntersection_Town12_Route13297_Weather14.tar.gz\": {\n        \"sha256\": \"ed96638ce6f48f0bb471c9675e2d808b38f77c9e8df976c75fccb19e6360639a\",\n        \"size\": 548054584\n    },\n    \"BlockedIntersection_Town12_Route13298_Weather15.tar.gz\": {\n        \"sha256\": \"85de9532b71527bc50659e0bade1b7c6a91ea66fbe1db81bd0a88d4cb9c23624\",\n        \"size\": 572195881\n    },\n    \"BlockedIntersection_Town12_Route13310_Weather1.tar.gz\": {\n        \"sha256\": \"6e73c7ae7341f66831302788f58fa7f1940d9faf69975c6f1e915a72a302cf87\",\n        \"size\": 373339971\n    },\n    \"BlockedIntersection_Town12_Route13324_Weather15.tar.gz\": {\n        \"sha256\": \"16e2d584f2970e237a9fd22116e04526436c9ef967c5e8c8e1a6e40eb6b79df0\",\n        \"size\": 318218531\n    },\n    \"BlockedIntersection_Town12_Route13328_Weather19.tar.gz\": {\n        \"sha256\": \"039f12549820218ff119c48664a7ed9b36926b1aeb96d6a87d887c1437f74df4\",\n        \"size\": 305981062\n    },\n    \"BlockedIntersection_Town12_Route13331_Weather22.tar.gz\": {\n        \"sha256\": \"85c316a65dda9497b2fb57c4bb7f779f924ae73ae631c3a81b8467b0d89e8b3a\",\n        \"size\": 1372167904\n    },\n    \"BlockedIntersection_Town12_Route13344_Weather9.tar.gz\": {\n        \"sha256\": \"c9176beb7e5647ea059e0b5bfe3b784b186de934fbb93e08d1ab1f090bbdca8b\",\n        \"size\": 451706966\n    },\n    \"BlockedIntersection_Town12_Route13349_Weather14.tar.gz\": {\n        \"sha256\": \"48bbf605695981ef99a26e683112a275ea427d5ec13467a2639776f5f4986592\",\n        \"size\": 803744784\n    },\n    \"BlockedIntersection_Town12_Route13350_Weather15.tar.gz\": {\n        \"sha256\": \"394181ce9d5b5f60a11abdf494e7651f6594bd3da6ea7d57df85c9467fc5e039\",\n        \"size\": 234257571\n    },\n    \"BlockedIntersection_Town12_Route13351_Weather8.tar.gz\": {\n        \"sha256\": \"de63a9ad5afbcda6ef613bad2d08f75a83ffd878cc9252b2891725248de36c24\",\n        \"size\": 460051358\n    },\n    \"BlockedIntersection_Town12_Route13361_Weather0.tar.gz\": {\n        \"sha256\": \"c161bae7c9ac9b088bb3680c2f44ec081d139e44feb9c08b1b046ce9764cba57\",\n        \"size\": 542322622\n    },\n    \"BlockedIntersection_Town12_Route13370_Weather9.tar.gz\": {\n        \"sha256\": \"b15e8826626af4b065f8b702c8e7e582e8bbeaf1a6479678dd2abad50874f44f\",\n        \"size\": 462931490\n    },\n    \"BlockedIntersection_Town12_Route13392_Weather5.tar.gz\": {\n        \"sha256\": \"4e1cf613798bfb97d13c8b488a663356060e683cc0ae4a0866feb6b136b0e773\",\n        \"size\": 245439158\n    },\n    \"BlockedIntersection_Town12_Route13395_Weather8.tar.gz\": {\n        \"sha256\": \"81e3bdf90ef5ec2cc15923e108ae2ba0c2e43fb1badb3edb49ec8c721a25ecb4\",\n        \"size\": 228339025\n    },\n    \"BlockedIntersection_Town12_Route13398_Weather11.tar.gz\": {\n        \"sha256\": \"c19a9b97ae9017ec0cbb46b46c8254c801b2b6f9ec9744b03beaaf37fee02907\",\n        \"size\": 330575542\n    },\n    \"BlockedIntersection_Town12_Route13430_Weather9.tar.gz\": {\n        \"sha256\": \"84ac8c40b4aeb99ea6bfc28416a1ed03a11c8d6ff0433836d28ed67729ffe124\",\n        \"size\": 516612858\n    },\n    \"BlockedIntersection_Town12_Route2204_Weather14.tar.gz\": {\n        \"sha256\": \"1c2222fee71024e5933963c9dc7fcde9d397b1954e271d2477d37bfcf1d23c55\",\n        \"size\": 314731787\n    },\n    \"BlockedIntersection_Town12_Route2205_Weather15.tar.gz\": {\n        \"sha256\": \"370ffa6341e4fd402d6a6d6de7363883275f6d7a78ae2dbae822d3f1b13d787c\",\n        \"size\": 296511284\n    },\n    \"BlockedIntersection_Town12_Route2206_Weather8.tar.gz\": {\n        \"sha256\": \"82dae80dd805c25aac191849bfb8718273f4bd79b919f62f7f28f5da680ea012\",\n        \"size\": 184457025\n    },\n    \"BlockedIntersection_Town12_Route2208_Weather18.tar.gz\": {\n        \"sha256\": \"2f65fbc388c7976c6d86d6a1311935706de06cde905d9bc4494a04e78824f1a7\",\n        \"size\": 366779485\n    },\n    \"BlockedIntersection_Town12_Route2209_Weather19.tar.gz\": {\n        \"sha256\": \"58805ea7316babb7cfb4d6f34a861ef654cf6008fc497357ed609ce9bc6fa634\",\n        \"size\": 258542255\n    },\n    \"BlockedIntersection_Town12_Route2212_Weather22.tar.gz\": {\n        \"sha256\": \"4e4404c179b2bb36e262b424f40949f7e8473d3ac67e855e916b5e22420f4197\",\n        \"size\": 258860933\n    },\n    \"BlockedIntersection_Town12_Route2213_Weather23.tar.gz\": {\n        \"sha256\": \"64b1399281faf359414ebdfb8d1399c56885811d192394c1b44eba77bc6d4d65\",\n        \"size\": 322685176\n    },\n    \"BlockedIntersection_Town12_Route2215_Weather25.tar.gz\": {\n        \"sha256\": \"09cc92b3052eff312734dfaae22aeae4f7b35277d4757e49f0d4e68a5e9f431e\",\n        \"size\": 540095410\n    },\n    \"BlockedIntersection_Town12_Route2216_Weather0.tar.gz\": {\n        \"sha256\": \"56288779d2cf8fbc447d6d314a09cddf02758751b2ea04206ddf70728232151c\",\n        \"size\": 425937731\n    },\n    \"BlockedIntersection_Town12_Route2217_Weather1.tar.gz\": {\n        \"sha256\": \"fc15f34ccf8346024494bc48b49859721d8951a28449ea2b8c560dfeef8afc0c\",\n        \"size\": 437247928\n    },\n    \"BlockedIntersection_Town12_Route2218_Weather2.tar.gz\": {\n        \"sha256\": \"c5cc43aa611e051c15c13fa7a1c2c9efaf4fab25225333125fc2fd8368a4c154\",\n        \"size\": 440023103\n    },\n    \"BlockedIntersection_Town12_Route2219_Weather3.tar.gz\": {\n        \"sha256\": \"38412720318db4da738b3c71d8a16832083f29d470383e1a23dec4c0267fae5d\",\n        \"size\": 513430152\n    },\n    \"BlockedIntersection_Town12_Route2220_Weather3.tar.gz\": {\n        \"sha256\": \"b6116ec4082fd1e7c80efa6a4c2f2f48e304a36a48437d57f2ac94e171ec72bf\",\n        \"size\": 349794128\n    },\n    \"BlockedIntersection_Town12_Route2221_Weather5.tar.gz\": {\n        \"sha256\": \"1f19be49a5d315a586d22f96f2208d0b5abe970fd1af0d8d6351a219c57cffc9\",\n        \"size\": 367368364\n    },\n    \"BlockedIntersection_Town12_Route2223_Weather7.tar.gz\": {\n        \"sha256\": \"bae4616a38247ed386e90fddfdc78987d4b4d3dfd10b62dc1c51e8952f09f66e\",\n        \"size\": 325963037\n    },\n    \"BlockedIntersection_Town12_Route2984_Weather14.tar.gz\": {\n        \"sha256\": \"65982f05fef8eef364303ccf8bae807e71d1e739ba9d36f2839f3cb0b983c322\",\n        \"size\": 361535185\n    },\n    \"BlockedIntersection_Town12_Route2985_Weather15.tar.gz\": {\n        \"sha256\": \"c22132180fb71dfc9281380fcc8ed06b4f7e7fe36da7b0fbadc9dbead822ea3e\",\n        \"size\": 316397923\n    },\n    \"BlockedIntersection_Town12_Route2986_Weather8.tar.gz\": {\n        \"sha256\": \"8d8a4b398a43d0c3b24141cf15545466749db1304b5977ed59452901fdae9245\",\n        \"size\": 213346419\n    },\n    \"BlockedIntersection_Town12_Route2987_Weather9.tar.gz\": {\n        \"sha256\": \"950ba113a3dd92c7aa815d1c574cbfb0f15c7ff12677a1bebede92694020d0a1\",\n        \"size\": 289900520\n    },\n    \"BlockedIntersection_Town12_Route2988_Weather18.tar.gz\": {\n        \"sha256\": \"498797dea004f15e0c60ed033005e784db76d87dc3a03028164be16eb506ea3f\",\n        \"size\": 296559633\n    },\n    \"BlockedIntersection_Town12_Route2989_Weather19.tar.gz\": {\n        \"sha256\": \"5308a7362ea92fbfd3369e369ddce652ad60ca3f74ccdf64ebe467e7d42a70b1\",\n        \"size\": 245992555\n    },\n    \"BlockedIntersection_Town12_Route2990_Weather20.tar.gz\": {\n        \"sha256\": \"0b93d86458bb9152d0ac1cfb98204b267d24585ab2a008f17e6b9fe6b8370241\",\n        \"size\": 562530032\n    },\n    \"BlockedIntersection_Town12_Route2992_Weather22.tar.gz\": {\n        \"sha256\": \"db2b1f9a7c968ba53b3b006442f03284a942b9d48db7a430055614e1d6e753d3\",\n        \"size\": 600791705\n    },\n    \"BlockedIntersection_Town12_Route2993_Weather23.tar.gz\": {\n        \"sha256\": \"366008efaf1587439f4bde8cf8cd0fd345431b819c719a661e9554703243d8f0\",\n        \"size\": 702502242\n    },\n    \"BlockedIntersection_Town12_Route2996_Weather0.tar.gz\": {\n        \"sha256\": \"08f88717c8fffc8f1c0948eaa3fe4ec54035f154b8410eae18477c0b0eca67d5\",\n        \"size\": 337182464\n    },\n    \"BlockedIntersection_Town12_Route2997_Weather1.tar.gz\": {\n        \"sha256\": \"74a77c9f061633e0ed8d3bac8eebd4cb5c410b75cb96c1ebe7fd85a449e42eea\",\n        \"size\": 331756680\n    },\n    \"BlockedIntersection_Town12_Route2999_Weather3.tar.gz\": {\n        \"sha256\": \"d5822f676d65ba3588255a808f8a0cb11fb6791d867e7055573bbbdad728c0d6\",\n        \"size\": 305535253\n    },\n    \"BlockedIntersection_Town12_Route3000_Weather3.tar.gz\": {\n        \"sha256\": \"6fdb1bffc74e3120384ec34c13e588c0531746dd462d13e87171d832ddfc93de\",\n        \"size\": 235115831\n    },\n    \"BlockedIntersection_Town12_Route3001_Weather5.tar.gz\": {\n        \"sha256\": \"457edefe84d8b22ed07343b141aa656ee500acd95b0c7c474807cbb8e457d282\",\n        \"size\": 334276886\n    },\n    \"BlockedIntersection_Town12_Route3002_Weather6.tar.gz\": {\n        \"sha256\": \"ef422a3c6db9721d9869dff9a77812ffc74b7298ab2e1d65cfd654acff22c129\",\n        \"size\": 377406944\n    },\n    \"BlockedIntersection_Town12_Route3003_Weather7.tar.gz\": {\n        \"sha256\": \"a4a5e6890b47431b46499ed656f1f13b03b074185d6f02d3eb477fc4a3117917\",\n        \"size\": 433829246\n    },\n    \"BlockedIntersection_Town13_Route3763_Weather14.tar.gz\": {\n        \"sha256\": \"9cf8f476feca5b379eeb8a6364401122e0c90cad25413ab7c77793dbf85e7f83\",\n        \"size\": 152379586\n    },\n    \"BlockedIntersection_Town13_Route3764_Weather15.tar.gz\": {\n        \"sha256\": \"4d65ed6b77e61398164eb5fe08e02911c0cbe77e9b3ef500a8937edb29332128\",\n        \"size\": 274482247\n    },\n    \"BlockedIntersection_Town13_Route3765_Weather8.tar.gz\": {\n        \"sha256\": \"29318d459a3723508fbf91f0ce178aa056825341827106da511603cd9c57d20d\",\n        \"size\": 253388762\n    },\n    \"BlockedIntersection_Town13_Route3766_Weather9.tar.gz\": {\n        \"sha256\": \"5baad48337dc2d15280d0184203e8e171b77cd4da267d1100ed6b96c4e749f6a\",\n        \"size\": 204044463\n    },\n    \"BlockedIntersection_Town13_Route3767_Weather18.tar.gz\": {\n        \"sha256\": \"f71a3a2d0812a0e7a7fa14f864711eda0da54b09520bc13aa8492dc42d7de22a\",\n        \"size\": 240377702\n    },\n    \"BlockedIntersection_Town13_Route3768_Weather19.tar.gz\": {\n        \"sha256\": \"b4a9ec05b16855af97d0245d5f16e958fae215b9d1d61a9f276a842e905a227b\",\n        \"size\": 570129403\n    },\n    \"BlockedIntersection_Town13_Route3769_Weather20.tar.gz\": {\n        \"sha256\": \"6a614a50ae69476daddec826a6b0819da815a2772b16adfadf4300031a6c3e6b\",\n        \"size\": 179097200\n    },\n    \"BlockedIntersection_Town13_Route3770_Weather21.tar.gz\": {\n        \"sha256\": \"30e9ece64dc3eb6021b45b6fdcf071cc2c6458116ac795484d58ff053ffce59a\",\n        \"size\": 184822202\n    },\n    \"BlockedIntersection_Town13_Route3771_Weather22.tar.gz\": {\n        \"sha256\": \"6b2df92413d7e660441e5020dfa08ae0bc262c3aeb5c9207d53599038ca642d4\",\n        \"size\": 291561529\n    },\n    \"BlockedIntersection_Town13_Route3775_Weather0.tar.gz\": {\n        \"sha256\": \"20ad2d305132c320074183ea771c96044cbf1ce893625003a62e7204a9c3387a\",\n        \"size\": 257301132\n    },\n    \"BlockedIntersection_Town13_Route3776_Weather1.tar.gz\": {\n        \"sha256\": \"37604b8ebd4728cbd23cd9cad9dce25ac8683902d879d14b3f6bc1600fc364aa\",\n        \"size\": 311797587\n    },\n    \"BlockedIntersection_Town13_Route3777_Weather2.tar.gz\": {\n        \"sha256\": \"31a3b8247d5f9ce88cc7d5f33693525842182c6581b1ffeb1ac7ab09de211e6d\",\n        \"size\": 652908072\n    },\n    \"BlockedIntersection_Town13_Route3778_Weather3.tar.gz\": {\n        \"sha256\": \"17d6e9f19b34696b73ff74356fd30586d839ac38cc3dd3ec6b63da587d040389\",\n        \"size\": 216427163\n    },\n    \"BlockedIntersection_Town13_Route3779_Weather3.tar.gz\": {\n        \"sha256\": \"06867aa9d9de95db597fc10efd4c69ce479a4945e91d1ce5952f331ccaca6780\",\n        \"size\": 351160917\n    },\n    \"BlockedIntersection_Town13_Route3780_Weather5.tar.gz\": {\n        \"sha256\": \"9e5599469ffdb1001360b8cc9e1efa3ea027039f8b7d45c529ab2f4b4f810f75\",\n        \"size\": 239999683\n    },\n    \"BlockedIntersection_Town15_Route27288_Weather10.tar.gz\": {\n        \"sha256\": \"4c15cebbd7607b4817822236a91bccc434b25a15d2b893f65a9691c7e8a39e24\",\n        \"size\": 1909963315\n    },\n    \"BlockedIntersection_Town15_Route27293_Weather15.tar.gz\": {\n        \"sha256\": \"3d2a47217bd91f9957e035a33e01b49b2bc2478a263eebeea2043a043f85d733\",\n        \"size\": 557980848\n    },\n    \"BlockedIntersection_Town15_Route27298_Weather22.tar.gz\": {\n        \"sha256\": \"c4995b2078b1e1c2c8e2b7c89b7ab17694cdab7513c43e0c861a742613b6491b\",\n        \"size\": 872299552\n    },\n    \"BlockedIntersection_Town15_Route27308_Weather7.tar.gz\": {\n        \"sha256\": \"3eca1e5e6c830b9a4830e34a557717b093690ae2110923ee22b28916e99e7e44\",\n        \"size\": 1057034503\n    },\n    \"BlockedIntersection_Town15_Route27313_Weather12.tar.gz\": {\n        \"sha256\": \"6ba9fe6eff89f118f32d3e19407e39ce57aeb34b5aa8723a5cd5f34774ff62f4\",\n        \"size\": 875895624\n    },\n    \"BlockedIntersection_Town15_Route27318_Weather19.tar.gz\": {\n        \"sha256\": \"f97b5b8f9f29cee836a2ec97954885a652e6936624e0bd9db48fc438863e06e6\",\n        \"size\": 1233483877\n    },\n    \"BlockedIntersection_Town15_Route27323_Weather25.tar.gz\": {\n        \"sha256\": \"67e76d96b99114e8fb4d8ed5bd46d6ef261119950e23467684a1698af5ae9d4f\",\n        \"size\": 1374432379\n    },\n    \"BlockedIntersection_Town15_Route27328_Weather3.tar.gz\": {\n        \"sha256\": \"026b92832c38b8414529b92faaa41b4c15425a1f994428777289941ae01c7c12\",\n        \"size\": 1679553103\n    },\n    \"BlockedIntersection_Town15_Route27333_Weather9.tar.gz\": {\n        \"sha256\": \"33caf968bf9a8fcb320836435760a2273139d19dfc0831b347013eb3a17776b3\",\n        \"size\": 1811840277\n    },\n    \"BlockedIntersection_Town15_Route27338_Weather14.tar.gz\": {\n        \"sha256\": \"92390104eb87999bec460cfbba3b92a1a507ce63d5f1eb2c67f7c16d4d965cfa\",\n        \"size\": 1170333331\n    },\n    \"BlockedIntersection_Town15_Route27343_Weather21.tar.gz\": {\n        \"sha256\": \"f8f8dd35c1fea0d00eeb48bff001fba5cd8d9856999a8f7a6eef2fd86faa81a5\",\n        \"size\": 1875385124\n    },\n    \"BlockedIntersection_Town15_Route27348_Weather0.tar.gz\": {\n        \"sha256\": \"c29bc50a950860053039d2b24bd231cb55b1d16e8668bc7d0af7615fc92c0227\",\n        \"size\": 1404772806\n    },\n    \"BlockedIntersection_Town15_Route27353_Weather6.tar.gz\": {\n        \"sha256\": \"18dd63ca5fc3eb271302cd73e4b578c265bd594fb1f8d835d314b19014f480cf\",\n        \"size\": 1348838455\n    },\n    \"BlockedIntersection_Town15_Route27358_Weather11.tar.gz\": {\n        \"sha256\": \"6a6d21054a004c595128746a91c3dd6842b02c146053ed04b1979134e2df615a\",\n        \"size\": 541664202\n    },\n    \"BlockedIntersection_Town15_Route27363_Weather18.tar.gz\": {\n        \"sha256\": \"e7241ca20804b43d4f97f25d9ceb3344a10791c608ffe2b2ceab3c9be8a5f097\",\n        \"size\": 1728494666\n    },\n    \"BlockedIntersection_Town15_Route27368_Weather23.tar.gz\": {\n        \"sha256\": \"993bdc366e391b64a0626fc94537a640f6b74f0cf19f77224a2c4aaa3eabc41b\",\n        \"size\": 1201125020\n    },\n    \"BlockedIntersection_Town15_Route27378_Weather8.tar.gz\": {\n        \"sha256\": \"05e95466379d653577e5fb21b788ddbcf4848383902d1d3708acc53c20359956\",\n        \"size\": 576377800\n    },\n    \"BlockedIntersection_Town15_Route27383_Weather13.tar.gz\": {\n        \"sha256\": \"21b731c55b8b659146cf3d4a5c8f01cc490a13c149a6ae4037a9ecaabb9a6d0b\",\n        \"size\": 1151696384\n    },\n    \"ConstructionObstacleTwoWays_Town11_Route25403_Weather11.tar.gz\": {\n        \"sha256\": \"e456ebc71365331756a159fce52cb2a8b9b40db95fcb5c53b5612ec7aa718874\",\n        \"size\": 118941160\n    },\n    \"ConstructionObstacleTwoWays_Town11_Route25424_Weather9.tar.gz\": {\n        \"sha256\": \"9330cdbb40a111ef6b78e745a0498add1dda12b2271bdd4fbafeb2de8398060f\",\n        \"size\": 51467927\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1825_Weather25.tar.gz\": {\n        \"sha256\": \"f6586292bb76d4047ce1631b24dc908496a211e79c9396e8e3055435b73c7e44\",\n        \"size\": 232351388\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1827_Weather1.tar.gz\": {\n        \"sha256\": \"110a4e9d03bc7188a5b27e731f58d6209d26c214bab24b16df1204236b2f943f\",\n        \"size\": 307871630\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1833_Weather7.tar.gz\": {\n        \"sha256\": \"c53125495c96c4e07ec2e0f66bf653b54f6a83b3815c781849deee71019b5865\",\n        \"size\": 336721653\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1834_Weather8.tar.gz\": {\n        \"sha256\": \"6ad75772a7cabd9a89c2feb9541a14c4d9e2b03f6438eae88944d87b099a52d7\",\n        \"size\": 297794413\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route1843_Weather9.tar.gz\": {\n        \"sha256\": \"8195aaed5b22a0ccb2afe992332e06580afe7100378cf1464aea451cd5407002\",\n        \"size\": 348459164\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20875_Weather22.tar.gz\": {\n        \"sha256\": \"8d0e0d2c4d632018efd183a6473127c14a83ceb536c8d930707a04f503402862\",\n        \"size\": 285674740\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20876_Weather23.tar.gz\": {\n        \"sha256\": \"2a058b80cf20d134079ce5b343f776435cb0597cc39d7122d89d15b6898a0955\",\n        \"size\": 264306927\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20877_Weather23.tar.gz\": {\n        \"sha256\": \"882648e35606939fab9ed3d3facccbeb1873740e46cadf8069a0b48cd68567e8\",\n        \"size\": 234946636\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20878_Weather25.tar.gz\": {\n        \"sha256\": \"c74e88879bde9f6451d3a277bce43a59ee203e10b3a07fc3e766001fdba37b03\",\n        \"size\": 234517274\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20879_Weather0.tar.gz\": {\n        \"sha256\": \"ef3b40719b8d3ab9809f23826e1821501490e8a33fa346e156612ba3031afc73\",\n        \"size\": 331566509\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20882_Weather3.tar.gz\": {\n        \"sha256\": \"eea621d30cb6ea0d2f3598c628a3ced673f1e21fc789290a237af38f594b5027\",\n        \"size\": 338593035\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20884_Weather5.tar.gz\": {\n        \"sha256\": \"f4300e64561465336aa0b993555fa167997867dcf8a7827d80ecd38ed7e939a0\",\n        \"size\": 305573697\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20885_Weather6.tar.gz\": {\n        \"sha256\": \"b70816a5744511acc2a208a73b681be7f02c6f8119efe9bcd214c6e56ea7d03d\",\n        \"size\": 295587465\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20887_Weather8.tar.gz\": {\n        \"sha256\": \"5673445da768eef361c3d49eb8b3a1582aa3b14f727365c840fde731d0f2eaa0\",\n        \"size\": 282991052\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20889_Weather10.tar.gz\": {\n        \"sha256\": \"f5c5472461a33092466b585497dae6b5d4af14cc7deb8a291e6ea26ea59f25eb\",\n        \"size\": 308078770\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20892_Weather13.tar.gz\": {\n        \"sha256\": \"cbcb2f184ff480e9253dab33d573f90259e73b2054485d317db291e380c69fbf\",\n        \"size\": 243127758\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20893_Weather14.tar.gz\": {\n        \"sha256\": \"a91d9531f2fc45a3f38c40e3b31b870d9a86b362efa7f5611e5d7256cbc81156\",\n        \"size\": 265543568\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20895_Weather8.tar.gz\": {\n        \"sha256\": \"1b2ab156159557ef9a4dc2d9d21b1893f73d59f88e907b6298eb6fa1abf372ec\",\n        \"size\": 299581860\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20897_Weather18.tar.gz\": {\n        \"sha256\": \"14ca8d4b4dc4dbefd75fbafd23dade01381d1bc47de02222ff00bee726b87c50\",\n        \"size\": 337427587\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20899_Weather20.tar.gz\": {\n        \"sha256\": \"776804b3ea17b05e9448368e4bfe6cb2071793278bead69c5e43177196c1d47f\",\n        \"size\": 300309759\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20900_Weather21.tar.gz\": {\n        \"sha256\": \"578eb814a1aaa74645dac0576d03db56829d34eaf13ba800a1890fa5b6136af0\",\n        \"size\": 245361569\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20904_Weather25.tar.gz\": {\n        \"sha256\": \"1a5c31dbc8e8190cf0461459a1b08c2855c49818087dbc4ee667a356b6f0e0a5\",\n        \"size\": 225775560\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20907_Weather2.tar.gz\": {\n        \"sha256\": \"42ecf9ff7b0bdfbda9671b1c7258b7b144bc22f7f2dd9737ccc99a7e0fc36858\",\n        \"size\": 311551467\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20908_Weather3.tar.gz\": {\n        \"sha256\": \"36473adf3051178e2f33fe164f117a26980fcbb0df04402b9cb9e83545656d94\",\n        \"size\": 302956533\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20912_Weather7.tar.gz\": {\n        \"sha256\": \"2f829d4835edb803239c8d93d23c4ba3dc3759180d5af68ab1bfa1fe86b0d9d5\",\n        \"size\": 310791327\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20915_Weather10.tar.gz\": {\n        \"sha256\": \"ea69dd57ad238c15c5f4edcede0ec1500b584a7fb13e1864b8ca2d3ab162bdcb\",\n        \"size\": 285088482\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20917_Weather12.tar.gz\": {\n        \"sha256\": \"359eeb1ffda5689108824ba00fa91fe7a49673ea50d1f7a00a2fa13135e88104\",\n        \"size\": 234520266\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20920_Weather15.tar.gz\": {\n        \"sha256\": \"11e9b07e14b9f2f651d0983963f7c64f54607c6e967d7213a747f773c346dfaf\",\n        \"size\": 280421653\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20921_Weather8.tar.gz\": {\n        \"sha256\": \"c0e021a55da0bfa2dd0da51c2c44c9f89b858870aebce60db54df822ba5f57c1\",\n        \"size\": 296664578\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20922_Weather9.tar.gz\": {\n        \"sha256\": \"a0d7bc0e6dd37d9e7656e4ebcd909118809370ac6e7c4c45d8d462f14ba7de21\",\n        \"size\": 238367379\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20929_Weather23.tar.gz\": {\n        \"sha256\": \"2f6e8c76db40a13e32aae4b6c3937844a7d1402e1f908ce56ac51ef0be0e0b85\",\n        \"size\": 257024114\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route20932_Weather1.tar.gz\": {\n        \"sha256\": \"d9ef374a54cd3fd87811e9f3766b288d7b0ba70af250ec42aa49cb347594cfd4\",\n        \"size\": 341891988\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route2606_Weather0.tar.gz\": {\n        \"sha256\": \"b99ef90fc90f395c5d934882de76bc42052e2d861c582a8a0968d08f267395d7\",\n        \"size\": 327945705\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route2608_Weather2.tar.gz\": {\n        \"sha256\": \"7e4c1c8398fa0efb70f88a9abef73f6950a6a4533e334a6a942c9fd445b88133\",\n        \"size\": 357240826\n    },\n    \"ConstructionObstacleTwoWays_Town12_Route2610_Weather3.tar.gz\": {\n        \"sha256\": \"5f651b01d889a3218acb55de0b4eccf57e85516797e58ec923b887c3aa4ff1e9\",\n        \"size\": 312547976\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29354_Weather18.tar.gz\": {\n        \"sha256\": \"f94774cc8c07fbd0a0955755b01fc8b47a58657d835d05baf0a99569bfb28139\",\n        \"size\": 428278815\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29464_Weather11.tar.gz\": {\n        \"sha256\": \"8bc18e678aa7f2646b1580bd47577e0c9f7ff19fef6017feb1c83a46af67546e\",\n        \"size\": 291354635\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29465_Weather12.tar.gz\": {\n        \"sha256\": \"ede6c5509b082e54657cf313c09bc03fb536b4c8328662df2ec7958254a715ec\",\n        \"size\": 342003683\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29473_Weather22.tar.gz\": {\n        \"sha256\": \"137b11fec6b37efccf67c36f0c8016bcaf7b5334e94c040b083a3f1a85eb2a5f\",\n        \"size\": 342809190\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29523_Weather0.tar.gz\": {\n        \"sha256\": \"58b20dcc48c317b062d1b1eeba99cd8b2f7956752a3985dae94391da925c0ed4\",\n        \"size\": 443191894\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29638_Weather0.tar.gz\": {\n        \"sha256\": \"482c74f834980c924e0fb05f8a0ac65a17c6eada31bda7499d3a9fd7c9b51bca\",\n        \"size\": 392486991\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29642_Weather5.tar.gz\": {\n        \"sha256\": \"bc48227b2e144e1ec53de7b41f98a4525d9be4555384577820a8fee76688522b\",\n        \"size\": 428965413\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29671_Weather11.tar.gz\": {\n        \"sha256\": \"fbffc60ad0bffafabaae3530b0100e9785286a31bf5dc03fb6aadc052606c70c\",\n        \"size\": 294992356\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29876_Weather9.tar.gz\": {\n        \"sha256\": \"01ddbf8211a2a9e1b9b0a602ee0f85d8ebbfb16952b4b0f537f329e2af0ad59b\",\n        \"size\": 264579352\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29917_Weather3.tar.gz\": {\n        \"sha256\": \"0c6ba6223c0e8c656a630e5c10a82dc1fbde7fd346e3348f6c7df51f12e4f523\",\n        \"size\": 391497931\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29936_Weather26.tar.gz\": {\n        \"sha256\": \"5db3a1380f17b30ea74a630e597922478eb468367d1c4e8cc3dd32e43c8d690f\",\n        \"size\": 388534438\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30103_Weather6.tar.gz\": {\n        \"sha256\": \"1c3ddca86f6c9c3e5203384aab403b08698540cba61a0f1fedca4893c3291af3\",\n        \"size\": 396316981\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30135_Weather15.tar.gz\": {\n        \"sha256\": \"a60f828f96ce6598c5523b9e079cff63245a468815e0fc3667b5d4452faaceab\",\n        \"size\": 490222172\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30171_Weather5.tar.gz\": {\n        \"sha256\": \"cc8c24d9466266cb20596e265a090d9b90acbc6dd3a17bef31d2453c1604e7ea\",\n        \"size\": 374459930\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30207_Weather20.tar.gz\": {\n        \"sha256\": \"e18df0ccc99600a7b6ec044eaef14f137473dad25213505cd5e224e87570603f\",\n        \"size\": 364279103\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30209_Weather22.tar.gz\": {\n        \"sha256\": \"210bc6fc1eed44237b5f88394da03b000bc9fc0e6f365f140bf4f272c041a1d5\",\n        \"size\": 585382599\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30284_Weather2.tar.gz\": {\n        \"sha256\": \"a67f373c5c19b5878e32a3678dc9f621aeeb99a4280af697ac01f3cf93ea9df6\",\n        \"size\": 403050836\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route3386_Weather1.tar.gz\": {\n        \"sha256\": \"fd666b3d3c5d32ebc6015aca69c31d9c304765b956b1817ce1820f4bd2f40247\",\n        \"size\": 486845537\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route3391_Weather6.tar.gz\": {\n        \"sha256\": \"26064dc07349c3c3b2e60fefc23a34ffdc322a3c1ac6ed23f477996fc53c5c38\",\n        \"size\": 412459107\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route540_Weather12.tar.gz\": {\n        \"sha256\": \"ddb5427ab8593bd2b939459e4e4ffdeeff6144bb995b066f87f68af5de9ba2b2\",\n        \"size\": 252424247\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route591_Weather19.tar.gz\": {\n        \"sha256\": \"8d09a8af461ef26372b8b6bf488501806f193f197ab0f5270ec67b30168cdd07\",\n        \"size\": 372011403\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route593_Weather21.tar.gz\": {\n        \"sha256\": \"ef719194ab67f248d65fcc98c26c6fa1350d0fad290339637eaaafe2ace57c60\",\n        \"size\": 391126042\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route800_Weather21.tar.gz\": {\n        \"sha256\": \"483c45ea5f1f5408240bd9f8327ae9397e9731e9b18a7859fb5c171eac7a386c\",\n        \"size\": 320038228\n    },\n    \"ConstructionObstacle_Town03_Route24746_Weather23.tar.gz\": {\n        \"sha256\": \"9f7acb2837e0952ed2a540d112086c7ea94c271419be975a90b0e84765c492ce\",\n        \"size\": 246150507\n    },\n    \"ConstructionObstacle_Town04_Route24765_Weather19.tar.gz\": {\n        \"sha256\": \"0977c7db38209d02950a8bcbc116e0af038b0c06536a6d7ccb4e72230199a93d\",\n        \"size\": 231151030\n    },\n    \"ConstructionObstacle_Town04_Route24785_Weather14.tar.gz\": {\n        \"sha256\": \"0ad3310b4d977882ef7292e7366a3ffe015ec42ce573167dc90102cac0939ee0\",\n        \"size\": 220613169\n    },\n    \"ConstructionObstacle_Town04_Route24795_Weather0.tar.gz\": {\n        \"sha256\": \"292c24ea1c00766f888c83c5dc55aa744435ac469999b41b65dab03b05a703c2\",\n        \"size\": 264688169\n    },\n    \"ConstructionObstacle_Town04_Route24815_Weather23.tar.gz\": {\n        \"sha256\": \"99f96dee5c47f1ebc385af8d5a86bdd0dab8f0c0c2d2aa8564b173a975bf92a4\",\n        \"size\": 195294012\n    },\n    \"ConstructionObstacle_Town06_Route24367_Weather10.tar.gz\": {\n        \"sha256\": \"8667617c39a65c82c96fe03c2bcb8869a4787599828cd77aefabefce9414647f\",\n        \"size\": 230595926\n    },\n    \"ConstructionObstacle_Town06_Route24377_Weather22.tar.gz\": {\n        \"sha256\": \"90defa786dbc233cbf8898cf2ff214a078bea9bc71ac7622fd59fbcd41066f98\",\n        \"size\": 212047729\n    },\n    \"ConstructionObstacle_Town12_Route1726_Weather3.tar.gz\": {\n        \"sha256\": \"af63105ef8a1378739f83bb7f598eeb55b8865161e6d21f538b34292c94208ef\",\n        \"size\": 414928651\n    },\n    \"ConstructionObstacle_Town12_Route1727_Weather5.tar.gz\": {\n        \"sha256\": \"f5f98c1819aba550e8ecf82b0297f2e6d003b7c790f679ae618f4609975f9df7\",\n        \"size\": 487022063\n    },\n    \"ConstructionObstacle_Town12_Route1728_Weather6.tar.gz\": {\n        \"sha256\": \"2954d69a85a98bed25859a7bae27bdfdeeab84953cb96718154f5c35afd03a41\",\n        \"size\": 466398313\n    },\n    \"ConstructionObstacle_Town12_Route1730_Weather8.tar.gz\": {\n        \"sha256\": \"276967a5f889919a376d0cca380a5b72dcfce9c5f17ef871cb089b387cbf8c83\",\n        \"size\": 305239513\n    },\n    \"ConstructionObstacle_Town12_Route1731_Weather9.tar.gz\": {\n        \"sha256\": \"f3175253446958ac73a63f2c8b1743ac6474d461cc3a1cc59bc5b96ee5cb2dc8\",\n        \"size\": 316133297\n    },\n    \"ConstructionObstacle_Town12_Route1733_Weather11.tar.gz\": {\n        \"sha256\": \"65463cbc6c6db3152b94721bada1249f8572e77ba6786cee42fbdf87cc8d2f00\",\n        \"size\": 129404318\n    },\n    \"ConstructionObstacle_Town12_Route1735_Weather13.tar.gz\": {\n        \"sha256\": \"58723734131134f59cd6c660b08e552caf4609b6cd7f877042a1c04fa0fb0a3a\",\n        \"size\": 393431297\n    },\n    \"ConstructionObstacle_Town12_Route1736_Weather14.tar.gz\": {\n        \"sha256\": \"df5c36371798a6670caed39fd5f11d52391c9d8a888c141b16a52ab29fb5a20d\",\n        \"size\": 150628866\n    },\n    \"ConstructionObstacle_Town12_Route1737_Weather15.tar.gz\": {\n        \"sha256\": \"478bd7be960b654d1c5205b0f67cfe99122ebfd4d51903ba45dc0e5eef8c4579\",\n        \"size\": 169404051\n    },\n    \"ConstructionObstacle_Town12_Route1738_Weather8.tar.gz\": {\n        \"sha256\": \"b002ec2cf1ae99de5c4d194eade208d8b7581cf5fbd4c604b31bd2f2cd39fd06\",\n        \"size\": 184639376\n    },\n    \"ConstructionObstacle_Town12_Route1739_Weather9.tar.gz\": {\n        \"sha256\": \"d386293c1501b454670ec00bcffac22862cc0638cd19e5d96a2c366e08be960c\",\n        \"size\": 274261690\n    },\n    \"ConstructionObstacle_Town12_Route1740_Weather18.tar.gz\": {\n        \"sha256\": \"619a9cc86a52e4c55061d5f7747d154d0b53f896463600369becba113b9dd0dc\",\n        \"size\": 197017598\n    },\n    \"ConstructionObstacle_Town12_Route1741_Weather19.tar.gz\": {\n        \"sha256\": \"161aa2d87fd6adaedee53eeef0a345fcb33b5fcb9155bb64399571451b0d4a48\",\n        \"size\": 360844689\n    },\n    \"ConstructionObstacle_Town12_Route1742_Weather20.tar.gz\": {\n        \"sha256\": \"7919b3e45d86e071a0074ca158747651b290339bb49102e37794290504877d12\",\n        \"size\": 366932776\n    },\n    \"ConstructionObstacle_Town12_Route1743_Weather21.tar.gz\": {\n        \"sha256\": \"a6bed5fae787bda5c3c6218d92bb094f5095219e42c5f5784068fae31f3bf745\",\n        \"size\": 162436205\n    },\n    \"ConstructionObstacle_Town12_Route18373_Weather8.tar.gz\": {\n        \"sha256\": \"fa51499e4e41138762724d4ea0cdab81212dff1b236d29b0c11821db10f6fb2e\",\n        \"size\": 172555367\n    },\n    \"ConstructionObstacle_Town12_Route18374_Weather9.tar.gz\": {\n        \"sha256\": \"c0cccf4ea6da8afe5288a4ea9adeec42728e5a25f996fec95bd14003242b9dfb\",\n        \"size\": 421943367\n    },\n    \"ConstructionObstacle_Town12_Route18375_Weather18.tar.gz\": {\n        \"sha256\": \"95d53291b694fe1a4622d967a866608e0b4ba46071c356a9d11c4ccc6d3f4ece\",\n        \"size\": 187139965\n    },\n    \"ConstructionObstacle_Town12_Route18376_Weather19.tar.gz\": {\n        \"sha256\": \"819928527de4224917d4b6f1f439c9db29c4ef64640cc6a4a5866d219f2fc167\",\n        \"size\": 433798388\n    },\n    \"ConstructionObstacle_Town12_Route18377_Weather20.tar.gz\": {\n        \"sha256\": \"5f6d5bb7b7605c7f02d738d7efe11c5356619e47a24ac7e95bc8af0c16cbf362\",\n        \"size\": 454778078\n    },\n    \"ConstructionObstacle_Town12_Route18378_Weather21.tar.gz\": {\n        \"sha256\": \"2a96e0562bc4671010fb71278c3b8b67186bfad84c2c86fb4c0667b3e51fbdf7\",\n        \"size\": 459428619\n    },\n    \"ConstructionObstacle_Town12_Route18379_Weather22.tar.gz\": {\n        \"sha256\": \"e65f547923cdb62c4cda20bc2d61d041bf21b4618c1f40e45e640ccecd27e4b2\",\n        \"size\": 471598304\n    },\n    \"ConstructionObstacle_Town12_Route18380_Weather23.tar.gz\": {\n        \"sha256\": \"5c6c3aeb261f5c0eeba3a788eb4abefa335a545e25b57235e7fda18dbdea16a1\",\n        \"size\": 475919013\n    },\n    \"ConstructionObstacle_Town12_Route18381_Weather23.tar.gz\": {\n        \"sha256\": \"a50c0c20fe7e7434605bd6df96ab9ae5fae3c8d4f123e4be04be7d661a8741f2\",\n        \"size\": 446976678\n    },\n    \"ConstructionObstacle_Town12_Route18382_Weather25.tar.gz\": {\n        \"sha256\": \"9bafe4480f5570c7c1715ecf8de2b381ac92d93abdd65270e07f6362a6822a82\",\n        \"size\": 236743605\n    },\n    \"ConstructionObstacle_Town12_Route18384_Weather1.tar.gz\": {\n        \"sha256\": \"9bfa3498fe646b502817fa998886d55db42c87506e8bb12b993d09818b8a5f2c\",\n        \"size\": 306231975\n    },\n    \"ConstructionObstacle_Town12_Route18385_Weather2.tar.gz\": {\n        \"sha256\": \"60140fec6a3d839e30e07b2d27642067f4457d51e8fdeb695c53d00db78b66f4\",\n        \"size\": 328522933\n    },\n    \"ConstructionObstacle_Town12_Route18388_Weather5.tar.gz\": {\n        \"sha256\": \"c4941e939970f236aafb1de95c9745b79ae27d9c95aef6422bbec8e4216c9af1\",\n        \"size\": 329334211\n    },\n    \"ConstructionObstacle_Town12_Route18389_Weather6.tar.gz\": {\n        \"sha256\": \"6c0cfadd25410031256a2482452e9d5e78db6e5aa1c1b3fb5ec2fa5db258fe9e\",\n        \"size\": 376794672\n    },\n    \"ConstructionObstacle_Town12_Route18390_Weather7.tar.gz\": {\n        \"sha256\": \"fb8ea78dd2965a697d4408446abb7c9dfc9ea616646e859ed635803de7724614\",\n        \"size\": 402535662\n    },\n    \"ConstructionObstacle_Town12_Route18391_Weather8.tar.gz\": {\n        \"sha256\": \"6e903f81d4637453fbbdf4bcc0b1a78cf694e39dfe4dd3b89675140e5fe035cf\",\n        \"size\": 182055988\n    },\n    \"ConstructionObstacle_Town12_Route18392_Weather9.tar.gz\": {\n        \"sha256\": \"0c70012de39be9dc823df6c8efd42dd78b2804eb48dfceade082b7774424ffa4\",\n        \"size\": 279730178\n    },\n    \"ConstructionObstacle_Town12_Route18393_Weather10.tar.gz\": {\n        \"sha256\": \"7759d02cbdbe1d6f7be73017eb5cf8e389eef914d4999a76ea71efd74fc6ec26\",\n        \"size\": 240322021\n    },\n    \"ConstructionObstacle_Town12_Route18394_Weather11.tar.gz\": {\n        \"sha256\": \"42750675a5de7b386e031923263e18e6d24c07f52344953344e2e6642d03c97a\",\n        \"size\": 287340115\n    },\n    \"ConstructionObstacle_Town12_Route18396_Weather13.tar.gz\": {\n        \"sha256\": \"195263d40551e74a507aa0f0985d6a375d61f5db03cb7af84f832ea3c3142e95\",\n        \"size\": 296545775\n    },\n    \"ConstructionObstacle_Town12_Route18397_Weather14.tar.gz\": {\n        \"sha256\": \"c2afc22d4172acfbe15d1f4564d79b832c076bf0bf7a3f66c482eaf050df41d9\",\n        \"size\": 165663225\n    },\n    \"ConstructionObstacle_Town12_Route18398_Weather15.tar.gz\": {\n        \"sha256\": \"b0f3158bf388a1d8bb7bc746c347acddfc8b72a1283bf9d9d68e9003416d3729\",\n        \"size\": 183257203\n    },\n    \"ConstructionObstacle_Town12_Route18399_Weather8.tar.gz\": {\n        \"sha256\": \"c85551cdcb5620c4c3cc26461190cad508ebd1559865f1cbc580b3fcbff10abb\",\n        \"size\": 173500003\n    },\n    \"ConstructionObstacle_Town12_Route18400_Weather9.tar.gz\": {\n        \"sha256\": \"fb5ffbf5f0791c8cfa24b8cce35c45fd5fcaf59e6dae75257abc67edcf3860c1\",\n        \"size\": 134139413\n    },\n    \"ConstructionObstacle_Town12_Route18401_Weather18.tar.gz\": {\n        \"sha256\": \"887b09ef0c6236fa78fdfd7d434a4b030ac57a27445cae9995114bc32bf4a8fb\",\n        \"size\": 195463347\n    },\n    \"ConstructionObstacle_Town12_Route18402_Weather19.tar.gz\": {\n        \"sha256\": \"b3cbad3c0ca856936e2c9d6d08f7714756b56ef0d5e8a208044fb083a897de28\",\n        \"size\": 196787574\n    },\n    \"ConstructionObstacle_Town12_Route18404_Weather21.tar.gz\": {\n        \"sha256\": \"23edfcaebe815860c49c49eb3ddcd8ecca88a4c0e0049dde5ce0fc69e7239cca\",\n        \"size\": 405132018\n    },\n    \"ConstructionObstacle_Town12_Route18405_Weather22.tar.gz\": {\n        \"sha256\": \"b26a72a90c88957b2b2b340ccea2608f397abbda5fe4443dd8092fe5b985ad4f\",\n        \"size\": 316430471\n    },\n    \"ConstructionObstacle_Town12_Route18406_Weather23.tar.gz\": {\n        \"sha256\": \"9057c4ee3a82d3954491c4f85aa512d378624f8405e7ceecc9ac3bfdc690eab9\",\n        \"size\": 150410056\n    },\n    \"ConstructionObstacle_Town12_Route18407_Weather23.tar.gz\": {\n        \"sha256\": \"7b566ee10ae73df314f31f5b45371672c00c5824679ccd869d01371f9fb1126a\",\n        \"size\": 543791322\n    },\n    \"ConstructionObstacle_Town12_Route18408_Weather25.tar.gz\": {\n        \"sha256\": \"51047ae488cb81189bc4657c242e1533ff5c515573dd566466f28bf6a5fabb9a\",\n        \"size\": 146498640\n    },\n    \"ConstructionObstacle_Town12_Route18409_Weather0.tar.gz\": {\n        \"sha256\": \"38894845067c370aea37a80b377641da61c7b1b5145d8affd0228529245e575e\",\n        \"size\": 590460169\n    },\n    \"ConstructionObstacle_Town12_Route18410_Weather1.tar.gz\": {\n        \"sha256\": \"af3bf1e6a87593ca9859d5d270672b50efb2cb4faf25206a762c6fdd92919ebf\",\n        \"size\": 480841707\n    },\n    \"ConstructionObstacle_Town12_Route18411_Weather2.tar.gz\": {\n        \"sha256\": \"96147f2f04500f8190dc6f6dbc2bf97b0c8ee740e92354d10a2c4432f80aee1a\",\n        \"size\": 475319952\n    },\n    \"ConstructionObstacle_Town12_Route18412_Weather3.tar.gz\": {\n        \"sha256\": \"2e8fd525beacdb15b3ba906f41178c1a5900318adf4f04a67dc355999f7f56d5\",\n        \"size\": 405190091\n    },\n    \"ConstructionObstacle_Town12_Route18413_Weather3.tar.gz\": {\n        \"sha256\": \"4dde7c69af97b44bc3f6c7223f7fe886cf92bc71bc4a606785cbad9d8dbcfa0d\",\n        \"size\": 437114325\n    },\n    \"ConstructionObstacle_Town12_Route18414_Weather5.tar.gz\": {\n        \"sha256\": \"ec056d516bdd5c844b938a1efaf150ec9a3671d81b16d8f400a1ca0bc682279d\",\n        \"size\": 184319310\n    },\n    \"ConstructionObstacle_Town12_Route18415_Weather6.tar.gz\": {\n        \"sha256\": \"1fbc27c069c0a4ee4ab4200d0a3fe4f6bd7577bc5f5fee80baa1fa47f51b0c72\",\n        \"size\": 176000337\n    },\n    \"ConstructionObstacle_Town12_Route18416_Weather7.tar.gz\": {\n        \"sha256\": \"6c214a902f7bc5788f71a7341dcee60901cab91457a026b0c6b3f23b7c0577d4\",\n        \"size\": 199392328\n    },\n    \"ConstructionObstacle_Town12_Route18417_Weather8.tar.gz\": {\n        \"sha256\": \"caa8e71cc626e0c1c330726797690058fa7181b500f146d92da21a761198de65\",\n        \"size\": 171009764\n    },\n    \"ConstructionObstacle_Town12_Route18418_Weather9.tar.gz\": {\n        \"sha256\": \"cfa30bcb621eb96d6171f565ef0ac7cdbb75b7c276e53cb668d5612318ef7ff8\",\n        \"size\": 390058560\n    },\n    \"ConstructionObstacle_Town12_Route18419_Weather10.tar.gz\": {\n        \"sha256\": \"0a6320ed5010efb6ce8cb3fb2e449b52b18bcbac46e6213ae27f5ed36eacf554\",\n        \"size\": 370768292\n    },\n    \"ConstructionObstacle_Town12_Route18420_Weather11.tar.gz\": {\n        \"sha256\": \"eb70e04ece3b3783600af1e9e6f2c38ff7ee9ccbb53836e3f54000d5cb6b5a6f\",\n        \"size\": 374143042\n    },\n    \"ConstructionObstacle_Town12_Route18421_Weather12.tar.gz\": {\n        \"sha256\": \"8f7eb6ae20884987ae5047618806a53b1e28ec5104384e36d54df4e0f656877c\",\n        \"size\": 304514595\n    },\n    \"ConstructionObstacle_Town12_Route18422_Weather13.tar.gz\": {\n        \"sha256\": \"4d9f06d9d1a92eb1d53507f9103b29160b43b0c0101003548f2fe0351ef902c5\",\n        \"size\": 374052898\n    },\n    \"ConstructionObstacle_Town12_Route18423_Weather14.tar.gz\": {\n        \"sha256\": \"605d21a68e29e64658cf10dbbca7b8ed659faf6600ec49fd30deb25408a30238\",\n        \"size\": 403780186\n    },\n    \"ConstructionObstacle_Town12_Route18424_Weather15.tar.gz\": {\n        \"sha256\": \"24a351bab9d7b34b06e370d1c2199ce5c04bf4c0d7958d838f137ef5f9f8e698\",\n        \"size\": 399187567\n    },\n    \"ConstructionObstacle_Town12_Route18425_Weather8.tar.gz\": {\n        \"sha256\": \"f4861d4f3fb5946e2e9d76502eff1ef81f93e99aae1dc319a0130080bdb37f7a\",\n        \"size\": 420313727\n    },\n    \"ConstructionObstacle_Town12_Route18426_Weather9.tar.gz\": {\n        \"sha256\": \"2e6655f73318117b49e55d4afb4fedfdee7ec2ba6bf3ce84f7c603cfd26dc432\",\n        \"size\": 376340488\n    },\n    \"ConstructionObstacle_Town12_Route18427_Weather18.tar.gz\": {\n        \"sha256\": \"ab9103c762256c1b283f1681019a6cf9c72e73de1bfae79d91a0d0c8636e4919\",\n        \"size\": 412342909\n    },\n    \"ConstructionObstacle_Town12_Route18428_Weather19.tar.gz\": {\n        \"sha256\": \"7743b8d2bf1b85f798d65a0ae9c4bd6f3cd4f0e2ba31770a6f92357ffaa32b75\",\n        \"size\": 354434812\n    },\n    \"ConstructionObstacle_Town12_Route18429_Weather20.tar.gz\": {\n        \"sha256\": \"f436d7b9ca7235b4dd5330baf26835fd0ed2a870f1e00fbf775ace6d2fe18608\",\n        \"size\": 169590558\n    },\n    \"ConstructionObstacle_Town12_Route18430_Weather21.tar.gz\": {\n        \"sha256\": \"fe5b80b52dcecad65a66eab2c8aabf705d849b7442c6c8c5fd0e259c579fdb1a\",\n        \"size\": 162942133\n    },\n    \"ConstructionObstacle_Town12_Route18431_Weather22.tar.gz\": {\n        \"sha256\": \"f748b1d5cf9d147095bbda076b38180c5d86d073885a365c1ae39c8a180625ea\",\n        \"size\": 356800821\n    },\n    \"ConstructionObstacle_Town12_Route18432_Weather23.tar.gz\": {\n        \"sha256\": \"0283afbe1dfe0952d7860f9e0c2ccf83361f7125ab76cf452e96bdcadb39026a\",\n        \"size\": 328084991\n    },\n    \"ConstructionObstacle_Town12_Route18433_Weather23.tar.gz\": {\n        \"sha256\": \"9ab81541309e5085e17d1a248ae2528a03215e2d69bcaa54f0e27f688f1330d9\",\n        \"size\": 498266275\n    },\n    \"ConstructionObstacle_Town12_Route18434_Weather25.tar.gz\": {\n        \"sha256\": \"18e3183d6737fbb5ac288d0e18ff7352a6c649f944c5980ca6bf0e303053fb9c\",\n        \"size\": 169224677\n    },\n    \"ConstructionObstacle_Town12_Route18435_Weather0.tar.gz\": {\n        \"sha256\": \"9d4bd4cf4ceba68a5a82a3f49237b3fed7a8731ca541dad29876b2c07580213a\",\n        \"size\": 176806754\n    },\n    \"ConstructionObstacle_Town12_Route18436_Weather1.tar.gz\": {\n        \"sha256\": \"1723baf87ba0d0f27543b317fc555b492f57ffd05139c4834852a78fe5f30e51\",\n        \"size\": 411415029\n    },\n    \"ConstructionObstacle_Town12_Route18440_Weather5.tar.gz\": {\n        \"sha256\": \"be8f8b4437c9e542b3725450051013530d448dcbcbd2dfc71890917f7293ebe4\",\n        \"size\": 191921864\n    },\n    \"ConstructionObstacle_Town12_Route18441_Weather6.tar.gz\": {\n        \"sha256\": \"1c2466f003aecf86a0f7a2ab8fc1d4e58687cb22421854b5a932092a3f7578cc\",\n        \"size\": 164438434\n    },\n    \"ConstructionObstacle_Town12_Route18443_Weather8.tar.gz\": {\n        \"sha256\": \"c82441e6dd724ad6e169eb5d00e1d0268eb13659bbdc1e3e31ae8e206fe83b44\",\n        \"size\": 320033511\n    },\n    \"ConstructionObstacle_Town12_Route18444_Weather9.tar.gz\": {\n        \"sha256\": \"3135466b206b4deed0cdbc6f3ff68c2371d8247ec114b48be65cc20dcc9c7c75\",\n        \"size\": 255830964\n    },\n    \"ConstructionObstacle_Town12_Route18445_Weather10.tar.gz\": {\n        \"sha256\": \"aba6e88ea3a11c9b6befb693de09fdbd24a77062386b244dcf77781cd643d8a7\",\n        \"size\": 288020640\n    },\n    \"ConstructionObstacle_Town12_Route18446_Weather11.tar.gz\": {\n        \"sha256\": \"fd09492fb60c71dc4bbb1e0a8c0737a6d2102d52f2b0431ee918de135ab434ca\",\n        \"size\": 304072839\n    },\n    \"ConstructionObstacle_Town12_Route18447_Weather12.tar.gz\": {\n        \"sha256\": \"c3a113e2248e49556a9840228c9d67552b9a97c2db2cef8815a791d96dddef80\",\n        \"size\": 303887761\n    },\n    \"ConstructionObstacle_Town12_Route18448_Weather13.tar.gz\": {\n        \"sha256\": \"87c47f698f43aacfc896a52ea7ef9e35f90b6af77fb63236b3e3e46a42a21cb0\",\n        \"size\": 338925988\n    },\n    \"ConstructionObstacle_Town12_Route18449_Weather14.tar.gz\": {\n        \"sha256\": \"a198183c3404e105d71916cb4bbc981a7844098f7ae1b28deae682320c85772f\",\n        \"size\": 234115698\n    },\n    \"ConstructionObstacle_Town12_Route18450_Weather15.tar.gz\": {\n        \"sha256\": \"f7be2edc64610949857b64eb366e3c759b3c0d149715cbc5e3cf4f0bb58da742\",\n        \"size\": 328432766\n    },\n    \"ConstructionObstacle_Town12_Route18451_Weather8.tar.gz\": {\n        \"sha256\": \"9f017fa765599271528b889b9ab3d1e72cd75f53d5652f03dcd3b9d0d9728ba2\",\n        \"size\": 277834353\n    },\n    \"ConstructionObstacle_Town12_Route18452_Weather9.tar.gz\": {\n        \"sha256\": \"c1b5779c81f0bb8e205bc4d0939a4abe13e1fa20afc449b30282f369b44aa703\",\n        \"size\": 284795301\n    },\n    \"ConstructionObstacle_Town12_Route18454_Weather19.tar.gz\": {\n        \"sha256\": \"27a4acab21a38a4b29dbcad8314a093819837b5762467b26948614b8aefea34f\",\n        \"size\": 178197287\n    },\n    \"ConstructionObstacle_Town12_Route18455_Weather20.tar.gz\": {\n        \"sha256\": \"432114719efdf7d85aaaa420bde747b62336ab084e9600c800b5126dfe962117\",\n        \"size\": 172913754\n    },\n    \"ConstructionObstacle_Town12_Route18456_Weather21.tar.gz\": {\n        \"sha256\": \"f922e33aaae32eceddda70671d45e4dec0cfbe9514f34c1f740ef479d9ee334f\",\n        \"size\": 163548859\n    },\n    \"ConstructionObstacle_Town12_Route18457_Weather22.tar.gz\": {\n        \"sha256\": \"5838a2461e88cbc837383ea56df7145a5c51b167b3133bb20277e90ee1b6b365\",\n        \"size\": 393883393\n    },\n    \"ConstructionObstacle_Town12_Route18458_Weather23.tar.gz\": {\n        \"sha256\": \"d7a73992a0231ab7aa351b79e939b4648de18c7b5f0e41f62e2888061f895d52\",\n        \"size\": 395728224\n    },\n    \"ConstructionObstacle_Town12_Route18459_Weather23.tar.gz\": {\n        \"sha256\": \"746b8f5ad445e0b43ea92da4a1ac5e000f4b790f0acc03e946d29391efa2df4a\",\n        \"size\": 155911667\n    },\n    \"ConstructionObstacle_Town12_Route18460_Weather25.tar.gz\": {\n        \"sha256\": \"7e4d5d80bd1c001a7c1421db0161ff293cc1dcb47bce32ef46f0453dbf7a7976\",\n        \"size\": 132816163\n    },\n    \"ConstructionObstacle_Town12_Route18461_Weather0.tar.gz\": {\n        \"sha256\": \"7f04edb4bf6d829c9fe47bec762e9cb759c172d4d212788bc51f09b645ac7a2e\",\n        \"size\": 192587755\n    },\n    \"ConstructionObstacle_Town12_Route18462_Weather1.tar.gz\": {\n        \"sha256\": \"a3fd3f060fc8bcf6dc9b8afd6c5c83e026bc5373dc5609802eb8afa3bf7e2c42\",\n        \"size\": 195611184\n    },\n    \"ConstructionObstacle_Town12_Route18463_Weather2.tar.gz\": {\n        \"sha256\": \"728b46ac6c058a0779e4ebf7f1fd92d5d66bc6dfed179fae7e83e6c2eeab1d07\",\n        \"size\": 218181448\n    },\n    \"ConstructionObstacle_Town12_Route18464_Weather3.tar.gz\": {\n        \"sha256\": \"6563fd0aab3f9d7519c567a9295f3056a90903edb75cb70ee6e0c090af579e1d\",\n        \"size\": 182253596\n    },\n    \"ConstructionObstacle_Town12_Route18465_Weather3.tar.gz\": {\n        \"sha256\": \"818f1ff8c4b90da2c9c0ffb5008fcb4dfea5bcfbe905c7b5556a6167ee5a782a\",\n        \"size\": 189694507\n    },\n    \"ConstructionObstacle_Town12_Route18466_Weather5.tar.gz\": {\n        \"sha256\": \"ede5fadddf82788f0b2b4a3c2ba7a566eeaa96eb4c6b1b8982606dabd5f328db\",\n        \"size\": 195829434\n    },\n    \"ConstructionObstacle_Town12_Route18467_Weather6.tar.gz\": {\n        \"sha256\": \"e40b9b460d7b9408c9ca5921248bd1053113dbba62d9db613464e43150f624bb\",\n        \"size\": 165514284\n    },\n    \"ConstructionObstacle_Town12_Route18468_Weather7.tar.gz\": {\n        \"sha256\": \"c2a90ce38f98df5a8330273c81dfe04d306358b52a07aae6f930bce271bb6029\",\n        \"size\": 204588724\n    },\n    \"ConstructionObstacle_Town12_Route18469_Weather8.tar.gz\": {\n        \"sha256\": \"7d4d2ba9abb0fefb4222bf08d27a8f344dc7732c0c9cbdc34786dd96b9ee097b\",\n        \"size\": 180627337\n    },\n    \"ConstructionObstacle_Town12_Route18470_Weather9.tar.gz\": {\n        \"sha256\": \"ecba95ca2bd50a2c24d4389af5dbc771e4e037ca1b6c9a9badd2cbdbf6c3d6fa\",\n        \"size\": 140260758\n    },\n    \"ConstructionObstacle_Town12_Route18471_Weather10.tar.gz\": {\n        \"sha256\": \"f123b7d26b05c10647693b0943863029f2a610cb53b9ef29ca0f91a54524b63b\",\n        \"size\": 176247054\n    },\n    \"ConstructionObstacle_Town12_Route18472_Weather11.tar.gz\": {\n        \"sha256\": \"0cecc655aee3614e70bbdb9b89900caf4cfd7c817d370eb5a03f54d9d04cb403\",\n        \"size\": 135278000\n    },\n    \"ConstructionObstacle_Town12_Route18473_Weather12.tar.gz\": {\n        \"sha256\": \"8c2091df786b6085d23d5dccc1bbfb289599dfeadcf06aada3fb4bfef2ce4196\",\n        \"size\": 705002750\n    },\n    \"ConstructionObstacle_Town12_Route18474_Weather13.tar.gz\": {\n        \"sha256\": \"52df3b2ad755abb184d56f2ee85fbf1b384cb1c8e591469ad95285a2ff16724d\",\n        \"size\": 142788477\n    },\n    \"ConstructionObstacle_Town12_Route18475_Weather14.tar.gz\": {\n        \"sha256\": \"cc774b321cb59ce7b814a9835d15f42d1997abec38e3044aff8260aeb9ac1e89\",\n        \"size\": 162825798\n    },\n    \"ConstructionObstacle_Town12_Route18477_Weather8.tar.gz\": {\n        \"sha256\": \"fd152dec1fc85fadee13167403cb87b03de57134f0f8086a626aa06ef9cab476\",\n        \"size\": 181256427\n    },\n    \"ConstructionObstacle_Town12_Route18478_Weather9.tar.gz\": {\n        \"sha256\": \"b9a169e9810ae1fd2f11902cca6b09119cd39b6f2f3b5f7e55b2906d6525dba1\",\n        \"size\": 146178635\n    },\n    \"ConstructionObstacle_Town12_Route18479_Weather18.tar.gz\": {\n        \"sha256\": \"d755d90ea426ccd8aecb43391308bb81d609e9ef4173c050910a429f8e890e44\",\n        \"size\": 497825583\n    },\n    \"ConstructionObstacle_Town12_Route18480_Weather19.tar.gz\": {\n        \"sha256\": \"91bba43ef1b6c26404c4c2257f0cb88d1c973eaf60d3fbc94e970f24bd9f2b4f\",\n        \"size\": 413042021\n    },\n    \"ConstructionObstacle_Town12_Route18481_Weather20.tar.gz\": {\n        \"sha256\": \"60489f07b9fdf5af1be095dc56fc1734f7feae5b572e580fd400ea7e6ce0ddbf\",\n        \"size\": 403581000\n    },\n    \"ConstructionObstacle_Town12_Route18482_Weather21.tar.gz\": {\n        \"sha256\": \"5d91f0db40e02d21ef988b061bb68cfc8dda781cf0e2c18ec400f1bf746c6173\",\n        \"size\": 394006393\n    },\n    \"ConstructionObstacle_Town12_Route18483_Weather22.tar.gz\": {\n        \"sha256\": \"3d6a39e60cf64b90ded115bdfa1baeb7ce004dfb6228e5f949ffa2b180d405c9\",\n        \"size\": 414093151\n    },\n    \"ConstructionObstacle_Town12_Route18484_Weather23.tar.gz\": {\n        \"sha256\": \"3cc577ab8cc7f4d18e7ae7260ab0ee3d91375101d90afcf93e0429bee83a4f1a\",\n        \"size\": 348733006\n    },\n    \"ConstructionObstacle_Town12_Route18485_Weather23.tar.gz\": {\n        \"sha256\": \"d3963a21b2a65b4d2497722db5528155353f5285974b6398a9049171f32f4432\",\n        \"size\": 312624791\n    },\n    \"ConstructionObstacle_Town12_Route18486_Weather25.tar.gz\": {\n        \"sha256\": \"4fb4c551cbdcb0fef2332d6232e1cb5ac37534cf01d37106e9a8889e389fae08\",\n        \"size\": 142127637\n    },\n    \"ConstructionObstacle_Town12_Route18487_Weather0.tar.gz\": {\n        \"sha256\": \"37ae1f3ee943d64779a60a57185133b8a5d62cfd7d3802674826d584472c5c4f\",\n        \"size\": 188421158\n    },\n    \"ConstructionObstacle_Town12_Route18488_Weather1.tar.gz\": {\n        \"sha256\": \"51faf26608c4dbfcfdd5364c3296049a15a77d01def0149b7d66c833cdcc14a5\",\n        \"size\": 276684928\n    },\n    \"ConstructionObstacle_Town12_Route18489_Weather2.tar.gz\": {\n        \"sha256\": \"033396df126039882a341e17f48a77101dc417b14a8246e92ad3b0f747b580f3\",\n        \"size\": 199585100\n    },\n    \"ConstructionObstacle_Town12_Route18490_Weather3.tar.gz\": {\n        \"sha256\": \"c48654a3a7169e95acef9b9e2a3ebc50a62dc32693e433b7d10fb2951cf0a80f\",\n        \"size\": 402428622\n    },\n    \"ConstructionObstacle_Town12_Route18491_Weather3.tar.gz\": {\n        \"sha256\": \"1d1e910a6bc62259a86cd89d03c2f05607542d39d469c19ceffb4d1805aadb4a\",\n        \"size\": 435931151\n    },\n    \"ConstructionObstacle_Town12_Route18493_Weather6.tar.gz\": {\n        \"sha256\": \"d55f95a509e5d6bc601aa98a225f1cec01bcfc13ea2c74fcd44aef5624052e98\",\n        \"size\": 383074854\n    },\n    \"ConstructionObstacle_Town12_Route18496_Weather9.tar.gz\": {\n        \"sha256\": \"e3a4f784488e88e0ade13cf704c5354cd8f0b6231618adb065ef26a5e0276016\",\n        \"size\": 262549538\n    },\n    \"ConstructionObstacle_Town12_Route18499_Weather12.tar.gz\": {\n        \"sha256\": \"bfded5cbe37410574dbe053c9c21d410d9e8595efcda7cced3c41d91e6b52c6e\",\n        \"size\": 164650723\n    },\n    \"ConstructionObstacle_Town12_Route18500_Weather13.tar.gz\": {\n        \"sha256\": \"0ae620aab23e6cdcbeb74cefc0492e8ddd8b5370bdc3ac071f35752a961a8d4f\",\n        \"size\": 135494528\n    },\n    \"ConstructionObstacle_Town12_Route18501_Weather14.tar.gz\": {\n        \"sha256\": \"d652393738dbe92992c983daf5e881e4099742a1ded2419d81ec1387f2fb8f14\",\n        \"size\": 238795160\n    },\n    \"ConstructionObstacle_Town12_Route18502_Weather15.tar.gz\": {\n        \"sha256\": \"b68d6f0859f239df0cad99d798a69d48b456ce37f12115d988d97c9c7764e16e\",\n        \"size\": 182464353\n    },\n    \"ConstructionObstacle_Town12_Route18503_Weather8.tar.gz\": {\n        \"sha256\": \"a98556cdd169cf8203735c651e166f63964ef41e901e58e697630a236964a1bf\",\n        \"size\": 183030256\n    },\n    \"ConstructionObstacle_Town12_Route18504_Weather9.tar.gz\": {\n        \"sha256\": \"844a862ddb37667df4c4b451386342ef0761cf3c14a4108aa030d9de29df606f\",\n        \"size\": 156696402\n    },\n    \"ConstructionObstacle_Town12_Route18505_Weather18.tar.gz\": {\n        \"sha256\": \"4030595d4414786bda35655e174c492cae2486e370764c0ff530f891ff95a09c\",\n        \"size\": 505129012\n    },\n    \"ConstructionObstacle_Town12_Route18506_Weather19.tar.gz\": {\n        \"sha256\": \"dba6e93a7b4d360683898512d4f747464f5cfaedf6c2e59bb562439db9e13274\",\n        \"size\": 436561946\n    },\n    \"ConstructionObstacle_Town12_Route18507_Weather20.tar.gz\": {\n        \"sha256\": \"be356728abfa4a7dfd70e6ea348c01f68b11c204c178f9bb0a27ebb973eb19a3\",\n        \"size\": 446989977\n    },\n    \"ConstructionObstacle_Town12_Route18508_Weather21.tar.gz\": {\n        \"sha256\": \"295764e050a37ac98836050e9f0d201966ee80688070f0bd711718d4a439ad49\",\n        \"size\": 392820801\n    },\n    \"ConstructionObstacle_Town12_Route18510_Weather23.tar.gz\": {\n        \"sha256\": \"d3b5b51b25e4ec2362a4b76d9646ad4a110583130b8acb064d12c956e26c912d\",\n        \"size\": 383475151\n    },\n    \"ConstructionObstacle_Town12_Route18511_Weather23.tar.gz\": {\n        \"sha256\": \"5b59a30cffaa1f5708a34fbc643534f102bd1ee9fe4a60a7e4a00ab072a17c43\",\n        \"size\": 400005552\n    },\n    \"ConstructionObstacle_Town12_Route18512_Weather25.tar.gz\": {\n        \"sha256\": \"90bfa6ff440a2756e1f77f05d9cf33a8d67d1f2e39b7324669beae09e9d84ffb\",\n        \"size\": 294300054\n    },\n    \"ConstructionObstacle_Town12_Route18513_Weather0.tar.gz\": {\n        \"sha256\": \"eeb98cdea468a57b8ecc0baeaa2e2a519b35fa3719df9558ce2d856c5f0c3b54\",\n        \"size\": 243461115\n    },\n    \"ConstructionObstacle_Town12_Route18514_Weather1.tar.gz\": {\n        \"sha256\": \"ab4c2f7387b9d725af0b3b4e68df6f4b090519fadc458068d8692e43778a87cf\",\n        \"size\": 518762298\n    },\n    \"ConstructionObstacle_Town12_Route18515_Weather2.tar.gz\": {\n        \"sha256\": \"cfd3d94eef8b2d1f12db167e2e16c23c43df15f3090dadfbc6340410c1465104\",\n        \"size\": 423406334\n    },\n    \"ConstructionObstacle_Town12_Route18516_Weather3.tar.gz\": {\n        \"sha256\": \"6bc4abcfe18889328d4f3da2509085bdc368082ba8a3bfaf0144f19df27272ce\",\n        \"size\": 431159900\n    },\n    \"ConstructionObstacle_Town12_Route18518_Weather5.tar.gz\": {\n        \"sha256\": \"116ccc03ca9c4fccd14456252e811e841ce657a3dcbf296305eac79ec79ac46f\",\n        \"size\": 506199029\n    },\n    \"ConstructionObstacle_Town12_Route18519_Weather6.tar.gz\": {\n        \"sha256\": \"e963ea7a50665cb7fcdd7d11034a12b5a68b65ebeeab87204e3f8a779f85f1dc\",\n        \"size\": 172040099\n    },\n    \"ConstructionObstacle_Town12_Route18520_Weather7.tar.gz\": {\n        \"sha256\": \"d7b303eb862ba1963dfe4a304bcc63131a38dae02eedecd15606ef9516ee0a10\",\n        \"size\": 389293586\n    },\n    \"ConstructionObstacle_Town12_Route18521_Weather8.tar.gz\": {\n        \"sha256\": \"8dc14ec3c36ab0f5ea9d063c9629561f59929278d96c455853e64e0ac1b1c060\",\n        \"size\": 171642581\n    },\n    \"ConstructionObstacle_Town12_Route18523_Weather10.tar.gz\": {\n        \"sha256\": \"e8e6a664f9aa6bdd4ee937fdc39667b9eb5cfca916524e032c5552198b072f04\",\n        \"size\": 180292542\n    },\n    \"ConstructionObstacle_Town12_Route18524_Weather11.tar.gz\": {\n        \"sha256\": \"017f5b8459d4fe4bd5b6bccb01bd87645b4d4b8d9c7362950275001e426520f0\",\n        \"size\": 187470643\n    },\n    \"ConstructionObstacle_Town12_Route18525_Weather12.tar.gz\": {\n        \"sha256\": \"418839c7a87cf1fe81d6780b89c4c3091556c262a5b30585a9a06bb214ecb27a\",\n        \"size\": 319819041\n    },\n    \"ConstructionObstacle_Town12_Route18526_Weather13.tar.gz\": {\n        \"sha256\": \"5533fa1bc996a7bce6b07cec399b0f177b44befe3cbeca689fc048b6e804569f\",\n        \"size\": 135341376\n    },\n    \"ConstructionObstacle_Town12_Route18527_Weather14.tar.gz\": {\n        \"sha256\": \"05666bae006e8fcb2629c4cb0e3fdce82add2a13c56a62aeb8f122858d655181\",\n        \"size\": 163650118\n    },\n    \"ConstructionObstacle_Town12_Route18528_Weather15.tar.gz\": {\n        \"sha256\": \"f707f27b6d146041c3f283933b361b7893e8f171af1f1322038571db40810587\",\n        \"size\": 403969533\n    },\n    \"ConstructionObstacle_Town12_Route18529_Weather8.tar.gz\": {\n        \"sha256\": \"e2dc8c9e641a007ed05ddb98bf832842261c9027ab11ab35d8a5d0f5a2ae3086\",\n        \"size\": 425862714\n    },\n    \"ConstructionObstacle_Town12_Route18530_Weather9.tar.gz\": {\n        \"sha256\": \"1ce24e2b25937d7cf3169672fa344f8c30a10440d46bd43a65ff59cc68fe0d17\",\n        \"size\": 304984438\n    },\n    \"ConstructionObstacle_Town12_Route18531_Weather18.tar.gz\": {\n        \"sha256\": \"228609e3e38bc5b4546c38062d0e3eab14c94a0a195efb1cfc69afdda2dacb61\",\n        \"size\": 380590731\n    },\n    \"ConstructionObstacle_Town12_Route18532_Weather19.tar.gz\": {\n        \"sha256\": \"a6955843a730339fbe5c92123205e2070f08d28dbc9359e5795c3e835ae2e937\",\n        \"size\": 291486705\n    },\n    \"ConstructionObstacle_Town12_Route18533_Weather20.tar.gz\": {\n        \"sha256\": \"f6813a5ddd173d3d84a950a5f84682b70e4386410caab8eeaca7a10af3d84c48\",\n        \"size\": 315750059\n    },\n    \"ConstructionObstacle_Town12_Route18534_Weather21.tar.gz\": {\n        \"sha256\": \"0e94bdc952084ad0814d78eed16b950349a7ca2941b14fde099996ccd439fc2d\",\n        \"size\": 327612402\n    },\n    \"ConstructionObstacle_Town12_Route18535_Weather22.tar.gz\": {\n        \"sha256\": \"1fb59f61244962a7f25046f3a208f620d69623ee5435eb0ffdfc218c63929857\",\n        \"size\": 295458001\n    },\n    \"ConstructionObstacle_Town12_Route18537_Weather23.tar.gz\": {\n        \"sha256\": \"024bec231b38074ab9b4e5cecf78d3fd2dbd18f427f6c253579146937ade443f\",\n        \"size\": 281891251\n    },\n    \"ConstructionObstacle_Town12_Route18538_Weather25.tar.gz\": {\n        \"sha256\": \"3622941c1ae2df2528a7a28359cb9486f76cbf1ca19965f54e278e969f064ca7\",\n        \"size\": 131824662\n    },\n    \"ConstructionObstacle_Town12_Route18539_Weather0.tar.gz\": {\n        \"sha256\": \"76994d1a003f204172dca7f8cedf62ec55a735d14d688c93908e2cbf9d882675\",\n        \"size\": 323787790\n    },\n    \"ConstructionObstacle_Town12_Route18540_Weather1.tar.gz\": {\n        \"sha256\": \"bb5ab73e40e4a1a2a73ced667b05f9a90c28a7f0cf02030957beea38c1e0605f\",\n        \"size\": 260362883\n    },\n    \"ConstructionObstacle_Town12_Route18541_Weather2.tar.gz\": {\n        \"sha256\": \"2135d5e8fe6b69d50616ed309b0d452d31011113c9e6a2243f82ac371e811a19\",\n        \"size\": 301914553\n    },\n    \"ConstructionObstacle_Town12_Route18543_Weather3.tar.gz\": {\n        \"sha256\": \"706e19b47e11e57dea86c9032c48cd6f16bdc1ec88cb43a99dbf7aa8cb63c9c0\",\n        \"size\": 463883909\n    },\n    \"ConstructionObstacle_Town12_Route18544_Weather5.tar.gz\": {\n        \"sha256\": \"e1a4153d397c60c41bd5139d1798fdd29be5b08e1e8ffdfd2c231021f219b48f\",\n        \"size\": 474819791\n    },\n    \"ConstructionObstacle_Town12_Route18545_Weather6.tar.gz\": {\n        \"sha256\": \"dbad177d04e5e6382654cfc0baf9d4414e2c9374a578906b5b85078fc253bf33\",\n        \"size\": 382968478\n    },\n    \"ConstructionObstacle_Town12_Route18546_Weather7.tar.gz\": {\n        \"sha256\": \"e06cf26ecb902f56cc9da81be91b7da6293ceebdd57188e187e1756debf03aa9\",\n        \"size\": 458816616\n    },\n    \"ConstructionObstacle_Town12_Route18547_Weather8.tar.gz\": {\n        \"sha256\": \"2bc9908c7c08d27292aad370ee0b6fb227ba9f838f9b96ac0866f2eac01256de\",\n        \"size\": 412330480\n    },\n    \"ConstructionObstacle_Town12_Route18549_Weather10.tar.gz\": {\n        \"sha256\": \"8b87dbb3953a1aba9113cfe4179f243903a34dac47ca7adeae4b7339f2028397\",\n        \"size\": 413094025\n    },\n    \"ConstructionObstacle_Town12_Route18550_Weather11.tar.gz\": {\n        \"sha256\": \"cb649640499c00edd0556ff1d7d34bdeba4e5e6282de43f3fce13bc3910c5d21\",\n        \"size\": 349835983\n    },\n    \"ConstructionObstacle_Town12_Route18551_Weather12.tar.gz\": {\n        \"sha256\": \"b9ccf8ab287453168654ca48701721b23ff049f8c9e25d5aa5ade371dc7a13ed\",\n        \"size\": 371395583\n    },\n    \"ConstructionObstacle_Town12_Route18553_Weather14.tar.gz\": {\n        \"sha256\": \"0106a44563051d8de1bf3bbf17d304e49d521401eaf15992e20a10406242d81a\",\n        \"size\": 153397030\n    },\n    \"ConstructionObstacle_Town12_Route18554_Weather15.tar.gz\": {\n        \"sha256\": \"3bf00a8c04029383aa67be9e27437caedc51e8fd3a4f54bda9564eca4ad93e2c\",\n        \"size\": 321782960\n    },\n    \"ConstructionObstacle_Town12_Route18555_Weather8.tar.gz\": {\n        \"sha256\": \"5181b1bc4e1a3b8f5e32debf2b6cf9172be46bc7ec9e09eacc6ec8a1b2e28ed0\",\n        \"size\": 401448922\n    },\n    \"ConstructionObstacle_Town12_Route18556_Weather9.tar.gz\": {\n        \"sha256\": \"59d314464aa3f0c0fb5ca4c11f29c9855b892f50bf023962cbe669e520d41e27\",\n        \"size\": 229292682\n    },\n    \"ConstructionObstacle_Town12_Route18557_Weather18.tar.gz\": {\n        \"sha256\": \"599309d847774ac848c59d554e562f21340ab92b3a23e95a2823716ab4ad7be1\",\n        \"size\": 204954056\n    },\n    \"ConstructionObstacle_Town12_Route18558_Weather19.tar.gz\": {\n        \"sha256\": \"b4e4ee5ad810b3b157482629d8505b6f08614d8b19a5ff6037f1a8b8c4d30724\",\n        \"size\": 362335270\n    },\n    \"ConstructionObstacle_Town12_Route18559_Weather20.tar.gz\": {\n        \"sha256\": \"64068a6da2121292fb819441fbb106a06d5494dabbfa1e972497dd9e20c49c81\",\n        \"size\": 310334672\n    },\n    \"ConstructionObstacle_Town12_Route18561_Weather22.tar.gz\": {\n        \"sha256\": \"7663f69ecf8a177ef20787f3a108ac2f8b2900dacb7ed50cd9547382678563f0\",\n        \"size\": 303128967\n    },\n    \"ConstructionObstacle_Town12_Route18563_Weather23.tar.gz\": {\n        \"sha256\": \"89351013550bc17050c7735a21cb587e6d7c23f8b9b14f8f67fc3c73501264f1\",\n        \"size\": 398738886\n    },\n    \"ConstructionObstacle_Town12_Route18564_Weather25.tar.gz\": {\n        \"sha256\": \"6f2f16a6755f04280c3f0b5604674e9877b6ddc57c9b264b1bcca2bc2c98c668\",\n        \"size\": 462855283\n    },\n    \"ConstructionObstacle_Town12_Route18565_Weather0.tar.gz\": {\n        \"sha256\": \"1e3046d4be4d139022726b381e7d46f94f8d10b870979339c916d73c3accfd14\",\n        \"size\": 529244283\n    },\n    \"ConstructionObstacle_Town12_Route18567_Weather2.tar.gz\": {\n        \"sha256\": \"076ed289debeb68c32a8cceaceaeb75faaee5545beb9610e715c7062e726d8a7\",\n        \"size\": 288869876\n    },\n    \"ConstructionObstacle_Town12_Route18568_Weather3.tar.gz\": {\n        \"sha256\": \"9c4fea85a906ca56478c8058555000420156c293fe220c95789016092b88ba36\",\n        \"size\": 467876711\n    },\n    \"ConstructionObstacle_Town12_Route18569_Weather3.tar.gz\": {\n        \"sha256\": \"2c8c226966966c71a048c30731ea4dfe8c7a7ea68e15354cafb20a2685369210\",\n        \"size\": 504080777\n    },\n    \"ConstructionObstacle_Town12_Route18570_Weather5.tar.gz\": {\n        \"sha256\": \"97186899deaedbb4f6a0c122a51b781c3e0a4957716b2f3340d4e8d9c58b7cb2\",\n        \"size\": 372162496\n    },\n    \"ConstructionObstacle_Town12_Route18572_Weather7.tar.gz\": {\n        \"sha256\": \"b21ee408ace29b0f83ac653326480d79228135893193ac415e489f5b7a6b428f\",\n        \"size\": 211127393\n    },\n    \"ConstructionObstacle_Town12_Route18573_Weather8.tar.gz\": {\n        \"sha256\": \"17713c0c007fba46aade79eb5a54d1da80f34144e6f34313c8c41b477757b7d9\",\n        \"size\": 171600364\n    },\n    \"ConstructionObstacle_Town12_Route18574_Weather9.tar.gz\": {\n        \"sha256\": \"48ca5ef94e841ba160e97cbca139a22a60402bda781878661a036b3da66bd147\",\n        \"size\": 176918484\n    },\n    \"ConstructionObstacle_Town12_Route18575_Weather10.tar.gz\": {\n        \"sha256\": \"888b05d2f7fd488329c51c640f34c0cef399cc1e6962e3bfa11891fe88db037e\",\n        \"size\": 434089064\n    },\n    \"ConstructionObstacle_Town12_Route18576_Weather11.tar.gz\": {\n        \"sha256\": \"4c837449822e2224e2eb852f1af2eba5b12ca07c7fa134769a8d9e479c844148\",\n        \"size\": 136996239\n    },\n    \"ConstructionObstacle_Town12_Route18577_Weather12.tar.gz\": {\n        \"sha256\": \"40d69f7dbbcf959afdc0a30ccb4fd7c9d842a7b7400d0c0774bf3153426ff735\",\n        \"size\": 155676549\n    },\n    \"ConstructionObstacle_Town12_Route18578_Weather13.tar.gz\": {\n        \"sha256\": \"fe52a95396fa4c9554b77b954ca79b6256be05eafdbfb22174a99c8fa4cb89fe\",\n        \"size\": 394578319\n    },\n    \"ConstructionObstacle_Town12_Route18579_Weather14.tar.gz\": {\n        \"sha256\": \"60a68eb6899c186579ae092467984dedfff9573ff1b100d40c7ea9500d1d4581\",\n        \"size\": 151420635\n    },\n    \"ConstructionObstacle_Town12_Route18581_Weather8.tar.gz\": {\n        \"sha256\": \"cdac801b74420e02b81421f571cb068a251b0b726241262c1c34ea3dd9628b88\",\n        \"size\": 173052228\n    },\n    \"ConstructionObstacle_Town12_Route18582_Weather9.tar.gz\": {\n        \"sha256\": \"75366765dd116fc808646793df258e71964e050c5a06d4750ccba8fd139c2010\",\n        \"size\": 415828671\n    },\n    \"ConstructionObstacle_Town12_Route18583_Weather18.tar.gz\": {\n        \"sha256\": \"26827ce35db199041178c576a28ff308d9a0dcdb2d05a10639c0f61cd74fc883\",\n        \"size\": 474281514\n    },\n    \"ConstructionObstacle_Town12_Route18584_Weather19.tar.gz\": {\n        \"sha256\": \"3672ae104fb0de4807f1d0feb576c464a58eb1cd01ba59cffd4630973aefc5b3\",\n        \"size\": 174566686\n    },\n    \"ConstructionObstacle_Town12_Route18585_Weather20.tar.gz\": {\n        \"sha256\": \"893968403a17de4a381149a0491f186555eeef803fe882420e2cba7b6c49d1be\",\n        \"size\": 253479544\n    },\n    \"ConstructionObstacle_Town12_Route18586_Weather21.tar.gz\": {\n        \"sha256\": \"67ea41bd9f8e2f77598fb0610810f7573a60e94559541a5cc79b6d0f112a1358\",\n        \"size\": 153138129\n    },\n    \"ConstructionObstacle_Town12_Route18588_Weather23.tar.gz\": {\n        \"sha256\": \"f66019eee0e12d07b27bdf879ab6bb3a141b7148a3a6871fbba7c1acfbc45d38\",\n        \"size\": 368968647\n    },\n    \"ConstructionObstacle_Town12_Route18589_Weather23.tar.gz\": {\n        \"sha256\": \"75bded5f87f552f489c2d015a990ff0893f04b1d5b3bff38e9fd55a071e22a0d\",\n        \"size\": 285153487\n    },\n    \"ConstructionObstacle_Town12_Route18590_Weather25.tar.gz\": {\n        \"sha256\": \"a9fbeeb3de2d1ac6f35ec749d44682f0687d1948ee5a64ac9320e3e44ce7f2b5\",\n        \"size\": 134151191\n    },\n    \"ConstructionObstacle_Town12_Route18592_Weather1.tar.gz\": {\n        \"sha256\": \"283dd7dc4c9fb069a044d62da2480d555f014dce1ffd6f8240be33d00a6874bd\",\n        \"size\": 456834766\n    },\n    \"ConstructionObstacle_Town12_Route18593_Weather2.tar.gz\": {\n        \"sha256\": \"407035201e077267f1a85c92cbb7c52f8328ebb154dc44cae41af8c7e76f7e29\",\n        \"size\": 472467074\n    },\n    \"ConstructionObstacle_Town12_Route18595_Weather3.tar.gz\": {\n        \"sha256\": \"81cf5a540f791414a1a957b40472af0b48bf02d58f1cb2b25186c1fb4dbf05e3\",\n        \"size\": 172494016\n    },\n    \"ConstructionObstacle_Town12_Route18596_Weather5.tar.gz\": {\n        \"sha256\": \"dcf549707c33b518d507415c25b22b90b883500b8d4bd56b75a2e8f604a9dfcd\",\n        \"size\": 184022803\n    },\n    \"ConstructionObstacle_Town12_Route18597_Weather6.tar.gz\": {\n        \"sha256\": \"88293bb3e189cba392abdd34f475dc824f7eb6568b5355da17fe5ba629356352\",\n        \"size\": 162229329\n    },\n    \"ConstructionObstacle_Town12_Route18598_Weather7.tar.gz\": {\n        \"sha256\": \"bc23b48d80287c7711f0fcd7ec29bd8a9d409f01dee6469e07685fc97cd3a0b1\",\n        \"size\": 326499505\n    },\n    \"ConstructionObstacle_Town12_Route18599_Weather8.tar.gz\": {\n        \"sha256\": \"c9960fc118df743ad721ea2a54fef2c373dc970dd1a170514d3b8ecaef10bf5f\",\n        \"size\": 188797263\n    },\n    \"ConstructionObstacle_Town12_Route18600_Weather9.tar.gz\": {\n        \"sha256\": \"273150cefdf5cce86312cddf998dffbf641e149361f1c573695837359d28e8da\",\n        \"size\": 432377196\n    },\n    \"ConstructionObstacle_Town12_Route18601_Weather10.tar.gz\": {\n        \"sha256\": \"a7d9d977bcf8a8b2250b6b0dd189464af0d97b513da02fe6ba4e937d4a215cbc\",\n        \"size\": 173697533\n    },\n    \"ConstructionObstacle_Town12_Route18602_Weather11.tar.gz\": {\n        \"sha256\": \"16ad286157f616afb214e6bd4abcc2f278aa027fb4754e4d381399743e5761fd\",\n        \"size\": 152369417\n    },\n    \"ConstructionObstacle_Town12_Route18603_Weather12.tar.gz\": {\n        \"sha256\": \"6d247959f9a40b0f259647154076808c89458bee38d3b066331766188b1adb4a\",\n        \"size\": 141858747\n    },\n    \"ConstructionObstacle_Town12_Route18604_Weather13.tar.gz\": {\n        \"sha256\": \"3b34fa3ea402ff5c49d72e0b3dbbdd23c4b868f4e1625cc52a767b4467048aca\",\n        \"size\": 358584400\n    },\n    \"ConstructionObstacle_Town12_Route18605_Weather14.tar.gz\": {\n        \"sha256\": \"67b9dc9b277f0c9057aafa12a57f63e04a2a75d819b16cedc3556a8f009996d5\",\n        \"size\": 403665975\n    },\n    \"ConstructionObstacle_Town12_Route18606_Weather15.tar.gz\": {\n        \"sha256\": \"21d80f69d20d72a44178567c46d5c68d03b2a0f61dd99a60fb87012547491f5c\",\n        \"size\": 423458250\n    },\n    \"ConstructionObstacle_Town12_Route18607_Weather8.tar.gz\": {\n        \"sha256\": \"4cf8d8a37755d1ce06b3301ecc9c63dd5d50336d2a4f3db912a4dd2c39ecc30e\",\n        \"size\": 193506820\n    },\n    \"ConstructionObstacle_Town12_Route18609_Weather18.tar.gz\": {\n        \"sha256\": \"0f3ac95037b08a714b7b3ec25bf1bf55f544d342327eb931ca1bf958d9b23423\",\n        \"size\": 188605578\n    },\n    \"ConstructionObstacle_Town12_Route18610_Weather19.tar.gz\": {\n        \"sha256\": \"1660cded432f5a3ee370a9f1cdf385308586086f274a5002dbe90a1625275fe7\",\n        \"size\": 197723407\n    },\n    \"ConstructionObstacle_Town12_Route18611_Weather20.tar.gz\": {\n        \"sha256\": \"1c379aeadf16d1ceada88dc99a334dbebd37496635dbebf386d5bb48f400e81e\",\n        \"size\": 340305861\n    },\n    \"ConstructionObstacle_Town12_Route18613_Weather22.tar.gz\": {\n        \"sha256\": \"a971734e38991a4bfde91463a066cf4b4ca850b67f5246ee5f3d863eba65455b\",\n        \"size\": 469838410\n    },\n    \"ConstructionObstacle_Town12_Route18614_Weather23.tar.gz\": {\n        \"sha256\": \"7dcd78f66a2933aa4b7394aa313e2ed4c89863169afd4e5eebb58652c1d234e7\",\n        \"size\": 410194177\n    },\n    \"ConstructionObstacle_Town12_Route18615_Weather23.tar.gz\": {\n        \"sha256\": \"6a09e7347a0380558d357a274d38f212affd6a47b308407d7bba408064b610e9\",\n        \"size\": 464978381\n    },\n    \"ConstructionObstacle_Town12_Route18616_Weather25.tar.gz\": {\n        \"sha256\": \"66781457cf91f902200c4908df3081fc886a42c04df9676c0eee6989ec2e500b\",\n        \"size\": 448167129\n    },\n    \"ConstructionObstacle_Town12_Route18617_Weather0.tar.gz\": {\n        \"sha256\": \"62d4799b9a94d3d95fb0272e8042fd9c73de968ad045ce26925994a19e75420b\",\n        \"size\": 195901673\n    },\n    \"ConstructionObstacle_Town12_Route18618_Weather1.tar.gz\": {\n        \"sha256\": \"8b6888a02d35438d2e4c44d3028aad45247e222b377119bdceb43bc528b6865b\",\n        \"size\": 195316607\n    },\n    \"ConstructionObstacle_Town12_Route18619_Weather2.tar.gz\": {\n        \"sha256\": \"6ce45a335f1e82a3ea761e78d2585dea0425a6239c51e7e94c7e9e24bd9a8451\",\n        \"size\": 158337951\n    },\n    \"ConstructionObstacle_Town12_Route18622_Weather5.tar.gz\": {\n        \"sha256\": \"cdd6a5b93f4763772f5e492761c9579a93acf694e50fa90d343a4fa431ca62d9\",\n        \"size\": 167451431\n    },\n    \"ConstructionObstacle_Town12_Route18623_Weather6.tar.gz\": {\n        \"sha256\": \"f4ddedde87ef55ccba74417a67b9a9f6d325829a57a5b2618f18485c5379f9c3\",\n        \"size\": 485088643\n    },\n    \"ConstructionObstacle_Town12_Route18624_Weather7.tar.gz\": {\n        \"sha256\": \"51006b61539c76cf5ad96c30144be0ce290f37b2d9ec45c8e52ed897ed52f01f\",\n        \"size\": 199571007\n    },\n    \"ConstructionObstacle_Town12_Route18625_Weather8.tar.gz\": {\n        \"sha256\": \"59f19d07cf134b24e5a8bcc337fdb61f107e89156d38a423e28138335c9b09ee\",\n        \"size\": 169558789\n    },\n    \"ConstructionObstacle_Town12_Route18626_Weather9.tar.gz\": {\n        \"sha256\": \"e163385f62c2d923db90cabfd2b13455185c3cc8197a537440b42994f109e3c7\",\n        \"size\": 140204504\n    },\n    \"ConstructionObstacle_Town12_Route18627_Weather10.tar.gz\": {\n        \"sha256\": \"d580e1e7f6f18cd988e5f4109cbdbd1e365d013ada94474bdd57be8c7ff25132\",\n        \"size\": 400765399\n    },\n    \"ConstructionObstacle_Town12_Route18628_Weather11.tar.gz\": {\n        \"sha256\": \"98e51f5e1e28fba7aba08945d31841eed2bb625a39339b6e51c067eaf4a65876\",\n        \"size\": 375805772\n    },\n    \"ConstructionObstacle_Town12_Route18629_Weather12.tar.gz\": {\n        \"sha256\": \"edf8587fa83f2c7582db2aee688d4cc0ba1cde091faad6075f76893302afe0d8\",\n        \"size\": 358381991\n    },\n    \"ConstructionObstacle_Town12_Route18630_Weather13.tar.gz\": {\n        \"sha256\": \"ceb9f88f512e5bbf4ab028f2b9b57631cadba922ad401a876e1abec761c2c279\",\n        \"size\": 474215142\n    },\n    \"ConstructionObstacle_Town12_Route18631_Weather14.tar.gz\": {\n        \"sha256\": \"5abb236f09a5ebea265d37bb1ff4135469dcd5c4244338501553a182305ab43f\",\n        \"size\": 396341513\n    },\n    \"ConstructionObstacle_Town12_Route18632_Weather15.tar.gz\": {\n        \"sha256\": \"c4ccfea1dc343fd8ce8687ca906ef44efe270fa7f2498db9faf8b5f2500643c6\",\n        \"size\": 371102789\n    },\n    \"ConstructionObstacle_Town12_Route18633_Weather8.tar.gz\": {\n        \"sha256\": \"a243c629c5172f090535ea0e610d423134dd982934259afbd52f6631e3213502\",\n        \"size\": 476331570\n    },\n    \"ConstructionObstacle_Town12_Route18634_Weather9.tar.gz\": {\n        \"sha256\": \"1c7722a825a4dc2b0590ce4355a5ef358698531d0b20e54b58f92ec73114072b\",\n        \"size\": 135287913\n    },\n    \"ConstructionObstacle_Town12_Route18635_Weather18.tar.gz\": {\n        \"sha256\": \"00822f18e568753152f2dfa859f08268f39803b9d30359f46cd9d9ca2683a95d\",\n        \"size\": 196498152\n    },\n    \"ConstructionObstacle_Town12_Route18636_Weather19.tar.gz\": {\n        \"sha256\": \"fc19729baaa67a0e732dad35e6ee741eff6935edc4458d7c9de966f60886bf55\",\n        \"size\": 482310940\n    },\n    \"ConstructionObstacle_Town12_Route18637_Weather20.tar.gz\": {\n        \"sha256\": \"a6e4b4dde1941d14c238427198088b0325664a1ff3117db55c4e439cde771e4f\",\n        \"size\": 478413999\n    },\n    \"ConstructionObstacle_Town12_Route18638_Weather21.tar.gz\": {\n        \"sha256\": \"7405e083069c23e0a519c58d975087e0c82fa067cfa2948e742643a2262de714\",\n        \"size\": 468161339\n    },\n    \"ConstructionObstacle_Town12_Route18639_Weather22.tar.gz\": {\n        \"sha256\": \"4c96df0215c654f681d48b6050f631edd35f401c8a5f962568de825283aa535b\",\n        \"size\": 552170772\n    },\n    \"ConstructionObstacle_Town12_Route18640_Weather23.tar.gz\": {\n        \"sha256\": \"31e487b56809e154ae6f43310d8270eae5591bed3beec6bc4c41611683c50d25\",\n        \"size\": 436874884\n    },\n    \"ConstructionObstacle_Town12_Route18641_Weather23.tar.gz\": {\n        \"sha256\": \"0f4ddabdddb51ccc9d6772a3d3b899e81ecf457f67c8da21e7384c5aa1556b2c\",\n        \"size\": 287491713\n    },\n    \"ConstructionObstacle_Town12_Route18642_Weather25.tar.gz\": {\n        \"sha256\": \"201bcf0e3c85e5a1ac08ce0212910bf64bfb3201890e6e5d1ae21699271c7361\",\n        \"size\": 132673112\n    },\n    \"ConstructionObstacle_Town12_Route18643_Weather0.tar.gz\": {\n        \"sha256\": \"ab40c6e0994bf51d2339dd425e5480aecc3ab6e9a697403265c9452354ee6a5c\",\n        \"size\": 180885845\n    },\n    \"ConstructionObstacle_Town12_Route18644_Weather1.tar.gz\": {\n        \"sha256\": \"b894d4c13a0e47be1cee1e6e7a68808f733914abb381e46bff1cc4f0c3fb467d\",\n        \"size\": 195087157\n    },\n    \"ConstructionObstacle_Town12_Route18645_Weather2.tar.gz\": {\n        \"sha256\": \"2f9a4848360e65965c9c2c05d84a4250eb85a65aefb37abbcde6d81aa23ecbc0\",\n        \"size\": 270362534\n    },\n    \"ConstructionObstacle_Town12_Route18647_Weather3.tar.gz\": {\n        \"sha256\": \"fccc98de7a77de1acc6430ad4ca30ef6f6d9a3dda79b821c3bbbb7762be08b17\",\n        \"size\": 186180899\n    },\n    \"ConstructionObstacle_Town12_Route18651_Weather8.tar.gz\": {\n        \"sha256\": \"7750816f59d6600301ee7bc566ae6d04e6567b923a53a1aca0b147a4e4717215\",\n        \"size\": 151560371\n    },\n    \"ConstructionObstacle_Town12_Route18653_Weather10.tar.gz\": {\n        \"sha256\": \"bc78f65e35e041198a41f54ab24301a1ab1a09a449c0a91ba9856c5ea44f529a\",\n        \"size\": 277888962\n    },\n    \"ConstructionObstacle_Town12_Route18654_Weather11.tar.gz\": {\n        \"sha256\": \"160b5486890288f82669e3aee786b843f1d9b7e8a67bd5510eeeec7915c1dc5b\",\n        \"size\": 133263595\n    },\n    \"ConstructionObstacle_Town12_Route18655_Weather12.tar.gz\": {\n        \"sha256\": \"208d260acc35165e458b163165d956980de2663b8e3b2c19c8e4901a289af611\",\n        \"size\": 354308818\n    },\n    \"ConstructionObstacle_Town12_Route18656_Weather13.tar.gz\": {\n        \"sha256\": \"f648d2b3d3a79a68ffed25f610d470ca0bbfbdbe4743a8379e85401870219e86\",\n        \"size\": 411068031\n    },\n    \"ConstructionObstacle_Town12_Route18657_Weather14.tar.gz\": {\n        \"sha256\": \"319a4012994cee88cf44717e38f6c1d7f7c47bf9b75b5d4083f7deccfd1e0d8f\",\n        \"size\": 386762996\n    },\n    \"ConstructionObstacle_Town12_Route18658_Weather15.tar.gz\": {\n        \"sha256\": \"bda93a7c216d446986ef80e97eef7f893e22093bf669c672be5ceb4218ee6b4f\",\n        \"size\": 384584490\n    },\n    \"ConstructionObstacle_Town12_Route18659_Weather8.tar.gz\": {\n        \"sha256\": \"daea164bcf165117d7664b3358b26faf67c2500e1a16c1b4bf1813f59d7e43e1\",\n        \"size\": 416985328\n    },\n    \"ConstructionObstacle_Town12_Route18661_Weather18.tar.gz\": {\n        \"sha256\": \"173f7be3ac5dadb96db1b18e5f69839e43b0ce19eeb76915de98e5c566a6cd02\",\n        \"size\": 186229961\n    },\n    \"ConstructionObstacle_Town12_Route18662_Weather19.tar.gz\": {\n        \"sha256\": \"2cbafb7a4157af491e3f5505e7c6776dc7958da80b355b52b9bb636ce753b1ac\",\n        \"size\": 464806079\n    },\n    \"ConstructionObstacle_Town12_Route18664_Weather21.tar.gz\": {\n        \"sha256\": \"dba9341c2c6154fae0755eb6dc7d0f10cbec20b5b7b0e32aa5e23bad868510dc\",\n        \"size\": 268504917\n    },\n    \"ConstructionObstacle_Town12_Route18665_Weather22.tar.gz\": {\n        \"sha256\": \"1897b562fb87a1db22aa9a81b1e1f6d222fe99eba07baec2b9995c7a8b62e9cd\",\n        \"size\": 304612585\n    },\n    \"ConstructionObstacle_Town12_Route18666_Weather23.tar.gz\": {\n        \"sha256\": \"b9a2388a5e2051899911d48e547789f2a92b2e48018043f4844921c2e5f878f8\",\n        \"size\": 282671031\n    },\n    \"ConstructionObstacle_Town12_Route18668_Weather25.tar.gz\": {\n        \"sha256\": \"762bed690ecce73b2f6230ec147ead21913e30b737c1e5b0a40eef10f2a74898\",\n        \"size\": 219104656\n    },\n    \"ConstructionObstacle_Town12_Route18669_Weather0.tar.gz\": {\n        \"sha256\": \"83c3ca5964752400699e5a8e0275ac12eb8273842091305d45b59809639d7e4a\",\n        \"size\": 384559080\n    },\n    \"ConstructionObstacle_Town12_Route18670_Weather1.tar.gz\": {\n        \"sha256\": \"e4cb6b3990b83faaa69a65dd36d7063c4cccffddc56c5952ae276e143a21379b\",\n        \"size\": 402824030\n    },\n    \"ConstructionObstacle_Town12_Route18672_Weather3.tar.gz\": {\n        \"sha256\": \"3c6da91b33d8fee522196dfe49d0c5cc3aa8f07b7ac549afac4d3850c433d948\",\n        \"size\": 367221081\n    },\n    \"ConstructionObstacle_Town12_Route18673_Weather3.tar.gz\": {\n        \"sha256\": \"d6514585dff5604a005d513d108860fe0602430ad1e01a68869ba773f28c5275\",\n        \"size\": 351602558\n    },\n    \"ConstructionObstacle_Town12_Route18674_Weather5.tar.gz\": {\n        \"sha256\": \"793c9fe973140cb46bb52c61fd73955fb697c469407fe0482b9d3492d2536ff0\",\n        \"size\": 345219285\n    },\n    \"ConstructionObstacle_Town12_Route18675_Weather6.tar.gz\": {\n        \"sha256\": \"2b79fdbf44b6a598c46e44225651e8681820567af06decba9af521300ab47cec\",\n        \"size\": 174986046\n    },\n    \"ConstructionObstacle_Town12_Route18676_Weather7.tar.gz\": {\n        \"sha256\": \"fcd1802c502ea5c5162f46f0b18e63e826042adba7909e9554205a2230cd65d2\",\n        \"size\": 300899692\n    },\n    \"ConstructionObstacle_Town12_Route18677_Weather8.tar.gz\": {\n        \"sha256\": \"d5b6ccf40ad30fc349dedfae2de577d8dddaf0e2d0d680363070373f199a21af\",\n        \"size\": 198335120\n    },\n    \"ConstructionObstacle_Town12_Route18678_Weather9.tar.gz\": {\n        \"sha256\": \"b0602425de092acd9a0e58862bd6b351966fdca52408139a81eb7be3c11f24db\",\n        \"size\": 247566481\n    },\n    \"ConstructionObstacle_Town12_Route18680_Weather11.tar.gz\": {\n        \"sha256\": \"3e7eb91d49536ded7bb0484745b52ac9dc0e605ad27fb2f076f125098744e27c\",\n        \"size\": 291680444\n    },\n    \"ConstructionObstacle_Town12_Route18682_Weather13.tar.gz\": {\n        \"sha256\": \"efb4bf5b31dc6761e1aa77e2af7d846f2938abaf897188775d1433f969fa624f\",\n        \"size\": 294634663\n    },\n    \"ConstructionObstacle_Town12_Route18683_Weather14.tar.gz\": {\n        \"sha256\": \"1176e20276df07f41537afde403018cb54ea299d003203e4abfc0bc6e52fa612\",\n        \"size\": 317366652\n    },\n    \"ConstructionObstacle_Town12_Route18684_Weather15.tar.gz\": {\n        \"sha256\": \"fac23fe7df5aeca9b5b88561adfe7320fdca907c7840ac8df5ffaab939464f38\",\n        \"size\": 340693920\n    },\n    \"ConstructionObstacle_Town12_Route18685_Weather8.tar.gz\": {\n        \"sha256\": \"3464f274168136e8e7b2a3d10fa9fcfa01a5fe77f5f78a1eb0c0762f5f929fd7\",\n        \"size\": 337518842\n    },\n    \"ConstructionObstacle_Town12_Route18686_Weather9.tar.gz\": {\n        \"sha256\": \"f764a1d685b39096d14921de692cfc90fdcacd4e738658beb33f869bb3030bd9\",\n        \"size\": 319993727\n    },\n    \"ConstructionObstacle_Town12_Route18687_Weather18.tar.gz\": {\n        \"sha256\": \"ebd5ed36a9f6d2e24861d8740ce809a12b95eca6b7200ae2876f7f54ddc6e7b0\",\n        \"size\": 419665510\n    },\n    \"ConstructionObstacle_Town12_Route18688_Weather19.tar.gz\": {\n        \"sha256\": \"16899639489121e5f289c2be060cb85ed52dc9b1735e9b33a335c4548c403cf8\",\n        \"size\": 185437746\n    },\n    \"ConstructionObstacle_Town12_Route18689_Weather20.tar.gz\": {\n        \"sha256\": \"71aaac85a92d9bfd15343163440bf80ad012eacd47952ced27146db5fabc2fdd\",\n        \"size\": 385226998\n    },\n    \"ConstructionObstacle_Town12_Route18691_Weather22.tar.gz\": {\n        \"sha256\": \"00ba6ab1c02cccf9086c8565c315b9032bb875148d5b33c2e88e718116000293\",\n        \"size\": 408580920\n    },\n    \"ConstructionObstacle_Town12_Route18692_Weather23.tar.gz\": {\n        \"sha256\": \"19364a04a4311cfd40dd02ab820a97f9bbb626bbf5316379985c10861abf7d0b\",\n        \"size\": 151723739\n    },\n    \"ConstructionObstacle_Town12_Route18693_Weather23.tar.gz\": {\n        \"sha256\": \"2baed2166f354295e9609c59dead2cee378e64a6c6140e3fc663943dd893563e\",\n        \"size\": 143857981\n    },\n    \"ConstructionObstacle_Town12_Route18694_Weather25.tar.gz\": {\n        \"sha256\": \"d5cb57f57b2474317ce945d42db73cafab44f070d658ce56f4d6ff136bfe4a94\",\n        \"size\": 320933738\n    },\n    \"ConstructionObstacle_Town12_Route18695_Weather0.tar.gz\": {\n        \"sha256\": \"b901468789edf5cf802e90e3d3318edb599949152c211f60b9c87e15a71cdf25\",\n        \"size\": 215222014\n    },\n    \"ConstructionObstacle_Town12_Route18697_Weather2.tar.gz\": {\n        \"sha256\": \"e4891e416f2a753fee37f64401ae69fbc53d42149206c0c279138f4c469c8973\",\n        \"size\": 197290543\n    },\n    \"ConstructionObstacle_Town12_Route18698_Weather3.tar.gz\": {\n        \"sha256\": \"a272390a7fca687a275b0e52a2e10ece91409bf947e555434088f132331e709a\",\n        \"size\": 189283972\n    },\n    \"ConstructionObstacle_Town12_Route18699_Weather3.tar.gz\": {\n        \"sha256\": \"a2b05b85f930382051ad69ceb9d9681f968971bc4b858aebc5b39ac3ac721ec1\",\n        \"size\": 320986391\n    },\n    \"ConstructionObstacle_Town12_Route18700_Weather5.tar.gz\": {\n        \"sha256\": \"fd2239bbc9a84df0ea4f7608070d581f284c73a65bf56f24f7f52c20d40abdf9\",\n        \"size\": 363274069\n    },\n    \"ConstructionObstacle_Town12_Route18701_Weather6.tar.gz\": {\n        \"sha256\": \"417fe716c64b049e1e362b58d272f510310f2498f0f791ca448360a48e17873c\",\n        \"size\": 316351688\n    },\n    \"ConstructionObstacle_Town12_Route18705_Weather10.tar.gz\": {\n        \"sha256\": \"f5cef238d3ef8befe74df382943842d7288e20368feac625f26b8a948e7134b6\",\n        \"size\": 357929742\n    },\n    \"ConstructionObstacle_Town12_Route18706_Weather11.tar.gz\": {\n        \"sha256\": \"35899689733412e1db74ee97dc1e821ea8d23a493d103379087ee12830aee5a2\",\n        \"size\": 426960578\n    },\n    \"ConstructionObstacle_Town12_Route18707_Weather12.tar.gz\": {\n        \"sha256\": \"a57e767c3b9f57c06f62612f39f69dad256e92474ffeccdbc4e7db91085e9ed9\",\n        \"size\": 131017170\n    },\n    \"ConstructionObstacle_Town12_Route18709_Weather14.tar.gz\": {\n        \"sha256\": \"1874340bd165f15391ef73a3d8a79a4bb4475e9304ea52de541895b3e4be1378\",\n        \"size\": 414552521\n    },\n    \"ConstructionObstacle_Town12_Route18710_Weather15.tar.gz\": {\n        \"sha256\": \"6e239aff9ffd49d27bfd525fba2a56ce2ce3eae2092792f44a5e6b0ff6779a8f\",\n        \"size\": 478407064\n    },\n    \"ConstructionObstacle_Town12_Route18711_Weather8.tar.gz\": {\n        \"sha256\": \"8d0d198fc038ad4b0924f7e46a4d66837ed50da7e6a84a019a9eb3cdcaca22d6\",\n        \"size\": 376628032\n    },\n    \"ConstructionObstacle_Town12_Route18712_Weather9.tar.gz\": {\n        \"sha256\": \"611ad76bd5636d0731e9eb1209b1be92a98b75587141b7b8d49f750fd46d1120\",\n        \"size\": 132694103\n    },\n    \"ConstructionObstacle_Town12_Route18713_Weather18.tar.gz\": {\n        \"sha256\": \"2066d73a3f992dbfd763891d850b87cd090984fed1d3e1c00a320105aad49a5c\",\n        \"size\": 190544375\n    },\n    \"ConstructionObstacle_Town12_Route18716_Weather21.tar.gz\": {\n        \"sha256\": \"3551c2804c0eefd667312ed86a0ee12ffaea4bcc12f0c8ed53ad947bb9549bd0\",\n        \"size\": 165200598\n    },\n    \"ConstructionObstacle_Town12_Route18718_Weather23.tar.gz\": {\n        \"sha256\": \"8b8a5fca5e38c6462f1745341603ea24f3d2ecae6754549e0ea7c70da7f4442d\",\n        \"size\": 153829621\n    },\n    \"ConstructionObstacle_Town12_Route18719_Weather23.tar.gz\": {\n        \"sha256\": \"54628294ed8a0285e74cd3ec9bfec9c3bd45bae22f8ea7d4d2154d540b7b9dd1\",\n        \"size\": 150066180\n    },\n    \"ConstructionObstacle_Town12_Route18720_Weather25.tar.gz\": {\n        \"sha256\": \"38fb4e656bfe77dd7bd0fc9290095942c963f2dcdc31344f48c76f1db0a3cad5\",\n        \"size\": 151686448\n    },\n    \"ConstructionObstacle_Town12_Route18722_Weather1.tar.gz\": {\n        \"sha256\": \"4bffa3b6ff6f1a50edb03c7f3a0af7ef7d358af8762f3161ac3d00e813790840\",\n        \"size\": 411244510\n    },\n    \"ConstructionObstacle_Town12_Route18723_Weather2.tar.gz\": {\n        \"sha256\": \"690a28acc2c1c7225fa7171d88bcf22e2886d2b7acd585a1ee2ac1387f97ea85\",\n        \"size\": 256652380\n    },\n    \"ConstructionObstacle_Town12_Route18724_Weather3.tar.gz\": {\n        \"sha256\": \"42696d5657c5af4f49937fee7eb6c7ebfd6ecf1b6813f98da73c8ad283299994\",\n        \"size\": 325482784\n    },\n    \"ConstructionObstacle_Town12_Route18725_Weather3.tar.gz\": {\n        \"sha256\": \"cd9e0e99fe85033bb198032fe259bde35fc49bae84dc1917ee0ab8d6b84d20ed\",\n        \"size\": 371218573\n    },\n    \"ConstructionObstacle_Town12_Route18726_Weather5.tar.gz\": {\n        \"sha256\": \"643cf92494e9272c57ffb3e0483dd0f76b99a61cb1290f94de0ffb8f4941ea79\",\n        \"size\": 191135100\n    },\n    \"ConstructionObstacle_Town12_Route18727_Weather6.tar.gz\": {\n        \"sha256\": \"6c313bad2951e5d313450e9033ceafe0e03777299082bcd1be27c325e3c0d16b\",\n        \"size\": 446809896\n    },\n    \"ConstructionObstacle_Town12_Route18728_Weather7.tar.gz\": {\n        \"sha256\": \"d193a5bab73612002dadc2743638c812bb33321728e3eec2b75c6f073584d875\",\n        \"size\": 184738613\n    },\n    \"ConstructionObstacle_Town12_Route18730_Weather9.tar.gz\": {\n        \"sha256\": \"d6719d3647e82a6ee9de49b6c66f055d1bb78f52797d52e1807a58c4b0eeeab7\",\n        \"size\": 131019620\n    },\n    \"ConstructionObstacle_Town12_Route18731_Weather10.tar.gz\": {\n        \"sha256\": \"45724f65b627eb49bcca334eaa5f95516b148ab43460314b3165a1398d23fd11\",\n        \"size\": 185786803\n    },\n    \"ConstructionObstacle_Town12_Route18733_Weather12.tar.gz\": {\n        \"sha256\": \"1f5f4b7a1f362de50e3c050fc0d25efba8e54bd1d83e8dda7b3927f647515372\",\n        \"size\": 137147981\n    },\n    \"ConstructionObstacle_Town12_Route18735_Weather14.tar.gz\": {\n        \"sha256\": \"eb9c4c4700e2714e6a53dc62010cc1cfaa8ddba252153c407ee6b1ee342f6ff1\",\n        \"size\": 156064890\n    },\n    \"ConstructionObstacle_Town12_Route18736_Weather15.tar.gz\": {\n        \"sha256\": \"307dbe07df3781d5be5bc42b87dac7af2d298b7ccca322e0a52fbb708b4b7d88\",\n        \"size\": 168662454\n    },\n    \"ConstructionObstacle_Town12_Route18737_Weather8.tar.gz\": {\n        \"sha256\": \"9408ed121a0fc394d6df61a584fe4aaeb81bd186afb1d020c3af8fe3028e3d47\",\n        \"size\": 189332270\n    },\n    \"ConstructionObstacle_Town12_Route18738_Weather9.tar.gz\": {\n        \"sha256\": \"a125f51391b5f18ac75bb2894adef8bf87ac19c42958c7af99607f26d968f74d\",\n        \"size\": 150617302\n    },\n    \"ConstructionObstacle_Town12_Route18739_Weather18.tar.gz\": {\n        \"sha256\": \"70fb27133ac99d11befa408b37d6b5b121df0b688ac01347149cd4c23226cc5e\",\n        \"size\": 196372644\n    },\n    \"ConstructionObstacle_Town12_Route18740_Weather19.tar.gz\": {\n        \"sha256\": \"512668d8480755566cd76de322d26562953dedd91c8ee4c0d57f562d7adce601\",\n        \"size\": 282117765\n    },\n    \"ConstructionObstacle_Town12_Route18741_Weather20.tar.gz\": {\n        \"sha256\": \"e2c2217a33c92f5e5a8ba36cde2831eb5526fe264ab1259a6875eb676708f528\",\n        \"size\": 295276057\n    },\n    \"ConstructionObstacle_Town12_Route18742_Weather21.tar.gz\": {\n        \"sha256\": \"aac0efe303e8310c86e71e6ed92c3eced2c1215982ae547323d5cafb314c954b\",\n        \"size\": 253151855\n    },\n    \"ConstructionObstacle_Town12_Route18743_Weather22.tar.gz\": {\n        \"sha256\": \"f5c226ec1889310438197b0a5b6973998497a47bbf69ae343b8e11102864fbb6\",\n        \"size\": 162664121\n    },\n    \"ConstructionObstacle_Town12_Route18744_Weather23.tar.gz\": {\n        \"sha256\": \"65f8bc2cf2cebc816c068575c30c64d6d8ea7cfd91d74cfd05b8bcff8fe15cf3\",\n        \"size\": 141313436\n    },\n    \"ConstructionObstacle_Town12_Route18745_Weather23.tar.gz\": {\n        \"sha256\": \"5fd7410323b2cea604299a73d6ab7ef59c8cca433c35537c32d127c1466bdeaf\",\n        \"size\": 144477246\n    },\n    \"ConstructionObstacle_Town12_Route18746_Weather25.tar.gz\": {\n        \"sha256\": \"aa29a5031db1fdbdab29f83b92959e6629188cc86469cc72377a301b703f2efe\",\n        \"size\": 144016190\n    },\n    \"ConstructionObstacle_Town12_Route2504_Weather2.tar.gz\": {\n        \"sha256\": \"9e76edfdc7772d2d7cf2766f963816501ea1c7ab3b24b6afdf2a9de74b7a076d\",\n        \"size\": 556949252\n    },\n    \"ConstructionObstacle_Town12_Route2507_Weather5.tar.gz\": {\n        \"sha256\": \"cc6652f05c07bedeca4866da0e5fda4caafbdda831dcdb38a130fc2c3f50ebbe\",\n        \"size\": 323601675\n    },\n    \"ConstructionObstacle_Town12_Route2508_Weather6.tar.gz\": {\n        \"sha256\": \"976cacfee695943a255705ae56b3319cca8e69db9c017808092cad97e172a7cb\",\n        \"size\": 361217676\n    },\n    \"ConstructionObstacle_Town12_Route2509_Weather7.tar.gz\": {\n        \"sha256\": \"5c8f5636ea9dc06314a3beebbb6f53bd5d231169e2b5e0306426e44016bb618e\",\n        \"size\": 482536426\n    },\n    \"ConstructionObstacle_Town12_Route2510_Weather8.tar.gz\": {\n        \"sha256\": \"5ef9b582cd6b95c53a40fe697fc4dda7a31090e2174df3569243eada3af983fa\",\n        \"size\": 437465007\n    },\n    \"ConstructionObstacle_Town12_Route2513_Weather11.tar.gz\": {\n        \"sha256\": \"21ce7da3330c31ae0a691146081cab4896e31043c96a2ff8f930f6443173b18d\",\n        \"size\": 402931525\n    },\n    \"ConstructionObstacle_Town12_Route2514_Weather12.tar.gz\": {\n        \"sha256\": \"5c961f87756ac411d9860819d93210d3a19a699352b96cc56cd46ecf3d2229d0\",\n        \"size\": 249926562\n    },\n    \"ConstructionObstacle_Town12_Route2515_Weather13.tar.gz\": {\n        \"sha256\": \"0b7493f3b054e00f6b8836f3b21a079256f408bad96bc5bec511f7801c0719ca\",\n        \"size\": 235612607\n    },\n    \"ConstructionObstacle_Town12_Route2516_Weather14.tar.gz\": {\n        \"sha256\": \"45cbcdad1291ebf4165998f071792286d89b734953945680d10b938d91acfbfe\",\n        \"size\": 214022939\n    },\n    \"ConstructionObstacle_Town12_Route2520_Weather18.tar.gz\": {\n        \"sha256\": \"3078656f097bc3de036df6bef022e900c3a36ace24787fe501af89bc3add570e\",\n        \"size\": 196497792\n    },\n    \"ConstructionObstacle_Town12_Route2522_Weather20.tar.gz\": {\n        \"sha256\": \"085510edcf963eede405780491269ee1f49ac386ac0c111a978083c08a39dfd7\",\n        \"size\": 382218210\n    },\n    \"ConstructionObstacle_Town12_Route2523_Weather21.tar.gz\": {\n        \"sha256\": \"d0813235f24a28007ce137882a961b6913bc5732d1a487a35cf8856c809f39c1\",\n        \"size\": 331460252\n    },\n    \"ConstructionObstacle_Town13_Route3284_Weather3.tar.gz\": {\n        \"sha256\": \"38ded5b1467cec56c7cb7f6c66fd1eae7bb872268784d69a7da50f88fccb7f73\",\n        \"size\": 699861920\n    },\n    \"ConstructionObstacle_Town13_Route3286_Weather5.tar.gz\": {\n        \"sha256\": \"15488f3dd5de4c5382fa3a332d2c1c234661c227e37c215860f7fd8fd833f7e9\",\n        \"size\": 524680275\n    },\n    \"ConstructionObstacle_Town13_Route3287_Weather6.tar.gz\": {\n        \"sha256\": \"5c425a8d4ef7955506a87265a057e9759d7c6ca16f19f84d3b4c8f4ec84de296\",\n        \"size\": 507075204\n    },\n    \"ConstructionObstacle_Town13_Route3289_Weather8.tar.gz\": {\n        \"sha256\": \"80c08ff34fc547d00c8a9d7808c36366f763d8656ee47722d8dffac7e1e5f826\",\n        \"size\": 514770364\n    },\n    \"ConstructionObstacle_Town13_Route3291_Weather10.tar.gz\": {\n        \"sha256\": \"7db75a62c693147b28902b4178f5edcbbf93fe975bb7361d30e1205cfbd253d2\",\n        \"size\": 307722786\n    },\n    \"ConstructionObstacle_Town13_Route3292_Weather11.tar.gz\": {\n        \"sha256\": \"9e1f31facdd78b7ea6f4acd5c80a6f3bb9b99613a75a1f1680f52c40810d0bcb\",\n        \"size\": 404285182\n    },\n    \"ConstructionObstacle_Town13_Route3293_Weather12.tar.gz\": {\n        \"sha256\": \"01588fc9c4a40da191dbf130b173adfceec2032cf672aaaba7d81b8d2c6adab4\",\n        \"size\": 513443124\n    },\n    \"ConstructionObstacle_Town13_Route3295_Weather14.tar.gz\": {\n        \"sha256\": \"a2db71fe082f2a36cef6109ff0a9c313486214f920b5978b13c0e1601cacead0\",\n        \"size\": 693154751\n    },\n    \"ConstructionObstacle_Town13_Route3296_Weather15.tar.gz\": {\n        \"sha256\": \"f67e57dd90dcc9d76591bd24d9064126bc5fef67dfb05be1298038d6d4f5a986\",\n        \"size\": 708914861\n    },\n    \"ConstructionObstacle_Town13_Route3297_Weather8.tar.gz\": {\n        \"sha256\": \"cb80c3e135574d2fd2044599e6f8b3f877c643de63aec748eb988cf452f82a88\",\n        \"size\": 693129679\n    },\n    \"ConstructionObstacle_Town13_Route3299_Weather18.tar.gz\": {\n        \"sha256\": \"dcbd5c1b1d2e8201e7cc8cfd69537effbd0d852cf0ce0ba143225b7282397ab9\",\n        \"size\": 767997872\n    },\n    \"ConstructionObstacle_Town13_Route3300_Weather19.tar.gz\": {\n        \"sha256\": \"8de7752b29614e9112acd1e59319db3e0fb32dccfe6cdc11bada5be2f8c68100\",\n        \"size\": 408269615\n    },\n    \"ConstructionObstacle_Town13_Route3302_Weather21.tar.gz\": {\n        \"sha256\": \"ed7ec0437c866adde50569d623798e2edb0736b45414df675456942145788c27\",\n        \"size\": 311545673\n    },\n    \"ControlLoss_Town02_Route24784_Weather13.tar.gz\": {\n        \"sha256\": \"73d3d1e559cf1ddd8eaeea974b07815fc1f0751aca019aa64d6b2978426a4009\",\n        \"size\": 128679745\n    },\n    \"ControlLoss_Town03_Route26595_Weather7.tar.gz\": {\n        \"sha256\": \"082875b49428b5e1a5ab7af6d6fb17da8775884e5507c40a989a3e14faca6b29\",\n        \"size\": 828918918\n    },\n    \"ControlLoss_Town03_Route26600_Weather12.tar.gz\": {\n        \"sha256\": \"9833bcc385cb6cfc80d967132312fbba9117051de8487da89d92b8daa10186c8\",\n        \"size\": 2238598737\n    },\n    \"ControlLoss_Town03_Route26655_Weather23.tar.gz\": {\n        \"sha256\": \"38cdd4ab172b02ac3b23e4cf4e7004833a841cc4c7b43db9aecc4f39553f510a\",\n        \"size\": 433268510\n    },\n    \"ControlLoss_Town03_Route26665_Weather8.tar.gz\": {\n        \"sha256\": \"0475757dfa6515bf3c36bdfeffee02ee82cbc1b09d27611a5c4d82695dcb5e98\",\n        \"size\": 454223655\n    },\n    \"ControlLoss_Town04_Route26599_Weather11.tar.gz\": {\n        \"sha256\": \"9c794e741f3b67937a1e79d66bc60bfe95e6de814c82a35acf4dd6bd235c9a01\",\n        \"size\": 218623301\n    },\n    \"ControlLoss_Town05_Route26706_Weather2.tar.gz\": {\n        \"sha256\": \"095adf420c3557abd474b8e145a50baff9c45bb382e5f8340380bdd1db46c28c\",\n        \"size\": 274460680\n    },\n    \"ControlLoss_Town05_Route26746_Weather22.tar.gz\": {\n        \"sha256\": \"99a717ccbb27c9daea8a8856c89c4fe4ae99c1760b2bbd1c61f4c7da61c652c1\",\n        \"size\": 247117722\n    },\n    \"ControlLoss_Town05_Route26751_Weather1.tar.gz\": {\n        \"sha256\": \"df1f97ac21758be6e7ba46889909b3b097ddf40dbf8e9d647a71a3d8c5ce0cae\",\n        \"size\": 415564008\n    },\n    \"ControlLoss_Town05_Route26786_Weather14.tar.gz\": {\n        \"sha256\": \"f729b02e51fb4c16447d77fc27f05178fcf5a4c941748e35b665c00559375e81\",\n        \"size\": 194081636\n    },\n    \"ControlLoss_Town05_Route26791_Weather21.tar.gz\": {\n        \"sha256\": \"2fb4e57d573c5814b10fbe5db18ce6055afa665414fca8fb44247581c03313cf\",\n        \"size\": 227560751\n    },\n    \"ControlLoss_Town10HD_Route24340_Weather6.tar.gz\": {\n        \"sha256\": \"df4c0c9f30fb75436ce525d478785da8a6e63759b79d2046d4d1602bf1be00b1\",\n        \"size\": 322202454\n    },\n    \"ControlLoss_Town11_Route26418_Weather14.tar.gz\": {\n        \"sha256\": \"a4f3d06242ebea8e81ff27256dfb9aca4840ea46f9c22509e292ff6e221cf6f7\",\n        \"size\": 96714183\n    },\n    \"ControlLoss_Town11_Route26432_Weather5.tar.gz\": {\n        \"sha256\": \"3ac43ee7c8550f1bd68ee5d8fe94d480f1e0f3c7940b7cab200d82b1de2124e0\",\n        \"size\": 127906808\n    },\n    \"CrossingBicycleFlow_Town12_Route2304_Weather10.tar.gz\": {\n        \"sha256\": \"4c8d0c088d5640a0d0a6e7b2fdf8cb0eba68845bf656a8770b6e811dfaa351f8\",\n        \"size\": 466000647\n    },\n    \"CrossingBicycleFlow_Town12_Route2305_Weather11.tar.gz\": {\n        \"sha256\": \"cee115505c3b490e8b824db842493aeb17b6f655b85ab1b052057fa96d86c0ee\",\n        \"size\": 369782935\n    },\n    \"CrossingBicycleFlow_Town12_Route2306_Weather12.tar.gz\": {\n        \"sha256\": \"e71ff14fd644f9c2c189d285f61e848fd57ac61ba99bf112ff54bedfc3515f94\",\n        \"size\": 318903527\n    },\n    \"CrossingBicycleFlow_Town12_Route2307_Weather13.tar.gz\": {\n        \"sha256\": \"a1a7a9b235baff01a6dfa76090078596c9494da0440cc259667ca3af9e963085\",\n        \"size\": 309300746\n    },\n    \"CrossingBicycleFlow_Town12_Route2308_Weather14.tar.gz\": {\n        \"sha256\": \"b1128f4fe6091392fc8cc6b5d2b44b759244e25a0685636959a387046fb24584\",\n        \"size\": 384229123\n    },\n    \"CrossingBicycleFlow_Town12_Route2309_Weather15.tar.gz\": {\n        \"sha256\": \"eb86aba50b669fd3473e678fcc7a06161be676267cb41395610a2266ad0c8cfa\",\n        \"size\": 424103377\n    },\n    \"CrossingBicycleFlow_Town12_Route2310_Weather8.tar.gz\": {\n        \"sha256\": \"778468cefbeb372ae3e550a0f4c9a7e70a66072612ff6e0c28bf42349a71f657\",\n        \"size\": 467911456\n    },\n    \"CrossingBicycleFlow_Town12_Route2311_Weather9.tar.gz\": {\n        \"sha256\": \"f54171a8d398b2e85271e00e96c20cef62e7148cfc66e90c59eac0e0bc8071e9\",\n        \"size\": 337817765\n    },\n    \"CrossingBicycleFlow_Town12_Route2313_Weather19.tar.gz\": {\n        \"sha256\": \"72f9b396f689513d42ff7f7417bcad5506a834ca5e8f1b9695c35034e93a45f9\",\n        \"size\": 513117425\n    },\n    \"CrossingBicycleFlow_Town12_Route2314_Weather20.tar.gz\": {\n        \"sha256\": \"bbbfbb559819e23e36888be763632864b48bbe61f3e31b8af82133ee594b1105\",\n        \"size\": 441765553\n    },\n    \"CrossingBicycleFlow_Town12_Route2315_Weather21.tar.gz\": {\n        \"sha256\": \"604ce8cbc131393f6b4cba9d23aee13d8eb7a9a4847e4efd699ec77a65e9376b\",\n        \"size\": 407151556\n    },\n    \"CrossingBicycleFlow_Town12_Route2316_Weather22.tar.gz\": {\n        \"sha256\": \"74205b44c36f0bb7bf598a7e3687c8a319a70b5260119d7aa652747ef495db17\",\n        \"size\": 886741059\n    },\n    \"CrossingBicycleFlow_Town12_Route2318_Weather23.tar.gz\": {\n        \"sha256\": \"71885a9e2c99cd21e1744cccfc4d1175052a386affc70aff4004e7dc3e7d440c\",\n        \"size\": 408438820\n    },\n    \"CrossingBicycleFlow_Town12_Route2321_Weather1.tar.gz\": {\n        \"sha256\": \"4183755d29f9b63fb202e5143f837f37b21f999a93d05f8f43f3ae2bf8318515\",\n        \"size\": 541492882\n    },\n    \"CrossingBicycleFlow_Town12_Route2322_Weather2.tar.gz\": {\n        \"sha256\": \"8d7815f75e64b5cf4e41810b96076da6f671bbdf52c4f8677149c1c0f472b7e9\",\n        \"size\": 754598561\n    },\n    \"CrossingBicycleFlow_Town12_Route3084_Weather10.tar.gz\": {\n        \"sha256\": \"fbae3661758aaaa599a834c618860997ea7256d69f1ef3b8367c887a094cf096\",\n        \"size\": 522325738\n    },\n    \"CrossingBicycleFlow_Town12_Route3085_Weather11.tar.gz\": {\n        \"sha256\": \"84424cdffe58a3e22aeb16fd0616e8f56fa4653dff3503fa8db7be3c066ffe3f\",\n        \"size\": 311996266\n    },\n    \"CrossingBicycleFlow_Town12_Route3086_Weather12.tar.gz\": {\n        \"sha256\": \"ebe42abf14c97180fa1938a998cbb601c2af81b8c86d154fc563f08a665d7ba9\",\n        \"size\": 402050341\n    },\n    \"CrossingBicycleFlow_Town12_Route3087_Weather13.tar.gz\": {\n        \"sha256\": \"c3e3eb394ab93fa5f5ebfba661a305c371754e96d0b1de341449a0a0ba51e28e\",\n        \"size\": 581810425\n    },\n    \"CrossingBicycleFlow_Town12_Route3090_Weather8.tar.gz\": {\n        \"sha256\": \"a69516493700c7e9d1d84433788a29f3bc7f86b949e7b24df8ca12c7bc09b963\",\n        \"size\": 409314737\n    },\n    \"CrossingBicycleFlow_Town12_Route3091_Weather9.tar.gz\": {\n        \"sha256\": \"91507edc19180e90582a06e3225b06c5d82e57bf5083a171b7f792924ab5af5a\",\n        \"size\": 284592432\n    },\n    \"CrossingBicycleFlow_Town12_Route3093_Weather19.tar.gz\": {\n        \"sha256\": \"6f7c7d9593cb43bdeb9d9f4744294a298af7a3bd12133650b12570966a451c88\",\n        \"size\": 887696266\n    },\n    \"CrossingBicycleFlow_Town12_Route3094_Weather20.tar.gz\": {\n        \"sha256\": \"2cb5bfb8b5df210c07bd4b3e2fa88c2390233071ba7586230152a04bf966c09a\",\n        \"size\": 864970503\n    },\n    \"CrossingBicycleFlow_Town12_Route3095_Weather21.tar.gz\": {\n        \"sha256\": \"4f07b81c71205f63aac147b23e5ee093b518242f2a0892c2c7d47b7f9cc755a2\",\n        \"size\": 825757251\n    },\n    \"CrossingBicycleFlow_Town12_Route3096_Weather22.tar.gz\": {\n        \"sha256\": \"b93fac6abc170e6d4a9759f2a57ee5a152db9d2bf1fdd381484d5ef69d95b685\",\n        \"size\": 416482342\n    },\n    \"CrossingBicycleFlow_Town12_Route3098_Weather23.tar.gz\": {\n        \"sha256\": \"5725fb2d131d818782a6ed9c63b3c634c460a01b094e08491f3ab1a9910e331f\",\n        \"size\": 354960097\n    },\n    \"CrossingBicycleFlow_Town12_Route3099_Weather25.tar.gz\": {\n        \"sha256\": \"03f9d55c551a1e0ee6078ac79e8f11eca19137da1f138b49f6b7b4dbbe96a5d0\",\n        \"size\": 391953111\n    },\n    \"CrossingBicycleFlow_Town12_Route3100_Weather0.tar.gz\": {\n        \"sha256\": \"31e27a2334485d3e23a416e60e6a8a5317dce9448587f901133ce98a592fb31d\",\n        \"size\": 451146041\n    },\n    \"CrossingBicycleFlow_Town12_Route3101_Weather1.tar.gz\": {\n        \"sha256\": \"d515ee3a9be78b6b98c6061a1e3d366076e7706de3a7a4fda2f9b59e9d10f17b\",\n        \"size\": 426169598\n    },\n    \"CrossingBicycleFlow_Town12_Route3102_Weather2.tar.gz\": {\n        \"sha256\": \"46d198fd18d440701b42d40359695d2547d22432858084f34c958302f3b8846f\",\n        \"size\": 1000854836\n    },\n    \"CrossingBicycleFlow_Town12_Route3103_Weather3.tar.gz\": {\n        \"sha256\": \"906e9b9fb00ebb715c5f9326c44f1a33fda869d44906a4be724c1b9cdfa57420\",\n        \"size\": 446728034\n    },\n    \"CrossingBicycleFlow_Town12_Route35363_Weather0.tar.gz\": {\n        \"sha256\": \"2832b2fb13adc4799d1a772084540606b6ae42682ac40c987e38772e21928482\",\n        \"size\": 439602532\n    },\n    \"CrossingBicycleFlow_Town12_Route35365_Weather0.tar.gz\": {\n        \"sha256\": \"5d20d0e8129690a3c6f00cc955364bf6ccb96b74343677026c3993a27178fecf\",\n        \"size\": 412199020\n    },\n    \"CrossingBicycleFlow_Town12_Route35370_Weather0.tar.gz\": {\n        \"sha256\": \"d3e04e2134b0c096b3e29fb2a7b44275d50a2bc6d9fde025274afb494cf45f1f\",\n        \"size\": 448038478\n    },\n    \"CrossingBicycleFlow_Town12_Route35371_Weather0.tar.gz\": {\n        \"sha256\": \"9933245a218470f6900008ed155e2d5e4c9272ffbf50072d73d7f70a551fa672\",\n        \"size\": 396295204\n    },\n    \"CrossingBicycleFlow_Town12_Route35372_Weather0.tar.gz\": {\n        \"sha256\": \"bb05ab30c6482cecb908936ff4b8701ef24e72a7cab7094b7f98b584cbd92e8b\",\n        \"size\": 436955189\n    },\n    \"CrossingBicycleFlow_Town12_Route35373_Weather0.tar.gz\": {\n        \"sha256\": \"3ce5d04dc11922f1206b805ec69897f82b466ba3709b34789657d922612e482b\",\n        \"size\": 723327734\n    },\n    \"CrossingBicycleFlow_Town12_Route35374_Weather0.tar.gz\": {\n        \"sha256\": \"e2d5045a49ba205cca06fb8ff2f3a18ab99719c0112cadfe27cd0cb45229aff7\",\n        \"size\": 428683935\n    },\n    \"CrossingBicycleFlow_Town12_Route35375_Weather0.tar.gz\": {\n        \"sha256\": \"9ab1dea344dcc2c4cad70b65e24e1acdddb5816d0e92496dbf6c8d66f9a7dc3c\",\n        \"size\": 444516218\n    },\n    \"CrossingBicycleFlow_Town12_Route35377_Weather0.tar.gz\": {\n        \"sha256\": \"bf7bcbd4382e360a9ef749a04df06296548526da173641eff52a4cd039451047\",\n        \"size\": 153502250\n    },\n    \"CrossingBicycleFlow_Town12_Route35379_Weather0.tar.gz\": {\n        \"sha256\": \"de1943f696a7a24faa5b3bf953ff7d32b1c00e14a04ba934c8a8113d0949d3ff\",\n        \"size\": 446561517\n    },\n    \"CrossingBicycleFlow_Town12_Route35380_Weather0.tar.gz\": {\n        \"sha256\": \"a4d43b71a67e8822bfd9bd8a06be8b4c0218f1e6e2663940b0813278c15ead15\",\n        \"size\": 412651894\n    },\n    \"CrossingBicycleFlow_Town12_Route35382_Weather0.tar.gz\": {\n        \"sha256\": \"c47a06b577a708b62b3efd14a872a0cb1112ad3b0fc9021725a145f0d5c452e5\",\n        \"size\": 445835376\n    },\n    \"CrossingBicycleFlow_Town12_Route35385_Weather0.tar.gz\": {\n        \"sha256\": \"5255b23dcc50f170bca000c6940c9ffd492aade53ce56d8428857d4e5356624b\",\n        \"size\": 447259050\n    },\n    \"CrossingBicycleFlow_Town12_Route35386_Weather0.tar.gz\": {\n        \"sha256\": \"6ffb522548db9f0dc3d3a8960f0e718af41a36ae26b1558c6cb880b1860bbfdb\",\n        \"size\": 474177579\n    },\n    \"CrossingBicycleFlow_Town12_Route35387_Weather0.tar.gz\": {\n        \"sha256\": \"7f5c4bc11ba95c969e4d66830fda51cf7104703d8280cce2058ce2ec81fe9a13\",\n        \"size\": 425640940\n    },\n    \"CrossingBicycleFlow_Town12_Route35390_Weather0.tar.gz\": {\n        \"sha256\": \"9be6e0d7dce8164d60eb69140d083079da43c39a6a09f1e73432b6a08b93b229\",\n        \"size\": 474146893\n    },\n    \"CrossingBicycleFlow_Town12_Route35392_Weather0.tar.gz\": {\n        \"sha256\": \"65eb097c515499060642ed0ebcf1b78bb1d085d56b5f8fa8cee793db5b8fde9d\",\n        \"size\": 513922153\n    },\n    \"CrossingBicycleFlow_Town12_Route35393_Weather0.tar.gz\": {\n        \"sha256\": \"ba742fe5f79df4096d34cf12d50c94c753eeafc6bc117a265cd1bff3a12349c7\",\n        \"size\": 546959666\n    },\n    \"CrossingBicycleFlow_Town12_Route35406_Weather0.tar.gz\": {\n        \"sha256\": \"da69bf899dccaeb558ac8ee88e14f871f43324840deb9f7425050d53b318eb6b\",\n        \"size\": 418753506\n    },\n    \"CrossingBicycleFlow_Town12_Route35407_Weather0.tar.gz\": {\n        \"sha256\": \"994c7b2c580014db3709aa74ebade6839d6d2bda15d2270087ed49a579fe8384\",\n        \"size\": 464015534\n    },\n    \"CrossingBicycleFlow_Town12_Route35409_Weather0.tar.gz\": {\n        \"sha256\": \"b2c3d578c57b34d77e431f41b7a81ddec589f0b041f3180609ee27c7324d73fd\",\n        \"size\": 456740089\n    },\n    \"CrossingBicycleFlow_Town12_Route35410_Weather0.tar.gz\": {\n        \"sha256\": \"b2d56412bf74a93529efce20dc6a08194070dcdf1748e837418f22be7cea6540\",\n        \"size\": 434086560\n    },\n    \"CrossingBicycleFlow_Town12_Route35411_Weather0.tar.gz\": {\n        \"sha256\": \"6c80e1606556252094d9b273d3f94eca0e5c343b656fe8a0b1b176924bb908ce\",\n        \"size\": 467817516\n    },\n    \"CrossingBicycleFlow_Town12_Route35414_Weather0.tar.gz\": {\n        \"sha256\": \"e2137f7ee48b12267d79e8cc3e4e7819f564f48d065b5e156293560d512ab65c\",\n        \"size\": 489287233\n    },\n    \"CrossingBicycleFlow_Town12_Route35415_Weather0.tar.gz\": {\n        \"sha256\": \"589ae359e734f97ddd69c63c7fe6bd65988139802cd4afaa561272bc1e3121a1\",\n        \"size\": 435032498\n    },\n    \"CrossingBicycleFlow_Town12_Route35421_Weather0.tar.gz\": {\n        \"sha256\": \"b1c97e124c8a338582f7f220c7195d93bfb8b1b35901e820c66c4bab43cd01b2\",\n        \"size\": 442547929\n    },\n    \"CrossingBicycleFlow_Town12_Route35422_Weather0.tar.gz\": {\n        \"sha256\": \"7cebcf0b57130008a5cc2d45cd9bf869a7cd46c76a622733d1a4ff3da00d2c84\",\n        \"size\": 933306254\n    },\n    \"CrossingBicycleFlow_Town12_Route35424_Weather1.tar.gz\": {\n        \"sha256\": \"94a9252220950c824cd87d2592eae1ee054087618bed8751a799ca09a4748c43\",\n        \"size\": 419609558\n    },\n    \"CrossingBicycleFlow_Town12_Route35425_Weather1.tar.gz\": {\n        \"sha256\": \"ab7f551043a767e022a886b0cb474abfa73092b60cf89dab550c07a0c6721fda\",\n        \"size\": 453159208\n    },\n    \"CrossingBicycleFlow_Town12_Route35428_Weather1.tar.gz\": {\n        \"sha256\": \"84e4b1aab7f33cbfad1771c91002c8eb252494848f6f2c1491b14834963286b2\",\n        \"size\": 423987383\n    },\n    \"CrossingBicycleFlow_Town12_Route35430_Weather1.tar.gz\": {\n        \"sha256\": \"77537a12e8c15f192644a47d4d41a92692312fedc517abd79c210f69eb014aab\",\n        \"size\": 444778695\n    },\n    \"CrossingBicycleFlow_Town12_Route35431_Weather1.tar.gz\": {\n        \"sha256\": \"5ce8e6915803e6e4f3ec615595d4f041a09c2302c7c764c338f858b3d052704c\",\n        \"size\": 402533613\n    },\n    \"CrossingBicycleFlow_Town12_Route35525_Weather2.tar.gz\": {\n        \"sha256\": \"4b2867f14e9bc5d4e77450ea7bf4de1524b651030a26d5379178eba4cb64053c\",\n        \"size\": 448709311\n    },\n    \"CrossingBicycleFlow_Town12_Route35527_Weather2.tar.gz\": {\n        \"sha256\": \"b802599dbffe7035a2fbb7a81541cf6a295de321a01086bd075b8637d073db02\",\n        \"size\": 465026053\n    },\n    \"CrossingBicycleFlow_Town12_Route35528_Weather2.tar.gz\": {\n        \"sha256\": \"4d80ec8c4b74ec19c42bec054a776b4fd1314fa78ba2bc04af04c86323753691\",\n        \"size\": 473593608\n    },\n    \"CrossingBicycleFlow_Town12_Route35534_Weather2.tar.gz\": {\n        \"sha256\": \"3e4a4c2120cd097f430791d8013dcb45c34a7e9a23bc78e27e758761202ee717\",\n        \"size\": 475502810\n    },\n    \"CrossingBicycleFlow_Town12_Route35535_Weather2.tar.gz\": {\n        \"sha256\": \"9d0a647b82bcc51f9416d800697a271ca575a7dd6af43ee63ab59657fafd6e9e\",\n        \"size\": 438878502\n    },\n    \"CrossingBicycleFlow_Town12_Route35537_Weather2.tar.gz\": {\n        \"sha256\": \"0ef3eb9a9d6b7ba0e3a996a68de1462f98bf78603c60b036d688eff1bfb47f84\",\n        \"size\": 527848674\n    },\n    \"CrossingBicycleFlow_Town12_Route35542_Weather2.tar.gz\": {\n        \"sha256\": \"4fc8c3c81099768aaa69924f463d235cf1c85708c00e53d8eafc54f7a02e66f3\",\n        \"size\": 914494609\n    },\n    \"CrossingBicycleFlow_Town12_Route35545_Weather3.tar.gz\": {\n        \"sha256\": \"d379e8d18c60d16b6aa2d550f91a15cb517df9ca22ebabb956d31315b279937c\",\n        \"size\": 399500243\n    },\n    \"CrossingBicycleFlow_Town12_Route35548_Weather3.tar.gz\": {\n        \"sha256\": \"7f47aa0fea672148dd062f9b43212c3b107513a258c075e8cc38e7b6de04fecf\",\n        \"size\": 400267949\n    },\n    \"CrossingBicycleFlow_Town12_Route35549_Weather3.tar.gz\": {\n        \"sha256\": \"d8fa1a27c1dac4b7ac14cc82aae6ca2b339138f43cf2b9dd0d934ac050401a23\",\n        \"size\": 551731192\n    },\n    \"CrossingBicycleFlow_Town12_Route35552_Weather3.tar.gz\": {\n        \"sha256\": \"eec8b0e4126bd6190e69af7236d5f9f0226c3c732524ff5143353000e520b4de\",\n        \"size\": 409992914\n    },\n    \"CrossingBicycleFlow_Town12_Route35553_Weather3.tar.gz\": {\n        \"sha256\": \"f18995390c0c6d2380ed2eabc0eb5cbd93925386c22fb8d0a5aa1c7ee21f69eb\",\n        \"size\": 681539460\n    },\n    \"CrossingBicycleFlow_Town12_Route35559_Weather3.tar.gz\": {\n        \"sha256\": \"f8fca7ae2b4b69c07a5aa593f5cf48883e78be7bc8bfd4f257022a499437de85\",\n        \"size\": 436679903\n    },\n    \"CrossingBicycleFlow_Town12_Route35561_Weather3.tar.gz\": {\n        \"sha256\": \"663e2b6e69f3c2b2d7a82466247a3422a83017d3ec8756e33c6a7293eea83e0a\",\n        \"size\": 469018109\n    },\n    \"CrossingBicycleFlow_Town12_Route35564_Weather3.tar.gz\": {\n        \"sha256\": \"fb1a134fad414446dcb6caa1e3e28ffa3ddc575b7531b843e57e621b3ddf5710\",\n        \"size\": 362731702\n    },\n    \"CrossingBicycleFlow_Town12_Route35566_Weather3.tar.gz\": {\n        \"sha256\": \"b761298f0e28a3755bad98721e2b35b21d77b390cba1ac36060343d40aa02a47\",\n        \"size\": 455982345\n    },\n    \"CrossingBicycleFlow_Town12_Route35567_Weather3.tar.gz\": {\n        \"sha256\": \"079d3beea9eb120312b4f7dcf2e3e9e828a3ef9144fc87f88befd28ca4590673\",\n        \"size\": 389728821\n    },\n    \"CrossingBicycleFlow_Town12_Route35569_Weather3.tar.gz\": {\n        \"sha256\": \"56eb97ac325dcceda14767440b623d69be1904b36a845c87f5585cdbd618ea72\",\n        \"size\": 665035485\n    },\n    \"CrossingBicycleFlow_Town12_Route35571_Weather3.tar.gz\": {\n        \"sha256\": \"957dd9e77495500024d058e509d70e8375c794d3a63007481fc1eb84323cd676\",\n        \"size\": 434162395\n    },\n    \"CrossingBicycleFlow_Town12_Route35577_Weather3.tar.gz\": {\n        \"sha256\": \"4bc7037a82e7eae466e0fea7200f24f2d7706fa63b61bd9e6475cb9f2437a69f\",\n        \"size\": 381015899\n    },\n    \"CrossingBicycleFlow_Town12_Route35580_Weather3.tar.gz\": {\n        \"sha256\": \"04e642a2b6156a49d14c43d9141e994819885fb47f3522ff4529feef54ee98d5\",\n        \"size\": 388358339\n    },\n    \"CrossingBicycleFlow_Town12_Route35581_Weather3.tar.gz\": {\n        \"sha256\": \"2d52e6da1f21952d1352f117ad0f18923382872a3219e430ffd70bfd40e9670d\",\n        \"size\": 482584790\n    },\n    \"CrossingBicycleFlow_Town12_Route35583_Weather3.tar.gz\": {\n        \"sha256\": \"3dce88e6edb76882a419129c03463bd4b8fbcaac6c5ba0a6fa59c6cc8edd4a23\",\n        \"size\": 512016011\n    },\n    \"CrossingBicycleFlow_Town12_Route35585_Weather3.tar.gz\": {\n        \"sha256\": \"246a8d258c329f5e4aff8759bf65986fbcb614886f7f36d80127e2d99eb26168\",\n        \"size\": 431367660\n    },\n    \"CrossingBicycleFlow_Town12_Route35595_Weather3.tar.gz\": {\n        \"sha256\": \"f25448e25302fd1df26959408d518c5e77cf7f1561f5a47e400f66873eedbd59\",\n        \"size\": 434394980\n    },\n    \"CrossingBicycleFlow_Town12_Route35597_Weather3.tar.gz\": {\n        \"sha256\": \"342fce9b6ade05c4223e48e8f5c1136728d09fbd9651549d5898b21674b8fe1a\",\n        \"size\": 515030571\n    },\n    \"CrossingBicycleFlow_Town12_Route35599_Weather3.tar.gz\": {\n        \"sha256\": \"3a8f4350a5f24b3f226ab3037b26a17155b2558ac5cb75dc60c80b3fb929c1b4\",\n        \"size\": 645373695\n    },\n    \"CrossingBicycleFlow_Town12_Route35602_Weather3.tar.gz\": {\n        \"sha256\": \"47fc00c227ad25b6d75d3810f9e812a392f27103d2310282d3b08ae6f62f674a\",\n        \"size\": 882017244\n    },\n    \"CrossingBicycleFlow_Town12_Route36561_Weather22.tar.gz\": {\n        \"sha256\": \"417b1417c2225caa7380e2bd9430ba577ef3b0b754c28ebd6d9fbbc6a1fb7cee\",\n        \"size\": 389884290\n    },\n    \"CrossingBicycleFlow_Town12_Route36562_Weather22.tar.gz\": {\n        \"sha256\": \"624aaa7240724a42d0d9678a1879b598c653cd4da275c9be813397ebb1217357\",\n        \"size\": 812156992\n    },\n    \"CrossingBicycleFlow_Town12_Route36563_Weather23.tar.gz\": {\n        \"sha256\": \"b6273dfd09f1b1b99f318617c51d1179302cccd3339c13e2f639919d369c1250\",\n        \"size\": 373287519\n    },\n    \"CrossingBicycleFlow_Town12_Route36566_Weather23.tar.gz\": {\n        \"sha256\": \"a01d51ce81d7896833bb6c565e17247ffb138a765ee9e3b57a3714b7268f1be9\",\n        \"size\": 373642745\n    },\n    \"CrossingBicycleFlow_Town12_Route36568_Weather23.tar.gz\": {\n        \"sha256\": \"c95c290f92d87bf28d3bccab04d1cb04d1a8c105805c105ff311c3cf7b0f769a\",\n        \"size\": 337690168\n    },\n    \"CrossingBicycleFlow_Town12_Route36570_Weather23.tar.gz\": {\n        \"sha256\": \"b3d50bea4516d6f27703d2930a4a58aceaeddd941aa6dc63695a2c98db4115f2\",\n        \"size\": 356837222\n    },\n    \"CrossingBicycleFlow_Town12_Route36573_Weather23.tar.gz\": {\n        \"sha256\": \"f4404266daf39093b91ffce43b0ffdb1155d2fc3606822d8a29117a10e145163\",\n        \"size\": 603958120\n    },\n    \"CrossingBicycleFlow_Town12_Route36574_Weather23.tar.gz\": {\n        \"sha256\": \"4df937586a1de2ab0c108d318bb4d0141b2dd5d9d9d6823331d13e29e522820f\",\n        \"size\": 345760823\n    },\n    \"CrossingBicycleFlow_Town12_Route36576_Weather23.tar.gz\": {\n        \"sha256\": \"95f25f3bf3546329ce5fa2251cd432e555fdb12ebaa1a780fe71ab7f6557e0fc\",\n        \"size\": 386361513\n    },\n    \"CrossingBicycleFlow_Town12_Route36577_Weather23.tar.gz\": {\n        \"sha256\": \"d82f75dd608e1ae97090656ad8c549caf903dd0c3af042278340c6944b293d32\",\n        \"size\": 114632227\n    },\n    \"CrossingBicycleFlow_Town12_Route36579_Weather23.tar.gz\": {\n        \"sha256\": \"3727e5981e4ae4f6ef6cec89a8e59c2e132bae6387b0f3e63e0b53c77219bbf7\",\n        \"size\": 364241893\n    },\n    \"CrossingBicycleFlow_Town12_Route36580_Weather23.tar.gz\": {\n        \"sha256\": \"6a574334055598f661a836281ff4fc7a9ee4d019b28a485f05ab7720bd608518\",\n        \"size\": 349862035\n    },\n    \"CrossingBicycleFlow_Town12_Route36581_Weather23.tar.gz\": {\n        \"sha256\": \"6b81bafdb89b0657d8e857608bb778e6e69a199d31939ce18fcaadf7a7be2899\",\n        \"size\": 385849752\n    },\n    \"CrossingBicycleFlow_Town12_Route36584_Weather23.tar.gz\": {\n        \"sha256\": \"fd05971219f20c527672607368a4e1257d18a67410e6aef6693ce2db8780f702\",\n        \"size\": 314802559\n    },\n    \"CrossingBicycleFlow_Town12_Route36589_Weather23.tar.gz\": {\n        \"sha256\": \"bf866a5f0195fcfe7199df1982ec0ad9b55f53c40564c567b47ff45305b9ace8\",\n        \"size\": 590040702\n    },\n    \"CrossingBicycleFlow_Town12_Route36590_Weather23.tar.gz\": {\n        \"sha256\": \"9de1824edd78246ff3452e39b241f5684601177fc9dcffd2aca5d0044e2eaa24\",\n        \"size\": 395051117\n    },\n    \"CrossingBicycleFlow_Town12_Route36592_Weather23.tar.gz\": {\n        \"sha256\": \"5836aa19d25cfd6113ff45c39c86994cf3167c88625be71ef8e7cad02cca64d4\",\n        \"size\": 434902899\n    },\n    \"CrossingBicycleFlow_Town12_Route36593_Weather23.tar.gz\": {\n        \"sha256\": \"4079e1eab1e2c4a7fee4fcf35cfa161ee744e4db63b71415b918f200c10f730e\",\n        \"size\": 427358702\n    },\n    \"CrossingBicycleFlow_Town12_Route36600_Weather23.tar.gz\": {\n        \"sha256\": \"2970ca6c7af8c195257eda78d7998a2f41d7bc8476282f1bf20a8d97986989a8\",\n        \"size\": 332908331\n    },\n    \"CrossingBicycleFlow_Town12_Route36602_Weather23.tar.gz\": {\n        \"sha256\": \"ddc2b91a17d404b083c686ab4f5adbea8efb98b40fd8005674df8b48802f8447\",\n        \"size\": 441579231\n    },\n    \"CrossingBicycleFlow_Town12_Route36605_Weather23.tar.gz\": {\n        \"sha256\": \"dc96736a066e5ac213a92b97f586d4794bffdf5eaab6ceb8700983f070038978\",\n        \"size\": 370928645\n    },\n    \"CrossingBicycleFlow_Town12_Route36606_Weather23.tar.gz\": {\n        \"sha256\": \"1dd525b09dcd0a97d93c61498a39807b7317c6e88d5e2121800cab99a86f91f1\",\n        \"size\": 342949261\n    },\n    \"CrossingBicycleFlow_Town12_Route36609_Weather23.tar.gz\": {\n        \"sha256\": \"f506594fade604747d484089cb890a1ec00ce2ded7a210e677d95060214f0737\",\n        \"size\": 388132110\n    },\n    \"CrossingBicycleFlow_Town12_Route36610_Weather23.tar.gz\": {\n        \"sha256\": \"2a0b40850e07fefec1c3904170a25e2429142ac391f0750a9c94dc9bfc9868f9\",\n        \"size\": 364253902\n    },\n    \"CrossingBicycleFlow_Town12_Route36611_Weather23.tar.gz\": {\n        \"sha256\": \"c3f796cee0538deb7d066071b8ead5bd61648340f4252c66474c3fca1538b90c\",\n        \"size\": 383864613\n    },\n    \"CrossingBicycleFlow_Town12_Route36613_Weather23.tar.gz\": {\n        \"sha256\": \"3c5a35cbbea1d8bf70c6eb763d5d3df5d341cb210a0805ed7f7fb788ba9ad201\",\n        \"size\": 430413439\n    },\n    \"CrossingBicycleFlow_Town12_Route36616_Weather23.tar.gz\": {\n        \"sha256\": \"39d4308b8265892c21f2ba45910c2de632caef627fb07b39b663674c2a47165d\",\n        \"size\": 435529955\n    },\n    \"CrossingBicycleFlow_Town12_Route36621_Weather23.tar.gz\": {\n        \"sha256\": \"41a0bbe73e1f0181d1e73a0154074b773807e0ce1fc391bd7f4168907351e7c8\",\n        \"size\": 362328260\n    },\n    \"CrossingBicycleFlow_Town12_Route36624_Weather25.tar.gz\": {\n        \"sha256\": \"8b90419415c56a7f66d0330704a4afd1e29a03b21bba0c4c40d045d4a753bd66\",\n        \"size\": 307866933\n    },\n    \"CrossingBicycleFlow_Town12_Route36625_Weather25.tar.gz\": {\n        \"sha256\": \"f7c92a0922b07955329ac2351bc428ec1b2713ec2a10045eea99d06c82e24f23\",\n        \"size\": 310723298\n    },\n    \"DynamicObjectCrossing_Town01_Route24221_Weather1.tar.gz\": {\n        \"sha256\": \"b537191b3a580db49deea52b968e723acea15944adfb634a1efba6a76c1ce0e1\",\n        \"size\": 317855932\n    },\n    \"DynamicObjectCrossing_Town01_Route24241_Weather25.tar.gz\": {\n        \"sha256\": \"0f40320f6b80f69cd78faa53008dcea86a0fdc3f3d3f3e19bde94321aaa15882\",\n        \"size\": 297984599\n    },\n    \"DynamicObjectCrossing_Town01_Route24281_Weather18.tar.gz\": {\n        \"sha256\": \"b06fe8d1e3796d8c468f31ca593705d1ed7d1de03a0937461c828076e65f89f0\",\n        \"size\": 287008780\n    },\n    \"DynamicObjectCrossing_Town01_Route24311_Weather26.tar.gz\": {\n        \"sha256\": \"ff9a7c209aa0ea0fff70b72e2042453b7f36a795bc343924395ca5b75e8e6161\",\n        \"size\": 289912537\n    },\n    \"DynamicObjectCrossing_Town01_Route24321_Weather10.tar.gz\": {\n        \"sha256\": \"1593e795729e8baae261ecad454a82debf2f84fa497c3890b91652ecdd41971c\",\n        \"size\": 291522846\n    },\n    \"DynamicObjectCrossing_Town01_Route24341_Weather7.tar.gz\": {\n        \"sha256\": \"45327a8e2ec3d1fbf4f70e9b4f00218614d972f901eda99f29b25e332b606954\",\n        \"size\": 852681089\n    },\n    \"DynamicObjectCrossing_Town01_Route24361_Weather3.tar.gz\": {\n        \"sha256\": \"a5c1c8d1e9e9f22ee7f76ce94144e20ba75f9afbc742b1ab8fd4004d9b756e9a\",\n        \"size\": 306135629\n    },\n    \"DynamicObjectCrossing_Town01_Route24371_Weather14.tar.gz\": {\n        \"sha256\": \"016f1a02cdde9ffe8e670618db2f4fb1b51b68281e39fba7e4e2f6c846196445\",\n        \"size\": 289241302\n    },\n    \"DynamicObjectCrossing_Town01_Route24381_Weather0.tar.gz\": {\n        \"sha256\": \"118750d391ab2b3d030c457d08699a7c4ddf981859de68ffb70372aaa3bf5f2b\",\n        \"size\": 889339113\n    },\n    \"DynamicObjectCrossing_Town02_Route24224_Weather5.tar.gz\": {\n        \"sha256\": \"e0ae8e2229c6e6496b14256caf56c364b31ddbb4db8558978b1d4045416440fc\",\n        \"size\": 248836513\n    },\n    \"DynamicObjectCrossing_Town02_Route24244_Weather1.tar.gz\": {\n        \"sha256\": \"178a4872d1ed6c9fa9d0f4b91012b2f8c3a9d998e011b665add3e40048fc41c6\",\n        \"size\": 94889365\n    },\n    \"DynamicObjectCrossing_Town11_Route24202_Weather6.tar.gz\": {\n        \"sha256\": \"5a4ae95c0ed6afc39242cdbf39c8617ad6fe8c7fa49ce223fc1565a1fe92bfc1\",\n        \"size\": 94319007\n    },\n    \"DynamicObjectCrossing_Town11_Route24242_Weather26.tar.gz\": {\n        \"sha256\": \"21267c34661209f37aef401ca1489cd4f28f094a35902a5f5b04ad2462fa7075\",\n        \"size\": 115861249\n    },\n    \"DynamicObjectCrossing_Town11_Route24252_Weather10.tar.gz\": {\n        \"sha256\": \"703021674b9e6687d19de7976f10f4ddccd8a15dc098561d5410128475d4d87a\",\n        \"size\": 59930181\n    },\n    \"DynamicObjectCrossing_Town11_Route24272_Weather7.tar.gz\": {\n        \"sha256\": \"6bb0da0ac493fa7f6788bdf31c93cf63cc0b1803b3b5280b18f0439a0485c00d\",\n        \"size\": 105842625\n    },\n    \"DynamicObjectCrossing_Town11_Route24292_Weather3.tar.gz\": {\n        \"sha256\": \"1f071a592479b737b1dfa36426c2335cf616258a8904bada3efe21e8037f54d2\",\n        \"size\": 112319185\n    },\n    \"DynamicObjectCrossing_Town11_Route24312_Weather0.tar.gz\": {\n        \"sha256\": \"7b69e3b744d6867e343b0b6058ce7f9cc38fb815c4adad3634b75c6b84f0f9d7\",\n        \"size\": 104938204\n    },\n    \"DynamicObjectCrossing_Town11_Route24322_Weather11.tar.gz\": {\n        \"sha256\": \"2dcdb0ddc00c4797318b27ac750795f6498b5f37dcd4a12e845b5c8ff58ca989\",\n        \"size\": 56986674\n    },\n    \"DynamicObjectCrossing_Town11_Route24332_Weather23.tar.gz\": {\n        \"sha256\": \"0d4f3fb74f6aed4d4207d4fc886981fd4da9db888c9365f30fbdb59c92452a86\",\n        \"size\": 45540083\n    },\n    \"DynamicObjectCrossing_Town11_Route24342_Weather8.tar.gz\": {\n        \"sha256\": \"e000bbe5d19b557ca1c72db2cd977a3a7a22ccf0f0917d9c195d5dd644d2ed8c\",\n        \"size\": 106991762\n    },\n    \"DynamicObjectCrossing_Town11_Route24362_Weather5.tar.gz\": {\n        \"sha256\": \"f467082bacf474c2db663eb4bede1a83f60cfef2c481bf381959fb897f49a2d3\",\n        \"size\": 134681752\n    },\n    \"DynamicObjectCrossing_Town11_Route24372_Weather15.tar.gz\": {\n        \"sha256\": \"bb3031053b3a2b132cd1073553c388117a0176667be692ac1f7fd194ba12d10d\",\n        \"size\": 94315352\n    },\n    \"DynamicObjectCrossing_Town12_Route1664_Weather20.tar.gz\": {\n        \"sha256\": \"93f979576c6ce0f6cfe8030a3108ca26648764f56dc71178524f1dcfa2bb4a91\",\n        \"size\": 232838657\n    },\n    \"DynamicObjectCrossing_Town12_Route1666_Weather22.tar.gz\": {\n        \"sha256\": \"418a7e36028eefc5b300e651cb20f9ae3965882e218ad497529683f111a7f400\",\n        \"size\": 149119502\n    },\n    \"DynamicObjectCrossing_Town12_Route1667_Weather23.tar.gz\": {\n        \"sha256\": \"0e8134031325544e82e4886eaf2e895caf6d309d1997206cefe7547019801438\",\n        \"size\": 118257579\n    },\n    \"DynamicObjectCrossing_Town12_Route1668_Weather23.tar.gz\": {\n        \"sha256\": \"9e62b6b032c563531ff0d47a99351963c0db31de2b2a951b376b57ddd3bdc435\",\n        \"size\": 125835785\n    },\n    \"DynamicObjectCrossing_Town12_Route1670_Weather0.tar.gz\": {\n        \"sha256\": \"46c302af665749a0e52edcfd54f1e4b78b9f3d8ba9233a296180f8d8f2d1f307\",\n        \"size\": 167266880\n    },\n    \"DynamicObjectCrossing_Town12_Route1671_Weather1.tar.gz\": {\n        \"sha256\": \"2aa2fa4c6c1bd134a5f6e68dfc3f3933dc95ec8daae7a14243583a469988c2a5\",\n        \"size\": 200422049\n    },\n    \"DynamicObjectCrossing_Town12_Route1672_Weather2.tar.gz\": {\n        \"sha256\": \"c4fb7ef1844e343495a83dc8fdf7871c7903a7e3354876249cb2b86319b26b75\",\n        \"size\": 171888297\n    },\n    \"DynamicObjectCrossing_Town12_Route1675_Weather5.tar.gz\": {\n        \"sha256\": \"8385edbd51029c38785a01b48a67c6233324bb99f825e8be8a34168deead2f88\",\n        \"size\": 367350587\n    },\n    \"DynamicObjectCrossing_Town12_Route1676_Weather6.tar.gz\": {\n        \"sha256\": \"c46548fc0956b630d97178c7aaf54175719a1f58e7cb46d2b708b84336112c7a\",\n        \"size\": 293550714\n    },\n    \"DynamicObjectCrossing_Town12_Route1677_Weather7.tar.gz\": {\n        \"sha256\": \"b307adb8d0f04a49702222b4a1f3c320a48335af13bfab04cfe6c30d99055315\",\n        \"size\": 154849586\n    },\n    \"DynamicObjectCrossing_Town12_Route1678_Weather8.tar.gz\": {\n        \"sha256\": \"ff6f232cb86a69b64fe7b8ba7b2df6e985ab2c611c53aac92fc5d9ba10ad661f\",\n        \"size\": 154034279\n    },\n    \"DynamicObjectCrossing_Town12_Route1679_Weather9.tar.gz\": {\n        \"sha256\": \"b06db3415234ae80a287429a4b154861cef350d5e7b34a0b8524228714172424\",\n        \"size\": 128838162\n    },\n    \"DynamicObjectCrossing_Town12_Route1680_Weather10.tar.gz\": {\n        \"sha256\": \"8193bad6977962a5196b43e3ec81b6f8c4ccb430a7d41c35a4e9f716804649f4\",\n        \"size\": 234753685\n    },\n    \"DynamicObjectCrossing_Town12_Route1682_Weather12.tar.gz\": {\n        \"sha256\": \"d24224d0ed2f43f3688160d311396f36b00067810d519f8c8563a35b9993d6ee\",\n        \"size\": 122361049\n    },\n    \"DynamicObjectCrossing_Town12_Route17715_Weather8.tar.gz\": {\n        \"sha256\": \"cb43d007ebd7389755524746e51797efbc1fb171f1ee8c4f3e13e65ed9d112ed\",\n        \"size\": 187298512\n    },\n    \"DynamicObjectCrossing_Town12_Route17716_Weather9.tar.gz\": {\n        \"sha256\": \"c42477946f37db7e6d837e2ffc506b99d5185f9fe9e2b2cb721aad0b44fd0672\",\n        \"size\": 128430005\n    },\n    \"DynamicObjectCrossing_Town12_Route17718_Weather11.tar.gz\": {\n        \"sha256\": \"035c6122c02716b66405c0b7b4216164ede1c2a4a17be2886b7a0af381fde729\",\n        \"size\": 308664024\n    },\n    \"DynamicObjectCrossing_Town12_Route17719_Weather12.tar.gz\": {\n        \"sha256\": \"785c7d9896a60f81dcb2fcbd3a6f2a502d3f5e86a3e789aaf6d84a94add1fc28\",\n        \"size\": 234985539\n    },\n    \"DynamicObjectCrossing_Town12_Route17720_Weather13.tar.gz\": {\n        \"sha256\": \"aa7aeafc9d795103be6317cd94ba83e2577afdc62abed9408003b1f8745f76d6\",\n        \"size\": 292399985\n    },\n    \"DynamicObjectCrossing_Town12_Route17721_Weather14.tar.gz\": {\n        \"sha256\": \"95e6acdb84bb82ddab13287119503428a026fb783a82468800ec71a38ac7bd9c\",\n        \"size\": 332502962\n    },\n    \"DynamicObjectCrossing_Town12_Route17722_Weather15.tar.gz\": {\n        \"sha256\": \"e93fffdcdf9bd3138f6637cc0b1e13ede92e276fbbaec959fae922bf4d09e045\",\n        \"size\": 307375598\n    },\n    \"DynamicObjectCrossing_Town12_Route17723_Weather8.tar.gz\": {\n        \"sha256\": \"ab5ccd905a80a434b3b0ab433e8a1ad50db603004a6db81f7d466745e7349203\",\n        \"size\": 163652794\n    },\n    \"DynamicObjectCrossing_Town12_Route17724_Weather9.tar.gz\": {\n        \"sha256\": \"1071bf3dddee03f4cf19f068646a41d195fd09ab3ec6ed59a8bfafc48abc07b6\",\n        \"size\": 108880100\n    },\n    \"DynamicObjectCrossing_Town12_Route17726_Weather19.tar.gz\": {\n        \"sha256\": \"05a1f6f4d49333f6abc44186a709e159c947068cad10b579ef9015741002e691\",\n        \"size\": 144550029\n    },\n    \"DynamicObjectCrossing_Town12_Route17727_Weather20.tar.gz\": {\n        \"sha256\": \"3685b8da694a0eff9531cc352443d40256ff8bd615f4d9986bdb31a194bee90e\",\n        \"size\": 261362387\n    },\n    \"DynamicObjectCrossing_Town12_Route17729_Weather22.tar.gz\": {\n        \"sha256\": \"cd349b143935436bca048ba25d07d9fd024d258d4bcc1e2bed731d2c2fd648d0\",\n        \"size\": 138794586\n    },\n    \"DynamicObjectCrossing_Town12_Route17733_Weather0.tar.gz\": {\n        \"sha256\": \"21b1a86b1bbde1beb63dc14eaecd8fd8a7885963461b2c453b9b1548b5858daa\",\n        \"size\": 167312032\n    },\n    \"DynamicObjectCrossing_Town12_Route17734_Weather1.tar.gz\": {\n        \"sha256\": \"95a7bab983292019ed313dd48ab3b0845d9f02ea7ae9028d10d6973831559eca\",\n        \"size\": 327852262\n    },\n    \"DynamicObjectCrossing_Town12_Route17736_Weather3.tar.gz\": {\n        \"sha256\": \"90894580a6a273ebd2a2745ce21682375a0f3ce8fdb5fe4e8d16375c7157d944\",\n        \"size\": 893681400\n    },\n    \"DynamicObjectCrossing_Town12_Route17737_Weather3.tar.gz\": {\n        \"sha256\": \"0ec20b425e6d84550f876ac30ad36b492f98e796df99cfa468e0f9957395e8a9\",\n        \"size\": 163923976\n    },\n    \"DynamicObjectCrossing_Town12_Route17738_Weather5.tar.gz\": {\n        \"sha256\": \"eda003da0715565be3d2806a0c8403f7cb35aaf13116bb99277dbf9b64150f8f\",\n        \"size\": 367153103\n    },\n    \"DynamicObjectCrossing_Town12_Route17739_Weather6.tar.gz\": {\n        \"sha256\": \"4601297eff5b35dd5ffa631ab75092b9056f78510e0551312e301994b6c41e21\",\n        \"size\": 368523083\n    },\n    \"DynamicObjectCrossing_Town12_Route17741_Weather8.tar.gz\": {\n        \"sha256\": \"929928a6c3537b3807611293ce8f3ce2ca2a27dc3e87682f809606b6ee34995f\",\n        \"size\": 144009950\n    },\n    \"DynamicObjectCrossing_Town12_Route17742_Weather9.tar.gz\": {\n        \"sha256\": \"58609907095de7e656d58d5993add0830e9d006024aea8105abd1e1e94ef4134\",\n        \"size\": 123685659\n    },\n    \"DynamicObjectCrossing_Town12_Route17746_Weather13.tar.gz\": {\n        \"sha256\": \"0292478af1ca2cdd5c8ca7d77b47e3848088ea87a5a6a6f11212701edae3a688\",\n        \"size\": 394628694\n    },\n    \"DynamicObjectCrossing_Town12_Route17747_Weather14.tar.gz\": {\n        \"sha256\": \"34503444848736ebdd918f20a5bd04c8054e42ac060027c2f036f823451bbe03\",\n        \"size\": 136137188\n    },\n    \"DynamicObjectCrossing_Town12_Route17748_Weather15.tar.gz\": {\n        \"sha256\": \"066c828fbdf0fa39bc59ab67db6721c55f4bf097bdc92c2c9814cc2815cc1ad8\",\n        \"size\": 130373627\n    },\n    \"DynamicObjectCrossing_Town12_Route17749_Weather8.tar.gz\": {\n        \"sha256\": \"01d40e7f59e6a1b0bf659e6c536a9a7558c18f86c91fd19048545e17eb2a1809\",\n        \"size\": 155113136\n    },\n    \"DynamicObjectCrossing_Town12_Route17750_Weather9.tar.gz\": {\n        \"sha256\": \"dd87c810f620f414f18f0f013e74f57ba1de2d840bc931f10f1b1c0528ad716b\",\n        \"size\": 129784164\n    },\n    \"DynamicObjectCrossing_Town12_Route17751_Weather18.tar.gz\": {\n        \"sha256\": \"c3468d9f204886c299f2134afeae7c587d32bad06e0fd28c747c1ba6c48c66f2\",\n        \"size\": 207767060\n    },\n    \"DynamicObjectCrossing_Town12_Route17752_Weather19.tar.gz\": {\n        \"sha256\": \"201dba0d7b50670155d0cd41b3f511ff4578d372b19a0b6a6f7b87ac1ff23a1d\",\n        \"size\": 266812441\n    },\n    \"DynamicObjectCrossing_Town12_Route17753_Weather20.tar.gz\": {\n        \"sha256\": \"2c816f8f8f356b11be191cf6a92177c71bcb8ff7a4813130ac316c14031b417a\",\n        \"size\": 135018779\n    },\n    \"DynamicObjectCrossing_Town12_Route17755_Weather22.tar.gz\": {\n        \"sha256\": \"9fd28fc993d526276c4e1ec73ff8da3d0182e7a3c46c80301725acdb2070e8aa\",\n        \"size\": 438823233\n    },\n    \"DynamicObjectCrossing_Town12_Route17756_Weather23.tar.gz\": {\n        \"sha256\": \"054d0e8447896e08a8cecb3e288eb657d4d3dc884f3cbfc7d25870c44171be7e\",\n        \"size\": 155585027\n    },\n    \"DynamicObjectCrossing_Town12_Route17758_Weather25.tar.gz\": {\n        \"sha256\": \"74ee5aa575e58b081e0b4f90bbe7072115f8445a996c4115e6642624cd9f9dd2\",\n        \"size\": 116116138\n    },\n    \"DynamicObjectCrossing_Town12_Route17759_Weather0.tar.gz\": {\n        \"sha256\": \"060c5f1dfbc0f50afc2d08dd7e9628bc41acc2c3812d0dcd37b0f38c1aa3c6f8\",\n        \"size\": 191677011\n    },\n    \"DynamicObjectCrossing_Town12_Route17760_Weather1.tar.gz\": {\n        \"sha256\": \"9619e56e6849cdde75bc515e947989b4aba3692e982c2937d55776610655ad94\",\n        \"size\": 161641563\n    },\n    \"DynamicObjectCrossing_Town12_Route17761_Weather2.tar.gz\": {\n        \"sha256\": \"42d8de47364cdae79f2420e5062cedc732dc8bb82fffd7cf7ef8ba2b5b13a3f9\",\n        \"size\": 418585397\n    },\n    \"DynamicObjectCrossing_Town12_Route17764_Weather5.tar.gz\": {\n        \"sha256\": \"a5068ec99c535c2a9e0d43655d88e650c01cd6633c73eaffd722158a8d3964dd\",\n        \"size\": 213800640\n    },\n    \"DynamicObjectCrossing_Town12_Route17765_Weather6.tar.gz\": {\n        \"sha256\": \"8493620f64ba50aa832216e8cd7fa8f56ebcc2486fed21dc6346a12a56e4cf71\",\n        \"size\": 211200733\n    },\n    \"DynamicObjectCrossing_Town12_Route17767_Weather8.tar.gz\": {\n        \"sha256\": \"55b89a54b5edbc603f9461f50e4a846022c675135714c8efc7eb37b7a59e6e9c\",\n        \"size\": 165099771\n    },\n    \"DynamicObjectCrossing_Town12_Route17769_Weather10.tar.gz\": {\n        \"sha256\": \"f1b381c6e41508033029a5bf70b5045886515fe683c6d1cdf9c159893dfdd632\",\n        \"size\": 165336295\n    },\n    \"DynamicObjectCrossing_Town12_Route17770_Weather11.tar.gz\": {\n        \"sha256\": \"b1ea3bb122a3e6838d3b0d86b142e5133ef6c0df4d4e8a9d993f51062a9cfdf6\",\n        \"size\": 136785555\n    },\n    \"DynamicObjectCrossing_Town12_Route17771_Weather12.tar.gz\": {\n        \"sha256\": \"c97c1c2238c91478fa3520b23a97d13bdf81976d79796f6dda91a48a505c2482\",\n        \"size\": 130866640\n    },\n    \"DynamicObjectCrossing_Town12_Route17773_Weather14.tar.gz\": {\n        \"sha256\": \"780e31327f2fdab896d848e60c39ba1ce1b06897433e7ecf6a19d54c44decd6c\",\n        \"size\": 132480915\n    },\n    \"DynamicObjectCrossing_Town12_Route17774_Weather15.tar.gz\": {\n        \"sha256\": \"095420883371fba62017d533eaccf31df52a3ba53b589bf7d50cbc3726fe0604\",\n        \"size\": 282775522\n    },\n    \"DynamicObjectCrossing_Town12_Route17775_Weather8.tar.gz\": {\n        \"sha256\": \"8473995b821aa0fe8f7c899b37e065be7f01f28231d466a68711db06fd7fb305\",\n        \"size\": 282552039\n    },\n    \"DynamicObjectCrossing_Town12_Route17776_Weather9.tar.gz\": {\n        \"sha256\": \"7273b0df96b30508b0337b9f7a5f261465116d703c590f418e931e97b335f777\",\n        \"size\": 235857839\n    },\n    \"DynamicObjectCrossing_Town12_Route17777_Weather18.tar.gz\": {\n        \"sha256\": \"5edeb93fee0145158763853186404747781ca7e79441acdee514d6b5d80fdc47\",\n        \"size\": 158987248\n    },\n    \"DynamicObjectCrossing_Town12_Route17778_Weather19.tar.gz\": {\n        \"sha256\": \"56661b87f20dfee3adaa21dd02fd30aa86d0355235d218d5fb5fcc13ec19032d\",\n        \"size\": 156202295\n    },\n    \"DynamicObjectCrossing_Town12_Route17779_Weather20.tar.gz\": {\n        \"sha256\": \"b0afb872ed5662fc7d9cd38f5b0329128bb56633180aba42f37091e4d7555796\",\n        \"size\": 217922300\n    },\n    \"DynamicObjectCrossing_Town12_Route17780_Weather21.tar.gz\": {\n        \"sha256\": \"a06f8b3015bfeb3bc92407ac21a1339ba56856253bcfc3c0bdb241df520588e7\",\n        \"size\": 242017825\n    },\n    \"DynamicObjectCrossing_Town12_Route17781_Weather22.tar.gz\": {\n        \"sha256\": \"1ce2bab5d3e9ab4dee4a147cfddef9decfc84d4bd2e63aaff2f94481ea40d37b\",\n        \"size\": 342375985\n    },\n    \"DynamicObjectCrossing_Town12_Route17782_Weather23.tar.gz\": {\n        \"sha256\": \"6b4de8fb8f2b5b744e6328292fc6846fce9f486af7384bd83f7a1e550e90dae5\",\n        \"size\": 137851583\n    },\n    \"DynamicObjectCrossing_Town12_Route17783_Weather23.tar.gz\": {\n        \"sha256\": \"386400d4be4d89b0779df325488e37ea38507f7b1bad6338477cf0ae97736d1f\",\n        \"size\": 149112986\n    },\n    \"DynamicObjectCrossing_Town12_Route17784_Weather25.tar.gz\": {\n        \"sha256\": \"53cef881dd4e1a774bdef631e809900d1f09cc029c468d15cbb9f37315b5d3af\",\n        \"size\": 222318973\n    },\n    \"DynamicObjectCrossing_Town12_Route17785_Weather0.tar.gz\": {\n        \"sha256\": \"87eb354dbfc27b20ab97f336abf6b75f93b2be4b80d55a9b50f9986a9104d954\",\n        \"size\": 302876811\n    },\n    \"DynamicObjectCrossing_Town12_Route17786_Weather1.tar.gz\": {\n        \"sha256\": \"4a7a9d6e1e6add0edfb657a008e1b1a2a637b16c7bb282cd0bb592c8964698a5\",\n        \"size\": 520471078\n    },\n    \"DynamicObjectCrossing_Town12_Route17787_Weather2.tar.gz\": {\n        \"sha256\": \"a39c4ee316b2544c155e82a40fe09dfebddd02f52620d1d1813da96ec5f33c4d\",\n        \"size\": 149755918\n    },\n    \"DynamicObjectCrossing_Town12_Route17789_Weather3.tar.gz\": {\n        \"sha256\": \"725fbd9854df1bded67c035116af920e4335d5727bcc468dcdbc3eba09e3b2ea\",\n        \"size\": 171064527\n    },\n    \"DynamicObjectCrossing_Town12_Route17790_Weather5.tar.gz\": {\n        \"sha256\": \"85a98e9b5fccb836fcca363efbda096cb620e38122fe44e19756b04417064e41\",\n        \"size\": 346801289\n    },\n    \"DynamicObjectCrossing_Town12_Route17791_Weather6.tar.gz\": {\n        \"sha256\": \"e1fe726d3ef1f2e3047401939525446c268c848d27381972a4c19498b61f5b98\",\n        \"size\": 239906304\n    },\n    \"DynamicObjectCrossing_Town12_Route17794_Weather9.tar.gz\": {\n        \"sha256\": \"90828a4e2c639dc481ca255443854dcbb352e17fe76e55707cf8c813df5124bf\",\n        \"size\": 308059842\n    },\n    \"DynamicObjectCrossing_Town12_Route17795_Weather10.tar.gz\": {\n        \"sha256\": \"12a80d14423b43a43f77f76342266cf490cfefe49ef5af0dd72e035e4c5de32d\",\n        \"size\": 303424420\n    },\n    \"DynamicObjectCrossing_Town12_Route17796_Weather11.tar.gz\": {\n        \"sha256\": \"bc44db2fb26c131404ecf6a1fa777eeb80fe39a0c67544f901514271bc8ddf7a\",\n        \"size\": 125873028\n    },\n    \"DynamicObjectCrossing_Town12_Route17797_Weather12.tar.gz\": {\n        \"sha256\": \"68f2ca867dfa0eb1f714f5addd1f8667f705e108abae5c1d341a2b6800f702ee\",\n        \"size\": 142297341\n    },\n    \"DynamicObjectCrossing_Town12_Route17798_Weather13.tar.gz\": {\n        \"sha256\": \"635149c6ff89a298c0de57dbfd5f3d472911dbe9163a4edfabd8503746769e5e\",\n        \"size\": 119822425\n    },\n    \"DynamicObjectCrossing_Town12_Route17799_Weather14.tar.gz\": {\n        \"sha256\": \"b63ab8845ed35d91122aca19e93c7979c3046211473b6388428454e6f2a76580\",\n        \"size\": 217231576\n    },\n    \"DynamicObjectCrossing_Town12_Route17800_Weather15.tar.gz\": {\n        \"sha256\": \"6e5010a235adae870ac64a14492cbcc4ecad9933c26af920d8d16c13085fc160\",\n        \"size\": 148638153\n    },\n    \"DynamicObjectCrossing_Town12_Route17801_Weather8.tar.gz\": {\n        \"sha256\": \"09a8c46d7995c331a03b013058cb2ba48fb5b62deb7b78b7027492a5dd72a0ae\",\n        \"size\": 444444357\n    },\n    \"DynamicObjectCrossing_Town12_Route17804_Weather19.tar.gz\": {\n        \"sha256\": \"99f57640fae4fd43a61c63ceecfc7e4e932a70abcccde7291a9f9a64631f9bb4\",\n        \"size\": 150966729\n    },\n    \"DynamicObjectCrossing_Town12_Route17805_Weather20.tar.gz\": {\n        \"sha256\": \"22f23fdbd4c72045b57a045281bd76b56a0a745fad61785d73a71297e2b83063\",\n        \"size\": 166268706\n    },\n    \"DynamicObjectCrossing_Town12_Route17807_Weather22.tar.gz\": {\n        \"sha256\": \"574d55db69264ddb2de79bb0f905aad1a211995b81caa261e72be99299303fb4\",\n        \"size\": 158357802\n    },\n    \"DynamicObjectCrossing_Town12_Route17808_Weather23.tar.gz\": {\n        \"sha256\": \"8f27510024783958d9a5d205c2df262d4d3e335b46e0c73a793d029867643ea7\",\n        \"size\": 252744665\n    },\n    \"DynamicObjectCrossing_Town12_Route17809_Weather23.tar.gz\": {\n        \"sha256\": \"879ac8047d669f9035cbd1076fadceafb18511a30f62473c105f39f2c7628602\",\n        \"size\": 324237540\n    },\n    \"DynamicObjectCrossing_Town12_Route17810_Weather25.tar.gz\": {\n        \"sha256\": \"cf80d25f0f6ba953a3090264a34c59b061bcef8a88a4e05de73700a87abca93f\",\n        \"size\": 126343265\n    },\n    \"DynamicObjectCrossing_Town12_Route17815_Weather3.tar.gz\": {\n        \"sha256\": \"d68072be6126d5ba09b4f36c06b9b363637f31fc74dacd8a3a1adf53e40728b5\",\n        \"size\": 375475491\n    },\n    \"DynamicObjectCrossing_Town12_Route17816_Weather5.tar.gz\": {\n        \"sha256\": \"15dacbf7c5e2bb0ebcfd4736d6a8a2a9f72fe9b74296d342c37de8fc3e540361\",\n        \"size\": 392875021\n    },\n    \"DynamicObjectCrossing_Town12_Route17817_Weather6.tar.gz\": {\n        \"sha256\": \"b9bcbed4aeec1cc4c712fd861c41383baafeb002f81c3d9643ae06e42bc206bc\",\n        \"size\": 303115909\n    },\n    \"DynamicObjectCrossing_Town12_Route17818_Weather7.tar.gz\": {\n        \"sha256\": \"57154ad5252e7b206065cc4158a1a14a749d90ddc368225cecb13b8ae0145882\",\n        \"size\": 176389013\n    },\n    \"DynamicObjectCrossing_Town12_Route17819_Weather8.tar.gz\": {\n        \"sha256\": \"28166d436c87f811fe50a1f339e1963d56947e73113d1593717bbad6bd36f8fc\",\n        \"size\": 432939323\n    },\n    \"DynamicObjectCrossing_Town12_Route17820_Weather9.tar.gz\": {\n        \"sha256\": \"45d0f6025124c864e300accf9b766118a18fad99d2464ed677fa0cb2d4d5ea94\",\n        \"size\": 125883010\n    },\n    \"DynamicObjectCrossing_Town12_Route17821_Weather10.tar.gz\": {\n        \"sha256\": \"699b433b1936298b16d0626395ad6370fc656c4b007b982dc80b462e4ff4f8a9\",\n        \"size\": 253174115\n    },\n    \"DynamicObjectCrossing_Town12_Route17822_Weather11.tar.gz\": {\n        \"sha256\": \"19cb263f65b60af233834ad47eca3cb0503ad3ed73edc6920d5daea7a3ba8a22\",\n        \"size\": 193232514\n    },\n    \"DynamicObjectCrossing_Town12_Route17823_Weather12.tar.gz\": {\n        \"sha256\": \"c1df4b5d9676119b9df48f829d85f071e775688ddd3055e1780b0accdf8086c4\",\n        \"size\": 135635180\n    },\n    \"DynamicObjectCrossing_Town12_Route17827_Weather8.tar.gz\": {\n        \"sha256\": \"71012aa7b60de630107dd75130e24fa5e311e14106a3f3ccd8f1d9035dcfe08d\",\n        \"size\": 425292157\n    },\n    \"DynamicObjectCrossing_Town12_Route17828_Weather9.tar.gz\": {\n        \"sha256\": \"f927fa4fde5f13cee0cb633de23acda7a95de98812d6f2dcebbbb2c8310d8a66\",\n        \"size\": 327043274\n    },\n    \"DynamicObjectCrossing_Town12_Route17830_Weather19.tar.gz\": {\n        \"sha256\": \"f77ef6c0ee21d06d807f20f5a58acdfa19768bc5eba825bb5c0f408b1cb4df99\",\n        \"size\": 178814473\n    },\n    \"DynamicObjectCrossing_Town12_Route17832_Weather21.tar.gz\": {\n        \"sha256\": \"6df1225ef6fbf633d969b3b1c75ce998b6759961a78b33580339e3b846fce416\",\n        \"size\": 123277475\n    },\n    \"DynamicObjectCrossing_Town12_Route17834_Weather23.tar.gz\": {\n        \"sha256\": \"819268baa3c07e181cf473d8b914b43a8ddffce05a7b3e16bf4d914146a36b85\",\n        \"size\": 112648315\n    },\n    \"DynamicObjectCrossing_Town12_Route17836_Weather25.tar.gz\": {\n        \"sha256\": \"bf34a1d66baff83d31d58175f1ed8bcbdee969f81faec9ffe9168da2cc13c752\",\n        \"size\": 129244651\n    },\n    \"DynamicObjectCrossing_Town12_Route17839_Weather2.tar.gz\": {\n        \"sha256\": \"fc9dbfa73e7ee2cb78c1994e3225af8b12a13e2bc132d55b01f0637b109baa73\",\n        \"size\": 526641947\n    },\n    \"DynamicObjectCrossing_Town12_Route17840_Weather3.tar.gz\": {\n        \"sha256\": \"437aee1ed7d6f9224f4241551a84ac392f6491d6e9d2149bb5f137bfb0131f43\",\n        \"size\": 263309584\n    },\n    \"DynamicObjectCrossing_Town12_Route17841_Weather3.tar.gz\": {\n        \"sha256\": \"416254d0a81e3afeb0b4270efd7f9fca921b2d258ba51d83c9b22cbf755fc7d4\",\n        \"size\": 328172941\n    },\n    \"DynamicObjectCrossing_Town12_Route17843_Weather6.tar.gz\": {\n        \"sha256\": \"6fff032fbdbc544b6c038e97a4a49d0130f4a833f0b364a85f62f46242be6488\",\n        \"size\": 425089050\n    },\n    \"DynamicObjectCrossing_Town12_Route17846_Weather9.tar.gz\": {\n        \"sha256\": \"45b9d68d7400b1c0030ac71f65f4c1fdaaf6dcf3f07affd9be5747b8fd2a2fee\",\n        \"size\": 711887210\n    },\n    \"DynamicObjectCrossing_Town12_Route17847_Weather10.tar.gz\": {\n        \"sha256\": \"5961a9c47bdbc3da15a75ebf0a88c0eacf36346f81e1ddbda20950ffe46ad375\",\n        \"size\": 252707597\n    },\n    \"DynamicObjectCrossing_Town12_Route17848_Weather11.tar.gz\": {\n        \"sha256\": \"bafe26b0c93611a111e9509c8a5e19b77f56168564d15aff5e38be0a23bcb22e\",\n        \"size\": 363126316\n    },\n    \"DynamicObjectCrossing_Town12_Route17849_Weather12.tar.gz\": {\n        \"sha256\": \"f49e20b273f422324a1ea77f95ff9b268a31dd2025995b92776c36939523a21b\",\n        \"size\": 331549708\n    },\n    \"DynamicObjectCrossing_Town12_Route17850_Weather13.tar.gz\": {\n        \"sha256\": \"92b081c308dbd67bcc181beec1a36e1fe1846258c76bd974ddba32037a2cf0d0\",\n        \"size\": 289558817\n    },\n    \"DynamicObjectCrossing_Town12_Route17851_Weather14.tar.gz\": {\n        \"sha256\": \"26c3d6a9a13b73b1f67750d5566d4839162ee374b9c15ba72fef1e92e65119b7\",\n        \"size\": 271721620\n    },\n    \"DynamicObjectCrossing_Town12_Route17852_Weather15.tar.gz\": {\n        \"sha256\": \"7403753bcc5ae31256351407639cb75e4d069f19bb9600a64b7e27ee34b09b0f\",\n        \"size\": 300548978\n    },\n    \"DynamicObjectCrossing_Town12_Route17853_Weather8.tar.gz\": {\n        \"sha256\": \"5be1753874b1bc69c7a3e397e14d3449d2f3595240d1d2f037b3a0bac651bb7a\",\n        \"size\": 287022563\n    },\n    \"DynamicObjectCrossing_Town12_Route17854_Weather9.tar.gz\": {\n        \"sha256\": \"0019cebf6ddb4a801fd05b4cb707e21ae3abc7a4183fdf72b5fff09175d3fdd8\",\n        \"size\": 334199367\n    },\n    \"DynamicObjectCrossing_Town12_Route17855_Weather18.tar.gz\": {\n        \"sha256\": \"009adcab4fc4f0d31a3f4211e9508e6837af0fa128afabf8066c619cbb300030\",\n        \"size\": 427929812\n    },\n    \"DynamicObjectCrossing_Town12_Route17857_Weather20.tar.gz\": {\n        \"sha256\": \"23abfd051826282e64929dc60386e53aba4892464e529794ed6c6be722ed3366\",\n        \"size\": 170251314\n    },\n    \"DynamicObjectCrossing_Town12_Route17859_Weather22.tar.gz\": {\n        \"sha256\": \"8cd5a005d8078161ab45982d41ce406b66bedfb34ea9fcbb67049ebbf3ca0369\",\n        \"size\": 270705698\n    },\n    \"DynamicObjectCrossing_Town12_Route17860_Weather23.tar.gz\": {\n        \"sha256\": \"c78105473b2628ac2fb136af8580cc7648a4c24f4c8324777db138c9cc9da4c8\",\n        \"size\": 117003079\n    },\n    \"DynamicObjectCrossing_Town12_Route17861_Weather23.tar.gz\": {\n        \"sha256\": \"20f6faf1307c3512a1025eb8e3a55af07a4a745ba54366b9551a204704fb5cc5\",\n        \"size\": 124354756\n    },\n    \"DynamicObjectCrossing_Town12_Route17862_Weather25.tar.gz\": {\n        \"sha256\": \"a64177f0e3b92ee3758a017743f73c7c3bea790cf20188f968fbdaaa0635f833\",\n        \"size\": 136229430\n    },\n    \"DynamicObjectCrossing_Town12_Route17863_Weather0.tar.gz\": {\n        \"sha256\": \"4c6fa64ed6c9137faa5f7b1bd70229e5a0f7764c730f3821e1d45610ab903b16\",\n        \"size\": 341596248\n    },\n    \"DynamicObjectCrossing_Town12_Route17864_Weather1.tar.gz\": {\n        \"sha256\": \"b510e1e00a4715fa3713c3af87db85112d2da47d21d5f167f24773cb087d7c1e\",\n        \"size\": 165079560\n    },\n    \"DynamicObjectCrossing_Town12_Route17865_Weather2.tar.gz\": {\n        \"sha256\": \"2c5913e5fa5b21f626db7a2e0c1775d1707372b906248a2f9269cd0b176db2d5\",\n        \"size\": 153882338\n    },\n    \"DynamicObjectCrossing_Town12_Route17866_Weather3.tar.gz\": {\n        \"sha256\": \"3dd4751284977360dee5393896b5cce725a5a49d806e792ef1e696c03ebad15b\",\n        \"size\": 160529766\n    },\n    \"DynamicObjectCrossing_Town12_Route17867_Weather3.tar.gz\": {\n        \"sha256\": \"c62d3958c6e9e593dc856bb97ddfe49f8986e467f7228e9447e406f68a3deeb3\",\n        \"size\": 174734426\n    },\n    \"DynamicObjectCrossing_Town12_Route17868_Weather5.tar.gz\": {\n        \"sha256\": \"057144155f26f30eacbdb3dcfd54288a467a89c88c225462f823af59a22a1751\",\n        \"size\": 890868012\n    },\n    \"DynamicObjectCrossing_Town12_Route17869_Weather6.tar.gz\": {\n        \"sha256\": \"d7c627d89415b1c7c6e96d3d4e27c7d89bf8acf0517dabf09f54a4df3b25a33f\",\n        \"size\": 157530210\n    },\n    \"DynamicObjectCrossing_Town12_Route17870_Weather7.tar.gz\": {\n        \"sha256\": \"7d89846509069caa52e987b5232b02c0968acf0c4d785afa7d7b1e9217701ece\",\n        \"size\": 179409034\n    },\n    \"DynamicObjectCrossing_Town12_Route17872_Weather9.tar.gz\": {\n        \"sha256\": \"cbe81c2691b6b14796e3d7ab92f882842739a458c184a76be9e04875cd2b0c12\",\n        \"size\": 320217971\n    },\n    \"DynamicObjectCrossing_Town12_Route17873_Weather10.tar.gz\": {\n        \"sha256\": \"c798cfe6251ac53a94d4f1d8dce44950b5dda611fec6bdb74b5de96092d884dd\",\n        \"size\": 185823610\n    },\n    \"DynamicObjectCrossing_Town12_Route17877_Weather14.tar.gz\": {\n        \"sha256\": \"457fff5b2b726d215eeed1208c28048fef6379baafc87038ec895babfe4d254e\",\n        \"size\": 139750229\n    },\n    \"DynamicObjectCrossing_Town12_Route17878_Weather15.tar.gz\": {\n        \"sha256\": \"67d83c10d6b80220a498d344f920598412d56478bf952c3a6cdef4a9bfaf6790\",\n        \"size\": 137372939\n    },\n    \"DynamicObjectCrossing_Town12_Route17879_Weather8.tar.gz\": {\n        \"sha256\": \"061260bad7ff18a1eb6e996b9136ed24ab30e0581c6e698109c32decda568d1c\",\n        \"size\": 293654444\n    },\n    \"DynamicObjectCrossing_Town12_Route17880_Weather9.tar.gz\": {\n        \"sha256\": \"490f825da003bf70aeeb82c368e9299d07bc9ce45d567a4037c68bc96419820b\",\n        \"size\": 288240300\n    },\n    \"DynamicObjectCrossing_Town12_Route17881_Weather18.tar.gz\": {\n        \"sha256\": \"8a8c17eee509fd46f058f17f0bd9491bf3dddfd7e5f46b5bff6233a04b4af4a4\",\n        \"size\": 313576557\n    },\n    \"DynamicObjectCrossing_Town12_Route17882_Weather19.tar.gz\": {\n        \"sha256\": \"c66225990434eb80d1fc5f0b8e98a15e44df5e5f6ad719b678ee8a1d741f39a9\",\n        \"size\": 151792604\n    },\n    \"DynamicObjectCrossing_Town12_Route17884_Weather21.tar.gz\": {\n        \"sha256\": \"9287ac36200fc9a2cebad8c42dfd23f86b95a47de9bc5df931dd70872092f4a3\",\n        \"size\": 427722021\n    },\n    \"DynamicObjectCrossing_Town12_Route17885_Weather22.tar.gz\": {\n        \"sha256\": \"c86a554832db2203c48b171dcfc09b30d2de4793c9717411b0e8331fb298c560\",\n        \"size\": 160278730\n    },\n    \"DynamicObjectCrossing_Town12_Route17886_Weather23.tar.gz\": {\n        \"sha256\": \"53a610b5d4bff24e10ab52fcd87c5210e06ffc54d94fc13e2598f41e09d2b1d0\",\n        \"size\": 120621641\n    },\n    \"DynamicObjectCrossing_Town12_Route17887_Weather23.tar.gz\": {\n        \"sha256\": \"e84edb3e7004cdcd0a072f14ab7cb7567f7cb9bf5a5a6479eed44d196a7c9732\",\n        \"size\": 143213712\n    },\n    \"DynamicObjectCrossing_Town12_Route17888_Weather25.tar.gz\": {\n        \"sha256\": \"161c21fac0286f26b4073f350876c89537e333a5ba67fece3bbea350096f6cf9\",\n        \"size\": 116977147\n    },\n    \"DynamicObjectCrossing_Town12_Route17889_Weather0.tar.gz\": {\n        \"sha256\": \"8092bbe1fefac46d8df3bde3b8eea57c81d0458346b7ac33818fd29a2b067d11\",\n        \"size\": 518845817\n    },\n    \"DynamicObjectCrossing_Town12_Route17891_Weather2.tar.gz\": {\n        \"sha256\": \"5f5f5a55b39500abb846545d291e31bdf17add0416b1cb7aecae5bc5407b3d82\",\n        \"size\": 344736265\n    },\n    \"DynamicObjectCrossing_Town12_Route17892_Weather3.tar.gz\": {\n        \"sha256\": \"34a0b43317f85e29c6c80758b327cc5dc62a3f7fc23e36143845059bc3a961ad\",\n        \"size\": 162393538\n    },\n    \"DynamicObjectCrossing_Town12_Route17893_Weather3.tar.gz\": {\n        \"sha256\": \"c3ef24aa68de23ff1dfc95da3ab4f2eac7c21cdf066382974299dbb4819e848f\",\n        \"size\": 198534418\n    },\n    \"DynamicObjectCrossing_Town12_Route17895_Weather6.tar.gz\": {\n        \"sha256\": \"45109c5b165472a7670ff10a841261161f21286a0ba17b4130a50b666e091f31\",\n        \"size\": 135787117\n    },\n    \"DynamicObjectCrossing_Town12_Route17896_Weather7.tar.gz\": {\n        \"sha256\": \"36104156423c43ef015730223d1f889d19e57d0b6ec06626a21bf9a1f41ebd53\",\n        \"size\": 188730104\n    },\n    \"DynamicObjectCrossing_Town12_Route17897_Weather8.tar.gz\": {\n        \"sha256\": \"7bfe812ebd278698a681338cac833cb97cbf6f14cc5f1de82ca01064642be4fb\",\n        \"size\": 181059417\n    },\n    \"DynamicObjectCrossing_Town12_Route17898_Weather9.tar.gz\": {\n        \"sha256\": \"be91b2dcad919905e227764d3efdbf7acdcdac6f1c16e63fa8a4dedbb8269d00\",\n        \"size\": 312833464\n    },\n    \"DynamicObjectCrossing_Town12_Route17901_Weather12.tar.gz\": {\n        \"sha256\": \"a30b46de1c51f7b85ec7120e1724eacb4904170df8e1ca6f6d3e64b5e75d5503\",\n        \"size\": 249780566\n    },\n    \"DynamicObjectCrossing_Town12_Route17904_Weather15.tar.gz\": {\n        \"sha256\": \"22c7a6afb1aefc421a74d223ec3c76b5e4cc2168c920bd7c01152c0455e84408\",\n        \"size\": 402819190\n    },\n    \"DynamicObjectCrossing_Town12_Route17905_Weather8.tar.gz\": {\n        \"sha256\": \"0ff0cdfb5097c5d034af5aecfb19af5d80f25a1494315e5ad7ae554882ed5457\",\n        \"size\": 153267183\n    },\n    \"DynamicObjectCrossing_Town12_Route17906_Weather9.tar.gz\": {\n        \"sha256\": \"8546c1331b8a41380eefa9b0188e755fa3f518d7e4082d2b856c905a3a8eea46\",\n        \"size\": 248924667\n    },\n    \"DynamicObjectCrossing_Town12_Route17907_Weather18.tar.gz\": {\n        \"sha256\": \"1564713745417b93cd35cd9b7a7e6ab75a25afc8714ea6f3846f303e08fb1f97\",\n        \"size\": 196477954\n    },\n    \"DynamicObjectCrossing_Town12_Route17908_Weather19.tar.gz\": {\n        \"sha256\": \"21de15e7795e30c7066b7ba087e60578e4b63e6e867a2d564f714bb9d12465ad\",\n        \"size\": 168684188\n    },\n    \"DynamicObjectCrossing_Town12_Route17909_Weather20.tar.gz\": {\n        \"sha256\": \"afc06180770e7e7c5fcc1011410fe200cc7a428b9f97e0b2ae78a4fa0eed86e8\",\n        \"size\": 202453040\n    },\n    \"DynamicObjectCrossing_Town12_Route17910_Weather21.tar.gz\": {\n        \"sha256\": \"88d8f47ccca645e3bcf19a76d989c84002693f96eb6ee064f4a9e1752edca57e\",\n        \"size\": 421700514\n    },\n    \"DynamicObjectCrossing_Town12_Route17911_Weather22.tar.gz\": {\n        \"sha256\": \"550271c2d34b45bf411f7bd0500662d43310f85829aa99bcd93d9ac9ec4cdfea\",\n        \"size\": 214718413\n    },\n    \"DynamicObjectCrossing_Town12_Route17913_Weather23.tar.gz\": {\n        \"sha256\": \"81a75cb76c17bf9e598c6be9f37f3dc76d1b3ae5a66a44821d7a8be1cd8db24c\",\n        \"size\": 642488707\n    },\n    \"DynamicObjectCrossing_Town12_Route17915_Weather0.tar.gz\": {\n        \"sha256\": \"f15731329fba3608fa137e34145f21d87c277d1a8463589042ba292fac964a4f\",\n        \"size\": 167324232\n    },\n    \"DynamicObjectCrossing_Town12_Route17916_Weather1.tar.gz\": {\n        \"sha256\": \"0d9e336503359a9d607871de80a1b2576f3e2fc9b5bef70270f8a6923c13da31\",\n        \"size\": 188521382\n    },\n    \"DynamicObjectCrossing_Town12_Route17917_Weather2.tar.gz\": {\n        \"sha256\": \"203ad03bf90735253a2590218f081def765129375ff13daae255f9fe69da46b0\",\n        \"size\": 198696826\n    },\n    \"DynamicObjectCrossing_Town12_Route17918_Weather3.tar.gz\": {\n        \"sha256\": \"12e64af92ce59feaabd3f201c59ea38aa123a8e428ff55b2076bbce8ea2df56c\",\n        \"size\": 416826656\n    },\n    \"DynamicObjectCrossing_Town12_Route17919_Weather3.tar.gz\": {\n        \"sha256\": \"a540d49fd0f02db7bad0c42d621d23e4e6691b30dfd6112310630d72c0deb648\",\n        \"size\": 161294568\n    },\n    \"DynamicObjectCrossing_Town12_Route17921_Weather6.tar.gz\": {\n        \"sha256\": \"80b35de11ff6752761fa1c8aed8c223f8812ab149af7435524ef04f730dfac81\",\n        \"size\": 149166776\n    },\n    \"DynamicObjectCrossing_Town12_Route17922_Weather7.tar.gz\": {\n        \"sha256\": \"474be83fc5cf0a8066cf3a88927bd732e1670e0113cb70adb0eb8e2661c3c6fc\",\n        \"size\": 162120338\n    },\n    \"DynamicObjectCrossing_Town12_Route17923_Weather8.tar.gz\": {\n        \"sha256\": \"8fe4af760f03d0782e6501c6809ad53647b1b19fa2ef1dec848bc41ce592da89\",\n        \"size\": 176895140\n    },\n    \"DynamicObjectCrossing_Town12_Route17925_Weather10.tar.gz\": {\n        \"sha256\": \"503cae73a64ee61eb9800370395ea6d1ce2d8a425b2317309a1ec7ad59369e4c\",\n        \"size\": 390579017\n    },\n    \"DynamicObjectCrossing_Town12_Route17928_Weather13.tar.gz\": {\n        \"sha256\": \"1e5af51743784db3ada0a11860fcad07c1d7f5b223ca2e874854ab2cdc012973\",\n        \"size\": 293717147\n    },\n    \"DynamicObjectCrossing_Town12_Route17929_Weather14.tar.gz\": {\n        \"sha256\": \"08b603cf3a78bb0909d0853a783f992458e7c6ef921115e29231c92b5352a036\",\n        \"size\": 1003131807\n    },\n    \"DynamicObjectCrossing_Town12_Route17930_Weather15.tar.gz\": {\n        \"sha256\": \"6ebaffb4912f463b105fa7717af5076caff2e10f864ba4568661b8d1e3306fc9\",\n        \"size\": 128301432\n    },\n    \"DynamicObjectCrossing_Town12_Route17931_Weather8.tar.gz\": {\n        \"sha256\": \"c85ad2d8b84ad481af440e56458c3bb8f0b83bcfdbd96eeb6c4370f629f977fb\",\n        \"size\": 331946694\n    },\n    \"DynamicObjectCrossing_Town12_Route17933_Weather18.tar.gz\": {\n        \"sha256\": \"c0180dd26bd8f457dbed1418dfadd04093cae628b6de09881fb16cbb435b46e6\",\n        \"size\": 211662405\n    },\n    \"DynamicObjectCrossing_Town12_Route17935_Weather20.tar.gz\": {\n        \"sha256\": \"6494e5512ba42ad8ba00f6831312e555e760540f0d5973f6c887b9ed0deb9487\",\n        \"size\": 164793292\n    },\n    \"DynamicObjectCrossing_Town12_Route17936_Weather21.tar.gz\": {\n        \"sha256\": \"184585d2d68df8e30a147d880d97fed74af9449a85042627d2dce7d3f4423f44\",\n        \"size\": 125753086\n    },\n    \"DynamicObjectCrossing_Town12_Route17937_Weather22.tar.gz\": {\n        \"sha256\": \"25dc5d81a722762af2c9ee7a0df69530ed7232f3e95c069b496718656d9fc78e\",\n        \"size\": 270963333\n    },\n    \"DynamicObjectCrossing_Town12_Route17940_Weather25.tar.gz\": {\n        \"sha256\": \"4c71cd94bc8a305eb971281234e8ac87d39b450d068eac44ede940718d08f3d4\",\n        \"size\": 240306994\n    },\n    \"DynamicObjectCrossing_Town12_Route17941_Weather0.tar.gz\": {\n        \"sha256\": \"7b55a41901e6539b4d3dae7b90ce0fbbb14524cf29805ab6b3f833b2e3fe676c\",\n        \"size\": 342762114\n    },\n    \"DynamicObjectCrossing_Town12_Route17942_Weather1.tar.gz\": {\n        \"sha256\": \"b10abbc01bfa07b7228415d595575cb25f34153d4272b83ba4dd6464396624d4\",\n        \"size\": 204598746\n    },\n    \"DynamicObjectCrossing_Town12_Route17943_Weather2.tar.gz\": {\n        \"sha256\": \"d64531d7c6b1bc1b0a785e96455ffcf938beb3fb5d3e7dee2b9c260d03d87422\",\n        \"size\": 173986549\n    },\n    \"DynamicObjectCrossing_Town12_Route17944_Weather3.tar.gz\": {\n        \"sha256\": \"08704fa2d06bc4c879af57236e27564d96be30e40f5cdc16439c00b287a0757f\",\n        \"size\": 538036401\n    },\n    \"DynamicObjectCrossing_Town12_Route17946_Weather5.tar.gz\": {\n        \"sha256\": \"f003051a2915f0772a5d444ae29d233101d7072ce4a26ca7d2f7dd1408270e78\",\n        \"size\": 168401626\n    },\n    \"DynamicObjectCrossing_Town12_Route17948_Weather7.tar.gz\": {\n        \"sha256\": \"f488eb520bb48bee45b78a659eeb2be9603fdf174bc9b39c544103c37262596c\",\n        \"size\": 209989438\n    },\n    \"DynamicObjectCrossing_Town12_Route17951_Weather10.tar.gz\": {\n        \"sha256\": \"08be540b6b0c6ac2a4ecd686a4452a20b28a346d1fb0d184089103c7be1df7c7\",\n        \"size\": 261137368\n    },\n    \"DynamicObjectCrossing_Town12_Route17952_Weather11.tar.gz\": {\n        \"sha256\": \"2f01f64bdef398a08318b9c6b247cbdc9a0055c528b0f1cb5246f8b840b2189c\",\n        \"size\": 723086189\n    },\n    \"DynamicObjectCrossing_Town12_Route17953_Weather12.tar.gz\": {\n        \"sha256\": \"3e89bebec1dcc32436ca7b43d3366039af1ded0d5aa20f28d210603ab3670e72\",\n        \"size\": 130169802\n    },\n    \"DynamicObjectCrossing_Town12_Route17954_Weather13.tar.gz\": {\n        \"sha256\": \"17830f9865f1d0d8f0df7108488e86a59eb6b6c61803c855c6d17938d4e6381c\",\n        \"size\": 134389513\n    },\n    \"DynamicObjectCrossing_Town12_Route17956_Weather15.tar.gz\": {\n        \"sha256\": \"44ae1169e60b62d84675a6b37ada77cf168cb6c547ba15ce214427611e7eaa06\",\n        \"size\": 390961340\n    },\n    \"DynamicObjectCrossing_Town12_Route17958_Weather9.tar.gz\": {\n        \"sha256\": \"74c541ec709ab5bd48e69a58c188083a7e339b2168a9b772f68532476e5222e6\",\n        \"size\": 120668175\n    },\n    \"DynamicObjectCrossing_Town12_Route17960_Weather19.tar.gz\": {\n        \"sha256\": \"6a3e2ad2f5351d6aef6c1075fa8b5e1dbe66ca0c24ab2b057afbbbdfd2a5eff1\",\n        \"size\": 194852277\n    },\n    \"DynamicObjectCrossing_Town12_Route17964_Weather23.tar.gz\": {\n        \"sha256\": \"8b90ddf4557ff63417972b660da200bc86f9461e092bbc3083f344b123f1ebb3\",\n        \"size\": 128078717\n    },\n    \"DynamicObjectCrossing_Town12_Route17966_Weather25.tar.gz\": {\n        \"sha256\": \"e97d1e3463c8a5b68a73c87cd7a2e8cfa4d91ed50802aa0dbafb424ed8c3b62a\",\n        \"size\": 232211491\n    },\n    \"DynamicObjectCrossing_Town12_Route17969_Weather2.tar.gz\": {\n        \"sha256\": \"86fe174c10cc36e40b34b7cdb9032a8b72a61e627f3114e84641a9a19a54bdf7\",\n        \"size\": 339473924\n    },\n    \"DynamicObjectCrossing_Town12_Route17970_Weather3.tar.gz\": {\n        \"sha256\": \"262bf770a559ef39750144c6a8777de793b7632063e0adc43d983d38599e79ef\",\n        \"size\": 265956033\n    },\n    \"DynamicObjectCrossing_Town12_Route17972_Weather5.tar.gz\": {\n        \"sha256\": \"c946d27c2c0b84efe2c577e994225bd7a8d825b0eb2380f970fa78478c3d1996\",\n        \"size\": 414202863\n    },\n    \"DynamicObjectCrossing_Town12_Route17973_Weather6.tar.gz\": {\n        \"sha256\": \"eadcecd255038ff1089252d27a5f38360aabda439c598f1a812f652ab9440a90\",\n        \"size\": 325741019\n    },\n    \"DynamicObjectCrossing_Town12_Route17975_Weather8.tar.gz\": {\n        \"sha256\": \"25012531675c47f95d6e0227e9a4339c80d844652391520343716ada865c0581\",\n        \"size\": 148491845\n    },\n    \"DynamicObjectCrossing_Town12_Route17978_Weather11.tar.gz\": {\n        \"sha256\": \"7cbd78bbb069f5fa57578e24d765dac90cdf3af636a9f28f8420848a136a74ba\",\n        \"size\": 113432218\n    },\n    \"DynamicObjectCrossing_Town12_Route17980_Weather13.tar.gz\": {\n        \"sha256\": \"ced09c88b12b118a4e6e36352f65d349d284f4ff2c5b40462c17ce8b8597944e\",\n        \"size\": 137826783\n    },\n    \"DynamicObjectCrossing_Town12_Route17981_Weather14.tar.gz\": {\n        \"sha256\": \"97da2745e71e2beae67050a74283c4b0c4e85a4f98c1feb09fda4333e775884f\",\n        \"size\": 294490082\n    },\n    \"DynamicObjectCrossing_Town12_Route17982_Weather15.tar.gz\": {\n        \"sha256\": \"b3b71eaff446d4807040e98206e76b74a1d5d7247ab9945996163aee61ac8b70\",\n        \"size\": 277850513\n    },\n    \"DynamicObjectCrossing_Town12_Route17983_Weather8.tar.gz\": {\n        \"sha256\": \"4a7d93cee43186f535db3a598ae7d41b37e67266ac492b9a74e3c28dcad94a5e\",\n        \"size\": 537212308\n    },\n    \"DynamicObjectCrossing_Town12_Route17984_Weather9.tar.gz\": {\n        \"sha256\": \"ea52215e12e377f6ebb7faef40534cb902c76e989d65edd051cd15e2248817e3\",\n        \"size\": 251877147\n    },\n    \"DynamicObjectCrossing_Town12_Route17985_Weather18.tar.gz\": {\n        \"sha256\": \"9c9569a6fc4ba1549f669bff5c265482e1b5202e12365cad8e554d5e588b3616\",\n        \"size\": 187037651\n    },\n    \"DynamicObjectCrossing_Town12_Route17986_Weather19.tar.gz\": {\n        \"sha256\": \"22106fd7d7b2d1081fcc79f651cbc9c3f128a6d4a53cc702983704502f63be7a\",\n        \"size\": 270946357\n    },\n    \"DynamicObjectCrossing_Town12_Route17987_Weather20.tar.gz\": {\n        \"sha256\": \"fd5b6eddf30662b49cf6fb81d31488449206ea73f7932e469e39a4edd31ed5f7\",\n        \"size\": 147695994\n    },\n    \"DynamicObjectCrossing_Town12_Route17988_Weather21.tar.gz\": {\n        \"sha256\": \"3c8f86ad196dcbc00867c226cb6674198b5c679f8fe31086bcc36bd407fbfd16\",\n        \"size\": 143546824\n    },\n    \"DynamicObjectCrossing_Town12_Route17993_Weather0.tar.gz\": {\n        \"sha256\": \"e36a8f6f9a5377d9fca8a4e520f467bceb2e0f3b31fdd0958e45056b562bb08e\",\n        \"size\": 608066760\n    },\n    \"DynamicObjectCrossing_Town12_Route17994_Weather1.tar.gz\": {\n        \"sha256\": \"01d966c35d1d9b795077612df3ae9b8de468eb4e4b1487eb1e777d430da313b6\",\n        \"size\": 186400840\n    },\n    \"DynamicObjectCrossing_Town12_Route17995_Weather2.tar.gz\": {\n        \"sha256\": \"595d38c4855584bc1fe2cb994639130422d6fa93e33851e932af440446eeb5b3\",\n        \"size\": 194872150\n    },\n    \"DynamicObjectCrossing_Town12_Route17997_Weather3.tar.gz\": {\n        \"sha256\": \"20586c4fed447d3827b002bb860a7aa29954d33d45b5bae9b2316ea38f74682c\",\n        \"size\": 399043316\n    },\n    \"DynamicObjectCrossing_Town12_Route17998_Weather5.tar.gz\": {\n        \"sha256\": \"e42887199f458b358d082af1d7813a3ac53e8fb9ea5e0fc1469c4d0c24c91263\",\n        \"size\": 144697870\n    },\n    \"DynamicObjectCrossing_Town12_Route17999_Weather6.tar.gz\": {\n        \"sha256\": \"218ab18ca8e4b3f5f9b1b68bd8c54333ad8da81591bc5e15d15148d6e02fe2c2\",\n        \"size\": 368558092\n    },\n    \"DynamicObjectCrossing_Town12_Route18001_Weather8.tar.gz\": {\n        \"sha256\": \"415f71dc728b66191e684ddf95137b4a62098c100fed928f159c1ec15b00b4ca\",\n        \"size\": 292723012\n    },\n    \"DynamicObjectCrossing_Town12_Route18002_Weather9.tar.gz\": {\n        \"sha256\": \"9522358fb33258b54b0d8c734b0b4f52d89f10fb046963afc42cbe74ad044040\",\n        \"size\": 106671269\n    },\n    \"DynamicObjectCrossing_Town12_Route18003_Weather10.tar.gz\": {\n        \"sha256\": \"3f07654511412b3ea7e825381dbd0652e03b47c17df69d44c66c887d8b9086fe\",\n        \"size\": 204761573\n    },\n    \"DynamicObjectCrossing_Town12_Route18004_Weather11.tar.gz\": {\n        \"sha256\": \"5f3f3130afb500e049f69728e587a890cf38ec303079d42b60c08545c338fe14\",\n        \"size\": 194897561\n    },\n    \"DynamicObjectCrossing_Town12_Route18005_Weather12.tar.gz\": {\n        \"sha256\": \"06f644cdac673c1abad4c38cde14376b53b46da14a833ef0af692e2e35a87638\",\n        \"size\": 218503132\n    },\n    \"DynamicObjectCrossing_Town12_Route18006_Weather13.tar.gz\": {\n        \"sha256\": \"f4db58da769d67b600d5f2ca8ad30b6e9814a1e52ef1d0cc5a8a279e98e7d7cc\",\n        \"size\": 263306156\n    },\n    \"DynamicObjectCrossing_Town12_Route18007_Weather14.tar.gz\": {\n        \"sha256\": \"681dcdf179ebb140557ab164140fbac52e980adbef586a138c3d2e293b88e643\",\n        \"size\": 258576033\n    },\n    \"DynamicObjectCrossing_Town12_Route18009_Weather8.tar.gz\": {\n        \"sha256\": \"704f20b2c2af06443785049fd552377f9a3a509f2e0bc49575d7e7ed68abdeaa\",\n        \"size\": 302053818\n    },\n    \"DynamicObjectCrossing_Town12_Route18010_Weather9.tar.gz\": {\n        \"sha256\": \"86285cb6938fd51ce977d76a9226b0f74aede39034230a21eb20df16b1c36cf3\",\n        \"size\": 278668600\n    },\n    \"DynamicObjectCrossing_Town12_Route18011_Weather18.tar.gz\": {\n        \"sha256\": \"d7958e176408c5c494603e817661368246e361cccf51e7d2124b53dd5bd66415\",\n        \"size\": 328671694\n    },\n    \"DynamicObjectCrossing_Town12_Route18012_Weather19.tar.gz\": {\n        \"sha256\": \"68abfefb1bd68f8b3656cee47ee3b04143ed7ca6a883090e03caf0ceb3a23838\",\n        \"size\": 175236841\n    },\n    \"DynamicObjectCrossing_Town12_Route18014_Weather21.tar.gz\": {\n        \"sha256\": \"37f5ca6adbf1aa9bba126afa87be835402c93c08216346ea2e8abe10eb99a906\",\n        \"size\": 133707704\n    },\n    \"DynamicObjectCrossing_Town12_Route18015_Weather22.tar.gz\": {\n        \"sha256\": \"4b5cd15692eebcb3c78f11c29f039b0d95519da8a9cb0bd80c827d1a6d4ae0fc\",\n        \"size\": 203983992\n    },\n    \"DynamicObjectCrossing_Town12_Route18016_Weather23.tar.gz\": {\n        \"sha256\": \"904c82c77370bfa67c3808fd78b0985e0148204026eea92f897ad97ef8b56811\",\n        \"size\": 383078032\n    },\n    \"DynamicObjectCrossing_Town12_Route18018_Weather25.tar.gz\": {\n        \"sha256\": \"fff113a7322c60fb995b0800d526748fc71f82a5dc6972eb9653f230183a5472\",\n        \"size\": 319266865\n    },\n    \"DynamicObjectCrossing_Town12_Route18019_Weather0.tar.gz\": {\n        \"sha256\": \"2d3ac08646e483c02f03b6dc2632757b5cee8def32bbc867f31662008ef549f5\",\n        \"size\": 344144352\n    },\n    \"DynamicObjectCrossing_Town12_Route18020_Weather1.tar.gz\": {\n        \"sha256\": \"7bfd5e9913ec59a4401eced3e3d2b0364ae8c8039a7e4e64c397ecff5810fdfa\",\n        \"size\": 417024967\n    },\n    \"DynamicObjectCrossing_Town12_Route18024_Weather5.tar.gz\": {\n        \"sha256\": \"3c7bf499f6e7aa7e4c2e4a8bc3d3f19b48f63602efcb43b3919d2b29e07db755\",\n        \"size\": 152380623\n    },\n    \"DynamicObjectCrossing_Town12_Route18025_Weather6.tar.gz\": {\n        \"sha256\": \"133328af565b13b4e77b487b07319a6c115fa8d694e2b732c02820ecee6e81a5\",\n        \"size\": 148201121\n    },\n    \"DynamicObjectCrossing_Town12_Route18026_Weather7.tar.gz\": {\n        \"sha256\": \"3f6f237d01dbb320c149b5974f5e2d42a785c8f330f69766de24a5a0eda1f1f2\",\n        \"size\": 426028341\n    },\n    \"DynamicObjectCrossing_Town12_Route18028_Weather9.tar.gz\": {\n        \"sha256\": \"a828b787513970ad6c3ee5a768265db15a1e8bfe108a974c9e4866627de9ca57\",\n        \"size\": 177374668\n    },\n    \"DynamicObjectCrossing_Town12_Route18029_Weather10.tar.gz\": {\n        \"sha256\": \"97acc348ec015411f683d00e217f6f9a160195f784eab4d5b6a96bf09d360ad4\",\n        \"size\": 370406281\n    },\n    \"DynamicObjectCrossing_Town12_Route18030_Weather11.tar.gz\": {\n        \"sha256\": \"a61fb3cc0435766f1731ef1caeeb4ade40585b367d61c6b73bf1a977fbb3a5fe\",\n        \"size\": 285847325\n    },\n    \"DynamicObjectCrossing_Town12_Route18031_Weather12.tar.gz\": {\n        \"sha256\": \"a70ae1977786f16655f2318a7ff16bbf405d5c63fc00dbe71c73b2ca7c7005c6\",\n        \"size\": 751947758\n    },\n    \"DynamicObjectCrossing_Town12_Route18032_Weather13.tar.gz\": {\n        \"sha256\": \"30bfde0fbcbdfd8512c1a412475d25ca973972ae00914b2f6d02a7bdddeb585f\",\n        \"size\": 240007108\n    },\n    \"DynamicObjectCrossing_Town12_Route18033_Weather14.tar.gz\": {\n        \"sha256\": \"b0d42002623ba927208fd9d26bbfb7491379c0b422aa53fa7da27da4b7ff23d9\",\n        \"size\": 126525741\n    },\n    \"DynamicObjectCrossing_Town12_Route18037_Weather18.tar.gz\": {\n        \"sha256\": \"9b907e716c17f5b7e85c2d7a9d37639e9afef19f0d48e376ba37cf644bceac9a\",\n        \"size\": 291218573\n    },\n    \"DynamicObjectCrossing_Town12_Route18039_Weather20.tar.gz\": {\n        \"sha256\": \"f500ee60f853586fe6d557da6a95b607ef5885140270a4ab5318e8073bec0985\",\n        \"size\": 158702425\n    },\n    \"DynamicObjectCrossing_Town12_Route18040_Weather21.tar.gz\": {\n        \"sha256\": \"b48d32c8f34ed01453eec31b1459ab007c5894e3c373ca26e297330ddb1a3600\",\n        \"size\": 143817153\n    },\n    \"DynamicObjectCrossing_Town12_Route18041_Weather22.tar.gz\": {\n        \"sha256\": \"24aef40984e3a9a8fce09c09859399414a7390e040d0ad86d367b005922e178c\",\n        \"size\": 147566316\n    },\n    \"DynamicObjectCrossing_Town12_Route18042_Weather23.tar.gz\": {\n        \"sha256\": \"16cd4ab0f340de79ce07b3646163b55b846ff3631720a3311af0d9a0e626e5b6\",\n        \"size\": 139226471\n    },\n    \"DynamicObjectCrossing_Town12_Route18043_Weather23.tar.gz\": {\n        \"sha256\": \"664c58675b8bc11e0513503cecfd533971cdb388f7459cdb20d426b63d42546e\",\n        \"size\": 379894155\n    },\n    \"DynamicObjectCrossing_Town12_Route18046_Weather1.tar.gz\": {\n        \"sha256\": \"6b566da4bc8f999174df2fbd1016a6fe1c853e7a7089a57253093e9b35ed77be\",\n        \"size\": 199562687\n    },\n    \"DynamicObjectCrossing_Town12_Route18048_Weather3.tar.gz\": {\n        \"sha256\": \"f5baea1bbc53c18be73555f70ff65801fb0d981b167707f860f934bf6256926e\",\n        \"size\": 378289288\n    },\n    \"DynamicObjectCrossing_Town12_Route18050_Weather5.tar.gz\": {\n        \"sha256\": \"8ac3513f61cbdcaa00dfac46e97ceded392f989918aba115f735e3137ff5ff63\",\n        \"size\": 301062097\n    },\n    \"DynamicObjectCrossing_Town12_Route18051_Weather6.tar.gz\": {\n        \"sha256\": \"28f9e8a58b0a2e9b65d5fa6a329bd716d719d467bd0693b2566cd50ec00cf714\",\n        \"size\": 361931099\n    },\n    \"DynamicObjectCrossing_Town12_Route18052_Weather7.tar.gz\": {\n        \"sha256\": \"270db24a271750b7106eee8ccb3d893bd5b5d06f8895c076f4a82e8b474055e4\",\n        \"size\": 407982221\n    },\n    \"DynamicObjectCrossing_Town12_Route18053_Weather8.tar.gz\": {\n        \"sha256\": \"803e26fb104759afc5a857939b2ad2fafa346c4ea4ca5da140b94d065d85c72e\",\n        \"size\": 151307994\n    },\n    \"DynamicObjectCrossing_Town12_Route18055_Weather10.tar.gz\": {\n        \"sha256\": \"4daf6b6f547d6cdae350aa8706e630cb5adc8a99eb8cebd84377ca475c8eb2f0\",\n        \"size\": 373727087\n    },\n    \"DynamicObjectCrossing_Town12_Route18056_Weather11.tar.gz\": {\n        \"sha256\": \"37648ea2f870d8328921da6a882c75144df4cfe8fa687090838ac63695adc981\",\n        \"size\": 362160793\n    },\n    \"DynamicObjectCrossing_Town12_Route18058_Weather13.tar.gz\": {\n        \"sha256\": \"f0b9313794a7fc9ec1e23cf44aab71b24de2b7ff9d53b90de4dd6338cf4f6966\",\n        \"size\": 202411156\n    },\n    \"DynamicObjectCrossing_Town12_Route18059_Weather14.tar.gz\": {\n        \"sha256\": \"d2ee01944b3af7d56f90fe50bd6294d1c327671d4a84c0bbeda1702321898203\",\n        \"size\": 429665307\n    },\n    \"DynamicObjectCrossing_Town12_Route18060_Weather15.tar.gz\": {\n        \"sha256\": \"cd78bee229adc9a63a7e6b6cb850c6e6ad44c7d9d9d20115fecf783d34d329a2\",\n        \"size\": 335259185\n    },\n    \"DynamicObjectCrossing_Town12_Route18061_Weather8.tar.gz\": {\n        \"sha256\": \"dcf59dd782c5230928e102c806439b380869387c04494813e2f558335244f877\",\n        \"size\": 363277945\n    },\n    \"DynamicObjectCrossing_Town12_Route18062_Weather9.tar.gz\": {\n        \"sha256\": \"962bd8c52cbf2f946b741df6ff8e806a4ea086a6ab227e5025d0088b61c9d5a6\",\n        \"size\": 107679114\n    },\n    \"DynamicObjectCrossing_Town12_Route18063_Weather18.tar.gz\": {\n        \"sha256\": \"fe6acf0dc3b1486072cb5072b13f7dcf8c8644d7f6322518dc3355e0e0d6beec\",\n        \"size\": 529476610\n    },\n    \"DynamicObjectCrossing_Town12_Route18065_Weather20.tar.gz\": {\n        \"sha256\": \"1626e7e7d8bc2714ce25282e67ef3a1e166f5fb6f05ecc9c45ec0f5d46ffdf41\",\n        \"size\": 275783573\n    },\n    \"DynamicObjectCrossing_Town12_Route18066_Weather21.tar.gz\": {\n        \"sha256\": \"6c408c894bcea34d54ca238100335dbcc22f89fe44cbda425f7cf48b2e3b06ab\",\n        \"size\": 242357784\n    },\n    \"DynamicObjectCrossing_Town12_Route18068_Weather23.tar.gz\": {\n        \"sha256\": \"70686036e40ba17faf7f5a75460c6a79ffd6120fc7c81567a76acaffbb139f68\",\n        \"size\": 420832119\n    },\n    \"DynamicObjectCrossing_Town12_Route18070_Weather25.tar.gz\": {\n        \"sha256\": \"a923d5b8930d2a07eb9201dacf624be04a69a3c48ffe37ad1008d2188c3dc6bf\",\n        \"size\": 139072975\n    },\n    \"DynamicObjectCrossing_Town12_Route18071_Weather0.tar.gz\": {\n        \"sha256\": \"014f4bcbbad8f7546573202fac0410b93070f626c4c140c6da015794668e759d\",\n        \"size\": 152986325\n    },\n    \"DynamicObjectCrossing_Town12_Route18072_Weather1.tar.gz\": {\n        \"sha256\": \"6c3047fa436287d9cc41799d900ff1fe42f96f46774daf76c7ddae22703041ce\",\n        \"size\": 310041891\n    },\n    \"DynamicObjectCrossing_Town12_Route18073_Weather2.tar.gz\": {\n        \"sha256\": \"b664bccfc82a16dfdb047cfe5bc4d199e8b4d972c9e6acd0b1d5ef675f990ec6\",\n        \"size\": 158433977\n    },\n    \"DynamicObjectCrossing_Town12_Route18074_Weather3.tar.gz\": {\n        \"sha256\": \"c8a84ed714d260ca4415e7f3ab758a778d7dd43c4ea20fb2c225e4ced1a7b8d6\",\n        \"size\": 274753621\n    },\n    \"DynamicObjectCrossing_Town12_Route18075_Weather3.tar.gz\": {\n        \"sha256\": \"483827d8ca70c2480bf78b5dd83ff00cc9feeb1e664d9fad9e515fc370c8c40e\",\n        \"size\": 364570239\n    },\n    \"DynamicObjectCrossing_Town12_Route18076_Weather5.tar.gz\": {\n        \"sha256\": \"8490471730682a2e3839cedfd00bc03fa5793517af750c99cbd8682f6d65fc54\",\n        \"size\": 309533304\n    },\n    \"DynamicObjectCrossing_Town12_Route18077_Weather6.tar.gz\": {\n        \"sha256\": \"802a894a4da2d655fe77fa1d707e9cd18f3300f258a2ae48ac5aa14ac701505a\",\n        \"size\": 261843127\n    },\n    \"DynamicObjectCrossing_Town12_Route18078_Weather7.tar.gz\": {\n        \"sha256\": \"e88054c08efcfb62a1d7bd8443ed762fecc4eacbc4ad25520d26c3ef01b8e0d0\",\n        \"size\": 381061656\n    },\n    \"DynamicObjectCrossing_Town12_Route18079_Weather8.tar.gz\": {\n        \"sha256\": \"6b5db052821a89ebad9120b39ba70ef82fc6e686b3c6e0a44c234becc0dff819\",\n        \"size\": 173703869\n    },\n    \"DynamicObjectCrossing_Town12_Route18081_Weather10.tar.gz\": {\n        \"sha256\": \"2c2bd02e34a3d3ac5634424fc18f575d6423e62ea3989c9bb71d7c93f8bf8fc1\",\n        \"size\": 346390374\n    },\n    \"DynamicObjectCrossing_Town12_Route18085_Weather14.tar.gz\": {\n        \"sha256\": \"146c2aecc5d03170cc392aed81636cc5d1249d2fc93f67c2494c6e8067c6a46a\",\n        \"size\": 420682403\n    },\n    \"DynamicObjectCrossing_Town12_Route18087_Weather8.tar.gz\": {\n        \"sha256\": \"c7452704a13561f6208437bd9fd7070502d1ee0397f4efa4457ce43990f759a3\",\n        \"size\": 363207956\n    },\n    \"DynamicObjectCrossing_Town12_Route18088_Weather9.tar.gz\": {\n        \"sha256\": \"37c2113715f7209e553b65071e584d288061d8351b35936c32a19784b650e53f\",\n        \"size\": 236199321\n    },\n    \"DynamicObjectCrossing_Town12_Route18089_Weather18.tar.gz\": {\n        \"sha256\": \"47f6fb090dc871da080f43ec81d911dd8dc81b9ef204f530ea359a4e6f0b4156\",\n        \"size\": 428943860\n    },\n    \"DynamicObjectCrossing_Town12_Route18090_Weather19.tar.gz\": {\n        \"sha256\": \"2f506b2747aa2fde732a5f673d767aa609a20cb6c8b7bc1ddf72fc525cb9adae\",\n        \"size\": 145678297\n    },\n    \"DynamicObjectCrossing_Town12_Route18091_Weather20.tar.gz\": {\n        \"sha256\": \"2b227512248acd416b15d5d824698d5b2e5aff51a94d5fc637fce600a772203f\",\n        \"size\": 154065875\n    },\n    \"DynamicObjectCrossing_Town12_Route18092_Weather21.tar.gz\": {\n        \"sha256\": \"7c41e5625c7b5f8f5994bf4aaefedfbc6f10ff64142cffc2b9becbe7eb170094\",\n        \"size\": 291953083\n    },\n    \"DynamicObjectCrossing_Town12_Route18093_Weather22.tar.gz\": {\n        \"sha256\": \"619a08e6a3f1212615b6d6419c64cfd60897a9ec59ac83832979cf24c3cf31be\",\n        \"size\": 133102949\n    },\n    \"DynamicObjectCrossing_Town12_Route18095_Weather23.tar.gz\": {\n        \"sha256\": \"a2c1ecc78131bbb599223ec08ea7ecd08a00fc8ced59033b93766a229ef21d65\",\n        \"size\": 249902174\n    },\n    \"DynamicObjectCrossing_Town12_Route18098_Weather1.tar.gz\": {\n        \"sha256\": \"c70f85982fc2ed8fc2a7e51a908e400f17f4941c9149ca1f11002c385ed75f44\",\n        \"size\": 305746013\n    },\n    \"DynamicObjectCrossing_Town12_Route18100_Weather3.tar.gz\": {\n        \"sha256\": \"78f9b65a899a52a5402f9ef4ccfa65bfa196fa43504d65f646a676b00e666d0d\",\n        \"size\": 145462505\n    },\n    \"DynamicObjectCrossing_Town12_Route18101_Weather3.tar.gz\": {\n        \"sha256\": \"007ffff2e83aa84f58fd7e11e64329d63ec376918a1782fd2cc0202b208c2c16\",\n        \"size\": 148834884\n    },\n    \"DynamicObjectCrossing_Town12_Route18102_Weather5.tar.gz\": {\n        \"sha256\": \"de0b286116214064317b8454cb058a8a11a614cb2afd43afaf7eba5df8c99419\",\n        \"size\": 521363016\n    },\n    \"DynamicObjectCrossing_Town12_Route18106_Weather9.tar.gz\": {\n        \"sha256\": \"8382bd1e3a6b2cdba74af5c6ad0dda050cb9fdbcbf173e094b76514c730c5515\",\n        \"size\": 183685782\n    },\n    \"DynamicObjectCrossing_Town12_Route18107_Weather10.tar.gz\": {\n        \"sha256\": \"01d3fc25e4711ac73830613b781a24d81563e7802766532cbaf8a08b6913719d\",\n        \"size\": 133501265\n    },\n    \"DynamicObjectCrossing_Town12_Route18108_Weather11.tar.gz\": {\n        \"sha256\": \"5f918e26a41fe5afa9d2424f530b98cfcd2b27d2c21dfa61b1600a9bb239351e\",\n        \"size\": 117807337\n    },\n    \"DynamicObjectCrossing_Town12_Route18110_Weather13.tar.gz\": {\n        \"sha256\": \"45625772db6792bb8969481c77ea05d436e3ecba93eb8954355b03fae7428c15\",\n        \"size\": 129704349\n    },\n    \"DynamicObjectCrossing_Town12_Route18116_Weather19.tar.gz\": {\n        \"sha256\": \"672fac36d81bdd22574a7099cc6afff42bcd3ee660b239299e769d6e58296230\",\n        \"size\": 352328274\n    },\n    \"DynamicObjectCrossing_Town12_Route18117_Weather20.tar.gz\": {\n        \"sha256\": \"85ca78187130231a486fabd12ed26a214fcb8bda87bf418fb9f4cc1ceccc5da8\",\n        \"size\": 311697093\n    },\n    \"DynamicObjectCrossing_Town12_Route18120_Weather23.tar.gz\": {\n        \"sha256\": \"1e0a70a00ec39cc456b9f4c39e26bff5ad2c98ac91ba8bd211037f7baf6c7416\",\n        \"size\": 122541021\n    },\n    \"DynamicObjectCrossing_Town12_Route18121_Weather23.tar.gz\": {\n        \"sha256\": \"a5a9e902b71bcafe24f4f373511105b8f0fc450af22319a65ab4f76230e3e44a\",\n        \"size\": 256319020\n    },\n    \"DynamicObjectCrossing_Town12_Route18122_Weather25.tar.gz\": {\n        \"sha256\": \"9099558316b8e0e1f670809f2b3112e4433558aa9e1963af6b180f651bc15d98\",\n        \"size\": 276252769\n    },\n    \"DynamicObjectCrossing_Town12_Route18123_Weather0.tar.gz\": {\n        \"sha256\": \"fcb74f5b04f4500492dc5e7d8e92860d6258ed4d03eb347e561c73e33f0f29a7\",\n        \"size\": 424767197\n    },\n    \"DynamicObjectCrossing_Town12_Route18126_Weather3.tar.gz\": {\n        \"sha256\": \"75ccb94f9546499edd0538822eacdfbe11ce3051302274c74a1f5718e8e52cb6\",\n        \"size\": 168772448\n    },\n    \"DynamicObjectCrossing_Town12_Route18127_Weather3.tar.gz\": {\n        \"sha256\": \"b5200d5ee04506807927d5e2f49d5158524a3d12dca6688dda3d659e50b7d6d1\",\n        \"size\": 529476728\n    },\n    \"DynamicObjectCrossing_Town12_Route18128_Weather5.tar.gz\": {\n        \"sha256\": \"b4f3743638efd022802d0dbb10827ff250a83855742dfa6c4210714e84c197af\",\n        \"size\": 293162849\n    },\n    \"DynamicObjectCrossing_Town12_Route18129_Weather6.tar.gz\": {\n        \"sha256\": \"17ec11c130ba4a9a1154fec15b39d39f7767c80783d014f285682c58175c61f2\",\n        \"size\": 271914217\n    },\n    \"DynamicObjectCrossing_Town12_Route18130_Weather7.tar.gz\": {\n        \"sha256\": \"19a9b236cb2f14c2d76a0e40e961facc045a51e71f8f003ec7efe71ee458248c\",\n        \"size\": 373284910\n    },\n    \"DynamicObjectCrossing_Town12_Route18131_Weather8.tar.gz\": {\n        \"sha256\": \"69d4f538cc3c3a0f07304348f784b30be2222407b7d2689dd5ea09d9d893af1d\",\n        \"size\": 443846141\n    },\n    \"DynamicObjectCrossing_Town12_Route18132_Weather9.tar.gz\": {\n        \"sha256\": \"147036dd782c74d91b6711c9780525a1bd7a869268668a81a5dffdfa15eca318\",\n        \"size\": 226194926\n    },\n    \"DynamicObjectCrossing_Town12_Route18133_Weather10.tar.gz\": {\n        \"sha256\": \"ede985d3adf28e030f68a46dcbac2eb788c65e975db4cd910992bb5b3f1529f1\",\n        \"size\": 270158920\n    },\n    \"DynamicObjectCrossing_Town12_Route18134_Weather11.tar.gz\": {\n        \"sha256\": \"25074af2e1423866b025e943c40755e4c89e59d39cccd14439830ae81aef90a5\",\n        \"size\": 108113696\n    },\n    \"DynamicObjectCrossing_Town12_Route18135_Weather12.tar.gz\": {\n        \"sha256\": \"96196bdd56cad1afab659a22dd93739baa127a698483d22ba33786e04eef56b5\",\n        \"size\": 306118236\n    },\n    \"DynamicObjectCrossing_Town12_Route18136_Weather13.tar.gz\": {\n        \"sha256\": \"9790371f27864dc3505562b90875c7bb9cd13addb3428a4eb6a66f7aa5b1b9a8\",\n        \"size\": 106957773\n    },\n    \"DynamicObjectCrossing_Town12_Route18138_Weather15.tar.gz\": {\n        \"sha256\": \"bcd46b2702da056e60a1eb6f5a5a66561564215371dd62746b2bb38fd7636c8a\",\n        \"size\": 292706297\n    },\n    \"DynamicObjectCrossing_Town12_Route18139_Weather8.tar.gz\": {\n        \"sha256\": \"7972202c9b1c85b83bbef8380fa241e30eabe348a39a1e8d2f7ce7c9014be0d5\",\n        \"size\": 337850949\n    },\n    \"DynamicObjectCrossing_Town12_Route18140_Weather9.tar.gz\": {\n        \"sha256\": \"ff38b5cf95bb99c22763586c3783762d30f7b8256e0969a60d7279f249bc5773\",\n        \"size\": 123998629\n    },\n    \"DynamicObjectCrossing_Town12_Route18141_Weather18.tar.gz\": {\n        \"sha256\": \"41ff574879c5597e45709583cc200a106eb43997d5bd3f656a1ef2120d1646b3\",\n        \"size\": 180682179\n    },\n    \"DynamicObjectCrossing_Town12_Route18145_Weather22.tar.gz\": {\n        \"sha256\": \"b67ebdab64271e95c19dc3538686d9974b80f9fda664776785cdaf75cc57f2f7\",\n        \"size\": 145637816\n    },\n    \"DynamicObjectCrossing_Town12_Route18146_Weather23.tar.gz\": {\n        \"sha256\": \"bd827a3e171d64815ac54f5b1bd301559993331856b117832a731082dd38bca4\",\n        \"size\": 146773049\n    },\n    \"DynamicObjectCrossing_Town12_Route18147_Weather23.tar.gz\": {\n        \"sha256\": \"9a1325286912757116ffef197a521c06bc35714c0f7e3328edac6ecc86a7cfb4\",\n        \"size\": 316169160\n    },\n    \"DynamicObjectCrossing_Town12_Route18148_Weather25.tar.gz\": {\n        \"sha256\": \"c35dcea2ad95f5900ae0603f67362f5a220869682a7770d45ff5331d4e52ac6f\",\n        \"size\": 369539435\n    },\n    \"DynamicObjectCrossing_Town12_Route18153_Weather3.tar.gz\": {\n        \"sha256\": \"1aab3675221e9e2b65333cf46eb8aee4b536eb4380c63d7efa1e287daf458418\",\n        \"size\": 321487366\n    },\n    \"DynamicObjectCrossing_Town12_Route18154_Weather5.tar.gz\": {\n        \"sha256\": \"73d8574cc153818a1f25810924e9567b1bbab5cd16f932ae446a9bd7955f1ca4\",\n        \"size\": 322519355\n    },\n    \"DynamicObjectCrossing_Town12_Route18155_Weather6.tar.gz\": {\n        \"sha256\": \"337f8a86170ad873fcdd5768238e6917265fda58414f85b24bef533ea32cc65c\",\n        \"size\": 585004347\n    },\n    \"DynamicObjectCrossing_Town12_Route18157_Weather8.tar.gz\": {\n        \"sha256\": \"2ac75725cb46f7eb3369555362451e2c6b44d439b6a8884ad5f50ebced36e594\",\n        \"size\": 309687392\n    },\n    \"DynamicObjectCrossing_Town12_Route18159_Weather10.tar.gz\": {\n        \"sha256\": \"5708f0f721c6c0f1ace29b0c7c8782282e230a7a94f5c475400ddcb9a5df6779\",\n        \"size\": 350774110\n    },\n    \"DynamicObjectCrossing_Town12_Route18160_Weather11.tar.gz\": {\n        \"sha256\": \"139208f0a0541ec5d6a28ea7f78d8aba55cf71fb730931bd7e3085f830f653f4\",\n        \"size\": 125863885\n    },\n    \"DynamicObjectCrossing_Town12_Route18161_Weather12.tar.gz\": {\n        \"sha256\": \"e3ed681b311b587eccc8ad6490f0a1ace9feaa90c93de4932fdae118f0820cea\",\n        \"size\": 133045607\n    },\n    \"DynamicObjectCrossing_Town12_Route18163_Weather14.tar.gz\": {\n        \"sha256\": \"cf840c807e388e192523903e8d3bc8c0a45d664a47c52f03c7e8277f20127af9\",\n        \"size\": 269957974\n    },\n    \"DynamicObjectCrossing_Town12_Route18166_Weather9.tar.gz\": {\n        \"sha256\": \"bc7358dead934fead1e002e60323b766389966ae368a3f6da40e6fb554a56948\",\n        \"size\": 381053630\n    },\n    \"DynamicObjectCrossing_Town12_Route18169_Weather20.tar.gz\": {\n        \"sha256\": \"cdaf7e58fa29420421f07c05a52199855ff5dcc8f2512c627b26bf3dda697d9f\",\n        \"size\": 326958369\n    },\n    \"DynamicObjectCrossing_Town12_Route18170_Weather21.tar.gz\": {\n        \"sha256\": \"817e1ba10d26c2c2b15dae5556b138cf7b06c6ec4cba73e3c75ce50a7dac04ce\",\n        \"size\": 164009851\n    },\n    \"DynamicObjectCrossing_Town12_Route18171_Weather22.tar.gz\": {\n        \"sha256\": \"b7f99645d83b8638c1e55c609c19f85a226efb755842559fc8326b7525948a9d\",\n        \"size\": 143009017\n    },\n    \"DynamicObjectCrossing_Town12_Route18173_Weather23.tar.gz\": {\n        \"sha256\": \"b6f4ce06c25e6949c654779dea010be55e443fe6fab6eb6595d05653ae38bed6\",\n        \"size\": 161077037\n    },\n    \"DynamicObjectCrossing_Town12_Route18174_Weather25.tar.gz\": {\n        \"sha256\": \"34419a7219233ecdcdd356d034ec18d15578548d6672c7b7d1859f34d63765e5\",\n        \"size\": 345978275\n    },\n    \"DynamicObjectCrossing_Town12_Route18175_Weather0.tar.gz\": {\n        \"sha256\": \"9493adb84996e37131907591f4b278dcf99a03a2e607aa81f594ee4bf63ccf26\",\n        \"size\": 204541780\n    },\n    \"DynamicObjectCrossing_Town12_Route18176_Weather1.tar.gz\": {\n        \"sha256\": \"0305afae90b105b81905a6d9c640edf1df5851679623f0407a191ccaad63346f\",\n        \"size\": 164881020\n    },\n    \"DynamicObjectCrossing_Town12_Route18178_Weather3.tar.gz\": {\n        \"sha256\": \"bfeb856e103d7945b65a8db7a5899f5660484613dd71182c7952c2523668cb8a\",\n        \"size\": 325190396\n    },\n    \"DynamicObjectCrossing_Town12_Route18179_Weather3.tar.gz\": {\n        \"sha256\": \"fdbe25ea3f70b3a9716a85bb160b1903d1851c547fbdeab13f281bcb917e4061\",\n        \"size\": 161073726\n    },\n    \"DynamicObjectCrossing_Town12_Route18182_Weather7.tar.gz\": {\n        \"sha256\": \"2ec379b95c5ba2bc2640ad7a9ccc48edec641e6bd1409c3efe064c7f7523c2ae\",\n        \"size\": 172695049\n    },\n    \"DynamicObjectCrossing_Town12_Route18183_Weather8.tar.gz\": {\n        \"sha256\": \"a7d572dba515a7d933f14ebb01add51d1368d1161eb5c0aea31552b41022fe34\",\n        \"size\": 355920446\n    },\n    \"DynamicObjectCrossing_Town12_Route18186_Weather11.tar.gz\": {\n        \"sha256\": \"6a1d2732dff95b10a0ee943d842b1c16bc82f1ab885d0a0991be4d023ec18793\",\n        \"size\": 278366484\n    },\n    \"DynamicObjectCrossing_Town12_Route18189_Weather14.tar.gz\": {\n        \"sha256\": \"ac0e60253d0f688a9456d2bed969bd20b19252b274876f7f6e65900eabaedeed\",\n        \"size\": 343739624\n    },\n    \"DynamicObjectCrossing_Town12_Route18190_Weather15.tar.gz\": {\n        \"sha256\": \"80a7ddd92b892d30020c0a0c550a8bc651bc175cbff071aff08648c2c658cef6\",\n        \"size\": 292235332\n    },\n    \"DynamicObjectCrossing_Town12_Route18191_Weather8.tar.gz\": {\n        \"sha256\": \"0727e37321a69688c35bafb9234dec5379ed53da255878ca524e339757f41908\",\n        \"size\": 257259200\n    },\n    \"DynamicObjectCrossing_Town12_Route18192_Weather9.tar.gz\": {\n        \"sha256\": \"962398e1e7aea97fbbad0d4ed56e03c9b86d4b0836cef2e4fd50a042ebb660d1\",\n        \"size\": 120659031\n    },\n    \"DynamicObjectCrossing_Town12_Route18193_Weather18.tar.gz\": {\n        \"sha256\": \"6fc5657d7f5f1950107b0cfb2e1462a61fb7ab242f167a73194f65ac0861d942\",\n        \"size\": 151248708\n    },\n    \"DynamicObjectCrossing_Town12_Route18195_Weather20.tar.gz\": {\n        \"sha256\": \"2d16a2dd3f4b71b49cb33419fdad95a6762ef303da55935abfc6d2addda057aa\",\n        \"size\": 134099719\n    },\n    \"DynamicObjectCrossing_Town12_Route18196_Weather21.tar.gz\": {\n        \"sha256\": \"75be286f9148889e1bbf834e35cf0117a7c41ab26535140c081f93b0060850ac\",\n        \"size\": 175620110\n    },\n    \"DynamicObjectCrossing_Town12_Route18199_Weather23.tar.gz\": {\n        \"sha256\": \"a1d2710e616cd1998c25eb2ae9bc60528dd82fa08285bbd0958c22d98857b660\",\n        \"size\": 117764159\n    },\n    \"DynamicObjectCrossing_Town12_Route18201_Weather0.tar.gz\": {\n        \"sha256\": \"baf6b3eee61cdb4b58e419482245d6a882bce2a657d04dacbbe1e1b2faf6d235\",\n        \"size\": 162019148\n    },\n    \"DynamicObjectCrossing_Town12_Route18202_Weather1.tar.gz\": {\n        \"sha256\": \"362042124555da068a8d6f1da7d33d78c18727c0679068ba6f18c357c656e51a\",\n        \"size\": 153510104\n    },\n    \"DynamicObjectCrossing_Town12_Route18203_Weather2.tar.gz\": {\n        \"sha256\": \"fee060303e284f795537de75df23db006186f6d030e7b8c9440b390b5c7bfabf\",\n        \"size\": 157423537\n    },\n    \"DynamicObjectCrossing_Town12_Route18205_Weather3.tar.gz\": {\n        \"sha256\": \"284312cb16d018a59b7df059b83c7a3f0001517c897c5e9e35db3b116eb43bc9\",\n        \"size\": 231293582\n    },\n    \"DynamicObjectCrossing_Town12_Route18206_Weather5.tar.gz\": {\n        \"sha256\": \"4680af875f8758f0fc40d4f323833e47ee7d4c48a3bee57198ddca89c234a361\",\n        \"size\": 381759548\n    },\n    \"DynamicObjectCrossing_Town12_Route18207_Weather6.tar.gz\": {\n        \"sha256\": \"7f2b2de4c329c25d5102fc2042057ff6e7b5d3429dcaad45fc51c3fc62fec7db\",\n        \"size\": 298766361\n    },\n    \"DynamicObjectCrossing_Town12_Route18209_Weather8.tar.gz\": {\n        \"sha256\": \"4e4e20d3c487c49f596acd40dff567ef3c78b848d02f6e09e4533e0469ef13d4\",\n        \"size\": 506315397\n    },\n    \"DynamicObjectCrossing_Town12_Route18210_Weather9.tar.gz\": {\n        \"sha256\": \"c9594d02a221b5a56bcb53a4880146d327b28894b04f965ae1df2a19fdb4dc5b\",\n        \"size\": 370548242\n    },\n    \"DynamicObjectCrossing_Town12_Route18212_Weather11.tar.gz\": {\n        \"sha256\": \"b751fd7ea25d1089e41ba945d74b5f0bedf6fa5e6305dda76731cf64f856be03\",\n        \"size\": 257882900\n    },\n    \"DynamicObjectCrossing_Town12_Route2444_Weather20.tar.gz\": {\n        \"sha256\": \"939e3f238eddda37fc9db8f5ef2539c1a950659fe90f6eed1e179c64e720101b\",\n        \"size\": 269754714\n    },\n    \"DynamicObjectCrossing_Town12_Route2445_Weather21.tar.gz\": {\n        \"sha256\": \"e478225114619c0dcafb6ee0e94d7a416596d26e82a60713c6ffb50a2caeceb5\",\n        \"size\": 166289808\n    },\n    \"DynamicObjectCrossing_Town12_Route2447_Weather23.tar.gz\": {\n        \"sha256\": \"7587686322838e195b1d7849887ab9579ebe4ce5deb20b7dd71234aa145529cd\",\n        \"size\": 116224601\n    },\n    \"DynamicObjectCrossing_Town12_Route2448_Weather23.tar.gz\": {\n        \"sha256\": \"5a72cd2d5e77751ab2516c0577b9b86f521f608b33a684a9c68abf9a29f55b8c\",\n        \"size\": 272621138\n    },\n    \"DynamicObjectCrossing_Town12_Route2449_Weather25.tar.gz\": {\n        \"sha256\": \"b36829fa1bcd9505486a4a439ab6c6d1daf18f6abd02e758458179d86a9f1ad9\",\n        \"size\": 123473936\n    },\n    \"DynamicObjectCrossing_Town12_Route2450_Weather0.tar.gz\": {\n        \"sha256\": \"34d6c70917cb2c260c63c619ca0ef3670319297c3154749f4496cba0a5574526\",\n        \"size\": 1295305143\n    },\n    \"DynamicObjectCrossing_Town12_Route2451_Weather1.tar.gz\": {\n        \"sha256\": \"4dce19042a3e974fb492f5f59c7a9ac23bf9f49ab515c5e45774f168aab8158b\",\n        \"size\": 299680789\n    },\n    \"DynamicObjectCrossing_Town12_Route2452_Weather2.tar.gz\": {\n        \"sha256\": \"042ca82520bb94b259f0c03bea1d688147d3d667dcc8da3de9226c1359d84008\",\n        \"size\": 223320074\n    },\n    \"DynamicObjectCrossing_Town12_Route2453_Weather3.tar.gz\": {\n        \"sha256\": \"6ba61e5e41509b7f01757f05274c8fd0bb36211a2ffadfa75156ec3c7411d5e9\",\n        \"size\": 161323338\n    },\n    \"DynamicObjectCrossing_Town12_Route2454_Weather3.tar.gz\": {\n        \"sha256\": \"e807a85b4b6e05a338b3a0c6380705626e6f5b196983ec9a23af00762474e123\",\n        \"size\": 147899898\n    },\n    \"DynamicObjectCrossing_Town12_Route2456_Weather6.tar.gz\": {\n        \"sha256\": \"2bc99dae0cf0c0e18095f3f453999034bd59c7594d89f11d7a64a2cd357654a9\",\n        \"size\": 341415160\n    },\n    \"DynamicObjectCrossing_Town12_Route2458_Weather8.tar.gz\": {\n        \"sha256\": \"0faf30ee8ab764d562a94e5fbc686853e33e835fec2ca0b81d39af60dcbae79c\",\n        \"size\": 230961793\n    },\n    \"DynamicObjectCrossing_Town12_Route2459_Weather9.tar.gz\": {\n        \"sha256\": \"997972f7e7ae031076a66f46ea003ef307947c8a2c7abd0df27872fbcb662a6a\",\n        \"size\": 281003225\n    },\n    \"DynamicObjectCrossing_Town12_Route2461_Weather11.tar.gz\": {\n        \"sha256\": \"7075ac79bfac458e4677dd971c2633d17269e1d4097417348fcc98a5b7ecaa3e\",\n        \"size\": 134788180\n    },\n    \"DynamicObjectCrossing_Town12_Route2463_Weather13.tar.gz\": {\n        \"sha256\": \"ad8abc6eb2ac8fc64ac8554df6c263e1ac43e84ef43bbcc426e95ed845ee6627\",\n        \"size\": 286908903\n    },\n    \"DynamicObjectCrossing_Town13_Route3223_Weather20.tar.gz\": {\n        \"sha256\": \"b2efbca9cb85798565c71224a1e973031c39fc013062bbb75825a40855001bb4\",\n        \"size\": 552786999\n    },\n    \"DynamicObjectCrossing_Town13_Route3224_Weather21.tar.gz\": {\n        \"sha256\": \"d0c5e4299671b06425e2052c58ad44a4081e987d9bc1343c3d02b2613c2a6044\",\n        \"size\": 170204770\n    },\n    \"DynamicObjectCrossing_Town13_Route3225_Weather22.tar.gz\": {\n        \"sha256\": \"3e8f28d80c46dcf59b6999935421e0a0930a81356b1aee685d40125afe782b65\",\n        \"size\": 250340689\n    },\n    \"DynamicObjectCrossing_Town13_Route3226_Weather23.tar.gz\": {\n        \"sha256\": \"09a239c0f76d8af2b63d0135b7ceec37042a6342085bad4e1f0b846870511c8a\",\n        \"size\": 244653594\n    },\n    \"DynamicObjectCrossing_Town13_Route3229_Weather0.tar.gz\": {\n        \"sha256\": \"aa9a59b092538c30f92b133d3ac6294dc36de84ad0af9abc2989f30856a2501b\",\n        \"size\": 224278249\n    },\n    \"DynamicObjectCrossing_Town13_Route3231_Weather2.tar.gz\": {\n        \"sha256\": \"0e911139078128c5c386964aaec9d7d1b1bdab957c5851a722cde8b44ae2f59f\",\n        \"size\": 395049651\n    },\n    \"DynamicObjectCrossing_Town13_Route3232_Weather3.tar.gz\": {\n        \"sha256\": \"c93d730f1e826b55c712238b0a272e8db89bbd4a181e0b353e8c8e4c597b230a\",\n        \"size\": 239467038\n    },\n    \"DynamicObjectCrossing_Town13_Route3233_Weather3.tar.gz\": {\n        \"sha256\": \"333455f119f06f75907ecb1aabed21eac8911404ec87e84a4701f4451472a3e3\",\n        \"size\": 222303428\n    },\n    \"DynamicObjectCrossing_Town13_Route3234_Weather5.tar.gz\": {\n        \"sha256\": \"8105d939e4395979fd768bc71aad366a4803462f8ef1f01fdd54fa45fc3eba07\",\n        \"size\": 267160429\n    },\n    \"DynamicObjectCrossing_Town13_Route3237_Weather8.tar.gz\": {\n        \"sha256\": \"3e45a43b9e0e23020e8de31f2b89c586e027947130ebe6f896607b8cf1cf7ee7\",\n        \"size\": 395823096\n    },\n    \"DynamicObjectCrossing_Town13_Route3238_Weather9.tar.gz\": {\n        \"sha256\": \"7c7abefe31089fb695b1d823e1a4b6abad831d78595aaaefb2d036e4790add01\",\n        \"size\": 296507236\n    },\n    \"DynamicObjectCrossing_Town13_Route3239_Weather10.tar.gz\": {\n        \"sha256\": \"23b8312c01101118f447407ee86285fb27239ab24355081906b1a95e79fe52b3\",\n        \"size\": 195901548\n    },\n    \"DynamicObjectCrossing_Town13_Route3240_Weather11.tar.gz\": {\n        \"sha256\": \"b6552b139e6398a66f20d0eb880c6990039f8f1a65fdb679aa2c511eb913e237\",\n        \"size\": 315159248\n    },\n    \"DynamicObjectCrossing_Town15_Route24313_Weather1.tar.gz\": {\n        \"sha256\": \"23b849224e1c0c564cf35df3b1d9bc39ecbc3c81a3937030b1bd2d25e023fdbf\",\n        \"size\": 401498249\n    },\n    \"DynamicObjectCrossing_Town15_Route24323_Weather12.tar.gz\": {\n        \"sha256\": \"709f6cb46a2cfb6adbcadbfc80dc88434130d9f8df53ebad7b8d42fc45c6c472\",\n        \"size\": 307360149\n    },\n    \"DynamicObjectCrossing_Town15_Route24333_Weather25.tar.gz\": {\n        \"sha256\": \"b061bf8cd59dbdf3302e41eb9538bd1e80ef26da41595f5ddfe7b7082bad52ed\",\n        \"size\": 418532017\n    },\n    \"DynamicObjectCrossing_Town15_Route24343_Weather9.tar.gz\": {\n        \"sha256\": \"ff82336e763a1dfc0ac29dc88b0cf6cda564f81e2755452042a401165733d2d8\",\n        \"size\": 475634918\n    },\n    \"DynamicObjectCrossing_Town15_Route24363_Weather6.tar.gz\": {\n        \"sha256\": \"86eea752787fe6e5745830856f09d4aba0011a57d0447707406ea0ddd4b96099\",\n        \"size\": 413293715\n    },\n    \"DynamicObjectCrossing_Town15_Route24383_Weather2.tar.gz\": {\n        \"sha256\": \"a79b361be8c8023fdf6dc763989faa7977c4f8987ad8ec19e6152e65666b743b\",\n        \"size\": 470801052\n    },\n    \"EnterActorFlow_Town03_Route27235_Weather2.tar.gz\": {\n        \"sha256\": \"d92267fa6f18d6b95bb0eb981185801a1a81934cb35554521c32aa15a66866af\",\n        \"size\": 110205965\n    },\n    \"EnterActorFlow_Town03_Route27240_Weather8.tar.gz\": {\n        \"sha256\": \"8ca80e67a93e8248230301797f1df69c9431041b054ffb4253e7bae9f5fcd13d\",\n        \"size\": 459753939\n    },\n    \"EnterActorFlow_Town03_Route27265_Weather10.tar.gz\": {\n        \"sha256\": \"439e3e5bc56af96c970acb8aafa908cdf0e478c29ac0400698af1fee4b541f20\",\n        \"size\": 142148682\n    },\n    \"EnterActorFlow_Town03_Route27280_Weather1.tar.gz\": {\n        \"sha256\": \"b54b2b3c7ee8603d8a8ac8452bc838198e4f7af868c4e1294abe700b4e480bf0\",\n        \"size\": 180055539\n    },\n    \"EnterActorFlow_Town03_Route27285_Weather7.tar.gz\": {\n        \"sha256\": \"ad42365b5dd2ded36bc0edf0beafe6497a8bac826b75183805f4145afbc81223\",\n        \"size\": 209813492\n    },\n    \"EnterActorFlow_Town03_Route27315_Weather14.tar.gz\": {\n        \"sha256\": \"d0129f71334c4e9a18a4cac48d038a1818991feb0d6260c34d7d959f4ccc0b30\",\n        \"size\": 216215158\n    },\n    \"EnterActorFlow_Town03_Route27320_Weather21.tar.gz\": {\n        \"sha256\": \"568eb182bd506a9a1720d56873791ae2c93155691fbb35b41987f4f642325b33\",\n        \"size\": 137228212\n    },\n    \"EnterActorFlow_Town03_Route27325_Weather0.tar.gz\": {\n        \"sha256\": \"47daa3c67913e89b8c821dfad31d138af80866bae5b7cbaaf259d27023a4f6e9\",\n        \"size\": 276351177\n    },\n    \"EnterActorFlow_Town04_Route27309_Weather8.tar.gz\": {\n        \"sha256\": \"d76b8e6bdb48508d6cd39348358a39ed72050e8fac8ada1d767568267b1803f3\",\n        \"size\": 136516010\n    },\n    \"EnterActorFlow_Town04_Route27314_Weather13.tar.gz\": {\n        \"sha256\": \"e44c9c1de95eb4fab36f37d13bf37da6107d2ba89b63d1a07c8dbfdb6edb0a5c\",\n        \"size\": 105512663\n    },\n    \"EnterActorFlow_Town04_Route27339_Weather15.tar.gz\": {\n        \"sha256\": \"414f0881dd28261abdfa5a6d9b4bad4827bee2b2881c2ba0d03796b045f85dab\",\n        \"size\": 597088882\n    },\n    \"EnterActorFlow_Town04_Route27344_Weather22.tar.gz\": {\n        \"sha256\": \"19bb17bc64724af21d9560108705831489b9304e90821954a31febc996b5e826\",\n        \"size\": 459243419\n    },\n    \"EnterActorFlow_Town04_Route27349_Weather1.tar.gz\": {\n        \"sha256\": \"7dd0034d48e772413c2a77822b2bafa755bbf5472474a533c64ad20f85bfbe41\",\n        \"size\": 147787110\n    },\n    \"EnterActorFlow_Town04_Route27369_Weather25.tar.gz\": {\n        \"sha256\": \"e3e5cd5c7e2465492f2881be0731c8b3dce54ac8d5ebca3eebdab854344bd5c0\",\n        \"size\": 415670100\n    },\n    \"EnterActorFlow_Town04_Route27379_Weather9.tar.gz\": {\n        \"sha256\": \"78ed18585fe95122e5c19a3630b2b5ba74854dbe0696d519f60d2815ddab3be4\",\n        \"size\": 544713756\n    },\n    \"EnterActorFlow_Town05_Route27426_Weather10.tar.gz\": {\n        \"sha256\": \"19996038966751017ca3e781eb7b5904fa91c0c89a42f6d8e379bc1452edfa75\",\n        \"size\": 123307159\n    },\n    \"EnterActorFlow_Town05_Route27486_Weather0.tar.gz\": {\n        \"sha256\": \"7e37034af855b5860d9f050604a61b2b4247fb6747edc0057bc7c590f8e9b359\",\n        \"size\": 334270116\n    },\n    \"EnterActorFlow_Town05_Route27491_Weather6.tar.gz\": {\n        \"sha256\": \"a424172e9cf24ce364fecaca47c7293d11a77a86af6b6176c9c563493ae2e073\",\n        \"size\": 410689477\n    },\n    \"EnterActorFlow_Town05_Route27506_Weather23.tar.gz\": {\n        \"sha256\": \"ae30b99ea2e9425630cfdb5c94f3940ead5c51c01d26485988a8d0246f288ad9\",\n        \"size\": 236561149\n    },\n    \"EnterActorFlow_Town11_Route27367_Weather22.tar.gz\": {\n        \"sha256\": \"a732d35b2169a1a329b67defdcdae28140e11885305defef0a7d910d9d85c943\",\n        \"size\": 30435224\n    },\n    \"EnterActorFlow_Town11_Route27372_Weather1.tar.gz\": {\n        \"sha256\": \"cdd44fd85a7975e516abe14dcf48c13ddbe53482cd0e2e0760b48b6462290a82\",\n        \"size\": 52694399\n    },\n    \"EnterActorFlow_Town11_Route27377_Weather7.tar.gz\": {\n        \"sha256\": \"23072db0018c9aa3933a0a62ab426c35353102c4428b071ee70cda3a029aa1ad\",\n        \"size\": 52791491\n    },\n    \"EnterActorFlow_Town11_Route27382_Weather12.tar.gz\": {\n        \"sha256\": \"8d91882829e96bfddb7421ee1c84d3dedc5e98c06085510da6ab48a0b5a02b36\",\n        \"size\": 72270935\n    },\n    \"EnterActorFlow_Town11_Route27397_Weather3.tar.gz\": {\n        \"sha256\": \"e0a4e11a75496b772392945b22e03fca38b96082b508201d3dad8865043d899f\",\n        \"size\": 46445134\n    },\n    \"EnterActorFlow_Town11_Route27402_Weather9.tar.gz\": {\n        \"sha256\": \"e2ed9289bb006a21905943983ffa3b9f36ea03e5f43401e3353125d75ff8ec81\",\n        \"size\": 79757754\n    },\n    \"EnterActorFlow_Town11_Route27412_Weather21.tar.gz\": {\n        \"sha256\": \"178fc1857de8b3700b9e9da70187e100bfccaab112de1bd862c01dc33064c177\",\n        \"size\": 57726160\n    },\n    \"EnterActorFlow_Town11_Route27417_Weather0.tar.gz\": {\n        \"sha256\": \"c80c281287b567d5f5e2d8a6f48699f611f0c984f92aaf73ecf452389a40b9dd\",\n        \"size\": 109074590\n    },\n    \"EnterActorFlow_Town11_Route27427_Weather11.tar.gz\": {\n        \"sha256\": \"b109cb21b349740af22232d062112528d53699e4d89f484bd9815367a967e7cf\",\n        \"size\": 35193248\n    },\n    \"EnterActorFlow_Town11_Route27447_Weather8.tar.gz\": {\n        \"sha256\": \"b79b8d64acf18022bd94b076e38fdd3c647ad5c7e921fd946ce36540cdec791e\",\n        \"size\": 97141822\n    },\n    \"EnterActorFlow_Town11_Route27462_Weather26.tar.gz\": {\n        \"sha256\": \"7477b22e6c8c5cc4bfafb79ce2e93d08eecc90cab89127dbf052b17756f822e3\",\n        \"size\": 55444981\n    },\n    \"EnterActorFlow_Town12_Route11440_Weather3.tar.gz\": {\n        \"sha256\": \"38b8ce845aeed21b3aa2f6627ef71b9ab864f22ed82e5d4990f616771aa58475\",\n        \"size\": 91784911\n    },\n    \"EnterActorFlow_Town12_Route11443_Weather6.tar.gz\": {\n        \"sha256\": \"e75fd2f312499d6e7471cbbf0cac5b95c8df813a28787baa64f81ebdce603399\",\n        \"size\": 102132828\n    },\n    \"EnterActorFlow_Town12_Route11445_Weather8.tar.gz\": {\n        \"sha256\": \"e66b07d799afa976f1f8b6a813832efc69eec0200d5a43f9833f101c4391e25b\",\n        \"size\": 205872317\n    },\n    \"EnterActorFlow_Town12_Route11447_Weather10.tar.gz\": {\n        \"sha256\": \"c6b460169ea29e74e174c9e8d1cee6047890f1f8678b1d83390e03079ebaefe3\",\n        \"size\": 206964911\n    },\n    \"EnterActorFlow_Town12_Route11450_Weather13.tar.gz\": {\n        \"sha256\": \"566f9798a8006aa05271e193d0e917f9f128977d005c884489cd132de532a840\",\n        \"size\": 432850598\n    },\n    \"EnterActorFlow_Town12_Route11451_Weather14.tar.gz\": {\n        \"sha256\": \"90e928fa0b72a553bbea0c48532ba4ad7c17a8a44dd5ed63b341e387d80667f2\",\n        \"size\": 250386593\n    },\n    \"EnterActorFlow_Town12_Route11452_Weather15.tar.gz\": {\n        \"sha256\": \"3317d95bada8f1cf5ff261ded979a20fa5d9ab2194f5721c875f2e93820fbff4\",\n        \"size\": 201980399\n    },\n    \"EnterActorFlow_Town12_Route11453_Weather8.tar.gz\": {\n        \"sha256\": \"8f1b0210336cea6f1cb6af2efc053a50a27d86201b499169a274d866bdeb1cfd\",\n        \"size\": 756698134\n    },\n    \"EnterActorFlow_Town12_Route11456_Weather19.tar.gz\": {\n        \"sha256\": \"9d8f47e2733bcadf81e10fb5b05a298ccb82f45dd5c96adddbc1d5af3cf81820\",\n        \"size\": 226468020\n    },\n    \"EnterActorFlow_Town12_Route11458_Weather21.tar.gz\": {\n        \"sha256\": \"d04ee1090a0462cef9f51b65db9cb4c7fc1772e18471d6b9d3b3ca24192c3ff1\",\n        \"size\": 409869659\n    },\n    \"EnterActorFlow_Town12_Route11460_Weather23.tar.gz\": {\n        \"sha256\": \"0a74019cbc3e48e781cb4286decfea1a733b8b1cc1e8f219a3efa3cf33b45440\",\n        \"size\": 194620319\n    },\n    \"EnterActorFlow_Town12_Route11461_Weather23.tar.gz\": {\n        \"sha256\": \"70089f46cfe8064e02cc0006f8e66b47224f46ae64fe510d3db315116f989b04\",\n        \"size\": 115057019\n    },\n    \"EnterActorFlow_Town12_Route11462_Weather25.tar.gz\": {\n        \"sha256\": \"36f6255124d7aa3a628d75c059a1b60c69482b6cccec53c9c2850fe9b0be64b0\",\n        \"size\": 115632645\n    },\n    \"EnterActorFlow_Town12_Route11464_Weather1.tar.gz\": {\n        \"sha256\": \"dea7cd62ac8f3791e3ddf13b3a4615daf057249002eec523dc02fcaf60b17489\",\n        \"size\": 193296713\n    },\n    \"EnterActorFlow_Town12_Route11465_Weather2.tar.gz\": {\n        \"sha256\": \"0ea5d52ca58eaea12249e82cd221f3c41db2842beac1885c985566d9516da374\",\n        \"size\": 191078347\n    },\n    \"EnterActorFlow_Town12_Route11466_Weather3.tar.gz\": {\n        \"sha256\": \"a199090ba6b1daaf5cf87b1ec1872b6ac12e77d43143a74eb07828e0958bbbea\",\n        \"size\": 248278950\n    },\n    \"EnterActorFlow_Town12_Route11467_Weather3.tar.gz\": {\n        \"sha256\": \"e72a4c596f07bec0d7761350eb5c5589922f60afe09817bcb85387c0b8a90eda\",\n        \"size\": 227775412\n    },\n    \"EnterActorFlow_Town12_Route11472_Weather9.tar.gz\": {\n        \"sha256\": \"d5f0ace7d99b7eea1f67d903500b274bf191ed5c4455d8b5e78c30f7731fe437\",\n        \"size\": 159965023\n    },\n    \"EnterActorFlow_Town12_Route11474_Weather11.tar.gz\": {\n        \"sha256\": \"5b077519038758084854ccbf3762f811bc27383dbc18060617998bf5317ebe18\",\n        \"size\": 161044906\n    },\n    \"EnterActorFlow_Town12_Route11476_Weather13.tar.gz\": {\n        \"sha256\": \"014796a4ec52ec3c919745d6ef50b728a454034e3364b34fc0c7d2a3bc197821\",\n        \"size\": 93174013\n    },\n    \"EnterActorFlow_Town12_Route11477_Weather14.tar.gz\": {\n        \"sha256\": \"d49f534630fb4462b1e6312de3567a757abcda139c9b3dd65960659321c9f12f\",\n        \"size\": 76845613\n    },\n    \"EnterActorFlow_Town12_Route11478_Weather15.tar.gz\": {\n        \"sha256\": \"bbb305148298621400aac0a7e1ce1a5d916f5f6f5695911456097a358bbcd2cc\",\n        \"size\": 358648991\n    },\n    \"EnterActorFlow_Town12_Route11480_Weather9.tar.gz\": {\n        \"sha256\": \"74fd4ed2cdb604b8bfc41b24e683799bb6a1c2817a1e596c67e4063c5fcdb0bb\",\n        \"size\": 403674611\n    },\n    \"EnterActorFlow_Town12_Route11481_Weather18.tar.gz\": {\n        \"sha256\": \"6527fe796dfb0f25c0e93d2bc6855443578ae440687af7e29d5134ca0b9c689f\",\n        \"size\": 868868969\n    },\n    \"EnterActorFlow_Town12_Route11482_Weather19.tar.gz\": {\n        \"sha256\": \"16cb5559a4b2b415ccc3fd684c47a0e6574a90ce6dd38fd2b8035e908cd53012\",\n        \"size\": 238517188\n    },\n    \"EnterActorFlow_Town12_Route11483_Weather20.tar.gz\": {\n        \"sha256\": \"0182da853dd65ceb7084bd225e73fbe201faa537c2faa847f3ced7b6b2206a57\",\n        \"size\": 351955951\n    },\n    \"EnterActorFlow_Town12_Route11484_Weather21.tar.gz\": {\n        \"sha256\": \"203ea3ef44e9934103f4587b410f87c1b5b9b25b192e16ba5df66ce679864da4\",\n        \"size\": 318166572\n    },\n    \"EnterActorFlow_Town12_Route11485_Weather22.tar.gz\": {\n        \"sha256\": \"5c94a588cc2282b2413ca8ab3131c1bd3ababe19205a5d1f57d3d13be78cfd65\",\n        \"size\": 698144426\n    },\n    \"EnterActorFlow_Town12_Route11487_Weather23.tar.gz\": {\n        \"sha256\": \"c1d378071f64deaee9503abe9cefe4ed158ebca1ebc3511d9e0ed25a8f707db7\",\n        \"size\": 466372759\n    },\n    \"EnterActorFlow_Town12_Route11489_Weather0.tar.gz\": {\n        \"sha256\": \"90c029564092397c960dc8acea0529877f086952ddd0c0aa8dd6134e8f5d21a1\",\n        \"size\": 238969922\n    },\n    \"EnterActorFlow_Town12_Route11490_Weather1.tar.gz\": {\n        \"sha256\": \"a9e9406fbaefd49a0b1c27d0a784c26b4fc4a9dd7218aded7348addbd63135ae\",\n        \"size\": 256441182\n    },\n    \"EnterActorFlow_Town12_Route11491_Weather2.tar.gz\": {\n        \"sha256\": \"76089e2c0a170dd8180db4e613395e3dbb93eeec4591b57d35693619dfb66def\",\n        \"size\": 785635586\n    },\n    \"EnterActorFlow_Town12_Route11492_Weather3.tar.gz\": {\n        \"sha256\": \"bb992ea441c3b7146f3d3a08e28ec3b44f08e89b4e5d56893e777f58af164041\",\n        \"size\": 618093087\n    },\n    \"EnterActorFlow_Town12_Route11495_Weather6.tar.gz\": {\n        \"sha256\": \"100bcc9b037a0a1cec9c7f14c096a9cba0df77ff7cb77a00bd1a9621ff3dfdaf\",\n        \"size\": 415353170\n    },\n    \"EnterActorFlow_Town12_Route11496_Weather7.tar.gz\": {\n        \"sha256\": \"bb0d8f393b01a1a20068023790320427363db9b0e76faa6f137700ff226de91b\",\n        \"size\": 240534987\n    },\n    \"EnterActorFlow_Town12_Route11497_Weather8.tar.gz\": {\n        \"sha256\": \"fb03062454f6eb7cc288d15f39a249f69783d081f26a04160a391fd8cf5ddee8\",\n        \"size\": 122593329\n    },\n    \"EnterActorFlow_Town12_Route11499_Weather10.tar.gz\": {\n        \"sha256\": \"11e4d903a5701086ff48507c621354eda7ca6afd43e329c6bba197600f778f7e\",\n        \"size\": 127652287\n    },\n    \"EnterActorFlow_Town12_Route11500_Weather11.tar.gz\": {\n        \"sha256\": \"329b4e1385265219b38e14ed8a9c53b479d85b66d5258f8d3e6c15f65dfe0703\",\n        \"size\": 462981732\n    },\n    \"EnterActorFlow_Town12_Route11503_Weather14.tar.gz\": {\n        \"sha256\": \"e6fa4a0d262688169007b7a75530206d6a48853e3b13cd173b3fb2f74e034772\",\n        \"size\": 505860765\n    },\n    \"EnterActorFlow_Town12_Route11505_Weather8.tar.gz\": {\n        \"sha256\": \"abf7757d3cd858c70c5340ae45646e42cd4660feb4a59ef48d79fa2d3ae68e9d\",\n        \"size\": 127019156\n    },\n    \"EnterActorFlow_Town12_Route11506_Weather9.tar.gz\": {\n        \"sha256\": \"f7643ca5fc0693e7f5e10922710f6f2930c5f4b767182ed6ea7bf8bab8329e1e\",\n        \"size\": 363305265\n    },\n    \"EnterActorFlow_Town12_Route11509_Weather20.tar.gz\": {\n        \"sha256\": \"88f3831808de71993ae44858fdb4e4d9354cdd2ba318fdd20006c139dda2c922\",\n        \"size\": 149281371\n    },\n    \"EnterActorFlow_Town12_Route11510_Weather21.tar.gz\": {\n        \"sha256\": \"a9df21b56cbcfe8f1dbd6a631236f5b6a778d0e7f6827b3ec2eea74ba50a6e5c\",\n        \"size\": 371774946\n    },\n    \"EnterActorFlow_Town12_Route11514_Weather25.tar.gz\": {\n        \"sha256\": \"5e4db2824bfb13abeafa34b6c336d39f8a1ace3b83c47bd54451f4996e5fc3bc\",\n        \"size\": 174191561\n    },\n    \"EnterActorFlow_Town12_Route11515_Weather0.tar.gz\": {\n        \"sha256\": \"4e093dedf9cb0ec8a517ca52f5656aa1e32e54e41adc9dee3a147718a87b4fcd\",\n        \"size\": 127377757\n    },\n    \"EnterActorFlow_Town12_Route11516_Weather1.tar.gz\": {\n        \"sha256\": \"df7876a4a71067e7d184c8b0e1dc6a0f888f73dc0300d68af3c9cc76fa92ce6d\",\n        \"size\": 459139697\n    },\n    \"EnterActorFlow_Town12_Route11517_Weather2.tar.gz\": {\n        \"sha256\": \"5474705a149834a6e6c308b0c1dffe45dddee49bd6e735a920e8aa2f336b7f5d\",\n        \"size\": 655372016\n    },\n    \"EnterActorFlow_Town12_Route11519_Weather3.tar.gz\": {\n        \"sha256\": \"e4aff32927e55364b8cc15b284b53140d4e46978778e8bf9994c1f6977d43256\",\n        \"size\": 159144661\n    },\n    \"EnterActorFlow_Town12_Route11522_Weather7.tar.gz\": {\n        \"sha256\": \"ae250dc39b94f3e0b2ecedd19cc19ab822d520b541d0d4a71c68e1992af6ff52\",\n        \"size\": 145074771\n    },\n    \"EnterActorFlow_Town12_Route11523_Weather8.tar.gz\": {\n        \"sha256\": \"c0faef0425ba4bfe4eb0ba3009fe3040558211383a5b5ad580f554d7bf7f82f6\",\n        \"size\": 212651931\n    },\n    \"EnterActorFlow_Town12_Route11527_Weather12.tar.gz\": {\n        \"sha256\": \"6dc2f280a9d905cf6251bf878eee475a5bbb4106b7993cdee4536c55c4703630\",\n        \"size\": 75197071\n    },\n    \"EnterActorFlow_Town12_Route11529_Weather14.tar.gz\": {\n        \"sha256\": \"a7c6cb23ef777cb3a5989bdbe44a0d32cd08e65dc1b900a5d42d8b27fe5fa13e\",\n        \"size\": 399102661\n    },\n    \"EnterActorFlow_Town12_Route11531_Weather8.tar.gz\": {\n        \"sha256\": \"ac26d67f0133c34ea93aff6ffb326a8c3128314dd0c6312e2068e8286e156c17\",\n        \"size\": 162979104\n    },\n    \"EnterActorFlow_Town12_Route11533_Weather18.tar.gz\": {\n        \"sha256\": \"d049a895eb8dd4e244128f30ceb0dace6f47b3d36a34bd94232aa05bcb537da3\",\n        \"size\": 173076205\n    },\n    \"EnterActorFlow_Town12_Route11538_Weather23.tar.gz\": {\n        \"sha256\": \"d6fc0fd294a6cac5d13fd6f9ca9a75ef601f6582f68d54ffa543645f4544b941\",\n        \"size\": 331717178\n    },\n    \"EnterActorFlow_Town12_Route11541_Weather0.tar.gz\": {\n        \"sha256\": \"9422722b26e1a17f8d8d58e5f60f800a7cdf33fcbe3085fd2b5314f96ee99e04\",\n        \"size\": 92950963\n    },\n    \"EnterActorFlow_Town12_Route11543_Weather2.tar.gz\": {\n        \"sha256\": \"84e2f4962221c1a4fa6e708110028292f6ae94af646104188bd0792620e60d6a\",\n        \"size\": 374730435\n    },\n    \"EnterActorFlow_Town12_Route11544_Weather3.tar.gz\": {\n        \"sha256\": \"48e03c033cc8cdafd4d8683da414cef91169bc026bc5feeaec95e3230516646b\",\n        \"size\": 505684948\n    },\n    \"EnterActorFlow_Town12_Route11545_Weather3.tar.gz\": {\n        \"sha256\": \"9c04a0fad90a818e5d10328ff929be672322eeda4ac67981ab40a8239a4769b1\",\n        \"size\": 394112587\n    },\n    \"EnterActorFlow_Town12_Route11547_Weather6.tar.gz\": {\n        \"sha256\": \"129d8841ef46ce42615889f3a68c3e7c4ad7629cbb12143660ca6034d93e3c64\",\n        \"size\": 288270996\n    },\n    \"EnterActorFlow_Town12_Route11548_Weather7.tar.gz\": {\n        \"sha256\": \"6f85f6ba0c96ec423be2739a224082dca0b1d6bf604900c2a3693945ce4d2bde\",\n        \"size\": 772362283\n    },\n    \"EnterActorFlow_Town12_Route11549_Weather8.tar.gz\": {\n        \"sha256\": \"e555e14b2436d7708419e0a328d71cf2fdc4a691792f747062cce50bb28365fa\",\n        \"size\": 681127231\n    },\n    \"EnterActorFlow_Town12_Route11550_Weather9.tar.gz\": {\n        \"sha256\": \"6a714d928a9055bf0bd0235339737b8cf12cdc976087ff92e55b39966d62930e\",\n        \"size\": 160807121\n    },\n    \"EnterActorFlow_Town12_Route11551_Weather10.tar.gz\": {\n        \"sha256\": \"0f9b6570e5613c5bdebe54f64659e8940397e81dd8f59f3c7ae0a702ce53793b\",\n        \"size\": 602074291\n    },\n    \"EnterActorFlow_Town12_Route11552_Weather11.tar.gz\": {\n        \"sha256\": \"d64ac20e73f2ea6ddb93f18804b3b0103bc961990ce244d3615fab1fdc3ef19e\",\n        \"size\": 76597512\n    },\n    \"EnterActorFlow_Town12_Route11554_Weather13.tar.gz\": {\n        \"sha256\": \"bbdf693bf3659e0aba3a679a8b3ac068a0503aefa0ca30aaf5b0e24336b5f05c\",\n        \"size\": 301682524\n    },\n    \"EnterActorFlow_Town12_Route11555_Weather14.tar.gz\": {\n        \"sha256\": \"e4c8aaa4e43f0aef7211843acf9ce8f1709c394c8ec2853f61f91f23cceb20fc\",\n        \"size\": 648963680\n    },\n    \"EnterActorFlow_Town12_Route11556_Weather15.tar.gz\": {\n        \"sha256\": \"8673249cd6a62faaafd6f6eb69191323fd654940fa452e57c92ef21770428183\",\n        \"size\": 83260183\n    },\n    \"EnterActorFlow_Town12_Route11557_Weather8.tar.gz\": {\n        \"sha256\": \"0c1b34c6e5fbb9e36e184587193381cf86f2e7326d5231e880bcdc95dc36a515\",\n        \"size\": 287146758\n    },\n    \"EnterActorFlow_Town12_Route11559_Weather18.tar.gz\": {\n        \"sha256\": \"cb42f8dba0e1d71e4fb84544e8f1eefa3e05520c65aa9325967d25fafa5f6ee5\",\n        \"size\": 188871767\n    },\n    \"EnterActorFlow_Town12_Route11566_Weather25.tar.gz\": {\n        \"sha256\": \"7411aa230f26f11f7b74dee6c0cd1a5c65d36acf69cc6e5265ffe3b950ae5051\",\n        \"size\": 578306739\n    },\n    \"EnterActorFlow_Town12_Route11570_Weather3.tar.gz\": {\n        \"sha256\": \"2ed0b76e332a1b261669a4d0c450e522fdb0ec5aac2e12b3b1135fcb781ebae8\",\n        \"size\": 460257568\n    },\n    \"EnterActorFlow_Town12_Route11571_Weather3.tar.gz\": {\n        \"sha256\": \"3a6617fd513df2e8076cd6a3aa1f1a42d934b19b519b915b6b161dd28a8d2651\",\n        \"size\": 102218359\n    },\n    \"EnterActorFlow_Town12_Route11572_Weather5.tar.gz\": {\n        \"sha256\": \"aeaea14a93dcc926e1a90f0cff6669ba1f66064d4a4b1bc45904408b11f0ae4c\",\n        \"size\": 244932874\n    },\n    \"EnterActorFlow_Town12_Route11573_Weather6.tar.gz\": {\n        \"sha256\": \"ea73e137c66f72ae68ecc9137b68be95d9fccf5569041b7e619eb13016cbd8d2\",\n        \"size\": 85126384\n    },\n    \"EnterActorFlow_Town12_Route11575_Weather8.tar.gz\": {\n        \"sha256\": \"12a1c5d110caf832d302291ec1a2f5c33feaa74662d03b92cb22a0f2d2bd4713\",\n        \"size\": 309946006\n    },\n    \"EnterActorFlow_Town12_Route11576_Weather9.tar.gz\": {\n        \"sha256\": \"27fc05bd3d060cece6c23eeae44bbef152932e7e077b6f8e36b2b23af273b7a5\",\n        \"size\": 884090987\n    },\n    \"EnterActorFlow_Town12_Route11578_Weather11.tar.gz\": {\n        \"sha256\": \"b342b3941dd2677232e95c6ebf31536d5e79525aaf30783d11ef69e43e1dd791\",\n        \"size\": 76740397\n    },\n    \"EnterActorFlow_Town12_Route11579_Weather12.tar.gz\": {\n        \"sha256\": \"8816ae44bba3fd14c3e6141501261ee7802592d69704cc1a7588ccc437b5fab0\",\n        \"size\": 268139232\n    },\n    \"EnterActorFlow_Town12_Route11581_Weather14.tar.gz\": {\n        \"sha256\": \"6796beed146918c7d44e0367ec2096e2b25e98389b34254810c72ac68b8e7722\",\n        \"size\": 82953242\n    },\n    \"EnterActorFlow_Town12_Route11582_Weather15.tar.gz\": {\n        \"sha256\": \"3f6141b39718e7e53239a51c14b96ed7dbee2ca15025bdd8e497aa8cb603e1cc\",\n        \"size\": 89413702\n    },\n    \"EnterActorFlow_Town12_Route11584_Weather9.tar.gz\": {\n        \"sha256\": \"4c07273ebe276b0005733b9b4dd30d5edadc3b35e740760fe48b73f03be14673\",\n        \"size\": 585582939\n    },\n    \"EnterActorFlow_Town12_Route11587_Weather20.tar.gz\": {\n        \"sha256\": \"51e9e1a0b690a816edaaa0a97ce84e88d121b094e5063607c0e8314506672f57\",\n        \"size\": 520807583\n    },\n    \"EnterActorFlow_Town12_Route11588_Weather21.tar.gz\": {\n        \"sha256\": \"aac7f63d81ed3ec32ddd259f458a21f3141c014e80b6efa781f9ba966d6569bc\",\n        \"size\": 140664032\n    },\n    \"EnterActorFlow_Town12_Route11590_Weather23.tar.gz\": {\n        \"sha256\": \"2d7edd7741aa2a96e1257a9b30a01c49fed3e70061144ec2c5338dcd586ff355\",\n        \"size\": 473516573\n    },\n    \"EnterActorFlow_Town12_Route11591_Weather23.tar.gz\": {\n        \"sha256\": \"8a054d2c0e39c8ff37950c0abb9020f9371b90aa2f0de94e8d64a18439a11126\",\n        \"size\": 303616327\n    },\n    \"EnterActorFlow_Town12_Route11592_Weather25.tar.gz\": {\n        \"sha256\": \"a71184a6c20f033f466d5495984b921a312b6d2a4113cbddbe7dfbfb30447628\",\n        \"size\": 106942765\n    },\n    \"EnterActorFlow_Town12_Route11593_Weather0.tar.gz\": {\n        \"sha256\": \"4e4e4719d4f6d903c57061810a62872bd91ba2fbc41c06051e4598b5a3499eac\",\n        \"size\": 790553280\n    },\n    \"EnterActorFlow_Town12_Route11596_Weather3.tar.gz\": {\n        \"sha256\": \"31f9e3b0e3e94e06bb77a7a57cbcda4004f944d509281c1a28f18220f3fa458f\",\n        \"size\": 244993418\n    },\n    \"EnterActorFlow_Town12_Route11601_Weather8.tar.gz\": {\n        \"sha256\": \"e4e1dacd111b2a54022ebd18f23f70060db9bcc013b2c7e217ca21e380a9f80d\",\n        \"size\": 172024603\n    },\n    \"EnterActorFlow_Town12_Route11603_Weather10.tar.gz\": {\n        \"sha256\": \"ce0c1e2447f3e4bc2930787907bd688fe14c1b2e8dfd668a55a7421d02965bd5\",\n        \"size\": 597606372\n    },\n    \"EnterActorFlow_Town12_Route11604_Weather11.tar.gz\": {\n        \"sha256\": \"ffd9ce4b2abc9418a7c80fe60ef088ef562327222b52b894179de6f3ba322eea\",\n        \"size\": 414896932\n    },\n    \"EnterActorFlow_Town12_Route11609_Weather8.tar.gz\": {\n        \"sha256\": \"bbc9eb2113f65736b6657c823ac5f764f40499866cfabd0fc3624b6527dc0f06\",\n        \"size\": 215816904\n    },\n    \"EnterActorFlow_Town12_Route11610_Weather9.tar.gz\": {\n        \"sha256\": \"a32dcd0b873a7ca4bcd87c0fb6140780d22f6db76098bbd723f228ec7caf3d52\",\n        \"size\": 381346160\n    },\n    \"EnterActorFlow_Town12_Route11611_Weather18.tar.gz\": {\n        \"sha256\": \"5a9cf6b19af10414d54d0f5f5e4fa8ab1aa292887f225546928bb2423e6b6568\",\n        \"size\": 203387916\n    },\n    \"EnterActorFlow_Town12_Route11613_Weather20.tar.gz\": {\n        \"sha256\": \"3578ddb23e4ee8621a45d21b47be43b8b661ab6211aef3d8b3b167ffa1d835f5\",\n        \"size\": 418708734\n    },\n    \"EnterActorFlow_Town12_Route11616_Weather23.tar.gz\": {\n        \"sha256\": \"473e8608b5b31329af8a81e4737fe9f7a1f38577dd3a55f9558f0098df81d67a\",\n        \"size\": 380406865\n    },\n    \"EnterActorFlow_Town12_Route11617_Weather23.tar.gz\": {\n        \"sha256\": \"0aa2805b8d7e9568891d1c97d72dc470f5a456cc7676f84a36269c99ffd12282\",\n        \"size\": 144396610\n    },\n    \"EnterActorFlow_Town12_Route11623_Weather3.tar.gz\": {\n        \"sha256\": \"93efc639ce5beb9814355341953d6b42727d17b4ab3884ac657cd55f53e3f299\",\n        \"size\": 235915827\n    },\n    \"EnterActorFlow_Town12_Route11624_Weather5.tar.gz\": {\n        \"sha256\": \"45414a5ca6ad7f28a4c1279aff0f58ff1aa45eece4109cc7fa3a5ed3b7cdd801\",\n        \"size\": 147831410\n    },\n    \"EnterActorFlow_Town12_Route11625_Weather6.tar.gz\": {\n        \"sha256\": \"e07f27179c301fbd7510cc618e15a908724c8df26a04f91ddc97e71cd826809f\",\n        \"size\": 387119672\n    },\n    \"EnterActorFlow_Town12_Route11627_Weather8.tar.gz\": {\n        \"sha256\": \"4f9b211fdbc8fabae7d1650a0f74011aa74915f6d4b4504bef658c78506d9568\",\n        \"size\": 122655316\n    },\n    \"EnterActorFlow_Town12_Route11628_Weather9.tar.gz\": {\n        \"sha256\": \"15200c54c4829d2ed0e46435a9aefd7ccce392cd1d986d31720c626623026527\",\n        \"size\": 74168809\n    },\n    \"EnterActorFlow_Town12_Route11629_Weather10.tar.gz\": {\n        \"sha256\": \"bec0d589da5c794411922e4a286ab83a6758b9db9bb05646aa3a25d5dc7b5163\",\n        \"size\": 376896035\n    },\n    \"EnterActorFlow_Town12_Route11633_Weather14.tar.gz\": {\n        \"sha256\": \"4422f0cef9b3eb64e4e49816862df2337090aac11f345a6fc9580bf56ad87044\",\n        \"size\": 89322356\n    },\n    \"EnterActorFlow_Town12_Route11634_Weather15.tar.gz\": {\n        \"sha256\": \"5f45a306b0586452a27785ac51f8e84d769edc1277686ea7308eafb642b9ae90\",\n        \"size\": 81125655\n    },\n    \"EnterActorFlow_Town12_Route11639_Weather20.tar.gz\": {\n        \"sha256\": \"7f3e2f46cacdcfd040ed62d130dd0eb7b0063a140648e165f0ed2ab083f76dba\",\n        \"size\": 194746298\n    },\n    \"EnterActorFlow_Town12_Route11640_Weather21.tar.gz\": {\n        \"sha256\": \"85eeb5f9125991610e9de5e3e7561a6f2066bdf0cdcee6a45baa9e97bc85ab49\",\n        \"size\": 640160805\n    },\n    \"EnterActorFlow_Town12_Route11642_Weather23.tar.gz\": {\n        \"sha256\": \"0cdf46f0b4742371b8514a967ffc97c79285d420b7f6357b36bda7bbf0f41516\",\n        \"size\": 216002124\n    },\n    \"EnterActorFlow_Town12_Route11645_Weather0.tar.gz\": {\n        \"sha256\": \"4eecbb5614cf580febd7b06f1c2860d8ee6b3aec2e9c794c1f16e9e2411030f8\",\n        \"size\": 236044013\n    },\n    \"EnterActorFlow_Town12_Route11646_Weather1.tar.gz\": {\n        \"sha256\": \"464905777870019e9e52534d4cc17602ade5f926892e3dd78e7cf1f53f5c858c\",\n        \"size\": 132606226\n    },\n    \"EnterActorFlow_Town12_Route11648_Weather3.tar.gz\": {\n        \"sha256\": \"592afdf5d0fe2482b623a6c90b532778d912e606d153ca05f6ee99c751909598\",\n        \"size\": 548986491\n    },\n    \"EnterActorFlow_Town12_Route11650_Weather5.tar.gz\": {\n        \"sha256\": \"0dcbb43ea0088cbdce4ba0f2ac48f17bd397698945c7846b75fd96c0253941a4\",\n        \"size\": 353120827\n    },\n    \"EnterActorFlow_Town12_Route11651_Weather6.tar.gz\": {\n        \"sha256\": \"b6aa63bd96dc91008b6008651c610b918f21c85642cb20186e0ea083bd71f2a1\",\n        \"size\": 97769782\n    },\n    \"EnterActorFlow_Town12_Route11652_Weather7.tar.gz\": {\n        \"sha256\": \"61a96e6e2236736e05601e5821c7668a58e527b48845f1b5d30b02c214406d0a\",\n        \"size\": 397518383\n    },\n    \"EnterActorFlow_Town12_Route11657_Weather12.tar.gz\": {\n        \"sha256\": \"a8409535fa06e817368e3f33930861d5cd413ba87c825636f3babe2ecc1c3be3\",\n        \"size\": 237793118\n    },\n    \"EnterActorFlow_Town12_Route11659_Weather14.tar.gz\": {\n        \"sha256\": \"d1d7292767d810038282f5c770142a251838cecded46a4888d42a8ee1484f5d4\",\n        \"size\": 613618255\n    },\n    \"EnterActorFlow_Town12_Route11660_Weather15.tar.gz\": {\n        \"sha256\": \"06323eb8b8bb2ba4a48f70105208abddacb7d2e8ff38d6e4585855a8e48bfa63\",\n        \"size\": 286815745\n    },\n    \"EnterActorFlow_Town12_Route11661_Weather8.tar.gz\": {\n        \"sha256\": \"50a1f3df002f1f66aa506282d4faa3805deec323ea7ed6f7c6c9f5238af44d81\",\n        \"size\": 514350536\n    },\n    \"EnterActorFlow_Town12_Route11663_Weather18.tar.gz\": {\n        \"sha256\": \"29a9b5365633d3ea1a2e3f5edcb050f3be0bffccde77cbf1ba9a7e6a723f6b84\",\n        \"size\": 89589536\n    },\n    \"EnterActorFlow_Town12_Route11665_Weather20.tar.gz\": {\n        \"sha256\": \"d8717a235c0729a4089fe35719511b5d67d96186a345123b22f5bccc6b6f6455\",\n        \"size\": 158811531\n    },\n    \"EnterActorFlow_Town12_Route11666_Weather21.tar.gz\": {\n        \"sha256\": \"818f3121ce780845215b98c3aef495e2a92260a2bd832a6d6c20ba1fcdb562a3\",\n        \"size\": 182626448\n    },\n    \"EnterActorFlow_Town12_Route11667_Weather22.tar.gz\": {\n        \"sha256\": \"572ef0b0551ed21a03b731aacb37657edb2592563dd2b12ce460ce649ec4c182\",\n        \"size\": 1007803313\n    },\n    \"EnterActorFlow_Town12_Route11668_Weather23.tar.gz\": {\n        \"sha256\": \"4e878506e6284cc3d4ce2b0d1a7f235efa57ff5f946e5e5b6133ff26ede4b3a4\",\n        \"size\": 107202161\n    },\n    \"EnterActorFlow_Town12_Route11669_Weather23.tar.gz\": {\n        \"sha256\": \"d334e03ef52cb16fa9bc413761824ad72f78d99d8bfbea462f706d5a4412a1c6\",\n        \"size\": 498577087\n    },\n    \"EnterActorFlow_Town12_Route11670_Weather25.tar.gz\": {\n        \"sha256\": \"f5f1f1d34c91fb25698a7cded1b057bf132ae59bb4c559d284a9d148096caa5e\",\n        \"size\": 337878054\n    },\n    \"EnterActorFlow_Town12_Route11671_Weather0.tar.gz\": {\n        \"sha256\": \"b00cecb0412c8b0d611f70d0292ca14922f9249b667bb29fb42a0ce16a43f214\",\n        \"size\": 221448084\n    },\n    \"EnterActorFlow_Town12_Route11672_Weather1.tar.gz\": {\n        \"sha256\": \"625633673a58ad80e18c32fe27a8f20eb414844335aafc28bbbfc6bc1b363586\",\n        \"size\": 450893045\n    },\n    \"EnterActorFlow_Town12_Route11676_Weather5.tar.gz\": {\n        \"sha256\": \"ebf360672237b933b8c76ef2e412577c7b8aae0b0b829df7feb055c1f63644ea\",\n        \"size\": 116334734\n    },\n    \"EnterActorFlow_Town12_Route11677_Weather6.tar.gz\": {\n        \"sha256\": \"c3c56c370fcaab4937f7ce57f1b62371d6fbb8cdec296f9bc4c7efcd52c64019\",\n        \"size\": 572734850\n    },\n    \"EnterActorFlow_Town12_Route11679_Weather8.tar.gz\": {\n        \"sha256\": \"274e8242325f73e63d5e1566d1106fb323dee6434eca374f7b86e9735ee680e5\",\n        \"size\": 545778978\n    },\n    \"EnterActorFlow_Town12_Route11681_Weather10.tar.gz\": {\n        \"sha256\": \"9c6c97495e40cb08fe3ac96d84997dc0e64ae6a6298dfeb0b686757f35d46493\",\n        \"size\": 350889084\n    },\n    \"EnterActorFlow_Town12_Route11682_Weather11.tar.gz\": {\n        \"sha256\": \"91c2c13d45ceaec54ab3c5af44f0b010b289b2c503f0cb313b52931ffb189965\",\n        \"size\": 670605811\n    },\n    \"EnterActorFlow_Town12_Route11683_Weather12.tar.gz\": {\n        \"sha256\": \"74599abd46ca9f0b7b6fbeb755793532eba1ba02c25064a1e56f9f0c7caccde3\",\n        \"size\": 237301230\n    },\n    \"EnterActorFlow_Town12_Route11686_Weather15.tar.gz\": {\n        \"sha256\": \"b18df1e5576085e724f16e86aad520f47b0b357c9b3bb845c3b5f9de6a7c7194\",\n        \"size\": 109985206\n    },\n    \"EnterActorFlow_Town12_Route11687_Weather8.tar.gz\": {\n        \"sha256\": \"3ac473ca2e017ce077a6c851bb78c4c6e1c2dc6198145680e7373e12fcc18b9f\",\n        \"size\": 433533637\n    },\n    \"EnterActorFlow_Town12_Route11688_Weather9.tar.gz\": {\n        \"sha256\": \"e0902ee18d372c1100b613660b71acd1c61168171500b062b6acdd50f3588e70\",\n        \"size\": 77156176\n    },\n    \"EnterActorFlow_Town12_Route11696_Weather25.tar.gz\": {\n        \"sha256\": \"292cd6a1b5f518307bc79a6155f992789d71f57a7fdf6673403ba37bbf93186d\",\n        \"size\": 235650726\n    },\n    \"EnterActorFlow_Town12_Route11698_Weather1.tar.gz\": {\n        \"sha256\": \"659a8268963a634d9f6649fe4b85ee27cb649bcd3c2e692ffb02ecfd4d50e88c\",\n        \"size\": 178748892\n    },\n    \"EnterActorFlow_Town12_Route11700_Weather3.tar.gz\": {\n        \"sha256\": \"f570dcd663f3bb789e9944eb530982e2d0943beb23178e2b664c2c04e3ccb8f6\",\n        \"size\": 519531397\n    },\n    \"EnterActorFlow_Town12_Route11702_Weather5.tar.gz\": {\n        \"sha256\": \"99aa74697f2aab024d8584120782be25e2aaa61c7087e8ae94ff9024fa0934bc\",\n        \"size\": 462913126\n    },\n    \"EnterActorFlow_Town12_Route11704_Weather7.tar.gz\": {\n        \"sha256\": \"42ad20d4517d6efdd7766b9224a521939e9a2001f6af6dc6275f82ee2bd40ce7\",\n        \"size\": 430415274\n    },\n    \"EnterActorFlow_Town12_Route11705_Weather8.tar.gz\": {\n        \"sha256\": \"7df62ba22f5e5a7f5c15d9e55c643561aa0a89494e2165a7090e5853872a5ad2\",\n        \"size\": 489681905\n    },\n    \"EnterActorFlow_Town12_Route11706_Weather9.tar.gz\": {\n        \"sha256\": \"a90db032453b2a269c7ac969aa6713fc706d2724237a3ef8eebf25b52307be93\",\n        \"size\": 147235110\n    },\n    \"EnterActorFlow_Town12_Route11709_Weather12.tar.gz\": {\n        \"sha256\": \"de6ca9631060855390256426fed77030f0ac66e412753579ef60390c4aad280a\",\n        \"size\": 177955769\n    },\n    \"EnterActorFlow_Town12_Route11710_Weather13.tar.gz\": {\n        \"sha256\": \"f9c7c1dcb4425c296669356768b35b086b841a95d7512de5ab72cfeb3eba045c\",\n        \"size\": 495777435\n    },\n    \"EnterActorFlow_Town12_Route11711_Weather14.tar.gz\": {\n        \"sha256\": \"f2da2ef686588530962159aea170abef517184a21e79be8db44735bc1eb0290a\",\n        \"size\": 251244124\n    },\n    \"EnterActorFlow_Town12_Route11713_Weather8.tar.gz\": {\n        \"sha256\": \"1bd8dabf2c477ede5b9d0946138db7eb59a79448ac55a381f5322256dd2e34da\",\n        \"size\": 90415187\n    },\n    \"EnterActorFlow_Town12_Route11714_Weather9.tar.gz\": {\n        \"sha256\": \"d0eb163dc772603e8ca384ec5a06bd4b4934c3627d9cf061224ce1767b07ab1d\",\n        \"size\": 440650677\n    },\n    \"EnterActorFlow_Town12_Route11715_Weather18.tar.gz\": {\n        \"sha256\": \"8fa47d93b890a9b02ec97213ac16d6d6081ebd9292a751652812819f395c9bdc\",\n        \"size\": 986442426\n    },\n    \"EnterActorFlow_Town12_Route11716_Weather19.tar.gz\": {\n        \"sha256\": \"bd59c46b0622dda190e1775da2031c4440b9b3d08a7f4f9515298c72d25c2327\",\n        \"size\": 890795494\n    },\n    \"EnterActorFlow_Town12_Route11717_Weather20.tar.gz\": {\n        \"sha256\": \"879ecc7473010ee1c17d4108717f1515f7ca9fddf9b6a9f89a6eeb51e6a8f000\",\n        \"size\": 675996788\n    },\n    \"EnterActorFlow_Town12_Route11720_Weather23.tar.gz\": {\n        \"sha256\": \"d2b499c47cf1af3a09933b15a28904b769b6dbf4794b598a637d211dcc8aba0e\",\n        \"size\": 93520453\n    },\n    \"EnterActorFlow_Town12_Route11722_Weather25.tar.gz\": {\n        \"sha256\": \"fd1ae460810f893e827f1956059225003cc962a4ccdef02a1974fb6c5e317d6a\",\n        \"size\": 683810852\n    },\n    \"EnterActorFlow_Town12_Route11726_Weather3.tar.gz\": {\n        \"sha256\": \"834ade863a883f5601c801b7234cded1c7a5e3ffb41c1cbf329a6ae7178034ee\",\n        \"size\": 198854380\n    },\n    \"EnterActorFlow_Town12_Route11727_Weather3.tar.gz\": {\n        \"sha256\": \"29011c2ee509bd9748d75c83219d7ab7cf28abe6d5e0d54b63942c0df627d813\",\n        \"size\": 195486554\n    },\n    \"EnterActorFlow_Town12_Route11728_Weather5.tar.gz\": {\n        \"sha256\": \"3de83bf99b7beb2d53a51f19c68998df7184ba429f7f95ad84092075dfad1258\",\n        \"size\": 213476935\n    },\n    \"EnterActorFlow_Town12_Route11731_Weather8.tar.gz\": {\n        \"sha256\": \"ac4b288bbcf94a4380d2e899d0ee450ab65246585836af65dd1a8aa50e7a36f9\",\n        \"size\": 201068690\n    },\n    \"EnterActorFlow_Town12_Route11733_Weather10.tar.gz\": {\n        \"sha256\": \"0b042560011cc162a34ef73ceee04e175d181ac61d9413f412915e178623b31e\",\n        \"size\": 539931658\n    },\n    \"EnterActorFlow_Town12_Route11734_Weather11.tar.gz\": {\n        \"sha256\": \"9702be634927319d0295d4f739df5b998ba6e5009cfcc489d832493b9ed60e10\",\n        \"size\": 438619825\n    },\n    \"EnterActorFlow_Town12_Route11736_Weather13.tar.gz\": {\n        \"sha256\": \"120a9052727cacc00986a8690e30a074cfd38fcc224807e751caa11b6fc49f0e\",\n        \"size\": 289840258\n    },\n    \"EnterActorFlow_Town12_Route11737_Weather14.tar.gz\": {\n        \"sha256\": \"eed1603fcc60542507235827a40bd79fd2031b4f7941165db1f52eff5a036ecf\",\n        \"size\": 152726977\n    },\n    \"EnterActorFlow_Town12_Route11738_Weather15.tar.gz\": {\n        \"sha256\": \"1dfe4373edf5a44c79d53c4d071ff1260c977d5b0cbed0c3ed731bccfea38848\",\n        \"size\": 277045049\n    },\n    \"EnterActorFlow_Town12_Route11742_Weather19.tar.gz\": {\n        \"sha256\": \"fddd5d08d637e3b2ff4ae00da4328b01229ae5099875909b16dbb6b7574e3093\",\n        \"size\": 98724018\n    },\n    \"EnterActorFlow_Town12_Route11744_Weather21.tar.gz\": {\n        \"sha256\": \"55a2f396395099a6f69d6bd326be2af39157db932e096d0ba87aab67bfba2e73\",\n        \"size\": 203789172\n    },\n    \"EnterActorFlow_Town12_Route11745_Weather22.tar.gz\": {\n        \"sha256\": \"0d47e611e7ffcad1fe81534a8e97c31cf9698cf0aaf0a1b743b37e844c9e019f\",\n        \"size\": 109346228\n    },\n    \"EnterActorFlow_Town12_Route11748_Weather25.tar.gz\": {\n        \"sha256\": \"3c7a10750da21894bf7cc6c89a6fe08acda18e33b2c41843508c1e7c2ad0d7f8\",\n        \"size\": 375410970\n    },\n    \"EnterActorFlow_Town12_Route11749_Weather0.tar.gz\": {\n        \"sha256\": \"bf54a190ad95a6ef9cda8e846e98be2a2aae147877981956e3b0fdae6e64b61c\",\n        \"size\": 363114725\n    },\n    \"EnterActorFlow_Town12_Route11752_Weather3.tar.gz\": {\n        \"sha256\": \"f62cfadc5e49910ed8c1208ecd51a2041f54eee130922fa70b400a05c2e2c5a8\",\n        \"size\": 528503017\n    },\n    \"EnterActorFlow_Town12_Route11755_Weather6.tar.gz\": {\n        \"sha256\": \"5f7565b4c30c776a711b389e1b9a43e0fe9ee71322848c0cae5a7b8a18daaf22\",\n        \"size\": 225258692\n    },\n    \"EnterActorFlow_Town12_Route11756_Weather7.tar.gz\": {\n        \"sha256\": \"952b3ce5981b6a621b516988774b25653e108eb2f01c7031dd5c6e2ea887b99f\",\n        \"size\": 264911345\n    },\n    \"EnterActorFlow_Town12_Route11757_Weather8.tar.gz\": {\n        \"sha256\": \"43faae05ce7914e0ce9f5a72547b33d20fd45a92a52d7fa195696fbc7eeaf37e\",\n        \"size\": 509004903\n    },\n    \"EnterActorFlow_Town12_Route11758_Weather9.tar.gz\": {\n        \"sha256\": \"deb906592fa5951329f82a9e5b4d4570f1af27997a4e8120fc3d17241a6c740c\",\n        \"size\": 472815820\n    },\n    \"EnterActorFlow_Town12_Route11759_Weather10.tar.gz\": {\n        \"sha256\": \"5ebed0dc5fa7fb613d41d04bcb587daff3de8d9e32852092af69bf4e1f7c1aa2\",\n        \"size\": 110568848\n    },\n    \"EnterActorFlow_Town12_Route11760_Weather11.tar.gz\": {\n        \"sha256\": \"d9c9f01189b048654d9c5cefd7c88f50ab6301992c5e5821bba34da280475b4c\",\n        \"size\": 322110338\n    },\n    \"EnterActorFlow_Town12_Route11761_Weather12.tar.gz\": {\n        \"sha256\": \"0913fee20e5688afad76046a9047216fac15773bae8b2a378697c01d89b11477\",\n        \"size\": 310645215\n    },\n    \"EnterActorFlow_Town12_Route11763_Weather14.tar.gz\": {\n        \"sha256\": \"776a74d078478cc1b8713fc68e0034927bc55665cbf29ea2ce3ddc9fd0919e9b\",\n        \"size\": 156398696\n    },\n    \"EnterActorFlow_Town12_Route11764_Weather15.tar.gz\": {\n        \"sha256\": \"99b40a70a91ffe1fa65489e0b9ba51a205e4956d54bc3dcff4178bd590dae0b3\",\n        \"size\": 200097409\n    },\n    \"EnterActorFlow_Town12_Route11765_Weather8.tar.gz\": {\n        \"sha256\": \"75849c2113e16cf3a99de38031a83598130794e98faece0a9bc0a2b050d347f9\",\n        \"size\": 752777043\n    },\n    \"EnterActorFlow_Town12_Route11767_Weather18.tar.gz\": {\n        \"sha256\": \"6c62d49bedf60fabf1a969a5e977af8c1ddfbbae45e622dc537c4c38d7f953ef\",\n        \"size\": 377639771\n    },\n    \"EnterActorFlow_Town12_Route11768_Weather19.tar.gz\": {\n        \"sha256\": \"a4e447e955b46b197fe39e9356dedea37474f49973cb66a52f89d2888312dcd6\",\n        \"size\": 861668544\n    },\n    \"EnterActorFlow_Town12_Route11770_Weather21.tar.gz\": {\n        \"sha256\": \"97fdb3f9fbfbeded53736d241abb5d073eb3ae06f6ac9fdc5f0be71c55059914\",\n        \"size\": 447277691\n    },\n    \"EnterActorFlow_Town12_Route11772_Weather23.tar.gz\": {\n        \"sha256\": \"e4a2fc867ac84c0713aabbd29d18847b17e44ee4e9b3fb74113f9d5014e5867c\",\n        \"size\": 183514326\n    },\n    \"EnterActorFlow_Town12_Route11774_Weather25.tar.gz\": {\n        \"sha256\": \"924fd8540ac7da7d9263c571efc246f62fa487c19f51d5c6f12f42cbffc48109\",\n        \"size\": 139687627\n    },\n    \"EnterActorFlow_Town12_Route11777_Weather2.tar.gz\": {\n        \"sha256\": \"dba4b01775359c93814455064ea11852a6819ee35139232b217867f52d0718d9\",\n        \"size\": 387999893\n    },\n    \"EnterActorFlow_Town12_Route11778_Weather3.tar.gz\": {\n        \"sha256\": \"e9f3fd7a4f08c8fafbda68aeafcbc07ba9393473243df651a51b6620e2a34189\",\n        \"size\": 388770259\n    },\n    \"EnterActorFlow_Town12_Route11779_Weather3.tar.gz\": {\n        \"sha256\": \"ec58d90d3479eb012e3538fc45714696ebf16a26ee374e2dc38324db02bd94d7\",\n        \"size\": 155898624\n    },\n    \"EnterActorFlow_Town12_Route11780_Weather5.tar.gz\": {\n        \"sha256\": \"26486a6889638c85c6f4af6c993c75c7bb2ed4009ec1771de54240f47554dd99\",\n        \"size\": 178314438\n    },\n    \"EnterActorFlow_Town12_Route11781_Weather6.tar.gz\": {\n        \"sha256\": \"4dffbaac3e35c2cde124f4799ecde1c29d9437f184f1d877abd0a97d7108a195\",\n        \"size\": 387701928\n    },\n    \"EnterActorFlow_Town12_Route11783_Weather8.tar.gz\": {\n        \"sha256\": \"42a5cd0ec2621d7eb2b1b0328eb717d3fc5f17053a639b5e525227f0b28be848\",\n        \"size\": 191919591\n    },\n    \"EnterActorFlow_Town12_Route11784_Weather9.tar.gz\": {\n        \"sha256\": \"581109d6d1500d195dcbe7ba5fdcbe423610fd6ac16e8bf214ba15dc357f45a5\",\n        \"size\": 300052209\n    },\n    \"EnterActorFlow_Town12_Route11785_Weather10.tar.gz\": {\n        \"sha256\": \"73abb2d4cbf68c104defefd1eb6d76d0820ae0bb9301fbd6ee148a81bd60adf3\",\n        \"size\": 546963079\n    },\n    \"EnterActorFlow_Town12_Route11788_Weather13.tar.gz\": {\n        \"sha256\": \"2a22e17a43520b9acd16ab2bdd60fc75a1119dcd2b2838cfb13403c4c15ebfce\",\n        \"size\": 496098354\n    },\n    \"EnterActorFlow_Town12_Route11789_Weather14.tar.gz\": {\n        \"sha256\": \"e5377816fb28c744211fc9036b223361e03cff3a29b0cb3ac70faf6fd509b671\",\n        \"size\": 614082455\n    },\n    \"EnterActorFlow_Town12_Route11791_Weather8.tar.gz\": {\n        \"sha256\": \"6df1f9d3f69d39d10b0c8897af92656891849c93db473ca0e22428790f0e7991\",\n        \"size\": 211519023\n    },\n    \"EnterActorFlow_Town12_Route11793_Weather18.tar.gz\": {\n        \"sha256\": \"acdd5c8d79272058e14c110d991a51d763d7861e4add1db0c3373eab6dd7bdd1\",\n        \"size\": 237731646\n    },\n    \"EnterActorFlow_Town12_Route11794_Weather19.tar.gz\": {\n        \"sha256\": \"577d1b2d037af740b3855150f126374993a9b94d7096948cbd0b6db65e5caecc\",\n        \"size\": 576830027\n    },\n    \"EnterActorFlow_Town12_Route11796_Weather21.tar.gz\": {\n        \"sha256\": \"88b799503c7da5929ff2c02102b492826ac42dbd5b98c1d8f64f22b8735d0896\",\n        \"size\": 202080873\n    },\n    \"EnterActorFlow_Town12_Route11797_Weather22.tar.gz\": {\n        \"sha256\": \"b346205c5bb870ee507566beb87ed2bcf8b381994e77906c4e3d7e68ca467771\",\n        \"size\": 123241101\n    },\n    \"EnterActorFlow_Town12_Route11798_Weather23.tar.gz\": {\n        \"sha256\": \"f389c060b4f6957718e5b418daade97f29be293ef82fa0d0b4de428a5736f577\",\n        \"size\": 417855072\n    },\n    \"EnterActorFlow_Town12_Route11800_Weather25.tar.gz\": {\n        \"sha256\": \"81dfa2701e0f8077b225e0acdd4c0332fec3f135266a67bb82a73515ce7433be\",\n        \"size\": 473242736\n    },\n    \"EnterActorFlow_Town12_Route11801_Weather0.tar.gz\": {\n        \"sha256\": \"8385384aacbe2ddea1299774e7a7f13304e981134caa75d3a8732834ea0d1b1f\",\n        \"size\": 305302014\n    },\n    \"EnterActorFlow_Town12_Route11804_Weather3.tar.gz\": {\n        \"sha256\": \"147aa6bb338b4ba04206f3275882ed8e5fc1fabcae6ac4ee86e8f308c18b1766\",\n        \"size\": 271547118\n    },\n    \"EnterActorFlow_Town12_Route11806_Weather5.tar.gz\": {\n        \"sha256\": \"0546db3e9296d900295ddf9002178461f957d4c7e04002260a8c5854b1d0e0ae\",\n        \"size\": 337080876\n    },\n    \"EnterActorFlow_Town12_Route11807_Weather6.tar.gz\": {\n        \"sha256\": \"9fda4f9a27a11e2ed516ab1b8f98e713735ac354c847675c78ce26e5c89dea5c\",\n        \"size\": 273339983\n    },\n    \"EnterActorFlow_Town12_Route11808_Weather7.tar.gz\": {\n        \"sha256\": \"5828e7a90a0dd6511fe0f1a6b255223ca45d74690fc58cb009a22c1e023e9867\",\n        \"size\": 117862838\n    },\n    \"EnterActorFlow_Town12_Route11810_Weather9.tar.gz\": {\n        \"sha256\": \"ad436aacebbff5482d84c515d2480d5244ed33139a15c5d59306b2c470342b03\",\n        \"size\": 225537014\n    },\n    \"EnterActorFlow_Town12_Route11811_Weather10.tar.gz\": {\n        \"sha256\": \"78db91cf83e0721f89fe5b32e98048bc528ad0af571fdb2727eb95c6d5f0d059\",\n        \"size\": 401653960\n    },\n    \"EnterActorFlow_Town12_Route11812_Weather11.tar.gz\": {\n        \"sha256\": \"160a1876ea06573a76e722edd6d1d2c96193abce36ec454ef7f29b8d5e77ebcf\",\n        \"size\": 255272691\n    },\n    \"EnterActorFlow_Town12_Route11813_Weather12.tar.gz\": {\n        \"sha256\": \"cf81926c37d66cec69604a220d4b156b338083315a8e127b1ecc5278f5e739e0\",\n        \"size\": 91863350\n    },\n    \"EnterActorFlow_Town12_Route11815_Weather14.tar.gz\": {\n        \"sha256\": \"8141d9ea82a10f439f58f98c7013bfe7098ce392649eea2326cee8785d86bf6f\",\n        \"size\": 102345893\n    },\n    \"EnterActorFlow_Town12_Route11816_Weather15.tar.gz\": {\n        \"sha256\": \"0296fe333173847ad44e25e5ecf68ba6ad49972de8af6528ca89a9ccaca25d73\",\n        \"size\": 363255689\n    },\n    \"EnterActorFlow_Town12_Route11817_Weather8.tar.gz\": {\n        \"sha256\": \"e8b48d70673efb89f1ceb15301fcfc71afc7f39e0e72941398b316f971205396\",\n        \"size\": 321450871\n    },\n    \"EnterActorFlow_Town12_Route11818_Weather9.tar.gz\": {\n        \"sha256\": \"81c3bdab8486b077a9e9962de224d460669dfa14f4d912f0891bba815eb50175\",\n        \"size\": 303202171\n    },\n    \"EnterActorFlow_Town12_Route11819_Weather18.tar.gz\": {\n        \"sha256\": \"1e72f33fcba15a5faec5356c9d08888c5addce158c77e43180fa63cc0a79097b\",\n        \"size\": 129446457\n    },\n    \"EnterActorFlow_Town12_Route11820_Weather19.tar.gz\": {\n        \"sha256\": \"493a65bd520089503608855ceffba7cbac9635ad6f9e338e3a15f8f84f7770b9\",\n        \"size\": 92358075\n    },\n    \"EnterActorFlow_Town12_Route11821_Weather20.tar.gz\": {\n        \"sha256\": \"a136a2526a78eab4eb2e60bfa270f275d9456c3713ef2896456aac0e01cf9c34\",\n        \"size\": 107325825\n    },\n    \"EnterActorFlow_Town12_Route11824_Weather23.tar.gz\": {\n        \"sha256\": \"1d6e58eb24fc21ce77f2f911c1aa81b9b4629771d4f2a49e2a1bedcc3468818d\",\n        \"size\": 109920008\n    },\n    \"EnterActorFlow_Town12_Route11825_Weather23.tar.gz\": {\n        \"sha256\": \"f8c44f52f1f121f67fbaad6a354b3c5370b3b122273cf08ba9852f1d8b53781b\",\n        \"size\": 354744439\n    },\n    \"EnterActorFlow_Town12_Route11826_Weather25.tar.gz\": {\n        \"sha256\": \"078e5a74727d614e9e9c302ff716051ed414b902c7c3ab6fc8139a7041cc1826\",\n        \"size\": 172772698\n    },\n    \"EnterActorFlow_Town12_Route11827_Weather0.tar.gz\": {\n        \"sha256\": \"2ae474a0f4befce3876f9f7b02e93e5e14e9b8e22131a8c03a114b814c3689ec\",\n        \"size\": 122502942\n    },\n    \"EnterActorFlow_Town12_Route11828_Weather1.tar.gz\": {\n        \"sha256\": \"1780bb70d28cb0a42697fc027239769421c1b83d019b07eb483a388c163af481\",\n        \"size\": 405843937\n    },\n    \"EnterActorFlow_Town12_Route11829_Weather2.tar.gz\": {\n        \"sha256\": \"20fee3558c330020ee92315ff2370a7a6f1f024a1d1462198387ce45f3c2a2d2\",\n        \"size\": 107598460\n    },\n    \"EnterActorFlow_Town12_Route11831_Weather3.tar.gz\": {\n        \"sha256\": \"7efa08fe0a82f6f8b2a3366751cd4c4bbc654c2ff2eae21d7dffc84dd18a8e3c\",\n        \"size\": 503231767\n    },\n    \"EnterActorFlow_Town12_Route11832_Weather5.tar.gz\": {\n        \"sha256\": \"e3367b1cb107a4db70c5b1a0a9d43145c0af23ea8e4cf9adcaa6e335c986c9c0\",\n        \"size\": 189759435\n    },\n    \"EnterActorFlow_Town12_Route11837_Weather10.tar.gz\": {\n        \"sha256\": \"259330049c9834688cec7d37ebc550bac8a749fbb30ccd19d690f47c1ceb0e9a\",\n        \"size\": 432472193\n    },\n    \"EnterActorFlow_Town12_Route11838_Weather11.tar.gz\": {\n        \"sha256\": \"099af46d4539b68cbcbbece4c68f6fafd8658b108de57784ca413c32b364b923\",\n        \"size\": 84301093\n    },\n    \"EnterActorFlow_Town12_Route11840_Weather13.tar.gz\": {\n        \"sha256\": \"687f0b959a7471193d56b3631674d4b10f2dde645d600516e23019eb49c2116f\",\n        \"size\": 138014164\n    },\n    \"EnterActorFlow_Town12_Route11841_Weather14.tar.gz\": {\n        \"sha256\": \"46ca47c81ae744c19280c0545194eee90dfca0f52ceef0fddde43d97b19e0920\",\n        \"size\": 465910784\n    },\n    \"EnterActorFlow_Town12_Route11842_Weather15.tar.gz\": {\n        \"sha256\": \"11d758395edcdb8b7a9d2b1b0e6ec2e40c7dc927e6c096bee1951d4a76a651bc\",\n        \"size\": 374092398\n    },\n    \"EnterActorFlow_Town12_Route11843_Weather8.tar.gz\": {\n        \"sha256\": \"7268ebcffefdf472606c8bdbc014d75e056f7a5b6598b19849ac148b6d4c8273\",\n        \"size\": 113584614\n    },\n    \"EnterActorFlow_Town12_Route11844_Weather9.tar.gz\": {\n        \"sha256\": \"eaa417ecfc80aa88abd8971fee090331bdbc3279e824a9a3b606f919c95b910d\",\n        \"size\": 68071384\n    },\n    \"EnterActorFlow_Town12_Route11845_Weather18.tar.gz\": {\n        \"sha256\": \"0a8b2a8f382098ebf4ae60a97b04b75ad68297e02799a98ae7e5673acd50af57\",\n        \"size\": 227148382\n    },\n    \"EnterActorFlow_Town12_Route11846_Weather19.tar.gz\": {\n        \"sha256\": \"52b7e0557c6d0554006374d038c4384b412579fd26c03331e242cae3c1ff6638\",\n        \"size\": 159324573\n    },\n    \"EnterActorFlow_Town12_Route11853_Weather0.tar.gz\": {\n        \"sha256\": \"a48854f18cc68143d21094f928e827dc4964bd526955c2d7f0fc3458596478f4\",\n        \"size\": 226480605\n    },\n    \"EnterActorFlow_Town12_Route11854_Weather1.tar.gz\": {\n        \"sha256\": \"89bf91ef0dcae025c07c18cd181f9c11a72f9a45f182f0c67e6a67be21075526\",\n        \"size\": 215909633\n    },\n    \"EnterActorFlow_Town12_Route11855_Weather2.tar.gz\": {\n        \"sha256\": \"f6062dd7b830d838846bb3a5cc6112ca26ae314bc95c2acc9bb0c0c45900c654\",\n        \"size\": 277623567\n    },\n    \"EnterActorFlow_Town12_Route11857_Weather3.tar.gz\": {\n        \"sha256\": \"bb11d4ef7b5ded1e744b39cbe31295ca7b8b880c736af8e3e08a225bf852ac48\",\n        \"size\": 518483765\n    },\n    \"EnterActorFlow_Town12_Route11859_Weather6.tar.gz\": {\n        \"sha256\": \"7ec6b37ab02fbc8134a483f66db1d2b4831c004be3e6176f569263ebc769f165\",\n        \"size\": 624834059\n    },\n    \"EnterActorFlow_Town12_Route11860_Weather7.tar.gz\": {\n        \"sha256\": \"37556873305dc2b399e726e8afc803f6fcfc5e21a04a54444e38231d27d30cb7\",\n        \"size\": 258656645\n    },\n    \"EnterActorFlow_Town12_Route11861_Weather8.tar.gz\": {\n        \"sha256\": \"cae19b66c5b04e6e76cafd4f69e00e55176cf0299847e92a71fe4fed7168eced\",\n        \"size\": 413183060\n    },\n    \"EnterActorFlow_Town12_Route11862_Weather9.tar.gz\": {\n        \"sha256\": \"ad213fadca43eef29dcb83be1991f2cb6b19d7bc4ed83cab224152c6b99387b4\",\n        \"size\": 139326668\n    },\n    \"EnterActorFlow_Town12_Route11863_Weather10.tar.gz\": {\n        \"sha256\": \"16cb21751fdefce52c50895ac530347e533cacf71cd8a1ba5eae7f11eecc500c\",\n        \"size\": 555622531\n    },\n    \"EnterActorFlow_Town12_Route11864_Weather11.tar.gz\": {\n        \"sha256\": \"d88d45c1f5fc0ad5251fb1d0e4a807dc5ede2b6ff9c4fe6c8802743ce0fd600d\",\n        \"size\": 141484695\n    },\n    \"EnterActorFlow_Town12_Route11865_Weather12.tar.gz\": {\n        \"sha256\": \"61f84b79f072e4da84bcac2801190f00c7438018539b002c30ced09a7d7838ff\",\n        \"size\": 509917134\n    },\n    \"EnterActorFlow_Town12_Route11866_Weather13.tar.gz\": {\n        \"sha256\": \"3a2a45b1a2c69b26a4384b2c3f35619e367dc7e504a24069cf3aa83f065bb32f\",\n        \"size\": 166978148\n    },\n    \"EnterActorFlow_Town12_Route11867_Weather14.tar.gz\": {\n        \"sha256\": \"fa3f70248386355795a6887e0a93d2b25b135fdf957ffc2219c93f09d702eb03\",\n        \"size\": 433337725\n    },\n    \"EnterActorFlow_Town12_Route11870_Weather9.tar.gz\": {\n        \"sha256\": \"82a4b5e221252460980040559776c1cf41e2f0fc5f06c6c60dec77903336cc86\",\n        \"size\": 147683433\n    },\n    \"EnterActorFlow_Town12_Route11871_Weather18.tar.gz\": {\n        \"sha256\": \"df586e81056c5dd49d1d3d6a27601ca2839ade2bf07205a0b28cfd7a072ded50\",\n        \"size\": 220801676\n    },\n    \"EnterActorFlow_Town12_Route11872_Weather19.tar.gz\": {\n        \"sha256\": \"c86dd525165d395a5614c04f11f17caf6ee44361012166cf0ebac8345dca793e\",\n        \"size\": 224533130\n    },\n    \"EnterActorFlow_Town12_Route11873_Weather20.tar.gz\": {\n        \"sha256\": \"3f4e3a981a7a04a708bff2a6d10873d4e68da6f3c67c9f6b41d11c6e8de72f14\",\n        \"size\": 626949401\n    },\n    \"EnterActorFlow_Town12_Route11874_Weather21.tar.gz\": {\n        \"sha256\": \"14fe38565311e81cbeac96d17b01948bd1c7f86c4c2c41273dbb7a7dec1849ad\",\n        \"size\": 434358397\n    },\n    \"EnterActorFlow_Town12_Route11875_Weather22.tar.gz\": {\n        \"sha256\": \"acb258beefcf1b4a01319358cf6acc7b083238217fef79a5e5454d17356ce10b\",\n        \"size\": 319931315\n    },\n    \"EnterActorFlow_Town12_Route11877_Weather23.tar.gz\": {\n        \"sha256\": \"8a0326b0e50ba687c7cf9dcc8ecd63ca8959f42ea503f1f4cc5d0238fbaa2dec\",\n        \"size\": 414548304\n    },\n    \"EnterActorFlow_Town12_Route11880_Weather1.tar.gz\": {\n        \"sha256\": \"8f4221b13da7032cbefbfae28c23ce6fbc9f04249218ea41711ded1aafc3239c\",\n        \"size\": 457633332\n    },\n    \"EnterActorFlow_Town12_Route11881_Weather2.tar.gz\": {\n        \"sha256\": \"0e806d3750bf8a09aede5b73892547003b83d6e6cd8f8033596dcfb2fbd31ccd\",\n        \"size\": 427896696\n    },\n    \"EnterActorFlow_Town12_Route11884_Weather5.tar.gz\": {\n        \"sha256\": \"e0e69961d963952af0995fa8b315264480973495b5a40d0e559e1833019e1f38\",\n        \"size\": 403533689\n    },\n    \"EnterActorFlow_Town12_Route11888_Weather9.tar.gz\": {\n        \"sha256\": \"d3035f50c66fb257092f819f4875712389ce3b4946d66280374a67b24865ea84\",\n        \"size\": 240258752\n    },\n    \"EnterActorFlow_Town12_Route11890_Weather11.tar.gz\": {\n        \"sha256\": \"e8cb4034c1e32b3488d1b69fd76b47a01050968a24e6b2ca03becd1b45d60c12\",\n        \"size\": 256268344\n    },\n    \"EnterActorFlow_Town12_Route11894_Weather15.tar.gz\": {\n        \"sha256\": \"c5437e8248ad1882883aa0e14a586f6477ccd7ce0cf4f94d4bf898d09c1c0ae2\",\n        \"size\": 357047627\n    },\n    \"EnterActorFlow_Town12_Route11896_Weather9.tar.gz\": {\n        \"sha256\": \"a83885ffe6de00862d60a6077d96682290722e76e24e01efc63f6864e97d0026\",\n        \"size\": 284137964\n    },\n    \"EnterActorFlow_Town12_Route11897_Weather18.tar.gz\": {\n        \"sha256\": \"911b0eec4f6a3522a53f700817d65af947fbed614836921d2035b7227e139cd1\",\n        \"size\": 571639009\n    },\n    \"EnterActorFlow_Town12_Route11899_Weather20.tar.gz\": {\n        \"sha256\": \"3cd23945bda4d1082e3a0b431d6622f0958c7363d2c1ab0f512f113dd5f42bca\",\n        \"size\": 187628378\n    },\n    \"EnterActorFlow_Town12_Route11902_Weather23.tar.gz\": {\n        \"sha256\": \"d701b7acc380c3fc53d6e3a35f5525205a75109b3aa17ffb4695347ca8b6cec6\",\n        \"size\": 453977702\n    },\n    \"EnterActorFlow_Town12_Route11903_Weather23.tar.gz\": {\n        \"sha256\": \"9c713699d026570b7a4757e47e92c6921681edf91bc4cc28d59720d825004db3\",\n        \"size\": 349481496\n    },\n    \"EnterActorFlow_Town12_Route11904_Weather25.tar.gz\": {\n        \"sha256\": \"e0d1c03f00abea1013d6cb1dfd80da1fe031cfb976559ad8c747b830ced37ae9\",\n        \"size\": 156221389\n    },\n    \"EnterActorFlow_Town12_Route11906_Weather1.tar.gz\": {\n        \"sha256\": \"c90c4ce76af8988bb57035df99fbf48c0d0c3732f17f4dfb3c85ddd395f7d4c8\",\n        \"size\": 415971717\n    },\n    \"EnterActorFlow_Town12_Route11908_Weather3.tar.gz\": {\n        \"sha256\": \"bf13db5fca4d39e62bd441a68843777f5195b6752dbd8e70a44b2795c2c2a09b\",\n        \"size\": 110329437\n    },\n    \"EnterActorFlow_Town12_Route11912_Weather7.tar.gz\": {\n        \"sha256\": \"6237f9c2ac66f9fcbe8096d529f1fc84cceced7171c6b4e5a463075e47fa9d62\",\n        \"size\": 445242954\n    },\n    \"EnterActorFlow_Town12_Route11913_Weather8.tar.gz\": {\n        \"sha256\": \"e7f1ac61af63f4ac1e421c2e055b49f060a722c156e97463498720048449efa9\",\n        \"size\": 183586133\n    },\n    \"EnterActorFlow_Town12_Route11916_Weather11.tar.gz\": {\n        \"sha256\": \"4c8d8161f4aa086912edba288c5ea1314842dfc79c9ecb1d1f121f9395c07868\",\n        \"size\": 250748216\n    },\n    \"EnterActorFlow_Town12_Route11918_Weather13.tar.gz\": {\n        \"sha256\": \"76941e7f950e4d7f1b90a6a2a5f58cb840cf3d366dcee784bbc774c190279387\",\n        \"size\": 258460585\n    },\n    \"EnterActorFlow_Town12_Route11921_Weather8.tar.gz\": {\n        \"sha256\": \"102e1358f8edc9e9de48d72075053717401e59100f4d9356313c7b390da143f5\",\n        \"size\": 437983754\n    },\n    \"EnterActorFlow_Town12_Route11922_Weather9.tar.gz\": {\n        \"sha256\": \"031ea808a99494a810d41e1c39bc3d6a9357769a749faa39faebe80f764691c3\",\n        \"size\": 473684056\n    },\n    \"EnterActorFlow_Town12_Route11923_Weather18.tar.gz\": {\n        \"sha256\": \"83cb955c0bfae06d6774eb2aabfc730eea8ccbc60b21a6a24f27e15e60bf8608\",\n        \"size\": 186341644\n    },\n    \"EnterActorFlow_Town12_Route11924_Weather19.tar.gz\": {\n        \"sha256\": \"8673e0482307489807c6ec500351237de23c59fee28c0e5f5418bb1e1ed6e8ef\",\n        \"size\": 531954685\n    },\n    \"EnterActorFlow_Town12_Route11927_Weather22.tar.gz\": {\n        \"sha256\": \"2ab331c36ccd3ce5d33b0d61f475165cdfdab8b283ecdbca464a1d9031cf85f4\",\n        \"size\": 325020497\n    },\n    \"EnterActorFlow_Town12_Route11928_Weather23.tar.gz\": {\n        \"sha256\": \"2866f1fb006c0e2ea8366bb82c5c245b834a75dfcb6532b95b58c1c1f38d4bd0\",\n        \"size\": 154370638\n    },\n    \"EnterActorFlow_Town12_Route11932_Weather1.tar.gz\": {\n        \"sha256\": \"c3b99b520a306ad89fdd4785d25ca13d05d8d36a8282d4e535a4d822a0ea24b7\",\n        \"size\": 227371006\n    },\n    \"EnterActorFlow_Town12_Route11933_Weather2.tar.gz\": {\n        \"sha256\": \"33de302a3a2ab1d6fc4f69f209e6ef9dad20bab513887b5a8662913772acfc94\",\n        \"size\": 501853009\n    },\n    \"EnterActorFlow_Town12_Route11934_Weather3.tar.gz\": {\n        \"sha256\": \"dc747d569c0cad64dceace3e6d9f21a67ed5ad37de3500625855e8ee1dc27058\",\n        \"size\": 623777687\n    },\n    \"EnterActorFlow_Town12_Route11935_Weather3.tar.gz\": {\n        \"sha256\": \"fb346b63593969e744d9221312b44857669509b27a1562821336de20f3e3b37a\",\n        \"size\": 292068268\n    },\n    \"EnterActorFlow_Town12_Route11936_Weather5.tar.gz\": {\n        \"sha256\": \"38e1cf547e2608b8fc355f95071098b0b6bcdac887b48e8df5781d74681b9c87\",\n        \"size\": 258080852\n    },\n    \"EnterActorFlow_Town12_Route11937_Weather6.tar.gz\": {\n        \"sha256\": \"de186f353e5fdc86eccc482aff1d02388c30d8d0ca346e938db327f4060f0b8c\",\n        \"size\": 97385747\n    },\n    \"EnterActorFlow_Town12_Route11939_Weather8.tar.gz\": {\n        \"sha256\": \"c33ea5ac1b3efc4013f632131f196413f68c1480f919bcf5a5aa4bafdd2db2e9\",\n        \"size\": 87965534\n    },\n    \"EnterActorFlow_Town12_Route11940_Weather9.tar.gz\": {\n        \"sha256\": \"80852b26c61e1251310020bd4a63c471a82ddbe3faa5ae2dd9ae3e6cc7318762\",\n        \"size\": 435828841\n    },\n    \"EnterActorFlow_Town12_Route11941_Weather10.tar.gz\": {\n        \"sha256\": \"d906122f3b115852a47be64464960fad0a338e5e44997dfbe646504c5d55fa06\",\n        \"size\": 451641963\n    },\n    \"EnterActorFlow_Town12_Route11942_Weather11.tar.gz\": {\n        \"sha256\": \"1680cf3288c9f3eabdb561c1bfa60bf2479923bd1752f5f524163d42e2e4a65f\",\n        \"size\": 144831392\n    },\n    \"EnterActorFlow_Town12_Route11943_Weather12.tar.gz\": {\n        \"sha256\": \"2af203441e2939f9a60baabc594717e1a20fe68fa769b2d1e2680af222892ad5\",\n        \"size\": 79617942\n    },\n    \"EnterActorFlow_Town12_Route11945_Weather14.tar.gz\": {\n        \"sha256\": \"9d0f60c142e4aeec003c83e2f0fa6aff0465610cb8cde4b8e8a35de5f33be630\",\n        \"size\": 412638623\n    },\n    \"EnterActorFlow_Town12_Route11947_Weather8.tar.gz\": {\n        \"sha256\": \"93a61322a82e3fdb780cd3dd13591b9fdac0ddd541e5e64d5accbd38aaddbf41\",\n        \"size\": 456149581\n    },\n    \"EnterActorFlow_Town12_Route11949_Weather18.tar.gz\": {\n        \"sha256\": \"ee3f8acb1b9b6bd608a2797ac628c8d89a2497ca0235f13c7f206d1a00573161\",\n        \"size\": 87736166\n    },\n    \"EnterActorFlow_Town12_Route11950_Weather19.tar.gz\": {\n        \"sha256\": \"babf35d5ce49ec1ea52514fd87084188f2ead7f01de834dc4ab6cbc881ce9ba9\",\n        \"size\": 105946283\n    },\n    \"EnterActorFlow_Town12_Route11954_Weather23.tar.gz\": {\n        \"sha256\": \"36b56575df185dc0e8b38e323c1163d098fddcd6befb44ad2fcfbdd06455ac51\",\n        \"size\": 449848306\n    },\n    \"EnterActorFlow_Town12_Route11956_Weather25.tar.gz\": {\n        \"sha256\": \"6ded80fef2122d61865aac3dc375b60ef4f0bf7a4e0be052ecc3751ce08d8a33\",\n        \"size\": 346048622\n    },\n    \"EnterActorFlow_Town12_Route11957_Weather0.tar.gz\": {\n        \"sha256\": \"242e8d9ed0e04c72cbf0cff633c77e2511a929d79147afb8051df40276d6f14a\",\n        \"size\": 377514493\n    },\n    \"EnterActorFlow_Town12_Route11960_Weather3.tar.gz\": {\n        \"sha256\": \"0d74be58651418eb0ca582d2f0609c641c404686f1dc529ad04af8d834435b03\",\n        \"size\": 107453458\n    },\n    \"EnterActorFlow_Town12_Route11961_Weather3.tar.gz\": {\n        \"sha256\": \"eebc730d2728a8dc12315759c219048483386f468f398ef02c9236dd86158dce\",\n        \"size\": 544562596\n    },\n    \"EnterActorFlow_Town12_Route11963_Weather6.tar.gz\": {\n        \"sha256\": \"6e3ead171f0193836f3c28d2448c16d47c8cdfc12bd03fe7feb35d44343f1d2e\",\n        \"size\": 201616126\n    },\n    \"EnterActorFlow_Town12_Route11964_Weather7.tar.gz\": {\n        \"sha256\": \"554095b92989ac111e27971844088cf2e5ca518753acb2bbaee8b9bea822743f\",\n        \"size\": 477850328\n    },\n    \"EnterActorFlow_Town12_Route11965_Weather8.tar.gz\": {\n        \"sha256\": \"99766d5829a14e0510a5380f4d692e08556b7a25ea8d8cd6ebe46d9ff006417b\",\n        \"size\": 374771497\n    },\n    \"EnterActorFlow_Town12_Route11966_Weather9.tar.gz\": {\n        \"sha256\": \"ea70023fc956919f88a3018a0932137c7bb7cdaed037f065d612348b68eb8a89\",\n        \"size\": 193934399\n    },\n    \"EnterActorFlow_Town12_Route11967_Weather10.tar.gz\": {\n        \"sha256\": \"479568400be1413f0582d736c9f1c1063bf1632a932cbfff1fda16f6ed42c3b0\",\n        \"size\": 93431243\n    },\n    \"EnterActorFlow_Town12_Route11968_Weather11.tar.gz\": {\n        \"sha256\": \"290a46757b9217a23d4fd74a5f96fa472cd0cc955637793df04d2d35352bfbe8\",\n        \"size\": 82719251\n    },\n    \"EnterActorFlow_Town12_Route11971_Weather14.tar.gz\": {\n        \"sha256\": \"688ba034a7d45fe13b8d818efcc4fb5a9390ed4ed6027bcf8cad1fcada357475\",\n        \"size\": 203398991\n    },\n    \"EnterActorFlow_Town12_Route11972_Weather15.tar.gz\": {\n        \"sha256\": \"490198bf9dfb04da4e9ab7f0b030d6a3d6ac22a8edbbece0dc112cfd57a9b05f\",\n        \"size\": 110753672\n    },\n    \"EnterActorFlow_Town12_Route11973_Weather8.tar.gz\": {\n        \"sha256\": \"36276978c15447e4f0a82f98c7faec6d54fb808c6762689224b85ce33b4e7cd6\",\n        \"size\": 232133692\n    },\n    \"EnterActorFlow_Town12_Route11974_Weather9.tar.gz\": {\n        \"sha256\": \"21785384c4b35063c0c04daeb397d5b5385322db21967612b1cdf75a5b62f654\",\n        \"size\": 361788977\n    },\n    \"EnterActorFlow_Town12_Route11977_Weather20.tar.gz\": {\n        \"sha256\": \"84e055b65479453ea1f66299ab907c20ab8b35e5cc26f0950961c51eb0b0c224\",\n        \"size\": 104230998\n    },\n    \"EnterActorFlow_Town12_Route11981_Weather23.tar.gz\": {\n        \"sha256\": \"98c3b2793873b0577fc41efafa63d346c962c55deaac6228ee515147a389cd92\",\n        \"size\": 137427494\n    },\n    \"EnterActorFlow_Town12_Route11982_Weather25.tar.gz\": {\n        \"sha256\": \"ad745cfa309f6e9608bea4ca156d656657e7a131b91259ff4fd65b2c3e09066e\",\n        \"size\": 94131980\n    },\n    \"EnterActorFlow_Town12_Route11984_Weather1.tar.gz\": {\n        \"sha256\": \"49c139f1571fb5e61abe324d74cc0cb33412efb4080cfaa4be0ee4a2627a2b88\",\n        \"size\": 491740926\n    },\n    \"EnterActorFlow_Town12_Route11986_Weather3.tar.gz\": {\n        \"sha256\": \"7dcfd68fab2c54fabbe6f2b973508de2385236fa2fdd70ddd279892f6e02ecb8\",\n        \"size\": 623135054\n    },\n    \"EnterActorFlow_Town12_Route11987_Weather3.tar.gz\": {\n        \"sha256\": \"4d95f90c72ab014cde6e819b32a762b37b5f3eb062cbf18f93fc1c466fcd210f\",\n        \"size\": 300609808\n    },\n    \"EnterActorFlow_Town12_Route11988_Weather5.tar.gz\": {\n        \"sha256\": \"2dd75054cd2971a9eb18dab9b333083b030070e5740f4eafa28df7e3c8c7fba1\",\n        \"size\": 248845616\n    },\n    \"EnterActorFlow_Town12_Route11989_Weather6.tar.gz\": {\n        \"sha256\": \"713e601405ba7648b81d09e9bb7d9f02f4b301a1e14b1b8e374b9f07cb6b3ab6\",\n        \"size\": 447277193\n    },\n    \"EnterActorFlow_Town12_Route11990_Weather7.tar.gz\": {\n        \"sha256\": \"0921e514d010af4d136e6d993ee4dd4f2522fca587b4ffa87fead93224e37fee\",\n        \"size\": 88343924\n    },\n    \"EnterActorFlow_Town12_Route11993_Weather10.tar.gz\": {\n        \"sha256\": \"3d7c23b5b945863b123f7c70aabbd4cfcab0382c068f0af8c09cc6aac56149a9\",\n        \"size\": 465589011\n    },\n    \"EnterActorFlow_Town12_Route11998_Weather15.tar.gz\": {\n        \"sha256\": \"fbd79fa4248343380ac9f72df06cd6c1d1104db412c42d618f8663b92b043253\",\n        \"size\": 98541580\n    },\n    \"EnterActorFlow_Town12_Route11999_Weather8.tar.gz\": {\n        \"sha256\": \"5053dca2377d982229d93e9780116876b63c9e3be8564bfc88130e39ac97780e\",\n        \"size\": 95571809\n    },\n    \"EnterActorFlow_Town12_Route12000_Weather9.tar.gz\": {\n        \"sha256\": \"6759cc101b927ceeae0a80aa2bf1a11930524f2bac734558837576bbbb232cd2\",\n        \"size\": 146724466\n    },\n    \"EnterActorFlow_Town12_Route12001_Weather18.tar.gz\": {\n        \"sha256\": \"0b7dfad6862d0089235d310d50a7ec9e41d6e47002d9211fdcb24d51db80baa8\",\n        \"size\": 430227297\n    },\n    \"EnterActorFlow_Town12_Route12004_Weather21.tar.gz\": {\n        \"sha256\": \"32289c152125cd80c75d417b1f6a02e92beacf0c51f534cd418e933955cf9bdd\",\n        \"size\": 575950793\n    },\n    \"EnterActorFlow_Town12_Route12010_Weather1.tar.gz\": {\n        \"sha256\": \"454173494131528342834702f2e32465865eed250875cdd200283ab3f3122a3d\",\n        \"size\": 273762804\n    },\n    \"EnterActorFlow_Town12_Route12014_Weather5.tar.gz\": {\n        \"sha256\": \"d9816baecfd98106318a783683769d8fdc01e34ba7fda0f33837b0697e91ed7a\",\n        \"size\": 106955014\n    },\n    \"EnterActorFlow_Town12_Route12017_Weather8.tar.gz\": {\n        \"sha256\": \"ff6d0449c77a373818412db350c7d91e8e82a9b817266b38d94654d2b1a79882\",\n        \"size\": 441535413\n    },\n    \"EnterActorFlow_Town12_Route12020_Weather11.tar.gz\": {\n        \"sha256\": \"46b43a71d1af7dfe9383779123554a8b5d1e28eb7f8996591b33c137ff871fcf\",\n        \"size\": 176958879\n    },\n    \"EnterActorFlow_Town12_Route12022_Weather13.tar.gz\": {\n        \"sha256\": \"0f8f20cbfa0ed53285bfff6ef08d5ecabc5a08d7287c2d6833988e13e00b98f2\",\n        \"size\": 83922326\n    },\n    \"EnterActorFlow_Town12_Route12024_Weather15.tar.gz\": {\n        \"sha256\": \"eab1335c22579f1495f821465551844f107ac8b36456c2f8144b7efbd7c072e9\",\n        \"size\": 421136778\n    },\n    \"EnterActorFlow_Town12_Route12026_Weather9.tar.gz\": {\n        \"sha256\": \"b85c86dd2e41d4469ba67ffce0e4479443a6665c4269d436af0a75b7881dd112\",\n        \"size\": 263222096\n    },\n    \"EnterActorFlow_Town12_Route12027_Weather18.tar.gz\": {\n        \"sha256\": \"71d2cb79bcd890f3dbf0d3855f8fe6800cb362c6b967df0c5a94911f122dcca7\",\n        \"size\": 635822709\n    },\n    \"EnterActorFlow_Town12_Route12030_Weather21.tar.gz\": {\n        \"sha256\": \"0bbb1fd40dda147d0fb5fa9e94593204ff8d622276aa8c39bc0e400b8cfab0c7\",\n        \"size\": 398548381\n    },\n    \"EnterActorFlow_Town12_Route12031_Weather22.tar.gz\": {\n        \"sha256\": \"8b5bb7443c2154c4827a931f1968a4b584b06167c42f115657a53df8d3e679f2\",\n        \"size\": 208005122\n    },\n    \"EnterActorFlow_Town12_Route12032_Weather23.tar.gz\": {\n        \"sha256\": \"b45303877fa9c2b006f671f6ff5cca115a6b368aae62b3aadcc22670f283df71\",\n        \"size\": 397564813\n    },\n    \"EnterActorFlow_Town12_Route12033_Weather23.tar.gz\": {\n        \"sha256\": \"6eecf972cbd357f8117fc8e80d0af3368f3f457894440ee585e76e33065729f1\",\n        \"size\": 761385867\n    },\n    \"EnterActorFlow_Town12_Route12035_Weather0.tar.gz\": {\n        \"sha256\": \"3a6683b7d9e30a6cbcbefab8a11068dd7ff9f11778b16bb3c686d1f79e9687b7\",\n        \"size\": 308467094\n    },\n    \"EnterActorFlow_Town12_Route12036_Weather1.tar.gz\": {\n        \"sha256\": \"cf0bfbc9c1eb2434d993945b95857286d795d8112cd2c8bc63f4d9b7fcd04260\",\n        \"size\": 380206670\n    },\n    \"EnterActorFlow_Town12_Route12038_Weather3.tar.gz\": {\n        \"sha256\": \"cc052e3593d4ff305b4869d4bb59d0c1e3e63ec28df5c25b7d1d74585cbe3279\",\n        \"size\": 439095059\n    },\n    \"EnterActorFlow_Town12_Route12041_Weather6.tar.gz\": {\n        \"sha256\": \"d9522df7a82a3b11d5be5616a24a65f36ab0f4ccfd1571e505a5e9acf7069c39\",\n        \"size\": 184603751\n    },\n    \"EnterActorFlow_Town12_Route12043_Weather8.tar.gz\": {\n        \"sha256\": \"a9bbbd28535921b8b54cdcd386320c1f95dbfc4f5559e9743020debbda834e5a\",\n        \"size\": 100933477\n    },\n    \"EnterActorFlow_Town12_Route12044_Weather9.tar.gz\": {\n        \"sha256\": \"b2c06cf9600778db28d95f2d6262bce2b07ccad03f83061aa7a9015cd7e12192\",\n        \"size\": 65743235\n    },\n    \"EnterActorFlow_Town12_Route12050_Weather15.tar.gz\": {\n        \"sha256\": \"d72bafc671d81a1a08014fd03497c7b8cf2a156b90013fa54596230a72a11469\",\n        \"size\": 178048156\n    },\n    \"EnterActorFlow_Town12_Route12052_Weather9.tar.gz\": {\n        \"sha256\": \"af0f85eecc4d102f1ebdb53cf81d3b4b7710bac22c73f8b6ad40d16ec809245d\",\n        \"size\": 191361723\n    },\n    \"EnterActorFlow_Town12_Route12053_Weather18.tar.gz\": {\n        \"sha256\": \"c4e854dcc4aa24399de5a0c822e882226f543970401563dbd0a183cc34a3daa7\",\n        \"size\": 525471432\n    },\n    \"EnterActorFlow_Town12_Route12054_Weather19.tar.gz\": {\n        \"sha256\": \"0300b90b727c78eb8c32fc1fb982106bf1527a5871d51600c9c9ac0f9652968f\",\n        \"size\": 395312346\n    },\n    \"EnterActorFlow_Town12_Route12060_Weather25.tar.gz\": {\n        \"sha256\": \"ed5062a1883dd99356e8769a2f55286435c813dc465c55afda8779b665043690\",\n        \"size\": 71753547\n    },\n    \"EnterActorFlow_Town12_Route12062_Weather1.tar.gz\": {\n        \"sha256\": \"5bc152a332fa81e08b5a3a218ea7b87b5246392c132fe25ce10a4c9508110438\",\n        \"size\": 98089944\n    },\n    \"EnterActorFlow_Town12_Route12065_Weather3.tar.gz\": {\n        \"sha256\": \"8e42b8965a5a245f19a7d38e0cbee05148a5e2768fbb5b6d16b5693471618083\",\n        \"size\": 85597886\n    },\n    \"EnterActorFlow_Town12_Route12066_Weather5.tar.gz\": {\n        \"sha256\": \"27f35abf3b7958c0395002cab9130ee7fe680ca69baffcc8f1f5b426ea1691b8\",\n        \"size\": 296162732\n    },\n    \"EnterActorFlow_Town12_Route12068_Weather7.tar.gz\": {\n        \"sha256\": \"77db17e5be9d5b4eef09fd9662e8abe9aca8bb394efa09a71bb187d8ebbf7ee6\",\n        \"size\": 454914722\n    },\n    \"EnterActorFlow_Town12_Route12071_Weather10.tar.gz\": {\n        \"sha256\": \"b4d96dd3b4d30b8ebf197191dc89c886859a5c4592b1bb1a9e865e08161f57ed\",\n        \"size\": 101182505\n    },\n    \"EnterActorFlow_Town12_Route12072_Weather11.tar.gz\": {\n        \"sha256\": \"53ca82bcf89a050724c4597c6e42a119ca15c05c4c1d2529a29cdb54906c939b\",\n        \"size\": 154884164\n    },\n    \"EnterActorFlow_Town12_Route12074_Weather13.tar.gz\": {\n        \"sha256\": \"82fd5d66d1eea7ca2b69eb75a941e0d65fde095d14e47e3672bd336a97fe8dc6\",\n        \"size\": 160110825\n    },\n    \"EnterActorFlow_Town12_Route12075_Weather14.tar.gz\": {\n        \"sha256\": \"c59bd5b6c30730caecb899aa0694d460d1f909aecc228e0193e58ec147cd14a0\",\n        \"size\": 306601647\n    },\n    \"EnterActorFlow_Town12_Route12079_Weather18.tar.gz\": {\n        \"sha256\": \"74f1ed621a5af55944e87f034ffb29bdaded0559932e70327f990d205127a47c\",\n        \"size\": 517639160\n    },\n    \"EnterActorFlow_Town12_Route12081_Weather20.tar.gz\": {\n        \"sha256\": \"e63185c3f137a233bbf929c1d9bb10e85d9a97b0e693b8f082d33bdd9bb3e4f8\",\n        \"size\": 95699112\n    },\n    \"EnterActorFlow_Town12_Route12083_Weather22.tar.gz\": {\n        \"sha256\": \"a4fb9c9b7c85dadb7663fcb4655ac3d55e21f7cf3e38034175453dfd5bd0b42c\",\n        \"size\": 469375007\n    },\n    \"EnterActorFlow_Town12_Route12085_Weather23.tar.gz\": {\n        \"sha256\": \"7aba7736ef9b1e697ffe059b24aada8727a6a08d1c88f73a423a541c34973517\",\n        \"size\": 240258064\n    },\n    \"EnterActorFlow_Town12_Route12087_Weather0.tar.gz\": {\n        \"sha256\": \"c5823bf73e5bee89c93a328b39c85500983a8fcb0955bfc4cd5f9128cb65629a\",\n        \"size\": 542274197\n    },\n    \"EnterActorFlow_Town12_Route12088_Weather1.tar.gz\": {\n        \"sha256\": \"c9ceab386da61764c7bef455036078d2578ca9b05ada21e661dbdabaa964e628\",\n        \"size\": 570734659\n    },\n    \"EnterActorFlow_Town12_Route12089_Weather2.tar.gz\": {\n        \"sha256\": \"c4029c337cb97627c2ba55a04784d25826720014c54663d28258a83d9aa5d85d\",\n        \"size\": 328291428\n    },\n    \"EnterActorFlow_Town12_Route12095_Weather8.tar.gz\": {\n        \"sha256\": \"06b1f045d43d6828ef45703984b2b75c632313b9b5334f36a289f12a02ee66b3\",\n        \"size\": 278695538\n    },\n    \"EnterActorFlow_Town12_Route12096_Weather9.tar.gz\": {\n        \"sha256\": \"76bfaf0e24d61a13a1674b6fb16b306f739d57a2aa447b83322dbf1880241004\",\n        \"size\": 226981646\n    },\n    \"EnterActorFlow_Town12_Route12097_Weather10.tar.gz\": {\n        \"sha256\": \"259dd21238310008444bb5fd90ebb1eace289c925ed3a79b0fa4f0659a122a03\",\n        \"size\": 301847889\n    },\n    \"EnterActorFlow_Town12_Route12099_Weather12.tar.gz\": {\n        \"sha256\": \"37355b03f7b715b12df91dd826ecc0a58fa873f7ee40e3259bae138168f27198\",\n        \"size\": 298115035\n    },\n    \"EnterActorFlow_Town12_Route12100_Weather13.tar.gz\": {\n        \"sha256\": \"8aff3915e1b8b5ff2e9b8da98666d31112a180edbaae5d8ae5b953937e0b33ff\",\n        \"size\": 143088199\n    },\n    \"EnterActorFlow_Town12_Route12101_Weather14.tar.gz\": {\n        \"sha256\": \"d3f0a14355415f827fa4753dc346c396d8340aabbedd189a17c4e5c6bfb43725\",\n        \"size\": 175813198\n    },\n    \"EnterActorFlow_Town12_Route12102_Weather15.tar.gz\": {\n        \"sha256\": \"af607e33f26c22d798885f9b034730398d8e918d9b5be9557c6080127d2e4ac2\",\n        \"size\": 198027233\n    },\n    \"EnterActorFlow_Town12_Route12105_Weather18.tar.gz\": {\n        \"sha256\": \"27dede68c6ed4cd952e88466935cfac4afe4c456229e4c0ffde5d733ce2bd60e\",\n        \"size\": 197872770\n    },\n    \"EnterActorFlow_Town12_Route12108_Weather21.tar.gz\": {\n        \"sha256\": \"89785a11df74f1abdb348c01167938a26269d2ca4f118f94063f0671a2cb7d9b\",\n        \"size\": 286114967\n    },\n    \"EnterActorFlow_Town12_Route12109_Weather22.tar.gz\": {\n        \"sha256\": \"6e6dcc21fb86fa0afa82e56f5520d188732754481e63520855336a0d0515e089\",\n        \"size\": 458186807\n    },\n    \"EnterActorFlow_Town12_Route12110_Weather23.tar.gz\": {\n        \"sha256\": \"97e2599b8dbdbb873f8cd5e0ea8b058fa2a1afb2c2b43812e23378eab53dfd17\",\n        \"size\": 570197312\n    },\n    \"EnterActorFlow_Town12_Route12111_Weather23.tar.gz\": {\n        \"sha256\": \"188608a592902e689b9665535ae6b5ee2c42f62018a6cc137fcb61676d5bde14\",\n        \"size\": 191032948\n    },\n    \"EnterActorFlow_Town12_Route12113_Weather0.tar.gz\": {\n        \"sha256\": \"967e09a37f313c6947e5f03b1c596c43f97c528c1dad0ef2eb67ca71a29ac69a\",\n        \"size\": 358379213\n    },\n    \"EnterActorFlow_Town12_Route12115_Weather2.tar.gz\": {\n        \"sha256\": \"c1d85e88a0e2e8565e0c3b88af40263e9751bc7103dc97bdcfa9c9d5dae7a8e3\",\n        \"size\": 96195612\n    },\n    \"EnterActorFlow_Town12_Route12116_Weather3.tar.gz\": {\n        \"sha256\": \"ce76dc569ceb9abd45c98e14bcf9f96d29718b53ada21ac549e4f67c08a50526\",\n        \"size\": 92201799\n    },\n    \"EnterActorFlow_Town12_Route12117_Weather3.tar.gz\": {\n        \"sha256\": \"b8c1257e6ba0b866f69f0638b4223a39cde4d674fd62bf9d6d8a0ce2769bf597\",\n        \"size\": 233805739\n    },\n    \"EnterActorFlow_Town12_Route12118_Weather5.tar.gz\": {\n        \"sha256\": \"2ebe40b9b28836f7d083392b14855265044ba338e3385a0ac271af865e9becea\",\n        \"size\": 492872806\n    },\n    \"EnterActorFlow_Town12_Route12119_Weather6.tar.gz\": {\n        \"sha256\": \"246a0057b32a2026a69e4f9dd0828203cb1cd81dbfbe391d5212a08150df0695\",\n        \"size\": 87739178\n    },\n    \"EnterActorFlow_Town12_Route12120_Weather7.tar.gz\": {\n        \"sha256\": \"36e844a2738d876357e80f5ef4d0a5af744816b5bd70f219dd88534eee20c976\",\n        \"size\": 202837302\n    },\n    \"EnterActorFlow_Town12_Route12124_Weather11.tar.gz\": {\n        \"sha256\": \"f91245a1f2231bf8aab50006b9a08ddb1ca20aa15d3a77310d6595faefd296f9\",\n        \"size\": 503697818\n    },\n    \"EnterActorFlow_Town12_Route12125_Weather12.tar.gz\": {\n        \"sha256\": \"2c64b5b762cfe4cfb021a2ae19407e84c3c071b35d8deb1c3338c648ff146e81\",\n        \"size\": 608458286\n    },\n    \"EnterActorFlow_Town12_Route12128_Weather15.tar.gz\": {\n        \"sha256\": \"c328c51a3742585cb3890d8eaac945530d1caff7f7178798ef2eabeca20e5363\",\n        \"size\": 386356987\n    },\n    \"EnterActorFlow_Town12_Route12129_Weather8.tar.gz\": {\n        \"sha256\": \"424c73e2787c86bbc12a4e2e4f78c913c41b854ba21b7b2b5e4469a9d180f0f7\",\n        \"size\": 110342690\n    },\n    \"EnterActorFlow_Town12_Route12130_Weather9.tar.gz\": {\n        \"sha256\": \"6a798f421b1697c8eaca104f31afcc80ee267cfe831cc05af1da48fac62bad6a\",\n        \"size\": 372757343\n    },\n    \"EnterActorFlow_Town12_Route12131_Weather18.tar.gz\": {\n        \"sha256\": \"484aac77631df7b492aa81578357de94b7c7cb60332de70555ac7d52a52f6ed9\",\n        \"size\": 526637690\n    },\n    \"EnterActorFlow_Town12_Route12133_Weather20.tar.gz\": {\n        \"sha256\": \"b6d0d5eec9d36616c97e47990b94a879d06d2c1d04691bc2341e921911b255be\",\n        \"size\": 641617741\n    },\n    \"EnterActorFlow_Town12_Route12136_Weather23.tar.gz\": {\n        \"sha256\": \"6d7a09aca2ff2704452f8456be10069834f15ad6df5fc6bfe8e2be23411d0c62\",\n        \"size\": 80086329\n    },\n    \"EnterActorFlow_Town12_Route12139_Weather0.tar.gz\": {\n        \"sha256\": \"1a7267c5b2c272451fdf020fee6589de8d8f3fc323a0abd58ad675db1603ac72\",\n        \"size\": 400219534\n    },\n    \"EnterActorFlow_Town12_Route12140_Weather1.tar.gz\": {\n        \"sha256\": \"4d3a43c557dc4ed28beda2da9cb59c8e85a5e5140ab48d0279a6d3c994842a63\",\n        \"size\": 92924473\n    },\n    \"EnterActorFlow_Town12_Route12141_Weather2.tar.gz\": {\n        \"sha256\": \"3f0c80cd6e783665a2292429124b6da260780fce65d4c9e5d3c0226c09b95fa3\",\n        \"size\": 442412901\n    },\n    \"EnterActorFlow_Town12_Route12143_Weather3.tar.gz\": {\n        \"sha256\": \"cfe8276618279259f046f716303de843b9fdc382e1940321d8be189899b54068\",\n        \"size\": 426743491\n    },\n    \"EnterActorFlow_Town12_Route12146_Weather7.tar.gz\": {\n        \"sha256\": \"92c216b020979b4f3778600d3be04e3cb1d73ee7968a4191de6e4b76a0b5910a\",\n        \"size\": 283778190\n    },\n    \"EnterActorFlow_Town12_Route12147_Weather8.tar.gz\": {\n        \"sha256\": \"f772ad6669253b6796ad8f692faa6cf9aec39bd90d3e2689c0571d81e554c094\",\n        \"size\": 182860415\n    },\n    \"EnterActorFlow_Town12_Route12148_Weather9.tar.gz\": {\n        \"sha256\": \"5ce93ada8f6be742f28faffc53ade38918e93df85628ffe6fd791191716ff3c9\",\n        \"size\": 298258217\n    },\n    \"EnterActorFlow_Town12_Route12149_Weather10.tar.gz\": {\n        \"sha256\": \"e6c433bc9aaf260e7f2f1d91e5e289d90adf49c6f5a579ba882e382f26323d6f\",\n        \"size\": 520533638\n    },\n    \"EnterActorFlow_Town12_Route12150_Weather11.tar.gz\": {\n        \"sha256\": \"8f9d505fa9a33c3cdc3873da65406a3a3ae1cb3a42c9abf403bd5ccc9ddb9c2b\",\n        \"size\": 452108008\n    },\n    \"EnterActorFlow_Town12_Route12155_Weather8.tar.gz\": {\n        \"sha256\": \"9ae0adbbfe313b9532bcde3c53a0eb7ba5838229454dc7373623b8b3532c300c\",\n        \"size\": 466150411\n    },\n    \"EnterActorFlow_Town12_Route12157_Weather18.tar.gz\": {\n        \"sha256\": \"a6d884142c8a6d4d2eebfce67c86950f72175504ffa2600e2213e6364a937412\",\n        \"size\": 200602095\n    },\n    \"EnterActorFlow_Town12_Route12158_Weather19.tar.gz\": {\n        \"sha256\": \"c89bf32a44f0781ffd4e96a20ba099ee1712380cbcc97b589a526373557cf74d\",\n        \"size\": 536483875\n    },\n    \"EnterActorFlow_Town12_Route12159_Weather20.tar.gz\": {\n        \"sha256\": \"ddbcd9d34bfcf325abd2c9fb2add6394ea3822ac58265151b8eef4eb69e979f6\",\n        \"size\": 106419306\n    },\n    \"EnterActorFlow_Town12_Route12162_Weather23.tar.gz\": {\n        \"sha256\": \"80785cb1efe053c9ff72b1c38256736b98c9885fabaa354ce7f164fa17d6b403\",\n        \"size\": 273560387\n    },\n    \"EnterActorFlow_Town12_Route12163_Weather23.tar.gz\": {\n        \"sha256\": \"3c239d8c51dd337b253693d967616181e2f482a6b2285aaa41e2588785f48a4b\",\n        \"size\": 78111843\n    },\n    \"EnterActorFlow_Town12_Route12164_Weather25.tar.gz\": {\n        \"sha256\": \"294eed04f030c040eb63490eba790b9db8bc9b8acebbd7ff30894d259e77e2f2\",\n        \"size\": 342118227\n    },\n    \"EnterActorFlow_Town12_Route12165_Weather0.tar.gz\": {\n        \"sha256\": \"fbe534e3032d63e5804e90b0a6d6a9607e7236b2a01d08fec5c86266841ec70b\",\n        \"size\": 354869245\n    },\n    \"EnterActorFlow_Town12_Route12166_Weather1.tar.gz\": {\n        \"sha256\": \"d0ab91fac8e14dfc21263164b9b6529d3dd03df898f6a918bed43116dd6bf950\",\n        \"size\": 87727191\n    },\n    \"EnterActorFlow_Town12_Route12167_Weather2.tar.gz\": {\n        \"sha256\": \"03df01bb6fa01de73f028845b712b8bfaadc266c0c43d4051bbe7de4b585cb2b\",\n        \"size\": 243260421\n    },\n    \"EnterActorFlow_Town12_Route12168_Weather3.tar.gz\": {\n        \"sha256\": \"5b00f87da5fbd8dfe6f999dbe3d60bad5099d3684e8bff055e9d30feba9895d5\",\n        \"size\": 177868283\n    },\n    \"EnterActorFlow_Town12_Route12169_Weather3.tar.gz\": {\n        \"sha256\": \"0ced18a35c8de7d408b64d71b160a1f933bd0efd029202e1dc195754d16587a8\",\n        \"size\": 221093897\n    },\n    \"EnterActorFlow_Town12_Route12171_Weather6.tar.gz\": {\n        \"sha256\": \"cf96a3ca792816bb8a2eb80db6875208e345ace42e3461b307d091c66dc104d3\",\n        \"size\": 116903220\n    },\n    \"EnterActorFlow_Town12_Route12175_Weather10.tar.gz\": {\n        \"sha256\": \"a26708b274afe9cd6a873371957ba85d7f5d392deed1242e323031aa3353f99b\",\n        \"size\": 573871362\n    },\n    \"EnterActorFlow_Town12_Route12177_Weather12.tar.gz\": {\n        \"sha256\": \"fde0aac1073ae7568b3b082364b17136fd5028fe317c33e43ae722f49f7977e5\",\n        \"size\": 269799512\n    },\n    \"EnterActorFlow_Town12_Route12178_Weather13.tar.gz\": {\n        \"sha256\": \"aab1b7874c1d93968d27c09631171dffff49e7c7fd1f8260c3fbf39d0a9565e2\",\n        \"size\": 71806596\n    },\n    \"EnterActorFlow_Town12_Route12179_Weather14.tar.gz\": {\n        \"sha256\": \"ae8aa7b77ecfaf1281bc2d9b951c0b97ed94872c0184154dba63df27ebdc969e\",\n        \"size\": 446457287\n    },\n    \"EnterActorFlow_Town12_Route12180_Weather15.tar.gz\": {\n        \"sha256\": \"e9f968a8bbebf059a525e68973d3568b76b46162b3826da784ea390cbe2c058b\",\n        \"size\": 78602467\n    },\n    \"EnterActorFlow_Town12_Route12181_Weather8.tar.gz\": {\n        \"sha256\": \"0fb8ee291467e7142f4f62035548fd0147bbeef07cef96d0c4ed5ff02ec0f70c\",\n        \"size\": 607327972\n    },\n    \"EnterActorFlow_Town12_Route12184_Weather19.tar.gz\": {\n        \"sha256\": \"2c49b87accf3345de539adde8f2a480bd164950b60e1edf0a8991c8c15734122\",\n        \"size\": 379741111\n    },\n    \"EnterActorFlow_Town12_Route12185_Weather20.tar.gz\": {\n        \"sha256\": \"95bdba11fbdc53f9eb0ed5b6b1e6812199b800a2b22dd67d1a6f9364a1e3945b\",\n        \"size\": 170332719\n    },\n    \"EnterActorFlow_Town12_Route12187_Weather22.tar.gz\": {\n        \"sha256\": \"f9265f87b8b7847c34a476cf5e547d9a4180c48a5d2152f4b705edc5dc52e346\",\n        \"size\": 224151486\n    },\n    \"EnterActorFlow_Town12_Route12189_Weather23.tar.gz\": {\n        \"sha256\": \"459818c29ceb470e6041cae58036513ff2c5eb9d5724b8a99fac2f5410a2df3d\",\n        \"size\": 308973250\n    },\n    \"EnterActorFlow_Town12_Route12191_Weather0.tar.gz\": {\n        \"sha256\": \"f08e5bb7605e7155f9b45b077a4045abff2a72f9436605a48f198bc0f734664f\",\n        \"size\": 619417026\n    },\n    \"EnterActorFlow_Town12_Route12193_Weather2.tar.gz\": {\n        \"sha256\": \"9aef298dd27b836032f6c02991d3b33addb81e0ad1542a04dd18bfadb5de26eb\",\n        \"size\": 205655630\n    },\n    \"EnterActorFlow_Town12_Route12194_Weather3.tar.gz\": {\n        \"sha256\": \"35f05b17043df5db93356ee9d405734c5bf23a06cf78a26119803c8bc1e568f1\",\n        \"size\": 353937203\n    },\n    \"EnterActorFlow_Town12_Route12198_Weather7.tar.gz\": {\n        \"sha256\": \"c034164b324991cba127611e3f6da7d53669a25476d8b06bfaadc082c2e22264\",\n        \"size\": 246528320\n    },\n    \"EnterActorFlow_Town12_Route12205_Weather14.tar.gz\": {\n        \"sha256\": \"570d7d661d730d2f435984e3e26af00e6693a6925815c608f84a9e642397b895\",\n        \"size\": 485608515\n    },\n    \"EnterActorFlow_Town12_Route12206_Weather15.tar.gz\": {\n        \"sha256\": \"17a85b3b4b9ced4bc8f0079f019f6d79b11c84f3990d4fdfb3857cc03bb41d49\",\n        \"size\": 95343569\n    },\n    \"EnterActorFlow_Town12_Route12209_Weather18.tar.gz\": {\n        \"sha256\": \"961389593d6068e927967394b97a1d30c6c16011bde6beee238ec2ab2bc719e3\",\n        \"size\": 504044670\n    },\n    \"EnterActorFlow_Town12_Route12210_Weather19.tar.gz\": {\n        \"sha256\": \"2aca95d525866e2d1b39259c88e18db8b05cb168c6ed198b39794ea7fc2d5225\",\n        \"size\": 178484369\n    },\n    \"EnterActorFlow_Town12_Route12211_Weather20.tar.gz\": {\n        \"sha256\": \"5cc8c3510e8260046c19a104ba0a58816c7215ce1c076d8fa4b47cee9dd48690\",\n        \"size\": 91826418\n    },\n    \"EnterActorFlow_Town12_Route12212_Weather21.tar.gz\": {\n        \"sha256\": \"049ee450e949fc805c4ee46a5610922625eda1d00af583bc821df14fb9bb1f45\",\n        \"size\": 215963442\n    },\n    \"EnterActorFlow_Town12_Route12213_Weather22.tar.gz\": {\n        \"sha256\": \"c9593f043285ba74414844f6d222bb6476ca6f2931ba5ebcdb31c5bdfe73fa4f\",\n        \"size\": 704076676\n    },\n    \"EnterActorFlow_Town12_Route12214_Weather23.tar.gz\": {\n        \"sha256\": \"e49de71b5828e6671fa00a8d9f6baad211bdf46a4916c9a0520ff41e1d2376fc\",\n        \"size\": 298972124\n    },\n    \"EnterActorFlow_Town12_Route12219_Weather2.tar.gz\": {\n        \"sha256\": \"b17069a23682de8b127c6a7c5e768442eaf1e165438fb140ef6e5a17431364dc\",\n        \"size\": 499720407\n    },\n    \"EnterActorFlow_Town12_Route12220_Weather3.tar.gz\": {\n        \"sha256\": \"8611fb6dc85603f5221923a3036ebdcfe52780751d89f531d35a7af55d83969a\",\n        \"size\": 237019639\n    },\n    \"EnterActorFlow_Town12_Route12221_Weather3.tar.gz\": {\n        \"sha256\": \"7d65145beff93377acc386e6df608680cee32ce35ca6d5ad35a3ba855575771c\",\n        \"size\": 236962113\n    },\n    \"EnterActorFlow_Town12_Route12222_Weather5.tar.gz\": {\n        \"sha256\": \"aaeb39805d07d34972c2a5ab6d3e79a1b4880533088941a07e4176ab20831d28\",\n        \"size\": 101058600\n    },\n    \"EnterActorFlow_Town12_Route12224_Weather7.tar.gz\": {\n        \"sha256\": \"d03cf8cdbe4c6792b06da43397dac859142fb12d941826808b1ad392172ba793\",\n        \"size\": 447110873\n    },\n    \"EnterActorFlow_Town12_Route12225_Weather8.tar.gz\": {\n        \"sha256\": \"5e4539ea0b5b0d06d233ef95127bfcd21df72217dd58bababbccdd47456501b7\",\n        \"size\": 308333960\n    },\n    \"EnterActorFlow_Town12_Route12227_Weather10.tar.gz\": {\n        \"sha256\": \"c36b419ddd426e62b2f738b47605ea95a1df4f7b125c80164b16db8623f0877b\",\n        \"size\": 136223494\n    },\n    \"EnterActorFlow_Town12_Route12228_Weather11.tar.gz\": {\n        \"sha256\": \"bdae070f7f7e85949b4779dff4c42b77c4a066c75d1a60da0da032b9c4700bc3\",\n        \"size\": 125449271\n    },\n    \"EnterActorFlow_Town12_Route12231_Weather14.tar.gz\": {\n        \"sha256\": \"554a2795300c5a208a3544faba211305c14fae0e4be5bc5544b4397c0f7ebdd0\",\n        \"size\": 87405792\n    },\n    \"EnterActorFlow_Town12_Route12232_Weather15.tar.gz\": {\n        \"sha256\": \"8c1f4cc43ec0b1ee7a72a1d913de44d149d854f394a34a2bacaf9f18e5f41409\",\n        \"size\": 1224398109\n    },\n    \"EnterActorFlow_Town12_Route12233_Weather8.tar.gz\": {\n        \"sha256\": \"4dfb8c7256253e4a51ce19b3f14dd40067c60ef218f7554e0b50860b4c8a09c6\",\n        \"size\": 294134477\n    },\n    \"EnterActorFlow_Town12_Route12235_Weather18.tar.gz\": {\n        \"sha256\": \"99b431e8c20147632fcbb4c02304e5484adbb587e160c7cfe8d888002b02fd02\",\n        \"size\": 105124182\n    },\n    \"EnterActorFlow_Town12_Route12236_Weather19.tar.gz\": {\n        \"sha256\": \"ec54649a4abb3e24443ee2c0b1fe1c2409e4b9ea263a86ddd9eb54ba6bd3ead6\",\n        \"size\": 168849487\n    },\n    \"EnterActorFlow_Town12_Route12238_Weather21.tar.gz\": {\n        \"sha256\": \"0f4b8e76c4867e1531e9c44725c5e05dcfdcab9c93093718a3f0adaffd6fd36c\",\n        \"size\": 530972321\n    },\n    \"EnterActorFlow_Town12_Route12240_Weather23.tar.gz\": {\n        \"sha256\": \"c015de7253ad5ea1d9811510f82f0c10f986a79207b046b059dcf3e43d0ce9d9\",\n        \"size\": 423897702\n    },\n    \"EnterActorFlow_Town12_Route12243_Weather0.tar.gz\": {\n        \"sha256\": \"ac8669b662fe3c8b21a0ec91ff04d1b665709485b5d5fe74519b0d1983f8796b\",\n        \"size\": 248389002\n    },\n    \"EnterActorFlow_Town12_Route12244_Weather1.tar.gz\": {\n        \"sha256\": \"ce97120e0eac87fc09831d270e3ea84383d0411b5adfc49b90edbcf880213a9c\",\n        \"size\": 340267956\n    },\n    \"EnterActorFlow_Town12_Route12247_Weather3.tar.gz\": {\n        \"sha256\": \"bed7e1c957fcdb97cee9e0f89175a613146c0425c517382ad8f98cd1ead08032\",\n        \"size\": 98402062\n    },\n    \"EnterActorFlow_Town12_Route12249_Weather6.tar.gz\": {\n        \"sha256\": \"7b0f5d987397cb34eed527deb24bc94df3adc33d58830e0bdbed7531088cfc64\",\n        \"size\": 238330005\n    },\n    \"EnterActorFlow_Town12_Route12250_Weather7.tar.gz\": {\n        \"sha256\": \"e73e8e60ed13c6dd2352dd8633733a6e9937097a84bbcb9244279b4562f16b30\",\n        \"size\": 121807655\n    },\n    \"EnterActorFlow_Town12_Route12252_Weather9.tar.gz\": {\n        \"sha256\": \"e67b41f996588bd3a3195f5ce187475ed3fb02d0c34e1967eaf0d6c532cbe760\",\n        \"size\": 191633161\n    },\n    \"EnterActorFlow_Town12_Route12253_Weather10.tar.gz\": {\n        \"sha256\": \"a143e7a4f1d098103104f3b81f75a5bb28ee871a39b22328b19cffc96d733ca3\",\n        \"size\": 88791322\n    },\n    \"EnterActorFlow_Town12_Route12254_Weather11.tar.gz\": {\n        \"sha256\": \"fac2dbbc4e3e97b78a418584aaace0562b91a14003bc697bf08467f4957a841c\",\n        \"size\": 80550119\n    },\n    \"EnterActorFlow_Town12_Route12256_Weather13.tar.gz\": {\n        \"sha256\": \"2782b7da87e7b5d2aeade8ea50005a9b63aace2f1752c9c3a354327509bd5b3e\",\n        \"size\": 97940423\n    },\n    \"EnterActorFlow_Town12_Route12257_Weather14.tar.gz\": {\n        \"sha256\": \"5bc04922e9bf4fa15f67993330c726b2430f51cb84ae5f5979fbc13ef0197fb2\",\n        \"size\": 433111720\n    },\n    \"EnterActorFlow_Town12_Route12258_Weather15.tar.gz\": {\n        \"sha256\": \"4dfb1eb4e7a7e61efdafb329f5db12a3ee3584911bd4e413aa440bf3d11adec2\",\n        \"size\": 191616824\n    },\n    \"EnterActorFlow_Town12_Route12259_Weather8.tar.gz\": {\n        \"sha256\": \"28f68dc7d98cadd5a820e69a8157767a9f3cb37d773b8328c069edc4b0706b20\",\n        \"size\": 169743917\n    },\n    \"EnterActorFlow_Town12_Route12260_Weather9.tar.gz\": {\n        \"sha256\": \"5e27aaeb8bf28d9399e637a46a11c20561a9e8e111f434910e23cce2fb163717\",\n        \"size\": 263557045\n    },\n    \"EnterActorFlow_Town12_Route12262_Weather19.tar.gz\": {\n        \"sha256\": \"c8e0795de49b83e8fb613caa735d9316dc2c166e6328186bd50fc3fae3f7f111\",\n        \"size\": 232114111\n    },\n    \"EnterActorFlow_Town12_Route12265_Weather22.tar.gz\": {\n        \"sha256\": \"1010f9eb7e5c546388d36d9807192ae8e5cde064c08c9f08dbb9a7515e4e3ea9\",\n        \"size\": 93808145\n    },\n    \"EnterActorFlow_Town12_Route12267_Weather23.tar.gz\": {\n        \"sha256\": \"356c88ab7e075641b622be215b9db0a14f4fc964bab365f5c02b1f9804b73cc4\",\n        \"size\": 345207334\n    },\n    \"EnterActorFlow_Town12_Route12269_Weather0.tar.gz\": {\n        \"sha256\": \"d88af8dea5146221a34a07f9d2d033fcdb0375ea543d7504dc672123a48d3f26\",\n        \"size\": 197439485\n    },\n    \"EnterActorFlow_Town12_Route12272_Weather3.tar.gz\": {\n        \"sha256\": \"960cd3095301d76c85739df3d4d3299da9761dea6bf55c34485c7b4d3c1d87d1\",\n        \"size\": 466074415\n    },\n    \"EnterActorFlow_Town12_Route12274_Weather5.tar.gz\": {\n        \"sha256\": \"19c30d7d3a743c991471809fc4368dd4b77f185680b8875d6e153131720649ad\",\n        \"size\": 110236118\n    },\n    \"EnterActorFlow_Town12_Route12276_Weather7.tar.gz\": {\n        \"sha256\": \"cb203c411a1f14e3932a1ac998620139188d674cb698d61d082a47521ea340d8\",\n        \"size\": 1070650127\n    },\n    \"EnterActorFlow_Town12_Route12279_Weather10.tar.gz\": {\n        \"sha256\": \"400d48640e3719e0b688e39432738c1a4db3772464dc8186854b054f4f3e468e\",\n        \"size\": 487396348\n    },\n    \"EnterActorFlow_Town12_Route12280_Weather11.tar.gz\": {\n        \"sha256\": \"7f56c737c40e2d8df18b6868fd412b9a02a900ba376ad5963d27cb82669f58ab\",\n        \"size\": 180355699\n    },\n    \"EnterActorFlow_Town12_Route12283_Weather14.tar.gz\": {\n        \"sha256\": \"a5d6c31a855870e1e7fdc1ad8f4524f79cb6600c45ee545ad299fea1af2825a7\",\n        \"size\": 467932274\n    },\n    \"EnterActorFlow_Town12_Route12285_Weather8.tar.gz\": {\n        \"sha256\": \"8f5701624e46ec80da4f96a1f67b654b39cb6a4eea2398b82f65f5d5d69da954\",\n        \"size\": 194102127\n    },\n    \"EnterActorFlow_Town12_Route12286_Weather9.tar.gz\": {\n        \"sha256\": \"a678fe6961877309213b5defdd4bd8025b570492017d02b978633ea053e1b9c3\",\n        \"size\": 107314169\n    },\n    \"EnterActorFlow_Town12_Route12287_Weather18.tar.gz\": {\n        \"sha256\": \"2c4f6bb4254c1fd0d660aeb9ed27a8de16eb20e89e5ab1f2e0bffe0729bb652f\",\n        \"size\": 174764937\n    },\n    \"EnterActorFlow_Town12_Route12292_Weather23.tar.gz\": {\n        \"sha256\": \"93e933ef9edc515345c380a754f1315e62ca684c7911fac593876fd6d65e3d07\",\n        \"size\": 84386560\n    },\n    \"EnterActorFlow_Town12_Route12296_Weather1.tar.gz\": {\n        \"sha256\": \"130faf6c8e0d60a8ad3cd4a315335b65d60d297c3c308ff522db6e4a1bf394d4\",\n        \"size\": 264798337\n    },\n    \"EnterActorFlow_Town12_Route12297_Weather2.tar.gz\": {\n        \"sha256\": \"444607f64a417eab3eb3dca5bc79ec30806d82e726544663a7bf01ecf2ab8ca4\",\n        \"size\": 101775548\n    },\n    \"EnterActorFlow_Town12_Route12299_Weather3.tar.gz\": {\n        \"sha256\": \"b222883e50be7daa4f7810bb1855e9c871b36e36f15dc7a48628968509e67173\",\n        \"size\": 408640090\n    },\n    \"EnterActorFlow_Town12_Route12300_Weather5.tar.gz\": {\n        \"sha256\": \"575ee4f398b0f34e412ed84b77f497f3a22d5892ee12a786972a68d6bf5b018f\",\n        \"size\": 548397428\n    },\n    \"EnterActorFlow_Town12_Route12301_Weather6.tar.gz\": {\n        \"sha256\": \"568ea79e16659895516da12311a8a0deef8f5931a6d876dc50ead5eaacc4c45e\",\n        \"size\": 505137903\n    },\n    \"EnterActorFlow_Town12_Route12302_Weather7.tar.gz\": {\n        \"sha256\": \"54f08f7c744a20fcf67182c61411fbd855ed1570177692c76f37d2da70576aba\",\n        \"size\": 112739553\n    },\n    \"EnterActorFlow_Town12_Route12306_Weather11.tar.gz\": {\n        \"sha256\": \"624f93b17b670b16390964c63fcfd7da22a9519de39ddbbf717f586d33ab94a8\",\n        \"size\": 177689448\n    },\n    \"EnterActorFlow_Town12_Route12307_Weather12.tar.gz\": {\n        \"sha256\": \"078f936422c9f430eb46a0a8dae5a39fd56abe46fbeece28e3ebebd30e54945f\",\n        \"size\": 162399600\n    },\n    \"EnterActorFlow_Town12_Route12308_Weather13.tar.gz\": {\n        \"sha256\": \"88abe8cf3a970cd900ba65c4f1964d8ca4adcd8e141870fe63bfbd15b6143b6f\",\n        \"size\": 350233657\n    },\n    \"EnterActorFlow_Town12_Route12309_Weather14.tar.gz\": {\n        \"sha256\": \"1a8b6531c80be83680d0e75f05fe253927aec43531efb9b7eb41a385a4edc888\",\n        \"size\": 458870766\n    },\n    \"EnterActorFlow_Town12_Route12313_Weather18.tar.gz\": {\n        \"sha256\": \"d59f9729f00501bfbdafb2f700f8500cec66b1d420b56c88b3fa5ebe068e7cb3\",\n        \"size\": 81378870\n    },\n    \"EnterActorFlow_Town12_Route12314_Weather19.tar.gz\": {\n        \"sha256\": \"f112b0de608c552b3f70689228d8b05ac2ef7b58137ed4129fbbfabbd01d00de\",\n        \"size\": 647718949\n    },\n    \"EnterActorFlow_Town12_Route12315_Weather20.tar.gz\": {\n        \"sha256\": \"4b1b2d4d9c4f4ace886880588130c5c083889aa9414e0652170a3e03dde4d673\",\n        \"size\": 214186538\n    },\n    \"EnterActorFlow_Town12_Route12317_Weather22.tar.gz\": {\n        \"sha256\": \"cacc43d7dff48b10a514034448bbc04657b18398c40686e842bd570e0754c335\",\n        \"size\": 194387844\n    },\n    \"EnterActorFlow_Town12_Route12321_Weather0.tar.gz\": {\n        \"sha256\": \"985b23be47b9c1e3ce3bf230713871be7c2f5f2a1fcdfe448d510c59c9f43db8\",\n        \"size\": 85411334\n    },\n    \"EnterActorFlow_Town12_Route12322_Weather1.tar.gz\": {\n        \"sha256\": \"e516b28293dd2c7db3947c79b6171519f181400a8202b74ae58e545015fbca01\",\n        \"size\": 428352879\n    },\n    \"EnterActorFlow_Town12_Route12323_Weather2.tar.gz\": {\n        \"sha256\": \"e9a8734ea63bac4f1af9b9def64a27132562b7fa2fa255812af3aaa4a5128ec8\",\n        \"size\": 593339994\n    },\n    \"EnterActorFlow_Town12_Route12324_Weather3.tar.gz\": {\n        \"sha256\": \"f978f31166e2389d53a054fb3c67bb12d8367d319f16d1f46de94045b33b4c95\",\n        \"size\": 330484176\n    },\n    \"EnterActorFlow_Town12_Route12327_Weather6.tar.gz\": {\n        \"sha256\": \"328d641056d5638206b6e69f92798054c9f6d2d82fa9048c708e08bf359ed34e\",\n        \"size\": 570191291\n    },\n    \"EnterActorFlow_Town12_Route12328_Weather7.tar.gz\": {\n        \"sha256\": \"b10a1e676acad5f708cd3c3f6ad3e8bb27bf2ebf08378e6efd339cb0dd6fedaf\",\n        \"size\": 463460221\n    },\n    \"EnterActorFlow_Town12_Route12335_Weather14.tar.gz\": {\n        \"sha256\": \"23be6032d4652bb641abb49bd0c9c0f2b507486852f2b1faee21d89ad97be787\",\n        \"size\": 151968833\n    },\n    \"EnterActorFlow_Town12_Route12336_Weather15.tar.gz\": {\n        \"sha256\": \"696e7578e774c10eb4f752fe88abc5f80043ddaedfc10f609d73e72c0c861883\",\n        \"size\": 370111759\n    },\n    \"EnterActorFlow_Town12_Route12338_Weather9.tar.gz\": {\n        \"sha256\": \"06d6308e5bff2fdbf5e62fa6d73651fddb4d5cc33b7fdefd7eba79413a79446f\",\n        \"size\": 1138558576\n    },\n    \"EnterActorFlow_Town12_Route12339_Weather18.tar.gz\": {\n        \"sha256\": \"98e28846306aa76d8c5403ed2ca503efebd58459baf07aad45438fe079ddbee1\",\n        \"size\": 530623872\n    },\n    \"EnterActorFlow_Town12_Route12341_Weather20.tar.gz\": {\n        \"sha256\": \"2151fce51155981ab83812e65d6f930aae92749873d42e04677f64ceaf06c857\",\n        \"size\": 109830992\n    },\n    \"EnterActorFlow_Town12_Route12342_Weather21.tar.gz\": {\n        \"sha256\": \"3995aa0ebe5874f04969d7783fb698da62f352632478df13a2e7b4218da75adf\",\n        \"size\": 237933712\n    },\n    \"EnterActorFlow_Town12_Route12344_Weather23.tar.gz\": {\n        \"sha256\": \"c3d68fb7b9570bad03f981fed7b64c9a6403b57a1f7aa5d9b50b2e022cdc5fab\",\n        \"size\": 1176554287\n    },\n    \"EnterActorFlow_Town12_Route12345_Weather23.tar.gz\": {\n        \"sha256\": \"4de7573c6be75b0fd07b8ef85d6990f58cecd2167a4b295f55393f76460687c2\",\n        \"size\": 357165223\n    },\n    \"EnterActorFlow_Town12_Route12347_Weather0.tar.gz\": {\n        \"sha256\": \"a1d81bde2b806290492859e088453234c4b8f3c7578173d45440a55844165afa\",\n        \"size\": 208576768\n    },\n    \"EnterActorFlow_Town12_Route12348_Weather1.tar.gz\": {\n        \"sha256\": \"df63213938340f79bd335bbc27ab45a4ecd75be4b96c2c178ed164e871244690\",\n        \"size\": 589444648\n    },\n    \"EnterActorFlow_Town12_Route12351_Weather3.tar.gz\": {\n        \"sha256\": \"2bae1ba27a57766a3d84919d22a3596af25ca3cbe30784e783d5d87e7bd9c717\",\n        \"size\": 408205401\n    },\n    \"EnterActorFlow_Town12_Route12352_Weather5.tar.gz\": {\n        \"sha256\": \"618affb0e1b1316e9d115348a95e6e0e3a8446085573e116b32a0a47fbaa98ed\",\n        \"size\": 291858183\n    },\n    \"EnterActorFlow_Town12_Route12356_Weather9.tar.gz\": {\n        \"sha256\": \"5d5f568a555606bd6fa1f62916947e13d91601eeb73f63bbfbe6be7009e208cd\",\n        \"size\": 147948519\n    },\n    \"EnterActorFlow_Town12_Route12359_Weather12.tar.gz\": {\n        \"sha256\": \"bead9c1f446e54410d1cff0cfffd5f9a1a5f45c0cfd6d058f3decd65931608b0\",\n        \"size\": 88630975\n    },\n    \"EnterActorFlow_Town12_Route12360_Weather13.tar.gz\": {\n        \"sha256\": \"879a7666256d608834d2b96c6de08189023929e3145786fe73b0c9bd71f54e4f\",\n        \"size\": 197753019\n    },\n    \"EnterActorFlow_Town12_Route12362_Weather15.tar.gz\": {\n        \"sha256\": \"1e060f0fa63aaca83bbb26d3e79318f71fba9c46d78e8980cb09556e6bf73783\",\n        \"size\": 316747156\n    },\n    \"EnterActorFlow_Town12_Route12363_Weather8.tar.gz\": {\n        \"sha256\": \"8408e694eea9afb8c56aa72174e27a28da4df6fc0b699f55f7a700f4e01960bd\",\n        \"size\": 380469846\n    },\n    \"EnterActorFlow_Town12_Route12365_Weather18.tar.gz\": {\n        \"sha256\": \"43ec556bc57603a9f9134465eec97cd1c93eec5085d171575b4856d9069aab62\",\n        \"size\": 213745131\n    },\n    \"EnterActorFlow_Town12_Route12368_Weather21.tar.gz\": {\n        \"sha256\": \"9a612f573eb370ca75020ac56650785a1e9601c31435284293ee5d6387c99c1c\",\n        \"size\": 229264920\n    },\n    \"EnterActorFlow_Town12_Route12369_Weather22.tar.gz\": {\n        \"sha256\": \"956cda3452da2e537b24b00d609312089734dc26cf17373fbedc07fd12221f23\",\n        \"size\": 330152692\n    },\n    \"EnterActorFlow_Town12_Route12370_Weather23.tar.gz\": {\n        \"sha256\": \"73c5f82be2b9a4126a906d71274d85ffae836e0a2b8dcdcafa176d874c1b23ba\",\n        \"size\": 337361225\n    },\n    \"EnterActorFlow_Town12_Route12371_Weather23.tar.gz\": {\n        \"sha256\": \"20860dc644444c9fba6f725b64d2499187e43ec5c6b9a52914da6755c69b99f9\",\n        \"size\": 282402482\n    },\n    \"EnterActorFlow_Town12_Route12372_Weather25.tar.gz\": {\n        \"sha256\": \"de6a3707f821852c913a2e6bfaa645c3e419276e8d9a99c9eb022683f2116f7d\",\n        \"size\": 256125286\n    },\n    \"EnterActorFlow_Town12_Route12375_Weather2.tar.gz\": {\n        \"sha256\": \"fd7e5b68288580c4788fbfe9600049a55b4697f880ed449556d2026bfb3a20b1\",\n        \"size\": 230573064\n    },\n    \"EnterActorFlow_Town12_Route12376_Weather3.tar.gz\": {\n        \"sha256\": \"9fb5ef2e1439610541f7fb74ccf8973cac9383a4372fc1bae970c2c70639626c\",\n        \"size\": 96563948\n    },\n    \"EnterActorFlow_Town12_Route12384_Weather11.tar.gz\": {\n        \"sha256\": \"4922d81c1008d614cb2ce2373fc27ee241cd22230e2afa83e6fe5ecc30c17d32\",\n        \"size\": 181822157\n    },\n    \"EnterActorFlow_Town12_Route12388_Weather15.tar.gz\": {\n        \"sha256\": \"0822142ebd0b241e8047348793de840174477f8685132e11c4336dbbe142f370\",\n        \"size\": 304849285\n    },\n    \"EnterActorFlow_Town12_Route12389_Weather8.tar.gz\": {\n        \"sha256\": \"3264e20495c225bb53c80833b4672464f84ff32fc400598247ef6d792cb63e8b\",\n        \"size\": 587817043\n    },\n    \"EnterActorFlow_Town12_Route12392_Weather19.tar.gz\": {\n        \"sha256\": \"fc59919bacc27c94a5b68d9b8c9044975fca1a9458d5e177b0e7ba305202f387\",\n        \"size\": 224052105\n    },\n    \"EnterActorFlow_Town12_Route12393_Weather20.tar.gz\": {\n        \"sha256\": \"b239b15091d77e27d27940997f291131fb726f69dca1966d7f770447ac07c26c\",\n        \"size\": 105780830\n    },\n    \"EnterActorFlow_Town12_Route12395_Weather22.tar.gz\": {\n        \"sha256\": \"1480452bcfe7ab77c2e0b8860988bf484c8be973feb17d5a8cb02d8ec4ca41f4\",\n        \"size\": 132168619\n    },\n    \"EnterActorFlow_Town12_Route12397_Weather23.tar.gz\": {\n        \"sha256\": \"897f1ecb5446e6ea781384842ee4d3a212e33193b9bec3906ee86b47d021b1ee\",\n        \"size\": 359309172\n    },\n    \"EnterActorFlow_Town12_Route12400_Weather1.tar.gz\": {\n        \"sha256\": \"10682a141d8ee5d3fd1cf6d0da3890335eb66334ab5e70320ff4dc0bf8d17a21\",\n        \"size\": 408971093\n    },\n    \"EnterActorFlow_Town12_Route12401_Weather2.tar.gz\": {\n        \"sha256\": \"c67b22f73b9697428e5c820091efbe39ebad8bbca6486354f535dbb9e7642b3b\",\n        \"size\": 217128839\n    },\n    \"EnterActorFlow_Town12_Route12402_Weather3.tar.gz\": {\n        \"sha256\": \"88a7bde7343c38c599323fb1c0109a109adf7c432049d6035bdc35bd4ba42def\",\n        \"size\": 335757519\n    },\n    \"EnterActorFlow_Town12_Route12403_Weather3.tar.gz\": {\n        \"sha256\": \"ebc2925c1225e32592e70563420e496f839744dfc7678f79043c2b4c83592c96\",\n        \"size\": 413564974\n    },\n    \"EnterActorFlow_Town12_Route12404_Weather5.tar.gz\": {\n        \"sha256\": \"8de7a9967034a0f833c5a4ef63e0a404d3f6b049893363eebbdbb4106a9f9e1d\",\n        \"size\": 196799962\n    },\n    \"EnterActorFlow_Town12_Route12405_Weather6.tar.gz\": {\n        \"sha256\": \"f98f7315beffba3e96cd5017792610b5ff3b374cd1a842b8440d84bde46a149e\",\n        \"size\": 441324515\n    },\n    \"EnterActorFlow_Town12_Route12406_Weather7.tar.gz\": {\n        \"sha256\": \"2209b0a1a8b4edc705fd08d02b6ec3c10046202298e3f39e5fa398cfdb6b0566\",\n        \"size\": 204601944\n    },\n    \"EnterActorFlow_Town12_Route12409_Weather10.tar.gz\": {\n        \"sha256\": \"36ce2e16f5b2cc19a9eee763bb18687045a6e3369f54024bd77396529900d226\",\n        \"size\": 143264027\n    },\n    \"EnterActorFlow_Town12_Route12411_Weather12.tar.gz\": {\n        \"sha256\": \"5b641d086d39bec1d10b0465ae02a27d6fffc5d014cec4fdd06226917f386e63\",\n        \"size\": 635091045\n    },\n    \"EnterActorFlow_Town12_Route12412_Weather13.tar.gz\": {\n        \"sha256\": \"04334f1fae5bb75a96c65087983b2531ef4919356d0b23eb739f2e0241d3b4f3\",\n        \"size\": 489039850\n    },\n    \"EnterActorFlow_Town12_Route12413_Weather14.tar.gz\": {\n        \"sha256\": \"d20c2294e5429ce3f62e3d9ffc643e571666fe9cec416ea683e2dd7ac5525164\",\n        \"size\": 346693031\n    },\n    \"EnterActorFlow_Town12_Route12420_Weather21.tar.gz\": {\n        \"sha256\": \"399b4492c7313a08833e00a7219d87156caed39058f65cbe97f9c2d9ef96a80b\",\n        \"size\": 474339649\n    },\n    \"EnterActorFlow_Town12_Route12421_Weather22.tar.gz\": {\n        \"sha256\": \"886f79bad7ee5c9d290509e3a3f9572a2c1e250ea457293c7916db3a64b0fb33\",\n        \"size\": 291168773\n    },\n    \"EnterActorFlow_Town12_Route12423_Weather23.tar.gz\": {\n        \"sha256\": \"fc2fc9d43a0ccdbe29f0d404f976abf3619f952938c27da0965a4399eda128a9\",\n        \"size\": 100584239\n    },\n    \"EnterActorFlow_Town12_Route12425_Weather0.tar.gz\": {\n        \"sha256\": \"c681de053b421534c1d99b5fc350d287fed5ca195ffd1a977d8fcd610b33ab16\",\n        \"size\": 744049987\n    },\n    \"EnterActorFlow_Town12_Route12429_Weather3.tar.gz\": {\n        \"sha256\": \"7bd8e16b1095f752143aa9a63f2e74d9caa59f6235e32720ab863fcecf7120e0\",\n        \"size\": 473605442\n    },\n    \"EnterActorFlow_Town12_Route12431_Weather6.tar.gz\": {\n        \"sha256\": \"265adf2c151b206d3d2331fd53aa6fea33e61da19c9be1c2eb20b78ce2b1be69\",\n        \"size\": 374092467\n    },\n    \"EnterActorFlow_Town12_Route12432_Weather7.tar.gz\": {\n        \"sha256\": \"8cde1cfce52bd14724dc999132bffc3e58ed698bc86eee0534aea386899d607b\",\n        \"size\": 339060605\n    },\n    \"EnterActorFlow_Town12_Route12433_Weather8.tar.gz\": {\n        \"sha256\": \"127db3e7da5e5cf258ee3e7aa6225a3058d2f40f5e4697a3fe46103d122ddffe\",\n        \"size\": 297737863\n    },\n    \"EnterActorFlow_Town12_Route2190_Weather0.tar.gz\": {\n        \"sha256\": \"bd4a267c26e8f6f81394ebcc56a611d0eeaf33fff53611e402080f30f30268b8\",\n        \"size\": 371068082\n    },\n    \"EnterActorFlow_Town12_Route2192_Weather2.tar.gz\": {\n        \"sha256\": \"92d5377b80fe35e5316b46687c93d9d2a8b42d68ce2cd260995cdbacbc63be2e\",\n        \"size\": 729737526\n    },\n    \"EnterActorFlow_Town12_Route2193_Weather3.tar.gz\": {\n        \"sha256\": \"abb9547369edd6d8dc937f4cbe040ace3bde317b99abbe9af1d2dc7dd77189b9\",\n        \"size\": 525954815\n    },\n    \"EnterActorFlow_Town12_Route2197_Weather7.tar.gz\": {\n        \"sha256\": \"0c2a584cfbd6dc043e4b75f5c4267aee4eaab1c0dcf195417386b58cd5cb653a\",\n        \"size\": 291256653\n    },\n    \"EnterActorFlow_Town12_Route2198_Weather8.tar.gz\": {\n        \"sha256\": \"706034f384f7b7a52eb34e8c5e680d1a57f79ab4b4b519d824e3dbb9fc805d5a\",\n        \"size\": 754400956\n    },\n    \"EnterActorFlow_Town12_Route2199_Weather9.tar.gz\": {\n        \"sha256\": \"69b7964b606c3c4941688fca19c75ee38bf27147d680011a692491c6130780ce\",\n        \"size\": 135826649\n    },\n    \"EnterActorFlow_Town12_Route2200_Weather10.tar.gz\": {\n        \"sha256\": \"ea7c370d0f84075899ce112ce9c26db463a111c1fd0fb2e998838176c17d0941\",\n        \"size\": 803419380\n    },\n    \"EnterActorFlow_Town12_Route2201_Weather11.tar.gz\": {\n        \"sha256\": \"9a6e504d7021ad2ffffe71fceed5c41d41ec7a62c34e33a61a0484788f58f077\",\n        \"size\": 358834331\n    },\n    \"EnterActorFlow_Town12_Route2964_Weather20.tar.gz\": {\n        \"sha256\": \"e9c36590b47b38eb051d3cbf4dbb047650298562af4896cb873d08f1dd57b74a\",\n        \"size\": 178813670\n    },\n    \"EnterActorFlow_Town12_Route2965_Weather21.tar.gz\": {\n        \"sha256\": \"4d82ac196d7dba2dceb1baf746187ad21d04f40012a8dace415d0b768ac9b8cc\",\n        \"size\": 631703548\n    },\n    \"EnterActorFlow_Town12_Route2966_Weather22.tar.gz\": {\n        \"sha256\": \"f4442b5c4107aded1ca850d72c8cf1e2528d2c4910f7b8204b1b19e282bc1dae\",\n        \"size\": 403626388\n    },\n    \"EnterActorFlow_Town12_Route2967_Weather23.tar.gz\": {\n        \"sha256\": \"3edf20e149f2a7f01ea2fa8a09e7c3f7bc575a40b284530bcf3fb7d177443c5a\",\n        \"size\": 313089409\n    },\n    \"EnterActorFlow_Town12_Route2968_Weather23.tar.gz\": {\n        \"sha256\": \"d8ea6b76f4309fc54149b2e86e69ee2e36c5f6630d66f2e26a8cbd7226c2eed8\",\n        \"size\": 292985607\n    },\n    \"EnterActorFlow_Town12_Route2970_Weather0.tar.gz\": {\n        \"sha256\": \"d6afaea6dbc0c4585a1a40f4894c0837c9b524e323d8c02fb5e6f00bb70d0a3c\",\n        \"size\": 251476019\n    },\n    \"EnterActorFlow_Town12_Route2971_Weather1.tar.gz\": {\n        \"sha256\": \"c21fc8dea12af572bc8049ba553464661359f287fd582267fd4f366efad0050d\",\n        \"size\": 240189858\n    },\n    \"EnterActorFlow_Town12_Route2978_Weather8.tar.gz\": {\n        \"sha256\": \"f9a433c9706ae1f4687bb3b489e7d94120b7b2521fe89b4a28b46fd9a3581782\",\n        \"size\": 236019736\n    },\n    \"EnterActorFlow_Town12_Route2980_Weather10.tar.gz\": {\n        \"sha256\": \"2decd68f6ae20aa9b0d6287ad0cde4a032f96d45d30fc5805154a79cadee8f13\",\n        \"size\": 389532394\n    },\n    \"EnterActorFlow_Town12_Route2983_Weather13.tar.gz\": {\n        \"sha256\": \"3041c0c2a71248af99022e5b971fd27161ce68cca3f2c11a9381f6301f6253ed\",\n        \"size\": 80582621\n    },\n    \"EnterActorFlow_Town13_Route3744_Weather21.tar.gz\": {\n        \"sha256\": \"8fe715dfca3b04f6f224fc37f0e74ef01649e2ae56e82a5192e1253856a3bd56\",\n        \"size\": 575369753\n    },\n    \"EnterActorFlow_Town13_Route3748_Weather25.tar.gz\": {\n        \"sha256\": \"8661994f7a8e0a5d9f4826980e5532142b84de2cdd6cdfb9a40616f6163572e8\",\n        \"size\": 371427129\n    },\n    \"EnterActorFlow_Town13_Route3749_Weather0.tar.gz\": {\n        \"sha256\": \"7dd471a72c5872cb9cb750115e28263763306ba6d597566f65b97c25c2b61665\",\n        \"size\": 439438010\n    },\n    \"EnterActorFlow_Town13_Route3750_Weather1.tar.gz\": {\n        \"sha256\": \"ba05a76d192e4b6c62d57416188827bf38cca3d1db436a0e4f7cd73ed44fa4b1\",\n        \"size\": 590428237\n    },\n    \"EnterActorFlow_Town13_Route3752_Weather3.tar.gz\": {\n        \"sha256\": \"575f99a08d272f60e5c794fdbd1b878c58b2520aec840483844ac26e6b0ebfe5\",\n        \"size\": 122230109\n    },\n    \"EnterActorFlow_Town13_Route3753_Weather3.tar.gz\": {\n        \"sha256\": \"8640b801c92daad7825fd526e328a7738291aae533dacb6abde2390c927daee5\",\n        \"size\": 139004731\n    },\n    \"EnterActorFlow_Town13_Route3755_Weather6.tar.gz\": {\n        \"sha256\": \"08efaf66a1da79eaf827bbbb70eaae3cbff1dabb983c790aa06a8f4879d5aeec\",\n        \"size\": 855095301\n    },\n    \"EnterActorFlow_Town13_Route3756_Weather7.tar.gz\": {\n        \"sha256\": \"6dc82909aa514900726e815cf44a41671c22fe4dde26fade0168d15c550a8ad4\",\n        \"size\": 147082782\n    },\n    \"EnterActorFlow_Town13_Route3757_Weather8.tar.gz\": {\n        \"sha256\": \"0f0d8ac7404ed5aaf7b8085e882584421f5a88a92feb43aa20494e93fe1e7e1f\",\n        \"size\": 110571571\n    },\n    \"EnterActorFlow_Town13_Route3758_Weather9.tar.gz\": {\n        \"sha256\": \"edd0e99aa3fd8036a0bc0cf3ba728fdaaa10e66d4d79254f40eaca64a78a029b\",\n        \"size\": 174465309\n    },\n    \"EnterActorFlow_Town13_Route3759_Weather10.tar.gz\": {\n        \"sha256\": \"3207367ae921f4c2600c6e22beb0a06c1dba16ae7fa9e6976598f6719bfd8ceb\",\n        \"size\": 132472306\n    },\n    \"EnterActorFlow_Town13_Route3760_Weather11.tar.gz\": {\n        \"sha256\": \"ff16833a45fc471762ca2e8d2842fa7ea8a9665003bffc57f5d8bb9f63ae2686\",\n        \"size\": 87430047\n    },\n    \"EnterActorFlow_Town15_Route27198_Weather12.tar.gz\": {\n        \"sha256\": \"b61aa017ffe63dc72e49ae60569b54303351d057f32ecff6f20a75160e6cceec\",\n        \"size\": 1570774411\n    },\n    \"EnterActorFlow_Town15_Route27258_Weather2.tar.gz\": {\n        \"sha256\": \"ce1115a0658521a699c9fb515a09fe007d4544a45415556dd884a376aeab90a5\",\n        \"size\": 1779043148\n    },\n    \"EnterActorFlow_Town15_Route27263_Weather8.tar.gz\": {\n        \"sha256\": \"6c9ef96487a2e1955908f4a2809005eb91cb788c3beb546577a628458a831f83\",\n        \"size\": 1326503834\n    },\n    \"EnterActorFlow_Town15_Route27273_Weather20.tar.gz\": {\n        \"sha256\": \"d890f94c0fffd7454cb73ee9c051049e8109acc32b00a4c2f5a3a10dc10ef431\",\n        \"size\": 1597941205\n    },\n    \"EnterActorFlow_Town15_Route27283_Weather5.tar.gz\": {\n        \"sha256\": \"7c914fce2b230ce48a5779166500e031b8f4694175478aac571c5989504e6be2\",\n        \"size\": 376624604\n    },\n    \"HardBreakRoute_Town01_Route24751_Weather2.tar.gz\": {\n        \"sha256\": \"9f13ed7200ce2e3c9cad87d44bd6536881bcc2624bfefd1d9c712dd5b5c63170\",\n        \"size\": 482541194\n    },\n    \"HardBreakRoute_Town01_Route24761_Weather13.tar.gz\": {\n        \"sha256\": \"f4b9557f29514879bbf07ae2516174f13a4f5bafd4916dca0ab7a203b02d4acb\",\n        \"size\": 392133061\n    },\n    \"HardBreakRoute_Town01_Route24771_Weather26.tar.gz\": {\n        \"sha256\": \"a5b3113c453ef2c264ff7d0fb91c1e0590e279c6e5f614d3b9c23bc8cc2405a1\",\n        \"size\": 469079983\n    },\n    \"HardBreakRoute_Town01_Route24781_Weather10.tar.gz\": {\n        \"sha256\": \"46cac1b884e1a1735c592b1b2a9f6fcd3e2fff819dc503e61f7b8c8c50baa920\",\n        \"size\": 653164871\n    },\n    \"HardBreakRoute_Town01_Route24791_Weather22.tar.gz\": {\n        \"sha256\": \"ea3a6efbbddd409b5b2e7b3845d063f904dd517a4720aa288116d6799570a525\",\n        \"size\": 404415972\n    },\n    \"HardBreakRoute_Town03_Route26449_Weather25.tar.gz\": {\n        \"sha256\": \"1ed401f12fa1fefc8d08634423a3a862b3c064755fba508657487444f50d497f\",\n        \"size\": 540724984\n    },\n    \"HardBreakRoute_Town03_Route26456_Weather6.tar.gz\": {\n        \"sha256\": \"0676245781782820d17af1d8d2c67cdc31a8220c752ad81e14234836d80e4173\",\n        \"size\": 1228560102\n    },\n    \"HardBreakRoute_Town03_Route26463_Weather13.tar.gz\": {\n        \"sha256\": \"f1c9964767205313e30ebb896a9f0a047097ea015dd8271339c7ebdd9c866209\",\n        \"size\": 392211964\n    },\n    \"HardBreakRoute_Town03_Route26470_Weather22.tar.gz\": {\n        \"sha256\": \"60618fdbdbbc679bc56f5b18a15379aa63e42b76b6458a4f8b87cfa605bd3d77\",\n        \"size\": 352800705\n    },\n    \"HardBreakRoute_Town03_Route26477_Weather3.tar.gz\": {\n        \"sha256\": \"f935a4e8d5ed6f642d972090b54055d6ab53658c962122c881dabfcedf09fad6\",\n        \"size\": 341935534\n    },\n    \"HardBreakRoute_Town03_Route26484_Weather11.tar.gz\": {\n        \"sha256\": \"4d8175282a993fdeb86660720e0fa299cac8a3d14f3abd10fc2ff223dc66fc7a\",\n        \"size\": 307099003\n    },\n    \"HardBreakRoute_Town03_Route26491_Weather20.tar.gz\": {\n        \"sha256\": \"73b85d73d72d0d4c91c4546f94a6755c181b37c7578b83a45025291d8940fb90\",\n        \"size\": 985144793\n    },\n    \"HardBreakRoute_Town03_Route26497_Weather0.tar.gz\": {\n        \"sha256\": \"3971b8aa3caa078f13cc0a49ffdf34c5ad9c64ea3750d9d1633e529011d01623\",\n        \"size\": 319544515\n    },\n    \"HardBreakRoute_Town03_Route26503_Weather7.tar.gz\": {\n        \"sha256\": \"de017d5c2cf2381add6a6ac2d59262233f3d264b84d2a23bbda75f611c96a459\",\n        \"size\": 345171464\n    },\n    \"HardBreakRoute_Town03_Route26509_Weather13.tar.gz\": {\n        \"sha256\": \"3299bee79dbb5c8de93a4f675b7c37d1a290ea5a28f31c7a7656267510ab8909\",\n        \"size\": 307999655\n    },\n    \"HardBreakRoute_Town03_Route26521_Weather1.tar.gz\": {\n        \"sha256\": \"aeb114f22845e6984fac145f51076a57116bd844a9f8faa1391ed21a0ecf0bc1\",\n        \"size\": 557063472\n    },\n    \"HardBreakRoute_Town03_Route26527_Weather8.tar.gz\": {\n        \"sha256\": \"84ab20a1fa53d7982f2d3340c77264109982e16f8dc53e1b05d2d5a0cd083df3\",\n        \"size\": 298568329\n    },\n    \"HardBreakRoute_Town03_Route26533_Weather14.tar.gz\": {\n        \"sha256\": \"9a0f29f6ed86ab576188ebeaee401b4f31f48711059cc974d33aac80acb685d9\",\n        \"size\": 167782030\n    },\n    \"HardBreakRoute_Town03_Route26539_Weather22.tar.gz\": {\n        \"sha256\": \"d20b2b9d8ecc83b3a9c667e9d6426bd9efec08b7583d39079fa25e9a4a412844\",\n        \"size\": 986955103\n    },\n    \"HardBreakRoute_Town03_Route26545_Weather2.tar.gz\": {\n        \"sha256\": \"1bd88e3b2a5c635b11ee52f3994271e4ebf16a7222f4316e33bb584c274c8e30\",\n        \"size\": 354910978\n    },\n    \"HardBreakRoute_Town03_Route26555_Weather13.tar.gz\": {\n        \"sha256\": \"f0f7884d7ee11d33a995985dc5b0d4671bfb493a0be8aba13e5c96f788762304\",\n        \"size\": 1050950534\n    },\n    \"HardBreakRoute_Town03_Route26560_Weather20.tar.gz\": {\n        \"sha256\": \"b213f381ca9f8a32da2c5f903def872b0cf91ef5ec409289cf17804175e64a70\",\n        \"size\": 390364237\n    },\n    \"HardBreakRoute_Town03_Route26565_Weather26.tar.gz\": {\n        \"sha256\": \"62f166c54d85e9ac84669954dbb7a7fa14387b1e888f99d22e5900c9e5ba0d62\",\n        \"size\": 654055077\n    },\n    \"HardBreakRoute_Town04_Route26399_Weather20.tar.gz\": {\n        \"sha256\": \"67ccebd65fff5a15ce361492be010505c945990018b627f2d65ce1db12ba434d\",\n        \"size\": 413229024\n    },\n    \"HardBreakRoute_Town04_Route26406_Weather1.tar.gz\": {\n        \"sha256\": \"b85db9a04f8935e7b010fb197bb78246ba3bc3e63e854abe57c749802c007bfd\",\n        \"size\": 359131527\n    },\n    \"HardBreakRoute_Town04_Route26420_Weather18.tar.gz\": {\n        \"sha256\": \"abc42d7e20f5a463caa7f9d7826271c9fcb34c08696b3b51f07197e53121b500\",\n        \"size\": 514798339\n    },\n    \"HardBreakRoute_Town04_Route26434_Weather7.tar.gz\": {\n        \"sha256\": \"3a482fc79be6378bd38cb5b25fcf7595e9606d00d27f9cd8ffdf3ed1ab1621f4\",\n        \"size\": 413151515\n    },\n    \"HardBreakRoute_Town04_Route26441_Weather14.tar.gz\": {\n        \"sha256\": \"85c4af8e2fa5fc043ffc24838f2395c80affa317ef290bf24735bd2796ebe2cd\",\n        \"size\": 371167758\n    },\n    \"HardBreakRoute_Town04_Route26448_Weather23.tar.gz\": {\n        \"sha256\": \"8af044671830ad3e782dfedad07fbf51b04ae41a8b87fb5dabc11b67664b8f5f\",\n        \"size\": 274881782\n    },\n    \"HardBreakRoute_Town04_Route26455_Weather5.tar.gz\": {\n        \"sha256\": \"3e4281962c4f71a68abe899f03eac85773f55bd90aada4e30e1ac99bf2001e8e\",\n        \"size\": 466165088\n    },\n    \"HardBreakRoute_Town04_Route26462_Weather12.tar.gz\": {\n        \"sha256\": \"261456435427c59123ce8d310b0e96df47bceea245a54034e52022fe1082f8b9\",\n        \"size\": 305805195\n    },\n    \"HardBreakRoute_Town04_Route26469_Weather21.tar.gz\": {\n        \"sha256\": \"a6fa1c22448db88f59d2d82b09b0593a7147345e01615dfc05f49949fb469f6b\",\n        \"size\": 257093281\n    },\n    \"HardBreakRoute_Town04_Route26476_Weather2.tar.gz\": {\n        \"sha256\": \"6779c5db8df0180fe657a3f70b07290480b308d39d3ed364b19d82684d11c325\",\n        \"size\": 363628622\n    },\n    \"HardBreakRoute_Town04_Route26483_Weather10.tar.gz\": {\n        \"sha256\": \"2d0f2b0de6a8a87e7d6ddc754d75939a04de704a448a1e21b6997b4230affddf\",\n        \"size\": 316754599\n    },\n    \"HardBreakRoute_Town04_Route26490_Weather19.tar.gz\": {\n        \"sha256\": \"d7752ae6f265ca5b110f85866b756f2706c18c49719707fb61a9bbe42b70fabd\",\n        \"size\": 247787330\n    },\n    \"HardBreakRoute_Town04_Route26496_Weather26.tar.gz\": {\n        \"sha256\": \"8ddf264f998bf675dffde3a0dc321c3fb68bb3cb628f486011983f641171252d\",\n        \"size\": 401589182\n    },\n    \"HardBreakRoute_Town04_Route26502_Weather6.tar.gz\": {\n        \"sha256\": \"8ce3cb2f558bc3fb37819bfa657d10015ca65582bd0ecfcc44c342cd5110db5e\",\n        \"size\": 337874597\n    },\n    \"HardBreakRoute_Town04_Route26508_Weather12.tar.gz\": {\n        \"sha256\": \"89c093d1db3b4ac3ba9d5e390162451331f429fccc1fa1abe64025393b264348\",\n        \"size\": 304682753\n    },\n    \"HardBreakRoute_Town05_Route26616_Weather5.tar.gz\": {\n        \"sha256\": \"4f68502679fc90d7e2e7f8fafef6bf1d879c6bbdea9867f8626bf1acc0062a03\",\n        \"size\": 868568245\n    },\n    \"HardBreakRoute_Town05_Route26626_Weather15.tar.gz\": {\n        \"sha256\": \"1c2bbc9a7aeeaab82fa1b0e961f75f367e4d74f09370e30ca551576f1b15aebc\",\n        \"size\": 674548337\n    },\n    \"HardBreakRoute_Town05_Route26636_Weather1.tar.gz\": {\n        \"sha256\": \"a397ca46f5460f1d9d35b163d1d42ea0e8dba8de28bf00b2fc9739f5f1911e31\",\n        \"size\": 315466470\n    },\n    \"HardBreakRoute_Town05_Route26641_Weather7.tar.gz\": {\n        \"sha256\": \"b20d63082d66e6d52756ac91dd32d85c9d6e6a228bed8bf0ac858665eae56ddd\",\n        \"size\": 393516011\n    },\n    \"HardBreakRoute_Town05_Route26646_Weather12.tar.gz\": {\n        \"sha256\": \"80f1fdd3ca4fd768ad457107761bea7cf94ca6bfb1c27d0bf44dfcf26105e9fa\",\n        \"size\": 344488785\n    },\n    \"HardBreakRoute_Town05_Route26651_Weather19.tar.gz\": {\n        \"sha256\": \"2f9c8264925c0d52c284c9af0185c730fbb43836176c777dc692d53610d570d5\",\n        \"size\": 272913680\n    },\n    \"HardBreakRoute_Town05_Route26656_Weather25.tar.gz\": {\n        \"sha256\": \"fb8361b7df9ea01a6bf28321d007295d705c48ed483faa2c1689dc8a57d1d21b\",\n        \"size\": 366473665\n    },\n    \"HardBreakRoute_Town05_Route26661_Weather3.tar.gz\": {\n        \"sha256\": \"ea1633efd3108bf4049db8723b185e6f12a7efbc089e930fea75c83fb3e2145a\",\n        \"size\": 431070870\n    },\n    \"HardBreakRoute_Town05_Route26666_Weather9.tar.gz\": {\n        \"sha256\": \"eba146bc56f6aa2aec29070cdd05419618eee78c393b5bf3f0a06eb46db27925\",\n        \"size\": 286289199\n    },\n    \"HardBreakRoute_Town05_Route26671_Weather14.tar.gz\": {\n        \"sha256\": \"84e2f8df5c5ca044dc7a58f56451c73265564eabed0684c8323f15fb51610e7f\",\n        \"size\": 309191944\n    },\n    \"HardBreakRoute_Town05_Route26676_Weather21.tar.gz\": {\n        \"sha256\": \"52e8e6d99a2ae2ffa45d18fe52d1085c235ab554c99eafafa3595662ecb1e570\",\n        \"size\": 242390083\n    },\n    \"HardBreakRoute_Town05_Route26681_Weather0.tar.gz\": {\n        \"sha256\": \"f6fabf5b8f7d1bd1394308ad8ab6c089cfd4200ac62da0b3411df5f636cc19c8\",\n        \"size\": 397195451\n    },\n    \"HardBreakRoute_Town05_Route26686_Weather6.tar.gz\": {\n        \"sha256\": \"ca75cf204df75ea31778fc43fcff2739f8c77199adc5b1ad83eaaf4cd7a60ff1\",\n        \"size\": 574626853\n    },\n    \"HardBreakRoute_Town05_Route26691_Weather11.tar.gz\": {\n        \"sha256\": \"afc69e8d64afcb265332e56cc5985a79f33f92b3723c5c52fd37bee3897c1527\",\n        \"size\": 484683571\n    },\n    \"HardBreakRoute_Town05_Route26701_Weather23.tar.gz\": {\n        \"sha256\": \"88d66485d841c06ad0195caa735b4fc10e7974fb65dd4515da00f27f8ccb757a\",\n        \"size\": 382590305\n    },\n    \"HardBreakRoute_Town10HD_Route24330_Weather21.tar.gz\": {\n        \"sha256\": \"49ee49dd8de0f9bb4c53bd60c939f07120d833b1e1b3f14b2c9da1891a4293b2\",\n        \"size\": 328465806\n    },\n    \"HardBreakRoute_Town12_Route1964_Weather8.tar.gz\": {\n        \"sha256\": \"e8e4fc804aae5efa495cf366d2aa263e978eecf2e8fcb56f3f93b4da8ca4558c\",\n        \"size\": 224070751\n    },\n    \"HardBreakRoute_Town12_Route1965_Weather9.tar.gz\": {\n        \"sha256\": \"fbc61366915d73a4f17320bb3769f16b31cd19e87b9be2cf82bc33922092d3a8\",\n        \"size\": 468376132\n    },\n    \"HardBreakRoute_Town12_Route1966_Weather10.tar.gz\": {\n        \"sha256\": \"f462bedb9cde67f8f0af8e93b1fca2a66f435b506227c57c3ecf17e063427525\",\n        \"size\": 233087731\n    },\n    \"HardBreakRoute_Town12_Route1967_Weather11.tar.gz\": {\n        \"sha256\": \"be23aee773a37035ff27669f9d11ed47adcc9085197f86cd22001fa4f73e877d\",\n        \"size\": 356745811\n    },\n    \"HardBreakRoute_Town12_Route1968_Weather12.tar.gz\": {\n        \"sha256\": \"17430d9f03b44b8b42b4a26002e3b8b7bd2e22d3d2eb882e5f42dea1e7f8628c\",\n        \"size\": 299768744\n    },\n    \"HardBreakRoute_Town12_Route1969_Weather13.tar.gz\": {\n        \"sha256\": \"62f1c2b84c336155da7f838f0531b6d4c199158e3321a2fb611e8f5cd2ae2693\",\n        \"size\": 238594944\n    },\n    \"HardBreakRoute_Town12_Route1970_Weather14.tar.gz\": {\n        \"sha256\": \"75b34d2485da23c87b7c61f790c9aa14ec58aab350b7256908e944804ff58d2a\",\n        \"size\": 197381303\n    },\n    \"HardBreakRoute_Town12_Route1971_Weather15.tar.gz\": {\n        \"sha256\": \"b06d9bc5fd8b493788cdd794159eb63c4582430984142e54d56636a726076d4b\",\n        \"size\": 233744957\n    },\n    \"HardBreakRoute_Town12_Route1972_Weather8.tar.gz\": {\n        \"sha256\": \"19aca690ab8c721f85843e0d3a1f304c23356f68e7bd2f17a8c0fb4844d32b29\",\n        \"size\": 488670006\n    },\n    \"HardBreakRoute_Town12_Route1973_Weather9.tar.gz\": {\n        \"sha256\": \"b8b14b24de79e78c85f566a1435afd0bdd33a8e29aa1fba8c9b5dc07c7361d73\",\n        \"size\": 427242828\n    },\n    \"HardBreakRoute_Town12_Route1974_Weather18.tar.gz\": {\n        \"sha256\": \"54d197e13c612a395981c7a4be85e2123d9ba6d6f1ae5badffa775284832d945\",\n        \"size\": 663016752\n    },\n    \"HardBreakRoute_Town12_Route1975_Weather19.tar.gz\": {\n        \"sha256\": \"18aacd1f338bd5db1b68228c63d996dda65ad4ebf2f1267a376ae0482c5616d8\",\n        \"size\": 478437649\n    },\n    \"HardBreakRoute_Town12_Route1977_Weather21.tar.gz\": {\n        \"sha256\": \"213df747fda56dd99c54fac2c01d53d8ff4307ea9bad73e3d15b4716547af712\",\n        \"size\": 361209315\n    },\n    \"HardBreakRoute_Town12_Route1978_Weather22.tar.gz\": {\n        \"sha256\": \"91bce831db929d78d7bd8b3f6e01261cfedc9a6114754d4d5aafa12836217efe\",\n        \"size\": 476414421\n    },\n    \"HardBreakRoute_Town12_Route1979_Weather23.tar.gz\": {\n        \"sha256\": \"f38137d3f24f33b6f0febba797bac96897361724b275603086d6effcd9825184\",\n        \"size\": 432538061\n    },\n    \"HardBreakRoute_Town12_Route1980_Weather23.tar.gz\": {\n        \"sha256\": \"06142a5ff0e5e6422c4d641ccd8010657e0e1768f0d9323822f3462058b964af\",\n        \"size\": 372340321\n    },\n    \"HardBreakRoute_Town12_Route1981_Weather25.tar.gz\": {\n        \"sha256\": \"008880b30bcde83b3886a37eaa7de26baba19ac4d2077018e20d8aa98dc042f7\",\n        \"size\": 627482944\n    },\n    \"HardBreakRoute_Town12_Route22633_Weather12.tar.gz\": {\n        \"sha256\": \"b58606f63aaacb5c012114ee0d6e575c1790dc3c294bf0b410c49d2dffb5a31a\",\n        \"size\": 473317064\n    },\n    \"HardBreakRoute_Town12_Route22634_Weather13.tar.gz\": {\n        \"sha256\": \"9df650e01b7aca83a16b48b2c0813c1139c4933c258683d972c01d5290200f35\",\n        \"size\": 298677188\n    },\n    \"HardBreakRoute_Town12_Route22635_Weather14.tar.gz\": {\n        \"sha256\": \"cf244cc1e8e8f2b817b6ff544deb14d08dddd336436eadb9926e187e8d769144\",\n        \"size\": 212063934\n    },\n    \"HardBreakRoute_Town12_Route22636_Weather15.tar.gz\": {\n        \"sha256\": \"5d629f8edc9b0f5bf66f795d469d89a90ed49359229e9b3c592a54c7232ff9ad\",\n        \"size\": 219644065\n    },\n    \"HardBreakRoute_Town12_Route22637_Weather8.tar.gz\": {\n        \"sha256\": \"a3a8cbae61ae04da3a011210a62ebf8eb38a0aea74fb509df2968bb17db76a38\",\n        \"size\": 233762286\n    },\n    \"HardBreakRoute_Town12_Route22638_Weather9.tar.gz\": {\n        \"sha256\": \"436f3b9aea4dfaef565ca464a9f24a70b24c4679ddc0222edd85fef0412d6aa3\",\n        \"size\": 370976565\n    },\n    \"HardBreakRoute_Town12_Route22639_Weather18.tar.gz\": {\n        \"sha256\": \"279f801cafe65dd38b551022ad61b9c28f43199c33e63080204ea6fbbd206f7d\",\n        \"size\": 378671007\n    },\n    \"HardBreakRoute_Town12_Route22640_Weather19.tar.gz\": {\n        \"sha256\": \"268adcfe5ded466d10c50ed75c908ae4ea495aaef8682690c7bc1ecf9976c425\",\n        \"size\": 351048617\n    },\n    \"HardBreakRoute_Town12_Route22641_Weather20.tar.gz\": {\n        \"sha256\": \"07434383745941395147e2a7cf04b060f7cd1a7c73c4b36ee80f9330ea7bb41b\",\n        \"size\": 394519549\n    },\n    \"HardBreakRoute_Town12_Route22642_Weather21.tar.gz\": {\n        \"sha256\": \"6e9576c4c103d336dc8ab16ae28d42af1e6a9153cb50f1402f8c826a5a5e477d\",\n        \"size\": 404207203\n    },\n    \"HardBreakRoute_Town12_Route22643_Weather22.tar.gz\": {\n        \"sha256\": \"7b66b541a4acdf7adbed657002a7ef242237b5da65a74a04a764d3599d8fe56a\",\n        \"size\": 218927248\n    },\n    \"HardBreakRoute_Town12_Route22644_Weather23.tar.gz\": {\n        \"sha256\": \"0087b7b7f89d6401ed5889a95d54e6b18726f13645f95ec4b2426bd0ad8cc8b3\",\n        \"size\": 216262895\n    },\n    \"HardBreakRoute_Town12_Route22645_Weather23.tar.gz\": {\n        \"sha256\": \"67bafae1052fd4510399a5d139562e0276d38b82aa7cbdf8e9d0541ca9f4604c\",\n        \"size\": 486432814\n    },\n    \"HardBreakRoute_Town12_Route22646_Weather25.tar.gz\": {\n        \"sha256\": \"2b68ca2dcf78299a1cda6198547d03c57df0524d65e5ae54d0abb98700f3b4b8\",\n        \"size\": 161594822\n    },\n    \"HardBreakRoute_Town12_Route22647_Weather0.tar.gz\": {\n        \"sha256\": \"2b1d6ea7c43db81e41b6b71154928dc5318a05eded6a6bac59218c496bdc41a1\",\n        \"size\": 203042139\n    },\n    \"HardBreakRoute_Town12_Route22648_Weather1.tar.gz\": {\n        \"sha256\": \"d6f1249ed9b387670c666e0b91b49eb903e42c536ee6552acec694d6dbf26856\",\n        \"size\": 217246076\n    },\n    \"HardBreakRoute_Town12_Route22649_Weather2.tar.gz\": {\n        \"sha256\": \"d02a51be95be90db12c7261ff8affe155e8da110a06647d82caf99b01c6479db\",\n        \"size\": 212672380\n    },\n    \"HardBreakRoute_Town12_Route22650_Weather3.tar.gz\": {\n        \"sha256\": \"0b7d5618b3f344adcebac02dcc208b8ea1bcb5893ffc0b2b7599a97b82df3c4f\",\n        \"size\": 594110863\n    },\n    \"HardBreakRoute_Town12_Route22651_Weather3.tar.gz\": {\n        \"sha256\": \"dd780c5064921e51c47689a1d187b92f063300e8441995812ecb2c9ada1000bf\",\n        \"size\": 390694856\n    },\n    \"HardBreakRoute_Town12_Route22652_Weather5.tar.gz\": {\n        \"sha256\": \"97f580a5e676c953761ce48ce7b3043864bb3639b79db9ef1357069e6dcc7785\",\n        \"size\": 709136644\n    },\n    \"HardBreakRoute_Town12_Route22653_Weather6.tar.gz\": {\n        \"sha256\": \"617cfafce923795966af5f65d05af9fe226255ee30b7a5bd52c5fe65d8f85bd9\",\n        \"size\": 742091872\n    },\n    \"HardBreakRoute_Town12_Route22654_Weather7.tar.gz\": {\n        \"sha256\": \"42a46b2af66afbe24ab14b0ad4620408c36564a5cc66716704bc590749009a7f\",\n        \"size\": 808547136\n    },\n    \"HardBreakRoute_Town12_Route22655_Weather8.tar.gz\": {\n        \"sha256\": \"4df380a6ccd405a8596a72a1d748c77d44a764058aed105c91087890da8b4a94\",\n        \"size\": 745807389\n    },\n    \"HardBreakRoute_Town12_Route22656_Weather9.tar.gz\": {\n        \"sha256\": \"c4e4587fab9b03b16beb02f791d4b233e46ab52cfceb68fb470644c60d830177\",\n        \"size\": 739152744\n    },\n    \"HardBreakRoute_Town12_Route22657_Weather10.tar.gz\": {\n        \"sha256\": \"c9bebf714d4ad073e23ba85855415a11f0b10efb7e551b25f145cc53016a4ac1\",\n        \"size\": 695603541\n    },\n    \"HardBreakRoute_Town12_Route22658_Weather11.tar.gz\": {\n        \"sha256\": \"8557344528838d3b1051e9246a6bd983102fda2e7b03294d7c22a5893ee74fc5\",\n        \"size\": 394114942\n    },\n    \"HardBreakRoute_Town12_Route22659_Weather12.tar.gz\": {\n        \"sha256\": \"0e547af3bc1b62b6231841daa8ebf10a2fc6ddb3d08a19587f924521d9d89551\",\n        \"size\": 391253369\n    },\n    \"HardBreakRoute_Town12_Route22660_Weather13.tar.gz\": {\n        \"sha256\": \"8faf0c64d3f0889e28726961674fb404051e1c9b1d4d955fcb6148469c20b384\",\n        \"size\": 403296241\n    },\n    \"HardBreakRoute_Town12_Route22661_Weather14.tar.gz\": {\n        \"sha256\": \"a31500eb5f7e2771094e926cef242948e91dc8de8f1bbb1bd03c2b3231b0c9a1\",\n        \"size\": 419252576\n    },\n    \"HardBreakRoute_Town12_Route22662_Weather15.tar.gz\": {\n        \"sha256\": \"1cf4dab6912a319249b4c1daa024dc8a266848cf60e0b54d8612fecd28b95434\",\n        \"size\": 427438379\n    },\n    \"HardBreakRoute_Town12_Route22663_Weather8.tar.gz\": {\n        \"sha256\": \"e063d98a53298910278f4ef7e21f754f5ef79b0210984691103b329a2a8b6fa0\",\n        \"size\": 299906562\n    },\n    \"HardBreakRoute_Town12_Route22666_Weather19.tar.gz\": {\n        \"sha256\": \"48ba0d5d119ca1c060684e926e982e24efdbe63b9f8385833429e39869a354eb\",\n        \"size\": 511163136\n    },\n    \"HardBreakRoute_Town12_Route22667_Weather20.tar.gz\": {\n        \"sha256\": \"e56168ef9e054a93053ea0206f305539d294c54ed6dea3412c1c67c63fb0361e\",\n        \"size\": 378217577\n    },\n    \"HardBreakRoute_Town12_Route22668_Weather21.tar.gz\": {\n        \"sha256\": \"503a3f3a9224e78c65653e8b52884a09e25ffb36f7cc47583739bee649dfcafc\",\n        \"size\": 388978438\n    },\n    \"HardBreakRoute_Town12_Route22669_Weather22.tar.gz\": {\n        \"sha256\": \"9e463bc0c09266ae9b0f12aa131244b71d8b593473c5c1e9c5667c9931131dc0\",\n        \"size\": 524981711\n    },\n    \"HardBreakRoute_Town12_Route22670_Weather23.tar.gz\": {\n        \"sha256\": \"1f41e422e0b41c7570749e9493bbcfe1dca05ef8cfc774ce4e9b8e48688a1f88\",\n        \"size\": 516004590\n    },\n    \"HardBreakRoute_Town12_Route22671_Weather23.tar.gz\": {\n        \"sha256\": \"448969e5c728ec63f29803019be12d357c7b8e29f14ddde6c9e3c6d809c5b863\",\n        \"size\": 493133368\n    },\n    \"HardBreakRoute_Town12_Route22673_Weather0.tar.gz\": {\n        \"sha256\": \"6299030e2a3d9b548b144a8c1f94e7e78b53c5ea942b3f2b491a31b90bf5a68e\",\n        \"size\": 592129901\n    },\n    \"HardBreakRoute_Town12_Route22674_Weather1.tar.gz\": {\n        \"sha256\": \"3f0ff48c3c1980613cf05c472cce4f1f7bed3059c1b20238e28db5da1316cae2\",\n        \"size\": 658452975\n    },\n    \"HardBreakRoute_Town12_Route22675_Weather2.tar.gz\": {\n        \"sha256\": \"ac16ab53e6c33e14713f7767291a75ff4dd034e430e5b73a207643ba54459907\",\n        \"size\": 598982725\n    },\n    \"HardBreakRoute_Town12_Route22676_Weather3.tar.gz\": {\n        \"sha256\": \"b76d3b4f118df70a987a70e8c06f8fc7ca951864c5627071e778c0306137600c\",\n        \"size\": 582633826\n    },\n    \"HardBreakRoute_Town12_Route22677_Weather3.tar.gz\": {\n        \"sha256\": \"e00486ed5c935bc039da1f1c69ce29e484fe95ba3ad65773dd69a6b0fb85e040\",\n        \"size\": 543238796\n    },\n    \"HardBreakRoute_Town12_Route22678_Weather5.tar.gz\": {\n        \"sha256\": \"7d1c096c1a538ccc59b76af65f8ae810b7caf205e0c4eeb2fa557642ab15ba4d\",\n        \"size\": 574473658\n    },\n    \"HardBreakRoute_Town12_Route22679_Weather6.tar.gz\": {\n        \"sha256\": \"aada51b7d28fbf55e9dd872ad46b4d281968718080cb9052f98d8d546ac96ff0\",\n        \"size\": 511821841\n    },\n    \"HardBreakRoute_Town12_Route22680_Weather7.tar.gz\": {\n        \"sha256\": \"d47e831b3a303257c187e083a4d8106a47561991bb37a5f52d3f47d627459404\",\n        \"size\": 451880482\n    },\n    \"HardBreakRoute_Town12_Route22681_Weather8.tar.gz\": {\n        \"sha256\": \"381faab5cec922aec9826021fb30df4467fadc3063dadb50f679e2401326649d\",\n        \"size\": 496660719\n    },\n    \"HardBreakRoute_Town12_Route22682_Weather9.tar.gz\": {\n        \"sha256\": \"1a1037fdb2f69c37553ba67653fcd71a231176b6d981bec067f21da3b64ac154\",\n        \"size\": 376473760\n    },\n    \"HardBreakRoute_Town12_Route22684_Weather11.tar.gz\": {\n        \"sha256\": \"f41744a31ee0b8e27ad203a43abed8da418bdaa045c97508800e74f1d1c75930\",\n        \"size\": 277604815\n    },\n    \"HardBreakRoute_Town12_Route22685_Weather12.tar.gz\": {\n        \"sha256\": \"bcd438698287de2dbf376d5ae204067ca5e480e97bac9697c4ef19d0558b1aa3\",\n        \"size\": 353526813\n    },\n    \"HardBreakRoute_Town12_Route22686_Weather13.tar.gz\": {\n        \"sha256\": \"75c5bb0e151e1d80a26e37e52bb5f31b242e996d53189c90094de72f8432b992\",\n        \"size\": 522120324\n    },\n    \"HardBreakRoute_Town12_Route22687_Weather14.tar.gz\": {\n        \"sha256\": \"9a7d339a70ecae7e16e6f1bd3221d899c96129ce3bdeeb131643937b833260c0\",\n        \"size\": 514102690\n    },\n    \"HardBreakRoute_Town12_Route22688_Weather15.tar.gz\": {\n        \"sha256\": \"4537eb51f8d8f0d4552d8b74a39c13ffc5a9ea46598639fdacff4f4383434972\",\n        \"size\": 268988968\n    },\n    \"HardBreakRoute_Town12_Route22689_Weather8.tar.gz\": {\n        \"sha256\": \"7ca3db4845c8889b154b050a40c2b3eeec719d1aa1b0aa9b355ebe886b57af5b\",\n        \"size\": 574594723\n    },\n    \"HardBreakRoute_Town12_Route22690_Weather9.tar.gz\": {\n        \"sha256\": \"44188bbef418d9a3ff8ab3066d3bbd4ab9c0b154281a94fd312a634237582fda\",\n        \"size\": 446859430\n    },\n    \"HardBreakRoute_Town12_Route22692_Weather19.tar.gz\": {\n        \"sha256\": \"ea07884fba9a342c7576aa8c3b28790b9173d4c032405b8b9f64fc07a5e70e5f\",\n        \"size\": 553337742\n    },\n    \"HardBreakRoute_Town12_Route22696_Weather23.tar.gz\": {\n        \"sha256\": \"515e4f4182a29906f4f1e3f9e448f6c13b1ee0e7df45a87e9fc121f1f8664cf3\",\n        \"size\": 449017171\n    },\n    \"HardBreakRoute_Town12_Route22697_Weather23.tar.gz\": {\n        \"sha256\": \"6c75b0cbcc47a7cbe620abba33f3b63fa4ff943402d3a3a536b67b51427ecd7e\",\n        \"size\": 479133938\n    },\n    \"HardBreakRoute_Town12_Route22698_Weather25.tar.gz\": {\n        \"sha256\": \"7ab9743660e8c5cb47a16432acd1ae7fc0c1f919c49bea46f77634ecfb4f4bc3\",\n        \"size\": 536137595\n    },\n    \"HardBreakRoute_Town12_Route22699_Weather0.tar.gz\": {\n        \"sha256\": \"56317f8263ef4d335c70fba0d20a988b5eb4ea08e29841ef3a69e74c8032b9c0\",\n        \"size\": 587585090\n    },\n    \"HardBreakRoute_Town12_Route22700_Weather1.tar.gz\": {\n        \"sha256\": \"438ee6827a97e99622a14a605d78131ba9c3b888f950fc04f492aaddbbc82170\",\n        \"size\": 659343847\n    },\n    \"HardBreakRoute_Town12_Route22701_Weather2.tar.gz\": {\n        \"sha256\": \"b0c12c01977f64ab5747b889673dfd5862c5fcb95ea863d4287b646b819a0090\",\n        \"size\": 662335626\n    },\n    \"HardBreakRoute_Town12_Route22703_Weather3.tar.gz\": {\n        \"sha256\": \"b61591d71fa5cf49daacfbd76b2975263f2ab11e4716a987f0399b29339fb65c\",\n        \"size\": 341105196\n    },\n    \"HardBreakRoute_Town12_Route22704_Weather5.tar.gz\": {\n        \"sha256\": \"51def0287f2a553deac3520c7eca4ff26187944ca03ad16a38c8f37ab3546fce\",\n        \"size\": 200089667\n    },\n    \"HardBreakRoute_Town12_Route22705_Weather6.tar.gz\": {\n        \"sha256\": \"0d252d027dad83e0f7f3f3298e06b3dad3825b354b4adf0ab56ccbc89c31f547\",\n        \"size\": 224786114\n    },\n    \"HardBreakRoute_Town12_Route22706_Weather7.tar.gz\": {\n        \"sha256\": \"737b5a5bb616c146102ecd141558e1f70cd12bb577b41f44058449a7fd605b9f\",\n        \"size\": 396462532\n    },\n    \"HardBreakRoute_Town12_Route22707_Weather8.tar.gz\": {\n        \"sha256\": \"861c4f97b1971e127669c1ab6ef5a5bb61a4dcfa218f955adb4ba738dc44bffc\",\n        \"size\": 222864624\n    },\n    \"HardBreakRoute_Town12_Route22708_Weather9.tar.gz\": {\n        \"sha256\": \"69967ecaf4cb9e3761de0abc85569321b37b40ad881691da6e6b5b0ec2adde33\",\n        \"size\": 164236190\n    },\n    \"HardBreakRoute_Town12_Route22709_Weather10.tar.gz\": {\n        \"sha256\": \"339e36b04ebef50b7882bbdd6807edf291ade6055930400ee45e26df52536bd4\",\n        \"size\": 503510039\n    },\n    \"HardBreakRoute_Town12_Route22710_Weather11.tar.gz\": {\n        \"sha256\": \"519c4d81550dd1ab87363ab5632839eb54becf12d8cce4cad4578667f7ce4fdb\",\n        \"size\": 319376839\n    },\n    \"HardBreakRoute_Town12_Route22711_Weather12.tar.gz\": {\n        \"sha256\": \"c88eaf162c70dcbf16769b449ecac98dd9b05ffd9d93f859895c9128e246f848\",\n        \"size\": 406638089\n    },\n    \"HardBreakRoute_Town12_Route22712_Weather13.tar.gz\": {\n        \"sha256\": \"961f858e692dc2b513c26bbb06834c2cb139e4c9049ef1ac36b941924abb7ae3\",\n        \"size\": 769829145\n    },\n    \"HardBreakRoute_Town12_Route22713_Weather14.tar.gz\": {\n        \"sha256\": \"05d01b65cd11d4199ab4391d5ac5feea1efc0b0d02976ac88898be68de61b388\",\n        \"size\": 179184573\n    },\n    \"HardBreakRoute_Town12_Route22714_Weather15.tar.gz\": {\n        \"sha256\": \"9568d815c98fcda1584710c7cc067ecd0704552667ecc7c6712eb19d87bf1481\",\n        \"size\": 421283539\n    },\n    \"HardBreakRoute_Town12_Route22715_Weather8.tar.gz\": {\n        \"sha256\": \"706c7da192f21d1efaba2597379e013f4b6b5bbe13c0577e84dd99212e52f598\",\n        \"size\": 468377540\n    },\n    \"HardBreakRoute_Town12_Route22716_Weather9.tar.gz\": {\n        \"sha256\": \"c82ab876fd4200a3fb4fa1271ca79b8b5e1e5d82c01b81bf81f522f74d6e7c6a\",\n        \"size\": 312330802\n    },\n    \"HardBreakRoute_Town12_Route22717_Weather18.tar.gz\": {\n        \"sha256\": \"8c9037ea3fc60c4c40e09e1c12b7b60412b7e9a8606a696382b59ea7e2621074\",\n        \"size\": 337114319\n    },\n    \"HardBreakRoute_Town12_Route22718_Weather19.tar.gz\": {\n        \"sha256\": \"1a3c4ee3c5c1956fdfbfb259db49036f1d168e6203dc37c5ad90fbf355e54fa9\",\n        \"size\": 194391691\n    },\n    \"HardBreakRoute_Town12_Route22719_Weather20.tar.gz\": {\n        \"sha256\": \"ece46c2bae10f951e25c49717eaad84dc317f21bdf851b66563aa8d59635657b\",\n        \"size\": 288328245\n    },\n    \"HardBreakRoute_Town12_Route22720_Weather21.tar.gz\": {\n        \"sha256\": \"ed720c91c9810752021bb466127e5de728295036232e30aba223c07863ba807d\",\n        \"size\": 470798516\n    },\n    \"HardBreakRoute_Town12_Route22721_Weather22.tar.gz\": {\n        \"sha256\": \"5d5365082e152238eee731b68a7cdd5f99b711bfbbb1b40e313f1efe46339fd2\",\n        \"size\": 198785378\n    },\n    \"HardBreakRoute_Town12_Route22722_Weather23.tar.gz\": {\n        \"sha256\": \"4e2e28d4ef91d810e4bbb6766ba94993a36452950f7125aafc79dd645e0d4cd3\",\n        \"size\": 398694477\n    },\n    \"HardBreakRoute_Town12_Route22723_Weather23.tar.gz\": {\n        \"sha256\": \"5f28d12f63dca10f93633c211d2986b9f45c573fb9f439d3da252871ebc2a2d1\",\n        \"size\": 329828342\n    },\n    \"HardBreakRoute_Town12_Route22724_Weather25.tar.gz\": {\n        \"sha256\": \"e5c4de11f4055b80b37dd0c875fd4738ebb18f291834058910cf0433e2b101d6\",\n        \"size\": 382342789\n    },\n    \"HardBreakRoute_Town12_Route22725_Weather0.tar.gz\": {\n        \"sha256\": \"516b118dfecf47809bb326642cc1a2509ead506655c91b6999df521d6ec82d23\",\n        \"size\": 303729382\n    },\n    \"HardBreakRoute_Town12_Route22726_Weather1.tar.gz\": {\n        \"sha256\": \"9f5a6770829136f4d96300ccd1c81c011773e3c05a8cf419a2c0ea978974e99f\",\n        \"size\": 785709788\n    },\n    \"HardBreakRoute_Town12_Route22727_Weather2.tar.gz\": {\n        \"sha256\": \"d6d78d38cd9753434c63c75f9da600d4204e840f74053f97dc7ec02af7f53794\",\n        \"size\": 200449100\n    },\n    \"HardBreakRoute_Town12_Route22728_Weather3.tar.gz\": {\n        \"sha256\": \"cc917c4e907e5d8482af6a211f0971941fe4bb651c572598633584b23a5b1852\",\n        \"size\": 180378641\n    },\n    \"HardBreakRoute_Town12_Route22731_Weather6.tar.gz\": {\n        \"sha256\": \"6a3d22697ec10336a8c973c1a1fe7204a0de45e4d68ffc1309d622b48618a220\",\n        \"size\": 504129675\n    },\n    \"HardBreakRoute_Town12_Route22732_Weather7.tar.gz\": {\n        \"sha256\": \"541e76abd8865b81657ba58a7d55abb357d9acc341612f92ca8d6ffb52b610c4\",\n        \"size\": 611788136\n    },\n    \"HardBreakRoute_Town12_Route22733_Weather8.tar.gz\": {\n        \"sha256\": \"392a7c5479a1c39b8d5a76d1c22007b6c5cf08b86fd82fd6ba92ff57d4640943\",\n        \"size\": 533660240\n    },\n    \"HardBreakRoute_Town12_Route22735_Weather10.tar.gz\": {\n        \"sha256\": \"e4f41b48d2d9507c97f04f58bf495d5dab6871f83f5648f6143427139f381b7a\",\n        \"size\": 442992930\n    },\n    \"HardBreakRoute_Town12_Route22736_Weather11.tar.gz\": {\n        \"sha256\": \"34369a698124eb149cd685ba68554e5cbc50fc68c020c3e0f55454c48c363332\",\n        \"size\": 482381814\n    },\n    \"HardBreakRoute_Town12_Route22737_Weather12.tar.gz\": {\n        \"sha256\": \"46a02601a6fd88123b1a1d95456a182b23fc5b5dde941d5fb8f4356d98621e11\",\n        \"size\": 461087036\n    },\n    \"HardBreakRoute_Town12_Route22738_Weather13.tar.gz\": {\n        \"sha256\": \"019d551f39b8fbd0afa05e4d52a3579487977d2ca5b3f0ff65c98b7c22122db6\",\n        \"size\": 410207573\n    },\n    \"HardBreakRoute_Town12_Route22739_Weather14.tar.gz\": {\n        \"sha256\": \"482aae7434512dfcf99a13f67978b8fb013b6d1b4ad6d84ccf000097ac4b1605\",\n        \"size\": 218914519\n    },\n    \"HardBreakRoute_Town12_Route22740_Weather15.tar.gz\": {\n        \"sha256\": \"fc021c97496a142c56d9356f3ce82220e43fbfd7ac2456fc54a057d8a96f0865\",\n        \"size\": 539776645\n    },\n    \"HardBreakRoute_Town12_Route22741_Weather8.tar.gz\": {\n        \"sha256\": \"d23cac6f9ad2b45c79b483ddf3af79a5532a5c7af7a3507cb104b85c61f23ef5\",\n        \"size\": 481308840\n    },\n    \"HardBreakRoute_Town12_Route22742_Weather9.tar.gz\": {\n        \"sha256\": \"68cb0e071df7dccadf8f30c568818514ec55b02cfebc0b97590df7ac70d4babe\",\n        \"size\": 538401199\n    },\n    \"HardBreakRoute_Town12_Route22743_Weather18.tar.gz\": {\n        \"sha256\": \"d5a5dcc1046a3df5a70ad95c618eb608dfa059e45986f66d2f6e45fc0a5f7088\",\n        \"size\": 552299105\n    },\n    \"HardBreakRoute_Town12_Route22744_Weather19.tar.gz\": {\n        \"sha256\": \"b516c65dea6223eef73c2bd5640251a7516c121d861602c875e84e7edaff711d\",\n        \"size\": 494154227\n    },\n    \"HardBreakRoute_Town12_Route22747_Weather22.tar.gz\": {\n        \"sha256\": \"6310d1e2206dd6f66dd9d34bd9f8d4f697c4eb043ef4a4e4244931bc276ba9ee\",\n        \"size\": 483079859\n    },\n    \"HardBreakRoute_Town12_Route22750_Weather25.tar.gz\": {\n        \"sha256\": \"a9f7e1f02f1a24b460b992ce386816e69804d905bae329867368fafabd0cba37\",\n        \"size\": 447796617\n    },\n    \"HardBreakRoute_Town12_Route22751_Weather0.tar.gz\": {\n        \"sha256\": \"9589b7d40fa0f7c8ee47ce252a4dcb58422d00f72a1ae6d247c065c87c2aed18\",\n        \"size\": 530373360\n    },\n    \"HardBreakRoute_Town12_Route22753_Weather2.tar.gz\": {\n        \"sha256\": \"2e7c13159ecdecfb13f44fed69e23d7c5333cdec19379a326a70b218710fb645\",\n        \"size\": 560715491\n    },\n    \"HardBreakRoute_Town12_Route22754_Weather3.tar.gz\": {\n        \"sha256\": \"bcb6cd6100540c38dde6dcd99c766c947c2f4faa634bd7fb6e834c6ff547b2e1\",\n        \"size\": 483204703\n    },\n    \"HardBreakRoute_Town12_Route22757_Weather6.tar.gz\": {\n        \"sha256\": \"5999da82bdf6f63ecc59eef802d18470ce4d7c0dedcda22c5357926888bf862f\",\n        \"size\": 580972192\n    },\n    \"HardBreakRoute_Town12_Route22758_Weather7.tar.gz\": {\n        \"sha256\": \"7ff17d3105162f67e448b666200977bf7daba9759ad72557d8aff1d9ce3955f1\",\n        \"size\": 630399902\n    },\n    \"HardBreakRoute_Town12_Route22759_Weather8.tar.gz\": {\n        \"sha256\": \"652b69d6d7f306072944b5a12241b587040389437789ea946860000d43585250\",\n        \"size\": 403889375\n    },\n    \"HardBreakRoute_Town12_Route22760_Weather9.tar.gz\": {\n        \"sha256\": \"d15bfb185fe402d69fd0db16205fc8c0cec76538144a993a96b1524861f2020c\",\n        \"size\": 549460142\n    },\n    \"HardBreakRoute_Town12_Route22764_Weather13.tar.gz\": {\n        \"sha256\": \"a355b987861e41236971a4da8eb3bdcff4fa33be7d1af6d6c2cf960c57d68e76\",\n        \"size\": 528332710\n    },\n    \"HardBreakRoute_Town12_Route22765_Weather14.tar.gz\": {\n        \"sha256\": \"c4fd8c8cb53474ba20a087c577d8328a83c6378f2066b69444e7135547ad8251\",\n        \"size\": 506352715\n    },\n    \"HardBreakRoute_Town12_Route22766_Weather15.tar.gz\": {\n        \"sha256\": \"6934c892c8cd658bd886c0012cbb9ea32d9fce1d2e996d7382eab5d5f6a595b2\",\n        \"size\": 386764156\n    },\n    \"HardBreakRoute_Town12_Route22768_Weather9.tar.gz\": {\n        \"sha256\": \"d1c77605edb626af3c6fda458cca3c898f4fc279dbe58999eecd55310eda8be7\",\n        \"size\": 202714898\n    },\n    \"HardBreakRoute_Town12_Route22769_Weather18.tar.gz\": {\n        \"sha256\": \"5fe23ae2a5cf96720f1a1ad079c54f96da8663917639c5ab68182b8d0c1b70d4\",\n        \"size\": 200217344\n    },\n    \"HardBreakRoute_Town12_Route22770_Weather19.tar.gz\": {\n        \"sha256\": \"c8f603080382cf70bcca01c95f4d01d82b74632de56d76e070211ecd004ad3f5\",\n        \"size\": 252602618\n    },\n    \"HardBreakRoute_Town12_Route22772_Weather21.tar.gz\": {\n        \"sha256\": \"dbd6c9274fcf4e8bdbdcdbc9b95b430b096579baee5873547e20cde1b1309c3e\",\n        \"size\": 239828338\n    },\n    \"HardBreakRoute_Town12_Route22774_Weather23.tar.gz\": {\n        \"sha256\": \"93f26e8dd673d40d9a5579b428886690a18ee008d2230be3886060b7eb4c1566\",\n        \"size\": 446325935\n    },\n    \"HardBreakRoute_Town12_Route22775_Weather23.tar.gz\": {\n        \"sha256\": \"e643be40697c52ff1527a8424a857897f4f0e74647117eabf28d5b9e3b25c19e\",\n        \"size\": 228754562\n    },\n    \"HardBreakRoute_Town12_Route22776_Weather25.tar.gz\": {\n        \"sha256\": \"4d6bb6d1d338b6efaa339c65eb56e0b72478fb169d2534f618e5a0b61b8a3dff\",\n        \"size\": 353634131\n    },\n    \"HardBreakRoute_Town12_Route22777_Weather0.tar.gz\": {\n        \"sha256\": \"5d3c8168db75a33d03f08c7f3d21122e79837502d13a8a5457fa95704d1fd60d\",\n        \"size\": 275229541\n    },\n    \"HardBreakRoute_Town12_Route22778_Weather1.tar.gz\": {\n        \"sha256\": \"9f0920fb2a872f430ef3c26582e635dd34f20bf57cc511cdcdd2de35da3d1ee7\",\n        \"size\": 684375660\n    },\n    \"HardBreakRoute_Town12_Route22779_Weather2.tar.gz\": {\n        \"sha256\": \"dd58ccef6b37b4f83ebacd3f9758949651775718e3b2f4919de58354f146da42\",\n        \"size\": 208646714\n    },\n    \"HardBreakRoute_Town12_Route22780_Weather3.tar.gz\": {\n        \"sha256\": \"74f8fbb0239071182e1024f3a84063a4f0f525569a24bc546988c8ef67a992ca\",\n        \"size\": 207338084\n    },\n    \"HardBreakRoute_Town12_Route22781_Weather3.tar.gz\": {\n        \"sha256\": \"77bbc0a1d562b26877adc22a6951972e997e5af99a83ffa44028d48e362dfcb0\",\n        \"size\": 210627123\n    },\n    \"HardBreakRoute_Town12_Route22782_Weather5.tar.gz\": {\n        \"sha256\": \"2cdfbf0e4e26dc4512e248825b453132e71620fafb43391c65bb0ba3be30b112\",\n        \"size\": 301812540\n    },\n    \"HardBreakRoute_Town12_Route22783_Weather6.tar.gz\": {\n        \"sha256\": \"02e7c608c12e23974376691795d91d1d7b092f666621f5ba9455db8593021bcc\",\n        \"size\": 679167315\n    },\n    \"HardBreakRoute_Town12_Route22784_Weather7.tar.gz\": {\n        \"sha256\": \"16fda098135f738c5e96b2543a22647030a85fb15f01c954699ac46fab2f8acc\",\n        \"size\": 581676143\n    },\n    \"HardBreakRoute_Town12_Route22785_Weather8.tar.gz\": {\n        \"sha256\": \"e876b3bf85a89b0f6d21f181bbd242c42a750e9b445d96193a5c6cdba2fe6dd8\",\n        \"size\": 210186790\n    },\n    \"HardBreakRoute_Town12_Route22786_Weather9.tar.gz\": {\n        \"sha256\": \"317c43c977c4576e7d9e3069773dc03e32ada7cbfa744f13f9951ac6a16a2f3b\",\n        \"size\": 286332366\n    },\n    \"HardBreakRoute_Town12_Route22787_Weather10.tar.gz\": {\n        \"sha256\": \"ae40dcc8dec0fa63621d4d5d5e494373953e89379f1708df49d257e870089661\",\n        \"size\": 885482426\n    },\n    \"HardBreakRoute_Town12_Route22788_Weather11.tar.gz\": {\n        \"sha256\": \"ccd5983a420bea3ed94369a0c8658907f03e48a59e081f16952776b65e7b62ab\",\n        \"size\": 152136502\n    },\n    \"HardBreakRoute_Town12_Route22789_Weather12.tar.gz\": {\n        \"sha256\": \"8891818435565ef15b546922f773e7201d7ffa3ce7044e9f5833c132b1be4077\",\n        \"size\": 120981907\n    },\n    \"HardBreakRoute_Town12_Route22790_Weather13.tar.gz\": {\n        \"sha256\": \"e420484199ea5555d6c7cca1325edc4725f779f4621e29cb17b352f36b5503ae\",\n        \"size\": 380711912\n    },\n    \"HardBreakRoute_Town12_Route22791_Weather14.tar.gz\": {\n        \"sha256\": \"dcba998ffe273816893068423faf879aed765e7dcb7f663712fb7fc7d5c9247d\",\n        \"size\": 526887431\n    },\n    \"HardBreakRoute_Town12_Route22792_Weather15.tar.gz\": {\n        \"sha256\": \"c6e74811f1fe9c360df521e34bf18783268d5100b689ad1f05f60038e259cb31\",\n        \"size\": 634036365\n    },\n    \"HardBreakRoute_Town12_Route22793_Weather8.tar.gz\": {\n        \"sha256\": \"7ae5a8f91c5f6c90eab32054291a60db0c7e60c8e9461a7d8dc10753f1d499b6\",\n        \"size\": 635063624\n    },\n    \"HardBreakRoute_Town12_Route22794_Weather9.tar.gz\": {\n        \"sha256\": \"12535e1c1809c9001c4942e17deaa60a0ee661d7b620b9d0188bd2ddb0fc0a43\",\n        \"size\": 176984597\n    },\n    \"HardBreakRoute_Town12_Route22795_Weather18.tar.gz\": {\n        \"sha256\": \"8269856da6f8b85be8de0a4b2257182f09892cd5528dcabf94b367c840869edf\",\n        \"size\": 392392810\n    },\n    \"HardBreakRoute_Town12_Route22798_Weather21.tar.gz\": {\n        \"sha256\": \"48f7d31f35302a414ac1fd090b3448aeade462291a16f720520eb30e1fd862bc\",\n        \"size\": 178044940\n    },\n    \"HardBreakRoute_Town12_Route22799_Weather22.tar.gz\": {\n        \"sha256\": \"cce1d9a521a3554b2409a0a061ae46a6412bf95a8ef7b63f0ca87969e397dc82\",\n        \"size\": 203494648\n    },\n    \"HardBreakRoute_Town12_Route22800_Weather23.tar.gz\": {\n        \"sha256\": \"4a52e747b05d99c379036fd3790596223877094dd5bcff21a23b34f0087739db\",\n        \"size\": 175220869\n    },\n    \"HardBreakRoute_Town12_Route22801_Weather23.tar.gz\": {\n        \"sha256\": \"f0f081e314ced0286166bbfe012c5dfc62239b2b63797d8e1bd44de333fde6f9\",\n        \"size\": 219150091\n    },\n    \"HardBreakRoute_Town12_Route22802_Weather25.tar.gz\": {\n        \"sha256\": \"025294a1aa6c8fbfd56e53a8cba6e6a500e3ae52ad186e96ce8ed83198af005f\",\n        \"size\": 197067766\n    },\n    \"HardBreakRoute_Town12_Route22803_Weather0.tar.gz\": {\n        \"sha256\": \"4d62c064ca2c9b9c1b5a3e601f1d3c6b67af24d3d70ccb0bc7bf503c3e3b9ec4\",\n        \"size\": 422754517\n    },\n    \"HardBreakRoute_Town12_Route22804_Weather1.tar.gz\": {\n        \"sha256\": \"6d3b6d302279c3508f062171e983cfc8e62d0d29e209b55f023d3cf2ec905b0b\",\n        \"size\": 561960989\n    },\n    \"HardBreakRoute_Town12_Route22805_Weather2.tar.gz\": {\n        \"sha256\": \"ae7183a49bf79c214cb5113b99cd948840289d8604bea956e6b8663784662cdc\",\n        \"size\": 539854014\n    },\n    \"HardBreakRoute_Town12_Route22806_Weather3.tar.gz\": {\n        \"sha256\": \"c9a55b0c5fe97659dd19681ed35794e2f416e0149d05aba0daed8747115f9e8b\",\n        \"size\": 604254324\n    },\n    \"HardBreakRoute_Town12_Route22807_Weather3.tar.gz\": {\n        \"sha256\": \"06d04b6ef2d703d1dff50a69bc57c1c941ac29e87cea16ba090c27e6131bbe3a\",\n        \"size\": 668156633\n    },\n    \"HardBreakRoute_Town12_Route22808_Weather5.tar.gz\": {\n        \"sha256\": \"ff45c51e160f0987044bea1093d998fa4f218e5920fca6a1cc89d550c2e1c4c4\",\n        \"size\": 690465213\n    },\n    \"HardBreakRoute_Town12_Route22809_Weather6.tar.gz\": {\n        \"sha256\": \"e012761d4331fd333637af0dbbad5ee7f6cde5efea28ffe0ec75c8d1b98b51c6\",\n        \"size\": 587384785\n    },\n    \"HardBreakRoute_Town12_Route22810_Weather7.tar.gz\": {\n        \"sha256\": \"7c6f1c023aaca60ddd1d0d3d284e63ae192de7b48441a9a749c33c09e6ceb8a9\",\n        \"size\": 548386770\n    },\n    \"HardBreakRoute_Town12_Route22811_Weather8.tar.gz\": {\n        \"sha256\": \"af39fd915fe508f00d2b137ee1640be26e762c5db827c11d835645dba85bd9e6\",\n        \"size\": 458146652\n    },\n    \"HardBreakRoute_Town12_Route22813_Weather10.tar.gz\": {\n        \"sha256\": \"5a9a8115c12e9c200e5ccd490639b16718c2c41293208496a16e857627c186f1\",\n        \"size\": 447189994\n    },\n    \"HardBreakRoute_Town12_Route22814_Weather11.tar.gz\": {\n        \"sha256\": \"e80a6d15f7ad4320df6373687e488b94048b5a6ccb6459644597467a70d26d2b\",\n        \"size\": 371590995\n    },\n    \"HardBreakRoute_Town12_Route22815_Weather12.tar.gz\": {\n        \"sha256\": \"e5f70a272bcf4575d6bb8cbdcb58d22d11b58130779efcd92f381fdc4a988edd\",\n        \"size\": 206878295\n    },\n    \"HardBreakRoute_Town12_Route22816_Weather13.tar.gz\": {\n        \"sha256\": \"9d1a70267eb6a92442af4f3604861bf34ce13503191fc397fced9dd820eec932\",\n        \"size\": 576664515\n    },\n    \"HardBreakRoute_Town12_Route22817_Weather14.tar.gz\": {\n        \"sha256\": \"dc37ee39ec77b680974c393a4a0340ba38a313683412c10601ab7cda45e8eb03\",\n        \"size\": 616557447\n    },\n    \"HardBreakRoute_Town12_Route22818_Weather15.tar.gz\": {\n        \"sha256\": \"3feed6fdd933ca9218293e2b1e8755295526624712baa50bba75de30f74383e6\",\n        \"size\": 509772737\n    },\n    \"HardBreakRoute_Town12_Route22819_Weather8.tar.gz\": {\n        \"sha256\": \"4953188f2539535086087f9132b8b5e4fddbbe8fc1d18b6a9ed48dd20d916b35\",\n        \"size\": 602571079\n    },\n    \"HardBreakRoute_Town12_Route22820_Weather9.tar.gz\": {\n        \"sha256\": \"1c1306d20634a11a30a5367a4be8b57bf261ed88e2f8bd3a1f84f259a835d70a\",\n        \"size\": 645584066\n    },\n    \"HardBreakRoute_Town12_Route22821_Weather18.tar.gz\": {\n        \"sha256\": \"d5e347afbdcd005d74e22d0f8d8fa7e9920ad68a41b3b024c74bc14176c82c01\",\n        \"size\": 535781946\n    },\n    \"HardBreakRoute_Town12_Route22822_Weather19.tar.gz\": {\n        \"sha256\": \"6db7573f47acb9b369347d0d37d7e0ce3ae33a285e82d723d9bec68c5e86e6f7\",\n        \"size\": 351655593\n    },\n    \"HardBreakRoute_Town12_Route22823_Weather20.tar.gz\": {\n        \"sha256\": \"4cf698d89f0b4da61abfce1fb0b74211f1b5c1ae3f02f7c6c91a028e55f5c6f7\",\n        \"size\": 243810761\n    },\n    \"HardBreakRoute_Town12_Route22824_Weather21.tar.gz\": {\n        \"sha256\": \"250b15924d49a051e65474dd90ac011b32c20f4ea72996dcc2484707736b1a11\",\n        \"size\": 228728286\n    },\n    \"HardBreakRoute_Town12_Route22825_Weather22.tar.gz\": {\n        \"sha256\": \"cb312f892080241d55cddb1c57adb2bec441fc1c01ed0158465e74ab5270085f\",\n        \"size\": 215307685\n    },\n    \"HardBreakRoute_Town12_Route22826_Weather23.tar.gz\": {\n        \"sha256\": \"a24a26365229e1fa44d8cc83ec0af9a82bd0662b6d77d61d23eaafd5188dceb2\",\n        \"size\": 430481826\n    },\n    \"HardBreakRoute_Town12_Route22828_Weather25.tar.gz\": {\n        \"sha256\": \"7c3575d443f23da1953898757688c72398203a17da111e3551d05d65736b2262\",\n        \"size\": 446121541\n    },\n    \"HardBreakRoute_Town12_Route22829_Weather0.tar.gz\": {\n        \"sha256\": \"d1071f678ca36ecc1f96cf1089397ba5e2271923876d8aeeaa4bb089c4f354d4\",\n        \"size\": 461707562\n    },\n    \"HardBreakRoute_Town12_Route22830_Weather1.tar.gz\": {\n        \"sha256\": \"40a37e6c34ebdc06b70636c9108c11d19f455b5cb3a30b510f6c38a143f66f96\",\n        \"size\": 530324024\n    },\n    \"HardBreakRoute_Town12_Route22831_Weather2.tar.gz\": {\n        \"sha256\": \"d03342200f391201f8a337329fa6f99a801f775aee5b4a44e3ab31258e83fbf7\",\n        \"size\": 485338235\n    },\n    \"HardBreakRoute_Town12_Route22833_Weather3.tar.gz\": {\n        \"sha256\": \"9281d93fbca72c58bca59aadc7c55f03c92e4d6193071a39c7d72fdadffa0168\",\n        \"size\": 374866596\n    },\n    \"HardBreakRoute_Town12_Route22834_Weather5.tar.gz\": {\n        \"sha256\": \"a5c3860f71f0051107f5c39278dff82075229020f44f097b43622bc14921eb53\",\n        \"size\": 677310543\n    },\n    \"HardBreakRoute_Town12_Route22837_Weather8.tar.gz\": {\n        \"sha256\": \"58d9023feecde11e0ce7f01d1f26f710dae6e1f4a7c7d78f638669a9c7281020\",\n        \"size\": 542603159\n    },\n    \"HardBreakRoute_Town12_Route22838_Weather9.tar.gz\": {\n        \"sha256\": \"a8dd5be0dc9bf800195bb247946a88f95b0f59ed3951b04c1bab80e46ee626a0\",\n        \"size\": 624067457\n    },\n    \"HardBreakRoute_Town12_Route22839_Weather10.tar.gz\": {\n        \"sha256\": \"e426e9084d72bdc48a5b1487db0563a14e92eb26dc29a7742dcb54fbd22d1206\",\n        \"size\": 676760878\n    },\n    \"HardBreakRoute_Town12_Route22840_Weather11.tar.gz\": {\n        \"sha256\": \"667521fcb20b57e929b3f1c8b7bf9524f1ce4467c839d983de8ab9654888db16\",\n        \"size\": 558665356\n    },\n    \"HardBreakRoute_Town12_Route22841_Weather12.tar.gz\": {\n        \"sha256\": \"03c2f91df91c4d477b883214bcff48cee039dbbeb42efe815a9ce52851205aad\",\n        \"size\": 598621459\n    },\n    \"HardBreakRoute_Town12_Route22842_Weather13.tar.gz\": {\n        \"sha256\": \"a7b993a62e873baa727f8d3070a15d1cc68dee9f12a0da388918c1163f4efad4\",\n        \"size\": 487225588\n    },\n    \"HardBreakRoute_Town12_Route22843_Weather14.tar.gz\": {\n        \"sha256\": \"035dee7e1f9e1f74bf0f90ceb7e9d7637b82d5c8d8c77ab1e4061716c1ed7503\",\n        \"size\": 586802765\n    },\n    \"HardBreakRoute_Town12_Route22844_Weather15.tar.gz\": {\n        \"sha256\": \"291ff9417899757a9ac26e934bb3e259d30205468f050013b5b94c8d99120bff\",\n        \"size\": 584136758\n    },\n    \"HardBreakRoute_Town12_Route22845_Weather8.tar.gz\": {\n        \"sha256\": \"64a6c72dc68f0f0743797af808dcae4d55dc842a19fc24d2a4d5c36b7ac44765\",\n        \"size\": 237980213\n    },\n    \"HardBreakRoute_Town12_Route22846_Weather9.tar.gz\": {\n        \"sha256\": \"f7b4195cb7c4f50ca5c7d61088da2fc5039516dbdb096c824097b0f0ab907014\",\n        \"size\": 162364924\n    },\n    \"HardBreakRoute_Town12_Route22847_Weather18.tar.gz\": {\n        \"sha256\": \"50bc8142b32b6274056e9858925d67e97d92dbcad0b70484f09d2fcd1d6727dc\",\n        \"size\": 230956674\n    },\n    \"HardBreakRoute_Town12_Route22848_Weather19.tar.gz\": {\n        \"sha256\": \"b1443df4cded4a303f9ce5329fe588862ba27ba2d61887bc1bcc60c52e0534f0\",\n        \"size\": 241765055\n    },\n    \"HardBreakRoute_Town12_Route22849_Weather20.tar.gz\": {\n        \"sha256\": \"489f6bd21baa9415a7dfc0dd24ebfd877d680c29bfce285f7344a1bd3edaafb1\",\n        \"size\": 202470796\n    },\n    \"HardBreakRoute_Town12_Route22850_Weather21.tar.gz\": {\n        \"sha256\": \"e1f0958aaa4867197ddaa89581055d4958690ed68174b3e902063b9fe5269b4b\",\n        \"size\": 390407048\n    },\n    \"HardBreakRoute_Town12_Route22851_Weather22.tar.gz\": {\n        \"sha256\": \"59d86bb9b7a7a608c93280bb68e9cc0f2f9dfa4ea0d761bd3416f6e6f510eef2\",\n        \"size\": 641375231\n    },\n    \"HardBreakRoute_Town12_Route22852_Weather23.tar.gz\": {\n        \"sha256\": \"487d1479f83a3f946e42b4b189e22c2be29d5a505bc5d5ff8f98a38731f879cd\",\n        \"size\": 635585070\n    },\n    \"HardBreakRoute_Town12_Route22853_Weather23.tar.gz\": {\n        \"sha256\": \"ec1705a26678da0d6895ea8aa4a814ff2e9b4251cdd41da01ad39365a79e9e48\",\n        \"size\": 592162104\n    },\n    \"HardBreakRoute_Town12_Route22854_Weather25.tar.gz\": {\n        \"sha256\": \"7aef76be4430a765df7db6d720b1f42c330c084f8c790460a72b2f18eb0d8c2b\",\n        \"size\": 535430706\n    },\n    \"HardBreakRoute_Town12_Route22855_Weather0.tar.gz\": {\n        \"sha256\": \"191c3e6474fbd9bd1cda9351fae6bcbe549bcfadd7fdf7ce0c6ddcc5686df2e8\",\n        \"size\": 584236779\n    },\n    \"HardBreakRoute_Town12_Route22857_Weather2.tar.gz\": {\n        \"sha256\": \"7ec2db90def5df30facc4e52d43d8e29ade15ad6ee95e572d9f9be6879d48294\",\n        \"size\": 602776581\n    },\n    \"HardBreakRoute_Town12_Route22858_Weather3.tar.gz\": {\n        \"sha256\": \"40776979e26ca1b915de54b1e206bd653f9b9eeed1da92914dc80b5e581f627a\",\n        \"size\": 470715132\n    },\n    \"HardBreakRoute_Town12_Route22859_Weather3.tar.gz\": {\n        \"sha256\": \"01b895403e7817a0d38926674ffe5885f93df08de221c99ebfbc3e88cb903d3d\",\n        \"size\": 521474126\n    },\n    \"HardBreakRoute_Town12_Route22860_Weather5.tar.gz\": {\n        \"sha256\": \"17198fd4bc9c8e5d013c3872e7d616bb3419ab2f2b9a79f7bd492c1d03ccd2e3\",\n        \"size\": 434189961\n    },\n    \"HardBreakRoute_Town12_Route22861_Weather6.tar.gz\": {\n        \"sha256\": \"47d6c2f233ae700813e0e988605f3e97ba95695d7420c5d981014acf09a4077e\",\n        \"size\": 214732756\n    },\n    \"HardBreakRoute_Town12_Route22862_Weather7.tar.gz\": {\n        \"sha256\": \"29c4caabc36181db6a841ec26400d1a4c1b4b0b43be40a7b6b0e677126468ace\",\n        \"size\": 165952680\n    },\n    \"HardBreakRoute_Town12_Route22863_Weather8.tar.gz\": {\n        \"sha256\": \"a2c5b6f2c4e1a2ec4d7b3ac185ac89aeae2a7502219955a9195583b9507b1f24\",\n        \"size\": 232676468\n    },\n    \"HardBreakRoute_Town12_Route22864_Weather9.tar.gz\": {\n        \"sha256\": \"c87e2e6a013d5c364db7b344d301b8e82118e2ef467f0c20e7332516dbe1b136\",\n        \"size\": 439261827\n    },\n    \"HardBreakRoute_Town12_Route22867_Weather12.tar.gz\": {\n        \"sha256\": \"5983c9d6770dc3e5d2cb86e52b2c6acbdbdb1de258c91cf7833f664b3ea6b519\",\n        \"size\": 386928495\n    },\n    \"HardBreakRoute_Town12_Route22868_Weather13.tar.gz\": {\n        \"sha256\": \"d44280dd2fa3686f6d180ef5dc8996c95175ae4630f5347f385dcc9829585c42\",\n        \"size\": 540845725\n    },\n    \"HardBreakRoute_Town12_Route22869_Weather14.tar.gz\": {\n        \"sha256\": \"d920c42c681af77ffddd8afdc4d8c2319c16afc81105780d2b5a2765f26cde52\",\n        \"size\": 495525130\n    },\n    \"HardBreakRoute_Town12_Route22870_Weather15.tar.gz\": {\n        \"sha256\": \"af5defbc4a12da79b0fcaeda9c391581e1fcf810efc35a1b11a1cff3b4d847cc\",\n        \"size\": 573742434\n    },\n    \"HardBreakRoute_Town12_Route22871_Weather8.tar.gz\": {\n        \"sha256\": \"5f12a22bcb2c1547f946b8b2b59d127666cea96d06bbc3be0c824f4717c01a74\",\n        \"size\": 517148588\n    },\n    \"HardBreakRoute_Town12_Route22872_Weather9.tar.gz\": {\n        \"sha256\": \"ec27b15a2fbb344851b216a024a68966b2d31e0bd7ecd74f2a1d0eaf838fab96\",\n        \"size\": 558904275\n    },\n    \"HardBreakRoute_Town12_Route22873_Weather18.tar.gz\": {\n        \"sha256\": \"fd12f0a5b5023a650915a55c337d9a0921215d0c0b55e34c046fcee3989e32eb\",\n        \"size\": 514358174\n    },\n    \"HardBreakRoute_Town12_Route22874_Weather19.tar.gz\": {\n        \"sha256\": \"a97ca093f919adf05a5ec032c205e83882d935524cd5267b96dbacb835b68b18\",\n        \"size\": 426565019\n    },\n    \"HardBreakRoute_Town12_Route22875_Weather20.tar.gz\": {\n        \"sha256\": \"ef8f6e408fdc0c49b9e5eacd5c0e51d40a428db0539f1cb90ee65273c0dbe28f\",\n        \"size\": 543933794\n    },\n    \"HardBreakRoute_Town12_Route22876_Weather21.tar.gz\": {\n        \"sha256\": \"53d3d784c0b76ef582bade6050d8e7a13f4fda35a6f87e8f20ebc4ed2c03c5b5\",\n        \"size\": 482511991\n    },\n    \"HardBreakRoute_Town12_Route22877_Weather22.tar.gz\": {\n        \"sha256\": \"351c32dbe13486c062dc71bb55acaf547401f45ac69507c93cc94bdc00bfa555\",\n        \"size\": 559936263\n    },\n    \"HardBreakRoute_Town12_Route22879_Weather23.tar.gz\": {\n        \"sha256\": \"dfa11aab5823188ccca914e2e46c0c70aa7745dba8e6431db23c43163c72e95a\",\n        \"size\": 400211743\n    },\n    \"HardBreakRoute_Town12_Route22880_Weather25.tar.gz\": {\n        \"sha256\": \"5d8e727452c814c4c8020accabcff3576d179d41d1fecea841747f9c3eba016f\",\n        \"size\": 424312679\n    },\n    \"HardBreakRoute_Town12_Route22881_Weather0.tar.gz\": {\n        \"sha256\": \"d1a0b7fb4feaffc7b63d9c8c3b816ef20ff1ab9dcdb500975b86bcd56a826cbc\",\n        \"size\": 604685496\n    },\n    \"HardBreakRoute_Town12_Route22882_Weather1.tar.gz\": {\n        \"sha256\": \"f951c603a25ac4e046185fb028470f2e616cedbbb58962d9b35cc4fc2e3c1f11\",\n        \"size\": 579867921\n    },\n    \"HardBreakRoute_Town12_Route22883_Weather2.tar.gz\": {\n        \"sha256\": \"c06514d64f18475d88481d67574302946322b07d75e09f00a328f71d8490e021\",\n        \"size\": 461132067\n    },\n    \"HardBreakRoute_Town12_Route22884_Weather3.tar.gz\": {\n        \"sha256\": \"a34ee2ef2097f0bf0b3152c087896c88de74661cea6ca724be329c561ee83333\",\n        \"size\": 498290981\n    },\n    \"HardBreakRoute_Town12_Route22885_Weather3.tar.gz\": {\n        \"sha256\": \"d3d4b8fea69364cfacb5105571d2d864c0b6cb9a1536ed253c6e8a36b614b883\",\n        \"size\": 544638327\n    },\n    \"HardBreakRoute_Town12_Route22886_Weather5.tar.gz\": {\n        \"sha256\": \"6104b2ab9b2401f6f9521525dd6b3f41f050312f389619716337dcada40e6813\",\n        \"size\": 603282018\n    },\n    \"HardBreakRoute_Town12_Route22887_Weather6.tar.gz\": {\n        \"sha256\": \"d5a3de6ef06fd2a3dcb62cd22cfcaeaa4fc4b1029d07c8fbd316ec384bbceb45\",\n        \"size\": 593788969\n    },\n    \"HardBreakRoute_Town12_Route22888_Weather7.tar.gz\": {\n        \"sha256\": \"c9308c752dd6df231f3d8d706706a60080d8b29db28f1468bc69538d1f36c81c\",\n        \"size\": 660591532\n    },\n    \"HardBreakRoute_Town12_Route22889_Weather8.tar.gz\": {\n        \"sha256\": \"65d72919079ae4964b954cc5a4f1a1374d0e3e84e8c0053df2e0c9725ec72c25\",\n        \"size\": 422641263\n    },\n    \"HardBreakRoute_Town12_Route22890_Weather9.tar.gz\": {\n        \"sha256\": \"b3b3f02559bd4006755080f21089ec958b74f2dae1c61aa4d14b31b1fe9173d2\",\n        \"size\": 579894846\n    },\n    \"HardBreakRoute_Town12_Route22891_Weather10.tar.gz\": {\n        \"sha256\": \"8275e8269fd2a25af7c73c207cc8cfc28eea3a8680725a75a430e4f6fd921712\",\n        \"size\": 351219099\n    },\n    \"HardBreakRoute_Town12_Route22892_Weather11.tar.gz\": {\n        \"sha256\": \"0ca2d389f891454334188811f45ff55db99f2ae061e8054c53878c581e96b6da\",\n        \"size\": 303874260\n    },\n    \"HardBreakRoute_Town12_Route22893_Weather12.tar.gz\": {\n        \"sha256\": \"64dd88c7c008b07119924807d54f75e6f319f96c430ea67b18c3e39772285f6a\",\n        \"size\": 457294328\n    },\n    \"HardBreakRoute_Town12_Route22894_Weather13.tar.gz\": {\n        \"sha256\": \"f2b02608f008754dc69cc466d0fe29ec5ae679679b87f47bf0abe712fc585f14\",\n        \"size\": 559393998\n    },\n    \"HardBreakRoute_Town12_Route22895_Weather14.tar.gz\": {\n        \"sha256\": \"68a52b2ee8c855c1c99570fa430f1b43e5e48809eb9bd889197502256f765d28\",\n        \"size\": 528187005\n    },\n    \"HardBreakRoute_Town12_Route22899_Weather18.tar.gz\": {\n        \"sha256\": \"6d51efd8a24972952ba425e57af3376a7d81a35bc32f175e2349fb9a63a2536d\",\n        \"size\": 328690242\n    },\n    \"HardBreakRoute_Town12_Route22900_Weather19.tar.gz\": {\n        \"sha256\": \"991acd40b3679c8632be11e39d5112656f74567e5ccfed9993e8189aee0c65d9\",\n        \"size\": 499356840\n    },\n    \"HardBreakRoute_Town12_Route22901_Weather20.tar.gz\": {\n        \"sha256\": \"96edfc5c1aa597f5ea2521773703b273edcb3ceda40fefcc20cdffaca20777dd\",\n        \"size\": 553510262\n    },\n    \"HardBreakRoute_Town12_Route22902_Weather21.tar.gz\": {\n        \"sha256\": \"4cbfcadaba112cfbf05fbd9b7f62b6d340699983edb23d4ee5fe64fadc8056b9\",\n        \"size\": 530888675\n    },\n    \"HardBreakRoute_Town12_Route22903_Weather22.tar.gz\": {\n        \"sha256\": \"386401dd4106c4781709f07c6fef984bb1c483c59144f79e19de75c5290aea70\",\n        \"size\": 462317332\n    },\n    \"HardBreakRoute_Town12_Route22904_Weather23.tar.gz\": {\n        \"sha256\": \"2ccd5c572d2fb675dee01a04c1a5524d89758347e5ac9017b8bd3f3f64d4b58b\",\n        \"size\": 419696430\n    },\n    \"HardBreakRoute_Town12_Route22905_Weather23.tar.gz\": {\n        \"sha256\": \"8d9677a712d43c08a82cedddd5f6b078decd1e2e8fc7a64855b1f40ab6677890\",\n        \"size\": 552455852\n    },\n    \"HardBreakRoute_Town12_Route22907_Weather0.tar.gz\": {\n        \"sha256\": \"ef8f2606c266c67b7e2a8db29e56de3cefb4453e561191a179a920dc631c6daf\",\n        \"size\": 218373070\n    },\n    \"HardBreakRoute_Town12_Route22908_Weather1.tar.gz\": {\n        \"sha256\": \"3a55d2dfe6cf38045086d84ecfedb0f961068bf054ecc1f85fb1c9e3447c6093\",\n        \"size\": 287138111\n    },\n    \"HardBreakRoute_Town12_Route22909_Weather2.tar.gz\": {\n        \"sha256\": \"c3a8313349c32400aa6db50123d8ad3d8a88046f5e9ec1a30931f9c958f1b09c\",\n        \"size\": 687991314\n    },\n    \"HardBreakRoute_Town12_Route22910_Weather3.tar.gz\": {\n        \"sha256\": \"97fa58d59ea6c8348eac9ff6dfba1fb2e523ca4110ead15f87ebc24f02127a18\",\n        \"size\": 677109519\n    },\n    \"HardBreakRoute_Town12_Route22911_Weather3.tar.gz\": {\n        \"sha256\": \"2d69da8a4a0db3da9a65b43d4ddf80ce17f75e9c31d515b9452fd863ddee018f\",\n        \"size\": 539384103\n    },\n    \"HardBreakRoute_Town12_Route22912_Weather5.tar.gz\": {\n        \"sha256\": \"752c946336fb535ec35be300423b9fb88a3a3607e1092ab43f4ff927f0387980\",\n        \"size\": 772439378\n    },\n    \"HardBreakRoute_Town12_Route22913_Weather6.tar.gz\": {\n        \"sha256\": \"3ce601169473a5bcaafb1ed9e75dbd95a91da7e5f5911aad041b5727d624cb84\",\n        \"size\": 198005316\n    },\n    \"HardBreakRoute_Town12_Route22914_Weather7.tar.gz\": {\n        \"sha256\": \"ee69c1c037d9b143fc1c31746e1a3eb473e5399d0381346b028f82b894264927\",\n        \"size\": 341497427\n    },\n    \"HardBreakRoute_Town12_Route22915_Weather8.tar.gz\": {\n        \"sha256\": \"f245ec431db01823476cfdb0c29bd16926d50cab5e0a77151d8a747285b57c92\",\n        \"size\": 273525061\n    },\n    \"HardBreakRoute_Town12_Route22916_Weather9.tar.gz\": {\n        \"sha256\": \"95e9d5a680f1cdfe7afbf941b20e7f16d368d1364a11e04e011af01f07c3def4\",\n        \"size\": 180700473\n    },\n    \"HardBreakRoute_Town12_Route22917_Weather10.tar.gz\": {\n        \"sha256\": \"2a84cc802617b24d5bc1322105ed76e95d2d5b9e8b541302b0bc498e666678b4\",\n        \"size\": 540044779\n    },\n    \"HardBreakRoute_Town12_Route22922_Weather15.tar.gz\": {\n        \"sha256\": \"717a95f8c2bbc3c4c82086824601e71d4e541cfb934af97a37218e90a14681ae\",\n        \"size\": 582140266\n    },\n    \"HardBreakRoute_Town12_Route22925_Weather18.tar.gz\": {\n        \"sha256\": \"a3c525d55d1e58da7acdc91e60c54028694177ef2c7a71b0bea8b8be843d703d\",\n        \"size\": 382783461\n    },\n    \"HardBreakRoute_Town12_Route22930_Weather23.tar.gz\": {\n        \"sha256\": \"1c982cc0a14f21034dbdea3e2d170e94563121c8894e6a5ce73914ec52c1f645\",\n        \"size\": 541883429\n    },\n    \"HardBreakRoute_Town12_Route22931_Weather23.tar.gz\": {\n        \"sha256\": \"aff3319111c000fa36e94ee1826c81639d5440f0c6584b160496973743b75aee\",\n        \"size\": 346098873\n    },\n    \"HardBreakRoute_Town12_Route22932_Weather25.tar.gz\": {\n        \"sha256\": \"23d49e4f675c7786d70616c919bec5a6d9712b04592ba5a1d515d6ef31a601ee\",\n        \"size\": 257271252\n    },\n    \"HardBreakRoute_Town12_Route22933_Weather0.tar.gz\": {\n        \"sha256\": \"2f9ab57bb21f86e810b2adae7037dfebd547575ad71bbe6f7558b0ca897caa7e\",\n        \"size\": 655538948\n    },\n    \"HardBreakRoute_Town12_Route22934_Weather1.tar.gz\": {\n        \"sha256\": \"12a2fa0e96a1ca3840b23a927a86c8ff983b0d6a73cd9d48423234a87c8fe63b\",\n        \"size\": 228307688\n    },\n    \"HardBreakRoute_Town12_Route22937_Weather3.tar.gz\": {\n        \"sha256\": \"b03d5ef55739c48d4b6595c916800d7bfb7bd37e91b5ff265625e3e744890a18\",\n        \"size\": 388249638\n    },\n    \"HardBreakRoute_Town12_Route22938_Weather5.tar.gz\": {\n        \"sha256\": \"6a64b73aa8fe74855e3099086345a2a4783c60be3e153946bb4d3a63cb5e7615\",\n        \"size\": 478670673\n    },\n    \"HardBreakRoute_Town12_Route22939_Weather6.tar.gz\": {\n        \"sha256\": \"78add96ce9ef8fe9c8a3574749acd5390f26739ff7888e96df2d56105e888940\",\n        \"size\": 544275191\n    },\n    \"HardBreakRoute_Town12_Route22941_Weather8.tar.gz\": {\n        \"sha256\": \"2d4e63008d65c528c34b800addc521de1a438b5e2062d690fa6817ba9d46e35c\",\n        \"size\": 475520714\n    },\n    \"HardBreakRoute_Town12_Route22942_Weather9.tar.gz\": {\n        \"sha256\": \"cf2d5f1cffbd18f3c9cab9ab1838d3797bdb67ff85bd868c0b99638bc3259d1c\",\n        \"size\": 421126796\n    },\n    \"HardBreakRoute_Town12_Route22943_Weather10.tar.gz\": {\n        \"sha256\": \"d1e8c2ab22b4d2b176e011cfab6bd69d50329f5679e7cd644df85ba98df07e65\",\n        \"size\": 409425111\n    },\n    \"HardBreakRoute_Town12_Route22944_Weather11.tar.gz\": {\n        \"sha256\": \"87ca9e616849c62a416de97b13528310aa2fd0ea2ba7657d6e23a470231c6fa1\",\n        \"size\": 510603656\n    },\n    \"HardBreakRoute_Town12_Route22945_Weather12.tar.gz\": {\n        \"sha256\": \"54031fb828753430ec9cd317a5b5c1798779a39d5ab4011ea5222125ccf1957a\",\n        \"size\": 327685580\n    },\n    \"HardBreakRoute_Town12_Route22946_Weather13.tar.gz\": {\n        \"sha256\": \"752902a14a084277a68167c7efa97322b08e4f93dc818259c761f30b2fc5ac3e\",\n        \"size\": 368131362\n    },\n    \"HardBreakRoute_Town12_Route22947_Weather14.tar.gz\": {\n        \"sha256\": \"1a37f6511c4b75f5f292af6a1a12c5201ba75579d6b0f478695acee3fbe9d90a\",\n        \"size\": 430571221\n    },\n    \"HardBreakRoute_Town12_Route22948_Weather15.tar.gz\": {\n        \"sha256\": \"598765d71b896167b4fe250d9edc0724c3adb99928fbef9536d295dfa26d4e35\",\n        \"size\": 582344752\n    },\n    \"HardBreakRoute_Town12_Route22949_Weather8.tar.gz\": {\n        \"sha256\": \"b58240126d96593df1e59a6cb171befa677e8c0a91627243c2908bca2dab1ad5\",\n        \"size\": 586832090\n    },\n    \"HardBreakRoute_Town12_Route22950_Weather9.tar.gz\": {\n        \"sha256\": \"f36e044f31c8ed3ab47023aca574b6af0a140b2342e3e5172a7ace73a4c66548\",\n        \"size\": 442265429\n    },\n    \"HardBreakRoute_Town12_Route22951_Weather18.tar.gz\": {\n        \"sha256\": \"13565f5ece935b1f0ef8aed368d8803a48b3ec51139e4f273aa99aa1f66c95d1\",\n        \"size\": 558741196\n    },\n    \"HardBreakRoute_Town12_Route22952_Weather19.tar.gz\": {\n        \"sha256\": \"a36ad2cff9efdcf034297ecc9bf301e5bdd4713bef3a5de3c74a1c21698728b2\",\n        \"size\": 454782048\n    },\n    \"HardBreakRoute_Town12_Route22953_Weather20.tar.gz\": {\n        \"sha256\": \"919a42ce8300e2df314d88b728762688aa9539d9f04440faf40b227634c719ab\",\n        \"size\": 508108135\n    },\n    \"HardBreakRoute_Town12_Route22954_Weather21.tar.gz\": {\n        \"sha256\": \"7df5695e5b5e4791dafe34c23bb8ac03c33c32fb1b136260ab0cdeff9a3e8851\",\n        \"size\": 549053218\n    },\n    \"HardBreakRoute_Town12_Route22955_Weather22.tar.gz\": {\n        \"sha256\": \"786b09941617a0aa140a26cbaa7440bc425236e421b03c5c17285db031fe15af\",\n        \"size\": 593060657\n    },\n    \"HardBreakRoute_Town12_Route22956_Weather23.tar.gz\": {\n        \"sha256\": \"6778157c46c2c62eae9b00221102717e8fc695d362454cd457a6ed39b3e58e37\",\n        \"size\": 615937891\n    },\n    \"HardBreakRoute_Town12_Route22957_Weather23.tar.gz\": {\n        \"sha256\": \"eeb20a7c1f3a319bc6a5a990f54544a1e6c7fd4fa6390a255aa43f57d669c78f\",\n        \"size\": 591234703\n    },\n    \"HardBreakRoute_Town12_Route22958_Weather25.tar.gz\": {\n        \"sha256\": \"df28cc2d67c501f9c4abee0901a2827ef79b245d65ea4c0a61e647bd49651d00\",\n        \"size\": 461055031\n    },\n    \"HardBreakRoute_Town12_Route22959_Weather0.tar.gz\": {\n        \"sha256\": \"ee44add7037223155977041fbdf43b4ac85b160f304a9606273da06f4135b490\",\n        \"size\": 420692828\n    },\n    \"HardBreakRoute_Town12_Route22961_Weather2.tar.gz\": {\n        \"sha256\": \"d9a79b122cc6dc7fe7001e46cd16852a1d5ee924fed4e11a25a65ca72a6ca0b8\",\n        \"size\": 694238662\n    },\n    \"HardBreakRoute_Town12_Route22962_Weather3.tar.gz\": {\n        \"sha256\": \"e4a5fd9c47b7d05a038f8f4517acf6f1a043ae35d0c0d6854ae752269f6acea3\",\n        \"size\": 586203360\n    },\n    \"HardBreakRoute_Town12_Route22963_Weather3.tar.gz\": {\n        \"sha256\": \"4e5b15bebeac2cff938a21144d503e9b94c4f85afeaf60c209abf0b3965101eb\",\n        \"size\": 394585881\n    },\n    \"HardBreakRoute_Town12_Route22964_Weather5.tar.gz\": {\n        \"sha256\": \"633a00f0dba9282d9d52478f67baf742ef4d9c8ab180bc7f9ec66b7d0893327f\",\n        \"size\": 609677427\n    },\n    \"HardBreakRoute_Town12_Route22967_Weather8.tar.gz\": {\n        \"sha256\": \"bab9288e21af9940101c04d6ec3f3ca1392bf6b6827f9083019a695dd4e4885a\",\n        \"size\": 190299132\n    },\n    \"HardBreakRoute_Town12_Route22968_Weather9.tar.gz\": {\n        \"sha256\": \"fc28ab1a5f9f2f9edb966cb352db06db6dabe00daa86764914a529f3023183c7\",\n        \"size\": 202749818\n    },\n    \"HardBreakRoute_Town12_Route22969_Weather10.tar.gz\": {\n        \"sha256\": \"baadb07674cc78a1ccdaa9e241183f514eb56dcab4db0a5077a08d761dad6557\",\n        \"size\": 189007607\n    },\n    \"HardBreakRoute_Town12_Route22971_Weather12.tar.gz\": {\n        \"sha256\": \"b6f9e6ad21fb8560642b7c0f2e1ff5b7049c6644af126150d2a131915e44300a\",\n        \"size\": 183375475\n    },\n    \"HardBreakRoute_Town12_Route22972_Weather13.tar.gz\": {\n        \"sha256\": \"3fe1f5069a114916af7faed000fb45e62545cc1aa49be7220897066c1b6d8a7a\",\n        \"size\": 377526890\n    },\n    \"HardBreakRoute_Town12_Route22973_Weather14.tar.gz\": {\n        \"sha256\": \"ed3237184028c14d067fc02e53564933103ecab21916e87319022c28ba634f64\",\n        \"size\": 365738758\n    },\n    \"HardBreakRoute_Town12_Route22974_Weather15.tar.gz\": {\n        \"sha256\": \"737025e52b20a8fe12077684b1defc9fc75c03294807b6a847442c7eacb70635\",\n        \"size\": 371369258\n    },\n    \"HardBreakRoute_Town12_Route22975_Weather8.tar.gz\": {\n        \"sha256\": \"013766561abefefb8231c5fc045fc7ee494ad5452b1d19dfc711cc54b1128779\",\n        \"size\": 485433253\n    },\n    \"HardBreakRoute_Town12_Route22976_Weather9.tar.gz\": {\n        \"sha256\": \"54c229567b501513a78787d7494776672a64b55ecf992bda4df4db83c573d9be\",\n        \"size\": 192107131\n    },\n    \"HardBreakRoute_Town12_Route22980_Weather21.tar.gz\": {\n        \"sha256\": \"95cb0ce9ea936a801cd062768aed26f118cf4921c362f7ad3d9623e709d407ca\",\n        \"size\": 225441408\n    },\n    \"HardBreakRoute_Town12_Route22981_Weather22.tar.gz\": {\n        \"sha256\": \"72f0be3617f487c8f891621377d98329b7b366c97db933ba03d877c0aad1101a\",\n        \"size\": 310872964\n    },\n    \"HardBreakRoute_Town12_Route22982_Weather23.tar.gz\": {\n        \"sha256\": \"a9b29acb748d324984780173f05b5c29949c0ad8feb99706eee99f339e452937\",\n        \"size\": 356469189\n    },\n    \"HardBreakRoute_Town12_Route22983_Weather23.tar.gz\": {\n        \"sha256\": \"b6b62fcf92037977de5d114df30e16df448e850c86834d43bd92d146e642c210\",\n        \"size\": 418169725\n    },\n    \"HardBreakRoute_Town12_Route22984_Weather25.tar.gz\": {\n        \"sha256\": \"e44f1cbbe7d441160e13e88322fc2ec0702abd78172a3100df415f3605fe3293\",\n        \"size\": 373724793\n    },\n    \"HardBreakRoute_Town12_Route22985_Weather0.tar.gz\": {\n        \"sha256\": \"7a9e0bef148b59cc457bcd96330e5175517311cdc9367b68db125f51958c8203\",\n        \"size\": 418584883\n    },\n    \"HardBreakRoute_Town12_Route22986_Weather1.tar.gz\": {\n        \"sha256\": \"170963c68a15d74f7d58e75e4fdac4474f5315f995ec1b0994721ef0cba1ebae\",\n        \"size\": 488319621\n    },\n    \"HardBreakRoute_Town12_Route22987_Weather2.tar.gz\": {\n        \"sha256\": \"f4df9867f987e5e4995b9e0e429286defbb91a1f6e000dce413312d072b9afcc\",\n        \"size\": 251666133\n    },\n    \"HardBreakRoute_Town12_Route22988_Weather3.tar.gz\": {\n        \"sha256\": \"1d5a65bf267738f662c06ed239791512459ff445e59341bd66d75bd62e44f0dd\",\n        \"size\": 221291507\n    },\n    \"HardBreakRoute_Town12_Route22989_Weather3.tar.gz\": {\n        \"sha256\": \"87c3bf127ea126ab78f0b595f8ec41b00f3ee0f914a6cd25d79dea0d9623b650\",\n        \"size\": 239591181\n    },\n    \"HardBreakRoute_Town12_Route22990_Weather5.tar.gz\": {\n        \"sha256\": \"7905fe7a971e0ed4141d7950d6356a397970d01619d9b9cf279be5827ebb4017\",\n        \"size\": 215309804\n    },\n    \"HardBreakRoute_Town12_Route22992_Weather7.tar.gz\": {\n        \"sha256\": \"bd1d297d6f47e5299885242af9ccfc45b9228741401d8cd91b294ce734a689e2\",\n        \"size\": 205617466\n    },\n    \"HardBreakRoute_Town12_Route22993_Weather8.tar.gz\": {\n        \"sha256\": \"e15449dae5a1ea6d0c12eb4ba51737659b94114aee61f64d697f4d52a6f884d1\",\n        \"size\": 560486180\n    },\n    \"HardBreakRoute_Town12_Route22994_Weather9.tar.gz\": {\n        \"sha256\": \"99cdc0695a9706dec3406457886cb55e2475a157f7425d589d68b31cba0fb688\",\n        \"size\": 281538380\n    },\n    \"HardBreakRoute_Town12_Route22995_Weather10.tar.gz\": {\n        \"sha256\": \"dc4dc7dc72a8bb576f625c80a11c35918595e9307c648f6d41a992235d62c9fc\",\n        \"size\": 206650540\n    },\n    \"HardBreakRoute_Town12_Route22996_Weather11.tar.gz\": {\n        \"sha256\": \"9c40fbc0594b0b289de78f3ea48376ce04e62fdb962c086bd8ce84d8e327f57b\",\n        \"size\": 158742596\n    },\n    \"HardBreakRoute_Town12_Route22997_Weather12.tar.gz\": {\n        \"sha256\": \"d76e2b821bd3637b029611cf63d840f86fd8066df1c6f5020c2b0ba89c6c75e6\",\n        \"size\": 290146466\n    },\n    \"HardBreakRoute_Town12_Route22998_Weather13.tar.gz\": {\n        \"sha256\": \"21d8707ba7dc341c33ffd6c52d9c2e76aa44d68dba92dbea58bcfb16198e410b\",\n        \"size\": 228432203\n    },\n    \"HardBreakRoute_Town12_Route22999_Weather14.tar.gz\": {\n        \"sha256\": \"bdd87fe159f301b362d98e0f5654e38a70df7a7d7fece7f89d0857a40e4485dd\",\n        \"size\": 370948906\n    },\n    \"HardBreakRoute_Town12_Route23000_Weather15.tar.gz\": {\n        \"sha256\": \"ee79a245ff700c656bd27d5c732ac8909d565740a6222e6688348833f14680a0\",\n        \"size\": 196836589\n    },\n    \"HardBreakRoute_Town12_Route23001_Weather8.tar.gz\": {\n        \"sha256\": \"ddc280cbb2006135d724f9fed9737f591ab2d779dc8f56e95781f9ce2d229798\",\n        \"size\": 467282251\n    },\n    \"HardBreakRoute_Town12_Route23002_Weather9.tar.gz\": {\n        \"sha256\": \"502e94a7c0b8527c2f22e254e66ba566f1db7073cd4803e9671589f8b7f2730d\",\n        \"size\": 359185583\n    },\n    \"HardBreakRoute_Town12_Route23003_Weather18.tar.gz\": {\n        \"sha256\": \"43268e666d2a45b8b3d780450d5f2760d351d2ea6da271c2f3df260362d919a2\",\n        \"size\": 464854140\n    },\n    \"HardBreakRoute_Town12_Route23004_Weather19.tar.gz\": {\n        \"sha256\": \"e5ea17f6da138202ebd48765774657a64e26fc3cede64244b9b640f8ba303157\",\n        \"size\": 427957479\n    },\n    \"HardBreakRoute_Town12_Route23005_Weather20.tar.gz\": {\n        \"sha256\": \"b0b9c519ae4d6f8c55fc36f068361dcb4257dd1f17eddfc9068a0ed59ec619c1\",\n        \"size\": 437534681\n    },\n    \"HardBreakRoute_Town12_Route23006_Weather21.tar.gz\": {\n        \"sha256\": \"915589d3ad9361fca7c0b31cfa4593abf7728d42022693a6fe85c3b15e158c47\",\n        \"size\": 458176335\n    },\n    \"HardBreakRoute_Town12_Route23007_Weather22.tar.gz\": {\n        \"sha256\": \"7f9be13103e9ac2b3cf8f8be3b56db4051521f8c09343da9db9ff8a993d8914c\",\n        \"size\": 392473181\n    },\n    \"HardBreakRoute_Town12_Route23008_Weather23.tar.gz\": {\n        \"sha256\": \"ae98ada8df0253453e4ec95fe51b1d7880a64661e7328a19d0d03f905eec403d\",\n        \"size\": 173657518\n    },\n    \"HardBreakRoute_Town12_Route23009_Weather23.tar.gz\": {\n        \"sha256\": \"9ef13820de92ad1ca8aea5afa4cafee0d6df8c28090c92f54c77badb13e97ddc\",\n        \"size\": 202438352\n    },\n    \"HardBreakRoute_Town12_Route23010_Weather25.tar.gz\": {\n        \"sha256\": \"885ca956d02962cabb6b4bb5be058858035ab6d5434d9e0c1a95d9bb8e58117b\",\n        \"size\": 304881376\n    },\n    \"HardBreakRoute_Town12_Route23011_Weather0.tar.gz\": {\n        \"sha256\": \"728b5e4a7b8a4cbeb11327d48d78feb6c061b26bddf19354ae9decfe9eeaf82c\",\n        \"size\": 479796031\n    },\n    \"HardBreakRoute_Town12_Route23012_Weather1.tar.gz\": {\n        \"sha256\": \"d12e3140b10a1e9ea3910d9c4856478fa60648f986cb397b408a21e9436d2dfe\",\n        \"size\": 453914248\n    },\n    \"HardBreakRoute_Town12_Route23013_Weather2.tar.gz\": {\n        \"sha256\": \"56c5ce084f949cab518e433c51eab9f89813b8650f522e087dd26a51a86ffce8\",\n        \"size\": 479208584\n    },\n    \"HardBreakRoute_Town12_Route23014_Weather3.tar.gz\": {\n        \"sha256\": \"7781c88e7dab90c72b96e3b8afb6b7290bf6456258547e43359694431afd8ae0\",\n        \"size\": 382039677\n    },\n    \"HardBreakRoute_Town12_Route23015_Weather3.tar.gz\": {\n        \"sha256\": \"b0369bff22f3f43bb4252e085907f53ef862ba3a6e75c3311951b46924939cd7\",\n        \"size\": 446446052\n    },\n    \"HardBreakRoute_Town12_Route23018_Weather7.tar.gz\": {\n        \"sha256\": \"e0f43bbb0fedc9bb33c3fb7fb4e4b527c12e48a945e70e57b48ea3ef7f431b4a\",\n        \"size\": 609954952\n    },\n    \"HardBreakRoute_Town12_Route23019_Weather8.tar.gz\": {\n        \"sha256\": \"7fda62254e4eedb1db2815314f59868884ecf1edae1ae900ffe04dfa2765b022\",\n        \"size\": 363193356\n    },\n    \"HardBreakRoute_Town12_Route23020_Weather9.tar.gz\": {\n        \"sha256\": \"04bd5bfa89133bbea91fa8dc3f3a5b9e196fc5801ba7c84334056f1302a4400a\",\n        \"size\": 216201195\n    },\n    \"HardBreakRoute_Town12_Route23021_Weather10.tar.gz\": {\n        \"sha256\": \"d2228f9c45f39c4713b7d7b664bc59810a2a69df395998874e3f0354c478df2d\",\n        \"size\": 251332445\n    },\n    \"HardBreakRoute_Town12_Route23022_Weather11.tar.gz\": {\n        \"sha256\": \"d741b47c81db19d421bfe876b5119fda33c6becd7a61b9feef066f5f7f9cfd47\",\n        \"size\": 190138658\n    },\n    \"HardBreakRoute_Town12_Route23023_Weather12.tar.gz\": {\n        \"sha256\": \"083c1cf054356d3dfd99067b01a68f2b90a44d6acf7f63ce1f48e5b32c06ccfa\",\n        \"size\": 352708157\n    },\n    \"HardBreakRoute_Town12_Route23024_Weather13.tar.gz\": {\n        \"sha256\": \"e50aa90202b320c99a458e4fc9b63656ebb13828ab9ef2ba3cc1eef4851f58f4\",\n        \"size\": 170749498\n    },\n    \"HardBreakRoute_Town12_Route23025_Weather14.tar.gz\": {\n        \"sha256\": \"505be60fab2daf288b07e6594c34d1265e060313e7d7dca752a784358d55a306\",\n        \"size\": 220707867\n    },\n    \"HardBreakRoute_Town12_Route23026_Weather15.tar.gz\": {\n        \"sha256\": \"222d98cbfc9231bcbce33de2737e6db88a0e2c91535fe8fa8cc945475c0d7880\",\n        \"size\": 474269752\n    },\n    \"HardBreakRoute_Town12_Route23027_Weather8.tar.gz\": {\n        \"sha256\": \"44a0c22d73fec240085efe93a1ee0bcd1e626fb4cb8e4f785bafd74f2313bfa2\",\n        \"size\": 636787527\n    },\n    \"HardBreakRoute_Town12_Route23028_Weather9.tar.gz\": {\n        \"sha256\": \"3e9650a39491c73f3d83eaf5b4bd92ba080da74947bcf210e7f061feb0f1c95d\",\n        \"size\": 159497527\n    },\n    \"HardBreakRoute_Town12_Route23033_Weather22.tar.gz\": {\n        \"sha256\": \"f6915368b492e2bcad9be2a944288dd542670a8f557435536a0875b299eccd47\",\n        \"size\": 322281670\n    },\n    \"HardBreakRoute_Town12_Route23034_Weather23.tar.gz\": {\n        \"sha256\": \"505b2bcc7faad7c5549ab1881b7aebd0272f032ebd54d200a0ac3d6fe79185d4\",\n        \"size\": 251969256\n    },\n    \"HardBreakRoute_Town12_Route23035_Weather23.tar.gz\": {\n        \"sha256\": \"a266f0cef998c0918710ee9e45feea2c7d05c495e696e7d811f967db5f7c17f9\",\n        \"size\": 204666288\n    },\n    \"HardBreakRoute_Town12_Route23037_Weather0.tar.gz\": {\n        \"sha256\": \"61253e95336ebb5af71b5ba5c093663635b0770c616de84cde4e5e9481eca967\",\n        \"size\": 721088441\n    },\n    \"HardBreakRoute_Town12_Route23038_Weather1.tar.gz\": {\n        \"sha256\": \"b49d10a2c060c7656cd59d62783cbd585c58174e012c04bc702d32caf9526f33\",\n        \"size\": 744797032\n    },\n    \"HardBreakRoute_Town12_Route23039_Weather2.tar.gz\": {\n        \"sha256\": \"0dd573b8b7389d39504c5d355eaecba2f0c5940b5f57944e124e8562c0d9af31\",\n        \"size\": 405000363\n    },\n    \"HardBreakRoute_Town12_Route23040_Weather3.tar.gz\": {\n        \"sha256\": \"d5eadfe10dc9252ff3c4c5ad22bfcd6d6d29a96d975771630bff759b4c9a807f\",\n        \"size\": 258569058\n    },\n    \"HardBreakRoute_Town12_Route23041_Weather3.tar.gz\": {\n        \"sha256\": \"cfbe8c3f25f6aaaa72a908fa421e46b762b8880db036447b22bf43236741db23\",\n        \"size\": 250317133\n    },\n    \"HardBreakRoute_Town12_Route23042_Weather5.tar.gz\": {\n        \"sha256\": \"0f0194fff0cd9488bdd74eb2ee964f753a7d8d6aebcfbdedccb4e723a8dde57c\",\n        \"size\": 253893828\n    },\n    \"HardBreakRoute_Town12_Route23044_Weather7.tar.gz\": {\n        \"sha256\": \"1dcbaae861266fb4b2ba6aefcdd05221ad9cd0d25d389956a9885002085454ea\",\n        \"size\": 687463164\n    },\n    \"HardBreakRoute_Town12_Route23045_Weather8.tar.gz\": {\n        \"sha256\": \"94a04ccbada2073fbd4d9bf49dda6752fde351693bec9164e5363f991a79270a\",\n        \"size\": 632630852\n    },\n    \"HardBreakRoute_Town12_Route23046_Weather9.tar.gz\": {\n        \"sha256\": \"38a43ed8afb9d2237f66e337301586408d19224e8120f53d880357ff64d1e33c\",\n        \"size\": 479226142\n    },\n    \"HardBreakRoute_Town12_Route23047_Weather10.tar.gz\": {\n        \"sha256\": \"f24bcd86308106b9f7d166f5a48908b106aa56035bd17f87e8cb57380ac7903e\",\n        \"size\": 427851442\n    },\n    \"HardBreakRoute_Town12_Route23048_Weather11.tar.gz\": {\n        \"sha256\": \"98697220950e2fe8310ccb69a70100bc0b32b7dbd27b699d2d88958f0767a6c2\",\n        \"size\": 454023249\n    },\n    \"HardBreakRoute_Town12_Route23049_Weather12.tar.gz\": {\n        \"sha256\": \"02b935ddaf052734b00b01530033139ba1c33c4fb5a3f37da3c4ad707075229e\",\n        \"size\": 511212889\n    },\n    \"HardBreakRoute_Town12_Route23050_Weather13.tar.gz\": {\n        \"sha256\": \"2970bbe12da1d23b8a086774bcb812de5a6992570109bbc19997b7ca51d4625c\",\n        \"size\": 489061378\n    },\n    \"HardBreakRoute_Town12_Route23051_Weather14.tar.gz\": {\n        \"sha256\": \"03f5706895f1f3d2285f9ecd9a9bbf148152ae9c2a197cec1ec9b6eaf1323e85\",\n        \"size\": 495556985\n    },\n    \"HardBreakRoute_Town12_Route23052_Weather15.tar.gz\": {\n        \"sha256\": \"0ce16bdc2c4102ff97a2de71aa590edec4ebd5fdce03547b9b3d4bf02fc0e94f\",\n        \"size\": 581628064\n    },\n    \"HardBreakRoute_Town12_Route23053_Weather8.tar.gz\": {\n        \"sha256\": \"86ec2943ed7f2538363842b7f3f21a9074ae239886e0012c434901a715d366b7\",\n        \"size\": 508749614\n    },\n    \"HardBreakRoute_Town12_Route23054_Weather9.tar.gz\": {\n        \"sha256\": \"ee71a6b60a20e381da1ce0e306bc7e7bfae63d12121a4dd4365cc631c5384a95\",\n        \"size\": 434929114\n    },\n    \"HardBreakRoute_Town12_Route23056_Weather19.tar.gz\": {\n        \"sha256\": \"6e36108fb93f874dc246c3522dc2e5b6b2f72e39e7e23ccea3678cc7dd9d28bc\",\n        \"size\": 571839123\n    },\n    \"HardBreakRoute_Town12_Route23059_Weather22.tar.gz\": {\n        \"sha256\": \"d17d9e1d580b535c485f3929b4fc13a2a3e3facda2f3669484cc3a15f933171c\",\n        \"size\": 532249753\n    },\n    \"HardBreakRoute_Town12_Route23060_Weather23.tar.gz\": {\n        \"sha256\": \"8a85e50479af863bb424232dbe9f7dd2ef09bdec22429a37c67b4a801ecdf737\",\n        \"size\": 462658219\n    },\n    \"HardBreakRoute_Town12_Route23061_Weather23.tar.gz\": {\n        \"sha256\": \"4660f5d56a80dfc0c1e1720d73ee674504405f6670358eb2097c85d5b9bc867e\",\n        \"size\": 570274999\n    },\n    \"HardBreakRoute_Town12_Route23062_Weather25.tar.gz\": {\n        \"sha256\": \"93e284b130195b4d0136d6e885938d5f0add2b96fe19aa8bb2c85c727b0a2948\",\n        \"size\": 450810253\n    },\n    \"HardBreakRoute_Town12_Route23063_Weather0.tar.gz\": {\n        \"sha256\": \"581ccdf0de8628543e0e066fdc817d8904fc28e8f12a3a0068e86db83820aff9\",\n        \"size\": 475484977\n    },\n    \"HardBreakRoute_Town12_Route23064_Weather1.tar.gz\": {\n        \"sha256\": \"5a70a39628bd6c27fd9e663cf2888b25b92e9b953006172bc607788a20666443\",\n        \"size\": 455933461\n    },\n    \"HardBreakRoute_Town12_Route23065_Weather2.tar.gz\": {\n        \"sha256\": \"c9585c8afb9313dbe37665bd19e182237561058b20a274737d1960c891e1248c\",\n        \"size\": 557701118\n    },\n    \"HardBreakRoute_Town12_Route23066_Weather3.tar.gz\": {\n        \"sha256\": \"54a03af94ecd5dbaebb9783199176cbc2c8ff39e1e5a3c7fde6c2c0984bceec2\",\n        \"size\": 438350983\n    },\n    \"HardBreakRoute_Town12_Route23067_Weather3.tar.gz\": {\n        \"sha256\": \"bc3a6909df0bba4d7fadd4f5f8c056cbb3075d66ec65bc5a99c6f7aafe50bcf4\",\n        \"size\": 337130135\n    },\n    \"HardBreakRoute_Town12_Route23068_Weather5.tar.gz\": {\n        \"sha256\": \"f72b441df928d5268d5f94da22b9620a3a85a35e0893ebbcf9237e32559bf040\",\n        \"size\": 510599934\n    },\n    \"HardBreakRoute_Town12_Route23069_Weather6.tar.gz\": {\n        \"sha256\": \"0471ae5ac2a2f850dec9782bf8d847d07a52bc9d0b3b110911c0b6fd3a84065d\",\n        \"size\": 216688923\n    },\n    \"HardBreakRoute_Town12_Route23070_Weather7.tar.gz\": {\n        \"sha256\": \"ae141cbb9ac504fae3d69599eda6bb1e7154cbf8bc945c904f7953e4ebb74f7f\",\n        \"size\": 281695201\n    },\n    \"HardBreakRoute_Town12_Route23071_Weather8.tar.gz\": {\n        \"sha256\": \"36e33e792ea93a431593bf56169ed925f93270bca782379dcbb51a374a249c86\",\n        \"size\": 221872352\n    },\n    \"HardBreakRoute_Town12_Route23072_Weather9.tar.gz\": {\n        \"sha256\": \"5a4e70e5ef98d11790cd7663a632638ff3bb391cfd2fe8765b50a0ec7ffc39f4\",\n        \"size\": 579098788\n    },\n    \"HardBreakRoute_Town12_Route23073_Weather10.tar.gz\": {\n        \"sha256\": \"34a4525148e75f7a611e8fa22746365c4ff94e118c25379496e2d2391c6bbdcf\",\n        \"size\": 400451032\n    },\n    \"HardBreakRoute_Town12_Route23074_Weather11.tar.gz\": {\n        \"sha256\": \"7c78e780a3ae5fae80ab5c3fb45ac682cabd709e66fbfc1e4cc5ac42223385c0\",\n        \"size\": 168770388\n    },\n    \"HardBreakRoute_Town12_Route23075_Weather12.tar.gz\": {\n        \"sha256\": \"39299a3b05417359d52a90907bb3e2d51e535398e1039d188b383bbfdca14429\",\n        \"size\": 211286051\n    },\n    \"HardBreakRoute_Town12_Route23076_Weather13.tar.gz\": {\n        \"sha256\": \"98f3d8b72cd98ce7b97112592d287fa9913ce5d78850ecb8b22d1ad9775c51ed\",\n        \"size\": 552205072\n    },\n    \"HardBreakRoute_Town12_Route23077_Weather14.tar.gz\": {\n        \"sha256\": \"7ec603adf20847a0215b5803aaf884fe87e7417bec9e2b20ec24107a6019ad48\",\n        \"size\": 503607331\n    },\n    \"HardBreakRoute_Town12_Route23078_Weather15.tar.gz\": {\n        \"sha256\": \"41bb34aa5c2b4a5881ff900026882974388ba9098bdc02cf2ff8a7e8e239b724\",\n        \"size\": 465083897\n    },\n    \"HardBreakRoute_Town12_Route23079_Weather8.tar.gz\": {\n        \"sha256\": \"89f1da83c55fd980bdbedb6197934073c0fe113af365f4ccfee99659d39e12ca\",\n        \"size\": 725363533\n    },\n    \"HardBreakRoute_Town12_Route23080_Weather9.tar.gz\": {\n        \"sha256\": \"358f11e4131765788165513482c7535b8de0b24f7820baaf25e3f8371b7bced3\",\n        \"size\": 551052858\n    },\n    \"HardBreakRoute_Town12_Route23081_Weather18.tar.gz\": {\n        \"sha256\": \"aff9d0277804b9978ea6acce678a168b58b32f3234f525a70c005fc18b081685\",\n        \"size\": 630781376\n    },\n    \"HardBreakRoute_Town12_Route23082_Weather19.tar.gz\": {\n        \"sha256\": \"0335a5dbbaa095863aa093864b2122adbd8fb1ef9969d980fbfe02b8a8d27946\",\n        \"size\": 427742162\n    },\n    \"HardBreakRoute_Town12_Route23084_Weather21.tar.gz\": {\n        \"sha256\": \"55083634e2a03a01991ad77416ec1399628b0c79609b27cfdac1f49c800a4cf7\",\n        \"size\": 482956222\n    },\n    \"HardBreakRoute_Town12_Route23088_Weather25.tar.gz\": {\n        \"sha256\": \"b93a68cfbc1c74351908a6f0bff18b5dceec97831442140b54acb11f03e0189a\",\n        \"size\": 1140139811\n    },\n    \"HardBreakRoute_Town12_Route23089_Weather0.tar.gz\": {\n        \"sha256\": \"38b77ce73a986c53c41590d27009ee725a2d608e5b3759b3eceb058f74a4e12b\",\n        \"size\": 238896881\n    },\n    \"HardBreakRoute_Town12_Route23090_Weather1.tar.gz\": {\n        \"sha256\": \"4a7cd06f2b2605c5d7a7f11976aa77a5137feafef8a5dfa5db5deec1b872bd3f\",\n        \"size\": 214854817\n    },\n    \"HardBreakRoute_Town12_Route23091_Weather2.tar.gz\": {\n        \"sha256\": \"2c53c08e8140caedc901d536e293a7e77f68cbce7bca7a58561b63d965927c07\",\n        \"size\": 747121745\n    },\n    \"HardBreakRoute_Town12_Route23092_Weather3.tar.gz\": {\n        \"sha256\": \"622a8244c99eba979468311965debb395fb9946fdd6ce24db9c5baee68206117\",\n        \"size\": 497846691\n    },\n    \"HardBreakRoute_Town12_Route23095_Weather6.tar.gz\": {\n        \"sha256\": \"7a890948ba32bec7540d6b71d04440edf7c7874e139ca85eea2e0674f02adf82\",\n        \"size\": 462768942\n    },\n    \"HardBreakRoute_Town12_Route23096_Weather7.tar.gz\": {\n        \"sha256\": \"69cb3b44201b44d1630466758377988e7e3fad528081e90657e2d51b77b2a03b\",\n        \"size\": 630741537\n    },\n    \"HardBreakRoute_Town12_Route23098_Weather9.tar.gz\": {\n        \"sha256\": \"a7025662e5b10d2c2eb17580066328f3457c1732bf9e8400c1d5c0ef11666e60\",\n        \"size\": 151438019\n    },\n    \"HardBreakRoute_Town12_Route23099_Weather10.tar.gz\": {\n        \"sha256\": \"699823ca1d478d9eb76668e43faa7de510a8f72cb7f7724ed010e22db4762cad\",\n        \"size\": 499993285\n    },\n    \"HardBreakRoute_Town12_Route23100_Weather11.tar.gz\": {\n        \"sha256\": \"5449cc8f431cfa4de8ecb61bd59710e17e2cf6cf53334a280addb6a7715da269\",\n        \"size\": 512406347\n    },\n    \"HardBreakRoute_Town12_Route23103_Weather14.tar.gz\": {\n        \"sha256\": \"96aed7b1fa11ac09ee5238f1c55e74c4c3492c786f090935f13f73cf4a3caf1a\",\n        \"size\": 503440698\n    },\n    \"HardBreakRoute_Town12_Route23104_Weather15.tar.gz\": {\n        \"sha256\": \"766dfb3470060e78f052a94b07e63766b1716304bdf501f0b0a2e7cefbed9f94\",\n        \"size\": 240096515\n    },\n    \"HardBreakRoute_Town12_Route23105_Weather8.tar.gz\": {\n        \"sha256\": \"2c8c8ee6f783db989eb3297a075e27b2e4ed5247df91cb2139ff8b6dd100f5bd\",\n        \"size\": 373662515\n    },\n    \"HardBreakRoute_Town12_Route23106_Weather9.tar.gz\": {\n        \"sha256\": \"dbc1b289ea444bbbe5dee66b244d143c1c9c9309875e021ed79e29a96f77f1c0\",\n        \"size\": 357536300\n    },\n    \"HardBreakRoute_Town12_Route23107_Weather18.tar.gz\": {\n        \"sha256\": \"0252ba1ae5f7906694b9523eb35548bc6297ee4cbbcfc4a972acf974ff435851\",\n        \"size\": 290159467\n    },\n    \"HardBreakRoute_Town12_Route23108_Weather19.tar.gz\": {\n        \"sha256\": \"789d773eaf1d205f2254a1aac61f03efe26190219143319cb51babbec05409ea\",\n        \"size\": 208951370\n    },\n    \"HardBreakRoute_Town12_Route23109_Weather20.tar.gz\": {\n        \"sha256\": \"989f77d84f70c5f59a4ef3406cf7c1720ebd27741aae30171a5e760f656a0f4a\",\n        \"size\": 447304473\n    },\n    \"HardBreakRoute_Town12_Route23110_Weather21.tar.gz\": {\n        \"sha256\": \"3f260260e1283a32747036a17d9af7b96aa44b0c78824a611dd3314b92e8a451\",\n        \"size\": 238662893\n    },\n    \"HardBreakRoute_Town12_Route23111_Weather22.tar.gz\": {\n        \"sha256\": \"ea64f3c2abfdc8a408d9898b8d4d4ca80a73ab53bc04035227b34af7f45dd608\",\n        \"size\": 386498488\n    },\n    \"HardBreakRoute_Town12_Route23112_Weather23.tar.gz\": {\n        \"sha256\": \"1f1e661a5f6d64160ff149758af4097d1fad16f4e82e2078dba410c5fe98e739\",\n        \"size\": 179737852\n    },\n    \"HardBreakRoute_Town12_Route23113_Weather23.tar.gz\": {\n        \"sha256\": \"93b232b6aed9ce8a46ea889218ea3c99e4054d90a7fe0202bcbc8b5aed223632\",\n        \"size\": 186128280\n    },\n    \"HardBreakRoute_Town12_Route23114_Weather25.tar.gz\": {\n        \"sha256\": \"09844dd8c483be5457afc656a1909d51a37aa6667e3f8bfa441fb6395e5858a3\",\n        \"size\": 414898269\n    },\n    \"HardBreakRoute_Town12_Route23115_Weather0.tar.gz\": {\n        \"sha256\": \"5a0f8db49c62d6a2b1706836c753f0e622918a940564b4601da1587239216ef6\",\n        \"size\": 584123535\n    },\n    \"HardBreakRoute_Town12_Route23116_Weather1.tar.gz\": {\n        \"sha256\": \"3b8832e7cf2f3af27d4d82ee5b23f015ab959d7428ccda25a34a81ba4caf5a47\",\n        \"size\": 624940462\n    },\n    \"HardBreakRoute_Town12_Route23117_Weather2.tar.gz\": {\n        \"sha256\": \"5d8bc025412bb9c1bf7c4fb0335d6b6be2ac4284e136facb627614eb52457c43\",\n        \"size\": 251350130\n    },\n    \"HardBreakRoute_Town12_Route23118_Weather3.tar.gz\": {\n        \"sha256\": \"bc94d921df895654527f5ad3d00269fccefb22364780b7b8964524e8388468f1\",\n        \"size\": 425322038\n    },\n    \"HardBreakRoute_Town12_Route23119_Weather3.tar.gz\": {\n        \"sha256\": \"0d0af07f8b16c6f1344a5e00c78217fce9d9eda0e3b67c67c255e756f3bb565c\",\n        \"size\": 407662222\n    },\n    \"HardBreakRoute_Town12_Route23120_Weather5.tar.gz\": {\n        \"sha256\": \"bf7e284bb363bf3c6325c90587a34566431e321a17663cfec7372f36fbd4a2a9\",\n        \"size\": 595002745\n    },\n    \"HardBreakRoute_Town12_Route23121_Weather6.tar.gz\": {\n        \"sha256\": \"7d9e073057131c5eff849bbe64c3023011dd9fcb3e3e448556ec54ba7ca0d070\",\n        \"size\": 218352734\n    },\n    \"HardBreakRoute_Town12_Route23122_Weather7.tar.gz\": {\n        \"sha256\": \"5bcfb703bf3aa68cede95d2367257155e851c1bf48e6248e69b2b2c9148260e0\",\n        \"size\": 649722928\n    },\n    \"HardBreakRoute_Town12_Route23123_Weather8.tar.gz\": {\n        \"sha256\": \"2132627e0ec94760745b93f5d224b858c163da6346de366ac322dabc113c9dfa\",\n        \"size\": 459268032\n    },\n    \"HardBreakRoute_Town12_Route23124_Weather9.tar.gz\": {\n        \"sha256\": \"2a9233e3acc03b67842761804cdbacbf095a40f8404601138ae654a596c142f6\",\n        \"size\": 458363183\n    },\n    \"HardBreakRoute_Town12_Route23125_Weather10.tar.gz\": {\n        \"sha256\": \"7fb2b4c1e6c908767407a040f2a5352facbfc37949461d40c370aa5c396b33cf\",\n        \"size\": 481434756\n    },\n    \"HardBreakRoute_Town12_Route23126_Weather11.tar.gz\": {\n        \"sha256\": \"dd77959b3ff8817b482487b032b227143327109dfd73ded22aca91c19326d41e\",\n        \"size\": 415964610\n    },\n    \"HardBreakRoute_Town12_Route23127_Weather12.tar.gz\": {\n        \"sha256\": \"715d89c51a4a8d2957472f097e2d942eea473267c7d3e9e9e44cf399cea60635\",\n        \"size\": 587643508\n    },\n    \"HardBreakRoute_Town12_Route23128_Weather13.tar.gz\": {\n        \"sha256\": \"64f06a880ef7d1904ac35c70953c3f4285cc92ab6954a158a01e653994dcd426\",\n        \"size\": 524135643\n    },\n    \"HardBreakRoute_Town12_Route23129_Weather14.tar.gz\": {\n        \"sha256\": \"313cc42d6e276ff799b31cfdae17e8ab5c90d2c35e9bff2cfa239f9ca52fb97f\",\n        \"size\": 387736532\n    },\n    \"HardBreakRoute_Town12_Route23130_Weather15.tar.gz\": {\n        \"sha256\": \"31df89313fff6e50b1a9a4ee08895c93cb0c8e28ee7599d4cf17760a370977c9\",\n        \"size\": 441344431\n    },\n    \"HardBreakRoute_Town12_Route23131_Weather8.tar.gz\": {\n        \"sha256\": \"0400e8e9107a0019f8fdad5dda9c9305f4f7b1f1f015f6efcf39944be805c8e6\",\n        \"size\": 500017327\n    },\n    \"HardBreakRoute_Town12_Route2745_Weather9.tar.gz\": {\n        \"sha256\": \"c8da855f9b793b17c560d009d1bba6e200d8864729ca9409ef1cfd8a5c57a94e\",\n        \"size\": 421640335\n    },\n    \"HardBreakRoute_Town12_Route2746_Weather10.tar.gz\": {\n        \"sha256\": \"ac576ca87e423ebf588a032d6cf63949e0bb249221ff8515fa2c60f19ad19eb7\",\n        \"size\": 234460086\n    },\n    \"HardBreakRoute_Town12_Route2747_Weather11.tar.gz\": {\n        \"sha256\": \"c7b11b773dcdb1ce55768ef73d7c5590b03b3f39fda992b7be757c10f682e043\",\n        \"size\": 587692086\n    },\n    \"HardBreakRoute_Town12_Route2748_Weather12.tar.gz\": {\n        \"sha256\": \"8651524fe70ad0daddd85d03de93f9431193bbd8cfb7689eae88f608452995c1\",\n        \"size\": 336773510\n    },\n    \"HardBreakRoute_Town12_Route2749_Weather13.tar.gz\": {\n        \"sha256\": \"71ebefcf5bddbfd556e85c836400ec43aaf147131b6c06b5268fd1b326beca01\",\n        \"size\": 473711225\n    },\n    \"HardBreakRoute_Town12_Route2750_Weather14.tar.gz\": {\n        \"sha256\": \"9a891b7306fe4623b53def6cc6639d45904b1964e3a70b9df8030f9df5d80dd0\",\n        \"size\": 570685954\n    },\n    \"HardBreakRoute_Town12_Route2751_Weather15.tar.gz\": {\n        \"sha256\": \"ece28a9385ed0b1e25d123bd3c6b0a89259e8a616c0fadf66e6f7510d136f6c8\",\n        \"size\": 579811770\n    },\n    \"HardBreakRoute_Town12_Route2754_Weather18.tar.gz\": {\n        \"sha256\": \"66777256cf3622854ccddd31dfa38bd05fa96988f4b844843b6690457e3a7e8e\",\n        \"size\": 365792927\n    },\n    \"HardBreakRoute_Town12_Route2755_Weather19.tar.gz\": {\n        \"sha256\": \"bd0f0cbb708ce8b90ee5893b8e7c1e9fd16fdc3816b9a8e660a291edfda6ea94\",\n        \"size\": 259476536\n    },\n    \"HardBreakRoute_Town12_Route2756_Weather20.tar.gz\": {\n        \"sha256\": \"b644d0c6154b802b800a346806248d076f68b80a835462ff8c77a4a09147d9e7\",\n        \"size\": 479617423\n    },\n    \"HardBreakRoute_Town12_Route2757_Weather21.tar.gz\": {\n        \"sha256\": \"6fae43ee9a0978977b10b6a96d125f82f33dac1c12d0e83abdece4ebd60eb98a\",\n        \"size\": 375582942\n    },\n    \"HardBreakRoute_Town12_Route2758_Weather22.tar.gz\": {\n        \"sha256\": \"d5b814bbfec1bc5b69cf31bdfdaa1076e95af89acb4af2357a7e53794a2abb3b\",\n        \"size\": 441089588\n    },\n    \"HardBreakRoute_Town12_Route2759_Weather23.tar.gz\": {\n        \"sha256\": \"161ade8c0a527545c4b290b9abeca7c80dd4879a02e9312b3fe67da240ccd586\",\n        \"size\": 526239390\n    },\n    \"HardBreakRoute_Town12_Route2760_Weather23.tar.gz\": {\n        \"sha256\": \"a8ba45aa0dde071c488438b0251a67334b98d65b8ad8389185794a8e7e27637d\",\n        \"size\": 417466847\n    },\n    \"HardBreakRoute_Town12_Route2761_Weather25.tar.gz\": {\n        \"sha256\": \"45e77d310118eb3e340989a42512f6eb1cbf508c938307d3934dd70117186dc7\",\n        \"size\": 391687442\n    },\n    \"HardBreakRoute_Town12_Route2763_Weather1.tar.gz\": {\n        \"sha256\": \"7af2b662edd1b1df521e44e7c0c20ff96992b5851c78112cf8bbfd059a607e9a\",\n        \"size\": 513474521\n    },\n    \"HardBreakRoute_Town13_Route3523_Weather8.tar.gz\": {\n        \"sha256\": \"738da1615aa9facbe1c114e1e1548ec2e2e4a7d6f3a35b5868c3edeb2e1e6f14\",\n        \"size\": 802056113\n    },\n    \"HardBreakRoute_Town13_Route3525_Weather10.tar.gz\": {\n        \"sha256\": \"412302dec905224b52a2809c9a078124b88009fbe7917f9f3b6a4e919a0f2bae\",\n        \"size\": 297360810\n    },\n    \"HardBreakRoute_Town13_Route3526_Weather11.tar.gz\": {\n        \"sha256\": \"5cc4b2368870d29e6ddb50bbc545b61e3741d04b3c7565227bc85f07568d4f6b\",\n        \"size\": 401120517\n    },\n    \"HardBreakRoute_Town13_Route3527_Weather12.tar.gz\": {\n        \"sha256\": \"85b9932a71c9f7c36751778c20510d9bb96db762b48abdd06a87e01ed8b828fd\",\n        \"size\": 677745558\n    },\n    \"HardBreakRoute_Town13_Route3528_Weather13.tar.gz\": {\n        \"sha256\": \"ab01800a3e6adbd73a20d67f570d534afdede688dc8669b76090364b3fb4838f\",\n        \"size\": 445341575\n    },\n    \"HardBreakRoute_Town13_Route3529_Weather14.tar.gz\": {\n        \"sha256\": \"be0a2654ac985798fb75f6aa81b2520a146c8ad8c6f12ee9b14692c6747de4df\",\n        \"size\": 289826725\n    },\n    \"HardBreakRoute_Town13_Route3530_Weather15.tar.gz\": {\n        \"sha256\": \"90103d66d857becef8dd5587b5add7fdf6b89fc1d206434ae7ed99dfa8cbabdc\",\n        \"size\": 552886564\n    },\n    \"HardBreakRoute_Town13_Route3531_Weather8.tar.gz\": {\n        \"sha256\": \"7ae4b669665cd581335ee1bf723465612a1a4d3d674d24b57f5c78e4fc298e6c\",\n        \"size\": 532548506\n    },\n    \"HardBreakRoute_Town13_Route3532_Weather9.tar.gz\": {\n        \"sha256\": \"4ddd3e6291479a9229f0a9267d86e3a8969f5288e964d423cdf7d66240b3d634\",\n        \"size\": 429344828\n    },\n    \"HardBreakRoute_Town13_Route3533_Weather18.tar.gz\": {\n        \"sha256\": \"0960190912a95613195802c6e9462f3036a8917f0fe4c96777587085f0448743\",\n        \"size\": 841215041\n    },\n    \"HardBreakRoute_Town13_Route3534_Weather19.tar.gz\": {\n        \"sha256\": \"317e61571bc79a9ef77aba35e9419b3e5294898be47a0db33d53e85af5c2aed7\",\n        \"size\": 742529770\n    },\n    \"HardBreakRoute_Town13_Route3536_Weather21.tar.gz\": {\n        \"sha256\": \"e508101aa4d70fda74a1231e545b37339f654a83db3326b9a0069106240d060c\",\n        \"size\": 304927614\n    },\n    \"HardBreakRoute_Town13_Route3537_Weather22.tar.gz\": {\n        \"sha256\": \"74beb3f175de28b58d709c43ae7b22c37f1796fe0e72e68e35263deffa74d6a1\",\n        \"size\": 582006786\n    },\n    \"HardBreakRoute_Town13_Route3540_Weather25.tar.gz\": {\n        \"sha256\": \"c3d2a84b884e5255ce2bd1f0fe209b87b60718aa4430856d0e4c542653c6f94a\",\n        \"size\": 521298150\n    },\n    \"HardBreakRoute_Town13_Route3541_Weather0.tar.gz\": {\n        \"sha256\": \"6b5b74c9e44876adce1555094dd2622a8836573c64fa48d1a82652cc29879af0\",\n        \"size\": 600347035\n    },\n    \"HardBreakRoute_Town13_Route3542_Weather1.tar.gz\": {\n        \"sha256\": \"a3385205f095ff04f38fb7ad93b4344374afb9f4bf612980071885b17aa8a565\",\n        \"size\": 784031323\n    },\n    \"HardBreakRoute_Town15_Route26633_Weather25.tar.gz\": {\n        \"sha256\": \"0c91f9a1c7570d2c7bc3005ece2ad11de96725cf7835c91f2f2ad7850cecf533\",\n        \"size\": 554736279\n    },\n    \"HardBreakRoute_Town15_Route26638_Weather3.tar.gz\": {\n        \"sha256\": \"44bfd573aeea172d738c7ca423adcfdcd8c8da9f7dd1b188c32a108a72e8393b\",\n        \"size\": 692519387\n    },\n    \"HardBreakRoute_Town15_Route26643_Weather9.tar.gz\": {\n        \"sha256\": \"46f47dd8ab2f12c5f5695dcf0fac5f5cea9b8e1dffd333ef6eb32617ccb80faa\",\n        \"size\": 511340307\n    },\n    \"HardBreakRoute_Town15_Route26648_Weather14.tar.gz\": {\n        \"sha256\": \"15dea1b2c8a34c95a0e528c906255c9b70af7c1d5c3fc9a4fb77d5eb58c0d404\",\n        \"size\": 770490617\n    },\n    \"HardBreakRoute_Town15_Route26653_Weather21.tar.gz\": {\n        \"sha256\": \"b9a18fa032e8b427bbec15d1e1a392e0f3e32cab35c80532a1aff310d9584af1\",\n        \"size\": 818242650\n    },\n    \"HardBreakRoute_Town15_Route26658_Weather0.tar.gz\": {\n        \"sha256\": \"6a44971abb389cc6ab18d35e60a75aa061621b7e0dbee877eb25098d30882c6d\",\n        \"size\": 468562607\n    },\n    \"HardBreakRoute_Town15_Route26668_Weather11.tar.gz\": {\n        \"sha256\": \"70cb994d6ff73ded1baa3dd0fc28da022e2e7100c7bb86230aba0102233eee1c\",\n        \"size\": 764576420\n    },\n    \"HardBreakRoute_Town15_Route26673_Weather18.tar.gz\": {\n        \"sha256\": \"0f7c2ac69d136bbc81bb24e4f2068999d32242de9178b231481dc2bcad9f5757\",\n        \"size\": 986103272\n    },\n    \"HardBreakRoute_Town15_Route26678_Weather23.tar.gz\": {\n        \"sha256\": \"1fef882e3584ab5c43c09075b2a7cb0be729f16dbb89e7e346a33bb0f00b9576\",\n        \"size\": 868506728\n    },\n    \"HardBreakRoute_Town15_Route26683_Weather2.tar.gz\": {\n        \"sha256\": \"6d040d2bbadc9cdf56e92ce8ccc0ea2d6bbc6634929790549eb4027ec41a9242\",\n        \"size\": 1037260952\n    },\n    \"HardBreakRoute_Town15_Route26688_Weather8.tar.gz\": {\n        \"sha256\": \"861a834966db81427b4abe7dcae694cd168138b3123a47ffdc04a17d7fe9120d\",\n        \"size\": 933102572\n    },\n    \"HardBreakRoute_Town15_Route26698_Weather20.tar.gz\": {\n        \"sha256\": \"fea0e88f00b1921cc100b3155cd39f3600b69d316e7eff58f1e8029c558eb135\",\n        \"size\": 285028902\n    },\n    \"HardBreakRoute_Town15_Route26703_Weather26.tar.gz\": {\n        \"sha256\": \"c9cf9c040a3445068aed1c353b40fc8f263aa97701ef72fcc9e5ad63074cea82\",\n        \"size\": 309800489\n    },\n    \"HardBreakRoute_Town15_Route26708_Weather5.tar.gz\": {\n        \"sha256\": \"09dc01b0e3e2ae3bb9a41550f898fb507fd6face0a8e9b3fd471e99dc9897814\",\n        \"size\": 1107449092\n    },\n    \"HardBreakRoute_Town15_Route26713_Weather10.tar.gz\": {\n        \"sha256\": \"1252cca66df55841f830ad2c3d796da0a2a5151bcfdbaeacc1f4cc8e5b13fce3\",\n        \"size\": 276253713\n    },\n    \"HardBreakRoute_Town15_Route26718_Weather15.tar.gz\": {\n        \"sha256\": \"c7fcf3ee311bf6c300515f5bdbdc6cd99bca94ee25c583f6614280df2787e160\",\n        \"size\": 196134749\n    },\n    \"HazardAtSideLaneTwoWays_Town03_Route25847_Weather20.tar.gz\": {\n        \"sha256\": \"c5169d3c8c4827e23f63a92570ee483fcf0e1c2be7d39bbc76dd1809b6446a2b\",\n        \"size\": 332427993\n    },\n    \"HazardAtSideLaneTwoWays_Town03_Route25854_Weather1.tar.gz\": {\n        \"sha256\": \"1e3876be0acb5f25078438bc82d7ec435fff220e0184c9c9a4a89d78b8c9c5ba\",\n        \"size\": 423877805\n    },\n    \"HazardAtSideLaneTwoWays_Town03_Route25861_Weather9.tar.gz\": {\n        \"sha256\": \"ee92ae9f9e7e4747c002df69b345086c286f296e4aefdad26efac7805d0d9ebc\",\n        \"size\": 343045420\n    },\n    \"HazardAtSideLaneTwoWays_Town03_Route25868_Weather18.tar.gz\": {\n        \"sha256\": \"548edb2a4be81389ef52c5c5e6a0ead7d6922625f2a4ec468cbbf8b260b11f05\",\n        \"size\": 370969977\n    },\n    \"HazardAtSideLaneTwoWays_Town03_Route25875_Weather26.tar.gz\": {\n        \"sha256\": \"7b0417835189c1b3deb0f60ebc902bf7355481f7f4f5fc94b4b12af57bb115b9\",\n        \"size\": 484424356\n    },\n    \"HazardAtSideLaneTwoWays_Town03_Route25882_Weather7.tar.gz\": {\n        \"sha256\": \"b4d9074ce6f223271f61d845330eb709b02c8efd2460b53f7064570976b44852\",\n        \"size\": 447441909\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25853_Weather0.tar.gz\": {\n        \"sha256\": \"4c11f3c3f41ba89fbe0df1bcaa4c4a9712825eb3d2fb1dfd13ed85cec267160d\",\n        \"size\": 340649118\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25874_Weather25.tar.gz\": {\n        \"sha256\": \"c1d4382c98449417a07d955e5c55a871629c631f48a6c54421efbb25b08c44bf\",\n        \"size\": 191700480\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25916_Weather20.tar.gz\": {\n        \"sha256\": \"d1f370a088085e482583250f6e0d36a5fd8289ee1a9faff34e86afb483e5352e\",\n        \"size\": 239686223\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25930_Weather9.tar.gz\": {\n        \"sha256\": \"0582f4f77c195fdebf0b6704b02b4f86600f67924f2360b9fa0cb27ecb737158\",\n        \"size\": 277314910\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25937_Weather18.tar.gz\": {\n        \"sha256\": \"167419efe18900e3ed1a6fef60443db37c742fc4ebe85af890d0475db544c5c7\",\n        \"size\": 347092318\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25944_Weather26.tar.gz\": {\n        \"sha256\": \"6d62245c13bc3a6cfe9511adf84c430d92f1e92fbe24c99b1c3af8d873f6dad4\",\n        \"size\": 371018711\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25951_Weather7.tar.gz\": {\n        \"sha256\": \"ca460b53e8b5c0bc92e6995123b5b2bc3cdf737f4a174f9b6672e1968e8cc283\",\n        \"size\": 352995899\n    },\n    \"HazardAtSideLaneTwoWays_Town04_Route25958_Weather14.tar.gz\": {\n        \"sha256\": \"2f1811f04391ffab597a6ff19debac3f9661cc6dcca26dd296ca398a71954a51\",\n        \"size\": 313142334\n    },\n    \"HazardAtSideLaneTwoWays_Town05_Route25941_Weather22.tar.gz\": {\n        \"sha256\": \"0f7dcd63a362006b9bdc729580c2f1e9673553a7dc6b31c42646d8f49795e7f9\",\n        \"size\": 203892464\n    },\n    \"HazardAtSideLaneTwoWays_Town05_Route25948_Weather3.tar.gz\": {\n        \"sha256\": \"a1c32c23b277dbf60deb8b8b62e8e94db30681626db421751cbc7369abd2ab1f\",\n        \"size\": 257504213\n    },\n    \"HazardAtSideLaneTwoWays_Town05_Route25955_Weather11.tar.gz\": {\n        \"sha256\": \"878cc14337707f3cbc3146c7b23e5f11576ad7e05beae4cb1d7de2ea3f131940\",\n        \"size\": 248507396\n    },\n    \"HazardAtSideLaneTwoWays_Town05_Route25983_Weather18.tar.gz\": {\n        \"sha256\": \"6ed07753749dd133ceada60b284c85625f3b8e627bdba692836e72344724014c\",\n        \"size\": 278891401\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24218_Weather25.tar.gz\": {\n        \"sha256\": \"b1062b57eccdda314125bd99254d2a6120df15f3bce78fd92997be0eb37534ff\",\n        \"size\": 349418383\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24228_Weather9.tar.gz\": {\n        \"sha256\": \"12a5fa10c839540f8e67f9ac82dfcef5a97f61f656507c56107b648e33d318f5\",\n        \"size\": 461497104\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24238_Weather21.tar.gz\": {\n        \"sha256\": \"690c6f13453278371eabb2fe3c279cd9435ffdb747ec24019b63c56072c2e39c\",\n        \"size\": 462774109\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24248_Weather6.tar.gz\": {\n        \"sha256\": \"cbcb50e7f8e184a74621ebd6fe950ac10ab3dda79f0dc99a9dc5b4a9a8081434\",\n        \"size\": 521350877\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24258_Weather18.tar.gz\": {\n        \"sha256\": \"4576c6cb262a104b10df5e9a5d6515f021b9e213d497175022b4a40f82d11f24\",\n        \"size\": 498348149\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24268_Weather2.tar.gz\": {\n        \"sha256\": \"000b1d5f83cd795ebbbda0236b72f28e150073ec8d1cb29f878db4b193cfbbad\",\n        \"size\": 673478981\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24278_Weather13.tar.gz\": {\n        \"sha256\": \"4763f63edede742deb0d803bffa152a34966f5a859d7bd56b2e56feaf24a29b1\",\n        \"size\": 392690986\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24288_Weather26.tar.gz\": {\n        \"sha256\": \"26de5275325fbf9b86e0a68dc114809cb687cb1261e530e9c683dd317b24cda4\",\n        \"size\": 523364994\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24298_Weather10.tar.gz\": {\n        \"sha256\": \"15a950bf467c0fc1aa002361acceff94833784ff33cce2ed1e9a93b137ae6f07\",\n        \"size\": 545317287\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24308_Weather22.tar.gz\": {\n        \"sha256\": \"b78710790d026b3f2af9502f0a6dd7a7a3226ce295e15e09cbb3fd678fe890bf\",\n        \"size\": 359248387\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24318_Weather7.tar.gz\": {\n        \"sha256\": \"220aaf14e5f0ef4c8f11ecf07f598af1c3151493a117674ff41d0ca234d883f3\",\n        \"size\": 509741264\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24328_Weather19.tar.gz\": {\n        \"sha256\": \"39b504c37f83712378ff4e2e253ea415506aa15cd86ab4cd627a35ec92bf0584\",\n        \"size\": 373580107\n    },\n    \"HazardAtSideLaneTwoWays_Town07_Route24378_Weather23.tar.gz\": {\n        \"sha256\": \"a2c5339cb600f52ae65897d2835704b43df08929537f19bce6e890beb501224d\",\n        \"size\": 486837344\n    },\n    \"HazardAtSideLaneTwoWays_Town10HD_Route24290_Weather1.tar.gz\": {\n        \"sha256\": \"666e4283913cc85015e791d12ebd2e8e149efeb3457a8097279d4fc1607d2e3e\",\n        \"size\": 273318260\n    },\n    \"HazardAtSideLaneTwoWays_Town11_Route25298_Weather23.tar.gz\": {\n        \"sha256\": \"9127c72a25c292db7d2840b8ac534b3b622e09402f2d176c308134ac71a8b01b\",\n        \"size\": 74587620\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1864_Weather12.tar.gz\": {\n        \"sha256\": \"22407024f3a521675d24ccf7fb0bfa6cece0d521a983edae4d872a6e6f14d762\",\n        \"size\": 466488176\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1865_Weather13.tar.gz\": {\n        \"sha256\": \"72555edf6914b5e82842d4d666ff8c0620f0644d28447e1a3670f7e0c1c60119\",\n        \"size\": 143510797\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1866_Weather14.tar.gz\": {\n        \"sha256\": \"88aea8f69b4d9ff98e63175d1e321c63e342360fe7841b0e9de1cc76412779e5\",\n        \"size\": 185980386\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1867_Weather15.tar.gz\": {\n        \"sha256\": \"675a55ded4000321ea905ce5bbed6c2e17cef958d0f2662022199c7c0334f388\",\n        \"size\": 304292089\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1868_Weather8.tar.gz\": {\n        \"sha256\": \"11877ed1cef8f65a61381c53d9138e3445af1f2924103eeb7e4277a10bb55c0b\",\n        \"size\": 363311974\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1869_Weather9.tar.gz\": {\n        \"sha256\": \"07416b1bb05dc217d2fe0466081b6023e4255025225150c8f4024903274390be\",\n        \"size\": 211636768\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1870_Weather18.tar.gz\": {\n        \"sha256\": \"0ff4eb08e4f60cc5555269ca5be47f019aa8a431ba349a5fa6f98ee8b99732bf\",\n        \"size\": 452810181\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1871_Weather19.tar.gz\": {\n        \"sha256\": \"5280963a79d47d848f7d0e44eefb1a4db0f5a2900068e1a8da833490312ad770\",\n        \"size\": 391837761\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1872_Weather20.tar.gz\": {\n        \"sha256\": \"00a82495dadc9964b28494c0b4634e62432ab647dd10345bddaf830b83957dd4\",\n        \"size\": 287522398\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1873_Weather21.tar.gz\": {\n        \"sha256\": \"fa54bd1630ea0201c824b04a8fb2c71e340433dae53fb0130498af1b1414138b\",\n        \"size\": 477539283\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1874_Weather22.tar.gz\": {\n        \"sha256\": \"a67bac4cf6f3a41052ae738e133dbc3430d332b7088234d6017fa109b84d45a7\",\n        \"size\": 761010165\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1875_Weather23.tar.gz\": {\n        \"sha256\": \"c7d3f5a4ed3d789d538e54d49b100a460e3b6074debcf7728ce456e606252f6a\",\n        \"size\": 145438806\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1876_Weather23.tar.gz\": {\n        \"sha256\": \"e086d3b1943415fad2ffe42116654af811f400aea9f669fc1395ae947c0b5b6c\",\n        \"size\": 299943930\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1877_Weather25.tar.gz\": {\n        \"sha256\": \"85fa396e5d47a29525e34c5f19971a47679e152c9031671d2bd9e1e9328a5889\",\n        \"size\": 154539212\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1878_Weather0.tar.gz\": {\n        \"sha256\": \"edbb43473251e0b8a5a62dcb5da2c3faf07348f188b4e398cccf7dd29d3c8a41\",\n        \"size\": 600462109\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1879_Weather1.tar.gz\": {\n        \"sha256\": \"b68c5d5eda8c0c050100f1900f79bdf5fffae151a0ed4695b5c2d23861fd31f6\",\n        \"size\": 384483752\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1880_Weather2.tar.gz\": {\n        \"sha256\": \"3a1f7b027cc55989db783cee01b2f6dea73f12f361c3a625c3f53250de4e4c51\",\n        \"size\": 565730155\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1881_Weather3.tar.gz\": {\n        \"sha256\": \"5a1f40d4a80428998b07f519ae7cf9c8882f02567fa9d2926a9e1455bd62f9c9\",\n        \"size\": 401430317\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route1882_Weather3.tar.gz\": {\n        \"sha256\": \"eb659960e7444a0cfb019714de1ede256ea410796297ca9756f16f6299af1774\",\n        \"size\": 431281500\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route20993_Weather10.tar.gz\": {\n        \"sha256\": \"a88d6283ad6bd4497ec568dba38e6a98afe25ff22db91e6f93a043ee73bde9d7\",\n        \"size\": 429386497\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route20996_Weather13.tar.gz\": {\n        \"sha256\": \"6aa763f288f38c074ebb512ecc650670f47d5df06e6f54740e5af68dca008e69\",\n        \"size\": 166412680\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route20997_Weather14.tar.gz\": {\n        \"sha256\": \"28b0e8fdbb762483b55a8368d71d049c75bff0354409b136b5c154ef7921e36f\",\n        \"size\": 153713884\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route20998_Weather15.tar.gz\": {\n        \"sha256\": \"c6837d3388bf101a53a938aa23e4e8791f52a6a201253bf72989891109880d1b\",\n        \"size\": 342209342\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route20999_Weather8.tar.gz\": {\n        \"sha256\": \"f042a81d8f3a45ea338c651ec86875dec6be91a39e2c02551e74c5558dafb81d\",\n        \"size\": 296547462\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21000_Weather9.tar.gz\": {\n        \"sha256\": \"2457d8483cec7e6cdebb0cd48321e358149f50f6d3a8c5c2b7f4305a6d47b896\",\n        \"size\": 315098592\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21001_Weather18.tar.gz\": {\n        \"sha256\": \"504ab97e65ce9207e61c0f5caee53935e9de5c805548081fdc1fb584a0dac0a3\",\n        \"size\": 386012192\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21002_Weather19.tar.gz\": {\n        \"sha256\": \"3f9a526bf979d1c47f8b690d028eb084ab79f1f8010f59dbea37c3d4e948bd33\",\n        \"size\": 313057065\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21003_Weather20.tar.gz\": {\n        \"sha256\": \"138d6cfacdea8363707e0b16de7935d96f32a74ca3713d8526e277066148470b\",\n        \"size\": 194778086\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21004_Weather21.tar.gz\": {\n        \"sha256\": \"8a06817d111c0bd21064c4a7fef9bfe3e1ef62f6ca86c1494feb55b40e9c1f2a\",\n        \"size\": 146868137\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21005_Weather22.tar.gz\": {\n        \"sha256\": \"83a076dbd932e50b6b7572f25554f62e70c085c344c3c9f8d8abe6f42c1fcd9c\",\n        \"size\": 145665541\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21006_Weather23.tar.gz\": {\n        \"sha256\": \"f53d6e20cf73473a14d2dc7470b6b34dff1cde537b5cf96a46e2bd4ce74f7f00\",\n        \"size\": 148410964\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21007_Weather23.tar.gz\": {\n        \"sha256\": \"010ab99155366aacb3db038a223ac252e66a035dfff1d8853fae927e1a1c4674\",\n        \"size\": 134240188\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21008_Weather25.tar.gz\": {\n        \"sha256\": \"a3d164b799b170fcd201b1b3e7d32626ea8b941654e07ea8de742fa7da02e08f\",\n        \"size\": 267735408\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21010_Weather1.tar.gz\": {\n        \"sha256\": \"35216fe9f1c2a570bfda2c476ce1caeb1f3769ba577d5c03a3fc2b14b5ef32f6\",\n        \"size\": 222404763\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21011_Weather2.tar.gz\": {\n        \"sha256\": \"4a194c4c09a23f51ea895d9e61eb1822de3b053ded7d1a91f363a1eb22b80bcd\",\n        \"size\": 376635768\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21012_Weather3.tar.gz\": {\n        \"sha256\": \"16f831814d8ed74d704a4cd684b5c81079415d9b586437cb954d502496f6a72c\",\n        \"size\": 461465565\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21013_Weather3.tar.gz\": {\n        \"sha256\": \"91ccf0ca75693b587ecd570b7b670b615102216cae89900eef0b7d93e720e608\",\n        \"size\": 490199384\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21014_Weather5.tar.gz\": {\n        \"sha256\": \"bc67c8733d9fb8f032647aaed13e3c3c40d1ebd48744010f0c5184fd7a35db42\",\n        \"size\": 543773232\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21015_Weather6.tar.gz\": {\n        \"sha256\": \"f1ad73e3ea227c52ee770088c6438cba8642c3cd97c55ee9c257fb844dd255e1\",\n        \"size\": 475049192\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21016_Weather7.tar.gz\": {\n        \"sha256\": \"ca4368f7e54ff638991810a119f58f46bd4deaeb9256949fda8bff05dfbeff06\",\n        \"size\": 550568247\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21018_Weather9.tar.gz\": {\n        \"sha256\": \"523f59e0534fb35900c15a3dba9273f76d079e1700274dce19306f36bbc08d58\",\n        \"size\": 439323688\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21019_Weather10.tar.gz\": {\n        \"sha256\": \"328b45214265f78f7afb9fbced0485b7b6e9c9ed3ee6cacbe9842c6f1ccc2663\",\n        \"size\": 387031346\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21020_Weather11.tar.gz\": {\n        \"sha256\": \"39e15119c793f5212c2ec02639aa2710d1ebe4d63ffadbef2fded6c8eebe31f3\",\n        \"size\": 417862699\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21021_Weather12.tar.gz\": {\n        \"sha256\": \"c681307b7867f34463e50276a034ad21d68c4221cb26ac849174855e58705647\",\n        \"size\": 410357030\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21022_Weather13.tar.gz\": {\n        \"sha256\": \"3e95d2ccc97ce08503e5fb92186190a26100d593054b3b562f9706fa89d8b9a7\",\n        \"size\": 296707342\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21023_Weather14.tar.gz\": {\n        \"sha256\": \"3bb30a62b62cfed856d08c7adb2acd23f8fe5e48de1f89a4b32065d9ae4d7605\",\n        \"size\": 410800522\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21024_Weather15.tar.gz\": {\n        \"sha256\": \"084675b503312fca38205f9e6c95de7bffa851f0457370a809fba5f55ccd6319\",\n        \"size\": 330818855\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21025_Weather8.tar.gz\": {\n        \"sha256\": \"3a8971545e34280e1bbe6850e62bbf386175edececf0b82fd2ef5ece1b8b0bb0\",\n        \"size\": 336618643\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21026_Weather9.tar.gz\": {\n        \"sha256\": \"ec3444a2980de45ca563c512fe696c7345a0c5280cfa17782ea07c9d7fc595c2\",\n        \"size\": 226040081\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21027_Weather18.tar.gz\": {\n        \"sha256\": \"d78f5ea24c679a5c563429e318be9b32cc5402ee9a282d9c96f93288fc0a512a\",\n        \"size\": 338382098\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21028_Weather19.tar.gz\": {\n        \"sha256\": \"df45f3118d62bf189e448225ceb178ade4121a3288ffced5043c3686b1ffc90b\",\n        \"size\": 415766550\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21029_Weather20.tar.gz\": {\n        \"sha256\": \"027bcab981599a0758c671c02ec4594becef7b81afc980cf56dc425e7267893c\",\n        \"size\": 340860827\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21032_Weather23.tar.gz\": {\n        \"sha256\": \"5ecbc841be9df05c3629ff839b67668729cdfbd6a47dfbc3e95d65f3525f1556\",\n        \"size\": 392371547\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21033_Weather23.tar.gz\": {\n        \"sha256\": \"932e1e24b2661da42800bf2feb636bfa06907e4835bbd0c53da6ab11d73474b2\",\n        \"size\": 457387725\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21034_Weather25.tar.gz\": {\n        \"sha256\": \"1c5cc3c9c136a185d8925a1b76a1f364a360a71e068d4df11bfe8f8ddfc128ec\",\n        \"size\": 460387961\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21035_Weather0.tar.gz\": {\n        \"sha256\": \"56bb7c99c281096d25fbb5a420c3eb43ae1a4cce3bca475afdc9bcea40ef9037\",\n        \"size\": 532918684\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21036_Weather1.tar.gz\": {\n        \"sha256\": \"5974081ef58543d8886530374612b487d14373238c8ccfbd6e7ab9edef874081\",\n        \"size\": 565791113\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21037_Weather2.tar.gz\": {\n        \"sha256\": \"4e94bb7510243eb73c740f3415b5bcf44296a211ce0d50fa2d866539cfd56e03\",\n        \"size\": 388666513\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21038_Weather3.tar.gz\": {\n        \"sha256\": \"2fc64d3eb6984469f4189873cb14b74be8e943fee8c3ba06e6bcd0f0d75fff9b\",\n        \"size\": 488022533\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21039_Weather3.tar.gz\": {\n        \"sha256\": \"ef2ce2bc2d582cb1db42984a7da763664bf7c47e4125ccf9950560482ba2b133\",\n        \"size\": 426596100\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21040_Weather5.tar.gz\": {\n        \"sha256\": \"64dd8fb7177c2b7a880fc08fb8e660c2f9e9c9b97cd47cf0c1ded3a4fa993c0c\",\n        \"size\": 478478711\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21041_Weather6.tar.gz\": {\n        \"sha256\": \"10363a44e0470fe13da2d18d2bd058f358590b2ed360a2444977f9f2938117aa\",\n        \"size\": 457735862\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21042_Weather7.tar.gz\": {\n        \"sha256\": \"1647d4674f5bbd6d0514c19641fde32e8bbb442f997d9bf2951b07dab9506014\",\n        \"size\": 548265557\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21043_Weather8.tar.gz\": {\n        \"sha256\": \"4f49fa6b05312ea3ce4432d6948b313bdb98593acdeb47e3b47ae9f011c7a459\",\n        \"size\": 283635120\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21044_Weather9.tar.gz\": {\n        \"sha256\": \"082819f4479db31e14bf005128ba07792525b9056a7778d50f2130de20f6a2e1\",\n        \"size\": 132597770\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21045_Weather10.tar.gz\": {\n        \"sha256\": \"9069dfff65ec9d6eccba367d47b726302ced59dd598f0d791f4dfe30843ff043\",\n        \"size\": 181637108\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21046_Weather11.tar.gz\": {\n        \"sha256\": \"5b2c39fb7c84b8fbf95ff3a12964eec60c8128235dbaf1097ba78dd2bff49177\",\n        \"size\": 148380282\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21047_Weather12.tar.gz\": {\n        \"sha256\": \"0e59eb91f9c17ab4f85e63aec2afae539b95206469223543678716741858cd2f\",\n        \"size\": 139957080\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21048_Weather13.tar.gz\": {\n        \"sha256\": \"20e05b16e5dad329f707b9d9b5274f42d8b5176821ee96825f562313f3e8800e\",\n        \"size\": 153358527\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21049_Weather14.tar.gz\": {\n        \"sha256\": \"ab25d613498650f2917b56a9acb3289a74d2376e05dd081ebb794bb07688c34b\",\n        \"size\": 421303548\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21050_Weather15.tar.gz\": {\n        \"sha256\": \"65878b9256b09945f49af0a21a2883bd2c41c0398a266212ba9cae5fd8fc4a6a\",\n        \"size\": 287707706\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21051_Weather8.tar.gz\": {\n        \"sha256\": \"60eb32771b445fda9ad7d4dedf0a8fc3dbfb8568b6b1211f7d1992a2357c4f07\",\n        \"size\": 443146058\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21052_Weather9.tar.gz\": {\n        \"sha256\": \"4c4959259fb8e1a1a8d208b9c20983ecd130a29bef2a14ede3005251b2e9b806\",\n        \"size\": 751652708\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21053_Weather18.tar.gz\": {\n        \"sha256\": \"f81d5f0e30dc68254cf296783513bba6223564107fe390829de58634b929991e\",\n        \"size\": 181737371\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21054_Weather19.tar.gz\": {\n        \"sha256\": \"90b551db7c0c86df0de1e7daabc18e55601abb05c2382b8f2e88bb754fdbf3f4\",\n        \"size\": 292376583\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21055_Weather20.tar.gz\": {\n        \"sha256\": \"cbed2e9f2b82a96bb4f451e22c83876933a2efca4990c6bdd19f5f79f8ce7d41\",\n        \"size\": 358162095\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21056_Weather21.tar.gz\": {\n        \"sha256\": \"629ae2e70c10940dd9c4950f0ddf407a43c002459f2299d83b825e15c624ab94\",\n        \"size\": 183712692\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21057_Weather22.tar.gz\": {\n        \"sha256\": \"64878570d733d3dea356b941e7bdac9c7b06d15f46a910568c6bc7017210bcc6\",\n        \"size\": 158167932\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21060_Weather25.tar.gz\": {\n        \"sha256\": \"f992d95eda8cb65823c0861bfb56b489d49c16e66a1d829c7ae8b05756486782\",\n        \"size\": 125507241\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21061_Weather0.tar.gz\": {\n        \"sha256\": \"57df5006b2de857822aee111851fa07d5ffc4986ea190afec53d08fbc55d51c7\",\n        \"size\": 165785073\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21062_Weather1.tar.gz\": {\n        \"sha256\": \"7d18a20c584e7b68e15ddd0317f5a6adb0fe9894399a404cc63430d96ac5a94e\",\n        \"size\": 165301745\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21064_Weather3.tar.gz\": {\n        \"sha256\": \"b6da19f1dc781db1639ded757006687f9e324711be2413648e896978f8296bf8\",\n        \"size\": 170996416\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21065_Weather3.tar.gz\": {\n        \"sha256\": \"aec43b09fd9f7e125c5b479c17c4c4fec70da477884f645a18d7bff6c174b3d5\",\n        \"size\": 443935349\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21068_Weather7.tar.gz\": {\n        \"sha256\": \"538ab685060145b35e615391392468e135c5bec2092b3c03fe09e788962823de\",\n        \"size\": 196234059\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21069_Weather8.tar.gz\": {\n        \"sha256\": \"895450cd3efb33e7f54d5f8ef7c2fb7777f3a0f7c493bb08cfc9a009db1b0324\",\n        \"size\": 410669143\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21070_Weather9.tar.gz\": {\n        \"sha256\": \"69f96c409e5724caf41578622cf7e1808ce21b700ae934adcd96f872c5acaec7\",\n        \"size\": 425093238\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21071_Weather10.tar.gz\": {\n        \"sha256\": \"de9214f9da51e240e61fbb1907e0b64469c5c712b424a4413af003bc404468d4\",\n        \"size\": 349665674\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21072_Weather11.tar.gz\": {\n        \"sha256\": \"9c447d67eae4bad25cb83a573d3a3494398c7de6deb5eecef7c3546f9ecc0d16\",\n        \"size\": 332208664\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21073_Weather12.tar.gz\": {\n        \"sha256\": \"2b59ca9ceb966de82f560803b61768851882bc9a8fc1b6ee42632443885bb12c\",\n        \"size\": 400599928\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21074_Weather13.tar.gz\": {\n        \"sha256\": \"84b261aa3eb478778be08eb1570636618eb2b1e3eeecee50762ff33bf7c062cb\",\n        \"size\": 315779543\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21075_Weather14.tar.gz\": {\n        \"sha256\": \"93745f718ca660ce1b5ade1081566b985d25642437ec430d08795bcb5a483abe\",\n        \"size\": 458388155\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21076_Weather15.tar.gz\": {\n        \"sha256\": \"9a45eba54e14a9d7ce6717830314ebc3e126f998c01622a62abc310d17cc9ab4\",\n        \"size\": 391610246\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21077_Weather8.tar.gz\": {\n        \"sha256\": \"e79a2d0604d1088b73ecfb3bd116972be0c7833f28d72650247a01e01f217e5f\",\n        \"size\": 462920293\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21078_Weather9.tar.gz\": {\n        \"sha256\": \"6636398b97764709cf34b7b39db18ddce5efa46c805988e2d5255d019dec64ba\",\n        \"size\": 431685141\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21079_Weather18.tar.gz\": {\n        \"sha256\": \"4f8ba7a6d92e864984c8acffcca9028a68f09f85b448326e4692e850df47a849\",\n        \"size\": 427349535\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21080_Weather19.tar.gz\": {\n        \"sha256\": \"bb4ff290a6ac50158be1f3dd1735e35301158e9dd0a79c29deb4d612a223196a\",\n        \"size\": 353173870\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21081_Weather20.tar.gz\": {\n        \"sha256\": \"a2a9705fbb7edbcaa3b1de228975108d7a10f0bd624c1e44b911fb5ce641f7a6\",\n        \"size\": 370374832\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21082_Weather21.tar.gz\": {\n        \"sha256\": \"8ced78ef4cc8449a4e40cfc135a2f31782022a30ffa24051ae7b5dd8d2d23e2f\",\n        \"size\": 263036650\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21083_Weather22.tar.gz\": {\n        \"sha256\": \"3804b5a5a2b34c6eb6c3858d2d80010f989e26fd9188b9394fd9059afc73b671\",\n        \"size\": 404620431\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21084_Weather23.tar.gz\": {\n        \"sha256\": \"70b949ab278b146a9225e7f8af5303bc5dd6c46f7848c98223e6556e092aba7e\",\n        \"size\": 334504734\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21085_Weather23.tar.gz\": {\n        \"sha256\": \"12797eaf233ac929212349374f245981207a034b8beb6d1d0d3bfb5bbea02873\",\n        \"size\": 312573065\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21086_Weather25.tar.gz\": {\n        \"sha256\": \"b3bcd8b1b75c14366de77d7c4c9ba3fb477dab181ffa0d73834f8bda651d970f\",\n        \"size\": 388803946\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21087_Weather0.tar.gz\": {\n        \"sha256\": \"b18d535660a1c9edd0ae012e984a326f647106f31f040a2d3dbebe5b4cac28a1\",\n        \"size\": 435867954\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21088_Weather1.tar.gz\": {\n        \"sha256\": \"ef69243e923b97cd22a672e864b15fe08988e690f55e090b263e9ec91d19f6ee\",\n        \"size\": 474954209\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21089_Weather2.tar.gz\": {\n        \"sha256\": \"f61a818e19f3d7c42dda00edda67ab39a5b0eb665c070adf187490f6717463aa\",\n        \"size\": 510154715\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21090_Weather3.tar.gz\": {\n        \"sha256\": \"a6caf6baff826ba0d3449e031e29a479e90262d6d6cb7136dab7d5d6635907ac\",\n        \"size\": 538597002\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21091_Weather3.tar.gz\": {\n        \"sha256\": \"8156250be5a645598affcb5897006996d83fa5f6e02deb63f801a2d961f972fc\",\n        \"size\": 470749806\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21092_Weather5.tar.gz\": {\n        \"sha256\": \"8819cb85d5c6cf2c1596a1d556564087a1681294ff51601e846165efda3112c3\",\n        \"size\": 358604403\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21093_Weather6.tar.gz\": {\n        \"sha256\": \"20108355045ee3fd5516d3d608dd78b0fca6c299017bb71d5400f91788b8c997\",\n        \"size\": 527494698\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21094_Weather7.tar.gz\": {\n        \"sha256\": \"c9762752c14704b72f58293eba2b95d9ec923d13a2f4178cc6ec9dc4928700a6\",\n        \"size\": 442591145\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21095_Weather8.tar.gz\": {\n        \"sha256\": \"2d07067535610760b91573015197d1327fe1f537c0ccb53cacd8d9c3ef8c09c0\",\n        \"size\": 511423693\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21096_Weather9.tar.gz\": {\n        \"sha256\": \"7088aa8866018d94538fe0176d3e0b0f3f3afd0d2b58ff2dbc01b37355a16375\",\n        \"size\": 468901530\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21097_Weather10.tar.gz\": {\n        \"sha256\": \"e0840af3f7be30a99eb1d974001a44490b335117f49b253ac81c6f5d441e31c9\",\n        \"size\": 505902357\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21098_Weather11.tar.gz\": {\n        \"sha256\": \"4259651020f44be2bfac6c8a46898dae6c6426356e7c86252df0116964e76203\",\n        \"size\": 413881213\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21099_Weather12.tar.gz\": {\n        \"sha256\": \"e91001d2e854d95b175008ec0b2c92ec5fef137110c58fb3f127730bbc5dddec\",\n        \"size\": 287525027\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21103_Weather8.tar.gz\": {\n        \"sha256\": \"42fdb96dc7650a1b4dccf61b282c34c3385273b80b33de2ab522fc4e3123133d\",\n        \"size\": 420802429\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21104_Weather9.tar.gz\": {\n        \"sha256\": \"6d6f81ebe0e37f76d1ffe48566942c98c33a85723400b620a05502acfd98dc57\",\n        \"size\": 279309085\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21105_Weather18.tar.gz\": {\n        \"sha256\": \"7c8b8845d91fc8a0a6f08df50b506713f48248a82a40f37e5bf66a7fd04a61c6\",\n        \"size\": 371938250\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21106_Weather19.tar.gz\": {\n        \"sha256\": \"5cfb0135c83a768d8f9a2980f49c0d030b6661c4d990fb4e971f786d3408d9c5\",\n        \"size\": 224266749\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21107_Weather20.tar.gz\": {\n        \"sha256\": \"b631e4c1ccd218f505b4f579636f2eeb6acfd5d04d9abf7bbc8d56a026979fc2\",\n        \"size\": 448409381\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21108_Weather21.tar.gz\": {\n        \"sha256\": \"cac2572caa041032c8a5d11367fab0e3dd78f0e56163c145f400e9fcc22ba54f\",\n        \"size\": 162325651\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21109_Weather22.tar.gz\": {\n        \"sha256\": \"83be3292330b934eb9335b7c090626e49385eff55bb243ca9a28aef034cc16ca\",\n        \"size\": 150422028\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21110_Weather23.tar.gz\": {\n        \"sha256\": \"7964a35539188762fc09d73756cd4fb666981b483617a39b5c8b1d403bc62ef4\",\n        \"size\": 123233341\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21111_Weather23.tar.gz\": {\n        \"sha256\": \"cb92d038c3b0c755ac947914d2151f7a959be2d50f2e6ae825c0ac2a9f9b6373\",\n        \"size\": 151891327\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21112_Weather25.tar.gz\": {\n        \"sha256\": \"b8fa440b1a85bab08bcbd26b36678fff728c24444730fe8183b874ac22dbf42d\",\n        \"size\": 151269342\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21113_Weather0.tar.gz\": {\n        \"sha256\": \"3166e4c2b6522d1dd95fb192c57c4b3c00d489ce0dbf875d350c95f6dcc7b2fa\",\n        \"size\": 289646157\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21114_Weather1.tar.gz\": {\n        \"sha256\": \"093b3ad02610fd6715315b5f7db90732f05a85523074c5586a72fb0714c57463\",\n        \"size\": 286423854\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21115_Weather2.tar.gz\": {\n        \"sha256\": \"ef91b385f078268d37fb860ad1e5f475b0181eac920284f4ef372a8a66c3b569\",\n        \"size\": 171497259\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21116_Weather3.tar.gz\": {\n        \"sha256\": \"972e0f0b89c1baef17dd08f305be0e60115fcc1b2452d46779669dc8e058e058\",\n        \"size\": 136326442\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21117_Weather3.tar.gz\": {\n        \"sha256\": \"690818f8488076b9771262e43a26e78d708909f03dc0aa1a5a2f81c2af5eb4fc\",\n        \"size\": 349616340\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21118_Weather5.tar.gz\": {\n        \"sha256\": \"c965925be504c900dfb4adef0aa107c954ec6edfc3921dbe4fd990ee59026326\",\n        \"size\": 460158881\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21119_Weather6.tar.gz\": {\n        \"sha256\": \"42bc1740c9bffb0c68d1cb3133cc26e491f5cd61293066b17bf5af75f1284044\",\n        \"size\": 429769128\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21120_Weather7.tar.gz\": {\n        \"sha256\": \"080aae2a723e6626dccad516ba5f98563f4371b3de5703f2563212e45bccf78b\",\n        \"size\": 184989759\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21121_Weather8.tar.gz\": {\n        \"sha256\": \"152b681a9795a64b2c19e44beceeda1f77fec31fcfe54981d6277bab1fcc9ff5\",\n        \"size\": 374813536\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21122_Weather9.tar.gz\": {\n        \"sha256\": \"42d16734cbbc3c97ffdacaf215406fb827beadb00f065ba6aaccc8b59d67fb41\",\n        \"size\": 297690121\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21123_Weather10.tar.gz\": {\n        \"sha256\": \"580d056116555a477d03947930513d71e78d1fdc8a992e38939db56a8a2af7b3\",\n        \"size\": 168852185\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21124_Weather11.tar.gz\": {\n        \"sha256\": \"94dfff1383ffc3ac333c2efd968cb7cec08940bbbda2d8ec24f7b75a28d25522\",\n        \"size\": 152333375\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21125_Weather12.tar.gz\": {\n        \"sha256\": \"0c2be15221b516cce467891fa167ed783598de61120b56ecdcffc6ae9ab9e652\",\n        \"size\": 141026316\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21126_Weather13.tar.gz\": {\n        \"sha256\": \"2e6a0a7b12ef4f2bbfeca9585c778582e02db489cf6e399d46c8f277f4595856\",\n        \"size\": 173025702\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21129_Weather8.tar.gz\": {\n        \"sha256\": \"ecf1eaa740c43577c670cc6b475b17db3c92ada0123a3ba275312849def7523c\",\n        \"size\": 441775360\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21130_Weather9.tar.gz\": {\n        \"sha256\": \"ddb7713c52c5f03f4288bcf6e11632d2e530acdf118c7749afb265e14bfdeeca\",\n        \"size\": 346412958\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21131_Weather18.tar.gz\": {\n        \"sha256\": \"e3f972db9172331086af1bcd16cde0b60ceca9552217b6a73408a7bb4ade0f3a\",\n        \"size\": 477146611\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21132_Weather19.tar.gz\": {\n        \"sha256\": \"d27b0439acc484ec564266a61f35b7b971322b571b6b8d0178ce21de21b484fc\",\n        \"size\": 501824738\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21133_Weather20.tar.gz\": {\n        \"sha256\": \"355ce9a2365b1066403e025207262580506a94a6d92d8b5572dc2d211eedfc33\",\n        \"size\": 483676041\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21134_Weather21.tar.gz\": {\n        \"sha256\": \"7eb8c1c4ea85f8c276372732e36b0e20b234458c87a35ae82c14eae48319717d\",\n        \"size\": 403059884\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21135_Weather22.tar.gz\": {\n        \"sha256\": \"770963f066c928a969b7177bd6095fb09a18a107650ce4aa6675b92994b85b18\",\n        \"size\": 371722880\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21136_Weather23.tar.gz\": {\n        \"sha256\": \"3bb314e3d84d4f8eea2d5781e75c67174090506f3ac50126210f2980cdd79edb\",\n        \"size\": 372938192\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21137_Weather23.tar.gz\": {\n        \"sha256\": \"970606af41b36023cbde50f0231075fa6bb14dd0899f3b1cd7e89a605bca4ba5\",\n        \"size\": 380885390\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21140_Weather1.tar.gz\": {\n        \"sha256\": \"d35b0075577e15babd1fc0b0b852d427b03e25eac9b43f1c33dbc545f428d093\",\n        \"size\": 385649475\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21141_Weather2.tar.gz\": {\n        \"sha256\": \"c484f8322a24d15d40356491f0e49a8f9704c348f548a17dc04718d40adb96e5\",\n        \"size\": 220126041\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21142_Weather3.tar.gz\": {\n        \"sha256\": \"eae68aef47cf64a4b558501fa81966c5e85a2c7906342000cc7cf57b454ed5a7\",\n        \"size\": 342728501\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21143_Weather3.tar.gz\": {\n        \"sha256\": \"e81513a9b82db6fba0aeea722a5e806b5c64cbf7dfd07ebe9b4f9930ba2bb12f\",\n        \"size\": 455566005\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21144_Weather5.tar.gz\": {\n        \"sha256\": \"797cc2ba7fabbe7aa7098421c8265b0e03e773ffcc26ab9502981e88fadd2af9\",\n        \"size\": 483226115\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21145_Weather6.tar.gz\": {\n        \"sha256\": \"de4d60100c0d859f20b1cf3893a8c07c9b6ab32b11a3f05a97187aa75931a72a\",\n        \"size\": 440552025\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21146_Weather7.tar.gz\": {\n        \"sha256\": \"0a2f8e07c27fdcb4ae1adb28da67335c71997099c74a259fec406fa36d78f724\",\n        \"size\": 395671270\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21147_Weather8.tar.gz\": {\n        \"sha256\": \"ac2676ff8acb45ad061de138f86361fbae71000ce6f19a140dfe2a4c8cf71bb1\",\n        \"size\": 199339886\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21149_Weather10.tar.gz\": {\n        \"sha256\": \"2a30faf27ef46176ba74f0cffe6a84ada7667af9922da64c5f21315c8f4413f8\",\n        \"size\": 167078157\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21150_Weather11.tar.gz\": {\n        \"sha256\": \"11b016d748ce1c24cb09f745eb763d8aa0bf74d34fdc37d1e259d373586cb95b\",\n        \"size\": 127589301\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21151_Weather12.tar.gz\": {\n        \"sha256\": \"2a0b4156c1747502e67068d1f68b3f4dab02cd1ed0680dbfa7349b99edbce188\",\n        \"size\": 149048142\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21152_Weather13.tar.gz\": {\n        \"sha256\": \"c454aae002e8ecb5cf5f93c0f9ff318eea4434e7f52feebc55ec54844a3fd243\",\n        \"size\": 156710556\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21153_Weather14.tar.gz\": {\n        \"sha256\": \"53ac393f5961bc9816e3157108b9284d9b56ef238008f032cd9da616f7e52def\",\n        \"size\": 145652828\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21154_Weather15.tar.gz\": {\n        \"sha256\": \"d977ade0a96e04881511727bba7a7783c4f26f0de8695bdb275de6dc832f37b7\",\n        \"size\": 372026102\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21155_Weather8.tar.gz\": {\n        \"sha256\": \"f3e387482c07ebe493f9b2904dd85e43f0558db237fd90f9af98571934e0fad0\",\n        \"size\": 567876837\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21156_Weather9.tar.gz\": {\n        \"sha256\": \"1fd666b10fda9ae482c43dd4b67ed8016efb0ac20f916a2f94340de379001030\",\n        \"size\": 519966282\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21157_Weather18.tar.gz\": {\n        \"sha256\": \"45145ae40b216332fcfe65854ac2ac36e2998ca5725dd251284122e8a4a20178\",\n        \"size\": 531818059\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21158_Weather19.tar.gz\": {\n        \"sha256\": \"93373dc431dc817300e64551aed59072aa1bdff273b7414a3d6ad6073d1b4e92\",\n        \"size\": 458351558\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21159_Weather20.tar.gz\": {\n        \"sha256\": \"e12055abe3ec7cf4c8a9f5bdf6ea428a0beb6e1bb4533714d3ffdbf695cd927a\",\n        \"size\": 357225662\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21160_Weather21.tar.gz\": {\n        \"sha256\": \"5b9eff05129dae83209c2de547c8156faf831966095c33ff382379fea829534e\",\n        \"size\": 460563766\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21161_Weather22.tar.gz\": {\n        \"sha256\": \"6138bbb514086abdd6de7563482e070f9d577f0816df67ef30efb155838f379c\",\n        \"size\": 373620042\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21162_Weather23.tar.gz\": {\n        \"sha256\": \"e92e45e5af4079ef92ebf75236879e5b73f85ddb2bd1eaa0fb2d20cebe36b67d\",\n        \"size\": 324298172\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21164_Weather25.tar.gz\": {\n        \"sha256\": \"8e946aaab0899355913ab38f6ca763af1559b280fc18d9d6277efd2c0f1a6f7a\",\n        \"size\": 301490625\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21165_Weather0.tar.gz\": {\n        \"sha256\": \"667eee6a8bb79d23464eb18468d7b9a7e89af44897e5c78d550c16b1ec91bd09\",\n        \"size\": 185309667\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21166_Weather1.tar.gz\": {\n        \"sha256\": \"dc67259d52e487ecbc6cb9350fd6577e23c5441e32bff51c927728cd168ed64c\",\n        \"size\": 149294669\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21167_Weather2.tar.gz\": {\n        \"sha256\": \"1cd7ca1e420a195ca11678d7e2475729279abd165d74db632d6370ec1fa1033a\",\n        \"size\": 202094789\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21168_Weather3.tar.gz\": {\n        \"sha256\": \"db10c11c1dbb1e7cbfbe691be548afe643409858886c293984c26f937d4b530d\",\n        \"size\": 414760389\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21169_Weather3.tar.gz\": {\n        \"sha256\": \"53bd7a816042f8bece17dc33324399f8ff0b728032ddba9dee01cbdb0d06c290\",\n        \"size\": 270004012\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21170_Weather5.tar.gz\": {\n        \"sha256\": \"919ddf9d056252cbada2cc45d2a14488f44ec90d3823ada3c4e0b6e982fdbaa6\",\n        \"size\": 406454864\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21171_Weather6.tar.gz\": {\n        \"sha256\": \"6b5b997adf7f3ed46d1923251f415039419d3420b77c83def2af5e9ce22222af\",\n        \"size\": 461270030\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21174_Weather9.tar.gz\": {\n        \"sha256\": \"8b0fb79a3676617d7a2119450ccf463f30cf98296d3c62f47d7bc02e932a6f38\",\n        \"size\": 433352549\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21175_Weather10.tar.gz\": {\n        \"sha256\": \"6a3edc33a71019e77cdc682ed8c0b1ce87bb3551d94c4abfedf420e445ed7045\",\n        \"size\": 367759681\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21176_Weather11.tar.gz\": {\n        \"sha256\": \"307fb97e7baaa0979f08b6f9cdf4d275679db591b3a97bebf113dd88327b3a61\",\n        \"size\": 444926350\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21177_Weather12.tar.gz\": {\n        \"sha256\": \"94e3f683a1c388daeba257c9ecb36d4dfc0ec12b31254a2c9a61cb0ac4815dd4\",\n        \"size\": 390484789\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21178_Weather13.tar.gz\": {\n        \"sha256\": \"c78f12866cea97ceafff5ce095879b0e23a272dd2afd7cbc9f963ad738ca1608\",\n        \"size\": 402693706\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21179_Weather14.tar.gz\": {\n        \"sha256\": \"5329c0d9729dceee77a991d01547c94e3c9d159eb9592c8e4ca1b63bc40c9eba\",\n        \"size\": 508595988\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21180_Weather15.tar.gz\": {\n        \"sha256\": \"d2eb2788273952c8685bcfb3cede1b212df4c1084aeae230b97948654b315932\",\n        \"size\": 430001590\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21181_Weather8.tar.gz\": {\n        \"sha256\": \"5d8a9174618b35eb7213c184ff3baaf3efba1ec05739df0682849103d6cf9af9\",\n        \"size\": 510470499\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21182_Weather9.tar.gz\": {\n        \"sha256\": \"effcedeb47f8264697c22a449ad09b7c262b7b9d6fe38e5103f2a5486dfc7e81\",\n        \"size\": 358935002\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21183_Weather18.tar.gz\": {\n        \"sha256\": \"0e6e9a5f7aa3057475bfa0436e75ed021973b02271b2efdd9162478f55834d9a\",\n        \"size\": 426490343\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21184_Weather19.tar.gz\": {\n        \"sha256\": \"6a575aa18d48029524fe5bca4bc2a4eb416d362fb2948cebde7b4b44aac4a9df\",\n        \"size\": 339856455\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21185_Weather20.tar.gz\": {\n        \"sha256\": \"d8f21f3a8d878a4843d0f6020aaa449334523fecc6d1694a1a2df841beb1c2d4\",\n        \"size\": 381559930\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21187_Weather22.tar.gz\": {\n        \"sha256\": \"0f0a61ac57eb91770a18188af3518ff61364b92d442b8db79048a78aabf86968\",\n        \"size\": 278266824\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21188_Weather23.tar.gz\": {\n        \"sha256\": \"838974f3b9f955f46a65017c639d7581aeed90833eba0f64c0789845043d0498\",\n        \"size\": 339606984\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21189_Weather23.tar.gz\": {\n        \"sha256\": \"5aea1e0d9b6032a08fdafb343b34874d4a22c97fee831264da732711c61ecac7\",\n        \"size\": 378288832\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21190_Weather25.tar.gz\": {\n        \"sha256\": \"a0b9e57ceb713d884395947306ee3c1e2b74c53144228c2e007bdcdd1d9ca199\",\n        \"size\": 406982058\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21191_Weather0.tar.gz\": {\n        \"sha256\": \"8394151ffedaf72af14dc7ad3dc2750efe80a643f011fb7de2dcae9d7f3254f8\",\n        \"size\": 533547844\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21193_Weather2.tar.gz\": {\n        \"sha256\": \"636da3ad1967dbc7844ccde7593b328f41bb5918bb0bf99f7163c3e1649d88e6\",\n        \"size\": 384962051\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21194_Weather3.tar.gz\": {\n        \"sha256\": \"46dc450b212a9452eaae6ff903d27f3838e167e7433e9423c9b8879e24b1f14c\",\n        \"size\": 550563911\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21195_Weather3.tar.gz\": {\n        \"sha256\": \"55dd1829ce4876d1f5ddd6e319f36bdac501e8b281f10435e0afe820da0f1fc1\",\n        \"size\": 364468743\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21196_Weather5.tar.gz\": {\n        \"sha256\": \"de3fa91fa3df82b111cef133ecc3b6eac9886a23c419e65c573c9dca6254e9cb\",\n        \"size\": 301996866\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21197_Weather6.tar.gz\": {\n        \"sha256\": \"4ee5de70486f5c80794d7f73cc670ca5f8c3b0a278aca1651d970103dd807b97\",\n        \"size\": 470158864\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21198_Weather7.tar.gz\": {\n        \"sha256\": \"795726469cbe19518b8e6c673844e62e929587c6c15f73bf293b6f2f978ac937\",\n        \"size\": 504292905\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21199_Weather8.tar.gz\": {\n        \"sha256\": \"0b009f785647d7b245280822b469ba1d434f5c43c7b08276b836638eeb66381e\",\n        \"size\": 424449540\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21200_Weather9.tar.gz\": {\n        \"sha256\": \"8f43aaedf6f105ffeb22738fd75b70912fbb382067470215ba19a880a6eaa0a6\",\n        \"size\": 422731317\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21201_Weather10.tar.gz\": {\n        \"sha256\": \"28a3059da5a307e5e340b150978bf3bb7ea1e9b6026b6488a0276e1aa8e13344\",\n        \"size\": 377163142\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21202_Weather11.tar.gz\": {\n        \"sha256\": \"a79b75410e1cc8816e63afc321f64a3927578c35ee84c948077b022294ea276c\",\n        \"size\": 328669010\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21203_Weather12.tar.gz\": {\n        \"sha256\": \"2af2216ab5414538d55ab3c2a3434eff6463ef98698a3530c9810d23d3b2f3f4\",\n        \"size\": 226513708\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21204_Weather13.tar.gz\": {\n        \"sha256\": \"743efb3c84aa2c5e293e87ec77cd6ca1dd243dfb68e5eeff5f170d60ead9a593\",\n        \"size\": 389854715\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21207_Weather8.tar.gz\": {\n        \"sha256\": \"f9c1618c47196458a9b9d9ef0e90924ed0f553a0bdcdc2c499949b6883f613d2\",\n        \"size\": 384338842\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21208_Weather9.tar.gz\": {\n        \"sha256\": \"0213c816168a530169b6748ec83ca883dd97c691ca8245a2e09c9a0b8e179ac9\",\n        \"size\": 389536382\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21209_Weather18.tar.gz\": {\n        \"sha256\": \"872b49914ee558ee56476c38e5fe974bc4d2094dcd4d1385853dc0c05c1a5f31\",\n        \"size\": 522118240\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21210_Weather19.tar.gz\": {\n        \"sha256\": \"c9100bd31d940fa88e868de7900281a54a02257c24706fdaeac5e7294b715938\",\n        \"size\": 445155745\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21211_Weather20.tar.gz\": {\n        \"sha256\": \"a566858586acc794467899f6d4107ae6fac9883a503651d78520f6b5ad611174\",\n        \"size\": 165588530\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21213_Weather22.tar.gz\": {\n        \"sha256\": \"cce27c01c8d38f0c17a8d14ba7641186cc83bb095ea1f18d63c2c5234f256531\",\n        \"size\": 260771243\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21214_Weather23.tar.gz\": {\n        \"sha256\": \"3ca1ef3dd2c60808eefea0885656965d3d45b97b84d9ade677f728ca3b5823f3\",\n        \"size\": 423237177\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21215_Weather23.tar.gz\": {\n        \"sha256\": \"b2d11bdaf79ec74997f044889a582ca971fa47f78738267c6dc21c7fdf14ff81\",\n        \"size\": 381967845\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21216_Weather25.tar.gz\": {\n        \"sha256\": \"de90252d50991a4f6e10f40adb92fc75c916cc1c3fde08d60d4f20530cc695e0\",\n        \"size\": 465344382\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21217_Weather0.tar.gz\": {\n        \"sha256\": \"1429cde187b7dbfa292e7cc47f83a737f166a7a60b1301421eec76c247b592a2\",\n        \"size\": 428426167\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21218_Weather1.tar.gz\": {\n        \"sha256\": \"6feca4a5f9ff2d8c4b7e3f83163db78ca18216ceb96267040fc56211dad7b882\",\n        \"size\": 492585711\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21219_Weather2.tar.gz\": {\n        \"sha256\": \"e776d191ebe3adf74b4cf0350a786d6a03f2595c1a3a087fbba4d69987f88f15\",\n        \"size\": 515362834\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21220_Weather3.tar.gz\": {\n        \"sha256\": \"8def4c14bd184ceca33b13fffeb47a6d822fdc36c6935d05e6867df57a766b0c\",\n        \"size\": 545599141\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21222_Weather5.tar.gz\": {\n        \"sha256\": \"d2dd1bc5745b8e1827608b86ced43878766b5f251bc5c2d4abad778016b57aa1\",\n        \"size\": 310881973\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21223_Weather6.tar.gz\": {\n        \"sha256\": \"e46479b8ca04c21136970bbebe08e2f3ad552a7a3d541de2ff0b2c65da8552d4\",\n        \"size\": 374419774\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21225_Weather8.tar.gz\": {\n        \"sha256\": \"96bbd036f42d548dcede59fa7068f7a32f089b226c814b27ac963e231a4be7ab\",\n        \"size\": 460726747\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21226_Weather9.tar.gz\": {\n        \"sha256\": \"e043a2b6f0d1dabaf61f079499a103f9e7f3a609f94a58c6dec3919f4e7d3963\",\n        \"size\": 432634392\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21227_Weather10.tar.gz\": {\n        \"sha256\": \"46e8833447a1fdab389757c651200ff495d99dda75e30006d8f5f5d241f63220\",\n        \"size\": 430272036\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21228_Weather11.tar.gz\": {\n        \"sha256\": \"203b50777d05506f6c4c3f15a71d5d75f027f272e926e67aef36e276a3328ea4\",\n        \"size\": 300859057\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21229_Weather12.tar.gz\": {\n        \"sha256\": \"62780eb2e6f422fc3168c4417bad172141ace6e17b212aa973bb44efc009a631\",\n        \"size\": 247806519\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21230_Weather13.tar.gz\": {\n        \"sha256\": \"61e0756a40a02426f708b4ddd9cc4ceaac88a55fbf41425d10fe16f7a7d1db70\",\n        \"size\": 139191418\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21231_Weather14.tar.gz\": {\n        \"sha256\": \"73d0de0436da7975b71b128e3089dd2a02aa0bc39adf1c4584d27b35702eb497\",\n        \"size\": 165117705\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21232_Weather15.tar.gz\": {\n        \"sha256\": \"f575d42cbec0fdac27b91dbe3cc675eea56ed0324031db2cc531fca0af5935ea\",\n        \"size\": 265647676\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21233_Weather8.tar.gz\": {\n        \"sha256\": \"03b51251d283cd89d1dc1c0fd3c473f2dfd65320279a0f055d247dd72a5b567b\",\n        \"size\": 303577903\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21235_Weather18.tar.gz\": {\n        \"sha256\": \"d71787ccfe0961baa6851caabff696d1d82c8c3bfe4b76b8770a8d08dac6d786\",\n        \"size\": 325004116\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21236_Weather19.tar.gz\": {\n        \"sha256\": \"b0faf7383947e419917a2522e37baa4c176bf8ffd4da0ff6c29ba4594578a6c1\",\n        \"size\": 440442941\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21237_Weather20.tar.gz\": {\n        \"sha256\": \"c38c0ce477d5571effcce0739c7ad5564a3c83c9d31de0d0ca76770247d3c438\",\n        \"size\": 345573818\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21238_Weather21.tar.gz\": {\n        \"sha256\": \"be3b2bfd2cc38774fdd4c8775a7085bb8d05e7ffdcd17f434186790a24e25773\",\n        \"size\": 355819663\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21241_Weather23.tar.gz\": {\n        \"sha256\": \"4a2aed216f92fcbcb1041fb5dd1b430e7235725fe845444ec84b6ebf4b2224ae\",\n        \"size\": 294036560\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21242_Weather25.tar.gz\": {\n        \"sha256\": \"87105dbd10cd69bdded4a8aca276aba83f5715ad2625efa8f18ab8e9b990488c\",\n        \"size\": 311945222\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21243_Weather0.tar.gz\": {\n        \"sha256\": \"656e5a283810d51f58f7304667b8f431ce12d074060d8ba59d5f2b5ece7d61cc\",\n        \"size\": 510841356\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21244_Weather1.tar.gz\": {\n        \"sha256\": \"5ae63abd79f57add848bcb7b58dda8af09d504a55e168a44b28d44880d98ed6e\",\n        \"size\": 553141039\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21245_Weather2.tar.gz\": {\n        \"sha256\": \"034f5c619047e239a9145f0da626a8b4c0f1c0534ebf80c54aa72e2ca435c03c\",\n        \"size\": 424356601\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21246_Weather3.tar.gz\": {\n        \"sha256\": \"14de0b50174e16fa9ad39f98efcaf8747fa8e5ce48417a26acb531ce9c1db898\",\n        \"size\": 456241765\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21247_Weather3.tar.gz\": {\n        \"sha256\": \"d7f9967b33bfb93343412ff7b9f978c820769944a191bd7772d9081cb3883ad0\",\n        \"size\": 416175491\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21248_Weather5.tar.gz\": {\n        \"sha256\": \"afb02a8176c3962a1d74f5b85fe0d2313e738e1ec9bb6ca2b8517047dcb19229\",\n        \"size\": 450283365\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21249_Weather6.tar.gz\": {\n        \"sha256\": \"1d11dcdcddbd48e2b98bbbbaac6ed46b26496e77ea0f59e152e3183b844639b0\",\n        \"size\": 525046882\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21250_Weather7.tar.gz\": {\n        \"sha256\": \"b738c2f6eafd298831ea8b27ccf896b49fbddac218a181679017177b99c15d12\",\n        \"size\": 550669983\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21251_Weather8.tar.gz\": {\n        \"sha256\": \"1dce2ff3814a5e251f37d1a030fc30550d74b5663301d1feb5619c4b85745a6c\",\n        \"size\": 534260177\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21252_Weather9.tar.gz\": {\n        \"sha256\": \"e67fac386d91b8cb33558026b38dd45ee6f08c035bd50db1972abe83e9c002a0\",\n        \"size\": 494290128\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21253_Weather10.tar.gz\": {\n        \"sha256\": \"749f0e41b7a039e49184b74e1318379b7452fb9c0a8d9fc446e945994be6f3e2\",\n        \"size\": 418553339\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21254_Weather11.tar.gz\": {\n        \"sha256\": \"84a18f891415c60dbc2775332bd757d6718d12b1db0eeec703b2f53c6ce25f45\",\n        \"size\": 265169001\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21255_Weather12.tar.gz\": {\n        \"sha256\": \"d71ee789d7cbc3a834214439a1a1cbfdca0a2898ed82b8917add4a106e941349\",\n        \"size\": 431986479\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21256_Weather13.tar.gz\": {\n        \"sha256\": \"0c2ad5a7abb1344a68530986cdb97ff7fcddca45b82b52d600512b7c79089391\",\n        \"size\": 535430512\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21258_Weather15.tar.gz\": {\n        \"sha256\": \"8bae5c1352ec05bd57b0a7c8f9de60689dafdffc2382ff0aaec90b73e1cc3078\",\n        \"size\": 256558775\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21259_Weather8.tar.gz\": {\n        \"sha256\": \"2dfc41ec9f723520396d5597d009e248203e6cca4ea3432b9528489b6767b1c0\",\n        \"size\": 452562951\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21260_Weather9.tar.gz\": {\n        \"sha256\": \"5abad17aece8ab91786dd7bf2341955e06e80a0a4a4779d95c9bdf96285e34c3\",\n        \"size\": 186312386\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21261_Weather18.tar.gz\": {\n        \"sha256\": \"3a22602fffe661978333ce565a00a2bbf45f3a4e815a01972b67617a944bb19c\",\n        \"size\": 323971474\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21262_Weather19.tar.gz\": {\n        \"sha256\": \"2d45b432ed839d8acddeb9c4ef577ecbf2b48a635c7eff35f30dde8ea3a7e903\",\n        \"size\": 148131545\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21263_Weather20.tar.gz\": {\n        \"sha256\": \"e3ff0e52e3bb7b3bd1b344f91a6818fa3305680039ed73c85846f04470677e8e\",\n        \"size\": 153788290\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21264_Weather21.tar.gz\": {\n        \"sha256\": \"397f00fe27494721e28ce9a4d39e2bd1feaea3c8dfe451eeddb9b36b807b853a\",\n        \"size\": 311203269\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21265_Weather22.tar.gz\": {\n        \"sha256\": \"fedbc9e734c691274134e6e4d6b947b83f8d063a39d2dbe1af10a5caa859179f\",\n        \"size\": 181905641\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21266_Weather23.tar.gz\": {\n        \"sha256\": \"a8ecf8cdc4e2058c89e3c64f4a8302eb1dbea50bc774b238d1df3e5bbb19ee23\",\n        \"size\": 278973343\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21267_Weather23.tar.gz\": {\n        \"sha256\": \"bfaed7c9a0b4f4729731f9751e39a57e0d8555836aa36434bd19ad06de43c531\",\n        \"size\": 314279882\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21268_Weather25.tar.gz\": {\n        \"sha256\": \"330500a9d381d916382466ef596e238be8b78b94b4623351363b279a78281e09\",\n        \"size\": 304797981\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21273_Weather3.tar.gz\": {\n        \"sha256\": \"95d706a47c6d9696edfe17b8494c0a9ac03f29308e4bf82c1e63653e8f04993d\",\n        \"size\": 314462100\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21274_Weather5.tar.gz\": {\n        \"sha256\": \"9eb2aeff4e862e0545acae8a88b6b5de36019ed39481fb09352619b41cb85771\",\n        \"size\": 378572917\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21275_Weather6.tar.gz\": {\n        \"sha256\": \"f83ec7b2f85f97345434e72d0a650b1f8df0b7f9628f3904b3aa23c5e5599802\",\n        \"size\": 422038388\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21277_Weather8.tar.gz\": {\n        \"sha256\": \"d1d7750b02908dceb0e753d3f162b1fcf0daa07016417b233d5896add392380d\",\n        \"size\": 310385428\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21278_Weather9.tar.gz\": {\n        \"sha256\": \"e43bbb84c795a10a42bbfa34587c0bb1b1fcfb05883c2ddfabee69a64974d91f\",\n        \"size\": 371978869\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21279_Weather10.tar.gz\": {\n        \"sha256\": \"295384c52244c012f7bbf52104e69fed581cbd2a194d183700eb6bef660937e3\",\n        \"size\": 171858401\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21280_Weather11.tar.gz\": {\n        \"sha256\": \"e98c0e831e7ef213e5a406274099e41a86b390ba3a9106db5ee4df6770f9ca64\",\n        \"size\": 144047509\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21281_Weather12.tar.gz\": {\n        \"sha256\": \"25e4decc60a2edbdf8fd58de2869c26d825cbc31066870852c50d64e0b7d9026\",\n        \"size\": 144939520\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21282_Weather13.tar.gz\": {\n        \"sha256\": \"1f48ee4e646d81efc7b56a5f43c4e66aae13878bd57b6731cb82dc57f990c910\",\n        \"size\": 263076453\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21283_Weather14.tar.gz\": {\n        \"sha256\": \"48a3ee0e8a2d511bc4cec9a4d94217891c25c1a8c729c2502421e89785cf9d34\",\n        \"size\": 145745176\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21284_Weather15.tar.gz\": {\n        \"sha256\": \"a5d2eafe09c070fbf48687674c96bc39be0824fa1d00b0e1ae852f4d9efdf286\",\n        \"size\": 405696405\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21285_Weather8.tar.gz\": {\n        \"sha256\": \"f93aa9cf4ff914f2a208d32ef13dd62826a48a6cd6985dc078eb8b451d237a8a\",\n        \"size\": 368547791\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21286_Weather9.tar.gz\": {\n        \"sha256\": \"33b4a5186012943c1de2a7d468451359af5fbe0a30d8bda40665d087c50217f9\",\n        \"size\": 134586161\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21287_Weather18.tar.gz\": {\n        \"sha256\": \"2ff63470b8cdf6461eaec36c89b8bd0c018cbf0e594f278f381c03511affe7c0\",\n        \"size\": 175965686\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21288_Weather19.tar.gz\": {\n        \"sha256\": \"b9a6e2224fe63a7e70e4533c09e38392d585730b3b1d6182ecdbdd110f48d9a0\",\n        \"size\": 285227057\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21289_Weather20.tar.gz\": {\n        \"sha256\": \"e4139538928c9e342caf3c029fb2852bf6165c74fb118b2c35565139e2947ca9\",\n        \"size\": 280624712\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21290_Weather21.tar.gz\": {\n        \"sha256\": \"b88422a61a759058b8b42c435af73e8902ae4b6858b589a47b434bbbe7835cae\",\n        \"size\": 168589909\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21291_Weather22.tar.gz\": {\n        \"sha256\": \"4e15fdfa35da25c4b27991937e2184ca6f7f63deedcee7779fc5ceec901034bf\",\n        \"size\": 306468580\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21292_Weather23.tar.gz\": {\n        \"sha256\": \"25438f33d8685a9088d44b95f20474d290dc27f8aaa0446c14c960b507a2f9bd\",\n        \"size\": 126455017\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21293_Weather23.tar.gz\": {\n        \"sha256\": \"75f7d016e375163033db990f20b3d3676eceeb7a6e210a36eb33ddcf87641861\",\n        \"size\": 163267941\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21294_Weather25.tar.gz\": {\n        \"sha256\": \"ae4b857b49e4dc90638c914b655b632821c397d9673afeb73c36b5f811761f30\",\n        \"size\": 270327785\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21296_Weather1.tar.gz\": {\n        \"sha256\": \"7b9141be6f334b53c008b200c7ed1b5530f547684c0d7b86d0e6eaf0aa95e4b3\",\n        \"size\": 320392512\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21297_Weather2.tar.gz\": {\n        \"sha256\": \"e6ecfc2791bccd253499957d2e2e559f25562048f296f793bbd682163d769b99\",\n        \"size\": 503377174\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21298_Weather3.tar.gz\": {\n        \"sha256\": \"909b52208430022f648d9927de858b32aa23d35eacfed7901fd05866a3444edd\",\n        \"size\": 283824462\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21299_Weather3.tar.gz\": {\n        \"sha256\": \"2f4645ca9225c1baad078659c2a9010760cf953b05b2a43315c6bec1ba7ea4be\",\n        \"size\": 216415963\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21300_Weather5.tar.gz\": {\n        \"sha256\": \"15104f915c5defb8e82d98b4d7f1cb815147a22b575790ac6f907eba63a4c7ad\",\n        \"size\": 311960638\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21301_Weather6.tar.gz\": {\n        \"sha256\": \"57ad51621743f19642d21b95c8c4e2c9bee813fefbea880c3c1156e3fad661c2\",\n        \"size\": 176198493\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21303_Weather8.tar.gz\": {\n        \"sha256\": \"bb04466d0cb010a134ba051783dc7173c462d1f492c213a778cfdd5ff77c1470\",\n        \"size\": 356733538\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21304_Weather9.tar.gz\": {\n        \"sha256\": \"399b60c8bb2b0812c733ed1a458c936252ab498865305670411f437090e83dd7\",\n        \"size\": 453397181\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21305_Weather10.tar.gz\": {\n        \"sha256\": \"e38cb32cab6dcc28da8950e3f3517527e8717e4f11386af0359cce1fe8d2d9c2\",\n        \"size\": 161447056\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21306_Weather11.tar.gz\": {\n        \"sha256\": \"9896f63b65cf076768df7910c44164dae373de34ce9016b67726bcae81e4a7b2\",\n        \"size\": 270480069\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21307_Weather12.tar.gz\": {\n        \"sha256\": \"1eb65222db587e2717ba367f5608886adf5bc5087e02547b25f775548e71b64b\",\n        \"size\": 141597177\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21308_Weather13.tar.gz\": {\n        \"sha256\": \"5c387c908ca77f8839b59240f4485d51251e85ee1eaada1b283680cb70b95438\",\n        \"size\": 286124635\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21309_Weather14.tar.gz\": {\n        \"sha256\": \"a626e2633004616847317b7af1b6a4fc1a083ea5cff8b0c2f8cb74939ec76a94\",\n        \"size\": 197175060\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21310_Weather15.tar.gz\": {\n        \"sha256\": \"e68cfa65cc3996d30e915b032014cf2c4b56b38d80af5052578f3d30b4cacb82\",\n        \"size\": 334249298\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21313_Weather18.tar.gz\": {\n        \"sha256\": \"6d1886d29465aee1328489bf28d20434d4ef582e404974300d22e763ed53de48\",\n        \"size\": 427079555\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21314_Weather19.tar.gz\": {\n        \"sha256\": \"4ed9182cf40a026edca1c2ca21c25fed7f3baab58eb70eec466e509517f0072a\",\n        \"size\": 196124996\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21315_Weather20.tar.gz\": {\n        \"sha256\": \"db132fce8bb26a99c53551e788d4ee7e2f7d7827bb9336cd224b2345753a115d\",\n        \"size\": 428645118\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21316_Weather21.tar.gz\": {\n        \"sha256\": \"bc2dcf01d9c375d0b543b053a229dd3d707a4e05449e9ce385d3fbb75d2fddea\",\n        \"size\": 436359720\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21317_Weather22.tar.gz\": {\n        \"sha256\": \"01e3dbb21c3b9cacdb3e9e1bd15ec9ee927e8af00d58f90af2e298bd1a696f62\",\n        \"size\": 420829115\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21318_Weather23.tar.gz\": {\n        \"sha256\": \"b2fe6342757e20755147f88e1041f7e0e984db044f23e83a06704f993a882bd3\",\n        \"size\": 388664891\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21319_Weather23.tar.gz\": {\n        \"sha256\": \"55bd60648d3beca217c4497950447cc4f8946394e258f031926994611c00d963\",\n        \"size\": 371860668\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21320_Weather25.tar.gz\": {\n        \"sha256\": \"bd514da4532771487f4597704ae9e3359998ec93ccfd01b3e48807b19e35cbc9\",\n        \"size\": 331975493\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21321_Weather0.tar.gz\": {\n        \"sha256\": \"6283ea4f3c88855e291eb0c39d4017e9a1df66bab95a5b083507304f9842559b\",\n        \"size\": 457407404\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21322_Weather1.tar.gz\": {\n        \"sha256\": \"5b5106967df71fe69fe160de6576d4f6858af8b49dd00cd60c8a75e75e5cc8d8\",\n        \"size\": 518655318\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21323_Weather2.tar.gz\": {\n        \"sha256\": \"f8ead26c5d94bc3de66a8b5bfd1d74528788c8fc629b75a8bbe27a936756731e\",\n        \"size\": 396770751\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21324_Weather3.tar.gz\": {\n        \"sha256\": \"996234d2abcb2f7d8e8feea27279683090457e803f4e4d9fdf2d8b5b59259c48\",\n        \"size\": 496101796\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21325_Weather3.tar.gz\": {\n        \"sha256\": \"246f119625e953f6f7db6751fbd11ce0f9affd49224620e78bb1a1e6aaa3ad96\",\n        \"size\": 421091024\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21326_Weather5.tar.gz\": {\n        \"sha256\": \"36c88879ad8c938ea11457a1f43e270d74444f2761d1ae6613a5ac2cb1b86ac4\",\n        \"size\": 366963533\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21327_Weather6.tar.gz\": {\n        \"sha256\": \"b09a83a6d4bc4955b29c6ce98bbdc08cdfa5071c28c71699186aa2de92f90155\",\n        \"size\": 477337311\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21328_Weather7.tar.gz\": {\n        \"sha256\": \"0495226a370f594b0d31b0244929bd4e5b6b591ae3eb8f3411723052033f5e6a\",\n        \"size\": 537152315\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21329_Weather8.tar.gz\": {\n        \"sha256\": \"6f5825de62009b2490a84695e996985f2aa7256e91a20a168dfa41be42aa8369\",\n        \"size\": 375804904\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21330_Weather9.tar.gz\": {\n        \"sha256\": \"1c91d5dad2ab25040a43299ce176a03b76d43118d6a30445c26366a9d4d70cbb\",\n        \"size\": 272141891\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21331_Weather10.tar.gz\": {\n        \"sha256\": \"5d450c49be0661c07cf48ea70d98c5e7bad2dd66cb89a772ad1344840270c090\",\n        \"size\": 429233195\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21332_Weather11.tar.gz\": {\n        \"sha256\": \"9162401782188eae80fd0bed1db36ad13c8794bf30e1595458e6837cbd0d1831\",\n        \"size\": 421512715\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21333_Weather12.tar.gz\": {\n        \"sha256\": \"36d7c4fbe8c904a8cba78780e81b673ded2d8bf675558f33ef8bf4949f084b1e\",\n        \"size\": 439719078\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21334_Weather13.tar.gz\": {\n        \"sha256\": \"e9767e22c20c67add5f18a30acc699c7e0eb90eef09046949bd0e7e058eb1bb0\",\n        \"size\": 375239911\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21335_Weather14.tar.gz\": {\n        \"sha256\": \"f49d7d30905d95aeb483b8132a7636fdab513f5c05fd8c745f46c81f13617a4f\",\n        \"size\": 325263932\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21337_Weather8.tar.gz\": {\n        \"sha256\": \"ed810ce16e431766280a80a781533b97aefad81fc2757302dbdeb471e327ecf1\",\n        \"size\": 569543364\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21338_Weather9.tar.gz\": {\n        \"sha256\": \"02950d762c39d3b3b9c9787816c0b4fa0448d2fd651491957a942dbe50402a8a\",\n        \"size\": 276315248\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21339_Weather18.tar.gz\": {\n        \"sha256\": \"15a8a3dc98ac2f310a00699f9752fd631480d4a1ad4c8d0c285acd5fc25246e5\",\n        \"size\": 282703293\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21340_Weather19.tar.gz\": {\n        \"sha256\": \"2a8731dfe756b8ed889d65c4fa1d5d2217153e27d7f3b7d5c1fe1f12492bed65\",\n        \"size\": 178365600\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21341_Weather20.tar.gz\": {\n        \"sha256\": \"a0f0f8a499b98d5aa1910aaca377516646ca54305a287043c85ced4686815680\",\n        \"size\": 197518270\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21342_Weather21.tar.gz\": {\n        \"sha256\": \"e28ad8b05b05bdea85405201e6c510687a5906908bef5a86f3862812c1ffa7cf\",\n        \"size\": 164894896\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21344_Weather23.tar.gz\": {\n        \"sha256\": \"05f829d150e5fe774799c9cb5d793f0bba88bb400fc882166fb03b23abaeac83\",\n        \"size\": 258459613\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21345_Weather23.tar.gz\": {\n        \"sha256\": \"c02bcce18983289504d5abd134c6765f7eb4a79063223f06d1e729e20bf2c33b\",\n        \"size\": 141522849\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21347_Weather0.tar.gz\": {\n        \"sha256\": \"4c39da3dd933dea4b598c5989ee2f74c51d6e7943d15bfcce350ca74f71997bd\",\n        \"size\": 447955632\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21348_Weather1.tar.gz\": {\n        \"sha256\": \"b60920b24ae286bf3258abf7775aad1015adc4fbd7519c30f1916d8ed83dee54\",\n        \"size\": 390059674\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21349_Weather2.tar.gz\": {\n        \"sha256\": \"9b16664413c0994e5aa4d03b712214423362a7e455ba36b48867533cd70a205a\",\n        \"size\": 631506580\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21352_Weather5.tar.gz\": {\n        \"sha256\": \"265680f0464e50238f35792c6808d57c6160db4f6ddd41913d417e74fec67edd\",\n        \"size\": 430890962\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21353_Weather6.tar.gz\": {\n        \"sha256\": \"a2f6faac94f309bc43763d06c9066fb0e8473119c17e7da3888d21c5b1e7234a\",\n        \"size\": 477167325\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21354_Weather7.tar.gz\": {\n        \"sha256\": \"ae0a1cb96a73e5b7519b7f78d8d0fd8b2a3c86007506897e5ba4a4e985b92db2\",\n        \"size\": 446113345\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21355_Weather8.tar.gz\": {\n        \"sha256\": \"8d7b0b127407bc4929bd4f68da92c21f4b1221805bb447124ad4327629412de2\",\n        \"size\": 508373097\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21356_Weather9.tar.gz\": {\n        \"sha256\": \"5dc2d73169dd814d77e76e9d5ed461ead5fd03d13284905e7c61bcf31e922df7\",\n        \"size\": 265071546\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21357_Weather10.tar.gz\": {\n        \"sha256\": \"468d08f42c5189021c8af33f3d5576c8e82fd787cc03d6531d350f52bd4d139c\",\n        \"size\": 360000530\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21358_Weather11.tar.gz\": {\n        \"sha256\": \"d5397cca0589e7f3e7f12407a506c016e61a0689dacc3896640ecc3b395b310e\",\n        \"size\": 1205071497\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21359_Weather12.tar.gz\": {\n        \"sha256\": \"deb97d6d35795e72c947ffe2b22887a7b310e267cc036de13906f27777ba8dcf\",\n        \"size\": 142774236\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21360_Weather13.tar.gz\": {\n        \"sha256\": \"994ffe6c62a09811d138cffc3f957efbb243be50d9998ad01278798e6688650d\",\n        \"size\": 124947313\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21361_Weather14.tar.gz\": {\n        \"sha256\": \"989d10b9da1eda6fdbd766324ef2f006ab052be8de79e7376fe964b8ac60c4c6\",\n        \"size\": 365572366\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21362_Weather15.tar.gz\": {\n        \"sha256\": \"abe5a757e29be5bf6de2944a0d94df0cb86baafe4bdcc2b7f993bbda05eb829a\",\n        \"size\": 349000876\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21363_Weather8.tar.gz\": {\n        \"sha256\": \"5fce5c35b2d278524277ac8129cfc9a430deb8b449d3cbc9da127315be39f4b0\",\n        \"size\": 347197210\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21364_Weather9.tar.gz\": {\n        \"sha256\": \"c3c5af01ee4522a83bc8e40df6b4f12c9d057a28729144117cd643c6188cf1fb\",\n        \"size\": 327326984\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21365_Weather18.tar.gz\": {\n        \"sha256\": \"f0f08febf05d26d2ae403de160fd78c096e76f98229bf81c60e33fd40e64c6c8\",\n        \"size\": 525442955\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21366_Weather19.tar.gz\": {\n        \"sha256\": \"425343ccf60cc9910178cc8691ba547e147f77fbb551478eb7d8fc6073342890\",\n        \"size\": 336895291\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21368_Weather21.tar.gz\": {\n        \"sha256\": \"261f15587d64d074e9b6f05153883cb2f3cee3e5f618cc2d07d5c3d9d53c8489\",\n        \"size\": 400382562\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21369_Weather22.tar.gz\": {\n        \"sha256\": \"17657eb0a1e811bc43ab1b13c511b3fd21a46e5a8792fe27e613b570ddfe275d\",\n        \"size\": 398748924\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21370_Weather23.tar.gz\": {\n        \"sha256\": \"5f52333d5472ef5cfd16ef80761b15ee1d71800348ffd95b4a5aa2da56c50e18\",\n        \"size\": 310635472\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21371_Weather23.tar.gz\": {\n        \"sha256\": \"2d544782dcec96b4a949887ea7f9d1cdea9898f85057f6cdc2faf3777775f54f\",\n        \"size\": 326666525\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21372_Weather25.tar.gz\": {\n        \"sha256\": \"235b956c52c68c26ac95beadffd9b3016bf5ea38b3a4968832250be93bcc37b8\",\n        \"size\": 370798570\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21373_Weather0.tar.gz\": {\n        \"sha256\": \"02de00199c04a2f384cfbacaf615fcaa1424b02f159383c0d190a4ad88731df3\",\n        \"size\": 325797699\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21374_Weather1.tar.gz\": {\n        \"sha256\": \"018f9ab5dccbaf1ffc8c0ab3a45879c33a63cb64974b36eb5acc2740f6e59d06\",\n        \"size\": 325198693\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21375_Weather2.tar.gz\": {\n        \"sha256\": \"9bc9a1da386d832c0c278ff6695e8f96b8407f84a8098c922593e6a4e3171afd\",\n        \"size\": 170858527\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21376_Weather3.tar.gz\": {\n        \"sha256\": \"6542fc8bd392b567c6db91b6e23a8a37c4d015e80e10b0fa67b3f2ee72134b21\",\n        \"size\": 587532980\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21378_Weather5.tar.gz\": {\n        \"sha256\": \"fcead141fdadd18b67fd958f23f2b90634c647795ccc8cc5f59a65a68b70e0a3\",\n        \"size\": 169370132\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21379_Weather6.tar.gz\": {\n        \"sha256\": \"ab2ebd56708c62c2d044e712cb8f20415b6c750640fdeb1d2f96283576c1d5ac\",\n        \"size\": 178835593\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21381_Weather8.tar.gz\": {\n        \"sha256\": \"42f8f751089c1c267f77e2d59c392350fe1b464dc919fae7d1f61e319c87df52\",\n        \"size\": 413294308\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21384_Weather11.tar.gz\": {\n        \"sha256\": \"82edb1773573297c2725a267bafb10930581cad9ce5da7b65b8a8785dfd6b20a\",\n        \"size\": 318217960\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21385_Weather12.tar.gz\": {\n        \"sha256\": \"39438aa514d5a42ea4a429a48ec0358cf291078958f41f6e75b4a9aae7e736ef\",\n        \"size\": 363086630\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21388_Weather15.tar.gz\": {\n        \"sha256\": \"2cc7ca85a250bb7261c28d92c7803c766874305cce9091a8f286cfc658cbadb7\",\n        \"size\": 374826232\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21389_Weather8.tar.gz\": {\n        \"sha256\": \"c92ff3dac690f6241643ac6fec4c68f8f6240de1a128dcb60ceeb1b080322c43\",\n        \"size\": 383068491\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21390_Weather9.tar.gz\": {\n        \"sha256\": \"330b7a2af3f6723aab891011e4b4d775c5e8a6afb735a5d749990169e75e7565\",\n        \"size\": 389926193\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21391_Weather18.tar.gz\": {\n        \"sha256\": \"31e14bb4d94664d4b24248ab42f5047d270e990557136aee4c069213d81e996b\",\n        \"size\": 433339204\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21392_Weather19.tar.gz\": {\n        \"sha256\": \"df6f9cdf16e798c50d8bad45430395c9739c9a31d38423e87d4dad21d1c48dc6\",\n        \"size\": 507663854\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21393_Weather20.tar.gz\": {\n        \"sha256\": \"cc24e9ae3b48abed405d3cbe8fc75cbeede16a4fe05d0ec3b65ac0aaafa5bebf\",\n        \"size\": 385735956\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21394_Weather21.tar.gz\": {\n        \"sha256\": \"042502a99800d0781b52dd3181ca59e64f6518e1750c73100945a5da2fa394d0\",\n        \"size\": 273483721\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21395_Weather22.tar.gz\": {\n        \"sha256\": \"13dd88223c9b9146c56c77e3eee1d56696974f146acf7a26fb9828c87da87229\",\n        \"size\": 356555803\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21397_Weather23.tar.gz\": {\n        \"sha256\": \"fef9b1f7f24e47111e078549589b6dc41b00798f1fc13de674ca167980c086e3\",\n        \"size\": 332737924\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21398_Weather25.tar.gz\": {\n        \"sha256\": \"8a07e62200daa2ec86a7f5b02d961700409aaa105c5d7869408a742632a4db02\",\n        \"size\": 300595451\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21399_Weather0.tar.gz\": {\n        \"sha256\": \"a5b2acd4cb08c7b0dc91a013e870ea13a79bc7a569c691b48d560e04b1c6c825\",\n        \"size\": 259063279\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21400_Weather1.tar.gz\": {\n        \"sha256\": \"29e74e2ab06dabb8a2c70d949aba3014a6815dd0962a15d7db94b177621a5e06\",\n        \"size\": 384178493\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21401_Weather2.tar.gz\": {\n        \"sha256\": \"831a00bc67981dce1a03ecd32441a0d67b1002e2eb65638ce396214abfc5819e\",\n        \"size\": 418720254\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21402_Weather3.tar.gz\": {\n        \"sha256\": \"1d1eee0e4e8cc37a94bbec5d503e4e72cf84ea75b435fffeea2118ab64d75139\",\n        \"size\": 760843808\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21403_Weather3.tar.gz\": {\n        \"sha256\": \"1b67a8da83d456d3f1cf883a0a0294f089325b5615548a474557de8eb8bb8cf6\",\n        \"size\": 451888929\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21405_Weather6.tar.gz\": {\n        \"sha256\": \"8efe330902fee755ace5652d9e6a6b9593bbc33ca9be4a776abf14b38257d684\",\n        \"size\": 785303099\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21406_Weather7.tar.gz\": {\n        \"sha256\": \"3e6e7ffed65af54ac3d433bf299eabed7d968654ed5ba4b6643c49d44daa490d\",\n        \"size\": 352926800\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21407_Weather8.tar.gz\": {\n        \"sha256\": \"6c757fefeea321b0977d11c360ca8a8c8985915e36b512989ab92fad239067b6\",\n        \"size\": 481860859\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21408_Weather9.tar.gz\": {\n        \"sha256\": \"c50c9b87f47d59ac6b16156c0061cbe5aee7e7c417b13599661eb57166fc1b16\",\n        \"size\": 338243781\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21409_Weather10.tar.gz\": {\n        \"sha256\": \"ed9e2ff765e9e9861640391b357227158c3a7ea80426fddca1e1fda5e7c9154d\",\n        \"size\": 307386036\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21410_Weather11.tar.gz\": {\n        \"sha256\": \"8af7cfe8cad727e5509a9f332caf88b4a0044ac0b378dfeace43c02e5ccae29d\",\n        \"size\": 442900221\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21411_Weather12.tar.gz\": {\n        \"sha256\": \"7d82b0c930d0ba200c236d6fcc2219e0610bb356114c20cc64ecbde7b706f080\",\n        \"size\": 308945752\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21412_Weather13.tar.gz\": {\n        \"sha256\": \"a1a5fdcd6c7dd0023146b263ceb7b7f5421e8ead7264067d12503d6f3c788c0e\",\n        \"size\": 298840392\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21413_Weather14.tar.gz\": {\n        \"sha256\": \"caef73307bd8bc8ab39ea694015bedda4e655ad0356be99287b3cb1ef1d6cff3\",\n        \"size\": 276206179\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21414_Weather15.tar.gz\": {\n        \"sha256\": \"1aa83533f0c18c3cfe9e0b39bff9d474528350096afb76ebc4c12fdad9d3b090\",\n        \"size\": 330339163\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21415_Weather8.tar.gz\": {\n        \"sha256\": \"2fa1bab8e44dc5c9e6c5a6e9065d4862017e0ac8cc11a6fcc06bf1c5b09d62e3\",\n        \"size\": 326433030\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21416_Weather9.tar.gz\": {\n        \"sha256\": \"48c39ecf08ca634738f1699435a982e3264dcee3b2eb9cdb54638c2106af0ae4\",\n        \"size\": 314076113\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21418_Weather19.tar.gz\": {\n        \"sha256\": \"d4673f5eed8f76f896d2eed2da4b65a88ef994e8f2c8f7cb02db69edfafeb941\",\n        \"size\": 348006943\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21419_Weather20.tar.gz\": {\n        \"sha256\": \"75e080f9e315b8a62510373c88e2f45da23a047b3c115243ce705a1d8e60490f\",\n        \"size\": 330062061\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21423_Weather23.tar.gz\": {\n        \"sha256\": \"3726bad2654091dc36ae09a4a971e278d8404fc320a9833d27b81646c502aae6\",\n        \"size\": 296235939\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21424_Weather25.tar.gz\": {\n        \"sha256\": \"80361dce1aea76fb2938d4bc62b2e0b29fea8fd90ec825cf6a7630d2fbf9a21e\",\n        \"size\": 289182456\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21426_Weather1.tar.gz\": {\n        \"sha256\": \"84ec365ffe4d204dd61963b470f5d9715cb99f4ad87aed2fcdd46f86352d7d7d\",\n        \"size\": 488427852\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21427_Weather2.tar.gz\": {\n        \"sha256\": \"d96430f942077491b007488de5227789607e0713a81de1474183cea1000989f9\",\n        \"size\": 499365332\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21428_Weather3.tar.gz\": {\n        \"sha256\": \"ba940d2592d4fbd3f2fe4a87c80162d85dddbd9c608e378d8c1be95f48d2cbb3\",\n        \"size\": 582257479\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21429_Weather3.tar.gz\": {\n        \"sha256\": \"d74c94f2bcc381f90d1d69abb8ac307ff315b4df194c9f38e85479afc69cdd70\",\n        \"size\": 480142647\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21430_Weather5.tar.gz\": {\n        \"sha256\": \"9ba1dc66d04c0144b03f5c79e5896225043669090e612a39e1445b6f6bf52f27\",\n        \"size\": 384104729\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21431_Weather6.tar.gz\": {\n        \"sha256\": \"71a65632f9cf71037e493704c769b33c0d010d8a5df1fec46100590b3cee1e42\",\n        \"size\": 341375339\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21432_Weather7.tar.gz\": {\n        \"sha256\": \"d54f449e780a091e9c2f10d4805aacdb1cfe41fda8945c11202a89a0052101ed\",\n        \"size\": 470091702\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21433_Weather8.tar.gz\": {\n        \"sha256\": \"5163298880c7a0771fe92487545b8a35ef595ecfb0be09ff18d7be5f57b8d1d5\",\n        \"size\": 410861777\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21434_Weather9.tar.gz\": {\n        \"sha256\": \"7acc75f838379a5f31abaed5ec86850038f725106803bab7274320f4bf436e90\",\n        \"size\": 376636482\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21435_Weather10.tar.gz\": {\n        \"sha256\": \"6abf35b749c4d86c5d5570dfb059ccac6174478299df6646a3933d2580de38e9\",\n        \"size\": 400409982\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21436_Weather11.tar.gz\": {\n        \"sha256\": \"ed4741b68b1199f3ac214d897c062f6040a50e84fbc3bafe015b5f1378c20872\",\n        \"size\": 443368972\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21437_Weather12.tar.gz\": {\n        \"sha256\": \"64865a8a4fa0383b8c4707d2e9bb63ee8f7c0594bb9c66e931577847a44b288e\",\n        \"size\": 136872781\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21438_Weather13.tar.gz\": {\n        \"sha256\": \"924cf6688907b18e98a87ec2c8c543d7c63cc8164b856df395a0ef6db8ac318a\",\n        \"size\": 155346868\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21440_Weather15.tar.gz\": {\n        \"sha256\": \"48fd30e4309358ec4bd1b5b71a0a879ad13dd6ddcdc9878ddb7617dece3a44bf\",\n        \"size\": 347673327\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21441_Weather8.tar.gz\": {\n        \"sha256\": \"19be95066e004c174aaeb78c24e780a4fcbacd422b97ed19dfbe1d69b725d494\",\n        \"size\": 167682186\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21442_Weather9.tar.gz\": {\n        \"sha256\": \"afdf81786cd06854d8e01cd1afdbc38fea18e2c95064bc19e43ef175206928e0\",\n        \"size\": 130772015\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21443_Weather18.tar.gz\": {\n        \"sha256\": \"128516a8d96dad4c0241cd3d9adf6ea7ed9f39b9a7a0532980655f46d6ca4531\",\n        \"size\": 300544371\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21444_Weather19.tar.gz\": {\n        \"sha256\": \"d115a1fa22710893cd8e15017c11f41872b7ec5e7518377f4de6fe4d84aaa0fa\",\n        \"size\": 224592733\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21445_Weather20.tar.gz\": {\n        \"sha256\": \"792fd9517c2552cd6f9909e47b393e110b861a4fecd4a0ef20d7317387224a30\",\n        \"size\": 178876659\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21446_Weather21.tar.gz\": {\n        \"sha256\": \"c2e9e851a25d7c87d6ecc387253570f2362282e835000e602e8f6fa679cf0499\",\n        \"size\": 153114182\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21447_Weather22.tar.gz\": {\n        \"sha256\": \"674b00a80ba555864665d4c95d49d6d3450d918ed0f78b11ef1f73b042cf4027\",\n        \"size\": 798457155\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21448_Weather23.tar.gz\": {\n        \"sha256\": \"017a7f6aad7be53064e7718bd29f7ab4223bcb9cf8335366b63f3e4668397159\",\n        \"size\": 172156523\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21449_Weather23.tar.gz\": {\n        \"sha256\": \"fb0445612c97cd2f9f3fa277c3ada72e9e370cb6ac4b867f7a16d3c0a9eb4a9b\",\n        \"size\": 129791103\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21450_Weather25.tar.gz\": {\n        \"sha256\": \"5d0e10e6e9c2e06e6e4c7249123130b611f1fb65ff77271607fdbc881d122b52\",\n        \"size\": 137714130\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21451_Weather0.tar.gz\": {\n        \"sha256\": \"953461014788e30173578c32220d3bda56510d689d5ed817c33a6755619efc71\",\n        \"size\": 178827322\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21452_Weather1.tar.gz\": {\n        \"sha256\": \"d50a7a4ac736bc65a89562baec5152da3d7faa3b14a37129378090eeb881da19\",\n        \"size\": 406446649\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21453_Weather2.tar.gz\": {\n        \"sha256\": \"b99dd02d2bbd9f6d49fa27e7cf08a1046cdd280e72e982877c36ee41d679ebce\",\n        \"size\": 231106578\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21456_Weather5.tar.gz\": {\n        \"sha256\": \"08dc85af17afeb0ad4ce23018c73080ec72ce91fe1869e15efb03045f6b6af54\",\n        \"size\": 359724697\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21457_Weather6.tar.gz\": {\n        \"sha256\": \"e1b0516da919a10efa1444ceb315d8a984b366289bea3b6beaa3420383654503\",\n        \"size\": 172534548\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21458_Weather7.tar.gz\": {\n        \"sha256\": \"598253b3ce8ff634f91b6020ed330518e89bfea1fac752f6132ef30b1a622e59\",\n        \"size\": 187936691\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21459_Weather8.tar.gz\": {\n        \"sha256\": \"2f31c804f67b75d5cd39a60fcc6ba53b4dea1b8fd03ae77e76642398ac0c9f61\",\n        \"size\": 347882367\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21460_Weather9.tar.gz\": {\n        \"sha256\": \"fd808ca097956d9c133ca0df802e091ae060c1d1e2ca07255a6fc93a852c74f5\",\n        \"size\": 286956111\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21461_Weather10.tar.gz\": {\n        \"sha256\": \"1998983d13336c251a609d4f322f97cba98e257acdbb1cf4baa2ec351104f340\",\n        \"size\": 301840993\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21462_Weather11.tar.gz\": {\n        \"sha256\": \"d5c134ee3cb0b9f3b69768e85104db9e09075f2b459cc22af6ecb518fb68750a\",\n        \"size\": 134338676\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21463_Weather12.tar.gz\": {\n        \"sha256\": \"b7071c5d841189e19a71b7b8580479a3d5ba47ba6e47402e9dd4019f1e87557d\",\n        \"size\": 368050577\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21464_Weather13.tar.gz\": {\n        \"sha256\": \"6922a81545506147d697a60dbddd415c3e9a2b441f2bb429162e95052e672b1e\",\n        \"size\": 383600935\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21465_Weather14.tar.gz\": {\n        \"sha256\": \"632b424b0d5eedafaa15dd03b5197361e7b615c347afdce4cc2b9f915d15e252\",\n        \"size\": 352664545\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21466_Weather15.tar.gz\": {\n        \"sha256\": \"ae32b62fdf41cbeab56fab56faf372614398b467e1bad86216bdfddd7839b6fb\",\n        \"size\": 453656364\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21467_Weather8.tar.gz\": {\n        \"sha256\": \"420c61f6da7c924a464307c60bba52aa8df5b6e1da1998d188a0b1c894e73ecb\",\n        \"size\": 459464038\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21468_Weather9.tar.gz\": {\n        \"sha256\": \"e8362f987c1fbd76e9776e5a2cf60d78782f14b44fd787437374a23826abfeb5\",\n        \"size\": 349222951\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21469_Weather18.tar.gz\": {\n        \"sha256\": \"fbf59c630c107fbc1628e9bda200cdc7c8832f2d958505a70465adf3f4b08918\",\n        \"size\": 519201744\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21470_Weather19.tar.gz\": {\n        \"sha256\": \"ea1ea64157e9ff1d20aff01f8802db034c338494a0042589e269f2978eb2239e\",\n        \"size\": 480220526\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21471_Weather20.tar.gz\": {\n        \"sha256\": \"faa379ace0486f0f7c2bb6c450f81b90fd0d1c3e56a2244d9a83ea3875f0a46f\",\n        \"size\": 458581458\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21472_Weather21.tar.gz\": {\n        \"sha256\": \"c88751fd7896f3d0b3cd8b4077dbf07711dfdfaaf9b45791df7b7d45ba9909c8\",\n        \"size\": 449554307\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21473_Weather22.tar.gz\": {\n        \"sha256\": \"0d2c43fb747a0a7f7526b53683b026b9a22765015a9a9bf5f28a80f09c3fd3b6\",\n        \"size\": 367133190\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21474_Weather23.tar.gz\": {\n        \"sha256\": \"8e5281b1f728696d8aab4df4a8c0b25ccd87eef40da879dd6b8e9be860fb5132\",\n        \"size\": 324247873\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21475_Weather23.tar.gz\": {\n        \"sha256\": \"4704a9b8a815054f92ec0d029fd3fbd426cc348fd52cbe971f91b703e4b8784c\",\n        \"size\": 345992814\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21476_Weather25.tar.gz\": {\n        \"sha256\": \"ac821b3d8650faf06f873d3da9530fb1c46f5e83fcda989361a34514508b4c09\",\n        \"size\": 394003945\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21477_Weather0.tar.gz\": {\n        \"sha256\": \"b4e294fa28f465a0050dabee0602d65072dda5ae2e0f968035d078240fa6b461\",\n        \"size\": 191673280\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21478_Weather1.tar.gz\": {\n        \"sha256\": \"19bd6b99797909a34066e9e465f195fe99ee554e97709e19fccc28692f206c48\",\n        \"size\": 186631638\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21480_Weather3.tar.gz\": {\n        \"sha256\": \"9e732fb4c2f22a23c327bbe4ea66f090781d54df08dcc46159e6ca934d15063a\",\n        \"size\": 155016593\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21481_Weather3.tar.gz\": {\n        \"sha256\": \"187e0e77fa738a1770fdeb252fc8837a4d5844f2de2713a793c9afd831a75e2b\",\n        \"size\": 518736011\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21482_Weather5.tar.gz\": {\n        \"sha256\": \"8fb8a51ab97aa48b6f5d052a95233f4ed5cca1cceda1156833f8e5986fc88118\",\n        \"size\": 539261238\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21483_Weather6.tar.gz\": {\n        \"sha256\": \"6fa27da89d93683d65d68505705cd1e15e667f1b39d01da0e1d7abe8fa9b16e4\",\n        \"size\": 164565643\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21484_Weather7.tar.gz\": {\n        \"sha256\": \"47c2034e4f49b4abdaef76831dd15b022926817197358c8377e72d77bf7fe0c8\",\n        \"size\": 326787338\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21485_Weather8.tar.gz\": {\n        \"sha256\": \"c7aa13442d20ef27f3d385e7a4a011743b4bf2680d13f1d11dfc4d03d31b3f36\",\n        \"size\": 269072956\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21486_Weather9.tar.gz\": {\n        \"sha256\": \"a0f2d26372d6876040360c59064bb750ff9f7d0e63f60fd2ac13f50e338aadc1\",\n        \"size\": 242702473\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21487_Weather10.tar.gz\": {\n        \"sha256\": \"b659f986a56e1aed5210c762ebf0851c41059631f833ec543b50cbf63dfad8f1\",\n        \"size\": 174412467\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21488_Weather11.tar.gz\": {\n        \"sha256\": \"7a446c273d6142a47569bc78a4af2daf94515f8ce16d8bf2879c249ac5c17ea7\",\n        \"size\": 297286416\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21489_Weather12.tar.gz\": {\n        \"sha256\": \"bdc0d1c1e7a867eb87c76dff0b79ba7aef6338a0feef21c477627d8174f9e037\",\n        \"size\": 130829484\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route21492_Weather15.tar.gz\": {\n        \"sha256\": \"62384948b4d448d57eda5394db3ede4008d6fe1cf1224a4264d2ee9658b497dc\",\n        \"size\": 363334685\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2644_Weather12.tar.gz\": {\n        \"sha256\": \"57cb5af1811726e179f2c0aec2e2a523eed8ec1d465b1bf30be3b01f5fa263c7\",\n        \"size\": 154801262\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2645_Weather13.tar.gz\": {\n        \"sha256\": \"7633e7a753d36fa22bdca0701eb610e0b8bea373824a95bacd9ef9b491f0587b\",\n        \"size\": 252423436\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2646_Weather14.tar.gz\": {\n        \"sha256\": \"0e13af9814265192628f533fb4cf08ffdce67157f14b76f1e597dd2da29f338b\",\n        \"size\": 492534632\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2647_Weather15.tar.gz\": {\n        \"sha256\": \"0c89361790bd90e23818cd7390867334c94386a5978bce76fa4393721d4fef30\",\n        \"size\": 286181797\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2648_Weather8.tar.gz\": {\n        \"sha256\": \"a65f69b93f8574d09ec062bb874e24ac92424780b064f23551d8c4483749b744\",\n        \"size\": 412563711\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2652_Weather20.tar.gz\": {\n        \"sha256\": \"a190cb971a53609139919e0f52537688fea61bd9bd23749efb72ae9c1d687509\",\n        \"size\": 334567880\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2653_Weather21.tar.gz\": {\n        \"sha256\": \"3a870a4dbb782d057beedb3a4a98a462d525e762bc5a4bbdda719b066382e072\",\n        \"size\": 489040486\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2654_Weather22.tar.gz\": {\n        \"sha256\": \"d5d17902b86ff0de52d3338adc103b0abc9ac35ab3596380dcfcd5dce16c7535\",\n        \"size\": 400261456\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2655_Weather23.tar.gz\": {\n        \"sha256\": \"bcc40bd0e5f0468ecd88876587d662c056db6d71dd2f65dd9b702f269fa1bd72\",\n        \"size\": 134914430\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2656_Weather23.tar.gz\": {\n        \"sha256\": \"ab6fc57e1e962828d610d542dc5c726970c3c3bc59e4277db40a959f919468f1\",\n        \"size\": 335570917\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2657_Weather25.tar.gz\": {\n        \"sha256\": \"1feb08952fa31a54fc013816a787483f4c8584922e8bf74320ef7ecf77011c96\",\n        \"size\": 391016896\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2659_Weather1.tar.gz\": {\n        \"sha256\": \"0c4ff3f5f2a279596d2696cff95d3de363a8e285dd1e161aba86cfef5c24d766\",\n        \"size\": 427996104\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2660_Weather2.tar.gz\": {\n        \"sha256\": \"ae0c590024a7d2014f19bdaeeb1855335db73c13079a83cb880d1065522ac737\",\n        \"size\": 447543871\n    },\n    \"HazardAtSideLaneTwoWays_Town12_Route2663_Weather5.tar.gz\": {\n        \"sha256\": \"4bdd0f98814dd0d4093e0c6c63e320c2131b6e13658ac9c335bf4e57849860e8\",\n        \"size\": 197419061\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3425_Weather14.tar.gz\": {\n        \"sha256\": \"ad8001105d044f8d47e79dcfd48aa68db1149ac264cc0192de2fbde5a3cbd399\",\n        \"size\": 546285867\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3426_Weather15.tar.gz\": {\n        \"sha256\": \"cfc27e8ba771e031a4a646daca0be0975d285825e90c2d3a7697d05148c7e9f5\",\n        \"size\": 571373497\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3427_Weather8.tar.gz\": {\n        \"sha256\": \"198f9c3a3a4e54c291e6004ed65f28c8bb1a90b70100f53fd2eaa4199996a168\",\n        \"size\": 218673769\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3429_Weather18.tar.gz\": {\n        \"sha256\": \"67ba85883a8cff7e250ead2e599b62dde7029733384cebce5e42b76504ea1f8b\",\n        \"size\": 333329789\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3430_Weather19.tar.gz\": {\n        \"sha256\": \"b0a07d54396af6bd14895f9a7da6134c689f19760155aed93358214b21b3cc98\",\n        \"size\": 571327952\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3431_Weather20.tar.gz\": {\n        \"sha256\": \"43401352a50e0fffbc158b483421f9838c97e72d83ff467191e5fd845b7d00bc\",\n        \"size\": 192066824\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3432_Weather21.tar.gz\": {\n        \"sha256\": \"adb9b666a8d9ab1192759448a4f2e9b0626381a666e9980b1cc596a0e1f049b9\",\n        \"size\": 282269047\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3433_Weather22.tar.gz\": {\n        \"sha256\": \"a82f151950fe9195be7ad4edd6793d2b29e51cea21e9dfa940a5736805ef5826\",\n        \"size\": 417899572\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3434_Weather23.tar.gz\": {\n        \"sha256\": \"d20d3cc9864ef4f5408413ede057c43e303fa9e623625e59293bf888054d8946\",\n        \"size\": 451520369\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3435_Weather23.tar.gz\": {\n        \"sha256\": \"d897b79da4827631f7b3470ab04b9fa850c9acc50c7c6a02d5f955c66d0bdc47\",\n        \"size\": 490968444\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3436_Weather25.tar.gz\": {\n        \"sha256\": \"46f17afe35b8b29b293f047d1f96f26c498364e3ac85a8b445c7969dbf7551e8\",\n        \"size\": 193212442\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3437_Weather0.tar.gz\": {\n        \"sha256\": \"157a3c5e83512cef6ab856320cea6756defed29063034e57c8cc4ce257a8a331\",\n        \"size\": 734805796\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3438_Weather1.tar.gz\": {\n        \"sha256\": \"8cae859ef6dd27dabee6d04d35c6e69e674d84d54becfa70ad9163feb516a820\",\n        \"size\": 757052765\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3440_Weather3.tar.gz\": {\n        \"sha256\": \"accf542501e83989a68d37416775915fdeee35b924e0fbc85139343168edbe1a\",\n        \"size\": 280370465\n    },\n    \"HazardAtSideLaneTwoWays_Town13_Route3442_Weather5.tar.gz\": {\n        \"sha256\": \"1e5aa94fc6ffcf7cb43059cf6155752d8e7624a04b40328aee378ad021f262c7\",\n        \"size\": 248517628\n    },\n    \"HazardAtSideLaneTwoWays_Town15_Route25971_Weather3.tar.gz\": {\n        \"sha256\": \"e00f25144499f8add12ff24e0944d5114eabf8febd80b3ee55e3734307ea8e57\",\n        \"size\": 487337056\n    },\n    \"HazardAtSideLane_Town04_Route25300_Weather26.tar.gz\": {\n        \"sha256\": \"6d4c6fb936f26772055272d1fba7902edccc6b0b444b593a65d50fc54a78fa6b\",\n        \"size\": 278754352\n    },\n    \"HazardAtSideLane_Town04_Route25314_Weather14.tar.gz\": {\n        \"sha256\": \"22a72f768e083648992e4041f85eead69dc8cff71f512834da10c3c46992e406\",\n        \"size\": 240927479\n    },\n    \"HazardAtSideLane_Town04_Route25321_Weather23.tar.gz\": {\n        \"sha256\": \"6312eb8e957b0487b94c4e589fbd166560cda3ad461440e287005e77c657f57d\",\n        \"size\": 225208050\n    },\n    \"HazardAtSideLane_Town04_Route25335_Weather12.tar.gz\": {\n        \"sha256\": \"f0da05c74f644e35624acb121252545529e02e6c9653b32d6d1e455d976a43a8\",\n        \"size\": 198295186\n    },\n    \"HazardAtSideLane_Town04_Route25342_Weather21.tar.gz\": {\n        \"sha256\": \"10735b86826880bedf76d5389ef55c165c6b457528934c2d28b45e75844362ee\",\n        \"size\": 192028736\n    },\n    \"HazardAtSideLane_Town04_Route25349_Weather2.tar.gz\": {\n        \"sha256\": \"0083a71e1aa7f6ca6b5b69f1abca45365777fa3bae00e717ffaed96a82f4b2eb\",\n        \"size\": 297444548\n    },\n    \"HazardAtSideLane_Town04_Route25363_Weather19.tar.gz\": {\n        \"sha256\": \"5eec7cf4c6ea333505f6d214b73bf5a58174f6b8c4e95215b99d15926752b10e\",\n        \"size\": 185771381\n    },\n    \"HazardAtSideLane_Town04_Route25391_Weather25.tar.gz\": {\n        \"sha256\": \"3de83b92f4f1b5e9b43ef590b646d6997b3c28d3784f5827b29ab762ae0629e2\",\n        \"size\": 239768365\n    },\n    \"HazardAtSideLane_Town04_Route25398_Weather6.tar.gz\": {\n        \"sha256\": \"9e43ec65a2e8a6845f82fc4f7b243f558c7430c8e58f3e5ba87855985cc266cf\",\n        \"size\": 266070351\n    },\n    \"HazardAtSideLane_Town04_Route25405_Weather13.tar.gz\": {\n        \"sha256\": \"42b0a59b57f598eb6d92a2ec068ce1b35ecbb68b3dd034c40353d53451b871d1\",\n        \"size\": 289393394\n    },\n    \"HazardAtSideLane_Town04_Route25419_Weather3.tar.gz\": {\n        \"sha256\": \"ce905e082b694f5ee607adb5713085afae9aaa0c50f2551f0a678a9ae6b3f011\",\n        \"size\": 321628349\n    },\n    \"HazardAtSideLane_Town04_Route25433_Weather20.tar.gz\": {\n        \"sha256\": \"850bbddd51cd6068ea2974d54a2a272007e24ebd5e96bb092afc0df285eb7215\",\n        \"size\": 198218619\n    },\n    \"HazardAtSideLane_Town05_Route25381_Weather12.tar.gz\": {\n        \"sha256\": \"c7036cc74de5f5f17ea2993634ff6925c7e546f93d46d9804a09b19558b66a4a\",\n        \"size\": 211623068\n    },\n    \"HazardAtSideLane_Town05_Route25388_Weather21.tar.gz\": {\n        \"sha256\": \"29ccde0910404c29b927c5673d04b272af8d3cb58925d4c10d3a12501b02e50a\",\n        \"size\": 242045497\n    },\n    \"HazardAtSideLane_Town05_Route25395_Weather2.tar.gz\": {\n        \"sha256\": \"0a3eeaab4a8dcfe041f22a3ac65daaf886e544c078f2357c3604d3000e169a06\",\n        \"size\": 215573235\n    },\n    \"HazardAtSideLane_Town05_Route25402_Weather10.tar.gz\": {\n        \"sha256\": \"f251e4e6bed9dfcaa0a094a8683378b9ae7cd5f8820222be9744038c3e96585a\",\n        \"size\": 208509470\n    },\n    \"HazardAtSideLane_Town05_Route25409_Weather19.tar.gz\": {\n        \"sha256\": \"a0fa30a077c6068d3cee909dec817f24aa5f36e084bde27da0f89fc3a8f09bc0\",\n        \"size\": 446184807\n    },\n    \"HazardAtSideLane_Town05_Route25423_Weather8.tar.gz\": {\n        \"sha256\": \"e18c2ab863998704aae2ba47ee49d5643f6a7787b2f1db886fa52e26c2939cfa\",\n        \"size\": 255031171\n    },\n    \"HazardAtSideLane_Town05_Route25430_Weather15.tar.gz\": {\n        \"sha256\": \"6468f53f3ac1c964597808568df44c5373dfea436e31d091fb91d023a8a244a9\",\n        \"size\": 202460205\n    },\n    \"HazardAtSideLane_Town05_Route25437_Weather25.tar.gz\": {\n        \"sha256\": \"a3df2ae416c04afb7f62f7f0ddad681f6b1c478dd2a30a028a4a3cb9c499203b\",\n        \"size\": 202767017\n    },\n    \"HazardAtSideLane_Town05_Route25444_Weather6.tar.gz\": {\n        \"sha256\": \"89fdf340869d30557f161ab26a97cbfdbdc7c4bdf3aee8c3bcf0c98d05935e80\",\n        \"size\": 260892506\n    },\n    \"HazardAtSideLane_Town12_Route1785_Weather11.tar.gz\": {\n        \"sha256\": \"3f94318aad110dfb9bd9f06400dfe28a8276163b383ad23d6cfd1f71964c8285\",\n        \"size\": 148339349\n    },\n    \"HazardAtSideLane_Town12_Route1786_Weather12.tar.gz\": {\n        \"sha256\": \"50cb04a0632390b9e90ecbfe16407705e3a3ddea9af65c169ce57b165a9b870f\",\n        \"size\": 166955913\n    },\n    \"HazardAtSideLane_Town12_Route1788_Weather14.tar.gz\": {\n        \"sha256\": \"119d2219a09784a50e207211c6bc8d254f32bfaf6a5aedaa283f506c061b7c48\",\n        \"size\": 464356034\n    },\n    \"HazardAtSideLane_Town12_Route1789_Weather15.tar.gz\": {\n        \"sha256\": \"5b88efd5cbe2eabf97ce35d75a51cc7a49c57854166d19837d7d928607ef5716\",\n        \"size\": 450958078\n    },\n    \"HazardAtSideLane_Town12_Route1790_Weather8.tar.gz\": {\n        \"sha256\": \"235989eb7c83ccaf4b80d7598b2abfcbcc41576c304343602099a9fe4db9e6b8\",\n        \"size\": 155661504\n    },\n    \"HazardAtSideLane_Town12_Route1791_Weather9.tar.gz\": {\n        \"sha256\": \"31257d52cb8588aabf4082d3447ba4a20dde08ec525a3b6ecfcfa1b0be00e693\",\n        \"size\": 450489585\n    },\n    \"HazardAtSideLane_Town12_Route1792_Weather18.tar.gz\": {\n        \"sha256\": \"933489c1d2bf5c45614f28014e1b6f0a7d382537affa022990d65040fce57a60\",\n        \"size\": 529216013\n    },\n    \"HazardAtSideLane_Town12_Route1793_Weather19.tar.gz\": {\n        \"sha256\": \"2f07f587f8a4aaef10cfe4477ed261c0bae5923e06cc2a97353b185e003d4be2\",\n        \"size\": 171721993\n    },\n    \"HazardAtSideLane_Town12_Route1794_Weather20.tar.gz\": {\n        \"sha256\": \"ee0ab8e38702bdf53194a93ce1ebc77b3f07271ed4dbc06258aa995b844ef428\",\n        \"size\": 179281591\n    },\n    \"HazardAtSideLane_Town12_Route1795_Weather21.tar.gz\": {\n        \"sha256\": \"8ac6f13f72ad03af38c68db055cecb518a8b79da7e6c3e36aced02963fb00054\",\n        \"size\": 399865114\n    },\n    \"HazardAtSideLane_Town12_Route1796_Weather22.tar.gz\": {\n        \"sha256\": \"37bf20cd05df49e27dca78c9d3eb88cb8dfc27d83cca9d6ee275326752061dfb\",\n        \"size\": 387937683\n    },\n    \"HazardAtSideLane_Town12_Route1797_Weather23.tar.gz\": {\n        \"sha256\": \"bfbc495cda6400a12c91b3947a59f4e3721bfe29f1bc80bbb977cdee74b3ffab\",\n        \"size\": 149668522\n    },\n    \"HazardAtSideLane_Town12_Route1798_Weather23.tar.gz\": {\n        \"sha256\": \"bb0b26a1de80bd7f151ec853eddce024d903508022a3cc7fbf4c370dc9ab27db\",\n        \"size\": 152380709\n    },\n    \"HazardAtSideLane_Town12_Route1799_Weather25.tar.gz\": {\n        \"sha256\": \"d71feb27533406ae8fece4ece40f7d4891b912dc2ca033f03da92ec8e9a5f199\",\n        \"size\": 145967334\n    },\n    \"HazardAtSideLane_Town12_Route1800_Weather0.tar.gz\": {\n        \"sha256\": \"3ebfb861c3160a3a88454b96e814c69b30724eabb3d799755a3f577131ceff30\",\n        \"size\": 453806283\n    },\n    \"HazardAtSideLane_Town12_Route1801_Weather1.tar.gz\": {\n        \"sha256\": \"fd70dea5fa289c3b022a3bfe9080176e350d3caeed7e088ec838c5c405c3dfce\",\n        \"size\": 236641171\n    },\n    \"HazardAtSideLane_Town12_Route1802_Weather2.tar.gz\": {\n        \"sha256\": \"a07aeba33b43d262f4d8acedc0018ac50319eb948eee499f2fbdd62c59025e3a\",\n        \"size\": 244418317\n    },\n    \"HazardAtSideLane_Town12_Route1803_Weather3.tar.gz\": {\n        \"sha256\": \"33921307714a05a012a8dcd3ef85cbda9404b96a3b2e65f3949c1224c40ebdf6\",\n        \"size\": 330898245\n    },\n    \"HazardAtSideLane_Town12_Route2564_Weather10.tar.gz\": {\n        \"sha256\": \"ed4aae798b4089d5a7ede89c6da497453a3d9961eb9031bcb59817aefa37ae17\",\n        \"size\": 168112707\n    },\n    \"HazardAtSideLane_Town12_Route2565_Weather11.tar.gz\": {\n        \"sha256\": \"b6e70645c1b696d69025c584b975486185aaadced321afbaa8db359126b7914b\",\n        \"size\": 206177920\n    },\n    \"HazardAtSideLane_Town12_Route2566_Weather12.tar.gz\": {\n        \"sha256\": \"c3aa0a7efac8a68251b4b957e474aa1be5b6dc9d2e9eee065401b5fc91e346b0\",\n        \"size\": 503477610\n    },\n    \"HazardAtSideLane_Town12_Route2567_Weather13.tar.gz\": {\n        \"sha256\": \"bdcc7bfe4f076d9caeb67ac2eb978de204340c17738af6c5ac87a42bec578bf3\",\n        \"size\": 163190944\n    },\n    \"HazardAtSideLane_Town12_Route2569_Weather15.tar.gz\": {\n        \"sha256\": \"a91a8d6142ac82251e4d0f0e756c43f84795014bcd4a50daf603b297b49798f6\",\n        \"size\": 155991281\n    },\n    \"HazardAtSideLane_Town12_Route2571_Weather9.tar.gz\": {\n        \"sha256\": \"e74cf2b8f2cf51d2072ef15ea45155fa2487bd4e7612c9730b4c8f268c88fa6e\",\n        \"size\": 323257291\n    },\n    \"HazardAtSideLane_Town12_Route2572_Weather18.tar.gz\": {\n        \"sha256\": \"24693ca6dfeae5bd494ebad82c1e3a0af52b9be6870a9b85594bad3f9945732e\",\n        \"size\": 526159589\n    },\n    \"HazardAtSideLane_Town12_Route2573_Weather19.tar.gz\": {\n        \"sha256\": \"12262b78366eb9c83ae34e326584e2754386310fa80bde2788f8482a811aeb8d\",\n        \"size\": 391820628\n    },\n    \"HazardAtSideLane_Town12_Route2574_Weather20.tar.gz\": {\n        \"sha256\": \"1aaa81c8ca450910aab867da28788c78108692a8f00ea338d0daf4d62204ff83\",\n        \"size\": 189689814\n    },\n    \"HazardAtSideLane_Town12_Route2575_Weather21.tar.gz\": {\n        \"sha256\": \"3f1504af37482855bb680159e31f712a11f6597b801fbb2d15110ab941eff430\",\n        \"size\": 165921583\n    },\n    \"HazardAtSideLane_Town12_Route2576_Weather22.tar.gz\": {\n        \"sha256\": \"0337bc3785f4e914cf86945a290912862d8477953206435a0e656eb8a8fb3007\",\n        \"size\": 189647264\n    },\n    \"HazardAtSideLane_Town12_Route2577_Weather23.tar.gz\": {\n        \"sha256\": \"d80614725212f8e1892fea25f72d1bbb2ad96ee3bb82649ceb0388b3ca7b3025\",\n        \"size\": 368740408\n    },\n    \"HazardAtSideLane_Town12_Route2579_Weather25.tar.gz\": {\n        \"sha256\": \"8fa6d783877b2504a811f70e729753d6649fab00ef4f709ca463794535f85b90\",\n        \"size\": 525708920\n    },\n    \"HazardAtSideLane_Town12_Route2581_Weather1.tar.gz\": {\n        \"sha256\": \"ca091ae8d47887657e52d1f3fcd2603f603715da15ac19a12915234bfc21c692\",\n        \"size\": 528100292\n    },\n    \"HazardAtSideLane_Town12_Route2583_Weather3.tar.gz\": {\n        \"sha256\": \"1b2d84a15fa2c116bd2cdb9bbfba8d0be6c3e1f05913073a3411b09ca4ab303b\",\n        \"size\": 461389254\n    },\n    \"HazardAtSideLane_Town13_Route112_Weather23.tar.gz\": {\n        \"sha256\": \"0bd1dc0af72aebb109e0f2753763fe45bb388a0a111e8f2ee8e3b7f9a62fe7f4\",\n        \"size\": 400697719\n    },\n    \"HazardAtSideLane_Town13_Route224_Weather20.tar.gz\": {\n        \"sha256\": \"02f0ada3b29aeb30917d1f0a8f3ccdc54b43c16418a277bd64b66ee29f155315\",\n        \"size\": 510143765\n    },\n    \"HazardAtSideLane_Town13_Route28359_Weather10.tar.gz\": {\n        \"sha256\": \"d824ea4f92dedca64596dbe295c9910195425118dbb1277c3559adb690910e54\",\n        \"size\": 513698464\n    },\n    \"HazardAtSideLane_Town13_Route28370_Weather23.tar.gz\": {\n        \"sha256\": \"792bb9c050049d4a9bbe99bc647531b59df9da0376cd69935390f5d9aa637ca4\",\n        \"size\": 542259716\n    },\n    \"HazardAtSideLane_Town13_Route28394_Weather25.tar.gz\": {\n        \"sha256\": \"5cc43c905fa8bc875a60f656fd6e22b69846e9a91c898235b34a955800b91834\",\n        \"size\": 273744020\n    },\n    \"HazardAtSideLane_Town13_Route28421_Weather2.tar.gz\": {\n        \"sha256\": \"9c17cc7c573294ea12fd4ad1f8f494543d28545f6737c2994d65f0227b427c82\",\n        \"size\": 672233916\n    },\n    \"HazardAtSideLane_Town13_Route28450_Weather9.tar.gz\": {\n        \"sha256\": \"c740a1410cba98dd4f83f8903e0690720b21b44a66113729f3449523f9dec917\",\n        \"size\": 240372690\n    },\n    \"HazardAtSideLane_Town13_Route28468_Weather3.tar.gz\": {\n        \"sha256\": \"d002961e8336d22bf4f56d3343194b59d245f28178417d0e64e63c60ed73bde4\",\n        \"size\": 685281530\n    },\n    \"HazardAtSideLane_Town13_Route28494_Weather7.tar.gz\": {\n        \"sha256\": \"770645cb16e6a3d683ee7449e7543c2fde9b53431e86b78b096b433793b41fd0\",\n        \"size\": 802217440\n    },\n    \"HazardAtSideLane_Town13_Route28504_Weather19.tar.gz\": {\n        \"sha256\": \"e4e98b5ca00c12883dfdcec4adcb58bc465c5ba737e9ac10ea4500cabd71340f\",\n        \"size\": 380032684\n    },\n    \"HazardAtSideLane_Town13_Route28510_Weather26.tar.gz\": {\n        \"sha256\": \"0700298fd6d418ea2a880f50635159bd7fc747b2bdae91308970d8229f68f810\",\n        \"size\": 531754581\n    },\n    \"HazardAtSideLane_Town13_Route28517_Weather7.tar.gz\": {\n        \"sha256\": \"71839fff15d3912a40fa551484673da1f47d56960cd21a2ff28540d2ef4c0b00\",\n        \"size\": 603619134\n    },\n    \"HazardAtSideLane_Town13_Route28518_Weather8.tar.gz\": {\n        \"sha256\": \"b2525b390b31f97c6d20f89956024bd857e3196b256e63e29468ae8608d005cb\",\n        \"size\": 564702065\n    },\n    \"HazardAtSideLane_Town13_Route28537_Weather3.tar.gz\": {\n        \"sha256\": \"9bee63c6745d8a74f2f69b2bbcef391376ad9144137c1258f31b6be21df93650\",\n        \"size\": 631617704\n    },\n    \"HazardAtSideLane_Town13_Route28539_Weather6.tar.gz\": {\n        \"sha256\": \"0551a3255a7e87f8847d5e5ca6c25d11925a6d23cd51527a7fab2f370951d399\",\n        \"size\": 662463899\n    },\n    \"HazardAtSideLane_Town13_Route28546_Weather13.tar.gz\": {\n        \"sha256\": \"b12f30e2bdfc67c83e607437982812398276da0ad1ab207b7c81f524f8e1cd05\",\n        \"size\": 567096266\n    },\n    \"HazardAtSideLane_Town13_Route28561_Weather5.tar.gz\": {\n        \"sha256\": \"9000c893fea0989b0e991c4366f76c2c95e0d2d4a521f6f0f7008f4a8cfc39ad\",\n        \"size\": 391828797\n    },\n    \"HazardAtSideLane_Town13_Route3343_Weather10.tar.gz\": {\n        \"sha256\": \"f24b8966a93a55c9bb81aa2030d3a245645b4e1c57ac476ead7d8925e2b1013f\",\n        \"size\": 527052261\n    },\n    \"HazardAtSideLane_Town13_Route3344_Weather11.tar.gz\": {\n        \"sha256\": \"857c6e38796d7c2486f9aea6a811f775aaabae700e5fdada005df8dac265f74d\",\n        \"size\": 377597137\n    },\n    \"HazardAtSideLane_Town13_Route3345_Weather12.tar.gz\": {\n        \"sha256\": \"86cc46769750bfd68481ca1f27445cb2bdc871a5cf42c231ea3f0a7421702461\",\n        \"size\": 544364473\n    },\n    \"HazardAtSideLane_Town13_Route3346_Weather13.tar.gz\": {\n        \"sha256\": \"cb9c757e497d6afbc9e32bc16df0ae0dc14a727032f5fc028b32798432296488\",\n        \"size\": 756757141\n    },\n    \"HazardAtSideLane_Town13_Route3347_Weather14.tar.gz\": {\n        \"sha256\": \"7f13b6fff6fe03fe956a058cb890a4b12cf6119ea0cadb9da13408c62f4f01ed\",\n        \"size\": 732269073\n    },\n    \"HazardAtSideLane_Town13_Route3348_Weather15.tar.gz\": {\n        \"sha256\": \"db4e30ca3bc0653756f43b9b5f58ad8f63a3f367829b66c3a50d25755bf20d47\",\n        \"size\": 752727090\n    },\n    \"HazardAtSideLane_Town13_Route3349_Weather8.tar.gz\": {\n        \"sha256\": \"df12d8f7f0e0d8fcfc93abc2fe60e27848ca806d2da223d3deee5d44c8fec93c\",\n        \"size\": 239774742\n    },\n    \"HazardAtSideLane_Town13_Route3350_Weather9.tar.gz\": {\n        \"sha256\": \"6cb1c83c6242f00eba00cc05d7c08814c54059e4a73811e2d4c68ff64158bab4\",\n        \"size\": 736639920\n    },\n    \"HazardAtSideLane_Town13_Route3351_Weather18.tar.gz\": {\n        \"sha256\": \"3472c557a4b9c817700b9f401a84d943cba93b03225e515ef1e11524d79c53e3\",\n        \"size\": 847342905\n    },\n    \"HazardAtSideLane_Town13_Route3352_Weather19.tar.gz\": {\n        \"sha256\": \"a123c8b289e5f2dbfe7fa2ecbc8e652758564c0355fa616f66be01836cdefb75\",\n        \"size\": 752266463\n    },\n    \"HazardAtSideLane_Town13_Route3354_Weather21.tar.gz\": {\n        \"sha256\": \"5a74bfbb8667274634b88d2046db3d8189c27986b9336c0dbe05cbb603f5ddd8\",\n        \"size\": 414030844\n    },\n    \"HazardAtSideLane_Town13_Route3355_Weather22.tar.gz\": {\n        \"sha256\": \"864795c4c1fbc83645f641d6a4ee5d946769958b9e060d0c3250c9e3f70c3e09\",\n        \"size\": 706208316\n    },\n    \"HazardAtSideLane_Town13_Route3357_Weather23.tar.gz\": {\n        \"sha256\": \"25192b5952d4c80c62e74da9d45d3556d1068a7f3184b2af426b0d5edf750b9f\",\n        \"size\": 755335090\n    },\n    \"HazardAtSideLane_Town13_Route3358_Weather25.tar.gz\": {\n        \"sha256\": \"32931add59f1430cd6e819288aae65ed19e79a9e55503b1c456d80885ae8ffd7\",\n        \"size\": 507158653\n    },\n    \"HazardAtSideLane_Town13_Route3359_Weather0.tar.gz\": {\n        \"sha256\": \"1373cf23f35aca2533f0f040e79501a5ef9dfb57eba2da89d33a6910d6ebe0c1\",\n        \"size\": 639033293\n    },\n    \"HazardAtSideLane_Town13_Route3360_Weather1.tar.gz\": {\n        \"sha256\": \"7320382242bd7f9f81d84a8617f439505f32c3043405598f2fae917216373be2\",\n        \"size\": 434930502\n    },\n    \"HazardAtSideLane_Town13_Route3361_Weather2.tar.gz\": {\n        \"sha256\": \"5294a6e60c4467b1e1217f5e9c8f55a04983fe7e3aef3a4f9727082771cd6363\",\n        \"size\": 397185183\n    },\n    \"HazardAtSideLane_Town13_Route444_Weather8.tar.gz\": {\n        \"sha256\": \"0182eff9be2bcb1fa4d338c9b04e8f164ceda662259df084479fa7a8d1e13282\",\n        \"size\": 717330447\n    },\n    \"HazardAtSideLane_Town13_Route469_Weather10.tar.gz\": {\n        \"sha256\": \"d4ab0deb536f1243938610f5e76a8134421dd16f7925c117c5275cc57ef89df6\",\n        \"size\": 265103176\n    },\n    \"HazardAtSideLane_Town15_Route25404_Weather12.tar.gz\": {\n        \"sha256\": \"3ab4667c8a37844e5287c10b0c4fb85fd7e5140638e1350bab80c7287290df18\",\n        \"size\": 644908144\n    },\n    \"HazardAtSideLane_Town15_Route25418_Weather2.tar.gz\": {\n        \"sha256\": \"821792286b247e2e19d748b3c24a1c6271ec0a90402c5a42c9cf77ddfa028d4e\",\n        \"size\": 545434108\n    },\n    \"HazardAtSideLane_Town15_Route25425_Weather10.tar.gz\": {\n        \"sha256\": \"6ee67a693d2c29292325f58605385e0f36a55863a6f7c4e751d335172a6a5964\",\n        \"size\": 378617456\n    },\n    \"HazardAtSideLane_Town15_Route25439_Weather0.tar.gz\": {\n        \"sha256\": \"82da86b6bf9297ca8e520d0bad4e3597eca3054a9dbd10a9977eae28498d3918\",\n        \"size\": 762426810\n    },\n    \"HighwayCutIn_Town12_Route2284_Weather8.tar.gz\": {\n        \"sha256\": \"60e7472234a0140236cb68129a534e8aec86a12784e1881b462fe16dcd5322b3\",\n        \"size\": 214687361\n    },\n    \"HighwayCutIn_Town12_Route2285_Weather9.tar.gz\": {\n        \"sha256\": \"8373d3d1333f75c598cec852cd762f813695069b854d82e211b59723a4ab07b3\",\n        \"size\": 271053734\n    },\n    \"HighwayCutIn_Town12_Route2286_Weather18.tar.gz\": {\n        \"sha256\": \"0f2dbf2fdb2983bd1c3ae15a927fed72dc8274f18679a5ef88f043ba8a66a7d5\",\n        \"size\": 264297293\n    },\n    \"HighwayCutIn_Town12_Route2287_Weather19.tar.gz\": {\n        \"sha256\": \"d0fbdd4290f2e092d6387c22713fe0e2d245396cae1a78f4d4a179d3b6bfae65\",\n        \"size\": 251857569\n    },\n    \"HighwayCutIn_Town12_Route2288_Weather20.tar.gz\": {\n        \"sha256\": \"a019c971cdd91fd6f0681c554ee7312497c157c15744d4aa2d2a39726ff2f1af\",\n        \"size\": 209685870\n    },\n    \"HighwayCutIn_Town12_Route2289_Weather21.tar.gz\": {\n        \"sha256\": \"4816620d9a0ca61f4cadb58ec930403253c3b19aeecf2f0cb1468817ae3fbba9\",\n        \"size\": 142040258\n    },\n    \"HighwayCutIn_Town12_Route2290_Weather22.tar.gz\": {\n        \"sha256\": \"15982a8af84803ac3cb93e9cec1c7400a019280dc8cddad9f1bca94a5edc11a6\",\n        \"size\": 237832076\n    },\n    \"HighwayCutIn_Town12_Route2291_Weather23.tar.gz\": {\n        \"sha256\": \"df1758e4bb1c151a4d0609eb8dd6a864485e207b8a7d277d4d0ab5d302cd8ba2\",\n        \"size\": 213131749\n    },\n    \"HighwayCutIn_Town12_Route2292_Weather23.tar.gz\": {\n        \"sha256\": \"f7318733a28877b15b34a0667824c3e26e607c39adc068e9a0adf3a7f192d155\",\n        \"size\": 149157544\n    },\n    \"HighwayCutIn_Town12_Route2293_Weather25.tar.gz\": {\n        \"sha256\": \"baae16549e3b3b6c56e5d3fd986b36455949070bc7a0ec7730cb0c6eb9d707e3\",\n        \"size\": 210455701\n    },\n    \"HighwayCutIn_Town12_Route2294_Weather0.tar.gz\": {\n        \"sha256\": \"4c085f910a87ed848d95d14bdc6a3aa89afb531ece4f7de34f0c602d84e2d364\",\n        \"size\": 204472041\n    },\n    \"HighwayCutIn_Town12_Route2295_Weather1.tar.gz\": {\n        \"sha256\": \"1823c70ac945135faa251be5b040b9ee915e54b355025a0343619bef35eca801\",\n        \"size\": 215314220\n    },\n    \"HighwayCutIn_Town12_Route2296_Weather2.tar.gz\": {\n        \"sha256\": \"b0b2ceba4e861769c1aa621af02ceae6339be039943a47f1cee6ddec26419c74\",\n        \"size\": 190802395\n    },\n    \"HighwayCutIn_Town12_Route2297_Weather3.tar.gz\": {\n        \"sha256\": \"de28fbf4806364d6ad82fb9eedd70594068f11a2d2956b29462468c700104681\",\n        \"size\": 234881356\n    },\n    \"HighwayCutIn_Town12_Route2298_Weather3.tar.gz\": {\n        \"sha256\": \"8b8ba22c04700a54fc8fa0379a96f89c053f214efdbc74ab39a1a954a5505158\",\n        \"size\": 241847264\n    },\n    \"HighwayCutIn_Town12_Route2299_Weather5.tar.gz\": {\n        \"sha256\": \"0341c973afebf90ac4a679cc69d8204c2402e5b1635335366cac69a03be7fe45\",\n        \"size\": 228339443\n    },\n    \"HighwayCutIn_Town12_Route2300_Weather6.tar.gz\": {\n        \"sha256\": \"9e664314e8ed0d4c292e43bab1ab0246128a0ded4b4f5969ec9aec4ff7650706\",\n        \"size\": 296330384\n    },\n    \"HighwayCutIn_Town12_Route2301_Weather7.tar.gz\": {\n        \"sha256\": \"ce6ff3656033395440b92f11680fe625187e93735c332cd3be07449e398215d4\",\n        \"size\": 249171332\n    },\n    \"HighwayCutIn_Town12_Route2302_Weather8.tar.gz\": {\n        \"sha256\": \"be467ec835c5b202a6ef6d817e080471c2efbd483e91acd4c9942a6654c4d419\",\n        \"size\": 226410497\n    },\n    \"HighwayCutIn_Town12_Route2303_Weather9.tar.gz\": {\n        \"sha256\": \"81f129b72b61b43d2b15d8c4f0207c99b6cb9721546349b0291825540ac567d6\",\n        \"size\": 201854101\n    },\n    \"HighwayCutIn_Town12_Route23645_Weather13.tar.gz\": {\n        \"sha256\": \"c7bf9690ff1f68df711bf87831ca082c66f7d4a7e80261542e44fcd4c99d8d26\",\n        \"size\": 247360472\n    },\n    \"HighwayCutIn_Town12_Route23648_Weather18.tar.gz\": {\n        \"sha256\": \"5b1403463373ef233de8bce99e808c0a8350799d7e9f09dabee3de41d3a3db9f\",\n        \"size\": 273949633\n    },\n    \"HighwayCutIn_Town12_Route23652_Weather22.tar.gz\": {\n        \"sha256\": \"a5b78f3c433ddd6c5792745df26e3e34aae8245a937501079c58ea16fc866f9a\",\n        \"size\": 201321186\n    },\n    \"HighwayCutIn_Town12_Route23654_Weather25.tar.gz\": {\n        \"sha256\": \"33be7ecc3e0e3d3921681bdbe8a3c685214b5eec63bdce16f4af2bd7782c4f72\",\n        \"size\": 192896353\n    },\n    \"HighwayCutIn_Town12_Route23667_Weather12.tar.gz\": {\n        \"sha256\": \"9c939206e3cfd80359f639fc5b04f48ef5c23d3f96ebf1b00a7ae6ab9e930b81\",\n        \"size\": 194355799\n    },\n    \"HighwayCutIn_Town12_Route23668_Weather13.tar.gz\": {\n        \"sha256\": \"b53ab3323546ae1da0076463f97d2cb1bece66774d7e8fcb9d7dcaa3b2253611\",\n        \"size\": 195715434\n    },\n    \"HighwayCutIn_Town12_Route23680_Weather1.tar.gz\": {\n        \"sha256\": \"bfa184e45464fd7c4d51cb1c7957c0c7a0f2141c17833e483bdfdf6303028960\",\n        \"size\": 173455430\n    },\n    \"HighwayCutIn_Town12_Route23681_Weather2.tar.gz\": {\n        \"sha256\": \"07a28967c30155f267fef003a6286ef44ce6ba67167be913f8edacda5093bec0\",\n        \"size\": 189316355\n    },\n    \"HighwayCutIn_Town12_Route23682_Weather3.tar.gz\": {\n        \"sha256\": \"fb0c38194abfb91f1abe451711045d70c5bd72b4dfa2db664a47db5a3718e493\",\n        \"size\": 198999573\n    },\n    \"HighwayCutIn_Town12_Route23683_Weather5.tar.gz\": {\n        \"sha256\": \"d7131b481ca2d34d3e1368cb56d9f065c8e3cd59263b686d51f511acfd27faff\",\n        \"size\": 226588157\n    },\n    \"HighwayCutIn_Town12_Route23684_Weather6.tar.gz\": {\n        \"sha256\": \"a829d62a9065978d357b708a8744682bc3127b4a2062621201f594447850dd9d\",\n        \"size\": 220570699\n    },\n    \"HighwayCutIn_Town12_Route23685_Weather7.tar.gz\": {\n        \"sha256\": \"fc9c81a4e36e01d41d70ad04b67ba96be959194ac94314c2c42f097302b552ac\",\n        \"size\": 309805424\n    },\n    \"HighwayCutIn_Town12_Route23686_Weather8.tar.gz\": {\n        \"sha256\": \"65b8302833e469732f62cb60e55d133877ddb0d4261ad93cb9f3449340731577\",\n        \"size\": 280114146\n    },\n    \"HighwayCutIn_Town12_Route23693_Weather15.tar.gz\": {\n        \"sha256\": \"71c2d8de0ae748c269b30b560e87bb6834c3903163f5e3ae9345cf5209930ec1\",\n        \"size\": 140463377\n    },\n    \"HighwayCutIn_Town12_Route23697_Weather21.tar.gz\": {\n        \"sha256\": \"875ce5acc3fa30363ca3d040707a71de182e4f54fcb2b0e90bce887d5133bb5a\",\n        \"size\": 204990632\n    },\n    \"HighwayCutIn_Town12_Route23698_Weather22.tar.gz\": {\n        \"sha256\": \"f5683fb40f08f484a9523677d1a46ce32696c61c13f4cf8e31bea4cd5d2f65ba\",\n        \"size\": 204616915\n    },\n    \"HighwayCutIn_Town12_Route23824_Weather8.tar.gz\": {\n        \"sha256\": \"3503af50ee29ca75e78ded6a821c8c8edada21a05ea3e72d2f55cab6c4867290\",\n        \"size\": 206245242\n    },\n    \"HighwayCutIn_Town12_Route23828_Weather12.tar.gz\": {\n        \"sha256\": \"a86d38a600ff0f858971a17fb8f480d89cf9ddcd475092ad0f079c76f7c510b3\",\n        \"size\": 192773071\n    },\n    \"HighwayCutIn_Town12_Route23833_Weather19.tar.gz\": {\n        \"sha256\": \"1e96c839b3eb25655476fa1f7a484256e5ccc3ce3c97ef64e704ac65309d9658\",\n        \"size\": 225235388\n    },\n    \"HighwayCutIn_Town12_Route23836_Weather22.tar.gz\": {\n        \"sha256\": \"6ad5a9cb53ba8712db9debe27c1789d860795adc4f06b72abe210d975e2dd8d4\",\n        \"size\": 234002324\n    },\n    \"HighwayCutIn_Town12_Route23855_Weather18.tar.gz\": {\n        \"sha256\": \"7d7df921c036c04875d333b78a05ec44e0656c910f9d9db59d7595a30ab8f219\",\n        \"size\": 226021071\n    },\n    \"HighwayCutIn_Town12_Route23856_Weather19.tar.gz\": {\n        \"sha256\": \"a37d304e53d08bc77b5753dd753b7e82c5df10a14d62f662838fdae786eae319\",\n        \"size\": 205105174\n    },\n    \"HighwayCutIn_Town12_Route23866_Weather3.tar.gz\": {\n        \"sha256\": \"cfb012b16c8e249aeaafe979b768deebb4caa35dfeb367f9200e530ca52a187a\",\n        \"size\": 160341126\n    },\n    \"HighwayCutIn_Town12_Route23868_Weather6.tar.gz\": {\n        \"sha256\": \"12a2d6ba687ac3c88e76a196794d4aa93017fbddc17f1c85b1ea37916e83f9d1\",\n        \"size\": 163765784\n    },\n    \"HighwayCutIn_Town12_Route23869_Weather7.tar.gz\": {\n        \"sha256\": \"85f6f61153fe5e6b4b9c54f4d1d716cf25c34fa9d704a4f6b57495218ffee7d9\",\n        \"size\": 193215404\n    },\n    \"HighwayCutIn_Town12_Route23870_Weather8.tar.gz\": {\n        \"sha256\": \"1b3b6b09d207c7ff433d72613e54698fa90d992216f517be8a36d9752927dac3\",\n        \"size\": 184298825\n    },\n    \"HighwayCutIn_Town12_Route23871_Weather9.tar.gz\": {\n        \"sha256\": \"0ad89a002ceb0469ca2a7606ba7f53a62e215929c156d032f75523df8b4f98ce\",\n        \"size\": 195970809\n    },\n    \"HighwayCutIn_Town12_Route23872_Weather10.tar.gz\": {\n        \"sha256\": \"d5ad8d324b14fc39d426c666b0bff9bfcab1f4be5d8cac0893adc9390af1160b\",\n        \"size\": 201789872\n    },\n    \"HighwayCutIn_Town12_Route23873_Weather11.tar.gz\": {\n        \"sha256\": \"9d1a7c66b5d3e7ebef9a3af027e9bb57a7b8ca2add83b3906a386d04e413756b\",\n        \"size\": 257400513\n    },\n    \"HighwayCutIn_Town12_Route23874_Weather12.tar.gz\": {\n        \"sha256\": \"8c7e748ab3a136e16ea7124570ca3a0a4391b9afc0677f4d54b6029c00ac7df8\",\n        \"size\": 248928901\n    },\n    \"HighwayCutIn_Town12_Route24012_Weather12.tar.gz\": {\n        \"sha256\": \"01e665537e1f9dff65601ce1abbb61fd843e7db0296e366ba04d316ec6e5b504\",\n        \"size\": 186851815\n    },\n    \"HighwayCutIn_Town12_Route24016_Weather18.tar.gz\": {\n        \"sha256\": \"aa94abfff689d2f402eb735d6426fc3319d2d271fafbb8d6d470651c0aabcbe0\",\n        \"size\": 222998111\n    },\n    \"HighwayCutIn_Town12_Route24021_Weather23.tar.gz\": {\n        \"sha256\": \"8c15ba91857497de2bb7e013098cc9cb225227bc05cc2e7d1b396b098e5b9939\",\n        \"size\": 224217373\n    },\n    \"HighwayCutIn_Town12_Route24028_Weather5.tar.gz\": {\n        \"sha256\": \"ff61cd35b4a5b3d178d14a8325c53f3dedfe7c4ce9eaa05007b10305a3617cc3\",\n        \"size\": 223294552\n    },\n    \"HighwayCutIn_Town12_Route24030_Weather7.tar.gz\": {\n        \"sha256\": \"f252eab65a72514ddafa77012923635b12192a8d683fe13b0fe8a86f0d837656\",\n        \"size\": 231981143\n    },\n    \"HighwayCutIn_Town12_Route24043_Weather22.tar.gz\": {\n        \"sha256\": \"23e37ff401794c5ac7bbfabee9c8d0b52baa5d2952c5af3a6ca0ca437cd4a47f\",\n        \"size\": 199557891\n    },\n    \"HighwayCutIn_Town12_Route24044_Weather23.tar.gz\": {\n        \"sha256\": \"959bb44d6db40e430d706a27c605c0f4617bc294e07204037fafa2d33ab677fe\",\n        \"size\": 199845899\n    },\n    \"HighwayCutIn_Town12_Route24054_Weather8.tar.gz\": {\n        \"sha256\": \"89b9e2862df36d2874d00b6df9402f4c4d9c0648ecbe124b696583b61873a3e4\",\n        \"size\": 154589142\n    },\n    \"HighwayCutIn_Town12_Route24056_Weather10.tar.gz\": {\n        \"sha256\": \"11ae65564cbec13ab916a287d9758718dd5855bf987b9a8db740b606bfec466c\",\n        \"size\": 152764306\n    },\n    \"HighwayCutIn_Town12_Route24057_Weather11.tar.gz\": {\n        \"sha256\": \"0ff07e876ea2f8c90db48f2124573280ebb92d0c14511539935ba80fbc40a71c\",\n        \"size\": 163655917\n    },\n    \"HighwayCutIn_Town12_Route24058_Weather12.tar.gz\": {\n        \"sha256\": \"65f923e51d55a8269ea6f20a9c0daa1e6bcf1fd5141611ff37010e3ed921f1d9\",\n        \"size\": 167688447\n    },\n    \"HighwayCutIn_Town12_Route24059_Weather13.tar.gz\": {\n        \"sha256\": \"071bef8a6537232fede563b0a961bcfffb3fd1e39efe009da50cd594dfcb006b\",\n        \"size\": 197834056\n    },\n    \"HighwayCutIn_Town12_Route24060_Weather14.tar.gz\": {\n        \"sha256\": \"968e734c3dea2027ceb013269cab1ed4ea6e21c4d04bc9d26940bd143c1bfc6f\",\n        \"size\": 216695967\n    },\n    \"HighwayCutIn_Town12_Route24061_Weather15.tar.gz\": {\n        \"sha256\": \"ea54f87cfb2ba5701deb3ffeb72dafb367d6dd1f96ff429bb7e637a76db321dc\",\n        \"size\": 284384976\n    },\n    \"HighwayCutIn_Town12_Route24062_Weather18.tar.gz\": {\n        \"sha256\": \"108bea3a5071e8b9ea97bc4dc4982b33404431b29b541d5bf532389bd17fecc1\",\n        \"size\": 300675138\n    },\n    \"HighwayCutIn_Town12_Route24073_Weather3.tar.gz\": {\n        \"sha256\": \"d7d5e01dacd743b3418f2424e9dee94adaabcfa8a25dd21071441aee63d06a92\",\n        \"size\": 238972281\n    },\n    \"HighwayCutIn_Town12_Route24074_Weather5.tar.gz\": {\n        \"sha256\": \"5ef9bbea781a3505d907b706829b9f230183f584fc80417204f72e765100f7cd\",\n        \"size\": 231009223\n    },\n    \"HighwayCutIn_Town12_Route3064_Weather8.tar.gz\": {\n        \"sha256\": \"5b4ba7c02d99b578ada8d96755782e0427a25c583d3dbe979cf21dac1395c01c\",\n        \"size\": 328919476\n    },\n    \"HighwayCutIn_Town12_Route3065_Weather9.tar.gz\": {\n        \"sha256\": \"0209112562fd374f50147d44661cab4ea50e7be1cb1e200c35ac171100dfcf9c\",\n        \"size\": 213044006\n    },\n    \"HighwayCutIn_Town12_Route3066_Weather18.tar.gz\": {\n        \"sha256\": \"d855cee05dfee827c4be23044ecfc9d25248b7633d4764f9c920752138407929\",\n        \"size\": 177450083\n    },\n    \"HighwayCutIn_Town12_Route3067_Weather19.tar.gz\": {\n        \"sha256\": \"534b1c45106ffca7a7190207d469a837cb2ea1805424bafdf3d0e50c96798b3b\",\n        \"size\": 157586460\n    },\n    \"HighwayCutIn_Town12_Route3068_Weather20.tar.gz\": {\n        \"sha256\": \"d51328d64b0b72ac3d12c19c2f8cd896533827d43e7a0f18f70ec5621f9129dc\",\n        \"size\": 231287505\n    },\n    \"HighwayCutIn_Town12_Route3069_Weather21.tar.gz\": {\n        \"sha256\": \"97f711b9cb170e060bfe282e0d9017946a74e90beea4bbe0f5040a200b3b882c\",\n        \"size\": 240510811\n    },\n    \"HighwayCutIn_Town12_Route3070_Weather22.tar.gz\": {\n        \"sha256\": \"8f665efb0ee05ed19fd629df09acbc826c24cebea6160fafbee71d48624138af\",\n        \"size\": 196272818\n    },\n    \"HighwayCutIn_Town12_Route3071_Weather23.tar.gz\": {\n        \"sha256\": \"1bbeec3761934978df0117cd2af2081a5d64b61d05b3c2eadb2cbc1b03d609a5\",\n        \"size\": 245649378\n    },\n    \"HighwayCutIn_Town12_Route3072_Weather23.tar.gz\": {\n        \"sha256\": \"205bbab560b8ac8516bce8e708a56eec43ed2f9f076b294717c46e951f8e0a6d\",\n        \"size\": 203644605\n    },\n    \"HighwayCutIn_Town12_Route3073_Weather25.tar.gz\": {\n        \"sha256\": \"f5efe7c8cb7330782b332a6a481ae081959e54f667cf40857ed0f9d0f53429c0\",\n        \"size\": 134932474\n    },\n    \"HighwayCutIn_Town12_Route3074_Weather0.tar.gz\": {\n        \"sha256\": \"d9ebc34f15c4d86a98b940349a89ac79986611ef6b0dfe79a2c306c50b5b6b19\",\n        \"size\": 251701178\n    },\n    \"HighwayCutIn_Town12_Route3075_Weather1.tar.gz\": {\n        \"sha256\": \"3c7c47da41ee422d76f474ab722df252fc6d51a733736d66510b0a5e129cf1ff\",\n        \"size\": 265956058\n    },\n    \"HighwayCutIn_Town12_Route3076_Weather2.tar.gz\": {\n        \"sha256\": \"db8d30af8f6ab3f9306d591e89ed864e3b7a4db3bc84c84340e7b079be79d3cf\",\n        \"size\": 257375005\n    },\n    \"HighwayCutIn_Town12_Route3077_Weather3.tar.gz\": {\n        \"sha256\": \"a283329c7dc967444abc70e6b61e53a5b84be0906b1bb1a4d0c8dbea7e0ede27\",\n        \"size\": 248281151\n    },\n    \"HighwayCutIn_Town12_Route3080_Weather6.tar.gz\": {\n        \"sha256\": \"b379be01b9ffc0e107dbe8455c9c29350fb28ba60dfc0efc8a865fd2e9b0868d\",\n        \"size\": 227636023\n    },\n    \"HighwayCutIn_Town12_Route3083_Weather9.tar.gz\": {\n        \"sha256\": \"42ef40b6278e4eeb9c771e4a66a0dff33bc0ec5e9bb799ad44627e39b6dee22c\",\n        \"size\": 197412618\n    },\n    \"HighwayCutIn_Town13_Route23641_Weather9.tar.gz\": {\n        \"sha256\": \"cfdbde202a0acc13ac4270bb40acd2693d8d30c61af8b9bdf528896a2a345f97\",\n        \"size\": 415961141\n    },\n    \"HighwayCutIn_Town13_Route23642_Weather10.tar.gz\": {\n        \"sha256\": \"e651e5dd9c9e53b04224623e9c1b15bb2f13526cb7f40dd0f23a8864b8350cfe\",\n        \"size\": 412654933\n    },\n    \"HighwayCutIn_Town13_Route23644_Weather12.tar.gz\": {\n        \"sha256\": \"422bdc6acae783eaa31871b52648812fb6db69e63e7047c0178baf1374771b63\",\n        \"size\": 530466135\n    },\n    \"HighwayCutIn_Town13_Route23647_Weather15.tar.gz\": {\n        \"sha256\": \"7e35d8bd25769ef14c18000df00737794f71a8824d045bf56a16c713965f597d\",\n        \"size\": 569725764\n    },\n    \"HighwayCutIn_Town13_Route23649_Weather19.tar.gz\": {\n        \"sha256\": \"7e8da32109fa5a9edf81a005afa95a5f9fc93b7c4d1a423f0280b2f7038fd00f\",\n        \"size\": 559309661\n    },\n    \"HighwayCutIn_Town13_Route23650_Weather20.tar.gz\": {\n        \"sha256\": \"0c027340c731ab434e7c0b5b652bf7b52131a98f94fe46e95830274950ff64c4\",\n        \"size\": 579860051\n    },\n    \"HighwayCutIn_Town13_Route23651_Weather21.tar.gz\": {\n        \"sha256\": \"782b760fba1aae73f55079c4413f4f0d1fe84c6263145a140de6fd29ef03120b\",\n        \"size\": 416231250\n    },\n    \"HighwayCutIn_Town13_Route23653_Weather23.tar.gz\": {\n        \"sha256\": \"307bc40544645589a7160ec4fdaebccaf9e7732d7884a7e25f062bc80ce80a9d\",\n        \"size\": 401998160\n    },\n    \"HighwayCutIn_Town13_Route23661_Weather6.tar.gz\": {\n        \"sha256\": \"1a936a57f2a88ecf39e35f7d03e3a60f4cd6504b496f496d6e63f9755a0c1e1c\",\n        \"size\": 179049177\n    },\n    \"HighwayCutIn_Town13_Route23662_Weather7.tar.gz\": {\n        \"sha256\": \"ab5b925940d2c2a5823ec7125d8866682c5595f26d2883b23028114eb31da923\",\n        \"size\": 200352932\n    },\n    \"HighwayCutIn_Town13_Route23674_Weather21.tar.gz\": {\n        \"sha256\": \"4afc6de1ce452f00cdf342bfbfbe78c3d12234b14f6c19c077b20c29fbd3adff\",\n        \"size\": 474175757\n    },\n    \"HighwayCutIn_Town13_Route23676_Weather23.tar.gz\": {\n        \"sha256\": \"c37de4812ea585a241be3482e59eb45af82e1abcd8e97c999d556c9cdebf0341\",\n        \"size\": 465876086\n    },\n    \"HighwayCutIn_Town13_Route23823_Weather7.tar.gz\": {\n        \"sha256\": \"130ff86a3cad4566cf939f1643557db6e1caae6bb49d1f72e45c1c004c560206\",\n        \"size\": 510907237\n    },\n    \"HighwayCutIn_Town13_Route23827_Weather11.tar.gz\": {\n        \"sha256\": \"9896700283b4b5f15a21f06613a62211be6ea819b984bccfd97fd60198ca1601\",\n        \"size\": 436318247\n    },\n    \"HighwayCutIn_Town13_Route23829_Weather13.tar.gz\": {\n        \"sha256\": \"1737170d547ae2ff32ac20dfcde20ceeb6134d7631992fb4e0198a35f34c3d87\",\n        \"size\": 399490311\n    },\n    \"HighwayCutIn_Town13_Route23830_Weather14.tar.gz\": {\n        \"sha256\": \"98ace5dfaf1a8f77b8949497043af555bd0f3ba7f48a18415d391e59f25c18d4\",\n        \"size\": 434294544\n    },\n    \"HighwayCutIn_Town13_Route23832_Weather18.tar.gz\": {\n        \"sha256\": \"917089395b7699ecc9d8cfefc95f3712e512007fc352b12d86d2ae527c456d51\",\n        \"size\": 573071811\n    },\n    \"HighwayCutIn_Town13_Route23835_Weather21.tar.gz\": {\n        \"sha256\": \"91c542192a3abead6c6bcd939f151d82b80382046a8d25f9d09b7fa7edc0c915\",\n        \"size\": 513984216\n    },\n    \"HighwayCutIn_Town13_Route23837_Weather23.tar.gz\": {\n        \"sha256\": \"0058fee7a99dc370acf84538d9c2cf353aa714cf21250ebc60d4559ceff6bf94\",\n        \"size\": 580090562\n    },\n    \"HighwayCutIn_Town13_Route23838_Weather25.tar.gz\": {\n        \"sha256\": \"8ef62501b00556ca3e16783d1d460c007d35cffbc5d5a7d225937411ec55bc11\",\n        \"size\": 566158788\n    },\n    \"HighwayCutIn_Town13_Route23849_Weather10.tar.gz\": {\n        \"sha256\": \"d588e1da7f526b092f75ebd47f3a79cab205b56371d5a6e132a5dfc1f84b1c51\",\n        \"size\": 164065695\n    },\n    \"HighwayCutIn_Town13_Route23850_Weather11.tar.gz\": {\n        \"sha256\": \"857ea6e4e264c3fae1d07461419707e4e445fc00ffcc9fa4a4408ca9bc46577d\",\n        \"size\": 169214957\n    },\n    \"HighwayCutIn_Town13_Route23864_Weather1.tar.gz\": {\n        \"sha256\": \"a9eda82a3aa0c0428c89c2978c133d6284aabd85eadfd861bc0a9877053d6fcd\",\n        \"size\": 555696285\n    },\n    \"HighwayCutIn_Town13_Route24011_Weather11.tar.gz\": {\n        \"sha256\": \"121c64666403ca3a0f00a46abbb6cc67d83ae63b271f5c2574b368b61eb36e33\",\n        \"size\": 451646078\n    },\n    \"HighwayCutIn_Town13_Route24015_Weather15.tar.gz\": {\n        \"sha256\": \"09ccfdf207de7ca122938abe6aeb2ace3702bf49617aef7b9f7e9ab044fe5fe8\",\n        \"size\": 475867906\n    },\n    \"HighwayCutIn_Town13_Route24017_Weather19.tar.gz\": {\n        \"sha256\": \"a0b18cc998221103ba672f79dcbade453e939762266b2c3afd9e7af604c1b001\",\n        \"size\": 424579727\n    },\n    \"HighwayCutIn_Town13_Route24018_Weather20.tar.gz\": {\n        \"sha256\": \"3f2079ddb6ba0c33f77d42433e22d1d7ea15ffca221770b989baff7e8a2792ea\",\n        \"size\": 374559586\n    },\n    \"HighwayCutIn_Town13_Route24020_Weather22.tar.gz\": {\n        \"sha256\": \"816d42e9b85fcae4bc0c65b42415a02fd4d9df8c03ead9e874d3d70b25e802bc\",\n        \"size\": 531043143\n    },\n    \"HighwayCutIn_Town13_Route24025_Weather1.tar.gz\": {\n        \"sha256\": \"0cd931187d74a45797f710d291b3edc5f75ee6bd45818069d7b0a142d8c0b79f\",\n        \"size\": 653560631\n    },\n    \"HighwayCutIn_Town13_Route24026_Weather2.tar.gz\": {\n        \"sha256\": \"f897a0d51d1ffe47e861c6f4bfd7f3681eee7a777509ca53e34f4d6c3bcf42c0\",\n        \"size\": 663016955\n    },\n    \"HighwayCutIn_Town13_Route24027_Weather3.tar.gz\": {\n        \"sha256\": \"aab20c296cafad1e82240efde73874debabcc97e4185cb4aa3c59f90296b2e9c\",\n        \"size\": 454885876\n    },\n    \"HighwayCutIn_Town13_Route24029_Weather6.tar.gz\": {\n        \"sha256\": \"9e4aa214d1fba64ac2918a3094d1b799dfb274254e5abf6d7ac802498f074098\",\n        \"size\": 468192004\n    },\n    \"HighwayCutIn_Town13_Route24037_Weather14.tar.gz\": {\n        \"sha256\": \"21a24e1148238bd9cd30cdc78bf299845b75ec2c9e01d5f78edb69c6e59d8867\",\n        \"size\": 175838626\n    },\n    \"HighwayCutIn_Town13_Route24038_Weather15.tar.gz\": {\n        \"sha256\": \"ddd3200d08a670e4fc6caa9f124736f9815afd87aeb1716ee5f26635291cc98c\",\n        \"size\": 177873990\n    },\n    \"HighwayCutIn_Town13_Route24050_Weather3.tar.gz\": {\n        \"sha256\": \"14e3e1a834a4703a531ac86612bfa2dcdbdbaf6bcb4bbb26ef04e8d23c35fe4f\",\n        \"size\": 504976606\n    },\n    \"HighwayCutIn_Town13_Route24052_Weather6.tar.gz\": {\n        \"sha256\": \"0daae39cbbab1732d40fb77610f0ca624a0353099c63728d7c61c3daed17880b\",\n        \"size\": 530178075\n    },\n    \"HighwayCutIn_Town13_Route3803_Weather2.tar.gz\": {\n        \"sha256\": \"1eecd024d47ae2db1ac9056482dec07938a0ef875cd152cbb900f3185555f24a\",\n        \"size\": 542335617\n    },\n    \"HighwayCutIn_Town13_Route3804_Weather3.tar.gz\": {\n        \"sha256\": \"6b6c2926035a15deb045ce9c991077f815e56a33e0b85542bf64893ed5c1ba93\",\n        \"size\": 235691091\n    },\n    \"HighwayCutIn_Town13_Route3805_Weather3.tar.gz\": {\n        \"sha256\": \"dedf0a960b2ca2eaf6bc6ce28fec5014b248037c13154173af6846197feb3e0f\",\n        \"size\": 482666908\n    },\n    \"HighwayCutIn_Town13_Route3806_Weather5.tar.gz\": {\n        \"sha256\": \"56a70db023dcf044201107bfc730dcc96f5ffb8fa1cbe31edea33b69e5a42f91\",\n        \"size\": 475762754\n    },\n    \"HighwayCutIn_Town13_Route3807_Weather6.tar.gz\": {\n        \"sha256\": \"121df0bdeb64f547acf7972377a840a836a3c8de72857833f458b5cb4f724609\",\n        \"size\": 472931410\n    },\n    \"HighwayCutIn_Town13_Route3808_Weather7.tar.gz\": {\n        \"sha256\": \"ae6117c6dac23b1ec85661e629177939d727210413bceacc3490a0036b6a1b28\",\n        \"size\": 556907905\n    },\n    \"HighwayCutIn_Town13_Route3811_Weather10.tar.gz\": {\n        \"sha256\": \"0495bab12f8faebdaa0ef3fe6401c087804cd621a8e596727929bc66ed35a73c\",\n        \"size\": 684481091\n    },\n    \"HighwayCutIn_Town13_Route3812_Weather11.tar.gz\": {\n        \"sha256\": \"a44b2a4a6537a3f0fda6a2f45f8d5c5dc12d8be86abcbad98de4839c766fe7d3\",\n        \"size\": 421488705\n    },\n    \"HighwayCutIn_Town13_Route3813_Weather12.tar.gz\": {\n        \"sha256\": \"7bf46fa60644cf043a2c77db0c59ab8de5c0216326c13cd260853951c3e4323e\",\n        \"size\": 493879220\n    },\n    \"HighwayCutIn_Town13_Route3814_Weather13.tar.gz\": {\n        \"sha256\": \"d547774c03d1023b14c4ccc730dd7d6f3887ccc727b2950c80935c39c34910c4\",\n        \"size\": 543274468\n    },\n    \"HighwayCutIn_Town13_Route3815_Weather14.tar.gz\": {\n        \"sha256\": \"33bccbdd051813e99964c9617f1373744e013987c40c7e33399ba74f13232e54\",\n        \"size\": 202089255\n    },\n    \"HighwayCutIn_Town13_Route3816_Weather15.tar.gz\": {\n        \"sha256\": \"5b8046a7322020026b2144c9fb06bf1177a26e53e29e1b8c0a253417059aedfd\",\n        \"size\": 473483319\n    },\n    \"HighwayCutIn_Town13_Route3817_Weather8.tar.gz\": {\n        \"sha256\": \"0de00c4e09ceb039110b382d1dfeb6257814a42674a9d04b2fb84e2642c6f8f3\",\n        \"size\": 523255795\n    },\n    \"HighwayCutIn_Town13_Route3818_Weather9.tar.gz\": {\n        \"sha256\": \"ddfef5110f91758890dab615fbc7d409d7118ba350a1bf66bfee1d64e3542456\",\n        \"size\": 550127887\n    },\n    \"HighwayCutIn_Town13_Route3819_Weather18.tar.gz\": {\n        \"sha256\": \"251fdf4fe4c673249cc3eb859eecddb6deca780681a1362d3a1000eabdc25101\",\n        \"size\": 642337702\n    },\n    \"HighwayCutIn_Town13_Route3820_Weather19.tar.gz\": {\n        \"sha256\": \"ccf270dad50a624324b4d101df1fb82045c93e5ad8162d34d194711bfc0d2c0f\",\n        \"size\": 587322161\n    },\n    \"HighwayCutIn_Town13_Route3821_Weather20.tar.gz\": {\n        \"sha256\": \"505e5672b87063331a9e856f9454e8a781c0aaf3f21e6c69fcec4afde7ba1935\",\n        \"size\": 558385065\n    },\n    \"HighwayCutIn_Town13_Route3822_Weather21.tar.gz\": {\n        \"sha256\": \"2131f6397502dbf336bde6a16de4f76fd71cb0a9d1c1182883fd5356cb7cf80b\",\n        \"size\": 552820855\n    },\n    \"HighwayCutIn_Town15_Route27388_Weather20.tar.gz\": {\n        \"sha256\": \"87b14a17701e07a0686877f0431164c53e943ea87e1b732b9bb6a77a2e049990\",\n        \"size\": 263172620\n    },\n    \"HighwayCutIn_Town15_Route27393_Weather26.tar.gz\": {\n        \"sha256\": \"662ef01da25e07306839a1c5b2a99a12f59307952e3b7a2d5fd235e71effc2a0\",\n        \"size\": 303404297\n    },\n    \"HighwayCutIn_Town15_Route27398_Weather5.tar.gz\": {\n        \"sha256\": \"f7ffa6089472ba868b3ede15e4c4fc22c2304e9329d681e3297addf8bc612600\",\n        \"size\": 236778155\n    },\n    \"HighwayCutIn_Town15_Route27403_Weather10.tar.gz\": {\n        \"sha256\": \"c71c82a3e19c8ce73dbec2bd90ed45f4ecad2f763fbd00a6a3a69df0cbfba810\",\n        \"size\": 285742561\n    },\n    \"HighwayCutIn_Town15_Route27408_Weather15.tar.gz\": {\n        \"sha256\": \"097570465adbde8ea1163a2f951a757c12ce7a3fc1abadced8f86d1d328d15b0\",\n        \"size\": 248409816\n    },\n    \"HighwayCutIn_Town15_Route27418_Weather1.tar.gz\": {\n        \"sha256\": \"be92192c21cd34b99ba0c39ea04628ac5a18378d718c889b8aa113ad934f3c99\",\n        \"size\": 218782772\n    },\n    \"HighwayCutIn_Town15_Route27423_Weather7.tar.gz\": {\n        \"sha256\": \"20b88dceb54454f39bc79fb12dc7207508b735645e8b859fbd4c2ef168e6185d\",\n        \"size\": 1819865315\n    },\n    \"HighwayCutIn_Town15_Route27428_Weather12.tar.gz\": {\n        \"sha256\": \"573394e347e4286aabc92cd4e66fd599944d0e4b8a77320017239105420f7a87\",\n        \"size\": 385887322\n    },\n    \"HighwayCutIn_Town15_Route27433_Weather19.tar.gz\": {\n        \"sha256\": \"02be8c4a36684b7f521731b70cd7c73478724d537c810b0e426295f1ca8744ab\",\n        \"size\": 978960317\n    },\n    \"HighwayCutIn_Town15_Route27448_Weather9.tar.gz\": {\n        \"sha256\": \"67889b92adc436f4ba4eef1540737adce7e564778c23c6a1dd6308a43dfb3f94\",\n        \"size\": 472937767\n    },\n    \"HighwayCutIn_Town15_Route27453_Weather14.tar.gz\": {\n        \"sha256\": \"fa96ab22879fb232a75833eeecf07136790c1c48821f451669d43fd89b49a215\",\n        \"size\": 3521638474\n    },\n    \"HighwayExit_Town06_Route25848_Weather21.tar.gz\": {\n        \"sha256\": \"cfe813f2382c73f10dbc0d78904bed774bf552946f36d9a2d7b6c8c22b91e01f\",\n        \"size\": 139463977\n    },\n    \"HighwayExit_Town06_Route25855_Weather2.tar.gz\": {\n        \"sha256\": \"f781c6db34fc46e07077a9c71e7b06ee2ef34812f7fb81eeea0350649abcd600\",\n        \"size\": 184818507\n    },\n    \"HighwayExit_Town06_Route25862_Weather10.tar.gz\": {\n        \"sha256\": \"ec5792c394197e8316fd1e5f48e1b0b3c3e74ec1e3f127a85fedca88fedaee75\",\n        \"size\": 134227417\n    },\n    \"HighwayExit_Town06_Route25869_Weather19.tar.gz\": {\n        \"sha256\": \"6252f61c852ba9ea18f4112c86339b6186f854786c308ecbe8518c6aef4ce4f0\",\n        \"size\": 140140004\n    },\n    \"HighwayExit_Town12_Route2224_Weather8.tar.gz\": {\n        \"sha256\": \"31fd7f2511d1ea4140d9cec849ccebb2476bc27da606f539d417147f2826fd1e\",\n        \"size\": 369721662\n    },\n    \"HighwayExit_Town12_Route2225_Weather9.tar.gz\": {\n        \"sha256\": \"b9e34c9028de1c6d7cc924f815e0e44306079f52037e46b214f420b9a32b24a4\",\n        \"size\": 297054822\n    },\n    \"HighwayExit_Town12_Route2226_Weather10.tar.gz\": {\n        \"sha256\": \"bbe961e27b0a2ee0bf5ef403c6499286c40433f8127ad328722ea2677f1c974e\",\n        \"size\": 338566586\n    },\n    \"HighwayExit_Town12_Route2227_Weather11.tar.gz\": {\n        \"sha256\": \"7e9f8498e9115141591f474f06523a542a53e9fe08232944f187d4cec93866b8\",\n        \"size\": 254884662\n    },\n    \"HighwayExit_Town12_Route2228_Weather12.tar.gz\": {\n        \"sha256\": \"7f86e905e4b404fb83a3ef05fc6ceabbd7d38bfcd8553d2d97b30e833729d357\",\n        \"size\": 252328632\n    },\n    \"HighwayExit_Town12_Route2229_Weather13.tar.gz\": {\n        \"sha256\": \"e0a1ffb5257298338fbb5f21b91d996ceb68786fb7597bbda2b25ef0219e4188\",\n        \"size\": 323437585\n    },\n    \"HighwayExit_Town12_Route2230_Weather14.tar.gz\": {\n        \"sha256\": \"06bba29a2d60ce4066ec7ef2e25599364b8fdd3db108f14dd511a4b6925f3389\",\n        \"size\": 245401357\n    },\n    \"HighwayExit_Town12_Route2231_Weather15.tar.gz\": {\n        \"sha256\": \"2035d9340c93f6b6dc304abe69cabb9ce52bb4d97141fc2d889bfdf81e9c39e2\",\n        \"size\": 351758513\n    },\n    \"HighwayExit_Town12_Route2232_Weather8.tar.gz\": {\n        \"sha256\": \"8a07ebf24877171e6043c77e09a1cf8282d7089521d122f5b2da0dc5b5b1e995\",\n        \"size\": 282785016\n    },\n    \"HighwayExit_Town12_Route2233_Weather9.tar.gz\": {\n        \"sha256\": \"4fda6776465e885e32f411384bccd7d7ffac9f2a4c3b512a354597e4c6618b5a\",\n        \"size\": 250107263\n    },\n    \"HighwayExit_Town12_Route2234_Weather18.tar.gz\": {\n        \"sha256\": \"ede18530ac9c9db32ede96e70ff1cffc550d8bac7eca51b36a15ebef7f4e8f49\",\n        \"size\": 378876349\n    },\n    \"HighwayExit_Town12_Route2235_Weather19.tar.gz\": {\n        \"sha256\": \"59e94053000dcf4e8259249daabc7ebadc781c1b0ca9c5fcd3d111af85359c38\",\n        \"size\": 253448233\n    },\n    \"HighwayExit_Town12_Route2236_Weather20.tar.gz\": {\n        \"sha256\": \"0014a70a125d942e5a8b39eb81a480fa55c7f8ce2fefa8019f36062a34fd77e5\",\n        \"size\": 331687354\n    },\n    \"HighwayExit_Town12_Route2237_Weather21.tar.gz\": {\n        \"sha256\": \"a0ca96cf26aa86a68cdfb7a51f5fae94ae0637621e6cc2d391561d1f573c510d\",\n        \"size\": 326657034\n    },\n    \"HighwayExit_Town12_Route2238_Weather22.tar.gz\": {\n        \"sha256\": \"9a2c6355c50e5033c9b493059c03b788c8b6953d2a6bdf26d631feac1a6b64cb\",\n        \"size\": 261371424\n    },\n    \"HighwayExit_Town12_Route2239_Weather23.tar.gz\": {\n        \"sha256\": \"9e1878d82836b7867932c38beb76f8b57b4ac734e442227061346640ad3b8069\",\n        \"size\": 252382497\n    },\n    \"HighwayExit_Town12_Route2240_Weather23.tar.gz\": {\n        \"sha256\": \"f62cde759239dc71ba2fa4d3fafe28e29f8951a74eb32082838f2950c703fe40\",\n        \"size\": 248198191\n    },\n    \"HighwayExit_Town12_Route2241_Weather25.tar.gz\": {\n        \"sha256\": \"a31d35c941e2a1a56b3e8596da32f195d79f8c2661e7dcc1b5a410bd016adddc\",\n        \"size\": 303811596\n    },\n    \"HighwayExit_Town12_Route2242_Weather0.tar.gz\": {\n        \"sha256\": \"81aaba23fe6d85d47da5f2a2f2ebe9e72ed2a2cd356f73b38ab55f1b2e9042b9\",\n        \"size\": 396249373\n    },\n    \"HighwayExit_Town12_Route2243_Weather1.tar.gz\": {\n        \"sha256\": \"8c01a0b12db56de304fe2041387ca1292d3fe4eac6f93ab10f2f93e9f12c74f9\",\n        \"size\": 311512545\n    },\n    \"HighwayExit_Town12_Route23638_Weather6.tar.gz\": {\n        \"sha256\": \"721c2dca48c06a6d2d204e798b557c2654a3e9936572e4ab5dd512e068fcf314\",\n        \"size\": 203202159\n    },\n    \"HighwayExit_Town12_Route23658_Weather2.tar.gz\": {\n        \"sha256\": \"b912ed2c8cdb42b0391473b1485a41fc5365930e3a60ae92b6e1c29702f803f7\",\n        \"size\": 190755104\n    },\n    \"HighwayExit_Town12_Route23659_Weather3.tar.gz\": {\n        \"sha256\": \"45a340807fb7e4c7bf62cb83b80c5fe1d4fe8144d857bbc9d349973ae54814b1\",\n        \"size\": 153684937\n    },\n    \"HighwayExit_Town12_Route23660_Weather5.tar.gz\": {\n        \"sha256\": \"0ab23a1f9269f1c7eb5d9fc300a7854d0dd4e771d0656c9cda00174546951b9f\",\n        \"size\": 157691247\n    },\n    \"HighwayExit_Town12_Route23671_Weather18.tar.gz\": {\n        \"sha256\": \"5bfe0aa890b5654cf0939d3badb7d58fed92623e78d1522f95878ae2b8edaa2d\",\n        \"size\": 204027733\n    },\n    \"HighwayExit_Town12_Route23672_Weather19.tar.gz\": {\n        \"sha256\": \"bd7322acea8a4db74fa6f7d14c29589c31ba9d083bf572ee3c79a3b01c0fce76\",\n        \"size\": 189303063\n    },\n    \"HighwayExit_Town12_Route23677_Weather25.tar.gz\": {\n        \"sha256\": \"3189a0c2b186f120cac7cea94c5d7a7ecf7cd17155178cf56eb21f40c1aac38f\",\n        \"size\": 234790003\n    },\n    \"HighwayExit_Town12_Route23687_Weather9.tar.gz\": {\n        \"sha256\": \"c391c34f6d06c5259daec3f1af98be6d615b2ed49e9b8358c85560245162d137\",\n        \"size\": 285942778\n    },\n    \"HighwayExit_Town12_Route23689_Weather11.tar.gz\": {\n        \"sha256\": \"a4dc12f5cf04e0b6bb65a2ee89166847e19a23c390b6accaef200b55100018b4\",\n        \"size\": 274651633\n    },\n    \"HighwayExit_Town12_Route23692_Weather14.tar.gz\": {\n        \"sha256\": \"f40ba74d90fd2d0a461ad4399804234ba7574281866173d7c86a9159d99359a6\",\n        \"size\": 197908066\n    },\n    \"HighwayExit_Town12_Route23704_Weather2.tar.gz\": {\n        \"sha256\": \"1c59779c1223af9eea6da81c47c1d76e3ee07cb24ae3c50a012d2340da73d5fe\",\n        \"size\": 297346951\n    },\n    \"HighwayExit_Town12_Route23715_Weather14.tar.gz\": {\n        \"sha256\": \"b27b355ecd9c6ccbcff3c393ca2ffa75dc856ed1fde7eac6b9841d0e45ec6209\",\n        \"size\": 126489911\n    },\n    \"HighwayExit_Town12_Route23717_Weather18.tar.gz\": {\n        \"sha256\": \"a74f84df618e37aed58b5d641984f0c7b294621b36b54d0949864726a15e92ca\",\n        \"size\": 145841620\n    },\n    \"HighwayExit_Town12_Route23834_Weather20.tar.gz\": {\n        \"sha256\": \"d4d36bf1557504d9e5d75231bd101f4045dab98a9dd40c6128fb5e6807322089\",\n        \"size\": 173143604\n    },\n    \"HighwayExit_Town12_Route23844_Weather5.tar.gz\": {\n        \"sha256\": \"6d64ed5fda72afdb746edfa4a80abeb8417fd5628caad5575c6f60758db74e11\",\n        \"size\": 191459271\n    },\n    \"HighwayExit_Town12_Route23846_Weather7.tar.gz\": {\n        \"sha256\": \"a3f6bda26c2708c713aa133d1594e890a5fc61921a6628c4033abf13296cb2d5\",\n        \"size\": 198220763\n    },\n    \"HighwayExit_Town12_Route23847_Weather8.tar.gz\": {\n        \"sha256\": \"eed5b5f676fa10b338efea8f2a2594411a868173fea0b45c3653501fb2c2c482\",\n        \"size\": 141252772\n    },\n    \"HighwayExit_Town12_Route23848_Weather9.tar.gz\": {\n        \"sha256\": \"f5c8221e3674a396d0ad448ce6c9957516c43bc6075eaa8a951821e3838c77e0\",\n        \"size\": 132746039\n    },\n    \"HighwayExit_Town12_Route23859_Weather22.tar.gz\": {\n        \"sha256\": \"cec876968391e0d3fc67816b450ad10b87b24526876a1d5673d2644d74284f01\",\n        \"size\": 174476540\n    },\n    \"HighwayExit_Town12_Route23865_Weather2.tar.gz\": {\n        \"sha256\": \"4973d466d44b5025d5b7eef7b9ba2a5057b1b623dcb62528d00c05a4bf766608\",\n        \"size\": 299019660\n    },\n    \"HighwayExit_Town12_Route23867_Weather5.tar.gz\": {\n        \"sha256\": \"1b118c6e20052c95d6c1dca266e14f00f9c9cf43ee91407a596812ee143d5771\",\n        \"size\": 293940507\n    },\n    \"HighwayExit_Town12_Route23875_Weather13.tar.gz\": {\n        \"sha256\": \"577332b2cd98ab86c00f834030610926cd538d6e3a57f3fc93daef0c0457f548\",\n        \"size\": 285881989\n    },\n    \"HighwayExit_Town12_Route23877_Weather15.tar.gz\": {\n        \"sha256\": \"3887cc9347b78944b7999a0b56fda345d708e5866e509f37deebf83be32961c0\",\n        \"size\": 303895906\n    },\n    \"HighwayExit_Town12_Route23891_Weather6.tar.gz\": {\n        \"sha256\": \"4a2d81a0083018fc021b893e408670c50ddef411cb594e0b8e96ec78317b5cad\",\n        \"size\": 296435304\n    },\n    \"HighwayExit_Town12_Route23892_Weather7.tar.gz\": {\n        \"sha256\": \"ac9cf30645c5eb858730b6727c103920dbce44bfe10ff857a072c87e934b49a4\",\n        \"size\": 318260510\n    },\n    \"HighwayExit_Town12_Route23903_Weather20.tar.gz\": {\n        \"sha256\": \"bff338a6cf2da08333653967ee06f48e08b391ef1b52be4f24ec8388eec812c8\",\n        \"size\": 134620213\n    },\n    \"HighwayExit_Town12_Route23905_Weather22.tar.gz\": {\n        \"sha256\": \"6ab48a58e6f153f8e8d8d0ec2401c5702fab9e07eaaab2ad275a5acf0376b213\",\n        \"size\": 143804443\n    },\n    \"HighwayExit_Town12_Route24019_Weather21.tar.gz\": {\n        \"sha256\": \"c063a90d25118e21f2aaa7bcdf163c1c43adf036b5519fcdb89ba2fb55521a32\",\n        \"size\": 189676207\n    },\n    \"HighwayExit_Town12_Route24032_Weather9.tar.gz\": {\n        \"sha256\": \"2922647e3655b1c7ed8462980c91cae330aae6d0712ad39fec287a4944a61e1e\",\n        \"size\": 162239479\n    },\n    \"HighwayExit_Town12_Route24034_Weather11.tar.gz\": {\n        \"sha256\": \"c5a00911683d7a5ff112d672b03cb545e3b79350001469a8a5bee949b197d040\",\n        \"size\": 170582001\n    },\n    \"HighwayExit_Town12_Route24035_Weather12.tar.gz\": {\n        \"sha256\": \"9a8d126286dfa7cc917a4f612a85669bfc9fc65471580b5c263e80e9aa002cc2\",\n        \"size\": 127752447\n    },\n    \"HighwayExit_Town12_Route24036_Weather13.tar.gz\": {\n        \"sha256\": \"f574601cfd73c4f21666fe23edd3931d0825deff7f8f105f8d4635c5b25a59a9\",\n        \"size\": 130848760\n    },\n    \"HighwayExit_Town12_Route24048_Weather1.tar.gz\": {\n        \"sha256\": \"11a8d4454aca9caa18f2ea7dceaa0903aec6378425b8cc853cd5652e15f9ac63\",\n        \"size\": 207906662\n    },\n    \"HighwayExit_Town12_Route24053_Weather7.tar.gz\": {\n        \"sha256\": \"bcf113f623222605401df6eeade27f71e6ff573d392c6c154f631137be1dd15f\",\n        \"size\": 300180833\n    },\n    \"HighwayExit_Town12_Route24055_Weather9.tar.gz\": {\n        \"sha256\": \"0d820f3375f79590520e687fc424a392dc1307c6ab7d4a25124ba646b4f8451d\",\n        \"size\": 253536805\n    },\n    \"HighwayExit_Town12_Route24063_Weather19.tar.gz\": {\n        \"sha256\": \"a696708e323bbe3d6b202809f4f97a427fff34798484c2a2e08f46e025bb4d89\",\n        \"size\": 269394971\n    },\n    \"HighwayExit_Town12_Route24065_Weather21.tar.gz\": {\n        \"sha256\": \"4ce6928008124353c2c6b52441900fbf52955504c91ac1916241b19b6f717a36\",\n        \"size\": 258295059\n    },\n    \"HighwayExit_Town12_Route24068_Weather25.tar.gz\": {\n        \"sha256\": \"b1a5a1e9f4856fbc66df21a92ba22f5d4abe64287b45dd84d2606b70158fb81c\",\n        \"size\": 182059857\n    },\n    \"HighwayExit_Town12_Route24080_Weather11.tar.gz\": {\n        \"sha256\": \"94cd3e76a85ffa991cd3939264bfc230df304441266cda7ac5a71303b7ccf175\",\n        \"size\": 272877802\n    },\n    \"HighwayExit_Town12_Route24091_Weather25.tar.gz\": {\n        \"sha256\": \"a055cef16ea1c7d52c466913bea71ad76790c77f7219b26faba315ad2b493eb3\",\n        \"size\": 119786819\n    },\n    \"HighwayExit_Town12_Route3004_Weather8.tar.gz\": {\n        \"sha256\": \"5fbe76f6a26c4490bc3666a194fc09dedd3a3e8db395e8b66da711ab655982b1\",\n        \"size\": 349358595\n    },\n    \"HighwayExit_Town12_Route3005_Weather9.tar.gz\": {\n        \"sha256\": \"09fde63dff689201f8f9aa265f0e7d50524d5cd9a5b8d443eb1211f012a1128d\",\n        \"size\": 318969882\n    },\n    \"HighwayExit_Town12_Route3006_Weather10.tar.gz\": {\n        \"sha256\": \"f8c7c7589b816799fb145c0bcace16ff7bac344dc3a6c3287ba569ce373f3f6e\",\n        \"size\": 330061064\n    },\n    \"HighwayExit_Town12_Route3007_Weather11.tar.gz\": {\n        \"sha256\": \"2ffc6c44a352a714d8dc2bd1783ca07d6368538aaa3e4dfa98238156cabffe63\",\n        \"size\": 314266709\n    },\n    \"HighwayExit_Town12_Route3008_Weather12.tar.gz\": {\n        \"sha256\": \"1d3eb845a1819a7558ca5710622c176f129519572201005aa3befe35a307b899\",\n        \"size\": 329231045\n    },\n    \"HighwayExit_Town12_Route3009_Weather13.tar.gz\": {\n        \"sha256\": \"c882690c361dcd85ff74daeb2c7c119cda9897104345004b8f91f88ddb8226a8\",\n        \"size\": 322413706\n    },\n    \"HighwayExit_Town12_Route3010_Weather14.tar.gz\": {\n        \"sha256\": \"80af5089a4f7fb070e4baf686aea7ff7e20c59932f90c63a85593c61859a08ae\",\n        \"size\": 262157977\n    },\n    \"HighwayExit_Town12_Route3011_Weather15.tar.gz\": {\n        \"sha256\": \"05a6bf5d003d07fda62345121fab67e33121fff21071cb0102736ffdfd6d1da9\",\n        \"size\": 370988239\n    },\n    \"HighwayExit_Town12_Route3012_Weather8.tar.gz\": {\n        \"sha256\": \"60bf55c59e5b4ac98c4961eea38143917b75153225e2bfbdd0d88adefc76ee61\",\n        \"size\": 293206206\n    },\n    \"HighwayExit_Town12_Route3013_Weather9.tar.gz\": {\n        \"sha256\": \"ccf9665cefd7c1205d267df328960e6a3014ce2290022cbae7ff5d60e809e678\",\n        \"size\": 322299317\n    },\n    \"HighwayExit_Town12_Route3014_Weather18.tar.gz\": {\n        \"sha256\": \"9b55237c1846fa42f964fc9df4051520c9cdd3d6b9e233f6b6619c8968dcad69\",\n        \"size\": 288366750\n    },\n    \"HighwayExit_Town12_Route3015_Weather19.tar.gz\": {\n        \"sha256\": \"a3b0f892835d1c8fbf037b6ea65faa42d7a5b5d41c67c319af692076f206c9f3\",\n        \"size\": 330790139\n    },\n    \"HighwayExit_Town12_Route3016_Weather20.tar.gz\": {\n        \"sha256\": \"f9baeecdedd1a758b2f7eff955cc20d6bc07ddae5f298ce90a14897f12e34eb0\",\n        \"size\": 263976893\n    },\n    \"HighwayExit_Town12_Route3017_Weather21.tar.gz\": {\n        \"sha256\": \"bc42884b3d3c18810531c09da68b337dcec46d57a7610e20bda04b86d2b48240\",\n        \"size\": 322684575\n    },\n    \"HighwayExit_Town12_Route3018_Weather22.tar.gz\": {\n        \"sha256\": \"fe31ee4fe49dc798dc3ef5b898e89ac4371b987459abd12b92651a631d3e23e2\",\n        \"size\": 250870448\n    },\n    \"HighwayExit_Town12_Route3019_Weather23.tar.gz\": {\n        \"sha256\": \"a98921bd8068263abf65ca6430742877a09c47ad43b52fff6020fd3c9d97fe1f\",\n        \"size\": 314180866\n    },\n    \"HighwayExit_Town12_Route3020_Weather23.tar.gz\": {\n        \"sha256\": \"524f4ecb8d34755143fddef51d899a25ab28da63e371ef16489fd43468b2c20e\",\n        \"size\": 318277226\n    },\n    \"HighwayExit_Town12_Route3021_Weather25.tar.gz\": {\n        \"sha256\": \"b6eeb877ef9b827067dae92dbbfa23ea52cd3b4f91c000750928ebe62480526c\",\n        \"size\": 247572661\n    },\n    \"HighwayExit_Town12_Route3022_Weather0.tar.gz\": {\n        \"sha256\": \"d7322b4465178d4cfa72aa001d4959a912240a16c3e5f1090d86f9d9d0f31113\",\n        \"size\": 318772634\n    },\n    \"HighwayExit_Town12_Route3023_Weather1.tar.gz\": {\n        \"sha256\": \"b74db41c851a2043acb461fb76600ce1fc0004b3abdfb6145e9d5d814ed401ce\",\n        \"size\": 402580719\n    },\n    \"HighwayExit_Town13_Route23633_Weather0.tar.gz\": {\n        \"sha256\": \"d0db4aa7f24870fcec92f915262c746683ec7e2cef7fca314a0bf5f6bd8554f5\",\n        \"size\": 350559908\n    },\n    \"HighwayExit_Town13_Route23637_Weather5.tar.gz\": {\n        \"sha256\": \"efac52928095293a5b402b64a985afbda47d272d04d5cc17286f14aa7bd0b6ac\",\n        \"size\": 344700317\n    },\n    \"HighwayExit_Town13_Route23657_Weather1.tar.gz\": {\n        \"sha256\": \"dc2a72439569f146248f423fc6d804507ea54323e18ac639f5f6c500caec3ba7\",\n        \"size\": 542595375\n    },\n    \"HighwayExit_Town13_Route23663_Weather8.tar.gz\": {\n        \"sha256\": \"bcb93fee831cfe91411678cf18e877bea8c76348ae2ad42ab69077df67fd43a2\",\n        \"size\": 500449870\n    },\n    \"HighwayExit_Town13_Route23665_Weather10.tar.gz\": {\n        \"sha256\": \"8b522c521bf94067f465c76fe5f0409200953c07cf79c4f570f4a26f76569c7a\",\n        \"size\": 501191819\n    },\n    \"HighwayExit_Town13_Route23670_Weather15.tar.gz\": {\n        \"sha256\": \"e365e1cf1ef34e79f452d8c68fbe05191ee6ea57f5ed7f717902202723cae80b\",\n        \"size\": 573338597\n    },\n    \"HighwayExit_Town13_Route23699_Weather23.tar.gz\": {\n        \"sha256\": \"c74ea6056ce7f24acf20f61968022d54c0097f3eaa9fa338ff4562ce0d03d87e\",\n        \"size\": 447441363\n    },\n    \"HighwayExit_Town13_Route23821_Weather5.tar.gz\": {\n        \"sha256\": \"c0aba80c5ea34a557b1b458c36751b2f5ca1ae8c5d40ba1904c62a4e6248e253\",\n        \"size\": 344295900\n    },\n    \"HighwayExit_Town13_Route23825_Weather9.tar.gz\": {\n        \"sha256\": \"a45b3b61951de36b51444245c7a154ba052127f87429b9a6d3dfb0c70a5a7bcf\",\n        \"size\": 322935706\n    },\n    \"HighwayExit_Town13_Route23843_Weather3.tar.gz\": {\n        \"sha256\": \"bbd5b3dd06888c504b34c8aa585554b9791677a55d1d0a39e712d27b084907a0\",\n        \"size\": 526268157\n    },\n    \"HighwayExit_Town13_Route23845_Weather6.tar.gz\": {\n        \"sha256\": \"f095dfed9e62a2d7c814d3023a50dc9f54b666cc431624746f8afe78414d56fe\",\n        \"size\": 514245217\n    },\n    \"HighwayExit_Town13_Route23851_Weather12.tar.gz\": {\n        \"sha256\": \"eea4941a51309f755048b7e46d78343238ef56d62d64ac5ff90b67f1bcc02e6d\",\n        \"size\": 498726585\n    },\n    \"HighwayExit_Town13_Route23853_Weather14.tar.gz\": {\n        \"sha256\": \"89dfe28b187185959660ff86aa0b487b76b68846f1a4d03f4e217a30678e24be\",\n        \"size\": 480707705\n    },\n    \"HighwayExit_Town13_Route23858_Weather21.tar.gz\": {\n        \"sha256\": \"323284d615a0ba0205d8e4cb307f889815c3c48d8963f2af1f65c70ab81f2c0d\",\n        \"size\": 507812841\n    },\n    \"HighwayExit_Town13_Route23887_Weather1.tar.gz\": {\n        \"sha256\": \"a2df9b28be297244ae66589a3c5383ec959866833ec4cdd995873f11e7da5c31\",\n        \"size\": 501498022\n    },\n    \"HighwayExit_Town13_Route23889_Weather3.tar.gz\": {\n        \"sha256\": \"2a37c99f68c48a8c24510ca0a24e33ecc257b274bbf12fcd2df4447ed2e454e4\",\n        \"size\": 502975534\n    },\n    \"HighwayExit_Town13_Route24009_Weather9.tar.gz\": {\n        \"sha256\": \"1cf60df9992033e09cb1c743396516d2656d5c1b19ff7d31bce24257e1e1774b\",\n        \"size\": 314568425\n    },\n    \"HighwayExit_Town13_Route24013_Weather13.tar.gz\": {\n        \"sha256\": \"42938aa3e86db6a854a6c9c948234bff4eb170fd0ed7754bda01b344ee03a3c9\",\n        \"size\": 328318400\n    },\n    \"HighwayExit_Town13_Route24031_Weather8.tar.gz\": {\n        \"sha256\": \"2660bbd8f5b9160db312857b4ba702008d6b617c83547bfc9bd031156fd13cb7\",\n        \"size\": 499998853\n    },\n    \"HighwayExit_Town13_Route24033_Weather10.tar.gz\": {\n        \"sha256\": \"c8190c65ba2b59b0ff9c6963481a41aab60546344fc4c15c0a386b1b74132fa9\",\n        \"size\": 503034778\n    },\n    \"HighwayExit_Town13_Route24039_Weather18.tar.gz\": {\n        \"sha256\": \"8a1318dabb0bf4b5adb32e8559dbb9aaf5d0ace0433346e6f320a14bf168af05\",\n        \"size\": 520613737\n    },\n    \"HighwayExit_Town13_Route24041_Weather20.tar.gz\": {\n        \"sha256\": \"05b227ca25b7fda4798880c7fc0639c54c19f6a03b7770f0e2b719dcb5e87ad8\",\n        \"size\": 499942193\n    },\n    \"HighwayExit_Town13_Route24075_Weather6.tar.gz\": {\n        \"sha256\": \"ae979c70cff22d864fdd8dd1e67b2f962d0c67980f3e1c25f05ec56246c4d2d4\",\n        \"size\": 508798717\n    },\n    \"HighwayExit_Town13_Route24077_Weather8.tar.gz\": {\n        \"sha256\": \"616455450d9132cdf9c76ff7dcde320f02caa1978a0871def7477f2b6565fc07\",\n        \"size\": 496488201\n    },\n    \"InterurbanActorFlow_Town06_Route25876_Weather0.tar.gz\": {\n        \"sha256\": \"9bb0738c03e397db3d00d6eab190592998210c41b602e86457428708b0d0caac\",\n        \"size\": 187172009\n    },\n    \"InterurbanActorFlow_Town06_Route25890_Weather15.tar.gz\": {\n        \"sha256\": \"549ae789df02c1e7000978e356b40c2d8f8ee3434a82dacb92620433d029e5f5\",\n        \"size\": 178678782\n    },\n    \"InterurbanActorFlow_Town06_Route25904_Weather6.tar.gz\": {\n        \"sha256\": \"a5951333301692f68a9bb38b074b833f331e18a9ee9ed7e642201417604e636d\",\n        \"size\": 184810070\n    },\n    \"InterurbanActorFlow_Town06_Route25911_Weather13.tar.gz\": {\n        \"sha256\": \"66c0e12c8a9bc719f7ea46c9f40fbacca1d86bf587c37a3c0d60fd013234e19a\",\n        \"size\": 138831843\n    },\n    \"InterurbanActorFlow_Town06_Route25918_Weather22.tar.gz\": {\n        \"sha256\": \"f699c64b860e423267e6d7f59ca985a431ea5c527c0c0dec9a9812d28675993b\",\n        \"size\": 130685657\n    },\n    \"InterurbanActorFlow_Town06_Route25939_Weather20.tar.gz\": {\n        \"sha256\": \"0b525134d052180255c3909619e8b499d7c1372d083af17bd7bec8fe2d990fe7\",\n        \"size\": 160244379\n    },\n    \"InterurbanActorFlow_Town06_Route25946_Weather1.tar.gz\": {\n        \"sha256\": \"58005f7725088e0ddc88cd27bbf6e8ad954121d8033fb58eb62180f556db6a8f\",\n        \"size\": 187985458\n    },\n    \"InterurbanActorFlow_Town06_Route25960_Weather18.tar.gz\": {\n        \"sha256\": \"b251469194907463b0893a7aa9f60e196faaab7d1c21556074ca660ed523988e\",\n        \"size\": 175658351\n    },\n    \"InterurbanActorFlow_Town06_Route25967_Weather26.tar.gz\": {\n        \"sha256\": \"6dd92ef0e39d057614cdf2a090c6e853397314b96d3e1d9ad4fe6081ae26e62f\",\n        \"size\": 188695343\n    },\n    \"InterurbanActorFlow_Town06_Route25974_Weather7.tar.gz\": {\n        \"sha256\": \"2564b2945768ab345d025e5927004deffc45b3cad2d6eedcc94b1fc8bffb5817\",\n        \"size\": 181226545\n    },\n    \"InterurbanActorFlow_Town12_Route2244_Weather2.tar.gz\": {\n        \"sha256\": \"173571764919caf520b670e941d256f6cd2fdba3083c0f82ca092eb0580d872c\",\n        \"size\": 282638855\n    },\n    \"InterurbanActorFlow_Town12_Route2245_Weather3.tar.gz\": {\n        \"sha256\": \"56224f771d89c7fe3c6829b2d4b82cdfd31df5409b051298123b02badc77b03e\",\n        \"size\": 362514517\n    },\n    \"InterurbanActorFlow_Town12_Route2246_Weather3.tar.gz\": {\n        \"sha256\": \"12b890d090d12ecb5e640804a9c11925d18b20a5c167febc65e9a00dd39f5de6\",\n        \"size\": 378916353\n    },\n    \"InterurbanActorFlow_Town12_Route2247_Weather5.tar.gz\": {\n        \"sha256\": \"00b83f35869b00b2b3563e9400d14b9f0786d4219fd36003adf6b46343eb50aa\",\n        \"size\": 367618541\n    },\n    \"InterurbanActorFlow_Town12_Route2248_Weather6.tar.gz\": {\n        \"sha256\": \"1a76311b0c1f3a66e3c62aea1787393164fc67914244ae65faa8a33a1012e61a\",\n        \"size\": 282511148\n    },\n    \"InterurbanActorFlow_Town12_Route2249_Weather7.tar.gz\": {\n        \"sha256\": \"e93f84fecc9ff53fa515b2570f9b199ad4326dc8c31e2889503cad88a15fba89\",\n        \"size\": 401793766\n    },\n    \"InterurbanActorFlow_Town12_Route2250_Weather8.tar.gz\": {\n        \"sha256\": \"d2454f812cb3c60eb4a216809b6990b32fda9a48595499829df21bf73fc5f81b\",\n        \"size\": 273152933\n    },\n    \"InterurbanActorFlow_Town12_Route2251_Weather9.tar.gz\": {\n        \"sha256\": \"6bb52277b121b102743db268efca8cbf48471268af97a11628fcfc80e44539b2\",\n        \"size\": 255067251\n    },\n    \"InterurbanActorFlow_Town12_Route2252_Weather10.tar.gz\": {\n        \"sha256\": \"ff95a7fcda1833c04b7edbaea685bf13e5d301657dc27508089c77e86ef4cf55\",\n        \"size\": 339755416\n    },\n    \"InterurbanActorFlow_Town12_Route2253_Weather11.tar.gz\": {\n        \"sha256\": \"126e8903438f46913b333db70454fcefbbca051444ec0bb7e7b6797f01bc9de2\",\n        \"size\": 235151418\n    },\n    \"InterurbanActorFlow_Town12_Route2254_Weather12.tar.gz\": {\n        \"sha256\": \"0526f6b06724a3461e7f8a3fcb94d077fc5cd55792d7e21508957938fcda5a62\",\n        \"size\": 242611260\n    },\n    \"InterurbanActorFlow_Town12_Route2255_Weather13.tar.gz\": {\n        \"sha256\": \"8dcd9daeeeb1680693f5db48e9ea36baa2e5b27fb108768daad70d15c20d9f9e\",\n        \"size\": 246840099\n    },\n    \"InterurbanActorFlow_Town12_Route2256_Weather14.tar.gz\": {\n        \"sha256\": \"a75978c5d5821f53a63344e79774c0348e6094f5a274b67853b6816df2d01be0\",\n        \"size\": 225454845\n    },\n    \"InterurbanActorFlow_Town12_Route2257_Weather15.tar.gz\": {\n        \"sha256\": \"e41ebfebfb97f1b499c58e105e05f36e210158af4a19abf74e050274d2239c08\",\n        \"size\": 356697043\n    },\n    \"InterurbanActorFlow_Town12_Route2258_Weather8.tar.gz\": {\n        \"sha256\": \"3c4993ee82ab144426805786f7edff7571106a0244b1df80351df8d2031a6725\",\n        \"size\": 350555650\n    },\n    \"InterurbanActorFlow_Town12_Route2259_Weather9.tar.gz\": {\n        \"sha256\": \"75835673aa84bd72e749dde53b67005e67ab818c78748a5f9278a0492aacb615\",\n        \"size\": 319310111\n    },\n    \"InterurbanActorFlow_Town12_Route2260_Weather18.tar.gz\": {\n        \"sha256\": \"81f8e6d5540ffbf3fd402be8691b11389d0cde834cd83091c49faf56c1c81c24\",\n        \"size\": 378218296\n    },\n    \"InterurbanActorFlow_Town12_Route2261_Weather19.tar.gz\": {\n        \"sha256\": \"8c1e31fa008fc1ce573a598f55fd1c74bd5e5f40699cdcc89b956eef3fbf73ea\",\n        \"size\": 261542345\n    },\n    \"InterurbanActorFlow_Town12_Route2262_Weather20.tar.gz\": {\n        \"sha256\": \"dff7fc6a9c3dff0b589d144489f4de52eae2b89cee5411b5d06b8e17821a7923\",\n        \"size\": 269576018\n    },\n    \"InterurbanActorFlow_Town12_Route2263_Weather21.tar.gz\": {\n        \"sha256\": \"db9264a872533f34d1f565024cbeef6459594373b12373a1fda19b1d16ffae0f\",\n        \"size\": 321341524\n    },\n    \"InterurbanActorFlow_Town12_Route23722_Weather23.tar.gz\": {\n        \"sha256\": \"6d2eba01a87fa8aff0e9e64b12f1a8d81d824223a300422daf0fb7f59e76f648\",\n        \"size\": 177535492\n    },\n    \"InterurbanActorFlow_Town12_Route23728_Weather3.tar.gz\": {\n        \"sha256\": \"2007b979688bc2f52f749553d00a0b3eb86dea7f74e42001665ca89ba3235db0\",\n        \"size\": 186857552\n    },\n    \"InterurbanActorFlow_Town12_Route23731_Weather7.tar.gz\": {\n        \"sha256\": \"7d5cfdc790348bd7a93549f49c4debd62c19260ca0184ad0ca674cdf00b92815\",\n        \"size\": 206740310\n    },\n    \"InterurbanActorFlow_Town12_Route23735_Weather11.tar.gz\": {\n        \"sha256\": \"568e5ceb0fee457301a16ea238a212a554c9ed1bf1a1b560f93eff5324ced09a\",\n        \"size\": 171890366\n    },\n    \"InterurbanActorFlow_Town12_Route23736_Weather12.tar.gz\": {\n        \"sha256\": \"347a776054fd6856d7082606ad65d144288f9386d88187d0a9223cffb1545c98\",\n        \"size\": 166258429\n    },\n    \"InterurbanActorFlow_Town12_Route23742_Weather20.tar.gz\": {\n        \"sha256\": \"7e4dbd4fb24a8eabf4f5b7eead10eb6e60e2cce66dbfc84c4089fe79ba194283\",\n        \"size\": 195671105\n    },\n    \"InterurbanActorFlow_Town12_Route23910_Weather1.tar.gz\": {\n        \"sha256\": \"51614a0d3a28822302e4afecc95dc5389abb5679726b92f4b5f978badd006851\",\n        \"size\": 203266370\n    },\n    \"InterurbanActorFlow_Town12_Route23916_Weather8.tar.gz\": {\n        \"sha256\": \"66c345d90c6f7d260129bae9a988cc6c1c4d6d92974ec91c609ef04b316851f4\",\n        \"size\": 181971742\n    },\n    \"InterurbanActorFlow_Town12_Route23919_Weather11.tar.gz\": {\n        \"sha256\": \"743cf592c1d2b42a531d92176872931c5cffa9b757c7d3b685f4723cc479953e\",\n        \"size\": 162007357\n    },\n    \"InterurbanActorFlow_Town12_Route23923_Weather15.tar.gz\": {\n        \"sha256\": \"63195acc0d9458c603ec325959ad2c7dddcc9f275c0694b9e401f86c60dabb9e\",\n        \"size\": 186437726\n    },\n    \"InterurbanActorFlow_Town12_Route23924_Weather18.tar.gz\": {\n        \"sha256\": \"83c4f9f51c307db8514b0f2cc0aea13ccb2a5e00b6288ad6c339334091c0cfe3\",\n        \"size\": 197490218\n    },\n    \"InterurbanActorFlow_Town12_Route23930_Weather25.tar.gz\": {\n        \"sha256\": \"bcd200a938ad708a59a46642bfd799192847a4be1afb4e41a020fcd951bb695d\",\n        \"size\": 188146735\n    },\n    \"InterurbanActorFlow_Town12_Route24098_Weather6.tar.gz\": {\n        \"sha256\": \"8278403766d649bf2d3088a58bbde017e3c3a45131eec9fa82e4e1d901b33e14\",\n        \"size\": 185062781\n    },\n    \"InterurbanActorFlow_Town12_Route24104_Weather12.tar.gz\": {\n        \"sha256\": \"9471b780f82226c282519cdc071dfb3b22375bbf076a19eab9fce0c62f30b838\",\n        \"size\": 171921392\n    },\n    \"InterurbanActorFlow_Town12_Route24107_Weather15.tar.gz\": {\n        \"sha256\": \"b1e972427f52566651139ffae5b2f5236bc9806d59cd679320d06b7796551842\",\n        \"size\": 187861182\n    },\n    \"InterurbanActorFlow_Town12_Route24111_Weather21.tar.gz\": {\n        \"sha256\": \"09d18399eb29cbd624380a5cebf5cc04796b595d8f473249a763603d37ae8b67\",\n        \"size\": 170789252\n    },\n    \"InterurbanActorFlow_Town12_Route24112_Weather22.tar.gz\": {\n        \"sha256\": \"c2b805510e106cd03d38280080401c78df73e37a56e82439e7b74db77a7940bd\",\n        \"size\": 168028177\n    },\n    \"InterurbanActorFlow_Town12_Route24117_Weather1.tar.gz\": {\n        \"sha256\": \"0028f2a3a59a48492490d7a04200001200a48c797ba03d96b2ce405287e2c63e\",\n        \"size\": 207785212\n    },\n    \"InterurbanActorFlow_Town12_Route3024_Weather2.tar.gz\": {\n        \"sha256\": \"9dfe79632f151426dacd505f05163dca9f714e4e3766aaf3a26a499cab73f55e\",\n        \"size\": 300333057\n    },\n    \"InterurbanActorFlow_Town12_Route3025_Weather3.tar.gz\": {\n        \"sha256\": \"0ffdc817bd5992e72b5152c68e109af6e74baf3ad56a0e57d9dd4e1f9291720e\",\n        \"size\": 377442063\n    },\n    \"InterurbanActorFlow_Town12_Route3026_Weather3.tar.gz\": {\n        \"sha256\": \"97426dfeddcc4e80f59b990ad13dfdcfaca7056293c121955bdff24b0fd38859\",\n        \"size\": 298092401\n    },\n    \"InterurbanActorFlow_Town12_Route3027_Weather5.tar.gz\": {\n        \"sha256\": \"9d2d16175521ebac3e0be498ea83a577290584026f107c47e20d5c2d27a86dad\",\n        \"size\": 290960139\n    },\n    \"InterurbanActorFlow_Town12_Route3028_Weather6.tar.gz\": {\n        \"sha256\": \"4edaa03b0681c22abeddf705867c0a04ab842f0f312ddcfb5e21f76c2249f169\",\n        \"size\": 290948698\n    },\n    \"InterurbanActorFlow_Town12_Route3029_Weather7.tar.gz\": {\n        \"sha256\": \"42d08d60ec8321c0d25eb5bf3329f03415096b1843fe5017519f43e622d25c49\",\n        \"size\": 413531054\n    },\n    \"InterurbanActorFlow_Town12_Route3030_Weather8.tar.gz\": {\n        \"sha256\": \"8f4d3cdc7e8d87481ab9b21df03b4c3a7bd9e237dc1424508c5b727fe52642b1\",\n        \"size\": 263749488\n    },\n    \"InterurbanActorFlow_Town12_Route3031_Weather9.tar.gz\": {\n        \"sha256\": \"90b22bfd4f76d2b5054d767f2b2f4c584f2195856d2c8e198a1b44068e09ce4d\",\n        \"size\": 237552285\n    },\n    \"InterurbanActorFlow_Town12_Route3032_Weather10.tar.gz\": {\n        \"sha256\": \"ecfb47768167928ce66131f2309b2d9a0c76fd5e96f99134a4c041dea3f8641d\",\n        \"size\": 336215492\n    },\n    \"InterurbanActorFlow_Town12_Route3033_Weather11.tar.gz\": {\n        \"sha256\": \"a0eeedeaa2a5dc7ebf11a4ecb5a97036e855a3fa86263b059ac3e39303bc8c6b\",\n        \"size\": 303243725\n    },\n    \"InterurbanActorFlow_Town12_Route3034_Weather12.tar.gz\": {\n        \"sha256\": \"a8af9a9e1c22cfb9af05651131c422915ed0f2bb17a1c8b850e53790a80e4c2f\",\n        \"size\": 243022513\n    },\n    \"InterurbanActorFlow_Town12_Route3035_Weather13.tar.gz\": {\n        \"sha256\": \"0f2697e15fe13da5295443d3aec9cb49ce8181e849038972e7b9d0c35ab99575\",\n        \"size\": 320965854\n    },\n    \"InterurbanActorFlow_Town12_Route3036_Weather14.tar.gz\": {\n        \"sha256\": \"06efb76254d46531d7a9c7ffe3a3b39637f17a1ee6e3f25ec40b40fd813d47ed\",\n        \"size\": 335306753\n    },\n    \"InterurbanActorFlow_Town12_Route3037_Weather15.tar.gz\": {\n        \"sha256\": \"10ad6a2a643da650905774681ba4c40d5e5d8d6f8342ce75947881495be1ebfb\",\n        \"size\": 354277434\n    },\n    \"InterurbanActorFlow_Town12_Route3038_Weather8.tar.gz\": {\n        \"sha256\": \"a1846b078254c4e279715a24c4dc619bd64bcee117c84c73291e0e11fbc26ae1\",\n        \"size\": 263602954\n    },\n    \"InterurbanActorFlow_Town12_Route3039_Weather9.tar.gz\": {\n        \"sha256\": \"18c963ed0ec85e1aa080b123feb987f07627be25f25f84056c78693f1ab77843\",\n        \"size\": 240794399\n    },\n    \"InterurbanActorFlow_Town12_Route3040_Weather18.tar.gz\": {\n        \"sha256\": \"86433b5d2cc7abdab10a122d1854eb9d190d1cc27fec0c01ce9415ae268f72c6\",\n        \"size\": 299187717\n    },\n    \"InterurbanActorFlow_Town12_Route3041_Weather19.tar.gz\": {\n        \"sha256\": \"17991143df75d4dafa2a5a81ccf5c4e63e4a2e83903f4c5fb553e8f93c8ecb3a\",\n        \"size\": 331128740\n    },\n    \"InterurbanActorFlow_Town12_Route3042_Weather20.tar.gz\": {\n        \"sha256\": \"5b45a315fc8e3795deb97e9416e6ebb160894eb9396d3d12ce1bdc59415d3dd9\",\n        \"size\": 324012368\n    },\n    \"InterurbanActorFlow_Town12_Route3043_Weather21.tar.gz\": {\n        \"sha256\": \"f81c7952630b7764915312a4f1b3a0b78c0ae369281d5935c1a9f3d74678e505\",\n        \"size\": 251047600\n    },\n    \"InterurbanActorFlow_Town13_Route23711_Weather10.tar.gz\": {\n        \"sha256\": \"882610323f697e337761c3230b6fd7d1753d75232edfd768cceac5c93351f488\",\n        \"size\": 494237816\n    },\n    \"InterurbanActorFlow_Town13_Route23713_Weather12.tar.gz\": {\n        \"sha256\": \"c7103fed3cfbc95cf0b7ee5204a0b03374e7d64c5eea42462798db4344d1e525\",\n        \"size\": 489682039\n    },\n    \"InterurbanActorFlow_Town13_Route23727_Weather2.tar.gz\": {\n        \"sha256\": \"8e5b1d7c456b9ff2d70bdc8c9d312a4d64d2304058fad9e2ebdf9ac61b2bab2d\",\n        \"size\": 491124497\n    },\n    \"InterurbanActorFlow_Town13_Route23899_Weather14.tar.gz\": {\n        \"sha256\": \"ee90c2ec21e645f39122c4eb7165dca009e22838a4f130d9f2e319d80d6abdf4\",\n        \"size\": 500259633\n    },\n    \"InterurbanActorFlow_Town13_Route23901_Weather18.tar.gz\": {\n        \"sha256\": \"9fa823cfc2645c92391578a50170be5639529afa5e0b108a199b4742743f2a8d\",\n        \"size\": 532125951\n    },\n    \"InterurbanActorFlow_Town13_Route23918_Weather10.tar.gz\": {\n        \"sha256\": \"1c8cfae871a0b453efe31351cd04cf7277ef3e91db602f0c6881cf56666397a4\",\n        \"size\": 427288202\n    },\n    \"InterurbanActorFlow_Town13_Route24087_Weather20.tar.gz\": {\n        \"sha256\": \"4d0a6472cc87c6deeab57fdc973d89363ccd54a5696074ddf3737eb2a6392881\",\n        \"size\": 471825835\n    },\n    \"InterurbanActorFlow_Town13_Route24103_Weather11.tar.gz\": {\n        \"sha256\": \"3465b5eaaf9ee605ecb436794ab1c3031401b4e9951986a9172f635a971f1cc6\",\n        \"size\": 470444354\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23700_Weather25.tar.gz\": {\n        \"sha256\": \"f45ba8ff31091d9cd10e8ba4821cab9e102db4f7deeb8889970b8bcf60bfc80e\",\n        \"size\": 173734262\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23708_Weather7.tar.gz\": {\n        \"sha256\": \"2e011736404e1fab9e9d617802487d627f748d6ed915ba0b7ace3bd8276f59b9\",\n        \"size\": 233181411\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23710_Weather9.tar.gz\": {\n        \"sha256\": \"30ffc53e7d0a8886975b6f5a28dc102e643a13873daff2ec40279675076b6dec\",\n        \"size\": 194094796\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23726_Weather1.tar.gz\": {\n        \"sha256\": \"47162f0dae248f735a9538fe7bb9f3875bb14e61065dbbd5bc93c22843bb04a3\",\n        \"size\": 246998566\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23739_Weather15.tar.gz\": {\n        \"sha256\": \"7ced3e6715a128610e30fc28934f154db29f9fb73c633ab653897a42ef26ccb1\",\n        \"size\": 297235584\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23888_Weather2.tar.gz\": {\n        \"sha256\": \"50ac917bd65a60a03505e2584d9d501ed8e3292907498f56367854325ddb1f26\",\n        \"size\": 209720717\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23890_Weather5.tar.gz\": {\n        \"sha256\": \"54e720c97d8d7093d9e2bb4c4ccc672038b96531843a72af1ccbe8958cc82a9b\",\n        \"size\": 208673863\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23913_Weather5.tar.gz\": {\n        \"sha256\": \"c1cf6c30986ffc60552e4119537b71dbff9f43ea33b6c53e2cdee7435c7bedf9\",\n        \"size\": 230585336\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route23914_Weather6.tar.gz\": {\n        \"sha256\": \"bad271e91a12e95e1303b0b7c9fe770b6e6bf69787bc6f58d27e543c4bb926e2\",\n        \"size\": 223404830\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route24076_Weather7.tar.gz\": {\n        \"sha256\": \"0b85dd3faee2e9df0ab77744d4c31022e25f38cc936fb5dfdc63aceeb8dbf5a6\",\n        \"size\": 215432132\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route24078_Weather9.tar.gz\": {\n        \"sha256\": \"93a6b44d014eb0971b5f64ea59bce81336a4b0ae20f7a7859382d86f92a69dbb\",\n        \"size\": 176338052\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route24086_Weather19.tar.gz\": {\n        \"sha256\": \"bc6c730d8e1efa2a4adf92a15316b03c0787577156973d1f0805edd1238ecfc6\",\n        \"size\": 215088507\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route24101_Weather9.tar.gz\": {\n        \"sha256\": \"46856c5eabfb8502556e5582bc7e8228759d3890aa5498500a746eed5d9f35b1\",\n        \"size\": 198793969\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route24102_Weather10.tar.gz\": {\n        \"sha256\": \"bc40948afd257674d2056e0d577773f5ddddccd4ca056e2b56797602033ca7e2\",\n        \"size\": 214714854\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38819_Weather5.tar.gz\": {\n        \"sha256\": \"61058908a45b8b0fa8b1b54967ca51e14122287f63939c7c036f3fa45ce72ea8\",\n        \"size\": 212426845\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38823_Weather5.tar.gz\": {\n        \"sha256\": \"db74c6015a4186bbc731d98a62b4dfafae4ad92f09e449222ca296e835d44249\",\n        \"size\": 237854704\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38849_Weather6.tar.gz\": {\n        \"sha256\": \"ea8271848adde37b8a4b264ce8273553c7a5e5f6bb53ca74fa89c03921b59431\",\n        \"size\": 235016089\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38861_Weather6.tar.gz\": {\n        \"sha256\": \"71a3419dde8e0710e46025161e154461449eaa36239bb1861b58c1997bb4c2ee\",\n        \"size\": 214322438\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38864_Weather6.tar.gz\": {\n        \"sha256\": \"c1ed37b21ef6b40f79691f51f54dc5c68e6f76d79b840d29ff7fe0ce2b5dce0c\",\n        \"size\": 226100184\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38867_Weather6.tar.gz\": {\n        \"sha256\": \"fec5ee0ef65740765d7a7e05aa5ba7da0d98a72cd9827e1187bd5f0f65b9880c\",\n        \"size\": 212159956\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38882_Weather7.tar.gz\": {\n        \"sha256\": \"9bc0d481f22fd46377c304c56abf5bd253dbaf1ab8a4f4858249daf37fad9e09\",\n        \"size\": 244877324\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38883_Weather7.tar.gz\": {\n        \"sha256\": \"0fada2167c6099287ec0e8eb72926b153fe37be84fd154d38b3a4f00dd9f9e1c\",\n        \"size\": 229491012\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38884_Weather7.tar.gz\": {\n        \"sha256\": \"a9ffd0e0ea3ad50520f5136a94225e8c571a5cd602b6ccc77b49c2c38f18b226\",\n        \"size\": 244087620\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39202_Weather15.tar.gz\": {\n        \"sha256\": \"afd1cb806029affdb034187b7e6a8e928c4bafdc67414b73882be144d37bdb8b\",\n        \"size\": 211493284\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39204_Weather15.tar.gz\": {\n        \"sha256\": \"0ed11433abac54391bb9fdbf139213362a79ee26935130602fb35fa6debeec10\",\n        \"size\": 216995538\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39206_Weather15.tar.gz\": {\n        \"sha256\": \"d346955fa047b85deb6d19987844869e5bd906c3bf0e4496435fd49cba73e28b\",\n        \"size\": 212261185\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39207_Weather15.tar.gz\": {\n        \"sha256\": \"5bac330e8e85ee54eb8e98a35d4be897fde0703c7b44b2161482b25a01cec78e\",\n        \"size\": 210979338\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39210_Weather15.tar.gz\": {\n        \"sha256\": \"04968ab4d9e3d365272667a9884b18fe452a734a1d56b4fa4445395cdb9bdff3\",\n        \"size\": 209378802\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39220_Weather15.tar.gz\": {\n        \"sha256\": \"ff42b3472073622a5e24d8a3f94e9c517bd84bdf0f1e82a349dd72c038ad15b6\",\n        \"size\": 210070739\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39221_Weather15.tar.gz\": {\n        \"sha256\": \"2081e92a17d37670bbac3944b646d02585a1a4896ba610133cf561f0a58579fa\",\n        \"size\": 201815632\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39223_Weather15.tar.gz\": {\n        \"sha256\": \"696a8a96e604e54186372f5d219b18614246134ae4e940e68aec29b5742760a9\",\n        \"size\": 207413822\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39227_Weather15.tar.gz\": {\n        \"sha256\": \"5e96f2ffdf56722a669df867fe64152fa4aa17cdcf4d810fd5b6667a883802e9\",\n        \"size\": 206076318\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39228_Weather15.tar.gz\": {\n        \"sha256\": \"cee809821a91430140bb3e18ed7700df1b538df61749bbc1d70c67846271f372\",\n        \"size\": 268793180\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39242_Weather18.tar.gz\": {\n        \"sha256\": \"1082766e7c08c0d25d4df60ccd398dfdead6f13c577c0bfdbb5e784068d329c2\",\n        \"size\": 232037200\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39246_Weather18.tar.gz\": {\n        \"sha256\": \"ac4ef1a8fa3557cc7ea01171565d7ae9ec7f762a721e48f4d8aabc88bb814878\",\n        \"size\": 231544740\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route23695_Weather19.tar.gz\": {\n        \"sha256\": \"80ba06f0355ad949ef2bfabe075acc53a1ace63bd4416c58f3ed70a2ac4c12d2\",\n        \"size\": 497730829\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route23696_Weather20.tar.gz\": {\n        \"sha256\": \"9e2db86ab7564492eb13d99cab1dcfc5110dd85d42797808bb902e8ce8461649\",\n        \"size\": 496128855\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route23883_Weather23.tar.gz\": {\n        \"sha256\": \"5cc7e6a49deaf18de0069b9d30f202ac865a403ee4cc152ab56dd0e9172604df\",\n        \"size\": 483635914\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route23884_Weather25.tar.gz\": {\n        \"sha256\": \"20c3c003127c870a5f24fa11850817c471f189f83d7fb9c84980187b54e31eea\",\n        \"size\": 492190850\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route24071_Weather1.tar.gz\": {\n        \"sha256\": \"74ac349edbbc9348c946b19cdf47be77f24458870be3c2762661ec47ffe35bc3\",\n        \"size\": 565714962\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route24072_Weather2.tar.gz\": {\n        \"sha256\": \"1a6300bcfc507189e9f20b49107070cb8905f07f23f1413f240424882627a776\",\n        \"size\": 549101021\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38832_Weather6.tar.gz\": {\n        \"sha256\": \"cccae8e0a4c9af93b70037a4a795b45edf5aec15e511ced4b3936f314405f6e9\",\n        \"size\": 467893177\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38872_Weather7.tar.gz\": {\n        \"sha256\": \"096517da14d8c720312d48997bf1cd9dad9b83fa9f8a4f1f576cd2624dffdd64\",\n        \"size\": 510038574\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38876_Weather7.tar.gz\": {\n        \"sha256\": \"bc611ae50db77f953714e27c5c0dda9d3eaee9f26b7ec980c04ec70a6048bfff\",\n        \"size\": 498477939\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39193_Weather15.tar.gz\": {\n        \"sha256\": \"59cb6372f45108fb02244edfc7c922eeeeafc7aa585ad44fa278d0471cfea421\",\n        \"size\": 533435643\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39196_Weather15.tar.gz\": {\n        \"sha256\": \"d3b244a268f65a1d4db72bc622e5d587b65dd1c310e3af448bf6a14bf298af9e\",\n        \"size\": 467051286\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39198_Weather15.tar.gz\": {\n        \"sha256\": \"ea8ee06e6b07867b4e32c131cf46add1642282a50a9041677bc8249cbf1581f0\",\n        \"size\": 518604585\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39232_Weather18.tar.gz\": {\n        \"sha256\": \"81fa6c4756ee24876627776d80e36f2c5be43dd1ab877997ce3c655c4cefcaba\",\n        \"size\": 470237661\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39233_Weather18.tar.gz\": {\n        \"sha256\": \"29e96d4f8443c0df7c79288dacdd51e536cc50f1ecd3881cfbf36506c948c273\",\n        \"size\": 551912378\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39237_Weather18.tar.gz\": {\n        \"sha256\": \"976c93fcf6b0aa0b1f01498ff7f46e66d017615f4d713d19fc1591e6abd82e45\",\n        \"size\": 466130690\n    },\n    \"InvadingTurn_Town04_Route26634_Weather26.tar.gz\": {\n        \"sha256\": \"2038fc3deef8f10296f332655e100b31d6de4281e2e3e5895a884ecf38bb30da\",\n        \"size\": 208663024\n    },\n    \"InvadingTurn_Town04_Route26639_Weather5.tar.gz\": {\n        \"sha256\": \"8b57b26d7348d9ae8e8d14ae233b324aa39d9963be333c87314597da1cadc49c\",\n        \"size\": 221104252\n    },\n    \"InvadingTurn_Town04_Route26649_Weather15.tar.gz\": {\n        \"sha256\": \"3c603c6121492b74d64d5f250d6d6eca910eb2402bd0af5e86f59a72a10c3d88\",\n        \"size\": 206954504\n    },\n    \"InvadingTurn_Town04_Route26654_Weather22.tar.gz\": {\n        \"sha256\": \"5866681a73b8c99238e2fddae0e11da21d3fa7615f3f0863181c5522ded6b976\",\n        \"size\": 290488963\n    },\n    \"InvadingTurn_Town04_Route26674_Weather19.tar.gz\": {\n        \"sha256\": \"bfe8ad810e36717e8d9d7a35337ae99727aff437240bf49bb62c6f1f173a4c0f\",\n        \"size\": 171202125\n    },\n    \"InvadingTurn_Town04_Route26684_Weather3.tar.gz\": {\n        \"sha256\": \"e84d4120e6e0cbca5a8d5471350c3f41b53a52246132f2da335223e161f5711f\",\n        \"size\": 176287067\n    },\n    \"InvadingTurn_Town04_Route26694_Weather14.tar.gz\": {\n        \"sha256\": \"f63e3235fcd778bcdb98340e56d2cec1267d61d093fd0d83308b5456acf6bac3\",\n        \"size\": 176803492\n    },\n    \"InvadingTurn_Town04_Route26699_Weather21.tar.gz\": {\n        \"sha256\": \"277e0f6b90ad25e81b2fb35a3ab210014f38646f9796ac69fe67f292e9458f33\",\n        \"size\": 106357090\n    },\n    \"InvadingTurn_Town04_Route26704_Weather0.tar.gz\": {\n        \"sha256\": \"41d366d320fb0c9bf1cdb4c5f01478ef509fe49093cbf2749832c0c9eeb09a50\",\n        \"size\": 190917471\n    },\n    \"InvadingTurn_Town05_Route26836_Weather20.tar.gz\": {\n        \"sha256\": \"950556c4d81fa20b06d255f79fb84e7d6ecedd2884939dedd496bfe957fef56a\",\n        \"size\": 132056710\n    },\n    \"InvadingTurn_Town11_Route26446_Weather21.tar.gz\": {\n        \"sha256\": \"33eb0bb9cbdcd86446d39b475fda17358a49af1da62940dc0980792add22c11d\",\n        \"size\": 45036639\n    },\n    \"InvadingTurn_Town11_Route26460_Weather10.tar.gz\": {\n        \"sha256\": \"2ad33cbb13e624165873f5c896c67f736fe8d604b9565496eef43e8139d2d0ef\",\n        \"size\": 93449352\n    },\n    \"InvadingTurn_Town11_Route26467_Weather19.tar.gz\": {\n        \"sha256\": \"c03163b588c75de57d4767e34ca62c75ce4c27966ab8149bc9ad43ba0f883c81\",\n        \"size\": 39115045\n    },\n    \"InvadingTurn_Town11_Route26474_Weather0.tar.gz\": {\n        \"sha256\": \"084f32830b35342c219f6c9325793089d09cb9e9aeb096fcb8533cb9250cb14c\",\n        \"size\": 67845476\n    },\n    \"InvadingTurn_Town11_Route26481_Weather8.tar.gz\": {\n        \"sha256\": \"fb545e199d370ae9ceb78f93d7af7c212898ed35e8315b957b6a6d5dc63c567b\",\n        \"size\": 111985495\n    },\n    \"InvadingTurn_Town11_Route26488_Weather15.tar.gz\": {\n        \"sha256\": \"78bcc5f301c6fe9c6275ef3d024bbccb702219a11512b3f48730bce0ab327a8b\",\n        \"size\": 92945173\n    },\n    \"InvadingTurn_Town11_Route26494_Weather23.tar.gz\": {\n        \"sha256\": \"9587bf6dcdc2529f9b6f28f5d81c08db33e8ba199532ab7185d766acbaf6214c\",\n        \"size\": 40191217\n    },\n    \"InvadingTurn_Town11_Route26500_Weather3.tar.gz\": {\n        \"sha256\": \"9e3a01e925193ca502f805163a51176c9c98a244bc14a3312a1c8206e841a113\",\n        \"size\": 154655277\n    },\n    \"InvadingTurn_Town11_Route26506_Weather10.tar.gz\": {\n        \"sha256\": \"1dd092b8aed1f2e4cfa410a44acc2b53749df402c9a1cfe8b06ab09d5ed0715e\",\n        \"size\": 44884723\n    },\n    \"InvadingTurn_Town11_Route26512_Weather18.tar.gz\": {\n        \"sha256\": \"a89e16c320418aea1727af2b1e60579745101e7acd3544e09d54e7bbdff5ce25\",\n        \"size\": 69514304\n    },\n    \"InvadingTurn_Town11_Route26518_Weather25.tar.gz\": {\n        \"sha256\": \"e24c3004af3b348b38dc4fd388b03bddcb83a08f3ee1658b5d429a77eab0a50d\",\n        \"size\": 32139908\n    },\n    \"InvadingTurn_Town11_Route26547_Weather5.tar.gz\": {\n        \"sha256\": \"0250dc956a27da2295c1cb7d768cc2fe5713f0b9271a1f5efcae27c4c68d1910\",\n        \"size\": 66779568\n    },\n    \"InvadingTurn_Town11_Route26557_Weather15.tar.gz\": {\n        \"sha256\": \"acf07f5d418a85a3e6eba5f6f5e43e8497e10328ae369ac59f809ea2c029cc7d\",\n        \"size\": 94192332\n    },\n    \"InvadingTurn_Town11_Route26562_Weather22.tar.gz\": {\n        \"sha256\": \"d01876cc1f5e0ecf78fc973807dd98c590804b80ca08d1f7073a78ab283a6780\",\n        \"size\": 36357148\n    },\n    \"InvadingTurn_Town12_Route2790_Weather2.tar.gz\": {\n        \"sha256\": \"0f45ae2188771f040a6a8f29910c5a6ab3ff26ede4ac0b9970cd8aa38d308ea6\",\n        \"size\": 359242019\n    },\n    \"InvadingTurn_Town12_Route2792_Weather3.tar.gz\": {\n        \"sha256\": \"104f8f9c1ff6aaef82803d30896cb435950be25f0710df6139ed21b1cb4b4bcc\",\n        \"size\": 256679723\n    },\n    \"InvadingTurn_Town12_Route2794_Weather6.tar.gz\": {\n        \"sha256\": \"4e06b4b6f2d03331100546d5e874e1604c2d30e9668ecaeca582de35def01c0b\",\n        \"size\": 202564729\n    },\n    \"InvadingTurn_Town12_Route2802_Weather14.tar.gz\": {\n        \"sha256\": \"d0a402adbf92305da142e3428b5ad0a44a08e0d0b3d4fe0cbbaf388433f57799\",\n        \"size\": 181417153\n    },\n    \"InvadingTurn_Town13_Route3564_Weather23.tar.gz\": {\n        \"sha256\": \"a56a51b11d38042bf8b3cf9d770dccb63cfff68d06b79d63e3df349186faec01\",\n        \"size\": 793636236\n    },\n    \"InvadingTurn_Town13_Route3565_Weather23.tar.gz\": {\n        \"sha256\": \"e65ca232480370f98462ec9dc8065dd8c8626390bcb881a4339c81d1c334f45d\",\n        \"size\": 306789444\n    },\n    \"InvadingTurn_Town13_Route3571_Weather3.tar.gz\": {\n        \"sha256\": \"92d2596df57b36e7f95bb6e6abef66ca29fb4c45b3c1152c3fc8a93119a21a9d\",\n        \"size\": 262066171\n    },\n    \"InvadingTurn_Town13_Route3572_Weather5.tar.gz\": {\n        \"sha256\": \"6746fe6d6875b2a6a732512536b007fe39b6162dfa5767182d847ac3cd74da63\",\n        \"size\": 1148698803\n    },\n    \"InvadingTurn_Town13_Route3575_Weather8.tar.gz\": {\n        \"sha256\": \"b5997112ee3b92e4144399f02b0e6b1944cea960033bfca1c9e8d49b8e49d128\",\n        \"size\": 133767935\n    },\n    \"InvadingTurn_Town13_Route3578_Weather11.tar.gz\": {\n        \"sha256\": \"861df305b91ab1339bb3e7fa2eb5e10ddfbc9238636afa9f8f9650af29a19157\",\n        \"size\": 387416111\n    },\n    \"InvadingTurn_Town13_Route3581_Weather14.tar.gz\": {\n        \"sha256\": \"acf66e1bb60824562bd208760879dc0a02f7ed4ab8f35f1224d196cba26e7361\",\n        \"size\": 379108243\n    },\n    \"InvadingTurn_Town15_Route26833_Weather15.tar.gz\": {\n        \"sha256\": \"68423c04e84c740d78a7f254cc95640ad6890081169f6fd4f5b8474edfeaa075\",\n        \"size\": 2155749574\n    },\n    \"InvadingTurn_Town15_Route26838_Weather22.tar.gz\": {\n        \"sha256\": \"9d511075feffc3a579582d29db07ff1142a3b0e3b32e8930c9bec38d4f447ec9\",\n        \"size\": 260436693\n    },\n    \"LaneChange_Town10HD_Route24200_Weather3.tar.gz\": {\n        \"sha256\": \"ee3d1d38e66a8bb360ac91109e84dfebe472a807896eb6332aa156f4477038c0\",\n        \"size\": 227052919\n    },\n    \"LaneChange_Town12_Route17551_Weather0.tar.gz\": {\n        \"sha256\": \"20c18c7dc698297cd2a780fbd54ec643254c5d158656aee10d6fbd93ce7b9ae9\",\n        \"size\": 618810379\n    },\n    \"LaneChange_Town12_Route17569_Weather18.tar.gz\": {\n        \"sha256\": \"fedc8d93ee1639fa8991bfd5fb7f462483330254daae81b40578a5c65da8b981\",\n        \"size\": 403291536\n    },\n    \"LaneChange_Town12_Route17575_Weather23.tar.gz\": {\n        \"sha256\": \"fb11e2e177c1d44cddf324befba0afded1e3f5fe58e4560e281046fbea16faba\",\n        \"size\": 267762124\n    },\n    \"LaneChange_Town12_Route17588_Weather11.tar.gz\": {\n        \"sha256\": \"b5c24c38d3c2164fb328c839c7d8b0c3d108e01c3adf13680db9559f9fc5ee89\",\n        \"size\": 184127968\n    },\n    \"MergerIntoSlowTrafficV2_Town06_Route26401_Weather22.tar.gz\": {\n        \"sha256\": \"f2aff9a8191617ad0078f95fbee348439deb68f98f51a447e2db88fa27b3bb76\",\n        \"size\": 409166242\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route23771_Weather0.tar.gz\": {\n        \"sha256\": \"74c6b670dee49f70505202125829a0e80c0af6091109513ae567de98b6e77977\",\n        \"size\": 305654064\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route23977_Weather26.tar.gz\": {\n        \"sha256\": \"71c09fbb337dce09d8f060354f4ff49437878cc115ecdbe463838beafc7aa09b\",\n        \"size\": 384644691\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37602_Weather11.tar.gz\": {\n        \"sha256\": \"6327ed9e73e7a473bb9d356dd22dabd8f0a94d82a343e0c10ab6f4c992807079\",\n        \"size\": 333050928\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37605_Weather11.tar.gz\": {\n        \"sha256\": \"e31a9a6eaa4ec8e1e1b629a4ad5dcca5b5c6421275f10e697fa5fac8e98d494c\",\n        \"size\": 253808707\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37611_Weather11.tar.gz\": {\n        \"sha256\": \"7e019b6b576cfe438ddbdbeee9a1c786bca2d73c98288a89fd2209e375844f95\",\n        \"size\": 175160390\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37653_Weather12.tar.gz\": {\n        \"sha256\": \"fa11aadef183c25900856b064ff573069aab05fef5296e0fd5be5c1ab18c9bf3\",\n        \"size\": 291962039\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37655_Weather12.tar.gz\": {\n        \"sha256\": \"61332b4327cf1fc2a98898af0c5a56f3be7e6028dc78e264178181d2eb65c0e7\",\n        \"size\": 296400973\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37659_Weather12.tar.gz\": {\n        \"sha256\": \"aa00d6260f18f0c721ae76c693268a712cc0cf2b0493fd74f8d37e6982df9d73\",\n        \"size\": 371595667\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37685_Weather12.tar.gz\": {\n        \"sha256\": \"55bcb3655dff34b555b21a47bca6469cf67f8aa01ff1886eefcab5c7479e73ef\",\n        \"size\": 229140411\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37691_Weather12.tar.gz\": {\n        \"sha256\": \"54827a0579a6228dd543acb9bb841748230419ba4a46fb3701b4ca3395ed66f7\",\n        \"size\": 313552986\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37692_Weather12.tar.gz\": {\n        \"sha256\": \"171102ed5abfae6a0afce8d11a6b972e8f0cd21cc07a38994a54c80b386e5728\",\n        \"size\": 293974884\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37693_Weather12.tar.gz\": {\n        \"sha256\": \"358b7cc7f5009e05a1aca78f0329affdfe430c737d06afcfeb4b6d7ac6e7343a\",\n        \"size\": 205877160\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37735_Weather13.tar.gz\": {\n        \"sha256\": \"7b1b5c9ccab51180b8f255c8a231f8406e91b5da81d61e861c951999a260d75b\",\n        \"size\": 299925805\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37745_Weather13.tar.gz\": {\n        \"sha256\": \"add35be5d5f59b7e21b032ba18a2f3a4300a8991dffefb5697d52b6cfab2a9b0\",\n        \"size\": 232876993\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37748_Weather13.tar.gz\": {\n        \"sha256\": \"8750c1fc94aaa53f6429a891b93bd3f3dd3e3ab6e2a494d4f0f3ce9203c89091\",\n        \"size\": 289881766\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37751_Weather13.tar.gz\": {\n        \"sha256\": \"7141ca06cb3d016b50ab255348e2c76a94c563d73aadfe5ab4fab03fdb1b8ac4\",\n        \"size\": 228526500\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37752_Weather13.tar.gz\": {\n        \"sha256\": \"4131efee33f7769115c80eb2c8ee8c36b56513c0e091f3a7df120e2236f053f4\",\n        \"size\": 304555164\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37771_Weather13.tar.gz\": {\n        \"sha256\": \"067725263cc7c57dbd288bbe75161f0148f7108fdfcb3de155a535d1f3b72288\",\n        \"size\": 246836180\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37773_Weather13.tar.gz\": {\n        \"sha256\": \"f92f8ad0f4b6049ffc1379c11f523b4cac136dc8c50920f0b4f6151d896bbfa5\",\n        \"size\": 312346874\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37774_Weather13.tar.gz\": {\n        \"sha256\": \"340727c61739db5e1f34e0aaf6d0f55b730c4bbf20f48a1b4b484a20c5bbb5f5\",\n        \"size\": 286231835\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37775_Weather13.tar.gz\": {\n        \"sha256\": \"37a1d5b2e123e1f4f700f30f31d17748f685601f2eb1d1e677afa32081cf5fa2\",\n        \"size\": 208583075\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37809_Weather14.tar.gz\": {\n        \"sha256\": \"34d9b5b661251239a337db55957e34126431b9e6b4728fd0d05b6dc5fc77e7f3\",\n        \"size\": 381415327\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37819_Weather14.tar.gz\": {\n        \"sha256\": \"d0d8f79fdc6b99312a7edf8997a4facf6cac2480e4220961d3402ecc26136e15\",\n        \"size\": 303162148\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37827_Weather14.tar.gz\": {\n        \"sha256\": \"f79c0013337183bc5b74c8b68873bb6c1f457abc2337f0cf995295d24fc5c3e6\",\n        \"size\": 243580719\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37830_Weather14.tar.gz\": {\n        \"sha256\": \"9cb244df8bb0c5cc1bdc899115d6178d8311e4c743cf2e9e4079ad342c80ae24\",\n        \"size\": 332911033\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37835_Weather14.tar.gz\": {\n        \"sha256\": \"a00070a70898c0a3830d61c3caa02ee4d0d202638d53718cf3f10111016b1414\",\n        \"size\": 306068872\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route23724_Weather26.tar.gz\": {\n        \"sha256\": \"01419d1041fe16312d6fc33ab7fdb2abb3330e7841f4b29a4c5cc7bc2b549a1b\",\n        \"size\": 605345687\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route24092_Weather26.tar.gz\": {\n        \"sha256\": \"bd3461e1331e4cc0aac24f68901edb2b03b4e5c7e90f2fe9861f50c62f4a5543\",\n        \"size\": 588217519\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37613_Weather11.tar.gz\": {\n        \"sha256\": \"d1dd950ed62f7ecab1c08d280263fac6645ca7f58a772ae4323e74366e896c8f\",\n        \"size\": 617841752\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37615_Weather11.tar.gz\": {\n        \"sha256\": \"b00614b9a7a395d358ce637d7cfd21af939a05121cc930836063058551339828\",\n        \"size\": 540691040\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37621_Weather11.tar.gz\": {\n        \"sha256\": \"72b891274f2bd073b0043324b05e288c8981cd4645f0626f3e8af0dda29ad8f8\",\n        \"size\": 596624847\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37632_Weather11.tar.gz\": {\n        \"sha256\": \"ffc6f4d8c3e471ed610c43beef37f3134f415ea6d16e973e3206bdd49478c5cf\",\n        \"size\": 411968519\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37644_Weather11.tar.gz\": {\n        \"sha256\": \"6d2888c03c82e6b8bfa73c6f884d533b791f21ca85b710ef40fe487d9dddc673\",\n        \"size\": 606286776\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37696_Weather12.tar.gz\": {\n        \"sha256\": \"f9e3e0f98d50e7a1f0628f5b692d05aa7d74c1f034ff9cf5620d3ca21835cebd\",\n        \"size\": 664203539\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37697_Weather12.tar.gz\": {\n        \"sha256\": \"657b0c79f01dafda5f016f43988c3a1a4343af2cb1b4d4c5be2f833349530438\",\n        \"size\": 541822795\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37702_Weather12.tar.gz\": {\n        \"sha256\": \"59a96d53d7dac44aeb1a7cfa7a3fa1b1ae9eba885afcaccecf42f00596837437\",\n        \"size\": 559209940\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37708_Weather12.tar.gz\": {\n        \"sha256\": \"93048ad39de01493de249c13540f4e7b13e7166f63c9f7b8a1f7aa43fa378a11\",\n        \"size\": 185601402\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37721_Weather12.tar.gz\": {\n        \"sha256\": \"e1021117d5b8d1f322cab17df090926983b8142072c47f651e37247dad524229\",\n        \"size\": 583726655\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37722_Weather12.tar.gz\": {\n        \"sha256\": \"d02cb8d1cdf0e6960c4eab3dd7fa6ea0b5b095295bb04949babb998b38a0bfdf\",\n        \"size\": 181202867\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37726_Weather12.tar.gz\": {\n        \"sha256\": \"7ef32e2c4a61fae4daf503215c93c7860a0c739e2f7c326eaca7ea7f2c7b051d\",\n        \"size\": 438547287\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37783_Weather13.tar.gz\": {\n        \"sha256\": \"ead338e1b6846cb3e2c072ee6db80e9903e33373cb5a38fef57e1b53a6736940\",\n        \"size\": 532692387\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37786_Weather13.tar.gz\": {\n        \"sha256\": \"0eba7c4aaaabac6a3ae4eb7799bca8f4c3c7958fccf365ad7b926e8c76765f32\",\n        \"size\": 183235887\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37794_Weather13.tar.gz\": {\n        \"sha256\": \"59a564b9202f44f2cc977754821c8769467fa187861f9358882c2e6d197fde1c\",\n        \"size\": 597019448\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37797_Weather13.tar.gz\": {\n        \"sha256\": \"b46fa3f2dd014231b4000416fa5f29612dd5410cf06bcb0d9d8fc1ae550fc8a5\",\n        \"size\": 196198764\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37800_Weather13.tar.gz\": {\n        \"sha256\": \"8e2bcc1171be7e7187157b40bafb208cf1c5d8d1fb5f780fcdd372f26b41a9a0\",\n        \"size\": 582669379\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37801_Weather13.tar.gz\": {\n        \"sha256\": \"a4317ffe74fb2bbf68a8bcb62a02d2fa3fd4dd91e00aec5ae715f7688165896c\",\n        \"size\": 556913725\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37803_Weather13.tar.gz\": {\n        \"sha256\": \"b8c96aec4d79ae6f35306ac4159c3f4ce0d2acf4f4e69d4d2def10f4c90b8fc3\",\n        \"size\": 575573395\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37808_Weather13.tar.gz\": {\n        \"sha256\": \"18195e40662ccccda02ee550c0d80808257c587877b9a0ff9de13861944f55e6\",\n        \"size\": 644065664\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2265_Weather23.tar.gz\": {\n        \"sha256\": \"4bbddd3d6891459d0876077c13c856e0ffdfc300f91131620ef5b3461e270340\",\n        \"size\": 265212469\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2266_Weather23.tar.gz\": {\n        \"sha256\": \"e7fe9c021000084a46c2d774152d0b30aaf8dbaa436e8f5af07fc273fddbdc12\",\n        \"size\": 332466998\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2267_Weather25.tar.gz\": {\n        \"sha256\": \"32cd3e5bf344f80731cc9b70d7f6e30df257e3496ab1293130bcc6fd3e1908b5\",\n        \"size\": 326260087\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2273_Weather5.tar.gz\": {\n        \"sha256\": \"2ce67ff17f73c1211d642c116915e066d5c2140fb9de2d53ea74e5d1e4ca1746\",\n        \"size\": 356401191\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2274_Weather6.tar.gz\": {\n        \"sha256\": \"682281f546de45741abcd0708f8e4975dbc411db0bb6ba4deed3cdb2053ee3d7\",\n        \"size\": 347221923\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2275_Weather7.tar.gz\": {\n        \"sha256\": \"123030b988624817ddcf9b6c4eb5702087985c630e2603c9b98c4ecc3dd4116f\",\n        \"size\": 491400713\n    },\n    \"MergerIntoSlowTraffic_Town12_Route2283_Weather15.tar.gz\": {\n        \"sha256\": \"68a67e2ff7352386a278a138ff22c5f2745f22db2ff7e598501e60f92edcb40d\",\n        \"size\": 370665396\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3047_Weather25.tar.gz\": {\n        \"sha256\": \"12093da7b5ad98e8b3d75a6cb002d588a4672d762dbab208c5a0e596eceef87d\",\n        \"size\": 321496038\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3048_Weather0.tar.gz\": {\n        \"sha256\": \"c8c10766f5a2a75c91d81cd4e3a150600a60c25558f469dfe08c199865634615\",\n        \"size\": 334559391\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3052_Weather3.tar.gz\": {\n        \"sha256\": \"d46bc8176a0ce02b57124744266b5bdad72bbe628ecb7daa1b24104c7a4c7614\",\n        \"size\": 381151363\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3054_Weather6.tar.gz\": {\n        \"sha256\": \"b429f04ada04491b54cc7a996ce2916c424226aabc8e0f266f58fca478daf7c1\",\n        \"size\": 258198069\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3056_Weather8.tar.gz\": {\n        \"sha256\": \"e771a620e5ec820127a44ef56538259720c165d9de4c3570d8d0dede75f8d037\",\n        \"size\": 359611036\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3057_Weather9.tar.gz\": {\n        \"sha256\": \"484723f52c907f15fe4bcaa88cfc2aea988815dab6519b4c37d1fe7ab1eb2fe5\",\n        \"size\": 333210033\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3059_Weather11.tar.gz\": {\n        \"sha256\": \"0701d74ef46b94a33fd3de0166119f171ff9af7bd875feb18169706941fa724c\",\n        \"size\": 244400203\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3060_Weather12.tar.gz\": {\n        \"sha256\": \"c7ad2e19e923e0a02e7dc33169a45c7aa77ccdbd30e7d06c1950ddc8a22cd485\",\n        \"size\": 363186101\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3061_Weather13.tar.gz\": {\n        \"sha256\": \"66f1473b3fc2ded7ddfea48133c209e87de388e53c20425d85c7466bf3ec671f\",\n        \"size\": 271499098\n    },\n    \"MergerIntoSlowTraffic_Town12_Route3062_Weather14.tar.gz\": {\n        \"sha256\": \"aa14d32c192af1435047a4396fece8debc3b51096e683888c8d9af81a4bd05c1\",\n        \"size\": 372989895\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3783_Weather8.tar.gz\": {\n        \"sha256\": \"07bd0557919fc4d5b808555fc6596188e3cfd2a615b5c30e253a76f68e61647d\",\n        \"size\": 710948191\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3785_Weather10.tar.gz\": {\n        \"sha256\": \"9ef94c08c5fd14e60438096b285cae7c8a38142891395370790d55b3223d62d6\",\n        \"size\": 341488363\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3786_Weather11.tar.gz\": {\n        \"sha256\": \"675f6002b1e4a32c7966786c78a50bc9cdcbd57a3beadf7ce33c946032e60575\",\n        \"size\": 364986449\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3787_Weather12.tar.gz\": {\n        \"sha256\": \"9eafa55e8dcdef344c61e06f73e3df6406bedb8150a9dad3ad0e36ada7052206\",\n        \"size\": 357355047\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3788_Weather13.tar.gz\": {\n        \"sha256\": \"7525542eb6929cbab96d886635b39b274b3d07e3bee9b9a7aa75a2c870552a52\",\n        \"size\": 572447658\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3789_Weather14.tar.gz\": {\n        \"sha256\": \"4f17c6de9dab88f4b0903d66090bc11f9fbdacca282910321d2c86a60bd120d5\",\n        \"size\": 820634491\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3792_Weather9.tar.gz\": {\n        \"sha256\": \"d3a7b38f727fa8e8d1effe1f71d865a7e47f0ba37740c61c233bdf2ed8399cbe\",\n        \"size\": 353817794\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3793_Weather18.tar.gz\": {\n        \"sha256\": \"738bbaf26cace2873c56cab29b67ac8182ab87f1f122d74186db272fe98e9c0f\",\n        \"size\": 403159361\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3797_Weather22.tar.gz\": {\n        \"sha256\": \"00d4cd5704c56d40678178380b344b7843b054853e6491e4d77db02a11759150\",\n        \"size\": 356960975\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3799_Weather23.tar.gz\": {\n        \"sha256\": \"ee35115bfb366991b90022a1e544ae18747a948c02a1fa4ddddf50c613e99b9a\",\n        \"size\": 346140100\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3800_Weather25.tar.gz\": {\n        \"sha256\": \"43859a9526d3e87148a3836f71cd8c04e1bde1ba0eb34985e75aca90e2cd8139\",\n        \"size\": 550162593\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3801_Weather0.tar.gz\": {\n        \"sha256\": \"74cb3f7aa3de579d36f9efe117d11e0dcbb2460394adcc35dc393afec7e95248\",\n        \"size\": 423711198\n    },\n    \"MergerIntoSlowTraffic_Town13_Route3802_Weather1.tar.gz\": {\n        \"sha256\": \"f65167488df83b22208a1ad067cd4d4cb6828a16d1b750c7615729503e903da1\",\n        \"size\": 629405789\n    },\n    \"NoScenario_Town03_Route26670_Weather13.tar.gz\": {\n        \"sha256\": \"c47290c9fa15bb8ec3641e6249e66856fe82842deceee9c24669ec901ff35566\",\n        \"size\": 147387996\n    },\n    \"NoScenario_Town03_Route26705_Weather1.tar.gz\": {\n        \"sha256\": \"dce9d157e615b26cb323ccd0148b7d2ee098acead9ee4e648176bba2260de8b9\",\n        \"size\": 237179273\n    },\n    \"NoScenario_Town03_Route26955_Weather25.tar.gz\": {\n        \"sha256\": \"50a6abd6afa4f357702bc3cfade68b99be20e94f0d9f8f9e4180fa773159bb9b\",\n        \"size\": 282157132\n    },\n    \"NoScenario_Town03_Route27530_Weather25.tar.gz\": {\n        \"sha256\": \"9a78af0db94ca61e79d805494fa37ff38efd0990b55829f18816041bd29ce6df\",\n        \"size\": 169380913\n    },\n    \"NoScenario_Town03_Route27535_Weather3.tar.gz\": {\n        \"sha256\": \"6ad04628fcd054145d74fdd6bfd42d8a52617356fc6ed801566254401f458ac3\",\n        \"size\": 291733414\n    },\n    \"NoScenario_Town03_Route27540_Weather9.tar.gz\": {\n        \"sha256\": \"005ca6766907995b411e32e8174fc6f78f9b807f352c4850d1e1a508201dac63\",\n        \"size\": 404596814\n    },\n    \"NoScenario_Town03_Route27545_Weather14.tar.gz\": {\n        \"sha256\": \"911b8e0450e6334efe64c304bb4001c63e3dcc764b9c64e867ab737b83cddee4\",\n        \"size\": 423142659\n    },\n    \"NoScenario_Town03_Route27550_Weather21.tar.gz\": {\n        \"sha256\": \"fc48750e00f316d39b85091bd8646894cc76f918a8bc6882c5227fd6c588287c\",\n        \"size\": 56755144\n    },\n    \"NoScenario_Town03_Route27555_Weather0.tar.gz\": {\n        \"sha256\": \"28678406c554cf3ef6909ec8e579e6694cdd0b7ba7940bc9a0220cd772bfde96\",\n        \"size\": 202332906\n    },\n    \"NoScenario_Town03_Route27560_Weather6.tar.gz\": {\n        \"sha256\": \"bd88e5875a3bad0ae32d755e56cde46fe89061f4c262e904b19a7c19d044aa99\",\n        \"size\": 319388796\n    },\n    \"NoScenario_Town03_Route27565_Weather11.tar.gz\": {\n        \"sha256\": \"26adb7b84261895f39a9a98a7287dde7a75b19491b4bbcd17660b08abb287dd9\",\n        \"size\": 173734466\n    },\n    \"NoScenario_Town03_Route27570_Weather18.tar.gz\": {\n        \"sha256\": \"6e9401737c9b588a7c3a6055ec6fbd84a24928d60875883a1489607a3b82dfdb\",\n        \"size\": 182331623\n    },\n    \"NoScenario_Town03_Route27575_Weather23.tar.gz\": {\n        \"sha256\": \"0b48676acbd8ccc6f040bd6781191e685f45f8178e8a290fcb75038d547512d3\",\n        \"size\": 65201275\n    },\n    \"NoScenario_Town03_Route27585_Weather8.tar.gz\": {\n        \"sha256\": \"c8502943042dea54462f8ef1c12bf6ddc6dd6ce1c7d663b6d58828d9bba86708\",\n        \"size\": 102462433\n    },\n    \"NoScenario_Town03_Route27590_Weather13.tar.gz\": {\n        \"sha256\": \"9781c08356f8e60343db003e0e07822f4c4d6007b667fc484dd5d011475beebc\",\n        \"size\": 109242986\n    },\n    \"NoScenario_Town03_Route27595_Weather20.tar.gz\": {\n        \"sha256\": \"67f0ff6d23e466433846c2479b224f0fb13ac320f19e8da9c19dd634c1561650\",\n        \"size\": 249131019\n    },\n    \"NoScenario_Town03_Route27600_Weather26.tar.gz\": {\n        \"sha256\": \"8286db5ecab5ce0e7f52030aad493c632d551b1ffdd4ad675f62e03f4cf9c23f\",\n        \"size\": 113230808\n    },\n    \"NoScenario_Town03_Route27605_Weather5.tar.gz\": {\n        \"sha256\": \"1dc14f5b27e98c92f2277b4e22a1be011177d88b9e2083e7d28a8d968666318c\",\n        \"size\": 185491934\n    },\n    \"NoScenario_Town03_Route27610_Weather10.tar.gz\": {\n        \"sha256\": \"63151675ded3eb76622e861ce29993f9c195114e617afcf9723e53eef5edc7dd\",\n        \"size\": 234137899\n    },\n    \"NoScenario_Town03_Route27615_Weather15.tar.gz\": {\n        \"sha256\": \"6acc193190dcd8eb13b75ee0ec7a4ce5b5fb48666d4cff895a2bd1d4e110694b\",\n        \"size\": 96036889\n    },\n    \"NoScenario_Town03_Route27625_Weather1.tar.gz\": {\n        \"sha256\": \"e4bd651694f5f724016ae47a81d8d34312621ab7c1f4dfc7efda84c9b4414e71\",\n        \"size\": 484469357\n    },\n    \"NoScenario_Town03_Route27630_Weather7.tar.gz\": {\n        \"sha256\": \"8457d1ed127ff75034bb6206f7edcbfcf25789c339f4ec2fce713b7f94873154\",\n        \"size\": 192542797\n    },\n    \"NoScenario_Town03_Route27635_Weather12.tar.gz\": {\n        \"sha256\": \"f8dee73708c9c13cba740e6bf5d52e6b39179145e3ed2e64e3a98a2117f8779d\",\n        \"size\": 236773511\n    },\n    \"NoScenario_Town03_Route27640_Weather19.tar.gz\": {\n        \"sha256\": \"d156b852046f288d4fee7e0b45957bf30fa2d0a1ba2d036d4d650fa0e47d5d85\",\n        \"size\": 300643577\n    },\n    \"NoScenario_Town03_Route27645_Weather25.tar.gz\": {\n        \"sha256\": \"d59847a02750d01007d2fb7df287b82e69b75b47d52a5f229465b5d71e79b0e9\",\n        \"size\": 54057795\n    },\n    \"NoScenario_Town03_Route27650_Weather3.tar.gz\": {\n        \"sha256\": \"b673554830be84dc869fefd07517a41fef5d7460ed66c41f65244e2a22a6c825\",\n        \"size\": 203266210\n    },\n    \"NoScenario_Town03_Route27655_Weather9.tar.gz\": {\n        \"sha256\": \"a3e01bd24b10f303dee04a4bfbddd9a6a0379eef6886fa01571a731e1a26634e\",\n        \"size\": 273171552\n    },\n    \"NoScenario_Town03_Route27660_Weather14.tar.gz\": {\n        \"sha256\": \"a98c7d0e9c06a98627c562c81e9dc083f1c2c76da3a3c8eacb2ff7f10dc52a4c\",\n        \"size\": 204294640\n    },\n    \"NoScenario_Town03_Route27665_Weather21.tar.gz\": {\n        \"sha256\": \"3dc48249f7e801058d1f6bdfe4fde669c2eae6f714bfab766136e7bea7140342\",\n        \"size\": 196709931\n    },\n    \"NoScenario_Town03_Route27670_Weather0.tar.gz\": {\n        \"sha256\": \"6cc8173370a58692cedc48bdc4f2fbc357b3a50b2c165ad372c63224623101e3\",\n        \"size\": 85095113\n    },\n    \"NoScenario_Town03_Route27680_Weather11.tar.gz\": {\n        \"sha256\": \"531eafb698d5d99cd11e81b27715aad2ae60d9a569c9e911838141481acaf237\",\n        \"size\": 92894788\n    },\n    \"NoScenario_Town03_Route27685_Weather18.tar.gz\": {\n        \"sha256\": \"ab94b9e0ec209a24ed5c9fcf7bf8d810d602d7ca7ced9c0eee79e9e18b7b1bee\",\n        \"size\": 135210442\n    },\n    \"NoScenario_Town03_Route27690_Weather23.tar.gz\": {\n        \"sha256\": \"d17d10e97c821cc3ae5e4913832fa84a69dbb8a077011c6de56b3f66114362c2\",\n        \"size\": 232474140\n    },\n    \"NoScenario_Town03_Route27695_Weather2.tar.gz\": {\n        \"sha256\": \"9435b909ea3385e75fb9ac43e6739eb2e7b3a63f457221f56921c34c6cc82433\",\n        \"size\": 94388749\n    },\n    \"NoScenario_Town03_Route27705_Weather13.tar.gz\": {\n        \"sha256\": \"12dfec40945d23c1540f1a04dacc2ebf8259c8d550da7ebca4acf9ecc1aab439\",\n        \"size\": 73743289\n    },\n    \"NoScenario_Town03_Route27715_Weather26.tar.gz\": {\n        \"sha256\": \"26833dd3fbe9d80563b526d2cf95ddce31e791046a72bace5a7abf45d781dedd\",\n        \"size\": 485065549\n    },\n    \"NoScenario_Town03_Route27720_Weather5.tar.gz\": {\n        \"sha256\": \"481f5d63921a63852999ad7d7e88279cb63d82eb3b5ef6817d71dac84f97ce5a\",\n        \"size\": 333837317\n    },\n    \"NoScenario_Town03_Route27725_Weather10.tar.gz\": {\n        \"sha256\": \"7a6f3d874470838ef2d431e9393f3a8efe57339a49605dbe83ac52fd9bd51d64\",\n        \"size\": 557925368\n    },\n    \"NoScenario_Town03_Route27730_Weather15.tar.gz\": {\n        \"sha256\": \"763e0f5f350c8c86aba6fb54d7a24d25abb9e0d52e3d775a1ab9a09cf9b62f01\",\n        \"size\": 716506966\n    },\n    \"NoScenario_Town03_Route27735_Weather22.tar.gz\": {\n        \"sha256\": \"13d284687c356f9f25790f098c769c58c6af70f5aec6997f0a1cf071346c0d79\",\n        \"size\": 278809806\n    },\n    \"NoScenario_Town03_Route27740_Weather1.tar.gz\": {\n        \"sha256\": \"782e9cdf64e298a2240b100b01d1ca34340c84b7f78694f438685987f43bb036\",\n        \"size\": 819130509\n    },\n    \"NoScenario_Town03_Route27745_Weather7.tar.gz\": {\n        \"sha256\": \"660a4a29ce574cfa2c3ba9bb0a54b4e67d68f5932026071d115b69b6c6e27d1e\",\n        \"size\": 368576517\n    },\n    \"NoScenario_Town03_Route27750_Weather12.tar.gz\": {\n        \"sha256\": \"e3b700a267ea12a862557d3596c3ca659825cfb172215ee987f88ecca3f45a0e\",\n        \"size\": 400032155\n    },\n    \"NoScenario_Town03_Route27755_Weather19.tar.gz\": {\n        \"sha256\": \"ca10871058ccf35df9c4a30ee4e3303ad2f51478d7a2cd0f774ec391b86a9de3\",\n        \"size\": 672756229\n    },\n    \"NoScenario_Town03_Route27760_Weather25.tar.gz\": {\n        \"sha256\": \"26376a0daab45035f1586d7c7bfcf18db0b791db477a2d4eb50bd0d7d4794b39\",\n        \"size\": 611624860\n    },\n    \"NoScenario_Town03_Route27765_Weather3.tar.gz\": {\n        \"sha256\": \"acc0581869b18f8e36e89b2cca4a2aeb34495449da5f4793c40339247e6c0872\",\n        \"size\": 488272658\n    },\n    \"NoScenario_Town03_Route27770_Weather9.tar.gz\": {\n        \"sha256\": \"8a7e82497269c0e73a666ab320019fb2f710d8ba4e9381a1c26c2a522a4402ca\",\n        \"size\": 639545191\n    },\n    \"NoScenario_Town03_Route27775_Weather14.tar.gz\": {\n        \"sha256\": \"b1634498e39a67d06f3860272ec72e520aacb8d5c85f869b57cc0ac59114a2d3\",\n        \"size\": 710714878\n    },\n    \"NoScenario_Town03_Route27780_Weather21.tar.gz\": {\n        \"sha256\": \"5792199430ec75a0adbb2f4728ed64314a47d1ab296841970add3f59eb6eecf5\",\n        \"size\": 637634211\n    },\n    \"NoScenario_Town03_Route27790_Weather6.tar.gz\": {\n        \"sha256\": \"d2d209bec5064a9b382a7590a7dff1f26f25c074c54040abb950745db1ad1d28\",\n        \"size\": 380941207\n    },\n    \"NoScenario_Town03_Route27795_Weather11.tar.gz\": {\n        \"sha256\": \"17455ad15d0250a8e392d19e077b982aabfeb6357d3942a2c5c4a8745b4d1895\",\n        \"size\": 506398797\n    },\n    \"NoScenario_Town03_Route27800_Weather18.tar.gz\": {\n        \"sha256\": \"bde21a87e1d189cf2115ce11ee00d8302f71010e08fa5ddefebde2e1bfaaf6c3\",\n        \"size\": 1295556719\n    },\n    \"NoScenario_Town03_Route27805_Weather23.tar.gz\": {\n        \"sha256\": \"b5c6c4e0be401504bf86f41ffcfbc6c09189605e6ca4ffeb97a87af673149798\",\n        \"size\": 300739483\n    },\n    \"NoScenario_Town03_Route27810_Weather2.tar.gz\": {\n        \"sha256\": \"f2d484fc9e36fd27ceb255141f1898fd113e73951cdf3ed7e569b9df37536d97\",\n        \"size\": 396885980\n    },\n    \"NoScenario_Town03_Route27815_Weather8.tar.gz\": {\n        \"sha256\": \"a518c6d665ce28c77e087b253f771cbdb2b22e951674d03dc5f3abdad7fdd3f3\",\n        \"size\": 348518260\n    },\n    \"NoScenario_Town03_Route27820_Weather13.tar.gz\": {\n        \"sha256\": \"65385ab2f269fe016dc0f15057b9ce3d83e5f1453812c0c105407321814ee749\",\n        \"size\": 114577773\n    },\n    \"NoScenario_Town03_Route27825_Weather20.tar.gz\": {\n        \"sha256\": \"7030b28f332de81fe2d361d3bfae39f6451ddf790dcdd714aaaf7c7d9eb707c4\",\n        \"size\": 79026943\n    },\n    \"NoScenario_Town03_Route27830_Weather26.tar.gz\": {\n        \"sha256\": \"634d83f6e5809772afe425e5a6b9ea57001bbc36016b4027d21aef6cdfa8590c\",\n        \"size\": 208410959\n    },\n    \"NoScenario_Town03_Route27835_Weather5.tar.gz\": {\n        \"sha256\": \"570fbb21124cbf874108562b75633a247651d9945474578568af28558c8263e8\",\n        \"size\": 544923252\n    },\n    \"NoScenario_Town03_Route27840_Weather10.tar.gz\": {\n        \"sha256\": \"7638b103ebbd80a8542279a4eaa62a10fc88fe3b40a53411b57f00c50b524fc7\",\n        \"size\": 305929794\n    },\n    \"NoScenario_Town03_Route27850_Weather22.tar.gz\": {\n        \"sha256\": \"e261031cdc57bd16097e9a82c2535495191d32e972656121c90f997974a29eb0\",\n        \"size\": 77958890\n    },\n    \"NoScenario_Town03_Route27855_Weather1.tar.gz\": {\n        \"sha256\": \"d30a5282f19bee532f268c881c59b37a2d5a19bc4547340e0a4243ea91973e26\",\n        \"size\": 104855346\n    },\n    \"NoScenario_Town03_Route27859_Weather6.tar.gz\": {\n        \"sha256\": \"aacaba159beda0de94dc4099d7665abe22554f0938c9c0f706cb2b8f8f7c8948\",\n        \"size\": 525669335\n    },\n    \"NoScenario_Town03_Route27863_Weather10.tar.gz\": {\n        \"sha256\": \"3784b09e963ff9f788c8653dff7973ae69e2fd9ca51ea66398d46cf982ba8f87\",\n        \"size\": 99705222\n    },\n    \"NoScenario_Town03_Route27867_Weather14.tar.gz\": {\n        \"sha256\": \"985e0a40ab46ede3e02185bedbd63ff91d0ca76aeae27d36916d0ae3fbea89d8\",\n        \"size\": 201598248\n    },\n    \"NoScenario_Town03_Route27871_Weather20.tar.gz\": {\n        \"sha256\": \"3ee6bdd93b4c4159aa09b3437dac95cfe8a5625a8aa8b10e7ef04c14aead0453\",\n        \"size\": 120511726\n    },\n    \"NoScenario_Town03_Route27875_Weather25.tar.gz\": {\n        \"sha256\": \"60dd42504195857f0db8c042144a526c67b38416097515c7bde14db1cba5ca9b\",\n        \"size\": 72626638\n    },\n    \"NoScenario_Town04_Route24755_Weather7.tar.gz\": {\n        \"sha256\": \"718fb767fadfdd10f7982391086609290705edfa52e5c66626c009163339bfa3\",\n        \"size\": 235230573\n    },\n    \"NoScenario_Town04_Route26779_Weather7.tar.gz\": {\n        \"sha256\": \"dd61e680d73dc1071c0f122d22f04629a81e6d6eac172110835d77987c1257fc\",\n        \"size\": 204992793\n    },\n    \"NoScenario_Town04_Route26804_Weather9.tar.gz\": {\n        \"sha256\": \"f41a5cad2b7520d0a15304f856951cc00690650b28c5eb40c77bddcc66d321bb\",\n        \"size\": 181540439\n    },\n    \"NoScenario_Town04_Route26959_Weather2.tar.gz\": {\n        \"sha256\": \"944142aa4c2a47afb49854b230bbc555ea702fd00121aa99c140530c841a332d\",\n        \"size\": 550804431\n    },\n    \"NoScenario_Town04_Route27609_Weather9.tar.gz\": {\n        \"sha256\": \"f370d5be1e81690a5e78f9928b7afc7e31ca16fb384db8260d700a69403e52de\",\n        \"size\": 109364475\n    },\n    \"NoScenario_Town04_Route27614_Weather14.tar.gz\": {\n        \"sha256\": \"95661a9e6868bfd43184ce66ef3b1dfa14ffb625dd868268a269a3be2b141a5c\",\n        \"size\": 530897254\n    },\n    \"NoScenario_Town04_Route27619_Weather21.tar.gz\": {\n        \"sha256\": \"277fdb47307c26cf6ced5f0d7a6af10b5444a4e7334be41f2f73316ff3bb4d53\",\n        \"size\": 206709648\n    },\n    \"NoScenario_Town04_Route27624_Weather0.tar.gz\": {\n        \"sha256\": \"3e3e30ac2af39a2aee71151e77cdc5ecce1ac35f4f6f1e83c6c19f4c3460c427\",\n        \"size\": 164562038\n    },\n    \"NoScenario_Town04_Route27629_Weather6.tar.gz\": {\n        \"sha256\": \"96bb51d2f2c0be4d6daecf19c7f55bf5f61805d1586160c0d5f3208450b3ea6e\",\n        \"size\": 123916548\n    },\n    \"NoScenario_Town04_Route27634_Weather11.tar.gz\": {\n        \"sha256\": \"c540afd1d66f802b313e69f6587bb6bc823be04ee3047450ce0710e2722c0a65\",\n        \"size\": 504832745\n    },\n    \"NoScenario_Town04_Route27639_Weather18.tar.gz\": {\n        \"sha256\": \"be33a24a161eddc7fbebba8f8433799f2d66b780cedbb15ab547defb511e59c0\",\n        \"size\": 132022114\n    },\n    \"NoScenario_Town04_Route27644_Weather23.tar.gz\": {\n        \"sha256\": \"c2bf78e9e47c61cc09bb3cd39bf7042f802c6c52025e218ee2bed4cd5ee2c1be\",\n        \"size\": 454320700\n    },\n    \"NoScenario_Town04_Route27649_Weather2.tar.gz\": {\n        \"sha256\": \"6867fe6affe5cf3eda9b9145584f64cdc251a0f64fed840ab04cb0ba8ff962cd\",\n        \"size\": 168117979\n    },\n    \"NoScenario_Town04_Route27659_Weather13.tar.gz\": {\n        \"sha256\": \"ff8127bfbce0cfaef9b64ea3a24fd97b023cad3c47286ce5737038790a777f67\",\n        \"size\": 191746986\n    },\n    \"NoScenario_Town04_Route27664_Weather20.tar.gz\": {\n        \"sha256\": \"52da4102541961b6e17fd8255fa6fa63044dc196c8737cc7bea9dceb783bc21e\",\n        \"size\": 413600054\n    },\n    \"NoScenario_Town04_Route27669_Weather26.tar.gz\": {\n        \"sha256\": \"ea727ed8fbc6c214fc096ca23ccadde1a5e3e8ad0bc562c596efd4cc30de670d\",\n        \"size\": 228392683\n    },\n    \"NoScenario_Town04_Route27674_Weather5.tar.gz\": {\n        \"sha256\": \"2756737e899d6feeb635e8164e2b8bb3b2ae5721677139ba3b3e38309610b0f6\",\n        \"size\": 415860898\n    },\n    \"NoScenario_Town04_Route27679_Weather10.tar.gz\": {\n        \"sha256\": \"955e798397cb4787e1aad3a594b0bb1db3b8d9b1953563d262b3853c7a1b74cb\",\n        \"size\": 511380433\n    },\n    \"NoScenario_Town04_Route27684_Weather15.tar.gz\": {\n        \"sha256\": \"1e55d7e204903f55834477862c975c247924612667fe681d9c0a12c267651113\",\n        \"size\": 241767645\n    },\n    \"NoScenario_Town04_Route27689_Weather22.tar.gz\": {\n        \"sha256\": \"7660a0b666cdc1b96fec8a8f8552e3c2d105d07d9b58f3552e760a219d4f8af7\",\n        \"size\": 158315613\n    },\n    \"NoScenario_Town04_Route27694_Weather1.tar.gz\": {\n        \"sha256\": \"10ed074a0584f0957cd569ccb3b9b2556a7a160af0063129c729c08173d20eda\",\n        \"size\": 652996887\n    },\n    \"NoScenario_Town04_Route27699_Weather7.tar.gz\": {\n        \"sha256\": \"91f0718de00a00a3ba271fe55c86fe0e7a38cc278a87d5290a7f47d2382eddf8\",\n        \"size\": 782466772\n    },\n    \"NoScenario_Town04_Route27704_Weather12.tar.gz\": {\n        \"sha256\": \"3d29b2513af23a0b417b9072b322586c1ad01b421401c6ade368c3c573461cd2\",\n        \"size\": 470039125\n    },\n    \"NoScenario_Town04_Route27709_Weather19.tar.gz\": {\n        \"sha256\": \"158fcf29cc387e56f671e9b7f6fac0904e01edee01c31418dc42ac6a4c9e0168\",\n        \"size\": 79711960\n    },\n    \"NoScenario_Town04_Route27714_Weather25.tar.gz\": {\n        \"sha256\": \"127aa9b0162c2263dbbc958fbf24ed8c119321ca3e2a548021e9d1efb302a5a7\",\n        \"size\": 446295588\n    },\n    \"NoScenario_Town04_Route27719_Weather3.tar.gz\": {\n        \"sha256\": \"e55123cdfb46b922703a232423b7a775b3840b3c7d105907e5cae7d8ba5bad0b\",\n        \"size\": 254008061\n    },\n    \"NoScenario_Town04_Route27724_Weather9.tar.gz\": {\n        \"sha256\": \"21b1ce5ac38ee9f69e41e0550109b94693768cddc82ef5718e048e845bdbbf91\",\n        \"size\": 134292496\n    },\n    \"NoScenario_Town04_Route27729_Weather14.tar.gz\": {\n        \"sha256\": \"497c7c2a31e645bbdb27f2ad868cef53f6e066318672a5ca635ef2fea540302a\",\n        \"size\": 105556015\n    },\n    \"NoScenario_Town04_Route27739_Weather0.tar.gz\": {\n        \"sha256\": \"b89041195dde51a7320899cff76551d8c784f038c6d6aae5740764124b8ee472\",\n        \"size\": 130289284\n    },\n    \"NoScenario_Town04_Route27744_Weather6.tar.gz\": {\n        \"sha256\": \"9ae787f64b25788df230e4d29d9119771cab40c8d70e731b80e30462a5552940\",\n        \"size\": 572303421\n    },\n    \"NoScenario_Town04_Route27749_Weather11.tar.gz\": {\n        \"sha256\": \"822bcb0532c1f0c8b6ab5f1157972103bfdae742667a8e7da26019b1c5bb6a9e\",\n        \"size\": 131889274\n    },\n    \"NoScenario_Town04_Route27754_Weather18.tar.gz\": {\n        \"sha256\": \"5e1535e056895ca18000dcabc7c3373d090ad2e6bb305c5d98bd4167c4620e24\",\n        \"size\": 399833107\n    },\n    \"NoScenario_Town04_Route27759_Weather23.tar.gz\": {\n        \"sha256\": \"0a1420157990c3119e9f6ae7f28d3935239cae4fd6f7b08fa15f658e0b23aa08\",\n        \"size\": 170614627\n    },\n    \"NoScenario_Town04_Route27764_Weather2.tar.gz\": {\n        \"sha256\": \"c29a68d6cc1da3b0a755a6b344037015cbf1f6211c55dfbea4bbf7192640211a\",\n        \"size\": 559067883\n    },\n    \"NoScenario_Town04_Route27769_Weather8.tar.gz\": {\n        \"sha256\": \"fb1e6993d5f303ac8da8de0a4968aeee98602f9c5089e50699140ba29e2b9050\",\n        \"size\": 210070001\n    },\n    \"NoScenario_Town04_Route27774_Weather13.tar.gz\": {\n        \"sha256\": \"6bcd871fc827ecfdb9d0642713b5a878131033555a1946daff0ab5ad37bed3d1\",\n        \"size\": 339791515\n    },\n    \"NoScenario_Town04_Route27779_Weather20.tar.gz\": {\n        \"sha256\": \"32a51481ebcaf5d0731fdad8dfb19732a180f8eb63d7b006f9f5d91033226e27\",\n        \"size\": 526030579\n    },\n    \"NoScenario_Town04_Route27784_Weather26.tar.gz\": {\n        \"sha256\": \"7ebea9b790512ae751f90143cb085d7bf16dadbac80654b68d671a70eaebb61e\",\n        \"size\": 587328108\n    },\n    \"NoScenario_Town04_Route27789_Weather5.tar.gz\": {\n        \"sha256\": \"b34ab1fa69e2bf12096ff7d8d440a60a9f78dbe794bb2fbf83cc02552db7b68f\",\n        \"size\": 244604886\n    },\n    \"NoScenario_Town04_Route27794_Weather10.tar.gz\": {\n        \"sha256\": \"6ddb015f4aaa944ef1f68ea2dc49fa137155cab48e1c75295d5f7f1fc25771b8\",\n        \"size\": 538982425\n    },\n    \"NoScenario_Town04_Route27804_Weather22.tar.gz\": {\n        \"sha256\": \"2589c5edff36d33a874beca4b10b84c098b5f85d0cadd069d769243e801a3d8d\",\n        \"size\": 519023993\n    },\n    \"NoScenario_Town04_Route27814_Weather7.tar.gz\": {\n        \"sha256\": \"e689123270703396ea37a601d72a2838a9c4306017d71f4cc847df7cd325827b\",\n        \"size\": 342560736\n    },\n    \"NoScenario_Town04_Route27824_Weather19.tar.gz\": {\n        \"sha256\": \"b213831bcac1e33492124d8447a0f0302179448462d0e4c2b50c211d15ca0bb9\",\n        \"size\": 567431895\n    },\n    \"NoScenario_Town04_Route27829_Weather25.tar.gz\": {\n        \"sha256\": \"fa48e07d33b329b51a9acd263b03ef8cb654d625c2b182865c2105731759a631\",\n        \"size\": 255765626\n    },\n    \"NoScenario_Town04_Route27844_Weather14.tar.gz\": {\n        \"sha256\": \"3f59f5305fd5bd9440963195297085e0cf033b69c46bce54305acd5ef54e11d9\",\n        \"size\": 517919283\n    },\n    \"NoScenario_Town04_Route27849_Weather21.tar.gz\": {\n        \"sha256\": \"3b091aced187faeb2815c2e5f8aa035095d9c1e7622d85b3ddbddd85a1ebd446\",\n        \"size\": 233374427\n    },\n    \"NoScenario_Town04_Route27858_Weather5.tar.gz\": {\n        \"sha256\": \"cbd713ec10fbdc0ef7fd1d8885a672f4025b4d74c4488e475154d18f2d4ba8e6\",\n        \"size\": 443102120\n    },\n    \"NoScenario_Town04_Route27862_Weather9.tar.gz\": {\n        \"sha256\": \"1c0ce84ddfa9c4bf365e4784ddf3735e449cd55c8796a878e24e288b66728ee9\",\n        \"size\": 123478746\n    },\n    \"NoScenario_Town04_Route27866_Weather13.tar.gz\": {\n        \"sha256\": \"a47138d90abb73d5830cf740c5544380467969eb7e52c5770ff1569ebaa7fd92\",\n        \"size\": 127586811\n    },\n    \"NoScenario_Town04_Route27870_Weather19.tar.gz\": {\n        \"sha256\": \"7496548c1c8b93ac60daba2b19bc0cced98f7d6ce33c5ae2dfad95b52dc6e41e\",\n        \"size\": 250370486\n    },\n    \"NoScenario_Town04_Route27886_Weather10.tar.gz\": {\n        \"sha256\": \"c8925cd0abbd69abd69737320a40c0abfe3f21b9679632e57a3643295655d1e4\",\n        \"size\": 245024714\n    },\n    \"NoScenario_Town04_Route27890_Weather14.tar.gz\": {\n        \"sha256\": \"b500dde9b395710a43a53cb4e323419c5eb6c3163635e9c170bb26d1cd5f3123\",\n        \"size\": 396246958\n    },\n    \"NoScenario_Town04_Route27894_Weather20.tar.gz\": {\n        \"sha256\": \"f9f8e0f883e4efc459ea9136fa7cae8bee8cbd3e1151a2ef1f0271ea1637f1e1\",\n        \"size\": 523793101\n    },\n    \"NoScenario_Town04_Route27898_Weather25.tar.gz\": {\n        \"sha256\": \"fd71cb465870319b2f87e46fd034d5582c4c7495688d18efc54e09b7e36fd61c\",\n        \"size\": 212567659\n    },\n    \"NoScenario_Town04_Route27902_Weather2.tar.gz\": {\n        \"sha256\": \"a9886a77503919e03058c71599bde57fb1fdd0d54e0e81e3a2e8c1d5ed9461d2\",\n        \"size\": 575999910\n    },\n    \"NoScenario_Town04_Route27906_Weather7.tar.gz\": {\n        \"sha256\": \"4635f641ca7b74c7fddf162ab3d04a1a02bc6aabed97a9018cb1d38eeadce441\",\n        \"size\": 609765742\n    },\n    \"NoScenario_Town04_Route27910_Weather11.tar.gz\": {\n        \"sha256\": \"b46ec211dc70389a6f6adef6ebeb34006728cb054639469be36dd4be7d2b354a\",\n        \"size\": 153817082\n    },\n    \"NoScenario_Town04_Route27914_Weather15.tar.gz\": {\n        \"sha256\": \"afeedec5178975b5a209911d4d30449ac9c36fd4c2d874f17be8d269c5f6e8dd\",\n        \"size\": 365760177\n    },\n    \"NoScenario_Town04_Route27918_Weather21.tar.gz\": {\n        \"sha256\": \"0571244e9d872a33cc50fcf2274dc87750ad0a82b95eed6781c74cf08d760dad\",\n        \"size\": 122327025\n    },\n    \"NoScenario_Town04_Route27922_Weather26.tar.gz\": {\n        \"sha256\": \"7600f5eb9193810bfcbc76adae802a666179ce601b544ca8e1d845c9a2472757\",\n        \"size\": 263466330\n    },\n    \"NoScenario_Town04_Route27926_Weather3.tar.gz\": {\n        \"sha256\": \"5c99879fe61b35a3c55992d746f69c862a4f37dac55bfa38c86cc0440541bc43\",\n        \"size\": 554568900\n    },\n    \"NoScenario_Town04_Route27930_Weather8.tar.gz\": {\n        \"sha256\": \"1d605293d4ec32c84926bdb08633265b55ce1e5930bf5823334a6c481b4b6fb9\",\n        \"size\": 162783849\n    },\n    \"NoScenario_Town04_Route27934_Weather12.tar.gz\": {\n        \"sha256\": \"3f3be1d45ef3516684e41f42498aae846379093a8c8c4e4e9ef8dfa96fa672fc\",\n        \"size\": 141298695\n    },\n    \"NoScenario_Town04_Route27942_Weather22.tar.gz\": {\n        \"sha256\": \"827914adecfde9118486c68c7af2891ad384682a64646a82c8adec40fc4f9f0b\",\n        \"size\": 381756564\n    },\n    \"NoScenario_Town04_Route27946_Weather0.tar.gz\": {\n        \"sha256\": \"93a8cfab928ff080e9d66f4bfb3f5a1614b7a0c4dcff5a0a48765c211ca53957\",\n        \"size\": 441629391\n    },\n    \"NoScenario_Town04_Route27950_Weather5.tar.gz\": {\n        \"sha256\": \"96c060fb87da3ba11f711e2ad48a790248512960fe7e743bae91d613ce35c667\",\n        \"size\": 735710817\n    },\n    \"NoScenario_Town04_Route27954_Weather9.tar.gz\": {\n        \"sha256\": \"dc6443f1a934657c12d56b6f82475b41f856ff6d12f3d4750a73a016ea5497c4\",\n        \"size\": 396422087\n    },\n    \"NoScenario_Town04_Route27958_Weather13.tar.gz\": {\n        \"sha256\": \"7b297b345421fb712639a98ba626e4594b09b039fa4fecf730241a84243a8f83\",\n        \"size\": 512767452\n    },\n    \"NoScenario_Town04_Route27962_Weather19.tar.gz\": {\n        \"sha256\": \"2692b2ccddbd7444abaff90b52cc1e85f94ba9eed158c071e5fe55ded761ff90\",\n        \"size\": 481816574\n    },\n    \"NoScenario_Town04_Route27965_Weather22.tar.gz\": {\n        \"sha256\": \"08caddb0ec35294943b97f7884b00a63469fe4e780f23d921bbcea461ee6773e\",\n        \"size\": 118841962\n    },\n    \"NoScenario_Town04_Route27971_Weather2.tar.gz\": {\n        \"sha256\": \"01b23199fa5a47f5f07472c31ab65bd70e3ad962e7f6964abd6e99be9043371b\",\n        \"size\": 1921282004\n    },\n    \"NoScenario_Town04_Route28100_Weather23.tar.gz\": {\n        \"sha256\": \"482de426c9150c27d64e2e54bba2422d8ad63f3998c95ee637a3450f5265a6fb\",\n        \"size\": 124557913\n    },\n    \"NoScenario_Town05_Route26403_Weather25.tar.gz\": {\n        \"sha256\": \"49e9d2676a313bad3f34abe629db00cbde666324ac5d6e66c6042273426e3c02\",\n        \"size\": 267067351\n    },\n    \"NoScenario_Town05_Route26806_Weather11.tar.gz\": {\n        \"sha256\": \"c008619a04e2572acd5126cc127c4a946b2ac6c75faaa069123ae4a94b711571\",\n        \"size\": 285374329\n    },\n    \"NoScenario_Town05_Route26831_Weather13.tar.gz\": {\n        \"sha256\": \"aacce049da23905163098e37b1b1bbe3784cbe077272187e0d13f1839022d869\",\n        \"size\": 1860984327\n    },\n    \"NoScenario_Town05_Route27121_Weather3.tar.gz\": {\n        \"sha256\": \"64f17e7695e6123871df7fcdd71cafa78478acefeb713d82c35170edc6da8240\",\n        \"size\": 641227919\n    },\n    \"NoScenario_Town05_Route27616_Weather18.tar.gz\": {\n        \"sha256\": \"7d56adb198a175637963fc9dabada263517671a0b686ae3aa2be1f7243cac499\",\n        \"size\": 155388866\n    },\n    \"NoScenario_Town05_Route27626_Weather2.tar.gz\": {\n        \"sha256\": \"36dd25701d45f7fdf0b63a5e584c1866623eca295a9f43e5eb1b972785fed082\",\n        \"size\": 284335710\n    },\n    \"NoScenario_Town05_Route27641_Weather20.tar.gz\": {\n        \"sha256\": \"d54eb6b8fc102f8fd8d2b7e4d90e8858f6fb7d58e829bd2a179edccb6f7b9cac\",\n        \"size\": 214431035\n    },\n    \"NoScenario_Town05_Route27671_Weather1.tar.gz\": {\n        \"sha256\": \"c08fab071c7a096c884bfa490fb2ecf7a5060953f1fbd183f60049d3677e2614\",\n        \"size\": 863211535\n    },\n    \"NoScenario_Town05_Route27681_Weather12.tar.gz\": {\n        \"sha256\": \"0c1c3aa92f6d839ab9349f9dd7e7a6c531d490e2d3cf4f8dd7f84c76fb0f6526\",\n        \"size\": 715023999\n    },\n    \"NoScenario_Town05_Route27701_Weather9.tar.gz\": {\n        \"sha256\": \"92ad971e823435bd8fc100bd2b7693d33faff64c9ccb3e4ce747f73ef75b1099\",\n        \"size\": 137582815\n    },\n    \"NoScenario_Town05_Route27711_Weather21.tar.gz\": {\n        \"sha256\": \"9a3826f03dbd096842d6ef5b96e41fcb2df61c04c961d3669fc1f58fb0b6a2ae\",\n        \"size\": 587422496\n    },\n    \"NoScenario_Town05_Route27716_Weather0.tar.gz\": {\n        \"sha256\": \"d372de636a2c1cf2cdaf3c92e859ea2213fc21a1c1a93c1578c89dddfc4b5e48\",\n        \"size\": 137087873\n    },\n    \"NoScenario_Town05_Route27721_Weather6.tar.gz\": {\n        \"sha256\": \"dbb33548f45a2c30c9a998549efe3415972d6226fca8c4300737331f9b44b4d8\",\n        \"size\": 646259739\n    },\n    \"NoScenario_Town05_Route27726_Weather11.tar.gz\": {\n        \"sha256\": \"298dd67382d85434325ad1dbb837db505529a9eaac3cad0005cb205226b58e7f\",\n        \"size\": 358363440\n    },\n    \"NoScenario_Town05_Route27731_Weather18.tar.gz\": {\n        \"sha256\": \"29419bf362abd7e6b1981bd27be08c0be9bb7c4bbd33169d822429ef4d70c3e4\",\n        \"size\": 756678479\n    },\n    \"NoScenario_Town05_Route27736_Weather23.tar.gz\": {\n        \"sha256\": \"736b5f06ea7326f855b0442ea4fd512609faef8bbc3ff597335e487e27d7dcdc\",\n        \"size\": 465493529\n    },\n    \"NoScenario_Town05_Route27741_Weather2.tar.gz\": {\n        \"sha256\": \"3ec49566445e77740d869efe8b9f6d7a5e9f622252808b0648324fb9ddbe0176\",\n        \"size\": 621537807\n    },\n    \"NoScenario_Town05_Route27746_Weather8.tar.gz\": {\n        \"sha256\": \"670dbbee9c726ef4f79473059bfaf66a58e8338930f043be08267dc8124b2cbe\",\n        \"size\": 574149160\n    },\n    \"NoScenario_Town05_Route27751_Weather13.tar.gz\": {\n        \"sha256\": \"4dd989c008e1e17f53432651d4d719db6c76207782729d7abc7f65794e445a0b\",\n        \"size\": 958491243\n    },\n    \"NoScenario_Town05_Route27756_Weather20.tar.gz\": {\n        \"sha256\": \"d81131797867b8babb0610b54d3dd99066438fe5d65b00685bf583f6ead49852\",\n        \"size\": 600059057\n    },\n    \"NoScenario_Town05_Route27761_Weather26.tar.gz\": {\n        \"sha256\": \"feea65351965b1141df4c3592caf256191dc5dedfcc85bd04cc401dceed509af\",\n        \"size\": 321809778\n    },\n    \"NoScenario_Town05_Route27766_Weather5.tar.gz\": {\n        \"sha256\": \"b9a5bec3df4aea32a3ec01221cd57237d91ebdb0010393bab4a616bb3f59b4bd\",\n        \"size\": 439336704\n    },\n    \"NoScenario_Town05_Route27771_Weather10.tar.gz\": {\n        \"sha256\": \"4b4d8e83c8b9c0dd7b2455e26770a0f045cc378786004b4673d9db8f5c80675f\",\n        \"size\": 530448669\n    },\n    \"NoScenario_Town05_Route27776_Weather15.tar.gz\": {\n        \"sha256\": \"4ca92b55edb2d5422383b8ee46e8576fc41d2defb9efc58165bfae51e012b116\",\n        \"size\": 582746733\n    },\n    \"NoScenario_Town05_Route27781_Weather22.tar.gz\": {\n        \"sha256\": \"5df64d9bd0ddada4d4df31658e759232562d501b7ebebb65b13ff7ab14bea885\",\n        \"size\": 87304527\n    },\n    \"NoScenario_Town05_Route27786_Weather1.tar.gz\": {\n        \"sha256\": \"c67471bd858959b32050bf3ff3dd9522795ea388dc979f5510549486e9775fcd\",\n        \"size\": 854409729\n    },\n    \"NoScenario_Town05_Route27791_Weather7.tar.gz\": {\n        \"sha256\": \"652cd26a56cbf4d425bb7eaf0f72ea089917e67cd08ed32807d24bc772a8bb17\",\n        \"size\": 417257657\n    },\n    \"NoScenario_Town05_Route27796_Weather12.tar.gz\": {\n        \"sha256\": \"bfdc20639279ada3725f8f381e2f21aff3fed6dd97e5d3e7f05cf121904edaf0\",\n        \"size\": 767713777\n    },\n    \"NoScenario_Town05_Route27801_Weather19.tar.gz\": {\n        \"sha256\": \"63a2bfb7c00ce8ab874195f4498ca791edf2a45025c817a6c00c2dcc5d99eddd\",\n        \"size\": 127412483\n    },\n    \"NoScenario_Town05_Route27806_Weather25.tar.gz\": {\n        \"sha256\": \"a7a569bdb84fd7dbc790d114c3b886acb31ad6b1520f78287f6393ee921999ad\",\n        \"size\": 597517231\n    },\n    \"NoScenario_Town05_Route27811_Weather3.tar.gz\": {\n        \"sha256\": \"124a684916493dbf5c2f06e31ae21b03197cee76d5e7e2ad248711eedd5d5c22\",\n        \"size\": 413054124\n    },\n    \"NoScenario_Town05_Route27816_Weather9.tar.gz\": {\n        \"sha256\": \"447872e686164ff96cf8ab691bc388e6618a88d1c545158d2706ce5e1321de04\",\n        \"size\": 86899090\n    },\n    \"NoScenario_Town05_Route27821_Weather14.tar.gz\": {\n        \"sha256\": \"9b37900dd46142630ab29fcf8a233b2ef991d4be22ab4f8fe6f69a3539894309\",\n        \"size\": 613009021\n    },\n    \"NoScenario_Town05_Route27826_Weather21.tar.gz\": {\n        \"sha256\": \"e30a63a62e542f465ed4f2d03a993501b12debe43da581b5bdc47278ee3b65d9\",\n        \"size\": 373576304\n    },\n    \"NoScenario_Town05_Route27831_Weather0.tar.gz\": {\n        \"sha256\": \"f02634e2b3b12c71b25facda688e7880c1b154cf2bf68ce65ef6e141de7132b7\",\n        \"size\": 753278894\n    },\n    \"NoScenario_Town05_Route27836_Weather6.tar.gz\": {\n        \"sha256\": \"3a4a2428f25c1aefb7a95ab5c69f6f29e0188ff3bd415b1d36792a74fd478f2d\",\n        \"size\": 581906033\n    },\n    \"NoScenario_Town05_Route27841_Weather11.tar.gz\": {\n        \"sha256\": \"2a208121c124bd03106a8011acc462d91cad2438dff2cafbad0069bf3b03911a\",\n        \"size\": 518207409\n    },\n    \"NoScenario_Town05_Route27846_Weather18.tar.gz\": {\n        \"sha256\": \"73dc819eaf8fb46f4ae206bc0b015f434e39187a1dd479e965c87a376fa30048\",\n        \"size\": 627828671\n    },\n    \"NoScenario_Town05_Route27851_Weather23.tar.gz\": {\n        \"sha256\": \"7fb51a0b62b74b28d89f299d6a924b377f0cf6d74795bd5a6bba42891c333a36\",\n        \"size\": 903790650\n    },\n    \"NoScenario_Town05_Route27856_Weather2.tar.gz\": {\n        \"sha256\": \"8a4a8416cdcf0259f1e4a21b394c9a0e9fbc4ee9ee208a618aeb105037ae67b4\",\n        \"size\": 758921996\n    },\n    \"NoScenario_Town05_Route27860_Weather7.tar.gz\": {\n        \"sha256\": \"0aa8579e01661aec5427b6a4c1884918a2f5424ee261c21e6dc4cfc52d539f9d\",\n        \"size\": 334825922\n    },\n    \"NoScenario_Town05_Route27864_Weather11.tar.gz\": {\n        \"sha256\": \"a31af183b3bcceb071b7f9e3ebaced13f7b503bf3b333b3bac91927385d4a3be\",\n        \"size\": 374680001\n    },\n    \"NoScenario_Town05_Route27868_Weather15.tar.gz\": {\n        \"sha256\": \"be93cdb3e0b69e8476a66e64e609cbbf35d3231287e1dfba3b409c31df894740\",\n        \"size\": 620537449\n    },\n    \"NoScenario_Town05_Route27872_Weather21.tar.gz\": {\n        \"sha256\": \"a6c2c19b76a9654cc74413755ca7c11b1ec44b6e039882f7984fc7590bd120d0\",\n        \"size\": 539237784\n    },\n    \"NoScenario_Town05_Route27876_Weather26.tar.gz\": {\n        \"sha256\": \"6ce02dd36f1611117dfe6f90bef34eede2d5a12082fffdd63fac00b50e620ded\",\n        \"size\": 116971579\n    },\n    \"NoScenario_Town05_Route27880_Weather3.tar.gz\": {\n        \"sha256\": \"7fab197bf410e2866010505b78378dd64b205af9f4411679fb1c702603654f99\",\n        \"size\": 824855310\n    },\n    \"NoScenario_Town05_Route27884_Weather8.tar.gz\": {\n        \"sha256\": \"ff94a2485836a1c31df17a68174b5c80eec0fadd7d1d2a1232507e7a91af03e5\",\n        \"size\": 392065166\n    },\n    \"NoScenario_Town05_Route27888_Weather12.tar.gz\": {\n        \"sha256\": \"32d3a379890b2e985aa88cb247835df020484c477a3c05434368e008e2b0312a\",\n        \"size\": 767030330\n    },\n    \"NoScenario_Town05_Route27892_Weather18.tar.gz\": {\n        \"sha256\": \"910bb34843ac5e5a7a82966b75b62a1c722cb83e130a561871e05db393969a12\",\n        \"size\": 157408131\n    },\n    \"NoScenario_Town05_Route27896_Weather22.tar.gz\": {\n        \"sha256\": \"efba7c10f258017f60a1cecb50984ce264787cbe8bf8727fad6a912604c3a80d\",\n        \"size\": 611575510\n    },\n    \"NoScenario_Town05_Route27904_Weather5.tar.gz\": {\n        \"sha256\": \"7a79818ba6d666af23391212ae48c548ffc85c88ee3a63d71e10d5e0175ff8e8\",\n        \"size\": 557171621\n    },\n    \"NoScenario_Town05_Route27908_Weather9.tar.gz\": {\n        \"sha256\": \"2ffe91538a08bb3b7aed9eb3ae1d8310a4d024681ce28246d11d683e9e6c5e44\",\n        \"size\": 515213090\n    },\n    \"NoScenario_Town05_Route27912_Weather13.tar.gz\": {\n        \"sha256\": \"5eb3d8f9056a80fc003a1a2a9d58ce9c16e96d185a3ac339a84b5872a311f53e\",\n        \"size\": 401635289\n    },\n    \"NoScenario_Town05_Route27916_Weather19.tar.gz\": {\n        \"sha256\": \"732f7e1281600ce79e784528c8d41d4e1d2aaece880a3fa8df2d76f6728657d0\",\n        \"size\": 237554293\n    },\n    \"NoScenario_Town05_Route27920_Weather23.tar.gz\": {\n        \"sha256\": \"4d1d1ba991e29340b7c12ef1715d2d75fb445a63f2ef7d32d1dd13b53fabf9bc\",\n        \"size\": 228978417\n    },\n    \"NoScenario_Town05_Route27924_Weather1.tar.gz\": {\n        \"sha256\": \"3a91f46e2f8dbcb084e69613caca496ff2e440ffebb4e2299a160308059413d6\",\n        \"size\": 410988811\n    },\n    \"NoScenario_Town05_Route27928_Weather6.tar.gz\": {\n        \"sha256\": \"a6652c8ceb50ee21326d602679b6c7ab6d65c66c0de6bbe81b1157a035650053\",\n        \"size\": 710328287\n    },\n    \"NoScenario_Town05_Route27932_Weather10.tar.gz\": {\n        \"sha256\": \"7bda40c63fa371d47038ab000205d09db7e923c0896f4b14479761dbc10da8a7\",\n        \"size\": 338008132\n    },\n    \"NoScenario_Town05_Route27936_Weather14.tar.gz\": {\n        \"sha256\": \"04743746e94f663ee75bd881d9c70e0d8967483cabdf968d133b15275e0e78ca\",\n        \"size\": 268527938\n    },\n    \"NoScenario_Town05_Route27940_Weather20.tar.gz\": {\n        \"sha256\": \"c0aa14e5b86e6407e145b6523f91fcd11c0517cfec28b43516146d3f0411070e\",\n        \"size\": 1113750223\n    },\n    \"NoScenario_Town05_Route27944_Weather25.tar.gz\": {\n        \"sha256\": \"f5695440fcb63193a5c893072625e6b9253ff4945739003deba8f1841b8249f0\",\n        \"size\": 138945030\n    },\n    \"NoScenario_Town05_Route27948_Weather2.tar.gz\": {\n        \"sha256\": \"c444e238d43d407f16999c1b47646423fdb3da5338c487d1795675328c70cecd\",\n        \"size\": 144078507\n    },\n    \"NoScenario_Town05_Route27952_Weather7.tar.gz\": {\n        \"sha256\": \"f44c3a60dea53508bfaa33ad1652cec3f64d617a186272ab4e29c43d7480074c\",\n        \"size\": 157663597\n    },\n    \"NoScenario_Town05_Route27960_Weather15.tar.gz\": {\n        \"sha256\": \"cbdab5655f402082cb50a7a74418795b64602fc11ae6038b6e2de369e839a6ea\",\n        \"size\": 393402762\n    },\n    \"NoScenario_Town05_Route27963_Weather20.tar.gz\": {\n        \"sha256\": \"c8a30596867dacf3fbed1a53510d68dc8a76de161187f446531f0f2feaeae8df\",\n        \"size\": 181001376\n    },\n    \"NoScenario_Town05_Route27966_Weather23.tar.gz\": {\n        \"sha256\": \"65abb99b5f32bca0ff58e4837bb3726006e706d10ed4aca9ad1eb9f235c8a31b\",\n        \"size\": 838630717\n    },\n    \"NoScenario_Town05_Route27969_Weather0.tar.gz\": {\n        \"sha256\": \"feec0256e3f4a3a590cbd0a783e0df23060721802c55737d4f90c8f4de2cfa8a\",\n        \"size\": 250619371\n    },\n    \"NoScenario_Town05_Route27972_Weather3.tar.gz\": {\n        \"sha256\": \"775e0f5605402a58c504c282d4e5ee97e56b0612c0cac8292986927a1a6d2492\",\n        \"size\": 194547607\n    },\n    \"NoScenario_Town05_Route27975_Weather7.tar.gz\": {\n        \"sha256\": \"805e0a35981b078fa7f515e8cbf8905e79ba44a31cb6273f2a6ce99731166a20\",\n        \"size\": 136072420\n    },\n    \"NoScenario_Town05_Route27978_Weather10.tar.gz\": {\n        \"sha256\": \"34dce0e5520d79546e711e64580ced60c45e87880527b5650c0d60c2081b79a0\",\n        \"size\": 138919937\n    },\n    \"NoScenario_Town05_Route27981_Weather13.tar.gz\": {\n        \"sha256\": \"4a0fa4402d6fabdd816b1696bb1f13f4a67a70f56fe82bfb028bf6184cdee06d\",\n        \"size\": 232829771\n    },\n    \"NoScenario_Town05_Route27984_Weather18.tar.gz\": {\n        \"sha256\": \"d57aa3df59eb96d2fdcfbe4c97197b62a522ccec79c3fc7118934f511d795ccc\",\n        \"size\": 198573991\n    },\n    \"NoScenario_Town05_Route27987_Weather21.tar.gz\": {\n        \"sha256\": \"8a42bcdc6078188c202255e20e6f8837e5980d1c083b2c95c3c7dae4127b774d\",\n        \"size\": 179774196\n    },\n    \"NoScenario_Town05_Route27990_Weather25.tar.gz\": {\n        \"sha256\": \"16e3bc6297922eaa3aba66de6b1540fd4fa164665ea41ea8d4ac01e6fbfb0858\",\n        \"size\": 104363976\n    },\n    \"NoScenario_Town05_Route27993_Weather1.tar.gz\": {\n        \"sha256\": \"eba2070adeceb873087d6d38f7fd9e2f038f7fc6c31f7cafa214e579891757e6\",\n        \"size\": 152092056\n    },\n    \"NoScenario_Town05_Route27996_Weather5.tar.gz\": {\n        \"sha256\": \"f3b7cdc88b22ed36aa49cb9e91e30881932882f0b32521bdf6f05114230240d8\",\n        \"size\": 179519712\n    },\n    \"NoScenario_Town05_Route27999_Weather8.tar.gz\": {\n        \"sha256\": \"97de4c3a86bfdc269acb655f3a0ff352261d0f8c0b449da25cce5705a7185ea3\",\n        \"size\": 136806922\n    },\n    \"NoScenario_Town10HD_Route24320_Weather9.tar.gz\": {\n        \"sha256\": \"07d550f7527a0f940089e654946cedba65bdc34bb7a04032671c141a838022ab\",\n        \"size\": 187263012\n    },\n    \"NoScenario_Town11_Route26777_Weather5.tar.gz\": {\n        \"sha256\": \"efb5dd4d811d5ae8349045f6e4741be7c446b0f67183600ebc212340d0849944\",\n        \"size\": 47993402\n    },\n    \"NoScenario_Town11_Route27667_Weather23.tar.gz\": {\n        \"sha256\": \"df6ad4a3be648c40aeabe3b3e0c79075da590ba047293152341a53f98eb8157b\",\n        \"size\": 29866975\n    },\n    \"NoScenario_Town11_Route27672_Weather2.tar.gz\": {\n        \"sha256\": \"29639d08cebe9656dd27926085c5e763e0b0df08e281e15f67719e720d3f9b4d\",\n        \"size\": 115341693\n    },\n    \"NoScenario_Town11_Route27677_Weather8.tar.gz\": {\n        \"sha256\": \"1740674903b3983980a3f0415d6e474589cd4dbce9b3c10961dde2e4342af1ff\",\n        \"size\": 90774807\n    },\n    \"NoScenario_Town11_Route27682_Weather13.tar.gz\": {\n        \"sha256\": \"4f95372f74c1ff125206f454178ba47cd91e1d47a3e43e4eceff8cfddef1b153\",\n        \"size\": 29674696\n    },\n    \"NoScenario_Town11_Route27687_Weather20.tar.gz\": {\n        \"sha256\": \"8d9aaa75806d09601c229b73a05118f6815cb7859e9a569b98bdb7fa2a88d595\",\n        \"size\": 25598851\n    },\n    \"NoScenario_Town11_Route27692_Weather26.tar.gz\": {\n        \"sha256\": \"baf211405d188461e567cac96a6332ec4e0892447a41a464943ced07b4e5dd56\",\n        \"size\": 47400958\n    },\n    \"NoScenario_Town11_Route27697_Weather5.tar.gz\": {\n        \"sha256\": \"0514c3386c14cf8b41ecd3cf054860f7f2a188a9febcb8006883404df8301fa2\",\n        \"size\": 34270480\n    },\n    \"NoScenario_Town11_Route27702_Weather10.tar.gz\": {\n        \"sha256\": \"4288a3261a97e8e38340bee3aec7faaa9fcb14bce92b7e9e6d519f02f2db6aeb\",\n        \"size\": 81797814\n    },\n    \"NoScenario_Town11_Route27712_Weather22.tar.gz\": {\n        \"sha256\": \"81b37e159e516eb9418df6a4ad95e79fbf0f9000e5e71bc353176f7283ce38bf\",\n        \"size\": 74516268\n    },\n    \"NoScenario_Town11_Route27717_Weather1.tar.gz\": {\n        \"sha256\": \"1bbdddbf15f5c910c61020bf1dae08be7c6e5789625a71753f9f7e6170544f5a\",\n        \"size\": 124306503\n    },\n    \"NoScenario_Town11_Route27722_Weather7.tar.gz\": {\n        \"sha256\": \"3922bd1f9107134fa2ab1a340b8a84d4f7544cd20bba1fe31a98d87fbd592d2f\",\n        \"size\": 36490593\n    },\n    \"NoScenario_Town11_Route27732_Weather19.tar.gz\": {\n        \"sha256\": \"b0445b2ee8b8664279ab6f2f4f0c7b61598db257c803d750a02c2950282c2355\",\n        \"size\": 23947720\n    },\n    \"NoScenario_Town11_Route27737_Weather25.tar.gz\": {\n        \"sha256\": \"23ae983317564c68fcc8ce820163bc646fb96d0791135308881047905d9c4e05\",\n        \"size\": 69397915\n    },\n    \"NoScenario_Town11_Route27742_Weather3.tar.gz\": {\n        \"sha256\": \"8456114b5dce325d5731ac109ca10759819b3c54d4e4866817cdace1a0a7b47e\",\n        \"size\": 44362029\n    },\n    \"NoScenario_Town11_Route27747_Weather9.tar.gz\": {\n        \"sha256\": \"5c317c53afda9d2f1885d3bfc1d452784ddb6e8fd19fce3d429a22b8f07bc47a\",\n        \"size\": 28793303\n    },\n    \"NoScenario_Town11_Route27752_Weather14.tar.gz\": {\n        \"sha256\": \"424821cbc8d9710152dab91681c9558aa75a46a316f72bfde662e32ed44c1d4b\",\n        \"size\": 29984369\n    },\n    \"NoScenario_Town11_Route27757_Weather21.tar.gz\": {\n        \"sha256\": \"a6541d10d6a2a3449e7d39c35f4132b6a99a3b4506399ed3d866c6005b96b664\",\n        \"size\": 26349275\n    },\n    \"NoScenario_Town11_Route27762_Weather0.tar.gz\": {\n        \"sha256\": \"1a4a709983f0a2cb03cc4f7b1de09d50d7b7d048ea7e5b140eb103d8483c0172\",\n        \"size\": 112464757\n    },\n    \"NoScenario_Town11_Route27767_Weather6.tar.gz\": {\n        \"sha256\": \"9d664b18101f24e945707bdefe8b8a556d8de1f16fd1d9be7b07497865b7919b\",\n        \"size\": 42088938\n    },\n    \"NoScenario_Town11_Route27772_Weather11.tar.gz\": {\n        \"sha256\": \"185c4585e259a0296faaa3eac3a990b9c872291e727f0628cf1f99de365d01a7\",\n        \"size\": 75921740\n    },\n    \"NoScenario_Town11_Route27777_Weather18.tar.gz\": {\n        \"sha256\": \"db537d9cf54d1f1a22e91a4f5c161eadded6feea3a3b49c4a91e867c62f69872\",\n        \"size\": 111891586\n    },\n    \"NoScenario_Town11_Route27782_Weather23.tar.gz\": {\n        \"sha256\": \"76fe9770836d0c748f630e2cab57055d8689d1566dd2f82a199930919b1efdad\",\n        \"size\": 24376351\n    },\n    \"NoScenario_Town11_Route27787_Weather2.tar.gz\": {\n        \"sha256\": \"5657ea23a205874d9cc9f6f154dee3fe8c9eba686fccb748f482184cb4a8ca96\",\n        \"size\": 44661202\n    },\n    \"NoScenario_Town11_Route27792_Weather8.tar.gz\": {\n        \"sha256\": \"3a09ef49960c5299ed8b09eb8198c3d520439682dab3b260bd98c770e71da50d\",\n        \"size\": 35111684\n    },\n    \"NoScenario_Town11_Route27797_Weather13.tar.gz\": {\n        \"sha256\": \"0f8a9651f4cd4d35e812c19b297c8a0ef7bbdb6573494658ee48d843f05647ee\",\n        \"size\": 27176409\n    },\n    \"NoScenario_Town11_Route27802_Weather20.tar.gz\": {\n        \"sha256\": \"634c9f803974ca90ce7b918b8abb945611d01ed5ec5482bafd51223e41f61732\",\n        \"size\": 73079993\n    },\n    \"NoScenario_Town11_Route27807_Weather26.tar.gz\": {\n        \"sha256\": \"1cd1ff73a3545f7d57b30efd1b616ce5ea9d61ef299121abeb5f79cc00b7eb11\",\n        \"size\": 137645548\n    },\n    \"NoScenario_Town11_Route27812_Weather5.tar.gz\": {\n        \"sha256\": \"366bc975bc598ac4941af7846e53a0963e540664c1c651fee4a32fbe8da27601\",\n        \"size\": 116092321\n    },\n    \"NoScenario_Town11_Route27817_Weather10.tar.gz\": {\n        \"sha256\": \"e02cf95c5cc99dbb7bcbad634d5af40c1425411bcee17a4cd3dd689876130425\",\n        \"size\": 74743685\n    },\n    \"NoScenario_Town11_Route27822_Weather15.tar.gz\": {\n        \"sha256\": \"1e71d35b013b2a6d442e59b3b0d66f5bbeb30030e2537413a6196d7a5d8a66a1\",\n        \"size\": 25584721\n    },\n    \"NoScenario_Town11_Route27827_Weather22.tar.gz\": {\n        \"sha256\": \"dd7548d12b94d9d91d5819f1b3430c5fab788f79e7b42cda7a27632d85f0bdf1\",\n        \"size\": 69736444\n    },\n    \"NoScenario_Town11_Route27832_Weather1.tar.gz\": {\n        \"sha256\": \"68abf356947ebdd2592657ac8091265ce4eb1bbb11d404565c9fe2448254763a\",\n        \"size\": 45161691\n    },\n    \"NoScenario_Town11_Route27837_Weather7.tar.gz\": {\n        \"sha256\": \"00af399f405949283442cc525d97a42b95b89690850a733507610cedf286afa1\",\n        \"size\": 127037071\n    },\n    \"NoScenario_Town11_Route27842_Weather12.tar.gz\": {\n        \"sha256\": \"32f3b4334e3499108ac064e0b715e105f69459851c48558c4bb88aa78ca3f475\",\n        \"size\": 33912932\n    },\n    \"NoScenario_Town11_Route27847_Weather19.tar.gz\": {\n        \"sha256\": \"9cb4a60364ccf7a2025595025b9c4ee18b1a4d1a935b05578c9e280cc823a537\",\n        \"size\": 26322455\n    },\n    \"NoScenario_Town11_Route27852_Weather25.tar.gz\": {\n        \"sha256\": \"037d348f2f3f442564978dab0263a37a6e69178d9d7bdac68298a68ac4455b8c\",\n        \"size\": 22772700\n    },\n    \"NoScenario_Town11_Route27857_Weather3.tar.gz\": {\n        \"sha256\": \"288e03fd9befd18368a0f6fa197f1c6461bd8f40406b8c5b12011009ec77a244\",\n        \"size\": 45040964\n    },\n    \"NoScenario_Town11_Route27861_Weather8.tar.gz\": {\n        \"sha256\": \"6b91f784d12872e5320a204ef44a491cc5892121aabdb9508f4f0018272ba022\",\n        \"size\": 93335373\n    },\n    \"NoScenario_Town11_Route27865_Weather12.tar.gz\": {\n        \"sha256\": \"315ee33b5d4e550119ce6cd9ead87f2492801e4571426bf6c45b4555fff30914\",\n        \"size\": 35746770\n    },\n    \"NoScenario_Town11_Route27869_Weather18.tar.gz\": {\n        \"sha256\": \"a54511627394be5f4f76539eb3e570b22e83a3789918a3749677665b8df4620c\",\n        \"size\": 44564736\n    },\n    \"NoScenario_Town11_Route27873_Weather22.tar.gz\": {\n        \"sha256\": \"713b6d54b23d3ffd0a6edfbfa2d13615fe1a2038dbde031eb828ff1e91ac0595\",\n        \"size\": 30894133\n    },\n    \"NoScenario_Town11_Route27877_Weather0.tar.gz\": {\n        \"sha256\": \"4f88ce7de5dccb1be83c55ac906147e9801489f72bf8366cf65f3bdf673880d2\",\n        \"size\": 47337292\n    },\n    \"NoScenario_Town11_Route27881_Weather5.tar.gz\": {\n        \"sha256\": \"6cf46e2410f98f80a3222293882f6a8550c57708b6304e3c6b13ed1c32181dbc\",\n        \"size\": 46886466\n    },\n    \"NoScenario_Town11_Route27889_Weather13.tar.gz\": {\n        \"sha256\": \"a71f2f27ddfd53c970da7bf983fef48ed563ab81dc131dcef6a06e714456fccf\",\n        \"size\": 31285336\n    },\n    \"NoScenario_Town11_Route27897_Weather23.tar.gz\": {\n        \"sha256\": \"88ac5e4538d74fd9ea9cd52a931eed130c5cb0d388f3fec5eba037bcd875c745\",\n        \"size\": 35576240\n    },\n    \"NoScenario_Town11_Route27901_Weather1.tar.gz\": {\n        \"sha256\": \"72285bc49651efe4bfa9d2af621ba0c89ae096011143a392ebf0a6576f5f0a8c\",\n        \"size\": 54316231\n    },\n    \"NoScenario_Town11_Route27905_Weather6.tar.gz\": {\n        \"sha256\": \"0918c17a7cf4663e05a7b8444808773fc8b35dceeb129d4934696de235fe071e\",\n        \"size\": 50376255\n    },\n    \"NoScenario_Town11_Route27909_Weather10.tar.gz\": {\n        \"sha256\": \"a8808f3c0a7b064f9446b1f66614af430e22cc364c9e0122901986bb08b310a3\",\n        \"size\": 31991038\n    },\n    \"NoScenario_Town11_Route27913_Weather14.tar.gz\": {\n        \"sha256\": \"eaa5a7b1338a47d8be4bba5287e9720dfdf3ecb7f0d279b1212f6d06aec1bc86\",\n        \"size\": 46179239\n    },\n    \"NoScenario_Town11_Route27917_Weather20.tar.gz\": {\n        \"sha256\": \"43424bc4e132948967cb1726628afd20ab1cf4db56d110dbaae0f0f42a2cfa18\",\n        \"size\": 23789655\n    },\n    \"NoScenario_Town11_Route27933_Weather11.tar.gz\": {\n        \"sha256\": \"4831a6fb7ec710caaac43a958c61d8d091ed6c7a61ea98e538316c16ef52548a\",\n        \"size\": 36053720\n    },\n    \"NoScenario_Town11_Route27937_Weather15.tar.gz\": {\n        \"sha256\": \"6b9cfbe75392583ba8367e71c1385e5b1df51b0688c65e443f70de306beda985\",\n        \"size\": 34651647\n    },\n    \"NoScenario_Town11_Route27941_Weather21.tar.gz\": {\n        \"sha256\": \"731f4c090f46d4c287144349825314fd8d30412040de06a4a9a1bf8285a77a35\",\n        \"size\": 27973852\n    },\n    \"NoScenario_Town12_Route11429_Weather18.tar.gz\": {\n        \"sha256\": \"c7bab0b322122a0eaf377c5475123f8efc8d8aba28fdf8230a683c88450c62a6\",\n        \"size\": 316702040\n    },\n    \"NoScenario_Town12_Route14285_Weather14.tar.gz\": {\n        \"sha256\": \"bf2709b178d7ca01caac7ffed16a72808427dcc37a64967727b68a8f8a4c9ccd\",\n        \"size\": 239185419\n    },\n    \"NoScenario_Town12_Route14319_Weather22.tar.gz\": {\n        \"sha256\": \"700e6351e7cceadb0d599b19464f88ddd9b8906632e720f3897c32601afee56d\",\n        \"size\": 201136115\n    },\n    \"NoScenario_Town12_Route14331_Weather8.tar.gz\": {\n        \"sha256\": \"c5ce87e84f158f8f88af5dfb2cf1069dd3d9e7f12d435a2f6b826a57a2e698a1\",\n        \"size\": 222089744\n    },\n    \"NoScenario_Town12_Route14443_Weather8.tar.gz\": {\n        \"sha256\": \"4bc8d90054d7ff35c7bea83842ea9ae6bba3f01043e88795af776e78246cd317\",\n        \"size\": 239119742\n    },\n    \"NoScenario_Town12_Route14453_Weather0.tar.gz\": {\n        \"sha256\": \"30dd4352836f73cb6f441148ccd8c8301ab597980c31c327aa46b35bbec66510\",\n        \"size\": 327782523\n    },\n    \"NoScenario_Town12_Route14476_Weather23.tar.gz\": {\n        \"sha256\": \"7d4e263ffcc02503bef766768de7815e4cd9b00a725f51a09eccc9e8cebb53fc\",\n        \"size\": 172496406\n    },\n    \"NoScenario_Town12_Route14557_Weather0.tar.gz\": {\n        \"sha256\": \"14381d4257e34869c1c64f08e9173c1fb45c84351e0e967f6516a155431ac7b7\",\n        \"size\": 190537547\n    },\n    \"NoScenario_Town12_Route14666_Weather5.tar.gz\": {\n        \"sha256\": \"fbb5d34c4756cf4e4df1716a8740b08a445e3f73577ecb1f37401e0dd34c6f77\",\n        \"size\": 235294781\n    },\n    \"NoScenario_Town12_Route14738_Weather25.tar.gz\": {\n        \"sha256\": \"601d4cfe8468bab25630623a5a7707a67d74c3b3a861aa1c7f289f74e5915db7\",\n        \"size\": 170882827\n    },\n    \"NoScenario_Town12_Route14816_Weather25.tar.gz\": {\n        \"sha256\": \"72e0fff6db80cdfe71e769dbad5aac62ea4fb3c790c62193c9125e750c7c940c\",\n        \"size\": 137763687\n    },\n    \"NoScenario_Town12_Route14817_Weather0.tar.gz\": {\n        \"sha256\": \"2f62c0262da5c3e68b4431681af5dc3b3d337862edefa8dc136912558cd14391\",\n        \"size\": 111353838\n    },\n    \"NoScenario_Town12_Route14911_Weather8.tar.gz\": {\n        \"sha256\": \"070a89febe4306a1a14c2834efe8687016609575b97d52b88cfd812d0196daf8\",\n        \"size\": 136598196\n    },\n    \"NoScenario_Town12_Route14918_Weather23.tar.gz\": {\n        \"sha256\": \"55a72bdf07d2d8661d0038b8939f1ffd5b5c520cd7af140a1fa12d62d5c54af7\",\n        \"size\": 193427425\n    },\n    \"NoScenario_Town12_Route15008_Weather9.tar.gz\": {\n        \"sha256\": \"a7849d9a6eb456191312d21a95c5d727946a526a5f1c018fff3d1b8b07932793\",\n        \"size\": 141885129\n    },\n    \"NoScenario_Town12_Route15086_Weather9.tar.gz\": {\n        \"sha256\": \"0ca64000da5becd3e8d1fdabb20a86fb1594ce71da7b548236354d610c762e48\",\n        \"size\": 166448059\n    },\n    \"NoScenario_Town12_Route15143_Weather14.tar.gz\": {\n        \"sha256\": \"eabb04e75524007adb66c6207469fa7d37f59bed9276e68a047f78d2e65088ed\",\n        \"size\": 180570953\n    },\n    \"NoScenario_Town12_Route15152_Weather23.tar.gz\": {\n        \"sha256\": \"718270ac2663c63827c040c2522bfe1683202fb69c522e6ae154067b7368ef2b\",\n        \"size\": 102974412\n    },\n    \"NoScenario_Town12_Route15476_Weather9.tar.gz\": {\n        \"sha256\": \"009f762878ccd987df5d47f411a251973332eac09a61dc8bf20eb2c7d1adcfe6\",\n        \"size\": 211300359\n    },\n    \"NoScenario_Town12_Route15738_Weather11.tar.gz\": {\n        \"sha256\": \"3576df3dacd883090b817e9d3dfd582e8c5c01937d5f90e8f40d2552ab7eeb44\",\n        \"size\": 157378864\n    },\n    \"NoScenario_Town12_Route15911_Weather2.tar.gz\": {\n        \"sha256\": \"69a77d533cd54087c0849cc443a60111fb23103a11bc37c0b36eaf382214c883\",\n        \"size\": 157066626\n    },\n    \"NoScenario_Town12_Route16008_Weather21.tar.gz\": {\n        \"sha256\": \"978010b531319fc0c6155cd1df1f4f565fbb7ab8c8cdf4f3fa3894c8abe44c7d\",\n        \"size\": 134961990\n    },\n    \"NoScenario_Town12_Route16152_Weather9.tar.gz\": {\n        \"sha256\": \"575f46e47b8fd425d1cbe1a087481535b71498b20052b2a0ff0d353f54926c70\",\n        \"size\": 88309798\n    },\n    \"NoScenario_Town12_Route1693_Weather23.tar.gz\": {\n        \"sha256\": \"b14b83ce94c64dc44e8ee36e38a390ccec9b469d59d7997dd6f987b55b595b33\",\n        \"size\": 461528475\n    },\n    \"NoScenario_Town12_Route1694_Weather23.tar.gz\": {\n        \"sha256\": \"ee43a53fd76efea4c37d011bf09c5bdb18726f4157ac647010ca56a4f2c7ce39\",\n        \"size\": 134891471\n    },\n    \"NoScenario_Town12_Route1761_Weather13.tar.gz\": {\n        \"sha256\": \"7f93cae49e4d8197df26e4f02827f99deab5d439e5b5506e1ac3ac2bb2e3d8df\",\n        \"size\": 426619138\n    },\n    \"NoScenario_Town12_Route18217_Weather8.tar.gz\": {\n        \"sha256\": \"0c215fb01b59c6a3874c8cfc767ce6b638a43a1fec1e62e08c4a8e6caf6bf39d\",\n        \"size\": 168926926\n    },\n    \"NoScenario_Town12_Route20690_Weather19.tar.gz\": {\n        \"sha256\": \"f39e69bbe409e6046666dd2515589c74a7ec7fa8626e7c1ea5a971017c899e11\",\n        \"size\": 302496297\n    },\n    \"NoScenario_Town12_Route2072_Weather12.tar.gz\": {\n        \"sha256\": \"b980efec6162c4fb268e4f0f5ac3fb9640164c1435e6a6879ce478d1e2703779\",\n        \"size\": 226650169\n    },\n    \"NoScenario_Town12_Route2139_Weather1.tar.gz\": {\n        \"sha256\": \"b4374613db105c7a7b96cbb1280df59313af96151b677b9e722e06595614bfb9\",\n        \"size\": 202722101\n    },\n    \"NoScenario_Town12_Route23745_Weather23.tar.gz\": {\n        \"sha256\": \"62d657de87f44a8c96f390e422c4e1ec39eb1d51dcb4d65a8dedc6cfcdf8359a\",\n        \"size\": 212155845\n    },\n    \"NoScenario_Town12_Route23746_Weather25.tar.gz\": {\n        \"sha256\": \"2236daec1769a5058a1ada60f1f6d8d3d596e971eaa3e465116ae917db17bb55\",\n        \"size\": 203134104\n    },\n    \"NoScenario_Town12_Route23749_Weather1.tar.gz\": {\n        \"sha256\": \"52935a65917d8c120055a1174cffec0f562490ce59d471f2c00ed6d2c8ad7f95\",\n        \"size\": 299018709\n    },\n    \"NoScenario_Town12_Route23752_Weather5.tar.gz\": {\n        \"sha256\": \"73e1dae330bf16cea3c4fd6360f2f070eb62ba62f2f510224c78e62f74befcd2\",\n        \"size\": 293015899\n    },\n    \"NoScenario_Town12_Route23755_Weather8.tar.gz\": {\n        \"sha256\": \"79cc6b1493b70665bd59a1d4e43a79f7f710d114c4d5d228da739f88b5e84ebb\",\n        \"size\": 286090804\n    },\n    \"NoScenario_Town12_Route23756_Weather9.tar.gz\": {\n        \"sha256\": \"641d44d04466cb689c27c9bb4323ef1bd9f20bf688263ce9968b4529c564b79e\",\n        \"size\": 261157500\n    },\n    \"NoScenario_Town12_Route23762_Weather15.tar.gz\": {\n        \"sha256\": \"bd14d6df9e04ae15d2a04c94084c4e98932c45b6a681552bcb33e9f660608d04\",\n        \"size\": 193363105\n    },\n    \"NoScenario_Town12_Route23764_Weather19.tar.gz\": {\n        \"sha256\": \"07fa576ac588b5a4c13acedcb94f376f57edda698f7a59eb5c0b608d44d94975\",\n        \"size\": 265926034\n    },\n    \"NoScenario_Town12_Route23766_Weather21.tar.gz\": {\n        \"sha256\": \"b2a174f05baf0ba8bfe1ae901790f9bf80882050124fe93a402b9d9836faa6da\",\n        \"size\": 241181458\n    },\n    \"NoScenario_Town12_Route23768_Weather23.tar.gz\": {\n        \"sha256\": \"a97c2d6edb0d2d36a2efd0537c828e4f88a7e9ea035d8e4e0e2275f0c3ce82d5\",\n        \"size\": 162604840\n    },\n    \"NoScenario_Town12_Route23774_Weather3.tar.gz\": {\n        \"sha256\": \"31a69d388c00655de195ac00be4d050529ba9c56da1d2f412092ce2bf67e2429\",\n        \"size\": 187254793\n    },\n    \"NoScenario_Town12_Route23776_Weather6.tar.gz\": {\n        \"sha256\": \"77c050884c2b40a041ae16e14f59f602fa738211bff3c4848e49d6947431f679\",\n        \"size\": 185804904\n    },\n    \"NoScenario_Town12_Route23777_Weather7.tar.gz\": {\n        \"sha256\": \"6481251067e32f3f328f1fb16824f043cd9ee973d4ed66a5d2a5401e2670adb6\",\n        \"size\": 159187655\n    },\n    \"NoScenario_Town12_Route23778_Weather8.tar.gz\": {\n        \"sha256\": \"1950b6d985e1591fd990b0a5654c4634f3c4eea1e9551d3a3548f3cb2db36918\",\n        \"size\": 137221432\n    },\n    \"NoScenario_Town12_Route23779_Weather9.tar.gz\": {\n        \"sha256\": \"5f1e9f1e1bcc12dc39cb4b6c328c3ecab28d39c97ceb202b7b70df8e13ba8661\",\n        \"size\": 190260728\n    },\n    \"NoScenario_Town12_Route23780_Weather10.tar.gz\": {\n        \"sha256\": \"b20ece8e0ecbac29aa1d2108c738ed52fe02fc471c0f4dc01956fd26be65efb7\",\n        \"size\": 198190673\n    },\n    \"NoScenario_Town12_Route23786_Weather18.tar.gz\": {\n        \"sha256\": \"38a7f5a85c2f6dc52f0e431ace8973bcc6746d8749690405418be124c34c3f3d\",\n        \"size\": 216525422\n    },\n    \"NoScenario_Town12_Route23791_Weather23.tar.gz\": {\n        \"sha256\": \"490ecc55e9625ffd305f0ab20d13d01b9fc91933f36ab67644130365854d436d\",\n        \"size\": 225329225\n    },\n    \"NoScenario_Town12_Route23792_Weather25.tar.gz\": {\n        \"sha256\": \"a4afc695c9d3eb9d38361edf7f0b52cf32531fa90ca6b4b3e8bb6e0739de0fb4\",\n        \"size\": 221380948\n    },\n    \"NoScenario_Town12_Route23795_Weather1.tar.gz\": {\n        \"sha256\": \"1afd1f1f10fe7776c3d4e40d4908312d259120833593f650a53b642f66467bb9\",\n        \"size\": 211351870\n    },\n    \"NoScenario_Town12_Route23798_Weather5.tar.gz\": {\n        \"sha256\": \"6607ebc0a353f81d9c4ea16e08184104dde5fb2d507ea8454c1e8a4852a4f7e1\",\n        \"size\": 299093239\n    },\n    \"NoScenario_Town12_Route23800_Weather7.tar.gz\": {\n        \"sha256\": \"1c2b7507f6c8eee7efabc64a7c3ef26197c4f9e31b78455f4b3a543c2aa2f797\",\n        \"size\": 300445056\n    },\n    \"NoScenario_Town12_Route23802_Weather9.tar.gz\": {\n        \"sha256\": \"aeff97cbd15760f0e7601e6a53d128663f6f4cdc623a3e2311320ef8b531ed6c\",\n        \"size\": 239391937\n    },\n    \"NoScenario_Town12_Route23803_Weather10.tar.gz\": {\n        \"sha256\": \"b2aa8a982f665f8d03e592ad9ac96aa750a7c3903916b345fd8df060bec0cfa0\",\n        \"size\": 352532559\n    },\n    \"NoScenario_Town12_Route23804_Weather11.tar.gz\": {\n        \"sha256\": \"ab6ed5049ba1893754310c40ed6ba9003dbc9aae7c45fe5c19a0323e7c0df21a\",\n        \"size\": 331133421\n    },\n    \"NoScenario_Town12_Route23805_Weather12.tar.gz\": {\n        \"sha256\": \"9b9fb16d72ab9b82dcdcbefe8e189fa990658248d46ff67a2e6c05f566fd8d78\",\n        \"size\": 271773961\n    },\n    \"NoScenario_Town12_Route23807_Weather14.tar.gz\": {\n        \"sha256\": \"973a89801645066b16cb84248e90e55c62aea798b0835321273d0c1eddfdc35d\",\n        \"size\": 293577255\n    },\n    \"NoScenario_Town12_Route23811_Weather20.tar.gz\": {\n        \"sha256\": \"91dd498ee37b8fd32de04b1980197180883bc6549a98f696f9afc01da9b419ec\",\n        \"size\": 291563168\n    },\n    \"NoScenario_Town12_Route23812_Weather21.tar.gz\": {\n        \"sha256\": \"c21344da146034574913d5fd8d2756a285a3aa81e66912cdb7dd42deb3d8121b\",\n        \"size\": 289039227\n    },\n    \"NoScenario_Town12_Route23813_Weather22.tar.gz\": {\n        \"sha256\": \"7cf5a0dd4f9cdb553416ad0262f64c5fc88e7c424cd3a9b3bd9ba3bd51c15367\",\n        \"size\": 202574273\n    },\n    \"NoScenario_Town12_Route23814_Weather23.tar.gz\": {\n        \"sha256\": \"97bf0ee28a610e1ee63898253720eec558b9f3b7ce404dafe596e3cad6d0cb7d\",\n        \"size\": 214017073\n    },\n    \"NoScenario_Town12_Route23819_Weather2.tar.gz\": {\n        \"sha256\": \"826c3dc7ada2b5aecb35726587d3a6efef40f2a46c16ab0587fa5484f754974c\",\n        \"size\": 147235715\n    },\n    \"NoScenario_Town12_Route23820_Weather3.tar.gz\": {\n        \"sha256\": \"1369aaabe58d2a0c7195186cd240d410eb1a36fea553625058892857817b75a6\",\n        \"size\": 139003044\n    },\n    \"NoScenario_Town12_Route23933_Weather1.tar.gz\": {\n        \"sha256\": \"3358fbc4f1f77add5f3a6a2fa992eda8c369d9eb2d7d092bf952c8f61efc3ff9\",\n        \"size\": 254248358\n    },\n    \"NoScenario_Town12_Route23934_Weather2.tar.gz\": {\n        \"sha256\": \"76fdd8762101a21ecb9e8cf46e9086f2806c00be55d6bb76c75dde2919cc00b9\",\n        \"size\": 253242208\n    },\n    \"NoScenario_Town12_Route23937_Weather6.tar.gz\": {\n        \"sha256\": \"fbac446ab4883f1b941ae57575819da1b423d28b3539b1810af3617b41c28d72\",\n        \"size\": 294496064\n    },\n    \"NoScenario_Town12_Route23940_Weather9.tar.gz\": {\n        \"sha256\": \"93902ead918e5db004965aa016c17d4d9bc505166e31f87cc80fcd2afb8a4b3d\",\n        \"size\": 253881566\n    },\n    \"NoScenario_Town12_Route23941_Weather10.tar.gz\": {\n        \"sha256\": \"8bfa7115d21f2ac5fd5965dd88d2975d67dd98f6af51c68bc0214a7fc6fcb24d\",\n        \"size\": 278758216\n    },\n    \"NoScenario_Town12_Route23943_Weather12.tar.gz\": {\n        \"sha256\": \"07adde4cdde4d8d0ccabd7cd991d2876dd5033acdb38ccceda22fd0b1189e34e\",\n        \"size\": 268342463\n    },\n    \"NoScenario_Town12_Route23944_Weather13.tar.gz\": {\n        \"sha256\": \"6f44416c0fc21ab83bf6146b15aad111b380cebf7f7c9bacf285405676f062ce\",\n        \"size\": 265517301\n    },\n    \"NoScenario_Town12_Route23952_Weather23.tar.gz\": {\n        \"sha256\": \"8b984e6baef2145df0fe99d39640f8669cc7074168fdeed9e3f72ed9daaaa4ab\",\n        \"size\": 240270495\n    },\n    \"NoScenario_Town12_Route23956_Weather1.tar.gz\": {\n        \"sha256\": \"36f91dd0c166ac37aa0a6ce903c2ea4cfe31f0924900d0d7820cb2e20cd3baeb\",\n        \"size\": 205778833\n    },\n    \"NoScenario_Town12_Route23958_Weather3.tar.gz\": {\n        \"sha256\": \"62dc4ddab5fd0afe0e36785afbec1240721a7a2ebb8ad8da6e2b2f2e7f4bcc95\",\n        \"size\": 197721317\n    },\n    \"NoScenario_Town12_Route23962_Weather8.tar.gz\": {\n        \"sha256\": \"1e0e16addfa044f78ee447e50bceed2d3cd398a1510f1f63b59eec1044411b60\",\n        \"size\": 178301722\n    },\n    \"NoScenario_Town12_Route23964_Weather10.tar.gz\": {\n        \"sha256\": \"b23b20801434b80d067ca8dcfde682a8c0ef5c4631ccc6e57699ede434eaa174\",\n        \"size\": 181635826\n    },\n    \"NoScenario_Town12_Route23965_Weather11.tar.gz\": {\n        \"sha256\": \"22260fad48de13df1173a179bc2987adf13b6e0263b5dcdd480d16cfe677aa26\",\n        \"size\": 118748602\n    },\n    \"NoScenario_Town12_Route23966_Weather12.tar.gz\": {\n        \"sha256\": \"d91382fef919e44566d9281f5aa127729ee54b36779b2d8c0be3316881e95585\",\n        \"size\": 126157888\n    },\n    \"NoScenario_Town12_Route23967_Weather13.tar.gz\": {\n        \"sha256\": \"7083ad8d427ac6493cc5d9372a97ceb25992196397705abb738247164cd83477\",\n        \"size\": 189005659\n    },\n    \"NoScenario_Town12_Route23968_Weather14.tar.gz\": {\n        \"sha256\": \"3d59b6861641b2bab343a1f63b6f7a8cb217a59b7faf1fc756b7e0eb71f10cc8\",\n        \"size\": 206307198\n    },\n    \"NoScenario_Town12_Route23971_Weather19.tar.gz\": {\n        \"sha256\": \"5699988c9e8d56deb52fc05ee1840055a4300ab625f9d5ea0cfa73418c11a84f\",\n        \"size\": 264861530\n    },\n    \"NoScenario_Town12_Route23972_Weather20.tar.gz\": {\n        \"sha256\": \"b953ee2c28eeddd55c9ccb94b4ade7e09531663cb286dca30b8376af9bbd1b3f\",\n        \"size\": 270454943\n    },\n    \"NoScenario_Town12_Route23973_Weather21.tar.gz\": {\n        \"sha256\": \"2b65560a72c2e9fb639bcb7cb1fa936c8578aae8daa5ebad974bd35e44e4dde1\",\n        \"size\": 185342977\n    },\n    \"NoScenario_Town12_Route23974_Weather22.tar.gz\": {\n        \"sha256\": \"59de0d015bdeb90c7147de2be8c48eb1dc1c82de51c2322bfea8e4986ac176d7\",\n        \"size\": 191186190\n    },\n    \"NoScenario_Town12_Route23979_Weather1.tar.gz\": {\n        \"sha256\": \"afceed10604752ffe51f1dccf2e8beac930cb4769987cf3ba8090ea2bdfe3a2f\",\n        \"size\": 259978060\n    },\n    \"NoScenario_Town12_Route23980_Weather2.tar.gz\": {\n        \"sha256\": \"fb08983fa3da198c4995a764c63ca3ad882944252cd9bfcd87ad293e5b80544c\",\n        \"size\": 250061707\n    },\n    \"NoScenario_Town12_Route23981_Weather3.tar.gz\": {\n        \"sha256\": \"ca5f4bdd86157c67c083bab80da1980adbab30f4e35b0732fc1e4d37314de62e\",\n        \"size\": 232471081\n    },\n    \"NoScenario_Town12_Route23982_Weather5.tar.gz\": {\n        \"sha256\": \"2569c7be1fdb4d44c494af094d8f43f6ce0bae09e9554cf1837319d83165e034\",\n        \"size\": 237138673\n    },\n    \"NoScenario_Town12_Route23983_Weather6.tar.gz\": {\n        \"sha256\": \"8775965140be2d0ace3eb54a7a50f5841917a0338b9a37161337ac261afe5e51\",\n        \"size\": 191614766\n    },\n    \"NoScenario_Town12_Route23984_Weather7.tar.gz\": {\n        \"sha256\": \"fe8eeb9df5cad586e437737d9e8a919dd418672380fd29e1c417ddcb0999d535\",\n        \"size\": 325029887\n    },\n    \"NoScenario_Town12_Route23985_Weather8.tar.gz\": {\n        \"sha256\": \"d48ab0ac15f823dfb8478e4c384907ef2c6af7387fe3174184a82fe2adb75a74\",\n        \"size\": 187754860\n    },\n    \"NoScenario_Town12_Route23988_Weather11.tar.gz\": {\n        \"sha256\": \"573c3148a633d104514deb335777adab6d4b764c689c8d69f87ad1e8bab49671\",\n        \"size\": 245864627\n    },\n    \"NoScenario_Town12_Route23990_Weather13.tar.gz\": {\n        \"sha256\": \"33abdefdbdfdcf8a67bfd3feaab44c6ebea84d3b4ec8b6b27fe28c30e95d4c4b\",\n        \"size\": 254049715\n    },\n    \"NoScenario_Town12_Route23991_Weather14.tar.gz\": {\n        \"sha256\": \"e9845e46fb98236f55fb0aaf03fe14122004160e04ae02da3e09c12a42e9a4ff\",\n        \"size\": 336489742\n    },\n    \"NoScenario_Town12_Route23993_Weather18.tar.gz\": {\n        \"sha256\": \"b8dcb772270de3f20ec48c8a9e3868068db055a552ac5c27983c34d83822c6f9\",\n        \"size\": 322687666\n    },\n    \"NoScenario_Town12_Route23995_Weather20.tar.gz\": {\n        \"sha256\": \"05119a5dfebabe3d92efa6203622043a40ee51f9fb1b56db5f7b86e0a46a5a2a\",\n        \"size\": 264391984\n    },\n    \"NoScenario_Town12_Route23999_Weather25.tar.gz\": {\n        \"sha256\": \"ab1d0185f6333949c65597f9c08169aa77ce132348a41bb34808a2c431d4b9cd\",\n        \"size\": 276200293\n    },\n    \"NoScenario_Town12_Route24002_Weather1.tar.gz\": {\n        \"sha256\": \"f28679b4bd5132c22011cfc074013d4b4b88f7bfb578206cc78b1d1aef4b06f9\",\n        \"size\": 260672881\n    },\n    \"NoScenario_Town12_Route24006_Weather6.tar.gz\": {\n        \"sha256\": \"3a183a78f8f0c7846a1d785b7a4797ee9ddcca62f9b0a0a36cc87ed6cc4bef9f\",\n        \"size\": 283918848\n    },\n    \"NoScenario_Town12_Route24007_Weather7.tar.gz\": {\n        \"sha256\": \"082f49bc8f4db7aad13d6cd29b4591a98cdba8c9da710a8d217e9036236a5219\",\n        \"size\": 155195119\n    },\n    \"NoScenario_Town12_Route24008_Weather8.tar.gz\": {\n        \"sha256\": \"83af8939e48147beddcd196dda04e878773e43dd029fd0de02f01889ce462673\",\n        \"size\": 137406011\n    },\n    \"NoScenario_Town12_Route24121_Weather6.tar.gz\": {\n        \"sha256\": \"86ad2d57967e2e7d6645a2514d2ee4f9a9e1d48cab64944a64cec02956e48147\",\n        \"size\": 242873949\n    },\n    \"NoScenario_Town12_Route24122_Weather7.tar.gz\": {\n        \"sha256\": \"09d27b1f7f1364017175f1585837212c3144c1b70bad8b102a517ed0d2bd0f3d\",\n        \"size\": 257318937\n    },\n    \"NoScenario_Town12_Route24125_Weather10.tar.gz\": {\n        \"sha256\": \"d102d3dee9989f20fdda8861944db420faf08e1f9211d11e55b923bee0111ed2\",\n        \"size\": 253734222\n    },\n    \"NoScenario_Town12_Route24128_Weather13.tar.gz\": {\n        \"sha256\": \"c0ba5f865bacbfb8915b2bd59652e1e482b2c386359aea2ccc369a04aff1cb38\",\n        \"size\": 257354784\n    },\n    \"NoScenario_Town12_Route24129_Weather14.tar.gz\": {\n        \"sha256\": \"894add4bf38d636fdb5467a54440583fa6ad90b1245aff7b3005e10aed7d088c\",\n        \"size\": 274719206\n    },\n    \"NoScenario_Town12_Route24130_Weather15.tar.gz\": {\n        \"sha256\": \"05e09433c7b615a51591ea770919a9d27a2bdab980125fc1442d9430c044ec92\",\n        \"size\": 284093336\n    },\n    \"NoScenario_Town12_Route24131_Weather18.tar.gz\": {\n        \"sha256\": \"3afec781ff96782423d7328a24f4788d1abf9a91dbfa689abb7c524dc7923b80\",\n        \"size\": 302847246\n    },\n    \"NoScenario_Town12_Route24132_Weather19.tar.gz\": {\n        \"sha256\": \"18b0e3f1b3b5db17a30d0b098634fd1dc64d551045f10397eea76bdd249f7f11\",\n        \"size\": 256988638\n    },\n    \"NoScenario_Town12_Route24140_Weather1.tar.gz\": {\n        \"sha256\": \"8efb61d33e66bdc7e8601aac859f856d0f38a32c3b916b09dd014207760e9729\",\n        \"size\": 262361564\n    },\n    \"NoScenario_Town12_Route24142_Weather3.tar.gz\": {\n        \"sha256\": \"3f58935b7a475c5592750b81c413c8ba03619fcd13921df8ab05ab3718b32332\",\n        \"size\": 262201294\n    },\n    \"NoScenario_Town12_Route24144_Weather6.tar.gz\": {\n        \"sha256\": \"d5630dacf1c5471c6c65b4447b8079a790732d56a9fb9459efa4474a1d7b4a71\",\n        \"size\": 185486745\n    },\n    \"NoScenario_Town12_Route24150_Weather12.tar.gz\": {\n        \"sha256\": \"4c0aad5b65ca039670707bc5e9dff3abda9b31f8c4876a46cba5e93973dc96e6\",\n        \"size\": 168543614\n    },\n    \"NoScenario_Town12_Route24152_Weather14.tar.gz\": {\n        \"sha256\": \"caa2cb3994998ed4254c9747a1c3d274584f43f30ba67b6fb0752d01e16169df\",\n        \"size\": 175211512\n    },\n    \"NoScenario_Town12_Route24153_Weather15.tar.gz\": {\n        \"sha256\": \"e5b712792c1cd0642341c8b1ac2c5cb25a97308978da237a17ad8470474e6586\",\n        \"size\": 134493310\n    },\n    \"NoScenario_Town12_Route24154_Weather18.tar.gz\": {\n        \"sha256\": \"d3f54b5d84423db6ba448938c163580c545d5785850e644d96314c89e37752b2\",\n        \"size\": 151796605\n    },\n    \"NoScenario_Town12_Route24155_Weather19.tar.gz\": {\n        \"sha256\": \"93fea10b7b7da7060c47a190516cee77527dbf155f0f893dd712afd7e37016b1\",\n        \"size\": 193192896\n    },\n    \"NoScenario_Town12_Route24156_Weather20.tar.gz\": {\n        \"sha256\": \"f30be2b5ca41c95353abab58239f68b2791eb927a1ac999828c72cdc6f8aab9c\",\n        \"size\": 199857559\n    },\n    \"NoScenario_Town12_Route24159_Weather23.tar.gz\": {\n        \"sha256\": \"1bc1ceb5d65cf1e9290408ed5e2a36d90de5d998275a6baae8e1b94cb953062f\",\n        \"size\": 265587095\n    },\n    \"NoScenario_Town12_Route24160_Weather25.tar.gz\": {\n        \"sha256\": \"5da4f54f0577ea95ba05f2ea437486a14d5ba4c514e75a6f57077245653f1fe2\",\n        \"size\": 252874300\n    },\n    \"NoScenario_Town12_Route24166_Weather5.tar.gz\": {\n        \"sha256\": \"215c6040905f32c78a2a8b7d695ba7e2be54357c9b2d19d925d4c7790165d45f\",\n        \"size\": 341255883\n    },\n    \"NoScenario_Town12_Route24167_Weather6.tar.gz\": {\n        \"sha256\": \"093911fe970feea5e00768e326dde8b80ee636ddeb14f0bcd93fc51e0f05ed1d\",\n        \"size\": 241546304\n    },\n    \"NoScenario_Town12_Route24168_Weather7.tar.gz\": {\n        \"sha256\": \"493f5dd600eabd9bdf325355318ed34358df471ce80557f9e3440fdd6a39dea3\",\n        \"size\": 260741877\n    },\n    \"NoScenario_Town12_Route24169_Weather8.tar.gz\": {\n        \"sha256\": \"12dbb1278b937ab2caf3b4c1e2c5cc2007d340d1357d5cf6c5b5ee520f9a0fb5\",\n        \"size\": 225176308\n    },\n    \"NoScenario_Town12_Route24170_Weather9.tar.gz\": {\n        \"sha256\": \"38399151c88224445930c6384becdf5dc7bf2232da70f170466e0102f699c294\",\n        \"size\": 207041062\n    },\n    \"NoScenario_Town12_Route24171_Weather10.tar.gz\": {\n        \"sha256\": \"dfda450ec34175b1f003da175783c957dec0ea17e6b3a6dee38692da057e0d3f\",\n        \"size\": 177887838\n    },\n    \"NoScenario_Town12_Route24172_Weather11.tar.gz\": {\n        \"sha256\": \"0bfdd568a979e6bb79642efebd4b4c48cbe90d6b9c470bee243e229f00fb770a\",\n        \"size\": 258209432\n    },\n    \"NoScenario_Town12_Route24173_Weather12.tar.gz\": {\n        \"sha256\": \"d5310ba6dd46dffaaf3c60356ea6287bf2ee3366504f9c41b7a57e11c9189ff0\",\n        \"size\": 173171570\n    },\n    \"NoScenario_Town12_Route24174_Weather13.tar.gz\": {\n        \"sha256\": \"aafceb1475ba7f7f4db1506680e52c4aa375e6e33456c7ea7b194c01b1b1e083\",\n        \"size\": 267643411\n    },\n    \"NoScenario_Town12_Route24176_Weather15.tar.gz\": {\n        \"sha256\": \"6578e9d4809f43ff9776ee2efe11f30b544cc82e47e66bae37b399b60328a138\",\n        \"size\": 280417148\n    },\n    \"NoScenario_Town12_Route24178_Weather19.tar.gz\": {\n        \"sha256\": \"0425cea71d13d0de3d570d82a313110a0e1bb1f43ee07fa65582f5054d45456a\",\n        \"size\": 238921596\n    },\n    \"NoScenario_Town12_Route24180_Weather21.tar.gz\": {\n        \"sha256\": \"c26af4f6e5df79c5583f6f7c01fb7652e560eacab57621fead8e659c0089bfa2\",\n        \"size\": 345769715\n    },\n    \"NoScenario_Town12_Route24181_Weather22.tar.gz\": {\n        \"sha256\": \"a25ebcf2664226d3f35dbea5fbb1f8b1cadab31028dab94fafb718aa395cc2fb\",\n        \"size\": 264922778\n    },\n    \"NoScenario_Town12_Route24183_Weather25.tar.gz\": {\n        \"sha256\": \"3202952f3031305b4d5f4e7c32130f95776889dc4089779fc600d9c0bac17d17\",\n        \"size\": 269752439\n    },\n    \"NoScenario_Town12_Route24186_Weather1.tar.gz\": {\n        \"sha256\": \"b8c856d23f469e646fbf26a2809198fb15093543ad9eb6e06ebc4ff5f1540c91\",\n        \"size\": 241025330\n    },\n    \"NoScenario_Town12_Route24187_Weather2.tar.gz\": {\n        \"sha256\": \"385040a5b34e551f4e391f7dec1a3a1b00513d9b4d9e490ccc291e0f9eab8e0a\",\n        \"size\": 329165720\n    },\n    \"NoScenario_Town12_Route24188_Weather3.tar.gz\": {\n        \"sha256\": \"91374dcb70b49312fe84fdba12a22fa4fedf9daf0feadc2b459ede9615cea7fe\",\n        \"size\": 307563483\n    },\n    \"NoScenario_Town12_Route24189_Weather5.tar.gz\": {\n        \"sha256\": \"6210baf25900d31a988cc50208b2e8e4d5691c8e09e0593b4c0e01d7fe4d339f\",\n        \"size\": 250048084\n    },\n    \"NoScenario_Town12_Route24190_Weather6.tar.gz\": {\n        \"sha256\": \"84dc15fb2108c9a21d0a21fcea390f4b1b3e638fdca5839c83fa9a357cb46567\",\n        \"size\": 245498646\n    },\n    \"NoScenario_Town12_Route24191_Weather7.tar.gz\": {\n        \"sha256\": \"9628bd4a61918196eb1c19cc00976886120bd4abcd831171e9288179656ac31e\",\n        \"size\": 226741701\n    },\n    \"NoScenario_Town12_Route24192_Weather8.tar.gz\": {\n        \"sha256\": \"d512d26ba41893e3f9abb89d8496d96c50eacace4b8cb0481420cfc8792e725e\",\n        \"size\": 206941077\n    },\n    \"NoScenario_Town12_Route24195_Weather11.tar.gz\": {\n        \"sha256\": \"b2e4a63fb503eb97505b3801c8ae886743edce185653063c656a43bdb61abbbb\",\n        \"size\": 123030199\n    },\n    \"NoScenario_Town12_Route24196_Weather12.tar.gz\": {\n        \"sha256\": \"45d73d7d7cc8983019b09da36dba331e04419c7b6bac0b23bba961c091ba501d\",\n        \"size\": 122945494\n    },\n    \"NoScenario_Town12_Route2483_Weather7.tar.gz\": {\n        \"sha256\": \"ed442e0bcc8649bbedd222b91fb83f9bab49e56c80d20b5d68c5fb46a5b5d4a9\",\n        \"size\": 1823440635\n    },\n    \"NoScenario_Town12_Route2798_Weather10.tar.gz\": {\n        \"sha256\": \"fb9289f3972efb71196e0b2196d45063f9275af241caf6788e7733f99cd587b5\",\n        \"size\": 225639856\n    },\n    \"NoScenario_Town12_Route28248_Weather8.tar.gz\": {\n        \"sha256\": \"9f58dfb19b34bddbd367dec1978e7f6f507bbf8d0605eb5044062ef193400da9\",\n        \"size\": 233509829\n    },\n    \"NoScenario_Town12_Route2910_Weather18.tar.gz\": {\n        \"sha256\": \"e9ffe4848fa6e8bee71a6ee6b4959a71e8cae0f56180e8b4ad9171a17ee89028\",\n        \"size\": 191720380\n    },\n    \"NoScenario_Town12_Route2917_Weather25.tar.gz\": {\n        \"sha256\": \"bbdf109eb48f221d84ed82062a0f93ff801d46169ff8a52560e224e696951714\",\n        \"size\": 146931903\n    },\n    \"NoScenario_Town12_Route2919_Weather1.tar.gz\": {\n        \"sha256\": \"476548244ebc8b5d55eac2e097fc3f73b644178302164656d9bb0d3fee9a7db8\",\n        \"size\": 177212963\n    },\n    \"NoScenario_Town12_Route35367_Weather0.tar.gz\": {\n        \"sha256\": \"8ee89a4dd157726644001fdace10251bb6aa766172d6f7f5a7bb2425aed73197\",\n        \"size\": 435790475\n    },\n    \"NoScenario_Town12_Route35383_Weather0.tar.gz\": {\n        \"sha256\": \"31337a0c1ba56b07b0d456f9fda45753a08d83f05d1b01d02ea13d518eca3b54\",\n        \"size\": 515915958\n    },\n    \"NoScenario_Town12_Route35388_Weather0.tar.gz\": {\n        \"sha256\": \"236a54a5946bb819100ca91f4d54a6d6f279de206f0df1d2fcaa9c37692689f5\",\n        \"size\": 132574036\n    },\n    \"NoScenario_Town12_Route35412_Weather0.tar.gz\": {\n        \"sha256\": \"107df550981d41168c32ae2a0cd6e2b04bf96495073b27936be2b8b8371ea719\",\n        \"size\": 127985166\n    },\n    \"NoScenario_Town12_Route35547_Weather3.tar.gz\": {\n        \"sha256\": \"fe7a929918c3607c9a39f0ba7a5032e7e043df5fe9f15bd27fbf42318f913e57\",\n        \"size\": 429600593\n    },\n    \"NoScenario_Town12_Route35598_Weather3.tar.gz\": {\n        \"sha256\": \"ac16fa151a1a2fe7e1431d139496548c68198018aaf94cd9103a1b581146b773\",\n        \"size\": 424013909\n    },\n    \"NoScenario_Town12_Route36567_Weather23.tar.gz\": {\n        \"sha256\": \"a3b418d5fc5e44de5bd32e7d2fd5018feda8322184b0c0d808031687b1526213\",\n        \"size\": 374184892\n    },\n    \"NoScenario_Town12_Route36588_Weather23.tar.gz\": {\n        \"sha256\": \"8638a5cccfd3173d48c4d772688457f850f606b0455ba0907c19a52da657c3ec\",\n        \"size\": 121325259\n    },\n    \"NoScenario_Town12_Route36604_Weather23.tar.gz\": {\n        \"sha256\": \"cddc39b1ffb4d18f7cd0c4ff6264a825ab9e150e44de1a5298c07cb6661f40d5\",\n        \"size\": 454372660\n    },\n    \"NoScenario_Town12_Route4044_Weather9.tar.gz\": {\n        \"sha256\": \"cda29dd5f146c5d34443b541cee219768f78baf7b21c4384a9d564e34c46bc65\",\n        \"size\": 204155793\n    },\n    \"NoScenario_Town12_Route4134_Weather3.tar.gz\": {\n        \"sha256\": \"cb4a8f51c69f13038c2884a1a4e0501c4a181fa70cc17743b8d32fe52244af5b\",\n        \"size\": 231941074\n    },\n    \"NoScenario_Town12_Route4237_Weather2.tar.gz\": {\n        \"sha256\": \"36be63734b21922ce13ece0c97e1cb0cf1e0097d5e424f383d561bdb6c548846\",\n        \"size\": 248662366\n    },\n    \"NoScenario_Town12_Route4337_Weather23.tar.gz\": {\n        \"sha256\": \"9bf033edac684d8934569a7a7d6502f48f98b18626691f5413c585a4095f0bbd\",\n        \"size\": 244527454\n    },\n    \"NoScenario_Town12_Route4515_Weather20.tar.gz\": {\n        \"sha256\": \"edec3efa37aea9f06da4850ef6c7afecd69ef581cf2fbd10879f111b246ab40a\",\n        \"size\": 254558183\n    },\n    \"NoScenario_Town12_Route4592_Weather19.tar.gz\": {\n        \"sha256\": \"035bf0312d21ff04c25e1d943d9015476a39ec2c51170742a7cdce73db46b31f\",\n        \"size\": 205237011\n    },\n    \"NoScenario_Town12_Route4599_Weather0.tar.gz\": {\n        \"sha256\": \"40b79b8e8d843d0a35d2692b69286fa83d42b3f7fd64d0c669f4aec54de0baf0\",\n        \"size\": 304161235\n    },\n    \"NoScenario_Town12_Route4708_Weather5.tar.gz\": {\n        \"sha256\": \"15d2a804960630961200d7609a2cc0b57092ed3da3abb50b90f3413ea5139a18\",\n        \"size\": 285918499\n    },\n    \"NoScenario_Town12_Route4733_Weather3.tar.gz\": {\n        \"sha256\": \"b80205da9609d32263fcc7a2dfc8fd11065999cc987a3bdca5b0f8f7429eebd1\",\n        \"size\": 224278400\n    },\n    \"NoScenario_Town12_Route4749_Weather20.tar.gz\": {\n        \"sha256\": \"38a26c45124c20cf2bb519e3da9180dbf3bb8c5dcee85d6b6074b75236bc44d9\",\n        \"size\": 174378297\n    },\n    \"NoScenario_Town12_Route4816_Weather9.tar.gz\": {\n        \"sha256\": \"9a425ae7bb570be1791de0b7d335122fee1a6f834087fdd7ea98377849806f77\",\n        \"size\": 129778246\n    },\n    \"NoScenario_Town12_Route4899_Weather14.tar.gz\": {\n        \"sha256\": \"565903e5870854aa5543ae1e0c8b7ead15866fcd6c0b3ac9666bdf33c3062f8d\",\n        \"size\": 194003853\n    },\n    \"NoScenario_Town12_Route4912_Weather1.tar.gz\": {\n        \"sha256\": \"03454ed2b8c8f91461d10fe6593f85b5e33e6c890a304528efadb387c2608c0b\",\n        \"size\": 178234984\n    },\n    \"NoScenario_Town12_Route5944_Weather19.tar.gz\": {\n        \"sha256\": \"e15da199dea3c3eb1555bc78cce40a9ad904819f6bf048cd74ce3ba3298a7b05\",\n        \"size\": 206736609\n    },\n    \"NoScenario_Town12_Route5969_Weather18.tar.gz\": {\n        \"sha256\": \"371e1dfab294d22b534fd9e680ccf282c463789e1c525fe0bf2656e6d8dea100\",\n        \"size\": 732182515\n    },\n    \"NoScenario_Town12_Route5982_Weather5.tar.gz\": {\n        \"sha256\": \"5d79549db9d6ca4aeed341201535ea77595dc72d0e383193eda90cf5f08e5be6\",\n        \"size\": 108611507\n    },\n    \"NoScenario_Town12_Route6054_Weather25.tar.gz\": {\n        \"sha256\": \"af5d8dd66990ecb409269e61dbc4c821f6304a1c24b40f14b5bfe48bd5adb3ed\",\n        \"size\": 490451420\n    },\n    \"NoScenario_Town12_Route6073_Weather18.tar.gz\": {\n        \"sha256\": \"d7c611bc50089de7374eff41a1b394a6916b1a5696a8053e1550a40397d72cbd\",\n        \"size\": 539376094\n    },\n    \"NoScenario_Town12_Route6077_Weather22.tar.gz\": {\n        \"sha256\": \"27fddb1df45349d8dd57bf1a01cd00ab2ba3dee3bdb8fcc8fc8a11605791dbe2\",\n        \"size\": 222080890\n    },\n    \"NoScenario_Town12_Route6083_Weather2.tar.gz\": {\n        \"sha256\": \"b2cdc9457160f863d80fb39f6b482af903ab0f2a07e2507c65c96f4832397543\",\n        \"size\": 144563794\n    },\n    \"NoScenario_Town12_Route6110_Weather3.tar.gz\": {\n        \"sha256\": \"3e6d746b33de2ab7ad818066c07ff4751e798e42a325e52eb585d6f16b876183\",\n        \"size\": 216454324\n    },\n    \"NoScenario_Town12_Route6164_Weather5.tar.gz\": {\n        \"sha256\": \"92dc05fbe012274ffcda1ff33a7705de08b1635c7f2bcb197628992e7e025793\",\n        \"size\": 187213055\n    },\n    \"NoScenario_Town12_Route6226_Weather15.tar.gz\": {\n        \"sha256\": \"94661714eae7598be6b1a4afcc87ddd94e5604084e563e1f8b8acacac0e5ab7e\",\n        \"size\": 340314574\n    },\n    \"NoScenario_Town12_Route6239_Weather2.tar.gz\": {\n        \"sha256\": \"a534055e70741ddeda9b77406b57cc22e6755108a67b55afa22b3cf5b92451a0\",\n        \"size\": 170915973\n    },\n    \"NoScenario_Town12_Route6284_Weather21.tar.gz\": {\n        \"sha256\": \"a331276ae7456a6a05ecf274a8efa90bd5e38846bafb17e96e2f11b0e1d1c68c\",\n        \"size\": 98358356\n    },\n    \"NoScenario_Town12_Route6316_Weather1.tar.gz\": {\n        \"sha256\": \"60662efc28e70702cdc3e8f982acb5449915a594c67609338c2061e4b250b1a7\",\n        \"size\": 520616949\n    },\n    \"NoScenario_Town12_Route6368_Weather1.tar.gz\": {\n        \"sha256\": \"6b14cfed1470d1524475736d462a8d47fd994033de01de3f7dbd80b2e73c22c2\",\n        \"size\": 108723963\n    },\n    \"NoScenario_Town12_Route6384_Weather9.tar.gz\": {\n        \"sha256\": \"7340b3ca7e37d672e2542b8216a295e5a010796746935e81319e12f2f1ecad46\",\n        \"size\": 153540227\n    },\n    \"NoScenario_Town12_Route6400_Weather7.tar.gz\": {\n        \"sha256\": \"975490c31b9cb3b746ddde657472d3bcfe3f0f9d422533c0633fdb38bde528e1\",\n        \"size\": 273859311\n    },\n    \"NoScenario_Town12_Route6461_Weather8.tar.gz\": {\n        \"sha256\": \"4ba844968b548f1e85091dc406fcecb60d764f66836cd7ecca1d5ef0084a1a22\",\n        \"size\": 81480161\n    },\n    \"NoScenario_Town12_Route6466_Weather21.tar.gz\": {\n        \"sha256\": \"82d03b2d485596ef4721a1798128ff21869ffeceb97c0bfd06d6dc6a38ab91bd\",\n        \"size\": 305811434\n    },\n    \"NoScenario_Town12_Route6474_Weather3.tar.gz\": {\n        \"sha256\": \"b175ca600556e0dcd1b6361cddc4ecafc23a52207da988347a60668da46a6542\",\n        \"size\": 413404980\n    },\n    \"NoScenario_Town12_Route6531_Weather8.tar.gz\": {\n        \"sha256\": \"1afd6f75943d04c0eaed5ead14bc5b13e0b185ac69eb542755003d0fe15fc92d\",\n        \"size\": 545222045\n    },\n    \"NoScenario_Town12_Route6619_Weather18.tar.gz\": {\n        \"sha256\": \"a15971fa75d97f0e7f61216bc04c3ea26d24a87d9f538ae542f18b567f984b0b\",\n        \"size\": 106348010\n    },\n    \"NoScenario_Town12_Route6680_Weather1.tar.gz\": {\n        \"sha256\": \"2c4a4f23198ae0e96689da0218ae3abdaeefd50bec44048cdd96a3c69dcf5dfd\",\n        \"size\": 201681401\n    },\n    \"NoScenario_Town12_Route6719_Weather14.tar.gz\": {\n        \"sha256\": \"8899d34fa23f15bd6b033fb567fc425073a7b749b324cd9f7fb4ffcf0bf9f13e\",\n        \"size\": 419687817\n    },\n    \"NoScenario_Town12_Route6768_Weather11.tar.gz\": {\n        \"sha256\": \"345cfd954ed1b8b87e34f224559ece2fb9607724efaa3a1667d39d710c63ef82\",\n        \"size\": 259637989\n    },\n    \"NoScenario_Town12_Route6791_Weather8.tar.gz\": {\n        \"sha256\": \"7dbada6fda92d2033f3bbed2f425230a49fa02b3f73ad6d0f47ad15de6b917d2\",\n        \"size\": 537488940\n    },\n    \"NoScenario_Town12_Route6796_Weather13.tar.gz\": {\n        \"sha256\": \"1e935782f34bc765b8eb4485ca346d1d18f1de3139f25b8210a3de8a773dac14\",\n        \"size\": 317177407\n    },\n    \"NoScenario_Town12_Route6820_Weather11.tar.gz\": {\n        \"sha256\": \"d420ead570f6def4971d863fa848cc0feb9988791944e076b63d1dbc5606e416\",\n        \"size\": 479939214\n    },\n    \"NoScenario_Town12_Route8775_Weather8.tar.gz\": {\n        \"sha256\": \"23982e866d414f881446e236092c3770e373ba77509aabc99b6173d643bfff36\",\n        \"size\": 174458427\n    },\n    \"NoScenario_Town12_Route8858_Weather21.tar.gz\": {\n        \"sha256\": \"5522fce04a329bc1112447f13cd67c89bf29d310998147cbe5163c4bafbd157a\",\n        \"size\": 146029060\n    },\n    \"NoScenario_Town12_Route9012_Weather19.tar.gz\": {\n        \"sha256\": \"91853ad13286b081274367783ed4150c28bab70e69383ceb255822441d0311ee\",\n        \"size\": 159650447\n    },\n    \"NoScenario_Town12_Route9346_Weather15.tar.gz\": {\n        \"sha256\": \"3b896454d7540785812b12216b73249151e9b096fb0f66fa5f22c1323d226c58\",\n        \"size\": 135636626\n    },\n    \"NoScenario_Town12_Route9598_Weather7.tar.gz\": {\n        \"sha256\": \"1beeb0c208c116542706bbb538e6569f33b7759479278530c75a6d1dcc179bbf\",\n        \"size\": 324096751\n    },\n    \"NoScenario_Town13_Route23688_Weather10.tar.gz\": {\n        \"sha256\": \"0cc114aaf33c5fd9800f30b7a36431141feccf40273322eb6f9fe67d094d3510\",\n        \"size\": 180429004\n    },\n    \"NoScenario_Town13_Route23690_Weather12.tar.gz\": {\n        \"sha256\": \"4115c59b2f121c1ad43f4638aacaaea98004ea6d2c6fb237209d64f78afddca3\",\n        \"size\": 183633709\n    },\n    \"NoScenario_Town13_Route23705_Weather3.tar.gz\": {\n        \"sha256\": \"cf2329b0eed0e0e8e76048af7db27db357dae1882790edd808be281f3946052d\",\n        \"size\": 186390551\n    },\n    \"NoScenario_Town13_Route23707_Weather6.tar.gz\": {\n        \"sha256\": \"5315a0be25179fd64c8e4a33ad5912650cda6750b4e783c8affcdbaa66a23e04\",\n        \"size\": 672868700\n    },\n    \"NoScenario_Town13_Route23709_Weather8.tar.gz\": {\n        \"sha256\": \"92fdd4cb54a06f74331130bdc11382b263f6a308a63ca9353ca7f1ad58ca80e3\",\n        \"size\": 654690397\n    },\n    \"NoScenario_Town13_Route23718_Weather19.tar.gz\": {\n        \"sha256\": \"cb3cbafcd1b08588b3d1b2fca189bb9e8103acee02badee9f7f122f689ee4f0d\",\n        \"size\": 485608458\n    },\n    \"NoScenario_Town13_Route23729_Weather5.tar.gz\": {\n        \"sha256\": \"8dee86cdba86a9185580725cb64d8300294378b8ab9d48892cd8f5c68603fdb5\",\n        \"size\": 192708722\n    },\n    \"NoScenario_Town13_Route23732_Weather8.tar.gz\": {\n        \"sha256\": \"7bb43884f748429e7dc5b1b4a832ec57e1e517b18b569ce00e22cb4b4be39207\",\n        \"size\": 204125765\n    },\n    \"NoScenario_Town13_Route23733_Weather9.tar.gz\": {\n        \"sha256\": \"7927a8a2ee7994924689d320960710e8507857772f101d450de8d8e9f2c65034\",\n        \"size\": 546650756\n    },\n    \"NoScenario_Town13_Route23737_Weather13.tar.gz\": {\n        \"sha256\": \"cdd1f52580c59df75d3203bfdf5bb5bc003d020f5dcd82674b9f1f68f87e6856\",\n        \"size\": 531095831\n    },\n    \"NoScenario_Town13_Route23743_Weather21.tar.gz\": {\n        \"sha256\": \"3eb04da9674f45ce7b4f1755fc375f3381064f9bbd1806344054d53d5150e52f\",\n        \"size\": 507355910\n    },\n    \"NoScenario_Town13_Route23744_Weather22.tar.gz\": {\n        \"sha256\": \"cdfb01ada941d788f05dc5fba7651fa04fa7aec39ad1b687a29a8d45cd205c35\",\n        \"size\": 483833852\n    },\n    \"NoScenario_Town13_Route23750_Weather2.tar.gz\": {\n        \"sha256\": \"d611c142102962672f7d21b768100d572ff547066c3a6909e325d34aff25688e\",\n        \"size\": 339477571\n    },\n    \"NoScenario_Town13_Route23757_Weather10.tar.gz\": {\n        \"sha256\": \"f0cfdb5cb962358e94308b2d5d309db8bd12cd1ce65a3d95396f70490b5db719\",\n        \"size\": 506895321\n    },\n    \"NoScenario_Town13_Route23759_Weather12.tar.gz\": {\n        \"sha256\": \"a5c4bdf7deda4580f8acff7befb332dfd332e5d0071bd5541d8851c461bbd5e8\",\n        \"size\": 484778560\n    },\n    \"NoScenario_Town13_Route23763_Weather18.tar.gz\": {\n        \"sha256\": \"9b9553f40e64eef30917be19df38aa10eda17d616441aaa8b0cf4423cc436f44\",\n        \"size\": 495409340\n    },\n    \"NoScenario_Town13_Route23765_Weather20.tar.gz\": {\n        \"sha256\": \"096b6ee85a426f7dd980c2bcfbcbb6c659f227b2bd1e02daffc05297949513a3\",\n        \"size\": 428728410\n    },\n    \"NoScenario_Town13_Route23769_Weather25.tar.gz\": {\n        \"sha256\": \"d5af51a77263bdfbd0d244f2d76a71e6d30d06b9625216bc0ddbab8689d34902\",\n        \"size\": 464829290\n    },\n    \"NoScenario_Town13_Route23773_Weather2.tar.gz\": {\n        \"sha256\": \"992b6fc10614819ba4a86bfb7d61f2a251344d31290c9177caf1f7f86c889837\",\n        \"size\": 586597587\n    },\n    \"NoScenario_Town13_Route23775_Weather5.tar.gz\": {\n        \"sha256\": \"3c9198b49ccfb9124a0161f011d259457adc1f564b267d3726c1cdd7c61ae5fd\",\n        \"size\": 565311920\n    },\n    \"NoScenario_Town13_Route23799_Weather6.tar.gz\": {\n        \"sha256\": \"b76a5fbe66a34185196c67c4f36265d94c7d77f61c9089c7820228c670eb008f\",\n        \"size\": 520666580\n    },\n    \"NoScenario_Town13_Route23801_Weather8.tar.gz\": {\n        \"sha256\": \"c2707e12f37aab37e20b41d936206224027ae14af752010868384053171a1707\",\n        \"size\": 495762585\n    },\n    \"NoScenario_Town13_Route23876_Weather14.tar.gz\": {\n        \"sha256\": \"af2994bc9e86db53ca2ee714d94020d0d4591961cc9ff4332dd3a7b98f2a837e\",\n        \"size\": 184911590\n    },\n    \"NoScenario_Town13_Route23878_Weather18.tar.gz\": {\n        \"sha256\": \"80f453e9c162148488159478f98a038744da0c0db0af3d38508ecb30230a9d94\",\n        \"size\": 202447093\n    },\n    \"NoScenario_Town13_Route23897_Weather12.tar.gz\": {\n        \"sha256\": \"6914c1f64af53de8f8c549ea7e0fe2581fff58bd10430f5c55381b7702d6ec8b\",\n        \"size\": 622467273\n    },\n    \"NoScenario_Town13_Route23911_Weather2.tar.gz\": {\n        \"sha256\": \"10146e31de12a731bf63220e474b661cc1d8eb5dd01bfb5fa0efaccfc1e40377\",\n        \"size\": 532503341\n    },\n    \"NoScenario_Town13_Route23912_Weather3.tar.gz\": {\n        \"sha256\": \"fd4e33be3e6af4b3a4e2ca01b2a5ba6958fd4293a7e858ebd56e01487bd1e5ae\",\n        \"size\": 487705835\n    },\n    \"NoScenario_Town13_Route23917_Weather9.tar.gz\": {\n        \"sha256\": \"7bbeb2eaf2a8a58876504ae7b26d6752155474ff35dd37fa06c00d3578e0511e\",\n        \"size\": 165089757\n    },\n    \"NoScenario_Town13_Route23920_Weather12.tar.gz\": {\n        \"sha256\": \"0bc8b6349c9dfdc61e4dcac286bf6ba47315196ec29370429901730013c0f6b4\",\n        \"size\": 195961498\n    },\n    \"NoScenario_Town13_Route23925_Weather19.tar.gz\": {\n        \"sha256\": \"2a277405dbf31996f39ee7ae77dd89dc1bad1d05daba77c80dc1e43e8e1e7e24\",\n        \"size\": 580448435\n    },\n    \"NoScenario_Town13_Route23926_Weather20.tar.gz\": {\n        \"sha256\": \"f0ed080bdb14a344bc1ac8974a0b3b3765491b63afdff3de8cde2cb2ff567c56\",\n        \"size\": 562001586\n    },\n    \"NoScenario_Town13_Route23935_Weather3.tar.gz\": {\n        \"sha256\": \"0efed0e3222fa49f24fc0f02459b1f22e46636f2f667d1b30bb5a15823779dbd\",\n        \"size\": 318020125\n    },\n    \"NoScenario_Town13_Route23938_Weather7.tar.gz\": {\n        \"sha256\": \"d3752fbf538a1d46c958cf8b294a00c401762b9cb13c35f13fa37fe954d635be\",\n        \"size\": 343431040\n    },\n    \"NoScenario_Town13_Route23947_Weather18.tar.gz\": {\n        \"sha256\": \"48890995756b4d320716d1d6a910dd5904225e6173b4303f7bde4b16aa52f840\",\n        \"size\": 549755746\n    },\n    \"NoScenario_Town13_Route23951_Weather22.tar.gz\": {\n        \"sha256\": \"46eda12ca8ed684101437537e0137b02631afc8a2a0b5b04f5aec0c82ae98ec8\",\n        \"size\": 442698780\n    },\n    \"NoScenario_Town13_Route23953_Weather25.tar.gz\": {\n        \"sha256\": \"ef25d756e8e9257cc4f89df31d0927e0d4e49ab95113a31d8aec892877128158\",\n        \"size\": 432460086\n    },\n    \"NoScenario_Town13_Route23957_Weather2.tar.gz\": {\n        \"sha256\": \"1c6320a3281a80fc06e638fb163ba5e027c354d9884ed5612ee57700ab137a60\",\n        \"size\": 531746320\n    },\n    \"NoScenario_Town13_Route23961_Weather7.tar.gz\": {\n        \"sha256\": \"3092a42bbacb80680e98b119baedbdfe1a62213d754e5d9aef4d32b73b0bf18f\",\n        \"size\": 586723500\n    },\n    \"NoScenario_Town13_Route23987_Weather10.tar.gz\": {\n        \"sha256\": \"61089a2d12af992377ceeeb53efe3428f5e02e5380dae6bd1ac8a50332e073d3\",\n        \"size\": 506176621\n    },\n    \"NoScenario_Town13_Route23989_Weather12.tar.gz\": {\n        \"sha256\": \"42b0723d2dde2c6eeed4817854acb0e5dac7356673923601b642b1ec619464fa\",\n        \"size\": 474458522\n    },\n    \"NoScenario_Town13_Route24064_Weather20.tar.gz\": {\n        \"sha256\": \"09fd83adf39b35811cdc167687c289b1937945d749436717160b2774adcb3b6d\",\n        \"size\": 167345592\n    },\n    \"NoScenario_Town13_Route24066_Weather22.tar.gz\": {\n        \"sha256\": \"64b06a534cd0dbe6dcfb6c5c49322904ced100df98dc0045719419731f2af886\",\n        \"size\": 175640021\n    },\n    \"NoScenario_Town13_Route24082_Weather13.tar.gz\": {\n        \"sha256\": \"12996026eee841364bd56933613ee20ccaa79136ec54e916e057622fd55744b1\",\n        \"size\": 179584086\n    },\n    \"NoScenario_Town13_Route24083_Weather14.tar.gz\": {\n        \"sha256\": \"a2aaf1a656b268a4fd36d136e1b337743c8d57385438efd79da3dcecfc5a9b84\",\n        \"size\": 613480865\n    },\n    \"NoScenario_Town13_Route24085_Weather18.tar.gz\": {\n        \"sha256\": \"bab41cb98a4f85ebabfd24fcf47800259d5f87f14e11d7b012e855f195facd10\",\n        \"size\": 631264357\n    },\n    \"NoScenario_Town13_Route24094_Weather1.tar.gz\": {\n        \"sha256\": \"c9713bae54fe21313a8bf4ba67f8e9f02400d12ce3d23d2ac5c0b0d774409f18\",\n        \"size\": 572163906\n    },\n    \"NoScenario_Town13_Route24099_Weather7.tar.gz\": {\n        \"sha256\": \"428b43f489cc69afbecee98e311f509833c894e8b778955508054b363c7b4536\",\n        \"size\": 525258329\n    },\n    \"NoScenario_Town13_Route24105_Weather13.tar.gz\": {\n        \"sha256\": \"b2ef05bfd6518f585a5802b0aed343d996e006c61ca6b5c1101eb8dd66468b34\",\n        \"size\": 174971729\n    },\n    \"NoScenario_Town13_Route24108_Weather18.tar.gz\": {\n        \"sha256\": \"f140fc8603f429535fa1b37caec43673a58dd9a40c73b73b0998d45d841f8cbd\",\n        \"size\": 213171034\n    },\n    \"NoScenario_Town13_Route24109_Weather19.tar.gz\": {\n        \"sha256\": \"0d921f05345ad22ae7504e6aeeba9bf9ddf2166180212e70243904f153227e85\",\n        \"size\": 663725847\n    },\n    \"NoScenario_Town13_Route24114_Weather25.tar.gz\": {\n        \"sha256\": \"60ceb5322d0b50531d1d47b3bae2fc8cfb668f8d72a707292fec411c85a88fb2\",\n        \"size\": 478581254\n    },\n    \"NoScenario_Town13_Route24119_Weather3.tar.gz\": {\n        \"sha256\": \"cc365f041bec140245ea33f8333032d74ad0f8d641ed8482b05a378dfd8ee1ef\",\n        \"size\": 506140071\n    },\n    \"NoScenario_Town13_Route24120_Weather5.tar.gz\": {\n        \"sha256\": \"b279e979713adb6b20e46e33e369443215da8563b76a83a3f49bbfdba92f1886\",\n        \"size\": 528314046\n    },\n    \"NoScenario_Town13_Route24123_Weather8.tar.gz\": {\n        \"sha256\": \"da4b6968f80a77ec1568f0925a9f99652ed52f97ca55885b2d2430dc4a3ab2fc\",\n        \"size\": 314613018\n    },\n    \"NoScenario_Town13_Route24126_Weather11.tar.gz\": {\n        \"sha256\": \"99bfe65396d9437e386bd586a7efdfa1b2793bea0be9f4d845f2ed4c5fea672a\",\n        \"size\": 314784252\n    },\n    \"NoScenario_Town13_Route24133_Weather20.tar.gz\": {\n        \"sha256\": \"e583fe1010b2ea7f968d7eee85a9a12329877944609431910cf425ce4ede4ac7\",\n        \"size\": 483550169\n    },\n    \"NoScenario_Town13_Route24135_Weather22.tar.gz\": {\n        \"sha256\": \"6e3ab5b6b6f517e4e1c7c274a13bef9f130d054917bf50ae3aa584dc5899401b\",\n        \"size\": 485885468\n    },\n    \"NoScenario_Town13_Route24141_Weather2.tar.gz\": {\n        \"sha256\": \"9a8ba325bec2a3d0de9c914632075ec9a23be17b8faf2c72e53044c22b490092\",\n        \"size\": 475033244\n    },\n    \"NoScenario_Town13_Route24143_Weather5.tar.gz\": {\n        \"sha256\": \"43ebf39107817d2a27fdbb7452fc18e68c6f396a7e0cda8ddb58eedb8c367c97\",\n        \"size\": 531291777\n    },\n    \"NoScenario_Town13_Route24145_Weather7.tar.gz\": {\n        \"sha256\": \"be27001de52c8836a8c3c5a8380b4218d0a38946f9236af8234be5237dffd7ee\",\n        \"size\": 528056222\n    },\n    \"NoScenario_Town13_Route24149_Weather11.tar.gz\": {\n        \"sha256\": \"2ab8f734c49347bf309fd2d10a649495547c8ff4dba174ddff5cabd390e8b775\",\n        \"size\": 530128025\n    },\n    \"NoScenario_Town13_Route24158_Weather22.tar.gz\": {\n        \"sha256\": \"ce30518c13aba518c1c5ce25aab46eabf1a41dc3bed7cfee5a302d9c3ca74efd\",\n        \"size\": 441592665\n    },\n    \"NoScenario_Town13_Route24175_Weather14.tar.gz\": {\n        \"sha256\": \"acf670448caffd330890ae66be6f5906142db4cb8eb6aee96e308b59684c2d8e\",\n        \"size\": 487426035\n    },\n    \"NoScenario_Town13_Route24177_Weather18.tar.gz\": {\n        \"sha256\": \"50db9c2802acd529e2d76bfe24cae5a07518a5b9a8dfbc4a833495aa2ed0d311\",\n        \"size\": 514772563\n    },\n    \"NoScenario_Town13_Route31866_Weather23.tar.gz\": {\n        \"sha256\": \"3b32fa52ea4aedb43791bc42906780582eafdff62f3ebd51e5b5d6635efcf2b8\",\n        \"size\": 200446089\n    },\n    \"NoScenario_Town13_Route31888_Weather22.tar.gz\": {\n        \"sha256\": \"51603bb753a287a6c7bbb0ed5bfbd707783a464818b44eb412db78972eeb5da7\",\n        \"size\": 441102543\n    },\n    \"NoScenario_Town13_Route3487_Weather23.tar.gz\": {\n        \"sha256\": \"3a81164d7f1817da51aa1c75b25f0e2ec95c21d6f4f6478218ff10107b2952b8\",\n        \"size\": 289295078\n    },\n    \"NoScenario_Town13_Route38829_Weather6.tar.gz\": {\n        \"sha256\": \"ada5496953af228f983a1cc5b3cc29ba6ea13e8e44be33db66e038de8b152acd\",\n        \"size\": 208933750\n    },\n    \"NoScenario_Town13_Route39189_Weather15.tar.gz\": {\n        \"sha256\": \"cd4da3bdd9960751dc6d3927ce0dbff9a5eeaf9325448ebd516c5f1f558c069b\",\n        \"size\": 194411073\n    },\n    \"NoScenario_Town13_Route39229_Weather18.tar.gz\": {\n        \"sha256\": \"afb84e074694033cb8c6ea2576fe99c549a58df147a50b486013b4305de1ec45\",\n        \"size\": 211572324\n    },\n    \"NoScenario_Town15_Route24753_Weather5.tar.gz\": {\n        \"sha256\": \"723352b75be84f7162a61a1024ea0203ff03a434af18dee505d6b2caeed97b12\",\n        \"size\": 344598284\n    },\n    \"NoScenario_Town15_Route24763_Weather15.tar.gz\": {\n        \"sha256\": \"94e01f9cb46073d382e02e910bc7ca304282e3d7ce7e8e42586b115ea45bbbc6\",\n        \"size\": 165190604\n    },\n    \"NoScenario_Town15_Route24773_Weather1.tar.gz\": {\n        \"sha256\": \"723ac623fde89f8c5e209ac2be1ea922846924553d571f1066c253615b9a9ecc\",\n        \"size\": 211213444\n    },\n    \"NoScenario_Town15_Route24783_Weather12.tar.gz\": {\n        \"sha256\": \"ac4b425fb3da1d6af5692399407e87142c654dfeff26784e9c3f32ba7c10502a\",\n        \"size\": 316339045\n    },\n    \"NoScenario_Town15_Route24793_Weather25.tar.gz\": {\n        \"sha256\": \"4f1a876e55e4056cb31281cc0142cf95f61e2c8076f717d73a3df39a5c2623fb\",\n        \"size\": 308420908\n    },\n    \"NoScenario_Town15_Route25334_Weather11.tar.gz\": {\n        \"sha256\": \"f8e9c1b924d99bb35160ed4d57b8af5aa62f9e41efd0123debafb56a8771e598\",\n        \"size\": 445641400\n    },\n    \"NoScenario_Town15_Route25887_Weather12.tar.gz\": {\n        \"sha256\": \"4e51f3c47ac11e6e5122248a0e3d249e89f4a4b1dddeee9216d43af68e79f0da\",\n        \"size\": 382149397\n    },\n    \"NoScenario_Town15_Route26433_Weather6.tar.gz\": {\n        \"sha256\": \"3678bab3326f0f0e413933e6cbd90c409c5c2b474ac9368d5c0d44d4c6166841\",\n        \"size\": 452588417\n    },\n    \"NoScenario_Town15_Route26519_Weather26.tar.gz\": {\n        \"sha256\": \"d8bd4029e59dc41c78b856ff3c25162223416b109de78a37c564f7f6dacff60b\",\n        \"size\": 371758001\n    },\n    \"NoScenario_Town15_Route26525_Weather6.tar.gz\": {\n        \"sha256\": \"80ff75faa57a136a3d6c1e03469fe6eb57dcc6e484e295581538b9d202add24e\",\n        \"size\": 529927301\n    },\n    \"NoScenario_Town15_Route26531_Weather12.tar.gz\": {\n        \"sha256\": \"0fc3de4aa1cbca46f72cc53dc42975c5951232a90b26b42d2d7cb108aa335388\",\n        \"size\": 303698936\n    },\n    \"NoScenario_Town15_Route26537_Weather20.tar.gz\": {\n        \"sha256\": \"b4b8223b9840500f94b7f3ecf2ae9a32ad307d4e6b54904b1ebe1886e3007a47\",\n        \"size\": 323647533\n    },\n    \"NoScenario_Town15_Route26543_Weather0.tar.gz\": {\n        \"sha256\": \"b44ec9b7f33ed1ec3d731e46dd2633759917f3c2fe538029ff1c4b76a3c938b9\",\n        \"size\": 349163589\n    },\n    \"NoScenario_Town15_Route26558_Weather18.tar.gz\": {\n        \"sha256\": \"cbccf8be2bfc79b2e8facd552e99e317621d28f91eb480bf2983d4b1799678eb\",\n        \"size\": 355339169\n    },\n    \"NoScenario_Town15_Route26563_Weather23.tar.gz\": {\n        \"sha256\": \"304797c19ecfd0ca9361197184f2bcb52631ad532ebcef6b38ee32a685b33187\",\n        \"size\": 886515250\n    },\n    \"NoScenario_Town15_Route26568_Weather2.tar.gz\": {\n        \"sha256\": \"4b74ddd1148f498e9bccf9c6492ec81e6bb72bd1b40ac87343806729fa2524bb\",\n        \"size\": 907675362\n    },\n    \"NoScenario_Town15_Route26598_Weather10.tar.gz\": {\n        \"sha256\": \"781ea95054e081440a7e051b4fca774e3cbcf003153c7edfa637b1fbdb564e99\",\n        \"size\": 330810994\n    },\n    \"NoScenario_Town15_Route27558_Weather3.tar.gz\": {\n        \"sha256\": \"8e75b954462f73b85ff21db6f3704b7260dd1a1885a939d7f8bb7ea6d20691cc\",\n        \"size\": 1732170759\n    },\n    \"NoScenario_Town15_Route27563_Weather9.tar.gz\": {\n        \"sha256\": \"d542b9a3ff7aa1281af09a907e4fc8e8b54a6a17564b0f9672eb063501c01427\",\n        \"size\": 198364160\n    },\n    \"NoScenario_Town15_Route27568_Weather14.tar.gz\": {\n        \"sha256\": \"71e52563d66a8843988c6e17fb57537b83ca1c2bee82cb83c6837cd28311b9d1\",\n        \"size\": 604562957\n    },\n    \"NoScenario_Town15_Route27573_Weather21.tar.gz\": {\n        \"sha256\": \"d19ddced671b16b6a4a2ab958707985da7d2a9224516e3cd04034fc595697a4c\",\n        \"size\": 273177804\n    },\n    \"NoScenario_Town15_Route27578_Weather0.tar.gz\": {\n        \"sha256\": \"30de2d76e2407c27c7d6a960ee2143b676283ec530a649ffa7d736a13bb2d3ff\",\n        \"size\": 742019229\n    },\n    \"NoScenario_Town15_Route27583_Weather6.tar.gz\": {\n        \"sha256\": \"4ace7f63820b107980a471894f7be936a71abc1e3eceb58e2d2c936251956c48\",\n        \"size\": 693046397\n    },\n    \"NoScenario_Town15_Route27588_Weather11.tar.gz\": {\n        \"sha256\": \"bbf143a7c33b02b72b06dc1f77977c5ccb8c8506b3fb934b2fb5b76847d75e11\",\n        \"size\": 910088130\n    },\n    \"NoScenario_Town15_Route27593_Weather18.tar.gz\": {\n        \"sha256\": \"9214aed9361a3e5bbbdaaa4cd39993b4d25f8949ebe932fb4c724c2abfecb8fa\",\n        \"size\": 1290546524\n    },\n    \"NoScenario_Town15_Route27598_Weather23.tar.gz\": {\n        \"sha256\": \"4521a1b80933cd765fae5e33c52a4fef98bbbda5b6e510a3bb2412ac7799a571\",\n        \"size\": 1325791581\n    },\n    \"NoScenario_Town15_Route27603_Weather2.tar.gz\": {\n        \"sha256\": \"0bacc8bd91d185f926f83c68e0c2e91cc52b862f5868d093965395a6f6d79918\",\n        \"size\": 1814911034\n    },\n    \"NoScenario_Town15_Route27608_Weather8.tar.gz\": {\n        \"sha256\": \"6e01dd9c400a4271a7de92e3c58d8ec826ce2eb281f8308c8c48781ae0bbe1a6\",\n        \"size\": 941902021\n    },\n    \"NoScenario_Town15_Route27613_Weather13.tar.gz\": {\n        \"sha256\": \"072ce7700d526e55a2d32951845607366c96f6fa64b5806c28eaa6dc91492992\",\n        \"size\": 1632303069\n    },\n    \"NoScenario_Town15_Route27618_Weather20.tar.gz\": {\n        \"sha256\": \"5c67439dc5f0bc2ca9098000dde76a784239a2e49fd871a4801b21fd37cd5fb2\",\n        \"size\": 1103481295\n    },\n    \"NoScenario_Town15_Route27623_Weather26.tar.gz\": {\n        \"sha256\": \"40924e44f293243526b29a687856b1a3d3ec2cf337d315461556c4d3bcb3788a\",\n        \"size\": 1201664546\n    },\n    \"NoScenario_Town15_Route27628_Weather5.tar.gz\": {\n        \"sha256\": \"b94035b0a150445e70d907b726ba29315c4a20af28576c4f7b94309399012ac1\",\n        \"size\": 344175413\n    },\n    \"NoScenario_Town15_Route27633_Weather10.tar.gz\": {\n        \"sha256\": \"94fe603a201123ecaf0141ea167d59304fbc6d9f5200686cd6643185f66c4883\",\n        \"size\": 1379412155\n    },\n    \"NoScenario_Town15_Route27638_Weather15.tar.gz\": {\n        \"sha256\": \"d09d8cc6c2a4d020af1d49fe545f7f52b92cc6b643f24f92e8f9e9671fdd3ab4\",\n        \"size\": 960679167\n    },\n    \"NoScenario_Town15_Route27643_Weather22.tar.gz\": {\n        \"sha256\": \"5061b7065694aefa38f01df72753a1a4d014d1b80dc3e440f0d8997edb23b574\",\n        \"size\": 1245367018\n    },\n    \"NoScenario_Town15_Route27648_Weather1.tar.gz\": {\n        \"sha256\": \"6579e0fb500bfbf1edc89b439d0991f4f7a1ea082c9d684d07fa4764eff69cc9\",\n        \"size\": 247375183\n    },\n    \"NoScenario_Town15_Route27653_Weather7.tar.gz\": {\n        \"sha256\": \"afd12a097cad51febaf13b4b3bf487f36b9f2c58a3c73f38c74ef2beccb6dd2a\",\n        \"size\": 1055548485\n    },\n    \"NoScenario_Town15_Route27658_Weather12.tar.gz\": {\n        \"sha256\": \"a86ecc791e8916c88ece405826f56da21ab90d77fae8632a050ccba8174a27e8\",\n        \"size\": 1617362228\n    },\n    \"NoScenario_Town15_Route27663_Weather19.tar.gz\": {\n        \"sha256\": \"52774cf92fa34844d0e92ca11101f0af009e646ba06270974943d27911086d8c\",\n        \"size\": 224612079\n    },\n    \"NoScenario_Town15_Route27668_Weather25.tar.gz\": {\n        \"sha256\": \"e0ab21f8225a9f9e6ffd4b85f7d51107530486b6082a5f183223f239bba8ce7b\",\n        \"size\": 555519650\n    },\n    \"NoScenario_Town15_Route27673_Weather3.tar.gz\": {\n        \"sha256\": \"f6dab248358b66f5657f14a413298cef79378a561591b92ebd87f582e3976033\",\n        \"size\": 333491603\n    },\n    \"NoScenario_Town15_Route27678_Weather9.tar.gz\": {\n        \"sha256\": \"bec79632ed1088e21c01de4960ca0e457956e3f2a68e0a7c321ffbda155e5c3c\",\n        \"size\": 625347801\n    },\n    \"NoScenario_Town15_Route27683_Weather14.tar.gz\": {\n        \"sha256\": \"e7160451b67070504238faab3f415e4d5ddb86adceed4dc3a84384b87a6a74bf\",\n        \"size\": 653922273\n    },\n    \"NoScenario_Town15_Route27688_Weather21.tar.gz\": {\n        \"sha256\": \"15e4f85e18cef16670e1d7f70a68bedbb7e88f8ac3f771d4823c3731b996a2a9\",\n        \"size\": 920831014\n    },\n    \"NoScenario_Town15_Route27693_Weather0.tar.gz\": {\n        \"sha256\": \"c1b8669022e6b5f5101d45208ed26574ea9bfe061393294d93e292c94dbc4a3e\",\n        \"size\": 1370312954\n    },\n    \"NoScenario_Town15_Route27698_Weather6.tar.gz\": {\n        \"sha256\": \"487a8ec642d90f669aba792d61dbd25a3bfc533136b4b7366002b067780a07d3\",\n        \"size\": 1420556329\n    },\n    \"NoScenario_Town15_Route27703_Weather11.tar.gz\": {\n        \"sha256\": \"97fbed999bfdfe13a671279443541916015938f5a663c7ac10e2cb385bd664aa\",\n        \"size\": 1598807157\n    },\n    \"NoScenario_Town15_Route27708_Weather18.tar.gz\": {\n        \"sha256\": \"2fe3dff7e2c1f182731267efeb3c85c28e73ac25bbec843f251548dccefc6d58\",\n        \"size\": 999827909\n    },\n    \"NoScenario_Town15_Route27713_Weather23.tar.gz\": {\n        \"sha256\": \"fe8d9e513e758a00c5e7260b82cfcb8a007e7298aa1c901966ce9eb81d2fda5f\",\n        \"size\": 1636546364\n    },\n    \"NoScenario_Town15_Route27718_Weather2.tar.gz\": {\n        \"sha256\": \"f5a0b0ba91f1b0d5f170df6c55bfa6bad3051f74484bc086ab76234d0cbf3474\",\n        \"size\": 1166509548\n    },\n    \"NoScenario_Town15_Route27723_Weather8.tar.gz\": {\n        \"sha256\": \"e9f3246cb66e19b8219a85e1e3eddbabe84c0e8d052c8ea3dbd85a13757b3d3f\",\n        \"size\": 1096294239\n    },\n    \"NoScenario_Town15_Route27728_Weather13.tar.gz\": {\n        \"sha256\": \"fda042866dd4cb99359f617e645778653356e3adbacd17aa76b42e1d5927aa7a\",\n        \"size\": 258357188\n    },\n    \"NoScenario_Town15_Route27733_Weather20.tar.gz\": {\n        \"sha256\": \"1d093a4e3fa1a859fdbf2e83e128488e3d267b726ed6927fd78be68050df1734\",\n        \"size\": 1404127602\n    },\n    \"NoScenario_Town15_Route27738_Weather26.tar.gz\": {\n        \"sha256\": \"dad5c642da482a01def7c29594467de14ca76a529c9e2b20bcbf3f3d4142a8ca\",\n        \"size\": 1094829454\n    },\n    \"NoScenario_Town15_Route27743_Weather5.tar.gz\": {\n        \"sha256\": \"d3e751d2c6596d6a19bf674c8c45c211a52f12cffcd59cc08310d6815f8b033f\",\n        \"size\": 1347776978\n    },\n    \"NoScenario_Town15_Route27748_Weather10.tar.gz\": {\n        \"sha256\": \"2f473bf77781a40ffbaacf9ce2c114a1699002d0c4cd509a6f0fe03c293aa571\",\n        \"size\": 219678659\n    },\n    \"NoScenario_Town15_Route27753_Weather15.tar.gz\": {\n        \"sha256\": \"dc8c960da8deb6875a9fb70845bff5c8eb7969ce1e7a9cd9a18ba989f64e9720\",\n        \"size\": 911696123\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town03_Route28055_Weather25.tar.gz\": {\n        \"sha256\": \"aaa77ad978c64c393e6942499ea03e8811461a5a74fc466ba1bc625cbda76107\",\n        \"size\": 568440312\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town03_Route28057_Weather0.tar.gz\": {\n        \"sha256\": \"86463d3f0797de209bbd2f7db3ef39eef2610711e04253845b14e4805b0dc2e7\",\n        \"size\": 395326548\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town03_Route28059_Weather2.tar.gz\": {\n        \"sha256\": \"935e3f3ab11272b864fa5d6bfd0954562dd9c070cd59a2d1dde623212521b9f4\",\n        \"size\": 954489089\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town03_Route28060_Weather3.tar.gz\": {\n        \"sha256\": \"90c61150ba60f5b9057a337dfc3b0aa9e9865ca861d5887c032f5bbae74ffcef\",\n        \"size\": 136290378\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town03_Route28062_Weather6.tar.gz\": {\n        \"sha256\": \"a8bd96da602c924727a69e1e6d8220eba71448125f20e75b9076d319bc4fca0b\",\n        \"size\": 197526555\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town04_Route28087_Weather8.tar.gz\": {\n        \"sha256\": \"f9f64009c9f3a9d4723159037768adfdde6c62ceae35e5c27bb42760edfe157e\",\n        \"size\": 621419409\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town04_Route28088_Weather9.tar.gz\": {\n        \"sha256\": \"e80f4b24a2c8185f480db319cb4567657c7351162b828f7f2dd5a55a9bc6c02c\",\n        \"size\": 579732357\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town04_Route28093_Weather14.tar.gz\": {\n        \"sha256\": \"9edad488b1f34e5e7cb0f3b06f189daddb6d3ec0e36ff01009cf562ab8e8105e\",\n        \"size\": 351733820\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town05_Route28114_Weather12.tar.gz\": {\n        \"sha256\": \"566a8f622f728f0c14ba9f1fea6c5a8851449e89c808a599f27ce5182acc1725\",\n        \"size\": 167458710\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town11_Route28161_Weather13.tar.gz\": {\n        \"sha256\": \"d0a6b147665f803f788a7062c1694517ee39059fad2e0fdc1d88fa3d41eacf3c\",\n        \"size\": 42026134\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town11_Route28166_Weather20.tar.gz\": {\n        \"sha256\": \"5fdae56468efcf14f168ac51654257f54e49aa81346c90759d56036e3c943dcb\",\n        \"size\": 42524825\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28210_Weather18.tar.gz\": {\n        \"sha256\": \"abc390bdaff7782c58234582aa40842c329e5dce78a166ef52c78cd278a651b4\",\n        \"size\": 172732630\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28211_Weather19.tar.gz\": {\n        \"sha256\": \"c3539e9860be47341fb874bd21847a4fdc3303099574b2d372717cdd65203f18\",\n        \"size\": 218364148\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28212_Weather20.tar.gz\": {\n        \"sha256\": \"0238f8d4d8ee47aceececaf60ecd41fea8c5303c74c58acd0097b63a2e231e15\",\n        \"size\": 359498597\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28216_Weather25.tar.gz\": {\n        \"sha256\": \"6c28a1ff782a8f12eedfba537d5e4f1212da1fe890c901b7da8126a7ff105f68\",\n        \"size\": 217621800\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28217_Weather26.tar.gz\": {\n        \"sha256\": \"860cc589c39d3739ab606d91a0a12409c85531c7d9d0e89e83dc4b311426e9df\",\n        \"size\": 215521579\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28219_Weather1.tar.gz\": {\n        \"sha256\": \"0ecba7e56c1e8601a767328759a2241f412b644806c52941da9a66c4c8c78167\",\n        \"size\": 247694935\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28223_Weather6.tar.gz\": {\n        \"sha256\": \"743e680b29ed90968b6ae875bf9754d55bba02f8ea8f31b99c4f1fd604a8f990\",\n        \"size\": 303688434\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28225_Weather8.tar.gz\": {\n        \"sha256\": \"8a302fb0f120c3cb2aca34423f2febae7c2ca96ffdcb93c767cfadd16be5fa81\",\n        \"size\": 164370097\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28228_Weather11.tar.gz\": {\n        \"sha256\": \"93d4085d1a335f67c157c550e9c86439ad6533def1f49379df27078e8f807ec7\",\n        \"size\": 314730074\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town12_Route28229_Weather12.tar.gz\": {\n        \"sha256\": \"3b9d696e2cc2b4189af685f7e8751b3fc20f3a49b88d09ff8478078f81e35644\",\n        \"size\": 616195921\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route2854_Weather2.tar.gz\": {\n        \"sha256\": \"dfa53cdd0aeff6ece76c42e4bb7dbc33c5f25c4de37b1578912cff1a84c81bc9\",\n        \"size\": 139704679\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33649_Weather10.tar.gz\": {\n        \"sha256\": \"ab2935e2a96b94382481cc8ec0dd2e3be1365f96a00978c931839df13de2a238\",\n        \"size\": 172430703\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33653_Weather14.tar.gz\": {\n        \"sha256\": \"4095f1e6ea0bf072a4def49cc4f2745a4ad1b549d7c28ce8e70a69c415301f53\",\n        \"size\": 96973991\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33662_Weather26.tar.gz\": {\n        \"sha256\": \"b417ff5313fe31d5ac81e212ab2fb92857a28b822f223b20ab72cb0982801121\",\n        \"size\": 188926060\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33668_Weather6.tar.gz\": {\n        \"sha256\": \"87d542cc3375b51334191f0a368b37154c3bda88eec3f01c45b32035465d143e\",\n        \"size\": 171582307\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33679_Weather19.tar.gz\": {\n        \"sha256\": \"ffb40980b945b9b490acb8ec9e6b246f29823b1bc43d389b6376117b9332f186\",\n        \"size\": 126074893\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33682_Weather22.tar.gz\": {\n        \"sha256\": \"04bde6a96c3565fe9ff95788d0aee2a4db8e86845793ab88fb159866fb9fc3e9\",\n        \"size\": 106942888\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33700_Weather15.tar.gz\": {\n        \"sha256\": \"04a91dc0bb6b6284cf877092b5a3ef2c40f417738e1ff7f1154c3e38444d627c\",\n        \"size\": 120016903\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33745_Weather14.tar.gz\": {\n        \"sha256\": \"80d2f466b126556f68cdc443f7a8c2f9652377524769eebc4ea61efeb5c7c457\",\n        \"size\": 138082292\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33834_Weather11.tar.gz\": {\n        \"sha256\": \"8fdec1fd5fb1502e6496e02c62a4b9849cedc1aeeb7d7d138e780f8cb3b65391\",\n        \"size\": 135488066\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33904_Weather12.tar.gz\": {\n        \"sha256\": \"632d04729d0c35d22aa0f1bb67164c3ff12a83a4ad72269595dc8e0737d16366\",\n        \"size\": 161451693\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33910_Weather20.tar.gz\": {\n        \"sha256\": \"318dc35b2b5ad73fc92a7edf277b3bb4c948492399e4222ec2e09b64d8ecee5c\",\n        \"size\": 145015240\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33918_Weather2.tar.gz\": {\n        \"sha256\": \"2efd8642cf28777d1541215602cb1b2aa6b67e104fbcaa1ae533ed5f2de4642c\",\n        \"size\": 172851734\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route26990_Weather11.tar.gz\": {\n        \"sha256\": \"19c32a0df1a499aa560914d08585dcc9c8e31e9324e9e9ee8aa5b62ba356bd44\",\n        \"size\": 1090508484\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route27000_Weather23.tar.gz\": {\n        \"sha256\": \"d6387c7d2de3571d49cd6024c723af3ad6465d157d798cd38c0ca7dee1ead155\",\n        \"size\": 400427343\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route27005_Weather2.tar.gz\": {\n        \"sha256\": \"541cc6c664a94bb822893799c9708180445d3fc3eaf20907b830e566de68d855\",\n        \"size\": 3240718555\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route27025_Weather26.tar.gz\": {\n        \"sha256\": \"5c217ec65378226fe1c4a82d19ff76c54b622ca426e998a70e4e2019a574fb16\",\n        \"size\": 401711972\n    },\n    \"NonSignalizedJunctionLeftTurn_Town03_Route27030_Weather5.tar.gz\": {\n        \"sha256\": \"e7e8916d96485a5b6c6cec707cd8f6160ffca15f6c3dd540d4359b2b4d108fda\",\n        \"size\": 375476073\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route27039_Weather14.tar.gz\": {\n        \"sha256\": \"f883401e8688bc8099913157694e76f56c0899c8ca126334ea76d3c398bf88af\",\n        \"size\": 289949086\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route27064_Weather18.tar.gz\": {\n        \"sha256\": \"16a602768b41b39a85af85da14e94f7e67373abf02e28ffa12ae9cf4813df56f\",\n        \"size\": 397563243\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route27069_Weather23.tar.gz\": {\n        \"sha256\": \"e74594eafb73a54ff81a5acfd6d24335616524e6c378a5d24ff3741b9bb272f6\",\n        \"size\": 223623572\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route27079_Weather8.tar.gz\": {\n        \"sha256\": \"3a56e77f2fdb7f84f4c1b2bf10176fdd4f8319e1a78a3c0c0ffb495698024e69\",\n        \"size\": 309392297\n    },\n    \"NonSignalizedJunctionLeftTurn_Town04_Route27094_Weather26.tar.gz\": {\n        \"sha256\": \"ce5963425c4f1322268eaad8a1d4f3df1202d8521fcec2050e4878c1e783f206\",\n        \"size\": 178661343\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route27146_Weather6.tar.gz\": {\n        \"sha256\": \"cd0cd2dfa63e92cdec6418562c76fa89a9310cd7a874647b139dae688cfdcdcc\",\n        \"size\": 523513300\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route27151_Weather11.tar.gz\": {\n        \"sha256\": \"6316cbcfcee20f4b802d978e43505179f09b2ec5d4b059880409796c3d3a647e\",\n        \"size\": 162521914\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route27176_Weather13.tar.gz\": {\n        \"sha256\": \"9a81437c13896d0f15ec41f4f853ded8914a7f7d6f017b6bdcdb205db2d12def\",\n        \"size\": 158064558\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route27186_Weather26.tar.gz\": {\n        \"sha256\": \"e40e6e8f0fbf77df887245ed6308f27fc39c21b3de42a9319190341209d9cb0f\",\n        \"size\": 201683362\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route27206_Weather22.tar.gz\": {\n        \"sha256\": \"220b3c793bf06b31ebc7d04d5c9d13d89a068f827aa4d34daff85b6bc3d8e911\",\n        \"size\": 139640688\n    },\n    \"NonSignalizedJunctionLeftTurn_Town05_Route27221_Weather12.tar.gz\": {\n        \"sha256\": \"8af5b86ec1b7f0065244f410debc1851a8bd65d90ab322b4a86494846e570fc1\",\n        \"size\": 166260915\n    },\n    \"NonSignalizedJunctionLeftTurn_Town11_Route26942_Weather9.tar.gz\": {\n        \"sha256\": \"0feca3006854834d1403fe26286c451bc4dce81951c1fa338196e3dcc4e0e6cc\",\n        \"size\": 39891061\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route2084_Weather23.tar.gz\": {\n        \"sha256\": \"45b9167bdd4ad56905f298866c2529a15aa086af4e5f9ed91776f641afffcc10\",\n        \"size\": 227819697\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route2086_Weather0.tar.gz\": {\n        \"sha256\": \"8a9d5f0989276afb5693624ff5f6eee3975a98365a6e0a56cf8537f00ce592bb\",\n        \"size\": 229409744\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route2091_Weather5.tar.gz\": {\n        \"sha256\": \"51960af646f78b82e2968086eb7ca73a4ccbfa917bb16f9d5c6a531243d3cc85\",\n        \"size\": 201787318\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route2881_Weather15.tar.gz\": {\n        \"sha256\": \"bd10e747909c023b0abb3808d76d7a25a65a703d14f579b24ef96923aaba43ba\",\n        \"size\": 226068653\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route2883_Weather9.tar.gz\": {\n        \"sha256\": \"d3a125a19d2ac04ea4f4ecc1fa918b9f894ba61ad373dc3aa80d55152a20de88\",\n        \"size\": 203370489\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7035_Weather18.tar.gz\": {\n        \"sha256\": \"62f4c13a3f9a2a1d2faf521a73c267107418c2b3243e10921f17b24eaeff63f0\",\n        \"size\": 169409643\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7094_Weather25.tar.gz\": {\n        \"sha256\": \"319a7b532dbe61a4a15f3f50707ba15d8ea4a353ce72d26da9908ff82d57876c\",\n        \"size\": 174249964\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7107_Weather12.tar.gz\": {\n        \"sha256\": \"c6a7f8da75738869ef09c13929b30207b4c911eb085506e43b4f7ba066908b71\",\n        \"size\": 255483261\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7178_Weather5.tar.gz\": {\n        \"sha256\": \"f8a970e88ddd7d4db268ba2b64c247131e4e81525be1f4828c8810e30b78a87e\",\n        \"size\": 113548732\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7207_Weather8.tar.gz\": {\n        \"sha256\": \"48ab7a0efd9dbc7b4975f9e3657ec825d321e5f8cefaaa581cecb5c669315cec\",\n        \"size\": 256189473\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7208_Weather9.tar.gz\": {\n        \"sha256\": \"8a3c88462c8e31ca6d97187d80decc305c38d8a2b8cbac3689fa5ce17ea8ad79\",\n        \"size\": 191467608\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7227_Weather2.tar.gz\": {\n        \"sha256\": \"58a82677deba6b17f67843c12ff57ff59c10a1ea8591626460dcc1acc78744e8\",\n        \"size\": 272631667\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7235_Weather10.tar.gz\": {\n        \"sha256\": \"847bf65216bd62b3a96d7a5b036e5820f2fab6ddd0692918ba9e7780c74c634a\",\n        \"size\": 224475265\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7293_Weather8.tar.gz\": {\n        \"sha256\": \"996b128ef35ca77141c010dd0628c8261e88ff5117b2aada7a6791ef7058a356\",\n        \"size\": 223321420\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7320_Weather9.tar.gz\": {\n        \"sha256\": \"3aeee64a3f02358d771613435e1737c7446748888b3303eb334b23e66f1c7182\",\n        \"size\": 219867847\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7331_Weather2.tar.gz\": {\n        \"sha256\": \"51a1ab7a1928dddc69dbcc461c68780f5dbd1b7a98e0c724034126d161baf580\",\n        \"size\": 256769394\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7332_Weather3.tar.gz\": {\n        \"sha256\": \"cbd76750ae0f69ed83505393f95a7e221d02e250229ce02f826864682970546f\",\n        \"size\": 243018755\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7335_Weather6.tar.gz\": {\n        \"sha256\": \"91c919a7a3041ded386b471562e72977b66ccb65456615dbb3d5a513488ace9f\",\n        \"size\": 269326396\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7341_Weather12.tar.gz\": {\n        \"sha256\": \"ad263ad0f5a6f2aa0d94b0946d1b5fb2b1bb84bbe2e73e261630d5b8cc02bf16\",\n        \"size\": 193578115\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7346_Weather9.tar.gz\": {\n        \"sha256\": \"9f3cfe9f2f1e8ed7350949ecf032d592b2dfa1c183916d06feb079366a4fc7cc\",\n        \"size\": 257721847\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7348_Weather19.tar.gz\": {\n        \"sha256\": \"f73581e4213aa3195ec4ae0aa58e51d32430c03598bba65d814785a24a0d166c\",\n        \"size\": 283675213\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7358_Weather3.tar.gz\": {\n        \"sha256\": \"cb802cc9d29ed66cce318c0da3e4461e203674b4cd67f53ab9cc9870cc6bf5d6\",\n        \"size\": 234220328\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7360_Weather5.tar.gz\": {\n        \"sha256\": \"62e4a7089807b145cdca203538ee8b9afce19c5d6dc6721d5396a369efc3fb8b\",\n        \"size\": 630908535\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7368_Weather13.tar.gz\": {\n        \"sha256\": \"9e61e3e437ba565b957960ba3c95fb0845d24df9ab35bef80c1ae2a361e3e0ba\",\n        \"size\": 174816944\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7369_Weather14.tar.gz\": {\n        \"sha256\": \"73e8e5d93701f25f39d27fb1f9e86e220c4fcc555b44b9d68d06a841f56fb94a\",\n        \"size\": 235685602\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7374_Weather19.tar.gz\": {\n        \"sha256\": \"e9ca0ec4245ea8bc14b163de7a0c919002493a1c76879068361a836c1001f7f0\",\n        \"size\": 146191078\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7379_Weather23.tar.gz\": {\n        \"sha256\": \"3f9e394686100c459033ddf685ad675f485bbf1322e8748b5e628ab99d4abddb\",\n        \"size\": 182224871\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7380_Weather25.tar.gz\": {\n        \"sha256\": \"16f782cd859ad4f2264e19f87086884e247502e42a6a3f7d792fe86bc6b2d536\",\n        \"size\": 259744122\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7384_Weather3.tar.gz\": {\n        \"sha256\": \"dae76aebf9148b35d3075640c1418000ad823a480060565b8c93547fce833376\",\n        \"size\": 149737837\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7385_Weather3.tar.gz\": {\n        \"sha256\": \"e836446c25151ee25bc260b3b033d69b06a286f45889b039e62659b4009e01d4\",\n        \"size\": 219375031\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7386_Weather5.tar.gz\": {\n        \"sha256\": \"b8a11832e70d84a0136955be72b6ac3803ebee3cc1611df1ce96313221be117d\",\n        \"size\": 1077908333\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7387_Weather6.tar.gz\": {\n        \"sha256\": \"19282318667fd33fa78517de182db6627d696a72147574c77b374694b7d5eb9f\",\n        \"size\": 236775089\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7392_Weather11.tar.gz\": {\n        \"sha256\": \"db7e3c0ee23968ca25666d4e1b03f9c63c4842f6eac1b4bc122e6615adb9febe\",\n        \"size\": 305905919\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7404_Weather23.tar.gz\": {\n        \"sha256\": \"eaaa154d5f4290f1605f96f926819c2e8a4bb92192fef670ecf7d90641bb47c8\",\n        \"size\": 176215208\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7420_Weather13.tar.gz\": {\n        \"sha256\": \"efd8469ce4e8d40438b838c562351950310068978c3cd1fcd7d2add74d6fb049\",\n        \"size\": 163367230\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7422_Weather15.tar.gz\": {\n        \"sha256\": \"bd7e14518d8ac510f2ad8d1f5a6037d9aed04a34046a3f5984b73d9f685a6d2f\",\n        \"size\": 247351926\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7427_Weather20.tar.gz\": {\n        \"sha256\": \"1a79dac5b07058b9dff17ffbd348ff333ff74a8e0c7c77c254b8bfc0faa203bf\",\n        \"size\": 243647575\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7435_Weather2.tar.gz\": {\n        \"sha256\": \"76e3440e9dc025f1f6d30c46660e2fc9ef6ac94bebda9b24858980ee148a59ff\",\n        \"size\": 253155808\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7441_Weather8.tar.gz\": {\n        \"sha256\": \"6ec1b21632b0ab193b8a75651bfb4a02d327dd560c8aa4d5d31e91e009cebf56\",\n        \"size\": 256286649\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7444_Weather11.tar.gz\": {\n        \"sha256\": \"66b7efff27e8db929f98b7086b554384bae90d2c87c00dbd3d1d9765aa45b8e3\",\n        \"size\": 596131050\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7447_Weather14.tar.gz\": {\n        \"sha256\": \"50aed5cd36996a69799031236239b8cf12f55996d2e95471f5bcc92db155abb6\",\n        \"size\": 182981541\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7449_Weather8.tar.gz\": {\n        \"sha256\": \"437fe8b8a4ecb02809ffd855dcbc91440a5620cbca55d2805588ef6fb8ccf9fc\",\n        \"size\": 206381993\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7462_Weather3.tar.gz\": {\n        \"sha256\": \"71929a3ccc8cc6613bfc1ad1bc1956c350ee9654b6163698c1ab653d6ae30d55\",\n        \"size\": 290999180\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7471_Weather12.tar.gz\": {\n        \"sha256\": \"c39493019ec55780e61a91d541533a45650ce9a5d6375c01b1c0da95c0fe493d\",\n        \"size\": 170562644\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7476_Weather9.tar.gz\": {\n        \"sha256\": \"082a88b4c05431efede8c6d9f157ce8d02a87fc56e9e9f7337e94189a606b914\",\n        \"size\": 263311632\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7481_Weather22.tar.gz\": {\n        \"sha256\": \"abc7d2a6bce5eb3fed95ea3cb88f5401d38e9348b6a157efecfe155448c89700\",\n        \"size\": 172377585\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7485_Weather0.tar.gz\": {\n        \"sha256\": \"f97bed570e09d16208a7cb5aa42ac3e6df4fccf48d5bc85821a59c8e96911c16\",\n        \"size\": 339320377\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7486_Weather1.tar.gz\": {\n        \"sha256\": \"aa294461c3bd232d1f89b5040e13b85bde5fb8ab81637a73efea9ca6ab5ec433\",\n        \"size\": 241072594\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7491_Weather6.tar.gz\": {\n        \"sha256\": \"516bf067269ef0998704e9d783d14e42990cbc82167ca4dc65423b461baeb6d2\",\n        \"size\": 227127763\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7505_Weather20.tar.gz\": {\n        \"sha256\": \"ca586c7937cbb043f46fbee813815c39093b45099f5ffa879a9d46ed377f6083\",\n        \"size\": 298504838\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7507_Weather22.tar.gz\": {\n        \"sha256\": \"a04fab93501f05d05cce552d395ef40dfb8bcd7dfbe61210e0160c85cc201c5a\",\n        \"size\": 175668523\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7509_Weather23.tar.gz\": {\n        \"sha256\": \"459364a43e9f60df6daa489ae482906119e9f661530c8ef67542fee25d4028d6\",\n        \"size\": 126636359\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7515_Weather3.tar.gz\": {\n        \"sha256\": \"443013126110ec08de0c2da9bd49eab351e88deba6b38bcacaa47b9e69dc74f6\",\n        \"size\": 243406521\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7521_Weather10.tar.gz\": {\n        \"sha256\": \"b6095ec69b3a44c2849479955532d045f4b1d718d7d30879a732b8e34fecfa29\",\n        \"size\": 164459327\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7522_Weather11.tar.gz\": {\n        \"sha256\": \"b7ffafba3a89c3d998964653c01385fe4b0a538c979f0c3ffb977e6f2ab03fd5\",\n        \"size\": 226274982\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7526_Weather15.tar.gz\": {\n        \"sha256\": \"b93a500b20ecc4f2dbddd541deaa6da2e905b8efe2a095189171b14287fb6fe4\",\n        \"size\": 240734003\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7537_Weather0.tar.gz\": {\n        \"sha256\": \"1fda70ab4c0a7c37c8ad7958195f3195c0c76c213558028364facdb3f25bc5c5\",\n        \"size\": 255420720\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7538_Weather1.tar.gz\": {\n        \"sha256\": \"5c9ce1f4dc9cbb2f184e636b325857177d118c61288c138dea086ff52c77cb44\",\n        \"size\": 241716378\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7543_Weather6.tar.gz\": {\n        \"sha256\": \"8dba54b2dff84f8f482a0143c3d25a8becd4cf0749987c2a63e0954182136190\",\n        \"size\": 823069246\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7547_Weather10.tar.gz\": {\n        \"sha256\": \"23d5833fa3ce1b1eb9b32e5a258e580f3a3030f4db5974fca5f554b6ff38200e\",\n        \"size\": 233491698\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7552_Weather15.tar.gz\": {\n        \"sha256\": \"c263cab2da1c0faa22905974477eb499d1797cd0845b8c83be93286472fdc364\",\n        \"size\": 283465851\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7565_Weather2.tar.gz\": {\n        \"sha256\": \"d791beab6f5fa6f7dec41a4e070960cdb1ef595579b3d043366b0f8e8e503da3\",\n        \"size\": 265477689\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7568_Weather5.tar.gz\": {\n        \"sha256\": \"419530430bf510df17ab52980c773f41d81e04caeca140b45ae49a41223283e6\",\n        \"size\": 266890603\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7576_Weather13.tar.gz\": {\n        \"sha256\": \"202fc1e3292a60ac2c2ae4aba6d94870fd48f6b58957c2830d706024ae41c75b\",\n        \"size\": 228621696\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7584_Weather21.tar.gz\": {\n        \"sha256\": \"cbf36dfc970df0e2c84b0e1d8000f3d1efb541e203256f3c3f09be9092d4ef30\",\n        \"size\": 235834670\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7591_Weather2.tar.gz\": {\n        \"sha256\": \"41d0a91d5c8b5ef3bbdaddcb323ac32de714a000725a5eddb1a88e0cad5aec10\",\n        \"size\": 267990462\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7631_Weather8.tar.gz\": {\n        \"sha256\": \"47630e3224060ba43e74730fc243f5b069a3c33603d8461bb4b66312b7090fc6\",\n        \"size\": 177192434\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7638_Weather23.tar.gz\": {\n        \"sha256\": \"52786343d79b62dce3d980b9f83087ef4107f0d79cbff41f0bcda506d49c86a5\",\n        \"size\": 224149283\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7641_Weather0.tar.gz\": {\n        \"sha256\": \"a78f8b6a3d4e6df857e29ced95b152e29f935daf66b6f1050bb2f058b7218371\",\n        \"size\": 266041278\n    },\n    \"NonSignalizedJunctionLeftTurn_Town13_Route3652_Weather7.tar.gz\": {\n        \"sha256\": \"4a61ad06152ae6a667cbec38514637b1ce2d5da708bba8cd04657035b29b97a3\",\n        \"size\": 154625027\n    },\n    \"NonSignalizedJunctionLeftTurn_Town13_Route3654_Weather9.tar.gz\": {\n        \"sha256\": \"5796f38b5b8b05c1036d72c15f705789de7fea7f9f55902413db59e4c039bd58\",\n        \"size\": 185759637\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27045_Weather22.tar.gz\": {\n        \"sha256\": \"380091da717bb9a394119735f0cb64560cf69db7f0ed6cd9ea9abdd38bc60978\",\n        \"size\": 130798807\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27050_Weather1.tar.gz\": {\n        \"sha256\": \"6de88cf4072accbc017eca65cceafe2c86d93c7ce82c8ba55a33989a482804db\",\n        \"size\": 764766291\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27065_Weather19.tar.gz\": {\n        \"sha256\": \"93445f47ad21e60cdd569d4aee0608a845ed694b513811881981caf38fdbb70f\",\n        \"size\": 522277325\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27070_Weather25.tar.gz\": {\n        \"sha256\": \"ed13c9af036803c3eca9fbf1306917125472090c0ee8b2d15e2c953f5f9c90e9\",\n        \"size\": 261153563\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27085_Weather14.tar.gz\": {\n        \"sha256\": \"519c615815396c99e9df694acf1b832a6eeb6f1161e3cf8156a7753e5eac5bf2\",\n        \"size\": 643666218\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27110_Weather18.tar.gz\": {\n        \"sha256\": \"53c200990d90f2bd9e979deaa366cab489d19edf0cae9fc25b3ad5f2a431faf6\",\n        \"size\": 500239403\n    },\n    \"NonSignalizedJunctionRightTurn_Town03_Route27120_Weather2.tar.gz\": {\n        \"sha256\": \"0a814b4bbd9705890203f38273d8fac1f919d5fb23e88a94de0dbf6ce9ee0363\",\n        \"size\": 117718717\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route27109_Weather15.tar.gz\": {\n        \"sha256\": \"8f0839c52e08b69fcca3e9149c1f54a2a1686b1dacbac785a6e675439f6b5d15\",\n        \"size\": 185570281\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route27114_Weather22.tar.gz\": {\n        \"sha256\": \"291d0c66bfd440f793cd2de0759dfdd231906afcf31e9d463384138e5d625c23\",\n        \"size\": 240942593\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route27144_Weather3.tar.gz\": {\n        \"sha256\": \"286ce4817e1dd54d605096b13bf3bfefb2ce5e6f83bd5386fc16e129a2455d76\",\n        \"size\": 419954387\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route27149_Weather9.tar.gz\": {\n        \"sha256\": \"7f09fa8c6bddb9b7c173ff8c3f43bbbf0316905c206aa33bf937077af4d691b0\",\n        \"size\": 208110513\n    },\n    \"NonSignalizedJunctionRightTurn_Town04_Route27159_Weather21.tar.gz\": {\n        \"sha256\": \"0a3c3ffb2c1b2179481ba295dd8384aeed8ff9f1c3942885bd3132a091f2d323\",\n        \"size\": 175104827\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27226_Weather19.tar.gz\": {\n        \"sha256\": \"f12573c057140c5ca864b73dcb0a62b1b0aebc4e7fb4109af0142db6e7c23b70\",\n        \"size\": 187896261\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27261_Weather6.tar.gz\": {\n        \"sha256\": \"b4f4389971c5282613e08f98eb981181248487b676e118d6d2ecbd5e1a84344b\",\n        \"size\": 254026794\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27266_Weather11.tar.gz\": {\n        \"sha256\": \"af9f2f5f8abfab8f374bf2c86fbd32d4b0324570107713080875f3901579219e\",\n        \"size\": 124935394\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27271_Weather18.tar.gz\": {\n        \"sha256\": \"446b157145e9dc526a2a9bdb15b9cdfe75e7ad57423def79297782dfbd800f6b\",\n        \"size\": 190059814\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27281_Weather2.tar.gz\": {\n        \"sha256\": \"a734cc450c700b59f083f04abd1160c625dbaec9348ffd262810c4abf1b2b07b\",\n        \"size\": 233086176\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27306_Weather5.tar.gz\": {\n        \"sha256\": \"bfc726b84426e945936615215a64638bc4871a6a2f6a2865d41a6bda46015436\",\n        \"size\": 167098635\n    },\n    \"NonSignalizedJunctionRightTurn_Town05_Route27311_Weather10.tar.gz\": {\n        \"sha256\": \"2495328e2b62cfc08e002651fe5710e19d99bc460bef2a075ba9da914865bbd2\",\n        \"size\": 175921871\n    },\n    \"NonSignalizedJunctionRightTurn_Town07_Route25303_Weather2.tar.gz\": {\n        \"sha256\": \"df9a2eb1ecfc2f159ac29579802792ac24abeaca2191d09dfb890191b43918c4\",\n        \"size\": 292099148\n    },\n    \"NonSignalizedJunctionRightTurn_Town07_Route25317_Weather19.tar.gz\": {\n        \"sha256\": \"c0f32cbcbc4a2a7f810b2d1a47c6da9359a490dca18f9b11c784b7ce010d38ce\",\n        \"size\": 569700387\n    },\n    \"NonSignalizedJunctionRightTurn_Town07_Route25324_Weather0.tar.gz\": {\n        \"sha256\": \"a77e2e246b15f9d1cb256424fee1b95bcc72fae08f56da0b65a43e1cab1c3b55\",\n        \"size\": 280391461\n    },\n    \"NonSignalizedJunctionRightTurn_Town11_Route26967_Weather11.tar.gz\": {\n        \"sha256\": \"c7f7e7fec9fa69e61afdd066d0225cb3fc17cb764e0387ff2ded6e306189ddb7\",\n        \"size\": 37733231\n    },\n    \"NonSignalizedJunctionRightTurn_Town11_Route26992_Weather13.tar.gz\": {\n        \"sha256\": \"e7e94da94f5caf62f133370bf7e22fb0e7ade3460183c4dff038a98ea5cb7a5e\",\n        \"size\": 34099418\n    },\n    \"NonSignalizedJunctionRightTurn_Town11_Route27002_Weather26.tar.gz\": {\n        \"sha256\": \"64cbede58f98fdefcbce012a14f25cf589ee0205748fad0f665084542fce0463\",\n        \"size\": 59766961\n    },\n    \"NonSignalizedJunctionRightTurn_Town11_Route27012_Weather10.tar.gz\": {\n        \"sha256\": \"75265d937cbb0a7ff86e0a2294ed43ebc20b6768b0058f852cc72ad6a9cf53b9\",\n        \"size\": 32196757\n    },\n    \"NonSignalizedJunctionRightTurn_Town11_Route27047_Weather25.tar.gz\": {\n        \"sha256\": \"2fbefd83a27d168844636e2c84b546e3acd0b620ff83a89dbdc36df5777cef93\",\n        \"size\": 25964338\n    },\n    \"NonSignalizedJunctionRightTurn_Town11_Route27052_Weather3.tar.gz\": {\n        \"sha256\": \"60552dadacec3b9de799ebfd4476ac6887fabed5edbbf52592431ccd22688f39\",\n        \"size\": 61467089\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2105_Weather19.tar.gz\": {\n        \"sha256\": \"394f2e12645b07f57245e4b9ee4ca47076ecbec7766df5afb1670b4466e85c4d\",\n        \"size\": 143936451\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2110_Weather23.tar.gz\": {\n        \"sha256\": \"9b93b57ea0803842de5007026745cd1a99665480f0325dc7dc5f09e6496b6dbf\",\n        \"size\": 153812567\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2115_Weather3.tar.gz\": {\n        \"sha256\": \"926d2a55e88054189e3fe4fb649c010f46be9caf87f7d74c47e43bd0362ef2fe\",\n        \"size\": 222529722\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2117_Weather5.tar.gz\": {\n        \"sha256\": \"13121e74ffbf716583f5d9fc1e0bdb7c3ade8808e89d010e19758fd99c1f00a9\",\n        \"size\": 134460459\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2120_Weather8.tar.gz\": {\n        \"sha256\": \"08cb24725bf28e877ae43c3f64e803eeb437e1825ce2e5ff2a640ed31a723cbc\",\n        \"size\": 198187697\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2887_Weather21.tar.gz\": {\n        \"sha256\": \"9e2a8d9202fdd5f538b59df4ce30ee2572b15a70d296eb95a329b15474d09ef3\",\n        \"size\": 154549596\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2898_Weather6.tar.gz\": {\n        \"sha256\": \"2355ece91bf0b7b1b15a685fb72152bcbf9e8ea2944f542cff7ec184c282d75c\",\n        \"size\": 290552926\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route2903_Weather11.tar.gz\": {\n        \"sha256\": \"4b14e6d0ddd149f8f50794c4e54c339c81bdc6037d6004aff67d1be6a8337dd7\",\n        \"size\": 121273162\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7685_Weather18.tar.gz\": {\n        \"sha256\": \"8098b2d2019a98f1f7ef38361e1f104852dc95994f9f29c98f18045dce0a3137\",\n        \"size\": 221015064\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7702_Weather9.tar.gz\": {\n        \"sha256\": \"e7869b02a84776e13dd4f4ed9aa2f533519ad234b6b9181ccb116f51f3ae53a8\",\n        \"size\": 238840657\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7735_Weather8.tar.gz\": {\n        \"sha256\": \"867bea18924846ff41c8ebefad0478278d9a28633244db2c293c442037c796d9\",\n        \"size\": 216779270\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7836_Weather13.tar.gz\": {\n        \"sha256\": \"060c250ef4784e07d19994bb7e8b9ce13ec15ef9899391e0376943b595e20f01\",\n        \"size\": 279174198\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7907_Weather6.tar.gz\": {\n        \"sha256\": \"629a42765ef479db34a67ff068ddb4981ebd8d8c70c27e6dc7ac0bb0d21c6ef3\",\n        \"size\": 251670242\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7979_Weather0.tar.gz\": {\n        \"sha256\": \"12614de6d36ef9c89c2d0e63b157adad325e9d1c749faa4deae23afb96d35afb\",\n        \"size\": 193980501\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7982_Weather3.tar.gz\": {\n        \"sha256\": \"ee3d8786d7c0a9f2c08025b6b257b122341770c081b359755c66300d42df6ab9\",\n        \"size\": 213723870\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8073_Weather8.tar.gz\": {\n        \"sha256\": \"da3f953be6935bc83535154ef68ce2b62f717f26c42099cfa5fc79d02b7d6561\",\n        \"size\": 288423933\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8181_Weather20.tar.gz\": {\n        \"sha256\": \"7ceca88f3f319501f3eb838aa66352691b9398dee121d7adf02b74c1fe0e4c16\",\n        \"size\": 214426966\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8209_Weather22.tar.gz\": {\n        \"sha256\": \"74054d0adede6417f53e196f7433b6c0eaba12a3c7627a81beb1aedca656f5c0\",\n        \"size\": 134530598\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8385_Weather8.tar.gz\": {\n        \"sha256\": \"ec42831c71a802627a6e79a115155b2abd7a194d7ff378c167abe843e728535e\",\n        \"size\": 139562493\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8424_Weather3.tar.gz\": {\n        \"sha256\": \"aac3064c58bbbb5a7e4d3e9f8b258ab4831233a45c4ede081ff13d2a0f1806c7\",\n        \"size\": 144734734\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route3666_Weather21.tar.gz\": {\n        \"sha256\": \"0b881360a816006365247d16ec89350d5909be5937b57639a7995277acf1a306\",\n        \"size\": 192470119\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route3670_Weather25.tar.gz\": {\n        \"sha256\": \"07c76af8a21bddff3bbedcbb2f8552fb7cf2f8394d18deeca0bdb7809aaf3875\",\n        \"size\": 114666547\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route3676_Weather5.tar.gz\": {\n        \"sha256\": \"dbd28b244c6fb060773966e294f580c6cbf1dfc7656bf33740003c78295a66d2\",\n        \"size\": 155030743\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route3680_Weather9.tar.gz\": {\n        \"sha256\": \"8d16c2ff59b6fd1bb82f7fff1340931dacd53015329d0b1f1e77f05cb3e28468\",\n        \"size\": 108440279\n    },\n    \"NonSignalizedJunctionRightTurn_Town13_Route3682_Weather11.tar.gz\": {\n        \"sha256\": \"d578fc1f42b8dcaff07b17b171714673704141e011fec0e577ebddd36b6a2337\",\n        \"size\": 92401533\n    },\n    \"OppositeVehicleRunningRedLight_Town03_Route26950_Weather19.tar.gz\": {\n        \"sha256\": \"db79fae9d02471666197daa09dfa1ee812652d836e5156db2728e15cd7e03db2\",\n        \"size\": 72740992\n    },\n    \"OppositeVehicleRunningRedLight_Town03_Route26960_Weather3.tar.gz\": {\n        \"sha256\": \"9834825d0eb3a94130c9412255fa26771b7c9447bf9bcd7ed95ce38efa1dce3f\",\n        \"size\": 112007680\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26944_Weather11.tar.gz\": {\n        \"sha256\": \"4cd181c1fd570bc992d8bc0cf8252e29fb0282f57c61033378dae17fca39c983\",\n        \"size\": 615497283\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26954_Weather23.tar.gz\": {\n        \"sha256\": \"71d3f2412f181bb87e1253dc20647685b536344f5699d88e1c9f5bd0d7f535f4\",\n        \"size\": 162777108\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26964_Weather8.tar.gz\": {\n        \"sha256\": \"f81e68eeb3405dec18d5123cee5b7c4cd693bf941787580783d61d2b1679ad27\",\n        \"size\": 222186229\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26969_Weather13.tar.gz\": {\n        \"sha256\": \"fc036d92c767ad7967a1105ab2f88fc42af79a041efc4dfe6f1ee9552db40f9a\",\n        \"size\": 174666999\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26974_Weather20.tar.gz\": {\n        \"sha256\": \"23fa2bfd6ce17b70b0dbda490cfef4784aab7827c844ad9bf58ef87056d177cb\",\n        \"size\": 157094171\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26979_Weather26.tar.gz\": {\n        \"sha256\": \"6a03a228b23d5938214e20cbb7a4a5e111bee735fd8d359f1b5ed786a0abbf9a\",\n        \"size\": 146961613\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26984_Weather5.tar.gz\": {\n        \"sha256\": \"50416901a80892b2d859f516670f1770d1e06801b0a4aa0e2e34b54f5758c518\",\n        \"size\": 193523714\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26989_Weather10.tar.gz\": {\n        \"sha256\": \"479ae40eda07d18b1af62e6f89e3a78c7901125e2f48d5b4a801b274a2eeb43d\",\n        \"size\": 265073251\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26994_Weather15.tar.gz\": {\n        \"sha256\": \"3c297fd5e6646226f17a8c14970e8bf858e29af7f8ffa4d3bc99624ccb7613df\",\n        \"size\": 601351740\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route26999_Weather22.tar.gz\": {\n        \"sha256\": \"c7083efd85918972c86726a904372732defc95ad46cd501eecaf302808f89607\",\n        \"size\": 210882162\n    },\n    \"OppositeVehicleRunningRedLight_Town04_Route27004_Weather1.tar.gz\": {\n        \"sha256\": \"660e295709c7ed4121a60482d7096098c24edbb374207903a414a3003c6e8aa3\",\n        \"size\": 198052924\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27046_Weather23.tar.gz\": {\n        \"sha256\": \"244ed7e7609db6834781d502da67fe3b667fbd687377aea9111c16369c19f6e3\",\n        \"size\": 591668008\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27051_Weather2.tar.gz\": {\n        \"sha256\": \"5509f2aa39c07deb60e268f9143d12a22b7a38048225e6a41dc2e8cf580d1f63\",\n        \"size\": 157069182\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27061_Weather13.tar.gz\": {\n        \"sha256\": \"fab6c5de6dc22c03cd9c5408a3d7b8c1c5b2553122ad4fc856c36910db007bd6\",\n        \"size\": 117639353\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27066_Weather20.tar.gz\": {\n        \"sha256\": \"3b2862cb7b5b3a56fbef6b6a8159e8b99836258610fdeba870b9d5df06c157b5\",\n        \"size\": 125295167\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27081_Weather10.tar.gz\": {\n        \"sha256\": \"66d08947e9a0aac3ca4ff17263e1c13bea1b67cb5c8d896bca9b5b9312cefb7f\",\n        \"size\": 128376420\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27096_Weather1.tar.gz\": {\n        \"sha256\": \"f1240c65f416dd02db0fba7061368e9eb1e9511c957be473430006e02fddd816\",\n        \"size\": 605690372\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27101_Weather7.tar.gz\": {\n        \"sha256\": \"228d55ae4735b3e92585f0c07e525757435a3bd3f1957f0b0a7cec33cc6e757d\",\n        \"size\": 187387549\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27106_Weather12.tar.gz\": {\n        \"sha256\": \"7f39aceda1e8e93b3eb95cab841a24a60e66bc8cb97de02a7b47387f9f599772\",\n        \"size\": 329141094\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27111_Weather19.tar.gz\": {\n        \"sha256\": \"df72542285270ee1f2c2f0939afff53fa094f0233e58ec73a8712199f6bedecd\",\n        \"size\": 135756831\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27116_Weather25.tar.gz\": {\n        \"sha256\": \"95d8b305bb9d38eb01c0e33c486ebfa06919ec20e84752f74043b27af71d3c30\",\n        \"size\": 110844755\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27126_Weather9.tar.gz\": {\n        \"sha256\": \"6fd43decfa7f3daba91123c68f0d239eb7f2171d0b6838bae7635c2ecfb566a1\",\n        \"size\": 513783307\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27131_Weather14.tar.gz\": {\n        \"sha256\": \"a5669f7b78095c9cf0e1c9dd1fac809c88664684ed28c5103bebb3d1735a1e38\",\n        \"size\": 127882491\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27136_Weather21.tar.gz\": {\n        \"sha256\": \"e10a8051fbf75b6b0570138644bf298dd6e4764c41519e3de888c6340453832a\",\n        \"size\": 660925048\n    },\n    \"OppositeVehicleRunningRedLight_Town05_Route27141_Weather0.tar.gz\": {\n        \"sha256\": \"744122712d5c15079277f98767e16e8e3ff53079f9d4b61a2eb1a46bc6a7258c\",\n        \"size\": 243030060\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2064_Weather3.tar.gz\": {\n        \"sha256\": \"a8397e9c8cdc9fae3e93ec3ff77f4c0d215fcc42f8a01439b29a2ef7d3536535\",\n        \"size\": 153529914\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2065_Weather5.tar.gz\": {\n        \"sha256\": \"891bb15999422f0f30a1bbcb159ed9823f20136eaa37a3e283ebbae287cef65f\",\n        \"size\": 156487530\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2066_Weather6.tar.gz\": {\n        \"sha256\": \"bde9831fb747a6d28ea9674a0f11f63a8f6c4de521764f29ec28cdea61b5bdcd\",\n        \"size\": 130391907\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2067_Weather7.tar.gz\": {\n        \"sha256\": \"0f9b24e2b45f2f599634ef9b1069ca67ad495a21b465c0d9b75ebda397fd799f\",\n        \"size\": 180336104\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2068_Weather8.tar.gz\": {\n        \"sha256\": \"1800e2401fd0c6a9dbf7f7fbc331f19c79e42a7a71592eccc840aebb4c205f3d\",\n        \"size\": 186687464\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2069_Weather9.tar.gz\": {\n        \"sha256\": \"3eb5876d7bfb1760508e00d23168755b95dcdd73830da55a294204d273683fe0\",\n        \"size\": 108839571\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2071_Weather11.tar.gz\": {\n        \"sha256\": \"dc44ff71c673ba2fa566a9f6ee01eaa4ccba90dd43438162b164d0c2460f53ed\",\n        \"size\": 126388126\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2074_Weather14.tar.gz\": {\n        \"sha256\": \"00b67f727c764e711086c88642483fa6617ce123b2431d45618fb7976c073f12\",\n        \"size\": 108641189\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2075_Weather15.tar.gz\": {\n        \"sha256\": \"5d7bcc760c17cd776e1442880840551e807e028601f306ce1d0e59811a10410e\",\n        \"size\": 140178028\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2076_Weather8.tar.gz\": {\n        \"sha256\": \"a0118c11d52e50459e9b726100d9e6bc09be2d1536cf0018efdc7a0d540514fd\",\n        \"size\": 155459838\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2077_Weather9.tar.gz\": {\n        \"sha256\": \"37074c8b8b10b4554586cc33c81dce7391b396f65994e82f16d4dd4c385d5217\",\n        \"size\": 104229706\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2078_Weather18.tar.gz\": {\n        \"sha256\": \"f85f271005d622c3a2fd750eb59b6f2298e82863631a2459a39db1aa70bb7a31\",\n        \"size\": 129281323\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2079_Weather19.tar.gz\": {\n        \"sha256\": \"e2141702a853c843f4f034e8e16f25b02a6dcd6e5c323425ceb14b318f9ffcdc\",\n        \"size\": 198942688\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2081_Weather21.tar.gz\": {\n        \"sha256\": \"60c0d5e7061445182a7e9e4a1a253f64623a77d21ab129fa70a150bdcbee08ec\",\n        \"size\": 189481106\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2082_Weather22.tar.gz\": {\n        \"sha256\": \"f39e88ea4851800732b2b3e2a22a0af59fa6a5ff4436a79d4cb28a7340c2c376\",\n        \"size\": 145191018\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2844_Weather3.tar.gz\": {\n        \"sha256\": \"458632461eefb77227bdf41e6aa9953313f8860c53a176cd44dba42649531c0a\",\n        \"size\": 154049004\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2846_Weather6.tar.gz\": {\n        \"sha256\": \"e92ad5b5cee4126377e3043eec277b684190127d9b26d3fe754a5578ce24893c\",\n        \"size\": 154377976\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2847_Weather7.tar.gz\": {\n        \"sha256\": \"93dd43f67af26bfa14cd8927447eedf31424afd7482f64fb78d965a77df24ea6\",\n        \"size\": 147577747\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2848_Weather8.tar.gz\": {\n        \"sha256\": \"02335e1a0ac2a10b769e9ee86713b3922bd89a12abb0c6f8bc55374371cf94e5\",\n        \"size\": 154512310\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2849_Weather9.tar.gz\": {\n        \"sha256\": \"307016a53ccf89469dd0b632f28dfe094bd46d49527c75f7333454ad88dfaa5c\",\n        \"size\": 176205129\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2851_Weather11.tar.gz\": {\n        \"sha256\": \"ea4c5b16b96b8afbc29b6e6b93a4088af99a1afe19b148e001d4a60b699265f7\",\n        \"size\": 101873632\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2852_Weather12.tar.gz\": {\n        \"sha256\": \"9a4812f93f9f0be3c65449cfddae54dfb8696adaa11f225e05731ad85ea6887d\",\n        \"size\": 108730251\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2858_Weather18.tar.gz\": {\n        \"sha256\": \"9290baca567dd393d22c17fe0730334980eff4b7fb47d491557cac1cfe197727\",\n        \"size\": 216987851\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2859_Weather19.tar.gz\": {\n        \"sha256\": \"7e3baada63c09e1e9ff48fdcc03bea7aa61f4e1b9ee64cd0690a8c17ae304d66\",\n        \"size\": 143853869\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2860_Weather20.tar.gz\": {\n        \"sha256\": \"d4da2a2954d515199af4e98e81891a6fd14954d418c32e9b514bd6b55a6e5e46\",\n        \"size\": 144226809\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2861_Weather21.tar.gz\": {\n        \"sha256\": \"145bcd5598011729a85cb047af6f8686e9fa07e43dcda50012eb1a0435174084\",\n        \"size\": 206270504\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route2863_Weather23.tar.gz\": {\n        \"sha256\": \"01824ba5dd496b4dd1c790ec8c4e003dbb75cd29506907ea12bf5319307299a5\",\n        \"size\": 112784903\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5923_Weather23.tar.gz\": {\n        \"sha256\": \"de529683bf5a2f69ba2333bcbf6bd3411e5e149105ee205476cbec4df51c2199\",\n        \"size\": 113473292\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5924_Weather25.tar.gz\": {\n        \"sha256\": \"5143b9e5de315ea288e4538cf3c1889418261dde247d3e9498f58b70e885bc5d\",\n        \"size\": 77049136\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5925_Weather0.tar.gz\": {\n        \"sha256\": \"ec7c408d9a128aca099b216b8d049b504c255cb37b50f772fdb4ce4ef5e2d037\",\n        \"size\": 144407455\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5930_Weather5.tar.gz\": {\n        \"sha256\": \"a0a7bd18feccd3a1eda24fb28599c171e47cb2c65b6758821ffb5aaab2502434\",\n        \"size\": 136944922\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5931_Weather6.tar.gz\": {\n        \"sha256\": \"5963845076c8c41ff0c16241067392ab5b53c3651d9114b4e80e23e43e6f1bb0\",\n        \"size\": 318452475\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5932_Weather7.tar.gz\": {\n        \"sha256\": \"75175e620d9c659bfb9c752612fb1af7ba7e86f6187d5ab256a029ecb7d32d9a\",\n        \"size\": 133439900\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5933_Weather8.tar.gz\": {\n        \"sha256\": \"ffa62c403fd4dfe5d11ec9a3b3f9fe7f6a6c8b2938677311fa0729f5a8d1325f\",\n        \"size\": 124255107\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5934_Weather9.tar.gz\": {\n        \"sha256\": \"41b0f88020d1a2830110968622578508278bb95dfafcee47ae7e2a6b4431d9e2\",\n        \"size\": 118024525\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5935_Weather10.tar.gz\": {\n        \"sha256\": \"e0cea18c02a0a835a606c58ec5137c44c1782cf0a2107f69159f441b5d940c21\",\n        \"size\": 129847730\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5936_Weather11.tar.gz\": {\n        \"sha256\": \"576ff74a34965a71b8c3c93918d805ca8d1544ce4f29a8c3c77411553cf6d891\",\n        \"size\": 105230770\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5937_Weather12.tar.gz\": {\n        \"sha256\": \"0cd5a95f8b3bec88f86881806ce3a178dbbeddccb8a4c11b105a40d009979232\",\n        \"size\": 177107019\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5939_Weather14.tar.gz\": {\n        \"sha256\": \"575df8260d2745e4da6b3d857dd806496110e44648743afd25a44128ed400275\",\n        \"size\": 209906736\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5940_Weather15.tar.gz\": {\n        \"sha256\": \"5c1cc8412c1a07138b81d7631071209a2baa72166b41a6430f2b5676423f2113\",\n        \"size\": 136175814\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5941_Weather8.tar.gz\": {\n        \"sha256\": \"80b0a11dc2d8112d411f031bbbf2656835c2038e63865aa23e5bed1376bcdaf4\",\n        \"size\": 189095471\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5942_Weather9.tar.gz\": {\n        \"sha256\": \"7496101cb6e47517d1a136c90631111ffd42f56f58e381902d92f537e6e12212\",\n        \"size\": 87220129\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5943_Weather18.tar.gz\": {\n        \"sha256\": \"76a07556b3a8fa3b00dac3893535d34f81d232a1daca5b027201ed69c43cf39f\",\n        \"size\": 142293684\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5945_Weather20.tar.gz\": {\n        \"sha256\": \"70ff2d38936b3537c9c4573be9b1abe5e8f018311da55d78e1fce4d4197eb2b8\",\n        \"size\": 129025707\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5946_Weather21.tar.gz\": {\n        \"sha256\": \"e1f40288e548a0283d7ead9db1d45f540ecfca0cf13329679d55e9608a63679d\",\n        \"size\": 116907031\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5947_Weather22.tar.gz\": {\n        \"sha256\": \"5b001aeaa33d94cf4538e1e9ed95c410914b49c87db2fb51e7b334177cebd64d\",\n        \"size\": 146039839\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5948_Weather23.tar.gz\": {\n        \"sha256\": \"fc2204eb263f5c96a5053b9d912a0df0dc4f2944d4225a828ddb671e917e4a22\",\n        \"size\": 126018808\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5949_Weather23.tar.gz\": {\n        \"sha256\": \"80e38674c81b2ecb6d4d7a0b9ba0335dd0d51006161fc4bd19ba40e82248ccc2\",\n        \"size\": 119151807\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5950_Weather25.tar.gz\": {\n        \"sha256\": \"ad5dc68c560caec9dd63668bdd32407620d40d50bfdb615bcab5e85a7800f6f1\",\n        \"size\": 149907549\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5952_Weather1.tar.gz\": {\n        \"sha256\": \"78b20aca28e4f686dfa73cc53b1f4e85bfbe9484c36f2ce02ba8c85dc57d088f\",\n        \"size\": 160592687\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5953_Weather2.tar.gz\": {\n        \"sha256\": \"53405e9d3d8292203b7615cb0ceff5ee635edb04231a18f66185ea8d8ab05304\",\n        \"size\": 94775382\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5954_Weather3.tar.gz\": {\n        \"sha256\": \"ddfc9dc4b27caa97c456ec50d204d00b78a830fc870cda2fb2162381cbf586ab\",\n        \"size\": 93852070\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5955_Weather3.tar.gz\": {\n        \"sha256\": \"4102fbee2d7850962d553ce867c8be6e61ce0c5139bf3cde1fdf74add0c7daeb\",\n        \"size\": 130016172\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5956_Weather5.tar.gz\": {\n        \"sha256\": \"beb8b0ec437c34bed8ee39f29f30be8bb0c17676a9592ba9e711d0b7288fc0be\",\n        \"size\": 259072684\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5957_Weather6.tar.gz\": {\n        \"sha256\": \"2c968b85ddbcb50fdcddc070c060a4d6516e69df0514af33b232b3644e2b3056\",\n        \"size\": 134966645\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5958_Weather7.tar.gz\": {\n        \"sha256\": \"e90331f75f47c13d74a5fb65ab8cf68eb55512ddc104a01df38ad87edaa2dd88\",\n        \"size\": 125376887\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5959_Weather8.tar.gz\": {\n        \"sha256\": \"ee4db48702df9a24d84fec063d2cc603261f81054acb106b4755475ea9d22660\",\n        \"size\": 156664333\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5960_Weather9.tar.gz\": {\n        \"sha256\": \"99c3ce112d8d3e5c7509163181edc97cc73b29e83204b3aa5b3a90999b4cc278\",\n        \"size\": 105143856\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5961_Weather10.tar.gz\": {\n        \"sha256\": \"3c1a337c69af3583daca5034eaa3e4c4e68d10d3cb60c151c6ab3bd8105de9cc\",\n        \"size\": 145496950\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5962_Weather11.tar.gz\": {\n        \"sha256\": \"0f3d8efe171cdab8abbe57aba20c9fb45b05499c4aa3dcd4db6c8825fb47bb2b\",\n        \"size\": 190482891\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5963_Weather12.tar.gz\": {\n        \"sha256\": \"8c8e4f8eab7e25777536400d3a9a2f1dce37b3200fe81e9b6b19ef1567f013b5\",\n        \"size\": 90165063\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5965_Weather14.tar.gz\": {\n        \"sha256\": \"6ce3ada4474b1cdd43c05122e44aa74ebb46ec88862133ec2f235ad697d31903\",\n        \"size\": 201902516\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5966_Weather15.tar.gz\": {\n        \"sha256\": \"8baf46cdf990e9c0edcb633a75124af9b677fc983ca6e1124b972c93ccc0a017\",\n        \"size\": 118159595\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5967_Weather8.tar.gz\": {\n        \"sha256\": \"518893649e0338682f60b7d215c9518ca7fef2958c565bd64172a253ad6bda8e\",\n        \"size\": 211800682\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5968_Weather9.tar.gz\": {\n        \"sha256\": \"9a9dbca2fe7722c64e7626c2f25b5843f227f6aee5dbdffffedd06b939cdb38e\",\n        \"size\": 116498344\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5970_Weather19.tar.gz\": {\n        \"sha256\": \"efc2fea7cd23fb439e14669d610299d89bed4fe68b56b0a6cd5dc59a0b52bdea\",\n        \"size\": 175981756\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5971_Weather20.tar.gz\": {\n        \"sha256\": \"d409fa343113f9a3072fcaf2132c84762eebb4569ebbe3143869cee50258b525\",\n        \"size\": 127294009\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5973_Weather22.tar.gz\": {\n        \"sha256\": \"e7e8b8613b103baf1c69bbebfd58ae5cb6b113ee7281a392ebe80baf9580c57e\",\n        \"size\": 130330820\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5974_Weather23.tar.gz\": {\n        \"sha256\": \"be6420674fe434012f0a4a5d9aab91074e15f11d3e1c1c7740187d20605a20d4\",\n        \"size\": 126187891\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5975_Weather23.tar.gz\": {\n        \"sha256\": \"36e2372341aa3baeffcddce6ba9e80fc0f1be48c88224c6c2825ed22a45bdf8c\",\n        \"size\": 153435730\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5976_Weather25.tar.gz\": {\n        \"sha256\": \"e7572bbaea7f0a0a004047ba427141f58ef7a746936552effd6ec6410d54cda3\",\n        \"size\": 105976585\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5977_Weather0.tar.gz\": {\n        \"sha256\": \"8d3525804b1ed749de389666581e8be6af6b669d6c206a48c9f9a4f80531ff9b\",\n        \"size\": 189469952\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5978_Weather1.tar.gz\": {\n        \"sha256\": \"ed8663b894a00d9cb689a5ff8337a76c6c2f3ef0d93123fe860f54729f151aac\",\n        \"size\": 136498359\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5979_Weather2.tar.gz\": {\n        \"sha256\": \"b263f396bf4f5da1847afd51868adf27db739e54894a8c15d78c297e30f53f84\",\n        \"size\": 136107147\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5980_Weather3.tar.gz\": {\n        \"sha256\": \"6e4b82901fb0ffba55b75996fe0a321aebc18338ae395e54adfdc3ec0ddbd53e\",\n        \"size\": 131744807\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5981_Weather3.tar.gz\": {\n        \"sha256\": \"35700d39cfa061820aac60c4f7cee5103ce71d638d503f192aea4fa34acb78ee\",\n        \"size\": 148068934\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5984_Weather7.tar.gz\": {\n        \"sha256\": \"248159fa4225575055b77dcb59710a2cec6895edc1477532767dce6910834f52\",\n        \"size\": 138271607\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5985_Weather8.tar.gz\": {\n        \"sha256\": \"0df9bd143a1512cbc0c69e81d027764cb475c17dbd4ff59fd4a0a566079b352e\",\n        \"size\": 179035816\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5986_Weather9.tar.gz\": {\n        \"sha256\": \"bceb72a63c23165f0ac7811f62a66dbfc4875030cbd12e1ed2815797adedefb6\",\n        \"size\": 191029766\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5987_Weather10.tar.gz\": {\n        \"sha256\": \"89e5b9447a5b5e21d6065381deb076cb8bfb9b895757fd98c4f6c5ea5e4ab2ef\",\n        \"size\": 110540482\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5988_Weather11.tar.gz\": {\n        \"sha256\": \"e287aa2754c05e3badb42aad539f3c1af90f51753db63bc8f97c4c4850c110a0\",\n        \"size\": 83293630\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5989_Weather12.tar.gz\": {\n        \"sha256\": \"bab2534edef3819690284a44044960fe792129ba1abe97e1429269b917309c91\",\n        \"size\": 150152842\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5990_Weather13.tar.gz\": {\n        \"sha256\": \"bbaab01f5225633eb39f5444c91a78a916e0ccf96008b1ed71225fd8fc567c49\",\n        \"size\": 109433879\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5991_Weather14.tar.gz\": {\n        \"sha256\": \"fc07b417953b9faad9b2b422fb2ae655fbe76966e59411f70fe2e7c27714785c\",\n        \"size\": 122460443\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5992_Weather15.tar.gz\": {\n        \"sha256\": \"54d2b56e78ad68636bc5b57eddc72930f15f3422a225986042688ca62bfab5e9\",\n        \"size\": 137861632\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5994_Weather9.tar.gz\": {\n        \"sha256\": \"013612ef9b1bfa5251a9a9ae57b77e2baf6c9430532b72a18574277f493f2785\",\n        \"size\": 135970913\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5995_Weather18.tar.gz\": {\n        \"sha256\": \"fade124134fec2a43a01c8aa5535b0129a065b8bccb620dfcc17d8abd40ad868\",\n        \"size\": 218181186\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5996_Weather19.tar.gz\": {\n        \"sha256\": \"8c1b4865fd5ca677ad75a775b3b854a80a28ecfc604a76969baca2f4df25c830\",\n        \"size\": 133644758\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5997_Weather20.tar.gz\": {\n        \"sha256\": \"9e590c80968661b135885a00cb1075d527278661be553b38a95064c0410f74a9\",\n        \"size\": 145039316\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5998_Weather21.tar.gz\": {\n        \"sha256\": \"dd975af45ad9483a38d7b10ea03459bdf035390a6e8ca3d399f17c6a8f8a4c0b\",\n        \"size\": 151532568\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route5999_Weather22.tar.gz\": {\n        \"sha256\": \"f5f9a30cc3b76b2e411132c375433afb5ef1a99a410b8a886ee145ea5056080b\",\n        \"size\": 144682195\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6000_Weather23.tar.gz\": {\n        \"sha256\": \"9b6bde92374b52fc01d0c1aa3369118c96276ffe5ab6a7afcc2f8009d62cbc88\",\n        \"size\": 121737235\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6001_Weather23.tar.gz\": {\n        \"sha256\": \"e84a58f1056f0338b70798d7774b9423f6e2a499ea9b99acbfd8a19a88d57124\",\n        \"size\": 96035596\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6002_Weather25.tar.gz\": {\n        \"sha256\": \"bd84b45fd0e71b24d26ace903b920c1fafdac76f7d04bff00a8c46a456e02abe\",\n        \"size\": 96212390\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6004_Weather1.tar.gz\": {\n        \"sha256\": \"0ec6a80a16da607743520d82e4d67fff3467ff449e750ddd98138e1eaeab4a42\",\n        \"size\": 158624067\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6005_Weather2.tar.gz\": {\n        \"sha256\": \"a82c1626977088913ee84491fbf5bc06cb4ff6dc624e6b27933da2a702a05574\",\n        \"size\": 200572425\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6006_Weather3.tar.gz\": {\n        \"sha256\": \"18f6899f119d7834d5c90a73353ee7ff0274f2bda41a01105bc4c91a01538081\",\n        \"size\": 140439812\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6007_Weather3.tar.gz\": {\n        \"sha256\": \"76022fa63f5460ee9476164cad64c677cf871aff574c7a1e242d5861e987e236\",\n        \"size\": 234934460\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6008_Weather5.tar.gz\": {\n        \"sha256\": \"93daa23d4c449b54146f459bc156930fcb606246a24ac2088f970029929a47be\",\n        \"size\": 106220426\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6009_Weather6.tar.gz\": {\n        \"sha256\": \"c12ddfa96310c24111b33242341c43c7dd379810ae1b26611cd9796c2db13538\",\n        \"size\": 120538502\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6010_Weather7.tar.gz\": {\n        \"sha256\": \"019c322f56cdeb20cf65b912dba81be701e3ddba61e60499b9d5c29c718b0d81\",\n        \"size\": 209220744\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6011_Weather8.tar.gz\": {\n        \"sha256\": \"5a8c3d4dfb62d6cec062bdd28a334405395999c0722d7c34285db8ec3afff347\",\n        \"size\": 116010342\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6012_Weather9.tar.gz\": {\n        \"sha256\": \"36424242cba9140970a2d8f41d9acb9d31890ae8f9de4c8840bddabc58f57b60\",\n        \"size\": 106915557\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6013_Weather10.tar.gz\": {\n        \"sha256\": \"c9463e861733426ee8c1bbea99e14cc947a6e07ce988541dcf3a49ca0924b1af\",\n        \"size\": 155637519\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6019_Weather8.tar.gz\": {\n        \"sha256\": \"dcc1450608306e23f9207e44d8a336b4d2de5b5d502af719bb13e8bd62e481b3\",\n        \"size\": 127249139\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6020_Weather9.tar.gz\": {\n        \"sha256\": \"2ced4b224fd1f843c1c0fd784db93e2ea8c15264d41cc138ccefb61ae448883b\",\n        \"size\": 156651393\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6021_Weather18.tar.gz\": {\n        \"sha256\": \"fddbebc660e81f57457e920ed531bb46b976f6b22814c7a316e809a047cc5988\",\n        \"size\": 155561737\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6023_Weather20.tar.gz\": {\n        \"sha256\": \"cae2e149e9f81f865385caeb2070e42e84d771d749ac186f6d36ff3d50cbab42\",\n        \"size\": 166730965\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6024_Weather21.tar.gz\": {\n        \"sha256\": \"10cbbe4671a92683d5ee3df3488b3594e65d09ee97689d8c0e5b2e80bad98720\",\n        \"size\": 95667843\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6025_Weather22.tar.gz\": {\n        \"sha256\": \"864c01377933c7870681d0193a285ff5db03d5784941bbc185552868fd42579e\",\n        \"size\": 183788420\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6026_Weather23.tar.gz\": {\n        \"sha256\": \"d70babe8fd4ea410a52eb4c51f1a95d4925727bfb3532515dc083f77afbb92ac\",\n        \"size\": 121063510\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6027_Weather23.tar.gz\": {\n        \"sha256\": \"4bb914d55a02ca791e4a2528541b6a083b8f1ce4920113d529738668cbe112b2\",\n        \"size\": 273767973\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6028_Weather25.tar.gz\": {\n        \"sha256\": \"d9a02436ecf516a99d99d1f7858700cf32ac28981e19ca8e88be36f04a221cbf\",\n        \"size\": 81301626\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6029_Weather0.tar.gz\": {\n        \"sha256\": \"c7b611a3cb270e24f062ba4d2eb6b64226c18b30c301615986bf4d95445c38a1\",\n        \"size\": 143073792\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6030_Weather1.tar.gz\": {\n        \"sha256\": \"586d7a26c12420973e93bc841f455f96f6ed17497c42fa1fd23d94658cdd74b5\",\n        \"size\": 133384520\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6031_Weather2.tar.gz\": {\n        \"sha256\": \"cd821e4a71e05bf3f5bc49c479f76fc7557a42e3853cfc432631c8afcadcf69c\",\n        \"size\": 164089749\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6032_Weather3.tar.gz\": {\n        \"sha256\": \"9394d2c70056a53b35ca6a8281195ace83fb8cd1c89aeeac91e6adc75e72b5e5\",\n        \"size\": 120654299\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6033_Weather3.tar.gz\": {\n        \"sha256\": \"4afadaf56bd58d709540549b58f462f9d4c274fcf9e872366da79ffb4b681148\",\n        \"size\": 143963936\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6034_Weather5.tar.gz\": {\n        \"sha256\": \"6ada0a5c77d6df730094516ba6ce53dcf2fdc7e9151954d9b3dc8a33f9b31537\",\n        \"size\": 220946550\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6036_Weather7.tar.gz\": {\n        \"sha256\": \"d760c250f16b21579b1fa0009cec22393cabad79b6cbbd3ba45148ecf6d45ac5\",\n        \"size\": 133546714\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6037_Weather8.tar.gz\": {\n        \"sha256\": \"9cc4156559ef429c2257ec3e02348d01a1894fad2563c50723af404289fe7019\",\n        \"size\": 144569559\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6042_Weather13.tar.gz\": {\n        \"sha256\": \"6279d560f2acdad63f26c1f60078fd674bdad4ebfb3fc423440ffc4af762cbeb\",\n        \"size\": 102495029\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6043_Weather14.tar.gz\": {\n        \"sha256\": \"40e754fa8bfa354c4e532b44a8de3a0b6b51a377644853bb00ab741ccc8822cc\",\n        \"size\": 106345770\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6044_Weather15.tar.gz\": {\n        \"sha256\": \"7a85f287413bbf34a2519738f36a954cff251b89b1715b6d1207bd586536e984\",\n        \"size\": 105077690\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6046_Weather9.tar.gz\": {\n        \"sha256\": \"1ef8da3e337397b567cfdfa6cd1033c730d9a86476525a2966e194651e63c95e\",\n        \"size\": 98328033\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6049_Weather20.tar.gz\": {\n        \"sha256\": \"690c7cac04da84564ae811ce082f5eb4d0afb1240b70acd886e63407d2a669f6\",\n        \"size\": 107378414\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6050_Weather21.tar.gz\": {\n        \"sha256\": \"2c1fbc0741f4b9bb536406dc7f4248cf80298c5714cb6da61886193751fc5aae\",\n        \"size\": 90962036\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6051_Weather22.tar.gz\": {\n        \"sha256\": \"684f1dcb62c464b8b09ca35fdecb31006c09704402a9f470397792e29d971d1b\",\n        \"size\": 107770392\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6052_Weather23.tar.gz\": {\n        \"sha256\": \"950688093700aaf707638fc16ceac16a7b80896d10369a6ca01465e4c6a6b7e6\",\n        \"size\": 129490870\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6055_Weather0.tar.gz\": {\n        \"sha256\": \"4872ae730566498f3ba32599c8c568d104e08e26e984eb43890eaada91be6e51\",\n        \"size\": 205164718\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6056_Weather1.tar.gz\": {\n        \"sha256\": \"8f4065690da941622cea6b1eee7e659968f0db4a2a53f5e0807aa3b1c107f517\",\n        \"size\": 144833228\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6057_Weather2.tar.gz\": {\n        \"sha256\": \"ce65a00903c470bcf74e8a4eb2eae31ccf7787efca93acd7354b18a1b44ecca7\",\n        \"size\": 143617849\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6058_Weather3.tar.gz\": {\n        \"sha256\": \"34a5e6305e242eb48e7af5b15079d59e874c45befec85da23befa779bfe1bd11\",\n        \"size\": 144454521\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6059_Weather3.tar.gz\": {\n        \"sha256\": \"e707194bd056d13cad5d053e813dc6a2eb3b3dc3e05d8444f0e325bcfbc9ec74\",\n        \"size\": 198669090\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6060_Weather5.tar.gz\": {\n        \"sha256\": \"48435fc84d4c217161ad08f3c2b9e9e219b1c5f61dfeddbb27a970dc16945d1c\",\n        \"size\": 112909504\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6061_Weather6.tar.gz\": {\n        \"sha256\": \"e4835d317921c6c30579542781dd75afec257d19b5e5f7445f66a7b6e17d6cb3\",\n        \"size\": 144586585\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6062_Weather7.tar.gz\": {\n        \"sha256\": \"2413c252fa771fa613d840a434fb8c8dc3e56db58d250e40f9646e8cb1defffc\",\n        \"size\": 184465498\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6063_Weather8.tar.gz\": {\n        \"sha256\": \"925ceb49245cdcab7c69fe0a2bc647e2c6e30b0d28ce86fd7eb49e12eea9a136\",\n        \"size\": 75945522\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6064_Weather9.tar.gz\": {\n        \"sha256\": \"51757417781bdd1300fcd9d171b0a00d6e8abf236f03584ee013e672923d9074\",\n        \"size\": 90911446\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6065_Weather10.tar.gz\": {\n        \"sha256\": \"b0f700f04ce5276b1b93051e381e18b01020e38b2912372805b1bdc4ea66c598\",\n        \"size\": 154207351\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6066_Weather11.tar.gz\": {\n        \"sha256\": \"6a2914fed9d0ef00068492e23a88a5e0424ce37bf613598d2b9ae3344169493b\",\n        \"size\": 165410425\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6069_Weather14.tar.gz\": {\n        \"sha256\": \"67bea7b99724667cacd3764445a8c955575e5ff59cbebf1abb7e9b48d310210c\",\n        \"size\": 128483710\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6070_Weather15.tar.gz\": {\n        \"sha256\": \"ecee2f691f2386a74559cd718a379dd50a375459e0f54a7afba15f8a905615fe\",\n        \"size\": 118669978\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6071_Weather8.tar.gz\": {\n        \"sha256\": \"4b716c4375e32b1c0d8fdab3821ccc1e234403a721c4007377266b121d8187eb\",\n        \"size\": 113896186\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6074_Weather19.tar.gz\": {\n        \"sha256\": \"98e7b0138494d67326143bb7e9fb90995d3f64608f4d0092518ab96646720e7c\",\n        \"size\": 180654851\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6075_Weather20.tar.gz\": {\n        \"sha256\": \"0481007dcf0394ebdfdf79c8e3e8f9b61161b913da7a1c4a488641df54eedb44\",\n        \"size\": 131044783\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6076_Weather21.tar.gz\": {\n        \"sha256\": \"149c5fc0f0a32bc85795990aa3d068e70d3a123cf382bd855ad4485cd06a8067\",\n        \"size\": 253139186\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6078_Weather23.tar.gz\": {\n        \"sha256\": \"37554488d6a8f30e1751089acd437e405e2d3cf7ec688f45281721b482112961\",\n        \"size\": 119017068\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6079_Weather23.tar.gz\": {\n        \"sha256\": \"1e56e5799687749c1547e4634983cb3b1b79313aaaa131199fd4ecfe15610ec6\",\n        \"size\": 127492911\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6080_Weather25.tar.gz\": {\n        \"sha256\": \"39da40059dfffc8cebdc4e550b5939448a71295c583960e1c711f75e22229f08\",\n        \"size\": 101189001\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6081_Weather0.tar.gz\": {\n        \"sha256\": \"45e4ece8a44fb0fcb5186e31b7ac3f7e0a73128bde53f4e0fb03cabf08ee71ea\",\n        \"size\": 126594439\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6084_Weather3.tar.gz\": {\n        \"sha256\": \"c70365a3babc55985da5b0f0cc51b1738a66a9b17a34fa52c62773958147eb2b\",\n        \"size\": 148717007\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6085_Weather3.tar.gz\": {\n        \"sha256\": \"465c70062bc5a1d92309a6667a835dbd562182601c574787431c8e197e4bb5a4\",\n        \"size\": 149513677\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6086_Weather5.tar.gz\": {\n        \"sha256\": \"82a74978a3045216adfd673c7734fce8991730fd7d7a013ef6943b8ba7656a16\",\n        \"size\": 136243100\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6087_Weather6.tar.gz\": {\n        \"sha256\": \"3643f09d588f4331a62eb0b44a84c523dc955cd4284dc61db0753e3dc73c63f2\",\n        \"size\": 87851512\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6088_Weather7.tar.gz\": {\n        \"sha256\": \"e9865bf0ffe0d78ee36d343cff3d2299c500b7308f9620c169427b43da953d7e\",\n        \"size\": 143902835\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6089_Weather8.tar.gz\": {\n        \"sha256\": \"3b16fa49aaf38f861995d31b6668dcc79fe67672d3066036907231040bb06bef\",\n        \"size\": 121741253\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6090_Weather9.tar.gz\": {\n        \"sha256\": \"bfdee0191cee98bbbfede2448309f1fa3faae88a2bbf1dd72c0dbcda035a2be2\",\n        \"size\": 117793497\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6091_Weather10.tar.gz\": {\n        \"sha256\": \"d121cf17ae894f1cc80515ed8ca2e9d9aa1908b1a277c610028ae63e8194a986\",\n        \"size\": 150922537\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6092_Weather11.tar.gz\": {\n        \"sha256\": \"376a2f705db66cecf9d1f9380214c2ec2bb822379ef2e042bdcd1edcb8c7f163\",\n        \"size\": 121046013\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6095_Weather14.tar.gz\": {\n        \"sha256\": \"cdec0c928f45420d4e57ce35a62ffce82393499de46d026bd3df9ea8e6dfacbc\",\n        \"size\": 129504317\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6096_Weather15.tar.gz\": {\n        \"sha256\": \"b0418ab2c409078c6a720402cbe66ad71109a0daa6f3f8faa2e9538a04bdcec1\",\n        \"size\": 121569090\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6097_Weather8.tar.gz\": {\n        \"sha256\": \"bc1ba07205489f72af699587643e2dad5f6a605923fc88f4b032638d1463f550\",\n        \"size\": 138558492\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6098_Weather9.tar.gz\": {\n        \"sha256\": \"4ec726cd2a432ee0989d97db749061d06175f1b2ee115483d360c5779e5d4523\",\n        \"size\": 175180762\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6100_Weather19.tar.gz\": {\n        \"sha256\": \"66fabf236dd04187ca5dc345fc0874aacad303be6f38ed171c1e864aac4b4f20\",\n        \"size\": 152167243\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6101_Weather20.tar.gz\": {\n        \"sha256\": \"f1a057b09f50ecde151a69f029f09726a3ca7b5e2e68cf9fd45d6d4afa45d2d6\",\n        \"size\": 135374985\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6103_Weather22.tar.gz\": {\n        \"sha256\": \"9a68277564a9edbab1920294e09088a1d801de98ea168273e821ec72ffde74a5\",\n        \"size\": 81966323\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6104_Weather23.tar.gz\": {\n        \"sha256\": \"5d4e1aade89ff858f7143254b8abec835105d111bf7396653d2470943f958ad9\",\n        \"size\": 118195107\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6106_Weather25.tar.gz\": {\n        \"sha256\": \"8c44f86ed890c73a30ab80c4f09cd64aa76b2ba5927fb7d154598d436cc59959\",\n        \"size\": 96271213\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6107_Weather0.tar.gz\": {\n        \"sha256\": \"c27a613306fe590bdf016f2e0941a16abe11b4d11c65c582b466a11997148478\",\n        \"size\": 286328878\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6108_Weather1.tar.gz\": {\n        \"sha256\": \"1a6293a2937d8e7d8eb61aac33d2441b7edcdbb3168c8ad411fcda31ef2ae2bc\",\n        \"size\": 134451690\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6109_Weather2.tar.gz\": {\n        \"sha256\": \"a2c7a6a046ddcefd1965c749286d0c145b2b0d1f96564eb1e05c93bb5f7a1326\",\n        \"size\": 114387328\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6111_Weather3.tar.gz\": {\n        \"sha256\": \"d59492ea63ffad589c0109c3be419b2b60176ed11a4a6f0d2cb558f4bd5d7e2a\",\n        \"size\": 165122073\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6112_Weather5.tar.gz\": {\n        \"sha256\": \"beb4943c2f056532d56292a19610071f31942f1e5f0bbbb7dcb402da17344c06\",\n        \"size\": 161308631\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6113_Weather6.tar.gz\": {\n        \"sha256\": \"539fbbd085da3e1b395fadbff444fabe5ac32cca7fc205cc8aa0acd72a2c3c8e\",\n        \"size\": 119158331\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6114_Weather7.tar.gz\": {\n        \"sha256\": \"31d7fbe0f7c3afd2bd8cc7ae7016263b2ebb519dbb4473e2ae4535bdf0c53c17\",\n        \"size\": 153251121\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6115_Weather8.tar.gz\": {\n        \"sha256\": \"033b55e2549d17c4744fa9beda407e930bdfc13abc96d710abad1af1cb00792f\",\n        \"size\": 139175035\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6116_Weather9.tar.gz\": {\n        \"sha256\": \"4375243962e8d889eaa5e6a046a871aad67bcb802ce80ed80b57a0b8625c286c\",\n        \"size\": 173433367\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6117_Weather10.tar.gz\": {\n        \"sha256\": \"b61deb43098a75e59b6c21da33b20ce5d6cb77ec3a4b4ab77d341966288b58c9\",\n        \"size\": 144145684\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6118_Weather11.tar.gz\": {\n        \"sha256\": \"b4b20e6df5dd7b86a6cd36084bb484128c955e367e9a6e80ff7626c47063bde7\",\n        \"size\": 148632498\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6119_Weather12.tar.gz\": {\n        \"sha256\": \"899f8e647234d4d913b5f95db2324d5c30d17fd7a0cf3ec8bcda1082275f258a\",\n        \"size\": 93907600\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6120_Weather13.tar.gz\": {\n        \"sha256\": \"f538699a75df1127a27ccc4776526f91364866b30988b73dcd89077198331c09\",\n        \"size\": 204189784\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6121_Weather14.tar.gz\": {\n        \"sha256\": \"2b61cb345a15d328ddeb0dbb051e09113d415cd439a9fe47a65c1fd2a5e056fe\",\n        \"size\": 112953187\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6123_Weather8.tar.gz\": {\n        \"sha256\": \"2af21b712c93558f00bbb5dbc8b0172b4fff3b7c600136f1725480ef7896a9c3\",\n        \"size\": 175451347\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6125_Weather18.tar.gz\": {\n        \"sha256\": \"9045d37dc934933ca394441b71d56c12b8f1a7e9cf8d4a84e9e0ac964ceb85ba\",\n        \"size\": 112810543\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6126_Weather19.tar.gz\": {\n        \"sha256\": \"74a426c5b5a09177392424ea48343030c5438a0340650c0d39af0e1111e51e94\",\n        \"size\": 194958574\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6127_Weather20.tar.gz\": {\n        \"sha256\": \"ed666ce225628bca3fdc69baaa13dada5b313e094d13c62e466c3081660e5328\",\n        \"size\": 136087111\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6128_Weather21.tar.gz\": {\n        \"sha256\": \"b51f12567567ba27da01b1bf963da6857f32540e59d2dab43d5a837a4d2d9ac2\",\n        \"size\": 99798481\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6129_Weather22.tar.gz\": {\n        \"sha256\": \"071a04d210ead806510232feb671902c3588e3a900889987a810ac1c529d5eee\",\n        \"size\": 188774497\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6130_Weather23.tar.gz\": {\n        \"sha256\": \"57303b748e684e0e4676e0d200d4861b2d8181ee0f3c32fc8857bac01d28e0fd\",\n        \"size\": 115520998\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6131_Weather23.tar.gz\": {\n        \"sha256\": \"eed348dac64ac6aa5fa4df8bff3226b8b506c197c916707013b34e97b8b82410\",\n        \"size\": 213765813\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6134_Weather1.tar.gz\": {\n        \"sha256\": \"be1245300c1db40f4d1355b135c098c160078b71b93b7d7c90dae79c35b6181c\",\n        \"size\": 191784287\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6135_Weather2.tar.gz\": {\n        \"sha256\": \"fd9df11bf09090d47949d1089bbe329816430a698ed86c941b5a44d60c4f2054\",\n        \"size\": 145181462\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6136_Weather3.tar.gz\": {\n        \"sha256\": \"a5fb9ebe73ee49c8dddacc6c568d12603825084cfdb6d0a664a15b477674eb25\",\n        \"size\": 125321184\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6137_Weather3.tar.gz\": {\n        \"sha256\": \"c511726047e4d493e64aa7fe1f2b53f9ce89afb411707e25cd4332755a86c397\",\n        \"size\": 122882461\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6138_Weather5.tar.gz\": {\n        \"sha256\": \"3f374643eb5d0ffad2aa0a015c9910fdbf62f617096191cc64de0b6d277a035f\",\n        \"size\": 137279208\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6139_Weather6.tar.gz\": {\n        \"sha256\": \"62f4cc778ef6ab6dc8af8b719c6c13ff21ece98f7d43a2deb592f7432985dc2d\",\n        \"size\": 299799649\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6140_Weather7.tar.gz\": {\n        \"sha256\": \"7a97fd1920df72a191c3aa115494722edef41dbe8dccf1074be6f0e33a182959\",\n        \"size\": 203263269\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6143_Weather10.tar.gz\": {\n        \"sha256\": \"fb90124fc6a37ac3ee40a264794c38c9797dfafc4cb97b06ac63552ceda2bbdb\",\n        \"size\": 118326487\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6144_Weather11.tar.gz\": {\n        \"sha256\": \"929f9a9ef94a26b7fd2b7e9e52e63246bacd11ccba4786980dee0caf42018e97\",\n        \"size\": 178550719\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6145_Weather12.tar.gz\": {\n        \"sha256\": \"984210a49aee9bec55c642add38a298bd1696b25488eab0f3e79784f314dd3ca\",\n        \"size\": 92930628\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6146_Weather13.tar.gz\": {\n        \"sha256\": \"aaeea97b0bd6a48005077762bca7c35778a0329b4cce712dd794e6858f233b30\",\n        \"size\": 87420619\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6147_Weather14.tar.gz\": {\n        \"sha256\": \"2279414d05f6a7a89640a32868877815b6a2ea067a48dc262be9c1e9f7020c55\",\n        \"size\": 132581236\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6148_Weather15.tar.gz\": {\n        \"sha256\": \"5d84b62ac14e59f71f8bde6c857c1c324dc7c4a5c96a6835022d2532082b5bc7\",\n        \"size\": 116022034\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6149_Weather8.tar.gz\": {\n        \"sha256\": \"a5f83ab62e2d72e3156d4e130f12e57fa71a1adc71b2765e7e0c85d5537a34ad\",\n        \"size\": 102865447\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6150_Weather9.tar.gz\": {\n        \"sha256\": \"c2beab01d7c7a0eba06d7edec336b57968a3ca020854960065441a91d57172e4\",\n        \"size\": 118881775\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6151_Weather18.tar.gz\": {\n        \"sha256\": \"3d1cb42b0c77dee4a5a751fdb037e74bd6f35b6550e6d6cb90726929170f2b4d\",\n        \"size\": 166678003\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6152_Weather19.tar.gz\": {\n        \"sha256\": \"de69dd771d49819740a4208ecd646593b1bd84182c6bffb17d64feaad7a3278c\",\n        \"size\": 136210927\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6153_Weather20.tar.gz\": {\n        \"sha256\": \"126d7d28a39d97ea47195be95e1d1023d197b2d91e80870e9109f367dd52b052\",\n        \"size\": 125029955\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6154_Weather21.tar.gz\": {\n        \"sha256\": \"e28c0c03003cfcfa09d5f1ef49292810d70e838c762b95a80fdab81278fbe619\",\n        \"size\": 133368902\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6156_Weather23.tar.gz\": {\n        \"sha256\": \"cdcadb137197920e0a65782382816d587772441b6bfff83af8469051d4c4e6f1\",\n        \"size\": 80677754\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6157_Weather23.tar.gz\": {\n        \"sha256\": \"83bd86157ad274e347214b29d43a97e9d3063d54078212bc133e6a362218f878\",\n        \"size\": 104780902\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6158_Weather25.tar.gz\": {\n        \"sha256\": \"37f169afaab845e647e3de3a3cae43443a58523684658d2f022319d57ee86a61\",\n        \"size\": 126190642\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6159_Weather0.tar.gz\": {\n        \"sha256\": \"ac7b093ea308438231579022f5072978295d29023368d19ce5a1d249dbf60567\",\n        \"size\": 133751873\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6160_Weather1.tar.gz\": {\n        \"sha256\": \"4a8ebc9247cd3401117e2f0b32909452bdac8a2ced959d8cd0495c6f17d77ff8\",\n        \"size\": 163998432\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6161_Weather2.tar.gz\": {\n        \"sha256\": \"ec7bc7e135520657bb69d1791bd6c9dbb53e6d5db4ce96602a7fda4ea684acd0\",\n        \"size\": 114956678\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6162_Weather3.tar.gz\": {\n        \"sha256\": \"8cd3e107df09fbb621b0d0a6ac9ed3e94809b0b632f57409acad1e83a4c7ff51\",\n        \"size\": 130430144\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6163_Weather3.tar.gz\": {\n        \"sha256\": \"bb81523c9e24edf2573deb055a490425b3b4f910c1081b3cad475449abd26d1a\",\n        \"size\": 140994952\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6165_Weather6.tar.gz\": {\n        \"sha256\": \"94211a554463d48cf1b2faa2f78fc9353dd9aba6b60a491e5e066b1c13182ef2\",\n        \"size\": 502996142\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6166_Weather7.tar.gz\": {\n        \"sha256\": \"2c304a1e25c9ce8a43d10b17e3efd7e2babdaabd07ac8bc61ce0e184e7f23b33\",\n        \"size\": 103480247\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6167_Weather8.tar.gz\": {\n        \"sha256\": \"2458cbf33f5baeb70823af3e5a4eff4ee4d91418783d9dad1d2e87f35b287d04\",\n        \"size\": 145132134\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6168_Weather9.tar.gz\": {\n        \"sha256\": \"4cd6116c58b7697ea59126b5b1800bad6c1be78e4f370f38f1659f10fe772350\",\n        \"size\": 113233849\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6170_Weather11.tar.gz\": {\n        \"sha256\": \"cc4ff16adc5ac46a4eeded0c32d0bbe76caf1e0aa18854dca41930cce3f5a0b9\",\n        \"size\": 105099613\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6171_Weather12.tar.gz\": {\n        \"sha256\": \"4deb408b35bb6ecfed1ab1096cc3da314eca0848afde049971d7972366d108b6\",\n        \"size\": 112272960\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6172_Weather13.tar.gz\": {\n        \"sha256\": \"9dbfe52952880211cd2320cbcd2fa9395978258a8c5544458d991c0f74cd864b\",\n        \"size\": 118094243\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6173_Weather14.tar.gz\": {\n        \"sha256\": \"bdd550e796c3aa0ceea1cb2e1d9435a0fe182de79a7085ce9b541f784816af57\",\n        \"size\": 320690774\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6175_Weather8.tar.gz\": {\n        \"sha256\": \"9c1aea9c581197fd3a9a76cd0930c6a0d5ae1849a9cfe401d20fbbb4a263c8e5\",\n        \"size\": 142676791\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6176_Weather9.tar.gz\": {\n        \"sha256\": \"c1fefbb3aa22025d6dab2ef5db11abb67c3846501f8cfd23aaa20610c910d62f\",\n        \"size\": 243149466\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6177_Weather18.tar.gz\": {\n        \"sha256\": \"c31b3144b4d370a1c5892c8ba73d2ed8f2da2d6a9e440176d3d1b212e3d529f1\",\n        \"size\": 163030334\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6178_Weather19.tar.gz\": {\n        \"sha256\": \"2489bb3935fa126dc5b44b782799fcec475c6b0259ada530bce6119090ee803f\",\n        \"size\": 149926945\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6179_Weather20.tar.gz\": {\n        \"sha256\": \"ed5fbdd24c6acee97ea1f2fdb72584d8800809cf47e8e6e2c9387617767c57d6\",\n        \"size\": 197940536\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6180_Weather21.tar.gz\": {\n        \"sha256\": \"2ff93a7974e5f0a6fd36c7f58850b6359639a7fd5a4c60b752b6bf6f5971c5a2\",\n        \"size\": 186139998\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6181_Weather22.tar.gz\": {\n        \"sha256\": \"2c00d9b39c36b66c2f85e38de3aef86706b2f6c3b5634170624f8b7fcfc65520\",\n        \"size\": 103354548\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6182_Weather23.tar.gz\": {\n        \"sha256\": \"382136b53284ec00731cd08590fd483bc1f0e8b202a85eca9996610980a3cca7\",\n        \"size\": 125423868\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6184_Weather25.tar.gz\": {\n        \"sha256\": \"d1d3e66ccccec7af92115b38053d00d9d6dcfbcb8df7060e5c5cf4f3d78c087a\",\n        \"size\": 104311164\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6185_Weather0.tar.gz\": {\n        \"sha256\": \"6a80b4d21998a330cbbe87211aa3d4372dbe6c4265ffe4af5c54da355417c368\",\n        \"size\": 149457301\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6186_Weather1.tar.gz\": {\n        \"sha256\": \"4292630286f8cd1306edc05791d95caa06b70db4921be8d73fe4a9aa2e00bcf9\",\n        \"size\": 105416476\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6187_Weather2.tar.gz\": {\n        \"sha256\": \"992d934291d9d470bef73e931c72ec790f4470f1589e6260c6957286221e81eb\",\n        \"size\": 126421669\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6188_Weather3.tar.gz\": {\n        \"sha256\": \"88d27e3f92657e6455902ef6c04e5f5dba7a1467c100e58eb9f8fb76eca18a32\",\n        \"size\": 110456300\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6189_Weather3.tar.gz\": {\n        \"sha256\": \"86bcd1f640a6b6e9b29f905aab35f1531ee68ad197e993bf94fdd09771826e39\",\n        \"size\": 134055799\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6192_Weather7.tar.gz\": {\n        \"sha256\": \"d711eac336a24a4bcc9b1317755097458ea28ec255ca9b600d5aa0355e32bea7\",\n        \"size\": 121083087\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6193_Weather8.tar.gz\": {\n        \"sha256\": \"9746b960a1256643dbf1ba2e8a24fa1e63fc4bdbc2fc84ebb2c117d3b4b1092f\",\n        \"size\": 115296981\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6195_Weather10.tar.gz\": {\n        \"sha256\": \"9015a29e953ddcc1a740398b76c10d24eea303a45c027c2570c1d1a05756685f\",\n        \"size\": 145674965\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6196_Weather11.tar.gz\": {\n        \"sha256\": \"2b0646c6747463d53df84d4a63b21bec40a577944642736e9c1109b71db1a9d7\",\n        \"size\": 116321037\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6197_Weather12.tar.gz\": {\n        \"sha256\": \"6cb9986df26ab6e44a081c6e91ba9f7efae5f9e92e4dcb92d54c8810cfd051c6\",\n        \"size\": 90092601\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6198_Weather13.tar.gz\": {\n        \"sha256\": \"6c63b48378b9f92069c5a6474a34d2dc0ba327e0a6120892354767af3d54cdfe\",\n        \"size\": 68879540\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6199_Weather14.tar.gz\": {\n        \"sha256\": \"cf75e4d3f877aa8b51bafe2929ea32356968ccecb6ef6133876a4adf216ed70e\",\n        \"size\": 196138206\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6201_Weather8.tar.gz\": {\n        \"sha256\": \"52d1594fbe0acec06459124005a613b6b3b13cffb2fc87a7d363b1fc7cb0540e\",\n        \"size\": 135927495\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6202_Weather9.tar.gz\": {\n        \"sha256\": \"4fed4f91fb973d7e99abf7f47ee5e33cfc6d7effb0a0f770a6bb5254adddcecb\",\n        \"size\": 105452353\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6204_Weather19.tar.gz\": {\n        \"sha256\": \"4d8ac5f678608b70c09faedff3ea049b4f121923ac9c6eba150581755bc22363\",\n        \"size\": 141937478\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6205_Weather20.tar.gz\": {\n        \"sha256\": \"8968a5fd4c4cf7577cd0a15c2bb90d6257b0f8703688f52b5cd7d19322a9182d\",\n        \"size\": 120091431\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6207_Weather22.tar.gz\": {\n        \"sha256\": \"4aad8c0186272486359fac65ba4dc26b25777751df3ad7040a7502b8baf95d5e\",\n        \"size\": 204098920\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6208_Weather23.tar.gz\": {\n        \"sha256\": \"8a3c6c2b3bbfa5aa4cd1a0e47603e04d8831d4dfb0ada6dccc7691a957d9e3d9\",\n        \"size\": 132230152\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6209_Weather23.tar.gz\": {\n        \"sha256\": \"feb5da723c0e923aa43182682c59b7e9d0499649e7e5c63fc0637225405718f9\",\n        \"size\": 128085645\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6210_Weather25.tar.gz\": {\n        \"sha256\": \"8606ca299f837a15739bdb9a1f704f39218ad5e93bfbce0278bcf51515051ced\",\n        \"size\": 103382707\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6212_Weather1.tar.gz\": {\n        \"sha256\": \"46f460d40ea602525273a8a13b2cdbe766351f3cc1e0fc06fc6cfc220fb99400\",\n        \"size\": 135878695\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6213_Weather2.tar.gz\": {\n        \"sha256\": \"49ff2d01d0dc15ed3a546050e057be5d657dd7df0f88f90d8ef53d211bf90456\",\n        \"size\": 181249335\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6214_Weather3.tar.gz\": {\n        \"sha256\": \"d61af73c9a7ae207ab2605697e3eab8b7963fa2737002719f3314e80eb44ca7f\",\n        \"size\": 121071008\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6215_Weather3.tar.gz\": {\n        \"sha256\": \"35f4e3c312cf78f66eda4a9476b1b19d92815eb734e4a122e04adcd15d74e4e6\",\n        \"size\": 139549723\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6216_Weather5.tar.gz\": {\n        \"sha256\": \"5ad0c4bdc39271960cbe045dcea51a1e71aa1782e732595b9de1e7326ef183f7\",\n        \"size\": 218327075\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6217_Weather6.tar.gz\": {\n        \"sha256\": \"f268340f571b1e549b65e597d244ff4df4f2a13cae5f97007a491d63ff3cf69b\",\n        \"size\": 216046398\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6218_Weather7.tar.gz\": {\n        \"sha256\": \"6cebb05bdff2e22bb5954ed01226592dbfc87da1e6032deff3ba11013326fcfb\",\n        \"size\": 160643157\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6219_Weather8.tar.gz\": {\n        \"sha256\": \"967591139124e4072ea8a0a4b869e756449cfc3e88f22a28834b89c527b9a31d\",\n        \"size\": 196152787\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6220_Weather9.tar.gz\": {\n        \"sha256\": \"c1e504de1c904d02c39af3bdf943d163ec0d7f53d116087ec486a239c870baa7\",\n        \"size\": 155815921\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6221_Weather10.tar.gz\": {\n        \"sha256\": \"da265ef67df5b5517113544c50de1f7955d316d99efc836d82f0c19b7a3fe94b\",\n        \"size\": 138472956\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6223_Weather12.tar.gz\": {\n        \"sha256\": \"9cf04fce5f0a8a550cffa5b5b1eb0e6197055409d4b8f49a9e6a008374671942\",\n        \"size\": 93897311\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6224_Weather13.tar.gz\": {\n        \"sha256\": \"fb019b972bc4af096b5ee937f31c4a3e30b9ebadea423fb7cfafc62ba5472c7b\",\n        \"size\": 79592627\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6225_Weather14.tar.gz\": {\n        \"sha256\": \"43c050ef1ed4d773e9c7461ef2b3f3eb611644eb936096a78c0ef3327adcc0bd\",\n        \"size\": 126457612\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6227_Weather8.tar.gz\": {\n        \"sha256\": \"35dadcb9efc9a0a5d8e43760b1ee752308aec4e5cd491f813686118f5aefb06f\",\n        \"size\": 111723075\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6228_Weather9.tar.gz\": {\n        \"sha256\": \"5556e12d03c3df9760ed244543de40b4aaea4b2dfa3ddf8f6867a9d1616f1e5e\",\n        \"size\": 139917210\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6229_Weather18.tar.gz\": {\n        \"sha256\": \"c99ea07fce492e8f884714d854075d4d99cf6e91afd02daf230e355c36b0014d\",\n        \"size\": 125889401\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6230_Weather19.tar.gz\": {\n        \"sha256\": \"1c2dd0e88890267e2c76117a8258a6774c6410d443d8167ce840b7f5138f1cff\",\n        \"size\": 187747457\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6231_Weather20.tar.gz\": {\n        \"sha256\": \"fc59913825d4fdbdec20a2eb33fa89c6937d987b325815302db086ffe4da30cc\",\n        \"size\": 91545337\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6232_Weather21.tar.gz\": {\n        \"sha256\": \"b1b0b3c2668e7b57ac3699094ff867668308ab7209f52e77585e33bb331081b2\",\n        \"size\": 145809196\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6233_Weather22.tar.gz\": {\n        \"sha256\": \"960e1b2ca83539a22ddbbb49c6e3d267f9b29bb2951b32e096b1ab4f50982365\",\n        \"size\": 125309615\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6236_Weather25.tar.gz\": {\n        \"sha256\": \"3b8576c9a9368f110124cffbefaf2bfeeb197e1e2135fb2fa89f4ec6b67f24c6\",\n        \"size\": 180329638\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6240_Weather3.tar.gz\": {\n        \"sha256\": \"fd824f6f104c6357bbffb1a1b37114cf56fa88e6f742287682db224a44317a46\",\n        \"size\": 122210262\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6241_Weather3.tar.gz\": {\n        \"sha256\": \"0e3b5641b7309796328833751ea731f06563a52529f3f79288d1c3f526fb4741\",\n        \"size\": 135343406\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6244_Weather7.tar.gz\": {\n        \"sha256\": \"4413d631fe23bbfaa23280f4cb493b0e7915ce1fa1f081732921a5c77ae53c48\",\n        \"size\": 204817291\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6245_Weather8.tar.gz\": {\n        \"sha256\": \"c6417aa0f0bf8df534022d83900fb4024390d83953c73e9eec20ce48d18796a1\",\n        \"size\": 134442477\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6246_Weather9.tar.gz\": {\n        \"sha256\": \"e90ecff66d8ba22a62be2fade2a3e09e18b46308e83f4d067bebdd42acbde65e\",\n        \"size\": 109626821\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6247_Weather10.tar.gz\": {\n        \"sha256\": \"b2ce563a8f52d92a0adc8fffb49539fbaa37ba71d66c9147eb7916c61dc6adb3\",\n        \"size\": 203550618\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6248_Weather11.tar.gz\": {\n        \"sha256\": \"e835c7595078f3b96d1a581879250343e3a20589c1c63d461ee406e9a35aa7dc\",\n        \"size\": 137510464\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6249_Weather12.tar.gz\": {\n        \"sha256\": \"f0e03871e264946526f64befc51dc3d11331a60e8b34ed9bf051a3e3494cc1a9\",\n        \"size\": 449068901\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6250_Weather13.tar.gz\": {\n        \"sha256\": \"b269c50e253a1de97c996e6be21f7cded514349de40e1aa98e3babeb05a3b1e8\",\n        \"size\": 143969142\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6251_Weather14.tar.gz\": {\n        \"sha256\": \"2ef3b1829271a9316652c68ddf86e62a3cc1c8c933b1462d56faa78f402ce597\",\n        \"size\": 137248007\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6253_Weather8.tar.gz\": {\n        \"sha256\": \"fb7b44d3e8d3de1a302a550ea0712ef590b48171b8f2ab24fc404e816f1053e4\",\n        \"size\": 580616469\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6254_Weather9.tar.gz\": {\n        \"sha256\": \"5d893e88f78b31b245c21c9176e352ef03e154f23213d953e0a8f46eeb79bd25\",\n        \"size\": 106448281\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6256_Weather19.tar.gz\": {\n        \"sha256\": \"7b768f0414f25056639144ce23dfbf2ff311da1212edf501b5bb4845fd2b4133\",\n        \"size\": 109637785\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6257_Weather20.tar.gz\": {\n        \"sha256\": \"71f12b044e894e60e85f6830da5ea2042434061a72aef0cfb4fd1374bc26f538\",\n        \"size\": 148263439\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6258_Weather21.tar.gz\": {\n        \"sha256\": \"62c6f15ab3da7ea02fb870f101e7ad78cfaacc3dda4dda3f58a37cdf1349edb2\",\n        \"size\": 127712115\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6259_Weather22.tar.gz\": {\n        \"sha256\": \"105619aff9e88ccad26ad9588f20e3a128f7a85be558f922d4b2abc9cbd17362\",\n        \"size\": 124775546\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6260_Weather23.tar.gz\": {\n        \"sha256\": \"29c6b61d46154d7f5c6b795d4751ae713af8b3b6693fbf1099fd30bacff1831a\",\n        \"size\": 91908643\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6261_Weather23.tar.gz\": {\n        \"sha256\": \"d0e05d70373c1d6dc0af750722f1f92b0946a382236ed9b5fc80b30bd77c6aca\",\n        \"size\": 151776729\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6262_Weather25.tar.gz\": {\n        \"sha256\": \"d47c8838a586881375fcb1c5c2f55442eb22254251a0983e61f2066cf3f47702\",\n        \"size\": 246420503\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6264_Weather1.tar.gz\": {\n        \"sha256\": \"3633277f490181a594119b9e4b3dbbc4c3f24fc18b07193676ffbe28f984f5df\",\n        \"size\": 152735948\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6265_Weather2.tar.gz\": {\n        \"sha256\": \"ee64fa8fbf4162801f8488dbe6936c0ac9ee4982732deb7cdf7d102e963eb394\",\n        \"size\": 132068641\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6266_Weather3.tar.gz\": {\n        \"sha256\": \"0ee2843aafbfb9a9daec54b870f3df2e49cf2c0e5c81c842dc7e542c59809b4e\",\n        \"size\": 191746088\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6267_Weather3.tar.gz\": {\n        \"sha256\": \"f62f1dc1487f9dfc747c214937628c3e28e222b68cf889ad79b7b3cc2fed107f\",\n        \"size\": 152224352\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6268_Weather5.tar.gz\": {\n        \"sha256\": \"f397877c29c638e674f2260158146e257d494f567d145b1cb0e6b3727a52d1ff\",\n        \"size\": 119759925\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6269_Weather6.tar.gz\": {\n        \"sha256\": \"d6edbb12dfd4cbf15164fc1c0f24cf21ff1292e885934feb39cfdec5cea4d9c5\",\n        \"size\": 115537019\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6270_Weather7.tar.gz\": {\n        \"sha256\": \"ab82d87d0931a73e660a21daad42bcb30f02dd3d75e3d3210b4547cf596c9822\",\n        \"size\": 166642585\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6271_Weather8.tar.gz\": {\n        \"sha256\": \"850a13a9c5601a69bf74bef8c1bfcf19e78c2155b7776a1e091dd6930defc6a4\",\n        \"size\": 148067619\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6272_Weather9.tar.gz\": {\n        \"sha256\": \"ef0fe8277b6cfa9563468c78c9257d607731f59d8398c2eb0e361f4388df3595\",\n        \"size\": 119488489\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6273_Weather10.tar.gz\": {\n        \"sha256\": \"75299d2e0c7c9eac8f9e0f56ef78526e7265db2e9eda113ba9898d8e44bf835a\",\n        \"size\": 132436603\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6275_Weather12.tar.gz\": {\n        \"sha256\": \"0d100b574b68128b466b0b96743775eec5e6914fc6bb12acfa48012f3ebb2684\",\n        \"size\": 113065217\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6277_Weather14.tar.gz\": {\n        \"sha256\": \"12b92d7dca057939346bbefbe4034d5421ff8979fe81adfe09eedd5dba8c44e8\",\n        \"size\": 99215301\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6279_Weather8.tar.gz\": {\n        \"sha256\": \"419b03859ba4a343676d955e4b7fe965a2e92e7938829ecedb176aedabe60d4f\",\n        \"size\": 137883090\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6282_Weather19.tar.gz\": {\n        \"sha256\": \"b5c5b1db17edb6d4359c22c07d10f69382b93fd9df0750706cfafa5230b20393\",\n        \"size\": 152914489\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6283_Weather20.tar.gz\": {\n        \"sha256\": \"7db6d0788f0706cb3cb691dbcb5e4907d9909fabd927940a2b7db21ebf7f236d\",\n        \"size\": 149933083\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6285_Weather22.tar.gz\": {\n        \"sha256\": \"5212b7ee4511489a05c9c1e0e6bd9ee6c6dd9ff0c896cadfda23df31d9b906cf\",\n        \"size\": 137776805\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6286_Weather23.tar.gz\": {\n        \"sha256\": \"d40cc6e6d756e733de98d67a6b8ac1f1644800bd9b9280105fca68016abffa7c\",\n        \"size\": 150593730\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6287_Weather23.tar.gz\": {\n        \"sha256\": \"50dcb89c2e53ee7b2a38e5c3fcabdc1ab1de74e8a68d98fbf8460ec06677e4d8\",\n        \"size\": 122910251\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6289_Weather0.tar.gz\": {\n        \"sha256\": \"061e0fa5c49f9910ca08364c4d0bdc50b9faea6f2c2ffa93bc75c1354c97b576\",\n        \"size\": 153065700\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6290_Weather1.tar.gz\": {\n        \"sha256\": \"4caab3d35e53f83e8321931724e4486b2ca4e3f9be0ed5600b914fe78c39c664\",\n        \"size\": 142058875\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6291_Weather2.tar.gz\": {\n        \"sha256\": \"fab4b36a378c12ef16cce9b529255f030b1b7611c9d01628a55ae1e80307e7d2\",\n        \"size\": 318245837\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6292_Weather3.tar.gz\": {\n        \"sha256\": \"e297d2c1f8bc2e614a005c996ec111393119982f0e64b902c4206f72dd4e88e1\",\n        \"size\": 147094010\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6293_Weather3.tar.gz\": {\n        \"sha256\": \"3467624bde9bff14bfc92766a44103458686540f2f2c6fb8a7af1500a9cde246\",\n        \"size\": 155430737\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6296_Weather7.tar.gz\": {\n        \"sha256\": \"44463c9f2b51ed672406e74d0be1b3145c925a1e748dba067c49050d9f6238ad\",\n        \"size\": 133469646\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6298_Weather9.tar.gz\": {\n        \"sha256\": \"e7b915501ab37aebbccfe4f157ce2dd84bab60ad6c744dd3829f8ca102d302eb\",\n        \"size\": 196333613\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6299_Weather10.tar.gz\": {\n        \"sha256\": \"eb97b6f6ca319f96d101db21b36232b64a914e60456df98e93e1d36a935e2f8d\",\n        \"size\": 237549500\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6300_Weather11.tar.gz\": {\n        \"sha256\": \"452dc22a75062c6dbb515efaaa0fa32558500acf14f202ca693725507442423e\",\n        \"size\": 69467380\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6301_Weather12.tar.gz\": {\n        \"sha256\": \"401bfc551351cea1ce618df1012edde39004e3308bd3612d520063d15f0a81f1\",\n        \"size\": 92543751\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6302_Weather13.tar.gz\": {\n        \"sha256\": \"82c1408a6e0a975ad76987b24bc747fe052e52d26c11d4df750bd6aee9b4bf05\",\n        \"size\": 122182490\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6303_Weather14.tar.gz\": {\n        \"sha256\": \"9472f90862cea5754e2ba4f9b7be1257b054e22f1e45b8cedb40e8b55a08d474\",\n        \"size\": 107647661\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6304_Weather15.tar.gz\": {\n        \"sha256\": \"a75576a8766372be7f87be4fec18b91e460b9b3a46942e12b730c1c701a3b9b7\",\n        \"size\": 121766892\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6306_Weather9.tar.gz\": {\n        \"sha256\": \"50cc329eead6f4bf38131407ea0c1fa3a33e71a190a9bd0239ac3f723afc5e58\",\n        \"size\": 84847548\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6307_Weather18.tar.gz\": {\n        \"sha256\": \"549d90c6d2e60d82cc537fe69a43dc001e5b72e8d01de8863f6132819484369c\",\n        \"size\": 206280108\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6308_Weather19.tar.gz\": {\n        \"sha256\": \"188f13c178c4db227938bf1a23ab4f5cf0c995eb91f0927e0b0da0f71940401d\",\n        \"size\": 253018755\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6309_Weather20.tar.gz\": {\n        \"sha256\": \"023474babb8f393b5cb09dc3bcdd8079b339ad1028f567c2694b2f78883ae157\",\n        \"size\": 142346361\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6310_Weather21.tar.gz\": {\n        \"sha256\": \"147a828b3900743f10772428c530aa6832ce8bed4aa009e37b8b71ac5c2eebaf\",\n        \"size\": 140340813\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6311_Weather22.tar.gz\": {\n        \"sha256\": \"9d5551aba2fd2ffdc9ba92a2e30879fa5cab06073aa05aacd73e07a1ce5b8985\",\n        \"size\": 95159691\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6312_Weather23.tar.gz\": {\n        \"sha256\": \"a518ea095b31023101b79ef1f129f7856cd4015655d09ba1e8264c51f5df7549\",\n        \"size\": 150273195\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6313_Weather23.tar.gz\": {\n        \"sha256\": \"db5caa7d85837cd4699f1b4bb9b0ca037b0c6e3a137ed1e0030ed3cc8227b6cc\",\n        \"size\": 108157477\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6314_Weather25.tar.gz\": {\n        \"sha256\": \"c8c97821ec2962bd951c843c39e3ae964758898e1056e8987c59eebac370d252\",\n        \"size\": 114587135\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6315_Weather0.tar.gz\": {\n        \"sha256\": \"a2be7fb28e0b9f15d02e6ddd3f49474a1d4ae2264af53ee449ee3a7102c09142\",\n        \"size\": 130859954\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6317_Weather2.tar.gz\": {\n        \"sha256\": \"62bbbb275bb80e71c1cce7e1f90663e3adb4110b6a36efbbfcfab1f0016e7632\",\n        \"size\": 127258823\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6321_Weather6.tar.gz\": {\n        \"sha256\": \"aa3eac0f5072a463650f6a7f6b1c2f0c8ee8008f4c4f9dd0b54519e884872697\",\n        \"size\": 159447056\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6322_Weather7.tar.gz\": {\n        \"sha256\": \"d9326d7752b6928b220a355737e73345302fbd0e53378ccff2dc91389f627187\",\n        \"size\": 105602014\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6323_Weather8.tar.gz\": {\n        \"sha256\": \"317ffcd6c2e937a4563ebe9ffec19b44f679e31803b6c0b82698474f540f9947\",\n        \"size\": 141969791\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6324_Weather9.tar.gz\": {\n        \"sha256\": \"9b57354aec6c6f240eed9377f590ed33b691d938c6e1aed552573fb72956c902\",\n        \"size\": 86448087\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6325_Weather10.tar.gz\": {\n        \"sha256\": \"06d5423bda034796ed30562c3a801f1299ba6df04528e758196dc32f84859586\",\n        \"size\": 143744385\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6326_Weather11.tar.gz\": {\n        \"sha256\": \"4ebb38b57d000d983529f494acf44c98f4de463497635a09337cf073bb646715\",\n        \"size\": 111997610\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6327_Weather12.tar.gz\": {\n        \"sha256\": \"eb597fe0259b9686dd64cc9e0cf7863a473bcbca1c26a8915d40ca9f8df17100\",\n        \"size\": 108051399\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6328_Weather13.tar.gz\": {\n        \"sha256\": \"1e478599a143e515efac1f65e5955a7aa751a31d728d5670affb6d9b6e444c7d\",\n        \"size\": 109004202\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6329_Weather14.tar.gz\": {\n        \"sha256\": \"d16db53dd257911ff938b1cb234f246a7f7cfa389c8c2be9f8254629c0d21661\",\n        \"size\": 99890945\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6330_Weather15.tar.gz\": {\n        \"sha256\": \"f168eb7426dae30a7f807cb3bc921e84c4fb8969eaf5e9c9d046bb233421517b\",\n        \"size\": 103296603\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6331_Weather8.tar.gz\": {\n        \"sha256\": \"b15ef51f69733d61806e0e52c44590a45f8dd03cb80eeef15d5aafbb9a8afdaf\",\n        \"size\": 218680541\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6333_Weather18.tar.gz\": {\n        \"sha256\": \"0c00bf11044bf570e252a329d6b3e4a05c2c40a0cc3f2ab0caec7461806c2166\",\n        \"size\": 160611297\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6334_Weather19.tar.gz\": {\n        \"sha256\": \"72013fb8742da936c6e952a70951b091912a914e96f7edb60415952fede5aec7\",\n        \"size\": 161033823\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6335_Weather20.tar.gz\": {\n        \"sha256\": \"7214d40a9379a46b481fc7958f7a43ba0b62fbcde171ec6682b4e9198dcb717e\",\n        \"size\": 153451693\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6336_Weather21.tar.gz\": {\n        \"sha256\": \"8e81bcdcf30bddf9621b72d356e82fe0245f060c2a7e292dad99f967448c2a37\",\n        \"size\": 202643460\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6337_Weather22.tar.gz\": {\n        \"sha256\": \"38373aacf92e7cdafd598ec71da17bbbc93563587c3532c709d995a26ac99b07\",\n        \"size\": 130314439\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6339_Weather23.tar.gz\": {\n        \"sha256\": \"cd5d0eeda80c1a230f855f8cb7e3514a55cf4fc5436ac62b37ed31bb39044d47\",\n        \"size\": 122476625\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6340_Weather25.tar.gz\": {\n        \"sha256\": \"827a97a2939db7973f70219dfb1821c81d13e67292522e47780fab13033a2f6a\",\n        \"size\": 103798447\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6341_Weather0.tar.gz\": {\n        \"sha256\": \"f8230f038c3d066ceafcbaf8771407b745c90be1ece0cde96fbc13e9164c7ed6\",\n        \"size\": 149222553\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6342_Weather1.tar.gz\": {\n        \"sha256\": \"069b84feba03f4984f020dbb50104b3e3539f464eefa3d9a9fb39ab28aa25f55\",\n        \"size\": 111431987\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6344_Weather3.tar.gz\": {\n        \"sha256\": \"2c2e3902276fdf5722d4435031cc9109f6fcbd440221db549fa2ba6b0dab9cfc\",\n        \"size\": 129692777\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6347_Weather6.tar.gz\": {\n        \"sha256\": \"f25d022635ed601110cbd2edec73b3c086e5bee8c76be0c741d804dc6bc41b8a\",\n        \"size\": 146675743\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6349_Weather8.tar.gz\": {\n        \"sha256\": \"b73365754576941964e1a1253ab8abc09c4b190801d6d7f153c5d61a9c3bcb40\",\n        \"size\": 116341690\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6351_Weather10.tar.gz\": {\n        \"sha256\": \"054abe4f29accdba9aa9843522e38ad4a222c3785de2d36f00e00360b68a3546\",\n        \"size\": 156927057\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6352_Weather11.tar.gz\": {\n        \"sha256\": \"83c9b47b0a3ad21683745ecfee9224e7016b44014b996e1b302960cda4238fcc\",\n        \"size\": 81473458\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6353_Weather12.tar.gz\": {\n        \"sha256\": \"4fb7da9e9fc7c378b2b348ed9e3049b4f7904c68970e0b66adf9d433bb23a39e\",\n        \"size\": 102216101\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6354_Weather13.tar.gz\": {\n        \"sha256\": \"feb6b4f167ed8ea6a2cd4d44f78c53750e9c37b883967e6cdace6da6cdf4cb59\",\n        \"size\": 84666785\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6355_Weather14.tar.gz\": {\n        \"sha256\": \"679d443f5750115274d2da96e21ace580870d0be5e6018976d91d6e743d1b69c\",\n        \"size\": 124865512\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6356_Weather15.tar.gz\": {\n        \"sha256\": \"3b77b942796c5f871cc28b84e4d4b445a5fd3d5ae10a6db3a71db34d019ab325\",\n        \"size\": 136434092\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6357_Weather8.tar.gz\": {\n        \"sha256\": \"9b65e88713d00561583ab03b53d057a865e29ee705c6a088dbfc982f9bf44471\",\n        \"size\": 127685302\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6358_Weather9.tar.gz\": {\n        \"sha256\": \"3ba69927822a9e8bf52e81e3b195f436d7a4ec0d966f906d2271973f4297d28d\",\n        \"size\": 70681646\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6359_Weather18.tar.gz\": {\n        \"sha256\": \"8593b66312c05930ba95404c8f690824afff5acedabf25a75b787579dc86388c\",\n        \"size\": 352192281\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6360_Weather19.tar.gz\": {\n        \"sha256\": \"4ae977411e1859fb0e67ba500a5bc3407a4d926ed41852ce55a9be6228306861\",\n        \"size\": 99909995\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6361_Weather20.tar.gz\": {\n        \"sha256\": \"4d215ae2cb0fb3f173647acb49734f31e1e9d8c67abc59a99d5ecc08d652d7b1\",\n        \"size\": 152748427\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6362_Weather21.tar.gz\": {\n        \"sha256\": \"f0f05b228994b62fbe319c48f9510ffe1d3d719c14c179edce3b23593c59caa4\",\n        \"size\": 128046186\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6365_Weather23.tar.gz\": {\n        \"sha256\": \"7f33cd2e687ae1d79114f8d2d37cec2a91fbe87459fff987db6f17e4c7c4e885\",\n        \"size\": 86301039\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6366_Weather25.tar.gz\": {\n        \"sha256\": \"5cfc753c6fde3041217286814cf6afdc6fe974c92287192fa1d62f7cb615aa0c\",\n        \"size\": 109543728\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6369_Weather2.tar.gz\": {\n        \"sha256\": \"c4570249cc2e227da15f05347fea259577b31d7f4579312ac890e165ddfa0f7e\",\n        \"size\": 134771176\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6370_Weather3.tar.gz\": {\n        \"sha256\": \"e32af6ae92279801772de7bc98e0ba70fde3a482cf905b775f3a12d442b9f096\",\n        \"size\": 141496872\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6372_Weather5.tar.gz\": {\n        \"sha256\": \"e1c43d82e125c7bef3b0164a9fde4df219d59ec327a79c55be0aaeddb0840cd9\",\n        \"size\": 133698483\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6373_Weather6.tar.gz\": {\n        \"sha256\": \"e9ff5d0a483c5c17fda5355c14e6147c2e2932acf377bfcdeaf2d29c634db049\",\n        \"size\": 143805922\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6374_Weather7.tar.gz\": {\n        \"sha256\": \"f85f20ab74bee16fa35e377d08d7effbd59708b00766d517dc9505a68a10a3f9\",\n        \"size\": 140357733\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6375_Weather8.tar.gz\": {\n        \"sha256\": \"7e9055038d07e29ec7bcd2483e8012f654446b392516619bd06791a5a3a4b14d\",\n        \"size\": 122255689\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6376_Weather9.tar.gz\": {\n        \"sha256\": \"2c846698550693f844812a224e95a87d04232669f177a4b3e46780a4bf886ecc\",\n        \"size\": 97556143\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6377_Weather10.tar.gz\": {\n        \"sha256\": \"cb4cd54df2865eb9a283988228d8e82fe6ccebb1d0d7ac02318bd589c22126d5\",\n        \"size\": 107761125\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6379_Weather12.tar.gz\": {\n        \"sha256\": \"d80ba29be716cd6851343fa4318afc572abbde36aadd54e9cd6a79e6a7f67de5\",\n        \"size\": 116470062\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6380_Weather13.tar.gz\": {\n        \"sha256\": \"6999d57fc13f9804cd3a32ee28d20c906d93bc123d016bd933c14f1505fc78bb\",\n        \"size\": 107303385\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6381_Weather14.tar.gz\": {\n        \"sha256\": \"ea3dcd91b54473e6b38919b5146e22c9503cb75c43630b68db0094a2aec44f9a\",\n        \"size\": 114590654\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6382_Weather15.tar.gz\": {\n        \"sha256\": \"d2fd0cbe042a2465d9457881784b4232d4bb071efb830edd06e0e31f10d30f41\",\n        \"size\": 134775218\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6386_Weather19.tar.gz\": {\n        \"sha256\": \"2acb102326c1c81d1b129b43a3405ea497e663f9393397ef37658e7762e4c8b5\",\n        \"size\": 143044289\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6388_Weather21.tar.gz\": {\n        \"sha256\": \"6b518f572c690ae04982c9af03a9249b63b1f59bc9c2cf51a50946eacca06852\",\n        \"size\": 125795698\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6391_Weather23.tar.gz\": {\n        \"sha256\": \"069b035c41aae40fcad53330fd11cf130099c1e4aa39f09f6762c300a6d1066c\",\n        \"size\": 104834352\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6392_Weather25.tar.gz\": {\n        \"sha256\": \"c36e9daf6deb4fd15c5ae6a98da68554685dafcec958060c2e5c7726786180d1\",\n        \"size\": 122918075\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6393_Weather0.tar.gz\": {\n        \"sha256\": \"d13b7925a33c9acab15a7cffa1e60e6aa0cea62b0877f80fcfdfb43b95b30083\",\n        \"size\": 108351127\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6394_Weather1.tar.gz\": {\n        \"sha256\": \"57fa492768779ac070f4be9a2463cb36ed306040662dbdf3a2a6eee46059639d\",\n        \"size\": 166435222\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6396_Weather3.tar.gz\": {\n        \"sha256\": \"8cd5f6687a2a9e4d008ab0a59ea6e712784009a3b7ca5c903ca65c32d7768616\",\n        \"size\": 126982434\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6397_Weather3.tar.gz\": {\n        \"sha256\": \"48179ff6f924d13170de357b2e95161885064c64fdb7dd39b08b0e143ee44b5c\",\n        \"size\": 116455991\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6398_Weather5.tar.gz\": {\n        \"sha256\": \"be9099f1178412c14d877652ae20c24b5a2c699a5e5f6b3862e822e3d9d7f2c0\",\n        \"size\": 155528120\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6399_Weather6.tar.gz\": {\n        \"sha256\": \"80a8b5ddea79b33d32be4bdc89591abfbc064165e2b57905b9fe31e0478c4c57\",\n        \"size\": 157993347\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6401_Weather8.tar.gz\": {\n        \"sha256\": \"5e8455888e2e1d07ccc0f73daa2e372786e198f95d78da0707a61d51eb2f38be\",\n        \"size\": 89278544\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6402_Weather9.tar.gz\": {\n        \"sha256\": \"67063550dd669043393e0872ab1359624813262056d447f3c5f9b429bfebcc2e\",\n        \"size\": 83011228\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6403_Weather10.tar.gz\": {\n        \"sha256\": \"8e59895f4bbf5a6caeb61cb034a9909e6e63ebe9077091eeb3b09b8a7af89757\",\n        \"size\": 254215298\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6404_Weather11.tar.gz\": {\n        \"sha256\": \"d000c1aae01f3da121c46ba744c683f8715ab8f83bb96841b4bed3a2db43b59f\",\n        \"size\": 90097020\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6405_Weather12.tar.gz\": {\n        \"sha256\": \"bb7901f69c89fc0861e275bb993dcea0897492a182cd1792767fbd680746c4ce\",\n        \"size\": 101217452\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6406_Weather13.tar.gz\": {\n        \"sha256\": \"8324a50a3556bdb8a880c986634fdc41f9cfb375e3b4d465ac8a5f4cc17555dc\",\n        \"size\": 158047310\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6407_Weather14.tar.gz\": {\n        \"sha256\": \"c09e0a4182ed19221f9412c52d00a56a845e3fe93acde922ca4cb73e4a2b7a95\",\n        \"size\": 110543286\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6408_Weather15.tar.gz\": {\n        \"sha256\": \"97601c74289336b816acd0564b4c3f9265434b21d2c80f362d284bbf4da2ee2a\",\n        \"size\": 219865449\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6409_Weather8.tar.gz\": {\n        \"sha256\": \"d11ee8e01219fce499344c886d3616b11e485c9a3fcfab17b5c093a57d984e96\",\n        \"size\": 116953845\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6412_Weather19.tar.gz\": {\n        \"sha256\": \"8bb2f5209ead5192362295fda8bd37eec0a2229eefd94149b8c6dd57e80d41c9\",\n        \"size\": 159442953\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6413_Weather20.tar.gz\": {\n        \"sha256\": \"d2417f9887cb97bdf1a457088b792e86af68e075b5c90bcdca587daad8c56182\",\n        \"size\": 206316110\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6414_Weather21.tar.gz\": {\n        \"sha256\": \"4fa48ce290728fa9e284d89da986a5671c7b119e95359c426a4cdf77a1325e6e\",\n        \"size\": 119236560\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6415_Weather22.tar.gz\": {\n        \"sha256\": \"72e43d6ab6c5c2972523bad7c7e9c3412bf1dea6cc8036a3f6a1e6e9ee597909\",\n        \"size\": 135810645\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6416_Weather23.tar.gz\": {\n        \"sha256\": \"994f686d346b6bc9f142275fcd96b7c7421fc85e62c63fa1460827e94f1ce42c\",\n        \"size\": 114984980\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6417_Weather23.tar.gz\": {\n        \"sha256\": \"0ebb883e14606cc431a0507fd50554b0b5e76d21049f205c826fd4a8dd9ac747\",\n        \"size\": 251819690\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6418_Weather25.tar.gz\": {\n        \"sha256\": \"14315f4b181cd619c9bf41c69e9f32a4b39b2a9cfca90d18fdab7efec3468f57\",\n        \"size\": 97037031\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6423_Weather3.tar.gz\": {\n        \"sha256\": \"5acdb4efd9e0cbf5c62b41f59d14cb6f29015ae71a2d94853d0c3ecc3ab4a107\",\n        \"size\": 122135096\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6424_Weather5.tar.gz\": {\n        \"sha256\": \"eec2feb15e6eca90402d5ceae07daa102b938376510bb822c67537d49bb6360b\",\n        \"size\": 170743730\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6425_Weather6.tar.gz\": {\n        \"sha256\": \"8a9a4f3d78d0489848328333ce3fc30aa59d4d80016460c39845d888c284ea0d\",\n        \"size\": 197993123\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6427_Weather8.tar.gz\": {\n        \"sha256\": \"b4a8789fbc06d2da46f07ca8076fcd679c8d4442d9495bc3b2c193f164af16fa\",\n        \"size\": 128045439\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6428_Weather9.tar.gz\": {\n        \"sha256\": \"afdaafcdb77ba0ee7eb7ce5fad6199804439acede2c14c3b95717d1bcef8521e\",\n        \"size\": 126899219\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6429_Weather10.tar.gz\": {\n        \"sha256\": \"55c98b3c02d9253d53a1481174e6dc5416a60c49c4a1aa0935168e6b94233045\",\n        \"size\": 127714926\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6430_Weather11.tar.gz\": {\n        \"sha256\": \"c255e4b1dfc9b33fdccf01602f5ee84844b1e967df6673107ca39068ea3a86bc\",\n        \"size\": 92488725\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6433_Weather14.tar.gz\": {\n        \"sha256\": \"bfb25a755c77b5dd0ed36eb99e4cb37e39848ce65989c5f66b9c4363697b509f\",\n        \"size\": 138353626\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6435_Weather8.tar.gz\": {\n        \"sha256\": \"3e7dc10d17eef7d09c00732900b55c966427380fce848a1224b4619e6b9d5e2c\",\n        \"size\": 219758492\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6436_Weather9.tar.gz\": {\n        \"sha256\": \"0fe47740db41310f890ec40c0601a0acc9f0eef78fca01f58b60e8679ecb8fca\",\n        \"size\": 102157971\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6437_Weather18.tar.gz\": {\n        \"sha256\": \"e832610b9c31fca106e82d5c338c100114240205c6ee8d0a9cae9a2f984841a7\",\n        \"size\": 149205778\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6438_Weather19.tar.gz\": {\n        \"sha256\": \"21ebda1b428b4937f2bb697b38360da0d17cf522511d619f78b027a41cfc1a90\",\n        \"size\": 141397209\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6441_Weather22.tar.gz\": {\n        \"sha256\": \"54c40a8e1235b257ef78f6e5e43829d80d63f8721b3e15db5268108407dc9bb1\",\n        \"size\": 113117622\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6442_Weather23.tar.gz\": {\n        \"sha256\": \"5dae53698ac924372fd4d5a71f3e1f3405bfc832fbec8544ab5ab870ccc7360e\",\n        \"size\": 96424374\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6443_Weather23.tar.gz\": {\n        \"sha256\": \"263a711b01faa5c9de5c3f9fd2111c7e04377425516bbf4444be4a1627c614ab\",\n        \"size\": 111122078\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6444_Weather25.tar.gz\": {\n        \"sha256\": \"e4fca80b5f0a170ee90f49e67c76275a32abbc8438b2fe9f42c8062400073f32\",\n        \"size\": 99552761\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6446_Weather1.tar.gz\": {\n        \"sha256\": \"a4dc4f3eb901cf803b81d2c5ddebc5ac45f1e8790aea78c0e2744cd8a2880adb\",\n        \"size\": 140692415\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6447_Weather2.tar.gz\": {\n        \"sha256\": \"a75ee547dfb371aa650d670104db8d32c65a2085b5ce7854f940521c25437dd2\",\n        \"size\": 150214968\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6448_Weather3.tar.gz\": {\n        \"sha256\": \"588f9498ef681ad898d3fd21ca07afdcb70fbddc002bc46f39a9e2d4fe67968b\",\n        \"size\": 130830735\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6449_Weather3.tar.gz\": {\n        \"sha256\": \"4ba3335a7dd7653ff3ea71904c5b061c833574ce2ea7739ab3940d8e7bd6fdc7\",\n        \"size\": 132911906\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6450_Weather5.tar.gz\": {\n        \"sha256\": \"b3e8c6fb8e167bdb19c17a9429e55c9d09eec76679d3eec08d413d40b2062d26\",\n        \"size\": 159645093\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6451_Weather6.tar.gz\": {\n        \"sha256\": \"e581c0845a3f489f64b0eba766e5031219741e621b586f11a8fffb118fc476a7\",\n        \"size\": 136285589\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6453_Weather8.tar.gz\": {\n        \"sha256\": \"b56563bf22f67e69c57af67564b565b6a165ae244c7f8006d254e53e7fa7c0c3\",\n        \"size\": 184948944\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6454_Weather9.tar.gz\": {\n        \"sha256\": \"534e7ca62782479538b1d26bb5f5bda81e7e89902c5152edcce207eae6e439e5\",\n        \"size\": 296420390\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6455_Weather10.tar.gz\": {\n        \"sha256\": \"b95c4e575cdf05cf85ae54e66ee5785e94fd385ddf0bb9ae6b750f72d9fc2aa5\",\n        \"size\": 154294500\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6456_Weather11.tar.gz\": {\n        \"sha256\": \"9d477270e2056c143c6441008c04b05c0a14da5c9af9c07e174676cf02e12d46\",\n        \"size\": 100529287\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6457_Weather12.tar.gz\": {\n        \"sha256\": \"855273c5dd2091b662f975c04916413cd7db3c919278035614c5fd54df72b708\",\n        \"size\": 128480172\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6459_Weather14.tar.gz\": {\n        \"sha256\": \"8fe59a8574a09e91951c19d90b1a464b4e3580e5b4bdb87d7825e99e342bb946\",\n        \"size\": 149903490\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6460_Weather15.tar.gz\": {\n        \"sha256\": \"94d3c10fa0103fde32eb19c5076cb5535df26e71a9fb38ffa4876089fdb668b8\",\n        \"size\": 338362050\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6462_Weather9.tar.gz\": {\n        \"sha256\": \"b21207e5ec881d1075cacaa66ec615e2863706e6d72a21cdb24c48cd6c3b14d4\",\n        \"size\": 116143037\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6463_Weather18.tar.gz\": {\n        \"sha256\": \"b9d71f1873b69fec1763f873508a92a9c46f96a1976513fa9c1178e4cf61b1ef\",\n        \"size\": 205935905\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6465_Weather20.tar.gz\": {\n        \"sha256\": \"566d7c4631da1d9526400a72f443ef044285373aa0fa890f4d66900064426819\",\n        \"size\": 134962319\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6467_Weather22.tar.gz\": {\n        \"sha256\": \"18277d7fe362ea9fad88e958f88acc7639f742a5f6b4dbd67c6d20ef695ca33e\",\n        \"size\": 125595587\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6468_Weather23.tar.gz\": {\n        \"sha256\": \"5b50d6cbef8fda5f215ef572f262c04d7b219673e0346fdd4c497cadb5f9ee5d\",\n        \"size\": 79759110\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6470_Weather25.tar.gz\": {\n        \"sha256\": \"a906a0ff908b4c55367874c0ebc33703acef8320bec04a0d90873f9481edf5dc\",\n        \"size\": 187150765\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6471_Weather0.tar.gz\": {\n        \"sha256\": \"25f2a203d7d91246643f89c2e770230002f7c5ec2a7981d44b1e7bfc23212579\",\n        \"size\": 140632798\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6473_Weather2.tar.gz\": {\n        \"sha256\": \"1f243e117f8541c61257310b5f087faf04d00f72ebb75c1246a95e6833418723\",\n        \"size\": 163377912\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6475_Weather3.tar.gz\": {\n        \"sha256\": \"46aee1d8c22dc12ff70e4113cd8e05133806552341a1854854877de4cfea03db\",\n        \"size\": 124823815\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6476_Weather5.tar.gz\": {\n        \"sha256\": \"e831d391a3a1a120b8ffb03c6ec40616e638426d600260ec62d5a4ca58029a3d\",\n        \"size\": 102211120\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6477_Weather6.tar.gz\": {\n        \"sha256\": \"65761c7ff0d52769ab16121d5d7fa63364e34da3dc93c54d5999973e9aef8766\",\n        \"size\": 116455282\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6478_Weather7.tar.gz\": {\n        \"sha256\": \"a0666c67ad0cfbf8d632d96314c33672b3867c18c418ba497c8840bb3778b184\",\n        \"size\": 135103432\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6479_Weather8.tar.gz\": {\n        \"sha256\": \"06799404b08aa36eeb7f7379ad4b2d1cd86f46387092a027260d5750e50fa717\",\n        \"size\": 121636362\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6480_Weather9.tar.gz\": {\n        \"sha256\": \"4faec7e33f3c517f4379ce5fa933b54caa7e452f507e907f106a38ff1a651de6\",\n        \"size\": 98762418\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6483_Weather12.tar.gz\": {\n        \"sha256\": \"23dbe7315834196a5da670e645c785d3cf09dbeeef44cd26bc461cb7d0f24e92\",\n        \"size\": 110585973\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6485_Weather14.tar.gz\": {\n        \"sha256\": \"87f33be86f1552cabc82a01daf6d2c52c3a8be1b6c44df6ee1a553e0a95ad2f3\",\n        \"size\": 115252289\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6486_Weather15.tar.gz\": {\n        \"sha256\": \"e5590564ea8afeb55a5666ae240b01e08baa1f77a547162b3782ed5159b64fc4\",\n        \"size\": 97672229\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6489_Weather18.tar.gz\": {\n        \"sha256\": \"49f2a32d1f25ce0e7ecc49a83711f47ba69a8b722e1629801c0098141a28ef84\",\n        \"size\": 96053238\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6492_Weather21.tar.gz\": {\n        \"sha256\": \"c43813b369345f6b0db94cb39df753952a00627d04d7bdcb92e9f328ec466ce0\",\n        \"size\": 173242311\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6496_Weather25.tar.gz\": {\n        \"sha256\": \"6da3ddb44babf225d83d62882f739c0a27b6e4a0e472d5524c0e751fbadb75d6\",\n        \"size\": 151678268\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6497_Weather0.tar.gz\": {\n        \"sha256\": \"60c777c677288b8f33cbff319dd227cb48c8ce5497644fc43ac27a8291e2a758\",\n        \"size\": 108637518\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6498_Weather1.tar.gz\": {\n        \"sha256\": \"fee1008750a718264121c3f1af19a12ac9673ab6a68f744824906c8ac6869a4a\",\n        \"size\": 114093247\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6499_Weather2.tar.gz\": {\n        \"sha256\": \"e620f5314be65c6a74344d05285723393ccf8119379cca4221037fbe99fb5673\",\n        \"size\": 185863778\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6500_Weather3.tar.gz\": {\n        \"sha256\": \"89abb13ec2ffa0292517cdc7edd552e1c0a784dc7112c7fd2d957e9ffb5be7a3\",\n        \"size\": 127190652\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6501_Weather3.tar.gz\": {\n        \"sha256\": \"4daa059e9f38f36b54b7a162984d6196d3f38c0cc7b74cd00121dbc9a6c447fa\",\n        \"size\": 195952237\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6502_Weather5.tar.gz\": {\n        \"sha256\": \"cd10ed85f735f6397e89f5b91c0b7a425cb60a5220bde834df1d3e33b3e50839\",\n        \"size\": 172704826\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6503_Weather6.tar.gz\": {\n        \"sha256\": \"059f11412c3dc3ebb917d1537af9cb6c3ffbc8e99fe4a7520912b57c8563ac32\",\n        \"size\": 110350896\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6504_Weather7.tar.gz\": {\n        \"sha256\": \"61cbccb01846c38068776cf4f25c511b498b37d870b770a616d5b765013b5b61\",\n        \"size\": 139048329\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6508_Weather11.tar.gz\": {\n        \"sha256\": \"11bf06ad4111319d11da7fb0cc91d0c334ed8f6f2c761d3b4493d8c520091a42\",\n        \"size\": 93182015\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6509_Weather12.tar.gz\": {\n        \"sha256\": \"266e4e349c91217091317fa840d7427c791055c618e126af2c35037056b4637a\",\n        \"size\": 173508204\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6512_Weather15.tar.gz\": {\n        \"sha256\": \"0820da4f7fef629040b48564ea1953873df4335db890f16f62615d37109f8c59\",\n        \"size\": 127237205\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6513_Weather8.tar.gz\": {\n        \"sha256\": \"ac3f28a88c11cb4b224aebd6e69c9924c41ae23b882810058c6bfbd057eacc95\",\n        \"size\": 134666392\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6516_Weather19.tar.gz\": {\n        \"sha256\": \"fba509972c1fa5758240abe229249eb4d510674feb336199b6de9d43f628edbb\",\n        \"size\": 251871039\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6517_Weather20.tar.gz\": {\n        \"sha256\": \"3b418391343ce5bdaa15112bd981fbf6fc848cf17c6c0bb53af92f5ca12dffda\",\n        \"size\": 199204331\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6518_Weather21.tar.gz\": {\n        \"sha256\": \"526721daf0acbc647d3c02240a57e3ddda4d8f0eff0c6c1cd0d46db282641082\",\n        \"size\": 129977208\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6520_Weather23.tar.gz\": {\n        \"sha256\": \"230b8c0cf7d2203325a65aec0cadb5eed6ed15483778d517d7f01149035460ca\",\n        \"size\": 94648584\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6521_Weather23.tar.gz\": {\n        \"sha256\": \"7796aede4d2f12e58d8aec81a10f1bb6ab468d2dde836a305a12cb217754a410\",\n        \"size\": 93402946\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6523_Weather0.tar.gz\": {\n        \"sha256\": \"b57f1130e8b6d177bbdbc2008cd12d267452efeb6ea0a8828126c12ee81658b9\",\n        \"size\": 110603504\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6524_Weather1.tar.gz\": {\n        \"sha256\": \"a5872eaa15d6ba057e0baab9ceb258ab52306daf35d7928fff60cb0786d2eb2c\",\n        \"size\": 159579324\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6525_Weather2.tar.gz\": {\n        \"sha256\": \"100e86dc1a330b25a55c30fa037485973ad975b62279958c06b6a32fb09ab44e\",\n        \"size\": 138313388\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6526_Weather3.tar.gz\": {\n        \"sha256\": \"1c51844f0c10d5080b5081451863f5ef8850143498ab07b19885e689ca767479\",\n        \"size\": 127989647\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6528_Weather5.tar.gz\": {\n        \"sha256\": \"d4c4320f4e0743bfdbb5054f9c37c5f760a165ebbdf428ef305a7a6367ea531e\",\n        \"size\": 276521413\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6529_Weather6.tar.gz\": {\n        \"sha256\": \"2dc306f6e6275c1913ab05f9403380eb5abb0efaf08c5c0113a0acd92f89028a\",\n        \"size\": 182574399\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6530_Weather7.tar.gz\": {\n        \"sha256\": \"00b9fdaec7a60bddda280fc9019db5aac2ffc959ea4854d02970446ca7b71ae2\",\n        \"size\": 178608930\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6532_Weather9.tar.gz\": {\n        \"sha256\": \"ddb24cf13be8e476bbc5905b95f62f205a25674cb4f899f208ae8453d26b4fe1\",\n        \"size\": 156291706\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6533_Weather10.tar.gz\": {\n        \"sha256\": \"9cd1ee018202e27f15707f3d1aadcdb7ec2e09b6a3bddf8711c2c63082330a20\",\n        \"size\": 189388178\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6534_Weather11.tar.gz\": {\n        \"sha256\": \"61001511eb3b913660cf4bf9483b5d71a79da79338e3c103cc0a7731a63c0b84\",\n        \"size\": 80554320\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6535_Weather12.tar.gz\": {\n        \"sha256\": \"60b0ad0a9c9bc1a4c45fc70ffc0641980da814889311897832e09ccb904864fb\",\n        \"size\": 116095732\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6537_Weather14.tar.gz\": {\n        \"sha256\": \"41cf46be06e8daa5f9e59f0c41ed72969e65b8f5e66f6b0b4e0a9ff6c5cccf36\",\n        \"size\": 155908833\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6539_Weather8.tar.gz\": {\n        \"sha256\": \"6cfff2159b96b9c6fa04afc0e368c434eda49148f9aecbccbaad27d1131166f0\",\n        \"size\": 122035464\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6540_Weather9.tar.gz\": {\n        \"sha256\": \"59eb8984dbc50ecaf1986f802b7b760fc771e4eef53fc73a2abbfe99d711ec27\",\n        \"size\": 152641617\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6541_Weather18.tar.gz\": {\n        \"sha256\": \"aa8d2474483075837bb8167a5648a9c0f30d4a41629059a1406ddde0977ee6bd\",\n        \"size\": 145213220\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6542_Weather19.tar.gz\": {\n        \"sha256\": \"fdf09ace6c892bb8fd7dd5ef265d866013e56b6363e8ce3a0e6cd367e92e0cbe\",\n        \"size\": 131594399\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6543_Weather20.tar.gz\": {\n        \"sha256\": \"be977cd0bca9145cadcc58da5c2a989e1bb0beecb6173f3fb4735a8a9c642852\",\n        \"size\": 139933738\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6544_Weather21.tar.gz\": {\n        \"sha256\": \"bbe6f5671efd8f17826bdf024c6699e53a755322e75735dba4d1667aed93dec6\",\n        \"size\": 167327261\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6546_Weather23.tar.gz\": {\n        \"sha256\": \"314e58ff038ebf7e4b863b7d4b07ff395c3a08cc8ec4501b76cc1cd76feeb11a\",\n        \"size\": 115904571\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6547_Weather23.tar.gz\": {\n        \"sha256\": \"55187e6507b8d056164bdb5b86145d55d45b2bd47bdee7cc0efd13661780c23a\",\n        \"size\": 114973576\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6548_Weather25.tar.gz\": {\n        \"sha256\": \"0f83ac8041e9732eb82b04f794031702e80d76da15baf3b7dc335ec9fb1eaf60\",\n        \"size\": 132396649\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6549_Weather0.tar.gz\": {\n        \"sha256\": \"10a37a34641214111e5cef7cb6035dfc36ee88b720935682bf29bdc62cb1b14f\",\n        \"size\": 97389463\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6550_Weather1.tar.gz\": {\n        \"sha256\": \"eb13a63333c417da525a92924306eadf64880b4fe77cc08f979437166c94f442\",\n        \"size\": 519092337\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6552_Weather3.tar.gz\": {\n        \"sha256\": \"2793ff7085780b29da60694e174a85e72b09baab6069f4a20fadfc01f557da1c\",\n        \"size\": 140894837\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6553_Weather3.tar.gz\": {\n        \"sha256\": \"66fa1d66261da28da79ebf69bb472b64c6392166e8989d8305f085301742bded\",\n        \"size\": 148016963\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6557_Weather8.tar.gz\": {\n        \"sha256\": \"40b94472594a468a42a0010660ffadd19d612c5bd2064cf40d62542e2985bdeb\",\n        \"size\": 158584996\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6558_Weather9.tar.gz\": {\n        \"sha256\": \"5c5af84240b86f855150d6d9fd616118a4d2f170386afc43eefe192f8b7f6e36\",\n        \"size\": 149423617\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6559_Weather10.tar.gz\": {\n        \"sha256\": \"b2c066445040d4774eec80b4f39352e0f0ea72a909dec8bbf9dbef1e2aac017a\",\n        \"size\": 135341628\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6560_Weather11.tar.gz\": {\n        \"sha256\": \"09d81871bca44f15347805e33ce7d6881b82c837ffa7dee5c9ce9e20e764ea88\",\n        \"size\": 103625955\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6563_Weather14.tar.gz\": {\n        \"sha256\": \"fe4b9977d1bdbdec2cbabf488e93af02236367c75bb0e742e40548084d95f712\",\n        \"size\": 97126008\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6564_Weather15.tar.gz\": {\n        \"sha256\": \"66436a17f2d6e77a7ae2090fc9b7567687419fdfc0942cfb5fa6ec755d9b085e\",\n        \"size\": 103553428\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6565_Weather8.tar.gz\": {\n        \"sha256\": \"a9097987d8cb5fdb5b7a19065a9cde4777c6728534acd2555898a74bff999211\",\n        \"size\": 119440802\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6566_Weather9.tar.gz\": {\n        \"sha256\": \"31d6d0cc371a14aacdee9adb99b94401af78ad8ad90d05e281e54dbd59b3ec28\",\n        \"size\": 120878823\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6568_Weather19.tar.gz\": {\n        \"sha256\": \"0ecd5e33798516d5a33108ba81cd2ac1c553693d05dcd060b39020c4a60eca65\",\n        \"size\": 114615843\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6570_Weather21.tar.gz\": {\n        \"sha256\": \"4cdd47bea7f859253f1a0b7a8294fe0b90bfb1f3717168816d0a193adf84ac87\",\n        \"size\": 114734630\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6571_Weather22.tar.gz\": {\n        \"sha256\": \"f7711e3b124e5481a4234be79646ab2bf899823bdcdf183a3f499c0accd96038\",\n        \"size\": 145641718\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6572_Weather23.tar.gz\": {\n        \"sha256\": \"0366cde74a059fe4d30a1d683257169824c5164fe67d60fc2ec67297299ba07c\",\n        \"size\": 121367710\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6573_Weather23.tar.gz\": {\n        \"sha256\": \"9ed51c8b710bb670d881d984c32404d65110799687cb5ca0a4559048cf923ab7\",\n        \"size\": 126923282\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6574_Weather25.tar.gz\": {\n        \"sha256\": \"a654997025ddd03c23972ab3b3e70cd77cf4ec0c9814e8dd365d37171af90c66\",\n        \"size\": 98869815\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6575_Weather0.tar.gz\": {\n        \"sha256\": \"30b99d4bdffca759a269cf42860f95354f767a06ef31c1fe8d0af73ce4a3cdd6\",\n        \"size\": 135088280\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6576_Weather1.tar.gz\": {\n        \"sha256\": \"b71b0d1175befc27dc719ec5c720ce32684c0938fdfe45aea2176e969ec8cf88\",\n        \"size\": 189183426\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6577_Weather2.tar.gz\": {\n        \"sha256\": \"51bede03d53dc2309ee15c96604622d605c1ccc8ef7f58898b588048e916cb2b\",\n        \"size\": 156533317\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6578_Weather3.tar.gz\": {\n        \"sha256\": \"214069ee8104c96d9b66ea9732d20f0af73076baf1c5af36679aeb82ddaf26b9\",\n        \"size\": 108039012\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6579_Weather3.tar.gz\": {\n        \"sha256\": \"99bae3fc597ee510f8205f9e95c015adfaf20561b34582cf35818bf727d4add7\",\n        \"size\": 143247680\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6580_Weather5.tar.gz\": {\n        \"sha256\": \"03c38d9a38df04840a8be5b3f5f8a1845bc77345669d8543662ad194961d71a4\",\n        \"size\": 146774874\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6581_Weather6.tar.gz\": {\n        \"sha256\": \"37d051bb7d67f3f0dd9a38d63163816ef79e6677c61197abc7b0194b133c0a56\",\n        \"size\": 122047872\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6583_Weather8.tar.gz\": {\n        \"sha256\": \"4909c5760d37487c9277e6b45afd3b4a815c7c6a6b825d7558022e8525595b6b\",\n        \"size\": 134625242\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6584_Weather9.tar.gz\": {\n        \"sha256\": \"460351d3afee8429c1412d1b46fddbba5ac35d62440800f09698e7fd44947cec\",\n        \"size\": 244359001\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6586_Weather11.tar.gz\": {\n        \"sha256\": \"a30ca0e820bfaa0d72977d844d45e50fd7cef687ace2463813f2cc6c74df35a1\",\n        \"size\": 112053397\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6587_Weather12.tar.gz\": {\n        \"sha256\": \"58f8e54126d2de2a3539a65070e05f96fee27738d9a5574e2bbe648054063f7c\",\n        \"size\": 125640706\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6588_Weather13.tar.gz\": {\n        \"sha256\": \"ed6962714b8e13c03ef66b2b2a80c6ec9be6ba83f03cd978e28d9a3829463560\",\n        \"size\": 76634815\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6589_Weather14.tar.gz\": {\n        \"sha256\": \"77c4689500a206262fc09a124f2a7b2cfeedd0ea932951278b43d4d2c1697bc2\",\n        \"size\": 116090280\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6590_Weather15.tar.gz\": {\n        \"sha256\": \"8bedcd59bb82aed6599c6420b373019445aaf7d52e157ff3d0ad8feec90d591c\",\n        \"size\": 126938798\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6591_Weather8.tar.gz\": {\n        \"sha256\": \"f7389fb697e09b60570d599946736b918a7b0a047e3dcf481a96881f72f1d74b\",\n        \"size\": 190046501\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6592_Weather9.tar.gz\": {\n        \"sha256\": \"444c33a0d6e0fc151926453ce4b8b7c51b23a6bd9eeaef00db043921e77d2432\",\n        \"size\": 106123588\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6593_Weather18.tar.gz\": {\n        \"sha256\": \"c4f51bb7fb386ea260bb787a709270a2b95106f88b7ca0a3d55f001af1d7917d\",\n        \"size\": 137209723\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6594_Weather19.tar.gz\": {\n        \"sha256\": \"bd114a2c46164a48d67520b3c1664f6dfc628cf25e5f0a42bdb543f808fbbccb\",\n        \"size\": 187439088\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6596_Weather21.tar.gz\": {\n        \"sha256\": \"2f767a4dc48d185b6b8bc28654114dcdbb597d4f7ac7b0c64f3a4504b48f676d\",\n        \"size\": 144365569\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6597_Weather22.tar.gz\": {\n        \"sha256\": \"f143374de5c6d748d8d8ede9a79fa3a319477d54638e899c3c1d3125da4188c0\",\n        \"size\": 129093023\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6600_Weather25.tar.gz\": {\n        \"sha256\": \"0d0162ad145806dc39d22101749658706a00065c9e857f29f929b016c9ead8d2\",\n        \"size\": 131874637\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6601_Weather0.tar.gz\": {\n        \"sha256\": \"869b763c7ce8564a6246092e1803f84bb2c1b148c70df5b9efdd6b79eb8d9695\",\n        \"size\": 146647402\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6604_Weather3.tar.gz\": {\n        \"sha256\": \"ed3fcc017ff37a6db0ff840509c7e3b90208696bb3f50b1e1916797cce7e3147\",\n        \"size\": 132430194\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6605_Weather3.tar.gz\": {\n        \"sha256\": \"7cbcb8affdc391ab4cf928d7f1fab0a0ad5571d6d236cff3898ff21a3bdba90d\",\n        \"size\": 113547476\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6606_Weather5.tar.gz\": {\n        \"sha256\": \"04e36b145aa35a513b7c962107fbc3cac1c8a8b0b413ea12a29ac012e711ca49\",\n        \"size\": 132080152\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6608_Weather7.tar.gz\": {\n        \"sha256\": \"1e1bc76c13fc9480f64595b56e286f41bccd67462affcee19852a1fbcc214b57\",\n        \"size\": 209764081\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6609_Weather8.tar.gz\": {\n        \"sha256\": \"e6a914de34c7ba10fdda29e9205d2529b1954d838f5b536395cc0e18700dcae8\",\n        \"size\": 95476812\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6610_Weather9.tar.gz\": {\n        \"sha256\": \"39693c1f4bf3cabde3ecbde515d0d7f31119bb0bc903ebc85844478816afadd9\",\n        \"size\": 118481440\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6611_Weather10.tar.gz\": {\n        \"sha256\": \"7f811dee1822e319aee6f34e489c16933be48fbfd5fc70e82adf21a3d218cebd\",\n        \"size\": 199434041\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6613_Weather12.tar.gz\": {\n        \"sha256\": \"7c02fbe1ab884a0b1459f95cda955ac2bbc1f3f0ecfa88003d405e048bcfe6c8\",\n        \"size\": 108008450\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6614_Weather13.tar.gz\": {\n        \"sha256\": \"39df455f872bb5f393e7fda90b711028070aea2ef21df6ff7d714c5b7ee7e878\",\n        \"size\": 120922412\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6615_Weather14.tar.gz\": {\n        \"sha256\": \"1156572b00cc68d2b69fa4d70c353e859d7b084e3592ad81b156801a01984b45\",\n        \"size\": 127410353\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6616_Weather15.tar.gz\": {\n        \"sha256\": \"be310c4a20a08e579d48e5100d7879f1ca108aa39c5c95f06888208d458e9108\",\n        \"size\": 127699249\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6620_Weather19.tar.gz\": {\n        \"sha256\": \"0ff43dc4903ff5eff27483f61011c2cf082d4959c3f7f6d292bb1fbdac14925a\",\n        \"size\": 173815071\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6622_Weather21.tar.gz\": {\n        \"sha256\": \"27a30dae1c4ad002dc8ec6d9be3474d1d6ce0d6eb6011c483149f8de98d344d2\",\n        \"size\": 113883654\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6623_Weather22.tar.gz\": {\n        \"sha256\": \"a83a721d09b27e8dcdba7ebf7133457f649f4f48c4d9daa6a47ae5164f2bb2a2\",\n        \"size\": 148777582\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6624_Weather23.tar.gz\": {\n        \"sha256\": \"514a1e207df3b5a744671655c9ec45bd214e7079e45ce6cf155207c6a1a6615f\",\n        \"size\": 132766603\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6625_Weather23.tar.gz\": {\n        \"sha256\": \"7fcfeafd3c450216c9539b1417c94db1db95d6d8fb0f289263b8b506018e08aa\",\n        \"size\": 198264572\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6626_Weather25.tar.gz\": {\n        \"sha256\": \"7c9e98ca5c3607fdd51cf87a885c50c534189468334ec8c636f33f5c5f86973e\",\n        \"size\": 137331063\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6627_Weather0.tar.gz\": {\n        \"sha256\": \"6f2386c48ced21371d19a62444530b433ba9b819440505c2eca644f28a666a56\",\n        \"size\": 130047086\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6629_Weather2.tar.gz\": {\n        \"sha256\": \"c62796af126147f7edac18394ae626f79dddac36c5dc8896923cef91575c5f7d\",\n        \"size\": 358234361\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6631_Weather3.tar.gz\": {\n        \"sha256\": \"dcd602c4cbaefdcef5475fa75fb3082c50e1c6bee924d941cc96f21a8b9dba1c\",\n        \"size\": 129164806\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6632_Weather5.tar.gz\": {\n        \"sha256\": \"68c6c548f294d505588b0e64317a8cdff120494591b493b325813d513d11a0d1\",\n        \"size\": 165190089\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6633_Weather6.tar.gz\": {\n        \"sha256\": \"6d252059a6c2e643ab52bf02bb2ef03154ff5b7ff426812a8d4e800c9815105a\",\n        \"size\": 207943535\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6636_Weather9.tar.gz\": {\n        \"sha256\": \"5e301f484ccaaca2e116fc3e05d9d32cf0370156a75f1e2130b62df8f6ea4e3d\",\n        \"size\": 97763893\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6637_Weather10.tar.gz\": {\n        \"sha256\": \"b2f8d703f87068fb86e3bfbe36a53473dd7d82b5f2e498809e6434984730cfa9\",\n        \"size\": 194053089\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6638_Weather11.tar.gz\": {\n        \"sha256\": \"4d605f1964aaf0f3dff771415cdb65235ff3f6f0d283a4f91a3e1ba7ac5a1d4b\",\n        \"size\": 106670559\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6639_Weather12.tar.gz\": {\n        \"sha256\": \"5b8d88c03fb5f0f6d4dd484f963ea404cc9b8d791afcfabc46b09d3b0179a1c3\",\n        \"size\": 117648614\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6640_Weather13.tar.gz\": {\n        \"sha256\": \"0f7cc21c51af03aad1a38bd30295b3a8ea5a53cbff12cdf96ee060288b052f10\",\n        \"size\": 109507787\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6641_Weather14.tar.gz\": {\n        \"sha256\": \"eb97c4c80f8b5edd73c5dc6545be9471ad2a7f8eb6faaa62495dc685e59eea81\",\n        \"size\": 100214152\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6644_Weather9.tar.gz\": {\n        \"sha256\": \"3a10b4e7f90219965026b62d04110a23a7ea6bc5a243fed90e6dd0f8fddf6170\",\n        \"size\": 105836123\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6645_Weather18.tar.gz\": {\n        \"sha256\": \"b0afe0d91ebcee524c015e794f08b8adce78b3a073f8a7ba861732062886a54e\",\n        \"size\": 165838899\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6649_Weather22.tar.gz\": {\n        \"sha256\": \"abc15cc04237ee30407aa160087f18cc646e9be957452003d09be4aed5ba774d\",\n        \"size\": 111878533\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6650_Weather23.tar.gz\": {\n        \"sha256\": \"0c0f2842013e32863ba544741fb520e0a3bdbcc5434146bc9fe5c65b7738b53d\",\n        \"size\": 130833734\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6652_Weather25.tar.gz\": {\n        \"sha256\": \"0e3523416b128ef78a8d876713c41d314de079bb34303dc5070a59a24698c9c1\",\n        \"size\": 143703299\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6654_Weather1.tar.gz\": {\n        \"sha256\": \"aaceb7fd734b87afcc90d575a5d45a482bdfd17b129f30a57366e58b8ec0c1b2\",\n        \"size\": 141046088\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6655_Weather2.tar.gz\": {\n        \"sha256\": \"9c4bbc998f975f1b93505382e04d3dc787d2de9232fe5cdd6a904451df47e398\",\n        \"size\": 224537201\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6656_Weather3.tar.gz\": {\n        \"sha256\": \"ef92f49ba3aace6b4b61ad16b3dd3d70d657dc3ed0c4b90997802e809264b76d\",\n        \"size\": 174831558\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6658_Weather5.tar.gz\": {\n        \"sha256\": \"2ac5777b8e947b1a029422099ed32b4361afb643e7a6b705ae236008a8ff2498\",\n        \"size\": 144798104\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6659_Weather6.tar.gz\": {\n        \"sha256\": \"8d3bd6b7ddc9c2074d713fd25efa58dd75821990a694d0c931f509e3ae72dd67\",\n        \"size\": 94401616\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6660_Weather7.tar.gz\": {\n        \"sha256\": \"a4358629fdc25134f51c82a1d821a2a9d32cd211c94215b5f70e6e88f8704639\",\n        \"size\": 134036756\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6662_Weather9.tar.gz\": {\n        \"sha256\": \"ed4ba70b65d29832d3f50fed748c17b362eb36e45e73e20d67e812ff9ed91c73\",\n        \"size\": 98153274\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6663_Weather10.tar.gz\": {\n        \"sha256\": \"e5cd5a25b2392e7cd65cb4af209341af85f1f35a5e698412f1f987f24f30cfa4\",\n        \"size\": 177185917\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6664_Weather11.tar.gz\": {\n        \"sha256\": \"faecb6c20dbb9ffdf9acd27080a5bf423ee409fd80d341fc0434beb3e6df914f\",\n        \"size\": 116977493\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6665_Weather12.tar.gz\": {\n        \"sha256\": \"838352a5afe89e9e7e3df63f039dd279a912eb85db713978c823cbb8cc8bf298\",\n        \"size\": 100163863\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6666_Weather13.tar.gz\": {\n        \"sha256\": \"b270a21bde2254b74420e96fb37107a37750b9607489186c161655d793a7873d\",\n        \"size\": 70469625\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6667_Weather14.tar.gz\": {\n        \"sha256\": \"0311a146cbb6ca55cb3d3524859d3daa102820ac1072e9b151b08eb014614d54\",\n        \"size\": 94917765\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6670_Weather9.tar.gz\": {\n        \"sha256\": \"429da4c56d0a02efc3e39b1e2ef522b8c9a2a1ce1e6478fb5dbbec43341b76aa\",\n        \"size\": 89794335\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6671_Weather18.tar.gz\": {\n        \"sha256\": \"19f173d3c26a481eb8bac0d054b1ac3219132877c10079ce028fe637be563cea\",\n        \"size\": 127404893\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6672_Weather19.tar.gz\": {\n        \"sha256\": \"a79fe2d3bd8dc7925df9534b3f74f75f899d6b026517b38f908992d49491a40b\",\n        \"size\": 101279288\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6673_Weather20.tar.gz\": {\n        \"sha256\": \"07e9d6f226370819c33fca8c92c2bcedadbbf9be413dbbfe32ccaf7046b4b20a\",\n        \"size\": 136424786\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6674_Weather21.tar.gz\": {\n        \"sha256\": \"57f1dc54ed0e517d947b2046dfc2a5bc304804970bb7055084d44518d1a66612\",\n        \"size\": 137959179\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6675_Weather22.tar.gz\": {\n        \"sha256\": \"36e4149dc78fd6b3fa663bdae1d7fa35123d5581a38d994fb9e2f7fda28b84cd\",\n        \"size\": 94488652\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6676_Weather23.tar.gz\": {\n        \"sha256\": \"438225e170bfb87db0419507bc81da5ee1b417a7d732ea10148f270a3c33a264\",\n        \"size\": 112789095\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6677_Weather23.tar.gz\": {\n        \"sha256\": \"0035a25926d5c861bb5660144e964279207ba96a8a52a40fe98c80865d8ad0ae\",\n        \"size\": 85655001\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6678_Weather25.tar.gz\": {\n        \"sha256\": \"0940d88716ca0db20abc230d06484d1b2fd674c7163d0635eedbf907c1b04b2b\",\n        \"size\": 149667901\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6679_Weather0.tar.gz\": {\n        \"sha256\": \"57dafa5d4f40132a454094fe318153f5d76db26c3d0932ffa806fd30b1a7f20f\",\n        \"size\": 216587594\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6681_Weather2.tar.gz\": {\n        \"sha256\": \"145a730f7d4a87042ca099f0a652637b89be7dbcf19d1cac7d6380a4ce9608e3\",\n        \"size\": 121689988\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6683_Weather3.tar.gz\": {\n        \"sha256\": \"37fb4a093f7ba2df4114aaaa959a6791f999af28a76fb79788445dc866db0528\",\n        \"size\": 143569052\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6684_Weather5.tar.gz\": {\n        \"sha256\": \"94357d6de4982b7aa67cc5a7fce8e2cfbbde0612c74f4fb4e6e12d901ca222ae\",\n        \"size\": 129669756\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6686_Weather7.tar.gz\": {\n        \"sha256\": \"9dd7ed041be471ec76d28331e697c208a988331c184bb861a373933c4a8ff267\",\n        \"size\": 179406616\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6687_Weather8.tar.gz\": {\n        \"sha256\": \"8db465f966a4a1bc57adff3c00655f96834d22017ff8557268979edc50b3e048\",\n        \"size\": 138739663\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6688_Weather9.tar.gz\": {\n        \"sha256\": \"06605a6fd9218cb0c52c4d0c40414bd91ff42d7d540c1388d4a367f74a4a7e85\",\n        \"size\": 107577678\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6689_Weather10.tar.gz\": {\n        \"sha256\": \"13d0f04e4202f825710c23385c36212c8cf5034497022616bf3c7fc800014584\",\n        \"size\": 126859580\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6690_Weather11.tar.gz\": {\n        \"sha256\": \"dcd7943e8b4d30d8647d8d8501eebf0fa9aa2fd6379a6253ae88e14d0cdb43c1\",\n        \"size\": 113820871\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6693_Weather14.tar.gz\": {\n        \"sha256\": \"4517e22fd71d5571495830ba2ab545d631b856aa6203be9be68fdde581e027c3\",\n        \"size\": 115476667\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6694_Weather15.tar.gz\": {\n        \"sha256\": \"3af78701429428db30e8cd27e9b4f4aef7e87cccd68fa2caf666cdc79049ec52\",\n        \"size\": 152610902\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6695_Weather8.tar.gz\": {\n        \"sha256\": \"f11b681065c7cbf682c15a77cdb69e4b0a55c35921eb609031d516fde9905036\",\n        \"size\": 172736219\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6696_Weather9.tar.gz\": {\n        \"sha256\": \"e1c1b0405f8977b1c180dc752b04e7f3f97d62644f5501922ab2e7d4132df24d\",\n        \"size\": 114825603\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6699_Weather20.tar.gz\": {\n        \"sha256\": \"3e36766dfae03a3905d8956a53cc91a41300d88e7de965ae828384993a4a5edb\",\n        \"size\": 142893841\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6700_Weather21.tar.gz\": {\n        \"sha256\": \"2120e795d8a6c7dc35c305888bbf22900341d4875fedded0f9a2427e3e19654c\",\n        \"size\": 111321561\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6701_Weather22.tar.gz\": {\n        \"sha256\": \"18ff006348ea341f9819b7ac47a646daa1dcaabcf5ec1c5e545a93347856dffd\",\n        \"size\": 98139066\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6702_Weather23.tar.gz\": {\n        \"sha256\": \"5a220c25f6db0d55c6ffea724a7deb405cb8e6355a7068e2e74264c356488955\",\n        \"size\": 126183289\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6703_Weather23.tar.gz\": {\n        \"sha256\": \"8e16f520962eaa9a4b5a45be3ca28f2c8a9a8ff5fbb9eb80e3216c5d604fa70a\",\n        \"size\": 143134789\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6704_Weather25.tar.gz\": {\n        \"sha256\": \"f66124a8b38f9d79f8e844dd1aefec503da7d081eb6b9e792003a400f37f327f\",\n        \"size\": 159257277\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6705_Weather0.tar.gz\": {\n        \"sha256\": \"5bb6ba3935459774f08787d0a850a15012371b2aa4157c072dc08fffa00225fa\",\n        \"size\": 141730373\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6706_Weather1.tar.gz\": {\n        \"sha256\": \"538c53f7427f985a6bd5ac54c17541d2f23125a6eed7890aec3ae5a391c9f3d0\",\n        \"size\": 122721165\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6708_Weather3.tar.gz\": {\n        \"sha256\": \"4b5e097e4cef620b53b18b891667fcbe263282c41c0f0dec96cb63e8ed636466\",\n        \"size\": 98075911\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6710_Weather5.tar.gz\": {\n        \"sha256\": \"7ed54cf469d9a288221b9a8116b11589942e25616f800639bfb39cf8c6ce17a5\",\n        \"size\": 119668357\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6712_Weather7.tar.gz\": {\n        \"sha256\": \"02cc5c159d6d361d30008bb280b9da294b6a88c7969d847babd2226982ba79bd\",\n        \"size\": 271874281\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6713_Weather8.tar.gz\": {\n        \"sha256\": \"b5db9d273db98d8e1869016873bb87ee30c7a05f2eb911a2ff82fb1b24d7d34a\",\n        \"size\": 144825785\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6714_Weather9.tar.gz\": {\n        \"sha256\": \"ebb586cc2f38e554f71eadc46c5eb486e95d5f62a37b2c710944acc2198f0025\",\n        \"size\": 117223833\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6715_Weather10.tar.gz\": {\n        \"sha256\": \"e783f35b81ee95b7c9dd1ae51d6385de4acfb31bdc194c586a45be3528b7b1f2\",\n        \"size\": 137558511\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6716_Weather11.tar.gz\": {\n        \"sha256\": \"acab7a91d6235a5194af34ef6fc7f6552cfec38307add267f7b81b0ea14fc129\",\n        \"size\": 101314185\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6717_Weather12.tar.gz\": {\n        \"sha256\": \"065e90b9973ad1748e7da230b050909f06f1947490ce7cc7be1373bb6c32ed9b\",\n        \"size\": 265308812\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6718_Weather13.tar.gz\": {\n        \"sha256\": \"3142bd5a7365538e28b4c54713de2cfed68f2ef794fb2124e4cf90ca610d37c3\",\n        \"size\": 281825050\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6720_Weather15.tar.gz\": {\n        \"sha256\": \"a051000cf8b73533ef5491e13a9b11512ec4cb0e75a504600845665a50a2ba25\",\n        \"size\": 105599310\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6721_Weather8.tar.gz\": {\n        \"sha256\": \"524f9768a2da3ec8cbcb8a3afe1ba16ebba28106d402396528c5c254f44e2166\",\n        \"size\": 122025319\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6722_Weather9.tar.gz\": {\n        \"sha256\": \"8a6f5fe18ccc32c4d63bf963e12ec46c2ad326940b0cad7e68d9b075f264008b\",\n        \"size\": 293442262\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6723_Weather18.tar.gz\": {\n        \"sha256\": \"0cbf2a0b03f9c74145f3fa2983004cc1a7ec1e7f91afb9b151689a3d004246c8\",\n        \"size\": 156102947\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6724_Weather19.tar.gz\": {\n        \"sha256\": \"84f6ab10fd48bce61d6c4dbaa0c5c8f61632c823f2dc91933d829548e20cf53d\",\n        \"size\": 155735309\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6725_Weather20.tar.gz\": {\n        \"sha256\": \"61b486521e307aa994f544b0b5e2719e2d6cd7f1ad3acce79f09112ddebdce9c\",\n        \"size\": 130779446\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6726_Weather21.tar.gz\": {\n        \"sha256\": \"6b6fbe4372fd055f484c741ca80fffc49f54474a264e34b6a281c155fd5b8ef5\",\n        \"size\": 180510565\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6727_Weather22.tar.gz\": {\n        \"sha256\": \"d58f96cf46e519aa3ac638bbd29a572bd3e6743ae0a673fd9c8f709d134b83bc\",\n        \"size\": 137620949\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6728_Weather23.tar.gz\": {\n        \"sha256\": \"7ef19d14ff67e688a248f8ded697d3a0697fe18b8cc7e4d7453577e53517724f\",\n        \"size\": 335328483\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6729_Weather23.tar.gz\": {\n        \"sha256\": \"cf820e4be861071fdcd900b5977ca43dc6e5000caa382c34b17d45cb2335dfd4\",\n        \"size\": 130844657\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6730_Weather25.tar.gz\": {\n        \"sha256\": \"df4ab4299101d032256e7f484cc71a6e3b0f60f3b8f09a6f408b9888b2fd2b7b\",\n        \"size\": 90651908\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6732_Weather1.tar.gz\": {\n        \"sha256\": \"b27864d9b59726be9eae5dabf2b3b756994fa63ff19e51bd3109df38a639b385\",\n        \"size\": 129095401\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6733_Weather2.tar.gz\": {\n        \"sha256\": \"3cc5b6e577d4b7f04f62a3451883ff339e78ee69ae7865c4dfbbc0b582a7cbb6\",\n        \"size\": 130536327\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6736_Weather5.tar.gz\": {\n        \"sha256\": \"4331fa7f4b98ed5a38db50c7210dfeefe9d9d160e5e9be1297eeb9a5c8b9fe72\",\n        \"size\": 180709887\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6737_Weather6.tar.gz\": {\n        \"sha256\": \"902745138170cb100ae6ebb5165b2b9965bc46096860d0c46d6aea0a8da404fd\",\n        \"size\": 141905684\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6738_Weather7.tar.gz\": {\n        \"sha256\": \"8b01d1af152f585944ee4912935fa80b9560902b80549a064a6b3c44e867577c\",\n        \"size\": 160032830\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6741_Weather10.tar.gz\": {\n        \"sha256\": \"d1a3f5d1fe25e6601e05f9df4088a3f35cf72999c51509560daee2c30a800f16\",\n        \"size\": 121526547\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6746_Weather15.tar.gz\": {\n        \"sha256\": \"e12d4b9c05a23a07870390b60ec6df3030afb2ec99a4cba6af07b453419d501a\",\n        \"size\": 146206838\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6747_Weather8.tar.gz\": {\n        \"sha256\": \"8175a6ebd5dadcc30792b702cc71623690d28580d2faf0da5ef1679ae8afa5b4\",\n        \"size\": 105965487\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6748_Weather9.tar.gz\": {\n        \"sha256\": \"3842ba0aa7a6fbf89a6e4a95758ef3447ebe575df8d746a81fe1897ffdc9c54a\",\n        \"size\": 103321497\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6749_Weather18.tar.gz\": {\n        \"sha256\": \"6a9d38c5c15038730d167722624c3ef7c347103b37bce68cbf52b3161d5c30a8\",\n        \"size\": 117724047\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6751_Weather20.tar.gz\": {\n        \"sha256\": \"0f154aad8a5a15b6cb60e950850c246865a37f10c3a91e81577227100505a1d3\",\n        \"size\": 155900867\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6752_Weather21.tar.gz\": {\n        \"sha256\": \"071cf57ea41bf3b89a58494e0e603eef7fdabacd5c46c1e1828b1de8afe496a8\",\n        \"size\": 156615277\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6753_Weather22.tar.gz\": {\n        \"sha256\": \"ab9ff8d2a4fb58deea7793a06c2606c72b276e5a01c72d217448133b5f574b6e\",\n        \"size\": 131871624\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6754_Weather23.tar.gz\": {\n        \"sha256\": \"809348343abd3537a65b7b672fbcdc11ab3a44fee46599a519b6347a789651e2\",\n        \"size\": 111280746\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6755_Weather23.tar.gz\": {\n        \"sha256\": \"d296de26a118e1b3652ffdd3aed3de303dd2836cca413184d9cfed0d91d116ef\",\n        \"size\": 143325787\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6756_Weather25.tar.gz\": {\n        \"sha256\": \"5bbcdf7f79809c096b084839e0322972131457fdbedff263cabaffc43a42227c\",\n        \"size\": 115190028\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6757_Weather0.tar.gz\": {\n        \"sha256\": \"64f9d6888df8fe8db265ef92f25cbf321c9c7e0ba43156b049b31d7eba1cf600\",\n        \"size\": 137588966\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6758_Weather1.tar.gz\": {\n        \"sha256\": \"545b8c0fb423aed1640a3e20c775ad379c129ce7eb3577ebf6abedcc18c1a4f8\",\n        \"size\": 150985841\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6759_Weather2.tar.gz\": {\n        \"sha256\": \"962d40e6fa5da2c9b49891caadb8cd2375cae5a51b05af8cd7131d8b54f7ecf9\",\n        \"size\": 143590484\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6761_Weather3.tar.gz\": {\n        \"sha256\": \"bdb150bff9d634d60c2e1e20c245d00bc53600d2deea9202011f4e05ec19607d\",\n        \"size\": 133811788\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6762_Weather5.tar.gz\": {\n        \"sha256\": \"c2ac66d03e8d5a238e8d578eb8d57b5e54a0ceaa0c66045ce91034264c050897\",\n        \"size\": 174018570\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6763_Weather6.tar.gz\": {\n        \"sha256\": \"f5e2999228fbf7b3246da9428764cd73a9f91ad7f582b1f91f09af0b0e69c466\",\n        \"size\": 171099503\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6764_Weather7.tar.gz\": {\n        \"sha256\": \"2fea6539a1691a2d2093de1c10718d5d95c41c068642318d3aa445484cfbd480\",\n        \"size\": 125085740\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6766_Weather9.tar.gz\": {\n        \"sha256\": \"12d10f0e262ae67fac55bacacdb8a190f0127861823f257eb2abfc931d4d9bfb\",\n        \"size\": 84643669\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6767_Weather10.tar.gz\": {\n        \"sha256\": \"bfdb28536c739a45d4e97389a7bf206f26caf3a74a8ddcbbd04fa90b297c33f5\",\n        \"size\": 117542311\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6769_Weather12.tar.gz\": {\n        \"sha256\": \"2505f6d172ecb58be9c9afdf80c340967e468b4cae32514542fed946b6dee569\",\n        \"size\": 118739099\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6773_Weather8.tar.gz\": {\n        \"sha256\": \"57ce804c7fcd9962d17ff37e0e38a0d5880b6b8c6af62149f0c96452dc79be3a\",\n        \"size\": 300991788\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6774_Weather9.tar.gz\": {\n        \"sha256\": \"379536068dc99a4d5bc539bd445b12c273e20fe37ebd13206f9c985bf17de023\",\n        \"size\": 115059987\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6775_Weather18.tar.gz\": {\n        \"sha256\": \"cd54ef85a48276c5f207ff87dddabbcf6985172347a98cbf8c7ea855cc287a1d\",\n        \"size\": 240230872\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6777_Weather20.tar.gz\": {\n        \"sha256\": \"27ce5a80e80ea81720957d20a35112add9f5e3e8b8a4b1c3366b323ab08b9285\",\n        \"size\": 99390016\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6778_Weather21.tar.gz\": {\n        \"sha256\": \"f6020ef02648426ad79a8282f8a694a0dc699493cd240cb5d579f734e844f8d8\",\n        \"size\": 147053722\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6779_Weather22.tar.gz\": {\n        \"sha256\": \"2513025a87e8dd78f0f9618ae39865b09c2f726dd2279c491511b69c936e5613\",\n        \"size\": 104886961\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6781_Weather23.tar.gz\": {\n        \"sha256\": \"055eadf72580cebfeede63d54cea26cf9a06686d88423525f398d2ceed3edaef\",\n        \"size\": 132214009\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6784_Weather1.tar.gz\": {\n        \"sha256\": \"186172a25ecbc3722c1d4a5fd2fa0ba1f1d74a670b8636334897f2f025d630d5\",\n        \"size\": 149764161\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6786_Weather3.tar.gz\": {\n        \"sha256\": \"78520e1c9bfbf21c600761af56b4ff60496ec3e9bba96ce7fb128ab5994e7f18\",\n        \"size\": 133509115\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6787_Weather3.tar.gz\": {\n        \"sha256\": \"ea1c9616c14b12bf1d42e618ae9bed70df146a3130d8779ea2b8f2217e6c3a0b\",\n        \"size\": 162996621\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6788_Weather5.tar.gz\": {\n        \"sha256\": \"089e5c2b58f1d532ea3675654536627f0befd7c39dfb590383a6097ee96e6d47\",\n        \"size\": 127422681\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6789_Weather6.tar.gz\": {\n        \"sha256\": \"72803dcdd778a3dd3d84087d708fb6bef8f9b39bce089f286e9adbf63e90316c\",\n        \"size\": 105566587\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6790_Weather7.tar.gz\": {\n        \"sha256\": \"af47896392be6b09ab3a4bb122ea6d5260d83b12fcdd13e457e3bca9ed05e088\",\n        \"size\": 187956261\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6794_Weather11.tar.gz\": {\n        \"sha256\": \"8581441c3032727a77ddb6eff4918f34464257d8e6ff52850ec1351753674d81\",\n        \"size\": 103224723\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6795_Weather12.tar.gz\": {\n        \"sha256\": \"fcf66b475263e0f085f3efaace01c509c067f6a365cf18b09008d3be20e010bb\",\n        \"size\": 98067887\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6797_Weather14.tar.gz\": {\n        \"sha256\": \"48508cf96532347b45ae16bd4a4f025085efec854c0cac8f654890a49045af31\",\n        \"size\": 116853037\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6798_Weather15.tar.gz\": {\n        \"sha256\": \"6d17cc66542ac509bfe6f7160f76de5c5e66dc268c812a3af4a7ab72724c8cc0\",\n        \"size\": 143274677\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6800_Weather9.tar.gz\": {\n        \"sha256\": \"2dc38a58b773feb95f392d09abcb80b988ad741a4e20972902994aaea57a4d89\",\n        \"size\": 172602690\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6801_Weather18.tar.gz\": {\n        \"sha256\": \"7665117c9cdf54dd5b26d365529bf885bbb800267e75d3ff34a64301fa05687d\",\n        \"size\": 139674295\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6802_Weather19.tar.gz\": {\n        \"sha256\": \"150ac87e8bb28d39dd22fa2b5fc40a7a84d9005c606ec369326a0e56a8473d58\",\n        \"size\": 123824281\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6804_Weather21.tar.gz\": {\n        \"sha256\": \"d15c20abe74745b969d4367d99cdca34eecb2a2ad520ff8871167ccf7b122df6\",\n        \"size\": 172444246\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6805_Weather22.tar.gz\": {\n        \"sha256\": \"eaf6bf1ca0791f2e07531830a29c21b966c724367d49fe4dfbfbac6f6999c7fd\",\n        \"size\": 107562253\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6806_Weather23.tar.gz\": {\n        \"sha256\": \"659375ad5a760d446581125bcca5c6148bd8abb65de778ba6ef2c995d13b1e62\",\n        \"size\": 130353704\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6807_Weather23.tar.gz\": {\n        \"sha256\": \"baae0c816799eb0b5f0f88ae3e7e3caf76c1569385831b86a90341e9169a1d13\",\n        \"size\": 95150877\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6809_Weather0.tar.gz\": {\n        \"sha256\": \"8549c1d9d9a263608b7cf8b8f3c7ee56eedbb40261de6906afdbecfca1556c83\",\n        \"size\": 120436793\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6811_Weather2.tar.gz\": {\n        \"sha256\": \"164c06e8eeee45554830ed2babf2d96548d0478aec42bcdc98f5191412f4ec79\",\n        \"size\": 107304725\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6812_Weather3.tar.gz\": {\n        \"sha256\": \"5ed56aa207b8e6255dc6aa2ca81e9dff22558716dfd365f5e7030bf76c685869\",\n        \"size\": 180780416\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6813_Weather3.tar.gz\": {\n        \"sha256\": \"fc895af9e2b0decf17cd4bb1b2891c9e6e57d20188c698aa1e765006cf6ae94c\",\n        \"size\": 195365820\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6814_Weather5.tar.gz\": {\n        \"sha256\": \"382652380ee0358b6e576670f8a868e6cc91a8b8d27d702734ce66e7599252d5\",\n        \"size\": 230654780\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6815_Weather6.tar.gz\": {\n        \"sha256\": \"58df81e2c42050a3aa9b54ba5e6a4296941cd1f9c7497c9ec6a3cab9310b0e5a\",\n        \"size\": 109321846\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6816_Weather7.tar.gz\": {\n        \"sha256\": \"47e6194433cc601f08edd58e6652fd2829aefdb028cbe5cde27917714a8f7f35\",\n        \"size\": 219741581\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6817_Weather8.tar.gz\": {\n        \"sha256\": \"c5b4fbcbf2bcdff820dc968b27cfd09dd93ca9189c056541240697479d34e4dd\",\n        \"size\": 88162614\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6818_Weather9.tar.gz\": {\n        \"sha256\": \"11ef324219ad83432f76e2c9ecf1bfbd3548c83d905ad17d4c7e0063cfe60621\",\n        \"size\": 104276109\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6819_Weather10.tar.gz\": {\n        \"sha256\": \"3c07fefb99a4966685ebe7a155e8fa84da76c209ce3f51aacc92131175537aaa\",\n        \"size\": 136268414\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6821_Weather12.tar.gz\": {\n        \"sha256\": \"f25500ca8ed3bd267d8a78df7a9a97167bb103ec78d7bc5c4cc964b36e30910f\",\n        \"size\": 80195797\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6824_Weather15.tar.gz\": {\n        \"sha256\": \"149677c7b117c5badd2bc323ffc1b51973febc8d4d4f4cb6b0605d5b507cec0c\",\n        \"size\": 121111606\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6825_Weather8.tar.gz\": {\n        \"sha256\": \"c1f09237a13ca8442a1c7c2eb2ee4c5e959295ae2fa8a3853e16eecfb6fe4c5c\",\n        \"size\": 131766767\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6829_Weather20.tar.gz\": {\n        \"sha256\": \"4056d9866fc89621b7fdf0f4142d4aab4cbf1f1e7304b8e82d3a59d4cf5e3e19\",\n        \"size\": 111972335\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6830_Weather21.tar.gz\": {\n        \"sha256\": \"51cc4b7a165e62ad62680dd0f3ac3abef873eff801f3f37413f76548f14224c7\",\n        \"size\": 158140268\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6831_Weather22.tar.gz\": {\n        \"sha256\": \"a98e82b92f329f41d22ec54379f1b58bf89f4651428fa4c7ec10dbb304c7d29f\",\n        \"size\": 108005648\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6832_Weather23.tar.gz\": {\n        \"sha256\": \"30532ab2266db913449089914e787159ee7fd611a371566d315441ff6c57200c\",\n        \"size\": 104666068\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6833_Weather23.tar.gz\": {\n        \"sha256\": \"d6fcf9cad34850969bd8e3e30f9dc5d298470633c16b75d6c5fdc5ce074659cc\",\n        \"size\": 149026657\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6834_Weather25.tar.gz\": {\n        \"sha256\": \"fd87d319c83a7547df8bb890b2ce161f17f179abb831ee3c9f0950a7d6db6b80\",\n        \"size\": 126355213\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6835_Weather0.tar.gz\": {\n        \"sha256\": \"b63d75641fbff63f7a8313f8f35a295d25c202ed78842ef15458f7aa6900ed1d\",\n        \"size\": 146356015\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6836_Weather1.tar.gz\": {\n        \"sha256\": \"b6cc877ad5cb13565c83cc359f0e7a8d91819755f6352ea1949e3175262ffa0b\",\n        \"size\": 144603920\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6837_Weather2.tar.gz\": {\n        \"sha256\": \"fcf684ea810bd6b8e55dbfbc6187667b4740bba2f022bfb5d82756a01e4e0cb4\",\n        \"size\": 143482245\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6838_Weather3.tar.gz\": {\n        \"sha256\": \"d2237eaeac37018a507cf26be6d19aec6d68a7784768ab5f737651aa458438e6\",\n        \"size\": 137350404\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6839_Weather3.tar.gz\": {\n        \"sha256\": \"fb99429c5587771eb095c3f6deaa491c56a78a340f65d1a9428367dba0de87ce\",\n        \"size\": 127113282\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6840_Weather5.tar.gz\": {\n        \"sha256\": \"039680f5764b9d99144c11a5cc4b3668e0f3e16926cad429fb9d3d55b50dbe41\",\n        \"size\": 123057122\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6841_Weather6.tar.gz\": {\n        \"sha256\": \"aa4cfec125eaa5f68d40c9f162aa81fc85a384c56a1d90db4819c2ac8db4460e\",\n        \"size\": 181463016\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6843_Weather8.tar.gz\": {\n        \"sha256\": \"98cb53c70e94da056f4d1696dc58ae4d40374eba381691001690359623e4cb37\",\n        \"size\": 138534274\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6844_Weather9.tar.gz\": {\n        \"sha256\": \"10729023b6325611ad9a7ef9e4f592d1e04de8f7e55dc4c4fc2bba40597b296a\",\n        \"size\": 91316868\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6845_Weather10.tar.gz\": {\n        \"sha256\": \"b60a052c8c34109260423fca07b955e59524038dbeabddda2256e4c5df2c1d34\",\n        \"size\": 118998172\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6846_Weather11.tar.gz\": {\n        \"sha256\": \"a8ad0920d81324fe7d4da6aeb0448377fbb5bd99b9d05e088b78488e4c1511d5\",\n        \"size\": 89320434\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6847_Weather12.tar.gz\": {\n        \"sha256\": \"2d624c94b3395f22f0ac5b7457337d580ba0c599683a3e58d42fb54bda326563\",\n        \"size\": 103232181\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6848_Weather13.tar.gz\": {\n        \"sha256\": \"2b8a1f234ba0f0b5f1b1dea69ad3794ffc6478f7827bd737058f929186cca787\",\n        \"size\": 117965644\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6849_Weather14.tar.gz\": {\n        \"sha256\": \"cce35521af9651dbef57e07a1d674d60942b4e11b0f3262f5e983a546bbcd6e5\",\n        \"size\": 102617944\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6850_Weather15.tar.gz\": {\n        \"sha256\": \"f38ef43f55186a9e87dd3ba37c415ad33eba10ec20cf8b7d0e5840132e9fd3b5\",\n        \"size\": 116444202\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6851_Weather8.tar.gz\": {\n        \"sha256\": \"716f25fefdf2e03661179377949a01cd9e6f4f7c732d704d1dce0e7f3e111edf\",\n        \"size\": 257735898\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6852_Weather9.tar.gz\": {\n        \"sha256\": \"02e0132c78c5b74341d3627eb79a1e97dcc6febdefa27e17fd410ee6319d4096\",\n        \"size\": 103300513\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6853_Weather18.tar.gz\": {\n        \"sha256\": \"1b4766421ed771a6d489c31ad591e48cd7aaaa362e3d87e1a00dfdfde3fe42a4\",\n        \"size\": 343712388\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6854_Weather19.tar.gz\": {\n        \"sha256\": \"3e74eca55cc4791445626645628ab0ae108bb2e2374c57ee48610774024ab5c4\",\n        \"size\": 108846373\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6855_Weather20.tar.gz\": {\n        \"sha256\": \"e5bc0e7a7d2a6f39c94dad518a71c6434b1973b773499836a8e234371491e53a\",\n        \"size\": 118688398\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6856_Weather21.tar.gz\": {\n        \"sha256\": \"4772076c2a1a4d0f76e5345be158af4e87b89495cd83655d11607381292d63c5\",\n        \"size\": 104956812\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6857_Weather22.tar.gz\": {\n        \"sha256\": \"5ddd0c3c0fd71d9f54ce3603b76370765da12a869c3303a681f5d7b90fca97fb\",\n        \"size\": 136364594\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6858_Weather23.tar.gz\": {\n        \"sha256\": \"b17ffddd7457183e9cb18c7874ff04f12190e86d1b42f19c8b87040b4abf1bbc\",\n        \"size\": 188791405\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6859_Weather23.tar.gz\": {\n        \"sha256\": \"35f2a6260ad7d2e96d36769651d2dfa3c285d020cdddcc315dba93e1d0063c31\",\n        \"size\": 113559267\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6860_Weather25.tar.gz\": {\n        \"sha256\": \"82ca21db6bfec2a4d513ada9a1dc20b7be2d624b76b11492e7bea4aa9df266db\",\n        \"size\": 100665424\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6861_Weather0.tar.gz\": {\n        \"sha256\": \"a354bf8ea1f23555386d6c54123a6fedba524f6b95911e5de2819a9edf2c8cdf\",\n        \"size\": 145222622\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6867_Weather6.tar.gz\": {\n        \"sha256\": \"d8902e3e1d8fda0eeac0804cd3464e8bce0389ba52e5c6f7f87211d22582228e\",\n        \"size\": 120270539\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6876_Weather15.tar.gz\": {\n        \"sha256\": \"c71d02e5779288f78d147ba955d8ab09f6dd4f4973aca0a3367189fb979a5311\",\n        \"size\": 102910185\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6898_Weather11.tar.gz\": {\n        \"sha256\": \"861a657a6a4655eb1d2815e8fb2d7adf61805656e6b2c34c56904d2a0c2b96df\",\n        \"size\": 103189337\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6915_Weather2.tar.gz\": {\n        \"sha256\": \"f15bbec682cfcd4974051c302582080c2d88a137fdb5c85edf4c6b470279e162\",\n        \"size\": 155971929\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6919_Weather6.tar.gz\": {\n        \"sha256\": \"6898fe5979ec5adfb2b1b6ab732f51496efc0efecefbe6f3e9e0894259ff1f24\",\n        \"size\": 125204743\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3623_Weather3.tar.gz\": {\n        \"sha256\": \"da101c6b6ff3acd82c7cd0ae5d228074724ee558a7cb0877094b1fac5cb2dc3e\",\n        \"size\": 315784684\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3626_Weather7.tar.gz\": {\n        \"sha256\": \"88527fd130b80c10d25c6a84d65dc46eebe548c474da8af02027b91c5e4810db\",\n        \"size\": 192182476\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3627_Weather8.tar.gz\": {\n        \"sha256\": \"2484fd5cc1d3a6ee16b4943c39b388310ada79ebdc54431a946980250334eb85\",\n        \"size\": 127093412\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3628_Weather9.tar.gz\": {\n        \"sha256\": \"45581eb3c272d339cee34ccdf4a1909bdf9d8e2241a2d0e8616926b34c2aebd2\",\n        \"size\": 140937774\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3629_Weather10.tar.gz\": {\n        \"sha256\": \"64af98086a2e7ec64d533932b80f97c9f26b7765d7b15b3764b08a876182fae3\",\n        \"size\": 131281166\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3630_Weather11.tar.gz\": {\n        \"sha256\": \"e31df20e5df83baabd9295d8079b06424e143ab25154b030304af60f51dcb57d\",\n        \"size\": 144686934\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3631_Weather12.tar.gz\": {\n        \"sha256\": \"0bd9aad0a235a34b933fb54fce18e7ea63f35875d82013dee0bb44ceef7598b4\",\n        \"size\": 118240132\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3633_Weather14.tar.gz\": {\n        \"sha256\": \"0be3e2daaef1a24ebb2dd09af6e50f91947ecfaa761ede444088fcabf39d44ee\",\n        \"size\": 151153966\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3634_Weather15.tar.gz\": {\n        \"sha256\": \"74d65a9949d6766ba0b1f6c286ba4ce028815b1628868abd0b9da9769b911603\",\n        \"size\": 169087296\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3635_Weather8.tar.gz\": {\n        \"sha256\": \"52a016b3840b3af9324cee6d433976bc794a6440942a3e6d8d6d5a1edabfb7ad\",\n        \"size\": 163138119\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3636_Weather9.tar.gz\": {\n        \"sha256\": \"47d9e2be57c63d33c9a2a07798548966e870e7b5d171793739cb6eda891dcc8e\",\n        \"size\": 122223812\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3637_Weather18.tar.gz\": {\n        \"sha256\": \"d365db205a1248937362a31ae6714b6607aba128dd3800999a756aacca929966\",\n        \"size\": 169375665\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3639_Weather20.tar.gz\": {\n        \"sha256\": \"c8b33df4744aeecf414db827609cc70eb15885a0ba92a2d6c543ad2bbf477780\",\n        \"size\": 113238533\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3640_Weather21.tar.gz\": {\n        \"sha256\": \"ad2133808b0c4d9c23320f55dec4ecfebcc84a0c7fd35b7b366b30af60c5e8f2\",\n        \"size\": 149826865\n    },\n    \"OppositeVehicleRunningRedLight_Town13_Route3642_Weather23.tar.gz\": {\n        \"sha256\": \"fa0dde55c5358b31810b32b92ea3aaebb68a4a18931ff94961bc9936554f339c\",\n        \"size\": 202754831\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27088_Weather19.tar.gz\": {\n        \"sha256\": \"c77b3a0a9f59d43ddf9961952db9095b70db6171c8b5fd0445a13c2c523b89f7\",\n        \"size\": 333407082\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27093_Weather25.tar.gz\": {\n        \"sha256\": \"e1335ad05345c8590f7eaf060818af5e05a2fc09f8363a8aa29ae67bcc584e49\",\n        \"size\": 347532179\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27098_Weather3.tar.gz\": {\n        \"sha256\": \"8cf1737fb0ab8401f2d53bfc17c708e45f7266180c46164dca9ce3adfece70fd\",\n        \"size\": 316922387\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27103_Weather9.tar.gz\": {\n        \"sha256\": \"7ac816d77393b72bc090b0a0ebeb39d503b0d2f39f262ddb100e79b680d34252\",\n        \"size\": 290335578\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27113_Weather21.tar.gz\": {\n        \"sha256\": \"cd896d175ae4d054e85495222ce2fce2e097364b83d2ee4687254310e55933fe\",\n        \"size\": 418023662\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27118_Weather0.tar.gz\": {\n        \"sha256\": \"8b24cc265c7ffe663d3dce3f90e156dbd7328870e4838fda78fc8f7c8609f0ef\",\n        \"size\": 429183039\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27123_Weather6.tar.gz\": {\n        \"sha256\": \"76cd9ae93bcfe6d662079ab7595ab07f2ab240f9d93d64ffc198b04dd82b9c07\",\n        \"size\": 461231046\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27128_Weather11.tar.gz\": {\n        \"sha256\": \"75e57253a2ed04c892333749591c6a652c21dd6f33155eec6ae1f11d89f47158\",\n        \"size\": 361920391\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27133_Weather18.tar.gz\": {\n        \"sha256\": \"68ec0a51d00bd33410286dbeac33d3eefebae1d68959e1964a3afe626e902f39\",\n        \"size\": 418758034\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27138_Weather23.tar.gz\": {\n        \"sha256\": \"7d764eb69b090a3b3646dd6fea3629bc986da2332716d03fa264b0836f9d5921\",\n        \"size\": 359225189\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27143_Weather2.tar.gz\": {\n        \"sha256\": \"120387ccd72da3ea7d1798f1ca13dbdd88a4b4deb065c55e911d8e0477f82cf7\",\n        \"size\": 346135677\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27148_Weather8.tar.gz\": {\n        \"sha256\": \"9db8eb1ab04925c4d10505d25d1294f00683d19428b0d4af04c5c1074009bfbb\",\n        \"size\": 270935825\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27153_Weather13.tar.gz\": {\n        \"sha256\": \"9a4b9d1ea50399a26059d27ab2719e8a27d719adbd72ce5ba5c7d462f7e4d1e4\",\n        \"size\": 343775739\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27173_Weather10.tar.gz\": {\n        \"sha256\": \"fb4cd9cc621ae30d4525199d61c9eaeaaf1f0b43db985e6c15bbfb94ff6bb084\",\n        \"size\": 327268530\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27178_Weather15.tar.gz\": {\n        \"sha256\": \"99f33eb0f24ff6ce9366da29b6aa513ffcf985408d74af0990aa6a6bfec8f650\",\n        \"size\": 303345227\n    },\n    \"OppositeVehicleRunningRedLight_Town15_Route27183_Weather22.tar.gz\": {\n        \"sha256\": \"6ec2bb610964e8bb7f045447a3283ddd13c8142a51f30808c8737ceb34a4582e\",\n        \"size\": 411061300\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27130_Weather13.tar.gz\": {\n        \"sha256\": \"50670dddbd04baf18920c4c0332c6f2a05f4d632443c8d562bd3182726974489\",\n        \"size\": 127359492\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27145_Weather5.tar.gz\": {\n        \"sha256\": \"f68667a7d48abd4dbcf40f8a2edacb058f21be15da76ef9a9a127b85291a3eaf\",\n        \"size\": 408321371\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27150_Weather10.tar.gz\": {\n        \"sha256\": \"d23ddada0b11306c38c1c810c4de0695155f87f1e6ca157a259ffb6f823b9d53\",\n        \"size\": 510065607\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27155_Weather15.tar.gz\": {\n        \"sha256\": \"c18227d97faaa83b64f84e66b9af4eb6b4e6230d9ce0f8df91bec8c175d0537a\",\n        \"size\": 163163025\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27160_Weather22.tar.gz\": {\n        \"sha256\": \"71af67afb5610ddfabd90ab37dcda316f001a605e670831af0271999d251e72b\",\n        \"size\": 164675526\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27165_Weather1.tar.gz\": {\n        \"sha256\": \"4deb9c907a79af5b54439c807d53a30841df50f5aa469b18f0bf066b604f6380\",\n        \"size\": 190239559\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27175_Weather12.tar.gz\": {\n        \"sha256\": \"0adebb5daef18707077db3970d4c8d270b69a303e76bb674a146667e615eca60\",\n        \"size\": 441232695\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27185_Weather25.tar.gz\": {\n        \"sha256\": \"f2f5393aef1eae2e3a0c399f20890937ff3b2ed75f363511dedee37f74ebe4cb\",\n        \"size\": 603617472\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27190_Weather3.tar.gz\": {\n        \"sha256\": \"8d1d7f27061338f2e4aff3421f710885885f4797ab0dc66af477d578fdd8ee14\",\n        \"size\": 169938251\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27200_Weather14.tar.gz\": {\n        \"sha256\": \"b4dd25df9da9eeaeaac214085023dec736ec284326cabda77561255285c08f5a\",\n        \"size\": 111968002\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27220_Weather11.tar.gz\": {\n        \"sha256\": \"4336c6151861bdf68b1ceb70aaaaa68d5ab520d8ca980ab42d5688091ca23ae0\",\n        \"size\": 112963178\n    },\n    \"OppositeVehicleTakingPriority_Town03_Route27225_Weather18.tar.gz\": {\n        \"sha256\": \"bcc4b6a903fb562bf51848d4bc21db3305e53a194ead0213d8122eee290118c4\",\n        \"size\": 172109422\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27209_Weather26.tar.gz\": {\n        \"sha256\": \"ba812c0dced25e37e0f78a736dc2dd2e772a37fd80220c69f325b3ff99439f65\",\n        \"size\": 793803281\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27214_Weather5.tar.gz\": {\n        \"sha256\": \"b5bcc5c8abef4d4d890519e5d3295fa75a6bd5db1954449f68f8befbb71dab55\",\n        \"size\": 198437871\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27239_Weather7.tar.gz\": {\n        \"sha256\": \"606e6953bb93e0ed8e28b11c4845701a229ed15a5ed5aee79f2b133e63c01ee9\",\n        \"size\": 475498045\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27254_Weather25.tar.gz\": {\n        \"sha256\": \"5a130fab6df026de25e74230ba6deb214a62e9083c61fcedec529e22dc02a76d\",\n        \"size\": 411402536\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27269_Weather14.tar.gz\": {\n        \"sha256\": \"fdf2d4dc4b9a859a38b63430d3c4a4641851a6e5f8cefb4e0f58f0054935f8eb\",\n        \"size\": 839690951\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27274_Weather21.tar.gz\": {\n        \"sha256\": \"5e3dad2330506aa1789cf341473fd645cfa22ee6dfb5ac4f3f82fc2ba3e010c3\",\n        \"size\": 1489219906\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27279_Weather0.tar.gz\": {\n        \"sha256\": \"94f66e3d0a9397f1ceca0b65e127a58e0a0318f1ccd7eeee5a47e2f2c4d0c825\",\n        \"size\": 1309162069\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27294_Weather18.tar.gz\": {\n        \"sha256\": \"27cc1f1e35e63f4056a26a3cbe2a77e1d06e3771d198e1e4b2e9e63c044cd552\",\n        \"size\": 211666962\n    },\n    \"OppositeVehicleTakingPriority_Town04_Route27299_Weather23.tar.gz\": {\n        \"sha256\": \"b1382d9af8239ce0be3750301c13e79601ed4200d8f85eda931a7a0b9b14b629\",\n        \"size\": 239058618\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27316_Weather15.tar.gz\": {\n        \"sha256\": \"29d6c4174891e20080d7e2bef169e20eede63d375f7871b12680b27016bdcb0d\",\n        \"size\": 1044242731\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27321_Weather22.tar.gz\": {\n        \"sha256\": \"9ba015a36d750265ec5c5f8cb0d3e77e0841908d5ce516eff4e54d9407996caa\",\n        \"size\": 201145319\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27336_Weather12.tar.gz\": {\n        \"sha256\": \"789513dc4f3d50cbd73768590ac40381f4357bca42711fb5014f0615b4a7ee69\",\n        \"size\": 135614318\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27341_Weather19.tar.gz\": {\n        \"sha256\": \"cf22a2333985a97a3063c7ae8e607899edc97d8d11e97dd69dce44c23e52e2b0\",\n        \"size\": 173972742\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27346_Weather25.tar.gz\": {\n        \"sha256\": \"7fd9218bece0d689b6316526964a8667a27620a09a8502446c8efb999adbd7ea\",\n        \"size\": 416201117\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27356_Weather9.tar.gz\": {\n        \"sha256\": \"1dbe0df2ec322bcc7d658e95729e0994abf063ee237fd654954b39cd4979a1da\",\n        \"size\": 252974548\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27366_Weather21.tar.gz\": {\n        \"sha256\": \"c339e4b48b3ca3fe1fd17124bebe200a6acbd704823afa78e7bf2c46549e7928\",\n        \"size\": 191159304\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27371_Weather0.tar.gz\": {\n        \"sha256\": \"b533bf90beb071360078a46845dbdc893301584bf95d6df978dc24fc5ea5b4fb\",\n        \"size\": 447182041\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27381_Weather11.tar.gz\": {\n        \"sha256\": \"4c0da58415ed2410394d1a02227c5dbb2ea9101ee17600b3f3a3be5efdb46322\",\n        \"size\": 151419666\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27386_Weather18.tar.gz\": {\n        \"sha256\": \"06469d0c45b41e28f38de729e5531ef83b1b55c818310adf2ea179e36cf99329\",\n        \"size\": 167317560\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27391_Weather23.tar.gz\": {\n        \"sha256\": \"ea5494280d7578cf7c5864552dd4030dc8cd1252129454ad670589bf27f87a87\",\n        \"size\": 165407760\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27396_Weather2.tar.gz\": {\n        \"sha256\": \"6142e2a1657ed584e205a5b796b9696d46eca4ddfde82945a65a982cf1550c9e\",\n        \"size\": 250170080\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27401_Weather8.tar.gz\": {\n        \"sha256\": \"37bce500ccd5f4fcacbd95c72c623723796c7e91e24e69a580ae14ccfbc6992d\",\n        \"size\": 172365784\n    },\n    \"OppositeVehicleTakingPriority_Town05_Route27411_Weather20.tar.gz\": {\n        \"sha256\": \"6f925a1c2afdb2cb77728ade0cccae5d89c0fb4dafb44c12a4a34d0e9a578762\",\n        \"size\": 133745869\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25352_Weather6.tar.gz\": {\n        \"sha256\": \"e0ee34d4e9849a02e74543c942557cf936414e22767b0e912779708b981402b6\",\n        \"size\": 280654665\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25359_Weather13.tar.gz\": {\n        \"sha256\": \"fe4531c4c9755c5b614d03c8672135e7e3aea3faa3a905cb230992c33e19124c\",\n        \"size\": 278445687\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25366_Weather22.tar.gz\": {\n        \"sha256\": \"259ec8aecf878dd48684841d5c102699a0d92a54208caafb0434f3c82b453630\",\n        \"size\": 181416576\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25373_Weather3.tar.gz\": {\n        \"sha256\": \"270276826113c16914fe4fd0eb4eca0194bd3e7870c2f76b16074f88395fe467\",\n        \"size\": 236717532\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25408_Weather18.tar.gz\": {\n        \"sha256\": \"8bff388d1ef070c3de84df332be16591032f0ddfada04808427b78f6ef7e75e8\",\n        \"size\": 726253291\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25422_Weather7.tar.gz\": {\n        \"sha256\": \"7d41d3a3bea0194cb00063fe8c5d1dfd88201bbbc527f6d3af8d1d978a3a817f\",\n        \"size\": 278169033\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25429_Weather14.tar.gz\": {\n        \"sha256\": \"189b9440eb2c3baef0ca306a65b529dd62d4adc1e3ada15b9f857363d2dd5056\",\n        \"size\": 705176988\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25436_Weather23.tar.gz\": {\n        \"sha256\": \"0cf483f95fc1395d8ec31da2a57a4414b24b58a530e99e330d5e24cb42683ea2\",\n        \"size\": 564762378\n    },\n    \"OppositeVehicleTakingPriority_Town07_Route25443_Weather5.tar.gz\": {\n        \"sha256\": \"032f7ee4578156393ade149b10ea1571e4075dbfc14ac4b47a3f552ff7be446a\",\n        \"size\": 236985171\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27067_Weather21.tar.gz\": {\n        \"sha256\": \"2f0cee66625c2255ed4583c447bc1f322c4527c1f9ab457459b33e11f80585ea\",\n        \"size\": 36830947\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27072_Weather0.tar.gz\": {\n        \"sha256\": \"0dabf2443f38eb55a8043560118652d91fd0f6c744a680507bc7027303606ae4\",\n        \"size\": 63561449\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27077_Weather6.tar.gz\": {\n        \"sha256\": \"c6b3fffaa11d8bc2f423ceaef7c6e920bcac889575a33d137aae7fab5c6ddd50\",\n        \"size\": 68205822\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27082_Weather11.tar.gz\": {\n        \"sha256\": \"cd8578c6a4c7ccf5516c12433418c2c3f42e4e4940bd3dea434418e94fa5725f\",\n        \"size\": 40671665\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27087_Weather18.tar.gz\": {\n        \"sha256\": \"4dc77f0a3b7bcbe467e1e290fb672fed7990f6777e78ee242b521d74a3d4d70e\",\n        \"size\": 65644299\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27092_Weather23.tar.gz\": {\n        \"sha256\": \"5993ffeaacc44981ac26695f9d6b48566bf520519844f1cb07e927143ad829c7\",\n        \"size\": 39514821\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27097_Weather2.tar.gz\": {\n        \"sha256\": \"eb556d08ef908957e938f000c1151e0383ae515027510adc35f3d3e6ae2befff\",\n        \"size\": 63033326\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27112_Weather20.tar.gz\": {\n        \"sha256\": \"5a77756267d3c905e42d448a4d6b83e5bc5ec5858876769d10e49de50f4da21d\",\n        \"size\": 37088398\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27117_Weather26.tar.gz\": {\n        \"sha256\": \"dfad5ebb40484cfe48b90118ba1da9dc7419344562a8a3c71cc8dc569d2ae2da\",\n        \"size\": 66635745\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27122_Weather5.tar.gz\": {\n        \"sha256\": \"d28c6352de817c9e25ce9d182a030492cc66dfc984b196c5494ced14a756aec6\",\n        \"size\": 61372786\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27132_Weather15.tar.gz\": {\n        \"sha256\": \"def8a69e93a14d1a2f9993cbc675b7e7af9ba398c0db299044bed6acaa42db9c\",\n        \"size\": 43663164\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27157_Weather19.tar.gz\": {\n        \"sha256\": \"d77811e510a417ce9a09285ee74b29126dd5fba04c06259a83b4f87d352a866e\",\n        \"size\": 44498501\n    },\n    \"OppositeVehicleTakingPriority_Town11_Route27162_Weather25.tar.gz\": {\n        \"sha256\": \"a1f2d9b24c78291f64f9cfaab98886623ae1d86308d2953f8a34934a6cc5cb96\",\n        \"size\": 34287254\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2124_Weather12.tar.gz\": {\n        \"sha256\": \"5b87d8f81c8bcfc1cee723f5f6b63df3c92e8def59754013a68e4cb408166e97\",\n        \"size\": 155312161\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2127_Weather15.tar.gz\": {\n        \"sha256\": \"b16530598c4177fc55bdb2a0d333b3c4e714915811fa8ea3c1a0962541db83f6\",\n        \"size\": 170324204\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2128_Weather8.tar.gz\": {\n        \"sha256\": \"f8bd974fa87f7b94328a4c913a31e013d4188558b0ce613e8fc81d6d8f43b022\",\n        \"size\": 224464827\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2129_Weather9.tar.gz\": {\n        \"sha256\": \"566a76432490efecf18e48e7e845ade97941faca683272f68dc1164f72a5d759\",\n        \"size\": 194477619\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2130_Weather18.tar.gz\": {\n        \"sha256\": \"597ac9b0c3ad01d3631d96e88f2ceac45b7caf0d9c3ab3bcef18e72a1e548990\",\n        \"size\": 233781321\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2131_Weather19.tar.gz\": {\n        \"sha256\": \"5d4b72eee1b938e7a03c5a70996b0d4e839bd684c9d368aab66cef01e666f5c3\",\n        \"size\": 183824804\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2132_Weather20.tar.gz\": {\n        \"sha256\": \"0f890d79239d059a49d3f5eab9aaa496e4e8d9b6779dbf8b0ee7526c91bb6310\",\n        \"size\": 194860855\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2134_Weather22.tar.gz\": {\n        \"sha256\": \"53613b7c3112b50ff940e2960504922aa103d58796c83dbd7cf4633d4259f10b\",\n        \"size\": 187585231\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2135_Weather23.tar.gz\": {\n        \"sha256\": \"8647636032701cdef5d1a0f6c332334e07d7747bfda6f9e2e129284e27ea998a\",\n        \"size\": 175801690\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2138_Weather0.tar.gz\": {\n        \"sha256\": \"f67f60caa4e764410d12ed6b7ee390b8d304dc33a59759827d75178f0d534a85\",\n        \"size\": 158875054\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2140_Weather2.tar.gz\": {\n        \"sha256\": \"7108b56c891eea3e68ca9f8bf7f66fda2f29457c586c0d0ebd578d01e18633bd\",\n        \"size\": 239269501\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2141_Weather3.tar.gz\": {\n        \"sha256\": \"b91b8c7aaa08e19e05d36ff5956741ea970a42d22c6d54eb9a598d989aedb814\",\n        \"size\": 197427204\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2142_Weather3.tar.gz\": {\n        \"sha256\": \"7ca267fdd7a2a87026107138f1d3ec360d0499233e5ecb9e2a9ceef9c57d0efa\",\n        \"size\": 217679263\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2143_Weather5.tar.gz\": {\n        \"sha256\": \"ab0b9a351d59e7d743b80cdee42c07473fb26ca5ca7b466f351cfb2ffbb9eed3\",\n        \"size\": 289660483\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2904_Weather12.tar.gz\": {\n        \"sha256\": \"4beea3955177ab8d9f410378251e7e52ea3a4994113f007f691eb4ef3faad434\",\n        \"size\": 246227355\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2905_Weather13.tar.gz\": {\n        \"sha256\": \"82670b560849c3be9092d6e38540f0fb752414577cce561ad5679b2713a6d65f\",\n        \"size\": 74670079\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2908_Weather8.tar.gz\": {\n        \"sha256\": \"cc49cdc9d85022eb8ab51ff7e4950a53be63273b5acb41548b479afc85f2096e\",\n        \"size\": 212980078\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2909_Weather9.tar.gz\": {\n        \"sha256\": \"90465a32e8ade0656f2ddc3837765394a2dc18206e5ef9563ca465e38560e9de\",\n        \"size\": 181938191\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2911_Weather19.tar.gz\": {\n        \"sha256\": \"ddd44680aeca2753924c13297c1ba3be1c6c12b86c62135732a6a8091da64e53\",\n        \"size\": 195176337\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2912_Weather20.tar.gz\": {\n        \"sha256\": \"c1f3374365ac7727e4471c0df64b3a838c51749f72cb8924a02c63180a889f82\",\n        \"size\": 158582533\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2913_Weather21.tar.gz\": {\n        \"sha256\": \"7a13106decf9b6cd97d1d6e195262ab75b3f34a67c49fe9ad6d98d5c8181027e\",\n        \"size\": 245831718\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2914_Weather22.tar.gz\": {\n        \"sha256\": \"3a4c16e62266336c85eb3df103da7c814ed73ed2b2022ac374e9375b603ebe7f\",\n        \"size\": 134698378\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2915_Weather23.tar.gz\": {\n        \"sha256\": \"cbb4888e1634e79c41c37c9c350aa90a647c33da8301053915a3461712bbf946\",\n        \"size\": 215286548\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2916_Weather23.tar.gz\": {\n        \"sha256\": \"cfe8434341e3b32ba261ec8a6d26b79be66cfef9535820288b04c03ecf91df78\",\n        \"size\": 236813961\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2918_Weather0.tar.gz\": {\n        \"sha256\": \"8028163b1084ef9d5900eb9e2f4571e4815aede8f8e67d979af6d9478c50a829\",\n        \"size\": 248808240\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2920_Weather2.tar.gz\": {\n        \"sha256\": \"7507c42eecfc1a54835438594099db1809ebc2c9f82e3f071ba7985c624ae84a\",\n        \"size\": 220649965\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2921_Weather3.tar.gz\": {\n        \"sha256\": \"6c3e63f88bd29bbee31b37851bb63405cdcdde26bbcd027d93c935b596a2827f\",\n        \"size\": 216575016\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2922_Weather3.tar.gz\": {\n        \"sha256\": \"7ff92d28c89709f57faf3ad52159bb80e9b823f36036fef9ff419b6b6b506912\",\n        \"size\": 210829664\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route2923_Weather5.tar.gz\": {\n        \"sha256\": \"62426bf4becc474babc8ba31252c5545d5efc314ff8510865255ef976fb21218\",\n        \"size\": 200169931\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8453_Weather6.tar.gz\": {\n        \"sha256\": \"62b942641c1af8c3dff3af0b5ad0a582abe902859ce488cc09f91fd31981c8f3\",\n        \"size\": 96039720\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8478_Weather5.tar.gz\": {\n        \"sha256\": \"24a58ed4281219ec0abb070662ada8fdf1171f115abff8fbc4812f9d24c15547\",\n        \"size\": 260137716\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8502_Weather3.tar.gz\": {\n        \"sha256\": \"5491c850360e5df6a6b4e38be80bc6b000b4da5ad6ff7ccbd227227838e43880\",\n        \"size\": 240503240\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8504_Weather5.tar.gz\": {\n        \"sha256\": \"5d13da2a84bc9b5fac6c0c98ad4909ed629ea33a24b94747e42bf38bb486f545\",\n        \"size\": 91666908\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8532_Weather7.tar.gz\": {\n        \"sha256\": \"12ebbefec09767a16698167d86c5f59e2bf5f9995edd4a2a797f7529283444e9\",\n        \"size\": 276242668\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8533_Weather8.tar.gz\": {\n        \"sha256\": \"1bdd30e7363786f3f53ca94da296d95d3b4214c1466cc462ce5aa0570c328053\",\n        \"size\": 201692643\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8537_Weather12.tar.gz\": {\n        \"sha256\": \"119ce8d636334dd741c7ce24cfbc125e2f066e5ec3c9b07cd62688145ab6fea2\",\n        \"size\": 135602145\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8545_Weather20.tar.gz\": {\n        \"sha256\": \"78997cda9880cb3a8c3d7c0296724bbbbd3ce721fedb387312ba29c0db3ce85b\",\n        \"size\": 298036134\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8552_Weather1.tar.gz\": {\n        \"sha256\": \"7f8eff1fa6ebb5f8af07fb2d83b0c5fe53680c5cfdba3a07cac6db671fde6ac9\",\n        \"size\": 363226408\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8558_Weather7.tar.gz\": {\n        \"sha256\": \"7858e6b609ff20a120f232f31ac20a3d94bea6016ab1f70b04b8dd12f366c64d\",\n        \"size\": 261852616\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8562_Weather11.tar.gz\": {\n        \"sha256\": \"29078c51c717db973b395a98a1592866a6e26a50838b806efdbf510b0050e0f0\",\n        \"size\": 249564573\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8568_Weather9.tar.gz\": {\n        \"sha256\": \"bcb8787eda7cf8df52e9fcae8af5231eed91f836ae4a3bff7d5e9805d4a5e7eb\",\n        \"size\": 187094007\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8613_Weather10.tar.gz\": {\n        \"sha256\": \"bf34253f4ba25a6585ae8689018440f15526f7dff10322ea88a2ffab7c65b03e\",\n        \"size\": 176668608\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8641_Weather12.tar.gz\": {\n        \"sha256\": \"7b91b02f1cf786e2e18058ab54db95091d4adccdd69e5ee70fa70bc281d7798b\",\n        \"size\": 152931223\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8659_Weather3.tar.gz\": {\n        \"sha256\": \"501a9105d972d1b85e4d390d6f7428f87ed30bcf276ce92b7d85f594a90e5e66\",\n        \"size\": 217757818\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8678_Weather23.tar.gz\": {\n        \"sha256\": \"3a0fdb8e04de1cc79a15777a7c32ebe7780acda78b14b52c15f666ea33b8a0ec\",\n        \"size\": 157124412\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8686_Weather5.tar.gz\": {\n        \"sha256\": \"2703f8e0329c90d7b4531a3cdd6f721cd4bab02aa440c96f194d1149540d5b21\",\n        \"size\": 187371598\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8705_Weather23.tar.gz\": {\n        \"sha256\": \"2a4ad7de5f8871bc76b675dd811c3239c7fc295eedc232eda9fdba987c97be19\",\n        \"size\": 194556837\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8721_Weather14.tar.gz\": {\n        \"sha256\": \"bcf981ff705124cf429fe917909b71e766f748237795ecf92af053f23b6913a0\",\n        \"size\": 277230311\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8722_Weather15.tar.gz\": {\n        \"sha256\": \"1a37fbe0be3a98189d4774245139f5754b365c16a14cd1275e984055d74a6a5f\",\n        \"size\": 325133068\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8733_Weather0.tar.gz\": {\n        \"sha256\": \"dafeaedd9564130c0e8f49bac6312e7c0655304ec55fbf8a30a67396455efa26\",\n        \"size\": 336125398\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8739_Weather6.tar.gz\": {\n        \"sha256\": \"b2883228764b12a17a47fbb48c7b02205c7738915615566ba9fcb965651e0254\",\n        \"size\": 210763234\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8742_Weather9.tar.gz\": {\n        \"sha256\": \"539c96c00c4b295c6d5d69317bf865529cdce96e8b5436800ac43aaaba28c573\",\n        \"size\": 324470689\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8744_Weather11.tar.gz\": {\n        \"sha256\": \"ec4adc2d0e666b17c04f96e9f4d369607b6a3d9389f7762af373a055319d149d\",\n        \"size\": 124179008\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8761_Weather2.tar.gz\": {\n        \"sha256\": \"81c3ab1f79f5ceaa54e7a3b114dfe55c191d13d3edc3641461ac806f3984adeb\",\n        \"size\": 284429182\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8784_Weather25.tar.gz\": {\n        \"sha256\": \"2a9f2afa437e39bba17e4de9191e238a093315c610674980dc0f88ffd3d06b39\",\n        \"size\": 220356786\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8806_Weather21.tar.gz\": {\n        \"sha256\": \"2999458367e77ffbc9a461fe33bc4e9e807c044d04bf1ad4410037e818ead435\",\n        \"size\": 203540348\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8818_Weather7.tar.gz\": {\n        \"sha256\": \"077d0a0602e00de34c6b5352e1ae6bc8ddf4dfd3bacc45a6f52cf763c9973877\",\n        \"size\": 211088139\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8831_Weather20.tar.gz\": {\n        \"sha256\": \"3abc36ed88aa9b4fdc3c3c1386972b5f6e6ab9ee2945abc72246bc52e4120c4a\",\n        \"size\": 228103398\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8848_Weather11.tar.gz\": {\n        \"sha256\": \"bfbeae0b9781c15b23debb80cdbc229b8808a7f53678799a15364dbb05576af1\",\n        \"size\": 276832756\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8852_Weather15.tar.gz\": {\n        \"sha256\": \"c70713d65374c56b7b1369646ebdc818ca6205b61afda49e5709146c61c6ab20\",\n        \"size\": 251656258\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8865_Weather2.tar.gz\": {\n        \"sha256\": \"280635945e99759a50ef1d6a091030489edbed146e7fdbd384190c9f0e74915b\",\n        \"size\": 238727986\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8908_Weather19.tar.gz\": {\n        \"sha256\": \"bc666fe659468dd6148d63065c480ad82231a60851c2b234d48781caddd7b857\",\n        \"size\": 210317399\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8911_Weather22.tar.gz\": {\n        \"sha256\": \"015fa197240e08e1d2d7734ce58284ae46f34b64731f83b1078d332bf31cfc4a\",\n        \"size\": 185151045\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8912_Weather23.tar.gz\": {\n        \"sha256\": \"850bf549316520863b75f53d76a16189cdeec9ddfe7d1045b9a3f62a6132960d\",\n        \"size\": 183700468\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8929_Weather14.tar.gz\": {\n        \"sha256\": \"5c5d32059fa3cd762feffc91360e7ab611c187cd8ada6369e2321ccab2fbfe2c\",\n        \"size\": 193753352\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8971_Weather3.tar.gz\": {\n        \"sha256\": \"ed79452e100ab1da5c7797d0a04dc26593551d4351a920ba8fde2514ef4831b9\",\n        \"size\": 210762286\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8992_Weather25.tar.gz\": {\n        \"sha256\": \"24dbeee0e05665be05cb6939bd99912c82e00fc6857f091ce3e0e8f78bc19003\",\n        \"size\": 208249943\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9005_Weather12.tar.gz\": {\n        \"sha256\": \"a29bc9cd058c7338e1eb4486d3c885f1cfbe2d4baf69c1ba09e7edc5ac79561e\",\n        \"size\": 254563904\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9011_Weather18.tar.gz\": {\n        \"sha256\": \"2b0f2688677bf903aa47446882f2b21848a069f486c4e89831c61b98a6396e06\",\n        \"size\": 263200103\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9035_Weather8.tar.gz\": {\n        \"sha256\": \"b143d0e51f7e684eab57b9101acbe8a7afb52933c7c48badb8e74ac0c2d19ab8\",\n        \"size\": 218162174\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9045_Weather0.tar.gz\": {\n        \"sha256\": \"a7f1e92d7cde018e4dfda460ff99763af2a6bdfc5e1fef113fb08107d02bf5ec\",\n        \"size\": 313601718\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9061_Weather8.tar.gz\": {\n        \"sha256\": \"de67ef84ca6d4905bc619d59fd099547a50105eb6532f6932266374e174b8406\",\n        \"size\": 263713152\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9092_Weather21.tar.gz\": {\n        \"sha256\": \"c84021d9d14a4d391f50883e8637fb368f73959c2a354421c53871c6077c14dc\",\n        \"size\": 184443632\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9094_Weather23.tar.gz\": {\n        \"sha256\": \"6de56d943eb0334711aa0a41c9691c4c6d50ddf6bdbd89c3ab7ae0a0b0d643e1\",\n        \"size\": 179032023\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9106_Weather9.tar.gz\": {\n        \"sha256\": \"fa8409211157f8c3f5bac9c8e5e2049e62ae4689adba7654ee07411421d4971f\",\n        \"size\": 240847285\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9119_Weather22.tar.gz\": {\n        \"sha256\": \"debc0da38a16eadb112cccf65cbc77f44b14a143694a837357d3f2825f9ddc7e\",\n        \"size\": 183446552\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9139_Weather8.tar.gz\": {\n        \"sha256\": \"eff0f47b119c944313da79b4aac94d4d506c0a1410133e47bae6b05a1ad2e7ec\",\n        \"size\": 302661636\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9180_Weather5.tar.gz\": {\n        \"sha256\": \"2e4915a66d2ba299bf4b579dcac2276c510ed0252966ee4320571d925c0ec9ba\",\n        \"size\": 304838529\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9184_Weather9.tar.gz\": {\n        \"sha256\": \"c24e7cb05de19ae57953ebacfa945200cc6598fcd3a4228e07005cd2552c60eb\",\n        \"size\": 175092794\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9197_Weather22.tar.gz\": {\n        \"sha256\": \"b6f6d11eed5f23f2a304ea92e0e6e342e473fb79367874b0476202b3a76f71d8\",\n        \"size\": 169519175\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9206_Weather5.tar.gz\": {\n        \"sha256\": \"0a23573f552fc902e8fd99edb5ef34887290aecd1e146ed95f007d355a23b498\",\n        \"size\": 261646483\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9231_Weather3.tar.gz\": {\n        \"sha256\": \"a4689c90ea1fc1b4862f1cbc0c684f13183d607cbab06dbb747f374656cdd119\",\n        \"size\": 292515177\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9244_Weather9.tar.gz\": {\n        \"sha256\": \"6dc990ec73feb59b59ec767a92af228efdb35d1ff2a2a5969b3b611749fcfe75\",\n        \"size\": 244726140\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9252_Weather25.tar.gz\": {\n        \"sha256\": \"3641c172e032459e466f03a9e80b805b55570e073b1c4fc823daece968cefd85\",\n        \"size\": 175204440\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9264_Weather11.tar.gz\": {\n        \"sha256\": \"d076980855373a5145b9310695cdb02006c8de8a2230cb56b38f18510cff9654\",\n        \"size\": 207513108\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9270_Weather9.tar.gz\": {\n        \"sha256\": \"85f51eff6089c30dcad27a0d7fb552dd83d045f3b73660ee81ff4ad22b453ec9\",\n        \"size\": 231943260\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9304_Weather25.tar.gz\": {\n        \"sha256\": \"95db63e38dcebcc5b7b3ea34b945d4b8fa625cb6850afc7f815ceff8f48dc872\",\n        \"size\": 131967556\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9331_Weather0.tar.gz\": {\n        \"sha256\": \"67887685dc372b70ea38689391eac0fdd785a3a940e9732f6654280160133591\",\n        \"size\": 205769315\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9339_Weather8.tar.gz\": {\n        \"sha256\": \"1941ec072d4c78bac26930bb4186a6c7d0f75256589d210696892b272f490782\",\n        \"size\": 179602502\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9358_Weather1.tar.gz\": {\n        \"sha256\": \"b4ca39c60a9bf5e301a1b200feaeea8c251412036de25274b9fc95db2bc7cd4d\",\n        \"size\": 200769408\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9363_Weather6.tar.gz\": {\n        \"sha256\": \"8d5e5ffca3b14eaecba64c75ad9a113c997d9d36b9a674a47e5429317c8459d6\",\n        \"size\": 212425710\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9369_Weather12.tar.gz\": {\n        \"sha256\": \"bd93ac90c57a223a8879c4985f8354746572b54dff87725a691aa97eb17b17ed\",\n        \"size\": 276153406\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9372_Weather15.tar.gz\": {\n        \"sha256\": \"2c8d5a85dcb2e206cf67902a5421b4fc3766381b2919fed807a6bf1055cbb97a\",\n        \"size\": 192812496\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9374_Weather9.tar.gz\": {\n        \"sha256\": \"43c35df51054c78bd8d3202baf093a3774b18dd6f72fb3d439e841c9615de9ba\",\n        \"size\": 238780126\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9383_Weather0.tar.gz\": {\n        \"sha256\": \"2ce3b10675e1f143c4ef45aff47ee59e432a0612a9aa6ff57b4aa1f8bd3feec7\",\n        \"size\": 261331028\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9388_Weather5.tar.gz\": {\n        \"sha256\": \"9e34398ac28d37b5a9bb4f3dcd69241f1d07c311b8a7df109e9dcffc8afddd4d\",\n        \"size\": 1194438050\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9411_Weather2.tar.gz\": {\n        \"sha256\": \"e1f3556ca57fb9626302100bce0124ad57644a53f3aeb10add9ebf72b45df62a\",\n        \"size\": 100734351\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9432_Weather23.tar.gz\": {\n        \"sha256\": \"570154946125e0b91a5fa817e3f33f7416ba874ac0bb021efcfa25fba49be6c2\",\n        \"size\": 227800316\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9434_Weather25.tar.gz\": {\n        \"sha256\": \"197e40f1d892349d991b6997474d52a470bc1d0fb65a2fb1e9185fa16d4b37f7\",\n        \"size\": 181207213\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3686_Weather15.tar.gz\": {\n        \"sha256\": \"a7c16dbc9bad37e2886ea8d177e861820ad28b21008e3d1d63eaff2b8aa8a74a\",\n        \"size\": 190854840\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3688_Weather9.tar.gz\": {\n        \"sha256\": \"f210dc0524e915656ebdec6726f911f4d0002edebca9418e64d8bda8690a5129\",\n        \"size\": 104844017\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3689_Weather18.tar.gz\": {\n        \"sha256\": \"862a64f09e33baf9766e3ad6250ab06f097c83c5103f63d34af6a15563266009\",\n        \"size\": 232591202\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3690_Weather19.tar.gz\": {\n        \"sha256\": \"81c555311a140ce82643a7bc82a612a5e39c1c89d3d3c341e194a148ffdead6a\",\n        \"size\": 200568972\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3693_Weather22.tar.gz\": {\n        \"sha256\": \"34c7f35a520f15390ab31ea6990f5468056d1a11c5ece8b35192dc226083245c\",\n        \"size\": 149870045\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3694_Weather23.tar.gz\": {\n        \"sha256\": \"062350d56c69d6df3a95a972c4b0382ef9db8f83033449796f212555960e6f61\",\n        \"size\": 182667325\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3695_Weather23.tar.gz\": {\n        \"sha256\": \"62167878e099f584f03059f84c422254522002d75205674c4a1ee70dca3e3c2e\",\n        \"size\": 122096177\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3696_Weather25.tar.gz\": {\n        \"sha256\": \"1ba39cbca43b0762d1503175e11233fee0755a0cb94f12fd5f159eb428790cf4\",\n        \"size\": 108792057\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3697_Weather0.tar.gz\": {\n        \"sha256\": \"05122e061dff07e7cbb33a1ff285de75ac758285c21eaf7e7489e4e7edadd0b6\",\n        \"size\": 144989488\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3698_Weather1.tar.gz\": {\n        \"sha256\": \"f621daed798fcee1d455febe5c6fd3c02dbdad321dd7b9af75242dc5bf315681\",\n        \"size\": 254515380\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3699_Weather2.tar.gz\": {\n        \"sha256\": \"b377c73a2250cb12788163c6cd16517ce6213ed4f74701d4b071cf28d616656a\",\n        \"size\": 172461791\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3700_Weather3.tar.gz\": {\n        \"sha256\": \"9dcddbb872e4523073595d976f04d150ccb5a8834582afd2cd2f7c90ed513c64\",\n        \"size\": 182284365\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3701_Weather3.tar.gz\": {\n        \"sha256\": \"f560839b9da488e78ca13c231c6a8f9b53566eda275e58fa923bcd87b5aee5af\",\n        \"size\": 123219892\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route3702_Weather5.tar.gz\": {\n        \"sha256\": \"789723a1fa9a2faddacd8ba74943931016fa4c743476d8066a047d98d82317f6\",\n        \"size\": 164787551\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25889_Weather14.tar.gz\": {\n        \"sha256\": \"155a1f90903eef7b456361650e580d47c1afdb42b27267b44abc3453bfeb134a\",\n        \"size\": 315414154\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25896_Weather23.tar.gz\": {\n        \"sha256\": \"f1e03ce5776a1991faec16fe6e93bdb9447a0f973d49e08123ea98f6bea5c733\",\n        \"size\": 1021683015\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25903_Weather5.tar.gz\": {\n        \"sha256\": \"816f7b90d49c49dc70383c8200737a3f8beb687065d7faaece7b07fd0a7d747e\",\n        \"size\": 342266128\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25910_Weather12.tar.gz\": {\n        \"sha256\": \"f0d9a4cd5ee62fab445806d97a5c5385ba515391f6341495fc0d3b214c731361\",\n        \"size\": 212458121\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25917_Weather21.tar.gz\": {\n        \"sha256\": \"12eac19ef9f3d13b720358f3aa9e0e732d6d93273d93531589cabbd1db4c6ede\",\n        \"size\": 1009791594\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25931_Weather10.tar.gz\": {\n        \"sha256\": \"176fc81aad2a95d6342b914ec867b429fe72f55f72099085f27f45055409eec5\",\n        \"size\": 257279637\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25938_Weather19.tar.gz\": {\n        \"sha256\": \"ca255af2c4d1a06c7d9be0cf95d1187910df65e91e66b8b0b706166b89fe3fb5\",\n        \"size\": 473669674\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25952_Weather8.tar.gz\": {\n        \"sha256\": \"664ad085939269c7b9f272031511ab923acbfebea4e4b50fb126a869cc2ae4af\",\n        \"size\": 409205812\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25959_Weather15.tar.gz\": {\n        \"sha256\": \"b253a81fc6a704b5ef443dcc4b3a5e0d1ec4a5a2d86da569d94dc0a3a6f3fc9c\",\n        \"size\": 1187446713\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25966_Weather25.tar.gz\": {\n        \"sha256\": \"ed9d738ec22a34c5f84abe4211feaa747f63991d436d065b14675aba41840114\",\n        \"size\": 301927178\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25973_Weather6.tar.gz\": {\n        \"sha256\": \"e982ec1c1ec6dedea7513840c1c6542008ff7f9c1b18410e0adf0ce514a756a0\",\n        \"size\": 677445422\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25980_Weather13.tar.gz\": {\n        \"sha256\": \"abe231f0a2c8dcd33230cc851cd2d3dd58b3c375f2d02aaff29270437e56c848\",\n        \"size\": 498581136\n    },\n    \"ParkedObstacleTwoWays_Town03_Route25987_Weather22.tar.gz\": {\n        \"sha256\": \"54bc1a8d66ca2353e1fb40c9670a17a8105e199047e44b1d8a221a27099f97f3\",\n        \"size\": 490051375\n    },\n    \"ParkedObstacleTwoWays_Town10HD_Route24300_Weather12.tar.gz\": {\n        \"sha256\": \"cd7c1907cd5e50c26469d28c8452dcb8661ceb0139138cb28b987f47f37bf575\",\n        \"size\": 212158601\n    },\n    \"ParkedObstacleTwoWays_Town11_Route25844_Weather15.tar.gz\": {\n        \"sha256\": \"dca321bc7537dc317691816d45df1120f73035dabc6a81378e222fca3931a830\",\n        \"size\": 70992718\n    },\n    \"ParkedObstacleTwoWays_Town11_Route25858_Weather6.tar.gz\": {\n        \"sha256\": \"54b00fc4dfea4f23646890874e33ce1122b908c1221311754bb370dc3b7b0489\",\n        \"size\": 96606874\n    },\n    \"ParkedObstacleTwoWays_Town11_Route25865_Weather13.tar.gz\": {\n        \"sha256\": \"b5ee875c20d5c0c3e57602bc68e8928d19f63b04de482ba0da2dcac947aa7d6c\",\n        \"size\": 83631650\n    },\n    \"ParkedObstacleTwoWays_Town11_Route25872_Weather22.tar.gz\": {\n        \"sha256\": \"fc08801cb11266995dad6abd2a8b89150bc01caf62adc04edf5dc407b006230f\",\n        \"size\": 90585030\n    },\n    \"ParkedObstacleTwoWays_Town11_Route25879_Weather3.tar.gz\": {\n        \"sha256\": \"2f3b7553969a9c8930eae1600d525e7973ea567152b5aea6539966b78e1523fe\",\n        \"size\": 130783261\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1885_Weather7.tar.gz\": {\n        \"sha256\": \"484572dfd56e33db723460ed9c60fda14152d239a8c92c5a91790c9a7c366f82\",\n        \"size\": 323643888\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1886_Weather8.tar.gz\": {\n        \"sha256\": \"be36e3b29697f17d21e8fb108edef6446121b53b48fb1c66c3becc625e511410\",\n        \"size\": 516499180\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1887_Weather9.tar.gz\": {\n        \"sha256\": \"1a509b3fd076fd4beacb4811dc6ef1c7a7d9e380ddbb7f8113006548a8ea2f4d\",\n        \"size\": 649033580\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1888_Weather10.tar.gz\": {\n        \"sha256\": \"d5058e935e288fcb7a5f7794a294d3e9994cd0d723e0735d3139e89ebd834356\",\n        \"size\": 518324351\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1889_Weather11.tar.gz\": {\n        \"sha256\": \"6f2c5ccb725347a2ba1cec46e21be6c0ab55e24a38c579b191b3fc00e078d128\",\n        \"size\": 708514242\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1890_Weather12.tar.gz\": {\n        \"sha256\": \"a8b4b355d491d2422679bdeb6ade5c3cc39c69298b3676fb51bf38d2d7cae075\",\n        \"size\": 830607264\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1892_Weather14.tar.gz\": {\n        \"sha256\": \"c2d6ead9cdf071b2632dcf4b37e3ac431b4c2e234469110c413d29088078300e\",\n        \"size\": 279098341\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1893_Weather15.tar.gz\": {\n        \"sha256\": \"87404c29aef70e323bd5bf6466f17e9ee28f574366e9b556343fbf11624d4383\",\n        \"size\": 268590047\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1897_Weather19.tar.gz\": {\n        \"sha256\": \"a8f22df298e2afd0e2c69eadcfec1ecf2b24cb7dbd4cb525b586475e868f5d74\",\n        \"size\": 619906052\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1898_Weather20.tar.gz\": {\n        \"sha256\": \"85e74c9eae8783e36ad78cd050c44fbf2844667cc35f03d363756dd8956efe41\",\n        \"size\": 297732366\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1899_Weather21.tar.gz\": {\n        \"sha256\": \"b9b149845c8552d2d63bc1a63e62fd31965ed688e6f75236ab23b85f1ba67f2a\",\n        \"size\": 694022088\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1901_Weather23.tar.gz\": {\n        \"sha256\": \"8d67feff6d19990895f0df8115bdcc213ad3efb5f961fba81f82dda044271b0b\",\n        \"size\": 209303077\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1902_Weather23.tar.gz\": {\n        \"sha256\": \"200db7528af975f8b4816b7cde0f2c14d6f68086785feba5c915c1c0216b2006\",\n        \"size\": 243512290\n    },\n    \"ParkedObstacleTwoWays_Town12_Route1903_Weather25.tar.gz\": {\n        \"sha256\": \"66310a5edeb7c5e1b84edf7e5186ecc1cfb4cbc9e56f96ac3d0693ba78c31fee\",\n        \"size\": 222395669\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21493_Weather8.tar.gz\": {\n        \"sha256\": \"fb7277879c517d27cfb25522d78f4079688d0f3c6513c1d5be5c67d0ce6704f1\",\n        \"size\": 295461100\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21494_Weather9.tar.gz\": {\n        \"sha256\": \"1b8ac6fcb54de71591aab203701dc5f09fd5869b8680f9d4b5a2d7047e263011\",\n        \"size\": 242332846\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21495_Weather18.tar.gz\": {\n        \"sha256\": \"52cc83b0379b27b3107970f868c0d72de2ea7cb33d378a563581c88d560f62c9\",\n        \"size\": 305137552\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21496_Weather19.tar.gz\": {\n        \"sha256\": \"b134f571bf5199acc74589af52412d39a28dcc1e2b2891b6d4d46a145b9cca58\",\n        \"size\": 295247273\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21497_Weather20.tar.gz\": {\n        \"sha256\": \"2d9e8a6813132d50c4d757c48e9fe79ca19b3d0e9c40396958c92dda3aa5bd40\",\n        \"size\": 262802203\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21498_Weather21.tar.gz\": {\n        \"sha256\": \"fb9ce379a021ae63e2997d4468aac7c3d2eaa7ea4ebe029242bf36b7fa90d116\",\n        \"size\": 229743181\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21499_Weather22.tar.gz\": {\n        \"sha256\": \"23f426ebe86267dcf870a381fa18486c23afb41a340e2100393481cafc4ed556\",\n        \"size\": 277123439\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21500_Weather23.tar.gz\": {\n        \"sha256\": \"a7ea654c7cb37a8de5b873df7b919729868e62355ed45d89ce1a8e6858a3d3c2\",\n        \"size\": 242973603\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21501_Weather23.tar.gz\": {\n        \"sha256\": \"98b7f4325684f539846c6f8893472898138f5c8e7ddd2b0b055684f5a3adee37\",\n        \"size\": 248125026\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21502_Weather25.tar.gz\": {\n        \"sha256\": \"1291ce6f91b94e9dc8c978dba1e0afae981b0cebe1b2306b07557e521fd9c36a\",\n        \"size\": 247085202\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21503_Weather0.tar.gz\": {\n        \"sha256\": \"343f3a37dc0cf5004fe5c7e9281218752e082057f68c9ed5aab0e60db3b128a9\",\n        \"size\": 293490210\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21504_Weather1.tar.gz\": {\n        \"sha256\": \"44ced2cfb0ae480a99da84dcd8349bb17b8159a2be805dab35cb4e1dfc7b575f\",\n        \"size\": 308733848\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21505_Weather2.tar.gz\": {\n        \"sha256\": \"dcf8ac347278e9a3b5ab53a3caa90641b6c25e0f8735d0e43f74c6ad01095fed\",\n        \"size\": 289208988\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21506_Weather3.tar.gz\": {\n        \"sha256\": \"dcd11d7119af6bc16ece964e8a0a8e92cd75613c461fb8a6e406f2e9596bb03a\",\n        \"size\": 312281562\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21507_Weather3.tar.gz\": {\n        \"sha256\": \"26a5e26b698c2699c64d1a4b42bacb3f7e546c84d83497f052a83fa7047ba539\",\n        \"size\": 270138260\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21508_Weather5.tar.gz\": {\n        \"sha256\": \"a77a23e722027955e9e923b1bec1dd7b8f85239c128a8c6337d751520954f745\",\n        \"size\": 295681919\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21509_Weather6.tar.gz\": {\n        \"sha256\": \"ef43ed5d49515b9404dfb693e0afcc130b4df4703b82e33c8ec4e63d0511ad95\",\n        \"size\": 284048787\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21510_Weather7.tar.gz\": {\n        \"sha256\": \"e58ecead79aba46ef1e014f55a4021d1d90ad5832cd9cb9633f5e47bf4c65b70\",\n        \"size\": 367823770\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21511_Weather8.tar.gz\": {\n        \"sha256\": \"56b280a1340412c29d40b36a2997b8523247750114abfbcab2b20a5ea6d6d59f\",\n        \"size\": 277159220\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21512_Weather9.tar.gz\": {\n        \"sha256\": \"93f21cc45d6111d905ea822ab9f674c5bfbdc92aea304872eed6f5b73116f3f0\",\n        \"size\": 221946519\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21513_Weather10.tar.gz\": {\n        \"sha256\": \"db2ced51c30d0a4fbed21364e99ffadf9330f0e08bc9c9f99aeb0b8f8f558eb8\",\n        \"size\": 257093446\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21514_Weather11.tar.gz\": {\n        \"sha256\": \"fdfd5c640fdfb39bc7e38bf5b1f39ed2ec4a4c8064ea5fc9625679d01b3e29dc\",\n        \"size\": 222093689\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21515_Weather12.tar.gz\": {\n        \"sha256\": \"da406bb3c21be6c1f2ed5b8caadba0b1e7f7e6b8895d6b0a9d0754b8d5d07d3c\",\n        \"size\": 223381416\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21516_Weather13.tar.gz\": {\n        \"sha256\": \"9f09b0624116f600bee96a84a5f6a70d6e6fe4ed54f93371ea9bc2cc2dc17cad\",\n        \"size\": 277071233\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21517_Weather14.tar.gz\": {\n        \"sha256\": \"72fe054bb833aee0eb733ae4b3beb1ec687b55df8dfbee4fed528bbcb302c331\",\n        \"size\": 269247882\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21518_Weather15.tar.gz\": {\n        \"sha256\": \"e141e8eeed1cf5fc3216fcbf2b1d4c6b678cf28623579ed2198543aaa9efac21\",\n        \"size\": 254963425\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21519_Weather8.tar.gz\": {\n        \"sha256\": \"73c2fbf4e0a270bdaed6415a5c8c18d29d9a4a478c51683bd3f3d22f30581f6f\",\n        \"size\": 276595465\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21520_Weather9.tar.gz\": {\n        \"sha256\": \"72b5cebd9122e626dec35c821900be20b9206e8140fedc14efed84151a217258\",\n        \"size\": 212287819\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21521_Weather18.tar.gz\": {\n        \"sha256\": \"9a5267355e207b6ea893b9789de8e866580f4fd4e452a164f3f31e7f618ce70a\",\n        \"size\": 291614783\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21522_Weather19.tar.gz\": {\n        \"sha256\": \"19872cc6416f4618d74b5e17a3725219062489f92b4960b51df330a2c9904ff4\",\n        \"size\": 283168784\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21523_Weather20.tar.gz\": {\n        \"sha256\": \"43ba3312c41eeb6c452a6e87934797c05fa553dbdebb07e10cab35135fb39563\",\n        \"size\": 268302779\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21524_Weather21.tar.gz\": {\n        \"sha256\": \"51d219603445c50bf715e06bed916f083f61e7f81c6a2a8660fe13b9be4e1aa1\",\n        \"size\": 231813480\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21527_Weather23.tar.gz\": {\n        \"sha256\": \"e91f549eff88645088049ac988499a4393cb3e3850562bba10de74ca5fbeb418\",\n        \"size\": 246989412\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21528_Weather25.tar.gz\": {\n        \"sha256\": \"817be31bbfda9a0845ccf608d657b4e0e2f9821c22a81627e70d5f72faec0b60\",\n        \"size\": 242859623\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21529_Weather0.tar.gz\": {\n        \"sha256\": \"22ec15f2da4e49c4dd76e75f3c10fef51493f96bfddd0bd8397e5c047fbc82cd\",\n        \"size\": 332645888\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21530_Weather1.tar.gz\": {\n        \"sha256\": \"f9d22d4d8fcd6297d537b9b6d46165faf241e7ddfcb2bc120c3e03e5cc3ea7a9\",\n        \"size\": 306023604\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21531_Weather2.tar.gz\": {\n        \"sha256\": \"eaa63ac57759a0cb0885e64f6c753d5db007ac4a46fab1ad8f1d42093ba82492\",\n        \"size\": 307667753\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21532_Weather3.tar.gz\": {\n        \"sha256\": \"dacd2a895a6d747f4e9cc1a6419062a89a88076746ad14d268eea49cf862401a\",\n        \"size\": 282150851\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21533_Weather3.tar.gz\": {\n        \"sha256\": \"13daa930c48889bd2cdfd3912ef144328f9a4d75cdcbd157e81ee7607d275094\",\n        \"size\": 289880043\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21534_Weather5.tar.gz\": {\n        \"sha256\": \"43f3fceeb4e8533db87551737bbe4288df2d050a98f366e54bbd05a6c7be536a\",\n        \"size\": 302086365\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21535_Weather6.tar.gz\": {\n        \"sha256\": \"a3daec6f8466cf30f81ed40434f9ba2f1a6b0405e8fd81ca88c1d0c974af5fa1\",\n        \"size\": 267392219\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21536_Weather7.tar.gz\": {\n        \"sha256\": \"ee83a052f925609c5e32704196652021c93a41b2368a3c66711fab845496cf27\",\n        \"size\": 355112501\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21537_Weather8.tar.gz\": {\n        \"sha256\": \"dc550248b32e33a622f53eec097ff5a7fe03da864f7fbe0c55df3431225268bb\",\n        \"size\": 273943237\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21538_Weather9.tar.gz\": {\n        \"sha256\": \"706d62bfa5f170ccd1567724ecc412edf44892513c1e3db9447b92f90b7594b8\",\n        \"size\": 234119218\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21539_Weather10.tar.gz\": {\n        \"sha256\": \"4280347f3145c8066a3f200bca3c96ee9f6eb82d70dfcf10912e39a30e0dafa2\",\n        \"size\": 280074086\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21540_Weather11.tar.gz\": {\n        \"sha256\": \"1124b4962c2b0f0c29bbc048d788f27bed072f517d78ccbd750bb6785266d73e\",\n        \"size\": 245411436\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21541_Weather12.tar.gz\": {\n        \"sha256\": \"a8d3e1863feb514dc12edbdbec3d1e5ee803ba44a564b26eb6ee93e9c5dad37f\",\n        \"size\": 232901915\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21542_Weather13.tar.gz\": {\n        \"sha256\": \"aa31d217535ff54ff901be0d00546d25d6bd46e91c1ad088a2ce4b8a6b16c7b6\",\n        \"size\": 219308621\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21543_Weather14.tar.gz\": {\n        \"sha256\": \"c874a6711af9498bafbb038889399d4b110b636647300f27bfbf6f1fa7c2a2fc\",\n        \"size\": 263617240\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21545_Weather8.tar.gz\": {\n        \"sha256\": \"1c125194fe204a85e7ba5e5d52aaa959947f57ab3877542c493b41da5301cd32\",\n        \"size\": 341152736\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21546_Weather9.tar.gz\": {\n        \"sha256\": \"851a0bdd5291815048b66942a3b8968a75fafa242a60cfdeb872beecc2d3d966\",\n        \"size\": 237692955\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21547_Weather18.tar.gz\": {\n        \"sha256\": \"560f1fcc999c6c119c190b7b4b7d6c4044d62e3f202b6b31e68f6298ae9e00bb\",\n        \"size\": 297021346\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21548_Weather19.tar.gz\": {\n        \"sha256\": \"7081458e1a9ff7ba4ee299a1caac37dd49c65906512702544219ce63b254356f\",\n        \"size\": 293821479\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21549_Weather20.tar.gz\": {\n        \"sha256\": \"d425700c1e5a295fdf64e793f9b18a007399be011a498cfb4891f12d841f94e7\",\n        \"size\": 272739331\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21550_Weather21.tar.gz\": {\n        \"sha256\": \"0a43798229a31be11524271fa712a19955982511afd8815ca26d95222c42300d\",\n        \"size\": 296354915\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21551_Weather22.tar.gz\": {\n        \"sha256\": \"5661e0947ec3a58262fce93550e1b6413937ecda00831a36c362dd9a0360a449\",\n        \"size\": 257573996\n    },\n    \"ParkedObstacleTwoWays_Town12_Route21552_Weather23.tar.gz\": {\n        \"sha256\": \"58168f0ba4d90c4118f16dbf9b4635f7a4027021bb7503dd1ec9ca7d26c27d3c\",\n        \"size\": 261068490\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2664_Weather6.tar.gz\": {\n        \"sha256\": \"5537270d4768a72e63abb7838ae5b76de0a9f839773f6f6c8eb2c8b58ab996d1\",\n        \"size\": 273728169\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2666_Weather8.tar.gz\": {\n        \"sha256\": \"0b90c6528cd7dea52982cd47c9b1a3e4821d8f4c6b2f8adea4867fb72d67f9e4\",\n        \"size\": 322624426\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2668_Weather10.tar.gz\": {\n        \"sha256\": \"18346fa347d6dc59cea9eb7456bd1a3cc6741cc04a5f312697bf1b742bc3602e\",\n        \"size\": 1062041137\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2671_Weather13.tar.gz\": {\n        \"sha256\": \"5eafd475137b4634e3e75e208694f6a27f63a59b3a687b3ebbc149f30f0c067a\",\n        \"size\": 472157091\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2672_Weather14.tar.gz\": {\n        \"sha256\": \"81da6bb45453265231bc55dd9405a04bc73a1f8593a986f680b5ec6d8a9067ff\",\n        \"size\": 249734200\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2673_Weather15.tar.gz\": {\n        \"sha256\": \"594a6128048c454e73511d21acab18f54a9a1aa69ce6753faf6a70532db00320\",\n        \"size\": 353338378\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2677_Weather19.tar.gz\": {\n        \"sha256\": \"2ebd21f14b97c29a1b73be7882bf77852ba3eb4838cde35915a2a2c8b9c24774\",\n        \"size\": 278778176\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2678_Weather20.tar.gz\": {\n        \"sha256\": \"977041f7eb0313d2ec0eeecee7e02f0b0de14706f00b55ccee86d1c60861e549\",\n        \"size\": 285181785\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2679_Weather21.tar.gz\": {\n        \"sha256\": \"ea14883da794d0400e0595fdcd6847b7e8241f2ec8b97883a09546560cf1cf78\",\n        \"size\": 434695207\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2680_Weather22.tar.gz\": {\n        \"sha256\": \"28834523a1170a720662d1707a9d73eae67ac761ea850ce122c5f5ea71d48551\",\n        \"size\": 293220606\n    },\n    \"ParkedObstacleTwoWays_Town12_Route2683_Weather25.tar.gz\": {\n        \"sha256\": \"32b46ab2a7274e9e5b4aa1f47a1a73577b9bd9ccae3c6b533b6fc71a4aaeed1f\",\n        \"size\": 226978631\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3443_Weather6.tar.gz\": {\n        \"sha256\": \"bc7addfb127877e222ab287a8383fc93bb92b63cc7941352df73e97633d5dbdf\",\n        \"size\": 308544531\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3444_Weather7.tar.gz\": {\n        \"sha256\": \"3b15536dbbaead410faf5d363234bd6b7566ac1c2b5d00a7d9c71afcc62812a8\",\n        \"size\": 703362168\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3445_Weather8.tar.gz\": {\n        \"sha256\": \"5848dfd64fea7c5d5895d86d34a9d85f44f03a2f709ae5ee306f1a69d1dad411\",\n        \"size\": 346586317\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3446_Weather9.tar.gz\": {\n        \"sha256\": \"73642af1da0a28fb2a97f185ca4f17af6e2dc45bdfc1ea5e59d33b1825ff3025\",\n        \"size\": 282041639\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3449_Weather12.tar.gz\": {\n        \"sha256\": \"a16a3bb2c88e4777437dc5f86087186c6f5ec291851a82fc7fdbaabf19f30e44\",\n        \"size\": 278037738\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3450_Weather13.tar.gz\": {\n        \"sha256\": \"516f070336cef2034860ab1b258f0c6a4c2baff1e023c4ce6f8093b324b3e5d6\",\n        \"size\": 153230033\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3451_Weather14.tar.gz\": {\n        \"sha256\": \"a30ef4c40429bbbd270fed768c284bc076e644c4d0b9e474ff8c4baf25a49fab\",\n        \"size\": 304582201\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3452_Weather15.tar.gz\": {\n        \"sha256\": \"3a4974ad0d2bbc50938593b199787ecafb1e99ef1900e2c77cc4b17bc410483f\",\n        \"size\": 374648081\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3453_Weather8.tar.gz\": {\n        \"sha256\": \"53cbed9cd3aa15a4dcfe75307606dd425a7b8b5b8671f68d00fd4b87b018df31\",\n        \"size\": 370957148\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3454_Weather9.tar.gz\": {\n        \"sha256\": \"7b5671b245117a4e0d2158165967c20ae1e51f60c9b84e3291b620adc5386698\",\n        \"size\": 244556646\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3455_Weather18.tar.gz\": {\n        \"sha256\": \"edbde7522820579acddc24c3b527ddd5e0a562651787f6a7cea8a9b00bc17d4c\",\n        \"size\": 362215421\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3456_Weather19.tar.gz\": {\n        \"sha256\": \"25280f7e4f551457d8f5a788938daff1a5c545db14e721253a787181858ac78a\",\n        \"size\": 671835531\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3457_Weather20.tar.gz\": {\n        \"sha256\": \"82e4a4c60f9b9b27ed5ff68c90ee2f3a399b04bff25b6007ba4f1b7a59c541ca\",\n        \"size\": 371506754\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3459_Weather22.tar.gz\": {\n        \"sha256\": \"c69acafcc6ddfe35640a339ea9fde37cf207553580f47ad790ffe3fda0265879\",\n        \"size\": 307083051\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3460_Weather23.tar.gz\": {\n        \"sha256\": \"a5a16a91cfa6e15a8821b232faadc5224fe93e19a951baacf6c6cca5ac9ae5c6\",\n        \"size\": 278720229\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3461_Weather23.tar.gz\": {\n        \"sha256\": \"d7a013329c606bee39e26740fe56943267c4f5671b593d0814a540b8a46f3e4c\",\n        \"size\": 554440779\n    },\n    \"ParkedObstacleTwoWays_Town13_Route3462_Weather25.tar.gz\": {\n        \"sha256\": \"15ee084112b3b1b2a26e050b6b8d664744e37979b06df8e4b1260c2464eeebd1\",\n        \"size\": 241607234\n    },\n    \"ParkedObstacle_Town04_Route25993_Weather2.tar.gz\": {\n        \"sha256\": \"42710376d9037701a3396bc4de6717b06e4e99c3298dffef6ceeec7167efad55\",\n        \"size\": 307596488\n    },\n    \"ParkedObstacle_Town05_Route25297_Weather22.tar.gz\": {\n        \"sha256\": \"319e88db2a9e3e485c5e751490e156311f3aa346ea65e566f0968767390b1198\",\n        \"size\": 168933852\n    },\n    \"ParkedObstacle_Town05_Route25304_Weather3.tar.gz\": {\n        \"sha256\": \"9fd068f234059c83c0308993a11a75f2d79726f50551cb630e2d0dbc234c02fb\",\n        \"size\": 308764952\n    },\n    \"ParkedObstacle_Town05_Route25311_Weather11.tar.gz\": {\n        \"sha256\": \"678c4a5a4d118ecf5d8c848e9d3bedebfab5c832a25184bbc2d3a5f27046528b\",\n        \"size\": 502823102\n    },\n    \"ParkedObstacle_Town05_Route25318_Weather20.tar.gz\": {\n        \"sha256\": \"9af4ae6e1b6f2dd24c7619de754f79d04beac079d437131941c757191d62bded\",\n        \"size\": 301653441\n    },\n    \"ParkedObstacle_Town05_Route25346_Weather26.tar.gz\": {\n        \"sha256\": \"d0cad834dfface2dfee2efeb92fb7c64a56a9947721dc3413b702dfed2b959ee\",\n        \"size\": 361700770\n    },\n    \"ParkedObstacle_Town05_Route25353_Weather7.tar.gz\": {\n        \"sha256\": \"af17ae69dcaabcb0fb422bc8c40588027bce0967043f8cddaa1c5dd23d50e25c\",\n        \"size\": 287447016\n    },\n    \"ParkedObstacle_Town05_Route25360_Weather14.tar.gz\": {\n        \"sha256\": \"232cb3f83a708a65293497234f4b1c0a94b776a48163cb956ac04aa6f6b22586\",\n        \"size\": 297922599\n    },\n    \"ParkedObstacle_Town05_Route25367_Weather23.tar.gz\": {\n        \"sha256\": \"1c37c1669a6e261d5b06555c0f5ca18b4a29c5a983716060a7a6b8ca8e2d3c8c\",\n        \"size\": 213754505\n    },\n    \"ParkedObstacle_Town05_Route25374_Weather5.tar.gz\": {\n        \"sha256\": \"bc6b5bc26ea99b68d0196b3e2cec4a5a567a9756130cd4da070aa46963f52cf7\",\n        \"size\": 220177178\n    },\n    \"ParkedObstacle_Town06_Route24747_Weather25.tar.gz\": {\n        \"sha256\": \"f79b4dfdf4ff0a29cebae85c14f609b5038cd8792ba43635449cc1c2a8429a4b\",\n        \"size\": 217828845\n    },\n    \"ParkedObstacle_Town06_Route24757_Weather9.tar.gz\": {\n        \"sha256\": \"df03a2da002747acfb8a9430b88a9c302661ece3cc4be05f3880a7b67a638f0b\",\n        \"size\": 207968117\n    },\n    \"ParkedObstacle_Town06_Route24767_Weather21.tar.gz\": {\n        \"sha256\": \"cc24924ebe9f1bae44683fd8319d1b8bac4cbbbc01d79beb19b3b6db83a52d14\",\n        \"size\": 196887359\n    },\n    \"ParkedObstacle_Town06_Route24777_Weather6.tar.gz\": {\n        \"sha256\": \"039cac265c118231327cdd441a3f80c7e970caf1032f8e60658101e0306c218d\",\n        \"size\": 264175635\n    },\n    \"ParkedObstacle_Town06_Route24787_Weather18.tar.gz\": {\n        \"sha256\": \"c59cd9ded97b8cc2d7d6410254af4d4460d4071f96725b982a648e2c27566d14\",\n        \"size\": 279568342\n    },\n    \"ParkedObstacle_Town06_Route24797_Weather2.tar.gz\": {\n        \"sha256\": \"bbcfba40f2bf30be726ac4f1b3f2a716c2d5bdc92ab7f1cd89d2b98540ac40fb\",\n        \"size\": 276331818\n    },\n    \"ParkedObstacle_Town06_Route24817_Weather26.tar.gz\": {\n        \"sha256\": \"06990ae121468c71cad94dfbc49cf0eac9b2a9471437d859274e58a91f29e236\",\n        \"size\": 302798644\n    },\n    \"ParkedObstacle_Town10HD_Route24250_Weather8.tar.gz\": {\n        \"sha256\": \"1d51e27f5037dce1b9e25dca96ac2c0561c7b1b3f0ca821236adbac25311c41e\",\n        \"size\": 258567024\n    },\n    \"ParkedObstacle_Town12_Route1766_Weather18.tar.gz\": {\n        \"sha256\": \"a49af96e31bb42af5506a967009954c38dd09f2f6f317728e54ce6f16142e92e\",\n        \"size\": 192864163\n    },\n    \"ParkedObstacle_Town12_Route1767_Weather19.tar.gz\": {\n        \"sha256\": \"9ae84a54fdcb2608099b8253a71a1052bc69ac439fe90e64fee9f28e1d9f2a8d\",\n        \"size\": 485809900\n    },\n    \"ParkedObstacle_Town12_Route1768_Weather20.tar.gz\": {\n        \"sha256\": \"2c0475d205d3163392a9f76528dfa3ee198a69957ff0c3c0c8e8612039bed86f\",\n        \"size\": 338029404\n    },\n    \"ParkedObstacle_Town12_Route1769_Weather21.tar.gz\": {\n        \"sha256\": \"c5e68af6bfdf959ef985bebb3e4d4fe76a11e40f1fcd8d11c938ac756f2b68ef\",\n        \"size\": 569167684\n    },\n    \"ParkedObstacle_Town12_Route1770_Weather22.tar.gz\": {\n        \"sha256\": \"d76eca63f81545497d64717c911c43aae64aa1f4141704c57e0315f45e815347\",\n        \"size\": 417684983\n    },\n    \"ParkedObstacle_Town12_Route1773_Weather25.tar.gz\": {\n        \"sha256\": \"ba79379e1cd13d75689a0957b893f27c464428e6875b39cec2ced4e85aab8063\",\n        \"size\": 408956670\n    },\n    \"ParkedObstacle_Town12_Route1774_Weather0.tar.gz\": {\n        \"sha256\": \"23e0a344c5a3bdaf8810edd7e72ba1c136cf5370ce281752532315a54506bc91\",\n        \"size\": 491567946\n    },\n    \"ParkedObstacle_Town12_Route1775_Weather1.tar.gz\": {\n        \"sha256\": \"cc609efd93708f949bbca0fdcb160662b39accbe6ee0ede0f5ce9f6603bfd3a2\",\n        \"size\": 415202528\n    },\n    \"ParkedObstacle_Town12_Route1776_Weather2.tar.gz\": {\n        \"sha256\": \"1d8772d65f809d4c43b3865a8e2e475a4bc90f369d06bf77cd1375ad2eed16cd\",\n        \"size\": 374388164\n    },\n    \"ParkedObstacle_Town12_Route1777_Weather3.tar.gz\": {\n        \"sha256\": \"7cc631f9c2a75843dff273a521b899e1f4cc78f38876e5c988ee7b00ea1bd254\",\n        \"size\": 929818338\n    },\n    \"ParkedObstacle_Town12_Route1778_Weather3.tar.gz\": {\n        \"sha256\": \"02da6be5b0f66f8dca9f5bc88106f32bc775b5460d80a85615b778b4ba0e3f7f\",\n        \"size\": 339662914\n    },\n    \"ParkedObstacle_Town12_Route1779_Weather5.tar.gz\": {\n        \"sha256\": \"2375cfef4fedc73246b7d2d8c2814d5390cfe891a44cb536ee017cf58cc9f7c0\",\n        \"size\": 260141355\n    },\n    \"ParkedObstacle_Town12_Route19373_Weather2.tar.gz\": {\n        \"sha256\": \"02ae92c8740260fae5f1fe24b3bc4c85736dd529516721449553e609ab953d25\",\n        \"size\": 164269760\n    },\n    \"ParkedObstacle_Town12_Route19374_Weather3.tar.gz\": {\n        \"sha256\": \"1a00e09481f07a2e05b34e959eb6518dc2c8fee023b6b583c7713fcc2e9d5e7d\",\n        \"size\": 553888202\n    },\n    \"ParkedObstacle_Town12_Route19376_Weather5.tar.gz\": {\n        \"sha256\": \"f08f9fafdbb789e1a6770cd62567b51aaff8f3d4aa0df417418567a3c8e67028\",\n        \"size\": 407567375\n    },\n    \"ParkedObstacle_Town12_Route19378_Weather7.tar.gz\": {\n        \"sha256\": \"eceab786401b16f90786802ffba14d23b3dcba3883e046801c9304165df71098\",\n        \"size\": 534672262\n    },\n    \"ParkedObstacle_Town12_Route19379_Weather8.tar.gz\": {\n        \"sha256\": \"10d1a6b5863b2a15ea93b9dc967b730a0283c60c7f92fbedae0b09746b71e18d\",\n        \"size\": 515170060\n    },\n    \"ParkedObstacle_Town12_Route19380_Weather9.tar.gz\": {\n        \"sha256\": \"7e9a67a7fd923e6048c780b1a4ddc8799b98d9c7f095f0a68c29300c46ade858\",\n        \"size\": 553964992\n    },\n    \"ParkedObstacle_Town12_Route19381_Weather10.tar.gz\": {\n        \"sha256\": \"fd0b962fe1589a6cd721749bb233cf2220e312346aab0babe63f8b0e3455b506\",\n        \"size\": 463774246\n    },\n    \"ParkedObstacle_Town12_Route19382_Weather11.tar.gz\": {\n        \"sha256\": \"f31e9916f2f30200690285bd63132d45d273b1f150698d3df8934ffc265b1b33\",\n        \"size\": 243861732\n    },\n    \"ParkedObstacle_Town12_Route19383_Weather12.tar.gz\": {\n        \"sha256\": \"932077de0abbd82f4653fd8cbf0b0c1b5facaff7c1e9d52a866bca4db623dde8\",\n        \"size\": 258249953\n    },\n    \"ParkedObstacle_Town12_Route19384_Weather13.tar.gz\": {\n        \"sha256\": \"cc20d5e8385e2df96c2a9fbb42ac4da90d432aa85b2909a7882929fa115cf28f\",\n        \"size\": 255567871\n    },\n    \"ParkedObstacle_Town12_Route19385_Weather14.tar.gz\": {\n        \"sha256\": \"64c2ab3347d8b6fc9c2ba1d97997b5ca364e23c6856dabf5f05c0a990209d089\",\n        \"size\": 280536993\n    },\n    \"ParkedObstacle_Town12_Route19387_Weather8.tar.gz\": {\n        \"sha256\": \"141938a8e66f2248c4fa01fc1034fd1193f6318ce9f963c2a0c4cd510d71e7cc\",\n        \"size\": 273033471\n    },\n    \"ParkedObstacle_Town12_Route19388_Weather9.tar.gz\": {\n        \"sha256\": \"5dc3f85f9bc07867d4e855fe8d4091c3b1ed9413da9b536941b042a6ed3091ca\",\n        \"size\": 268522159\n    },\n    \"ParkedObstacle_Town12_Route19389_Weather18.tar.gz\": {\n        \"sha256\": \"70c43c160da4e0132646a7434363daed90ff0d14ba5587b94140488651292b2f\",\n        \"size\": 385953202\n    },\n    \"ParkedObstacle_Town12_Route19390_Weather19.tar.gz\": {\n        \"sha256\": \"59f7328d47a3becb3f0f4b2e679ae2855021e6e07ec13e31c15d49b30b602447\",\n        \"size\": 385913691\n    },\n    \"ParkedObstacle_Town12_Route19394_Weather23.tar.gz\": {\n        \"sha256\": \"307db1840b9edf07aeb690b2021f11fd73b7fc4e36377c2137ece83c327727a7\",\n        \"size\": 293530695\n    },\n    \"ParkedObstacle_Town12_Route19395_Weather23.tar.gz\": {\n        \"sha256\": \"2d9d4c3a9bfe37a60d8335a45ebb4bad9cca5e87d6e81fe99e88376949aeb072\",\n        \"size\": 263712122\n    },\n    \"ParkedObstacle_Town12_Route19396_Weather25.tar.gz\": {\n        \"sha256\": \"f5c8544b7640bc34d6821be20be390fcd2f075d488b6262d1447ad73267b7406\",\n        \"size\": 282262299\n    },\n    \"ParkedObstacle_Town12_Route19401_Weather3.tar.gz\": {\n        \"sha256\": \"748a4e85c0859ea948ee7e8ecf87beeaeb4b2eb245853caf65426fa73602ab20\",\n        \"size\": 183509195\n    },\n    \"ParkedObstacle_Town12_Route19404_Weather7.tar.gz\": {\n        \"sha256\": \"ac4a83eee34dcd4aef0a78758f3a016e950f893e11889c2936bc82c10d034d73\",\n        \"size\": 450262033\n    },\n    \"ParkedObstacle_Town12_Route19405_Weather8.tar.gz\": {\n        \"sha256\": \"0446289ce72b85a768e636fbe829c8b614edcd2e0ea4d1bb0799e56f53faf947\",\n        \"size\": 332594866\n    },\n    \"ParkedObstacle_Town12_Route19408_Weather11.tar.gz\": {\n        \"sha256\": \"6faf0f8502587ed08c23a20bd0916ac654eb988d6be74da16e903eddf22c78cc\",\n        \"size\": 143895532\n    },\n    \"ParkedObstacle_Town12_Route19409_Weather12.tar.gz\": {\n        \"sha256\": \"8a31668519d22f2e374e4c6e18e3fa74d9d609f3068822f4510f4f63f0c4cb6b\",\n        \"size\": 415687648\n    },\n    \"ParkedObstacle_Town12_Route19410_Weather13.tar.gz\": {\n        \"sha256\": \"d5ee5dab5f4fc32cfa055b02d783203b8b4b5976a1a23f6152832b485a457d0c\",\n        \"size\": 389473578\n    },\n    \"ParkedObstacle_Town12_Route19413_Weather8.tar.gz\": {\n        \"sha256\": \"afa3ed94b229467785c1c9821b80530d5789b5bd9ae43f49b02b6f60576aa08b\",\n        \"size\": 382592180\n    },\n    \"ParkedObstacle_Town12_Route19415_Weather18.tar.gz\": {\n        \"sha256\": \"ec85d5bc7bad333cc2dd8d1325dd7becadf03bc6997781dbe47cdc4994b859b5\",\n        \"size\": 181054915\n    },\n    \"ParkedObstacle_Town12_Route19418_Weather21.tar.gz\": {\n        \"sha256\": \"b3c2377ac79ffd3a00cf6a14ec43928d67b8793a4ceed26862dcc47bb20e2244\",\n        \"size\": 413982835\n    },\n    \"ParkedObstacle_Town12_Route19419_Weather22.tar.gz\": {\n        \"sha256\": \"85403fbb85217064f0f2219dcb8571df4f258c38026c26d9065de22a2dad9082\",\n        \"size\": 378297307\n    },\n    \"ParkedObstacle_Town12_Route19420_Weather23.tar.gz\": {\n        \"sha256\": \"a87b08e17722631ae1548709acb3c01fb918616639a674b120ec9adf5f585e46\",\n        \"size\": 385077146\n    },\n    \"ParkedObstacle_Town12_Route19422_Weather25.tar.gz\": {\n        \"sha256\": \"343e34ec580d3beba9f381993a5dbdf0d6455c51afc27e2d5824b29d6cba7834\",\n        \"size\": 352900455\n    },\n    \"ParkedObstacle_Town12_Route19423_Weather0.tar.gz\": {\n        \"sha256\": \"b74477e9303631889078a47e57b77f875cc0628e05d054ce25b5f493af5d1ad3\",\n        \"size\": 417851716\n    },\n    \"ParkedObstacle_Town12_Route19424_Weather1.tar.gz\": {\n        \"sha256\": \"fbee4ebc97d4fc8488df587175f23911b7d07494b561f54df8081119511994c3\",\n        \"size\": 397019627\n    },\n    \"ParkedObstacle_Town12_Route19425_Weather2.tar.gz\": {\n        \"sha256\": \"629bf539220f68c11aa25a38caa8b45ea6737fdc2c0884601d077bc556650590\",\n        \"size\": 403408528\n    },\n    \"ParkedObstacle_Town12_Route19426_Weather3.tar.gz\": {\n        \"sha256\": \"e33b426ea7487107edb26b8f391253c6f73bd5cd9bf745023a8948e69ea45de6\",\n        \"size\": 359886064\n    },\n    \"ParkedObstacle_Town12_Route19427_Weather3.tar.gz\": {\n        \"sha256\": \"84e31db99b223e50b2559c809aaec70e8716fbd16c83f83a6113d3c8571e5247\",\n        \"size\": 423344449\n    },\n    \"ParkedObstacle_Town12_Route19428_Weather5.tar.gz\": {\n        \"sha256\": \"7692d2fc519ff96f28034b0abdfba24122708f3442c820cda372e7f77b902319\",\n        \"size\": 457320512\n    },\n    \"ParkedObstacle_Town12_Route19430_Weather7.tar.gz\": {\n        \"sha256\": \"ee76a49f50d2b74aab0d6b88cf02dbd55465108250088fc8bd30cdeef474ab6a\",\n        \"size\": 216015388\n    },\n    \"ParkedObstacle_Town12_Route19433_Weather10.tar.gz\": {\n        \"sha256\": \"1925aa435df0b05d914700967e5fc98b61697423b8e962c5960d28c9d955cd91\",\n        \"size\": 382940658\n    },\n    \"ParkedObstacle_Town12_Route19435_Weather12.tar.gz\": {\n        \"sha256\": \"a409e3ea2c952b0afe1542450b71c6abddc674821adde76c6d42ce7304671c06\",\n        \"size\": 113629322\n    },\n    \"ParkedObstacle_Town12_Route19437_Weather14.tar.gz\": {\n        \"sha256\": \"8aa8b9681e036d593386ab874433542b02354515719a742d78d2e74cfb3a0675\",\n        \"size\": 340168332\n    },\n    \"ParkedObstacle_Town12_Route19440_Weather9.tar.gz\": {\n        \"sha256\": \"f802d3c392f4f33cd85e90a41118e6d42e9c94d79148a966f5e400215db89b10\",\n        \"size\": 208602129\n    },\n    \"ParkedObstacle_Town12_Route19443_Weather20.tar.gz\": {\n        \"sha256\": \"cde12f50abab2d79f5cca769fcb2de33418fba49cda400bd0cee89892e042e6e\",\n        \"size\": 342616374\n    },\n    \"ParkedObstacle_Town12_Route19444_Weather21.tar.gz\": {\n        \"sha256\": \"1b7f254d6b8b86fe03835cc3de341af2c6bba858f9723571ef39f55b7c43b030\",\n        \"size\": 279743921\n    },\n    \"ParkedObstacle_Town12_Route19445_Weather22.tar.gz\": {\n        \"sha256\": \"315a7d5f7254124a509a165606c5deebf363119251a76579822ba19be239ef63\",\n        \"size\": 345765151\n    },\n    \"ParkedObstacle_Town12_Route19446_Weather23.tar.gz\": {\n        \"sha256\": \"281489e94848ec61a5b7a8285a8562999242bb440782a93ea7a1e97f5d93ec74\",\n        \"size\": 306845613\n    },\n    \"ParkedObstacle_Town12_Route19447_Weather23.tar.gz\": {\n        \"sha256\": \"cb13311f417f73238b7ea963e1169324b5b4caab6a6a48661a9fc060e1dd52d2\",\n        \"size\": 307505000\n    },\n    \"ParkedObstacle_Town12_Route19448_Weather25.tar.gz\": {\n        \"sha256\": \"3376deca70c18e9611c7806396dfe2328527a1915683d29b44e085d233d291ee\",\n        \"size\": 314485436\n    },\n    \"ParkedObstacle_Town12_Route19449_Weather0.tar.gz\": {\n        \"sha256\": \"addf41269ca661a7420386acbaa50aa497cb79c39027c6c8e924a5cbc994af60\",\n        \"size\": 267904201\n    },\n    \"ParkedObstacle_Town12_Route19450_Weather1.tar.gz\": {\n        \"sha256\": \"5608fab5760cb80c0ee06509100a6f8b74425091e4bea7331b4b1755834a6900\",\n        \"size\": 408452099\n    },\n    \"ParkedObstacle_Town12_Route19451_Weather2.tar.gz\": {\n        \"sha256\": \"d3ef8ecf07f61a00c592b5a02eecd7424f380cd3b12d82ec94925ba02932fa87\",\n        \"size\": 271892199\n    },\n    \"ParkedObstacle_Town12_Route19452_Weather3.tar.gz\": {\n        \"sha256\": \"0f9121338edd98969db344e5d35aafba18f81758658123fe6b2423007587fc41\",\n        \"size\": 319453717\n    },\n    \"ParkedObstacle_Town12_Route19456_Weather7.tar.gz\": {\n        \"sha256\": \"58b3527e8ac54b2f253778e21a2dd14dc0b306af1db6f20137b8899f7bfd1a15\",\n        \"size\": 158393504\n    },\n    \"ParkedObstacle_Town12_Route19457_Weather8.tar.gz\": {\n        \"sha256\": \"957cf811fc66deecf40bc7ffc8329f36c55e38377d99c74b34922c149a2cb644\",\n        \"size\": 426629022\n    },\n    \"ParkedObstacle_Town12_Route19458_Weather9.tar.gz\": {\n        \"sha256\": \"771f7a613453a6a88f3cb610bb6854697c08495b179e8474651d008ee9ab249e\",\n        \"size\": 408657362\n    },\n    \"ParkedObstacle_Town12_Route19459_Weather10.tar.gz\": {\n        \"sha256\": \"87a7dc541524a119c36f4525c92edb3003292f0baec1ad0054879dab641a9e3b\",\n        \"size\": 174277807\n    },\n    \"ParkedObstacle_Town12_Route19461_Weather12.tar.gz\": {\n        \"sha256\": \"d4f34181d9f293442092eb483e9a2f2db824df657a6772faaa31e6e378f4b071\",\n        \"size\": 398297186\n    },\n    \"ParkedObstacle_Town12_Route19467_Weather18.tar.gz\": {\n        \"sha256\": \"d8cc4c93a3b1e5559e037762f3d7b115fbfc4386cc47021cab36d9e5310a161c\",\n        \"size\": 165707621\n    },\n    \"ParkedObstacle_Town12_Route19469_Weather20.tar.gz\": {\n        \"sha256\": \"676ab372a89b5f70c99444a09ffaad432ec77650073eed9b73c0c4a6fa9e805b\",\n        \"size\": 139481858\n    },\n    \"ParkedObstacle_Town12_Route19473_Weather23.tar.gz\": {\n        \"sha256\": \"c3aca8ed5003e6fabc54fb93f096d7c1f77ff1be2be31f7badfeaab6b6dc1121\",\n        \"size\": 153198584\n    },\n    \"ParkedObstacle_Town12_Route19474_Weather25.tar.gz\": {\n        \"sha256\": \"672ec8a8c6ca09a4ad7c051f12a121fbfc8c7afd228f896d8c6f0d0cf50ce9c1\",\n        \"size\": 152995632\n    },\n    \"ParkedObstacle_Town12_Route19477_Weather2.tar.gz\": {\n        \"sha256\": \"0aa8ccad7e3635478e8eaff1098e46957cc36cfa35bd07ffe7326d5e9cdcfac0\",\n        \"size\": 188976097\n    },\n    \"ParkedObstacle_Town12_Route19479_Weather3.tar.gz\": {\n        \"sha256\": \"6f73b37011f73826e7a9d2e442156680f4a9c3a5a7362120ad67729539bf0fa3\",\n        \"size\": 459615765\n    },\n    \"ParkedObstacle_Town12_Route19480_Weather5.tar.gz\": {\n        \"sha256\": \"8c8c1d01f3b6938f10df0f2e91ca2808c43f26763bff81db46e25701b47c1b23\",\n        \"size\": 906446945\n    },\n    \"ParkedObstacle_Town12_Route19485_Weather10.tar.gz\": {\n        \"sha256\": \"3edf22514cc724b4157735f3bc8ce4707ceffb727be7962a32c578d52af11a51\",\n        \"size\": 364198435\n    },\n    \"ParkedObstacle_Town12_Route19486_Weather11.tar.gz\": {\n        \"sha256\": \"086abb5fb66d0e2e15f48afa0a292f0565675d8a5047bd1a1bb781c51c0488b7\",\n        \"size\": 137742955\n    },\n    \"ParkedObstacle_Town12_Route19487_Weather12.tar.gz\": {\n        \"sha256\": \"0214d2b395f2a341d2c79962367a432553eec9566a7930f5044e7b7c418a3435\",\n        \"size\": 208161915\n    },\n    \"ParkedObstacle_Town12_Route19488_Weather13.tar.gz\": {\n        \"sha256\": \"a8fb79a37c02b55c36a8f189fa39fd4af986db92aa61a3d221bcb658eaa1bc88\",\n        \"size\": 208160898\n    },\n    \"ParkedObstacle_Town12_Route19492_Weather9.tar.gz\": {\n        \"sha256\": \"4015d81c25592972e89e3c40cd83b8b94598df9ded9956ac303eceac1473ad4e\",\n        \"size\": 429691753\n    },\n    \"ParkedObstacle_Town12_Route19493_Weather18.tar.gz\": {\n        \"sha256\": \"92510a49a3f911bebeb76ef4a29dc7692f97d7e8bd08fd9bb941138687194e9c\",\n        \"size\": 349027085\n    },\n    \"ParkedObstacle_Town12_Route19494_Weather19.tar.gz\": {\n        \"sha256\": \"74e36bf2648958d8942f86fba5e3251200b45653270fc6118118e955eb3f29b1\",\n        \"size\": 324047350\n    },\n    \"ParkedObstacle_Town12_Route19495_Weather20.tar.gz\": {\n        \"sha256\": \"bfdd777504b5d018cd49cea12264797c6288c45daf04dd77cb3b2f3574a0520a\",\n        \"size\": 163809563\n    },\n    \"ParkedObstacle_Town12_Route19496_Weather21.tar.gz\": {\n        \"sha256\": \"abdb9f6ea5d7040cb471e76f425682aff1f2318273f345cfcc944bc25ef50745\",\n        \"size\": 395657888\n    },\n    \"ParkedObstacle_Town12_Route19497_Weather22.tar.gz\": {\n        \"sha256\": \"7c36b9633aa181880428fe62f0dd73fe2384544127f456eab42812d223edf76b\",\n        \"size\": 155138059\n    },\n    \"ParkedObstacle_Town12_Route19501_Weather0.tar.gz\": {\n        \"sha256\": \"9c293c7c408171b81fb6d3d61249de0755025a839208cde6e9cf23d273a23792\",\n        \"size\": 250798728\n    },\n    \"ParkedObstacle_Town12_Route19502_Weather1.tar.gz\": {\n        \"sha256\": \"4b5a4dfdfdb665c6e342238a87b0aefff11e64fcc680d803dc8fe4481ae3d4d4\",\n        \"size\": 324700423\n    },\n    \"ParkedObstacle_Town12_Route19504_Weather3.tar.gz\": {\n        \"sha256\": \"3841a9947c7d178a61e730931c0139c55f5824876e2be1b9832de0e5f0befadd\",\n        \"size\": 307873267\n    },\n    \"ParkedObstacle_Town12_Route19505_Weather3.tar.gz\": {\n        \"sha256\": \"64069165610575ca659ff9eed11d97a5393512c6a0f08add97db627bcf9491f5\",\n        \"size\": 474001416\n    },\n    \"ParkedObstacle_Town12_Route19506_Weather5.tar.gz\": {\n        \"sha256\": \"c3113e0ce11806941341c1f84a30e6a5a836774608a49ff9d425513d111dc997\",\n        \"size\": 470738922\n    },\n    \"ParkedObstacle_Town12_Route19507_Weather6.tar.gz\": {\n        \"sha256\": \"ef2034152fcee2c4184e4ac7d141fd1527a9449f941f30bbc6cc07fd2449f17a\",\n        \"size\": 466130236\n    },\n    \"ParkedObstacle_Town12_Route19510_Weather9.tar.gz\": {\n        \"sha256\": \"9589ac49128a491b0af3e839e588484d6ba360da44cf2296db9700d42608f201\",\n        \"size\": 394545405\n    },\n    \"ParkedObstacle_Town12_Route19511_Weather10.tar.gz\": {\n        \"sha256\": \"20b7586d8f7f7bf4d8ee250293fbfc35327054ba335cad940d41caaf878925b3\",\n        \"size\": 413507709\n    },\n    \"ParkedObstacle_Town12_Route19512_Weather11.tar.gz\": {\n        \"sha256\": \"fe072a58427866f387f46764ce70d585f4b0cb4b38ea238033e99e9bc23146c9\",\n        \"size\": 240075457\n    },\n    \"ParkedObstacle_Town12_Route19513_Weather12.tar.gz\": {\n        \"sha256\": \"ff8e75220e9bde3d592b748023353e8b0415a5062ccd5a9ea4b6ef927f3f47f5\",\n        \"size\": 190157070\n    },\n    \"ParkedObstacle_Town12_Route19514_Weather13.tar.gz\": {\n        \"sha256\": \"facde41370e2324dc21f0b9561b5e7c11b62017776fb958ee5dac10ac6442d3d\",\n        \"size\": 271502081\n    },\n    \"ParkedObstacle_Town12_Route19518_Weather9.tar.gz\": {\n        \"sha256\": \"caf1146949dd1aae891ea8101e71032030a2062a4c930540fd495ab49c347ced\",\n        \"size\": 487214536\n    },\n    \"ParkedObstacle_Town12_Route19519_Weather18.tar.gz\": {\n        \"sha256\": \"a03513c53d3984b93ad91b67c00e90d2b95647b6565b7025de8c019bef6d4443\",\n        \"size\": 196388399\n    },\n    \"ParkedObstacle_Town12_Route19520_Weather19.tar.gz\": {\n        \"sha256\": \"472d19f5a947444a03f0277181f0757d9fbf899b278549a9b49a51f8d31d698f\",\n        \"size\": 305571828\n    },\n    \"ParkedObstacle_Town12_Route19521_Weather20.tar.gz\": {\n        \"sha256\": \"b65762dca34c763fd1008c2019e9e82c92bae1ca19d16313dd4a4f6fe8fd78e9\",\n        \"size\": 168012629\n    },\n    \"ParkedObstacle_Town12_Route19522_Weather21.tar.gz\": {\n        \"sha256\": \"96d5c4812b94de67a9ae4797c707dece872ad52897228597458783b3c38745ed\",\n        \"size\": 432734010\n    },\n    \"ParkedObstacle_Town12_Route19524_Weather23.tar.gz\": {\n        \"sha256\": \"8de43abf43b1e00a96f2c588757cbdca406fe207245fb5b3f89c19163315cdad\",\n        \"size\": 294989262\n    },\n    \"ParkedObstacle_Town12_Route19530_Weather3.tar.gz\": {\n        \"sha256\": \"9a731a1dd26f1db43673a690990844c5ace2c5bd76dcdc956100109a4eff6b18\",\n        \"size\": 342712538\n    },\n    \"ParkedObstacle_Town12_Route19531_Weather3.tar.gz\": {\n        \"sha256\": \"1e16797cfcdd6b9725caecda8b92f0a79e5cd73cf120297927972893e768e2c2\",\n        \"size\": 343289475\n    },\n    \"ParkedObstacle_Town12_Route19533_Weather6.tar.gz\": {\n        \"sha256\": \"c2c2266ede7b25bcc097ca296aae006e636b537cc6a3efbc70cd0ff557e354ed\",\n        \"size\": 326339986\n    },\n    \"ParkedObstacle_Town12_Route19534_Weather7.tar.gz\": {\n        \"sha256\": \"584e34a971e94e63e9f55916dce3cc0f07239542e47d9b6c78819375b4f15b42\",\n        \"size\": 392121715\n    },\n    \"ParkedObstacle_Town12_Route19535_Weather8.tar.gz\": {\n        \"sha256\": \"d8a9bbae1d68b4da1b5a9c28c99fd591c5595b2af5e235a483cc231d0bd9f450\",\n        \"size\": 303427486\n    },\n    \"ParkedObstacle_Town12_Route19536_Weather9.tar.gz\": {\n        \"sha256\": \"4c086e1d03f5a03be3e9a71335125b416e788913437342f9681bdb6677610bd9\",\n        \"size\": 298848658\n    },\n    \"ParkedObstacle_Town12_Route19537_Weather10.tar.gz\": {\n        \"sha256\": \"5ce4b029487c94f2282e307e937c2e98f3dafa9855e63ea94cd7704535cd512b\",\n        \"size\": 302460758\n    },\n    \"ParkedObstacle_Town12_Route19540_Weather13.tar.gz\": {\n        \"sha256\": \"c08847a92a7c9d403d77a660cdf392a9f9e8d26123153fdf6318252836c4681c\",\n        \"size\": 190556648\n    },\n    \"ParkedObstacle_Town12_Route19541_Weather14.tar.gz\": {\n        \"sha256\": \"4b8295a24ac634221a7b30321f5bb0b6a76d337ac47e42af44c0b92dcb9a0c72\",\n        \"size\": 257265549\n    },\n    \"ParkedObstacle_Town12_Route19542_Weather15.tar.gz\": {\n        \"sha256\": \"4869d1bd55d34a91200c72ed9375a4cbf8ae8d46c80c3040cbafa91dbc7ad1b3\",\n        \"size\": 165569517\n    },\n    \"ParkedObstacle_Town12_Route19543_Weather8.tar.gz\": {\n        \"sha256\": \"fcfa8f1ee90425b26b24ea9432cb1f8cc314c93b5ceb69fd1775a9967d897975\",\n        \"size\": 226798442\n    },\n    \"ParkedObstacle_Town12_Route19544_Weather9.tar.gz\": {\n        \"sha256\": \"6be3a17ef5fff5b4d89a05dbdc9cecdd7e363064c43a6495200a17780403f96b\",\n        \"size\": 372748215\n    },\n    \"ParkedObstacle_Town12_Route19545_Weather18.tar.gz\": {\n        \"sha256\": \"6ddfd53efcda95e6d80e7e541308b1d5b64a8bb1c16a6e74bf4f25488916a710\",\n        \"size\": 362190981\n    },\n    \"ParkedObstacle_Town12_Route19546_Weather19.tar.gz\": {\n        \"sha256\": \"90f8220cc260a6511eb0555eeb5c398254efd95b84db3718498fa044e7a22b30\",\n        \"size\": 361001510\n    },\n    \"ParkedObstacle_Town12_Route19549_Weather22.tar.gz\": {\n        \"sha256\": \"b0927894631ae37f1554f3320bb632d3fd92554f533c447c2667cfa34a28bef2\",\n        \"size\": 393345360\n    },\n    \"ParkedObstacle_Town12_Route19550_Weather23.tar.gz\": {\n        \"sha256\": \"4c0a4a2af0468bd70180f8d8b4637c13b2ebf14c8619fe0123ce925db1bf9e0f\",\n        \"size\": 390831773\n    },\n    \"ParkedObstacle_Town12_Route19551_Weather23.tar.gz\": {\n        \"sha256\": \"d86da5958683fac0e895c48089f435675eaa090a79a28d233c874afae909a5aa\",\n        \"size\": 364525366\n    },\n    \"ParkedObstacle_Town12_Route19552_Weather25.tar.gz\": {\n        \"sha256\": \"fb37e7f3a16334c2c32b5e68339e5eb246f727d131d78a4e01b9903a2ecd8f01\",\n        \"size\": 308440215\n    },\n    \"ParkedObstacle_Town12_Route19553_Weather0.tar.gz\": {\n        \"sha256\": \"cd7196acce9f482ed6c6ec07fda42c72155c40f4d728ee0506e0d86974178d7e\",\n        \"size\": 156182310\n    },\n    \"ParkedObstacle_Town12_Route19556_Weather3.tar.gz\": {\n        \"sha256\": \"a16af3115d541bedf7da15d8d1d3cb87161ee5d68ab57807ddd453d958131768\",\n        \"size\": 275901728\n    },\n    \"ParkedObstacle_Town12_Route19560_Weather7.tar.gz\": {\n        \"sha256\": \"8d8590db3ba6ce411bc2df9e3058dc0b752e80ca486e59b22a29722b2efcb0d7\",\n        \"size\": 452333730\n    },\n    \"ParkedObstacle_Town12_Route19561_Weather8.tar.gz\": {\n        \"sha256\": \"6fda029eb9ad34ea7ea6bfd3fa69cf9da0a92bda999c0bf6964301432aa70444\",\n        \"size\": 730696524\n    },\n    \"ParkedObstacle_Town12_Route19562_Weather9.tar.gz\": {\n        \"sha256\": \"d2524d9afdad0442b40923dd9596763f21b75adc02135871ace8d85448632fab\",\n        \"size\": 274375508\n    },\n    \"ParkedObstacle_Town12_Route19563_Weather10.tar.gz\": {\n        \"sha256\": \"742126c03b95db7eed4732251069a2887aedeb73a2e4372307c4611899d555d2\",\n        \"size\": 354886606\n    },\n    \"ParkedObstacle_Town12_Route19567_Weather14.tar.gz\": {\n        \"sha256\": \"d78b12751213d765c0685bc32dcb8df0b645a64edf0b7cc7bf26769b818f2379\",\n        \"size\": 220892274\n    },\n    \"ParkedObstacle_Town12_Route19568_Weather15.tar.gz\": {\n        \"sha256\": \"8f40a537148a63cec242b86cc53a64098fdcb7915b6b025fc191e2afe70e9bea\",\n        \"size\": 356673176\n    },\n    \"ParkedObstacle_Town12_Route19573_Weather20.tar.gz\": {\n        \"sha256\": \"d968c72f047c54714791fc20e5c1826d97d9648e4d022dd940695235eb877777\",\n        \"size\": 161856888\n    },\n    \"ParkedObstacle_Town12_Route19574_Weather21.tar.gz\": {\n        \"sha256\": \"19f64ce5a739db6fc9a919e6a31f0b7994a36edf58fe8b4680756fd85c44817d\",\n        \"size\": 285058913\n    },\n    \"ParkedObstacle_Town12_Route19578_Weather25.tar.gz\": {\n        \"sha256\": \"639ce17656666c5588fe2b80eff0ad3804cae3f5cdd88baf5fd61f3ce8daaca1\",\n        \"size\": 388962769\n    },\n    \"ParkedObstacle_Town12_Route19581_Weather2.tar.gz\": {\n        \"sha256\": \"59e35360277da766374bcd3f7dd2036fd3b033235eba9e892a628d22f9af9a73\",\n        \"size\": 536931419\n    },\n    \"ParkedObstacle_Town12_Route19582_Weather3.tar.gz\": {\n        \"sha256\": \"a023a851aa3e1e5ef26f176a0eafa24874ee905dbc8693bd2301783b54926cb6\",\n        \"size\": 472033114\n    },\n    \"ParkedObstacle_Town12_Route19583_Weather3.tar.gz\": {\n        \"sha256\": \"c3faae9a321063d6902888c638e623ddf80aac0af7f1000320b8a05cb8798077\",\n        \"size\": 427011897\n    },\n    \"ParkedObstacle_Town12_Route19584_Weather5.tar.gz\": {\n        \"sha256\": \"569829a15779d2a113ee3e3b2d2eaeca3b66d789bf99cd7251e0db2cb9ccbb38\",\n        \"size\": 168444940\n    },\n    \"ParkedObstacle_Town12_Route19586_Weather7.tar.gz\": {\n        \"sha256\": \"a790eec57923137afbc2f70ce629c9e10e2c474134966b3df12ed4b919a877be\",\n        \"size\": 176645889\n    },\n    \"ParkedObstacle_Town12_Route19587_Weather8.tar.gz\": {\n        \"sha256\": \"c848ae82957c79578d37ccd1623113a8b04a59bfb500c326ab016f9ac814e2bc\",\n        \"size\": 414796630\n    },\n    \"ParkedObstacle_Town12_Route19588_Weather9.tar.gz\": {\n        \"sha256\": \"a1c3e3e633ee3ed47e0d90bd90617da04430e6a5205e767470e6dfd059fffeb7\",\n        \"size\": 347322572\n    },\n    \"ParkedObstacle_Town12_Route19589_Weather10.tar.gz\": {\n        \"sha256\": \"c05232c37c2ec1e421f53c5cd850ec92e95a60a0050906e637f5c3a226c97577\",\n        \"size\": 287579200\n    },\n    \"ParkedObstacle_Town12_Route19590_Weather11.tar.gz\": {\n        \"sha256\": \"edbea9010f11c350f93497fc2f753428a642aca64681486ca295b28a642dd605\",\n        \"size\": 139236264\n    },\n    \"ParkedObstacle_Town12_Route19596_Weather9.tar.gz\": {\n        \"sha256\": \"886a2c684c802d6f2de48fb744990df14b9dcafa6f1046a39838a1156790abf8\",\n        \"size\": 134238041\n    },\n    \"ParkedObstacle_Town12_Route19599_Weather20.tar.gz\": {\n        \"sha256\": \"abf219153111098dcca2a90bfba1bfa96c9410864f5726a20d81f8889562e02f\",\n        \"size\": 154277690\n    },\n    \"ParkedObstacle_Town12_Route2545_Weather9.tar.gz\": {\n        \"sha256\": \"efd374021c24330509bd5d1d60a98592ef3f05a85929db43148f4541149d2b61\",\n        \"size\": 125265504\n    },\n    \"ParkedObstacle_Town12_Route2546_Weather18.tar.gz\": {\n        \"sha256\": \"1729d117c4a4efe8dd1ef856f141c6a0541fd66fcb7e51331c600c90637fc834\",\n        \"size\": 331016119\n    },\n    \"ParkedObstacle_Town12_Route2547_Weather19.tar.gz\": {\n        \"sha256\": \"492ab042ea2683cb8664560409d0825ab2761421838e8e4da67e08d0dfac8a7f\",\n        \"size\": 345514456\n    },\n    \"ParkedObstacle_Town12_Route2548_Weather20.tar.gz\": {\n        \"sha256\": \"ec08a3507f183c9f4d31338333201282ed72c64993f6ce29722e0b9941985ba3\",\n        \"size\": 2423332449\n    },\n    \"ParkedObstacle_Town12_Route2549_Weather21.tar.gz\": {\n        \"sha256\": \"422dece424c09cf9cadff78b6598d48de8e4b00774bf7026a7dbc9e4cba138ef\",\n        \"size\": 333208201\n    },\n    \"ParkedObstacle_Town12_Route2552_Weather23.tar.gz\": {\n        \"sha256\": \"897e794130d881eae9822b94d3651ee95d5eca4192460fe7dde5b4869cb719d1\",\n        \"size\": 409675211\n    },\n    \"ParkedObstacle_Town12_Route2553_Weather25.tar.gz\": {\n        \"sha256\": \"90e31157f1993f8f3bc57dfa287acfb8e230947b14fefa4c38a59d4def0c89fd\",\n        \"size\": 474790656\n    },\n    \"ParkedObstacle_Town12_Route2554_Weather0.tar.gz\": {\n        \"sha256\": \"1bcee49ef4645b39932216793338953566766256e5bafa7856e4f86e6170bf8b\",\n        \"size\": 393312567\n    },\n    \"ParkedObstacle_Town12_Route2555_Weather1.tar.gz\": {\n        \"sha256\": \"02666fc8e57939611f4bb2b3ffa941a5b3dbf388abef5f33c9f83f68450aba2d\",\n        \"size\": 509056104\n    },\n    \"ParkedObstacle_Town12_Route2558_Weather3.tar.gz\": {\n        \"sha256\": \"3a3287dfc1c34322b62e289ea318c277d1180224765dd2b4b9d09f0355faf8dd\",\n        \"size\": 464530902\n    },\n    \"ParkedObstacle_Town12_Route2559_Weather5.tar.gz\": {\n        \"sha256\": \"e37cd0828fc719acd7a397058b4f92576536cdd2b4a63fde9170f304f1c3ec12\",\n        \"size\": 401595022\n    },\n    \"ParkedObstacle_Town12_Route2560_Weather6.tar.gz\": {\n        \"sha256\": \"45188575499a6d95aae6ecf802e7cc46f8971f306b581783dac21c6ae6744a5d\",\n        \"size\": 464977331\n    },\n    \"ParkedObstacle_Town12_Route2563_Weather9.tar.gz\": {\n        \"sha256\": \"f082ed51249474cd5271299785732f5c9aa3323573f8a1a59490e95481727408\",\n        \"size\": 125776632\n    },\n    \"ParkedObstacle_Town13_Route3323_Weather8.tar.gz\": {\n        \"sha256\": \"0444e7a39aebe478622c9b67689bfafa41a721623941028dd4cb734a8ce0a445\",\n        \"size\": 478057633\n    },\n    \"ParkedObstacle_Town13_Route3325_Weather18.tar.gz\": {\n        \"sha256\": \"dbdb30e1d691d9ca8e368ccbb67ba201872df20701e075aaced0968681a63313\",\n        \"size\": 558051859\n    },\n    \"ParkedObstacle_Town13_Route3327_Weather20.tar.gz\": {\n        \"sha256\": \"6d3de96608c4afb2b0f8651ff81218c6b99ec6f5f580dfb3f4d4fea7e48ca76c\",\n        \"size\": 390472162\n    },\n    \"ParkedObstacle_Town13_Route3329_Weather22.tar.gz\": {\n        \"sha256\": \"27744db687895e468d28237a192f690114ac9689d84af1cb1678cddc53ffecc4\",\n        \"size\": 568407986\n    },\n    \"ParkedObstacle_Town13_Route3330_Weather23.tar.gz\": {\n        \"sha256\": \"5814e04fa5df4c3c074e22449205c2f8bbbb7c2d999871a5cab9bae03880739c\",\n        \"size\": 690455603\n    },\n    \"ParkedObstacle_Town13_Route3331_Weather23.tar.gz\": {\n        \"sha256\": \"6d7e3471b74da5e7d8b7d6380f957ea26210df4bb2b8af50c5f45f1084fb13a5\",\n        \"size\": 624000458\n    },\n    \"ParkedObstacle_Town13_Route3332_Weather25.tar.gz\": {\n        \"sha256\": \"401270a956f5bec2ae256f3af9538fcae678d58f9351661d813a2e4bc3ce9443\",\n        \"size\": 465333999\n    },\n    \"ParkedObstacle_Town13_Route3334_Weather1.tar.gz\": {\n        \"sha256\": \"6ecaee740ff5071b8a02e23d1cbe1e4b8279d660a9067f3e43831d5284c10b75\",\n        \"size\": 808623845\n    },\n    \"ParkedObstacle_Town13_Route3335_Weather2.tar.gz\": {\n        \"sha256\": \"e748804d0d8e2032a62c81ca7ef9f82f29aa99cb8060fe10f792a7073785e7f2\",\n        \"size\": 798856982\n    },\n    \"ParkedObstacle_Town13_Route3336_Weather3.tar.gz\": {\n        \"sha256\": \"539ae538c976ee5c9f84f85bd89cb7b8bf8400cab43f14e2fa4ca0d2e4919cd4\",\n        \"size\": 471205349\n    },\n    \"ParkedObstacle_Town13_Route3338_Weather5.tar.gz\": {\n        \"sha256\": \"79bc677883b1baec4a8fb186f383437fee6e1e36f1e6d45dfc721250d6034042\",\n        \"size\": 718729640\n    },\n    \"ParkedObstacle_Town13_Route3340_Weather7.tar.gz\": {\n        \"sha256\": \"c8d72378d018a2e51fa09b5705106068055827a6ef81527169f3bcc30f33d0c2\",\n        \"size\": 547028266\n    },\n    \"ParkedObstacle_Town13_Route3342_Weather9.tar.gz\": {\n        \"sha256\": \"a779b7932748c8b575888dc0b6a5efad89c7a2ef59358e1de8d47c552b2ef91c\",\n        \"size\": 344326705\n    },\n    \"ParkedObstacle_Town15_Route25299_Weather25.tar.gz\": {\n        \"sha256\": \"8d95612a234c6c08e0e2cd4f53e926a92090397da6fba0fa971b0ea50b9569bc\",\n        \"size\": 554479438\n    },\n    \"ParkedObstacle_Town15_Route25306_Weather6.tar.gz\": {\n        \"sha256\": \"e6e1dbc4c5b74a56d5dd2c225947920cd2cea6c5ee9b56da9edccbbfdef829c6\",\n        \"size\": 610633926\n    },\n    \"ParkedObstacle_Town15_Route25313_Weather13.tar.gz\": {\n        \"sha256\": \"03436fd9461d0faaa3ba7fe99e5b0fd6bcb334c72cae2b0cb526aa60bc32a59d\",\n        \"size\": 475007379\n    },\n    \"ParkedObstacle_Town15_Route25320_Weather22.tar.gz\": {\n        \"sha256\": \"455cb74a71e0b2b3dd5c7f4bccb881e6130d90a605e831ed4336129001668111\",\n        \"size\": 590072070\n    },\n    \"ParkedObstacle_Town15_Route25327_Weather3.tar.gz\": {\n        \"sha256\": \"b13b4cedf63dfec4bbdd0ea1d9035f527edad01443bee60efcab026dfb866f95\",\n        \"size\": 938610926\n    },\n    \"ParkedObstacle_Town15_Route25341_Weather20.tar.gz\": {\n        \"sha256\": \"31cd48bbb415b34ab6700e1d1eb76235280ef6c92c2b021296b65a7511039c0b\",\n        \"size\": 225104727\n    },\n    \"ParkedObstacle_Town15_Route25348_Weather1.tar.gz\": {\n        \"sha256\": \"fbcddd6cc5b308a82911970dd8a5cee3e119657f19511b5480aa6e6a5877911a\",\n        \"size\": 249455062\n    },\n    \"ParkedObstacle_Town15_Route25355_Weather9.tar.gz\": {\n        \"sha256\": \"c3178ca9be33cb2aaabfacb6c6a434a58fd3c3113df8cbc6c3ca6e99044cf623\",\n        \"size\": 627223298\n    },\n    \"ParkedObstacle_Town15_Route25362_Weather18.tar.gz\": {\n        \"sha256\": \"50dc4c830e6e4e154121f1ee2dd8ef09e35201e93f1754e12ed71e2174abb1ac\",\n        \"size\": 629704023\n    },\n    \"ParkedObstacle_Town15_Route25376_Weather7.tar.gz\": {\n        \"sha256\": \"ce983c04e0ce360823c3ff867020b7f2b77e24c70f8dc77b487fc205b145d56b\",\n        \"size\": 624075516\n    },\n    \"ParkedObstacle_Town15_Route25383_Weather14.tar.gz\": {\n        \"sha256\": \"0840bf8cfb122637a6c71ddb3972da833736492ed56944e728d7c0dddfb7124b\",\n        \"size\": 567903151\n    },\n    \"ParkedObstacle_Town15_Route25390_Weather23.tar.gz\": {\n        \"sha256\": \"b4519467f55a30990784aa26030a045e7d893009098da605336c2a8c8d1ac60e\",\n        \"size\": 756523412\n    },\n    \"ParkingCrossingPedestrian_Town02_Route24274_Weather9.tar.gz\": {\n        \"sha256\": \"b9df722ff0b52c4f189b2a3aad04057b36aea2d6bf92e0d4df1812443ad5ab38\",\n        \"size\": 527795050\n    },\n    \"ParkingCrossingPedestrian_Town02_Route24284_Weather21.tar.gz\": {\n        \"sha256\": \"e27df7fa5c4b129e6b1cff34531c0c6c1d2ef543008706daa6d364934e5fd151\",\n        \"size\": 144312104\n    },\n    \"ParkingCrossingPedestrian_Town02_Route24294_Weather6.tar.gz\": {\n        \"sha256\": \"3394f68765ade78881107f98856961188532a6856897344df3a40aa17a7b9434\",\n        \"size\": 428372451\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24206_Weather10.tar.gz\": {\n        \"sha256\": \"225af69fbf5fac3c3f087b4da1ae2fdf94b94a31f750d200a9330c6bedba1a08\",\n        \"size\": 290083106\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24216_Weather22.tar.gz\": {\n        \"sha256\": \"a2ded7712c3ca19f0d27ca8ba92665b520b6805db0aa679462558035b53d4212\",\n        \"size\": 299630775\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24226_Weather7.tar.gz\": {\n        \"sha256\": \"017b40602f5e58908e206736cd8de918aec50338932495803764476b6b6274ee\",\n        \"size\": 240349623\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24236_Weather19.tar.gz\": {\n        \"sha256\": \"240ee0088fc7564c055e0e1f74d51624cf12eeaa9fb24c39864fbf5d4ebf1a67\",\n        \"size\": 178604264\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24246_Weather3.tar.gz\": {\n        \"sha256\": \"54a22af4430215be8411dab59a23f8a19693154b9dec27b7960d620d1f382ece\",\n        \"size\": 388191905\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24256_Weather14.tar.gz\": {\n        \"sha256\": \"d7396dbfa95b21992f464215ad7bc5b001b891ff26d644043cdea60db23313ed\",\n        \"size\": 192307705\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24266_Weather0.tar.gz\": {\n        \"sha256\": \"9a4453b9f53307742109976bb7c542bc352fe910e79d3268e236c4c107aeb8c9\",\n        \"size\": 411544524\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24276_Weather11.tar.gz\": {\n        \"sha256\": \"55db32a18c23c3ee52574c03668489c9009bab75d75eac4e06d1dc8c0e582bf9\",\n        \"size\": 308153219\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24286_Weather23.tar.gz\": {\n        \"sha256\": \"d5357723c9327ce1ed65066802cbae97486006c495b4940046864385573717ff\",\n        \"size\": 190058730\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24296_Weather8.tar.gz\": {\n        \"sha256\": \"57510073d59f0055b3857befd288dc422eefd1b39c3c8609b7548814857e7467\",\n        \"size\": 365149285\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24306_Weather20.tar.gz\": {\n        \"sha256\": \"9ed8bccad35be48f749eb05becdfc393180d74708e6741f7df0d45ec9b4789b1\",\n        \"size\": 285540416\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24316_Weather5.tar.gz\": {\n        \"sha256\": \"194f3503b69b98b1a7030fb3c6c81b4cc47be0e92f1be906e9e18f47a53894d5\",\n        \"size\": 394166737\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24326_Weather15.tar.gz\": {\n        \"sha256\": \"5b08bad18d03ee73cf09f2238e3ac8b2f9b129854ccd72a4a6b030f8c3bf295e\",\n        \"size\": 372429486\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24336_Weather1.tar.gz\": {\n        \"sha256\": \"a3ffd9c1ecac3262f731f14e71fd134795c55435db8ed1ba71bf371b21f43f15\",\n        \"size\": 465886173\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24346_Weather12.tar.gz\": {\n        \"sha256\": \"9370665c7d447c0e404f702dcb3511214f2d889a03325b337350ed6fa78c9d63\",\n        \"size\": 460042200\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24356_Weather25.tar.gz\": {\n        \"sha256\": \"ec0e27d5c5e9c6c2e1d3716ab33c44b20f875ed5298d32f8395c0262f9f3a51a\",\n        \"size\": 324802885\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24366_Weather9.tar.gz\": {\n        \"sha256\": \"361604a5d1ee5e7cbe9252c5c503c3ffdc9c9014d3173a8d33b930f32d02b334\",\n        \"size\": 395540666\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24376_Weather21.tar.gz\": {\n        \"sha256\": \"74f615f365992704aaac63250b7b0d7f1c65389b84ca713c6f634577b64e7922\",\n        \"size\": 297393627\n    },\n    \"ParkingCrossingPedestrian_Town03_Route24386_Weather6.tar.gz\": {\n        \"sha256\": \"ada43c35ed83e5e20cc48c3ddc6f87d595bf0d4f3f60d2328f9402d5cd09179e\",\n        \"size\": 366594065\n    },\n    \"ParkingCrossingPedestrian_Town10HD_Route24220_Weather0.tar.gz\": {\n        \"sha256\": \"39612f584135c5b7989b04dc70c500b871df5c3715de5d7300a70926c8392494\",\n        \"size\": 261341604\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1684_Weather14.tar.gz\": {\n        \"sha256\": \"f2acfec7baf08a25d2c57400c309f8642f36c9b59501a09da5db7b27274be9e3\",\n        \"size\": 154653367\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1685_Weather15.tar.gz\": {\n        \"sha256\": \"ef9055ae10a8b2f6bdd470ed3bd5668ef370fd703bd1f14a42492d850fb82aba\",\n        \"size\": 174838547\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1687_Weather9.tar.gz\": {\n        \"sha256\": \"9e032a78d61435bbf6f0f6b1a65389fa9ce67062c4a7f80952e5f69839adbdd7\",\n        \"size\": 160913347\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1688_Weather18.tar.gz\": {\n        \"sha256\": \"e2a395a6f9cc51ec02060e811816427f78afee8db10dfba9f7a41ec417a3e78f\",\n        \"size\": 209480045\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1689_Weather19.tar.gz\": {\n        \"sha256\": \"aca367f583cc20997ba1d2320bd4f7b5475f0e944e2bca8901020c1157dfa907\",\n        \"size\": 189523686\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1690_Weather20.tar.gz\": {\n        \"sha256\": \"d493381c1f022da27d0807bd1bc36335cea72c4c4b7e32671f155601ca52e32d\",\n        \"size\": 205266359\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1691_Weather21.tar.gz\": {\n        \"sha256\": \"6d709e31c0e619d643f13c63792a4213a097bf654d253ff0e5f1cb7dec254408\",\n        \"size\": 193405256\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1692_Weather22.tar.gz\": {\n        \"sha256\": \"299fa492cfe0ddc8c9498e92b9c6d3389bca1df145df30e4ea39a22c5550a3be\",\n        \"size\": 175152916\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1695_Weather25.tar.gz\": {\n        \"sha256\": \"930ef14d3230b8d9c4361f6cdfeb2d8bbaaf8167452a8d7a30e717896f2bbeb6\",\n        \"size\": 162513338\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1696_Weather0.tar.gz\": {\n        \"sha256\": \"705bb61ddae547f3ba84598081fdc2ba60f77191aaf2b96759ec956e339101eb\",\n        \"size\": 206811224\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1697_Weather1.tar.gz\": {\n        \"sha256\": \"8b7a15ea7ff6e8ef4dab22928b62652427dd7e5199898b53dd5bcfc3de037dfa\",\n        \"size\": 199355916\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1698_Weather2.tar.gz\": {\n        \"sha256\": \"7c2fec70adde9b74b26ebdeeacd786eb33da0df979608f827a8a7071c7e2a8b4\",\n        \"size\": 207263211\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1699_Weather3.tar.gz\": {\n        \"sha256\": \"3f1a934c9af6905bc5265c04628bad3333c7b9074ece7979f1127235c27ee6fa\",\n        \"size\": 183914998\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1700_Weather3.tar.gz\": {\n        \"sha256\": \"a3f34b58b87ac77782c84b202b250d9eb3d3a53319f346f6a80deb47b864542e\",\n        \"size\": 215732214\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1701_Weather5.tar.gz\": {\n        \"sha256\": \"21e4b51545188f70966d6baa49147b57a518dbdc260ea047c123dbab523ffea2\",\n        \"size\": 189241528\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1702_Weather6.tar.gz\": {\n        \"sha256\": \"82ee135a7623774df2e6e96726ab77628b167ed89f7b45acc9c1ff87b3dc0007\",\n        \"size\": 197228552\n    },\n    \"ParkingCrossingPedestrian_Town12_Route1703_Weather7.tar.gz\": {\n        \"sha256\": \"e6e3ca7ca5f7271b5f8ace4b286d4c9bceae29026097132f5cd3e2d2a0d9393b\",\n        \"size\": 218871666\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18213_Weather12.tar.gz\": {\n        \"sha256\": \"c1ce6483d0698161576926376e5ab8f380608a56f28120a643a871208c9760a6\",\n        \"size\": 155490256\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18214_Weather13.tar.gz\": {\n        \"sha256\": \"09363eeb7e0ae71ca2bf6673947dfb902ba93c0e1fead7abd9f6df313fc51249\",\n        \"size\": 165537903\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18215_Weather14.tar.gz\": {\n        \"sha256\": \"491bb04cef4695704678397db8189c470d74e6b436bbb39ce9e317b1b00d4ab3\",\n        \"size\": 178595885\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18216_Weather15.tar.gz\": {\n        \"sha256\": \"0a71b30e56cc88af3d751ea1028ad563adaed209539bdfb3096506eeadfc2de3\",\n        \"size\": 183274723\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18219_Weather18.tar.gz\": {\n        \"sha256\": \"5d1ffed0a04793ac513e7908479e862fab6cfdfab07163b4f0407fde3579355e\",\n        \"size\": 206114017\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18220_Weather19.tar.gz\": {\n        \"sha256\": \"9bb6107c748cdde8e65f61a72d9337ee418a3699504ca9c241586a514c20368c\",\n        \"size\": 173513602\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18221_Weather20.tar.gz\": {\n        \"sha256\": \"52959cdf7fbda084969a57016d954ecad6edaf059b7d041b5c8cc3817d8f5ac0\",\n        \"size\": 172445993\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18222_Weather21.tar.gz\": {\n        \"sha256\": \"e010c82723ae252e3cf3ffdffeaaee0778b9cd9e3c4ce7880ed4d5258257665d\",\n        \"size\": 159754471\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18223_Weather22.tar.gz\": {\n        \"sha256\": \"7d204ab1b164b0504935c3489b541534a0826ad99057b298406fe9f6d076c3dd\",\n        \"size\": 176340450\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18224_Weather23.tar.gz\": {\n        \"sha256\": \"e314012c4563eafd5232eeb76353f1a9b6b2fba9324270e024a1c1ffc6350347\",\n        \"size\": 172873027\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18225_Weather23.tar.gz\": {\n        \"sha256\": \"01ddaf424830f6953d8373828114b8aa036498d4702522d3b09174b42b4bf590\",\n        \"size\": 159173390\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18226_Weather25.tar.gz\": {\n        \"sha256\": \"2819300b7c655d6b149a29562516503c8214591c5fa112750414733c54bb3c9f\",\n        \"size\": 148894526\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18227_Weather0.tar.gz\": {\n        \"sha256\": \"48e561a219cfb5211ae04efd0358c7c44c7d3f5f0bffc08f42cbbc967cfdc7a6\",\n        \"size\": 199946127\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18228_Weather1.tar.gz\": {\n        \"sha256\": \"df29a9114a4c6d62083133e610648925ac2d3302dda85443d9da922f38564db4\",\n        \"size\": 221022187\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18229_Weather2.tar.gz\": {\n        \"sha256\": \"0acc28c8b8cbbceadf643eaa0774401f235dc6a5f559fb1ce73bdd7b5d3afcc7\",\n        \"size\": 191684960\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18230_Weather3.tar.gz\": {\n        \"sha256\": \"55303295e3ef25b9e3566a4fb53bab4402c3cfa5c463ce43c6783cfd57f8034a\",\n        \"size\": 211675495\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18231_Weather3.tar.gz\": {\n        \"sha256\": \"630dd6c155468b6599b8214ce1e727f12752af6a7acc0228b36d85125d237678\",\n        \"size\": 192366853\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18232_Weather5.tar.gz\": {\n        \"sha256\": \"03314fb0be1783eff85923475c502d12c2c702c95aca88a51b7c166c75fa1703\",\n        \"size\": 203539420\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18233_Weather6.tar.gz\": {\n        \"sha256\": \"835fbcb0f859b7ecf4576df1b956e42050428fb27c342e7f78de76427592c187\",\n        \"size\": 180465645\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18234_Weather7.tar.gz\": {\n        \"sha256\": \"8d2fa0e7f17c2145ea2b3fe776fb7a2b5a173f33ec726350ba47f0e58c1dac90\",\n        \"size\": 206353121\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18235_Weather8.tar.gz\": {\n        \"sha256\": \"9763bedec7eb0b3c0efe43c894c598acc0c1b579b3c43d3d6cb580d92e4b0563\",\n        \"size\": 184909062\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18236_Weather9.tar.gz\": {\n        \"sha256\": \"69ba9cea98acd28a51d1d0e83d933a5576a8f5661ac94b51840e7e499ad665b4\",\n        \"size\": 137107284\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18237_Weather10.tar.gz\": {\n        \"sha256\": \"e7c7441a473beee42daee9cc6bce376d949574105a5f2c2844268354c6c62b72\",\n        \"size\": 183855706\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18239_Weather12.tar.gz\": {\n        \"sha256\": \"186df6c26521b8ca97508d1d934f33c4b4dec2fb0a8d56a429b686fdc506c017\",\n        \"size\": 141257767\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18240_Weather13.tar.gz\": {\n        \"sha256\": \"7b26a1201b545aaab76bddbe977abebe6322f606f99532a634461774e2b2d540\",\n        \"size\": 143997266\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18241_Weather14.tar.gz\": {\n        \"sha256\": \"2fe4e238b8dc8e72f2d2ce37101272ab83e0f600f7187582b192deaa41949fbb\",\n        \"size\": 161747088\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18242_Weather15.tar.gz\": {\n        \"sha256\": \"b7276bac27da9bfdf4d2c2ca6cb9063b92ffc6df522b6236f38e3f2287e7d6dc\",\n        \"size\": 172482665\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18243_Weather8.tar.gz\": {\n        \"sha256\": \"787616e8f8bca48440bada35875ba6aebdfd07841129c6959f8acb44f28a5edd\",\n        \"size\": 193428742\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18244_Weather9.tar.gz\": {\n        \"sha256\": \"d1077fa26b75aa5ba612b5ba38f041e065d428817d06f598cf5d17e1708fd917\",\n        \"size\": 111158565\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18245_Weather18.tar.gz\": {\n        \"sha256\": \"2ac76df86a1ee0c55cd27f5bcdf873f7b0b64196da78b6eb8f5d82c8730c2b9f\",\n        \"size\": 196766586\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18247_Weather20.tar.gz\": {\n        \"sha256\": \"f0d4a8db1eb8aa41760622b9c5c416586628d7370142619946747f9d0d4ad352\",\n        \"size\": 170350460\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18248_Weather21.tar.gz\": {\n        \"sha256\": \"1d25b22fc610f54294d34cda9490fc7362ffefb12a0f949453c86bf5a1188e64\",\n        \"size\": 149662311\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18249_Weather22.tar.gz\": {\n        \"sha256\": \"3744ec632c40b480e42831cc409def9c0b0d95db5e4e9c0345e10a9b4709d4f8\",\n        \"size\": 178506433\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18250_Weather23.tar.gz\": {\n        \"sha256\": \"b153fa9a4de81d6ec52bd11d6c2beb488b822a1e63aa6a6a84d54cec0017a495\",\n        \"size\": 151776234\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18251_Weather23.tar.gz\": {\n        \"sha256\": \"0becab4db0ca8bdff433434cc2ffb482395b62e215a52aa8fef3b19f411d5f26\",\n        \"size\": 149249975\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18252_Weather25.tar.gz\": {\n        \"sha256\": \"5b54e596053f0ea2244becf7be50954e5106b1db3584123a20613c6a8497faa1\",\n        \"size\": 160770379\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18253_Weather0.tar.gz\": {\n        \"sha256\": \"ef71309c4772dd73bdbebb0e1e61ab4b11f1cc2321e0a8f3221c7214f17b3408\",\n        \"size\": 194456818\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18254_Weather1.tar.gz\": {\n        \"sha256\": \"fcbea1a45b1fad0acc4bdd789dcd73c2cef039498dfe601a86ef2e4373259aba\",\n        \"size\": 227933272\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18255_Weather2.tar.gz\": {\n        \"sha256\": \"bca1470d5899640339aeb6df8b40eeb022ac4e31f3286051c74f273fcd27bf02\",\n        \"size\": 209254395\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18256_Weather3.tar.gz\": {\n        \"sha256\": \"824cde73d501433788f1c22ca8624f26bdb683970ea540a6b5b1262d272d36d4\",\n        \"size\": 199698439\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18257_Weather3.tar.gz\": {\n        \"sha256\": \"ee14e54fb3ed996c6a77ee2a29d4de504188286c845e3d250f70d840fb562c96\",\n        \"size\": 187553091\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18258_Weather5.tar.gz\": {\n        \"sha256\": \"b3d9d56be7f22b13b5a73c7491975495a6d2f8a7ec7a6733cb63466d1b13fe0d\",\n        \"size\": 198280855\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18259_Weather6.tar.gz\": {\n        \"sha256\": \"a1de549e53faefbb72c5264cc9333d2e398f2c0f6368a28a073b3a2834046779\",\n        \"size\": 182088532\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18260_Weather7.tar.gz\": {\n        \"sha256\": \"bd1b8712faeb0cd30fcc35561201a10c642c7450b451bca61c440f2a7d46ecd6\",\n        \"size\": 215120919\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18261_Weather8.tar.gz\": {\n        \"sha256\": \"85bf01d48635cf7f630bcd64eb2ccad4e022fbdf96f458c1fef05b15be786463\",\n        \"size\": 185445755\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18262_Weather9.tar.gz\": {\n        \"sha256\": \"15040315ed965049a89caec35f5d32c9511ed95bb6fbf93a21a7df19b06c82b6\",\n        \"size\": 146827863\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18263_Weather10.tar.gz\": {\n        \"sha256\": \"f58f6f35bb86ab1e379c84f19de0757e4d56ee62e85d99d00ce7fae6667cc12b\",\n        \"size\": 183919332\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18264_Weather11.tar.gz\": {\n        \"sha256\": \"a8319f77df580e2003c273afbcb98a1a071e7323876aa5eefd93f59b187a37ac\",\n        \"size\": 157906350\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18265_Weather12.tar.gz\": {\n        \"sha256\": \"5c3fbcd882c21178fcade53264f1436e4792d3f6779d78ec2b4045ea443b063a\",\n        \"size\": 139378456\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18266_Weather13.tar.gz\": {\n        \"sha256\": \"0c4868f3feec0076b86c530a005f6cc84b87a997d00728596bd16c889be812b6\",\n        \"size\": 151101749\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18267_Weather14.tar.gz\": {\n        \"sha256\": \"682eb171c5f56d153183e54c74ba81d847ce1c5aad10b23f53718ae5a38960af\",\n        \"size\": 134965982\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18268_Weather15.tar.gz\": {\n        \"sha256\": \"f390a218f0282a65eb29e7491cd71a4669e5b39f19969a0c85983256ca714a13\",\n        \"size\": 172243568\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18269_Weather8.tar.gz\": {\n        \"sha256\": \"ba954ff8b4f624ba180093b7d7d328d66a38d0a97822ce7c74807d56c386bb98\",\n        \"size\": 214187305\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18270_Weather9.tar.gz\": {\n        \"sha256\": \"7a0b0c8fd090ad78a25fe2b369fa700b8031b0fad1e5abcfdc29ada148129d01\",\n        \"size\": 121578819\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18271_Weather18.tar.gz\": {\n        \"sha256\": \"f072baf7dddcb7cd8110f4cbc12082d1117875dc28f38c1e3d4fff822d6fbbee\",\n        \"size\": 201325614\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18272_Weather19.tar.gz\": {\n        \"sha256\": \"641a31e2521987aad54e921525b0d48e51071698839eadc5ee0cc889e790008c\",\n        \"size\": 214194083\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18273_Weather20.tar.gz\": {\n        \"sha256\": \"6a31248f89a2dacffbd4e8f8fbaa9d02e903737438a92b7873c2b87db791a052\",\n        \"size\": 176860578\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18274_Weather21.tar.gz\": {\n        \"sha256\": \"a7e362f8da5e847d9dc53a6bd47d1adb5f632ddfe0306225fe009ece56d9abf1\",\n        \"size\": 170651689\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18275_Weather22.tar.gz\": {\n        \"sha256\": \"292aaa2d87e4f507f7975ed9b2cb6fe2ee7c6305e98f3a2c960882b32c142291\",\n        \"size\": 166915890\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18276_Weather23.tar.gz\": {\n        \"sha256\": \"d5508b6c9452338b1ab700e74d5a34b2337fcc667d7cae0e15e5492d4d488bd1\",\n        \"size\": 168347458\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18277_Weather23.tar.gz\": {\n        \"sha256\": \"80ba095611425af72fe9e22a4acab282ebf7ab280741c63dafee21cc29ead5da\",\n        \"size\": 156131550\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18278_Weather25.tar.gz\": {\n        \"sha256\": \"75261801cedf41ff12dff39137d3cd7c8853704f7b954d445198deaae66fefac\",\n        \"size\": 143561693\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18279_Weather0.tar.gz\": {\n        \"sha256\": \"26b3692cf88415663bcb390dc3dce08e5663bfb08a0e34b44ae4d6685ac6ae0a\",\n        \"size\": 196692070\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18280_Weather1.tar.gz\": {\n        \"sha256\": \"8ea7cbf758ba22853aced88d55b330bded65f69c74d1d20561e79fb39caa5a02\",\n        \"size\": 212664774\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18281_Weather2.tar.gz\": {\n        \"sha256\": \"faebaf024ec23dc26dc0cbee3ce47c3507be7d0dda90263038454b26e8ca6792\",\n        \"size\": 193404852\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18282_Weather3.tar.gz\": {\n        \"sha256\": \"e4d0f131290419292da28d58556000ddfad2a60b1b5d8009e126e7cd2fb03bef\",\n        \"size\": 181673959\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18283_Weather3.tar.gz\": {\n        \"sha256\": \"d6ec04d1c301ae7504dbdc5a8bb2574eccf2b33ba26d93b13182a7aaa59cb3a5\",\n        \"size\": 216426642\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18284_Weather5.tar.gz\": {\n        \"sha256\": \"c8f1bd6ddfa54d881a762335eb94de4456401bfe1e832dceb7037441212a67b6\",\n        \"size\": 199282381\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18285_Weather6.tar.gz\": {\n        \"sha256\": \"408fbc734e96a07c52114bfbc43adbbe1ef924230b62bb0d22022f67bd332aa0\",\n        \"size\": 182897426\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18286_Weather7.tar.gz\": {\n        \"sha256\": \"351c62b709e1438bb1b20117a275237f4038c95fd8315687d6820106960fb761\",\n        \"size\": 222361343\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18287_Weather8.tar.gz\": {\n        \"sha256\": \"c8f47a299de208f3c37f0777b1c7f54ea8927bc54bea3b22ac6714f7c1f3b1a6\",\n        \"size\": 175879392\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18288_Weather9.tar.gz\": {\n        \"sha256\": \"fcc25154a2883b6dfa7a72e1003ac46af278c41c02a29a888af17923f6a5b74e\",\n        \"size\": 145802624\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18289_Weather10.tar.gz\": {\n        \"sha256\": \"06f23e62dd08097dd412517d2c0e2800e131c461ddac3d7e127f68f08749fe08\",\n        \"size\": 196457034\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18290_Weather11.tar.gz\": {\n        \"sha256\": \"11a3011246b0060999b3c2137a5b73ec9f749efc2ce986da8534cf5f0e7c9c8e\",\n        \"size\": 136123020\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18291_Weather12.tar.gz\": {\n        \"sha256\": \"58599400817863c6175d3922e61e1e5f706a1ea7a31cb292ed255783f886e6ed\",\n        \"size\": 143546090\n    },\n    \"ParkingCrossingPedestrian_Town12_Route18292_Weather13.tar.gz\": {\n        \"sha256\": \"81cbb54b6bf45efdd8e9a69a21b92c559bf27c137fb38b093613bafa0223cef4\",\n        \"size\": 156798536\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2464_Weather14.tar.gz\": {\n        \"sha256\": \"0fd3409c955c8168acbfa3c91ebe2dfe0f70eea93169d48042eb7d586761a712\",\n        \"size\": 274904875\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2465_Weather15.tar.gz\": {\n        \"sha256\": \"d679875a2e8b9f7d04045e3b07c68b9878d9abb5c06e0c941a0b369954414215\",\n        \"size\": 169107219\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2466_Weather8.tar.gz\": {\n        \"sha256\": \"49104b5dcac096d81a96f40143f33c9a1612937a24f2a03fba1d68c964bfdb83\",\n        \"size\": 195220920\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2469_Weather19.tar.gz\": {\n        \"sha256\": \"30f13cad23fa9f822d42362cb6511a6bbb9c62a48f5ed3f2636d7d0685a18404\",\n        \"size\": 166222079\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2470_Weather20.tar.gz\": {\n        \"sha256\": \"c11742a12eccb9fc758c0401f1fb274b9a5da7143651bca106731a1bf197ac5c\",\n        \"size\": 178761463\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2471_Weather21.tar.gz\": {\n        \"sha256\": \"9423ff82ad75c3cb0495d4177f39480c5aa6512ff7e6eb65ba8a18ee90443058\",\n        \"size\": 161668984\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2472_Weather22.tar.gz\": {\n        \"sha256\": \"83340a95fa575d9d09820f6426e886abbd63b7986621ec5ac376c365788ee25d\",\n        \"size\": 253644618\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2473_Weather23.tar.gz\": {\n        \"sha256\": \"e68525174b74d51ffe660e4a98b11d7b7861be81e795618da3cc49236118fd6b\",\n        \"size\": 156096096\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2474_Weather23.tar.gz\": {\n        \"sha256\": \"1360ced2db7a328f92f2de15fcbc21b5d66dfb457d20cb8550d5ebd2c9475d28\",\n        \"size\": 166696548\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2475_Weather25.tar.gz\": {\n        \"sha256\": \"9caf66d73668152b8e48c89cbf115a9e722a6cc0ee29cfa9a3052e46e977fec8\",\n        \"size\": 152386876\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2476_Weather0.tar.gz\": {\n        \"sha256\": \"7772a59f207d16c232f6a851db48beb111d80078357e0cd45077b696419582d7\",\n        \"size\": 239227709\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2477_Weather1.tar.gz\": {\n        \"sha256\": \"d68d909599adbe4a880d76517e22b35ddeadbd50272b19472b28d4f44b347295\",\n        \"size\": 218739411\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2479_Weather3.tar.gz\": {\n        \"sha256\": \"a3bf0ff0a5177cda084870900e8013aac64dfee0d3388166c389df1344210b3f\",\n        \"size\": 206522349\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2480_Weather3.tar.gz\": {\n        \"sha256\": \"1049e59d79511ca9cd582724bdd0cba7bf09ade5e345310c06d54fc69726e0b9\",\n        \"size\": 192005960\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2481_Weather5.tar.gz\": {\n        \"sha256\": \"4f0ccd301914272c52fb3759f5833c9eb00a5dca4e410e3812bdd2dd0a0bc50f\",\n        \"size\": 208177696\n    },\n    \"ParkingCrossingPedestrian_Town12_Route2482_Weather6.tar.gz\": {\n        \"sha256\": \"9d032bfbc323b4b81c97892beb5c96b7e85158c501ecad75dc4de1712b6a937b\",\n        \"size\": 202085663\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3243_Weather14.tar.gz\": {\n        \"sha256\": \"0fb8ba87b02b0d04de9be67054ace724b66c43d9ce0d45eac984918087ad8115\",\n        \"size\": 582321520\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3244_Weather15.tar.gz\": {\n        \"sha256\": \"5202d3833b40cac6c8fd42ef1f0a886eee528f629aa92481a341fc6e4c48b2c9\",\n        \"size\": 431614777\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3245_Weather8.tar.gz\": {\n        \"sha256\": \"55dfec3cb8cb8b3d05177e5e05f1d9d90e4d2a32312cba6ecef5f801e9d6a6c7\",\n        \"size\": 313994041\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3246_Weather9.tar.gz\": {\n        \"sha256\": \"67f86cb15cd8d7755d50dde23db63e53868da87d9ce3b9680c2a8851b8d67d21\",\n        \"size\": 174107448\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3247_Weather18.tar.gz\": {\n        \"sha256\": \"24782b3b808ac3ecb80e9ed1f5a5ff1e39ef05b183c5545e0dd3b36280d70e3d\",\n        \"size\": 204554221\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3248_Weather19.tar.gz\": {\n        \"sha256\": \"8f20643454ee3a5c7a5f9e7819a0c3789588a6a847336cee4d7c71679e8a17b3\",\n        \"size\": 244311957\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3249_Weather20.tar.gz\": {\n        \"sha256\": \"a629809e57869ce59a7b2d78ed0fca91b22be10b30ecbc543ec1a98018dcf28b\",\n        \"size\": 220700319\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3250_Weather21.tar.gz\": {\n        \"sha256\": \"bd28c4eb7cc7d441a59ae3b9835ec59b7768abade9f57f6fde047844ef64f051\",\n        \"size\": 502538145\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3252_Weather23.tar.gz\": {\n        \"sha256\": \"4e6719916e5c30f298483d8cd3438042c7e6aeb0da97cc5ac793084cacaaad49\",\n        \"size\": 195818180\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3253_Weather23.tar.gz\": {\n        \"sha256\": \"8956b78e0c3958edaf1d6718504391608929f2f16c12b69b43c7bc4779649911\",\n        \"size\": 199816278\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3254_Weather25.tar.gz\": {\n        \"sha256\": \"763db7775b87b19b628e888962a407370a5e32787f8167078a77e84840666463\",\n        \"size\": 165871095\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3255_Weather0.tar.gz\": {\n        \"sha256\": \"2826b0b7cc74d75ad50992bf7bde2fda4a0cdba281e79abdbf8640f3a985e8a1\",\n        \"size\": 464003544\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3256_Weather1.tar.gz\": {\n        \"sha256\": \"bf050c174f12f7be1bc3ab2f9c1337e2fa0f26c5d097ebba49ca4d014f8de4a9\",\n        \"size\": 514634093\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3257_Weather2.tar.gz\": {\n        \"sha256\": \"4db1dc7e9663172270685bd35ed1e2f23387a8590321fdc80e7999f524558eac\",\n        \"size\": 437713565\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3258_Weather3.tar.gz\": {\n        \"sha256\": \"48e630c5df18826581994d7222be9ba7bdb7240c16ec17f87fe79905ac5ab6ea\",\n        \"size\": 240764683\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3259_Weather3.tar.gz\": {\n        \"sha256\": \"b9fb3a22d44b3761edebe86434c9dd7ff18be5359b8e9cf5b52650d54c44dd43\",\n        \"size\": 221662237\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3260_Weather5.tar.gz\": {\n        \"sha256\": \"2fee816b3db7311afa38a0eaa7d41391693e448c79545aa0fd4a2531a0ef6a74\",\n        \"size\": 219903902\n    },\n    \"ParkingCrossingPedestrian_Town13_Route3262_Weather7.tar.gz\": {\n        \"sha256\": \"7189df5320a8c3ce0c64cbef0edaff96312a896fbc06b07649c30fce80d4f98a\",\n        \"size\": 192810739\n    },\n    \"ParkingCutIn_Town05_Route24749_Weather0.tar.gz\": {\n        \"sha256\": \"11193724999976ecfd6603acd7940d96935b7242bbe3f55a650d6ff48fdba0f5\",\n        \"size\": 241371623\n    },\n    \"ParkingCutIn_Town05_Route24759_Weather11.tar.gz\": {\n        \"sha256\": \"665ec32a724d6580333b987ffe199b895ca23c76c02d4a00d5cb10c8a22c71f7\",\n        \"size\": 173968264\n    },\n    \"ParkingCutIn_Town05_Route24769_Weather23.tar.gz\": {\n        \"sha256\": \"2beeda532b31b5abd6068d6ccd8f93364e488eb9e7f48b7d1726ec92d302fcfd\",\n        \"size\": 192331275\n    },\n    \"ParkingCutIn_Town05_Route24789_Weather20.tar.gz\": {\n        \"sha256\": \"499382f068139a285be4b9ed12bd20c46fdb9aaeb0ef8ab979c741eb784e0e16\",\n        \"size\": 193717870\n    },\n    \"ParkingCutIn_Town05_Route24799_Weather5.tar.gz\": {\n        \"sha256\": \"44a20064a50bc5f3ffa6a8e3933cba093ffed859f3967b35728fcc21f5300790\",\n        \"size\": 264258775\n    },\n    \"ParkingCutIn_Town05_Route24819_Weather1.tar.gz\": {\n        \"sha256\": \"cd66691e5615f9b71afac0aee2b0e88aa434763d89125b9bc48483d1eb2d3cbf\",\n        \"size\": 247227862\n    },\n    \"ParkingCutIn_Town12_Route1704_Weather8.tar.gz\": {\n        \"sha256\": \"892282ad334fd972bb6aeecf4902a19cfaf44bb7dbbe352b62af88358cc1ccb2\",\n        \"size\": 164672153\n    },\n    \"ParkingCutIn_Town12_Route1705_Weather9.tar.gz\": {\n        \"sha256\": \"78ca144f12ec710d36d2871b8107dcabe7ec7a7b991594b76a8ba7c3af7332f6\",\n        \"size\": 155676051\n    },\n    \"ParkingCutIn_Town12_Route1706_Weather10.tar.gz\": {\n        \"sha256\": \"c822bcb28ce562c17a0657ee37590634431202d438882be841cb86ced2f8f81c\",\n        \"size\": 189766408\n    },\n    \"ParkingCutIn_Town12_Route1707_Weather11.tar.gz\": {\n        \"sha256\": \"2a3ae00acf3d5d226836550738be5c39df93a9f64c38cebb4baf99a15b09b691\",\n        \"size\": 145651545\n    },\n    \"ParkingCutIn_Town12_Route1708_Weather12.tar.gz\": {\n        \"sha256\": \"cbfe3e809eddebea8efa740cde902048d3b28990aeaed95aef79ffd57060e5ec\",\n        \"size\": 149313125\n    },\n    \"ParkingCutIn_Town12_Route1709_Weather13.tar.gz\": {\n        \"sha256\": \"0ce6492085eba629dfdea6ed7980df6c0a6f5771b1d02100b4a8d479e09c58c7\",\n        \"size\": 163767152\n    },\n    \"ParkingCutIn_Town12_Route1710_Weather14.tar.gz\": {\n        \"sha256\": \"cadaa97ab934d224ec941e8e51c716e5ba7109ef8cfb142941b0d700bc93bd59\",\n        \"size\": 181212606\n    },\n    \"ParkingCutIn_Town12_Route1711_Weather15.tar.gz\": {\n        \"sha256\": \"1218416756fc0f8fbbdb9944b58ba6d8f7ee70e96fe9a85326791a1f85ae48c1\",\n        \"size\": 152571162\n    },\n    \"ParkingCutIn_Town12_Route1712_Weather8.tar.gz\": {\n        \"sha256\": \"8ff9e8e2423168076fd31f4ec303a423b8f0b7e9b01bd12c8f6e84d30e9d7549\",\n        \"size\": 195979504\n    },\n    \"ParkingCutIn_Town12_Route1713_Weather9.tar.gz\": {\n        \"sha256\": \"9e38177efbc289efbe51055418ecc196ec3e6b4e803b273d7972dd10a0742f1f\",\n        \"size\": 150969885\n    },\n    \"ParkingCutIn_Town12_Route1714_Weather18.tar.gz\": {\n        \"sha256\": \"6b9176ac72d933b7c93e5826b84c8e77db9ce7f27aed2088f7c3d6ca7b5d0d9a\",\n        \"size\": 212302442\n    },\n    \"ParkingCutIn_Town12_Route1715_Weather19.tar.gz\": {\n        \"sha256\": \"62ea642631c523d76ccb6325e882c9efc2b8888dd469bb40fe93c43d72d6d9b6\",\n        \"size\": 233779398\n    },\n    \"ParkingCutIn_Town12_Route1716_Weather20.tar.gz\": {\n        \"sha256\": \"005e5884de8f926b71d58d0b83592568a1713101dd90a41ffc8269e57c91a601\",\n        \"size\": 189395124\n    },\n    \"ParkingCutIn_Town12_Route1717_Weather21.tar.gz\": {\n        \"sha256\": \"f955f887aaf0c3aa63999b32ab34d7a71c2100b20e04e18c9c9da69a4d175463\",\n        \"size\": 179054416\n    },\n    \"ParkingCutIn_Town12_Route1718_Weather22.tar.gz\": {\n        \"sha256\": \"02573d76b58e68bc2165551e90c9952ca2ac795dc87683eb1e9ca787603a4f10\",\n        \"size\": 174922353\n    },\n    \"ParkingCutIn_Town12_Route1719_Weather23.tar.gz\": {\n        \"sha256\": \"6a9d0c185b3ec3c0a6f76413c76e7c96b1328301262628ef06da998e88556a13\",\n        \"size\": 161891751\n    },\n    \"ParkingCutIn_Town12_Route1720_Weather23.tar.gz\": {\n        \"sha256\": \"295bd39993791b8b384a24b7217234f532ac0099d62b8663791a4fe8fdf074ff\",\n        \"size\": 173627356\n    },\n    \"ParkingCutIn_Town12_Route1721_Weather25.tar.gz\": {\n        \"sha256\": \"a5372ef38b7a19744db266f1488f46066c0734e460858b9693c847b567dd918b\",\n        \"size\": 141851811\n    },\n    \"ParkingCutIn_Town12_Route1722_Weather0.tar.gz\": {\n        \"sha256\": \"e7ba8c41e4e1650351ae31c301d42a77fa3a71759ca47a9102772da738ef368a\",\n        \"size\": 208850423\n    },\n    \"ParkingCutIn_Town12_Route1723_Weather1.tar.gz\": {\n        \"sha256\": \"ea0cee97216bccb21f9020582be6491419025a24bf4b0d6aeaa8d7a6d6c197f5\",\n        \"size\": 209191215\n    },\n    \"ParkingCutIn_Town12_Route18293_Weather14.tar.gz\": {\n        \"sha256\": \"0e7606c6136ab41d48b77aafe7876ba7430d5fd7f8cccf18466b4a152a876ce8\",\n        \"size\": 175701029\n    },\n    \"ParkingCutIn_Town12_Route18294_Weather15.tar.gz\": {\n        \"sha256\": \"87067ba2631a68bc64c2278dcbde1cf7d8e9bb6ca601463c7c2330838f189501\",\n        \"size\": 185739635\n    },\n    \"ParkingCutIn_Town12_Route18295_Weather8.tar.gz\": {\n        \"sha256\": \"95133381af5fb4d15bc5b0f2ad435132a2fcbef31b1ed4dfe34989bc0aad1f17\",\n        \"size\": 206346834\n    },\n    \"ParkingCutIn_Town12_Route18296_Weather9.tar.gz\": {\n        \"sha256\": \"8ae8746bc0f343a812bfe856a4b4ce14fa6fbcfea70845e3be0396f87dcfa64a\",\n        \"size\": 161922062\n    },\n    \"ParkingCutIn_Town12_Route18297_Weather18.tar.gz\": {\n        \"sha256\": \"81ee17c14695de633443e6f632c6213439204e0937f5e547fd4db75f4e60ae85\",\n        \"size\": 213856338\n    },\n    \"ParkingCutIn_Town12_Route18298_Weather19.tar.gz\": {\n        \"sha256\": \"1df0be166f1b80d569c207e96b0b09fcc1caff5b79491f67475d6329b148fbe1\",\n        \"size\": 206456583\n    },\n    \"ParkingCutIn_Town12_Route18299_Weather20.tar.gz\": {\n        \"sha256\": \"cd66b84e3f5c5637338d7ebbb5eeda1b93948698f9b3f8ad88cda8300e77236b\",\n        \"size\": 191113247\n    },\n    \"ParkingCutIn_Town12_Route18300_Weather21.tar.gz\": {\n        \"sha256\": \"6be1e04df849efcfd1b92eb02e8cdd49804a50b00c4c41e5349cb4a66229a93b\",\n        \"size\": 158435765\n    },\n    \"ParkingCutIn_Town12_Route18301_Weather22.tar.gz\": {\n        \"sha256\": \"8f53c9eeb7e6d0d77aa31a6235383a6282d2576d506bba7f081c6e9449a848f0\",\n        \"size\": 164430343\n    },\n    \"ParkingCutIn_Town12_Route18302_Weather23.tar.gz\": {\n        \"sha256\": \"019ec92059bd611213da14df697a30513415fa3a7893e3ebd2e92fb6c611af58\",\n        \"size\": 150160861\n    },\n    \"ParkingCutIn_Town12_Route18303_Weather23.tar.gz\": {\n        \"sha256\": \"303bfdb2beff034372be326230e881263f7acfc58fe9b732b7c996ddabf3048b\",\n        \"size\": 156158004\n    },\n    \"ParkingCutIn_Town12_Route18304_Weather25.tar.gz\": {\n        \"sha256\": \"7eb57c5dc1db91661be7885c33def0a35f23250a6fbda22c0095a99b6b4816ea\",\n        \"size\": 159862813\n    },\n    \"ParkingCutIn_Town12_Route18305_Weather0.tar.gz\": {\n        \"sha256\": \"fcfe5a742019adb78956a237e284b15b64ce52f60dc20fa6ea9c950d5655f28c\",\n        \"size\": 221950605\n    },\n    \"ParkingCutIn_Town12_Route18306_Weather1.tar.gz\": {\n        \"sha256\": \"e0ece169222345a0569bfedd320761955fdd12db6a590926f78d9568209513fd\",\n        \"size\": 215783188\n    },\n    \"ParkingCutIn_Town12_Route18307_Weather2.tar.gz\": {\n        \"sha256\": \"e042acec882d3d1a1fcc61b526ba83458a92fb41b31cb4a6aa9aa51f95b8dfc0\",\n        \"size\": 199055703\n    },\n    \"ParkingCutIn_Town12_Route18308_Weather3.tar.gz\": {\n        \"sha256\": \"7c605107d20b536014c12328420a60355b602c8a64391582f3fa0dd24c1eeb14\",\n        \"size\": 208982243\n    },\n    \"ParkingCutIn_Town12_Route18309_Weather3.tar.gz\": {\n        \"sha256\": \"0db2ee8ae8d63a6b070d6b949e988a784a792f3d8d4fa0868d9bb94fa993412d\",\n        \"size\": 195494670\n    },\n    \"ParkingCutIn_Town12_Route18310_Weather5.tar.gz\": {\n        \"sha256\": \"02515e294eea2e67a34f60c8650d85d1986e4740542ebd78da9f4be7e5ae3883\",\n        \"size\": 217556791\n    },\n    \"ParkingCutIn_Town12_Route18311_Weather6.tar.gz\": {\n        \"sha256\": \"640a5ea4c64c946288e4399a2e8c6e537db2ea5e08f97d265755b50e53afbc28\",\n        \"size\": 191589594\n    },\n    \"ParkingCutIn_Town12_Route18312_Weather7.tar.gz\": {\n        \"sha256\": \"4ca34a1bc76e596bfbb39478eea0a58366bb3de3635e7b7ad4cad9b5648ad8e6\",\n        \"size\": 222081821\n    },\n    \"ParkingCutIn_Town12_Route18313_Weather8.tar.gz\": {\n        \"sha256\": \"c85b9fed127709deb47eaa7353d273ea08860e2a91713027df59e3e261110429\",\n        \"size\": 181764060\n    },\n    \"ParkingCutIn_Town12_Route18314_Weather9.tar.gz\": {\n        \"sha256\": \"6891b491dc903557068b7178da4c1753a226c4fc48bf6ea40622d67715f39448\",\n        \"size\": 144216928\n    },\n    \"ParkingCutIn_Town12_Route18315_Weather10.tar.gz\": {\n        \"sha256\": \"88732ceac78ac35d24b653ce7eb5a2459fdf626add025316455d24c9e33390d4\",\n        \"size\": 196805398\n    },\n    \"ParkingCutIn_Town12_Route18316_Weather11.tar.gz\": {\n        \"sha256\": \"909bf47533f75a6dc94c896c3c05e291e45c245a859ad5cb456676eadd80db76\",\n        \"size\": 147561246\n    },\n    \"ParkingCutIn_Town12_Route18317_Weather12.tar.gz\": {\n        \"sha256\": \"4629562daed4a01c6b58b8c84e2b78a5a0309c86fbb000240cd3dc1dbe129b96\",\n        \"size\": 151956980\n    },\n    \"ParkingCutIn_Town12_Route18318_Weather13.tar.gz\": {\n        \"sha256\": \"fe9952c29c18a409ca00badf9de4f4b1bd0c72840e9bc95cf3b948c590e0e96e\",\n        \"size\": 142470268\n    },\n    \"ParkingCutIn_Town12_Route18319_Weather14.tar.gz\": {\n        \"sha256\": \"db8724f01abd41ca6b448efa127b20db0723d338b0fde3046a9917ad28f2dcb1\",\n        \"size\": 157582521\n    },\n    \"ParkingCutIn_Town12_Route18320_Weather15.tar.gz\": {\n        \"sha256\": \"75b8a54dd133a51d2d427e22e09b0b50d02fa9b4c4046f9dab7233de04abd9f9\",\n        \"size\": 173787098\n    },\n    \"ParkingCutIn_Town12_Route18321_Weather8.tar.gz\": {\n        \"sha256\": \"cb33b963725498128602fdd0ccbcb05932e7a4c5f49636db8ad30c29e5cf902f\",\n        \"size\": 195639338\n    },\n    \"ParkingCutIn_Town12_Route18322_Weather9.tar.gz\": {\n        \"sha256\": \"16cd772e823196567febc09fd1ad25e5d7b4f41676071e2a698d1eac69bf15cd\",\n        \"size\": 145246093\n    },\n    \"ParkingCutIn_Town12_Route18323_Weather18.tar.gz\": {\n        \"sha256\": \"8934753f9d70fb82fbace595a2a17b0079cc5007fb22dd2bfda8a7ee489931ff\",\n        \"size\": 212776940\n    },\n    \"ParkingCutIn_Town12_Route18324_Weather19.tar.gz\": {\n        \"sha256\": \"7ef90f6e416ce605867c72995eaa39fb6e5bab7e134b7cfd34a4bb059519f493\",\n        \"size\": 167681472\n    },\n    \"ParkingCutIn_Town12_Route18325_Weather20.tar.gz\": {\n        \"sha256\": \"985926c5adce57c25f9fc8a161bde18d937589679697f0d4dc5e8fb65847e518\",\n        \"size\": 171697636\n    },\n    \"ParkingCutIn_Town12_Route18326_Weather21.tar.gz\": {\n        \"sha256\": \"c645cb9f1ea4b8f267affba7cd9dc61bdcaa9368a15c40868db4836264d9c97d\",\n        \"size\": 175781329\n    },\n    \"ParkingCutIn_Town12_Route18327_Weather22.tar.gz\": {\n        \"sha256\": \"642d3cb463ff4330c930c735c550ed5aed1b71f058db5d36843cdd12a9406f9a\",\n        \"size\": 164270463\n    },\n    \"ParkingCutIn_Town12_Route18328_Weather23.tar.gz\": {\n        \"sha256\": \"66e837bafb823473c0eace289dd94f85a8d1f7bb6fc772a908efdf1899d3ef17\",\n        \"size\": 150122064\n    },\n    \"ParkingCutIn_Town12_Route18329_Weather23.tar.gz\": {\n        \"sha256\": \"7fc972fd7d92a60929c9e88e11dbb1e50415b3df769d74cdaf0e1eb85daa261d\",\n        \"size\": 168235099\n    },\n    \"ParkingCutIn_Town12_Route18330_Weather25.tar.gz\": {\n        \"sha256\": \"baa4bd204b4bb549128c85d8c50c167710c16491d51988d86d122bf730a27e45\",\n        \"size\": 150330929\n    },\n    \"ParkingCutIn_Town12_Route18331_Weather0.tar.gz\": {\n        \"sha256\": \"c9ed541892fb1a53f51330938cd5f547c98f0e50c86139be0bba784bdbd5ff34\",\n        \"size\": 208693280\n    },\n    \"ParkingCutIn_Town12_Route18332_Weather1.tar.gz\": {\n        \"sha256\": \"5924a5c130c6f2dd659c176b11c121eaefc53085e3212fe89e363aded2d62826\",\n        \"size\": 228528696\n    },\n    \"ParkingCutIn_Town12_Route18333_Weather2.tar.gz\": {\n        \"sha256\": \"a64bdaabd68bf6feb064dfeb1590e8fcae3a4eb442c2a5ea0da3896ce21d1745\",\n        \"size\": 197743573\n    },\n    \"ParkingCutIn_Town12_Route18334_Weather3.tar.gz\": {\n        \"sha256\": \"0bea23fab9ac3b0f5e3e0c94059e8842b7bfeebae6dc73fd598dfc100a1df27e\",\n        \"size\": 203392901\n    },\n    \"ParkingCutIn_Town12_Route18335_Weather3.tar.gz\": {\n        \"sha256\": \"8f782f2670b6de5b941c8dd9197e0963be32d3ead051d55e98c7c4b9cf2ea366\",\n        \"size\": 194494226\n    },\n    \"ParkingCutIn_Town12_Route18336_Weather5.tar.gz\": {\n        \"sha256\": \"85f076f3dd3d28c561342a2fb016847cbcec81da94d1f477cd11b8389549bff0\",\n        \"size\": 202782468\n    },\n    \"ParkingCutIn_Town12_Route18337_Weather6.tar.gz\": {\n        \"sha256\": \"f798a6ede4990db10262619de168b0a7979cfb0639ffbe529fc6b8930a1748ae\",\n        \"size\": 179001823\n    },\n    \"ParkingCutIn_Town12_Route18338_Weather7.tar.gz\": {\n        \"sha256\": \"06ecca2e384f6d0d75c5006c50a13a698a9b55da810e3c121ed5e2341880b50d\",\n        \"size\": 217617549\n    },\n    \"ParkingCutIn_Town12_Route18339_Weather8.tar.gz\": {\n        \"sha256\": \"b47793d7b7339ea6c2be53084f21d0171a91e35aa0fac5d12de8a9f7fcdc407c\",\n        \"size\": 191971697\n    },\n    \"ParkingCutIn_Town12_Route18340_Weather9.tar.gz\": {\n        \"sha256\": \"f659cd67fe54654f7b73e54c8197071e7692d9f7c4b78599208ecef221998be8\",\n        \"size\": 144787335\n    },\n    \"ParkingCutIn_Town12_Route18341_Weather10.tar.gz\": {\n        \"sha256\": \"256ad886144e136ceebcd1e2eb6e88daafcc383038641aeddca1fd7713d0e0de\",\n        \"size\": 184953812\n    },\n    \"ParkingCutIn_Town12_Route18342_Weather11.tar.gz\": {\n        \"sha256\": \"db70f5bdee7376384513d1a0228c7823e84bc0604ba30f3896636c177dc87ac8\",\n        \"size\": 146733793\n    },\n    \"ParkingCutIn_Town12_Route18343_Weather12.tar.gz\": {\n        \"sha256\": \"22a3c4dcef221c1f695a796dd0913a6287cd0372d013fbf52ee5fbb60c7110a7\",\n        \"size\": 152902494\n    },\n    \"ParkingCutIn_Town12_Route18344_Weather13.tar.gz\": {\n        \"sha256\": \"686625971c75ddd8be81237ba1003f0b7210a845ef68d52098573bf492f48d2e\",\n        \"size\": 164864113\n    },\n    \"ParkingCutIn_Town12_Route18345_Weather14.tar.gz\": {\n        \"sha256\": \"7bb3c1a4ea90b86aa5a101b87c3c1fd09bf8af69bcee1587ccd60bfec366637e\",\n        \"size\": 158606101\n    },\n    \"ParkingCutIn_Town12_Route18346_Weather15.tar.gz\": {\n        \"sha256\": \"7ea0fdb209e7a89700df708eaf0cc9ae5e2cde0d984981a6d3de0f2d1ed0ce90\",\n        \"size\": 175396530\n    },\n    \"ParkingCutIn_Town12_Route18347_Weather8.tar.gz\": {\n        \"sha256\": \"7b7374ee792ef5db968f106e3a6563da5bfaaf3145813f241b534ca03715b875\",\n        \"size\": 159418577\n    },\n    \"ParkingCutIn_Town12_Route18348_Weather9.tar.gz\": {\n        \"sha256\": \"80880ebce89c94ecc7bf4be3835e7c259e3c905a5f5797e9b813dbfcffc76756\",\n        \"size\": 146105222\n    },\n    \"ParkingCutIn_Town12_Route18349_Weather18.tar.gz\": {\n        \"sha256\": \"599345b4727a1d29f0b96dc7373cf817e0bf596882183116780fca968324a549\",\n        \"size\": 214190698\n    },\n    \"ParkingCutIn_Town12_Route18350_Weather19.tar.gz\": {\n        \"sha256\": \"0534257e846ef04a11c9d3f960dcdb0cfdfc7d2629cf3d351a25b245bde6929a\",\n        \"size\": 176718435\n    },\n    \"ParkingCutIn_Town12_Route18351_Weather20.tar.gz\": {\n        \"sha256\": \"711e5393d19fbd069771c019e744923fc2deed1c475b5d334e8ca290af2070e8\",\n        \"size\": 183039514\n    },\n    \"ParkingCutIn_Town12_Route18352_Weather21.tar.gz\": {\n        \"sha256\": \"d7d2ee578a47aee1bf4bb920161d101ff983d081335a240d6eb125cc0b3bf779\",\n        \"size\": 200928909\n    },\n    \"ParkingCutIn_Town12_Route18353_Weather22.tar.gz\": {\n        \"sha256\": \"227a9b1b89a15dee445c334087d5fbc486b00fe2820b83d16695448f1476aa4d\",\n        \"size\": 175981350\n    },\n    \"ParkingCutIn_Town12_Route18354_Weather23.tar.gz\": {\n        \"sha256\": \"8fa7abffb6a108841656a917098c179e621682ac04ed53bb41a6b2f3176563c2\",\n        \"size\": 156331679\n    },\n    \"ParkingCutIn_Town12_Route18355_Weather23.tar.gz\": {\n        \"sha256\": \"78fd3fec3ee6bd076152b8b7f1a9643293ba5360f8ecda57e2a6e1bfcb80d645\",\n        \"size\": 152972507\n    },\n    \"ParkingCutIn_Town12_Route18356_Weather25.tar.gz\": {\n        \"sha256\": \"68c53d03220639a98514eaf9e53a543133bff917ee47ee6aa47d8dd155e81daf\",\n        \"size\": 155008853\n    },\n    \"ParkingCutIn_Town12_Route18357_Weather0.tar.gz\": {\n        \"sha256\": \"4a7058f7906fb2eb599ebbb523ea975408f2a6a662cfa536b136fc37a18bb483\",\n        \"size\": 204908499\n    },\n    \"ParkingCutIn_Town12_Route18358_Weather1.tar.gz\": {\n        \"sha256\": \"6787722cf231426058904788fb9fbb501acc945067832c7f40f668ed694991f6\",\n        \"size\": 216110940\n    },\n    \"ParkingCutIn_Town12_Route18359_Weather2.tar.gz\": {\n        \"sha256\": \"498e868241b559f81070d2be04a5de9eb272dc78b2a3270a2fa54bd7c2e4cb81\",\n        \"size\": 190557852\n    },\n    \"ParkingCutIn_Town12_Route18360_Weather3.tar.gz\": {\n        \"sha256\": \"11edb4da4ff2816462a82bb148f60e635f82530b2e02aa20cef6315a1d0152c5\",\n        \"size\": 203284732\n    },\n    \"ParkingCutIn_Town12_Route18361_Weather3.tar.gz\": {\n        \"sha256\": \"65339d886d19c1796137ba84904d0bb46d604c51b6336e1ceadaf8a218c959ec\",\n        \"size\": 194897553\n    },\n    \"ParkingCutIn_Town12_Route18362_Weather5.tar.gz\": {\n        \"sha256\": \"bf930a91e2e8228ec778638be8b7539a924dc130f7134afe3e402e4f5d220972\",\n        \"size\": 185707861\n    },\n    \"ParkingCutIn_Town12_Route18363_Weather6.tar.gz\": {\n        \"sha256\": \"480025428335f2bd81011e6b00ada5905dcaa6aff6b6d69004034158abc07e33\",\n        \"size\": 197191184\n    },\n    \"ParkingCutIn_Town12_Route18364_Weather7.tar.gz\": {\n        \"sha256\": \"28912ee2754e1ebb8e20c0b876d591601772c2e186f9b50998f0a99081318ecc\",\n        \"size\": 222139168\n    },\n    \"ParkingCutIn_Town12_Route18365_Weather8.tar.gz\": {\n        \"sha256\": \"4f1b3cd9ccafff240424127e3cda5bd8fa0d8563b9cfae306ec7521788e27713\",\n        \"size\": 207262904\n    },\n    \"ParkingCutIn_Town12_Route18366_Weather9.tar.gz\": {\n        \"sha256\": \"766d23d6d5b157fbf1837557db9bb66a4ab533006def44d6ba809625290593c9\",\n        \"size\": 141922641\n    },\n    \"ParkingCutIn_Town12_Route18367_Weather10.tar.gz\": {\n        \"sha256\": \"14ed10f0f705fea9056937c9831e2382cc7535c039983df25643c41912ce6f70\",\n        \"size\": 183998769\n    },\n    \"ParkingCutIn_Town12_Route18368_Weather11.tar.gz\": {\n        \"sha256\": \"aecb8ddce7b5b0cc978b1bcef56d612dd192a226ff864080b5f37f3c0feb8dca\",\n        \"size\": 153320207\n    },\n    \"ParkingCutIn_Town12_Route18369_Weather12.tar.gz\": {\n        \"sha256\": \"535c9d23065d80720d132ed088426bd74ac3452778655f6690bf4c965adc830c\",\n        \"size\": 160382829\n    },\n    \"ParkingCutIn_Town12_Route18370_Weather13.tar.gz\": {\n        \"sha256\": \"c697279c2ba65867ba1ef642337d84f4dfb4e1908d95a1e13808be031f2dd0fe\",\n        \"size\": 145649761\n    },\n    \"ParkingCutIn_Town12_Route18371_Weather14.tar.gz\": {\n        \"sha256\": \"bd4df1b69e5a01b9e582bddf5d32e04d162258adb08a6e0fa1564eb07d9b5a1d\",\n        \"size\": 159995316\n    },\n    \"ParkingCutIn_Town12_Route18372_Weather15.tar.gz\": {\n        \"sha256\": \"9e6ffad2e174b7dd48d27d8a38725eb41d5198a4cd3c7891a5fb1f3a5331b5de\",\n        \"size\": 191469413\n    },\n    \"ParkingCutIn_Town12_Route2484_Weather8.tar.gz\": {\n        \"sha256\": \"c6bfd442231be39437f6f27f497801da3f671a77628ed7ff9141c50f67007639\",\n        \"size\": 215806794\n    },\n    \"ParkingCutIn_Town12_Route2485_Weather9.tar.gz\": {\n        \"sha256\": \"34759634e70e7f5f80866829a5758ceb9f9ba2b6bc501ab75e6d1c9725ab31f7\",\n        \"size\": 151593488\n    },\n    \"ParkingCutIn_Town12_Route2486_Weather10.tar.gz\": {\n        \"sha256\": \"2f3a195464e35ced8e94b8da805b0dda2c22d038ea51724444fbbb1c2077f2cb\",\n        \"size\": 175303127\n    },\n    \"ParkingCutIn_Town12_Route2487_Weather11.tar.gz\": {\n        \"sha256\": \"ca03dfa553754e468ec7a7e4b8ee843b975c95d5233cc47aa98f8f455b74d81d\",\n        \"size\": 151413992\n    },\n    \"ParkingCutIn_Town12_Route2488_Weather12.tar.gz\": {\n        \"sha256\": \"2799b25bf374e7590881bfeb396634c6a752005f4273b28a95f8c9461af5856a\",\n        \"size\": 121768939\n    },\n    \"ParkingCutIn_Town12_Route2489_Weather13.tar.gz\": {\n        \"sha256\": \"69bb9fb1abdb2a95a76b5e0ea138db79daf5355188e872bd686b6549e936cc29\",\n        \"size\": 152125572\n    },\n    \"ParkingCutIn_Town12_Route2490_Weather14.tar.gz\": {\n        \"sha256\": \"19a314c909d0df3986747a4b6358fa934088542819108866f8f636c9f902ac07\",\n        \"size\": 186194200\n    },\n    \"ParkingCutIn_Town12_Route2491_Weather15.tar.gz\": {\n        \"sha256\": \"4806f92bda21d2e84143b5b83f7572d790edf2250e1a59a353e770878a5ab97d\",\n        \"size\": 192457117\n    },\n    \"ParkingCutIn_Town12_Route2492_Weather8.tar.gz\": {\n        \"sha256\": \"abddc99b12d1e8a6e09f57131f9a2ec37134d56ad20789ba081cac6b1c329253\",\n        \"size\": 200599251\n    },\n    \"ParkingCutIn_Town12_Route2493_Weather9.tar.gz\": {\n        \"sha256\": \"1c6fbb6beff08177d7de0d2ad0bb5b569c36279c9456e327d592b3ec9cc76167\",\n        \"size\": 140640892\n    },\n    \"ParkingCutIn_Town12_Route2494_Weather18.tar.gz\": {\n        \"sha256\": \"bde57b6197bd2de69610fdec397bfdad9161e6c32600274ee46eef9ef12a0377\",\n        \"size\": 215568865\n    },\n    \"ParkingCutIn_Town12_Route2495_Weather19.tar.gz\": {\n        \"sha256\": \"bf40c84ef16b3a4f98a5491057b6982298d4d347ba83299ce30d1ac221d8c79a\",\n        \"size\": 186871969\n    },\n    \"ParkingCutIn_Town12_Route2496_Weather20.tar.gz\": {\n        \"sha256\": \"9359de26fff8cfef4133be29570c6b218fb165442c23bedfa9c0e61e52f728a4\",\n        \"size\": 187530951\n    },\n    \"ParkingCutIn_Town12_Route2497_Weather21.tar.gz\": {\n        \"sha256\": \"e524ecb84c2264088cfba4d33b6c0085ab92b5f697e4e009353d2d1c7dfef4fc\",\n        \"size\": 174422028\n    },\n    \"ParkingCutIn_Town12_Route2498_Weather22.tar.gz\": {\n        \"sha256\": \"0aca5ca0abf1799290b9fde8b89f0eb5c496aca98d2d08477f074c8cc204af4d\",\n        \"size\": 174078717\n    },\n    \"ParkingCutIn_Town12_Route2499_Weather23.tar.gz\": {\n        \"sha256\": \"42661e99c617f9df78122fd0df249cba03ab47fbb70d27c4f52c3eaecb6072ab\",\n        \"size\": 169794736\n    },\n    \"ParkingCutIn_Town12_Route2500_Weather23.tar.gz\": {\n        \"sha256\": \"9b41cdb9846505986bc1ac89e8815491f2465bafad9390e7464a65a3b25002ce\",\n        \"size\": 150734982\n    },\n    \"ParkingCutIn_Town12_Route2501_Weather25.tar.gz\": {\n        \"sha256\": \"5975c51e6b493af3dd5f42bc41c5129ac2b9d7d3f862df7778ef64450ef7a1a4\",\n        \"size\": 153739602\n    },\n    \"ParkingCutIn_Town12_Route2502_Weather0.tar.gz\": {\n        \"sha256\": \"47d27bf45077e20a6897334bee0ac178df6ea43c1a4b4665279ed7dc91ca7df9\",\n        \"size\": 224497276\n    },\n    \"ParkingCutIn_Town12_Route2503_Weather1.tar.gz\": {\n        \"sha256\": \"5acdcd5da420ae5921647bbc12552fe0fdff7f7f94962eb11b42043c0be72c41\",\n        \"size\": 210963678\n    },\n    \"ParkingCutIn_Town13_Route3263_Weather8.tar.gz\": {\n        \"sha256\": \"e011efc2123147bfc190e98d827266636f161ae1dbfe23e3b66c6b2ddaf52135\",\n        \"size\": 332044312\n    },\n    \"ParkingCutIn_Town13_Route3265_Weather10.tar.gz\": {\n        \"sha256\": \"1e4a0ee2022105ead14b70d1af44ab9e808fbb9bb8ee4988b60b1e8f2e25bea1\",\n        \"size\": 201222046\n    },\n    \"ParkingCutIn_Town13_Route3266_Weather11.tar.gz\": {\n        \"sha256\": \"40e45fe680b68542ed807c92a6eab52e33b7f60deb8a3fb619bfa93191aed669\",\n        \"size\": 386621111\n    },\n    \"ParkingCutIn_Town13_Route3267_Weather12.tar.gz\": {\n        \"sha256\": \"0e11db7577045fd723d4fbae0de3035b467653a33aba3f587292e511d4c6e099\",\n        \"size\": 176894156\n    },\n    \"ParkingCutIn_Town13_Route3268_Weather13.tar.gz\": {\n        \"sha256\": \"7384515e105a43569659b42aad40e96881e4ee8c1281f6f0a62a23a9e360a97e\",\n        \"size\": 236012741\n    },\n    \"ParkingCutIn_Town13_Route3269_Weather14.tar.gz\": {\n        \"sha256\": \"1067f6812393b7e0060d64fc0d59060faa4d6281891dac5c50260a16686afdab\",\n        \"size\": 638830540\n    },\n    \"ParkingCutIn_Town13_Route3270_Weather15.tar.gz\": {\n        \"sha256\": \"585c0cde5231331d5869fbdc61979c0ae2e91862bf0777303e505aacf6703e6f\",\n        \"size\": 321411120\n    },\n    \"ParkingCutIn_Town13_Route3271_Weather8.tar.gz\": {\n        \"sha256\": \"831c462868a6558d3d02dfa01dbd45b395897b7a836eeb8d6f4f2edee8cf0030\",\n        \"size\": 208831449\n    },\n    \"ParkingCutIn_Town13_Route3272_Weather9.tar.gz\": {\n        \"sha256\": \"979bf4622034fc1f473155e39de454b864ec5e1823532efe412eea7a4525d71f\",\n        \"size\": 348365541\n    },\n    \"ParkingCutIn_Town13_Route3273_Weather18.tar.gz\": {\n        \"sha256\": \"7e8a23bea03c9f1095901e3cdb40ea5c83d6b3c05e9530f76bf8edd8e1a74647\",\n        \"size\": 209601732\n    },\n    \"ParkingCutIn_Town13_Route3274_Weather19.tar.gz\": {\n        \"sha256\": \"44d70af73e8be21117073fb4c72d746f592475483dc95c837521077c9c680cbb\",\n        \"size\": 508783593\n    },\n    \"ParkingCutIn_Town13_Route3275_Weather20.tar.gz\": {\n        \"sha256\": \"7f091cd0c727edd217ef3325b9c3dd70a11c996854c9909d0aa7ac5bd43ae22e\",\n        \"size\": 187004900\n    },\n    \"ParkingCutIn_Town13_Route3276_Weather21.tar.gz\": {\n        \"sha256\": \"943a203b708d98f09aaa4defd8663ed4fe408df1355d3b1ff1c7be234086c101\",\n        \"size\": 342009005\n    },\n    \"ParkingCutIn_Town13_Route3277_Weather22.tar.gz\": {\n        \"sha256\": \"075b3e055673ad2bccb011fcda97dcf8e664d2dac81fd82729312d57dfbc5b1a\",\n        \"size\": 349019421\n    },\n    \"ParkingCutIn_Town13_Route3278_Weather23.tar.gz\": {\n        \"sha256\": \"bb45ef0326fd75393149c810a03c50f260c5122d185caefdfe65d4450565443a\",\n        \"size\": 168907215\n    },\n    \"ParkingCutIn_Town13_Route3279_Weather23.tar.gz\": {\n        \"sha256\": \"0adc1e62e2e4c8186cc8bf77e79a02ba38a490a5a7451ff57f9d76663e70390b\",\n        \"size\": 560536842\n    },\n    \"ParkingCutIn_Town13_Route3280_Weather25.tar.gz\": {\n        \"sha256\": \"07b52f7e568488f840acf66c744dc4e2e544dc9c759095a3df5f02e4ed91e236\",\n        \"size\": 174975550\n    },\n    \"ParkingCutIn_Town13_Route3281_Weather0.tar.gz\": {\n        \"sha256\": \"298d5e7523982792d2755a10d3ab0c5f8e7908aeb615f9b2ce79644c652ba104\",\n        \"size\": 216247983\n    },\n    \"ParkingCutIn_Town13_Route3282_Weather1.tar.gz\": {\n        \"sha256\": \"a8a3016649d34149066ea827d117365f74d12071d0c04e6bc83b3256bcf97376\",\n        \"size\": 233051486\n    },\n    \"ParkingExit_Town03_Route26393_Weather12.tar.gz\": {\n        \"sha256\": \"cb578df2938621c2b3b9c6358b9340d9bcd6eebb2cde7b40b86d8f0690da3a99\",\n        \"size\": 312221458\n    },\n    \"ParkingExit_Town03_Route26400_Weather21.tar.gz\": {\n        \"sha256\": \"0b497b550321c92e93e8888f8d9d42d15db9046b3f6c5ed3626e166df6dd0e82\",\n        \"size\": 274855444\n    },\n    \"ParkingExit_Town03_Route26414_Weather10.tar.gz\": {\n        \"sha256\": \"01bd31106d506ad16528d4aa9d5ccf8eefb92481f9029dd2a2d4c0a4bb895529\",\n        \"size\": 333481355\n    },\n    \"ParkingExit_Town03_Route26428_Weather0.tar.gz\": {\n        \"sha256\": \"4e948a4376c4bf15f22ac3d6b20843a4781d5dca35ea2531bf3c7b6467f4b8ab\",\n        \"size\": 394013953\n    },\n    \"ParkingExit_Town03_Route26435_Weather8.tar.gz\": {\n        \"sha256\": \"740de156c1c1f5f812ff96ea13f3b7cd92ba41cc76571414171bbf91c2b712f8\",\n        \"size\": 380023662\n    },\n    \"ParkingExit_Town05_Route26499_Weather2.tar.gz\": {\n        \"sha256\": \"2eaf70d9d1945ee30abe74ffe31b1fb336edc1b5319e716c721dce0a9ad991bf\",\n        \"size\": 267339516\n    },\n    \"ParkingExit_Town05_Route26511_Weather15.tar.gz\": {\n        \"sha256\": \"d9184d568783bc195c99a1a3e7f6dd032e0148af65a1911373a87857f65521d0\",\n        \"size\": 243744313\n    },\n    \"ParkingExit_Town05_Route26523_Weather3.tar.gz\": {\n        \"sha256\": \"dcee162c4eb0e0e05c9a4b12dbd8e76f0dd30a14d8ce3347c9d6ea075c55f91b\",\n        \"size\": 1616991258\n    },\n    \"ParkingExit_Town05_Route26551_Weather9.tar.gz\": {\n        \"sha256\": \"eb798f98ee1f2c4c76f86d038fa34cc340146915bfc01b5e0bb8e9be648cd0c6\",\n        \"size\": 259566413\n    },\n    \"ParkingExit_Town05_Route26561_Weather21.tar.gz\": {\n        \"sha256\": \"ffa8076d750873ab0f3985a6aa50d32369a7aa46ce44d9fb6e1a8d6e277f87a8\",\n        \"size\": 252141915\n    },\n    \"ParkingExit_Town05_Route26566_Weather0.tar.gz\": {\n        \"sha256\": \"048abf30389edfc84204e97419cd80aadb094232899ff066a116bbc750bf3c07\",\n        \"size\": 334057730\n    },\n    \"ParkingExit_Town12_Route1944_Weather14.tar.gz\": {\n        \"sha256\": \"0de54f09e05265a9aead2f188e1abeafd931c112742feddc4db4ec64e9467274\",\n        \"size\": 174399311\n    },\n    \"ParkingExit_Town12_Route1948_Weather18.tar.gz\": {\n        \"sha256\": \"16b8b583e1123e7f5884caa0a6d729638b13126732844d0600937982f1614e4f\",\n        \"size\": 196844722\n    },\n    \"ParkingExit_Town12_Route1949_Weather19.tar.gz\": {\n        \"sha256\": \"24e288a776f34f4f6a848179ea866a669747e88786bf69bf65f196daba2b57d4\",\n        \"size\": 204677033\n    },\n    \"ParkingExit_Town12_Route1951_Weather21.tar.gz\": {\n        \"sha256\": \"7ccc99c28b1d90ee2e931c5a542379a5153d45b679cff5ef03f6426aa8feda76\",\n        \"size\": 173592441\n    },\n    \"ParkingExit_Town12_Route1952_Weather22.tar.gz\": {\n        \"sha256\": \"75ce10806cdf9c349e887999dfa024a4cf3431e6e48f43455f01cfec14ded491\",\n        \"size\": 189250723\n    },\n    \"ParkingExit_Town12_Route1954_Weather23.tar.gz\": {\n        \"sha256\": \"6a1c4a10246e90faada6f4a80b93a19ec76cb6c9924b42e21c078c35f03772e3\",\n        \"size\": 150716734\n    },\n    \"ParkingExit_Town12_Route1955_Weather25.tar.gz\": {\n        \"sha256\": \"4c631eea644c2874fd84d6a2c43dad18f84b31fa5210bdcddc5f4c17e0ba1f31\",\n        \"size\": 117908794\n    },\n    \"ParkingExit_Town12_Route1956_Weather0.tar.gz\": {\n        \"sha256\": \"741fb7c182c562e130b9ab0d1867cbdc1d124eac6369af7328d761311e512f31\",\n        \"size\": 219782464\n    },\n    \"ParkingExit_Town12_Route1957_Weather1.tar.gz\": {\n        \"sha256\": \"46f44e6fcac473e97d68063e689931dd30ba4c811133ad8d3fc1bd84b1461f77\",\n        \"size\": 214425660\n    },\n    \"ParkingExit_Town12_Route1959_Weather3.tar.gz\": {\n        \"sha256\": \"981c7734b27f74a7db4496e0392083c5328ad8f96eb761c46827d8f12fc37fc6\",\n        \"size\": 189649472\n    },\n    \"ParkingExit_Town12_Route1960_Weather3.tar.gz\": {\n        \"sha256\": \"2e7324546cc0f38a948dba03a466da4e822612a990f67e22c7d9f604280862b3\",\n        \"size\": 195433645\n    },\n    \"ParkingExit_Town12_Route1961_Weather5.tar.gz\": {\n        \"sha256\": \"c0f3cdbc95225083fd77de0606178df985191891366aa9895ae12ced68bf011a\",\n        \"size\": 185869775\n    },\n    \"ParkingExit_Town12_Route1963_Weather7.tar.gz\": {\n        \"sha256\": \"9ec5cc024a8e37caaf4e97f7146ac7b65e82316565ee02a61b9f5147252b2cf9\",\n        \"size\": 227074129\n    },\n    \"ParkingExit_Town12_Route22553_Weather10.tar.gz\": {\n        \"sha256\": \"b673c7b94c70619fafcc8aef975e9378ef95f51548fbb06bdd62de65523b36a8\",\n        \"size\": 181802473\n    },\n    \"ParkingExit_Town12_Route22555_Weather12.tar.gz\": {\n        \"sha256\": \"1fefd4c50d7ad5e88395add930ad74751b1725f09a8b5e0057b71160ac15d31d\",\n        \"size\": 151072759\n    },\n    \"ParkingExit_Town12_Route22556_Weather13.tar.gz\": {\n        \"sha256\": \"e95a7a26fde063547ecc90bf4240c3527239ac8315903c3694d869ab4063c03c\",\n        \"size\": 148594640\n    },\n    \"ParkingExit_Town12_Route22558_Weather15.tar.gz\": {\n        \"sha256\": \"5143a305424e517bfa6c4ada50c2d49ab62655136b7ae240a5650f19d7a47b63\",\n        \"size\": 169130606\n    },\n    \"ParkingExit_Town12_Route22559_Weather8.tar.gz\": {\n        \"sha256\": \"dd19fed4bb9f4a6979226934c4191296c0e07ad02ba471c4b638ab852b5c623b\",\n        \"size\": 178842926\n    },\n    \"ParkingExit_Town12_Route22561_Weather18.tar.gz\": {\n        \"sha256\": \"2e87c2be4077d3fbe20e20da7981c7fc45b8883f6c88334b3043245bf1fe32ea\",\n        \"size\": 173938820\n    },\n    \"ParkingExit_Town12_Route22562_Weather19.tar.gz\": {\n        \"sha256\": \"f10d9e66c4627d37c141ccf2399d81df4b1869e819316dfb6b0331c7be7c10d9\",\n        \"size\": 170059439\n    },\n    \"ParkingExit_Town12_Route22563_Weather20.tar.gz\": {\n        \"sha256\": \"120aa855759a0f186c5b0e06ed231697f3c19262c6efebc5a70d8caf7c10edca\",\n        \"size\": 172826233\n    },\n    \"ParkingExit_Town12_Route22564_Weather21.tar.gz\": {\n        \"sha256\": \"9e9323875eb697fa439cddf1687c8dd92c9fc76ec3193d69be1d9c8d78c6a786\",\n        \"size\": 171519749\n    },\n    \"ParkingExit_Town12_Route22565_Weather22.tar.gz\": {\n        \"sha256\": \"d0dd9f47ffab011552860508285a8f5e242a9c8af76ee2c6797ef35694d0faf0\",\n        \"size\": 166868745\n    },\n    \"ParkingExit_Town12_Route22566_Weather23.tar.gz\": {\n        \"sha256\": \"2a1fae8ebd8c4b047504e1f4d9b99116630d836c1e36624a0f12fe5db97d4940\",\n        \"size\": 157814434\n    },\n    \"ParkingExit_Town12_Route22567_Weather23.tar.gz\": {\n        \"sha256\": \"0d8e88a441e7ba86e6a31116c323c669774edcb6f7a6379a255484f822424432\",\n        \"size\": 151608752\n    },\n    \"ParkingExit_Town12_Route22569_Weather0.tar.gz\": {\n        \"sha256\": \"c0c55df24dc322f8237c821b93c7c4ce2c2a5803112f8c71192ced1d5be969f2\",\n        \"size\": 183317027\n    },\n    \"ParkingExit_Town12_Route22571_Weather2.tar.gz\": {\n        \"sha256\": \"4e8e08f31c063c98dc6929698460a68e0c973fd79714caeb58362cd87ec624bb\",\n        \"size\": 184669756\n    },\n    \"ParkingExit_Town12_Route22572_Weather3.tar.gz\": {\n        \"sha256\": \"8e7fd1ad7639388e967f976a0a22cc6998c88b4707d3a8f6f1eeba6e4e988422\",\n        \"size\": 199943352\n    },\n    \"ParkingExit_Town12_Route22573_Weather3.tar.gz\": {\n        \"sha256\": \"515f6ca1b25465160d781eef5977c29512d9e17837f6df44d4ec36c5cde9736c\",\n        \"size\": 178335998\n    },\n    \"ParkingExit_Town12_Route22574_Weather5.tar.gz\": {\n        \"sha256\": \"2e2af35d062f5a1d7c3df5db9f8647d6eb74771a4c197e3076e26dc66ce30938\",\n        \"size\": 176817577\n    },\n    \"ParkingExit_Town12_Route22575_Weather6.tar.gz\": {\n        \"sha256\": \"c90a6f03132a2b16cb0c45084041114428e64b40fda3e73a9c085f8cf54486ce\",\n        \"size\": 172873553\n    },\n    \"ParkingExit_Town12_Route22576_Weather7.tar.gz\": {\n        \"sha256\": \"a02a8fbc9782dff2b3bed7dac3eb454a16f11844f2c3bd58339ef3cffd110c37\",\n        \"size\": 183022717\n    },\n    \"ParkingExit_Town12_Route22577_Weather8.tar.gz\": {\n        \"sha256\": \"91a11c0bc698ee090c1276cc8f4dbb9ba97c3fedeb3f5491e5742f508e5819c7\",\n        \"size\": 180068417\n    },\n    \"ParkingExit_Town12_Route22578_Weather9.tar.gz\": {\n        \"sha256\": \"85bb0ac76a411fa9d8c48bbf731e5922c3510673e5c835974d03fce9a919313d\",\n        \"size\": 134975381\n    },\n    \"ParkingExit_Town12_Route22579_Weather10.tar.gz\": {\n        \"sha256\": \"2395c56051bd5c736dd842277a9f14df28b9b3a590df3863c9923a3cba7443f5\",\n        \"size\": 166826563\n    },\n    \"ParkingExit_Town12_Route22580_Weather11.tar.gz\": {\n        \"sha256\": \"02320bcc74f84b8474c0eeea6fee59610b45843ff2b05a8932c8b4d94b102110\",\n        \"size\": 140675793\n    },\n    \"ParkingExit_Town12_Route22581_Weather12.tar.gz\": {\n        \"sha256\": \"2d11720b36b6b567fa0fd1b38ab5c06c8c2defd66e68d1a816201e45e8e58584\",\n        \"size\": 143238809\n    },\n    \"ParkingExit_Town12_Route22582_Weather13.tar.gz\": {\n        \"sha256\": \"910d9bfba742d69937428ac290f8ae5a8a29ceda53cc39b1365ebbc8bd35e842\",\n        \"size\": 146831629\n    },\n    \"ParkingExit_Town12_Route22585_Weather8.tar.gz\": {\n        \"sha256\": \"2bb15e3421f2747066f70a2e59d059cbedab6c71ce269fa80f50b954dcfb1077\",\n        \"size\": 169524121\n    },\n    \"ParkingExit_Town12_Route22586_Weather9.tar.gz\": {\n        \"sha256\": \"3e0fb4eaabd7f873d42638c81ece4d46d103a1f0b08c30edb5592ee3e611b1c0\",\n        \"size\": 145448444\n    },\n    \"ParkingExit_Town12_Route22587_Weather18.tar.gz\": {\n        \"sha256\": \"e218e9c430c1798061be8fecdf53301f7ba62c6e23d9bc6c575ec1a708859dce\",\n        \"size\": 181050704\n    },\n    \"ParkingExit_Town12_Route22588_Weather19.tar.gz\": {\n        \"sha256\": \"04b69d88bcf92a200a7ebcb3a0daa2103d19f65302c9310c5535aa5c69074d85\",\n        \"size\": 174098921\n    },\n    \"ParkingExit_Town12_Route22589_Weather20.tar.gz\": {\n        \"sha256\": \"ab2df85e1188df9dfd8b0c6fc864641a078b97215e82547644600b7fb53d5260\",\n        \"size\": 183818712\n    },\n    \"ParkingExit_Town12_Route22590_Weather21.tar.gz\": {\n        \"sha256\": \"50ab9251035e5ad7ccf62d09e832e4fa2b098ef0043a64e15ca351d0644a352e\",\n        \"size\": 163318947\n    },\n    \"ParkingExit_Town12_Route22591_Weather22.tar.gz\": {\n        \"sha256\": \"b293e9485d3eead67977299fae1db83122eb904d7c3bac6187ff1a07e24062b4\",\n        \"size\": 164313325\n    },\n    \"ParkingExit_Town12_Route22593_Weather23.tar.gz\": {\n        \"sha256\": \"0c33cc433eb652589d56dfb15201c92e8764a9f98d144aa89a5e44725862343e\",\n        \"size\": 144309405\n    },\n    \"ParkingExit_Town12_Route22594_Weather25.tar.gz\": {\n        \"sha256\": \"0fdcc444df74fced19eff38490e8cf96f266c6c28a2e699ba1f6aaf2d8ed2cbd\",\n        \"size\": 142354943\n    },\n    \"ParkingExit_Town12_Route22595_Weather0.tar.gz\": {\n        \"sha256\": \"8476c3b5f754717ada713567fa69891cbd481bf03ac728c0ad93336546f4e723\",\n        \"size\": 181572864\n    },\n    \"ParkingExit_Town12_Route22596_Weather1.tar.gz\": {\n        \"sha256\": \"7bbec0add2f8ea5cfbe569476086f79a53abb6458eef24d0d6c48686ddd61c1c\",\n        \"size\": 185582972\n    },\n    \"ParkingExit_Town12_Route22597_Weather2.tar.gz\": {\n        \"sha256\": \"d6d6a882e79d55d25c9d6ec499131cad5942793f093904850c54d85cdcc199a3\",\n        \"size\": 181108991\n    },\n    \"ParkingExit_Town12_Route22598_Weather3.tar.gz\": {\n        \"sha256\": \"f5efaaddab1ee8e6092ffc235e719e1a07c6b46327a3d8b40aa2289c03f97977\",\n        \"size\": 187820748\n    },\n    \"ParkingExit_Town12_Route22599_Weather3.tar.gz\": {\n        \"sha256\": \"922507367d2a5af98e55e8eb5894e1eac9e033fe768bd2a27eb99dfc98c7c7d8\",\n        \"size\": 190997194\n    },\n    \"ParkingExit_Town12_Route22600_Weather5.tar.gz\": {\n        \"sha256\": \"33238a6376154b519196de7450464073493255939d3fe9cfc6c457a1c6343edb\",\n        \"size\": 177905139\n    },\n    \"ParkingExit_Town12_Route22601_Weather6.tar.gz\": {\n        \"sha256\": \"7d337c32ce6a86f3bc9688250087f5fe51ae68a9c727e06969c87240a0b11826\",\n        \"size\": 173156160\n    },\n    \"ParkingExit_Town12_Route22602_Weather7.tar.gz\": {\n        \"sha256\": \"b169ebe8ce9ea686e05236c7e18a6fb7d4a3ba637afd37f7bbe47bda65ac5478\",\n        \"size\": 192269997\n    },\n    \"ParkingExit_Town12_Route22603_Weather8.tar.gz\": {\n        \"sha256\": \"10bc29bd492f5672bfc888c11eb40eff66641fe5617f28ab1187ed379267d68e\",\n        \"size\": 183102348\n    },\n    \"ParkingExit_Town12_Route22604_Weather9.tar.gz\": {\n        \"sha256\": \"b96b64dd48976726a9e54a634cba0e7eb38b3b5a2dd3fd3c87ec9a58d314eaa3\",\n        \"size\": 157327577\n    },\n    \"ParkingExit_Town12_Route22605_Weather10.tar.gz\": {\n        \"sha256\": \"f520dc282162115e7e3914cae611d0e3ae14ba327304a1eb9d5aed873d54f1b4\",\n        \"size\": 169238122\n    },\n    \"ParkingExit_Town12_Route22606_Weather11.tar.gz\": {\n        \"sha256\": \"f8fc058fd801619fb3b74555b8398974c336aa661751a25b64fe3f8a22f22349\",\n        \"size\": 143774414\n    },\n    \"ParkingExit_Town12_Route22607_Weather12.tar.gz\": {\n        \"sha256\": \"6da347f424b2f612c6d00688dd374c7d8805f92cbccc87285fdb76eb150d33e8\",\n        \"size\": 111174656\n    },\n    \"ParkingExit_Town12_Route22608_Weather13.tar.gz\": {\n        \"sha256\": \"1108bd00529cd086b7fd9fa0f6c9238f2995f1b00869a8cc5fc212ecf45a8c13\",\n        \"size\": 146966982\n    },\n    \"ParkingExit_Town12_Route22609_Weather14.tar.gz\": {\n        \"sha256\": \"825175fc3ee8f5d40d3d4837533152c608053a71104354f32cb57d101043b721\",\n        \"size\": 162660749\n    },\n    \"ParkingExit_Town12_Route22611_Weather8.tar.gz\": {\n        \"sha256\": \"46bee26121bcce44672ee94747caab28a9bcc8e8c2132ef6cb6e0e5e055c74b9\",\n        \"size\": 174624798\n    },\n    \"ParkingExit_Town12_Route22613_Weather18.tar.gz\": {\n        \"sha256\": \"3b0d2ed1c939795e96b5ace30ca3673fc0e24f60d41a385fa144d8c5be90bcc0\",\n        \"size\": 197939934\n    },\n    \"ParkingExit_Town12_Route22615_Weather20.tar.gz\": {\n        \"sha256\": \"1912ac031006e36f0a76a290642ea737fd1c3bf89d1e14d16af85337a06e5c2e\",\n        \"size\": 162926770\n    },\n    \"ParkingExit_Town12_Route22616_Weather21.tar.gz\": {\n        \"sha256\": \"91b6a966d1892ce280f36ebf166931af364317a8715b195607252d66e76dba83\",\n        \"size\": 166837656\n    },\n    \"ParkingExit_Town12_Route22617_Weather22.tar.gz\": {\n        \"sha256\": \"e02a7fb90e414f52949c52a5d372aa4c5d14c7dd242ad6672c5497b945c4be9d\",\n        \"size\": 161126001\n    },\n    \"ParkingExit_Town12_Route22619_Weather23.tar.gz\": {\n        \"sha256\": \"044138a592fbf9874685146c7c52797c94c03d0f27acfdec8a88a8426e1f4612\",\n        \"size\": 150354574\n    },\n    \"ParkingExit_Town12_Route22620_Weather25.tar.gz\": {\n        \"sha256\": \"40a43ab1f1e946ca746ba9f4def12d0a22610155fac814955f968200e645bb5e\",\n        \"size\": 143977071\n    },\n    \"ParkingExit_Town12_Route22621_Weather0.tar.gz\": {\n        \"sha256\": \"40512fcf731633d66a65d57041ceda08bb6bdb22d0d9b16f84f450f059bdc93a\",\n        \"size\": 192029997\n    },\n    \"ParkingExit_Town12_Route22622_Weather1.tar.gz\": {\n        \"sha256\": \"3e302237ee5fe7e7c241c185d91c90cdd73009d56e12fb6a822ca48d801eb017\",\n        \"size\": 181627211\n    },\n    \"ParkingExit_Town12_Route22625_Weather3.tar.gz\": {\n        \"sha256\": \"c55af1a5898c696d374238453da0b6a18f53d6854754d4ce70e78bdcbf1ae92b\",\n        \"size\": 185890538\n    },\n    \"ParkingExit_Town12_Route22626_Weather5.tar.gz\": {\n        \"sha256\": \"c89c71ae30d2d49dae98fbf88faddeb503785fac47bf9584d4efb381b2e32761\",\n        \"size\": 189250880\n    },\n    \"ParkingExit_Town12_Route22627_Weather6.tar.gz\": {\n        \"sha256\": \"482552660d4d3db451e6516b379eaae607fd9253adc04f19f70ba404ddcc2582\",\n        \"size\": 163438178\n    },\n    \"ParkingExit_Town12_Route22628_Weather7.tar.gz\": {\n        \"sha256\": \"0eebbf134d081e364a8d6a0bb3546547d8aaa1fb00e023252bc04bf08ed13d3d\",\n        \"size\": 195632122\n    },\n    \"ParkingExit_Town12_Route22629_Weather8.tar.gz\": {\n        \"sha256\": \"7fb57c6e881b712a4e617c2ee26d262e41612a73bb0c5a8d960fdd49e5fe5f41\",\n        \"size\": 183002427\n    },\n    \"ParkingExit_Town12_Route22630_Weather9.tar.gz\": {\n        \"sha256\": \"3b53b03dc889d505b7d1134430f3d48273de876370287ccb3b2f99af21e38bf6\",\n        \"size\": 135761213\n    },\n    \"ParkingExit_Town12_Route22631_Weather10.tar.gz\": {\n        \"sha256\": \"203bcc95ac351d2437d1658e12e790097080898c1dadfc65f80d09e9fc24bae3\",\n        \"size\": 166988673\n    },\n    \"ParkingExit_Town12_Route22632_Weather11.tar.gz\": {\n        \"sha256\": \"07feca63c3ffffdd20ccb448da4b9008d792b98c40ac82c36999438300e3bcb3\",\n        \"size\": 152567295\n    },\n    \"ParkingExit_Town12_Route2724_Weather14.tar.gz\": {\n        \"sha256\": \"de681413144fb5518cae7fb2a2f24cf2d95abdb30742c42ca0ad36b30dcf8893\",\n        \"size\": 158190795\n    },\n    \"ParkingExit_Town12_Route2726_Weather8.tar.gz\": {\n        \"sha256\": \"18a90148b47bf4333287853873985cd202363cffa6dfa4981592aa5663c6db96\",\n        \"size\": 198824245\n    },\n    \"ParkingExit_Town12_Route2728_Weather18.tar.gz\": {\n        \"sha256\": \"d469038f205f0be03549d46fc66a9c961e5fed1da6f1595eb81f899d395869ca\",\n        \"size\": 204539404\n    },\n    \"ParkingExit_Town12_Route2730_Weather20.tar.gz\": {\n        \"sha256\": \"b089bf5bdd502916e2f47c5751cba50fe3d42aa46606942ce958ff2f8a90f1ab\",\n        \"size\": 176484829\n    },\n    \"ParkingExit_Town12_Route2731_Weather21.tar.gz\": {\n        \"sha256\": \"f22b8e3bbf487433451f00dae65257b2852b7b507b28c30bb2f6277dcc6f6744\",\n        \"size\": 159702449\n    },\n    \"ParkingExit_Town12_Route2732_Weather22.tar.gz\": {\n        \"sha256\": \"a6712b17a2632958c75cb0116bac27d5f7d8835d4e1e03d909a683303fb431f4\",\n        \"size\": 164230041\n    },\n    \"ParkingExit_Town12_Route2733_Weather23.tar.gz\": {\n        \"sha256\": \"f8f1a1c350e372591bb86a7176288fbac5cd04b1111f58cafbb1684bc8270405\",\n        \"size\": 149899539\n    },\n    \"ParkingExit_Town12_Route2734_Weather23.tar.gz\": {\n        \"sha256\": \"a1e37ff9c9c8f9f57ac657b0e9fa7b5ba9c9132ddb532bcc67765abb7b348d6c\",\n        \"size\": 173925553\n    },\n    \"ParkingExit_Town12_Route2735_Weather25.tar.gz\": {\n        \"sha256\": \"fa2cddb811b176c34d375061d3ed6a2d8fd77c6abcfb2b8bff196e7f05560eb1\",\n        \"size\": 145473962\n    },\n    \"ParkingExit_Town12_Route2736_Weather0.tar.gz\": {\n        \"sha256\": \"e1578409fafe56a7534d0119e879d3e28589657a8c098c5c02cbcbeb9a3bfd59\",\n        \"size\": 199067384\n    },\n    \"ParkingExit_Town12_Route2737_Weather1.tar.gz\": {\n        \"sha256\": \"1dc8c22f8b24b8c1396289ec89a4ef8a4f3ccb926634e18ea873f31332f92b5f\",\n        \"size\": 197497703\n    },\n    \"ParkingExit_Town12_Route2740_Weather3.tar.gz\": {\n        \"sha256\": \"864da9477cad810308695ea1fc9346e2b65ed6d3a559c0aabd9eb541443923f0\",\n        \"size\": 188795271\n    },\n    \"ParkingExit_Town12_Route2741_Weather5.tar.gz\": {\n        \"sha256\": \"843e41d421d585664c2b65e9712990626d9f0a41f2862dc2c1719e6c70df803f\",\n        \"size\": 191138048\n    },\n    \"ParkingExit_Town12_Route2742_Weather6.tar.gz\": {\n        \"sha256\": \"085a81ab459256e8e4a74f87219ea6b5bfa45843db26f8ad78ecc89e71882f7e\",\n        \"size\": 175822569\n    },\n    \"ParkingExit_Town13_Route3503_Weather14.tar.gz\": {\n        \"sha256\": \"32630a67df91c50069631379a19d1cb85ed6121e63c1fc1c1b96dd0db080aed3\",\n        \"size\": 202949993\n    },\n    \"ParkingExit_Town13_Route3504_Weather15.tar.gz\": {\n        \"sha256\": \"6f3683722587633fc012fa7aeade9d7cd9a3043aae69389ce2caae23e15aa0bb\",\n        \"size\": 472647390\n    },\n    \"ParkingExit_Town13_Route3505_Weather8.tar.gz\": {\n        \"sha256\": \"5db4124c5c68d1bdcb870afec6f08f75381953441f36b0c0536d5ae2ec93101b\",\n        \"size\": 231128057\n    },\n    \"ParkingExit_Town13_Route3506_Weather9.tar.gz\": {\n        \"sha256\": \"9a55d1ddfa15b38b435bd8488ade0504567205d6613b9c8010901493b3164ac4\",\n        \"size\": 299655097\n    },\n    \"ParkingExit_Town13_Route3507_Weather18.tar.gz\": {\n        \"sha256\": \"a4d6b47e46fb14df37c8b4e969bb20e131ce42d0460e2b6fdcfacb53da9b7774\",\n        \"size\": 525515473\n    },\n    \"ParkingExit_Town13_Route3508_Weather19.tar.gz\": {\n        \"sha256\": \"33b00bf6d16fe0c13a059d1771105b0475f1d09357d3abcb84488a6e1e206cc2\",\n        \"size\": 197226220\n    },\n    \"ParkingExit_Town13_Route3509_Weather20.tar.gz\": {\n        \"sha256\": \"dce6fd8558d290459c8faac7b98f0a85c43a4abfbb08a5d8bb1b7a19764294c8\",\n        \"size\": 193304512\n    },\n    \"ParkingExit_Town13_Route3510_Weather21.tar.gz\": {\n        \"sha256\": \"28b3cebe98740902b83bba9ff3aba1c17e4e8f7e08235e5e6a6c50e7b4581f00\",\n        \"size\": 220461123\n    },\n    \"ParkingExit_Town13_Route3511_Weather22.tar.gz\": {\n        \"sha256\": \"b5d5c24ffd80cd505c224831ee43ce7f47a6e16b424cdc9b7666aee4e54e88a4\",\n        \"size\": 458310172\n    },\n    \"ParkingExit_Town13_Route3512_Weather23.tar.gz\": {\n        \"sha256\": \"dc1bec43f9c60e41f1edd7188899bb2431ef943d968d8d53370b896b57491ff6\",\n        \"size\": 436092844\n    },\n    \"ParkingExit_Town13_Route3513_Weather23.tar.gz\": {\n        \"sha256\": \"12e601e8cb8bf9670109cd093bc8b55be1d1465d08b874191da0f0efb6d9d8e0\",\n        \"size\": 572244277\n    },\n    \"ParkingExit_Town13_Route3514_Weather25.tar.gz\": {\n        \"sha256\": \"3ab1172baee8f35835c9831f3c26b3fc0739d89d70970606fbe7e8812926d554\",\n        \"size\": 145142209\n    },\n    \"ParkingExit_Town13_Route3517_Weather2.tar.gz\": {\n        \"sha256\": \"58caeae00cee561382bec665bedf676c35610951d054486f5e7b11fc194dc72d\",\n        \"size\": 217232592\n    },\n    \"ParkingExit_Town13_Route3518_Weather3.tar.gz\": {\n        \"sha256\": \"73ddb7242e77fd09fe74cad3ee60ba84579a4edc31d070a5b3ceedd4682dc4fc\",\n        \"size\": 237435764\n    },\n    \"ParkingExit_Town13_Route3519_Weather3.tar.gz\": {\n        \"sha256\": \"90ea16e947537465c7882873d58b5269df1c9a2c84b2f1fa20039b5f4df43dd9\",\n        \"size\": 228862462\n    },\n    \"ParkingExit_Town13_Route3520_Weather5.tar.gz\": {\n        \"sha256\": \"acf67cd3e4971965878b4b783cb5634b6b3ab37ddc36948070e3f22c1f56ee5b\",\n        \"size\": 215685844\n    },\n    \"ParkingExit_Town13_Route3521_Weather6.tar.gz\": {\n        \"sha256\": \"b006118fabbf0aa122bb298c6852495aefb7d27f152d939d36e456a6c3fd4c4e\",\n        \"size\": 185921002\n    },\n    \"ParkingExit_Town13_Route3522_Weather7.tar.gz\": {\n        \"sha256\": \"60789be596ee06aeb0dbb97b5d09ca4bef459dd2aa4ef695fb7b0c67efbc9f86\",\n        \"size\": 552712097\n    },\n    \"PedestrianCrossing_Town03_Route27445_Weather6.tar.gz\": {\n        \"sha256\": \"c1525a026c76ce286776f884e11ad3f159d21561344211d243a981a7a9d2c67e\",\n        \"size\": 108010772\n    },\n    \"PedestrianCrossing_Town03_Route27450_Weather11.tar.gz\": {\n        \"sha256\": \"03cb64a4cc88c4f24a0df770652a70d8b913ceca1ef4f649e58e07dbeb5ed4e1\",\n        \"size\": 148750771\n    },\n    \"PedestrianCrossing_Town03_Route27455_Weather18.tar.gz\": {\n        \"sha256\": \"0f933242f849bb6a5c236c11f9eb4db21838dd9cb80efa46797bbf0ba565c93a\",\n        \"size\": 172444910\n    },\n    \"PedestrianCrossing_Town03_Route27460_Weather23.tar.gz\": {\n        \"sha256\": \"f2e1eef8cfbcc6745c42ec19b783a637b7ad927815a4955d30abf390d0210943\",\n        \"size\": 83362841\n    },\n    \"PedestrianCrossing_Town03_Route27470_Weather8.tar.gz\": {\n        \"sha256\": \"007c002b7c97a44b44633ad328ff54fcb295160bae617aef92c2871611730424\",\n        \"size\": 270723237\n    },\n    \"PedestrianCrossing_Town03_Route27475_Weather13.tar.gz\": {\n        \"sha256\": \"e3e1d65d59e35eee6946b7a48f27895ee79a2d1c95a8cce0396539eae93181eb\",\n        \"size\": 392521936\n    },\n    \"PedestrianCrossing_Town03_Route27485_Weather26.tar.gz\": {\n        \"sha256\": \"11a13d217cca3978d1326e7020f75e5f8f68cda127b1f12b324868faaccbf024\",\n        \"size\": 187216843\n    },\n    \"PedestrianCrossing_Town03_Route27495_Weather10.tar.gz\": {\n        \"sha256\": \"39e3dff4bc56b9704aae7d8d3ce46185a9a648fe2db76fdb4ed633b478d4ace9\",\n        \"size\": 410179593\n    },\n    \"PedestrianCrossing_Town03_Route27500_Weather15.tar.gz\": {\n        \"sha256\": \"c8781db076572e6b3cb9a88713561b4bc65db295005e6acfff8757187e581e87\",\n        \"size\": 141318094\n    },\n    \"PedestrianCrossing_Town03_Route27515_Weather7.tar.gz\": {\n        \"sha256\": \"a45f373c5234ae61de7f1e75d15c3411a9c38798a30605ee3b6f3757632f4cb5\",\n        \"size\": 1005790578\n    },\n    \"PedestrianCrossing_Town04_Route27509_Weather0.tar.gz\": {\n        \"sha256\": \"c856c2753ebc8c460b7724ac9852439fdcb44db74c608ba342f2dd4313b261c6\",\n        \"size\": 125534205\n    },\n    \"PedestrianCrossing_Town04_Route27519_Weather11.tar.gz\": {\n        \"sha256\": \"6c34531b0a681f2f4064c7736e06898515a47d39fc03769f66ea2ce2906f4b87\",\n        \"size\": 508064085\n    },\n    \"PedestrianCrossing_Town04_Route27529_Weather23.tar.gz\": {\n        \"sha256\": \"e0637df8f37f28dddfe0bed59da586cedf7799201e13a9aec613cb08daabc31c\",\n        \"size\": 201913151\n    },\n    \"PedestrianCrossing_Town04_Route27539_Weather8.tar.gz\": {\n        \"sha256\": \"0bf88db5edc83f66692e564823991fd7adca5d49340ae8a49728554d2c33a827\",\n        \"size\": 120466916\n    },\n    \"PedestrianCrossing_Town04_Route27549_Weather20.tar.gz\": {\n        \"sha256\": \"250214b9fb4fada708da0bd9f0d7eb94c57b36bc1a17525411a6bc7a3d719bb2\",\n        \"size\": 431039718\n    },\n    \"PedestrianCrossing_Town04_Route27559_Weather5.tar.gz\": {\n        \"sha256\": \"b17482a91601418e32ac052728d9f7207954b808563c0de5b56da735854b39ae\",\n        \"size\": 251032111\n    },\n    \"PedestrianCrossing_Town04_Route27569_Weather15.tar.gz\": {\n        \"sha256\": \"f98538daacdf419d87b955cf122c81e49dfbdb638f2a8e2f44c8dd123b0b8f93\",\n        \"size\": 623970330\n    },\n    \"PedestrianCrossing_Town04_Route27574_Weather22.tar.gz\": {\n        \"sha256\": \"5b50b0d40883a29e7c2378e5a4d32c680a830081f6b2e780fc04e2cace3c68e2\",\n        \"size\": 214419578\n    },\n    \"PedestrianCrossing_Town04_Route27584_Weather7.tar.gz\": {\n        \"sha256\": \"d7a998fe0eadc96092748ac496a7d8e9670626280b2d2014b4ed5ec2ea9266f0\",\n        \"size\": 702556464\n    },\n    \"PedestrianCrossing_Town04_Route27594_Weather19.tar.gz\": {\n        \"sha256\": \"6b48c3588f67406e0655823c52c066b8dc70dbfe212dace9bd8c11cdfc00b747\",\n        \"size\": 420363556\n    },\n    \"PedestrianCrossing_Town04_Route27604_Weather3.tar.gz\": {\n        \"sha256\": \"ff4ef9760942b06ad5914c16329aa61ce1a2b953f78e4e74b745d2fc6a14ea0f\",\n        \"size\": 670745119\n    },\n    \"PedestrianCrossing_Town05_Route27636_Weather13.tar.gz\": {\n        \"sha256\": \"1e3d13680332d620adeeb109bebf873ec2352c5d9a6b9acb811663d304f0b779\",\n        \"size\": 278256270\n    },\n    \"PedestrianCrossing_Town05_Route27651_Weather5.tar.gz\": {\n        \"sha256\": \"e7db3294450513e526508731d2fa08d239a6e276eff407dc911eca1a7a93a7be\",\n        \"size\": 1101086901\n    },\n    \"PedestrianCrossing_Town05_Route27656_Weather10.tar.gz\": {\n        \"sha256\": \"b489e07baad8451a3e33ae2fd6ee96e66627b6393e43737c58a5952f76ea9b7e\",\n        \"size\": 525526073\n    },\n    \"PedestrianCrossing_Town05_Route27661_Weather15.tar.gz\": {\n        \"sha256\": \"07489379f0c53c23cfabf7d598d58d7ec2cf045b1794e7b9fd52dd7b58f30fee\",\n        \"size\": 579479533\n    },\n    \"PedestrianCrossing_Town05_Route27676_Weather7.tar.gz\": {\n        \"sha256\": \"9708ce524638b1cc095086da9e152718f0e2eff12a0358f418e697179bb265d7\",\n        \"size\": 879832056\n    },\n    \"PedestrianCrossing_Town05_Route27706_Weather14.tar.gz\": {\n        \"sha256\": \"fe79a5961539ba343e76910a0b55a09264716a40dc952dc7503b9343a4a33a5f\",\n        \"size\": 241301596\n    },\n    \"PedestrianCrossing_Town07_Route25863_Weather11.tar.gz\": {\n        \"sha256\": \"f2b72eaf372c81d99cfe5b8edf049e064d90f0fbc13d87c33813dd7e6eea64f6\",\n        \"size\": 502339460\n    },\n    \"PedestrianCrossing_Town07_Route25877_Weather1.tar.gz\": {\n        \"sha256\": \"a967a9909c4d70c714001cf34376263ccad0590c0cad296a2884aae7c1b71ee9\",\n        \"size\": 839709233\n    },\n    \"PedestrianCrossing_Town07_Route25905_Weather7.tar.gz\": {\n        \"sha256\": \"8794eef29da0534bf74e32ff1433d3f56f3d83d010c5e4fc7794c3af4e8d169e\",\n        \"size\": 612040802\n    },\n    \"PedestrianCrossing_Town11_Route27572_Weather20.tar.gz\": {\n        \"sha256\": \"2477043230370eaac7823eb4e66c86b2a51ced85066e075bb00d6b361f477766\",\n        \"size\": 31242518\n    },\n    \"PedestrianCrossing_Town11_Route27582_Weather5.tar.gz\": {\n        \"sha256\": \"6e97821b91ddf29247774f58722a473078b86f6f2499cde7d17366b51d98bd9c\",\n        \"size\": 100412430\n    },\n    \"PedestrianCrossing_Town11_Route27587_Weather10.tar.gz\": {\n        \"sha256\": \"9a45c590a0416ad659ae03a835c58dc1c8241e147ae7bbb6f011a4f29000f9c2\",\n        \"size\": 35694664\n    },\n    \"PedestrianCrossing_Town11_Route27592_Weather15.tar.gz\": {\n        \"sha256\": \"5ab2bfe90b61870a89fc5860f689678ad1881aa0573b189a96feed132be5b3c5\",\n        \"size\": 73094216\n    },\n    \"PedestrianCrossing_Town11_Route27607_Weather7.tar.gz\": {\n        \"sha256\": \"c026cc10ac9e37dc8297552e9c2611973a3a805a95bb3ddee82fbc9755d48203\",\n        \"size\": 80978374\n    },\n    \"PedestrianCrossing_Town11_Route27612_Weather12.tar.gz\": {\n        \"sha256\": \"60e3d15740598a223851980a4bde3c6cb8d2342d34688cf445f30a9fb2e77494\",\n        \"size\": 39423454\n    },\n    \"PedestrianCrossing_Town11_Route27617_Weather19.tar.gz\": {\n        \"sha256\": \"f54a5da1ec8f1c37774fb455793d216da152972a34bebd0256faa6bfb546b708\",\n        \"size\": 72159900\n    },\n    \"PedestrianCrossing_Town11_Route27622_Weather25.tar.gz\": {\n        \"sha256\": \"5f9b58a5e69b5b410387ed94da169ec178414f5d8ddc7d7f5f620d5864a5700b\",\n        \"size\": 69138210\n    },\n    \"PedestrianCrossing_Town11_Route27627_Weather3.tar.gz\": {\n        \"sha256\": \"339b45855a314dcd3996fa27aca79111c0ccc1cd8967c8014b47980336c1b92d\",\n        \"size\": 108726252\n    },\n    \"PedestrianCrossing_Town11_Route27632_Weather9.tar.gz\": {\n        \"sha256\": \"8ad5b8972c1d2fb121f78757ebb91e1fdf24dec397dd36c1f9484c4b71c06924\",\n        \"size\": 73316223\n    },\n    \"PedestrianCrossing_Town11_Route27637_Weather14.tar.gz\": {\n        \"sha256\": \"aadc22858ef0f41a64f479a9fb2e2acf28c25a2c80fe660c7a15313409b70ab2\",\n        \"size\": 82223892\n    },\n    \"PedestrianCrossing_Town11_Route27647_Weather0.tar.gz\": {\n        \"sha256\": \"2649bcac34203fa78bae191cd7dddbcc3ce9e75a45c0fdf9494c30e579bacbbd\",\n        \"size\": 108537635\n    },\n    \"PedestrianCrossing_Town11_Route27652_Weather6.tar.gz\": {\n        \"sha256\": \"daa94308ffffe2cbd47f87e7d33d35be2b64f6a8b336f3061f997ef02e813d45\",\n        \"size\": 44038470\n    },\n    \"PedestrianCrossing_Town11_Route27662_Weather18.tar.gz\": {\n        \"sha256\": \"f94fd810cfb084827e4668100c1a11c13e4dac5d312058a51e42c4e3df253378\",\n        \"size\": 108448020\n    },\n    \"PedestrianCrossing_Town12_Route13479_Weather14.tar.gz\": {\n        \"sha256\": \"2206c7b042d88a1eda1dedccbfff877b124d05114f9eee195625b750a834b245\",\n        \"size\": 690745041\n    },\n    \"PedestrianCrossing_Town12_Route13486_Weather21.tar.gz\": {\n        \"sha256\": \"3d6715aca813dcd679664aeb8face5bdb8612a89a822c4a7bea16eae828bfc63\",\n        \"size\": 166431391\n    },\n    \"PedestrianCrossing_Town12_Route13496_Weather5.tar.gz\": {\n        \"sha256\": \"efba148909c9fd2207c7d00cab3d3defc99b6b27edb85ba4f773e7aeb0ba234d\",\n        \"size\": 251249252\n    },\n    \"PedestrianCrossing_Town12_Route13531_Weather14.tar.gz\": {\n        \"sha256\": \"e8787583a6def034429088bcd051de2fa212fb0e5a902450eff14073f536af5b\",\n        \"size\": 284085849\n    },\n    \"PedestrianCrossing_Town12_Route13537_Weather20.tar.gz\": {\n        \"sha256\": \"8941f40d22c9eef31ded4f372a62bfd707b805ddd785a1bb6792492af0f1f7a8\",\n        \"size\": 539087539\n    },\n    \"PedestrianCrossing_Town12_Route13603_Weather8.tar.gz\": {\n        \"sha256\": \"5518997ae51d25760fe93e22d128047a9d82b43e362e72dc9e25952dac3ea7e1\",\n        \"size\": 176867665\n    },\n    \"PedestrianCrossing_Town12_Route13610_Weather15.tar.gz\": {\n        \"sha256\": \"e547d8a4d936842e7b57745aa28cd362cf3b5fe109336bef8c6b448bd32f4ae9\",\n        \"size\": 450366229\n    },\n    \"PedestrianCrossing_Town12_Route13616_Weather21.tar.gz\": {\n        \"sha256\": \"e6dfb6d107237ee023bfb3620f14cd2f21c2f5e56ff08b46bd30c4fde900c25e\",\n        \"size\": 461588316\n    },\n    \"PedestrianCrossing_Town12_Route13619_Weather23.tar.gz\": {\n        \"sha256\": \"a96217cb06bcc55861184d1665e5fff39b58443747307bd9ad92ec2834a9fe5f\",\n        \"size\": 82021793\n    },\n    \"PedestrianCrossing_Town12_Route13662_Weather15.tar.gz\": {\n        \"sha256\": \"9dcb444d0138c6a405bd490c20450a32952cbb3724458563581cab32c6990bbe\",\n        \"size\": 482021943\n    },\n    \"PedestrianCrossing_Town12_Route13673_Weather0.tar.gz\": {\n        \"sha256\": \"cad823dcee7904bacff5d57078a70b228e49f1bf02189655c1ce75b8e05820c7\",\n        \"size\": 297695125\n    },\n    \"PedestrianCrossing_Town12_Route13703_Weather3.tar.gz\": {\n        \"sha256\": \"5ca18111edc9638638178731dfa6755a9ca2eccd926cd4d95afbf429c637601c\",\n        \"size\": 236396095\n    },\n    \"PedestrianCrossing_Town12_Route13716_Weather9.tar.gz\": {\n        \"sha256\": \"7a4097da4e544f2b7bd603fa945361fb1fc2be68a1734d0cae6630d017dafdfd\",\n        \"size\": 432715779\n    },\n    \"PedestrianCrossing_Town12_Route13721_Weather22.tar.gz\": {\n        \"sha256\": \"f3982fb3a50c1cc194194b6b526b176c5c5bd748261eab18bc9b03851d856814\",\n        \"size\": 521197541\n    },\n    \"PedestrianCrossing_Town12_Route13740_Weather15.tar.gz\": {\n        \"sha256\": \"2fcd7c7dfe7ea68f9ab52f4c2c37ebde0b9be14f6a9de66949811c2073031005\",\n        \"size\": 314099259\n    },\n    \"PedestrianCrossing_Town12_Route14145_Weather3.tar.gz\": {\n        \"sha256\": \"cf838f5001fe8e4df69ab0bb264935342e14ff2657c6d1e484a878ade06c7eca\",\n        \"size\": 189104673\n    },\n    \"PedestrianCrossing_Town12_Route14146_Weather5.tar.gz\": {\n        \"sha256\": \"149daf7a1ead9fd3f0eaae9b4ffe4bbf0ee7fd241b23991ca2dce5a503c13d5a\",\n        \"size\": 320508419\n    },\n    \"PedestrianCrossing_Town12_Route14147_Weather6.tar.gz\": {\n        \"sha256\": \"00bb578527b70e639ed0f9c9b00a1b071313b65c2eda2f1732f64053c05eae77\",\n        \"size\": 441736270\n    },\n    \"PedestrianCrossing_Town12_Route14148_Weather7.tar.gz\": {\n        \"sha256\": \"7b9eeb25edee3a64881846e6d6701a6d055e98a5e68be2a8fe1f00d1f8bbe6f2\",\n        \"size\": 374392891\n    },\n    \"PedestrianCrossing_Town12_Route14151_Weather10.tar.gz\": {\n        \"sha256\": \"6ea57c451fdecb62c70da439eb4c79e8d59c19e84f3e96ec71c2561972b4887a\",\n        \"size\": 486641270\n    },\n    \"PedestrianCrossing_Town12_Route14153_Weather12.tar.gz\": {\n        \"sha256\": \"f829e869230abf1ff676b888d06fa0c655ec1de33fcfa0733a9619a0278e37ff\",\n        \"size\": 74524843\n    },\n    \"PedestrianCrossing_Town12_Route14154_Weather13.tar.gz\": {\n        \"sha256\": \"5b48d73f69dd2e66c4aa9925c88e979aada8761e56a73ac7b121ac940aaf3c58\",\n        \"size\": 156515415\n    },\n    \"PedestrianCrossing_Town12_Route14155_Weather14.tar.gz\": {\n        \"sha256\": \"a9a0d2e79cb99ed7da047c241aa1ac3090da6f66a38196b39893cc280e71f604\",\n        \"size\": 369022028\n    },\n    \"PedestrianCrossing_Town12_Route14156_Weather15.tar.gz\": {\n        \"sha256\": \"5e850096eab201cf91641d70c4c4b3b8c95976973bcd42a08cb44f5e24894d30\",\n        \"size\": 237046542\n    },\n    \"PedestrianCrossing_Town12_Route14157_Weather8.tar.gz\": {\n        \"sha256\": \"b686e9bd5091e1cf31e513f65bf0f108af7c81d5ecd0c4e59de3be38cfd4e6c7\",\n        \"size\": 317841562\n    },\n    \"PedestrianCrossing_Town12_Route14158_Weather9.tar.gz\": {\n        \"sha256\": \"df36dec5a011186cf02a553c3db1c132e5c8f7cfaa4f5167cc111d17a221caca\",\n        \"size\": 557760612\n    },\n    \"PedestrianCrossing_Town12_Route14159_Weather18.tar.gz\": {\n        \"sha256\": \"1fdc6e455b35b27456d81f5bc0dad75c8b90f95aeb070b6434ec12e42027ad7b\",\n        \"size\": 96981722\n    },\n    \"PedestrianCrossing_Town12_Route14160_Weather19.tar.gz\": {\n        \"sha256\": \"172b86a428c0817a80fc213ea78ff0b5a834b6e5a7bc8d3af8a2d0cfc51a5a10\",\n        \"size\": 353331552\n    },\n    \"PedestrianCrossing_Town12_Route14161_Weather20.tar.gz\": {\n        \"sha256\": \"0d1ebdb9758ca4c6f45496894ceaa5453e32bad32e27e174deb82ce8b1c18362\",\n        \"size\": 354316278\n    },\n    \"PedestrianCrossing_Town12_Route14162_Weather21.tar.gz\": {\n        \"sha256\": \"0de6a49a9319f895c1bc417c303bb60aff458bfa442db3cbca33ad225ddef474\",\n        \"size\": 425704139\n    },\n    \"PedestrianCrossing_Town12_Route14163_Weather22.tar.gz\": {\n        \"sha256\": \"4114734db799944b4800ae688badba1611a2b5cc48f37924ec4fde121d709580\",\n        \"size\": 353284932\n    },\n    \"PedestrianCrossing_Town12_Route14164_Weather23.tar.gz\": {\n        \"sha256\": \"f5465670701fc33bdd4e8ae020ba9f6c7e520de5a5c2f635ddd8dbee0480ac1f\",\n        \"size\": 83981710\n    },\n    \"PedestrianCrossing_Town12_Route14165_Weather23.tar.gz\": {\n        \"sha256\": \"72650349457e56d79b69f360c5ee47e5c340678121257f994e834e712924ec00\",\n        \"size\": 1133303332\n    },\n    \"PedestrianCrossing_Town12_Route14166_Weather25.tar.gz\": {\n        \"sha256\": \"b0c8ab159bc4e96ee03fc2713b1839df0772d21cacc22fcadf08edf75334093c\",\n        \"size\": 439367579\n    },\n    \"PedestrianCrossing_Town12_Route14169_Weather2.tar.gz\": {\n        \"sha256\": \"2e8f1775a453f99f6790ae02fb2a910d81269fb37a88b4fbfa27afe8f5cc0129\",\n        \"size\": 196894899\n    },\n    \"PedestrianCrossing_Town12_Route14170_Weather3.tar.gz\": {\n        \"sha256\": \"a4368ed5bd456983ca75883a8e8baf43e23e2a44bbd7be75c3a7e38fd8df8046\",\n        \"size\": 362315890\n    },\n    \"PedestrianCrossing_Town12_Route14171_Weather3.tar.gz\": {\n        \"sha256\": \"a5163f2cb0da6f6b69a8c30abd7fa40a48e31f0a9c17d4132c3da3ccd056e5c0\",\n        \"size\": 316702544\n    },\n    \"PedestrianCrossing_Town12_Route14172_Weather5.tar.gz\": {\n        \"sha256\": \"9ca921ae28173d6c716f727f48834648c56f094f74456a36697c4da4c557b7ab\",\n        \"size\": 435746454\n    },\n    \"PedestrianCrossing_Town12_Route14175_Weather8.tar.gz\": {\n        \"sha256\": \"67d7e98e1890d854fd8e996d0a57c6e11ba0935933eb20eebb743a06c4f4e9f2\",\n        \"size\": 156057279\n    },\n    \"PedestrianCrossing_Town12_Route14176_Weather9.tar.gz\": {\n        \"sha256\": \"743c39da59891180955fd0acfe75ab96e50be422f266c3fff73eccbf2a52e23c\",\n        \"size\": 161369087\n    },\n    \"PedestrianCrossing_Town12_Route14177_Weather10.tar.gz\": {\n        \"sha256\": \"c6d3cc5aae74bc9577d77a472394740a251b111bb784f50ae7fe97720a8e4d9f\",\n        \"size\": 753515015\n    },\n    \"PedestrianCrossing_Town12_Route14178_Weather11.tar.gz\": {\n        \"sha256\": \"f10023cb7744cff8da5e730dec47bf7d7573e685612f9403fecd631be8c1767e\",\n        \"size\": 147546795\n    },\n    \"PedestrianCrossing_Town12_Route14179_Weather12.tar.gz\": {\n        \"sha256\": \"5d7609898806163b52e925492f55ade946666166ee277b7417d474e853bef7a7\",\n        \"size\": 612202094\n    },\n    \"PedestrianCrossing_Town12_Route14181_Weather14.tar.gz\": {\n        \"sha256\": \"029349d4730dab7c8348a321892a07885d4288be8f32faad6472cacce623277c\",\n        \"size\": 151205535\n    },\n    \"PedestrianCrossing_Town12_Route14182_Weather15.tar.gz\": {\n        \"sha256\": \"b80ee57df6d884b1353205e585b56d71afde2cf422d7402144c1673a5f1adb78\",\n        \"size\": 307054131\n    },\n    \"PedestrianCrossing_Town12_Route14183_Weather8.tar.gz\": {\n        \"sha256\": \"8ef13c59f18450476c385ed7183be0db8a3797e82bc7faa3ad34a94d8fcc6f6e\",\n        \"size\": 609011818\n    },\n    \"PedestrianCrossing_Town12_Route14185_Weather18.tar.gz\": {\n        \"sha256\": \"e054dbb203e77ca5bf18957a4ccf47a91f84476c1cf3753f8c44d192848890b8\",\n        \"size\": 346449510\n    },\n    \"PedestrianCrossing_Town12_Route14186_Weather19.tar.gz\": {\n        \"sha256\": \"804a2c844b37b049a9c4720df3177dca765e19cd1b91af516f96cc9ec59d010b\",\n        \"size\": 205812237\n    },\n    \"PedestrianCrossing_Town12_Route14187_Weather20.tar.gz\": {\n        \"sha256\": \"865b8f5eca42e5dbf245e4977442617de4b36977e3083ea5fd6ea94a622c10d0\",\n        \"size\": 423348313\n    },\n    \"PedestrianCrossing_Town12_Route14188_Weather21.tar.gz\": {\n        \"sha256\": \"c45d05b4956d267abb2f9bfbd7cb75cbe1ca19078e90828f363a19e7279ea170\",\n        \"size\": 194988752\n    },\n    \"PedestrianCrossing_Town12_Route14189_Weather22.tar.gz\": {\n        \"sha256\": \"bca9209b085773142f69ee7d2c83c609883ee871d54d1e32e3e58e71df31259f\",\n        \"size\": 797954029\n    },\n    \"PedestrianCrossing_Town12_Route14191_Weather23.tar.gz\": {\n        \"sha256\": \"34511bd2b0e21e8689d8e9196ddc81c2d40d05e1cff6e63e46dc1e73871bde14\",\n        \"size\": 301630357\n    },\n    \"PedestrianCrossing_Town12_Route14192_Weather25.tar.gz\": {\n        \"sha256\": \"770d2cfc6703b84e89063f45c0978a55b1c67d717c082f4789e20b9aa8e22242\",\n        \"size\": 177061411\n    },\n    \"PedestrianCrossing_Town12_Route14193_Weather0.tar.gz\": {\n        \"sha256\": \"09cf36b4177402b77910a8bcc2ee7e71708b964527aea61a7629b0f740a864f8\",\n        \"size\": 472004996\n    },\n    \"PedestrianCrossing_Town12_Route14194_Weather1.tar.gz\": {\n        \"sha256\": \"e4f9311ca44fbcb554cc8ec5f032f3c8e31b20fda2d6619577ea532a63a839c2\",\n        \"size\": 392368856\n    },\n    \"PedestrianCrossing_Town12_Route14195_Weather2.tar.gz\": {\n        \"sha256\": \"2a74d90b002b08a3be38258f3efb0a60ac5b1e79652cc5353902de738be8fe7f\",\n        \"size\": 110264081\n    },\n    \"PedestrianCrossing_Town12_Route14196_Weather3.tar.gz\": {\n        \"sha256\": \"972e6e70659fcf2e938118d3b3186ee575fdc6300e167335c64b8bb1d3204d8a\",\n        \"size\": 288403322\n    },\n    \"PedestrianCrossing_Town12_Route14198_Weather5.tar.gz\": {\n        \"sha256\": \"ce14ca1cbd9f7490668b46283d8c2e309942c63c313ba200a05aa4e487566cec\",\n        \"size\": 185939427\n    },\n    \"PedestrianCrossing_Town12_Route14199_Weather6.tar.gz\": {\n        \"sha256\": \"71e6c7b0263ed10d58569055273daa0e236d13a23d7c4ba19568495eca193036\",\n        \"size\": 274055033\n    },\n    \"PedestrianCrossing_Town12_Route14200_Weather7.tar.gz\": {\n        \"sha256\": \"49899cec47b9b74aca22fceb23f2c967613df51bdd8f7ed723363adff79392cc\",\n        \"size\": 802064429\n    },\n    \"PedestrianCrossing_Town12_Route14201_Weather8.tar.gz\": {\n        \"sha256\": \"41a5ca3b32cf52306e0951e7b046f84d4d2ee3b8b47d3e64ad883001e12cb61c\",\n        \"size\": 254716109\n    },\n    \"PedestrianCrossing_Town12_Route14202_Weather9.tar.gz\": {\n        \"sha256\": \"011be94e681adbd1b6aabd36253c2ea9fd08d25e00671be3b276a6cd2064d242\",\n        \"size\": 99080884\n    },\n    \"PedestrianCrossing_Town12_Route14203_Weather10.tar.gz\": {\n        \"sha256\": \"aef62d7805baf8d621ef38a571e661839af056949560eab96e0ea40294080e83\",\n        \"size\": 213702438\n    },\n    \"PedestrianCrossing_Town12_Route14205_Weather12.tar.gz\": {\n        \"sha256\": \"962b2816d2ab9afcb28ab3f236a16aa79a0f6ee639c0b216063aebaedaa74238\",\n        \"size\": 297404563\n    },\n    \"PedestrianCrossing_Town12_Route14207_Weather14.tar.gz\": {\n        \"sha256\": \"d53f7b514eb5eecd68e0dcb4d77ab8c116a263ffcd78c54561011de66ce6d1fa\",\n        \"size\": 286524851\n    },\n    \"PedestrianCrossing_Town12_Route14208_Weather15.tar.gz\": {\n        \"sha256\": \"a7ae76692a6927bda5f075f63e768638796f758ecde2278b6562027471ed55be\",\n        \"size\": 315691854\n    },\n    \"PedestrianCrossing_Town12_Route14209_Weather8.tar.gz\": {\n        \"sha256\": \"fcb8152a8815aaa0f531e2ad3c9f83013dda6d8a58e6aec58e452700488ac4d7\",\n        \"size\": 189367723\n    },\n    \"PedestrianCrossing_Town12_Route14210_Weather9.tar.gz\": {\n        \"sha256\": \"b53b52acbb94dc8f16024177cce4fb99ba578f1dee6b26b44605a82d34f95a47\",\n        \"size\": 141073046\n    },\n    \"PedestrianCrossing_Town12_Route14211_Weather18.tar.gz\": {\n        \"sha256\": \"04e2ed7911a5485d60cafccc3bd46fe0f8695da03b80e63ee853e2f5e9c7b418\",\n        \"size\": 244384083\n    },\n    \"PedestrianCrossing_Town12_Route14212_Weather19.tar.gz\": {\n        \"sha256\": \"06646a0f2ae33cd276c756a9c571d956847436736fd318a1ea18cc796607d085\",\n        \"size\": 539080633\n    },\n    \"PedestrianCrossing_Town12_Route14213_Weather20.tar.gz\": {\n        \"sha256\": \"bcb8a80f8c093929b85483d5bf95df9d6698c828621f3f9b35852d7b7ae377cb\",\n        \"size\": 358714905\n    },\n    \"PedestrianCrossing_Town12_Route14214_Weather21.tar.gz\": {\n        \"sha256\": \"b849b774d280ee052c4e50ef6e7382b64992d4cd987c88f3e49eff397aab23ff\",\n        \"size\": 255561612\n    },\n    \"PedestrianCrossing_Town12_Route14215_Weather22.tar.gz\": {\n        \"sha256\": \"b3f2174a613ad197c50cb961c038c1ccdbea5e1b1030ed23b4a9d9f6e2e9153d\",\n        \"size\": 463037496\n    },\n    \"PedestrianCrossing_Town12_Route14216_Weather23.tar.gz\": {\n        \"sha256\": \"33aa8539c15285eb2885f664b53d26431799c49dbc49c468112b5f7becb72f77\",\n        \"size\": 492218941\n    },\n    \"PedestrianCrossing_Town12_Route14217_Weather23.tar.gz\": {\n        \"sha256\": \"1cfd9b549ca7661638c1d769855c29f37988ad3139b5af2bc4e482a912d52de2\",\n        \"size\": 860248345\n    },\n    \"PedestrianCrossing_Town12_Route14219_Weather0.tar.gz\": {\n        \"sha256\": \"4f4443021a6203db0800a14e006a706421015bf100318018fc55a70625a6df86\",\n        \"size\": 562503886\n    },\n    \"PedestrianCrossing_Town12_Route14220_Weather1.tar.gz\": {\n        \"sha256\": \"14520b9df4fa328c0d2f7cc289b7a6251dd6f409850fcfd1d3d51588aa17d8e8\",\n        \"size\": 198022928\n    },\n    \"PedestrianCrossing_Town12_Route14221_Weather2.tar.gz\": {\n        \"sha256\": \"c557f9f5e054985dd69c951b1a7c6a9dd0b5dcc625a719c8aff22bdc7c57c006\",\n        \"size\": 429653343\n    },\n    \"PedestrianCrossing_Town12_Route14222_Weather3.tar.gz\": {\n        \"sha256\": \"a9f8bd582607a77c9e58be2f995ce6e8d1a5d2ca9e67d0cb4d632154ce0f4df1\",\n        \"size\": 461613755\n    },\n    \"PedestrianCrossing_Town12_Route14223_Weather3.tar.gz\": {\n        \"sha256\": \"e4e1c2b58a6c84161180f4963c471da7eb09caa1f7aca842f13376fe87a9ec23\",\n        \"size\": 165504512\n    },\n    \"PedestrianCrossing_Town12_Route14224_Weather5.tar.gz\": {\n        \"sha256\": \"6f7f9a76b494ba3837190218df1997f720fbcea76de4a7333cf149481545ad78\",\n        \"size\": 242416776\n    },\n    \"PedestrianCrossing_Town12_Route14229_Weather10.tar.gz\": {\n        \"sha256\": \"d6cc98875ddf0944eebe2236a7cb9e8eb83d123e00829162f0fec57ca15ded8e\",\n        \"size\": 426815882\n    },\n    \"PedestrianCrossing_Town12_Route14230_Weather11.tar.gz\": {\n        \"sha256\": \"b7280871deba27d214bcde0e18f198a9583a890039934852ea304b8575202b4a\",\n        \"size\": 220432319\n    },\n    \"PedestrianCrossing_Town12_Route14231_Weather12.tar.gz\": {\n        \"sha256\": \"b498242f37f0f5cd60df3a138982a382f1b9e69702064527a6a0c2d4cf29a3cc\",\n        \"size\": 334107773\n    },\n    \"PedestrianCrossing_Town12_Route14233_Weather14.tar.gz\": {\n        \"sha256\": \"4a17ec7fb5f9921c360b9229449361a4141bca1a50615b0cd72fae45ec964e86\",\n        \"size\": 272528193\n    },\n    \"PedestrianCrossing_Town12_Route14234_Weather15.tar.gz\": {\n        \"sha256\": \"85507cf940b1dfbbfa91bb50671c5fbd69a46e55440b5475247df33e9027615a\",\n        \"size\": 491935668\n    },\n    \"PedestrianCrossing_Town12_Route14235_Weather8.tar.gz\": {\n        \"sha256\": \"2170c30b1deeada7ae864823f4765c0522b5c109962d87b810449dbdddb265c3\",\n        \"size\": 183034740\n    },\n    \"PedestrianCrossing_Town12_Route14236_Weather9.tar.gz\": {\n        \"sha256\": \"db80520f71f8dde4ef257fa3770b456f0bf13fb09818b04be0178f38004618e6\",\n        \"size\": 143515901\n    },\n    \"PedestrianCrossing_Town12_Route14240_Weather21.tar.gz\": {\n        \"sha256\": \"d622487045d3f598242662a8c8783cc14966bb751526cba58469adec4f798b0b\",\n        \"size\": 193929987\n    },\n    \"PedestrianCrossing_Town12_Route14241_Weather22.tar.gz\": {\n        \"sha256\": \"6f087e46d44085037cf7cc764f5c172b78d5290a69deaea076928813a4866533\",\n        \"size\": 380807211\n    },\n    \"PedestrianCrossing_Town12_Route14242_Weather23.tar.gz\": {\n        \"sha256\": \"01de9778ea741c58beb970b8015380a3048b1af2274e7a92576d39c41651af7c\",\n        \"size\": 164364744\n    },\n    \"PedestrianCrossing_Town12_Route14243_Weather23.tar.gz\": {\n        \"sha256\": \"9aa65b83e08801b42ec7015e7305c3275233484a1a334d47116cd7d07ea9aebb\",\n        \"size\": 316535061\n    },\n    \"PedestrianCrossing_Town12_Route14244_Weather25.tar.gz\": {\n        \"sha256\": \"ec0ecc2edf9a0f4158a691b9c85436cbf67a2c236061df260a8d22f856fae8ee\",\n        \"size\": 150705325\n    },\n    \"PedestrianCrossing_Town12_Route14247_Weather2.tar.gz\": {\n        \"sha256\": \"08b8363a7afdd7e983ee499e93eb0e5a0b846befc1a612ef30ed8025b3549ace\",\n        \"size\": 469738299\n    },\n    \"PedestrianCrossing_Town12_Route14248_Weather3.tar.gz\": {\n        \"sha256\": \"3ddc8285e77f9044fc1caae27cd88a62e3f9a2645e7031134ec198a107f2fdc6\",\n        \"size\": 418483525\n    },\n    \"PedestrianCrossing_Town12_Route14250_Weather5.tar.gz\": {\n        \"sha256\": \"fafb5f0130681e8ac653d2e5a135bdb970eab8b792289224d69644b9b729e5b4\",\n        \"size\": 270080353\n    },\n    \"PedestrianCrossing_Town12_Route14251_Weather6.tar.gz\": {\n        \"sha256\": \"99ab1926e5abf1d6892a9fd031a9e60151a183f2a06ccc596dffb7c3d76291f1\",\n        \"size\": 88809915\n    },\n    \"PedestrianCrossing_Town12_Route14252_Weather7.tar.gz\": {\n        \"sha256\": \"d2b0e358390c0839713ccb3ee3c2a884be10f23a3d57838a261594ceae7164b4\",\n        \"size\": 233456437\n    },\n    \"PedestrianCrossing_Town12_Route14253_Weather8.tar.gz\": {\n        \"sha256\": \"6b569662311868415272147bf658b5bab999ca29a166cf4c299836eac4c4c528\",\n        \"size\": 185531328\n    },\n    \"PedestrianCrossing_Town12_Route14254_Weather9.tar.gz\": {\n        \"sha256\": \"9c1a876cc7b3dd3e495ae5ce8c49a4439397cee5484972291dafdccf771fc3e2\",\n        \"size\": 315898632\n    },\n    \"PedestrianCrossing_Town12_Route14255_Weather10.tar.gz\": {\n        \"sha256\": \"ab6aa3c62a2a8d1ba3d84dfd6cbcd0149ec8e601179da511d647c4a48fda5c4d\",\n        \"size\": 511148533\n    },\n    \"PedestrianCrossing_Town12_Route14257_Weather12.tar.gz\": {\n        \"sha256\": \"f165b23a3bc4145afa2474c33065dfb3c2b6e1d8e67eddefa31946d3c0205378\",\n        \"size\": 474162513\n    },\n    \"PedestrianCrossing_Town12_Route14258_Weather13.tar.gz\": {\n        \"sha256\": \"3c7bda66ffee8b256d6c15a0a62ebe4c91f94eb1dcdf40676e488fbf911935df\",\n        \"size\": 659441459\n    },\n    \"PedestrianCrossing_Town12_Route14259_Weather14.tar.gz\": {\n        \"sha256\": \"c6e4ac2a35cf797beb32689e1ff8a5f2d878413b9a5ae72717f290755512f65a\",\n        \"size\": 174073485\n    },\n    \"PedestrianCrossing_Town12_Route14261_Weather8.tar.gz\": {\n        \"sha256\": \"0dad6811dfd9d83fda66017249ed7157b6ed1d407b856ad7b5d18421f2f72cf7\",\n        \"size\": 281439409\n    },\n    \"PedestrianCrossing_Town12_Route14262_Weather9.tar.gz\": {\n        \"sha256\": \"d0fa863f8ed4c62fe7671fbe310e86f6e50d27df9d2fae2e1f676adc29e2258e\",\n        \"size\": 324539983\n    },\n    \"PedestrianCrossing_Town12_Route14263_Weather18.tar.gz\": {\n        \"sha256\": \"48cea3add04aec2f91deba6d96207f72892c4f28a7ad8dbfbb67c9c402f121f2\",\n        \"size\": 314697692\n    },\n    \"PedestrianCrossing_Town12_Route14264_Weather19.tar.gz\": {\n        \"sha256\": \"c2e3c12f98773d9eed3182bb6f5383d792322c8ffda986911d87db525780d08c\",\n        \"size\": 642278986\n    },\n    \"PedestrianCrossing_Town12_Route14266_Weather21.tar.gz\": {\n        \"sha256\": \"0611a16d4fe6803e65c8f842bff34009e0d092fb19f88df690ecb30436eb7bb8\",\n        \"size\": 316260716\n    },\n    \"PedestrianCrossing_Town12_Route14267_Weather22.tar.gz\": {\n        \"sha256\": \"eb7a4ad1bff9ef20e1a01363b0cf0ec7db290c85a59ec4c0cf013d043e5875f8\",\n        \"size\": 473223199\n    },\n    \"PedestrianCrossing_Town12_Route14269_Weather23.tar.gz\": {\n        \"sha256\": \"effc10f3450de182947ead29da7a8e766b6770489757b1de4703ecc155066e88\",\n        \"size\": 399818469\n    },\n    \"PedestrianCrossing_Town12_Route14270_Weather25.tar.gz\": {\n        \"sha256\": \"67bbb338fb55c0ed49866c0965f2f490f7e8d122cc2706942c0ba46f47760699\",\n        \"size\": 114663975\n    },\n    \"PedestrianCrossing_Town12_Route14272_Weather1.tar.gz\": {\n        \"sha256\": \"adc4abb06e434ff43cc39f770b15775651506dce015cbc6e35d585c3421c073f\",\n        \"size\": 218710062\n    },\n    \"PedestrianCrossing_Town12_Route14273_Weather2.tar.gz\": {\n        \"sha256\": \"b20542c507c8ea3083db274f18e38165b63dc0d209dd90fd88809c822e153cc4\",\n        \"size\": 299322177\n    },\n    \"PedestrianCrossing_Town12_Route14274_Weather3.tar.gz\": {\n        \"sha256\": \"cf5ba4093949c9f93e59936ee5a0ada6c8af2de0db7b339612dc70025681f445\",\n        \"size\": 313081089\n    },\n    \"PedestrianCrossing_Town12_Route14275_Weather3.tar.gz\": {\n        \"sha256\": \"7a0fa72bd2efbbc8307aa4dced28acc2c127814300cba49beac432e054638bea\",\n        \"size\": 330534989\n    },\n    \"PedestrianCrossing_Town12_Route14276_Weather5.tar.gz\": {\n        \"sha256\": \"91f01d2cd8aa2d7c181fa8f6c07ad4f6f5b8f41d97a093ff896d12470477cc8e\",\n        \"size\": 280650319\n    },\n    \"PedestrianCrossing_Town12_Route14277_Weather6.tar.gz\": {\n        \"sha256\": \"7f3c54555ac6247911b40b599c3a9780db9ca8739b72121a01005889a966289f\",\n        \"size\": 434312000\n    },\n    \"PedestrianCrossing_Town12_Route14279_Weather8.tar.gz\": {\n        \"sha256\": \"e5bd97dee809128e3b2bda1b4b8debb12c10415ebf7028937a4163480f9538fe\",\n        \"size\": 193852018\n    },\n    \"PedestrianCrossing_Town12_Route14280_Weather9.tar.gz\": {\n        \"sha256\": \"eb1beed36ed1474d8a288ec25199298074d08ba615dfa9c620e0a356129a8d53\",\n        \"size\": 167051835\n    },\n    \"PedestrianCrossing_Town12_Route14281_Weather10.tar.gz\": {\n        \"sha256\": \"679f0e104ca7c8ec26567a157833fdde69bb870bb929e980a9edb39692f49c7d\",\n        \"size\": 159226056\n    },\n    \"PedestrianCrossing_Town12_Route14282_Weather11.tar.gz\": {\n        \"sha256\": \"19a141d4658269b63e73196f05b6abb8eeeedf24f515ea8b1d77bcaeeefaf050\",\n        \"size\": 225784267\n    },\n    \"PedestrianCrossing_Town12_Route14283_Weather12.tar.gz\": {\n        \"sha256\": \"daca5f880fee9394b2f683b56d4dc9740a4b61b8fbbdee70806ab304e96557c0\",\n        \"size\": 241132052\n    },\n    \"PedestrianCrossing_Town12_Route14286_Weather15.tar.gz\": {\n        \"sha256\": \"650dd5433aab49e5747d82576f2cd9fd2beb16b272b098fcf6fa53f3e0c33606\",\n        \"size\": 210875013\n    },\n    \"PedestrianCrossing_Town12_Route14287_Weather8.tar.gz\": {\n        \"sha256\": \"e209bc1109d932856142f627f810354181ebdf144f9988d6b39467e6c94ec8e2\",\n        \"size\": 477757806\n    },\n    \"PedestrianCrossing_Town12_Route14289_Weather18.tar.gz\": {\n        \"sha256\": \"621ff4c19780eb19c6d7df3a3b5af44729a142b4b1f4b5bc5cb60b2649a1142f\",\n        \"size\": 167535681\n    },\n    \"PedestrianCrossing_Town12_Route14290_Weather19.tar.gz\": {\n        \"sha256\": \"b2d2e9f9da3744637d437be92f7d0d8c5e65da6b391ea9120ca219dc06364dd4\",\n        \"size\": 513044657\n    },\n    \"PedestrianCrossing_Town12_Route14292_Weather21.tar.gz\": {\n        \"sha256\": \"b69aee6655ff9268e95601d7ed961e0245525de7f27d3ee0c825c1b930974baa\",\n        \"size\": 197899273\n    },\n    \"PedestrianCrossing_Town12_Route14294_Weather23.tar.gz\": {\n        \"sha256\": \"19d9e960279d6630fafb783f1a168a8a5be9df13d9b1046162c0cdb8ab3ce2e0\",\n        \"size\": 304324176\n    },\n    \"PedestrianCrossing_Town12_Route14295_Weather23.tar.gz\": {\n        \"sha256\": \"1589ab0e25cf719a13636f5690ddfb35381bb609a54a177e52f1347e91cc3cde\",\n        \"size\": 200116812\n    },\n    \"PedestrianCrossing_Town12_Route14296_Weather25.tar.gz\": {\n        \"sha256\": \"ec32fd39872f531b9441871fd32d3319070d6c19688ca76e3fb0db04369b7ab4\",\n        \"size\": 164350488\n    },\n    \"PedestrianCrossing_Town12_Route14297_Weather0.tar.gz\": {\n        \"sha256\": \"5dab5e5300c3e5452f8a6f056ca247d1575a42b7f5ecf5ed8d2a5275c5b871d4\",\n        \"size\": 228510032\n    },\n    \"PedestrianCrossing_Town12_Route14298_Weather1.tar.gz\": {\n        \"sha256\": \"daa5f88f06e99d216dcf04d6a0bfe615ba06e97153deeb06d18236cc744dd898\",\n        \"size\": 103225712\n    },\n    \"PedestrianCrossing_Town12_Route14299_Weather2.tar.gz\": {\n        \"sha256\": \"9377b4f2fb158cd48770a26efb7d9c8e35b3653d05bef63c5deb1ee10dedab53\",\n        \"size\": 234118221\n    },\n    \"PedestrianCrossing_Town12_Route14300_Weather3.tar.gz\": {\n        \"sha256\": \"1a2504401c0c27690101706f6fa1367cff4e8597c3c4c5671c874d222ef08c01\",\n        \"size\": 299958129\n    },\n    \"PedestrianCrossing_Town12_Route14301_Weather3.tar.gz\": {\n        \"sha256\": \"363a82fc07e051606656dbb7dcb576e3ebf74463c1d4295d06d713e78d6293ab\",\n        \"size\": 482706318\n    },\n    \"PedestrianCrossing_Town12_Route14302_Weather5.tar.gz\": {\n        \"sha256\": \"8cb4d1d81a4eae565077adfbfb12f09d3624f25bb29c58d4aa721b73748aa105\",\n        \"size\": 171239833\n    },\n    \"PedestrianCrossing_Town12_Route14303_Weather6.tar.gz\": {\n        \"sha256\": \"a8f17604f5ddd94ccf3246399a05a887b89b123ca3fc0fbf3fbce96d32dfb52d\",\n        \"size\": 350724361\n    },\n    \"PedestrianCrossing_Town12_Route14305_Weather8.tar.gz\": {\n        \"sha256\": \"c8bc731ac2600d8ca296ad8871d22418b8f28c70499a084443ac746eb3e2f8b8\",\n        \"size\": 179932775\n    },\n    \"PedestrianCrossing_Town12_Route14306_Weather9.tar.gz\": {\n        \"sha256\": \"a7a9664eb9acb2e7f5f4c5e76f3b74a96c848bc394ae11feac5765a5fb2a57f8\",\n        \"size\": 271007390\n    },\n    \"PedestrianCrossing_Town12_Route14307_Weather10.tar.gz\": {\n        \"sha256\": \"0d834b52c13cb95473478f17e407b4f5dd1f29b29d037701dee887dc88b87838\",\n        \"size\": 309243480\n    },\n    \"PedestrianCrossing_Town12_Route14308_Weather11.tar.gz\": {\n        \"sha256\": \"b448b7cf10d853299a90c0e94bb7a7b537710c394fad365289440285814c2218\",\n        \"size\": 165598329\n    },\n    \"PedestrianCrossing_Town12_Route14309_Weather12.tar.gz\": {\n        \"sha256\": \"9cb7236a7827fb862550a17cc3730cb73082cc2692303be52a17aaabdf3cae1c\",\n        \"size\": 94031507\n    },\n    \"PedestrianCrossing_Town12_Route14310_Weather13.tar.gz\": {\n        \"sha256\": \"972af3f3d12bb31016b6e82b0a10ef2ee43ebead2f4acd0cdaa7196692eb5d0a\",\n        \"size\": 478606665\n    },\n    \"PedestrianCrossing_Town12_Route14311_Weather14.tar.gz\": {\n        \"sha256\": \"c000b157a547aa6c6746650f95812e6713fcaefc92079b60004f9af42ffdf276\",\n        \"size\": 647836545\n    },\n    \"PedestrianCrossing_Town12_Route14312_Weather15.tar.gz\": {\n        \"sha256\": \"25ad7da4323f50830f2d0f76ea0502aff4917a21a60411ba54061691e93814bf\",\n        \"size\": 399580059\n    },\n    \"PedestrianCrossing_Town12_Route14313_Weather8.tar.gz\": {\n        \"sha256\": \"89927386917220cb1c398087a7bbf6238433fd6f56a8d136262c29de6bd7b705\",\n        \"size\": 308159875\n    },\n    \"PedestrianCrossing_Town12_Route14316_Weather19.tar.gz\": {\n        \"sha256\": \"4ed452ffe4c9976fbfe1132cc57f695131914ac775f084e7cc723295cf188017\",\n        \"size\": 446869941\n    },\n    \"PedestrianCrossing_Town12_Route14318_Weather21.tar.gz\": {\n        \"sha256\": \"6a28bd9648c149701884d23d009a7b8f563c5311a1401904dbd08de2a9bfbfd2\",\n        \"size\": 442872198\n    },\n    \"PedestrianCrossing_Town12_Route14320_Weather23.tar.gz\": {\n        \"sha256\": \"1ad8999671d308307035947522e616b5bf17b84062f39d735264d72cdacaec15\",\n        \"size\": 442261204\n    },\n    \"PedestrianCrossing_Town12_Route14321_Weather23.tar.gz\": {\n        \"sha256\": \"a1e0dfb4b5f175d18dd528ad0ef511d35cdd1118ed0968fe21cb685f0159a770\",\n        \"size\": 411807710\n    },\n    \"PedestrianCrossing_Town12_Route14322_Weather25.tar.gz\": {\n        \"sha256\": \"64e8c67a11aa6f1eaa55bf154760dc406e46fc82851a0ab73033e90351febc38\",\n        \"size\": 492630878\n    },\n    \"PedestrianCrossing_Town12_Route14323_Weather0.tar.gz\": {\n        \"sha256\": \"6878ca35ebb6542ec04bd241050de0af9aa23aea7e80810b5926c598a9363c08\",\n        \"size\": 105268027\n    },\n    \"PedestrianCrossing_Town12_Route14324_Weather1.tar.gz\": {\n        \"sha256\": \"247870c97bdf0683afd5630217240f8c11e9a7ad27993113c73231db99dfbd3a\",\n        \"size\": 239771797\n    },\n    \"PedestrianCrossing_Town12_Route14325_Weather2.tar.gz\": {\n        \"sha256\": \"78a706a14e47d891957a1029dd29bb66704fba2618f6252c69192a2caa48d29a\",\n        \"size\": 326294090\n    },\n    \"PedestrianCrossing_Town12_Route14326_Weather3.tar.gz\": {\n        \"sha256\": \"fd6d4a563e3ed4001589fabfd26a428bcd8e9192584f1c78738e97e9ccfef5d1\",\n        \"size\": 215030666\n    },\n    \"PedestrianCrossing_Town12_Route14328_Weather5.tar.gz\": {\n        \"sha256\": \"3ffa17dd1d78874b13cdf630e7c9346316275630519c1a72969e1cf6e019abd6\",\n        \"size\": 461888707\n    },\n    \"PedestrianCrossing_Town12_Route14329_Weather6.tar.gz\": {\n        \"sha256\": \"3ba225e0c51917b0c0472330dffe2254f140af81b5316f4ff4ee4d35943d894e\",\n        \"size\": 230577600\n    },\n    \"PedestrianCrossing_Town12_Route14330_Weather7.tar.gz\": {\n        \"sha256\": \"cf237ccee231b72f08f28c67bd47c7281d7b6a14048a8f9d3aae44c2da49c3f9\",\n        \"size\": 551501930\n    },\n    \"PedestrianCrossing_Town12_Route14332_Weather9.tar.gz\": {\n        \"sha256\": \"563f215f475b5cd0a9264a6e39bb5cd08fa36f02027f39f5dffedce9d6e8796c\",\n        \"size\": 143830555\n    },\n    \"PedestrianCrossing_Town12_Route14334_Weather11.tar.gz\": {\n        \"sha256\": \"63846a1b04b0e7537d1ae0563405051c92698028800e84c43d2185b964348ff7\",\n        \"size\": 336152428\n    },\n    \"PedestrianCrossing_Town12_Route14335_Weather12.tar.gz\": {\n        \"sha256\": \"d1e06d2d61b58ece9d4fc3ab6686e9a6eda925ee1a2035e4fa3b89fe6b46eb0c\",\n        \"size\": 270489027\n    },\n    \"PedestrianCrossing_Town12_Route14336_Weather13.tar.gz\": {\n        \"sha256\": \"97a96d8f38449f0397200499a93191726445c6a653882a683630d7b48c030d0d\",\n        \"size\": 340486124\n    },\n    \"PedestrianCrossing_Town12_Route14337_Weather14.tar.gz\": {\n        \"sha256\": \"4f1a3e6f7f9b856a63255e7be88292df29fd548a47ab5387ab7aae0335cd1ddd\",\n        \"size\": 182541823\n    },\n    \"PedestrianCrossing_Town12_Route14338_Weather15.tar.gz\": {\n        \"sha256\": \"6c9dd82eb1a626f432e14691ba74bc5cf504b585922d71a496e226e11c3ee2d1\",\n        \"size\": 232604448\n    },\n    \"PedestrianCrossing_Town12_Route14339_Weather8.tar.gz\": {\n        \"sha256\": \"1f6038d2e4a5fead75847c74d3cb429e9df1a7ef6352b3356c79998ec7bac3a3\",\n        \"size\": 180242466\n    },\n    \"PedestrianCrossing_Town12_Route14340_Weather9.tar.gz\": {\n        \"sha256\": \"cf4491bf5ed85e021ab85742f3752d153eaa68af826ea2af543133e63aaea8fa\",\n        \"size\": 151156760\n    },\n    \"PedestrianCrossing_Town12_Route14341_Weather18.tar.gz\": {\n        \"sha256\": \"0d7a8b25698f0e20d187870c1e6bff35a7078836a603afbf3c57e4225928f1b8\",\n        \"size\": 402547952\n    },\n    \"PedestrianCrossing_Town12_Route14342_Weather19.tar.gz\": {\n        \"sha256\": \"5294bc439b3bda4fc2a195cae0dea4a4295e58fa599b519a34308c696a4b5492\",\n        \"size\": 243876402\n    },\n    \"PedestrianCrossing_Town12_Route14343_Weather20.tar.gz\": {\n        \"sha256\": \"44435fce7c91952841f51d1e80a3a773e8eebb2e760def9695a07ab31c8e05ab\",\n        \"size\": 519720298\n    },\n    \"PedestrianCrossing_Town12_Route14344_Weather21.tar.gz\": {\n        \"sha256\": \"03e4d8de465bb8a92aa9a74ea86f3b9403d348cc35726af7205c2a22ec74bc74\",\n        \"size\": 543780764\n    },\n    \"PedestrianCrossing_Town12_Route14345_Weather22.tar.gz\": {\n        \"sha256\": \"ae0abced4fd3e5be2924406939d751b5b02fcd257434776b87c7f0a5618eb9b9\",\n        \"size\": 430904273\n    },\n    \"PedestrianCrossing_Town12_Route14346_Weather23.tar.gz\": {\n        \"sha256\": \"991fcc3989aa5947a15ec97a865d7a081b408c1ed1be47fbb1756c558d7bd244\",\n        \"size\": 196950935\n    },\n    \"PedestrianCrossing_Town12_Route14349_Weather0.tar.gz\": {\n        \"sha256\": \"d47e37dc8e98560c74555bc994a17835961bd81b1ca831e2bc058f6a6f36db80\",\n        \"size\": 349405569\n    },\n    \"PedestrianCrossing_Town12_Route14350_Weather1.tar.gz\": {\n        \"sha256\": \"0db2eea618777f8b3af60e3d121ec2eedfa1e581ed815c580406c0e12cba2c2e\",\n        \"size\": 586331495\n    },\n    \"PedestrianCrossing_Town12_Route14351_Weather2.tar.gz\": {\n        \"sha256\": \"1bc8dc8c51da70e68f032f074873f464eab40aaf3106a3336454254f54d79570\",\n        \"size\": 256963565\n    },\n    \"PedestrianCrossing_Town12_Route14352_Weather3.tar.gz\": {\n        \"sha256\": \"b6fcfa494db0bc19d82fe1f9cf871bc067ac600c985039e04c299abe7c4fa537\",\n        \"size\": 514283977\n    },\n    \"PedestrianCrossing_Town12_Route14354_Weather5.tar.gz\": {\n        \"sha256\": \"bc7df18ceb98e2f0c4c48505e5b58ed8bff41221a0956f14a21f5e1bfd5bdd51\",\n        \"size\": 311972563\n    },\n    \"PedestrianCrossing_Town12_Route14355_Weather6.tar.gz\": {\n        \"sha256\": \"21de776660048026ef9cf3d38cd694e0d7aa2e37234e99e4db4ff64c85643151\",\n        \"size\": 299529140\n    },\n    \"PedestrianCrossing_Town12_Route14356_Weather7.tar.gz\": {\n        \"sha256\": \"d56930f57193c57e07138d9374e00b304c5b9b09eda3e445554cf24e320b6f4a\",\n        \"size\": 413729813\n    },\n    \"PedestrianCrossing_Town12_Route14357_Weather8.tar.gz\": {\n        \"sha256\": \"31488bb125b43fafcbccbd7476e879616a9096d22fad5966a647cc45c6e04203\",\n        \"size\": 320883196\n    },\n    \"PedestrianCrossing_Town12_Route14358_Weather9.tar.gz\": {\n        \"sha256\": \"28fe5ee6bf2a4426e4d6b6320e54a0cc0f45ca8c17dd602ffaae1cea080cbb67\",\n        \"size\": 182691005\n    },\n    \"PedestrianCrossing_Town12_Route14359_Weather10.tar.gz\": {\n        \"sha256\": \"d09cf074a07084a87f7df865b48decb1b6ba1b621c9e2d9c374370d9c231c841\",\n        \"size\": 329090385\n    },\n    \"PedestrianCrossing_Town12_Route14361_Weather12.tar.gz\": {\n        \"sha256\": \"285c7362dece1baf4342f0e50fbc76d863460a7e2e4ea9b3653a287b0615a382\",\n        \"size\": 333567940\n    },\n    \"PedestrianCrossing_Town12_Route14362_Weather13.tar.gz\": {\n        \"sha256\": \"8d17991de9863c5ed81949981edfc596f4479682543ae8c824a4b8e2143eabe0\",\n        \"size\": 272532528\n    },\n    \"PedestrianCrossing_Town12_Route14364_Weather15.tar.gz\": {\n        \"sha256\": \"3b17c3df9d9b52d1831921bfbc140bb3ee1545a1c5324f13dfa660d0f4e0cf1d\",\n        \"size\": 113257749\n    },\n    \"PedestrianCrossing_Town12_Route14365_Weather8.tar.gz\": {\n        \"sha256\": \"3c46dd5bf618ae5245bb1da139995d91a6e645e256e23bb7c9f6950a59f81b93\",\n        \"size\": 224781296\n    },\n    \"PedestrianCrossing_Town12_Route14366_Weather9.tar.gz\": {\n        \"sha256\": \"436f5d723d684375d4fc4770c48a399bf54e1ae880d0f20bcbd5345142b8aaa8\",\n        \"size\": 299856351\n    },\n    \"PedestrianCrossing_Town12_Route14367_Weather18.tar.gz\": {\n        \"sha256\": \"4bc202ce305454435e151d524f2ae1630050974dd1e26e5fd862615055e8b580\",\n        \"size\": 179487950\n    },\n    \"PedestrianCrossing_Town12_Route14368_Weather19.tar.gz\": {\n        \"sha256\": \"079384de7fa7a4511fbbc441002a72a16df74fd55b279fd87d7d074004e7deef\",\n        \"size\": 233125684\n    },\n    \"PedestrianCrossing_Town12_Route14369_Weather20.tar.gz\": {\n        \"sha256\": \"f057868dcbbeffe774932109fed940d35b86b6bdc4c9432a4f6b6d61573d3518\",\n        \"size\": 342329586\n    },\n    \"PedestrianCrossing_Town12_Route14371_Weather22.tar.gz\": {\n        \"sha256\": \"f714f7c9a1226ec41cfaac89cab6b62390e1e09cb68837eb4771eda37bd6e912\",\n        \"size\": 289957529\n    },\n    \"PedestrianCrossing_Town12_Route14372_Weather23.tar.gz\": {\n        \"sha256\": \"8d19e5f86b331e5c49585d0ffcd6563ba9348bb7399b1165f307fe9345c40b6e\",\n        \"size\": 97057941\n    },\n    \"PedestrianCrossing_Town12_Route14375_Weather0.tar.gz\": {\n        \"sha256\": \"f13104dedc7c658036b57ec95a227c0940fdbb1ce242d83bed5ec7980d707b76\",\n        \"size\": 410929018\n    },\n    \"PedestrianCrossing_Town12_Route14376_Weather1.tar.gz\": {\n        \"sha256\": \"5d44c0a0a573f954d53e0ba5955e7c284316ab755aee1c8f6be3e911f5fc55b6\",\n        \"size\": 198707885\n    },\n    \"PedestrianCrossing_Town12_Route14377_Weather2.tar.gz\": {\n        \"sha256\": \"a69b484c0a8f1224acae192d1905d80d461125cb2c608545da96953f8e8c801c\",\n        \"size\": 565752734\n    },\n    \"PedestrianCrossing_Town12_Route14378_Weather3.tar.gz\": {\n        \"sha256\": \"11cb6d9fc520f106df16e06f3c1355da57b5b8237fd5fff96a61be893f95fa9c\",\n        \"size\": 324864951\n    },\n    \"PedestrianCrossing_Town12_Route14379_Weather3.tar.gz\": {\n        \"sha256\": \"af77e543706a146c688f82875105d034ddf829c1315f1a5aacd780f783882d79\",\n        \"size\": 511248976\n    },\n    \"PedestrianCrossing_Town12_Route14380_Weather5.tar.gz\": {\n        \"sha256\": \"3780675810aaa3cc75b6f2c3388536cdabe9c58278621d1fe73b80ec719775cd\",\n        \"size\": 289786790\n    },\n    \"PedestrianCrossing_Town12_Route14381_Weather6.tar.gz\": {\n        \"sha256\": \"f64654baface4f8777630b1336900a2913fd5a464f4dd29050bdb796a9c03fff\",\n        \"size\": 135534928\n    },\n    \"PedestrianCrossing_Town12_Route14382_Weather7.tar.gz\": {\n        \"sha256\": \"62d943eef9b9c913fac5906b1ba56cba2c9ae9a5fab77fead42b4fd0b9183f22\",\n        \"size\": 309405954\n    },\n    \"PedestrianCrossing_Town12_Route14384_Weather9.tar.gz\": {\n        \"sha256\": \"f2398893f535ae3660d879f31d7df1a43544666da1f196af9a7fd0f568a4abb5\",\n        \"size\": 133577450\n    },\n    \"PedestrianCrossing_Town12_Route14385_Weather10.tar.gz\": {\n        \"sha256\": \"15542864ac27fdf0ae943de7a44b1f6878e9b835d9983de7f00caab0d33cd785\",\n        \"size\": 204139328\n    },\n    \"PedestrianCrossing_Town12_Route14386_Weather11.tar.gz\": {\n        \"sha256\": \"06923e7828a633eee2888381df5f721674551ebb40abf49f624346b0f48c152f\",\n        \"size\": 190978903\n    },\n    \"PedestrianCrossing_Town12_Route14388_Weather13.tar.gz\": {\n        \"sha256\": \"f5d6c10516a27b7a549191d6e0d7a09c409f4158da6c38b7ae3c64f3a2d23dfd\",\n        \"size\": 338452163\n    },\n    \"PedestrianCrossing_Town12_Route14389_Weather14.tar.gz\": {\n        \"sha256\": \"ca891bdc5b40d8544b4842b7b24245ffa74306516805505c2082e058d4e0d14b\",\n        \"size\": 317654434\n    },\n    \"PedestrianCrossing_Town12_Route14390_Weather15.tar.gz\": {\n        \"sha256\": \"91309560e63ec1bed4d680b5a4cff3bd8c400177796e94067233472b9143c6fb\",\n        \"size\": 476817319\n    },\n    \"PedestrianCrossing_Town12_Route14391_Weather8.tar.gz\": {\n        \"sha256\": \"3a118c19217fd64e9b8da4fe247f496653de35712f87d0ef3ec09cff6993b43e\",\n        \"size\": 543163369\n    },\n    \"PedestrianCrossing_Town12_Route14392_Weather9.tar.gz\": {\n        \"sha256\": \"4b044cd44517d351306890e64766743b815a243a4015ca4626292fb95ca49646\",\n        \"size\": 242218549\n    },\n    \"PedestrianCrossing_Town12_Route14393_Weather18.tar.gz\": {\n        \"sha256\": \"23db220f161df63a06240ae248b76c9b97df32d25cfe02057a45a7886fdeaf0d\",\n        \"size\": 356924058\n    },\n    \"PedestrianCrossing_Town12_Route14396_Weather21.tar.gz\": {\n        \"sha256\": \"4269e5acd6269d0b888ff8aa5219b24d5e295f004edcab4701019ca97364afa2\",\n        \"size\": 293214866\n    },\n    \"PedestrianCrossing_Town12_Route14397_Weather22.tar.gz\": {\n        \"sha256\": \"f87ca2b6e6e815284ce31b521f41133d1cca85326ae4d26cccf72dc9eb65bba5\",\n        \"size\": 337464701\n    },\n    \"PedestrianCrossing_Town12_Route14398_Weather23.tar.gz\": {\n        \"sha256\": \"80aa73bea2bfafdc816b324c5f38ba6c43c7afa2044db3af6c7b7ff00b8ce204\",\n        \"size\": 188055010\n    },\n    \"PedestrianCrossing_Town12_Route14399_Weather23.tar.gz\": {\n        \"sha256\": \"2e03c46594a8f1d4df17b12baeb3b5ad8cc42f6ee1bf3c8c114b428f737f9596\",\n        \"size\": 382928761\n    },\n    \"PedestrianCrossing_Town12_Route14400_Weather25.tar.gz\": {\n        \"sha256\": \"03bf295ccd90bd9b8f1f8308754a653fe69cdb2a840f378abba9db9a10e9ea9b\",\n        \"size\": 623813151\n    },\n    \"PedestrianCrossing_Town12_Route14401_Weather0.tar.gz\": {\n        \"sha256\": \"ff000eb3bd6bf4c8978b29d44e84bfd8c95f16c9c18e9d44ec357a774ba7af31\",\n        \"size\": 436575513\n    },\n    \"PedestrianCrossing_Town12_Route14402_Weather1.tar.gz\": {\n        \"sha256\": \"e452e700e768596c32636967d3ae3b0569bcf2902421e5c4fcf73f3abc3cb709\",\n        \"size\": 293865965\n    },\n    \"PedestrianCrossing_Town12_Route14403_Weather2.tar.gz\": {\n        \"sha256\": \"627de18cf6cfbf8be06cdc0db556a683be24d3256e9f723a74180469c5c3dce2\",\n        \"size\": 415126503\n    },\n    \"PedestrianCrossing_Town12_Route14404_Weather3.tar.gz\": {\n        \"sha256\": \"a413a8d24515e9f34dc29d7946ec78ec5618ef01f796adb4d4b7bda209eec4bd\",\n        \"size\": 514255871\n    },\n    \"PedestrianCrossing_Town12_Route14405_Weather3.tar.gz\": {\n        \"sha256\": \"6699ece1e38da1a68ffca6eee76ad9e09ecee60fc7f94e588f834035700b6a79\",\n        \"size\": 211152568\n    },\n    \"PedestrianCrossing_Town12_Route14406_Weather5.tar.gz\": {\n        \"sha256\": \"0dd84969179f375fa3b846aa90d1a5d4a7243bec7075641b21debcf3e3fe4fa5\",\n        \"size\": 253076358\n    },\n    \"PedestrianCrossing_Town12_Route14407_Weather6.tar.gz\": {\n        \"sha256\": \"b7c0dd2cfdaa0cb30ce5b752e287fd6b595b9ef0c9a2840a207c1c59476fe92d\",\n        \"size\": 391401941\n    },\n    \"PedestrianCrossing_Town12_Route14408_Weather7.tar.gz\": {\n        \"sha256\": \"e40b75820274d24a78142935d2f78268e7903342dc752e51d23e4cb3f0015233\",\n        \"size\": 619477444\n    },\n    \"PedestrianCrossing_Town12_Route14409_Weather8.tar.gz\": {\n        \"sha256\": \"62398d944644ca476feef62ad04cc809576f14c9d5beac40d6e1d69c11fbb2cd\",\n        \"size\": 334477679\n    },\n    \"PedestrianCrossing_Town12_Route14411_Weather10.tar.gz\": {\n        \"sha256\": \"8c6078b562df749ede641ee02c8389f7dc78ec552a96fa81ac801a631624fea3\",\n        \"size\": 361970333\n    },\n    \"PedestrianCrossing_Town12_Route14412_Weather11.tar.gz\": {\n        \"sha256\": \"2e57e4aca8e792387750557c1a6357212feb7b9422fe91cb3e27bdbbf74240b9\",\n        \"size\": 329482645\n    },\n    \"PedestrianCrossing_Town12_Route14414_Weather13.tar.gz\": {\n        \"sha256\": \"a8c8bfa343f7e4161c7bbc883991232db828fcd958690c3ce208192c60805d9b\",\n        \"size\": 320850644\n    },\n    \"PedestrianCrossing_Town12_Route14415_Weather14.tar.gz\": {\n        \"sha256\": \"ea433f84ff52247a9356ec624f271092b86a4119a1a7afacc9fbb30130bfa849\",\n        \"size\": 412958483\n    },\n    \"PedestrianCrossing_Town12_Route14418_Weather9.tar.gz\": {\n        \"sha256\": \"d3218639fa21ee8191c5b3f80274e7b8f08c7a874f0e65f515f463bf64902c14\",\n        \"size\": 179972982\n    },\n    \"PedestrianCrossing_Town12_Route14419_Weather18.tar.gz\": {\n        \"sha256\": \"88dff54d51cbb5abed96e49c5da423773a6f470d34abd38613ec73ec78ffbbe7\",\n        \"size\": 770111707\n    },\n    \"PedestrianCrossing_Town12_Route14421_Weather20.tar.gz\": {\n        \"sha256\": \"5af5ba8988381b20f7087374c42321b8d95c610140314123e4d5228b09e1efbe\",\n        \"size\": 339471219\n    },\n    \"PedestrianCrossing_Town12_Route14423_Weather22.tar.gz\": {\n        \"sha256\": \"8b3e8041b569a72d0f79e37d9272ca1101aa17454d10fa0c3e7bfda6594598fb\",\n        \"size\": 406934462\n    },\n    \"PedestrianCrossing_Town12_Route14424_Weather23.tar.gz\": {\n        \"sha256\": \"6480fd97fea8292df1acbb9f8fafacca268fe88fb0a14226a85db09a481ea9d6\",\n        \"size\": 283110822\n    },\n    \"PedestrianCrossing_Town12_Route14425_Weather23.tar.gz\": {\n        \"sha256\": \"5dd60c45a4c0ec0651fea25936e53e0a2dfedcb59672722825b995218dc28eb2\",\n        \"size\": 237364214\n    },\n    \"PedestrianCrossing_Town12_Route14426_Weather25.tar.gz\": {\n        \"sha256\": \"8b0eeb119494321410fb3a3fe83f6b9e86525ea0e98ab44bb56cf97ea8faa52a\",\n        \"size\": 370292051\n    },\n    \"PedestrianCrossing_Town12_Route14427_Weather0.tar.gz\": {\n        \"sha256\": \"8bcf2548d51505c25d8c3fdd3e5e327f022a58c1ab3650d3b67c79db0e29370f\",\n        \"size\": 251042236\n    },\n    \"PedestrianCrossing_Town12_Route14428_Weather1.tar.gz\": {\n        \"sha256\": \"55095931e5cfed37c273290f424a7cc9adf0aa5b95ab113b701433d483ccaa28\",\n        \"size\": 382150828\n    },\n    \"PedestrianCrossing_Town12_Route14429_Weather2.tar.gz\": {\n        \"sha256\": \"198e59cb384ef8d07a3907fc788988033d362bfa32d91ceb274bae9aa43a599c\",\n        \"size\": 94002707\n    },\n    \"PedestrianCrossing_Town12_Route14430_Weather3.tar.gz\": {\n        \"sha256\": \"f80d14f8901e9fe1dd3f4562bd9b0d70a594d40e87279eea93a0e24cec0d8abc\",\n        \"size\": 620720285\n    },\n    \"PedestrianCrossing_Town12_Route14431_Weather3.tar.gz\": {\n        \"sha256\": \"797dd7eeac82a2ced4494a402048306a4bacdf030b8fb2453e2d7da244580dd5\",\n        \"size\": 412782778\n    },\n    \"PedestrianCrossing_Town12_Route14432_Weather5.tar.gz\": {\n        \"sha256\": \"f1cbafb515a440a41ed395cb351b1d4044e14cbd69ca88f425f4580c5486c583\",\n        \"size\": 316939490\n    },\n    \"PedestrianCrossing_Town12_Route14433_Weather6.tar.gz\": {\n        \"sha256\": \"5344f3bf6ec11eee75d52b51065f3fa4c8d82887c3f548bec673a1aeec83ed94\",\n        \"size\": 389527697\n    },\n    \"PedestrianCrossing_Town12_Route14434_Weather7.tar.gz\": {\n        \"sha256\": \"e3ccbbfbf2dc762249b4a900cd0316df142a7f00591689bf7f274df1d07bd0aa\",\n        \"size\": 121190424\n    },\n    \"PedestrianCrossing_Town12_Route14435_Weather8.tar.gz\": {\n        \"sha256\": \"e69d430ca1aa5db2ace6e6869cfa1b08394383b562126a6b6f220454421c8308\",\n        \"size\": 1021377173\n    },\n    \"PedestrianCrossing_Town12_Route14436_Weather9.tar.gz\": {\n        \"sha256\": \"d85b0bedabab0b766a3b9fb714c91c08327fdc7c4d24b49ae7d25b7dfe76b6a1\",\n        \"size\": 344070405\n    },\n    \"PedestrianCrossing_Town12_Route14437_Weather10.tar.gz\": {\n        \"sha256\": \"47bd994c76c3af78a7a58d97768b31f157f659c34f88d7cf0c871824b823a8bf\",\n        \"size\": 283661983\n    },\n    \"PedestrianCrossing_Town12_Route14438_Weather11.tar.gz\": {\n        \"sha256\": \"a5052c7de9bf3ac11514b2ab61b410c46bd6ddc4bdb2795111b133f361736a58\",\n        \"size\": 391807929\n    },\n    \"PedestrianCrossing_Town12_Route14439_Weather12.tar.gz\": {\n        \"sha256\": \"7e769667877e0797aac26815dd7d84977fc313a0ea3b292c1bef729d22d1f9e2\",\n        \"size\": 76552666\n    },\n    \"PedestrianCrossing_Town12_Route14440_Weather13.tar.gz\": {\n        \"sha256\": \"a5436b32e9e4c88c11074257c8326adc9bf05b9b1def56b074fdf62e12322fc4\",\n        \"size\": 1105542016\n    },\n    \"PedestrianCrossing_Town12_Route14441_Weather14.tar.gz\": {\n        \"sha256\": \"366742609e096e0d7ac888d85efdeb93decf3f4c3273bb6fd0cbdd8c8c2ad134\",\n        \"size\": 164186516\n    },\n    \"PedestrianCrossing_Town12_Route14444_Weather9.tar.gz\": {\n        \"sha256\": \"c5f0b8e1b4765d5cf4873290ae87227d1dc8218422fc5336c5ac7d42cd0eb6b8\",\n        \"size\": 247256281\n    },\n    \"PedestrianCrossing_Town12_Route14445_Weather18.tar.gz\": {\n        \"sha256\": \"7c0ff247338f0e4d59a2b8c2a840be3a2d847be83f1fa0cdfe48bdfed3cda968\",\n        \"size\": 403844793\n    },\n    \"PedestrianCrossing_Town12_Route14446_Weather19.tar.gz\": {\n        \"sha256\": \"d5130e1bb3dc17662e327bf2c09125f7275fd246c32587bdc50e218fb9afca46\",\n        \"size\": 610229303\n    },\n    \"PedestrianCrossing_Town12_Route14450_Weather23.tar.gz\": {\n        \"sha256\": \"c38af0382e28b61923f3514465b56795153cabb02533cdedcf257eccf1bd59ca\",\n        \"size\": 428008331\n    },\n    \"PedestrianCrossing_Town12_Route14451_Weather23.tar.gz\": {\n        \"sha256\": \"4b3a26f084097e0c3b8bb8edd8f6e4b07bed28656a4473ea5abd8799a8614da2\",\n        \"size\": 144609909\n    },\n    \"PedestrianCrossing_Town12_Route14452_Weather25.tar.gz\": {\n        \"sha256\": \"8dfddc816abf81ec7efb8af69ac1bfa0538852345dbba55de1c116ffc382526e\",\n        \"size\": 80999935\n    },\n    \"PedestrianCrossing_Town12_Route14454_Weather1.tar.gz\": {\n        \"sha256\": \"8b03739cb71ae1a9bf80d6d32102ed765ee0d1ca05d2aefe08597ad4cb7854d6\",\n        \"size\": 337266623\n    },\n    \"PedestrianCrossing_Town12_Route14455_Weather2.tar.gz\": {\n        \"sha256\": \"9c5ef784d26a4749ae5ccd3f92984416dbd2a28b6140cdc922bc5fa370424b19\",\n        \"size\": 288258807\n    },\n    \"PedestrianCrossing_Town12_Route14456_Weather3.tar.gz\": {\n        \"sha256\": \"6e8d80c6e4476188073ed530cd3e64617b72c396f4d1d50b06a1886233b78435\",\n        \"size\": 673901199\n    },\n    \"PedestrianCrossing_Town12_Route2324_Weather3.tar.gz\": {\n        \"sha256\": \"20d27fc36fa2873ff777d6606756649d8fda48a9a625885029f5748e233c42a0\",\n        \"size\": 186770377\n    },\n    \"PedestrianCrossing_Town12_Route2325_Weather5.tar.gz\": {\n        \"sha256\": \"1c6e416ba69dc96edc785af42b54d60f62549485473038f9803e7480d3ff5c28\",\n        \"size\": 356730246\n    },\n    \"PedestrianCrossing_Town12_Route2326_Weather6.tar.gz\": {\n        \"sha256\": \"f3d53f136c3048f9ac0b45234aa3d2ac81d8473332cf4237049044291ee06776\",\n        \"size\": 296106443\n    },\n    \"PedestrianCrossing_Town12_Route2327_Weather7.tar.gz\": {\n        \"sha256\": \"910ecff24ff5e64355f68faa29572c1dd0f62983203be4b13bfa2519d13417d6\",\n        \"size\": 799337118\n    },\n    \"PedestrianCrossing_Town12_Route2328_Weather8.tar.gz\": {\n        \"sha256\": \"8e9f40be05416d1dfde628132ea2154a648b1d67f6c1ccf76edbd5cc575a097a\",\n        \"size\": 345293333\n    },\n    \"PedestrianCrossing_Town12_Route2330_Weather10.tar.gz\": {\n        \"sha256\": \"3cffe0cdf477d0f539bad02b01ce6a5a35ef72695e26313b5b508cce43829fba\",\n        \"size\": 313619361\n    },\n    \"PedestrianCrossing_Town12_Route2331_Weather11.tar.gz\": {\n        \"sha256\": \"fecd9b67d22c8e7437ef863a0167015e542fb041b72fa6e61d56cbf9f96295b4\",\n        \"size\": 433637040\n    },\n    \"PedestrianCrossing_Town12_Route2333_Weather13.tar.gz\": {\n        \"sha256\": \"26a3ecbd45c212b8bab24066db27c66587d08401ae0e3f2e68a0607dbb0ba3cd\",\n        \"size\": 270173419\n    },\n    \"PedestrianCrossing_Town12_Route2336_Weather8.tar.gz\": {\n        \"sha256\": \"6d8b0c7aac84d504697e7a9fe38adb0934bd2e4c98704b0e332dcc56c7aeb382\",\n        \"size\": 343086957\n    },\n    \"PedestrianCrossing_Town12_Route2337_Weather9.tar.gz\": {\n        \"sha256\": \"b4da33575624bb72476999c070d51defa37e334e3f1c6718cdfdec84d1996f75\",\n        \"size\": 144252229\n    },\n    \"PedestrianCrossing_Town12_Route2338_Weather18.tar.gz\": {\n        \"sha256\": \"0623ac7f9d5fe433ca8b11ccc7d79fc3fb0b76580ebf9db82e5de30a773b6f42\",\n        \"size\": 186814023\n    },\n    \"PedestrianCrossing_Town12_Route2341_Weather21.tar.gz\": {\n        \"sha256\": \"a745957f1804fd803967478c2ed630a045bae7036cd5f4ea746005130e681a8f\",\n        \"size\": 232378495\n    },\n    \"PedestrianCrossing_Town12_Route2342_Weather22.tar.gz\": {\n        \"sha256\": \"27a25e6abaed6341a04203f488fa03b1111b22b61f20590f25102151acc2ab54\",\n        \"size\": 319606335\n    },\n    \"PedestrianCrossing_Town12_Route2343_Weather23.tar.gz\": {\n        \"sha256\": \"a18abb3d74ba3c782a33cac70e4137c07668a9dd7032a4bfc6effcd05da72f75\",\n        \"size\": 364790054\n    },\n    \"PedestrianCrossing_Town12_Route3104_Weather3.tar.gz\": {\n        \"sha256\": \"c8200388dc80567bd1b4cc9743473fba94b78b46e1ec181b4042a7d901ef322a\",\n        \"size\": 213273081\n    },\n    \"PedestrianCrossing_Town12_Route3105_Weather5.tar.gz\": {\n        \"sha256\": \"edc0a7cb8b6f8b63ab9a1d0373b7f1eec2284c68f85b80b9a13cea7bc84458f6\",\n        \"size\": 290698072\n    },\n    \"PedestrianCrossing_Town12_Route3106_Weather6.tar.gz\": {\n        \"sha256\": \"50bfad81dd3faadf8bbea71100c0f41a8890124db04ff68ab9fd9189e11c1f2c\",\n        \"size\": 156774393\n    },\n    \"PedestrianCrossing_Town12_Route3107_Weather7.tar.gz\": {\n        \"sha256\": \"bb16aa9e92d6af8d4a0472c0a63bc6fb4d936e1abbe85e512609018d14c244b0\",\n        \"size\": 149332882\n    },\n    \"PedestrianCrossing_Town12_Route3108_Weather8.tar.gz\": {\n        \"sha256\": \"8dd8ef95701569b04a7530d6505e47189d52571266e908a40b846785b025eb06\",\n        \"size\": 327882155\n    },\n    \"PedestrianCrossing_Town12_Route3109_Weather9.tar.gz\": {\n        \"sha256\": \"f030358da6167810016bc7d967634d7e400108835a58011d9cc4dbb680b5a9bf\",\n        \"size\": 138484292\n    },\n    \"PedestrianCrossing_Town12_Route3110_Weather10.tar.gz\": {\n        \"sha256\": \"b283779f87877aaa2138b3097b6cb77f4c67180f8245fa2799475cc5b0465d0e\",\n        \"size\": 199292903\n    },\n    \"PedestrianCrossing_Town12_Route3113_Weather13.tar.gz\": {\n        \"sha256\": \"6c20ca0e2fbfcd17b8637289a57230ea41efbc03d9eb81fa6d84a03327853751\",\n        \"size\": 185808026\n    },\n    \"PedestrianCrossing_Town12_Route3115_Weather15.tar.gz\": {\n        \"sha256\": \"ab1b8c3d9ae0ddf5303bac7de032db5576f6623290e78fd1e868e5d623804c4d\",\n        \"size\": 188471297\n    },\n    \"PedestrianCrossing_Town12_Route3117_Weather9.tar.gz\": {\n        \"sha256\": \"3d9fa6fa13cd78135494124b3abb55b0b5740d7b9bf0a8e2bcf36bb8ef83a627\",\n        \"size\": 189315314\n    },\n    \"PedestrianCrossing_Town12_Route3118_Weather18.tar.gz\": {\n        \"sha256\": \"29e4d2ac4a6785a309d4fa3613a9465c8861a65944ea96f6d62b25ccd56dcf8f\",\n        \"size\": 279558342\n    },\n    \"PedestrianCrossing_Town12_Route3119_Weather19.tar.gz\": {\n        \"sha256\": \"b58cef12543e9cc1fc2cf35933c8f74a16ffb3924ef94b303254b455c69e9eee\",\n        \"size\": 222156105\n    },\n    \"PedestrianCrossing_Town12_Route3120_Weather20.tar.gz\": {\n        \"sha256\": \"ea62168900b5c3dfb7a207f993d7394a9d5419e16be43ded974a74df3770b6a2\",\n        \"size\": 191580507\n    },\n    \"PedestrianCrossing_Town12_Route3121_Weather21.tar.gz\": {\n        \"sha256\": \"4508f6e915923e02a00642e22c9ef58e0f468af50b0843b9ff65696180be3a6a\",\n        \"size\": 177633434\n    },\n    \"PedestrianCrossing_Town12_Route3122_Weather22.tar.gz\": {\n        \"sha256\": \"e6caf12f85c3533c3e7cbb29c623843e75ffe615226ff6ebdd539d36830dc6ab\",\n        \"size\": 432304752\n    },\n    \"PedestrianCrossing_Town12_Route3123_Weather23.tar.gz\": {\n        \"sha256\": \"be0eb671969477fbc74327a3fa0aad815175206f69037f37a079bac8b0434ba1\",\n        \"size\": 256205562\n    },\n    \"PedestrianCrossing_Town13_Route3823_Weather22.tar.gz\": {\n        \"sha256\": \"2b4573ede2dd665a6d953762d69221a27b411a82ac6ce2c6cf8055a401b78acc\",\n        \"size\": 126750866\n    },\n    \"PedestrianCrossing_Town13_Route3824_Weather23.tar.gz\": {\n        \"sha256\": \"d7e96c6b13f9d19b25306e3f8a872f2c51bc5e73932f1ea8038474f9b138889e\",\n        \"size\": 173496702\n    },\n    \"PedestrianCrossing_Town13_Route3825_Weather23.tar.gz\": {\n        \"sha256\": \"280e8cfc3a9ebb2224ff716c005bd1fe9dc098e6e390fb03ddafa923199a319a\",\n        \"size\": 471109448\n    },\n    \"PedestrianCrossing_Town13_Route3826_Weather25.tar.gz\": {\n        \"sha256\": \"917ea088138b1bb2b3aee7135a11a35119fbae7d542881103c011b6d88dada52\",\n        \"size\": 176926597\n    },\n    \"PedestrianCrossing_Town13_Route3827_Weather0.tar.gz\": {\n        \"sha256\": \"c470a520f5c17c9fafee280788bbef3489ac48f3a1ddf36050a6653ff4cc3f40\",\n        \"size\": 135251201\n    },\n    \"PedestrianCrossing_Town13_Route3828_Weather1.tar.gz\": {\n        \"sha256\": \"d6bf4dbea2214439c2f0df5d3d21551109e898fd302dfc1455e1dc45a9df3de0\",\n        \"size\": 428135404\n    },\n    \"PedestrianCrossing_Town13_Route3829_Weather2.tar.gz\": {\n        \"sha256\": \"9fae4256995c927ae4b9d5b87cf88de5434c0dbcbd8d0a66b188c0c3d428d67e\",\n        \"size\": 230076073\n    },\n    \"PedestrianCrossing_Town13_Route3830_Weather3.tar.gz\": {\n        \"sha256\": \"be229445b1d79e7dfbc98f1c6ffb347b9caf89e6563edb700bb656155cdebcbc\",\n        \"size\": 131136778\n    },\n    \"PedestrianCrossing_Town13_Route3831_Weather3.tar.gz\": {\n        \"sha256\": \"514d3735f91770da806969b220ec62e790f0b5fb3ae1dc2245c44a41cc1e880c\",\n        \"size\": 223859204\n    },\n    \"PedestrianCrossing_Town13_Route3832_Weather5.tar.gz\": {\n        \"sha256\": \"590fba9fcd90e8216fea552c7f662900b2a9e87adcd3af9b79034314d0df8aaa\",\n        \"size\": 610914006\n    },\n    \"PedestrianCrossing_Town13_Route3833_Weather6.tar.gz\": {\n        \"sha256\": \"64b322c37676a71347b89035f487a4120af479ad34bf9047bfb5420559e443f6\",\n        \"size\": 340059762\n    },\n    \"PedestrianCrossing_Town13_Route3834_Weather7.tar.gz\": {\n        \"sha256\": \"3a8be1559ccd968ef547faf7d050549ff1cf314418cecc99baa25fa792675143\",\n        \"size\": 693578032\n    },\n    \"PedestrianCrossing_Town13_Route3835_Weather8.tar.gz\": {\n        \"sha256\": \"ff580a705666d6ac851c32794e1c625b81e65d1b312eb99c68fa442db438ddea\",\n        \"size\": 600451975\n    },\n    \"PedestrianCrossing_Town13_Route3840_Weather13.tar.gz\": {\n        \"sha256\": \"7bb41eba00d93ab0e70d14c6ca41d9ebbf9612d0636fa8f6e74d884794045a5f\",\n        \"size\": 231316204\n    },\n    \"PedestrianCrossing_Town13_Route3841_Weather14.tar.gz\": {\n        \"sha256\": \"b31f8309ab3467567df8018ae9598e41d4aa8b7ac9101fc03cf900399d88b39c\",\n        \"size\": 199339565\n    },\n    \"PedestrianCrossing_Town15_Route27458_Weather21.tar.gz\": {\n        \"sha256\": \"bdc3dbdd61c43d2c3e87a34e6a237b337b52e021c7dd0fb0f9b0149459c92747\",\n        \"size\": 1460249522\n    },\n    \"PedestrianCrossing_Town15_Route27463_Weather0.tar.gz\": {\n        \"sha256\": \"a941027100fe5db0a81fb12391b532bed0888fe81696f15aece9737082083980\",\n        \"size\": 326036507\n    },\n    \"PedestrianCrossing_Town15_Route27468_Weather6.tar.gz\": {\n        \"sha256\": \"77f9934871462992aa48ff759337984f24ccaf4b85ab38b200fa6c87e886b191\",\n        \"size\": 992668526\n    },\n    \"PedestrianCrossing_Town15_Route27473_Weather11.tar.gz\": {\n        \"sha256\": \"fa4529088bd4f7c3cd94544b7ccb5e0b7f336be492d628d8c79caa71aab15a3a\",\n        \"size\": 290089964\n    },\n    \"PedestrianCrossing_Town15_Route27483_Weather23.tar.gz\": {\n        \"sha256\": \"6c18febc2ee81a11d1d7e31378296ffa10afd9c02011231f669197debf269f95\",\n        \"size\": 854453423\n    },\n    \"PedestrianCrossing_Town15_Route27488_Weather2.tar.gz\": {\n        \"sha256\": \"d7e1120eca19b9cf465ee486b27259a27b08b044fa4221ed3308d4b150dd303e\",\n        \"size\": 1333566373\n    },\n    \"PedestrianCrossing_Town15_Route27493_Weather8.tar.gz\": {\n        \"sha256\": \"b04144dc446237a82f647274dcb1a7eeb9cd10f074e92be80673e84365ed4448\",\n        \"size\": 1558631842\n    },\n    \"PedestrianCrossing_Town15_Route27498_Weather13.tar.gz\": {\n        \"sha256\": \"b1bc532f4083d591bfecca0bb72e328386efbcd0c4bc0ce8a84fd30f05024beb\",\n        \"size\": 842307296\n    },\n    \"PedestrianCrossing_Town15_Route27503_Weather20.tar.gz\": {\n        \"sha256\": \"ce15ac53941e939de2ca7ae9e57663255de1b06fa79e71b6f786b2606233e1d1\",\n        \"size\": 288501306\n    },\n    \"PedestrianCrossing_Town15_Route27508_Weather26.tar.gz\": {\n        \"sha256\": \"249c30b504a88591470d076d2fabe155414a5d8a0bc41795106549385539007f\",\n        \"size\": 1769929973\n    },\n    \"PedestrianCrossing_Town15_Route27518_Weather10.tar.gz\": {\n        \"sha256\": \"2a4a48629fda4428fa3e7c8fd483f0645aef1495da24e33d3cb5480649554d17\",\n        \"size\": 970912814\n    },\n    \"PedestrianCrossing_Town15_Route27523_Weather15.tar.gz\": {\n        \"sha256\": \"ad956bdb14e58f9e07a242a5353c5aea8362e36f12e6d17d658d9896364ee3b7\",\n        \"size\": 924585444\n    },\n    \"PedestrianCrossing_Town15_Route27533_Weather1.tar.gz\": {\n        \"sha256\": \"701fe1e4aeea56c8949948c396c808fc90bd4666a734cbdf6c852649f7674528\",\n        \"size\": 1351364107\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town03_Route28064_Weather8.tar.gz\": {\n        \"sha256\": \"df0dbadf99f5dc02ff20cf79ee3249977d89c1c2eb74ca9268cb263b7b2fccb5\",\n        \"size\": 224096095\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town03_Route28065_Weather9.tar.gz\": {\n        \"sha256\": \"1a1947dbd253f9926733f5379b55076b8e32ba8caa76af6eddc13b32ed4906b9\",\n        \"size\": 320710610\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town03_Route28066_Weather10.tar.gz\": {\n        \"sha256\": \"c1ea8417566c5b5af4aa7b524ce105cb7c6bc74e1abd8ab73ef5bdae2ce6a17a\",\n        \"size\": 141633359\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town03_Route28067_Weather11.tar.gz\": {\n        \"sha256\": \"7974fa0f2fe27b095309494876e2b07d5a1f9355aef78a2f8bbb640a605df8d0\",\n        \"size\": 123334502\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town04_Route28099_Weather22.tar.gz\": {\n        \"sha256\": \"16e8ae8163021d8c33d5d0f12aeb0b935be5563c66041d0659baf761bf6f8e47\",\n        \"size\": 180838411\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town05_Route28124_Weather25.tar.gz\": {\n        \"sha256\": \"d0e37f6d7d9149bafdb21d8ab843a210e803cf56d0c13ed836b7a4d896028ac2\",\n        \"size\": 139413680\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town05_Route28126_Weather0.tar.gz\": {\n        \"sha256\": \"67cad7ea9ae51346bad6b1c68a290ad42ba1e0966094b66060a80837d86f7a99\",\n        \"size\": 264241778\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town05_Route28129_Weather3.tar.gz\": {\n        \"sha256\": \"e69db5103dc3fdefe366104b7b667356d33083e578d9616303825ffd12568a4d\",\n        \"size\": 339021339\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town05_Route28130_Weather5.tar.gz\": {\n        \"sha256\": \"2fc7e45e9103acb92447adedf1419e4d3acad6e43ee49af1ff31309458655268\",\n        \"size\": 240370012\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town05_Route28131_Weather6.tar.gz\": {\n        \"sha256\": \"6eb4c47aa442603e7738341f6c3f45953f43852bcf2b1d53c6e1e512e39fa7e2\",\n        \"size\": 395346454\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town10HD_Route28144_Weather21.tar.gz\": {\n        \"sha256\": \"b1210f265b01cf572ccbcd65ecd0001ce04833dfe5ade9e4d5276f9a1e726979\",\n        \"size\": 286954028\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town10HD_Route28145_Weather22.tar.gz\": {\n        \"sha256\": \"e171e246bd27d0a2305d17927479df622b9fb17f6e026a691c1e095675c424d7\",\n        \"size\": 249004651\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town10HD_Route28147_Weather25.tar.gz\": {\n        \"sha256\": \"7915ad38eeb1e4418f0f9b34ed2a23e549ef91b2d8f6f5cedb77f68bb96765d5\",\n        \"size\": 235544019\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town10HD_Route28148_Weather26.tar.gz\": {\n        \"sha256\": \"bc1d2b0642f062722960f07df13c7e693e31bac24f1fabef8ce908990e5680f4\",\n        \"size\": 331243883\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town10HD_Route28149_Weather0.tar.gz\": {\n        \"sha256\": \"f0ea235d2c14228eac1f2493fe315af9f6135f8991bfd675c6c7a072cf2c48b1\",\n        \"size\": 302241099\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28233_Weather18.tar.gz\": {\n        \"sha256\": \"3e37ce953d1b0471efb4dd72c42ca7a4d82a2f3db12957adb858d5bb49281fa3\",\n        \"size\": 142495668\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28234_Weather19.tar.gz\": {\n        \"sha256\": \"cc1278d25441770e22472c7258021176ac9a42b7e33f295cd0b574b148bbbbda\",\n        \"size\": 207457827\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28241_Weather0.tar.gz\": {\n        \"sha256\": \"2e868e0cd95b93fbb82c5a09b40a16423dbdf5c74c9c405efda781a8b12b77b0\",\n        \"size\": 159053556\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28243_Weather2.tar.gz\": {\n        \"sha256\": \"cc6ebfe606ed0531a18a227c4256ecc1fbb1abe52302b29f833dc9b5c6989f98\",\n        \"size\": 169905243\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28246_Weather6.tar.gz\": {\n        \"sha256\": \"2384bf5e73f5ae4cccadb3df7bc9f990ba1bb6775429f5f277ea2ce4d520f9a4\",\n        \"size\": 170075667\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28247_Weather7.tar.gz\": {\n        \"sha256\": \"9fb99c1fb53b38f284ed6f544b253cfff8fa979f9f67582a73d9e01d67239428\",\n        \"size\": 150335208\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28249_Weather9.tar.gz\": {\n        \"sha256\": \"6668c5027a8b81a645571ed6059d7475894eef9653c2adfa65901b8ee8ca18c3\",\n        \"size\": 116062104\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28330_Weather0.tar.gz\": {\n        \"sha256\": \"2493f565d9ea9478035a22f365b79722949f9296a85929293a09f4dd5847e6cc\",\n        \"size\": 407851419\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town12_Route28346_Weather19.tar.gz\": {\n        \"sha256\": \"d69ae7eb0715a1a661342f4d5103169d04ee5cce26c8f0d69d24c54e2839bc83\",\n        \"size\": 200216901\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34453_Weather9.tar.gz\": {\n        \"sha256\": \"abc888bef050d05aba16642dfe831f3c033cebad14139c06b0690c3ddc27173f\",\n        \"size\": 129571984\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34463_Weather21.tar.gz\": {\n        \"sha256\": \"29a4515a0191ca378234237f86d0ecc52f11918d27e8d06ca0cd11008d22df1a\",\n        \"size\": 162106750\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34620_Weather15.tar.gz\": {\n        \"sha256\": \"9325debc990fbd76919c7b93ce645630bd29ac242fa716333eb3e8e6d8476d70\",\n        \"size\": 332976666\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34622_Weather19.tar.gz\": {\n        \"sha256\": \"a61aba0b232d1affbbbc08845efea13356c2edc826f19d96a9b4da7a73c083bb\",\n        \"size\": 194526948\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34637_Weather9.tar.gz\": {\n        \"sha256\": \"5a9c4b6d160d47cbbbe767e7cbbffe5a5d11e6383010f0966f8b36d2d19905fb\",\n        \"size\": 377963747\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34642_Weather14.tar.gz\": {\n        \"sha256\": \"5b5d78a4876aea4cff9f04f022656d1ff29cdd83d6d4b718bbac899557dc8f69\",\n        \"size\": 133560599\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34660_Weather9.tar.gz\": {\n        \"sha256\": \"e0ee0ccf6d065e5b229ae6958258e278f4e50869a2a9d16b0998e73ba82ab486\",\n        \"size\": 162178104\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34668_Weather19.tar.gz\": {\n        \"sha256\": \"fd54845755449f47593b1ffdb360daa9a74575070f8e1ded24a96cb9338ea18c\",\n        \"size\": 188997289\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34671_Weather22.tar.gz\": {\n        \"sha256\": \"496504ceed7c0fc454d9fe1c83b852186ab73786c0442890239587db3437aff0\",\n        \"size\": 150768687\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34673_Weather25.tar.gz\": {\n        \"sha256\": \"bd292d94d34aa86fdee99acc7c652b969b0b706c4291fb72840b5a4439e812dc\",\n        \"size\": 141420601\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34692_Weather20.tar.gz\": {\n        \"sha256\": \"1444856b86536f910cbb6a452511fc9a76011a0e6ed4ff4421b0125804116859\",\n        \"size\": 166998025\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route28194_Weather26.tar.gz\": {\n        \"sha256\": \"0559dfb1dd730bcca99293bc4079d6808c7e629504c57a5307a84a5c9777ce2a\",\n        \"size\": 479562439\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route28195_Weather0.tar.gz\": {\n        \"sha256\": \"41f533a7a939448ea30fb0ea8ad6b1789abc702619d2cda409007b417f7d20c6\",\n        \"size\": 710434252\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route28196_Weather1.tar.gz\": {\n        \"sha256\": \"17f67c129158c8bb61fe4b846ec6b2e69cb0cdf1aba89315f7ec0eb195c5034b\",\n        \"size\": 576136090\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route28197_Weather2.tar.gz\": {\n        \"sha256\": \"dc60fce78dcf1afbbdf3ef5e3438bac9595668aa57ee2f7ad88529812ce62633\",\n        \"size\": 581057582\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route28198_Weather3.tar.gz\": {\n        \"sha256\": \"b93213ec437bec78a6b370d3082e339fe9b57b48653fe72238fcaa3cffa3beb5\",\n        \"size\": 460748166\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town15_Route28199_Weather5.tar.gz\": {\n        \"sha256\": \"aa5f9809bf3ddec7402af612343f35788fceea65354beca7ce1188effcea30ac\",\n        \"size\": 472624885\n    },\n    \"SignalizedJunctionLeftTurn_Town03_Route26700_Weather22.tar.gz\": {\n        \"sha256\": \"26b9d3d46b4e6619cc04e04ef7ee4d537aa5cf923b0a5c0852f1037d39c1e07f\",\n        \"size\": 293663409\n    },\n    \"SignalizedJunctionLeftTurn_Town04_Route26709_Weather6.tar.gz\": {\n        \"sha256\": \"57d711def35eb61b8a55bf2322fffe11d3deb3c514ca28c1f30bb8d8227b3776\",\n        \"size\": 372948715\n    },\n    \"SignalizedJunctionLeftTurn_Town04_Route26719_Weather18.tar.gz\": {\n        \"sha256\": \"c0b11d37adc0209d4b028458e63f5ed4d448dacd78db2b5df7e0292726ab09fe\",\n        \"size\": 268610730\n    },\n    \"SignalizedJunctionLeftTurn_Town04_Route26744_Weather20.tar.gz\": {\n        \"sha256\": \"b81c456b3bf0062d272eec9033643ffbe67be1024c18f757211aa9feefb9efba\",\n        \"size\": 210225975\n    },\n    \"SignalizedJunctionLeftTurn_Town10HD_Route24360_Weather2.tar.gz\": {\n        \"sha256\": \"940a996a646e8cc6377812e6a416dde8c07205698b8360492b74cbfeaa1bfea7\",\n        \"size\": 346403711\n    },\n    \"SignalizedJunctionLeftTurn_Town10HD_Route24380_Weather26.tar.gz\": {\n        \"sha256\": \"313c0df10fe7255cc35114a7d24706d7b0552d411efbb8b19f4338bc1572bd6c\",\n        \"size\": 387415114\n    },\n    \"SignalizedJunctionLeftTurn_Town11_Route26602_Weather14.tar.gz\": {\n        \"sha256\": \"1ee81e56ac9dcb1a0d708d92f4e90b5399a5a9938190b57687ccae542e6d439d\",\n        \"size\": 59220502\n    },\n    \"SignalizedJunctionLeftTurn_Town11_Route26637_Weather2.tar.gz\": {\n        \"sha256\": \"fc0797e5e0bf9d36dba65253b33db0af632e835f2fe28ef8e2d7f672767f5176\",\n        \"size\": 81500796\n    },\n    \"SignalizedJunctionLeftTurn_Town11_Route26647_Weather13.tar.gz\": {\n        \"sha256\": \"b4c7d159aeb39869dfe9effee19b079c202af37fd467862027a517d6c54ffe59\",\n        \"size\": 52978745\n    },\n    \"SignalizedJunctionLeftTurn_Town11_Route26657_Weather26.tar.gz\": {\n        \"sha256\": \"31adb82c61f91631a5c06fe88ea4f775f8121084617920aa03903a7586366db6\",\n        \"size\": 123049683\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2031_Weather23.tar.gz\": {\n        \"sha256\": \"93f5ed06f2f0143f3073cea478c09a0c3449f7f1e464d2b69c1f70f1d265a8d0\",\n        \"size\": 1082595652\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2039_Weather5.tar.gz\": {\n        \"sha256\": \"9a114718e77cb65e66b692016ba1879d62a777c38dad550bc44c74413eef3367\",\n        \"size\": 174898425\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2040_Weather6.tar.gz\": {\n        \"sha256\": \"7284e4d0b2be9725070c91707d23424bfa0c0921aaeaa8b909c7b5339b23756e\",\n        \"size\": 135734301\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2816_Weather2.tar.gz\": {\n        \"sha256\": \"d3b4e1af652cecec0455cd1481f57cfc0057415bfb8a4556161f7642a04410f1\",\n        \"size\": 167860369\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2818_Weather3.tar.gz\": {\n        \"sha256\": \"317debd412288175d64363fa98a5f95f00fef4abc9e5f378b258d43b175769bc\",\n        \"size\": 160397897\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2820_Weather6.tar.gz\": {\n        \"sha256\": \"39c2d9588bcf514655763f99d0f3e3adb0944d25b6b1a8d747d409926d8344ef\",\n        \"size\": 192441652\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route2821_Weather7.tar.gz\": {\n        \"sha256\": \"a3107edc305163deffde0ade1aafaafc5b5e1eb03c40e34a3537d08cad04cf27\",\n        \"size\": 258997992\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3925_Weather2.tar.gz\": {\n        \"sha256\": \"4fecdcd961beaad463cb10c82ae81077fa38becb605f484e12cf655326a60d2b\",\n        \"size\": 193124268\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3936_Weather13.tar.gz\": {\n        \"sha256\": \"6c9546538ca0e5817b4a8719ed86c19bb3c4867802a487571a972d5393de62a9\",\n        \"size\": 130285798\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3941_Weather18.tar.gz\": {\n        \"sha256\": \"614cfd65ac68a2346f02628ca446e06748f610878c9bd96783f01701ae4c29cb\",\n        \"size\": 146896796\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3950_Weather1.tar.gz\": {\n        \"sha256\": \"f09ff0d852c0acb78638c65b0ea9da2626a679c25abd1a9e7de964b7139de02e\",\n        \"size\": 199626479\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3985_Weather10.tar.gz\": {\n        \"sha256\": \"a7a7c728c9386b0015443c914745e3a3e5d687afd96cc55d7ca13362ed5458cb\",\n        \"size\": 315012346\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3994_Weather19.tar.gz\": {\n        \"sha256\": \"c211ad16f935157884284e9ddf50707d5e7e8ac54120fec9a6982df194c47e08\",\n        \"size\": 236261680\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route3995_Weather20.tar.gz\": {\n        \"sha256\": \"373537f7df2b70afe7da27d677fd282a5a16be72a5e0d43845c7b5d1307dec42\",\n        \"size\": 232218535\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4000_Weather25.tar.gz\": {\n        \"sha256\": \"bab8cd94e8aaa7e3fa2cdfaaf98644ffedc2fa47c550198098f6af79785b17d5\",\n        \"size\": 132586250\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4002_Weather1.tar.gz\": {\n        \"sha256\": \"3c2cfc2a2f8cdd93bdc4a69116076ddf064cc880470a18dfe81d67745534b0cd\",\n        \"size\": 394716661\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4005_Weather3.tar.gz\": {\n        \"sha256\": \"ba459a8ca9b5af1588c35ccb21a924634419ed25e2943442090541f1630cbe77\",\n        \"size\": 315414681\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4006_Weather5.tar.gz\": {\n        \"sha256\": \"b28c4498c3350c9b1d0128cd27e8665a8b0b5fe590cdf5566a0c43445faaddf7\",\n        \"size\": 145171766\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4008_Weather7.tar.gz\": {\n        \"sha256\": \"6ada4916d7719d960a645f256fa987efa52c0b8a487a1d0e7569944ed6a22b19\",\n        \"size\": 540246493\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4012_Weather11.tar.gz\": {\n        \"sha256\": \"7342f7833c393af2008096a034d738aa481696a5035cf8764966ccbb345c7c5f\",\n        \"size\": 249318313\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4016_Weather15.tar.gz\": {\n        \"sha256\": \"ca94830a8bb58c8646a7554a10df840565ac5b029597609ca71eca2bcd6778bc\",\n        \"size\": 144804755\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4020_Weather19.tar.gz\": {\n        \"sha256\": \"139fbe919462a89248ba6b4363f837fb9974d039c8ced84132585caed1e9c479\",\n        \"size\": 195167590\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4024_Weather23.tar.gz\": {\n        \"sha256\": \"0d99ff593854471a45855ce975b48f901ac6c59c401d66a2cffb243846b0275f\",\n        \"size\": 109916638\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4031_Weather3.tar.gz\": {\n        \"sha256\": \"0f11a922730fd88292ef1bcd31049fad594865edc32affbfc94f4613542d37f1\",\n        \"size\": 224263661\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4038_Weather11.tar.gz\": {\n        \"sha256\": \"bcc1c7eacdafdee4967f0df10c7ff06068e9018e9533848ddd36059f022f02c7\",\n        \"size\": 267282090\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4045_Weather18.tar.gz\": {\n        \"sha256\": \"54df2514eabe67da303f55e8873ea1c5748554c832d6040ed951c838d074bb33\",\n        \"size\": 129451516\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4062_Weather9.tar.gz\": {\n        \"sha256\": \"f754e35cefad67a0cd4967b0b55c826c4aed151663aeee5268bd86eca3fae64b\",\n        \"size\": 219881317\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4072_Weather19.tar.gz\": {\n        \"sha256\": \"fe6b3e9cc92eb0cf179e4cb141a54a92455bbb039be3f49026ddae218947972d\",\n        \"size\": 173566771\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4075_Weather22.tar.gz\": {\n        \"sha256\": \"3d4c495a63928bbac4d63d58e8ca3c5657c441f5c949bda7ea556481e0d14295\",\n        \"size\": 142017243\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4082_Weather3.tar.gz\": {\n        \"sha256\": \"b6e9a2f0c41c8e939fd833b58273d52def933e5dc3620cd9adc29ad46449bc1e\",\n        \"size\": 270941621\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4101_Weather22.tar.gz\": {\n        \"sha256\": \"1763f9c19fef898e1d52dae7b34f2de2c43c66a8ce5a5f817d74f990993c9978\",\n        \"size\": 158600280\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4108_Weather3.tar.gz\": {\n        \"sha256\": \"b88eaa5b7b3e274cbe1585272edb7057498caa45348c36e138ec8710212f1278\",\n        \"size\": 159957303\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4142_Weather11.tar.gz\": {\n        \"sha256\": \"4b658e45d5f267ee6d12554fb664c14c6ebd687a3522183b770981ac3c6be1fb\",\n        \"size\": 133611200\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4155_Weather23.tar.gz\": {\n        \"sha256\": \"945865e9c3956cef1811bea4e1b094af2f862abc2969f2c0c077ac35037b7ab7\",\n        \"size\": 128075176\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4162_Weather5.tar.gz\": {\n        \"sha256\": \"9b89561afc147e0353c4a6bc5391d490088adf86f27a0734f879cb76028e7f50\",\n        \"size\": 152736445\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4167_Weather10.tar.gz\": {\n        \"sha256\": \"09ee69d1fa6be08bcb092210ca09b800f11f751eabcb51c1cd8f2066fa51c577\",\n        \"size\": 135109501\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4169_Weather12.tar.gz\": {\n        \"sha256\": \"14e5667ad1f1b57441338c28db53bf41531764aa393ac9c1451ec84bec26e303\",\n        \"size\": 177950795\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4174_Weather9.tar.gz\": {\n        \"sha256\": \"7997d5eb9a0a4493ed1e40c0e5c1f305d53c6db463673888405d3c9a8ce97c96\",\n        \"size\": 121959649\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4183_Weather0.tar.gz\": {\n        \"sha256\": \"7b2619c0111ed2223ab56690393a9d494debff2a87196cd3409a62d16e0a7ef1\",\n        \"size\": 217020828\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4184_Weather1.tar.gz\": {\n        \"sha256\": \"72dacb962e21f6c5feacc1bda40329839a93695674b5de4ad671b1df3b1b7740\",\n        \"size\": 144639515\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4188_Weather5.tar.gz\": {\n        \"sha256\": \"74b42990f0559a15ff11113a5f948adfe98946cd26a11d4d9aa36ef5235c765f\",\n        \"size\": 142842503\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4198_Weather15.tar.gz\": {\n        \"sha256\": \"440226b1ac75e8b30236337c6149d0561df54f9c07b2629d0131d9801b475701\",\n        \"size\": 134352545\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4199_Weather8.tar.gz\": {\n        \"sha256\": \"0ff789ce103940a80971f5dd932ab5226716f73462f3fd74c74db7ef2b47fd23\",\n        \"size\": 290853157\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4200_Weather9.tar.gz\": {\n        \"sha256\": \"20cfa37419b6c95c2564f998298eae9d62872603b4168d94d7d9a3cce0312b0a\",\n        \"size\": 107274165\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4204_Weather21.tar.gz\": {\n        \"sha256\": \"a60b716afb90cd648efba4d339dd2238e4d4ad182ef9643a62897635c0d41f59\",\n        \"size\": 230109199\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4208_Weather25.tar.gz\": {\n        \"sha256\": \"bd49dee92c09ed79d8eb91ec8cb97bf79132f9cba5925add577608aca431fcd3\",\n        \"size\": 114865410\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4209_Weather0.tar.gz\": {\n        \"sha256\": \"256f264de1a63f8f588277e142802b3db0b21ed9b895fc77f0a67f18651735e8\",\n        \"size\": 178678485\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4210_Weather1.tar.gz\": {\n        \"sha256\": \"81f5ade99ee16357873987a4912790d257a87ba71df29051bcd2d2f173e5e436\",\n        \"size\": 175687948\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4215_Weather6.tar.gz\": {\n        \"sha256\": \"e2558f5b6f4bf5a9f559952c721c17083915b8ed676225c43662d2b8961318e1\",\n        \"size\": 136694795\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4217_Weather8.tar.gz\": {\n        \"sha256\": \"6ce8b7699120d09cd1872af9c402338396439969f33945c4983ed4ada33f2e58\",\n        \"size\": 159190586\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4228_Weather19.tar.gz\": {\n        \"sha256\": \"eaa51f4f827a699ee5915c07bb7d222394817d7a0436d95996469f32dd142c91\",\n        \"size\": 232211364\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4230_Weather21.tar.gz\": {\n        \"sha256\": \"4476b8dc34a5d12c552f04302e513728403fa211a7b03d0ee0a05e90061fb0f3\",\n        \"size\": 187962743\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4249_Weather14.tar.gz\": {\n        \"sha256\": \"b1962fd6977ca7d172e575e77805995c26240dbdf90dd4f454b37d5df56457fe\",\n        \"size\": 199386156\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4251_Weather8.tar.gz\": {\n        \"sha256\": \"accfe8f93f8c5904cab3b8febde521e0a2ffc7c196f163aaca4e6c1c9290927d\",\n        \"size\": 268416940\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4259_Weather23.tar.gz\": {\n        \"sha256\": \"f37e539f1d3bbee3ab84e8889d565d68b1128c13b9393865da5df8f54174e366\",\n        \"size\": 180751785\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4276_Weather15.tar.gz\": {\n        \"sha256\": \"b0d00c989686abe7fbf8b947ad71aa9ad3f56768f44f29be1133bc11733404e2\",\n        \"size\": 148705408\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4279_Weather18.tar.gz\": {\n        \"sha256\": \"ea02b25a8f1932d965c588d994f3424509aed4fc620c9578fc3770c50565c577\",\n        \"size\": 622694723\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4283_Weather22.tar.gz\": {\n        \"sha256\": \"fa7da24a1bad3afcfa59d4eec0eb04705bd09251504ce0b7758e8c9f7442b4c6\",\n        \"size\": 156088153\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4284_Weather23.tar.gz\": {\n        \"sha256\": \"8fd32198daa6ee3d3e65ad1f086135b68ed611b023c4eba1f883a37d731c7864\",\n        \"size\": 155366001\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4291_Weather3.tar.gz\": {\n        \"sha256\": \"83dd09cd2c90fe19580874c8beef44d2b3f8248acc1b7d3af2474dac74aed38d\",\n        \"size\": 174488900\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4293_Weather6.tar.gz\": {\n        \"sha256\": \"bb86084f24357543ed4bebd19150c66abd0b86accb4628a97cb8b7ffcfaa6750\",\n        \"size\": 123192447\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4294_Weather7.tar.gz\": {\n        \"sha256\": \"8402ce4298399c190eec7f2b9be90cc2958cc79a400395e3a8ebc573649c6bac\",\n        \"size\": 201888486\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4302_Weather15.tar.gz\": {\n        \"sha256\": \"fc9b74e8f7c0d61507f0063b8606db98661d1de91df559a348fcb29d8decb312\",\n        \"size\": 349483443\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4307_Weather20.tar.gz\": {\n        \"sha256\": \"3f6eef837de270a5ec3796536a241f9a6fac508b2740670a3ce06260fa008634\",\n        \"size\": 158796376\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4319_Weather6.tar.gz\": {\n        \"sha256\": \"eb4f9f9447ae0000f2cde986b8036a4619036d8672c3ea84e2a1d5e2fcfff621\",\n        \"size\": 234507320\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4328_Weather15.tar.gz\": {\n        \"sha256\": \"248e913a04b15956a33423827fa8371f4208bb13c6a9b95db5508c1ad4868059\",\n        \"size\": 177601023\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4330_Weather9.tar.gz\": {\n        \"sha256\": \"7c7e3e03fb90a4b4eef4045e4ae38e3d5b743a5f2000e605b95c29e8c02c60fb\",\n        \"size\": 100619186\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4341_Weather2.tar.gz\": {\n        \"sha256\": \"3f53d350ba9706dd783e660696df2f4ead69e88e62d51e36ff19bb1419dd61e2\",\n        \"size\": 416341163\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4354_Weather15.tar.gz\": {\n        \"sha256\": \"9bea62ba841297c3a244bfaac292748d2c443ad9821853dfb221d71d75f20aab\",\n        \"size\": 138247071\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4360_Weather21.tar.gz\": {\n        \"sha256\": \"b928477a1a5a5dbd8677f250594e835bc1ff5ee2c4321e03cd9bb87243f475e9\",\n        \"size\": 141479784\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4363_Weather23.tar.gz\": {\n        \"sha256\": \"0b2c3b97e375f9eb18bef1c0146b2f7a923b26d92ccb32d74172d238051e35fd\",\n        \"size\": 190305282\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4388_Weather23.tar.gz\": {\n        \"sha256\": \"38c7ec8d3f3b50ad8ee7443b3ab3a4463252cb178f5a506931945086df32a098\",\n        \"size\": 110752502\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4406_Weather15.tar.gz\": {\n        \"sha256\": \"0ba3b1d42377a0cfaab51f10ee62b383eb77a175400ef1567ccf6b55d2513499\",\n        \"size\": 170273168\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4414_Weather23.tar.gz\": {\n        \"sha256\": \"23349d00ce724114e10448c360cf0bff468be121adfef319b261c45cf5c26790\",\n        \"size\": 132297996\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4422_Weather5.tar.gz\": {\n        \"sha256\": \"9813d5d5b5da2b4b0f4ca26e8de1211efb3933a56b10ed2cc9638104008cae23\",\n        \"size\": 219377429\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4423_Weather6.tar.gz\": {\n        \"sha256\": \"3a567e5e3de3a4554566062ef1b254ef9e1feb591169a5eb6b6112ef8c678850\",\n        \"size\": 138505131\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4424_Weather7.tar.gz\": {\n        \"sha256\": \"148fcf3a94e55a2989829953544a468c18505b5dd47429c29b0df3185e1d17b2\",\n        \"size\": 221467648\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4428_Weather11.tar.gz\": {\n        \"sha256\": \"a67dc323d46effc65cf6e13efaf516cd2801a0dc20c7e7966ca7de82de6db429\",\n        \"size\": 162383647\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4439_Weather22.tar.gz\": {\n        \"sha256\": \"3c0a8d773fb32f8c621599ebe50fa71a46b598d3e63bf500da0b0d2e37c227a4\",\n        \"size\": 267625418\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4445_Weather2.tar.gz\": {\n        \"sha256\": \"186121d2459b4a752b4e7d385db5965356f6422093706eb3e98ff3887bab3ccd\",\n        \"size\": 321825602\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4447_Weather3.tar.gz\": {\n        \"sha256\": \"3e513679552e036a87739b66cc497b1a3b0ea41a1e3c2aa9d085b6844f65fb5f\",\n        \"size\": 159675203\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4459_Weather8.tar.gz\": {\n        \"sha256\": \"b597320e63aa8c3713e8224d3591d64ca391a0b16bbd8cf95f161cea80fceaad\",\n        \"size\": 191015058\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4462_Weather19.tar.gz\": {\n        \"sha256\": \"332ac7ae89537e534badb6a53768f3ba6d12f5bf7ba3264be91640011d3434d4\",\n        \"size\": 210579496\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4468_Weather25.tar.gz\": {\n        \"sha256\": \"28c684382c56e3646167f503a407891c7e2e802dd67054850bca4b4d90cfc95a\",\n        \"size\": 123104517\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4477_Weather8.tar.gz\": {\n        \"sha256\": \"dec0d0191d1cccf237c050c2bb087e1c8666dc400ec2f188c1000d6d5ea712a2\",\n        \"size\": 136614980\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4490_Weather21.tar.gz\": {\n        \"sha256\": \"54ca23ecc22cc38be9423d1b2028ba757f47309eaba0aed959470fdbc1bfb80c\",\n        \"size\": 218490076\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4505_Weather10.tar.gz\": {\n        \"sha256\": \"e12a756d1e6983ae48484038701ab9f831488cbb0127791973fa46a2761cd5f9\",\n        \"size\": 243313329\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4508_Weather13.tar.gz\": {\n        \"sha256\": \"16fc553f075d1d7094bf7cc6412001a967497bf712de5176aa1daee100bc8861\",\n        \"size\": 384190823\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4510_Weather15.tar.gz\": {\n        \"sha256\": \"cc92ec1c4fcc25158d3623524beb302dacc25e29599fbc93569acc68f33aee00\",\n        \"size\": 214492505\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4513_Weather18.tar.gz\": {\n        \"sha256\": \"db803d473652bee960d2fd443c79630807160871514d0dacc04f5da70d4373b4\",\n        \"size\": 177318945\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4517_Weather22.tar.gz\": {\n        \"sha256\": \"a1a1868b378fc109c1c1adea1b6e97b127d7bc38c57afe85e359c97e7de0d362\",\n        \"size\": 207332278\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4521_Weather0.tar.gz\": {\n        \"sha256\": \"4976a3d1541cbe5033f6daa19ce4af665254fccbb55a3907c53c66f6e1443246\",\n        \"size\": 230983389\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4542_Weather21.tar.gz\": {\n        \"sha256\": \"83765acd033b60be3c384ed591c5bbbebbe0879c09dcd9f9192f587eebac3152\",\n        \"size\": 140387076\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4548_Weather1.tar.gz\": {\n        \"sha256\": \"b9c715b394360bcc04f4a92ebe5b7ca6f081df0d04b411059fd4cb464e4fec3e\",\n        \"size\": 181821369\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4558_Weather11.tar.gz\": {\n        \"sha256\": \"cf6912b715e5b0213e632928b49b3a146abdc3742718cc78f2c032a78d164666\",\n        \"size\": 99299084\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4595_Weather22.tar.gz\": {\n        \"sha256\": \"fa4dfdaf162dd042281bcb3956567a217d58ecb1b62d34e9e7756a8ca369ecb8\",\n        \"size\": 343702225\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4609_Weather10.tar.gz\": {\n        \"sha256\": \"78e6de0deb962ac9d3252b18f8bddf67220967830ae907c7a6930dc08eb0faf3\",\n        \"size\": 265943635\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4616_Weather9.tar.gz\": {\n        \"sha256\": \"a2e513ff67cf551d360e5b8905e105e6b8c1704cd9156943425356389901d203\",\n        \"size\": 118812536\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4619_Weather20.tar.gz\": {\n        \"sha256\": \"47ac10b1cf54ec1bd383faea646d46135155ad43bc72f46e0529288c7c317960\",\n        \"size\": 162480288\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4627_Weather2.tar.gz\": {\n        \"sha256\": \"a607dcd5b4bccbc1465aee4897484bf9ee5664377205cc202a929083e0cac350\",\n        \"size\": 174678990\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4631_Weather6.tar.gz\": {\n        \"sha256\": \"21e5967989063f74a518e97edd70ae2ec48c290e3c89f320ad548297f3a7e1a5\",\n        \"size\": 162994693\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4642_Weather9.tar.gz\": {\n        \"sha256\": \"ea79c8bdae623baf6fe6fdb15c905cef952d2bc5481d64630f78d0b883c1a82c\",\n        \"size\": 319727598\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4646_Weather21.tar.gz\": {\n        \"sha256\": \"15759712d49e5e7400147761a9e70c149c648bbee5f9377648e70beb0a9d694c\",\n        \"size\": 207011912\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4648_Weather23.tar.gz\": {\n        \"sha256\": \"96c678a6d2b9b8fbf17732d609a27e97d9ad710d3cce9f98b9e723780f93f862\",\n        \"size\": 209715580\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4655_Weather3.tar.gz\": {\n        \"sha256\": \"ce1b400f3f8415fd8632b2b43d30f28f5fd9e21b52c52e49ff69f586ebfa4323\",\n        \"size\": 167889112\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4656_Weather5.tar.gz\": {\n        \"sha256\": \"9f12fb20f59b878484f86093aea72cf5daa9efab2f74670ea5b6f9b2f0326211\",\n        \"size\": 152361381\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4669_Weather18.tar.gz\": {\n        \"sha256\": \"48080f7388dc259ea079e72dee121f88f59cb8b6e12933172f1782539284cfaa\",\n        \"size\": 251499565\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4676_Weather25.tar.gz\": {\n        \"sha256\": \"7a938e73aad3bb5a67a17b1b67cf8d914d1bc8055a2ced0242ea9b3a6f20b5de\",\n        \"size\": 239484541\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4683_Weather6.tar.gz\": {\n        \"sha256\": \"4a4ba6adf2c4d787c66abf232a5b84f6cc4c89ad9fc199f6efb804bc3b088e25\",\n        \"size\": 126183088\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4691_Weather14.tar.gz\": {\n        \"sha256\": \"86a09033895fd277f7d3e93720ce3c71ae58f915abfcf5f370b28c71e75515e6\",\n        \"size\": 204750050\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4692_Weather15.tar.gz\": {\n        \"sha256\": \"e692e1926be97dccabed7a8d595fe7a51940bbad69e9009db9ede3b301efa1fd\",\n        \"size\": 157107363\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4717_Weather14.tar.gz\": {\n        \"sha256\": \"921a947bf5979164645d0a6bb86ba88d7767d75b8a80c0dac2531785f6840ce3\",\n        \"size\": 145947367\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4725_Weather22.tar.gz\": {\n        \"sha256\": \"430be77b95d7bccd9f8ac515f2a0d87893e12760e4342459e47dcc24c54b0097\",\n        \"size\": 140303560\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4735_Weather6.tar.gz\": {\n        \"sha256\": \"3d5d40d4f958ab2c0db0091c1d3c33695f28cd7636cf5f9869b130453c1b6a84\",\n        \"size\": 132930051\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4737_Weather8.tar.gz\": {\n        \"sha256\": \"d3b59ca4810a699d2b378fa849cafe78e64c3a19658dac9c98b87ce23ea84de1\",\n        \"size\": 142632726\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4738_Weather9.tar.gz\": {\n        \"sha256\": \"b38787e57c455b7d8943b67a9f6cc8d18345ebf939f903e11e6e6c00c7390bec\",\n        \"size\": 108289483\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4754_Weather25.tar.gz\": {\n        \"sha256\": \"c60f475888029cbafe81dd4616297c2932ade6d04655dbaf2a3816511caa3c88\",\n        \"size\": 158370667\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4758_Weather3.tar.gz\": {\n        \"sha256\": \"be436fc2dfc02c80745e24b9bd9463435cf466eaabe45aa5475cb4bd7f264f05\",\n        \"size\": 199016601\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4762_Weather7.tar.gz\": {\n        \"sha256\": \"a14c403b9e0252fbc07d53b84011dca596e0458baac144692985a0085c2885f7\",\n        \"size\": 389588968\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4776_Weather21.tar.gz\": {\n        \"sha256\": \"656722baeab2a198253f85c090019b415cb59d908d24df200f8b7e95c0a0234d\",\n        \"size\": 175589852\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4792_Weather11.tar.gz\": {\n        \"sha256\": \"6798e4e0fd402a48e452b1b111a596662f35a98005d2a177b792c12b2dcd51ad\",\n        \"size\": 110811171\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4805_Weather23.tar.gz\": {\n        \"sha256\": \"f139d66c1f18bb6c87814a0d6e8cb1f4df2db4f919f56d988efbf1555cb50466\",\n        \"size\": 132454095\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4825_Weather18.tar.gz\": {\n        \"sha256\": \"7853cd9c624efd2d94e37f9ee53afd64d5e17e5b9aeba21c60ef8720428039fb\",\n        \"size\": 167317167\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4826_Weather19.tar.gz\": {\n        \"sha256\": \"b4bfa7574d3379e656b5fa0155c6b29444fc1d8efc9f51d4ff23bc96438515c2\",\n        \"size\": 149114945\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4830_Weather23.tar.gz\": {\n        \"sha256\": \"be88b1c567988cc9e66a90bfefe2ee01d121cdfb5af0c7048a65802bc404e635\",\n        \"size\": 131055171\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4833_Weather0.tar.gz\": {\n        \"sha256\": \"16fb53a887ad010b32ce03064708bb8194aeef9360cb7c4ea39b3a08ed269abe\",\n        \"size\": 216395944\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4834_Weather1.tar.gz\": {\n        \"sha256\": \"5902d2a2e2c41ae6e278b699c0d84484a398ce60e7c8e5aa2d29151c1e4d245a\",\n        \"size\": 162635687\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4842_Weather9.tar.gz\": {\n        \"sha256\": \"7ad0e744307c72ded7b73c2433687f5e68a5babcf21de4e88b56f9f72b568db2\",\n        \"size\": 130545362\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4846_Weather13.tar.gz\": {\n        \"sha256\": \"35675a93b47a723d213c72e74bfbb54350b22f39dbf494a833e0f3938018b19a\",\n        \"size\": 113591381\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4855_Weather22.tar.gz\": {\n        \"sha256\": \"40615350bf1a9762e3b094740cc1fbf0a1e2083bd9ddda938acf20b54cbd76db\",\n        \"size\": 132044255\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4873_Weather14.tar.gz\": {\n        \"sha256\": \"77af78bdf130c6efd9c5760619c733178f0a2633a53c5468b2514e278b912ef6\",\n        \"size\": 127558286\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4883_Weather23.tar.gz\": {\n        \"sha256\": \"0513bf4d03289d8783c189ce6aee45b9a061a98f7f0c7d4781c45e77efe4c6d5\",\n        \"size\": 132096544\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4895_Weather10.tar.gz\": {\n        \"sha256\": \"e31756e26138a294666519306acff71ecb623bf1776061fe31aad4c576bb660c\",\n        \"size\": 195261119\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4901_Weather8.tar.gz\": {\n        \"sha256\": \"62c1d7e7c32cca2bb89417841f1aaaecafe20f8b61de021fa7626b6c2c70aa11\",\n        \"size\": 138086106\n    },\n    \"SignalizedJunctionLeftTurn_Town12_Route4920_Weather9.tar.gz\": {\n        \"sha256\": \"75c39e8f0592d2be64bd8459d538c696f645907b9cf8d5e76e1e9836959e6463\",\n        \"size\": 134204724\n    },\n    \"SignalizedJunctionLeftTurn_Town13_Route3590_Weather23.tar.gz\": {\n        \"sha256\": \"93baf2a894794959704065ecc4b0071d4f8433af7ac80757a88b2b249741d537\",\n        \"size\": 204758802\n    },\n    \"SignalizedJunctionLeftTurn_Town15_Route26968_Weather12.tar.gz\": {\n        \"sha256\": \"4454eaba16b76a028eafef6e9a35cce79cb4913582e1c3a873357a44b579a232\",\n        \"size\": 434545718\n    },\n    \"SignalizedJunctionLeftTurn_Town15_Route26978_Weather25.tar.gz\": {\n        \"sha256\": \"b15a0a53e704cb85a821733cea08d0b6c168b0e9d9833cae97684d3c23af796e\",\n        \"size\": 385300760\n    },\n    \"SignalizedJunctionRightTurn_Town03_Route26775_Weather2.tar.gz\": {\n        \"sha256\": \"2de8ac23a8065e8f5bb1f00e8625fe54afff4ecbf74d327d412bb549a2537af9\",\n        \"size\": 136186870\n    },\n    \"SignalizedJunctionRightTurn_Town03_Route26800_Weather5.tar.gz\": {\n        \"sha256\": \"75694ee6c6d84b82c87615d6db595ca69e2519b162feb8b16c9dfb4df5bcae14\",\n        \"size\": 128266980\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route26946_Weather13.tar.gz\": {\n        \"sha256\": \"03c99728f343ff1b84d443dd1c2ca9c71d65f51874d98a410d8508b8281c6740\",\n        \"size\": 141032643\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route26951_Weather20.tar.gz\": {\n        \"sha256\": \"5bed7a8681b7d5bc2ca51460444846bc764722eebf8a1d3ec3806e38283d1460\",\n        \"size\": 143822800\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route26956_Weather26.tar.gz\": {\n        \"sha256\": \"5c283820cd32527e5ad1fbc12e209f78e7ae95a1a8f3102de33b999bdae296eb\",\n        \"size\": 225561009\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route26966_Weather10.tar.gz\": {\n        \"sha256\": \"d763c548b71edf8ded9519be6848a62f3e3fa35ecb987ee5a901b73e061f928b\",\n        \"size\": 163544541\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route26971_Weather15.tar.gz\": {\n        \"sha256\": \"c413aa9c4f85bd43f0abb378614155fd2ddd33b39c510eafd24a724de9f16cdd\",\n        \"size\": 180973485\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route27001_Weather25.tar.gz\": {\n        \"sha256\": \"4e5d854d8c27b348160bd5132e2db2721ee76e80b1377d63079a2ceef70bca2d\",\n        \"size\": 168287402\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route27031_Weather6.tar.gz\": {\n        \"sha256\": \"bd708e37ca48dafa94f7d9e96f12fb87a82aee3bfed47911322e6b4e625af279\",\n        \"size\": 158407199\n    },\n    \"SignalizedJunctionRightTurn_Town05_Route27041_Weather18.tar.gz\": {\n        \"sha256\": \"53cc95cb7928765be3715746b522da87304e54ebf9aad99b276f80073c3ba9b0\",\n        \"size\": 165612502\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26672_Weather15.tar.gz\": {\n        \"sha256\": \"d7a17309c581cf7a36ec90daad34a65ffe8d85708f55d56624b389e80b63feff\",\n        \"size\": 49441041\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26682_Weather1.tar.gz\": {\n        \"sha256\": \"8e19a48357dad903b8eb782fbeb0e332790adac11c3e9a338118cad3385c6836\",\n        \"size\": 81094455\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26687_Weather7.tar.gz\": {\n        \"sha256\": \"099930170d8cd336b7d190f5ee43d46e31d2cf0af886aaeac71f7a7b5057d2b7\",\n        \"size\": 103928420\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26707_Weather3.tar.gz\": {\n        \"sha256\": \"76117fc462d2f74aa9b3cf8abea45c673c4f1cd3fb462df9f424bef44d7d2956\",\n        \"size\": 66170461\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26732_Weather6.tar.gz\": {\n        \"sha256\": \"74614bdd268161c45ba289651b50e2e33c92a307616ad9518d9c40e244d553fa\",\n        \"size\": 50245954\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26742_Weather18.tar.gz\": {\n        \"sha256\": \"312fb5eba3e73e502f1f8675ba1d838f34eef66351ac321101f7ff8696012881\",\n        \"size\": 90780218\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26747_Weather23.tar.gz\": {\n        \"sha256\": \"dac01057058e28cf4dbdfcc0a5d57069d317aca974e0ec37b7ac9c1231166e3f\",\n        \"size\": 48137027\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26752_Weather2.tar.gz\": {\n        \"sha256\": \"944f8932b42d47411fb52e2018d4dd5c73a5fd0f732f544bb1bd7b11905a7594\",\n        \"size\": 72538516\n    },\n    \"SignalizedJunctionRightTurn_Town11_Route26762_Weather13.tar.gz\": {\n        \"sha256\": \"a386689920d57b6d47625595c44d37c656bfea03e89baf962339490128e5e71c\",\n        \"size\": 51594144\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2044_Weather10.tar.gz\": {\n        \"sha256\": \"4148401f5df38e4ebccc4a3556741aae64a9e39933057f3996aceb10f25f4c40\",\n        \"size\": 303679015\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2047_Weather13.tar.gz\": {\n        \"sha256\": \"bae9ac8a668f9e7b62ee6e60616e4ec5207080c9f54375e65e0b5b33cf3c399c\",\n        \"size\": 306187658\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2050_Weather8.tar.gz\": {\n        \"sha256\": \"04e03adcdd42033420137a8011b4baf6918f0b6235806c2fa5aa34d1e9f47736\",\n        \"size\": 231436305\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2053_Weather19.tar.gz\": {\n        \"sha256\": \"305531c63d114271c720e2a646e1fae201fc31c67062f990b467450fff204241\",\n        \"size\": 282758488\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2057_Weather23.tar.gz\": {\n        \"sha256\": \"901e8d1ccaf50447a09fb1e105045d84078b9d4d211005131167584c96e57475\",\n        \"size\": 182170982\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2060_Weather0.tar.gz\": {\n        \"sha256\": \"cde938e0dc60ea87d903dd6688649126dce5636c7e62fcf41a03bcaf6927eb42\",\n        \"size\": 146436590\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2062_Weather2.tar.gz\": {\n        \"sha256\": \"5dffabf86c27a6b42bd276d09bec99928ffa731e12228f417cce600c4d69c3eb\",\n        \"size\": 134221071\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2824_Weather10.tar.gz\": {\n        \"sha256\": \"d25efa43f979ff6f884c27ad00bb1ff6a5d408eac54de05524a489afcf11d174\",\n        \"size\": 200209488\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2827_Weather13.tar.gz\": {\n        \"sha256\": \"78bcd7e3e1b5bdcdfbe2dc019c63a5a610830dce80dfe55f6369e080ac1f3cf2\",\n        \"size\": 171202682\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2829_Weather15.tar.gz\": {\n        \"sha256\": \"673a2cbac05ff58912eebcbb26581bf425b2dcaae59da0c0ded81f630c11a0da\",\n        \"size\": 113637683\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2833_Weather19.tar.gz\": {\n        \"sha256\": \"744ece4d87e9a56001136dc618b6cb54bb660a285474f7b6d5d578d2642d8f5e\",\n        \"size\": 142581444\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route2843_Weather3.tar.gz\": {\n        \"sha256\": \"ebb254d69986f168d3ddd589c26295831dabf7815701710e0aece36a5c2b326a\",\n        \"size\": 196775070\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4925_Weather14.tar.gz\": {\n        \"sha256\": \"b64d84ac719925fdcee5a6e57dea5962abb288024a1cc75906b2768482e8eaa8\",\n        \"size\": 175635612\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4929_Weather18.tar.gz\": {\n        \"sha256\": \"6dd51df170d1ce0de14db4ae32c23b809f0f94b4a9696c8c45e6fb08b6abe044\",\n        \"size\": 152337662\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4933_Weather22.tar.gz\": {\n        \"sha256\": \"7a6faf95043703cc04f53d0a5d31c124360d2a42f1e2f746e208f8dddf57056e\",\n        \"size\": 151872845\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4937_Weather0.tar.gz\": {\n        \"sha256\": \"77257957f652528f7c53975c1a87366feef08afdccbb60642f7ba6bd1b14099d\",\n        \"size\": 123555294\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4939_Weather2.tar.gz\": {\n        \"sha256\": \"cc8f9e5e59e2c67e54b55bae7daf5fb78b15561a8dbb47c0998aff9293d6af54\",\n        \"size\": 174871363\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4944_Weather7.tar.gz\": {\n        \"sha256\": \"4b183054e4f17791779ddae62b181c406380b91d90011c7a91df7f16d1ca68ed\",\n        \"size\": 135993980\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4945_Weather8.tar.gz\": {\n        \"sha256\": \"aae15c2e3ff693701b1358206c34cb2063bc212fec1b19a27ce74e65abef0868\",\n        \"size\": 141623086\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4946_Weather9.tar.gz\": {\n        \"sha256\": \"f4683698886420f212095d6099507fefb359bec0fc921dde01ea248c704fbd88\",\n        \"size\": 121989134\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4951_Weather14.tar.gz\": {\n        \"sha256\": \"e8ec1fc8909047b4a4bf5258f73479563701f29c4bd717b4c4d00533d02bbe1a\",\n        \"size\": 148063606\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4953_Weather8.tar.gz\": {\n        \"sha256\": \"fec76c02c597ced50609f345e3ca025dcf34f1cdfffb468f58eb00332e25c33f\",\n        \"size\": 168267333\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4959_Weather22.tar.gz\": {\n        \"sha256\": \"0ffb00bc4f9f9d904a0fe35770b32bb4d69d645931e377c2a97c10f16675f4be\",\n        \"size\": 141185332\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4961_Weather23.tar.gz\": {\n        \"sha256\": \"acf40e9d56c7e2adc9dad09854419679c5e5a033bf12c95ab8406405cf81d225\",\n        \"size\": 159590264\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4962_Weather25.tar.gz\": {\n        \"sha256\": \"a72d83d723d4af708212055912e6b2e6128122496f22b1a3a1b5b0fed1378413\",\n        \"size\": 166293578\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4964_Weather1.tar.gz\": {\n        \"sha256\": \"2562047e71a4c3c49293b6d263ea6e1280e39406f25b5df2dab6c712d867be03\",\n        \"size\": 178494724\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4966_Weather3.tar.gz\": {\n        \"sha256\": \"b6d0da45f2c05be93974004677d378ab05c2282ad43e638db6a129390793faec\",\n        \"size\": 220703010\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4969_Weather6.tar.gz\": {\n        \"sha256\": \"28442c2a22fe1e163753345f60151ad59e2eddc1fc37c4b8f1fc65cce7a80c54\",\n        \"size\": 150231265\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4970_Weather7.tar.gz\": {\n        \"sha256\": \"6df891266e07cafd1b6fca6cf7de397e33dd68a68d0634c451a588a6fcaa2c72\",\n        \"size\": 152663807\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4974_Weather11.tar.gz\": {\n        \"sha256\": \"df0a61fd8d3d57487d25d285504d723ff53d41c7e0e48a9a5c1d31a7a7555c1b\",\n        \"size\": 173414853\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4977_Weather14.tar.gz\": {\n        \"sha256\": \"04fc19890fc369e82be270202831235fbf87fc8131400e2b786e0b803141df9a\",\n        \"size\": 119566884\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4979_Weather8.tar.gz\": {\n        \"sha256\": \"670201351091bbbf34f4f921d48f3e05ed85c94963ae853a3d8ad4970053aaea\",\n        \"size\": 114417904\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4987_Weather23.tar.gz\": {\n        \"sha256\": \"4d813497395d8912a2acf54b21d769d2b196798c5db9c4858a66fb550fb81e83\",\n        \"size\": 148004478\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4993_Weather3.tar.gz\": {\n        \"sha256\": \"6ce6f8a48e3a995e2fdc98d762397d035f7fadc57db9f5a67c84c68606c2ed90\",\n        \"size\": 182354711\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4995_Weather6.tar.gz\": {\n        \"sha256\": \"85f8573f5a325bb14661910318a24952aea86d513705308755f3458cbfaf7092\",\n        \"size\": 122465555\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route4997_Weather8.tar.gz\": {\n        \"sha256\": \"b846b71dd2c72fc35e11cb50a14481e15a16de884189ad1f62cd01681ef1a678\",\n        \"size\": 127921143\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5003_Weather14.tar.gz\": {\n        \"sha256\": \"27920c899ba0f979c87ae79f0aa97d9925ea6398257add7bc7a2c9dedefa3751\",\n        \"size\": 112523766\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5008_Weather19.tar.gz\": {\n        \"sha256\": \"47231dd5ffad94b024fcbceec8cc4cc09de282fd194a4b7e872a47623fb4c474\",\n        \"size\": 128251416\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5014_Weather25.tar.gz\": {\n        \"sha256\": \"0d93d2108193703cc1787619817ae3a1b174d86b9bb7d1d751cf72e72b585e8c\",\n        \"size\": 111325934\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5018_Weather3.tar.gz\": {\n        \"sha256\": \"bae49f845cb0f8dbe73b77d5b3aa18e2caf9c4b15612e01cff9a3b656ad24f0d\",\n        \"size\": 159526057\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5019_Weather3.tar.gz\": {\n        \"sha256\": \"b50114075ed91f1194ed19a19937a6460af923c3063dd7a6ed7f4e07b3a41dcb\",\n        \"size\": 145520996\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5021_Weather6.tar.gz\": {\n        \"sha256\": \"508833e5edb2628f4e2e371e2239e148b68feb5f39e77a8d5231c5f1a2ba807a\",\n        \"size\": 115791821\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5022_Weather7.tar.gz\": {\n        \"sha256\": \"e12f835afad93ff4b576179c9c05fec642ab40e1f0ef650682aa12d40fe7838c\",\n        \"size\": 226909662\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5024_Weather9.tar.gz\": {\n        \"sha256\": \"31a37d5cb4d50aaaee6138d1a51fad70c313e19dbfd77032c66831dbd17c553c\",\n        \"size\": 101791147\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5025_Weather10.tar.gz\": {\n        \"sha256\": \"ca6d5ee500bef723e4e46f5d46cbaa5d1fc9d16cf2753a329bf51dadc5f88351\",\n        \"size\": 151434847\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5033_Weather18.tar.gz\": {\n        \"sha256\": \"11277ecc78a784ad82647bca0185f97e6aea7343f3fbe3b272a331b27be18e29\",\n        \"size\": 120753157\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5035_Weather20.tar.gz\": {\n        \"sha256\": \"9180f32e33afe1c2fd482c21fa14ad7c92ed23554bbfa2b8a44131aa2aa565f0\",\n        \"size\": 161979814\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5036_Weather21.tar.gz\": {\n        \"sha256\": \"af82d14b4729b39597ff859fc1c9bfbb4cb5accbe5958a8b0a69b8247f22b0eb\",\n        \"size\": 180701025\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5044_Weather3.tar.gz\": {\n        \"sha256\": \"7dda123c92aff12e8df0403c56858358a2988cc9cbf6703ed13fe3871fe5ddc4\",\n        \"size\": 145747102\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5051_Weather10.tar.gz\": {\n        \"sha256\": \"a46787dbb103591ee92590abeee20e65181054037c07228da1b8d526182e2400\",\n        \"size\": 196619171\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5052_Weather11.tar.gz\": {\n        \"sha256\": \"85432eab939d68cf7e962fedb275e5195732788312e4ea5c142a1f67c0d824e4\",\n        \"size\": 284322185\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5053_Weather12.tar.gz\": {\n        \"sha256\": \"020546971a0a4a692b46cc7a466c579796c8b54c67d8c39b5c9d82da7142e0f2\",\n        \"size\": 168605457\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5056_Weather15.tar.gz\": {\n        \"sha256\": \"203696bee90476e7b1f074c840eb8063aa7992b9dca0f5a4f5dcbddbd81d4be1\",\n        \"size\": 115532885\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5059_Weather18.tar.gz\": {\n        \"sha256\": \"840111e294a669a45df9735edbc096ba919f6f902b85c942358e4be515af6c85\",\n        \"size\": 166549852\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5064_Weather23.tar.gz\": {\n        \"sha256\": \"004ce33fb644f9272a3965c3ff5f2b6d507da93982c538d4cdf052f69d12bc9c\",\n        \"size\": 185347831\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5065_Weather23.tar.gz\": {\n        \"sha256\": \"138eca2c0d601923368c03b25cf1c3bf66bd6b998c1fbbf8f05734184cb4ddee\",\n        \"size\": 107258572\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5067_Weather0.tar.gz\": {\n        \"sha256\": \"63958148120d8c8fe8102ea914a107bf5c4e506393bd38bd9f180f6f70a738d9\",\n        \"size\": 177770325\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5068_Weather1.tar.gz\": {\n        \"sha256\": \"93942136ab42cfbe9e8ecb7e582a1ce50464e3f3f80bbde1b1d1f3134d65b2ef\",\n        \"size\": 165383548\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5080_Weather13.tar.gz\": {\n        \"sha256\": \"42e7682fd066177ef916cd3772ccd0c9e4a2832fa8b255bb557a6e2f17b610d3\",\n        \"size\": 118534293\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5087_Weather20.tar.gz\": {\n        \"sha256\": \"0c914742f6b5d890ebc8c2c7360ebe5cc09b37c3ce3d74319d84cb53505457e4\",\n        \"size\": 131549850\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5092_Weather25.tar.gz\": {\n        \"sha256\": \"3de078e6a1bb7b2ae27bc14a7e03de7bfa4e100dd078f97fa8ace7dc0dcc1851\",\n        \"size\": 143443764\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5093_Weather0.tar.gz\": {\n        \"sha256\": \"5d4120a942e8c595d40c24eb894ca497de3bbbbd696393dad790879ad56290e3\",\n        \"size\": 113500266\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5094_Weather1.tar.gz\": {\n        \"sha256\": \"b9d160c1c7e2282996d3c83ca10e89a320365f6fedd5f94502b39837d5bc56b9\",\n        \"size\": 128189040\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5100_Weather7.tar.gz\": {\n        \"sha256\": \"5b9c5ab7806aa44f30ec4ff1e6674c790bbe78f27c283cc7c3a23fce8b6b692d\",\n        \"size\": 160770142\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5119_Weather0.tar.gz\": {\n        \"sha256\": \"8a39608c9852ea0f99c13b07c9d2a0c7794d17f031dbc293f48b4c41a38599ee\",\n        \"size\": 175007523\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5122_Weather3.tar.gz\": {\n        \"sha256\": \"f4fb9942387bd6391587d3a251998cde802a6ac4ae5b66b5946720d05c01d650\",\n        \"size\": 148593725\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5123_Weather3.tar.gz\": {\n        \"sha256\": \"226e75fb9e818828d2219d42074b40952a5e37494a1d3bc30e135376169d74a7\",\n        \"size\": 160222213\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5124_Weather5.tar.gz\": {\n        \"sha256\": \"57061d11a4bf96ebdbc468c54ff273e8e14a652f3697995990ee36679b873208\",\n        \"size\": 169069687\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5126_Weather7.tar.gz\": {\n        \"sha256\": \"15e30a68320b8918940afc4ceea128f2753ef9a218b48638595ed5b8c7302b98\",\n        \"size\": 141928247\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5129_Weather10.tar.gz\": {\n        \"sha256\": \"d78a1677998aa6cf08bb721db6e88ccbdc92651ec1bc7f6b2ddc38611c25726c\",\n        \"size\": 127172121\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5133_Weather14.tar.gz\": {\n        \"sha256\": \"8d8c5bd8199f3d1df43d58b12454758b8a1349eff19ea7ed21618b274de67e1f\",\n        \"size\": 115636079\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5147_Weather2.tar.gz\": {\n        \"sha256\": \"e0dfc47619e857b45882148f0baae1aaf1ec499aa2def3375d4ae1a5a19ec9d7\",\n        \"size\": 209269276\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5150_Weather5.tar.gz\": {\n        \"sha256\": \"1114fdf07509e2be6f4f3e24170b70d47bb9c6c2ac3282b517f210930da2bdc0\",\n        \"size\": 131609530\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5152_Weather7.tar.gz\": {\n        \"sha256\": \"50400b4fb425352071dcdb18ef55d2a15c71278d7090d707ee0c3183112068a0\",\n        \"size\": 172233554\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5155_Weather10.tar.gz\": {\n        \"sha256\": \"62cb138f426387a429d946b3fc0d2255bd8da4b7a7f27a66475ee9e6000dccc6\",\n        \"size\": 151014350\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5159_Weather14.tar.gz\": {\n        \"sha256\": \"239a638a22b492bbb6dc42cf3d32e85ad91edd98863c48211d2c8ce8ad84b1c5\",\n        \"size\": 134371802\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5160_Weather15.tar.gz\": {\n        \"sha256\": \"02b30dfc03dc9f1469c985ac36f358809e522b1ad91862b915ac802893e3441b\",\n        \"size\": 133736971\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5164_Weather19.tar.gz\": {\n        \"sha256\": \"b2967dbd07c37ec31ef2be31134eb21cde3f7121574fa27b1ef146d32ca8cf2e\",\n        \"size\": 136886605\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5179_Weather8.tar.gz\": {\n        \"sha256\": \"641aed4785155878196f6ca7aa335ab6ddea4808d6a79eec74061a02ccc5cda3\",\n        \"size\": 116140725\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5182_Weather11.tar.gz\": {\n        \"sha256\": \"489c52cecc07387562a7a053a78c30228cfc81a1e38625ce529b8e9181281e69\",\n        \"size\": 123694549\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5184_Weather13.tar.gz\": {\n        \"sha256\": \"2195a9c876c7ad298794138384c81af165f9252f351388d70724d4bcaf041a11\",\n        \"size\": 95565559\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5186_Weather15.tar.gz\": {\n        \"sha256\": \"eb676bd66ec2e6d30d00a9c4ccfe681cad74618c5634b62cee209bf2a858fafe\",\n        \"size\": 197225206\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5189_Weather18.tar.gz\": {\n        \"sha256\": \"4f4f6334f6fd74b885d287b2cb2b9a11d34643c8ad32c48681f6a10532a79c9c\",\n        \"size\": 172350909\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5191_Weather20.tar.gz\": {\n        \"sha256\": \"79dfc6fdc81cbd019c730b2f0b1594e3609c66a2230f8136a5c2f19fbf0415df\",\n        \"size\": 119684886\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5197_Weather0.tar.gz\": {\n        \"sha256\": \"7823c0b4081fff30d2cf904d1ca9a137e9a30081278677858730369a4dd57f28\",\n        \"size\": 134832556\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5198_Weather1.tar.gz\": {\n        \"sha256\": \"e46f3e5540142ea18bb6c802f22d38b471e882395c087d4e6a64d7e3122f9cac\",\n        \"size\": 127275913\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5212_Weather15.tar.gz\": {\n        \"sha256\": \"c8fd59116f35e308e91639b172b06ab5624e98e48822ce02c2f2b2e685884baa\",\n        \"size\": 133841231\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5213_Weather8.tar.gz\": {\n        \"sha256\": \"4addba8e74d3f87fd3c1bfbb336beb462cf5f244549cde823fa07829fc1ca250\",\n        \"size\": 127528953\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5221_Weather23.tar.gz\": {\n        \"sha256\": \"ba40f1be05b5adcf9d6cf3d0a32187ce5446e72c6e2ac340892c4378a45c7ef2\",\n        \"size\": 108781623\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5222_Weather25.tar.gz\": {\n        \"sha256\": \"878aa6d70697f2f027d98f80f4687ea0d86e44b48271fa69d90c56c02c8da25e\",\n        \"size\": 101181233\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5223_Weather0.tar.gz\": {\n        \"sha256\": \"94ba55df5bda820fe87b9f265f3c6add73b84c115857cd798afe28ebe11b04b3\",\n        \"size\": 109645134\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5228_Weather5.tar.gz\": {\n        \"sha256\": \"deb79255a7edb83e0bc29d8f2d3680c81ace525492e09b92d8297222ea244682\",\n        \"size\": 139564758\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5232_Weather9.tar.gz\": {\n        \"sha256\": \"883e129e829993433f8a03a46a025fcfb808f414a283e97aabd9412a4d3711f4\",\n        \"size\": 182944572\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5239_Weather8.tar.gz\": {\n        \"sha256\": \"4d3e19665614eb8a1c23211d324cd4a0d53736fa5c4f363123c37bfc971c4c5a\",\n        \"size\": 141654432\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5241_Weather18.tar.gz\": {\n        \"sha256\": \"7cbcf5c5fd40f915829a33298409dddd1783cab413d1a99a8676aaf38853fe4a\",\n        \"size\": 128461400\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5244_Weather21.tar.gz\": {\n        \"sha256\": \"b039b57974ac030d360c619858d16e23405f98d2627f8fa57072bde22b0f7d37\",\n        \"size\": 133555548\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5245_Weather22.tar.gz\": {\n        \"sha256\": \"18a54965895b9e13eb0426e7de931a0f3b905bd7047ffec103be49c77d6ea52f\",\n        \"size\": 132614379\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5250_Weather1.tar.gz\": {\n        \"sha256\": \"e281df3c100032aa164429344f79b32f61c3a3e05b46a9f088b93f7144d2628c\",\n        \"size\": 147251770\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5252_Weather3.tar.gz\": {\n        \"sha256\": \"18f6d9a3022512e9dec9c5ce68ff57ec8667bc9491c22e0b04412368ec3831d9\",\n        \"size\": 133537598\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5253_Weather3.tar.gz\": {\n        \"sha256\": \"506bc10b34468796492f6890959ece28f89a59b6cbf9cc364756b2bd1695fe8f\",\n        \"size\": 136936406\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5256_Weather7.tar.gz\": {\n        \"sha256\": \"e9e2154d2e241a9271e38a8d8d0889083ee9482a56d17eaca5599ab08cff9b74\",\n        \"size\": 168133847\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5268_Weather19.tar.gz\": {\n        \"sha256\": \"6ff312ccf62dd56c6cb8c27cb5ae7a8f0859292934d13600c84ab42a23bdc109\",\n        \"size\": 173666398\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5274_Weather25.tar.gz\": {\n        \"sha256\": \"c0c6472591bd0802c1a0f97f6557856d06b057f252706954adfb917092146649\",\n        \"size\": 144295340\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5276_Weather1.tar.gz\": {\n        \"sha256\": \"e0fee45fdf6614348346beed59dc6f6c1355df7221dffdabe962d58eeb7fcbf0\",\n        \"size\": 153341954\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5285_Weather10.tar.gz\": {\n        \"sha256\": \"85bc8020457793324d94208c007785007826b93cd25906cebc4bfc1c4f661ef5\",\n        \"size\": 130467616\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5290_Weather15.tar.gz\": {\n        \"sha256\": \"832ccfb9f1934a7fa1e6039bbe02dafc3fd2830ea06752b18ead940dae43dca8\",\n        \"size\": 110967271\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5291_Weather8.tar.gz\": {\n        \"sha256\": \"36f686f537fddff61099de2b3f96cd687e50196900c5706aaf082d4d24ebbfd9\",\n        \"size\": 143372752\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5297_Weather22.tar.gz\": {\n        \"sha256\": \"dd13628ea6cc19e63402452e90a1d9995f0d513fddf372b1f1e2976e3796a845\",\n        \"size\": 134974345\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5302_Weather1.tar.gz\": {\n        \"sha256\": \"d164fdec82e8e9a1e278bfe53b6051c758f042da41f87ec3dd5661fe404ffaca\",\n        \"size\": 119469942\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5313_Weather12.tar.gz\": {\n        \"sha256\": \"214e5d851aa198a94b49c0c81fe47e501f81b72d6bbfdb37d29c9aba539187c0\",\n        \"size\": 112190662\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5317_Weather8.tar.gz\": {\n        \"sha256\": \"4c173ef9d0355be1b998b570bd5b1f26eca944bffe6217217c93ac7cd92c2d5d\",\n        \"size\": 156538222\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5319_Weather18.tar.gz\": {\n        \"sha256\": \"0ec5aa91465e9e4aaaf9d3cc57d8d5f63ecf4e2c9b6fc2faaba09b1782cdd3b0\",\n        \"size\": 159801716\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5328_Weather1.tar.gz\": {\n        \"sha256\": \"c5f7ad437c9f5a44e405350d044cf0560312821da477f61d1b6aeb52c8cd1da7\",\n        \"size\": 227200497\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5337_Weather10.tar.gz\": {\n        \"sha256\": \"c7f4d84ac9f0d71d36535725babe3b61e4a11652e3d631383a7b974bfb4689eb\",\n        \"size\": 158039602\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5348_Weather21.tar.gz\": {\n        \"sha256\": \"180e7f6fe3e51194d9f48b871c0e2fac84d794b55b4dd47f9c68e7af30826324\",\n        \"size\": 130161737\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5354_Weather1.tar.gz\": {\n        \"sha256\": \"4d351f9c5eec35e5a4f363c18bd303c0ad0de0ac32f9aee9e3dd7085d4bedebb\",\n        \"size\": 272895661\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5356_Weather3.tar.gz\": {\n        \"sha256\": \"9444ef81628947cb620b375e242fe4c82a1a00cab217076d7844b5b148b228a9\",\n        \"size\": 120316732\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5360_Weather7.tar.gz\": {\n        \"sha256\": \"217f5f5d022ad21310871402f9e9db3250eb0b21984a2845f8f60eef23de2561\",\n        \"size\": 209223447\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5367_Weather14.tar.gz\": {\n        \"sha256\": \"dfc328318a8507e8507773d8e8cb42de2ce006394c9c9d8128471e50a8f636da\",\n        \"size\": 122683244\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5369_Weather8.tar.gz\": {\n        \"sha256\": \"21630de1c6e1cb9033b3d6db4e51007df848530a110d93c5ea8f1f8c0b052142\",\n        \"size\": 145351119\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5370_Weather9.tar.gz\": {\n        \"sha256\": \"1bfdd58a723bd02fdce71ca26af6c3aafc25873d518b022478baa42628bbf8c3\",\n        \"size\": 95630960\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5372_Weather19.tar.gz\": {\n        \"sha256\": \"4de499a875d835e7965b89733275ff519994a3e1eb67f03c18e29d61deca5c9f\",\n        \"size\": 142517657\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5374_Weather21.tar.gz\": {\n        \"sha256\": \"ab4926622d50f40e69d2937b7a47950405c41317c093540f408da192fb296e33\",\n        \"size\": 154896395\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5379_Weather0.tar.gz\": {\n        \"sha256\": \"3d441bcf7dd73a2796732cfdaff5c9e497e7f33f70f447980062f503e0eb68d7\",\n        \"size\": 167690543\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5380_Weather1.tar.gz\": {\n        \"sha256\": \"78646aa71da3070e147f0cb25dacc701fc881bb584c6516219d76bcbe3afab79\",\n        \"size\": 196792408\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5385_Weather6.tar.gz\": {\n        \"sha256\": \"c1da6aef189381b8429f9a00eb66bfc576536f3b264b52f2278cfe9dfa404af1\",\n        \"size\": 127764516\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5387_Weather8.tar.gz\": {\n        \"sha256\": \"85b7583898633b34d523597121e26e1116cf8789b7928389e1d25e111c2cde0a\",\n        \"size\": 152608459\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5392_Weather13.tar.gz\": {\n        \"sha256\": \"4b1d11b98b3b2ff3b36d1d803e40a881b7e0c414205a28381c99696adf49de13\",\n        \"size\": 101494415\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5398_Weather19.tar.gz\": {\n        \"sha256\": \"42b056177e7c9703fa939cf77411aa6a15e9d249f5c1385260d2427140bac6a8\",\n        \"size\": 122653995\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5399_Weather20.tar.gz\": {\n        \"sha256\": \"c275e498c804f50592374126e7d5602f627b3f6a427e5a953229f19fb0265299\",\n        \"size\": 144961414\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5407_Weather2.tar.gz\": {\n        \"sha256\": \"5c4d797884c2a0b977b0b716a0f9e02239ddb994ad77fcd98dc8b91dac7df6ce\",\n        \"size\": 132918636\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5410_Weather5.tar.gz\": {\n        \"sha256\": \"b669b2f3a0e6603ae454f60a21d36def84949f2f5f9af40010d466877770675c\",\n        \"size\": 139485616\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5413_Weather8.tar.gz\": {\n        \"sha256\": \"73fc1941edb1f32855523a44a4816a347d258975e244b87ee9690fd6161dcfc6\",\n        \"size\": 107760723\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5423_Weather18.tar.gz\": {\n        \"sha256\": \"baabe7d8d314cd7025f9158ac268f0968c41fbaaf9112c471548d01537f0f2f8\",\n        \"size\": 162686610\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5424_Weather19.tar.gz\": {\n        \"sha256\": \"31eccd3e341eb5254300f6a9a64fe41a770016dec17eb48c802ed3cd726942cf\",\n        \"size\": 132984222\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5431_Weather0.tar.gz\": {\n        \"sha256\": \"133bb9418ba03d1e7844cfaa5b214801b21bbe91312f691d9010d9632443fc44\",\n        \"size\": 128442952\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5435_Weather3.tar.gz\": {\n        \"sha256\": \"f0415310152835738f22a587c890649b7c39323679ac3ac431924e900b114d14\",\n        \"size\": 129529741\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5436_Weather5.tar.gz\": {\n        \"sha256\": \"68f70037cbfd3cfee14153a25195b0eee80de811565cae216a7276705548d285\",\n        \"size\": 246530707\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5437_Weather6.tar.gz\": {\n        \"sha256\": \"dd7688529377368be9d216228e776d1b618a82c147504dca656f8f273840cc18\",\n        \"size\": 134706086\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5442_Weather11.tar.gz\": {\n        \"sha256\": \"d69e39ec0a6e0034879657ce41d5fc6344983bbce7ff71563a0face38e91d12c\",\n        \"size\": 130168297\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5445_Weather14.tar.gz\": {\n        \"sha256\": \"fda11a2067c6b9a452d77949d26adc51322babf74844a80cf14c35675e34f8c8\",\n        \"size\": 118560062\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5448_Weather9.tar.gz\": {\n        \"sha256\": \"434bf52d6ec8dbea64c5858695a9e7b34d454d2ec2b595b59e198f7a1b646c66\",\n        \"size\": 190908945\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5450_Weather19.tar.gz\": {\n        \"sha256\": \"6f74dde3c7f1166169e0d1c4cd0401be95462a0aa8c710018c278103680c1434\",\n        \"size\": 140855571\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5455_Weather23.tar.gz\": {\n        \"sha256\": \"fe3188c1710b11673e840f696c015b1777db0ee20323268fc2bb271c5cdeb82c\",\n        \"size\": 106801048\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5457_Weather0.tar.gz\": {\n        \"sha256\": \"dcf65c7f2d1209f7f03d1052a892b023214bb58f30c9e33e638ee2ddbe4b0d0b\",\n        \"size\": 157655736\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5458_Weather1.tar.gz\": {\n        \"sha256\": \"0863e13b4b5e0e0fb3de7f8c883b74ade6883da6c7f6457e6e2f6ac88f1a53e2\",\n        \"size\": 220592898\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5465_Weather8.tar.gz\": {\n        \"sha256\": \"9e03ecaff4af46d04ebf550068b1453b6e74d4ead14253b10f5e075b374dbb9c\",\n        \"size\": 148102663\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5468_Weather11.tar.gz\": {\n        \"sha256\": \"334c5e9f96bbe6fcd7ebdc5f7c1b25f77ddca01d4c7fed0c484ca7f984efeab5\",\n        \"size\": 98346872\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5476_Weather19.tar.gz\": {\n        \"sha256\": \"04753808a7e3c3999573f87ee88a361da3f14db4cfc0ca89b50cd603d330575f\",\n        \"size\": 140241583\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5477_Weather20.tar.gz\": {\n        \"sha256\": \"3cad71b1f3d37cb1b2f357ae0b2c05353180bfbb572f2c8b5aba639b0932db2d\",\n        \"size\": 131765321\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5479_Weather22.tar.gz\": {\n        \"sha256\": \"72bad271da60a142b23f0ce0156504312d52cdee2785e9565c1a6dcb1e12d828\",\n        \"size\": 130249060\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5482_Weather25.tar.gz\": {\n        \"sha256\": \"c9ebc4c02b6532c3e541c77b5e8f2308d8fe85e2300aa726f068f0ddea7e6afe\",\n        \"size\": 107502240\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5489_Weather6.tar.gz\": {\n        \"sha256\": \"4a0e4f4369d559bdb471d069e98dac453860d45b48f17a4348c22c15a136f6f1\",\n        \"size\": 235972649\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5503_Weather20.tar.gz\": {\n        \"sha256\": \"a24682e4a58b71267bfeb3dc7ce38bdc029516b79fa1aefafc4bcdbea1563439\",\n        \"size\": 258404798\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5507_Weather23.tar.gz\": {\n        \"sha256\": \"85457a9b8f1486a9e0088d55264f0645248180511460daeae68944b863420cf7\",\n        \"size\": 174921749\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5509_Weather0.tar.gz\": {\n        \"sha256\": \"a28c9f3547d4118418f7b30f0d8e3e4fe31c82e5d9e13624cc89d69a010c1661\",\n        \"size\": 235259840\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5513_Weather3.tar.gz\": {\n        \"sha256\": \"6a104b27b1c1b55d7b896ec5cc486f436ca12e420d52b40cdaaec931fdddece3\",\n        \"size\": 174471551\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5521_Weather12.tar.gz\": {\n        \"sha256\": \"4bca9c2668c26b36af39b8d3034b014ded2af8d9de771842a83719cafb2bd6f3\",\n        \"size\": 156976076\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5523_Weather14.tar.gz\": {\n        \"sha256\": \"4349164f5bd367fd865467bfb8e50a68fad2e6664789bc77b86059c166c607dc\",\n        \"size\": 544363856\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5527_Weather18.tar.gz\": {\n        \"sha256\": \"53058a51de625a1290ad3e370e2890c57fe880882ace8ee4949aa6c8b39ec4b5\",\n        \"size\": 224245741\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5528_Weather19.tar.gz\": {\n        \"sha256\": \"d1a7eaa9a62011c95031b21e5c0264a6a51775f212949c154a4610c6fa199b2f\",\n        \"size\": 135738139\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5534_Weather25.tar.gz\": {\n        \"sha256\": \"a26469fcb538853154475152927115d4bbb28f998fb82da59d2f55d2f56fb959\",\n        \"size\": 99165918\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5537_Weather2.tar.gz\": {\n        \"sha256\": \"33b725885ce3a01ca805a9eada37ed42e4b92a0e32bb969cf6e7576dce14f754\",\n        \"size\": 123829484\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5538_Weather3.tar.gz\": {\n        \"sha256\": \"8a96afa42a0d24e099ef73689a21c1846a6733503f36d59226fb297b182b6320\",\n        \"size\": 328422376\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5539_Weather3.tar.gz\": {\n        \"sha256\": \"b0a7604c654a6abe0e00e52f746e4e8e3b0c41dac1e7ae6d0d4e33d4a95c0521\",\n        \"size\": 128683389\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5541_Weather6.tar.gz\": {\n        \"sha256\": \"e35816c2b2230b3e09d399d364427a1068e77314cc11c6649a199a2b7c418d70\",\n        \"size\": 104806518\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5544_Weather9.tar.gz\": {\n        \"sha256\": \"b2afd339483a14dd2e2fe2352716e3d35686bc6e7ec4d2f1ee6d47ac21c869dd\",\n        \"size\": 122506123\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5550_Weather15.tar.gz\": {\n        \"sha256\": \"976029298e83628ce9d7b9687940d01dfc20de12993d96c260f3487033390b08\",\n        \"size\": 126885658\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5552_Weather9.tar.gz\": {\n        \"sha256\": \"02987168b28cf399f5229d1e171a77f1d8b594cb4289bd40ad525974b1a6b086\",\n        \"size\": 101391440\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5555_Weather20.tar.gz\": {\n        \"sha256\": \"c2f774fa4a4fe0711995672dac9a500efae045f4f4322fd30da8ef14cb0af160\",\n        \"size\": 142293365\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5559_Weather23.tar.gz\": {\n        \"sha256\": \"0acfb592cf3bd420d349ca2bdd902551757508dcbedd06016a267edc6c914c0c\",\n        \"size\": 117444341\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5560_Weather25.tar.gz\": {\n        \"sha256\": \"e03ccf38a45ff16469c13a176ebcc3ac6d7297131c8892e374dceff57d80c0ea\",\n        \"size\": 100831512\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5562_Weather1.tar.gz\": {\n        \"sha256\": \"989ec5d3ef44e272f7ce42903d0e1b7cebed194878522b13a1f1173e84d7ca76\",\n        \"size\": 128276736\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5567_Weather6.tar.gz\": {\n        \"sha256\": \"a9a8db41604864e44a8ead11b1a998266906bfe63b4998418da879b25adfdce2\",\n        \"size\": 119233308\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5577_Weather8.tar.gz\": {\n        \"sha256\": \"00962b8272371f7587499c932d750566b8f75569ad3019cab6dba06f72aecf15\",\n        \"size\": 129947451\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5578_Weather9.tar.gz\": {\n        \"sha256\": \"b692eee101af43e7ca5aea9f1df432bd5d51a096db77cf8c2eabb96fc454d1a5\",\n        \"size\": 108695354\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5582_Weather21.tar.gz\": {\n        \"sha256\": \"2af91e25f8440b5cd2dff4c4f3791f5fc699617ef3d4d51ec839d3ed29fcaa7c\",\n        \"size\": 189746248\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5587_Weather0.tar.gz\": {\n        \"sha256\": \"65e5ddfe624cbde6558b63a9165317ba6116c89276b0e958dd23d990032eb29d\",\n        \"size\": 290708125\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5598_Weather11.tar.gz\": {\n        \"sha256\": \"ce64c2e8fc8e78182e6bd67f4a17b5c9ca17cdf1d57769b48fb6542d4cf9ac22\",\n        \"size\": 109183586\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5599_Weather12.tar.gz\": {\n        \"sha256\": \"564209e549e8a84f4f1de97e96359378418c185012b86447f8d1f73229ce1403\",\n        \"size\": 108571296\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5601_Weather14.tar.gz\": {\n        \"sha256\": \"115ffbfed100518993178c97505eefcbae1c8d6d7f1f8a8b7fa637427e5a3d0c\",\n        \"size\": 113728331\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5606_Weather19.tar.gz\": {\n        \"sha256\": \"df416b1746d392c20eb89230dc1b96ed95a428cccd7e3fe6b079488dae76ddca\",\n        \"size\": 152875526\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5608_Weather21.tar.gz\": {\n        \"sha256\": \"f509010e00c071d02f14093b4a18cdd08c5120382e50c3b4fbad0e765091a38e\",\n        \"size\": 107134129\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5609_Weather22.tar.gz\": {\n        \"sha256\": \"2d5bf593c85de8714b848b20ec37b1838b282585359a37991a6e0c2b179808eb\",\n        \"size\": 218248150\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5620_Weather7.tar.gz\": {\n        \"sha256\": \"ce964a288181d5e20dd06eb04d2319d524469ec9b772f46cea80f4746ab10582\",\n        \"size\": 146069744\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5621_Weather8.tar.gz\": {\n        \"sha256\": \"57552ec2f8088aa314036c226e5a487497a55e1326ce8cf64aabc23ffb48952b\",\n        \"size\": 133014910\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5624_Weather11.tar.gz\": {\n        \"sha256\": \"23a1a8e6b8a8a4617668681393394220e66325ce13987b61bbdce25c9f137181\",\n        \"size\": 114276913\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5627_Weather14.tar.gz\": {\n        \"sha256\": \"180d3af269fbf1b868321f9b611ea0d8887bb865ce500c03442e093319265c4c\",\n        \"size\": 130616898\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5633_Weather20.tar.gz\": {\n        \"sha256\": \"9d1ff669b54e3d96835d3c2fd1bcd46a5f687c7b59f4b6057183171585444074\",\n        \"size\": 161105315\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5636_Weather23.tar.gz\": {\n        \"sha256\": \"f16dbc3fdc6cd22f7218c45d68416f28ae7519216e071a45baf6dff89f13087d\",\n        \"size\": 217304064\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5637_Weather23.tar.gz\": {\n        \"sha256\": \"fe0c9d3205154cefa5ce1e9d323c22e88a6bb7da47048a35f74c2cba72c3df14\",\n        \"size\": 104319210\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5638_Weather25.tar.gz\": {\n        \"sha256\": \"f81f7d0a90451e52c55e82993a5acb1ead0569be6d0a6ffd7fcbb2f18b18227d\",\n        \"size\": 123930887\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5645_Weather6.tar.gz\": {\n        \"sha256\": \"08ee9d819648fcfad95d598db818d048690f3272948c5eb4d76a52acd2cc642a\",\n        \"size\": 136303080\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5646_Weather7.tar.gz\": {\n        \"sha256\": \"49063fb5822193f1adf2123baa6506db9ce58002f354bac62b48f69659e8b38b\",\n        \"size\": 222205281\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5649_Weather10.tar.gz\": {\n        \"sha256\": \"a189e65da9645b0aa9ae7de59b11342a83576218bb0feaf6dc1630860ec0afab\",\n        \"size\": 193643631\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5650_Weather11.tar.gz\": {\n        \"sha256\": \"220278c4cdf7347a30f5a65f6cf919d0989b4430f425f738851163552f057725\",\n        \"size\": 103493941\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5658_Weather19.tar.gz\": {\n        \"sha256\": \"f9dd8197c89fef57eca0fcde7fed7ab277ac783f000191ffd70b2a495d730de1\",\n        \"size\": 169305659\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5668_Weather3.tar.gz\": {\n        \"sha256\": \"f1a306b2e45deab6981c039f68e7f7d53222fc8b653f9c9e89b326c392410dbe\",\n        \"size\": 154446116\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5671_Weather6.tar.gz\": {\n        \"sha256\": \"e31e9c5b1f0080b2153d109cd72db967f76181f1aebc7d5620e1354efea5ef1a\",\n        \"size\": 127447588\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5687_Weather22.tar.gz\": {\n        \"sha256\": \"3aa62e2138de874bbafa1557300ed71f292c5ed257700a5212973b0d596a1b09\",\n        \"size\": 133724853\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5692_Weather1.tar.gz\": {\n        \"sha256\": \"17bb4bb72151d62ca3661f0778c6eaffb8a757107564edcbc128055459c20507\",\n        \"size\": 263929450\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5693_Weather2.tar.gz\": {\n        \"sha256\": \"73d5253eeff4f779bff67932c5dac8db0e40f7a5005223a537bcb77029e00243\",\n        \"size\": 233078009\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5694_Weather3.tar.gz\": {\n        \"sha256\": \"573d27af8d5ec90461253c0eb198321c66bbb22638cf0e7fdf3703bc34f5069b\",\n        \"size\": 137459732\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5695_Weather3.tar.gz\": {\n        \"sha256\": \"a3bde5612982cc172f22e5b4685cf36e704d6c0bfa69d1cbb1fb8055e9ac359e\",\n        \"size\": 329912998\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5696_Weather5.tar.gz\": {\n        \"sha256\": \"6d4778d15cc5044af9af9e36bd9c75c1ab160db87b116da7ac7e1deccc56bd25\",\n        \"size\": 123003434\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5703_Weather12.tar.gz\": {\n        \"sha256\": \"d02ec221ad0d24b3c78bf871a1f09325f28d514380b20cf2a066afe8a964e13e\",\n        \"size\": 100981617\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5705_Weather14.tar.gz\": {\n        \"sha256\": \"0b7d853a499daeb7c33d447bc0b70aa88ab7a0b53495e48bd2cec81760ee51e8\",\n        \"size\": 119765217\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5708_Weather9.tar.gz\": {\n        \"sha256\": \"5a9e9640221d5ccf3dc06aa548c7dfe7dfecaa4f96ac6484cd2b5f1ed004d921\",\n        \"size\": 106323050\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5711_Weather20.tar.gz\": {\n        \"sha256\": \"162d9f91d0e8960a1d641bfc2b4117ef24fb6d96c5a7b1cad62742abce813e17\",\n        \"size\": 208503990\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5722_Weather5.tar.gz\": {\n        \"sha256\": \"6fa5a07c3b86310cad6a3a9ab5d2bad6832d095194727603d2bd0bf2874e4b54\",\n        \"size\": 156290179\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5734_Weather9.tar.gz\": {\n        \"sha256\": \"7d48cb0f400b2d2a5c24a04c3036289f6fedd6a50c09b6bc163b9e59a0912bcd\",\n        \"size\": 177527852\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5736_Weather19.tar.gz\": {\n        \"sha256\": \"bde5109577f0c7310502b7bac6054c8be97ceb55ba4f47437092cdcee819d878\",\n        \"size\": 152047299\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5737_Weather20.tar.gz\": {\n        \"sha256\": \"882178be8240bb04c2f1630a602a1074861651db3f4b1c535201c1b83b114576\",\n        \"size\": 164605707\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5740_Weather23.tar.gz\": {\n        \"sha256\": \"fdc3cab7ac874a458de76a59c48a4979a35116bed6e1ba455094d20cf264e268\",\n        \"size\": 205811168\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5744_Weather1.tar.gz\": {\n        \"sha256\": \"3c5c372ca40ff3886809cad80ad4a51d3edb6fefc2466b1c16a6956db40c3484\",\n        \"size\": 157456573\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5754_Weather11.tar.gz\": {\n        \"sha256\": \"ca41f4649729ab96332fe2a80ee4e97e633791f3d491f2e9c94e33c0e3b6ac74\",\n        \"size\": 102704524\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5759_Weather8.tar.gz\": {\n        \"sha256\": \"ed7ad7fc9a553bf9ebd672b26968b5615f595405dacdaa5bccdb29b94458e712\",\n        \"size\": 105281120\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5765_Weather22.tar.gz\": {\n        \"sha256\": \"ae1a1d33280502fb504b19fc714f1656d3da43f4e9bfc70670f6655ece31a1e8\",\n        \"size\": 117831770\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5766_Weather23.tar.gz\": {\n        \"sha256\": \"fb2f343d5a018a48b0a8c7e23e9db094481c5eab5562e7eb488fe446acb09ed7\",\n        \"size\": 213160404\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5770_Weather1.tar.gz\": {\n        \"sha256\": \"bb435dc51fa3672688da022d487b8e23134ce6733d20fa99f636c70aa1f5cba3\",\n        \"size\": 125915742\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5774_Weather5.tar.gz\": {\n        \"sha256\": \"e0889cbe65e59b7865efcb0ef21128ecd048029247c2b6030997c1e982b09fc5\",\n        \"size\": 148757878\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5775_Weather6.tar.gz\": {\n        \"sha256\": \"e069b2eb036cf58d38cacd623c4f1a226e94f030d9a4a6b26a639737a6190ced\",\n        \"size\": 157673131\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5778_Weather9.tar.gz\": {\n        \"sha256\": \"4516aa5edf225d16ac0fe67738c3da32dc212f72fb5544d1f19b592912b89669\",\n        \"size\": 118149875\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5780_Weather11.tar.gz\": {\n        \"sha256\": \"899398dcc954db2638dc9db2cf47ec0cefda7ebbd88f119a5647935b49cbaa57\",\n        \"size\": 86300535\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5787_Weather18.tar.gz\": {\n        \"sha256\": \"04350b264593de490fe61cddb0a74a23e4b007b82b1d4f9f3996a55312b4ae93\",\n        \"size\": 154910549\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5789_Weather20.tar.gz\": {\n        \"sha256\": \"2ca4b5fdecdefac0fe7015de5eace1b1707dcec1bc7e4ae4a6e350a11138b2a0\",\n        \"size\": 133977837\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5790_Weather21.tar.gz\": {\n        \"sha256\": \"81dbae005ad61177b53e7591de3ab6c56035f89736aa0e83da6c6cd04f3290df\",\n        \"size\": 120056921\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5796_Weather1.tar.gz\": {\n        \"sha256\": \"ecfebb30a2e0f86c19a90623ed371f5eaefd125a3ece9f9fa63cc988b75787a4\",\n        \"size\": 128129843\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5797_Weather2.tar.gz\": {\n        \"sha256\": \"0431de052b6b2f5402a9a3ca24b7c0cc91c854749eb285a72e654d71c3cc60cf\",\n        \"size\": 155080290\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5801_Weather6.tar.gz\": {\n        \"sha256\": \"0aea7e8067ed0857c428a56340c92b2aaf210b56aeb02893d24e7d40c9991fba\",\n        \"size\": 132811175\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5804_Weather9.tar.gz\": {\n        \"sha256\": \"9d378399a2e13199e073456774eb14e029f4e3fd5e6ddbf28b9874a93cfb4452\",\n        \"size\": 146040434\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5809_Weather14.tar.gz\": {\n        \"sha256\": \"f845a87bbb11423d847b60214eea03644b7400cf08c39cbe556c9a817dd869f1\",\n        \"size\": 118443709\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5817_Weather22.tar.gz\": {\n        \"sha256\": \"b403d0d945a7e00651ba9d2789b353c1931f7f3ceb0bebe99a170c4f01b8bb8b\",\n        \"size\": 160144373\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5822_Weather1.tar.gz\": {\n        \"sha256\": \"98d8ec0defc47aa258335468f3d8377e1aaab28480231a012768b3e664dba620\",\n        \"size\": 124188944\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5825_Weather3.tar.gz\": {\n        \"sha256\": \"b18fff57215f2d5511b90ca2d0158eb53676c99f8e51790e0f556f9b4ebda6ad\",\n        \"size\": 170269105\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5826_Weather5.tar.gz\": {\n        \"sha256\": \"d3cdbd78e77b633ad40c150c80e6580ab471ca8ba5d0a460fcb8c3b602c84cf1\",\n        \"size\": 127331904\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5833_Weather12.tar.gz\": {\n        \"sha256\": \"a392cea5cec548d6e6d6e3abb11b00d8c3fb4f042229fafae13bace4079d3fa2\",\n        \"size\": 101198049\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5839_Weather18.tar.gz\": {\n        \"sha256\": \"d9928a4b1c82f0003a0cf2853df2f2b8bb0c563c615b7fc8794f9ea8c0927a66\",\n        \"size\": 122201861\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5844_Weather23.tar.gz\": {\n        \"sha256\": \"c023befb0d2d609ac0d400902fbeb11d6a5a879444b94882b128e0869637d8d4\",\n        \"size\": 130079602\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5846_Weather25.tar.gz\": {\n        \"sha256\": \"9738104b262986ae976de958bcee274267a1422215b028b870e19b84b97dfb5c\",\n        \"size\": 116227128\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5847_Weather0.tar.gz\": {\n        \"sha256\": \"003d0eeb7535bcc43b029d9e3901b120f5ccac57a5b3d9a136a6398c7ba54fc4\",\n        \"size\": 180318005\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5858_Weather11.tar.gz\": {\n        \"sha256\": \"c7dc3a49cdbf6425da2590bcd1797d88eccd23941527478bf1b877e3d647ae38\",\n        \"size\": 97140613\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5859_Weather12.tar.gz\": {\n        \"sha256\": \"e72836442325c1c25b954e104e885588de70e1d410b961b7083d434c9f6a111f\",\n        \"size\": 108520766\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5860_Weather13.tar.gz\": {\n        \"sha256\": \"fec152cf5d18ed46ed4ecb0aa2c94e50cbf5298a701a90c96a9d1bda393b50c0\",\n        \"size\": 117932792\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5862_Weather15.tar.gz\": {\n        \"sha256\": \"0c9227880447e38732d4d3eace8457ef4b507a68115d31af29d05f99bdddfcf0\",\n        \"size\": 191134573\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5865_Weather18.tar.gz\": {\n        \"sha256\": \"5ecd6760f3bb539fdf683f22f48be51afdaa5a1191919e3bcc4d33f7a8e1abf0\",\n        \"size\": 131245964\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5867_Weather20.tar.gz\": {\n        \"sha256\": \"520af62105495d90c6f7facf72ceb6519f1c82c670eb9dd359f51048496db274\",\n        \"size\": 130314605\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5869_Weather22.tar.gz\": {\n        \"sha256\": \"0a40b8d2299cac23971662682aa4677dac0a6f4cd933ba9d224a6b7856b80585\",\n        \"size\": 227878029\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5873_Weather0.tar.gz\": {\n        \"sha256\": \"c3618cd6b716c40f57b8079d13d73d155fbed4fde6073a0cbf97143d0c99425e\",\n        \"size\": 175282368\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5874_Weather1.tar.gz\": {\n        \"sha256\": \"8d4297bb5a3fdb17b117f3b88b26c1b8e74ef34af1db43fbaf081997ccfed064\",\n        \"size\": 256516625\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5876_Weather3.tar.gz\": {\n        \"sha256\": \"64b276d8d5c1b6c60bcf2863acf63b093200909a4b477670141fa58aa9fb8715\",\n        \"size\": 267900063\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5881_Weather8.tar.gz\": {\n        \"sha256\": \"2be189e8a747351ff504575455609ebd6dbe0be8f9dc1642edc65bcc822a2409\",\n        \"size\": 126118118\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5886_Weather13.tar.gz\": {\n        \"sha256\": \"959fdf41ad7c8fcc8b2fa714c410ca81949b6d5c7867c7c6e007b7c8fab26ae9\",\n        \"size\": 113465817\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5899_Weather0.tar.gz\": {\n        \"sha256\": \"139bd12dd4f954d02bfcff470759b1921c1f929ec9fb6a1e54d5e1d73f06513a\",\n        \"size\": 162154922\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5902_Weather3.tar.gz\": {\n        \"sha256\": \"655f7cdf99e8ef1c221162c9cf23413219fcf192edb995874db337ba2cc7d64d\",\n        \"size\": 108802645\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5903_Weather3.tar.gz\": {\n        \"sha256\": \"a015d12ef7c1ec89d9d9ed3a85890b905d4fc30ccd6e79a48f025105176f8ab1\",\n        \"size\": 119565735\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5905_Weather6.tar.gz\": {\n        \"sha256\": \"d4d74e183eb90620f87c144059600157d1f72286bb3fa733439b8f6f2c835495\",\n        \"size\": 128130700\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5907_Weather8.tar.gz\": {\n        \"sha256\": \"4d4fe9fcae9d6cbdc64c144d0e96b0cc4294c78c61f6e325e6790441069d7367\",\n        \"size\": 134883553\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5914_Weather15.tar.gz\": {\n        \"sha256\": \"b693e4497ca35a91311d8faeb7dd95690aba28796d522f131a7dcc232b8a47c1\",\n        \"size\": 110020309\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5917_Weather18.tar.gz\": {\n        \"sha256\": \"ca92aee4d6097bc6febf030f2870a35de18cea2caeadc154bf04745e58ead364\",\n        \"size\": 294955520\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5919_Weather20.tar.gz\": {\n        \"sha256\": \"86cd2999999dfc868b22c132b9d68a92d94a418624e304ab9657c1b872b32a07\",\n        \"size\": 126421647\n    },\n    \"SignalizedJunctionRightTurn_Town12_Route5922_Weather23.tar.gz\": {\n        \"sha256\": \"8fca0fe3de1f68f9ec4c1159d46ca20975944a18edf4cf580a9051fb72d8f659\",\n        \"size\": 147431920\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3603_Weather10.tar.gz\": {\n        \"sha256\": \"6f03e4e87b811977ef1551c7e7f432f5bc7cb79bfc6bc45cf86f6bfe5c073522\",\n        \"size\": 301799449\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3604_Weather11.tar.gz\": {\n        \"sha256\": \"1e50df3a6a8f1e34850b461fd70cd433afd4fefeca51253a3b5aec3d334eb283\",\n        \"size\": 125117313\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3605_Weather12.tar.gz\": {\n        \"sha256\": \"a0366be1776f2397da97b04e938ae284a5ef3044d9ff0d09665964651dc1fb70\",\n        \"size\": 128314017\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3607_Weather14.tar.gz\": {\n        \"sha256\": \"862dd4ad07076ff043d622bfbc5a8474906cfe3ae7665fe73225fa1c4d3fbc4b\",\n        \"size\": 140832930\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3610_Weather9.tar.gz\": {\n        \"sha256\": \"077a2d4444885b493f955ea7da596c5121704074c139d2eb1ac2dc2256c8ba0d\",\n        \"size\": 181944177\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3611_Weather18.tar.gz\": {\n        \"sha256\": \"dbdb7ca0acd0373944da531999524808d927774eb07796866ff79edc7e2b0bc5\",\n        \"size\": 145104125\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3612_Weather19.tar.gz\": {\n        \"sha256\": \"c28c00740177f74cc08510fdfea087055a110de3c066551742fbd84a25b5b490\",\n        \"size\": 175203473\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3613_Weather20.tar.gz\": {\n        \"sha256\": \"6595bde19daa86186ecd708c782ecfc06047aa762e78e4ea800c8d7114711cde\",\n        \"size\": 205180837\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3619_Weather0.tar.gz\": {\n        \"sha256\": \"1a9ec05e550a07a5a3c9a6f71538831cef5064fc819cc40bd51b8ecf910ab69f\",\n        \"size\": 164326015\n    },\n    \"SignalizedJunctionRightTurn_Town13_Route3622_Weather3.tar.gz\": {\n        \"sha256\": \"38684bf1bdfeeeb9e03f076e0cb2a73e22c6570f68cf6eec10223c6d8a991962\",\n        \"size\": 165405868\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27018_Weather18.tar.gz\": {\n        \"sha256\": \"7a1c2c483d97bdcba3816a8bf86446e926193c52f22c6774d5d4d019d1e09ae6\",\n        \"size\": 483930921\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27023_Weather23.tar.gz\": {\n        \"sha256\": \"72268e3f935a49470195737c6fd9cb51cfe4ba9f425a06a6f55433aad42e4d23\",\n        \"size\": 433481357\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27028_Weather2.tar.gz\": {\n        \"sha256\": \"b0f73737d3a10886586ded5123e872e41efc208b9b19435805de394c509e56de\",\n        \"size\": 396054349\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27033_Weather8.tar.gz\": {\n        \"sha256\": \"571d39c508926fdfcc4a0dcb35c7a8ab53b9e68618ab5f75c2d2687c1ea376c4\",\n        \"size\": 371656770\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27043_Weather20.tar.gz\": {\n        \"sha256\": \"d902fe54887980c7fef1aeb5ac7cfbe5386b15e0e504571a5233389472cc4b5e\",\n        \"size\": 382864526\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27048_Weather26.tar.gz\": {\n        \"sha256\": \"b78069c84c6e27fb06ff05f5acb3391b00a14b17cbb81843eede8c82094526e8\",\n        \"size\": 455060019\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27053_Weather5.tar.gz\": {\n        \"sha256\": \"671750ec7d0a6ce9fb6e2de4a7d2c258bc7aabfe3137d00bb5d20fae28a34d9f\",\n        \"size\": 401810570\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27058_Weather10.tar.gz\": {\n        \"sha256\": \"e6704a84fa9da229c9bb983ffffbba5a5c76ac9349d4bafcac46881221c3e32d\",\n        \"size\": 420767923\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27063_Weather15.tar.gz\": {\n        \"sha256\": \"0ed74fe5ee17c806c84dba4a9132eb358cb146401d8cf1b90dedc105be95bf7c\",\n        \"size\": 347363725\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27068_Weather22.tar.gz\": {\n        \"sha256\": \"1c209c7986357f82f5eb22bc12b92b2f593ab7f9f2ed0d1d696180c121fe8f28\",\n        \"size\": 418947402\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27073_Weather1.tar.gz\": {\n        \"sha256\": \"bdab7d20a729278668afd7102abecd408b6bb08bd12838b73896923daa21dd32\",\n        \"size\": 444154939\n    },\n    \"SignalizedJunctionRightTurn_Town15_Route27083_Weather12.tar.gz\": {\n        \"sha256\": \"a591ea53019137acc0b17dcbce222065db00c687525028c6f9699fed26125e80\",\n        \"size\": 354776181\n    },\n    \"StaticCutIn_Town05_Route26396_Weather15.tar.gz\": {\n        \"sha256\": \"ad35cd19095129ac5e73c437b38dfc1cd589bbce8951705c32dde3751ac58697\",\n        \"size\": 332528866\n    },\n    \"StaticCutIn_Town05_Route26410_Weather6.tar.gz\": {\n        \"sha256\": \"958db733b2ca2d08c94fc092e3a633efaab0a8255653a48259612b48230a306d\",\n        \"size\": 236408029\n    },\n    \"StaticCutIn_Town05_Route26424_Weather22.tar.gz\": {\n        \"sha256\": \"72e8967b8ae21e3cda389cfccfd1b93b1d5306a0db8d8412246ea3be4e059a64\",\n        \"size\": 161799958\n    },\n    \"StaticCutIn_Town05_Route26431_Weather3.tar.gz\": {\n        \"sha256\": \"ba7d65447cd240e2f728a8b37e25d41b7e335f82a0f7eb302093da7219ffd997\",\n        \"size\": 206524138\n    },\n    \"StaticCutIn_Town05_Route26438_Weather11.tar.gz\": {\n        \"sha256\": \"6c65e57a73c5b70b694dc0c3144e858fad5cec8edb399c19895fbc829a169101\",\n        \"size\": 519194908\n    },\n    \"StaticCutIn_Town05_Route26445_Weather20.tar.gz\": {\n        \"sha256\": \"fe0fbbb3522d794febed59d8bcb5b98103fa7e3f14ac6c0edb62ba935efb850f\",\n        \"size\": 220396314\n    },\n    \"StaticCutIn_Town05_Route26452_Weather1.tar.gz\": {\n        \"sha256\": \"1dfc29d2b775da225ea3dded46cb07798e694ae970af58a0ab951dcb234b36e0\",\n        \"size\": 323736153\n    },\n    \"StaticCutIn_Town05_Route26459_Weather9.tar.gz\": {\n        \"sha256\": \"e5a99ba6bce7e3fc65d62df5c96740536e048102fd443a5debeafe63dff06a5a\",\n        \"size\": 255643591\n    },\n    \"StaticCutIn_Town05_Route26466_Weather18.tar.gz\": {\n        \"sha256\": \"5701e43e063ac8e548685f70a38466c1ca4585ef24e6164b5f20a6c2576ae6e5\",\n        \"size\": 203318189\n    },\n    \"StaticCutIn_Town05_Route26473_Weather26.tar.gz\": {\n        \"sha256\": \"1b51f20246567ef376a55ac02881e9e12b924ab745d0a85d980843f9b889d8b9\",\n        \"size\": 232684566\n    },\n    \"StaticCutIn_Town05_Route26480_Weather7.tar.gz\": {\n        \"sha256\": \"00758ca44e930021056a4123f579ee3ccf740f512b16e70f95253b3afbd2cfdc\",\n        \"size\": 646822083\n    },\n    \"StaticCutIn_Town05_Route26487_Weather14.tar.gz\": {\n        \"sha256\": \"a187554070ff45df41edd73266a443a600a794bb274faae030b90521f0342f27\",\n        \"size\": 272939669\n    },\n    \"StaticCutIn_Town05_Route26493_Weather22.tar.gz\": {\n        \"sha256\": \"4198e03e4081190a327e047682c616aba8d58004eb54b78034dbbd2bcf4da095\",\n        \"size\": 234391356\n    },\n    \"StaticCutIn_Town06_Route25358_Weather12.tar.gz\": {\n        \"sha256\": \"0568ec312062b12b9f903b69ac724654b653f857740cdc509d37963015555bb4\",\n        \"size\": 215317548\n    },\n    \"StaticCutIn_Town06_Route25365_Weather21.tar.gz\": {\n        \"sha256\": \"5ea9594f337b24a6d0c54d8c37c32d4d16fcb5ac7a02f6a56774e7eef3138941\",\n        \"size\": 175890726\n    },\n    \"StaticCutIn_Town06_Route25379_Weather10.tar.gz\": {\n        \"sha256\": \"31986f277b3a4bd605cd43bd7141246285a0ec7b6de1ed8b0d5cd57ae8e719e7\",\n        \"size\": 198482277\n    },\n    \"StaticCutIn_Town06_Route25386_Weather19.tar.gz\": {\n        \"sha256\": \"b93914689f2d56886db2e52d980c2fe485be0e6c835ecfad22316cddcd20743d\",\n        \"size\": 175356594\n    },\n    \"StaticCutIn_Town06_Route25400_Weather8.tar.gz\": {\n        \"sha256\": \"11d499de79380227f42c8bdbc12bb1ec25d51b784c7194554f16fa6c88fa4612\",\n        \"size\": 228288136\n    },\n    \"StaticCutIn_Town06_Route25407_Weather15.tar.gz\": {\n        \"sha256\": \"3a1390c3ae2919f6679d1c1dee0fdfd90afd69ebc8af74544053b41efbf5c3bb\",\n        \"size\": 203126556\n    },\n    \"StaticCutIn_Town06_Route25414_Weather25.tar.gz\": {\n        \"sha256\": \"c35f262d59990fa6f7b2acab0d7a307e95b0e21e36e3ed4e0f8dd01b45a99ee2\",\n        \"size\": 192598710\n    },\n    \"StaticCutIn_Town06_Route25421_Weather6.tar.gz\": {\n        \"sha256\": \"bc647c4a9af5137d4203fa98b71707f3191f4175caf1d17623a962dadd0f9509\",\n        \"size\": 235093866\n    },\n    \"StaticCutIn_Town06_Route25435_Weather22.tar.gz\": {\n        \"sha256\": \"cb93a4c22a34c85157c54126b6ea5d84580d5e8ab3bcc40ad00f9a91789c4d86\",\n        \"size\": 164151292\n    },\n    \"StaticCutIn_Town06_Route25442_Weather3.tar.gz\": {\n        \"sha256\": \"e1f33f19ba8d61d5b1490bfd89e452c18fd59a7ba7b6984e1873db54a1a9ad0a\",\n        \"size\": 251047799\n    },\n    \"StaticCutIn_Town12_Route1924_Weather20.tar.gz\": {\n        \"sha256\": \"69d15bb978da9e8e6c96e30c5086006c0216600639a1f54e85e68859115b2e5e\",\n        \"size\": 402286268\n    },\n    \"StaticCutIn_Town12_Route1925_Weather21.tar.gz\": {\n        \"sha256\": \"d5f1a7d5edb2cebff326ea34301b298cf5451645bc33d5606d2baaec6d8be462\",\n        \"size\": 384937520\n    },\n    \"StaticCutIn_Town12_Route1926_Weather22.tar.gz\": {\n        \"sha256\": \"61009283b8e4699b8dc60def6edf333d228834fb74f5f5eb04006f7b1eddc4f8\",\n        \"size\": 289178974\n    },\n    \"StaticCutIn_Town12_Route1927_Weather23.tar.gz\": {\n        \"sha256\": \"825e6d144acad819b3632c781adeef3264bf32f78089fc8d68a943df195a4de3\",\n        \"size\": 293132936\n    },\n    \"StaticCutIn_Town12_Route1928_Weather23.tar.gz\": {\n        \"sha256\": \"12ea5ba3c7c438067c2533ef5f0e10dec3c875de068e526ea7a5482ee35c5bb8\",\n        \"size\": 154618445\n    },\n    \"StaticCutIn_Town12_Route1929_Weather25.tar.gz\": {\n        \"sha256\": \"358178fcff05b960ea277f86d544b80c802c1b91d926824a3f2dd37f205337a2\",\n        \"size\": 131391120\n    },\n    \"StaticCutIn_Town12_Route1930_Weather0.tar.gz\": {\n        \"sha256\": \"54192fdc090bb81093e6f94b243f99d3a10c25662262bdb6cec65f38c6f5b5de\",\n        \"size\": 373245435\n    },\n    \"StaticCutIn_Town12_Route1931_Weather1.tar.gz\": {\n        \"sha256\": \"7a970dfc91bd86dd73019eae6f99fbb130c831984d6cf3eecb653333c86e4612\",\n        \"size\": 417131767\n    },\n    \"StaticCutIn_Town12_Route1932_Weather2.tar.gz\": {\n        \"sha256\": \"846181ea277a31a0acd58b072f0f83ffad19c3f6454eb2e5c7954f35fe945dad\",\n        \"size\": 200374395\n    },\n    \"StaticCutIn_Town12_Route1933_Weather3.tar.gz\": {\n        \"sha256\": \"a34912cfd1d7efe5d758e9c901f9ca9df5cc2ed48505fb72cf0234159c59cfa9\",\n        \"size\": 466165092\n    },\n    \"StaticCutIn_Town12_Route1934_Weather3.tar.gz\": {\n        \"sha256\": \"0e5e58276303e6838bcfe970bddfcd2a50b155d4f14d58d2ada667451da71dc8\",\n        \"size\": 199360724\n    },\n    \"StaticCutIn_Town12_Route1935_Weather5.tar.gz\": {\n        \"sha256\": \"ed7656071f0cbe781b571e71e067d39b613cdb1ea07cf338b186f35d5fc32024\",\n        \"size\": 439144090\n    },\n    \"StaticCutIn_Town12_Route1936_Weather6.tar.gz\": {\n        \"sha256\": \"4706ad390e5d2528967afac7201bd9d62d447832151704060fd145bac2ced642\",\n        \"size\": 468477486\n    },\n    \"StaticCutIn_Town12_Route1937_Weather7.tar.gz\": {\n        \"sha256\": \"0210407b7cb9468fe81448a4ed52fbe1f66ebcc99de2a66d8c9e5f6b54bd81af\",\n        \"size\": 416174611\n    },\n    \"StaticCutIn_Town12_Route1938_Weather8.tar.gz\": {\n        \"sha256\": \"afac47480c955e26d1f093a2dfb487245d3ca199f807ac2b7a590bb00b5d678c\",\n        \"size\": 372144125\n    },\n    \"StaticCutIn_Town12_Route1939_Weather9.tar.gz\": {\n        \"sha256\": \"86d717a9007523855b5f7d08bba5beb891b6b9720ec20393bb653485088c735c\",\n        \"size\": 466035086\n    },\n    \"StaticCutIn_Town12_Route1940_Weather10.tar.gz\": {\n        \"sha256\": \"c30f55aa443c07b67ac582c59c9594c5e2797760fb10fea187c3fe33d8acf618\",\n        \"size\": 291752793\n    },\n    \"StaticCutIn_Town12_Route1941_Weather11.tar.gz\": {\n        \"sha256\": \"e5a99d9994202efc92dba059b6eb1993850bb2e41e3a7a0178200762e20dc6e4\",\n        \"size\": 123984210\n    },\n    \"StaticCutIn_Town12_Route22114_Weather13.tar.gz\": {\n        \"sha256\": \"77beaf8a9466e1cda505250911f700d0c80d0383e4bf274c0dbbb699e3de9eb9\",\n        \"size\": 146066175\n    },\n    \"StaticCutIn_Town12_Route22115_Weather14.tar.gz\": {\n        \"sha256\": \"7561fe93a65b89bdb140dffd5645886a06262558a917c378d4c6ab0a6dc9aa35\",\n        \"size\": 396611978\n    },\n    \"StaticCutIn_Town12_Route22116_Weather15.tar.gz\": {\n        \"sha256\": \"9b90911846e686c63da69357a799b880ec6749d9151f65e198fb74cf0e5a36ef\",\n        \"size\": 161037337\n    },\n    \"StaticCutIn_Town12_Route22117_Weather8.tar.gz\": {\n        \"sha256\": \"ff62271867d8c69db95619b8ca952197006413a74f9e70d1cf6bf1ae7756d361\",\n        \"size\": 167152758\n    },\n    \"StaticCutIn_Town12_Route22118_Weather9.tar.gz\": {\n        \"sha256\": \"f44acf0b3567d51164a992913e253b475610ccc03dd68902238a0009bd97453c\",\n        \"size\": 193150087\n    },\n    \"StaticCutIn_Town12_Route22119_Weather18.tar.gz\": {\n        \"sha256\": \"81e8fd4c70622d0ded08c7dfe439af29bbee3a3fc67a4decfc4ab4517db5a0ae\",\n        \"size\": 446770852\n    },\n    \"StaticCutIn_Town12_Route22120_Weather19.tar.gz\": {\n        \"sha256\": \"f28f3309f6e9d866cada0ff6fc07ec7a9d2d201c8e6df82fef754fc6fbf949d3\",\n        \"size\": 306307782\n    },\n    \"StaticCutIn_Town12_Route22121_Weather20.tar.gz\": {\n        \"sha256\": \"cb49d8b6a437129f32ea24ba9bb9545a349c39ba40568a3aa65435620e227ffc\",\n        \"size\": 352240249\n    },\n    \"StaticCutIn_Town12_Route22122_Weather21.tar.gz\": {\n        \"sha256\": \"10f7c0627ed5aa5c6d17ee1be71ce18f78b40a3087897a8ddf5b8e7eac4958b1\",\n        \"size\": 314517287\n    },\n    \"StaticCutIn_Town12_Route22123_Weather22.tar.gz\": {\n        \"sha256\": \"cc9309e7900e703b0085ef51e16e718d3109c8d67c1d6a70fd6b05d1a4d03de0\",\n        \"size\": 337233734\n    },\n    \"StaticCutIn_Town12_Route22124_Weather23.tar.gz\": {\n        \"sha256\": \"762c11dfd536c09c450feff894e777ba305c33bf6945273a6876605d4d99c9ac\",\n        \"size\": 360500973\n    },\n    \"StaticCutIn_Town12_Route22125_Weather23.tar.gz\": {\n        \"sha256\": \"f2c67f19e338871db4bb7a01ecef9cea18af5f0504cbe9b31f4008b8b2f0acad\",\n        \"size\": 337261476\n    },\n    \"StaticCutIn_Town12_Route22126_Weather25.tar.gz\": {\n        \"sha256\": \"b033c2d2a85efee35122ebd67fd49e510a58fabb3dc19b1461e947b3a4f7117a\",\n        \"size\": 352285088\n    },\n    \"StaticCutIn_Town12_Route22127_Weather0.tar.gz\": {\n        \"sha256\": \"ed2e09364529acbd4409046181a6571af8884e73967faa7e7faf82e1aa51d76c\",\n        \"size\": 443571145\n    },\n    \"StaticCutIn_Town12_Route22128_Weather1.tar.gz\": {\n        \"sha256\": \"1f90c1703b7b54c399507613dc6c06d0aabd7e4aca8b4d6fca2d3c96151a978e\",\n        \"size\": 454080400\n    },\n    \"StaticCutIn_Town12_Route22129_Weather2.tar.gz\": {\n        \"sha256\": \"37a172dc3572951525c867d2fd0a4562c57164af991670dc2ab02af2a8ce64f2\",\n        \"size\": 317801678\n    },\n    \"StaticCutIn_Town12_Route22130_Weather3.tar.gz\": {\n        \"sha256\": \"dc8f6071e5811f2960fe2ec482b69d207920e182db6e543ed85f7ecf8dda451d\",\n        \"size\": 182696030\n    },\n    \"StaticCutIn_Town12_Route22131_Weather3.tar.gz\": {\n        \"sha256\": \"694cc9b767ca19e0f49275946fcfc1a3814efde4cf71e0299a637bf4884f8f9f\",\n        \"size\": 356221272\n    },\n    \"StaticCutIn_Town12_Route22132_Weather5.tar.gz\": {\n        \"sha256\": \"f3723e23f915fee7fc2edc2e316eee4fd307f83af7a9f02c5504b03d77283b76\",\n        \"size\": 346836806\n    },\n    \"StaticCutIn_Town12_Route22133_Weather6.tar.gz\": {\n        \"sha256\": \"ff6b198f3854c7703a578374da3a757b4b8470f61ff1b18af8681d006b063377\",\n        \"size\": 329441595\n    },\n    \"StaticCutIn_Town12_Route22134_Weather7.tar.gz\": {\n        \"sha256\": \"7b05936d2f45614c8f780646a07a252530382d8a1e3781590e40388878154a37\",\n        \"size\": 387477556\n    },\n    \"StaticCutIn_Town12_Route22135_Weather8.tar.gz\": {\n        \"sha256\": \"00b23ed25f06e9ffe885317082e90b575959d65654ffd7f9099137785d4c1b6c\",\n        \"size\": 325381433\n    },\n    \"StaticCutIn_Town12_Route22136_Weather9.tar.gz\": {\n        \"sha256\": \"bc46e0d9cc1cfcbab1f6f836e8f7ec4363499b449f87e686583b5c8bf71ff3df\",\n        \"size\": 315635163\n    },\n    \"StaticCutIn_Town12_Route22138_Weather11.tar.gz\": {\n        \"sha256\": \"bdbece5095090670ebc0210ea038afcc69781ea9a13ed02e2e610cf9c046173d\",\n        \"size\": 239871071\n    },\n    \"StaticCutIn_Town12_Route22139_Weather12.tar.gz\": {\n        \"sha256\": \"80b05a5eda92b84b1ffedf6f96f34b3116a16a388fbd1d9110be0051163d88e3\",\n        \"size\": 138608204\n    },\n    \"StaticCutIn_Town12_Route22140_Weather13.tar.gz\": {\n        \"sha256\": \"6c3b118aeaa3857ca58480f449524d4dc7d2af1ee9115134179af48c3c7a4c6c\",\n        \"size\": 381707140\n    },\n    \"StaticCutIn_Town12_Route22141_Weather14.tar.gz\": {\n        \"sha256\": \"b76b2e6191e2c00c3d13b1be664b1cc49c6c8c86889dfe6656767ada18943d70\",\n        \"size\": 147590761\n    },\n    \"StaticCutIn_Town12_Route22142_Weather15.tar.gz\": {\n        \"sha256\": \"6a417f017626e3e5c55831f641e83b28e417c0c5805fc1d6f673d02e9b650118\",\n        \"size\": 155663722\n    },\n    \"StaticCutIn_Town12_Route22143_Weather8.tar.gz\": {\n        \"sha256\": \"3bf76887dd2da170a848ae87d1315dbe019b1ffffd23da182c7c716a962da343\",\n        \"size\": 336055919\n    },\n    \"StaticCutIn_Town12_Route22144_Weather9.tar.gz\": {\n        \"sha256\": \"9c9230385b52141bfca754dd069a17045bece499a472c5979f3e7cfe721757fa\",\n        \"size\": 131073259\n    },\n    \"StaticCutIn_Town12_Route22145_Weather18.tar.gz\": {\n        \"sha256\": \"2fb61fd6937fb128c00893cbd6404096ea37f2eb12cf3605d6f79e3e2387f459\",\n        \"size\": 177949098\n    },\n    \"StaticCutIn_Town12_Route22146_Weather19.tar.gz\": {\n        \"sha256\": \"e0fd9885bf8d58b511705ea7273f6c4de5453756f6cbfe4bdb3a0ad60d5d305e\",\n        \"size\": 377853383\n    },\n    \"StaticCutIn_Town12_Route22147_Weather20.tar.gz\": {\n        \"sha256\": \"8db3077c1a3bdcbbaac968e204dba1fa94407237c4e8a5ae2867a9977ff876b8\",\n        \"size\": 305726973\n    },\n    \"StaticCutIn_Town12_Route22148_Weather21.tar.gz\": {\n        \"sha256\": \"6cbab84f68bf24c8deb2dbe329752a533bae9a9a853111a66fa608bef5b2b8c6\",\n        \"size\": 328294620\n    },\n    \"StaticCutIn_Town12_Route22149_Weather22.tar.gz\": {\n        \"sha256\": \"2b38534584f0d76aea564caa70f55b26654a17efc7a979e8b8f01675bf913dc1\",\n        \"size\": 301418845\n    },\n    \"StaticCutIn_Town12_Route22150_Weather23.tar.gz\": {\n        \"sha256\": \"1a12c5b3cb7dba9ac1e535090d21f924f7fe6908bf2075653cf60dd007e9eae0\",\n        \"size\": 285317947\n    },\n    \"StaticCutIn_Town12_Route22151_Weather23.tar.gz\": {\n        \"sha256\": \"d9ebbaafdbbab9a78926749d9d3a747044ce7a117d3f711438abbdfcc6283637\",\n        \"size\": 292817763\n    },\n    \"StaticCutIn_Town12_Route22152_Weather25.tar.gz\": {\n        \"sha256\": \"a5b86e1ecf615c0ec1648675c4364c499147407f55000ae8330efe84bed31110\",\n        \"size\": 277815069\n    },\n    \"StaticCutIn_Town12_Route22153_Weather0.tar.gz\": {\n        \"sha256\": \"d0b4e6b6803aa8dbd7aa0c8b0c6f6625896a7a4892621b4b8f2db2887f2b885c\",\n        \"size\": 168437315\n    },\n    \"StaticCutIn_Town12_Route22154_Weather1.tar.gz\": {\n        \"sha256\": \"eaa5f353ee2701d9bfcd7d138a8ec5c519bdb89d040224832362188d1c6ed4be\",\n        \"size\": 467969387\n    },\n    \"StaticCutIn_Town12_Route22155_Weather2.tar.gz\": {\n        \"sha256\": \"2ad6608c1e9122aadcd9e1f4c342783642c02b01b0009953a30c2bbf67940ed0\",\n        \"size\": 253618487\n    },\n    \"StaticCutIn_Town12_Route22156_Weather3.tar.gz\": {\n        \"sha256\": \"8450dfd221b04bfc4a9b975928837555c1dd585be5a4c5229a175f0bbee77ba2\",\n        \"size\": 253841813\n    },\n    \"StaticCutIn_Town12_Route22157_Weather3.tar.gz\": {\n        \"sha256\": \"639f32ca05ba74ac1fd2e6a6e800372a9812f7789f8b899664a274505f3a34be\",\n        \"size\": 199071329\n    },\n    \"StaticCutIn_Town12_Route22158_Weather5.tar.gz\": {\n        \"sha256\": \"12e69f0e1d3fc6a00d1e85875db8b3a794e80b8ce5dbbba5d4ea2c52bc83aa14\",\n        \"size\": 261387173\n    },\n    \"StaticCutIn_Town12_Route22159_Weather6.tar.gz\": {\n        \"sha256\": \"110682c96fd5a28bb8a9214c7e31423e5b9827d5ec92d48f2b5eb22d0fcce5b5\",\n        \"size\": 455329711\n    },\n    \"StaticCutIn_Town12_Route22160_Weather7.tar.gz\": {\n        \"sha256\": \"2b6f3c210a27e5844dced68dc2608a946f2c0c0a6ff2dac6f116760983cc490b\",\n        \"size\": 428616852\n    },\n    \"StaticCutIn_Town12_Route22161_Weather8.tar.gz\": {\n        \"sha256\": \"3b1aa52efdcfd118873942d28c698b731c88661301af6083fe028a4b8a12e1bc\",\n        \"size\": 408750827\n    },\n    \"StaticCutIn_Town12_Route22162_Weather9.tar.gz\": {\n        \"sha256\": \"18ada1e069b2d456e8d663ad9c15415b394f53de197c35e3c24d11d7d65488f0\",\n        \"size\": 361173468\n    },\n    \"StaticCutIn_Town12_Route22163_Weather10.tar.gz\": {\n        \"sha256\": \"b9383021daa18d87314a9279bd0c3f36fd0944e311dddfa4dedfdb178a904a75\",\n        \"size\": 399206092\n    },\n    \"StaticCutIn_Town12_Route22164_Weather11.tar.gz\": {\n        \"sha256\": \"90e78e802ffc751b618c5947b888de243b5aa30f49a72119a063426a90441636\",\n        \"size\": 373375915\n    },\n    \"StaticCutIn_Town12_Route22165_Weather12.tar.gz\": {\n        \"sha256\": \"e1c68cdc0155ff95c744476e30b720c2246813779ab1608e42408e4a2662b7ac\",\n        \"size\": 378409413\n    },\n    \"StaticCutIn_Town12_Route22166_Weather13.tar.gz\": {\n        \"sha256\": \"ad97c786f240e7afcc9abfbd45aed64d00c9ade84ce320f7409ab4d28d82a0d7\",\n        \"size\": 386261838\n    },\n    \"StaticCutIn_Town12_Route22168_Weather15.tar.gz\": {\n        \"sha256\": \"a13a32ad62931e86fbae5221082afbe25342cf7cf796cd102ccdbbb34d7f76b5\",\n        \"size\": 423558119\n    },\n    \"StaticCutIn_Town12_Route22169_Weather8.tar.gz\": {\n        \"sha256\": \"0155a1cf3779870ebef8a78783cdb583a2434e47753e344f9c36bfd96459953b\",\n        \"size\": 450020202\n    },\n    \"StaticCutIn_Town12_Route22170_Weather9.tar.gz\": {\n        \"sha256\": \"277d72810d3c8b6da69ab82ce35f3b1654bc24430fcc18c36a7da264d0078dab\",\n        \"size\": 126797457\n    },\n    \"StaticCutIn_Town12_Route22171_Weather18.tar.gz\": {\n        \"sha256\": \"07ab49445627555c2f5cf329c7c298b6f42e87b0f5d0e66438b09f5d31ae80c3\",\n        \"size\": 357247213\n    },\n    \"StaticCutIn_Town12_Route22172_Weather19.tar.gz\": {\n        \"sha256\": \"8a8c1cab1b4540b1d78c41422047a7788cbc007f3eba6339e35366dabd88a5d6\",\n        \"size\": 336348131\n    },\n    \"StaticCutIn_Town12_Route22173_Weather20.tar.gz\": {\n        \"sha256\": \"b29cfe2c3aff13c14d00f7b3b146b64c20a1c099eabbf997c0b48e571756aec1\",\n        \"size\": 154921046\n    },\n    \"StaticCutIn_Town12_Route22174_Weather21.tar.gz\": {\n        \"sha256\": \"de23bd2899abd996b842ff2509f2e9fcfc7ab798786832dae915b5b53c79692a\",\n        \"size\": 393130953\n    },\n    \"StaticCutIn_Town12_Route22175_Weather22.tar.gz\": {\n        \"sha256\": \"932ad105841c34b268f869c306a3d3dcb5c994a8fde3a2a2e9e5707f6761a65e\",\n        \"size\": 402857689\n    },\n    \"StaticCutIn_Town12_Route22176_Weather23.tar.gz\": {\n        \"sha256\": \"4dd58ce4b01876f61ee6744078b927e824d9d8142d02f04b0b0c158c54c3c49e\",\n        \"size\": 145189671\n    },\n    \"StaticCutIn_Town12_Route22177_Weather23.tar.gz\": {\n        \"sha256\": \"5aeddd3f5e9bd561b3c3d6dbc2e14fc6c36f46f9c3ad4a817f73484ddfeac2fb\",\n        \"size\": 145436116\n    },\n    \"StaticCutIn_Town12_Route22178_Weather25.tar.gz\": {\n        \"sha256\": \"3a12b650d8317c14d2e3614745ffecf6acc6552eb76c3d3807c25cd46a2736e9\",\n        \"size\": 428547431\n    },\n    \"StaticCutIn_Town12_Route22179_Weather0.tar.gz\": {\n        \"sha256\": \"571c1875d6b668f58262dbf5e4c9ec14acb5ad051ed91b8992fcd18dc5e0c944\",\n        \"size\": 731030775\n    },\n    \"StaticCutIn_Town12_Route22180_Weather1.tar.gz\": {\n        \"sha256\": \"798414b3688fc36dcb0f1c3c001b7dce539ec04d13a48452830fcf39f5e7553c\",\n        \"size\": 179720658\n    },\n    \"StaticCutIn_Town12_Route22181_Weather2.tar.gz\": {\n        \"sha256\": \"423b346d711ef6312f1c2270764e84791e1005d9135cd29416671b71ca215430\",\n        \"size\": 512208691\n    },\n    \"StaticCutIn_Town12_Route22182_Weather3.tar.gz\": {\n        \"sha256\": \"586773cd4d584643fe95a73ee30035115adfb8ba3562380e2635cc3f7c1cc184\",\n        \"size\": 406005669\n    },\n    \"StaticCutIn_Town12_Route22183_Weather3.tar.gz\": {\n        \"sha256\": \"3e3a49b9ae5f33dfc4abedf93d57d5863d7b4ba0902529f844f362a4345a0a3e\",\n        \"size\": 379534858\n    },\n    \"StaticCutIn_Town12_Route22184_Weather5.tar.gz\": {\n        \"sha256\": \"f6489cee7a5b72303cb5bc3c6573d45c028059651d2822341d11501d108e3f41\",\n        \"size\": 373672368\n    },\n    \"StaticCutIn_Town12_Route22185_Weather6.tar.gz\": {\n        \"sha256\": \"2c7060b8edd49fc47242152145f54a1769b31e106f65f4ef83bb5754f63f2024\",\n        \"size\": 344063736\n    },\n    \"StaticCutIn_Town12_Route22186_Weather7.tar.gz\": {\n        \"sha256\": \"dace29c4a1e019f329b7bbc7ca1fd0529ea818d428ee972ee95fd23fe0586681\",\n        \"size\": 372675272\n    },\n    \"StaticCutIn_Town12_Route22187_Weather8.tar.gz\": {\n        \"sha256\": \"f6c61a354acadb1dd18c19145581dff4f41d4688ab9fd604277af1135ec7ed81\",\n        \"size\": 321138506\n    },\n    \"StaticCutIn_Town12_Route22188_Weather9.tar.gz\": {\n        \"sha256\": \"7cd02ebaf0f81d148dbac2b08260a13b78e415c7c8dac7acd88b6e983ebac9df\",\n        \"size\": 302862561\n    },\n    \"StaticCutIn_Town12_Route22189_Weather10.tar.gz\": {\n        \"sha256\": \"196c390fdef2ccb805b6323dc08ed2d6343a1a41bb7bb5ccf698cd030aecc435\",\n        \"size\": 303753874\n    },\n    \"StaticCutIn_Town12_Route22190_Weather11.tar.gz\": {\n        \"sha256\": \"6cbafd6dc58711dd41eb5e25dfcc77cb3f94b53852785ab2c235057ab5d71884\",\n        \"size\": 290571278\n    },\n    \"StaticCutIn_Town12_Route22191_Weather12.tar.gz\": {\n        \"sha256\": \"b2c22fdee9d61d6e3db9e13de3defa3380b453480c17858c5bd4fb695a39336d\",\n        \"size\": 275490683\n    },\n    \"StaticCutIn_Town12_Route22192_Weather13.tar.gz\": {\n        \"sha256\": \"4402a5014846ef76359cc70402946d9c78e29f747a9a3f192e80f15abbe6511f\",\n        \"size\": 335511341\n    },\n    \"StaticCutIn_Town12_Route22193_Weather14.tar.gz\": {\n        \"sha256\": \"c2c5cec65a733862a3cdea8c8a89801bbee740d5373d84b9475aa5a1c28a0594\",\n        \"size\": 326360096\n    },\n    \"StaticCutIn_Town12_Route22194_Weather15.tar.gz\": {\n        \"sha256\": \"8dbd6093d20e357554fe1c5a158e9ec6070e598aee3d3eae493da519b5af46b9\",\n        \"size\": 507774377\n    },\n    \"StaticCutIn_Town12_Route22195_Weather8.tar.gz\": {\n        \"sha256\": \"9b5d59cde3419fe2eb9816664a79665cfd509fa672786e9bbf0ae38e22aeaf62\",\n        \"size\": 162184470\n    },\n    \"StaticCutIn_Town12_Route22196_Weather9.tar.gz\": {\n        \"sha256\": \"11c66945de4220473f95b62c746c69ae7d4a07788fa8299a44398e900ffdf80b\",\n        \"size\": 403781071\n    },\n    \"StaticCutIn_Town12_Route22197_Weather18.tar.gz\": {\n        \"sha256\": \"d8b3faabe28d989eccda38d1e6991c1da16064ec6822fe8fdb0255be604ce0d0\",\n        \"size\": 505217194\n    },\n    \"StaticCutIn_Town12_Route22198_Weather19.tar.gz\": {\n        \"sha256\": \"8625095c35d510e7564e741869cbefd4731b49c6ad18bc6ffe9ed0692ed80a1a\",\n        \"size\": 398561386\n    },\n    \"StaticCutIn_Town12_Route22199_Weather20.tar.gz\": {\n        \"sha256\": \"a62fb82c3a26d8713b230875beba14dae255e1842b3c83c250c800d1001f1b1d\",\n        \"size\": 358197104\n    },\n    \"StaticCutIn_Town12_Route22200_Weather21.tar.gz\": {\n        \"sha256\": \"58f8fd12659ce91c83887b3db22b47e47d4c9816174d5866aa6d2b3e55fa04d9\",\n        \"size\": 379471173\n    },\n    \"StaticCutIn_Town12_Route22201_Weather22.tar.gz\": {\n        \"sha256\": \"04bd00d00d710d3a7f16ce04d87a149fa433f3c97dca53764dd44fcafb5e3999\",\n        \"size\": 386834822\n    },\n    \"StaticCutIn_Town12_Route22202_Weather23.tar.gz\": {\n        \"sha256\": \"8a834632092c4379431f04ecfdf9263ef858d2fd01465e7a9629c9ced1f1d01b\",\n        \"size\": 381675939\n    },\n    \"StaticCutIn_Town12_Route22203_Weather23.tar.gz\": {\n        \"sha256\": \"8fc024951c3ce038aedc8960918d2427483f10284e4013f2435d7b5ccd7bf2c7\",\n        \"size\": 360892049\n    },\n    \"StaticCutIn_Town12_Route22204_Weather25.tar.gz\": {\n        \"sha256\": \"0a84bfce52a9eaf575ff5ccb21ceca3aa9252f9cc2beca7ceaa97f30ad78d813\",\n        \"size\": 372729383\n    },\n    \"StaticCutIn_Town12_Route22205_Weather0.tar.gz\": {\n        \"sha256\": \"e99004a8b4f39f663f9b820ac0266980dc226d0721e3fbbe52e7f0e3d62eb495\",\n        \"size\": 389062645\n    },\n    \"StaticCutIn_Town12_Route22206_Weather1.tar.gz\": {\n        \"sha256\": \"f37c405f3409643e27cb1ce9b9eceb4aef330549c6580af494003c89bc5cc3c2\",\n        \"size\": 278897716\n    },\n    \"StaticCutIn_Town12_Route22207_Weather2.tar.gz\": {\n        \"sha256\": \"fd62b3ff7eb61f189af5e5f7ce7aa747828c14f0438c760ba003a6b6fd85093c\",\n        \"size\": 379858844\n    },\n    \"StaticCutIn_Town12_Route22208_Weather3.tar.gz\": {\n        \"sha256\": \"cab7116b7672e32376ee821f0d84724f9193cdd40359d1f80be5b045fe31975a\",\n        \"size\": 537032680\n    },\n    \"StaticCutIn_Town12_Route22209_Weather3.tar.gz\": {\n        \"sha256\": \"70a0aefef8cf868042c85f464993b198282b4a96c6912928799c2968fce82065\",\n        \"size\": 772350536\n    },\n    \"StaticCutIn_Town12_Route22210_Weather5.tar.gz\": {\n        \"sha256\": \"0be0581e4edec21280125bc0a39c53377fdc63f904c3d2ad3a6b2766d9cec423\",\n        \"size\": 423261906\n    },\n    \"StaticCutIn_Town12_Route22211_Weather6.tar.gz\": {\n        \"sha256\": \"e5cb300bd7ace0b79b153b23a821b9996f011c9e08b5c1f5bc9f83c19d5d8945\",\n        \"size\": 391026763\n    },\n    \"StaticCutIn_Town12_Route22212_Weather7.tar.gz\": {\n        \"sha256\": \"fb866d119f64ab2a919203be8023d1b11ee6ec7040e4feb127d21a2b79735a7b\",\n        \"size\": 465309944\n    },\n    \"StaticCutIn_Town12_Route22213_Weather8.tar.gz\": {\n        \"sha256\": \"d035a0e895391f301821367114d00297aacb70ad1f3a52b3e7e7f212f7b6d8a2\",\n        \"size\": 377559670\n    },\n    \"StaticCutIn_Town12_Route22214_Weather9.tar.gz\": {\n        \"sha256\": \"2a84355950005ace889d18639f59173ed4bd2b4c2af747e84bdfadb86024b79a\",\n        \"size\": 388023328\n    },\n    \"StaticCutIn_Town12_Route22215_Weather10.tar.gz\": {\n        \"sha256\": \"8efad33e630b9b69d78e9e6310b5d88371d16c83c8e5e2ece1dd0135d7dd6a25\",\n        \"size\": 436350379\n    },\n    \"StaticCutIn_Town12_Route22216_Weather11.tar.gz\": {\n        \"sha256\": \"680e9592a0459ea370d8c1f7b0469f20655696d6005bb980280d06e2527c3023\",\n        \"size\": 372781781\n    },\n    \"StaticCutIn_Town12_Route22217_Weather12.tar.gz\": {\n        \"sha256\": \"f5e79ec5297c05511c5b231abb3e76636ba45694bd62b5e4892bca0a7656ba23\",\n        \"size\": 410524425\n    },\n    \"StaticCutIn_Town12_Route22218_Weather13.tar.gz\": {\n        \"sha256\": \"e957e5663687dbf8ee580f708890d282c82a40e8119d2a0f963f4d3dc803edd8\",\n        \"size\": 344536707\n    },\n    \"StaticCutIn_Town12_Route22219_Weather14.tar.gz\": {\n        \"sha256\": \"df200fe8f7a6be1257def9456bd260bb9c390d6791e9c13370be32ccf58f31bc\",\n        \"size\": 374659369\n    },\n    \"StaticCutIn_Town12_Route22220_Weather15.tar.gz\": {\n        \"sha256\": \"08bff32ce948bb73724a4a90c6af28426c8ad69dcb2b40346f0ffe60a7a9d6ba\",\n        \"size\": 384207277\n    },\n    \"StaticCutIn_Town12_Route22221_Weather8.tar.gz\": {\n        \"sha256\": \"6f374a1de2c41a167be72ebfddd011625b3050538cf43c904c669f9e56e1ce11\",\n        \"size\": 451971749\n    },\n    \"StaticCutIn_Town12_Route22222_Weather9.tar.gz\": {\n        \"sha256\": \"5e17b29717fe267ce753b390acfded07eab5028f5d78b7dc46cf068df341a0ca\",\n        \"size\": 132154489\n    },\n    \"StaticCutIn_Town12_Route22223_Weather18.tar.gz\": {\n        \"sha256\": \"6dfcdb6e91412b5bb6e7f8411a5e1f4814e1863bce2097795c407cfe29dcf422\",\n        \"size\": 175041709\n    },\n    \"StaticCutIn_Town12_Route22224_Weather19.tar.gz\": {\n        \"sha256\": \"54b42bceca8f7b1f98c5ecaf5b57860b46327cfd609ab1789ddcec6e65a6b31a\",\n        \"size\": 238213763\n    },\n    \"StaticCutIn_Town12_Route22225_Weather20.tar.gz\": {\n        \"sha256\": \"1ad8b0a949fb1eecd075f2c7ada2aab3b3bd843e08f1985ae19c708cd69462b2\",\n        \"size\": 593492916\n    },\n    \"StaticCutIn_Town12_Route22226_Weather21.tar.gz\": {\n        \"sha256\": \"df36626bcf1674cc0b8a447742437415b700d85b0984a744a478980c3119b8b4\",\n        \"size\": 155976123\n    },\n    \"StaticCutIn_Town12_Route22227_Weather22.tar.gz\": {\n        \"sha256\": \"bb1a33942d02534ecb7f14a9902785092191eb557aed6079dbceda97c9681124\",\n        \"size\": 149618618\n    },\n    \"StaticCutIn_Town12_Route22228_Weather23.tar.gz\": {\n        \"sha256\": \"9160e44f8a0449120ad5c54e3a7faa7a187831c4d7b7339b9c17f3bb7d3185d9\",\n        \"size\": 436982565\n    },\n    \"StaticCutIn_Town12_Route22229_Weather23.tar.gz\": {\n        \"sha256\": \"cec00ce1f5dcb4c369395ee726214a3a95d6751e3da84975d59fdb7992727128\",\n        \"size\": 134600168\n    },\n    \"StaticCutIn_Town12_Route22230_Weather25.tar.gz\": {\n        \"sha256\": \"51f1234124d4c8ebb81a0af48017bf9d314ab8cded42cfcaa21de77c7870bd69\",\n        \"size\": 244987784\n    },\n    \"StaticCutIn_Town12_Route22231_Weather0.tar.gz\": {\n        \"sha256\": \"e8f9424e0174179ae72394f467b8c65d5fbff5e94406006ec7dc9d9ffb782a41\",\n        \"size\": 386060383\n    },\n    \"StaticCutIn_Town12_Route22232_Weather1.tar.gz\": {\n        \"sha256\": \"ddee35c295b16ffedab739e3fa5452dfd6634eac81f8f86a2bd73d2d43ec4f3d\",\n        \"size\": 334079993\n    },\n    \"StaticCutIn_Town12_Route22233_Weather2.tar.gz\": {\n        \"sha256\": \"fe5dcab8e400e495834bdaca77ee939bc6d84a89d13c480cde3c2adfd0b19927\",\n        \"size\": 311613872\n    },\n    \"StaticCutIn_Town12_Route22234_Weather3.tar.gz\": {\n        \"sha256\": \"d21ea8b2b48ef2a449f44b5c6ddad4366b607b1228a261eda633da1a52dba10d\",\n        \"size\": 321101325\n    },\n    \"StaticCutIn_Town12_Route22235_Weather3.tar.gz\": {\n        \"sha256\": \"c2a5bb19a810d1c7ed20ae2eddf0fb22e0a55e5f2a7db6aff51be4b1bad8de95\",\n        \"size\": 311998921\n    },\n    \"StaticCutIn_Town12_Route22236_Weather5.tar.gz\": {\n        \"sha256\": \"d2112a6252e88f1831d58772319267fddbaef9644032422ecce43cdb1dbf8bfd\",\n        \"size\": 372630738\n    },\n    \"StaticCutIn_Town12_Route22237_Weather6.tar.gz\": {\n        \"sha256\": \"f591fafc2fb7279b5c25051d608636ffb68af2bbbe39082d0fc0fca3a27dd814\",\n        \"size\": 405642325\n    },\n    \"StaticCutIn_Town12_Route22238_Weather7.tar.gz\": {\n        \"sha256\": \"08523bb0dcced71ff1cc2bd8852232868ea5cacda322810f6c11215ce4ea25e4\",\n        \"size\": 343632321\n    },\n    \"StaticCutIn_Town12_Route22239_Weather8.tar.gz\": {\n        \"sha256\": \"d502e082dcff9b66f6235d81b7f9441a9e39fff2ef82782270055ae5f29d9592\",\n        \"size\": 329869466\n    },\n    \"StaticCutIn_Town12_Route22240_Weather9.tar.gz\": {\n        \"sha256\": \"63d87f0ff854de36f79c31732ed089e9e870fbaca6c1fdcdcb05c258bc707478\",\n        \"size\": 346594126\n    },\n    \"StaticCutIn_Town12_Route22241_Weather10.tar.gz\": {\n        \"sha256\": \"7d29ac89588e4a76cc97442ee5d94215f77dc7615c67bc8b2fafab182c71d3a3\",\n        \"size\": 325448738\n    },\n    \"StaticCutIn_Town12_Route22242_Weather11.tar.gz\": {\n        \"sha256\": \"313df406cff5319c2f40e85da17488cf0b8fc08557d8ce895f27b76ae60b7979\",\n        \"size\": 724183359\n    },\n    \"StaticCutIn_Town12_Route22243_Weather12.tar.gz\": {\n        \"sha256\": \"d0891164f5894c8cf192c0931b495626e36794a1fda0bd3105ecbc91b43174a8\",\n        \"size\": 286490459\n    },\n    \"StaticCutIn_Town12_Route22244_Weather13.tar.gz\": {\n        \"sha256\": \"370332000350d57eef9e41f351ad6c119a22fee22ec7e2b8d2ced21e1f525397\",\n        \"size\": 306167315\n    },\n    \"StaticCutIn_Town12_Route22245_Weather14.tar.gz\": {\n        \"sha256\": \"c288c72be92533fa853414e842676bd953e8b3881d9627a6a0cb76b928f9a1e2\",\n        \"size\": 270345932\n    },\n    \"StaticCutIn_Town12_Route22246_Weather15.tar.gz\": {\n        \"sha256\": \"003390861c33d7381352aee96c1378b52ac64399a7aa6be0f8f02d769023a606\",\n        \"size\": 146319447\n    },\n    \"StaticCutIn_Town12_Route22247_Weather8.tar.gz\": {\n        \"sha256\": \"ffbf47e265220d5e68846bf6852a02d0c70f32cc7eac6b742dc7ece1ad924b0e\",\n        \"size\": 170928738\n    },\n    \"StaticCutIn_Town12_Route22248_Weather9.tar.gz\": {\n        \"sha256\": \"c5bf0dd6e608f03e36e72721a0cc931864880cd2b25c6a9d6f8ae446de1aad72\",\n        \"size\": 132578253\n    },\n    \"StaticCutIn_Town12_Route22249_Weather18.tar.gz\": {\n        \"sha256\": \"c0138f2bcbc1f9d6855a4861f72a44222469f7fb3eebe5a8d07af4c6af3e373d\",\n        \"size\": 336128107\n    },\n    \"StaticCutIn_Town12_Route22250_Weather19.tar.gz\": {\n        \"sha256\": \"f612c46aae90e40743b9df2fc19336e871b8f59a996e63c09955eacad4a40462\",\n        \"size\": 388432871\n    },\n    \"StaticCutIn_Town12_Route22251_Weather20.tar.gz\": {\n        \"sha256\": \"b1319c25d9c5738f4bbcf06b354d588ab166efd7d8ecb5d1efa956c7149eee98\",\n        \"size\": 348814500\n    },\n    \"StaticCutIn_Town12_Route22252_Weather21.tar.gz\": {\n        \"sha256\": \"1c9fc7ba50c2d02ab94e40cc26d1d77481466e853b794a5ddc9ab1e86ea23cc5\",\n        \"size\": 404733042\n    },\n    \"StaticCutIn_Town12_Route22253_Weather22.tar.gz\": {\n        \"sha256\": \"73f171fc32caa8d0a4f2182ee37943e057a8530bf90bcf56705f52d6370d668c\",\n        \"size\": 154245551\n    },\n    \"StaticCutIn_Town12_Route22254_Weather23.tar.gz\": {\n        \"sha256\": \"1f33dcf18617dc5e9822af82d4885ed5232ea13320147947ff6a8243f612aed8\",\n        \"size\": 326044813\n    },\n    \"StaticCutIn_Town12_Route22255_Weather23.tar.gz\": {\n        \"sha256\": \"1342e1e7a5f9e7b31c8d582f16423cf5e72386a817e585e27d6ebd6ac7fae546\",\n        \"size\": 203174262\n    },\n    \"StaticCutIn_Town12_Route22256_Weather25.tar.gz\": {\n        \"sha256\": \"6345c75cf7aad736a8b9c7213cc9da671cb2ed7bee50201ed81be40833f9cb56\",\n        \"size\": 372434521\n    },\n    \"StaticCutIn_Town12_Route22258_Weather1.tar.gz\": {\n        \"sha256\": \"c079625ac96881b39998e2acf98336ddd7e75c990119fbad8dd47e2459b5eebf\",\n        \"size\": 340721894\n    },\n    \"StaticCutIn_Town12_Route22259_Weather2.tar.gz\": {\n        \"sha256\": \"1f4afb419c1230d271b90e03a381c7358c70afb5fe878e2ae704fbe5ff29a242\",\n        \"size\": 338418700\n    },\n    \"StaticCutIn_Town12_Route22260_Weather3.tar.gz\": {\n        \"sha256\": \"f08d4711ad7ae5c66d6240eea925169238efb6d3e6712c4c6d3cf5f627f55fe9\",\n        \"size\": 332232605\n    },\n    \"StaticCutIn_Town12_Route22261_Weather3.tar.gz\": {\n        \"sha256\": \"163b4097ba006fa975bd856dfcadb3db1fefee1eea9eed689e0537478ee86598\",\n        \"size\": 339682901\n    },\n    \"StaticCutIn_Town12_Route22263_Weather6.tar.gz\": {\n        \"sha256\": \"e273346286e98e9e957ac67fd6580834884dd2ebbe425c5986ccb02de00e7130\",\n        \"size\": 336307618\n    },\n    \"StaticCutIn_Town12_Route22264_Weather7.tar.gz\": {\n        \"sha256\": \"32f1cbd7740a6b60352d73f1bb32793df76b52884576b424666dbfe433d945be\",\n        \"size\": 394385638\n    },\n    \"StaticCutIn_Town12_Route22265_Weather8.tar.gz\": {\n        \"sha256\": \"854b7a5ad2dd6edbdf04f601ed6b99902b782478a57b417a80203f7937cc2c31\",\n        \"size\": 804852510\n    },\n    \"StaticCutIn_Town12_Route22266_Weather9.tar.gz\": {\n        \"sha256\": \"461a1ee4444bc530a644ed16f42dc5838bf1a84d0ae16d6a9bc04c910378527b\",\n        \"size\": 266224085\n    },\n    \"StaticCutIn_Town12_Route22267_Weather10.tar.gz\": {\n        \"sha256\": \"bc2527cf0b8212d53980abd6a59fb02d2013787d1ac2c951781321b9987d27d2\",\n        \"size\": 232384207\n    },\n    \"StaticCutIn_Town12_Route22268_Weather11.tar.gz\": {\n        \"sha256\": \"f1d077cd7b225edcba2150eeaf1dee3c0200a8272bbfa850b78f1153774ff952\",\n        \"size\": 390400607\n    },\n    \"StaticCutIn_Town12_Route22269_Weather12.tar.gz\": {\n        \"sha256\": \"154cc9e70a111166ded7ff2ca1f8a951118d19199434686a79b3115ab6feb549\",\n        \"size\": 322624957\n    },\n    \"StaticCutIn_Town12_Route22270_Weather13.tar.gz\": {\n        \"sha256\": \"13ebe1e08c65cf49b6f6085adb622146481b914d51c4f73cb16be2580c68e3de\",\n        \"size\": 138035304\n    },\n    \"StaticCutIn_Town12_Route22271_Weather14.tar.gz\": {\n        \"sha256\": \"e6b82c570a6711464eb21da1b6c0020e23f6444b2cc6c50d61ecf6e16d6761f2\",\n        \"size\": 283410960\n    },\n    \"StaticCutIn_Town12_Route22272_Weather15.tar.gz\": {\n        \"sha256\": \"7a1515af63344f22111ca776aad753a3216081f50570c3c39f15026001976a08\",\n        \"size\": 302601062\n    },\n    \"StaticCutIn_Town12_Route22273_Weather8.tar.gz\": {\n        \"sha256\": \"a8792cdaa3b403e1c1fde3859e660b4656a2484b8d99950ded65e01ab54f8992\",\n        \"size\": 277173931\n    },\n    \"StaticCutIn_Town12_Route22274_Weather9.tar.gz\": {\n        \"sha256\": \"4d08b1ba914df179756bd142ea3ba86043b0efa6eeab779736552f687bff739b\",\n        \"size\": 311339053\n    },\n    \"StaticCutIn_Town12_Route22275_Weather18.tar.gz\": {\n        \"sha256\": \"ff3c67c031d6206008ad364382e972c79a697ac1b6ab3200e793a6c2a423781c\",\n        \"size\": 175020011\n    },\n    \"StaticCutIn_Town12_Route22276_Weather19.tar.gz\": {\n        \"sha256\": \"f792db2c8ac3a6ccda92f33a0985cf6f78f3753c718177413c6f6e8f2f3028d6\",\n        \"size\": 271149405\n    },\n    \"StaticCutIn_Town12_Route22277_Weather20.tar.gz\": {\n        \"sha256\": \"553f162c780848f44147c9c23104bbf96cf7a0349d96c2fdd5e22d517cd77390\",\n        \"size\": 729237980\n    },\n    \"StaticCutIn_Town12_Route22278_Weather21.tar.gz\": {\n        \"sha256\": \"c6030d0489676be861b72b0cb232728a262556e3011223833d73bc1b6635bcc2\",\n        \"size\": 402294204\n    },\n    \"StaticCutIn_Town12_Route22279_Weather22.tar.gz\": {\n        \"sha256\": \"9296fcfff16272e2f810be6a89589dbcc288b7ca7266398ef6eca390bc527eec\",\n        \"size\": 150391780\n    },\n    \"StaticCutIn_Town12_Route22280_Weather23.tar.gz\": {\n        \"sha256\": \"d957c59813b4953cbfabdb7640f791f03775db2da8e74e5e7ddff8840bbee2c1\",\n        \"size\": 273891959\n    },\n    \"StaticCutIn_Town12_Route22281_Weather23.tar.gz\": {\n        \"sha256\": \"38f73aedf71b9f254461623a687498432c8e84642633f4a6afcc28c249b02b30\",\n        \"size\": 136808777\n    },\n    \"StaticCutIn_Town12_Route22282_Weather25.tar.gz\": {\n        \"sha256\": \"dbab2c1643c7156cd122b7f0f674ec689f51da65e77a45dbb8bc85a19c8fd871\",\n        \"size\": 353778609\n    },\n    \"StaticCutIn_Town12_Route22283_Weather0.tar.gz\": {\n        \"sha256\": \"df034e86397aec91ff42e14c0ce404c92bd3d450449ae38b8f5a9b14134e9c5b\",\n        \"size\": 430922298\n    },\n    \"StaticCutIn_Town12_Route22284_Weather1.tar.gz\": {\n        \"sha256\": \"16d8ccab88522504866781ce8006b4a806b6e96c004c3ed3213795a7b36ed4db\",\n        \"size\": 162244749\n    },\n    \"StaticCutIn_Town12_Route22285_Weather2.tar.gz\": {\n        \"sha256\": \"16e599930911ed0b38183672b188f39f159ded812b9de526a80386abd074be5e\",\n        \"size\": 267527458\n    },\n    \"StaticCutIn_Town12_Route22286_Weather3.tar.gz\": {\n        \"sha256\": \"c72c674b33dd1e485ca995bf2a9177f69f1a64fadfae464e3fb1b4f7e64248c1\",\n        \"size\": 183185094\n    },\n    \"StaticCutIn_Town12_Route22287_Weather3.tar.gz\": {\n        \"sha256\": \"9a7a6cdb3fc0ea849d067df336a3ebcd78298735f429217ba8f06bf636f9532b\",\n        \"size\": 253027951\n    },\n    \"StaticCutIn_Town12_Route22288_Weather5.tar.gz\": {\n        \"sha256\": \"3cf4d81c894de9fd2e18402f00da9234f61a7a8cebd9cb18b4f88d38ac1a0b99\",\n        \"size\": 472884701\n    },\n    \"StaticCutIn_Town12_Route22289_Weather6.tar.gz\": {\n        \"sha256\": \"6dc055671644fdf0c68057952563698c987c2978a5d3ef592160f0b04a95a69c\",\n        \"size\": 177726506\n    },\n    \"StaticCutIn_Town12_Route22291_Weather8.tar.gz\": {\n        \"sha256\": \"1660865105f936a65499b965b0187359c633bd5862c5f95812ac743b036292c3\",\n        \"size\": 176678470\n    },\n    \"StaticCutIn_Town12_Route22292_Weather9.tar.gz\": {\n        \"sha256\": \"9ad526a38f3b2ddc6ea4b6cd445e48dd045074e48d2c6022def42d77805ce9fe\",\n        \"size\": 137123235\n    },\n    \"StaticCutIn_Town12_Route22293_Weather10.tar.gz\": {\n        \"sha256\": \"12658eddfca121257bb53fedba1821497f44bf84cc08a941d43a05c355e72fce\",\n        \"size\": 280205406\n    },\n    \"StaticCutIn_Town12_Route22294_Weather11.tar.gz\": {\n        \"sha256\": \"ccfbae75e25ebebbdc6852af042e0d5b1faedae497da0c99f80b78efd222f48b\",\n        \"size\": 303800999\n    },\n    \"StaticCutIn_Town12_Route22295_Weather12.tar.gz\": {\n        \"sha256\": \"c7b1ccc0bedda1a3c6ddcd8a7c8c84bba7a33dabb5a7500e0f035fd3e22fb802\",\n        \"size\": 128625702\n    },\n    \"StaticCutIn_Town12_Route22296_Weather13.tar.gz\": {\n        \"sha256\": \"59ce57029c31d32d4da1db718e4173268c3a904351a45d5d67ba37a1e949abec\",\n        \"size\": 135660009\n    },\n    \"StaticCutIn_Town12_Route22297_Weather14.tar.gz\": {\n        \"sha256\": \"365ef4469752fbdfd4f8d78abaddbbcd9293ccc5a2c480548e0ba8c1a377ee19\",\n        \"size\": 284361375\n    },\n    \"StaticCutIn_Town12_Route22298_Weather15.tar.gz\": {\n        \"sha256\": \"d54acdac46d31deb7d3b35137427bae260c63fe83fa1f3d869bfdbdcffd14b03\",\n        \"size\": 278175649\n    },\n    \"StaticCutIn_Town12_Route22299_Weather8.tar.gz\": {\n        \"sha256\": \"cef61fa0adfb6303b28e0bd0c3ce895fe9bb583afebacb87aaddfce7c5686728\",\n        \"size\": 261193312\n    },\n    \"StaticCutIn_Town12_Route22300_Weather9.tar.gz\": {\n        \"sha256\": \"13ce3ada5463dfdc0f013cb677db48791940af8bf78c3860f9938aa8640dfc01\",\n        \"size\": 309610718\n    },\n    \"StaticCutIn_Town12_Route22301_Weather18.tar.gz\": {\n        \"sha256\": \"953dbf6d897503511378e1823af3e76ba7aab0cbfc45b3bb887ec939a367e7d5\",\n        \"size\": 322449732\n    },\n    \"StaticCutIn_Town12_Route22302_Weather19.tar.gz\": {\n        \"sha256\": \"4b9b96a7550952d86edc96d5e512f52a28500ce5fac045f7f3e30b8991f844af\",\n        \"size\": 293495162\n    },\n    \"StaticCutIn_Town12_Route22303_Weather20.tar.gz\": {\n        \"sha256\": \"f5992cbe5cdf1619261559e6a9e9bdeb5cca94959a8a11bbeb0c0c017435d3bf\",\n        \"size\": 302332783\n    },\n    \"StaticCutIn_Town12_Route22304_Weather21.tar.gz\": {\n        \"sha256\": \"96b502c6f4e3a093c993759a8d81ff7d1c65b629b7da8a918ae487e13b2be842\",\n        \"size\": 311169353\n    },\n    \"StaticCutIn_Town12_Route22305_Weather22.tar.gz\": {\n        \"sha256\": \"51557dd14afe036c3b447e0d81a700b9269fd28864f5a2d506aaac311c9371e2\",\n        \"size\": 285050967\n    },\n    \"StaticCutIn_Town12_Route22306_Weather23.tar.gz\": {\n        \"sha256\": \"5cf7f9e9e4a3ecae42e06db9320d2e72afdbe5c749b212ad19be63a5832accd8\",\n        \"size\": 362972514\n    },\n    \"StaticCutIn_Town12_Route22307_Weather23.tar.gz\": {\n        \"sha256\": \"a70b9c12ffd42a8cb8b29863eead04ff99f21a81866bbce72cd6651b1b806f6a\",\n        \"size\": 314085657\n    },\n    \"StaticCutIn_Town12_Route22308_Weather25.tar.gz\": {\n        \"sha256\": \"1ddf24db9b6827a351c6cc33244f265c17b082273af5e7fb3c1c445c67c666e9\",\n        \"size\": 131745987\n    },\n    \"StaticCutIn_Town12_Route22309_Weather0.tar.gz\": {\n        \"sha256\": \"26b7d0f8706ec434c43ba29be05ed14bf2245f013114f0eedab955ef3bca6962\",\n        \"size\": 171858680\n    },\n    \"StaticCutIn_Town12_Route22312_Weather3.tar.gz\": {\n        \"sha256\": \"36b7e912e38444ac373b1a2d4a106ebe4575a4e68b528722dfc2fb2c66c3816a\",\n        \"size\": 219792133\n    },\n    \"StaticCutIn_Town12_Route22313_Weather3.tar.gz\": {\n        \"sha256\": \"13daee2a956f95ff4913dd88714657ec059e032f10316533051acf1d6f0b70ef\",\n        \"size\": 167586777\n    },\n    \"StaticCutIn_Town12_Route22314_Weather5.tar.gz\": {\n        \"sha256\": \"9c0851a6887af9ed5098768d56af73a390b830753687d58316a72495bc795a79\",\n        \"size\": 175527793\n    },\n    \"StaticCutIn_Town12_Route22315_Weather6.tar.gz\": {\n        \"sha256\": \"0398a9029895184fc77141887855eaf625c7a863cd88a32babfb37e5c32517d9\",\n        \"size\": 422929494\n    },\n    \"StaticCutIn_Town12_Route22316_Weather7.tar.gz\": {\n        \"sha256\": \"874b06e96ae612fcd8298c826a6d6f150fb739c158e358f82dc024252539cd70\",\n        \"size\": 252144122\n    },\n    \"StaticCutIn_Town12_Route22318_Weather9.tar.gz\": {\n        \"sha256\": \"ff74caecae3149e5fe5d7bb8f61910ab02a8139423aeef67d1a55ec7a0f3ea38\",\n        \"size\": 308006688\n    },\n    \"StaticCutIn_Town12_Route22320_Weather11.tar.gz\": {\n        \"sha256\": \"d7336c16a665cdea45a32aff5beb04f846e3ef9bfa7e6b76458c998e8bb3da31\",\n        \"size\": 234427705\n    },\n    \"StaticCutIn_Town12_Route22321_Weather12.tar.gz\": {\n        \"sha256\": \"e0d6ddd4a3ce4dc30605254d511d9fd1b471f96f86b4ebd148e370cde9a68a20\",\n        \"size\": 166187277\n    },\n    \"StaticCutIn_Town12_Route22322_Weather13.tar.gz\": {\n        \"sha256\": \"ea7606eb051b501ae515f702ac9ba5bcc26288d17e6dd26265641e45b695717c\",\n        \"size\": 213734160\n    },\n    \"StaticCutIn_Town12_Route22323_Weather14.tar.gz\": {\n        \"sha256\": \"3e75ae0088c2bf87661be189e096f5ebaf7870a207d3d224548c352f6e1123e1\",\n        \"size\": 152296822\n    },\n    \"StaticCutIn_Town12_Route22324_Weather15.tar.gz\": {\n        \"sha256\": \"440bc636d2371383c2c4b0041f4e505acc0cbb29c36ff5cef7542f230374364d\",\n        \"size\": 229755414\n    },\n    \"StaticCutIn_Town12_Route22325_Weather8.tar.gz\": {\n        \"sha256\": \"255c849a8b347711b5342be5a4116cffdb08780a49bf4949255efddad02fd35b\",\n        \"size\": 163573271\n    },\n    \"StaticCutIn_Town12_Route22326_Weather9.tar.gz\": {\n        \"sha256\": \"7c4386da463749ed5ca6a04fb72ec3e2600455b75c917c7b3f44602d5b2d04fd\",\n        \"size\": 140515953\n    },\n    \"StaticCutIn_Town12_Route22327_Weather18.tar.gz\": {\n        \"sha256\": \"9bb1a84268e513688a9b2462e2fb3354d76c3408cdf3ac1fb2b7dd4876b78f92\",\n        \"size\": 309385222\n    },\n    \"StaticCutIn_Town12_Route22328_Weather19.tar.gz\": {\n        \"sha256\": \"35887b5765ebd57e5a20d44f99d96a065b03ca6e441cb20ded221e58f84d1c84\",\n        \"size\": 340894034\n    },\n    \"StaticCutIn_Town12_Route22329_Weather20.tar.gz\": {\n        \"sha256\": \"f8d86e29bb29c2dca1d25dc9103c158140bf8457c16cbe4ad80f953c159ba080\",\n        \"size\": 380790930\n    },\n    \"StaticCutIn_Town12_Route22330_Weather21.tar.gz\": {\n        \"sha256\": \"f375da7ff11d3749a40d167a3fcb3c7d7db5bf15d263e2ec448439a85e628b1a\",\n        \"size\": 292461207\n    },\n    \"StaticCutIn_Town12_Route22331_Weather22.tar.gz\": {\n        \"sha256\": \"41b83180c96bb2f385229a62229f2b719947fb46cb171a5dd02b29a4aed5e419\",\n        \"size\": 333058871\n    },\n    \"StaticCutIn_Town12_Route22332_Weather23.tar.gz\": {\n        \"sha256\": \"11bbb5a9cd57aedceaffb073a1bf5d38c5ddf269bd34644ce67639ce5e6a3091\",\n        \"size\": 336283054\n    },\n    \"StaticCutIn_Town12_Route22333_Weather23.tar.gz\": {\n        \"sha256\": \"6cfe68c35d48d78b74d085b4f8eba1fea0f293ab8841b811a79e1590e7244ec7\",\n        \"size\": 309974364\n    },\n    \"StaticCutIn_Town12_Route22334_Weather25.tar.gz\": {\n        \"sha256\": \"8d3e42f7def46e749733441dce656b2117611c2d4dddf7cc383ffc7e53e6cc4f\",\n        \"size\": 134813917\n    },\n    \"StaticCutIn_Town12_Route22335_Weather0.tar.gz\": {\n        \"sha256\": \"4da3be5311b010786afe2d24e2af2bea74ea624a2e39df16f828c3026c4d37a5\",\n        \"size\": 370972588\n    },\n    \"StaticCutIn_Town12_Route22336_Weather1.tar.gz\": {\n        \"sha256\": \"6acfba642b9c6ee6062c043eb060f3cf8d7297fa1c78a6742154f10445573c60\",\n        \"size\": 374462847\n    },\n    \"StaticCutIn_Town12_Route22337_Weather2.tar.gz\": {\n        \"sha256\": \"4843625f97c335030270167c1f9ea3e96a38d6cf21e11b82d18c4883dccd9119\",\n        \"size\": 187260513\n    },\n    \"StaticCutIn_Town12_Route22338_Weather3.tar.gz\": {\n        \"sha256\": \"92fe5eddb6d277a4bd67b44acc0b0d77f652ca43d3092043c381865ed6928edd\",\n        \"size\": 171917090\n    },\n    \"StaticCutIn_Town12_Route22340_Weather5.tar.gz\": {\n        \"sha256\": \"7133b032d55b6735ab2eedc1270fe65a127e1e921d1373a83e6296e7f2d8b9ca\",\n        \"size\": 172537989\n    },\n    \"StaticCutIn_Town12_Route22341_Weather6.tar.gz\": {\n        \"sha256\": \"00793c67a0147c836cea6b58076594301d7a2c962ddce79d46b6515c57fed324\",\n        \"size\": 337599236\n    },\n    \"StaticCutIn_Town12_Route22342_Weather7.tar.gz\": {\n        \"sha256\": \"7d64d70e286ad4fa0a7f23ea203d09709b9a51d2a4cf41114c57d78415432cfa\",\n        \"size\": 353084620\n    },\n    \"StaticCutIn_Town12_Route22343_Weather8.tar.gz\": {\n        \"sha256\": \"7c22385f0f75c5f595e7ee283bc3b07de2b3af40aadbd884e5f331fee2e8136c\",\n        \"size\": 311590371\n    },\n    \"StaticCutIn_Town12_Route22344_Weather9.tar.gz\": {\n        \"sha256\": \"ee2eb9c7b495fc23dab8e93516f8131700c60e59cc4445ff39757c0546bedbe1\",\n        \"size\": 280003795\n    },\n    \"StaticCutIn_Town12_Route22345_Weather10.tar.gz\": {\n        \"sha256\": \"1ab02df8a96597070223fedace6acf149c607b797f5a5f2d82c7dd0965786464\",\n        \"size\": 302311892\n    },\n    \"StaticCutIn_Town12_Route22346_Weather11.tar.gz\": {\n        \"sha256\": \"4c74a224a0de3b297d1cf8db0eb4db745f13c63287c5de33f26651d7ead93be7\",\n        \"size\": 274658540\n    },\n    \"StaticCutIn_Town12_Route22348_Weather13.tar.gz\": {\n        \"sha256\": \"f7f94b083130e259dec36b27e7d8156ef49a8876ff69882f077f66ab724d4ad7\",\n        \"size\": 131371887\n    },\n    \"StaticCutIn_Town12_Route22349_Weather14.tar.gz\": {\n        \"sha256\": \"dd6f86e9d3be11754d7f3cc92ccc8661846ba59ea82a3b2c4fcab7352d7be517\",\n        \"size\": 409273415\n    },\n    \"StaticCutIn_Town12_Route22352_Weather9.tar.gz\": {\n        \"sha256\": \"d2bfdad17ebbdd6ca3b72ada4bb780bc7135b175dc2aaeafbc2f971c4837ded5\",\n        \"size\": 188645511\n    },\n    \"StaticCutIn_Town12_Route22353_Weather18.tar.gz\": {\n        \"sha256\": \"4b8c286a8ee97e86d0e62419349fd08166c5502b3c075b4ec02032128a033e1a\",\n        \"size\": 403342639\n    },\n    \"StaticCutIn_Town12_Route22354_Weather19.tar.gz\": {\n        \"sha256\": \"85ace9df2f1b1d69e856e0044a4d7732536beb10541a082917af873d61c57c4f\",\n        \"size\": 343016571\n    },\n    \"StaticCutIn_Town12_Route22355_Weather20.tar.gz\": {\n        \"sha256\": \"867e77b4935eaf631e3e46860144e56dd35d46f25a07ebc95bbfbae21ca8edfe\",\n        \"size\": 339146651\n    },\n    \"StaticCutIn_Town12_Route22356_Weather21.tar.gz\": {\n        \"sha256\": \"cf1829ba6ca6cf449e5a614de8547b0c16a2cc7c5487a4aaffd77b8858c611df\",\n        \"size\": 345351955\n    },\n    \"StaticCutIn_Town12_Route22357_Weather22.tar.gz\": {\n        \"sha256\": \"e74e992a1740f7e72bcec569a578db168068a0642fb4e238bb74eb10b66bddba\",\n        \"size\": 344508181\n    },\n    \"StaticCutIn_Town12_Route22358_Weather23.tar.gz\": {\n        \"sha256\": \"0f783a61d698f413efbd04c9750311440e63fce6d90cdc73ca0e336e41844b27\",\n        \"size\": 378123267\n    },\n    \"StaticCutIn_Town12_Route22359_Weather23.tar.gz\": {\n        \"sha256\": \"29b4df2bf50b9401dcd30f98eb734528b95190c0edb73290fffd305fd27e8ad2\",\n        \"size\": 413040856\n    },\n    \"StaticCutIn_Town12_Route22360_Weather25.tar.gz\": {\n        \"sha256\": \"20fe56b1eb96d8ff2142576dd69eced7b68de8052a58c8c47082dc2a7ff0e2eb\",\n        \"size\": 140913705\n    },\n    \"StaticCutIn_Town12_Route22361_Weather0.tar.gz\": {\n        \"sha256\": \"0f362434e5af8f468819fe70df0f137c07bb0e8fcac3b147e403118fec8fd0c5\",\n        \"size\": 304669139\n    },\n    \"StaticCutIn_Town12_Route22362_Weather1.tar.gz\": {\n        \"sha256\": \"b84ef1ba7881ba15833efd0dd684c1aa1d7f632262a854e230778495af87cdc9\",\n        \"size\": 465276181\n    },\n    \"StaticCutIn_Town12_Route22363_Weather2.tar.gz\": {\n        \"sha256\": \"94e274dd413e59bde1857f39cb888b3932e6f3a67c86471b7e808376eecf6ab9\",\n        \"size\": 186813406\n    },\n    \"StaticCutIn_Town12_Route22364_Weather3.tar.gz\": {\n        \"sha256\": \"d5a5758e986fdcecb71a89cfb33410ab3eb630a3bfc630858b25db2264ac8a96\",\n        \"size\": 180836576\n    },\n    \"StaticCutIn_Town12_Route22365_Weather3.tar.gz\": {\n        \"sha256\": \"ecad844f2529ea0b42a9a1c5c8cf92dac02b5002f464cbecb28d503c94417a29\",\n        \"size\": 167963000\n    },\n    \"StaticCutIn_Town12_Route22366_Weather5.tar.gz\": {\n        \"sha256\": \"a7ca0d79ed184c79640ccd93f5d4c397166d2283e3ba3e1311f0d9b3ab4a4b55\",\n        \"size\": 428791146\n    },\n    \"StaticCutIn_Town12_Route22367_Weather6.tar.gz\": {\n        \"sha256\": \"d9499654656bfabdde6fb4235f9a9059a56b0d3771e1ecf840577d04ab39084a\",\n        \"size\": 364776913\n    },\n    \"StaticCutIn_Town12_Route22368_Weather7.tar.gz\": {\n        \"sha256\": \"32aed4af21e5d52778c13736534067edb9d587090faa1fce5e65b742176458cf\",\n        \"size\": 391024331\n    },\n    \"StaticCutIn_Town12_Route22369_Weather8.tar.gz\": {\n        \"sha256\": \"5740faab889d799334910b7e60d673d007fbf28869b48544022a708faa80a3ac\",\n        \"size\": 287022366\n    },\n    \"StaticCutIn_Town12_Route22370_Weather9.tar.gz\": {\n        \"sha256\": \"a3e52edb79216aeccc7b9843afc229640df126579b263d5a560c56ea89eb0a94\",\n        \"size\": 295077991\n    },\n    \"StaticCutIn_Town12_Route22371_Weather10.tar.gz\": {\n        \"sha256\": \"765786d6d944a7f5c8be14aa9e65cdf42d9f4fb6e97236ca3020dd61cad3eed9\",\n        \"size\": 303217438\n    },\n    \"StaticCutIn_Town12_Route22372_Weather11.tar.gz\": {\n        \"sha256\": \"a200cf57a553533eb5d988423792020a5286bfd675c90b682c9ea93b67df8932\",\n        \"size\": 154351676\n    },\n    \"StaticCutIn_Town12_Route22373_Weather12.tar.gz\": {\n        \"sha256\": \"70678d936fde2b30667905da7ec4ed3d04868720cca5fa9764684b0fc2f9d9b4\",\n        \"size\": 388488890\n    },\n    \"StaticCutIn_Town12_Route22374_Weather13.tar.gz\": {\n        \"sha256\": \"78d47ac22f85a6c6638f102b72428bd9aaf36c45f5ec8383de1a63a081dca084\",\n        \"size\": 162616523\n    },\n    \"StaticCutIn_Town12_Route22375_Weather14.tar.gz\": {\n        \"sha256\": \"d9337f27452970f62ba70d702fa0b794dfe2ec4647847b8e44fd53f14e14c36f\",\n        \"size\": 144378398\n    },\n    \"StaticCutIn_Town12_Route22376_Weather15.tar.gz\": {\n        \"sha256\": \"1982c171e94745f6ebb4524467d6c836d306d99789f13c536d7d061cd1707880\",\n        \"size\": 149650724\n    },\n    \"StaticCutIn_Town12_Route22377_Weather8.tar.gz\": {\n        \"sha256\": \"c8aebdef410cbe440af1bbd5bc7dffa4875503d88a35f107bb5ed16a644d81e5\",\n        \"size\": 447348852\n    },\n    \"StaticCutIn_Town12_Route22378_Weather9.tar.gz\": {\n        \"sha256\": \"55e015b00562d97635a7604c6140a12d9ce75961378b69f99ad6cfc6fb6ef57d\",\n        \"size\": 459676860\n    },\n    \"StaticCutIn_Town12_Route22379_Weather18.tar.gz\": {\n        \"sha256\": \"c2772e6371e5ee8fd4594b74456a514eb00ee4ab22305ac4b3a67da481279b82\",\n        \"size\": 523571199\n    },\n    \"StaticCutIn_Town12_Route22380_Weather19.tar.gz\": {\n        \"sha256\": \"715967cf251c14c8223abf71474af0b0c43e7055ad2bc2a02ba32b52a160c7b9\",\n        \"size\": 510893243\n    },\n    \"StaticCutIn_Town12_Route22382_Weather21.tar.gz\": {\n        \"sha256\": \"61e6c88d67fee2e96b1bfbfbb714373f2888e548e1dbc73614c5303ee2fb94b5\",\n        \"size\": 159849553\n    },\n    \"StaticCutIn_Town12_Route22383_Weather22.tar.gz\": {\n        \"sha256\": \"f69d68dec462fc00ad1c8bda7fcde8fde291153f03a5b55aa8627b61c7ea485f\",\n        \"size\": 250351244\n    },\n    \"StaticCutIn_Town12_Route22384_Weather23.tar.gz\": {\n        \"sha256\": \"b61c672634582b573b4fc85447417fa13c5fd0ad20e9019a0710d9f6dfea032a\",\n        \"size\": 159424442\n    },\n    \"StaticCutIn_Town12_Route22387_Weather0.tar.gz\": {\n        \"sha256\": \"ffabe27dc47cd73961d5dc99fd3c9040e1b26d5043730068a929b935491dcdee\",\n        \"size\": 413002891\n    },\n    \"StaticCutIn_Town12_Route22388_Weather1.tar.gz\": {\n        \"sha256\": \"298c0da94e6bc294f4e7f454c06f07537ecd813ce38401280d514a8b89a923be\",\n        \"size\": 190028864\n    },\n    \"StaticCutIn_Town12_Route22389_Weather2.tar.gz\": {\n        \"sha256\": \"fd8dff0a19304d276b90e6885642669ba2dd33a4b490e7561c7d3a776b80bb13\",\n        \"size\": 298017049\n    },\n    \"StaticCutIn_Town12_Route22390_Weather3.tar.gz\": {\n        \"sha256\": \"06c460cd6d3ce2673448952eba28e054508537c427c1838984ec1266e0015620\",\n        \"size\": 512051968\n    },\n    \"StaticCutIn_Town12_Route22391_Weather3.tar.gz\": {\n        \"sha256\": \"767c9a4431473e517dfb50031a14095dd7225dc1fd0597ae0722384fc25331d5\",\n        \"size\": 353764064\n    },\n    \"StaticCutIn_Town12_Route22392_Weather5.tar.gz\": {\n        \"sha256\": \"d0cd080039e6ac9c4fdb6ffe1335a0baee557fc040a996acfeaac29a500cb160\",\n        \"size\": 340038350\n    },\n    \"StaticCutIn_Town12_Route22393_Weather6.tar.gz\": {\n        \"sha256\": \"9bbf9ea6ef4810524631da7bfaebe9b67593801e674b367b4814f8cc37fceb8e\",\n        \"size\": 320675042\n    },\n    \"StaticCutIn_Town12_Route22395_Weather8.tar.gz\": {\n        \"sha256\": \"38ec645fa39b1c8023efbcdc26ee29eaddef7a74965e176f39c5734dc9588fc9\",\n        \"size\": 328640207\n    },\n    \"StaticCutIn_Town12_Route22396_Weather9.tar.gz\": {\n        \"sha256\": \"d05cfa8ca7f6ee42d772681da10f8325db8ccfae8c96a94483924726fa989298\",\n        \"size\": 298046573\n    },\n    \"StaticCutIn_Town12_Route22397_Weather10.tar.gz\": {\n        \"sha256\": \"b82fc91a4e5db68b15f1c23651be38421e464f1cd00a69b34bd7be85e2cf3d2e\",\n        \"size\": 310200375\n    },\n    \"StaticCutIn_Town12_Route22398_Weather11.tar.gz\": {\n        \"sha256\": \"d77732ea5855e1a5e32be4a1651b20b1c2e9d6bcd2b4f0ff5e5c9af320717dba\",\n        \"size\": 286034871\n    },\n    \"StaticCutIn_Town12_Route22399_Weather12.tar.gz\": {\n        \"sha256\": \"13cbec5d5e5206236cce030f428e5dcf6684b844dbcfbec718a82d3d63d2ce5a\",\n        \"size\": 226682137\n    },\n    \"StaticCutIn_Town12_Route22400_Weather13.tar.gz\": {\n        \"sha256\": \"f692f2f982827802d9f658260efe7aba132a2e73cd7a91b319e0222f3efd4a91\",\n        \"size\": 131577652\n    },\n    \"StaticCutIn_Town12_Route22401_Weather14.tar.gz\": {\n        \"sha256\": \"0cfcb2694c3f1020bf6dbdf1a55b996aac2cca01b0372b016e54c16195f3116d\",\n        \"size\": 143024357\n    },\n    \"StaticCutIn_Town12_Route22402_Weather15.tar.gz\": {\n        \"sha256\": \"fee3687d6d9d48387ccfbe9f81b3c5e87a32607d80146bc2c235278cce244972\",\n        \"size\": 163319490\n    },\n    \"StaticCutIn_Town12_Route22403_Weather8.tar.gz\": {\n        \"sha256\": \"a19a0d92c6ffecf4cda52520976be403c9a2f7c66ca368fe0923cf571521e232\",\n        \"size\": 246947216\n    },\n    \"StaticCutIn_Town12_Route22404_Weather9.tar.gz\": {\n        \"sha256\": \"78bf5695ea19108c4d0f8a2e0aaf0f8dc381bb6b13fcf393be80f2348006e895\",\n        \"size\": 390508503\n    },\n    \"StaticCutIn_Town12_Route22406_Weather19.tar.gz\": {\n        \"sha256\": \"0990f09e3b003376136065cb9ca8e87937c9dd2f1722efd8f8a972fb2f9d5394\",\n        \"size\": 417901848\n    },\n    \"StaticCutIn_Town12_Route22407_Weather20.tar.gz\": {\n        \"sha256\": \"80de8356387e66c3f6de0f10a763fe32e12abcaab01500605fd409ffa63bbaf1\",\n        \"size\": 418685260\n    },\n    \"StaticCutIn_Town12_Route22408_Weather21.tar.gz\": {\n        \"sha256\": \"a7fef9d5df9947dcb2f2addb53843285a054456883c8591be64249570ea9c7cd\",\n        \"size\": 403179952\n    },\n    \"StaticCutIn_Town12_Route22409_Weather22.tar.gz\": {\n        \"sha256\": \"943cc63a5ced6c1702c9c5d602ebb3eb349b1e02e3b4ee3716990a87c224c018\",\n        \"size\": 394073751\n    },\n    \"StaticCutIn_Town12_Route22410_Weather23.tar.gz\": {\n        \"sha256\": \"b3dac7686068d2bc685a3f343570fe71faa3c0c625126c12f72ecdc522f90ffd\",\n        \"size\": 392867970\n    },\n    \"StaticCutIn_Town12_Route22411_Weather23.tar.gz\": {\n        \"sha256\": \"c27cf5aadf81349507f6a634453c1454b1cd882cb0428413a5085f0dba2d49da\",\n        \"size\": 382864538\n    },\n    \"StaticCutIn_Town12_Route22412_Weather25.tar.gz\": {\n        \"sha256\": \"1aa34a4e42c1e2fa76c2257f1f081dd160c484dde3004f4e4de76a525b7d083b\",\n        \"size\": 304370052\n    },\n    \"StaticCutIn_Town12_Route22414_Weather1.tar.gz\": {\n        \"sha256\": \"7da7d5b795af0b549fd75c28579fd198150faccf55df97d6fa1d02e6a0454d37\",\n        \"size\": 306996894\n    },\n    \"StaticCutIn_Town12_Route22415_Weather2.tar.gz\": {\n        \"sha256\": \"54f25fe5548fc961ada04f4807f8ec79f580aa44b52b7a5ec2cc7c2f5943c1b4\",\n        \"size\": 371579983\n    },\n    \"StaticCutIn_Town12_Route22416_Weather3.tar.gz\": {\n        \"sha256\": \"8ff8eb8ed01cc8afa09ecb2a9c7b57b8238b85ebfdb61c8399a7e15edafb59ec\",\n        \"size\": 172087116\n    },\n    \"StaticCutIn_Town12_Route22417_Weather3.tar.gz\": {\n        \"sha256\": \"1fb2a2ea68573627f03dadbe93b558af390265c45ac30742e52dd8665f35e78e\",\n        \"size\": 278423310\n    },\n    \"StaticCutIn_Town12_Route22418_Weather5.tar.gz\": {\n        \"sha256\": \"e084656832dbeacb38ae6b0816e154f6e6e2da757299503baf8233b64715a38c\",\n        \"size\": 369152781\n    },\n    \"StaticCutIn_Town12_Route22420_Weather7.tar.gz\": {\n        \"sha256\": \"4e14c0753617da7e6784b425e89966949714dc2fa00db77ad13917ff6121ef45\",\n        \"size\": 372660316\n    },\n    \"StaticCutIn_Town12_Route22421_Weather8.tar.gz\": {\n        \"sha256\": \"bade3ceea1b1cc0256b353184bb5d9121bdf0c5536f3d05bd8793730cd7c1518\",\n        \"size\": 308973011\n    },\n    \"StaticCutIn_Town12_Route22422_Weather9.tar.gz\": {\n        \"sha256\": \"c37364b8876c51b6bd38b4b32662829d469a2724ae3f5369d861a389e1f8f739\",\n        \"size\": 287073576\n    },\n    \"StaticCutIn_Town12_Route22423_Weather10.tar.gz\": {\n        \"sha256\": \"9d354f7ff450a3b9442e5b431455c78f103d2cddef58bb03c3eef73be007e72a\",\n        \"size\": 304466973\n    },\n    \"StaticCutIn_Town12_Route22426_Weather13.tar.gz\": {\n        \"sha256\": \"2ebf2feb8317bd6c26c0973f3ad5c011fed97282f8ee0c7400330cfd17d3cb36\",\n        \"size\": 267236323\n    },\n    \"StaticCutIn_Town12_Route22427_Weather14.tar.gz\": {\n        \"sha256\": \"b7a0e14af969504b91af90a8755b26b9c431ee49a0afaab27c66fed8de61bd02\",\n        \"size\": 275922135\n    },\n    \"StaticCutIn_Town12_Route22428_Weather15.tar.gz\": {\n        \"sha256\": \"ee0303ef4379ba43993ede8a66b3d31a9ef06aadcdf9a92cfe30c33f0ed05162\",\n        \"size\": 421908368\n    },\n    \"StaticCutIn_Town12_Route22429_Weather8.tar.gz\": {\n        \"sha256\": \"3eee7b0bd542f35c745a52501c156a54e062025dd85fde075696c5ae8e3e6d51\",\n        \"size\": 411996930\n    },\n    \"StaticCutIn_Town12_Route22430_Weather9.tar.gz\": {\n        \"sha256\": \"2ad8817a055f61bd58e7cd586351fec5070d00359c304d23831c2dc301eeeaea\",\n        \"size\": 132160339\n    },\n    \"StaticCutIn_Town12_Route22431_Weather18.tar.gz\": {\n        \"sha256\": \"7ced5ed541db17677f5430f12bb438d47a29e2db50ec40fad845098f8c6cf091\",\n        \"size\": 470416903\n    },\n    \"StaticCutIn_Town12_Route22432_Weather19.tar.gz\": {\n        \"sha256\": \"233f42bdd19fc398acd1f3a5a1d419a21544c8f4eeeb1b416bfb60945d3a215c\",\n        \"size\": 376546916\n    },\n    \"StaticCutIn_Town12_Route22433_Weather20.tar.gz\": {\n        \"sha256\": \"758afe99a83c0686ac0184b624d3fca6c44f0e035485570c6a0c9e48b5eb92ff\",\n        \"size\": 289782175\n    },\n    \"StaticCutIn_Town12_Route22434_Weather21.tar.gz\": {\n        \"sha256\": \"cd7feb905a9375ac67c433fdabb4124c0ad597d3c3578fc1aa73825e4453467c\",\n        \"size\": 301615899\n    },\n    \"StaticCutIn_Town12_Route22435_Weather22.tar.gz\": {\n        \"sha256\": \"dec381aec01a0b753f14e5e19a98d57cfaa17c0545908fb3a90f50727e373542\",\n        \"size\": 284796684\n    },\n    \"StaticCutIn_Town12_Route22436_Weather23.tar.gz\": {\n        \"sha256\": \"dd5d6c459a74a0d335db7d3c03de75a589e2e4d882b6f36bbbabab94eebb6405\",\n        \"size\": 341958863\n    },\n    \"StaticCutIn_Town12_Route22437_Weather23.tar.gz\": {\n        \"sha256\": \"4e125b610e4a9c3094d48f2997aadeb7dae32114b1fcfa8a70b69185deaeccdd\",\n        \"size\": 237558438\n    },\n    \"StaticCutIn_Town12_Route22438_Weather25.tar.gz\": {\n        \"sha256\": \"01c1c9fd354c551a4d7246a35651ec3aded095eea6ee550b741d0ed2a1f9b1de\",\n        \"size\": 372229460\n    },\n    \"StaticCutIn_Town12_Route22439_Weather0.tar.gz\": {\n        \"sha256\": \"1a560ce69efce691cb51ff565d7f4875ef3fb6196daab08720ece21b234f7b70\",\n        \"size\": 442380723\n    },\n    \"StaticCutIn_Town12_Route22440_Weather1.tar.gz\": {\n        \"sha256\": \"646b41b76b84c99797a979f1cbe2e3d0aa3d145aa5fbc2ceec77e24fdec9a873\",\n        \"size\": 440437578\n    },\n    \"StaticCutIn_Town12_Route22441_Weather2.tar.gz\": {\n        \"sha256\": \"b0fc848fa06b05fff515a94d0da99708de861cb1bfd083bfe443e92b438c8edd\",\n        \"size\": 436737658\n    },\n    \"StaticCutIn_Town12_Route22442_Weather3.tar.gz\": {\n        \"sha256\": \"10342b7a5eaf0c0bd654049cc5ff05ce46e068b75e2d63e31666173ed5212fb1\",\n        \"size\": 447080827\n    },\n    \"StaticCutIn_Town12_Route22443_Weather3.tar.gz\": {\n        \"sha256\": \"a9f36382872e5a81ec0ee41671f073524f5b8455d5a90aafa87dbc14607c10a6\",\n        \"size\": 392855933\n    },\n    \"StaticCutIn_Town12_Route22444_Weather5.tar.gz\": {\n        \"sha256\": \"7b0c577f1f279c8c3aa03fc641453306292f599cd3740d0b81ae83106f02daf6\",\n        \"size\": 174585602\n    },\n    \"StaticCutIn_Town12_Route22445_Weather6.tar.gz\": {\n        \"sha256\": \"013fe223656261287903368179af3a41a8cd55517e549b07db81f2f1920b717c\",\n        \"size\": 336818603\n    },\n    \"StaticCutIn_Town12_Route22446_Weather7.tar.gz\": {\n        \"sha256\": \"093c7bff7bed91adf28ee5db15679ff491147a5e8b343634ca2a682f078e61ee\",\n        \"size\": 292751561\n    },\n    \"StaticCutIn_Town12_Route22447_Weather8.tar.gz\": {\n        \"sha256\": \"9723386cb68fae9975e7b9d0650b911a1c8349efe209f7aebc2b16b7db9a56e5\",\n        \"size\": 337105532\n    },\n    \"StaticCutIn_Town12_Route22448_Weather9.tar.gz\": {\n        \"sha256\": \"23e70a3cb708693c5ecf71ac8b655ca85730e371c07255a409b5a9b02c081fc1\",\n        \"size\": 142004050\n    },\n    \"StaticCutIn_Town12_Route22449_Weather10.tar.gz\": {\n        \"sha256\": \"e735aa7760f771fb16ca32fe4218cd2607a8133ae2137b966f1de4869abd4316\",\n        \"size\": 169388072\n    },\n    \"StaticCutIn_Town12_Route22450_Weather11.tar.gz\": {\n        \"sha256\": \"a605569b8681a743bbd7bfde278a2d1fe43e8ef88993dcfbbc93e721fa9d3074\",\n        \"size\": 315373831\n    },\n    \"StaticCutIn_Town12_Route22452_Weather13.tar.gz\": {\n        \"sha256\": \"f0eb54e353f3e58bb89516dc595eca59057e6eacfbeb3d4cf8d906e9f0156537\",\n        \"size\": 131381811\n    },\n    \"StaticCutIn_Town12_Route22453_Weather14.tar.gz\": {\n        \"sha256\": \"8664f613355995aa2292fce90d802281cb89a1dac4a807228a3dbc397f8db9d0\",\n        \"size\": 305241630\n    },\n    \"StaticCutIn_Town12_Route22454_Weather15.tar.gz\": {\n        \"sha256\": \"b16586478882cdfb3c6d1ea90030b80426e369449757fc1a085d55efb9c91321\",\n        \"size\": 499487408\n    },\n    \"StaticCutIn_Town12_Route22455_Weather8.tar.gz\": {\n        \"sha256\": \"1bde10b8904f58c861f70fa1711f99b48489af7289058d2de03b48684bcc6371\",\n        \"size\": 382707022\n    },\n    \"StaticCutIn_Town12_Route22456_Weather9.tar.gz\": {\n        \"sha256\": \"3f40534d2430a9c4f3b062695ea9c9affbecbda984ed811859f0329620938820\",\n        \"size\": 377451006\n    },\n    \"StaticCutIn_Town12_Route22457_Weather18.tar.gz\": {\n        \"sha256\": \"30795c32bb288096046c59b2579943090a7c022b2846714e08656a900f32881f\",\n        \"size\": 747068348\n    },\n    \"StaticCutIn_Town12_Route22458_Weather19.tar.gz\": {\n        \"sha256\": \"91de09b0495802215c414dafed627f56d4ca47875db32d9dce385e3c7b462580\",\n        \"size\": 785206223\n    },\n    \"StaticCutIn_Town12_Route22459_Weather20.tar.gz\": {\n        \"sha256\": \"296b710e807308fdbbb48aca0c11e367a23378f8fd0eecf5c76998d1e428aa00\",\n        \"size\": 630950193\n    },\n    \"StaticCutIn_Town12_Route22460_Weather21.tar.gz\": {\n        \"sha256\": \"e47eaa5f1bbf0babe522356e74554ca8e62efcb05672b6501a4460da825beffe\",\n        \"size\": 148915746\n    },\n    \"StaticCutIn_Town12_Route22461_Weather22.tar.gz\": {\n        \"sha256\": \"474b99c606b613dd3dc5743d8f617c872ef431d8ff73fe9ad9ec067381fcf1b4\",\n        \"size\": 170620101\n    },\n    \"StaticCutIn_Town12_Route22464_Weather25.tar.gz\": {\n        \"sha256\": \"85ef43e31e3b6f5e08d82bb8ae49cd95e8395fb67b19ae24211e47cdcf61bcf5\",\n        \"size\": 122024904\n    },\n    \"StaticCutIn_Town12_Route22465_Weather0.tar.gz\": {\n        \"sha256\": \"4c509f6821bb3d7e8f4362b8b2f7f128f7f75509baaa938daa9c0b4ada783cdf\",\n        \"size\": 179118489\n    },\n    \"StaticCutIn_Town12_Route22467_Weather2.tar.gz\": {\n        \"sha256\": \"deb787278be453bcc054d8d148cd8ba20260af98938142e1282eaa2e36652c50\",\n        \"size\": 352889992\n    },\n    \"StaticCutIn_Town12_Route22468_Weather3.tar.gz\": {\n        \"sha256\": \"1cfa8f6a1346c9496952616506cf30e68b749edc7e7a25b4d153c0ebd6f55aad\",\n        \"size\": 346032775\n    },\n    \"StaticCutIn_Town12_Route22469_Weather3.tar.gz\": {\n        \"sha256\": \"ced061b4799c232f7796d85350bb7e593141cdf2569876861bc2588aaf012374\",\n        \"size\": 354516648\n    },\n    \"StaticCutIn_Town12_Route22470_Weather5.tar.gz\": {\n        \"sha256\": \"65af6915bdd21d49b9605ab8609a05b20a34fc558d0224d7fe1d2ed207284db0\",\n        \"size\": 330493748\n    },\n    \"StaticCutIn_Town12_Route22471_Weather6.tar.gz\": {\n        \"sha256\": \"bbd14739f5e3ea7b925c28c1dc01f9cd0470477c18e0e29be7f02ed02f1f5e90\",\n        \"size\": 320177768\n    },\n    \"StaticCutIn_Town12_Route22472_Weather7.tar.gz\": {\n        \"sha256\": \"50fbb4682ac5e3de323859c37d827a66137ae3c5585e3e3666f8ba79a7432a32\",\n        \"size\": 333826160\n    },\n    \"StaticCutIn_Town12_Route22473_Weather8.tar.gz\": {\n        \"sha256\": \"c9f1e3962198a13e4d2cd7664b832c4c4b1d19a95e9ff34695ee7d519ed187fb\",\n        \"size\": 359985793\n    },\n    \"StaticCutIn_Town12_Route22474_Weather9.tar.gz\": {\n        \"sha256\": \"a55f7bfa07f3a840f0440521c151c1d26470af5e91dd01da3217e10f8243e04c\",\n        \"size\": 138966746\n    },\n    \"StaticCutIn_Town12_Route22475_Weather10.tar.gz\": {\n        \"sha256\": \"66a76aca3d0d35151e34e8d4a3d62ffc5d815ad098632cfe31ce7568ce84908e\",\n        \"size\": 264291530\n    },\n    \"StaticCutIn_Town12_Route22476_Weather11.tar.gz\": {\n        \"sha256\": \"6e3630b7aafcf9027a9c66e074d70f764f9d9ebecd320ef5263e3a1226fb2063\",\n        \"size\": 211942800\n    },\n    \"StaticCutIn_Town12_Route22477_Weather12.tar.gz\": {\n        \"sha256\": \"945a657faf16922635eccfbb5de2916a8fa272b3be822793c82677f2e6fbd572\",\n        \"size\": 130856284\n    },\n    \"StaticCutIn_Town12_Route22478_Weather13.tar.gz\": {\n        \"sha256\": \"32ca767fc056ba3d9efd0959d8f4c694c03228d5d07360b98e002eea909cee76\",\n        \"size\": 137758058\n    },\n    \"StaticCutIn_Town12_Route22479_Weather14.tar.gz\": {\n        \"sha256\": \"2df93f2d214ec5773ac53cd6dedbd2777dc793c04f2e6e2186b622a07356e178\",\n        \"size\": 212526492\n    },\n    \"StaticCutIn_Town12_Route22480_Weather15.tar.gz\": {\n        \"sha256\": \"9f00006b88bb545ad964e271fe3747ab55d7d394b105becc4e1003c0299b52cc\",\n        \"size\": 309682173\n    },\n    \"StaticCutIn_Town12_Route22481_Weather8.tar.gz\": {\n        \"sha256\": \"5d36d28a07dae28167b4069b5a40a21bffa806618214a7ffe5f39a88fff58f18\",\n        \"size\": 245822555\n    },\n    \"StaticCutIn_Town12_Route22482_Weather9.tar.gz\": {\n        \"sha256\": \"c9edc4c6ed6be3ff870e5f4bddd195ae92a7416e0cafee40d3ef7868f48c74e5\",\n        \"size\": 438653752\n    },\n    \"StaticCutIn_Town12_Route22483_Weather18.tar.gz\": {\n        \"sha256\": \"47f5c31c1931dfce639b2c3c70c17b0a184ad7e0d4effb4e1acf30feed4e82e3\",\n        \"size\": 450809044\n    },\n    \"StaticCutIn_Town12_Route22484_Weather19.tar.gz\": {\n        \"sha256\": \"a06ea99f413ce9731315e50e42976dc1c24fb9f72b4678a15aefdfb98c986910\",\n        \"size\": 326365782\n    },\n    \"StaticCutIn_Town12_Route22485_Weather20.tar.gz\": {\n        \"sha256\": \"0ea388ccb7ddbfe8960d1c740d867f62c451f9c0a7171ac8ae135a2a99f897d1\",\n        \"size\": 159218665\n    },\n    \"StaticCutIn_Town12_Route22486_Weather21.tar.gz\": {\n        \"sha256\": \"30c336383cf7146b5c37004226735a877945cf926efcdb8252802402d7b28b02\",\n        \"size\": 375569868\n    },\n    \"StaticCutIn_Town12_Route22487_Weather22.tar.gz\": {\n        \"sha256\": \"4c9c3c613e476bdedfd7e7393425d07887b38654869bc1424288ce9c9dda8036\",\n        \"size\": 396465062\n    },\n    \"StaticCutIn_Town12_Route22488_Weather23.tar.gz\": {\n        \"sha256\": \"ac5df835dc99812daf3d3fc5a1a54a0933e183803f04a2376fed67cae8c54cd2\",\n        \"size\": 423538781\n    },\n    \"StaticCutIn_Town12_Route22489_Weather23.tar.gz\": {\n        \"sha256\": \"b160698b454e0721bb078feb61089b59a26827ab3d2720b12f34dd4b5454e6d8\",\n        \"size\": 158782630\n    },\n    \"StaticCutIn_Town12_Route22490_Weather25.tar.gz\": {\n        \"sha256\": \"d660d094f27ea902ad6cdb48892742d04dfddf5b1e6f8798b349d8c86433e067\",\n        \"size\": 200630021\n    },\n    \"StaticCutIn_Town12_Route22491_Weather0.tar.gz\": {\n        \"sha256\": \"71e9c6f13d779c272000ee5a2ea511c0f49759cc4e7a0c2efa7e475bffd7b04d\",\n        \"size\": 170688278\n    },\n    \"StaticCutIn_Town12_Route22492_Weather1.tar.gz\": {\n        \"sha256\": \"8166eede715b30e4445e84400eeb690e17b97a74e18066e0ee55d2129acae9ef\",\n        \"size\": 178320412\n    },\n    \"StaticCutIn_Town12_Route22493_Weather2.tar.gz\": {\n        \"sha256\": \"48033f3c04dbe3992371cd51c4372c5d7fc446c740f9887344067858571d034b\",\n        \"size\": 441272912\n    },\n    \"StaticCutIn_Town12_Route22494_Weather3.tar.gz\": {\n        \"sha256\": \"d575f65a3c2d3cd71547fbadf65fada4d7dbfda43325ca12e979b19fe38ddfbd\",\n        \"size\": 173385387\n    },\n    \"StaticCutIn_Town12_Route22495_Weather3.tar.gz\": {\n        \"sha256\": \"063967335793490fde1a232ccdc624f6bc39aceb80252e1a3016dada503afe81\",\n        \"size\": 349740007\n    },\n    \"StaticCutIn_Town12_Route22496_Weather5.tar.gz\": {\n        \"sha256\": \"0c65f68235b167d607a27c518b9dd93a2ae62a421c9779ffd3593fa995f7a2a7\",\n        \"size\": 182841592\n    },\n    \"StaticCutIn_Town12_Route22497_Weather6.tar.gz\": {\n        \"sha256\": \"d71570cae5be9c02515ef6dbed508ddb0fb11fba90b1d23e649791d101b83232\",\n        \"size\": 347574702\n    },\n    \"StaticCutIn_Town12_Route22498_Weather7.tar.gz\": {\n        \"sha256\": \"18e0f194f6bcbff51c8371e60f336e65c1d2d488ca9d25e6d0fa15e2bd81c88d\",\n        \"size\": 794618882\n    },\n    \"StaticCutIn_Town12_Route22499_Weather8.tar.gz\": {\n        \"sha256\": \"81ae06cac07237d759e59cf0460ff54b04ac8f52c6c95fe3af4f981a6fffc1e9\",\n        \"size\": 397349388\n    },\n    \"StaticCutIn_Town12_Route22500_Weather9.tar.gz\": {\n        \"sha256\": \"cccc8d1a0c0521c8fbe7671efcfe8d218fddba9dbe09a995c661650c107cb434\",\n        \"size\": 120020807\n    },\n    \"StaticCutIn_Town12_Route22501_Weather10.tar.gz\": {\n        \"sha256\": \"b982515a6973e198491f9cddce15fff0f05cd822eff140a43cd7cc5a5ee982cf\",\n        \"size\": 160318043\n    },\n    \"StaticCutIn_Town12_Route22502_Weather11.tar.gz\": {\n        \"sha256\": \"13676f7a1df8f21eac6e94b6c6c8290d2446d6f9756cabeef467d53c63ec6ade\",\n        \"size\": 139202870\n    },\n    \"StaticCutIn_Town12_Route22506_Weather15.tar.gz\": {\n        \"sha256\": \"9fd956300d9d7f79d306ddf54d93d1208c79aa0f4e55876507141088f3951ec3\",\n        \"size\": 164494101\n    },\n    \"StaticCutIn_Town12_Route22507_Weather8.tar.gz\": {\n        \"sha256\": \"fc0137a41577c278a936e894171b4271d77c5fb4afa6127cbc19e54d8eb95f61\",\n        \"size\": 170201100\n    },\n    \"StaticCutIn_Town12_Route22508_Weather9.tar.gz\": {\n        \"sha256\": \"21936ef3bf55d917f11456a33dd73bcdf618f66099e55e1b3019e13e6a08b5ab\",\n        \"size\": 120723242\n    },\n    \"StaticCutIn_Town12_Route22510_Weather19.tar.gz\": {\n        \"sha256\": \"5111342f91068c418722607c8b42983954da609c9d4172654a2df5c139e254ab\",\n        \"size\": 179369924\n    },\n    \"StaticCutIn_Town12_Route22511_Weather20.tar.gz\": {\n        \"sha256\": \"18b9f738e72b15a09cd3af1991a0eef8e83d276b1363ad02510b57cc3fa5fc6f\",\n        \"size\": 312812320\n    },\n    \"StaticCutIn_Town12_Route22512_Weather21.tar.gz\": {\n        \"sha256\": \"2dd9511bf4f3c7608268a43926152a4819031c6fabc478943d4fa570ece962b1\",\n        \"size\": 361902321\n    },\n    \"StaticCutIn_Town12_Route22513_Weather22.tar.gz\": {\n        \"sha256\": \"40aa7d3b19d2c8019e3cd7823995b7f8b22daff789d20a458908778c0f1ddff7\",\n        \"size\": 147285888\n    },\n    \"StaticCutIn_Town12_Route22514_Weather23.tar.gz\": {\n        \"sha256\": \"df37d9481732c351c9bd79923e2fce44459f8d198f677e5da85eed78718d0c1d\",\n        \"size\": 144931882\n    },\n    \"StaticCutIn_Town12_Route22515_Weather23.tar.gz\": {\n        \"sha256\": \"273487059191bd5ca139e9a21ef1cf137749bac489c229c7175a6ee0eb7a6cee\",\n        \"size\": 407793987\n    },\n    \"StaticCutIn_Town12_Route22516_Weather25.tar.gz\": {\n        \"sha256\": \"edf5d44ca45de4fdfc857fb7ba51ac47d97c31d0a3cf79971a03b6f52526cfd3\",\n        \"size\": 382863305\n    },\n    \"StaticCutIn_Town12_Route22517_Weather0.tar.gz\": {\n        \"sha256\": \"a7789745ff51a0f3bf21db6ad0994da6ffd85373323bd6a7c805da21ff9cb87a\",\n        \"size\": 171109425\n    },\n    \"StaticCutIn_Town12_Route22518_Weather1.tar.gz\": {\n        \"sha256\": \"1b2b8a0bbb8e1ae6b8092e722f12c3e4ab14680efea734097f343a85af71d9ef\",\n        \"size\": 333602102\n    },\n    \"StaticCutIn_Town12_Route22519_Weather2.tar.gz\": {\n        \"sha256\": \"50995149853ef7c38385ed76e8f62dae86202931a4f9e8180a3516f0c5c7bc55\",\n        \"size\": 434298262\n    },\n    \"StaticCutIn_Town12_Route22520_Weather3.tar.gz\": {\n        \"sha256\": \"77b9221b95308b74b081184fd595cbf554b51eaa659536639c4848980d452be8\",\n        \"size\": 397470268\n    },\n    \"StaticCutIn_Town12_Route22521_Weather3.tar.gz\": {\n        \"sha256\": \"d6c010bb7fe540377b7546bb78f41756d9a9c2d81393f5c0d8f7a968c66bbc04\",\n        \"size\": 396472472\n    },\n    \"StaticCutIn_Town12_Route22522_Weather5.tar.gz\": {\n        \"sha256\": \"a06259e65645a456590247cbddec52714501d7a68245425a438bde32adb20185\",\n        \"size\": 431555551\n    },\n    \"StaticCutIn_Town12_Route22523_Weather6.tar.gz\": {\n        \"sha256\": \"243663465061843a946640826dab89ffd11e38ccad6e5cd3734a49f4cf04ff87\",\n        \"size\": 391556505\n    },\n    \"StaticCutIn_Town12_Route22524_Weather7.tar.gz\": {\n        \"sha256\": \"20e627eb111e41a2f424a950107d37df5590a359b5b7322c13b9fab66886d49a\",\n        \"size\": 463021563\n    },\n    \"StaticCutIn_Town12_Route22525_Weather8.tar.gz\": {\n        \"sha256\": \"59d14d482c0c2d3522b310e488450ec03e9a9a8513d9fcf8c7fd6ecffead2522\",\n        \"size\": 450221026\n    },\n    \"StaticCutIn_Town12_Route22526_Weather9.tar.gz\": {\n        \"sha256\": \"a8227f41303751a358d173a508cc413d0a2107cfb46ccfbd85f271bd04e1c9ae\",\n        \"size\": 379077474\n    },\n    \"StaticCutIn_Town12_Route22527_Weather10.tar.gz\": {\n        \"sha256\": \"8d7f59b2f6647ad1e3936caee6e750c520655da9b0c54916cd3c024cf1ac2d31\",\n        \"size\": 412629886\n    },\n    \"StaticCutIn_Town12_Route22529_Weather12.tar.gz\": {\n        \"sha256\": \"99c8c1f2afcbc3213362e64b6fa4bf632a989b27c1297305b41ac5f4012011f1\",\n        \"size\": 204018863\n    },\n    \"StaticCutIn_Town12_Route22530_Weather13.tar.gz\": {\n        \"sha256\": \"6ab5a50a205863e3e8cc9ff5b25d336b1370ba4cdc26c13048fc81222f77bff2\",\n        \"size\": 124393646\n    },\n    \"StaticCutIn_Town12_Route22531_Weather14.tar.gz\": {\n        \"sha256\": \"f901007334338bf3157a0b71b9ea543d1ef6c8ecb1efbe61003e6e49525b1885\",\n        \"size\": 167665619\n    },\n    \"StaticCutIn_Town12_Route22532_Weather15.tar.gz\": {\n        \"sha256\": \"9d194094d35eaef9c3c881fea587d26bf9313948060736e274c56557c8253752\",\n        \"size\": 300218778\n    },\n    \"StaticCutIn_Town12_Route22533_Weather8.tar.gz\": {\n        \"sha256\": \"4b61d61e06ec152028449c8774d650eb959e6e2e26e8814fbe7529300be1b869\",\n        \"size\": 284070728\n    },\n    \"StaticCutIn_Town12_Route22534_Weather9.tar.gz\": {\n        \"sha256\": \"59ade2983e19ea677130ab938b9f70b08abc72c05a82a9cc2e8c3a9bbd1ba83f\",\n        \"size\": 283303627\n    },\n    \"StaticCutIn_Town12_Route22535_Weather18.tar.gz\": {\n        \"sha256\": \"d626fa95ab5672d7d8c9335192ad3e2ff6ee66bc4d628a73f299cf13467392ec\",\n        \"size\": 321787499\n    },\n    \"StaticCutIn_Town12_Route22537_Weather20.tar.gz\": {\n        \"sha256\": \"170890d2205885c11cc2836035c01fb20eb262261ac5c44dbf76829ab174f0a5\",\n        \"size\": 319344998\n    },\n    \"StaticCutIn_Town12_Route22538_Weather21.tar.gz\": {\n        \"sha256\": \"dcdc5c514248483825f930e5d7bc6904583292edc5d8d93dd151e0d8e08f8c64\",\n        \"size\": 453917431\n    },\n    \"StaticCutIn_Town12_Route22539_Weather22.tar.gz\": {\n        \"sha256\": \"1b874e3f632ea86131dedc9106db6702b591f4eef5174cf9e5bd4afbc60a8dbf\",\n        \"size\": 383847398\n    },\n    \"StaticCutIn_Town12_Route22540_Weather23.tar.gz\": {\n        \"sha256\": \"8eea65679cb08f5f7e3c50ba5dadaf3e3e19d4aa787e7c140159c7a87c67977a\",\n        \"size\": 404262795\n    },\n    \"StaticCutIn_Town12_Route22541_Weather23.tar.gz\": {\n        \"sha256\": \"274a4c39bc01f6b4c78c7b7f29aee34d0e22bb6218e6cc644b6008b72c748d9d\",\n        \"size\": 595518052\n    },\n    \"StaticCutIn_Town12_Route22542_Weather25.tar.gz\": {\n        \"sha256\": \"f010cbc70f0c8e3c410c4f739cece03da7fdade0ca2ac89422c33590b914ac9e\",\n        \"size\": 409351987\n    },\n    \"StaticCutIn_Town12_Route22543_Weather0.tar.gz\": {\n        \"sha256\": \"7ea7eeb27ba98905ebdb07cf12e255eaf10e600ad8308308d2e98770598660ab\",\n        \"size\": 479212371\n    },\n    \"StaticCutIn_Town12_Route22544_Weather1.tar.gz\": {\n        \"sha256\": \"1613d7bed8004aa4076e0d7b0bb5d700e53450814071c37d63d4a88c61128279\",\n        \"size\": 355464532\n    },\n    \"StaticCutIn_Town12_Route22547_Weather3.tar.gz\": {\n        \"sha256\": \"31ab8692d66110b6db60cfed266e0c8ba190d57aa9e5eee85a6756603bceba55\",\n        \"size\": 172788493\n    },\n    \"StaticCutIn_Town12_Route22548_Weather5.tar.gz\": {\n        \"sha256\": \"74eeb1a7568dd0033633e960ba8cf20cab0f5bfea0096889c933deba15408e1b\",\n        \"size\": 163954603\n    },\n    \"StaticCutIn_Town12_Route22549_Weather6.tar.gz\": {\n        \"sha256\": \"a0593ca100234017050ca2bc610aa8f98d317acf41064931ede34e5907087d4e\",\n        \"size\": 449929524\n    },\n    \"StaticCutIn_Town12_Route22550_Weather7.tar.gz\": {\n        \"sha256\": \"58d69241e8a17590f758c35c7237d9cd511cc5559ca42392d06ea7fbd6e42811\",\n        \"size\": 494803421\n    },\n    \"StaticCutIn_Town12_Route22551_Weather8.tar.gz\": {\n        \"sha256\": \"23f6dbe7be1b961d43c1362173a8b368403d6a21fb9878055f2e5d24afc03f22\",\n        \"size\": 255307285\n    },\n    \"StaticCutIn_Town12_Route22552_Weather9.tar.gz\": {\n        \"sha256\": \"050c27c28f2ad953bb47971b54aca0991bd63917d785f7444573f201fe8ff56e\",\n        \"size\": 176652060\n    },\n    \"StaticCutIn_Town12_Route2704_Weather20.tar.gz\": {\n        \"sha256\": \"9ed52908eacfb8b4c61090ccaefaa782673f050c6c56ab779af8fe9097cab963\",\n        \"size\": 170937682\n    },\n    \"StaticCutIn_Town12_Route2705_Weather21.tar.gz\": {\n        \"sha256\": \"3aca086b072d64d37d8db5717a29d311124dab8e6f777a8f6d47fb272a301eb9\",\n        \"size\": 171781144\n    },\n    \"StaticCutIn_Town12_Route2706_Weather22.tar.gz\": {\n        \"sha256\": \"90273bfb644c2be0a43967431dcfdada24aae7f23be948b4ed0653c95a9d8f91\",\n        \"size\": 412207784\n    },\n    \"StaticCutIn_Town12_Route2709_Weather25.tar.gz\": {\n        \"sha256\": \"ecf9200792dc1e0c54713ad167b0724055471f3255bbb064ced6b50d6887bbe4\",\n        \"size\": 329913826\n    },\n    \"StaticCutIn_Town12_Route2710_Weather0.tar.gz\": {\n        \"sha256\": \"8551ceea229d9938bfa3c876c60e6561bb95cff6ae8a02dcb198f227f63f43d7\",\n        \"size\": 461552281\n    },\n    \"StaticCutIn_Town12_Route2711_Weather1.tar.gz\": {\n        \"sha256\": \"f4165af6422663a3ac5fc4fbfe5760c159097b96f86c421ef26a633d9d477976\",\n        \"size\": 372095352\n    },\n    \"StaticCutIn_Town12_Route2712_Weather2.tar.gz\": {\n        \"sha256\": \"5c02183cd6c838b6382595322d071a2f523240f6de3b2191c9a6520d413f548c\",\n        \"size\": 355973026\n    },\n    \"StaticCutIn_Town12_Route2713_Weather3.tar.gz\": {\n        \"sha256\": \"7d732496d846df07faa1dac37cea6e216c41baeaef86edcf02a0894ca3b6eb56\",\n        \"size\": 364356377\n    },\n    \"StaticCutIn_Town12_Route2714_Weather3.tar.gz\": {\n        \"sha256\": \"25dd199d3213bd275b6696f934e6cfe334c53d40fa28af111a07bbfb75b83572\",\n        \"size\": 511431841\n    },\n    \"StaticCutIn_Town12_Route2715_Weather5.tar.gz\": {\n        \"sha256\": \"19a8cfe5e0266500150933ec61f77c7f4a0b7ecd4bdaadddac1c49fc7ad76b83\",\n        \"size\": 479407620\n    },\n    \"StaticCutIn_Town12_Route2716_Weather6.tar.gz\": {\n        \"sha256\": \"8577da2450482fcbe5d5b724c4bdc54424dad4d247415a24c28524ca1aa02b49\",\n        \"size\": 440780984\n    },\n    \"StaticCutIn_Town12_Route2717_Weather7.tar.gz\": {\n        \"sha256\": \"a479bf55d20155e235c34f5039f9a4baf6c71a54f64a2e3dad0aff183ff1d9fd\",\n        \"size\": 477864120\n    },\n    \"StaticCutIn_Town12_Route2718_Weather8.tar.gz\": {\n        \"sha256\": \"7840966a7ef7b8f497037b256fbdd1c596f4485753e24006ab235eb8c6041c6b\",\n        \"size\": 459092283\n    },\n    \"StaticCutIn_Town12_Route2719_Weather9.tar.gz\": {\n        \"sha256\": \"6a97e24870ae776c6bc155404dd227008c2ed5928203238bf8cf1ae54466e8ec\",\n        \"size\": 400767380\n    },\n    \"StaticCutIn_Town12_Route2720_Weather10.tar.gz\": {\n        \"sha256\": \"45529bffcee42739a77836017d30014fa2126f05f2b48bf6a73d179fb3752e45\",\n        \"size\": 495338645\n    },\n    \"StaticCutIn_Town12_Route2721_Weather11.tar.gz\": {\n        \"sha256\": \"e89c6f5902d32a7cd37666726f8fc5a9d52cf4a08fb0bbac372f8d839d713c65\",\n        \"size\": 228779467\n    },\n    \"StaticCutIn_Town12_Route2722_Weather12.tar.gz\": {\n        \"sha256\": \"ceb069fd5a344f2a7a2319dd794fd6732873d26e24024b15b913e74a0302b104\",\n        \"size\": 270837779\n    },\n    \"StaticCutIn_Town12_Route2723_Weather13.tar.gz\": {\n        \"sha256\": \"6c2159055a51e57cec3e987662f3d746ead408dc6d9f50c0f98d3d2d472cb10c\",\n        \"size\": 312864790\n    },\n    \"StaticCutIn_Town13_Route3483_Weather20.tar.gz\": {\n        \"sha256\": \"8d77430ec8e87b99c1695eea2c41a5f6af5726b84c39396a7ca4f36284b15c62\",\n        \"size\": 516058339\n    },\n    \"StaticCutIn_Town13_Route3484_Weather21.tar.gz\": {\n        \"sha256\": \"5467087552f33e7eb08a83cb8eac021b5eed538f7585c2873eb57359e2db4bc1\",\n        \"size\": 444935137\n    },\n    \"StaticCutIn_Town13_Route3488_Weather25.tar.gz\": {\n        \"sha256\": \"695e28c9b70534e98fe34ec4c726c9e718d9e052c4204d8ce4cd5ff92a21c20d\",\n        \"size\": 657794072\n    },\n    \"StaticCutIn_Town13_Route3489_Weather0.tar.gz\": {\n        \"sha256\": \"53d5ea30cba05618735c7c9d6fe30444d3facbeceabbf0ca47e70d2bbdb14b88\",\n        \"size\": 811115951\n    },\n    \"StaticCutIn_Town13_Route3490_Weather1.tar.gz\": {\n        \"sha256\": \"00b33afae2278e7fd1431e2b5fd30aebb53ca5e78b6a4ee9e189f163222b2a45\",\n        \"size\": 702133607\n    },\n    \"StaticCutIn_Town13_Route3491_Weather2.tar.gz\": {\n        \"sha256\": \"d2bd6dd4133e5a2a8562b0ea8d581db61b86fface304403748146f6e60c975f3\",\n        \"size\": 807344728\n    },\n    \"StaticCutIn_Town13_Route3492_Weather3.tar.gz\": {\n        \"sha256\": \"49af9e0f96c26cfa611c19c21bac8a28c133f426bbc3f760762e9fcd14fe851f\",\n        \"size\": 732107651\n    },\n    \"StaticCutIn_Town13_Route3493_Weather3.tar.gz\": {\n        \"sha256\": \"26ff5bbe0e86577aeda2573b39b9f67ccfa2f79d68b15efda61bfe1d308a1eb9\",\n        \"size\": 608527581\n    },\n    \"StaticCutIn_Town13_Route3494_Weather5.tar.gz\": {\n        \"sha256\": \"fb44e81ae75dd0af7fffede85d4c5cd88609aaf997d34b077c4b22a2a2c1683c\",\n        \"size\": 484613690\n    },\n    \"StaticCutIn_Town13_Route3495_Weather6.tar.gz\": {\n        \"sha256\": \"b4daf4863d837ef870066c5d91ea9f64ef7784e281e7a39b4ca56e8b63a762e9\",\n        \"size\": 630182822\n    },\n    \"StaticCutIn_Town13_Route3496_Weather7.tar.gz\": {\n        \"sha256\": \"8e5df034c8b8e96f74a38e8325b59accc2ee02dd2131002e6acaf185be41ae81\",\n        \"size\": 132173011\n    },\n    \"StaticCutIn_Town13_Route3497_Weather8.tar.gz\": {\n        \"sha256\": \"e1ad1f443097e85848b4c32f870ad59f245fa05437b3422044b308b3891069a9\",\n        \"size\": 124804375\n    },\n    \"StaticCutIn_Town13_Route3498_Weather9.tar.gz\": {\n        \"sha256\": \"b7a9efb418684fa73cfb37d7da34678247017b72d4c65c27ab97ac5f6eeb337f\",\n        \"size\": 105791258\n    },\n    \"StaticCutIn_Town13_Route3500_Weather11.tar.gz\": {\n        \"sha256\": \"324c7acd0e6154b2d3dd7f5650c8c87b816bc96163f08a049f37a12bca017d60\",\n        \"size\": 705300847\n    },\n    \"StaticCutIn_Town13_Route3501_Weather12.tar.gz\": {\n        \"sha256\": \"ed576cf9160207872d73b463a1aac2a11a075da681c2f72d2492da9d709f2ce6\",\n        \"size\": 713330520\n    },\n    \"StaticCutIn_Town13_Route3502_Weather13.tar.gz\": {\n        \"sha256\": \"9607afbee3071534e94ebec11acb143fda694031b0b45f7981e718e375ec2392\",\n        \"size\": 667552556\n    },\n    \"StaticCutIn_Town15_Route26398_Weather19.tar.gz\": {\n        \"sha256\": \"19ddef5c2953f35f98e2acf04fa3814e0b7980d7968c4a82f3f4a67b24ab03b2\",\n        \"size\": 565746764\n    },\n    \"StaticCutIn_Town15_Route26405_Weather0.tar.gz\": {\n        \"sha256\": \"ee1429808fdbfbadac36f1438fb7d97f4b5b7e58015eaa4c0f86f2123c75ec87\",\n        \"size\": 875179603\n    },\n    \"StaticCutIn_Town15_Route26412_Weather8.tar.gz\": {\n        \"sha256\": \"90f10697f6fe9ddeedff1d4522ae7791580de79f48de1d934b617f0b680611c2\",\n        \"size\": 491392418\n    },\n    \"StaticCutIn_Town15_Route26426_Weather25.tar.gz\": {\n        \"sha256\": \"fbd5e58e775d22a6c30f0d3de452b5b4d1b066eecca7831319d7f7aae62d3452\",\n        \"size\": 758546747\n    },\n    \"StaticCutIn_Town15_Route26440_Weather13.tar.gz\": {\n        \"sha256\": \"e9ef762d51e50711ed8bf77cd92812401d7179e5f124229bc3b5f1c2406dc156\",\n        \"size\": 385043750\n    },\n    \"StaticCutIn_Town15_Route26447_Weather22.tar.gz\": {\n        \"sha256\": \"778e6280d3428321cc84d0f1fa3ae47d9e380d1345610a1156cedbe83bc02944\",\n        \"size\": 909390350\n    },\n    \"StaticCutIn_Town15_Route26461_Weather11.tar.gz\": {\n        \"sha256\": \"2846c47ba3eee65731655166178399d8e26e552470e1639ce29da08384abfc9e\",\n        \"size\": 1024466463\n    },\n    \"StaticCutIn_Town15_Route26468_Weather20.tar.gz\": {\n        \"sha256\": \"4de950714b321676ca0ac2073f70ec1bc48fc1c0dbfd43b60dcfd27f90828afd\",\n        \"size\": 1135381072\n    },\n    \"StaticCutIn_Town15_Route26489_Weather18.tar.gz\": {\n        \"sha256\": \"a19cbb4f2c882e0ef137c297ab710c0eaec25fce5f7d2395d89df82dcec7a092\",\n        \"size\": 215675474\n    },\n    \"StaticCutIn_Town15_Route26495_Weather25.tar.gz\": {\n        \"sha256\": \"fb5881aab39e314533eeaa5032b11517c84a2bda8e67108bdf4cde2e3418b11f\",\n        \"size\": 466332875\n    },\n    \"StaticCutIn_Town15_Route26501_Weather5.tar.gz\": {\n        \"sha256\": \"54e4342801da3f19b3d9f31bc48c2627c84be34d249509139039e2cc8fab13b1\",\n        \"size\": 547744430\n    },\n    \"StaticCutIn_Town15_Route26507_Weather11.tar.gz\": {\n        \"sha256\": \"0a51e998c6eecb6132411c205c92e961d755490789465506cba37c9350626400\",\n        \"size\": 531117521\n    },\n    \"StaticCutIn_Town15_Route26513_Weather19.tar.gz\": {\n        \"sha256\": \"52b5c0998b2563720bc8fca5bbcd33aa43a51ee8305ab123a0be7549567d3b6d\",\n        \"size\": 199871057\n    },\n    \"TJunction_Town01_Route28034_Weather0.tar.gz\": {\n        \"sha256\": \"ee314a4657bd6ef7ededd01d00b0eba91d75c0972a90a65868f47135e6a3fa9f\",\n        \"size\": 690158485\n    },\n    \"TJunction_Town01_Route28035_Weather1.tar.gz\": {\n        \"sha256\": \"286e22488d34253f117ee94e6acbcf7c48cf7f23dcb362ed2b12290e7e940537\",\n        \"size\": 744819437\n    },\n    \"TJunction_Town01_Route28036_Weather2.tar.gz\": {\n        \"sha256\": \"e6531ab151d2a6ea418a68a90589a7681319bb3b37956b7c6e646ec1a395af72\",\n        \"size\": 438933301\n    },\n    \"TJunction_Town01_Route28037_Weather3.tar.gz\": {\n        \"sha256\": \"87b53aede5c3d4bec43b1ee637a68a2ffbae5b24f04f7cae6b96a4b8d6c743b5\",\n        \"size\": 182360055\n    },\n    \"TJunction_Town01_Route28038_Weather5.tar.gz\": {\n        \"sha256\": \"f42cceef47e2e6822c04c207079ccf64844f6742a95e53e7b9fc864e4057cbd0\",\n        \"size\": 264067298\n    },\n    \"TJunction_Town01_Route28039_Weather6.tar.gz\": {\n        \"sha256\": \"3ae792d02f8197ac824142f4efaf68a3ba8d8d007562103603d4f493f789a9ae\",\n        \"size\": 904203277\n    },\n    \"TJunction_Town01_Route28040_Weather7.tar.gz\": {\n        \"sha256\": \"ee610ce776d31189ead118dfa89dc192a6be2afba395b6e98bf98c14be12d862\",\n        \"size\": 571358153\n    },\n    \"TJunction_Town01_Route28041_Weather8.tar.gz\": {\n        \"sha256\": \"896a748281675ab275badcab78d911759694a35daaf74efc78707288fa93f068\",\n        \"size\": 1262620695\n    },\n    \"TJunction_Town01_Route28042_Weather9.tar.gz\": {\n        \"sha256\": \"8d5696005a27571e5964411ce9f8fd0690b8473543dc050dad55adfe3b47e1e3\",\n        \"size\": 324024807\n    },\n    \"TJunction_Town01_Route28043_Weather10.tar.gz\": {\n        \"sha256\": \"7ab9b5d1f8d67e5387e01ee1d38ae7566b4bbea3e95e10cf3a262778a3800680\",\n        \"size\": 131884223\n    },\n    \"TJunction_Town02_Route28044_Weather11.tar.gz\": {\n        \"sha256\": \"9d5e0c517a5f8de7b152ebf0e8e998c8f074f1a26b3fb295650a47f7176a9c25\",\n        \"size\": 119476835\n    },\n    \"TJunction_Town02_Route28045_Weather12.tar.gz\": {\n        \"sha256\": \"47c89dc13536bfc4fad6a36e34bef9a3b4a069eb99a7ffcb0ff160872d6f366d\",\n        \"size\": 218979347\n    },\n    \"TJunction_Town02_Route28046_Weather13.tar.gz\": {\n        \"sha256\": \"ccacc03872680cb93fecc87c96ccb941e3ef363905cd0a026a3ef71b2aa39687\",\n        \"size\": 215962491\n    },\n    \"TJunction_Town02_Route28047_Weather14.tar.gz\": {\n        \"sha256\": \"97b09facd153bcefc08c501d79f598ff285be49d8f16a5ac855c50167c065a78\",\n        \"size\": 1061532149\n    },\n    \"TJunction_Town02_Route28048_Weather15.tar.gz\": {\n        \"sha256\": \"1efb2e4d1e562f631c43b1629c4b05c0eb47bed1bf787e3b8ef043aa9ffe682e\",\n        \"size\": 655756643\n    },\n    \"TJunction_Town02_Route28051_Weather20.tar.gz\": {\n        \"sha256\": \"dbb2ca22f2c8f4fd90163c011f01402c93125acb99531239b6d2a2a9a8c051ed\",\n        \"size\": 180724353\n    },\n    \"TJunction_Town02_Route28052_Weather21.tar.gz\": {\n        \"sha256\": \"2c69a3be32789fbc17f799791c1e8c6a88756a8826988ec5ecb8aff31a530ce0\",\n        \"size\": 253602720\n    },\n    \"TJunction_Town02_Route28053_Weather22.tar.gz\": {\n        \"sha256\": \"8ab7eed6593944bfb2b33564d9f89268b8d65be4d519d05e28f7b500123a07e4\",\n        \"size\": 108427650\n    },\n    \"TJunction_Town03_Route27887_Weather11.tar.gz\": {\n        \"sha256\": \"b62400b40678b29cfb71eb6f9a62db4e6318ec44de81d0a8b8747ca026d513a2\",\n        \"size\": 212969345\n    },\n    \"TJunction_Town03_Route27891_Weather15.tar.gz\": {\n        \"sha256\": \"d2e193e4bca593e406e4ee12fd331515d88b976c53ba67d51c42c5c35295e25f\",\n        \"size\": 654645718\n    },\n    \"TJunction_Town03_Route27899_Weather26.tar.gz\": {\n        \"sha256\": \"03e07e56437a04004e9539a79be608f1e30dd425bf628d61fb90e1d4230eecd4\",\n        \"size\": 177396831\n    },\n    \"TJunction_Town03_Route27907_Weather8.tar.gz\": {\n        \"sha256\": \"a95c5000a93d17e2a1f0356706c014b75115f92767e8949666e533e66e7bf385\",\n        \"size\": 101301348\n    },\n    \"TJunction_Town03_Route27915_Weather18.tar.gz\": {\n        \"sha256\": \"281d0b488e6a01fab5be714c8bcc97dc00a542ad70d7ea61d0163727dc9f234a\",\n        \"size\": 771556654\n    },\n    \"TJunction_Town03_Route27919_Weather22.tar.gz\": {\n        \"sha256\": \"d24502a272f13cbd2ec3f40cf1f3396274335c8e346c78064442ea6f69f34581\",\n        \"size\": 206883721\n    },\n    \"TJunction_Town03_Route27927_Weather5.tar.gz\": {\n        \"sha256\": \"c9b314b13dd293970f29b8fb6c8424d250bd87f5d2801964fc83af697e53406a\",\n        \"size\": 300269411\n    },\n    \"TJunction_Town03_Route27931_Weather9.tar.gz\": {\n        \"sha256\": \"81663b516f0991c11a3d8a54dabb784648a085b8365517cde5ce6e20980e83a1\",\n        \"size\": 64081800\n    },\n    \"TJunction_Town03_Route27935_Weather13.tar.gz\": {\n        \"sha256\": \"0b910211bb961c15260fba516ea1a147cba61e981e7ca41ee7c0d3bc18cfe85d\",\n        \"size\": 92634964\n    },\n    \"TJunction_Town03_Route27939_Weather19.tar.gz\": {\n        \"sha256\": \"0d6f4dc177fdbea275943876cbc18929cd0b44d24b07ff725feb05c02e6a5640\",\n        \"size\": 257991741\n    },\n    \"TJunction_Town03_Route27943_Weather23.tar.gz\": {\n        \"sha256\": \"bfbaa81c230f87ee58e5ff69e501c9f0a52fb3f38402dfe64cc8b8b2b5a3822b\",\n        \"size\": 130581736\n    },\n    \"TJunction_Town03_Route27947_Weather1.tar.gz\": {\n        \"sha256\": \"7d6139abe7eb2f37aec778a6e0551e91ef30cfc1b56257030f1da7fd116034f3\",\n        \"size\": 127202935\n    },\n    \"TJunction_Town03_Route27951_Weather6.tar.gz\": {\n        \"sha256\": \"21b644eefe5966c499399cb4ae1d1b5f922ed5245ca98c43a44df621bb4d0ea8\",\n        \"size\": 368980527\n    },\n    \"TJunction_Town03_Route27955_Weather10.tar.gz\": {\n        \"sha256\": \"77775774839b817b524b9bc3de33acaa17606a81a8e833db161c614dd6b37784\",\n        \"size\": 535716618\n    },\n    \"TJunction_Town03_Route27959_Weather14.tar.gz\": {\n        \"sha256\": \"a7064a1c4b3783dc661822d326957b27555f3118b7d8ec7af0331f04095ba2e4\",\n        \"size\": 798925295\n    },\n    \"TJunction_Town04_Route27974_Weather6.tar.gz\": {\n        \"sha256\": \"cb7cd3b5edbb2929363d35fea71585912ce82dd3c68ec7ab2d1cb05a368edfd0\",\n        \"size\": 117360776\n    },\n    \"TJunction_Town04_Route27977_Weather9.tar.gz\": {\n        \"sha256\": \"2fbe64b0cc121fdc15c8a7df15da84957a6dec33eb85c1840bb84702204a4755\",\n        \"size\": 204235760\n    },\n    \"TJunction_Town04_Route27980_Weather12.tar.gz\": {\n        \"sha256\": \"02fdb7abcccda51a12203c29008a5a22f1560d0900662f2d0babdc0bee13560f\",\n        \"size\": 90339672\n    },\n    \"TJunction_Town04_Route27983_Weather15.tar.gz\": {\n        \"sha256\": \"86ce923ed5c343af8de0543a02337a0b59975586c3b2e656851dff7af701a3d8\",\n        \"size\": 290821618\n    },\n    \"TJunction_Town04_Route27986_Weather20.tar.gz\": {\n        \"sha256\": \"4fd21ef59f6319a66f6bcea11df7ed454b4e8b51923c9b1f071ac2caeeac009f\",\n        \"size\": 86010658\n    },\n    \"TJunction_Town04_Route27989_Weather23.tar.gz\": {\n        \"sha256\": \"409b18f76af8d60c8744b3a7a75f87fb795e309a25b14719e6a4859cfdc2a3af\",\n        \"size\": 238148877\n    },\n    \"TJunction_Town04_Route27992_Weather0.tar.gz\": {\n        \"sha256\": \"884221911539509dafd75b33bbcc316846fa0fd5ad995008a1adfbc4da445f23\",\n        \"size\": 150021724\n    },\n    \"TJunction_Town04_Route27995_Weather3.tar.gz\": {\n        \"sha256\": \"a3512e0e788cf433ea4f4a92b638e7fa11dda74ea8463a37caa1663c8b29f663\",\n        \"size\": 290525020\n    },\n    \"TJunction_Town04_Route27998_Weather7.tar.gz\": {\n        \"sha256\": \"58d720316fa37be6da82c7415cb56edbda95cd31d0c84fd5cc64ec1206fc35f3\",\n        \"size\": 141496010\n    },\n    \"TJunction_Town04_Route28001_Weather10.tar.gz\": {\n        \"sha256\": \"fff89871c15553a3ab731622e4c2191fc2742b17863b6b211a57c7658c9ec019\",\n        \"size\": 122799544\n    },\n    \"TJunction_Town04_Route28004_Weather13.tar.gz\": {\n        \"sha256\": \"dd62396751e80176d8213afddb1fa6567e6833261c54de05f2598c5ae13473b0\",\n        \"size\": 263119956\n    },\n    \"TJunction_Town04_Route28007_Weather18.tar.gz\": {\n        \"sha256\": \"faac64827e9df02bb0e5b5020f55c67cbaa41dfa72cebf42c721bbe894bb18de\",\n        \"size\": 285003513\n    },\n    \"TJunction_Town04_Route28009_Weather20.tar.gz\": {\n        \"sha256\": \"5fc03e4d812a3a859dad177d47adbeb05ad748818c79996e2fbaa6c15c5cba91\",\n        \"size\": 222814204\n    },\n    \"TJunction_Town04_Route28011_Weather22.tar.gz\": {\n        \"sha256\": \"a3d035f9953271e1672ecc346b8e4f1685f953131be45e9011a730b9d77d25d7\",\n        \"size\": 228106565\n    },\n    \"TJunction_Town04_Route28013_Weather25.tar.gz\": {\n        \"sha256\": \"66778bd918a0fbf06adccc7c12f7fe405e5e3b1e8b23e259cd932cf15b3a57b7\",\n        \"size\": 152292905\n    },\n    \"TJunction_Town04_Route28015_Weather0.tar.gz\": {\n        \"sha256\": \"069965f9ab9c1ac0c9065b0d8ffa7767cc52b0a0c19324654839147561d04758\",\n        \"size\": 615974833\n    },\n    \"TJunction_Town04_Route28017_Weather2.tar.gz\": {\n        \"sha256\": \"c903a29ae33a201d29e20be1599f9ce68147603451ee58f0185aead0477bffed\",\n        \"size\": 238818009\n    },\n    \"TJunction_Town04_Route28019_Weather5.tar.gz\": {\n        \"sha256\": \"86ed6b3ff196780c5343a646fe55736cb52b6ec44b7f7fd1e01e42147313b08b\",\n        \"size\": 128784299\n    },\n    \"TJunction_Town04_Route28021_Weather7.tar.gz\": {\n        \"sha256\": \"0488c634437d046b1c680a3f62eb52d0af06209e99410ddabc171051a34283d3\",\n        \"size\": 292951113\n    },\n    \"TJunction_Town04_Route28023_Weather9.tar.gz\": {\n        \"sha256\": \"e687e87882780c76d8cef2417b319ff6fedebd69c86cbb56711bddf0a9fadca6\",\n        \"size\": 273211887\n    },\n    \"TJunction_Town04_Route28104_Weather1.tar.gz\": {\n        \"sha256\": \"153bdb31cb99484bd426c4a34714ed1088ada94e17125d2d85130cf911f463cf\",\n        \"size\": 141111195\n    },\n    \"TJunction_Town04_Route28105_Weather2.tar.gz\": {\n        \"sha256\": \"f3e04e0491675390e8e6771884ee6ccb4b6bbb399b39da0dba600bcf2de18a94\",\n        \"size\": 157916197\n    },\n    \"TJunction_Town04_Route28107_Weather5.tar.gz\": {\n        \"sha256\": \"a7a08c5fc9cf1fac946d06fb7ac96d93f3b2f646855659efb69514e8b223cceb\",\n        \"size\": 218303348\n    },\n    \"TJunction_Town04_Route28108_Weather6.tar.gz\": {\n        \"sha256\": \"d6f8f39dac07f7f19e45e995c11ddc706ef96356e39b1af91fd8e34a3ad763da\",\n        \"size\": 225305457\n    },\n    \"TJunction_Town04_Route28109_Weather7.tar.gz\": {\n        \"sha256\": \"d37c7309ef00024e51eb7416ad61347f569c278f0521a1d99011352e3478ae7f\",\n        \"size\": 155359787\n    },\n    \"TJunction_Town04_Route28111_Weather9.tar.gz\": {\n        \"sha256\": \"99645995307e6d5dcaca09107ea751eb436b7ce0309da083302d970ae1c54f0e\",\n        \"size\": 138131791\n    },\n    \"TJunction_Town04_Route28112_Weather10.tar.gz\": {\n        \"sha256\": \"5677ce9cc3c2c8d4b64b4f67cbf5c60b5863cb1c0a04301841dcbb2ffaf1a73e\",\n        \"size\": 254367471\n    },\n    \"TJunction_Town04_Route28113_Weather11.tar.gz\": {\n        \"sha256\": \"394e6a2e3a71f3f925887e1bd51f6d0b30d7b48f2981216ee19301f6b860de33\",\n        \"size\": 239006573\n    },\n    \"TJunction_Town05_Route28002_Weather11.tar.gz\": {\n        \"sha256\": \"b88f2bc132528ebbd7dbd2fbe437c638878a7e9f1d0378e504a35ca6ee9327c7\",\n        \"size\": 674543052\n    },\n    \"TJunction_Town05_Route28005_Weather14.tar.gz\": {\n        \"sha256\": \"40a3a7c0fa171d6c07a1e7cb40c0fac852ef61fb4debe44b67ed94f700f80671\",\n        \"size\": 431686914\n    },\n    \"TJunction_Town05_Route28010_Weather21.tar.gz\": {\n        \"sha256\": \"b4596de07fe85f961e9e6aec239487dbe62063490e04ee5899f94c7207930ea8\",\n        \"size\": 590002662\n    },\n    \"TJunction_Town05_Route28012_Weather23.tar.gz\": {\n        \"sha256\": \"626b66fb6ecfd229c8f9c22a78205f2123e7fe81c450654ce737fdfc15555bf1\",\n        \"size\": 735454878\n    },\n    \"TJunction_Town05_Route28014_Weather26.tar.gz\": {\n        \"sha256\": \"8fd30913826c471efe0cf9d32cd90dff9176662a47bc3bdf32369aba955ab8b0\",\n        \"size\": 706269144\n    },\n    \"TJunction_Town05_Route28016_Weather1.tar.gz\": {\n        \"sha256\": \"2f80c370f8b8f0d2eaac9c63d91fc61a79aa3b2f7da0fead577325f6be0e0bf7\",\n        \"size\": 710531687\n    },\n    \"TJunction_Town05_Route28018_Weather3.tar.gz\": {\n        \"sha256\": \"73ccd8e8264008a97e6faa54eb8689543504dd1f85086abfe6b2d2a07af0a01b\",\n        \"size\": 382725542\n    },\n    \"TJunction_Town05_Route28020_Weather6.tar.gz\": {\n        \"sha256\": \"2413b172c5171a4ee035835260c92f37c3f646b739bf85db21e2ca288e381d06\",\n        \"size\": 359796593\n    },\n    \"TJunction_Town05_Route28022_Weather8.tar.gz\": {\n        \"sha256\": \"7a7d48edd3e9463b1741ad9111de7a741e836397148ed2c4e7be981a524386c4\",\n        \"size\": 1218779135\n    },\n    \"TJunction_Town05_Route28024_Weather10.tar.gz\": {\n        \"sha256\": \"15f3d947d3f58a77377143dd330a995fc6d0358e3b436219f0145db1f0369a3a\",\n        \"size\": 626148347\n    },\n    \"TJunction_Town05_Route28025_Weather11.tar.gz\": {\n        \"sha256\": \"3af8d623eb7bf9ced0264aa3d35207beeaa6d784870db0ff09f2fbc288b25ee7\",\n        \"size\": 366375468\n    },\n    \"TJunction_Town05_Route28026_Weather12.tar.gz\": {\n        \"sha256\": \"06b83c3367b483b0fc574b7a1ea8e511f4fc50765c117e0665a859d61bfe2c59\",\n        \"size\": 448740371\n    },\n    \"TJunction_Town05_Route28027_Weather13.tar.gz\": {\n        \"sha256\": \"ced6677fbe61b622dea9d4151d91299bad9ff2e882a55ce1717116a17fd71319\",\n        \"size\": 350392966\n    },\n    \"TJunction_Town05_Route28028_Weather14.tar.gz\": {\n        \"sha256\": \"5f415d03613604e4c0d7dbbd3de2de23b9156edbfbfd53a6c70378521fbe2f73\",\n        \"size\": 811476503\n    },\n    \"TJunction_Town05_Route28029_Weather15.tar.gz\": {\n        \"sha256\": \"cf6fe727ada3b567e71590b26f6555a69aca911e76ba886853fc71d4c90f9407\",\n        \"size\": 427649859\n    },\n    \"TJunction_Town05_Route28030_Weather18.tar.gz\": {\n        \"sha256\": \"5c0177c7938208574a48b13b325dd6ab47d010b3cbf4a7821d501dcf71593867\",\n        \"size\": 790199348\n    },\n    \"TJunction_Town05_Route28031_Weather19.tar.gz\": {\n        \"sha256\": \"b043dc22f69c57dc1a38ea271fc2a1e5c7e94732c15e98b8dbdd0ff55b77efcf\",\n        \"size\": 726594312\n    },\n    \"TJunction_Town05_Route28032_Weather20.tar.gz\": {\n        \"sha256\": \"42bf4d25065d10f5a8c2b8ed7f18c4a6f03521332b3b146462bb0fa055814beb\",\n        \"size\": 648923978\n    },\n    \"TJunction_Town05_Route28033_Weather21.tar.gz\": {\n        \"sha256\": \"ee55a01a77a7607d4a376620a2628e9ef98f57ad5bdefa398e84f3348aa83f25\",\n        \"size\": 717177987\n    },\n    \"TJunction_Town05_Route28134_Weather9.tar.gz\": {\n        \"sha256\": \"4e045dafe372a329635f68fcce7b171f0a74eb9d6732f97c6303bcd2a94f73e9\",\n        \"size\": 308445511\n    },\n    \"TJunction_Town05_Route28135_Weather10.tar.gz\": {\n        \"sha256\": \"be198cb77dc405fc510be7e2be4ce920f897e561ebadf82beba20540d3a41c73\",\n        \"size\": 683902158\n    },\n    \"TJunction_Town05_Route28136_Weather11.tar.gz\": {\n        \"sha256\": \"dbaec8d8f9ae5dfeb73a0f75b31a93c162e26e9f557e8136bd240d87e5754ce5\",\n        \"size\": 365792707\n    },\n    \"TJunction_Town05_Route28137_Weather12.tar.gz\": {\n        \"sha256\": \"a105ae5ba6a41cceab4d9a1181bdd455d7dece46eb1618363fb134c7f90ce3e0\",\n        \"size\": 663612728\n    },\n    \"TJunction_Town05_Route28138_Weather13.tar.gz\": {\n        \"sha256\": \"12a00f729e53cb329ebddb4428498907be2d3fd74fd127dc85b7d6db7e0fd20e\",\n        \"size\": 792907090\n    },\n    \"TJunction_Town05_Route28139_Weather14.tar.gz\": {\n        \"sha256\": \"33cb880a10ae5d3296bf6fab40c189290a91a972c67e0cae3b8cb587c620a6c7\",\n        \"size\": 405344388\n    },\n    \"TJunction_Town05_Route28140_Weather15.tar.gz\": {\n        \"sha256\": \"df3cdb547ace69637dd10a9b046c559f2bc49798ea2354a660ab2b83a3741236\",\n        \"size\": 1258523910\n    },\n    \"TJunction_Town05_Route28141_Weather18.tar.gz\": {\n        \"sha256\": \"03471816f9d937f85388f578ce97794bd41a37f33766143352d819cd02730c46\",\n        \"size\": 386102674\n    },\n    \"TJunction_Town05_Route28142_Weather19.tar.gz\": {\n        \"sha256\": \"02520796da1cf850fb9ffbf17931992bf3338e0f51bfdcc3cc09c1ba30e4a3cd\",\n        \"size\": 720001748\n    },\n    \"TJunction_Town05_Route28143_Weather20.tar.gz\": {\n        \"sha256\": \"cbe12bee1592948dbc43cb588cb87895a1b6fb7865bdeaa963aa6cda9ee9c21a\",\n        \"size\": 525037229\n    },\n    \"TJunction_Town06_Route26429_Weather1.tar.gz\": {\n        \"sha256\": \"69ed987934855ed821f117331a457b28f5b8ec64ffcb902e21c1874bf4407be3\",\n        \"size\": 764228229\n    },\n    \"TJunction_Town06_Route26436_Weather9.tar.gz\": {\n        \"sha256\": \"74dbe2226d3e01db547350ae890b49fe1d55f183e395c02619e88507f268ceee\",\n        \"size\": 626008350\n    },\n    \"TJunction_Town06_Route26443_Weather18.tar.gz\": {\n        \"sha256\": \"b95141cb7e377f8ecff05cc9153d9e5f39b917b17ae629e2fe78fdc1d8a602e7\",\n        \"size\": 917247074\n    },\n    \"TJunction_Town06_Route26471_Weather23.tar.gz\": {\n        \"sha256\": \"edb4817dba440e34758accd93b19709144192bf20a050e023410da5ebce10ace\",\n        \"size\": 620085181\n    },\n    \"TJunction_Town06_Route26485_Weather12.tar.gz\": {\n        \"sha256\": \"157c9c8f9b84e8d521e9d5b22700e6da17e0c9ade5a4d80c0f99ff880af9e14c\",\n        \"size\": 736167365\n    },\n    \"TJunction_Town06_Route26492_Weather21.tar.gz\": {\n        \"sha256\": \"dd31baf8ac903c8e7d4fa9f90cf0ca1f65978b444ec7cc50ed068aa674a95796\",\n        \"size\": 633407793\n    },\n    \"TJunction_Town06_Route26498_Weather1.tar.gz\": {\n        \"sha256\": \"28767cbf7c1ccc0244bbcf6e5bb20e18325dfea7642230004b7b93f22ba12459\",\n        \"size\": 863293764\n    },\n    \"TJunction_Town06_Route26510_Weather14.tar.gz\": {\n        \"sha256\": \"ee5b22f5365a4b1dfd27279b05135cbdd5ea76ce92c3e8d514dfd9ed59dff117\",\n        \"size\": 672922027\n    },\n    \"TJunction_Town07_Route26402_Weather23.tar.gz\": {\n        \"sha256\": \"5adc5933ac96ff6a416d56faa2fb8c6364dc1adf44579bf932945abdd60c89e8\",\n        \"size\": 403329066\n    },\n    \"TJunction_Town07_Route26437_Weather10.tar.gz\": {\n        \"sha256\": \"2a306def13ac363d82ce0197b3c5463bb6ba2ec11e634c6aeeb4500edcfdf474\",\n        \"size\": 123710058\n    },\n    \"TJunction_Town07_Route26444_Weather19.tar.gz\": {\n        \"sha256\": \"c5e1608f5b8c42d9eaae198418394772a1c2c5a8a7b3fd17e0bc340fa39e52ac\",\n        \"size\": 524826114\n    },\n    \"TJunction_Town07_Route26458_Weather8.tar.gz\": {\n        \"sha256\": \"b8ed23523fc49cf3af2b492b01d59e50eb7c3507d3fc0bdcbb7cdf70b763ebd9\",\n        \"size\": 229580236\n    },\n    \"TJunction_Town07_Route26472_Weather25.tar.gz\": {\n        \"sha256\": \"0e4b5aae3dc7718e8271635de814864c9408f2d08bc7ee296f92f8531d02743b\",\n        \"size\": 269618000\n    },\n    \"TJunction_Town07_Route26479_Weather6.tar.gz\": {\n        \"sha256\": \"8080c8e6b821718765b7e79f6ed1116b44f6c8f3c240e5e3d948102dc28c610d\",\n        \"size\": 203947648\n    },\n    \"TJunction_Town07_Route26486_Weather13.tar.gz\": {\n        \"sha256\": \"68119ae8c9abfeb2bbeff2cdc464d5737687f7dcd5ffa012089b73ea4e052965\",\n        \"size\": 260164517\n    },\n    \"TJunction_Town10HD_Route28150_Weather1.tar.gz\": {\n        \"sha256\": \"9f6e5f26009feaf5e36809bf191cb3cb8baf1ccd7b762d80f9b42db3c058ed54\",\n        \"size\": 472632632\n    },\n    \"TJunction_Town10HD_Route28151_Weather2.tar.gz\": {\n        \"sha256\": \"708285895cc3208d5cf7564fc7e3c846903b17b7063ae0766e4a70fdf0eab79c\",\n        \"size\": 474455863\n    },\n    \"TJunction_Town10HD_Route28152_Weather3.tar.gz\": {\n        \"sha256\": \"52c058d93283d6d33ca6944b707f0a544a35de768c93903929ce9faa93ee4701\",\n        \"size\": 453396329\n    },\n    \"TJunction_Town10HD_Route28153_Weather5.tar.gz\": {\n        \"sha256\": \"3ce4d992909715a891397c7fee0d75b7e7455ff718f26c79c5730e717613cbf0\",\n        \"size\": 453830049\n    },\n    \"TJunction_Town10HD_Route28154_Weather6.tar.gz\": {\n        \"sha256\": \"d6a76d7b31b1f656bc7b733edb2d107745d9e1a1667b0d1e858d41b300bd26e1\",\n        \"size\": 466035269\n    },\n    \"TJunction_Town10HD_Route28155_Weather7.tar.gz\": {\n        \"sha256\": \"5c6ea2368bc62171ca125e86b05b57efedfd9a3664a3f7bfc41f74b0ac41a5f0\",\n        \"size\": 599678869\n    },\n    \"TJunction_Town10HD_Route28156_Weather8.tar.gz\": {\n        \"sha256\": \"4ad9a400c947e0642b9121f20f514403d5a991c82defdc3153d0fb0890466e6d\",\n        \"size\": 432352572\n    },\n    \"TJunction_Town10HD_Route28157_Weather9.tar.gz\": {\n        \"sha256\": \"168b0278f1ea59d6a8470d8b2728a1e263ec883946952ea7cb921fcf5098ef43\",\n        \"size\": 664982961\n    },\n    \"TJunction_Town10HD_Route28158_Weather10.tar.gz\": {\n        \"sha256\": \"fa741953fcc803ee6affd9e681735991b9e5a410e8cdb0378a3ff7f9cd59e1dc\",\n        \"size\": 178400314\n    },\n    \"TJunction_Town11_Route27949_Weather3.tar.gz\": {\n        \"sha256\": \"3af4a14354d3c4195d37884d0c2719b63c8f2b50c0bf36e36c76a75ddbf76598\",\n        \"size\": 181193143\n    },\n    \"TJunction_Town11_Route27953_Weather8.tar.gz\": {\n        \"sha256\": \"c88d599a48ee80097ab3f8445376b4483b37268956563484ccd022ba33ec37e7\",\n        \"size\": 168792792\n    },\n    \"TJunction_Town11_Route27964_Weather21.tar.gz\": {\n        \"sha256\": \"366fa95e9074659408e6b55e3297ebafc080a4cd20326b0942559cb3415515f1\",\n        \"size\": 67753246\n    },\n    \"TJunction_Town11_Route27967_Weather25.tar.gz\": {\n        \"sha256\": \"c37aff848db94f5c7adeceb0be32d79fe7770fb4778a24ade7ee2504fc71a4be\",\n        \"size\": 74341672\n    },\n    \"TJunction_Town11_Route27973_Weather5.tar.gz\": {\n        \"sha256\": \"5b2fe3e6de2caabad27b0c5a30fc1f362dda17dbdf3a1ee8ce76d40f5d56f9eb\",\n        \"size\": 201171858\n    },\n    \"TJunction_Town11_Route27979_Weather11.tar.gz\": {\n        \"sha256\": \"0c67ddd803d035020366ec7aecc074a9fb7fd35f887a24bf3cf69694b2d42769\",\n        \"size\": 144075525\n    },\n    \"TJunction_Town11_Route27982_Weather14.tar.gz\": {\n        \"sha256\": \"612e969514cf4f1f4cdf8772b0b192866bca6bc1d63a630fd95ef6bdaef1d3fd\",\n        \"size\": 159219620\n    },\n    \"TJunction_Town11_Route27991_Weather26.tar.gz\": {\n        \"sha256\": \"3d59fc67036a65f090d7e66c9b92f641cf8c6db043d1d1526c1088bae85259d8\",\n        \"size\": 218541298\n    },\n    \"TJunction_Town11_Route27994_Weather2.tar.gz\": {\n        \"sha256\": \"ff8a33723ab8fbf7ff118a9776f49ca1fc7df2e587138e8e16427f03ad5eaee7\",\n        \"size\": 132207502\n    },\n    \"TJunction_Town11_Route27997_Weather6.tar.gz\": {\n        \"sha256\": \"aa5ee11d9f6b6aa30e71526a25eb2d7dd62e05100e8e03b5438c70bd3c43e269\",\n        \"size\": 188790029\n    },\n    \"TJunction_Town11_Route28003_Weather12.tar.gz\": {\n        \"sha256\": \"0377c0ba326fe6d24854f6e6f15260dbf9376dcbee25e8f157bbdf5cfb5575a0\",\n        \"size\": 133536849\n    },\n    \"TJunction_Town11_Route28006_Weather15.tar.gz\": {\n        \"sha256\": \"dd47288826d93c8172260a4c60812421a87aabbe91c413cfb897287f9d9ac3ff\",\n        \"size\": 133666037\n    },\n    \"TJunction_Town11_Route28186_Weather15.tar.gz\": {\n        \"sha256\": \"f3d440b585922e147f1ee44ad9e29d063e6f372491b99b5ee66df9acb576757e\",\n        \"size\": 174102673\n    },\n    \"TJunction_Town11_Route28187_Weather18.tar.gz\": {\n        \"sha256\": \"a3b2d8124d0001a3e5035b8430b52a1d517bcd100267aeec49ee87ed68f2c2fc\",\n        \"size\": 162806107\n    },\n    \"TJunction_Town12_Route28251_Weather11.tar.gz\": {\n        \"sha256\": \"b8af95fb5af7a1d142b6eba10d608cde4c48175829024bf4aaebb13df9e278bb\",\n        \"size\": 224083054\n    },\n    \"TJunction_Town12_Route28252_Weather12.tar.gz\": {\n        \"sha256\": \"c45c57ea20bd9b0568c55d75d149dedec72cec51c0eb70cb8f93b6faabe7e094\",\n        \"size\": 184746343\n    },\n    \"TJunction_Town12_Route28253_Weather13.tar.gz\": {\n        \"sha256\": \"acd307f40ccb4874e6066b3eb1104ffedf5a4f925606fd99936b511b25dc579e\",\n        \"size\": 752740698\n    },\n    \"TJunction_Town12_Route28255_Weather15.tar.gz\": {\n        \"sha256\": \"d4451006493a4324619f84766b98e12ef9bb80a6de62fe9d539bb67f95ea0092\",\n        \"size\": 400605295\n    },\n    \"TJunction_Town12_Route28256_Weather18.tar.gz\": {\n        \"sha256\": \"1f807cbfbc4aeddab0dc8f0992b8fa987bcd7aa1a76dc653e4ca388de950a947\",\n        \"size\": 369816967\n    },\n    \"TJunction_Town12_Route28257_Weather19.tar.gz\": {\n        \"sha256\": \"449213a76f2680b1499f61863e4411fec9b88ac4c9c66c3b6e869cb0d58b39de\",\n        \"size\": 509697204\n    },\n    \"TJunction_Town12_Route28258_Weather20.tar.gz\": {\n        \"sha256\": \"d8c41509acf50ca739de166e0d110bef60b597acca18735930c4c34211ee0f80\",\n        \"size\": 226510063\n    },\n    \"TJunction_Town12_Route28259_Weather21.tar.gz\": {\n        \"sha256\": \"b6c1331e98e62d4df3e980c917d93493f1ec3cd896afea14d63af1010ede700c\",\n        \"size\": 423259863\n    },\n    \"TJunction_Town12_Route28260_Weather22.tar.gz\": {\n        \"sha256\": \"9e1c2c07b9b1c8f546e260fe3c2850a39d22f4a394dcaffb3eca8daf43a9a17f\",\n        \"size\": 556624647\n    },\n    \"TJunction_Town12_Route28261_Weather23.tar.gz\": {\n        \"sha256\": \"bc79bf0eea0b26e631695f8740175bc8473871053aee20af47da14aa87609e59\",\n        \"size\": 351564741\n    },\n    \"TJunction_Town12_Route28262_Weather25.tar.gz\": {\n        \"sha256\": \"24c8182910bbeb7225f2dc4ac2fc95fbe134f8eda1708938da8794066787cf38\",\n        \"size\": 157070617\n    },\n    \"TJunction_Town12_Route28263_Weather26.tar.gz\": {\n        \"sha256\": \"bf3f4ff8fd54b66e28f162499f66d92f2948f8c20ff52381b41b789625d88479\",\n        \"size\": 602215941\n    },\n    \"TJunction_Town12_Route28264_Weather0.tar.gz\": {\n        \"sha256\": \"5a61d88840f2a2e3a52f8644751f2ab384c2d6194286038912cf7ba055fda299\",\n        \"size\": 380982942\n    },\n    \"TJunction_Town12_Route28265_Weather1.tar.gz\": {\n        \"sha256\": \"837c79400faaf1567c5aa0cc28c930d678008e108b57c2796948f605ed3d61a7\",\n        \"size\": 449420270\n    },\n    \"TJunction_Town12_Route28266_Weather2.tar.gz\": {\n        \"sha256\": \"bbc7cb93d6af5aab4eb2ba43d36ee319da96403a7beef173e35a5026f1c9dd8d\",\n        \"size\": 345118319\n    },\n    \"TJunction_Town15_Route27758_Weather22.tar.gz\": {\n        \"sha256\": \"61f590b7fd6c842e9bf4c2e78564c4052b5062ab73229f1613c369f755d6ba64\",\n        \"size\": 437790358\n    },\n    \"TJunction_Town15_Route27768_Weather7.tar.gz\": {\n        \"sha256\": \"080b6768e3055bbc25e7cb50e64dd9044024960da2cefef47e67ab2e20063290\",\n        \"size\": 958030356\n    },\n    \"TJunction_Town15_Route27778_Weather19.tar.gz\": {\n        \"sha256\": \"15f9d7a5ef25ecb62b457cd3f3d03e6826a5fa189bed7ef05c5e2bbf64443208\",\n        \"size\": 141613559\n    },\n    \"TJunction_Town15_Route27783_Weather25.tar.gz\": {\n        \"sha256\": \"4b065576e374ac08cd5d4b89b5c5a3276e938955b91809f78ed3f212b2fdf613\",\n        \"size\": 1388450454\n    },\n    \"TJunction_Town15_Route27788_Weather3.tar.gz\": {\n        \"sha256\": \"d9488135f7389120d9129d031d45d9778ad06dee4b176200c131739b7d120ac5\",\n        \"size\": 432702401\n    },\n    \"TJunction_Town15_Route27793_Weather9.tar.gz\": {\n        \"sha256\": \"3b06251b36437c80d0ed2df5d6843a678aa15cdec9d76ac1065a0e1bd2dbecf0\",\n        \"size\": 369811003\n    },\n    \"TJunction_Town15_Route27798_Weather14.tar.gz\": {\n        \"sha256\": \"146890e18549da4d81a0ef113bfc8c48554e7675b494ab73dad6c82e2565bcc1\",\n        \"size\": 796783629\n    },\n    \"TJunction_Town15_Route27803_Weather21.tar.gz\": {\n        \"sha256\": \"a129d83690338cd69e8ba94e9b711da2f933288f7b339ba3630fec227be72465\",\n        \"size\": 773934491\n    },\n    \"TJunction_Town15_Route27808_Weather0.tar.gz\": {\n        \"sha256\": \"3a8948014c28c16cce0159f22fee9e858dbf41917f57af1afdfec5ba4e537403\",\n        \"size\": 410060206\n    },\n    \"TJunction_Town15_Route27813_Weather6.tar.gz\": {\n        \"sha256\": \"a6b03b8b53dff2eda7f5e165bc777fbd995cc5c4feab086992ad67a15d000b27\",\n        \"size\": 1238179023\n    },\n    \"TJunction_Town15_Route27818_Weather11.tar.gz\": {\n        \"sha256\": \"37577c1ccb7d1512549e9f480125a1876df4a659f1cf5294fc288320ae016b7d\",\n        \"size\": 418715296\n    },\n    \"TJunction_Town15_Route27823_Weather18.tar.gz\": {\n        \"sha256\": \"6ba153e0bc15396fe4c04121cb671f8ed2e4d8ab49a1980944617a81356f4d12\",\n        \"size\": 900265110\n    },\n    \"TJunction_Town15_Route27828_Weather23.tar.gz\": {\n        \"sha256\": \"2c44a55be397aaf0cc79f063518dcc898b770373500fb5a15c9e511f3a08ff8f\",\n        \"size\": 555589780\n    },\n    \"TJunction_Town15_Route27838_Weather8.tar.gz\": {\n        \"sha256\": \"187729feda6b8cd3223286c8056043686c0dc9174316d52a67419be0de7377f4\",\n        \"size\": 774712267\n    },\n    \"TJunction_Town15_Route27853_Weather26.tar.gz\": {\n        \"sha256\": \"b7a3cd76e06a491d5f0261a7e46ea2f2f2ed25d2210f41a8efa32a4a8be6f8e0\",\n        \"size\": 490971388\n    },\n    \"TJunction_Town15_Route28200_Weather6.tar.gz\": {\n        \"sha256\": \"0e3b5437d34c5a73df420442669cee2af1c276d03f9d32857a1f529f65eaebe1\",\n        \"size\": 1662994230\n    },\n    \"TJunction_Town15_Route28204_Weather10.tar.gz\": {\n        \"sha256\": \"707a1768a60efb177ffb31eec193698201ca21f52b46a7b9c93850857a1f6276\",\n        \"size\": 434985704\n    },\n    \"TJunction_Town15_Route28206_Weather12.tar.gz\": {\n        \"sha256\": \"1e3dc5f21af2efa0f8a7903ce09669d9ca886918057dbbe7f755be84fedb1cd0\",\n        \"size\": 1165712876\n    },\n    \"TJunction_Town15_Route28207_Weather13.tar.gz\": {\n        \"sha256\": \"3fbebd46151bfa5de02cd690bcd5ebfc48d4c9f06d783c2073d0dd36030bf3fe\",\n        \"size\": 338634393\n    },\n    \"TJunction_Town15_Route28208_Weather14.tar.gz\": {\n        \"sha256\": \"5bf878b1695e053cf6c2b2af255346d4e540517bc44ac7ad1a4fa3fe2c8b939f\",\n        \"size\": 544691289\n    },\n    \"TJunction_Town15_Route28209_Weather15.tar.gz\": {\n        \"sha256\": \"aeae61a87df0741ba26b1e84111b9edbf2a595b0f810c1777a8f2aa08c74fbf2\",\n        \"size\": 1566376565\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16557_Weather23.tar.gz\": {\n        \"sha256\": \"7ea3900292a2a02ddbf19d369017499f96682e8a5bdda3a92dbd87e66210fe69\",\n        \"size\": 164690589\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16565_Weather6.tar.gz\": {\n        \"sha256\": \"f31a7d00c5d2711f1c8bf1fc7bded21871f37a9ea5c5356cdbc3dd9a28106eb6\",\n        \"size\": 156396031\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16592_Weather7.tar.gz\": {\n        \"sha256\": \"f02cac528a987a9e12f513a073805a3e22f7d6607ecd3f6a7553f928994bfc3d\",\n        \"size\": 141353668\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16606_Weather21.tar.gz\": {\n        \"sha256\": \"e0c91362a508f217e2eaef101409ebcae4e75a7b77813d76d591f07139dd32e5\",\n        \"size\": 164272480\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16625_Weather14.tar.gz\": {\n        \"sha256\": \"fb591f6164030bcca5d13ba66a025b92246070735e77341c8c68cd578e37f7b2\",\n        \"size\": 128509610\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16630_Weather19.tar.gz\": {\n        \"sha256\": \"bbef85d093d85c2a57e49a321052f00836bb53f04f0947698069ce8173eab03a\",\n        \"size\": 274387602\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16633_Weather22.tar.gz\": {\n        \"sha256\": \"26800519ac3954ffbd7d40f52a9cb2d03d19082316136bc1832aa979099e01c3\",\n        \"size\": 195716495\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16670_Weather7.tar.gz\": {\n        \"sha256\": \"da8eb094ee73357d52afa860900c722064bd33d06736cabf784e511da486fbd6\",\n        \"size\": 303062182\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16671_Weather8.tar.gz\": {\n        \"sha256\": \"c3c6eaf612796a01ef33aedccee3c8ab262294fef23553e3e436ea75ac6dece7\",\n        \"size\": 148670239\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16681_Weather18.tar.gz\": {\n        \"sha256\": \"a297167c6f4e98fb6bcbc35d7f2494a7dc331fb483a7718b89cea60cdf94ebd9\",\n        \"size\": 188615508\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16685_Weather22.tar.gz\": {\n        \"sha256\": \"97612581e7ea20d9415df8e02aecec1f7ff41d1b1d74e118c9ab365ae25bd7e2\",\n        \"size\": 222790881\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16719_Weather3.tar.gz\": {\n        \"sha256\": \"525d878edb369080c41224a2e79bd5ea6cc98b53105ea9869db8214313189b26\",\n        \"size\": 154066029\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16726_Weather11.tar.gz\": {\n        \"sha256\": \"4017c2d2de7b7e1c9331c9a38a55a73e67c4a235e46cfb7b077a2ab5a8592227\",\n        \"size\": 230266208\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16744_Weather3.tar.gz\": {\n        \"sha256\": \"b7c55ac31e92dc728506224580f03fcb93a542b9162bb0c7c12e4ead3477c5fc\",\n        \"size\": 133766252\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16756_Weather15.tar.gz\": {\n        \"sha256\": \"8306e4e4a425bf9ed2728471fccc4d33695722c89dd0c5176553d4a53b2509da\",\n        \"size\": 134697033\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16763_Weather22.tar.gz\": {\n        \"sha256\": \"f1a7ca0487a410d4ed93f31c28f69d44a2fa3dcc3ee4fef483f368780c6b436d\",\n        \"size\": 155715499\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16773_Weather6.tar.gz\": {\n        \"sha256\": \"20d15df98564f77d00ca061272fbff465686e517024d216c3e666d1b7503b742\",\n        \"size\": 214606234\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16774_Weather7.tar.gz\": {\n        \"sha256\": \"9a54723420c5f89530898e0c5f3c4bdb86b40a99d70176b47b30206098f88528\",\n        \"size\": 195363434\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16778_Weather11.tar.gz\": {\n        \"sha256\": \"d983b6140cd51db570b44630403251bd6b63d5f5916d32544214d2dddadaddbb\",\n        \"size\": 97153017\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16798_Weather5.tar.gz\": {\n        \"sha256\": \"1218aa854ee3da88604d7a43c4b271926ed38352a11fb7b384d545d454c96419\",\n        \"size\": 63753908\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16804_Weather11.tar.gz\": {\n        \"sha256\": \"2bf3c6a75976103edc6e3cb9f18e855752953da8469ddc25229becc6db97142e\",\n        \"size\": 153134641\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16815_Weather22.tar.gz\": {\n        \"sha256\": \"6457a4aa396e5402a3fbf63e5f437ec630b84ea798ee2322045fa2875e2c7d6b\",\n        \"size\": 103112683\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16823_Weather3.tar.gz\": {\n        \"sha256\": \"04e3831d51b6d4e76d661028de55d0117a7bfac16a8e01238460e6b009c6b080\",\n        \"size\": 202145321\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2404_Weather6.tar.gz\": {\n        \"sha256\": \"629e8363faf8f1c17f4e52de32e04913c8ffa08b572cf241ba2a5d24c42e36bf\",\n        \"size\": 169378763\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2405_Weather7.tar.gz\": {\n        \"sha256\": \"fce1a41eda47ef5d687559f0f8d83d23aa97a7ded2c7da4bfbf4165465fd4b9e\",\n        \"size\": 140040112\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2406_Weather8.tar.gz\": {\n        \"sha256\": \"2679743390e8da5bd03f119bf939c4ddc66368f115c3a6f05a03511bac74da4c\",\n        \"size\": 155131026\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2407_Weather9.tar.gz\": {\n        \"sha256\": \"9ee2113f86b0be29d8b18a89b2f7f2507d122ffad01f6393dcf4a4131433a506\",\n        \"size\": 146319366\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2409_Weather11.tar.gz\": {\n        \"sha256\": \"9936df09f697e38e5ef24de69799bf3ba886da673e8ab715abd32e7dc7a12e3e\",\n        \"size\": 74610968\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2410_Weather12.tar.gz\": {\n        \"sha256\": \"762e117108d339ae011f3cf79c112818a01efed7e30ba2c052b3b1dbf414b5ac\",\n        \"size\": 127148910\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2411_Weather13.tar.gz\": {\n        \"sha256\": \"b8015575839883d1f99720e4a8d9234d22f770d6db6b376365459307dcf5136a\",\n        \"size\": 140118135\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2413_Weather15.tar.gz\": {\n        \"sha256\": \"2e64720e6df3d859a2ae3563ad26210212a3c0d650c0b521ac30202ae1a993fc\",\n        \"size\": 115044319\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2414_Weather8.tar.gz\": {\n        \"sha256\": \"fa6e7e9627c19e23424d7544d499466c00ccdf9b84988e925342267fd90aa411\",\n        \"size\": 173567024\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2415_Weather9.tar.gz\": {\n        \"sha256\": \"6137c95dd1a0047455b32fa5acb973fce1e49c24b674f8842f61c1c159b1d34b\",\n        \"size\": 69007583\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2416_Weather18.tar.gz\": {\n        \"sha256\": \"1668de70fe24c1ab013d25c5746d44ba2f7bcca39d1494f06043cfbb7093cfb8\",\n        \"size\": 237301997\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2417_Weather19.tar.gz\": {\n        \"sha256\": \"72a32189314f2b35725210167a95127eed6c4a4ebfb16172d6dbcb6301f0f2bb\",\n        \"size\": 145277360\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2418_Weather20.tar.gz\": {\n        \"sha256\": \"5b14109c2bc064f4e3bc5983031c5d59b91f0a70e289147ba3ba5bb2810ac514\",\n        \"size\": 140844987\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2421_Weather23.tar.gz\": {\n        \"sha256\": \"3050369da43cf9e6068a6047269a7fbce75a01bc4742d67151811cc7471543d4\",\n        \"size\": 145845150\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2422_Weather23.tar.gz\": {\n        \"sha256\": \"ad9531642bbdd1e125d05765895abd8bc73eaeea65511ab0955b7c655373f398\",\n        \"size\": 114070290\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route2423_Weather25.tar.gz\": {\n        \"sha256\": \"f1d0e934f9816f92509edd0b4135784a6ab7a31e4b49a35a7ae00814a4af0b4b\",\n        \"size\": 126055634\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3184_Weather6.tar.gz\": {\n        \"sha256\": \"3a1dd60989c81b948a9c76061b75fd8307e0f3c674605678b891ef2e43f08b5a\",\n        \"size\": 146377636\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3185_Weather7.tar.gz\": {\n        \"sha256\": \"b676c41803fdffbf9dbe36989dc5a22204de3e34b92034b2694d1470fc261911\",\n        \"size\": 246710423\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3186_Weather8.tar.gz\": {\n        \"sha256\": \"87881a92521d148dbc465ce26c249ae753bec923d802a6c264651d27d525fee4\",\n        \"size\": 79420725\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3187_Weather9.tar.gz\": {\n        \"sha256\": \"1e7a992998fc6b9de1d145a9b3cd8e43d2af9f604e67b818e67a5624d74a0b52\",\n        \"size\": 142953626\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3188_Weather10.tar.gz\": {\n        \"sha256\": \"86fd1176a5a45ad283317b3ada5e19ec4a43af820c0fc61fc5c84f60bc579123\",\n        \"size\": 111704180\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3189_Weather11.tar.gz\": {\n        \"sha256\": \"bf3aea4dd5a67a20f9ea7f80515fc99686ea3e9dd21f74e4d7734f9e4dcccec8\",\n        \"size\": 163373219\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3191_Weather13.tar.gz\": {\n        \"sha256\": \"343081f07da3ae7cc98e5afa9a04b768da54aff803b6a9aa058b6cafef062947\",\n        \"size\": 94673296\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3192_Weather14.tar.gz\": {\n        \"sha256\": \"7a0ff993f3465bc67443dceab7a8d3f1461bc4c3b7df35a4a019de5313beec1e\",\n        \"size\": 156426647\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3193_Weather15.tar.gz\": {\n        \"sha256\": \"3da41478d0a26b81075646228481ff8e853d006c9c43517ab8e5a6ea0968a0e0\",\n        \"size\": 141688812\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3194_Weather8.tar.gz\": {\n        \"sha256\": \"5c13503dea7f33d38f400aaaed179708ea778f04db72706925a3ae7d6dfcd798\",\n        \"size\": 175132433\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3196_Weather18.tar.gz\": {\n        \"sha256\": \"54c5b66d6f2646507fb3bfe9c222bd644d3695e0bb054e8bdb45ef98c41901ed\",\n        \"size\": 190159883\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3197_Weather19.tar.gz\": {\n        \"sha256\": \"320d2ce816767cfd12378a1b3daeda1c40c1019bec83e463fe078851c4416ecf\",\n        \"size\": 136103805\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3198_Weather20.tar.gz\": {\n        \"sha256\": \"4ca81f88f0ca547d6f6366135c6b7280f6a48fd010f3d9e9eb2813e9d2b9f85e\",\n        \"size\": 181680875\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3199_Weather21.tar.gz\": {\n        \"sha256\": \"e60a805414a03d3b164af967025ff8d72a792adcae5e263ef7b2ce92c19d6fd3\",\n        \"size\": 212993116\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3200_Weather22.tar.gz\": {\n        \"sha256\": \"53118578675853b6e7ccf698e1f7932540dd85e6283163b53657a8da44a0b34e\",\n        \"size\": 149077086\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route3202_Weather23.tar.gz\": {\n        \"sha256\": \"52e8deb45f7dab8b64487bc2d001ba107beccc4097913838b54d2ff6ec0064f7\",\n        \"size\": 106081525\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3903_Weather23.tar.gz\": {\n        \"sha256\": \"f29f75aa0c45fe23264463cf955263eb79b2d86d77d104cd6a8dd265e21d322d\",\n        \"size\": 121927737\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3904_Weather25.tar.gz\": {\n        \"sha256\": \"728ba729692a726d38e8095550679b3f1476d4b2c6ec2cf93f265567965f8e79\",\n        \"size\": 136385878\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3905_Weather0.tar.gz\": {\n        \"sha256\": \"49694d26cbb170f723c28640393472707e4dd3db0a105e17edfcb2c773904562\",\n        \"size\": 108118237\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3906_Weather1.tar.gz\": {\n        \"sha256\": \"1deb2175f4c22d9a383fa10088bfa9c8ce3334f3f64cc9e17a6d8c225b342b88\",\n        \"size\": 234681642\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3907_Weather2.tar.gz\": {\n        \"sha256\": \"3de01c8a4e022b138dafed13e93cc0cb649600bfb702c9a7d2d91123f872fb44\",\n        \"size\": 126498932\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3908_Weather3.tar.gz\": {\n        \"sha256\": \"6976af2ef8233a7785c29d9a4949f7b9347f91cc44431a667095168b72bc4c66\",\n        \"size\": 153020057\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3909_Weather3.tar.gz\": {\n        \"sha256\": \"b757e0d48e633719892f232b2051c09c21618288b970bd100c8c099711483855\",\n        \"size\": 138888923\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3910_Weather5.tar.gz\": {\n        \"sha256\": \"d2248cb107c3a7018195737d52bc98853ebac578a4da35c1ee6492741bde5874\",\n        \"size\": 115176921\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3911_Weather6.tar.gz\": {\n        \"sha256\": \"488f820f8006204b2726d4e8f38448a9836862a6f5227a2233cfdec02b8ca140\",\n        \"size\": 148734610\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3913_Weather8.tar.gz\": {\n        \"sha256\": \"bdb38ff4f4885b734e9a027e022e44483005ef51459be0640a33152f65e88689\",\n        \"size\": 161445617\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3914_Weather9.tar.gz\": {\n        \"sha256\": \"7e83d408ccfdc4ba37bc9a6bb36990a2c0f7f9b03730365488d27430b3002c12\",\n        \"size\": 139539288\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3915_Weather10.tar.gz\": {\n        \"sha256\": \"ba0f15bfddc6ddf448cf67986dc7c1c7074b27e56f4ec1cd1cee6c592a37b15e\",\n        \"size\": 92519199\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3916_Weather11.tar.gz\": {\n        \"sha256\": \"ca47a1586128f55e9c151603e59afbfc30fc5b0964381d9d656503d866378953\",\n        \"size\": 77044587\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3918_Weather13.tar.gz\": {\n        \"sha256\": \"673a0260c73300bf0c168698c7bb2a7898c5389cd45e53a0fde95eb05fdd7e7d\",\n        \"size\": 121692754\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3919_Weather14.tar.gz\": {\n        \"sha256\": \"53c7bccd203820c479925369b2f5309b1ae5546aebb050a6375bb7e6a8add717\",\n        \"size\": 176949586\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3920_Weather15.tar.gz\": {\n        \"sha256\": \"a5bf5b9378235f92e3efeadf7ca642cea8d95b6d17998b45a9a7009ed8c090f5\",\n        \"size\": 122881398\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3921_Weather8.tar.gz\": {\n        \"sha256\": \"6342995da7f4cf3e622efa5a77d3c1a422e9c50cad342acfac44f1e7d20baf94\",\n        \"size\": 102483772\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town13_Route3922_Weather9.tar.gz\": {\n        \"sha256\": \"2e6f614cf6e2cd2d34d5422a68e038d17af1746b9d0f209a006cd1df8896336d\",\n        \"size\": 81783853\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16482_Weather1.tar.gz\": {\n        \"sha256\": \"7b838554998189013114545b6f2580578dc6bc8573090e1086b35c7cb7429909\",\n        \"size\": 182997866\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16502_Weather21.tar.gz\": {\n        \"sha256\": \"3b47f664d0f0565e09b4e5e76005905b8a70e152504dccce3007ca76e90f5352\",\n        \"size\": 271512945\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16508_Weather1.tar.gz\": {\n        \"sha256\": \"386325b156cc35104bfe2d5cdb053eb3b1b19e5d7b2bdcfc64b9cb0d11b18718\",\n        \"size\": 77227180\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16521_Weather14.tar.gz\": {\n        \"sha256\": \"885054366864f120adaa831fd4c31d7f9282a475293b4a51e47f99f058c59236\",\n        \"size\": 95695300\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16525_Weather18.tar.gz\": {\n        \"sha256\": \"ed8be01619352e4018de9c7161e490a93cc67a8901a0f8d70274f9eb3693afab\",\n        \"size\": 113025321\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2384_Weather12.tar.gz\": {\n        \"sha256\": \"1d842c77c1bd1763d7a9ee9f40f9e674526eaad9d762146af0679b89426bab26\",\n        \"size\": 171583207\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2385_Weather13.tar.gz\": {\n        \"sha256\": \"af502dec3a173c480df8ab9e2c21019f264b08706299cb439db00cb4b34987d7\",\n        \"size\": 96471699\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2386_Weather14.tar.gz\": {\n        \"sha256\": \"62a285b8d7e1289fe09a2563566506e7d82237c1728148946c7f5419beabfb3d\",\n        \"size\": 96467055\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2390_Weather18.tar.gz\": {\n        \"sha256\": \"13e0f6403cc4dbc3b35696747bb3d3d9ec0192ce2b5f9c372a155efbda8f6d9e\",\n        \"size\": 123836949\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2392_Weather20.tar.gz\": {\n        \"sha256\": \"79be8d20452ee8cf7ee78240f1a3a659a6faccc0040305f31175b6b449925af9\",\n        \"size\": 112771929\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2393_Weather21.tar.gz\": {\n        \"sha256\": \"f42446734339a95ba279cf4d026d24d08b8308761c543ce7a6ff929fed971318\",\n        \"size\": 147521511\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2395_Weather23.tar.gz\": {\n        \"sha256\": \"8432be5a08af6a7e5f662c551adc52a03cd95b6f7976d2c8cfab5d52abc6c264\",\n        \"size\": 97733579\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2396_Weather23.tar.gz\": {\n        \"sha256\": \"ce6d6f37e2c1ef9e23aa9d9197cd5d5e5d6f208b103c635b33e942bed8485359\",\n        \"size\": 108614355\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2397_Weather25.tar.gz\": {\n        \"sha256\": \"7a53a426db6fe4784e7b4fc88cd39eb7a77b29aaa44693c305769ec2107d7abc\",\n        \"size\": 165322917\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2398_Weather0.tar.gz\": {\n        \"sha256\": \"324a873d710183ad605e94125a3bc9618475de75d6a71266b430520e5f07ec00\",\n        \"size\": 129232615\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2401_Weather3.tar.gz\": {\n        \"sha256\": \"123c1c2d2aca44cb7708267c16ee016f0b02fd1a45e82093e84f0d01e7755e41\",\n        \"size\": 114470894\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2402_Weather3.tar.gz\": {\n        \"sha256\": \"3fe7eda54c29b6fab6da1d3729b1eec936051adae0159d9327f7a4dcd75d113a\",\n        \"size\": 207211076\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route2403_Weather5.tar.gz\": {\n        \"sha256\": \"64194104d939df087f3a0046f134eadb06d1646135101eb311a1de96c010e8c2\",\n        \"size\": 228368621\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3164_Weather12.tar.gz\": {\n        \"sha256\": \"56184663bec7f5f8675f587b2755d6663ce04e41e5523231d98f3d412bd9310a\",\n        \"size\": 119797077\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3165_Weather13.tar.gz\": {\n        \"sha256\": \"444573c5fdc196ab9d6d8aa1cc9b74fac20d2297c1aa4402d73193d1e880cfa9\",\n        \"size\": 195040366\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3166_Weather14.tar.gz\": {\n        \"sha256\": \"97011009e3d71cf9cc02c82cace802ac74fa2c5f9caf5f58ad7340b789a8a21a\",\n        \"size\": 123953831\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3167_Weather15.tar.gz\": {\n        \"sha256\": \"a18d513edab8a9a7d72620a2e9779b4484304c6eaec5e1d720ceca1730389944\",\n        \"size\": 122132613\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3171_Weather19.tar.gz\": {\n        \"sha256\": \"eb421acedb94c1c7a0ad2b40cbe9a6afbcda5cf904663005d8fc8cb1eec6a569\",\n        \"size\": 98399546\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3172_Weather20.tar.gz\": {\n        \"sha256\": \"db8fb6520271b61e7ea128663a7ac3fee20cf5140bace5176e16cc536bb7e3e8\",\n        \"size\": 100362699\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3173_Weather21.tar.gz\": {\n        \"sha256\": \"9ed642e41ce4073100353f211e656ec0a3e7271ec79ded783f1dddcbaac0183f\",\n        \"size\": 107544779\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3174_Weather22.tar.gz\": {\n        \"sha256\": \"12d6ab478278a16567507675234603df2b8d5b602898cc8e01a47ba1a4cb1544\",\n        \"size\": 115590040\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3176_Weather23.tar.gz\": {\n        \"sha256\": \"b492abaf641e5a20786151c8c0e83a1bbbbac90848c26075b41024d82b7df1ba\",\n        \"size\": 89848989\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3177_Weather25.tar.gz\": {\n        \"sha256\": \"2b1f5c6b2bfc6c6448f1579ed266da99be1dccaedc73630fe2ccc663bc09b3c7\",\n        \"size\": 131723952\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3178_Weather0.tar.gz\": {\n        \"sha256\": \"afce811af5f8b1d4b87ad626b1d3adad62a41866a8e6f43013469490612af70c\",\n        \"size\": 116925457\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3179_Weather1.tar.gz\": {\n        \"sha256\": \"f4e9d83676d9ae3e2c6f718cd538e9ef9d64b101ffac9b4d81d21bccb6225a15\",\n        \"size\": 145241324\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3180_Weather2.tar.gz\": {\n        \"sha256\": \"06bfa6dc34745f212f32d96d473b5d745e4198efc546b5bea8cd4889dbe1be30\",\n        \"size\": 136289816\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3181_Weather3.tar.gz\": {\n        \"sha256\": \"8508868fa4265b8046b1e4a9ed6f3995493670eccf9af2ee39ff49c1c7916768\",\n        \"size\": 117166425\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route3183_Weather5.tar.gz\": {\n        \"sha256\": \"473d025e138f296ca80ece68939f961cb98c7a3ebca6574f1a967c80715f1081\",\n        \"size\": 179169131\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3883_Weather3.tar.gz\": {\n        \"sha256\": \"0df4b91b7f49b78ca61f4e36557cbf3d6ac107e5109b86ede87b5007b0f14bd4\",\n        \"size\": 142733089\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3884_Weather5.tar.gz\": {\n        \"sha256\": \"f03b243aa2a6ff08def939dfa40684a072fc78f5d767c82bc8ab941e76e6306b\",\n        \"size\": 213658098\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3885_Weather6.tar.gz\": {\n        \"sha256\": \"af57c34fe65ed3a7bbecd6f8f87ab6c95f8d19f380ce82045c54c98c73041e2e\",\n        \"size\": 136034389\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3886_Weather7.tar.gz\": {\n        \"sha256\": \"aa2af3c8436d286e0554fc786f87d0b48169752e294cc042fd68c8869907a4eb\",\n        \"size\": 135688979\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3887_Weather8.tar.gz\": {\n        \"sha256\": \"a67ed871ac65cf53e3989b79984070e7f887c3517528e15c7c115e9d2aa18e52\",\n        \"size\": 78544991\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3888_Weather9.tar.gz\": {\n        \"sha256\": \"151b7cf46d5c09a001f08b73f54b431b5968a9aace6a039ba67634fa6de0a21d\",\n        \"size\": 455900115\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3889_Weather10.tar.gz\": {\n        \"sha256\": \"48c99136d54f8deb294c95e13658cf3030b55cbcdb2dff6abf2c9c38edab1b9c\",\n        \"size\": 145716993\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3890_Weather11.tar.gz\": {\n        \"sha256\": \"780624c3adb1cfc2b575ed7bf6f527b4550a378a65f7510f2a6712cd47677f07\",\n        \"size\": 118825757\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3893_Weather14.tar.gz\": {\n        \"sha256\": \"db2e647976b1dacdc160cdf4d8d080aa21c60c7ae973f2e392b76e9aad35a99d\",\n        \"size\": 77141861\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3894_Weather15.tar.gz\": {\n        \"sha256\": \"c65c47ee0f6e67a48d6e28a005baaf7e67addd04fc24e18512397570a753b8be\",\n        \"size\": 80193532\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3895_Weather8.tar.gz\": {\n        \"sha256\": \"07136214c8a3f353b15d7f9168969699f7c3f384c3c9ef98eaafe372518bbe28\",\n        \"size\": 104272862\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3896_Weather9.tar.gz\": {\n        \"sha256\": \"fe61791e1a683b04a8e5e752259453995e7f3bf8642ebc70ee1bc3e01b05feb9\",\n        \"size\": 120648089\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3897_Weather18.tar.gz\": {\n        \"sha256\": \"efb089e2921f9f33574c2642f976b190127f4cbcdd5f3b8e10c7db4ca9da0eb7\",\n        \"size\": 88967590\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3898_Weather19.tar.gz\": {\n        \"sha256\": \"6b025166feb2ae8c62f705deed6621c8fac8a8298b583b3794d6d554e8f0f392\",\n        \"size\": 91977309\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3900_Weather21.tar.gz\": {\n        \"sha256\": \"256a023a053f6290af6b638ee87000008dc5d2a040168df26ef7a0ddeda0cfa8\",\n        \"size\": 115247151\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3901_Weather22.tar.gz\": {\n        \"sha256\": \"319120b6d6c2ddda8c8aa223e2fc85d2690b174716042dcfa5bdd8f36640545f\",\n        \"size\": 110708589\n    },\n    \"VanillaNonSignalizedTurn_Town13_Route3902_Weather23.tar.gz\": {\n        \"sha256\": \"6eac941a28e848258cdabe7cf9b1c1926884e3cac234f26fcc2cc011266161e5\",\n        \"size\": 121793932\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25912_Weather14.tar.gz\": {\n        \"sha256\": \"78cb4684fd87bc8b473f1a07d711eba95c11cfde5d8704398ea4932d354dfc08\",\n        \"size\": 200204694\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25919_Weather23.tar.gz\": {\n        \"sha256\": \"b8d22cc444e5291c4899a4841309d22b893ed6611b187c9cb74d283440e667cd\",\n        \"size\": 646259711\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25926_Weather5.tar.gz\": {\n        \"sha256\": \"e6645ac947f254cf67af15dcb47953777a05a7fa73109bf53a2056b574e135ea\",\n        \"size\": 160063320\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25933_Weather12.tar.gz\": {\n        \"sha256\": \"1961b05309eceae56a22c11eac42bc412ae922b40af750dca7c5ddb0067d6e71\",\n        \"size\": 359885894\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25940_Weather21.tar.gz\": {\n        \"sha256\": \"999f77d861c36f71ff1823a99e52c487b2b4c10aa9c4585cd92ba4bbf6144777\",\n        \"size\": 114108942\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25954_Weather10.tar.gz\": {\n        \"sha256\": \"5dc3b2d7e979679ee21d9994db90c7d761e4eaf092e579465d6fa5639f1e3a69\",\n        \"size\": 183842991\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25961_Weather19.tar.gz\": {\n        \"sha256\": \"8e54506109cb926329c7e8e796cd01fab8472f6075cf468084c59cd0e4c93e6b\",\n        \"size\": 324727708\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25968_Weather0.tar.gz\": {\n        \"sha256\": \"dca8bfefa2cd4140d1c3940f146913ee0a17e67984bba076ae5fae957b5127d9\",\n        \"size\": 850496401\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25975_Weather8.tar.gz\": {\n        \"sha256\": \"e54804b8616b65f99a61d02c8465d5c9cd5e5fab1a36e06b67967313aca07c53\",\n        \"size\": 353970948\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town07_Route25982_Weather15.tar.gz\": {\n        \"sha256\": \"17132d278d0acbeb8801316db0bd8f6c0944fb435d61133a13b140ef6091d267\",\n        \"size\": 409054765\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town10HD_Route24820_Weather2.tar.gz\": {\n        \"sha256\": \"96df4e383a5bea2fa196f5e54183d5a45db984626ca1810f391b970d5e8287d8\",\n        \"size\": 405130843\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14458_Weather5.tar.gz\": {\n        \"sha256\": \"f877f45882a990683afb3ab4de64442b2aff6d477adeae98772ab49043a26d73\",\n        \"size\": 560150996\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14459_Weather6.tar.gz\": {\n        \"sha256\": \"51f14c30362b0fee7a3a299ca7ed03777d3852e9338b36b5f7bf9b83cb531197\",\n        \"size\": 278210561\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14461_Weather8.tar.gz\": {\n        \"sha256\": \"70e861a394931e7dfc56be2b1597c4e319b700afcfcfc0937ac31d6aa34abbc3\",\n        \"size\": 483799065\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14462_Weather9.tar.gz\": {\n        \"sha256\": \"ef835e0792f5118af3a49adf9009b214bde733e16cd5c6d8341cefeed83540e0\",\n        \"size\": 372180484\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14463_Weather10.tar.gz\": {\n        \"sha256\": \"65383eba099e39c47c42c299d89526d4c466cf98802169fb92cf7021ba45f9f7\",\n        \"size\": 89276906\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14464_Weather11.tar.gz\": {\n        \"sha256\": \"e3045d907c2938378e16fddaf845f6bd63f07217afa2c8185e040d8f82538e59\",\n        \"size\": 176954992\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14465_Weather12.tar.gz\": {\n        \"sha256\": \"d69abfe96efe8a846c3a193a9e848c7247c24b40341bab76b9594199e3dcd996\",\n        \"size\": 167944731\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14466_Weather13.tar.gz\": {\n        \"sha256\": \"d9b3532277bc03eeebb56aecc1f6d74242a79592178ac45ed2b2d6b377d7d31c\",\n        \"size\": 328052803\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14467_Weather14.tar.gz\": {\n        \"sha256\": \"5c6d303334f7988f3011a1c13a90bd0890d3817456a71c4dc0420e9240192096\",\n        \"size\": 334402044\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14468_Weather15.tar.gz\": {\n        \"sha256\": \"65ef0590d60c6831d787b019db68586858045452920afec527b6eeca469a23b0\",\n        \"size\": 450692800\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14469_Weather8.tar.gz\": {\n        \"sha256\": \"c37fd8b3c33f199b39659e6f3034d228709027f0b0344f4d56172e93c3119275\",\n        \"size\": 605463987\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14470_Weather9.tar.gz\": {\n        \"sha256\": \"2ce0d75cdf190c827384a89057f0989ec5be0995455d244b31d2c5c37de68232\",\n        \"size\": 85610833\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14471_Weather18.tar.gz\": {\n        \"sha256\": \"feecae3a83394f158affc0c9574883c976c929f6f7d1ec7b0ee608345ee7698f\",\n        \"size\": 237555716\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14472_Weather19.tar.gz\": {\n        \"sha256\": \"3cbd39819a38767696a7913c73087e5fde2bb1f4ccfb31da85f6d035e47da3eb\",\n        \"size\": 374735071\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14473_Weather20.tar.gz\": {\n        \"sha256\": \"2a432de66a86d500e24a98d110255bb8a3cda5f09fb016f03c73dca4262f3411\",\n        \"size\": 761068016\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14474_Weather21.tar.gz\": {\n        \"sha256\": \"399698ba54fd1284481c9981b4100d09906a799d7edb462c14b567eb4c4e64fc\",\n        \"size\": 207775686\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14475_Weather22.tar.gz\": {\n        \"sha256\": \"e2bd7206437561f0812a802e449d24023d9f0733d78470e64812e3f03e910744\",\n        \"size\": 354775154\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14477_Weather23.tar.gz\": {\n        \"sha256\": \"291d9132836870b69f180213ec6cf31bd24a721644f4f8cd8336f3cf51f6bd25\",\n        \"size\": 385527642\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14478_Weather25.tar.gz\": {\n        \"sha256\": \"323e87d37b4e8e4028b2dd545169a2cf6f5457ec35a614a1f595bb33c3f5b672\",\n        \"size\": 195847449\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14479_Weather0.tar.gz\": {\n        \"sha256\": \"ffc7598403c9af8a670337cb420d49105a29b6d477affff709170d24cd8aab83\",\n        \"size\": 90342550\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14480_Weather1.tar.gz\": {\n        \"sha256\": \"7cdcfde472998845ab690ca2f2cc49531a8de1663f2e63b3e76bbe0c5bd8a3cf\",\n        \"size\": 196538683\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14481_Weather2.tar.gz\": {\n        \"sha256\": \"2b192cb0bede1691483498c913d451be269c42152f7e764e4de568813d675a45\",\n        \"size\": 290208160\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14482_Weather3.tar.gz\": {\n        \"sha256\": \"a1180ee7edd38168efc3656e82b37b039bde9a2f78df83ab4cf80d31328f13ce\",\n        \"size\": 169711317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14483_Weather3.tar.gz\": {\n        \"sha256\": \"466ca0cc3709c9ec9abf6a0c9dd366e7bfbc2b2effa7c4fc6be2015fedfae921\",\n        \"size\": 338598865\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14484_Weather5.tar.gz\": {\n        \"sha256\": \"af25c42ea49b9515353a6f3992509bbc7598f5d811cef37d6d82345581ebd558\",\n        \"size\": 310311687\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14485_Weather6.tar.gz\": {\n        \"sha256\": \"acfbddd82fea365067d5a16a0547a60350bb35ac3d8ef04ae0789203723d8854\",\n        \"size\": 124492432\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14486_Weather7.tar.gz\": {\n        \"sha256\": \"b9552a5b5ad6ffd73c11fc137ddb500b6ad8ac930c8057c7996d4d1c8334ce8e\",\n        \"size\": 216140703\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14487_Weather8.tar.gz\": {\n        \"sha256\": \"0af861d1a512379aee1ac90a6f55e13d792fb4af54d9f6b886f2d00f6c1fa020\",\n        \"size\": 283118940\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14488_Weather9.tar.gz\": {\n        \"sha256\": \"816c7c9fea61640ebddd490a23be93ae585c7bd5fbd94b8a92eca64508b3e856\",\n        \"size\": 110021858\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14489_Weather10.tar.gz\": {\n        \"sha256\": \"a15e2872341ce9533904e684b7262536c27b6a0d612485d8af477267ecd0674d\",\n        \"size\": 211455207\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14490_Weather11.tar.gz\": {\n        \"sha256\": \"8b31452e15f070a18b6b87d0d3ffd41907c5ade383aadc6fa27cac3f92225b53\",\n        \"size\": 463185182\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14491_Weather12.tar.gz\": {\n        \"sha256\": \"9530be19aceb1e9ec822d8bc1154bbd5e92427218334ff8fe1ca0be445bafb03\",\n        \"size\": 162626147\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14492_Weather13.tar.gz\": {\n        \"sha256\": \"899125f378e30ca7770d1ec700ce7321f59510f558d6bc79c0430c0334ce9559\",\n        \"size\": 263978995\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14493_Weather14.tar.gz\": {\n        \"sha256\": \"dffeb51f645813d6ec949d6a36caf96c35c1e888a6f8ff296813602d8028c313\",\n        \"size\": 456756687\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14494_Weather15.tar.gz\": {\n        \"sha256\": \"4d081f1d4d1b19740496157aa6f919a0ba140116bfa7a206700709b4143be13a\",\n        \"size\": 303078871\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14495_Weather8.tar.gz\": {\n        \"sha256\": \"f7bf274d2779756316fdfc55902d1f387a2f7b0772166201f5fab473cdfeb5a5\",\n        \"size\": 745522268\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14496_Weather9.tar.gz\": {\n        \"sha256\": \"3f259b9a17b9912f5672dc730d25fb7277c47b70e37975c75b6b2069aad2c90e\",\n        \"size\": 200860079\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14497_Weather18.tar.gz\": {\n        \"sha256\": \"18fa2f4996e57afb6488e353692cfd88bef70b0f1ca2e83f1117a2d8b4fe1b8f\",\n        \"size\": 70302544\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14498_Weather19.tar.gz\": {\n        \"sha256\": \"a148d3000434f2cfa1214f8f4a1593b9bbc44ed1010d99a0ec09ed07b968e205\",\n        \"size\": 645098894\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14499_Weather20.tar.gz\": {\n        \"sha256\": \"c91e704bd17920612ed0f3d4851c3524350a77e3f673952fb862f34eba17f5a8\",\n        \"size\": 695960508\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14500_Weather21.tar.gz\": {\n        \"sha256\": \"c8e85fa3b795c93127c25c543b21c5d475578064b0ff5acc6901f0314698609e\",\n        \"size\": 84960833\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14501_Weather22.tar.gz\": {\n        \"sha256\": \"f4a40c85948cd657814e26aa916a060dcc855a79fed194b61f4862bb33d30318\",\n        \"size\": 472626165\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14502_Weather23.tar.gz\": {\n        \"sha256\": \"ebe5ff78c665acbd1d3f38139c6ca38537ef6cf9ae0dfa9220df0b12c3fdf401\",\n        \"size\": 526906795\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14503_Weather23.tar.gz\": {\n        \"sha256\": \"5370bc85ee9a13ec825148d156a9d12410ed557231908b11bfee81d36e10e343\",\n        \"size\": 181335737\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14504_Weather25.tar.gz\": {\n        \"sha256\": \"242c25745e4abe422a2a876b368ea67c20ea6188bc1f1e1d7ed282aaba5beb43\",\n        \"size\": 267461915\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14505_Weather0.tar.gz\": {\n        \"sha256\": \"09e48b738cf82e876a61945080701fe8d3b1db48a8c113fb1629686c712419ab\",\n        \"size\": 648322382\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14506_Weather1.tar.gz\": {\n        \"sha256\": \"59b82367f08cec0d8c954cec45e98a0b68f1db927c65728bce9745621b2b584d\",\n        \"size\": 86100266\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14507_Weather2.tar.gz\": {\n        \"sha256\": \"24436dc053ceb52644b1d877188865be880b6d542872741848170771b66702ef\",\n        \"size\": 214598544\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14508_Weather3.tar.gz\": {\n        \"sha256\": \"9ad3fad4bacd162c41fe37b12fe5182555824952ce1262fa2b0985488c8b3e79\",\n        \"size\": 85982773\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14509_Weather3.tar.gz\": {\n        \"sha256\": \"126758eec430c1712c3f354327fb00b2089cda48cadeef6056945b3eff612f9d\",\n        \"size\": 115025234\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14510_Weather5.tar.gz\": {\n        \"sha256\": \"090f5a9eadb3e1eee46d986e6c3ba69a6478e06483d6e3a7e61a464178e2768e\",\n        \"size\": 168046484\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14511_Weather6.tar.gz\": {\n        \"sha256\": \"d3c684a703c3f416120a786502dbfa2676f2cad9bdf3b7db96304685e64ab6f6\",\n        \"size\": 66924288\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14512_Weather7.tar.gz\": {\n        \"sha256\": \"06309f18f594d87c0051d65ebb11bca948bb7df9cd5db4bcc19eebb82a4b7468\",\n        \"size\": 218921314\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14513_Weather8.tar.gz\": {\n        \"sha256\": \"cadcf385e08d6d83127f95f75c66ab96614adbfcc4f8f60186768f85e5979ba7\",\n        \"size\": 93587145\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14514_Weather9.tar.gz\": {\n        \"sha256\": \"275450cb25f33e969cfa747ff3d4d28a6b10debe8e0e3405c51c3c05f72ba599\",\n        \"size\": 290903152\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14515_Weather10.tar.gz\": {\n        \"sha256\": \"251275fe9fa4377641de46b32e7b1e13ed1daff463e41906a530b5a810cdb85d\",\n        \"size\": 441121306\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14516_Weather11.tar.gz\": {\n        \"sha256\": \"a1b28b94ec44153bee1efe34a7ebac6ae828f44fe2742b3bd2d543f2d9fccd0a\",\n        \"size\": 85017701\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14517_Weather12.tar.gz\": {\n        \"sha256\": \"bd9fd7f9a531ae7feb53ce84ecec779b925e2b31e27fa1c758987fb90daf8a2a\",\n        \"size\": 534645153\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14518_Weather13.tar.gz\": {\n        \"sha256\": \"222dbd7b7278d78dc925974ea22bbfe4bd571d1d9b3139c23c428c95c3f03c5f\",\n        \"size\": 543518804\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14519_Weather14.tar.gz\": {\n        \"sha256\": \"d5be81dedc71bc9c25b6f84c7febf4f1391ae4f1d6c963a078a438e0132c9061\",\n        \"size\": 68390892\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14520_Weather15.tar.gz\": {\n        \"sha256\": \"e7a4b235cfc1d0cd29292519e8db378585c520f8861bf7afafdd7a6a96ae3ddc\",\n        \"size\": 215325553\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14521_Weather8.tar.gz\": {\n        \"sha256\": \"09c4d3d5e499573a4e4eba8754e8b3b761da6a90f265ecfa9ba033b1cb9730a2\",\n        \"size\": 636223912\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14522_Weather9.tar.gz\": {\n        \"sha256\": \"e2f622d26e3e12d7118755eb5d0f8220c910904d8bc51cbff32457848912474f\",\n        \"size\": 382931472\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14523_Weather18.tar.gz\": {\n        \"sha256\": \"9d77926c3821ee4a04efd07abfc15f8a285ad3eaa5ad04b75f9755443fa5e5bb\",\n        \"size\": 213485995\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14524_Weather19.tar.gz\": {\n        \"sha256\": \"79945a2d1a3424c239b69c096709278cd19a299446782a8e2f0698c7078a572d\",\n        \"size\": 96928081\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14525_Weather20.tar.gz\": {\n        \"sha256\": \"23ea97fb6336f7f0537edaf98a6694b9e5cfc0fad8aff0a036f18fcc10472342\",\n        \"size\": 549274205\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14526_Weather21.tar.gz\": {\n        \"sha256\": \"e8cccf2ee8295521c03143fa1c77adbc851fb6c5b72967ee56de856c87e3704a\",\n        \"size\": 415491843\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14527_Weather22.tar.gz\": {\n        \"sha256\": \"90b620acf34e71491e9706479467007fa8e5d4a596f9ee17cd9a794fa44bdf49\",\n        \"size\": 317564394\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14528_Weather23.tar.gz\": {\n        \"sha256\": \"edac7ad2afd79aa24442cf4884f573956ba11b859a2e84bc34bb1a4e34ff5ac2\",\n        \"size\": 273690190\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14529_Weather23.tar.gz\": {\n        \"sha256\": \"f1f515ed2ec72faae1a0799195c72168bb88eb02bb83f8c199e347c9010c0ff2\",\n        \"size\": 576490147\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14530_Weather25.tar.gz\": {\n        \"sha256\": \"f37a300c4d2df98bc7ea71079003a7d3344bacd46173ca8bc1b100fd86358b8f\",\n        \"size\": 201453893\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14531_Weather0.tar.gz\": {\n        \"sha256\": \"ebefe88ffa71140a3e95ddf44007e4aab33444382395363df1d1c9f206ca940e\",\n        \"size\": 79958941\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14532_Weather1.tar.gz\": {\n        \"sha256\": \"3645535726d3c8b42f58c54e6019d9c8d1724e6081e9c2c6a2cfef3fbb97eb64\",\n        \"size\": 493971029\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14533_Weather2.tar.gz\": {\n        \"sha256\": \"6527e2b110ba3a806747bb764aeb0c316415527e22aefb3733d83703135f6bb6\",\n        \"size\": 454422597\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14534_Weather3.tar.gz\": {\n        \"sha256\": \"30d67119e30a5670942f5f2af9fc800d71f58322782f955232532f327298f862\",\n        \"size\": 114591138\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14535_Weather3.tar.gz\": {\n        \"sha256\": \"53d43ceabdb426ba4e509ee32e4ffe06d1159a0f12b47f62d1c60fa7a732c2c2\",\n        \"size\": 405197830\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14536_Weather5.tar.gz\": {\n        \"sha256\": \"5cdd626e8c75536c03e6127db547e20a1db4d217684c3ab48186571da7c38ceb\",\n        \"size\": 507430722\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14537_Weather6.tar.gz\": {\n        \"sha256\": \"9180dc727af67a7fd66638eae7b1f570b522c5f9b9eab2ea97c6e0c4a25b4113\",\n        \"size\": 362963973\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14538_Weather7.tar.gz\": {\n        \"sha256\": \"a2cbf0b002da0ee1f173cc81eb51747608b25dd8c89c02fded90879549259bf0\",\n        \"size\": 105999821\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14539_Weather8.tar.gz\": {\n        \"sha256\": \"9d6a1c2e5ef1e998d82884567c62bf6469ac66ab9568e620b9a6592347dcf1f8\",\n        \"size\": 319981600\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14540_Weather9.tar.gz\": {\n        \"sha256\": \"af7c5d57e137b7c9d1d7d760651928f1b49ff134ffcecb6de456f0c363709230\",\n        \"size\": 250917323\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14541_Weather10.tar.gz\": {\n        \"sha256\": \"33491476c70c2d270977079990e2c0f301ca40c774f11181d512c642bfcf8098\",\n        \"size\": 551276244\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14542_Weather11.tar.gz\": {\n        \"sha256\": \"4b07a1f5c0946c553b72382b12d40767605dbc54bba2dca994a9ee6c9f496549\",\n        \"size\": 56433868\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14543_Weather12.tar.gz\": {\n        \"sha256\": \"d7f8b56fbde4101f1cb603eda982bf0b80c2e89d4548da283c48d2ebf1fc43a4\",\n        \"size\": 364525640\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14544_Weather13.tar.gz\": {\n        \"sha256\": \"abb018d5b1ecee11eb20358a28454424186dd21c4ff67334bba270b8de43ccd4\",\n        \"size\": 303847880\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14545_Weather14.tar.gz\": {\n        \"sha256\": \"53dce3247c7dd6116e6bf6ead1f6b2a80d90d240f8507f671272e09d8045b166\",\n        \"size\": 320068374\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14546_Weather15.tar.gz\": {\n        \"sha256\": \"3f7f6e4f231954e8b00c1f2bbdcffb103849f3c4e979c361649b5d3ae6b85eff\",\n        \"size\": 178058110\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14547_Weather8.tar.gz\": {\n        \"sha256\": \"baa253b82d7e0d146ac9ded7aa7c522aa349fdbe5401dab4d76f39c0d9402474\",\n        \"size\": 111542184\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14548_Weather9.tar.gz\": {\n        \"sha256\": \"a14b23159d36538784b2f78925d01c251750e1ea1e504162ebee833623d8f785\",\n        \"size\": 64991214\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14549_Weather18.tar.gz\": {\n        \"sha256\": \"d28bccaab1a24f7529935f6308c4dbbc68b532acebdd6af9d337d79287c86a87\",\n        \"size\": 82841076\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14550_Weather19.tar.gz\": {\n        \"sha256\": \"2625b06b1f31a06b1932c344f8ab6145bb51a201ff7b8769dbe39bc8eb762e83\",\n        \"size\": 362050521\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14551_Weather20.tar.gz\": {\n        \"sha256\": \"835b257f1861c92f00899a741080237b175c44e885cf64aab559f3b69b2a0718\",\n        \"size\": 554974581\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14552_Weather21.tar.gz\": {\n        \"sha256\": \"939170561434e8d12ee082907507f549db5642026698584171be8b05951408df\",\n        \"size\": 560775683\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14553_Weather22.tar.gz\": {\n        \"sha256\": \"749242819ff67cacf3f2e6e6e31dcdbc0f62ae37727f465f03f86c595aca2942\",\n        \"size\": 414911018\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14554_Weather23.tar.gz\": {\n        \"sha256\": \"cb1054ba7448cf39ae037c78baf55b95752f23414af01a575d101dc1f8ac3c64\",\n        \"size\": 191116881\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14555_Weather23.tar.gz\": {\n        \"sha256\": \"354f46274c8859a975b92199399373eebde7d1c930c48340ff34e0b61f01d1a6\",\n        \"size\": 852770162\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14556_Weather25.tar.gz\": {\n        \"sha256\": \"881729c01edb38d148a38e9b96ed6f3760356c2fc843eef54814a498a8ca678b\",\n        \"size\": 503841287\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14558_Weather1.tar.gz\": {\n        \"sha256\": \"4b3a344aa51dd210c8d59a8f7218297aa4ee1163bbe5c70e5f08c0de38a333ca\",\n        \"size\": 174209480\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14559_Weather2.tar.gz\": {\n        \"sha256\": \"4492c529f0921e62e3b19594a6b39ba860013b191200b87d67ac599f03d6b7a7\",\n        \"size\": 257994706\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14560_Weather3.tar.gz\": {\n        \"sha256\": \"216743a19b6d4ac34159c15a0f332fb328a295fbc7bae1c9f7b13001ebabe46f\",\n        \"size\": 1097211228\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14561_Weather3.tar.gz\": {\n        \"sha256\": \"ed770fd946baa8dcbdcbe32d5ec99eff25859f58994966dc0c96dd3049152bf3\",\n        \"size\": 90150570\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14562_Weather5.tar.gz\": {\n        \"sha256\": \"57bd8758a5fb076960f91884fff75ced0cbaf89f5b7caeb44a78e2d28d7eec7e\",\n        \"size\": 350144684\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14563_Weather6.tar.gz\": {\n        \"sha256\": \"f39c2c620a710725b963ec186786398616fdc267379831d413370499ba1759ca\",\n        \"size\": 97120510\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14565_Weather8.tar.gz\": {\n        \"sha256\": \"da07dfb16d5c01ff49a29dcca59b8a707eae270d8ff09fa0ab61a6a3ffeaa9eb\",\n        \"size\": 94917997\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14566_Weather9.tar.gz\": {\n        \"sha256\": \"84bf1a3348ab656192a02a35b0defebc03ba6c826d7f5ab71f6a36ba7c20691a\",\n        \"size\": 491521519\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14567_Weather10.tar.gz\": {\n        \"sha256\": \"917cd33527b86cd3a29f7a0d5c13a1769585b29cde3491e3b11f124500051e05\",\n        \"size\": 291370871\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14568_Weather11.tar.gz\": {\n        \"sha256\": \"629c9524caa6d775f90604a61d440c26e5ec7feb2c1ebbe2ea0c8ea237e71cd6\",\n        \"size\": 95550788\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14569_Weather12.tar.gz\": {\n        \"sha256\": \"1709c690a58351afb48f62a630fa9bfb10f076d8cfd502edafb0d47ce0d2a401\",\n        \"size\": 449715654\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14570_Weather13.tar.gz\": {\n        \"sha256\": \"de2644f16ad95336cde89d7c02c004d9e6bec6b32ee6bb658fc37aac3dd5cfa0\",\n        \"size\": 214911325\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14571_Weather14.tar.gz\": {\n        \"sha256\": \"983692dc969fbf4ad7081460977ae516af7dc7dab2aa3d153dd3f9362858a5b6\",\n        \"size\": 100185747\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14572_Weather15.tar.gz\": {\n        \"sha256\": \"c0be00f65d7a690fdc5b50b9c5e9a8683eb4554bbe776b4da752347ef274e29f\",\n        \"size\": 694024770\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14573_Weather8.tar.gz\": {\n        \"sha256\": \"85398988874e9fdc331a55fb844774ec1c1257b142be659bf0b4eae9746ac86c\",\n        \"size\": 420710931\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14574_Weather9.tar.gz\": {\n        \"sha256\": \"68feea9b6d4188307c397bdc4dff31fb0b8b997d6905f947031afdc9f55ac2ea\",\n        \"size\": 313357202\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14575_Weather18.tar.gz\": {\n        \"sha256\": \"e944260da98f4181eb408711fa8da3388735c53ec538017c8ab7f43157cbe68e\",\n        \"size\": 363062317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14576_Weather19.tar.gz\": {\n        \"sha256\": \"d53278189051b217838ede6bb94146ce471bb5f205984d9ba9704a8986bdbb94\",\n        \"size\": 262215993\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14577_Weather20.tar.gz\": {\n        \"sha256\": \"86d17ebf619eb7571aa8bc73000c44c2e9a9a2028d36da5acd90c8151a668335\",\n        \"size\": 318419365\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14578_Weather21.tar.gz\": {\n        \"sha256\": \"aeded289c69f855b4db736b89587c90a658021f7b7420a440177af3dc6eb2a97\",\n        \"size\": 342041975\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14579_Weather22.tar.gz\": {\n        \"sha256\": \"1fa743679ef0769975512cb75704dd2eeca86f67ea3ff7cba6f51b33dab5c6ae\",\n        \"size\": 521330467\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14580_Weather23.tar.gz\": {\n        \"sha256\": \"e1797e74b9d9d0e8d46d946b8b3049a6751a873dee5a3ba714b52c9a1bc1e35a\",\n        \"size\": 603432298\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14581_Weather23.tar.gz\": {\n        \"sha256\": \"a1e8b0a457330df8e277d540b3f7ac8b59a9b02a1a9fd4e963aee82557b8e7a6\",\n        \"size\": 449843791\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14582_Weather25.tar.gz\": {\n        \"sha256\": \"624bbb9cf84ee3e9655683c65ff376ba5502ebd13631a40643bd7a432c7958e7\",\n        \"size\": 139578492\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14583_Weather0.tar.gz\": {\n        \"sha256\": \"28974b353c57660f70d1d31889ad34c37af85c7819ccc381a2d8366607ecb77c\",\n        \"size\": 865547266\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14584_Weather1.tar.gz\": {\n        \"sha256\": \"d601b298edf218d4eedce4cf0a4b7e849b1aa6b49f27dc1fbf3ea60d4086e173\",\n        \"size\": 780043311\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14585_Weather2.tar.gz\": {\n        \"sha256\": \"212f00e7645cfb127bf13924125930eeb58023127d3d88368398d90bcfa5c9b4\",\n        \"size\": 265025690\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14586_Weather3.tar.gz\": {\n        \"sha256\": \"2ea464767e8dd4ff74ed7c9f04e5237beec6f14b97a45c61927c01562446499f\",\n        \"size\": 114649298\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14587_Weather3.tar.gz\": {\n        \"sha256\": \"bb80400d9f81037fdc288bd6ee478ea55a7f6c1a4ca31f942df8e807aeea6077\",\n        \"size\": 76358368\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14588_Weather5.tar.gz\": {\n        \"sha256\": \"c97945858294c2089200ee72b69c78c19bfc87d8e7dd94b58eec2953657be77e\",\n        \"size\": 118711558\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14589_Weather6.tar.gz\": {\n        \"sha256\": \"a02a49ad91f9304ce8e81b3da148227f10ba963e47ae370bf17ad258718dd29b\",\n        \"size\": 212302326\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14590_Weather7.tar.gz\": {\n        \"sha256\": \"c47bc019145f10db51e0acb42e0786074167735f2d27ec83ea434291c0bef006\",\n        \"size\": 331007773\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14591_Weather8.tar.gz\": {\n        \"sha256\": \"178fee5bfe3582917672cf27cd187fa71c025ce2efadf7860adac02696b3cad4\",\n        \"size\": 86316152\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14592_Weather9.tar.gz\": {\n        \"sha256\": \"d64d858767c7cf1803c4f792d3caec232ec42b304e3ad5fe5ee0ab103a4aea81\",\n        \"size\": 153288598\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14593_Weather10.tar.gz\": {\n        \"sha256\": \"f7bbb02393329cf112698c13db03686253c7cf715e31982a5e5e94c6e34b7136\",\n        \"size\": 356506204\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14594_Weather11.tar.gz\": {\n        \"sha256\": \"6a718440aa54d64c73b1662b92f62767281e6ca74432cbbb342cd3ad31395a67\",\n        \"size\": 185410415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14596_Weather13.tar.gz\": {\n        \"sha256\": \"c27788386773468d30d74f3f7674a10d59e31e583596b34db46ed5bd332a5ac6\",\n        \"size\": 255386242\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14597_Weather14.tar.gz\": {\n        \"sha256\": \"b43caee498808d1713218502ea71d79fdda31a0e5da69ba50eb0132ab4d7656d\",\n        \"size\": 182494479\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14598_Weather15.tar.gz\": {\n        \"sha256\": \"1407202b5bda4e081b889c01241eb63a616965be704ca33d11ff1cecec092c59\",\n        \"size\": 195114331\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14599_Weather8.tar.gz\": {\n        \"sha256\": \"b8f14bf30e8cb6be16a63b25fff30ae409ae27834b504eeea51608e7558ea450\",\n        \"size\": 441295050\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14600_Weather9.tar.gz\": {\n        \"sha256\": \"77e3ec1382e27432ae42605e213f5a715a584e8dafb81386cad2a3255e05e1f1\",\n        \"size\": 177184829\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14601_Weather18.tar.gz\": {\n        \"sha256\": \"928b1b6b934c3dfa4f24b7e731078507e4a8eda7187dc75f7c73ce0f32d602d0\",\n        \"size\": 834229438\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14602_Weather19.tar.gz\": {\n        \"sha256\": \"f6d3eca2ba3736932588165fd5fed8d86931c8e6f83bf463aa3a87d11f4c79cc\",\n        \"size\": 106122250\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14603_Weather20.tar.gz\": {\n        \"sha256\": \"5b0beb80386dd7c67c86341a538c46e6d30fd52058fdf3c0eb4645591f90bb74\",\n        \"size\": 464579090\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14604_Weather21.tar.gz\": {\n        \"sha256\": \"81b66b7c77edc795980030a3142bc5cd4c652c22376d988f1c0abf7be2f82340\",\n        \"size\": 86469040\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14606_Weather23.tar.gz\": {\n        \"sha256\": \"1493c5e408d5da4322e43733d4dd9902775556de2dd1223e1167771f94a1f455\",\n        \"size\": 173913493\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14607_Weather23.tar.gz\": {\n        \"sha256\": \"78e1c04deadcbe3fbfca55717387f11bd05a54664f1db5a0131b4924cfb8377e\",\n        \"size\": 622829385\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14608_Weather25.tar.gz\": {\n        \"sha256\": \"55524a59ec60cdc4286aab1d9017111193d1e2965f440d8c3406ffe67310b7ed\",\n        \"size\": 378568206\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14609_Weather0.tar.gz\": {\n        \"sha256\": \"3897ed3684f2d5ca19c9b88a09a39eb7d07a993194aecb51ea9166bd60261cc5\",\n        \"size\": 474893084\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14610_Weather1.tar.gz\": {\n        \"sha256\": \"7285d307967cb7bcc75b3b2784aea59c65fc16e140f6ea6e26dd065c68d7bde4\",\n        \"size\": 353160564\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14611_Weather2.tar.gz\": {\n        \"sha256\": \"986a64873049290b3cd21af1a83e2d0659a157b1e15b4755ae71b72160cd7a1b\",\n        \"size\": 531333816\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14612_Weather3.tar.gz\": {\n        \"sha256\": \"1005e1b12cd3b1c4537750353a95cb8fdfcabb257c91ce67a0fffefe2634c065\",\n        \"size\": 219256505\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14613_Weather3.tar.gz\": {\n        \"sha256\": \"15d49b049783cdab3702044c24ad5757cd12b0f1d122c89091373dcf7d716c05\",\n        \"size\": 75743036\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14615_Weather6.tar.gz\": {\n        \"sha256\": \"7f1afaab6408eb87c43db9205bdbe396804e352263b80096eb4ec0974760a34a\",\n        \"size\": 234076055\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14616_Weather7.tar.gz\": {\n        \"sha256\": \"22e5216b5fad8c88a5062096382587e71669892ed38951b18f183e31303df7bb\",\n        \"size\": 471030496\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14617_Weather8.tar.gz\": {\n        \"sha256\": \"253f17189199982d23786ad3454c9cb7d0772eba91988d86d243274d26531953\",\n        \"size\": 946651569\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14618_Weather9.tar.gz\": {\n        \"sha256\": \"9b946c4b903d3b56b9fbfc82484c19a8de8271c6c8646f14bdbc978efc9a4128\",\n        \"size\": 515466700\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14619_Weather10.tar.gz\": {\n        \"sha256\": \"09aa2eda624658e262483aab2bfb458ad7c7a85d1c3908265d91b509443b32eb\",\n        \"size\": 87164059\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14620_Weather11.tar.gz\": {\n        \"sha256\": \"8f4b8a53fd68e23ffd23cfc8c4ba5b95919ead1800e9dc3230e31ca65ae44af9\",\n        \"size\": 69668389\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14621_Weather12.tar.gz\": {\n        \"sha256\": \"48d978d11c621172104cdb84fb2706b2a414b7c62873e07e715cba8606ecba0c\",\n        \"size\": 565759171\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14622_Weather13.tar.gz\": {\n        \"sha256\": \"3b63717ab61705b58b98efc956ff88bb41c815be2640a0b966432d60a440702d\",\n        \"size\": 164831086\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14623_Weather14.tar.gz\": {\n        \"sha256\": \"cb534d7f56991cb593a6273a1acb98b8ed215a76e530a53bdeeac67aed822672\",\n        \"size\": 219967505\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14624_Weather15.tar.gz\": {\n        \"sha256\": \"2aa14368f68a56e7bd91749d1dc99e31eeccab571cb79b7f708784afdea1fec0\",\n        \"size\": 116893860\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14625_Weather8.tar.gz\": {\n        \"sha256\": \"2d005ad134af3b4573ff7b460802ce806c01fb4d60b0258b36908e01d96efec7\",\n        \"size\": 298983014\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14626_Weather9.tar.gz\": {\n        \"sha256\": \"02852612b9654ea2d435c0872e0747cab854f987530dc855954659e13f03132e\",\n        \"size\": 434006216\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14627_Weather18.tar.gz\": {\n        \"sha256\": \"04e7c4ca01bb27065ea6ade2e4850c902f624c84621011308e0a5529e11a86e4\",\n        \"size\": 432237778\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14628_Weather19.tar.gz\": {\n        \"sha256\": \"a0f2eec829cde9b827036f6219303f361d000231b17159d68817e009c5710bfd\",\n        \"size\": 72115762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14629_Weather20.tar.gz\": {\n        \"sha256\": \"302f20b4d699b64b25830e89342c4c69cb03e7b0512d9983a506bc5f5768df1e\",\n        \"size\": 572753415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14630_Weather21.tar.gz\": {\n        \"sha256\": \"755508dd0f485cc22cd2724d9df6e98d39280e67c067964b0c5d2de079db4398\",\n        \"size\": 123653113\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14631_Weather22.tar.gz\": {\n        \"sha256\": \"c8aca6eddc4e7b150331df16ffe8bc9ec5ecbda9ffa076d195a34ad62d863c71\",\n        \"size\": 342074046\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14632_Weather23.tar.gz\": {\n        \"sha256\": \"a70b80c7bea2e35e953d593150e39c02fe6351a15d5c5d8adb56919a0aeab68c\",\n        \"size\": 193387529\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14633_Weather23.tar.gz\": {\n        \"sha256\": \"c36653d06516faa74bb5a80af8dc16e2a1fec8b19295c406629462a758a143fc\",\n        \"size\": 388055050\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14634_Weather25.tar.gz\": {\n        \"sha256\": \"b7ff36e89e9ee5ea57fe794066cbbef45a4bea6b7c38334cae894a13af695550\",\n        \"size\": 409927281\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14635_Weather0.tar.gz\": {\n        \"sha256\": \"2160bdc9d78daf8ad24c1617b7a8940125093eb65a6fcb3ab131c4bb7f1ac9d5\",\n        \"size\": 427480275\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14636_Weather1.tar.gz\": {\n        \"sha256\": \"230efca478de95100cb77975da362d3f97a99e71ca884bb2a972f9ae42961a82\",\n        \"size\": 357091084\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14637_Weather2.tar.gz\": {\n        \"sha256\": \"d63479b772aa137d9073fb11937c933ea1317c97aeb444723f1600a17a63fcbd\",\n        \"size\": 98591251\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14638_Weather3.tar.gz\": {\n        \"sha256\": \"b09a0d48803eae6dea01bdfc8536ef4fce66701dc7f96794615b7a166d49bcc6\",\n        \"size\": 643204781\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14639_Weather3.tar.gz\": {\n        \"sha256\": \"561e9c48f7a0b9981ab8e25ebfcc88ae04805acdc58078663bd5e6bfe1ef37ff\",\n        \"size\": 560857712\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14640_Weather5.tar.gz\": {\n        \"sha256\": \"77114e30a3ff99e4d461e6433810485deb4a96137aad4a9eb3e7c368080e5311\",\n        \"size\": 334299201\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14641_Weather6.tar.gz\": {\n        \"sha256\": \"9af55229b0cbe8f9e20f6fe706b7f791d5122f91ff64674cade83f181f14fea4\",\n        \"size\": 777974186\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14642_Weather7.tar.gz\": {\n        \"sha256\": \"ceff47e35f74d5e7b0ec4cfabf58cd48c069f75e146f40909e51a391f3a4be87\",\n        \"size\": 227426004\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14643_Weather8.tar.gz\": {\n        \"sha256\": \"2dd9594608a5111584e50ed23c021ac0ea13a86246db5204228f8680d95b992c\",\n        \"size\": 214221532\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14644_Weather9.tar.gz\": {\n        \"sha256\": \"7b3e43a4f474472db9f19a10fd20d0efbcb6c6f2c01f12eec191ed24fb0f4cef\",\n        \"size\": 66473602\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14645_Weather10.tar.gz\": {\n        \"sha256\": \"186e112cccbbef006110b3b7265f368e08832712f600f5866faeec17ebeb8115\",\n        \"size\": 562718718\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14646_Weather11.tar.gz\": {\n        \"sha256\": \"f8a47d6411b04e3adbd024af6307652cde648b2c02c8472f6c6ce1f78e74fa9c\",\n        \"size\": 372661457\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14647_Weather12.tar.gz\": {\n        \"sha256\": \"c39c0848c3fe461c4be19ee0748e37db0db38837b97604d07bbca9c118eeeeed\",\n        \"size\": 145847265\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14648_Weather13.tar.gz\": {\n        \"sha256\": \"0b86b8465643afd1b08e9f9f0de4e59d9e3b81522f21685d2c28adb56c66f0e9\",\n        \"size\": 300501762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14649_Weather14.tar.gz\": {\n        \"sha256\": \"dc0d587fa40133fbd4ef0752b2adad0598ca72432fe29ddefdc95af944dccaa1\",\n        \"size\": 165673469\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14650_Weather15.tar.gz\": {\n        \"sha256\": \"67f2cc5be39b51e50655bb61467ae917c98b9dbf03d4dbe0fa987ea686f46762\",\n        \"size\": 347457334\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14651_Weather8.tar.gz\": {\n        \"sha256\": \"35314495406f64c19d1f031127d558057f0dfdeadfaa81c9fc25071734e50a60\",\n        \"size\": 460459011\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14652_Weather9.tar.gz\": {\n        \"sha256\": \"2f26494b85f389c8016df2aa39188de22767925c0cbea02d1ef654f3364eb3e0\",\n        \"size\": 256169463\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14653_Weather18.tar.gz\": {\n        \"sha256\": \"a4678d89a317a0003236c2e380ca2e68c816a748d443786829d9acbab647e777\",\n        \"size\": 166659316\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14654_Weather19.tar.gz\": {\n        \"sha256\": \"0a7c95c34cc4f9077a3cbf38861b37baa3231969973cde9f46d38a6f6e7b1aa8\",\n        \"size\": 552665124\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14655_Weather20.tar.gz\": {\n        \"sha256\": \"35148ede3820cb0c590dae811775ffc36a08a74edf110a6b0d33499771f112a4\",\n        \"size\": 82372171\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14656_Weather21.tar.gz\": {\n        \"sha256\": \"7f7ce1a2877e67cda0f7f0525d5c247e0ecf4fb8c7de768b3755176a6738b2da\",\n        \"size\": 386614282\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14657_Weather22.tar.gz\": {\n        \"sha256\": \"434212b4b3b8d352c9a68f5a6514aebd1fbe24229c03e458bf9a364b14766bdb\",\n        \"size\": 65941420\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14658_Weather23.tar.gz\": {\n        \"sha256\": \"94c23e83c739403a1888e542624410474991ac60b527800109137599c9d0060f\",\n        \"size\": 160152672\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14659_Weather23.tar.gz\": {\n        \"sha256\": \"91df58fc5e70acfbd9fbf190e80d3d835f4a065c00bb9e85ee66e0648740a118\",\n        \"size\": 321513331\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14660_Weather25.tar.gz\": {\n        \"sha256\": \"d628d512cc80cb2e986ee0dda20a0ac1f96bb2a8593b023ee8b07e41761203c8\",\n        \"size\": 156713859\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14661_Weather0.tar.gz\": {\n        \"sha256\": \"9331382e0da3b8d453d8930a8d653bbe7cfea0030283df5e1956f64545253c39\",\n        \"size\": 77425090\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14662_Weather1.tar.gz\": {\n        \"sha256\": \"b5e72df31048612353d13c160c4cf471dc54fbdcbfc1137d01db5df7a8b59215\",\n        \"size\": 568972547\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14663_Weather2.tar.gz\": {\n        \"sha256\": \"fb114c142d5b6e3d5caaca941c478dbfacd01e9b2522232b5b0f6cc3931d5b44\",\n        \"size\": 755378916\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14664_Weather3.tar.gz\": {\n        \"sha256\": \"7de1931b52c565fca6335cc8869cb44c3f83f4abd138090c9899f7d9ed0bd274\",\n        \"size\": 117263502\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14665_Weather3.tar.gz\": {\n        \"sha256\": \"08f588c562547a0e34e3f520a808f7dd97d2ecc7ddaef35f8ca71d3aeb382a41\",\n        \"size\": 338635782\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14667_Weather6.tar.gz\": {\n        \"sha256\": \"3d2478c828f7f96680cab40595d145f019d9e05e4182a26c58dfd648c4dd6271\",\n        \"size\": 320154263\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14668_Weather7.tar.gz\": {\n        \"sha256\": \"26c2385f4bfa7c210ef9c1426d41e3c823843567fac306af18772e7df379cd5c\",\n        \"size\": 210666738\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14669_Weather8.tar.gz\": {\n        \"sha256\": \"f8e7c07dd52a3397d94ead378dedbc269b49aba8ccda5e6ba99bc1d3ac9a4642\",\n        \"size\": 524672599\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14670_Weather9.tar.gz\": {\n        \"sha256\": \"cc247da1b71b1d8dc3e23bc0aea780048852622b8b405a3698889b6bb21b1941\",\n        \"size\": 66601200\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14671_Weather10.tar.gz\": {\n        \"sha256\": \"63ebe3eb9dd7d2a8a49bfb658b146af640f918af3a6b17e2acd8f3d2d94df630\",\n        \"size\": 102349619\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14672_Weather11.tar.gz\": {\n        \"sha256\": \"9ebdb43aaeee98ba099c50b06bf7e59e54756a52ea2ba9da1b64748447ccf19a\",\n        \"size\": 79870355\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14673_Weather12.tar.gz\": {\n        \"sha256\": \"458faa19febf6c85a19ae15f2dd755409206e5fae7d7cf5ab76077070cef0582\",\n        \"size\": 528529941\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14674_Weather13.tar.gz\": {\n        \"sha256\": \"4a32d57fd1865f94db68c8f243410b42332c8b29a801795d33df81afe9093bc1\",\n        \"size\": 245361543\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14675_Weather14.tar.gz\": {\n        \"sha256\": \"1f703dc450b837c8b339b2a8f9ea9fe520768630be53ca94199865fb83a254a6\",\n        \"size\": 312933963\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14676_Weather15.tar.gz\": {\n        \"sha256\": \"1dec63203c32b0338b9eb5626b04cbbb9c26801b3793051fd96351495b9159ae\",\n        \"size\": 383607707\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14677_Weather8.tar.gz\": {\n        \"sha256\": \"d293aa163c538de88678eea664bc3ee3002d2a169340356c8e18613724abdbb3\",\n        \"size\": 193134731\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14678_Weather9.tar.gz\": {\n        \"sha256\": \"7707690fcf239bb9e2fa0353b9de067c137001897bcae956f1e143429b67c549\",\n        \"size\": 292640722\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14679_Weather18.tar.gz\": {\n        \"sha256\": \"0d857e1df76c6f776a3f912e24a0e586d7842a2ec46db78cc77a635a4240b811\",\n        \"size\": 227948430\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14680_Weather19.tar.gz\": {\n        \"sha256\": \"232bc03fb01f95c158c59d85762f2741d8e0b77f7206125d97431681b26982cd\",\n        \"size\": 359093115\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14681_Weather20.tar.gz\": {\n        \"sha256\": \"f435a484c543112145e021aca3119664776ac0bb9dd8ecd1fc462f84aff5e1e2\",\n        \"size\": 446610596\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14682_Weather21.tar.gz\": {\n        \"sha256\": \"cc537a9223ea06e437c114c373b64e20c09d2f544ba8408a65b1dbbed04c4ec5\",\n        \"size\": 517923336\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14683_Weather22.tar.gz\": {\n        \"sha256\": \"08fd053155836724f654372e3ff0e513c7ee3107761918811f927bd1ea665642\",\n        \"size\": 193032822\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14684_Weather23.tar.gz\": {\n        \"sha256\": \"ab62bc55ee5ed9eebe94cc84019b3b30bf8647acfe07880dc68e2549d78f5180\",\n        \"size\": 88277574\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14685_Weather23.tar.gz\": {\n        \"sha256\": \"a564c6e3ee703e4a54218d3ff55fa04d39f4f6fbefe3179dd74ef8256ceeccb6\",\n        \"size\": 85883010\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14686_Weather25.tar.gz\": {\n        \"sha256\": \"abf300095afa98a9cbc10ba36ef5eb3196f19465ab3b5f01a837989f9fe9f42b\",\n        \"size\": 111637889\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14687_Weather0.tar.gz\": {\n        \"sha256\": \"1e951eb9cd4ee845dbde76fdd6955b51dc242266232e2d7f6df1bf5e56194ee7\",\n        \"size\": 392376550\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14688_Weather1.tar.gz\": {\n        \"sha256\": \"ea5fdae05de411ca4d922975aa6db147a4adb98ddb31aea76a72daad1ae70f6b\",\n        \"size\": 133058846\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14689_Weather2.tar.gz\": {\n        \"sha256\": \"d368f2007835e9d5980c62626f790b1c6a48fde7bb266419413923a4684a79ee\",\n        \"size\": 293386072\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14690_Weather3.tar.gz\": {\n        \"sha256\": \"753b44889760319c34e35594e4d1a91c22492ea8ca7393969a11c6b7825cc6f1\",\n        \"size\": 449863841\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14691_Weather3.tar.gz\": {\n        \"sha256\": \"8d4866dbd8c72943c7e231347d7bc9c829957e8cb9f9498bba878e82a6967c83\",\n        \"size\": 260993038\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14692_Weather5.tar.gz\": {\n        \"sha256\": \"ce757d0fde2e17932f17ab0964a2c4ff6fef811e842884787fe10b83ad885f90\",\n        \"size\": 75152657\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14693_Weather6.tar.gz\": {\n        \"sha256\": \"85be9568ab61458fc9ba70fb06c293ea8c79cf8c1da6e6a231e75fe94b3e22fb\",\n        \"size\": 731800476\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14694_Weather7.tar.gz\": {\n        \"sha256\": \"d2acc476576d4e7c07243721991a4024ad37f51b408869552590d6d1f28f921f\",\n        \"size\": 324623914\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14695_Weather8.tar.gz\": {\n        \"sha256\": \"dd827c2aa5266257bb52f2c8f50b32bdb815fd87be1ef97d4e90b78e83f48b6f\",\n        \"size\": 574480159\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14696_Weather9.tar.gz\": {\n        \"sha256\": \"d40ccd4d40e2fcc18ab85d9351ddac075529ce31df95571374c702f066c076cc\",\n        \"size\": 243274523\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14697_Weather10.tar.gz\": {\n        \"sha256\": \"520bd5c3e0ebdb03644e8ab1f618c7b6a27888a1df25dbad25e432f0d19ab22b\",\n        \"size\": 137125138\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14698_Weather11.tar.gz\": {\n        \"sha256\": \"10378f7a5dce7f986e6346dcbe60c0fca18e73f27eb78f9bafc6c9d1eeec9921\",\n        \"size\": 264568682\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14699_Weather12.tar.gz\": {\n        \"sha256\": \"b8b3c0cf0d86110898bd813dd90392f6ba442a16cedaf15d7899f4fb3175fa2e\",\n        \"size\": 401292415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14700_Weather13.tar.gz\": {\n        \"sha256\": \"4ea476a9acb974fbabe8f6b41af4502e366a37f0c5a3629329ddb6b21b0907b5\",\n        \"size\": 259594597\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14701_Weather14.tar.gz\": {\n        \"sha256\": \"4745386ced258b154a1d729210cfb30becaf15b39c9aad2e92461a981ecde59e\",\n        \"size\": 93908714\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14702_Weather15.tar.gz\": {\n        \"sha256\": \"e3d28c865b6cf6052951e56157461f5c8b2700879c1fad70f45b6779d9998a7b\",\n        \"size\": 473388030\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14703_Weather8.tar.gz\": {\n        \"sha256\": \"c0ea22c909cf4adc619e4c7e1fc811ff62a70d8e33ef937ede4eddc8b59c085e\",\n        \"size\": 451625902\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14704_Weather9.tar.gz\": {\n        \"sha256\": \"667f348db8fcd15dab6ca6df7bac13b9fba93f547f1749bd71a395eb0e1bdfad\",\n        \"size\": 102905837\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14705_Weather18.tar.gz\": {\n        \"sha256\": \"2dec82913410ee3d1dbb418b939d97a3101375f3637ffb8c3e31f40f7ac3b2ad\",\n        \"size\": 221424248\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14706_Weather19.tar.gz\": {\n        \"sha256\": \"542f31beb9801977dd95a5b6cbc50df936af11b166528e09c93a567978a871d1\",\n        \"size\": 110094493\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14707_Weather20.tar.gz\": {\n        \"sha256\": \"21ff858a0c88e3f4e7b62ad7afc5a93024fecd8cc3a9563227d192bc060df8eb\",\n        \"size\": 90994628\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14708_Weather21.tar.gz\": {\n        \"sha256\": \"781c0986a99317e905b747e69b79c52abded3ce3cc941c9642214853bd1b32dc\",\n        \"size\": 82792662\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14709_Weather22.tar.gz\": {\n        \"sha256\": \"707529228453486aee27daa97d63ba88f8aeee9d924eb577e2cf0713c6a68f16\",\n        \"size\": 509487579\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14710_Weather23.tar.gz\": {\n        \"sha256\": \"35f67998dd43f12de7d4586de036ecc158faddcac0bda1402ef9ef6b90a3a288\",\n        \"size\": 438694896\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14711_Weather23.tar.gz\": {\n        \"sha256\": \"4449151e5ab9fc80e7928e0c72c0a8af90740579f5de133909e07805d6d196a2\",\n        \"size\": 237055475\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14712_Weather25.tar.gz\": {\n        \"sha256\": \"472daf70c55620bf33dcd9bb0fff3c6dd9b0a72dc20398abf16b24ffab0b081a\",\n        \"size\": 85446792\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14713_Weather0.tar.gz\": {\n        \"sha256\": \"71a86dc3d510483619e3f98abc1f6344130eeced9eb33867b30d82bb8581bd96\",\n        \"size\": 99828971\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14714_Weather1.tar.gz\": {\n        \"sha256\": \"9c24d619d67100377fc865eaff9a83cc25bdf144da79ecb79345efc7804cd7a5\",\n        \"size\": 394078927\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14715_Weather2.tar.gz\": {\n        \"sha256\": \"57a93160d9ca0f1a0c972e39a4aabc8bffa7b8caabf23e4e32cd7ead1dc95790\",\n        \"size\": 233132497\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14716_Weather3.tar.gz\": {\n        \"sha256\": \"d95d7ce5815fcf3bf59a452c8856a19d4d89af66f7a2754e41597ee0357044c6\",\n        \"size\": 93357147\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14718_Weather5.tar.gz\": {\n        \"sha256\": \"2eef47aecdde69dfde16c2f0025a5196c23de332e1ac6556e1d09149a591797b\",\n        \"size\": 90098830\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14719_Weather6.tar.gz\": {\n        \"sha256\": \"b809fe0d45a7bc8d7e0bbf356127579c55d3c396cc96734d6045f8f3aeb6d48c\",\n        \"size\": 614908183\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14720_Weather7.tar.gz\": {\n        \"sha256\": \"485190f32b3c53e202f4dd786ff28738c8b06fdbefaf9f2720df95a2cca3873d\",\n        \"size\": 393548790\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14721_Weather8.tar.gz\": {\n        \"sha256\": \"36c5125410b4661ae81adffe08a4d97b456df48a33bdc03cfa05347a26bba594\",\n        \"size\": 430180803\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14722_Weather9.tar.gz\": {\n        \"sha256\": \"758cad5fc449ee3dea5fb43ad061b2b3d2c04155bd051c040192b67256b87cc1\",\n        \"size\": 140426420\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14723_Weather10.tar.gz\": {\n        \"sha256\": \"7e723cdbcf239bf876683df5699c5cd8c86654469a3f3ab928e096e75213307a\",\n        \"size\": 323891715\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14724_Weather11.tar.gz\": {\n        \"sha256\": \"801eac1d330a803030689c9d62e8f989c6de963f9547e18f62429f85a3b4c1e6\",\n        \"size\": 360569762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14725_Weather12.tar.gz\": {\n        \"sha256\": \"ae729649baf5b22a9340edcab3355ea537d8e327461f03a6963f68248875d4e3\",\n        \"size\": 61430874\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14726_Weather13.tar.gz\": {\n        \"sha256\": \"ee646448b3c92d541a5a3afceb3d083703767465e2420351edb6d58449627c42\",\n        \"size\": 305346448\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14727_Weather14.tar.gz\": {\n        \"sha256\": \"4e1bd00beba4f03a9847f322e7f1e95ebb33be065e3741121b7c42215c29e9a2\",\n        \"size\": 324405136\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14728_Weather15.tar.gz\": {\n        \"sha256\": \"9ec2f57b15b3b928ac62971d821a2cc165501854cdd53274b281223b9cb20838\",\n        \"size\": 251469589\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14729_Weather8.tar.gz\": {\n        \"sha256\": \"51d512013f1a33f631130673b4910e993ce37065bd2e7a14da1abc3e49b786e3\",\n        \"size\": 295657824\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14730_Weather9.tar.gz\": {\n        \"sha256\": \"be68b0358a0a7b72931ac44b5a871e08bc9b9ee93f4826db1afc380f9855257b\",\n        \"size\": 314719804\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14731_Weather18.tar.gz\": {\n        \"sha256\": \"3cd0972afc681f78fe075a110a2a70019d1cb5977ead9f0e54d33bf06e90d330\",\n        \"size\": 194579119\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14732_Weather19.tar.gz\": {\n        \"sha256\": \"fdec8a8fbc0a5489ea956866af32f61cb9b3601af390d0d8e0aebe4eac9efb9a\",\n        \"size\": 451609423\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14733_Weather20.tar.gz\": {\n        \"sha256\": \"25e9f4b688c96e73a9a7d68a98af5a29d02e60e283796e2f06067aaa83e5d14e\",\n        \"size\": 435180981\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14734_Weather21.tar.gz\": {\n        \"sha256\": \"bff283419945265b49232121de46aaa45a104045875a43160a0a0eead06d140f\",\n        \"size\": 534821388\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14735_Weather22.tar.gz\": {\n        \"sha256\": \"18d2fc04254eb3cf8af44779905ea8020cc1cda10ee5cb269f85b72ed4b93950\",\n        \"size\": 88153645\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14736_Weather23.tar.gz\": {\n        \"sha256\": \"92b75b56e469b798ece56d070046d5b29bb1b5dec8a1ae37557289e0e1399ed9\",\n        \"size\": 384816923\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14737_Weather23.tar.gz\": {\n        \"sha256\": \"5b83ae2d0e74d5aae423c1266a869d24c793c2ec334b3dfc89da5b162da4c8da\",\n        \"size\": 313778496\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14739_Weather0.tar.gz\": {\n        \"sha256\": \"fcd8f408442881d33df9faf3ad648f165fd902e455841d038f264c0310f72031\",\n        \"size\": 690247931\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14740_Weather1.tar.gz\": {\n        \"sha256\": \"b778fb8bb2422a202e12db3fcf5a1b88f3bb55100609070ec041588943354023\",\n        \"size\": 866819791\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14741_Weather2.tar.gz\": {\n        \"sha256\": \"0231d1c141500e053093104c411eefc78e5af0d17620e1b122f4c6322c8193a9\",\n        \"size\": 480785748\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14742_Weather3.tar.gz\": {\n        \"sha256\": \"791c211795158c7f27952300cb1bb06af091af8da0478eb16e742814ef571688\",\n        \"size\": 221409287\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14743_Weather3.tar.gz\": {\n        \"sha256\": \"4d85749ddaf9b993f97c7db2ca9493adfa627fe988bba50d5430a00236a3addf\",\n        \"size\": 130098580\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14744_Weather5.tar.gz\": {\n        \"sha256\": \"9a551eecd71378852b5d84144429b679e8e0099202e274579442152ea8912c07\",\n        \"size\": 248428391\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14745_Weather6.tar.gz\": {\n        \"sha256\": \"3a3e8918cf64df4a21ac72cd4c3e580e4bdc3e004c2a5e899e600ddc9a253a5b\",\n        \"size\": 492221621\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14746_Weather7.tar.gz\": {\n        \"sha256\": \"071f594dbee22a36fff20a07f5e785cacbf2c74af4eaa58389cc1941d6ba6744\",\n        \"size\": 395846497\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14747_Weather8.tar.gz\": {\n        \"sha256\": \"8924e1cfaf837d1110f2cbdd38f027bb01fcfa9289b57e4073d2586d1533200e\",\n        \"size\": 219091442\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14748_Weather9.tar.gz\": {\n        \"sha256\": \"c4697c316c30c4c6d149e6da20219ef064b7758f0e26659298bea8339b67929a\",\n        \"size\": 235518677\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14749_Weather10.tar.gz\": {\n        \"sha256\": \"ba3b42193aa0fdd3f7f68681be94b081cd215e2a17577eaa2fba1e24389de0bc\",\n        \"size\": 100763523\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14750_Weather11.tar.gz\": {\n        \"sha256\": \"ebf1fcc0c67f9e9394c9d97122821aee7e646bb4f89a791774b2fb15738ed5ae\",\n        \"size\": 462176403\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14751_Weather12.tar.gz\": {\n        \"sha256\": \"16be47c9e9b833671d7879c2ecad8326fe371077d92f426e8134822f50e6c113\",\n        \"size\": 179351386\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14752_Weather13.tar.gz\": {\n        \"sha256\": \"5086a7a88917da3b8f8e71363127948620b45c992158e14d99aa9c7da29a0bd2\",\n        \"size\": 181372611\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14753_Weather14.tar.gz\": {\n        \"sha256\": \"166d090f77b6901b67ec511c6c34f9a06570f9c3fa4f3e36613c46f10d18af69\",\n        \"size\": 384268206\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14754_Weather15.tar.gz\": {\n        \"sha256\": \"5a489dd09f38164029024671c3df0de6902882f15be7bba550613a3509735bcc\",\n        \"size\": 220313163\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14755_Weather8.tar.gz\": {\n        \"sha256\": \"e98afd48a8eca5dcf1eb8b482be8888655fd3cb4947c14f289bf6dab445527c4\",\n        \"size\": 473774067\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14756_Weather9.tar.gz\": {\n        \"sha256\": \"9b58ac380e82ab7f23bd69e98b17889cd75353cc1b2e2e46e8e4d4cc581bde83\",\n        \"size\": 160568591\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14757_Weather18.tar.gz\": {\n        \"sha256\": \"f65a0b8786b83110a1eab9430cf325f2070509c2f5153b36c024b4b66316cc02\",\n        \"size\": 85232503\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14758_Weather19.tar.gz\": {\n        \"sha256\": \"7863003675ae1482a46a4d5584d4f5bc7b3260fe49acadd5d7c1569749f851f2\",\n        \"size\": 412993062\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14760_Weather21.tar.gz\": {\n        \"sha256\": \"d855c513dcff6a14ad9967aaecf978f1c697ce1979a317f7bfc0b701258f9df0\",\n        \"size\": 222105785\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14761_Weather22.tar.gz\": {\n        \"sha256\": \"9d1a47e15903935c0c297de4b766b246ecc80b87d528d5c85e4a9153b1bce312\",\n        \"size\": 91570520\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14762_Weather23.tar.gz\": {\n        \"sha256\": \"8d16249311b1c7625cf61427445d4a3d83c2e66f5470830819085b854c39d468\",\n        \"size\": 407737729\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14763_Weather23.tar.gz\": {\n        \"sha256\": \"5ef52eb90232b00c026d8ab0b0d4748d6c5801eebf92ddb5a40c25df732da396\",\n        \"size\": 404434415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14764_Weather25.tar.gz\": {\n        \"sha256\": \"0393608d30cfcece7073d6dc7db21bb29369f0107fa735d98f9526582dccb59d\",\n        \"size\": 489854076\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14765_Weather0.tar.gz\": {\n        \"sha256\": \"12d771e4952ff2ac7583011dbe432af2f101fdfcafffc0704be690d92ccd6a1c\",\n        \"size\": 84306277\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14767_Weather2.tar.gz\": {\n        \"sha256\": \"4531191bf3f4c5c4dbb19183e02a41f653bf894b413e527f949f83f9c3a0302c\",\n        \"size\": 380517225\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14768_Weather3.tar.gz\": {\n        \"sha256\": \"edd06d889511770385dca5278800cc99af2c9fb3025f9527254ceee40482f549\",\n        \"size\": 320491838\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14769_Weather3.tar.gz\": {\n        \"sha256\": \"56043a0080dc068ce498827a644c3624590b0b339f9a77b26ffb42719852f1e0\",\n        \"size\": 219424013\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14770_Weather5.tar.gz\": {\n        \"sha256\": \"553ead3cfe8659997a63b8e0610ae8ab833fec629b28e7115b49a866fb507a25\",\n        \"size\": 85994512\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14771_Weather6.tar.gz\": {\n        \"sha256\": \"e992e4c9584f9d82b26c1217d289de3d3645e5cd450161d7ce94a8c1fa12b341\",\n        \"size\": 221228514\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14772_Weather7.tar.gz\": {\n        \"sha256\": \"dc3a5c4f05bbbdf942c61bfcd548e114fb3819d143c88bc888f3d29b8025c4f0\",\n        \"size\": 804822081\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14773_Weather8.tar.gz\": {\n        \"sha256\": \"30cbd52498310d8f88affc544b3229a69070f0c99d3ab4c0f575aadf7d0c7dea\",\n        \"size\": 137939415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14774_Weather9.tar.gz\": {\n        \"sha256\": \"a3ca944d63dd1aefb0c01d77c72858c38cf84e7480ece622c4113d2cc7b944bd\",\n        \"size\": 92657931\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14775_Weather10.tar.gz\": {\n        \"sha256\": \"4edb2947e290c1fbfde05969513c774112f54107a36c5c2cc54ee0beeaa8f37a\",\n        \"size\": 79687818\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14776_Weather11.tar.gz\": {\n        \"sha256\": \"3e038af498488b61270f34c9a89593b9ec5f2a23dd5c1423efe58467cabac0b0\",\n        \"size\": 309408756\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14777_Weather12.tar.gz\": {\n        \"sha256\": \"dafb4a30a142d0386d347a8418d76527f2b16913f619e2e30a953ab2d8273a6e\",\n        \"size\": 71208910\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14778_Weather13.tar.gz\": {\n        \"sha256\": \"c4f57fedb403a838c33c59c714bf496b0cd070d372704771f97efc70a417c133\",\n        \"size\": 55344538\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14779_Weather14.tar.gz\": {\n        \"sha256\": \"b76776c3088859ad6a3bc11aff7ec63c1854d73e7e8206160a16888bbc95d110\",\n        \"size\": 409140217\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14780_Weather15.tar.gz\": {\n        \"sha256\": \"ce0cbc6026968a9f793956fb0a9ce5cf41298ccfb2b6c65998af0e1ea09f93d8\",\n        \"size\": 245007626\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14781_Weather8.tar.gz\": {\n        \"sha256\": \"1d25534def46c420b996220b293e2358ea27271bb874a9953425e86a56209afd\",\n        \"size\": 100582258\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14782_Weather9.tar.gz\": {\n        \"sha256\": \"1c42cb3c48eaf1d54a108a8b8239527ac604b3d5df0816cd4cfaecdade9b317e\",\n        \"size\": 166400153\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14783_Weather18.tar.gz\": {\n        \"sha256\": \"cc6ec903737f8caf36e66eeffffa7dad5077b23b63625f228c180ba8b05b9bac\",\n        \"size\": 544360244\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14784_Weather19.tar.gz\": {\n        \"sha256\": \"489c355efad300d0d15d73251afe16d4d905f2377103478be27ce3c526246384\",\n        \"size\": 580879874\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14785_Weather20.tar.gz\": {\n        \"sha256\": \"083d9d0e86ac41fac7322ffef36bb0e106298ae5fc1b747adf3fc888435f2374\",\n        \"size\": 412486160\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14786_Weather21.tar.gz\": {\n        \"sha256\": \"309431ffe4e3b71c2d76374df1f8ad7b3e4bbc114720f5f6c2379759b209a9b5\",\n        \"size\": 316495894\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14788_Weather23.tar.gz\": {\n        \"sha256\": \"ceba36f50678268a0f1c5539704bb0bd817e56304e46f1c01280c6480c7fd95d\",\n        \"size\": 592869578\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14789_Weather23.tar.gz\": {\n        \"sha256\": \"527747003cc22544113146467d7a853527f8ecb703475a72317c5ad81bb29240\",\n        \"size\": 359861206\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14790_Weather25.tar.gz\": {\n        \"sha256\": \"e3209647b9b5baa68d43c4d7ec80263609ec8fbd5215a65a797f7fd29fcd3137\",\n        \"size\": 429946982\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14791_Weather0.tar.gz\": {\n        \"sha256\": \"c60ca133e35098add133eebfc1b5a3bb80b1c25a0357808dbc4f09a4288c744e\",\n        \"size\": 186158655\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14792_Weather1.tar.gz\": {\n        \"sha256\": \"064f92098b9e6b3fb5b9ef0044b43a43effbddaf42d985724fcf6e3f2a48454b\",\n        \"size\": 582773057\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14793_Weather2.tar.gz\": {\n        \"sha256\": \"2866b5837fa7cf8d17612cdc4e0ca0f708403d1d2f0a3988777d0b7c19163bde\",\n        \"size\": 648771748\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14794_Weather3.tar.gz\": {\n        \"sha256\": \"7b9a2b4df01806138f6b536fa2eb1b13690fb6e2b003369a2f095d3acf1b65fd\",\n        \"size\": 154720254\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14795_Weather3.tar.gz\": {\n        \"sha256\": \"99737a7d4d31075b6ebb7064c8eb4cab56343df42ba88c69b2196037713fb0c8\",\n        \"size\": 335160494\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14796_Weather5.tar.gz\": {\n        \"sha256\": \"ac628b4e761b0327bbf67d6615fcbfad680bdc05419a03c98f6016782e662247\",\n        \"size\": 310896450\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14797_Weather6.tar.gz\": {\n        \"sha256\": \"0f0267ab39689e9c938e718aac24e85b0629e0e0dc3964cf1727e04f615417ce\",\n        \"size\": 462101922\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14798_Weather7.tar.gz\": {\n        \"sha256\": \"d1a057d1176005faf90a72ab202c092b1217b559c89a62afa1782e352f7f078c\",\n        \"size\": 334497317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14799_Weather8.tar.gz\": {\n        \"sha256\": \"e96087d482224e9f94eb14f4fe97e84684ade5c15c8362e4876df31f30733d21\",\n        \"size\": 88720484\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14800_Weather9.tar.gz\": {\n        \"sha256\": \"6975e1a06b1596047c619dafac3290630142bc1d7c17d510f517f68c3c678840\",\n        \"size\": 115842383\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14801_Weather10.tar.gz\": {\n        \"sha256\": \"3e1dd9c933ac6e1a986e163c7fcc1da6218a673a3831f1614e42f49ddf87481e\",\n        \"size\": 429078098\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14802_Weather11.tar.gz\": {\n        \"sha256\": \"40a85a6871d896ccffc27cb0ef3ac11255734b856c299eb5f7106ebe647791cb\",\n        \"size\": 462700430\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14803_Weather12.tar.gz\": {\n        \"sha256\": \"d4a915ce27dccef2d30d61a45916e6cd2072232df7f71ba20caad41de9a73cda\",\n        \"size\": 285151386\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14804_Weather13.tar.gz\": {\n        \"sha256\": \"09e3c7a5c00972199dc49118f385a0ebe36e4842febde6d28407ce156245b4e6\",\n        \"size\": 54401145\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14805_Weather14.tar.gz\": {\n        \"sha256\": \"ff5702f57b8c7917a7e5fd6ced01df529273523988d756386a27109f05843e91\",\n        \"size\": 269197951\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14806_Weather15.tar.gz\": {\n        \"sha256\": \"18b33a55c305bff0326dfc3450077bf14509a9fdf09fb50440be26a0df18f8fa\",\n        \"size\": 84223669\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14807_Weather8.tar.gz\": {\n        \"sha256\": \"cf5405bc847b915328e9a880f9873ba5e5ebea46d266f2cd0be6d63b4367070e\",\n        \"size\": 247555567\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14808_Weather9.tar.gz\": {\n        \"sha256\": \"e0301eb028af484ea9dbdb604471aba86feb4a739c4f90c50adf615b5cfa7cb2\",\n        \"size\": 71913291\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14809_Weather18.tar.gz\": {\n        \"sha256\": \"bbe7dfdbf17bc977bfd372822afff8accf1c09adcd7712ae167a9c56cb469a30\",\n        \"size\": 326228069\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14810_Weather19.tar.gz\": {\n        \"sha256\": \"f2caca770cb28fa61aca4190b4f67b8e3eff448ddf33620750f12a57299e44d3\",\n        \"size\": 650742216\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14811_Weather20.tar.gz\": {\n        \"sha256\": \"b317b1f3ef6795980dd4f11387a45c50b4e840dc115aa38f1d0d45bb60ebe583\",\n        \"size\": 200946686\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14812_Weather21.tar.gz\": {\n        \"sha256\": \"034b1a803766158d0b58c9a8712038070bb7f2322d2f05c07d198c07ca27600d\",\n        \"size\": 114100277\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14813_Weather22.tar.gz\": {\n        \"sha256\": \"ec212efabba22711addec93d3fbe69830bcdf28c1c3862861d0d7725de8d6409\",\n        \"size\": 209977206\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14814_Weather23.tar.gz\": {\n        \"sha256\": \"49c15fd305f913d2be3bd10a60c3547b0ecabc76603b7ed2b55d29ed924e163d\",\n        \"size\": 389407264\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14815_Weather23.tar.gz\": {\n        \"sha256\": \"a2d5f50081da5e3f619050e510d830df1d7b608431d2bb57ad1c74f43b60b271\",\n        \"size\": 276062793\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14818_Weather1.tar.gz\": {\n        \"sha256\": \"4f1c306b27be59974afc9d3dc99f147b92fb11aebf76cf88fdbd3c844c9d7cc5\",\n        \"size\": 550609988\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14819_Weather2.tar.gz\": {\n        \"sha256\": \"d3ffd81ed12ae0e5d9ac78517c4b9a62d890c5b8558cd1e8b90e3c58a83fa144\",\n        \"size\": 545855738\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14820_Weather3.tar.gz\": {\n        \"sha256\": \"fbdc5faaf2d769c7022da3045b8c1c657e76f519f13e39193caab04158b7d7df\",\n        \"size\": 223591807\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14821_Weather3.tar.gz\": {\n        \"sha256\": \"1694f7cb9b7fb31dd460aca55bc49502b9b7213c152f9fd8c69114b00306c937\",\n        \"size\": 617488683\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14822_Weather5.tar.gz\": {\n        \"sha256\": \"ee53fb13db1916ddcfcf7d01521141ac2d41ca47d80badeb422ca9ba81698dc2\",\n        \"size\": 446792317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14823_Weather6.tar.gz\": {\n        \"sha256\": \"4b23218a0c31dfebeb13fc40e14c71847fc7961291e81a8c2f9355fc60033228\",\n        \"size\": 126370286\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14824_Weather7.tar.gz\": {\n        \"sha256\": \"56fbbb80f8a1d73d1788b64cdb2799eb8b2d1bbe38f7bd3e4ec91355f466baf2\",\n        \"size\": 666867762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14825_Weather8.tar.gz\": {\n        \"sha256\": \"46f505f4b5df94504159f9ad22749747119fddda557149371b5db6bfcf1d69e3\",\n        \"size\": 450023925\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14826_Weather9.tar.gz\": {\n        \"sha256\": \"fa208c9d80a3355c398a462da2bdcd4096a59c99b6bb3dcc9609e6dfe385b1e3\",\n        \"size\": 80596381\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14827_Weather10.tar.gz\": {\n        \"sha256\": \"0ccf453a46bb3814fc7f1ad1a4e958be4c13053d3c02d84d4e21a5534c3a5b25\",\n        \"size\": 341164554\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14828_Weather11.tar.gz\": {\n        \"sha256\": \"badb8487050c74f1b1ec71a592b3cfccbb0e152803b59ecdbdc52f85de40fd58\",\n        \"size\": 198157142\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14830_Weather13.tar.gz\": {\n        \"sha256\": \"2e08094ca1361f44a1ae4944be3bcd09121247929574d4a10e8246abe75d45af\",\n        \"size\": 369137434\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14831_Weather14.tar.gz\": {\n        \"sha256\": \"4f36ad495fb70d95fca59afc9efb6d089f629d74eeb8c7139770309b01e3aac7\",\n        \"size\": 149313075\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14832_Weather15.tar.gz\": {\n        \"sha256\": \"80145987349afeab2cac5ee97c86475c769cf828c9b63ac60143868cf346ea0e\",\n        \"size\": 314227111\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14833_Weather8.tar.gz\": {\n        \"sha256\": \"8b56b7086bfeb21b53c08332b7b14f9a74877cc66c9d14de449695e2fa22160a\",\n        \"size\": 312886580\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14834_Weather9.tar.gz\": {\n        \"sha256\": \"56e14aa1354f349ceb7f2c47073a7b0d59c8034483c1222dc429af32d4624b97\",\n        \"size\": 144643697\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14835_Weather18.tar.gz\": {\n        \"sha256\": \"c185bc27f03b2859208277fa443995136b90a8f28bcdcdd979135135d2c33c27\",\n        \"size\": 525716310\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14836_Weather19.tar.gz\": {\n        \"sha256\": \"c67c3ab1a15e7769d6c0dece1147419f99d8f8dedd7c06a95d3ead076f0aa0cb\",\n        \"size\": 406406860\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14837_Weather20.tar.gz\": {\n        \"sha256\": \"feb2f3550ac54ef4847505ec6aace03a136f3f59c9a0cfe87cb6dfa8f6df46c6\",\n        \"size\": 838603999\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14838_Weather21.tar.gz\": {\n        \"sha256\": \"959f51fff206218dc7b968c7c6b9c79488085262c2d164982676e97e4207a837\",\n        \"size\": 489557507\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14839_Weather22.tar.gz\": {\n        \"sha256\": \"3e7c38d67f825f434242041b0de1d65a5ff2489229449a9bfa34fb35dcb450fe\",\n        \"size\": 385188149\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14840_Weather23.tar.gz\": {\n        \"sha256\": \"b5fee164aab4d2847fbc69b221e4107aa5e6e2917069180862121492469bc3c6\",\n        \"size\": 314007970\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14841_Weather23.tar.gz\": {\n        \"sha256\": \"6de82930da425c6aa3eef23996ae47313629096daf41166f643eb46032269c45\",\n        \"size\": 335504167\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14842_Weather25.tar.gz\": {\n        \"sha256\": \"a4873172beb48d6214ffa5e252fd8375275e03815d0846c79b8b98d129ca93e8\",\n        \"size\": 170309812\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14843_Weather0.tar.gz\": {\n        \"sha256\": \"f65d423b47d24b85ae85fdfe3cac04d2033a02e5bde9f7c1e8ddf37cffbc7bdb\",\n        \"size\": 82145998\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14844_Weather1.tar.gz\": {\n        \"sha256\": \"ff504de5d9e7b7a2f6558e4cafdf0a063fbc0a8dd3c3cf83169012d1c690ec7b\",\n        \"size\": 89508487\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14845_Weather2.tar.gz\": {\n        \"sha256\": \"32d3a361714382a89ee8c9d65575abdc559d6c8c87b1d81602a1ceda46468a71\",\n        \"size\": 598936158\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14846_Weather3.tar.gz\": {\n        \"sha256\": \"9b974c87d17a45488d422a86451f75791c5e8d15a452c8ef6f8780e8ad6b63ef\",\n        \"size\": 489071138\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14848_Weather5.tar.gz\": {\n        \"sha256\": \"836308d41a56d7d6c95783577ab06289eaeb5b6ce9c20fb7f916e85eb313fd65\",\n        \"size\": 222708333\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14849_Weather6.tar.gz\": {\n        \"sha256\": \"4e9d52e1b2b2cf1ed5c9923d0be36d83f074dece34d380c28ac65b7123db76d2\",\n        \"size\": 100452113\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14850_Weather7.tar.gz\": {\n        \"sha256\": \"5c54a54caef713ef6e80632aa3678aea8a715f63134545c6a83b10b40f94421e\",\n        \"size\": 643374677\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14851_Weather8.tar.gz\": {\n        \"sha256\": \"969626783048007120f8a8499d994992654e1d2e430edd9e6407d31523123946\",\n        \"size\": 730780048\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14852_Weather9.tar.gz\": {\n        \"sha256\": \"ad5f4ed790cc7d7d61c91ee97a8ed97258dc7866b1053c927b5b8886722ad414\",\n        \"size\": 135164541\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14853_Weather10.tar.gz\": {\n        \"sha256\": \"a0f0d03ae1319af400fdc3317ce8ededad668daaeffa80e6337875f2bf9af483\",\n        \"size\": 90047359\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14854_Weather11.tar.gz\": {\n        \"sha256\": \"661673c9371ce7ad49de74934675b3474a06c32aa702bd0e0492546d20a62321\",\n        \"size\": 474608850\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14855_Weather12.tar.gz\": {\n        \"sha256\": \"205a04757cd55f7f2865f122b7f45b6069e220dea3042e807d147062f30aff67\",\n        \"size\": 69649546\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14856_Weather13.tar.gz\": {\n        \"sha256\": \"92ebc97dc9e2e0f95268ef0e9ee5e11d9a0c331c0e7c40c85e0f61e35b501a94\",\n        \"size\": 240053370\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14857_Weather14.tar.gz\": {\n        \"sha256\": \"afe8551de4de64c1a9d9c2f7151b15a64c9bccf0ecaab0e931c410c59dbf4b64\",\n        \"size\": 172701824\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14858_Weather15.tar.gz\": {\n        \"sha256\": \"b6991854a840622704a6ad3023a28e54c11459588211bf4b99e290d9c9c600c4\",\n        \"size\": 356535722\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14859_Weather8.tar.gz\": {\n        \"sha256\": \"849602d23813f64bd54f2cf5305643678c9a9b33b8f3ac979f06a53a000c1723\",\n        \"size\": 219772570\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14860_Weather9.tar.gz\": {\n        \"sha256\": \"0deb0519e06d202e141e09b0503b26c76277b5be6dbca50c02f949dc5ac34c67\",\n        \"size\": 261537926\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14861_Weather18.tar.gz\": {\n        \"sha256\": \"de0fc5be94e6291a402677ffbb51669b3dd7f1db5a99ac1df490f24d98c5f9a5\",\n        \"size\": 195449187\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14862_Weather19.tar.gz\": {\n        \"sha256\": \"00acbcd8d6a87254935e9bd98467272c37db29d6c8cc8d1cd4a0e363f96b403b\",\n        \"size\": 242880503\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14863_Weather20.tar.gz\": {\n        \"sha256\": \"2e6df2e0ea732d1b41c0e3e3ee333148d1c4e0a0761d233dbdf0695febaa2f50\",\n        \"size\": 196300446\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14864_Weather21.tar.gz\": {\n        \"sha256\": \"6ce2b0a70633bf1c8358bdaf72aac80fe56c8249a4321d835612e6e0127f0b41\",\n        \"size\": 331606944\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14865_Weather22.tar.gz\": {\n        \"sha256\": \"42f6d929f5ec76faad95c338a59b2d7c51482005627f35d0af84e04857708651\",\n        \"size\": 212696811\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14866_Weather23.tar.gz\": {\n        \"sha256\": \"2656e267144df3678a7cce4ea67189644f93ed561200c19c980005a01e2bec40\",\n        \"size\": 369618621\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14867_Weather23.tar.gz\": {\n        \"sha256\": \"032ea8bd3a8aacc9b8980a205402e5902341451e4e15ceb1c1b5da9101d54e72\",\n        \"size\": 71726401\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14868_Weather25.tar.gz\": {\n        \"sha256\": \"334c9b2ab00a06ccca2b86f569aaf3e156a0e1585ee7eb7a5a406295f55a8b67\",\n        \"size\": 215930600\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14869_Weather0.tar.gz\": {\n        \"sha256\": \"fe6fa46ae0348615bd19cc1b9bc1d20b4715c81c9d4543a8e63ab9e8bb5794d0\",\n        \"size\": 503282474\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14870_Weather1.tar.gz\": {\n        \"sha256\": \"2001df74a14b7a0085472418fdcdae0d44ee2d6f38c0496fde11c861f985d8f4\",\n        \"size\": 274706571\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14871_Weather2.tar.gz\": {\n        \"sha256\": \"e46be3e2e95c442fe3041708474c43301a057203edf9f9d55246c2a8c46926b9\",\n        \"size\": 485630366\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14872_Weather3.tar.gz\": {\n        \"sha256\": \"0a7a584d07cb04a92a6d2b668287dc954aacc7defde831149bf9e3154c4f796f\",\n        \"size\": 838668217\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14873_Weather3.tar.gz\": {\n        \"sha256\": \"2020b84c40b8198cf4e14b06898798b80e8ee3ecaa2a2bd76e061a008fba60ec\",\n        \"size\": 265332749\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14874_Weather5.tar.gz\": {\n        \"sha256\": \"74c5b27ea7371ac827229c6bf88049fe6d700fe519471bd8ff4539c191d355d4\",\n        \"size\": 732021411\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14875_Weather6.tar.gz\": {\n        \"sha256\": \"675d6a3f76dc25b8f79bec08d26a3872e68a411fbd72107fcae3b8e0263863b7\",\n        \"size\": 70319372\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14876_Weather7.tar.gz\": {\n        \"sha256\": \"a7b89545082fb478747331b44bf4a1e88c811d036789e48a991b122e12f28fa1\",\n        \"size\": 673714383\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14877_Weather8.tar.gz\": {\n        \"sha256\": \"90b4ca1eaa5dd8bd353514cdad115e528b65371b636019a1f3e07f1ac10e3beb\",\n        \"size\": 329427716\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14878_Weather9.tar.gz\": {\n        \"sha256\": \"b1330a1e7a4bda2cace776bd8263e9ce47c0ec09aa0ec0d40db0e3fd3ce6a32b\",\n        \"size\": 65726773\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14879_Weather10.tar.gz\": {\n        \"sha256\": \"432a7a580a72f3383fb490c3a4ae16d59c5a2979492fdb40249087372d3f9446\",\n        \"size\": 422211350\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14880_Weather11.tar.gz\": {\n        \"sha256\": \"eeceb3d72f532fbb32b989cacf062ee88fc4834e0941ab26241f600d7e63752a\",\n        \"size\": 390877194\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14881_Weather12.tar.gz\": {\n        \"sha256\": \"6460426419a7791f8be571fa84f8dfa0758c8d1b5a37c90a90fea450bc6a8a79\",\n        \"size\": 435968695\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14882_Weather13.tar.gz\": {\n        \"sha256\": \"b7dfe4d12d10af3cb0ad7cbc7f68f2d2ad7ef6f696da2d32d95b34f6816235c0\",\n        \"size\": 350322477\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14883_Weather14.tar.gz\": {\n        \"sha256\": \"fad6d84191e39711ed2a840c97463215b1f9128b5c4fcbc26c614c4c487c0f04\",\n        \"size\": 271855492\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14884_Weather15.tar.gz\": {\n        \"sha256\": \"9febcc934b7633856b3509e5afcca1557adf1ee24257ed48ae392e8e8e24b772\",\n        \"size\": 62134924\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14885_Weather8.tar.gz\": {\n        \"sha256\": \"43d58a05fff7efae5805f5eda3159e9265920895789e1c6a6813e9590f98e45e\",\n        \"size\": 193080661\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14886_Weather9.tar.gz\": {\n        \"sha256\": \"bf4c2972fa585a3b9b4e27b7b252f542378db6235428ab462f97d16e4497ecef\",\n        \"size\": 253616870\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14887_Weather18.tar.gz\": {\n        \"sha256\": \"d28ddc2bfa7eae519c651d4be5d8e331a926517660b6f46d35d253fc4cfff109\",\n        \"size\": 455589751\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14888_Weather19.tar.gz\": {\n        \"sha256\": \"bf5f3d7cb79870932aa7d815c625f161eedf34df1e1707cd6cd11d5c0fd643ff\",\n        \"size\": 93757593\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14889_Weather20.tar.gz\": {\n        \"sha256\": \"c2ef6a4da9d686917a22f975091ac524b2237eadc75b9279fa4d2847e550aeb4\",\n        \"size\": 403418518\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14890_Weather21.tar.gz\": {\n        \"sha256\": \"80726f09db1054d03253dfb6e9fcc7ae5a476457e29a607ac9eaf680a9e2ea75\",\n        \"size\": 405948866\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14891_Weather22.tar.gz\": {\n        \"sha256\": \"29df911f437e14924e1bb2ecc6dedcca3fd518360d0b13e83d4f79ba8b277fc6\",\n        \"size\": 261887210\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14892_Weather23.tar.gz\": {\n        \"sha256\": \"0c052919199db3a51488b4c8219f659513de4ce09a8f02eb4674b4c8c485e82e\",\n        \"size\": 623213306\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14893_Weather23.tar.gz\": {\n        \"sha256\": \"d21e5c87c6ce9da6c722aaf65898da8ec617e024944f1613f2e0d8cb34c2de9c\",\n        \"size\": 296341403\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14894_Weather25.tar.gz\": {\n        \"sha256\": \"dc3212ac832d5e358917905310737650de8b152ada210c85e7665e4ce7d9b243\",\n        \"size\": 287623510\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14895_Weather0.tar.gz\": {\n        \"sha256\": \"ce73f8cf3cdaf0ba38b91ce62bb030be3e58d6f0e7f2f00553c25884e332b73d\",\n        \"size\": 511773292\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14896_Weather1.tar.gz\": {\n        \"sha256\": \"c8d7225eaa44e721fe56e5f38663c00502f5ec5f870c0322a640bcd678a61a40\",\n        \"size\": 78339762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14897_Weather2.tar.gz\": {\n        \"sha256\": \"d34242526fea62edd37264c5d882e25fe5556c72103dba813920aa7ef09bd3c9\",\n        \"size\": 240853335\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14898_Weather3.tar.gz\": {\n        \"sha256\": \"f6531282ff40bdb3a3b93c724ff907f9a0a4823d1da053ba3afea37ee056a7bf\",\n        \"size\": 677695344\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14899_Weather3.tar.gz\": {\n        \"sha256\": \"30bfd3be2f7e0dedd99abf1215627670480d3d0859b946c8380c3ca7cb503ee0\",\n        \"size\": 112066047\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14900_Weather5.tar.gz\": {\n        \"sha256\": \"8f1aa706035b9d81eeed021382fd124f77623d88e98c97630f76fad8c044dba8\",\n        \"size\": 195122419\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14901_Weather6.tar.gz\": {\n        \"sha256\": \"f62ca7d175eb3484bce78328877fffd2cfbcb1cd79eb64f7dda6b6d9f5995597\",\n        \"size\": 314183637\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14902_Weather7.tar.gz\": {\n        \"sha256\": \"22d9c6da3fa57a6a1cd50b8e74ee6f683addb305413b477f3aa980069d0aaf95\",\n        \"size\": 92275621\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14903_Weather8.tar.gz\": {\n        \"sha256\": \"e1af12c329cdd2676670b56e40733abc4e251f860f666585d2d6803c9152840c\",\n        \"size\": 373419810\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14905_Weather10.tar.gz\": {\n        \"sha256\": \"5cb25779cefdb52cd990b5d039f4f156fa0d215b90281c43ccb6a4c813abb585\",\n        \"size\": 228124990\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14906_Weather11.tar.gz\": {\n        \"sha256\": \"05c0e7301f57b3031384dcd34f855a7e9d6d39f203e4974b0d933803cdd418d4\",\n        \"size\": 154225493\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14908_Weather13.tar.gz\": {\n        \"sha256\": \"2549da00bd4c9280322c8e818e8f6a348e1e9ae39a8e85d4f17f7b03410cbeeb\",\n        \"size\": 151117656\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14909_Weather14.tar.gz\": {\n        \"sha256\": \"9d58bdafebcef3559992f25fd548612d06e7fc896d5857edc805f8952bbf9b86\",\n        \"size\": 294744669\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14910_Weather15.tar.gz\": {\n        \"sha256\": \"29e768e320c1287a839aa993547beda059f2fc69110287bf9bacb8b42ac641d8\",\n        \"size\": 585415366\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14912_Weather9.tar.gz\": {\n        \"sha256\": \"d5350bcc57c639870bb7cbda85cc58c69ca75e72062ffb8ef3e64ac231bb3a4a\",\n        \"size\": 183505827\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14913_Weather18.tar.gz\": {\n        \"sha256\": \"dfccd4cacecdffb048ff2874ac989b8255afc135901a29249fb8988fedf06931\",\n        \"size\": 932114391\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14914_Weather19.tar.gz\": {\n        \"sha256\": \"5bc1e67bea9ee4dd35dcbdc38442bf1f59f61ff2952ac57c553b9c31b7f3310c\",\n        \"size\": 329407272\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14915_Weather20.tar.gz\": {\n        \"sha256\": \"67217ab6b5fcb8d2f5ea36f3efb51fd87894c250116fb579ec2a5ea6ce63a947\",\n        \"size\": 485249005\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14916_Weather21.tar.gz\": {\n        \"sha256\": \"88b87c9ed47e640a452a3d3adeafb490e1239bdeadf4b038f2e42e6a70c7d141\",\n        \"size\": 81689765\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14917_Weather22.tar.gz\": {\n        \"sha256\": \"d4953d8131cf301b02ecff9870d961c5c35ab127ac911bbf2522e2988ef11b7f\",\n        \"size\": 286946984\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14919_Weather23.tar.gz\": {\n        \"sha256\": \"9799d57353ce117c5613a76f58c023649b0c29c643678ef6e55bf292d185c29e\",\n        \"size\": 551420050\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14920_Weather25.tar.gz\": {\n        \"sha256\": \"367ca2b3ff81b0b3d6c102916edb3211d5debee1a7cea7ae8cbf6e1936140bd5\",\n        \"size\": 54315945\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14921_Weather0.tar.gz\": {\n        \"sha256\": \"3d7c0ae822f68a224e88180d6c4d77947144c0bdb1e8504c4c0956166f72515c\",\n        \"size\": 149296462\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14922_Weather1.tar.gz\": {\n        \"sha256\": \"49cd8be0b940767c94c7ce053685b2865b8a49dbeafc34e19da08b04c2bfd4ce\",\n        \"size\": 396286916\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14923_Weather2.tar.gz\": {\n        \"sha256\": \"0f51b6512ad8061ac48a934d4c4157e954982777fc9bafb8a44e9b16888df5a8\",\n        \"size\": 102851600\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14924_Weather3.tar.gz\": {\n        \"sha256\": \"a7760378cc3c0d07b8208d1941ce6d756c38cd0ea817f48484658b8489b1d79f\",\n        \"size\": 332704453\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14925_Weather3.tar.gz\": {\n        \"sha256\": \"cc419b6bc1209471ab1995ab7316597d4999b4068862f7199393466809bbdd62\",\n        \"size\": 360074840\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14926_Weather5.tar.gz\": {\n        \"sha256\": \"ec054358d8c38484bd558d7f83facef079d5deb0b7c92b2d0f048222d4c94e06\",\n        \"size\": 197690576\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14927_Weather6.tar.gz\": {\n        \"sha256\": \"53900d0c05d62ab8cde00f878c866e63cbc5cbe5e41b79b519b7047726954554\",\n        \"size\": 546357312\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14928_Weather7.tar.gz\": {\n        \"sha256\": \"c502854faa33939822c59766eb216a3d89c5c12f449c6beca130f9a78508a5ef\",\n        \"size\": 140607080\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14929_Weather8.tar.gz\": {\n        \"sha256\": \"7d492acaaaa972576a0d3773708b3ef5eff7312c3dec915c4c16592c34d58306\",\n        \"size\": 473287283\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14930_Weather9.tar.gz\": {\n        \"sha256\": \"4dc81f921531fb7446fdf066999c535e009644b0db01c5b6301f9e217cd214ba\",\n        \"size\": 327722031\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14931_Weather10.tar.gz\": {\n        \"sha256\": \"89017d0ad90a9bbee1da3bd4b2d11e374362189fa27c8e069f5b06a20a878044\",\n        \"size\": 485922552\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14932_Weather11.tar.gz\": {\n        \"sha256\": \"15d512512271a785c875f738e9a09744747a8060502dbed37db70b85b61d6d6b\",\n        \"size\": 190289825\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14933_Weather12.tar.gz\": {\n        \"sha256\": \"1314263a725d100f4caa6857986367e5c1560a7d2be04bd4aafcb7cf5a72be03\",\n        \"size\": 363438533\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14934_Weather13.tar.gz\": {\n        \"sha256\": \"ecb7afaae67948a60a5f6dc356de02b23f2f2bc17cfe14544df6afada56b51e9\",\n        \"size\": 342617340\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14935_Weather14.tar.gz\": {\n        \"sha256\": \"594ed1bdf1f7b1805995d214f4a7052a88d94fe5573285d81068bc2022bcd530\",\n        \"size\": 60003483\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14937_Weather8.tar.gz\": {\n        \"sha256\": \"3e81c178b1c73d98ec6f3e91d2807c6fad4048784942a2761be249041b049c40\",\n        \"size\": 411192438\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14939_Weather18.tar.gz\": {\n        \"sha256\": \"5e6bb9c27ca071b63d360ec40dff5a35dcf5de9377d02a44bbe7aaf09661ebc3\",\n        \"size\": 390535589\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14940_Weather19.tar.gz\": {\n        \"sha256\": \"c9632ba5d33a37eccec58b31b247f72684496decb429ab602236e0ec46160a36\",\n        \"size\": 219136622\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14942_Weather21.tar.gz\": {\n        \"sha256\": \"3fddae418927c4791b8b76681c9931d179440c49e299e4f785bbb7fb018b144d\",\n        \"size\": 202647877\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14944_Weather23.tar.gz\": {\n        \"sha256\": \"8acca815dbab74a688329496cc74b02c597292c1284ccfb34d1f5ca4e0c47e5d\",\n        \"size\": 332987465\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14945_Weather23.tar.gz\": {\n        \"sha256\": \"a1c1cb096bc39b4b41af116de4d03a4dc95604b85173dc83c7fd8445fa682c7a\",\n        \"size\": 307205164\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14946_Weather25.tar.gz\": {\n        \"sha256\": \"b17b6d92a63f03b184b6cd3c311d73109ca4ace67cb6d434a61018dc6dd6af00\",\n        \"size\": 142145911\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14947_Weather0.tar.gz\": {\n        \"sha256\": \"065c4d113cb25380673b37cb693038dd7ca9203a8afbf64d5bc00773c6003f4b\",\n        \"size\": 145911709\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14948_Weather1.tar.gz\": {\n        \"sha256\": \"4c9de4ecf395fb1111191f2cb56ed29cb175df58f81e8dfcf045c1b391922a28\",\n        \"size\": 612712449\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14950_Weather3.tar.gz\": {\n        \"sha256\": \"c2bc932b1a41b9e1dcfc74ec6b415ecbd4578ff81b7d9ffb0f8a46e7c035324c\",\n        \"size\": 410060591\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14951_Weather3.tar.gz\": {\n        \"sha256\": \"fbcd5c3a908a2e3466b5d6faa433ae48963be68dbac9bd06e8c7d2fa2a9d1213\",\n        \"size\": 426018774\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14952_Weather5.tar.gz\": {\n        \"sha256\": \"ec0497b3c6e58814c6edd79faa464e65b284cb1f9564685e507b344cadfc040b\",\n        \"size\": 97294944\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14953_Weather6.tar.gz\": {\n        \"sha256\": \"7b655f8783a74d59cda30273784869597aa3640da8f2d0da9d96ef65985c2925\",\n        \"size\": 68828446\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14954_Weather7.tar.gz\": {\n        \"sha256\": \"7635d4aaf9bc1fb45d8e070a70dfeba3e82596dd8e12c0d4291af38c534daab0\",\n        \"size\": 237215725\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14955_Weather8.tar.gz\": {\n        \"sha256\": \"90f3644abf3e9600a751dd66557aad34753eac98b24e4f78e3c7e45c198bacad\",\n        \"size\": 205117999\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14956_Weather9.tar.gz\": {\n        \"sha256\": \"60c7c7c9c5586b0e9da4c5efc7303498909bcd99f4e2562f64dd7144bfe82fb2\",\n        \"size\": 112552986\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14957_Weather10.tar.gz\": {\n        \"sha256\": \"fb799a73adb15eb595bf8ef003e306c287ba28e2530418754fc184e04c8e8d9b\",\n        \"size\": 210357795\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14958_Weather11.tar.gz\": {\n        \"sha256\": \"eb62166196fed20ff8b59c16cbf154c59955d63cc79ac6487f79ac32b9f742f8\",\n        \"size\": 336585477\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14959_Weather12.tar.gz\": {\n        \"sha256\": \"6a226f9739cfc98f589d237f8385f4ae53dab4e0f51a72941febcf1a2ef53029\",\n        \"size\": 263887749\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14960_Weather13.tar.gz\": {\n        \"sha256\": \"8816e8ac5eaf11ecda5dedeb7d88a718efee1598331a54d0f462c33cdc366031\",\n        \"size\": 435182235\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14961_Weather14.tar.gz\": {\n        \"sha256\": \"c64b5425b127634b8fae697c9c14ceb65f17f9fe292a766856a4e80b0d4de3e7\",\n        \"size\": 77889962\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14962_Weather15.tar.gz\": {\n        \"sha256\": \"dee5fe3713a152f997ac2db8721be8e9ba9d913bc8d0e143f10d2af0b6b70251\",\n        \"size\": 64294422\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14963_Weather8.tar.gz\": {\n        \"sha256\": \"c9d411cc00bda72c5b1a348aeb9ea261db8da491a66ce56f909533a4e2d4f884\",\n        \"size\": 283195280\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14964_Weather9.tar.gz\": {\n        \"sha256\": \"b0773bac82e9e92f8a5084024e9795d2c3a472f0a8c2ee4a6cb2cff986bcb5a3\",\n        \"size\": 411736012\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14965_Weather18.tar.gz\": {\n        \"sha256\": \"4d07117afe15a91cc7e71a7aaf51896372ebd4811000507a9bf35a8a0305f4ea\",\n        \"size\": 230585706\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14966_Weather19.tar.gz\": {\n        \"sha256\": \"f93abcdc0527016a0af8c2899e41de77ce203fe68e44a87b6bcf6896acded723\",\n        \"size\": 101667301\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14967_Weather20.tar.gz\": {\n        \"sha256\": \"dd9734814c251c967725f20b26abec676b3d3dc6b7c95a9cf633d6be972af97e\",\n        \"size\": 320239704\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14969_Weather22.tar.gz\": {\n        \"sha256\": \"842427961cb6180d267031d502a10d4cbf9a74b1c60ae10d8e427efc5ed0bd30\",\n        \"size\": 74867527\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14970_Weather23.tar.gz\": {\n        \"sha256\": \"7892930e2d0cc89d6c371a7fd0ca1f0f0de87ad819577e9c42a334bc03ee7983\",\n        \"size\": 218882297\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14971_Weather23.tar.gz\": {\n        \"sha256\": \"6d67e2746718cc68cbc25f22f0750e61bbf32ddb910e4498a931f806043a49f3\",\n        \"size\": 425347298\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14972_Weather25.tar.gz\": {\n        \"sha256\": \"77d5d7a5ae20e95d53371b5b70b50a96abd6ac80998f01c3f40b2aa28722bf6a\",\n        \"size\": 77686110\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14974_Weather1.tar.gz\": {\n        \"sha256\": \"d4d30e17907b85747d9cec6abf6020a497517f67daa9ce63e4078a484955de7f\",\n        \"size\": 249720805\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14975_Weather2.tar.gz\": {\n        \"sha256\": \"ac58d431dc075ccd11e97600d5986628118f22dca909eb213c12e2ea3fdbe11d\",\n        \"size\": 245839453\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14976_Weather3.tar.gz\": {\n        \"sha256\": \"4d68e9ec11dab556faee5d75a22a9674745c9439fc4632e1372c514cd0fa9c1e\",\n        \"size\": 205947583\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14977_Weather3.tar.gz\": {\n        \"sha256\": \"4b899354c4e60199bd183cc53439968414b472d8db62476a659a8546fb5e940b\",\n        \"size\": 184037577\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14978_Weather5.tar.gz\": {\n        \"sha256\": \"a3454b61aca155a2429ea0329d3ea3501da87f7df15c4f1cd58035dc0cf66e5a\",\n        \"size\": 316801747\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14979_Weather6.tar.gz\": {\n        \"sha256\": \"d6ffe4a417aeb1f6df36797e2518e2e9eccc06e5631fb6fd62cfecb8c19fd707\",\n        \"size\": 178439362\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14981_Weather8.tar.gz\": {\n        \"sha256\": \"46d3edae4de3c2f6273ae1c9b934f6df0a2030f2d8ca017d4e99b379892add42\",\n        \"size\": 1227354361\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14982_Weather9.tar.gz\": {\n        \"sha256\": \"220f2bac43c151ade306c70d2dab3867e0081dbdf559c187c693c2a8e474ffb1\",\n        \"size\": 288507578\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14983_Weather10.tar.gz\": {\n        \"sha256\": \"b5e8c9ec2d1f2f2029be6318a6304c9303d639597241a478f3b3d6cef700127a\",\n        \"size\": 245913015\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14984_Weather11.tar.gz\": {\n        \"sha256\": \"d363f0bb4831d54cbee2948b811bd1a33203a3c0c8942057eea71b66ec837de0\",\n        \"size\": 638937753\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14985_Weather12.tar.gz\": {\n        \"sha256\": \"fc87d472f623900b4e552a86f8c9cbbef7559dbc211ec910c5437ada8cee3734\",\n        \"size\": 67112651\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14986_Weather13.tar.gz\": {\n        \"sha256\": \"6b785d3ebf9cf2001054e63ecfe62d1ffc9c1040e8415432d1d28492f6f97294\",\n        \"size\": 366191299\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14987_Weather14.tar.gz\": {\n        \"sha256\": \"11fc05a651f12ef29ebd835ea42100ee73be95bb3b536fe11b0995b7b32cde57\",\n        \"size\": 204765564\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14988_Weather15.tar.gz\": {\n        \"sha256\": \"08fdece8f319d3fa60208c456ee08cdf1529b0c2b7a59de9f185f902577f6775\",\n        \"size\": 222099452\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14989_Weather8.tar.gz\": {\n        \"sha256\": \"8887be1b2d332e1d41117325614afe25f19849ceac8ec95e528be826deb8e390\",\n        \"size\": 432542335\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14990_Weather9.tar.gz\": {\n        \"sha256\": \"b40788c57aeaf48f8755b8ce086181be549a6da2dd89186c3dcf6de9a00e61e9\",\n        \"size\": 194362237\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14991_Weather18.tar.gz\": {\n        \"sha256\": \"33be90719bae2c9bf466dd03fdfbba1a48a4201d71e4a8c20feb9d902d5c6b44\",\n        \"size\": 349419186\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14992_Weather19.tar.gz\": {\n        \"sha256\": \"3a02b795da5f2229e062ed83f223dedb4b77e9d9f13dd4e98bea4f555253d4a2\",\n        \"size\": 198310410\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14993_Weather20.tar.gz\": {\n        \"sha256\": \"14a2cbb5bc852cd294593826dddfc6db338f1590d18cff6b8dccf14466bdf433\",\n        \"size\": 475763975\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14994_Weather21.tar.gz\": {\n        \"sha256\": \"d333c98a16c41f68ab0d9f4fb78a7f3051b4d068ace8478726aedd827debbf15\",\n        \"size\": 240151427\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14995_Weather22.tar.gz\": {\n        \"sha256\": \"387223464ff60690007be0210647275e3267f343506a244d3c8ed07be2a542f6\",\n        \"size\": 562338687\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14996_Weather23.tar.gz\": {\n        \"sha256\": \"2bbaae75107954d198374e364b01cdfbcd4b079d9d4bfa853ef5a6a390f894bf\",\n        \"size\": 184283414\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14997_Weather23.tar.gz\": {\n        \"sha256\": \"f4f5ab2c6e04fb96d2c8880d83c3dfdbf5836d39b7ee871c73cd76ade53f30ff\",\n        \"size\": 345862350\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14998_Weather25.tar.gz\": {\n        \"sha256\": \"dcef87f56a7b4bb198073eab081df8933e437e577411d374054f36ae2721db96\",\n        \"size\": 365553612\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route14999_Weather0.tar.gz\": {\n        \"sha256\": \"49a34a65f1d65e1e11a55e692eb48db5ec8bf167d7a038008dc6886d077b8c97\",\n        \"size\": 266787008\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15000_Weather1.tar.gz\": {\n        \"sha256\": \"c4918735d5906f0b5b2ce0dfc1d25fce1a3cf301afb90315d2b46d2edaf1d02a\",\n        \"size\": 573151127\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15001_Weather2.tar.gz\": {\n        \"sha256\": \"0a0e423e453045660d74b240df4d8f53759dc9c09b07ea4c3bce3549548f8227\",\n        \"size\": 260410450\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15002_Weather3.tar.gz\": {\n        \"sha256\": \"1607ca681d5200740efa3b6ba583cb9067b373ad76c8d31786dd57e27cd1acd6\",\n        \"size\": 250577141\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15003_Weather3.tar.gz\": {\n        \"sha256\": \"5d5d91739f29e922595cc5cf2c98e7a63d197a976001d0df4d7907ec6da9a7f4\",\n        \"size\": 231208350\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15004_Weather5.tar.gz\": {\n        \"sha256\": \"397805d4cb8a4a97c6b5889d31e51ce3662e06c373c0ea99073e2a0a93001fdd\",\n        \"size\": 336303440\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15005_Weather6.tar.gz\": {\n        \"sha256\": \"06f9daf7de11ae645edb150b4e9099664158c7c9f4e8d801beb6a56a77963c9f\",\n        \"size\": 82141073\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15006_Weather7.tar.gz\": {\n        \"sha256\": \"6d672447629d46e336d182523f5a0ba6e30d2876c0145e0e7574b409e7442154\",\n        \"size\": 128344845\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15007_Weather8.tar.gz\": {\n        \"sha256\": \"cee87fdfdc5f1f246c792508983549a7d3426cab0f12e6f7cf31c175bcf21130\",\n        \"size\": 485677758\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15009_Weather10.tar.gz\": {\n        \"sha256\": \"66a297d70f5eeb198d4137eb7a95395a75eda98d4a6396d5cd461ee466fafc8d\",\n        \"size\": 92541182\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15010_Weather11.tar.gz\": {\n        \"sha256\": \"6c621c923433439cd0868c8bd3857e4fe71871c53e31f5aa415ba7bc42476891\",\n        \"size\": 191714512\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15011_Weather12.tar.gz\": {\n        \"sha256\": \"9bce7a5a1ee8b04eff3e09f09937578833aa747c5eaf8bc381a71131fe1e8e1a\",\n        \"size\": 90481106\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15012_Weather13.tar.gz\": {\n        \"sha256\": \"071b2779ee2c7b8c091c6133272d3f5979455cafa478cc451e1807e40ea25fcc\",\n        \"size\": 340074472\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15013_Weather14.tar.gz\": {\n        \"sha256\": \"bbd4b5709f8849f09afe9f07ea149780c48417c561b6321d8c18622e8a9fc0b5\",\n        \"size\": 321105880\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15016_Weather9.tar.gz\": {\n        \"sha256\": \"7b27865fed445c57e9b01fe82c1a3321ffddb143cbd76d91a9652be7d3b68c5f\",\n        \"size\": 272262506\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15017_Weather18.tar.gz\": {\n        \"sha256\": \"5bc62dd114f6c49a36f9339fe61389b1acefe72149b601219ee1d626ea136690\",\n        \"size\": 237441201\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15018_Weather19.tar.gz\": {\n        \"sha256\": \"deab22a9ee648e00e0ad4352b124e1e25a7ca698681a9800491adbcbc3a2628d\",\n        \"size\": 497428330\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15019_Weather20.tar.gz\": {\n        \"sha256\": \"2ba686e054f3d72fa574b6318372fcf68be53d44f91ab176316d4f653544cc20\",\n        \"size\": 429506356\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15020_Weather21.tar.gz\": {\n        \"sha256\": \"49a217d4c54dfaadb3fff661a92c13454d82e24294385f912d949eb5e65210e3\",\n        \"size\": 406684279\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15021_Weather22.tar.gz\": {\n        \"sha256\": \"0df314599bd322cac44b00c255b8908191fbfa24ff0ccc0d3ba0fb6e56b39981\",\n        \"size\": 509865944\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15022_Weather23.tar.gz\": {\n        \"sha256\": \"a028cdf0d89fa02cc813279989c6718c40e204f2d1a73046dec50030fc30b094\",\n        \"size\": 206232377\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15023_Weather23.tar.gz\": {\n        \"sha256\": \"a1da3f1b1d99481b3589b21caeb4230ef63105a95ab861c6fddb6a50691b663d\",\n        \"size\": 237013587\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15024_Weather25.tar.gz\": {\n        \"sha256\": \"c5c7e1814c69cbc751e7e6b06c823af6c62eea9c1aedf8f7d1755f7b199f8e64\",\n        \"size\": 249086145\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15025_Weather0.tar.gz\": {\n        \"sha256\": \"4714396448052f88183557359e1b36bbd1f884bf4c759906b04665c21e4e42bd\",\n        \"size\": 801560929\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15026_Weather1.tar.gz\": {\n        \"sha256\": \"eacb18a38663d89d91c5b086e7905bd353ab40253a3d5c11603d8e5c6d40822d\",\n        \"size\": 104463454\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15027_Weather2.tar.gz\": {\n        \"sha256\": \"f48c7d1a7a8e4ce9cd91759c72591b3d19dd422ed7f5154da8a8260dc61f3178\",\n        \"size\": 358574465\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15028_Weather3.tar.gz\": {\n        \"sha256\": \"f7ef3ee07dacc8c71470039d5363a019ad526899096e19057c73fb987a95ed32\",\n        \"size\": 431835014\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15029_Weather3.tar.gz\": {\n        \"sha256\": \"fbc649a66933d24f3090d731ae16fafe6368f2d68fb611ce28cf068fe04e73c5\",\n        \"size\": 99622392\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15030_Weather5.tar.gz\": {\n        \"sha256\": \"eb8e6e60bdc50549b7f841453f61fe1029090de3cd35402ce5d7de9060337773\",\n        \"size\": 170863712\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15031_Weather6.tar.gz\": {\n        \"sha256\": \"b1f0d6bf439c121f052c08f9096cf3190c5a03c9a10e640cf6d0612f1b6f8db8\",\n        \"size\": 68039452\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15032_Weather7.tar.gz\": {\n        \"sha256\": \"994412ceea8d56df9e277d9c524a0a59792ed4e58076ad73e055ede1ff3cb3f1\",\n        \"size\": 413957533\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15034_Weather9.tar.gz\": {\n        \"sha256\": \"375fab9de09f00daea10fd8d5c25e4506a8ac2b8c6df8d2db8c63f6b4e3f5c7c\",\n        \"size\": 75246959\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15035_Weather10.tar.gz\": {\n        \"sha256\": \"2b217a96440dfb7670644f42cdb69029221e6e38df4f32d6cad5ccf90576aceb\",\n        \"size\": 464722543\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15036_Weather11.tar.gz\": {\n        \"sha256\": \"a416479e2f0610eda597fdd5c597a048e96181cfc24d7c9787c69f6316808d9c\",\n        \"size\": 75379362\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15037_Weather12.tar.gz\": {\n        \"sha256\": \"0b384255df9ca70ee246c0af64dba461192921e165cb0863f6871e5ab0ff6129\",\n        \"size\": 368187526\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15038_Weather13.tar.gz\": {\n        \"sha256\": \"05fe2b3d617c0e1355d157a7be011cfaeb639a007a6ca5638601b5470d22df7c\",\n        \"size\": 126328826\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15039_Weather14.tar.gz\": {\n        \"sha256\": \"151f4f20cfbd9378258e69a4a468fb16bcee6e942d88af4fd78332709b4c18e4\",\n        \"size\": 87530245\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15040_Weather15.tar.gz\": {\n        \"sha256\": \"1ded276ef578b82414d9bec92c651105d00f881883675976e0d0002de2b7bce4\",\n        \"size\": 281115997\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15041_Weather8.tar.gz\": {\n        \"sha256\": \"606a8fbc361479afd0e79ddd1684c99238da043dbdf072eedc0a396fdf7c386e\",\n        \"size\": 97809187\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15042_Weather9.tar.gz\": {\n        \"sha256\": \"2d2098e3f1adacd1c13c0cf97bde581d255763fc8c6c5c8653ff10bb0f38f195\",\n        \"size\": 262717068\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15043_Weather18.tar.gz\": {\n        \"sha256\": \"86f87c1966f544367923559292bafac532e0b5a8407f4c45e8efa54329941c15\",\n        \"size\": 83769529\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15044_Weather19.tar.gz\": {\n        \"sha256\": \"b9c7484c1ce50414d1ef3e030ba2392a553c0c9fc8776239f9d497c27912defc\",\n        \"size\": 70796452\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15045_Weather20.tar.gz\": {\n        \"sha256\": \"7012739aee1316ef578d47402b9d231a460258c4347a476b9f009c6f6b989e1a\",\n        \"size\": 525287917\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15046_Weather21.tar.gz\": {\n        \"sha256\": \"f03d4071de1cba314526fa9de7721d286b3c55b3f0151c7c9bde70ccc1af5ca6\",\n        \"size\": 155201272\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15047_Weather22.tar.gz\": {\n        \"sha256\": \"a10b6bbf4b395411ac05e4fa2a698e9ae3c633a8d7d2ee78dc785f806aacec76\",\n        \"size\": 82667598\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15048_Weather23.tar.gz\": {\n        \"sha256\": \"6ee4ab7399b4b3e38efe16ec2321bd6ffddab19efab7fdb95a4cd8d83ad1cffd\",\n        \"size\": 259787839\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15049_Weather23.tar.gz\": {\n        \"sha256\": \"8725959728fadce86fae6415af737cc5d267174177932e483cabfe55b5c6ac47\",\n        \"size\": 76278294\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15050_Weather25.tar.gz\": {\n        \"sha256\": \"2c48634022644a85229644b45c09e3ddf412e5d92237e31f1d74d597cacf850f\",\n        \"size\": 176091274\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15051_Weather0.tar.gz\": {\n        \"sha256\": \"b88e01d8fbded1b39f0191626d14fd0bc975803e0e38f65cdcc3be2dca80adc5\",\n        \"size\": 91294440\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15052_Weather1.tar.gz\": {\n        \"sha256\": \"840411861ea98f270b0f5a8403a92cd5f1c4642bc896383c340db4c190e65057\",\n        \"size\": 101934888\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15053_Weather2.tar.gz\": {\n        \"sha256\": \"61ff103e7de8775948750cfccf0eac4bdb178780b0f99ef668297ee1265a1e1b\",\n        \"size\": 444139368\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15054_Weather3.tar.gz\": {\n        \"sha256\": \"8c10a8c97d5f6f4b433934f5dee7daf1dc24db25613cfac2a9a38b7c8a128d90\",\n        \"size\": 70405370\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15055_Weather3.tar.gz\": {\n        \"sha256\": \"c263b487916252ac78259ced1e5b31374e97941d23fbaeb76e3c54cdc3779a7f\",\n        \"size\": 435267316\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15056_Weather5.tar.gz\": {\n        \"sha256\": \"8281ba76036f48704e8fc3c64c629e83065c7c8aebca6645c3b7bd8049043af4\",\n        \"size\": 242115455\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15057_Weather6.tar.gz\": {\n        \"sha256\": \"43aed5f11d160e258203af5e85160a5e80582b14bcf59a979b7840fb5a2bd739\",\n        \"size\": 91447686\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15058_Weather7.tar.gz\": {\n        \"sha256\": \"83a93d76fe4e228c6a21718d219caea272844a36ea889ccfbf3cbcc2ba56cb0f\",\n        \"size\": 266313825\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15059_Weather8.tar.gz\": {\n        \"sha256\": \"11c49690cc5ba65cfdbde83dd0fa311f2b556d01b9080276ef10b71b35b7a5fc\",\n        \"size\": 436291561\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15060_Weather9.tar.gz\": {\n        \"sha256\": \"8b281aee075ac451fd292683e044afdcd5e477e63942d9a401c2b352b59f5136\",\n        \"size\": 501844541\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15061_Weather10.tar.gz\": {\n        \"sha256\": \"7d752db4084e41a16dccca26cc9ad53cc8099f3d37fb22d80646055424aa90ef\",\n        \"size\": 433385864\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15062_Weather11.tar.gz\": {\n        \"sha256\": \"e2437130a89bc54cde94ea19fd29aad9f984f2bef6cf2b6196de3726e9216c7d\",\n        \"size\": 60195446\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15063_Weather12.tar.gz\": {\n        \"sha256\": \"f751c1fbd4a21b3d5c95141c719803808b40c540ae2dc26ee2c7e3be77ab34f9\",\n        \"size\": 328399286\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15064_Weather13.tar.gz\": {\n        \"sha256\": \"3aaacfa920e4c4c5c53df59b18cd09f6fb5169b3a3f557b508ccfecc2a3b8c43\",\n        \"size\": 269298348\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15065_Weather14.tar.gz\": {\n        \"sha256\": \"5aae20f4f3dd56e46d82a27c6d56f3c328c146eaec8f1b4b0918caaacbf0f105\",\n        \"size\": 196166201\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15066_Weather15.tar.gz\": {\n        \"sha256\": \"42eed6d83bccb7660d648824ef1b832ca5e2c0eaef800ee28bb092040220739c\",\n        \"size\": 73025116\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15067_Weather8.tar.gz\": {\n        \"sha256\": \"0293f47f1c4f6662ada2b66852158714d215f0cecc84b5d4b33b60af43bda0a8\",\n        \"size\": 295770778\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15068_Weather9.tar.gz\": {\n        \"sha256\": \"312d83c8078c71dbc37bba5c84766eaddf8b54ba4cc4f1fbfa3448c32bcdfd24\",\n        \"size\": 72655644\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15069_Weather18.tar.gz\": {\n        \"sha256\": \"fa8d85b43798e1d6b55b00698107e5ba239b9ee3b02002f8f8b8e08919491ad7\",\n        \"size\": 96820076\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15070_Weather19.tar.gz\": {\n        \"sha256\": \"cde4dc9694f29b73930fce7c25b6a61bf4c0e3935488c4e09a7911af97df0ec9\",\n        \"size\": 258914575\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15071_Weather20.tar.gz\": {\n        \"sha256\": \"5e78bffa2eaa64d39036c21efed8ff7da1d9b2bd79840bc857b70a491a732dfe\",\n        \"size\": 557126160\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15072_Weather21.tar.gz\": {\n        \"sha256\": \"f12f393ce6945eb259e19675f68ff93a9ea283a55a4f2871ab1fd8f1d4c34f9b\",\n        \"size\": 296142381\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15073_Weather22.tar.gz\": {\n        \"sha256\": \"12accad43a29f28fb144a557367e40a5c466e1c4dde31d5eae8bc8cf51cfb005\",\n        \"size\": 216471825\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15074_Weather23.tar.gz\": {\n        \"sha256\": \"a8d4c91e7501566bf7e0c2952eff8abc17e8d6f5cd46f3c405e14ac866ef4478\",\n        \"size\": 233965607\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15075_Weather23.tar.gz\": {\n        \"sha256\": \"10a13786979ff7a00da6e315c6e3d1a5cff381bfa55d22006f8def62b7ae5589\",\n        \"size\": 94503630\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15077_Weather0.tar.gz\": {\n        \"sha256\": \"898299646629aa28f53072fb2508549b6fbebae914cea7803e5748dae1a17ce2\",\n        \"size\": 213196076\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15078_Weather1.tar.gz\": {\n        \"sha256\": \"f5638cb2156becd5a7d88dfd6731eea1ed8d50707877c5dd998cad6a4dc8029c\",\n        \"size\": 881392343\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15079_Weather2.tar.gz\": {\n        \"sha256\": \"5b854a6b13f1b953e6f5fa0a315a818fed085766b83aa9fba40bacc1e4040d49\",\n        \"size\": 396338419\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15080_Weather3.tar.gz\": {\n        \"sha256\": \"4919f2146bc6901b1af593ee4ab90a618515ef335b8ee5364e05ec31588269ea\",\n        \"size\": 68747840\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15081_Weather3.tar.gz\": {\n        \"sha256\": \"985b8312b69b59e58bc5259fb045076348ec9a21414a524b453d506c23c64b77\",\n        \"size\": 189990157\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15082_Weather5.tar.gz\": {\n        \"sha256\": \"f59940f3042940378bed81b1f8e15f90e6c4e6184f9d8b14010f2d5e647b60bf\",\n        \"size\": 431263097\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15083_Weather6.tar.gz\": {\n        \"sha256\": \"46e97fbe39443d1189c105d503889896a9d55fec31946d34a7a364dfdee3e9c9\",\n        \"size\": 522427711\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15084_Weather7.tar.gz\": {\n        \"sha256\": \"c7f12a72fa8caa8c7b64f8753b0d1df690b8ae8d4489fce7d5448c9b41da4be2\",\n        \"size\": 556827504\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15085_Weather8.tar.gz\": {\n        \"sha256\": \"d1d91749e70d8324ca9b208ebbeeeb0d897d84e9e4475d2cf43d1806d370f20d\",\n        \"size\": 70310261\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15087_Weather10.tar.gz\": {\n        \"sha256\": \"880eb9eafc55b77a659933c3cb839ea3c0e324cf1146d9c51d1bdeeb68a8c7ac\",\n        \"size\": 475314811\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15088_Weather11.tar.gz\": {\n        \"sha256\": \"d1ecd822c22ee87cf79c11eb53c0fbb6b68c280a6f3c333370e8f212d03a1fe2\",\n        \"size\": 364355967\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15089_Weather12.tar.gz\": {\n        \"sha256\": \"4dab5ad6f0e033c963084762fc5014dcdeffc0331040a664521846e6bb3012c4\",\n        \"size\": 143724018\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15090_Weather13.tar.gz\": {\n        \"sha256\": \"6d36f820dece2d2207db909e8cee509baa1b0142bb5ca7d9085095858da1c6cc\",\n        \"size\": 181356996\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15091_Weather14.tar.gz\": {\n        \"sha256\": \"96b8c53ba1273b0ba64b65fd83b473a354d63b65fb93639c93a8dd07076f13e8\",\n        \"size\": 380236399\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15092_Weather15.tar.gz\": {\n        \"sha256\": \"f09c61b9fcdd8206da2215b9233d2ec65279424c0fe6e647d1a6546baef3d4df\",\n        \"size\": 60861407\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15093_Weather8.tar.gz\": {\n        \"sha256\": \"07d282a96404afa8edc6909cd2103aaa9a417d12c2d78af6b6713ffaeb52bbe0\",\n        \"size\": 75836095\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15094_Weather9.tar.gz\": {\n        \"sha256\": \"eb94437a24440217d4c1bad63183a6b34a9fe7f5ce35ba54f5389dc537c160a4\",\n        \"size\": 243668594\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15095_Weather18.tar.gz\": {\n        \"sha256\": \"944e5538a54eab5c4efd820a89435220328113a9ba41511ef8c498535923d53c\",\n        \"size\": 660532004\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15096_Weather19.tar.gz\": {\n        \"sha256\": \"a018bd75b964342ffae2d537600aaf2b4459cfbea9c295579250811082f479a6\",\n        \"size\": 499915632\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15097_Weather20.tar.gz\": {\n        \"sha256\": \"ae8751495b0dc1600b99970647dbc83e419f0318287211e0ecd5ada3bae6164b\",\n        \"size\": 642132262\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15098_Weather21.tar.gz\": {\n        \"sha256\": \"c9fedc1fc036e9ec869fcb4f930adfeaf144af7bf24d02dd3c26ba5af14a32ff\",\n        \"size\": 522220379\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15099_Weather22.tar.gz\": {\n        \"sha256\": \"935093c510f0d53b310acda62dff2e60128fb1d4038304538f196cb3dd6c2464\",\n        \"size\": 189353284\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15100_Weather23.tar.gz\": {\n        \"sha256\": \"a91a25c8270c1aa351c2259121430440cdaf30010df7a3db685d45f02edfab97\",\n        \"size\": 423205460\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15101_Weather23.tar.gz\": {\n        \"sha256\": \"0180f4a4e14664d71b5c2a57f22ea394d7c762a60e8ca46a63092699966772f5\",\n        \"size\": 345218004\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15102_Weather25.tar.gz\": {\n        \"sha256\": \"ace0db94dfd0562c3062493ff203e3df1ea3e7ba2a0c28fae9db8e2012e8be13\",\n        \"size\": 298494390\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15103_Weather0.tar.gz\": {\n        \"sha256\": \"b8dfbe809d2f418ac55056b674004d8912db788beefcb54b04e613d06c9b2ce1\",\n        \"size\": 224703575\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15104_Weather1.tar.gz\": {\n        \"sha256\": \"ea46952857308aae161a0db7838ffaa6e54e70a82a3a74390daa38d694cab9d1\",\n        \"size\": 562557527\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15105_Weather2.tar.gz\": {\n        \"sha256\": \"305f401e285aa0c4a6e7a28a790604a6f52368f3622bec6d1fd154d3f4d49d8a\",\n        \"size\": 175520232\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15106_Weather3.tar.gz\": {\n        \"sha256\": \"8f9680d851fcc45d8a302ec998776376f4be051d8d4c7ec13f159c26a7087f2f\",\n        \"size\": 217415646\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15107_Weather3.tar.gz\": {\n        \"sha256\": \"038acf6f8550f14129aad8425869bc10a83eb7945d2445a6fd4f716d5f6ecbbc\",\n        \"size\": 410561868\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15108_Weather5.tar.gz\": {\n        \"sha256\": \"98b4ea0334c4657da09a89534e6cde2bddb50fa5aacdbfe0fb8190481a978ded\",\n        \"size\": 358164985\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15109_Weather6.tar.gz\": {\n        \"sha256\": \"946688e35fc693306990929cccabd64665c004f2b7664e67384a31ed03009ccd\",\n        \"size\": 490484105\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15110_Weather7.tar.gz\": {\n        \"sha256\": \"7ee0da048bb1c2d7e8a3f29a57ae51c7d35bab21ce53e1dc69e1377b1c0708ac\",\n        \"size\": 82837150\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15111_Weather8.tar.gz\": {\n        \"sha256\": \"6a79e460e1d4ba87ecddb8835a5751ef83d17fe2c6fbd9b593007bf1b0bebbc3\",\n        \"size\": 281752060\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15112_Weather9.tar.gz\": {\n        \"sha256\": \"d38ee1de824eb95d563eba7f607ddb23fdd8a219bb8d7732073c1b8fcd78411b\",\n        \"size\": 375955520\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15113_Weather10.tar.gz\": {\n        \"sha256\": \"514ab54d91aeb0189033a651f571427280a4a55b4d650bb049899f9dd409c019\",\n        \"size\": 97110736\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15114_Weather11.tar.gz\": {\n        \"sha256\": \"d47b75c2b6663dc4cd5ad428e4ef8920d3e6382a75b3ab4615cd10ae1ec9695d\",\n        \"size\": 251363971\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15115_Weather12.tar.gz\": {\n        \"sha256\": \"270a7221ccc8641a9ed3eeb1cff3edf8eb2a7d8ab6e802430ed346fdfd92f8a5\",\n        \"size\": 383518937\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15116_Weather13.tar.gz\": {\n        \"sha256\": \"9143677f7e087fa9fd41ebb2fdd8c89eac555d42e8df5a68a93826fbbed9ccd0\",\n        \"size\": 439303476\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15117_Weather14.tar.gz\": {\n        \"sha256\": \"b2036f646886ebf4217c0aacdf689c5dbae24f01a636eeb78d353959e17eca80\",\n        \"size\": 629357132\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15118_Weather15.tar.gz\": {\n        \"sha256\": \"6bea7cf257ced958124d233b3d8a3311b17e527f3db01e5dc0a94af96dc9fa0f\",\n        \"size\": 439182039\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15119_Weather8.tar.gz\": {\n        \"sha256\": \"bb5bb5c5e383feac9b9ce5a78e86355664c70278fb04d11b36dee87093dfc4b8\",\n        \"size\": 562078258\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15120_Weather9.tar.gz\": {\n        \"sha256\": \"1df71a285a6b3abed0fb559cbcd1e682a41be18a0e7c0d607f2f3b6b9d8e22e6\",\n        \"size\": 70013921\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15121_Weather18.tar.gz\": {\n        \"sha256\": \"0b37d3f1f9aa0fd682747abe57cd6cb7f20735c3fb0340989b210b6689d8f02a\",\n        \"size\": 240739535\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15122_Weather19.tar.gz\": {\n        \"sha256\": \"1a14fe98af590c06dc6d416f020561e11b1afa8d63c1f1a048fb9fb4696b6e37\",\n        \"size\": 253221644\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15123_Weather20.tar.gz\": {\n        \"sha256\": \"5b742d061807b1e515266709f9d85ac492c4fef76faf58ea9ec1df8d68d5d412\",\n        \"size\": 304849969\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15124_Weather21.tar.gz\": {\n        \"sha256\": \"c8fc5473abeb4a8da6928bcfcf2d354179a3c3c65124d68c692d4fa8b5064997\",\n        \"size\": 150882982\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15125_Weather22.tar.gz\": {\n        \"sha256\": \"697a407100201de024c7cbf796190cdd79c9b2dffe34fc38c96010c3e8de4886\",\n        \"size\": 67195600\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15126_Weather23.tar.gz\": {\n        \"sha256\": \"7a7a6751adcb4a4d54b930f9bd8718cfd210dbbee006b244f71554b7a64b94e9\",\n        \"size\": 90370641\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15127_Weather23.tar.gz\": {\n        \"sha256\": \"1b8366bb8bc0a7c6602a2a93157ed16d9b009738650fac1b3d7a765fd6826618\",\n        \"size\": 64116885\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15128_Weather25.tar.gz\": {\n        \"sha256\": \"2f0a55967f6e405eb4729de0978d3345d04103416a4cae5c5112a8c1182d21e8\",\n        \"size\": 158549946\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15129_Weather0.tar.gz\": {\n        \"sha256\": \"7a2c22e3df0646bfc7ce48454474e3b14bbd1c702652e68f87cd9dcc2175f9b8\",\n        \"size\": 108116581\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15130_Weather1.tar.gz\": {\n        \"sha256\": \"54b0c2f0567dcaee9af503986f3283ddfbf695e16979207e0d41e40ba214bda3\",\n        \"size\": 96698969\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15131_Weather2.tar.gz\": {\n        \"sha256\": \"3d2982543fecc3ae98e315881e4e3acde6d8c7269730be9cb52bd70bc79921a9\",\n        \"size\": 206041844\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15132_Weather3.tar.gz\": {\n        \"sha256\": \"8c16d22181777e1750f4609c16e455e84e89b00e774cd421c5d6044d9b964527\",\n        \"size\": 508519290\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15133_Weather3.tar.gz\": {\n        \"sha256\": \"f809bd7284cd891f9f9878c79f80cece80a7a5335a6cd80137e88f6cdfca9088\",\n        \"size\": 493137991\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15134_Weather5.tar.gz\": {\n        \"sha256\": \"742640a295e07bc34a1e98953b5c5cbc4aff7b47d8762d1d3bac35c5174e39c8\",\n        \"size\": 198124766\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15135_Weather6.tar.gz\": {\n        \"sha256\": \"043d8981c6614537b4bcac1b71b0d2bc9a1db2fce144bc35ffef777ff7efde65\",\n        \"size\": 516327415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15136_Weather7.tar.gz\": {\n        \"sha256\": \"bb28c15fe014bc9b9f8c926461c817735c4e1d27c31aa7389b6b9988289c2c0c\",\n        \"size\": 224866966\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15137_Weather8.tar.gz\": {\n        \"sha256\": \"57dbc09445f39fbcd7dd589d1e84374cf6040843e51e1c412d6da8ea84c2dff2\",\n        \"size\": 327040641\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15138_Weather9.tar.gz\": {\n        \"sha256\": \"f7081f90e178b7c80a0c4416d883da748d87f2579c839f0ec4e17572582fa918\",\n        \"size\": 67209844\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15139_Weather10.tar.gz\": {\n        \"sha256\": \"e6e4f48c2df9b44ff14a030427676cc0f17857fe01ba1e86d1476aa73b99179f\",\n        \"size\": 410765104\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15140_Weather11.tar.gz\": {\n        \"sha256\": \"36630e9f7764e9f86d5c9efc2815a57748c9e209f6487c6ee2cf9fc1b4c45f96\",\n        \"size\": 292291177\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15141_Weather12.tar.gz\": {\n        \"sha256\": \"daa89e760b60a2f5fe69ab872f00f3461f5b8db54f838567655ef749cd928251\",\n        \"size\": 369652384\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15142_Weather13.tar.gz\": {\n        \"sha256\": \"abe091adf483cdd9b6c659c7ac21832c735fdb6f2c2f1e915d2103a3ee7a45a0\",\n        \"size\": 287721263\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15144_Weather15.tar.gz\": {\n        \"sha256\": \"8234378934a2afee6b51332a035fee7a9813ff4fbafa6e69c522ee48c5b744c1\",\n        \"size\": 293302046\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15145_Weather8.tar.gz\": {\n        \"sha256\": \"f09256dda1c6e53efeb6f6927c92ba9da205d15a3ea08f651e86745275ec0095\",\n        \"size\": 85982121\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15146_Weather9.tar.gz\": {\n        \"sha256\": \"16f2a5a2fbd52b72ae52913533a0aad50a66bfb94f6ff9cdfd031801b4bb4350\",\n        \"size\": 285105492\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15147_Weather18.tar.gz\": {\n        \"sha256\": \"706c7e9f3e6f6097561de25626531b0ecf87fcdae1485b240f54092e7276b9a6\",\n        \"size\": 294017129\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15148_Weather19.tar.gz\": {\n        \"sha256\": \"0e7cd51c2454eeb30e85587cb83d08ad6163061bbe43001627d1cfe0659e3ffa\",\n        \"size\": 249328651\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15149_Weather20.tar.gz\": {\n        \"sha256\": \"2731c686412b948fed5bff6e3006c5d54cff7cff4a3f9a226b47107e4002bc3f\",\n        \"size\": 479058896\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15150_Weather21.tar.gz\": {\n        \"sha256\": \"93115f26855512c34fafbe86d2f9c910a494f210d5570ae22cca4d8595eec8c5\",\n        \"size\": 117579309\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15151_Weather22.tar.gz\": {\n        \"sha256\": \"ff945888b50041ff5f28487ed38ed0939241442e319b394cbb25e27fad4d628b\",\n        \"size\": 528328290\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15153_Weather23.tar.gz\": {\n        \"sha256\": \"2b957f2bec56004167f775ae8f0207cfb95cf69d426c23a00f3acfa2fe961068\",\n        \"size\": 258701647\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15154_Weather25.tar.gz\": {\n        \"sha256\": \"5f170f2048fedeef24c2a432221fa56af343477dd4942e835017ffa04759c556\",\n        \"size\": 240854254\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15155_Weather0.tar.gz\": {\n        \"sha256\": \"d9829e5f841b23e7f17c03dc06bf9243ab7ddf39d72b7ca86e62e6abf371f9ec\",\n        \"size\": 307711174\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15156_Weather1.tar.gz\": {\n        \"sha256\": \"ad3b92f9d3b75ee1a21bcf9cf9376aa1c2ab1125b2abb8614b7a74b3671bfed1\",\n        \"size\": 345290530\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15157_Weather2.tar.gz\": {\n        \"sha256\": \"01e1f486b66362a3434638a041a63ea57ccbd6a6c45256e4fb818697fd2d61c5\",\n        \"size\": 761490075\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15158_Weather3.tar.gz\": {\n        \"sha256\": \"018942693b14f40bb342793dc7f33784089d032c120f22e6819a10df90f3f884\",\n        \"size\": 83280709\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15159_Weather3.tar.gz\": {\n        \"sha256\": \"c1cf83799ed81d815c97aaa566f618520b105985484b51cd2cce0da0223c9518\",\n        \"size\": 410905739\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15160_Weather5.tar.gz\": {\n        \"sha256\": \"f7b184b2d159bf0cca0c9c9fd70837666fe16b1b3fce49a654d707457e4ca33c\",\n        \"size\": 817894567\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15161_Weather6.tar.gz\": {\n        \"sha256\": \"478cb95489cc51a9a253e7fb7ea4d025eabbc3e5b44bb1404f6de712ad3f0759\",\n        \"size\": 84545541\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15162_Weather7.tar.gz\": {\n        \"sha256\": \"65b4e3667cefde622ea6bf428d61c8dd6c8f5df8fb478bbf5821e7b582a80ade\",\n        \"size\": 105083464\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15163_Weather8.tar.gz\": {\n        \"sha256\": \"98e794f6914d1bf32939c390a743407957ab3eeeeb81ecd84b95e4674a8fb47c\",\n        \"size\": 526799481\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15165_Weather10.tar.gz\": {\n        \"sha256\": \"746479f4c99018542d8d2c4d50014436f6d22ed359ac7b7da10a1559b9f4f240\",\n        \"size\": 84435366\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15166_Weather11.tar.gz\": {\n        \"sha256\": \"6876687c095e87777482838773e7676531d401fd86db2dc3b54befe76402f54a\",\n        \"size\": 260800809\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15167_Weather12.tar.gz\": {\n        \"sha256\": \"771c5e2511adc63134b9337070c57b9c210063b3e03686d5993882f9a1380a05\",\n        \"size\": 462155765\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15168_Weather13.tar.gz\": {\n        \"sha256\": \"4729b3265c31bcce8c0775bb8fe8053faec62ea4b4743973575711a795b9c0fa\",\n        \"size\": 167158175\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15169_Weather14.tar.gz\": {\n        \"sha256\": \"cdb270559798296cf5512b65f739a64b686dcc857b432d7a9f0efa267fde680e\",\n        \"size\": 81871883\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15170_Weather15.tar.gz\": {\n        \"sha256\": \"f198d217c1d781d27ab4f4eed86f3d571843dad15b0379eebed04450d78a3979\",\n        \"size\": 389309647\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15171_Weather8.tar.gz\": {\n        \"sha256\": \"f99e3c07e98af23fc7cada98b30d2efd771d74701166ddd35c14bde7cc4470e0\",\n        \"size\": 378271522\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15172_Weather9.tar.gz\": {\n        \"sha256\": \"beb772f55f2dd1de3b75b63c7cbc1cd853f2a85ef89f010b6bcfdcdb12389674\",\n        \"size\": 73317762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15173_Weather18.tar.gz\": {\n        \"sha256\": \"ccab83578d3f35e3494e104c0aa631f92a050b764469815f15988c29cb28e5a3\",\n        \"size\": 88832165\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15174_Weather19.tar.gz\": {\n        \"sha256\": \"e2aafc6089cc86ec2a8e28547a3d1ac7159e6486a49abdf7a2b6d06188a2b053\",\n        \"size\": 391368591\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15175_Weather20.tar.gz\": {\n        \"sha256\": \"ce9e1ec05631b3191762b0710504c2c8b9565507688b88aa60c21f348b997d0b\",\n        \"size\": 506948549\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15176_Weather21.tar.gz\": {\n        \"sha256\": \"51d61bf09285047f9383c94a6f49ff5cf602780267160e57493d6fedb39588cc\",\n        \"size\": 485820370\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15177_Weather22.tar.gz\": {\n        \"sha256\": \"8223de69d99540a2c190e9b0296eb77c89ad0060f26e5ed0660a2b679e441773\",\n        \"size\": 101618782\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15178_Weather23.tar.gz\": {\n        \"sha256\": \"a65a67969cef312016ae0f6f03110aa1db20a8a79405cbaba2b168dcf797f388\",\n        \"size\": 582702516\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15179_Weather23.tar.gz\": {\n        \"sha256\": \"5650d1cfd68e2df720c3f52841a03449da2c7f0e19f389f590451801001a6201\",\n        \"size\": 204217893\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15180_Weather25.tar.gz\": {\n        \"sha256\": \"2e44bad5da33ddc2292f97b149704b89ddbb84b0e42b5fae35696d71912bfd8b\",\n        \"size\": 287670829\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15181_Weather0.tar.gz\": {\n        \"sha256\": \"427ede100fc1cd616d56c5f1a6bd598498c534cab69daca5c9f7ccaa4b73da2a\",\n        \"size\": 812457954\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15182_Weather1.tar.gz\": {\n        \"sha256\": \"ae7522143f766bcbf89aa4e58eafe5591ceefd2c7072925759dc92bd8be373af\",\n        \"size\": 508141688\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15183_Weather2.tar.gz\": {\n        \"sha256\": \"0f2453ddc07d45557ea2fc8cd694e44f956b4e200e0c7865fdbdf9ca0a2b6e3a\",\n        \"size\": 344795349\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15184_Weather3.tar.gz\": {\n        \"sha256\": \"b6345e1708957573f8f278b9ab219a7c131ed806e10734ccd67eec526beb788d\",\n        \"size\": 393881094\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15185_Weather3.tar.gz\": {\n        \"sha256\": \"9900f366c19c34d4ae115b90eaded906911ff311abf744833d06b687e8c3dd66\",\n        \"size\": 243628046\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15187_Weather6.tar.gz\": {\n        \"sha256\": \"c39a65dfbf0525b9819a8012df9153c094667797c03dc3d24eca3da08c18eeb7\",\n        \"size\": 210967307\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15188_Weather7.tar.gz\": {\n        \"sha256\": \"94e5cf56ce36b4aff5877029372066f59a6c1e272340ed01ade1516a44ff7534\",\n        \"size\": 254689124\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15189_Weather8.tar.gz\": {\n        \"sha256\": \"cbabea2ddafa217c37f50003ead6cd51bbeca87021c714cad140d4fc67a89e92\",\n        \"size\": 450448168\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15191_Weather10.tar.gz\": {\n        \"sha256\": \"2b6cd898e0ff676edc42b318a2507a198030501bc5e981527ec4dd3bfcdfbab5\",\n        \"size\": 137242152\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15192_Weather11.tar.gz\": {\n        \"sha256\": \"1634711387093355230aac8ce1ce565cd930e57518916b09626c9396cc367679\",\n        \"size\": 154679692\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15193_Weather12.tar.gz\": {\n        \"sha256\": \"5c520c8ed839c8add1b7c07bb0cbfb6f5823434886a7d16221aa87b4fe8e6669\",\n        \"size\": 351552308\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15194_Weather13.tar.gz\": {\n        \"sha256\": \"9fa0c3869ba5fe09d8f5d05a01ce8a4ce4dc480f6170a5eccefca6eb2862d05d\",\n        \"size\": 98927255\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15195_Weather14.tar.gz\": {\n        \"sha256\": \"faf6d291f1cfaf3442f526fef982d41ff48beb2bd88f8a17b51f2fdeb969e578\",\n        \"size\": 155544664\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15196_Weather15.tar.gz\": {\n        \"sha256\": \"c67fcaecc706581787608fd08b6a52294f128579bb3d817ea8e8e4d179b02077\",\n        \"size\": 352844772\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15197_Weather8.tar.gz\": {\n        \"sha256\": \"3405ddbd2a3a50efa7240f756bc31b3d424456343755888bbf078361f0f4dd78\",\n        \"size\": 305344457\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15198_Weather9.tar.gz\": {\n        \"sha256\": \"9e62bfb4995e3e9ba1bc02ca02d576607ac2157c8e8bfce47da2ff591dfac829\",\n        \"size\": 263676077\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15199_Weather18.tar.gz\": {\n        \"sha256\": \"8368ed0c2889cb9638c903fd97055fe515bf6729655753fa9e96adb1ae8f2165\",\n        \"size\": 210879040\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15200_Weather19.tar.gz\": {\n        \"sha256\": \"76c80b4d52de7219b3434d32f366da82ff357401668f743c4bf519480f2c761d\",\n        \"size\": 346098959\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15201_Weather20.tar.gz\": {\n        \"sha256\": \"e9d283903ee56f003c7738fe9b42ce152c11dfe9fd4235c8e4555502d4e404da\",\n        \"size\": 437246693\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15202_Weather21.tar.gz\": {\n        \"sha256\": \"d25cc4aea7a967c158f4a30c35000484e644932422d9fa9dcfa6876a00418903\",\n        \"size\": 244703528\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15203_Weather22.tar.gz\": {\n        \"sha256\": \"3e5bf52d5ad47baec17f18ef71037a258d1273438a57b323b841434810da1ec9\",\n        \"size\": 340423588\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15204_Weather23.tar.gz\": {\n        \"sha256\": \"0bc0ca142067b02725a89006d26a82fceaaa53df9e91264303abcbced4950c34\",\n        \"size\": 86236942\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15205_Weather23.tar.gz\": {\n        \"sha256\": \"9a8ae1381329c73c251eed394cbf01aaa9b9a9c6923d2f3b73f5283f0828071d\",\n        \"size\": 363846091\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15206_Weather25.tar.gz\": {\n        \"sha256\": \"67c2a6531f82d8e1ef7d93aca9d3443c6b1afc6afac5f3c923b688937de5ead7\",\n        \"size\": 327121182\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15207_Weather0.tar.gz\": {\n        \"sha256\": \"be355f1d37ea694d31be6092f421ed0d05b1060e22666615436cacdfe75a4e6e\",\n        \"size\": 122459746\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15208_Weather1.tar.gz\": {\n        \"sha256\": \"b7e6b3c4540101b019892af1558dff082d27281a62e42b456028304fc33c9a55\",\n        \"size\": 569149292\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15209_Weather2.tar.gz\": {\n        \"sha256\": \"f77239e0f34ebfe1a70a26159b3ff5672ea8376e5d10c622f5da4da6d50553d6\",\n        \"size\": 278895726\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15210_Weather3.tar.gz\": {\n        \"sha256\": \"f4503fd08cfc279bd6de23f3760952aa68b1465146a257cadb315ea9e72b7cd7\",\n        \"size\": 137414947\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15211_Weather3.tar.gz\": {\n        \"sha256\": \"089747679741353c66eff8c43718548011fae95f8becffb96424255793c5f8dd\",\n        \"size\": 428663225\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15212_Weather5.tar.gz\": {\n        \"sha256\": \"4887d701f83c1fc9179b6878f9beded1f1b680e93a102798ce391f3658aeef2f\",\n        \"size\": 284744469\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15213_Weather6.tar.gz\": {\n        \"sha256\": \"b399b2cf53cbb5640e0b8becc907589ad76b1a12e6cbf6a5ef5803d1d373d3b2\",\n        \"size\": 318538406\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15214_Weather7.tar.gz\": {\n        \"sha256\": \"9a9abfc26a3342024c757f56fa96dc5f30b80d5952924add9cccd340bc0cd0d5\",\n        \"size\": 203624673\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15215_Weather8.tar.gz\": {\n        \"sha256\": \"6a44350653be4338942304eb65f4147082990677431b632cfcfbb758a8313b07\",\n        \"size\": 112605720\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15216_Weather9.tar.gz\": {\n        \"sha256\": \"8522adbae608eedee34953738591d10eab43ece5a35fcb59b5672a0a23f8fdde\",\n        \"size\": 163750238\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15217_Weather10.tar.gz\": {\n        \"sha256\": \"fa97ec6cf8066fc377cdf3d338cf1f487ca5e0790d345c40238323a30c8970b9\",\n        \"size\": 370458653\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15218_Weather11.tar.gz\": {\n        \"sha256\": \"8b0494b661107e63cae777375fe785b675b888ae8125f75d2a9556efe0b645b1\",\n        \"size\": 248512809\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15219_Weather12.tar.gz\": {\n        \"sha256\": \"3258b861d88b9197d4adb901adccb6635580c9ea378cf4f3be161756833d3dd5\",\n        \"size\": 169441671\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15220_Weather13.tar.gz\": {\n        \"sha256\": \"491e46eec14f478a400aaae3b935342fc038df59d36c6674b31a1a487189ed4c\",\n        \"size\": 358075715\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15222_Weather15.tar.gz\": {\n        \"sha256\": \"7e509ec1f6dbb7d02f07dc43b279ecc2ac90eafe03b7b236f1c45a58ac6f1ebc\",\n        \"size\": 794417071\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15223_Weather8.tar.gz\": {\n        \"sha256\": \"d7dcde080e657f893a542f70f10fe338c8f41f1146cbb35fb2eee16725e58a78\",\n        \"size\": 335524006\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15224_Weather9.tar.gz\": {\n        \"sha256\": \"68c9ee100a5ce6472cfcf3287592ca9272354e168d7c0a699216e064387dd005\",\n        \"size\": 65226514\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15225_Weather18.tar.gz\": {\n        \"sha256\": \"4c0311b08e90f192cf527c7b244bd7a78c905f467f19ab249b370ea3a3198016\",\n        \"size\": 194408552\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15226_Weather19.tar.gz\": {\n        \"sha256\": \"1fdea4cd0d7f8a5ae71a3b30734657a92001ff072c689f0aea7596fd8e317271\",\n        \"size\": 80744761\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15227_Weather20.tar.gz\": {\n        \"sha256\": \"ccda380f39176a813b4bb3eab9bca61fe27d94a8b479a24de6b900182721f5b7\",\n        \"size\": 604152700\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15228_Weather21.tar.gz\": {\n        \"sha256\": \"d1b9d1fdb99c3dad89641b7fefbf9fc9efe08abefef5457eb54d905a2a3706eb\",\n        \"size\": 373097632\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15229_Weather22.tar.gz\": {\n        \"sha256\": \"e6a4a5c01fec6a9baa7c32f0f83aae150cfee8514928f22f39c440fe49a0ecd0\",\n        \"size\": 148374971\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15230_Weather23.tar.gz\": {\n        \"sha256\": \"749017da3092a5d3ca5279cf657e9c7f912db7d4b91e1cc53decbc9854e73334\",\n        \"size\": 316066041\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15231_Weather23.tar.gz\": {\n        \"sha256\": \"6ec35ec6fa283525dd530591b461a21ac2af3660e12204bae2d3204f5d411cab\",\n        \"size\": 60819620\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15232_Weather25.tar.gz\": {\n        \"sha256\": \"02786c94169c1b607c940cd379f7c5869011a8ef4cc50223786f86ed04fb1cf4\",\n        \"size\": 139265804\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15233_Weather0.tar.gz\": {\n        \"sha256\": \"df1c9ce0c492179893a8017d8b35062003df4c9e101e55bd7c69b513e82bfec8\",\n        \"size\": 86237491\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15234_Weather1.tar.gz\": {\n        \"sha256\": \"b5caa7a6f27490bf83cddb649cb89d8d41f9c5642855657044a0db1f57af8233\",\n        \"size\": 669158455\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15235_Weather2.tar.gz\": {\n        \"sha256\": \"13ae217ee7e9e23a7d607eaad0b23e78396156c14aed9e795ff4f15f10e2047d\",\n        \"size\": 410924482\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15236_Weather3.tar.gz\": {\n        \"sha256\": \"6f87f58e0756b59d5c3a7cb0efb0e83a0f7bca8dc14dafcb5d5f3522dce519b3\",\n        \"size\": 229948280\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15237_Weather3.tar.gz\": {\n        \"sha256\": \"6f26780eef0f34d4a13ed05e61c1f394836f63ba3ca385dd4e5915f89f664e4a\",\n        \"size\": 243674888\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15238_Weather5.tar.gz\": {\n        \"sha256\": \"e9d4e2641afdcc69ee7e5534d4a0909246a5e4cb52aacaa390d3e27c928d4951\",\n        \"size\": 75978635\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15239_Weather6.tar.gz\": {\n        \"sha256\": \"0971c2deb4d37ae86e9f2f466f77e3340eb73ec5cc32acc2a05b289dae84411f\",\n        \"size\": 185213601\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15240_Weather7.tar.gz\": {\n        \"sha256\": \"e1af95d3522ac1e157ba85c8db82604bf79fa9a25e731940fa053cfd9021977f\",\n        \"size\": 612691683\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15242_Weather9.tar.gz\": {\n        \"sha256\": \"4e13bab6c2bf2144271f45e79eeeba7171d3fb802d299f0652463c251c634d37\",\n        \"size\": 219031673\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15243_Weather10.tar.gz\": {\n        \"sha256\": \"4fd2972ae93e0d7a5c4727fe229d729b1a00c2eb4f637a7fc917f4a25f33a196\",\n        \"size\": 412325695\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15244_Weather11.tar.gz\": {\n        \"sha256\": \"af749e47adb7f3f6586f8694a51fa38c260b3aa096e7e76b1795e6d2dfd27e7a\",\n        \"size\": 521225575\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15245_Weather12.tar.gz\": {\n        \"sha256\": \"cea57c5e14812878c8b69769c96a9cacb844be2378d238fb4c0fc3e837e12f62\",\n        \"size\": 86660132\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15246_Weather13.tar.gz\": {\n        \"sha256\": \"1a8ff9b989dfcb0dcd06762d905b6b18a24229fca41304761101b5e81fdd14c3\",\n        \"size\": 421049135\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15247_Weather14.tar.gz\": {\n        \"sha256\": \"f921bde3722b4eb9a9a4805021b745db8dcd9ac58164c369c357cef7397e4931\",\n        \"size\": 177652467\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15248_Weather15.tar.gz\": {\n        \"sha256\": \"23ff4b52f9e9e17d371111f2df7d8f7cf76c8f6942eb80d3c1742040d1c5e4e2\",\n        \"size\": 321999392\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15249_Weather8.tar.gz\": {\n        \"sha256\": \"1ed9616011813a85f902394543c40376b88b33b50664164c175e1d04e8139b50\",\n        \"size\": 324628742\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15250_Weather9.tar.gz\": {\n        \"sha256\": \"5a9a3323a0511e7a41d3041a02de17aad9da147183e2d1c986dedf16640021ad\",\n        \"size\": 103050854\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15251_Weather18.tar.gz\": {\n        \"sha256\": \"d4b594fc2849b7975b5510ac10f9d4c82c1b73dfb9919aa029f0e2394be203a7\",\n        \"size\": 96152862\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15253_Weather20.tar.gz\": {\n        \"sha256\": \"c8e1c0c535e99621794321d7448577ee236f55442f5f8dd183f168ad049b9fdd\",\n        \"size\": 448255132\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15254_Weather21.tar.gz\": {\n        \"sha256\": \"0ba1429c23625628bf49544bf88230308d9a7bea471e96ceb8d3fde3346e1176\",\n        \"size\": 88355316\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15255_Weather22.tar.gz\": {\n        \"sha256\": \"8ba433701761ee35d08f1efcfb5cd871741358085a73de53ab02a0480648d7b6\",\n        \"size\": 174819396\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15256_Weather23.tar.gz\": {\n        \"sha256\": \"b3c993f7239cbdaef04a643dd1e9430d08f6965e1e964dfede1faab5413821d0\",\n        \"size\": 284891962\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15258_Weather25.tar.gz\": {\n        \"sha256\": \"623c1322d5a8f7f0cefad5961a1f132cb44f0835276a58dd1a4c1a7acdcea4eb\",\n        \"size\": 162327571\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15259_Weather0.tar.gz\": {\n        \"sha256\": \"6173e97f27fcd753f116fc985cf612c7f65990a751842658b579cba4f8dde8c0\",\n        \"size\": 88681394\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15260_Weather1.tar.gz\": {\n        \"sha256\": \"4468e74c47b532f5c3eb9ff7bee10f6bd3d0f5d1147ded961aae8c0cabc98100\",\n        \"size\": 388838423\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15261_Weather2.tar.gz\": {\n        \"sha256\": \"f4332ef019fd2b98d7f4ca741cb578d4d968bbabee080473cf359bf8aee5aa80\",\n        \"size\": 71478298\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15262_Weather3.tar.gz\": {\n        \"sha256\": \"b600c9de8b282e5a8af8f1e344b947267bcda4d4e2bbaa3d31e1f71debdb5c85\",\n        \"size\": 485874261\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15263_Weather3.tar.gz\": {\n        \"sha256\": \"d44d235d561ae704ecaf1a5304141ff9a4f168dec13bfcbb4961d889e6fbf24d\",\n        \"size\": 341403757\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15265_Weather6.tar.gz\": {\n        \"sha256\": \"b4db57e7cba30ce572ef43467d36cb995a8f231afd0bba92f072b9531ad62829\",\n        \"size\": 82528391\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15266_Weather7.tar.gz\": {\n        \"sha256\": \"820c3fe7804e4c275061c7dc094af66812597d593dbfc4ebd6f3356dd6debcd8\",\n        \"size\": 338293953\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15267_Weather8.tar.gz\": {\n        \"sha256\": \"83f35359d8c3ebb8fae23623c230e2f8cf46f836cc0bf9b1446d9cd5e3d1a2c2\",\n        \"size\": 350419945\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15268_Weather9.tar.gz\": {\n        \"sha256\": \"64da2ee12c9e4919e11cb0c9308709c32e269cd1ccc74bf3c0799b5429a4a342\",\n        \"size\": 326879870\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15270_Weather11.tar.gz\": {\n        \"sha256\": \"ce38aea825617e0903e492cfc8c9298324383f86b80fe68fbd66fad0755b79f0\",\n        \"size\": 69404245\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15271_Weather12.tar.gz\": {\n        \"sha256\": \"9fa31cf13eac020b7be21b386f5ce38361ace53122034174de22ea645f336d32\",\n        \"size\": 169456393\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15272_Weather13.tar.gz\": {\n        \"sha256\": \"7485b85aef8dc7747d6fce1bd12a00badf4ace966438bf8bbe779af4b9ce16a3\",\n        \"size\": 182396270\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15273_Weather14.tar.gz\": {\n        \"sha256\": \"00dffb1614b03fcf9502684e976ac4a755137e6a1b6543f1b9d3c56fe82488e0\",\n        \"size\": 303288790\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15274_Weather15.tar.gz\": {\n        \"sha256\": \"b6c7dfb015086173c5964b68bbdb8d55b10cf4127055f7656c89a7ad268ee76a\",\n        \"size\": 277415814\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15275_Weather8.tar.gz\": {\n        \"sha256\": \"79df553a9d9363e4948c475f8b0ec8c17e97b2a248b725ee40ed1e6745094e62\",\n        \"size\": 345944247\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15276_Weather9.tar.gz\": {\n        \"sha256\": \"22178faf5cfb1c4df84cee613fb5ae0682db8078f3e971b42ffe9815db7c873b\",\n        \"size\": 401336594\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15277_Weather18.tar.gz\": {\n        \"sha256\": \"d1bec99cec71bc97194339a59383cbd57a1a45e7549d762aa54d2c3802b5a2f2\",\n        \"size\": 191844321\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15278_Weather19.tar.gz\": {\n        \"sha256\": \"d20d5e9c09e191b7d823504fa8ab8ac58a9d2b840df61d939247cad326b9e440\",\n        \"size\": 446668663\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15279_Weather20.tar.gz\": {\n        \"sha256\": \"7e2fc93614c01cc227703de8838d2ec31983990a9d947ed8c33a073dfdaf0164\",\n        \"size\": 111439145\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15280_Weather21.tar.gz\": {\n        \"sha256\": \"f0759c86bf0317b3cac32277798d9a13f5b33926d5162056b1797e0e3ea880db\",\n        \"size\": 78908274\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15281_Weather22.tar.gz\": {\n        \"sha256\": \"572b2246206c5071423a89ab4872bb9281da7fcf1860cff49a070d718f91f9ea\",\n        \"size\": 524651967\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15282_Weather23.tar.gz\": {\n        \"sha256\": \"7b2437f39d788985683fb89fa0f52dfa7ee0d039569d2ee36bf0fa44e8920d44\",\n        \"size\": 303537831\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15283_Weather23.tar.gz\": {\n        \"sha256\": \"dbd2cffeefba104dcc08b9c7b5069f95daddd953bc12889fa3915eed20df2e57\",\n        \"size\": 170883293\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15287_Weather2.tar.gz\": {\n        \"sha256\": \"439afea83d7d8263e95226a0114af13d12b7fcd40fecf3668f291ef36ff00ffa\",\n        \"size\": 533341453\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15288_Weather3.tar.gz\": {\n        \"sha256\": \"4a31ee30a1b27f7d72c988e093396d9ea3bd460ad22461740ba806bdf8ab0be0\",\n        \"size\": 473758210\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15289_Weather3.tar.gz\": {\n        \"sha256\": \"646f49bb2ff7ef9fc035e1a1890e45f0d1f57b493237f7ec7cd63487e6ee0f41\",\n        \"size\": 112674830\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15290_Weather5.tar.gz\": {\n        \"sha256\": \"cbec3df7a6b8b540cf7c267fcb9681312f0d2c9f59d6d5b069d8e33c4f852576\",\n        \"size\": 111833482\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15291_Weather6.tar.gz\": {\n        \"sha256\": \"d540101661e289ae43311e10005cc265e59358eac738a88d6f7a83e4d369d40e\",\n        \"size\": 433111317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15292_Weather7.tar.gz\": {\n        \"sha256\": \"1d93cd20331f0f3d583c3ff949d71e969b19b46e9627eff262b7ee2458477c22\",\n        \"size\": 308745106\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15293_Weather8.tar.gz\": {\n        \"sha256\": \"447219f2d829631c3bda5846063308ec1c438e9aa4711bd174411b9fbbc34fe6\",\n        \"size\": 79912469\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15294_Weather9.tar.gz\": {\n        \"sha256\": \"bd4799c0cf053bd1d42131eb28afd495502de9f922a3a24fe29f2d5488cddde4\",\n        \"size\": 70505284\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15295_Weather10.tar.gz\": {\n        \"sha256\": \"bdbe51caf9d090898fb4d30a89eb8a9dc0238c3d5897190a3931255545f4bc86\",\n        \"size\": 196102584\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15296_Weather11.tar.gz\": {\n        \"sha256\": \"f105a44092cfbde2061ee9525958105596279a09ea46a6e2e4034978f952b4ac\",\n        \"size\": 109346556\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15297_Weather12.tar.gz\": {\n        \"sha256\": \"9baa088a8a893f6fa756b2eb3dc1fb8cf493e2a70476fe0337bd62ffdcef7dd5\",\n        \"size\": 270636332\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15300_Weather15.tar.gz\": {\n        \"sha256\": \"5b869a491b5800bb9a66a580a6c0137571263bd40224a76db4b1f93d9bed8cbe\",\n        \"size\": 275108596\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15301_Weather8.tar.gz\": {\n        \"sha256\": \"1db6196eba037f6710a8ede0432cb97b8ab066360b46ea377fc2f4e139d87146\",\n        \"size\": 246487494\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15302_Weather9.tar.gz\": {\n        \"sha256\": \"4a1f9f2613b218444eb4b4127eb78bcba48946686ca032afdee6c3bbc4fa8c67\",\n        \"size\": 76231542\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15303_Weather18.tar.gz\": {\n        \"sha256\": \"1c06314112cf22bd5b9429e864170e1287ae9077fc2285833e9cd73f11fb2016\",\n        \"size\": 391502672\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15304_Weather19.tar.gz\": {\n        \"sha256\": \"05e9179b513d2c8c61ffba461a623a1dc14ff7821680b7010a0b048a977378b7\",\n        \"size\": 292122972\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15305_Weather20.tar.gz\": {\n        \"sha256\": \"fc7735ec6ac4e8f8efed6f633e300952cc5328d6e3f65893c5ffdee2d25aca32\",\n        \"size\": 424266529\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15306_Weather21.tar.gz\": {\n        \"sha256\": \"a81843f3634bffc319830d493eecee175f22c4bb31dc91ba98dbfc6129080493\",\n        \"size\": 439562793\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15307_Weather22.tar.gz\": {\n        \"sha256\": \"222f47bb83496ab060c80517c715521d50da231da36822e79f98e7227765f1ff\",\n        \"size\": 175401195\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15309_Weather23.tar.gz\": {\n        \"sha256\": \"e8f6035dca27306458ca9d1f86d149aba5becb916be7ef9b3a2d80a76df4dd5d\",\n        \"size\": 241774626\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15310_Weather25.tar.gz\": {\n        \"sha256\": \"e6071cebddbd17d30f05f2e8ceee385719db2073db8e5007c5a53683f85e5006\",\n        \"size\": 280471802\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15311_Weather0.tar.gz\": {\n        \"sha256\": \"81a4b87893a1acc676815fea3a1db64076c59a2cf19386c963e7615c59cd065a\",\n        \"size\": 69326795\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15312_Weather1.tar.gz\": {\n        \"sha256\": \"67ab0f691d1d438b4ad3b0b77b3018b88c3d5e0f12ecb8dfd80ab2955e8a951a\",\n        \"size\": 460545874\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15313_Weather2.tar.gz\": {\n        \"sha256\": \"3892cc8b7927b586eea1d0fb24d53bd93cfeb3245be48ac52a86f0c2187e2176\",\n        \"size\": 503828382\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15314_Weather3.tar.gz\": {\n        \"sha256\": \"7052c8a356634f50ac684f6a440f4f7f0f1ca55dd1a9dd1ead5af77cf0e6599b\",\n        \"size\": 217497273\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15315_Weather3.tar.gz\": {\n        \"sha256\": \"389327852f5952e52dca24f4bb6a0d0ff3bf34cbed2c589c78f45b56177636b2\",\n        \"size\": 481720311\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15316_Weather5.tar.gz\": {\n        \"sha256\": \"8af94796588d4ee59b857676b2926b573b8aee411d14289fca71c82a56bc7449\",\n        \"size\": 461358923\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15317_Weather6.tar.gz\": {\n        \"sha256\": \"418bc402bf6ac02bc686a39044898892be793d879b4ec2575603c0c5464e5879\",\n        \"size\": 127004916\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15318_Weather7.tar.gz\": {\n        \"sha256\": \"2b1236318c0825307e795081bc479f4fffedaad6037ef05208e2914af40886ba\",\n        \"size\": 129802886\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15319_Weather8.tar.gz\": {\n        \"sha256\": \"4314ff63132ffc761bf04509f4e6c8fd12e20e533966351e84aae4bb547d72d1\",\n        \"size\": 167501317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15320_Weather9.tar.gz\": {\n        \"sha256\": \"521f04f256572996b0b07dd76143eb8f8f738e603b4779b2871e0f1ea3c1bfa0\",\n        \"size\": 154515933\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15321_Weather10.tar.gz\": {\n        \"sha256\": \"81a6d18747ef3307f21595d912bd079b86c5702973bbca95422d0dd898402fb8\",\n        \"size\": 375866703\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15322_Weather11.tar.gz\": {\n        \"sha256\": \"7ab8e386dd399cc97648f81a886c4b20265ed000f51bc91fa1e3cc592d378179\",\n        \"size\": 221450415\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15323_Weather12.tar.gz\": {\n        \"sha256\": \"e6f93d2f29e8e0f28fdfbf06125228e60319419261830e5be7ff6633b94add17\",\n        \"size\": 253122938\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15324_Weather13.tar.gz\": {\n        \"sha256\": \"c030e618c0b63f2c1fcc1f22b54901e0e9e4b0e83037a4261a9bf834b7129b97\",\n        \"size\": 345981792\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15325_Weather14.tar.gz\": {\n        \"sha256\": \"414b2d65b9935c1bdf15f968c3cbde45616f41ca1847244a6c561884b8668345\",\n        \"size\": 246914173\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15326_Weather15.tar.gz\": {\n        \"sha256\": \"ddacbeee332a046dcf0e98781e7406443d6c15e1e9f982ec3ffea78f46f0784a\",\n        \"size\": 142842103\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15327_Weather8.tar.gz\": {\n        \"sha256\": \"454e374f4c5896347f670292058cf62a21b3b5a2392404efbe0be0c4c44b4b5f\",\n        \"size\": 317887312\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15328_Weather9.tar.gz\": {\n        \"sha256\": \"d81f959b49885bcdbac0dd1ec91ca651a3516d14fdacd52bc2ea0d06e481c225\",\n        \"size\": 564662636\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15329_Weather18.tar.gz\": {\n        \"sha256\": \"f16a411bb20c26014418e85103dd05d8f4215f3b02bc4a9472920a2de41a420f\",\n        \"size\": 86114755\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15330_Weather19.tar.gz\": {\n        \"sha256\": \"6a8ef429174d58d547fdebd850a601eee8f90efa03afa8c2aafd53235dc17b98\",\n        \"size\": 412509849\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15331_Weather20.tar.gz\": {\n        \"sha256\": \"a182cbfde6f586ea87a7dbe35745ccf1ee25f9ebcb8dd620e618bfaa63d2410b\",\n        \"size\": 118742675\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15332_Weather21.tar.gz\": {\n        \"sha256\": \"39011b60b5ae95db6d343104e638094e762c2fbdefbc9fc9d9b5e786d83a0990\",\n        \"size\": 435686491\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15333_Weather22.tar.gz\": {\n        \"sha256\": \"55dad4ae1b6e1bce8253d5201bfb480ce6809afe57f3922e0bb835ee1857ea78\",\n        \"size\": 71146501\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15334_Weather23.tar.gz\": {\n        \"sha256\": \"ca1f2a63cdf31487dcc3e58a05e2a9468d6d4431a9ccbef166f71ab4ed66ad35\",\n        \"size\": 403035552\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15335_Weather23.tar.gz\": {\n        \"sha256\": \"7abbd3c9171a34833d1f9161da06bdb6ea9480595a60b2ac81f81e8c47b3244d\",\n        \"size\": 620015277\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15336_Weather25.tar.gz\": {\n        \"sha256\": \"c2ca1a3189296196bb5735edfe1744df604427d36c0fd3e6e3b6cf58c80d93ee\",\n        \"size\": 317057027\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15337_Weather0.tar.gz\": {\n        \"sha256\": \"f6f58f7f15e1b707bf5549ec47ec07f20d789a74d1568bb334254f5dbacce5bf\",\n        \"size\": 658315217\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15338_Weather1.tar.gz\": {\n        \"sha256\": \"b7448001225b5f1ad861ef8570d6fc612cccd49fe3a8d66749e663cdb9900df2\",\n        \"size\": 216114837\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15339_Weather2.tar.gz\": {\n        \"sha256\": \"9a3ee13a31cf06ec1fb8068f3f357f8b9e9cc8baa3939d74128bf2488237829c\",\n        \"size\": 244977786\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15342_Weather5.tar.gz\": {\n        \"sha256\": \"7bcbadce07e920e648ca3222f76639b80877ff18fc7580359bc996321d200715\",\n        \"size\": 537785229\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15343_Weather6.tar.gz\": {\n        \"sha256\": \"f6293476dc214d8dcee4ad6eac6f17069ce7d564bc4beaf79b9807bb4a492b7e\",\n        \"size\": 411336605\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15344_Weather7.tar.gz\": {\n        \"sha256\": \"685e7db63ad84623cbf2dba818f9e98b4eba1943fb2bac155251b9e7d454b007\",\n        \"size\": 556401958\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15346_Weather9.tar.gz\": {\n        \"sha256\": \"97364886fe45263c1a597e00f548a458207afbd2159ffab582df3d84fd488bb8\",\n        \"size\": 86306905\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15348_Weather11.tar.gz\": {\n        \"sha256\": \"503df558cdb1b8a583b28f070737007f359cae6188b11a901433afd9487a77eb\",\n        \"size\": 313030762\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15349_Weather12.tar.gz\": {\n        \"sha256\": \"a12a27f2f899bda834b3346ced8de20256419abbc6f9f9efd5cff1ec1b1e6792\",\n        \"size\": 167267554\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15350_Weather13.tar.gz\": {\n        \"sha256\": \"e8cdde84a2c71c95d5d3b5d99f12c395a2e59de34fad3e7db9f1c071d258b84a\",\n        \"size\": 304743303\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15351_Weather14.tar.gz\": {\n        \"sha256\": \"4ff032e81b9d0d3720aef7ebd8f7c4794ac8a9738742bbc828fe7fa39e036729\",\n        \"size\": 223229900\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15352_Weather15.tar.gz\": {\n        \"sha256\": \"c45269e87957fd030cbcdfbdf3e371967e0a11ee18f3d66b2aa44682923b1ab5\",\n        \"size\": 64873188\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15353_Weather8.tar.gz\": {\n        \"sha256\": \"10d524a501803b7a180b9284c3745175ddba26a0b9ab5de17341de95a4b8270f\",\n        \"size\": 469230185\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15354_Weather9.tar.gz\": {\n        \"sha256\": \"9f6f8e7a4be9ff04f6445427731c1fe6a9f4990eab45d8f44809f335c94289e5\",\n        \"size\": 456349113\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15355_Weather18.tar.gz\": {\n        \"sha256\": \"62b18d438e096e12d5642020e33c2e270a9c966b788ae019ac9381ab0980eb5b\",\n        \"size\": 491142852\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15356_Weather19.tar.gz\": {\n        \"sha256\": \"c333b5475c7c4fadf90499eb00a02c619bcc56110b74f0a1ac61181e0887d59d\",\n        \"size\": 208572636\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15357_Weather20.tar.gz\": {\n        \"sha256\": \"8383941a34645b0a8df0b0c8025644bd2bc5ff07593a15e2ea2dfe1eb32ccfee\",\n        \"size\": 566545711\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15358_Weather21.tar.gz\": {\n        \"sha256\": \"96460182e6ce9760d3b790147ab40f9fe2b439463a49874007ed81da9134c5a4\",\n        \"size\": 70035187\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15359_Weather22.tar.gz\": {\n        \"sha256\": \"cbf36a910983df4448addb0b20e69e4897ebf5fe24184f4d8c5927770dc494ed\",\n        \"size\": 401466922\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15360_Weather23.tar.gz\": {\n        \"sha256\": \"1ff3a628f3810606c69443b44a5efaaf83ce319b4b6a39f6a9ae633780c2ebaa\",\n        \"size\": 77510371\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15361_Weather23.tar.gz\": {\n        \"sha256\": \"ef88c0f8362fd936f8e9685e779caac23a4d9756e4c7b7a23ba60f39a2af9571\",\n        \"size\": 170618238\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15362_Weather25.tar.gz\": {\n        \"sha256\": \"3c3820445c71dd3ac597f1f160285470f57d8016fe03dcdf36019bd1e4ef4e74\",\n        \"size\": 233224830\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15363_Weather0.tar.gz\": {\n        \"sha256\": \"9073d7703c5d37c698d75b8f2da8a7453192902129ea15786caa7b033df845fd\",\n        \"size\": 256606290\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15364_Weather1.tar.gz\": {\n        \"sha256\": \"1b5db04ab4c67448632e3db9045aae30cea250c5af7d9f56586493c0112a35df\",\n        \"size\": 516383405\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15365_Weather2.tar.gz\": {\n        \"sha256\": \"f6aa5cd0f7810511a7f9581ab687a1032b244a1254aadf56db9cc2a03733cb5e\",\n        \"size\": 191970495\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15366_Weather3.tar.gz\": {\n        \"sha256\": \"629139cedb1d3790c1c9ecfb4ec9bc7976bee17447121e199554089f0413ac59\",\n        \"size\": 432482241\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15367_Weather3.tar.gz\": {\n        \"sha256\": \"d4c09c5f5e47c307177525e39d3e3dfb5e2923e150cc1d00839d87ae9df76d53\",\n        \"size\": 608572671\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15368_Weather5.tar.gz\": {\n        \"sha256\": \"3658a0d427fc6428751d5277e9f415b3de1c77a55d72a186fed16bd84673e0ef\",\n        \"size\": 191343110\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15369_Weather6.tar.gz\": {\n        \"sha256\": \"b44ec6357e17a0a8f1b69bd8839f2c46f6210a359fbff788bbbaa30ffe19b20e\",\n        \"size\": 469406323\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15370_Weather7.tar.gz\": {\n        \"sha256\": \"fcbef01977ebc2c97f593072e4e307682efa75109c90734f6aba3e52ddfae761\",\n        \"size\": 591444060\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15371_Weather8.tar.gz\": {\n        \"sha256\": \"ed34d31e828c25a71516f66019930b164aad5beb6622aea9aee1759c7756df39\",\n        \"size\": 297517652\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15372_Weather9.tar.gz\": {\n        \"sha256\": \"95cd063d53f2ba61ae2efd4fdbf12b09b8a53d9131d27724d380137be12e199b\",\n        \"size\": 196526401\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15373_Weather10.tar.gz\": {\n        \"sha256\": \"8601b4419e9dd3884e7cd8531c074574945d4b44272461b7bd3af204000750b5\",\n        \"size\": 236909462\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15374_Weather11.tar.gz\": {\n        \"sha256\": \"bb428878084aff7c692eca8a7963abcbbe31a4dbfc07c15ec6cc812ff9d46f59\",\n        \"size\": 237578921\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15375_Weather12.tar.gz\": {\n        \"sha256\": \"ca5cc2a92f004e1614bd72c963e354d4401d7824ab62dabe1bccbd4053c0401d\",\n        \"size\": 142386724\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15376_Weather13.tar.gz\": {\n        \"sha256\": \"ac8157adbbcce7715035007557066c213493939bdf1aabe5e7d341a59093c2b5\",\n        \"size\": 75786796\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15377_Weather14.tar.gz\": {\n        \"sha256\": \"b2cf0a7ed3b0c512e97355c9dc51c4f2a62d9ec036e1e0faccbf7fcbd2f11f27\",\n        \"size\": 388756351\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15378_Weather15.tar.gz\": {\n        \"sha256\": \"54dcfc21bb87232b3f5d1b0fb3acebf2cd7158792041544a214d3d1c13001fac\",\n        \"size\": 161098623\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15380_Weather9.tar.gz\": {\n        \"sha256\": \"042336eb9bdeaff87974b662fde6e60bb05a702603776e1a24d5a5590facc35d\",\n        \"size\": 245342334\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15381_Weather18.tar.gz\": {\n        \"sha256\": \"d937c63d41ec21c79012070a1e848cf0a8a3610cc2a7f58e7df4e44ead861c49\",\n        \"size\": 234742608\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15382_Weather19.tar.gz\": {\n        \"sha256\": \"b68491e209e28c3bde6edd6e699d4629903ad09fc57fcd136dd6a8be873a7703\",\n        \"size\": 358299988\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15383_Weather20.tar.gz\": {\n        \"sha256\": \"5eb7da8ce432b2270a19a08d54fd84527541d7b2c6426a77617c1ac627bd3490\",\n        \"size\": 342930487\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15384_Weather21.tar.gz\": {\n        \"sha256\": \"481e044c761859c50a46d48142621b9050777a383710a079d5269a4c782e1bda\",\n        \"size\": 268634067\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15385_Weather22.tar.gz\": {\n        \"sha256\": \"a6da3e5f9ec94df213be159bece6baf50d5a8bb62cd503ec9cd9b985eac92908\",\n        \"size\": 258556617\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15386_Weather23.tar.gz\": {\n        \"sha256\": \"4b487034e7434ca43a39604a61239dd08b638a5ad119b2ca8bf6e78d2fcc14d6\",\n        \"size\": 173995206\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15387_Weather23.tar.gz\": {\n        \"sha256\": \"e19e168ac88a4bf584f8646e380522e5c09478c3c7d26e3f2a8da502ea24c4b6\",\n        \"size\": 239233318\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15388_Weather25.tar.gz\": {\n        \"sha256\": \"cf5f76060fdd47fc2127b838169c12fc9a183be93aaca9b93a8e0a7d4802a3b9\",\n        \"size\": 150929293\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15389_Weather0.tar.gz\": {\n        \"sha256\": \"40aca6bd03fd21db25a415f26616dc7c91e1c066755195d6c6c16caabde91be1\",\n        \"size\": 112960664\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15390_Weather1.tar.gz\": {\n        \"sha256\": \"7d726342cc65cc51b5d38a3b75693f43c052f50f1bfab7b43a0616d406951a50\",\n        \"size\": 90651029\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15391_Weather2.tar.gz\": {\n        \"sha256\": \"992f50945cf0c259fc2a03a742629457e43cf2bb3515ae426240ec3f004ae9a4\",\n        \"size\": 239288653\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15392_Weather3.tar.gz\": {\n        \"sha256\": \"6304c465fac4861ab56f9c37e69cb97567a30a1a32791e3d9835e7623118264f\",\n        \"size\": 176399014\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15393_Weather3.tar.gz\": {\n        \"sha256\": \"0b91a9307bd21d5aa28800cd63cec053897253d75ab962a22c406ce4602d8ca7\",\n        \"size\": 371475317\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15394_Weather5.tar.gz\": {\n        \"sha256\": \"502c42a47558e8a1ccdc801d19c0964c429daaa3baa5b93757ee0fed417baef8\",\n        \"size\": 416127666\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15395_Weather6.tar.gz\": {\n        \"sha256\": \"2fee767ff4b3c9549bac14711aa36a450a5f831f357ed297ed8c106f2bd6c5e7\",\n        \"size\": 439107774\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15396_Weather7.tar.gz\": {\n        \"sha256\": \"8a73a7b0daf37cf1c405d4061124aa798ba8775ff5f7a987e392127b44697fe1\",\n        \"size\": 481487555\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15397_Weather8.tar.gz\": {\n        \"sha256\": \"097472cd8d97d9a000075d2b80f4c75b8da148cf366087c8d46c9b13ae19c1f2\",\n        \"size\": 456080331\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15398_Weather9.tar.gz\": {\n        \"sha256\": \"31e4b8ca253ed7916cab38709b3dda6d15b41bcb955490d76b9dd7d1d36a5b6f\",\n        \"size\": 317840643\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15399_Weather10.tar.gz\": {\n        \"sha256\": \"b0501714e784143f6e5f7c4dd18657a83d3d5596c366fd21cd98b879606a38cd\",\n        \"size\": 118762297\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15400_Weather11.tar.gz\": {\n        \"sha256\": \"13d6817efc071f54426f32973a26d0e94149deccce70d28880400f7427bea822\",\n        \"size\": 80162299\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15401_Weather12.tar.gz\": {\n        \"sha256\": \"935c680f09af75a181bea9caa11e7834240e8de0748b758e2af3c4a6612dcd06\",\n        \"size\": 153695383\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15402_Weather13.tar.gz\": {\n        \"sha256\": \"2c6343f4c858cee16289ddb8761beffeb2ff2a979eda9a5109c0644875185dd8\",\n        \"size\": 131456096\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15404_Weather15.tar.gz\": {\n        \"sha256\": \"6dc56fb455186a719f663c83b86e3518f2627fb511933130826113470a4be902\",\n        \"size\": 322053599\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15405_Weather8.tar.gz\": {\n        \"sha256\": \"20718c015bc32639ca3dfeec3a31b7b2a5189c1629683c9ba21a907d7679e615\",\n        \"size\": 636649553\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15406_Weather9.tar.gz\": {\n        \"sha256\": \"a37ebf4e51fedd3681685b265c0aed2c4e242db4dddb9c4f27aebd2f8d7c227a\",\n        \"size\": 340944545\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15407_Weather18.tar.gz\": {\n        \"sha256\": \"eb7684f0d7d22d6c3f3b28507da0c4986d91db0ff8991251ac2f6a78c4ee30ea\",\n        \"size\": 591148617\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15408_Weather19.tar.gz\": {\n        \"sha256\": \"3fe7eff3bdf2894276d95732cc484a02f122488251725dc5233985360a09bce2\",\n        \"size\": 325838076\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15409_Weather20.tar.gz\": {\n        \"sha256\": \"d1598ae0376ae23a61bf674305777fb99e14cf54504ded3a422280853da360c9\",\n        \"size\": 496953775\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15410_Weather21.tar.gz\": {\n        \"sha256\": \"f36f56d063d6c32664745098449a63cc562d801df5d4dae25aa9526e817f90bb\",\n        \"size\": 118079836\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15411_Weather22.tar.gz\": {\n        \"sha256\": \"8852637fb96e8a43546246bef63c605fd2c8b63f1ac82e51917a8f3ddeb8c4bc\",\n        \"size\": 521956349\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15412_Weather23.tar.gz\": {\n        \"sha256\": \"01c331e618f91f177a1a46b52ae01dd6edb6c759ccc5f64a9827ce939cb0b9e9\",\n        \"size\": 120427079\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15413_Weather23.tar.gz\": {\n        \"sha256\": \"efb8276efce8f73c930e3852602a9dd74c3de1fbd50ca7d65d08e7c513768ce9\",\n        \"size\": 60741092\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15414_Weather25.tar.gz\": {\n        \"sha256\": \"37fe5ca7f5bb4680cadcc5ca85673842b2df3e4dc5ec268452b21ba9fec724e3\",\n        \"size\": 508533934\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15415_Weather0.tar.gz\": {\n        \"sha256\": \"f0e6dbbf981e1e30e148100144b6b94173d3603eb51b54254891dc6f073d3634\",\n        \"size\": 87149046\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15417_Weather2.tar.gz\": {\n        \"sha256\": \"f6853db4c969a85274cc287559dc446d5b12213ba5b6a29a28b03553c44a3e24\",\n        \"size\": 438906223\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15418_Weather3.tar.gz\": {\n        \"sha256\": \"fcb12f3478afaded52dd9eaa2ced0944a2be4f9c1fd3b54fd2881d30204459b0\",\n        \"size\": 484362558\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15419_Weather3.tar.gz\": {\n        \"sha256\": \"b30b0cc2e2fd8a8c3bafe5a054064c76ed60ace7b778e03e2f11622a60e72267\",\n        \"size\": 199586644\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15420_Weather5.tar.gz\": {\n        \"sha256\": \"01bbcbfba1145522b754e37d885c95b6d06d29150ff44dbec80d85c56c67cc01\",\n        \"size\": 490115856\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15421_Weather6.tar.gz\": {\n        \"sha256\": \"b10c06e5ba8b70efbf040b70667c4dceb77bdc1afc313582199ee9f0350b53b4\",\n        \"size\": 208857221\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15422_Weather7.tar.gz\": {\n        \"sha256\": \"cc0ef809b1055dc63afd73861759cc1ff74f489bc83554aed648c2f0f4893591\",\n        \"size\": 110938719\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15423_Weather8.tar.gz\": {\n        \"sha256\": \"b95d11f1f539170d6f9af03d5a6433063c4c92e5218f0cda9a20f33e50a9e6e9\",\n        \"size\": 390189181\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15424_Weather9.tar.gz\": {\n        \"sha256\": \"3a30b87ca86cfaf56d0a8968cd00b8abfc9bcc749b82eab7d1160aaa6c693cef\",\n        \"size\": 97048861\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15425_Weather10.tar.gz\": {\n        \"sha256\": \"83604c6e067379d50fda75aa5042484c1a3cbc53d2bc8908e8268f3d57819744\",\n        \"size\": 331154044\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15427_Weather12.tar.gz\": {\n        \"sha256\": \"a7c26ed8a19e4e6f242051da59b9b5e3ea17c4defed2c09b42b083b6995f110b\",\n        \"size\": 388723235\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15428_Weather13.tar.gz\": {\n        \"sha256\": \"5f765d90392e9cebe82e1a81034666b8aca84b1a83735dc3dd0051e4453820b1\",\n        \"size\": 517663813\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15429_Weather14.tar.gz\": {\n        \"sha256\": \"8b6ae420f2483004a96cfaac4caf2a9779047211aed1ba9b0d741972d324cdf5\",\n        \"size\": 87202443\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15430_Weather15.tar.gz\": {\n        \"sha256\": \"52b2d6dac3b47b071fdc71d4e836afa0207bd43412471eb9b177a299e1020592\",\n        \"size\": 286965386\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15431_Weather8.tar.gz\": {\n        \"sha256\": \"591bcd095d66cf17576c6f15a4bfc8cffeb52198b29ac79f8f7b45da11d854c4\",\n        \"size\": 483625335\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15432_Weather9.tar.gz\": {\n        \"sha256\": \"269a61d9b7a6584a87e2c14da5a0e69d3c3d8f45f0e0adcb4c3e0bdc27f23865\",\n        \"size\": 419468174\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15433_Weather18.tar.gz\": {\n        \"sha256\": \"57106085b95f0a7af08581c44b283dfcf5b7aa4c7e7696482667017f06ad83b9\",\n        \"size\": 444981128\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15434_Weather19.tar.gz\": {\n        \"sha256\": \"69e73381ab04165589c8c84d11a1ed56a43fcbf1ae961087c0ba7e3dede1bc98\",\n        \"size\": 888716466\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15435_Weather20.tar.gz\": {\n        \"sha256\": \"2d8dc0e7c153b31b5a299347d2f931fc6c188a815bf99b6545d50d7812286d81\",\n        \"size\": 327424638\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15436_Weather21.tar.gz\": {\n        \"sha256\": \"088165da9283097e6bc87651f2b42e6cc1d1b9fcce73ed210f672be27b8c0f7c\",\n        \"size\": 620782321\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15437_Weather22.tar.gz\": {\n        \"sha256\": \"a4dc6ed07749950ab8035d155e835cadbc1395b3ab23aae60d55db6387117815\",\n        \"size\": 537869862\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15438_Weather23.tar.gz\": {\n        \"sha256\": \"0a5bb1073d2c89d48a5ef82837978403f9231ac873e3088166bb88e5104e103a\",\n        \"size\": 267274374\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15439_Weather23.tar.gz\": {\n        \"sha256\": \"7acd4135bcfedc094ac06216062b3954cf2e07221f659d8e9f963cda4f69b558\",\n        \"size\": 72273379\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15440_Weather25.tar.gz\": {\n        \"sha256\": \"832aa33d6333e6672e490f6ab1aa109251e87498bbec3d795c7edc1eda2de539\",\n        \"size\": 146155621\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15441_Weather0.tar.gz\": {\n        \"sha256\": \"0d84c8f0890722f58a73fb5c07717d7618a63fcc29c5733450df99ee0468d42f\",\n        \"size\": 303143099\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15442_Weather1.tar.gz\": {\n        \"sha256\": \"445aea0c8d3d1e66d05ef128f98f2cb7500f8e4edf8daaad47c772e7cd28039e\",\n        \"size\": 108329127\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15443_Weather2.tar.gz\": {\n        \"sha256\": \"bc8e3d5e550f17a9621041d70720491a31c620b7b71cf4b06f07d3c6344f2ef6\",\n        \"size\": 791451357\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15444_Weather3.tar.gz\": {\n        \"sha256\": \"1869109ba9aeec7df094b1c904c1d2da423895cddb4a48c0377e100e04d4548f\",\n        \"size\": 393757724\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15445_Weather3.tar.gz\": {\n        \"sha256\": \"b72fb7c9492fd474497ad137668d46703c1327360d24d861274b7823a31e7a79\",\n        \"size\": 528777190\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15446_Weather5.tar.gz\": {\n        \"sha256\": \"d37c4e7853436651e394ea382a8dd76b19a5208924a8d1c0bede0b6930004225\",\n        \"size\": 113851425\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15447_Weather6.tar.gz\": {\n        \"sha256\": \"8cc12a7dac28297a67e885368fc3567f713d0cdac704bd85cd9626609ea3b42d\",\n        \"size\": 401235982\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15448_Weather7.tar.gz\": {\n        \"sha256\": \"f8aa9f0e866232c86eb55310165c74232c4e73175fe56cb5036d149d1466dac3\",\n        \"size\": 507142155\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15449_Weather8.tar.gz\": {\n        \"sha256\": \"d5ce96bb8360068a158dc7f5401871340e88ab177a6ba3c3a981d29ca0d096da\",\n        \"size\": 331038664\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15450_Weather9.tar.gz\": {\n        \"sha256\": \"d5e956d06d1026b605354d9e5e659af3482318c208d6f60081c3f22e88ac21b7\",\n        \"size\": 70712584\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15452_Weather11.tar.gz\": {\n        \"sha256\": \"d5f2ca2c44ce16fb192376db3f1e55995392db8bb9be451cc3bf4f9dd8270573\",\n        \"size\": 156521677\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15455_Weather14.tar.gz\": {\n        \"sha256\": \"07786d8685e9b920183214e22b0c65ec68c29ab3ee798ebdf42a6e8b402beadf\",\n        \"size\": 68321816\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15456_Weather15.tar.gz\": {\n        \"sha256\": \"e6b4b349e03e750cab8bac2b05fbba73995fdfadca0d23291c98d7176de0df34\",\n        \"size\": 367589725\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15457_Weather8.tar.gz\": {\n        \"sha256\": \"15e42fb770d8ad25bdd2c3cbb295db019114b45dddbd789e8a5262a0d113683a\",\n        \"size\": 207582024\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2344_Weather23.tar.gz\": {\n        \"sha256\": \"51b13c02728c4ac0ee3f92ba456382a8896731d5906e2915f7111fe3e2205a90\",\n        \"size\": 420248665\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2345_Weather25.tar.gz\": {\n        \"sha256\": \"ebe059c671f4cc3fb11446582ce4ac0b6910f5d9ac8aef222d90d32acd0df1fa\",\n        \"size\": 208612393\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2346_Weather0.tar.gz\": {\n        \"sha256\": \"7863cb3aee9af4062d73d0fb142f35892c9e9205699d38cec8a9c7c7a7fa275a\",\n        \"size\": 347562718\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2347_Weather1.tar.gz\": {\n        \"sha256\": \"9518f2372a1918a4f59efdb10583b9e3bd5d44db724497de9b2c117f593b671b\",\n        \"size\": 281047780\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2348_Weather2.tar.gz\": {\n        \"sha256\": \"9e919dbf39c61ae235ce25ff9f87953b136c216655482ec7b9012f5f48e7b35e\",\n        \"size\": 102473859\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2349_Weather3.tar.gz\": {\n        \"sha256\": \"be5a72bfdc08f7e993fe2db6e9c4f57a5635412663f4709d8e57b19b0cde44b5\",\n        \"size\": 96729135\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2350_Weather3.tar.gz\": {\n        \"sha256\": \"890db4e50474d2d3f21cbcbbaf714a3bc18d5e42923103195d7f62b191e1fe6e\",\n        \"size\": 555305416\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2351_Weather5.tar.gz\": {\n        \"sha256\": \"9a3e994aada5343162221a6e0cc04572f60e393cc1c0966675d8f4a38686be17\",\n        \"size\": 387012803\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2352_Weather6.tar.gz\": {\n        \"sha256\": \"535f9b35f268c3e76e4d59e31903eee75da2ef6b539ca77ca0828b4e718f4de5\",\n        \"size\": 364544203\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2353_Weather7.tar.gz\": {\n        \"sha256\": \"62208ad4b44a87913784a57b22e7686f87be6e34ef8b02227031c416180732e6\",\n        \"size\": 130031419\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2354_Weather8.tar.gz\": {\n        \"sha256\": \"caa2dd40da63041b640ff07ba64a453d38f7add9111db31151049b12c130a739\",\n        \"size\": 476777648\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2355_Weather9.tar.gz\": {\n        \"sha256\": \"e6f7a298ec61726e036787cdd61b78a46cde53fa8e7aa9bed7b7005694976ee5\",\n        \"size\": 183227325\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2356_Weather10.tar.gz\": {\n        \"sha256\": \"f1e303efaab25b98f13a234eb0a664aba98faeec8b6bffd6e456dbd265fef0a1\",\n        \"size\": 323594041\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2359_Weather13.tar.gz\": {\n        \"sha256\": \"e4264b95b0ed87991f4de4c4289a0e9b9e12bc01e3ac48dd806106929ea4ed9d\",\n        \"size\": 498963014\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2360_Weather14.tar.gz\": {\n        \"sha256\": \"1d37670f195737aca3476516c975e34200bba012453c61a18db3aa9098dbc65f\",\n        \"size\": 170584591\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2361_Weather15.tar.gz\": {\n        \"sha256\": \"4db5cc41a3e2651799ec23d4e222f432a9b05e12567fe2d15743cf04ddcfbbfc\",\n        \"size\": 249462841\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2362_Weather8.tar.gz\": {\n        \"sha256\": \"e317b50bc762225823c32f88f6e3fbfd4884bd436e2dc6a23e4be79eb7686820\",\n        \"size\": 336413866\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route2363_Weather9.tar.gz\": {\n        \"sha256\": \"4600055d98918e64aff2af059e7f038d08d8f2e65dbefae64e72d1b63b8080e4\",\n        \"size\": 363579037\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3124_Weather23.tar.gz\": {\n        \"sha256\": \"5c03369f6377857e94142c4fd4614cfaeb1dce1eb13386497a20b8e79256c014\",\n        \"size\": 231239449\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3125_Weather25.tar.gz\": {\n        \"sha256\": \"175042685f4b8c2f1e098c240084c292b10b6438584db199fd8de1e3531c9229\",\n        \"size\": 170185831\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3126_Weather0.tar.gz\": {\n        \"sha256\": \"d4ff7f85e9721dbf6274f219dd7416f1bc0faedfcfb36f20faaa772308ab439d\",\n        \"size\": 131369051\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3127_Weather1.tar.gz\": {\n        \"sha256\": \"b02e6dd368abc16e1881c9e69e933f39b35a865fd89b281b642fde52b6b9362c\",\n        \"size\": 95841473\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3128_Weather2.tar.gz\": {\n        \"sha256\": \"2643d9a09c75774a160e32b52f396ce388fbc8a856abe3ee7a72d5dbed4f82dc\",\n        \"size\": 542901556\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3129_Weather3.tar.gz\": {\n        \"sha256\": \"b1704da2159df31324779937e39eb68ee0ef20c338b3cb5154e0e946c9a9f514\",\n        \"size\": 82141744\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3132_Weather6.tar.gz\": {\n        \"sha256\": \"8d58a78c0974f3e4c07472e646e37b269f0fb48acba8cbd74ff28ad0a9373c29\",\n        \"size\": 361396411\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3133_Weather7.tar.gz\": {\n        \"sha256\": \"8a55962b9ccf477f2215083eff587f85c3a00fbec9d140fb9283dc648689e190\",\n        \"size\": 620702658\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3134_Weather8.tar.gz\": {\n        \"sha256\": \"21d2a66e42d2ac61e12495a205a427f06038caa3e74131f1224f58db421b7140\",\n        \"size\": 745724889\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3135_Weather9.tar.gz\": {\n        \"sha256\": \"2bc7409320bade560031ce062c3f9de3875d14acc3cdf760b0cc9818fd2e99b5\",\n        \"size\": 266610108\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3136_Weather10.tar.gz\": {\n        \"sha256\": \"f4ec0735a2aafa6a672543d01abef21b248dd44b7ef7f662d1284f852a65fa4e\",\n        \"size\": 185015166\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3137_Weather11.tar.gz\": {\n        \"sha256\": \"5e61f28f40087784aa4e6ac2bcd5b32f0d09e1431174b6aad4ba60f9750de302\",\n        \"size\": 783076559\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3138_Weather12.tar.gz\": {\n        \"sha256\": \"c7cb544478301270d2e5b1d323bbc5f9ffc2ab552adb4da2dd29eed7727a272e\",\n        \"size\": 181272574\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3139_Weather13.tar.gz\": {\n        \"sha256\": \"c97da202dbb4a2e0dd69268b59e9916754782b112cf1ee089a51b77845637f6d\",\n        \"size\": 253564199\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3140_Weather14.tar.gz\": {\n        \"sha256\": \"ca95dea7673f0131655d895cd8fbaa3ce0a8abdca1e7d91ba55cf409b00feab4\",\n        \"size\": 500150775\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3141_Weather15.tar.gz\": {\n        \"sha256\": \"91618560f356e11427a598dbd9229fd71b0e8ceb1ae671cabe805b9d8e211a2c\",\n        \"size\": 501070021\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3142_Weather8.tar.gz\": {\n        \"sha256\": \"a4827632d141cc6b35015394cf2743a08d788ec1e2517c8d248dce3599a9e4c8\",\n        \"size\": 142339919\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route3143_Weather9.tar.gz\": {\n        \"sha256\": \"07ec1466219474517242041ee2682655c9921143053a09262939c641966fe160\",\n        \"size\": 58654233\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3843_Weather8.tar.gz\": {\n        \"sha256\": \"a39c1fd50f4131b7e54a5898da35243fc6c033d5ceff1dc26242e21d9f0d9adb\",\n        \"size\": 253582447\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3845_Weather18.tar.gz\": {\n        \"sha256\": \"4f63e02a85198cf0e57e8508e9029575b64b85959dfa53c9c91596d09fa05793\",\n        \"size\": 395870475\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3846_Weather19.tar.gz\": {\n        \"sha256\": \"731ee60a48839c1ca3d04b38fef357f547e420cad667b269f539952b2caa8d85\",\n        \"size\": 717752934\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3847_Weather20.tar.gz\": {\n        \"sha256\": \"08985d0f775b7d5e69a556f4fc9faa6e742ca540749d511fa2a576daed4f2ea9\",\n        \"size\": 474810419\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3848_Weather21.tar.gz\": {\n        \"sha256\": \"7cb9a35c99154bba5702b7714ce25153caaeff2d1a6af8171650376a1252de82\",\n        \"size\": 412577459\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3849_Weather22.tar.gz\": {\n        \"sha256\": \"837f80a8cc75f23fce32aa67604d5bcc00c3df99393d170d709c7dbd920c6c8d\",\n        \"size\": 396271318\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3850_Weather23.tar.gz\": {\n        \"sha256\": \"290625f469252bf4f458050aa47bd3ecea23f13ea47406c7eeffc96708d7a789\",\n        \"size\": 75949858\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3851_Weather23.tar.gz\": {\n        \"sha256\": \"76075c8195aba946619c33aaabda554800ea0b551f22eaad71b98a2579dd8662\",\n        \"size\": 74136550\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3852_Weather25.tar.gz\": {\n        \"sha256\": \"c6cd5e3bc2db225b72743021beacdf5910435d202dbcd3a604ad1be9a3285504\",\n        \"size\": 75717319\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3853_Weather0.tar.gz\": {\n        \"sha256\": \"a840370c98d23354161e450efc00a7e29b16309ec714cf564bdc8ad83e924b5f\",\n        \"size\": 513649333\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3854_Weather1.tar.gz\": {\n        \"sha256\": \"b079703dcd0241467f6bc8af8366e55ee7dc76c0ff380279bb637f6b75415eb1\",\n        \"size\": 263178754\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3855_Weather2.tar.gz\": {\n        \"sha256\": \"c644eee1a42b62a5ab3deb99bc9da04b168f8869fabc27a36d9bea74f8b52631\",\n        \"size\": 96195962\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3856_Weather3.tar.gz\": {\n        \"sha256\": \"24b5bd23e5d2646424656953056337aa08d5ad321f0d2f9d39c2577f545b404c\",\n        \"size\": 375465463\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3857_Weather3.tar.gz\": {\n        \"sha256\": \"167b3372e24fdf6aedebee6ac486301e3fd483a429b6e2365a9ad6ac9493aa5e\",\n        \"size\": 237314479\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3858_Weather5.tar.gz\": {\n        \"sha256\": \"a5147e3387a852f5e7592717e2fdfeb35192b445aa7d3fa17be2d3b6289a5693\",\n        \"size\": 274754042\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3859_Weather6.tar.gz\": {\n        \"sha256\": \"1330b25cf8c033af58d3a524308b479b4192b4b0c53a686b7b917c0b7e6cf143\",\n        \"size\": 281573836\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3860_Weather7.tar.gz\": {\n        \"sha256\": \"2bf45646c1e62521f966291335587ef14d9d9367c5636ac67036af27add5f4cf\",\n        \"size\": 282081432\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3861_Weather8.tar.gz\": {\n        \"sha256\": \"bc1c06fd240094d0e3396efff6a91f56371fe0d91aedbbab53b3d1fe20fd5a76\",\n        \"size\": 520888789\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town13_Route3862_Weather9.tar.gz\": {\n        \"sha256\": \"1aaf98a80c5dacc92584ec2acecf04d70cff42eccbb6f5fd6c7b30dc1b8c13bf\",\n        \"size\": 332106248\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town10HD_Route24840_Weather26.tar.gz\": {\n        \"sha256\": \"486ad28dafb9521e702f3bd45054058ba09a1d721a5cd5f60696fe6730ef21d8\",\n        \"size\": 238094088\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15458_Weather9.tar.gz\": {\n        \"sha256\": \"2dd3720a6ac3959a19173f338972768b8e25ceb87397bea6f70f28e643dbb5fe\",\n        \"size\": 472298262\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15459_Weather18.tar.gz\": {\n        \"sha256\": \"ba0b5a034695b95e6769e0f940e8e8846efb4e0aac6ab2c328e9dc14c83cfcb2\",\n        \"size\": 343073430\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15460_Weather19.tar.gz\": {\n        \"sha256\": \"42d1ebd7817e4102d3bd82ed37dd74247135ddb9ac615abfa41615be0189a392\",\n        \"size\": 517626497\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15461_Weather20.tar.gz\": {\n        \"sha256\": \"b349c5b04be9b1d01c2ea9784c30819972faf33a8266284999186bfbd91af7bf\",\n        \"size\": 566846894\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15462_Weather21.tar.gz\": {\n        \"sha256\": \"3260d3b9eee5f90d36ea66124ca7cf20593d08011ede94738dd485f6e64d9e0f\",\n        \"size\": 458566826\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15463_Weather22.tar.gz\": {\n        \"sha256\": \"f85b2ff642960f82ab362855a8b245770f8154900ea0ed7baafc64137aa04ecd\",\n        \"size\": 141320106\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15464_Weather23.tar.gz\": {\n        \"sha256\": \"a54d4c5bf073c5415f6498a2b5ff7bfe80473c8aaa38d00113cd3afd551527f3\",\n        \"size\": 246158059\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15465_Weather23.tar.gz\": {\n        \"sha256\": \"7431a705eebe93418ea570919f828b2677415a6d74ff2c1e42d5f046dcb7df64\",\n        \"size\": 221548691\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15466_Weather25.tar.gz\": {\n        \"sha256\": \"63a82c27339bda968e7471b838691b13f240cc1e847ee12d480074791f8dc008\",\n        \"size\": 376791037\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15467_Weather0.tar.gz\": {\n        \"sha256\": \"e497d5d317d295e1733a533bc76c5cefcd4905758d88b172cf10e4d2a7477f6f\",\n        \"size\": 470095022\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15468_Weather1.tar.gz\": {\n        \"sha256\": \"8c62f944abac3e3d451097885784d06e9ea4deca2855dc07aade73d0f3ec8d64\",\n        \"size\": 577195238\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15469_Weather2.tar.gz\": {\n        \"sha256\": \"e26abd102c5fccbaf1bf3a14a59ac37ce4961ead12f7e5a6e573605686498cea\",\n        \"size\": 695379687\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15470_Weather3.tar.gz\": {\n        \"sha256\": \"fe4cc5283a3620ed716c7729d61076bc663e98596609580c11ee519b80dbe459\",\n        \"size\": 167870657\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15472_Weather5.tar.gz\": {\n        \"sha256\": \"31a3ae1096d712a5e21f70490377376ced02479d8efa9e87cce4ddb0b2974fdd\",\n        \"size\": 404251896\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15473_Weather6.tar.gz\": {\n        \"sha256\": \"f59c481838f80bd8f17d3e451285ddecfba4d6a976f27c007dbc981c1de7cbbf\",\n        \"size\": 859827977\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15474_Weather7.tar.gz\": {\n        \"sha256\": \"9f19fc05ef3fcd9e6e49a32d5054b7a5113af068b3d1553ae2550a2f5857cf72\",\n        \"size\": 316440313\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15475_Weather8.tar.gz\": {\n        \"sha256\": \"dd71823e2775aed4decdfde6c7dcec342322aa0f3f3ab4b9ad2ec048e7d187b0\",\n        \"size\": 436343971\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15477_Weather10.tar.gz\": {\n        \"sha256\": \"ca4837fedee327738fa8937a922b66e1f1f4636687ee8b2705babc015b71e88a\",\n        \"size\": 517481631\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15478_Weather11.tar.gz\": {\n        \"sha256\": \"7aac7597c16c735d9d345dfe486f4a91ac0881fbf71b542c6b675b879c07b027\",\n        \"size\": 244882578\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15479_Weather12.tar.gz\": {\n        \"sha256\": \"fdb693bbeb662c804d2c0cc1b8acc7f2935c19c8b417dbb568c07a190d2ce3fc\",\n        \"size\": 110787808\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15481_Weather14.tar.gz\": {\n        \"sha256\": \"13cc53508387c82149cc6d85b571df1fd22304476fc43f490330b612300d8ec0\",\n        \"size\": 260672999\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15482_Weather15.tar.gz\": {\n        \"sha256\": \"38792ae8446f26d0db0e4fbbc44d35d31ef3e8fa81282b15cfbfeaa1c8608541\",\n        \"size\": 201069726\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15483_Weather8.tar.gz\": {\n        \"sha256\": \"66a6b0f9c33d933d209d19c1d9e96d7746c6b357b4e030ff38397b46589831d4\",\n        \"size\": 376279262\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15484_Weather9.tar.gz\": {\n        \"sha256\": \"7b8fa016676ed23080e3fb5fff6a4a397c4db3559d6df81809a9e11d41d07273\",\n        \"size\": 268587619\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15485_Weather18.tar.gz\": {\n        \"sha256\": \"b7ece957bb6a7c37e291ab357cd95741b75e7a8d7151bda6ac76cf771f90fe81\",\n        \"size\": 226023802\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15486_Weather19.tar.gz\": {\n        \"sha256\": \"45fcb6642a65aa2c8247c67ba419e708d836b5aa274f98ccf1bc7c0473d2ada2\",\n        \"size\": 266050303\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15487_Weather20.tar.gz\": {\n        \"sha256\": \"f6e455d5ca5f2373f4c2b3a6608ae266cbbb2ef97f38a94cfaf436c14430b4d0\",\n        \"size\": 378769498\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15490_Weather23.tar.gz\": {\n        \"sha256\": \"b82e5c0359af9a44efed6b4a4b7e01ec3f08d396b4e6b5993df5557da26845fb\",\n        \"size\": 574206881\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15493_Weather0.tar.gz\": {\n        \"sha256\": \"14f95ba1ade1e30500804619428c31064116e00f239454c4ed8e9267e8647669\",\n        \"size\": 610580450\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15494_Weather1.tar.gz\": {\n        \"sha256\": \"c04b62ae70cfdc55398fef187adf8995d290c754e2a972e084e4ca93239a3d67\",\n        \"size\": 433712761\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15495_Weather2.tar.gz\": {\n        \"sha256\": \"e1658842eea78a6cd2eaf82cf9c73219cf4c857f43882656c9d68734d7defb3c\",\n        \"size\": 913610278\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15496_Weather3.tar.gz\": {\n        \"sha256\": \"afea16671afe102f2a7c4faaaf7314643ebaa95a40322ac98d86f63ab737eae8\",\n        \"size\": 309217098\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15497_Weather3.tar.gz\": {\n        \"sha256\": \"39f6544cebb6b92f682c523e013d3d2e4ee82b1adfb614d9d36b70762e2ce3ff\",\n        \"size\": 123426297\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15498_Weather5.tar.gz\": {\n        \"sha256\": \"1a1d33cdcb4236eeeb266da9fd420f974347441a8a11b00d54394db4a81bd33c\",\n        \"size\": 774874414\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15499_Weather6.tar.gz\": {\n        \"sha256\": \"b8776f97d70ecb014d891da07da40bb2ddae97351d853deedecea3d59db2b679\",\n        \"size\": 746499643\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15500_Weather7.tar.gz\": {\n        \"sha256\": \"12fb75244a52235e735dab246074b2bf3cdb2ade230ba458a96bb052b2459b09\",\n        \"size\": 149830710\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15501_Weather8.tar.gz\": {\n        \"sha256\": \"75791d76b9d641b64b5632676417cc75f4d51603059fe9432eaf7d8b7046625f\",\n        \"size\": 518901634\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15502_Weather9.tar.gz\": {\n        \"sha256\": \"a079ecfc9f64ce1b1d0e240a6ffe5435dfabade0d7a063dddac06221f2fc65a1\",\n        \"size\": 527889502\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15503_Weather10.tar.gz\": {\n        \"sha256\": \"f44088a5061bbfa6c7cbcfc9ba12de284a91e15261c15b1cdc4d8ce0cace8f3a\",\n        \"size\": 266102306\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15504_Weather11.tar.gz\": {\n        \"sha256\": \"189b88c776dd82b361ce053b096bb00b7e90392dd9dc11cb8d24f2b8f89a3609\",\n        \"size\": 366223177\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15505_Weather12.tar.gz\": {\n        \"sha256\": \"3cf96b8d5b2b2ac95b887a310b4098573431c295d47287a882113ba486e8f01f\",\n        \"size\": 549658222\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15506_Weather13.tar.gz\": {\n        \"sha256\": \"8b0d3056cf1d6e13151de4c26889c126448b5ec609f914131fbe19520fde20b5\",\n        \"size\": 112806772\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15507_Weather14.tar.gz\": {\n        \"sha256\": \"28d475652ec2869b9234fb13f1cd2c206df8209df080193b20e2bf84080fc666\",\n        \"size\": 227758601\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15508_Weather15.tar.gz\": {\n        \"sha256\": \"1334a3fb4f6dd35a8c727a7869db5ae90961c8973f1cdbfc441c5dca0f2d5961\",\n        \"size\": 136765472\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15509_Weather8.tar.gz\": {\n        \"sha256\": \"45289088953ceb168243dd6c283c08f9625c5c2ec5a98c6ba60b3fa91ae91410\",\n        \"size\": 180043520\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15510_Weather9.tar.gz\": {\n        \"sha256\": \"c2e79636b4166cab7ac0e76207e605937484784334d62de29617f5541c971554\",\n        \"size\": 188852703\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15511_Weather18.tar.gz\": {\n        \"sha256\": \"8158b0b1de16ee377c258da16993b1a7a1915920ef74d3ba8a8e0b177a849a71\",\n        \"size\": 138172859\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15512_Weather19.tar.gz\": {\n        \"sha256\": \"2cbc6ab7bcb0fee55a95179ec46fce8542827107d04e6ccf856a8a1bab8c041f\",\n        \"size\": 271097793\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15513_Weather20.tar.gz\": {\n        \"sha256\": \"9b18b982db7def2a1bbb3474f83479502d81beeb86f1896638a2ed2e60c31960\",\n        \"size\": 167680550\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15514_Weather21.tar.gz\": {\n        \"sha256\": \"e90e0307de0d97b8361e5c232d8553ef199b5cd90706d9a230bb63e1b44b871c\",\n        \"size\": 372982991\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15515_Weather22.tar.gz\": {\n        \"sha256\": \"f5233e37c81357c4acb13a21b91b2ebc4c33ea4cc6dd2cdacfeb8403944d1c7c\",\n        \"size\": 471610455\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15516_Weather23.tar.gz\": {\n        \"sha256\": \"0b409644fca95ed202430cf352498b7e9d499b37bc1c46063d04fac1234f4d97\",\n        \"size\": 161108465\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15517_Weather23.tar.gz\": {\n        \"sha256\": \"6f0cc218b99d8497c31e3dfbd5aa6869d758c8f95e824e1c648625c93ba0a381\",\n        \"size\": 665011033\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15518_Weather25.tar.gz\": {\n        \"sha256\": \"88dd663cb39b26f8d63452d6123e820a8c5e1565a019773d195a5f595a2b07ef\",\n        \"size\": 565289487\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15519_Weather0.tar.gz\": {\n        \"sha256\": \"57435cea2e503789d51da99bf52fde4b3e7a06a82a7b39be265edefa343b126a\",\n        \"size\": 139457959\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15522_Weather3.tar.gz\": {\n        \"sha256\": \"67d6e8f75fc7013f659e8fc4bdcd2f18cd5044f4eef1eee0a01fa024ac9c7c3c\",\n        \"size\": 570779772\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15523_Weather3.tar.gz\": {\n        \"sha256\": \"38b3079b52f6177f1113cdc4a6dec7fdc67ccfc93877ddd9175e2130f505a065\",\n        \"size\": 267421387\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15524_Weather5.tar.gz\": {\n        \"sha256\": \"4acf00bc1ef1090fdfb3685eaff15483812cba37d262a091325a52a6c1fd9048\",\n        \"size\": 150991638\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15525_Weather6.tar.gz\": {\n        \"sha256\": \"2e5c493b60f7bb5cb3afc867103c295fa78d9c8597f8bcb81d9a7d774cbd6458\",\n        \"size\": 539932392\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15526_Weather7.tar.gz\": {\n        \"sha256\": \"e7fd023fc82136ec99b74357dec23484fda2b71cd28d3fa6ec3c7e427ab6b6ad\",\n        \"size\": 553334506\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15527_Weather8.tar.gz\": {\n        \"sha256\": \"653f585d346a08ada0265b3ac1d1ca809860750c5459043cd4c86516cf195027\",\n        \"size\": 363550599\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15528_Weather9.tar.gz\": {\n        \"sha256\": \"aa797b921964e9ce7614f80d2c41fe2e27147303061ad33593427705a7fd2a61\",\n        \"size\": 310426471\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15529_Weather10.tar.gz\": {\n        \"sha256\": \"f771b3f99b87eefe3b8a24c776931ffb6c2980f671cf9827b764a42a1acdf886\",\n        \"size\": 741136647\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15530_Weather11.tar.gz\": {\n        \"sha256\": \"616ad92dfbfecf9a4054680e2cc275fb895f70d591363bcacff35ef82278cd32\",\n        \"size\": 263723184\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15531_Weather12.tar.gz\": {\n        \"sha256\": \"6e361e3cb627239d27ffc837bd429392d0bd0cfc837d4dd6c21f55d16cb49c73\",\n        \"size\": 111297504\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15532_Weather13.tar.gz\": {\n        \"sha256\": \"5e1e90a0cd68675d4722c3c01f44de5fb181a0bba373229d95662325b2bb8ae8\",\n        \"size\": 426339473\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15533_Weather14.tar.gz\": {\n        \"sha256\": \"43f5666bb45aa362843a4cb2a8ec9c879fb8324233a984f3b84dfcbe29e1e024\",\n        \"size\": 460167965\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15534_Weather15.tar.gz\": {\n        \"sha256\": \"68747426bc997f158fbed0cd24922f6a3aa316de6bb12c9684c05b50f6655dbb\",\n        \"size\": 193998728\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15535_Weather8.tar.gz\": {\n        \"sha256\": \"c89f151fd72e8d68682d3c6dea5dda3a82a30ea5c5d7fb6cc23efa2450307a5b\",\n        \"size\": 446570525\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15536_Weather9.tar.gz\": {\n        \"sha256\": \"bf393e6bcb1f0063cf2f2e5c30cfa393d1dc7844da2097953809b9f3fdc6fe36\",\n        \"size\": 453866523\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15537_Weather18.tar.gz\": {\n        \"sha256\": \"3ec59928bb6ab912b415b527aac91ed999eed71b019fe8cdbfc52d446c6b0737\",\n        \"size\": 462063466\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15538_Weather19.tar.gz\": {\n        \"sha256\": \"0e8d9bb01bad8c5a6e81aa655a3a696599a918831b4fcceb1967a20b170a64d3\",\n        \"size\": 178790712\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15539_Weather20.tar.gz\": {\n        \"sha256\": \"374bca549cbaa612b51370d0b1828e69eb97a2517d468b7d1980f4697641eb45\",\n        \"size\": 399001647\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15540_Weather21.tar.gz\": {\n        \"sha256\": \"0e3ebd0d058458045569d3c6a01aaa2567504cef619b1606a7292e52d006d0e4\",\n        \"size\": 362789457\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15541_Weather22.tar.gz\": {\n        \"sha256\": \"5e2ceb94cd5fa61aa8039e45ff2298815a5041e67e0970a13c4341a5825068ba\",\n        \"size\": 607330324\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15542_Weather23.tar.gz\": {\n        \"sha256\": \"7ae8785947e728e2c76d98df30023e7f54b6e604f7d9120dca2016d4878a8d38\",\n        \"size\": 106004193\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15543_Weather23.tar.gz\": {\n        \"sha256\": \"80926e0be6ea44ee82b1c16be352e69ffd8a4d6d0a42cb87fbda493497ddeff6\",\n        \"size\": 436655069\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15544_Weather25.tar.gz\": {\n        \"sha256\": \"cd3c414cea61a10458dd1ea8c2a4d00adb097ff9f3f3e3b0b28cb4a0a818c144\",\n        \"size\": 337746270\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15545_Weather0.tar.gz\": {\n        \"sha256\": \"f18750b876a03a4464f00a0c3adea2a573853eb1412f7927cbf0a9b0c8cb95c3\",\n        \"size\": 550840171\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15547_Weather2.tar.gz\": {\n        \"sha256\": \"dad78559781349abc9aae3d38ea039e4e38b0fd3726d695f1dc822bd0a080c6b\",\n        \"size\": 175423815\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15548_Weather3.tar.gz\": {\n        \"sha256\": \"03d821bb609e9ee0019157ea428704081b15e4553032dd293ecb97d63ca8a3c3\",\n        \"size\": 136083243\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15549_Weather3.tar.gz\": {\n        \"sha256\": \"c9f930324b7aa88409e9ee0b88e71f60a4c8e6d181519742ead29679ae6a04f3\",\n        \"size\": 116063145\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15550_Weather5.tar.gz\": {\n        \"sha256\": \"6ad64adc2397a7fcfd2a96134e0ce7b51c46efdcffb9f3b9f4492f7dd9e5dc13\",\n        \"size\": 375729071\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15551_Weather6.tar.gz\": {\n        \"sha256\": \"5acd64eb51cadf2a0433d6916a50ff68ef720a43a86cd039181966107db2b059\",\n        \"size\": 737560148\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15552_Weather7.tar.gz\": {\n        \"sha256\": \"b6209f2917f4ff9ad603a9c3fd87a65ef09cc20c84119afdc753392e448b1670\",\n        \"size\": 721661365\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15553_Weather8.tar.gz\": {\n        \"sha256\": \"6eec3ae8b6818f870e4c32071923400ad8e43e9586070edc2b263a53dcfc7328\",\n        \"size\": 471712594\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15554_Weather9.tar.gz\": {\n        \"sha256\": \"965d4fab0f026b7a6490739fe6afcc7b1b77b081047cd5c1b00d8c96acfce172\",\n        \"size\": 202692892\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15555_Weather10.tar.gz\": {\n        \"sha256\": \"f94669131a81dd3ad23c08b492d8bd2a9aebbfe541f3811b924be07445e57f50\",\n        \"size\": 970457801\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15558_Weather13.tar.gz\": {\n        \"sha256\": \"348a0160571e1a80082b99a5172dc75bae75acd222824fff7d9cfdff3ce0f96a\",\n        \"size\": 237288870\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15559_Weather14.tar.gz\": {\n        \"sha256\": \"e320461e9fb3abd5c5aaedc3025113dc77b749cf2b21886c772952370522a167\",\n        \"size\": 276713051\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15560_Weather15.tar.gz\": {\n        \"sha256\": \"fef796b6f972c944617c3b85f20572456529c063b0e7add46636fa13feb45798\",\n        \"size\": 1059910941\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15561_Weather8.tar.gz\": {\n        \"sha256\": \"34743b82fe7f2a413b65c92428695cae79c464602fee84e3462e2fab2f30e7fd\",\n        \"size\": 126656911\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15562_Weather9.tar.gz\": {\n        \"sha256\": \"53dc33093c15216d6f06ce698caa73bcdad88dd0e601ff86d9b1427d1033b18d\",\n        \"size\": 320670277\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15564_Weather19.tar.gz\": {\n        \"sha256\": \"f2c62bfb792db2cf4fc36f28115d5addb6c691f760c00f1d2f7fb878173acd4d\",\n        \"size\": 194371230\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15565_Weather20.tar.gz\": {\n        \"sha256\": \"72e55953bf9bacef4d90899acd3bf833d9b5f066ca69bf0fa8feeb28a906035d\",\n        \"size\": 165213189\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15566_Weather21.tar.gz\": {\n        \"sha256\": \"8787f89f1f739b7c15f755c9fdcad00fdc225747abc5b965fde13fc7f4b41662\",\n        \"size\": 632181660\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15567_Weather22.tar.gz\": {\n        \"sha256\": \"2403eb1a24aaca81ba858431caea773d81734187c7bc034cad6e7eb6b9279986\",\n        \"size\": 333309425\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15568_Weather23.tar.gz\": {\n        \"sha256\": \"59475384b64882a8433a0329f17e578a6ad1ae5f569df1f64b4c0245488009ad\",\n        \"size\": 200338035\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15569_Weather23.tar.gz\": {\n        \"sha256\": \"33713029eee65203091e8cf69b6db7f9db331a706f99f16a7ccb20ef79d63fb4\",\n        \"size\": 534569560\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15570_Weather25.tar.gz\": {\n        \"sha256\": \"13e88f6e2aae024027fb7245eba8dc5b41a7e08c42645020eb89b4aa6e0490a0\",\n        \"size\": 260362011\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15571_Weather0.tar.gz\": {\n        \"sha256\": \"5042931c2f7eec9b903349d63f6a29a1ffaeb8cd01c7b25da568d33e9b39c958\",\n        \"size\": 174461626\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15572_Weather1.tar.gz\": {\n        \"sha256\": \"77682fc2c25b1a139d663ee52e0ac91303576343d54feff7f0b64be1d75682cc\",\n        \"size\": 852793031\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15575_Weather3.tar.gz\": {\n        \"sha256\": \"76b5b3503db8caf450056702a9234d4f0268771379f2d60e76982bc5e6bb417f\",\n        \"size\": 415012449\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15576_Weather5.tar.gz\": {\n        \"sha256\": \"6471e36e80a612dee6a65ae64bd1152987e0d139df2c6a36e7c1573d2e5a826e\",\n        \"size\": 328438902\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15577_Weather6.tar.gz\": {\n        \"sha256\": \"a4d362dcc6e75928fe6c796478fba6d8f43564a47fe2934a802169a4ffd7f020\",\n        \"size\": 351453266\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15578_Weather7.tar.gz\": {\n        \"sha256\": \"401d4d4a71b885cf36458eab4f914176575fc57d681b54c66a716b3806e9dcf9\",\n        \"size\": 429573448\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15580_Weather9.tar.gz\": {\n        \"sha256\": \"5e41f41cc4ab44b3329c4a3a034ace52f736b147150de1e6030067db2851c456\",\n        \"size\": 647894472\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15581_Weather10.tar.gz\": {\n        \"sha256\": \"784449285911981a893ff6ba6ee647a4d92a3d6c4ea78979e7f2c396d0b4dacf\",\n        \"size\": 605108883\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15582_Weather11.tar.gz\": {\n        \"sha256\": \"7d25e777c2ae95930a999180d6376d500c849a60dd33ab5b74ef8bca148b79cb\",\n        \"size\": 182995583\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15584_Weather13.tar.gz\": {\n        \"sha256\": \"276b75f6c90d3643299e625103b942a5a2c0a8c343cce8c0380e3d95638438af\",\n        \"size\": 698740607\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15585_Weather14.tar.gz\": {\n        \"sha256\": \"e9816198227c49d6abf02ad6ebfcd7f1d9e82ecf6256c9f0202a72d18df76598\",\n        \"size\": 315271715\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15586_Weather15.tar.gz\": {\n        \"sha256\": \"c473faafef8435866e982f3b316546a6ed85cb9a053645accdbbff57c84c4708\",\n        \"size\": 147423202\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15587_Weather8.tar.gz\": {\n        \"sha256\": \"5cba78a7f93268cae7eea2937001e70ddeac1a12808f96fd006dd4fb483723e0\",\n        \"size\": 132143471\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15588_Weather9.tar.gz\": {\n        \"sha256\": \"3f0075d7659d7b69acf847a18c1fb6abda819eee98d20bb3c2e541b6a8941f5c\",\n        \"size\": 163854276\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15589_Weather18.tar.gz\": {\n        \"sha256\": \"dd76bb9afb575b039a99b8e4220be94815d469e36b81727368643395cb9b083e\",\n        \"size\": 303550357\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15590_Weather19.tar.gz\": {\n        \"sha256\": \"47c765cb62910a613b89e80dcd9e1e25e431ccd6b318d21b7f6175481769ab73\",\n        \"size\": 383470014\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15591_Weather20.tar.gz\": {\n        \"sha256\": \"dbb5d933fd53f7e3676d47a12647ed7ac0ae0bcba15627cff85fa505a663464b\",\n        \"size\": 146269941\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15592_Weather21.tar.gz\": {\n        \"sha256\": \"ca8e704dc0af26104e21b8d077547d8a3fab9935e4eaf1895edb6ef0dde0e1be\",\n        \"size\": 252515623\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15593_Weather22.tar.gz\": {\n        \"sha256\": \"915bc79b1a44fad691e687a3cb9c7a465568ae1c08b6238a88f43815b76c47f7\",\n        \"size\": 375710771\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15595_Weather23.tar.gz\": {\n        \"sha256\": \"f193e78c20d0c64db2b4a6a8621e2c5ea93f2d197e4f9a559a0b9c601ec25e09\",\n        \"size\": 222932224\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15596_Weather25.tar.gz\": {\n        \"sha256\": \"8e72bc279f3496fff3fa1a8170e7ed7597f102d17a7d1fa6d59e54b2d4d2498f\",\n        \"size\": 277687605\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15597_Weather0.tar.gz\": {\n        \"sha256\": \"a06eba147020a0391e5a8a5be6784b955b8c135815a104464e06d0ebb9bda35d\",\n        \"size\": 277188907\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15598_Weather1.tar.gz\": {\n        \"sha256\": \"79f902f0254057c4458ddd9859be2e44b353dbe8b9705639c3344b1571b5fdb0\",\n        \"size\": 296065217\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15599_Weather2.tar.gz\": {\n        \"sha256\": \"aac8ed008cad291e5dd98ca53fbcf04c8163cd74f995895aa1e9eba7f71b86a4\",\n        \"size\": 535799788\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15600_Weather3.tar.gz\": {\n        \"sha256\": \"7f07ce2f05dbf94b4c70f7365a3dfe97292fab9409ebd90ac061a2fc8ca4527e\",\n        \"size\": 325421672\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15601_Weather3.tar.gz\": {\n        \"sha256\": \"6cee5bdd2b8ca45907fb5edf91502113ec3c0dd25cebc06c8df1140bc2955a48\",\n        \"size\": 885838990\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15602_Weather5.tar.gz\": {\n        \"sha256\": \"39e551aea503a019621c3f48c4457a0a71ae8cb70516bcf39d3b992dd946d99f\",\n        \"size\": 186695704\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15604_Weather7.tar.gz\": {\n        \"sha256\": \"52257139873b7a5b353ed8e0f001fa6eb5ac001d85adf9b1273656b0ccdb27b9\",\n        \"size\": 169107198\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15606_Weather9.tar.gz\": {\n        \"sha256\": \"690142904919f7cfe19077552414984e704dd080262c956d95c9027f8b7f94ef\",\n        \"size\": 206482493\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15611_Weather14.tar.gz\": {\n        \"sha256\": \"0e4fc25ca5dd65867108d7a86146c9f277dd02bbbd0bf5c55c66c787c843b285\",\n        \"size\": 488845611\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15613_Weather8.tar.gz\": {\n        \"sha256\": \"ef6fbbee0f4e09d0c64afb233b5ae904296efb542ba345fbcef0fdd6553a2fa9\",\n        \"size\": 146862669\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15622_Weather25.tar.gz\": {\n        \"sha256\": \"701443d34f30654a316c875b74d96c7d7b1d4d840af868719a2646928e95d17c\",\n        \"size\": 196670625\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15638_Weather15.tar.gz\": {\n        \"sha256\": \"b84b01d16330dc4f9921e6269833d70ab771fe59b7336ae26d4f0d2118a0072c\",\n        \"size\": 659360399\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15639_Weather8.tar.gz\": {\n        \"sha256\": \"a90e3b1956b796c6981892a53382a4003ed9cff00a99fdac68d152a1346ccf46\",\n        \"size\": 630650447\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15694_Weather19.tar.gz\": {\n        \"sha256\": \"ffe5c03751db87b2ee2f452a374a7e2ea984a9a4b8500d8e761e9a6cc7a9c018\",\n        \"size\": 385943480\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15699_Weather23.tar.gz\": {\n        \"sha256\": \"b5b3654f1e294a6120b1d2a077c3e701d8f5ba744ee1a6fc6d08784847401d4c\",\n        \"size\": 472627484\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15736_Weather9.tar.gz\": {\n        \"sha256\": \"2d4baf34a74ce8e508b23c6e9b6159082cc5dfd99a24d305c5fd7f7d17e759cb\",\n        \"size\": 347616648\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15759_Weather6.tar.gz\": {\n        \"sha256\": \"45a44807a8ff66a4431a4d454a8ea755caab94a5f769f00c0bc8bebd213c1912\",\n        \"size\": 410341582\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15761_Weather8.tar.gz\": {\n        \"sha256\": \"d5f893934a929807f1ddf41f03f7b8af88ec6b95dc64d5fa479e05c7123e7444\",\n        \"size\": 179137153\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15785_Weather6.tar.gz\": {\n        \"sha256\": \"4a48603e83c4bfd8a6a8e3bc50d1fdbe38191f99560e7f748e4f09eeeb56291a\",\n        \"size\": 467302945\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15798_Weather19.tar.gz\": {\n        \"sha256\": \"81644c81d814f5b31fd88f86f4f83305777a21695354938cbc4612ab62be63c1\",\n        \"size\": 346424342\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15819_Weather14.tar.gz\": {\n        \"sha256\": \"877737de6c30f1f9420d2a3d661944affb9a800da0214ed2bf72e9e5be93801f\",\n        \"size\": 530762618\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15831_Weather0.tar.gz\": {\n        \"sha256\": \"8e0f49ee6b9892a801b137248e5452962218b345d2f0095b4c33c4ee6d7c7502\",\n        \"size\": 226906837\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15832_Weather1.tar.gz\": {\n        \"sha256\": \"7055b9e82158a4e13180aa03863b309d8b436b6e2cad60db57a1a8f8e7c573c0\",\n        \"size\": 415177728\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15842_Weather11.tar.gz\": {\n        \"sha256\": \"ec769a690cd9ccdb81d8690268cfb4c885d97fa4af649123ff943ec0ab4d0d41\",\n        \"size\": 203332470\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15849_Weather18.tar.gz\": {\n        \"sha256\": \"7e8d5c2fedeb695b3ff89e4e9172d725a06bdf61df091719045bc1ab07c7a8b6\",\n        \"size\": 164720064\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15854_Weather23.tar.gz\": {\n        \"sha256\": \"53d14db46c6ee45fc4bf1aec69bc26e5835b5059305c6693e623d7ad416b3672\",\n        \"size\": 573884929\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15856_Weather25.tar.gz\": {\n        \"sha256\": \"0ab86c8c65a561098db851c72836d34fc0ac77bc03350d8a051728701acf3803\",\n        \"size\": 315832066\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15868_Weather11.tar.gz\": {\n        \"sha256\": \"063d5fcd64ee902e0cf8a866ce7423efacd3939f6cbc419a30bc36709499ba5f\",\n        \"size\": 281504812\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15881_Weather23.tar.gz\": {\n        \"sha256\": \"81ef6c397fd549c33bf7b066a0806bb9591b501ee6782004fbdc532e27aeb355\",\n        \"size\": 551889530\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15883_Weather0.tar.gz\": {\n        \"sha256\": \"d5172e624be6e3bede9ea5f06653cecf3950651a4d6dcbf4e058440c5430c6c4\",\n        \"size\": 388707547\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15896_Weather13.tar.gz\": {\n        \"sha256\": \"cd37ec74e1dc7c11d7c02eaf556c4ab0a2ac3925cde277de207303a670a8640e\",\n        \"size\": 118209937\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15923_Weather14.tar.gz\": {\n        \"sha256\": \"aa03d6939455d805b63d5fb74d4575d38106d845cb9d78881dd64395747a3020\",\n        \"size\": 121242218\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15944_Weather9.tar.gz\": {\n        \"sha256\": \"f3897a06d4a9183804d5b47d3f650e5e4f28c37b6d224ba318de599e4835feac\",\n        \"size\": 346740844\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15953_Weather18.tar.gz\": {\n        \"sha256\": \"3f11329fb07e47d8851cf9ba4df147dc6b0fddeecbc2e45d4042cc86e0e7d4ad\",\n        \"size\": 129011930\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15954_Weather19.tar.gz\": {\n        \"sha256\": \"09ace22f7402d45342ffe1cfecd442a15180a91d56dc162e8027f9f907cac839\",\n        \"size\": 317630535\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15961_Weather0.tar.gz\": {\n        \"sha256\": \"07485150e69cb69d027db6d7f5ed0484cf9c4164f549884545dd15004a80cd21\",\n        \"size\": 174413700\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15962_Weather1.tar.gz\": {\n        \"sha256\": \"7cf7a1464ca1fd110e4d96770be62bfb7710e9915ec0c65974584f398af9639d\",\n        \"size\": 134787266\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15972_Weather11.tar.gz\": {\n        \"sha256\": \"bfd29c1bae1824b5ae353d949163611ca84472caf0aa859132fd56752355419e\",\n        \"size\": 117584748\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15989_Weather2.tar.gz\": {\n        \"sha256\": \"f0a7a4263d9c2a34eb4b28c418169c3db66fbdb70cfaff55580a651417de9662\",\n        \"size\": 490938418\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15990_Weather3.tar.gz\": {\n        \"sha256\": \"5cf8a9d21c900571e3e5077a598814415c01825d8a6cd13db1b70a5ad7549deb\",\n        \"size\": 335688202\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15997_Weather10.tar.gz\": {\n        \"sha256\": \"d9dd898aac756610041a4d7597ff4932e3e86eefa3a8d6838989a11d44c13bff\",\n        \"size\": 451393995\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16006_Weather19.tar.gz\": {\n        \"sha256\": \"75507ef89c6fa82cf4f3ac6cea81ab1fc0b16ef20b44dd34d219e6337b1bf59b\",\n        \"size\": 208314272\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16022_Weather9.tar.gz\": {\n        \"sha256\": \"e9c36c133550cdd7c02543213ba00e88ceb20e32d0c8a5f11ad6ed327466bcd1\",\n        \"size\": 229484759\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16037_Weather23.tar.gz\": {\n        \"sha256\": \"fc2469738e77c72d74b39dbccf0b7c715f8c556df15937a5b01bf65d33d5b65c\",\n        \"size\": 435646776\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16061_Weather22.tar.gz\": {\n        \"sha256\": \"cd0450ede26e02fadf0ae9b001ee6ec79c4446616d96b38648efc7d170f11c22\",\n        \"size\": 458374366\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16066_Weather1.tar.gz\": {\n        \"sha256\": \"6f63329d7c3d1f3f1b5478e47a934f746001305549f84537a74251f5cc164f2c\",\n        \"size\": 175678545\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16071_Weather6.tar.gz\": {\n        \"sha256\": \"71d794417870fedeb2b9af1c4553c2c83f5b838e2da6bf08ecfd26c804da286b\",\n        \"size\": 550024249\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16076_Weather11.tar.gz\": {\n        \"sha256\": \"1db0047c85f3c1e7b1bdbff3255c1010c057e884b1d0992db0dbe939d00c285d\",\n        \"size\": 208413741\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16078_Weather13.tar.gz\": {\n        \"sha256\": \"d49ee7800ed85bc28e2d752b74dd8550dfcf6e7c313c6019de72a96ef4fff35b\",\n        \"size\": 478711565\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16085_Weather20.tar.gz\": {\n        \"sha256\": \"c6a92590e2492924aefa26197c28311dfa93ff767d9730ff9e0b1a2d51c1783e\",\n        \"size\": 145085968\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16112_Weather21.tar.gz\": {\n        \"sha256\": \"1dc8f04dec776d42517daa29cc437f3e1d7bc8ac9ff710c5bede908c9b689195\",\n        \"size\": 520888791\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16114_Weather23.tar.gz\": {\n        \"sha256\": \"c96a690ccd15310a0311a97d174b20ef0e4490f3775370cc278fdba6cc4f109e\",\n        \"size\": 329056108\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16116_Weather25.tar.gz\": {\n        \"sha256\": \"bbd678f1bce61210c136bcd8efadd4ce293ec7caa08fbf8dbd900c52ce7b2f2a\",\n        \"size\": 449071396\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16170_Weather1.tar.gz\": {\n        \"sha256\": \"1dad7b17d2caa61a2b6adc1c8d8b7232c89e62c5e1332b246ebd97a2e1b9401a\",\n        \"size\": 525648900\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16174_Weather5.tar.gz\": {\n        \"sha256\": \"197184cf17e3a81dbc9102a883c2319e0253ee64ea07caf9bfe24343848e7834\",\n        \"size\": 412835838\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16177_Weather8.tar.gz\": {\n        \"sha256\": \"2cb0b8fdc29019fb8b11602a97795c41441520d49744523ebf54d3c91e9592a7\",\n        \"size\": 154681085\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16184_Weather15.tar.gz\": {\n        \"sha256\": \"b4e40a385b6052d16f21c22584e43a8f7dcdb4151da374bbe048c1f695213765\",\n        \"size\": 394697707\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16187_Weather18.tar.gz\": {\n        \"sha256\": \"cdf59fa1e4da6618c3c6398c3ba23149e449d960a44231bfd0201fc6cbb08927\",\n        \"size\": 291393231\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16193_Weather23.tar.gz\": {\n        \"sha256\": \"edd7359313dfcc475da10c8830ed3cba82eb2357cad6b126a2cfb8a8af9471fd\",\n        \"size\": 411861309\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16217_Weather22.tar.gz\": {\n        \"sha256\": \"38f8f8aaa7d14971c6a9de6f3737185c153864356661909881e31c8c5f0874b5\",\n        \"size\": 441914486\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16236_Weather15.tar.gz\": {\n        \"sha256\": \"bbf11673e4bf1af0941b9a7c02c65b2d9b526a1443a774fb4be3f082107a3f1e\",\n        \"size\": 304266437\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16261_Weather14.tar.gz\": {\n        \"sha256\": \"acaeef1e41eaea524c47c87a08d4e4dc3539bbb89473b4ba9e79abd5c095ebf3\",\n        \"size\": 101588280\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16274_Weather1.tar.gz\": {\n        \"sha256\": \"1c5dec6a93727bc38fe16f070414c8655bc13c0f27756b2ed0c535513667273d\",\n        \"size\": 390033102\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16297_Weather23.tar.gz\": {\n        \"sha256\": \"2f11798d56ff52e72695a3cf73eb23f7f760dad3fa1450152acf5006b0c9ab2f\",\n        \"size\": 350402085\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16312_Weather13.tar.gz\": {\n        \"sha256\": \"d8d53ecaee75fad30d71e6dd53024093c550f3bfde3fe253c21d81391ea6df04\",\n        \"size\": 418703774\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16315_Weather8.tar.gz\": {\n        \"sha256\": \"ddabcd5d9c72e7eb2c125943571ddb32c36fda093103639a01c79f973e972407\",\n        \"size\": 525000887\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16355_Weather3.tar.gz\": {\n        \"sha256\": \"fee4e180ff5cac1e3c3e6264bd2d80042c31ab90d9957ceb7879212c41499c11\",\n        \"size\": 520548913\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16389_Weather12.tar.gz\": {\n        \"sha256\": \"7060c7e1b84854b8e57bb9fa3f5236b7d4c79df39fee17e7f95b204c2ac1173f\",\n        \"size\": 153004756\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16395_Weather18.tar.gz\": {\n        \"sha256\": \"fa1408b1d9158fd266b88b19f827d1f45538bb70b64f0b29d892fc96daa333c9\",\n        \"size\": 526746491\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16396_Weather19.tar.gz\": {\n        \"sha256\": \"8dfe4892393bf8548a78b55d05697c5c6d9cf4f5b05985d4445843989db97cd5\",\n        \"size\": 521008890\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16399_Weather22.tar.gz\": {\n        \"sha256\": \"b70ef600de2234258b6efe19449a301425760c93adde2ea5e51e44075893fb72\",\n        \"size\": 203034988\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16400_Weather23.tar.gz\": {\n        \"sha256\": \"26786e4c2adecee3bd0127b6050a362b00ddfc04ae7c0d60f0e34b220e0509ce\",\n        \"size\": 142915916\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16402_Weather25.tar.gz\": {\n        \"sha256\": \"8c66792d01befd179b015cf3ee7140de11cf8b7113bccaa84a3eb7d95d10b368\",\n        \"size\": 169859410\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16408_Weather5.tar.gz\": {\n        \"sha256\": \"6b1ade56d868d59624f3043f978dcdd185fd8d097f8e2b62d0c220f3211ea61c\",\n        \"size\": 350270938\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16425_Weather22.tar.gz\": {\n        \"sha256\": \"8c262f2ca94c164fea92a82b8ee670ed452ca6075484d7ec7863f99e6a3cbcc1\",\n        \"size\": 363603361\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16433_Weather3.tar.gz\": {\n        \"sha256\": \"417bc511ef0c5e36fdd97f4e402a5b4a9c8fc832b165c5858a24877a95b7670f\",\n        \"size\": 493473808\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16446_Weather9.tar.gz\": {\n        \"sha256\": \"652a7ca996d89a2fc4498da1b4890ca2925f52f638887c2fdd97a70eda6132b9\",\n        \"size\": 178863552\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16447_Weather18.tar.gz\": {\n        \"sha256\": \"38bbc8182a58d18ca11f35efd9ce9d5c10af5b4de019e37e0e825968cfdecef7\",\n        \"size\": 520590224\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16453_Weather23.tar.gz\": {\n        \"sha256\": \"ab681f049122ccccbb5e333f308677f0228ebfffe7759ca8bc5b5bc18be0026b\",\n        \"size\": 331284517\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16454_Weather25.tar.gz\": {\n        \"sha256\": \"5f131e11441b7e631c4e57b45b8b77078bd4a9d2dd5a8569f746dbfe139d8329\",\n        \"size\": 254912213\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2364_Weather18.tar.gz\": {\n        \"sha256\": \"62dcf455748a5af0f1d3c72fdf5d2537ec3284ed6013d3892b58bac565a61f4e\",\n        \"size\": 130161214\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2365_Weather19.tar.gz\": {\n        \"sha256\": \"0359c12c11dcd34c14b810bd910a0ac5531e9f9298359ccb3b64444dfd59877c\",\n        \"size\": 455233480\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2367_Weather21.tar.gz\": {\n        \"sha256\": \"955baf0efdb662242569b040554d8ae90af1274a860cdc1f50c5a24e1b6bea21\",\n        \"size\": 142334546\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2368_Weather22.tar.gz\": {\n        \"sha256\": \"c4f69dfa156b1d3a41bae537e17647d14a21f21e3c305985efdbba1673598eb5\",\n        \"size\": 299142306\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2369_Weather23.tar.gz\": {\n        \"sha256\": \"3fcf46da20b8fe4fcf5b42599282e8ecb5a4080a018c7750db7fcda5b671743a\",\n        \"size\": 490908085\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2370_Weather23.tar.gz\": {\n        \"sha256\": \"55355551f9b21fd3f896fd931f29797b8f4efb3e4b4cc9e068abe3fa389e8135\",\n        \"size\": 514431832\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2371_Weather25.tar.gz\": {\n        \"sha256\": \"11b3ef9d2b203c81dbc5288dc74dc36b49a5ddaac1ae35d7cd3cb9bc8cd44e8e\",\n        \"size\": 440578561\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2372_Weather0.tar.gz\": {\n        \"sha256\": \"684e936cb4b04d5b014de9e7931463bfbb631a32cb725cae63d8c49938ae914d\",\n        \"size\": 197592463\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2373_Weather1.tar.gz\": {\n        \"sha256\": \"9995da35a22afc5eb20026f8d67a54605bbed5dfd286e88f37f84d68449522d5\",\n        \"size\": 1562549069\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2374_Weather2.tar.gz\": {\n        \"sha256\": \"d2dd88b598541d1519961c07a9a449533680371dbef4d117d443395867e50ecf\",\n        \"size\": 555010093\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2375_Weather3.tar.gz\": {\n        \"sha256\": \"c7450529848ae0840b2d39c61751be613f9b89ee3fecccdffd67b4ecf9e129d6\",\n        \"size\": 552308845\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2377_Weather5.tar.gz\": {\n        \"sha256\": \"012cfce711385800c42529532ba0ce37a70e431c4f608638dd9f59724c88bc3d\",\n        \"size\": 866722397\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2378_Weather6.tar.gz\": {\n        \"sha256\": \"a64142c16d4759462b169d8a9934e3b065a317a6d4fc46900b6fda73c019de66\",\n        \"size\": 286539848\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2379_Weather7.tar.gz\": {\n        \"sha256\": \"b75b00140db8e9b3fe6741c724c81a2153f917f960ee40ddadf4e595b850d037\",\n        \"size\": 468486123\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2380_Weather8.tar.gz\": {\n        \"sha256\": \"36053310e31284ae68d3f27457e8ac233143d0810bf2df2b04eb7cc3f3f152cf\",\n        \"size\": 342412446\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2381_Weather9.tar.gz\": {\n        \"sha256\": \"67ab249b1b20eacb3b343d3f22cb8fca6ee305e3fae4a90b678d5484ae8ae70d\",\n        \"size\": 405684689\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route2382_Weather10.tar.gz\": {\n        \"sha256\": \"bc408dad70fb9b4ed6824d269afc0892a39326f8b31e2f7332d9ec5fdfc2522b\",\n        \"size\": 271243639\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3144_Weather18.tar.gz\": {\n        \"sha256\": \"8c9d1aa79eb635a4935d4a7d6f5f901e19f63223766adf1655623c604aa6dc5a\",\n        \"size\": 756752384\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3145_Weather19.tar.gz\": {\n        \"sha256\": \"2d18f09bd105fa0538e8dfbf627e72dbbd14bb27a5155e72e089f65360953f81\",\n        \"size\": 160158828\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3146_Weather20.tar.gz\": {\n        \"sha256\": \"92e6bbc2ff1b361853291c12a78464c6815ade1cf392b217c33044331779ee3e\",\n        \"size\": 136786783\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3147_Weather21.tar.gz\": {\n        \"sha256\": \"932c6e0786b5b8fbdfbd357ca601dc5fa94d2eea6300f1169cf5c3e8249683d2\",\n        \"size\": 135978613\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3149_Weather23.tar.gz\": {\n        \"sha256\": \"81e39819125400277136fa5490f773a686ccb2c22311491e8cd08afabb9f971e\",\n        \"size\": 458621039\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3150_Weather23.tar.gz\": {\n        \"sha256\": \"cfba261491605fb718740f9a98aa77737e3823c00b2c25f5f17b55b2eb5e0119\",\n        \"size\": 430042185\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3151_Weather25.tar.gz\": {\n        \"sha256\": \"5cf8e82be20f1adac314f36742a8e2821a7ba12e7a7cf653e38b2e301700c549\",\n        \"size\": 405892040\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3152_Weather0.tar.gz\": {\n        \"sha256\": \"e24247b6c732f5ac24b5aad516096f9935a164c7d95877c043680221a7688a1a\",\n        \"size\": 544186447\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3153_Weather1.tar.gz\": {\n        \"sha256\": \"472fe73de7c44e0264e8b352faa807e9d00f237bfeacdd11667182da18372f14\",\n        \"size\": 386749913\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3154_Weather2.tar.gz\": {\n        \"sha256\": \"3d7867689932e934b2891441c346ac2bf108ff25d941fe3bdd858e3233aed349\",\n        \"size\": 510162973\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3155_Weather3.tar.gz\": {\n        \"sha256\": \"5bbe5b8cb9d58f570a64bc7baed97c35814350e248f268042fe3e000afe916b0\",\n        \"size\": 417853207\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3156_Weather3.tar.gz\": {\n        \"sha256\": \"f8062509cd244ca83e6ce4082947f3e52c25c58ad755aec625bd1f57b65c2e0a\",\n        \"size\": 319374705\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3157_Weather5.tar.gz\": {\n        \"sha256\": \"f90ac1233d317eb750f73e1f4a7784e8f38ec4730e3d22fd04a5c3411dd3f8c0\",\n        \"size\": 164360019\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3158_Weather6.tar.gz\": {\n        \"sha256\": \"f6456ea9e3ab61f8a3326be72cf2513759231c067d8c4c5c4fa661cf5215685b\",\n        \"size\": 704668252\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3159_Weather7.tar.gz\": {\n        \"sha256\": \"66d27aafde07e075910e8db832fe45a7bc6445517f60aa5e0ae33691ade64441\",\n        \"size\": 268517004\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3160_Weather8.tar.gz\": {\n        \"sha256\": \"a0e4edb25e5c7d49a00c7c065555d9232fc012bb381125ba9f1e56fc554b6e9a\",\n        \"size\": 571492826\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3161_Weather9.tar.gz\": {\n        \"sha256\": \"d6f98b02a79e871c8bd73d3e4616288fef80d292f30ec5053b106cffc6baaacb\",\n        \"size\": 366298223\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route3163_Weather11.tar.gz\": {\n        \"sha256\": \"cd85f73de5a4b2e888d5aeccb0d302881dccb7bac6da9f4b9934dca4d73f2447\",\n        \"size\": 854220979\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3865_Weather12.tar.gz\": {\n        \"sha256\": \"2df1a353ee57e67bc8d3e9d2638006bdd4dd1baebaa0b99bf98fc71ea7623add\",\n        \"size\": 613306574\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3866_Weather13.tar.gz\": {\n        \"sha256\": \"70c66907e62a3b023bf16641aab71b6ef190b4d5093374d5bc648e7915d771a3\",\n        \"size\": 252041350\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3869_Weather8.tar.gz\": {\n        \"sha256\": \"6d952b3592656c183b0d0cb894578a1c9c1570198dd8aaa1cdbad951c89398a0\",\n        \"size\": 448440500\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3870_Weather9.tar.gz\": {\n        \"sha256\": \"817fe6f48eab99125a1e6e04f827ad8805e3e148f24f659dbfb936dda31e3f23\",\n        \"size\": 319826152\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3871_Weather18.tar.gz\": {\n        \"sha256\": \"c6dc52e4951faad4c650a78f8f8764ba37ff86c96916fd1e93a4ccea049c03f8\",\n        \"size\": 756756110\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3872_Weather19.tar.gz\": {\n        \"sha256\": \"dded1d797cd876f9ec6e0d3bc401a311b7a826d12b3d498c8a011653b26ef39d\",\n        \"size\": 367039256\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3873_Weather20.tar.gz\": {\n        \"sha256\": \"7112e97f6d0aee3ce46ebb88da5e195f57f9852e2d46182ef9d4c7fb7a81600d\",\n        \"size\": 187863536\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3874_Weather21.tar.gz\": {\n        \"sha256\": \"5c231ff1a535eb03d59b006bbac4b7dd6b70e534303f59f83d90d83d084cbafe\",\n        \"size\": 543349294\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3876_Weather23.tar.gz\": {\n        \"sha256\": \"14f9fb30c11bc0f7f48c806d14a44d05303059cc847fed4384182bcf22d6e87e\",\n        \"size\": 251345839\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3877_Weather23.tar.gz\": {\n        \"sha256\": \"e46a286b9f20276a5cbe161d980e5bf9ecc88ef77acc1fad2d169ff84422ff1f\",\n        \"size\": 535331857\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3878_Weather25.tar.gz\": {\n        \"sha256\": \"bb4f5cdd8f9f33c88935da8d183f9c1072ba583222f44e70d37d4cea02ee6a7a\",\n        \"size\": 116158371\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3879_Weather0.tar.gz\": {\n        \"sha256\": \"0e0c118a644b0f675454c13406165587e9ebe234399b603c169371276a4f4a19\",\n        \"size\": 1771450092\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3880_Weather1.tar.gz\": {\n        \"sha256\": \"bfd83ee62aa3d1bf2490f2177bf7d67cf036ed044d544fc23b241022d78bc8e8\",\n        \"size\": 688495832\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3881_Weather2.tar.gz\": {\n        \"sha256\": \"fa0e9b340de84f335584d706ae52a46f05264af21a269d99bbe8b9d8e13ae7fe\",\n        \"size\": 587501024\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town13_Route3882_Weather3.tar.gz\": {\n        \"sha256\": \"4211cf324dc535bd75f479f0d35334385453cb57bc9ac35b60aca81d18818f68\",\n        \"size\": 366572203\n    },\n    \"VehicleOpensDoorTwoWays_Town11_Route25928_Weather7.tar.gz\": {\n        \"sha256\": \"f22124d204b31a846d1f99b720e8d1863cc437d016ca1715a9c19487c92f7fdb\",\n        \"size\": 195280425\n    },\n    \"VehicleOpensDoorTwoWays_Town11_Route25942_Weather23.tar.gz\": {\n        \"sha256\": \"7d1f6107ad525aa19edfce9255a1357814d7acc00fad034e2b630994e62fcfc3\",\n        \"size\": 94639889\n    },\n    \"VehicleOpensDoorTwoWays_Town11_Route25949_Weather5.tar.gz\": {\n        \"sha256\": \"3024c80877b4eaeb171c086ab1754761f98a1d7a3a2aa07d210832ed9a6e0fa8\",\n        \"size\": 425246894\n    },\n    \"VehicleOpensDoorTwoWays_Town11_Route25956_Weather12.tar.gz\": {\n        \"sha256\": \"68f2285febb2ba2e1ad3c6a30d7fc391a6bbc6c4760ecab688e3eef2fa50769c\",\n        \"size\": 78033267\n    },\n    \"VehicleOpensDoorTwoWays_Town11_Route25970_Weather2.tar.gz\": {\n        \"sha256\": \"b5e7124598954bb5f00618981e033ba3980b4012a199e940e29a75dcae0593c8\",\n        \"size\": 101754396\n    },\n    \"VehicleOpensDoorTwoWays_Town11_Route25977_Weather10.tar.gz\": {\n        \"sha256\": \"38d2d739ab1b88fe1504c544b5054b2e98ea0458ca436b8dd61dd8d204be8e98\",\n        \"size\": 73489292\n    },\n    \"VehicleOpensDoorTwoWays_Town12_Route21581_Weather0.tar.gz\": {\n        \"sha256\": \"ba92890c690c41c51340773a080f75c0ff6f8ce8ec38863d4cf4896b2ab40ce6\",\n        \"size\": 331268905\n    },\n    \"VehicleOpensDoorTwoWays_Town12_Route21623_Weather8.tar.gz\": {\n        \"sha256\": \"cd0243a8af198c564d93a694a68f53741f3ef62beb7dba11e020e51f2d2f9979\",\n        \"size\": 152114542\n    },\n    \"VehicleOpensDoorTwoWays_Town12_Route21627_Weather20.tar.gz\": {\n        \"sha256\": \"e34c4622492b54c1b9a33ee9e8eabd015bcb7365afb35da7840877a56bd11180\",\n        \"size\": 314488870\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31862_Weather19.tar.gz\": {\n        \"sha256\": \"cd7a95bae58cf606b425e83f7a6adbdfbb537e396f25f2dc7a3c9f925bb9f708\",\n        \"size\": 653867783\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31880_Weather12.tar.gz\": {\n        \"sha256\": \"e1659bc1f8e044a7605d01dc2299f3054df81f6564e154f46821b08b35c6bf76\",\n        \"size\": 928869279\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31886_Weather20.tar.gz\": {\n        \"sha256\": \"1f6da6c1d95dd636a9afe6354943d48320ce3f0d3e067472269c7ef0c7468d61\",\n        \"size\": 321666207\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31901_Weather10.tar.gz\": {\n        \"sha256\": \"199f4a4dacbbd3ff37bdd2868c8524b91831e9365a49083f719e7ef04460d7e5\",\n        \"size\": 341820009\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31904_Weather13.tar.gz\": {\n        \"sha256\": \"6f0cd08125ddf8d06545a9731fa37145b1d96462c8d17d556eff35dad978e0a0\",\n        \"size\": 186144261\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31921_Weather7.tar.gz\": {\n        \"sha256\": \"0b2745a957c635abaf1a66f4ed0223b18f098ce74b926ded5ff3f8f2794a4651\",\n        \"size\": 1069906054\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31937_Weather26.tar.gz\": {\n        \"sha256\": \"94e73cb708172242e0788ea09369ef98f3aa7767af39236654ba9c8337868eca\",\n        \"size\": 341949971\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3464_Weather1.tar.gz\": {\n        \"sha256\": \"bd0a8045b325dcbf0a1f2c980632da71009928e588aa7b36fe8d6bc7a4d2e152\",\n        \"size\": 322924842\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3468_Weather5.tar.gz\": {\n        \"sha256\": \"723cbb3bdad332ccfcd0003f009e3c2dd09ab478ed08b92c58870e9a7f07ccc1\",\n        \"size\": 1089307103\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3471_Weather8.tar.gz\": {\n        \"sha256\": \"85f3b1c916d7e62b72d1e1bc64e6ebbdaca5f3a011f6d0d4c6cce55c5a7d7429\",\n        \"size\": 512272098\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3472_Weather9.tar.gz\": {\n        \"sha256\": \"f87471628385e7105763948507e759d68286acb6cc009ac80f94bb488d1694a4\",\n        \"size\": 915334513\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3476_Weather13.tar.gz\": {\n        \"sha256\": \"3e2738ea37b45be0b30eca3b716102e57540c6b0674213e95b1b94cca75316de\",\n        \"size\": 624880770\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3477_Weather14.tar.gz\": {\n        \"sha256\": \"4aec95ce1e34c8f88e22ffb578c1c46f158fe4223e5a2a1917594ce720270e7c\",\n        \"size\": 942219801\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3479_Weather8.tar.gz\": {\n        \"sha256\": \"4601dade1be6d1d0f4bcff031fe72adab440aede63256ad1e32a032bb9582d13\",\n        \"size\": 812034734\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3480_Weather9.tar.gz\": {\n        \"sha256\": \"fcba1c6df0f9cbbabc424979284444bf78ebd6325f763ceddd869530a6ecbf7f\",\n        \"size\": 241109120\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route3482_Weather19.tar.gz\": {\n        \"sha256\": \"31fb7c95198d069957d1da9092fa8acaf9237838b703561e4319d3c14ec00af6\",\n        \"size\": 766440978\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27267_Weather12.tar.gz\": {\n        \"sha256\": \"57612979c3e96979c37625ccc746098f2b2a94cfddd5e1340216ba0b525d5aaf\",\n        \"size\": 41355804\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27272_Weather19.tar.gz\": {\n        \"sha256\": \"34ac2c3eca4d61a106289e697f7931044f36595c118a61a684e506b448aa9642\",\n        \"size\": 41656578\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27277_Weather25.tar.gz\": {\n        \"sha256\": \"8cd3b06387ac96a4754863280901e08f6af438be456b4e378c6dd4503ae68bf4\",\n        \"size\": 67166863\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27282_Weather3.tar.gz\": {\n        \"sha256\": \"ce828680bac7a9b6a529f7cfff5e88054282ac6eb7ca32ae50ad271ba7332aab\",\n        \"size\": 99957947\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27287_Weather9.tar.gz\": {\n        \"sha256\": \"071f38b7e87f9b426e2025ca1416f0fc95bbea1531029551243c73a4f8bca5ab\",\n        \"size\": 40917649\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27292_Weather14.tar.gz\": {\n        \"sha256\": \"68a3fe90dea089dcf7273b4b8b4b4fee83d53416dc173abae87a74399ebe69e2\",\n        \"size\": 41894094\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27297_Weather21.tar.gz\": {\n        \"sha256\": \"1e81b56aa586ff9a44a472ff7045fc471c529544e08742c53ca9b535030c4d02\",\n        \"size\": 27360102\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27307_Weather6.tar.gz\": {\n        \"sha256\": \"d78e815afa78cd29f3ec034e39a1bc2eb5460a51784067cc7b90ff5b9ca628d9\",\n        \"size\": 108625902\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27312_Weather11.tar.gz\": {\n        \"sha256\": \"28538019d7880bb851052fd3fb69b549bd52e0ad0c7f1a55384fc0922c85936b\",\n        \"size\": 79358249\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27317_Weather18.tar.gz\": {\n        \"sha256\": \"acce0ce538ff814fbc9e4b1c92bbf9a7caa6b75098f7742cd7083c368133c01c\",\n        \"size\": 116580148\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27322_Weather23.tar.gz\": {\n        \"sha256\": \"544f8ebab0f00c67d81d7c3de359f9a020bdbec92d43ddce847c6414053ed6a7\",\n        \"size\": 72407563\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27327_Weather2.tar.gz\": {\n        \"sha256\": \"8b5b4d6ae8a7934c550953520811ee4b695da34e7633b5c59ec58a68889d584e\",\n        \"size\": 46082951\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27332_Weather8.tar.gz\": {\n        \"sha256\": \"4edd8fb7a5c8f6b18d8cee24e3865b65e5ee30dda24be677cecf3aff20f2a77a\",\n        \"size\": 94788871\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27337_Weather13.tar.gz\": {\n        \"sha256\": \"2e155179f8a9716af4d36f3a1a6bf672dfaff2b6cb568339086a8e8ca07a0f75\",\n        \"size\": 32789983\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27347_Weather26.tar.gz\": {\n        \"sha256\": \"d72d37140aa5e28159a30c80e332d4b69acd1f8ebc38372f31b6f72aee68ba50\",\n        \"size\": 64319811\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27352_Weather5.tar.gz\": {\n        \"sha256\": \"82355e4a3b07efc8eb0d3d79beaed10f57fb0cef696eedbd7ca3177e8b9ceb0b\",\n        \"size\": 46954472\n    },\n    \"VehicleTurningRoutePedestrian_Town11_Route27357_Weather10.tar.gz\": {\n        \"sha256\": \"c0f4e1313a14f8cce16499390f8cb535b3d0f1328a900e92bdaebd110f15126f\",\n        \"size\": 35547495\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10738_Weather3.tar.gz\": {\n        \"sha256\": \"fee7676e9b265739ca4e078c96de39db41a78bcefdd45692ac164d5427cd9732\",\n        \"size\": 308893997\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10739_Weather3.tar.gz\": {\n        \"sha256\": \"962fdb268a0f65ab5a2cb63a7ef3bf31fba098ff9a073f27f4926fb99c10a66f\",\n        \"size\": 81520592\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10742_Weather7.tar.gz\": {\n        \"sha256\": \"671a239985c0ddcb5ffc3329a00eccb3b5da243a8656f298d0a62e4dfceee81c\",\n        \"size\": 348140292\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10743_Weather8.tar.gz\": {\n        \"sha256\": \"ba3cb57320533db6acde345cc60f52f41e303e7c05176b63752b8a9c7cc75dcd\",\n        \"size\": 442885142\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10744_Weather9.tar.gz\": {\n        \"sha256\": \"fd4bf4c15b0aa25a5dd5887c495728bf4902b5705adc69b95d45ebeadf1bf9bc\",\n        \"size\": 204335044\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10745_Weather10.tar.gz\": {\n        \"sha256\": \"1ff2bad2d2e05e05f5c511f3f780cb04ac202734ca9153a56d04a2afdd08d285\",\n        \"size\": 692121980\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10748_Weather13.tar.gz\": {\n        \"sha256\": \"9518fb927b4535486854f1c51a96e180e255f54a275e0de0c500c3adb9c08c8b\",\n        \"size\": 509549224\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10750_Weather15.tar.gz\": {\n        \"sha256\": \"d182796cf7b8ce79d7168d65cdcc87745fe89eee9b56000f74705ed3eccd4c96\",\n        \"size\": 207768261\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10751_Weather8.tar.gz\": {\n        \"sha256\": \"04744f325800ee2247243646f4da5c0c6bdb37e64406b462e60912a839ac5baa\",\n        \"size\": 101255068\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10754_Weather19.tar.gz\": {\n        \"sha256\": \"6ffe7a4805f861f6ad04cb9a49df7f5ab13edb477bedc3b0d03972b6e3f9ca85\",\n        \"size\": 361954062\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10756_Weather21.tar.gz\": {\n        \"sha256\": \"17ac1d2b4989272313ce38c65b0361ac0f5bf547327cb50eae9e58a9e88fb353\",\n        \"size\": 336082172\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10758_Weather23.tar.gz\": {\n        \"sha256\": \"15049c257ab7f914786a96cc77ce5923624c0db83352cc8231676997d826f0a0\",\n        \"size\": 166565838\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10761_Weather0.tar.gz\": {\n        \"sha256\": \"ccff350285e3e0a0d3a0973cdec69064e961b82727adc3db631aab33f1222f02\",\n        \"size\": 315037401\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10762_Weather1.tar.gz\": {\n        \"sha256\": \"e8000ab1814290d50e049a235274598468baad6223fd10eefc44c7c56da60952\",\n        \"size\": 210457335\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10763_Weather2.tar.gz\": {\n        \"sha256\": \"d30357aed887b8520e1ac598e55ad01e2f0825d4bf20a18b7d308df073e5d7f8\",\n        \"size\": 86320465\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10765_Weather3.tar.gz\": {\n        \"sha256\": \"3432f4e0a1901e48a819acbe364f7bb33010cde059d4cf3c3700d812425b0c77\",\n        \"size\": 384277127\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10766_Weather5.tar.gz\": {\n        \"sha256\": \"431c92c63e6c4b31eea633d884f9d98cd5ca640946cd444f9b40a3e0d819b681\",\n        \"size\": 96577755\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10770_Weather9.tar.gz\": {\n        \"sha256\": \"f8c45c24f69a8a761b164e1e724083b3a0bc972fdbb708fd9ff86ed752d8f4a2\",\n        \"size\": 161137793\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10772_Weather11.tar.gz\": {\n        \"sha256\": \"7d5db06844d5b98901bd94fba01561e0a2d5274cd6741a43b24030d309124a84\",\n        \"size\": 72761783\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10775_Weather14.tar.gz\": {\n        \"sha256\": \"587d029f8952b06c1018c19a2244c715ef9feff99178de6334efcad8f7771fe7\",\n        \"size\": 118728809\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10777_Weather8.tar.gz\": {\n        \"sha256\": \"0e22e64f4fcf55d482bfd3a055832ca0bf10621ff2800458b06d82a21f0cc786\",\n        \"size\": 285231071\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10778_Weather9.tar.gz\": {\n        \"sha256\": \"395bd4ffc01dc1df6f835b7fb0ced7791b9ab809256ddca625c3a8873af4be8f\",\n        \"size\": 314843485\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10779_Weather18.tar.gz\": {\n        \"sha256\": \"a05c6fd5c03d87da207bac119617454dc5d18a58ac57ceddf7feb0a3ad8e664f\",\n        \"size\": 392458371\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10780_Weather19.tar.gz\": {\n        \"sha256\": \"f06c5345d2661714e7035e371c621121d0912a8ec6e995259f7f4c8eb2b66312\",\n        \"size\": 116940469\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10781_Weather20.tar.gz\": {\n        \"sha256\": \"df0c2c104e1de45e6d0cbf831d6bb3fbb9e665635468a4fac1fec77a455c8aae\",\n        \"size\": 433466298\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10784_Weather23.tar.gz\": {\n        \"sha256\": \"4542a4117cfe732983f3a3f4582e282e65f877cd711d73a40f06148985144e16\",\n        \"size\": 182983205\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10785_Weather23.tar.gz\": {\n        \"sha256\": \"a1bbf2627248ac203a610a29236120fa28366068b0484f58d9e6d15bdb62b406\",\n        \"size\": 120917278\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10786_Weather25.tar.gz\": {\n        \"sha256\": \"3e8cda66c722c8463de987876f6ff8118af0a7e8dd1faf8b73a460e948bf920f\",\n        \"size\": 239406720\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10788_Weather1.tar.gz\": {\n        \"sha256\": \"67c7b111ead3ecf423e5952d8f992da3c1fab8df403501b4f7cc12aac25239f7\",\n        \"size\": 353192516\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10791_Weather3.tar.gz\": {\n        \"sha256\": \"09dd97d336e793a833d9d4608c5500b99c787ac4fda9f3db41cbb17cfff484da\",\n        \"size\": 286997467\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10792_Weather5.tar.gz\": {\n        \"sha256\": \"209906f2f57e2e9c7ba6caea5d6561730aa1493ad9afcdfe13d54c0e6a5a4104\",\n        \"size\": 333868958\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10793_Weather6.tar.gz\": {\n        \"sha256\": \"45384612a694f97b8dffbea269bd0173cb894ee4062826a7f7ad7495891c9651\",\n        \"size\": 119356792\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10795_Weather8.tar.gz\": {\n        \"sha256\": \"b8a6096bea273ff2b0839f5a377a287b3d2eee36a26f379992559797bba5dc06\",\n        \"size\": 311463716\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10796_Weather9.tar.gz\": {\n        \"sha256\": \"cf224475375ecf7f7a8489edc9d8a6bead449cb4a7776b28fcc5866f8a09762f\",\n        \"size\": 83316187\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10798_Weather11.tar.gz\": {\n        \"sha256\": \"a584af793c6527add624a032e66367c489b77ff1dbc79a2ee1fb5f942e43557c\",\n        \"size\": 178543555\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10800_Weather13.tar.gz\": {\n        \"sha256\": \"e6575fc0727a9e354b559b71b38303598847bb06d3f15a90840de41ca7062e02\",\n        \"size\": 66895154\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10802_Weather15.tar.gz\": {\n        \"sha256\": \"811689c9c41155d0bf959d8376e5c56ee5b0d79c757dfcd0e7ea4ff3e67037b2\",\n        \"size\": 197966281\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10803_Weather8.tar.gz\": {\n        \"sha256\": \"e52473e745b17a0f37ebd7944e72c59cf6eb6df4ad5c39154dc8250f4992d137\",\n        \"size\": 323473424\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10806_Weather19.tar.gz\": {\n        \"sha256\": \"147d6e2a7f6ba4d585d6615c23577d1cca5c5f3f59f1b67fba1cb890d161be3d\",\n        \"size\": 132152986\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10809_Weather22.tar.gz\": {\n        \"sha256\": \"ed9faae300844198c49066f15dfd72ab5063e065b8e94d125baa74b8afa7690b\",\n        \"size\": 213580734\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10811_Weather23.tar.gz\": {\n        \"sha256\": \"64a80a827c0de28be7259be6f09e1a09fed1592fb78dc794288928be123c28ea\",\n        \"size\": 222385902\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10812_Weather25.tar.gz\": {\n        \"sha256\": \"ac6e8f4038702770b510e7771ccc98b964ba1915ba2b4feaf0e8d4916bdae147\",\n        \"size\": 643802845\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10813_Weather0.tar.gz\": {\n        \"sha256\": \"48c4583af6b6a6a6413c82e7d2e2794c82316650b68ba5ba19b0287a7c9a5c6f\",\n        \"size\": 97367536\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10814_Weather1.tar.gz\": {\n        \"sha256\": \"eb41a901cc87c2e8b6dee12f6f81d8683c30f7d89c17809643bf6a8f17816c8c\",\n        \"size\": 281198493\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10815_Weather2.tar.gz\": {\n        \"sha256\": \"47678e9eb52a9658d58c39b91f36a5494e77c5a711c4744da3e2959c42f12b3f\",\n        \"size\": 330549158\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10817_Weather3.tar.gz\": {\n        \"sha256\": \"898d873123b8769cf798fe29d09d91b3da101395b222b64c70a4998a1d90f834\",\n        \"size\": 194742676\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10819_Weather6.tar.gz\": {\n        \"sha256\": \"fd795232f581f414919f82c8c15a9991d2e6f9ba8dcd33d734e2661527ffceb1\",\n        \"size\": 285475705\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10820_Weather7.tar.gz\": {\n        \"sha256\": \"c7dea0e6b7875248eed0824f4a4dcd5ced4eace8d83ab88dc5dc5974766ea0fb\",\n        \"size\": 192251347\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10822_Weather9.tar.gz\": {\n        \"sha256\": \"cb8cf0d0e82623b5cc2169b6fd5018cb514d92a7885c5de0d958ce5fca5de89a\",\n        \"size\": 220040482\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10825_Weather12.tar.gz\": {\n        \"sha256\": \"d050d7cc08af869e7bfda71aaacb5c3d26d4cfb0db67bde40b6810d517a5aeea\",\n        \"size\": 408792995\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10826_Weather13.tar.gz\": {\n        \"sha256\": \"a6bdcd5cb878f66ecd206963333e46c23e2159984d0791a7b27b39556f4d6f89\",\n        \"size\": 198757220\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10828_Weather15.tar.gz\": {\n        \"sha256\": \"b89fc06025b81ec2bb77010b5d4491e041970be86a5cc94288c9551cc1285c92\",\n        \"size\": 261913078\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10833_Weather20.tar.gz\": {\n        \"sha256\": \"d42692997e619eadd8916f51971cbdfd96ecea268bd9237eeab8f6f996a21309\",\n        \"size\": 189349826\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10834_Weather21.tar.gz\": {\n        \"sha256\": \"1ee5d88b8577f11d96d8f5e63745b6f0865eeb136e7f2322e46ad702e3113b94\",\n        \"size\": 204714538\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10839_Weather0.tar.gz\": {\n        \"sha256\": \"496500a834c1deab27a38a1d60c0c23151ab7ad84edf214beab4715ada660e6a\",\n        \"size\": 127047575\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10840_Weather1.tar.gz\": {\n        \"sha256\": \"8743fd4ad8ede4a5392f278b9ec62ee0e421784bc4ae6b1afb2eae9a60ada8ed\",\n        \"size\": 439905937\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10842_Weather3.tar.gz\": {\n        \"sha256\": \"b3286f86e4c0a24b618de11188a28ce115d59d2195b37402f42239a61f7d18fd\",\n        \"size\": 565428150\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10843_Weather3.tar.gz\": {\n        \"sha256\": \"524d997bb317988346fce6dc45d19a73a7d5a40b77eef9d295729608e2c46a98\",\n        \"size\": 253808908\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10844_Weather5.tar.gz\": {\n        \"sha256\": \"8dbcc1c614c58a899661bd41a90cde2d82e01c0a800d9ab379c7d38926474524\",\n        \"size\": 238532711\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10847_Weather8.tar.gz\": {\n        \"sha256\": \"6a50f6adea8462ea958c304661d07c0ef2e6fe77acbbec48837516500a71bbef\",\n        \"size\": 398444077\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10855_Weather8.tar.gz\": {\n        \"sha256\": \"e1eb3da7de83f6a72053153153caa4d109a17559a6b7d45245ad374f6ed3ac43\",\n        \"size\": 96394960\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10856_Weather9.tar.gz\": {\n        \"sha256\": \"403f98fa7f9a77cd3698f4143c4c9be6163e00b6b5f28071fd47de5326a79595\",\n        \"size\": 327157399\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10857_Weather18.tar.gz\": {\n        \"sha256\": \"f0b49453fa0e2624ca1b6656804e25e701def3aae64e0293769bc630fa8835ff\",\n        \"size\": 139512728\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10858_Weather19.tar.gz\": {\n        \"sha256\": \"931ff31bbf7ca3096182169369b3139a2260fe0f302bea32649f081c3cce8d66\",\n        \"size\": 236034889\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10859_Weather20.tar.gz\": {\n        \"sha256\": \"74694bc71416b123122b6c4bdaee1c8e1ad68568cfa205a4e27ce4c364922324\",\n        \"size\": 492852402\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10860_Weather21.tar.gz\": {\n        \"sha256\": \"07c8123a88253698b869d18cfcee174d488aa725c9c7fd4293ac3ccdf6b54b8a\",\n        \"size\": 243370684\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10861_Weather22.tar.gz\": {\n        \"sha256\": \"6099a84843a3872c5cccf3be9dd3e75844b05decc9ffb10c0efa17f0ff0c4640\",\n        \"size\": 525622768\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10863_Weather23.tar.gz\": {\n        \"sha256\": \"b9147468c5fd40801278247d54dd5d9611d7e39dadb03389fbfbb1697bb6e686\",\n        \"size\": 90501269\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10864_Weather25.tar.gz\": {\n        \"sha256\": \"67b7e1c77e6b8bbedac5731e95ff1e8d428d34d4aa2712758adcbdff12980efe\",\n        \"size\": 182639562\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10866_Weather1.tar.gz\": {\n        \"sha256\": \"78d0a6fa1bab6aece4ad5a7bb8e21547fec35f6f1235f38c21c02d49fbd24378\",\n        \"size\": 415603963\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10873_Weather8.tar.gz\": {\n        \"sha256\": \"406a673d8184aafa16cbbd73fef5c959903e99e5b7c1ad047a5273647132810c\",\n        \"size\": 443264263\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10874_Weather9.tar.gz\": {\n        \"sha256\": \"35a7f2cd86565b5cbde6fd874d73c65c26eba4951c0d7cc12599b72e97f9686e\",\n        \"size\": 237301387\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10876_Weather11.tar.gz\": {\n        \"sha256\": \"4b6261c83c683adcca02554c77aafbb7dbe21c99135f6c4319dffb283a7f60b0\",\n        \"size\": 323398929\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10877_Weather12.tar.gz\": {\n        \"sha256\": \"72fbe583008b5d849a7f81cacb962ca100bf0016c653dc4c6de8ae5c2bfa7de7\",\n        \"size\": 201096441\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10878_Weather13.tar.gz\": {\n        \"sha256\": \"12797db7cb99d2efafb401826e4e8f6b9e20ccc173792b915ea8b0e0f5091cb2\",\n        \"size\": 97122084\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10880_Weather15.tar.gz\": {\n        \"sha256\": \"2d99ca63ea4b7147ed3203aa58aaf6657774e6793adb9575eed845fea381cd92\",\n        \"size\": 320393320\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10881_Weather8.tar.gz\": {\n        \"sha256\": \"4dfc189bea17dc3db97782d0b34c553097167eed1eb4ccab4a438bf5a3a2d261\",\n        \"size\": 233113921\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10882_Weather9.tar.gz\": {\n        \"sha256\": \"b21ab5e21cfa55d449c5a08da4e35434feb887029220e98a39a2afa90f274511\",\n        \"size\": 85756213\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10885_Weather20.tar.gz\": {\n        \"sha256\": \"fb0de413b18e6aacea07b9ee78427845ef5620d18c5015183c7ad6846d787322\",\n        \"size\": 224569693\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10886_Weather21.tar.gz\": {\n        \"sha256\": \"7c4bfa52699d705a00a2822134b215d25b9b8db6858fcb3fd5d51264d9f5e0d2\",\n        \"size\": 290578456\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10888_Weather23.tar.gz\": {\n        \"sha256\": \"4f816eff4a489c1b633bcb3066de3577e45aac0770cce7eab56ed2f8a59cd47e\",\n        \"size\": 225389218\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10889_Weather23.tar.gz\": {\n        \"sha256\": \"b7d34cbc4af27f3b90c0bcb679c18de237c5cb269ade85e9399d8a814216e2c2\",\n        \"size\": 234930643\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10890_Weather25.tar.gz\": {\n        \"sha256\": \"8859949ee08f09744027b6785d588aea1f9eb559dd53f0178569e9ebdf686926\",\n        \"size\": 108617753\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10892_Weather1.tar.gz\": {\n        \"sha256\": \"7ed96b75fd53c8f28f97f0c9373924c8ce0f30dfdff0ed9a63c8d50f6d120bef\",\n        \"size\": 571084493\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10893_Weather2.tar.gz\": {\n        \"sha256\": \"8a11a78d8db989e1e9aa65162373022a728a64987318877b7c11ae388d8e1a73\",\n        \"size\": 395974697\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10896_Weather5.tar.gz\": {\n        \"sha256\": \"041ef1e8f8fbed858583b333f98f14694229473dde87b111909694a5d4e5bbb2\",\n        \"size\": 259120059\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10898_Weather7.tar.gz\": {\n        \"sha256\": \"bec52341478e3ae427879427d9a9209589203a591784f69650daceb2be78322f\",\n        \"size\": 115212375\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10900_Weather9.tar.gz\": {\n        \"sha256\": \"cf9cd2236358d26e04a0321d56c76490c69cc884141eec2f1009b3206554b470\",\n        \"size\": 171828306\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10906_Weather15.tar.gz\": {\n        \"sha256\": \"3a30d630f1ef31515cbd5eee83e5b7c24a72f92ba94bcfd69302e08d85f44af1\",\n        \"size\": 383141003\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10908_Weather9.tar.gz\": {\n        \"sha256\": \"04a57e0e95d575d13027b734967dd212468da776ea1222d9641aaddc41e28219\",\n        \"size\": 316674783\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10914_Weather23.tar.gz\": {\n        \"sha256\": \"146fee3236538dd100a7672304fbdf22aa761a43cf9ef92f3310da7a9f196009\",\n        \"size\": 427951630\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10915_Weather23.tar.gz\": {\n        \"sha256\": \"c789bc35dad59eda5b1c9415d001cf6bab495943820762d49dc267d19c99c8c6\",\n        \"size\": 194551716\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10917_Weather0.tar.gz\": {\n        \"sha256\": \"c2386ef9bd6143103ceb1addb8f42b2906f6c3c6210397a24657b1c7c3fb261c\",\n        \"size\": 292461551\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10919_Weather2.tar.gz\": {\n        \"sha256\": \"cb4ae461858605e67c328e11baf8c20cbd7d11a7a609ade3c47b62fef1e87426\",\n        \"size\": 300388600\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10921_Weather3.tar.gz\": {\n        \"sha256\": \"7105fba301fb11f77b7170e94429c5332b75c8b8531045923a9598d0a30bbf4b\",\n        \"size\": 528397987\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10925_Weather8.tar.gz\": {\n        \"sha256\": \"514dd1b851bcdbe29e2e2e5f3f2e1c374a933739dc9c40a723be86bb7c67dd96\",\n        \"size\": 124643770\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10927_Weather10.tar.gz\": {\n        \"sha256\": \"3b20ac17d21beaa8164fdf2ce239fb9d034c42a868adbfbdff484c063b7b4974\",\n        \"size\": 205788036\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10928_Weather11.tar.gz\": {\n        \"sha256\": \"edd7e064141eb9c8fed34c4f26a5cfca519d5fdf77b6946af64a072120220e1d\",\n        \"size\": 228435249\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10930_Weather13.tar.gz\": {\n        \"sha256\": \"49f1dc7c9b07071bfc3b9abc4fcad1aec0dba7e3d2aa82c1daf18f12e7029c03\",\n        \"size\": 174511812\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10933_Weather8.tar.gz\": {\n        \"sha256\": \"4758b40f6db8f5b03588df580c5e07f1be9a9d18c3a66d0c8df5785ad7b37fcf\",\n        \"size\": 525766655\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10936_Weather19.tar.gz\": {\n        \"sha256\": \"be6c64d57d93e0885b48aee29874a2ec98b43b8990296eab88b610947b48e9fd\",\n        \"size\": 366361786\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10938_Weather21.tar.gz\": {\n        \"sha256\": \"6621719b7714de6ee41c4473624e69d97c911bdf09cf2303124c4267248480c5\",\n        \"size\": 173481891\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10941_Weather23.tar.gz\": {\n        \"sha256\": \"2cc1183ac9349ef7a5379b12bcabb8847c45fdbff6054f3b9a5111fcd4f73ded\",\n        \"size\": 220660285\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10942_Weather25.tar.gz\": {\n        \"sha256\": \"abbbf3d8e8d6fe1c621f44891e339249afbac1294b6777c8f0720c26d5f477d9\",\n        \"size\": 195270664\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10943_Weather0.tar.gz\": {\n        \"sha256\": \"4fc7a19406bfa1192f3fa6d9a9070fda7dc1582da29039487a62222040cc3ef6\",\n        \"size\": 297136039\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10945_Weather2.tar.gz\": {\n        \"sha256\": \"1d26e3878677aea310d7398eb2103cff0403ba6d7c0dbea6fa20e658336dfff2\",\n        \"size\": 151084815\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10947_Weather3.tar.gz\": {\n        \"sha256\": \"9ece07b9b8491fcc84196a00ca93ae2127279b2b770a2fde6cb01503fcb8c56f\",\n        \"size\": 284977225\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10948_Weather5.tar.gz\": {\n        \"sha256\": \"2ca04818945392c13c323b13b793ed19e3530589558140973bc640fd838eba7f\",\n        \"size\": 293463827\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10950_Weather7.tar.gz\": {\n        \"sha256\": \"c676f076d67468efdd7b78c94d6aab65ee332d47f14964314b691d73caacfd44\",\n        \"size\": 384715552\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10958_Weather15.tar.gz\": {\n        \"sha256\": \"cb7a49097fed2293b42157e641141210940eb9dbbc546e7a9126b236acac41e0\",\n        \"size\": 278843501\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10961_Weather18.tar.gz\": {\n        \"sha256\": \"41b40a50f8f5693e7314f5770bfc6ec981061abe6cfef800836731b22b340a98\",\n        \"size\": 130538943\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10962_Weather19.tar.gz\": {\n        \"sha256\": \"f6119b5b265ac50ee6a92810d4a85b17bb15afcc40209f2a53520044af4e1117\",\n        \"size\": 381957161\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10963_Weather20.tar.gz\": {\n        \"sha256\": \"542a013b3e3bf033fb6ee4055ee78bc3c8bc954c619f3af2abeb71ccbf9b34ef\",\n        \"size\": 167181933\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10965_Weather22.tar.gz\": {\n        \"sha256\": \"df6404d05f264f1ba7de41f62bae8be96e9c5e2eeb586873e84093bee78007ed\",\n        \"size\": 227253446\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10966_Weather23.tar.gz\": {\n        \"sha256\": \"e30e63742fa4190a0151ef3d3cee4e86da1812f339f4f13cf31c2961459a9563\",\n        \"size\": 196028452\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10973_Weather3.tar.gz\": {\n        \"sha256\": \"af75738d687caa345fe88fefa462d010ad7c171c6b270b1eadcc030ef5df65d9\",\n        \"size\": 355203484\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10976_Weather7.tar.gz\": {\n        \"sha256\": \"8741f254f5304ddddf744b0ca2e79ccd2961cc56ff355e114de1c987952e2696\",\n        \"size\": 507220942\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10979_Weather10.tar.gz\": {\n        \"sha256\": \"6b278a93c569c00abeaf162ca4371ca287fbf54dea993afc8ad544228dc605b4\",\n        \"size\": 209813091\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10980_Weather11.tar.gz\": {\n        \"sha256\": \"84c72d65d8f2996ba1e547142e465865baab871bd4fcfc86c2a92c277f247408\",\n        \"size\": 136569519\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10982_Weather13.tar.gz\": {\n        \"sha256\": \"c4e03250830f625774874b09b181e3c8e9abb2369c6292f21d164b6c8ba50be9\",\n        \"size\": 290366673\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10986_Weather9.tar.gz\": {\n        \"sha256\": \"4201da6d73943acc80a77fb919956559d9dcb56c4949dd3208699c63db56c6ed\",\n        \"size\": 231034283\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10988_Weather19.tar.gz\": {\n        \"sha256\": \"6ebada0cfdd699820deb106139e4abf4c0c5faeb7963f161815ec408cdcb1c0c\",\n        \"size\": 278687456\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10989_Weather20.tar.gz\": {\n        \"sha256\": \"a2bdee7bc1e43ec7eeacd9ff8945d8f9d7cc6c25d4a7c14d60e7916c99e38309\",\n        \"size\": 327620366\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10991_Weather22.tar.gz\": {\n        \"sha256\": \"61a37aab218690604b9b8d8fc6484b7001fb63d749802b94e186be819934930a\",\n        \"size\": 423313513\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10994_Weather25.tar.gz\": {\n        \"sha256\": \"770e5db53ba9a5faf8a06c7a8d432fe136ccf19d202c442c94f810c5f68c7638\",\n        \"size\": 265900907\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10995_Weather0.tar.gz\": {\n        \"sha256\": \"9b9fb47972dffd991cc1ff93de9b8bec10498b805b03c8cc6eb0e119965c3cba\",\n        \"size\": 111248715\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10996_Weather1.tar.gz\": {\n        \"sha256\": \"630c2d06e68507915bb66e4809d920cc72fddcd4a6e301c7de1fc7e6b701f291\",\n        \"size\": 256030563\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route10998_Weather3.tar.gz\": {\n        \"sha256\": \"874c5f40f4e4f0f34e3af43e848a0654f52457a29334e7662ebb745f72988821\",\n        \"size\": 91927657\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11000_Weather5.tar.gz\": {\n        \"sha256\": \"7498ef3764c3b93d160d7071929978fc768b46a952faf02249aeb9306419c5f2\",\n        \"size\": 199755031\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11001_Weather6.tar.gz\": {\n        \"sha256\": \"11f438455fa4b272516d28a9234d79364e88d8063d5fe8aabb64e0d95b1b0cd4\",\n        \"size\": 361169794\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11004_Weather9.tar.gz\": {\n        \"sha256\": \"44a56c7213d674f7300c2f2d26c3771c0a0ce7b47197346451ab02ce43ae5e5d\",\n        \"size\": 174912911\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11005_Weather10.tar.gz\": {\n        \"sha256\": \"eb63625b3699c244f965d79358910941a0d111fbc234b80f77d943673c59f875\",\n        \"size\": 113339517\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11009_Weather14.tar.gz\": {\n        \"sha256\": \"e113c91fa3a788262f594e36372b1ca0684c0c23619795271a71d8b4a0d79006\",\n        \"size\": 316115973\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11010_Weather15.tar.gz\": {\n        \"sha256\": \"1681ffed21bee979230576f6e3b6ea739a13f94d8e83cf99cd258088733ec373\",\n        \"size\": 251518880\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11011_Weather8.tar.gz\": {\n        \"sha256\": \"e3cb8d0696da8d47d21234d2b058885a09667755d5ae2dc2a1ebc4521489b4c5\",\n        \"size\": 380875943\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11013_Weather18.tar.gz\": {\n        \"sha256\": \"8d5402cee1117dc02e0aa839d59953c5604bf20ca9fdd68c121972644a689e1e\",\n        \"size\": 210365461\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11014_Weather19.tar.gz\": {\n        \"sha256\": \"39337240b52601d37b0b00b3b11dd503a3b9bebf8968bb378e130b55b4b35b0e\",\n        \"size\": 95476428\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11015_Weather20.tar.gz\": {\n        \"sha256\": \"f30597177659f93d194758aaa7cca1cd54bd9eeeb4d7be1b22400186f481d663\",\n        \"size\": 479022171\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11017_Weather22.tar.gz\": {\n        \"sha256\": \"44b11f2e43c8a8b7f3b35468665e043fb82f41296d42aee71fb683e358bd7f43\",\n        \"size\": 279240014\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11018_Weather23.tar.gz\": {\n        \"sha256\": \"f03d5558626ed59eba5f185f4e8c2d291f8eea7024af3150414008ecb3e86afc\",\n        \"size\": 259156616\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11021_Weather0.tar.gz\": {\n        \"sha256\": \"0dae16f4f1dcf97d8f880e8850974eac27ef29b26aab360882030a4bd9284213\",\n        \"size\": 125316964\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11022_Weather1.tar.gz\": {\n        \"sha256\": \"f67f364ed9ea5053b87e2eee278c8b524c9f09760a050516726855e8225d9aa6\",\n        \"size\": 359826726\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11024_Weather3.tar.gz\": {\n        \"sha256\": \"60b3c51d46d76053c1043e687fb187870ca7a66c903774b386fa9a669e9cff5b\",\n        \"size\": 113137364\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11025_Weather3.tar.gz\": {\n        \"sha256\": \"797e4e92c855464aa5f9cfd4f883ff600d1082bf9320dce7332aef6361ae2ee4\",\n        \"size\": 211281025\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11030_Weather9.tar.gz\": {\n        \"sha256\": \"ad735a24ed3f66c520975e43fdd198d01746a09e80f5230712737a9c4ada6ff4\",\n        \"size\": 265880258\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11031_Weather10.tar.gz\": {\n        \"sha256\": \"fc938c34d844e570fff5aac97c5f66364399f91698b45e896f1d3ccf90b06ec0\",\n        \"size\": 190119750\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11033_Weather12.tar.gz\": {\n        \"sha256\": \"f5d6de3cfe90351657dea4457e2f6f6ea1410ca0b4d743c578a4f12877bbacd1\",\n        \"size\": 222814672\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11035_Weather14.tar.gz\": {\n        \"sha256\": \"04129914f914c5ade3bad2a12fa5527e344b0e13fda0f5ad5c4e1e1f1d551e11\",\n        \"size\": 104990043\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11036_Weather15.tar.gz\": {\n        \"sha256\": \"f09201b61638fb65226aa9b583bd0404bd80a1137d9ed7616f48e9ceb5b6e204\",\n        \"size\": 474980103\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11037_Weather8.tar.gz\": {\n        \"sha256\": \"62844cbcafedc90aceea5b0310d0579f001b69d3df3c97b9cf7196d904d548a6\",\n        \"size\": 192367196\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11038_Weather9.tar.gz\": {\n        \"sha256\": \"d7f83de706fcac38cc6be16c2d6813cf0c752980c75c6b378002cf87871d6924\",\n        \"size\": 370128265\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11039_Weather18.tar.gz\": {\n        \"sha256\": \"6d064ae20824acd39a97b503acfa3f920f0d2bc37da2dfb373438b93b52b656b\",\n        \"size\": 137137795\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11040_Weather19.tar.gz\": {\n        \"sha256\": \"4bbba28c2e123910e5c512ddd9f864d2970d9f846f24192a89807c2f760fef1b\",\n        \"size\": 129859488\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11041_Weather20.tar.gz\": {\n        \"sha256\": \"99a236ee4b3d705de457b7c5ae05e53747d2996eff6d50dc82920fc1180bf7e0\",\n        \"size\": 133098417\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11043_Weather22.tar.gz\": {\n        \"sha256\": \"25993c783fc77a9078d5050d11277937619af8fd103a11010724a6eb7f190d30\",\n        \"size\": 145808954\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11044_Weather23.tar.gz\": {\n        \"sha256\": \"e7b94aefd8b4913bb02a3ce948c7cca975b809d3e354e3be16c67a88ea46ab88\",\n        \"size\": 200991806\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11045_Weather23.tar.gz\": {\n        \"sha256\": \"acaccef2fe535a0f710282149ba7aff7fbe65336b188a9a0ccfbd4c620639f81\",\n        \"size\": 99990914\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11046_Weather25.tar.gz\": {\n        \"sha256\": \"b6c09aec32e8fdbe7c8cfc7197cb46b84577107968ee1f1fac49961179d9d0a1\",\n        \"size\": 123677864\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11047_Weather0.tar.gz\": {\n        \"sha256\": \"34c87dd01bc15addc0a0df7a1999635fe9ccd1e3ac78bbcc95082f32e62528ef\",\n        \"size\": 399931598\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11048_Weather1.tar.gz\": {\n        \"sha256\": \"dae8a4cb7860198dc609e6a52bf919d2c6afa8362f64fc7cd35ec4ba643168c1\",\n        \"size\": 267289976\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11049_Weather2.tar.gz\": {\n        \"sha256\": \"5115f250e2e0df920e9480e154dcfad49aec6ed9bcd521f10aa67eb73c7e7f49\",\n        \"size\": 297049920\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11052_Weather5.tar.gz\": {\n        \"sha256\": \"5fa0a231d2a3eff5140a8d535767aba45546dd6deb05d5b3af3047ffea79f557\",\n        \"size\": 87015655\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11054_Weather7.tar.gz\": {\n        \"sha256\": \"eec5f0a0b19ffb861af1ee2c80c56ef4d3cf2ad5adcd50d66430aebd1bd2bd92\",\n        \"size\": 669925642\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11056_Weather9.tar.gz\": {\n        \"sha256\": \"894e13305c9112fc7c4082bf06fddd9408e7eb991cc2087a126cff38886a2aa6\",\n        \"size\": 351733336\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11059_Weather12.tar.gz\": {\n        \"sha256\": \"5f8138d396e9b49e69d99c35b8cb29af8faad18e3e566fc7047992a148091fb2\",\n        \"size\": 210030278\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11062_Weather15.tar.gz\": {\n        \"sha256\": \"8f464a3921cb2669825c1761c7fee1279414e76cba81929987ea4c22169b5289\",\n        \"size\": 171806705\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11065_Weather18.tar.gz\": {\n        \"sha256\": \"d606c7416dd4d1c14bd6068cdba504adb5e08597b41b0327c731875d7c63703a\",\n        \"size\": 93946178\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11066_Weather19.tar.gz\": {\n        \"sha256\": \"dbc0ca75f928b4568e540b22f2d3b43cf5a8057addc8cfc28f84d32cb55ebbbb\",\n        \"size\": 479963277\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11067_Weather20.tar.gz\": {\n        \"sha256\": \"b3732b4c8b4170aee312f0b54033afbd750aebb1682b0195be80ffba71d84ce1\",\n        \"size\": 609602814\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11068_Weather21.tar.gz\": {\n        \"sha256\": \"64e01090441a53ce706d5f2d6e9f3de4792e27a4b71ce7c0231bd7e079f2722b\",\n        \"size\": 222584793\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11069_Weather22.tar.gz\": {\n        \"sha256\": \"a1f5e7c6e520a14afd71d9e1dcaad7412c924cb711720f8097e7ad420efafe5b\",\n        \"size\": 180510198\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11071_Weather23.tar.gz\": {\n        \"sha256\": \"5bcc5f271d2f536808d2f1119b02cb648a39fa8ad2ea8a4e90a0bd66a46b0e6f\",\n        \"size\": 212375086\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11075_Weather2.tar.gz\": {\n        \"sha256\": \"0b90aebd107735113df45c8d8726863680a219d8f83e05631046ea2ace5ef285\",\n        \"size\": 264638851\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11077_Weather3.tar.gz\": {\n        \"sha256\": \"54f222a4c3f75faa8d1f22a62e6ff74ea101d40e6171dd52b7d6fbce7a9e9c21\",\n        \"size\": 99211151\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11078_Weather5.tar.gz\": {\n        \"sha256\": \"0d943fdd23c0648d99840eacfe8337f8612a3b8f4ea4e0ac8bda518a78de028e\",\n        \"size\": 289138425\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11081_Weather8.tar.gz\": {\n        \"sha256\": \"f5298c22324944e0718d55600a6993c5b00db6f2f1e881c07af11cae0f24b9cf\",\n        \"size\": 462643868\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11083_Weather10.tar.gz\": {\n        \"sha256\": \"37a2cf7afb2920566ded1ba8dbec6732a96c7c3dea1290fd6f27162c24eeaa67\",\n        \"size\": 558096118\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11084_Weather11.tar.gz\": {\n        \"sha256\": \"6415d3f6abb0057278d47e795241c4ed83e0c1672a60c3c777bea81599e4389e\",\n        \"size\": 85584131\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11085_Weather12.tar.gz\": {\n        \"sha256\": \"17bbe00bde295079ea8ba5acf6cbf900fdc0b4b32ae46023f7b1bb151dc8bb13\",\n        \"size\": 329843776\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11089_Weather8.tar.gz\": {\n        \"sha256\": \"ced891e70a864ed3db9a20efb764f8cd701842b7be6d8254faf5b27e22b3fdfd\",\n        \"size\": 176522820\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11093_Weather20.tar.gz\": {\n        \"sha256\": \"3c3156c94934b03660cf4162d8f821d2ef746418585939ae8595688577b47501\",\n        \"size\": 298924352\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11094_Weather21.tar.gz\": {\n        \"sha256\": \"955348ade1998b1582b38c458a3377806491ce8dff311259be167b6acc7e9b5a\",\n        \"size\": 296190876\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11095_Weather22.tar.gz\": {\n        \"sha256\": \"43cf13652e33196e186b9dcc249fad078f0ffe5457b1414693d2be10c7b7af60\",\n        \"size\": 212585263\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11096_Weather23.tar.gz\": {\n        \"sha256\": \"087d4d0da00b0b0cbc51d84c72fab5a713029951d101708b4a277d08c3ad61a8\",\n        \"size\": 156117474\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11098_Weather25.tar.gz\": {\n        \"sha256\": \"aabfe24eff0146485e8baf90085ad0f2f4d4371bdd30ac621a28ec2557e8ea32\",\n        \"size\": 412477838\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11103_Weather3.tar.gz\": {\n        \"sha256\": \"5e1210e7bb437279e797970e1e1b691b5779b984c9c2545fbe57e2120e08dc79\",\n        \"size\": 252679930\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11104_Weather5.tar.gz\": {\n        \"sha256\": \"9c678cfacee7aa0117fb8060c07fd0834f47d1a3da83a6db3d9fd50b363a036e\",\n        \"size\": 177895811\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11106_Weather7.tar.gz\": {\n        \"sha256\": \"0c233661f66e91493a8e7c6653cf584d34e333fc23d8a2c5cc0fa9ef49c74f77\",\n        \"size\": 147698661\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11114_Weather15.tar.gz\": {\n        \"sha256\": \"cc49edebebd8184f804b3ae43608c3cb2e629129f0d8f0a50c0e06e929cc6ca9\",\n        \"size\": 452096654\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11115_Weather8.tar.gz\": {\n        \"sha256\": \"d8f13dac86d8e7fcab3dcb9f865f3862a4ee41551fbb65019f5a9b327377fed5\",\n        \"size\": 261175698\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11119_Weather20.tar.gz\": {\n        \"sha256\": \"fd97f0bd7dd8ca55228114b67d683e714fc02add40c6bb5f53393735492a59b4\",\n        \"size\": 324478649\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11121_Weather22.tar.gz\": {\n        \"sha256\": \"06ba42dce5244359fd343aeb78246503a3a12ae225239ca32ce8688223d3efc2\",\n        \"size\": 137063842\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11122_Weather23.tar.gz\": {\n        \"sha256\": \"ea0fbfc99fa78a03a6d405dc0cff4a7f4c34c52a8fba1c71b4e000215c1a0dfc\",\n        \"size\": 211330507\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11123_Weather23.tar.gz\": {\n        \"sha256\": \"1d752bc02a0a3342caa90d0cec3f2aa88bf87f9516d4ff3b113ae0e281266e22\",\n        \"size\": 510433953\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11125_Weather0.tar.gz\": {\n        \"sha256\": \"8a7febfb9801b21e841cc1f86555a526a262955df25d2a43a681db0241616c60\",\n        \"size\": 443819256\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11126_Weather1.tar.gz\": {\n        \"sha256\": \"7787d9ef3e89ea9155a4156df97cea047bdb8b73e04c4202ad9ead68723ab15f\",\n        \"size\": 520737963\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11127_Weather2.tar.gz\": {\n        \"sha256\": \"950a23a2e6fac9480f271897f4574ffea882196a1ed11a69ea006f8efc01c471\",\n        \"size\": 196697983\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11128_Weather3.tar.gz\": {\n        \"sha256\": \"5cecd3a40ff4849fc36e1f3a0da623d171a99d7c5ec07c5ccf44abc724c5c207\",\n        \"size\": 119033024\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11131_Weather6.tar.gz\": {\n        \"sha256\": \"5be7a2bb71ead98ff9b77412787aa32c30615375c97f3a174a3ef4257db25d00\",\n        \"size\": 285224351\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11134_Weather9.tar.gz\": {\n        \"sha256\": \"c859af1944a597ae01dc3916823e6a7243165f894fd61d8232765a0473e07bb8\",\n        \"size\": 111622118\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11137_Weather12.tar.gz\": {\n        \"sha256\": \"7403773d7416eb11a5804ffecd19f081f6dea1e216baa1f040143bdab8b62e7b\",\n        \"size\": 224588891\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11139_Weather14.tar.gz\": {\n        \"sha256\": \"670f79b3856ea7d8f131ea45c954985666093476433c95c01d79738845f89832\",\n        \"size\": 280489446\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11141_Weather8.tar.gz\": {\n        \"sha256\": \"65b51d960c9d317cdc5a6eed732799fe1fd4f0c288cdc883981d77db4ccd6127\",\n        \"size\": 250569801\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11143_Weather18.tar.gz\": {\n        \"sha256\": \"aec9847a31e2bfac4d8195a6719557d06623ed9c31ae18e63ba7345afc325a8e\",\n        \"size\": 182013417\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11147_Weather22.tar.gz\": {\n        \"sha256\": \"1b27c50bf9817bc09778d5b3e71a9205e60065f217298cd332942413fdba6eb2\",\n        \"size\": 360145381\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11149_Weather23.tar.gz\": {\n        \"sha256\": \"ed123d28a57ae12014dd1d5a44c56a6a97443a02e12a65f925f0aa2cccfc5e45\",\n        \"size\": 213232795\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11150_Weather25.tar.gz\": {\n        \"sha256\": \"5dce4a8be15c33a1adeea2160fb611e67d81211d85926b76b685ce00d5e7f8a0\",\n        \"size\": 241749196\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11152_Weather1.tar.gz\": {\n        \"sha256\": \"8675ed45bfd8c3b87738dec28d94ed09e3ad0b5ce0bb6314da32269a894b9ebe\",\n        \"size\": 419404485\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11154_Weather3.tar.gz\": {\n        \"sha256\": \"3d901a3c6164f8d90c1e4463867097acf8e96b9b14df3bc8a476d3002e2b86d8\",\n        \"size\": 216583726\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11155_Weather3.tar.gz\": {\n        \"sha256\": \"f5a69a464d1fc8c8303fcd58c88c89e888aa8625a57f73b6b7d2deb59000c971\",\n        \"size\": 235042011\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11156_Weather5.tar.gz\": {\n        \"sha256\": \"ec7c3ee956f8906f8fcbddb6dd851a7635ec3a90eaf17ad096a76b457295398c\",\n        \"size\": 105512848\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11159_Weather8.tar.gz\": {\n        \"sha256\": \"6de02e07a049a1364b84796dc33b62d7accc96b4b75f7db6d60966341a580de1\",\n        \"size\": 423503601\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11160_Weather9.tar.gz\": {\n        \"sha256\": \"8f5afff4bf7d43083d64faca4e6d685c67b9bf24b6f7662eac3d6bb48fd44a2a\",\n        \"size\": 70443651\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11161_Weather10.tar.gz\": {\n        \"sha256\": \"1fed73c3aaae042692f20d4182a85dab0e4f7dd68451ce575ea198bbf754bddb\",\n        \"size\": 199512317\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11162_Weather11.tar.gz\": {\n        \"sha256\": \"688c141ac17c12732266abc238b63f064713d172f0f8e73c72844a312f8c7ef4\",\n        \"size\": 744038960\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11163_Weather12.tar.gz\": {\n        \"sha256\": \"7102fa376d4f290e25daa352a0574efa5dda311cbb9476e14f4c660ef2eb5bdd\",\n        \"size\": 205373534\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11164_Weather13.tar.gz\": {\n        \"sha256\": \"f695d5ee2af4f4cc1bffa15ca23920b62f270cf137f6ba9bdf59a179ed0242c5\",\n        \"size\": 349898471\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11169_Weather18.tar.gz\": {\n        \"sha256\": \"6fb8204a808b343816e87b35dbb5db4aeca5a73cbbf1055284512a3466cdd7cc\",\n        \"size\": 255087337\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11171_Weather20.tar.gz\": {\n        \"sha256\": \"fbdca1ed03df996bab64457bd56d815e070a22701ebb0c1514367b3b49e5e4dd\",\n        \"size\": 845238092\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11172_Weather21.tar.gz\": {\n        \"sha256\": \"ef5852025904d85f066cfb45b7323d616c26b12343195083e2c8b36736712d4e\",\n        \"size\": 498827047\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11175_Weather23.tar.gz\": {\n        \"sha256\": \"89be797a5ced3af976b2e38e01f9c691d2ac100882bf97347856d09ebb6e40a2\",\n        \"size\": 474566071\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11176_Weather25.tar.gz\": {\n        \"sha256\": \"062ff902370a7ae8715ce7de1b01ddba33876b05877c63bb9abcf9c4eb3e6e81\",\n        \"size\": 163703484\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11178_Weather1.tar.gz\": {\n        \"sha256\": \"47f42792ae36e56e2ba587b2c39497edcbc38511dc2fd34e5c9496329276c17f\",\n        \"size\": 632951520\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11180_Weather3.tar.gz\": {\n        \"sha256\": \"27fc488a2b9d1d08437a60c81b238f5908f31f082e8c4f6ae956183b3e0d14c0\",\n        \"size\": 164242324\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11183_Weather6.tar.gz\": {\n        \"sha256\": \"2039189e08d162db0abc8f78f6a3eb7ab8ffdc99a55697898a132d816b75904e\",\n        \"size\": 281813857\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11184_Weather7.tar.gz\": {\n        \"sha256\": \"e9deda55a5d833735cbda2ed5088684d03b6848b8171db1f891774447b58e431\",\n        \"size\": 353267928\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11185_Weather8.tar.gz\": {\n        \"sha256\": \"bc9c845d424a5da4b2d4b25ee956f6d4d502b1c25b71697087b92912a8ab88b7\",\n        \"size\": 408627243\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11187_Weather10.tar.gz\": {\n        \"sha256\": \"8067df8ff80baa169177cb80dcdfc113ea5b199e3d9a8769c5750d537a44681a\",\n        \"size\": 199412930\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11188_Weather11.tar.gz\": {\n        \"sha256\": \"6803ad6c9d96985ff8b6cf135dccfc0acd2313b1c99244be0140658e7d07ddd6\",\n        \"size\": 559266862\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11189_Weather12.tar.gz\": {\n        \"sha256\": \"2f6a55405b101d6d0c54b5c2e65132265e39279f61a3093f1dd0c3dc93d45b61\",\n        \"size\": 187971671\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11191_Weather14.tar.gz\": {\n        \"sha256\": \"84f492aa91cdbc2a4fe5919157f1bbe45c404fe42769f6d3be9bc6ffee015f00\",\n        \"size\": 311186668\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11193_Weather8.tar.gz\": {\n        \"sha256\": \"fee4ac746c3e5a4aad7058c76a8c2988fb25557ebfd3b4e3b8586dc97310a7fa\",\n        \"size\": 356384771\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11195_Weather18.tar.gz\": {\n        \"sha256\": \"3da8de661e0becdc51b97d7f149ff9cfd9de5accde22e2fee3beb952d3a085ce\",\n        \"size\": 301581065\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11197_Weather20.tar.gz\": {\n        \"sha256\": \"a419d39418a0836a51a45053f2eac630570db53c622bd1a7545b4e5145cff934\",\n        \"size\": 477831035\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11198_Weather21.tar.gz\": {\n        \"sha256\": \"77a1511de4cfb6591550ed4b34335bd9d069fd2b4b9ca7de6e7ead980154577a\",\n        \"size\": 239498443\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11200_Weather23.tar.gz\": {\n        \"sha256\": \"216e7f5139968403c9e36f7318eeb79aa4994547616c981476b989a4c3b93dce\",\n        \"size\": 278101046\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11201_Weather23.tar.gz\": {\n        \"sha256\": \"df1e1aa204e87823ec8e12afa10b518b0cf30588fdb6396326ce71ba4572a3d0\",\n        \"size\": 163210189\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11202_Weather25.tar.gz\": {\n        \"sha256\": \"9c1c3e93962fe545948603fe926fcf93364486741ae540c7d5ac6c6d17a32b48\",\n        \"size\": 295354536\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11203_Weather0.tar.gz\": {\n        \"sha256\": \"730ffd7064b6c1b45ecfb788193082796a5f1e161096ae7cb8ea58df529475cc\",\n        \"size\": 576220221\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11204_Weather1.tar.gz\": {\n        \"sha256\": \"dcf93308f5790687be005622f45db0cc640e76f1c8b973604bb4f135152db456\",\n        \"size\": 521351914\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11206_Weather3.tar.gz\": {\n        \"sha256\": \"94034d0d0914627053d7a5192da96a72ffe2f2c44fad8ac8a7010caffa4c3d79\",\n        \"size\": 1143933097\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11211_Weather8.tar.gz\": {\n        \"sha256\": \"80ac2ad70a1d01203291f990c1f7c1c01f45df50034ae48c2e5d9b74da2725c2\",\n        \"size\": 472536056\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11212_Weather9.tar.gz\": {\n        \"sha256\": \"de28b9f4bbe6f46a34e3d03d4e76c4d7fb5cb915ae3be7df2237887f27d4e36a\",\n        \"size\": 294990038\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11215_Weather12.tar.gz\": {\n        \"sha256\": \"21c2522c869d82af6fdb642a22565e499a843eaa1b90a7fff7dbe8937f2bb303\",\n        \"size\": 355542084\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11217_Weather14.tar.gz\": {\n        \"sha256\": \"6fa71a0d2a04e46d186826ba7453c2485679550a4a78ade4071aa4a5335657cd\",\n        \"size\": 103787983\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11219_Weather8.tar.gz\": {\n        \"sha256\": \"4919f94aee623feab470a232a4a9037f30baf76878b761906bc3170e6dd16d1f\",\n        \"size\": 234121757\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11220_Weather9.tar.gz\": {\n        \"sha256\": \"b4ae54047ef296f3e53e0b3acfd4c2d00338587528396799bd203288fb713571\",\n        \"size\": 302347573\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11222_Weather19.tar.gz\": {\n        \"sha256\": \"cb4b75ca44a1a8332eceb4e918a57345b1061002b1c4077785ae2fe8ed306fc5\",\n        \"size\": 358283289\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11224_Weather21.tar.gz\": {\n        \"sha256\": \"ba259c928e3e3b5234606b9a9477acc3c3c77611446e5004f9a079e11ffebaaf\",\n        \"size\": 335014735\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11225_Weather22.tar.gz\": {\n        \"sha256\": \"b7497f5e1e5f2ab9f58a10f17f3370598ed59b7d795d3aa57d8c47efd2989247\",\n        \"size\": 231854935\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11226_Weather23.tar.gz\": {\n        \"sha256\": \"c87ef28a2ee32c77bc0d8c580008157110bd43894b5c06de99d543d13e4bbdcc\",\n        \"size\": 292864445\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11229_Weather0.tar.gz\": {\n        \"sha256\": \"46da2392132bb48af2053becc9d726a9e738c17081c35138870a02be1e84adf6\",\n        \"size\": 357818008\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11230_Weather1.tar.gz\": {\n        \"sha256\": \"d5605abd64709de74624bdb19ca4a22b0a429d8bb682e4042cfd7b5313632aff\",\n        \"size\": 489428557\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11233_Weather3.tar.gz\": {\n        \"sha256\": \"768148efda937c68fd7a750f10089429f7142a0055fbbe532c48f8cfda8ab3b2\",\n        \"size\": 204571477\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11234_Weather5.tar.gz\": {\n        \"sha256\": \"5d808337801a1b33e34e5540f7edebdc0f74ddae3ea87f33d6a1842e06c25ca6\",\n        \"size\": 173485128\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11237_Weather8.tar.gz\": {\n        \"sha256\": \"d3bea22262080df9455756fa6d000539501c22726b3ce3119897e48ced88fd0c\",\n        \"size\": 230617980\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11238_Weather9.tar.gz\": {\n        \"sha256\": \"2c2298f896a35391defb5f511c043692b420a347b66c9a916075b5d86390bdd7\",\n        \"size\": 440398088\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11242_Weather13.tar.gz\": {\n        \"sha256\": \"94971cb1ef6fecb55b05f4534b7e3d24271fc089080bc7eb484d684dcdf27a6c\",\n        \"size\": 245165219\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11244_Weather15.tar.gz\": {\n        \"sha256\": \"9cd5cc32e3f6cbdd15a033ac5dbb61c871b2f8fee6dfb34d69f9fc8dbbbccbf7\",\n        \"size\": 352272833\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11245_Weather8.tar.gz\": {\n        \"sha256\": \"306f0a2564545f1fc4dee0758c2bbb804f31c7fb1249e6750aacafb1b7123eb8\",\n        \"size\": 298906509\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11246_Weather9.tar.gz\": {\n        \"sha256\": \"68d137633263caf78b9e43b9505df7a66b3e6eb8f7261c12ad6ab49a345a7f5f\",\n        \"size\": 243291618\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11247_Weather18.tar.gz\": {\n        \"sha256\": \"77f670fb3fc25416198038582d49970984e2d37222948a79b05df35a2d981f95\",\n        \"size\": 538163373\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11249_Weather20.tar.gz\": {\n        \"sha256\": \"58ec429592bf7941be74f0ac5a120d446a77325d9fb03e1b76ea8803d1663152\",\n        \"size\": 326800166\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11251_Weather22.tar.gz\": {\n        \"sha256\": \"05603495f4e76c1fa822a98cb1107c528546ec864bb411de5f7941e804d450c4\",\n        \"size\": 341217708\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11255_Weather0.tar.gz\": {\n        \"sha256\": \"de45d4f8940e846a98c1c0e291c8b5142a0ed56d3cabd5a267c5483069a8a852\",\n        \"size\": 580460371\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11258_Weather3.tar.gz\": {\n        \"sha256\": \"b1e2e6ff17138b7f56bbe45dc91dceb4cf27ac4fad9bc89abaa358d26801c12d\",\n        \"size\": 386854318\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11261_Weather6.tar.gz\": {\n        \"sha256\": \"979c5ad015f026f9642c2f3750054220ed8a4ad25d82323ed57f1ac81cdf7676\",\n        \"size\": 264868861\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11265_Weather10.tar.gz\": {\n        \"sha256\": \"26397ef5eb14194f1890831afeb97b979a63babf308befb83e21421b62f3b5e1\",\n        \"size\": 189022470\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11273_Weather18.tar.gz\": {\n        \"sha256\": \"7b7924051442211ff0ddd76cde2f381f87d6e043765f7a25a5e19f9ed65a77ea\",\n        \"size\": 119164476\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11276_Weather21.tar.gz\": {\n        \"sha256\": \"85868e524e896963a442a493f06f16a71fd9387cce34e6bc47d932ce8b005dce\",\n        \"size\": 463027253\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11278_Weather23.tar.gz\": {\n        \"sha256\": \"324c3698ce82c80c51e597d6de1d1cf764b894e694bde476545408d81dc4f7b1\",\n        \"size\": 244257532\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11279_Weather23.tar.gz\": {\n        \"sha256\": \"fa0d859d7da2bdaa8af45cc8042ddbb5b864c2ff8f8e99c3e8f61ea0babb2f9b\",\n        \"size\": 234791040\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11281_Weather0.tar.gz\": {\n        \"sha256\": \"22bad36f0fa305a88e61c663a14aeb17b240031d49a7261ccd4829bc25c0ade7\",\n        \"size\": 184506279\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11282_Weather1.tar.gz\": {\n        \"sha256\": \"70f3b96d18a1d762163ccb03dff04549dea77ba4def8a201c8b74b4fc3302f78\",\n        \"size\": 199368999\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11283_Weather2.tar.gz\": {\n        \"sha256\": \"07a9e1843eed3273c5a0b4607d00a54755cf9e11f23b6d27415a7c28116a82f8\",\n        \"size\": 576216626\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11285_Weather3.tar.gz\": {\n        \"sha256\": \"74b066f86e41461b425f1003a3266e9e818fa22faa0348d2c227bf38273cbd06\",\n        \"size\": 368640442\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11286_Weather5.tar.gz\": {\n        \"sha256\": \"ac60bbb6994aff97bfaebce290388a44ac1e2e581df8d03cf78673197bcc615d\",\n        \"size\": 588210044\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11287_Weather6.tar.gz\": {\n        \"sha256\": \"97e3667de7ec8744108112de13782a4c9db15c9e50c264e66cad2e23af6a96e0\",\n        \"size\": 165160741\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11288_Weather7.tar.gz\": {\n        \"sha256\": \"da0a9b0dd1300b2b86e3a41d451c5d055f0a21f9e344274736e632523b59b4f4\",\n        \"size\": 123616825\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11294_Weather13.tar.gz\": {\n        \"sha256\": \"26b3acb742389443c278b4d8c796516c607d2d150ddd8818fc18060439909ca6\",\n        \"size\": 220300706\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11297_Weather8.tar.gz\": {\n        \"sha256\": \"414fe2dd6af18d4fd997fd66ed9764f498ae2b4e9cf1ec12166fec96cae4b4bd\",\n        \"size\": 213556636\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11299_Weather18.tar.gz\": {\n        \"sha256\": \"70d1567ccd08ec23268b0411d6b9109841cdc0b7e04f98ca67e118bb844d6284\",\n        \"size\": 212390813\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11301_Weather20.tar.gz\": {\n        \"sha256\": \"c774749e147ec18c88095a2145f57a33cd708b50c19bdf64976a609d70aa6f0e\",\n        \"size\": 258075350\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11302_Weather21.tar.gz\": {\n        \"sha256\": \"a620694ab09b85f4198cd45c7571a2f9220a01272efb8cb8c876de5ac05ddf10\",\n        \"size\": 351816694\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11304_Weather23.tar.gz\": {\n        \"sha256\": \"3c2d3b2ba39ccf963222aa590f954ccdd6a17d7f7bd460ff747f4c7ce3bbc716\",\n        \"size\": 318923423\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11305_Weather23.tar.gz\": {\n        \"sha256\": \"05e9b08b510e557e397dcaaa022a851589e8a12f65e0e7ad92e2aa7e5173cb20\",\n        \"size\": 236273369\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11306_Weather25.tar.gz\": {\n        \"sha256\": \"c8fdc7a3d3f000fe4a489af784267ede3f54af35f1b028ce31d9839722c8978d\",\n        \"size\": 299276083\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11307_Weather0.tar.gz\": {\n        \"sha256\": \"189a694ebb5974cbe0fdcff9ee50eb7ff739ffa8d4ca695131ca415137ae2867\",\n        \"size\": 372669220\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11308_Weather1.tar.gz\": {\n        \"sha256\": \"abebc27fa712dd92cef3883bbb4af825ac5cd3179d1057b0465bc0ecfbb669ad\",\n        \"size\": 390563835\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11315_Weather8.tar.gz\": {\n        \"sha256\": \"7fdcb322c09c32cb8559ce3d41e1915db8a155c08cdf7b5ce7e944728793f272\",\n        \"size\": 519665515\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11319_Weather12.tar.gz\": {\n        \"sha256\": \"08e9677eace97fd9f54d3c30fdc12f590bab538991497ddbf92fb59760175c2b\",\n        \"size\": 209193716\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11322_Weather15.tar.gz\": {\n        \"sha256\": \"9ccaeb2dfd7a0babf6bc735c1147964e3492f061a15a4e41f73979347ec2077b\",\n        \"size\": 595417876\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11323_Weather8.tar.gz\": {\n        \"sha256\": \"7f603c71c5a5f8266bb01d2577b0e0b4fa14eb29e9c0558716f13254d61a1229\",\n        \"size\": 518233222\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11324_Weather9.tar.gz\": {\n        \"sha256\": \"58fa915124c5471a2a21c4d88a530937f2b1c01c9f20c26d3f19e41949143e11\",\n        \"size\": 200194838\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11327_Weather20.tar.gz\": {\n        \"sha256\": \"42c44fec6b7bcd23bdda5fb36defee7ff10580086d490fd478f3700cf18e0249\",\n        \"size\": 81734963\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11329_Weather22.tar.gz\": {\n        \"sha256\": \"59207d7f88cee99ca136213f5475bb93a51362fb70b0f11e1af3b2f42da2e65a\",\n        \"size\": 122520977\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11331_Weather23.tar.gz\": {\n        \"sha256\": \"66e648c3cbe094b9d642d92cbb31293880e76e5ef4362367f7162d0414e5c85e\",\n        \"size\": 611403737\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11332_Weather25.tar.gz\": {\n        \"sha256\": \"7e81331fc558d0677a05dfe737783f6d8d6661dc0cdffb37daf6ccc283629b20\",\n        \"size\": 222480113\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11333_Weather0.tar.gz\": {\n        \"sha256\": \"136e206c0f967f7f70c5dc7c6d847d4664089568a01d950b518266448970dc7b\",\n        \"size\": 274272060\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11334_Weather1.tar.gz\": {\n        \"sha256\": \"80986f43f03bca920605290d7b9391ae698ab9db7f8c708b03034ae3fac43680\",\n        \"size\": 105674947\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11338_Weather5.tar.gz\": {\n        \"sha256\": \"2c2c03cc77b8f848daa09e71adfa2caa64e2a0cc37a63dde46336052d891e447\",\n        \"size\": 841999745\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11339_Weather6.tar.gz\": {\n        \"sha256\": \"f87cc875e611c468d239c0c04f1232c5ac876c1d297c0f187e536b5cac78a0f3\",\n        \"size\": 523256204\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11344_Weather11.tar.gz\": {\n        \"sha256\": \"214b66aa62f32592b67ad51fc65224cdc634ef912219aa364fd84426094e3cb4\",\n        \"size\": 261393189\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11347_Weather14.tar.gz\": {\n        \"sha256\": \"227275af41f997cf70231546d928059f79afce42c62b05475c3034e901ab9c81\",\n        \"size\": 175211608\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11350_Weather9.tar.gz\": {\n        \"sha256\": \"3a6d3a328e06a54936dd57616a581a090f6fba6d3a6270787ac719cd9543d06b\",\n        \"size\": 183097797\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11351_Weather18.tar.gz\": {\n        \"sha256\": \"ab512d52551ecc2caf09fab7b42770c84784439404eecab9151dbf3501904d5f\",\n        \"size\": 184976333\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11355_Weather22.tar.gz\": {\n        \"sha256\": \"b5b0c94439ea46f4a0b910f4f798a1e2608d2c386a773571147bd9376ee94576\",\n        \"size\": 192560324\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11356_Weather23.tar.gz\": {\n        \"sha256\": \"44551b408aba48f633aa505c46e8c282ec13e19249cb24ef84d58ccec14758c3\",\n        \"size\": 81301105\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11357_Weather23.tar.gz\": {\n        \"sha256\": \"1a213128e8d63c0207b0b714633128d73b2eb172dedd957a1a6fe5febdad9936\",\n        \"size\": 201755921\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11358_Weather25.tar.gz\": {\n        \"sha256\": \"f55f42938a173447d536d11de8221374f713fbf71093e880d47f827265d17763\",\n        \"size\": 275038526\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11360_Weather1.tar.gz\": {\n        \"sha256\": \"8c51774c22d297f5a19932d4153cf8263b885bf5ade7591fd9b4b6b52a980d37\",\n        \"size\": 348868476\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11361_Weather2.tar.gz\": {\n        \"sha256\": \"9ba650e488c7db24c9a5e4c7549e8a8eb6087d809c147a5411d602d873e5222d\",\n        \"size\": 94115738\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11362_Weather3.tar.gz\": {\n        \"sha256\": \"4f687369a2a927c55dfef83e1d7d2de4617aa8d11a7fdf2122889789e221f21d\",\n        \"size\": 357634066\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11364_Weather5.tar.gz\": {\n        \"sha256\": \"1c4a9c9d94b5536dbfb1f1f550a77ba5a086752ee33e8081be19e936ecbcfa8b\",\n        \"size\": 117134449\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11367_Weather8.tar.gz\": {\n        \"sha256\": \"bdb90430a234fcf77c1a5bc5fddee3c06728d71d4070828b8ff840d61cdc89b1\",\n        \"size\": 319799381\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11369_Weather10.tar.gz\": {\n        \"sha256\": \"7af20b2378617d1e05f0d358ece331d039cdd2b34b4a3504693f1ab774dc2e00\",\n        \"size\": 154518848\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11370_Weather11.tar.gz\": {\n        \"sha256\": \"fd481c3e70f478d7e0f5fc4b9fcf19dae3a88950b742f3135e641de9fcd6c519\",\n        \"size\": 95341986\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11371_Weather12.tar.gz\": {\n        \"sha256\": \"f92eaf85b1ab22d6e0076c5db4b0c7df7e24dfbd93970e1dbfb3871da74bd86d\",\n        \"size\": 416223584\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11374_Weather15.tar.gz\": {\n        \"sha256\": \"831b2fa2481a466d34ec3763453766535267e4ba3dd621d13322854e503c6870\",\n        \"size\": 111795222\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11375_Weather8.tar.gz\": {\n        \"sha256\": \"eb4a5085ce9ef7255bf637ba517258acb8240c4f5098ed1e37c077de57182922\",\n        \"size\": 265810294\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11377_Weather18.tar.gz\": {\n        \"sha256\": \"5745eb28046b220a92eded53662ba7625cc0481df7b1841f476af40f8e803db5\",\n        \"size\": 306994320\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11378_Weather19.tar.gz\": {\n        \"sha256\": \"cb4419b1f555abee73303203960beedc08d0787188c5cd898925a4b9b5f01ccc\",\n        \"size\": 234746487\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11380_Weather21.tar.gz\": {\n        \"sha256\": \"2c781e0c787b37f069f0fffb7bbd9d6f2dd895ad357ba8736c62ebbb9bb6bd76\",\n        \"size\": 204265276\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11381_Weather22.tar.gz\": {\n        \"sha256\": \"20e5e44a555545ccb84774677cc2a29028d4cb5575f8aaf8bc83a77e2c9b45f6\",\n        \"size\": 531732686\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11383_Weather23.tar.gz\": {\n        \"sha256\": \"47ba425282cccfeece39eba4ff60f90577372ec2090db7e8ade34db0d241dc75\",\n        \"size\": 762709970\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11385_Weather0.tar.gz\": {\n        \"sha256\": \"5c3a0c28a4017155e4681c4099074636f9beea02318f8bfea4483ec5fbca303d\",\n        \"size\": 272372987\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11386_Weather1.tar.gz\": {\n        \"sha256\": \"6c1432545f0ab59136b8dee0214ed03de25a0daef69d1df39495ca5b4d3df72f\",\n        \"size\": 340470700\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11390_Weather5.tar.gz\": {\n        \"sha256\": \"f0209b51b0d34c629f27b20fd02f55279f60c971e763bba588d5e2f630944f4c\",\n        \"size\": 374169281\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11392_Weather7.tar.gz\": {\n        \"sha256\": \"8a0c2c70baf29bd46b00952ff9fc75b1f25f6ec80ad570299f7947928d2910aa\",\n        \"size\": 301981160\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11393_Weather8.tar.gz\": {\n        \"sha256\": \"e9119a16943a509ebb2354d40091ae62db90f882dc2ba3ea9dd7d7deff230d8b\",\n        \"size\": 116564773\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11396_Weather11.tar.gz\": {\n        \"sha256\": \"564e53808fafde5cef7016d3a3b40758d1021a1c8fcc7f4476c854e84c3cda09\",\n        \"size\": 65812543\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11400_Weather15.tar.gz\": {\n        \"sha256\": \"44732481fac2275d4da381128ea2104716dc75e78d42f59895c2dbce4ebe7867\",\n        \"size\": 180266346\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11402_Weather9.tar.gz\": {\n        \"sha256\": \"0bebc432d8cdf6405b6015d50b0918ed20421c3c4da64901d8aec0da7b71f282\",\n        \"size\": 341192086\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11405_Weather20.tar.gz\": {\n        \"sha256\": \"4acc33343f526bfa3ddd6e54deb133aa8252e4ee77074005c827dddd8302b2d7\",\n        \"size\": 119761242\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11406_Weather21.tar.gz\": {\n        \"sha256\": \"ac2790c0ea50986726aa1e90203898edcb8fff7e580247808f30d3c81b200c7b\",\n        \"size\": 138720139\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11409_Weather23.tar.gz\": {\n        \"sha256\": \"8099127974d74dd6f26b21cbfd05fea8b0a1e3c6facf0e68a028243350d1874e\",\n        \"size\": 156605212\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11412_Weather1.tar.gz\": {\n        \"sha256\": \"8ddafd5fea8e0db21ee7893e7c34aa6f6019e86903fd7d4778f2e3ab5ac6a29a\",\n        \"size\": 605570240\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11414_Weather3.tar.gz\": {\n        \"sha256\": \"57eb1bf183a0c673ee60a2b80c8a5c6d0fa004982b1969f25b8d5591878b9527\",\n        \"size\": 213816701\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11415_Weather3.tar.gz\": {\n        \"sha256\": \"d9fbb14ea105e2428a5d4c436eec3c69d8195e43a2fd97eadd633d8f38264d6f\",\n        \"size\": 543304446\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11416_Weather5.tar.gz\": {\n        \"sha256\": \"9056a504955cf5b045a356e362bc36b4305d72e400dfbe53aeb361aa94bc852c\",\n        \"size\": 413304848\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11420_Weather9.tar.gz\": {\n        \"sha256\": \"903d8855219bab467c25cb071a7ed68b40ce63c8849a545f69c494210b1ce241\",\n        \"size\": 201199305\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11421_Weather10.tar.gz\": {\n        \"sha256\": \"33631204cbe555aa4ac6136f1088ffa5f4285522b97d3cc0fa2ddebcd483b37e\",\n        \"size\": 476615194\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11422_Weather11.tar.gz\": {\n        \"sha256\": \"a0d2cdb88aa91c7a427d36f4b19755b38128bedc7e9a4697cd5f4d77b764370b\",\n        \"size\": 223587367\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11423_Weather12.tar.gz\": {\n        \"sha256\": \"c91124c657f797d93f1b9823d996d466934daa16dbc887800e982541e5160998\",\n        \"size\": 247508109\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11425_Weather14.tar.gz\": {\n        \"sha256\": \"9f73c66190449587ebfd40b7ed2fe44737c90af893c758876fcb02be8296e53b\",\n        \"size\": 375444521\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11427_Weather8.tar.gz\": {\n        \"sha256\": \"a79d84156412397d1eda1fc33402bc0d6769431ce32a1a976f1ab60f299653bc\",\n        \"size\": 232964025\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11428_Weather9.tar.gz\": {\n        \"sha256\": \"5b989d002f7b505ed5a0e16f844a62e0243db05a4878f67e08257908b24b3578\",\n        \"size\": 70186905\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11430_Weather19.tar.gz\": {\n        \"sha256\": \"dc5545fdf8f0523d4a4cee4fcd3786ac3d984536aeb8664b399efb0890bb457a\",\n        \"size\": 348693023\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route11434_Weather23.tar.gz\": {\n        \"sha256\": \"ae3bc670372a20aa65a19f880e1f150936e816e35df3a12d1848b298f39ac32e\",\n        \"size\": 213649567\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2164_Weather0.tar.gz\": {\n        \"sha256\": \"88297ad029995332365cec2dcbe006146dcc255cf48457569e3a41ea3d931025\",\n        \"size\": 337847129\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2165_Weather1.tar.gz\": {\n        \"sha256\": \"83d2636d385cdb4265cdc76eac621dbdaa6aa100e97e01a240895140cf14e1b6\",\n        \"size\": 633969311\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2170_Weather6.tar.gz\": {\n        \"sha256\": \"8d86c9350d792fa131fb70ccf548ff8706459d5382affef4d8c45e09ed4a4c8a\",\n        \"size\": 457736835\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2172_Weather8.tar.gz\": {\n        \"sha256\": \"096c7a89ae8ac24c6da354a14ec9cdec433ec730d8f31a0e33d66813a8c9580c\",\n        \"size\": 282858465\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2173_Weather9.tar.gz\": {\n        \"sha256\": \"2ee02bb50dc1f434a827cd1f3693eb5a384777a35a2ace159483c1487350aa1b\",\n        \"size\": 118455215\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2177_Weather13.tar.gz\": {\n        \"sha256\": \"70d3b24d6975972cda836aa7e336fbe7ba29ac826d9db00bd6937863e7309faa\",\n        \"size\": 128352313\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2179_Weather15.tar.gz\": {\n        \"sha256\": \"7d05543e645587469cd83ccc977740f24e14e896e1ca9f859c976548024e1d31\",\n        \"size\": 155871555\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2180_Weather8.tar.gz\": {\n        \"sha256\": \"54e0f08d2978d9c356416e22cfe4b0acd94c8a5a662f182d81623fed9f034ca3\",\n        \"size\": 227051844\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2181_Weather9.tar.gz\": {\n        \"sha256\": \"6d9603afbe78e0bae0ed23f60ff6fca43c065df9ed9f28a26a40739639ff3dcc\",\n        \"size\": 371712654\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2946_Weather2.tar.gz\": {\n        \"sha256\": \"0704746aef4847f7aeed78932e593928ce3ac3b9f97c07d9fcb537189deea5a9\",\n        \"size\": 218909616\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2947_Weather3.tar.gz\": {\n        \"sha256\": \"158f837a468328c19d2ae6da05c9c41da61d75b48463d7dd8eb8a006a9b42890\",\n        \"size\": 462080133\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2951_Weather7.tar.gz\": {\n        \"sha256\": \"2a44fc277adc8ffb8e3672983ee973c0ba784dbdce55b2efc204f50ddf89347f\",\n        \"size\": 355259193\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2952_Weather8.tar.gz\": {\n        \"sha256\": \"f4bcba54be89c0a54f550f67c084d071c1700b4ea26e9fefcdf8b0618be5a962\",\n        \"size\": 195108533\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2957_Weather13.tar.gz\": {\n        \"sha256\": \"73555e3fb3117e81ac927b2a4a6cd06a10c811d36b51c2056e2f262c2a9184c5\",\n        \"size\": 409529804\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2958_Weather14.tar.gz\": {\n        \"sha256\": \"7ee6764ab4179a769c3ddeef48ddc764403e9749a186b24ecce3ace1f24f56c4\",\n        \"size\": 214843970\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2962_Weather18.tar.gz\": {\n        \"sha256\": \"6e9e4d4c4ff89cb931bd9079c9f339fa2e58edafacd3f7a765e9fe2fd8537c26\",\n        \"size\": 349403875\n    },\n    \"VehicleTurningRoutePedestrian_Town12_Route2963_Weather19.tar.gz\": {\n        \"sha256\": \"03939b91c3a8500347c36b280fc04453797d955dfef4c2ec20f98f9412ce516e\",\n        \"size\": 270805174\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3723_Weather0.tar.gz\": {\n        \"sha256\": \"13a2566934d13a4d3e1e1542f05bb0d1173caa7b13885f64f990711c26aa79c1\",\n        \"size\": 638508217\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3724_Weather1.tar.gz\": {\n        \"sha256\": \"69508f0e10e385691c779e41d40b329f977910135dab304b9b813f0cba4fd554\",\n        \"size\": 182455510\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3726_Weather3.tar.gz\": {\n        \"sha256\": \"a35b17cbfe3e5b732ca1bbed0eec91986d835bef15ce66fa601cc6539eeae45b\",\n        \"size\": 138771494\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3727_Weather3.tar.gz\": {\n        \"sha256\": \"a5f7b06af27e9beab4b050679e94ff7f6d850dbd614df48140552a693611461e\",\n        \"size\": 189421771\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3729_Weather6.tar.gz\": {\n        \"sha256\": \"6331a514966b9d6c64cba20249d2fc91b2525de43fb49d50417bc8a46f0c4dd9\",\n        \"size\": 150279071\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3731_Weather8.tar.gz\": {\n        \"sha256\": \"14911b5d70ed0ef607f3a081377f10bf378983d946e13155d99f3df2d2c128d2\",\n        \"size\": 435586547\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3735_Weather12.tar.gz\": {\n        \"sha256\": \"bc76e9e79f43da0844402404e0751ea6f4acb7eaed2b97a8fa8a3e4fe2daebd1\",\n        \"size\": 148455179\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3737_Weather14.tar.gz\": {\n        \"sha256\": \"1286bcfc4f3f2703b015de3a4ae40b199b89207b0da178f760392f1afce62afd\",\n        \"size\": 528359644\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3739_Weather8.tar.gz\": {\n        \"sha256\": \"519760693695c9471bc6998a5cf2314efd107dfcd4de044c0bec0cf739bce588\",\n        \"size\": 149817293\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3741_Weather18.tar.gz\": {\n        \"sha256\": \"f701d1eb11f75b518106f517473e640e2b97fdb622c4979c0e5737e552c37d58\",\n        \"size\": 166191161\n    },\n    \"VehicleTurningRoutePedestrian_Town13_Route3742_Weather19.tar.gz\": {\n        \"sha256\": \"604abfbb1583f74b13f2ceba069293288f2cefb89e49d7ed647f3eba13f1b8a7\",\n        \"size\": 167085026\n    },\n    \"VehicleTurningRoute_Town11_Route27167_Weather3.tar.gz\": {\n        \"sha256\": \"12a4e1926a93c0c78573c3a15409889424d426efde119fe57e8c76f4694f698e\",\n        \"size\": 63291913\n    },\n    \"VehicleTurningRoute_Town11_Route27172_Weather9.tar.gz\": {\n        \"sha256\": \"3cb0b14f15ec4d0d449203a69a603dbc6ad4c2295ba6cc35b94a82fa53c6456f\",\n        \"size\": 42601875\n    },\n    \"VehicleTurningRoute_Town11_Route27177_Weather14.tar.gz\": {\n        \"sha256\": \"686424b41ceb927361e37be03c2e02cdfa03f306518ee53795e14d0803855f5e\",\n        \"size\": 93886620\n    },\n    \"VehicleTurningRoute_Town11_Route27182_Weather21.tar.gz\": {\n        \"sha256\": \"12f4462444edaa7245f41df31d77f697d270010613aa83e8f7196924553d08ff\",\n        \"size\": 58824476\n    },\n    \"VehicleTurningRoute_Town11_Route27187_Weather0.tar.gz\": {\n        \"sha256\": \"4f4886ee56036d983adacefe51dea4e77a3ca8463bce32022b36e3d290c5dda4\",\n        \"size\": 60636886\n    },\n    \"VehicleTurningRoute_Town11_Route27192_Weather6.tar.gz\": {\n        \"sha256\": \"20c8c79ff78776be9cff40589300fde85cb11ead07fc719a421bd358593e1d5c\",\n        \"size\": 57021180\n    },\n    \"VehicleTurningRoute_Town11_Route27197_Weather11.tar.gz\": {\n        \"sha256\": \"8aae8e095079ad13c4dea10aa80644b037fd058f4c82e4ad5d8b2d16e319facf\",\n        \"size\": 40974983\n    },\n    \"VehicleTurningRoute_Town11_Route27202_Weather18.tar.gz\": {\n        \"sha256\": \"1443022e5f47f29fafa3309e5cda8e50d1a89785c0e3ded19d938dd9aeadb668\",\n        \"size\": 64814063\n    },\n    \"VehicleTurningRoute_Town11_Route27207_Weather23.tar.gz\": {\n        \"sha256\": \"c9ff7244d1b08fa9864cf79599d4bcec00d1e364942414668a16b32d2e3dd446\",\n        \"size\": 73989770\n    },\n    \"VehicleTurningRoute_Town11_Route27212_Weather2.tar.gz\": {\n        \"sha256\": \"7c7b9c1a83a353c28aaf8193d9574307d7ae5855b326f3d84cc83ad06a56bfff\",\n        \"size\": 127005964\n    },\n    \"VehicleTurningRoute_Town11_Route27217_Weather8.tar.gz\": {\n        \"sha256\": \"f25d7f39864c92037a604220e763d98c3b09b765372ee538b57e33b9fbf58684\",\n        \"size\": 101870485\n    },\n    \"VehicleTurningRoute_Town11_Route27222_Weather13.tar.gz\": {\n        \"sha256\": \"f0abe0a082977e26a288425521799f41741aeba3a1bac6f32f7b3c992547b4bd\",\n        \"size\": 80791637\n    },\n    \"VehicleTurningRoute_Town11_Route27232_Weather26.tar.gz\": {\n        \"sha256\": \"505776f18dd333dacc6c057440435dffa090c85e9ba0fdbc3c7ec49b63aa0536\",\n        \"size\": 134134191\n    },\n    \"VehicleTurningRoute_Town11_Route27242_Weather10.tar.gz\": {\n        \"sha256\": \"238daabc241fb20968a2a116dd9c7210974421d471000c597b310efd8aa16c6a\",\n        \"size\": 87139434\n    },\n    \"VehicleTurningRoute_Town11_Route27247_Weather15.tar.gz\": {\n        \"sha256\": \"8a8ec21f0eeffa1f10b9e086c01ba99d209722aebdb58bbf2762f557564ea48e\",\n        \"size\": 50740931\n    },\n    \"VehicleTurningRoute_Town11_Route27252_Weather22.tar.gz\": {\n        \"sha256\": \"b991b99f05ee6f31f962eae30d7cfb51fd3ecf0e320a9f68661c65ffa677ac90\",\n        \"size\": 41310864\n    },\n    \"VehicleTurningRoute_Town11_Route27257_Weather1.tar.gz\": {\n        \"sha256\": \"ad79743f482bbefff8ceb85cf42eeb54af293ff3aa95c3d1206206f76df0329e\",\n        \"size\": 62224072\n    },\n    \"VehicleTurningRoute_Town11_Route27262_Weather7.tar.gz\": {\n        \"sha256\": \"c765b3c4609399ae5e5c4d7eac8c4e33fee3dc7afea48183c627236fa2dd690d\",\n        \"size\": 89288141\n    },\n    \"VehicleTurningRoute_Town12_Route2144_Weather6.tar.gz\": {\n        \"sha256\": \"d94779e4399fc525ce81758e0604c4b6de566b42750913a4bce064f300a8a2db\",\n        \"size\": 186590737\n    },\n    \"VehicleTurningRoute_Town12_Route2145_Weather7.tar.gz\": {\n        \"sha256\": \"a9bd80d833a2b3f030986ae655b6470a1c1eac0c6dfb7b5b195b33d8c12e7f2c\",\n        \"size\": 98379076\n    },\n    \"VehicleTurningRoute_Town12_Route2146_Weather8.tar.gz\": {\n        \"sha256\": \"e2a202abf9e1f423f708cb9f85003f1e09c42560ca379eeee6e6f9fc0f7b417f\",\n        \"size\": 481030311\n    },\n    \"VehicleTurningRoute_Town12_Route2147_Weather9.tar.gz\": {\n        \"sha256\": \"6b898cd19d590068b77f518dcfb8a250dc74a1bb52bf6cc3b4b71582c2e5873c\",\n        \"size\": 256040782\n    },\n    \"VehicleTurningRoute_Town12_Route2148_Weather10.tar.gz\": {\n        \"sha256\": \"e0a4712b3cc7927768cc866791a108c87acafa5a38eb90b59b63650829f08db3\",\n        \"size\": 229060887\n    },\n    \"VehicleTurningRoute_Town12_Route2149_Weather11.tar.gz\": {\n        \"sha256\": \"90c1b0b6c4c0dc2a27375f686b153491b293790b9fadee54c785a2507b211e46\",\n        \"size\": 180318096\n    },\n    \"VehicleTurningRoute_Town12_Route2150_Weather12.tar.gz\": {\n        \"sha256\": \"a1e8fd5b20cfa004c7608914a3b105882dd50e1399bbe9a6a093f8144fc69b47\",\n        \"size\": 267464546\n    },\n    \"VehicleTurningRoute_Town12_Route2151_Weather13.tar.gz\": {\n        \"sha256\": \"2f1d39b8565a5da8fad9db2a90543215be5e6250990ea2506bb28366ab5e5c90\",\n        \"size\": 245707246\n    },\n    \"VehicleTurningRoute_Town12_Route2154_Weather8.tar.gz\": {\n        \"sha256\": \"f727a6360eecda3a757978316fd2833be6bbaf30f6538a69d830a27d14109662\",\n        \"size\": 245589116\n    },\n    \"VehicleTurningRoute_Town12_Route2156_Weather18.tar.gz\": {\n        \"sha256\": \"f3527ddd110b2cf430230fe175a271cc342efd00c2f203b5b7954200c0ac25cc\",\n        \"size\": 326505126\n    },\n    \"VehicleTurningRoute_Town12_Route2158_Weather20.tar.gz\": {\n        \"sha256\": \"01c4e321f5f6716df5ecf6c4c63cbb6baf7c0c8dc8d2c6e8ac4c1150a33f27f4\",\n        \"size\": 216510535\n    },\n    \"VehicleTurningRoute_Town12_Route2160_Weather22.tar.gz\": {\n        \"sha256\": \"51c84b1ca33dcdf8e8edc6f5e734c2f4465e86bebb7d3004cb9fc5bb5dde0a56\",\n        \"size\": 301120799\n    },\n    \"VehicleTurningRoute_Town12_Route2161_Weather23.tar.gz\": {\n        \"sha256\": \"2e49b8006de5b2d939096a3f7e9856c70f0254e5cc7f5e0b5a9e7ac24df2aad8\",\n        \"size\": 153147268\n    },\n    \"VehicleTurningRoute_Town12_Route2162_Weather23.tar.gz\": {\n        \"sha256\": \"e0f36d580539e741de07bb41d10df9011d00f9c0ceedf54ae78279c6af4e8e47\",\n        \"size\": 205528076\n    },\n    \"VehicleTurningRoute_Town12_Route2163_Weather25.tar.gz\": {\n        \"sha256\": \"8c0c1dacaa1e4681b492ba00638bd2dff2f170912a597a42241895f1065c96be\",\n        \"size\": 114342408\n    },\n    \"VehicleTurningRoute_Town12_Route2926_Weather8.tar.gz\": {\n        \"sha256\": \"7c906d6fe80f16fcb4b11d354c957dd1bd29a71f53164f49a59cac231cd8cb74\",\n        \"size\": 206845592\n    },\n    \"VehicleTurningRoute_Town12_Route2927_Weather9.tar.gz\": {\n        \"sha256\": \"fd47c93eec3642a038e9525b778f26f4986d659e017b0701c56fa11cd3a085c6\",\n        \"size\": 236256528\n    },\n    \"VehicleTurningRoute_Town12_Route2928_Weather10.tar.gz\": {\n        \"sha256\": \"a5cef33d2e754167fce9f9797bd0fc24d80201ba3ee560997832e790f4ec8f83\",\n        \"size\": 208670663\n    },\n    \"VehicleTurningRoute_Town12_Route2930_Weather12.tar.gz\": {\n        \"sha256\": \"069c6eb8e27d6e4428ea7f3c474348399c827f6da124b83e38de83cf4a757361\",\n        \"size\": 500771544\n    },\n    \"VehicleTurningRoute_Town12_Route2931_Weather13.tar.gz\": {\n        \"sha256\": \"a3a489ebf8568b8ce5a780e8c20e04833fd467f3bfeac21f950e2ae090420834\",\n        \"size\": 292355818\n    },\n    \"VehicleTurningRoute_Town12_Route2932_Weather14.tar.gz\": {\n        \"sha256\": \"34b65f6717f558ea046be6bc5c7eedab6b128617beb52b75ddd6bc023a2e3bb0\",\n        \"size\": 85418954\n    },\n    \"VehicleTurningRoute_Town12_Route2933_Weather15.tar.gz\": {\n        \"sha256\": \"81498b3d2649b1cd1f145266576a5995d46e92bfee773460a167a74a735e133b\",\n        \"size\": 290443369\n    },\n    \"VehicleTurningRoute_Town12_Route2934_Weather8.tar.gz\": {\n        \"sha256\": \"54d572889f99e12b75a77bab96068641855cc7583067ef09cd0cc5e8307bfa24\",\n        \"size\": 171502453\n    },\n    \"VehicleTurningRoute_Town12_Route2935_Weather9.tar.gz\": {\n        \"sha256\": \"70b54bcf4c015d058cf1947ff3c07d98b776296b19a85ef32fdf2313806c7385\",\n        \"size\": 697232522\n    },\n    \"VehicleTurningRoute_Town12_Route2936_Weather18.tar.gz\": {\n        \"sha256\": \"4bc9fe692690b065d2d70b48e3245cacc8a94b10ee869e9e14eae0eb2e57a89e\",\n        \"size\": 1008492709\n    },\n    \"VehicleTurningRoute_Town12_Route2938_Weather20.tar.gz\": {\n        \"sha256\": \"a4e9c6d391c7d29c661213c7fb9f7d46523d8c40f0af1a645b91736713d034cc\",\n        \"size\": 223718622\n    },\n    \"VehicleTurningRoute_Town12_Route2939_Weather21.tar.gz\": {\n        \"sha256\": \"c0bba99d13895749190dbb9660b7244f8c02535b4a63e419bfcf1c2f5515d30c\",\n        \"size\": 455972550\n    },\n    \"VehicleTurningRoute_Town12_Route2941_Weather23.tar.gz\": {\n        \"sha256\": \"05c3bc21365ce89fd87589a1d765176f7cfbc7a5e01beccbf11227e450db9cad\",\n        \"size\": 127779444\n    },\n    \"VehicleTurningRoute_Town12_Route2943_Weather25.tar.gz\": {\n        \"sha256\": \"420a54f601f6d2b0d06a256e6ff8394a3d8fc570964c83cf0ba98c877aadff3a\",\n        \"size\": 160109657\n    },\n    \"VehicleTurningRoute_Town12_Route9444_Weather9.tar.gz\": {\n        \"sha256\": \"a6f206c673889cc5192ffd86c8dc759cee00a6fefc9745a2f26968bcdd967c9b\",\n        \"size\": 369908162\n    },\n    \"VehicleTurningRoute_Town12_Route9462_Weather1.tar.gz\": {\n        \"sha256\": \"303e91cc25cee66a65df237d3329e5afa4683b5bea3c9ae0ec7319d23f64b725\",\n        \"size\": 183019189\n    },\n    \"VehicleTurningRoute_Town12_Route9498_Weather11.tar.gz\": {\n        \"sha256\": \"2923b0087add567c1ee47f1d64ad8dcb4f740e1a7584f6093ea7af44a18eb67d\",\n        \"size\": 317618008\n    },\n    \"VehicleTurningRoute_Town12_Route9507_Weather20.tar.gz\": {\n        \"sha256\": \"74d74089489f0cb02653da653060e689347fd8529bd0895215d74686c64c3b42\",\n        \"size\": 336107436\n    },\n    \"VehicleTurningRoute_Town12_Route9532_Weather19.tar.gz\": {\n        \"sha256\": \"8e11200f58115b24bd6a5471a9b55375ab06e32ff199e75fe66d6d90dabda9b7\",\n        \"size\": 174335519\n    },\n    \"VehicleTurningRoute_Town12_Route9539_Weather0.tar.gz\": {\n        \"sha256\": \"06e59554abdbed26984720b0321919f1cb09b8f6ce49593a9dfa699e9c5442d6\",\n        \"size\": 752545793\n    },\n    \"VehicleTurningRoute_Town12_Route9565_Weather0.tar.gz\": {\n        \"sha256\": \"a61eab54ae9ee2c9ed205adf85e8cb828fadf4d97081407e3cd075e17cfc6ef6\",\n        \"size\": 297263835\n    },\n    \"VehicleTurningRoute_Town12_Route9567_Weather2.tar.gz\": {\n        \"sha256\": \"088f861b4492df0821a4e82739cf7834b041a6fece4506033cba8dc6404209a9\",\n        \"size\": 408430639\n    },\n    \"VehicleTurningRoute_Town12_Route9576_Weather11.tar.gz\": {\n        \"sha256\": \"091de74a79965d86dc52ac9aa60eb049bbcb535699a22df2c429c41ab2f7bb62\",\n        \"size\": 304404438\n    },\n    \"VehicleTurningRoute_Town12_Route9589_Weather23.tar.gz\": {\n        \"sha256\": \"64b320b5c99a1cd43cd87c525f64be1a73cf1826855aa78cf6b54f3bb9df739b\",\n        \"size\": 271198534\n    },\n    \"VehicleTurningRoute_Town12_Route9591_Weather0.tar.gz\": {\n        \"sha256\": \"73a2fe9b3f702ab89315b44131e55c7d35045c62566af19d4dc8f696adbe8551\",\n        \"size\": 439014579\n    },\n    \"VehicleTurningRoute_Town12_Route9597_Weather6.tar.gz\": {\n        \"sha256\": \"724ce3838eaa365434d170f6f8dda5e3a0cf6c91f3b6e40d7bb32616beb8b990\",\n        \"size\": 86057484\n    },\n    \"VehicleTurningRoute_Town12_Route9599_Weather8.tar.gz\": {\n        \"sha256\": \"4ee52699da6c3fd5248871dc4b8f19d6760d2e4c2c6d1fb810f6debf25bf73c4\",\n        \"size\": 344028766\n    },\n    \"VehicleTurningRoute_Town12_Route9637_Weather20.tar.gz\": {\n        \"sha256\": \"51cfa1be7104c821254f2bbde3b7ff8d551cb70ca737c7a791aeb3c9890b752c\",\n        \"size\": 219034409\n    },\n    \"VehicleTurningRoute_Town12_Route9642_Weather25.tar.gz\": {\n        \"sha256\": \"0e61207bdd34edc5d5c0aec31e2320d8f636344f87cccbaac13945523ede0894\",\n        \"size\": 221788034\n    },\n    \"VehicleTurningRoute_Town12_Route9647_Weather3.tar.gz\": {\n        \"sha256\": \"fc1f2db4285957f3d608f654eae9aecd717e9d0a38b00a9a10efa8ce42bb301f\",\n        \"size\": 294349856\n    },\n    \"VehicleTurningRoute_Town12_Route9657_Weather14.tar.gz\": {\n        \"sha256\": \"42a3094fa48057d9f2ab18b1fa01176d95860d4beac1a727b03363c2ad23071e\",\n        \"size\": 226585347\n    },\n    \"VehicleTurningRoute_Town12_Route9661_Weather18.tar.gz\": {\n        \"sha256\": \"ab948ebb895cf8ff9f8c03946821eb91287d242d044f2ce2caa1e696b423d377\",\n        \"size\": 321508189\n    },\n    \"VehicleTurningRoute_Town12_Route9673_Weather3.tar.gz\": {\n        \"sha256\": \"87e14f263626c620426316b18b33b1b733b9208ecd9a93f66edaca073c4aa74f\",\n        \"size\": 212278541\n    },\n    \"VehicleTurningRoute_Town12_Route9686_Weather9.tar.gz\": {\n        \"sha256\": \"0d27d40561d03af6cef556052493639c2a3e9ba748bcf9b682280c0428013d2b\",\n        \"size\": 137120668\n    },\n    \"VehicleTurningRoute_Town12_Route9687_Weather18.tar.gz\": {\n        \"sha256\": \"8ea3ef193614da8440806ac33ed6782a84cfd3a2e9ff8c7ab1376bb434db6b49\",\n        \"size\": 313583034\n    },\n    \"VehicleTurningRoute_Town12_Route9691_Weather22.tar.gz\": {\n        \"sha256\": \"a3e70030a363979be7652b57f62746a06f2b8a1c33265abdb7d2574b23869ee4\",\n        \"size\": 207456612\n    },\n    \"VehicleTurningRoute_Town12_Route9703_Weather8.tar.gz\": {\n        \"sha256\": \"ab67fbd59d400230a21253f55cb23a30dc585680925416f1a0fe1c744d4f5748\",\n        \"size\": 801947006\n    },\n    \"VehicleTurningRoute_Town12_Route9708_Weather13.tar.gz\": {\n        \"sha256\": \"d4be83d9c5b506605cf50246d607d78df2a964cfcedaea45f217b796aafab650\",\n        \"size\": 366067711\n    },\n    \"VehicleTurningRoute_Town12_Route9723_Weather2.tar.gz\": {\n        \"sha256\": \"16e159be1c387da2c386331eff8f5a427d8c2c3bd13921f6b9b325e16acc992c\",\n        \"size\": 201494852\n    },\n    \"VehicleTurningRoute_Town12_Route9735_Weather14.tar.gz\": {\n        \"sha256\": \"7b0bd8abb08899976eb72eb136690b1009d90baefdfa1b98c0a605559575c500\",\n        \"size\": 337724429\n    },\n    \"VehicleTurningRoute_Town12_Route9749_Weather2.tar.gz\": {\n        \"sha256\": \"19cba10a194dfa65391b31fac9b263e2ab80ed06384bc8d7f7cd9cb8a6709121\",\n        \"size\": 144279932\n    },\n    \"VehicleTurningRoute_Town12_Route9759_Weather12.tar.gz\": {\n        \"sha256\": \"43c8714d7eca6836cdc255ee73faebb171bfda4f3246f97d473d888c3923817e\",\n        \"size\": 242846493\n    },\n    \"VehicleTurningRoute_Town12_Route9767_Weather20.tar.gz\": {\n        \"sha256\": \"78bda5a11bf98e401da09602220ca602f8793ebc7a3293d019af672df06d1901\",\n        \"size\": 190724834\n    },\n    \"VehicleTurningRoute_Town12_Route9791_Weather18.tar.gz\": {\n        \"sha256\": \"130e8b10ac8e472e81dec7d25060c3834096d962888b254eb2eaa511af43c291\",\n        \"size\": 297052093\n    },\n    \"VehicleTurningRoute_Town13_Route3703_Weather6.tar.gz\": {\n        \"sha256\": \"bd7da8ebe020bc63a72c66e194176fcc78216ca5dac9328d8c6a2a97ee5d0396\",\n        \"size\": 178534411\n    },\n    \"VehicleTurningRoute_Town13_Route3705_Weather8.tar.gz\": {\n        \"sha256\": \"c2bcba417a177ffd9314adfaedec69287e7a0d67b6836a03cd2d1af729db072b\",\n        \"size\": 175666081\n    },\n    \"VehicleTurningRoute_Town13_Route3706_Weather9.tar.gz\": {\n        \"sha256\": \"fe64450ddefbf683f5ac76f60cf4e42c17396260d09227914a987d68cec0562f\",\n        \"size\": 139165078\n    },\n    \"VehicleTurningRoute_Town13_Route3707_Weather10.tar.gz\": {\n        \"sha256\": \"dfd34c528f117f71f72865ab0d40c8d5d3da8c5fad12938a47769521a0b694f0\",\n        \"size\": 144366086\n    },\n    \"VehicleTurningRoute_Town13_Route3708_Weather11.tar.gz\": {\n        \"sha256\": \"7703b543639567381d67b5492788df5e4fe18caa68167da66e9612cec97c10d2\",\n        \"size\": 167160799\n    },\n    \"VehicleTurningRoute_Town13_Route3710_Weather13.tar.gz\": {\n        \"sha256\": \"5064fb8c2e3c704b9a958bd67380a944c25ef697e0f1778d312f4192302bdafa\",\n        \"size\": 221180254\n    },\n    \"VehicleTurningRoute_Town13_Route3711_Weather14.tar.gz\": {\n        \"sha256\": \"c6157586ba5f8f7ec32a5e3fbce860ab1139c515c7c00d7a89f921db5a411246\",\n        \"size\": 206090498\n    },\n    \"VehicleTurningRoute_Town13_Route3712_Weather15.tar.gz\": {\n        \"sha256\": \"995c0c8b20498bddf27b28006bc5573d58ea2013b9175f0de3a903f8d06ea017\",\n        \"size\": 180292402\n    },\n    \"VehicleTurningRoute_Town13_Route3714_Weather9.tar.gz\": {\n        \"sha256\": \"861f9a3fd05a71084d3f50f6107401590a5b554d761362763ac73af398c1e0e1\",\n        \"size\": 144721007\n    },\n    \"VehicleTurningRoute_Town13_Route3715_Weather18.tar.gz\": {\n        \"sha256\": \"fac13b2b2edc2228fbd0dfd41d140e60bd5756401c7f79cb22164010dea4a321\",\n        \"size\": 410267959\n    },\n    \"VehicleTurningRoute_Town13_Route3717_Weather20.tar.gz\": {\n        \"sha256\": \"7cf29e9fdd49c8119ef5d313226740d3e189a9fc39232f67cf1ee1f22184bd0a\",\n        \"size\": 157219423\n    },\n    \"VehicleTurningRoute_Town13_Route3719_Weather22.tar.gz\": {\n        \"sha256\": \"972164b3eb449ac4e84ba178f70d5c35fbcb2b876bb027c699c28c83edebe972\",\n        \"size\": 149118938\n    },\n    \"YieldToEmergencyVehicle_Town03_Route25378_Weather9.tar.gz\": {\n        \"sha256\": \"3f31c296f3ec814945d1cbd073886146bce57e9998aba016918e97f24baeef79\",\n        \"size\": 120084660\n    },\n    \"YieldToEmergencyVehicle_Town03_Route25427_Weather12.tar.gz\": {\n        \"sha256\": \"5df5dfa88ccbee1ccfa5fc46c12162e1eb31480714f64eeb87e08161d3d0dacd\",\n        \"size\": 153750874\n    },\n    \"YieldToEmergencyVehicle_Town12_Route1809_Weather9.tar.gz\": {\n        \"sha256\": \"fea0c6acf0e449bff163897f72f846d92a28869d08906a1db4e910082881475d\",\n        \"size\": 306700337\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20598_Weather5.tar.gz\": {\n        \"sha256\": \"cd38b6a21ee44a72cb6c9403ba21154a609b2af2e7e0f517c85f83642f5c6d7c\",\n        \"size\": 142366081\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20604_Weather11.tar.gz\": {\n        \"sha256\": \"10ed2f24ed4671310a6bd1cb9bff48b1a163c74e0fe3d43d488007d01e30d201\",\n        \"size\": 1079611986\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20606_Weather13.tar.gz\": {\n        \"sha256\": \"6727d652988c98ddc0cc625616ca0a0166d21e85fd9b8e0827b1c3c61104bcca\",\n        \"size\": 1102761740\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20614_Weather21.tar.gz\": {\n        \"sha256\": \"1787af85ed87e0bdc41e2634b05a0f6cb5be19476bced89bfe07f9c0ba779f37\",\n        \"size\": 229601175\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20623_Weather3.tar.gz\": {\n        \"sha256\": \"2a92b27b7786c7b97a7fff451613d17683495dcdeb6a15454946f3a54d057ae9\",\n        \"size\": 299865624\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20625_Weather6.tar.gz\": {\n        \"sha256\": \"03234d3557dfe9a8fc0297d6c60561b559cdd42901619812dfd7231f78d046f4\",\n        \"size\": 340296035\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20626_Weather7.tar.gz\": {\n        \"sha256\": \"189f95025ce78ce8e6b51e80e5909bf9324ca8a6926388fcb05d0b1956495234\",\n        \"size\": 249841207\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20629_Weather10.tar.gz\": {\n        \"sha256\": \"981098da3f5dd0cb792b3beee816d326380f552ca36ba29cdff8821354a9d158\",\n        \"size\": 231003962\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20639_Weather20.tar.gz\": {\n        \"sha256\": \"1de9e72121d1073d298565e52e8283c52471a4944b27d9d795ff03ee78e1acd3\",\n        \"size\": 252148715\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20641_Weather22.tar.gz\": {\n        \"sha256\": \"75dc643cad28c0b6e028318fef4c0492fec0681c03acf6be4770c950f9565691\",\n        \"size\": 1252658348\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20646_Weather1.tar.gz\": {\n        \"sha256\": \"30657ce98d5a1a784901564c85467d6191e34fcaa8ae527d00631236a335429a\",\n        \"size\": 423391376\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20647_Weather2.tar.gz\": {\n        \"sha256\": \"f23bc1f8d5b2d077d31e4160ac7084addbed6dac33db388cf75bfb36ee46bf6d\",\n        \"size\": 331905270\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20648_Weather3.tar.gz\": {\n        \"sha256\": \"7d2edee8b8a727abe691aa17689789a432229dbf53e793e8eb45d2e67ebc60e5\",\n        \"size\": 391970939\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20652_Weather7.tar.gz\": {\n        \"sha256\": \"1a9faf5f4b7cd94b3661d27b03a210d72f9b3feb6bad1b5081cd6d36629c43e5\",\n        \"size\": 463094073\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20654_Weather9.tar.gz\": {\n        \"sha256\": \"a9ec61867c21c2a9713c18d51f8e10ba5587d938e2810826387233bbcd97125c\",\n        \"size\": 234480762\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20662_Weather9.tar.gz\": {\n        \"sha256\": \"8306525d946f5b558724ddc73a697177829431038eebc3431a3cd9be5d854177\",\n        \"size\": 90932924\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20663_Weather18.tar.gz\": {\n        \"sha256\": \"e8a7d4bd30a4ca19704a76202a260985d83d621d73b4bbf64528f329ddc4988f\",\n        \"size\": 325637745\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20666_Weather21.tar.gz\": {\n        \"sha256\": \"59f5a9d0e927ecd4ce9a98e1e355e7b2f79ec51f45fcece88a576fd733c724cb\",\n        \"size\": 152741780\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20667_Weather22.tar.gz\": {\n        \"sha256\": \"8d336e9a333e272dac360435d9e05faecfe169b4e10b12284c63cedf969a4ea8\",\n        \"size\": 133493006\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20668_Weather23.tar.gz\": {\n        \"sha256\": \"e2a47eabfd1fe4d1745c767e70bb0cd3ae702ed03d46d87653851327f456ed8a\",\n        \"size\": 107407079\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20672_Weather1.tar.gz\": {\n        \"sha256\": \"aafc202de37e96f871061739b8040259c43a0752e331c409c1486ef55a755a85\",\n        \"size\": 291048636\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20674_Weather3.tar.gz\": {\n        \"sha256\": \"a219833af9e93bd60d089f1897602f5d1513a6c7d11ddd0fd2e833bbbc1d3638\",\n        \"size\": 294105084\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20679_Weather8.tar.gz\": {\n        \"sha256\": \"29cef0429503ea3691f75c0a300f20da4b14a37aa6a159bd549534f44c8da74d\",\n        \"size\": 343449024\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20681_Weather10.tar.gz\": {\n        \"sha256\": \"45c9060d38d182cf9e39033a49edd4578b356cc822a0a2898b47f3217c220c88\",\n        \"size\": 266703872\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20682_Weather11.tar.gz\": {\n        \"sha256\": \"8877b84667e7ec889c781d9bc0033ed3c7b8ae3c093ed50f3923fa75e482ed96\",\n        \"size\": 307582741\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20687_Weather8.tar.gz\": {\n        \"sha256\": \"35703fcc0e1ac2feab9b34e25dd1588d0ef72491c94e4ff9c4423f2cf900f7c4\",\n        \"size\": 250309755\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20691_Weather20.tar.gz\": {\n        \"sha256\": \"5434797e1fe1657673b23db03b6b4b8baa63ce1cadece929a4178f00a061b6c7\",\n        \"size\": 323921121\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20694_Weather23.tar.gz\": {\n        \"sha256\": \"3684bb2ed7d0910cc70fb98c2c991aa263463e701bf103324797b97944659bf6\",\n        \"size\": 356874081\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20698_Weather1.tar.gz\": {\n        \"sha256\": \"8e670b752c56b23c4d0c994f8aff00314b01b9706b22b5becc25f40cf9b1303f\",\n        \"size\": 1452283507\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20701_Weather3.tar.gz\": {\n        \"sha256\": \"5be2af4cbcb500a3578280e81fc5ae8fc3a60045a8895f7e914deee65629129a\",\n        \"size\": 447402851\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20703_Weather6.tar.gz\": {\n        \"sha256\": \"98f638a1802e1996da14b1cc9f5a17ded361465c8840ca4f1f082130f831806a\",\n        \"size\": 1239384353\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20705_Weather8.tar.gz\": {\n        \"sha256\": \"5f098bee7a171baec27a474101b1a7fdd56728a9d482ecbbaea70225bdbcaac4\",\n        \"size\": 1144181101\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20708_Weather11.tar.gz\": {\n        \"sha256\": \"bba672c134f70ef444a8ebee3925032c533eaa6dd4f1a66553e66d38c3f24a95\",\n        \"size\": 1130215317\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20718_Weather21.tar.gz\": {\n        \"sha256\": \"ab89b2e330b2c2adf19297d42ce993a76ebcf547bb7bffcc8ca4dccba3a49130\",\n        \"size\": 515326147\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20720_Weather23.tar.gz\": {\n        \"sha256\": \"6e715339dc51f19de04c70a0a69027aa784c56bc0f5d00a7bbf5f267a899e6e6\",\n        \"size\": 252118664\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20726_Weather3.tar.gz\": {\n        \"sha256\": \"3eefb1cea5c94fa55e40b1527d621dae6e31002686668410ac1053f14b0be7ff\",\n        \"size\": 487284620\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20727_Weather3.tar.gz\": {\n        \"sha256\": \"a13cdf49fa12c2a995395b44ac24717adbb03845418138e5f81408c08fdcdcc4\",\n        \"size\": 372118359\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20728_Weather5.tar.gz\": {\n        \"sha256\": \"348df08df610ac78d9d41bdd68d504148813f40a5d01de27b63db53984eb9d06\",\n        \"size\": 363142003\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20729_Weather6.tar.gz\": {\n        \"sha256\": \"6e9bb4d06234535f82f21b3b77ff59d83b9d5a03da090490885e786cd785d33a\",\n        \"size\": 348350205\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20733_Weather10.tar.gz\": {\n        \"sha256\": \"5e01b8a8b8d5c811a338bf9e602edf7e17996b25344d1f171fabb079e7d4b612\",\n        \"size\": 213462669\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20734_Weather11.tar.gz\": {\n        \"sha256\": \"3e78b1bf2dba56fa6f29df178be23ff00a8d3ed8615533cb3de74587aa890233\",\n        \"size\": 120875413\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20740_Weather9.tar.gz\": {\n        \"sha256\": \"5e66272c392d6f8883434a139589c94a08220991f10c284915ff56f0de5847e3\",\n        \"size\": 321198954\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20745_Weather22.tar.gz\": {\n        \"sha256\": \"510bbd7c2084822c31c06872ca1c2a8e26ec2590a5abd060df7670819fb4a6bc\",\n        \"size\": 287548418\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20750_Weather1.tar.gz\": {\n        \"sha256\": \"acaf47f6e1fbfb0ac3910bb43ff58a47686997c64643409e2e34ca69fec574f8\",\n        \"size\": 423830712\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20751_Weather2.tar.gz\": {\n        \"sha256\": \"bd4c4c34733daa43f35deeb6beb643f632c456e5e313674dc92f00a54b3a210a\",\n        \"size\": 117925381\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20755_Weather6.tar.gz\": {\n        \"sha256\": \"1e8b18a45f823013472bbf7f0b7fb97ec9614cd4eeecbd109e66e527a23bc91e\",\n        \"size\": 257237803\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20762_Weather13.tar.gz\": {\n        \"sha256\": \"871698ed624b201077ab08bdaf0fb50d6244a0fcdb0ad341b6c4d7cccfd77316\",\n        \"size\": 1008371965\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20766_Weather9.tar.gz\": {\n        \"sha256\": \"b73c14632f3bff54b9bc07bb63627316bd6949f75f40f5810f12d34334b1f368\",\n        \"size\": 958607834\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20768_Weather19.tar.gz\": {\n        \"sha256\": \"b8e0468f8d55982f6ac23266bf82bc9bfcff55d84f48719fab83133c7f3ed8c3\",\n        \"size\": 316554713\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20769_Weather20.tar.gz\": {\n        \"sha256\": \"3b68e76d80fa1e02aef079ddb9023eb1b168bf6e6d4a4f7c66662cb731ad520e\",\n        \"size\": 1356592457\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20773_Weather23.tar.gz\": {\n        \"sha256\": \"4c4ee954add22809af8d48301b6380a808fa914887cf83c54e7bbb0f344a50c2\",\n        \"size\": 279998315\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20774_Weather25.tar.gz\": {\n        \"sha256\": \"4a36e522f02f046c1e8c610e2dee7c912251a7a731cdc38c28b810991523eea9\",\n        \"size\": 250563522\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20775_Weather0.tar.gz\": {\n        \"sha256\": \"37b6b55c42776ffd9a441950b1da996092af6e62dea996c251e02614b7e89d4a\",\n        \"size\": 123119705\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20777_Weather2.tar.gz\": {\n        \"sha256\": \"8f2189620dcf322e4e5b53c1a8ecd9f390bd82a1bc834cfc516fddb2d91caf9f\",\n        \"size\": 441778692\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20778_Weather3.tar.gz\": {\n        \"sha256\": \"86369696eca2638a19212b8f54594579e0fb8ce934dfac256d2d4c0342c106b9\",\n        \"size\": 258638700\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20785_Weather10.tar.gz\": {\n        \"sha256\": \"76ba2c489dd7cd163fab0a07e6da3a15276c7b7fd20a48cb61bc1bc30e32a9e8\",\n        \"size\": 139757232\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20791_Weather8.tar.gz\": {\n        \"sha256\": \"7a71b4c6c17c5fa30320d6bfdd55597457b82bde58b41e6685a27a23419f3056\",\n        \"size\": 377679021\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20793_Weather18.tar.gz\": {\n        \"sha256\": \"8dd55b11a3f863beffbe342fdb33e55bb5f0ac212e3a782997fa81a67da83335\",\n        \"size\": 244568487\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20796_Weather21.tar.gz\": {\n        \"sha256\": \"21803eb8fedbc26fd4c8d73bd378af655faba520235e8dd870888c5dc6970ff9\",\n        \"size\": 1396251953\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20802_Weather1.tar.gz\": {\n        \"sha256\": \"c8cf1f0c8689e17bc035463ebee0c6701b5e8a14f9e6b3b778c46de44c52817a\",\n        \"size\": 140552801\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20806_Weather5.tar.gz\": {\n        \"sha256\": \"9c646bc6b92eba0610ea93b8aeb43291b8cc37466285b63061fd8bdc88be166c\",\n        \"size\": 1440956037\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20811_Weather10.tar.gz\": {\n        \"sha256\": \"0af5713b364441ca6196d802bd77187ed02acd72b988f6315e4c272e26fb9437\",\n        \"size\": 581589381\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20815_Weather14.tar.gz\": {\n        \"sha256\": \"824f642cf2f6f23a1be5607fc1bff0d899fd08b58ea3bc63ffccedf98b09a3a1\",\n        \"size\": 104041353\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20826_Weather25.tar.gz\": {\n        \"sha256\": \"255c67027b7ba5e521f84e186c34140bb8e69aed7d8acd698ae14f9067551501\",\n        \"size\": 319354712\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20828_Weather1.tar.gz\": {\n        \"sha256\": \"25ae46a9ac3cc746cf1d6c1f9c8a252c36973982b11de4ec9ad242cae07a78b1\",\n        \"size\": 216286549\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20830_Weather3.tar.gz\": {\n        \"sha256\": \"385023cae91ad22651ad58f1c026a0f6a79c8d6c174b6994269eda3faf4efb04\",\n        \"size\": 390777950\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20832_Weather5.tar.gz\": {\n        \"sha256\": \"e9e04c0aa170140f69378c2ea71f26f69c6d6bb86e888e50c4ee6b838a38d60f\",\n        \"size\": 237304708\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20836_Weather9.tar.gz\": {\n        \"sha256\": \"491c0e694f1dfc104924c585b5187970bb636ebab762ba69ad4a7ac007de982f\",\n        \"size\": 122687079\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20840_Weather13.tar.gz\": {\n        \"sha256\": \"d51c04e0557ac425100a8f8ae168205aa989b5417fa59f55b7fc287f346fad30\",\n        \"size\": 258503680\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20843_Weather8.tar.gz\": {\n        \"sha256\": \"016312a3ff3886313b0eb83ad34f3db726dd0712e833e64db7d45628f6bffe54\",\n        \"size\": 351504705\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20854_Weather1.tar.gz\": {\n        \"sha256\": \"88cd117ce4e70512e0aeeaba511eb80c62f54850ffe9cffca194950aff5221f7\",\n        \"size\": 363812225\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20855_Weather2.tar.gz\": {\n        \"sha256\": \"957caa6aaee5853f263f3c82f8f48f3e7a5a1c3f718cd45a649a0b0a8a1269c7\",\n        \"size\": 690506193\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20860_Weather7.tar.gz\": {\n        \"sha256\": \"057e374e43ca6cc533e9feafab570dd5bab564d919e33c22c0c6eeaafb2a7636\",\n        \"size\": 239925061\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20862_Weather9.tar.gz\": {\n        \"sha256\": \"e240fdd510c8b3fa59452b52e6875d398be3fe4b7d44376fe5e418cf2add124a\",\n        \"size\": 202299686\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20865_Weather12.tar.gz\": {\n        \"sha256\": \"9a4523de9c9265f30ab50aecfd3fc3e48499d787024b5538792a1a726d35762c\",\n        \"size\": 419658950\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20866_Weather13.tar.gz\": {\n        \"sha256\": \"af52f511c8b8c494b74cc501e09116aa3bc8872b4c479950d83e1a838f2a2ace\",\n        \"size\": 812089285\n    },\n    \"YieldToEmergencyVehicle_Town12_Route20867_Weather14.tar.gz\": {\n        \"sha256\": \"d83128b507a53c9e50f9b772c0befc18cef39e047c06af78391106497e25bf48\",\n        \"size\": 624978200\n    },\n    \"YieldToEmergencyVehicle_Town12_Route2587_Weather7.tar.gz\": {\n        \"sha256\": \"98fab75f891848a72b7c8f4fc19e760098483803d055491272d285629a7d8886\",\n        \"size\": 188164334\n    },\n    \"YieldToEmergencyVehicle_Town12_Route2599_Weather19.tar.gz\": {\n        \"sha256\": \"ce9854b540f6d2a9ba8a7a8702654d2e35b4c7ea9b0f665ccb452851e05157af\",\n        \"size\": 195756282\n    },\n    \"YieldToEmergencyVehicle_Town13_Route3366_Weather7.tar.gz\": {\n        \"sha256\": \"64cac8d916ffcd22c83fc664638aa351c64c5fe2225d4a348e6834dedf01bdbf\",\n        \"size\": 421995463\n    },\n    \"YieldToEmergencyVehicle_Town13_Route3368_Weather9.tar.gz\": {\n        \"sha256\": \"d03906eba79502e65ae2445711647bb0501e24c8c01e1555076506fb41ce07f9\",\n        \"size\": 169880405\n    },\n    \"YieldToEmergencyVehicle_Town13_Route3371_Weather12.tar.gz\": {\n        \"sha256\": \"f27a2011e5c9fdc53b7607b7048e4baa3e61969bfce4a1cd3b5f46a23b050775\",\n        \"size\": 716244029\n    },\n    \"AccidentTwoWays_Town13_Route1002_Weather14.tar.gz\": {\n        \"sha256\": \"4d9f0897cfe69916e27eb4da6907a1d5e1fb84ae6514c0c6c365eed2711067e2\",\n        \"size\": 310351951\n    },\n    \"AccidentTwoWays_Town13_Route1021_Weather10.tar.gz\": {\n        \"sha256\": \"0bf091073e5499c2584320836a8854ac535e21b2d3f34002c21b30a226e332ef\",\n        \"size\": 383257195\n    },\n    \"AccidentTwoWays_Town13_Route1023_Weather12.tar.gz\": {\n        \"sha256\": \"9217cd6160bb081e8ee5ed03bb0477a08259f036ed1c00a647853592bee5bfb8\",\n        \"size\": 253090661\n    },\n    \"AccidentTwoWays_Town13_Route1036_Weather1.tar.gz\": {\n        \"sha256\": \"c01bba2f49f196f5cd5aa772f2c533a367eb29245fd5df1fe6b1ca5b41cca758\",\n        \"size\": 455863928\n    },\n    \"AccidentTwoWays_Town13_Route1039_Weather5.tar.gz\": {\n        \"sha256\": \"5837f4d0d70af25fb405b21ec536002c7f871e59342145cc2cafb73f7c26fc14\",\n        \"size\": 366916639\n    },\n    \"AccidentTwoWays_Town13_Route1069_Weather12.tar.gz\": {\n        \"sha256\": \"0bbc249a9f09853a483624b2a26de2e235b8f8d7b10afd07f3dfdc9c76315466\",\n        \"size\": 300680154\n    },\n    \"AccidentTwoWays_Town13_Route1079_Weather25.tar.gz\": {\n        \"sha256\": \"89acb230a4e6055b50c46e19e57ccd97a8cff88a860d60c86b634abc5443bad8\",\n        \"size\": 245170071\n    },\n    \"AccidentTwoWays_Town13_Route1081_Weather0.tar.gz\": {\n        \"sha256\": \"a103850f5c6d07ab4a6b816b9d00a75ccc71cdb8993175f780b56ecfb7574aca\",\n        \"size\": 437471759\n    },\n    \"AccidentTwoWays_Town13_Route1088_Weather8.tar.gz\": {\n        \"sha256\": \"838569ff5f252cda2bc3c29353943b43e57675a27512b5643b7adf1c5e80103d\",\n        \"size\": 896122580\n    },\n    \"AccidentTwoWays_Town13_Route1101_Weather23.tar.gz\": {\n        \"sha256\": \"7674911d24147c077e655b97da2779fde73ef7834d0e01415e15b6e296a13c92\",\n        \"size\": 303004544\n    },\n    \"AccidentTwoWays_Town13_Route1125_Weather25.tar.gz\": {\n        \"sha256\": \"e972099d7d7164d29e09e66c77ce1dee07d8f73ace95b5b696b1000c23674284\",\n        \"size\": 251516156\n    },\n    \"AccidentTwoWays_Town13_Route1149_Weather26.tar.gz\": {\n        \"sha256\": \"0586abe64ab46361e6ea93b9f9d47ff23689f73edcd80fe8b5dabe01bd20f366\",\n        \"size\": 477219180\n    },\n    \"AccidentTwoWays_Town13_Route1160_Weather11.tar.gz\": {\n        \"sha256\": \"ae021365cf1b19df91fc530c8843d0304e66b4663e79995e05323a41ddfc84ca\",\n        \"size\": 242505307\n    },\n    \"AccidentTwoWays_Town13_Route1177_Weather5.tar.gz\": {\n        \"sha256\": \"be48e5d6e22b7fbbe1294338198ec4a52c5bb5f25c91f30796bf6e0c803dd5d0\",\n        \"size\": 720431867\n    },\n    \"AccidentTwoWays_Town13_Route1179_Weather7.tar.gz\": {\n        \"sha256\": \"ad93e84d2d3612190310e47d2f2ce629be1845fcb499411cc5de60dd4591408a\",\n        \"size\": 395916156\n    },\n    \"AccidentTwoWays_Town13_Route1180_Weather8.tar.gz\": {\n        \"sha256\": \"3c5ff7e6473686221761e79c9d9e2aa32ff8263bfe57c596593597bb182b0acb\",\n        \"size\": 490317232\n    },\n    \"AccidentTwoWays_Town13_Route1185_Weather13.tar.gz\": {\n        \"sha256\": \"84faf266d67754f609ef3aefb28823c5ce1a5f4ed5011eef267642afce0dad94\",\n        \"size\": 732193686\n    },\n    \"AccidentTwoWays_Town13_Route1187_Weather15.tar.gz\": {\n        \"sha256\": \"1e564988636546b5121cab48aaca4383a5a68d5e730a3da3b6a63ea1280ffc6d\",\n        \"size\": 297955430\n    },\n    \"AccidentTwoWays_Town13_Route1188_Weather18.tar.gz\": {\n        \"sha256\": \"2b04063e7b391ce4c6caf243fd3ed864c158a095a67d681bcfbbb2b7b7b7f987\",\n        \"size\": 909348084\n    },\n    \"AccidentTwoWays_Town13_Route1189_Weather19.tar.gz\": {\n        \"sha256\": \"a71bcbffd552ea863d975bba887f1f8ee048f34c7283c7d021bc08f9286b8c6c\",\n        \"size\": 374914257\n    },\n    \"AccidentTwoWays_Town13_Route1191_Weather21.tar.gz\": {\n        \"sha256\": \"a40a7078f796ef76130e1cb6a6cc24ad635ff8be43bbae80c4af889f4916bddd\",\n        \"size\": 381335644\n    },\n    \"AccidentTwoWays_Town13_Route1193_Weather23.tar.gz\": {\n        \"sha256\": \"b17961b309e992f2f28d91ac51cd59758b3e32048b78f676b2a267fbea1d0ddc\",\n        \"size\": 597927346\n    },\n    \"AccidentTwoWays_Town13_Route1194_Weather25.tar.gz\": {\n        \"sha256\": \"b432e8a02f7e4bc53a38a1cca9a3e17fde7b5e6bda458decb3df9d2870af2e92\",\n        \"size\": 253822572\n    },\n    \"AccidentTwoWays_Town13_Route1195_Weather26.tar.gz\": {\n        \"sha256\": \"b7b51e47fd3ef373d58619aaab14114578f6386a418da2cba0ee9c6b746993f2\",\n        \"size\": 453013316\n    },\n    \"AccidentTwoWays_Town13_Route1205_Weather10.tar.gz\": {\n        \"sha256\": \"53b083995cf0e6e202cb325bf410a77154bceed808ba962df92837650403b4a3\",\n        \"size\": 501456824\n    },\n    \"AccidentTwoWays_Town13_Route1207_Weather12.tar.gz\": {\n        \"sha256\": \"ba5584d7e9f2142cf50dc33ad28d80a87f948d28956418125017b26f80bccdbf\",\n        \"size\": 945862343\n    },\n    \"AccidentTwoWays_Town13_Route1214_Weather21.tar.gz\": {\n        \"sha256\": \"fd728a44dd1267e5351d8cb73fc45c1009c06c875ac3cce6d17fa171e92540ba\",\n        \"size\": 288591808\n    },\n    \"AccidentTwoWays_Town13_Route1217_Weather25.tar.gz\": {\n        \"sha256\": \"88df4f4a3505304a49361b506da6cf45cf2051355fb3246d8a169b47ff7ae769\",\n        \"size\": 252646330\n    },\n    \"AccidentTwoWays_Town13_Route1219_Weather0.tar.gz\": {\n        \"sha256\": \"e647721c29aa12a03183e93f45e46ab5bb3c19b467b50d35ee83df5a81350040\",\n        \"size\": 450915952\n    },\n    \"AccidentTwoWays_Town13_Route1220_Weather1.tar.gz\": {\n        \"sha256\": \"4f7e9e978cf027651baa94fe692541e6446a2a01ad76a5f70fc977478d34050a\",\n        \"size\": 410747943\n    },\n    \"AccidentTwoWays_Town13_Route1221_Weather2.tar.gz\": {\n        \"sha256\": \"f17c18f1ebee9e1b9abef21a53d15c2710a5ec3d69eccc5eea588cf2b0be7cf0\",\n        \"size\": 371865384\n    },\n    \"AccidentTwoWays_Town13_Route1222_Weather3.tar.gz\": {\n        \"sha256\": \"01b2c6b99872d4082083550b3e250550de4a0630746fd42c5f46cc896fcff7d2\",\n        \"size\": 810337252\n    },\n    \"AccidentTwoWays_Town13_Route1223_Weather5.tar.gz\": {\n        \"sha256\": \"6c18a4f373e8201f5cae3709a418e458224fb7f46069e85c34ba57de48958a9d\",\n        \"size\": 554564932\n    },\n    \"AccidentTwoWays_Town13_Route1229_Weather11.tar.gz\": {\n        \"sha256\": \"28e8c9c4b182806f1757b539cfebce635088e7c51fac23b3d1fbfa353e1c8f38\",\n        \"size\": 309057159\n    },\n    \"AccidentTwoWays_Town13_Route1232_Weather14.tar.gz\": {\n        \"sha256\": \"7c6c8176da360721d16bb98cf3aefb4e1a2db25cc3dbf0ce4e3bffd791b59bf5\",\n        \"size\": 661891352\n    },\n    \"AccidentTwoWays_Town13_Route1233_Weather15.tar.gz\": {\n        \"sha256\": \"ed1413728779cd2d7bd80fa41cd461c33c3426c8cdb98506ccc8ab32a0d5198e\",\n        \"size\": 476157717\n    },\n    \"AccidentTwoWays_Town13_Route1234_Weather18.tar.gz\": {\n        \"sha256\": \"14aebfa9fcf83d066aac111ac6af0d095aeaa7da20813830c7bdd3a119b97bdb\",\n        \"size\": 357074214\n    },\n    \"AccidentTwoWays_Town13_Route1239_Weather23.tar.gz\": {\n        \"sha256\": \"1e98b1ba75948679c3351c8a643a806056f92c565ce542f7100b0fe24542481e\",\n        \"size\": 287610434\n    },\n    \"AccidentTwoWays_Town13_Route1240_Weather25.tar.gz\": {\n        \"sha256\": \"e4832fb931eb53c4f5f8c993a37cce1e0985b15b9332a1dd389241a9a3c6844c\",\n        \"size\": 315166060\n    },\n    \"AccidentTwoWays_Town13_Route1241_Weather26.tar.gz\": {\n        \"sha256\": \"74c82a148665cbec4903fee41bf4f1e051971e4b22c698ea580b8bf23e477c84\",\n        \"size\": 389253083\n    },\n    \"AccidentTwoWays_Town13_Route1242_Weather0.tar.gz\": {\n        \"sha256\": \"dee93dbe186f788f7ddc4516569e996c6a34297e6f7a170c3529381016f45d7c\",\n        \"size\": 922760844\n    },\n    \"AccidentTwoWays_Town13_Route1247_Weather6.tar.gz\": {\n        \"sha256\": \"1ec7dbad4a7a8b7c2c531a94adc162a57882c74ad41f90414415663678d9db8a\",\n        \"size\": 426174728\n    },\n    \"AccidentTwoWays_Town13_Route1248_Weather7.tar.gz\": {\n        \"sha256\": \"3037c6cb5f48f88e2466f5ef54a6175cdce10754cea10ef15214ab3356673633\",\n        \"size\": 357975834\n    },\n    \"AccidentTwoWays_Town13_Route1249_Weather8.tar.gz\": {\n        \"sha256\": \"b2c05e837d1239f0e035ae90973683cc15fd024e48f7fec29e862af5b2b4c4f8\",\n        \"size\": 327332516\n    },\n    \"AccidentTwoWays_Town13_Route1252_Weather11.tar.gz\": {\n        \"sha256\": \"be7981f1513772d7cd9663538255339774b6839320eee9ebf0103cc0d4d01d3d\",\n        \"size\": 254664633\n    },\n    \"AccidentTwoWays_Town13_Route1257_Weather18.tar.gz\": {\n        \"sha256\": \"ffbc792e88f440c6fb60302248ec59fde980a339720400c1b973be10486eedac\",\n        \"size\": 370067055\n    },\n    \"AccidentTwoWays_Town13_Route1260_Weather21.tar.gz\": {\n        \"sha256\": \"813c24c9582512811258cef8cd8ca189fbdb4079c3b80c30d261c88860c2d2c0\",\n        \"size\": 311426870\n    },\n    \"AccidentTwoWays_Town13_Route1261_Weather22.tar.gz\": {\n        \"sha256\": \"119c7f1fd59b57a78d273a348c8ee880787df2862a662024a399b02652c2926d\",\n        \"size\": 369702165\n    },\n    \"AccidentTwoWays_Town13_Route1263_Weather25.tar.gz\": {\n        \"sha256\": \"87b97ac26a3188421f29cf403be6e742fcf3df3bd68b8894fc52440ed8463c7d\",\n        \"size\": 258448990\n    },\n    \"AccidentTwoWays_Town13_Route1265_Weather0.tar.gz\": {\n        \"sha256\": \"1fb6224e3cc9642c7b34c54a1ad75cc5e7bceeb26d36fb526c17726004dc449f\",\n        \"size\": 403383363\n    },\n    \"AccidentTwoWays_Town13_Route1267_Weather2.tar.gz\": {\n        \"sha256\": \"09c11d86821ddf75f8bdf021121ba803b93a4143aee2b3c076646ea69aac3023\",\n        \"size\": 352106604\n    },\n    \"AccidentTwoWays_Town13_Route1268_Weather3.tar.gz\": {\n        \"sha256\": \"783691309a61fac2cbaf2d16ea36c64adea1b5c9ef938640ee269beb56282b85\",\n        \"size\": 357194748\n    },\n    \"AccidentTwoWays_Town13_Route1269_Weather5.tar.gz\": {\n        \"sha256\": \"83c5fb7e6f7a89469cdb30024f7fc2a8a8e07f3d9aba20d0c4fecd24a2d87b13\",\n        \"size\": 326157908\n    },\n    \"AccidentTwoWays_Town13_Route1270_Weather6.tar.gz\": {\n        \"sha256\": \"f114c7454c3714d3deefbabca8e75800efc5f7c5ef104f14d47fb2750e4545c6\",\n        \"size\": 366149676\n    },\n    \"AccidentTwoWays_Town13_Route1272_Weather8.tar.gz\": {\n        \"sha256\": \"f0a2e93733b2c9a8ddfdcc57565035cff1677e5304d064b667b7b14b99e8d655\",\n        \"size\": 420499311\n    },\n    \"AccidentTwoWays_Town13_Route1275_Weather11.tar.gz\": {\n        \"sha256\": \"0edbe163ee208d2b8b5619c63e495f3b3b18b1bdfe38a58c75e836b893e74943\",\n        \"size\": 317353806\n    },\n    \"AccidentTwoWays_Town13_Route1282_Weather20.tar.gz\": {\n        \"sha256\": \"53dbfe4018c36d938b61a1b5dcad1a7561407677a4ab1f8d41bce0b275d5006e\",\n        \"size\": 347564279\n    },\n    \"AccidentTwoWays_Town13_Route1287_Weather26.tar.gz\": {\n        \"sha256\": \"3e427f86fff27bf95d78c48d8c2c23c2463dea5d688bbda9e4fb749e346479cb\",\n        \"size\": 445103625\n    },\n    \"AccidentTwoWays_Town13_Route1289_Weather1.tar.gz\": {\n        \"sha256\": \"212314b0a3013d1dfb50723a95f5f108cdbc84ab15a3b5de346a7381a3f89e5c\",\n        \"size\": 446239886\n    },\n    \"AccidentTwoWays_Town13_Route1294_Weather7.tar.gz\": {\n        \"sha256\": \"58379f8022500b0fef448f5c0bad75b169fff5fb8aa2747c0d9feebbc32e713a\",\n        \"size\": 404022987\n    },\n    \"AccidentTwoWays_Town13_Route1297_Weather10.tar.gz\": {\n        \"sha256\": \"464358cc56d413125bc9828467b83a22cdb0de770957e2fc030435c15345c62d\",\n        \"size\": 521572464\n    },\n    \"AccidentTwoWays_Town13_Route1298_Weather11.tar.gz\": {\n        \"sha256\": \"e836b1973526cff333f41a997e6323e01814fc14ac138c6565bb343ad088b13e\",\n        \"size\": 264074769\n    },\n    \"AccidentTwoWays_Town13_Route1299_Weather12.tar.gz\": {\n        \"sha256\": \"774f9d3c89f9e549fed9d5cad71777023f2325d5cbdef24b24138d47dfae1d01\",\n        \"size\": 248381786\n    },\n    \"AccidentTwoWays_Town13_Route1306_Weather21.tar.gz\": {\n        \"sha256\": \"5b942acc29404f921eb3e9f5c7787a3ea23e836e2ba724e5987c2b4b74340001\",\n        \"size\": 292493978\n    },\n    \"AccidentTwoWays_Town13_Route1323_Weather13.tar.gz\": {\n        \"sha256\": \"8af5bc9db4ddd932aa3a05771edd58d4fe0a92a16be22fe5415e3b072b38d96f\",\n        \"size\": 259780820\n    },\n    \"AccidentTwoWays_Town13_Route1325_Weather15.tar.gz\": {\n        \"sha256\": \"e8413d7f0679707b8519d86c349c41fecc85f085d2442276bd64094ac1b00b17\",\n        \"size\": 605827373\n    },\n    \"AccidentTwoWays_Town13_Route1329_Weather21.tar.gz\": {\n        \"sha256\": \"b3494fc6492f9c17ab25eb62134ec71b462e1377ff2789c8008505de0d78d51c\",\n        \"size\": 408396151\n    },\n    \"AccidentTwoWays_Town13_Route1330_Weather22.tar.gz\": {\n        \"sha256\": \"dc023a4dee48fab673b85aab992256e266d3e47fbab7b441d390dd33d337994f\",\n        \"size\": 324470502\n    },\n    \"AccidentTwoWays_Town13_Route1354_Weather23.tar.gz\": {\n        \"sha256\": \"1c04e61e183d525bf3eaf9cb96dac982a2225e3aa3c66a9ec0757c592dd84455\",\n        \"size\": 269697745\n    },\n    \"AccidentTwoWays_Town13_Route1360_Weather3.tar.gz\": {\n        \"sha256\": \"8419cce8e2312a6cf40be39ddb93934f290dfd720c665cce58c4e00f097d4947\",\n        \"size\": 346072804\n    },\n    \"AccidentTwoWays_Town13_Route1373_Weather19.tar.gz\": {\n        \"sha256\": \"9447397dfa38a324e7e229059a1da32fdd7853bbca5947cfc9af48e413d60fd7\",\n        \"size\": 526922266\n    },\n    \"AccidentTwoWays_Town13_Route1383_Weather3.tar.gz\": {\n        \"sha256\": \"9730139124e6b28bcc792acc2c8e3db669e4823c34b218a09f0f177c952402cf\",\n        \"size\": 406286094\n    },\n    \"AccidentTwoWays_Town13_Route1384_Weather5.tar.gz\": {\n        \"sha256\": \"466a32b5bdb6d06ae7cec9684b6de7cda215f29362f439f3e074080b0fb08eda\",\n        \"size\": 400706253\n    },\n    \"AccidentTwoWays_Town13_Route1385_Weather6.tar.gz\": {\n        \"sha256\": \"0d020ba520989f67da27bb3c2ccd2299d276d970fd72cf8641f63bf5ec014527\",\n        \"size\": 364859590\n    },\n    \"AccidentTwoWays_Town13_Route1386_Weather7.tar.gz\": {\n        \"sha256\": \"f5b57d051ce5e1e31d13667fdedece1d6159367a874f29513248c078d6b4ee08\",\n        \"size\": 400166787\n    },\n    \"AccidentTwoWays_Town13_Route30350_Weather26.tar.gz\": {\n        \"sha256\": \"fae87519a4cbeb7029b6109af24be23d346f198934c9d4d6ef2b66455a45f8ad\",\n        \"size\": 424320019\n    },\n    \"AccidentTwoWays_Town13_Route30351_Weather0.tar.gz\": {\n        \"sha256\": \"236be9554874e5d9724b01d7506001b825481e0d7d6be8b5c80134080b31c8ac\",\n        \"size\": 389893533\n    },\n    \"AccidentTwoWays_Town13_Route30352_Weather1.tar.gz\": {\n        \"sha256\": \"a422e213fbd77b78ef098cfd0e4156a15d1d5510848bb1a06a7ab0d3374d24c8\",\n        \"size\": 343905088\n    },\n    \"AccidentTwoWays_Town13_Route30354_Weather3.tar.gz\": {\n        \"sha256\": \"41ae3832ec4519e3773bf1e80cc94a3b13131866549b14f57ecc7a27e2f891ec\",\n        \"size\": 392203524\n    },\n    \"AccidentTwoWays_Town13_Route30355_Weather5.tar.gz\": {\n        \"sha256\": \"bf165892beeb7bd7c155916f5f477ace655a5f5778cb98e442297940ff0610cd\",\n        \"size\": 356198582\n    },\n    \"AccidentTwoWays_Town13_Route30356_Weather6.tar.gz\": {\n        \"sha256\": \"89f54f5a52660fcce3a2128f62e75e1cabcdfc9133b177cae451c6be4cbc6414\",\n        \"size\": 372758363\n    },\n    \"AccidentTwoWays_Town13_Route30357_Weather7.tar.gz\": {\n        \"sha256\": \"a6a7b360f075ee3fcde966018dea96885d320a46a00c6714ec75ff1e2aac1a61\",\n        \"size\": 365164202\n    },\n    \"AccidentTwoWays_Town13_Route30358_Weather8.tar.gz\": {\n        \"sha256\": \"335a0aefa8439e4c65abc253e2174f2a0d0468d5fdc0ba048becf8ce2fcdb767\",\n        \"size\": 369859989\n    },\n    \"AccidentTwoWays_Town13_Route30363_Weather13.tar.gz\": {\n        \"sha256\": \"8e5f9e64cc92f08bd1abd9efaa90c6974805a09d6d2cffd1d3a2783f2ab941a4\",\n        \"size\": 318770070\n    },\n    \"AccidentTwoWays_Town13_Route30364_Weather14.tar.gz\": {\n        \"sha256\": \"f2bd967689c5461e43688aacf341711605a7491af9a90f51b19525699cd90267\",\n        \"size\": 357908341\n    },\n    \"AccidentTwoWays_Town13_Route30367_Weather19.tar.gz\": {\n        \"sha256\": \"7b292d936e1313c1e0b104f1a53cc29af417aee92f990f2551e049205c2beb29\",\n        \"size\": 337657997\n    },\n    \"AccidentTwoWays_Town13_Route30370_Weather22.tar.gz\": {\n        \"sha256\": \"3fffdcdd03d077542d5a43d957d013959052bebf15400fbb06b53f8d5ce131a0\",\n        \"size\": 408549231\n    },\n    \"AccidentTwoWays_Town13_Route30376_Weather2.tar.gz\": {\n        \"sha256\": \"729af623d996731e8d8c4b0dd19617b74dfd2896d317abc82f49e885d532a5b2\",\n        \"size\": 399511495\n    },\n    \"AccidentTwoWays_Town13_Route30379_Weather6.tar.gz\": {\n        \"sha256\": \"564496cdcb364cc27fd7e2d650cdbc8d3bd2303af46e4ff8391fc0684133c425\",\n        \"size\": 361750839\n    },\n    \"AccidentTwoWays_Town13_Route30382_Weather9.tar.gz\": {\n        \"sha256\": \"d4e2c9bfd0b6a7d8110e55503199c7a5ef37d2261045bc884adb6bef395dacb1\",\n        \"size\": 238729668\n    },\n    \"AccidentTwoWays_Town13_Route30383_Weather10.tar.gz\": {\n        \"sha256\": \"10777b108723ec6ccd41b54f1163bb3db9b18ebedd95940d582b6b1bd7be0886\",\n        \"size\": 295289528\n    },\n    \"AccidentTwoWays_Town13_Route30387_Weather14.tar.gz\": {\n        \"sha256\": \"e5b89ed9dea757c582478861487b59f09dd669f6fa1c8c5c3a79712ebae28ee3\",\n        \"size\": 336700653\n    },\n    \"AccidentTwoWays_Town13_Route30389_Weather18.tar.gz\": {\n        \"sha256\": \"eb46dbc1e190d62219d408caca73ad2aca4adec54dca325d3df4e06475974b8e\",\n        \"size\": 427220350\n    },\n    \"AccidentTwoWays_Town13_Route30391_Weather20.tar.gz\": {\n        \"sha256\": \"5fa04753dda131fc1ff0265dd202b1913758770691a31eaa9cba95e8bd3fff99\",\n        \"size\": 695246278\n    },\n    \"AccidentTwoWays_Town13_Route30392_Weather21.tar.gz\": {\n        \"sha256\": \"d7a2591563829b48ff0a0dcd3664ac1535bf2a283ace72e4a113c0d27b595cac\",\n        \"size\": 306668826\n    },\n    \"AccidentTwoWays_Town13_Route30394_Weather23.tar.gz\": {\n        \"sha256\": \"9041bd90c729cfbfcff2971b2e1f3f7fd8ee2b3c97c0cc41f3d1495af1034311\",\n        \"size\": 348636517\n    },\n    \"AccidentTwoWays_Town13_Route30395_Weather25.tar.gz\": {\n        \"sha256\": \"d84042651246a2195c4ce568ddeb2b0b496e3c79c420565cd5bfdb37c51f5f2d\",\n        \"size\": 264087266\n    },\n    \"AccidentTwoWays_Town13_Route30396_Weather26.tar.gz\": {\n        \"sha256\": \"52a8c99997f3b6564e3d627fe437f18be0e8800e644f40e547231d3dd0bf711d\",\n        \"size\": 386940164\n    },\n    \"AccidentTwoWays_Town13_Route30398_Weather1.tar.gz\": {\n        \"sha256\": \"a660286e0cb0b862c728b70b2e8992ba3c70ebe5dda4df64f8a40c94e1972c97\",\n        \"size\": 392603569\n    },\n    \"AccidentTwoWays_Town13_Route30400_Weather3.tar.gz\": {\n        \"sha256\": \"9d660d0e7772df472a0e8f4f01fde2a9ff7dbc42df5b26eff0b89a8e3a48c9bc\",\n        \"size\": 357805019\n    },\n    \"AccidentTwoWays_Town13_Route30404_Weather8.tar.gz\": {\n        \"sha256\": \"2a5a98f29e79aabd6875d66d06cbb5b0863388208d095d21d2a663495c5951ff\",\n        \"size\": 355108801\n    },\n    \"AccidentTwoWays_Town13_Route30405_Weather9.tar.gz\": {\n        \"sha256\": \"414a7203781e0895863c5a96d6fcce3e8f3e404ad2bb4baf74a7216cb389ebc7\",\n        \"size\": 565112305\n    },\n    \"AccidentTwoWays_Town13_Route30406_Weather10.tar.gz\": {\n        \"sha256\": \"72d52a2c68958a1288bd3e3e9efc7c5fd0bcaf8fc1091f88c879bc72e53e761e\",\n        \"size\": 377091606\n    },\n    \"AccidentTwoWays_Town13_Route30412_Weather18.tar.gz\": {\n        \"sha256\": \"6b57ac1bac8ca5f306074393267c6c86ed2f0a716e321a632d0fa9b8edbbf5d4\",\n        \"size\": 408707444\n    },\n    \"AccidentTwoWays_Town13_Route30414_Weather20.tar.gz\": {\n        \"sha256\": \"1e827fcfab1acbafea242b86d929c89cfb1f2ee245bf7e09bbe5bad75ccee849\",\n        \"size\": 670125082\n    },\n    \"AccidentTwoWays_Town13_Route30415_Weather21.tar.gz\": {\n        \"sha256\": \"23f987247a84f6215fb39466adca0c16b1b054d9492d5d705555d3d783d5ee17\",\n        \"size\": 669668670\n    },\n    \"AccidentTwoWays_Town13_Route30417_Weather23.tar.gz\": {\n        \"sha256\": \"2123f73c373aab4aad0f1404c08fe9da71ea1bb4d6dd134358596e23b30c0464\",\n        \"size\": 283743730\n    },\n    \"AccidentTwoWays_Town13_Route30420_Weather0.tar.gz\": {\n        \"sha256\": \"370663cc9c8fa6d5070c4227ad4616e52ee525b74c96901d92bf3a321f2fd440\",\n        \"size\": 462087715\n    },\n    \"AccidentTwoWays_Town13_Route30422_Weather2.tar.gz\": {\n        \"sha256\": \"8b99071ff56e1a1b6788c4a3433d4e80b8ec5c6eea1f7ac2e1298fa99b4d9550\",\n        \"size\": 638123285\n    },\n    \"AccidentTwoWays_Town13_Route30427_Weather8.tar.gz\": {\n        \"sha256\": \"15a4195f7ec4b244e0f9c035e4ae8dc1b28727fc92429d2929cae8b59bc4c53d\",\n        \"size\": 336765175\n    },\n    \"AccidentTwoWays_Town13_Route30428_Weather9.tar.gz\": {\n        \"sha256\": \"8836fe396097d786d03d6be38541c8cd990770fc1f0db4864282af0ef5eac7cc\",\n        \"size\": 256980089\n    },\n    \"AccidentTwoWays_Town13_Route30431_Weather12.tar.gz\": {\n        \"sha256\": \"c065b05a353d9f6bca6d6313c9980561859977741d268e4a27efd4e24c3e20d0\",\n        \"size\": 255119374\n    },\n    \"AccidentTwoWays_Town13_Route30432_Weather13.tar.gz\": {\n        \"sha256\": \"aa6de82b7affbd11a73c74be96882f9f006eea8b269c8262babff88e0c1a8f8f\",\n        \"size\": 322725279\n    },\n    \"AccidentTwoWays_Town13_Route30434_Weather15.tar.gz\": {\n        \"sha256\": \"c5a1829386360e56470f89f5b3efd2cfa3d5313f61950aba9e71571f3389c113\",\n        \"size\": 309330080\n    },\n    \"AccidentTwoWays_Town13_Route30435_Weather18.tar.gz\": {\n        \"sha256\": \"0834fefcc412c9fe2ca25a9f9af56b38da7f67b8a61a08b02fcdaf1e1731536d\",\n        \"size\": 658146734\n    },\n    \"AccidentTwoWays_Town13_Route30436_Weather19.tar.gz\": {\n        \"sha256\": \"9ce7729d49005a867e61b632ae3c6c5cfe880fa048a76afc81059d7ec1cf6c12\",\n        \"size\": 356956625\n    },\n    \"AccidentTwoWays_Town13_Route30437_Weather20.tar.gz\": {\n        \"sha256\": \"7f7d569697bcd294632a320946fe6f6e07c08090cb0c0b3c84d0d3b32fadcc55\",\n        \"size\": 335506656\n    },\n    \"AccidentTwoWays_Town13_Route30438_Weather21.tar.gz\": {\n        \"sha256\": \"5fdf6cde26f385fe1da7081046c577bcde51bcd3b1fbeb839c4a7f267c97a60f\",\n        \"size\": 344296747\n    },\n    \"AccidentTwoWays_Town13_Route30443_Weather0.tar.gz\": {\n        \"sha256\": \"740fa11c16c41f60b08b81bddeddeebf8fb2f5d9c4f090c8c79627bfe1428e62\",\n        \"size\": 487073955\n    },\n    \"AccidentTwoWays_Town13_Route30444_Weather1.tar.gz\": {\n        \"sha256\": \"e45ad0f8acc859400a1812575a6e657957c57409aae584267dda73f07594d1e5\",\n        \"size\": 336488605\n    },\n    \"AccidentTwoWays_Town13_Route30445_Weather2.tar.gz\": {\n        \"sha256\": \"0274e37f57985c3eb994b5594a372293e3073ed03c19c37b02459c4eed147351\",\n        \"size\": 766677452\n    },\n    \"AccidentTwoWays_Town13_Route30446_Weather3.tar.gz\": {\n        \"sha256\": \"3f9c37f01e9cc338041f0f481b3c4e006a37e3b847f3352faddd70e8c14780cc\",\n        \"size\": 458162038\n    },\n    \"AccidentTwoWays_Town13_Route30448_Weather6.tar.gz\": {\n        \"sha256\": \"ad1c6dd3a2924b6e7908076f2156a8ebf1dc8f386136f6d7f80974e2ffaec0c9\",\n        \"size\": 769457934\n    },\n    \"AccidentTwoWays_Town13_Route30453_Weather11.tar.gz\": {\n        \"sha256\": \"58c98227e028ff1ae0b7c9d996f7d1a4451094a826a2cc8bf6d68220b365f48a\",\n        \"size\": 478635160\n    },\n    \"AccidentTwoWays_Town13_Route30454_Weather12.tar.gz\": {\n        \"sha256\": \"68d027bb20ccbc125318169a401f100bbd282470b3928f946088ef2dabf98faa\",\n        \"size\": 278571210\n    },\n    \"AccidentTwoWays_Town13_Route30457_Weather15.tar.gz\": {\n        \"sha256\": \"ec8d7848cf251ccca614faadf57102cef4cbcfed043fe40e3f5c4496b9df9fa2\",\n        \"size\": 324043937\n    },\n    \"AccidentTwoWays_Town13_Route30460_Weather20.tar.gz\": {\n        \"sha256\": \"181d1378e1770059f86e7831a33e4950e2dcca922eeda3af7d55ee8443a85f16\",\n        \"size\": 376853234\n    },\n    \"AccidentTwoWays_Town13_Route30461_Weather21.tar.gz\": {\n        \"sha256\": \"6f510a009bb6cc6734c0413f26ec2fdfc61bef8174e748298361aa6820574a48\",\n        \"size\": 284648227\n    },\n    \"AccidentTwoWays_Town13_Route30463_Weather23.tar.gz\": {\n        \"sha256\": \"4a0e00531c02fbd3de9054aa716c8d0cc2660f938a11ea8e4156b9331c10e6e2\",\n        \"size\": 290107401\n    },\n    \"AccidentTwoWays_Town13_Route30464_Weather25.tar.gz\": {\n        \"sha256\": \"9ed75d8b87ec96b0b42605e708a3ecf5ba9d6be7edd4df312dd3a96d13d160c7\",\n        \"size\": 274900892\n    },\n    \"AccidentTwoWays_Town13_Route30465_Weather26.tar.gz\": {\n        \"sha256\": \"c209a19bdcfce9dad7d390ec3c9d86ac58406fda037fc46cf76f182a0df17048\",\n        \"size\": 469807223\n    },\n    \"AccidentTwoWays_Town13_Route30466_Weather0.tar.gz\": {\n        \"sha256\": \"8181965d4518fbb2ff9594f0c781508648ab6b69b08931fcf6809161f97dfe12\",\n        \"size\": 383293771\n    },\n    \"AccidentTwoWays_Town13_Route30467_Weather1.tar.gz\": {\n        \"sha256\": \"61aeaf315e18991531272e76ce4b8280b03688275573b59aa9283a3474feebb9\",\n        \"size\": 451005439\n    },\n    \"AccidentTwoWays_Town13_Route30468_Weather2.tar.gz\": {\n        \"sha256\": \"62edb6cd661d1069c5476f84cef99d64e040d14d020bb1577ee8bc96d10cca73\",\n        \"size\": 398701266\n    },\n    \"AccidentTwoWays_Town13_Route30473_Weather8.tar.gz\": {\n        \"sha256\": \"6c2dc905f871024395ef2b26bcc99feb49a7503137a0abd87bb14712c8e99efc\",\n        \"size\": 368416046\n    },\n    \"AccidentTwoWays_Town13_Route30475_Weather10.tar.gz\": {\n        \"sha256\": \"23003c0eca4b06aaa78b5b981dab710c74d2501e80bf8812b248441bf3e15b73\",\n        \"size\": 414135363\n    },\n    \"AccidentTwoWays_Town13_Route30477_Weather12.tar.gz\": {\n        \"sha256\": \"0860dd1832510567a877b8f31ae0b35a2f6e1c9a3f2c4ac4b18370e02ad6dabb\",\n        \"size\": 264191610\n    },\n    \"AccidentTwoWays_Town13_Route30479_Weather14.tar.gz\": {\n        \"sha256\": \"339db3222166a945c8c90e341eeb33bb23ec437691ea64a4e7149a6c4ca50fee\",\n        \"size\": 291272556\n    },\n    \"AccidentTwoWays_Town13_Route30481_Weather18.tar.gz\": {\n        \"sha256\": \"0d3380da21472bb04a8cc5d93c2d65c147c4b0b2b84fd31ce62ada3db66afe4d\",\n        \"size\": 675644764\n    },\n    \"AccidentTwoWays_Town13_Route30483_Weather20.tar.gz\": {\n        \"sha256\": \"a3b09e8ed8d793c1bab899997e6872bee466d8c71a8e4020b2dd2273acb521ad\",\n        \"size\": 361591264\n    },\n    \"AccidentTwoWays_Town13_Route30485_Weather22.tar.gz\": {\n        \"sha256\": \"f5c21e3d9daa8286a079c6b7893cbe7436498af5cb4be53e45837950b231d1aa\",\n        \"size\": 573728845\n    },\n    \"AccidentTwoWays_Town13_Route30486_Weather23.tar.gz\": {\n        \"sha256\": \"854824b9c5640217e7721724f08c3e38755e44b782e8f542710c86f8b3de8909\",\n        \"size\": 431413147\n    },\n    \"AccidentTwoWays_Town13_Route30488_Weather26.tar.gz\": {\n        \"sha256\": \"19e0fa6b3e037397cc7bfac8c6346d1aa6fce140410e9dd1ef5921c6cbf132d1\",\n        \"size\": 384429802\n    },\n    \"AccidentTwoWays_Town13_Route30489_Weather0.tar.gz\": {\n        \"sha256\": \"22078a3aacc9b697c2e3e9ff0602f7d014ae4e8fbc578c68ac7d91103f2de539\",\n        \"size\": 386268043\n    },\n    \"AccidentTwoWays_Town13_Route30493_Weather5.tar.gz\": {\n        \"sha256\": \"6e710a8449aa21df9ea8e7b0a5bfeb6b64f1d1db37fe0fa2a2ff3ab0f00d9bd1\",\n        \"size\": 368297312\n    },\n    \"AccidentTwoWays_Town13_Route30494_Weather6.tar.gz\": {\n        \"sha256\": \"a4a8f9dd6aa259fc60a8a34e177adadf59a29ed54c9e629a8efac220f3e11ae6\",\n        \"size\": 378874534\n    },\n    \"AccidentTwoWays_Town13_Route30497_Weather9.tar.gz\": {\n        \"sha256\": \"b03ef11f5b42d2cb04286e1538974257ecf1616d1ff1f0127ad9f75c47c41884\",\n        \"size\": 272278739\n    },\n    \"AccidentTwoWays_Town13_Route30498_Weather10.tar.gz\": {\n        \"sha256\": \"b1871511f9046d79129d2781388afacfefa2382797eab5c803ac52211612d99f\",\n        \"size\": 305565634\n    },\n    \"AccidentTwoWays_Town13_Route30499_Weather11.tar.gz\": {\n        \"sha256\": \"a0bdcdef6c05c9d2dc91bd9233c754729bc5667c5961c0f98a35a36f24ce149b\",\n        \"size\": 245053717\n    },\n    \"AccidentTwoWays_Town13_Route30500_Weather12.tar.gz\": {\n        \"sha256\": \"1e556775a1a1e504ae9a50149388ea68578fdfdba525e9026d422ac7d0dd6141\",\n        \"size\": 377782522\n    },\n    \"AccidentTwoWays_Town13_Route30501_Weather13.tar.gz\": {\n        \"sha256\": \"d461d4bdd5df925b07ea1399aac49413d46483bee94a12d62727abbb2233a4ab\",\n        \"size\": 160325994\n    },\n    \"AccidentTwoWays_Town13_Route30505_Weather19.tar.gz\": {\n        \"sha256\": \"23dd8527804f8c2907c161688d150b41f6707b02fc8cd20d685c1158b0276493\",\n        \"size\": 402422650\n    },\n    \"AccidentTwoWays_Town13_Route30506_Weather20.tar.gz\": {\n        \"sha256\": \"09d2ac528a10afe044791c741dd990b316789f668321b3542fbab71ac0822194\",\n        \"size\": 414706952\n    },\n    \"AccidentTwoWays_Town13_Route30507_Weather21.tar.gz\": {\n        \"sha256\": \"bb3aacc24e724df263c37c92828e393719b82001c92aafba0d0960ddad24a0c9\",\n        \"size\": 331099359\n    },\n    \"AccidentTwoWays_Town13_Route30511_Weather26.tar.gz\": {\n        \"sha256\": \"f97d8fef13c21ca58419584fdcaae047c93249ea0ebf61e668edc7a68c4703e6\",\n        \"size\": 405276982\n    },\n    \"AccidentTwoWays_Town13_Route30512_Weather0.tar.gz\": {\n        \"sha256\": \"d7acef02547bb9b35fb5da9b10d5eb525716eff13255edc965da5c6842efb9e3\",\n        \"size\": 392637001\n    },\n    \"AccidentTwoWays_Town13_Route30515_Weather3.tar.gz\": {\n        \"sha256\": \"d0585f4139dd10e1d3d55e97af317547b040e7e70299bebb5b08e3db35dab6ad\",\n        \"size\": 367656580\n    },\n    \"AccidentTwoWays_Town13_Route30517_Weather6.tar.gz\": {\n        \"sha256\": \"b1777551b4f9264603567fceebf27db3b5ccb1977130c154d9aedcac68b3cca1\",\n        \"size\": 926743110\n    },\n    \"AccidentTwoWays_Town13_Route30518_Weather7.tar.gz\": {\n        \"sha256\": \"2f9fa65df25c5c4b51d2c54787dd260a5219bc43c63f9f9360e224ff5b20b1dd\",\n        \"size\": 1167325982\n    },\n    \"AccidentTwoWays_Town13_Route30520_Weather9.tar.gz\": {\n        \"sha256\": \"88b68075e204517c4f77e4bdcb63cbdc973bd7a7ccc44640f40f7318f17a4e87\",\n        \"size\": 303447091\n    },\n    \"AccidentTwoWays_Town13_Route30522_Weather11.tar.gz\": {\n        \"sha256\": \"f10393a1203310683fbbdfefc746b14d643b70b40a039104535a0b0f6651db4b\",\n        \"size\": 349623340\n    },\n    \"AccidentTwoWays_Town13_Route30523_Weather12.tar.gz\": {\n        \"sha256\": \"10f4cfb4ccb24cc811babbf9b59e63682c34dfdcf10a5b34cd20e350031da135\",\n        \"size\": 279195405\n    },\n    \"AccidentTwoWays_Town13_Route30528_Weather19.tar.gz\": {\n        \"sha256\": \"306231cb6d630a96d8f326b2451abaa1e04a759479f0543446c66d3a827e3881\",\n        \"size\": 765603826\n    },\n    \"AccidentTwoWays_Town13_Route30537_Weather2.tar.gz\": {\n        \"sha256\": \"30af5b268298b09aa821282387f6ce911a08ac52eb04e506e68d43d804e2a01b\",\n        \"size\": 903164737\n    },\n    \"AccidentTwoWays_Town13_Route30540_Weather6.tar.gz\": {\n        \"sha256\": \"1c9f578e3bc9153bca5d01a6ef1d520af23791a7f5e36b2efb8ea3239f5b0a9e\",\n        \"size\": 349502945\n    },\n    \"AccidentTwoWays_Town13_Route30541_Weather7.tar.gz\": {\n        \"sha256\": \"5d7cad45cb700815ce55b5cf443b67fabdf3a58de4c6158daef264a9a8271f14\",\n        \"size\": 384328963\n    },\n    \"BlockedIntersection_Town12_Route12458_Weather7.tar.gz\": {\n        \"sha256\": \"d77a37bd1c69dc0ec23f35ec4756bfcd252b539d4e720af592fe56e1d5a409e1\",\n        \"size\": 1095529242\n    },\n    \"BlockedIntersection_Town12_Route12459_Weather8.tar.gz\": {\n        \"sha256\": \"b26a2af78ab1ced8762f80d3d53cf3b0cf52a155cf414dd297640a99d6c32834\",\n        \"size\": 332746915\n    },\n    \"BlockedIntersection_Town12_Route12494_Weather9.tar.gz\": {\n        \"sha256\": \"cf790fb1ca99c78e8a807f6d99ef26f3b6f535bca0a16f7ef6a94d2c39f3a323\",\n        \"size\": 213443598\n    },\n    \"BlockedIntersection_Town12_Route12534_Weather5.tar.gz\": {\n        \"sha256\": \"b6d21b3cd3321e3b94c1d02bbae15b4601422e0d9e815e105c4c99e3d69504f0\",\n        \"size\": 809344795\n    },\n    \"BlockedIntersection_Town12_Route12570_Weather15.tar.gz\": {\n        \"sha256\": \"1a7d5be3ed83b45cda46cbec558394b12040afc826c2f25612317465aa556710\",\n        \"size\": 433114020\n    },\n    \"BlockedIntersection_Town12_Route12571_Weather8.tar.gz\": {\n        \"sha256\": \"d7bf73e2b7ee8bb2de30a8d43c865b100dd170611dc799c33db32c8252cbab9d\",\n        \"size\": 403843762\n    },\n    \"BlockedIntersection_Town12_Route12604_Weather23.tar.gz\": {\n        \"sha256\": \"95b3d5f2fa9dd435c61b2b8d4e2ec897395c6aab4d690bc438836c899d50d148\",\n        \"size\": 641057922\n    },\n    \"BlockedIntersection_Town12_Route12643_Weather10.tar.gz\": {\n        \"sha256\": \"c971ce88627354278a7d97101e0330335207b87cffec46be17fe2d274cbafeea\",\n        \"size\": 256480757\n    },\n    \"BlockedIntersection_Town12_Route12676_Weather9.tar.gz\": {\n        \"sha256\": \"61da9f0d796a9df534dfa5ad62b7bb97e47540806ed625d1239c9dc80b5e5ed7\",\n        \"size\": 237133777\n    },\n    \"BlockedIntersection_Town12_Route12677_Weather18.tar.gz\": {\n        \"sha256\": \"9ba0213e7d1fd586a082be825bbf7411d44c2202f1ac17c6173345f7fa0872b0\",\n        \"size\": 346119790\n    },\n    \"BlockedIntersection_Town12_Route12678_Weather19.tar.gz\": {\n        \"sha256\": \"ed39440e8590be1f04c7097aa087aae89e96c850c033d55f58fe7a530bd635b1\",\n        \"size\": 279575870\n    },\n    \"BlockedIntersection_Town12_Route12679_Weather20.tar.gz\": {\n        \"sha256\": \"5d75a570d6c920ac106449bff5758503f1e6529b18039a407d85153b195c5766\",\n        \"size\": 542057172\n    },\n    \"BlockedIntersection_Town12_Route12680_Weather21.tar.gz\": {\n        \"sha256\": \"15685e67b54ccaa7fefd5941eb9eb00b7a75aa01508b63b3f0d0c98b825a9565\",\n        \"size\": 342475776\n    },\n    \"BlockedIntersection_Town12_Route12681_Weather22.tar.gz\": {\n        \"sha256\": \"427a2472e246aed0b94171f507aaef7c1d63bf0947968c4864a33100d09193de\",\n        \"size\": 563440234\n    },\n    \"BlockedIntersection_Town12_Route12683_Weather23.tar.gz\": {\n        \"sha256\": \"da8f885a0bb0cd66f51744426be378587b7ebc6334bc21ef5bb76cd21f5c0ae8\",\n        \"size\": 716151554\n    },\n    \"BlockedIntersection_Town12_Route12684_Weather25.tar.gz\": {\n        \"sha256\": \"559c6317b97283ad812cd8e01b256fa6f179ac4eb0e2dd43b25b4f6e5cac5000\",\n        \"size\": 369326250\n    },\n    \"BlockedIntersection_Town12_Route12685_Weather0.tar.gz\": {\n        \"sha256\": \"e4dacace27a62a62e5995fd39bcb877ca515f869b37869b12222c7c5027e4e9a\",\n        \"size\": 648971735\n    },\n    \"BlockedIntersection_Town12_Route12687_Weather2.tar.gz\": {\n        \"sha256\": \"9b6e26da51ba0ec3208ba58ebd260bf100dbee5f5c7477f7a8ab41fceebce4dc\",\n        \"size\": 254737395\n    },\n    \"BlockedIntersection_Town12_Route12688_Weather3.tar.gz\": {\n        \"sha256\": \"38fca2ca0c8ca83d93cefdd98f19ff8dd1c5665b7b6eb8c388d6b4a5c0451036\",\n        \"size\": 316516126\n    },\n    \"BlockedIntersection_Town12_Route12690_Weather5.tar.gz\": {\n        \"sha256\": \"8fae4067ea267487142618f840037af7b10259ed3bc5273268f64dd9d3a4e494\",\n        \"size\": 672101677\n    },\n    \"BlockedIntersection_Town12_Route12691_Weather6.tar.gz\": {\n        \"sha256\": \"349158a5a18fdacec42e1920438a6cbec92b2169149420e1cd095e28d609fba4\",\n        \"size\": 512358324\n    },\n    \"BlockedIntersection_Town12_Route12692_Weather7.tar.gz\": {\n        \"sha256\": \"1dc3296ac93dcc068f5397da13fb9c59e2d8e09b3382a838a263219dcce9f5d3\",\n        \"size\": 556975970\n    },\n    \"BlockedIntersection_Town12_Route12693_Weather8.tar.gz\": {\n        \"sha256\": \"c60e01a09770e39a933f62017bdfc97fc9971eab5efc6baea9cc9580b89b9e7e\",\n        \"size\": 610672457\n    },\n    \"BlockedIntersection_Town12_Route12694_Weather9.tar.gz\": {\n        \"sha256\": \"6ba319e4ee0e1a095c0aecc77ac7a352ba6f55427cf1474337cc3f5256f32461\",\n        \"size\": 327763716\n    },\n    \"BlockedIntersection_Town12_Route12695_Weather10.tar.gz\": {\n        \"sha256\": \"d7702e65e6ec2d85107ac39135639b50b7cfbb075fa115bbcbe5241176b45a5a\",\n        \"size\": 729618925\n    },\n    \"BlockedIntersection_Town12_Route12696_Weather11.tar.gz\": {\n        \"sha256\": \"d1b18a70a227ee3285bf25026b40f340037405801de990b162ad17a59ca7fe15\",\n        \"size\": 496498099\n    },\n    \"BlockedIntersection_Town12_Route12697_Weather12.tar.gz\": {\n        \"sha256\": \"7f3d014b5fa794fb4cd19f13c97302bda46eddebfefac946d6f6da8f2aaf46b6\",\n        \"size\": 264525642\n    },\n    \"BlockedIntersection_Town12_Route12698_Weather13.tar.gz\": {\n        \"sha256\": \"6c140e365d36d3ba0aa689f57bac7b9648ce85330fa81791505e7a1179e2e80e\",\n        \"size\": 160292516\n    },\n    \"BlockedIntersection_Town12_Route12699_Weather14.tar.gz\": {\n        \"sha256\": \"a4cd1c2a37ee232421f0ff6da4d25ac302c9d30ac29ab5999dd426ea5efc9f55\",\n        \"size\": 586294115\n    },\n    \"BlockedIntersection_Town12_Route12701_Weather8.tar.gz\": {\n        \"sha256\": \"4552e8734466c0b2d131a6f683907f908eede53e08721b299b7ad2d66c39529b\",\n        \"size\": 259846204\n    },\n    \"BlockedIntersection_Town12_Route12703_Weather18.tar.gz\": {\n        \"sha256\": \"94f97c900c1cda488ef4e55589b389b51f64e8799c6ca0a4eae05162e10c3ae6\",\n        \"size\": 408932403\n    },\n    \"BlockedIntersection_Town12_Route12704_Weather19.tar.gz\": {\n        \"sha256\": \"9b57dfd03f252fd585b51a642c26d498b2b4ab2f058ce3b95119834369b1e8ce\",\n        \"size\": 514119577\n    },\n    \"BlockedIntersection_Town12_Route12705_Weather20.tar.gz\": {\n        \"sha256\": \"6ea88823b7d1300fd068167e19281384372854114b177505b6c2c3bfec36c33d\",\n        \"size\": 371172389\n    },\n    \"BlockedIntersection_Town12_Route12706_Weather21.tar.gz\": {\n        \"sha256\": \"1fc9dd57e686be74130f16b4b21b18ad6245451555d0b8dea1eb3642738e3722\",\n        \"size\": 344661197\n    },\n    \"BlockedIntersection_Town12_Route12707_Weather22.tar.gz\": {\n        \"sha256\": \"887735ea016f1aa303ebbfa6e0a8839eb256207a3bbce9be120a1bb868a164ca\",\n        \"size\": 322238628\n    },\n    \"BlockedIntersection_Town12_Route12708_Weather23.tar.gz\": {\n        \"sha256\": \"a1545a958e536bd5389f9fd794c76f7541def28083f1b97136ec707890b4fdb2\",\n        \"size\": 135579173\n    },\n    \"BlockedIntersection_Town12_Route12709_Weather23.tar.gz\": {\n        \"sha256\": \"59a00b5e5f5a96240f0ec56ae5cee9fde6fdbd714059001e6b36e07cfc3c8b21\",\n        \"size\": 214858828\n    },\n    \"BlockedIntersection_Town12_Route12712_Weather1.tar.gz\": {\n        \"sha256\": \"16888a6d95e3e1db3652566151bc93c679621bc170505088315efbf65e7883b8\",\n        \"size\": 697338057\n    },\n    \"BlockedIntersection_Town12_Route12713_Weather2.tar.gz\": {\n        \"sha256\": \"9dfa00b92413890196da1c4df8af457d64e79c2b17e3b9f4c29c68b3c2fad981\",\n        \"size\": 527138768\n    },\n    \"BlockedIntersection_Town12_Route12714_Weather3.tar.gz\": {\n        \"sha256\": \"a08650474f614eb17b8dbea46711ed7ab5de9aae2ec9d040d56225707589426e\",\n        \"size\": 299495431\n    },\n    \"BlockedIntersection_Town12_Route12715_Weather3.tar.gz\": {\n        \"sha256\": \"c3f65e34a419afe82cc0f60344805fc888116b986c2f9bcd180251d982b2ee84\",\n        \"size\": 470076998\n    },\n    \"BlockedIntersection_Town12_Route12716_Weather5.tar.gz\": {\n        \"sha256\": \"9ac492618034c947d22c2ae07aee523b071ffc870cb064d4cb353741bfc90ee3\",\n        \"size\": 268550646\n    },\n    \"BlockedIntersection_Town12_Route12719_Weather8.tar.gz\": {\n        \"sha256\": \"9839de327e045d6068aba2a98eda457a50f6b364c4ace4e830a0510d83601073\",\n        \"size\": 385073973\n    },\n    \"BlockedIntersection_Town12_Route12720_Weather9.tar.gz\": {\n        \"sha256\": \"d34dae481c90650a43270e8e022c78f174874dc783fe6fc424d6982a024e33ae\",\n        \"size\": 445262421\n    },\n    \"BlockedIntersection_Town12_Route12721_Weather10.tar.gz\": {\n        \"sha256\": \"4971a7f65600eaef21602fce2ccba9906ce173c78884f096ff5e95de623fee0f\",\n        \"size\": 222631986\n    },\n    \"BlockedIntersection_Town12_Route12722_Weather11.tar.gz\": {\n        \"sha256\": \"19774f217a6c746fdc1d2095f19b4b56dbdd7d8c9a57ac0a52dbfdcb20dc081c\",\n        \"size\": 621196799\n    },\n    \"BlockedIntersection_Town12_Route12723_Weather12.tar.gz\": {\n        \"sha256\": \"e67385b5b2dcad1e5c83dcf37b53e4c06406e3678ef68302d7bc5e9a982b4e37\",\n        \"size\": 356428668\n    },\n    \"BlockedIntersection_Town12_Route12724_Weather13.tar.gz\": {\n        \"sha256\": \"bc51c1b5a876823a9bf151af431db1c83552b0bb785616ef454a0e4331d280f9\",\n        \"size\": 325067903\n    },\n    \"BlockedIntersection_Town12_Route12727_Weather8.tar.gz\": {\n        \"sha256\": \"0532928d5d1ce0d5d155eb40876f6c8fc4781972990b843e4cf67aee4d9d082a\",\n        \"size\": 1014667043\n    },\n    \"BlockedIntersection_Town12_Route12729_Weather18.tar.gz\": {\n        \"sha256\": \"b2db6e14b9c4d3f5a4d7ed8451bb4690570eee161011fbc85eaaef33dd3d27b8\",\n        \"size\": 329246087\n    },\n    \"BlockedIntersection_Town12_Route12731_Weather20.tar.gz\": {\n        \"sha256\": \"656b16d970959889ced734fbf273037902398aac95a47767046a491aa5a27fb9\",\n        \"size\": 259751221\n    },\n    \"BlockedIntersection_Town12_Route12732_Weather21.tar.gz\": {\n        \"sha256\": \"1736640de0233005af5ce9b84c86ca947524be3b07ceff6cea39f0e97107aec7\",\n        \"size\": 649350793\n    },\n    \"BlockedIntersection_Town12_Route12733_Weather22.tar.gz\": {\n        \"sha256\": \"ad8e1f151d745a148f3484d676e9df379b409c4d05ff8ff4ba32d9a7cff0f869\",\n        \"size\": 578969631\n    },\n    \"BlockedIntersection_Town12_Route12734_Weather23.tar.gz\": {\n        \"sha256\": \"d2cb03af1ac585fc4442698644c203cee494d63367ec81aeea4d7c36369aae0f\",\n        \"size\": 250222453\n    },\n    \"BlockedIntersection_Town12_Route12736_Weather25.tar.gz\": {\n        \"sha256\": \"2c40c1990d25a195c467a13f2797a29dd1bacec8d58210b55a7e015dbdf8896a\",\n        \"size\": 263181797\n    },\n    \"BlockedIntersection_Town12_Route12737_Weather0.tar.gz\": {\n        \"sha256\": \"183667347d336df18aa4f507373714a60c1fee030aa3a4779a41a54655f30445\",\n        \"size\": 409223658\n    },\n    \"BlockedIntersection_Town12_Route12738_Weather1.tar.gz\": {\n        \"sha256\": \"85a09a717fcbdef35b9b5aee1c01d9b6398aa0c3a830de315d97f46e5334c03c\",\n        \"size\": 569167009\n    },\n    \"BlockedIntersection_Town12_Route12739_Weather2.tar.gz\": {\n        \"sha256\": \"5077b00980454e974e69f37dc2d45a60f3ddb2aa3be9ddc9530d6a987ffbb730\",\n        \"size\": 618694455\n    },\n    \"BlockedIntersection_Town12_Route12740_Weather3.tar.gz\": {\n        \"sha256\": \"cb7a5f6dd22dab3865dce3d4df63444e2e72c8e7d4461fd327e20498f06aea64\",\n        \"size\": 432305622\n    },\n    \"BlockedIntersection_Town12_Route12744_Weather7.tar.gz\": {\n        \"sha256\": \"08b59f502f9892dfc23ab2ea6f2ddae99eb0d4137b3b04ff1e240792e8bd045a\",\n        \"size\": 223038291\n    },\n    \"BlockedIntersection_Town12_Route12745_Weather8.tar.gz\": {\n        \"sha256\": \"ebf70b02192f180bb00e7afcb8f3323ca4b6cde764d4076352d3fcde615dbd00\",\n        \"size\": 645118416\n    },\n    \"BlockedIntersection_Town12_Route12746_Weather9.tar.gz\": {\n        \"sha256\": \"af814b562ba1368281eeeb29d18dff79fc8ff5ce89985c98acb1bf1978aa27cc\",\n        \"size\": 177928270\n    },\n    \"BlockedIntersection_Town12_Route12747_Weather10.tar.gz\": {\n        \"sha256\": \"433dda2369dcef863b578d0b47da48c6c578b9ba76d1f83b511caed92816dda3\",\n        \"size\": 404070338\n    },\n    \"BlockedIntersection_Town12_Route12748_Weather11.tar.gz\": {\n        \"sha256\": \"d9ba213f2ccf49ce9407d5ed672057aaf39ba0292c7ed6ff6cc7ff91d655ad34\",\n        \"size\": 430062221\n    },\n    \"BlockedIntersection_Town12_Route12750_Weather13.tar.gz\": {\n        \"sha256\": \"d53757c64b080e165fa460fd2f72ed6c0953dc282f7fb33f8c6504cb5bb67100\",\n        \"size\": 156690345\n    },\n    \"BlockedIntersection_Town12_Route12751_Weather14.tar.gz\": {\n        \"sha256\": \"4ad64873066e1e2e97b7cb4b6d993b4c43bc4bed5994d859dcdcc1957f9f14cc\",\n        \"size\": 539462530\n    },\n    \"BlockedIntersection_Town12_Route12752_Weather15.tar.gz\": {\n        \"sha256\": \"da1e4005cb734ca8afbf08fb9c99ac3ec9a542d25823bcde0fb22523b033bd63\",\n        \"size\": 880627457\n    },\n    \"BlockedIntersection_Town12_Route12753_Weather8.tar.gz\": {\n        \"sha256\": \"f6302456db0bb373b214d6cd0aca78db9c38d4872f1274b7ed0e5f0df4e90998\",\n        \"size\": 338259872\n    },\n    \"BlockedIntersection_Town12_Route12755_Weather18.tar.gz\": {\n        \"sha256\": \"c152acbe466efec3eb53fae57e3bab27d61a3ceb1967761d771ae3bccf8c6f9f\",\n        \"size\": 242946527\n    },\n    \"BlockedIntersection_Town12_Route12756_Weather19.tar.gz\": {\n        \"sha256\": \"7cbe481922abf3bfe528e586cf35a9046633f26d1a4a0b4cb3f152d300c3c310\",\n        \"size\": 528181770\n    },\n    \"BlockedIntersection_Town12_Route12757_Weather20.tar.gz\": {\n        \"sha256\": \"6c148985bc7f2b0e8449433f7d115f867f5770fbecf755287f29e99fceb3e65e\",\n        \"size\": 391295552\n    },\n    \"BlockedIntersection_Town12_Route12759_Weather22.tar.gz\": {\n        \"sha256\": \"17af364e3caada24acdfe5a522becb173951c57b838c38b3ce818ba541661545\",\n        \"size\": 300859469\n    },\n    \"BlockedIntersection_Town12_Route12760_Weather23.tar.gz\": {\n        \"sha256\": \"26078463220cd200dd84f1cf5f9997c9fba4abe7c7c5e654cf0690e24406e08a\",\n        \"size\": 520811645\n    },\n    \"BlockedIntersection_Town12_Route12761_Weather23.tar.gz\": {\n        \"sha256\": \"9e4a07ee4adac92ff3dd8781d57a787172e07281af2bb58cb2b322c89c29bf97\",\n        \"size\": 297770938\n    },\n    \"BlockedIntersection_Town12_Route12762_Weather25.tar.gz\": {\n        \"sha256\": \"08592e489b173377c688a10675c48de1302cf70019af87fcc62888828c06d300\",\n        \"size\": 246246402\n    },\n    \"BlockedIntersection_Town12_Route12763_Weather0.tar.gz\": {\n        \"sha256\": \"58b0d045a2de246d6a63ca41a8c52d1caf2b111d5fa08d149dec16f01069de14\",\n        \"size\": 562824964\n    },\n    \"BlockedIntersection_Town12_Route12764_Weather1.tar.gz\": {\n        \"sha256\": \"128def3f945a51082b195a788a3efca93dad3db18e5884cb98319a99a16c967e\",\n        \"size\": 312931151\n    },\n    \"BlockedIntersection_Town12_Route12765_Weather2.tar.gz\": {\n        \"sha256\": \"0c41a7fd7e5d66461e8ebf0762efc5a03550c94461938c41269a6b23484eb209\",\n        \"size\": 409080033\n    },\n    \"BlockedIntersection_Town12_Route12767_Weather3.tar.gz\": {\n        \"sha256\": \"659ecc7dea48709b328e25076e00b0a9aa8568c536ead7bfb82743c51f104ea9\",\n        \"size\": 1439932157\n    },\n    \"BlockedIntersection_Town12_Route12768_Weather5.tar.gz\": {\n        \"sha256\": \"7d845eba5078d2f403c575d5aa330e3a537691ec6e436c962d8bf566d65ab059\",\n        \"size\": 275337237\n    },\n    \"BlockedIntersection_Town12_Route12769_Weather6.tar.gz\": {\n        \"sha256\": \"2daff5c5187dd2b44045d142ec111364f5357e0c5de906c62e0972477a40c800\",\n        \"size\": 425593423\n    },\n    \"BlockedIntersection_Town12_Route12770_Weather7.tar.gz\": {\n        \"sha256\": \"8d09d83df4aceaa18ae431d7138fe93bb3a203f5d3313ecb9e4b8f2a3d00aa46\",\n        \"size\": 540046048\n    },\n    \"BlockedIntersection_Town12_Route12771_Weather8.tar.gz\": {\n        \"sha256\": \"c38fc5cd9c598e960ae7cefe36cd3fff4ad1de4d787423d6358a7ba6f584c427\",\n        \"size\": 516041232\n    },\n    \"BlockedIntersection_Town12_Route12772_Weather9.tar.gz\": {\n        \"sha256\": \"1acadeaa9fa2153f57adb23aedd890728b949a0868e4210887f7244dc9c5d7e4\",\n        \"size\": 627786382\n    },\n    \"BlockedIntersection_Town12_Route12773_Weather10.tar.gz\": {\n        \"sha256\": \"dc93953c459d7ce9493034e729f466e7b331dd99a273abc9228631abe7fed4fa\",\n        \"size\": 582787511\n    },\n    \"BlockedIntersection_Town12_Route12775_Weather12.tar.gz\": {\n        \"sha256\": \"1c990c8ae681b8baa23bded059f070de399179f2fa9301b957c9b0c40e6d4cd1\",\n        \"size\": 393836433\n    },\n    \"BlockedIntersection_Town12_Route12776_Weather13.tar.gz\": {\n        \"sha256\": \"817ea46266855bfcf3419687bbafd4f83cbaf312a50afecf687ba8c8f15b07ac\",\n        \"size\": 448468285\n    },\n    \"BlockedIntersection_Town12_Route12777_Weather14.tar.gz\": {\n        \"sha256\": \"2f02a25b1b02b9417d24e4f619e1d300c0307c92d1f4f34811abe291e0210f1f\",\n        \"size\": 290706479\n    },\n    \"BlockedIntersection_Town12_Route12778_Weather15.tar.gz\": {\n        \"sha256\": \"9d45476a59617c6a379c60cde64f743b91499c7de168302afe8cf98689cfbab6\",\n        \"size\": 399700227\n    },\n    \"BlockedIntersection_Town12_Route12779_Weather8.tar.gz\": {\n        \"sha256\": \"48d76f6e3e7a781ae5660ed6a20736dc95e368c9b8cb7a3636081cadc6686053\",\n        \"size\": 554510033\n    },\n    \"BlockedIntersection_Town12_Route12780_Weather9.tar.gz\": {\n        \"sha256\": \"66558919d75d42af715ef7e6b87791a3f54b9189591145b98779512b63bc7d49\",\n        \"size\": 577138274\n    },\n    \"BlockedIntersection_Town12_Route12781_Weather18.tar.gz\": {\n        \"sha256\": \"4d1f9535da84a5681e2e795aa5f10773803be7a6dcdab93acd64b77b6391c718\",\n        \"size\": 305232563\n    },\n    \"BlockedIntersection_Town12_Route12784_Weather21.tar.gz\": {\n        \"sha256\": \"84086a6631fad291ebfdffec538652212e19edf44ab8e177b6efcb8bbbe455bf\",\n        \"size\": 317540134\n    },\n    \"BlockedIntersection_Town12_Route12785_Weather22.tar.gz\": {\n        \"sha256\": \"341e772839e715106f17151cb96af9d1d7dc4f4c0cce80e11ce4234cb74a67dc\",\n        \"size\": 251575557\n    },\n    \"BlockedIntersection_Town12_Route12789_Weather0.tar.gz\": {\n        \"sha256\": \"deccddaa80f42894bb3fb3ccc0975e9273bd4e2d683204bd0e9b156fe8896aa5\",\n        \"size\": 523059830\n    },\n    \"BlockedIntersection_Town12_Route12790_Weather1.tar.gz\": {\n        \"sha256\": \"cfb1fa52cd86a258a210373c7ab9c8104164275f4dea1e3f14ef6f0cb6b9bf71\",\n        \"size\": 367403729\n    },\n    \"BlockedIntersection_Town12_Route12791_Weather2.tar.gz\": {\n        \"sha256\": \"5a6710ee187ccb597a25f033bd3e136b4985ed154fe1e7a9dab5566fef51908b\",\n        \"size\": 483472024\n    },\n    \"BlockedIntersection_Town12_Route12792_Weather3.tar.gz\": {\n        \"sha256\": \"f305ba4bb2ba1f4bade68e47177cc4aeb113f9c04594663ed445509e6414f9d0\",\n        \"size\": 577501718\n    },\n    \"BlockedIntersection_Town12_Route12793_Weather3.tar.gz\": {\n        \"sha256\": \"40059aae2e475500f5b26e954660add903ba005926d58aa4eeff9582a44df3fe\",\n        \"size\": 409510260\n    },\n    \"BlockedIntersection_Town12_Route12794_Weather5.tar.gz\": {\n        \"sha256\": \"156e839f441229ef2d6ad0e71a0d9a1f0708200ff869d1822a1d93901c34636e\",\n        \"size\": 321934462\n    },\n    \"BlockedIntersection_Town12_Route12795_Weather6.tar.gz\": {\n        \"sha256\": \"0beeec2bd09958492c66971fdc5a99185d9f5c354d076ab0b7e99174e5aabe2a\",\n        \"size\": 218299133\n    },\n    \"BlockedIntersection_Town12_Route12796_Weather7.tar.gz\": {\n        \"sha256\": \"28ea98c3248d1a531d67941fc1103e30780b4ae28fcd28827739d0916255abaf\",\n        \"size\": 1008630300\n    },\n    \"BlockedIntersection_Town12_Route12797_Weather8.tar.gz\": {\n        \"sha256\": \"bcbbb9fdb624d90646d9fb8f0f37c757b800b245654ef61211d497f7f4169d16\",\n        \"size\": 445979577\n    },\n    \"BlockedIntersection_Town12_Route12798_Weather9.tar.gz\": {\n        \"sha256\": \"1d9fcfa8edf5ae2102d886141ff1f0ae250bf696239897315c1739354be26b44\",\n        \"size\": 316137144\n    },\n    \"BlockedIntersection_Town12_Route12799_Weather10.tar.gz\": {\n        \"sha256\": \"fd14d7e26894b364352b4ae0c15d3d8e3d4dab4a8c9afe8fa43a8aa23ae56299\",\n        \"size\": 744884746\n    },\n    \"BlockedIntersection_Town12_Route12800_Weather11.tar.gz\": {\n        \"sha256\": \"e8b8a19cf3060d63d625f1125eaa9d9630b1deace87b8b165106ba73e895005b\",\n        \"size\": 447098995\n    },\n    \"BlockedIntersection_Town12_Route12801_Weather12.tar.gz\": {\n        \"sha256\": \"aeacefccb445787dd59d2f670c43ea01db1ad629bab1546893ca1416a8808113\",\n        \"size\": 342915240\n    },\n    \"BlockedIntersection_Town12_Route12802_Weather13.tar.gz\": {\n        \"sha256\": \"6e089f5d368c8b27f52092bcdac2cbfef8c4042839fb2a2bceec274d24f0ffe1\",\n        \"size\": 382299735\n    },\n    \"BlockedIntersection_Town12_Route12804_Weather15.tar.gz\": {\n        \"sha256\": \"c1520d84a7ebff20c2b1b71d64a9b743f5f55ce4255fbf4c4d2e990815a625a7\",\n        \"size\": 341576705\n    },\n    \"BlockedIntersection_Town12_Route12805_Weather8.tar.gz\": {\n        \"sha256\": \"335b5044293e5c37328fdf829dadc02e7039981495aeb89992b5a0327e490eb3\",\n        \"size\": 317182812\n    },\n    \"BlockedIntersection_Town12_Route12806_Weather9.tar.gz\": {\n        \"sha256\": \"0903f8f689f21f5e37d8e76fd07ad8ada65b7b665f741a2466457fcfdb721ff3\",\n        \"size\": 253571623\n    },\n    \"BlockedIntersection_Town12_Route12807_Weather18.tar.gz\": {\n        \"sha256\": \"8288896c9eba5be39be520fa90241717b6d0f0ff77aef22f6b2d87af5985cac1\",\n        \"size\": 317815990\n    },\n    \"BlockedIntersection_Town12_Route12809_Weather20.tar.gz\": {\n        \"sha256\": \"7145c89be82ac8aaf30a3d6c82adac412680011931cb7f9ea373fa827195f879\",\n        \"size\": 302689911\n    },\n    \"BlockedIntersection_Town12_Route12810_Weather21.tar.gz\": {\n        \"sha256\": \"1b4b5d17e1b4698b93e01eee943c41256d394959e46f5d4a3e040b5c2700a6a4\",\n        \"size\": 569569333\n    },\n    \"BlockedIntersection_Town12_Route12811_Weather22.tar.gz\": {\n        \"sha256\": \"3643f4afb4b57ebc15da0f57d7e1e85cfa07495bedcadf8302d946df3071f557\",\n        \"size\": 239380255\n    },\n    \"BlockedIntersection_Town12_Route12812_Weather23.tar.gz\": {\n        \"sha256\": \"7fe1f5824566ea96b3aee9052d5f3bb67cbdfafaca0b116a56173a28b982b123\",\n        \"size\": 414703665\n    },\n    \"BlockedIntersection_Town12_Route12813_Weather23.tar.gz\": {\n        \"sha256\": \"6b91ddf18e1907999476ce02c3c05bf63b3892a51f4b479d209ec48f0ea33a87\",\n        \"size\": 229183430\n    },\n    \"BlockedIntersection_Town12_Route12814_Weather25.tar.gz\": {\n        \"sha256\": \"1cbff615ab99072f524f98f8e4fa119fdec53ea84556b1c3d0f80df568a119fe\",\n        \"size\": 479307288\n    },\n    \"BlockedIntersection_Town12_Route12815_Weather0.tar.gz\": {\n        \"sha256\": \"3c1ad66d40e0f947a2a7ce51a53e30f208afdd6702b2baf01ad61fc4a427fb31\",\n        \"size\": 681301262\n    },\n    \"BlockedIntersection_Town12_Route12816_Weather1.tar.gz\": {\n        \"sha256\": \"117cd27c729b5f29433eaf5b808d797ca8992b907e40745f1cd30f83548667ac\",\n        \"size\": 366547113\n    },\n    \"BlockedIntersection_Town12_Route12817_Weather2.tar.gz\": {\n        \"sha256\": \"d50316ee2e39e3f51f31bc900ca0d992236d4356f8d2ad701e7ac39371933ba6\",\n        \"size\": 339254308\n    },\n    \"BlockedIntersection_Town12_Route12818_Weather3.tar.gz\": {\n        \"sha256\": \"7acce99ed1071bd284862b3a35817c7ad5340f5860b4d7b23e99aa2fb831cd86\",\n        \"size\": 240687073\n    },\n    \"BlockedIntersection_Town12_Route12819_Weather3.tar.gz\": {\n        \"sha256\": \"7c91222ea54f11861a8899729c1e92184563eb8b4f31a37ac068446baf191618\",\n        \"size\": 271326927\n    },\n    \"BlockedIntersection_Town12_Route12824_Weather9.tar.gz\": {\n        \"sha256\": \"59215b1895148da9447d0f2626dcbe6d9d3bc8d5261d98dfe4562bf50942eac2\",\n        \"size\": 497158483\n    },\n    \"BlockedIntersection_Town12_Route12826_Weather11.tar.gz\": {\n        \"sha256\": \"d7009d58c0a1e106a0b350d300974f4c6dd324c0cf70b60f0018874759d07e13\",\n        \"size\": 296108700\n    },\n    \"BlockedIntersection_Town12_Route12828_Weather13.tar.gz\": {\n        \"sha256\": \"27c3c7b0598dc72f3cc1b1f19451c6318b7a05b0f913e9268f3dec990ebaac6c\",\n        \"size\": 211246302\n    },\n    \"BlockedIntersection_Town12_Route12830_Weather15.tar.gz\": {\n        \"sha256\": \"c8ab417e9a407c16d2da70d8d36a724e52080e6c64092e030b4f2b58b95e8a96\",\n        \"size\": 531396034\n    },\n    \"BlockedIntersection_Town12_Route12831_Weather8.tar.gz\": {\n        \"sha256\": \"0b7857ab8e48531bda5043697234a777019528b9323933676c1763304cf90abe\",\n        \"size\": 304582611\n    },\n    \"BlockedIntersection_Town12_Route12832_Weather9.tar.gz\": {\n        \"sha256\": \"679450a449477aed2662da260a19d673fa7528ffec8f949e08a77c25fde0398f\",\n        \"size\": 214960875\n    },\n    \"BlockedIntersection_Town12_Route12833_Weather18.tar.gz\": {\n        \"sha256\": \"d8ece67d84abf94ebc94d7dc5565c6c74da5be4499032f25d1bb11beef0e8149\",\n        \"size\": 491163841\n    },\n    \"BlockedIntersection_Town12_Route12835_Weather20.tar.gz\": {\n        \"sha256\": \"a649f3373923a82bfbaac3bc07a51638354ee2ec39b472a002f20883c0ac0d8f\",\n        \"size\": 293912094\n    },\n    \"BlockedIntersection_Town12_Route12840_Weather25.tar.gz\": {\n        \"sha256\": \"b8ab26b44620981c9425d8aa62a856bab61ec381c593822384a6728606082d46\",\n        \"size\": 289214860\n    },\n    \"BlockedIntersection_Town12_Route12841_Weather0.tar.gz\": {\n        \"sha256\": \"2174f9b61f6ff482302b16bb74cb80321bf6ca8996ebfb8bc2fd616c72c3c575\",\n        \"size\": 513143213\n    },\n    \"BlockedIntersection_Town12_Route12842_Weather1.tar.gz\": {\n        \"sha256\": \"d8834cc63a02d7287d44307460e80833673958401885242c345030049a725a33\",\n        \"size\": 590098879\n    },\n    \"BlockedIntersection_Town12_Route12843_Weather2.tar.gz\": {\n        \"sha256\": \"7eb64380f0174abb1e75d78727baf6d291f8fe9296f9f238253fc4542571cd87\",\n        \"size\": 422407426\n    },\n    \"BlockedIntersection_Town12_Route12844_Weather3.tar.gz\": {\n        \"sha256\": \"28a1fae42b694b6712004e20772452474a9b3a9778e997b5031a584b9f8a0234\",\n        \"size\": 282104860\n    },\n    \"BlockedIntersection_Town12_Route12846_Weather5.tar.gz\": {\n        \"sha256\": \"6be5889367726e01b808f916f6de38e21c4aab7e15e5955ae57e5f7c323209be\",\n        \"size\": 491339597\n    },\n    \"BlockedIntersection_Town12_Route12847_Weather6.tar.gz\": {\n        \"sha256\": \"1870c21afd700ede5180a3a65337343e444709608ccbe656810470118d8604b3\",\n        \"size\": 297855722\n    },\n    \"BlockedIntersection_Town12_Route12848_Weather7.tar.gz\": {\n        \"sha256\": \"bfa07f53aacd2dbe8b989039c48c362e0f5f440ca48d902a39b9cba7b02241f0\",\n        \"size\": 345663895\n    },\n    \"BlockedIntersection_Town12_Route12849_Weather8.tar.gz\": {\n        \"sha256\": \"f6dd8f6482bd865bced114d6fec79c692f0004c80587525211f98889bfd45dfd\",\n        \"size\": 298123187\n    },\n    \"BlockedIntersection_Town12_Route12850_Weather9.tar.gz\": {\n        \"sha256\": \"ee09e2b3394ccc5826c3932c86b5164e467c361220503b86848c57505b18bcb6\",\n        \"size\": 350705841\n    },\n    \"BlockedIntersection_Town12_Route12851_Weather10.tar.gz\": {\n        \"sha256\": \"b38c75c38b56707cf4b55f739fab0b44ffd30a760388af7ff538ae5e8b0483a2\",\n        \"size\": 797437471\n    },\n    \"BlockedIntersection_Town12_Route12852_Weather11.tar.gz\": {\n        \"sha256\": \"912bcd15e4d928156ba5ff7d24d0e0f96b7bdab0feba42af26ca171058df1171\",\n        \"size\": 437123807\n    },\n    \"BlockedIntersection_Town12_Route12853_Weather12.tar.gz\": {\n        \"sha256\": \"94eb28cd01b13f4eeae4dd206977c302d105f6479c02f19f0884a10d1ad72f62\",\n        \"size\": 163412337\n    },\n    \"BlockedIntersection_Town12_Route12857_Weather8.tar.gz\": {\n        \"sha256\": \"433def79def8461c428c066935d40016945e32f127560d771585fc6d959b1c4a\",\n        \"size\": 371159099\n    },\n    \"BlockedIntersection_Town12_Route12858_Weather9.tar.gz\": {\n        \"sha256\": \"899a09b455fbafcd3a4853f983fd2807f2b47de320a166bbfe36d07f8bb56875\",\n        \"size\": 335449013\n    },\n    \"BlockedIntersection_Town12_Route12859_Weather18.tar.gz\": {\n        \"sha256\": \"e066123c385409cdfe25faae831008c3ed65e6ae99e078676a0f75434a0e2270\",\n        \"size\": 548720075\n    },\n    \"BlockedIntersection_Town12_Route12860_Weather19.tar.gz\": {\n        \"sha256\": \"e084bc2bc6dabd07eec7f4886e7ab0b9a15a8fc8accf5130f9c9f37e32b4fa33\",\n        \"size\": 338978841\n    },\n    \"BlockedIntersection_Town12_Route12861_Weather20.tar.gz\": {\n        \"sha256\": \"70508bdb36ca0d05f2cc1eca304682129a8e9fc2917b2da82e2d710fa8a78a67\",\n        \"size\": 565350792\n    },\n    \"BlockedIntersection_Town12_Route12862_Weather21.tar.gz\": {\n        \"sha256\": \"cd80994f981792e3b0596a0258a5af89d839e6b64c3fa9ff8708c02e18b7054c\",\n        \"size\": 287974301\n    },\n    \"BlockedIntersection_Town12_Route12863_Weather22.tar.gz\": {\n        \"sha256\": \"a850000c465291563bf1749afc156de0779342bcbf092814234824091cf783ed\",\n        \"size\": 469089717\n    },\n    \"BlockedIntersection_Town12_Route12864_Weather23.tar.gz\": {\n        \"sha256\": \"73aa8f33b0d45035d40e32158a672e2f3ea1df680306d7f9279d48cb4ddac16a\",\n        \"size\": 438703212\n    },\n    \"BlockedIntersection_Town12_Route12865_Weather23.tar.gz\": {\n        \"sha256\": \"cce51e26b9160e98d1d90eeb5fc7f424c4f4c62b09479fd9c7bbb441a1324077\",\n        \"size\": 625248498\n    },\n    \"BlockedIntersection_Town12_Route12866_Weather25.tar.gz\": {\n        \"sha256\": \"3ce1177065785fdc8d25cae1385a70b4feb07068bdc503063d6c856e69c7d2de\",\n        \"size\": 203957474\n    },\n    \"BlockedIntersection_Town12_Route12867_Weather0.tar.gz\": {\n        \"sha256\": \"0794915e5d65320e561e29dcfa617b25aeb8ef00bc875ac73fdacb8cca0afef5\",\n        \"size\": 654932112\n    },\n    \"BlockedIntersection_Town12_Route12868_Weather1.tar.gz\": {\n        \"sha256\": \"61b519696df4bc5dded49dca94365a1f82c9e3ed0cabb852d37e262f988aa79a\",\n        \"size\": 549549870\n    },\n    \"BlockedIntersection_Town12_Route12870_Weather3.tar.gz\": {\n        \"sha256\": \"8918d8d05d6f59d2e6d1883f520bfb5021d0d6e2f5b7eb2301b87dfcfba93592\",\n        \"size\": 841563661\n    },\n    \"BlockedIntersection_Town12_Route12871_Weather3.tar.gz\": {\n        \"sha256\": \"3e67e00b7a585a1f0ae02c1811b91f1d08f6c18afc9075f75ab6eec55cbd45ce\",\n        \"size\": 1036478035\n    },\n    \"BlockedIntersection_Town12_Route12872_Weather5.tar.gz\": {\n        \"sha256\": \"3d04e4e42f27f7124cd45630958021f1a85e87d4002afa0ad966b93f5fa6b8cc\",\n        \"size\": 404152815\n    },\n    \"BlockedIntersection_Town12_Route12874_Weather7.tar.gz\": {\n        \"sha256\": \"c69d065067a95fb3ff94fca2982157fda737b9626e636e4ba7e05a1844bbe6b9\",\n        \"size\": 660005148\n    },\n    \"BlockedIntersection_Town12_Route12875_Weather8.tar.gz\": {\n        \"sha256\": \"986ee51bd46cd969bc8ab0c642b583301c9a2e5320ea1054b10dbb78866bc6af\",\n        \"size\": 352769060\n    },\n    \"BlockedIntersection_Town12_Route12876_Weather9.tar.gz\": {\n        \"sha256\": \"631c0336c7cad28d24700014182e02e106f908954fd28e5311d3843509cb4053\",\n        \"size\": 244439536\n    },\n    \"BlockedIntersection_Town12_Route12877_Weather10.tar.gz\": {\n        \"sha256\": \"18df3404711f39e9b36ec14eefba40d2bace673f9e70520f3c7cf69cb745df33\",\n        \"size\": 318190548\n    },\n    \"BlockedIntersection_Town12_Route12879_Weather12.tar.gz\": {\n        \"sha256\": \"f0f4b046d59b9dfb0e14dcd1af2f3208b972e3be19e7f35b07edea0c317dbe38\",\n        \"size\": 523042592\n    },\n    \"BlockedIntersection_Town12_Route12881_Weather14.tar.gz\": {\n        \"sha256\": \"f366dbebd893911f2a54b53c07f5f2ffdadf7f77734e23308cd0a3d397ded218\",\n        \"size\": 396959919\n    },\n    \"BlockedIntersection_Town12_Route12882_Weather15.tar.gz\": {\n        \"sha256\": \"5b917c59b86a6bce40682fda7126701e9354d7a87056d344930ea144cf469854\",\n        \"size\": 284884409\n    },\n    \"BlockedIntersection_Town12_Route12884_Weather9.tar.gz\": {\n        \"sha256\": \"0d925f9fb266fac749157aa4e51fdf2ce7aa330fdcfdd04221825783c58cb9ad\",\n        \"size\": 324791264\n    },\n    \"BlockedIntersection_Town12_Route12885_Weather18.tar.gz\": {\n        \"sha256\": \"b49e385f5f028630cdf1fdfc29e18a56c605a4dc544ae1327dbdf70be959bbe4\",\n        \"size\": 472375774\n    },\n    \"BlockedIntersection_Town12_Route12886_Weather19.tar.gz\": {\n        \"sha256\": \"3fa2dab5b6df993886a8e6a8dab5607a1f7616c80f1aa2b545a85fe97e95ed46\",\n        \"size\": 302165966\n    },\n    \"BlockedIntersection_Town12_Route12887_Weather20.tar.gz\": {\n        \"sha256\": \"ad64bb1acc4efd55e13c671387d86872b38eb9cf17b0bfd3767c325cff2d235c\",\n        \"size\": 332048609\n    },\n    \"BlockedIntersection_Town12_Route12890_Weather23.tar.gz\": {\n        \"sha256\": \"7e7b6f4d3b988c7eb43b817e9c397196a56c90bb7ce068074060516479f6fc12\",\n        \"size\": 543344372\n    },\n    \"BlockedIntersection_Town12_Route12891_Weather23.tar.gz\": {\n        \"sha256\": \"8cf71a5e2756e8dfa679c65fdc64a1ee4061ac226b7fc811c534443e16371543\",\n        \"size\": 378355181\n    },\n    \"BlockedIntersection_Town12_Route12892_Weather25.tar.gz\": {\n        \"sha256\": \"19abaa3832747052a0bccd899171087b2b2ff59ec8ff592fd0c2ee92253a760c\",\n        \"size\": 368621898\n    },\n    \"BlockedIntersection_Town12_Route12893_Weather0.tar.gz\": {\n        \"sha256\": \"875ad6236b8db3124589f7fa002747d301b2b15a2a29fdc2ce9d504d6699a762\",\n        \"size\": 321575657\n    },\n    \"BlockedIntersection_Town12_Route12894_Weather1.tar.gz\": {\n        \"sha256\": \"cd8ddef9441597125322e08980df6f54f707562b88b32da158feef78740305e9\",\n        \"size\": 336292445\n    },\n    \"BlockedIntersection_Town12_Route12895_Weather2.tar.gz\": {\n        \"sha256\": \"06f4432f6eccb76ea84433a12895d6a0711d4297184018ad384d09f4ab65f8e0\",\n        \"size\": 343872488\n    },\n    \"BlockedIntersection_Town12_Route12896_Weather3.tar.gz\": {\n        \"sha256\": \"fd69ae0806dc347fbf4a1b6c636a53631508aa78d2335e4e76cddaa092c7c3fc\",\n        \"size\": 559306391\n    },\n    \"BlockedIntersection_Town12_Route12897_Weather3.tar.gz\": {\n        \"sha256\": \"63d515eefa6e5820d123268150c136ccec5095936bdb5111acbfd7db3318b258\",\n        \"size\": 589001525\n    },\n    \"BlockedIntersection_Town12_Route12898_Weather5.tar.gz\": {\n        \"sha256\": \"9350301d0827ba297334cc7d0a1dae2f02a16c6bf1f30199edf530a6342552db\",\n        \"size\": 520522635\n    },\n    \"BlockedIntersection_Town12_Route12901_Weather8.tar.gz\": {\n        \"sha256\": \"08a1a3c075ca8b2ca2bf1b99a60ddf0553eceecfaabc9b1f402ca986f947184b\",\n        \"size\": 444410228\n    },\n    \"BlockedIntersection_Town12_Route12902_Weather9.tar.gz\": {\n        \"sha256\": \"2d1e9755217bae3e1dde85c314e8fb8af80c13f20e05698a3d09d4e50c7d5b3c\",\n        \"size\": 418931387\n    },\n    \"BlockedIntersection_Town12_Route12903_Weather10.tar.gz\": {\n        \"sha256\": \"346d094372c6e4f297a11f3d9adf54cf67a4d574b853625b261669e1a1afc271\",\n        \"size\": 632921355\n    },\n    \"BlockedIntersection_Town12_Route12904_Weather11.tar.gz\": {\n        \"sha256\": \"8ac5233739419ac5ba3e0a58c2cb8c0a3163b6c473b48f25d1f572ddbe064bd8\",\n        \"size\": 263054040\n    },\n    \"BlockedIntersection_Town12_Route12905_Weather12.tar.gz\": {\n        \"sha256\": \"cbabea1b8eb66d7574ac0c078061e2eea77b6084d6778be11e444bd1a414fa33\",\n        \"size\": 192504334\n    },\n    \"BlockedIntersection_Town12_Route12906_Weather13.tar.gz\": {\n        \"sha256\": \"ab4313d8641a72db0aac06814b33beb5eab4d7b60b59bb6a957a28fd11ef628a\",\n        \"size\": 400738011\n    },\n    \"BlockedIntersection_Town12_Route12907_Weather14.tar.gz\": {\n        \"sha256\": \"1fc04d9fa569eee0b6f491f6361c244fce7a3f227537a6eea988979b84333d6c\",\n        \"size\": 465500302\n    },\n    \"BlockedIntersection_Town12_Route12908_Weather15.tar.gz\": {\n        \"sha256\": \"b60e350bcd7e94789b413218e2d629622e1f938892d2b0ae0277c32e6feb7e34\",\n        \"size\": 449090396\n    },\n    \"BlockedIntersection_Town12_Route12909_Weather8.tar.gz\": {\n        \"sha256\": \"2abc43507b5cc2bc99fe7529ef22f3aa4cee874264f552bdc47461dee34798fd\",\n        \"size\": 337179679\n    },\n    \"BlockedIntersection_Town12_Route12910_Weather9.tar.gz\": {\n        \"sha256\": \"572ef0fefc3541348fc53a1c65a0571e0ea17fcab891563651a0d72ed817e373\",\n        \"size\": 418416472\n    },\n    \"BlockedIntersection_Town12_Route12911_Weather18.tar.gz\": {\n        \"sha256\": \"1c9cf9beeb6aebfa0ad222eb41d386813edbbcc1213abf581cdc1857375dd59d\",\n        \"size\": 373685064\n    },\n    \"BlockedIntersection_Town12_Route12913_Weather20.tar.gz\": {\n        \"sha256\": \"ee1efee85efd310bc4ef9191631b48cf4e903fe8ae30c187969bdfc1d56abcd7\",\n        \"size\": 258165864\n    },\n    \"BlockedIntersection_Town12_Route12915_Weather22.tar.gz\": {\n        \"sha256\": \"b23313d22e6e0c7ba7c4967da1bb44115781fbed21bd162b48570095bf76b054\",\n        \"size\": 574668370\n    },\n    \"BlockedIntersection_Town12_Route12917_Weather23.tar.gz\": {\n        \"sha256\": \"2404ac972e151d5a40daf47698eeca9ffe51a4485bc59df6c7c1ac541410eceb\",\n        \"size\": 514756827\n    },\n    \"BlockedIntersection_Town12_Route12918_Weather25.tar.gz\": {\n        \"sha256\": \"2e16d053a8bde7a74d55a0116e800d8590adea85d7191dfcae67f28207e9f696\",\n        \"size\": 570931613\n    },\n    \"BlockedIntersection_Town12_Route12920_Weather1.tar.gz\": {\n        \"sha256\": \"34dbb5fe0409bc0cd07d6a77febb52fd727a2a22c938b5e58b69b91238a52ca7\",\n        \"size\": 255175393\n    },\n    \"BlockedIntersection_Town12_Route12921_Weather2.tar.gz\": {\n        \"sha256\": \"fd912fc6ec3c0568554bd4945a3dd592708c2a0fb4f7cbc358db2a4172bd84c3\",\n        \"size\": 328337432\n    },\n    \"BlockedIntersection_Town12_Route12922_Weather3.tar.gz\": {\n        \"sha256\": \"0b00fd59cf7499a2c31a98bb1737248641b10d984a0cb3d1598b1566078f2756\",\n        \"size\": 329381030\n    },\n    \"BlockedIntersection_Town12_Route12923_Weather3.tar.gz\": {\n        \"sha256\": \"2b66107fc169e55292de71f44b4c6328cb3458a4128f7928efe3d719fbe0145c\",\n        \"size\": 496250633\n    },\n    \"BlockedIntersection_Town12_Route12924_Weather5.tar.gz\": {\n        \"sha256\": \"eaad114d80a97ce0f36c387f518a7d05609bb47fa977cadcd3bbcb9264a93630\",\n        \"size\": 308770442\n    },\n    \"BlockedIntersection_Town12_Route12928_Weather9.tar.gz\": {\n        \"sha256\": \"90c8c7992ab7c5b480aa40ede3ab1649c135a1c8bfca6c973ca5d61102d91105\",\n        \"size\": 204868415\n    },\n    \"BlockedIntersection_Town12_Route12929_Weather10.tar.gz\": {\n        \"sha256\": \"9b5449ec28e794916040fa0ec6142f718a5544779ed3f1b06562d3d77f83fd54\",\n        \"size\": 355944865\n    },\n    \"BlockedIntersection_Town12_Route12930_Weather11.tar.gz\": {\n        \"sha256\": \"cc6b47340a6e729de199c282055123a410feb30df08d94abce039f53897c1195\",\n        \"size\": 339256697\n    },\n    \"BlockedIntersection_Town12_Route12931_Weather12.tar.gz\": {\n        \"sha256\": \"4c13e430b6d5344299971981bfc839c47e2849965789d090c822d35045c8d0ab\",\n        \"size\": 399487540\n    },\n    \"BlockedIntersection_Town12_Route12932_Weather13.tar.gz\": {\n        \"sha256\": \"b8be4497fda02272c17fe6844b1d93e9f0d33a1a5433da23a8a80f9909d0756b\",\n        \"size\": 276586603\n    },\n    \"BlockedIntersection_Town12_Route12933_Weather14.tar.gz\": {\n        \"sha256\": \"32f7ef8582f16d85b6c4190022d2703d3f03831df7a63177aac1a8328608e2e8\",\n        \"size\": 926955708\n    },\n    \"BlockedIntersection_Town12_Route12934_Weather15.tar.gz\": {\n        \"sha256\": \"78b9affdc32cbc7cbaeb7bc166fcd7c20a89d593a601db75e3eda59fbb9dbffa\",\n        \"size\": 307850202\n    },\n    \"BlockedIntersection_Town12_Route12935_Weather8.tar.gz\": {\n        \"sha256\": \"bf8966a4e73fec74896392102b80a9c992d09795e59a9cf04245145f7853aa69\",\n        \"size\": 369855255\n    },\n    \"BlockedIntersection_Town12_Route12938_Weather19.tar.gz\": {\n        \"sha256\": \"449964ac4a2750165ddd368b97305aaaeaf3726c655af5a633860fd404ce4e67\",\n        \"size\": 433062405\n    },\n    \"BlockedIntersection_Town12_Route12939_Weather20.tar.gz\": {\n        \"sha256\": \"da430827e29b3545861fa68095d21e5602548948bdf1d418d53b33257590e2d4\",\n        \"size\": 309161939\n    },\n    \"BlockedIntersection_Town12_Route12940_Weather21.tar.gz\": {\n        \"sha256\": \"fe132e040db609f97fe02bf0ebb8c24a4da6c9f369dc143e70ac0a7fd1800d61\",\n        \"size\": 138901327\n    },\n    \"BlockedIntersection_Town12_Route12942_Weather23.tar.gz\": {\n        \"sha256\": \"304a2c4e0bd44ab8a7e13106287fad89e6fbc090a8729e009d78473fd9396e2b\",\n        \"size\": 300517378\n    },\n    \"BlockedIntersection_Town12_Route12945_Weather0.tar.gz\": {\n        \"sha256\": \"e106c2e1a84867db1661bbf812b5a00a50599e693532a687ee0c6f32fd471240\",\n        \"size\": 246744419\n    },\n    \"BlockedIntersection_Town12_Route12947_Weather2.tar.gz\": {\n        \"sha256\": \"fe86c5a8a09d4fde2b8cfdfe156ec13e1768635ec77c29825dc131a57b9438e4\",\n        \"size\": 562885502\n    },\n    \"BlockedIntersection_Town12_Route12948_Weather3.tar.gz\": {\n        \"sha256\": \"4b70a78cb7822f4cb55eb35956a325b88fddc2631d632e68408fe5a231430f5e\",\n        \"size\": 451537931\n    },\n    \"BlockedIntersection_Town12_Route12949_Weather3.tar.gz\": {\n        \"sha256\": \"a8549c21b0ced9ee6266f74a14ae04a9ff33ab5a6ef33034de2f2c385594f6f8\",\n        \"size\": 258658477\n    },\n    \"BlockedIntersection_Town12_Route12950_Weather5.tar.gz\": {\n        \"sha256\": \"fd5ed7a86875103f82fed52160419097ce3720dc7f0e817e89b0bbdc36e1e4c2\",\n        \"size\": 617639366\n    },\n    \"BlockedIntersection_Town12_Route12952_Weather7.tar.gz\": {\n        \"sha256\": \"489bd8af9aef95420ce771b3ce9840f2b7a43d1137ee8e05702a34d219adb5b8\",\n        \"size\": 470542282\n    },\n    \"BlockedIntersection_Town12_Route12954_Weather9.tar.gz\": {\n        \"sha256\": \"9665ce7f521b54bb6c6ab75fc60f5dcc9074285d98f8b603c9520214dac933e5\",\n        \"size\": 229215281\n    },\n    \"BlockedIntersection_Town12_Route12956_Weather11.tar.gz\": {\n        \"sha256\": \"f3674c13f487bf721770e1e5cb77bbd85f817bf1d335d214f0c7e63b7091765d\",\n        \"size\": 285334703\n    },\n    \"BlockedIntersection_Town12_Route12958_Weather13.tar.gz\": {\n        \"sha256\": \"351f62aea459bd31bd34dbb02a977a1761666257c1507c1316cc01e7210ee8c1\",\n        \"size\": 530382015\n    },\n    \"BlockedIntersection_Town12_Route12960_Weather15.tar.gz\": {\n        \"sha256\": \"f5d6a8e830247fa270110f9aec2413d31cb2230108c930b2713a0894a7d3868c\",\n        \"size\": 479034302\n    },\n    \"BlockedIntersection_Town12_Route12964_Weather19.tar.gz\": {\n        \"sha256\": \"d787bc5491e5356a0781e0907521824054d7c189dd633bc167f4d7abb0e12735\",\n        \"size\": 594304550\n    },\n    \"BlockedIntersection_Town12_Route12965_Weather20.tar.gz\": {\n        \"sha256\": \"1793a4b40cf5ff8d4ac3ab7f67030c5588734c89e25c8dd0dbbd11ca7b4fd1bf\",\n        \"size\": 718997609\n    },\n    \"BlockedIntersection_Town12_Route12966_Weather21.tar.gz\": {\n        \"sha256\": \"03aa1a7782fe5283e5d5419104d3d91ff7f1c87734b1d80563c0f8af99c6cba2\",\n        \"size\": 305200572\n    },\n    \"BlockedIntersection_Town12_Route12969_Weather23.tar.gz\": {\n        \"sha256\": \"4610db16019c732e6e02220e400cb3d8a51ca33b9dcfda5eae743d25022cc55c\",\n        \"size\": 307551100\n    },\n    \"BlockedIntersection_Town12_Route12971_Weather0.tar.gz\": {\n        \"sha256\": \"659b6be9e6e82edaf2f055a39c9fb402e7a60b392ea084807fad29078f689df8\",\n        \"size\": 342252012\n    },\n    \"BlockedIntersection_Town12_Route12972_Weather1.tar.gz\": {\n        \"sha256\": \"c9e099f548b5ab52c9f3ef809320e071cd70179f307555df98a30c20681a471e\",\n        \"size\": 471559984\n    },\n    \"BlockedIntersection_Town12_Route12973_Weather2.tar.gz\": {\n        \"sha256\": \"99b36b5f5ed1aa401ad3994fc190e2da007fd96b0f4d9073395713edc88885a8\",\n        \"size\": 476133109\n    },\n    \"BlockedIntersection_Town12_Route12974_Weather3.tar.gz\": {\n        \"sha256\": \"23d226089b9ed1b419bcdc4d8fa707840c98767c844fe4b9d1725657f64309cb\",\n        \"size\": 603201173\n    },\n    \"BlockedIntersection_Town12_Route12975_Weather3.tar.gz\": {\n        \"sha256\": \"32b0e0a0ddb98465968b2ed1335fc7c906cf168d4135a947f2999da04e3ebfb6\",\n        \"size\": 430534027\n    },\n    \"BlockedIntersection_Town12_Route12976_Weather5.tar.gz\": {\n        \"sha256\": \"91535234f29aebf0189defdd4c14bd14697a75472a5e8365538376435d75ebca\",\n        \"size\": 266024354\n    },\n    \"BlockedIntersection_Town12_Route12978_Weather7.tar.gz\": {\n        \"sha256\": \"22c0b5ab117ff3ab0eca12e7a53fe70dffe3b7d1fca676f5964211f25faec310\",\n        \"size\": 306900919\n    },\n    \"BlockedIntersection_Town12_Route12979_Weather8.tar.gz\": {\n        \"sha256\": \"0530bdfb7e63bf828fb5c7aa3dcc0847260ec7aad17583b7a039745b0f16f907\",\n        \"size\": 200633466\n    },\n    \"BlockedIntersection_Town12_Route12980_Weather9.tar.gz\": {\n        \"sha256\": \"f9794107179dbc2f40a2c50fbc5aced013d1e56bc37f31fad72d044710649004\",\n        \"size\": 322036295\n    },\n    \"BlockedIntersection_Town12_Route12981_Weather10.tar.gz\": {\n        \"sha256\": \"e548d35be991954b1d9c71955f5f194621fb89b5fa9f7a1fd5fa2c9f30d1d82a\",\n        \"size\": 457962771\n    },\n    \"BlockedIntersection_Town12_Route12982_Weather11.tar.gz\": {\n        \"sha256\": \"34fc00b520715abc9df88c679e94e1ce5867c8a5381d69e02c317c09ed75f5f1\",\n        \"size\": 264645790\n    },\n    \"BlockedIntersection_Town12_Route12983_Weather12.tar.gz\": {\n        \"sha256\": \"a0645eda0faaf3517cc0bd21655094e0138de9cab33561945c9a21fda53d7ef3\",\n        \"size\": 442373217\n    },\n    \"BlockedIntersection_Town12_Route12984_Weather13.tar.gz\": {\n        \"sha256\": \"4989f5e43b4c452dd5e49a30bd3b2dfe9f116564f9259715fd1c4de616c7ea4d\",\n        \"size\": 606859202\n    },\n    \"BlockedIntersection_Town12_Route12986_Weather15.tar.gz\": {\n        \"sha256\": \"f895356cbe1f1d2e5d611939e2a70ebd188769c47bdbacd6416cb7474e7a2383\",\n        \"size\": 271583881\n    },\n    \"BlockedIntersection_Town12_Route12987_Weather8.tar.gz\": {\n        \"sha256\": \"83347f72a67e5c3303eb32693948a16d661adf34728186d0467f6a6744dc35e7\",\n        \"size\": 206785874\n    },\n    \"BlockedIntersection_Town12_Route12989_Weather18.tar.gz\": {\n        \"sha256\": \"1aa67e63db9d2bf38d2a5d04822a5722d215a61fe2312ae88675de77963a78e4\",\n        \"size\": 467676772\n    },\n    \"BlockedIntersection_Town12_Route12990_Weather19.tar.gz\": {\n        \"sha256\": \"6c0245e3fd8dd484a02e35c30662fd884707d2edfc8ab044d106653fb1738360\",\n        \"size\": 265485211\n    },\n    \"BlockedIntersection_Town12_Route12994_Weather23.tar.gz\": {\n        \"sha256\": \"9834474928c16f854d55a8bbe377cab19ad9490a3b80850a233b701790e1cc3d\",\n        \"size\": 441084277\n    },\n    \"BlockedIntersection_Town12_Route12995_Weather23.tar.gz\": {\n        \"sha256\": \"b56c988757aca550d134de85958585c5f0ad5bffe162cf90e977607499f786c4\",\n        \"size\": 653436973\n    },\n    \"BlockedIntersection_Town12_Route12996_Weather25.tar.gz\": {\n        \"sha256\": \"8a625a10c3ccca77d78830d45c5c214ffaeb9213483fbd5eef6b11f42e3859db\",\n        \"size\": 338234955\n    },\n    \"BlockedIntersection_Town12_Route12997_Weather0.tar.gz\": {\n        \"sha256\": \"797d82e8312d246401eb1acabc07d53e8abb3a41d74ee6b3ec2b3f7ea1ce6789\",\n        \"size\": 714221036\n    },\n    \"BlockedIntersection_Town12_Route12998_Weather1.tar.gz\": {\n        \"sha256\": \"bb08663eb4ae522294f3b8c35c426379e9951888916a58b8eb21de18e9fd7a88\",\n        \"size\": 328683360\n    },\n    \"BlockedIntersection_Town12_Route12999_Weather2.tar.gz\": {\n        \"sha256\": \"2a85efea68a48861bd3b480ae90fe243f2eabab9521a53a696b871a6e9d05baf\",\n        \"size\": 373915429\n    },\n    \"BlockedIntersection_Town12_Route13000_Weather3.tar.gz\": {\n        \"sha256\": \"e9b9b037e6852dc78614438291126b5fb08ffe8c90f90732bc2edc4a02f79fe5\",\n        \"size\": 557990044\n    },\n    \"BlockedIntersection_Town12_Route13001_Weather3.tar.gz\": {\n        \"sha256\": \"1e61d9f37fcb316d548b03a5c87ce3495e3a906d086167e570a6fd569b513303\",\n        \"size\": 347201712\n    },\n    \"BlockedIntersection_Town12_Route13004_Weather7.tar.gz\": {\n        \"sha256\": \"829b987cf6844c4c0a4a3b5a37175af252949dc4984d4f2b1372bfe4286ab0c8\",\n        \"size\": 315563452\n    },\n    \"BlockedIntersection_Town12_Route13005_Weather8.tar.gz\": {\n        \"sha256\": \"1f9a8bed9eba85bd231cb68635e6471e04d7cbb33b4986f08f2913d0d86d072e\",\n        \"size\": 256168206\n    },\n    \"BlockedIntersection_Town12_Route13006_Weather9.tar.gz\": {\n        \"sha256\": \"8e4725d8948dea71ee42f9afa2887ceaef0b6ea1e2228fa9cc2c8510852be442\",\n        \"size\": 278602100\n    },\n    \"BlockedIntersection_Town12_Route13007_Weather10.tar.gz\": {\n        \"sha256\": \"e312dcbdd878881eb9467c3196b041af492cec27f23b9cf86ad60d5354887f46\",\n        \"size\": 656623091\n    },\n    \"BlockedIntersection_Town12_Route13008_Weather11.tar.gz\": {\n        \"sha256\": \"ba67ec648d112718cbc70a555cc718832c8ef0947dc52f979bc02c0068e5cebc\",\n        \"size\": 521652541\n    },\n    \"BlockedIntersection_Town12_Route13010_Weather13.tar.gz\": {\n        \"sha256\": \"9fcdca2228fc9d1509983614dbb4ca3586e235fba360e08911658124b21a1ada\",\n        \"size\": 642912014\n    },\n    \"BlockedIntersection_Town12_Route13011_Weather14.tar.gz\": {\n        \"sha256\": \"6de51cbdfcb204ed7dee577b59e381459e757405168730a72bdf084e82d8ce20\",\n        \"size\": 146021161\n    },\n    \"BlockedIntersection_Town12_Route13012_Weather15.tar.gz\": {\n        \"sha256\": \"47bdd88d2010d8a08e521558d789bfca57c4f48fdd992fe876816aabbb108fc9\",\n        \"size\": 508661443\n    },\n    \"BlockedIntersection_Town12_Route13014_Weather9.tar.gz\": {\n        \"sha256\": \"d26d5bc6721d94c87154192e069fa6cba9cd17bbc9b60990d706ab914d8301a3\",\n        \"size\": 360029366\n    },\n    \"BlockedIntersection_Town12_Route13017_Weather20.tar.gz\": {\n        \"sha256\": \"8a238038b948799519fdd4621fcad5baff426c62d2d0ead8919f7174df3769ba\",\n        \"size\": 258976935\n    },\n    \"BlockedIntersection_Town12_Route13018_Weather21.tar.gz\": {\n        \"sha256\": \"176dcb05ef798dcbdd931f4cc21b6847e5c9049cc2193fcea71ab7af1f9286a9\",\n        \"size\": 459479830\n    },\n    \"BlockedIntersection_Town12_Route13019_Weather22.tar.gz\": {\n        \"sha256\": \"42f4ec3e7da6c25a964f1fbf7e750f9201de96f04c3bd301a6201c9c3dde7727\",\n        \"size\": 343245204\n    },\n    \"BlockedIntersection_Town12_Route13021_Weather23.tar.gz\": {\n        \"sha256\": \"5bf3c33ad8e6f21c4baf81237b5db85e7fcb7623fda98c1812de97835735b070\",\n        \"size\": 527694651\n    },\n    \"BlockedIntersection_Town12_Route13022_Weather25.tar.gz\": {\n        \"sha256\": \"0e15f39c9f95836b690f5ed2d8c4db295d243ec1dcc182f668210be19c3f5651\",\n        \"size\": 603667264\n    },\n    \"BlockedIntersection_Town12_Route13023_Weather0.tar.gz\": {\n        \"sha256\": \"2572235755b9e95ffe837717f4c90e1f3a17ab325ca62bdda81a397fc35cd42b\",\n        \"size\": 326812040\n    },\n    \"BlockedIntersection_Town12_Route13024_Weather1.tar.gz\": {\n        \"sha256\": \"2144908b8ec9480112084e8564863c745a22597df24a2544c18bcf3e38be4a37\",\n        \"size\": 542928000\n    },\n    \"BlockedIntersection_Town12_Route13027_Weather3.tar.gz\": {\n        \"sha256\": \"f3e1aea256175b5ccb3149f9045097a22da8c2f4397bd799ab71572cdacd944f\",\n        \"size\": 289601322\n    },\n    \"BlockedIntersection_Town12_Route13028_Weather5.tar.gz\": {\n        \"sha256\": \"211b9fd8957d74358e10eed126ca00142cbd5e21fb66d2a0bea9ede3a4302576\",\n        \"size\": 626832475\n    },\n    \"BlockedIntersection_Town12_Route13029_Weather6.tar.gz\": {\n        \"sha256\": \"f072cbf4619a2b8786cb24b414039f38da0bc52649cb74caecf04a2bd49b6a4f\",\n        \"size\": 525605763\n    },\n    \"BlockedIntersection_Town12_Route13030_Weather7.tar.gz\": {\n        \"sha256\": \"ad63b7aedd33c1883a786c5a113cf929dc1fb521af5a8c62ae81e030b2e8d017\",\n        \"size\": 1077823502\n    },\n    \"BlockedIntersection_Town12_Route13032_Weather9.tar.gz\": {\n        \"sha256\": \"698a28323d52288f8c174a62dde0fd0a36c7018acd5ff5aa1ea18be255261e62\",\n        \"size\": 515574165\n    },\n    \"BlockedIntersection_Town12_Route13033_Weather10.tar.gz\": {\n        \"sha256\": \"0aaf060edb37d02d6b45aafd46fe9ac6b4c917b45e1df239b5d1a1859f24a8d2\",\n        \"size\": 302927481\n    },\n    \"BlockedIntersection_Town12_Route13034_Weather11.tar.gz\": {\n        \"sha256\": \"be64d5d63a5cd01e6f4f83c84fe4ccbeba5331889d9179fc04f18efc7eec3b90\",\n        \"size\": 393221991\n    },\n    \"BlockedIntersection_Town12_Route13036_Weather13.tar.gz\": {\n        \"sha256\": \"a04df486fa77e10e29023dbb8b165696cbf75ee3d3e180ba9fe812e69c2de1e5\",\n        \"size\": 383065663\n    },\n    \"BlockedIntersection_Town12_Route13037_Weather14.tar.gz\": {\n        \"sha256\": \"e8d276d14ecdc5ca46e5b0f572f80edb3460a8f98693307e189b63476a2701e5\",\n        \"size\": 297851695\n    },\n    \"BlockedIntersection_Town12_Route13039_Weather8.tar.gz\": {\n        \"sha256\": \"eb4beb391fe55a83397b28a5b6145c76a87fce8c36c59f059f4cfb03c4baef8d\",\n        \"size\": 306533605\n    },\n    \"BlockedIntersection_Town12_Route13040_Weather9.tar.gz\": {\n        \"sha256\": \"4770d67fac8974bfbfa9f1995a5902287e776180bb808b2bc51297e74c5897d6\",\n        \"size\": 447836458\n    },\n    \"BlockedIntersection_Town12_Route13041_Weather18.tar.gz\": {\n        \"sha256\": \"0c158b3525b2f69361bb4bd8497554f02073f3d6d71b3dcf62f8625935be1ba1\",\n        \"size\": 352635630\n    },\n    \"BlockedIntersection_Town12_Route13042_Weather19.tar.gz\": {\n        \"sha256\": \"2f0d9583185d0f0445aa8770c00adf4d9888401b2d0167fc1f7abcce180d36ec\",\n        \"size\": 250268234\n    },\n    \"BlockedIntersection_Town12_Route13043_Weather20.tar.gz\": {\n        \"sha256\": \"479c097b2bdf5f4620104357871f0c0cc1a4cd60b129afa7857314fe6a011848\",\n        \"size\": 234677617\n    },\n    \"BlockedIntersection_Town12_Route13044_Weather21.tar.gz\": {\n        \"sha256\": \"5a6638918abf57af1ef55c9b0885d792a6ef05bbdb87f312da5c2bc86293d956\",\n        \"size\": 211376406\n    },\n    \"BlockedIntersection_Town12_Route13045_Weather22.tar.gz\": {\n        \"sha256\": \"3a1fa94b5cc476675ad87185c63aebf64a43e3570f0f580ce232ed7757567d62\",\n        \"size\": 279211982\n    },\n    \"BlockedIntersection_Town12_Route13046_Weather23.tar.gz\": {\n        \"sha256\": \"fcbcb94b6794fe457cb6207c77a35d3a51e296721fe10c74d4f425f43d9ca1c2\",\n        \"size\": 315956239\n    },\n    \"BlockedIntersection_Town12_Route13047_Weather23.tar.gz\": {\n        \"sha256\": \"fba2dc631ffabe71e71a3fc602af816fbf4c69dbff9c855cf61af59ee6107cf8\",\n        \"size\": 298260753\n    },\n    \"BlockedIntersection_Town12_Route13048_Weather25.tar.gz\": {\n        \"sha256\": \"565f164ba06eec83209639271c6ed033b13e9e0211376d883af0436ec5e45849\",\n        \"size\": 362621656\n    },\n    \"BlockedIntersection_Town12_Route13049_Weather0.tar.gz\": {\n        \"sha256\": \"4fdddc90c42e770c03eee37f0b422c3262335075a07d3bf863cbbce5ddd9d1b5\",\n        \"size\": 761267662\n    },\n    \"BlockedIntersection_Town12_Route13050_Weather1.tar.gz\": {\n        \"sha256\": \"7150d3042e02592451960917d44338a9fe4714bfc8c305901c06b62c33507696\",\n        \"size\": 430258824\n    },\n    \"BlockedIntersection_Town12_Route13051_Weather2.tar.gz\": {\n        \"sha256\": \"5eb569b22314800bffb50fc906bf87a551778e8553b3b927a5c0dee577240fee\",\n        \"size\": 629682917\n    },\n    \"BlockedIntersection_Town12_Route13052_Weather3.tar.gz\": {\n        \"sha256\": \"468ad6edbb975d0dc8872c7e1889f2feac8a7dda497ee3c8686ed28772b2af49\",\n        \"size\": 408203444\n    },\n    \"BlockedIntersection_Town12_Route13053_Weather3.tar.gz\": {\n        \"sha256\": \"9672e3e8b39410bc94d9f21969c972231efb6627fca0d80b90eb34908b2859e9\",\n        \"size\": 336057895\n    },\n    \"BlockedIntersection_Town12_Route13054_Weather5.tar.gz\": {\n        \"sha256\": \"5873e4e404949bedea90e43bbf1d6ed70655e6f6caa788737f95960ac10d1d0d\",\n        \"size\": 241643588\n    },\n    \"BlockedIntersection_Town12_Route13055_Weather6.tar.gz\": {\n        \"sha256\": \"8160cd2d8883bda30b3cb600edb41990d848b59fa72b2e90b30269de66193484\",\n        \"size\": 636752181\n    },\n    \"BlockedIntersection_Town12_Route13056_Weather7.tar.gz\": {\n        \"sha256\": \"e899eecf736db148355ea7d1c98e3bc4d449f5bbd3a84217fff164076f8f8351\",\n        \"size\": 461340995\n    },\n    \"BlockedIntersection_Town12_Route13057_Weather8.tar.gz\": {\n        \"sha256\": \"fbc61800ad2ae9af7abdd78b07dbe67d1b72b3b6d1ac15aaa43ecff5de225dea\",\n        \"size\": 310811107\n    },\n    \"BlockedIntersection_Town12_Route13059_Weather10.tar.gz\": {\n        \"sha256\": \"f29d8b2394ed2f052efb81c9c5c98e6aa9908ce45833110540c78f1d1c88460e\",\n        \"size\": 266226549\n    },\n    \"BlockedIntersection_Town12_Route13060_Weather11.tar.gz\": {\n        \"sha256\": \"227fb1954ba03de57ccfc801c8b3750af3ac57b8ff561eb65ef3f1d51a7ac12c\",\n        \"size\": 291833226\n    },\n    \"BlockedIntersection_Town12_Route13063_Weather14.tar.gz\": {\n        \"sha256\": \"1ede7320da45fb48afaefffc134fed2e4a373cbcf1001ddbb857fab38c40ebed\",\n        \"size\": 205430799\n    },\n    \"BlockedIntersection_Town12_Route13064_Weather15.tar.gz\": {\n        \"sha256\": \"5ed15b2cc62f4e7c73c4de97b400fecebcef7d97d692bdc9d5ad399b7d182152\",\n        \"size\": 713155089\n    },\n    \"BlockedIntersection_Town12_Route13065_Weather8.tar.gz\": {\n        \"sha256\": \"0a78a8f4284bd2f0026764f5116644eef233526d7f48d690fc7db77b47e0c17a\",\n        \"size\": 227725881\n    },\n    \"BlockedIntersection_Town12_Route13066_Weather9.tar.gz\": {\n        \"sha256\": \"99d7d037eed9b514442bbdc025212dbaec44b9a39cd8aa3411a8efd278a4cf32\",\n        \"size\": 318470807\n    },\n    \"BlockedIntersection_Town12_Route13067_Weather18.tar.gz\": {\n        \"sha256\": \"0fc4b8eb6d8826ece413d7568c75aec84c98266a19e897b9981d05d9aeeb4ec9\",\n        \"size\": 269294614\n    },\n    \"BlockedIntersection_Town12_Route13068_Weather19.tar.gz\": {\n        \"sha256\": \"ed614c910b97827d8c315ce0e20d31652d6c08122c21ec483385421e5fe4c3a8\",\n        \"size\": 347055152\n    },\n    \"BlockedIntersection_Town12_Route13070_Weather21.tar.gz\": {\n        \"sha256\": \"6b0c5caff8c915a6bd8033edf587d08c06b3dc4ad38901bffb325f4d8ebebde3\",\n        \"size\": 345895723\n    },\n    \"BlockedIntersection_Town12_Route13071_Weather22.tar.gz\": {\n        \"sha256\": \"01176b8527ed18d5482928a8c7e897ef0ffd165fc81e76a4361f2a5b0ba7557b\",\n        \"size\": 452886186\n    },\n    \"BlockedIntersection_Town12_Route13072_Weather23.tar.gz\": {\n        \"sha256\": \"d414038feeadb50928770db4ad6bdef38286e68b6a29bb295fd99bff38779d6c\",\n        \"size\": 419198984\n    },\n    \"BlockedIntersection_Town12_Route13073_Weather23.tar.gz\": {\n        \"sha256\": \"e5a52315d5c4402f2d5dfc87e4db2967a112e9d3264cef3773fb59a2c4e96495\",\n        \"size\": 330199429\n    },\n    \"BlockedIntersection_Town12_Route13074_Weather25.tar.gz\": {\n        \"sha256\": \"beec1dea779077cf564292fd6d9b0c99453c9145e0344a7568128e67748ee6e8\",\n        \"size\": 380123292\n    },\n    \"BlockedIntersection_Town12_Route13075_Weather0.tar.gz\": {\n        \"sha256\": \"ef85e89e5406994cd95bc7f0966610f5325b2086c04774cb3743bcd5f614c130\",\n        \"size\": 342240447\n    },\n    \"BlockedIntersection_Town12_Route13077_Weather2.tar.gz\": {\n        \"sha256\": \"21f15f8230f6a9ca8b7da76db152537670334b8d4f554aca829ae219b0035b32\",\n        \"size\": 389200192\n    },\n    \"BlockedIntersection_Town12_Route13078_Weather3.tar.gz\": {\n        \"sha256\": \"18ef6bccb6b5caefc9d15347555afd332fd3a5ab3dde1ea11be228bad86ecd8e\",\n        \"size\": 322314726\n    },\n    \"BlockedIntersection_Town12_Route13080_Weather5.tar.gz\": {\n        \"sha256\": \"5b2ae33873eb68424f3c1eac91a90dd0d922082e631eebe06ca01d708cdb7467\",\n        \"size\": 319302196\n    },\n    \"BlockedIntersection_Town12_Route13081_Weather6.tar.gz\": {\n        \"sha256\": \"4457b2428e0c2f72282c1745c889b0b9e06e5966ce1eb85f88d99325cadb7356\",\n        \"size\": 331312003\n    },\n    \"BlockedIntersection_Town12_Route13082_Weather7.tar.gz\": {\n        \"sha256\": \"fc4fafada442fa527e6b4c7638008a8cd1546d2c7c40606b956b7dc7de3ba113\",\n        \"size\": 605036010\n    },\n    \"BlockedIntersection_Town12_Route13084_Weather9.tar.gz\": {\n        \"sha256\": \"8fc7d9aece3c5dc85fee9137f4fa213c1189e424805daf18510b7f5b7697f974\",\n        \"size\": 213175789\n    },\n    \"BlockedIntersection_Town12_Route13085_Weather10.tar.gz\": {\n        \"sha256\": \"9c7cb4071a94fd5118ccd09285c143dadc4c84ea6a9c2ad6a2f91ea0e406c15a\",\n        \"size\": 191052779\n    },\n    \"BlockedIntersection_Town12_Route13086_Weather11.tar.gz\": {\n        \"sha256\": \"2d296f80ffba526a740a83105d3bdacbdeca2900eb5f7a7349924d84fa7dcbb1\",\n        \"size\": 335253827\n    },\n    \"BlockedIntersection_Town12_Route13087_Weather12.tar.gz\": {\n        \"sha256\": \"ff3874dde6c9ace4c812db9181b1a7e76c5febd28982e0de4a801efde3f940e5\",\n        \"size\": 321379716\n    },\n    \"BlockedIntersection_Town12_Route13088_Weather13.tar.gz\": {\n        \"sha256\": \"18bb83295c605bb70839764ebf4d3c19e84df4eaba09cb8de3f55e9d5879160a\",\n        \"size\": 480532316\n    },\n    \"BlockedIntersection_Town12_Route13089_Weather14.tar.gz\": {\n        \"sha256\": \"1afdd8a0065e834688b1ab3aa1226a91e50c4cab687531e3e53250225e4b45fb\",\n        \"size\": 348904496\n    },\n    \"BlockedIntersection_Town12_Route13090_Weather15.tar.gz\": {\n        \"sha256\": \"92604be8a7f692001d5946fd9235ef1ffc97d03cb21e3a1ccd14426245fca3fc\",\n        \"size\": 321696484\n    },\n    \"BlockedIntersection_Town12_Route13091_Weather8.tar.gz\": {\n        \"sha256\": \"3dcde2139bd9d0cce919ae767ec406988c213f15c2aa931f62e8df4529a29108\",\n        \"size\": 576384224\n    },\n    \"BlockedIntersection_Town12_Route13092_Weather9.tar.gz\": {\n        \"sha256\": \"d2e4582eb6b726acb0363e90d29c7f6d5af01a02c065fc4da217627a6574aaad\",\n        \"size\": 208405337\n    },\n    \"BlockedIntersection_Town12_Route13093_Weather18.tar.gz\": {\n        \"sha256\": \"1b91d645115ffce170569f827e393ff730a105102902b934adedef5a655fdef5\",\n        \"size\": 790506064\n    },\n    \"BlockedIntersection_Town12_Route13094_Weather19.tar.gz\": {\n        \"sha256\": \"0fe0c7777d34cf728ecbc113a501f1a95d64bb3933f7460bf3c9c9761333f540\",\n        \"size\": 1087261183\n    },\n    \"BlockedIntersection_Town12_Route13095_Weather20.tar.gz\": {\n        \"sha256\": \"0a4b1fbb72ba7f079db0ed3deb07626c2ba977f98294ff9a9b113707f422ddbb\",\n        \"size\": 393153396\n    },\n    \"BlockedIntersection_Town12_Route13099_Weather23.tar.gz\": {\n        \"sha256\": \"43f0ff0d8fcf121dc9d3defdc91ccc1ed02b98231b09d68fe75788ad9a9ea22c\",\n        \"size\": 206027083\n    },\n    \"BlockedIntersection_Town12_Route13101_Weather0.tar.gz\": {\n        \"sha256\": \"508106d309445790d3b3fe1e7340c3230344ad66e2d2136d4ee0a747d263dae9\",\n        \"size\": 523354206\n    },\n    \"BlockedIntersection_Town12_Route13102_Weather1.tar.gz\": {\n        \"sha256\": \"a637696b41b645ab675db5435da6180f90314ef941184e9154fdb08e4f9a3557\",\n        \"size\": 260898287\n    },\n    \"BlockedIntersection_Town12_Route13104_Weather3.tar.gz\": {\n        \"sha256\": \"9b4bc3b8c7c147c5aa96e4ff71fca1083c374cb6b9c678fa388a020c265382e6\",\n        \"size\": 527141044\n    },\n    \"BlockedIntersection_Town12_Route13105_Weather3.tar.gz\": {\n        \"sha256\": \"34e1c61a44b770cf7e378cae3d6a8aa8eb9a81141165c1904ee73c1f228f81c8\",\n        \"size\": 647928172\n    },\n    \"BlockedIntersection_Town12_Route13106_Weather5.tar.gz\": {\n        \"sha256\": \"cbfdf8f4545cff46d07fad41bfe300bb22312b15d22e22f85ae2de325ca05ec2\",\n        \"size\": 330661416\n    },\n    \"BlockedIntersection_Town12_Route13107_Weather6.tar.gz\": {\n        \"sha256\": \"aa0a5a2ba62ce1b2db0b400462e1f666ffa0e9a82f2b0b6843028adc47e48b1c\",\n        \"size\": 612995648\n    },\n    \"BlockedIntersection_Town12_Route13108_Weather7.tar.gz\": {\n        \"sha256\": \"e1fb8d3cc22157ae51ee99eb0dc52358ecb8d508d8a4d961588db8a11bb39211\",\n        \"size\": 648123221\n    },\n    \"BlockedIntersection_Town12_Route13109_Weather8.tar.gz\": {\n        \"sha256\": \"7f17ebe6579d7b61b9b2c10d061be0f0ba7af1d6128d3c941b3204ec27fcc511\",\n        \"size\": 420183062\n    },\n    \"BlockedIntersection_Town12_Route13110_Weather9.tar.gz\": {\n        \"sha256\": \"909e20eb80a178bf1e925873ea7ec9d5dfe35fd5654ecc1dadf3ba5d5dfe1238\",\n        \"size\": 300914984\n    },\n    \"BlockedIntersection_Town12_Route13113_Weather12.tar.gz\": {\n        \"sha256\": \"b2db19e5e1682f14a973b3d8ba463aaecf83d332e7a498e58399801fdf278380\",\n        \"size\": 246590018\n    },\n    \"BlockedIntersection_Town12_Route13114_Weather13.tar.gz\": {\n        \"sha256\": \"b583bafe3ae658648430bf486a9a11360febbc10b1907dd103be03e46edb3f39\",\n        \"size\": 355540832\n    },\n    \"BlockedIntersection_Town12_Route13115_Weather14.tar.gz\": {\n        \"sha256\": \"a482094ba1ba1aaa960655e76ec22e654baa59c7a7b3e171ebb597f91aa8c8ba\",\n        \"size\": 490267309\n    },\n    \"BlockedIntersection_Town12_Route13116_Weather15.tar.gz\": {\n        \"sha256\": \"9e8451605ead43b6a8c4586881fabc8200e24317763626de58b9aa141655aa91\",\n        \"size\": 216781321\n    },\n    \"BlockedIntersection_Town12_Route13119_Weather18.tar.gz\": {\n        \"sha256\": \"bc6ab06ab871d4cb21174e89d8afea9f12828446721edf63ebe4328de16b3015\",\n        \"size\": 359214508\n    },\n    \"BlockedIntersection_Town12_Route13120_Weather19.tar.gz\": {\n        \"sha256\": \"23f4cd7d013052e359f47287b639cf9fec273059366e8a24bff314c03f736702\",\n        \"size\": 557849103\n    },\n    \"BlockedIntersection_Town12_Route13121_Weather20.tar.gz\": {\n        \"sha256\": \"a814988ad00603d3d56376d717aef45741ff6afc50ecfd5a355de12f1c750844\",\n        \"size\": 215069893\n    },\n    \"BlockedIntersection_Town12_Route13124_Weather23.tar.gz\": {\n        \"sha256\": \"7480dea847e3138303117f5b66366da73269c3e3bbcc3f6c17898a8655f05a90\",\n        \"size\": 376460434\n    },\n    \"BlockedIntersection_Town12_Route13125_Weather23.tar.gz\": {\n        \"sha256\": \"e35ae780057dfc97100cb668a2785e3cc51c7a5118a966bcca0235abb140d204\",\n        \"size\": 745191986\n    },\n    \"BlockedIntersection_Town12_Route13126_Weather25.tar.gz\": {\n        \"sha256\": \"c972b22ebecbad1a84c6f79e7656d979d0d0a9d6e5ac3072f56499e5dd4f8097\",\n        \"size\": 309126427\n    },\n    \"BlockedIntersection_Town12_Route13127_Weather0.tar.gz\": {\n        \"sha256\": \"83d697a7d613378902405a86cd86af8a8b437b553f974e2c6f8b62d72c6721a5\",\n        \"size\": 506633130\n    },\n    \"BlockedIntersection_Town12_Route13132_Weather5.tar.gz\": {\n        \"sha256\": \"58fc066dd3ae4d269c339d081889bdcd9f50f0b4069a824d2d5510fa04db5422\",\n        \"size\": 484930908\n    },\n    \"BlockedIntersection_Town12_Route13133_Weather6.tar.gz\": {\n        \"sha256\": \"113b71b54f86d0a6071465484e50e5fda0477d3cb397082ae9e634e49bee7a5f\",\n        \"size\": 203065378\n    },\n    \"BlockedIntersection_Town12_Route13134_Weather7.tar.gz\": {\n        \"sha256\": \"1b43898cdd6d5d37412b13b8f102a5905f25a8491ae7fa5ca5a58e176dd83f34\",\n        \"size\": 276867462\n    },\n    \"BlockedIntersection_Town12_Route13135_Weather8.tar.gz\": {\n        \"sha256\": \"1be3fff38767f3f8b4e51562de30ecf30425d3b95c120a958439f114d75c3b81\",\n        \"size\": 346147999\n    },\n    \"BlockedIntersection_Town12_Route13138_Weather11.tar.gz\": {\n        \"sha256\": \"97a62aa9751362fc1c19a3b251bc59dcd3b16b994c696d5b39e39eaed39ff3c5\",\n        \"size\": 389401520\n    },\n    \"BlockedIntersection_Town12_Route13139_Weather12.tar.gz\": {\n        \"sha256\": \"ae41dea3f28954392f5497fd8dcf7e93a35b6ba5d6a161150dad797e34ebe597\",\n        \"size\": 371854545\n    },\n    \"BlockedIntersection_Town12_Route13140_Weather13.tar.gz\": {\n        \"sha256\": \"d821f1dcb7aad79870ae39d3c824758dd8190391c8924490a53c308333cf8b9f\",\n        \"size\": 200801115\n    },\n    \"BlockedIntersection_Town12_Route13141_Weather14.tar.gz\": {\n        \"sha256\": \"524e289890a26c9201d97e68edb2a96debb20b52e13df1c0ecec6acab39afe07\",\n        \"size\": 455603150\n    },\n    \"BlockedIntersection_Town12_Route13142_Weather15.tar.gz\": {\n        \"sha256\": \"d0a951b0f06e394756927bbbc706b246d256e7b736487b4917e21754b8c4297f\",\n        \"size\": 406148846\n    },\n    \"BlockedIntersection_Town12_Route13143_Weather8.tar.gz\": {\n        \"sha256\": \"87fb34fcda477c992e63d4ac05a4b2eb1a643937484762816aa4fcba8293db59\",\n        \"size\": 207692708\n    },\n    \"BlockedIntersection_Town12_Route13144_Weather9.tar.gz\": {\n        \"sha256\": \"5f0453180af307ba5403a209720aad2faa6b2e6054cdc4ab43a83e093ab606f6\",\n        \"size\": 276345068\n    },\n    \"BlockedIntersection_Town12_Route13146_Weather19.tar.gz\": {\n        \"sha256\": \"4d22802d7515280b8d0b6768bf820571b06eb1c97df05b672c83845c5f8bbcf0\",\n        \"size\": 346117031\n    },\n    \"BlockedIntersection_Town12_Route13147_Weather20.tar.gz\": {\n        \"sha256\": \"33c9f3bb62eb5f43612fbfd8ae8e6b0aa6c91268e0bf25cd591b7809511029b2\",\n        \"size\": 937127654\n    },\n    \"BlockedIntersection_Town12_Route13149_Weather22.tar.gz\": {\n        \"sha256\": \"f9df9c41af6d41ea6fcfe0be3425e83f73b9aa9117ffb8a5048f9fed0f4fd729\",\n        \"size\": 303121643\n    },\n    \"BlockedIntersection_Town12_Route13150_Weather23.tar.gz\": {\n        \"sha256\": \"b0ec4233d33e705d27538a300fe7d61a4cc5576568b4e3b107f6c9cfdbde30d0\",\n        \"size\": 411001725\n    },\n    \"BlockedIntersection_Town12_Route13151_Weather23.tar.gz\": {\n        \"sha256\": \"1ee060bd7bf4aec603e9254cfbd5a620e960bca4f83c795f09ccb14706082f94\",\n        \"size\": 685149267\n    },\n    \"BlockedIntersection_Town12_Route13153_Weather0.tar.gz\": {\n        \"sha256\": \"0efb8e7fcfdd11086751487cb73fcb4b62fd9e3a013975eb63c8049cba230aab\",\n        \"size\": 489576898\n    },\n    \"BlockedIntersection_Town12_Route13155_Weather2.tar.gz\": {\n        \"sha256\": \"ea1c108b25f1a83f31e7d5212809792c83e9685021256c2d5cd8437523046b3f\",\n        \"size\": 360870728\n    },\n    \"BlockedIntersection_Town12_Route13159_Weather6.tar.gz\": {\n        \"sha256\": \"e89b7a1f98c9abd802ff62fad7938cc1dcd89b7d060201dc2899626cf8d5cf85\",\n        \"size\": 464102083\n    },\n    \"BlockedIntersection_Town12_Route13160_Weather7.tar.gz\": {\n        \"sha256\": \"797aa2b36cf18e13f22d0395404c8a42051414b61f43ae23f595dc0bcbf87de3\",\n        \"size\": 615315099\n    },\n    \"BlockedIntersection_Town12_Route13161_Weather8.tar.gz\": {\n        \"sha256\": \"42c434a2f4e03bcfe239d2a27145de8d9da5009c3b8df607faf528b57aaf6c1f\",\n        \"size\": 546718753\n    },\n    \"BlockedIntersection_Town12_Route13163_Weather10.tar.gz\": {\n        \"sha256\": \"4942294ee05c9705de044a969954539cae11cb3dea07e31512d0c7fc356f5721\",\n        \"size\": 254109713\n    },\n    \"BlockedIntersection_Town12_Route13164_Weather11.tar.gz\": {\n        \"sha256\": \"42685d8b92e1c051e4f45dc5e8de23a8517b053646019ff3c44e639ab1e84341\",\n        \"size\": 372165068\n    },\n    \"BlockedIntersection_Town12_Route13166_Weather13.tar.gz\": {\n        \"sha256\": \"65e60f2c0b28c832bba7c669f3994130cd5e68e9d8878532b9b69359fe5a0358\",\n        \"size\": 372167034\n    },\n    \"BlockedIntersection_Town12_Route13167_Weather14.tar.gz\": {\n        \"sha256\": \"ac5692050306aebebd26f68119513f586029e5bceff743f22a8d5be25a5d4901\",\n        \"size\": 1392848400\n    },\n    \"BlockedIntersection_Town12_Route13168_Weather15.tar.gz\": {\n        \"sha256\": \"4c6d29a1485d9829be9a652ec79caa3febc76138879c0650dde5cd44fdd9c311\",\n        \"size\": 244481294\n    },\n    \"BlockedIntersection_Town12_Route13169_Weather8.tar.gz\": {\n        \"sha256\": \"4ddd9c388d58dafc33fc141caf49cc1221804b8447cdb5f56515d53422bdfc77\",\n        \"size\": 377950955\n    },\n    \"BlockedIntersection_Town12_Route13176_Weather23.tar.gz\": {\n        \"sha256\": \"c55362275761d7488acb0fc8465a97ca6aa5cb2437489c4b78591a96c2d7b711\",\n        \"size\": 461210902\n    },\n    \"BlockedIntersection_Town12_Route13178_Weather25.tar.gz\": {\n        \"sha256\": \"221da706c3c7f2b1c71080dfc84dc2235c368f2e0bbd341e7f511049a228e2e0\",\n        \"size\": 257892533\n    },\n    \"BlockedIntersection_Town12_Route13179_Weather0.tar.gz\": {\n        \"sha256\": \"adaf9fb1ed7d7cc859b984dc4cf1370a8367ff342b0c9e06389af540960456b3\",\n        \"size\": 770381446\n    },\n    \"BlockedIntersection_Town12_Route13180_Weather1.tar.gz\": {\n        \"sha256\": \"a43343bcd5b6103c5b21b38af5abae549153817410a640a9da2b1965497324f3\",\n        \"size\": 360389037\n    },\n    \"BlockedIntersection_Town12_Route13181_Weather2.tar.gz\": {\n        \"sha256\": \"f89a129f11d5ad83007bb6bb70473157c86b9b377ba61d67e3551993ee3a61a3\",\n        \"size\": 634146929\n    },\n    \"BlockedIntersection_Town12_Route13182_Weather3.tar.gz\": {\n        \"sha256\": \"7718c0e616bd56786a3101d6fdba9ab6ec3f76e8d2fa7f991d2bf5208b9c3bcc\",\n        \"size\": 237317562\n    },\n    \"BlockedIntersection_Town12_Route13183_Weather3.tar.gz\": {\n        \"sha256\": \"b3db40ddf75615f125c0d40f0ca66804585010317cd7cd74a15030f4bc353d48\",\n        \"size\": 544422332\n    },\n    \"BlockedIntersection_Town12_Route13185_Weather6.tar.gz\": {\n        \"sha256\": \"2d21d492adc98d1710f458f2467af4b2f37d91a9f5cd08d39af8508c9f6dc9d3\",\n        \"size\": 260816729\n    },\n    \"BlockedIntersection_Town12_Route13186_Weather7.tar.gz\": {\n        \"sha256\": \"9a0db8ae61153abb6d281d3840aea35dcb5dd0aa05d65badd5953036fc6b71df\",\n        \"size\": 657488170\n    },\n    \"BlockedIntersection_Town12_Route13187_Weather8.tar.gz\": {\n        \"sha256\": \"09afa2cdac6cb8af772f2967fe5616bf60bbfe5d18ebec4f1216600642941486\",\n        \"size\": 342251164\n    },\n    \"BlockedIntersection_Town12_Route13188_Weather9.tar.gz\": {\n        \"sha256\": \"4dcf0bad631ca3b803f9f2b6429537ec8ff939d73566f1330c7e31838acca774\",\n        \"size\": 378889803\n    },\n    \"BlockedIntersection_Town12_Route13189_Weather10.tar.gz\": {\n        \"sha256\": \"e0a73ede484fb42d83f2b9ae4dd804a41a5792586c280fa13775bfb08ad2e020\",\n        \"size\": 238805879\n    },\n    \"BlockedIntersection_Town12_Route13191_Weather12.tar.gz\": {\n        \"sha256\": \"d360a8da0ece9aee4c7244dabb3e68fa71b1592f0aeb5c6d19aed7621b128bdc\",\n        \"size\": 271518890\n    },\n    \"BlockedIntersection_Town12_Route13192_Weather13.tar.gz\": {\n        \"sha256\": \"a2ed23406848b78c847cf4836e450faef5adea10b3e1c1bf894b0895e29d7d92\",\n        \"size\": 341234249\n    },\n    \"BlockedIntersection_Town12_Route13195_Weather8.tar.gz\": {\n        \"sha256\": \"ba7a800a819d0771eb537f8d2a6d357bf767ea1fb0eb8bdf5f765b7db6b90b06\",\n        \"size\": 342073763\n    },\n    \"BlockedIntersection_Town12_Route13196_Weather9.tar.gz\": {\n        \"sha256\": \"9887b51b52a0bb6ce9813cc1042084d09c4a183c6cbc0e144f03409770f09f41\",\n        \"size\": 167640069\n    },\n    \"BlockedIntersection_Town12_Route13197_Weather18.tar.gz\": {\n        \"sha256\": \"0530291b4c91723e192aeb170eb005c4da88d3dbba64c81058c71ea473ef8faa\",\n        \"size\": 417096483\n    },\n    \"BlockedIntersection_Town12_Route13198_Weather19.tar.gz\": {\n        \"sha256\": \"bc0d24450667babcafb728a8542902fd8784661b4379d8e3767dadf0500280d4\",\n        \"size\": 744158570\n    },\n    \"BlockedIntersection_Town12_Route13200_Weather21.tar.gz\": {\n        \"sha256\": \"babcae7f7658168264df91c659f2a1090a0ece9d5b5110c192ca8ac32e6871f3\",\n        \"size\": 499593545\n    },\n    \"BlockedIntersection_Town12_Route13201_Weather22.tar.gz\": {\n        \"sha256\": \"20d4945c362ef2b6a3da6dfe87d6f0c89403abca8617940fb69f809f11ad673f\",\n        \"size\": 462500864\n    },\n    \"BlockedIntersection_Town12_Route13202_Weather23.tar.gz\": {\n        \"sha256\": \"58477b0515bb2a5c0eafe8edbb5c1542e89c1bf7c361ff9f06e972b47dd5aea5\",\n        \"size\": 228391600\n    },\n    \"BlockedIntersection_Town12_Route13203_Weather23.tar.gz\": {\n        \"sha256\": \"f248fb077acc0578097e2a3edcbf91624725b512d12cf76d3c86371e5936449e\",\n        \"size\": 439922902\n    },\n    \"BlockedIntersection_Town12_Route13204_Weather25.tar.gz\": {\n        \"sha256\": \"3b7956e8759428822fcd53f18929c65facce38fc729cfabcf1315e19a1a46424\",\n        \"size\": 264853539\n    },\n    \"BlockedIntersection_Town12_Route13205_Weather0.tar.gz\": {\n        \"sha256\": \"d7c4bccb06df540d2e66c19b338e05b37c65ace6d6075bb4abb4f67501beb36a\",\n        \"size\": 269020818\n    },\n    \"BlockedIntersection_Town12_Route13207_Weather2.tar.gz\": {\n        \"sha256\": \"a5c7e1c14c1eb06a228a92a1697725eab625bb7cb890189acba07ee8575f6c7c\",\n        \"size\": 530201603\n    },\n    \"BlockedIntersection_Town12_Route13208_Weather3.tar.gz\": {\n        \"sha256\": \"feb7b079ee4e83aeb0d34835d54704adc2de03df3574992d7e38c72af1aeb79a\",\n        \"size\": 395632829\n    },\n    \"BlockedIntersection_Town12_Route13212_Weather7.tar.gz\": {\n        \"sha256\": \"a5a9c46d288b8af33ea2b0de138e9547047e4bc843c0a0b738f56af83c9fba62\",\n        \"size\": 539929397\n    },\n    \"BlockedIntersection_Town12_Route13213_Weather8.tar.gz\": {\n        \"sha256\": \"e9543b9c6394aee625615929fd94ab6537be9205eee98d7efe4c895a848b5bd9\",\n        \"size\": 342022351\n    },\n    \"BlockedIntersection_Town12_Route13214_Weather9.tar.gz\": {\n        \"sha256\": \"03d4483a0975a3eaa38c9eafb725da09bc0280675dd9b77957211a908d7248f5\",\n        \"size\": 269469939\n    },\n    \"BlockedIntersection_Town12_Route13215_Weather10.tar.gz\": {\n        \"sha256\": \"c1890dfedd50e5641f59507a5500ac8678f30d36811740540f0735bb711dbdd8\",\n        \"size\": 659727516\n    },\n    \"BlockedIntersection_Town12_Route13216_Weather11.tar.gz\": {\n        \"sha256\": \"5015e36c7e855a2b8b5b23ffc4050e8b6ad7695f3d9b508db00308b667b54d4a\",\n        \"size\": 177608202\n    },\n    \"BlockedIntersection_Town12_Route13217_Weather12.tar.gz\": {\n        \"sha256\": \"bc7133852183a4c8e86769ae3e048348aa811b12a7bee3e828c4354ee02a6f3b\",\n        \"size\": 275383573\n    },\n    \"BlockedIntersection_Town12_Route13219_Weather14.tar.gz\": {\n        \"sha256\": \"8c0cae251ad76fae50eed4ec6ff4581898cdfc9aa82212005ec95a538622a415\",\n        \"size\": 474645340\n    },\n    \"BlockedIntersection_Town12_Route13220_Weather15.tar.gz\": {\n        \"sha256\": \"9672935ed6fd552bdb71f4d32dfc710048a54e290d853fe4d1ba98ba40735015\",\n        \"size\": 223245617\n    },\n    \"BlockedIntersection_Town12_Route13221_Weather8.tar.gz\": {\n        \"sha256\": \"d235a0b83aba640842192b0df49f075c5ae42ba9a67cd79eaa7bf1ba9bd7e240\",\n        \"size\": 213169504\n    },\n    \"BlockedIntersection_Town12_Route13222_Weather9.tar.gz\": {\n        \"sha256\": \"862e6428b1b3feda9b1cdc7e81da6a6404e45db42830a9b002fae39f19f16468\",\n        \"size\": 270447213\n    },\n    \"BlockedIntersection_Town12_Route13224_Weather19.tar.gz\": {\n        \"sha256\": \"91a505763d9b056f8946755dc9372f20322084075870b6a8611f56d9bad949c7\",\n        \"size\": 336701449\n    },\n    \"BlockedIntersection_Town12_Route13226_Weather21.tar.gz\": {\n        \"sha256\": \"1bd82d9b4689cd4633208a2f669a7f0102780b0b6f1e0785acc6c6e1a5d1a9fb\",\n        \"size\": 342419547\n    },\n    \"BlockedIntersection_Town12_Route13228_Weather23.tar.gz\": {\n        \"sha256\": \"501aeb9c04533d5a34e8f16dd4cc9da4e7435ddbbc5675f485a6741c981b11e2\",\n        \"size\": 294885157\n    },\n    \"BlockedIntersection_Town12_Route13229_Weather23.tar.gz\": {\n        \"sha256\": \"468311ebd85e3cf0377bf0b5ee4005afd1545162de9c7d903e88620efa4d1e78\",\n        \"size\": 411508694\n    },\n    \"BlockedIntersection_Town12_Route13230_Weather25.tar.gz\": {\n        \"sha256\": \"203a666feaf2b57ef583592029dda067a4889019b8bc88cfc249917a5033808f\",\n        \"size\": 431967455\n    },\n    \"BlockedIntersection_Town12_Route13231_Weather0.tar.gz\": {\n        \"sha256\": \"2b4660b6f32f9a99f3245ea911efd2b97bc6751eb401637b411b7ed46b647c81\",\n        \"size\": 386914718\n    },\n    \"BlockedIntersection_Town12_Route13232_Weather1.tar.gz\": {\n        \"sha256\": \"0cf6bbcc3071a2aa7508a527614064ee49dbf5d16fbece21f867d2a610700c3b\",\n        \"size\": 576418494\n    },\n    \"BlockedIntersection_Town12_Route13233_Weather2.tar.gz\": {\n        \"sha256\": \"126ce25128aa502d38b5da77b0ebce008cc528f5beb295fced64cc0b8aa1ff2b\",\n        \"size\": 449921674\n    },\n    \"BlockedIntersection_Town12_Route13234_Weather3.tar.gz\": {\n        \"sha256\": \"f1ca1b650d5423e28dedebebc4460809d962daa7ab2165a4c9fdfb711fb82451\",\n        \"size\": 660984420\n    },\n    \"BlockedIntersection_Town12_Route13236_Weather5.tar.gz\": {\n        \"sha256\": \"5c05789f3d6e309a3e8683170f096aedd1aa6ffa64f34381d3140611cc828d9c\",\n        \"size\": 349155806\n    },\n    \"BlockedIntersection_Town12_Route13239_Weather8.tar.gz\": {\n        \"sha256\": \"86239da5ce871cf2b073d6a0a7d8f8f9682fbfe3d368d50cd067e7092eeff4c6\",\n        \"size\": 329003499\n    },\n    \"BlockedIntersection_Town12_Route13242_Weather11.tar.gz\": {\n        \"sha256\": \"097ac161a6be60723b1d954b80c9f3d04b0d43813887056d03ff7f9f26294b3d\",\n        \"size\": 504891997\n    },\n    \"BlockedIntersection_Town12_Route13243_Weather12.tar.gz\": {\n        \"sha256\": \"2dc66409c1eb20c01cfab1dac37a2ff425aa927c4f07749be6a98380b6a15cd8\",\n        \"size\": 388509677\n    },\n    \"BlockedIntersection_Town12_Route13244_Weather13.tar.gz\": {\n        \"sha256\": \"dd87678ee827f3bdcfa2a2ad157d7aff893fe18c0bb91df198f238f6fe64d506\",\n        \"size\": 301741481\n    },\n    \"BlockedIntersection_Town12_Route13245_Weather14.tar.gz\": {\n        \"sha256\": \"8489b6858dcd3c434685fbb814fa3fe3dbf17e9878bdf87aa934c70a98ad14c7\",\n        \"size\": 227156744\n    },\n    \"BlockedIntersection_Town12_Route13246_Weather15.tar.gz\": {\n        \"sha256\": \"e0f99e6ecd5ca5d82e92874f72c2d7026ad59f93cae38b8176cc99cfb4bdb5d9\",\n        \"size\": 382729364\n    },\n    \"BlockedIntersection_Town12_Route13247_Weather8.tar.gz\": {\n        \"sha256\": \"8d80de64ee49991c25b427f14a2be90f51cda3226974ea882e3215d73b9d8ec2\",\n        \"size\": 441110062\n    },\n    \"BlockedIntersection_Town12_Route13251_Weather20.tar.gz\": {\n        \"sha256\": \"7eff292ab38573719b4d2dd785e31efac831091c992f233af03002ac3d4ca748\",\n        \"size\": 328859701\n    },\n    \"BlockedIntersection_Town12_Route13252_Weather21.tar.gz\": {\n        \"sha256\": \"4500497d6507792a9d056f2baaff91827d2edddff0aba97ac5c9443b9ad82e74\",\n        \"size\": 593789040\n    },\n    \"BlockedIntersection_Town12_Route13253_Weather22.tar.gz\": {\n        \"sha256\": \"6d1d260f6fc8e544b6c0c3a101598cd337d06081a3e254a56449fa70843b05aa\",\n        \"size\": 253974819\n    },\n    \"BlockedIntersection_Town12_Route13254_Weather23.tar.gz\": {\n        \"sha256\": \"0091e42f7595bc56c93a3364d1f2460e96f0d95b138314b482845d95b56e89c0\",\n        \"size\": 304909182\n    },\n    \"BlockedIntersection_Town12_Route13255_Weather23.tar.gz\": {\n        \"sha256\": \"50698fa64ce895efc20ec19e49afa6c4f11ae9f33e84e6b4a3d30e2640d125a7\",\n        \"size\": 152908547\n    },\n    \"BlockedIntersection_Town12_Route13257_Weather0.tar.gz\": {\n        \"sha256\": \"a92d6a705e6a22effffd9ecb3e7faa10f222c011143421954d1a91fab0fb0f37\",\n        \"size\": 383778928\n    },\n    \"BlockedIntersection_Town12_Route13258_Weather1.tar.gz\": {\n        \"sha256\": \"dc4831806c5ceada898fdeba60314d1a18538c779b59b9a7c41e7fd74bdd58e2\",\n        \"size\": 358055145\n    },\n    \"BlockedIntersection_Town12_Route13259_Weather2.tar.gz\": {\n        \"sha256\": \"bfe039b97a086c7de16e7dd552035eff768e8edf3bf0ebdd2745a371f9ec4783\",\n        \"size\": 322942720\n    },\n    \"BlockedIntersection_Town12_Route13260_Weather3.tar.gz\": {\n        \"sha256\": \"a0ae521ecb15bd3ff4222aab35caa0a54c1092100f3564032ae6b17f0958f10e\",\n        \"size\": 333628670\n    },\n    \"BlockedIntersection_Town12_Route13261_Weather3.tar.gz\": {\n        \"sha256\": \"8e90cf28c82970190a8c35c14c96ed8788e5804eda66feec0de4795ce102ad15\",\n        \"size\": 427068861\n    },\n    \"BlockedIntersection_Town12_Route13263_Weather6.tar.gz\": {\n        \"sha256\": \"170468097face4fb6703e2959149928538dc99d09b8f3d1b864e64761dd2d3c2\",\n        \"size\": 291413422\n    },\n    \"BlockedIntersection_Town12_Route13264_Weather7.tar.gz\": {\n        \"sha256\": \"91f6286550d8f5724315c9bb154c255de1ec28c85faa7156fc9e555017201736\",\n        \"size\": 612123441\n    },\n    \"BlockedIntersection_Town12_Route13266_Weather9.tar.gz\": {\n        \"sha256\": \"035781c500257990c4b56f4efc860abf10ba1f5e5574837364ba40ae018ccd32\",\n        \"size\": 1364948020\n    },\n    \"BlockedIntersection_Town12_Route13267_Weather10.tar.gz\": {\n        \"sha256\": \"bcd14694743453bb25523ff748ff600001b847bc9c0d7a467d5e3f2e0e6574b6\",\n        \"size\": 448151074\n    },\n    \"BlockedIntersection_Town12_Route13269_Weather12.tar.gz\": {\n        \"sha256\": \"b9ed66b795ef479ed14c0f2f188c872162b09ad09295502423bef762c5792244\",\n        \"size\": 204446924\n    },\n    \"BlockedIntersection_Town12_Route13270_Weather13.tar.gz\": {\n        \"sha256\": \"1a2b64595a83a7f6c919a1bedabffcc40a83dc88b6a2bd3c9bf3df6105db2fb8\",\n        \"size\": 292959543\n    },\n    \"BlockedIntersection_Town12_Route13272_Weather15.tar.gz\": {\n        \"sha256\": \"15e2a78c0748bd31d68a8412235a2a39ffc2bd1bf2aa53cc9219907c8198a5f4\",\n        \"size\": 263174875\n    },\n    \"BlockedIntersection_Town12_Route13275_Weather18.tar.gz\": {\n        \"sha256\": \"9f6406875e2354bdafccf871f725708a862be475079256b905a5db4d5e2d4c8e\",\n        \"size\": 1046836110\n    },\n    \"BlockedIntersection_Town12_Route13276_Weather19.tar.gz\": {\n        \"sha256\": \"71c88aa52c2698b6983deb6df3d1d7c2c98843ff5908492777f3a6cc3aba4a43\",\n        \"size\": 234425787\n    },\n    \"BlockedIntersection_Town12_Route13277_Weather20.tar.gz\": {\n        \"sha256\": \"dbbaeaeacd9a29c25e6186d31b1f9bde4f16c255a24e7055ad0c9487c407fe2a\",\n        \"size\": 369637857\n    },\n    \"BlockedIntersection_Town12_Route13278_Weather21.tar.gz\": {\n        \"sha256\": \"e6c70087282d330b2682c63851c14917e611ee73fe44d2462358b4a86100bddf\",\n        \"size\": 546298752\n    },\n    \"BlockedIntersection_Town12_Route13279_Weather22.tar.gz\": {\n        \"sha256\": \"5e99a441bee9df2c5dc36a5b6474753e6d8c596b25c7c5684b4f471861913b6a\",\n        \"size\": 435713223\n    },\n    \"BlockedIntersection_Town12_Route13281_Weather23.tar.gz\": {\n        \"sha256\": \"d1ec362b751e98341c3a63ece42f94c613c43c05670ac03ba9a7c76af06b9d37\",\n        \"size\": 278537999\n    },\n    \"BlockedIntersection_Town12_Route13282_Weather25.tar.gz\": {\n        \"sha256\": \"bdf2fd7fc60d16dad9993e301b8509b29891fdc4382303fa6809070fb3287635\",\n        \"size\": 315506663\n    },\n    \"BlockedIntersection_Town12_Route13283_Weather0.tar.gz\": {\n        \"sha256\": \"00ab0f7e6b091704e6b5b30af766088eeeafd7265be265cb6630d145b77b97e5\",\n        \"size\": 391583620\n    },\n    \"BlockedIntersection_Town12_Route13284_Weather1.tar.gz\": {\n        \"sha256\": \"24528a8bc32d128df2134453461b024436038de451f0297f1c4211c315ba3703\",\n        \"size\": 527822762\n    },\n    \"BlockedIntersection_Town12_Route13285_Weather2.tar.gz\": {\n        \"sha256\": \"cb26037d4a2b17c86faabe297c4514e74529fd4c31f9d6c8206d88dbdca82f93\",\n        \"size\": 361550748\n    },\n    \"BlockedIntersection_Town12_Route13289_Weather6.tar.gz\": {\n        \"sha256\": \"cf6d4485cee269b83f638e7f4a93314a5c13329f14f6dbf6840bcbd5342f0c19\",\n        \"size\": 484801794\n    },\n    \"BlockedIntersection_Town12_Route13292_Weather9.tar.gz\": {\n        \"sha256\": \"c70da2fd8be409df59817724a3eb8de23827f633f1414e143e37874209c7a5a3\",\n        \"size\": 251966163\n    },\n    \"BlockedIntersection_Town12_Route13294_Weather11.tar.gz\": {\n        \"sha256\": \"7b2eee8c12805be44b17e124aca87941124b744f9030c1fc03aa0e6f2776dab2\",\n        \"size\": 648101000\n    },\n    \"BlockedIntersection_Town12_Route13295_Weather12.tar.gz\": {\n        \"sha256\": \"68ba720a5c8c27c492971d8e9aa8aed42be1a6c79184f255634a76561eb71782\",\n        \"size\": 271929114\n    },\n    \"BlockedIntersection_Town12_Route13296_Weather13.tar.gz\": {\n        \"sha256\": \"597f486cc42723e0fd378ddda413f215acbc10120bdc12352078f37129d50c5a\",\n        \"size\": 405402297\n    },\n    \"BlockedIntersection_Town12_Route13299_Weather8.tar.gz\": {\n        \"sha256\": \"c821ac03bf9ae4d149d5051b1671e2f605540880ce66f51f7440c4902c4cac38\",\n        \"size\": 374467033\n    },\n    \"BlockedIntersection_Town12_Route13300_Weather9.tar.gz\": {\n        \"sha256\": \"a258b8ac43c3b425b45b87803d6fd0b6ceac7f445b6db688b108ce834665ab4b\",\n        \"size\": 330377768\n    },\n    \"BlockedIntersection_Town12_Route13302_Weather19.tar.gz\": {\n        \"sha256\": \"aee154efe32c69bcd4015318464afa9496a806645312a61ce2f2eb28b51e3315\",\n        \"size\": 412709079\n    },\n    \"BlockedIntersection_Town12_Route13303_Weather20.tar.gz\": {\n        \"sha256\": \"64217723a8d08dc24208a2417f46988ada81ce127dd0cfe5b0805fd20d7ead3f\",\n        \"size\": 279675275\n    },\n    \"BlockedIntersection_Town12_Route13305_Weather22.tar.gz\": {\n        \"sha256\": \"77869b7ee15ff3d1ad954ebdc257ae2aaf45a1297c2b4fd89d289db264528d64\",\n        \"size\": 411804472\n    },\n    \"BlockedIntersection_Town12_Route13306_Weather23.tar.gz\": {\n        \"sha256\": \"4838bcb8905d0570e201791df7a5da8c66ceac1573bce4c8241a94270e5250f3\",\n        \"size\": 415172377\n    },\n    \"BlockedIntersection_Town12_Route13307_Weather23.tar.gz\": {\n        \"sha256\": \"729b384c0c2fa84fd11750b2e2ba38ca9632eb97f96f44b9ef665566aee807a2\",\n        \"size\": 318439632\n    },\n    \"BlockedIntersection_Town12_Route13308_Weather25.tar.gz\": {\n        \"sha256\": \"c37a0d8ef959c96d92f202907306f91686ad7d7f264f1b5c1ef2433c50ee1fbe\",\n        \"size\": 346389818\n    },\n    \"BlockedIntersection_Town12_Route13311_Weather2.tar.gz\": {\n        \"sha256\": \"006413e02de4dca7cc8fe3a3d3377ad8eed42c3698523fe3b45f1577cb8c9a74\",\n        \"size\": 366320681\n    },\n    \"BlockedIntersection_Town12_Route13312_Weather3.tar.gz\": {\n        \"sha256\": \"2b9729f83b3d10504e0f18fbd1dc133f48bc88f3a88a30a1531f3021371ff172\",\n        \"size\": 399752032\n    },\n    \"BlockedIntersection_Town12_Route13313_Weather3.tar.gz\": {\n        \"sha256\": \"d13591b451a611ab2a9d7edc985692ea2b050c06538bbcc2d335a8f40efecdf9\",\n        \"size\": 424244616\n    },\n    \"BlockedIntersection_Town12_Route13314_Weather5.tar.gz\": {\n        \"sha256\": \"69b8a7e338e3f1c6fdca396fa1064096eeb9444f3320ae4b9aec5f30e74a9fa6\",\n        \"size\": 317473296\n    },\n    \"BlockedIntersection_Town12_Route13315_Weather6.tar.gz\": {\n        \"sha256\": \"d6b0803e40b7e4385cfafceeb0f159c9d7659d0f7eb11af91913b95f2b8949c5\",\n        \"size\": 469117944\n    },\n    \"BlockedIntersection_Town12_Route13316_Weather7.tar.gz\": {\n        \"sha256\": \"33a07e5cf2395d2a41327804353c6902074c4b55d80f6c9066039ff9ba67ef3b\",\n        \"size\": 527550404\n    },\n    \"BlockedIntersection_Town12_Route13318_Weather9.tar.gz\": {\n        \"sha256\": \"9572983928aef6b1fe87fb026c07f93b5d3de6228393977777eba5d4d474b09e\",\n        \"size\": 129005716\n    },\n    \"BlockedIntersection_Town12_Route13321_Weather12.tar.gz\": {\n        \"sha256\": \"bd17d87d7fbdc09cea8fe9d45a094d0561c29ebc42d59a1868be05d7f040f175\",\n        \"size\": 394909504\n    },\n    \"BlockedIntersection_Town12_Route13322_Weather13.tar.gz\": {\n        \"sha256\": \"11849f1b3e52543e29e639eb5d089df4a4bffa39d2ff6fde0e95f33858b1b812\",\n        \"size\": 499958930\n    },\n    \"BlockedIntersection_Town12_Route13323_Weather14.tar.gz\": {\n        \"sha256\": \"b50e13ecd7a4ab91c33581fde8a1f23ba30594c9c8c227c22be9ac74bd0ac811\",\n        \"size\": 154036232\n    },\n    \"BlockedIntersection_Town12_Route13325_Weather8.tar.gz\": {\n        \"sha256\": \"cda4a1a5bfeae87b3ae55eda0421afc40b370f8c5b8e55d382c460a0435c270a\",\n        \"size\": 439746050\n    },\n    \"BlockedIntersection_Town12_Route13329_Weather20.tar.gz\": {\n        \"sha256\": \"2f1ff3df972b846f8d13006d70905801847ad33080eb96f11814bafbe35606be\",\n        \"size\": 396368750\n    },\n    \"BlockedIntersection_Town12_Route13330_Weather21.tar.gz\": {\n        \"sha256\": \"8c66bbf2924465914f64ba406cb619b2c923dae49ab6652459d0af98ff6f6287\",\n        \"size\": 257575651\n    },\n    \"BlockedIntersection_Town12_Route13333_Weather23.tar.gz\": {\n        \"sha256\": \"bc2a9aab456e672231394b00267759499cb25b657e6c97c70338850636c94a11\",\n        \"size\": 539568492\n    },\n    \"BlockedIntersection_Town12_Route13334_Weather25.tar.gz\": {\n        \"sha256\": \"28bac85c82ba305d3713e571259ac9843bc3560dc212cf748bb3005166434bcc\",\n        \"size\": 322785546\n    },\n    \"BlockedIntersection_Town12_Route13335_Weather0.tar.gz\": {\n        \"sha256\": \"ea6560ccdaafcf0f3cb6c4b256b178f53468980083aa7ebe7416412bc9692de7\",\n        \"size\": 499142158\n    },\n    \"BlockedIntersection_Town12_Route13336_Weather1.tar.gz\": {\n        \"sha256\": \"a11ffa87f26c29f2ab599ae143643d1bb2bfb1156505c9de9681c1202e27e5d1\",\n        \"size\": 290991748\n    },\n    \"BlockedIntersection_Town12_Route13337_Weather2.tar.gz\": {\n        \"sha256\": \"fee97d58b51fd90ab576915a9427847623e975dd0ffed46c29c7a2d6d5c41abb\",\n        \"size\": 466177498\n    },\n    \"BlockedIntersection_Town12_Route13338_Weather3.tar.gz\": {\n        \"sha256\": \"de0de7f27c1028c6058e3c5c8b9908699c810242c839e5a833c9f267d8a867ad\",\n        \"size\": 345693970\n    },\n    \"BlockedIntersection_Town12_Route13339_Weather3.tar.gz\": {\n        \"sha256\": \"082ba167d0583f2a7e3035ef500ff5be178c316b318ac02e61bd5779c82e143e\",\n        \"size\": 272174435\n    },\n    \"BlockedIntersection_Town12_Route13340_Weather5.tar.gz\": {\n        \"sha256\": \"a6f1d97cecaf7f5a2407d5c37ffc490ab7361103e6bf62a88f8e89316dabd3e4\",\n        \"size\": 576644751\n    },\n    \"BlockedIntersection_Town12_Route13341_Weather6.tar.gz\": {\n        \"sha256\": \"81fa237e85b870b4dfbede061224a646c25042a8f00b9f4e9f8e3564a1f343bb\",\n        \"size\": 338320211\n    },\n    \"BlockedIntersection_Town12_Route13342_Weather7.tar.gz\": {\n        \"sha256\": \"b01e928d1c4db8b9b1d08113ed2ea58d61ff74537f076f8002c2a292bd78967c\",\n        \"size\": 597977926\n    },\n    \"BlockedIntersection_Town12_Route13343_Weather8.tar.gz\": {\n        \"sha256\": \"048af110ceab7746d303c4143cb31ad8c95d2c0078d45d2f91891ebec9863b7b\",\n        \"size\": 176615950\n    },\n    \"BlockedIntersection_Town12_Route13345_Weather10.tar.gz\": {\n        \"sha256\": \"fa279ec937a6c263fe38b622cbe4acc2a29b96e05ee79dda0681e18851fc6d11\",\n        \"size\": 659816289\n    },\n    \"BlockedIntersection_Town12_Route13348_Weather13.tar.gz\": {\n        \"sha256\": \"579ceb67899534a56d86509a72e6b00e4c5495119e8b0df71a89b69611521c90\",\n        \"size\": 339321831\n    },\n    \"BlockedIntersection_Town12_Route13352_Weather9.tar.gz\": {\n        \"sha256\": \"e0899f7c7a1a55c781a224d64220b8e5bb1f6974ea1a57afff4ff8d2452ba1f6\",\n        \"size\": 439453887\n    },\n    \"BlockedIntersection_Town12_Route13353_Weather18.tar.gz\": {\n        \"sha256\": \"48f9c38facad88ef38c45dad8562c251751f5a31a135e89fa5585b145fc8034e\",\n        \"size\": 435713352\n    },\n    \"BlockedIntersection_Town12_Route13354_Weather19.tar.gz\": {\n        \"sha256\": \"70bd33f36908205aa40fa0e1bef17c475a63c8f8be129eadaedc7ffcbd090185\",\n        \"size\": 275293210\n    },\n    \"BlockedIntersection_Town12_Route13355_Weather20.tar.gz\": {\n        \"sha256\": \"8addfeedcb1ebdef72cc716646d11c4c76e8ea568dbc8aabc75e76ad42bb18a3\",\n        \"size\": 375098285\n    },\n    \"BlockedIntersection_Town12_Route13356_Weather21.tar.gz\": {\n        \"sha256\": \"ccdcc20a9465687ff0bce75e18061a5e45d7c0bd701719f397a870f00bc1134e\",\n        \"size\": 386075532\n    },\n    \"BlockedIntersection_Town12_Route13357_Weather22.tar.gz\": {\n        \"sha256\": \"1a63f8a127d38047983fccb1b96699d5f8d8952ecef37abde8cbf3a49ff80468\",\n        \"size\": 226771270\n    },\n    \"BlockedIntersection_Town12_Route13358_Weather23.tar.gz\": {\n        \"sha256\": \"204f0c7dbcaadd3b5d5eeb6cd02eb1aa24766efdb12063bb02dfbdd35ea698a2\",\n        \"size\": 450975187\n    },\n    \"BlockedIntersection_Town12_Route13359_Weather23.tar.gz\": {\n        \"sha256\": \"af5c313847d7d8b55f434fb426ec186247b688c26a2135b770e4bd4bd7426516\",\n        \"size\": 459325572\n    },\n    \"BlockedIntersection_Town12_Route13360_Weather25.tar.gz\": {\n        \"sha256\": \"27cf89884893dbddf94fd840f4b813d9e09b5af1da189e29a4049b7c684f4234\",\n        \"size\": 208805372\n    },\n    \"BlockedIntersection_Town12_Route13364_Weather3.tar.gz\": {\n        \"sha256\": \"186b917b71f4424ad7fb7f6eccd151bc981b9a641783a79e612f81eb603d86da\",\n        \"size\": 395976121\n    },\n    \"BlockedIntersection_Town12_Route13365_Weather3.tar.gz\": {\n        \"sha256\": \"4e8023197f4a725252413b26dbcd2c97816610af150d80e6f52e73e2ac378631\",\n        \"size\": 901455355\n    },\n    \"BlockedIntersection_Town12_Route13366_Weather5.tar.gz\": {\n        \"sha256\": \"3ce6ad868c3ee05158377729050d6e1dfc00e31c0d7c23b64eb84522afd765c6\",\n        \"size\": 280627259\n    },\n    \"BlockedIntersection_Town12_Route13367_Weather6.tar.gz\": {\n        \"sha256\": \"b9be7a8e21be6ffdfc9232f974872306ad3709dc7d649d6427769bd6425d0d82\",\n        \"size\": 249894154\n    },\n    \"BlockedIntersection_Town12_Route13368_Weather7.tar.gz\": {\n        \"sha256\": \"0ead5b2a6efdcf0b9195f59ae46250bdc9d1be234d4b4bd5af00f65b4526b336\",\n        \"size\": 435048759\n    },\n    \"BlockedIntersection_Town12_Route13369_Weather8.tar.gz\": {\n        \"sha256\": \"be57027247b832f48a4ae927b62ae455299040a7f522315156263bbdc7642f63\",\n        \"size\": 491622492\n    },\n    \"BlockedIntersection_Town12_Route13371_Weather10.tar.gz\": {\n        \"sha256\": \"a7ad99c3c2acde4936c28a0d59ceef20aea7378d49127bab6324e953f3869d91\",\n        \"size\": 333655057\n    },\n    \"BlockedIntersection_Town12_Route13372_Weather11.tar.gz\": {\n        \"sha256\": \"83e45ff3668ce4f8a7b9bd3fc60d067c7788f252c2db5222095d4bd46cb030ce\",\n        \"size\": 512598715\n    },\n    \"BlockedIntersection_Town12_Route13373_Weather12.tar.gz\": {\n        \"sha256\": \"9400b9a21ef77263ed857222329df20ad2ad7f52ec208d82a1b073cac4aaadc6\",\n        \"size\": 206615169\n    },\n    \"BlockedIntersection_Town12_Route13374_Weather13.tar.gz\": {\n        \"sha256\": \"e67d3010a5706c8707dc1831bc22cbb6f48a689cfa54ea4a975cc22a74221980\",\n        \"size\": 403615194\n    },\n    \"BlockedIntersection_Town12_Route13375_Weather14.tar.gz\": {\n        \"sha256\": \"81771ee001f2acd23cce3d78c1cc127c072f2edb325ac522cf4a3ef76e3fb69d\",\n        \"size\": 254788210\n    },\n    \"BlockedIntersection_Town12_Route13376_Weather15.tar.gz\": {\n        \"sha256\": \"783b0dbeed9180fa184959857145fb40a429ab46f724ebc9dc1d258ef5442824\",\n        \"size\": 378241220\n    },\n    \"BlockedIntersection_Town12_Route13377_Weather8.tar.gz\": {\n        \"sha256\": \"49b7b5c9d39f17dc457fa7f48a6d4f6df17eb99671bf19caa67c2214398d2a2a\",\n        \"size\": 495009795\n    },\n    \"BlockedIntersection_Town12_Route13378_Weather9.tar.gz\": {\n        \"sha256\": \"37bda867f01d8ddd5e47f7451586cd216aa63c6a31d8580510e4fc777d56ab7a\",\n        \"size\": 197009164\n    },\n    \"BlockedIntersection_Town12_Route13379_Weather18.tar.gz\": {\n        \"sha256\": \"cbc6c7f79930101e8f0c1e10e72c51fdb04366eea9d0d6a425d6b790dcee3301\",\n        \"size\": 427142039\n    },\n    \"BlockedIntersection_Town12_Route13380_Weather19.tar.gz\": {\n        \"sha256\": \"5ef8bf05c6909e8bfdac02e68e7f7d67b85a133bd9c2c016397adae4e8507ce1\",\n        \"size\": 228449592\n    },\n    \"BlockedIntersection_Town12_Route13381_Weather20.tar.gz\": {\n        \"sha256\": \"799e033e5b9a872770a3c9fd6b8cfa75cf2acb93ab6b52ee00a2e03fd3812bbc\",\n        \"size\": 638851489\n    },\n    \"BlockedIntersection_Town12_Route13382_Weather21.tar.gz\": {\n        \"sha256\": \"ad441856f88fdf2c6e6ff3b01d0afd8d9dc3a55ae8a12a42a061ed8d6752530a\",\n        \"size\": 369805544\n    },\n    \"BlockedIntersection_Town12_Route13383_Weather22.tar.gz\": {\n        \"sha256\": \"a83aa5af96c62176e671df7875c10dcf2ae642abe70b4b9c636d78d4a2304cbb\",\n        \"size\": 222462825\n    },\n    \"BlockedIntersection_Town12_Route13384_Weather23.tar.gz\": {\n        \"sha256\": \"de9fb7b75b52240452f54ab6bf4a6c691f1a4d9eda28018f5352e9dd1f045980\",\n        \"size\": 475492724\n    },\n    \"BlockedIntersection_Town12_Route13385_Weather23.tar.gz\": {\n        \"sha256\": \"6ccc864365324c84bff300fa8303be6bbe9ced77ccff719dab31ada6fdd3695f\",\n        \"size\": 285547767\n    },\n    \"BlockedIntersection_Town12_Route13386_Weather25.tar.gz\": {\n        \"sha256\": \"1376f851f58deb91e7625e9050f0aa0ca9bfedaef7a9f044c13b3fa22457bc15\",\n        \"size\": 323149070\n    },\n    \"BlockedIntersection_Town12_Route13387_Weather0.tar.gz\": {\n        \"sha256\": \"5a88e2a5056a8db6af179ff3e299effcdd760af7c3d04983abe7214c74ed372b\",\n        \"size\": 275660388\n    },\n    \"BlockedIntersection_Town12_Route13388_Weather1.tar.gz\": {\n        \"sha256\": \"dc71f67c2651f999949d7eb2f6d5cf469d38c1443415bbe59a4009f01fca5b60\",\n        \"size\": 253432519\n    },\n    \"BlockedIntersection_Town12_Route13389_Weather2.tar.gz\": {\n        \"sha256\": \"a46fb10a8fbb54a323a43ebbfeb7eca3baacd78df1fe7e462158ceed5eac68a7\",\n        \"size\": 751999063\n    },\n    \"BlockedIntersection_Town12_Route13391_Weather3.tar.gz\": {\n        \"sha256\": \"2be16a2c4c44ce365f589fd0cb81d6004571036c115d0f3405e12999275fc7c4\",\n        \"size\": 232755587\n    },\n    \"BlockedIntersection_Town12_Route13393_Weather6.tar.gz\": {\n        \"sha256\": \"b214593af2abfb44b5d7d005acc973566e134bb8d575545dd622042be21f632d\",\n        \"size\": 525255244\n    },\n    \"BlockedIntersection_Town12_Route13394_Weather7.tar.gz\": {\n        \"sha256\": \"275f3df7d47ecbe2099fc1a421fe5323d59d338ab75be1576fa33e66487794b5\",\n        \"size\": 592099029\n    },\n    \"BlockedIntersection_Town12_Route13396_Weather9.tar.gz\": {\n        \"sha256\": \"41035ebb9b4f8b2006823c8d412fb0cf7ed1fb922fdf90308ef3a2b489422ab0\",\n        \"size\": 450031045\n    },\n    \"BlockedIntersection_Town12_Route13397_Weather10.tar.gz\": {\n        \"sha256\": \"a4e2982717caf73aa3e9566c0c87e7f7f343491a6c725ff948b93d6113d4aecb\",\n        \"size\": 407668726\n    },\n    \"BlockedIntersection_Town12_Route13402_Weather15.tar.gz\": {\n        \"sha256\": \"5c27f209a82d48185cd7c95b2ca91ca993749f3ba20108f96e6895e6a1b622b7\",\n        \"size\": 337705683\n    },\n    \"BlockedIntersection_Town12_Route13403_Weather8.tar.gz\": {\n        \"sha256\": \"19d515ff73350aa541b116a434f7027932cae3c4a3f3cfde191b579e515b3e8c\",\n        \"size\": 534335798\n    },\n    \"BlockedIntersection_Town12_Route13405_Weather18.tar.gz\": {\n        \"sha256\": \"afa44581e3fac4d90a915a3b43b5efecbba6c8ffd151e3bea2e7a2b968223f7d\",\n        \"size\": 813519631\n    },\n    \"BlockedIntersection_Town12_Route13406_Weather19.tar.gz\": {\n        \"sha256\": \"c2b51799d9e3b6f7913829b19edcafc82e686a786c9c3fb8406b7c5857e6fb9a\",\n        \"size\": 568262780\n    },\n    \"BlockedIntersection_Town12_Route13407_Weather20.tar.gz\": {\n        \"sha256\": \"874737690fa95088b3eba59f8f353a2d829241fb2d15d72d54bd3a7f3b71d804\",\n        \"size\": 336626451\n    },\n    \"BlockedIntersection_Town12_Route13408_Weather21.tar.gz\": {\n        \"sha256\": \"7eade4921f9e588d192bee9eab4d7d71bbaaef9777fa805503a4c80964aca89c\",\n        \"size\": 200031664\n    },\n    \"BlockedIntersection_Town12_Route13409_Weather22.tar.gz\": {\n        \"sha256\": \"8ec14349ba6fb6e66f2f9d749f3e4e903fb36c4eae166a0e87b70a35c43018c6\",\n        \"size\": 541673505\n    },\n    \"BlockedIntersection_Town12_Route13411_Weather23.tar.gz\": {\n        \"sha256\": \"6b53357541daaf349ca881857ed33480641ce915f328e32fe004bd4df2a1e03b\",\n        \"size\": 416768970\n    },\n    \"BlockedIntersection_Town12_Route13412_Weather25.tar.gz\": {\n        \"sha256\": \"4aa17a326d3bf052d004bfceaa23f580a9e12824d5070e91f5bf9539fb5c1e4a\",\n        \"size\": 261037352\n    },\n    \"BlockedIntersection_Town12_Route13413_Weather0.tar.gz\": {\n        \"sha256\": \"ca22b8787e7f1aa7c39d3228c066677b93caa303d1ce03422f516c38b623c763\",\n        \"size\": 256311217\n    },\n    \"BlockedIntersection_Town12_Route13414_Weather1.tar.gz\": {\n        \"sha256\": \"f8aad8a1be57ba3aa4fdfdd3ad4427c4dc04c4870ae3876de549406c8aa7763f\",\n        \"size\": 374725161\n    },\n    \"BlockedIntersection_Town12_Route13415_Weather2.tar.gz\": {\n        \"sha256\": \"7a81af6b6df9f1f5918d18bf8374a13aa7e68d126454f56c4aacefd4e6f633e9\",\n        \"size\": 431988281\n    },\n    \"BlockedIntersection_Town12_Route13416_Weather3.tar.gz\": {\n        \"sha256\": \"3523cfc0567c4906299dca059fc54103d872ec536827b1f414a932100c4604c3\",\n        \"size\": 448905435\n    },\n    \"BlockedIntersection_Town12_Route13417_Weather3.tar.gz\": {\n        \"sha256\": \"f8783049827091fa2cfddd2e301c5d95cae5c7f1776301bab1de05b419e8e5f7\",\n        \"size\": 358360300\n    },\n    \"BlockedIntersection_Town12_Route13418_Weather5.tar.gz\": {\n        \"sha256\": \"ac63e048fd44f5167664d662d33cccbbec39b474e2a741b9b91a0351a6874bee\",\n        \"size\": 226238366\n    },\n    \"BlockedIntersection_Town12_Route13420_Weather7.tar.gz\": {\n        \"sha256\": \"33c34fa18b2a950eb05830749334b6ab50deaf79619a38274fde1990ecd38d61\",\n        \"size\": 388731537\n    },\n    \"BlockedIntersection_Town12_Route13421_Weather8.tar.gz\": {\n        \"sha256\": \"5ce049165429eaf75677526e13d8be81ad945803b7e37569c45e051ea57dfff6\",\n        \"size\": 366739772\n    },\n    \"BlockedIntersection_Town12_Route13422_Weather9.tar.gz\": {\n        \"sha256\": \"9671abdf8b6e46db40793b1ba87f1df5da0952a0fc69c0370d0a9cd9210cc66a\",\n        \"size\": 500376984\n    },\n    \"BlockedIntersection_Town12_Route13423_Weather10.tar.gz\": {\n        \"sha256\": \"ac68eb3e442136e170efa441555eacd6ae80c2a914350b5a291f5c09d96be483\",\n        \"size\": 426576541\n    },\n    \"BlockedIntersection_Town12_Route13425_Weather12.tar.gz\": {\n        \"sha256\": \"165b4757727655a52e5f7e94edcf58056eabf0efa039585233e7f52bba113b08\",\n        \"size\": 350830319\n    },\n    \"BlockedIntersection_Town12_Route13426_Weather13.tar.gz\": {\n        \"sha256\": \"b42e474721c53add1b25926774ce714b509ab4d72e1ec3ac317db76875120cb2\",\n        \"size\": 463516315\n    },\n    \"BlockedIntersection_Town12_Route13428_Weather15.tar.gz\": {\n        \"sha256\": \"954d9aa0884902d69310facd21549570ccbc3ebddd718ebe413df95fbcbaedc0\",\n        \"size\": 1222737070\n    },\n    \"BlockedIntersection_Town12_Route13429_Weather8.tar.gz\": {\n        \"sha256\": \"c3d878b9eb606aa77595c6ec535ad8992a2e692007330701617c521454c6a27c\",\n        \"size\": 355689404\n    },\n    \"BlockedIntersection_Town12_Route13431_Weather18.tar.gz\": {\n        \"sha256\": \"3babc30e46ffee25099871639474a7ffbd0c1411eb177d78e9564d971b1e058b\",\n        \"size\": 497794424\n    },\n    \"BlockedIntersection_Town12_Route13432_Weather19.tar.gz\": {\n        \"sha256\": \"574eeb0ef3c45fbe2532eb3ac1e5d4a632745c48d34c6bc30e8970628fd31cb8\",\n        \"size\": 218863458\n    },\n    \"BlockedIntersection_Town12_Route13433_Weather20.tar.gz\": {\n        \"sha256\": \"d66cc637e92b46fdc99f94274e28f30c83564b184f904cb6605fc1a4e7c53cfd\",\n        \"size\": 391253857\n    },\n    \"BlockedIntersection_Town12_Route13435_Weather22.tar.gz\": {\n        \"sha256\": \"db1320eec47b0c928ada5efba050b75d47d1e9c09f281aa795d1c78aa5c60d2e\",\n        \"size\": 389039622\n    },\n    \"BlockedIntersection_Town12_Route13436_Weather23.tar.gz\": {\n        \"sha256\": \"9ab480a9019209cc7bcc6c336dd581b39ac7b676db0429809b3b1c4113f5eabd\",\n        \"size\": 705029536\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29361_Weather26.tar.gz\": {\n        \"sha256\": \"4f36123153e1b3ba45f7dad8ddb7f6d06ebd582e208acba8b279c5efbb4c1331\",\n        \"size\": 424197585\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29362_Weather0.tar.gz\": {\n        \"sha256\": \"b2fea8ad74c4058f8a82399b354b55c01b3dd9d71fcf2fc2cc77dbe846841917\",\n        \"size\": 442828976\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29364_Weather2.tar.gz\": {\n        \"sha256\": \"3fd708ed955b75ab0d22b3a121345ef7e3271560cdd761a283e0ca0df62760e7\",\n        \"size\": 447331488\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29367_Weather6.tar.gz\": {\n        \"sha256\": \"9c39154fe8b1c421d39d1924a47b3a7c93ab8026ca1b39ecf07b9a368b7d3114\",\n        \"size\": 353525588\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29370_Weather9.tar.gz\": {\n        \"sha256\": \"44d12fb82c517045d8dc773804e73da85c76c2200ff6d0c610d4010227eef9d9\",\n        \"size\": 356362929\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29371_Weather10.tar.gz\": {\n        \"sha256\": \"3c6a91070e27135867c3820315920777b9f08a035c3f69368f29f1a2b3d2c3f4\",\n        \"size\": 347772558\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29373_Weather12.tar.gz\": {\n        \"sha256\": \"92839a7b95d2522c9d6f1ca7a5fdbf245bd2596e4ffec484e6d26a6acd6e88e0\",\n        \"size\": 366935800\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29378_Weather19.tar.gz\": {\n        \"sha256\": \"67e6b7aa8fe11c2dd8fe55c2b379c4bcfaf1e176b4bd71f1caeb530b995d0906\",\n        \"size\": 389126431\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29384_Weather26.tar.gz\": {\n        \"sha256\": \"e0cbde3fe023157148c2b57b651bbfd2cb00d8a0438d0ddef6553ca6dbc9dfa7\",\n        \"size\": 392867037\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29388_Weather3.tar.gz\": {\n        \"sha256\": \"abdcf0cc5ee3bd9e9b54421533af629779f497b150657f04630bb82a4d951a4c\",\n        \"size\": 320335753\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29390_Weather6.tar.gz\": {\n        \"sha256\": \"8b1f885d7912551e6788b4c4846ea6e463ce192592c648d29d9a9244d5dbaee1\",\n        \"size\": 355557138\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29391_Weather7.tar.gz\": {\n        \"sha256\": \"60693ceefd92f7404c48596484433ff7e8e8deef98b47133466deb153763f941\",\n        \"size\": 776263372\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29392_Weather8.tar.gz\": {\n        \"sha256\": \"119002ca2959d6f5fd51b29e4102e95f327b755f696e0b69f20a9cbd17b392c8\",\n        \"size\": 342898072\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29398_Weather14.tar.gz\": {\n        \"sha256\": \"3172b5b1e4e67155483c15868b7cb92a59e1f18796bcb15caecb1cfd4029ff9a\",\n        \"size\": 313411666\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29406_Weather25.tar.gz\": {\n        \"sha256\": \"0a9ab5645c709efeef61a53d87cfa5cda596815432705e608643604a23327f80\",\n        \"size\": 269112944\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29411_Weather3.tar.gz\": {\n        \"sha256\": \"1bf98e1afb952ea07bb7b442951cfc871adc3c89a18b280cb0eb1888256eaf89\",\n        \"size\": 439145639\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29430_Weather26.tar.gz\": {\n        \"sha256\": \"cb87a105756d5e403cc9e0540ff3b4c27878e02263d4df24e6648a163bd06f9f\",\n        \"size\": 442952696\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29433_Weather2.tar.gz\": {\n        \"sha256\": \"4363d4f67039987063cec3eb5702b59b59d117defb8a6a8f4a88e0a5b0329c82\",\n        \"size\": 429982709\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29451_Weather23.tar.gz\": {\n        \"sha256\": \"0dc2c2b1e1f9a3b6b3659343d844e0e4e7cb89df9db81817817986752010711e\",\n        \"size\": 344136023\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29468_Weather15.tar.gz\": {\n        \"sha256\": \"0418d32f294d043a3aa8706db0a03353620b0504613626ed0fd609a25a65b693\",\n        \"size\": 352734456\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29471_Weather20.tar.gz\": {\n        \"sha256\": \"86297e5fc5d869813406c5e23caef13a08ccb724155e6b65242d19b3a2dcf6f4\",\n        \"size\": 385261324\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29474_Weather23.tar.gz\": {\n        \"sha256\": \"2a4915496a1ed0116483baf0c9fcd39b539ce934a2e183a1b72f384dc9437c96\",\n        \"size\": 365821300\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29475_Weather25.tar.gz\": {\n        \"sha256\": \"7a18c2de2a7612c4e147785eb678d88c2f3e9c471db5ab1eeaf2693e4561505d\",\n        \"size\": 303575538\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29476_Weather26.tar.gz\": {\n        \"sha256\": \"e27019d6b295420e9722e55d80035e40785271509e385b555212e414b6f133c4\",\n        \"size\": 649026023\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29492_Weather18.tar.gz\": {\n        \"sha256\": \"4faaf83d0e28017945a3b37b561ade7f73eb0a2c3e6ac0fe3b83b78e8c89e383\",\n        \"size\": 392379326\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29493_Weather19.tar.gz\": {\n        \"sha256\": \"a20919c9b1b1ffdb05ddc275cfaae36ef3e16491c03da87dc47f549064dd68e3\",\n        \"size\": 412755197\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29499_Weather26.tar.gz\": {\n        \"sha256\": \"297b73817be084eb4908398d4b4909cad287c219b1cf189ad9b64af254fb5f71\",\n        \"size\": 438074128\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29501_Weather1.tar.gz\": {\n        \"sha256\": \"2ebabbb492b67ee6dfbdc5952444d97b1f70cbcd910dfea8f1f4cb65bac4192a\",\n        \"size\": 223748514\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29505_Weather6.tar.gz\": {\n        \"sha256\": \"c72f90a380ea2ac7220c569919857f10d34febabe111db173383fe9508767e3c\",\n        \"size\": 370303247\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29506_Weather7.tar.gz\": {\n        \"sha256\": \"dc1602d695c0cb1ddc40c79bf65330755144ef9de51ac2d405bff411adc0d9fd\",\n        \"size\": 469290562\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29515_Weather18.tar.gz\": {\n        \"sha256\": \"beaf8da95349315efeca77fde084aa8c047b2b27ea3d6760dc1a23f2de09e117\",\n        \"size\": 413936302\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29521_Weather25.tar.gz\": {\n        \"sha256\": \"fc77af93e27228bea40a48218aa14ccb0dc9e49344c7135563386cd6a50469ad\",\n        \"size\": 255794378\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29534_Weather12.tar.gz\": {\n        \"sha256\": \"79b355be0420bfde590d4472fc7208aebfaca0f60c5e3ed4ebabf42cdd9bc6a8\",\n        \"size\": 269550600\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29607_Weather18.tar.gz\": {\n        \"sha256\": \"4218c042d3bdae110930ea80b443dc12dc8120683a87431e765d089fa5ad9186\",\n        \"size\": 353591831\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29616_Weather1.tar.gz\": {\n        \"sha256\": \"436b8f8edd5c27e0a04dcf84035d9f3b9d1001eb5006f3a5b681f9ff3bb75d31\",\n        \"size\": 446721285\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29618_Weather3.tar.gz\": {\n        \"sha256\": \"06320425af500d785ceb26693975a912a02904164a08ce616bee18328f757a61\",\n        \"size\": 391256464\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29635_Weather23.tar.gz\": {\n        \"sha256\": \"e6a9c373e3e657bc64631b5e77143badcfa6d28b006587631d49df1d1be50f82\",\n        \"size\": 379358295\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29641_Weather3.tar.gz\": {\n        \"sha256\": \"21b93665bf54b389dc97f090d1fdf1894bfad4eb4051212dc85bf8aa42d71cd4\",\n        \"size\": 490252460\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29647_Weather10.tar.gz\": {\n        \"sha256\": \"84f0b251aca0e62467774fcc18d276cd34f427004e8af672f06db20f37288313\",\n        \"size\": 357421132\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29648_Weather11.tar.gz\": {\n        \"sha256\": \"d333fe15f8c46ef1f51b8ea63ba9e9680c9aef10d89ea8949548ca2c91a92af2\",\n        \"size\": 267047562\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29673_Weather13.tar.gz\": {\n        \"sha256\": \"e0447f52d066879572e5aeb0b95f63c1e66a5eb4583d5332cceee77a3b38c567\",\n        \"size\": 695534057\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29680_Weather22.tar.gz\": {\n        \"sha256\": \"406b8c707581831730f67ba270958ed49189f10c7149f33561c7abc1be907aac\",\n        \"size\": 311147558\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29718_Weather12.tar.gz\": {\n        \"sha256\": \"1244d9ec6e980be9068f0fb0654e6b510780cfc805b867c5e2cb8965a4a42eb2\",\n        \"size\": 260167014\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29720_Weather14.tar.gz\": {\n        \"sha256\": \"cb6a2bbfbab2e90788bf52d0dd2cca7c43f33ab7fe85bf3cbaaa0cc83cba4e7f\",\n        \"size\": 307965147\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29725_Weather21.tar.gz\": {\n        \"sha256\": \"87429f2efe4e71bca39728d2dc0fe4239c2229b433c2984b5ac3585625807fe1\",\n        \"size\": 309412664\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29856_Weather12.tar.gz\": {\n        \"sha256\": \"c9f050a02e3ada0b306508b0351c5dd071af75ca378c697fdaf2a59d91a87c4f\",\n        \"size\": 250457772\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29859_Weather15.tar.gz\": {\n        \"sha256\": \"58baaf15b2d66112462df4f2c14522c7bfafd37c1a8d4324c8a9acd728b98474\",\n        \"size\": 308390720\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29871_Weather3.tar.gz\": {\n        \"sha256\": \"cd7b92801b5cd242b787e1b7912bd74a84a688b8c005207a8932cfd4d481d677\",\n        \"size\": 375773506\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29872_Weather5.tar.gz\": {\n        \"sha256\": \"c6d5214aae566900f2eb40ae29370ebf39a1d9061e0e97138fb47a85368a5a60\",\n        \"size\": 408710626\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29873_Weather6.tar.gz\": {\n        \"sha256\": \"9aa313b9a502e5a2db2c3c6e5ec9f052dd525240b83a78bdbaedf3fe15c96be8\",\n        \"size\": 282903655\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29875_Weather8.tar.gz\": {\n        \"sha256\": \"43feb8529fc811e06355d5e81509409811e4bf0fe5fc34a87ad57a3bc7b54c53\",\n        \"size\": 345124279\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29877_Weather10.tar.gz\": {\n        \"sha256\": \"910494b8162694cd787c97112689131a54561ab395dc0ae94c50c38404ef3153\",\n        \"size\": 343186837\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29879_Weather12.tar.gz\": {\n        \"sha256\": \"37a8610acb846996addd7ac165249ae575a9d49ef2f050e64bfa6cdf44c02b20\",\n        \"size\": 307305058\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29887_Weather22.tar.gz\": {\n        \"sha256\": \"ac8d3643b6086478070945578fcef8fa3628b05f8d07d51f972d1695019c1a38\",\n        \"size\": 720714333\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29891_Weather0.tar.gz\": {\n        \"sha256\": \"3df58dd1b0749cec4db777b5ffa29b9548665a0a7a4f1bc6ed5261e1d2b3958b\",\n        \"size\": 414110458\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29892_Weather1.tar.gz\": {\n        \"sha256\": \"274efe30c6a7edac3ed0e62567adc0c5e874af5b692f879239c88367897883a8\",\n        \"size\": 393977366\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29896_Weather6.tar.gz\": {\n        \"sha256\": \"15c189625b9826492a714fbc60fe320ab041bf83fc3a5df847a5d5793e5d53ce\",\n        \"size\": 375737572\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29898_Weather8.tar.gz\": {\n        \"sha256\": \"40828b3edb5e0414dd6ac031514e2ab8bb600b487a06a1ebfc6be3c377567d8e\",\n        \"size\": 350067479\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29918_Weather5.tar.gz\": {\n        \"sha256\": \"59634443a07ee516b001e1d345cd7b0549c0904d3ac17b961c2c999a9a007627\",\n        \"size\": 383397371\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29924_Weather11.tar.gz\": {\n        \"sha256\": \"63daea0bd46a3b184cad0814327bb65c382bf4694480b50825d4c2fe6e570f4b\",\n        \"size\": 262166451\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29929_Weather18.tar.gz\": {\n        \"sha256\": \"aa27043858033889d698a98eda740749fb31c3d336d9be2e2cf695413c13ec7e\",\n        \"size\": 383478960\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29932_Weather21.tar.gz\": {\n        \"sha256\": \"cfc1174507fb51b9584ae92b6e0d08e6c941de83518f5f4b653c875fe8ac23f3\",\n        \"size\": 355978751\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29933_Weather22.tar.gz\": {\n        \"sha256\": \"23bbef3799e2a35163aea5f422e1562530c180ed9c33e5c3c8ba3ee963d9835d\",\n        \"size\": 338508811\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29934_Weather23.tar.gz\": {\n        \"sha256\": \"6e75141fa244b58e0caab91375a92d73c98a1cb0e175ee8102b73365b3ff70b3\",\n        \"size\": 307997971\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route29937_Weather0.tar.gz\": {\n        \"sha256\": \"99ece4b8d86a91fc3c0a4b63891db8b473dfb5d8cea5d6779d4e488ad15d4c56\",\n        \"size\": 784570570\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30086_Weather12.tar.gz\": {\n        \"sha256\": \"61e39484fd76d8cf13ae78badf978f2e4ea5d79f76fbcf81cf6a25345639ae10\",\n        \"size\": 284063353\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30087_Weather13.tar.gz\": {\n        \"sha256\": \"7a7d1b83d27d8b7448c7cb244f2c2710bff6a36526ea1245ece32c80dcc15b63\",\n        \"size\": 332523064\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30090_Weather18.tar.gz\": {\n        \"sha256\": \"4512e44814553db4cc145a6de33e14249a586cfed0e27f68e7d862cd8a27cdc6\",\n        \"size\": 446846415\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30091_Weather19.tar.gz\": {\n        \"sha256\": \"98fab5d46fd9fe4e7f56b611c1737a7c640a72e043550824efda96cf74a0f8d0\",\n        \"size\": 507717064\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30094_Weather22.tar.gz\": {\n        \"sha256\": \"5477dbde1d8ddc9c776e51728c3b568fe554deb33ef7d9f28ca2b9b7a72b499c\",\n        \"size\": 329078321\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30102_Weather5.tar.gz\": {\n        \"sha256\": \"93ceb229a7f2f28572ec223b2a1a5e190d5897dd6fd76b0e9b8a009fcf356847\",\n        \"size\": 458996629\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30104_Weather7.tar.gz\": {\n        \"sha256\": \"d004ab80b32e7917b6165e9d3e18415ac442483c3dca816df23571f009186286\",\n        \"size\": 419449718\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30107_Weather10.tar.gz\": {\n        \"sha256\": \"f64454f02c87aa9ead541036567c2c1bd80186005c2cf90db7f16c57d00c4e4c\",\n        \"size\": 402043457\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30108_Weather11.tar.gz\": {\n        \"sha256\": \"4f8debe6a85f8a5f0c389a84cff9854e6e6d55b0fa8ffc1327c35896e05a5ba4\",\n        \"size\": 265487699\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30118_Weather23.tar.gz\": {\n        \"sha256\": \"a56d9d530e0e3047c0c03f151e09a150310b6fff4e488fa01bdab6a93dd294cc\",\n        \"size\": 452794511\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30120_Weather26.tar.gz\": {\n        \"sha256\": \"8b09180d7459b6c902369103ac89027b9ca960aa14b6b646803bafd4768d9a01\",\n        \"size\": 400200882\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30123_Weather2.tar.gz\": {\n        \"sha256\": \"ca8a2514484b033572a86046971c38dc525fe3b70bc59f6bec3fef5d82b276fa\",\n        \"size\": 872310896\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30124_Weather3.tar.gz\": {\n        \"sha256\": \"9ad2751f16ad8c4818408d221c40704b37da83a0915ea02d6c5d61f452ccc13a\",\n        \"size\": 351135087\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30138_Weather20.tar.gz\": {\n        \"sha256\": \"f8ab16cdb88256337c5591835436b8bf4e774364aed8e24c9a68b56cdff202d2\",\n        \"size\": 391138663\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30143_Weather26.tar.gz\": {\n        \"sha256\": \"69a3cdc8bf718ba1895ff924c2cb7d2cb05c01d7b9896f78c4166c799282317b\",\n        \"size\": 415189294\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30144_Weather0.tar.gz\": {\n        \"sha256\": \"9104d952e6c3d5e070a95a7eac8220607dbf5b0075e6d5f066a9a766ccee658e\",\n        \"size\": 442885598\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30148_Weather5.tar.gz\": {\n        \"sha256\": \"57806f10a9375dddf0a7b2a9965e36c7b0abe89baf03a924c9887e4926a2fd60\",\n        \"size\": 385038008\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30158_Weather15.tar.gz\": {\n        \"sha256\": \"a5f62c47d876a4f836c389c56293b563b077647a2e56c3fccb1b7e5b4369256d\",\n        \"size\": 307646303\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30162_Weather21.tar.gz\": {\n        \"sha256\": \"d8c8c6ff6c6aed88d1539d69d3b64ac87b826420fe45fb4f385a7e6b0a970c12\",\n        \"size\": 489205117\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30163_Weather22.tar.gz\": {\n        \"sha256\": \"ba98aeea60a2a1f78c04b6537054dd47e2afd9184cb5bcb94a43c75780913da5\",\n        \"size\": 348884892\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30164_Weather23.tar.gz\": {\n        \"sha256\": \"4d6d3f7f642913465fd55e26140c29b6177b42a562e8e11fb880a11aae2b991c\",\n        \"size\": 320250186\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30167_Weather0.tar.gz\": {\n        \"sha256\": \"31af45cef56e2b686130a92a8c5fa7580585e33c8225636c8cb3316d584f92be\",\n        \"size\": 466052443\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30188_Weather25.tar.gz\": {\n        \"sha256\": \"b9e4eeb28c25da38ab868fed1885dd592b3d2b842fbfda14600c22544950e5c0\",\n        \"size\": 256147543\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30189_Weather26.tar.gz\": {\n        \"sha256\": \"fc5bcfce92b43350f8535f43bc6592f1863f5614ccb35a6536614d7551dab7ae\",\n        \"size\": 436619224\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30198_Weather9.tar.gz\": {\n        \"sha256\": \"5c0dce431c7602ee5ae411d47573d0c187731ed3360ee0e2ddfbb9b1db87cb80\",\n        \"size\": 248179887\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30199_Weather10.tar.gz\": {\n        \"sha256\": \"284e13e8663ef0df594c74f433d542deb31a5708a1c5054fccd33ed173b6325d\",\n        \"size\": 358215501\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30222_Weather10.tar.gz\": {\n        \"sha256\": \"16a177c70898b4801fb0383e603c82f4c1bfc3cc3e403b0505ec151c7298a59a\",\n        \"size\": 365626815\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30223_Weather11.tar.gz\": {\n        \"sha256\": \"de9a3f0358a2268e654ef11321e54e21b9b25c14a25b495fb8bd6e6cd26fb0cf\",\n        \"size\": 272693799\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30244_Weather9.tar.gz\": {\n        \"sha256\": \"745783fad229c9193b3c5dc5979fffa285f7ee20f85cb905fc9b5d5d74a8bfcf\",\n        \"size\": 307946165\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30257_Weather25.tar.gz\": {\n        \"sha256\": \"271683870cac695e33116a638ec405416fb6832c8c6695c980fc45ee9d6f8bd0\",\n        \"size\": 253367543\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30268_Weather10.tar.gz\": {\n        \"sha256\": \"fab62069cca934e6c9373a6775b85ce5c54550d5d6644a159b6b0cb1e6494897\",\n        \"size\": 411369878\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30274_Weather18.tar.gz\": {\n        \"sha256\": \"f1de3d456bb9581fb7ec04a45997a8d7793d2f2df8872a03009e9f8c871a9475\",\n        \"size\": 743367500\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30282_Weather0.tar.gz\": {\n        \"sha256\": \"f9e544bece2456ec4eecfa860ce1b7803b6805c11aaae6cb132aba2c7c30b560\",\n        \"size\": 461974356\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30287_Weather6.tar.gz\": {\n        \"sha256\": \"9d54374d87f6c0c3d712503d215a279b4309612b03d975be5e09c74a9480530b\",\n        \"size\": 342170421\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route30294_Weather13.tar.gz\": {\n        \"sha256\": \"33d8c1bd2f6e35761b24ce20275a0e0092f9c88b6ebbe8b6244e6d60fad819e5\",\n        \"size\": 294449892\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route538_Weather10.tar.gz\": {\n        \"sha256\": \"1def608be6e055f04513f03b40fa135730514ac1950916cb470ebfe247e424e6\",\n        \"size\": 364403818\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route589_Weather15.tar.gz\": {\n        \"sha256\": \"c83bc04552d321d955be854348d9da90f06e799434ee0d85717eb559ea6d9fe6\",\n        \"size\": 305940518\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route597_Weather26.tar.gz\": {\n        \"sha256\": \"31749f868d9019447933efaa7ded24236c1e16cefe2f53dd267111b83a88c2b2\",\n        \"size\": 369928584\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route624_Weather3.tar.gz\": {\n        \"sha256\": \"7fe7e7b6a69541f37332058ef2e493be4887f727a0fbeae492d4877b96d020c0\",\n        \"size\": 424411974\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route780_Weather25.tar.gz\": {\n        \"sha256\": \"e55d042c96e8b849327064d028612c5fc2dd965ae80de7f4da60cf87cca7b673\",\n        \"size\": 308262769\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route802_Weather23.tar.gz\": {\n        \"sha256\": \"dd039199b01bc752f9acb434ac98eefec7cc0868f3e0c7c583f6511a14bd11bb\",\n        \"size\": 310181595\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route821_Weather19.tar.gz\": {\n        \"sha256\": \"666b4bf4d70b341ac938bdab21b223400a5e78bb04a6cc3b96d460e7cc6588cc\",\n        \"size\": 367101151\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route852_Weather1.tar.gz\": {\n        \"sha256\": \"a642272fab5554b41766e257303b4c5ee206938339cf61408ab49672c173b4d8\",\n        \"size\": 433590728\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route895_Weather25.tar.gz\": {\n        \"sha256\": \"4705e03d998ea251e25359a9b435d40d84e42944e80dfa98ab77d8c91bbdbb3b\",\n        \"size\": 319625195\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route912_Weather18.tar.gz\": {\n        \"sha256\": \"da5dbe907d90a7fd22c109d92e98589548f465eeda9e75ea3690b71d7d576b4c\",\n        \"size\": 389488901\n    },\n    \"ConstructionObstacleTwoWays_Town13_Route921_Weather1.tar.gz\": {\n        \"sha256\": \"e630df0e233521126c68f24720660933f81acfeac4b048cae0409773b2359f1f\",\n        \"size\": 368301513\n    },\n    \"ControlLoss_Town13_Route2022_Weather25.tar.gz\": {\n        \"sha256\": \"c88c7c2cbe2e5bde2af39d63ae77127934150a94ec8b69cb2e3551a56770b015\",\n        \"size\": 229739655\n    },\n    \"ControlLoss_Town13_Route2023_Weather26.tar.gz\": {\n        \"sha256\": \"3fa0c2514053dfc4c2e08aeaea9b5dafdf707e023e4d9f3c354dfdede6f41823\",\n        \"size\": 274289545\n    },\n    \"ControlLoss_Town13_Route32765_Weather26.tar.gz\": {\n        \"sha256\": \"65e1296f37383dae39a82ca981a2bb5b67fb11dfb3aa7de4d2f76a89d3ae4cd1\",\n        \"size\": 535042557\n    },\n    \"ControlLoss_Town13_Route32769_Weather3.tar.gz\": {\n        \"sha256\": \"3ee0510f0f7dc959f91335588b6fefc8206e23038c7872333678cca04da3659f\",\n        \"size\": 572802081\n    },\n    \"ControlLoss_Town13_Route32899_Weather21.tar.gz\": {\n        \"sha256\": \"309190a79a69bff76f2e69dfe6b265d32bcad20a23ec8eea24f8d27619f5f8e0\",\n        \"size\": 155969711\n    },\n    \"CrossingBicycleFlow_Town12_Route35364_Weather0.tar.gz\": {\n        \"sha256\": \"807d6262bf922721879ed0592129f397b807eac48b4accdcaac8f3aa8aff76af\",\n        \"size\": 405949472\n    },\n    \"CrossingBicycleFlow_Town12_Route35368_Weather0.tar.gz\": {\n        \"sha256\": \"c2d61f94dc1b582a450427b70c46b093df983b388925238f286d7020e5c438ec\",\n        \"size\": 412225568\n    },\n    \"CrossingBicycleFlow_Town12_Route35381_Weather0.tar.gz\": {\n        \"sha256\": \"3e074de00a8a0c3a04c3974b9c930e7bac1922925e101a0df74ddb6385b4beb7\",\n        \"size\": 476060971\n    },\n    \"CrossingBicycleFlow_Town12_Route35384_Weather0.tar.gz\": {\n        \"sha256\": \"fe36262b0fa55115d1ac4a0c1bded03d0fb97238f0ac7e67e86bd81a57083c75\",\n        \"size\": 385226419\n    },\n    \"CrossingBicycleFlow_Town12_Route35389_Weather0.tar.gz\": {\n        \"sha256\": \"19e006fef0b9ffd1a1485147d962cdee1fc04da08acaf52bbbbb87c962a97652\",\n        \"size\": 710203372\n    },\n    \"CrossingBicycleFlow_Town12_Route35391_Weather0.tar.gz\": {\n        \"sha256\": \"174283599ea351b49da106d9f3160e21a353dd93b4791ca2de06c32dcc41712f\",\n        \"size\": 453121160\n    },\n    \"CrossingBicycleFlow_Town12_Route35394_Weather0.tar.gz\": {\n        \"sha256\": \"7a72adf2a68722122b85f6afc0aeec77b3d4147a8c25add0c6a78de2bb8af280\",\n        \"size\": 635110079\n    },\n    \"CrossingBicycleFlow_Town12_Route35395_Weather0.tar.gz\": {\n        \"sha256\": \"32f7a4129e6ca31fdc49256aa738d529c093b68207b0f1296ad50e7509233db8\",\n        \"size\": 449116847\n    },\n    \"CrossingBicycleFlow_Town12_Route35397_Weather0.tar.gz\": {\n        \"sha256\": \"545d4c3fe440d36f5208111434b9e26a675bfceb89cd0d3a0ec62c44452dc160\",\n        \"size\": 431292709\n    },\n    \"CrossingBicycleFlow_Town12_Route35398_Weather0.tar.gz\": {\n        \"sha256\": \"3f1cac1793869c557db86aaa59e3c951e595b39af39218e316ede7bb8ba75523\",\n        \"size\": 463109458\n    },\n    \"CrossingBicycleFlow_Town12_Route35399_Weather0.tar.gz\": {\n        \"sha256\": \"9eea1bdc43a7b460b82b2808a40fef30aa10a26caafdd493d73d07ac5bf1be90\",\n        \"size\": 512937254\n    },\n    \"CrossingBicycleFlow_Town12_Route35405_Weather0.tar.gz\": {\n        \"sha256\": \"45f123e8f828e970ae25992003b7455ea490086c660e4b455fb633bd2c40df33\",\n        \"size\": 450652178\n    },\n    \"CrossingBicycleFlow_Town12_Route35408_Weather0.tar.gz\": {\n        \"sha256\": \"8bc5fda8e57314b8bc9d1c939fed711ee7c8546fe2225414b5f8b8383fb8ba02\",\n        \"size\": 474222271\n    },\n    \"CrossingBicycleFlow_Town12_Route35416_Weather0.tar.gz\": {\n        \"sha256\": \"d101d93b6e0d34ec909ece8ed62e7970ab780eae559e55a36480d5ddb78860d3\",\n        \"size\": 516088680\n    },\n    \"CrossingBicycleFlow_Town12_Route35417_Weather0.tar.gz\": {\n        \"sha256\": \"25e73785cd706ba546e7886ff52f3124fc48da8d0d2c31dcfc33ab471726de7e\",\n        \"size\": 537569243\n    },\n    \"CrossingBicycleFlow_Town12_Route35420_Weather0.tar.gz\": {\n        \"sha256\": \"47669e9da34f5c60bc12661b3c2f4560ee464391ec5c419bedf5c082f6811243\",\n        \"size\": 458635319\n    },\n    \"CrossingBicycleFlow_Town12_Route35426_Weather1.tar.gz\": {\n        \"sha256\": \"2e0f1a443c17a7abf217f9b89a99c30a97480167f928df9e9c2c6aa09830739f\",\n        \"size\": 450599293\n    },\n    \"CrossingBicycleFlow_Town12_Route35429_Weather1.tar.gz\": {\n        \"sha256\": \"6895e35e9b13b0cd37048b22812ea9abe62e33b82669575f32277fe21ab7ab6b\",\n        \"size\": 552871306\n    },\n    \"CrossingBicycleFlow_Town12_Route35526_Weather2.tar.gz\": {\n        \"sha256\": \"c3e12771b2439445f260e430a3fa075f6ac1493e89f01b753b449aa8f6fd7096\",\n        \"size\": 418342156\n    },\n    \"CrossingBicycleFlow_Town12_Route35529_Weather2.tar.gz\": {\n        \"sha256\": \"714a623523b7da356932855ec4b7549155bbc7b44cc9813295c101257850a5b8\",\n        \"size\": 465820983\n    },\n    \"CrossingBicycleFlow_Town12_Route35530_Weather2.tar.gz\": {\n        \"sha256\": \"9d5af10f4f578025ac32aef47997af81fc2d560a12b80003dbd6053c216a2ee7\",\n        \"size\": 430408034\n    },\n    \"CrossingBicycleFlow_Town12_Route35531_Weather2.tar.gz\": {\n        \"sha256\": \"5f2409b4a63e4c88f26e0fbf6f7963846d4cf68eb157b6c37a3d50a2e2e5ff73\",\n        \"size\": 463996997\n    },\n    \"CrossingBicycleFlow_Town12_Route35536_Weather2.tar.gz\": {\n        \"sha256\": \"6dd1d02a435003abcea1520daa863cd05b9ec1e342a2260d7a3cf92bc472c373\",\n        \"size\": 499435893\n    },\n    \"CrossingBicycleFlow_Town12_Route35539_Weather2.tar.gz\": {\n        \"sha256\": \"eb42fec04d2e2ad72ddae57f2d2ac7760ee20a30e250e2416c32b28cd8fbcf37\",\n        \"size\": 631810793\n    },\n    \"CrossingBicycleFlow_Town12_Route35541_Weather2.tar.gz\": {\n        \"sha256\": \"5af1f44d99a7d93f5375870be3f0dd84121438c1a218a8c71f6e9b31ba37bf66\",\n        \"size\": 438149667\n    },\n    \"CrossingBicycleFlow_Town12_Route35543_Weather3.tar.gz\": {\n        \"sha256\": \"96851ae52add9a716cc736dafd0d2300547a379ccfb3777f1d37ad00c2a2df96\",\n        \"size\": 423414404\n    },\n    \"CrossingBicycleFlow_Town12_Route35544_Weather3.tar.gz\": {\n        \"sha256\": \"5701a47c21bbe82c2f54898173d128afa415b7b794b2d5c71cc3aec360f7b0e2\",\n        \"size\": 412122796\n    },\n    \"CrossingBicycleFlow_Town12_Route35546_Weather3.tar.gz\": {\n        \"sha256\": \"cb8f9188c56075930f3596228ad350df759fc08885000e0d332ca540da8874ce\",\n        \"size\": 438798824\n    },\n    \"CrossingBicycleFlow_Town12_Route35550_Weather3.tar.gz\": {\n        \"sha256\": \"5c59034d08320bd292661eeb24d9440f9b05aeaa30e1b4ea18fd44532d0236a5\",\n        \"size\": 429519808\n    },\n    \"CrossingBicycleFlow_Town12_Route35551_Weather3.tar.gz\": {\n        \"sha256\": \"45c3bfc4bac11b807a663de4676c233c798093700159a342d9c52f3258d65e83\",\n        \"size\": 389526428\n    },\n    \"CrossingBicycleFlow_Town12_Route35554_Weather3.tar.gz\": {\n        \"sha256\": \"3c2c8de6e85bae67a79ac7a6611e50028ccb5a66358e4cf77698deddeef24868\",\n        \"size\": 413338272\n    },\n    \"CrossingBicycleFlow_Town12_Route35557_Weather3.tar.gz\": {\n        \"sha256\": \"c6f63c46cdde1d33114e9e6a1c60ea89f95b0770388ec69717ad71dbe9ab83b9\",\n        \"size\": 147374988\n    },\n    \"CrossingBicycleFlow_Town12_Route35558_Weather3.tar.gz\": {\n        \"sha256\": \"23f1a9e97285ea1dd6f2fdcf56d1affb464c6863ab6127ccf7d7fc29b8f4135f\",\n        \"size\": 954481181\n    },\n    \"CrossingBicycleFlow_Town12_Route35562_Weather3.tar.gz\": {\n        \"sha256\": \"c9fc041dc075242e759f051285bb847d1da1e7bd5a05384ea3556880f29e2f9b\",\n        \"size\": 437113033\n    },\n    \"CrossingBicycleFlow_Town12_Route35565_Weather3.tar.gz\": {\n        \"sha256\": \"58965931a5047e1bb47e456af1cd32217d578334d48a435dbf7d60b02fefcbdc\",\n        \"size\": 437182879\n    },\n    \"CrossingBicycleFlow_Town12_Route35570_Weather3.tar.gz\": {\n        \"sha256\": \"61a4e0e4a6b4dd5f675276c6eb5b72954d7859dffeab4e8bb7743141a90c2df2\",\n        \"size\": 453308079\n    },\n    \"CrossingBicycleFlow_Town12_Route35572_Weather3.tar.gz\": {\n        \"sha256\": \"0b4e00fcadd516e5be2a62a22a22f9651891adfaf6465f519c15a6179195617c\",\n        \"size\": 542978260\n    },\n    \"CrossingBicycleFlow_Town12_Route35573_Weather3.tar.gz\": {\n        \"sha256\": \"4b3b0ae3d4b6f428e616b71fa39c82c2edbe1bd3ef98da57899af235b233b97a\",\n        \"size\": 498592730\n    },\n    \"CrossingBicycleFlow_Town12_Route35574_Weather3.tar.gz\": {\n        \"sha256\": \"3e4b8d969d278a3733f4ec092af0d8857865da111b890d88ac09413ce854fe28\",\n        \"size\": 612639872\n    },\n    \"CrossingBicycleFlow_Town12_Route35575_Weather3.tar.gz\": {\n        \"sha256\": \"12d575cda5483f5d14e30cee19e6df877d094be20f821526cbe1dea2ce489bc8\",\n        \"size\": 433745433\n    },\n    \"CrossingBicycleFlow_Town12_Route35576_Weather3.tar.gz\": {\n        \"sha256\": \"8304fb03e14bc96436383ccdf256e8ac3d02a65d970cf30e3f7c528bb8543d32\",\n        \"size\": 170624469\n    },\n    \"CrossingBicycleFlow_Town12_Route35578_Weather3.tar.gz\": {\n        \"sha256\": \"028a32bd100c96dacd25658635eca2707e1f498f9d6b0e765956ed6d39e2ed8e\",\n        \"size\": 441053312\n    },\n    \"CrossingBicycleFlow_Town12_Route35579_Weather3.tar.gz\": {\n        \"sha256\": \"09c55f0d2f4db45afa8d659ec5985088cd9ca547052e4cc6364a52b6fd47bb30\",\n        \"size\": 434926410\n    },\n    \"CrossingBicycleFlow_Town12_Route35582_Weather3.tar.gz\": {\n        \"sha256\": \"e1d3dc3ef5c040291d2afe69b31aec0d247f382aff3464acd3795e518412e70a\",\n        \"size\": 447774578\n    },\n    \"CrossingBicycleFlow_Town12_Route35586_Weather3.tar.gz\": {\n        \"sha256\": \"1a7a998bf43ef7a52f79cf3350e2596787afdba3612fd792c67b9586c01a58d2\",\n        \"size\": 410021272\n    },\n    \"CrossingBicycleFlow_Town12_Route35587_Weather3.tar.gz\": {\n        \"sha256\": \"524c99ddb197502078f53142bdc33caad586e114fb188441a8df6a6a83d1f90c\",\n        \"size\": 447140405\n    },\n    \"CrossingBicycleFlow_Town12_Route35588_Weather3.tar.gz\": {\n        \"sha256\": \"c1b4c6fe69591f92b56d54cbd36343d185421fa60cceb5d67f14b03c2d7e48b5\",\n        \"size\": 468034313\n    },\n    \"CrossingBicycleFlow_Town12_Route35589_Weather3.tar.gz\": {\n        \"sha256\": \"e44a7d46c89338ac5098d0e39054924c2818cd8c730732691ca7150cdf70a1ad\",\n        \"size\": 449655499\n    },\n    \"CrossingBicycleFlow_Town12_Route35594_Weather3.tar.gz\": {\n        \"sha256\": \"b08f1995996cbe6699a503a44512c671966b1db3d7eb5e1d6a3468175659c7b9\",\n        \"size\": 468364695\n    },\n    \"CrossingBicycleFlow_Town12_Route35596_Weather3.tar.gz\": {\n        \"sha256\": \"85dad858af332a1da0b389de843a1efdc127b643c0a78348ab92446859818d90\",\n        \"size\": 503631119\n    },\n    \"CrossingBicycleFlow_Town12_Route35600_Weather3.tar.gz\": {\n        \"sha256\": \"de596330395362badcffae7c1ba7aa652496d901076b20a5659febcbd63f04c6\",\n        \"size\": 416471577\n    },\n    \"CrossingBicycleFlow_Town12_Route35601_Weather3.tar.gz\": {\n        \"sha256\": \"761d6c9d1e8e6517dbc4e964feee207380950ab9e3843b1f0c0bceabbb87e877\",\n        \"size\": 418228315\n    },\n    \"CrossingBicycleFlow_Town12_Route36560_Weather22.tar.gz\": {\n        \"sha256\": \"cb563cd431407ac7d01ccc6a9bc0d7a4918107f570d9cd9d495ec9ce745987f4\",\n        \"size\": 366390767\n    },\n    \"CrossingBicycleFlow_Town12_Route36564_Weather23.tar.gz\": {\n        \"sha256\": \"7163a05544fbee2f934a17b6c5f82ab12f42d63f8514755567de775db45b56b2\",\n        \"size\": 343218198\n    },\n    \"CrossingBicycleFlow_Town12_Route36565_Weather23.tar.gz\": {\n        \"sha256\": \"59025b1be02e46c6e86823073958c894d6abf3f1e4bacfcdab9afb50aa5c4aa9\",\n        \"size\": 370862785\n    },\n    \"CrossingBicycleFlow_Town12_Route36569_Weather23.tar.gz\": {\n        \"sha256\": \"54cd364b7dbe5c2cdaa02890a8ffa00d5eb70927193c1e12a2734d6a0a8285c1\",\n        \"size\": 489342797\n    },\n    \"CrossingBicycleFlow_Town12_Route36571_Weather23.tar.gz\": {\n        \"sha256\": \"0f0c8cc5b12f988c0e441fa1bead328c6eaaef6b43e52fd08bb5ecc18d9bbf6d\",\n        \"size\": 447396626\n    },\n    \"CrossingBicycleFlow_Town12_Route36572_Weather23.tar.gz\": {\n        \"sha256\": \"d54a0c873c3167014ec27a0e3e1ce3aec3568a291557b8c01570cbc678acce6d\",\n        \"size\": 364834681\n    },\n    \"CrossingBicycleFlow_Town12_Route36575_Weather23.tar.gz\": {\n        \"sha256\": \"3136f45519b66697d48fd11313253d54bc0fde87b0948c0e886ab317b3dc46b8\",\n        \"size\": 367387165\n    },\n    \"CrossingBicycleFlow_Town12_Route36578_Weather23.tar.gz\": {\n        \"sha256\": \"be3134ada8f5716b059186e2b50027c2d15aacc21b6941ceaeef370cfbe5a066\",\n        \"size\": 802241115\n    },\n    \"CrossingBicycleFlow_Town12_Route36582_Weather23.tar.gz\": {\n        \"sha256\": \"b0c2a81aa12bd98484484b2d07293dd20c6dbfa36081cc96d4d40bbfebd47359\",\n        \"size\": 364962325\n    },\n    \"CrossingBicycleFlow_Town12_Route36585_Weather23.tar.gz\": {\n        \"sha256\": \"c72573f1b1f38463709d2cf500ff3f7c1560ca00b6d6adb5bc8e2fe7ec707fa7\",\n        \"size\": 373472527\n    },\n    \"CrossingBicycleFlow_Town12_Route36586_Weather23.tar.gz\": {\n        \"sha256\": \"9e196708cc235e3b0a892f6e07f0e95fcfde903a39e597cc2d92c706fb135a5e\",\n        \"size\": 385762948\n    },\n    \"CrossingBicycleFlow_Town12_Route36587_Weather23.tar.gz\": {\n        \"sha256\": \"781fb1ad249ccd83b71134ac5bff7f73e94d296fb725d2f26fa1d52a260159c8\",\n        \"size\": 328561442\n    },\n    \"CrossingBicycleFlow_Town12_Route36591_Weather23.tar.gz\": {\n        \"sha256\": \"a23eea269b9d34ef0cd07b2036c589fdde59dd6d6f2d0e937c1830614f942c14\",\n        \"size\": 380760696\n    },\n    \"CrossingBicycleFlow_Town12_Route36594_Weather23.tar.gz\": {\n        \"sha256\": \"da7be81cd2a4053bbe808773e28326f3b28dc8892c46f2b6e6166228bb726392\",\n        \"size\": 531323046\n    },\n    \"CrossingBicycleFlow_Town12_Route36595_Weather23.tar.gz\": {\n        \"sha256\": \"ba9939d89079c370a2c223e2433dd3fea2bd601b5b1fa6265517af1244dd107d\",\n        \"size\": 360884723\n    },\n    \"CrossingBicycleFlow_Town12_Route36596_Weather23.tar.gz\": {\n        \"sha256\": \"bb4e52a91ab22e88a30d445200578e9655f18eeff4230a0eddefab2567d2f216\",\n        \"size\": 144264443\n    },\n    \"CrossingBicycleFlow_Town12_Route36597_Weather23.tar.gz\": {\n        \"sha256\": \"085dec00193a7b8e015372924d747b9d84b6e778c5dcc486959ad87a05e170e4\",\n        \"size\": 341862432\n    },\n    \"CrossingBicycleFlow_Town12_Route36601_Weather23.tar.gz\": {\n        \"sha256\": \"bc245533d863cbd6067146bcca996c22df5cbf2f6fcabeb692b7ff0f0e567378\",\n        \"size\": 416867324\n    },\n    \"CrossingBicycleFlow_Town12_Route36603_Weather23.tar.gz\": {\n        \"sha256\": \"d32fc76bfacf3a47d323562fa26ed2b2c41d65dd0de8ddbea90ebcd0cee052e4\",\n        \"size\": 461238165\n    },\n    \"CrossingBicycleFlow_Town12_Route36607_Weather23.tar.gz\": {\n        \"sha256\": \"77713139986b3d8759a79f159dbc69eb106e8a3c88c2dfa4eaac53337b50b48d\",\n        \"size\": 388703743\n    },\n    \"CrossingBicycleFlow_Town12_Route36608_Weather23.tar.gz\": {\n        \"sha256\": \"594d4f6ec0b2b2a76153e1d1bff9388b9d06435fd29ed535fecc2eccfcab2118\",\n        \"size\": 390361382\n    },\n    \"CrossingBicycleFlow_Town12_Route36615_Weather23.tar.gz\": {\n        \"sha256\": \"5c47c81aedb9afa97e75f528b92fdfd69bf3b673ea4cb4c313f888d1aa42d786\",\n        \"size\": 372463994\n    },\n    \"CrossingBicycleFlow_Town12_Route36617_Weather23.tar.gz\": {\n        \"sha256\": \"735e90fcc74d0476f5ce03063dd8c17c31bc3735fd3c65f179bd00353a1b7ce7\",\n        \"size\": 466107418\n    },\n    \"CrossingBicycleFlow_Town12_Route36620_Weather23.tar.gz\": {\n        \"sha256\": \"9e95da393bafc99a45a0961e5c41b25e3a0f1ebc793cfda36c858d1fdb12ab1f\",\n        \"size\": 401822571\n    },\n    \"CrossingBicycleFlow_Town12_Route36622_Weather23.tar.gz\": {\n        \"sha256\": \"7f6e1028e96cb65eaa90d7625e2be3beee6caa1e74d5bbd83db17b6772ad8596\",\n        \"size\": 784233239\n    },\n    \"CrossingBicycleFlow_Town12_Route36623_Weather25.tar.gz\": {\n        \"sha256\": \"42f637646b500ea4d9055908a39b93fb882f49742c33d3e3eb8976bca826bae4\",\n        \"size\": 348527466\n    },\n    \"CrossingBicycleFlow_Town12_Route36626_Weather25.tar.gz\": {\n        \"sha256\": \"22564b16ddd39fbe8963d577f96aba926da72ed9478f8c2417e7d6698dcb652f\",\n        \"size\": 341889865\n    },\n    \"EnterActorFlow_Town12_Route11524_Weather9.tar.gz\": {\n        \"sha256\": \"c1498cb44480927c5a365efaf11044c4e1fae2f9dd5de59bb099313d0a938551\",\n        \"size\": 445867014\n    },\n    \"EnterActorFlow_Town12_Route11563_Weather22.tar.gz\": {\n        \"sha256\": \"5fa7136513ab3cdc15ecb11bb1846bd2da26183bb2be4ea30ebc0e6d31ea3f58\",\n        \"size\": 455045698\n    },\n    \"EnterActorFlow_Town12_Route12418_Weather19.tar.gz\": {\n        \"sha256\": \"ebb74415ec3854e3ad5020a3c1c47812c6a06fafef14930b55f45f15f0748058\",\n        \"size\": 152391228\n    },\n    \"EnterActorFlow_Town12_Route12419_Weather20.tar.gz\": {\n        \"sha256\": \"d2ff00c28abb5067ac3a2537b4e836aa71081e37c8af970b65481aeed3f28bf6\",\n        \"size\": 589057161\n    },\n    \"HazardAtSideLane_Town13_Route0_Weather0.tar.gz\": {\n        \"sha256\": \"e2aadc2918aa2fb9bdf2222f5329bed0c11981f9b7934a0c50248bb361e32b11\",\n        \"size\": 473121564\n    },\n    \"HazardAtSideLane_Town13_Route100_Weather9.tar.gz\": {\n        \"sha256\": \"9b2ccf21136a0d6667637215584001356036439732545ddd4d2719c12c557257\",\n        \"size\": 619747336\n    },\n    \"HazardAtSideLane_Town13_Route117_Weather2.tar.gz\": {\n        \"sha256\": \"ec569c7befce08f418b427d11c07dc1707f661ab649e752827db36495627f354\",\n        \"size\": 732169920\n    },\n    \"HazardAtSideLane_Town13_Route125_Weather11.tar.gz\": {\n        \"sha256\": \"0389daa0a919684f8cfbc7b5126720767ebead813fc54b0e85249b9af784e700\",\n        \"size\": 665375816\n    },\n    \"HazardAtSideLane_Town13_Route126_Weather12.tar.gz\": {\n        \"sha256\": \"ff960061eafdd2b4fb5ee7cd72bfd3cbcf8fa06b02990d1512105cc49ad268b3\",\n        \"size\": 157119249\n    },\n    \"HazardAtSideLane_Town13_Route130_Weather18.tar.gz\": {\n        \"sha256\": \"9107023ae6ba2f400670b6951e71aa88b88fed0da3adc8f823589be7dbba04fb\",\n        \"size\": 1071102579\n    },\n    \"HazardAtSideLane_Town13_Route138_Weather0.tar.gz\": {\n        \"sha256\": \"b1e85cd7b6a463d17cd04a76d9767ea57e491cac5f6970b66ec9cfa7783bbe72\",\n        \"size\": 394381312\n    },\n    \"HazardAtSideLane_Town13_Route154_Weather19.tar.gz\": {\n        \"sha256\": \"1555897ca3c8b77d9855b6100d6f8edda43cc517d23b3e8a490762ef85af0ed1\",\n        \"size\": 1094217539\n    },\n    \"HazardAtSideLane_Town13_Route16_Weather19.tar.gz\": {\n        \"sha256\": \"4a6c07a252b8fd02fb36a4136d98b3b91c269de5034b38c1b46ee31076ba7fb1\",\n        \"size\": 625137942\n    },\n    \"HazardAtSideLane_Town13_Route175_Weather15.tar.gz\": {\n        \"sha256\": \"e09dc4b18cb115808657faf5aa3e1a3a92e0cd4206e273d8ef98e5409d31b6cb\",\n        \"size\": 522912184\n    },\n    \"HazardAtSideLane_Town13_Route17_Weather20.tar.gz\": {\n        \"sha256\": \"8dabecec58ec3f5c210f8520611b283c45faf1512aed386978007503b250571b\",\n        \"size\": 600776675\n    },\n    \"HazardAtSideLane_Town13_Route182_Weather25.tar.gz\": {\n        \"sha256\": \"31d8f004feeae25ad74aeccbd3b63ec059d28bc556ae5ef1f7d295fd387a407d\",\n        \"size\": 631685273\n    },\n    \"HazardAtSideLane_Town13_Route186_Weather2.tar.gz\": {\n        \"sha256\": \"97fd54b1a9f60550ce09100db83f4f04b7026688d9de7757f43d70e4ddcc4f6e\",\n        \"size\": 929538873\n    },\n    \"HazardAtSideLane_Town13_Route190_Weather7.tar.gz\": {\n        \"sha256\": \"bc814937337f72d8c75d1d09e624148cd1c7deeca6d60840ae86ccb3d2bc13c3\",\n        \"size\": 786696974\n    },\n    \"HazardAtSideLane_Town13_Route191_Weather8.tar.gz\": {\n        \"sha256\": \"07c9aca2a3eeb92ac940c2c056470152959861dee8bfcef1dfd7232ad03ffd7c\",\n        \"size\": 807678755\n    },\n    \"HazardAtSideLane_Town13_Route210_Weather3.tar.gz\": {\n        \"sha256\": \"f28155177ed70f06eaf14014aea635e2fb9ee9dffa97eacb2ef7f179210d806e\",\n        \"size\": 337035575\n    },\n    \"HazardAtSideLane_Town13_Route213_Weather7.tar.gz\": {\n        \"sha256\": \"e10ccd73fbafed9b9b7622a265a1a40d5fee414e8f3844f51eec07b88b83244f\",\n        \"size\": 504224087\n    },\n    \"HazardAtSideLane_Town13_Route228_Weather25.tar.gz\": {\n        \"sha256\": \"35e718b1b6cfd93ff96b47de2aab45cf6a6acdee1196da3aabd3633e78464b0f\",\n        \"size\": 663945499\n    },\n    \"HazardAtSideLane_Town13_Route229_Weather26.tar.gz\": {\n        \"sha256\": \"756c55c3abe1f8e4fd6d083a01bdfb9dc1ae382f42a99e9f53cf5b045c1275f0\",\n        \"size\": 671650096\n    },\n    \"HazardAtSideLane_Town13_Route246_Weather19.tar.gz\": {\n        \"sha256\": \"c785f3b8ee6d720eb84c0897bc9d0cf47b49059bbaafb585f5e38f98eadb5950\",\n        \"size\": 504752557\n    },\n    \"HazardAtSideLane_Town13_Route249_Weather22.tar.gz\": {\n        \"sha256\": \"4f5fedec3ce87add2afd31292fd4266b4f632c2204c59d0e484835f1233d8f30\",\n        \"size\": 468780499\n    },\n    \"HazardAtSideLane_Town13_Route264_Weather12.tar.gz\": {\n        \"sha256\": \"a1a2e9445a20941878ffafb5e19f3be1ea1aa76ed0dd87a232ffea23243110c4\",\n        \"size\": 590330647\n    },\n    \"HazardAtSideLane_Town13_Route269_Weather19.tar.gz\": {\n        \"sha256\": \"02878d103e9c3e03cbeb95058c40e9fe6a6f856e771bbc2f497d5ff47eb08773\",\n        \"size\": 905770925\n    },\n    \"HazardAtSideLane_Town13_Route278_Weather2.tar.gz\": {\n        \"sha256\": \"6ac68fd5a59ca897d1021d7f72adf406c0e4daf5e2a99b67fab6105ea6d4efd9\",\n        \"size\": 757012759\n    },\n    \"HazardAtSideLane_Town13_Route28353_Weather3.tar.gz\": {\n        \"sha256\": \"369dd5c962773903dfec9150df9c04433c69bee929238d3e579a4b1fe3b767a4\",\n        \"size\": 552499849\n    },\n    \"HazardAtSideLane_Town13_Route28354_Weather5.tar.gz\": {\n        \"sha256\": \"3b089c83e9c0e5941f7a10a7d2dd39d2244bce0bf5368b48378e6bcb5cdeb74d\",\n        \"size\": 542491032\n    },\n    \"HazardAtSideLane_Town13_Route28364_Weather15.tar.gz\": {\n        \"sha256\": \"7e569f45bb01344b2cfd0f34826f8ab5f46feef3a72bf61f9a3b3a2f5843499c\",\n        \"size\": 239127896\n    },\n    \"HazardAtSideLane_Town13_Route28365_Weather18.tar.gz\": {\n        \"sha256\": \"9b27812ca4114e7ce2f5d313c0370d719013d05ecd4402314b502f3ba31283f2\",\n        \"size\": 420568640\n    },\n    \"HazardAtSideLane_Town13_Route28366_Weather19.tar.gz\": {\n        \"sha256\": \"99cad012eed195dea807c365f5847b1d5a6f2796b358f70ebe5e4b621e6b92bd\",\n        \"size\": 582168485\n    },\n    \"HazardAtSideLane_Town13_Route28367_Weather20.tar.gz\": {\n        \"sha256\": \"38410dd45f2255ab9b7842bbc66f91d967132e6f3e477474cebebc4f8d886ad3\",\n        \"size\": 615753809\n    },\n    \"HazardAtSideLane_Town13_Route28368_Weather21.tar.gz\": {\n        \"sha256\": \"a723c464d4578f4fa2087dd9e8d357af281b70d9d8ba900511718a01949fdcb3\",\n        \"size\": 528546424\n    },\n    \"HazardAtSideLane_Town13_Route28369_Weather22.tar.gz\": {\n        \"sha256\": \"e380c15776348bfcfdccddfbe9e66820b91bdd7932b5136bff20c7cdb22977d6\",\n        \"size\": 590047444\n    },\n    \"HazardAtSideLane_Town13_Route28371_Weather25.tar.gz\": {\n        \"sha256\": \"47d4dc9a9429b5f2b4f871eea7bd55fa30b3b8e7a31cea2f39af684755fdeed9\",\n        \"size\": 221948103\n    },\n    \"HazardAtSideLane_Town13_Route28372_Weather26.tar.gz\": {\n        \"sha256\": \"4a3945690a7a41393564e6d3c2ab18dbd140f7368d6f46ea9bc926f65600b835\",\n        \"size\": 497789053\n    },\n    \"HazardAtSideLane_Town13_Route28373_Weather0.tar.gz\": {\n        \"sha256\": \"ffa58027df0ea9dab7ad43bdcccf82f30a9dd44c0b9700a8350e9a38b2f135e2\",\n        \"size\": 664547868\n    },\n    \"HazardAtSideLane_Town13_Route28374_Weather1.tar.gz\": {\n        \"sha256\": \"b91cb537c73fd150478ae6d1e0140de5ccf3b922ad0b361851eadf0b9a73a37f\",\n        \"size\": 618755314\n    },\n    \"HazardAtSideLane_Town13_Route28384_Weather12.tar.gz\": {\n        \"sha256\": \"2b5705510653fd232ecf6f925e039ad50c46571b7061276b882851284672a581\",\n        \"size\": 1016938267\n    },\n    \"HazardAtSideLane_Town13_Route28385_Weather13.tar.gz\": {\n        \"sha256\": \"c1ff12e79f9f3e96d0e0c8f98d59993bba62c317b554a2849ea0d84616acf4ef\",\n        \"size\": 364495294\n    },\n    \"HazardAtSideLane_Town13_Route28388_Weather18.tar.gz\": {\n        \"sha256\": \"ef33b52dfead52579ff2bc7640376a14ab27094305a3fd6a686c3d7ed1d336ec\",\n        \"size\": 569566295\n    },\n    \"HazardAtSideLane_Town13_Route28389_Weather19.tar.gz\": {\n        \"sha256\": \"2e445434860096149517c3d357f096660abedf652b51bb19962cf5cfe337f5e5\",\n        \"size\": 423194338\n    },\n    \"HazardAtSideLane_Town13_Route28390_Weather20.tar.gz\": {\n        \"sha256\": \"fa3f971a8b3ea5f288cd31aa3289f2bc1549d939e6fb7c5f09c715a22c679792\",\n        \"size\": 402174502\n    },\n    \"HazardAtSideLane_Town13_Route28391_Weather21.tar.gz\": {\n        \"sha256\": \"40fd5c177b82120723cb71de22636697e400217f27e30f1ed68032aa6395d9dd\",\n        \"size\": 451708894\n    },\n    \"HazardAtSideLane_Town13_Route28392_Weather22.tar.gz\": {\n        \"sha256\": \"059168bdbd7c59247fd9911be6dee031b2a7c10329da2e781479618f1b23564f\",\n        \"size\": 223535427\n    },\n    \"HazardAtSideLane_Town13_Route28395_Weather26.tar.gz\": {\n        \"sha256\": \"02d3890249b1e83a014c06261da3f676fb255db02854aedb4096c23c7eb166f7\",\n        \"size\": 481111586\n    },\n    \"HazardAtSideLane_Town13_Route28396_Weather0.tar.gz\": {\n        \"sha256\": \"446de7502e93f0cf6d5b8dd4d92995cb758a23896907128e38c8475f1ff9a7ad\",\n        \"size\": 423328463\n    },\n    \"HazardAtSideLane_Town13_Route28397_Weather1.tar.gz\": {\n        \"sha256\": \"509d2a2861f3928df10b2aae502d37129d2744f4f972351967f176bcdac1b04f\",\n        \"size\": 270742296\n    },\n    \"HazardAtSideLane_Town13_Route28399_Weather3.tar.gz\": {\n        \"sha256\": \"6d4f9c768260b18da3d1f0984814518a6c7d72469c9c73d82f34317ae57064af\",\n        \"size\": 402149432\n    },\n    \"HazardAtSideLane_Town13_Route28400_Weather5.tar.gz\": {\n        \"sha256\": \"fc1b34f4de3919d19732dff642e3648413494caa96814fc12dc5ce8f38be7030\",\n        \"size\": 338197999\n    },\n    \"HazardAtSideLane_Town13_Route28407_Weather12.tar.gz\": {\n        \"sha256\": \"247f8701472d706f5c4340609f6235342633894359db95f9858e24b7e1d7c074\",\n        \"size\": 380236106\n    },\n    \"HazardAtSideLane_Town13_Route28409_Weather14.tar.gz\": {\n        \"sha256\": \"37ca9cfcfd730aef27f95353891718fd9ee774e9669c923a6ac6281dbe3ec5e5\",\n        \"size\": 339747412\n    },\n    \"HazardAtSideLane_Town13_Route28410_Weather15.tar.gz\": {\n        \"sha256\": \"4cd790d0e5399f8f092529e7269db19cfb3558b328bb9854c600fb7b672eefec\",\n        \"size\": 372271090\n    },\n    \"HazardAtSideLane_Town13_Route28412_Weather19.tar.gz\": {\n        \"sha256\": \"86c0055144c8c2d021af2cfe2082399f9e4310240125d1a5029a204c5b60ac7b\",\n        \"size\": 677960983\n    },\n    \"HazardAtSideLane_Town13_Route28413_Weather20.tar.gz\": {\n        \"sha256\": \"fa8bd76e9dc21765d425283c4fae2710264e1f728fdf3a4d2e9807212d2f8ab8\",\n        \"size\": 394318455\n    },\n    \"HazardAtSideLane_Town13_Route28416_Weather23.tar.gz\": {\n        \"sha256\": \"6612988f31553123055781af01b0a8bf99ca808fe8c4ab232b3172739fafbe12\",\n        \"size\": 591376121\n    },\n    \"HazardAtSideLane_Town13_Route28418_Weather26.tar.gz\": {\n        \"sha256\": \"fa0693fb9907e25441ed1c12525cf78ab6c2f83b0ad4b62713e877b272ee37d4\",\n        \"size\": 369750923\n    },\n    \"HazardAtSideLane_Town13_Route28420_Weather1.tar.gz\": {\n        \"sha256\": \"be8125a167e1a40fc912f78c9db764a0bc6d211bd7032c513cc1d0cdc00b4d10\",\n        \"size\": 499459277\n    },\n    \"HazardAtSideLane_Town13_Route28426_Weather8.tar.gz\": {\n        \"sha256\": \"55975017da02a8eeff62296a1bea94e6d365b008ecafaeb16de96e9367febc12\",\n        \"size\": 517593601\n    },\n    \"HazardAtSideLane_Town13_Route28427_Weather9.tar.gz\": {\n        \"sha256\": \"84eea9753b7318f8860f19f8129458407802f086dd85180d45e379eb7d68736d\",\n        \"size\": 593484302\n    },\n    \"HazardAtSideLane_Town13_Route28428_Weather10.tar.gz\": {\n        \"sha256\": \"14b6b7878fd5b29fa6c5418ae3ec4fab0bfe7c2ffdb6ba1bccaaf3312f82eafb\",\n        \"size\": 1794518856\n    },\n    \"HazardAtSideLane_Town13_Route28430_Weather12.tar.gz\": {\n        \"sha256\": \"b04512b77fa07b4b0c5168ccc0300ec3616fb7d84d2301c130776b5f6b90d131\",\n        \"size\": 338573240\n    },\n    \"HazardAtSideLane_Town13_Route28431_Weather13.tar.gz\": {\n        \"sha256\": \"58843827d70cfad132bf5553e0c21e40c2db3b0f35a65453aacf25b9bbec0032\",\n        \"size\": 370785567\n    },\n    \"HazardAtSideLane_Town13_Route28436_Weather20.tar.gz\": {\n        \"sha256\": \"cd692002e5f7617000586a292a8ec6f1f00c62ff54c71d2e3c6f409d20454647\",\n        \"size\": 1042160317\n    },\n    \"HazardAtSideLane_Town13_Route28439_Weather23.tar.gz\": {\n        \"sha256\": \"92491192da8861343a2facd03cc2f1d8464a91f6730658fa19ce1d911c63920c\",\n        \"size\": 318413225\n    },\n    \"HazardAtSideLane_Town13_Route28442_Weather0.tar.gz\": {\n        \"sha256\": \"84aba5b6f4dce5bc02dfe641569217be970b159599fe0f22e503696048bbe900\",\n        \"size\": 547395688\n    },\n    \"HazardAtSideLane_Town13_Route28451_Weather10.tar.gz\": {\n        \"sha256\": \"79b1b368689a40d90692eb93bac23e17e90f0767539a041e401a1019e0d62750\",\n        \"size\": 489529052\n    },\n    \"HazardAtSideLane_Town13_Route28452_Weather11.tar.gz\": {\n        \"sha256\": \"3aa031265146705383aa78a1eb6946766eef1b307bd0ce76b777dbdb21c21a95\",\n        \"size\": 630336934\n    },\n    \"HazardAtSideLane_Town13_Route28453_Weather12.tar.gz\": {\n        \"sha256\": \"2b00066134e60d807e0382c9f5326c268fedbf01548965a091a6d1a7118d27fe\",\n        \"size\": 348435578\n    },\n    \"HazardAtSideLane_Town13_Route28455_Weather14.tar.gz\": {\n        \"sha256\": \"172fac047cbf9a90d23e7d9e5e418ea88b7663eb9178a2c4c4add4e05b02a43d\",\n        \"size\": 318323959\n    },\n    \"HazardAtSideLane_Town13_Route28457_Weather18.tar.gz\": {\n        \"sha256\": \"60b00b953820de7879d9790da22b09b3fe1340a9811bc92fb1feae509164fa09\",\n        \"size\": 293097590\n    },\n    \"HazardAtSideLane_Town13_Route28460_Weather21.tar.gz\": {\n        \"sha256\": \"910775546a78767a9a324ad82fbc1f9d791f055b7b2ffa90076072bb97583b1a\",\n        \"size\": 680985838\n    },\n    \"HazardAtSideLane_Town13_Route28461_Weather22.tar.gz\": {\n        \"sha256\": \"a6032711a650b1fe8b314b239d792d1459070a48557a84dd686b5ef5dea93924\",\n        \"size\": 464767376\n    },\n    \"HazardAtSideLane_Town13_Route28462_Weather23.tar.gz\": {\n        \"sha256\": \"867b83a362cf24c25fbfec533c931d0dea3d56c32bbd792a4afae9381c5d3585\",\n        \"size\": 580038413\n    },\n    \"HazardAtSideLane_Town13_Route28463_Weather25.tar.gz\": {\n        \"sha256\": \"6cafa941803445b4cff08bdcfacae024c488e7d2cd0ba5535cf60978d1f5b4b3\",\n        \"size\": 276340033\n    },\n    \"HazardAtSideLane_Town13_Route28464_Weather26.tar.gz\": {\n        \"sha256\": \"fede4f56dea88081843d47ce486ed1ced5f34a2b06677f39348d598425afa99a\",\n        \"size\": 442652204\n    },\n    \"HazardAtSideLane_Town13_Route28466_Weather1.tar.gz\": {\n        \"sha256\": \"8a6aaebaeabe6f337b0511787a29018769f83f6411fb340249f454b30ca11cb9\",\n        \"size\": 423232428\n    },\n    \"HazardAtSideLane_Town13_Route28469_Weather5.tar.gz\": {\n        \"sha256\": \"56c12713bc3c281763ecd38268aee4e7c24eff46be965cea150e455b4ac6caed\",\n        \"size\": 761303956\n    },\n    \"HazardAtSideLane_Town13_Route28470_Weather6.tar.gz\": {\n        \"sha256\": \"3ce810db562ae773ea6f92e30b79aec28d7c207cfce7fc7b44c159294dd3ab0d\",\n        \"size\": 739957789\n    },\n    \"HazardAtSideLane_Town13_Route28471_Weather7.tar.gz\": {\n        \"sha256\": \"db81203093c9d2164755469388d27896acc5ef2215c570786da8556852ff13e7\",\n        \"size\": 532768843\n    },\n    \"HazardAtSideLane_Town13_Route28476_Weather12.tar.gz\": {\n        \"sha256\": \"5f0f101731840cff5e0013c8afd97d9ea307814cd22c968d95e050fc00ad7933\",\n        \"size\": 564307070\n    },\n    \"HazardAtSideLane_Town13_Route28477_Weather13.tar.gz\": {\n        \"sha256\": \"b579edb755a207fce34ea608d3745c2f521f2414838502664a19abd5bc1f318c\",\n        \"size\": 498982930\n    },\n    \"HazardAtSideLane_Town13_Route28478_Weather14.tar.gz\": {\n        \"sha256\": \"a3908eaec32619beb8af1ff68c4e262fe5e861859b4f1dd3c98d6690aa6d8e52\",\n        \"size\": 588926143\n    },\n    \"HazardAtSideLane_Town13_Route28479_Weather15.tar.gz\": {\n        \"sha256\": \"7ae58d557fadaa665e771fb61fbc72e77ce043084b8603c821ba7714fdead1ed\",\n        \"size\": 576184265\n    },\n    \"HazardAtSideLane_Town13_Route28487_Weather26.tar.gz\": {\n        \"sha256\": \"1dfadc532255ab83bfd47be1492b3446b8bdb4b7918ccd1d62ae981cc8804415\",\n        \"size\": 353471280\n    },\n    \"HazardAtSideLane_Town13_Route28493_Weather6.tar.gz\": {\n        \"sha256\": \"faa74380476aab80c3e6c7b40112efe5aaca92d44f3a56f86343453e6877cd43\",\n        \"size\": 572377714\n    },\n    \"HazardAtSideLane_Town13_Route28496_Weather9.tar.gz\": {\n        \"sha256\": \"c6e886433ccdc9f0efefec71827c7e38bb39a885dedbbf0ca85f6cbc2825d90f\",\n        \"size\": 696521735\n    },\n    \"HazardAtSideLane_Town13_Route28498_Weather11.tar.gz\": {\n        \"sha256\": \"180585cd7fa5472cdd26eb2b69974e52f757f2ac4e93c12e2d013430e081dec2\",\n        \"size\": 308296092\n    },\n    \"HazardAtSideLane_Town13_Route28501_Weather14.tar.gz\": {\n        \"sha256\": \"402a310372a10e3eaf79d8e9587f0eadf24bde7fb6ccca31b44ac3fd156bd2c1\",\n        \"size\": 539441484\n    },\n    \"HazardAtSideLane_Town13_Route28505_Weather20.tar.gz\": {\n        \"sha256\": \"ea0abce018f25e4ddedafad8bf8fddada483f96b46f068bf5a81bc065617c3d9\",\n        \"size\": 368040802\n    },\n    \"HazardAtSideLane_Town13_Route28506_Weather21.tar.gz\": {\n        \"sha256\": \"c635770cd933e120cadc14e4e97dc5ab9e6939b5e1c52e38ce93169fa0e993bc\",\n        \"size\": 422386590\n    },\n    \"HazardAtSideLane_Town13_Route28512_Weather1.tar.gz\": {\n        \"sha256\": \"d01f98d45c3a90262ab4e6456bfb1473c060102e9934f8bbc5d047c8d3d619ea\",\n        \"size\": 540956770\n    },\n    \"HazardAtSideLane_Town13_Route28516_Weather6.tar.gz\": {\n        \"sha256\": \"f0bb334195cea9de04a078adb7a91e446adfb4eb2347d42298778b9264346058\",\n        \"size\": 598244911\n    },\n    \"HazardAtSideLane_Town13_Route28519_Weather9.tar.gz\": {\n        \"sha256\": \"f5ef7e6d11ea5afeeea408c5a7451de42425f20e014b772fe0ae9cf5b9c21ca9\",\n        \"size\": 550586696\n    },\n    \"HazardAtSideLane_Town13_Route28520_Weather10.tar.gz\": {\n        \"sha256\": \"6d104ea7abb25253faf0b20ee0b46ca59e3e11168d90a605d0b87c5fd611c9fd\",\n        \"size\": 514823897\n    },\n    \"HazardAtSideLane_Town13_Route28521_Weather11.tar.gz\": {\n        \"sha256\": \"3e3f0a7836ef8d93faf57799f86d9207305c462277e955cfd36cc3d83e50a493\",\n        \"size\": 644126736\n    },\n    \"HazardAtSideLane_Town13_Route28522_Weather12.tar.gz\": {\n        \"sha256\": \"e7c7ce98d78d659312db41a2346410d26c031acf126a1c9e25be89d59b54a390\",\n        \"size\": 708664740\n    },\n    \"HazardAtSideLane_Town13_Route28523_Weather13.tar.gz\": {\n        \"sha256\": \"bbd48d30e5a8ff4205fe1dfcc2238a66ba6a994aeeb35659858dc46ec04aae5b\",\n        \"size\": 497584513\n    },\n    \"HazardAtSideLane_Town13_Route28524_Weather14.tar.gz\": {\n        \"sha256\": \"63b72fb6f572a65fd008b544453179c4fc9dd7ffcfba7a9bb0c3884d4d2244d8\",\n        \"size\": 528108338\n    },\n    \"HazardAtSideLane_Town13_Route28525_Weather15.tar.gz\": {\n        \"sha256\": \"e2f3e6ef17c1b146be61f15510c464866c975b7ab2c0de784ddc2755961af150\",\n        \"size\": 569225847\n    },\n    \"HazardAtSideLane_Town13_Route28526_Weather18.tar.gz\": {\n        \"sha256\": \"1042d7f068e19a8ebff5e0c0710d69482f3dd3844f390445d764955115ca7613\",\n        \"size\": 672460009\n    },\n    \"HazardAtSideLane_Town13_Route28527_Weather19.tar.gz\": {\n        \"sha256\": \"03b3c94de8b5a9edd8645eb415c33c21dd367a0e2ca0dfccc467a1751d9d4bd7\",\n        \"size\": 774755715\n    },\n    \"HazardAtSideLane_Town13_Route28529_Weather21.tar.gz\": {\n        \"sha256\": \"bd9b9fde55054e0c8ef3090e62bc6c7b8dc413b2c183fdc3756c8eaee97dd850\",\n        \"size\": 417618912\n    },\n    \"HazardAtSideLane_Town13_Route28530_Weather22.tar.gz\": {\n        \"sha256\": \"99d231ec507234bea2009287d6cb8ae81e162c81d8ee6be7898155e5ce73cb19\",\n        \"size\": 348603645\n    },\n    \"HazardAtSideLane_Town13_Route28531_Weather23.tar.gz\": {\n        \"sha256\": \"e5f46051961d961c2414c52a0e865f64575c3a2f0af76bac9611e5ee2fd37eef\",\n        \"size\": 569407259\n    },\n    \"HazardAtSideLane_Town13_Route28533_Weather26.tar.gz\": {\n        \"sha256\": \"5e52e52885b9bc140ef0d5a63a31828bf6029853ea726be69dd27402ad53f127\",\n        \"size\": 362416674\n    },\n    \"HazardAtSideLane_Town13_Route28535_Weather1.tar.gz\": {\n        \"sha256\": \"fd0bde54ac5e709e7ca3607bbadfbf167a2d844c114e249bb5deaf9334b2435c\",\n        \"size\": 745315085\n    },\n    \"HazardAtSideLane_Town13_Route28538_Weather5.tar.gz\": {\n        \"sha256\": \"6854d7af3949a7fde8335f9a1d6033f2cc15fb12ff256797fcf8308b1e4f5d2a\",\n        \"size\": 625090663\n    },\n    \"HazardAtSideLane_Town13_Route28540_Weather7.tar.gz\": {\n        \"sha256\": \"211fa5e773c9bddfa7ad5e49219449c70c2409f57a2a8053f768df496d56034c\",\n        \"size\": 682343537\n    },\n    \"HazardAtSideLane_Town13_Route28541_Weather8.tar.gz\": {\n        \"sha256\": \"ef28d3223cf96ca269d71d6f7f076e1844f0fc7bb0a6a093f7816e0bbc10c5e0\",\n        \"size\": 722607323\n    },\n    \"HazardAtSideLane_Town13_Route28542_Weather9.tar.gz\": {\n        \"sha256\": \"28a00b10c1ca8026d07d0d34141d1207f1014440523360e979153279361812b4\",\n        \"size\": 555230626\n    },\n    \"HazardAtSideLane_Town13_Route28544_Weather11.tar.gz\": {\n        \"sha256\": \"2fc96e8e190060f95444e889ae47314ce6e64e9d39fe05124cf52ed2b3fb6973\",\n        \"size\": 554575591\n    },\n    \"HazardAtSideLane_Town13_Route28547_Weather14.tar.gz\": {\n        \"sha256\": \"4a4019bea30b69171eb0ccc53a623129f5e5f030de10e6130140f25aa000c92c\",\n        \"size\": 625745651\n    },\n    \"HazardAtSideLane_Town13_Route28551_Weather20.tar.gz\": {\n        \"sha256\": \"362280a0c37c803a5c2fd40fd1763d4991f8caf144e57b5f909de623e5408182\",\n        \"size\": 304169100\n    },\n    \"HazardAtSideLane_Town13_Route28555_Weather25.tar.gz\": {\n        \"sha256\": \"9cab4eb7ac4d8db5aefabacc9e23b978c9ba4f05668dc82397916a8343bce697\",\n        \"size\": 584139255\n    },\n    \"HazardAtSideLane_Town13_Route28556_Weather26.tar.gz\": {\n        \"sha256\": \"e81da9aeb1acd301b60e077d698d253be1fff46c407f525bb03fe705aa3f3240\",\n        \"size\": 492076051\n    },\n    \"HazardAtSideLane_Town13_Route28557_Weather0.tar.gz\": {\n        \"sha256\": \"2d5716d126ff41f32cf02d5bf78b9d40bb9dd6af952e088af0d372b97f9aa754\",\n        \"size\": 408351398\n    },\n    \"HazardAtSideLane_Town13_Route28560_Weather3.tar.gz\": {\n        \"sha256\": \"1cf62f00bc7e0b84fc0f5051f5c5d1e28baac26e1339401a7b28975fad6075c8\",\n        \"size\": 405141497\n    },\n    \"HazardAtSideLane_Town13_Route28564_Weather8.tar.gz\": {\n        \"sha256\": \"a5cd77196fd774449dcf32e5019e3269948d404321b5acbd2d7e79b407cb5176\",\n        \"size\": 319682996\n    },\n    \"HazardAtSideLane_Town13_Route28566_Weather10.tar.gz\": {\n        \"sha256\": \"9630719b337b38b6a43354e69326fedeb155510de70b878268c62e668e478e17\",\n        \"size\": 452022633\n    },\n    \"HazardAtSideLane_Town13_Route28567_Weather11.tar.gz\": {\n        \"sha256\": \"1b6e36921283ee41072e788b283c380219ce09d37af7a2d0cfa7f59329c36853\",\n        \"size\": 280535948\n    },\n    \"HazardAtSideLane_Town13_Route28568_Weather12.tar.gz\": {\n        \"sha256\": \"67b5b650c709ad70bd0273db9f354a53c412a0f3c884f0c798ed91463a37c769\",\n        \"size\": 510262077\n    },\n    \"HazardAtSideLane_Town13_Route28569_Weather13.tar.gz\": {\n        \"sha256\": \"98ec43d953b9a2d2c39152fc78ad8622da38eef29844413debdf8b44b16ac036\",\n        \"size\": 482450243\n    },\n    \"HazardAtSideLane_Town13_Route28570_Weather14.tar.gz\": {\n        \"sha256\": \"b20b29511ab00e3bf90f52c0e2c8be35fd4f305cf6f175452afa42be8d108aed\",\n        \"size\": 760436619\n    },\n    \"HazardAtSideLane_Town13_Route28575_Weather21.tar.gz\": {\n        \"sha256\": \"69d89e76dc3540e8288081df3b428d8a4f5dde9bcfb1b44042638558ad126ec3\",\n        \"size\": 584733412\n    },\n    \"HazardAtSideLane_Town13_Route28579_Weather26.tar.gz\": {\n        \"sha256\": \"0db9c773e5a576832cc8e7b2608f2c866ffc57dbb66434c13238837e0ddf8661\",\n        \"size\": 742120740\n    },\n    \"HazardAtSideLane_Town13_Route289_Weather14.tar.gz\": {\n        \"sha256\": \"996473c1807ef5ac94fa1de3a5c833925c68cfb9cc4e767474c7cc9a48eb3031\",\n        \"size\": 2239560708\n    },\n    \"HazardAtSideLane_Town13_Route296_Weather23.tar.gz\": {\n        \"sha256\": \"b51190bd0a50d07c6d5323ce7003e4ad397ab619e18d79c88d64b6b0a7669d3c\",\n        \"size\": 701590317\n    },\n    \"HazardAtSideLane_Town13_Route297_Weather25.tar.gz\": {\n        \"sha256\": \"e43dbff3a2d10373a6ca419c27cd6b3b6b4a86b6aa0cbaa9f5a3daa0393c6657\",\n        \"size\": 683079278\n    },\n    \"HazardAtSideLane_Town13_Route310_Weather12.tar.gz\": {\n        \"sha256\": \"8588520a40c7218a8408321d95260fdb76b2fc40129ff8267dc4ad480ce9fc18\",\n        \"size\": 649420813\n    },\n    \"HazardAtSideLane_Town13_Route319_Weather23.tar.gz\": {\n        \"sha256\": \"77833999d87720b8971ab79eadf01efc94add912b6ddd0933b46084b4eb8947b\",\n        \"size\": 448083699\n    },\n    \"HazardAtSideLane_Town13_Route323_Weather1.tar.gz\": {\n        \"sha256\": \"2f3fd7fb9fb358731219c2492831f817a7a662b558066ac91967b63ef74d3c95\",\n        \"size\": 209889036\n    },\n    \"HazardAtSideLane_Town13_Route335_Weather14.tar.gz\": {\n        \"sha256\": \"77967c4bbbac046932958c80b8a6766fbc394b4a821bee0d558cc8b6df11fea8\",\n        \"size\": 254633711\n    },\n    \"HazardAtSideLane_Town13_Route340_Weather21.tar.gz\": {\n        \"sha256\": \"de6fcb1bba732b0a3c240a1272923048b21bd45a75483eb33c5c0c0f57a2929c\",\n        \"size\": 370278177\n    },\n    \"HazardAtSideLane_Town13_Route341_Weather22.tar.gz\": {\n        \"sha256\": \"09d5ead057f1aa6d41eee0d678c2f1d2c261ca4ca7eac7ebe8ab15a13fa6ed24\",\n        \"size\": 424173644\n    },\n    \"HazardAtSideLane_Town13_Route343_Weather25.tar.gz\": {\n        \"sha256\": \"654938952b7e4c063439324e7fa538208e19d3319ecb2a66bd92d4c8fa637ed9\",\n        \"size\": 151279094\n    },\n    \"HazardAtSideLane_Town13_Route346_Weather1.tar.gz\": {\n        \"sha256\": \"7532d978af7fa1941126235443f3ac4cea679d7037397fbec6b4dd65e02d81d7\",\n        \"size\": 1799013425\n    },\n    \"HazardAtSideLane_Town13_Route394_Weather3.tar.gz\": {\n        \"sha256\": \"c363c2d4c775a306a577ad687f8e5eebd5017b9930cbaf84f685060e3e9b6025\",\n        \"size\": 462169216\n    },\n    \"HazardAtSideLane_Town13_Route399_Weather9.tar.gz\": {\n        \"sha256\": \"849b0b454c1e2aa906843857a1f29c8598dcc80ebb7a4c9ab3969ba5f2b9242e\",\n        \"size\": 427204024\n    },\n    \"HazardAtSideLane_Town13_Route416_Weather2.tar.gz\": {\n        \"sha256\": \"ba73208d234d335129f0334bee3d1d10609b1807b8d63526f31dc225072db1b7\",\n        \"size\": 555773631\n    },\n    \"HazardAtSideLane_Town13_Route422_Weather9.tar.gz\": {\n        \"sha256\": \"939c88f1647e8f9f0be3d2a369cf91af82e05c111b4451baab9bc54c2b7788a6\",\n        \"size\": 738061094\n    },\n    \"HazardAtSideLane_Town13_Route438_Weather1.tar.gz\": {\n        \"sha256\": \"93ae7be92b44cf185375337b53bfd73445c9aeadb90ba0fb8f1958690c1e3649\",\n        \"size\": 675744292\n    },\n    \"HazardAtSideLane_Town13_Route445_Weather9.tar.gz\": {\n        \"sha256\": \"9991ff30c4e58043f2767d0af2bb7c8edc8abf96768fd183a8c3aaf0556626c8\",\n        \"size\": 724253781\n    },\n    \"HazardAtSideLane_Town13_Route93_Weather1.tar.gz\": {\n        \"sha256\": \"ceae8664060311e1cb6abbdb12dffa6c4d247a991edc7a5b60b47fd3b45ef08e\",\n        \"size\": 576784068\n    },\n    \"HazardAtSideLane_Town13_Route94_Weather2.tar.gz\": {\n        \"sha256\": \"f33be9ef9151ac58ce3199437977ac20cea77206c23b7f709e84fdfd4149a67e\",\n        \"size\": 538297120\n    },\n    \"HazardAtSideLane_Town13_Route96_Weather5.tar.gz\": {\n        \"sha256\": \"07e53d7f939e1020a650a9315170fcdd4a0f2aded42e3f1eebd4861b6f9bb400\",\n        \"size\": 330919649\n    },\n    \"HighwayCutIn_Town12_Route13445_Weather6.tar.gz\": {\n        \"sha256\": \"f93d2e83602adc7b95ddfae3c7058975b8e89a4a55060b8b592be82cca457aaa\",\n        \"size\": 301229357\n    },\n    \"HighwayCutIn_Town12_Route13446_Weather7.tar.gz\": {\n        \"sha256\": \"f71e0c25fcf4755b1405fb755c60688e09da63346975be6906a677d8abd32ebb\",\n        \"size\": 243380103\n    },\n    \"HighwayCutIn_Town12_Route13447_Weather8.tar.gz\": {\n        \"sha256\": \"87069a993f88592af5b0559625d342b277d2985c0b48bea4648414dfebb3369e\",\n        \"size\": 164802902\n    },\n    \"HighwayCutIn_Town12_Route13448_Weather9.tar.gz\": {\n        \"sha256\": \"849a56c6b97cd861c93eba9f1bce3864ce4e2642cb9139a4be4980f0ffa115b6\",\n        \"size\": 212864662\n    },\n    \"HighwayCutIn_Town12_Route13449_Weather10.tar.gz\": {\n        \"sha256\": \"f69931eb392a0083c145e4751fb74f6ac470650a6a3301446d15b67da09dcfcc\",\n        \"size\": 232244347\n    },\n    \"HighwayCutIn_Town12_Route13450_Weather11.tar.gz\": {\n        \"sha256\": \"4b9bb2ce0b187ae61c43f7b5ac11104d6339e33a7c41698793ccd8c7a777f424\",\n        \"size\": 193682648\n    },\n    \"HighwayCutIn_Town12_Route13452_Weather13.tar.gz\": {\n        \"sha256\": \"e197e60c62b9c3cec894610a0672132c2a91699e374289bec1c508d3ec2c701a\",\n        \"size\": 175828251\n    },\n    \"HighwayCutIn_Town12_Route13453_Weather14.tar.gz\": {\n        \"sha256\": \"6f52160f94f17c273c610bb1aa5581adeb3539117ad3bcdd14e82c9b97b7bea2\",\n        \"size\": 245278916\n    },\n    \"HighwayCutIn_Town12_Route13454_Weather15.tar.gz\": {\n        \"sha256\": \"b84dda4ca870e39aad71f75a780c2fec028386598b147ac807be953ced0841ed\",\n        \"size\": 308080696\n    },\n    \"HighwayCutIn_Town12_Route13455_Weather8.tar.gz\": {\n        \"sha256\": \"97134ee725a6ec4d041d373cf11f3ca2cac4f859f487f72526c4aaa48a671c97\",\n        \"size\": 160719534\n    },\n    \"HighwayCutIn_Town12_Route13456_Weather9.tar.gz\": {\n        \"sha256\": \"84418140dcf3c2dfab205616c8ce01fba72bd6a9c199659ca232ab14045fae15\",\n        \"size\": 227409422\n    },\n    \"HighwayCutIn_Town12_Route13457_Weather18.tar.gz\": {\n        \"sha256\": \"044f1c6e3464a7d38f500978a50bdb66f662a9e80db3ad0dc878f3ff63f54e0b\",\n        \"size\": 329084533\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38821_Weather5.tar.gz\": {\n        \"sha256\": \"156f22545fc9cffff14136b6a2ebadabcbf73757344c3b7f4a933c95a6095fa0\",\n        \"size\": 220042964\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38842_Weather6.tar.gz\": {\n        \"sha256\": \"1640118d1d2b02617b8ff44ded98bab16949fc722aabc097805863d517b5bf8b\",\n        \"size\": 229230454\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38846_Weather6.tar.gz\": {\n        \"sha256\": \"8055499b8bbc219f31c6701369e9fe2f8efbd563fa2e1be70c451b103518b74c\",\n        \"size\": 224621366\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38848_Weather6.tar.gz\": {\n        \"sha256\": \"862b4813d1a7a34ecd79c080a43f75543f0dfd0da6161986e6848933a49e6a8c\",\n        \"size\": 231551707\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38854_Weather6.tar.gz\": {\n        \"sha256\": \"6aedebe1659e31e84956bbf982ae9177d04bb1220bb062cd46984de92c056665\",\n        \"size\": 211244401\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38856_Weather6.tar.gz\": {\n        \"sha256\": \"8a32e88385dd8df9a8cd901f40468fd7e95e6cd39afb0311778bc633b56f3a74\",\n        \"size\": 218241679\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38858_Weather6.tar.gz\": {\n        \"sha256\": \"eede41f19fdc60c9ff9fe7207053886bb90c35ac2854e1df839ef796bf14d1e6\",\n        \"size\": 217187328\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38859_Weather6.tar.gz\": {\n        \"sha256\": \"6733b38939f53ffce4c2a47bb4cc7bd59579f03712933274f5d8784dac425ee7\",\n        \"size\": 212642974\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38863_Weather6.tar.gz\": {\n        \"sha256\": \"9b400f2aea95a650a72ee8ff392209d7afdd37e298d0f23a99d7cb7c0fdc6e4c\",\n        \"size\": 228832493\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route38868_Weather6.tar.gz\": {\n        \"sha256\": \"48873ac893a3836ed7f14af08418c7a2e84e1986f8b3d5045dc810abb6bd2a16\",\n        \"size\": 288286140\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39188_Weather14.tar.gz\": {\n        \"sha256\": \"1730ff7ef9781f0c2c91d3642435a86fe0f6982c87f9e8eb1746e362a1e2fd71\",\n        \"size\": 262248250\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39205_Weather15.tar.gz\": {\n        \"sha256\": \"9c35f6751e58a4d7ed470ad233c2d736e9c4780c755e99c3abca6188fba8d769\",\n        \"size\": 218583453\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39211_Weather15.tar.gz\": {\n        \"sha256\": \"a2c0a217ecbcc8eba2b5fb6ca8d2d542ed9a0d0cd66321ae8416d9a3b9b223bf\",\n        \"size\": 216147399\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39218_Weather15.tar.gz\": {\n        \"sha256\": \"04cb6b8cf6dd49a10383f769169009b7f0c5d393c473a9ab02c888dbbd85d729\",\n        \"size\": 205379141\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39224_Weather15.tar.gz\": {\n        \"sha256\": \"a6c95015486f33562dab36dd25581ef58208c643edcfb202d750d064dcd8aea4\",\n        \"size\": 209973538\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39244_Weather18.tar.gz\": {\n        \"sha256\": \"1705f35289cbecdaa59d1639f35aefb4e88581fd8c4a4c4a0f16c14ec7ce2d36\",\n        \"size\": 225948305\n    },\n    \"InterurbanAdvancedActorFlow_Town12_Route39245_Weather18.tar.gz\": {\n        \"sha256\": \"bd6f359bd29087482be345a01ed62140f3da1f6e48c015ab3e3a50d89443bc93\",\n        \"size\": 232743268\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38833_Weather6.tar.gz\": {\n        \"sha256\": \"d149f5486d8b9e33f0fe488ea6beac849cd6816b18e6accb9b102264a87a173a\",\n        \"size\": 528204534\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38836_Weather6.tar.gz\": {\n        \"sha256\": \"1d617da0dc8079e4ad68e1df2860d2bb3c8a7775c41bab9cb71b1de0ae39bf3f\",\n        \"size\": 461139043\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38837_Weather6.tar.gz\": {\n        \"sha256\": \"faa5b1e1be0b73fe4cce0dbb05d60aa72a10154547416807b94f1772ba1aae8e\",\n        \"size\": 475421118\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38838_Weather6.tar.gz\": {\n        \"sha256\": \"57bd8361f3a92c30e4e2cba04b4229d7c25e2083fbf89fba2209130f705a4c9f\",\n        \"size\": 530404621\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38873_Weather7.tar.gz\": {\n        \"sha256\": \"6a6da678cef91995c0c1241a6fa7179cd67a64fcc943a0d586a0074526e889a5\",\n        \"size\": 566927851\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route38877_Weather7.tar.gz\": {\n        \"sha256\": \"f86580699cda3d4ee365ba03e95ce1634bc22e49fdf0fa2efddef62060a9b32e\",\n        \"size\": 521787968\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39192_Weather15.tar.gz\": {\n        \"sha256\": \"996ea1a20f5ff6e358d0e5437d2fb838a269056bc1999eb56f793f14f9a606bf\",\n        \"size\": 452353682\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39197_Weather15.tar.gz\": {\n        \"sha256\": \"599f90e626ec490652fc43a6f55cfd5a4916b5c818e7a7aac0b372dbdc259032\",\n        \"size\": 461492075\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39236_Weather18.tar.gz\": {\n        \"sha256\": \"f9d36a4e15486d2f369f6e04635458dea6a6584e183a45de43374321cbc66583\",\n        \"size\": 483071302\n    },\n    \"InterurbanAdvancedActorFlow_Town13_Route39238_Weather18.tar.gz\": {\n        \"sha256\": \"cc22764bdb4e48776c86b577c508d7a56f53344f88b0d5b3598880af2a29a1be\",\n        \"size\": 549758158\n    },\n    \"LaneChange_Town04_Route24315_Weather3.tar.gz\": {\n        \"sha256\": \"dad1ff6941430e09a45e01b31822b658bc3e42d53dbce4648ad85f38f9cdbc55\",\n        \"size\": 230213557\n    },\n    \"LaneChange_Town04_Route24325_Weather14.tar.gz\": {\n        \"sha256\": \"f3fbe9ca5da9e6af9b219e700c7c3e9e359959d54aef70e1c3dfeb71d25654b6\",\n        \"size\": 201460917\n    },\n    \"LaneChange_Town05_Route24259_Weather19.tar.gz\": {\n        \"sha256\": \"02927fdcca1137c74824a9ca46eacd5f4dfb9d32b4cc31e27f712f708d8529cc\",\n        \"size\": 232928802\n    },\n    \"LaneChange_Town05_Route24359_Weather1.tar.gz\": {\n        \"sha256\": \"15b9d43e3a46f5c8c9fe4fd3ca2d6fc8b6bf7449564eba65920675986a97d553\",\n        \"size\": 239377500\n    },\n    \"LaneChange_Town06_Route24237_Weather20.tar.gz\": {\n        \"sha256\": \"a4ed701d716b2f8e0e91cc3755cbd55c024fe4362d919afe18b18f1fc9507d55\",\n        \"size\": 166206224\n    },\n    \"LaneChange_Town06_Route24247_Weather5.tar.gz\": {\n        \"sha256\": \"bfec27965e2c1cf4ff7f679bbbe4c05cc074d7d733a390c13fb77708739b129a\",\n        \"size\": 175667535\n    },\n    \"LaneChange_Town06_Route24277_Weather12.tar.gz\": {\n        \"sha256\": \"30e5687dfabb98b10421612d9b8c1ec4ad4d02a713c4fa68e83f28c18a8ccdbe\",\n        \"size\": 148519653\n    },\n    \"LaneChange_Town12_Route1644_Weather0.tar.gz\": {\n        \"sha256\": \"27f284e39e0b2cd6faf652d5706f85d279ff6e596ef478bfd5ed7116d9119d3c\",\n        \"size\": 367121744\n    },\n    \"LaneChange_Town12_Route1654_Weather10.tar.gz\": {\n        \"sha256\": \"b664472d01c131524bd9ba422bf1df34a538c29be279830ad8cb5d6729bc6250\",\n        \"size\": 204584925\n    },\n    \"LaneChange_Town12_Route1656_Weather12.tar.gz\": {\n        \"sha256\": \"d4bd27f6444bc2dae824111afc5ff67daa81e65104cd96a0425ecedda674c7bc\",\n        \"size\": 370342329\n    },\n    \"LaneChange_Town12_Route1659_Weather15.tar.gz\": {\n        \"sha256\": \"30f931fedc744df5f5f83c82801a778b9561559d51a65273e0f2402cb412facc\",\n        \"size\": 202267059\n    },\n    \"LaneChange_Town12_Route17553_Weather2.tar.gz\": {\n        \"sha256\": \"4b1d5e1cd488e667f003a2765e9963fbc8574c1ef458dbb119f0f8ce0e77dd32\",\n        \"size\": 215619720\n    },\n    \"LaneChange_Town12_Route17563_Weather12.tar.gz\": {\n        \"sha256\": \"96aead66917da732612edfd1f4462ba266bec861318a993a83cfcadb5016f74b\",\n        \"size\": 293471952\n    },\n    \"LaneChange_Town12_Route17570_Weather19.tar.gz\": {\n        \"sha256\": \"f8d89301389e33d43b0e2060add0e86b4850f39803b994bd05206f8fca0d2083\",\n        \"size\": 329695678\n    },\n    \"LaneChange_Town12_Route17572_Weather21.tar.gz\": {\n        \"sha256\": \"afef0ddae0f0bc1f2ed69e497e2f5338974910b33ce1fbc1e0289e25c5d52478\",\n        \"size\": 230817499\n    },\n    \"LaneChange_Town12_Route17578_Weather1.tar.gz\": {\n        \"sha256\": \"6e3f5dc08eb132a763260643830a91d9da5cec991119ee3cd67fa3b0e5f754c2\",\n        \"size\": 262440263\n    },\n    \"LaneChange_Town12_Route17581_Weather3.tar.gz\": {\n        \"sha256\": \"e225b1e94ba3d2e23ee22f0c033aac652deda415e1d20d0911a1ed19a69d2ebd\",\n        \"size\": 257846151\n    },\n    \"LaneChange_Town12_Route17587_Weather10.tar.gz\": {\n        \"sha256\": \"61de665c32d137c7769893a7d7edcd9ec37587fb40c058be10b0ef142ac8a750\",\n        \"size\": 348349052\n    },\n    \"LaneChange_Town12_Route17598_Weather21.tar.gz\": {\n        \"sha256\": \"982d8d18eb1f95dec7260fa306de64a02c128cd7aea7c6005e7dec83cae79c87\",\n        \"size\": 242812005\n    },\n    \"LaneChange_Town12_Route17604_Weather1.tar.gz\": {\n        \"sha256\": \"deca3fd6e97cebfc418d59301e4664df8a9ec21b8691a83d8a0496d68998d7ea\",\n        \"size\": 460254941\n    },\n    \"LaneChange_Town12_Route17609_Weather6.tar.gz\": {\n        \"sha256\": \"d10b19ae6594fb4373c040717c61b20305d82bd3f802e1ed45f961dfb6c28d2e\",\n        \"size\": 287800350\n    },\n    \"LaneChange_Town12_Route17611_Weather8.tar.gz\": {\n        \"sha256\": \"f9c20c1d0a8c2ecc9c34b1458411f9086109c4ca3c152be3d640c128110bf508\",\n        \"size\": 257466282\n    },\n    \"LaneChange_Town12_Route17612_Weather9.tar.gz\": {\n        \"sha256\": \"4dbfd671b52b2a9085e47f395bbbee1583aa9f570d4de0427e3824a479950bbe\",\n        \"size\": 350451802\n    },\n    \"LaneChange_Town12_Route17614_Weather11.tar.gz\": {\n        \"sha256\": \"899f6562f8085781b9200e4420bb46aab7b897c49bd019cf702021910283fa11\",\n        \"size\": 282792547\n    },\n    \"LaneChange_Town12_Route17624_Weather21.tar.gz\": {\n        \"sha256\": \"fd3537bdf1855d1f6f8f16621470c94bd151ffb9ff8394cde67ccfab06047c64\",\n        \"size\": 150506728\n    },\n    \"LaneChange_Town12_Route17629_Weather0.tar.gz\": {\n        \"sha256\": \"09cccd7f70f484d4402afe889a38184f366e1bde00cacf218c653b1f2fe93096\",\n        \"size\": 253730472\n    },\n    \"LaneChange_Town12_Route17635_Weather6.tar.gz\": {\n        \"sha256\": \"90f5d8e51bb652e7232ac3e5a2c2a728e2fc1214e1a4e95dceb619d7b02a1505\",\n        \"size\": 332222246\n    },\n    \"LaneChange_Town12_Route17646_Weather9.tar.gz\": {\n        \"sha256\": \"1e789460942e6965906526263dbce6bdd7857130bd35be34c7337f8d1acec773\",\n        \"size\": 276426926\n    },\n    \"LaneChange_Town12_Route17655_Weather0.tar.gz\": {\n        \"sha256\": \"eafd78fb49d43535e026f81e91c72e60b01c2005e0bb27e1ce1c8842890f1ee8\",\n        \"size\": 393230869\n    },\n    \"LaneChange_Town12_Route17663_Weather8.tar.gz\": {\n        \"sha256\": \"d79b3dce5fd89efbdcad78fb834f0d9b479859f0e6dd80a180149f0e5f4ba2ff\",\n        \"size\": 563241200\n    },\n    \"LaneChange_Town12_Route17668_Weather13.tar.gz\": {\n        \"sha256\": \"fed4e458d5b3d55aa95e584198ffb927610784313d7df2719e27df0ce8466e68\",\n        \"size\": 328935832\n    },\n    \"LaneChange_Town12_Route17671_Weather8.tar.gz\": {\n        \"sha256\": \"22b57d4b3e7b09478b965e33d620399f06462f324191d14e1315d19fa0fe9e34\",\n        \"size\": 290577326\n    },\n    \"LaneChange_Town12_Route17672_Weather9.tar.gz\": {\n        \"sha256\": \"3474a9e72ae807f96183a7158c82f6d139026a96f779beb8dae887344f399302\",\n        \"size\": 322775662\n    },\n    \"LaneChange_Town12_Route17689_Weather8.tar.gz\": {\n        \"sha256\": \"0368ecbb2982650ada643aec516911e6efecf8cadad71c33d0d3faf02e80048c\",\n        \"size\": 302394503\n    },\n    \"LaneChange_Town12_Route17690_Weather9.tar.gz\": {\n        \"sha256\": \"9a75ffdeb8982f20ee215803745caa9eb562c17c02519d0612dd05f4ba0052d8\",\n        \"size\": 316299145\n    },\n    \"LaneChange_Town12_Route17691_Weather10.tar.gz\": {\n        \"sha256\": \"0895c1fdd95e7d75aac1d5101d0aea762081999bf21986a577e15f2d5bf91983\",\n        \"size\": 318095727\n    },\n    \"LaneChange_Town12_Route17695_Weather14.tar.gz\": {\n        \"sha256\": \"98707d7cf66dea7d7e2c47b5cdc7d935992c91321aaac8f6098ce89b85d84d15\",\n        \"size\": 209674460\n    },\n    \"LaneChange_Town12_Route17707_Weather0.tar.gz\": {\n        \"sha256\": \"3c6684b028568f14648a0041e857aa45d29d9a2c1ae2a45e604fd17aed04f3e7\",\n        \"size\": 378936906\n    },\n    \"LaneChange_Town12_Route2425_Weather1.tar.gz\": {\n        \"sha256\": \"b7d71be26ad0490cd25590a898cf82d05e0ba761fcb82b7cb15c9bb04bc112ee\",\n        \"size\": 237701286\n    },\n    \"LaneChange_Town12_Route2427_Weather3.tar.gz\": {\n        \"sha256\": \"505fa521210f80640bb29dbb42b62137da5ca8ef61bae46e637949a68a7311d1\",\n        \"size\": 320912731\n    },\n    \"LaneChange_Town12_Route2431_Weather7.tar.gz\": {\n        \"sha256\": \"8e685365e6810c9a353719ffc3c2c9eae6f119da0bd62296aaa57df602626591\",\n        \"size\": 266714896\n    },\n    \"LaneChange_Town12_Route2432_Weather8.tar.gz\": {\n        \"sha256\": \"e2531fb99972bc03e31eac5fd8adf1451d068260c45328e00c6e92e5cd1145a3\",\n        \"size\": 330643821\n    },\n    \"LaneChange_Town12_Route2435_Weather11.tar.gz\": {\n        \"sha256\": \"ffa98034eb532717612d3b499673af66ec5fc81364fbc739a031f10995fa1ea4\",\n        \"size\": 251781622\n    },\n    \"LaneChange_Town13_Route3207_Weather3.tar.gz\": {\n        \"sha256\": \"20d97aae6d511d2ceab2d99fef77d3d69927e83c6ab98768e72e41dbd93ee74d\",\n        \"size\": 665546446\n    },\n    \"LaneChange_Town13_Route3208_Weather5.tar.gz\": {\n        \"sha256\": \"16dfe04f7dee86447abc5712481b19f98e1767b5d3e0df6d57e0be2e286d0086\",\n        \"size\": 684798768\n    },\n    \"LaneChange_Town13_Route3217_Weather14.tar.gz\": {\n        \"sha256\": \"0d1c26ebbb44628679a69aaa16fdd0b444f042e57b66dbf88f976d324cf1c446\",\n        \"size\": 132141428\n    },\n    \"LaneChange_Town15_Route24303_Weather15.tar.gz\": {\n        \"sha256\": \"a275478b89d4bbb59fb4d720bfa58b2be9d08ea3746f3c4b8282a94f4058d6bb\",\n        \"size\": 447871181\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37596_Weather11.tar.gz\": {\n        \"sha256\": \"0197c2c726f072765d2a19035a33e366f5a2700e9f4d77c4dcb76d23e9bb7655\",\n        \"size\": 344439639\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37598_Weather11.tar.gz\": {\n        \"sha256\": \"5b2843bf7ff8af713ba4015b73de4e31dc3a23138ceaedc5f894d4499ceea8f5\",\n        \"size\": 275628052\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37603_Weather11.tar.gz\": {\n        \"sha256\": \"5a78fd3ecd076ce44401b19bcbb9e503a45b248e52d378d99de464b98d312b14\",\n        \"size\": 222689605\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37610_Weather11.tar.gz\": {\n        \"sha256\": \"4c233c99dc728830423a4a93d2d97b29c84354e9f1d9a269e23876e8b7c422f3\",\n        \"size\": 290170521\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37663_Weather12.tar.gz\": {\n        \"sha256\": \"4a82e508370586b84c58f077fedecf6140d56038240beca44f0a0e74d15e0a79\",\n        \"size\": 235751335\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37667_Weather12.tar.gz\": {\n        \"sha256\": \"57e3bd229d72678a13d7902287ffe8e61c2cb54d726ecef01bdcb938fc67abc8\",\n        \"size\": 254689453\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37671_Weather12.tar.gz\": {\n        \"sha256\": \"14aae9cc5c4c294255376a8b0fd7fb1d64a56d0b8b72220fcaf95a585dd567f4\",\n        \"size\": 319303570\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37674_Weather12.tar.gz\": {\n        \"sha256\": \"7c61fd67ea192048c12b8f0ffbf4e1336ca981d5199990e0e05efbfa8251a2aa\",\n        \"size\": 289683496\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37680_Weather12.tar.gz\": {\n        \"sha256\": \"7222f1cc77e8666ef71fc2e24776510e73a1a511f66343cfad9de55798a51dfb\",\n        \"size\": 312116369\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37687_Weather12.tar.gz\": {\n        \"sha256\": \"049cb9881406427cd3b870a68aa42d6efa592fb4f339dc7cbf3ffee3e4170fd4\",\n        \"size\": 291427583\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37727_Weather13.tar.gz\": {\n        \"sha256\": \"67527146775be7560159baa108cdc00d539615ba3ee20929e11b7c62f0fe9272\",\n        \"size\": 371809355\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37737_Weather13.tar.gz\": {\n        \"sha256\": \"b9bbb7f5ace562dfb61bd9ebd486b897530f58e9b12f802be3170e20815c7526\",\n        \"size\": 254469225\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37741_Weather13.tar.gz\": {\n        \"sha256\": \"86736bf952521ed9584770841877b1ff358c6ea65160cd4b27f3eb1d80931808\",\n        \"size\": 387930112\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37749_Weather13.tar.gz\": {\n        \"sha256\": \"723c7942613f501eecdd50ee2faf65d744210ceb19d6292f69c805a181544405\",\n        \"size\": 237276373\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37753_Weather13.tar.gz\": {\n        \"sha256\": \"e07b45197403848c9488ff043380cdb8ccafa7456f83df3952de48b2cda4e2fa\",\n        \"size\": 328260055\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37769_Weather13.tar.gz\": {\n        \"sha256\": \"5ff1c7226780408002d66e229b6b7dc8814405d2ea745c7e3faf47e0168f6299\",\n        \"size\": 297568622\n    },\n    \"MergerIntoSlowTrafficV2_Town12_Route37831_Weather14.tar.gz\": {\n        \"sha256\": \"88720318272d65be1538b849ff8865f10e74e5a44f55621c2ba2f1f63722bac7\",\n        \"size\": 262451571\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route3515_Weather22.tar.gz\": {\n        \"sha256\": \"ea6751e38e55a74b21c0a3398fe93312d7fc3237d43a44aae7183b86a8608a24\",\n        \"size\": 613860875\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route3516_Weather23.tar.gz\": {\n        \"sha256\": \"a5ddcf7ef450ed89604a9da7cd1064da9b18059eb5832f45dffabef807550687\",\n        \"size\": 184981176\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route3539_Weather23.tar.gz\": {\n        \"sha256\": \"21cef9c17c1d52250d3537eb676d78d6faa0cdaff04f7ac78baad5c68ca2d62e\",\n        \"size\": 652365053\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37619_Weather11.tar.gz\": {\n        \"sha256\": \"78bd62b844c1372d9720dcfd4916a9c0e0814ffbeddd89f3960b9178e1e72dbe\",\n        \"size\": 548196576\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37622_Weather11.tar.gz\": {\n        \"sha256\": \"8ab82e4bd7a652e8eeab6c6d57594d3f8c8e7c773ed85f3cad169b90d20e2ad8\",\n        \"size\": 176676258\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37625_Weather11.tar.gz\": {\n        \"sha256\": \"a998d8dfac2b55fb01aa2abdcc17d88b6e5cc93e6459d79b657215c41dec337d\",\n        \"size\": 487825443\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37626_Weather11.tar.gz\": {\n        \"sha256\": \"af5332941bddeec0b8d8d32b0185390c02e234e0a19df3f66cf32e402abc7d0b\",\n        \"size\": 182407730\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37630_Weather11.tar.gz\": {\n        \"sha256\": \"f8beec5483207d638c2bfe5f3bd1cc899b6d58af95499d6a049e6f93a65d3301\",\n        \"size\": 604255181\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37633_Weather11.tar.gz\": {\n        \"sha256\": \"fff6d8e7ed977de847df3419f2e387227c7c03476bf8ccb0b23a64a7f805d6f2\",\n        \"size\": 189125485\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37635_Weather11.tar.gz\": {\n        \"sha256\": \"2ce4660f6985ddc6724b711ea608f76f546cf94dff3db34aca4f873939011094\",\n        \"size\": 633883398\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37636_Weather11.tar.gz\": {\n        \"sha256\": \"9f9bec1f01376bde29070f3a2543db8ae76c699527b40dcfbe576bc4e0553459\",\n        \"size\": 546960355\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37637_Weather11.tar.gz\": {\n        \"sha256\": \"9e5912471716e1182225c91383d6a9ac6d43ca0ad548793a815be3801c5c5a64\",\n        \"size\": 540758224\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37639_Weather11.tar.gz\": {\n        \"sha256\": \"1ad0489d3e2ffd1838f9cb205755f65e1b40833eae105a643850f7479aa4cafe\",\n        \"size\": 569322037\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37640_Weather11.tar.gz\": {\n        \"sha256\": \"e755b9252977134df166d893b5e03ec6e639ceacf197724b819824494c3e2cfb\",\n        \"size\": 188492429\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37642_Weather11.tar.gz\": {\n        \"sha256\": \"0eaeff8ed45f4ddf7b2d838befbd9bf81bf9e0b865184e11903ea0c465ecd504\",\n        \"size\": 659799611\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37701_Weather12.tar.gz\": {\n        \"sha256\": \"8cacb6c9be2ca36ae99a2e9eea387d07202399886a7f210d15cdbd7fdff2c48e\",\n        \"size\": 535173778\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37704_Weather12.tar.gz\": {\n        \"sha256\": \"4ce4c3a3708e719bb2ff022d8001bbab020edc0fee930046135f645fd0de5711\",\n        \"size\": 183285107\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37712_Weather12.tar.gz\": {\n        \"sha256\": \"cbba205587c6fcc56846a2cab50a11b0841b5556915956221272205d3d37e73a\",\n        \"size\": 566577997\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37715_Weather12.tar.gz\": {\n        \"sha256\": \"8b3438e23636772f0368d9ef9330a6e8bba803527e2afa8920b8322ce1342a14\",\n        \"size\": 197741547\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37717_Weather12.tar.gz\": {\n        \"sha256\": \"d962552ef1ea6a06338cbf753a8162a840d8d22b9696ea9b8b8a437552816196\",\n        \"size\": 615414104\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37719_Weather12.tar.gz\": {\n        \"sha256\": \"86f0c02006e7ddbe1c7342beea57f1a06c241a9c489d4d35a85cb3679d1276ff\",\n        \"size\": 548942403\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37784_Weather13.tar.gz\": {\n        \"sha256\": \"9d1a524f14534a87b263cf4928ad8151197355312cfe37a337a474edfb2d7721\",\n        \"size\": 547844842\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37789_Weather13.tar.gz\": {\n        \"sha256\": \"1bca59fc4a91f8ab73773081a8457fe51a77d682481540dadcb49eff8e6bd6dd\",\n        \"size\": 489179696\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37793_Weather13.tar.gz\": {\n        \"sha256\": \"8194600948c64694b6794fd68540c6262ffea9c00d0acc349b145c3c47142920\",\n        \"size\": 467812898\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37804_Weather13.tar.gz\": {\n        \"sha256\": \"73590d42dfc62fbc2f27c352cc6e84e3757fdde3fbfcaafe7ff80c09ac8d220a\",\n        \"size\": 187608726\n    },\n    \"MergerIntoSlowTrafficV2_Town13_Route37806_Weather13.tar.gz\": {\n        \"sha256\": \"27d8e6e93c151186647d3ed173b3b3fac597824d3a3dc1da7d16eb6a5a8925d7\",\n        \"size\": 582920039\n    },\n    \"MergerIntoSlowTraffic_Town12_Route13441_Weather2.tar.gz\": {\n        \"sha256\": \"42e0e80c827d06b7b8e8be4ec7c2bae7375b655119eb9f10b15277f8cbb3fa7c\",\n        \"size\": 261502935\n    },\n    \"MergerIntoSlowTraffic_Town12_Route13443_Weather3.tar.gz\": {\n        \"sha256\": \"5596614ee2aa7df9cab30f71d1ae6d8763cde66aa386608368b36cd8adabc6fd\",\n        \"size\": 248282296\n    },\n    \"NoScenario_Town12_Route12961_Weather8.tar.gz\": {\n        \"sha256\": \"94e3f453d9422615d50a7648009ab6eaf447cb72cf663fbded6ca390e36f72d5\",\n        \"size\": 204944393\n    },\n    \"NoScenario_Town12_Route13482_Weather9.tar.gz\": {\n        \"sha256\": \"3cd1f8e19d1aac5db8560f9020404ab5f06ca9d70bfff15c4a6e122d66166d64\",\n        \"size\": 185991456\n    },\n    \"NoScenario_Town12_Route13555_Weather12.tar.gz\": {\n        \"sha256\": \"f7b014d483625e9f4f999b4c0eaacbe1cb8b950d014a7f6142bbde87ad1aba44\",\n        \"size\": 547955813\n    },\n    \"NoScenario_Town12_Route13636_Weather15.tar.gz\": {\n        \"sha256\": \"fd2a8357ddc065e5429cd387f21c5e5f7eafba8fc7c86f27fe086270f9e33066\",\n        \"size\": 264204626\n    },\n    \"NoScenario_Town12_Route13654_Weather7.tar.gz\": {\n        \"sha256\": \"08b7e7ac5ca9f9a9327ed45eb8d5e3050909aa4be8577fade4fb5058bddfec55\",\n        \"size\": 261716054\n    },\n    \"NoScenario_Town12_Route13711_Weather12.tar.gz\": {\n        \"sha256\": \"7e5b58724ef82c85a040e81c81cb101a8bf5095a92f1c26bbe9d8c9496cefd4d\",\n        \"size\": 262692781\n    },\n    \"NoScenario_Town12_Route13730_Weather5.tar.gz\": {\n        \"sha256\": \"53ab49c1e5dae9ed86dbf9b7a52e6415489ca2df1cae05e413034efa7a36428b\",\n        \"size\": 285264948\n    },\n    \"NoScenario_Town12_Route15299_Weather14.tar.gz\": {\n        \"sha256\": \"ae32031be2ffd198951fa4a0740c9b625b60ff134a8890af094dc7964487b758\",\n        \"size\": 83840985\n    },\n    \"NoScenario_Town12_Route15557_Weather12.tar.gz\": {\n        \"sha256\": \"f3754e5202360dc147580d2a7f2eb28ff0dc5fb8fc326a216328ad54dab4ffe8\",\n        \"size\": 145170944\n    },\n    \"NoScenario_Town12_Route15666_Weather9.tar.gz\": {\n        \"sha256\": \"04ab5f401d824807243dd2db703ea5b368de773e8dedbd2e473d8287280426b5\",\n        \"size\": 182222754\n    },\n    \"NoScenario_Town12_Route15816_Weather11.tar.gz\": {\n        \"sha256\": \"d63060c70517b7a6adbb90e34d20e383263a7f5291491517317ad204b391a187\",\n        \"size\": 149304256\n    },\n    \"NoScenario_Town12_Route15817_Weather12.tar.gz\": {\n        \"sha256\": \"e924110f769e16d846e6cf31d684962ef4aa5642c039485dd3a291f7b21ddc50\",\n        \"size\": 95718064\n    },\n    \"NoScenario_Town12_Route16086_Weather21.tar.gz\": {\n        \"sha256\": \"803198583277c10a307b588957eb36defdc099b2f794397bf49b93b819b58a15\",\n        \"size\": 169727477\n    },\n    \"NoScenario_Town12_Route16143_Weather0.tar.gz\": {\n        \"sha256\": \"412e23424e0d3300b18dcd6a542597942c22e88f73302915bb5820b66eaed74f\",\n        \"size\": 222159260\n    },\n    \"NoScenario_Town12_Route16186_Weather9.tar.gz\": {\n        \"sha256\": \"a45b29979a314dc7ef684f3dd78abd653a617ab32f5434248219d067c7a20d39\",\n        \"size\": 256215118\n    },\n    \"NoScenario_Town12_Route16299_Weather0.tar.gz\": {\n        \"sha256\": \"9676c96dcc3685a51425072c6d5fdbb522bf16771b85bbf8b2f05b64672bdc62\",\n        \"size\": 102856662\n    },\n    \"NoScenario_Town12_Route35404_Weather0.tar.gz\": {\n        \"sha256\": \"9c15b3827abcec3986c5b602c0fcb18572a8d9a7c1a8cb3a725acc32aa273810\",\n        \"size\": 517661231\n    },\n    \"NoScenario_Town12_Route35418_Weather0.tar.gz\": {\n        \"sha256\": \"790bc2282f9f0eb095dd9a1ba9b564cb8ec75b18f53de826d96fac50a50e566a\",\n        \"size\": 441247409\n    },\n    \"NoScenario_Town12_Route35427_Weather1.tar.gz\": {\n        \"sha256\": \"98cc5d1db6f266ed7a132535efa5076fff474a8df8b035d7ae3864fc487af4b6\",\n        \"size\": 458321195\n    },\n    \"NoScenario_Town12_Route35532_Weather2.tar.gz\": {\n        \"sha256\": \"2fe4843c979156b8044fdbad7b3aab4d4ae1a4f93e4fa5138f09c38ff799c1b4\",\n        \"size\": 129996921\n    },\n    \"NoScenario_Town12_Route35538_Weather2.tar.gz\": {\n        \"sha256\": \"a2709bb7eab29790f8f5c76cda09813a0d3b43319cba636e80bce0c460a30162\",\n        \"size\": 448115906\n    },\n    \"NoScenario_Town12_Route35563_Weather3.tar.gz\": {\n        \"sha256\": \"6826ec8c69ca012d057128d8375624117af56d44f5353c60ee9481b6ee03b046\",\n        \"size\": 502398048\n    },\n    \"NoScenario_Town12_Route35568_Weather3.tar.gz\": {\n        \"sha256\": \"7eb8bd24b243e60f831884761a767a817b22999dfa2341b22db55c63e6ca73fd\",\n        \"size\": 133254997\n    },\n    \"NoScenario_Town12_Route35584_Weather3.tar.gz\": {\n        \"sha256\": \"bd257906d7bfbe08297377b3c520235e12a43c235ba148911f819c84d8b3b78b\",\n        \"size\": 501840989\n    },\n    \"NoScenario_Town12_Route35592_Weather3.tar.gz\": {\n        \"sha256\": \"e17a1405d586b5e8e536c93b8e08e8b919fc088c53a257870bd280b4423066ca\",\n        \"size\": 131444293\n    },\n    \"NoScenario_Town12_Route36583_Weather23.tar.gz\": {\n        \"sha256\": \"5d5972e7e7f9d52cb2b054e17edd224f8c88bfae83dad0a762c17799c074c73c\",\n        \"size\": 447394420\n    },\n    \"NoScenario_Town12_Route36612_Weather23.tar.gz\": {\n        \"sha256\": \"4ab0178c196525ef9ca3ee24bff7a4d3bbf151f19df1f664f780cf9c43f6c84a\",\n        \"size\": 106929631\n    },\n    \"NoScenario_Town12_Route36618_Weather23.tar.gz\": {\n        \"sha256\": \"d701e61dd359608b8c87b0b0afa747c298184a22294dffa96671e4930a9ec4ec\",\n        \"size\": 369744929\n    },\n    \"NoScenario_Town12_Route6734_Weather3.tar.gz\": {\n        \"sha256\": \"df507c974c6e9d8fcb3c8ed54dbd9d8b4fe49daba3fbf06ed9d017056197b778\",\n        \"size\": 230939243\n    },\n    \"NoScenario_Town12_Route6901_Weather14.tar.gz\": {\n        \"sha256\": \"26e6deb59c0dc8300e5235fb7888d02d2040c67548a94f5b881290c61bf73fd9\",\n        \"size\": 181383991\n    },\n    \"NoScenario_Town12_Route8446_Weather25.tar.gz\": {\n        \"sha256\": \"191b7fe9e1174ebfb176660e8d626f38c8f10b17c4312bed73cd0eccd6322cb7\",\n        \"size\": 198243065\n    },\n    \"NoScenario_Town12_Route8462_Weather15.tar.gz\": {\n        \"sha256\": \"1ee61cdbfa1b14e59db51625265555c373479e092d5b4a87096e5cf9aeb7dacb\",\n        \"size\": 128043858\n    },\n    \"NoScenario_Town12_Route8471_Weather23.tar.gz\": {\n        \"sha256\": \"9e2e7bce110823bad99c18e2a0daeeed0c60c39ba923236cd2838d31c26e12d4\",\n        \"size\": 155792734\n    },\n    \"NoScenario_Town12_Route8487_Weather14.tar.gz\": {\n        \"sha256\": \"b6acd5697e8a6e6274d4ef9c8a8a96c0c6d94972cc2ead25690ce24195a832b7\",\n        \"size\": 177427217\n    },\n    \"NoScenario_Town12_Route8495_Weather22.tar.gz\": {\n        \"sha256\": \"f7c2166dbbcf7f03df8296b5b44f37f7c03f86cc5eab792ef0df7907c72a24e3\",\n        \"size\": 184029439\n    },\n    \"NoScenario_Town12_Route8505_Weather6.tar.gz\": {\n        \"sha256\": \"173a3746dcaea1a45aff9451af6b30cf2d956b3027f4b47635e8597ffef33ba8\",\n        \"size\": 131790263\n    },\n    \"NoScenario_Town12_Route8508_Weather9.tar.gz\": {\n        \"sha256\": \"5362c0696b146828aeecb23b858a67f262f9cae522aa4d548e878980a615423f\",\n        \"size\": 211526352\n    },\n    \"NoScenario_Town12_Route8509_Weather10.tar.gz\": {\n        \"sha256\": \"8fc760a3902aeeda50ddc60604e6081340a60e8285809ca728320f8b494fedd8\",\n        \"size\": 169104398\n    },\n    \"NoScenario_Town12_Route8513_Weather14.tar.gz\": {\n        \"sha256\": \"830d3d2125ad40d49eeae01de1a5e44670181ef444ced395e2532991bc3a53c0\",\n        \"size\": 172457629\n    },\n    \"NoScenario_Town12_Route8518_Weather19.tar.gz\": {\n        \"sha256\": \"852a0d77852890cce4761e7e4d16a2afd09ba922cb3d3ec1b311a47a45e8f789\",\n        \"size\": 303578188\n    },\n    \"NoScenario_Town12_Route8538_Weather13.tar.gz\": {\n        \"sha256\": \"de007187f64d4f4b04b4a404d2b7642e0100355f5b775ee16a53df755fc694be\",\n        \"size\": 121746520\n    },\n    \"NoScenario_Town12_Route8554_Weather3.tar.gz\": {\n        \"sha256\": \"a8a6ced22e850a9de148f0366d7f5ba45d028ce80abd9750ac3cdcff5201a03e\",\n        \"size\": 230402508\n    },\n    \"NoScenario_Town12_Route8569_Weather18.tar.gz\": {\n        \"sha256\": \"7ad72f6d1677857ff3b873b64128d80194ec2976579e5c938f0ff41511c75b3d\",\n        \"size\": 158537958\n    },\n    \"NoScenario_Town12_Route8575_Weather23.tar.gz\": {\n        \"sha256\": \"8b1f4fc16a4909ef9b1a72976ca6caf878d0e83dcbcfa459bd57aef92caee83b\",\n        \"size\": 147334768\n    },\n    \"NoScenario_Town12_Route8582_Weather5.tar.gz\": {\n        \"sha256\": \"27b4d90ccb76d6cf71bee77abd8a06957a062160c507d96ae3c84b3ed5b72ebc\",\n        \"size\": 167540574\n    },\n    \"NoScenario_Town12_Route8596_Weather19.tar.gz\": {\n        \"sha256\": \"b86b5671684c442e70d9514349693a800aa72fd7263fab8a176c4272f0b80162\",\n        \"size\": 180984609\n    },\n    \"NoScenario_Town12_Route8608_Weather5.tar.gz\": {\n        \"sha256\": \"d38bb4e5c02267471a31f1599cd274b5d8097b678b966c2faadffc2768ae2b6d\",\n        \"size\": 206088096\n    },\n    \"NoScenario_Town12_Route8614_Weather11.tar.gz\": {\n        \"sha256\": \"008a2d78aea9068fa584bb85829e6ad76f0b8ea4d21459dc9e51e857d11b7c4e\",\n        \"size\": 146643188\n    },\n    \"NoScenario_Town12_Route8624_Weather21.tar.gz\": {\n        \"sha256\": \"e28ba32a548658eaad0c862d14c34adc74644bde49e8e72ec8b10f9fc40679aa\",\n        \"size\": 222079443\n    },\n    \"NoScenario_Town12_Route8651_Weather22.tar.gz\": {\n        \"sha256\": \"d9ce3e514cd95fc225490f2382ff0d0ad25639d3eef9438cfae91a5e904216f3\",\n        \"size\": 185113471\n    },\n    \"NoScenario_Town12_Route8664_Weather9.tar.gz\": {\n        \"sha256\": \"325b84f8f576b74870112a7a76301859fe747fc7fcc0e74e2edb7c727c2d1e6f\",\n        \"size\": 149845309\n    },\n    \"NoScenario_Town12_Route8667_Weather12.tar.gz\": {\n        \"sha256\": \"159658d4cf94c1067481c4f098c5585750e05515fee9bbdfdc212c47001b9ef0\",\n        \"size\": 196158289\n    },\n    \"NoScenario_Town12_Route8671_Weather8.tar.gz\": {\n        \"sha256\": \"ae62779f12341da316653d9b5704bc0db711ffc901667feb9a357c7d0aa248c5\",\n        \"size\": 224798135\n    },\n    \"NoScenario_Town12_Route8673_Weather18.tar.gz\": {\n        \"sha256\": \"7ca98994d420526eff6f55d870097501becb3748c365a8efda23ccc42d892166\",\n        \"size\": 186967128\n    },\n    \"NoScenario_Town12_Route8698_Weather9.tar.gz\": {\n        \"sha256\": \"744e348691c386160a299e4a2c636c68c62e1f935d8f17d10b52020416d0d9a7\",\n        \"size\": 165892628\n    },\n    \"NoScenario_Town12_Route8711_Weather3.tar.gz\": {\n        \"sha256\": \"8f6f9d3d00f4b82d0e09fda4e9b07e94735b73c00ba19e62a498ead865bfedcf\",\n        \"size\": 242427220\n    },\n    \"NoScenario_Town12_Route8720_Weather13.tar.gz\": {\n        \"sha256\": \"37aed67476c0813b4c385e78d80e5058407fdb55a5e024fa94e4deb8fa8396f3\",\n        \"size\": 123070984\n    },\n    \"NoScenario_Town12_Route8746_Weather13.tar.gz\": {\n        \"sha256\": \"b709d644513324ca82abd363f73b73599155234416956f6f5bfe3e83ec2c664b\",\n        \"size\": 133610419\n    },\n    \"NoScenario_Town12_Route8780_Weather21.tar.gz\": {\n        \"sha256\": \"904cc2dd8f7e80356f03badc0c7e3919edd50aa91416e40e2d2047e2099127ea\",\n        \"size\": 169344445\n    },\n    \"NoScenario_Town12_Route8783_Weather23.tar.gz\": {\n        \"sha256\": \"455bc4f1204e7807212746896c08ea7f4d1fcde1529c2bf830ed2b89af7eab57\",\n        \"size\": 184840039\n    },\n    \"NoScenario_Town12_Route8805_Weather20.tar.gz\": {\n        \"sha256\": \"1caf4b9252e9b79c66ae6a8530fd3ca0e903bcf375f7f2d5f7fdf8e3017dcd40\",\n        \"size\": 165945526\n    },\n    \"NoScenario_Town12_Route8812_Weather1.tar.gz\": {\n        \"sha256\": \"9008d3920582bdfd60b4e7cc671233883b669a2404c21370c1498e54c7ba72fb\",\n        \"size\": 192689918\n    },\n    \"NoScenario_Town12_Route8815_Weather3.tar.gz\": {\n        \"sha256\": \"230cd9a7c90f19d52693c156b7d36298c61d3d5201e4a1b79383b31c898740b8\",\n        \"size\": 177755486\n    },\n    \"NoScenario_Town12_Route8816_Weather5.tar.gz\": {\n        \"sha256\": \"112c0519ffbb09234f338058a54f424e04052c7a8341e7cfb7c906af0c58baca\",\n        \"size\": 174456992\n    },\n    \"NoScenario_Town12_Route8825_Weather14.tar.gz\": {\n        \"sha256\": \"205e9060011f97f62b616260ce8684f039aa54fd2d5f4d9b7aa2fae50744a16f\",\n        \"size\": 118006635\n    },\n    \"NoScenario_Town12_Route8829_Weather18.tar.gz\": {\n        \"sha256\": \"ea4eed6356219ef67696363b73c7eaf959b6a92f767c40fdd9bbfb70179274ef\",\n        \"size\": 179559704\n    },\n    \"NoScenario_Town12_Route8867_Weather3.tar.gz\": {\n        \"sha256\": \"233d291a76ea626422acae21c997b064ea5d84d50da0898a7d940a39e63a7c64\",\n        \"size\": 123766302\n    },\n    \"NoScenario_Town12_Route8879_Weather8.tar.gz\": {\n        \"sha256\": \"2a3aed39120fcbc63d7041b9ffcc3d038d0a5e7ed1f1ee1128913c6da10e6081\",\n        \"size\": 129523326\n    },\n    \"NoScenario_Town12_Route8882_Weather19.tar.gz\": {\n        \"sha256\": \"ca8b33925af330a6f2756cc064df3ef05ef872d5294618caf3a6601b4d66b8df\",\n        \"size\": 187559064\n    },\n    \"NoScenario_Town12_Route8883_Weather20.tar.gz\": {\n        \"sha256\": \"ed7ba6a0636b206dc7c242d44d466948eeabb36787f1ad4bb22a81de5e2bcdfc\",\n        \"size\": 163046794\n    },\n    \"NoScenario_Town12_Route8884_Weather21.tar.gz\": {\n        \"sha256\": \"483f7baa06813ea7c2baaff5c023392a7c8569d972c443e5720e702b3181b8c4\",\n        \"size\": 147485195\n    },\n    \"NoScenario_Town12_Route8896_Weather7.tar.gz\": {\n        \"sha256\": \"81e215d8276f1f4dfb6cbf405297a055b9ff74d7fd73e55c2f6825fe65c2210e\",\n        \"size\": 185745511\n    },\n    \"NoScenario_Town12_Route8900_Weather11.tar.gz\": {\n        \"sha256\": \"6f83936f5aae004abd18b8cad49ca009f008f2b39b1e2884fdb129b1a74d5a99\",\n        \"size\": 167039042\n    },\n    \"NoScenario_Town12_Route8904_Weather15.tar.gz\": {\n        \"sha256\": \"2b29d59192e4c545c1d8094fa89ae4e258c5c32a273d71962942043395ac3700\",\n        \"size\": 320724924\n    },\n    \"NoScenario_Town12_Route8919_Weather3.tar.gz\": {\n        \"sha256\": \"5628e8269de0053b08506280bf5e5695dfbb6180260dbf231849775518f329a5\",\n        \"size\": 175122422\n    },\n    \"NoScenario_Town12_Route8955_Weather14.tar.gz\": {\n        \"sha256\": \"ceb729cdef969e63c34b5990a821134372ffdb1abfaa3c766ad8b668456988ea\",\n        \"size\": 159397939\n    },\n    \"NoScenario_Town12_Route8980_Weather13.tar.gz\": {\n        \"sha256\": \"677ac3606f4e8056e3446efd7395abec3dcb2346ba89211e512e67ce02ccbfcb\",\n        \"size\": 127809281\n    },\n    \"NoScenario_Town12_Route8982_Weather15.tar.gz\": {\n        \"sha256\": \"886dc14604ca8c53f6b834eb717c60c5eb3846483d4d0a59c8672ea805bc3dec\",\n        \"size\": 213237185\n    },\n    \"NoScenario_Town12_Route9013_Weather20.tar.gz\": {\n        \"sha256\": \"313207a430f8d89e92716627b35821439d56d282bdfbf4faf6b3465629e95821\",\n        \"size\": 206358328\n    },\n    \"NoScenario_Town12_Route9030_Weather11.tar.gz\": {\n        \"sha256\": \"de3801f6622d431d77d7508796573efea6f6bb6504f964c5124d51c2d00d4360\",\n        \"size\": 114594080\n    },\n    \"NoScenario_Town12_Route9032_Weather13.tar.gz\": {\n        \"sha256\": \"3975cb73627ad79a46318444e764c742630465f476580ab33632c3931f75a4ad\",\n        \"size\": 184514531\n    },\n    \"NoScenario_Town12_Route9034_Weather15.tar.gz\": {\n        \"sha256\": \"b866657b9029ec4db1d164f70b25ba17d23188fec75c5e2bc0d70280d8b5cf9d\",\n        \"size\": 165238269\n    },\n    \"NoScenario_Town12_Route9036_Weather9.tar.gz\": {\n        \"sha256\": \"7484909440aae7c81d5390810be7040931eb6abf0a03bdc0c5e28b7c52e8fb1e\",\n        \"size\": 106123002\n    },\n    \"NoScenario_Town12_Route9057_Weather12.tar.gz\": {\n        \"sha256\": \"81b9cbc9a0673245d4f7322aeca9a2754bc613db6dc08b08e33415a5cf1cf041\",\n        \"size\": 156780866\n    },\n    \"NoScenario_Town12_Route9064_Weather19.tar.gz\": {\n        \"sha256\": \"83be1890d2fe2409b5b11aeba68460562f435c098e51707880369bb090014098\",\n        \"size\": 171081238\n    },\n    \"NoScenario_Town12_Route9075_Weather3.tar.gz\": {\n        \"sha256\": \"8009b6499060ce9a0f53dc2fe67a3271473bd36bd3d7c6e2f46bf2e8e0d9e557\",\n        \"size\": 378799033\n    },\n    \"NoScenario_Town12_Route9076_Weather5.tar.gz\": {\n        \"sha256\": \"db9a46ced9733ae6f94b42b1d26bc701fdaee396715cf926f817c15932d18e59\",\n        \"size\": 180518924\n    },\n    \"NoScenario_Town12_Route9078_Weather7.tar.gz\": {\n        \"sha256\": \"4d579e99d33caa18c616a3d0d0c299ab87442c31e6d8f1baa7d8f09247532f2f\",\n        \"size\": 213035380\n    },\n    \"NoScenario_Town12_Route9086_Weather15.tar.gz\": {\n        \"sha256\": \"0de9f9d2edd3e63e279e5eb8cdfce4640eb3f5e3d0e7a0e6630900bc92b5c927\",\n        \"size\": 137849769\n    },\n    \"NoScenario_Town12_Route9097_Weather0.tar.gz\": {\n        \"sha256\": \"fafd69c7b7f668b3f2ba323a7183eea942f3528247db377755bd9c52b1fce7dd\",\n        \"size\": 245430504\n    },\n    \"NoScenario_Town12_Route9109_Weather12.tar.gz\": {\n        \"sha256\": \"f9d74a42699b185b0af360eb7e8c96978a32e4c4bc74e9b016410e5ca077a996\",\n        \"size\": 203179018\n    },\n    \"NoScenario_Town12_Route9113_Weather8.tar.gz\": {\n        \"sha256\": \"9d46da9adcc0e73acad44c8963dd39254def5219ce672e27e432313f8c08b9f0\",\n        \"size\": 175462194\n    },\n    \"NoScenario_Town12_Route9129_Weather6.tar.gz\": {\n        \"sha256\": \"441de3197777664ae75d2f6c4d715c0ac489aad71ef0c3d6ee32514390d694b2\",\n        \"size\": 139171836\n    },\n    \"NoScenario_Town12_Route9143_Weather20.tar.gz\": {\n        \"sha256\": \"cd181c7fba76d6f411c0c63d5b6f5e8bf7a66664236222a5d6066725210c6bec\",\n        \"size\": 125020996\n    },\n    \"NoScenario_Town12_Route9157_Weather8.tar.gz\": {\n        \"sha256\": \"36073e729071537051fb4e064c527d42da80df696ddfe9c5f94a5f36642ed89f\",\n        \"size\": 166381107\n    },\n    \"NoScenario_Town12_Route9159_Weather10.tar.gz\": {\n        \"sha256\": \"edc7f7c3798d7478e87bebaf474ad34f5b1eb26f603359fec141c1f44c66ef04\",\n        \"size\": 147654837\n    },\n    \"NoScenario_Town12_Route9215_Weather14.tar.gz\": {\n        \"sha256\": \"570b2f2133eb67b496efc4187ebcf64ad58c7ba1fb21b52bd40714730c6ff582\",\n        \"size\": 123154037\n    },\n    \"NoScenario_Town12_Route9218_Weather9.tar.gz\": {\n        \"sha256\": \"10dfded00761fc886f1e9fa99169245dff03b94f183b2dc0cb841a0959fa714b\",\n        \"size\": 162367519\n    },\n    \"NoScenario_Town12_Route9225_Weather23.tar.gz\": {\n        \"sha256\": \"2f949809f224381a5ac3e0c45f73403ec8fdf3e15e09e70136fb936c4480731c\",\n        \"size\": 246576031\n    },\n    \"NoScenario_Town12_Route9239_Weather12.tar.gz\": {\n        \"sha256\": \"ccd8f0d299e03333232333e189fcd114cbc34f07a1401608f16a35496bd97880\",\n        \"size\": 153773709\n    },\n    \"NoScenario_Town12_Route9257_Weather3.tar.gz\": {\n        \"sha256\": \"acfef7fb9aa7d8f1f62b7b4bfc9d7e9b24d008675ccd121c4ac11e6aaf19b6fe\",\n        \"size\": 138686780\n    },\n    \"NoScenario_Town12_Route9267_Weather14.tar.gz\": {\n        \"sha256\": \"763396f37f17daf2c9335ba502b50964052fb3ced593d59f63b50136420c1689\",\n        \"size\": 200418869\n    },\n    \"NoScenario_Town12_Route9288_Weather9.tar.gz\": {\n        \"sha256\": \"2ea33a0101b52c77b8c1913466a89ad85d18ca27040485b887bc3d541c749496\",\n        \"size\": 117316732\n    },\n    \"NoScenario_Town12_Route9290_Weather11.tar.gz\": {\n        \"sha256\": \"5dc9b5a506fc66b8078a840e57f6dd29b1c5c6f3f6b4cabe739a59731a6456cf\",\n        \"size\": 155251992\n    },\n    \"NoScenario_Town12_Route9294_Weather15.tar.gz\": {\n        \"sha256\": \"12a1200d5d1d8f656903683a9b4c98c8dc36290fa66265b844fffa80c4962b4e\",\n        \"size\": 288680144\n    },\n    \"NoScenario_Town12_Route9298_Weather19.tar.gz\": {\n        \"sha256\": \"c2127cffdc435893fd2d56fe95db1253b4d5f0cc2c47fb8f01941e549f4e9fea\",\n        \"size\": 207484472\n    },\n    \"NoScenario_Town12_Route9306_Weather1.tar.gz\": {\n        \"sha256\": \"b989db0a450ff5cdb10c9489e863cce0c309dec2650709b446736732f31b1170\",\n        \"size\": 179830370\n    },\n    \"NoScenario_Town12_Route9314_Weather9.tar.gz\": {\n        \"sha256\": \"390b8220591f142430f489cc16dee52449b6948990bb67cb7ba4fc6af002f38a\",\n        \"size\": 191366063\n    },\n    \"NoScenario_Town12_Route9318_Weather13.tar.gz\": {\n        \"sha256\": \"461a498df5d69d5d9f067d80d48306effd7c1c633f63b1ed238c454c472e4788\",\n        \"size\": 161476393\n    },\n    \"NoScenario_Town12_Route9329_Weather23.tar.gz\": {\n        \"sha256\": \"b43ac89e930757915cd2898669c90361096c74ba2f9038990d1ea6395c7215c5\",\n        \"size\": 133281209\n    },\n    \"NoScenario_Town12_Route9337_Weather6.tar.gz\": {\n        \"sha256\": \"494272462a17be50e699f442591498c577e095da50efced665bf26570fbbd3ab\",\n        \"size\": 195280495\n    },\n    \"NoScenario_Town12_Route9350_Weather19.tar.gz\": {\n        \"sha256\": \"4d0696da1f233b71b9a49a91719e2c8a467d5111b86e717cc9d1cf4278e35d1a\",\n        \"size\": 189863283\n    },\n    \"NoScenario_Town12_Route9353_Weather22.tar.gz\": {\n        \"sha256\": \"02df207f9b9e6ffb164b2f94fc497c4f0359b2b85ef9a6aedccfd679dce767a4\",\n        \"size\": 162643731\n    },\n    \"NoScenario_Town12_Route9356_Weather25.tar.gz\": {\n        \"sha256\": \"50e8290de25e4ec428804a3f99144f60630c65a672f8582659fd446628fd9099\",\n        \"size\": 129174705\n    },\n    \"NoScenario_Town12_Route9361_Weather3.tar.gz\": {\n        \"sha256\": \"2be97bd4be5bfeaed7c06de0bd875aa3aa9b541d38fa15e514c4b1af72f0153f\",\n        \"size\": 155411512\n    },\n    \"NoScenario_Town12_Route9381_Weather23.tar.gz\": {\n        \"sha256\": \"e1414bc9552c8524f2acffc2693e92184f3b05219de12f485a976973edb36a77\",\n        \"size\": 114126559\n    },\n    \"NoScenario_Town12_Route9406_Weather23.tar.gz\": {\n        \"sha256\": \"a571420930c32329ddd273199586f573d50628f65fdc643bbfbf602dda03d139\",\n        \"size\": 348907103\n    },\n    \"NoScenario_Town12_Route9422_Weather13.tar.gz\": {\n        \"sha256\": \"5795c442f985caba256aa5b5f2d1ae1f7de5942b60f985fef3172aaf01c47c03\",\n        \"size\": 202381523\n    },\n    \"NoScenario_Town12_Route9425_Weather8.tar.gz\": {\n        \"sha256\": \"f1e0659415b772be0eebdf3cb1de6021fd7045bcb6d7c5597d31658ec30345ac\",\n        \"size\": 160324056\n    },\n    \"NoScenario_Town12_Route9611_Weather20.tar.gz\": {\n        \"sha256\": \"e4fc74d87b4a93d53d6b365015caeb003a6a5325078d1c1897fa3428d3f04ed4\",\n        \"size\": 660146995\n    },\n    \"NoScenario_Town12_Route9628_Weather11.tar.gz\": {\n        \"sha256\": \"be612d5f6b749403e7cd21b2bfd840fd73cfbcc29dd6d5748ba063d52436e884\",\n        \"size\": 716659553\n    },\n    \"NoScenario_Town12_Route9658_Weather15.tar.gz\": {\n        \"sha256\": \"dc028a56a0393a372bf286d2a4edac5d0caed52c25680498fb91bd291f810c79\",\n        \"size\": 138274673\n    },\n    \"NoScenario_Town12_Route9680_Weather11.tar.gz\": {\n        \"sha256\": \"a260ab58adfd897d5dedf0dae660b19fe02580837f7abc3eec768b446f3c5af7\",\n        \"size\": 243781797\n    },\n    \"NoScenario_Town12_Route9731_Weather10.tar.gz\": {\n        \"sha256\": \"2745bd5ebfc1d1675d0af043965c0a249d0399c508ea574e2e72edbd39dc2468\",\n        \"size\": 830605103\n    },\n    \"NoScenario_Town12_Route9734_Weather13.tar.gz\": {\n        \"sha256\": \"100e5b5d2cbcee6f0a22c651492da5611a466a4d34782cbac5af77d302a8974a\",\n        \"size\": 293843438\n    },\n    \"NoScenario_Town13_Route31368_Weather6.tar.gz\": {\n        \"sha256\": \"6ddc1c4b819025c7e0891d0a5a6cbeeefc01c51660c287a30f2f84102e13bab3\",\n        \"size\": 144986903\n    },\n    \"NoScenario_Town13_Route31916_Weather1.tar.gz\": {\n        \"sha256\": \"bbdd494ed68bbc55dbc930d62f57a22737005582cc1d5c20e8a037fb623a361a\",\n        \"size\": 346354021\n    },\n    \"NoScenario_Town13_Route31940_Weather2.tar.gz\": {\n        \"sha256\": \"af3407352cbdcf37201e766191532817bf2c49aa4c523b5217aff6632f7e24b2\",\n        \"size\": 295514742\n    },\n    \"NoScenario_Town13_Route34478_Weather11.tar.gz\": {\n        \"sha256\": \"689fd64bea6a75f9e7a27b2fb6bf6f1828828e1192b346b68d7788cc543227f4\",\n        \"size\": 91100551\n    },\n    \"NoScenario_Town13_Route34656_Weather5.tar.gz\": {\n        \"sha256\": \"82d4d32b61da4065bd34da80d5bbc38654edf4fc563b8118227f4c79af7d79f4\",\n        \"size\": 133002266\n    },\n    \"NoScenario_Town13_Route34686_Weather12.tar.gz\": {\n        \"sha256\": \"1b153856c3b1e7ddb3f96172a12f43a30a94668f73fc133f6517750d71327fcf\",\n        \"size\": 95012001\n    },\n    \"NoScenario_Town13_Route3485_Weather13.tar.gz\": {\n        \"sha256\": \"05fe8ae53e01ae063210fb1edba910a8a4a73f0fcfb30782650225262c85a6e3\",\n        \"size\": 116133119\n    },\n    \"NoScenario_Town13_Route38840_Weather6.tar.gz\": {\n        \"sha256\": \"4f51b2b56a5f5c68d18bb95821f2585cdb4f2ce11afd1ca82ce8564441a17106\",\n        \"size\": 208888096\n    },\n    \"NoScenario_Town13_Route38841_Weather6.tar.gz\": {\n        \"sha256\": \"7d2082da0eeabcb494886763d54596b29952522faca77b1125e3ac526913d14b\",\n        \"size\": 207207642\n    },\n    \"NoScenario_Town13_Route38869_Weather7.tar.gz\": {\n        \"sha256\": \"6fdf6c3c5d6d4a89d3b0d49e55582abc33b0211046aaeecc721efe8c96cec1a1\",\n        \"size\": 230268896\n    },\n    \"NoScenario_Town13_Route38880_Weather7.tar.gz\": {\n        \"sha256\": \"713997447c7a0da2d907a2b3d30be3b4919e0ac23ff909360f4c7d739a0dac9c\",\n        \"size\": 230011496\n    },\n    \"NoScenario_Town13_Route38881_Weather7.tar.gz\": {\n        \"sha256\": \"9542b668edae41f4b02389f415eb7154f90b504deca3dfc969b23c34752f4ad0\",\n        \"size\": 219006539\n    },\n    \"NoScenario_Town13_Route39200_Weather15.tar.gz\": {\n        \"sha256\": \"579ffbf3de972dfbe647afb26310301ac487faa6b71878f8d42800a001b21243\",\n        \"size\": 196949643\n    },\n    \"NoScenario_Town13_Route39201_Weather15.tar.gz\": {\n        \"sha256\": \"ae3562321ab194eb730a26ed98904693b0dea857f002099bb2c6771a0f15f254\",\n        \"size\": 188938304\n    },\n    \"NoScenario_Town13_Route39240_Weather18.tar.gz\": {\n        \"sha256\": \"c0f9cb2d9a5e7006c2369fa7bc0edb45bd0481864025b9a673df4c6eb0a013dc\",\n        \"size\": 212987322\n    },\n    \"NoScenario_Town13_Route39241_Weather18.tar.gz\": {\n        \"sha256\": \"11a41ef3bfd6ba59556eb4fb9303f792d889213d15a6a2080171bbf923acb6ec\",\n        \"size\": 207275862\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route2738_Weather1.tar.gz\": {\n        \"sha256\": \"bae478eee4962edbfee32650d0318a1e1eb24f389826d384f4dc80b37e8d5272\",\n        \"size\": 147613188\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route2853_Weather1.tar.gz\": {\n        \"sha256\": \"3304aab9dd1c1b7d16897f4c07166ad60f888f809765fa92f3e64277a19c186c\",\n        \"size\": 171010457\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route2906_Weather9.tar.gz\": {\n        \"sha256\": \"724f58894c322987a7e79e278f877d03248c44a704536f6423af4a1ff0ce21d7\",\n        \"size\": 121857031\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route2907_Weather10.tar.gz\": {\n        \"sha256\": \"0974f75d17a8f13ccde06629e0f7e0377b64fbef760ca4ccbb72b557c2fd2f67\",\n        \"size\": 152116589\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route2995_Weather6.tar.gz\": {\n        \"sha256\": \"a44705de32079d34aefa5a134d5d5b565244994bd5698d058b0c87f53eade90d\",\n        \"size\": 119113602\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33612_Weather21.tar.gz\": {\n        \"sha256\": \"6a3b74680968fe58e75b7f2ef6b3c72d76583294e8faeb5e3e34f01ad82a0802\",\n        \"size\": 79611848\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33619_Weather2.tar.gz\": {\n        \"sha256\": \"f8350bd7989ab2d9081a0a02e1ae913d6a24db54d01c4c48d8c41f20854ea43a\",\n        \"size\": 197295596\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33620_Weather3.tar.gz\": {\n        \"sha256\": \"735d02db2aeebfcf18490ca15201c28a45ed61379b2e38fe5a1a1c1d79ee4703\",\n        \"size\": 276629197\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33622_Weather6.tar.gz\": {\n        \"sha256\": \"7da9de2e1df173ba9e0201d8f3d6c2a2385e2dfa4266d696d50f8603c0ff2871\",\n        \"size\": 135342708\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33624_Weather8.tar.gz\": {\n        \"sha256\": \"0108b36d07d69aef25a4db6f15e70dab4f831e2ea1d3297a40bc83e3f1ef5302\",\n        \"size\": 238954010\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33629_Weather13.tar.gz\": {\n        \"sha256\": \"0438d7abfd1570187f1bc2b210618591cc309fef70aca4b7ca7c703566f86375\",\n        \"size\": 498187133\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33630_Weather14.tar.gz\": {\n        \"sha256\": \"24a3a6786cb4117a7c2e72b1d59cf8f44e6ebcc7364edc28ce4cb4c255674b83\",\n        \"size\": 142802511\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33631_Weather15.tar.gz\": {\n        \"sha256\": \"76f2541286e55f889c9f3b91c0eba4980796790e7e6922dbf90cb966a0feb5cc\",\n        \"size\": 139673400\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33632_Weather18.tar.gz\": {\n        \"sha256\": \"309d66110035142dc4afc8f3b505d4ab32016df21ee2b07cb8f700cfc06697bd\",\n        \"size\": 141472911\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33633_Weather19.tar.gz\": {\n        \"sha256\": \"4b718b3c7a4f1e45092265b0ab39a069ef6401f82b802afda544144be7bf939f\",\n        \"size\": 128356180\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33635_Weather21.tar.gz\": {\n        \"sha256\": \"be0463fc6c5d443170bc21f5eb73ceccfb1c0aa5eacc263ebb8a55668bb06813\",\n        \"size\": 144180535\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33641_Weather1.tar.gz\": {\n        \"sha256\": \"685f9fd49d0e358802f711a59b2bf664b589497d5687f2ada983420ce6fafe1b\",\n        \"size\": 187610504\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33642_Weather2.tar.gz\": {\n        \"sha256\": \"dd2423a1af4851b55dfb725d011d9cc88fa9b187138fff5119a0c53e8ecdc986\",\n        \"size\": 274142098\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33643_Weather3.tar.gz\": {\n        \"sha256\": \"ac69ae61a2de60f890cb7dbb7eec52b8bc8421fcbb6737ff1b788f6b12f9ac4c\",\n        \"size\": 177914736\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33644_Weather5.tar.gz\": {\n        \"sha256\": \"e6fa553d82a745ca19acd6fe5d05fc59eb0bd4dcc587bd51de87cebf695071f8\",\n        \"size\": 123234140\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33647_Weather8.tar.gz\": {\n        \"sha256\": \"55f4589de5ba8f9b3e30d7fd040b3803016ae35a3f9f8886c98e6e84a4bee8be\",\n        \"size\": 164401408\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33650_Weather11.tar.gz\": {\n        \"sha256\": \"60b54723c97290c78d9d1bb36ef837d7e097c4528c7daea4a366d27f6562b9fa\",\n        \"size\": 137479188\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33658_Weather21.tar.gz\": {\n        \"sha256\": \"3f063d798c64bc8518537af0066a2135f3d9d4e666f23fdfe906c9a297f90fc6\",\n        \"size\": 123125020\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33660_Weather23.tar.gz\": {\n        \"sha256\": \"2833753b8a65b9d3cf6f5a23c8224e820861b6079a23a190bfe6c98b4503e563\",\n        \"size\": 129199202\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33663_Weather0.tar.gz\": {\n        \"sha256\": \"5be7189bc9a5e6536d4fc0a286e4b6c41a88c64d300fdac869542fda186c4625\",\n        \"size\": 152342641\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33665_Weather2.tar.gz\": {\n        \"sha256\": \"2449e74b20dad490abcdc686275c4593aab53ba7744e7bb0fcb610dd7b15e0de\",\n        \"size\": 164486868\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33672_Weather10.tar.gz\": {\n        \"sha256\": \"f37f60a5232cb7469f719eb7c4270b3d7aae19d4c308be7c57ff4f2a6586e9b0\",\n        \"size\": 610962347\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33673_Weather11.tar.gz\": {\n        \"sha256\": \"df5a05972bf08f5fde08f1fea0c1d2e1e9030fb5783fdf4fb1680e441ec01fba\",\n        \"size\": 284255414\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33674_Weather12.tar.gz\": {\n        \"sha256\": \"57565a9efe88de9234128a6df6730a83fe752ce92744ed222ed9a8dbd48a0ae3\",\n        \"size\": 141700638\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33678_Weather18.tar.gz\": {\n        \"sha256\": \"14dc6263e82c43672c31326f838c7f35cbb6130fdc145a8287ba7f3e1238bc91\",\n        \"size\": 159131787\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33684_Weather25.tar.gz\": {\n        \"sha256\": \"daff4345095809b119070e9f2008a114345a9e09924792873b7781a0d2abca82\",\n        \"size\": 140605164\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33686_Weather0.tar.gz\": {\n        \"sha256\": \"afbbf0f27211e244d1abd53504f4338cd85584d5096bc1ac7ea176926b5158a5\",\n        \"size\": 174512704\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33697_Weather12.tar.gz\": {\n        \"sha256\": \"57f9a532d75d07088fe07715d248d36aa62be3d6ccf1b427485043b85f97d28c\",\n        \"size\": 121913829\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33705_Weather22.tar.gz\": {\n        \"sha256\": \"13e96d5268de31619d1418a4ce7b244796a89a0231f125c30f332fb40b5c204e\",\n        \"size\": 146288581\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33707_Weather25.tar.gz\": {\n        \"sha256\": \"dd0bbfaf41b54fc684ab0d52722fe0223727028f8ab2865cb48055aff4982d25\",\n        \"size\": 141026906\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33710_Weather1.tar.gz\": {\n        \"sha256\": \"de18e8e86ff295ba7fb18ae206ca64320995338b400d38431f13358d0d9e135b\",\n        \"size\": 159164627\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33713_Weather5.tar.gz\": {\n        \"sha256\": \"d20352c117d5811ef37245566dc662cf35c242919ad5530cc3bcde1363808471\",\n        \"size\": 140459289\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33714_Weather6.tar.gz\": {\n        \"sha256\": \"f28fb83d66d0c91f6bf31e80d24e19b3e2da21a2e4a0dcef2ff862fc0fdf1d4b\",\n        \"size\": 149546916\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33715_Weather7.tar.gz\": {\n        \"sha256\": \"91c0090554d6428ae160b96dca7eb7647c896f71ade49e36881af3acb34299ec\",\n        \"size\": 236474489\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33716_Weather8.tar.gz\": {\n        \"sha256\": \"04debc07bd6efb7aa59ff801e3f73e141d881062396249a2dd417c838b04ceb9\",\n        \"size\": 125720638\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33726_Weather20.tar.gz\": {\n        \"sha256\": \"9c47b7773e06479d8159b809a86dc8ccdf277920e482da6f6287a49bca74aa5d\",\n        \"size\": 111846562\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33730_Weather25.tar.gz\": {\n        \"sha256\": \"4132f46f4a2a6400382f0959fb41e4f06e77ff9d6a0f7658d2dfdf428d734b7c\",\n        \"size\": 133572448\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33732_Weather0.tar.gz\": {\n        \"sha256\": \"c37466376c645e5f8a19611f46bd6623b1fd2d025c3f2973a7c4afcf178ce8c0\",\n        \"size\": 178767301\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33735_Weather3.tar.gz\": {\n        \"sha256\": \"0c4b759063ff17249cd42e5469dd7b0bd9c0da8d8d584c942c310ebd6dfbb6b2\",\n        \"size\": 172868510\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33740_Weather9.tar.gz\": {\n        \"sha256\": \"0a80f14e29e203c5ff3c9a9c0d5f42d60990077cb2df45a6d9c1da5f55764771\",\n        \"size\": 119611105\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33741_Weather10.tar.gz\": {\n        \"sha256\": \"5c15ff1f50bb7edc8e963efd374cd5c0b7047b10cf096402b2af695d33993705\",\n        \"size\": 149189168\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33742_Weather11.tar.gz\": {\n        \"sha256\": \"6c736f8b90373fa9e77fc3a997b0715374520996e7d84da78b32628b481e3728\",\n        \"size\": 465286062\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33747_Weather18.tar.gz\": {\n        \"sha256\": \"d756afc48f2b7e408ad67806067a8ca476c070ae10ae84bdb20b4d643ae8e7ac\",\n        \"size\": 449154910\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33749_Weather20.tar.gz\": {\n        \"sha256\": \"7f89086ce8a78ded730f37ea1f30cb2a1f3bd317a5bec1661adb3b8bb87f60df\",\n        \"size\": 79449897\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33750_Weather21.tar.gz\": {\n        \"sha256\": \"c78c21a3450a99c0ee3940154ff3ff8dd8999ebe93b0c17a38868860887d8772\",\n        \"size\": 136466927\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33751_Weather22.tar.gz\": {\n        \"sha256\": \"519bcd5cdced679d87752f39ad1ff81086dc2626fa204d2d7acfa750525f8316\",\n        \"size\": 149668109\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33756_Weather1.tar.gz\": {\n        \"sha256\": \"2fc183387e6102e9ec05ba369c95f178e8afeff8282a1ec1301da79f746e9d09\",\n        \"size\": 188744902\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33757_Weather2.tar.gz\": {\n        \"sha256\": \"a6c181881ff91b5c987859d54328ea6f8f798730e7dafe793a165e4495226cf8\",\n        \"size\": 109734686\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33760_Weather6.tar.gz\": {\n        \"sha256\": \"6214af4fbe48260e24ba4f045b3d1ba64809156b9d508b19771c2b8bf9f5c421\",\n        \"size\": 149323405\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33761_Weather7.tar.gz\": {\n        \"sha256\": \"fb77376613c71ad8c15338b107d0330a4e86bf9204f55b52ab788587d0d891f4\",\n        \"size\": 156478418\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33763_Weather9.tar.gz\": {\n        \"sha256\": \"543364d792b7a8295466a5557ab4cea8364a24a1bebf45a0428ef14d37e70407\",\n        \"size\": 93996211\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33766_Weather12.tar.gz\": {\n        \"sha256\": \"28a82fe08b1e366810a3e6a6c5ce4be0cb6722dfc198e0b06c1e27cd28e8ad5b\",\n        \"size\": 113201766\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33767_Weather13.tar.gz\": {\n        \"sha256\": \"9952fcbfc825039f1d0c5ed3105262f9035c151306f6899edb2d13903b289c19\",\n        \"size\": 120684292\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33768_Weather14.tar.gz\": {\n        \"sha256\": \"27c062bec5fb427bdbf5cf95a719bf560d6bcb1cada62fa4a3deec902c20c1e0\",\n        \"size\": 213419423\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33771_Weather19.tar.gz\": {\n        \"sha256\": \"a4262b51172726aa51af39e9f3d828319d54a48e2bd97dc0005dc8c3b93dc927\",\n        \"size\": 125738995\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33774_Weather22.tar.gz\": {\n        \"sha256\": \"e01f4016f90ce0096d9b428f8b84a92bba797cb39289274120693627971d28a5\",\n        \"size\": 161494984\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33775_Weather23.tar.gz\": {\n        \"sha256\": \"eb362d0b4830a72b92585016f5b232554106cfdb0f2a02b19c46a8f95b87ae8c\",\n        \"size\": 147175764\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33777_Weather26.tar.gz\": {\n        \"sha256\": \"8de30db7b93dd8db65145eaa03417aed3d074f716c839f483b58832f8ed18fe7\",\n        \"size\": 186324942\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33778_Weather0.tar.gz\": {\n        \"sha256\": \"da47d950f36d93356746cd800432675702d4c33d6af20e0b7cf7c3abbcb6451d\",\n        \"size\": 216786181\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33779_Weather1.tar.gz\": {\n        \"sha256\": \"639c8885ebd2ee51bdd361f6ec0053b994a2bf6c9daa4c342c050d6953ae6e86\",\n        \"size\": 173950154\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33790_Weather13.tar.gz\": {\n        \"sha256\": \"bbeac7b76b7e5c65e930a14e6bda22ce666e958fb21761e59c82cc690f03da50\",\n        \"size\": 458989583\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33794_Weather19.tar.gz\": {\n        \"sha256\": \"5adda70e7876ce32a8b54e4bfa6eff509c9c7a27770c14f538f6cc96e41b7b62\",\n        \"size\": 158983689\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33796_Weather21.tar.gz\": {\n        \"sha256\": \"4dbddc9b51a46a718e6b9614eb5d1815fb0d84d6a51868f926385507aa04880c\",\n        \"size\": 118125146\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33797_Weather22.tar.gz\": {\n        \"sha256\": \"6ff401aab900271e731ef4cc1269084489b54a6b1cf936707016b7b2f11dd4b9\",\n        \"size\": 107713225\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33804_Weather3.tar.gz\": {\n        \"sha256\": \"db8d47aa74cce6562dedf7e57508ffce025ffd8abd129bdb871a6963b2a4ac6f\",\n        \"size\": 162015936\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33806_Weather6.tar.gz\": {\n        \"sha256\": \"778ed547e670fa6a0da860fbb169f8663c074ec6f9485b1b9952ca1ec0562a4b\",\n        \"size\": 133121674\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33807_Weather7.tar.gz\": {\n        \"sha256\": \"89b171c853df29fb3ac9edaf0099b839b3f71c30988ae9e376221290b0f28526\",\n        \"size\": 209356698\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33811_Weather11.tar.gz\": {\n        \"sha256\": \"6ff82c2a522e6aa5e1e9e5cd6a2bab2258d135fbf946e1e7cce4a070a587ffbd\",\n        \"size\": 169080617\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33817_Weather19.tar.gz\": {\n        \"sha256\": \"bca54521c60bdc60a057be62f3aef1bca57f286e42d24bded0bb596102e93be7\",\n        \"size\": 120114095\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33819_Weather21.tar.gz\": {\n        \"sha256\": \"5c7034ef46962ca2b1820932ab2c0be6b8471755b023dde60d45a079e6d0dab9\",\n        \"size\": 103135544\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33820_Weather22.tar.gz\": {\n        \"sha256\": \"01f239e6d211090ef97437f4ded837534dc377a49e2c3f1a5e3a6d936fa4aadb\",\n        \"size\": 165507616\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33826_Weather2.tar.gz\": {\n        \"sha256\": \"0c94e50d9fe206eb05e034744d2e8e2940e9424ef01708e26917250f136e38f1\",\n        \"size\": 122503947\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33827_Weather3.tar.gz\": {\n        \"sha256\": \"8d984d57d9dce5e666a0ea94f871e6af33dc92eeefd88079c96d11187518f3ec\",\n        \"size\": 106458940\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33841_Weather20.tar.gz\": {\n        \"sha256\": \"00102ded5e108c226d2bb2e6ac1c48aa081f44722f1d981bcfec1bbb633d8c63\",\n        \"size\": 161162405\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33844_Weather23.tar.gz\": {\n        \"sha256\": \"12d7c4dffbed02c37ea2859d67c44fafb203f240d1db4ac3846daf8cc58b5d38\",\n        \"size\": 357579855\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33847_Weather0.tar.gz\": {\n        \"sha256\": \"82487ace5b8ece3311c196d8cdb5a0ba556e577d3e12f9cdfa663b7f0e89a276\",\n        \"size\": 158586670\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33852_Weather6.tar.gz\": {\n        \"sha256\": \"4b0de83347b377c425cade00d4b4a1c66f7d3064f836de5bf71f8811fcf4533e\",\n        \"size\": 146946843\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33855_Weather9.tar.gz\": {\n        \"sha256\": \"3ab2b7d466d789abcdd03cb1639dde8b819125f188d2d2070da6c6a974895029\",\n        \"size\": 135557848\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33858_Weather12.tar.gz\": {\n        \"sha256\": \"09bee063f0524f7681526b1c9d10774805bac0dc9396f412a3aa1aa5a8b5f4a0\",\n        \"size\": 191428680\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33859_Weather13.tar.gz\": {\n        \"sha256\": \"b6c03e5d25857883c25f5ccf7356e6e0ab81b00f6a2b345f1cb718ca53ac8ed4\",\n        \"size\": 130408599\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33861_Weather15.tar.gz\": {\n        \"sha256\": \"169738f93ec9d367392ee476549ee8ff45b5d427cb5247b01a9a66d402c88855\",\n        \"size\": 140223286\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33864_Weather20.tar.gz\": {\n        \"sha256\": \"248a3b23ad7491ec4bd8609687e816b2a2e3c9a1b2e1357decfe852f96178cfb\",\n        \"size\": 157415804\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33865_Weather21.tar.gz\": {\n        \"sha256\": \"d8066b917de8497a7256c0db93e567ff28f7f6d1f1c877f50c7cfb5818f5d8b7\",\n        \"size\": 240455817\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33866_Weather22.tar.gz\": {\n        \"sha256\": \"360bf7d0181322adc48ebc59a2884bc8fa787062e2904856c77212bb3d8623ab\",\n        \"size\": 134876079\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33869_Weather26.tar.gz\": {\n        \"sha256\": \"909137d03a6b5ad796edcfc0ec944f6ee79539adfc72450fbe9e6c3d8316655a\",\n        \"size\": 285170908\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33870_Weather0.tar.gz\": {\n        \"sha256\": \"2ec1e5534c2230b429a0c650ae25ea69a56d40d612d2bb30b128b86758dca855\",\n        \"size\": 181609531\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33877_Weather8.tar.gz\": {\n        \"sha256\": \"c1826ab17f36bb09f3e980e09545c7d9efbd073d3d4475fd942b237099669359\",\n        \"size\": 409092222\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33880_Weather11.tar.gz\": {\n        \"sha256\": \"df73062ba5f728ed7775f666d14bbd0fd25ff9816383ea670dca22674e0a9d47\",\n        \"size\": 128733654\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33882_Weather13.tar.gz\": {\n        \"sha256\": \"553de27517c2ba9681a3073da5df2912cb4f26c193f75af676a1994638f93659\",\n        \"size\": 116020619\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33883_Weather14.tar.gz\": {\n        \"sha256\": \"9cd53efdb9af6169ed183e31ed03f0e7a92d9c859201c47b8837071eaf5dda0a\",\n        \"size\": 135410746\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33888_Weather21.tar.gz\": {\n        \"sha256\": \"776b10858dca1a49d97f3772b53a105bb97adade9e3eec187828683ae6cac6ab\",\n        \"size\": 160247711\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33890_Weather23.tar.gz\": {\n        \"sha256\": \"17459762201b1c8e1337cbd670c30cbbee31605e42441597b43269d4fe50d855\",\n        \"size\": 120291006\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33893_Weather0.tar.gz\": {\n        \"sha256\": \"dffebbf56f3f91846fa2f45201cc0901cd009eb86f8a922fe124f639c36ff3c3\",\n        \"size\": 137736489\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33898_Weather6.tar.gz\": {\n        \"sha256\": \"aada80e5cbc6bcbcd42bd34c11a9ee7199a862ba04ba90c107d12ce0fd271235\",\n        \"size\": 158453537\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33902_Weather10.tar.gz\": {\n        \"sha256\": \"c10666db3a6c3b15457ac2440255cc85a637c27364d4e2fb99578a45347a519f\",\n        \"size\": 100865916\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33907_Weather15.tar.gz\": {\n        \"sha256\": \"13d25ef974a366e1335e36e92a83f549b9633e2d10cb433595c0a7b3d0c34045\",\n        \"size\": 125228693\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33909_Weather19.tar.gz\": {\n        \"sha256\": \"7390462f9344cf09bf41aae16629cc7c17e07f9defdbd86a3bf15e0312ff5013\",\n        \"size\": 196753438\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33912_Weather22.tar.gz\": {\n        \"sha256\": \"19106ecb399a3bdb1970dbbc8c1834c91848a5cfeda2cc69843a55e1605188ed\",\n        \"size\": 441877333\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33913_Weather23.tar.gz\": {\n        \"sha256\": \"e27cfe6362562dd20bb9e0d68095fafeab0da94b0f00d5353dbe5e69d956fe36\",\n        \"size\": 111899241\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33928_Weather13.tar.gz\": {\n        \"sha256\": \"59e37f8bf1baf2dd67bd5a5cd2030d27a37297f759bb7f5e945c66bcf236a4d7\",\n        \"size\": 124458523\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33930_Weather15.tar.gz\": {\n        \"sha256\": \"29dc445db77199dca337420ccaa9cfe3f20894d1db689920bf9178168d0dc123\",\n        \"size\": 138749146\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33934_Weather21.tar.gz\": {\n        \"sha256\": \"fb7500478bb6bf89d5138a0776ceca2442e8d40b663c019e3cf67957e6f3e5f9\",\n        \"size\": 156674782\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33935_Weather22.tar.gz\": {\n        \"sha256\": \"867d3dc92bf8513a10cd6c2fb515316eee374881d980f36232217a69f537c60a\",\n        \"size\": 123408784\n    },\n    \"NonSignalizedJunctionLeftTurnEnterFlow_Town13_Route33936_Weather23.tar.gz\": {\n        \"sha256\": \"77f37e3caeed068e9221d428043f333f0009867f3c419726f248e4d179c74fa8\",\n        \"size\": 122722791\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6924_Weather11.tar.gz\": {\n        \"sha256\": \"00699ad3c9cabae46481ad3d12d33911aaac6c03524e4adf1a80ce5dfc395860\",\n        \"size\": 184114355\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6929_Weather8.tar.gz\": {\n        \"sha256\": \"b6905741b7039cee72d7d09930eef9a7addf658465dc61656c5ed2caa575927a\",\n        \"size\": 214884949\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6930_Weather9.tar.gz\": {\n        \"sha256\": \"c346458d6286b9b5126e73607ac26bf7aa9c5d28d9f7690430917f99d77a5f7e\",\n        \"size\": 203465687\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6943_Weather3.tar.gz\": {\n        \"sha256\": \"1018595fae51346ad353cb189c9291e5dd97ea805d0f1a8aab406cc82b6c57a0\",\n        \"size\": 225399897\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6947_Weather8.tar.gz\": {\n        \"sha256\": \"a132357b1e7e0250d5c225c7fe7aa0dedd2b6c2c9409f7851434f85bac7657ed\",\n        \"size\": 215026528\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6949_Weather10.tar.gz\": {\n        \"sha256\": \"3af167c6d0477923a697327bc4e3a85a36174cf698e34f8615f9aeb03408f5d0\",\n        \"size\": 181802233\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6953_Weather14.tar.gz\": {\n        \"sha256\": \"ab21d478d7395a7dc5f36662f0256610ef5d4c3c811aa69057a2c57ebe7a0902\",\n        \"size\": 188123978\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6961_Weather22.tar.gz\": {\n        \"sha256\": \"6e3511485c54d5b1388fa8a109ad8ab36537e3bc1f940bd0463c6899f3cfbc69\",\n        \"size\": 227524154\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6965_Weather0.tar.gz\": {\n        \"sha256\": \"7fa252ed93beb94cb54e2d616cdf1e90e444737400218ae503e3110c77508f08\",\n        \"size\": 230263221\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6969_Weather3.tar.gz\": {\n        \"sha256\": \"6fcff07da145465e0aeb829dcc75330b9f084ed3a831d17a6771a5616b976e17\",\n        \"size\": 345196512\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6971_Weather6.tar.gz\": {\n        \"sha256\": \"f4255add12845587d6ee31a35b9b338e034a7f27758ecb2bb8a57c20c06e5ed9\",\n        \"size\": 275788133\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6972_Weather7.tar.gz\": {\n        \"sha256\": \"d1b383845e16113a222e19f8e763a055e5ab7971fe47b397c95677d2ef42706b\",\n        \"size\": 635446787\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6979_Weather14.tar.gz\": {\n        \"sha256\": \"4cfc798c39d33cb82524246114bd297e9ab542fc2b3dd98445d6524e012e1708\",\n        \"size\": 298607553\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6991_Weather0.tar.gz\": {\n        \"sha256\": \"5d6bbff9eb5ae2086bcc1da50aace63bbb6d45b57d56011e5d425baae273e6cd\",\n        \"size\": 313208241\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route6999_Weather8.tar.gz\": {\n        \"sha256\": \"565035bba086bd6b4b0aeb04962b7294f207a01338bd14ab59016416b008dcac\",\n        \"size\": 222052984\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7002_Weather11.tar.gz\": {\n        \"sha256\": \"55662ab18d3c4028e780c8eb52cdf25e8c768aa82ab6b941ac775389ce30d177\",\n        \"size\": 195903167\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7005_Weather14.tar.gz\": {\n        \"sha256\": \"cd315b01f412aea2072ac41f50a7df104efe0a7634dad581860592d1345ecb98\",\n        \"size\": 195590496\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7008_Weather9.tar.gz\": {\n        \"sha256\": \"4727fec4a83a01748de7214396d8cf35dd8afa8c6c98136d1c44bbb63194d5e9\",\n        \"size\": 178296730\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7011_Weather20.tar.gz\": {\n        \"sha256\": \"aac381cbe69c233acc5b4624c4827ee6222bd40b8367f54ff744a682dd860d62\",\n        \"size\": 158290171\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7015_Weather23.tar.gz\": {\n        \"sha256\": \"aa2467d50ef4346b7efd78249c71d87b59190f792acc67b51daf155fa849920f\",\n        \"size\": 216210727\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7019_Weather2.tar.gz\": {\n        \"sha256\": \"3b65193f7d1b5cf5ef3f5f71504b44fbe1c259e34035265aa1c6c22a93fd8386\",\n        \"size\": 251330002\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7024_Weather7.tar.gz\": {\n        \"sha256\": \"41f748239c653309ce8e6e72d07034d9dd9e8ce6b54a48403fd2765330b9320c\",\n        \"size\": 251763484\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7030_Weather13.tar.gz\": {\n        \"sha256\": \"2bad4bae9aa1867cabb980f98d37670dfa38949f7c72ea4331e3ade3d136015e\",\n        \"size\": 215573021\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7045_Weather2.tar.gz\": {\n        \"sha256\": \"3452785470cc81c9c1c47303a0ab33d3f64a3c3a9bea019e127122416d44438f\",\n        \"size\": 291203876\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7049_Weather6.tar.gz\": {\n        \"sha256\": \"f795130061f82887b530b62d878462acfaaed46c1b301d291836f73d845a82e9\",\n        \"size\": 228548310\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7055_Weather12.tar.gz\": {\n        \"sha256\": \"34f76f7e61b76a44b3fdd85737321299d433395324ee368a233d8bf36b16a685\",\n        \"size\": 269432961\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7076_Weather7.tar.gz\": {\n        \"sha256\": \"d1193d9b21d2f7e67cc6c76e91d5bedd5ef6d63153352f15741fd61da96f2985\",\n        \"size\": 430178504\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7084_Weather15.tar.gz\": {\n        \"sha256\": \"f7e63217fb597d13c3475a871d561b8ea020524d955153cdb94bee2edae8ed7b\",\n        \"size\": 285228707\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7086_Weather9.tar.gz\": {\n        \"sha256\": \"143845d9f20f07662776543dce8de316a15d27954e414397e34e4cf59661e77b\",\n        \"size\": 200795134\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7087_Weather18.tar.gz\": {\n        \"sha256\": \"cca2f4c7f107e0e5cd5beae62d5a521d9faf07050c3da108196ba8be7989d437\",\n        \"size\": 271160756\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7091_Weather22.tar.gz\": {\n        \"sha256\": \"219cb7f47dbe413ed3b22a84997a92e5cb9cf72f0a2c574f1202e8b98ef5e82a\",\n        \"size\": 169505260\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7093_Weather23.tar.gz\": {\n        \"sha256\": \"2ff90cfdbdf6358ecc976cca30805aa6233777b362d8c031631a01175233b8db\",\n        \"size\": 209669491\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7111_Weather8.tar.gz\": {\n        \"sha256\": \"c872e7eba072ac7857fdcbb8608d55033b81a6af3839193f18054941a46e25ba\",\n        \"size\": 228096552\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7114_Weather19.tar.gz\": {\n        \"sha256\": \"1a7d7b1d318cbfb2e5144c4a7233c1044a099648f0086c2969cdeca785ab2e45\",\n        \"size\": 206520258\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7117_Weather22.tar.gz\": {\n        \"sha256\": \"bf2cdd9f2068f0d6c73a7e49c9bd78b73416e1ae55e94dd8661767b85447e3c2\",\n        \"size\": 280790458\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7118_Weather23.tar.gz\": {\n        \"sha256\": \"2a49018a448b6214520acdd031f37a5d8a0224fa50fe6cde6bd2a149a8263565\",\n        \"size\": 186523616\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7123_Weather2.tar.gz\": {\n        \"sha256\": \"8305530b3e1998c7009aa896bb48d99bbc68f6c811c685bdd11a6695259fd833\",\n        \"size\": 381563356\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7128_Weather7.tar.gz\": {\n        \"sha256\": \"a795c2359289e2d8aa5c4b19871104f3b329c6701223417a3d2b5ba41a3257fd\",\n        \"size\": 237364570\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7132_Weather11.tar.gz\": {\n        \"sha256\": \"2ac94c47f1b51a7853621bc828f460c50d3454999f7548c4d12c30769682d745\",\n        \"size\": 229318515\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7138_Weather9.tar.gz\": {\n        \"sha256\": \"3baa809f83c128ff02821c933a762090e05c9fbcd17530079647534f8e564d38\",\n        \"size\": 286110938\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7147_Weather0.tar.gz\": {\n        \"sha256\": \"827b6991033e0cca5e18059a37c18459e816715366a30b3caea544019c5f6613\",\n        \"size\": 300525813\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7151_Weather3.tar.gz\": {\n        \"sha256\": \"e50ce1797da3b0c0b5ecf461dda76127f3f95a7c7f6cb38e847fec4d338501c9\",\n        \"size\": 246088848\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7154_Weather7.tar.gz\": {\n        \"sha256\": \"0ca40d6f5d0e82e66456a66607b489e215a230043b7b65bccd7b64c85a5dc1d9\",\n        \"size\": 180396406\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7156_Weather9.tar.gz\": {\n        \"sha256\": \"f0e57540554d414e410975a78edf2fb1fc2c4dc1b0d0950473f68fbc878c6264\",\n        \"size\": 161903290\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7161_Weather14.tar.gz\": {\n        \"sha256\": \"363e0aef4d8eeab33ff7544e7ec0e1cc5d5a8270dbf18706823895780a1cd7af\",\n        \"size\": 279656131\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7170_Weather23.tar.gz\": {\n        \"sha256\": \"22fa61642e9822a7b1b9f0bfd92da72e5b1e3c4ce8b6b4ecf2e30d23f3c99780\",\n        \"size\": 323830356\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7172_Weather25.tar.gz\": {\n        \"sha256\": \"e6316be5bdd6de8615b3261fa01966701462b0c236897c9f10c986583173bf3e\",\n        \"size\": 153127738\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7174_Weather1.tar.gz\": {\n        \"sha256\": \"8da6c9b6b34b8e1f46929d0175213072d1819baa30dc8f90f2d808a8466397e1\",\n        \"size\": 245568701\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7181_Weather8.tar.gz\": {\n        \"sha256\": \"ac9b4cb1be49f780a954567dbf51633159ee3900b026364557dde61890e327fb\",\n        \"size\": 212789269\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7191_Weather18.tar.gz\": {\n        \"sha256\": \"2d7e2cb8ad69e22fb567b089d49685558a876b2b9a5ee8b817a551aaf06371da\",\n        \"size\": 396556458\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7197_Weather23.tar.gz\": {\n        \"sha256\": \"cb912c510ed1634179fa8a6c62763e93e38cdce1f435aad1b2e639fa3cee465a\",\n        \"size\": 130955575\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7200_Weather1.tar.gz\": {\n        \"sha256\": \"caabae857e33dbd545b943b9ec70cbcad19f8ba17d44cd4f8c9bd422fd5c383a\",\n        \"size\": 375583453\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7201_Weather2.tar.gz\": {\n        \"sha256\": \"62c96d81e03e0da08fc2fce6f46e01fba23694dcb8c88e5f4d58e21accc3d7ef\",\n        \"size\": 320420019\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7218_Weather19.tar.gz\": {\n        \"sha256\": \"f04bbd356997ca84160ae7911aceed5ba0917e05cf2d10f3057cb651701a84a8\",\n        \"size\": 171579526\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7239_Weather14.tar.gz\": {\n        \"sha256\": \"698cb88f2adb5059eeae70d395935f7cdc808bdb12d4998187660a79b0232554\",\n        \"size\": 1831116989\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7247_Weather22.tar.gz\": {\n        \"sha256\": \"ef45a80d44397c4d11968e23dc8393c1832feba0de3fcc9e51372fbf0fc21297\",\n        \"size\": 224237036\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7249_Weather23.tar.gz\": {\n        \"sha256\": \"83f14540c5eaee4b9325c2309db2bc91d6e626324271d6844a8c32cbe7023fa6\",\n        \"size\": 242276109\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7262_Weather11.tar.gz\": {\n        \"sha256\": \"1c26c40da0d5ee62f7115814a6a79c9a2ef56039a0e5f151ff924e6a24adc620\",\n        \"size\": 181824062\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7268_Weather9.tar.gz\": {\n        \"sha256\": \"b3d95a286f39cf12c4047c81ea318722142b321f0bc0d24ce947890ce75e68dc\",\n        \"size\": 159064796\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7269_Weather18.tar.gz\": {\n        \"sha256\": \"dd1334d86a558549165961eb8d88c8e06aaf59e9796162f0e2f25a40a15b27c9\",\n        \"size\": 298398842\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7275_Weather23.tar.gz\": {\n        \"sha256\": \"b0d74da8889d5041137ef05f00f8da92f6558d9f48acc9225a7355bf24e4ba35\",\n        \"size\": 222513918\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7280_Weather3.tar.gz\": {\n        \"sha256\": \"bf1da9a2632bd345a9ad16b3907fce6d6a6fe33f44ecfb8d0c55fc7432b3c885\",\n        \"size\": 257554893\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7287_Weather10.tar.gz\": {\n        \"sha256\": \"895ddceeeac2786004ed66b0f8edae1cb4b94057a6e9acbf1dada1d425054358\",\n        \"size\": 288248199\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7290_Weather13.tar.gz\": {\n        \"sha256\": \"a335ea2b4e593ed9aa47b19a88a680a016e67158f4a410edeb2025915d13895e\",\n        \"size\": 205392804\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7295_Weather18.tar.gz\": {\n        \"sha256\": \"98aabc971d8ce480e033224f7b3e65895cd5779f0c1e11f43e237ec21286b7d0\",\n        \"size\": 338135167\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7317_Weather14.tar.gz\": {\n        \"sha256\": \"b420c2370ab6e55e05b1c1af1fa1fee001c01b0653bba1caa49e4ca7e2d84299\",\n        \"size\": 242670170\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7322_Weather19.tar.gz\": {\n        \"sha256\": \"c5581afd8840c787cfc424c639140cabefd6355c5d2600ddbebe4946f4f116d6\",\n        \"size\": 110322200\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7323_Weather20.tar.gz\": {\n        \"sha256\": \"ea805ad83f3a7de40426cb26e1c959c28846a987cb2707ac5812f5375f87e455\",\n        \"size\": 172911199\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7409_Weather2.tar.gz\": {\n        \"sha256\": \"d81427f369bb2715d9fc408fa95d9ba21a9c9dd355c23bec7afb66464462c58c\",\n        \"size\": 183753231\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7453_Weather20.tar.gz\": {\n        \"sha256\": \"fc739c951f92b3ead3ebf85a009bbb3162cecf2e4c16e2b99681ff935708a3fd\",\n        \"size\": 216696443\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7540_Weather3.tar.gz\": {\n        \"sha256\": \"2212bdd31660ecf658241301cc8dea22ab65c36f3b5a1fd0ca522395e513c00a\",\n        \"size\": 183670816\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7541_Weather3.tar.gz\": {\n        \"sha256\": \"528c9482a06737decbc1f70669f271a2c813153b42b8946142c5d436e1e1897d\",\n        \"size\": 280817022\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7597_Weather8.tar.gz\": {\n        \"sha256\": \"4cf634128ac67423be72307f4e8c6ae5992e93aa86984e0ac16dce1bd8f8fafa\",\n        \"size\": 246468882\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7616_Weather1.tar.gz\": {\n        \"sha256\": \"80968914dad282dbc371f4e06b1e1292d9f13caedd802a7982cdb0b6e233c065\",\n        \"size\": 246548309\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7622_Weather7.tar.gz\": {\n        \"sha256\": \"e53b857edd290d56746f6debb0e0aabe9fc71dc38da4cb81ca06310a9a7f1263\",\n        \"size\": 109918967\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7623_Weather8.tar.gz\": {\n        \"sha256\": \"dda43276712e940542d3d0151f42c3e50c2013307923e6aef8bd67c6e403b54d\",\n        \"size\": 220545094\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7624_Weather9.tar.gz\": {\n        \"sha256\": \"9f2b3a8a22f875d26e88c9a85185de67e5b819e417a7dc387ccb701d4bd45f4e\",\n        \"size\": 228520525\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7628_Weather13.tar.gz\": {\n        \"sha256\": \"e6f84aedeeee72b3d767d46d138ef95a562dd59ad83edc89d77a47137aaf652e\",\n        \"size\": 221492626\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7639_Weather23.tar.gz\": {\n        \"sha256\": \"32721383fbb7800a3dc84ede00f74cf5c5ceeb8769951776e7bd1dd56ee8243d\",\n        \"size\": 177689350\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7640_Weather25.tar.gz\": {\n        \"sha256\": \"3912e61529a0b62f7eed96bdcd428506b7ac79b4e65cc27fb7aeb2508b9ab9e8\",\n        \"size\": 178563963\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7644_Weather3.tar.gz\": {\n        \"sha256\": \"4f6343d026c1edc05100cf35e23983766163a24b8d0b899240b90b1eec2b97ca\",\n        \"size\": 301175360\n    },\n    \"NonSignalizedJunctionLeftTurn_Town12_Route7646_Weather5.tar.gz\": {\n        \"sha256\": \"d2ebf948e8af52913953dc859f9d6b2a652fb1baa1f343ad63e535106f92d29e\",\n        \"size\": 245097424\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7665_Weather23.tar.gz\": {\n        \"sha256\": \"51ef4e11f900fa3d2c1dff2e148f3be44c5e3c9c15c6b8f751f9b725ae82284d\",\n        \"size\": 137948882\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7668_Weather1.tar.gz\": {\n        \"sha256\": \"d42645d7b81721a002965afbd7319012fb527fe39bb0c9ce34fa50eeb4749dae\",\n        \"size\": 283786332\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7671_Weather3.tar.gz\": {\n        \"sha256\": \"6634a96e77ae6d76c58ae2d88e3dc9c89d0355804635445a203f1039845dc62b\",\n        \"size\": 283839045\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7674_Weather7.tar.gz\": {\n        \"sha256\": \"3f0dfcecdbb0e155b45f9305f387cc55d3f25ea85a42304a5e8838321d0401ce\",\n        \"size\": 179711865\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7679_Weather12.tar.gz\": {\n        \"sha256\": \"11f9f206433ef7c9680834dbb4c851a19c0f9caa872d6c4d491ffc324353d449\",\n        \"size\": 74775239\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7683_Weather8.tar.gz\": {\n        \"sha256\": \"e7df6ec80bb0f1cf8efa188cbe9d8ebfeb4cadb77ee372b99e1b1f58e03dd309\",\n        \"size\": 207483082\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7686_Weather19.tar.gz\": {\n        \"sha256\": \"2a00cccea441aa31001fe617d424c0a45205e063b03e18185b065d5ba4263d11\",\n        \"size\": 192742888\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7689_Weather22.tar.gz\": {\n        \"sha256\": \"60bae88803af76c04e559a0f372ff89b66952b3e27ed9b89a0541bf101815882\",\n        \"size\": 110788734\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7690_Weather23.tar.gz\": {\n        \"sha256\": \"f613626d61e7a0f3b75a02f8b895429308d56d3866bc87e2ffe0bd843a857b4d\",\n        \"size\": 128809076\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7691_Weather23.tar.gz\": {\n        \"sha256\": \"5c3633108d2c4409cd5057f0ac171e836fcb642028ea33fd523cb11e9b889e4c\",\n        \"size\": 163273406\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7693_Weather0.tar.gz\": {\n        \"sha256\": \"fbcd7d7d814b3e7f5f1df9e51a595f516c6b305ce270d8388cca3c8241dcd6bd\",\n        \"size\": 205791938\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7696_Weather3.tar.gz\": {\n        \"sha256\": \"ca6c7aed0d5f2131e3289d3205ed806c57d29c7750ba4720d6056c9c222b92ab\",\n        \"size\": 189367287\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7697_Weather3.tar.gz\": {\n        \"sha256\": \"9cfeaa9e14435efa5445afffb00be41d754b1464485a368a71b4450f43b820f0\",\n        \"size\": 275153211\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7698_Weather5.tar.gz\": {\n        \"sha256\": \"64913b5c5b382a2d290c5b3cc17bd2904b3dfd69c43ef984e17d17afc6a60951\",\n        \"size\": 156172898\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7701_Weather8.tar.gz\": {\n        \"sha256\": \"f57617a3ecd702ea039a3b1e7b5e41a9a257451a7cf5b15e502f9c3acc09d2e4\",\n        \"size\": 138368128\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7705_Weather12.tar.gz\": {\n        \"sha256\": \"143e67597249b86e199481ec8ea10637b07cc817268e03e0bebc088ba0aaec1e\",\n        \"size\": 116257761\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7706_Weather13.tar.gz\": {\n        \"sha256\": \"70929a19a8160514444601ffe9a5a1005d47d6a256970b28de8bc2a156542c2b\",\n        \"size\": 119024129\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7709_Weather8.tar.gz\": {\n        \"sha256\": \"252833785a8395d0992188c2df6268776b716570ff49ea1601a7d414d8856cab\",\n        \"size\": 210492318\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7713_Weather20.tar.gz\": {\n        \"sha256\": \"4ecb4082dcaf84e5b3840b5988c689c5109f160dd9d86f5e0f29c29a09570cb0\",\n        \"size\": 189038184\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7714_Weather21.tar.gz\": {\n        \"sha256\": \"3abec492ac8ca2cee4f4183f543551920a8cc2b9344172aadc01d4ad3c0115e7\",\n        \"size\": 266238341\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7724_Weather5.tar.gz\": {\n        \"sha256\": \"39859a9d717e2eb554a7c773d1f0806507f7b3781fc4341f797c6bc0c8e12207\",\n        \"size\": 166295332\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7725_Weather6.tar.gz\": {\n        \"sha256\": \"00b23ccc4ec38516298de4dfb6aa2a75382ae7a48daebe12e9954fd6149d5c4b\",\n        \"size\": 172982238\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7728_Weather9.tar.gz\": {\n        \"sha256\": \"ad14b2df75161849f7486fe10d68f3d5ebeddc6964dc0649b7810befaa3c29fa\",\n        \"size\": 153400174\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7739_Weather20.tar.gz\": {\n        \"sha256\": \"62381abdb0fe44f3e7878d175565b339bf1152a7cf59e85c374f69b55d45356b\",\n        \"size\": 140096646\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7760_Weather15.tar.gz\": {\n        \"sha256\": \"a63d258c60c151f24352c3a3f834025537d7e15354494af18ca3a5559432a8bb\",\n        \"size\": 534274190\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7763_Weather18.tar.gz\": {\n        \"sha256\": \"3d6fb5496725e28eae36ac409b58debcccdcc6762576e6e879244800fb62c114\",\n        \"size\": 197728095\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7765_Weather20.tar.gz\": {\n        \"sha256\": \"0d66c0107964870bfa2478b90113cefe4d50d0829a8d14e87ddcbc3e92d60153\",\n        \"size\": 196855907\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7781_Weather10.tar.gz\": {\n        \"sha256\": \"8568164c444d6076329efd9eec0d986d4f8d162f0ff2c749bc7ec0b59f235b97\",\n        \"size\": 181913960\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7782_Weather11.tar.gz\": {\n        \"sha256\": \"f4f35ecd717c3645a7c2084f728ad791df0b099a8bea54038c8b14416f8adf22\",\n        \"size\": 202299828\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7799_Weather2.tar.gz\": {\n        \"sha256\": \"90c21e37c047cdbc59c8462f37fe87d16f35ea437aa3f23e3ee9ef6902633406\",\n        \"size\": 194664553\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7812_Weather15.tar.gz\": {\n        \"sha256\": \"3d6e7fa6226fb53903674508ee8c677097ae6a6f9b2daa51cd1b62eb1ff34da3\",\n        \"size\": 277374684\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7814_Weather9.tar.gz\": {\n        \"sha256\": \"4dc29bd03f197e56889857da88f319ca392973423d21edf8fd962ed2c446eff9\",\n        \"size\": 160979978\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7816_Weather19.tar.gz\": {\n        \"sha256\": \"b6f454020faf5aff7e050e3a84dd1f52392d5f34266710b98b0042e56e7898a7\",\n        \"size\": 152166781\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7821_Weather23.tar.gz\": {\n        \"sha256\": \"bb668cd407841744970a73eb3fb4487c5f85b0544de2ab9f6ea85ddf5e09a1b5\",\n        \"size\": 164614028\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7822_Weather25.tar.gz\": {\n        \"sha256\": \"e995f213b5da63d07f571cf33a5c4e76c75d477c7868319b79d43826da4ecc35\",\n        \"size\": 184442257\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7823_Weather0.tar.gz\": {\n        \"sha256\": \"46398e1d0a60f9a528858ac89d6db6fa618217894865970e9e2d0b1b2784e4d7\",\n        \"size\": 263238893\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7830_Weather7.tar.gz\": {\n        \"sha256\": \"16eb03f2b5e4738b3588cc66d9cc65aaff3972e6ecca715973b0596eb02a2bf0\",\n        \"size\": 337570989\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7835_Weather12.tar.gz\": {\n        \"sha256\": \"df1272e0b5208a95393b0594b0e60d73e2d022421b11a317a136e4d98f2e8082\",\n        \"size\": 110272724\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7838_Weather15.tar.gz\": {\n        \"sha256\": \"9f12ddfe4a74b6f4bdf8e75a2f9d1ef7dab10f1b85c3653d6ef967e6a1f9bcaa\",\n        \"size\": 179943535\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7840_Weather9.tar.gz\": {\n        \"sha256\": \"a7974f4be19729525e09e8eaad8b13ed012cc8492b18094c02ef41df8e84ce3f\",\n        \"size\": 233996995\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7852_Weather3.tar.gz\": {\n        \"sha256\": \"159312d44b5b418f9df82ab60b970b2d042412aaacdef6c688924804a152ce30\",\n        \"size\": 134823458\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7853_Weather3.tar.gz\": {\n        \"sha256\": \"06027fcf5a6e9eb3ca903822f98314927978c191ed8ee544b9083d73e77fa27d\",\n        \"size\": 208807776\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7857_Weather8.tar.gz\": {\n        \"sha256\": \"a85566df464e3a9958c1b922d6b1bd23fd0f1cbe5f1e5cfed72375e4b78eef7a\",\n        \"size\": 292289863\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7863_Weather14.tar.gz\": {\n        \"sha256\": \"36f272ed6ef0a31b20c37198925e280527efbce5fce1c7e3fab317b4e5b4a9fc\",\n        \"size\": 173766661\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7864_Weather15.tar.gz\": {\n        \"sha256\": \"4f28f7a9572b5c600fe314809c30a0abea7497a7b85924c27e31db8eb882bbd1\",\n        \"size\": 247047535\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7865_Weather8.tar.gz\": {\n        \"sha256\": \"7feec80624b0e8e9e3262deb6b721973ae9b2d7f6a19e3609e93e350fed72dd3\",\n        \"size\": 280444438\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7868_Weather19.tar.gz\": {\n        \"sha256\": \"46f8966309c86630a65defacbe27fcd8651ad4fa614e8423aaafbf708e639a1c\",\n        \"size\": 247269408\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7871_Weather22.tar.gz\": {\n        \"sha256\": \"815a4986e31f94468686e5ddc0b3284d9b9085f9f869b53c9dd89c9609191c01\",\n        \"size\": 122404528\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7881_Weather6.tar.gz\": {\n        \"sha256\": \"7e93b9caa43af6593e68907c2f0ac7469f708308410ed70f6c757255fbb03694\",\n        \"size\": 215083157\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7892_Weather9.tar.gz\": {\n        \"sha256\": \"648d6e513d504a89b17b8c8f208d8cb6b3bf0dd8503643206ac6f05d69805473\",\n        \"size\": 137656476\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7893_Weather18.tar.gz\": {\n        \"sha256\": \"5ceaacb5fa21c5f3a1f7dbe84778df59dd6977d16c16c80bc2d233d78786c4dd\",\n        \"size\": 376115547\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7901_Weather0.tar.gz\": {\n        \"sha256\": \"736d0ab02cfb1b573c997bec6a098ca85660946f12a63624b0e4d715f3aad0e2\",\n        \"size\": 285708252\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7910_Weather9.tar.gz\": {\n        \"sha256\": \"87f0fa768bafba16ef86e26e3a6cb76e7af1a3e5d049ef27f27e4759181221d0\",\n        \"size\": 246600777\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7911_Weather10.tar.gz\": {\n        \"sha256\": \"5b3fa8e620caee5c673305a64d5fe8cbeaddde169f6032f8715d684cb3b54a30\",\n        \"size\": 172538094\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7914_Weather13.tar.gz\": {\n        \"sha256\": \"b649a351f61aaeca67b5a47858972226560ff16e3a1852fd8fc1ad9c1e6fbf73\",\n        \"size\": 124979043\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7922_Weather21.tar.gz\": {\n        \"sha256\": \"c2776c2070038007f17aff60674c8c8318adb73b91cf5ef2b18b59c63365cce0\",\n        \"size\": 208867937\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7949_Weather22.tar.gz\": {\n        \"sha256\": \"b7851c2a4ab21d0f1f368a121523be3c89ff9f2f586e3324acc5b5a161ccee69\",\n        \"size\": 196949001\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7953_Weather0.tar.gz\": {\n        \"sha256\": \"46bf9b608887f94d243b30064d8bf4f70b4b1ef908c3d31539e4bb5929c4f735\",\n        \"size\": 238874839\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7955_Weather2.tar.gz\": {\n        \"sha256\": \"e7e09c8c41e8fb9fbea018efb9eb6b8abb7dfef01e6694de3e9c37e0ddb2199f\",\n        \"size\": 175877709\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7956_Weather3.tar.gz\": {\n        \"sha256\": \"49361cb0c06b1374e408c9b8ac0e72e76002f85eb5f7d83808e1e730c94c7a7d\",\n        \"size\": 212205602\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7963_Weather10.tar.gz\": {\n        \"sha256\": \"7f393219a868631c6ebdd9d44c3c6e8c5d70c36133ee43d7a9e6fc8ac165606d\",\n        \"size\": 225579509\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7964_Weather11.tar.gz\": {\n        \"sha256\": \"a1eefa34c449bcb069aa1b06c1db91ea0e85eafa9eac04c8704a108c77dd1f46\",\n        \"size\": 155949654\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7965_Weather12.tar.gz\": {\n        \"sha256\": \"0ee8be9c99ede1aab737c3b1aa341b6cc19df111904506321bee757bfe094543\",\n        \"size\": 139411235\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7968_Weather15.tar.gz\": {\n        \"sha256\": \"70a0906bff38bac4d1f95011c8d8b7774c1aa18b488dd0b83357c9138c9543db\",\n        \"size\": 118414169\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7981_Weather2.tar.gz\": {\n        \"sha256\": \"36cb04fa61816811937df442891ff6cc770e3a30d6ed79a999e4f9fa171fff5a\",\n        \"size\": 802579749\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route7993_Weather14.tar.gz\": {\n        \"sha256\": \"9f50570c1577b6762fe9afa14aa1a525893c381999526e9fb5457e3ef5901f58\",\n        \"size\": 146273681\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8000_Weather21.tar.gz\": {\n        \"sha256\": \"a9cbe923d4bfdaa3488901049d60943b0800a7e8fd0beaf1de20330fe3d991cf\",\n        \"size\": 128849185\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8002_Weather23.tar.gz\": {\n        \"sha256\": \"e582f2aa779c1e6f76e5fe776b1faae122511df68a766ad69bc48fd5faf52084\",\n        \"size\": 148476371\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8006_Weather1.tar.gz\": {\n        \"sha256\": \"72a3dda82f3e5510da7edb620d07581acd08a0f19650fa545a6b790fe9083c0c\",\n        \"size\": 192493521\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8008_Weather3.tar.gz\": {\n        \"sha256\": \"0ba56b59b1033bb49a0e5212856a36ad58bb61152c5594608145a15d909818c5\",\n        \"size\": 206494944\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8009_Weather3.tar.gz\": {\n        \"sha256\": \"b544aadc157c0a85bc72e0981f01de538b52272e7ad4eafbd115899fea24b3a9\",\n        \"size\": 156291720\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8015_Weather10.tar.gz\": {\n        \"sha256\": \"4f028924e64b80eb0fe245d70076b1149df9d2218839f7ae52429805976d72de\",\n        \"size\": 131135079\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8016_Weather11.tar.gz\": {\n        \"sha256\": \"03416644df65399e439a2c1c1b1d510a28fffd8825f6838d3408573d240b65c7\",\n        \"size\": 206837643\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8022_Weather9.tar.gz\": {\n        \"sha256\": \"4291d5b6acd41354bfd24e0564a9e38e88b4ce11abc4a71c5792e7fe16848de4\",\n        \"size\": 174994190\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8023_Weather18.tar.gz\": {\n        \"sha256\": \"6ab93bbb48f08db68d0b433ff1f3f75f91eae2973b5f4b66129f4b8e1c892601\",\n        \"size\": 194095709\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8030_Weather25.tar.gz\": {\n        \"sha256\": \"795277a50ccd99c2d16ff9c9ef09a962823880af9a157d6b17b2a99ca48b36c2\",\n        \"size\": 125440361\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8031_Weather0.tar.gz\": {\n        \"sha256\": \"d0ca1344514094b26492cfed15be94e2f4b192a465d394516de1d14ab4564963\",\n        \"size\": 334813074\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8037_Weather6.tar.gz\": {\n        \"sha256\": \"bc3c732002174b1d6dda1f94db794529cacae85ca5e00b18124ee0f753a9da5f\",\n        \"size\": 232630111\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8051_Weather20.tar.gz\": {\n        \"sha256\": \"306cbf2f1c7e0547cd7fe96672ea41f0486bcdd5b5f46f5d4d404a2e76c6717f\",\n        \"size\": 202672153\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8060_Weather3.tar.gz\": {\n        \"sha256\": \"d962fd2f18a868a0776cd4f197b9898deac43c9c8e80e54623f0bface4bd9235\",\n        \"size\": 198971659\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8063_Weather6.tar.gz\": {\n        \"sha256\": \"9522c90fe33e164dda55b1c0fd10f8e062bfaf900c95e1f4676b882ed46c7ee6\",\n        \"size\": 290786213\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8069_Weather12.tar.gz\": {\n        \"sha256\": \"c6cdc6044b32c094edbd7758cbe0231ff2b0370902dcaa4774cbdfe7e6e8cdd6\",\n        \"size\": 185210155\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8082_Weather25.tar.gz\": {\n        \"sha256\": \"270b66d6d2184a87f5977c6aaca67d203d057e5fb91de20bf54d82d4ecd09b74\",\n        \"size\": 119475973\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8086_Weather3.tar.gz\": {\n        \"sha256\": \"55f69ad40ec4c56f3e1f00b77b26b8e15bc5c5e079b5378de437ede610263314\",\n        \"size\": 151279186\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8087_Weather3.tar.gz\": {\n        \"sha256\": \"8d3714023548388024baa26ac211e873b5495ce8955b3c113f45a09ad38e7439\",\n        \"size\": 215495425\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8103_Weather20.tar.gz\": {\n        \"sha256\": \"533df353ca2ecb51c86d9b8faad4c0680578fe370c476391f9e6b42d3136f86e\",\n        \"size\": 228111654\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8108_Weather25.tar.gz\": {\n        \"sha256\": \"a8ab8663a419123c59ad74214e3e550bf2353d0138f41b9184ebb9a0676e4e21\",\n        \"size\": 162890893\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8112_Weather3.tar.gz\": {\n        \"sha256\": \"ac9a93422f4787e2e81945259e8507c11ab9122f519e38dfd447745a378a8f68\",\n        \"size\": 156174335\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8118_Weather9.tar.gz\": {\n        \"sha256\": \"c5cbf389aa6c69104ff98122622f64889fb5e74bd0207810381e88ce6be8cd7f\",\n        \"size\": 186687805\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8124_Weather15.tar.gz\": {\n        \"sha256\": \"66678375f784cd9d433923536012bc40fb8755006600b687a4152c6b5c8ad98b\",\n        \"size\": 191436146\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8136_Weather1.tar.gz\": {\n        \"sha256\": \"24bb3eb67b03201b1fde2b3f672036f7d76e79a1febb1ed4716c1765b44c5639\",\n        \"size\": 218799495\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8138_Weather3.tar.gz\": {\n        \"sha256\": \"9de8180c071bcc41d835597031b0ad061378ce9b6cc1bbff6cda51c58a137fc3\",\n        \"size\": 262797763\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8141_Weather6.tar.gz\": {\n        \"sha256\": \"c6838b15236f5e2d642dc1821e0b99b0d577e1582c2614cc221568c902a7756a\",\n        \"size\": 165354788\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8142_Weather7.tar.gz\": {\n        \"sha256\": \"e4ceaade5d817cef17411cb5abb1b38488b3f4657499af2d1897b91162296b83\",\n        \"size\": 183543905\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8150_Weather15.tar.gz\": {\n        \"sha256\": \"b353310a180b480ef4e821eb1aaf6df59b5372883a8e687dd2e58758cc18bad1\",\n        \"size\": 164214570\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8152_Weather9.tar.gz\": {\n        \"sha256\": \"5d9b8e98a0139df9ba62ea261472a3a989bb1d4d24b82082f08ce20a444456c1\",\n        \"size\": 180678862\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8153_Weather18.tar.gz\": {\n        \"sha256\": \"5341683c4841146031bb1a5a95ac190b1f6f38dd31921c3d6d92781c098b73b3\",\n        \"size\": 240090538\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8158_Weather23.tar.gz\": {\n        \"sha256\": \"7227622f86ed3fa9835d74e4eadf9b4265a2fb7aeed938daccae9deaa7170f35\",\n        \"size\": 81959626\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8159_Weather23.tar.gz\": {\n        \"sha256\": \"bc417037dfaaeb1c0a0d34622ed7cf28a758ff6ce9dbc1173698083e8f82a6f0\",\n        \"size\": 234566772\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8168_Weather7.tar.gz\": {\n        \"sha256\": \"e2e0bb7f9dbee48a59af916b06061313c36622b23a210427f5e92bb44ae26ff6\",\n        \"size\": 205008634\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8170_Weather9.tar.gz\": {\n        \"sha256\": \"c88fd3065a882808dce33523e1f44ff2f72cfe420eab6034540ba6627272d5c1\",\n        \"size\": 259893307\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8175_Weather14.tar.gz\": {\n        \"sha256\": \"8694cdd634bd7df8ce3207814fa3889e077c4dee4da6578cb95907eab391a017\",\n        \"size\": 231025840\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8186_Weather25.tar.gz\": {\n        \"sha256\": \"2f50be5d421207be8bdb20ee183d7bea2d3e671ed133e828fc8631e9d392998a\",\n        \"size\": 121598445\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8188_Weather1.tar.gz\": {\n        \"sha256\": \"31f440335361fe8ba7baf3188e6f4e6db5067a76731481d68997732d613a7384\",\n        \"size\": 269546596\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8191_Weather3.tar.gz\": {\n        \"sha256\": \"0b9958c75799771a2a3e0c3907fe412d37e7903f824723e0b3c427fc834b8c85\",\n        \"size\": 213169974\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8200_Weather13.tar.gz\": {\n        \"sha256\": \"5af3c749e28c246f1d2e814c332eb47a72f9c6c91dd552b7f9b73d6574068ce3\",\n        \"size\": 164149546\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8205_Weather18.tar.gz\": {\n        \"sha256\": \"c39324c9323936cdcf53d94ff597e324746a043bf7e149422d4c23d1d184a2f7\",\n        \"size\": 169411362\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8206_Weather19.tar.gz\": {\n        \"sha256\": \"75a40b8c92a83cc6c877a1fa1561a1a91262f51cd3a49764fb51ffeb324ccd8a\",\n        \"size\": 169864439\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8214_Weather1.tar.gz\": {\n        \"sha256\": \"04756ad720f4e4ef74f7d4d6b7afbe235a72d7d1cfc97780b17c98cb1a696c54\",\n        \"size\": 222276316\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8219_Weather6.tar.gz\": {\n        \"sha256\": \"a6b5b8b5b717788d2f9914e053dce1a20550efbfe1679b220538cecbecd61729\",\n        \"size\": 176225686\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8222_Weather9.tar.gz\": {\n        \"sha256\": \"ef87d7ddda1d4a1e9957932064d2cb5ba53daf9b2bc85641d03d806f585c5fbd\",\n        \"size\": 203399237\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8224_Weather11.tar.gz\": {\n        \"sha256\": \"eaeb99604a482354441fe6ab0a41fdf960d4236342b03a3ef4a5429188dde946\",\n        \"size\": 128651203\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8238_Weather25.tar.gz\": {\n        \"sha256\": \"bd62932fb0d24af5b0c2755b45f0295d00019c868105099a0f31a7a02147a043\",\n        \"size\": 130212867\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8244_Weather5.tar.gz\": {\n        \"sha256\": \"ec9e66c5c1f4d72fb96cbd12ecbd2f0e80f5640a29424b2ab719916a345cd9f8\",\n        \"size\": 201306336\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8250_Weather11.tar.gz\": {\n        \"sha256\": \"52b99888302370b06e6115fffb589100a762c3357c449818971de4ee9512d8b9\",\n        \"size\": 201815890\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8252_Weather13.tar.gz\": {\n        \"sha256\": \"bd1e0b164d36af0f2d885543c85f01eb75c25640f7034c89327cbb6d78f1b1a0\",\n        \"size\": 171979964\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8254_Weather15.tar.gz\": {\n        \"sha256\": \"0bf7d5aa301b48de5a1b1999b1d730bf1e948b8eae38bea83da8e5b01195803f\",\n        \"size\": 179376159\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8255_Weather8.tar.gz\": {\n        \"sha256\": \"04524aceec3192b6d6a90b174717c646d37d1140f8540ae47c72dc2218d86503\",\n        \"size\": 183321722\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8257_Weather18.tar.gz\": {\n        \"sha256\": \"88555da0c2bf9b5d49f587c5fb724393234d76a18bd501d19e00cfe93ccd6fca\",\n        \"size\": 118133272\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8269_Weather3.tar.gz\": {\n        \"sha256\": \"17c87488a4b0db869ef06c86a78609b861f95615ad2a01a02f9426e1cdcfc49b\",\n        \"size\": 132866802\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8276_Weather11.tar.gz\": {\n        \"sha256\": \"b2e726a734600ea7a5909af128bf981d3dbd5695ba1b53975729a8cdaa2d9fe5\",\n        \"size\": 221637049\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8277_Weather12.tar.gz\": {\n        \"sha256\": \"ef51a2b7f94803ead4c654c56fa522d08d53346a9cfda2b38705db3d60249a53\",\n        \"size\": 150013618\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8293_Weather2.tar.gz\": {\n        \"sha256\": \"afe657d7c87186f2d282ed7c308fdb2062fc7110dcff0e9d9f5c7eb31d5504b3\",\n        \"size\": 150063854\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8294_Weather3.tar.gz\": {\n        \"sha256\": \"534c88f87706b49040e7453053fa80107d00f8877413b08353d5688b275fbd09\",\n        \"size\": 160046864\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8307_Weather8.tar.gz\": {\n        \"sha256\": \"d9ebe71af2b6f1aa640119c5eaa98995c97cfd7206d863c53f493aefcdd75859\",\n        \"size\": 150479048\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8318_Weather1.tar.gz\": {\n        \"sha256\": \"c719e6771398c8354658556b7f866208804a27161655c317b80aae77a4262d7c\",\n        \"size\": 104311418\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8319_Weather2.tar.gz\": {\n        \"sha256\": \"34017983142f789344b6ebe79aac6fe3d2188e76e8bcd0c95925ec573018a00a\",\n        \"size\": 172104709\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8322_Weather5.tar.gz\": {\n        \"sha256\": \"5c42569f478cd4155a14ee933c805412d9ada31596b07eb192168a5af5f598b6\",\n        \"size\": 137135351\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8339_Weather22.tar.gz\": {\n        \"sha256\": \"ab2c0bffd8adf89d92b31b95df1185ba1f3d3d6a338f03a71cfa3c05182eb64a\",\n        \"size\": 174435370\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8347_Weather3.tar.gz\": {\n        \"sha256\": \"c209c297692b372ec6104f2e85b77561ac6437c0e6e079807142575fe9b8e704\",\n        \"size\": 199023979\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8348_Weather5.tar.gz\": {\n        \"sha256\": \"13a221c9c5f3aa42ba3da7038d518c2f40b14e549d9a5be261089115f5c243c3\",\n        \"size\": 158811978\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8350_Weather7.tar.gz\": {\n        \"sha256\": \"7673c7130c3b245890a8e6e69b8d506f79bd6ee48c2f47771ca628542f29b5ee\",\n        \"size\": 391894356\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8355_Weather12.tar.gz\": {\n        \"sha256\": \"e42ff79acbaff8357bf487cf86842c8a423321796f1f72875930edc8ae301a53\",\n        \"size\": 138160684\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8364_Weather21.tar.gz\": {\n        \"sha256\": \"f0470d949dc749a5693bc63f222156c326df608da754a08a5e30d915aa18cf2f\",\n        \"size\": 117148262\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8370_Weather1.tar.gz\": {\n        \"sha256\": \"69020618de9d0ad720a7cc40a0b1dbebd110faaf7633f5b8720131ccaa16f01a\",\n        \"size\": 799966757\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8390_Weather21.tar.gz\": {\n        \"sha256\": \"0608ebbaa9463e19b4dbce0af15a8a18e001e46670ac0f9b7baf1e4ff9c3673a\",\n        \"size\": 298767066\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8398_Weather3.tar.gz\": {\n        \"sha256\": \"0ac2987e4baa51fcb5c962829d8bf0c3164934a7a896fd1961366c55abacf296\",\n        \"size\": 195623903\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8402_Weather7.tar.gz\": {\n        \"sha256\": \"2d3c84df6430275727153a2205c3e3cbe5f7b37551d64e30c1f3ccf8674195ce\",\n        \"size\": 206375948\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8409_Weather14.tar.gz\": {\n        \"sha256\": \"51a4c6f600d965ad7b312a2a728ad18f25ce195e4ca87246b8c8c8bec22800e8\",\n        \"size\": 144998702\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8412_Weather9.tar.gz\": {\n        \"sha256\": \"0a8921ff10c166d1a3a9f123f03d530de5631200ce0d09036303232ff9efab06\",\n        \"size\": 133001735\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8426_Weather5.tar.gz\": {\n        \"sha256\": \"3e5a06040c7fa2094b182c5f99eab2b26db560730badb9fd709057f613a9c0f2\",\n        \"size\": 170079475\n    },\n    \"NonSignalizedJunctionRightTurn_Town12_Route8428_Weather7.tar.gz\": {\n        \"sha256\": \"f0053ce652cf4127c07a1744ddb907377c4a2d86013db1475cff6975a2a0eb48\",\n        \"size\": 156397622\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6191_Weather6.tar.gz\": {\n        \"sha256\": \"8d053f86c2a390a2e06f9c73fccd494143bb249f5ce09111ff177ff0cef2f3ec\",\n        \"size\": 137040443\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6234_Weather23.tar.gz\": {\n        \"sha256\": \"3f9a64a57090c7bc5fe2fda05af49e8bf41cef6ff465804ac66f1a78fb584415\",\n        \"size\": 129619344\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6235_Weather23.tar.gz\": {\n        \"sha256\": \"8450923a6d40a283c9c301a0f656959aab0583128a6fdb5926523333009e7919\",\n        \"size\": 130956273\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6280_Weather9.tar.gz\": {\n        \"sha256\": \"73781cce049b6f87dba5d4678e87388d159dd3b1f01b3bd02a377231bcaa5e91\",\n        \"size\": 175834923\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6281_Weather18.tar.gz\": {\n        \"sha256\": \"48dae68e0e90706f7456ffaf41bae51bdb15679f742e1af8cd7ecae84333d3a2\",\n        \"size\": 198305597\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6319_Weather3.tar.gz\": {\n        \"sha256\": \"ce529f6ffecacf7b68b2d6d97661273d0ba716bff3c80dc82486afc5ecfc058b\",\n        \"size\": 100101424\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6320_Weather5.tar.gz\": {\n        \"sha256\": \"9c7305362f2b35dd229dcc3b0520342af222bb13267444862eecf7842324eec7\",\n        \"size\": 158447808\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6363_Weather22.tar.gz\": {\n        \"sha256\": \"7eb659cb2bb68fa2f77c5c0d64c11fb9d7a6ad46336b453eae40783239e044a4\",\n        \"size\": 93492018\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6364_Weather23.tar.gz\": {\n        \"sha256\": \"4196cbd4f34df698bb38ed3ab2c5430a10d92c8a99acd6ec7c93fc87118219d6\",\n        \"size\": 134617978\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6410_Weather9.tar.gz\": {\n        \"sha256\": \"c1e41d39ab761a87c1ce98e7f9b95cf8a5dff65182a381e89426cfcdcddac66e\",\n        \"size\": 102159394\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6411_Weather18.tar.gz\": {\n        \"sha256\": \"7b2c26f85edbfd8c21ee1ce0c1174c873996bb2be0da273f8a0765d2fa9d9a13\",\n        \"size\": 108638663\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6458_Weather13.tar.gz\": {\n        \"sha256\": \"5420d83fed4e99c2c882802053b7c5f338e3bb9d6045af65c06d09de76f86132\",\n        \"size\": 115208036\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6507_Weather10.tar.gz\": {\n        \"sha256\": \"6f50e2732cda6a7d7a3da391149f266b50c6e449be5f8aac56b0050b1e429e6c\",\n        \"size\": 83106120\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6554_Weather5.tar.gz\": {\n        \"sha256\": \"423d88b34113dbb4539a3d475f4d8ffcff32abc2a6d6cbbd53df8f2fde005e5b\",\n        \"size\": 132499148\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6598_Weather23.tar.gz\": {\n        \"sha256\": \"edec0d40a59b5211d754a3ab8329d815b717094a9c7bad420939ddfa32768caf\",\n        \"size\": 127668318\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6599_Weather23.tar.gz\": {\n        \"sha256\": \"6895a17ffeb2b9b000b3cac7177656bbe7c719e980a85c86fca9f6cde885db5d\",\n        \"size\": 163857061\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6648_Weather21.tar.gz\": {\n        \"sha256\": \"8ec62dd826cb120e0037e25503f3efb1a8af3a6fbe96bf544a82814559eb6389\",\n        \"size\": 121130131\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6691_Weather12.tar.gz\": {\n        \"sha256\": \"6b8f8ee12d43e4186203560d285ba317299455885e67a3f3b3c9620e2e873172\",\n        \"size\": 122269168\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6692_Weather13.tar.gz\": {\n        \"sha256\": \"befe5ec089bac263124527c7165028aa22e5dbb13391ccd9b5ecf6045461c179\",\n        \"size\": 87158965\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6782_Weather25.tar.gz\": {\n        \"sha256\": \"f69b909bde9713e85364baca0626fe413ac5843f3822283d0b4faef260396e36\",\n        \"size\": 101581582\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6783_Weather0.tar.gz\": {\n        \"sha256\": \"79e4c44d60bbd1506d0d9a053157a96bb265496839f6f26fe2aa648f1792f450\",\n        \"size\": 115999602\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6827_Weather18.tar.gz\": {\n        \"sha256\": \"7190a17f374ac4b5d2924c5f0415b2baf9dcd805892986d8df65ba4f9ab72e74\",\n        \"size\": 94732256\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6828_Weather19.tar.gz\": {\n        \"sha256\": \"df6afaafa8c110a04ae3df986966bbbfc3eb719b2386d9cc888e5c1c6f106bb5\",\n        \"size\": 104827766\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6862_Weather1.tar.gz\": {\n        \"sha256\": \"d8780420a5ef78ebc1ad0631b70bbe0237988bb3aa3448e960b2678014721566\",\n        \"size\": 119253469\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6863_Weather2.tar.gz\": {\n        \"sha256\": \"f6fe9d2e0e8ee1d94bb4a86172deba19872a5a935845a038912b59923acbffd7\",\n        \"size\": 143200270\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6864_Weather3.tar.gz\": {\n        \"sha256\": \"72584d90dd7c789fb9fff6bcca96b0631dfc5646b0451c7dca1d8a2d73230e52\",\n        \"size\": 141258011\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6865_Weather3.tar.gz\": {\n        \"sha256\": \"0a705bffde47410234acf7f61ffba4433624914651d2b7338f91be11a2ac16d4\",\n        \"size\": 124251146\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6866_Weather5.tar.gz\": {\n        \"sha256\": \"1793b35cd769d894c56be459faea3bd81012b1b83600a7102fb96649fd1d2cad\",\n        \"size\": 167181843\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6868_Weather7.tar.gz\": {\n        \"sha256\": \"33738ec669be72eb64545751c630a1c7fbf980f7be8faee984cc0f5ce028de45\",\n        \"size\": 158307608\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6869_Weather8.tar.gz\": {\n        \"sha256\": \"dc6f041b332c9ecccc6e61d3f499564d3c21953892e4c9056ecf08c20d53fe72\",\n        \"size\": 150887855\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6871_Weather10.tar.gz\": {\n        \"sha256\": \"4b0be04352e1f53b1e809f2f02a205ec1e8c086cb27e166a311276e94a3ad4dc\",\n        \"size\": 145504692\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6873_Weather12.tar.gz\": {\n        \"sha256\": \"40d90530dee4bd6bf1b976ac0603344cd3b019f8e5775b0a8856d354ead9caa1\",\n        \"size\": 328301924\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6875_Weather14.tar.gz\": {\n        \"sha256\": \"9f02f6c83e297a330aed5e1c88e4bfa0ad96ddbce7fdcaa7319a73d9be529972\",\n        \"size\": 144138229\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6877_Weather8.tar.gz\": {\n        \"sha256\": \"ff6cdffe68d59ded7241a775d671465fa2c6e383f95ede272ffba4fec6d17d84\",\n        \"size\": 167860808\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6878_Weather9.tar.gz\": {\n        \"sha256\": \"bcebe256318d0efd658ae516ffe5424a471b4c3942cd295e0b099bfff44444e9\",\n        \"size\": 97965679\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6879_Weather18.tar.gz\": {\n        \"sha256\": \"36ef1f324995cf8cce1470e60fc3f54f35ef2b5160dea079db8126a6075723e6\",\n        \"size\": 111980852\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6880_Weather19.tar.gz\": {\n        \"sha256\": \"1c4ed38f037c2a821f4cbe950260d4014f125408baef9d1dede370a6c5174220\",\n        \"size\": 140012099\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6881_Weather20.tar.gz\": {\n        \"sha256\": \"145c898e216fe1cdecc4bc0f0464acbdf7e74926c72077023234afe8406ecae4\",\n        \"size\": 191654513\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6882_Weather21.tar.gz\": {\n        \"sha256\": \"2e97638b5ea3ecc0e0912efdae6e46239668e061e24950f057d952c3244cae93\",\n        \"size\": 180652710\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6883_Weather22.tar.gz\": {\n        \"sha256\": \"c1ee9a0ab974b821e26808313daa3aac1b76edcac052b09966baa832b5ed55af\",\n        \"size\": 148367525\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6884_Weather23.tar.gz\": {\n        \"sha256\": \"ff3c3458cf7fb85382336144045c02e53be353893a92b26b7f3296c35d0b18e3\",\n        \"size\": 325861340\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6885_Weather23.tar.gz\": {\n        \"sha256\": \"2d45fb61d75daa40160ba72dfb26401c96ac12b8f669c637b3d4205f69cc9293\",\n        \"size\": 194039487\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6886_Weather25.tar.gz\": {\n        \"sha256\": \"727386d61bfbe33524a61f7fbdb0b599ee79e8de79a3be912fa478eaf9ef5ca2\",\n        \"size\": 127173851\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6887_Weather0.tar.gz\": {\n        \"sha256\": \"1bfcc147f2124a1806a76f019b4b4c1f7cad080d691029647e26b95c19c3a9d7\",\n        \"size\": 242899176\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6890_Weather3.tar.gz\": {\n        \"sha256\": \"06392d2ddc25c449cd110fc8e8037585aec0febd56b4d4dad3e8bbc1babd2bb0\",\n        \"size\": 131874520\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6891_Weather3.tar.gz\": {\n        \"sha256\": \"af1895efe5cc316d0897738770c3f5607392b28633712c19d006a4e35d992376\",\n        \"size\": 160572926\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6892_Weather5.tar.gz\": {\n        \"sha256\": \"4f9ed51ff3505f2ebb370e5c0bb92427dbb673806e1fbdf63b9aecbda2343f56\",\n        \"size\": 119710918\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6894_Weather7.tar.gz\": {\n        \"sha256\": \"a281041b88a77602598b1123f1e4965263f5c1f0faa3446fb21280a32dbc9b38\",\n        \"size\": 230366420\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6895_Weather8.tar.gz\": {\n        \"sha256\": \"037a4025ba7644ea8ab70b4680f969030c55fbc9e900a7b133070019641a0a50\",\n        \"size\": 94534994\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6896_Weather9.tar.gz\": {\n        \"sha256\": \"fe1f9c7a63438cbd7070f7c513c1582c02fe8c29612ad7dd46443218270c4e35\",\n        \"size\": 105893112\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6899_Weather12.tar.gz\": {\n        \"sha256\": \"510d8ad4b86bb3a7b559d045a60dfdc0d6e57d23a16a91a96c774bd2fec78422\",\n        \"size\": 141954002\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6900_Weather13.tar.gz\": {\n        \"sha256\": \"45e4caaf39a731f125988c0e4bc401d54a90f4f2bfcd7d00e1d21e9faa5976bb\",\n        \"size\": 104375804\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6905_Weather18.tar.gz\": {\n        \"sha256\": \"dae4b30e68cee889f6e533041fba8863728c90d6b4e12f46eeab671b08613174\",\n        \"size\": 355976858\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6906_Weather19.tar.gz\": {\n        \"sha256\": \"16d5308a01518310fd5665b97f3e5c90491990ba6cb9d5a62fd693af10440e70\",\n        \"size\": 140978408\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6909_Weather22.tar.gz\": {\n        \"sha256\": \"77a469683a2c44b2c099e00e810a1bb2cc84f20de42e8e9537b0479a9c44ee30\",\n        \"size\": 131985099\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6910_Weather23.tar.gz\": {\n        \"sha256\": \"5a3171cb35d3b8e8f9c4d212d774a18b5d0f6ce70ce998508f000596ffd1a43e\",\n        \"size\": 112138636\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6911_Weather23.tar.gz\": {\n        \"sha256\": \"fde6fdc52dde2dfe832e4878f1562fc1fe484c6fde58ad53978e3c2c2a02a154\",\n        \"size\": 134428472\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6912_Weather25.tar.gz\": {\n        \"sha256\": \"b720f794cebf3072c42b91f5ca2426ad10a7f3dfecc04159a83b8031e6480463\",\n        \"size\": 110716486\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6913_Weather0.tar.gz\": {\n        \"sha256\": \"7029885e10c15bdd83eaec264f421bb93658b9be904db36f2e6d8841c90731e3\",\n        \"size\": 131598724\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6914_Weather1.tar.gz\": {\n        \"sha256\": \"7162b1dea1f52b561f4c5963fd6b1fb5a395636ecf2489f9b67a4beaf634897f\",\n        \"size\": 120539488\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6918_Weather5.tar.gz\": {\n        \"sha256\": \"93c96f7a1a1680c9beeb33ec60964fd08a741e2e99593d1e90cdd59d0fbd40b1\",\n        \"size\": 483151802\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6920_Weather7.tar.gz\": {\n        \"sha256\": \"830d35f9249d6234bf70f4d3a0bcc7f9bd0a1653b7b32363d9af79c61a8aadca\",\n        \"size\": 182158187\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6921_Weather8.tar.gz\": {\n        \"sha256\": \"35b1a56bf39cd73b31bf8ed598ff1348c14beb9532f724a91d1e08de7480c16c\",\n        \"size\": 138593107\n    },\n    \"OppositeVehicleRunningRedLight_Town12_Route6922_Weather9.tar.gz\": {\n        \"sha256\": \"56db9c23bcf1894af9bc9e08cf0043085ab8e06ab975469af4829a246e4c0e48\",\n        \"size\": 123210222\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8438_Weather9.tar.gz\": {\n        \"sha256\": \"ce32ea634d1b984f99077dae0e652efa5ab506ab8053dfce68ec451691b7a019\",\n        \"size\": 154748483\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8439_Weather18.tar.gz\": {\n        \"sha256\": \"18d6f4524c95b0ff3551b9a0d7effb8bae941c50ded6c99c07e3ca4d9e4fe73b\",\n        \"size\": 234249582\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8444_Weather23.tar.gz\": {\n        \"sha256\": \"0c29375105909e18befe7cf70764470ee4ecac7d3331f31801a5019c2cf920b3\",\n        \"size\": 179346884\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8445_Weather23.tar.gz\": {\n        \"sha256\": \"2ee819e4ac4a21fe3a7352d2574ddde6366517744fd2f4069e147118bffb2620\",\n        \"size\": 194789032\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8449_Weather2.tar.gz\": {\n        \"sha256\": \"eaf3006a4fdb154320d7860aa49281d556cb90beb325093c0dde21e15f599e38\",\n        \"size\": 168988335\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8450_Weather3.tar.gz\": {\n        \"sha256\": \"3aa98ff8f47515fd222d756b6b997a02234681c44ac9458527f00fe0a1fe7583\",\n        \"size\": 230821952\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8451_Weather3.tar.gz\": {\n        \"sha256\": \"a732a33262adb3c7504c9e91c662357c681ff7d25d68b2ae8083d5e8d209c7ec\",\n        \"size\": 292843174\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8452_Weather5.tar.gz\": {\n        \"sha256\": \"9ab88a8e4d8e1dce2b23d9186d06f39a06fa0b577e102eb3ad644687717c8a9b\",\n        \"size\": 202519914\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8454_Weather7.tar.gz\": {\n        \"sha256\": \"3a8b96fd4f24b837f2186488ff1cdcc28e133cf17b07c11dcc68dc77eabf6f39\",\n        \"size\": 298739431\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8455_Weather8.tar.gz\": {\n        \"sha256\": \"b1cd6a82a40047806aac07e3469066cdcfffc127fa65826e527e2d9edd45109f\",\n        \"size\": 270709252\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8456_Weather9.tar.gz\": {\n        \"sha256\": \"b905f44f109eccaaf30ab8be0ec761313f01f54a01aa840c69f7c2aee2a056a4\",\n        \"size\": 131714332\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8457_Weather10.tar.gz\": {\n        \"sha256\": \"6e671b5681ffdeb7bc1df149708428084619f671d32eb3855b2bc0b7890e079f\",\n        \"size\": 203481992\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8458_Weather11.tar.gz\": {\n        \"sha256\": \"1348f875df62118a24a6ae6f40b06d23cd87e53cabbdb4f87b05d4b318f00c35\",\n        \"size\": 205371823\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8460_Weather13.tar.gz\": {\n        \"sha256\": \"5b6d5dd1fcb2b5ad50d51691f113959a5990ad81487e35ecb00df32e56503acf\",\n        \"size\": 201354301\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8461_Weather14.tar.gz\": {\n        \"sha256\": \"b60896248782da3fe24816b7735c8a9ac236e1a93f6da982295a38bcd69ef042\",\n        \"size\": 187870322\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8463_Weather8.tar.gz\": {\n        \"sha256\": \"6ba7ae2658ffa674344377b4b5beaa6a95612321cfe1e8f3ef6c1d4a164d673c\",\n        \"size\": 298642111\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8464_Weather9.tar.gz\": {\n        \"sha256\": \"2647b54cf413c3adb168757d8fedc63ebeca64c4594867b4c6501cee21ae26aa\",\n        \"size\": 214590701\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8465_Weather18.tar.gz\": {\n        \"sha256\": \"4c6dc079a6948d21976e1df454a5075d46528630cc1466c3e28347cd15c4e220\",\n        \"size\": 129769892\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8466_Weather19.tar.gz\": {\n        \"sha256\": \"206fd5310dd1a5703179fc3aec7f69b36d2c9319aaed24f8e3c7d50d78d7917c\",\n        \"size\": 239351001\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8467_Weather20.tar.gz\": {\n        \"sha256\": \"ed80548a782c7876db87f77b3737d267ae594ae4eb6796521bd9aba40bcb1106\",\n        \"size\": 224366924\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8468_Weather21.tar.gz\": {\n        \"sha256\": \"5e6def94a60188d4e7dcc821c6f31461c6d4f9c9d713009b94819eb7be8bf192\",\n        \"size\": 239558892\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8469_Weather22.tar.gz\": {\n        \"sha256\": \"de9bc2bf97dce78e51bb68ae746d97c20e04c63621f5e56962035eab55a6804a\",\n        \"size\": 163665959\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8470_Weather23.tar.gz\": {\n        \"sha256\": \"822785f4e3eb580917ee099078cc0b2896b6f91b9f429a21c2d09ca231c00fc5\",\n        \"size\": 175841198\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8473_Weather0.tar.gz\": {\n        \"sha256\": \"ef1ac20e6a172a71b75d54958a76adf18696e33eb10f9bb451f321e70f1eed40\",\n        \"size\": 284553674\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8474_Weather1.tar.gz\": {\n        \"sha256\": \"ae1fb93d78ec250f0e4c733e1431b6cde1a9c1078170d4041ddbc3ed0b7a33f8\",\n        \"size\": 278502613\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8475_Weather2.tar.gz\": {\n        \"sha256\": \"b6af8064c93b5054772c51b242c83b485c249c5d067c509568bf148aa1ab4efb\",\n        \"size\": 99429215\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8476_Weather3.tar.gz\": {\n        \"sha256\": \"fc68e0b4640f97e928fd247e1dbcef198344403d28860631611a433fbd1bc0cd\",\n        \"size\": 108348415\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8477_Weather3.tar.gz\": {\n        \"sha256\": \"fcee277df0ed500a802a09bc074e17d9186c2f1b14fdc7d8f7bdadf046aca4f1\",\n        \"size\": 287503552\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8480_Weather7.tar.gz\": {\n        \"sha256\": \"9a388067a4334cffb5f077700942690dd5deda18b09a8b7c83f4851b62f63009\",\n        \"size\": 196354917\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8481_Weather8.tar.gz\": {\n        \"sha256\": \"c92ece20a6b975e0f92415f3e870eb515687e09806a6d364d57dd1e745196b95\",\n        \"size\": 247361569\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8484_Weather11.tar.gz\": {\n        \"sha256\": \"6621a8b60b4c2d38eef55e99bc7c2bc389f4e11fd4e2b8337d20f4d64bff0905\",\n        \"size\": 193786811\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8485_Weather12.tar.gz\": {\n        \"sha256\": \"06f3113cfb340f0d13a95ae90e38a08c5ae37e03d3d0b8ead57ec6b88c8d3ef7\",\n        \"size\": 155034482\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8486_Weather13.tar.gz\": {\n        \"sha256\": \"2e3c089f030625d450c210796d78474c65bc9f61ae8515a76936a2838667a66d\",\n        \"size\": 198761719\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8488_Weather15.tar.gz\": {\n        \"sha256\": \"0f8582909a765782a83555170c43c9004808fd00b4e9c42793c1f8c6e08fe14f\",\n        \"size\": 226355343\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8489_Weather8.tar.gz\": {\n        \"sha256\": \"8b5a26adeb6914a713972cf39c29f0f207f82cc2ea01c62900bad94f6a9f4aa1\",\n        \"size\": 215413267\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8490_Weather9.tar.gz\": {\n        \"sha256\": \"8a2dc88ee333c91b4560f6990833763e8c0f204110303e2ede2a147949ae8e53\",\n        \"size\": 205949045\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8493_Weather20.tar.gz\": {\n        \"sha256\": \"3f4f96ed3ba2b5b7da65b50a038ef93dcd89526fb1ed70d47b6bd4ef9cd388dc\",\n        \"size\": 201156893\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8494_Weather21.tar.gz\": {\n        \"sha256\": \"48f070bc922a371809b9dc1750863c0404d6d732e13ca25cbee215d7fa6935f3\",\n        \"size\": 160755310\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8496_Weather23.tar.gz\": {\n        \"sha256\": \"3ee64e1802d9969aeea1ebc0f379f8feb3d0d73dcd6b0fac142010336d3df006\",\n        \"size\": 235396243\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8497_Weather23.tar.gz\": {\n        \"sha256\": \"fa2d2b8fcad385d274102f0bc56de17c2fdd65beba5f610f919d214dc055ef8c\",\n        \"size\": 139828955\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8500_Weather1.tar.gz\": {\n        \"sha256\": \"3fe91f80a7cdc4657260f9e9326ff1b6c06a74842fc5133929ead691bc136162\",\n        \"size\": 445993317\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8503_Weather3.tar.gz\": {\n        \"sha256\": \"6393992888eb3f942fa09e179a835341c6c542e0639f48723c5b0215cbe231bb\",\n        \"size\": 239792351\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8506_Weather7.tar.gz\": {\n        \"sha256\": \"e9cd1ee526cdc6dd31fb09a63b95623645d74a23360b64aef9eeac6f68a95954\",\n        \"size\": 134133327\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8507_Weather8.tar.gz\": {\n        \"sha256\": \"e28cb5177a87749646708096e4c59722cd432b9ca724eca1bcd84e8b05065619\",\n        \"size\": 227320083\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8512_Weather13.tar.gz\": {\n        \"sha256\": \"f0544c39810e6b03a626f4175517110f1b4662b01732033b6aa3354b6c0c27ed\",\n        \"size\": 204450494\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8514_Weather15.tar.gz\": {\n        \"sha256\": \"b03a977b5c7e5abd519222c096db4c68fdf37a5ff345fdeabeee7f7f3abca5ff\",\n        \"size\": 819355232\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8515_Weather8.tar.gz\": {\n        \"sha256\": \"bdc617877f091e3ea45d5df0ae12a17fa89818de5b8e57eb56ec3d5a1110320d\",\n        \"size\": 182458028\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8516_Weather9.tar.gz\": {\n        \"sha256\": \"a52c45b41e385bd4a5ea68b4e81d41853f22d41d09c36755051a309e0068eba4\",\n        \"size\": 198981424\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8517_Weather18.tar.gz\": {\n        \"sha256\": \"d3bcc21e90e2b6d096695bf92047a3f48ab5a3c90064cf8d7aa368f883d854dc\",\n        \"size\": 188744739\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8519_Weather20.tar.gz\": {\n        \"sha256\": \"8565344326a5b956c220156b6eb4e9d13afdfd2fa34ba4fcc6797b090d9ef49e\",\n        \"size\": 169529849\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8520_Weather21.tar.gz\": {\n        \"sha256\": \"6d18045c6579f9c1ad69b62d8c51fb0f24a489247d1b0f0a5e8c9b861690205f\",\n        \"size\": 346302854\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8521_Weather22.tar.gz\": {\n        \"sha256\": \"8ce4ad848c56fa52e41201686d5e6c4bb28d302b19959278fe3235ef1fd892dc\",\n        \"size\": 195675380\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8522_Weather23.tar.gz\": {\n        \"sha256\": \"c12a78d63c03fbea639b583bb7d4d7e99a2d37d006bb28a5987ac4d4ec73bf72\",\n        \"size\": 137977627\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8523_Weather23.tar.gz\": {\n        \"sha256\": \"0246608e83ef6b39dcd28de73763cb613dd1e746ae94d8c98cee7fb2a14ab182\",\n        \"size\": 233254695\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8526_Weather1.tar.gz\": {\n        \"sha256\": \"0753657fae8dfe74e8b5f0fa39dfc0e6f1e9e81e2b0def4855b3d92906d9d754\",\n        \"size\": 584733803\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8527_Weather2.tar.gz\": {\n        \"sha256\": \"9e882aef9dea775fa89a065da6a0748c2cd3ca97e267f1a48bbb436f512766e3\",\n        \"size\": 194761318\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8528_Weather3.tar.gz\": {\n        \"sha256\": \"c8cf30ccf3a605721094f55ac0000f0863ac1914321ebc65fadf032991702826\",\n        \"size\": 275310956\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8529_Weather3.tar.gz\": {\n        \"sha256\": \"2870f4e54c1ed394f08fd84d915447b5f4a297b76a328e72b071e2db9edde3c4\",\n        \"size\": 170618706\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8531_Weather6.tar.gz\": {\n        \"sha256\": \"1e077eff5fdd46b3efb7438f4d63d3ee4904b0e811b43033464f5db9682fde97\",\n        \"size\": 251120235\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8535_Weather10.tar.gz\": {\n        \"sha256\": \"cc23a188a3ef9902c421d7ecab8895f81ca91040d22df962aaaf28b66677689a\",\n        \"size\": 107544180\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8536_Weather11.tar.gz\": {\n        \"sha256\": \"11a617ca2b3a7b0d83cb5886f0fa16b67a9041cd89c8ac674c751eaeb2bc7977\",\n        \"size\": 162476791\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8539_Weather14.tar.gz\": {\n        \"sha256\": \"bb3789a411c1622eb9b50e309c5452148205448bd364ed78f45418bc4791e079\",\n        \"size\": 165606751\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8540_Weather15.tar.gz\": {\n        \"sha256\": \"a53e649ea1d8bfab3e224b3a99b0172e7572a354887b3fcbb0664aa22649c7ab\",\n        \"size\": 236481065\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8541_Weather8.tar.gz\": {\n        \"sha256\": \"50ce46fcd53dd05b576d69f855e2c3da9703ffc8afc153989cc751d857cbbe0d\",\n        \"size\": 341476306\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8542_Weather9.tar.gz\": {\n        \"sha256\": \"a5bc6364a2026eb9f0f067ba14f36dbc639a37bb14771eb5fab5d3d853ac1a39\",\n        \"size\": 214066910\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8543_Weather18.tar.gz\": {\n        \"sha256\": \"8b24c3a6530d08465502801eb6ab7cd0a33f1900f21241cb69e42c372201f94a\",\n        \"size\": 246921200\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8547_Weather22.tar.gz\": {\n        \"sha256\": \"8fb94e4212c9a169b7ca666285fe43bbeb8e189af3d08c2189e80857d644d38d\",\n        \"size\": 184315813\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8549_Weather23.tar.gz\": {\n        \"sha256\": \"efb02ca5227f6bd4c7f4745504c2a2ec73c28207360e03a50179bb464f7c6962\",\n        \"size\": 248373254\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8551_Weather0.tar.gz\": {\n        \"sha256\": \"013e991f234bbf82a23e0c8efe342615cab73dc03642b5aa4cdc137bd84f4620\",\n        \"size\": 269803878\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8553_Weather2.tar.gz\": {\n        \"sha256\": \"15c04ad7c82dc43f344fa7ac90690f401f2cb3b38ddded3ed0414245caa9d2ec\",\n        \"size\": 358978543\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8555_Weather3.tar.gz\": {\n        \"sha256\": \"402435081971143b8914d1cad85f0b8a10fc5c50eed818616a62f04699409248\",\n        \"size\": 414104285\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8556_Weather5.tar.gz\": {\n        \"sha256\": \"969ce77df65fca9aa0d7437470ccf8a4485078893087d4affe6bf2c733b6ab63\",\n        \"size\": 247585573\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8557_Weather6.tar.gz\": {\n        \"sha256\": \"538543f3cb40d798455634d8473344ef0f59f0bcdc4b83c80e1cc9add602d4d6\",\n        \"size\": 215500450\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8559_Weather8.tar.gz\": {\n        \"sha256\": \"3df2bb957127d928959aee1bbbc4abb8955e0047d64637126f7b3b625cae1fa4\",\n        \"size\": 239380060\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8564_Weather13.tar.gz\": {\n        \"sha256\": \"74e7ec8e7b290dc91fcec5a18fb3778843b1c029e310850e88c41e19345ea16d\",\n        \"size\": 197073737\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8565_Weather14.tar.gz\": {\n        \"sha256\": \"5618196e494b6d69ff97e2cc175d1f236ffe3f4379d926217cb561e7eff175f3\",\n        \"size\": 236345090\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8567_Weather8.tar.gz\": {\n        \"sha256\": \"e2fd1419a57f50d4b027220cbee85ca6e427f0928133dc8ffd479fe210ca037c\",\n        \"size\": 176221426\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8570_Weather19.tar.gz\": {\n        \"sha256\": \"8e4d8553fa1fc5fe6848528bd8e7852ccee90c96563dbc320d9d81fa567be5a0\",\n        \"size\": 181045091\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8573_Weather22.tar.gz\": {\n        \"sha256\": \"b72e833308cd6c99d619d7c70f81aa15f1eab9597b27bf9bc253c354b287ae2c\",\n        \"size\": 178160881\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8574_Weather23.tar.gz\": {\n        \"sha256\": \"1507d9e389e537519e4449d71efc210bf56e3908d1abd4fb9b5ffa60df105a95\",\n        \"size\": 210487462\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8578_Weather1.tar.gz\": {\n        \"sha256\": \"08ae3ce42dbe82e76da8fcdcfc43ede699f189bd725918aa12ef18a61e387d2f\",\n        \"size\": 261631599\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8579_Weather2.tar.gz\": {\n        \"sha256\": \"c573a9c27fd71287db7f5fcf7d88d5ef458b6c00aec57bf74160bead5ac74446\",\n        \"size\": 261605483\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8580_Weather3.tar.gz\": {\n        \"sha256\": \"0c5bb92585578712c3878d2c2e657981c0a293a97f32f7d53027d61c1abccacb\",\n        \"size\": 194065617\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8581_Weather3.tar.gz\": {\n        \"sha256\": \"c1665ce9c80b1c9e62f5047fadc5abba6087be5209735d83abedf9744c316173\",\n        \"size\": 253478567\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8583_Weather6.tar.gz\": {\n        \"sha256\": \"9348c7cf5c9b91dd4563aee8909ee19bf612d2f909cbdc699abe6e81ace0af0c\",\n        \"size\": 194729283\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8584_Weather7.tar.gz\": {\n        \"sha256\": \"60a59393b7942f1a4d7c80f259688ad0f392359935f7afbb1d7bb094386fbfe7\",\n        \"size\": 222395183\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8586_Weather9.tar.gz\": {\n        \"sha256\": \"2e18d6cb6d4664360063c50233401ae90248fa719e966238c709490f55a9147a\",\n        \"size\": 203030107\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8587_Weather10.tar.gz\": {\n        \"sha256\": \"f746002b526ba888ac9581f0a2ab0dca35a875ad427fb0a04bb1c5a82a2bebe5\",\n        \"size\": 190034360\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8589_Weather12.tar.gz\": {\n        \"sha256\": \"2ae56b651769e756b8548bf1e235282690a7f781415e283ce2221eaf608f67c4\",\n        \"size\": 202730327\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8595_Weather18.tar.gz\": {\n        \"sha256\": \"6bb9d15f1af522e3bc629fc934f026ae29df94b56854bee51b17218cdd83a8d7\",\n        \"size\": 278310220\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8597_Weather20.tar.gz\": {\n        \"sha256\": \"2d9b74893567f9bc3b12abe13b5962de333afb8809efe130bf053046fca444e3\",\n        \"size\": 194996954\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8600_Weather23.tar.gz\": {\n        \"sha256\": \"fcf3dd5d2858c81330f79208e7347965c50f9d3248bdf95a51fae72cd5526bd6\",\n        \"size\": 131819507\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8602_Weather25.tar.gz\": {\n        \"sha256\": \"ae3dcc22bdf33b5820ac56e2423a0411949f9e9f04722955ad08a1248ca70d55\",\n        \"size\": 232716160\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8604_Weather1.tar.gz\": {\n        \"sha256\": \"98618a98a5ed37fcee849859618faf9e9676c14dd417c809cb1a8a1bc7745964\",\n        \"size\": 268890161\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8605_Weather2.tar.gz\": {\n        \"sha256\": \"b1e8354efa801c01a473e29b2f46519399065fd0af872b93ec95ce73d2fc2b2c\",\n        \"size\": 291831999\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8607_Weather3.tar.gz\": {\n        \"sha256\": \"3b02f4f7abecf73d3a3386d5865cae7a206fb337f8c51af4f7a509359b8f8970\",\n        \"size\": 296105884\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8612_Weather9.tar.gz\": {\n        \"sha256\": \"9e0150cc08d87283310638d67329388be2ef3fa7e0ca43bdca2282deac75960f\",\n        \"size\": 137048948\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8615_Weather12.tar.gz\": {\n        \"sha256\": \"223c09e3e93a3e990f0ed719e66b53c2f7e82715f71661ef54eb089851d813b5\",\n        \"size\": 121323631\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8616_Weather13.tar.gz\": {\n        \"sha256\": \"f52ee0bd14a0b64af01118b9e8a6a9bae04d3f7e7c23474db0318420e3579044\",\n        \"size\": 205576438\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8617_Weather14.tar.gz\": {\n        \"sha256\": \"0cee616bef05ce958ccf2959ed84c1cd59bd42fa658de9d9c1c58912c230219e\",\n        \"size\": 232044420\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8618_Weather15.tar.gz\": {\n        \"sha256\": \"3dd7d71190c04dc6657b9fc6e491c5ab01346fad6f03ac3a49e5f1ae195b1109\",\n        \"size\": 183219671\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8620_Weather9.tar.gz\": {\n        \"sha256\": \"38dd6c21ac48facbf5faba87d049a5bd7e362cabf7e828f6c1594349ac7716c0\",\n        \"size\": 518472489\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8622_Weather19.tar.gz\": {\n        \"sha256\": \"771e11be201a8f184868f67f9b99b7fa465d0a3078008430f7040f9a57872851\",\n        \"size\": 741864209\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8623_Weather20.tar.gz\": {\n        \"sha256\": \"e86024f12fca74f924ae1e66bd2f9beffdf3acdded4911b52543da457e400ee8\",\n        \"size\": 104064753\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8625_Weather22.tar.gz\": {\n        \"sha256\": \"fa45a6361e5310ea414b94d532d3c1828367602d42d93a55c866240eb1c3b36d\",\n        \"size\": 175477811\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8626_Weather23.tar.gz\": {\n        \"sha256\": \"dccbe81ca34789d33e1fb8258cc19b164fc3679a0bb849b7c7dd2c87f58871b7\",\n        \"size\": 246992419\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8627_Weather23.tar.gz\": {\n        \"sha256\": \"463775341aa42e3ceaac2f6b52e0e8296d4412c55558f5532861bbecee92b52c\",\n        \"size\": 220247134\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8628_Weather25.tar.gz\": {\n        \"sha256\": \"827934e2e88a1cfb41214b011a820e593be59ca286b571340f248986507297d1\",\n        \"size\": 135817968\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8629_Weather0.tar.gz\": {\n        \"sha256\": \"464ac01041d88885ae67127c5151cd5aaf7f1064da7686a4080e0004748cf2cf\",\n        \"size\": 285049077\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8630_Weather1.tar.gz\": {\n        \"sha256\": \"7c3f2ea94c85d9a3d5448cabfca7e239054ca6064a3e6edca7c49f203430ad29\",\n        \"size\": 299768051\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8633_Weather3.tar.gz\": {\n        \"sha256\": \"a45be0404b17b742f9a82ce41341110c7473058f7e683d10266be59bfaef3355\",\n        \"size\": 226521502\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8638_Weather9.tar.gz\": {\n        \"sha256\": \"4516da7e26e471831391b6703c45b82d309ac0174dda2971ce8996431793b881\",\n        \"size\": 247046383\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8639_Weather10.tar.gz\": {\n        \"sha256\": \"57f34ded6b30b4746bf1669ba4125d0c0b095de17ab62d7a6ea2fa2c58b5f537\",\n        \"size\": 242971183\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8640_Weather11.tar.gz\": {\n        \"sha256\": \"bb58371951afb9f2da41ccf84b5e0c423aa701723339cbf387db2561a3cfef57\",\n        \"size\": 139702787\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8642_Weather13.tar.gz\": {\n        \"sha256\": \"8c329fb8210ab6a6e3f08287bf6da2aaa705294593876851d39985d4c6623c71\",\n        \"size\": 141046254\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8643_Weather14.tar.gz\": {\n        \"sha256\": \"87a69b9a89b871af4a8035ce49d924624e102b5cf4df7d3df8461a679c20cb2f\",\n        \"size\": 225684856\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8646_Weather9.tar.gz\": {\n        \"sha256\": \"6012d295fe20b74302a9efad3f9f82edffda41cb4a5f957f87d5ae8fdd49f106\",\n        \"size\": 184118168\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8647_Weather18.tar.gz\": {\n        \"sha256\": \"1c51b2594c0c0282bc9ae74c34cda4b25c5ee088dcf2a72df38e9f934f8d2935\",\n        \"size\": 118955629\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8648_Weather19.tar.gz\": {\n        \"sha256\": \"66f92f3381110549bac6c497cba819632893a1600fdaba93d5250bcd0bddf73d\",\n        \"size\": 209785887\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8649_Weather20.tar.gz\": {\n        \"sha256\": \"30383e48a496d803a7c37820c7594f71e0b3c0de31002e64b7fc412bb719e520\",\n        \"size\": 180671638\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8650_Weather21.tar.gz\": {\n        \"sha256\": \"4f2d56241adf6dc960b0de3d1d8f85e588d96442fe4377d8e240f073c8ccab8d\",\n        \"size\": 398620078\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8652_Weather23.tar.gz\": {\n        \"sha256\": \"c2de503f523ed54c1238b5fb9c28081972496f123a05a406e1a7f39544e75e24\",\n        \"size\": 222261138\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8653_Weather23.tar.gz\": {\n        \"sha256\": \"0ec2d4939ad8f2d7b6c95be2257d465c91c50544811177e2f5137e5b60d207e4\",\n        \"size\": 493654604\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8654_Weather25.tar.gz\": {\n        \"sha256\": \"6e3b7084b15677f215aee36cf5d0900305a3d4547997098ce4a2d888f19ec52a\",\n        \"size\": 231034727\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8655_Weather0.tar.gz\": {\n        \"sha256\": \"3399b5ac2461935d3d0b25139434a383cb258b0781feb3a2ad394f7451fe1e03\",\n        \"size\": 271606537\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8656_Weather1.tar.gz\": {\n        \"sha256\": \"e9b0b35f973cf01db26e3c823c05c1478fe45e2500080d49b76aa2f354ce0de1\",\n        \"size\": 283279769\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8657_Weather2.tar.gz\": {\n        \"sha256\": \"80bc7f94dfacb9f3e26d43b80ae14f9f13a9ad8f9c5da20c6371cb8b470460ef\",\n        \"size\": 176498819\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8658_Weather3.tar.gz\": {\n        \"sha256\": \"0f817cf75e317b94d481d1d5593f71c83f171dc7d5b13cc3f156738a6660bcd4\",\n        \"size\": 226434351\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8660_Weather5.tar.gz\": {\n        \"sha256\": \"6c85d9c91abc551c08351252a31de81372b0b8da2482dd027583d2343ba7b237\",\n        \"size\": 213452513\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8661_Weather6.tar.gz\": {\n        \"sha256\": \"ad0c03d9ac9877a858fb6b79ea84a0e0398da4a21d9918340a19aa1942b6a4c1\",\n        \"size\": 277236964\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8662_Weather7.tar.gz\": {\n        \"sha256\": \"e5e2330a67744d9e2bd798a9820d9513095dfbe644f282db38be8c9b5cf69ea9\",\n        \"size\": 282752546\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8663_Weather8.tar.gz\": {\n        \"sha256\": \"85c6441628541020a8fa605665337b419b6a4ce45851360ae8cb10a40c996c14\",\n        \"size\": 224033734\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8665_Weather10.tar.gz\": {\n        \"sha256\": \"0aa226dea859a6ee5ba2640d44728b4cb0273b07d38864ce69d0718d4d11d1b2\",\n        \"size\": 254778478\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8666_Weather11.tar.gz\": {\n        \"sha256\": \"87d66f333adc7114a0e214e34d1292c13e1f5ba5c489f6f07d80f5aa42dc5fbb\",\n        \"size\": 137743210\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8668_Weather13.tar.gz\": {\n        \"sha256\": \"81c41a0e0d582d8d7a2afb3ccb5ad8a49cab405450fa00c3a8c5294a604d4b5c\",\n        \"size\": 142334012\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8669_Weather14.tar.gz\": {\n        \"sha256\": \"6b4a8ad8ae7ebcb86c928ca17a724f990c5220e91dc9d1256a0e2454dcf327c7\",\n        \"size\": 252661988\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8670_Weather15.tar.gz\": {\n        \"sha256\": \"b9c9b7ec070fbc3c3b095e839f6b8ae06f564aca65dbc3fe4603154df83d265d\",\n        \"size\": 283162190\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8672_Weather9.tar.gz\": {\n        \"sha256\": \"77ede775dfa9d12b85c042935bae9bafd074a2998de93b2488c42ffabb6f5f21\",\n        \"size\": 194630478\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8674_Weather19.tar.gz\": {\n        \"sha256\": \"da01d8fcc9f5007324a6500ae233a59bdadbf8148110c6e521f4fbaa44782e8f\",\n        \"size\": 201052215\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8677_Weather22.tar.gz\": {\n        \"sha256\": \"cf9312beab4214a5ae66cc8954272325caf76e9daf07ccaaae08c6fdc441c021\",\n        \"size\": 180767799\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8679_Weather23.tar.gz\": {\n        \"sha256\": \"2126c9dd5563f55a6548fe8b8ec6c3867c3fafa488d362e65405d19b462bcb7c\",\n        \"size\": 516288232\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8680_Weather25.tar.gz\": {\n        \"sha256\": \"0b651d5b83f3aeedde909bbd4dfb0e33827c0f356d1e414f4ddd6ca0518e6047\",\n        \"size\": 165078073\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8682_Weather1.tar.gz\": {\n        \"sha256\": \"4acadea91455246fcd81972f69545c0506516c80e94ec00c94fc40a349e4e2e0\",\n        \"size\": 214383439\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8685_Weather3.tar.gz\": {\n        \"sha256\": \"36fe92c29a8a72c8fd1e34cd2c3edcbdc561a4653378b71f36e7dde4f69b3ebd\",\n        \"size\": 234230246\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8687_Weather6.tar.gz\": {\n        \"sha256\": \"678f22e77130d29450e1887f57fda2bcdfa0686067bddc66f90414f7efae38c6\",\n        \"size\": 317201035\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8688_Weather7.tar.gz\": {\n        \"sha256\": \"0d95df255d3526b8f9e622de5dcea227d0d24d91d41b3dcaf75d4f27b6be4fb6\",\n        \"size\": 311686560\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8693_Weather12.tar.gz\": {\n        \"sha256\": \"2f4e810a9a577095be61e1150bd57a66c6c5eec1ea60eb51e6cd124b73028f8e\",\n        \"size\": 288835121\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8694_Weather13.tar.gz\": {\n        \"sha256\": \"11287120bbc7d979a70b4ed7d7073ef4dcea8e1dd00049873e9b6c2450c06498\",\n        \"size\": 286567240\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8695_Weather14.tar.gz\": {\n        \"sha256\": \"70c354670d3578ba58829f72cd5056e53b1dc26abbfee18e3cbce9494f8b68f2\",\n        \"size\": 132332798\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8696_Weather15.tar.gz\": {\n        \"sha256\": \"4797f4cbb811d4044ebb70595c4be05035f778bd145e11f691a5552ad9cf854e\",\n        \"size\": 244481458\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8700_Weather19.tar.gz\": {\n        \"sha256\": \"c115ce8aeb1206593db7c03b19bb582cf4f120730f9568d36b56f9c7a798af08\",\n        \"size\": 193161862\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8702_Weather21.tar.gz\": {\n        \"sha256\": \"ea7f68de69e179b3f98a61d951c090f4420988d8abcb00dd3dc3b983cb90efb8\",\n        \"size\": 176800234\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8704_Weather23.tar.gz\": {\n        \"sha256\": \"8c0eda0942f325dbd347a2a730eed71d34ab79a12a65cab7780aa6ab3337ad91\",\n        \"size\": 178945381\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8707_Weather0.tar.gz\": {\n        \"sha256\": \"ec933fe6bd62721b8f7b0b49cb0648deb6f2ba6f91641b21873cca8da19fc2e1\",\n        \"size\": 261317089\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8712_Weather5.tar.gz\": {\n        \"sha256\": \"ada51fcd32bc499c16cf33c453be7907d13fbd1363654a34917a8224cde48ba4\",\n        \"size\": 162623685\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8713_Weather6.tar.gz\": {\n        \"sha256\": \"f3d62848e6834a1f0dbe398ff6d18b102aa252a59f4917e13bec2fd3b4f87445\",\n        \"size\": 267610644\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8714_Weather7.tar.gz\": {\n        \"sha256\": \"6969dca1b6595a71ffc524e8b2f4f4307f85886dced05be84872f0053291b469\",\n        \"size\": 204970532\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8716_Weather9.tar.gz\": {\n        \"sha256\": \"2e8ecdb9b75e96530cdd7bb4ba6cf7eee36431e8c7c4b2dbeb74e939eb202d37\",\n        \"size\": 161344853\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8719_Weather12.tar.gz\": {\n        \"sha256\": \"3ab800795b99563bc403fd7cfaab39bdfe3e410fcd35ba2818db9d1973c9f1c2\",\n        \"size\": 175847023\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8723_Weather8.tar.gz\": {\n        \"sha256\": \"690772b1f1399f1500336f5cf7730d95aaad0c18807ea9ab5742a09d172c1432\",\n        \"size\": 299685945\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8725_Weather18.tar.gz\": {\n        \"sha256\": \"c7c413da6b79dc04d59eb87b5c1ca9b85f86ebc8d387cfa26ff292724e27c1da\",\n        \"size\": 218526419\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8726_Weather19.tar.gz\": {\n        \"sha256\": \"4d5f7a89f2f741be28dfa81da3a5a79269d98f32067c43df89e53c21fefb200b\",\n        \"size\": 318815476\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8727_Weather20.tar.gz\": {\n        \"sha256\": \"db6db8b33fc0e46bef43cb83308ca57e96a3a817ed1df3a52b538d5ee7d98b17\",\n        \"size\": 184967508\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8728_Weather21.tar.gz\": {\n        \"sha256\": \"902423eb1ac1ff38014c90592b72a361dbad38990355816a9312363ff41abc63\",\n        \"size\": 205982161\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8729_Weather22.tar.gz\": {\n        \"sha256\": \"b8df1896c6e2680ecd22b09d844c4363baf09fb8570a4de9009db30033670f22\",\n        \"size\": 208172018\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8731_Weather23.tar.gz\": {\n        \"sha256\": \"88f0c945cd74c6053ec9f086b0a82af79ec5336eeb356520123f954ba6802a3b\",\n        \"size\": 236071655\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8732_Weather25.tar.gz\": {\n        \"sha256\": \"529bfb5b89854f313ee433072b5a473e95dc229c972923df1a590d76d7b44824\",\n        \"size\": 147972629\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8734_Weather1.tar.gz\": {\n        \"sha256\": \"2beb7a03b13a96719ffd22587e961347781c53df43628dee98ca6fb19bba3c38\",\n        \"size\": 223692686\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8737_Weather3.tar.gz\": {\n        \"sha256\": \"3ba5597e443ae7d54448241ef7053ccf076758af2743631dd49f36831549406b\",\n        \"size\": 202955535\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8738_Weather5.tar.gz\": {\n        \"sha256\": \"a8c25d1401f6e1d093df39bd5da6bf21c51bbeb2f22e02ad225c7cb9fe738952\",\n        \"size\": 299110342\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8740_Weather7.tar.gz\": {\n        \"sha256\": \"1c371a759ba414f358b63fe59a3644237276b9b9293c7413511a39ddbc58a8d5\",\n        \"size\": 226924277\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8743_Weather10.tar.gz\": {\n        \"sha256\": \"b300b80a69f90428c7dbec12b8b83defa5cb20be1b19a650ba65525984541ab0\",\n        \"size\": 261038454\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8745_Weather12.tar.gz\": {\n        \"sha256\": \"1bc08ec5ba1385617e72fd36e6fc6d2f7ba9d8127f99824d285fcdedf10dc642\",\n        \"size\": 181815090\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8747_Weather14.tar.gz\": {\n        \"sha256\": \"af30389f3e9b36129948663a33f8ea40e846618a6f923022f1df655ddce4cf10\",\n        \"size\": 325332403\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8748_Weather15.tar.gz\": {\n        \"sha256\": \"ce2e4dd2df211e9f0e1b399c30214e61cce2396c660edcdd0f8d4462b92a59f9\",\n        \"size\": 277805118\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8749_Weather8.tar.gz\": {\n        \"sha256\": \"e5886774a13fdf14f8a69290f1c25962632786f4168826f48295809399157161\",\n        \"size\": 239433668\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8750_Weather9.tar.gz\": {\n        \"sha256\": \"ef53308b4c7395708ca855612aec7245c7142733b75d77795882e0872105f2a9\",\n        \"size\": 229750594\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8751_Weather18.tar.gz\": {\n        \"sha256\": \"cc9cf75da6fdde4f8d051184742d7870ddf4477b90ddd1b56a7d92ea66a056ce\",\n        \"size\": 212770876\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8752_Weather19.tar.gz\": {\n        \"sha256\": \"710a3973611c90d9ed2bfb61fb3533f488693fca25492e3cd419d15da40f2e04\",\n        \"size\": 251159499\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8753_Weather20.tar.gz\": {\n        \"sha256\": \"4c36da7311ad3bb1c5974a7e402e071baaf16eae4454c986e89d6f7320dd31e8\",\n        \"size\": 189654365\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8754_Weather21.tar.gz\": {\n        \"sha256\": \"39c9b10b8a30476e05a5896aef012f4235a8cc387a2a503f4d3bd34294e2d2f8\",\n        \"size\": 195795155\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8755_Weather22.tar.gz\": {\n        \"sha256\": \"ca371ec2c9764262673496ce6d48c101446429771f476a1070f8cfa5e82913ba\",\n        \"size\": 162393288\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8756_Weather23.tar.gz\": {\n        \"sha256\": \"f0c7b771b343dee92d594ad3e2086201ddad1d685773629ebeca02b320ba405d\",\n        \"size\": 138042047\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8757_Weather23.tar.gz\": {\n        \"sha256\": \"96010e63b45e847f94e68907132cf7aa7176a577089ab1d66e2425ea9621bc30\",\n        \"size\": 223816463\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8758_Weather25.tar.gz\": {\n        \"sha256\": \"68f52a79333e1a42a453c59e98f05f9e0ecfcf5c24946ddff53bc2cf16ef6ce0\",\n        \"size\": 184550042\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8762_Weather3.tar.gz\": {\n        \"sha256\": \"92ee2d30eae4a38efe071eb063cf68c1b25e1d02050fcd15448396bb4021cff2\",\n        \"size\": 251842675\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8763_Weather3.tar.gz\": {\n        \"sha256\": \"d24e43e926520156f71b6f0c91586492acb0e07d166b7702b8aaddd1240801de\",\n        \"size\": 193168307\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8764_Weather5.tar.gz\": {\n        \"sha256\": \"fac9d64decc6a19267dfb7ecffcff4f4bc86c9e0aa32c9feb0cb94be726359c8\",\n        \"size\": 227127059\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8765_Weather6.tar.gz\": {\n        \"sha256\": \"068a95b5846eaf6d63300c061efab004e2d541611148aa78b919d6f6403b6334\",\n        \"size\": 287393043\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8766_Weather7.tar.gz\": {\n        \"sha256\": \"37a58be9a715050c5fa23ef70658cba4968b7acad78bc745a0499157d804ac44\",\n        \"size\": 277726874\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8767_Weather8.tar.gz\": {\n        \"sha256\": \"7e3260288599307287d511788cb3e46c0311c02543737e6ce8a3f155f21a5d38\",\n        \"size\": 174256353\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8768_Weather9.tar.gz\": {\n        \"sha256\": \"e6fcec5f4ed753894be51208d5557438ae50b429d6c3718629fda8ff0ffc59b4\",\n        \"size\": 230155088\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8769_Weather10.tar.gz\": {\n        \"sha256\": \"399c17a0812ccbcf6c634a57670bdbcfa76237f9453c6ce47810e6b9cfb7274c\",\n        \"size\": 258245402\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8770_Weather11.tar.gz\": {\n        \"sha256\": \"d1956a8abf9853c7ab4e7b6eb2b0f9dd9095d2110560cc3f8bff67734fc67eff\",\n        \"size\": 75338929\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8773_Weather14.tar.gz\": {\n        \"sha256\": \"bba6e4dbf8fca134bb09899799efd1fdaa2bb6017089d3aa4aadcd27f29975b7\",\n        \"size\": 123456284\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8774_Weather15.tar.gz\": {\n        \"sha256\": \"3ec2bd32fad9f457b3a93becc53281b235fe061ca98f9eeaac8c89beba67cd39\",\n        \"size\": 203415031\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8776_Weather9.tar.gz\": {\n        \"sha256\": \"a15f233d223ef7de888c61fcde3c1981147adb1149aedf839546f199025314f8\",\n        \"size\": 188984148\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8777_Weather18.tar.gz\": {\n        \"sha256\": \"779da89d30efb11b433525e49edd33a9aaa9eaf68a6e26f996604ecc0e48fbd6\",\n        \"size\": 251340855\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8778_Weather19.tar.gz\": {\n        \"sha256\": \"96ff2e1fb67deb0f3ee9bd4f386c8533a679365e56a8dc3aa16a033431ad02a7\",\n        \"size\": 236413725\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8779_Weather20.tar.gz\": {\n        \"sha256\": \"1833c1e7dd77722bde20d3ac4c04e431acdd60aae490c4468efa75b50d5e8647\",\n        \"size\": 145426196\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8781_Weather22.tar.gz\": {\n        \"sha256\": \"ae1cd5b44d3e29b64b14e160d762042c946d8498013cc6aa752fe4df9e1c52c6\",\n        \"size\": 118708813\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8782_Weather23.tar.gz\": {\n        \"sha256\": \"fed0344ca92dc66444728b3db928b477e4b84508c956a8780a74cc52f480d354\",\n        \"size\": 192918644\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8785_Weather0.tar.gz\": {\n        \"sha256\": \"1d78f93848a8fee30ce506eec9b1bb3d0340fd319ba2114f3a5156c24874abe1\",\n        \"size\": 423768297\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8786_Weather1.tar.gz\": {\n        \"sha256\": \"00aa3d50eda053b3aaeab1c0bed859628c59223e41c9bc00ac74824f18b74939\",\n        \"size\": 454736999\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8787_Weather2.tar.gz\": {\n        \"sha256\": \"452a1eca727cf1fbf52faa2948ef557141c4b91d7a007f3ddf45b93a110340c5\",\n        \"size\": 804750125\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8788_Weather3.tar.gz\": {\n        \"sha256\": \"33cc1db31f040e633e1387185a7999e72a5cb50b56fe4b3194a1164180c1b7b9\",\n        \"size\": 155525890\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8789_Weather3.tar.gz\": {\n        \"sha256\": \"7ffeba016e7a0405399e3b053746a249816c683e5b8648b8fa12b100c57a63e9\",\n        \"size\": 227802398\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8790_Weather5.tar.gz\": {\n        \"sha256\": \"53e8268901a81f7dca2f31f0abe6f744adee7e4a6a3c04b01fd1bbcb23c692de\",\n        \"size\": 322295728\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8791_Weather6.tar.gz\": {\n        \"sha256\": \"e08f445b55d2092b0d5ec63ebb153257026d60cdeb6e489dc68a30564b59ad70\",\n        \"size\": 222972534\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8792_Weather7.tar.gz\": {\n        \"sha256\": \"eb4a2b0999a89ea278628dd5ed6f3bbebb2db19376825590fda6b7132107f25c\",\n        \"size\": 269604133\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8793_Weather8.tar.gz\": {\n        \"sha256\": \"164de98c25e8febbaed14647b78e934884cc47754d8161b4194fd6daa9c19eec\",\n        \"size\": 234954993\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8794_Weather9.tar.gz\": {\n        \"sha256\": \"a3f25ed8972630e0bcc7d655d2fec7eaede0d15f2455bae76b9f21b8f94098bf\",\n        \"size\": 276564212\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8795_Weather10.tar.gz\": {\n        \"sha256\": \"f492774a2c4175b18fd52befa0af66bad32528d6e951cc8f8157e24b93661791\",\n        \"size\": 184246496\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8796_Weather11.tar.gz\": {\n        \"sha256\": \"0e26a5a3bdbfae96fc6f9952328a22a08031738d0d77c6871bb41537a4fcc7c4\",\n        \"size\": 126766508\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8798_Weather13.tar.gz\": {\n        \"sha256\": \"5eab8a9cea20ce67dfd771811fb76401772fb55ebfbf9de8fa7c5f207203affe\",\n        \"size\": 249658744\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8801_Weather8.tar.gz\": {\n        \"sha256\": \"b1326883ee13cae54a169d4eafcf96de2158d5d5107dfea7bd117f15eb770c0a\",\n        \"size\": 189953818\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8802_Weather9.tar.gz\": {\n        \"sha256\": \"56b97d620987b14e0e72d105ba34648ad4ea4fa02bf8b023b648675b65cae1a0\",\n        \"size\": 328390824\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8803_Weather18.tar.gz\": {\n        \"sha256\": \"164cf7cbbe9f5b2a0dcd1ec1ce776c562fb7e5f5ce230f99d4d289dfa69f2f09\",\n        \"size\": 254707136\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8807_Weather22.tar.gz\": {\n        \"sha256\": \"ff718ababac0007015683fe2e8b3dd68142046415d4e0fa5f3141bc64464621b\",\n        \"size\": 188060074\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8808_Weather23.tar.gz\": {\n        \"sha256\": \"e0a312311ce58f2050795c8d48284fe2324e05dcdd0bd0eea6e39e50e51cfd56\",\n        \"size\": 181110396\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8809_Weather23.tar.gz\": {\n        \"sha256\": \"94523bf8afcf5e1386ae3249dee57950848e81342812ee5726b7f3e35d354f9e\",\n        \"size\": 231109233\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8810_Weather25.tar.gz\": {\n        \"sha256\": \"6956563dcc4faf59dcd8ab1e65323ecfd24548a575b8af415cf5a59ea39154a4\",\n        \"size\": 219944498\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8811_Weather0.tar.gz\": {\n        \"sha256\": \"a9c0ec154ade2db742f7a06b1e508f19ab37dae181d1b161f61ec59872d30d65\",\n        \"size\": 331686064\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8813_Weather2.tar.gz\": {\n        \"sha256\": \"2d6d7547de357fc4d99bab777563fee20e99c236380385f7f06abaa25d9c706a\",\n        \"size\": 335614219\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8814_Weather3.tar.gz\": {\n        \"sha256\": \"57eefde61fc8bf4dc6b0c10b9422d5e366fc301a970e74ee45664ee2598000f7\",\n        \"size\": 220003932\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8819_Weather8.tar.gz\": {\n        \"sha256\": \"0d5444a133080212574e0d12615e1a61ba1301347ff62654d8717eca4d782a44\",\n        \"size\": 201841841\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8820_Weather9.tar.gz\": {\n        \"sha256\": \"5b3a127d0bef32a36f84ad9106e81719eba805011311d400bb9b5c54f80e0a40\",\n        \"size\": 297068729\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8821_Weather10.tar.gz\": {\n        \"sha256\": \"e99ffe16dfb885f736da024e0c432610494c8146e56c579435222ad1e4ecdac4\",\n        \"size\": 113323808\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8822_Weather11.tar.gz\": {\n        \"sha256\": \"ba40ff30a9ac40e937eebdeffb8dd352a165c035724671e5d4feabe4c9e14e38\",\n        \"size\": 139798833\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8823_Weather12.tar.gz\": {\n        \"sha256\": \"c92857a0bf90df69d570f171377a9888f1d7ecd177b753ab72985d55fe9e8a83\",\n        \"size\": 123860620\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8824_Weather13.tar.gz\": {\n        \"sha256\": \"71d141b6ff3d36d162c4092e86013cdcb103b7bb75f795c9212b9eee0cbef495\",\n        \"size\": 246023332\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8826_Weather15.tar.gz\": {\n        \"sha256\": \"e9348095270dcaab2905ffe59f25e65601245e3e183950f9b97f0fefeb472a8a\",\n        \"size\": 242539483\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8827_Weather8.tar.gz\": {\n        \"sha256\": \"c30c3cd54edb6ba1c49ae2691df22c15a4b34e2cbe59c2f34cd508d0a7e7d505\",\n        \"size\": 200126404\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8828_Weather9.tar.gz\": {\n        \"sha256\": \"d0813d599f3fad69620985c1b334b77873c924e9ad2d875e2f0b019e5eca9398\",\n        \"size\": 184655091\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8830_Weather19.tar.gz\": {\n        \"sha256\": \"a8772b4c02295bdd9c69057ddb19286a2c20f840c708d645f644d0cd84fccca7\",\n        \"size\": 262160757\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8832_Weather21.tar.gz\": {\n        \"sha256\": \"a0c18bee0b805d202dc84df263b880a001ea9c487c5277e8a671a344d29f5778\",\n        \"size\": 165337269\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8834_Weather23.tar.gz\": {\n        \"sha256\": \"630a8fadf8781202e2c75598db00553ae69caeb6fd63ade2db7ff04ec9a7f07a\",\n        \"size\": 241799267\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8835_Weather23.tar.gz\": {\n        \"sha256\": \"29fa70212595900c166e2c91f319dda05dcd8c4ed9722208b339313d4d7231af\",\n        \"size\": 210528610\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8836_Weather25.tar.gz\": {\n        \"sha256\": \"863a0b7356f6191eebbde9fdbb9e818e842b38bbdcbaabb3ad6bf5738fcf75d9\",\n        \"size\": 188637581\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8838_Weather1.tar.gz\": {\n        \"sha256\": \"668ef191930d07edf1ec993a86f4388eb3e5c3a05ea0d8afa1427bd07f7b7218\",\n        \"size\": 200448082\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8839_Weather2.tar.gz\": {\n        \"sha256\": \"72dbd4b050dafe5f3242a5eb3be29f8f700312b45204f054bb9d4b72b55d36f0\",\n        \"size\": 98514855\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8840_Weather3.tar.gz\": {\n        \"sha256\": \"dd3692138a0294dd72869c284dcaee6c9b590f5c3047a5ad01e1405b33cb8ed1\",\n        \"size\": 217244555\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8843_Weather6.tar.gz\": {\n        \"sha256\": \"287eb64f22301422ed6c5a0ffdece435ab2f6c199d3d2892f994a77ddbbe085c\",\n        \"size\": 219881212\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8844_Weather7.tar.gz\": {\n        \"sha256\": \"7bda6ca1bc2ffb43252735cf8704e5abee93a90ed766c3f277d6680fbfe98e26\",\n        \"size\": 307856242\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8845_Weather8.tar.gz\": {\n        \"sha256\": \"0aba22ab7396e0f81a3da007dbb877eccc7b7657b0a2ec2ecd4e93a4b186a657\",\n        \"size\": 286784182\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8846_Weather9.tar.gz\": {\n        \"sha256\": \"7647bb19b2b165cac74a04974fec8b1f713fae97f351a759f8932152a48bdf7a\",\n        \"size\": 209990076\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8847_Weather10.tar.gz\": {\n        \"sha256\": \"98ddb4d4648cae28ccef0c6239b105096ed42eb51f745d23dac7ea6e7e05247a\",\n        \"size\": 210474457\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8849_Weather12.tar.gz\": {\n        \"sha256\": \"86def11a93e81c44f5f46c477ebdab9bda1a956e0551ea7b6d8bd77181b5e37f\",\n        \"size\": 162328332\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8850_Weather13.tar.gz\": {\n        \"sha256\": \"dd54beb229db6a77ee55ad48bcc33abb3c91f9aef28a837e2aafbaa1ac08c0b3\",\n        \"size\": 180958326\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8851_Weather14.tar.gz\": {\n        \"sha256\": \"b8c5595c282b50914267043f6ba4035792d6db75e3d344c1e15c52bdb88a4828\",\n        \"size\": 150654455\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8853_Weather8.tar.gz\": {\n        \"sha256\": \"b5c32ef21cbb072a445ac862310ae7b5915cd7ee82c50968f0ba7ea230f3074c\",\n        \"size\": 263893003\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8855_Weather18.tar.gz\": {\n        \"sha256\": \"5d123d4e5db2b3fbae9aa1a35dda3b07bf2bcfdec28fc7f6c02ba620c6213106\",\n        \"size\": 224202989\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8856_Weather19.tar.gz\": {\n        \"sha256\": \"6c5d366a62ce3840c82ebd00891121e28ccfd5ed0f0a5ab20be4562e5f3d171e\",\n        \"size\": 128351135\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8857_Weather20.tar.gz\": {\n        \"sha256\": \"b6549589cca8e387639b205be770e3d1738d895031cd2425850584b0994c701c\",\n        \"size\": 322076984\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8859_Weather22.tar.gz\": {\n        \"sha256\": \"44a6fd3befbf4315add71d60a3cd7bb17d23b09f5e14c577998c93e71c91864e\",\n        \"size\": 254964936\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8860_Weather23.tar.gz\": {\n        \"sha256\": \"2fa3146d2350371052f027623876a76c3f69ddea500ad9d37cb4942c4556458d\",\n        \"size\": 254710628\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8862_Weather25.tar.gz\": {\n        \"sha256\": \"5d4d083a23dcd744ec5ffaa23d816364a6a74b17fb82f61584b287e412f91003\",\n        \"size\": 199863340\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8863_Weather0.tar.gz\": {\n        \"sha256\": \"7c28220452380ad05046c56d6884d1c160763b90b01060ef9f4fac8f9892f316\",\n        \"size\": 331361647\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8864_Weather1.tar.gz\": {\n        \"sha256\": \"05e1f0bfb3fc5f62011194f901ba7d1f7ca4376f1805ddc6ca4910500901f26e\",\n        \"size\": 253011529\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8866_Weather3.tar.gz\": {\n        \"sha256\": \"ea45a11488cacb2e19384eae92f93355c71e7c7ec33f64c6d144795695d6dcc2\",\n        \"size\": 273119231\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8868_Weather5.tar.gz\": {\n        \"sha256\": \"14dda6849dc3dddbfabaadb706b509aeeba3ee341df6601820e196ca0a134dc2\",\n        \"size\": 168588105\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8869_Weather6.tar.gz\": {\n        \"sha256\": \"c4b2ba6b7444158124ecbc863c8aaca841e01987ea5ca56713abb8a0de7fc3bc\",\n        \"size\": 214956867\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8870_Weather7.tar.gz\": {\n        \"sha256\": \"9b8a8cc987fc3f4fbbb3f77b2caea9ab441087346e3cfc882186e327165e4a96\",\n        \"size\": 217692160\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8871_Weather8.tar.gz\": {\n        \"sha256\": \"b0a458f3616412310ffe0d0a7dfc5113a18db091951ce6a4ba9177c01050ce92\",\n        \"size\": 274380774\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8873_Weather10.tar.gz\": {\n        \"sha256\": \"4907960a9476e164d0dda37685c96bc643ccf83826e20b0d8a52dafed6e0a744\",\n        \"size\": 135601107\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8874_Weather11.tar.gz\": {\n        \"sha256\": \"6f801282730d9bce170cf1bd35cf28b809a4493c94c8384e1036264ae92354b1\",\n        \"size\": 146758197\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8876_Weather13.tar.gz\": {\n        \"sha256\": \"023fb493726ecd3d93d8342ffd9ddae148967499b879a1b9da31f58b6dcd0e29\",\n        \"size\": 227269703\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8877_Weather14.tar.gz\": {\n        \"sha256\": \"53bc5c7ef2398c0291d80fad921728541789d27aceaaf8f32fbc561a375f2cf4\",\n        \"size\": 207293959\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8880_Weather9.tar.gz\": {\n        \"sha256\": \"fd3b9ec8b163d510cb1c38ceff9a2c709028bd5e0dec2e9ceebaf4775b3fae0c\",\n        \"size\": 150194791\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8881_Weather18.tar.gz\": {\n        \"sha256\": \"447b47df8305a58140f49cd5462f49c84240682429913074ab58f99951eac27a\",\n        \"size\": 217632113\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8888_Weather25.tar.gz\": {\n        \"sha256\": \"9b95d5a064cd44a6b02df755c35d1f36bb9f212050b5501f791b70c2268c2688\",\n        \"size\": 151585112\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8889_Weather0.tar.gz\": {\n        \"sha256\": \"db6868f003cea39a94c610492f20b26b412ef1103e1b277760976b02b8fdef23\",\n        \"size\": 249948871\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8890_Weather1.tar.gz\": {\n        \"sha256\": \"a88a943c2a162674af957541223e35548fc2b8ef629b305a4c56f5154609fa8b\",\n        \"size\": 401176141\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8892_Weather3.tar.gz\": {\n        \"sha256\": \"c828ee7f65dbe70165279b40f2c9794e61a8e88c17c9363b58c0dee889d2f5bc\",\n        \"size\": 231013788\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8894_Weather5.tar.gz\": {\n        \"sha256\": \"6f308423e3b65c417250bf21bc75319ebbefd6abb7854ce65f64fc1827efd2a5\",\n        \"size\": 256103798\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8895_Weather6.tar.gz\": {\n        \"sha256\": \"8f0ace3d6edb63186214bd01a30a8f70995a134aaeabae202eca8e7a853d6b3d\",\n        \"size\": 189164421\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8897_Weather8.tar.gz\": {\n        \"sha256\": \"11a9164b3cc7865e4cfaa01abca525f6586d0743c212b1e4c6ce7948337f6f20\",\n        \"size\": 168028422\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8898_Weather9.tar.gz\": {\n        \"sha256\": \"4f86794644fea7b09579d1ba20faccc2b922bb8363d9395da39ae1fda341c5b3\",\n        \"size\": 260285246\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8899_Weather10.tar.gz\": {\n        \"sha256\": \"74daa19d2fe04e8f68f6103033346c65cddaa3118b0c1e943e1d062a6a9a1bcf\",\n        \"size\": 224877653\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8901_Weather12.tar.gz\": {\n        \"sha256\": \"0ba3f96b08e796ffdd266939fa7aaf777b9746d441bbe958a903e3679650283b\",\n        \"size\": 313285965\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8902_Weather13.tar.gz\": {\n        \"sha256\": \"82ec2a41fddef217e2f32cf6a495278b33167a96fd943693af56cde6a4421791\",\n        \"size\": 228066431\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8903_Weather14.tar.gz\": {\n        \"sha256\": \"d520e46e0ab13eedb2bd948ed0182510fd9649b59225bf10a9452ddc75c36269\",\n        \"size\": 234689960\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8905_Weather8.tar.gz\": {\n        \"sha256\": \"cc9f046c2f2672871a6e583aaff7b61b4f26717d7564c5169c66577748712bcb\",\n        \"size\": 121967358\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8907_Weather18.tar.gz\": {\n        \"sha256\": \"f3d8de5f50bd31d4946ed97bc10524b2598656ee44b5c51e487010cd88092d03\",\n        \"size\": 328187827\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8913_Weather23.tar.gz\": {\n        \"sha256\": \"7543ddfe138e86e8875f1b1d4cf9d5f6c8e91424043962e23efa51b431b2375c\",\n        \"size\": 173262009\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8914_Weather25.tar.gz\": {\n        \"sha256\": \"74f36b3a7b5b3da78742f750246116f72edd211efa2c83c4dbc569cc401066d7\",\n        \"size\": 210331545\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8916_Weather1.tar.gz\": {\n        \"sha256\": \"766eb5df99caf809448230eaf039e1795a10491fe6a03cffe47e0c6e1bc40da1\",\n        \"size\": 105758999\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8918_Weather3.tar.gz\": {\n        \"sha256\": \"bcea196d88d9b2858819c3dbdbd25168b53750cbf44a8d85f049b4e64f783a25\",\n        \"size\": 122283420\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8920_Weather5.tar.gz\": {\n        \"sha256\": \"58c443b2d5c492cbdd8c1e7333a0da2e1907bc7b3781b6145ba91960967a234e\",\n        \"size\": 298948610\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8921_Weather6.tar.gz\": {\n        \"sha256\": \"cb4e61eb4cff6889ae037a23c0269ef7e2256805bdbc325fc6ca8c8fb29ef8c3\",\n        \"size\": 218003146\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8927_Weather12.tar.gz\": {\n        \"sha256\": \"e6a8cc42538fb60c032473657ad5931e1ff1a7dfd2735e462b26e31adeb16eb1\",\n        \"size\": 226161403\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8928_Weather13.tar.gz\": {\n        \"sha256\": \"b1f0f7ea8c4ffaca3dfc0da705287bae687550a28e69522934cacb54ccf22d0d\",\n        \"size\": 288251769\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8931_Weather8.tar.gz\": {\n        \"sha256\": \"5099a69013abaaa1c4285d68a27c2018cfd62f50ae45ffd69edae4d02eed329f\",\n        \"size\": 284970002\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8935_Weather20.tar.gz\": {\n        \"sha256\": \"d12c9f57aeb5bc3da8f5fe989b8e3df9a9149e2b3e703d3dc2156e48fb1b39f8\",\n        \"size\": 159116192\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8936_Weather21.tar.gz\": {\n        \"sha256\": \"296f9b42e190a210f1159b1e44617838782532fea7a8531a2341b84fd1409ddc\",\n        \"size\": 209000627\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8937_Weather22.tar.gz\": {\n        \"sha256\": \"46d01c77f5f15201f92271740aa0233055b839f2542ed012b67214017c6d6261\",\n        \"size\": 400712854\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8939_Weather23.tar.gz\": {\n        \"sha256\": \"9d3b50e7a9db660c4d708dcbee23d9997a2fe36426a2f90c12ff42f2e7fa24c3\",\n        \"size\": 145698305\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8940_Weather25.tar.gz\": {\n        \"sha256\": \"d79a9116761e23d6f6bfdf4a603cbd41187bd6aac59a4a5717af47553f826982\",\n        \"size\": 267304184\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8942_Weather1.tar.gz\": {\n        \"sha256\": \"bffe7f5d3e1898e360e4d8ad1e4377ba2c873b2b80851c3d868f80ad054fb384\",\n        \"size\": 273498413\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8943_Weather2.tar.gz\": {\n        \"sha256\": \"c461307df8bfe02559b7d701bddf4d222b9956d0d05bd4d039689ab3915efdd5\",\n        \"size\": 236322101\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8944_Weather3.tar.gz\": {\n        \"sha256\": \"b5c6fcf67c7d8097c123bb0bccb1a4463592fb86f4c9669aa716343be6a18e31\",\n        \"size\": 236951364\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8945_Weather3.tar.gz\": {\n        \"sha256\": \"e5653adc03dd36ff2a36f14a729cec92a14112889d5943d104a2a97a47fa3c97\",\n        \"size\": 292857134\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8947_Weather6.tar.gz\": {\n        \"sha256\": \"b5fa739cd124b2d48be43bdf7712615bf6dcb6e810826742fcd5fd7a851e08ca\",\n        \"size\": 273616520\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8948_Weather7.tar.gz\": {\n        \"sha256\": \"f8ce4f62b554c112aa62cedf694d8b6ac8502b9de579f0ec22f3300f128ef424\",\n        \"size\": 241026394\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8949_Weather8.tar.gz\": {\n        \"sha256\": \"aab16f74dc0413d164a6fc0d9ccc7f9e69e2c84eb7b79778d32ca0c62a058335\",\n        \"size\": 195381042\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8950_Weather9.tar.gz\": {\n        \"sha256\": \"3db8cbde7d4a4969ee2751b46fcb69c5347fb5a19eeff94fe415bf398b9901dd\",\n        \"size\": 165071910\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8951_Weather10.tar.gz\": {\n        \"sha256\": \"21b3b9c27d99c2e222758d61154d1cfdbdace6f7b36880165417095c8d19d07f\",\n        \"size\": 221264133\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8952_Weather11.tar.gz\": {\n        \"sha256\": \"b28ac9b7f8c391e27822f90d230e6e5a0803ea15d91138a0ab5282e4bd3485ce\",\n        \"size\": 158274639\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8953_Weather12.tar.gz\": {\n        \"sha256\": \"4fd0bae9f9c3b175f7fd7d2433a250915e66ad3bd80d7ba17531e8658bdfbec5\",\n        \"size\": 200322266\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8954_Weather13.tar.gz\": {\n        \"sha256\": \"78ba263e22c0a0bcf0fb60975906f4175cf39ca19b02cd26f2297e01a66c39c2\",\n        \"size\": 238020857\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8957_Weather8.tar.gz\": {\n        \"sha256\": \"af02e586871f24c3e8901f634e55f45a32b50ee77ac0ad21c1e83acd582b064b\",\n        \"size\": 669896231\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8958_Weather9.tar.gz\": {\n        \"sha256\": \"d1fff34baadaf9cc5830cdab6bc955c80336f82d88a9635567e24f2905bbbbbd\",\n        \"size\": 92581067\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8959_Weather18.tar.gz\": {\n        \"sha256\": \"09d0c400b3f97b83c8b6ed1eb2554ccdf9334c3e5f0bbd74c976fbcff46e1b33\",\n        \"size\": 211423073\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8960_Weather19.tar.gz\": {\n        \"sha256\": \"534ff1a54559c65b2b4cb7d227cccddd0d90e3077494ad9e7446a0e6637a8169\",\n        \"size\": 177092921\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8961_Weather20.tar.gz\": {\n        \"sha256\": \"5105cc76cb95cd95a4fecad4443c909b73f52e595cd4ecb0da355df019e7f037\",\n        \"size\": 230138683\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8962_Weather21.tar.gz\": {\n        \"sha256\": \"0b740f16ab40c80a200f1d1223396cf945ba9ff0bddd831eef9471059feaac5b\",\n        \"size\": 186750006\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8966_Weather25.tar.gz\": {\n        \"sha256\": \"ccd53a3b87f3b1f6d499549cea61dcf014773284a06c38a4a9937dadcee8160e\",\n        \"size\": 148849362\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8967_Weather0.tar.gz\": {\n        \"sha256\": \"4c8b4f100e91601469e41b4d6e6324826ef70fa147ab1016edd625675056afcb\",\n        \"size\": 280533844\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8970_Weather3.tar.gz\": {\n        \"sha256\": \"9b90aaed45ca4ae307555d7502437bac4e50aae5766cd9da8a87131e4f86144d\",\n        \"size\": 100481497\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8973_Weather6.tar.gz\": {\n        \"sha256\": \"2f6df562fdcaf365d7e06cf2d169ddcabd17e717e635b34fd85180af41dee7a6\",\n        \"size\": 212018978\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8974_Weather7.tar.gz\": {\n        \"sha256\": \"ada9c9ad7c31c51044fdb6e773962eff1b0ef4753a8cc60f2e613c7c63b545c7\",\n        \"size\": 208804391\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8975_Weather8.tar.gz\": {\n        \"sha256\": \"40825b31c87277c627fc1628b8a5a7da286abc306fb17c2735de13aed7d919c6\",\n        \"size\": 213941668\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8977_Weather10.tar.gz\": {\n        \"sha256\": \"c7907231c008c424ff032c811ae235e1541cf1b4c4094648fdca1f9ed242dea8\",\n        \"size\": 202468079\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8978_Weather11.tar.gz\": {\n        \"sha256\": \"881cf80cdadc211b832e0b2901f6e0f5da868c353c7b1efe5cd70b7e46b20ebe\",\n        \"size\": 173034580\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8979_Weather12.tar.gz\": {\n        \"sha256\": \"bd676dbd76824f5e014a5ee8e88855f4ed03489c22ac8128f0d41c462dba3afd\",\n        \"size\": 220071923\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8981_Weather14.tar.gz\": {\n        \"sha256\": \"a06d11e4768885892b27090caac958bb258440b840cb00d11dc76907131f34bb\",\n        \"size\": 229833369\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8983_Weather8.tar.gz\": {\n        \"sha256\": \"69a664bdd1150b5e6d9632281257145d0aef0e99b77178312fbc6de487ea6a17\",\n        \"size\": 154406427\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8984_Weather9.tar.gz\": {\n        \"sha256\": \"c90b22d5ddb92c2480c5767983f8cb963f79fd688b5559ebde9b067c3c6f04e5\",\n        \"size\": 157676461\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8985_Weather18.tar.gz\": {\n        \"sha256\": \"964d82bb1f972a411072de33d6fb93ef08b4992a1bbf7246f25d27d78ee1ad92\",\n        \"size\": 197009140\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8986_Weather19.tar.gz\": {\n        \"sha256\": \"20a4b7d87133c4aaf913721acbaa03d5e21973da6ba0b6d3b8af248ed1f9a481\",\n        \"size\": 190988675\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8988_Weather21.tar.gz\": {\n        \"sha256\": \"45db8710956ee48f1fdf38b5c29af0d11d8175f901993f8875f897e5f29149b8\",\n        \"size\": 130901890\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8989_Weather22.tar.gz\": {\n        \"sha256\": \"47cb31caf783348bd8049c19e16d076449360b8d359d02be26e6fa39224d766b\",\n        \"size\": 152300056\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8990_Weather23.tar.gz\": {\n        \"sha256\": \"adcc6b3ab5b9b896debd4da4d2857dae9f5cdf62fb1859c1ba5eed5531f684ae\",\n        \"size\": 147232506\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8991_Weather23.tar.gz\": {\n        \"sha256\": \"f3ac68ecfae697385808a00317a6a3f318e3b1c856eb920c1dcc82fbc373cbdf\",\n        \"size\": 208606333\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8994_Weather1.tar.gz\": {\n        \"sha256\": \"473b55ccb90120fdb475394bbcc461dc8171c9568321d6d1bcc0fb7073633924\",\n        \"size\": 238642601\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8996_Weather3.tar.gz\": {\n        \"sha256\": \"6a532ea952c96132b5d559e4cf0231924be22684a13635448d8a27d1ef1179db\",\n        \"size\": 187824970\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8997_Weather3.tar.gz\": {\n        \"sha256\": \"f8ceacb2c4d3bd78857b2aa62dcc685e9b58fbc59c9a67125dcf7ffec2af2e6c\",\n        \"size\": 159526071\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route8999_Weather6.tar.gz\": {\n        \"sha256\": \"abd8924d6a6fba676efeb8c8d6496f06412e4a1397d6ef22de13222b96c2983e\",\n        \"size\": 208756470\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9000_Weather7.tar.gz\": {\n        \"sha256\": \"db25c4d2040380f76314d5199f45b7eae254402dd389eed2723d4fe0abeee39f\",\n        \"size\": 451944127\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9003_Weather10.tar.gz\": {\n        \"sha256\": \"7b8432fc7cc6f22e123dbc6abb2091130b02fa7c8e9a3c0339d073424cdea3ff\",\n        \"size\": 275235593\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9006_Weather13.tar.gz\": {\n        \"sha256\": \"f0a42766862e4f074e6b536b862ff0ffe6c97dad886a52fd28aa7577356ee5cc\",\n        \"size\": 168018311\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9007_Weather14.tar.gz\": {\n        \"sha256\": \"00773930d342623e7462ec8129b11322ad51026970cc6c4be4ee7790cf4452a3\",\n        \"size\": 369810590\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9008_Weather15.tar.gz\": {\n        \"sha256\": \"976b9dcf75d4371f9fba67cf5e85e7cd77b051187a13a581e9f37be7ef5614aa\",\n        \"size\": 275524511\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9009_Weather8.tar.gz\": {\n        \"sha256\": \"4f9343b4b1f570d49c9061ba825e965abaf054a11d66c8600b5704385282341b\",\n        \"size\": 236825440\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9010_Weather9.tar.gz\": {\n        \"sha256\": \"d0fd018358c802c41eb74605e58e752744869ada253a5e0a728e612999ddda06\",\n        \"size\": 246068729\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9014_Weather21.tar.gz\": {\n        \"sha256\": \"36d00df2333fc07bf323ef3beaae830742f6c3da48a09b5c0d30c7540264933c\",\n        \"size\": 164460005\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9015_Weather22.tar.gz\": {\n        \"sha256\": \"8f8e277a617af828fb7dc4bad555ec9f12edd84425b262bfa0d6ec0fe1ce7f85\",\n        \"size\": 166358009\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9016_Weather23.tar.gz\": {\n        \"sha256\": \"9227ee417ded48c3544ec6f9b41e0392aafdd1e4e997d081fef1da546c2700a3\",\n        \"size\": 204935194\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9017_Weather23.tar.gz\": {\n        \"sha256\": \"b2b0cf85123616ffcedcc96a46d1f34bed4971397d485ed488e812694c4cd20c\",\n        \"size\": 123552774\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9018_Weather25.tar.gz\": {\n        \"sha256\": \"da2653635e8c4c05da32a2968328c677bd5910d3283f1779ede2607c7ba402e4\",\n        \"size\": 167464953\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9019_Weather0.tar.gz\": {\n        \"sha256\": \"7bdeff16ebf1d98352374d53f5c4a5e25e2fe080d7e4ed04357050846684d5d1\",\n        \"size\": 375094172\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9020_Weather1.tar.gz\": {\n        \"sha256\": \"e5c17a534af53101d36ebcfeffdfe12cc1d66784a75ad9c53b7cba464a440cfc\",\n        \"size\": 247405014\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9021_Weather2.tar.gz\": {\n        \"sha256\": \"4dba3f3d2afa6f722530d1591274f32ac818adf49c51e8e296cff9e81db012d8\",\n        \"size\": 321139564\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9023_Weather3.tar.gz\": {\n        \"sha256\": \"aa291caf3d73867d677ba0c4d7adb6b2641102e93daa149906ff671bb0cad19f\",\n        \"size\": 212808566\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9024_Weather5.tar.gz\": {\n        \"sha256\": \"9f1dcfa9ec9e8e8815707654a25641977515c7d321e6e7e341e0e59e79943297\",\n        \"size\": 216440409\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9025_Weather6.tar.gz\": {\n        \"sha256\": \"6fa531493f371c8f3527fdfc9b8819103cea3fca86dac90aa93a4098a2423cd3\",\n        \"size\": 249400360\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9026_Weather7.tar.gz\": {\n        \"sha256\": \"383521801edbf5a441f4cf99418628e49c9660d22848daf481d944ff67da4d37\",\n        \"size\": 299440416\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9027_Weather8.tar.gz\": {\n        \"sha256\": \"3819440fc22016ed7573b2fd5ab19a43aa7c66dc0b5e6700a7ea2a5d4400d289\",\n        \"size\": 250672651\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9028_Weather9.tar.gz\": {\n        \"sha256\": \"f655b83b493c5172881d806bd5140a54f58e80b924afa924b4a004ee2ad9243f\",\n        \"size\": 186545725\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9029_Weather10.tar.gz\": {\n        \"sha256\": \"a483a70a087caf9cbdfccd27663ab8c53ecce2d378c4d2cd559c7afd76c397e0\",\n        \"size\": 203923938\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9031_Weather12.tar.gz\": {\n        \"sha256\": \"2f510b499d7bbd10d4ad37e1dfc9afb1f484da23e6e5ffea318a0b033888938a\",\n        \"size\": 200086662\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9033_Weather14.tar.gz\": {\n        \"sha256\": \"eb235f5c39a048d8cb179904e7648b224ea60b1277353b5b003e6e5d277559d1\",\n        \"size\": 552658607\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9037_Weather18.tar.gz\": {\n        \"sha256\": \"67eaca18545fe316ed250b24ed7c6b51f663f93582487de345dcb70093d72a7b\",\n        \"size\": 328761939\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9041_Weather22.tar.gz\": {\n        \"sha256\": \"a95f8d973a7b09ac518e81114003cc55b4735f9a51700a7a2c0ecdfe78b1aed9\",\n        \"size\": 207588841\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9044_Weather25.tar.gz\": {\n        \"sha256\": \"193aa23dda892e8cc6eceb6842f3fab1d37df436fc9661b6a438a0d690f5af88\",\n        \"size\": 205351516\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9046_Weather1.tar.gz\": {\n        \"sha256\": \"8d1d9683345e1b95a4b0f8689e95706c0a107abff8d91cdd0640d49898a8f355\",\n        \"size\": 311269854\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9047_Weather2.tar.gz\": {\n        \"sha256\": \"9fedd70e6df514ca68ecba229e4d209ad9611301bd25cc53283a12d7562b5d59\",\n        \"size\": 217060106\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9049_Weather3.tar.gz\": {\n        \"sha256\": \"2652b0045299f07578cde095e3d815f7c1ca3fd7e2bf45510d553a4d96bc9e19\",\n        \"size\": 232369546\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9051_Weather6.tar.gz\": {\n        \"sha256\": \"24989c38f09b0060d27ba82507a90f892cd21c060bda0cf0dc3dc73b18ec35dd\",\n        \"size\": 290006111\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9052_Weather7.tar.gz\": {\n        \"sha256\": \"ae88882d981be41bd2964c2da615c6614f0998adf77417f1480e67f9a54927ca\",\n        \"size\": 298281708\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9053_Weather8.tar.gz\": {\n        \"sha256\": \"3ae98accdf0dbc5b8d658bdb614025447f8f344f5412c2cdc774604f604576d2\",\n        \"size\": 223856088\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9054_Weather9.tar.gz\": {\n        \"sha256\": \"fe0ee26a667c66f7fd87e48cce1fed04a232421109db3cc6b64f25f889e9c557\",\n        \"size\": 174269930\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9055_Weather10.tar.gz\": {\n        \"sha256\": \"18f541b0a181d8f157a926603127cbc468fca91501e6f9fc0dbc4be98f6e483b\",\n        \"size\": 252168972\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9056_Weather11.tar.gz\": {\n        \"sha256\": \"321c2e1903e818c9ff7136d7ae7e769c6d0c9f7f4ee3144482a0985dd18fdc54\",\n        \"size\": 650721650\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9058_Weather13.tar.gz\": {\n        \"sha256\": \"671acb46aa0145cda73516a00f9fc2ee3ec230256b4536e0ed17efc0d715022a\",\n        \"size\": 198129660\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9059_Weather14.tar.gz\": {\n        \"sha256\": \"b41b61328bf8f041b48adc5299c691ef05d80913e0e5faf4b9e79bfaa83a6ddc\",\n        \"size\": 222355401\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9063_Weather18.tar.gz\": {\n        \"sha256\": \"5d4d708c5b8f29dd954d7f4bc385454923e69cba858f20dbeb351ee2d44f4d0a\",\n        \"size\": 191358769\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9065_Weather20.tar.gz\": {\n        \"sha256\": \"0d018140436df240921cd6f180c4c1a911bf110323b29b13e4e55f1668b64a90\",\n        \"size\": 127678548\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9066_Weather21.tar.gz\": {\n        \"sha256\": \"4ebe7bbb71a44dde7d296a408c1bdb440602e7b6e00cc7ae112011b94e1bfd6f\",\n        \"size\": 174554070\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9067_Weather22.tar.gz\": {\n        \"sha256\": \"e630c90496a090c47faa7fbabbbbf390c439ef6f9d9c3bedb634af811f5141ec\",\n        \"size\": 189844888\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9068_Weather23.tar.gz\": {\n        \"sha256\": \"0123192cb16086abaa1adc0c5df99e1369648680d785e684a5776580fb6c97b1\",\n        \"size\": 174578735\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9069_Weather23.tar.gz\": {\n        \"sha256\": \"a969c5ac834bf5acfe1de63616566f5c2e0d890478b0f2e89b6844c1e8e909bc\",\n        \"size\": 203129908\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9070_Weather25.tar.gz\": {\n        \"sha256\": \"001d057031ae661448966de8dad38bbf488ba8799e63b1c503e20276c2e1d59d\",\n        \"size\": 221007149\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9072_Weather1.tar.gz\": {\n        \"sha256\": \"ee01b2ea0a771839ebe7ece7316af407982592b99cf576ab2f10f2fab8548ad5\",\n        \"size\": 271818140\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9073_Weather2.tar.gz\": {\n        \"sha256\": \"321a66e34200d69ea4b2ec502c4cdcf3907b269d530f4ea281c21e9f6b18fdc8\",\n        \"size\": 204195787\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9077_Weather6.tar.gz\": {\n        \"sha256\": \"0c97a28ab7179da1d239ec6652e5d22268794270860616d4ac55ea64e7cc8658\",\n        \"size\": 161876622\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9079_Weather8.tar.gz\": {\n        \"sha256\": \"a7d65caadf489a9257003111682b17018d0e130772310a19ede78571bb1951fc\",\n        \"size\": 302953914\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9080_Weather9.tar.gz\": {\n        \"sha256\": \"e0544f9a87501dd01780f1c2763da1d8f99a32dcdc8e4afacd61de90aa4d769b\",\n        \"size\": 202155241\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9083_Weather12.tar.gz\": {\n        \"sha256\": \"e5b0d97da3806c5255200bfc4892a916b7209c9f8778adab49a5eb6b4f570f28\",\n        \"size\": 241896592\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9084_Weather13.tar.gz\": {\n        \"sha256\": \"26634f3c227ba678044e6a0140762acc4ed6c31d2e92b4b09f978245fcdfa52f\",\n        \"size\": 204122121\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9085_Weather14.tar.gz\": {\n        \"sha256\": \"b24cff3183bf571feb994e4869a1abb97bb00a8ad36247465e25c3fcfcb4cb83\",\n        \"size\": 196459837\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9088_Weather9.tar.gz\": {\n        \"sha256\": \"a4950e983f702325be8cbfadca52926ca223d3b9df36332dd5a98927ffc6982e\",\n        \"size\": 175866999\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9089_Weather18.tar.gz\": {\n        \"sha256\": \"7d743b698c8a0dd64a8187ce20abf6406240bb14bd1a4445e886da7d7be9617b\",\n        \"size\": 261460779\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9090_Weather19.tar.gz\": {\n        \"sha256\": \"7b796dba01ff251b6f30e776ba404b82a6b1d306363f37fc6e3e205a1420ca45\",\n        \"size\": 209097135\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9091_Weather20.tar.gz\": {\n        \"sha256\": \"4d8827a58e2ab12bfe278b2f069c0120c1eafc82eb7e625a4e381b6ad5f9f2dd\",\n        \"size\": 280188697\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9095_Weather23.tar.gz\": {\n        \"sha256\": \"688cdf5e453805b59d31ae35a613fcb68965dca7bc36e3a3329312d0b0feecf5\",\n        \"size\": 100072778\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9096_Weather25.tar.gz\": {\n        \"sha256\": \"e1a35410d45ac196a5a9c841ef886466c951cec5dfce136950aeb7c16de5493b\",\n        \"size\": 176612840\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9098_Weather1.tar.gz\": {\n        \"sha256\": \"e7fd42c0a6dd4f65b4a821da32cf3f256821cd6c7bfdddfae3c4498cbd4f110f\",\n        \"size\": 197664107\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9100_Weather3.tar.gz\": {\n        \"sha256\": \"5277748649ff90a71a546100419c3a01aaa2ae339d7978950aa6eed0f475dbde\",\n        \"size\": 282006740\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9103_Weather6.tar.gz\": {\n        \"sha256\": \"39de660ba3894050b9e913ac8662d2d92ca8a2579e8ce83540414016636b6a02\",\n        \"size\": 254605965\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9104_Weather7.tar.gz\": {\n        \"sha256\": \"7248d2dc40733b1213261681b8d97bcc3978b86bd9c87375bb691c153d28d25b\",\n        \"size\": 211368008\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9105_Weather8.tar.gz\": {\n        \"sha256\": \"b83bc5f67cac612de30c448f9e1cc31ddae11448c315395075d496dce431e95b\",\n        \"size\": 196779047\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9107_Weather10.tar.gz\": {\n        \"sha256\": \"bf827061db6f4074e2c0f1e58250901a728524d94b63b1052e5ceb09d055d739\",\n        \"size\": 204343981\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9110_Weather13.tar.gz\": {\n        \"sha256\": \"121f4d4b5da8f381bc5897f5f6ef0678cb51a0a10848df18d399b48cb87c0ca2\",\n        \"size\": 179198458\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9112_Weather15.tar.gz\": {\n        \"sha256\": \"94e3478a4ae1f13e205e7d038b1a84ccb5d8e69d6a8d453396cb3f51eedcb892\",\n        \"size\": 250941970\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9114_Weather9.tar.gz\": {\n        \"sha256\": \"ee4ee232ddc5deae3b73afa070f421c18bb5b3c867abba77584928585b424d9d\",\n        \"size\": 186173592\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9115_Weather18.tar.gz\": {\n        \"sha256\": \"ffe7547ca817066d8ecd89ffd86ca4cd0fe2e27e260a4a9e067ae66f27ec81c4\",\n        \"size\": 868248787\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9116_Weather19.tar.gz\": {\n        \"sha256\": \"705e9f94039bbc85006cb36456d4af1f4b8a18b6be110b95a329daca6d9d84df\",\n        \"size\": 202953424\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9118_Weather21.tar.gz\": {\n        \"sha256\": \"9241a2c9166124300d840627bc8d5d4a3a3c6c1c4e61fd370eb15dc9e8bce4c0\",\n        \"size\": 234838273\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9121_Weather23.tar.gz\": {\n        \"sha256\": \"adc3440505f1312b2a8de6c73b3323ba4bdafa3cdb7313a70fc679f63e2a04d4\",\n        \"size\": 175616735\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9126_Weather3.tar.gz\": {\n        \"sha256\": \"b1edee3ee6da62cab3255ce4b4d808f9f1cd2356cda9f0279e5e3c6b7bb70277\",\n        \"size\": 203258178\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9127_Weather3.tar.gz\": {\n        \"sha256\": \"46fb9c34f74725378a70b0dffdddc30fd560601b01435372f691ec9b3772865e\",\n        \"size\": 624745207\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9128_Weather5.tar.gz\": {\n        \"sha256\": \"4172bd1ca8bb4723db58e79fd9a98df3ecf49282fb4d509adeff40c72ba74ee7\",\n        \"size\": 154439227\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9131_Weather8.tar.gz\": {\n        \"sha256\": \"5f1eb022d947576e23db436e6d0b11b9b93b793b37e72969e983cde212f35253\",\n        \"size\": 192921542\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9132_Weather9.tar.gz\": {\n        \"sha256\": \"34abf093bc162010e53d8576208e3a4cf73a4d9050970cbda6bdf8770d1789e9\",\n        \"size\": 229418341\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9133_Weather10.tar.gz\": {\n        \"sha256\": \"7b26c539ed4a5ce2de752b42e43ad229207d8fa073e7c540fd2d37271e2faeaf\",\n        \"size\": 158626857\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9134_Weather11.tar.gz\": {\n        \"sha256\": \"1c8814677c4335a5bce9cffe8dd2ec4af5af446b5f73073d41902e30f0db47f1\",\n        \"size\": 139373642\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9135_Weather12.tar.gz\": {\n        \"sha256\": \"6697dfdd0cc77b28cc93122e058842dede3673bdcd254e659c87158601ee94fd\",\n        \"size\": 233811204\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9136_Weather13.tar.gz\": {\n        \"sha256\": \"980794a4eac9f25e74b2c88f04ecd3e355b66b5b8982f6157a5e66ce8b3ac765\",\n        \"size\": 210096302\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9140_Weather9.tar.gz\": {\n        \"sha256\": \"e02ec564207f6e9a5521a77d161b4429b1a9d9d0f9a70f1f91229b3ff3d51fb5\",\n        \"size\": 173357822\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9144_Weather21.tar.gz\": {\n        \"sha256\": \"6cb82fd5f9963de2ba3c8093b82d047d4c70de117eab88008a4fbb32a648c14b\",\n        \"size\": 191164826\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9146_Weather23.tar.gz\": {\n        \"sha256\": \"d65149cd56baee77e81a35f1c95b0324f167594f4bcf73fc19ab9f13bc8521bd\",\n        \"size\": 218804322\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9147_Weather23.tar.gz\": {\n        \"sha256\": \"802b7f7fdd9c250ba4c35f1f32972ba4f36af6ebd7b923e5b2a4bf57ffaae03b\",\n        \"size\": 195823894\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9148_Weather25.tar.gz\": {\n        \"sha256\": \"9aaf18ae72eaa0d8ebcb004a51fefaf8fb095d544b4f782a5eefe5f6f351dddd\",\n        \"size\": 179731007\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9149_Weather0.tar.gz\": {\n        \"sha256\": \"3024852686ebe47187932e3d1a11e437a5f41b9ff94d376f46b50b3d0a7bc2dd\",\n        \"size\": 215584728\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9150_Weather1.tar.gz\": {\n        \"sha256\": \"76e2f61c9331b2612c8407c77b288fec56751ee508848f92e61ffb48350cafbc\",\n        \"size\": 295851945\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9151_Weather2.tar.gz\": {\n        \"sha256\": \"c26e73c0ff90fe872bb86366958b0c3ce980482e64ce745f551fe9d03c9ad6a6\",\n        \"size\": 233646598\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9152_Weather3.tar.gz\": {\n        \"sha256\": \"518baaf026cbc0c4bd432ca7d82dc94b2a3bbf3f11e2b5638228766a24b30a11\",\n        \"size\": 277292654\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9154_Weather5.tar.gz\": {\n        \"sha256\": \"929f546484a437b585976b68889bdba3429fa52b30a1ecce71d71bd0e2da9c0f\",\n        \"size\": 265700786\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9155_Weather6.tar.gz\": {\n        \"sha256\": \"183fc7a248b3bb21df703b5e8290c97c3ad982f69181e491425bb6fdb74e9eb7\",\n        \"size\": 219574928\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9156_Weather7.tar.gz\": {\n        \"sha256\": \"9f2aad3452f49ae8de66e55d33d241aedb2a0530271236fbf4aae32dfb519951\",\n        \"size\": 290030885\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9158_Weather9.tar.gz\": {\n        \"sha256\": \"8f8f4d6c115593ea2a3bf290ac1b3b58caf08a3c14ea3fab07cff9c20afc2ad0\",\n        \"size\": 178634451\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9160_Weather11.tar.gz\": {\n        \"sha256\": \"442185262ce30f0217b737d96a99e21057132a530394b071b960b781f99ed969\",\n        \"size\": 180037821\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9161_Weather12.tar.gz\": {\n        \"sha256\": \"8f985eda1f6ef80fe0a01ae391af953e30d10bffe34334f5cfb938883e2edc0a\",\n        \"size\": 275635615\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9162_Weather13.tar.gz\": {\n        \"sha256\": \"2979faaee7047c47ff7eb57921d75d7431a8ccb55257eaffa61d1a1664f7aadf\",\n        \"size\": 241180910\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9163_Weather14.tar.gz\": {\n        \"sha256\": \"2432e93a167ae6a7c541bbdc1f8a3c56a5db7cfd596104e9d97dc4afe3be94c0\",\n        \"size\": 92532569\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9164_Weather15.tar.gz\": {\n        \"sha256\": \"5d7a4fc579c6e3c67b4937998b7be9c5bfa89c62a8d6ec85e42d5b46d1813939\",\n        \"size\": 92632444\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9165_Weather8.tar.gz\": {\n        \"sha256\": \"651a13e85f83eaba08ee7424c195ec78310c9637b3408205f76b862cd3929346\",\n        \"size\": 162984608\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9166_Weather9.tar.gz\": {\n        \"sha256\": \"44b3fd04142adfe7401ef7f4fc407616fb460e5ad50c8882773bc4e43b11b0c5\",\n        \"size\": 180362494\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9169_Weather20.tar.gz\": {\n        \"sha256\": \"0b667e1b916c64147ba4dbd7495a3559acf7bb830edc895c726aa6a43be27ae4\",\n        \"size\": 221043060\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9170_Weather21.tar.gz\": {\n        \"sha256\": \"45b6f016c71f15f25308e7cb2e1024dcc30b85a3a23e05c525ba88ff68bba642\",\n        \"size\": 188267823\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9171_Weather22.tar.gz\": {\n        \"sha256\": \"48f36c115d55c7929d6b36b72711ebbc6a22786c7ceca800c2a4952c022f114e\",\n        \"size\": 233301191\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9174_Weather25.tar.gz\": {\n        \"sha256\": \"a0bfab87173177991bd98b26bc5fcb2255a45fe973c21cbea2a85a9f39ad68bf\",\n        \"size\": 204933213\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9175_Weather0.tar.gz\": {\n        \"sha256\": \"826e8ec254571b6ffb0562de6fb36ce1ee8ccb064ac78d41f39afe84808086f4\",\n        \"size\": 330439125\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9177_Weather2.tar.gz\": {\n        \"sha256\": \"de8f91c2c054a017ec8acec1bad74fd50cfc94cdf9fe62038e38d7d1f9b5dda3\",\n        \"size\": 179809868\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9179_Weather3.tar.gz\": {\n        \"sha256\": \"d5941b3d9b86bd2de0c4015dab8f78ea240bc223ea816caf48832a062bdc7fe7\",\n        \"size\": 184793074\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9181_Weather6.tar.gz\": {\n        \"sha256\": \"da20953254bb3149e533f31763f8300052899155b485a810b026f520eabce88d\",\n        \"size\": 170311006\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9182_Weather7.tar.gz\": {\n        \"sha256\": \"452db931bb164b027cabfeda3f6fbe04f7cd45b7d08e2c22b71ca8014fc00847\",\n        \"size\": 192771473\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9185_Weather10.tar.gz\": {\n        \"sha256\": \"1da5627befbec63a021e719cfada5c93ef3bb4134c95d628a184966a74ebe087\",\n        \"size\": 203589640\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9186_Weather11.tar.gz\": {\n        \"sha256\": \"ff0ca33a645945aaa6c2e2ae840f41aeeb7cef27980c9991e494017e670dee15\",\n        \"size\": 236286561\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9187_Weather12.tar.gz\": {\n        \"sha256\": \"748be31aff59debb67cd478d03a67dc28b21e99053c70005cda1a3a860f91f44\",\n        \"size\": 258667631\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9188_Weather13.tar.gz\": {\n        \"sha256\": \"6d1488385e4c1c4617795e9eebe8c98e79624467e5f8b8a3a54b16bcb9e6d41b\",\n        \"size\": 147075871\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9189_Weather14.tar.gz\": {\n        \"sha256\": \"a6a5d36b2368dd84984a7f5e627ba46f3789de874f033eb07ea0786e777fef2a\",\n        \"size\": 268546200\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9190_Weather15.tar.gz\": {\n        \"sha256\": \"5b46597e87818205fea55bfdd6a05261c3ccb75cb2b3a71679427c1e4197aaf5\",\n        \"size\": 173169867\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9191_Weather8.tar.gz\": {\n        \"sha256\": \"4629e22c13930916b9773d8c5c44f1d2cb40d6561e793ec7da14487b7d79d2da\",\n        \"size\": 236174781\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9193_Weather18.tar.gz\": {\n        \"sha256\": \"0411693b9dfa864e1c33d984b48018226d090ededef47928bbc8c4c040b4bab2\",\n        \"size\": 256935288\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9194_Weather19.tar.gz\": {\n        \"sha256\": \"bace1c2e2aea9644cf45881cfb445d8021c160df21aa5cdc8c34f770ef3c590f\",\n        \"size\": 90085651\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9196_Weather21.tar.gz\": {\n        \"sha256\": \"65dc908f545c15c9b5962c6e07e2bdc10935a13653c356001f48ad093740859c\",\n        \"size\": 343387395\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9198_Weather23.tar.gz\": {\n        \"sha256\": \"75dc02e9ab102ca6e277f23ad4a8e0cd58cb5c3936bf98028ecfc4a93bd1ed99\",\n        \"size\": 195040994\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9199_Weather23.tar.gz\": {\n        \"sha256\": \"71093793ddcc2d0646d235578a47a926176896ba56a501f53a212fc2bd20c487\",\n        \"size\": 202664133\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9200_Weather25.tar.gz\": {\n        \"sha256\": \"0813876a46588b4594792814cb7198d4726eab4de2395873242bb2a4502ec96b\",\n        \"size\": 142981814\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9202_Weather1.tar.gz\": {\n        \"sha256\": \"6b085c6fc701f2d2698b4386a6db5a6493562b8db1ea63047649674b24fbcfae\",\n        \"size\": 333780930\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9204_Weather3.tar.gz\": {\n        \"sha256\": \"77d627d02ede8efe3ba4cc606de5082c5e5e11cf90d5e0e53efed6fa8a3af223\",\n        \"size\": 277326292\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9207_Weather6.tar.gz\": {\n        \"sha256\": \"3f87ec199376f9e2b683c0639f45916b2623bfb48028ee252e1aaf9aac5f45ea\",\n        \"size\": 212110603\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9209_Weather8.tar.gz\": {\n        \"sha256\": \"d2afb64a57ec58f570a400efb0f26fbbd723a533c201330b3c520dd6e563faaf\",\n        \"size\": 187519663\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9214_Weather13.tar.gz\": {\n        \"sha256\": \"3fe6a3b3b06756775532a974e5e872d9b502b9ce44674b5409858e566d213cab\",\n        \"size\": 217118187\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9216_Weather15.tar.gz\": {\n        \"sha256\": \"d21fae9af5e4ef4bd2f132a7c81bf75a8812f57ea227e54846bbd88a2bface3d\",\n        \"size\": 193734779\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9217_Weather8.tar.gz\": {\n        \"sha256\": \"b5614ba0b1f5a327a833c7c6619cf768083ea9eae299ea40a385e1d02da0be3c\",\n        \"size\": 216165577\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9219_Weather18.tar.gz\": {\n        \"sha256\": \"2c75158ce615bbd08fb546a46a439e0b932a44adfcfc64cfde1d51df72f06079\",\n        \"size\": 184292239\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9220_Weather19.tar.gz\": {\n        \"sha256\": \"c031e75ae512719adf8946e95d0b5c872ad80c9d2974a3e7ebeda8c3a42c5c6a\",\n        \"size\": 201568281\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9222_Weather21.tar.gz\": {\n        \"sha256\": \"c9a8fceb386d70ff5f137410f864e145c1a04b6790ac1d292e1dd6f16302028a\",\n        \"size\": 188440741\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9223_Weather22.tar.gz\": {\n        \"sha256\": \"a81e197e0aa53e5f4a970c6153b170a997abd4732cb0dd9e0774625f47faf9c3\",\n        \"size\": 259048935\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9224_Weather23.tar.gz\": {\n        \"sha256\": \"7acf3ca10020a9519d77dbd3c783801471b4e53b16b842a8ece7d4c5a33bc156\",\n        \"size\": 180639775\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9228_Weather1.tar.gz\": {\n        \"sha256\": \"be0569098703863ab96e40e9cd52150c488a6dfe40a964af987e65987be6b90e\",\n        \"size\": 210230370\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9230_Weather3.tar.gz\": {\n        \"sha256\": \"c48578566b5ce9e8a3c4b27febe6742707a4a4f7436d43c7db4e1210743f7e27\",\n        \"size\": 301762419\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9232_Weather5.tar.gz\": {\n        \"sha256\": \"74d309c0caa83e023bb4f83860d400da872c4d240a8f42a13071d8bcf1884d4f\",\n        \"size\": 174274176\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9234_Weather7.tar.gz\": {\n        \"sha256\": \"68460df35df77d24c1255bc2986089bc0c680091cc63a085834c3b0d3c527022\",\n        \"size\": 209047900\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9235_Weather8.tar.gz\": {\n        \"sha256\": \"235deb38564b7a6598d4cae40520e76682ca8b3a02d1ee9cf70a1be34c93b023\",\n        \"size\": 254606653\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9236_Weather9.tar.gz\": {\n        \"sha256\": \"208e8b641d096c6a6e7f25fe6b53d0ff3dfd5a3b47dbc9527898cd66d70cfd4e\",\n        \"size\": 207758726\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9237_Weather10.tar.gz\": {\n        \"sha256\": \"e70ec4914fc91e547f8c90ddc64485266260bc2c0905e2bc5c8f434fd40d9d9a\",\n        \"size\": 209709812\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9238_Weather11.tar.gz\": {\n        \"sha256\": \"0fe1abfb53139e1ec4e4aea566264fbc8377df9717a41210fc027804947e1496\",\n        \"size\": 158974601\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9240_Weather13.tar.gz\": {\n        \"sha256\": \"14a1db43b2d7bc687b504ea4ff5c13527a4a292ce5a96af274073bab1097a1b9\",\n        \"size\": 187262408\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9241_Weather14.tar.gz\": {\n        \"sha256\": \"fbbf88a3a0a81dd8ece01a4d6e548c45afe3c15e9154c206b4e7c5b73bedc857\",\n        \"size\": 277978757\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9242_Weather15.tar.gz\": {\n        \"sha256\": \"f9f1078004a21ba1f819e3174dc6da1eb7de1bd84835e2a8cf220b7622def88d\",\n        \"size\": 205752132\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9243_Weather8.tar.gz\": {\n        \"sha256\": \"4a12097fad7e38643f83d4da2236f694206c79fb30d7f68bdf5099a0384fcb45\",\n        \"size\": 299824191\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9246_Weather19.tar.gz\": {\n        \"sha256\": \"c3ba045d9b173b8006544ebd4d0eae6e072b38925f9571a1fd476b8f13b9d4d2\",\n        \"size\": 166814165\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9248_Weather21.tar.gz\": {\n        \"sha256\": \"26c82176557e556b37b20491cfa630d0fb416e2ab2b4fb3229f13b08f1dee849\",\n        \"size\": 303207620\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9249_Weather22.tar.gz\": {\n        \"sha256\": \"cf3ff365c46c01bce6a296bf7b03155ff2768dae0eb134fa70c4423616e6bff1\",\n        \"size\": 166133620\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9253_Weather0.tar.gz\": {\n        \"sha256\": \"b97549e78ecb5f2f5abaa5932d8808e3aef771a7214b8009c62b7df331a406bb\",\n        \"size\": 234264021\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9254_Weather1.tar.gz\": {\n        \"sha256\": \"834cebdbef158e633d341b692e22ac61ad7295db4955518ee8bc52a589287a5c\",\n        \"size\": 294908383\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9256_Weather3.tar.gz\": {\n        \"sha256\": \"2e899516480824c223d954bcd108718f4d011b37cbdd4448d53051e53eeccf85\",\n        \"size\": 109478203\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9258_Weather5.tar.gz\": {\n        \"sha256\": \"235a39617fab405d1c1d8c53e44faeb476ace65e67fa14016d7575b357f51da1\",\n        \"size\": 230031012\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9259_Weather6.tar.gz\": {\n        \"sha256\": \"a4ef73a9ed9e0dd81e766972385d3f5200510bedbc608aa985183f1d7c05ac97\",\n        \"size\": 225233755\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9261_Weather8.tar.gz\": {\n        \"sha256\": \"229e5c2325527d9483c45922fe4019182d3f5bb70e1d7c05e255449c50de5262\",\n        \"size\": 213781620\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9262_Weather9.tar.gz\": {\n        \"sha256\": \"df608621779e065b81ec2d8558e332f64b1b53291f63046e43d8a5a3d2edef43\",\n        \"size\": 206952739\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9265_Weather12.tar.gz\": {\n        \"sha256\": \"1e3df31e158b654dae29e06c49a3609ba4814d060f5f42b14956287c2cb98be0\",\n        \"size\": 203734185\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9266_Weather13.tar.gz\": {\n        \"sha256\": \"86f40f4dd764f99242737f5f28534cb0d100dce86876071f1cac84a906feb975\",\n        \"size\": 182679994\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9268_Weather15.tar.gz\": {\n        \"sha256\": \"0d0b052e54fe8712b370f36e1b37b557ee3c3a7c55b3b56c4e3742c17fc67b50\",\n        \"size\": 197767981\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9272_Weather19.tar.gz\": {\n        \"sha256\": \"5a86eee1ee067b3ddcb4f100aef60619995eee373c19a0606fba1519fe60a3c7\",\n        \"size\": 250416207\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9273_Weather20.tar.gz\": {\n        \"sha256\": \"fbf271f996985d7052c54c6035963a8102e6ed4d8b0311030655e6f1d065ae61\",\n        \"size\": 149046162\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9275_Weather22.tar.gz\": {\n        \"sha256\": \"81812a7e0f278f86984aeb604d52161f75f47ae17985ce29822952c05bab84ed\",\n        \"size\": 181755115\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9276_Weather23.tar.gz\": {\n        \"sha256\": \"bb5c3f9371373e58cdbc7222a06af4784cdafdb6434b4e822e3048da953322cb\",\n        \"size\": 235349315\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9277_Weather23.tar.gz\": {\n        \"sha256\": \"6afed410e0f505cc95ade45554c5aab00ee9c6aeee73e21ff0a7bf1a8e53f923\",\n        \"size\": 163405330\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9278_Weather25.tar.gz\": {\n        \"sha256\": \"83f119634c874908e65b30dd31ba19df81d26a421499201169baff2e17e5f994\",\n        \"size\": 147544392\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9279_Weather0.tar.gz\": {\n        \"sha256\": \"1dfbe7e6728b8ceb0b0e25dd40f1709ad7ed4cddd04e8c7d178a1883187504e8\",\n        \"size\": 264988054\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9280_Weather1.tar.gz\": {\n        \"sha256\": \"ff07e1b10644844b237bd4d4ce3fddd9413cd1ea0449ab1a77cbfaf1a4ef65f3\",\n        \"size\": 277269838\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9281_Weather2.tar.gz\": {\n        \"sha256\": \"ba1a215bacfec22a8351ec0f34093552fc42654c8f5c99474e7c4f55da74d2a4\",\n        \"size\": 243935887\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9282_Weather3.tar.gz\": {\n        \"sha256\": \"d5f6d8df794a48ba9086eeb3258177432286220494497e317c4201bc9123a7b0\",\n        \"size\": 205316449\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9283_Weather3.tar.gz\": {\n        \"sha256\": \"2493fe18c0d1e6e75c6ff7e72f748aba9871ce18bc60ea8fbc8f3f55182319ba\",\n        \"size\": 210327348\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9284_Weather5.tar.gz\": {\n        \"sha256\": \"4badf51c55047960c3d907017a515c8006b04e1fbad81d1507c6abe265e78418\",\n        \"size\": 192366946\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9285_Weather6.tar.gz\": {\n        \"sha256\": \"eeed187cd65f89bcb2297e2f40501f17a8e76821800fa89edaac334d70198793\",\n        \"size\": 209821773\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9286_Weather7.tar.gz\": {\n        \"sha256\": \"453bc8e1da55d68b109eccfc280aa23a27fe4e16087c011238e30fe48b13b962\",\n        \"size\": 274955697\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9289_Weather10.tar.gz\": {\n        \"sha256\": \"81d84b8ebd8c54ce3e179d5a9097dcb98c3d01afb8490baed8d0ff3e289e63b7\",\n        \"size\": 124234171\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9291_Weather12.tar.gz\": {\n        \"sha256\": \"d9ac13bd5d616ac47faeab45bca3a246f20fc636fd6e41032eaeff78da832a46\",\n        \"size\": 183300936\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9295_Weather8.tar.gz\": {\n        \"sha256\": \"efc0abf4647b14483d184a48dbc4ac144f696a5b6ca546429bdb77027e14cc9d\",\n        \"size\": 187065440\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9299_Weather20.tar.gz\": {\n        \"sha256\": \"59a1157c0cc130b1848cccff2570db8ca4c9cc6f7ee04b028779765d2d914b20\",\n        \"size\": 244863716\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9301_Weather22.tar.gz\": {\n        \"sha256\": \"f025c6301dfa791b58ca189e18fe01e0dda74c9c2e9e1c0cf3745a79d83447fa\",\n        \"size\": 151519060\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9302_Weather23.tar.gz\": {\n        \"sha256\": \"75442cfe4b060b0e5aeccfd744ebd3c3c6f001bc28648d12a4aa735134f6d045\",\n        \"size\": 220213872\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9303_Weather23.tar.gz\": {\n        \"sha256\": \"f694f26a6bbd146f40146079f99ef4fe2036e261495f625b4811ac4315fabde0\",\n        \"size\": 242387904\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9307_Weather2.tar.gz\": {\n        \"sha256\": \"fbf0d796d6f3d933ed271e02303485808c11d39fc947479d281c63c08993cb35\",\n        \"size\": 240081748\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9309_Weather3.tar.gz\": {\n        \"sha256\": \"fb6fc41721af7fbd712e17742c7aab62f7ed35eb69f6680070c50879b774d4f6\",\n        \"size\": 277637170\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9310_Weather5.tar.gz\": {\n        \"sha256\": \"7bac761fedd35e63e9bfb07533acaba83ddd0721cce9fc962bbb1ec996b3936a\",\n        \"size\": 302999610\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9311_Weather6.tar.gz\": {\n        \"sha256\": \"b1f3934555b3d8d53905e9a9074ac43dace7c2b416131ca23f86330f8df2025b\",\n        \"size\": 183066760\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9315_Weather10.tar.gz\": {\n        \"sha256\": \"ba45f40cae2d16a3ca7512349f163fe826d7cf6bbf697f19598a5b350838896c\",\n        \"size\": 172384070\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9316_Weather11.tar.gz\": {\n        \"sha256\": \"261de3f9092f5449d85db1e120241d5dca73d1ec455b31f2379aa2a0d8a6b129\",\n        \"size\": 135319854\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9319_Weather14.tar.gz\": {\n        \"sha256\": \"570a14022e4a6c202ff963a1f0bc9557adabbded2d72a79d127c34d3bdf1df66\",\n        \"size\": 240449542\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9320_Weather15.tar.gz\": {\n        \"sha256\": \"a84665ab2a072b68918f585d28962540d58fb637dfc380ee28fa5a8bc9bf2cae\",\n        \"size\": 196046704\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9321_Weather8.tar.gz\": {\n        \"sha256\": \"524fdbbb775d794c81f4fad6720b709a0b5b1dbb33ab732267b46786ddd46ef4\",\n        \"size\": 201844522\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9322_Weather9.tar.gz\": {\n        \"sha256\": \"05e846f8439b01e8b87f1aaa1b1b629f9750d8d4ff6bfb337d6e0de76d199743\",\n        \"size\": 300171635\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9324_Weather19.tar.gz\": {\n        \"sha256\": \"2ae8a93c9b049be19465731cf55a1afc487c2459d01ae952070312aaaae1cc70\",\n        \"size\": 171688575\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9326_Weather21.tar.gz\": {\n        \"sha256\": \"fabf1da3f8bb7a6fd8ab0c0023ed1a03bed02a8bf3d4e15934298f772f3741f2\",\n        \"size\": 153596623\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9328_Weather23.tar.gz\": {\n        \"sha256\": \"87011937fcbd7f28e19642bcec9e45772975de9f7875d1bf2809cc6da536a5bb\",\n        \"size\": 184650478\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9330_Weather25.tar.gz\": {\n        \"sha256\": \"69b84bc4a62ab5373502f4487673b67e564c0b7fcbc3a2857843c9d2cd7e91ba\",\n        \"size\": 84593208\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9332_Weather1.tar.gz\": {\n        \"sha256\": \"104ff0d922c69f71e7c6f869d7065ce4823e91baae8111054cc6f6da1c65899f\",\n        \"size\": 305522663\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9333_Weather2.tar.gz\": {\n        \"sha256\": \"4f140bb5619abff823b5f73d19ba1fe9029c7235652bc39d500a539a909673fa\",\n        \"size\": 243500911\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9334_Weather3.tar.gz\": {\n        \"sha256\": \"fe8bdc1a3de48cefc8f9aef5143198f9a1a087498a83196ec43515288a6a130b\",\n        \"size\": 345574761\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9335_Weather3.tar.gz\": {\n        \"sha256\": \"84daa298ab7afa3dfdc4b123eeda5038fe0876dc3efa6015425b7895926f7009\",\n        \"size\": 243395209\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9338_Weather7.tar.gz\": {\n        \"sha256\": \"26a1d9c627fefc643d06be0859b65406bf6c9d2f8c7821609b47553d09ff5f16\",\n        \"size\": 356120948\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9340_Weather9.tar.gz\": {\n        \"sha256\": \"013226532f16c7001493eb5330ba1a3d1eb957a927ca9a36b84eb4b7d74b96ef\",\n        \"size\": 236316153\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9344_Weather13.tar.gz\": {\n        \"sha256\": \"4689abd7b347ea1c98c79ce5cdd7e9217c96a9487026525bdb29e8f3099c0286\",\n        \"size\": 243273727\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9345_Weather14.tar.gz\": {\n        \"sha256\": \"84999a708425ca9830a4260a75965dc1b9ae2d990c2a0e4db805d63d62d644ec\",\n        \"size\": 242396725\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9347_Weather8.tar.gz\": {\n        \"sha256\": \"257005eb2a4ff986bfc17e836f03c58689ad901c1d48cd8285c184057df1a001\",\n        \"size\": 179242244\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9348_Weather9.tar.gz\": {\n        \"sha256\": \"7837d788dc89ef56d8653cf6e7acf56b013a106fca85498805c275c4c004d4d6\",\n        \"size\": 167424053\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9349_Weather18.tar.gz\": {\n        \"sha256\": \"928f008817e7944980a4fcba58d3eb256e2f60f906226a47c30b57266a437011\",\n        \"size\": 275811450\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9351_Weather20.tar.gz\": {\n        \"sha256\": \"4483e5d3454e2bcf8d7a39bca1b301f4163e241a99618aecbd65a12922eed323\",\n        \"size\": 182385945\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9352_Weather21.tar.gz\": {\n        \"sha256\": \"04d1f2e73e44954db52271f0492d7305314d84cbc26220f2cd9c103502f6e0a9\",\n        \"size\": 212727275\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9354_Weather23.tar.gz\": {\n        \"sha256\": \"a50ccd7d4fc443602be5a2f18a63e2f0ac839bdd0adc6dad7b1f305a8c52e8f5\",\n        \"size\": 165255642\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9355_Weather23.tar.gz\": {\n        \"sha256\": \"711b17c91b4490d02f727e3ffd0f531e2bd656cdca1ca00713f1427e9736dff4\",\n        \"size\": 196290473\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9359_Weather2.tar.gz\": {\n        \"sha256\": \"d6bd4298b2fcbd1b0f60071b14a3d8e0da7889560a94afead948da19691ccc6b\",\n        \"size\": 278841851\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9360_Weather3.tar.gz\": {\n        \"sha256\": \"ebcf31c7bd5c556dcd207ec4d00b4477ee9c4de2b1f6321ff118b6abdffbea3d\",\n        \"size\": 178793739\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9362_Weather5.tar.gz\": {\n        \"sha256\": \"53796646ed02c0b8fda3ee9ac843b942f7f43317d90c6e1d9a99b4d5ff7baf18\",\n        \"size\": 226246141\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9364_Weather7.tar.gz\": {\n        \"sha256\": \"45ce6efb8309830e960294c09e7c920061bff877be4d1f07b02f1145752f7cf1\",\n        \"size\": 200134158\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9367_Weather10.tar.gz\": {\n        \"sha256\": \"2992115c5cd219a5b41458accf7ba060550db1f006c6cacf4cd5b23343d7377d\",\n        \"size\": 227296104\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9368_Weather11.tar.gz\": {\n        \"sha256\": \"beaa2510e732aa3a47dee4b18e6b645dfa8b2a4d916dcbd20e1e31d52af2ee86\",\n        \"size\": 200609102\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9370_Weather13.tar.gz\": {\n        \"sha256\": \"da80683a21ca15d1ae4334e308766396ab4b99f03b5562064d2979541eb127a6\",\n        \"size\": 223760728\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9371_Weather14.tar.gz\": {\n        \"sha256\": \"1b7698c18ff0e5f91add99131a9016702dac68bbb3f76b9e805d39c3f7d483a8\",\n        \"size\": 286084106\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9373_Weather8.tar.gz\": {\n        \"sha256\": \"6e5817170cf94bf4583b57f682533b1b49d2e728155078b064a4a8aef22a5fd5\",\n        \"size\": 279090914\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9375_Weather18.tar.gz\": {\n        \"sha256\": \"3de11f78b818a6dd1a6b16f3cc212696b387abe65e9c576069070cbcfe6c0d95\",\n        \"size\": 321789243\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9376_Weather19.tar.gz\": {\n        \"sha256\": \"f63ddc79460c1cc492fa92db619b9e53125774ee1476e6e72f30cb19292a89bf\",\n        \"size\": 201064024\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9377_Weather20.tar.gz\": {\n        \"sha256\": \"aee8025bac0f276da43e76ecb39ea2cabc882e37e3fa708be11799954c4dce37\",\n        \"size\": 255225501\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9378_Weather21.tar.gz\": {\n        \"sha256\": \"a3c103841783c5947edea5fcce055e23db6673d5b0662a2ba8d5d166d5cf79dc\",\n        \"size\": 209299048\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9382_Weather25.tar.gz\": {\n        \"sha256\": \"a16caa7a8e4e84263d5bbff8c750d5cd5ea5219b4c905b618e3574bcbc73272f\",\n        \"size\": 166027367\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9384_Weather1.tar.gz\": {\n        \"sha256\": \"b5a2748325f4e1eec31bf61c77175b502e8ca9939ad46f5b39123b534bb45e04\",\n        \"size\": 250625862\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9389_Weather6.tar.gz\": {\n        \"sha256\": \"15a7b87618122ca4267aa13418a7c1228663f9647e0313f11ed13f9bffd5afb5\",\n        \"size\": 190074103\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9390_Weather7.tar.gz\": {\n        \"sha256\": \"44676a29c825a0e09ecbac1c8d41cb80e69ce3a195659d4c6123e5e9e34823cb\",\n        \"size\": 335722056\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9393_Weather10.tar.gz\": {\n        \"sha256\": \"97763a31706728b740d4e670ca18723d151bf6e8a428a346fae4ce1fac294131\",\n        \"size\": 216961381\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9395_Weather12.tar.gz\": {\n        \"sha256\": \"f1f73b859ed40121237fbcd2774327027d5b841e8d0774e9cb811e31e8a25c3f\",\n        \"size\": 208574248\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9396_Weather13.tar.gz\": {\n        \"sha256\": \"7f85531848f458bf7b680e092cfd00b4eff3dddda5a10dcf6e2b797ddee679e8\",\n        \"size\": 148902053\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9398_Weather15.tar.gz\": {\n        \"sha256\": \"75ea430c5be0c3b7d2619a6fa63c09883f20ac13fcfe776501a0d4a7e20f7dfe\",\n        \"size\": 207112910\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9399_Weather8.tar.gz\": {\n        \"sha256\": \"26e066148807796016b0241363510143be745b0891a2af8082b5785a4b34cb4b\",\n        \"size\": 210102630\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9401_Weather18.tar.gz\": {\n        \"sha256\": \"2e8fcd654de691e801fea88a9e6841367ea8178d27b303232d8b49c150bc5ce1\",\n        \"size\": 111917346\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9403_Weather20.tar.gz\": {\n        \"sha256\": \"7ebdc48dbfb052a0fea124cd7eefd39a7e3baea8e4cdee71006c6d0d7c28064c\",\n        \"size\": 224245877\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9404_Weather21.tar.gz\": {\n        \"sha256\": \"bae74135d599d24c64460c6649d60f404c683066c624bc9ea86250d7eb4d358e\",\n        \"size\": 226443003\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9405_Weather22.tar.gz\": {\n        \"sha256\": \"39a661e87fb413bf023c69eeed261db21853d4fe2be84ecab7dcf3930206c894\",\n        \"size\": 188366076\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9407_Weather23.tar.gz\": {\n        \"sha256\": \"ee0692eda31825170829dbce783486882891cd4af678bb339d02f511dba390d4\",\n        \"size\": 163630621\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9408_Weather25.tar.gz\": {\n        \"sha256\": \"e7e7089645c04b8302113f2d7837db9eedf4309157031bc9b3a59265128bac14\",\n        \"size\": 134856046\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9409_Weather0.tar.gz\": {\n        \"sha256\": \"6968cbff71e460aa076ed9360112d2f621d8a55983df42ca5a89ae0d7625d915\",\n        \"size\": 239943253\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9410_Weather1.tar.gz\": {\n        \"sha256\": \"93c1265ed38345231f6efd6aaa8309ca235ddbefe6409585cc7ccf29df11d1c3\",\n        \"size\": 290569449\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9412_Weather3.tar.gz\": {\n        \"sha256\": \"9e64746c62deb32bfd4b85fad302a78c31f30169719cfc112035e3d0405edce7\",\n        \"size\": 210656460\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9413_Weather3.tar.gz\": {\n        \"sha256\": \"713f24d8a5c752ed30ccb1f13ac8aa218d7046e54b298621a2b39aa1c8dbb8b3\",\n        \"size\": 290716916\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9415_Weather6.tar.gz\": {\n        \"sha256\": \"cb64d03cc68a372ca5c24d67951f845a2685ebb62be99425fec7181932d65264\",\n        \"size\": 226496883\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9417_Weather8.tar.gz\": {\n        \"sha256\": \"b7325d5c14742bcf4238061f330edf265355da210bf53acb2fe80e13d0c436d7\",\n        \"size\": 158444884\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9418_Weather9.tar.gz\": {\n        \"sha256\": \"d48a3704da5bb76c997c63f4d0323257d42c7980ace4fb9b161fcbaec3304b6d\",\n        \"size\": 153682956\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9419_Weather10.tar.gz\": {\n        \"sha256\": \"cffbd2a582fe0cc02ed0c2e465c2e88de21fe41b91e9582639e4003781d445b6\",\n        \"size\": 228856953\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9420_Weather11.tar.gz\": {\n        \"sha256\": \"77c8e24f6c8105a03798ca460d4001f83a854d452cb5fd6ee647d517558a0850\",\n        \"size\": 96450241\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9421_Weather12.tar.gz\": {\n        \"sha256\": \"07c56b9b80895214b5553fe3f7a0feefdf03a4204c90f2222f859286654e2fe8\",\n        \"size\": 266222778\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9423_Weather14.tar.gz\": {\n        \"sha256\": \"2fbe6d52d821ab763a1950927f60ac6810577eae53a5227e6ca9376c6d2cfee1\",\n        \"size\": 200028424\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9426_Weather9.tar.gz\": {\n        \"sha256\": \"b4f0706535135fb7067a5ba28c1371bfe5614719020ed9d32e7209a01647e664\",\n        \"size\": 185582757\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9427_Weather18.tar.gz\": {\n        \"sha256\": \"77834c5164b4811169cae94688136d3edfaa96175e927eb3f660519058ad8b94\",\n        \"size\": 212612945\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9430_Weather21.tar.gz\": {\n        \"sha256\": \"f5f5508c2bc99eda3faea953ac0e842d0093db7f2c8b5bc7847c06b73ff08d83\",\n        \"size\": 219753730\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9431_Weather22.tar.gz\": {\n        \"sha256\": \"655c5172864c4cea3e523b593f7c9f09529309b2d7e50609822a4f2fddd3c0ba\",\n        \"size\": 179500023\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9435_Weather0.tar.gz\": {\n        \"sha256\": \"5e6de7828a25ac615588a0ee7b97d9c75a056c1f60a8f70a5b0bd18891eac56e\",\n        \"size\": 237332833\n    },\n    \"OppositeVehicleTakingPriority_Town12_Route9436_Weather1.tar.gz\": {\n        \"sha256\": \"287fe589d06b39a509e4e4f86fc353e839593783b92a429aa98ee18cd8b68770\",\n        \"size\": 405710459\n    },\n    \"PedestrianCrossing_Town12_Route13458_Weather19.tar.gz\": {\n        \"sha256\": \"40b57185d7143690d6980ff0f353913e76913be504e14ff5dad0292d3bdccc3a\",\n        \"size\": 570918925\n    },\n    \"PedestrianCrossing_Town12_Route13459_Weather20.tar.gz\": {\n        \"sha256\": \"5d00977fe729cd3119fd1146e512aae9832cf57e46c28c742bef6d3545d3af45\",\n        \"size\": 300842211\n    },\n    \"PedestrianCrossing_Town12_Route13461_Weather22.tar.gz\": {\n        \"sha256\": \"d9e56e6594bc74e312b2c5da4c7174db6f3df243eaf372f76a2cb83afadeb461\",\n        \"size\": 443886014\n    },\n    \"PedestrianCrossing_Town12_Route13463_Weather23.tar.gz\": {\n        \"sha256\": \"7c2f77cfa7d9889c39604084439bff58602715cb69d9d2deedfd0c7f7c2dd8fe\",\n        \"size\": 92245069\n    },\n    \"PedestrianCrossing_Town12_Route13465_Weather0.tar.gz\": {\n        \"sha256\": \"7fab0ac7b901f4707775820989189dce3085cc52cdafe403ced1376ae56a561f\",\n        \"size\": 217036435\n    },\n    \"PedestrianCrossing_Town12_Route13466_Weather1.tar.gz\": {\n        \"sha256\": \"3e651bf4425acc5a960426be3bcab8d3e012a10d10de418da6ec7f599b384b72\",\n        \"size\": 195671429\n    },\n    \"PedestrianCrossing_Town12_Route13467_Weather2.tar.gz\": {\n        \"sha256\": \"62732c0e8e12fbe3673501c9167d9abac108a8559cda3cfb3d6a0a2fbeda6056\",\n        \"size\": 344980012\n    },\n    \"PedestrianCrossing_Town12_Route13468_Weather3.tar.gz\": {\n        \"sha256\": \"086c8c0b196ca691b83f59ba1731641a194e586fd31d6ca0e56739cdcc02f47e\",\n        \"size\": 404909483\n    },\n    \"PedestrianCrossing_Town12_Route13471_Weather6.tar.gz\": {\n        \"sha256\": \"d3dbca71192e417389e32e638e1e0bbee18873d94482dc4d930883d8362ab39a\",\n        \"size\": 350772666\n    },\n    \"PedestrianCrossing_Town12_Route13472_Weather7.tar.gz\": {\n        \"sha256\": \"a93e4fdbab144a268f3c7356a80a55a0b18a32b280caf923a6d7b8a059ef3765\",\n        \"size\": 523252487\n    },\n    \"PedestrianCrossing_Town12_Route13473_Weather8.tar.gz\": {\n        \"sha256\": \"ad01895a21b02488d2aa3fd3a5899275d412b7f8fc5aaa06d5c5d1ce8f882acb\",\n        \"size\": 608692055\n    },\n    \"PedestrianCrossing_Town12_Route13474_Weather9.tar.gz\": {\n        \"sha256\": \"dde76a0eae21afcd73696bac8ed4460a1b5361c3e82e66c10c5a68b8cc9aa130\",\n        \"size\": 764208228\n    },\n    \"PedestrianCrossing_Town12_Route13475_Weather10.tar.gz\": {\n        \"sha256\": \"cb78ae6f7ab0a2ddda481c8f2f759c357fcfdcef3707444eb779e199a2a96a7a\",\n        \"size\": 545611748\n    },\n    \"PedestrianCrossing_Town12_Route13476_Weather11.tar.gz\": {\n        \"sha256\": \"7291691d31a27a9af68a93ad3855c7f481fbeeba8a952789f64535176189704b\",\n        \"size\": 223322392\n    },\n    \"PedestrianCrossing_Town12_Route13478_Weather13.tar.gz\": {\n        \"sha256\": \"d623aa0c73a943c64c98c5e7fc16ba03ac36f38dd207a91c3b1445ceed8b8684\",\n        \"size\": 180513662\n    },\n    \"PedestrianCrossing_Town12_Route13480_Weather15.tar.gz\": {\n        \"sha256\": \"80b0c1830b3ce4977bba836148e7980d50a6a9c0e56247d0f4cd8135bcc43e37\",\n        \"size\": 186968975\n    },\n    \"PedestrianCrossing_Town12_Route13481_Weather8.tar.gz\": {\n        \"sha256\": \"9e8fc30d9571ed94ec0c9aa1821cf4c10127399a786a9f7591e6e8b36b331f2f\",\n        \"size\": 282293049\n    },\n    \"PedestrianCrossing_Town12_Route13485_Weather20.tar.gz\": {\n        \"sha256\": \"9a8e8b43ad812dc26b8fca752c4382ff1390c4d283231f113676d4d6aecf4ae1\",\n        \"size\": 439920879\n    },\n    \"PedestrianCrossing_Town12_Route13488_Weather23.tar.gz\": {\n        \"sha256\": \"c6eaab0e0d8911695a4b7c2b7141314279afba340ab81413499a00efc5966566\",\n        \"size\": 193752882\n    },\n    \"PedestrianCrossing_Town12_Route13489_Weather23.tar.gz\": {\n        \"sha256\": \"fbc963147f77ce25277ea2444ba4abda9c599661b120111597e2bbf8db22d8aa\",\n        \"size\": 129765335\n    },\n    \"PedestrianCrossing_Town12_Route13490_Weather25.tar.gz\": {\n        \"sha256\": \"2df89f493f45f6b2e3a45e4af7a0fe5c1343e9c5a8b3b401dd37e2df9671fc88\",\n        \"size\": 143094793\n    },\n    \"PedestrianCrossing_Town12_Route13492_Weather1.tar.gz\": {\n        \"sha256\": \"99abdc0956a8f42c310cedd3bdfe4e1fe478e6cd317412841fcae5302e805cd6\",\n        \"size\": 219351730\n    },\n    \"PedestrianCrossing_Town12_Route13493_Weather2.tar.gz\": {\n        \"sha256\": \"c47f405ab4b693e0cbb34a2bc51e7e8acd60acafb657dfcf60f9741c4708bb81\",\n        \"size\": 171785109\n    },\n    \"PedestrianCrossing_Town12_Route13494_Weather3.tar.gz\": {\n        \"sha256\": \"1d0ed3f4e65f8c9898f34918366ca5cb6a11b47f667f6366b58a81e909f45dd7\",\n        \"size\": 328647056\n    },\n    \"PedestrianCrossing_Town12_Route13495_Weather3.tar.gz\": {\n        \"sha256\": \"4205df8a1057e28fbc9aa821984202b897f6dbc47cc8bbdb39ff39d7e9a984cc\",\n        \"size\": 183654360\n    },\n    \"PedestrianCrossing_Town12_Route13497_Weather6.tar.gz\": {\n        \"sha256\": \"2accd3fbb33d5d5bbe6ef540231c02cf66913fd202c3873e4721e64ba2a2149a\",\n        \"size\": 204854888\n    },\n    \"PedestrianCrossing_Town12_Route13498_Weather7.tar.gz\": {\n        \"sha256\": \"106b408f42f557dff6a4bded9b6d6ada1013baca9a2e2e8ff97a5134bd0868ec\",\n        \"size\": 406525867\n    },\n    \"PedestrianCrossing_Town12_Route13499_Weather8.tar.gz\": {\n        \"sha256\": \"97260b8e08dda885f04a38e5b4c34753bf80c7c50cff0062c9cd60e1dbfcf602\",\n        \"size\": 293020305\n    },\n    \"PedestrianCrossing_Town12_Route13500_Weather9.tar.gz\": {\n        \"sha256\": \"575c14e30559e14ffa8c6cfe550991bed89753ad29ef1a48a6b39cdc9768e108\",\n        \"size\": 102037558\n    },\n    \"PedestrianCrossing_Town12_Route13501_Weather10.tar.gz\": {\n        \"sha256\": \"b2c8de9bcc6d3c9b14fccfbc81a0383c1e808c50104b903b6148a2d6b42b268b\",\n        \"size\": 316521896\n    },\n    \"PedestrianCrossing_Town12_Route13503_Weather12.tar.gz\": {\n        \"sha256\": \"4819f97fa59f3e97cdab21ca058824cd3203b752f5ac1148ce09d79b8b505799\",\n        \"size\": 151377952\n    },\n    \"PedestrianCrossing_Town12_Route13504_Weather13.tar.gz\": {\n        \"sha256\": \"ab06b273f145d885edc4aae60f2f34ac59881bc86575b3e59e95317ff9216898\",\n        \"size\": 235982439\n    },\n    \"PedestrianCrossing_Town12_Route13505_Weather14.tar.gz\": {\n        \"sha256\": \"844ac6f315a810249b5d4c0691a139538dfc85acd6a841c2109501c9f400ce61\",\n        \"size\": 708641062\n    },\n    \"PedestrianCrossing_Town12_Route13506_Weather15.tar.gz\": {\n        \"sha256\": \"9bb183933e491e9f4c7aef4282b5b08e8de58b7c6436be662d13e86f6ce1d9ee\",\n        \"size\": 166582650\n    },\n    \"PedestrianCrossing_Town12_Route13507_Weather8.tar.gz\": {\n        \"sha256\": \"781ece5a51ad7fdacbc085cda6953f08724d52705a523bb9b527041167b55150\",\n        \"size\": 553171000\n    },\n    \"PedestrianCrossing_Town12_Route13508_Weather9.tar.gz\": {\n        \"sha256\": \"d9f87edcb43bdbd2af8a3e3e68f28b4c34ff8670c54b667b7910d7206d59d3f9\",\n        \"size\": 180063877\n    },\n    \"PedestrianCrossing_Town12_Route13510_Weather19.tar.gz\": {\n        \"sha256\": \"19f5da219c3b01fdfcc1e801f495447f93d165bc836943e089d61f7b61d44099\",\n        \"size\": 127337296\n    },\n    \"PedestrianCrossing_Town12_Route13511_Weather20.tar.gz\": {\n        \"sha256\": \"dbc37c163d86578ada9728c8dbf6e1f0c254ab2ff5252975c08c80c6f1c1de07\",\n        \"size\": 402631854\n    },\n    \"PedestrianCrossing_Town12_Route13513_Weather22.tar.gz\": {\n        \"sha256\": \"f0f14c49e3030e973e69d182c65551f39f1319a14ee457c5da24bbb17ac592c3\",\n        \"size\": 482669159\n    },\n    \"PedestrianCrossing_Town12_Route13514_Weather23.tar.gz\": {\n        \"sha256\": \"10575d97dfeb4e1d6fab534eedc1d7e4a15fe7875fb498c1266a777422b42415\",\n        \"size\": 686687958\n    },\n    \"PedestrianCrossing_Town12_Route13515_Weather23.tar.gz\": {\n        \"sha256\": \"03d85b7cf11326ede1a2f712d06be23c8fdc1d935a84d9ba8d335e2667bb6a92\",\n        \"size\": 191063477\n    },\n    \"PedestrianCrossing_Town12_Route13516_Weather25.tar.gz\": {\n        \"sha256\": \"95fa49bcdfba4ba7ae9ae18751fe1983fd2f5c8337986cd8ceddfa4dd6482dad\",\n        \"size\": 440825591\n    },\n    \"PedestrianCrossing_Town12_Route13517_Weather0.tar.gz\": {\n        \"sha256\": \"c0668c63f987fbe942f883742898c3c8f7235459662febe87385d30d6e9ec993\",\n        \"size\": 355295797\n    },\n    \"PedestrianCrossing_Town12_Route13518_Weather1.tar.gz\": {\n        \"sha256\": \"e1464282f059649f68e6e42977237a5e491a10d502556ea6a27eb63330a2d440\",\n        \"size\": 350534950\n    },\n    \"PedestrianCrossing_Town12_Route13519_Weather2.tar.gz\": {\n        \"sha256\": \"c44ddd208898687d5b6f5ffadb55b01b7308afd5a2db85759a022895e4416a31\",\n        \"size\": 182726006\n    },\n    \"PedestrianCrossing_Town12_Route13521_Weather3.tar.gz\": {\n        \"sha256\": \"bec62321ad81a4506aff098e3a241b0e4325e9967179d826e534740d18f4010b\",\n        \"size\": 227626337\n    },\n    \"PedestrianCrossing_Town12_Route13523_Weather6.tar.gz\": {\n        \"sha256\": \"a4f791ed42e325f72dfeff37b096ec3a967c07de1829ba71d956d79294831458\",\n        \"size\": 504716607\n    },\n    \"PedestrianCrossing_Town12_Route13526_Weather9.tar.gz\": {\n        \"sha256\": \"882f27b6153e5254119c28c9237485411eef2d11401e0b14ba5a08c2d7985d5f\",\n        \"size\": 213340364\n    },\n    \"PedestrianCrossing_Town12_Route13527_Weather10.tar.gz\": {\n        \"sha256\": \"fba5debaf049d2724f5a93f635aeaa8729e3dcb0fbba2b6f42ad3231d3b37973\",\n        \"size\": 244407029\n    },\n    \"PedestrianCrossing_Town12_Route13528_Weather11.tar.gz\": {\n        \"sha256\": \"aebbd0ba9c857e8424ffb0310cebd231427664624057c2603ee7a632e757a8ed\",\n        \"size\": 478066582\n    },\n    \"PedestrianCrossing_Town12_Route13529_Weather12.tar.gz\": {\n        \"sha256\": \"84529a4fa4b9a0bd1be3401063d0530a688637251f3755267ed405ac4241e4d7\",\n        \"size\": 568727556\n    },\n    \"PedestrianCrossing_Town12_Route13532_Weather15.tar.gz\": {\n        \"sha256\": \"962f41bb92329e7fd65ec8d6dd5019520bac7a2675954f057d39f9240b55025e\",\n        \"size\": 403445788\n    },\n    \"PedestrianCrossing_Town12_Route13534_Weather9.tar.gz\": {\n        \"sha256\": \"fae23e30cdceee0f9e6a0925b5af5a68b189958297a7b6b06f96e32c8b1af856\",\n        \"size\": 162818600\n    },\n    \"PedestrianCrossing_Town12_Route13538_Weather21.tar.gz\": {\n        \"sha256\": \"ce94f96eab03ccea0b6c1250c1b97fed0582e04f735132b187fa7580ddcb4fec\",\n        \"size\": 104728440\n    },\n    \"PedestrianCrossing_Town12_Route13539_Weather22.tar.gz\": {\n        \"sha256\": \"1438eb6e20dfa98bd3d63b8c3e4ef91c3397f7f754d96a72a8b05b74cdc22cc5\",\n        \"size\": 544380938\n    },\n    \"PedestrianCrossing_Town12_Route13540_Weather23.tar.gz\": {\n        \"sha256\": \"863d387f25d1b86ba2795e2febab08b6ae64cacf65aea7e3121037070f52e16f\",\n        \"size\": 166214357\n    },\n    \"PedestrianCrossing_Town12_Route13541_Weather23.tar.gz\": {\n        \"sha256\": \"229f1a25cbb76a89b081e82b36e94d7c1aff65085ae6b6304ece3ac34c7c17ea\",\n        \"size\": 427830836\n    },\n    \"PedestrianCrossing_Town12_Route13542_Weather25.tar.gz\": {\n        \"sha256\": \"41a0af97c64f2f0f647e28c8651b4e6b6343297bdc2c7d405fa703d70f8aa471\",\n        \"size\": 464047785\n    },\n    \"PedestrianCrossing_Town12_Route13543_Weather0.tar.gz\": {\n        \"sha256\": \"bbd936555f5da6841e8bbf589898ba7bbe0134838ee8a4ca7cb332d554f4bada\",\n        \"size\": 148326789\n    },\n    \"PedestrianCrossing_Town12_Route13544_Weather1.tar.gz\": {\n        \"sha256\": \"015efb3b6a64adc7ff66fe6617ca66149ede71648fe0fbe4e491395a62f89ef4\",\n        \"size\": 205269156\n    },\n    \"PedestrianCrossing_Town12_Route13546_Weather3.tar.gz\": {\n        \"sha256\": \"aa219dbd41c6f9c31932f23ff22d79f385e79a2f57eed1ae311417321e96949d\",\n        \"size\": 463571879\n    },\n    \"PedestrianCrossing_Town12_Route13548_Weather5.tar.gz\": {\n        \"sha256\": \"f6381111b99a6e22585d8dd94a031665350ec9adaed607ccd35f8833985bea0e\",\n        \"size\": 172083915\n    },\n    \"PedestrianCrossing_Town12_Route13552_Weather9.tar.gz\": {\n        \"sha256\": \"081a7480f3923ea52e73feb1dc4815e42aa4b070b0798535ce9e95cccb910075\",\n        \"size\": 149497811\n    },\n    \"PedestrianCrossing_Town12_Route13553_Weather10.tar.gz\": {\n        \"sha256\": \"d3b642a9580c1e8684303875f24af1a96743bae6725c211c175536022979f390\",\n        \"size\": 428394858\n    },\n    \"PedestrianCrossing_Town12_Route13556_Weather13.tar.gz\": {\n        \"sha256\": \"778b20b502f975530bdd1d3c53849c72fc4365f4505d0e31b0ae2ac5825754dd\",\n        \"size\": 171582435\n    },\n    \"PedestrianCrossing_Town12_Route13557_Weather14.tar.gz\": {\n        \"sha256\": \"ee0e91ac9f942c7bc5745e0f28ff01a20315256d57880e607fc7d8fd461e1306\",\n        \"size\": 91807767\n    },\n    \"PedestrianCrossing_Town12_Route13558_Weather15.tar.gz\": {\n        \"sha256\": \"1e49a79bfa02020734e3250bc4ea928392ed4faa0a093bac21883dd9d9249fd4\",\n        \"size\": 581524481\n    },\n    \"PedestrianCrossing_Town12_Route13561_Weather18.tar.gz\": {\n        \"sha256\": \"d022439c7eaa7fd7c5dc27ae5a5864a169e29eeab6bf11860f7a0fbe0f6a13f9\",\n        \"size\": 684397706\n    },\n    \"PedestrianCrossing_Town12_Route13562_Weather19.tar.gz\": {\n        \"sha256\": \"40b1fa200554136260883afb8c27859d734d550130816e29b292ebd7c4b067f8\",\n        \"size\": 550202854\n    },\n    \"PedestrianCrossing_Town12_Route13563_Weather20.tar.gz\": {\n        \"sha256\": \"e32a87c2e0ac843a9a4c9ff2121877968d91ac78102ce6bd8d230fc386bc72bc\",\n        \"size\": 343564001\n    },\n    \"PedestrianCrossing_Town12_Route13564_Weather21.tar.gz\": {\n        \"sha256\": \"40d9fb0b8627248dcd8fbb27f67e270db49ea5b9073fedc7a8d59ef8bacb772d\",\n        \"size\": 211111192\n    },\n    \"PedestrianCrossing_Town12_Route13565_Weather22.tar.gz\": {\n        \"sha256\": \"38c19cbb1b1db2b58228585b2f1a34110bf76842e7602fa40159252cc4ed95db\",\n        \"size\": 208637863\n    },\n    \"PedestrianCrossing_Town12_Route13569_Weather0.tar.gz\": {\n        \"sha256\": \"730128cfd1e21498879715a2fee36cf4a5b350007c68b8f315fb413a86b39b42\",\n        \"size\": 211635430\n    },\n    \"PedestrianCrossing_Town12_Route13570_Weather1.tar.gz\": {\n        \"sha256\": \"7416801a5b9915c93b9860b83003594a200359041754b1f660e2e1a9dd24bcff\",\n        \"size\": 316525075\n    },\n    \"PedestrianCrossing_Town12_Route13571_Weather2.tar.gz\": {\n        \"sha256\": \"26b313e7065b2a087350c0911e0b0a1317afc4738294ae8d232963c1d9266ae3\",\n        \"size\": 517671712\n    },\n    \"PedestrianCrossing_Town12_Route13572_Weather3.tar.gz\": {\n        \"sha256\": \"65c497ffb82d7978fc5480152c7bb1ec6ac948d1d48640c00447f5881f79e4ea\",\n        \"size\": 459993325\n    },\n    \"PedestrianCrossing_Town12_Route13574_Weather5.tar.gz\": {\n        \"sha256\": \"20cd023d1ed984f42dcec05ea460ff0badb309ac0341a7b0b9a9026b4f8bbeb5\",\n        \"size\": 312109071\n    },\n    \"PedestrianCrossing_Town12_Route13577_Weather8.tar.gz\": {\n        \"sha256\": \"f6184c2a8991aaadd82a9bcc222d23672527482a9c6515ac4a12e50ff21b05ab\",\n        \"size\": 635396331\n    },\n    \"PedestrianCrossing_Town12_Route13578_Weather9.tar.gz\": {\n        \"sha256\": \"f3975fedc8d76b5f09cacdf80866a916053893c492e7f2f309f16a4714d98634\",\n        \"size\": 196218527\n    },\n    \"PedestrianCrossing_Town12_Route13580_Weather11.tar.gz\": {\n        \"sha256\": \"398c6d7d15651d6819e8f3b141bf196da35ec97587ca9a435c1d1e26b6aedf94\",\n        \"size\": 360157833\n    },\n    \"PedestrianCrossing_Town12_Route13581_Weather12.tar.gz\": {\n        \"sha256\": \"44fbed894d8261be6f1fdc41ebea627fdfe1f54c9180d7d48af15ec740935ee9\",\n        \"size\": 367971402\n    },\n    \"PedestrianCrossing_Town12_Route13582_Weather13.tar.gz\": {\n        \"sha256\": \"c78280c73a0cb8c6d0619cbde27a657f393cbe8c6ba6f0d10717ab51549fb43d\",\n        \"size\": 155681265\n    },\n    \"PedestrianCrossing_Town12_Route13584_Weather15.tar.gz\": {\n        \"sha256\": \"21b67a1fcef7c8af6cc548c3c2e9098fc52e192327b0b31deda372ee4d82f46f\",\n        \"size\": 375064810\n    },\n    \"PedestrianCrossing_Town12_Route13585_Weather8.tar.gz\": {\n        \"sha256\": \"1220a87f310f7bf4ceab52a4df8cdb18a5c1856f31463d9ac6fff60403459250\",\n        \"size\": 454109294\n    },\n    \"PedestrianCrossing_Town12_Route13586_Weather9.tar.gz\": {\n        \"sha256\": \"46154bf760b6b1efa03da393c24e718a3cbc2b432046fe4bfca9fb275bf85546\",\n        \"size\": 307730316\n    },\n    \"PedestrianCrossing_Town12_Route13589_Weather20.tar.gz\": {\n        \"sha256\": \"87d910b9a1d87f61e0fff67e0550c7c2bab681a47f33ec6aea1e551b8524ed5d\",\n        \"size\": 334897953\n    },\n    \"PedestrianCrossing_Town12_Route13590_Weather21.tar.gz\": {\n        \"sha256\": \"756eb8b4999b3205d1361879e87450928772f9632a1fca656b4fddf9e618778a\",\n        \"size\": 305488852\n    },\n    \"PedestrianCrossing_Town12_Route13591_Weather22.tar.gz\": {\n        \"sha256\": \"c101b6d096bb10381915c682fa31198a9307e672c7369f32ab825a520c1c5da1\",\n        \"size\": 294988284\n    },\n    \"PedestrianCrossing_Town12_Route13592_Weather23.tar.gz\": {\n        \"sha256\": \"eea9743362a351162253aa4472e0dc198167e0e33b06fad885bb1887f41e59bf\",\n        \"size\": 607128636\n    },\n    \"PedestrianCrossing_Town12_Route13593_Weather23.tar.gz\": {\n        \"sha256\": \"6e3cf3682e98e53715229995668ae1200f33423cbf6667e882c0ad850ffaa218\",\n        \"size\": 480204576\n    },\n    \"PedestrianCrossing_Town12_Route13594_Weather25.tar.gz\": {\n        \"sha256\": \"9fe1eb83ee99b76a1faaec8695275e0f3b370439f6d4397a5d78708638f5691f\",\n        \"size\": 118388720\n    },\n    \"PedestrianCrossing_Town12_Route13595_Weather0.tar.gz\": {\n        \"sha256\": \"2bee2130a573cf52f5bd8efe8a50308e5f99d358499dda3431673499f5fdd7ec\",\n        \"size\": 451699955\n    },\n    \"PedestrianCrossing_Town12_Route13596_Weather1.tar.gz\": {\n        \"sha256\": \"210076dc6b17d98ad06660a2644481c72b94fa521198006554ed9c2f26ee1008\",\n        \"size\": 381716566\n    },\n    \"PedestrianCrossing_Town12_Route13597_Weather2.tar.gz\": {\n        \"sha256\": \"cf8de29e889d6b181a92ee95cbb68c0727f071e4a8cb44fce11a843363af9951\",\n        \"size\": 297322300\n    },\n    \"PedestrianCrossing_Town12_Route13598_Weather3.tar.gz\": {\n        \"sha256\": \"25218b85a70e3fb06bc01f1a9114f026dba31f01e532cc2be64fae4c5222a566\",\n        \"size\": 719381069\n    },\n    \"PedestrianCrossing_Town12_Route13599_Weather3.tar.gz\": {\n        \"sha256\": \"80aa93d7cc00a7061502961dd38fe1e6b6dfead17c10c0a6dad75f1a6257696a\",\n        \"size\": 94162841\n    },\n    \"PedestrianCrossing_Town12_Route13601_Weather6.tar.gz\": {\n        \"sha256\": \"defc8882db47fe8487dd04c6e7bf8f1158cceac5bc343b33a80aae9116470c9f\",\n        \"size\": 286845753\n    },\n    \"PedestrianCrossing_Town12_Route13602_Weather7.tar.gz\": {\n        \"sha256\": \"7fd81ea65824585417733d5265613612468425906f626fbd524670485ca77eda\",\n        \"size\": 389297097\n    },\n    \"PedestrianCrossing_Town12_Route13604_Weather9.tar.gz\": {\n        \"sha256\": \"634cb4b77c06bd57bf28cd6cb5f7c3ea38c35a35ae2a09b830cee39750774500\",\n        \"size\": 275809040\n    },\n    \"PedestrianCrossing_Town12_Route13605_Weather10.tar.gz\": {\n        \"sha256\": \"99316d37504d2a825cd3d91a20d1da666f0871e4bf6a141136fbad58a173977e\",\n        \"size\": 862296032\n    },\n    \"PedestrianCrossing_Town12_Route13609_Weather14.tar.gz\": {\n        \"sha256\": \"aeec4948fa0a044ba9c44a10ec6b8d868d9ba229177d415daeeb63e2d2c1b114\",\n        \"size\": 397510968\n    },\n    \"PedestrianCrossing_Town12_Route13611_Weather8.tar.gz\": {\n        \"sha256\": \"dcb8763eaed5f5943dc3f6b841942ae64eeeb493db58b65716e4bbf984221f19\",\n        \"size\": 811243762\n    },\n    \"PedestrianCrossing_Town12_Route13612_Weather9.tar.gz\": {\n        \"sha256\": \"a0fa10ef09e74545b1a6cac90f695e28c5b7ca7963a32cf5db3bcbc22b3ae8d5\",\n        \"size\": 171487661\n    },\n    \"PedestrianCrossing_Town12_Route13613_Weather18.tar.gz\": {\n        \"sha256\": \"5efa337955fadea7be148260db5c715e5e87dcdb583574f7d948a3dbf3f1672e\",\n        \"size\": 271466864\n    },\n    \"PedestrianCrossing_Town12_Route13614_Weather19.tar.gz\": {\n        \"sha256\": \"7bda1e82856282ca9a1b7a2bf5c7dc83ccf6821ad26e24d526287a4427e277b1\",\n        \"size\": 437724140\n    },\n    \"PedestrianCrossing_Town12_Route13615_Weather20.tar.gz\": {\n        \"sha256\": \"b395e4c46aca3ad68f037fdad6d05742e7078b4b89f3959aaef6ac890833586a\",\n        \"size\": 207644725\n    },\n    \"PedestrianCrossing_Town12_Route13620_Weather25.tar.gz\": {\n        \"sha256\": \"131ad56b58f58abd91691a72e64247c8209bc8b8d635c34eb39fcda5bfefd547\",\n        \"size\": 243328394\n    },\n    \"PedestrianCrossing_Town12_Route13622_Weather1.tar.gz\": {\n        \"sha256\": \"fb588a4fcefe7066a53add0919ac122b9ccbf0e102d96890dcc6038c0afc379a\",\n        \"size\": 343948993\n    },\n    \"PedestrianCrossing_Town12_Route13624_Weather3.tar.gz\": {\n        \"sha256\": \"9aa1b16fa4f7bb96b405aee384222c03b2631590ffb91ae258daa60754231442\",\n        \"size\": 738121123\n    },\n    \"PedestrianCrossing_Town12_Route13625_Weather3.tar.gz\": {\n        \"sha256\": \"c505468c4e23fc989d7970706d12b1c7a7ee0f94cd756a8c8a523ad811e9e535\",\n        \"size\": 352326734\n    },\n    \"PedestrianCrossing_Town12_Route13627_Weather6.tar.gz\": {\n        \"sha256\": \"c054ff7fafa5db130180e0fc166998b1901e941d91da3f4a9fde80d9301a1193\",\n        \"size\": 268809857\n    },\n    \"PedestrianCrossing_Town12_Route13628_Weather7.tar.gz\": {\n        \"sha256\": \"ac9e42e62c83c3a13edbd839b370cc44ed4173371c08470be169ad87afab9ddc\",\n        \"size\": 330391760\n    },\n    \"PedestrianCrossing_Town12_Route13630_Weather9.tar.gz\": {\n        \"sha256\": \"89113f7bb1aed22eef45fc2c58ee40f45638e8b3a926a1aa5b033eb09e2ccb72\",\n        \"size\": 216774479\n    },\n    \"PedestrianCrossing_Town12_Route13632_Weather11.tar.gz\": {\n        \"sha256\": \"8bdd12eec6a2c19ab46231f47c35b3ec03923ade3ba6d2c4d9e85798c30f3b78\",\n        \"size\": 587216805\n    },\n    \"PedestrianCrossing_Town12_Route13633_Weather12.tar.gz\": {\n        \"sha256\": \"4c503ceba6f62235de083d39b2e10400756b8f2957c7a26aaf1ffbd7fdeebc64\",\n        \"size\": 103770895\n    },\n    \"PedestrianCrossing_Town12_Route13634_Weather13.tar.gz\": {\n        \"sha256\": \"d49db5056056e5897fe8c4932bf9db6b9145d38f045ca3a5bd98cf32f0395980\",\n        \"size\": 499327667\n    },\n    \"PedestrianCrossing_Town12_Route13635_Weather14.tar.gz\": {\n        \"sha256\": \"89ac6fa0d8776bc6bd87308c20a715c2cc6b7dbdb4ba90a29eee8600f0ac1dd6\",\n        \"size\": 253135482\n    },\n    \"PedestrianCrossing_Town12_Route13637_Weather8.tar.gz\": {\n        \"sha256\": \"e6c7d4cccf82766b7b33a54ac37c34e55bc2cc4590a868f0f937efcb5b9e545b\",\n        \"size\": 470129496\n    },\n    \"PedestrianCrossing_Town12_Route13640_Weather19.tar.gz\": {\n        \"sha256\": \"f900c8e8db1eeaf17a166e943462eb7533c03d8b8f27b84b86e8a8cfe5d57357\",\n        \"size\": 559902781\n    },\n    \"PedestrianCrossing_Town12_Route13641_Weather20.tar.gz\": {\n        \"sha256\": \"35000a6d02e56919821a82c788cc38eb1012e7b42ea8f2acdc2435faf8afbbf6\",\n        \"size\": 541799753\n    },\n    \"PedestrianCrossing_Town12_Route13642_Weather21.tar.gz\": {\n        \"sha256\": \"9882557adbbbdc98003ee769306a068231c57fb0f34854e05b717757c54bafa9\",\n        \"size\": 224722023\n    },\n    \"PedestrianCrossing_Town12_Route13644_Weather23.tar.gz\": {\n        \"sha256\": \"694ea5ab188852c3ae1e6db384c63af09d56f32d3380b97d8ca771bb65b0ca5d\",\n        \"size\": 278376673\n    },\n    \"PedestrianCrossing_Town12_Route13645_Weather23.tar.gz\": {\n        \"sha256\": \"8f36164af9b95b8a637c2009844a8b8fc65c38a965effb397222e5000882539a\",\n        \"size\": 638070046\n    },\n    \"PedestrianCrossing_Town12_Route13646_Weather25.tar.gz\": {\n        \"sha256\": \"6a49ab358cd5cb489445ec7544d3c5f5e7a564886b2b689f6e641a294ed01e5b\",\n        \"size\": 580532676\n    },\n    \"PedestrianCrossing_Town12_Route13648_Weather1.tar.gz\": {\n        \"sha256\": \"d5e27457ac4f66c2952293238f8689aa9e466b7d83445eef368095c7e2d259ad\",\n        \"size\": 411362284\n    },\n    \"PedestrianCrossing_Town12_Route13649_Weather2.tar.gz\": {\n        \"sha256\": \"cedc79d470f867505ff9b152a078757e12a45af9be70b8c0b6711910fc83e7c2\",\n        \"size\": 359207329\n    },\n    \"PedestrianCrossing_Town12_Route13652_Weather5.tar.gz\": {\n        \"sha256\": \"4aca96ff5079d5336032f15f36e05624af2e7308c926ffa24790d6d58c953db4\",\n        \"size\": 763668802\n    },\n    \"PedestrianCrossing_Town12_Route13653_Weather6.tar.gz\": {\n        \"sha256\": \"57405fc8f3fce1d4868a496a9ee87bf5400069d9d9998728da0565f2ab36a16f\",\n        \"size\": 350179391\n    },\n    \"PedestrianCrossing_Town12_Route13655_Weather8.tar.gz\": {\n        \"sha256\": \"61aacf755045606ea966f4cb6c121ab3821a47bedc305730253dad071875b973\",\n        \"size\": 347372777\n    },\n    \"PedestrianCrossing_Town12_Route13656_Weather9.tar.gz\": {\n        \"sha256\": \"82852678f4e0e21ced22b8bb251e5e305c0dc66a5b7038384baa7b75cca218d0\",\n        \"size\": 427385959\n    },\n    \"PedestrianCrossing_Town12_Route13657_Weather10.tar.gz\": {\n        \"sha256\": \"a0bcb48310f06bf4a13332ee2e90bb2fc29a48995aef8fe9065a1673bfefde2b\",\n        \"size\": 520973356\n    },\n    \"PedestrianCrossing_Town12_Route13658_Weather11.tar.gz\": {\n        \"sha256\": \"48263aab61db8c5dcbf7572fc9136073042366aa1d1aebe4a0349a65a50f62cf\",\n        \"size\": 146273919\n    },\n    \"PedestrianCrossing_Town12_Route13659_Weather12.tar.gz\": {\n        \"sha256\": \"e48d204619f552f1e83fb7a33c0526f1e14b289e1deebe611ad0892445ea5736\",\n        \"size\": 672104946\n    },\n    \"PedestrianCrossing_Town12_Route13660_Weather13.tar.gz\": {\n        \"sha256\": \"34316ebc4a2a9bbf7917225dffb442e25ce0bc85f8b9fa684192ae3de9ca834f\",\n        \"size\": 348703121\n    },\n    \"PedestrianCrossing_Town12_Route13661_Weather14.tar.gz\": {\n        \"sha256\": \"2f7a408675d132c3bfce5134efe41558ba19943a66e5c7c47f643d099cdb9aff\",\n        \"size\": 217747006\n    },\n    \"PedestrianCrossing_Town12_Route13664_Weather9.tar.gz\": {\n        \"sha256\": \"edc4cbfb64180d4c366153a7301419f9b52becb9efd2bd74bcd2c67ac7210409\",\n        \"size\": 415057336\n    },\n    \"PedestrianCrossing_Town12_Route13665_Weather18.tar.gz\": {\n        \"sha256\": \"dfd371f4d3599ba0a05c5e7f497ab7d744342e44cbd6a63806c22481303ba119\",\n        \"size\": 184481529\n    },\n    \"PedestrianCrossing_Town12_Route13666_Weather19.tar.gz\": {\n        \"sha256\": \"904c5d366e491f30feca6d7a9370b1737ce6ade86755332b17d039a2409f6b5e\",\n        \"size\": 607222418\n    },\n    \"PedestrianCrossing_Town12_Route13667_Weather20.tar.gz\": {\n        \"sha256\": \"2c35a5a82a8fa7568c55595ce717e70db5efebf7fd1aaadeee59db21edb46ae1\",\n        \"size\": 208106894\n    },\n    \"PedestrianCrossing_Town12_Route13669_Weather22.tar.gz\": {\n        \"sha256\": \"dd7f5413462e419ea3229a2a53032aae33cfa6295fbdcedee0b0658ce2c48f58\",\n        \"size\": 406710094\n    },\n    \"PedestrianCrossing_Town12_Route13671_Weather23.tar.gz\": {\n        \"sha256\": \"ccbb4d563a9e9483f217d47b268bea52f9d4ce9e08a4b66181cc68917df3f7cd\",\n        \"size\": 366273256\n    },\n    \"PedestrianCrossing_Town12_Route13675_Weather2.tar.gz\": {\n        \"sha256\": \"d4b9749cb0c4b944e50626a49f5e9ab13ca8f06d0376d1652778ac71f8131552\",\n        \"size\": 188304957\n    },\n    \"PedestrianCrossing_Town12_Route13676_Weather3.tar.gz\": {\n        \"sha256\": \"953647c7aec833cbadbd46e0a0dbfc9927230b7dbd4f6dd501e1ca669f5e4aaa\",\n        \"size\": 337804978\n    },\n    \"PedestrianCrossing_Town12_Route13677_Weather3.tar.gz\": {\n        \"sha256\": \"dcf933f21813a40a85fb956c7c545a808f08f6457826b42adb5cfae0b7e23238\",\n        \"size\": 724581596\n    },\n    \"PedestrianCrossing_Town12_Route13678_Weather5.tar.gz\": {\n        \"sha256\": \"b048ec2a26b79cd907c96a79889981a25a548ead35728c0859e09ef0f3480ceb\",\n        \"size\": 539335316\n    },\n    \"PedestrianCrossing_Town12_Route13679_Weather6.tar.gz\": {\n        \"sha256\": \"c7a6e90f93972fb40767d3d3324e61735578f37250c0005cda2ad48a61f88d1a\",\n        \"size\": 382145986\n    },\n    \"PedestrianCrossing_Town12_Route13680_Weather7.tar.gz\": {\n        \"sha256\": \"f83529b188c48f802f1d4ea53e9373ac25f0779b3e45fbad80433d1bfa72015b\",\n        \"size\": 638202076\n    },\n    \"PedestrianCrossing_Town12_Route13681_Weather8.tar.gz\": {\n        \"sha256\": \"211b178a33514d8d438bd6e296319c25eec8535afb393fe0672fd85fbf7cf29d\",\n        \"size\": 292562148\n    },\n    \"PedestrianCrossing_Town12_Route13682_Weather9.tar.gz\": {\n        \"sha256\": \"7f90db31f8295a521e9741f37686d802f22a46ae3544373f315e096c794a13ab\",\n        \"size\": 155416604\n    },\n    \"PedestrianCrossing_Town12_Route13685_Weather12.tar.gz\": {\n        \"sha256\": \"3de2efd9e7072fba2badbdd8a49365ecbdb1671d06f04f025139832fc5991d7f\",\n        \"size\": 304725467\n    },\n    \"PedestrianCrossing_Town12_Route13686_Weather13.tar.gz\": {\n        \"sha256\": \"ba34c7b319e2c9c0130bb0936ae330c029d8088c5b07d12a7364f1ee2c53efa3\",\n        \"size\": 369969953\n    },\n    \"PedestrianCrossing_Town12_Route13687_Weather14.tar.gz\": {\n        \"sha256\": \"11489af9eb025370b61130c27f3a7eed182ddca55a1696a024b8978aaa54a921\",\n        \"size\": 607901828\n    },\n    \"PedestrianCrossing_Town12_Route13691_Weather18.tar.gz\": {\n        \"sha256\": \"320503de56f388017b10417211de5db1302599d2a1575c19b30d8b5326576ada\",\n        \"size\": 253036408\n    },\n    \"PedestrianCrossing_Town12_Route13692_Weather19.tar.gz\": {\n        \"sha256\": \"d67e676af80c46b52871079114549a12a36bfa1316d717998ca18aa4546968a8\",\n        \"size\": 464952130\n    },\n    \"PedestrianCrossing_Town12_Route13694_Weather21.tar.gz\": {\n        \"sha256\": \"cb5a12ad4c8bc372887245a9559a1e2c92940e3b361cb0960556952e10f415d9\",\n        \"size\": 505386616\n    },\n    \"PedestrianCrossing_Town12_Route13695_Weather22.tar.gz\": {\n        \"sha256\": \"b55372ac6aa66227955e93a012317441af11de6483d7140075713f3d063fbd6a\",\n        \"size\": 168008650\n    },\n    \"PedestrianCrossing_Town12_Route13696_Weather23.tar.gz\": {\n        \"sha256\": \"8eea05df1334dd25834228f7e6e9e9fae7f10fea22ee8bdb06131172ef825f19\",\n        \"size\": 214023200\n    },\n    \"PedestrianCrossing_Town12_Route13697_Weather23.tar.gz\": {\n        \"sha256\": \"e073e48f915b07931ccad2ab23ec5202e9a6135b90abd0c8e391de5e1c63347d\",\n        \"size\": 162577848\n    },\n    \"PedestrianCrossing_Town12_Route13699_Weather0.tar.gz\": {\n        \"sha256\": \"36cd5acfff89866cb1cd5f55d519511033898fb467af1a9b6146363632c69cdf\",\n        \"size\": 363898463\n    },\n    \"PedestrianCrossing_Town12_Route13700_Weather1.tar.gz\": {\n        \"sha256\": \"83296aee1e1143b96d31ecb2964464ae94bbe7c5ed0ff9399847bdd0dd83252c\",\n        \"size\": 239059964\n    },\n    \"PedestrianCrossing_Town12_Route13702_Weather3.tar.gz\": {\n        \"sha256\": \"b5fe11bc09f300e2bbb93d3df85c9b2e6efbc8bfa578d33682d0664c4423dffd\",\n        \"size\": 398423442\n    },\n    \"PedestrianCrossing_Town12_Route13704_Weather5.tar.gz\": {\n        \"sha256\": \"a2060df5ced0642de378520742a9497d7a62ba98ca92a9d25f0ce53156654376\",\n        \"size\": 102574138\n    },\n    \"PedestrianCrossing_Town12_Route13705_Weather6.tar.gz\": {\n        \"sha256\": \"eb6f736ccd20a33a215b453194787b405dfdda28f27558fb2b2d00b919830a49\",\n        \"size\": 414780166\n    },\n    \"PedestrianCrossing_Town12_Route13706_Weather7.tar.gz\": {\n        \"sha256\": \"a06856596cf59466e0ce9b2fcef7004cae83b27e8fd724dd882711fc09bacde5\",\n        \"size\": 599658396\n    },\n    \"PedestrianCrossing_Town12_Route13707_Weather8.tar.gz\": {\n        \"sha256\": \"0956e5f206787801d3c6fb0dfd41db518cf73765808d33ef26d433aae8288059\",\n        \"size\": 636689201\n    },\n    \"PedestrianCrossing_Town12_Route13708_Weather9.tar.gz\": {\n        \"sha256\": \"55d18def53084073be8d8a5f71d2648a77316706f135683eabee7a79fda0caf3\",\n        \"size\": 280386627\n    },\n    \"PedestrianCrossing_Town12_Route13714_Weather15.tar.gz\": {\n        \"sha256\": \"fa3b561b58f670eb63636a892d6675d7471f7a47ad5b66d0c359df010ced90a8\",\n        \"size\": 627679217\n    },\n    \"PedestrianCrossing_Town12_Route13715_Weather8.tar.gz\": {\n        \"sha256\": \"582ae631601ea9f66af93bae128e0ddf5f8a7159a06b1ab7bf727034495e9675\",\n        \"size\": 190252770\n    },\n    \"PedestrianCrossing_Town12_Route13717_Weather18.tar.gz\": {\n        \"sha256\": \"24ee1fc93ac9e772a4c87c1b290a8bb9690b07cf9d94e77902dbdf58021c7dcc\",\n        \"size\": 372424371\n    },\n    \"PedestrianCrossing_Town12_Route13719_Weather20.tar.gz\": {\n        \"sha256\": \"c3719f0e30201b48e061532cf2bd9174244a0d099fa4e7f363161c76d45bfcbe\",\n        \"size\": 325504902\n    },\n    \"PedestrianCrossing_Town12_Route13720_Weather21.tar.gz\": {\n        \"sha256\": \"95f93e070ce8cfc46137ed65a2226d6f67d10764ed66ad2036118da43f81dfe3\",\n        \"size\": 502174293\n    },\n    \"PedestrianCrossing_Town12_Route13723_Weather23.tar.gz\": {\n        \"sha256\": \"abb196f8407f207dd276a225352e1a0a24b997e2bf258b4ccdcd05d593c593bb\",\n        \"size\": 137724958\n    },\n    \"PedestrianCrossing_Town12_Route13724_Weather25.tar.gz\": {\n        \"sha256\": \"760d2fb0addd533e1681ae0fafba87aae54b56b34360b9b94eed41a4c213bad9\",\n        \"size\": 107907334\n    },\n    \"PedestrianCrossing_Town12_Route13725_Weather0.tar.gz\": {\n        \"sha256\": \"0f8ab83369c2d5e05f40e8cfd2665263d51d34c2e4d8ee39845891b27aaa8da9\",\n        \"size\": 1132529463\n    },\n    \"PedestrianCrossing_Town12_Route13726_Weather1.tar.gz\": {\n        \"sha256\": \"26aad6160cdb328517d617d6fead8b5508462a7808aa537123fadee8f72ce871\",\n        \"size\": 181739390\n    },\n    \"PedestrianCrossing_Town12_Route13727_Weather2.tar.gz\": {\n        \"sha256\": \"c25f9b08b922f5eb3ba344b56251599cb495a1008ad62d8a13944e2a1b7a1007\",\n        \"size\": 553058863\n    },\n    \"PedestrianCrossing_Town12_Route13728_Weather3.tar.gz\": {\n        \"sha256\": \"4670efc9fc4f883920966b1fb40462e7283a9ba16067072be8e0c619163d3786\",\n        \"size\": 341822079\n    },\n    \"PedestrianCrossing_Town12_Route13729_Weather3.tar.gz\": {\n        \"sha256\": \"4c8c7de18d2de961be4bd10d9222e9926ea5edbe45087ef224c607407bdcb9cc\",\n        \"size\": 227764477\n    },\n    \"PedestrianCrossing_Town12_Route13731_Weather6.tar.gz\": {\n        \"sha256\": \"bc8ef563ce323a1053ee3c369bf72e2fc26424d64b8875ccdbcdaec61b3ca6b1\",\n        \"size\": 329240402\n    },\n    \"PedestrianCrossing_Town12_Route13733_Weather8.tar.gz\": {\n        \"sha256\": \"3bdbb1f9d0a25bb1db76f6351f2469d60f9b12b824c10173e01b9e41d9944753\",\n        \"size\": 400994018\n    },\n    \"PedestrianCrossing_Town12_Route13736_Weather11.tar.gz\": {\n        \"sha256\": \"6806ee36b6c88bf7880dcaa6fc8edf11e51fa6ac664f112418b6f40fbc580e12\",\n        \"size\": 335805205\n    },\n    \"PedestrianCrossing_Town12_Route13737_Weather12.tar.gz\": {\n        \"sha256\": \"bd31e8b65310830de69dee690f5b139fbc64260f44b732ef45714e1a8f71f0ec\",\n        \"size\": 428036193\n    },\n    \"PedestrianCrossing_Town12_Route13738_Weather13.tar.gz\": {\n        \"sha256\": \"e48a12d9223f564a83469d29fbbed32ebe4df0bfde3a3c465e78caa857640565\",\n        \"size\": 327813886\n    },\n    \"PedestrianCrossing_Town12_Route13739_Weather14.tar.gz\": {\n        \"sha256\": \"632a3e4cc9f6db88918ba45b2aba374dbbad5982215668af298d111451805c29\",\n        \"size\": 301433244\n    },\n    \"PedestrianCrossing_Town12_Route13743_Weather18.tar.gz\": {\n        \"sha256\": \"f568b2866db3c2dcd61051253a82fe2e8da405c8516d04456cb5032b63c59d7a\",\n        \"size\": 281910831\n    },\n    \"PedestrianCrossing_Town12_Route13744_Weather19.tar.gz\": {\n        \"sha256\": \"28adca0f526ae6cbc463dd676cbc7509048947e8a878035b20c90b8c502564a1\",\n        \"size\": 656101506\n    },\n    \"PedestrianCrossing_Town12_Route13746_Weather21.tar.gz\": {\n        \"sha256\": \"5aff82a3d390ffbbcab2e1147c1d5c59b80cb0d052b2b3f36bfdb71c67635901\",\n        \"size\": 309142753\n    },\n    \"PedestrianCrossing_Town12_Route13747_Weather22.tar.gz\": {\n        \"sha256\": \"23fdf5f0716b27fd6fa214e8250f17902087c48088fe20051514237fbd00f45e\",\n        \"size\": 761656891\n    },\n    \"PedestrianCrossing_Town12_Route13748_Weather23.tar.gz\": {\n        \"sha256\": \"ccaca093a761b763ac24a2c88960403f1723ddec7c8ec6c1d5ed7075ecd00c69\",\n        \"size\": 302739274\n    },\n    \"PedestrianCrossing_Town12_Route13749_Weather23.tar.gz\": {\n        \"sha256\": \"b0ebc4267ca6f6293a730e21fc93c7539326e8fec81226bfe6afd7ec3d6ef343\",\n        \"size\": 715873322\n    },\n    \"PedestrianCrossing_Town12_Route13750_Weather25.tar.gz\": {\n        \"sha256\": \"5a918a73719eb0b8bcd086b60b6b18756839902b9bac25e53173698453169e26\",\n        \"size\": 221141857\n    },\n    \"PedestrianCrossing_Town12_Route13751_Weather0.tar.gz\": {\n        \"sha256\": \"1418b9531a211bebae2e792a46ccd2582e3bbdec60cbf99a05c39730ac7ee5ba\",\n        \"size\": 214727111\n    },\n    \"PedestrianCrossing_Town12_Route13753_Weather2.tar.gz\": {\n        \"sha256\": \"057a712e612c12f38d739809badbaa8f597789638e118be3b07d9f10accaa11d\",\n        \"size\": 445820262\n    },\n    \"PedestrianCrossing_Town12_Route13754_Weather3.tar.gz\": {\n        \"sha256\": \"f5bac0b622f6f8c52d976fddfda79340e1f6cff99121a9dec6846929f1431986\",\n        \"size\": 716525833\n    },\n    \"PedestrianCrossing_Town12_Route13756_Weather5.tar.gz\": {\n        \"sha256\": \"8fd2391e3766d1349c15c8e4bc9105023e373c9488c5473a87c8db650e59a869\",\n        \"size\": 463388347\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route3088_Weather7.tar.gz\": {\n        \"sha256\": \"a05ff2d353b2cc2e1ec18b789ea7a5d20f4f70300446705f2ee396d6697b984f\",\n        \"size\": 198909020\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route3131_Weather3.tar.gz\": {\n        \"sha256\": \"4423c49fa90d98de0dadc13f7abc6469dda296b00c4fada4cdf56fa9b227126b\",\n        \"size\": 151242335\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route3170_Weather22.tar.gz\": {\n        \"sha256\": \"443394224a6ff07a25372be62251c908a365469e4c8b2d3db9ca4f46a4284665\",\n        \"size\": 205794994\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34444_Weather26.tar.gz\": {\n        \"sha256\": \"96445fdcf6cd29ad2994692ce8eb17bfffee9e5c4dbb52156822b559590e1281\",\n        \"size\": 207683558\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34447_Weather2.tar.gz\": {\n        \"sha256\": \"cc032df28d6d4804f6bacd99ba5c4a1014e3a50a8c0c5cf5b38411fd776f6d8b\",\n        \"size\": 316527640\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34451_Weather7.tar.gz\": {\n        \"sha256\": \"94aba711db8882d8d564b8eadadbf8e33a6651d59b6de30a21ac2609f10b6f85\",\n        \"size\": 193574996\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34452_Weather8.tar.gz\": {\n        \"sha256\": \"a54342b28a89fbde291a4af7dc3641b4d1a1e47c8b8488b3dd84d2ab0a1448f1\",\n        \"size\": 181804594\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34457_Weather13.tar.gz\": {\n        \"sha256\": \"001bbb2d87ee303649591612165ad31c86049d0e8d75cc9a615444988342ed9e\",\n        \"size\": 143323896\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34459_Weather15.tar.gz\": {\n        \"sha256\": \"d2ea89e0d59ab3ba4ee6c95c967b9b67b6a0e249c62125e6208fbb253f6962a1\",\n        \"size\": 233680189\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34465_Weather23.tar.gz\": {\n        \"sha256\": \"14681f96248e1ffb82bc5bf9ca05b309a7406c325e9184b1c64c07fc8678c3d4\",\n        \"size\": 185334072\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34466_Weather25.tar.gz\": {\n        \"sha256\": \"89bcee15d160e2991fb700443cadd46beac1daa13e69efb238fa6194dc3dc172\",\n        \"size\": 245451982\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34468_Weather0.tar.gz\": {\n        \"sha256\": \"ae8a072d4a7731e12c2a6859983901d01fbe82ce16060b4baa0bac454afb02d3\",\n        \"size\": 199849871\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34476_Weather9.tar.gz\": {\n        \"sha256\": \"4ae97ba18f5fc0e21e6d099c8af09d1f6ef6cd0b353276db5c69f674e805c530\",\n        \"size\": 119568107\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34477_Weather10.tar.gz\": {\n        \"sha256\": \"1aad68ddbcb676c8d9eada71de12a4273ef83dd6b238151c3307eefd3d448a23\",\n        \"size\": 199614480\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route3447_Weather23.tar.gz\": {\n        \"sha256\": \"cbb37dbb1792360b1cbf393b231a9bd4323cd3e2c64a4f8dc77f072f7edf9105\",\n        \"size\": 150894965\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34480_Weather13.tar.gz\": {\n        \"sha256\": \"2c0ecd0cef845f2d55af1f3f427a04bc22fcf5f6b8fd42d6566b5d5d3706796f\",\n        \"size\": 131601146\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34484_Weather19.tar.gz\": {\n        \"sha256\": \"cab3bdf39d7ed10f47cc8970cd0a41f5c46b2b5aecb2c8da4894c315645aa8af\",\n        \"size\": 223434264\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34485_Weather20.tar.gz\": {\n        \"sha256\": \"d4772efae87fbb3c59334648da5316a870d990292a516c590b14f49adc521837\",\n        \"size\": 195554885\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34486_Weather21.tar.gz\": {\n        \"sha256\": \"024a850c5523da1a41c9683e7327869b887dde170f88149038f3a3ff2bd43a22\",\n        \"size\": 162338856\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34491_Weather0.tar.gz\": {\n        \"sha256\": \"a58ad97552317feaf717cac53ba0edc24f495f70d8a9fd6bbebed9f72de684ea\",\n        \"size\": 330257518\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34492_Weather1.tar.gz\": {\n        \"sha256\": \"b57faba327c4bfea6f2603118d37775c6d1c984f3f2acbbe3039d2659a6129fd\",\n        \"size\": 160135684\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34495_Weather5.tar.gz\": {\n        \"sha256\": \"105b615aaf084e759fc2cfc43e94a3079e44104950d5e621e25a8eeab62ffb0d\",\n        \"size\": 189443646\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34496_Weather6.tar.gz\": {\n        \"sha256\": \"fa3b29539a8b7584002bb2921cba90c1a139341b53a4b29a0c655b9097d5bf20\",\n        \"size\": 194589910\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34497_Weather7.tar.gz\": {\n        \"sha256\": \"8d06abce2bfb3d7242e2f3e46eb70e32fc8637e9427b2ecd6ce2b7fd623b4aa7\",\n        \"size\": 176753096\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34502_Weather12.tar.gz\": {\n        \"sha256\": \"a8c6b9f48b1bef78aafda2c15c171650bdc161e39e220899b8ece29e7cb0008e\",\n        \"size\": 166193434\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34504_Weather14.tar.gz\": {\n        \"sha256\": \"c201a062180bccb584bf8bdaa6148d3a9464426edc2846c2189634f0daffba47\",\n        \"size\": 137134272\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34505_Weather15.tar.gz\": {\n        \"sha256\": \"58a7f15d3ee46b4772ae9c12a148534434bc1dc1d9f5244f8f14d968ea82c08f\",\n        \"size\": 192395491\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34506_Weather18.tar.gz\": {\n        \"sha256\": \"6d336526c73cc790d82b03bc716635ef11a0c765fc6e1d0ecb848964e87c1b0a\",\n        \"size\": 163820373\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34508_Weather20.tar.gz\": {\n        \"sha256\": \"29b787d5c0652317891b1f0b759a29c9f403d681ffbc109e73cb2b78d57953a2\",\n        \"size\": 183384480\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34511_Weather23.tar.gz\": {\n        \"sha256\": \"8f42ff07f7933a0129a496c1f70aae56d319415c79f08c2ca815d4a81f83a96d\",\n        \"size\": 167672480\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34512_Weather25.tar.gz\": {\n        \"sha256\": \"8c791ce1510c6d4c5aea5a6950e4e64fdda66f1b291dc671c6c099f1e88ac2ea\",\n        \"size\": 135649433\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34515_Weather1.tar.gz\": {\n        \"sha256\": \"acfcae36cf3a529ba6dbb91199db4a244d4795dea0a8bea3fbc9087ad2703736\",\n        \"size\": 174386852\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34517_Weather3.tar.gz\": {\n        \"sha256\": \"34a73f557eb6d97b93748e41d50a1d7a4d5cd1f0c3fb8ca18e237d8d8e69b215\",\n        \"size\": 155521639\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34520_Weather7.tar.gz\": {\n        \"sha256\": \"923925dceefd027fae4ddec7f0511d076d002c5adf3d7657732e99eb23c818c4\",\n        \"size\": 208914721\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34525_Weather12.tar.gz\": {\n        \"sha256\": \"0b4501097f7464b52ca162ca3d2024a4ba67a5b4c8e48971bd79e199a6ede54b\",\n        \"size\": 137042620\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34528_Weather15.tar.gz\": {\n        \"sha256\": \"90813dba38dbee21a2f22bf61f1866923a968cc3f64259cc55ee65e237bce3cc\",\n        \"size\": 162287638\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34530_Weather19.tar.gz\": {\n        \"sha256\": \"2125be7d8da77f9af12c3e53cd04c32a70ab0712e27cfeaeb7abb7d2ed7890d5\",\n        \"size\": 306596040\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34533_Weather22.tar.gz\": {\n        \"sha256\": \"cb9837b847339ecf99529962090a7767f0017abe14239f0a4b3a737123628e5f\",\n        \"size\": 148389183\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34538_Weather1.tar.gz\": {\n        \"sha256\": \"eca4fdb3236cedd066d407ca8df076fabcea06c42c66150bab28333c5509d32d\",\n        \"size\": 183135952\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34540_Weather3.tar.gz\": {\n        \"sha256\": \"b1d45358cbe4f6c3dc72cad89fdfb7682e5366c7a6e73b6b48d36b5d94793021\",\n        \"size\": 199446462\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34542_Weather6.tar.gz\": {\n        \"sha256\": \"bb8b85f5001d0b88d1d562233381a0f88400405979542745c88d2cb354220f52\",\n        \"size\": 160194214\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34543_Weather7.tar.gz\": {\n        \"sha256\": \"4ca33183b702d6f27d16db546ba600d5a31d40dd04a9c0a8b516e9cdc029ff55\",\n        \"size\": 327235110\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34545_Weather9.tar.gz\": {\n        \"sha256\": \"f7163d254ec344680d47baaa068086ae6a158d4b5e62fd953d63333a959902a2\",\n        \"size\": 205622252\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34547_Weather11.tar.gz\": {\n        \"sha256\": \"7460e9e8f98a2bcfd83d9e2e95e93e4d60d1b95069e50836d4e62631b1b72887\",\n        \"size\": 107055826\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34549_Weather13.tar.gz\": {\n        \"sha256\": \"277defef7693eb4b3c6893ec2a699bb571d9b615687355f6103992695290c69b\",\n        \"size\": 130164180\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34554_Weather20.tar.gz\": {\n        \"sha256\": \"bc6b4b151aa1d6bc227e0176c8939e80753502b1ebeffa7e693fe76a534508b0\",\n        \"size\": 191971368\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34558_Weather25.tar.gz\": {\n        \"sha256\": \"df8d1f3047bff4d3bbd77266444780224232563d90f395a740703261b5897c8c\",\n        \"size\": 147205570\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34562_Weather2.tar.gz\": {\n        \"sha256\": \"61f2874ec6943dd5a6746af0e32d65be8c9d9c150bc798438936a35f5c5bfa9d\",\n        \"size\": 219354525\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34563_Weather3.tar.gz\": {\n        \"sha256\": \"2fa4cdf8e56b8332efc5245a0132ccecf1704619ee98cc976dd2ff929d7a4ff2\",\n        \"size\": 162630464\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34567_Weather8.tar.gz\": {\n        \"sha256\": \"e838c0f79cfbe03b6fd53bbc5ed73cdec80799ac5a8a433877783b84d3882581\",\n        \"size\": 188476575\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34568_Weather9.tar.gz\": {\n        \"sha256\": \"816a9d3c1514484579c24e91cf89e06ccfcbc6e6d5b22a591a30fa8b2e17196c\",\n        \"size\": 128507451\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34569_Weather10.tar.gz\": {\n        \"sha256\": \"21e4ef37d8fbe65a7c33f6568b7306cccc5dec1b18782fda74264a00de2ee5e8\",\n        \"size\": 205588922\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34570_Weather11.tar.gz\": {\n        \"sha256\": \"30bd6d96ad12a48eb313dce920b7f7510dd8b144da4e9a9b41e1a72c1eaacfef\",\n        \"size\": 155338285\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34571_Weather12.tar.gz\": {\n        \"sha256\": \"a7c2f47a01f809591df7d73ad13becd174eefb4da7fc4bf1799dfebd83684341\",\n        \"size\": 271663712\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34573_Weather14.tar.gz\": {\n        \"sha256\": \"528015cb41c7641c82d726c99c5d8b249151f0c9774252e4073f0bdeb60d7bb8\",\n        \"size\": 268452029\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34574_Weather15.tar.gz\": {\n        \"sha256\": \"326cee13b60e2191da65ebfb7787123eb3b6c0df02cc7ac552fd1dce835441e2\",\n        \"size\": 152206456\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34578_Weather21.tar.gz\": {\n        \"sha256\": \"db7d0e32dfd4f7d0efffbbad9e15102baf34ca4afe13cd45fce29f3b171edad2\",\n        \"size\": 192854436\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34579_Weather22.tar.gz\": {\n        \"sha256\": \"f37369f4c78bf7587f59616705521cf2538ec189b0ea92b81e9a54c6829e5f09\",\n        \"size\": 379069404\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34582_Weather26.tar.gz\": {\n        \"sha256\": \"f104a32b5a866396ab3971476579ed7bb562c30806c373fd1ac83791436b4902\",\n        \"size\": 268745077\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34583_Weather0.tar.gz\": {\n        \"sha256\": \"83dd0149d5ae5403060aa3e2dcd551bdc046e9fc6d911a73fe47573587a97a84\",\n        \"size\": 183420966\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34584_Weather1.tar.gz\": {\n        \"sha256\": \"ff53cb0d4bcefc239411859fc5da8d00e042269f82f7a68d0f6a64d68ffd6d1b\",\n        \"size\": 189049953\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34589_Weather7.tar.gz\": {\n        \"sha256\": \"2374f71d59be698818ef1eb45a9eecbc579cd8d17babad6cd7f6758af77856cc\",\n        \"size\": 338982699\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34590_Weather8.tar.gz\": {\n        \"sha256\": \"b51389b3a0a3a9248a37f7a436d1bbceeb0b30562399e280171d8ada15174b64\",\n        \"size\": 189954635\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34591_Weather9.tar.gz\": {\n        \"sha256\": \"1df94b1958a7b2dac5d3ab75b7863ef17fd77c5d77bd7c21fbdd4226e11c11bc\",\n        \"size\": 149442146\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34596_Weather14.tar.gz\": {\n        \"sha256\": \"b667d647fdde70a22afa279c953999030be9e011fd1131576e8cb00efbc48ddc\",\n        \"size\": 164784079\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34598_Weather18.tar.gz\": {\n        \"sha256\": \"724ca31f55b9c7a0611490636222e3e47b47e7a95b472889d8f78ad6df278190\",\n        \"size\": 223292825\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34600_Weather20.tar.gz\": {\n        \"sha256\": \"30c7dd8eb6f9dc51df5bd6475694d143123e61aeba4bbd2de124bcb7866bd8ca\",\n        \"size\": 204335244\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34601_Weather21.tar.gz\": {\n        \"sha256\": \"1721e75b33acd01e3364675ac98338512fd9d0c9d8987438680bbc05e93d9ff2\",\n        \"size\": 186084306\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34602_Weather22.tar.gz\": {\n        \"sha256\": \"07b48e17f828c8f59c744d21987acab0964125f38f1e8ca2a68ea7a42478d29b\",\n        \"size\": 164434937\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34605_Weather26.tar.gz\": {\n        \"sha256\": \"6f5934ead2737e7f58b8ad6dd0baf247a9681cc90e5be068dbe2657a64b025be\",\n        \"size\": 253875122\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34607_Weather1.tar.gz\": {\n        \"sha256\": \"921fa33e063d1969dc102ad2967696da7a80f3ea59e7b0e27d06d9326f0df682\",\n        \"size\": 326346284\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34608_Weather2.tar.gz\": {\n        \"sha256\": \"e60bfcce202feae4cda870217d66c0a83a1caf3fce560bef24be059f4e556339\",\n        \"size\": 196547568\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34613_Weather8.tar.gz\": {\n        \"sha256\": \"cae25b14c45e0215ac6c6ed09e57d38217aebf0fca4b484062f08338366c7a98\",\n        \"size\": 307634179\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34614_Weather9.tar.gz\": {\n        \"sha256\": \"7b09afbb6a05b6288a72cebf28a73f2d416d1327ed41d4738e8b0e2f33639ab5\",\n        \"size\": 167290810\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34616_Weather11.tar.gz\": {\n        \"sha256\": \"df79b3ee2d39418a0aae4955d58236b00a6c3ea8aae0ead769578227aa539120\",\n        \"size\": 120769888\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34617_Weather12.tar.gz\": {\n        \"sha256\": \"07381359bfaeb9979040667f34513f12bf60363f7aeafd91538e89746eca8665\",\n        \"size\": 127407957\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34618_Weather13.tar.gz\": {\n        \"sha256\": \"0ebf9146f0a90a32c23fb44bfdc619ef174488559238c3315418e1132e701cc1\",\n        \"size\": 146832979\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34623_Weather20.tar.gz\": {\n        \"sha256\": \"81ff0dbbb85ac65b933176321125b7f6d78036cf6bbd5fc1fbf45c1423f34ed0\",\n        \"size\": 204421094\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34625_Weather22.tar.gz\": {\n        \"sha256\": \"96bb559882b3f0ae4b2e0307e5964c481b96a92066b12879abcf8d0d23744776\",\n        \"size\": 163977553\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34627_Weather25.tar.gz\": {\n        \"sha256\": \"e12aa416874a45a170c328910dfadc69458eecd88a816c082adac148ab24cd76\",\n        \"size\": 127527673\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34628_Weather26.tar.gz\": {\n        \"sha256\": \"1918fe4a2e7002ba1f26a813b76a2b591be1327e5aec56b4534bbf18a524e751\",\n        \"size\": 220331045\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34630_Weather1.tar.gz\": {\n        \"sha256\": \"95cff95c4770ee950942540e2eb842e4d54fdad5b219c6304f8ef35e32ccb1cf\",\n        \"size\": 232090320\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34634_Weather6.tar.gz\": {\n        \"sha256\": \"459fc00e53476b2afcdd354c030112a95f8895f4778d50f2b4f954559da738ae\",\n        \"size\": 187816137\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34635_Weather7.tar.gz\": {\n        \"sha256\": \"417f4d28fe918fb267423d0ed021eec7014f353a3fda19cfa167a1cf76e4c0b4\",\n        \"size\": 188260864\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34639_Weather11.tar.gz\": {\n        \"sha256\": \"ece853aeda684e5abc63d61bc3366481835ae61b3da363e628d1989fccd41c82\",\n        \"size\": 135371371\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34641_Weather13.tar.gz\": {\n        \"sha256\": \"2647c0686dbde0db8d3836066b4dd7e92872c596379e132cacd7b06bc71ac738\",\n        \"size\": 134594031\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34645_Weather19.tar.gz\": {\n        \"sha256\": \"de7f8f911d675d25f3aab0827fded46635c0e8054b2d5fa83b8f5d7c37c3a715\",\n        \"size\": 266035385\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34648_Weather22.tar.gz\": {\n        \"sha256\": \"964441242f9e9105e9ccde7f5b482e58e625d0f2a1ea2b1ed7850f12547acd6e\",\n        \"size\": 205664243\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34650_Weather25.tar.gz\": {\n        \"sha256\": \"fbc2ef5eabaac79cb2512bde252a9f18c63a419bf9a513e2604ebc7db2069524\",\n        \"size\": 286127185\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34659_Weather8.tar.gz\": {\n        \"sha256\": \"ea3134529f4373e3809c7ff1bab8786b149cd7fa161d3204a05b65f46ccd7e02\",\n        \"size\": 201868720\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34665_Weather14.tar.gz\": {\n        \"sha256\": \"abf6c950adb5bc1e12a46cac550cfd4a68d05bfbd0e46d8ed130d4360ff3f40f\",\n        \"size\": 151442208\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34667_Weather18.tar.gz\": {\n        \"sha256\": \"0c6599fff560acf00a7a57c96ae06cb17c623edfe2439347958210e96ad8e075\",\n        \"size\": 265024155\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34669_Weather20.tar.gz\": {\n        \"sha256\": \"e8e1e4b6050333c41acfeec513ea97d3d3898be5f55d8dccf6f6d411f1795ddc\",\n        \"size\": 220336095\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34670_Weather21.tar.gz\": {\n        \"sha256\": \"e8df2bf6df5f09e568480688d5da774888ef423eaa59d925e7c10c03e9fdca84\",\n        \"size\": 177926852\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34677_Weather2.tar.gz\": {\n        \"sha256\": \"b9ff46c0b838f3b2e61ca13fc26190e972cb6c7eb305081ef8a5229cf378bc39\",\n        \"size\": 189568987\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34678_Weather3.tar.gz\": {\n        \"sha256\": \"f373e7956504dc279374a0a95b0e012bf0b3b783fd8465db0ee348f4a64fef5a\",\n        \"size\": 204151912\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34683_Weather9.tar.gz\": {\n        \"sha256\": \"af7e46972ddf8d3fa5a4e49885872159e7690be6677d94d4bb6cd6f7c73d90d5\",\n        \"size\": 141204450\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34685_Weather11.tar.gz\": {\n        \"sha256\": \"8e56940431d80be6ea96d696df2174dd21dfc2add7b568c455d136ce9f24195b\",\n        \"size\": 216899004\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34687_Weather13.tar.gz\": {\n        \"sha256\": \"b82b9b97e9e096bb43b4678acb446e3abf1a03c87cbbcd918d206c90b59c6ebf\",\n        \"size\": 168808245\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34689_Weather15.tar.gz\": {\n        \"sha256\": \"c2ba3330e3e2d9c8a6a64113654947c7bfc235e925d7d621d5715e735425d6d2\",\n        \"size\": 156131182\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34690_Weather18.tar.gz\": {\n        \"sha256\": \"737786627ce8b8e73eecc946beb1df2286c3d95a40be6d1f1e0c091fe9254569\",\n        \"size\": 211087662\n    },\n    \"SignalizedJunctionLeftTurnEnterFlow_Town13_Route34693_Weather21.tar.gz\": {\n        \"sha256\": \"dd403081ea3e6c472831d1cc641a8151da140aff7c7d1cb8008c25e1e6850d82\",\n        \"size\": 298957981\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16551_Weather18.tar.gz\": {\n        \"sha256\": \"1fc2d66f3f4f84e951ae5f6a1d83af83f0a977fdebf24927c8b61e109aad1ef4\",\n        \"size\": 180621993\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16552_Weather19.tar.gz\": {\n        \"sha256\": \"185d0b565784ec00ae6174aa479ea925f702e0070cb5a4fef2a398ca106047a9\",\n        \"size\": 124094602\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16553_Weather20.tar.gz\": {\n        \"sha256\": \"870a19b85cb64a5fc8b995f1a4f79c5964d4485af447fd4f800a82b6292c82da\",\n        \"size\": 149895832\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16556_Weather23.tar.gz\": {\n        \"sha256\": \"bc2398d5a169b768c3a0fa1d14deaa2023c0d70e8d879a420f99bb0283d61d9c\",\n        \"size\": 119612890\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16562_Weather3.tar.gz\": {\n        \"sha256\": \"926c5ca1938d37f8bb178f2f5abe081a0f82525b852738edc34f20f4e7029914\",\n        \"size\": 143737390\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16563_Weather3.tar.gz\": {\n        \"sha256\": \"fa393d81199c810109e385802dcfaa88a97509be4037fcd4dcc0a518a868cf13\",\n        \"size\": 180174889\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16564_Weather5.tar.gz\": {\n        \"sha256\": \"adb43fc1e5acfbe261124421ad36cfba1e29d5fc51137f0387b0c9554ad99f33\",\n        \"size\": 250064768\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16566_Weather7.tar.gz\": {\n        \"sha256\": \"533f52068f5d4fbbe80d463606dc2a2c689db578017e5b242d16c9216cd051a6\",\n        \"size\": 71937742\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16567_Weather8.tar.gz\": {\n        \"sha256\": \"0259504042e9d6f02a0556df1dd71cfa2890a2e0dd6e765b2fce2591ec78f3a4\",\n        \"size\": 234535642\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16568_Weather9.tar.gz\": {\n        \"sha256\": \"6421ca9f6133c9002f3e40cf7fb23ad141c97e00e71223f5ba7c1d0d38dcb933\",\n        \"size\": 94750573\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16569_Weather10.tar.gz\": {\n        \"sha256\": \"47f1f697273063001ad3c59985c1c9952d61cba95d39fc5245cf1205755eed10\",\n        \"size\": 168464416\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16570_Weather11.tar.gz\": {\n        \"sha256\": \"43cd3f2362f95ec3516358526bf5db091dff0e4ad0f2e52baa3f7d6d45de82fb\",\n        \"size\": 167661584\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16572_Weather13.tar.gz\": {\n        \"sha256\": \"426c54f97f30a2643e64a62ae9d6452b0a6d84d92d53ae415459b8ac0db0d6cf\",\n        \"size\": 154378113\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16573_Weather14.tar.gz\": {\n        \"sha256\": \"130aea652345963b8246908c1f1d8ab683d1e5021e49cc84da88573907bcdb52\",\n        \"size\": 130469188\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16574_Weather15.tar.gz\": {\n        \"sha256\": \"ab4bef73c9b4c42dc97f5e6585664583de0597a169e6926019e554fa57ee34f0\",\n        \"size\": 98849096\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16575_Weather8.tar.gz\": {\n        \"sha256\": \"7b73cff579576d3583a919cd0b781c7851a1209b79513133c06bc103a97be252\",\n        \"size\": 274661086\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16576_Weather9.tar.gz\": {\n        \"sha256\": \"d1fa1468de131dd9796778582c729f8fd22995f838933a7d8604ab84cb851e5d\",\n        \"size\": 150866445\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16577_Weather18.tar.gz\": {\n        \"sha256\": \"ee2dd97d0d13d26e86c2391f58c4c3dc47e7897534c6f8c6f08555310534038f\",\n        \"size\": 99605762\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16580_Weather21.tar.gz\": {\n        \"sha256\": \"94ebfc78191cf302fa189e7ab08dbc4c64fdf05f3d5cc7cd2730f46999ff42ba\",\n        \"size\": 211577485\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16581_Weather22.tar.gz\": {\n        \"sha256\": \"a03182094c25228e63aac520274a626cdc58510944ce6769493efeaa18451ddf\",\n        \"size\": 113222366\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16582_Weather23.tar.gz\": {\n        \"sha256\": \"e071f29832a9ec6cb37ac49820563f54703751002dbcded5dfc5c0677b651c5f\",\n        \"size\": 110955692\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16583_Weather23.tar.gz\": {\n        \"sha256\": \"f149e2759f2b78c72b7a93b075b0540f02da33cafb9ee8138e0c0c53aed77148\",\n        \"size\": 125589775\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16585_Weather0.tar.gz\": {\n        \"sha256\": \"e157ea020be589e1bd04ab90e13ad658debe4740f5d80273c3dadcdeb7517fe5\",\n        \"size\": 223905312\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16586_Weather1.tar.gz\": {\n        \"sha256\": \"2a5ae772467d1f562db463de5f65ce5f3f1ab4279093131d86738ea6ac08ad80\",\n        \"size\": 220912194\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16588_Weather3.tar.gz\": {\n        \"sha256\": \"e0130d17b673f9d96c21da1e26a9030039d35b269d816f116b53f54f6c2479aa\",\n        \"size\": 77434778\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16589_Weather3.tar.gz\": {\n        \"sha256\": \"68d7b4b946fb560f16a5a1023d014f388f4ca69ed7d461c855437d123cc97fe6\",\n        \"size\": 238321261\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16590_Weather5.tar.gz\": {\n        \"sha256\": \"7dd58da3b0343132f585b2da783d19a2bf0aa2d5a42894d10b51af2e3e6e5260\",\n        \"size\": 191392879\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16591_Weather6.tar.gz\": {\n        \"sha256\": \"8c2c6934c86634ac921d589da629da96fb1ea8d2f4aacf80d108d2c8a29882e8\",\n        \"size\": 139528921\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16593_Weather8.tar.gz\": {\n        \"sha256\": \"a97ca801f9bec969aaff57834cee8a154f1b6085b4cb40c95d7e43feca4c08fd\",\n        \"size\": 189897901\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16594_Weather9.tar.gz\": {\n        \"sha256\": \"503256b68cdfc13bbb93f3fe4650db659f65a8d42ba22bc2d2d25e1f9a5371e4\",\n        \"size\": 181467032\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16595_Weather10.tar.gz\": {\n        \"sha256\": \"a959bfee41379b3bc3308206dfa014ff5438ac3daecf88889f0e12d4bcb52e2e\",\n        \"size\": 169072492\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16596_Weather11.tar.gz\": {\n        \"sha256\": \"0e937b32f8cd7ad85894416614484e138009a999e626b47d584d131ccf89571a\",\n        \"size\": 110357197\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16597_Weather12.tar.gz\": {\n        \"sha256\": \"bc44d3f6ef68ba3cae5c01cf92f59813e045d3437f22351910e5316c6fa22534\",\n        \"size\": 154763568\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16599_Weather14.tar.gz\": {\n        \"sha256\": \"0903ee3409183357f61d6d275b740a931e8357838e05a56763e03fac13bb8d0f\",\n        \"size\": 200937792\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16600_Weather15.tar.gz\": {\n        \"sha256\": \"9d96b976232aa489dc67ab9e4af4da858e375221e91ab0a3e82d425e5d94c2ab\",\n        \"size\": 172133310\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16601_Weather8.tar.gz\": {\n        \"sha256\": \"64afe924725e4cd43bba2363f08b9473e9ba718a4d84201daa7b4965bd98e931\",\n        \"size\": 212390016\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16604_Weather19.tar.gz\": {\n        \"sha256\": \"833aff4570281474960d2db3fef884274c886e0450ebda10938b6ad9d0294501\",\n        \"size\": 162420797\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16605_Weather20.tar.gz\": {\n        \"sha256\": \"1a24afd9312ab83df98139ecd491c85ab50d21984c419534ebe415cfc2d780d2\",\n        \"size\": 157720613\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16608_Weather23.tar.gz\": {\n        \"sha256\": \"6476cec6edbf23482279df0c6c0e40beafae206b37dfc432c56b10299f8a05cc\",\n        \"size\": 138437039\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16610_Weather25.tar.gz\": {\n        \"sha256\": \"71016b5cae8e7f31656390bdc944b1ae66d21898bd47cbefa802535c68830476\",\n        \"size\": 267199803\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16611_Weather0.tar.gz\": {\n        \"sha256\": \"9633fc8dc9e1795f729acebf763d0b3d8c544b83b77b8481db6ae4a297e9b8e5\",\n        \"size\": 291258520\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16614_Weather3.tar.gz\": {\n        \"sha256\": \"78b45abbd08d2bb109c886431c0e366491e7e4a4b58ee60d30cafc686ee517f0\",\n        \"size\": 191459933\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16615_Weather3.tar.gz\": {\n        \"sha256\": \"255250aff24809d656d354969a89831fffb64516396ccb6130efbc746775cb91\",\n        \"size\": 70962670\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16616_Weather5.tar.gz\": {\n        \"sha256\": \"03de389a748899038c42dd209f34006e20b0b7cd97e73eba95629679718a13a1\",\n        \"size\": 113969481\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16617_Weather6.tar.gz\": {\n        \"sha256\": \"464254120b4e9b240cce08792642a0a14cf220c08ee045f0616abe7fe82f49ea\",\n        \"size\": 182166318\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16619_Weather8.tar.gz\": {\n        \"sha256\": \"b719c5e2884372830b947726b2420b2f6a534962f5e703e302d4ca665e077358\",\n        \"size\": 148564792\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16620_Weather9.tar.gz\": {\n        \"sha256\": \"16793a2ec0bb5c77811d8574e12b9bc18e4f44c26b47699cd2f31b75ca70035e\",\n        \"size\": 108573226\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16623_Weather12.tar.gz\": {\n        \"sha256\": \"4dc1ad4e3b686f0935a41d9cab58ed9de696201d67904135fa57ca030a3fcc91\",\n        \"size\": 132329986\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16627_Weather8.tar.gz\": {\n        \"sha256\": \"b130d7ced727f657fa2de649df3b91135565664fde51dc9fbddaddb4f69baa58\",\n        \"size\": 127037402\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16631_Weather20.tar.gz\": {\n        \"sha256\": \"6afe34919b2f5e708a46bff6e32f0faa1c58f01839721c146b2c17adb78d87aa\",\n        \"size\": 133308240\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16632_Weather21.tar.gz\": {\n        \"sha256\": \"a4e40c4cfbe4d0c237ffa689278980437d0253eca824f5f8154e7bc7052376e1\",\n        \"size\": 164408587\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16634_Weather23.tar.gz\": {\n        \"sha256\": \"ea14082dfa215f6d0751fa51b41439039f951ac75ba4c25ef6e24d79d72eede6\",\n        \"size\": 227711295\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16635_Weather23.tar.gz\": {\n        \"sha256\": \"bb50826a7f372d5c659c32bd6966151c22958d37ee4f846aceafc51c3a648e93\",\n        \"size\": 288722991\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16636_Weather25.tar.gz\": {\n        \"sha256\": \"c114ca24ba25ed9424ac5e2db40c22686e2457ae723dc6367d67f8385a08d9c2\",\n        \"size\": 119071315\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16637_Weather0.tar.gz\": {\n        \"sha256\": \"37c5aea34e0c9ccdde78aaf3c9c12da5d50953c63d2236d6210d76cb6d95378d\",\n        \"size\": 282399683\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16638_Weather1.tar.gz\": {\n        \"sha256\": \"5bfa5500b6cc80a4fd2a55ed640064982b0d8983a49929e5fa146b6f08ce9b3a\",\n        \"size\": 138264509\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16639_Weather2.tar.gz\": {\n        \"sha256\": \"39f0a5f460540e5be607fa8f061611b32aaa182c045b6b98abc289e2362d5d86\",\n        \"size\": 223725483\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16640_Weather3.tar.gz\": {\n        \"sha256\": \"298f1adb783e87394ca362e1115c5cbfb7cc77437325726db39f07e67d3df168\",\n        \"size\": 192563538\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16641_Weather3.tar.gz\": {\n        \"sha256\": \"645d1d912881026bd9a193a749d530005c12d71455d25bc643d4309ded8bfe48\",\n        \"size\": 195555465\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16642_Weather5.tar.gz\": {\n        \"sha256\": \"435cc45d570384f785a3408d4fbe871513beb24ccb739ca4d45400f529c048f5\",\n        \"size\": 154231060\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16643_Weather6.tar.gz\": {\n        \"sha256\": \"63d57cef88d02dc263aa577df965ea47a5878fa4624d7cb5bc7ef95986f78158\",\n        \"size\": 79886176\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16644_Weather7.tar.gz\": {\n        \"sha256\": \"907b9c372ca011cedc98f72f5b84ef78416bd2dd8380f746fe38f71d66ec6731\",\n        \"size\": 368296651\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16645_Weather8.tar.gz\": {\n        \"sha256\": \"6c781e2bd0dcaf4be5ad46a5184ab92dc31115f325738937f1ddcffd998b3d48\",\n        \"size\": 119805066\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16646_Weather9.tar.gz\": {\n        \"sha256\": \"2867bcbfd3a30935cd49a17a4cba10b3457c3304dae9f58369a1e554f52fa41d\",\n        \"size\": 109324827\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16648_Weather11.tar.gz\": {\n        \"sha256\": \"b851cda45389eca05261d91474cb0924663fc6042ca82902fba3cbf5649ec863\",\n        \"size\": 272484934\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16649_Weather12.tar.gz\": {\n        \"sha256\": \"d6ba10d5acdb71fe7748238271e06662b922be0e13eea91d4806d607d19776ee\",\n        \"size\": 197108111\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16650_Weather13.tar.gz\": {\n        \"sha256\": \"269e2ac6d774277f76234ebc9fb9e50d7110f40f98dc8d6ca97b59395a261572\",\n        \"size\": 164518383\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16651_Weather14.tar.gz\": {\n        \"sha256\": \"bc60d4ed195a934810ad7af8a9d8a21afd1b8ba6381d350c804904ec973c4bd3\",\n        \"size\": 169502710\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16654_Weather9.tar.gz\": {\n        \"sha256\": \"189ac5bdd0c792a988eeadd7a449bd9d83cc9cd999361b91a37701d4c0c52435\",\n        \"size\": 186388951\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16655_Weather18.tar.gz\": {\n        \"sha256\": \"f38d8b87d5d22b2fd72ea06ae937f4af37c3010b3ecc91ab3d3071f0f7e83d93\",\n        \"size\": 190643031\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16657_Weather20.tar.gz\": {\n        \"sha256\": \"0037a4c63bf0d20b3b949382009dacef20f83b593e6a083308212785dcb941f5\",\n        \"size\": 195043411\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16658_Weather21.tar.gz\": {\n        \"sha256\": \"97281cd04cc2e30c802a2c80f9276da16627987d1396335c5e7cb137561a0fd1\",\n        \"size\": 193362201\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16659_Weather22.tar.gz\": {\n        \"sha256\": \"f43a06b8964ac15ee4c527b3f4d20aea3739086bfa3a54065762f3cca80625c3\",\n        \"size\": 188214875\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16660_Weather23.tar.gz\": {\n        \"sha256\": \"76a9c2f8ce266be10f58f6f4cf9fc15e0e7f17a033f7321d7645ca6ec0e60fcc\",\n        \"size\": 153938806\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16661_Weather23.tar.gz\": {\n        \"sha256\": \"26a39fb4a06e491d38683966588b5955d1a874756dd3cad610af7ca8f54a6a9a\",\n        \"size\": 204496694\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16662_Weather25.tar.gz\": {\n        \"sha256\": \"1bfe77a3dbf7679d85be4035d2af8ba2dbc765d313c08dbc03a7ad610c6affb4\",\n        \"size\": 138555468\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16663_Weather0.tar.gz\": {\n        \"sha256\": \"f0f08242c74ef3a58964f01e347c2398bd51154be0c8aca8af06ba5c3143de43\",\n        \"size\": 329077751\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16664_Weather1.tar.gz\": {\n        \"sha256\": \"f7bbb50f29bd44f1ab73a600812b55ddecc98f356f1415744999a58e69460229\",\n        \"size\": 149948326\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16665_Weather2.tar.gz\": {\n        \"sha256\": \"c74aae229636e62c11c570fb6ca06c9fdf1692ef625f069c2995b04ca29b6b69\",\n        \"size\": 167591396\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16666_Weather3.tar.gz\": {\n        \"sha256\": \"476a1ce4401f73528f356782b273dd805c92071dc072a5eb3fe6f4e849675baa\",\n        \"size\": 183861212\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16667_Weather3.tar.gz\": {\n        \"sha256\": \"8e27cf6048e883895c9c77136005c7c3654bd895855d15d64f5684d17363c419\",\n        \"size\": 157080578\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16668_Weather5.tar.gz\": {\n        \"sha256\": \"489121e7fa9398175c54ed8079c05467a9ae02f6d3c00d8f0f2f37d71ed9b7cc\",\n        \"size\": 144507262\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16669_Weather6.tar.gz\": {\n        \"sha256\": \"f8b6cb60fdfc5f43bd9b311450bcd2ef981383508dd3454ec6d7324667b02604\",\n        \"size\": 229046015\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16673_Weather10.tar.gz\": {\n        \"sha256\": \"2cca933f2fe73388a15444b426469a0d39ad79724df683e62c0fbfdee1f781b1\",\n        \"size\": 158972570\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16676_Weather13.tar.gz\": {\n        \"sha256\": \"a3e4f81045591d8b408d635432a7b72295e13b0b1cb585193014dc85b9ab6697\",\n        \"size\": 172550339\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16677_Weather14.tar.gz\": {\n        \"sha256\": \"c2a7feff25a4ff66ad8737d31f7545c45a3362e2220ae0f37487661e93fda93a\",\n        \"size\": 112195435\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16678_Weather15.tar.gz\": {\n        \"sha256\": \"f4b240b7ef6c341ae959c8e5cf575ecda35bec44e5a7b45de037f3e839352ccf\",\n        \"size\": 105262960\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16682_Weather19.tar.gz\": {\n        \"sha256\": \"6a2b91d4c9c0225d6a91170ae020c2b0f8c7997f0bc9816f22868d5a763b1a9f\",\n        \"size\": 165978515\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16683_Weather20.tar.gz\": {\n        \"sha256\": \"5c6ad8892cd190dc6e65f0c46210e381fc07efac01cb4684eb45665467f68536\",\n        \"size\": 123876778\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16684_Weather21.tar.gz\": {\n        \"sha256\": \"2da3200576bf85ee9899ffc689813c8a0eba751dc2e50623d6a646826ba74677\",\n        \"size\": 137045641\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16686_Weather23.tar.gz\": {\n        \"sha256\": \"4edd0837dc04b3e07b33df682e400f24c5dac7b0ea4eda7bf9f1e7d19f240798\",\n        \"size\": 128981053\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16687_Weather23.tar.gz\": {\n        \"sha256\": \"c55dd1fee587e0c22116b2913d210f1c9bdb8e2f967e010b4b8b8b2bc616cb87\",\n        \"size\": 175230769\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16688_Weather25.tar.gz\": {\n        \"sha256\": \"654fefaf0af7087d2dfa847abafd0482a1dee41101867421c3e98b11d8d20339\",\n        \"size\": 128179803\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16689_Weather0.tar.gz\": {\n        \"sha256\": \"b95e838ef15d64c6254d481685e5868e6563a9dc0632ad0133bd51c92d56d998\",\n        \"size\": 210652062\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16690_Weather1.tar.gz\": {\n        \"sha256\": \"e3516487de781763bace9e627da74ab3fed43a70950fff4ab6d92a60a7d052d0\",\n        \"size\": 149433039\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16691_Weather2.tar.gz\": {\n        \"sha256\": \"256c633e27cf75661c58889baafeca58d8b6b491af9fc2de2b63ada306fcf12f\",\n        \"size\": 172539956\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16692_Weather3.tar.gz\": {\n        \"sha256\": \"6552fc1302219d03d3f3ce5641ba2906ebeb545cd33006157abfa236f0652aaf\",\n        \"size\": 144311875\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16693_Weather3.tar.gz\": {\n        \"sha256\": \"f4041dd6d6014161b221d5421cbab7c4785cd10f86f2b761d4ff1e09b043986e\",\n        \"size\": 193829451\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16695_Weather6.tar.gz\": {\n        \"sha256\": \"363e0a26b07e53df121525b8f40dc620fd8ee06946f802c0ca9d83cf2d4431de\",\n        \"size\": 147399986\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16697_Weather8.tar.gz\": {\n        \"sha256\": \"f6e07a9e2823dd46170166f1aabbf6f1534543e3a5ce71c36af7b8e25da870a3\",\n        \"size\": 166452095\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16698_Weather9.tar.gz\": {\n        \"sha256\": \"376a11857d267461b8ffe6f519a388222c160a8cf26851707e3b92ff5073babf\",\n        \"size\": 161641375\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16700_Weather11.tar.gz\": {\n        \"sha256\": \"357914fd806de7321d238d0eadfeed4c0761a20fae1c5f4a364680b4d537adfd\",\n        \"size\": 146491433\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16701_Weather12.tar.gz\": {\n        \"sha256\": \"e06dc1253dc3d715fdbcd2d72d7b03c7a4fbd5b8069c0247316a45461d964e26\",\n        \"size\": 164600365\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16702_Weather13.tar.gz\": {\n        \"sha256\": \"a0c04b779a946637c07e87685f7a0a2706c5c52e226ef7f29bfc83ccc999f89d\",\n        \"size\": 162707466\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16703_Weather14.tar.gz\": {\n        \"sha256\": \"172053d3f34dc933297a35b4413fa3bb1f5ccf6fd1397ffb1ee946dad65f4ddc\",\n        \"size\": 234853847\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16704_Weather15.tar.gz\": {\n        \"sha256\": \"ca9783f2b07200229507809242db55601aaccacffc2819b69a00307053b4f227\",\n        \"size\": 198769879\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16705_Weather8.tar.gz\": {\n        \"sha256\": \"caf443a911de20af43cce19254ed76b27c46812b82a1c907d1274a48ddd0f656\",\n        \"size\": 124201139\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16707_Weather18.tar.gz\": {\n        \"sha256\": \"cb5be18467fc159852b26dbeb16983cfff69b03f58583217ef0042cfb047dac6\",\n        \"size\": 238408987\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16708_Weather19.tar.gz\": {\n        \"sha256\": \"21c5d985ca8e7f357131bab7b7a6fa7fdae25b71c443ff29429c50935e2f3e3e\",\n        \"size\": 151461603\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16709_Weather20.tar.gz\": {\n        \"sha256\": \"f5e37d050f5714182bcba2efc2b0e161d5b404799ddfe929ca1653f24b746755\",\n        \"size\": 163409736\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16710_Weather21.tar.gz\": {\n        \"sha256\": \"a15f252788ace478c199443c738ed52ba6a7d70f93ec41f33abbb5e24ed4f6ce\",\n        \"size\": 206043482\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16713_Weather23.tar.gz\": {\n        \"sha256\": \"dc77aa6ccbb15295c47a8e9337ffaa823d8db8854c65f635cc0c61d83036c621\",\n        \"size\": 173744012\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16714_Weather25.tar.gz\": {\n        \"sha256\": \"03963675f39185484a0c4e65717950cda30d8f9690972ebf6099db7de6bbcc12\",\n        \"size\": 150281200\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16715_Weather0.tar.gz\": {\n        \"sha256\": \"5710087247440e081f0d91430caf1c6ad5a84928e8aac9a38172c45ea070836e\",\n        \"size\": 171997089\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16717_Weather2.tar.gz\": {\n        \"sha256\": \"78a6fc71a2d3af8ab3d4eb11b4339b47ee82dc6c1c2c67c556d6a847651c7d77\",\n        \"size\": 121871818\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16718_Weather3.tar.gz\": {\n        \"sha256\": \"d52617925801a92a2213323a7ea882224dfada3a337dc36a0605f1242b1247a7\",\n        \"size\": 144919048\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16720_Weather5.tar.gz\": {\n        \"sha256\": \"01ccd14ffa77661877768d0e193aa3cc94f932c06b56d4a2ff4201a2cdb91987\",\n        \"size\": 107321029\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16721_Weather6.tar.gz\": {\n        \"sha256\": \"deab4e07affc7698ad95e11b06eaf222142139496732bb41ce9f323fb7b9ed3a\",\n        \"size\": 202558187\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16722_Weather7.tar.gz\": {\n        \"sha256\": \"b6c60e1754254d280c4e8a352a5d89b23124cb11518aad38d719f3785c934d11\",\n        \"size\": 248962718\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16723_Weather8.tar.gz\": {\n        \"sha256\": \"05a28dace3798171666baa1289c6178cad98a3d5bb87d5ed32b98e9ebd004f95\",\n        \"size\": 139427267\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16724_Weather9.tar.gz\": {\n        \"sha256\": \"cc92ac4f36c51cef7d674c86b8c5d64f7b7b77aa5e462b80e62fb177641535a7\",\n        \"size\": 123207940\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16725_Weather10.tar.gz\": {\n        \"sha256\": \"4ac036bf6271e287e7b22e7f195501b3a9379cb610e3d32895b5466d86a2da83\",\n        \"size\": 164902291\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16729_Weather14.tar.gz\": {\n        \"sha256\": \"67ed12c0fc93501f7b265c3b066f075ba08eae2547cabbb44a930f53ceab7009\",\n        \"size\": 130244996\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16730_Weather15.tar.gz\": {\n        \"sha256\": \"d76734443a5d5db6eef77ff556cf4b9bbf456db097181874dcd47306ceebaa17\",\n        \"size\": 227889936\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16731_Weather8.tar.gz\": {\n        \"sha256\": \"8e20683019e4faa49987ba6186017bc6bc834b48616011bf668d207887942ed9\",\n        \"size\": 233887310\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16732_Weather9.tar.gz\": {\n        \"sha256\": \"cd367d45a91ad66b979cca14b98ed4f04c2c84accfbfaad57250e58b8594ae70\",\n        \"size\": 95843211\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16733_Weather18.tar.gz\": {\n        \"sha256\": \"4097ba94e0374c7f24512b05bd8b36ab2f16df390843b3e1fae8ae85c0dd9fd1\",\n        \"size\": 202179110\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16736_Weather21.tar.gz\": {\n        \"sha256\": \"e97584ba1b2ae7b664d47b352908ab956837df443577f31d6ebcfa95551d28a7\",\n        \"size\": 147102933\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16740_Weather25.tar.gz\": {\n        \"sha256\": \"ba06736645cd5079f313a3a0cbcd49d4f89b6bbb0a80aad52a3d557d6413c3b9\",\n        \"size\": 549953980\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16742_Weather1.tar.gz\": {\n        \"sha256\": \"6960d80fd1ca223e1ed9981c064dd59ea8ac8f9acb934dc97d84e45811ed2c6c\",\n        \"size\": 265844881\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16743_Weather2.tar.gz\": {\n        \"sha256\": \"924f1d18524c60913b43f2cfb967fda1bcb4e84aae55f235bf6fe2d08b9e48e4\",\n        \"size\": 141555598\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16745_Weather3.tar.gz\": {\n        \"sha256\": \"275c875a67189902d9d88516eab1267a5331cbd045e7ceff86d26bc6b9783c30\",\n        \"size\": 124173086\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16746_Weather5.tar.gz\": {\n        \"sha256\": \"d78120d1c6e881b2357d32bd8a0f0fdf4551d9bf832096e2d2b7b6da85a5763a\",\n        \"size\": 199818494\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16748_Weather7.tar.gz\": {\n        \"sha256\": \"43454bd112057e5586a30efd9cb4f483981a9c96df1e667bd3e10a92de3ea644\",\n        \"size\": 157809431\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16749_Weather8.tar.gz\": {\n        \"sha256\": \"30c9982fb56faf0588ff2f11123325d026421e17e77a23301e8dfb510e9b40b8\",\n        \"size\": 140585327\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16750_Weather9.tar.gz\": {\n        \"sha256\": \"8db40ab956e2072f34652c850af5c93d9bac443f6b06f5c3602f6f71c2b1a1cc\",\n        \"size\": 62079331\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16751_Weather10.tar.gz\": {\n        \"sha256\": \"936bb602edee996b8335a805ded9cddced7bf9e86a4081fbb49045b3db18f412\",\n        \"size\": 151678539\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16752_Weather11.tar.gz\": {\n        \"sha256\": \"da1dc034a7aabddb7b8e0398a7f0d3475f4b62b2b489ad3a414130e7832796bf\",\n        \"size\": 171632701\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16753_Weather12.tar.gz\": {\n        \"sha256\": \"a69c1e009e8350ffe752d551157843c3b39c833e15d55c63e8062e44b7d65a6d\",\n        \"size\": 233194251\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16755_Weather14.tar.gz\": {\n        \"sha256\": \"f7b5d9e37cf6a169446a8e8e20f9c6015098c17c66454f3695c4e90eeeea1ce9\",\n        \"size\": 242879190\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16757_Weather8.tar.gz\": {\n        \"sha256\": \"2ff623be8e5a275adff7db0a2a67ae14c4aa50e82b2d6e6e7c6d19bf1554d9d8\",\n        \"size\": 115204478\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16761_Weather20.tar.gz\": {\n        \"sha256\": \"63b37802a250ca01dc7771bc57e3b7a9d92976acf641ac7d84adf6e8c368ccb9\",\n        \"size\": 182108944\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16762_Weather21.tar.gz\": {\n        \"sha256\": \"f101dceb414d719db57381384f1e509704edb24d3fed472a56573edb841f34c0\",\n        \"size\": 172827754\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16764_Weather23.tar.gz\": {\n        \"sha256\": \"b049239711e43d587e65cedbe65e2aa0917e91c9eff27ff8e6d0dc77fe597b5c\",\n        \"size\": 126077025\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16765_Weather23.tar.gz\": {\n        \"sha256\": \"b5895a9ba0eff28644cb7f3e74a2e37f29ca866e217039087fef6a71e4f9280e\",\n        \"size\": 154394193\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16766_Weather25.tar.gz\": {\n        \"sha256\": \"2dc95f3fad1c1c45bffcf15cb03dffc75e1c4c9e4e26b0fb4ea10f3196396241\",\n        \"size\": 103899661\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16768_Weather1.tar.gz\": {\n        \"sha256\": \"d41bf338442450d630786a14ce13b3cb9f2a442c196b30a88ff2bbd7e0dfccce\",\n        \"size\": 129790653\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16769_Weather2.tar.gz\": {\n        \"sha256\": \"9317c5e315f969a7fdecf72fbf837c11af821629fa06606d1356eed60a6ddc71\",\n        \"size\": 247908021\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16770_Weather3.tar.gz\": {\n        \"sha256\": \"06ccb0a2d4b34743cb6333801752e8f470de6fc688dd335745f614e7ac963209\",\n        \"size\": 231243865\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16771_Weather3.tar.gz\": {\n        \"sha256\": \"94d103e9030015ea74dadfd00dacdb05235d94cd49ed26f5af6ecb00eaa3fb6c\",\n        \"size\": 289356454\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16775_Weather8.tar.gz\": {\n        \"sha256\": \"df3937449ee3b6a892865f68b1c866e17fa624a399f52bb231e9aba9ec23232d\",\n        \"size\": 106773977\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16779_Weather12.tar.gz\": {\n        \"sha256\": \"3a28378db76404251d5d2b391cdc28b869b34a20d16004edb4c671cda848976e\",\n        \"size\": 122778492\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16781_Weather14.tar.gz\": {\n        \"sha256\": \"9771b643d40a2f0ccfc698886dcee3a66931b4752c9e51b3c021588ce1e0dc65\",\n        \"size\": 188263785\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16782_Weather15.tar.gz\": {\n        \"sha256\": \"ffb36158e2d0cd30f09e75f4abf921e11a81b128d96a265ef959f041946a90d9\",\n        \"size\": 177931459\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16783_Weather8.tar.gz\": {\n        \"sha256\": \"b58231afb55c696deaed79167ffed4a49d1a4c811ea351c3613ceb862272f1cb\",\n        \"size\": 154992147\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16786_Weather19.tar.gz\": {\n        \"sha256\": \"e318a02b7f4df66dddc03fdf88a333cfd0318e3f613c37e8c9d38e247834f255\",\n        \"size\": 196389390\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16788_Weather21.tar.gz\": {\n        \"sha256\": \"56313a918b01ae82e975d2c0287e3d2dc902191db18640db007b224cc7009979\",\n        \"size\": 95819143\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16789_Weather22.tar.gz\": {\n        \"sha256\": \"ca2e4bdace0615f0525ef599ded4d7091290ab9e23d047779d1901c7356a9170\",\n        \"size\": 166325695\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16790_Weather23.tar.gz\": {\n        \"sha256\": \"297c78bdaa620feb8bafbf50d5acccdc61c793187212356a36db428ad21987df\",\n        \"size\": 224497683\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16791_Weather23.tar.gz\": {\n        \"sha256\": \"61790d8d41bb58c52de72e703cdc0fd50ecab82cf7531e9e233465b1a069fe22\",\n        \"size\": 195610330\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16792_Weather25.tar.gz\": {\n        \"sha256\": \"69c7c4cb16ce45f0d01255f43f139c90ec82c17e1649da7b93b349928695ad36\",\n        \"size\": 134676089\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16793_Weather0.tar.gz\": {\n        \"sha256\": \"ee2c7a94e3b723ca533b18c8d70ba8c62d087fe4cd41c15cf3b01bdb321c3070\",\n        \"size\": 118229325\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16794_Weather1.tar.gz\": {\n        \"sha256\": \"4de8cfff66bede1a8459a8ca109bf4245ba5be235d9682100fcb7b9126dbda28\",\n        \"size\": 219743970\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16797_Weather3.tar.gz\": {\n        \"sha256\": \"571b90d1af10b1e06866c3171e6de688116189828fd5ded4fba7a9f3fd322850\",\n        \"size\": 165535521\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16799_Weather6.tar.gz\": {\n        \"sha256\": \"79d14a8fe1e01f26cccd1a8130e6647893683efdecab24011d06f27495a1f746\",\n        \"size\": 180234856\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16800_Weather7.tar.gz\": {\n        \"sha256\": \"a7702a49a9358418a0bc71616091dfc7c59d055ef17392e2d93fb1ad0f546683\",\n        \"size\": 423584015\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16801_Weather8.tar.gz\": {\n        \"sha256\": \"ab8f4230ada849509eee9edc00b7ee538cd008f58cfaffe4a87d6e05182faf2f\",\n        \"size\": 201454033\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16802_Weather9.tar.gz\": {\n        \"sha256\": \"d57074177913fec750914573b151a855c1dcd4687cc94acdac269293005d3c0a\",\n        \"size\": 101692867\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16803_Weather10.tar.gz\": {\n        \"sha256\": \"208802f103e3ad95792a8b0dd1352a43914326cc468cc5f7717346e144c42b5a\",\n        \"size\": 140066200\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16805_Weather12.tar.gz\": {\n        \"sha256\": \"14e8bf29772f93d75b7ad6df03548dd4060082565e67205348bf0ea37b321dc1\",\n        \"size\": 148092567\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16806_Weather13.tar.gz\": {\n        \"sha256\": \"26a6c7726d247224a26df1e0c66db7698e886cfc03d67bb122d7176742ee5843\",\n        \"size\": 90981450\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16809_Weather8.tar.gz\": {\n        \"sha256\": \"7a8ffff1907b4c784da0094fa225aeda41e48f3e4f43140cb98b4fda37cd1b16\",\n        \"size\": 121595307\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16811_Weather18.tar.gz\": {\n        \"sha256\": \"25c5dfe912d4d20239f0a80260bd8acaadc8ecf553fe063018e3bb22a5d8e456\",\n        \"size\": 147595799\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16813_Weather20.tar.gz\": {\n        \"sha256\": \"21fe49563dc6591123d503c2990c4b9685a0b9adee599adb4f80f6872c068918\",\n        \"size\": 186182826\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16814_Weather21.tar.gz\": {\n        \"sha256\": \"9c052ce83694b114994620cc04c3a0f9b8445bd1bc35a3fb694e1c2281082035\",\n        \"size\": 142834053\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16817_Weather23.tar.gz\": {\n        \"sha256\": \"eefda98da84a42a33d19be33184b888ef41d78c9f543a7f975df03f2d86a7181\",\n        \"size\": 215824717\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16818_Weather25.tar.gz\": {\n        \"sha256\": \"b26611d5a03ce4dd430a7cb6021ec722642ec413e4d00bf46e83bebd5c236a17\",\n        \"size\": 173402927\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16819_Weather0.tar.gz\": {\n        \"sha256\": \"b952903966474e64553c03a6ed1517b85d7fecfad0e586c2be4d0a9dfbf0b2ba\",\n        \"size\": 163244596\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16821_Weather2.tar.gz\": {\n        \"sha256\": \"45381feb0e0be5d1276cb5f959074465a160d29215dc35476c2ba85b7bd6a8e4\",\n        \"size\": 157880807\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16822_Weather3.tar.gz\": {\n        \"sha256\": \"b5211ccb30820d4db5f147479544904093132911ccc0d371b8a57481beff7627\",\n        \"size\": 214696411\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16824_Weather5.tar.gz\": {\n        \"sha256\": \"c6271ec22b9ba1a797a358d4737ac8b3313ec564e4b0f62a045e970100c88348\",\n        \"size\": 163026080\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16825_Weather6.tar.gz\": {\n        \"sha256\": \"a2ef1d31a839bddd807d693ca9adf77237dfbbe0075ad072e5dec8f8708082fa\",\n        \"size\": 270219335\n    },\n    \"VanillaNonSignalizedTurnEncounterStopsign_Town12_Route16826_Weather7.tar.gz\": {\n        \"sha256\": \"529af297e480eb7258ce60e0223646b43f79acd3e21a04078cd8658d85ff7657\",\n        \"size\": 172019043\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16461_Weather6.tar.gz\": {\n        \"sha256\": \"2006a0ca567e43c033eb1d6d17e67bd93cf55b5e68ccacfb9aa54f0deb325780\",\n        \"size\": 120219384\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16462_Weather7.tar.gz\": {\n        \"sha256\": \"668b7aa46748c3b15bce940d30be154edc239671295c6e7cf348576776190c4e\",\n        \"size\": 113006664\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16463_Weather8.tar.gz\": {\n        \"sha256\": \"2653d158d92b6fd9b5548bbc07dc8417051fca6549b038cc94cda8e4599ab260\",\n        \"size\": 692629012\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16464_Weather9.tar.gz\": {\n        \"sha256\": \"bb4f3d1096a865c1224e3ed4d627b2ce8a3c1c65470745e6929852779ae4f104\",\n        \"size\": 108137287\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16465_Weather10.tar.gz\": {\n        \"sha256\": \"fb1a3158651a4982dbba331de047fca0ebe74c1631969c445c5c3aa1f4b1a266\",\n        \"size\": 391373666\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16466_Weather11.tar.gz\": {\n        \"sha256\": \"5513309d181d157502669eb0208c192cdc4c93f1c705540d212060ab93916d67\",\n        \"size\": 469523921\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16467_Weather12.tar.gz\": {\n        \"sha256\": \"5f03fa7d4496e5ec436285cace6052e0483dcd2e923b54cf98cd88d51ff2fa4e\",\n        \"size\": 152217488\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16468_Weather13.tar.gz\": {\n        \"sha256\": \"171e67492c07f519643d824aea43047f3c08d95e5f1e81b389d9228b175ffa61\",\n        \"size\": 116863388\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16469_Weather14.tar.gz\": {\n        \"sha256\": \"fae75f0d987095c5d8dab93b59f200b1065a511d4658c51088cb8ebd1a169781\",\n        \"size\": 320165379\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16470_Weather15.tar.gz\": {\n        \"sha256\": \"299678e0bb92064fbdc2a56bf05e2ac52e7bd2723ad6a244ff9eeb1226c0027b\",\n        \"size\": 539481310\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16471_Weather8.tar.gz\": {\n        \"sha256\": \"e9626cfa61322f0addd0eb99f7b5dcd9d5ae08092a7f017806f5e734e1b9e521\",\n        \"size\": 585413865\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16472_Weather9.tar.gz\": {\n        \"sha256\": \"076b2f38db30a1af66e7119cc472b354db00c13d9cdd04c7fa17cf4ac8b9548b\",\n        \"size\": 287201263\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16474_Weather19.tar.gz\": {\n        \"sha256\": \"25f63a1494881a34abd81efdb6b99fd6be1dc59211bf5eed9b6a2f9c2b994d95\",\n        \"size\": 144219417\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16475_Weather20.tar.gz\": {\n        \"sha256\": \"cef63d99d65ab4bde2309fd369043f821ebb8053f14dc0a149aa9e8a0d3090fc\",\n        \"size\": 183398527\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16476_Weather21.tar.gz\": {\n        \"sha256\": \"c27aeae113fc26922159ca37d26a15f7a7681011536d561056fc7cf0b078eb39\",\n        \"size\": 182246909\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16477_Weather22.tar.gz\": {\n        \"sha256\": \"73126fe873feb25bec27ea0056fddeb866194d2ccde4a2bb34de33e595e634a2\",\n        \"size\": 291028260\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16478_Weather23.tar.gz\": {\n        \"sha256\": \"44be79ed6c1b5b78fb43655ee9fdf882ad4bfe1d48f36ac599c5163a66844602\",\n        \"size\": 631621707\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16479_Weather23.tar.gz\": {\n        \"sha256\": \"94842ec2c42829bbf3d2131e375523e9addfee5fb7d3b078075c5d3d74edb368\",\n        \"size\": 493929903\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16480_Weather25.tar.gz\": {\n        \"sha256\": \"b45e200a7fbd452c4d7575d36b9ac9d9bb85a344e202c90cc77400939df373bd\",\n        \"size\": 231735947\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16481_Weather0.tar.gz\": {\n        \"sha256\": \"deb7ff5573862acdbe07e1e252d878dcc9da2246a28946c1030ee32570179996\",\n        \"size\": 185369446\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16486_Weather5.tar.gz\": {\n        \"sha256\": \"fa5f9df5b76db9e8756a550abed0ed706403b467eaa704041a631cd39c7d713a\",\n        \"size\": 296886423\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16488_Weather7.tar.gz\": {\n        \"sha256\": \"c54c60163957d90d81c5b1b28f1832771fabd2e6f46b961c469d19979187c118\",\n        \"size\": 86186142\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16489_Weather8.tar.gz\": {\n        \"sha256\": \"72e4534641bc60fb1c1d633e88d9fdb2569c44f2f3dc9cf4377037b90d9f7fb7\",\n        \"size\": 298178927\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16491_Weather10.tar.gz\": {\n        \"sha256\": \"d2af1d53d900429890d8e11c4718aa034387e50970a30888b910ad45dc6112c9\",\n        \"size\": 125128875\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16492_Weather11.tar.gz\": {\n        \"sha256\": \"78f9cf79d63473b742f3f40435828aa55fde070776208f96be666a5bb337fe32\",\n        \"size\": 231324453\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16493_Weather12.tar.gz\": {\n        \"sha256\": \"479d1096cd6ed3fc76e7d1db2844f0f93293cd5ef7d9b15da710194b4584c88a\",\n        \"size\": 90619150\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16494_Weather13.tar.gz\": {\n        \"sha256\": \"aff9ed371ac30e69cd17a19ae81a7ac479123411dc068b32ecce509e8dba8e09\",\n        \"size\": 511840352\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16495_Weather14.tar.gz\": {\n        \"sha256\": \"d1772f39ff7d886d5528d4af0260f99591db4bcdb5783ed9d085a8769033bdf1\",\n        \"size\": 690128827\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16496_Weather15.tar.gz\": {\n        \"sha256\": \"710b39bcca9ebbd2a9adec0147ca126b0978b6a2d8aa696924235c397ff21b3a\",\n        \"size\": 103979381\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16498_Weather9.tar.gz\": {\n        \"sha256\": \"3cb8915fa8795e8eb3ba424a2a4e13f60c6d186cd7c333d61d363f1665edfbe9\",\n        \"size\": 992518714\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16500_Weather19.tar.gz\": {\n        \"sha256\": \"44bffb5546694fec2f5091b5a9c51e445eae8271ec1370be62d064018de7c4c8\",\n        \"size\": 601840196\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16501_Weather20.tar.gz\": {\n        \"sha256\": \"a8cf37ddde3da5cca8665343c6bbc74bcf587880c5b97f4159551efeb21037d3\",\n        \"size\": 314176782\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16503_Weather22.tar.gz\": {\n        \"sha256\": \"d6aeb20ee32483133f91d61da9944768a171f440b90db164099afd2a4078527f\",\n        \"size\": 188744849\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16504_Weather23.tar.gz\": {\n        \"sha256\": \"096fcf931170366f677c224d0ee5dc1dc9517b28322362204bfb081851ee5ef3\",\n        \"size\": 553813997\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16505_Weather23.tar.gz\": {\n        \"sha256\": \"26515ef4a62b8cc445a48b6cf16756d2ab3e1291c139caa249445617673de42f\",\n        \"size\": 267215299\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16506_Weather25.tar.gz\": {\n        \"sha256\": \"36ec9b736713fb1883207c5cf0b482144a32a0d99e7df0808e57e7845b127618\",\n        \"size\": 91947044\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16509_Weather2.tar.gz\": {\n        \"sha256\": \"a99e8754fc058367a763cf81edf4d548a8774c41e1149dc8e1373b622d48e446\",\n        \"size\": 303759886\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16510_Weather3.tar.gz\": {\n        \"sha256\": \"4570e02003516e80c0c7d8e7697b37f0c4914d9d6909583336d97a92be2e3a3a\",\n        \"size\": 223691687\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16511_Weather3.tar.gz\": {\n        \"sha256\": \"20939d6f80e80f0a1cbf08b1ee605bf43ba8332b37fcf48826e5ae817cc0d04f\",\n        \"size\": 217701033\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16512_Weather5.tar.gz\": {\n        \"sha256\": \"86d29044f1c3d5ae62c48f937a650a679190229fe77d8a18651c707c3ec292fb\",\n        \"size\": 305971798\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16513_Weather6.tar.gz\": {\n        \"sha256\": \"00217c01f523faa956d5282878e07bf7cb11e8cdf68a1b424f60506e517b0fb5\",\n        \"size\": 718123363\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16514_Weather7.tar.gz\": {\n        \"sha256\": \"f782b84a3e0c7d89a2752013a3bbd34050accf6c8365f5cd1444f0ff304f1ed3\",\n        \"size\": 142901581\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16515_Weather8.tar.gz\": {\n        \"sha256\": \"84c7875cd865a799fcb8b8a58b0b9862290dc28bba7b9ee32c07398dcfc267a2\",\n        \"size\": 107451014\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16516_Weather9.tar.gz\": {\n        \"sha256\": \"caaed4acfac60db04529c8b8bb10a26b6e5553cfe2defb932c8eb6c7f8ee8364\",\n        \"size\": 892299096\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16517_Weather10.tar.gz\": {\n        \"sha256\": \"56d8d5cca7b19c7c947157eb52b37b7c90a59ba9866063297ca09774e834040e\",\n        \"size\": 149253679\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16518_Weather11.tar.gz\": {\n        \"sha256\": \"f26dd4f7671f77cfb61daa6bac2d278000069965d68b1a4461348b1e8a22ad40\",\n        \"size\": 63267061\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16519_Weather12.tar.gz\": {\n        \"sha256\": \"96ada0f1d68e7fca074d3721fb83b619184c3670377aa93f58a01efb9190bdc4\",\n        \"size\": 200776411\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16520_Weather13.tar.gz\": {\n        \"sha256\": \"37fee18e70b55fb2cfa9477b7d633a8d73a68af93febb98050ebe7db8df76f84\",\n        \"size\": 82875807\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16522_Weather15.tar.gz\": {\n        \"sha256\": \"2032dd30f56ba480c5cc50f980abf0b87cafd2995f4d2117b50346b57104bfcb\",\n        \"size\": 650878655\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16523_Weather8.tar.gz\": {\n        \"sha256\": \"de7676f541047e4262d5dff4b547378d3d2b75c140dc9c24f31d90fd5036dfc9\",\n        \"size\": 242202734\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16524_Weather9.tar.gz\": {\n        \"sha256\": \"a3257ea119f4adab2c2af4c8d8d0a8006bf18825bed1696129e1d6fa93338bb7\",\n        \"size\": 230867975\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16526_Weather19.tar.gz\": {\n        \"sha256\": \"9fbdd638a14fd339d84c60816b8ca4c64f46c2dce253182ea371bb973e88f5e9\",\n        \"size\": 550956461\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16527_Weather20.tar.gz\": {\n        \"sha256\": \"d35a56b23d472bed780bdaf850a358e71cd7fd4c784a43ad29ba9a997dc7c327\",\n        \"size\": 100686143\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16528_Weather21.tar.gz\": {\n        \"sha256\": \"bed954616840b017ca8f387d1565efa6246942564e52a7630b7a44b39a1b4a44\",\n        \"size\": 85640054\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16529_Weather22.tar.gz\": {\n        \"sha256\": \"7c349857cb1cd98f2e0d1efc0e565582b9110068425223fee438961bd58457c8\",\n        \"size\": 285143093\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16532_Weather25.tar.gz\": {\n        \"sha256\": \"605472a101dcc8cc5b40afce472a138f1eed91d538324311e501f6dcdb2198dd\",\n        \"size\": 94819928\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16533_Weather0.tar.gz\": {\n        \"sha256\": \"3e806dc75b61341a5301e765232e4bb9ec46f25e9d5b36f95552c44a1dd48de1\",\n        \"size\": 127836182\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16534_Weather1.tar.gz\": {\n        \"sha256\": \"1aeb6674ae23076f71af496c85323b2a1e187ae42e6a58ae801aa49b1249d5a5\",\n        \"size\": 289965910\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16535_Weather2.tar.gz\": {\n        \"sha256\": \"b3e054796440605cd3b954a84f24aec53a015b323fc16c2c94872953bc6de146\",\n        \"size\": 88337030\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16536_Weather3.tar.gz\": {\n        \"sha256\": \"19d2514d5bdac387cef2516c81d11236b3712e8fcc09152a8c5f2863f628139a\",\n        \"size\": 705622872\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16537_Weather3.tar.gz\": {\n        \"sha256\": \"5bed374776513c3e74e5efacbacf13a4a593fca6574cb2c1af72f2d44c7573b5\",\n        \"size\": 267031592\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16538_Weather5.tar.gz\": {\n        \"sha256\": \"8b0a1d245aa4ffc6eca0aedc92b5c33a186ca13bab0bcf056ebbfdcced91672a\",\n        \"size\": 95626861\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16539_Weather6.tar.gz\": {\n        \"sha256\": \"42fc284012434e7360b26d037bce7d0563255596d9c311368cdd004a4b312c5f\",\n        \"size\": 748382642\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16540_Weather7.tar.gz\": {\n        \"sha256\": \"4da3ac3037fae87f164ce7ff0e8f7faeb7e4a143a4658cd5ea4471ab816d135c\",\n        \"size\": 404948351\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16541_Weather8.tar.gz\": {\n        \"sha256\": \"2ec7616c06f797984e90f4633357ffa9c90bdcbc0de74adaac5cd6bd1703a0a2\",\n        \"size\": 363868796\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16542_Weather9.tar.gz\": {\n        \"sha256\": \"52583c22fed2cd45f16b95b0866d4bc8a4eab6c79473381001d9cea5306c6aeb\",\n        \"size\": 230353885\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16543_Weather10.tar.gz\": {\n        \"sha256\": \"1cf6d217df164c6cbd0b88619c252cbc23d4f4fd9d4309f0abf69a6b62cd7833\",\n        \"size\": 610211140\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16544_Weather11.tar.gz\": {\n        \"sha256\": \"c8175179be87c19389023875bd7eadf67e20e914eb2871dcbe9f7aab007ef5b6\",\n        \"size\": 227627314\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16545_Weather12.tar.gz\": {\n        \"sha256\": \"5952c4c4487346c35b28256f3154cf0199ac0bb221fa129fd49a2532ca8ed50b\",\n        \"size\": 617782172\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16546_Weather13.tar.gz\": {\n        \"sha256\": \"7e8561d6cfd8ab68e34b5787532af5d6047d3a6da5b0be5aecf66effe6707fd2\",\n        \"size\": 577778931\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16547_Weather14.tar.gz\": {\n        \"sha256\": \"050d4652fb26816f5ce2784e13c2b9cfde8c23398515c8d969bdd85ec2cca14d\",\n        \"size\": 84616811\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16548_Weather15.tar.gz\": {\n        \"sha256\": \"6708d6b0e45e44435d45ca5589b29ca383e0992ab962eb42e7423f33047d3c4a\",\n        \"size\": 72193506\n    },\n    \"VanillaNonSignalizedTurn_Town12_Route16550_Weather9.tar.gz\": {\n        \"sha256\": \"c4d500fbda99e3e6d6f436bb5ff24006109de9fb9df5ec9eedb99e06a35bfe9d\",\n        \"size\": 451392410\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15257_Weather23.tar.gz\": {\n        \"sha256\": \"e3471daf1519d7242634c3d27e2114ba839b0e172b88f9bb312282a06b1ac9d0\",\n        \"size\": 94155256\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15298_Weather13.tar.gz\": {\n        \"sha256\": \"77a752c8c7b1309070852eda4726f6c5a0d19a35f7ac407504ed607b5fd9805e\",\n        \"size\": 122105862\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15340_Weather3.tar.gz\": {\n        \"sha256\": \"77e711ab7246778194ac089839aaeeaede7997a91a24ef10ece2917367e22b35\",\n        \"size\": 252393199\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15379_Weather8.tar.gz\": {\n        \"sha256\": \"652005d2b206e1129185d2e046e7893fda011dec370d9c336e90b58e17b9e8ae\",\n        \"size\": 88008797\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15416_Weather1.tar.gz\": {\n        \"sha256\": \"86a4f5d06533be12bbe52399f651a3e84b8a8b09c45ae5e7c8b76056d6cb354e\",\n        \"size\": 239311308\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15453_Weather12.tar.gz\": {\n        \"sha256\": \"6604626b62690b26c231d383dbcbc4829378eb6d17eaaba15f73fb691c12fa00\",\n        \"size\": 221791333\n    },\n    \"VanillaSignalizedTurnEncounterGreenLight_Town12_Route15454_Weather13.tar.gz\": {\n        \"sha256\": \"f5fcf0ab2e8b802339911589450117a407dd710fdc192eff785e3582ba7e3999\",\n        \"size\": 214423680\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15488_Weather21.tar.gz\": {\n        \"sha256\": \"065b1171e132aaa9459a85fe5e0ddb027e3e01b4fa56fe3bc8355d99bf351d40\",\n        \"size\": 175873314\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15489_Weather22.tar.gz\": {\n        \"sha256\": \"035f8532f303a42ecc0a11cdf626686d68489b9cfa8f2fa2639787c5cb209ad2\",\n        \"size\": 265634481\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15520_Weather1.tar.gz\": {\n        \"sha256\": \"fefba3b1d001d6b7b8cd70c690f9c3400ab2f2710128ba7f10b866a089f5a30a\",\n        \"size\": 310570322\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15521_Weather2.tar.gz\": {\n        \"sha256\": \"ba970210b31eda1fe3fa470c26de19079f5ce47e3560cc07560503850068d38b\",\n        \"size\": 752212007\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15594_Weather23.tar.gz\": {\n        \"sha256\": \"525532641eb7cc7010a209e404f21cfaea6ff8d0a744b907b1a54b8674cabbe3\",\n        \"size\": 256331502\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15607_Weather10.tar.gz\": {\n        \"sha256\": \"3ed70ed11c0111e29c9c7a67f93c2a4ede78801e49cbf1830ebe52c744bc356c\",\n        \"size\": 798624885\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15608_Weather11.tar.gz\": {\n        \"sha256\": \"f175a6597cdd48cff074e2afd0e058b0eb0c3a1f650456eab8edaf7db5d6cc44\",\n        \"size\": 402786593\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15609_Weather12.tar.gz\": {\n        \"sha256\": \"fae853a7eb3fc551c22376a5de1f57cec366d484b2d794ae6d0dcb6cecc9c088\",\n        \"size\": 267321157\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15610_Weather13.tar.gz\": {\n        \"sha256\": \"09044d0c386ede89b0dd9ab0943685bb6528b89beb1f9d076a3c6715a6035e50\",\n        \"size\": 297688325\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15615_Weather18.tar.gz\": {\n        \"sha256\": \"10158317c26ba7c4076bf7d57fc1703448b83d6223d65b03dd6fd48c875cfea7\",\n        \"size\": 304164751\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15616_Weather19.tar.gz\": {\n        \"sha256\": \"98b6aef58ab24667945c47e2c0458e8ad9eaa30ecd54cb56bc919ad4de5ed2c1\",\n        \"size\": 542706396\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15617_Weather20.tar.gz\": {\n        \"sha256\": \"f1f4d8b29a41e6ca395020f687d242b0599ca234632dcc41e73887654b661b9c\",\n        \"size\": 949856888\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15618_Weather21.tar.gz\": {\n        \"sha256\": \"bd96a350d9e42e7c3305e310f405448fa0e0e93cf320f1b791e77e0079ad61c6\",\n        \"size\": 671166665\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15619_Weather22.tar.gz\": {\n        \"sha256\": \"f3f4b08c5155a0cf3b53452fb4a07a6102ea517ddbb520199afbe8fb312be893\",\n        \"size\": 148962420\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15620_Weather23.tar.gz\": {\n        \"sha256\": \"fb480fc859109eea2a36da682a06f8476b2045418e194aa47b14ab16dc012a68\",\n        \"size\": 118999147\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15621_Weather23.tar.gz\": {\n        \"sha256\": \"4c086bb5001bec701ed51c79030dd3f8bc820dc20a235008b8b7284879785fe6\",\n        \"size\": 643717266\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15623_Weather0.tar.gz\": {\n        \"sha256\": \"0e0ebbe90f9f6d18df027dff99842ef699219cfc0df75823f5d71e8c7a03c85d\",\n        \"size\": 354222594\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15624_Weather1.tar.gz\": {\n        \"sha256\": \"29f0385b32a19aa684e60327d9b283cef43e2a625c5771afcee21265fa400859\",\n        \"size\": 190780421\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15625_Weather2.tar.gz\": {\n        \"sha256\": \"3ce02447dabba97e2312c8dd590f3fa9d7380fed0e00d517a3058762e1786303\",\n        \"size\": 345339221\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15626_Weather3.tar.gz\": {\n        \"sha256\": \"14698e2af748d0521b25e5196a8a13c1921922a68bb85794e876c9ae54574f26\",\n        \"size\": 618127580\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15627_Weather3.tar.gz\": {\n        \"sha256\": \"f50bcb59dde8348ad8b6f9ebef56ac99c211e2641331a3bb92e8a701f6e95932\",\n        \"size\": 463400732\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15628_Weather5.tar.gz\": {\n        \"sha256\": \"83e6444a5f367b5a2ea81add932ce95fbd898a0751d94ecc4ff934add31ace62\",\n        \"size\": 102733567\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15630_Weather7.tar.gz\": {\n        \"sha256\": \"3324c713b6e78e9d7162c9e6483d1b0dd3ba6a9700e226014bb8056b7f0fcbd2\",\n        \"size\": 230794936\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15631_Weather8.tar.gz\": {\n        \"sha256\": \"80b0187e2f8387059f75300b39f7d7f401834408ae9da86b929676ab5c79e888\",\n        \"size\": 425267798\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15632_Weather9.tar.gz\": {\n        \"sha256\": \"bb4c5785253880f10a76291e677a39b5cf9976b7948978e50cd83efc5ce1de02\",\n        \"size\": 222050601\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15633_Weather10.tar.gz\": {\n        \"sha256\": \"a48dc49ee5206a8a48eeac02e6abba0f43e3bc65b257a12bc7cd9bd0e6fb9250\",\n        \"size\": 505542413\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15634_Weather11.tar.gz\": {\n        \"sha256\": \"1756eb1d839e1af6af64a30c4def5b060bc7c8f1786f26421b00917fcb205ea0\",\n        \"size\": 458955274\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15635_Weather12.tar.gz\": {\n        \"sha256\": \"3ffa4103e11cc091426edd6e7b8afe8b76236ed0069e5f6af9cd732bbf11a610\",\n        \"size\": 370605484\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15636_Weather13.tar.gz\": {\n        \"sha256\": \"a6e11ee3cff0cf4fd46e89fc1d512e55993c252e815a28560f1ab8f68b0c2b55\",\n        \"size\": 332871305\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15637_Weather14.tar.gz\": {\n        \"sha256\": \"799792cba90d6e18d6ccee59c41ddb7efd5b8e930cb4b60b00ed5e74db7d74fa\",\n        \"size\": 127322894\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15640_Weather9.tar.gz\": {\n        \"sha256\": \"c834e6df153c3286a441711663e75b7e54cb7dadc341dfca55f817f347f5d22a\",\n        \"size\": 310434911\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15641_Weather18.tar.gz\": {\n        \"sha256\": \"e07dc9448a37e1d91a9f2b8486093382586a5da7c8a4ed8a044d0691aa425e25\",\n        \"size\": 945381877\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15642_Weather19.tar.gz\": {\n        \"sha256\": \"598c8bc477d9a113b77270566464f21c34b26d2f1277f32621b3caa6b3e9f118\",\n        \"size\": 298683184\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15643_Weather20.tar.gz\": {\n        \"sha256\": \"d7ba17303d2ce3af95f17ba1baa56dec68e221313b609f18a435764da2e89d79\",\n        \"size\": 287869211\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15644_Weather21.tar.gz\": {\n        \"sha256\": \"93570e14cd779e20aeeae0243874c3ee4b7beab1bc870121f68582b48a65b613\",\n        \"size\": 149689693\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15646_Weather23.tar.gz\": {\n        \"sha256\": \"356447ce1259c1ab869789c7aa289958eb3de672fe414505b5b3a4f51eb36e7d\",\n        \"size\": 443356506\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15647_Weather23.tar.gz\": {\n        \"sha256\": \"eedace9be0437681d6ac8a10815bb47ee2c1f2d2c92d11311d7fd94fe9ba3658\",\n        \"size\": 189701728\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15648_Weather25.tar.gz\": {\n        \"sha256\": \"08fb97ede75aa823daa12bca78ec4b32d533ccf9fc91ce1e5f8f64ebc45594ce\",\n        \"size\": 339356060\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15649_Weather0.tar.gz\": {\n        \"sha256\": \"c3b75b454f5020edec22a4ccf9781f18d89eb689ca18c75ccad1192746d57b60\",\n        \"size\": 258142812\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15650_Weather1.tar.gz\": {\n        \"sha256\": \"2cf99eeacf64cfbb11e8dd3be8a839201f2ea87595a0fedc1784f5d2d203b12b\",\n        \"size\": 466240485\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15651_Weather2.tar.gz\": {\n        \"sha256\": \"c913c6033c204efe2a135c0aad0b7b85b6f2ae2651491a0bed0240a23b40ca77\",\n        \"size\": 520521256\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15653_Weather3.tar.gz\": {\n        \"sha256\": \"aeda715d1a28c5bea4684c10e1e9dd55d4a024d861fc53fcfedb9ae1ca5f89b0\",\n        \"size\": 216341807\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15654_Weather5.tar.gz\": {\n        \"sha256\": \"5539ed7a988663c621dcbf5c85ef4feb91d76fdb8e1e8849c635a429fe46d5a4\",\n        \"size\": 550210230\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15655_Weather6.tar.gz\": {\n        \"sha256\": \"e1058fe02f4c374f566fccb9e99dc48ef569c6388ac0fa7225fb064958d78fa7\",\n        \"size\": 126172302\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15656_Weather7.tar.gz\": {\n        \"sha256\": \"4213b6a5cb1335e6c1f1d45c2724101c2324e9db70234acf1dffc6473bec2088\",\n        \"size\": 655962730\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15658_Weather9.tar.gz\": {\n        \"sha256\": \"21dc2c5958c04f0e6b1fccad2ae489e56596081218f49ec47242e6d045dd3a23\",\n        \"size\": 173571372\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15660_Weather11.tar.gz\": {\n        \"sha256\": \"d7dcbdc5a1dab3ecb43970fd4c57f9ea46dbe1c1245f366091fdb4c6a4520681\",\n        \"size\": 206031104\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15661_Weather12.tar.gz\": {\n        \"sha256\": \"226a9a51d14891156db7bddb72c2d44f12ed9d76a235a92c31363b5d5bdfcb58\",\n        \"size\": 114287772\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15662_Weather13.tar.gz\": {\n        \"sha256\": \"9e962b7720df34edc4e1ffe90ce93dbd2199953e29ce58ce6ad8161f2a8cc608\",\n        \"size\": 473046993\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15664_Weather15.tar.gz\": {\n        \"sha256\": \"a7ce7d40b6e1d58f040446d23690c6e69f399e633aeba5eb165082d0dcc18487\",\n        \"size\": 143088475\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15665_Weather8.tar.gz\": {\n        \"sha256\": \"4262b648935b2bd826732797a697141180382fbb08d61a2e2b2aa1f2caaf727a\",\n        \"size\": 460206843\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15667_Weather18.tar.gz\": {\n        \"sha256\": \"530e33a5c1362d08dc06d525d3f529bf9de8ac372ae73443879dde40c2f0cfa6\",\n        \"size\": 388318110\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15668_Weather19.tar.gz\": {\n        \"sha256\": \"2700f4c380e5399f913dee1478ee293cf67324a66f188d9621bf009878710349\",\n        \"size\": 270959569\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15669_Weather20.tar.gz\": {\n        \"sha256\": \"d22c71e34dba8cc1c21dc5963b2abde4590c7fe091a236fed78d7a6954e52be8\",\n        \"size\": 565303176\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15670_Weather21.tar.gz\": {\n        \"sha256\": \"7f24059c43d7c1435e80a3fe6d037b90d0b894e4492c13c9b7b761e85f29f406\",\n        \"size\": 152176120\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15671_Weather22.tar.gz\": {\n        \"sha256\": \"d6547e6ead6e3cca917695d73d5a096e5a930ce3ec2d19ebd5a2090d131c8450\",\n        \"size\": 160433020\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15672_Weather23.tar.gz\": {\n        \"sha256\": \"403f77d60826599b8e400dbc236cb693a05d176ffef9b83e7bda718a10c69733\",\n        \"size\": 162655928\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15673_Weather23.tar.gz\": {\n        \"sha256\": \"6bc14b4fc957858854cc3d6f1229d05339d51c49678070af07c4397c4bd6667a\",\n        \"size\": 635827057\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15674_Weather25.tar.gz\": {\n        \"sha256\": \"f0ce01683276d7045422a0ed819f99a1baac309c5de276044d056f2bae463817\",\n        \"size\": 282924303\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15675_Weather0.tar.gz\": {\n        \"sha256\": \"9bcfdd64973f775fb62785dd5aa82e70c224dbcd0718c04351b1056b90a7d866\",\n        \"size\": 439112162\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15676_Weather1.tar.gz\": {\n        \"sha256\": \"3839784a7110580f771ba0c5a027bb3d7e1c042186ef715b0af6bc7ba479081b\",\n        \"size\": 503813850\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15677_Weather2.tar.gz\": {\n        \"sha256\": \"24571abe71f47fea042d1b59a678437acf1e11c4b0d1384aa638f774c5952c72\",\n        \"size\": 258896448\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15678_Weather3.tar.gz\": {\n        \"sha256\": \"ca49d1ca0a79b4dd87e89648c5fd8cb06e0cc745a63a307c9947ae1554247548\",\n        \"size\": 448050718\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15679_Weather3.tar.gz\": {\n        \"sha256\": \"f353ae7d2cfe4fb37d58bbe82abcf1699674cd40d459bae9e5a3773d4830d3a5\",\n        \"size\": 251865816\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15680_Weather5.tar.gz\": {\n        \"sha256\": \"3526b2002053e0cc75b22d8325e1471eaf6bf1023fa36e924aa5e1290b6f8934\",\n        \"size\": 384404868\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15681_Weather6.tar.gz\": {\n        \"sha256\": \"d2e2ec9343718623dd0ba8343cf99a169ee943751eae251b03e8188938827678\",\n        \"size\": 481942242\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15682_Weather7.tar.gz\": {\n        \"sha256\": \"078e49157c6f333edf2325200df78a126d74d8a978d4044a4cf98c0e24c4f7f9\",\n        \"size\": 713898752\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15683_Weather8.tar.gz\": {\n        \"sha256\": \"0fdf4577a182884928db7eff714e6f7e29a5ef1ba34d18f0783bbb7219da9cdd\",\n        \"size\": 240223760\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15684_Weather9.tar.gz\": {\n        \"sha256\": \"d0767a9607150014ddb5bb86512de0bf3c4ada86a874f3e0a5da4b2ad27b361f\",\n        \"size\": 120614514\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15685_Weather10.tar.gz\": {\n        \"sha256\": \"1d6c710fb4dd93cdedf950e4f2f3be9a600557bb2a1e660d36d9501f4dc9e507\",\n        \"size\": 157304563\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15686_Weather11.tar.gz\": {\n        \"sha256\": \"75294eb133d99bf7d946c9aef8bd67786704845e96881b84931774d6f0b3ea6f\",\n        \"size\": 178664404\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15687_Weather12.tar.gz\": {\n        \"sha256\": \"d8f2b64c7e14e6f6381320c2b32f2c6335e6bce0de7bcb3bea12cbd79f001c2e\",\n        \"size\": 346101152\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15688_Weather13.tar.gz\": {\n        \"sha256\": \"afc738a6f5ed223fb76303a9496ec51490c981753ca3e48f672a337feaf12627\",\n        \"size\": 167464834\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15689_Weather14.tar.gz\": {\n        \"sha256\": \"9d1750b4f7f6b007b70a3c33ebf504b6f1eea5d1d897a813b15cc6ec8724d82d\",\n        \"size\": 304097905\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15690_Weather15.tar.gz\": {\n        \"sha256\": \"d85f711c0d9486d06d0f72969ccc0a6a0f5f1f01f02013638e5d1027e6160220\",\n        \"size\": 464923936\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15691_Weather8.tar.gz\": {\n        \"sha256\": \"aea5df31909a0f409536997a24a10882a1e23991d10fb7428eaf00ae0454f5e4\",\n        \"size\": 317866644\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15692_Weather9.tar.gz\": {\n        \"sha256\": \"ff73f90dec321dfc7ff46431aa85cdefc828f1c64c385436d987cbfd499a677e\",\n        \"size\": 102137617\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15695_Weather20.tar.gz\": {\n        \"sha256\": \"c27feec8421f1d5e1ece6bba212b00a00005837c4683b45c7b1ed6419a3b3244\",\n        \"size\": 678844351\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15697_Weather22.tar.gz\": {\n        \"sha256\": \"5a2ab1ccefa2c4f467cbda55d8339d09f08e5636d58e4934ceafc8ef5dbf7258\",\n        \"size\": 204635589\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15698_Weather23.tar.gz\": {\n        \"sha256\": \"27d563e7968c264c753ed479b9a3223ae92d49794dc8254695a5af0e68ed6f14\",\n        \"size\": 343916461\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15700_Weather25.tar.gz\": {\n        \"sha256\": \"7e485c687b435266ed035c3a0c2d3c27d9d7d1a440e3b0dff2150f4cf30083ea\",\n        \"size\": 286663447\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15701_Weather0.tar.gz\": {\n        \"sha256\": \"7b7f952737716d9f6b31440a61c63ac06ac0efef9998871860855cb8dd7af35b\",\n        \"size\": 158027047\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15702_Weather1.tar.gz\": {\n        \"sha256\": \"19217430d4eafcbff9cb81d26e5f38c208ae4a186a6142cd57c33aac16d0acdd\",\n        \"size\": 658468661\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15703_Weather2.tar.gz\": {\n        \"sha256\": \"91aa0c92288ea852d50633616ccec6c3ca1a075b12b45b2bad7e895a1903fef2\",\n        \"size\": 558718373\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15704_Weather3.tar.gz\": {\n        \"sha256\": \"dcd9afdae66164646da78850575ddcb94766f38c0b3539233eea4bd7658282dd\",\n        \"size\": 207867657\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15706_Weather5.tar.gz\": {\n        \"sha256\": \"5ce99d1af716fe1a524c09969236fbc1e3fb29771e0278c84cf32ba3ef998f3d\",\n        \"size\": 174761720\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15707_Weather6.tar.gz\": {\n        \"sha256\": \"e63c939251dae5bb5c0d35ab85fa90964d9da95d5b06e20335b9ca6d03bd59d4\",\n        \"size\": 135468937\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15708_Weather7.tar.gz\": {\n        \"sha256\": \"d682d90f33b977200c4208bb5e7091b433404e1343eac2a7eda239a6b966b02f\",\n        \"size\": 124127022\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15709_Weather8.tar.gz\": {\n        \"sha256\": \"5f8304fdec26bd19c8efa231777bae54a379fe6a14e05c0afe89241682889a0e\",\n        \"size\": 565385118\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15710_Weather9.tar.gz\": {\n        \"sha256\": \"dcfe2a675f17d8724a69fd5a218bcfdf66c9b9aa2719f128ad44f8e1ba2707f8\",\n        \"size\": 441851398\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15712_Weather11.tar.gz\": {\n        \"sha256\": \"a94b6600ce626508e0e0d64c3e7e313dd6ac41a1492328f4018f7891e12a0f7b\",\n        \"size\": 134008832\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15713_Weather12.tar.gz\": {\n        \"sha256\": \"f5089307e53ba23d4512845666f2e1ea4d5176d3a720e5aaa03f6ab794811ea7\",\n        \"size\": 136439155\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15716_Weather15.tar.gz\": {\n        \"sha256\": \"854ee7d1c7168eb532c8644af059d088af3f81d469025becfb2e9558a4589cc3\",\n        \"size\": 131748196\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15718_Weather9.tar.gz\": {\n        \"sha256\": \"6ae3fe25b3b991b688f3fd162da1f210763d303fe9ed75fbaae844791ef53f2d\",\n        \"size\": 130483336\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15719_Weather18.tar.gz\": {\n        \"sha256\": \"b50afd48ac4a522ceee0c91241b270ac79c2a6bfc902b369e7aaadd280acaf64\",\n        \"size\": 720939881\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15720_Weather19.tar.gz\": {\n        \"sha256\": \"060bf2cd564cf21efee25c653f97f28e50a15a63bcb797539a5d46d0125571d7\",\n        \"size\": 463087734\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15721_Weather20.tar.gz\": {\n        \"sha256\": \"01e6884002c49b22473f90af791e21722f3d3dba8c8ac1d7a3754b6324c9032e\",\n        \"size\": 548407118\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15722_Weather21.tar.gz\": {\n        \"sha256\": \"ce3f349a4d0b18c98d41ad88145c6c9d6e90083da65307f6dae6b4900bc1036a\",\n        \"size\": 231047382\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15723_Weather22.tar.gz\": {\n        \"sha256\": \"5ed6d3d03bcf2c91cec691238dafed75c80aa13f1a854c7aea443532ef8441a0\",\n        \"size\": 362527104\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15724_Weather23.tar.gz\": {\n        \"sha256\": \"99c0bf304f452e7c95d76e1f54f18be96c1db3814de675e08a70b8eece79fb7a\",\n        \"size\": 451430162\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15726_Weather25.tar.gz\": {\n        \"sha256\": \"b0d4736e44f5aff2b68f0ba2cd200233a3b03994ecffb3d64375332ed2d44fbf\",\n        \"size\": 350351445\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15727_Weather0.tar.gz\": {\n        \"sha256\": \"22390bd1335f7f412af3acc8e7c32c53bbb9b33bc9f37b6bfa5dccfbc3872d7f\",\n        \"size\": 482460770\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15728_Weather1.tar.gz\": {\n        \"sha256\": \"749d30583544ad10fcc0013e7de7f8ac91ba0d9f62a691314908fb3bf6f97b76\",\n        \"size\": 353988017\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15729_Weather2.tar.gz\": {\n        \"sha256\": \"d88676901370bf12f8f0fe48a4a441ffd351d7a1da7312f7382a5cf17fddc4fb\",\n        \"size\": 368248991\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15732_Weather5.tar.gz\": {\n        \"sha256\": \"48e432874ba0cc556f689fd661f8dbe840ac0c52b725790c451428971d25f773\",\n        \"size\": 495841064\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15733_Weather6.tar.gz\": {\n        \"sha256\": \"0c4e79cc60c5a94b24e6c2ea1364bacb68f438c92ce825ba034637277da517dc\",\n        \"size\": 420982993\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15734_Weather7.tar.gz\": {\n        \"sha256\": \"25a313f6ec2078bb6aac9389285936f471e22638b857ff003c84de0fbbf883c0\",\n        \"size\": 595050892\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15735_Weather8.tar.gz\": {\n        \"sha256\": \"aba1d00051af31c5b281e849e8f0bbec7c60be28a0f5847ee1531b47ec4fcd84\",\n        \"size\": 145287626\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15737_Weather10.tar.gz\": {\n        \"sha256\": \"a69d28d0630c49d1f3ca54b144b0668009b1e16ebc0339f1fb525a2ac036dbec\",\n        \"size\": 437380152\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15739_Weather12.tar.gz\": {\n        \"sha256\": \"cdfbc3627e575d444badc34e032041c5bba0a51ad2c296c0709aea977a181d4a\",\n        \"size\": 604585464\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15740_Weather13.tar.gz\": {\n        \"sha256\": \"895bcfe9ce0c2cb455a8ecdc264fde68dd95db5d083647686d8fc9352255be4a\",\n        \"size\": 782799619\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15741_Weather14.tar.gz\": {\n        \"sha256\": \"2b8649dc4104cefba3f8e79c85a62d16aafc519084d4cd3199915d9f6e2632a2\",\n        \"size\": 486890676\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15744_Weather9.tar.gz\": {\n        \"sha256\": \"914a0de663dedb81b880c88273c8aaab1486b084f06202e84af44001ba0efacc\",\n        \"size\": 236003022\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15745_Weather18.tar.gz\": {\n        \"sha256\": \"8d3d617e2c72d7d01e738f7f117464a9557f138a4753eae1897151771a081723\",\n        \"size\": 569855324\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15747_Weather20.tar.gz\": {\n        \"sha256\": \"8184d9227d25bbd713822be230f12900db1fe2a1c0466c10ab08ece54780c45e\",\n        \"size\": 299795730\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15749_Weather22.tar.gz\": {\n        \"sha256\": \"cc7901f8d8b9258d77b730479e0da3d2ca6c49b8e1eec1847720328c66ffc18e\",\n        \"size\": 166972845\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15750_Weather23.tar.gz\": {\n        \"sha256\": \"694c1e2f9df9dfcc0c5f5732dfae803ef2e5341ac4de1958406219a7ec1be893\",\n        \"size\": 498428366\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15751_Weather23.tar.gz\": {\n        \"sha256\": \"65b89af6d13db77b583ffda0dd1aa224890662e1f90fb5ca1f81e5c758304525\",\n        \"size\": 275102941\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15752_Weather25.tar.gz\": {\n        \"sha256\": \"5a82f40409f7bdbce83eb9e3606ed8ce0a8250296b80ec1c69316baf2c1c2f00\",\n        \"size\": 232081978\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15755_Weather2.tar.gz\": {\n        \"sha256\": \"baa7dcd1cac2c6ff87088b0d9682d43bf1060179e1dcecaedb5cdab98a125d6c\",\n        \"size\": 579844629\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15756_Weather3.tar.gz\": {\n        \"sha256\": \"1524740b9b0ec64c950b92485a55760be0278b0fb3ec181dee29601b899099ae\",\n        \"size\": 289596495\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15757_Weather3.tar.gz\": {\n        \"sha256\": \"a8fd655a68091a31638c08e71c79c593660af01b8c7f01409cfd0baee8e8e0bd\",\n        \"size\": 165301013\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15758_Weather5.tar.gz\": {\n        \"sha256\": \"b3ed5c78a42e9135fd42a8cec2629942154704ef0f41fda228a3c81af3f42a83\",\n        \"size\": 439520602\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15760_Weather7.tar.gz\": {\n        \"sha256\": \"dade18a24cae1ddc32534feede6ad033f435986cfb9f61a2a96cec475701aeb1\",\n        \"size\": 314543510\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15762_Weather9.tar.gz\": {\n        \"sha256\": \"d8bcf8007c129a8efae87639c3eefd7d58305cdc8780acc5dfe751af54fe9020\",\n        \"size\": 379800291\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15764_Weather11.tar.gz\": {\n        \"sha256\": \"48438fed968c9344de3932309ca78bc37286e70da55a37a2041e1c7ee17a3e74\",\n        \"size\": 488388928\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15767_Weather14.tar.gz\": {\n        \"sha256\": \"56fba3ca05c91d1fee8112bad71872d073810e6fa19e437685fa6a9935cc0087\",\n        \"size\": 375043154\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15768_Weather15.tar.gz\": {\n        \"sha256\": \"eed6171fd2081d98383c8174d2c55ec5d017614fe50f2c1fc93de1b258f979f9\",\n        \"size\": 339077709\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15769_Weather8.tar.gz\": {\n        \"sha256\": \"7c6f1d2eb243b8881d2bf53681043270439614371c9d53ca5626f5c002c0c49a\",\n        \"size\": 409722398\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15770_Weather9.tar.gz\": {\n        \"sha256\": \"5896beb46dc629bf5d247a06b51b2457f99cefff5cc4d38666ef9b87f73a4d72\",\n        \"size\": 110291522\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15771_Weather18.tar.gz\": {\n        \"sha256\": \"667af4225cca4d9f0e39d1acfb5369130496e7eb58cc3d41c68af320c75d6c3a\",\n        \"size\": 311625002\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15772_Weather19.tar.gz\": {\n        \"sha256\": \"06455bf3743b82f5ca99970f8c083493a7cadc4c4f581396f77c3cd1c4b8a823\",\n        \"size\": 899439135\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15773_Weather20.tar.gz\": {\n        \"sha256\": \"d63457239bd69bf5c6319d4dd90595708315fede60b46ab3d629c44b35b3f9a3\",\n        \"size\": 231375340\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15774_Weather21.tar.gz\": {\n        \"sha256\": \"edcbfd1050628b16ee08bcdfdee845c6c6d6b1128e3be524d915896b54799234\",\n        \"size\": 212842220\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15779_Weather0.tar.gz\": {\n        \"sha256\": \"a1aa3c8baa74d90456aa7d077a09a49e5f87968a91457c7b6f52ca0ffda6f4c3\",\n        \"size\": 565749882\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15781_Weather2.tar.gz\": {\n        \"sha256\": \"1a64f2fabc08d700e763ae5bb7a050fd8ba1dcf1e6fe8665e6ace98cc248e093\",\n        \"size\": 187121492\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15782_Weather3.tar.gz\": {\n        \"sha256\": \"4510876862038cb1366ba115f98175ee19ec36de1896363f7fd39ba893f39dd7\",\n        \"size\": 276698186\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15784_Weather5.tar.gz\": {\n        \"sha256\": \"667fe1a2d2b9d1e65fdc82dbed95cfdb3cb6fa943d16719aea7e7f70dac0d093\",\n        \"size\": 603560636\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15786_Weather7.tar.gz\": {\n        \"sha256\": \"652eb83bf1e01869e99b09f3afaf39e8760721bbaf7e12c98a5efe73260e52bd\",\n        \"size\": 457238852\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15789_Weather10.tar.gz\": {\n        \"sha256\": \"c66a424d1ab4abe713392180464c2c4ca3f9d2a86ba3805e5274424ed90f9ac1\",\n        \"size\": 452299210\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15790_Weather11.tar.gz\": {\n        \"sha256\": \"32989adbeb09a5ee9291f4a053df2623ecd53f2eccf820b5bc43aecf60b35524\",\n        \"size\": 473737959\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15792_Weather13.tar.gz\": {\n        \"sha256\": \"e56f9dd26edfa2d3631b783313fa07ba2e739dbe5c629f4c912fd3ab7b207e2b\",\n        \"size\": 596818027\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15793_Weather14.tar.gz\": {\n        \"sha256\": \"902af59e8f17beba239a2e51b1d9e216250ecdeba50bd6a92cbf1b537e4a308b\",\n        \"size\": 608038782\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15794_Weather15.tar.gz\": {\n        \"sha256\": \"383d6f6c8f5fbed0d4cbfa744641a94e52afa1b2d8ba87179df3889d8d0494ff\",\n        \"size\": 185870429\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15796_Weather9.tar.gz\": {\n        \"sha256\": \"fdf1d8ed88ce5aaa6c10bc5e59cee4575b30baed1d845b45e59f425b5293d956\",\n        \"size\": 291737704\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15799_Weather20.tar.gz\": {\n        \"sha256\": \"608f931395cd71f52c92548c8501d5e97dfadbed4c96a3ed5bda47d66512f631\",\n        \"size\": 141500105\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15801_Weather22.tar.gz\": {\n        \"sha256\": \"f9fd8245f98b000cfb2969dd40b342fdd141008242ee5edc3fa902ac998a3331\",\n        \"size\": 466919966\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15802_Weather23.tar.gz\": {\n        \"sha256\": \"86ef0243df5c8dd21f23aa14c2dfba577a49a0c4b64ef844103195c8d76af383\",\n        \"size\": 548849441\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15803_Weather23.tar.gz\": {\n        \"sha256\": \"8534d724f3bb8799b2e7b5c33b11f5ffe3befa40842ec56715e4e1b74dac9b21\",\n        \"size\": 357154392\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15804_Weather25.tar.gz\": {\n        \"sha256\": \"152bacfa127abf7eacad96d0e92ce15ee9facc9106977e08c4662c8d459a5935\",\n        \"size\": 97054227\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15805_Weather0.tar.gz\": {\n        \"sha256\": \"45aba5e61548a68f207af799e22ef4429029056755125463d02ffc00f3abf342\",\n        \"size\": 396152374\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15807_Weather2.tar.gz\": {\n        \"sha256\": \"f89984b4f548a53e500f6c2900bd47de778e458142925a6be4549fa3d383c205\",\n        \"size\": 325104624\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15808_Weather3.tar.gz\": {\n        \"sha256\": \"670bd3bd213f70646a781e8c391ed1022b70887c5854cb13ad185b5cecc84137\",\n        \"size\": 154815080\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15809_Weather3.tar.gz\": {\n        \"sha256\": \"4d2e9ae9502535dbd3bd98fcefa9f8b31454104696d25a0c15e046f554250513\",\n        \"size\": 395407206\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15810_Weather5.tar.gz\": {\n        \"sha256\": \"e8ed9b35fa5d2b5d7854922646a3d0b05720b6b271c9f80bf142406fd02f2b30\",\n        \"size\": 719795754\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15811_Weather6.tar.gz\": {\n        \"sha256\": \"9f69042b2a491e3431248b33d3865c1355082eff57c8d5f872b0f07863223e1f\",\n        \"size\": 225157844\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15812_Weather7.tar.gz\": {\n        \"sha256\": \"c2cade93a7ceb6970fcc37acb8b04392186306aa99be44d0b8cf05eae9055ce7\",\n        \"size\": 222460729\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15813_Weather8.tar.gz\": {\n        \"sha256\": \"5dd4a6a93d3673f2346c6f1d16e80bef98bfccb3d0915e41bc359dd81f01b65a\",\n        \"size\": 256605213\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15814_Weather9.tar.gz\": {\n        \"sha256\": \"a1ebecdbca4c5e5f3513b95dd2aa22098f14d5571de833909208f9fb16f14740\",\n        \"size\": 371089435\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15815_Weather10.tar.gz\": {\n        \"sha256\": \"6cefb539a99b5e123159ec08e17fda27c6cde7c5c04255e45908ab843c596335\",\n        \"size\": 395866988\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15818_Weather13.tar.gz\": {\n        \"sha256\": \"d571e250cb9161c580290decd0434a1f4437587867aa5b76863dc2743c037b2d\",\n        \"size\": 470166991\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15820_Weather15.tar.gz\": {\n        \"sha256\": \"8d81e635454bd6499016d9a2496c9c8b8e4a898b0c230b52162fc01bc1df0036\",\n        \"size\": 254445764\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15824_Weather19.tar.gz\": {\n        \"sha256\": \"ce4a4bbe49d67d06d390eb4af6cf2ee26d1e9a23d89379f811b56511e574877b\",\n        \"size\": 789917039\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15825_Weather20.tar.gz\": {\n        \"sha256\": \"4f3f01701b3235996c7441b9bc11f86c6c88c1a2e45a996bbef2845d74613c4c\",\n        \"size\": 535041080\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15826_Weather21.tar.gz\": {\n        \"sha256\": \"89f6af8c54a56cafda84ba0741cd3cae751e5df2ed21ae07d9bfbb0510478a7d\",\n        \"size\": 135650726\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15827_Weather22.tar.gz\": {\n        \"sha256\": \"230eed812b1a02d75d57a20a4e4150d378ef4679ddc46ddc6d56db87181ff2d9\",\n        \"size\": 433716255\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15828_Weather23.tar.gz\": {\n        \"sha256\": \"ee693b0ff186c1fb116ebd2250f3e51db5917b22a7728e9e644e4f21b6ead41a\",\n        \"size\": 275956677\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15830_Weather25.tar.gz\": {\n        \"sha256\": \"07709ddc9c799ee52f61eb9daaa28cf1b40ebfd618c9ebbd6b278e28b6648ec5\",\n        \"size\": 379090093\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15833_Weather2.tar.gz\": {\n        \"sha256\": \"9f71f8f7c907808d49d9dd19462d7ca56cfa7e716fd6ad20a5bd7f7b03d007bd\",\n        \"size\": 364086163\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15834_Weather3.tar.gz\": {\n        \"sha256\": \"929e70bdc08b838d308424270c860912e514a4136d10e9e449769f2bc8e850bb\",\n        \"size\": 224559479\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15835_Weather3.tar.gz\": {\n        \"sha256\": \"33d8fb0285ffff38d8e493bb760e0f74472db743f9f5547c70fa6e01fbce06ad\",\n        \"size\": 550901862\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15837_Weather6.tar.gz\": {\n        \"sha256\": \"e83b6abd395a0d897f66a13f2ba12eff9392c9b957f9e1bc78325cbddf3e0b44\",\n        \"size\": 858940910\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15838_Weather7.tar.gz\": {\n        \"sha256\": \"8441f439a06f5f9788f880d30b50be562f76e6adafd22f3d41ea22140296a52c\",\n        \"size\": 607130433\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15839_Weather8.tar.gz\": {\n        \"sha256\": \"beaead63a279f17ddc51b0b4e26b92e74aaa98ae9d290e37928f02ae7fa0bfa2\",\n        \"size\": 440226951\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15840_Weather9.tar.gz\": {\n        \"sha256\": \"4222adf4f382e9cfb38606d29224c7b74839283b04fc56ad08501f5318bb8578\",\n        \"size\": 312496732\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15841_Weather10.tar.gz\": {\n        \"sha256\": \"e60cf71cd994ac397b250dde49df74711dfb2344402788cd79a5f01c750f574d\",\n        \"size\": 462478372\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15843_Weather12.tar.gz\": {\n        \"sha256\": \"7936e39fbe39e4fc14ece700340f14bcd1240ff2e36782d25a0da4b50a1b6476\",\n        \"size\": 116336152\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15845_Weather14.tar.gz\": {\n        \"sha256\": \"7aa48aff9deb4b0e78ec9ee8a580117127036d17e8f642fe0d07e188518ac781\",\n        \"size\": 541974375\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15848_Weather9.tar.gz\": {\n        \"sha256\": \"a5f94b5bd13d6f58e74a925283db286ce4836127706296c57a6d9449b0874365\",\n        \"size\": 232124402\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15850_Weather19.tar.gz\": {\n        \"sha256\": \"71fa1fb566e06c45fb16bc2bf086ebf87dba75b4c0cb677667074736f4b5f933\",\n        \"size\": 694773870\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15851_Weather20.tar.gz\": {\n        \"sha256\": \"9d8f370c367082e6c33e43f4e2760746cde856a933b1c010aefedba1087d0f8e\",\n        \"size\": 864496397\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15852_Weather21.tar.gz\": {\n        \"sha256\": \"25f55cad7652460c08e34db7c9d6f401b77a82dc8430a6e928570d5028e0bddb\",\n        \"size\": 209059815\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15853_Weather22.tar.gz\": {\n        \"sha256\": \"6987344d3fdaca62299dd9dd279ae4263a34f02b2f424ee56a53007321d0b41e\",\n        \"size\": 126079138\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15855_Weather23.tar.gz\": {\n        \"sha256\": \"5934e5383301f7a70e7e5cbfdf9e9effd7f62045876582e2050d189dc6fb73d7\",\n        \"size\": 119811790\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15857_Weather0.tar.gz\": {\n        \"sha256\": \"1127901479e29a5bedf612a35dba5ef0d7b6effc543a091de85fb30764843dc5\",\n        \"size\": 267350089\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15858_Weather1.tar.gz\": {\n        \"sha256\": \"b8b9f12840f8b0c73d57ddeca7991c725d381c85176a709bf0ad47c880e298e5\",\n        \"size\": 469369553\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15859_Weather2.tar.gz\": {\n        \"sha256\": \"ad216afccb69e22ada5c2d64d51937fa5fb29ef58c2e769a2a6792edaaa79e30\",\n        \"size\": 282062245\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15860_Weather3.tar.gz\": {\n        \"sha256\": \"cf8e8f049171c5a16d2125e92968885cb234a3a1042f4c7eff9b229037d35e12\",\n        \"size\": 387751983\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15861_Weather3.tar.gz\": {\n        \"sha256\": \"d8ab28101471e542c7b964c66f9272646ae29cdf28e1f87dbdf8124dfdfce19f\",\n        \"size\": 242489019\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15862_Weather5.tar.gz\": {\n        \"sha256\": \"1ffbdcf056d390e217f19ceb9dfbb8b2a7c13841153201f02fc7a34415321145\",\n        \"size\": 265822098\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15865_Weather8.tar.gz\": {\n        \"sha256\": \"633fc1aa8ed8f55e3eedf0b6260de02bc6f3e9db49c7d1bd8aaf7a86dedfdb76\",\n        \"size\": 289918847\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15866_Weather9.tar.gz\": {\n        \"sha256\": \"d53913394d6f155f1fbb9a976c9d82964c4f7af8db5eada21631a32367420bc0\",\n        \"size\": 373877045\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15867_Weather10.tar.gz\": {\n        \"sha256\": \"98a945c3599871eee20e660db8d9a96d4412812f9dd1dc0d1add8a816b4d7bf9\",\n        \"size\": 119847935\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15870_Weather13.tar.gz\": {\n        \"sha256\": \"ac9bfc174890a8ac977878f8a005831bcda37dc7276e9f771e1d2cc3128c09cc\",\n        \"size\": 263576838\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15871_Weather14.tar.gz\": {\n        \"sha256\": \"b1a160dafd652ab29295f3b675098c2586f0c78eecba6287b9c0785bc053ecf5\",\n        \"size\": 460507091\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15872_Weather15.tar.gz\": {\n        \"sha256\": \"8a03767df025d3aef5ab443b5cadac882cbbdd5ce94ccd0132fde92f7b650137\",\n        \"size\": 922595592\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15873_Weather8.tar.gz\": {\n        \"sha256\": \"4b84a09369dedbeaad288ebf33715c3d0f499c8a065ee3de1500a89c61295353\",\n        \"size\": 309180555\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15874_Weather9.tar.gz\": {\n        \"sha256\": \"5d405882f3ce087f56990b610824ba2602e8f8398c024530b6bc2727a27a201d\",\n        \"size\": 690797248\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15876_Weather19.tar.gz\": {\n        \"sha256\": \"bee3d8e6b5713d5e39486169e4a65dad3184f4dbc10f1ab4aa8b712992e37a9a\",\n        \"size\": 722890996\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15877_Weather20.tar.gz\": {\n        \"sha256\": \"c5b85050fadc74dc4e6a53ce1f768bd75f4d51bac314774f165e325069d4a930\",\n        \"size\": 451175967\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15878_Weather21.tar.gz\": {\n        \"sha256\": \"fdee4971e3a086abe8af0243cfd2aad9a8bde698544af73c50e267ce12b186fb\",\n        \"size\": 144276747\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15879_Weather22.tar.gz\": {\n        \"sha256\": \"25c5701903e54b7df40635820c135621430ffc65639eb7596aa145bfea6847cb\",\n        \"size\": 418722805\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15882_Weather25.tar.gz\": {\n        \"sha256\": \"d390f378d80b8e3d35ec3133dbac62ba7484751ddaaa16246865a6c52bbf7ff6\",\n        \"size\": 389685624\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15884_Weather1.tar.gz\": {\n        \"sha256\": \"491fdedd824668669f30158a5b2b25cf7ef8f30fd0194e4c73b482607269fdc6\",\n        \"size\": 127419509\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15887_Weather3.tar.gz\": {\n        \"sha256\": \"55f12eb971e40049c30a2684998fd768878ff8d98b6d34eeaedbf7f57bb9176b\",\n        \"size\": 515450609\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15888_Weather5.tar.gz\": {\n        \"sha256\": \"550f31d5ea023c01dd3e8cb689878c14e96fb15c753be4746081a20d322b4b72\",\n        \"size\": 135988536\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15889_Weather6.tar.gz\": {\n        \"sha256\": \"55ec1b6826f0d19e647c076a15603409fb7967e2ae79e8e9193ea6642b91a5ab\",\n        \"size\": 415168428\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15890_Weather7.tar.gz\": {\n        \"sha256\": \"af345c53c601c0552eb4d5697f9b8aa3f41fb805460ae5359b9d4a5265251bb8\",\n        \"size\": 556923615\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15891_Weather8.tar.gz\": {\n        \"sha256\": \"582fc3800cb050cf8e4da6fb0b537d0bf1e73bb4056f0f14b6f5d2b7fc03a9ce\",\n        \"size\": 324223735\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15892_Weather9.tar.gz\": {\n        \"sha256\": \"f484f2648df2ff451ff99ba604a0ac9274c38f3263919741579a1ed59ac7fafc\",\n        \"size\": 628973018\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15893_Weather10.tar.gz\": {\n        \"sha256\": \"aa9cc0ef7cb8ebc7363270042786cd9ad9d3b287c490b47652ed11a44d80f5f4\",\n        \"size\": 399116368\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15894_Weather11.tar.gz\": {\n        \"sha256\": \"cc2e6d9db7ab0b4ccd6fb03346ed814ec3e7de41e813695c1c3b279f84bd455a\",\n        \"size\": 329024931\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15895_Weather12.tar.gz\": {\n        \"sha256\": \"5c43250fc0a93c530a999715606c89b2329d6687e0851790ab3c1462cee6b188\",\n        \"size\": 455335980\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15897_Weather14.tar.gz\": {\n        \"sha256\": \"826bec110649d3381270618b861d39ee89e7df786ae54abd9111a57f184afc67\",\n        \"size\": 251246186\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15898_Weather15.tar.gz\": {\n        \"sha256\": \"ab330cb39014a9657d9896fcd0546ddec15f91bbd9050db44439824a8db49653\",\n        \"size\": 679828711\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15899_Weather8.tar.gz\": {\n        \"sha256\": \"0c2b7c6e2d601b4eea83ea1bc15915374477ff32245be6971fa00ef1db4c9520\",\n        \"size\": 172885467\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15902_Weather19.tar.gz\": {\n        \"sha256\": \"88a677b046b4ca0d250e948dd348b88d5c7a269eeec79d86abe39422209635ab\",\n        \"size\": 163192678\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15903_Weather20.tar.gz\": {\n        \"sha256\": \"199a7ef67605669f428dbe327a0deb554f13fb42a1c155215490466d4f7dd88a\",\n        \"size\": 469568034\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15904_Weather21.tar.gz\": {\n        \"sha256\": \"3c62557980e62d18efcad32c4b25b834298a7a78b82e1e260e284fec06a8a799\",\n        \"size\": 125024137\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15905_Weather22.tar.gz\": {\n        \"sha256\": \"e399f45446e858a5f11ed137933bc571382191da46f7c8fde2277aeed6d28390\",\n        \"size\": 283432577\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15906_Weather23.tar.gz\": {\n        \"sha256\": \"014488a4ca74d1beec527ceb25363c276c6c93a5a240797c0747e07ac7f15f1d\",\n        \"size\": 224588964\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15907_Weather23.tar.gz\": {\n        \"sha256\": \"6dcc231325136312f0f0a9836b37678e254cd97d4abdd92de655e7c25530065f\",\n        \"size\": 712387461\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15909_Weather0.tar.gz\": {\n        \"sha256\": \"fb85a0259c688f2f4f7d84cb293a078e95c3964d93e804eef174b7b4c57bd024\",\n        \"size\": 409680460\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15910_Weather1.tar.gz\": {\n        \"sha256\": \"28c2ef5b11fbe0158e023b85c118add9aa100faebde10463393b6435ad48f767\",\n        \"size\": 717558607\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15913_Weather3.tar.gz\": {\n        \"sha256\": \"a5ce6f8cbdc37907bc8560c9357b41ccacfd9f1f50a6eb9d080066b40ce2bf5b\",\n        \"size\": 985442534\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15914_Weather5.tar.gz\": {\n        \"sha256\": \"3eaa2c8347ed2f0675760d85b4e4fe701cb0adcb65a6b2320bd641bd2b966e15\",\n        \"size\": 389023740\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15915_Weather6.tar.gz\": {\n        \"sha256\": \"266600d0e62b61e9d2a7921c817689b866cb4a610c31ed077bbd9d6374b0588f\",\n        \"size\": 490725094\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15917_Weather8.tar.gz\": {\n        \"sha256\": \"5a7a43f534ead2b65b05e57d1b4151c8c9fdbabf0d8a5a7bdd519401550d0324\",\n        \"size\": 367550244\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15919_Weather10.tar.gz\": {\n        \"sha256\": \"c849504f0c977c548c70537d8b8e12811e0440a61772464a32d210a3702b1c96\",\n        \"size\": 712833501\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15921_Weather12.tar.gz\": {\n        \"sha256\": \"8b9328d0284515964703bb436f1ffe7cf3251422b9c0a9528e8c35e182a0ca01\",\n        \"size\": 202261220\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15922_Weather13.tar.gz\": {\n        \"sha256\": \"a08fca7650fb4cc3f51105f8b631265a115a6f542673eb43ee2a645484e4295a\",\n        \"size\": 371000805\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15925_Weather8.tar.gz\": {\n        \"sha256\": \"09b7b27d0496b0956823402d12104fc55985b3398359c0e0b7bb9552598eb163\",\n        \"size\": 404318009\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15926_Weather9.tar.gz\": {\n        \"sha256\": \"84d191d717bba0d21cb7d84b530e97c5500d196157d3b05642067a474a40c182\",\n        \"size\": 201548995\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15928_Weather19.tar.gz\": {\n        \"sha256\": \"860378b9f17dfb300f9406591b4e315d092e79c31cc6fedbc318e88fdb5bcc79\",\n        \"size\": 238297036\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15929_Weather20.tar.gz\": {\n        \"sha256\": \"daa5a6164e4a19ac8f0774a1209d860b5c18854d2a3feba8fb25eb9ebe9e03e6\",\n        \"size\": 584823515\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15931_Weather22.tar.gz\": {\n        \"sha256\": \"8b5e5919fb29c52a9e44ae9a40c757f428b1fe9a1d42ae81962dbdd588e4e105\",\n        \"size\": 452854042\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15933_Weather23.tar.gz\": {\n        \"sha256\": \"1d1b611738a0a7b2ac248acf9b5d32db754dd034dd67b990c368e63bd17e69c7\",\n        \"size\": 434024690\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15934_Weather25.tar.gz\": {\n        \"sha256\": \"a5789facf88e0f45a6e421954a069465650287fafe5f9dab7147b73ac85c60c1\",\n        \"size\": 383181777\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15935_Weather0.tar.gz\": {\n        \"sha256\": \"8e4281d450435e795e97abae18359a0912f85f99c48f7728cb104b32a36ba55e\",\n        \"size\": 128362107\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15937_Weather2.tar.gz\": {\n        \"sha256\": \"5b7be1c323f4422ef94ecd446a4660c669ee93d2aa31331469e5588c100de571\",\n        \"size\": 670846255\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15938_Weather3.tar.gz\": {\n        \"sha256\": \"634a3acef20ebeb2e297ce90f84e54960bc3d4707aa9a49f4c9e687fa71650f6\",\n        \"size\": 435139516\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15941_Weather6.tar.gz\": {\n        \"sha256\": \"bc825f41e333c5da57c5a62ee76e1b7a1a268c4e4e823f267a064b855515aa4c\",\n        \"size\": 133427027\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15942_Weather7.tar.gz\": {\n        \"sha256\": \"331b9104b078d39518d1fecbca81d65caf28e5f81ec9954bbdfab18ea23fd331\",\n        \"size\": 328379326\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15946_Weather11.tar.gz\": {\n        \"sha256\": \"d02e15f833c8be9a221ceff23523927e464020102fa0839026f9ebfa30f0dfcd\",\n        \"size\": 212705031\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15947_Weather12.tar.gz\": {\n        \"sha256\": \"6c01aa85e71e3aa9119a3326de66f55cab4d387ff2e46bb9ea89a3e62876c4ff\",\n        \"size\": 158225238\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15948_Weather13.tar.gz\": {\n        \"sha256\": \"b3a28e9954010d26f67d5c7f01d0da73fcd12bc20fbf98008f7128bb598adf1d\",\n        \"size\": 457222394\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15950_Weather15.tar.gz\": {\n        \"sha256\": \"29e80061c3441e7e6cbd3cea66c817fff2c8fd8a98298d6e8997e9f0ab63f1ce\",\n        \"size\": 429823393\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15951_Weather8.tar.gz\": {\n        \"sha256\": \"1e6d3413b361eaa256d9ebb1476eada8e7e2180b83c223148bd7edcabac32448\",\n        \"size\": 453899441\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15952_Weather9.tar.gz\": {\n        \"sha256\": \"1a7b5346037f10332e0755f1655ea451ea33fbf21e3d1774ef57614e4c93fee9\",\n        \"size\": 107177676\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15955_Weather20.tar.gz\": {\n        \"sha256\": \"3ada84fc09e8b08e1327fc0cdc5fc95f677d170dfebbcaa432ba531981592ab5\",\n        \"size\": 260929424\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15956_Weather21.tar.gz\": {\n        \"sha256\": \"55e6f485d0c34e10bfe2f202604d137c87ac07e4ba398f7ebce1ef772052073f\",\n        \"size\": 168361779\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15957_Weather22.tar.gz\": {\n        \"sha256\": \"3a06d9d75976dad58a5b5d45df64b4fe96c636bc8aa439cd930d241a991c3356\",\n        \"size\": 246126376\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15958_Weather23.tar.gz\": {\n        \"sha256\": \"5e38f5ca68b835e3951a6629ff05238d82efd2f74ab08c2884df2d4d68eba1b7\",\n        \"size\": 420247249\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15959_Weather23.tar.gz\": {\n        \"sha256\": \"059bd573e9b2fdefab615a216e3b18eecfa720fa418057f37fee0f174d07b936\",\n        \"size\": 342632844\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15963_Weather2.tar.gz\": {\n        \"sha256\": \"be28a4a77d4c9db611627f220b18d883cace94f5c9718d41a52782b996cc4d19\",\n        \"size\": 354691395\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15964_Weather3.tar.gz\": {\n        \"sha256\": \"bff924b804c53d4fb3ec391fd157d1a204f919b94f82b0db301636f816f15cef\",\n        \"size\": 614257696\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15965_Weather3.tar.gz\": {\n        \"sha256\": \"fc083d79052806b262d3b7c89bc33e96f7b40fe898d31532b67fa3e49b9d04db\",\n        \"size\": 288338787\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15966_Weather5.tar.gz\": {\n        \"sha256\": \"ce8de03017aed5f388cc40b1278f47ca10cb23b1aa8a9200464a4b72e20690ab\",\n        \"size\": 150876478\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15967_Weather6.tar.gz\": {\n        \"sha256\": \"f4aa4d0d7d0ade0415b10fff96217b2d80f7df278cce64b7e3109cc78d7e1977\",\n        \"size\": 324179295\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15969_Weather8.tar.gz\": {\n        \"sha256\": \"6ef5163fb89ac83948c841576aa39fe78ec66dc19d4383612d5737e1640f658c\",\n        \"size\": 124409463\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15971_Weather10.tar.gz\": {\n        \"sha256\": \"fa900ea1b42d0d7b533c81b4851094f499eac0fde3c32852dc7b193e3a83738c\",\n        \"size\": 568738594\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15974_Weather13.tar.gz\": {\n        \"sha256\": \"2a3f4ffe36742f4d591ae278b62546e06503bae32a007c5416ac2a0f42b6f3ab\",\n        \"size\": 175333067\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15975_Weather14.tar.gz\": {\n        \"sha256\": \"3894b2bd856e6d05a0a3b7c458ec21f8c544df5efd4ca35a195cb094dd322e35\",\n        \"size\": 265658187\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15976_Weather15.tar.gz\": {\n        \"sha256\": \"507971b0fd819dc70bb1f738c9c1bf423ab6c9aafac58b4dcbcd9a9edc02d331\",\n        \"size\": 237081687\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15977_Weather8.tar.gz\": {\n        \"sha256\": \"4cdd0a7beac4d0eaeaafa658cfc5dbee0d1bf85dda828ba77a2ea2542242bb06\",\n        \"size\": 212262760\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15980_Weather19.tar.gz\": {\n        \"sha256\": \"2d7fe73d2b1904680ad161a0df867c7609951c11cbeb85c2c97afd60eeb37eaf\",\n        \"size\": 148820012\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15981_Weather20.tar.gz\": {\n        \"sha256\": \"e3c7cfd3f69318dee51fcb95f38672198ac0e85a7676d08cdf27b095e1e06757\",\n        \"size\": 1402463795\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15982_Weather21.tar.gz\": {\n        \"sha256\": \"c0945b0cade7bb40683c403899623e8c7a3281ef08e75542dbab390f2b167d54\",\n        \"size\": 406782446\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15983_Weather22.tar.gz\": {\n        \"sha256\": \"fc2e1cca9ba1b13357bc296bf7b5fc52b831dce9a2ce3a2c7a9c8e09dbd0d1da\",\n        \"size\": 256385928\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15984_Weather23.tar.gz\": {\n        \"sha256\": \"3759c74f0708e2adf460e56a35dabccfdcea6b2550669961b50327b02dccd7d5\",\n        \"size\": 773377500\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15985_Weather23.tar.gz\": {\n        \"sha256\": \"27b7004fa6f8c4fb1f27865c711360c653ac308705ad92121993d05633d3175b\",\n        \"size\": 150617345\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15986_Weather25.tar.gz\": {\n        \"sha256\": \"32fa5d57cc0f7726b57ce605a03a2d79ee7839dc68d33b01177fc11140452b39\",\n        \"size\": 386974863\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15987_Weather0.tar.gz\": {\n        \"sha256\": \"5ea1aa69132c231c4327105e78b3df83d8fb1ea90b0bfb3444cf3ebc28a6ba2a\",\n        \"size\": 294386082\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15988_Weather1.tar.gz\": {\n        \"sha256\": \"5302ce22af9a731d83e5b4244691ad6d6582a40db17ed6a2cc6f8ec656acb277\",\n        \"size\": 325526615\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15991_Weather3.tar.gz\": {\n        \"sha256\": \"d51c886977eff197a1c91b85203fe9db48601c22cd3f395c8d4d4116c77ba274\",\n        \"size\": 408042960\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15992_Weather5.tar.gz\": {\n        \"sha256\": \"0094c5705adf9d9f9573b0a83f657bf146d4de8441b68e0935d9911bfd4ce923\",\n        \"size\": 241668452\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15993_Weather6.tar.gz\": {\n        \"sha256\": \"a4c172354bfef1fe38f6513073496856e17724553b98c102093f44916432ec8a\",\n        \"size\": 488746856\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15994_Weather7.tar.gz\": {\n        \"sha256\": \"362907eac96aa6ca7282a89650411685aeb34f32e2829e76a0bd4684a31243db\",\n        \"size\": 303519774\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15995_Weather8.tar.gz\": {\n        \"sha256\": \"2cbb3d2c7366ad3f4e6024b15cbb0ac34cffec4bbe3295af059773cf3c0ce64e\",\n        \"size\": 663499364\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15996_Weather9.tar.gz\": {\n        \"sha256\": \"699f010f3b1e51df6b18124d150edc0b25730b88d5bbb42cbfac267cbdddf434\",\n        \"size\": 217916318\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15998_Weather11.tar.gz\": {\n        \"sha256\": \"cfc4ce30ec862c5d4aefddb842b397cede4175e544c7a3737beb3e5508c372e1\",\n        \"size\": 426119425\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route15999_Weather12.tar.gz\": {\n        \"sha256\": \"e7d8a3a5bdf20ec74b639bb4575abb8a1be638c38f793d6f69e99aa44bf78f29\",\n        \"size\": 259040334\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16000_Weather13.tar.gz\": {\n        \"sha256\": \"a06f2201086c3544ff1fe491582b9b5e14c5932c92e09df06c828e15692f4f60\",\n        \"size\": 445224178\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16001_Weather14.tar.gz\": {\n        \"sha256\": \"edbe8b13edd1dcb2863318ce6d693e5ab4bcdf231bcb5c3b97f4aafaaf5f69c7\",\n        \"size\": 266530626\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16002_Weather15.tar.gz\": {\n        \"sha256\": \"4fa669f15948803e724967827a03a9582bb9c502d6bb5f4842fbc4fd6cb5286d\",\n        \"size\": 240102225\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16003_Weather8.tar.gz\": {\n        \"sha256\": \"21fcd8f985ea4dbdd1ecbe843268a980bcdc63115ad8ffe017ed11865a55b069\",\n        \"size\": 339405250\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16004_Weather9.tar.gz\": {\n        \"sha256\": \"c112ee6452d2781238ddcfc5fdb474c1ebb4f9f704065685e6b370b9b3df1981\",\n        \"size\": 281334583\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16005_Weather18.tar.gz\": {\n        \"sha256\": \"252097bc169a429f7738e0423fc6b15b5f4551a389fbf1b40dc56c7263722c3b\",\n        \"size\": 144259441\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16007_Weather20.tar.gz\": {\n        \"sha256\": \"2019ea5d1c0a337972ae29cb784e70d3eae7e362beab0715f082f821ae594a58\",\n        \"size\": 574399174\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16009_Weather22.tar.gz\": {\n        \"sha256\": \"04b4db49efa1875a69e648a3760dbda0112737b9efece8c748fb2938cb926728\",\n        \"size\": 130323430\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16010_Weather23.tar.gz\": {\n        \"sha256\": \"8acba944e993e54da11600c8a01a2b07cb4952060d6708735406a72ae257a07b\",\n        \"size\": 298537916\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16011_Weather23.tar.gz\": {\n        \"sha256\": \"836dda6291a0780fc874cbc3ef26221ed4a089a5931875b58e5bd176bc2e8e94\",\n        \"size\": 143051944\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16012_Weather25.tar.gz\": {\n        \"sha256\": \"3aa4e43fa8b2f178cf64700d8feeccc156d3b02b5a424fedab03d38d798c30f6\",\n        \"size\": 345209428\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16015_Weather2.tar.gz\": {\n        \"sha256\": \"c90476519cee1fba3dba1c74944350ed1f7cc7033f2e3cd9b04a1cb37e761ecc\",\n        \"size\": 181004400\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16016_Weather3.tar.gz\": {\n        \"sha256\": \"a0c513b67539d1c42d02d9b393547ffd0696aad2403302cefa8cc2e867d2d528\",\n        \"size\": 415404494\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16017_Weather3.tar.gz\": {\n        \"sha256\": \"976262c57ebc857cabb39b0a3fd47ff05e0c91e0beacacb999f12e7679915280\",\n        \"size\": 293582623\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16019_Weather6.tar.gz\": {\n        \"sha256\": \"c4e6916a5d414eede4786c61cc880a7856295a6447f00868de420568398206fc\",\n        \"size\": 409377657\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16020_Weather7.tar.gz\": {\n        \"sha256\": \"5edb8980bde994bab6201ecbb359c2a0e9c238818fd2ced9e78fb897a627ad29\",\n        \"size\": 517669010\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16021_Weather8.tar.gz\": {\n        \"sha256\": \"a052e3a25a6a1ddcde6a33aa90f837e634e0372a929ea74f998cf9ba282afc18\",\n        \"size\": 566267319\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16023_Weather10.tar.gz\": {\n        \"sha256\": \"2a018aed99490344d2e596ed1a3d612c28bc63b1af3a436398f8a7728f4fc6e7\",\n        \"size\": 342091303\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16024_Weather11.tar.gz\": {\n        \"sha256\": \"54c49de47be652ed07e5830ad16dc8726ee8d60a3aeb857a02b53fee194c0153\",\n        \"size\": 278760665\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16025_Weather12.tar.gz\": {\n        \"sha256\": \"2c46626ac75474aa6dbd5747defe91b72869b2027456d94c14cfba7e578c1a1b\",\n        \"size\": 707391876\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16026_Weather13.tar.gz\": {\n        \"sha256\": \"98cc7973564b4662a03411451198adb00315512d5c73aab9d2df7bc230522ef5\",\n        \"size\": 133318372\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16027_Weather14.tar.gz\": {\n        \"sha256\": \"2ab2d4fb8a8920575ee22cfe58c7eea756d78dc6682d8318d8233278596acff0\",\n        \"size\": 361091991\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16028_Weather15.tar.gz\": {\n        \"sha256\": \"4ae5d35b0a901ee87e00d4a1e69f3fb9167fbdacb0abdf84a73c450f5145d099\",\n        \"size\": 427889688\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16029_Weather8.tar.gz\": {\n        \"sha256\": \"dd3e31ba78ced096dc57d60bb8dbecfbc694a88140aaf54ddc0f427e0ae80128\",\n        \"size\": 161871139\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16030_Weather9.tar.gz\": {\n        \"sha256\": \"f937c0cc43aeeefdf299fd0cb5161036caeddfce8606fffac08f01308fb64bfc\",\n        \"size\": 184469971\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16031_Weather18.tar.gz\": {\n        \"sha256\": \"776e8936633886da07c8ffd8fbdc911c1e08fa20065fde43a0702fe2a8f9b669\",\n        \"size\": 123638760\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16032_Weather19.tar.gz\": {\n        \"sha256\": \"dcad4546bd98b42e09e91c8fd7a17ef368ec81f81db82fe08a9b1d49e36ecbab\",\n        \"size\": 402947504\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16035_Weather22.tar.gz\": {\n        \"sha256\": \"2587613263f8bd98cc04e08125e70a4b2343d7f45ecb067867f41a0aabadc028\",\n        \"size\": 489474531\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16036_Weather23.tar.gz\": {\n        \"sha256\": \"367cd9051a0747c2c4ae62349f9513f66fe865fdf99255a426065f96901e56fa\",\n        \"size\": 150406834\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16038_Weather25.tar.gz\": {\n        \"sha256\": \"0f4c365589200af9d497c1d69a3f50a641eca73031fd8fd6014baeaac1bf2f5d\",\n        \"size\": 165991788\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16039_Weather0.tar.gz\": {\n        \"sha256\": \"0a5526cd267e9cc5062bcf1e861ca5f6d2f3f252adcc25d7fd36efe0499fad5f\",\n        \"size\": 158242340\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16040_Weather1.tar.gz\": {\n        \"sha256\": \"a525a5120bf8dbe5dd89597ca860dbd549e3d4331b06ef9a95f1e267b3abdcc9\",\n        \"size\": 419213039\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16041_Weather2.tar.gz\": {\n        \"sha256\": \"71f00be74a5dae27b9591cd57798ce2d8f78e81990bf9f421aee1ae6325f683d\",\n        \"size\": 185276413\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16042_Weather3.tar.gz\": {\n        \"sha256\": \"98735fffc13966a59345f57eae141f779d84f7d5f21eccc4e7ab1ae713da046d\",\n        \"size\": 439570721\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16044_Weather5.tar.gz\": {\n        \"sha256\": \"557f6768d7c142762d533a21e12e6d17caba4d734abe8cac17038430e58cc74a\",\n        \"size\": 113791112\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16045_Weather6.tar.gz\": {\n        \"sha256\": \"e3692ed662300231fa9a39c0bceaa76104477305d1772f80783e54a481dde0d0\",\n        \"size\": 528629468\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16046_Weather7.tar.gz\": {\n        \"sha256\": \"f9627301f28d6583b48dc19227733145d62c427a0cd7c4f3c0c940b1ad13ab30\",\n        \"size\": 227161160\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16047_Weather8.tar.gz\": {\n        \"sha256\": \"d748ad5f9376fe1ca39b00067292af276108d3dedbe8daea6adc8feaf22d9818\",\n        \"size\": 139029936\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16050_Weather11.tar.gz\": {\n        \"sha256\": \"1b65011db327cffa33641d269d773500b5014dc45cfb5aa2c0c2dc2ae2161cce\",\n        \"size\": 225918427\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16051_Weather12.tar.gz\": {\n        \"sha256\": \"91e1fcfed8fef65ff3c3c73b52e125feaab633641fff838a5147849c94d361a6\",\n        \"size\": 121082726\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16053_Weather14.tar.gz\": {\n        \"sha256\": \"09c3fb6e5170a1644176e9c2d05f40c96aab8be07de40d37d82d80e114b89f54\",\n        \"size\": 422596800\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16054_Weather15.tar.gz\": {\n        \"sha256\": \"956bcf3919453283d96b37fbe83aa8b5c207f889162f0b3baa67706b1750f226\",\n        \"size\": 116715055\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16055_Weather8.tar.gz\": {\n        \"sha256\": \"16987ad65c071186be0004520130b9aaf5ca749ef737bf4f39bb8e9dbeb30663\",\n        \"size\": 503835669\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16056_Weather9.tar.gz\": {\n        \"sha256\": \"6094ece4778092bbf30dd93d0be55cb6818e01f6cddbc70b0ddb22aeee5e8988\",\n        \"size\": 230789428\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16057_Weather18.tar.gz\": {\n        \"sha256\": \"933e456648be5a40b10216ed634e3aa36988846bc1413b0d727854d2e161e289\",\n        \"size\": 159042389\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16058_Weather19.tar.gz\": {\n        \"sha256\": \"4c195f6b7698f8f348af51c5aae0ef7e81ede0e726a74e411700198fcc065dc9\",\n        \"size\": 353622773\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16060_Weather21.tar.gz\": {\n        \"sha256\": \"21b6465bd8403d9d3a9eebbf2142c73d87a6ca65a59747c55471f7596b9e8228\",\n        \"size\": 684157687\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16062_Weather23.tar.gz\": {\n        \"sha256\": \"12954d55d30863813443f4e69b3424bc5e2bc15be891e7e6cc2bc6eac16a8bb9\",\n        \"size\": 111021351\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16063_Weather23.tar.gz\": {\n        \"sha256\": \"cd224099791d3c8d669bf1b47120da39079d47652f03632041c50d0d82958324\",\n        \"size\": 400641111\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16064_Weather25.tar.gz\": {\n        \"sha256\": \"ba7c3dcac2a0a148da66ca97628fe9e04b6e11c2cd1f16bfc461d3c9342762ff\",\n        \"size\": 314245472\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16065_Weather0.tar.gz\": {\n        \"sha256\": \"b51274c4c7a4df16c2fd91b230d05e5027fba4747b5d66563bf52e206ab5533f\",\n        \"size\": 313585054\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16067_Weather2.tar.gz\": {\n        \"sha256\": \"5bd055a241cea33342f8a737beb04bfd3865a6ea66fc48a8afd6555940378d2b\",\n        \"size\": 360154287\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16068_Weather3.tar.gz\": {\n        \"sha256\": \"ad34a478e28e6f4cb5b87efeb5ad831757b58737fa79c9d651b0f2606b787141\",\n        \"size\": 152324074\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16069_Weather3.tar.gz\": {\n        \"sha256\": \"9103a9eb359c0eda474e5533a007fac4801a432fb88d3c0ca9f0ad434c3d6fc1\",\n        \"size\": 173895390\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16070_Weather5.tar.gz\": {\n        \"sha256\": \"bde0df12026dcdd535a37b533894683763471256bd907887b823c307261afa02\",\n        \"size\": 290870263\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16073_Weather8.tar.gz\": {\n        \"sha256\": \"fd0cc4389d6852af930f050587373c3231de027b03502e4de7ab5441dc1aadea\",\n        \"size\": 276653707\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16074_Weather9.tar.gz\": {\n        \"sha256\": \"efcd9a8f8cfac916a39c42e1a348f9a7f4d1c3de9ce4fc9f4488246068b12d4c\",\n        \"size\": 265453137\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16075_Weather10.tar.gz\": {\n        \"sha256\": \"fee018f0926edaa1db760bb4a7b9d14827bf4c26307a78f19a86df0aacb8e236\",\n        \"size\": 180669418\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16079_Weather14.tar.gz\": {\n        \"sha256\": \"a12a76e7a9549f573c348ee5cabecbe212cff8414b86c640e34e66ed048a2749\",\n        \"size\": 393338750\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16080_Weather15.tar.gz\": {\n        \"sha256\": \"4f10abfbebb48ef52b3321bac6f2f332547a7bf27dc88a2beff1070f50894653\",\n        \"size\": 122554562\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16081_Weather8.tar.gz\": {\n        \"sha256\": \"2457bb88583d5fcbca710cc719882423f8750f80bcffc4fe4c87ce01893aceda\",\n        \"size\": 231550909\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16082_Weather9.tar.gz\": {\n        \"sha256\": \"4b1f5843a3ad962d48e7a495e5cdb4502b382c192a1f8dcd70d75813602cc047\",\n        \"size\": 395877917\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16083_Weather18.tar.gz\": {\n        \"sha256\": \"003d5fe0b64e29586e1e17e9a4e23d57339e6e51339334444fb653d2ef5bcbd3\",\n        \"size\": 651921261\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16084_Weather19.tar.gz\": {\n        \"sha256\": \"011f107984c4d61d14a5566d4c279f65286e2d70a2ae9bdbafaf78f6f18d0731\",\n        \"size\": 631745927\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16089_Weather23.tar.gz\": {\n        \"sha256\": \"bf1a16a91dfbf4c731b9b2f777a8bbdbe993bed60469990f77a3e3b398816d5f\",\n        \"size\": 204182419\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16092_Weather1.tar.gz\": {\n        \"sha256\": \"3aa2f9b9860263fd9508dd025a2c0110b869a69ab693d5768db7cac8cb5b70f6\",\n        \"size\": 137918145\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16094_Weather3.tar.gz\": {\n        \"sha256\": \"3867c1cbe71096c4ae79d8ba49c0a765010bd97fa75fb704fcae88174f7a795c\",\n        \"size\": 343246205\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16095_Weather3.tar.gz\": {\n        \"sha256\": \"d8a88746ba53052b56016d82879858b7112fe2645871f3b45517b272ccc30822\",\n        \"size\": 712531490\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16096_Weather5.tar.gz\": {\n        \"sha256\": \"200b8ab07ae4e32ec4852c6fbceb87670a43ac0101ee5f129e7116a3acd9304d\",\n        \"size\": 508640916\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16097_Weather6.tar.gz\": {\n        \"sha256\": \"30d10c19754b79f08c5a537f2a6a4a4cfd63623aabe384077a27b4b81ede7c0c\",\n        \"size\": 651910376\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16098_Weather7.tar.gz\": {\n        \"sha256\": \"377d17bbffc3305147c102cc7a91d86c2283f14d9469592b4f3ef41838092a5a\",\n        \"size\": 658404886\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16100_Weather9.tar.gz\": {\n        \"sha256\": \"5a2d6b6478b05bed615d684cdd3f82bc62df0be0aa493072cfcc336a366c0c36\",\n        \"size\": 391396761\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16101_Weather10.tar.gz\": {\n        \"sha256\": \"772e73fccf37715fbe51eb749469c489769524d5b91b819e7a7f6215d907e044\",\n        \"size\": 462541378\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16102_Weather11.tar.gz\": {\n        \"sha256\": \"6fb3ed2a640d7b36825c0c4faedd5483139fc6619f35552990c3cee80e1b6539\",\n        \"size\": 330774679\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16104_Weather13.tar.gz\": {\n        \"sha256\": \"fbf1061f15b3773c528449f925c8c841eda594dae2a1110d8bb206752a038437\",\n        \"size\": 445771739\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16105_Weather14.tar.gz\": {\n        \"sha256\": \"eebe1069639deee65748c9d19ce7728a001bb241a5885724ca86f5c6eaafa067\",\n        \"size\": 194398896\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16106_Weather15.tar.gz\": {\n        \"sha256\": \"b6908e184e8907585a924eca365625517dce1fa22f165d90652589e6f584fe32\",\n        \"size\": 250150694\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16107_Weather8.tar.gz\": {\n        \"sha256\": \"bc1e90c83d37b7bde53e57b7b893a0bb1bf100f2a1107913118640493e15c3f0\",\n        \"size\": 443993366\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16108_Weather9.tar.gz\": {\n        \"sha256\": \"590b74fb90083346287b93368b9dee07fe7be5d1d7619f2b4a59525110d710b8\",\n        \"size\": 324824359\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16111_Weather20.tar.gz\": {\n        \"sha256\": \"23645b646b1c4d66063f5cddf892f450d7432d5d4ecf9b411ef9acf1993f1aa7\",\n        \"size\": 357653555\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16113_Weather22.tar.gz\": {\n        \"sha256\": \"001c7e5e3d85c07146de53d77f6777f68536659a9a3196d62837a2571f7281ec\",\n        \"size\": 127241486\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16115_Weather23.tar.gz\": {\n        \"sha256\": \"41e8df486f28c5f7031713b9017f01fa0aca99442856acbcbbe9e36ba64654cc\",\n        \"size\": 454868453\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16117_Weather0.tar.gz\": {\n        \"sha256\": \"d3f2b9ff15305a28564f8b0f455e4c993d5921885830f009c72879d0fa6da8ea\",\n        \"size\": 858825088\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16118_Weather1.tar.gz\": {\n        \"sha256\": \"bd9c0b3dec904562da11b6c19a6995ff02fc653c7190ee1d8da64ad3857a9f16\",\n        \"size\": 601465884\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16120_Weather3.tar.gz\": {\n        \"sha256\": \"c115a57c4c2882e597d6f36067b9aae053b21d2886633fc0e504db72a28437fa\",\n        \"size\": 130997825\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16121_Weather3.tar.gz\": {\n        \"sha256\": \"44e3e4fcdf02a619ece862c22932a5b2947349e8f1fab1870a33480b32383314\",\n        \"size\": 286359388\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16123_Weather6.tar.gz\": {\n        \"sha256\": \"eb16212dc99e4ca2b53f8cdfeb0dd9739bf612b5b4b5bd9ca2be07970d417238\",\n        \"size\": 378961993\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16124_Weather7.tar.gz\": {\n        \"sha256\": \"185951f8d64de598d65bd14a637a45f889cd7b7174c84423e86c3bff468f762c\",\n        \"size\": 279882620\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16126_Weather9.tar.gz\": {\n        \"sha256\": \"3868a35958581b28f946bbad2a9e3b2ac141ab646260ef5f9c7c62feedf10299\",\n        \"size\": 129229398\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16129_Weather12.tar.gz\": {\n        \"sha256\": \"cf1ea8268cbff8c1ec24feea95496f7e9d532d337a57807763591b5af7949874\",\n        \"size\": 125090551\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16130_Weather13.tar.gz\": {\n        \"sha256\": \"5c4a5e4c3bcf53032daacc1d30499c0f143300a8eab051e90173f3b650efeb39\",\n        \"size\": 123875429\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16131_Weather14.tar.gz\": {\n        \"sha256\": \"c1de136aa0a811cf3d169e67bee12f4ff556745d996dc6cb4b0b1b1e752afe16\",\n        \"size\": 216863867\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16132_Weather15.tar.gz\": {\n        \"sha256\": \"9340165f36c5441bfd236874550843003bdabc401ed4eb505556ea1d4d4399e6\",\n        \"size\": 542860998\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16133_Weather8.tar.gz\": {\n        \"sha256\": \"7d191dde79fc47b8ca94db7c3e7e5962bddf1c5eac6ebfc531b6f455edf4a56f\",\n        \"size\": 541582380\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16134_Weather9.tar.gz\": {\n        \"sha256\": \"023cf13f74660fe5636f9578f090b0a37a5b69669ba9add26d2d9546a7dbbd63\",\n        \"size\": 200932084\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16135_Weather18.tar.gz\": {\n        \"sha256\": \"3a02e36662ad73ca690a6d016378f9d4bb0315499ebf821180cebe59f5f22acc\",\n        \"size\": 626172836\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16136_Weather19.tar.gz\": {\n        \"sha256\": \"920c0b8641c53574f0aeb2fcf215a7adccfc70517e46f9418a743272d9243e04\",\n        \"size\": 288581941\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16137_Weather20.tar.gz\": {\n        \"sha256\": \"bb1455f9832d1d6710d5cb29a1bf512308e63841778150bd92377e5c77c63c94\",\n        \"size\": 476024426\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16138_Weather21.tar.gz\": {\n        \"sha256\": \"291dda8ad3639cdf8699ba55c907c5e688cb435b1fe9a66cee6706b026cd31ea\",\n        \"size\": 131671136\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16139_Weather22.tar.gz\": {\n        \"sha256\": \"4bb29c7f307a0b73d99e115cc65885da27e044a63a1f5c663bacde4006bde6e1\",\n        \"size\": 403938412\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16140_Weather23.tar.gz\": {\n        \"sha256\": \"5c98493fea2a34cfca9128e18d396c21dd09ad326d4229a4576324652fffd057\",\n        \"size\": 358800974\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16141_Weather23.tar.gz\": {\n        \"sha256\": \"d85a97ce92e3495dba42c8b97b89bd6a3e8dc461716f08922e4b00c9a5e7572e\",\n        \"size\": 471461871\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16142_Weather25.tar.gz\": {\n        \"sha256\": \"18863e8068f6ac70ad15d1bab1d3350265bcf7a7c5b69334e5276a0b080cca32\",\n        \"size\": 308257269\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16144_Weather1.tar.gz\": {\n        \"sha256\": \"ebbc059e7929463d67b88a8964c2b0ba8c238201b7e9ae3406be1b89fe002c41\",\n        \"size\": 415038066\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16147_Weather3.tar.gz\": {\n        \"sha256\": \"76902e5251d6666d3f6870d1d9b02496976fe3f0564fd1431ed07312d1ca7dc0\",\n        \"size\": 352740416\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16148_Weather5.tar.gz\": {\n        \"sha256\": \"bb4ff3cafd00227ff016aa52582b6fbcebb6f870913a3dfbe255191caddf236d\",\n        \"size\": 303680955\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16149_Weather6.tar.gz\": {\n        \"sha256\": \"faff93d9c3fb3ecac01e2b1dd018097decfbf3c971d825a5f02fc7511f88a9a6\",\n        \"size\": 490533675\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16150_Weather7.tar.gz\": {\n        \"sha256\": \"2217d76a7728b2654356268eded617e9b8de7a3fbd8083622be20206e05ad384\",\n        \"size\": 193687443\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16151_Weather8.tar.gz\": {\n        \"sha256\": \"efdee70b7403c5354c5504ad581aa2bbc6a3ecde3059d2fa6436adc7f144115b\",\n        \"size\": 675754179\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16153_Weather10.tar.gz\": {\n        \"sha256\": \"7e0c6277e428a5b19eb37b01414c3aba5c0fa725fe7ce34b99b716cf8cb94381\",\n        \"size\": 341580344\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16154_Weather11.tar.gz\": {\n        \"sha256\": \"2f6f08d6758f0b0899ff9e0ecc7a31074ea88287d90b114293c547cdd8e9c77c\",\n        \"size\": 268992558\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16155_Weather12.tar.gz\": {\n        \"sha256\": \"e69cdacfd77de2bd2d443eb449051ff437a47aeda37e629532dadb3b1e780401\",\n        \"size\": 290564452\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16156_Weather13.tar.gz\": {\n        \"sha256\": \"ecaf079561807b25fe0509087ff08a94d48d2bfec82646997a4d93218df9d7e6\",\n        \"size\": 295202545\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16157_Weather14.tar.gz\": {\n        \"sha256\": \"360ddc3220a6b159354dc9e75eb8194cb015d2270d264399a98b266aa7db76b1\",\n        \"size\": 751628047\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16158_Weather15.tar.gz\": {\n        \"sha256\": \"27915d994ea58a0af1ec635a36811f1dc4e923628c524638406ee595296b9d90\",\n        \"size\": 141852308\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16159_Weather8.tar.gz\": {\n        \"sha256\": \"e26b8c5759e68254694c8930b5bbbfc28adbb8b0642d239a5e4b9bac81c5c378\",\n        \"size\": 451859619\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16160_Weather9.tar.gz\": {\n        \"sha256\": \"5fce600698673806d83fc5feed128a30c6d89936f17460fbf3d584e2b66173ef\",\n        \"size\": 724624795\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16161_Weather18.tar.gz\": {\n        \"sha256\": \"0cc6b86838bb7a5e267bd294d4c72ea2a23bce8e84228700c03d06afb40722cd\",\n        \"size\": 157655057\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16162_Weather19.tar.gz\": {\n        \"sha256\": \"7cc9e2e45efc660a23d48466a01bd1e20f5b4c1a3b9078ba83370c61358c7d27\",\n        \"size\": 181097835\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16163_Weather20.tar.gz\": {\n        \"sha256\": \"dbc98b943f512ec9a05531a44f4d0d2b5eddd96bdd853732dbb5b061d54906ab\",\n        \"size\": 622134082\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16164_Weather21.tar.gz\": {\n        \"sha256\": \"14ce14dc7b46c5745a66135337e61d210af70bc90300c93d85ece2eaa3cbaff3\",\n        \"size\": 417088458\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16165_Weather22.tar.gz\": {\n        \"sha256\": \"729703e9de0cf95002c9f08a5070352740f2433e5ebfc4908f59489c6e09cb9b\",\n        \"size\": 132629519\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16166_Weather23.tar.gz\": {\n        \"sha256\": \"64846c846540770a741ccde22409414b9750ac2683b29c66fe1d1898bb9d2f98\",\n        \"size\": 357312679\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16167_Weather23.tar.gz\": {\n        \"sha256\": \"7b83af8742626554af681cb1771294e17f88ffdca89984677729ac5513e9bc80\",\n        \"size\": 603968296\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16171_Weather2.tar.gz\": {\n        \"sha256\": \"a8d5d89ad21c517f311f1db96e17d1fb680332de156d348a1cf3dbe742c1b6de\",\n        \"size\": 461463466\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16172_Weather3.tar.gz\": {\n        \"sha256\": \"28a0c9f90490192b9a861cb71e369d5fcc8e31df099aaf6ab938ddc91e09e790\",\n        \"size\": 154250420\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16173_Weather3.tar.gz\": {\n        \"sha256\": \"35de6699eb5de96fb30e8934372d6b7ccfd00ce9ae2b6916635180f4bdf47fcc\",\n        \"size\": 137865573\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16175_Weather6.tar.gz\": {\n        \"sha256\": \"a95f54737cbcd1b64325d97fcdb314974b8e72257c52fa8ff4fdd765607737ba\",\n        \"size\": 526081730\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16176_Weather7.tar.gz\": {\n        \"sha256\": \"942f3089f7e1930d1af6fac50f4226f4b36845d8e56d9487c3ec91df42e8a5ce\",\n        \"size\": 612534804\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16178_Weather9.tar.gz\": {\n        \"sha256\": \"7f3b905d2e633a5057c8efe3421fb1a1d0afb1e55cded5a45fdb0fb65a407b47\",\n        \"size\": 624519507\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16179_Weather10.tar.gz\": {\n        \"sha256\": \"166ecde4c94f49922a5c818af681a410e1ed1d0e37fab8df1c8a7bb26b0e3f92\",\n        \"size\": 282542219\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16181_Weather12.tar.gz\": {\n        \"sha256\": \"e863988960da1e8f63e22158d4615e7e93f1d6292fb3e981b6b2d6d3bde9dc3d\",\n        \"size\": 733974898\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16182_Weather13.tar.gz\": {\n        \"sha256\": \"bf4a3b827c2cd06c3dc2928d519bb1f91d321811763fcfefd0d1ec79e7e152ad\",\n        \"size\": 434769046\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16183_Weather14.tar.gz\": {\n        \"sha256\": \"46ee78dae38d38595a42acff6b32a6e000d462b963c3e7cb88ad5e7d70335213\",\n        \"size\": 367871097\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16185_Weather8.tar.gz\": {\n        \"sha256\": \"3b828860c95a70f030f946412ac042e3e45f202497bb9bd971d628c6d828bdbd\",\n        \"size\": 300140945\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16188_Weather19.tar.gz\": {\n        \"sha256\": \"fdeb5582adb7215fd022c27afdddc17c5d252cd91d185371eccc273eeb471a10\",\n        \"size\": 319916820\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16189_Weather20.tar.gz\": {\n        \"sha256\": \"91bcae762d46f176253508c2536a219deda0ab01e497a26660e6c0a2d61be2a2\",\n        \"size\": 536576476\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16190_Weather21.tar.gz\": {\n        \"sha256\": \"6ddee05f86686ca48d4409b3a28d90c94211369d8af9fad100b8f810b7269424\",\n        \"size\": 148488510\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16191_Weather22.tar.gz\": {\n        \"sha256\": \"8a6e17724324578bdabecb578e125fb20584561e9400d1b215a9917527c974ba\",\n        \"size\": 198516608\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16195_Weather0.tar.gz\": {\n        \"sha256\": \"abde74decf574114202f29972991defcbc6d8c587c2a719a4930c0728109504c\",\n        \"size\": 252800175\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16196_Weather1.tar.gz\": {\n        \"sha256\": \"82de626575de00e8106a61100a5251883cf06b71a83bc0f50f4bf2309f9fa201\",\n        \"size\": 459928282\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16197_Weather2.tar.gz\": {\n        \"sha256\": \"81bf5cbb1ffcb7df2d055fd6e91c5b21ce96750e423003459f35bd26226ddf24\",\n        \"size\": 414246458\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16199_Weather3.tar.gz\": {\n        \"sha256\": \"6c8d9a2655f88bef90fd5147241689b5b80b6dd862ed47a0d94c88ff3b254994\",\n        \"size\": 261012545\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16201_Weather6.tar.gz\": {\n        \"sha256\": \"b3cc6ae52b0c01de232494ecb7d289334856d0a9a1f8e11d13c48d42add9eb3d\",\n        \"size\": 452886055\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16202_Weather7.tar.gz\": {\n        \"sha256\": \"5dbe41d16e377279f3732095000244e0b9d2288c69b71b3b920aad68e6476e76\",\n        \"size\": 344637532\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16203_Weather8.tar.gz\": {\n        \"sha256\": \"eb4a6d471ea67810a3a5a720808cb217b969723ecdfdd20435fd38ca6f81616c\",\n        \"size\": 389527769\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16204_Weather9.tar.gz\": {\n        \"sha256\": \"c26529ca4b679138bec3de90b10c23e014bb00064f0c8bcaf5e9fa64b2595dc8\",\n        \"size\": 119225187\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16205_Weather10.tar.gz\": {\n        \"sha256\": \"b70ee43dfd473c7b6ce1d7e1ecc27ac0cd4ea2c387d9295b2236792aa15dfbb7\",\n        \"size\": 481458021\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16208_Weather13.tar.gz\": {\n        \"sha256\": \"ddd8bbd29dabb7eefb48c506c7ccf169a784a49d0edb2139bbcbafd88a5097fe\",\n        \"size\": 450932930\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16209_Weather14.tar.gz\": {\n        \"sha256\": \"03542098a2cbef70d71919d2cd8e141d264d0dfde58f5cc824533554d6e9b7d8\",\n        \"size\": 286012265\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16210_Weather15.tar.gz\": {\n        \"sha256\": \"1abad59638bce287fb03fc51ab358ce9385fb741713f90884cc8ba0a9d9f51fc\",\n        \"size\": 180457794\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16211_Weather8.tar.gz\": {\n        \"sha256\": \"ac4047e924aee49eae892a513b246a089030302841649d9180c54abaa347a10c\",\n        \"size\": 473233805\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16212_Weather9.tar.gz\": {\n        \"sha256\": \"2d42f8574278810c9293fad8a53c6b1c8e2145f33a5f4e2c653a6bbd85145bb7\",\n        \"size\": 294038450\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16213_Weather18.tar.gz\": {\n        \"sha256\": \"4dc15f1c459e95647de8363664ceaf8be4a05344a836633db7ff774cc5ef2421\",\n        \"size\": 396701943\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16214_Weather19.tar.gz\": {\n        \"sha256\": \"036d88c1695433a057958af10e564aca30a7333b7f95324024e2c3b53403015d\",\n        \"size\": 268799209\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16215_Weather20.tar.gz\": {\n        \"sha256\": \"d05ec760975b2c0833371d5e2c23839dd7adf6e89dd2063c8638b77beb7105e8\",\n        \"size\": 190938962\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16216_Weather21.tar.gz\": {\n        \"sha256\": \"740cb6e69757960148fcf1c16617789e1c9bca05a957d21d181254acca415198\",\n        \"size\": 261066119\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16220_Weather25.tar.gz\": {\n        \"sha256\": \"01b990b7ecaaee69b041a0586d0c88f0045cf88b44304d685d8eb822be465425\",\n        \"size\": 370454288\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16221_Weather0.tar.gz\": {\n        \"sha256\": \"416f7e5e558d938674d191941223ce11ebd3d963abd6cc025f861a05d5cdda24\",\n        \"size\": 475353890\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16222_Weather1.tar.gz\": {\n        \"sha256\": \"d8e74176777353adab1a7df52384671544421d5daf3152b67f573b5c1f21b913\",\n        \"size\": 1089174629\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16225_Weather3.tar.gz\": {\n        \"sha256\": \"7230277bddff3d0dd0ac1336422420bb224a32e6a6d41c15de67bf314e095ef5\",\n        \"size\": 228816373\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16226_Weather5.tar.gz\": {\n        \"sha256\": \"f7b8e1fc1e8f36f984193fea16286e2a55179efe7f743125fb2a202786247f7f\",\n        \"size\": 137874547\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16227_Weather6.tar.gz\": {\n        \"sha256\": \"4e48b0764059126ee416f1798486e27d097976598fe3799e301772bc462d9980\",\n        \"size\": 635135691\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16228_Weather7.tar.gz\": {\n        \"sha256\": \"ba922cfbde07aa7b7ba9154184397ae3461e665706abc0b2e74680f48e57d6f6\",\n        \"size\": 512152109\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16229_Weather8.tar.gz\": {\n        \"sha256\": \"a8c9812faf6f2294acdce3fc691e862344dc0546659eafb37fadcc368df133c9\",\n        \"size\": 264962622\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16230_Weather9.tar.gz\": {\n        \"sha256\": \"386989b8bcefd041081d4bb1fecaa9e8a3e5387137b1f5d6bc75b8f1d96b543f\",\n        \"size\": 347307498\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16231_Weather10.tar.gz\": {\n        \"sha256\": \"0a673f30d4878f7f7ef5045ba7fc46644800b095c9bb85a44ce341ca99d5f7bf\",\n        \"size\": 142235628\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16232_Weather11.tar.gz\": {\n        \"sha256\": \"8e7d930c5e1eda4d3810f2e1414536827c0e6eb3e5772df3de747a9864d4ad64\",\n        \"size\": 178946396\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16235_Weather14.tar.gz\": {\n        \"sha256\": \"af5a9c001587de2518479c9eb785ac46b8dbf0d64a676329daf16e5fed494721\",\n        \"size\": 402809761\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16237_Weather8.tar.gz\": {\n        \"sha256\": \"7ec5e91d49acdf88c0401a8e26ea93e8a201ef5d809529b1630e70437f2f4704\",\n        \"size\": 233523742\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16238_Weather9.tar.gz\": {\n        \"sha256\": \"89fca193e1091ee4d0022f40676eaed8e65d3a4980eb68ee138a456984cd9c7a\",\n        \"size\": 92688868\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16239_Weather18.tar.gz\": {\n        \"sha256\": \"0ee99796dd43db051d62b5bd7fc5befc142630131819242a01112746a21c282f\",\n        \"size\": 251780310\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16240_Weather19.tar.gz\": {\n        \"sha256\": \"8165ff7b30b7c17984f6bce1edb0e09016550e4b224a44e1753a9bd7063a67a1\",\n        \"size\": 628943531\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16241_Weather20.tar.gz\": {\n        \"sha256\": \"0a9a61b5907c8ccb477b881b0e6eb82ac45620a727d3496059cebaea2a2d0874\",\n        \"size\": 405590367\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16242_Weather21.tar.gz\": {\n        \"sha256\": \"c5717f42560d6895731591dda40c65b0ca63ced596b9522c1543196f3491cda4\",\n        \"size\": 338026739\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16246_Weather25.tar.gz\": {\n        \"sha256\": \"5440652083527fdf5632a034b1200878d9ae0c70d3a0273ef9fc0d7019d917b3\",\n        \"size\": 467010912\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16247_Weather0.tar.gz\": {\n        \"sha256\": \"41de8c763c41deb821a476360edfb54f0ab965e52bf8d117ac0018bab2434604\",\n        \"size\": 283313525\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16248_Weather1.tar.gz\": {\n        \"sha256\": \"04e184952d22bf0c6fcc497335fb9482f46fa9f5b380f4aecacfbdd6f0249f5e\",\n        \"size\": 429762758\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16249_Weather2.tar.gz\": {\n        \"sha256\": \"c5c928014d9fcdcaac12dd85f317adb823a11e5bf62e388e7807be8b49468d96\",\n        \"size\": 447820793\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16250_Weather3.tar.gz\": {\n        \"sha256\": \"e37929c552be219c18896ad82f138a3b3f8f95a7d3bc3f3c6e885626a6e9fb4e\",\n        \"size\": 205493199\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16251_Weather3.tar.gz\": {\n        \"sha256\": \"57d82ca21052f2975d6fb42fa833ce8f04028947f61c6d73e632b90d454e4590\",\n        \"size\": 150338384\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16253_Weather6.tar.gz\": {\n        \"sha256\": \"b257f54de202d080eba75b027d3a6fe6316e835dd08fd03160822670ba2460e8\",\n        \"size\": 366377486\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16254_Weather7.tar.gz\": {\n        \"sha256\": \"b265428074cb31b156b79541bcb68a680f6767f007189a4de68644598158e57a\",\n        \"size\": 187584777\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16256_Weather9.tar.gz\": {\n        \"sha256\": \"17bb5a09bc3606870be78c13e34c8aacac546813abeb8e54e5c5a1d70fb2569e\",\n        \"size\": 327170184\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16257_Weather10.tar.gz\": {\n        \"sha256\": \"282f0b37927d8caa5270f7d22cc0da10035f28d96d672764fe62743c855e920a\",\n        \"size\": 154295756\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16258_Weather11.tar.gz\": {\n        \"sha256\": \"04c1e884c6b50cf0ca6da90818f9c1256b78b5a3c62c1271526a6a738cf502ed\",\n        \"size\": 197279804\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16259_Weather12.tar.gz\": {\n        \"sha256\": \"185bcd32d8785c975e4757cb6a4d52a6c5c0be3fbed437b2110fe45dc498a61f\",\n        \"size\": 125104108\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16260_Weather13.tar.gz\": {\n        \"sha256\": \"2d0e153642ee81064e907852f9fbef44d3d997b4d4d30fe2a1e831f5c2cef0c8\",\n        \"size\": 344975854\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16262_Weather15.tar.gz\": {\n        \"sha256\": \"ece2721e43310d0922d360a1085fc78b64cd12746bb64808bd7c9c906e07ec52\",\n        \"size\": 503321543\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16263_Weather8.tar.gz\": {\n        \"sha256\": \"0d3f5310741f9337b6ae42e9ebfd5a7b081a3a4e9225c49b9ef90939e50266f1\",\n        \"size\": 398974883\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16265_Weather18.tar.gz\": {\n        \"sha256\": \"155e7a420999834e51fa85fcaad5b0c3ced68811d7de38fc92c05a5448ba1161\",\n        \"size\": 178846573\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16266_Weather19.tar.gz\": {\n        \"sha256\": \"edf05a7514566898f9487cd6f2c52547b24a940d14bb536d2134c5d040c2efd4\",\n        \"size\": 385474350\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16267_Weather20.tar.gz\": {\n        \"sha256\": \"0ef574b36a7d130cb54c973dd5715d0a56a0d85e98d0a963ee776b26d9442df8\",\n        \"size\": 433491935\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16268_Weather21.tar.gz\": {\n        \"sha256\": \"a18be6e59f0b969edc8d3a7d17bde2d198624d111a02c950480d5f865d1e946c\",\n        \"size\": 421101517\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16269_Weather22.tar.gz\": {\n        \"sha256\": \"644a63fbf819834f76659ec28fa8c0010271eb9852c636165502193949f67b5a\",\n        \"size\": 457440403\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16271_Weather23.tar.gz\": {\n        \"sha256\": \"e8cbfe6595d48838ddc45c59bd977fe97c24232914bc9927bea04ccfcc878a1d\",\n        \"size\": 226294152\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16272_Weather25.tar.gz\": {\n        \"sha256\": \"bcfa085372497ffd9be2eec09e3ec349f2937385b5ea181bde583cf25403a5e5\",\n        \"size\": 293582807\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16273_Weather0.tar.gz\": {\n        \"sha256\": \"6b9d181e9905bea26ff9fbc4832ac0ee52120032ad6c06ab39379ab35c0b838d\",\n        \"size\": 407997256\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16275_Weather2.tar.gz\": {\n        \"sha256\": \"4926dfdd33ed87a8b76fd9b30a58be99b654637784f82931400415aca8c3553a\",\n        \"size\": 425966082\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16276_Weather3.tar.gz\": {\n        \"sha256\": \"cd5886da4cec7f7e704e7e25f769aebf297fafbf289c0df199078a87d97bcd48\",\n        \"size\": 566950972\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16277_Weather3.tar.gz\": {\n        \"sha256\": \"f9a7503b391c5df53b94ada8a0342e12b8360be371da9b206a35461e04e9d375\",\n        \"size\": 222393071\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16278_Weather5.tar.gz\": {\n        \"sha256\": \"2b1237db1466a97981d6ac83c0702b7b8636efa4e25ab2ff7dc13002323d0efd\",\n        \"size\": 447469277\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16279_Weather6.tar.gz\": {\n        \"sha256\": \"8f3e1fa1f60a477ec5cd716e5d2cabf1a79544070384964ac1522118a32a2c64\",\n        \"size\": 185567990\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16280_Weather7.tar.gz\": {\n        \"sha256\": \"eccc033208e401e2b8218c82e811334ae838a19dd75c4cfaefeb48938c7db471\",\n        \"size\": 156190818\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16281_Weather8.tar.gz\": {\n        \"sha256\": \"513bf7b4351794378168513d32480f216f2dab29322ff4b711c161b55842dfe0\",\n        \"size\": 556516909\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16282_Weather9.tar.gz\": {\n        \"sha256\": \"b9a3c9b9146b687725dc7bf062399da8210ce25afb6d74bf2294ada9dd8d7e3b\",\n        \"size\": 317346817\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16283_Weather10.tar.gz\": {\n        \"sha256\": \"3b63dfacf01c32ad84909e6c93d2c89c0f090c18addd8ecc214684870acb6527\",\n        \"size\": 254345721\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16287_Weather14.tar.gz\": {\n        \"sha256\": \"14e1fbc651bb3595be699f7bf7d273c7dee832c4cf2255c4cd0d581efb2612c2\",\n        \"size\": 575034268\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16288_Weather15.tar.gz\": {\n        \"sha256\": \"edf1c756b19b75625034b4f369d0f2d24ebd706480b576b86f7b4a0c2ae895b5\",\n        \"size\": 470793817\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16289_Weather8.tar.gz\": {\n        \"sha256\": \"6cd0f8fd35f6abb98229ae24d45c20c620690dce70e2b0979c487cf88a340d67\",\n        \"size\": 200444844\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16290_Weather9.tar.gz\": {\n        \"sha256\": \"834b3fcb1f394c0d4b7f10dd51a3763eab42ab3f2b6e4ebde4a1aca60c5b1ab3\",\n        \"size\": 142657925\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16291_Weather18.tar.gz\": {\n        \"sha256\": \"6a280e1d1e6035c3a60d55fa0549d66c2e75fd79495b7e5625f7f1f55cf5c9be\",\n        \"size\": 526926828\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16292_Weather19.tar.gz\": {\n        \"sha256\": \"ae9bd62bbc36d1715030e5f56c7f16c3290850bfe13a6100dc9321cd64c1446b\",\n        \"size\": 368016483\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16293_Weather20.tar.gz\": {\n        \"sha256\": \"8d2cd30539c4453fa5fff3f3ba63990c8049af5147f46d2840d88b690027c6f6\",\n        \"size\": 156135475\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16294_Weather21.tar.gz\": {\n        \"sha256\": \"37ccf25e608e060b56eb1e9979cc63bc0cbbeeabeb50b5ac323eeb9b80acfd1b\",\n        \"size\": 150480351\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16295_Weather22.tar.gz\": {\n        \"sha256\": \"64c555e7c0495f4553f3c6e526f639cf13f55d4f07ad9a550a57cec3f3bb21b6\",\n        \"size\": 241108932\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16296_Weather23.tar.gz\": {\n        \"sha256\": \"15114172219df79937a27e0425d2d006c700ff923de0e314e4ac8cc698427bc7\",\n        \"size\": 177614298\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16300_Weather1.tar.gz\": {\n        \"sha256\": \"8a6c979a6e6f9eff79408bd3879d6933a5a1355f8a638953db36829b0632209d\",\n        \"size\": 397058568\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16301_Weather2.tar.gz\": {\n        \"sha256\": \"f3ebfa596460d801c91d212117ef2af23b165c04c8af401dc41583e6c0845060\",\n        \"size\": 340846167\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16302_Weather3.tar.gz\": {\n        \"sha256\": \"1fa3786a68d017897bdaef56459accb7e197552f29afd258868ba9197be644bb\",\n        \"size\": 156963347\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16303_Weather3.tar.gz\": {\n        \"sha256\": \"368b8cc4400cbf11d5c9dfd17db1ac0429a2cc3a3b3c68d1972d6b1587a43fb5\",\n        \"size\": 430325090\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16304_Weather5.tar.gz\": {\n        \"sha256\": \"77dfaf1b833d2ec0b7314385f057d10d4331cc699a28b41a6d1607a17f0de670\",\n        \"size\": 343063637\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16306_Weather7.tar.gz\": {\n        \"sha256\": \"32aeb8642eb67a369fb05230cf14ed4b469f99922307f8a4f5d7231ade88681f\",\n        \"size\": 552740722\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16307_Weather8.tar.gz\": {\n        \"sha256\": \"e910c0cab94426f1ced3ea0039f8bfc065d7f2e6245ca51fd97e0c3de47daeb5\",\n        \"size\": 208887148\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16309_Weather10.tar.gz\": {\n        \"sha256\": \"8b65926fbcb8fab5da4d714f69738a24017365e54a9f71469317b9dd9c7fe7c3\",\n        \"size\": 351232368\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16310_Weather11.tar.gz\": {\n        \"sha256\": \"474e219d72c962d3b6b6d4c859aacb6b4e2ed8310f714493a292ede691b28563\",\n        \"size\": 405524383\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16311_Weather12.tar.gz\": {\n        \"sha256\": \"74f451ff2628c033db446c647c1bd32aab3572956c511d14996e107f2596e955\",\n        \"size\": 91344938\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16313_Weather14.tar.gz\": {\n        \"sha256\": \"b879c352f10a4e250c6bd5b9b3513953a2a54f14397d49a1b16a6a3cb72f80d8\",\n        \"size\": 472864995\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16314_Weather15.tar.gz\": {\n        \"sha256\": \"fa3bb91cd3bbb8ef3edd43ca3d7268294ebae93f29621e70ff1b72cd703378f0\",\n        \"size\": 238512790\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16316_Weather9.tar.gz\": {\n        \"sha256\": \"1a08d05e6d6db8b07609e459ccd6db0297cb8fc6c76489e562a7bce6164a8176\",\n        \"size\": 411293367\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16317_Weather18.tar.gz\": {\n        \"sha256\": \"eccb1a0b572ec0eddd9f8410aea728b9dbc41256691d5f23af8502933181e6d3\",\n        \"size\": 243568755\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16318_Weather19.tar.gz\": {\n        \"sha256\": \"2b3603676119f4e6b62a8ef9da928422702c57c5753e837d9e5fd4223e6c795c\",\n        \"size\": 226407410\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16319_Weather20.tar.gz\": {\n        \"sha256\": \"2069495a8f1668392b5a577cc94c89eebf0eb637f44fd5adcd64756ede943145\",\n        \"size\": 239008819\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16320_Weather21.tar.gz\": {\n        \"sha256\": \"d7b9c94a919cd843d92309492b5b705a2b89f2efde31983e4343ed1b0b7b2a1d\",\n        \"size\": 259633566\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16322_Weather23.tar.gz\": {\n        \"sha256\": \"606409d44f6614dda914ae5a9dcd76267ff853d6d378b650e0469ccd5df9ead4\",\n        \"size\": 294746296\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16323_Weather23.tar.gz\": {\n        \"sha256\": \"29f8ae36053988fe4a7143d2f4f841da0c34e660f1cb4bfc6c1c0a1ef48a49da\",\n        \"size\": 328666744\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16326_Weather1.tar.gz\": {\n        \"sha256\": \"1421935859e2a1977859615e07502b1bdf1090da5c39b93430bfc7ba04e2afaa\",\n        \"size\": 254701385\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16328_Weather3.tar.gz\": {\n        \"sha256\": \"c58ac9b5d4c2bd01082de0466d4eba20b006383687069aae33687d18bc3013b6\",\n        \"size\": 701427472\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16329_Weather3.tar.gz\": {\n        \"sha256\": \"e89ff0a245707d4ddbead0e4b2ea134916398b45d573ff47079b26bdbb635db9\",\n        \"size\": 141512936\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16330_Weather5.tar.gz\": {\n        \"sha256\": \"2c3e26be24368715159bedfb3913f458f7b3cbf0b221626434804e1968437462\",\n        \"size\": 479899727\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16331_Weather6.tar.gz\": {\n        \"sha256\": \"2c474f3425f62d4a8f4f24d99604558f5258e178a4e19842fba16209dac7f07a\",\n        \"size\": 157754587\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16332_Weather7.tar.gz\": {\n        \"sha256\": \"aba2d51b4e49c7a4673824fe76f3838550f320161661b786e0ec9ec2c9c9bf24\",\n        \"size\": 526342214\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16333_Weather8.tar.gz\": {\n        \"sha256\": \"cb24dcc540485fce8dd0bf694579b9b5f84b3457bd4c632e74ea756083908710\",\n        \"size\": 131765011\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16334_Weather9.tar.gz\": {\n        \"sha256\": \"c8fd6b49a03c6f7f6a5db85fc4bedd02ead25f477f2a8f76b12089b8347e9131\",\n        \"size\": 421948673\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16335_Weather10.tar.gz\": {\n        \"sha256\": \"64671e173e2b1c376c5f932ef424ab676150b57b96fc63568a09ff5e7fc32fad\",\n        \"size\": 813631475\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16337_Weather12.tar.gz\": {\n        \"sha256\": \"dc6077afc5bcf39d958f2986574b2376b0b25f7ff1023bb64062c41c5297449f\",\n        \"size\": 598353708\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16339_Weather14.tar.gz\": {\n        \"sha256\": \"97a254b9a34024115737fde61c4f26332e975bbfc147e6006043ae6b8729ca72\",\n        \"size\": 263025901\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16340_Weather15.tar.gz\": {\n        \"sha256\": \"4cd9ee977babd77e67d3686cab6fa64f543aa92987935d67b0adbeab13484ea0\",\n        \"size\": 300149452\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16341_Weather8.tar.gz\": {\n        \"sha256\": \"c46bc89acdb5fc0fbf7d355eac0f9ac738da4e8f1fd3d50852c52f7106f3d030\",\n        \"size\": 218674963\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16342_Weather9.tar.gz\": {\n        \"sha256\": \"053e9bb2dd24494b10da2d00dfefdf0d8c3247510725d48de66a4249ea1cdb4c\",\n        \"size\": 451373424\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16343_Weather18.tar.gz\": {\n        \"sha256\": \"fd92e23a62746be52262417df733cf53df76adf00e493ba490aa43d73afb5fee\",\n        \"size\": 518322780\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16344_Weather19.tar.gz\": {\n        \"sha256\": \"13dbc9064cf042fce02f9dfccf35a80fc22651a36923511ec3e59b23df2cf995\",\n        \"size\": 605882692\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16346_Weather21.tar.gz\": {\n        \"sha256\": \"f2938102625b92ac57151267acde14b524ffa76ebc4370bad6ebfa90e638ecdb\",\n        \"size\": 182169793\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16348_Weather23.tar.gz\": {\n        \"sha256\": \"66e0fb6d9c905f5edc200b97cd3070a9a1cdfef1fb63c7622c33ab44ad28d528\",\n        \"size\": 412561310\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16349_Weather23.tar.gz\": {\n        \"sha256\": \"27325696d59905764b314a468d1baba7ef78e762510f128e4554397370db2671\",\n        \"size\": 231054342\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16350_Weather25.tar.gz\": {\n        \"sha256\": \"a8a520b5fdc073fca9c00e7881f0fa0a5e39e9fba5a45a33dd5bc74ad10e7d17\",\n        \"size\": 333757145\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16351_Weather0.tar.gz\": {\n        \"sha256\": \"02af4eb02130072245da84f49c9bb5a9df1ff35fb75f3dfbbf9628e9a5435b1b\",\n        \"size\": 329550882\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16352_Weather1.tar.gz\": {\n        \"sha256\": \"2c09434a83e532ed63279febd48d3bd1c18620c15c3f1530438e82a41599b852\",\n        \"size\": 135581402\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16353_Weather2.tar.gz\": {\n        \"sha256\": \"1540ce4f9ba3fc6deb1fc27685839ad4c66d2cce05f759d80b5552d312b2b8cc\",\n        \"size\": 521293164\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16354_Weather3.tar.gz\": {\n        \"sha256\": \"410db4b0f331c04d647d781f949298acf02b507b316af6fcae009c6607b822d3\",\n        \"size\": 630184919\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16356_Weather5.tar.gz\": {\n        \"sha256\": \"c9c9b803f35d6f4dfbd657b75591250ba664a293c9be38d843988680a9252bbe\",\n        \"size\": 256456648\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16357_Weather6.tar.gz\": {\n        \"sha256\": \"9942a0db2028d9a90643d4c4cf7702845d34eac81cf5f198c15bd9681f2c89f2\",\n        \"size\": 549540346\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16358_Weather7.tar.gz\": {\n        \"sha256\": \"11a8b7db7cde5b19bc0b503ec9714c5136417a16fcfb863aebbee42135af5233\",\n        \"size\": 144004645\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16359_Weather8.tar.gz\": {\n        \"sha256\": \"236b3beac84d0a270da4a60778db439e33cdd8e0a1e0b6a7c11e8b50d893217c\",\n        \"size\": 454837534\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16360_Weather9.tar.gz\": {\n        \"sha256\": \"1111e55f06d6b55316d84cebd19c663c1874ea43505e9138c9a8a0579469f0ef\",\n        \"size\": 131140531\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16361_Weather10.tar.gz\": {\n        \"sha256\": \"237838f3328e6e35edbb6829ffa76c66e44d8985017985fdf9382640ad49b1af\",\n        \"size\": 272527213\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16362_Weather11.tar.gz\": {\n        \"sha256\": \"68999d43e3b5d6fb039e5fe8431b24d43e319a22bad4d6148898b8d2a64c321b\",\n        \"size\": 282846194\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16363_Weather12.tar.gz\": {\n        \"sha256\": \"f9c160a4f38fa84aa77da06c515bad86e2dcb0c3fbcc5eca8825049562833bef\",\n        \"size\": 242804814\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16364_Weather13.tar.gz\": {\n        \"sha256\": \"01be767d73839ac2f4ff2f9cab26e0d9369700c82c8b2be42206386b62b5dccd\",\n        \"size\": 480090512\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16365_Weather14.tar.gz\": {\n        \"sha256\": \"241a587808296267fba360ab3e5c09234853e19a1c5546eddddef180208ed817\",\n        \"size\": 202791962\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16368_Weather9.tar.gz\": {\n        \"sha256\": \"8b802f52e47fc0500dd804ffbf7cfb8b7277709716958baf6dd728f89e1de11e\",\n        \"size\": 205824204\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16370_Weather19.tar.gz\": {\n        \"sha256\": \"5991ac40741014323dc212234614faf62a26aacdc480be3fbc766f79b45f8f55\",\n        \"size\": 665303083\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16371_Weather20.tar.gz\": {\n        \"sha256\": \"f8686cd20e56d9f747ae9c0887cf232cca3b120b31939f1d2e0fbf297e7aba04\",\n        \"size\": 404605917\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16372_Weather21.tar.gz\": {\n        \"sha256\": \"a60281084672eb5fcb53b2c434915902c3325dcf9b18340b63db6e307592e46f\",\n        \"size\": 294430141\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16373_Weather22.tar.gz\": {\n        \"sha256\": \"b4ca8a44bee046d53ce2a5617bb01f866a4012b39aede5e6270a245cb56f3106\",\n        \"size\": 278205682\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16374_Weather23.tar.gz\": {\n        \"sha256\": \"a52f76b835dbea29aea60427da8bbfdbe2723c664fbfaa11b2a3819c9fcaede3\",\n        \"size\": 317001593\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16375_Weather23.tar.gz\": {\n        \"sha256\": \"e6ec5d14afd7a84bb0a3c242a04fcd95f88e049ddbe7baa1dd4266d7e24a4581\",\n        \"size\": 199140500\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16377_Weather0.tar.gz\": {\n        \"sha256\": \"1c44af0270aa1674ebd3f3666724d20bd9a691418739b4f51183c8c9935d9728\",\n        \"size\": 510730789\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16378_Weather1.tar.gz\": {\n        \"sha256\": \"341207119b8f86003863e56d353ca2dee937ccedb0e4b71c9106d910569f1568\",\n        \"size\": 228507782\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16379_Weather2.tar.gz\": {\n        \"sha256\": \"f6798c7587a1cbc2c292411f97b1b1b29326211e90aa2b9232f120795ba10c8e\",\n        \"size\": 131912046\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16380_Weather3.tar.gz\": {\n        \"sha256\": \"005a95d75016c426e057b08495c6de2c1b4008226d4c7c995fb69751352b89b4\",\n        \"size\": 404511504\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16381_Weather3.tar.gz\": {\n        \"sha256\": \"0b206f1616e4eb715ae7749300ef17798f959e711327d9da91e9eb172dbf1f85\",\n        \"size\": 276201766\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16383_Weather6.tar.gz\": {\n        \"sha256\": \"622d05a52651c382c22085b39ce17ad24f0636389f5664ff605ee62c28d4d035\",\n        \"size\": 423150236\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16384_Weather7.tar.gz\": {\n        \"sha256\": \"024d7fb776c1d645dd199a561d6614be4d9a411e01c04f313d73d35fb1d688b1\",\n        \"size\": 363447158\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16385_Weather8.tar.gz\": {\n        \"sha256\": \"d26fe27da7a63bafe5be7d2dffa88c5d17ad7751b142a08ef632c7757c906f64\",\n        \"size\": 362574686\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16386_Weather9.tar.gz\": {\n        \"sha256\": \"957897246c0027d23fb3255c47ddd461fcaa3041dc1736bad9eb0599a1519abe\",\n        \"size\": 188081343\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16387_Weather10.tar.gz\": {\n        \"sha256\": \"a81fbc46f9614e46b304845a8f5018f9e3b67fd70d3fcc2081d21ab1ef5e4ee7\",\n        \"size\": 340665340\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16390_Weather13.tar.gz\": {\n        \"sha256\": \"d442e44460c4b932a9e49ab9d96b51bf5294324bdf80d1733a9c747177a0e62a\",\n        \"size\": 117646173\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16391_Weather14.tar.gz\": {\n        \"sha256\": \"7e9a6a3544f74e8216afba0352f9610324d27747c98b4e511b528c53b196a61b\",\n        \"size\": 250489746\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16392_Weather15.tar.gz\": {\n        \"sha256\": \"2d09fef3e21dc97db6eadb07c11eca06809d234c49ba19043546f093704054bb\",\n        \"size\": 203029369\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16393_Weather8.tar.gz\": {\n        \"sha256\": \"54b314bd336899b09f556535bb0e8545db9d9d57e89137ba665d3c492dd9de52\",\n        \"size\": 451602377\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16394_Weather9.tar.gz\": {\n        \"sha256\": \"74b434200c961ddce2911b93999161cb0d0f57c081894445a9c41e4374ace3e8\",\n        \"size\": 363289387\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16397_Weather20.tar.gz\": {\n        \"sha256\": \"50b31fa8554ee3f9c6fa97002f5e4a8c6fb8f8d6bf3fe291ad72fd0b9306df55\",\n        \"size\": 564660261\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16398_Weather21.tar.gz\": {\n        \"sha256\": \"1570b6ffaeb875d7b97cee3999182ec7287bed2454978f83d1278b6fe87ad8ac\",\n        \"size\": 453451496\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16405_Weather2.tar.gz\": {\n        \"sha256\": \"00db93b7be54a7fbbaf71b11bfe45884a1c5451b3e4393e5867f6fcaff29df9d\",\n        \"size\": 791125077\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16406_Weather3.tar.gz\": {\n        \"sha256\": \"b064d47641326b37a99626c046de7851b17680f41e69e0f5fe6359852cf0204a\",\n        \"size\": 494001357\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16407_Weather3.tar.gz\": {\n        \"sha256\": \"1af5e96bd8d97cab0e6e524cc9043aebfdffd184b494b76db74514c3fc699769\",\n        \"size\": 608241573\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16409_Weather6.tar.gz\": {\n        \"sha256\": \"4cc580526decfa1041935366c615611cef444894e4467bbf4e61b8df0b8cc6d5\",\n        \"size\": 550687079\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16410_Weather7.tar.gz\": {\n        \"sha256\": \"f5d1e15c08d17dac8b45b2c486ac24ef8969690137bfbbce433c8d8f9166ce22\",\n        \"size\": 214827067\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16411_Weather8.tar.gz\": {\n        \"sha256\": \"8d003be9892af5f427b70d032a2b5031b1df50cfa47d9744fde16b16b2b131ee\",\n        \"size\": 596892981\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16414_Weather11.tar.gz\": {\n        \"sha256\": \"01288376a499f68cce788e7b0b730c14c0dca83040f20538620e269ac5fa135a\",\n        \"size\": 588766872\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16416_Weather13.tar.gz\": {\n        \"sha256\": \"70a25dd1d3e0dc9a04942e388c6a9adb1b682d4d01929158a35995d6a27deed1\",\n        \"size\": 228809382\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16417_Weather14.tar.gz\": {\n        \"sha256\": \"8d38388957d4f99e9bc3a7f1ceb059b23ac9cccf738d54b4699abe211e787c16\",\n        \"size\": 431762742\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16418_Weather15.tar.gz\": {\n        \"sha256\": \"384c082dac0ef24c90198adb3c0d2e88924cbb8dd8b2c8089cfe6b6a533559b3\",\n        \"size\": 499943085\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16420_Weather9.tar.gz\": {\n        \"sha256\": \"9d7e05d205e8d14f1208c55789127fda3db056d0a18703b35a42cc12d5384488\",\n        \"size\": 465831564\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16421_Weather18.tar.gz\": {\n        \"sha256\": \"d6a063e35f2466a6d6eb0dfa950f1ad41a309551de57fad1c4af762c2ebfe8df\",\n        \"size\": 255406457\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16422_Weather19.tar.gz\": {\n        \"sha256\": \"e0135c4e0bbed55a2d140bf13f1c09d9b9fc0af90bdba9019c14a54c5d0887ba\",\n        \"size\": 168969697\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16423_Weather20.tar.gz\": {\n        \"sha256\": \"e5c51ed648813f1cbfc4ca08a81990bbc768c2ecbbe07ff98fda2c6838c16e36\",\n        \"size\": 478459774\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16424_Weather21.tar.gz\": {\n        \"sha256\": \"ee879f21fa91a58617fbb1856b55b7f06a9f321094962473f9c998ad60b25b77\",\n        \"size\": 170598978\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16427_Weather23.tar.gz\": {\n        \"sha256\": \"85cc36d8c79a5638b577655f14ab19dc9313cffec8596474d1085aff892f173e\",\n        \"size\": 481925138\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16428_Weather25.tar.gz\": {\n        \"sha256\": \"6524030e1328b283c6828d84e0de22141e7d4d3638a602548eb9856b6d939e0f\",\n        \"size\": 555865087\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16430_Weather1.tar.gz\": {\n        \"sha256\": \"2fbab514bd778a5f1da2706e41d18c85c15ca7efbadbd1ff0f2c1a500cb3a56c\",\n        \"size\": 397665210\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16431_Weather2.tar.gz\": {\n        \"sha256\": \"5321f28144a7ef7e59123acfc8dd7319a84d109ee28252f3ceab53e9f279158d\",\n        \"size\": 580049656\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16432_Weather3.tar.gz\": {\n        \"sha256\": \"10d1c0a2ef0c6df39dc09abb0991dc7749112371695b6d302d886dda5bd5646e\",\n        \"size\": 599240047\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16434_Weather5.tar.gz\": {\n        \"sha256\": \"cc65b86a6feb843464806ff0b15db69193663e99018a69a7327dcd020f5123ab\",\n        \"size\": 1044738335\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16438_Weather9.tar.gz\": {\n        \"sha256\": \"15bcf17060e7bd2ad757cbdae67e8eadfe1207338e05d2fb014985b64fd91777\",\n        \"size\": 257613729\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16441_Weather12.tar.gz\": {\n        \"sha256\": \"d15c2569ab374ef427b2ebe1e0ae01027be38068e33cd1af3fd2a96bdce9645d\",\n        \"size\": 299496214\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16442_Weather13.tar.gz\": {\n        \"sha256\": \"a7564409610c7fc52d7288c8dee5d9a75e2d9357dc54294a18c9fb9448539f9b\",\n        \"size\": 160662882\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16443_Weather14.tar.gz\": {\n        \"sha256\": \"79fc69ebfd1820264c7ec6012f7c6885ab03c7fe8c66353dc130ec1ccccadd27\",\n        \"size\": 784236065\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16444_Weather15.tar.gz\": {\n        \"sha256\": \"3dde0a7b34c4a1b356ff096812b02a350b26f7b2235c70fb9490a4f363886ead\",\n        \"size\": 420746267\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16448_Weather19.tar.gz\": {\n        \"sha256\": \"ddd81aa54811af100723c12ab84b2962bff3dc1cb341354c908cf4800e702791\",\n        \"size\": 527911059\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16449_Weather20.tar.gz\": {\n        \"sha256\": \"077ba595ed4c46aecb467fdb9bf55d532bf1f48d0bbba1df0f76c3a785090c8f\",\n        \"size\": 431362931\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16450_Weather21.tar.gz\": {\n        \"sha256\": \"659d20597a8806f43628562c04a825c28b5c7eef20eb5d571a5892739cf298dc\",\n        \"size\": 123526094\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16452_Weather23.tar.gz\": {\n        \"sha256\": \"ef32762a44ef4bb7f847568637027fc74a390ee5eaefc2cca6551237e96eb7f2\",\n        \"size\": 226684694\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16456_Weather1.tar.gz\": {\n        \"sha256\": \"018de2d9ef02f665a1c78b1ecb8bc33c5de6b60cbea8dba2900707058f4ce678\",\n        \"size\": 512506389\n    },\n    \"VanillaSignalizedTurnEncounterRedLight_Town12_Route16457_Weather2.tar.gz\": {\n        \"sha256\": \"f176b235a18087b1a256aa4b7c97189e7aacba803819ccfc3365584bab89b838\",\n        \"size\": 284620783\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route1906_Weather23.tar.gz\": {\n        \"sha256\": \"4d9b35a52fe637ef1d5f0201b8f7664f8d60974ab3525d6f41642b1c1ef793e9\",\n        \"size\": 240218925\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route1907_Weather25.tar.gz\": {\n        \"sha256\": \"5e1e66eaaaa99127b8d5f82ed4b8cbfe9f5c96f249dffd61c568c50f2a317350\",\n        \"size\": 549567785\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route1942_Weather11.tar.gz\": {\n        \"sha256\": \"2db4629d0e0f6df8ed420c0521e48f7c9192874ed35a8a03c585a42e375fef1c\",\n        \"size\": 250482691\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route1945_Weather14.tar.gz\": {\n        \"sha256\": \"19d6bb1985441d39a72038f753b4f0765b6d7ea0f58b29ca720a279bb3d91aa9\",\n        \"size\": 297789580\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route1946_Weather15.tar.gz\": {\n        \"sha256\": \"da311d0b4972ae737bb508eb5d912e6bc2a6649081a01612072e8b80f734aed2\",\n        \"size\": 904322275\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route1984_Weather7.tar.gz\": {\n        \"sha256\": \"339cd10f08999e2791862d777fadd56110eababdb4cf9bd24b4a00eb86453b1b\",\n        \"size\": 319832540\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31859_Weather14.tar.gz\": {\n        \"sha256\": \"bb21713bb9a724656f4bd45bcdbb414b72f0902dabe455866bdf7e328f9e7b29\",\n        \"size\": 807400138\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31861_Weather18.tar.gz\": {\n        \"sha256\": \"ce00d7ffd6c9a656f68c5a93f37100c8efbcdc1bbb00a80e1d00c6061a2acdb0\",\n        \"size\": 443701274\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31864_Weather21.tar.gz\": {\n        \"sha256\": \"1db6d03557f0bea43a87db3bdc688546e59c1896d832d3bb2ad63b35815d1d7c\",\n        \"size\": 2136163742\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31865_Weather22.tar.gz\": {\n        \"sha256\": \"31a3cab60bd03193fafe6132d71b2cce795910de941091e5963722c862071e1b\",\n        \"size\": 281554241\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31867_Weather25.tar.gz\": {\n        \"sha256\": \"7cc8023f3e65e786cfeb69577cba15f3ed2c861264086a9e5b9bd84c8800519d\",\n        \"size\": 229624565\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31869_Weather0.tar.gz\": {\n        \"sha256\": \"11e5610aa72e39055e6009a67d8a59a42af32ac8ff14e6b963c117814327fe3c\",\n        \"size\": 644430701\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31872_Weather3.tar.gz\": {\n        \"sha256\": \"32fb4aac36cbd1b71d1447bf0577eab77ccd564878d912443dd0562064799ab9\",\n        \"size\": 305598626\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31874_Weather6.tar.gz\": {\n        \"sha256\": \"dfc540c2dbe7f935f776ed20b6cf30bb603ed5f218acbf346ec842345647ad6e\",\n        \"size\": 2309488734\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31877_Weather9.tar.gz\": {\n        \"sha256\": \"2d47a42cee7c8f097f726f50d0ea13e7fcb1313b288d6f46bc9eb3b89a971f7b\",\n        \"size\": 408009522\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31879_Weather11.tar.gz\": {\n        \"sha256\": \"48a18a15f89ee5902c5b8f01f28dcc89f8a8223a7f4548142c5980e13b091af8\",\n        \"size\": 588577158\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31881_Weather13.tar.gz\": {\n        \"sha256\": \"c7e0e0469348dfdeb147b8f3fcf0c27384b87057a89e6fd2a8946d6149460413\",\n        \"size\": 735072315\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31882_Weather14.tar.gz\": {\n        \"sha256\": \"ab46041c9d435952124f2405da6b3d8920fb3aed2b5ef757ce01329ef25049e6\",\n        \"size\": 1007063295\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31883_Weather15.tar.gz\": {\n        \"sha256\": \"4ebf39bcfa8920aef78cecb0532a23bc93fed84a88e15578f348ede26caf59ff\",\n        \"size\": 294104199\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31884_Weather18.tar.gz\": {\n        \"sha256\": \"ebd6e0283d72d64e4bb08d34bcc63f01e7455652b5cb6465ad876b2e9c4e23fa\",\n        \"size\": 357936021\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31889_Weather23.tar.gz\": {\n        \"sha256\": \"501efa1b745e86522642a85245ba20fb86217a46227c0c8b7147d5a74417267a\",\n        \"size\": 297000226\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31890_Weather25.tar.gz\": {\n        \"sha256\": \"c308f5f33773b97f33c0a38b9e9fafe33348ffdd1d560555159ad453e001c8a3\",\n        \"size\": 1053683421\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31891_Weather26.tar.gz\": {\n        \"sha256\": \"3b55f656afca0422686f4337d420f558771c5d55693f7aeea894295894b4ba2a\",\n        \"size\": 736294348\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31897_Weather6.tar.gz\": {\n        \"sha256\": \"d9fce40efebac7ff2cf92e5ff106d0f6518d5eed75589e6e2e6e4a7a0c224a7b\",\n        \"size\": 328127099\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31898_Weather7.tar.gz\": {\n        \"sha256\": \"e95c32b7311032a1e7fed0b6f28e7e51fd83046bc568e9cfa30554520008755f\",\n        \"size\": 392037539\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31899_Weather8.tar.gz\": {\n        \"sha256\": \"57fa6b4a14d2db51d4767d880e7dcedb14bbc561f92b8b2540b07f30e569218f\",\n        \"size\": 373219608\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31900_Weather9.tar.gz\": {\n        \"sha256\": \"186ed25208af018c863a68a980199adac66e36be897a5b5d3d33356667f775e0\",\n        \"size\": 303063864\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31902_Weather11.tar.gz\": {\n        \"sha256\": \"1a33e3ed854b94c66470c6cb94ce2f613f3954b8a7512dbdb7c7e4b60bd57c05\",\n        \"size\": 239462260\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31903_Weather12.tar.gz\": {\n        \"sha256\": \"a25ab61058770fd5b39ecbbd379743b80737dc8bf5eb6f1391740d8f99504932\",\n        \"size\": 255964548\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31905_Weather14.tar.gz\": {\n        \"sha256\": \"9a16a72999a4fde3e72e5606428f005a6db90fc1f3c1d503bf4e6085635836ee\",\n        \"size\": 1398477781\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31909_Weather20.tar.gz\": {\n        \"sha256\": \"b89e3291ec11658c6a2495b92277c5fb59bd881f60d5d5dd47e41e313bb0d0e7\",\n        \"size\": 452755851\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31910_Weather21.tar.gz\": {\n        \"sha256\": \"724972ad7ad42bf6219ac3434c73aeecea3d97835c37e08fc69af0c6db586512\",\n        \"size\": 284171033\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31911_Weather22.tar.gz\": {\n        \"sha256\": \"1859bd9095e3dd22d80a778f20571606bdb32997bd05a00cedc8af328708a603\",\n        \"size\": 264689389\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31917_Weather2.tar.gz\": {\n        \"sha256\": \"8b8e7cf7d69e72641de603c0884929e2d60c16c05b0cad614626b947681628e4\",\n        \"size\": 367727359\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31918_Weather3.tar.gz\": {\n        \"sha256\": \"fd32b8c668187e3ff6114680f6217ef338ad59724ddc3f7b3573fdfcf34b8f94\",\n        \"size\": 298661442\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31919_Weather5.tar.gz\": {\n        \"sha256\": \"5a966f0b577f0e3cf58a7442487826355a34e0d5e2d5304ac996f5bc92e0018b\",\n        \"size\": 291437633\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31922_Weather8.tar.gz\": {\n        \"sha256\": \"d099118b1cb3fcf6ee7512eb70e4e889eb5dc076c7b1d6d384444ed98a9b375e\",\n        \"size\": 678976098\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31923_Weather9.tar.gz\": {\n        \"sha256\": \"5f26044021c0f6e25d126d0064c48e3dea360d0a2248a6891258cd4e803db6d9\",\n        \"size\": 621218318\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31928_Weather14.tar.gz\": {\n        \"sha256\": \"be4261aacb2c0faec7c0be90ae7d0c63eddf6d169298430706a48da1012211da\",\n        \"size\": 848602589\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31930_Weather18.tar.gz\": {\n        \"sha256\": \"bd05817bbb411bc9b86f20834c718c9499f40153abac6c74bfee5139dc24782a\",\n        \"size\": 985314084\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31934_Weather22.tar.gz\": {\n        \"sha256\": \"0cade72dccdf0381072a6e8c027be811c548b64c98a751717b85570b87c13acf\",\n        \"size\": 448175192\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31938_Weather0.tar.gz\": {\n        \"sha256\": \"f47ac3a565a5adf835aa242d659b0d7cb0c2615537df32571b137475835aae58\",\n        \"size\": 322552120\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31939_Weather1.tar.gz\": {\n        \"sha256\": \"5d7c4f08ff29566dfcb68125071994493316e20b315dfc8a97d76fc45293d8d5\",\n        \"size\": 321744451\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31943_Weather6.tar.gz\": {\n        \"sha256\": \"0ac2a06fbe68cca357ee3b4b2d3a5b9b98f77c7e6eb2dbd3467dc59f5f5e053a\",\n        \"size\": 313892947\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31945_Weather8.tar.gz\": {\n        \"sha256\": \"794bf3ebefe00786fcd8742e7ae37e9faa1551a3c3c3e63c979c1d13a0fc2ec4\",\n        \"size\": 780650511\n    },\n    \"VehicleOpensDoorTwoWays_Town13_Route31946_Weather9.tar.gz\": {\n        \"sha256\": \"6fa2d502baaa250916fb41679565025b48cbd076ab6221dff2f61c34668c503b\",\n        \"size\": 548574417\n    },\n    \"VehicleTurningRoute_Town12_Route9437_Weather2.tar.gz\": {\n        \"sha256\": \"ad03633ad76729c81d42ed7fd8a6b88b760d76399a9038a3a859cd9f6a7ff775\",\n        \"size\": 579473508\n    },\n    \"VehicleTurningRoute_Town12_Route9438_Weather3.tar.gz\": {\n        \"sha256\": \"347f1a2f3d9467ddf728c6bccdce0be2342fb8a5aa19d7d0df9e8131a334aed1\",\n        \"size\": 306897927\n    },\n    \"VehicleTurningRoute_Town12_Route9439_Weather3.tar.gz\": {\n        \"sha256\": \"da968cf50857ddbd8e66560c8b6a7a9f17f2a14835d2c9351ce2023dad82f1a7\",\n        \"size\": 515361406\n    },\n    \"VehicleTurningRoute_Town12_Route9440_Weather5.tar.gz\": {\n        \"sha256\": \"0decf545d1c6739e7e4c7b968b832498f196750f3fc59accad797a8031b8fff2\",\n        \"size\": 125902433\n    },\n    \"VehicleTurningRoute_Town12_Route9441_Weather6.tar.gz\": {\n        \"sha256\": \"900b9561bd47355437e570c3b7cbcf547e43eba08ef04565b94552a6ceb8afa3\",\n        \"size\": 216788960\n    },\n    \"VehicleTurningRoute_Town12_Route9443_Weather8.tar.gz\": {\n        \"sha256\": \"6ffd54d2003f9ff8fadf310b848a5e9cb4535a70df80c45302b9e1baf28e9782\",\n        \"size\": 375377453\n    },\n    \"VehicleTurningRoute_Town12_Route9448_Weather13.tar.gz\": {\n        \"sha256\": \"aa1d33eff78dc2bf74f94c40d27ad0d5caa073a978864fd7d0ce850caa00a23a\",\n        \"size\": 215631277\n    },\n    \"VehicleTurningRoute_Town12_Route9449_Weather14.tar.gz\": {\n        \"sha256\": \"1f283bd9458bdac47cd2969a6abb30318d98ab039d8d3a904457d3f6c2f7873b\",\n        \"size\": 342289593\n    },\n    \"VehicleTurningRoute_Town12_Route9450_Weather15.tar.gz\": {\n        \"sha256\": \"8f89ce1ccfee36d56f95894ec4a7c237bcec0570dcefa0130326e92abdef110c\",\n        \"size\": 227383465\n    },\n    \"VehicleTurningRoute_Town12_Route9451_Weather8.tar.gz\": {\n        \"sha256\": \"ca30acf63aa18f3526f3175c6a6e18102835eb476cc9ef3d8f7c72e80596b05d\",\n        \"size\": 415158005\n    },\n    \"VehicleTurningRoute_Town12_Route9453_Weather18.tar.gz\": {\n        \"sha256\": \"a5b60672d418e0ca6f72d4b91d95d288da1228132d9d1c1a6b8c61c2cc26c1ba\",\n        \"size\": 102137296\n    },\n    \"VehicleTurningRoute_Town12_Route9455_Weather20.tar.gz\": {\n        \"sha256\": \"2b00459e1ae103fc5830a3b0a5559437f2ce5f3bc205cb10cd725be4d8a85fa3\",\n        \"size\": 204709961\n    },\n    \"VehicleTurningRoute_Town12_Route9456_Weather21.tar.gz\": {\n        \"sha256\": \"752c5bfacb8c6abb0a9993f2209d2718083b4f89e1cd4a72193ff247d7ec123d\",\n        \"size\": 168397756\n    },\n    \"VehicleTurningRoute_Town12_Route9457_Weather22.tar.gz\": {\n        \"sha256\": \"7a0868edc8e459f70a4fbfa2ff9e1a668a00cafb8698fcda04d809658cc5ce39\",\n        \"size\": 337164365\n    },\n    \"VehicleTurningRoute_Town12_Route9459_Weather23.tar.gz\": {\n        \"sha256\": \"db9c7996ebdc354b72ee574d283b6e69d08c67b6b27f75dc23f5eee49931f267\",\n        \"size\": 251380013\n    },\n    \"VehicleTurningRoute_Town12_Route9460_Weather25.tar.gz\": {\n        \"sha256\": \"9c99a6182e52008600b83cb6875e10f09d3776ecc0c88511018ec96bea3169a5\",\n        \"size\": 156629163\n    },\n    \"VehicleTurningRoute_Town12_Route9464_Weather3.tar.gz\": {\n        \"sha256\": \"78481ad1d974d95ee38a7f3de0009cd9e537999e2c89baa8c6411c795501de7b\",\n        \"size\": 218975536\n    },\n    \"VehicleTurningRoute_Town12_Route9465_Weather3.tar.gz\": {\n        \"sha256\": \"3d96e6079a3b77b8d4a4da18638dd0076eeae61ac5b12fa6f173aee925a9c689\",\n        \"size\": 529357463\n    },\n    \"VehicleTurningRoute_Town12_Route9466_Weather5.tar.gz\": {\n        \"sha256\": \"fda9854478b182a551263e2e8dc1b22838948b98c26db07f12392225f6bd1812\",\n        \"size\": 235173642\n    },\n    \"VehicleTurningRoute_Town12_Route9467_Weather6.tar.gz\": {\n        \"sha256\": \"ecf5b515f21afb3972b0d01daf93851bf5846008ce9e4a5291eedb1971803f68\",\n        \"size\": 95831568\n    },\n    \"VehicleTurningRoute_Town12_Route9468_Weather7.tar.gz\": {\n        \"sha256\": \"220933863882edfbebff3efac4f928977213429c24f2fb50d036feccd0847af8\",\n        \"size\": 292823565\n    },\n    \"VehicleTurningRoute_Town12_Route9469_Weather8.tar.gz\": {\n        \"sha256\": \"b5d55893c59a4182653e61f4fa6ee7f4b75c8d4feabda13fe1df00067aa44917\",\n        \"size\": 664216294\n    },\n    \"VehicleTurningRoute_Town12_Route9470_Weather9.tar.gz\": {\n        \"sha256\": \"0877f3997cd15c7d70b700e75a663fd83fd22b2017ce372d25ee494544972a43\",\n        \"size\": 237473204\n    },\n    \"VehicleTurningRoute_Town12_Route9471_Weather10.tar.gz\": {\n        \"sha256\": \"3ac5f3b7016bf06f65d00bf090ed80fa11e55fe9830c11f8d7201473ad03a913\",\n        \"size\": 592310694\n    },\n    \"VehicleTurningRoute_Town12_Route9474_Weather13.tar.gz\": {\n        \"sha256\": \"46d1a161b143ad6e259e69b453520f5a4f733ab6c3497537d270584b6ea8b50f\",\n        \"size\": 77008008\n    },\n    \"VehicleTurningRoute_Town12_Route9475_Weather14.tar.gz\": {\n        \"sha256\": \"f0a768b0816d718623f5e24f093e1ec97c7b66670e903f51244896a17356a684\",\n        \"size\": 167590471\n    },\n    \"VehicleTurningRoute_Town12_Route9477_Weather8.tar.gz\": {\n        \"sha256\": \"bc4995c34b6c129ed0214123ec18a3693f936ff8bbcf94f4c29ba0a87b6184fa\",\n        \"size\": 124807987\n    },\n    \"VehicleTurningRoute_Town12_Route9478_Weather9.tar.gz\": {\n        \"sha256\": \"aa0d8d2baf8dec42721f07ce1b974b83a5c5f79d0eb879b6b4c2a8c3557809b7\",\n        \"size\": 138071186\n    },\n    \"VehicleTurningRoute_Town12_Route9479_Weather18.tar.gz\": {\n        \"sha256\": \"a69ca63c73c52ad5bf43eb2a8256aa760765287dc2a088ff6c63f2341026bed5\",\n        \"size\": 106244736\n    },\n    \"VehicleTurningRoute_Town12_Route9480_Weather19.tar.gz\": {\n        \"sha256\": \"945ce4b7e9befe2267dd4edb03d5a3335056f1881aa44dc0c3bde7dd498cc77a\",\n        \"size\": 268734930\n    },\n    \"VehicleTurningRoute_Town12_Route9481_Weather20.tar.gz\": {\n        \"sha256\": \"2ad2c1903e3c0608cb9565d97dba830108ab539c0ed44d87eb74e527f802d484\",\n        \"size\": 190618704\n    },\n    \"VehicleTurningRoute_Town12_Route9483_Weather22.tar.gz\": {\n        \"sha256\": \"8b0528314bfea2503cc0c2a6fecb3962d703e34cdb4f2dd474e6b1e3215eb7b0\",\n        \"size\": 605456119\n    },\n    \"VehicleTurningRoute_Town12_Route9484_Weather23.tar.gz\": {\n        \"sha256\": \"0ac03102c2c58a6ece5812355ed6925580ecf255c462dc815ab1a0c6ac0ac781\",\n        \"size\": 100899977\n    },\n    \"VehicleTurningRoute_Town12_Route9487_Weather0.tar.gz\": {\n        \"sha256\": \"c08185b137a3323795f0aa4a198b6bcef70141c2965020a577af9b825ee9e30d\",\n        \"size\": 298953088\n    },\n    \"VehicleTurningRoute_Town12_Route9488_Weather1.tar.gz\": {\n        \"sha256\": \"7f2eda1c6185caf0f99fd5e126a9d2ea99b0e4954a7924fc442e32064440afcb\",\n        \"size\": 288985851\n    },\n    \"VehicleTurningRoute_Town12_Route9490_Weather3.tar.gz\": {\n        \"sha256\": \"ad395aa9c4a47cf22976379116476042144996482f5d695c51374e68db6db7d7\",\n        \"size\": 286625058\n    },\n    \"VehicleTurningRoute_Town12_Route9491_Weather3.tar.gz\": {\n        \"sha256\": \"4e7afa6a1f77cffcfc2cf856944745165cae57092db4b30323d39fc83f1e485d\",\n        \"size\": 273187302\n    },\n    \"VehicleTurningRoute_Town12_Route9492_Weather5.tar.gz\": {\n        \"sha256\": \"38308c59b9c84f6251ea8c6f966f367eb860ed76864b18457601cd367c0a6631\",\n        \"size\": 661399110\n    },\n    \"VehicleTurningRoute_Town12_Route9493_Weather6.tar.gz\": {\n        \"sha256\": \"466bfe10ccaf177cbdf9be62b2ef31a7c9b7483dc8374d6eefb125d09ac5f199\",\n        \"size\": 229358621\n    },\n    \"VehicleTurningRoute_Town12_Route9496_Weather9.tar.gz\": {\n        \"sha256\": \"199c4cfe13a53efbee8fd8f8cbfb4d3754639f33357085d34fd736b3f15e1792\",\n        \"size\": 351012908\n    },\n    \"VehicleTurningRoute_Town12_Route9497_Weather10.tar.gz\": {\n        \"sha256\": \"7bea06cc217015d6099131e0ca8241c0be058713baa3a393461f0dafe047fdad\",\n        \"size\": 152483671\n    },\n    \"VehicleTurningRoute_Town12_Route9501_Weather14.tar.gz\": {\n        \"sha256\": \"faaf23ec7c08de3496d6d2b675007ec8c68c493d6de35bb69e800c0a735d37fd\",\n        \"size\": 258021864\n    },\n    \"VehicleTurningRoute_Town12_Route9502_Weather15.tar.gz\": {\n        \"sha256\": \"e8715e821c6abf66cb3270a3720e69405bb61bec9dea595b234d75fdb9114b6c\",\n        \"size\": 85190954\n    },\n    \"VehicleTurningRoute_Town12_Route9503_Weather8.tar.gz\": {\n        \"sha256\": \"f18328ea3e4737c6b6539f8abf364c389df2d1c9e7b646e106258fa0e1eafc49\",\n        \"size\": 424376200\n    },\n    \"VehicleTurningRoute_Town12_Route9504_Weather9.tar.gz\": {\n        \"sha256\": \"c30a8b5dcd79a8b907950ac3dfaa4eaa9c8912b9a5f3c96d93c4b26a2dfad543\",\n        \"size\": 289743149\n    },\n    \"VehicleTurningRoute_Town12_Route9505_Weather18.tar.gz\": {\n        \"sha256\": \"612ed7ff16acca1fe168812a768529cca1df4a4b1019c8975c1ffeca3554ebd9\",\n        \"size\": 279737983\n    },\n    \"VehicleTurningRoute_Town12_Route9506_Weather19.tar.gz\": {\n        \"sha256\": \"5b81bfc9fdcd5e3c38db2c474536048f738784c64e4e662144dd302ecaca120d\",\n        \"size\": 200951505\n    },\n    \"VehicleTurningRoute_Town12_Route9508_Weather21.tar.gz\": {\n        \"sha256\": \"ef746a08311cb19b8658a961f29cd9a8be181ce56d1b1d515bad95244250d084\",\n        \"size\": 90682972\n    },\n    \"VehicleTurningRoute_Town12_Route9509_Weather22.tar.gz\": {\n        \"sha256\": \"6ac78633456af837566475bf51c874b11c8ec8af20b86c618222043b699dc962\",\n        \"size\": 201095622\n    },\n    \"VehicleTurningRoute_Town12_Route9510_Weather23.tar.gz\": {\n        \"sha256\": \"68f0c546a4ffc3a1aae6b5b1b75915ccd81bf9beb89eb839201a09c26ca4ac89\",\n        \"size\": 763867530\n    },\n    \"VehicleTurningRoute_Town12_Route9511_Weather23.tar.gz\": {\n        \"sha256\": \"e8b76a80191f6f2b6578bb007c80ecf831c110ad9202d7e52bcb7e6337a771c4\",\n        \"size\": 200089298\n    },\n    \"VehicleTurningRoute_Town12_Route9512_Weather25.tar.gz\": {\n        \"sha256\": \"bc1141323d4939a0d6fa5801823f23c9909bc3ef58fd5d56b4b8bdad5f487f38\",\n        \"size\": 186713341\n    },\n    \"VehicleTurningRoute_Town12_Route9513_Weather0.tar.gz\": {\n        \"sha256\": \"26c8373e7af312f9a7b8fda07da892b383032ccb663d1c1b14683917be446989\",\n        \"size\": 284842981\n    },\n    \"VehicleTurningRoute_Town12_Route9516_Weather3.tar.gz\": {\n        \"sha256\": \"3f2031c94ef39be124f09e22349674799f258749932e6f54d7c052544cbe81e1\",\n        \"size\": 100813890\n    },\n    \"VehicleTurningRoute_Town12_Route9519_Weather6.tar.gz\": {\n        \"sha256\": \"b15023b58edf7fe74a97624f9fce6c7be403dca7b360217808dba7f5a7756dc1\",\n        \"size\": 252489743\n    },\n    \"VehicleTurningRoute_Town12_Route9520_Weather7.tar.gz\": {\n        \"sha256\": \"7db71f78bcf4a63013fc22ecac446940b24293878eef3b28ce5a4b9e1e21a023\",\n        \"size\": 323172960\n    },\n    \"VehicleTurningRoute_Town12_Route9521_Weather8.tar.gz\": {\n        \"sha256\": \"105b41234a6ea996899b547c15c66bf1d5b77523ef41cbf2bce4cfddaf4fb7a5\",\n        \"size\": 309917927\n    },\n    \"VehicleTurningRoute_Town12_Route9522_Weather9.tar.gz\": {\n        \"sha256\": \"7c4f4fcd4cea9dfa3fa02ee081316e960a5790614faad0fd796929c8edbe33f4\",\n        \"size\": 132958067\n    },\n    \"VehicleTurningRoute_Town12_Route9523_Weather10.tar.gz\": {\n        \"sha256\": \"f54a8dd317ee565227945e40a30a844064495dd2fbb84ff6fb2d814ca65c46a9\",\n        \"size\": 548404059\n    },\n    \"VehicleTurningRoute_Town12_Route9524_Weather11.tar.gz\": {\n        \"sha256\": \"01b9e708e075db2240c1945af8d996c1725b2992047492f357af0f03b8659c07\",\n        \"size\": 1200141483\n    },\n    \"VehicleTurningRoute_Town12_Route9526_Weather13.tar.gz\": {\n        \"sha256\": \"6883e0b5a81c1eb1bf988d97e3abc2fb5aeb83eb1bb5d6869fc001cb782028fb\",\n        \"size\": 276970039\n    },\n    \"VehicleTurningRoute_Town12_Route9527_Weather14.tar.gz\": {\n        \"sha256\": \"f574b3703a4899cc87676a0dbff2ad27bab03b2fb1b886688025acd51f7f6ebb\",\n        \"size\": 336418472\n    },\n    \"VehicleTurningRoute_Town12_Route9528_Weather15.tar.gz\": {\n        \"sha256\": \"e76589cb95dcded9b296a2754928d08a3b7659bcd3969403f1654ebf9476de4b\",\n        \"size\": 245115346\n    },\n    \"VehicleTurningRoute_Town12_Route9530_Weather9.tar.gz\": {\n        \"sha256\": \"9eb9b68e3a0922595ba5f23bcaf55f0143b7eb5f4417b96640a5c79d7c463114\",\n        \"size\": 214459554\n    },\n    \"VehicleTurningRoute_Town12_Route9533_Weather20.tar.gz\": {\n        \"sha256\": \"117beb7d5dd03d4b652b85a0b1faa5c15175df92b91422841abeb044dda4a1ca\",\n        \"size\": 313690948\n    },\n    \"VehicleTurningRoute_Town12_Route9536_Weather23.tar.gz\": {\n        \"sha256\": \"aa77f77e9f6f228ebcada184b50f9e6301145e0c4b28b5081cd2e9977c2ab417\",\n        \"size\": 268235852\n    },\n    \"VehicleTurningRoute_Town12_Route9537_Weather23.tar.gz\": {\n        \"sha256\": \"8b706e1287fba98eae9d8db710d6b1e00dc4019bf85379fee9039a2b03d884c7\",\n        \"size\": 170763673\n    },\n    \"VehicleTurningRoute_Town12_Route9538_Weather25.tar.gz\": {\n        \"sha256\": \"5d67028c1e0303a5d467194883401fc6427856da38df8602b7bd2f9a99816029\",\n        \"size\": 349200481\n    },\n    \"VehicleTurningRoute_Town12_Route9540_Weather1.tar.gz\": {\n        \"sha256\": \"a9befbf155dc00b76536ec3cf5ce857852ece4fd31ab043a6e36e79b21348460\",\n        \"size\": 122671615\n    },\n    \"VehicleTurningRoute_Town12_Route9541_Weather2.tar.gz\": {\n        \"sha256\": \"a113ff0b70b6b25b8bee7cfd22f37b04d99fadbffe30b06256913079fbda7802\",\n        \"size\": 231371787\n    },\n    \"VehicleTurningRoute_Town12_Route9544_Weather5.tar.gz\": {\n        \"sha256\": \"ca5281b7d2312136304ba18348ac48b9f8bdd5eb7606ab689bfc8d7a1e4f1ecc\",\n        \"size\": 197936364\n    },\n    \"VehicleTurningRoute_Town12_Route9545_Weather6.tar.gz\": {\n        \"sha256\": \"dc7ef91629662d5132d44a1c25e31543b915d743c4380c61891cfbbb9f90bdf2\",\n        \"size\": 236443236\n    },\n    \"VehicleTurningRoute_Town12_Route9546_Weather7.tar.gz\": {\n        \"sha256\": \"162a3d092f8f0858e3bc64d3be1544bce61669e820e53ba2842c6e81f9cb8e34\",\n        \"size\": 330155571\n    },\n    \"VehicleTurningRoute_Town12_Route9548_Weather9.tar.gz\": {\n        \"sha256\": \"86206e27bd46260a0b74e5ddf0bed320dbf36756941e783496bca632fc6c1b85\",\n        \"size\": 86889456\n    },\n    \"VehicleTurningRoute_Town12_Route9551_Weather12.tar.gz\": {\n        \"sha256\": \"e71510d82947b2be4a6d33bdbe4f87fa9a38d226c9a799e25ce81f410b9fc77d\",\n        \"size\": 366080625\n    },\n    \"VehicleTurningRoute_Town12_Route9552_Weather13.tar.gz\": {\n        \"sha256\": \"41595635795e8e8e9f9b4b2dec7c1019f35dff6319b94273ff2242fbd4c497d5\",\n        \"size\": 579802991\n    },\n    \"VehicleTurningRoute_Town12_Route9555_Weather8.tar.gz\": {\n        \"sha256\": \"7ac3fe91a9163719a3b0a8bd9fbd6b22ead821dcbc3cde88766826c81f050158\",\n        \"size\": 680376263\n    },\n    \"VehicleTurningRoute_Town12_Route9559_Weather20.tar.gz\": {\n        \"sha256\": \"813cbda5572a5fdc358459cf92104233f535b2705ce3912bbe8b33cbb2277e78\",\n        \"size\": 563519872\n    },\n    \"VehicleTurningRoute_Town12_Route9560_Weather21.tar.gz\": {\n        \"sha256\": \"fc73f8af773746891bd12f346afe372b5775b5bdb6d82f92c4bbc3c619954d85\",\n        \"size\": 466834558\n    },\n    \"VehicleTurningRoute_Town12_Route9562_Weather23.tar.gz\": {\n        \"sha256\": \"dd6440139e850c085222f85a55d3c455624902bc7994406dbd3d7f1786247800\",\n        \"size\": 248844635\n    },\n    \"VehicleTurningRoute_Town12_Route9563_Weather23.tar.gz\": {\n        \"sha256\": \"e02ec08eb568e7f23be2e7472b26841daa8c49967a4df29f87eeac9acb876d64\",\n        \"size\": 119731618\n    },\n    \"VehicleTurningRoute_Town12_Route9564_Weather25.tar.gz\": {\n        \"sha256\": \"8e71ab51d7713e8a34f87e35a3b1de814729c40aef322ce48c55beb64f8509c3\",\n        \"size\": 206358571\n    },\n    \"VehicleTurningRoute_Town12_Route9568_Weather3.tar.gz\": {\n        \"sha256\": \"f140ff490fbfb4b7826cfb1f9815344fc44dd82ce28384821510fd78bae25f09\",\n        \"size\": 441548540\n    },\n    \"VehicleTurningRoute_Town12_Route9569_Weather3.tar.gz\": {\n        \"sha256\": \"4ee042122969929a61d6b32dbb10ad3465ac1920d5589eafc2f0e459fe2f873a\",\n        \"size\": 111788769\n    },\n    \"VehicleTurningRoute_Town12_Route9570_Weather5.tar.gz\": {\n        \"sha256\": \"d253cd75a096a0b7b1be3acac0950c0a6dea6c12688e7e251943aaeddad71c4c\",\n        \"size\": 623679305\n    },\n    \"VehicleTurningRoute_Town12_Route9575_Weather10.tar.gz\": {\n        \"sha256\": \"b49bc4542cc61507c7e01e6b5c7a0acd71fb5b548ebeb7cfc043f2b7cd3c0990\",\n        \"size\": 205303716\n    },\n    \"VehicleTurningRoute_Town12_Route9577_Weather12.tar.gz\": {\n        \"sha256\": \"3d27461badfe59aa8f1bd0f06256b4a64175164d3833b769367fa9e6b6f4904e\",\n        \"size\": 464877829\n    },\n    \"VehicleTurningRoute_Town12_Route9578_Weather13.tar.gz\": {\n        \"sha256\": \"c3365273b42bbd7d8fe058d42274680a05af1af6509cc680268c44dadb701d71\",\n        \"size\": 402262384\n    },\n    \"VehicleTurningRoute_Town12_Route9580_Weather15.tar.gz\": {\n        \"sha256\": \"df2452656aa37c85f6aba8fed1b4b0b401609e925cb08a59f0243cda5353ef7d\",\n        \"size\": 169877491\n    },\n    \"VehicleTurningRoute_Town12_Route9582_Weather9.tar.gz\": {\n        \"sha256\": \"bf692daba5ebd11196e13a17e22c23316e2f72ae1ff7f8225fd7094a89429cff\",\n        \"size\": 91874506\n    },\n    \"VehicleTurningRoute_Town12_Route9583_Weather18.tar.gz\": {\n        \"sha256\": \"dcbff13efdb870c498151642d9db8258c4179c52be191ca40f2d44c472403528\",\n        \"size\": 317767645\n    },\n    \"VehicleTurningRoute_Town12_Route9584_Weather19.tar.gz\": {\n        \"sha256\": \"06d15cb32f49898012475b6a4117c55c40abeac33461d3f94b04f7dd44341367\",\n        \"size\": 242050354\n    },\n    \"VehicleTurningRoute_Town12_Route9585_Weather20.tar.gz\": {\n        \"sha256\": \"592e53ed0766accdc4756a62471814c641b5807f03746ae649d0b5d68cc15847\",\n        \"size\": 189886752\n    },\n    \"VehicleTurningRoute_Town12_Route9588_Weather23.tar.gz\": {\n        \"sha256\": \"aafcb42e79bb8a2fed64b719013866ea8d8c5a102beffe8887402b5afc9addff\",\n        \"size\": 273613523\n    },\n    \"VehicleTurningRoute_Town12_Route9590_Weather25.tar.gz\": {\n        \"sha256\": \"62e2e4eb27788395dcb84a1f7e2d31b172609ddfa7e4e510370a45d0cece5157\",\n        \"size\": 251569421\n    },\n    \"VehicleTurningRoute_Town12_Route9593_Weather2.tar.gz\": {\n        \"sha256\": \"ad2d1df420ca8f9d513fef3edb5ee1d8f4552deb69a71d8716d74fcc28d2ec87\",\n        \"size\": 224792519\n    },\n    \"VehicleTurningRoute_Town12_Route9596_Weather5.tar.gz\": {\n        \"sha256\": \"e9d26be12b6e77d1905b564a3cd0c8890c79a235c0b298803393effe9cf1be2d\",\n        \"size\": 292503281\n    },\n    \"VehicleTurningRoute_Town12_Route9600_Weather9.tar.gz\": {\n        \"sha256\": \"08691639462a89e8361471e4b9a24f3fba504c0e3d33f27d9d7c6b9098bc20a4\",\n        \"size\": 272395765\n    },\n    \"VehicleTurningRoute_Town12_Route9601_Weather10.tar.gz\": {\n        \"sha256\": \"14d7e97d26db95e86e8c1805f949960c60addb1d6dfd20d196afbe8c100418c6\",\n        \"size\": 319845814\n    },\n    \"VehicleTurningRoute_Town12_Route9603_Weather12.tar.gz\": {\n        \"sha256\": \"77f47c5256789ce1ce7ffafb7189a7f22a709128f3072103ccc94f1a2d943afb\",\n        \"size\": 425249743\n    },\n    \"VehicleTurningRoute_Town12_Route9604_Weather13.tar.gz\": {\n        \"sha256\": \"da2828512007d4f4046050168338cf6915eb2441dc611a2a5546ec193b862e8f\",\n        \"size\": 141708899\n    },\n    \"VehicleTurningRoute_Town12_Route9605_Weather14.tar.gz\": {\n        \"sha256\": \"3fa2760b01a4613b96cd5b881cc56533a237ef78314af102ae3a6c02c34003ce\",\n        \"size\": 122147860\n    },\n    \"VehicleTurningRoute_Town12_Route9606_Weather15.tar.gz\": {\n        \"sha256\": \"f0d8a5cb97f79e10367081fb6489f9b5aef917a8af258245501cbeb10a97ada7\",\n        \"size\": 84211479\n    },\n    \"VehicleTurningRoute_Town12_Route9607_Weather8.tar.gz\": {\n        \"sha256\": \"376142329f803fa1cbff277ee28681391d27b8e28d50fed07017d94c3a56505d\",\n        \"size\": 527803444\n    },\n    \"VehicleTurningRoute_Town12_Route9609_Weather18.tar.gz\": {\n        \"sha256\": \"6f7bbbbe84996ea6e4aa4aecc5b1ccc060e019602be62ea6f8105405e5778a2a\",\n        \"size\": 114377548\n    },\n    \"VehicleTurningRoute_Town12_Route9610_Weather19.tar.gz\": {\n        \"sha256\": \"6305eb55a1818cec60c4b8018e8540db5854cdc06d3042faf62bbff0890cec3e\",\n        \"size\": 241318813\n    },\n    \"VehicleTurningRoute_Town12_Route9612_Weather21.tar.gz\": {\n        \"sha256\": \"0c5d5e00a230b6edf6b3948adbe0dd155ff4302952a17f935e82774d239ea19f\",\n        \"size\": 471099093\n    },\n    \"VehicleTurningRoute_Town12_Route9613_Weather22.tar.gz\": {\n        \"sha256\": \"2293afddba7690f6e9f1ea65f999f89bdafc6e65db23d330c13be2c03a8f6261\",\n        \"size\": 186392912\n    },\n    \"VehicleTurningRoute_Town12_Route9615_Weather23.tar.gz\": {\n        \"sha256\": \"a6bdc18fc2509e7a2ebe0d4c04dd64e6f086a188f941d8417f130e52c007c9f7\",\n        \"size\": 243655354\n    },\n    \"VehicleTurningRoute_Town12_Route9616_Weather25.tar.gz\": {\n        \"sha256\": \"3914637b1463636134880a167a14f3590c8c0d05b9dd0ab8fa7db32221d3db76\",\n        \"size\": 246910775\n    },\n    \"VehicleTurningRoute_Town12_Route9618_Weather1.tar.gz\": {\n        \"sha256\": \"fb959ac3bf7ec076c5d6c94df44f942fe862db3a39d5efb9577b2c58e84ec099\",\n        \"size\": 331279264\n    },\n    \"VehicleTurningRoute_Town12_Route9619_Weather2.tar.gz\": {\n        \"sha256\": \"e5672e7ced06ce484c3696945484a1aa8d8c0ff2bd94c07039cc69e8688d3b73\",\n        \"size\": 433355543\n    },\n    \"VehicleTurningRoute_Town12_Route9620_Weather3.tar.gz\": {\n        \"sha256\": \"5a85fba466553e62bdea948fcbe30511c78ab159e4653234852c6fd3e5352d8a\",\n        \"size\": 180617772\n    },\n    \"VehicleTurningRoute_Town12_Route9622_Weather5.tar.gz\": {\n        \"sha256\": \"212f7fa5d6e33485433d169f546944f3305787403b19171ac46bdf8befae7f17\",\n        \"size\": 400879426\n    },\n    \"VehicleTurningRoute_Town12_Route9624_Weather7.tar.gz\": {\n        \"sha256\": \"729c0805c2c6368b426a2dc35166cc663854923b44d8e8d49ebe8fe8e6031200\",\n        \"size\": 134828798\n    },\n    \"VehicleTurningRoute_Town12_Route9625_Weather8.tar.gz\": {\n        \"sha256\": \"8f6ca4bd606bc2cafcc344966d04949b4014748eb7963e5fd4786d22f78aed64\",\n        \"size\": 423329935\n    },\n    \"VehicleTurningRoute_Town12_Route9626_Weather9.tar.gz\": {\n        \"sha256\": \"f27ff9231fcd317f00eec754f9711a7e9796a1eed28a836f13bc33956b2a0b8c\",\n        \"size\": 232463258\n    },\n    \"VehicleTurningRoute_Town12_Route9636_Weather19.tar.gz\": {\n        \"sha256\": \"ac49811a6e0be309def92bdefc434808dbd47adf5eb6b067203e0b570610101c\",\n        \"size\": 218650065\n    },\n    \"VehicleTurningRoute_Town12_Route9638_Weather21.tar.gz\": {\n        \"sha256\": \"4e7c13e870c3adf54c282bed0d459ce75bb51f88f136110eb4ca4202f25ab1d6\",\n        \"size\": 217273106\n    },\n    \"VehicleTurningRoute_Town12_Route9639_Weather22.tar.gz\": {\n        \"sha256\": \"a4d85bfbd6540b1aaea7aa3c541e8e858329f4ee0ec2f8e1f869b6bbd1de1d5e\",\n        \"size\": 275032569\n    },\n    \"VehicleTurningRoute_Town12_Route9640_Weather23.tar.gz\": {\n        \"sha256\": \"ddfb977577ab0ce515961ba992b961bc943ca6dba05b436e846ab958491eeb75\",\n        \"size\": 281864689\n    },\n    \"VehicleTurningRoute_Town12_Route9643_Weather0.tar.gz\": {\n        \"sha256\": \"99f527da8b0d5ee5c94f85000f7c075a8530d0bfd17aa1d2efac6e60ccd383c5\",\n        \"size\": 365050661\n    },\n    \"VehicleTurningRoute_Town12_Route9644_Weather1.tar.gz\": {\n        \"sha256\": \"453e0e6f3ca0f67938951bb8049a346e7bc61e64584120efaf148ba027da044e\",\n        \"size\": 218507175\n    },\n    \"VehicleTurningRoute_Town12_Route9648_Weather5.tar.gz\": {\n        \"sha256\": \"625767eb8e69ecc80ba6d8c54db4cfa9bf46935057a0fee80c089403f2f73fe2\",\n        \"size\": 332903222\n    },\n    \"VehicleTurningRoute_Town12_Route9649_Weather6.tar.gz\": {\n        \"sha256\": \"97dc58b00e20440f29fd34684a4e009dffcc1ffbde44ce2bb8067dfa14a569ab\",\n        \"size\": 395885424\n    },\n    \"VehicleTurningRoute_Town12_Route9650_Weather7.tar.gz\": {\n        \"sha256\": \"593f433debd9cfe5da5c59624a7409fd90ef711988fa4d3ce943ec6e5b69e5ff\",\n        \"size\": 544760411\n    },\n    \"VehicleTurningRoute_Town12_Route9652_Weather9.tar.gz\": {\n        \"sha256\": \"d3f44c27bf841e62d27eff2fbd887c828345909694d8cb712c66e3d51b01c002\",\n        \"size\": 269102685\n    },\n    \"VehicleTurningRoute_Town12_Route9654_Weather11.tar.gz\": {\n        \"sha256\": \"927536f61ddee62733273b5b8066be3ad5e806fa870602a7b43ccc8ce6a38264\",\n        \"size\": 202763906\n    },\n    \"VehicleTurningRoute_Town12_Route9655_Weather12.tar.gz\": {\n        \"sha256\": \"5d146205c6b83065e8139111684b90df43c406c13e49592e6bbf06bd3d29441b\",\n        \"size\": 233881176\n    },\n    \"VehicleTurningRoute_Town12_Route9659_Weather8.tar.gz\": {\n        \"sha256\": \"2c7fd93e8fe3f205e21808eff4bad5a495972c3fe4ac697551264ab5d69d3ac1\",\n        \"size\": 102812636\n    },\n    \"VehicleTurningRoute_Town12_Route9660_Weather9.tar.gz\": {\n        \"sha256\": \"8da1131981a82ee4bcadf9872951251c3e5ae3a8fddbdc5e99c82aba4a58f176\",\n        \"size\": 267109726\n    },\n    \"VehicleTurningRoute_Town12_Route9662_Weather19.tar.gz\": {\n        \"sha256\": \"2166621fd084726e0cdcfdc25522fd61a84579b9ab0b75851f7ac1cbcf6ca2b1\",\n        \"size\": 211575188\n    },\n    \"VehicleTurningRoute_Town12_Route9664_Weather21.tar.gz\": {\n        \"sha256\": \"e7861aa7a1b0b9364a52411419d5f2560b5671314e7b5c33363d61356c350b29\",\n        \"size\": 507215916\n    },\n    \"VehicleTurningRoute_Town12_Route9666_Weather23.tar.gz\": {\n        \"sha256\": \"e8dfa2ce866ce192ecac88c1d7a7c6a23c5acd0a31db6253b8723c669705f8da\",\n        \"size\": 374388674\n    },\n    \"VehicleTurningRoute_Town12_Route9667_Weather23.tar.gz\": {\n        \"sha256\": \"9d34fa1e127da4e71ae8622001c407b6e4f6b64f19c44fa80818ca5e39dfbfee\",\n        \"size\": 476394474\n    },\n    \"VehicleTurningRoute_Town12_Route9668_Weather25.tar.gz\": {\n        \"sha256\": \"28a46a703b57a06bca5b8a6faf5c59af0d99ec3770b2a0af5506f21caf84ecae\",\n        \"size\": 155903049\n    },\n    \"VehicleTurningRoute_Town12_Route9669_Weather0.tar.gz\": {\n        \"sha256\": \"3831c28156dcf92612501053a8beb6141ecf3143dc5c99b8b1e3482f4a5dab55\",\n        \"size\": 581259110\n    },\n    \"VehicleTurningRoute_Town12_Route9671_Weather2.tar.gz\": {\n        \"sha256\": \"a53b3a1d002767fcb8921fc5220d9486859c8bbe7a06edc822531dae18f4c74f\",\n        \"size\": 268774237\n    },\n    \"VehicleTurningRoute_Town12_Route9675_Weather6.tar.gz\": {\n        \"sha256\": \"2945884ba6424f4006543ec21ad94de075a69a7ca8891bf67473a63606a1c861\",\n        \"size\": 471115642\n    },\n    \"VehicleTurningRoute_Town12_Route9679_Weather10.tar.gz\": {\n        \"sha256\": \"a3a0c55870f9ae0d42432152e5a1fad426038140e294f23cb2461b7d468c357a\",\n        \"size\": 93607140\n    },\n    \"VehicleTurningRoute_Town12_Route9682_Weather13.tar.gz\": {\n        \"sha256\": \"4b475c8c79ce491342faa2f8537846c005ed5829aa6250a5b75b6c6d698c176a\",\n        \"size\": 199307504\n    },\n    \"VehicleTurningRoute_Town12_Route9683_Weather14.tar.gz\": {\n        \"sha256\": \"7c3b5957213450f1c817ace1cc0403c3e6047801bf4c2ca08474a0113598ab6a\",\n        \"size\": 557310574\n    },\n    \"VehicleTurningRoute_Town12_Route9684_Weather15.tar.gz\": {\n        \"sha256\": \"3a090857012976ea5f6d0129cb7de5629391304980ae64e0f2e8b39419de3354\",\n        \"size\": 260611417\n    },\n    \"VehicleTurningRoute_Town12_Route9685_Weather8.tar.gz\": {\n        \"sha256\": \"765f85f8ee0603009100e1bd3cecfa5ff752e920e0f3a23dc5d22db7236f666c\",\n        \"size\": 528133569\n    },\n    \"VehicleTurningRoute_Town12_Route9688_Weather19.tar.gz\": {\n        \"sha256\": \"bccb95597661801cdf31a35dd58ade7f38cb3a07e17967c57303bbb6cbb86525\",\n        \"size\": 199831263\n    },\n    \"VehicleTurningRoute_Town12_Route9689_Weather20.tar.gz\": {\n        \"sha256\": \"236a733a66ef7712bd36fba747746c7d349156d955aee154ca04661223e23090\",\n        \"size\": 529625038\n    },\n    \"VehicleTurningRoute_Town12_Route9690_Weather21.tar.gz\": {\n        \"sha256\": \"64beffd3da564daadcc431bddd51290db3eba70016cf82cb92eaa4d269851273\",\n        \"size\": 524119323\n    },\n    \"VehicleTurningRoute_Town12_Route9692_Weather23.tar.gz\": {\n        \"sha256\": \"f5beb7c9a0ef789bfc01f95487de598816c997f7657358d9ff4723d493f754a6\",\n        \"size\": 502421496\n    },\n    \"VehicleTurningRoute_Town12_Route9694_Weather25.tar.gz\": {\n        \"sha256\": \"ec378e51afc285a4fd3648a1b2fd66b4538472bd874d11e51b9da917c3b37a99\",\n        \"size\": 516931396\n    },\n    \"VehicleTurningRoute_Town12_Route9695_Weather0.tar.gz\": {\n        \"sha256\": \"b327f06ec78d869d6dcfdcfb7de00d6970b25b80d76210c8e581500a21309691\",\n        \"size\": 132056444\n    },\n    \"VehicleTurningRoute_Town12_Route9696_Weather1.tar.gz\": {\n        \"sha256\": \"aff77a697c4aca085152cf743b090340d65e0e8d329ffbd2944167f4ea74c015\",\n        \"size\": 271699329\n    },\n    \"VehicleTurningRoute_Town12_Route9697_Weather2.tar.gz\": {\n        \"sha256\": \"ec9717d94a6382686d5cb7491e463fc33e7c88ec0fe6e8016ead4e1f14717b48\",\n        \"size\": 452584667\n    },\n    \"VehicleTurningRoute_Town12_Route9698_Weather3.tar.gz\": {\n        \"sha256\": \"4c8f00aed0719ee49cfbf1329af05c6f0ce54862f17e5b04ac39a440b9d4844d\",\n        \"size\": 379367181\n    },\n    \"VehicleTurningRoute_Town12_Route9699_Weather3.tar.gz\": {\n        \"sha256\": \"1c9b346c630a776e7ee0e433950551157daa478afb03c13dc363fe0c451c535a\",\n        \"size\": 337057771\n    },\n    \"VehicleTurningRoute_Town12_Route9700_Weather5.tar.gz\": {\n        \"sha256\": \"ec0c34254a6fc82643fde1aef19e935b061c6e64707592487d3764e438d031e4\",\n        \"size\": 300412848\n    },\n    \"VehicleTurningRoute_Town12_Route9701_Weather6.tar.gz\": {\n        \"sha256\": \"3c01abdd7b007f312b577507cde8cb6e57fd630837bbadd98a7c90c7a248031f\",\n        \"size\": 172059504\n    },\n    \"VehicleTurningRoute_Town12_Route9702_Weather7.tar.gz\": {\n        \"sha256\": \"25f7ccdea0c83751e4c116146e730c63bce34065511883bb5bb4faf5e07585ee\",\n        \"size\": 553354844\n    },\n    \"VehicleTurningRoute_Town12_Route9704_Weather9.tar.gz\": {\n        \"sha256\": \"37d7034b02bfae6926116d4353794ac0e82dc9ed851aece072671a9c177b24d1\",\n        \"size\": 386177264\n    },\n    \"VehicleTurningRoute_Town12_Route9707_Weather12.tar.gz\": {\n        \"sha256\": \"8129e19db327443d03625c1745f8d069a5111b3689337eeb660d475ec01b9900\",\n        \"size\": 289895719\n    },\n    \"VehicleTurningRoute_Town12_Route9709_Weather14.tar.gz\": {\n        \"sha256\": \"91d5ccd1cbe246c3a5211fdda4d83fdcd52b352b7831fa949c29e44e09cde420\",\n        \"size\": 83660295\n    },\n    \"VehicleTurningRoute_Town12_Route9710_Weather15.tar.gz\": {\n        \"sha256\": \"e802212eab4fa458478a60ad85b918d912f91ee73b2c1945ff9b69cb31709a21\",\n        \"size\": 291257831\n    },\n    \"VehicleTurningRoute_Town12_Route9712_Weather9.tar.gz\": {\n        \"sha256\": \"0e6c9e75b47b405db084429d2a5a8ea3039661fc0b60bb8f498845c00501bee1\",\n        \"size\": 378213244\n    },\n    \"VehicleTurningRoute_Town12_Route9714_Weather19.tar.gz\": {\n        \"sha256\": \"41a23189cea9e365108ab8ffb69a6485f7c5d6410855f59fbfe7ad294905ffd7\",\n        \"size\": 106649238\n    },\n    \"VehicleTurningRoute_Town12_Route9717_Weather22.tar.gz\": {\n        \"sha256\": \"1b524b39fc8a176cf438b1d7f3e00bc8fbab8dd20934745d67609824bd015f93\",\n        \"size\": 160994275\n    },\n    \"VehicleTurningRoute_Town12_Route9718_Weather23.tar.gz\": {\n        \"sha256\": \"e8aeb4ecab167e4861aaed387a1ac8c3c86b3fdd1109851876b7cb297e766426\",\n        \"size\": 499121886\n    },\n    \"VehicleTurningRoute_Town12_Route9719_Weather23.tar.gz\": {\n        \"sha256\": \"3b200be093f1cdb6db07551a5e0efbbec2e387becdd8d7c4aca0f912dee6e8d9\",\n        \"size\": 178524663\n    },\n    \"VehicleTurningRoute_Town12_Route9720_Weather25.tar.gz\": {\n        \"sha256\": \"879442ca2f51156be8975399d0408404b95b99fae0ab29961cec1b51240ea18c\",\n        \"size\": 293632723\n    },\n    \"VehicleTurningRoute_Town12_Route9721_Weather0.tar.gz\": {\n        \"sha256\": \"913d261406a06adea5a1e9b7b9243f8f198da9ccc24875a580a7c3d07ffb0196\",\n        \"size\": 312716327\n    },\n    \"VehicleTurningRoute_Town12_Route9722_Weather1.tar.gz\": {\n        \"sha256\": \"020e6ea81800c0253e98a754700fcf5fe76dc6ca756c519a7563be4429ab624e\",\n        \"size\": 320043427\n    },\n    \"VehicleTurningRoute_Town12_Route9724_Weather3.tar.gz\": {\n        \"sha256\": \"7b286a3a632354b11e46319d020902e103d421d636b0540cf01e24bf80e21f0b\",\n        \"size\": 181937593\n    },\n    \"VehicleTurningRoute_Town12_Route9725_Weather3.tar.gz\": {\n        \"sha256\": \"00dbdfc94171f86a119b7fdc386e32b9706e52aa792c3baa185dd7ec0e39e9d8\",\n        \"size\": 331832948\n    },\n    \"VehicleTurningRoute_Town12_Route9726_Weather5.tar.gz\": {\n        \"sha256\": \"3f7a894ed7e5cbca63d40b1c84904aab19024c7f23b15ba475fe4988d70704c1\",\n        \"size\": 426396162\n    },\n    \"VehicleTurningRoute_Town12_Route9727_Weather6.tar.gz\": {\n        \"sha256\": \"2f5115a8b478f06f469640562bb9b6eb7b9ede693fb46b0719ff930c69603d27\",\n        \"size\": 282209401\n    },\n    \"VehicleTurningRoute_Town12_Route9729_Weather8.tar.gz\": {\n        \"sha256\": \"68bb450011f4e81f02a40ddb0231157d70034bab93add57d7ed19c291902c574\",\n        \"size\": 239991641\n    },\n    \"VehicleTurningRoute_Town12_Route9730_Weather9.tar.gz\": {\n        \"sha256\": \"13d83da37f2b3ee7a3e04689dc04e139c304d4a72eb6c65e1e63396eb3a3309d\",\n        \"size\": 469329493\n    },\n    \"VehicleTurningRoute_Town12_Route9736_Weather15.tar.gz\": {\n        \"sha256\": \"6ad2eefe80559c6072c35fac5bdaea40255393b48f2ea3288e41a5e89934b783\",\n        \"size\": 497816318\n    },\n    \"VehicleTurningRoute_Town12_Route9737_Weather8.tar.gz\": {\n        \"sha256\": \"53054dec7ab80f090e1a3960e133e174fab07bde7bac75189c1570fb2abf5078\",\n        \"size\": 417085281\n    },\n    \"VehicleTurningRoute_Town12_Route9738_Weather9.tar.gz\": {\n        \"sha256\": \"71a83427f01a5372b1a2733b4de8250749482641af2b53f4404ea19353160ad5\",\n        \"size\": 230266298\n    },\n    \"VehicleTurningRoute_Town12_Route9740_Weather19.tar.gz\": {\n        \"sha256\": \"da97631303fc5e11878c5d977b2ccaa8053078aae11b3a6a04699ec7522cf4b9\",\n        \"size\": 488186054\n    },\n    \"VehicleTurningRoute_Town12_Route9741_Weather20.tar.gz\": {\n        \"sha256\": \"fa611a4bbe427001e50a8aaa7f3ad9b9113d7a7d171280fd50ae1ed44eca9c5c\",\n        \"size\": 113685500\n    },\n    \"VehicleTurningRoute_Town12_Route9742_Weather21.tar.gz\": {\n        \"sha256\": \"094f423148105e611aedcfea2fa3e4745d11acc1d82421f8e46db32254252b12\",\n        \"size\": 260807932\n    },\n    \"VehicleTurningRoute_Town12_Route9743_Weather22.tar.gz\": {\n        \"sha256\": \"cb698a6eb6994bc69169c3796b9d79eb9fe68af7ba30c37e9dcca0a23ee2df80\",\n        \"size\": 411163857\n    },\n    \"VehicleTurningRoute_Town12_Route9744_Weather23.tar.gz\": {\n        \"sha256\": \"a857f7d83753e52c1b983521d9bc23462d2aec44690b62f8948816754a7091fc\",\n        \"size\": 226745011\n    },\n    \"VehicleTurningRoute_Town12_Route9745_Weather23.tar.gz\": {\n        \"sha256\": \"0a4d7464492a8c58c4a340f1558abc2be3fd234ac34afcb0f1698eb0d50a76ea\",\n        \"size\": 604108152\n    },\n    \"VehicleTurningRoute_Town12_Route9748_Weather1.tar.gz\": {\n        \"sha256\": \"9bc7c2e0159f74791ffe41ab067d51769dfbc9d68e93ebfa90f32faf8d4305f9\",\n        \"size\": 675504271\n    },\n    \"VehicleTurningRoute_Town12_Route9753_Weather6.tar.gz\": {\n        \"sha256\": \"4b12bf4a425ddca38d8271c9aa2d6f60584b6b3721ed6a296291a1bc60e565eb\",\n        \"size\": 186975135\n    },\n    \"VehicleTurningRoute_Town12_Route9754_Weather7.tar.gz\": {\n        \"sha256\": \"995257072000c8dca0451f00637f9356ff3cb74ed917e7a590ca77c921e6c910\",\n        \"size\": 369364579\n    },\n    \"VehicleTurningRoute_Town12_Route9756_Weather9.tar.gz\": {\n        \"sha256\": \"900ee8f878531fb6ef2cbc3309b08889b89beb645bdf6262f9e172da794a61ea\",\n        \"size\": 247819686\n    },\n    \"VehicleTurningRoute_Town12_Route9760_Weather13.tar.gz\": {\n        \"sha256\": \"0eb9ec6191bdf48a3466a99aa14c615d5dfdb5bdd4e4ad0e0695d058e40fdc89\",\n        \"size\": 260383863\n    },\n    \"VehicleTurningRoute_Town12_Route9761_Weather14.tar.gz\": {\n        \"sha256\": \"1d5a0deed7ac91309074e5f342c00dcf5d471333922dfa467de0da3e2b585ea7\",\n        \"size\": 230257669\n    },\n    \"VehicleTurningRoute_Town12_Route9762_Weather15.tar.gz\": {\n        \"sha256\": \"b827885888814ecda3aea308d9a4e2222b5c4132bfac99017c39acd2f4a487dc\",\n        \"size\": 266854004\n    },\n    \"VehicleTurningRoute_Town12_Route9763_Weather8.tar.gz\": {\n        \"sha256\": \"80230bf237fbde32ce4bf9091ef38e9514ed6a6ade8b18e854b84ace6bd27068\",\n        \"size\": 87716522\n    },\n    \"VehicleTurningRoute_Town12_Route9764_Weather9.tar.gz\": {\n        \"sha256\": \"d3357c3e584f2930c878a4d6528be33bb7ec6f72abb140104cce49454c7939e5\",\n        \"size\": 136330572\n    },\n    \"VehicleTurningRoute_Town12_Route9765_Weather18.tar.gz\": {\n        \"sha256\": \"26fd7a961b34ab396f84eda3852801995954cd99368fa779518a1597c97a0109\",\n        \"size\": 407384054\n    },\n    \"VehicleTurningRoute_Town12_Route9768_Weather21.tar.gz\": {\n        \"sha256\": \"35a506db56e6a41ebf2213b6ebff00e9162ce8e8b2d55bfcbacbc4cfefe9f8f2\",\n        \"size\": 562003467\n    },\n    \"VehicleTurningRoute_Town12_Route9769_Weather22.tar.gz\": {\n        \"sha256\": \"df6099f5c968b41fb18b4a787ef1fa4d7f3854325b47581628d34172c02d2c0a\",\n        \"size\": 155811141\n    },\n    \"VehicleTurningRoute_Town12_Route9770_Weather23.tar.gz\": {\n        \"sha256\": \"527804e325739336e5ffb96120ddabc63b54d5415f321688a689359279dca9ad\",\n        \"size\": 179615488\n    },\n    \"VehicleTurningRoute_Town12_Route9775_Weather2.tar.gz\": {\n        \"sha256\": \"0f6de9d74f69e316cfda057e3b46890781d6ab01df96d46a934901eb1f052ce9\",\n        \"size\": 122632732\n    },\n    \"VehicleTurningRoute_Town12_Route9776_Weather3.tar.gz\": {\n        \"sha256\": \"c2219a6f0efb3ce0bb4395651697ae3b37ca0d85dd3793200ae6522479308032\",\n        \"size\": 337498241\n    },\n    \"VehicleTurningRoute_Town12_Route9777_Weather3.tar.gz\": {\n        \"sha256\": \"987344ca79b1c97119c58d7c7e98f2dbed230a6259960e1416d278a81db93106\",\n        \"size\": 362448604\n    },\n    \"VehicleTurningRoute_Town12_Route9780_Weather7.tar.gz\": {\n        \"sha256\": \"716bb3dad9df9c8ab0478657ad64792422fd1383f313e472db0e7a68de98f320\",\n        \"size\": 116869409\n    },\n    \"VehicleTurningRoute_Town12_Route9781_Weather8.tar.gz\": {\n        \"sha256\": \"87015def58b55efb67c965c34c5507e074d451eda10a530d64f59c788ac31e1e\",\n        \"size\": 388803880\n    },\n    \"VehicleTurningRoute_Town12_Route9784_Weather11.tar.gz\": {\n        \"sha256\": \"f94c95d94063a1ae5c8de8a5101e3842b1e1f9694d544bd1ad012e8dc3cbab19\",\n        \"size\": 212976822\n    },\n    \"VehicleTurningRoute_Town12_Route9785_Weather12.tar.gz\": {\n        \"sha256\": \"18b1f03dc884f93c5d75f3979bdc123ead820ae445fde092600956f56dfd773e\",\n        \"size\": 117723012\n    },\n    \"VehicleTurningRoute_Town12_Route9786_Weather13.tar.gz\": {\n        \"sha256\": \"bebc5a708c52dde45d5f380214cd50d388aec7cec41f990bbe41c04202663a46\",\n        \"size\": 236928873\n    },\n    \"VehicleTurningRoute_Town12_Route9787_Weather14.tar.gz\": {\n        \"sha256\": \"e8c4d28a2e8d25f7de57239de07e8a6da1832d2b7f52388dace2b85a7b961c95\",\n        \"size\": 295672296\n    },\n    \"VehicleTurningRoute_Town12_Route9789_Weather8.tar.gz\": {\n        \"sha256\": \"d09de30e6120a6b36e4dcd5276605a8215cb66ae292c133d5029f116e9b44974\",\n        \"size\": 97930520\n    },\n    \"VehicleTurningRoute_Town12_Route9790_Weather9.tar.gz\": {\n        \"sha256\": \"13c220c985d50fc6ba291811221d32d629b82cab4664065b67b632ca95ba9ef2\",\n        \"size\": 680529561\n    }\n}"
  },
  {
    "path": "close_loop/VAD_MomAD/docs/bench2drive_mini_10.json",
    "content": "{\n    \"AccidentTwoWays_Town12_Route1444_Weather0.tar.gz\": {\n        \"sha256\": \"2690cb0053a2e9208f50f9d48c4a1c5befae4179c07e6fb8f06dc4434fb82178\",\n        \"size\": 341845960\n    },\n    \"Accident_Town03_Route156_Weather0.tar.gz\": {\n        \"sha256\": \"09780cfaae07b13f65f11addfffbda8dea7723a6dfbbe0b49f493303805d24fa\",\n        \"size\": 264497958\n    },\n    \"ConstructionObstacle_Town05_Route68_Weather8.tar.gz\": {\n        \"sha256\": \"7a1e93168780f5dc4d38b6b5b357e74a62736c935adc3fa74b1ed35028c61e76\",\n        \"size\": 287017092\n    },\n    \"ControlLoss_Town11_Route401_Weather11.tar.gz\": {\n        \"sha256\": \"9e3abe0c9b25f0e50e597ac0f62a5cf681acd9631e439b23cabac77b85355043\",\n        \"size\": 99078817\n    },\n    \"DynamicObjectCrossing_Town02_Route13_Weather6.tar.gz\": {\n        \"sha256\": \"b040f5993726dfb3a1dc1aaf5e2e4f93404a0124272d6f47f2469fca53ca25f2\",\n        \"size\": 280176944\n    },\n    \"HardBreakRoute_Town01_Route30_Weather3.tar.gz\": {\n        \"sha256\": \"2f6593d05e288a88cf37d8043d1e448842a4b1ceaed5544fe13100c174a4cb04\",\n        \"size\": 426576889\n    },\n    \"OppositeVehicleTakingPriority_Town13_Route600_Weather2.tar.gz\": {\n        \"sha256\": \"757a8e7415081447c2d172592723de194b05ad3fb9416e9fc215844e1dac58dc\",\n        \"size\": 177697783\n    },\n    \"ParkedObstacle_Town10HD_Route371_Weather7.tar.gz\": {\n        \"sha256\": \"78464d659875f8b2bc5901c763bc9ba154c3eaf021196f4d6077d9ef17c705e4\",\n        \"size\": 264725091\n    },\n    \"VehicleTurningRoute_Town15_Route443_Weather1.tar.gz\": {\n        \"sha256\": \"97a066963571c10fd91ec0ee45bd5fc598e79ea2f1cf153e8617887ad83b2b5a\",\n        \"size\": 487312838\n    },\n    \"YieldToEmergencyVehicle_Town04_Route165_Weather7.tar.gz\": {\n        \"sha256\": \"feb52345f09a5358728dd2ed32db93cf64a5d2b0d04d4719a38d408c60c212df\",\n        \"size\": 183804370\n    }\n}"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/.pylintrc",
    "content": "[MESSAGES CONTROL]\nmax-line-length=120\ndisable=no-self-use,anomalous-backslash-in-string,too-many-arguments,too-few-public-methods,too-many-instance-attributes,redefined-variable-type,unused-argument,wildcard-import,unused-wildcard-import,bare-except,broad-except,bad-continuation,too-many-lines,too-many-branches,locally-disabled,too-many-locals,too-many-statements,duplicate-code,too-many-nested-blocks,fixme\nignored-modules=carla,carla.command\nvariable-rgx=[a-z0-9_]{1,40}$\nfunction-rgx=[a-z0-9_]{1,40}$\nextension-pkg-whitelist=cv2,pygame,numpy"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/CHANGELOG.md",
    "content": "## Latest changes\n\n* Added support to ROS agents, which are meant to inherit from the new `ROS1Agent` and `ROS2Agent` agents. The old `RosAgent` has been deleted.\n* Improved the format of the printed runtime information\n* Added optional side mirrors to the hyman agent\n* Improved the performance of the routes by initializing the scenarios during runtime\n* Improved result writer output, in the same wasy as ScenarioRunner's one.\n* Improved the initialization and cleanup of the Leaderboard.\n* Improved the robustness of the resuming functionality\n* Improved the example Dockerfile and added new example for ROS based agents\n* Added new utility scripts:\n    - merge_statistics.py: join two or more json results into one\n    - route_creator.py: simplifies the creation of new routes\n    - route_displayer.py: parse and debug route xml files from inside the simulator\n    - route_summarizer.py: parses the route xml file into a table.\n    - scenario_creator.py: uses the spectator and terminal inputs to automatically add scenarios to a route\n    - scenario_orderer.py: modifies the scenarios part of the route file to be ordered according to their route's position\n    - weather_creator.py: gets the current simulation's weather in the route format for easy copy.\n* The `StatisticsManager` class has been remade to add robustness, remove unneeded complexity and hardcoded values. Its interaction with other classes has remained unchanged\n* Routes have had the same changed as the ones in ScenarioRunner\n* Added parked vehicles to the routes. These are parsed from a file with all their possible positions.\n* Added new arguments to the leaderboard:\n    - `routes-subset` allows to run part of the routes. Use `-` to run groups of routes (i.e `0-4`), `,` to run specific routes (i.e `1,6,8,14`), or a combination of the two (i.e `0-2,5,8-10`).\n    - `debug-checkpoint` defines the endpoint of the live results, created when the `debug` argument is 2 or higher.\n* Added support for traffic manager hybrid mode.\n* Added a new attribute to the global statistics, *scores_std_dev*, which calculates the standard deviation of the scores done throughout the simulation.\n* Fixed bug causing the global infractions to not be correctly calculated\n\n* Creating stable version for the CARLA online leaderboard\n* Initial creation of the repository\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/LICENSE",
    "content": "MIT License\n\nCopyright (c) 2019 CARLA\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/README.md",
    "content": "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.\n\nAutonomous 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.\n\nAgents will face multiple traffic situations based in the NHTSA typology, such as:\n\n* Lane merging\n* Lane changing\n* Negotiations at traffic intersections\n* Negotiations at roundabouts\n* Handling traffic lights and traffic signs\n* Coping with pedestrians, cyclists and other elements\n\nThe 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.\n\nMore information can be found [here](https://leaderboard.carla.org/)"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/Gemfile",
    "content": "source \"https://rubygems.org\"\n\ngem \"jekyll\", \"~> 3.8.5\"\n\ngroup :jekyll_plugins do\n  gem \"jekyll-feed\", \"~> 0.6\"\n  gem \"jekyll-paginate\", \"~> 1.1.0\"\n  gem \"jekyll-sitemap\"\nend\n\n# Windows does not include zoneinfo files, so bundle the tzinfo-data gem\ngem \"tzinfo-data\", platforms: [:mingw, :mswin, :x64_mingw, :jruby]\n\n# Performance-booster for watching directories on Windows\ngem \"wdm\", \"~> 0.1.0\" if Gem.win_platform?\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/LICENSE",
    "content": "The MIT License (MIT)\n\nCopyright (c) 2013-2019 Blackrock Digital LLC\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in\nall copies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN\nTHE SOFTWARE.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/README.md",
    "content": "## Welcome to GitHub Pages\n\nYou can use the [editor on GitHub](https://github.com/carla-simulator/leaderboard/edit/master/README.md) to maintain and preview the content for your website in Markdown files.\n\nWhenever you commit to this repository, GitHub Pages will run [Jekyll](https://jekyllrb.com/) to rebuild the pages in your site, from the content in your Markdown files.\n\n### Markdown\n\nMarkdown is a lightweight and easy-to-use syntax for styling your writing. It includes conventions for\n\n```markdown\nSyntax highlighted code block\n\n# Header 1\n## Header 2\n### Header 3\n\n- Bulleted\n- List\n\n1. Numbered\n2. List\n\n**Bold** and _Italic_ and `Code` text\n\n[Link](url) and ![Image](src)\n```\n\nFor more details see [GitHub Flavored Markdown](https://guides.github.com/features/mastering-markdown/).\n\n### Jekyll Themes\n\nYour Pages site will use the layout and styles from the Jekyll theme you have selected in your [repository settings](https://github.com/carla-simulator/leaderboard/settings). The name of this theme is saved in the Jekyll `_config.yml` configuration file.\n\n### Support or Contact\n\nHaving trouble with Pages? Check out our [documentation](https://help.github.com/categories/github-pages-basics/) or [contact support](https://github.com/contact) and we’ll help you sort it out.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_config.yml",
    "content": "title:              CARLA Leaderboard\nemail:              carla.simulator@gmail.com\ndescription:        CARLA Autonomous Driving competition\nauthor:             CARLA Team\nbaseurl:            \"\"\nurl:                https://leaderboard.carla.org/\n\n# Social Profiles\ngithub_username:   carla-simulator\ntwitter_username:  carlasimulator\ndiscord_invite:    8kqACuC\nyoutube_channel:   UC1llP9ekCwt8nEJzMJBQekg\n\ntwitter:\n  username: carlasimulator\n\nsocial:\n  name: CARLA Simulator\n  links:\n    - https://github.com/carla-simulator/carla\n    - https://twitter.com/carlasimulator\n    - https://discord.gg/8kqACuC\n    - https://www.youtube.com/channel/UC1llP9ekCwt8nEJzMJBQekg\n\n# Build settings\nmarkdown:           kramdown\npaginate:           5\npaginate_path:      \"/posts/page:num/\"\nplugins:\n  - jekyll-feed\n  - jekyll-paginate\n  - jekyll-sitemap ## Uncomment this line to silently generate a sitemaps.org compliant sitemap for your Jekyll site\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_includes/footer.html",
    "content": "<!-- Footer -->\n\n<hr>\n\n<footer>\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n        <ul class=\"list-inline text-center\">\n          {% if site.email %}\n          <li class=\"list-inline-item\">\n            <a href=\"mailto:{{ site.email | encode_email }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"far fa-envelope fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.twitter_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://twitter.com/{{ site.twitter_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-twitter fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.facebook_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://www.facebook.com/{{ site.facebook_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-facebook-f fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.linkedin_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://www.linkedin.com/in/{{ site.linkedin_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-linkedin fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n          {% if site.github_username %}\n          <li class=\"list-inline-item\">\n            <a href=\"https://github.com/{{ site.github_username }}\">\n              <span class=\"fa-stack fa-lg\">\n                <i class=\"fas fa-circle fa-stack-2x\"></i>\n                <i class=\"fab fa-github fa-stack-1x fa-inverse\"></i>\n              </span>\n            </a>\n          </li>\n          {% endif %}\n        </ul>\n        <p class=\"copyright text-muted\">Copyright &copy; {{ site.author }} {{ 'now' | date: \"%Y\" }}</p>\n      </div>\n    </div>\n  </div>\n</footer>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_includes/google-analytics.html",
    "content": "<!-- Global site tag (gtag.js) - Google Analytics -->\n<script async src=\"https://www.googletagmanager.com/gtag/js?id={{ site.google_analytics }}\"></script>\n<script>\n  window.dataLayer = window.dataLayer || [];\n  function gtag(){dataLayer.push(arguments);}\n  gtag('js', new Date());\n\n  gtag('config', '{{ site.google_analytics }}');\n</script>\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_includes/head.html",
    "content": "<head>\n\n  <meta charset=\"utf-8\">\n  <meta name=\"viewport\" content=\"width=device-width, initial-scale=1, shrink-to-fit=no\">\n\n  <title>\n    {% if page.title %}{{ page.title | escape }} - {{ site.title | escape }}\n    {% else %}{{ site.title | escape }}{% endif %}\n  </title>\n\n  <meta name=\"description\" content=\"{{ page.excerpt | default: site.description | strip_html | normalize_whitespace | truncate: 160 | escape }}\">\n\n  <link href='https://fonts.googleapis.com/css?family=Lora:400,700,400italic,700italic' rel='stylesheet' type='text/css'>\n  <link href='https://fonts.googleapis.com/css?family=Open+Sans:300italic,400italic,600italic,700italic,800italic,400,300,600,700,800' rel='stylesheet' type='text/css'>\n\n  <link rel=\"stylesheet\" href=\"{{\"/assets/vendor/bootstrap/css/bootstrap.min.css\" | relative_url }}\">\n\n  <link rel=\"stylesheet\" href=\"{{\"/assets/vendor/fontawesome-free/css/all.min.css\" | relative_url }}\">\n\n  <link rel=\"stylesheet\" href=\"{{\"/assets/main.css\" | relative_url }}\">\n  <link rel=\"canonical\" href=\"{{ page.url | replace:'index.html','' | absolute_url }}\">\n  <link rel=\"alternate\" type=\"application/rss+xml\" title=\"{{ site.title | escape }}\" href=\"{{ \"/feed.xml\" | relative_url }}\">\n\n</head>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_includes/navbar.html",
    "content": "<!-- Navigation -->\n<nav class=\"navbar navbar-expand-lg navbar-light fixed-top\" id=\"mainNav\">\n  <div class=\"container\">\n    <a class=\"navbar-brand\" href=\"{{\"/\" | relative_url }}\">{{ site.title | escape }}</a>\n    <button class=\"navbar-toggler navbar-toggler-right\" type=\"button\" data-toggle=\"collapse\" data-target=\"#navbarResponsive\" aria-controls=\"navbarResponsive\" aria-expanded=\"false\" aria-label=\"Toggle navigation\">\n      Menu\n      <i class=\"fa fa-bars\"></i>\n    </button>\n    <div class=\"collapse navbar-collapse\" id=\"navbarResponsive\">\n      <ul class=\"navbar-nav ml-auto\">\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{\"/\" | relative_url }}\">Home</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{\"/get_started\" | relative_url }}\">Getting started</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{ \"/submit\" | relative_url }}\">Submit</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{ \"/leaderboard\" | relative_url }}\">Leaderboard</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" target=\"_blank\" href=\"https://github.com/carla-simulator/leaderboard\">GitHub</a>\n        </li>\n        <li class=\"nav-item\">\n          <a class=\"nav-link\" href=\"{{\"/contact\" | relative_url }}\">About</a>\n        </li>\n      </ul>\n    </div>\n  </div>\n</nav>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_includes/read_time.html",
    "content": "<span class=\"reading-time\" title=\"Estimated read time\">\n  {% assign words = include.content | number_of_words %}\n  {% if words < 270 %} 1 min {% else %} {{ words | divided_by:135 }} mins {% endif %} read </span>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_includes/scripts.html",
    "content": "<script src=\"{{\"/assets/vendor/jquery/jquery.min.js\" | relative_url }}\"></script>\n<script src=\"{{\"/assets/vendor/bootstrap/js/bootstrap.bundle.min.js\" | relative_url }}\"></script>\n<script src=\"{{\"/assets/vendor/startbootstrap-clean-blog/js/clean-blog.min.js\" | relative_url }}\"></script>\n\n<script src=\"{{\"/assets/scripts.js\" | relative_url }}\"></script>\n\n{% if page.url contains 'contact' %}\n  <!-- Form Validation -->\n  <script src=\"{{\"/assets/vendor/startbootstrap-clean-blog/js/jqBootstrapValidation.js\" | relative_url }}\"></script>\n  <!-- Send Form -->\n  <script>\n    $(function () {\n\n      $(\"#contactForm input,#contactForm textarea\").jqBootstrapValidation({\n        preventSubmit: true,\n        submitError: function ($form, event, errors) {\n          // additional error messages or events\n        },\n        submitSuccess: function ($form, event) {\n          event.preventDefault(); // prevent default submit behaviour\n          // get values from FORM\n          var name = $(\"input#name\").val();\n          var email = $(\"input#email\").val();\n          var phone = $(\"input#phone\").val();\n          var message = $(\"textarea#message\").val();\n          var firstName = name; // For Success/Failure Message\n          // Check for white space in name for Success/Fail message\n          if (firstName.indexOf(' ') >= 0) {\n            firstName = name.split(' ').slice(0, -1).join(' ');\n          }\n          $this = $(\"#sendMessageButton\");\n          $this.prop(\"disabled\", true); // Disable submit button until AJAX call is complete to prevent duplicate messages\n          $.ajax({\n            url: \"//formspree.io/{{ site.email }}\",\n            type: \"POST\",\n            data: {\n              name: name,\n              phone: phone,\n              email: email,\n              message: message\n            },\n            cache: false,\n            success: function () {\n              // Success message\n              $('#success').html(\"<div class='alert alert-success'>\");\n              $('#success > .alert-success').html(\"<button type='button' class='close' data-dismiss='alert' aria-hidden='true'>&times;\").append(\"</button>\");\n              $('#success > .alert-success').append(\"<strong>Your message has been sent. </strong>\");\n              $('#success > .alert-success').append('</div>');\n              //clear all fields\n              $('#contactForm').trigger(\"reset\");\n            },\n            error: function () {\n              // Fail message\n              $('#success').html(\"<div class='alert alert-danger'>\");\n              $('#success > .alert-danger').html(\"<button type='button' class='close' data-dismiss='alert' aria-hidden='true'>&times;\").append(\"</button>\");\n              $('#success > .alert-danger').append($(\"<strong>\").text(\"Sorry \" + firstName + \", it seems that my mail server is not responding. Please try again later!\"));\n              $('#success > .alert-danger').append('</div>');\n              //clear all fields\n              $('#contactForm').trigger(\"reset\");\n            },\n            complete: function () {\n              setTimeout(function () {\n                $this.prop(\"disabled\", false); // Re-enable submit button when AJAX call is complete\n              }, 1000);\n            }\n          });\n        },\n        filter: function () {\n          return $(this).is(\":visible\");\n        }\n      });\n\n      $(\"a[data-toggle=\\\"tab\\\"]\").click(function (e) {\n        e.preventDefault();\n        $(this).tab(\"show\");\n      });\n    });\n\n    /*When clicking on Full hide fail/success boxes */\n    $('#name').focus(function () {\n      $('#success').html('');\n    });\n  </script>\n{% endif %}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_layouts/default.html",
    "content": "<!DOCTYPE html>\n\n<html>\n\n{% include head.html %}\n\n<body>\n\n  {% include navbar.html %}\n\n  {{ content }}\n\n  {% include footer.html %}\n\n  {% include scripts.html %}\n\n  {% include google-analytics.html %}\n\n</body>\n\n</html>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_layouts/home.html",
    "content": "---\nlayout: default\n---\n\n<!-- Page Header -->\n{% if page.background %}\n<header class=\"masthead\" style=\"background-image: url('{{ page.background | prepend: site.baseurl | replace: '//', '/' }}')\">\n  {% else %}\n  <header class=\"masthead\">\n    {% endif %}\n    <div class=\"overlay\"></div>\n    <div class=\"container\">\n      <div class=\"row\">\n        <div class=\"col-lg-8 col-md-10 mx-auto\">\n          <div class=\"page-heading\">\n            \n          </div>\n        </div>\n      </div>\n    </div>\n  </header>\n\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n\n        {{ content }}\n\n      </div>\n    </div>\n  </div>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_layouts/page.html",
    "content": "---\nlayout: default\n---\n\n<!-- Page Header -->\n{% if page.background %}\n<header class=\"masthead\" style=\"background-image: url('{{ page.background | prepend: site.baseurl | replace: '//', '/' }}')\">\n  {% else %}\n  <header class=\"masthead\">\n    {% endif %}\n    <div class=\"overlay\"></div>\n    <div class=\"container\">\n      <div class=\"row\">\n        <div class=\"col-lg-8 col-md-10 mx-auto\">\n          <div class=\"page-heading\">\n            <h1>{{ page.title }}</h1>\n            {% if page.description %}\n            <span class=\"subheading\">{{ page.description }}</span>\n            {% endif %}\n          </div>\n        </div>\n      </div>\n    </div>\n  </header>\n\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n\n        {{ content }}\n\n      </div>\n    </div>\n  </div>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_layouts/post.html",
    "content": "---\nlayout: default\n---\n\n<!-- Page Header -->\n{% if page.background %}\n<header class=\"masthead\" style=\"background-image: url('{{ page.background | prepend: site.baseurl | replace: '//', '/' }}')\">\n  {% else %}\n  <header class=\"masthead\">\n    {% endif %}\n    <div class=\"overlay\"></div>\n    <div class=\"container\">\n      <div class=\"row\">\n        <div class=\"col-lg-8 col-md-10 mx-auto\">\n          <div class=\"post-heading\">\n            <h1>{{ page.title }}</h1>\n            {% if page.subtitle %}\n            <h2 class=\"subheading\">{{ page.subtitle }}</h2>\n            {% endif %}\n            <span class=\"meta\">Posted by\n              <a href=\"#\">{% if page.author %}{{ page.author }}{% else %}{{ site.author }}{% endif %}</a>\n              on {{ page.date | date: '%B %d, %Y' }} &middot; {% include read_time.html\n              content=page.content %}\n            </span>\n          </div>\n        </div>\n      </div>\n    </div>\n  </header>\n\n  <div class=\"container\">\n    <div class=\"row\">\n      <div class=\"col-lg-8 col-md-10 mx-auto\">\n\n        {{ content }}\n\n        <hr>\n\n        <div class=\"clearfix\">\n\n          {% if page.previous.url %}\n          <a class=\"btn btn-primary float-left\" href=\"{{ page.previous.url | prepend: site.baseurl | replace: '//', '/' }}\" data-toggle=\"tooltip\" data-placement=\"top\" title=\"{{ page.previous.title }}\">&larr; Previous<span class=\"d-none d-md-inline\">\n              Post</span></a>\n          {% endif %}\n          {% if page.next.url %}\n          <a class=\"btn btn-primary float-right\" href=\"{{ page.next.url | prepend: site.baseurl | replace: '//', '/' }}\" data-toggle=\"tooltip\" data-placement=\"top\" title=\"{{ page.next.title }}\">Next<span class=\"d-none d-md-inline\">\n              Post</span> &rarr;</a>\n          {% endif %}\n\n        </div>\n\n      </div>\n    </div>\n  </div>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/_sass/styles.scss",
    "content": "// Import Core Clean Blog SCSS\n@import \"../assets/vendor/startbootstrap-clean-blog/scss/clean-blog.scss\";\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/about.html",
    "content": "---\nlayout: page\ntitle: About us\ndescription: This is what I do.\nbackground: '/img/bg-about.jpg'\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/main.scss",
    "content": "---\n# Only the main Sass file needs front matter (the dashes are enough)\n---\n\n@import \"styles\";\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/scripts.js",
    "content": "$(function () {\n  $('[data-toggle=\"tooltip\"]').tooltip()\n})\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/bootstrap/css/bootstrap.css",
    "content": "/*!\n * Bootstrap v4.3.1 (https://getbootstrap.com/)\n * Copyright 2011-2019 The Bootstrap Authors\n * Copyright 2011-2019 Twitter, Inc.\n * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n */\n:root {\n  --blue: #007bff;\n  --indigo: #6610f2;\n  --purple: #6f42c1;\n  --pink: #e83e8c;\n  --red: #dc3545;\n  --orange: #fd7e14;\n  --yellow: #ffc107;\n  --green: #28a745;\n  --teal: #20c997;\n  --cyan: #17a2b8;\n  --white: #fff;\n  --gray: #6c757d;\n  --gray-dark: #343a40;\n  --primary: #007bff;\n  --secondary: #6c757d;\n  --success: #28a745;\n  --info: #17a2b8;\n  --warning: #ffc107;\n  --danger: #dc3545;\n  --light: #f8f9fa;\n  --dark: #343a40;\n  --breakpoint-xs: 0;\n  --breakpoint-sm: 576px;\n  --breakpoint-md: 768px;\n  --breakpoint-lg: 992px;\n  --breakpoint-xl: 1200px;\n  --font-family-sans-serif: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  --font-family-monospace: SFMono-Regular, Menlo, Monaco, Consolas, \"Liberation Mono\", \"Courier New\", monospace;\n}\n\n*,\n*::before,\n*::after {\n  box-sizing: border-box;\n}\n\nhtml {\n  font-family: sans-serif;\n  line-height: 1.15;\n  -webkit-text-size-adjust: 100%;\n  -webkit-tap-highlight-color: rgba(0, 0, 0, 0);\n}\n\narticle, aside, figcaption, figure, footer, header, hgroup, main, nav, section {\n  display: block;\n}\n\nbody {\n  margin: 0;\n  font-family: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #212529;\n  text-align: left;\n  background-color: #fff;\n}\n\n[tabindex=\"-1\"]:focus {\n  outline: 0 !important;\n}\n\nhr {\n  box-sizing: content-box;\n  height: 0;\n  overflow: visible;\n}\n\nh1, h2, h3, h4, h5, h6 {\n  margin-top: 0;\n  margin-bottom: 0.5rem;\n}\n\np {\n  margin-top: 0;\n  margin-bottom: 1rem;\n}\n\nabbr[title],\nabbr[data-original-title] {\n  text-decoration: underline;\n  -webkit-text-decoration: underline dotted;\n  text-decoration: underline dotted;\n  cursor: help;\n  border-bottom: 0;\n  -webkit-text-decoration-skip-ink: none;\n  text-decoration-skip-ink: none;\n}\n\naddress {\n  margin-bottom: 1rem;\n  font-style: normal;\n  line-height: inherit;\n}\n\nol,\nul,\ndl {\n  margin-top: 0;\n  margin-bottom: 1rem;\n}\n\nol ol,\nul ul,\nol ul,\nul ol {\n  margin-bottom: 0;\n}\n\ndt {\n  font-weight: 700;\n}\n\ndd {\n  margin-bottom: .5rem;\n  margin-left: 0;\n}\n\nblockquote {\n  margin: 0 0 1rem;\n}\n\nb,\nstrong {\n  font-weight: bolder;\n}\n\nsmall {\n  font-size: 80%;\n}\n\nsub,\nsup {\n  position: relative;\n  font-size: 75%;\n  line-height: 0;\n  vertical-align: baseline;\n}\n\nsub {\n  bottom: -.25em;\n}\n\nsup {\n  top: -.5em;\n}\n\na {\n  color: #007bff;\n  text-decoration: none;\n  background-color: transparent;\n}\n\na:hover {\n  color: #0056b3;\n  text-decoration: underline;\n}\n\na:not([href]):not([tabindex]) {\n  color: inherit;\n  text-decoration: none;\n}\n\na:not([href]):not([tabindex]):hover, a:not([href]):not([tabindex]):focus {\n  color: inherit;\n  text-decoration: none;\n}\n\na:not([href]):not([tabindex]):focus {\n  outline: 0;\n}\n\npre,\ncode,\nkbd,\nsamp {\n  font-family: SFMono-Regular, Menlo, Monaco, Consolas, \"Liberation Mono\", \"Courier New\", monospace;\n  font-size: 1em;\n}\n\npre {\n  margin-top: 0;\n  margin-bottom: 1rem;\n  overflow: auto;\n}\n\nfigure {\n  margin: 0 0 1rem;\n}\n\nimg {\n  vertical-align: middle;\n  border-style: none;\n}\n\nsvg {\n  overflow: hidden;\n  vertical-align: middle;\n}\n\ntable {\n  border-collapse: collapse;\n}\n\ncaption {\n  padding-top: 0.75rem;\n  padding-bottom: 0.75rem;\n  color: #6c757d;\n  text-align: left;\n  caption-side: bottom;\n}\n\nth {\n  text-align: inherit;\n}\n\nlabel {\n  display: inline-block;\n  margin-bottom: 0.5rem;\n}\n\nbutton {\n  border-radius: 0;\n}\n\nbutton:focus {\n  outline: 1px dotted;\n  outline: 5px auto -webkit-focus-ring-color;\n}\n\ninput,\nbutton,\nselect,\noptgroup,\ntextarea {\n  margin: 0;\n  font-family: inherit;\n  font-size: inherit;\n  line-height: inherit;\n}\n\nbutton,\ninput {\n  overflow: visible;\n}\n\nbutton,\nselect {\n  text-transform: none;\n}\n\nselect {\n  word-wrap: normal;\n}\n\nbutton,\n[type=\"button\"],\n[type=\"reset\"],\n[type=\"submit\"] {\n  -webkit-appearance: button;\n}\n\nbutton:not(:disabled),\n[type=\"button\"]:not(:disabled),\n[type=\"reset\"]:not(:disabled),\n[type=\"submit\"]:not(:disabled) {\n  cursor: pointer;\n}\n\nbutton::-moz-focus-inner,\n[type=\"button\"]::-moz-focus-inner,\n[type=\"reset\"]::-moz-focus-inner,\n[type=\"submit\"]::-moz-focus-inner {\n  padding: 0;\n  border-style: none;\n}\n\ninput[type=\"radio\"],\ninput[type=\"checkbox\"] {\n  box-sizing: border-box;\n  padding: 0;\n}\n\ninput[type=\"date\"],\ninput[type=\"time\"],\ninput[type=\"datetime-local\"],\ninput[type=\"month\"] {\n  -webkit-appearance: listbox;\n}\n\ntextarea {\n  overflow: auto;\n  resize: vertical;\n}\n\nfieldset {\n  min-width: 0;\n  padding: 0;\n  margin: 0;\n  border: 0;\n}\n\nlegend {\n  display: block;\n  width: 100%;\n  max-width: 100%;\n  padding: 0;\n  margin-bottom: .5rem;\n  font-size: 1.5rem;\n  line-height: inherit;\n  color: inherit;\n  white-space: normal;\n}\n\nprogress {\n  vertical-align: baseline;\n}\n\n[type=\"number\"]::-webkit-inner-spin-button,\n[type=\"number\"]::-webkit-outer-spin-button {\n  height: auto;\n}\n\n[type=\"search\"] {\n  outline-offset: -2px;\n  -webkit-appearance: none;\n}\n\n[type=\"search\"]::-webkit-search-decoration {\n  -webkit-appearance: none;\n}\n\n::-webkit-file-upload-button {\n  font: inherit;\n  -webkit-appearance: button;\n}\n\noutput {\n  display: inline-block;\n}\n\nsummary {\n  display: list-item;\n  cursor: pointer;\n}\n\ntemplate {\n  display: none;\n}\n\n[hidden] {\n  display: none !important;\n}\n\nh1, h2, h3, h4, h5, h6,\n.h1, .h2, .h3, .h4, .h5, .h6 {\n  margin-bottom: 0.5rem;\n  font-weight: 500;\n  line-height: 1.2;\n}\n\nh1, .h1 {\n  font-size: 2.5rem;\n}\n\nh2, .h2 {\n  font-size: 2rem;\n}\n\nh3, .h3 {\n  font-size: 1.75rem;\n}\n\nh4, .h4 {\n  font-size: 1.5rem;\n}\n\nh5, .h5 {\n  font-size: 1.25rem;\n}\n\nh6, .h6 {\n  font-size: 1rem;\n}\n\n.lead {\n  font-size: 1.25rem;\n  font-weight: 300;\n}\n\n.display-1 {\n  font-size: 6rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\n.display-2 {\n  font-size: 5.5rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\n.display-3 {\n  font-size: 4.5rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\n.display-4 {\n  font-size: 3.5rem;\n  font-weight: 300;\n  line-height: 1.2;\n}\n\nhr {\n  margin-top: 1rem;\n  margin-bottom: 1rem;\n  border: 0;\n  border-top: 1px solid rgba(0, 0, 0, 0.1);\n}\n\nsmall,\n.small {\n  font-size: 80%;\n  font-weight: 400;\n}\n\nmark,\n.mark {\n  padding: 0.2em;\n  background-color: #fcf8e3;\n}\n\n.list-unstyled {\n  padding-left: 0;\n  list-style: none;\n}\n\n.list-inline {\n  padding-left: 0;\n  list-style: none;\n}\n\n.list-inline-item {\n  display: inline-block;\n}\n\n.list-inline-item:not(:last-child) {\n  margin-right: 0.5rem;\n}\n\n.initialism {\n  font-size: 90%;\n  text-transform: uppercase;\n}\n\n.blockquote {\n  margin-bottom: 1rem;\n  font-size: 1.25rem;\n}\n\n.blockquote-footer {\n  display: block;\n  font-size: 80%;\n  color: #6c757d;\n}\n\n.blockquote-footer::before {\n  content: \"\\2014\\00A0\";\n}\n\n.img-fluid {\n  max-width: 100%;\n  height: auto;\n}\n\n.img-thumbnail {\n  padding: 0.25rem;\n  background-color: #fff;\n  border: 1px solid #dee2e6;\n  border-radius: 0.25rem;\n  max-width: 100%;\n  height: auto;\n}\n\n.figure {\n  display: inline-block;\n}\n\n.figure-img {\n  margin-bottom: 0.5rem;\n  line-height: 1;\n}\n\n.figure-caption {\n  font-size: 90%;\n  color: #6c757d;\n}\n\ncode {\n  font-size: 87.5%;\n  color: #e83e8c;\n  word-break: break-word;\n}\n\na > code {\n  color: inherit;\n}\n\nkbd {\n  padding: 0.2rem 0.4rem;\n  font-size: 87.5%;\n  color: #fff;\n  background-color: #212529;\n  border-radius: 0.2rem;\n}\n\nkbd kbd {\n  padding: 0;\n  font-size: 100%;\n  font-weight: 700;\n}\n\npre {\n  display: block;\n  font-size: 87.5%;\n  color: #212529;\n}\n\npre code {\n  font-size: inherit;\n  color: inherit;\n  word-break: normal;\n}\n\n.pre-scrollable {\n  max-height: 340px;\n  overflow-y: scroll;\n}\n\n.container {\n  width: 100%;\n  padding-right: 15px;\n  padding-left: 15px;\n  margin-right: auto;\n  margin-left: auto;\n}\n\n@media (min-width: 576px) {\n  .container {\n    max-width: 540px;\n  }\n}\n\n@media (min-width: 768px) {\n  .container {\n    max-width: 720px;\n  }\n}\n\n@media (min-width: 992px) {\n  .container {\n    max-width: 960px;\n  }\n}\n\n@media (min-width: 1200px) {\n  .container {\n    max-width: 1140px;\n  }\n}\n\n.container-fluid {\n  width: 100%;\n  padding-right: 15px;\n  padding-left: 15px;\n  margin-right: auto;\n  margin-left: auto;\n}\n\n.row {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  margin-right: -15px;\n  margin-left: -15px;\n}\n\n.no-gutters {\n  margin-right: 0;\n  margin-left: 0;\n}\n\n.no-gutters > .col,\n.no-gutters > [class*=\"col-\"] {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.col-1, .col-2, .col-3, .col-4, .col-5, .col-6, .col-7, .col-8, .col-9, .col-10, .col-11, .col-12, .col,\n.col-auto, .col-sm-1, .col-sm-2, .col-sm-3, .col-sm-4, .col-sm-5, .col-sm-6, .col-sm-7, .col-sm-8, .col-sm-9, .col-sm-10, .col-sm-11, .col-sm-12, .col-sm,\n.col-sm-auto, .col-md-1, .col-md-2, .col-md-3, .col-md-4, .col-md-5, .col-md-6, .col-md-7, .col-md-8, .col-md-9, .col-md-10, .col-md-11, .col-md-12, .col-md,\n.col-md-auto, .col-lg-1, .col-lg-2, .col-lg-3, .col-lg-4, .col-lg-5, .col-lg-6, .col-lg-7, .col-lg-8, .col-lg-9, .col-lg-10, .col-lg-11, .col-lg-12, .col-lg,\n.col-lg-auto, .col-xl-1, .col-xl-2, .col-xl-3, .col-xl-4, .col-xl-5, .col-xl-6, .col-xl-7, .col-xl-8, .col-xl-9, .col-xl-10, .col-xl-11, .col-xl-12, .col-xl,\n.col-xl-auto {\n  position: relative;\n  width: 100%;\n  padding-right: 15px;\n  padding-left: 15px;\n}\n\n.col {\n  -ms-flex-preferred-size: 0;\n  flex-basis: 0;\n  -ms-flex-positive: 1;\n  flex-grow: 1;\n  max-width: 100%;\n}\n\n.col-auto {\n  -ms-flex: 0 0 auto;\n  flex: 0 0 auto;\n  width: auto;\n  max-width: 100%;\n}\n\n.col-1 {\n  -ms-flex: 0 0 8.333333%;\n  flex: 0 0 8.333333%;\n  max-width: 8.333333%;\n}\n\n.col-2 {\n  -ms-flex: 0 0 16.666667%;\n  flex: 0 0 16.666667%;\n  max-width: 16.666667%;\n}\n\n.col-3 {\n  -ms-flex: 0 0 25%;\n  flex: 0 0 25%;\n  max-width: 25%;\n}\n\n.col-4 {\n  -ms-flex: 0 0 33.333333%;\n  flex: 0 0 33.333333%;\n  max-width: 33.333333%;\n}\n\n.col-5 {\n  -ms-flex: 0 0 41.666667%;\n  flex: 0 0 41.666667%;\n  max-width: 41.666667%;\n}\n\n.col-6 {\n  -ms-flex: 0 0 50%;\n  flex: 0 0 50%;\n  max-width: 50%;\n}\n\n.col-7 {\n  -ms-flex: 0 0 58.333333%;\n  flex: 0 0 58.333333%;\n  max-width: 58.333333%;\n}\n\n.col-8 {\n  -ms-flex: 0 0 66.666667%;\n  flex: 0 0 66.666667%;\n  max-width: 66.666667%;\n}\n\n.col-9 {\n  -ms-flex: 0 0 75%;\n  flex: 0 0 75%;\n  max-width: 75%;\n}\n\n.col-10 {\n  -ms-flex: 0 0 83.333333%;\n  flex: 0 0 83.333333%;\n  max-width: 83.333333%;\n}\n\n.col-11 {\n  -ms-flex: 0 0 91.666667%;\n  flex: 0 0 91.666667%;\n  max-width: 91.666667%;\n}\n\n.col-12 {\n  -ms-flex: 0 0 100%;\n  flex: 0 0 100%;\n  max-width: 100%;\n}\n\n.order-first {\n  -ms-flex-order: -1;\n  order: -1;\n}\n\n.order-last {\n  -ms-flex-order: 13;\n  order: 13;\n}\n\n.order-0 {\n  -ms-flex-order: 0;\n  order: 0;\n}\n\n.order-1 {\n  -ms-flex-order: 1;\n  order: 1;\n}\n\n.order-2 {\n  -ms-flex-order: 2;\n  order: 2;\n}\n\n.order-3 {\n  -ms-flex-order: 3;\n  order: 3;\n}\n\n.order-4 {\n  -ms-flex-order: 4;\n  order: 4;\n}\n\n.order-5 {\n  -ms-flex-order: 5;\n  order: 5;\n}\n\n.order-6 {\n  -ms-flex-order: 6;\n  order: 6;\n}\n\n.order-7 {\n  -ms-flex-order: 7;\n  order: 7;\n}\n\n.order-8 {\n  -ms-flex-order: 8;\n  order: 8;\n}\n\n.order-9 {\n  -ms-flex-order: 9;\n  order: 9;\n}\n\n.order-10 {\n  -ms-flex-order: 10;\n  order: 10;\n}\n\n.order-11 {\n  -ms-flex-order: 11;\n  order: 11;\n}\n\n.order-12 {\n  -ms-flex-order: 12;\n  order: 12;\n}\n\n.offset-1 {\n  margin-left: 8.333333%;\n}\n\n.offset-2 {\n  margin-left: 16.666667%;\n}\n\n.offset-3 {\n  margin-left: 25%;\n}\n\n.offset-4 {\n  margin-left: 33.333333%;\n}\n\n.offset-5 {\n  margin-left: 41.666667%;\n}\n\n.offset-6 {\n  margin-left: 50%;\n}\n\n.offset-7 {\n  margin-left: 58.333333%;\n}\n\n.offset-8 {\n  margin-left: 66.666667%;\n}\n\n.offset-9 {\n  margin-left: 75%;\n}\n\n.offset-10 {\n  margin-left: 83.333333%;\n}\n\n.offset-11 {\n  margin-left: 91.666667%;\n}\n\n@media (min-width: 576px) {\n  .col-sm {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-sm-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-sm-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-sm-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-sm-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-sm-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-sm-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-sm-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-sm-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-sm-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-sm-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-sm-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-sm-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-sm-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-sm-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-sm-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-sm-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-sm-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-sm-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-sm-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-sm-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-sm-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-sm-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-sm-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-sm-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-sm-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-sm-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-sm-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-sm-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-sm-0 {\n    margin-left: 0;\n  }\n  .offset-sm-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-sm-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-sm-3 {\n    margin-left: 25%;\n  }\n  .offset-sm-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-sm-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-sm-6 {\n    margin-left: 50%;\n  }\n  .offset-sm-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-sm-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-sm-9 {\n    margin-left: 75%;\n  }\n  .offset-sm-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-sm-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n@media (min-width: 768px) {\n  .col-md {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-md-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-md-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-md-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-md-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-md-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-md-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-md-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-md-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-md-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-md-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-md-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-md-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-md-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-md-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-md-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-md-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-md-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-md-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-md-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-md-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-md-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-md-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-md-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-md-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-md-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-md-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-md-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-md-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-md-0 {\n    margin-left: 0;\n  }\n  .offset-md-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-md-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-md-3 {\n    margin-left: 25%;\n  }\n  .offset-md-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-md-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-md-6 {\n    margin-left: 50%;\n  }\n  .offset-md-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-md-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-md-9 {\n    margin-left: 75%;\n  }\n  .offset-md-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-md-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n@media (min-width: 992px) {\n  .col-lg {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-lg-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-lg-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-lg-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-lg-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-lg-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-lg-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-lg-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-lg-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-lg-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-lg-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-lg-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-lg-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-lg-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-lg-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-lg-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-lg-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-lg-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-lg-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-lg-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-lg-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-lg-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-lg-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-lg-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-lg-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-lg-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-lg-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-lg-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-lg-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-lg-0 {\n    margin-left: 0;\n  }\n  .offset-lg-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-lg-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-lg-3 {\n    margin-left: 25%;\n  }\n  .offset-lg-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-lg-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-lg-6 {\n    margin-left: 50%;\n  }\n  .offset-lg-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-lg-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-lg-9 {\n    margin-left: 75%;\n  }\n  .offset-lg-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-lg-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n@media (min-width: 1200px) {\n  .col-xl {\n    -ms-flex-preferred-size: 0;\n    flex-basis: 0;\n    -ms-flex-positive: 1;\n    flex-grow: 1;\n    max-width: 100%;\n  }\n  .col-xl-auto {\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    width: auto;\n    max-width: 100%;\n  }\n  .col-xl-1 {\n    -ms-flex: 0 0 8.333333%;\n    flex: 0 0 8.333333%;\n    max-width: 8.333333%;\n  }\n  .col-xl-2 {\n    -ms-flex: 0 0 16.666667%;\n    flex: 0 0 16.666667%;\n    max-width: 16.666667%;\n  }\n  .col-xl-3 {\n    -ms-flex: 0 0 25%;\n    flex: 0 0 25%;\n    max-width: 25%;\n  }\n  .col-xl-4 {\n    -ms-flex: 0 0 33.333333%;\n    flex: 0 0 33.333333%;\n    max-width: 33.333333%;\n  }\n  .col-xl-5 {\n    -ms-flex: 0 0 41.666667%;\n    flex: 0 0 41.666667%;\n    max-width: 41.666667%;\n  }\n  .col-xl-6 {\n    -ms-flex: 0 0 50%;\n    flex: 0 0 50%;\n    max-width: 50%;\n  }\n  .col-xl-7 {\n    -ms-flex: 0 0 58.333333%;\n    flex: 0 0 58.333333%;\n    max-width: 58.333333%;\n  }\n  .col-xl-8 {\n    -ms-flex: 0 0 66.666667%;\n    flex: 0 0 66.666667%;\n    max-width: 66.666667%;\n  }\n  .col-xl-9 {\n    -ms-flex: 0 0 75%;\n    flex: 0 0 75%;\n    max-width: 75%;\n  }\n  .col-xl-10 {\n    -ms-flex: 0 0 83.333333%;\n    flex: 0 0 83.333333%;\n    max-width: 83.333333%;\n  }\n  .col-xl-11 {\n    -ms-flex: 0 0 91.666667%;\n    flex: 0 0 91.666667%;\n    max-width: 91.666667%;\n  }\n  .col-xl-12 {\n    -ms-flex: 0 0 100%;\n    flex: 0 0 100%;\n    max-width: 100%;\n  }\n  .order-xl-first {\n    -ms-flex-order: -1;\n    order: -1;\n  }\n  .order-xl-last {\n    -ms-flex-order: 13;\n    order: 13;\n  }\n  .order-xl-0 {\n    -ms-flex-order: 0;\n    order: 0;\n  }\n  .order-xl-1 {\n    -ms-flex-order: 1;\n    order: 1;\n  }\n  .order-xl-2 {\n    -ms-flex-order: 2;\n    order: 2;\n  }\n  .order-xl-3 {\n    -ms-flex-order: 3;\n    order: 3;\n  }\n  .order-xl-4 {\n    -ms-flex-order: 4;\n    order: 4;\n  }\n  .order-xl-5 {\n    -ms-flex-order: 5;\n    order: 5;\n  }\n  .order-xl-6 {\n    -ms-flex-order: 6;\n    order: 6;\n  }\n  .order-xl-7 {\n    -ms-flex-order: 7;\n    order: 7;\n  }\n  .order-xl-8 {\n    -ms-flex-order: 8;\n    order: 8;\n  }\n  .order-xl-9 {\n    -ms-flex-order: 9;\n    order: 9;\n  }\n  .order-xl-10 {\n    -ms-flex-order: 10;\n    order: 10;\n  }\n  .order-xl-11 {\n    -ms-flex-order: 11;\n    order: 11;\n  }\n  .order-xl-12 {\n    -ms-flex-order: 12;\n    order: 12;\n  }\n  .offset-xl-0 {\n    margin-left: 0;\n  }\n  .offset-xl-1 {\n    margin-left: 8.333333%;\n  }\n  .offset-xl-2 {\n    margin-left: 16.666667%;\n  }\n  .offset-xl-3 {\n    margin-left: 25%;\n  }\n  .offset-xl-4 {\n    margin-left: 33.333333%;\n  }\n  .offset-xl-5 {\n    margin-left: 41.666667%;\n  }\n  .offset-xl-6 {\n    margin-left: 50%;\n  }\n  .offset-xl-7 {\n    margin-left: 58.333333%;\n  }\n  .offset-xl-8 {\n    margin-left: 66.666667%;\n  }\n  .offset-xl-9 {\n    margin-left: 75%;\n  }\n  .offset-xl-10 {\n    margin-left: 83.333333%;\n  }\n  .offset-xl-11 {\n    margin-left: 91.666667%;\n  }\n}\n\n.table {\n  width: 100%;\n  margin-bottom: 1rem;\n  color: #212529;\n}\n\n.table th,\n.table td {\n  padding: 0.75rem;\n  vertical-align: top;\n  border-top: 1px solid #dee2e6;\n}\n\n.table thead th {\n  vertical-align: bottom;\n  border-bottom: 2px solid #dee2e6;\n}\n\n.table tbody + tbody {\n  border-top: 2px solid #dee2e6;\n}\n\n.table-sm th,\n.table-sm td {\n  padding: 0.3rem;\n}\n\n.table-bordered {\n  border: 1px solid #dee2e6;\n}\n\n.table-bordered th,\n.table-bordered td {\n  border: 1px solid #dee2e6;\n}\n\n.table-bordered thead th,\n.table-bordered thead td {\n  border-bottom-width: 2px;\n}\n\n.table-borderless th,\n.table-borderless td,\n.table-borderless thead th,\n.table-borderless tbody + tbody {\n  border: 0;\n}\n\n.table-striped tbody tr:nth-of-type(odd) {\n  background-color: rgba(0, 0, 0, 0.05);\n}\n\n.table-hover tbody tr:hover {\n  color: #212529;\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table-primary,\n.table-primary > th,\n.table-primary > td {\n  background-color: #b8daff;\n}\n\n.table-primary th,\n.table-primary td,\n.table-primary thead th,\n.table-primary tbody + tbody {\n  border-color: #7abaff;\n}\n\n.table-hover .table-primary:hover {\n  background-color: #9fcdff;\n}\n\n.table-hover .table-primary:hover > td,\n.table-hover .table-primary:hover > th {\n  background-color: #9fcdff;\n}\n\n.table-secondary,\n.table-secondary > th,\n.table-secondary > td {\n  background-color: #d6d8db;\n}\n\n.table-secondary th,\n.table-secondary td,\n.table-secondary thead th,\n.table-secondary tbody + tbody {\n  border-color: #b3b7bb;\n}\n\n.table-hover .table-secondary:hover {\n  background-color: #c8cbcf;\n}\n\n.table-hover .table-secondary:hover > td,\n.table-hover .table-secondary:hover > th {\n  background-color: #c8cbcf;\n}\n\n.table-success,\n.table-success > th,\n.table-success > td {\n  background-color: #c3e6cb;\n}\n\n.table-success th,\n.table-success td,\n.table-success thead th,\n.table-success tbody + tbody {\n  border-color: #8fd19e;\n}\n\n.table-hover .table-success:hover {\n  background-color: #b1dfbb;\n}\n\n.table-hover .table-success:hover > td,\n.table-hover .table-success:hover > th {\n  background-color: #b1dfbb;\n}\n\n.table-info,\n.table-info > th,\n.table-info > td {\n  background-color: #bee5eb;\n}\n\n.table-info th,\n.table-info td,\n.table-info thead th,\n.table-info tbody + tbody {\n  border-color: #86cfda;\n}\n\n.table-hover .table-info:hover {\n  background-color: #abdde5;\n}\n\n.table-hover .table-info:hover > td,\n.table-hover .table-info:hover > th {\n  background-color: #abdde5;\n}\n\n.table-warning,\n.table-warning > th,\n.table-warning > td {\n  background-color: #ffeeba;\n}\n\n.table-warning th,\n.table-warning td,\n.table-warning thead th,\n.table-warning tbody + tbody {\n  border-color: #ffdf7e;\n}\n\n.table-hover .table-warning:hover {\n  background-color: #ffe8a1;\n}\n\n.table-hover .table-warning:hover > td,\n.table-hover .table-warning:hover > th {\n  background-color: #ffe8a1;\n}\n\n.table-danger,\n.table-danger > th,\n.table-danger > td {\n  background-color: #f5c6cb;\n}\n\n.table-danger th,\n.table-danger td,\n.table-danger thead th,\n.table-danger tbody + tbody {\n  border-color: #ed969e;\n}\n\n.table-hover .table-danger:hover {\n  background-color: #f1b0b7;\n}\n\n.table-hover .table-danger:hover > td,\n.table-hover .table-danger:hover > th {\n  background-color: #f1b0b7;\n}\n\n.table-light,\n.table-light > th,\n.table-light > td {\n  background-color: #fdfdfe;\n}\n\n.table-light th,\n.table-light td,\n.table-light thead th,\n.table-light tbody + tbody {\n  border-color: #fbfcfc;\n}\n\n.table-hover .table-light:hover {\n  background-color: #ececf6;\n}\n\n.table-hover .table-light:hover > td,\n.table-hover .table-light:hover > th {\n  background-color: #ececf6;\n}\n\n.table-dark,\n.table-dark > th,\n.table-dark > td {\n  background-color: #c6c8ca;\n}\n\n.table-dark th,\n.table-dark td,\n.table-dark thead th,\n.table-dark tbody + tbody {\n  border-color: #95999c;\n}\n\n.table-hover .table-dark:hover {\n  background-color: #b9bbbe;\n}\n\n.table-hover .table-dark:hover > td,\n.table-hover .table-dark:hover > th {\n  background-color: #b9bbbe;\n}\n\n.table-active,\n.table-active > th,\n.table-active > td {\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table-hover .table-active:hover {\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table-hover .table-active:hover > td,\n.table-hover .table-active:hover > th {\n  background-color: rgba(0, 0, 0, 0.075);\n}\n\n.table .thead-dark th {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #454d55;\n}\n\n.table .thead-light th {\n  color: #495057;\n  background-color: #e9ecef;\n  border-color: #dee2e6;\n}\n\n.table-dark {\n  color: #fff;\n  background-color: #343a40;\n}\n\n.table-dark th,\n.table-dark td,\n.table-dark thead th {\n  border-color: #454d55;\n}\n\n.table-dark.table-bordered {\n  border: 0;\n}\n\n.table-dark.table-striped tbody tr:nth-of-type(odd) {\n  background-color: rgba(255, 255, 255, 0.05);\n}\n\n.table-dark.table-hover tbody tr:hover {\n  color: #fff;\n  background-color: rgba(255, 255, 255, 0.075);\n}\n\n@media (max-width: 575.98px) {\n  .table-responsive-sm {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-sm > .table-bordered {\n    border: 0;\n  }\n}\n\n@media (max-width: 767.98px) {\n  .table-responsive-md {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-md > .table-bordered {\n    border: 0;\n  }\n}\n\n@media (max-width: 991.98px) {\n  .table-responsive-lg {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-lg > .table-bordered {\n    border: 0;\n  }\n}\n\n@media (max-width: 1199.98px) {\n  .table-responsive-xl {\n    display: block;\n    width: 100%;\n    overflow-x: auto;\n    -webkit-overflow-scrolling: touch;\n  }\n  .table-responsive-xl > .table-bordered {\n    border: 0;\n  }\n}\n\n.table-responsive {\n  display: block;\n  width: 100%;\n  overflow-x: auto;\n  -webkit-overflow-scrolling: touch;\n}\n\n.table-responsive > .table-bordered {\n  border: 0;\n}\n\n.form-control {\n  display: block;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  padding: 0.375rem 0.75rem;\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n  transition: border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .form-control {\n    transition: none;\n  }\n}\n\n.form-control::-ms-expand {\n  background-color: transparent;\n  border: 0;\n}\n\n.form-control:focus {\n  color: #495057;\n  background-color: #fff;\n  border-color: #80bdff;\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.form-control::-webkit-input-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control::-moz-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control:-ms-input-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control::-ms-input-placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control::placeholder {\n  color: #6c757d;\n  opacity: 1;\n}\n\n.form-control:disabled, .form-control[readonly] {\n  background-color: #e9ecef;\n  opacity: 1;\n}\n\nselect.form-control:focus::-ms-value {\n  color: #495057;\n  background-color: #fff;\n}\n\n.form-control-file,\n.form-control-range {\n  display: block;\n  width: 100%;\n}\n\n.col-form-label {\n  padding-top: calc(0.375rem + 1px);\n  padding-bottom: calc(0.375rem + 1px);\n  margin-bottom: 0;\n  font-size: inherit;\n  line-height: 1.5;\n}\n\n.col-form-label-lg {\n  padding-top: calc(0.5rem + 1px);\n  padding-bottom: calc(0.5rem + 1px);\n  font-size: 1.25rem;\n  line-height: 1.5;\n}\n\n.col-form-label-sm {\n  padding-top: calc(0.25rem + 1px);\n  padding-bottom: calc(0.25rem + 1px);\n  font-size: 0.875rem;\n  line-height: 1.5;\n}\n\n.form-control-plaintext {\n  display: block;\n  width: 100%;\n  padding-top: 0.375rem;\n  padding-bottom: 0.375rem;\n  margin-bottom: 0;\n  line-height: 1.5;\n  color: #212529;\n  background-color: transparent;\n  border: solid transparent;\n  border-width: 1px 0;\n}\n\n.form-control-plaintext.form-control-sm, .form-control-plaintext.form-control-lg {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.form-control-sm {\n  height: calc(1.5em + 0.5rem + 2px);\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  border-radius: 0.2rem;\n}\n\n.form-control-lg {\n  height: calc(1.5em + 1rem + 2px);\n  padding: 0.5rem 1rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n  border-radius: 0.3rem;\n}\n\nselect.form-control[size], select.form-control[multiple] {\n  height: auto;\n}\n\ntextarea.form-control {\n  height: auto;\n}\n\n.form-group {\n  margin-bottom: 1rem;\n}\n\n.form-text {\n  display: block;\n  margin-top: 0.25rem;\n}\n\n.form-row {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  margin-right: -5px;\n  margin-left: -5px;\n}\n\n.form-row > .col,\n.form-row > [class*=\"col-\"] {\n  padding-right: 5px;\n  padding-left: 5px;\n}\n\n.form-check {\n  position: relative;\n  display: block;\n  padding-left: 1.25rem;\n}\n\n.form-check-input {\n  position: absolute;\n  margin-top: 0.3rem;\n  margin-left: -1.25rem;\n}\n\n.form-check-input:disabled ~ .form-check-label {\n  color: #6c757d;\n}\n\n.form-check-label {\n  margin-bottom: 0;\n}\n\n.form-check-inline {\n  display: -ms-inline-flexbox;\n  display: inline-flex;\n  -ms-flex-align: center;\n  align-items: center;\n  padding-left: 0;\n  margin-right: 0.75rem;\n}\n\n.form-check-inline .form-check-input {\n  position: static;\n  margin-top: 0;\n  margin-right: 0.3125rem;\n  margin-left: 0;\n}\n\n.valid-feedback {\n  display: none;\n  width: 100%;\n  margin-top: 0.25rem;\n  font-size: 80%;\n  color: #28a745;\n}\n\n.valid-tooltip {\n  position: absolute;\n  top: 100%;\n  z-index: 5;\n  display: none;\n  max-width: 100%;\n  padding: 0.25rem 0.5rem;\n  margin-top: .1rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  color: #fff;\n  background-color: rgba(40, 167, 69, 0.9);\n  border-radius: 0.25rem;\n}\n\n.was-validated .form-control:valid, .form-control.is-valid {\n  border-color: #28a745;\n  padding-right: calc(1.5em + 0.75rem);\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 8 8'%3e%3cpath fill='%2328a745' d='M2.3 6.73L.6 4.53c-.4-1.04.46-1.4 1.1-.8l1.1 1.4 3.4-3.8c.6-.63 1.6-.27 1.2.7l-4 4.6c-.43.5-.8.4-1.1.1z'/%3e%3c/svg%3e\");\n  background-repeat: no-repeat;\n  background-position: center right calc(0.375em + 0.1875rem);\n  background-size: calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .form-control:valid:focus, .form-control.is-valid:focus {\n  border-color: #28a745;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.was-validated .form-control:valid ~ .valid-feedback,\n.was-validated .form-control:valid ~ .valid-tooltip, .form-control.is-valid ~ .valid-feedback,\n.form-control.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated textarea.form-control:valid, textarea.form-control.is-valid {\n  padding-right: calc(1.5em + 0.75rem);\n  background-position: top calc(0.375em + 0.1875rem) right calc(0.375em + 0.1875rem);\n}\n\n.was-validated .custom-select:valid, .custom-select.is-valid {\n  border-color: #28a745;\n  padding-right: calc((1em + 0.75rem) * 3 / 4 + 1.75rem);\n  background: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e\") no-repeat right 0.75rem center/8px 10px, url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 8 8'%3e%3cpath fill='%2328a745' d='M2.3 6.73L.6 4.53c-.4-1.04.46-1.4 1.1-.8l1.1 1.4 3.4-3.8c.6-.63 1.6-.27 1.2.7l-4 4.6c-.43.5-.8.4-1.1.1z'/%3e%3c/svg%3e\") #fff no-repeat center right 1.75rem/calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .custom-select:valid:focus, .custom-select.is-valid:focus {\n  border-color: #28a745;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.was-validated .custom-select:valid ~ .valid-feedback,\n.was-validated .custom-select:valid ~ .valid-tooltip, .custom-select.is-valid ~ .valid-feedback,\n.custom-select.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .form-control-file:valid ~ .valid-feedback,\n.was-validated .form-control-file:valid ~ .valid-tooltip, .form-control-file.is-valid ~ .valid-feedback,\n.form-control-file.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .form-check-input:valid ~ .form-check-label, .form-check-input.is-valid ~ .form-check-label {\n  color: #28a745;\n}\n\n.was-validated .form-check-input:valid ~ .valid-feedback,\n.was-validated .form-check-input:valid ~ .valid-tooltip, .form-check-input.is-valid ~ .valid-feedback,\n.form-check-input.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:valid ~ .custom-control-label, .custom-control-input.is-valid ~ .custom-control-label {\n  color: #28a745;\n}\n\n.was-validated .custom-control-input:valid ~ .custom-control-label::before, .custom-control-input.is-valid ~ .custom-control-label::before {\n  border-color: #28a745;\n}\n\n.was-validated .custom-control-input:valid ~ .valid-feedback,\n.was-validated .custom-control-input:valid ~ .valid-tooltip, .custom-control-input.is-valid ~ .valid-feedback,\n.custom-control-input.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:valid:checked ~ .custom-control-label::before, .custom-control-input.is-valid:checked ~ .custom-control-label::before {\n  border-color: #34ce57;\n  background-color: #34ce57;\n}\n\n.was-validated .custom-control-input:valid:focus ~ .custom-control-label::before, .custom-control-input.is-valid:focus ~ .custom-control-label::before {\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.was-validated .custom-control-input:valid:focus:not(:checked) ~ .custom-control-label::before, .custom-control-input.is-valid:focus:not(:checked) ~ .custom-control-label::before {\n  border-color: #28a745;\n}\n\n.was-validated .custom-file-input:valid ~ .custom-file-label, .custom-file-input.is-valid ~ .custom-file-label {\n  border-color: #28a745;\n}\n\n.was-validated .custom-file-input:valid ~ .valid-feedback,\n.was-validated .custom-file-input:valid ~ .valid-tooltip, .custom-file-input.is-valid ~ .valid-feedback,\n.custom-file-input.is-valid ~ .valid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-file-input:valid:focus ~ .custom-file-label, .custom-file-input.is-valid:focus ~ .custom-file-label {\n  border-color: #28a745;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.25);\n}\n\n.invalid-feedback {\n  display: none;\n  width: 100%;\n  margin-top: 0.25rem;\n  font-size: 80%;\n  color: #dc3545;\n}\n\n.invalid-tooltip {\n  position: absolute;\n  top: 100%;\n  z-index: 5;\n  display: none;\n  max-width: 100%;\n  padding: 0.25rem 0.5rem;\n  margin-top: .1rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  color: #fff;\n  background-color: rgba(220, 53, 69, 0.9);\n  border-radius: 0.25rem;\n}\n\n.was-validated .form-control:invalid, .form-control.is-invalid {\n  border-color: #dc3545;\n  padding-right: calc(1.5em + 0.75rem);\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23dc3545' viewBox='-2 -2 7 7'%3e%3cpath stroke='%23dc3545' d='M0 0l3 3m0-3L0 3'/%3e%3ccircle r='.5'/%3e%3ccircle cx='3' r='.5'/%3e%3ccircle cy='3' r='.5'/%3e%3ccircle cx='3' cy='3' r='.5'/%3e%3c/svg%3E\");\n  background-repeat: no-repeat;\n  background-position: center right calc(0.375em + 0.1875rem);\n  background-size: calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .form-control:invalid:focus, .form-control.is-invalid:focus {\n  border-color: #dc3545;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.was-validated .form-control:invalid ~ .invalid-feedback,\n.was-validated .form-control:invalid ~ .invalid-tooltip, .form-control.is-invalid ~ .invalid-feedback,\n.form-control.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated textarea.form-control:invalid, textarea.form-control.is-invalid {\n  padding-right: calc(1.5em + 0.75rem);\n  background-position: top calc(0.375em + 0.1875rem) right calc(0.375em + 0.1875rem);\n}\n\n.was-validated .custom-select:invalid, .custom-select.is-invalid {\n  border-color: #dc3545;\n  padding-right: calc((1em + 0.75rem) * 3 / 4 + 1.75rem);\n  background: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e\") no-repeat right 0.75rem center/8px 10px, url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23dc3545' viewBox='-2 -2 7 7'%3e%3cpath stroke='%23dc3545' d='M0 0l3 3m0-3L0 3'/%3e%3ccircle r='.5'/%3e%3ccircle cx='3' r='.5'/%3e%3ccircle cy='3' r='.5'/%3e%3ccircle cx='3' cy='3' r='.5'/%3e%3c/svg%3E\") #fff no-repeat center right 1.75rem/calc(0.75em + 0.375rem) calc(0.75em + 0.375rem);\n}\n\n.was-validated .custom-select:invalid:focus, .custom-select.is-invalid:focus {\n  border-color: #dc3545;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.was-validated .custom-select:invalid ~ .invalid-feedback,\n.was-validated .custom-select:invalid ~ .invalid-tooltip, .custom-select.is-invalid ~ .invalid-feedback,\n.custom-select.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .form-control-file:invalid ~ .invalid-feedback,\n.was-validated .form-control-file:invalid ~ .invalid-tooltip, .form-control-file.is-invalid ~ .invalid-feedback,\n.form-control-file.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .form-check-input:invalid ~ .form-check-label, .form-check-input.is-invalid ~ .form-check-label {\n  color: #dc3545;\n}\n\n.was-validated .form-check-input:invalid ~ .invalid-feedback,\n.was-validated .form-check-input:invalid ~ .invalid-tooltip, .form-check-input.is-invalid ~ .invalid-feedback,\n.form-check-input.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:invalid ~ .custom-control-label, .custom-control-input.is-invalid ~ .custom-control-label {\n  color: #dc3545;\n}\n\n.was-validated .custom-control-input:invalid ~ .custom-control-label::before, .custom-control-input.is-invalid ~ .custom-control-label::before {\n  border-color: #dc3545;\n}\n\n.was-validated .custom-control-input:invalid ~ .invalid-feedback,\n.was-validated .custom-control-input:invalid ~ .invalid-tooltip, .custom-control-input.is-invalid ~ .invalid-feedback,\n.custom-control-input.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-control-input:invalid:checked ~ .custom-control-label::before, .custom-control-input.is-invalid:checked ~ .custom-control-label::before {\n  border-color: #e4606d;\n  background-color: #e4606d;\n}\n\n.was-validated .custom-control-input:invalid:focus ~ .custom-control-label::before, .custom-control-input.is-invalid:focus ~ .custom-control-label::before {\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.was-validated .custom-control-input:invalid:focus:not(:checked) ~ .custom-control-label::before, .custom-control-input.is-invalid:focus:not(:checked) ~ .custom-control-label::before {\n  border-color: #dc3545;\n}\n\n.was-validated .custom-file-input:invalid ~ .custom-file-label, .custom-file-input.is-invalid ~ .custom-file-label {\n  border-color: #dc3545;\n}\n\n.was-validated .custom-file-input:invalid ~ .invalid-feedback,\n.was-validated .custom-file-input:invalid ~ .invalid-tooltip, .custom-file-input.is-invalid ~ .invalid-feedback,\n.custom-file-input.is-invalid ~ .invalid-tooltip {\n  display: block;\n}\n\n.was-validated .custom-file-input:invalid:focus ~ .custom-file-label, .custom-file-input.is-invalid:focus ~ .custom-file-label {\n  border-color: #dc3545;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.25);\n}\n\n.form-inline {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-flow: row wrap;\n  flex-flow: row wrap;\n  -ms-flex-align: center;\n  align-items: center;\n}\n\n.form-inline .form-check {\n  width: 100%;\n}\n\n@media (min-width: 576px) {\n  .form-inline label {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex-align: center;\n    align-items: center;\n    -ms-flex-pack: center;\n    justify-content: center;\n    margin-bottom: 0;\n  }\n  .form-inline .form-group {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex: 0 0 auto;\n    flex: 0 0 auto;\n    -ms-flex-flow: row wrap;\n    flex-flow: row wrap;\n    -ms-flex-align: center;\n    align-items: center;\n    margin-bottom: 0;\n  }\n  .form-inline .form-control {\n    display: inline-block;\n    width: auto;\n    vertical-align: middle;\n  }\n  .form-inline .form-control-plaintext {\n    display: inline-block;\n  }\n  .form-inline .input-group,\n  .form-inline .custom-select {\n    width: auto;\n  }\n  .form-inline .form-check {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex-align: center;\n    align-items: center;\n    -ms-flex-pack: center;\n    justify-content: center;\n    width: auto;\n    padding-left: 0;\n  }\n  .form-inline .form-check-input {\n    position: relative;\n    -ms-flex-negative: 0;\n    flex-shrink: 0;\n    margin-top: 0;\n    margin-right: 0.25rem;\n    margin-left: 0;\n  }\n  .form-inline .custom-control {\n    -ms-flex-align: center;\n    align-items: center;\n    -ms-flex-pack: center;\n    justify-content: center;\n  }\n  .form-inline .custom-control-label {\n    margin-bottom: 0;\n  }\n}\n\n.btn {\n  display: inline-block;\n  font-weight: 400;\n  color: #212529;\n  text-align: center;\n  vertical-align: middle;\n  -webkit-user-select: none;\n  -moz-user-select: none;\n  -ms-user-select: none;\n  user-select: none;\n  background-color: transparent;\n  border: 1px solid transparent;\n  padding: 0.375rem 0.75rem;\n  font-size: 1rem;\n  line-height: 1.5;\n  border-radius: 0.25rem;\n  transition: color 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .btn {\n    transition: none;\n  }\n}\n\n.btn:hover {\n  color: #212529;\n  text-decoration: none;\n}\n\n.btn:focus, .btn.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.btn.disabled, .btn:disabled {\n  opacity: 0.65;\n}\n\na.btn.disabled,\nfieldset:disabled a.btn {\n  pointer-events: none;\n}\n\n.btn-primary {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-primary:hover {\n  color: #fff;\n  background-color: #0069d9;\n  border-color: #0062cc;\n}\n\n.btn-primary:focus, .btn-primary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(38, 143, 255, 0.5);\n}\n\n.btn-primary.disabled, .btn-primary:disabled {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-primary:not(:disabled):not(.disabled):active, .btn-primary:not(:disabled):not(.disabled).active,\n.show > .btn-primary.dropdown-toggle {\n  color: #fff;\n  background-color: #0062cc;\n  border-color: #005cbf;\n}\n\n.btn-primary:not(:disabled):not(.disabled):active:focus, .btn-primary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-primary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(38, 143, 255, 0.5);\n}\n\n.btn-secondary {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-secondary:hover {\n  color: #fff;\n  background-color: #5a6268;\n  border-color: #545b62;\n}\n\n.btn-secondary:focus, .btn-secondary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(130, 138, 145, 0.5);\n}\n\n.btn-secondary.disabled, .btn-secondary:disabled {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-secondary:not(:disabled):not(.disabled):active, .btn-secondary:not(:disabled):not(.disabled).active,\n.show > .btn-secondary.dropdown-toggle {\n  color: #fff;\n  background-color: #545b62;\n  border-color: #4e555b;\n}\n\n.btn-secondary:not(:disabled):not(.disabled):active:focus, .btn-secondary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-secondary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(130, 138, 145, 0.5);\n}\n\n.btn-success {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-success:hover {\n  color: #fff;\n  background-color: #218838;\n  border-color: #1e7e34;\n}\n\n.btn-success:focus, .btn-success.focus {\n  box-shadow: 0 0 0 0.2rem rgba(72, 180, 97, 0.5);\n}\n\n.btn-success.disabled, .btn-success:disabled {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-success:not(:disabled):not(.disabled):active, .btn-success:not(:disabled):not(.disabled).active,\n.show > .btn-success.dropdown-toggle {\n  color: #fff;\n  background-color: #1e7e34;\n  border-color: #1c7430;\n}\n\n.btn-success:not(:disabled):not(.disabled):active:focus, .btn-success:not(:disabled):not(.disabled).active:focus,\n.show > .btn-success.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(72, 180, 97, 0.5);\n}\n\n.btn-info {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-info:hover {\n  color: #fff;\n  background-color: #138496;\n  border-color: #117a8b;\n}\n\n.btn-info:focus, .btn-info.focus {\n  box-shadow: 0 0 0 0.2rem rgba(58, 176, 195, 0.5);\n}\n\n.btn-info.disabled, .btn-info:disabled {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-info:not(:disabled):not(.disabled):active, .btn-info:not(:disabled):not(.disabled).active,\n.show > .btn-info.dropdown-toggle {\n  color: #fff;\n  background-color: #117a8b;\n  border-color: #10707f;\n}\n\n.btn-info:not(:disabled):not(.disabled):active:focus, .btn-info:not(:disabled):not(.disabled).active:focus,\n.show > .btn-info.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(58, 176, 195, 0.5);\n}\n\n.btn-warning {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-warning:hover {\n  color: #212529;\n  background-color: #e0a800;\n  border-color: #d39e00;\n}\n\n.btn-warning:focus, .btn-warning.focus {\n  box-shadow: 0 0 0 0.2rem rgba(222, 170, 12, 0.5);\n}\n\n.btn-warning.disabled, .btn-warning:disabled {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-warning:not(:disabled):not(.disabled):active, .btn-warning:not(:disabled):not(.disabled).active,\n.show > .btn-warning.dropdown-toggle {\n  color: #212529;\n  background-color: #d39e00;\n  border-color: #c69500;\n}\n\n.btn-warning:not(:disabled):not(.disabled):active:focus, .btn-warning:not(:disabled):not(.disabled).active:focus,\n.show > .btn-warning.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(222, 170, 12, 0.5);\n}\n\n.btn-danger {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-danger:hover {\n  color: #fff;\n  background-color: #c82333;\n  border-color: #bd2130;\n}\n\n.btn-danger:focus, .btn-danger.focus {\n  box-shadow: 0 0 0 0.2rem rgba(225, 83, 97, 0.5);\n}\n\n.btn-danger.disabled, .btn-danger:disabled {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-danger:not(:disabled):not(.disabled):active, .btn-danger:not(:disabled):not(.disabled).active,\n.show > .btn-danger.dropdown-toggle {\n  color: #fff;\n  background-color: #bd2130;\n  border-color: #b21f2d;\n}\n\n.btn-danger:not(:disabled):not(.disabled):active:focus, .btn-danger:not(:disabled):not(.disabled).active:focus,\n.show > .btn-danger.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(225, 83, 97, 0.5);\n}\n\n.btn-light {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-light:hover {\n  color: #212529;\n  background-color: #e2e6ea;\n  border-color: #dae0e5;\n}\n\n.btn-light:focus, .btn-light.focus {\n  box-shadow: 0 0 0 0.2rem rgba(216, 217, 219, 0.5);\n}\n\n.btn-light.disabled, .btn-light:disabled {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-light:not(:disabled):not(.disabled):active, .btn-light:not(:disabled):not(.disabled).active,\n.show > .btn-light.dropdown-toggle {\n  color: #212529;\n  background-color: #dae0e5;\n  border-color: #d3d9df;\n}\n\n.btn-light:not(:disabled):not(.disabled):active:focus, .btn-light:not(:disabled):not(.disabled).active:focus,\n.show > .btn-light.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(216, 217, 219, 0.5);\n}\n\n.btn-dark {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-dark:hover {\n  color: #fff;\n  background-color: #23272b;\n  border-color: #1d2124;\n}\n\n.btn-dark:focus, .btn-dark.focus {\n  box-shadow: 0 0 0 0.2rem rgba(82, 88, 93, 0.5);\n}\n\n.btn-dark.disabled, .btn-dark:disabled {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-dark:not(:disabled):not(.disabled):active, .btn-dark:not(:disabled):not(.disabled).active,\n.show > .btn-dark.dropdown-toggle {\n  color: #fff;\n  background-color: #1d2124;\n  border-color: #171a1d;\n}\n\n.btn-dark:not(:disabled):not(.disabled):active:focus, .btn-dark:not(:disabled):not(.disabled).active:focus,\n.show > .btn-dark.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(82, 88, 93, 0.5);\n}\n\n.btn-outline-primary {\n  color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-outline-primary:hover {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-outline-primary:focus, .btn-outline-primary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.5);\n}\n\n.btn-outline-primary.disabled, .btn-outline-primary:disabled {\n  color: #007bff;\n  background-color: transparent;\n}\n\n.btn-outline-primary:not(:disabled):not(.disabled):active, .btn-outline-primary:not(:disabled):not(.disabled).active,\n.show > .btn-outline-primary.dropdown-toggle {\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.btn-outline-primary:not(:disabled):not(.disabled):active:focus, .btn-outline-primary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-primary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.5);\n}\n\n.btn-outline-secondary {\n  color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-outline-secondary:hover {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-outline-secondary:focus, .btn-outline-secondary.focus {\n  box-shadow: 0 0 0 0.2rem rgba(108, 117, 125, 0.5);\n}\n\n.btn-outline-secondary.disabled, .btn-outline-secondary:disabled {\n  color: #6c757d;\n  background-color: transparent;\n}\n\n.btn-outline-secondary:not(:disabled):not(.disabled):active, .btn-outline-secondary:not(:disabled):not(.disabled).active,\n.show > .btn-outline-secondary.dropdown-toggle {\n  color: #fff;\n  background-color: #6c757d;\n  border-color: #6c757d;\n}\n\n.btn-outline-secondary:not(:disabled):not(.disabled):active:focus, .btn-outline-secondary:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-secondary.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(108, 117, 125, 0.5);\n}\n\n.btn-outline-success {\n  color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-outline-success:hover {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-outline-success:focus, .btn-outline-success.focus {\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.5);\n}\n\n.btn-outline-success.disabled, .btn-outline-success:disabled {\n  color: #28a745;\n  background-color: transparent;\n}\n\n.btn-outline-success:not(:disabled):not(.disabled):active, .btn-outline-success:not(:disabled):not(.disabled).active,\n.show > .btn-outline-success.dropdown-toggle {\n  color: #fff;\n  background-color: #28a745;\n  border-color: #28a745;\n}\n\n.btn-outline-success:not(:disabled):not(.disabled):active:focus, .btn-outline-success:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-success.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.5);\n}\n\n.btn-outline-info {\n  color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-outline-info:hover {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-outline-info:focus, .btn-outline-info.focus {\n  box-shadow: 0 0 0 0.2rem rgba(23, 162, 184, 0.5);\n}\n\n.btn-outline-info.disabled, .btn-outline-info:disabled {\n  color: #17a2b8;\n  background-color: transparent;\n}\n\n.btn-outline-info:not(:disabled):not(.disabled):active, .btn-outline-info:not(:disabled):not(.disabled).active,\n.show > .btn-outline-info.dropdown-toggle {\n  color: #fff;\n  background-color: #17a2b8;\n  border-color: #17a2b8;\n}\n\n.btn-outline-info:not(:disabled):not(.disabled):active:focus, .btn-outline-info:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-info.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(23, 162, 184, 0.5);\n}\n\n.btn-outline-warning {\n  color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-outline-warning:hover {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-outline-warning:focus, .btn-outline-warning.focus {\n  box-shadow: 0 0 0 0.2rem rgba(255, 193, 7, 0.5);\n}\n\n.btn-outline-warning.disabled, .btn-outline-warning:disabled {\n  color: #ffc107;\n  background-color: transparent;\n}\n\n.btn-outline-warning:not(:disabled):not(.disabled):active, .btn-outline-warning:not(:disabled):not(.disabled).active,\n.show > .btn-outline-warning.dropdown-toggle {\n  color: #212529;\n  background-color: #ffc107;\n  border-color: #ffc107;\n}\n\n.btn-outline-warning:not(:disabled):not(.disabled):active:focus, .btn-outline-warning:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-warning.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(255, 193, 7, 0.5);\n}\n\n.btn-outline-danger {\n  color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-outline-danger:hover {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-outline-danger:focus, .btn-outline-danger.focus {\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.5);\n}\n\n.btn-outline-danger.disabled, .btn-outline-danger:disabled {\n  color: #dc3545;\n  background-color: transparent;\n}\n\n.btn-outline-danger:not(:disabled):not(.disabled):active, .btn-outline-danger:not(:disabled):not(.disabled).active,\n.show > .btn-outline-danger.dropdown-toggle {\n  color: #fff;\n  background-color: #dc3545;\n  border-color: #dc3545;\n}\n\n.btn-outline-danger:not(:disabled):not(.disabled):active:focus, .btn-outline-danger:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-danger.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.5);\n}\n\n.btn-outline-light {\n  color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-outline-light:hover {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-outline-light:focus, .btn-outline-light.focus {\n  box-shadow: 0 0 0 0.2rem rgba(248, 249, 250, 0.5);\n}\n\n.btn-outline-light.disabled, .btn-outline-light:disabled {\n  color: #f8f9fa;\n  background-color: transparent;\n}\n\n.btn-outline-light:not(:disabled):not(.disabled):active, .btn-outline-light:not(:disabled):not(.disabled).active,\n.show > .btn-outline-light.dropdown-toggle {\n  color: #212529;\n  background-color: #f8f9fa;\n  border-color: #f8f9fa;\n}\n\n.btn-outline-light:not(:disabled):not(.disabled):active:focus, .btn-outline-light:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-light.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(248, 249, 250, 0.5);\n}\n\n.btn-outline-dark {\n  color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-outline-dark:hover {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-outline-dark:focus, .btn-outline-dark.focus {\n  box-shadow: 0 0 0 0.2rem rgba(52, 58, 64, 0.5);\n}\n\n.btn-outline-dark.disabled, .btn-outline-dark:disabled {\n  color: #343a40;\n  background-color: transparent;\n}\n\n.btn-outline-dark:not(:disabled):not(.disabled):active, .btn-outline-dark:not(:disabled):not(.disabled).active,\n.show > .btn-outline-dark.dropdown-toggle {\n  color: #fff;\n  background-color: #343a40;\n  border-color: #343a40;\n}\n\n.btn-outline-dark:not(:disabled):not(.disabled):active:focus, .btn-outline-dark:not(:disabled):not(.disabled).active:focus,\n.show > .btn-outline-dark.dropdown-toggle:focus {\n  box-shadow: 0 0 0 0.2rem rgba(52, 58, 64, 0.5);\n}\n\n.btn-link {\n  font-weight: 400;\n  color: #007bff;\n  text-decoration: none;\n}\n\n.btn-link:hover {\n  color: #0056b3;\n  text-decoration: underline;\n}\n\n.btn-link:focus, .btn-link.focus {\n  text-decoration: underline;\n  box-shadow: none;\n}\n\n.btn-link:disabled, .btn-link.disabled {\n  color: #6c757d;\n  pointer-events: none;\n}\n\n.btn-lg, .btn-group-lg > .btn {\n  padding: 0.5rem 1rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n  border-radius: 0.3rem;\n}\n\n.btn-sm, .btn-group-sm > .btn {\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  border-radius: 0.2rem;\n}\n\n.btn-block {\n  display: block;\n  width: 100%;\n}\n\n.btn-block + .btn-block {\n  margin-top: 0.5rem;\n}\n\ninput[type=\"submit\"].btn-block,\ninput[type=\"reset\"].btn-block,\ninput[type=\"button\"].btn-block {\n  width: 100%;\n}\n\n.fade {\n  transition: opacity 0.15s linear;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .fade {\n    transition: none;\n  }\n}\n\n.fade:not(.show) {\n  opacity: 0;\n}\n\n.collapse:not(.show) {\n  display: none;\n}\n\n.collapsing {\n  position: relative;\n  height: 0;\n  overflow: hidden;\n  transition: height 0.35s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .collapsing {\n    transition: none;\n  }\n}\n\n.dropup,\n.dropright,\n.dropdown,\n.dropleft {\n  position: relative;\n}\n\n.dropdown-toggle {\n  white-space: nowrap;\n}\n\n.dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0.3em solid;\n  border-right: 0.3em solid transparent;\n  border-bottom: 0;\n  border-left: 0.3em solid transparent;\n}\n\n.dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropdown-menu {\n  position: absolute;\n  top: 100%;\n  left: 0;\n  z-index: 1000;\n  display: none;\n  float: left;\n  min-width: 10rem;\n  padding: 0.5rem 0;\n  margin: 0.125rem 0 0;\n  font-size: 1rem;\n  color: #212529;\n  text-align: left;\n  list-style: none;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.15);\n  border-radius: 0.25rem;\n}\n\n.dropdown-menu-left {\n  right: auto;\n  left: 0;\n}\n\n.dropdown-menu-right {\n  right: 0;\n  left: auto;\n}\n\n@media (min-width: 576px) {\n  .dropdown-menu-sm-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-sm-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n@media (min-width: 768px) {\n  .dropdown-menu-md-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-md-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n@media (min-width: 992px) {\n  .dropdown-menu-lg-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-lg-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n@media (min-width: 1200px) {\n  .dropdown-menu-xl-left {\n    right: auto;\n    left: 0;\n  }\n  .dropdown-menu-xl-right {\n    right: 0;\n    left: auto;\n  }\n}\n\n.dropup .dropdown-menu {\n  top: auto;\n  bottom: 100%;\n  margin-top: 0;\n  margin-bottom: 0.125rem;\n}\n\n.dropup .dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0;\n  border-right: 0.3em solid transparent;\n  border-bottom: 0.3em solid;\n  border-left: 0.3em solid transparent;\n}\n\n.dropup .dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropright .dropdown-menu {\n  top: 0;\n  right: auto;\n  left: 100%;\n  margin-top: 0;\n  margin-left: 0.125rem;\n}\n\n.dropright .dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0.3em solid transparent;\n  border-right: 0;\n  border-bottom: 0.3em solid transparent;\n  border-left: 0.3em solid;\n}\n\n.dropright .dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropright .dropdown-toggle::after {\n  vertical-align: 0;\n}\n\n.dropleft .dropdown-menu {\n  top: 0;\n  right: 100%;\n  left: auto;\n  margin-top: 0;\n  margin-right: 0.125rem;\n}\n\n.dropleft .dropdown-toggle::after {\n  display: inline-block;\n  margin-left: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n}\n\n.dropleft .dropdown-toggle::after {\n  display: none;\n}\n\n.dropleft .dropdown-toggle::before {\n  display: inline-block;\n  margin-right: 0.255em;\n  vertical-align: 0.255em;\n  content: \"\";\n  border-top: 0.3em solid transparent;\n  border-right: 0.3em solid;\n  border-bottom: 0.3em solid transparent;\n}\n\n.dropleft .dropdown-toggle:empty::after {\n  margin-left: 0;\n}\n\n.dropleft .dropdown-toggle::before {\n  vertical-align: 0;\n}\n\n.dropdown-menu[x-placement^=\"top\"], .dropdown-menu[x-placement^=\"right\"], .dropdown-menu[x-placement^=\"bottom\"], .dropdown-menu[x-placement^=\"left\"] {\n  right: auto;\n  bottom: auto;\n}\n\n.dropdown-divider {\n  height: 0;\n  margin: 0.5rem 0;\n  overflow: hidden;\n  border-top: 1px solid #e9ecef;\n}\n\n.dropdown-item {\n  display: block;\n  width: 100%;\n  padding: 0.25rem 1.5rem;\n  clear: both;\n  font-weight: 400;\n  color: #212529;\n  text-align: inherit;\n  white-space: nowrap;\n  background-color: transparent;\n  border: 0;\n}\n\n.dropdown-item:hover, .dropdown-item:focus {\n  color: #16181b;\n  text-decoration: none;\n  background-color: #f8f9fa;\n}\n\n.dropdown-item.active, .dropdown-item:active {\n  color: #fff;\n  text-decoration: none;\n  background-color: #007bff;\n}\n\n.dropdown-item.disabled, .dropdown-item:disabled {\n  color: #6c757d;\n  pointer-events: none;\n  background-color: transparent;\n}\n\n.dropdown-menu.show {\n  display: block;\n}\n\n.dropdown-header {\n  display: block;\n  padding: 0.5rem 1.5rem;\n  margin-bottom: 0;\n  font-size: 0.875rem;\n  color: #6c757d;\n  white-space: nowrap;\n}\n\n.dropdown-item-text {\n  display: block;\n  padding: 0.25rem 1.5rem;\n  color: #212529;\n}\n\n.btn-group,\n.btn-group-vertical {\n  position: relative;\n  display: -ms-inline-flexbox;\n  display: inline-flex;\n  vertical-align: middle;\n}\n\n.btn-group > .btn,\n.btn-group-vertical > .btn {\n  position: relative;\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n}\n\n.btn-group > .btn:hover,\n.btn-group-vertical > .btn:hover {\n  z-index: 1;\n}\n\n.btn-group > .btn:focus, .btn-group > .btn:active, .btn-group > .btn.active,\n.btn-group-vertical > .btn:focus,\n.btn-group-vertical > .btn:active,\n.btn-group-vertical > .btn.active {\n  z-index: 1;\n}\n\n.btn-toolbar {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-pack: start;\n  justify-content: flex-start;\n}\n\n.btn-toolbar .input-group {\n  width: auto;\n}\n\n.btn-group > .btn:not(:first-child),\n.btn-group > .btn-group:not(:first-child) {\n  margin-left: -1px;\n}\n\n.btn-group > .btn:not(:last-child):not(.dropdown-toggle),\n.btn-group > .btn-group:not(:last-child) > .btn {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.btn-group > .btn:not(:first-child),\n.btn-group > .btn-group:not(:first-child) > .btn {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.dropdown-toggle-split {\n  padding-right: 0.5625rem;\n  padding-left: 0.5625rem;\n}\n\n.dropdown-toggle-split::after,\n.dropup .dropdown-toggle-split::after,\n.dropright .dropdown-toggle-split::after {\n  margin-left: 0;\n}\n\n.dropleft .dropdown-toggle-split::before {\n  margin-right: 0;\n}\n\n.btn-sm + .dropdown-toggle-split, .btn-group-sm > .btn + .dropdown-toggle-split {\n  padding-right: 0.375rem;\n  padding-left: 0.375rem;\n}\n\n.btn-lg + .dropdown-toggle-split, .btn-group-lg > .btn + .dropdown-toggle-split {\n  padding-right: 0.75rem;\n  padding-left: 0.75rem;\n}\n\n.btn-group-vertical {\n  -ms-flex-direction: column;\n  flex-direction: column;\n  -ms-flex-align: start;\n  align-items: flex-start;\n  -ms-flex-pack: center;\n  justify-content: center;\n}\n\n.btn-group-vertical > .btn,\n.btn-group-vertical > .btn-group {\n  width: 100%;\n}\n\n.btn-group-vertical > .btn:not(:first-child),\n.btn-group-vertical > .btn-group:not(:first-child) {\n  margin-top: -1px;\n}\n\n.btn-group-vertical > .btn:not(:last-child):not(.dropdown-toggle),\n.btn-group-vertical > .btn-group:not(:last-child) > .btn {\n  border-bottom-right-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.btn-group-vertical > .btn:not(:first-child),\n.btn-group-vertical > .btn-group:not(:first-child) > .btn {\n  border-top-left-radius: 0;\n  border-top-right-radius: 0;\n}\n\n.btn-group-toggle > .btn,\n.btn-group-toggle > .btn-group > .btn {\n  margin-bottom: 0;\n}\n\n.btn-group-toggle > .btn input[type=\"radio\"],\n.btn-group-toggle > .btn input[type=\"checkbox\"],\n.btn-group-toggle > .btn-group > .btn input[type=\"radio\"],\n.btn-group-toggle > .btn-group > .btn input[type=\"checkbox\"] {\n  position: absolute;\n  clip: rect(0, 0, 0, 0);\n  pointer-events: none;\n}\n\n.input-group {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-align: stretch;\n  align-items: stretch;\n  width: 100%;\n}\n\n.input-group > .form-control,\n.input-group > .form-control-plaintext,\n.input-group > .custom-select,\n.input-group > .custom-file {\n  position: relative;\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  width: 1%;\n  margin-bottom: 0;\n}\n\n.input-group > .form-control + .form-control,\n.input-group > .form-control + .custom-select,\n.input-group > .form-control + .custom-file,\n.input-group > .form-control-plaintext + .form-control,\n.input-group > .form-control-plaintext + .custom-select,\n.input-group > .form-control-plaintext + .custom-file,\n.input-group > .custom-select + .form-control,\n.input-group > .custom-select + .custom-select,\n.input-group > .custom-select + .custom-file,\n.input-group > .custom-file + .form-control,\n.input-group > .custom-file + .custom-select,\n.input-group > .custom-file + .custom-file {\n  margin-left: -1px;\n}\n\n.input-group > .form-control:focus,\n.input-group > .custom-select:focus,\n.input-group > .custom-file .custom-file-input:focus ~ .custom-file-label {\n  z-index: 3;\n}\n\n.input-group > .custom-file .custom-file-input:focus {\n  z-index: 4;\n}\n\n.input-group > .form-control:not(:last-child),\n.input-group > .custom-select:not(:last-child) {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.input-group > .form-control:not(:first-child),\n.input-group > .custom-select:not(:first-child) {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.input-group > .custom-file {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n}\n\n.input-group > .custom-file:not(:last-child) .custom-file-label,\n.input-group > .custom-file:not(:last-child) .custom-file-label::after {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.input-group > .custom-file:not(:first-child) .custom-file-label {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.input-group-prepend,\n.input-group-append {\n  display: -ms-flexbox;\n  display: flex;\n}\n\n.input-group-prepend .btn,\n.input-group-append .btn {\n  position: relative;\n  z-index: 2;\n}\n\n.input-group-prepend .btn:focus,\n.input-group-append .btn:focus {\n  z-index: 3;\n}\n\n.input-group-prepend .btn + .btn,\n.input-group-prepend .btn + .input-group-text,\n.input-group-prepend .input-group-text + .input-group-text,\n.input-group-prepend .input-group-text + .btn,\n.input-group-append .btn + .btn,\n.input-group-append .btn + .input-group-text,\n.input-group-append .input-group-text + .input-group-text,\n.input-group-append .input-group-text + .btn {\n  margin-left: -1px;\n}\n\n.input-group-prepend {\n  margin-right: -1px;\n}\n\n.input-group-append {\n  margin-left: -1px;\n}\n\n.input-group-text {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  padding: 0.375rem 0.75rem;\n  margin-bottom: 0;\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  text-align: center;\n  white-space: nowrap;\n  background-color: #e9ecef;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n}\n\n.input-group-text input[type=\"radio\"],\n.input-group-text input[type=\"checkbox\"] {\n  margin-top: 0;\n}\n\n.input-group-lg > .form-control:not(textarea),\n.input-group-lg > .custom-select {\n  height: calc(1.5em + 1rem + 2px);\n}\n\n.input-group-lg > .form-control,\n.input-group-lg > .custom-select,\n.input-group-lg > .input-group-prepend > .input-group-text,\n.input-group-lg > .input-group-append > .input-group-text,\n.input-group-lg > .input-group-prepend > .btn,\n.input-group-lg > .input-group-append > .btn {\n  padding: 0.5rem 1rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n  border-radius: 0.3rem;\n}\n\n.input-group-sm > .form-control:not(textarea),\n.input-group-sm > .custom-select {\n  height: calc(1.5em + 0.5rem + 2px);\n}\n\n.input-group-sm > .form-control,\n.input-group-sm > .custom-select,\n.input-group-sm > .input-group-prepend > .input-group-text,\n.input-group-sm > .input-group-append > .input-group-text,\n.input-group-sm > .input-group-prepend > .btn,\n.input-group-sm > .input-group-append > .btn {\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n  border-radius: 0.2rem;\n}\n\n.input-group-lg > .custom-select,\n.input-group-sm > .custom-select {\n  padding-right: 1.75rem;\n}\n\n.input-group > .input-group-prepend > .btn,\n.input-group > .input-group-prepend > .input-group-text,\n.input-group > .input-group-append:not(:last-child) > .btn,\n.input-group > .input-group-append:not(:last-child) > .input-group-text,\n.input-group > .input-group-append:last-child > .btn:not(:last-child):not(.dropdown-toggle),\n.input-group > .input-group-append:last-child > .input-group-text:not(:last-child) {\n  border-top-right-radius: 0;\n  border-bottom-right-radius: 0;\n}\n\n.input-group > .input-group-append > .btn,\n.input-group > .input-group-append > .input-group-text,\n.input-group > .input-group-prepend:not(:first-child) > .btn,\n.input-group > .input-group-prepend:not(:first-child) > .input-group-text,\n.input-group > .input-group-prepend:first-child > .btn:not(:first-child),\n.input-group > .input-group-prepend:first-child > .input-group-text:not(:first-child) {\n  border-top-left-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.custom-control {\n  position: relative;\n  display: block;\n  min-height: 1.5rem;\n  padding-left: 1.5rem;\n}\n\n.custom-control-inline {\n  display: -ms-inline-flexbox;\n  display: inline-flex;\n  margin-right: 1rem;\n}\n\n.custom-control-input {\n  position: absolute;\n  z-index: -1;\n  opacity: 0;\n}\n\n.custom-control-input:checked ~ .custom-control-label::before {\n  color: #fff;\n  border-color: #007bff;\n  background-color: #007bff;\n}\n\n.custom-control-input:focus ~ .custom-control-label::before {\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-control-input:focus:not(:checked) ~ .custom-control-label::before {\n  border-color: #80bdff;\n}\n\n.custom-control-input:not(:disabled):active ~ .custom-control-label::before {\n  color: #fff;\n  background-color: #b3d7ff;\n  border-color: #b3d7ff;\n}\n\n.custom-control-input:disabled ~ .custom-control-label {\n  color: #6c757d;\n}\n\n.custom-control-input:disabled ~ .custom-control-label::before {\n  background-color: #e9ecef;\n}\n\n.custom-control-label {\n  position: relative;\n  margin-bottom: 0;\n  vertical-align: top;\n}\n\n.custom-control-label::before {\n  position: absolute;\n  top: 0.25rem;\n  left: -1.5rem;\n  display: block;\n  width: 1rem;\n  height: 1rem;\n  pointer-events: none;\n  content: \"\";\n  background-color: #fff;\n  border: #adb5bd solid 1px;\n}\n\n.custom-control-label::after {\n  position: absolute;\n  top: 0.25rem;\n  left: -1.5rem;\n  display: block;\n  width: 1rem;\n  height: 1rem;\n  content: \"\";\n  background: no-repeat 50% / 50% 50%;\n}\n\n.custom-checkbox .custom-control-label::before {\n  border-radius: 0.25rem;\n}\n\n.custom-checkbox .custom-control-input:checked ~ .custom-control-label::after {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 8 8'%3e%3cpath fill='%23fff' d='M6.564.75l-3.59 3.612-1.538-1.55L0 4.26 2.974 7.25 8 2.193z'/%3e%3c/svg%3e\");\n}\n\n.custom-checkbox .custom-control-input:indeterminate ~ .custom-control-label::before {\n  border-color: #007bff;\n  background-color: #007bff;\n}\n\n.custom-checkbox .custom-control-input:indeterminate ~ .custom-control-label::after {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 4'%3e%3cpath stroke='%23fff' d='M0 2h4'/%3e%3c/svg%3e\");\n}\n\n.custom-checkbox .custom-control-input:disabled:checked ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-checkbox .custom-control-input:disabled:indeterminate ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-radio .custom-control-label::before {\n  border-radius: 50%;\n}\n\n.custom-radio .custom-control-input:checked ~ .custom-control-label::after {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='-4 -4 8 8'%3e%3ccircle r='3' fill='%23fff'/%3e%3c/svg%3e\");\n}\n\n.custom-radio .custom-control-input:disabled:checked ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-switch {\n  padding-left: 2.25rem;\n}\n\n.custom-switch .custom-control-label::before {\n  left: -2.25rem;\n  width: 1.75rem;\n  pointer-events: all;\n  border-radius: 0.5rem;\n}\n\n.custom-switch .custom-control-label::after {\n  top: calc(0.25rem + 2px);\n  left: calc(-2.25rem + 2px);\n  width: calc(1rem - 4px);\n  height: calc(1rem - 4px);\n  background-color: #adb5bd;\n  border-radius: 0.5rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out, -webkit-transform 0.15s ease-in-out;\n  transition: transform 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  transition: transform 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out, -webkit-transform 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-switch .custom-control-label::after {\n    transition: none;\n  }\n}\n\n.custom-switch .custom-control-input:checked ~ .custom-control-label::after {\n  background-color: #fff;\n  -webkit-transform: translateX(0.75rem);\n  transform: translateX(0.75rem);\n}\n\n.custom-switch .custom-control-input:disabled:checked ~ .custom-control-label::before {\n  background-color: rgba(0, 123, 255, 0.5);\n}\n\n.custom-select {\n  display: inline-block;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  padding: 0.375rem 1.75rem 0.375rem 0.75rem;\n  font-size: 1rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  vertical-align: middle;\n  background: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e\") no-repeat right 0.75rem center/8px 10px;\n  background-color: #fff;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n  -webkit-appearance: none;\n  -moz-appearance: none;\n  appearance: none;\n}\n\n.custom-select:focus {\n  border-color: #80bdff;\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-select:focus::-ms-value {\n  color: #495057;\n  background-color: #fff;\n}\n\n.custom-select[multiple], .custom-select[size]:not([size=\"1\"]) {\n  height: auto;\n  padding-right: 0.75rem;\n  background-image: none;\n}\n\n.custom-select:disabled {\n  color: #6c757d;\n  background-color: #e9ecef;\n}\n\n.custom-select::-ms-expand {\n  display: none;\n}\n\n.custom-select-sm {\n  height: calc(1.5em + 0.5rem + 2px);\n  padding-top: 0.25rem;\n  padding-bottom: 0.25rem;\n  padding-left: 0.5rem;\n  font-size: 0.875rem;\n}\n\n.custom-select-lg {\n  height: calc(1.5em + 1rem + 2px);\n  padding-top: 0.5rem;\n  padding-bottom: 0.5rem;\n  padding-left: 1rem;\n  font-size: 1.25rem;\n}\n\n.custom-file {\n  position: relative;\n  display: inline-block;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  margin-bottom: 0;\n}\n\n.custom-file-input {\n  position: relative;\n  z-index: 2;\n  width: 100%;\n  height: calc(1.5em + 0.75rem + 2px);\n  margin: 0;\n  opacity: 0;\n}\n\n.custom-file-input:focus ~ .custom-file-label {\n  border-color: #80bdff;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-file-input:disabled ~ .custom-file-label {\n  background-color: #e9ecef;\n}\n\n.custom-file-input:lang(en) ~ .custom-file-label::after {\n  content: \"Browse\";\n}\n\n.custom-file-input ~ .custom-file-label[data-browse]::after {\n  content: attr(data-browse);\n}\n\n.custom-file-label {\n  position: absolute;\n  top: 0;\n  right: 0;\n  left: 0;\n  z-index: 1;\n  height: calc(1.5em + 0.75rem + 2px);\n  padding: 0.375rem 0.75rem;\n  font-weight: 400;\n  line-height: 1.5;\n  color: #495057;\n  background-color: #fff;\n  border: 1px solid #ced4da;\n  border-radius: 0.25rem;\n}\n\n.custom-file-label::after {\n  position: absolute;\n  top: 0;\n  right: 0;\n  bottom: 0;\n  z-index: 3;\n  display: block;\n  height: calc(1.5em + 0.75rem);\n  padding: 0.375rem 0.75rem;\n  line-height: 1.5;\n  color: #495057;\n  content: \"Browse\";\n  background-color: #e9ecef;\n  border-left: inherit;\n  border-radius: 0 0.25rem 0.25rem 0;\n}\n\n.custom-range {\n  width: 100%;\n  height: calc(1rem + 0.4rem);\n  padding: 0;\n  background-color: transparent;\n  -webkit-appearance: none;\n  -moz-appearance: none;\n  appearance: none;\n}\n\n.custom-range:focus {\n  outline: none;\n}\n\n.custom-range:focus::-webkit-slider-thumb {\n  box-shadow: 0 0 0 1px #fff, 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-range:focus::-moz-range-thumb {\n  box-shadow: 0 0 0 1px #fff, 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-range:focus::-ms-thumb {\n  box-shadow: 0 0 0 1px #fff, 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.custom-range::-moz-focus-outer {\n  border: 0;\n}\n\n.custom-range::-webkit-slider-thumb {\n  width: 1rem;\n  height: 1rem;\n  margin-top: -0.25rem;\n  background-color: #007bff;\n  border: 0;\n  border-radius: 1rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  -webkit-appearance: none;\n  appearance: none;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-range::-webkit-slider-thumb {\n    transition: none;\n  }\n}\n\n.custom-range::-webkit-slider-thumb:active {\n  background-color: #b3d7ff;\n}\n\n.custom-range::-webkit-slider-runnable-track {\n  width: 100%;\n  height: 0.5rem;\n  color: transparent;\n  cursor: pointer;\n  background-color: #dee2e6;\n  border-color: transparent;\n  border-radius: 1rem;\n}\n\n.custom-range::-moz-range-thumb {\n  width: 1rem;\n  height: 1rem;\n  background-color: #007bff;\n  border: 0;\n  border-radius: 1rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  -moz-appearance: none;\n  appearance: none;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-range::-moz-range-thumb {\n    transition: none;\n  }\n}\n\n.custom-range::-moz-range-thumb:active {\n  background-color: #b3d7ff;\n}\n\n.custom-range::-moz-range-track {\n  width: 100%;\n  height: 0.5rem;\n  color: transparent;\n  cursor: pointer;\n  background-color: #dee2e6;\n  border-color: transparent;\n  border-radius: 1rem;\n}\n\n.custom-range::-ms-thumb {\n  width: 1rem;\n  height: 1rem;\n  margin-top: 0;\n  margin-right: 0.2rem;\n  margin-left: 0.2rem;\n  background-color: #007bff;\n  border: 0;\n  border-radius: 1rem;\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n  appearance: none;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-range::-ms-thumb {\n    transition: none;\n  }\n}\n\n.custom-range::-ms-thumb:active {\n  background-color: #b3d7ff;\n}\n\n.custom-range::-ms-track {\n  width: 100%;\n  height: 0.5rem;\n  color: transparent;\n  cursor: pointer;\n  background-color: transparent;\n  border-color: transparent;\n  border-width: 0.5rem;\n}\n\n.custom-range::-ms-fill-lower {\n  background-color: #dee2e6;\n  border-radius: 1rem;\n}\n\n.custom-range::-ms-fill-upper {\n  margin-right: 15px;\n  background-color: #dee2e6;\n  border-radius: 1rem;\n}\n\n.custom-range:disabled::-webkit-slider-thumb {\n  background-color: #adb5bd;\n}\n\n.custom-range:disabled::-webkit-slider-runnable-track {\n  cursor: default;\n}\n\n.custom-range:disabled::-moz-range-thumb {\n  background-color: #adb5bd;\n}\n\n.custom-range:disabled::-moz-range-track {\n  cursor: default;\n}\n\n.custom-range:disabled::-ms-thumb {\n  background-color: #adb5bd;\n}\n\n.custom-control-label::before,\n.custom-file-label,\n.custom-select {\n  transition: background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .custom-control-label::before,\n  .custom-file-label,\n  .custom-select {\n    transition: none;\n  }\n}\n\n.nav {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  padding-left: 0;\n  margin-bottom: 0;\n  list-style: none;\n}\n\n.nav-link {\n  display: block;\n  padding: 0.5rem 1rem;\n}\n\n.nav-link:hover, .nav-link:focus {\n  text-decoration: none;\n}\n\n.nav-link.disabled {\n  color: #6c757d;\n  pointer-events: none;\n  cursor: default;\n}\n\n.nav-tabs {\n  border-bottom: 1px solid #dee2e6;\n}\n\n.nav-tabs .nav-item {\n  margin-bottom: -1px;\n}\n\n.nav-tabs .nav-link {\n  border: 1px solid transparent;\n  border-top-left-radius: 0.25rem;\n  border-top-right-radius: 0.25rem;\n}\n\n.nav-tabs .nav-link:hover, .nav-tabs .nav-link:focus {\n  border-color: #e9ecef #e9ecef #dee2e6;\n}\n\n.nav-tabs .nav-link.disabled {\n  color: #6c757d;\n  background-color: transparent;\n  border-color: transparent;\n}\n\n.nav-tabs .nav-link.active,\n.nav-tabs .nav-item.show .nav-link {\n  color: #495057;\n  background-color: #fff;\n  border-color: #dee2e6 #dee2e6 #fff;\n}\n\n.nav-tabs .dropdown-menu {\n  margin-top: -1px;\n  border-top-left-radius: 0;\n  border-top-right-radius: 0;\n}\n\n.nav-pills .nav-link {\n  border-radius: 0.25rem;\n}\n\n.nav-pills .nav-link.active,\n.nav-pills .show > .nav-link {\n  color: #fff;\n  background-color: #007bff;\n}\n\n.nav-fill .nav-item {\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  text-align: center;\n}\n\n.nav-justified .nav-item {\n  -ms-flex-preferred-size: 0;\n  flex-basis: 0;\n  -ms-flex-positive: 1;\n  flex-grow: 1;\n  text-align: center;\n}\n\n.tab-content > .tab-pane {\n  display: none;\n}\n\n.tab-content > .active {\n  display: block;\n}\n\n.navbar {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: justify;\n  justify-content: space-between;\n  padding: 0.5rem 1rem;\n}\n\n.navbar > .container,\n.navbar > .container-fluid {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: justify;\n  justify-content: space-between;\n}\n\n.navbar-brand {\n  display: inline-block;\n  padding-top: 0.3125rem;\n  padding-bottom: 0.3125rem;\n  margin-right: 1rem;\n  font-size: 1.25rem;\n  line-height: inherit;\n  white-space: nowrap;\n}\n\n.navbar-brand:hover, .navbar-brand:focus {\n  text-decoration: none;\n}\n\n.navbar-nav {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  padding-left: 0;\n  margin-bottom: 0;\n  list-style: none;\n}\n\n.navbar-nav .nav-link {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.navbar-nav .dropdown-menu {\n  position: static;\n  float: none;\n}\n\n.navbar-text {\n  display: inline-block;\n  padding-top: 0.5rem;\n  padding-bottom: 0.5rem;\n}\n\n.navbar-collapse {\n  -ms-flex-preferred-size: 100%;\n  flex-basis: 100%;\n  -ms-flex-positive: 1;\n  flex-grow: 1;\n  -ms-flex-align: center;\n  align-items: center;\n}\n\n.navbar-toggler {\n  padding: 0.25rem 0.75rem;\n  font-size: 1.25rem;\n  line-height: 1;\n  background-color: transparent;\n  border: 1px solid transparent;\n  border-radius: 0.25rem;\n}\n\n.navbar-toggler:hover, .navbar-toggler:focus {\n  text-decoration: none;\n}\n\n.navbar-toggler-icon {\n  display: inline-block;\n  width: 1.5em;\n  height: 1.5em;\n  vertical-align: middle;\n  content: \"\";\n  background: no-repeat center center;\n  background-size: 100% 100%;\n}\n\n@media (max-width: 575.98px) {\n  .navbar-expand-sm > .container,\n  .navbar-expand-sm > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 576px) {\n  .navbar-expand-sm {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-sm .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-sm .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-sm .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-sm > .container,\n  .navbar-expand-sm > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-sm .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-sm .navbar-toggler {\n    display: none;\n  }\n}\n\n@media (max-width: 767.98px) {\n  .navbar-expand-md > .container,\n  .navbar-expand-md > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 768px) {\n  .navbar-expand-md {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-md .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-md .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-md .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-md > .container,\n  .navbar-expand-md > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-md .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-md .navbar-toggler {\n    display: none;\n  }\n}\n\n@media (max-width: 991.98px) {\n  .navbar-expand-lg > .container,\n  .navbar-expand-lg > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 992px) {\n  .navbar-expand-lg {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-lg .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-lg .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-lg .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-lg > .container,\n  .navbar-expand-lg > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-lg .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-lg .navbar-toggler {\n    display: none;\n  }\n}\n\n@media (max-width: 1199.98px) {\n  .navbar-expand-xl > .container,\n  .navbar-expand-xl > .container-fluid {\n    padding-right: 0;\n    padding-left: 0;\n  }\n}\n\n@media (min-width: 1200px) {\n  .navbar-expand-xl {\n    -ms-flex-flow: row nowrap;\n    flex-flow: row nowrap;\n    -ms-flex-pack: start;\n    justify-content: flex-start;\n  }\n  .navbar-expand-xl .navbar-nav {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .navbar-expand-xl .navbar-nav .dropdown-menu {\n    position: absolute;\n  }\n  .navbar-expand-xl .navbar-nav .nav-link {\n    padding-right: 0.5rem;\n    padding-left: 0.5rem;\n  }\n  .navbar-expand-xl > .container,\n  .navbar-expand-xl > .container-fluid {\n    -ms-flex-wrap: nowrap;\n    flex-wrap: nowrap;\n  }\n  .navbar-expand-xl .navbar-collapse {\n    display: -ms-flexbox !important;\n    display: flex !important;\n    -ms-flex-preferred-size: auto;\n    flex-basis: auto;\n  }\n  .navbar-expand-xl .navbar-toggler {\n    display: none;\n  }\n}\n\n.navbar-expand {\n  -ms-flex-flow: row nowrap;\n  flex-flow: row nowrap;\n  -ms-flex-pack: start;\n  justify-content: flex-start;\n}\n\n.navbar-expand > .container,\n.navbar-expand > .container-fluid {\n  padding-right: 0;\n  padding-left: 0;\n}\n\n.navbar-expand .navbar-nav {\n  -ms-flex-direction: row;\n  flex-direction: row;\n}\n\n.navbar-expand .navbar-nav .dropdown-menu {\n  position: absolute;\n}\n\n.navbar-expand .navbar-nav .nav-link {\n  padding-right: 0.5rem;\n  padding-left: 0.5rem;\n}\n\n.navbar-expand > .container,\n.navbar-expand > .container-fluid {\n  -ms-flex-wrap: nowrap;\n  flex-wrap: nowrap;\n}\n\n.navbar-expand .navbar-collapse {\n  display: -ms-flexbox !important;\n  display: flex !important;\n  -ms-flex-preferred-size: auto;\n  flex-basis: auto;\n}\n\n.navbar-expand .navbar-toggler {\n  display: none;\n}\n\n.navbar-light .navbar-brand {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-brand:hover, .navbar-light .navbar-brand:focus {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-nav .nav-link {\n  color: rgba(0, 0, 0, 0.5);\n}\n\n.navbar-light .navbar-nav .nav-link:hover, .navbar-light .navbar-nav .nav-link:focus {\n  color: rgba(0, 0, 0, 0.7);\n}\n\n.navbar-light .navbar-nav .nav-link.disabled {\n  color: rgba(0, 0, 0, 0.3);\n}\n\n.navbar-light .navbar-nav .show > .nav-link,\n.navbar-light .navbar-nav .active > .nav-link,\n.navbar-light .navbar-nav .nav-link.show,\n.navbar-light .navbar-nav .nav-link.active {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-toggler {\n  color: rgba(0, 0, 0, 0.5);\n  border-color: rgba(0, 0, 0, 0.1);\n}\n\n.navbar-light .navbar-toggler-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg viewBox='0 0 30 30' xmlns='http://www.w3.org/2000/svg'%3e%3cpath stroke='rgba(0, 0, 0, 0.5)' stroke-width='2' stroke-linecap='round' stroke-miterlimit='10' d='M4 7h22M4 15h22M4 23h22'/%3e%3c/svg%3e\");\n}\n\n.navbar-light .navbar-text {\n  color: rgba(0, 0, 0, 0.5);\n}\n\n.navbar-light .navbar-text a {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-light .navbar-text a:hover, .navbar-light .navbar-text a:focus {\n  color: rgba(0, 0, 0, 0.9);\n}\n\n.navbar-dark .navbar-brand {\n  color: #fff;\n}\n\n.navbar-dark .navbar-brand:hover, .navbar-dark .navbar-brand:focus {\n  color: #fff;\n}\n\n.navbar-dark .navbar-nav .nav-link {\n  color: rgba(255, 255, 255, 0.5);\n}\n\n.navbar-dark .navbar-nav .nav-link:hover, .navbar-dark .navbar-nav .nav-link:focus {\n  color: rgba(255, 255, 255, 0.75);\n}\n\n.navbar-dark .navbar-nav .nav-link.disabled {\n  color: rgba(255, 255, 255, 0.25);\n}\n\n.navbar-dark .navbar-nav .show > .nav-link,\n.navbar-dark .navbar-nav .active > .nav-link,\n.navbar-dark .navbar-nav .nav-link.show,\n.navbar-dark .navbar-nav .nav-link.active {\n  color: #fff;\n}\n\n.navbar-dark .navbar-toggler {\n  color: rgba(255, 255, 255, 0.5);\n  border-color: rgba(255, 255, 255, 0.1);\n}\n\n.navbar-dark .navbar-toggler-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg viewBox='0 0 30 30' xmlns='http://www.w3.org/2000/svg'%3e%3cpath stroke='rgba(255, 255, 255, 0.5)' stroke-width='2' stroke-linecap='round' stroke-miterlimit='10' d='M4 7h22M4 15h22M4 23h22'/%3e%3c/svg%3e\");\n}\n\n.navbar-dark .navbar-text {\n  color: rgba(255, 255, 255, 0.5);\n}\n\n.navbar-dark .navbar-text a {\n  color: #fff;\n}\n\n.navbar-dark .navbar-text a:hover, .navbar-dark .navbar-text a:focus {\n  color: #fff;\n}\n\n.card {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  min-width: 0;\n  word-wrap: break-word;\n  background-color: #fff;\n  background-clip: border-box;\n  border: 1px solid rgba(0, 0, 0, 0.125);\n  border-radius: 0.25rem;\n}\n\n.card > hr {\n  margin-right: 0;\n  margin-left: 0;\n}\n\n.card > .list-group:first-child .list-group-item:first-child {\n  border-top-left-radius: 0.25rem;\n  border-top-right-radius: 0.25rem;\n}\n\n.card > .list-group:last-child .list-group-item:last-child {\n  border-bottom-right-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n}\n\n.card-body {\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  padding: 1.25rem;\n}\n\n.card-title {\n  margin-bottom: 0.75rem;\n}\n\n.card-subtitle {\n  margin-top: -0.375rem;\n  margin-bottom: 0;\n}\n\n.card-text:last-child {\n  margin-bottom: 0;\n}\n\n.card-link:hover {\n  text-decoration: none;\n}\n\n.card-link + .card-link {\n  margin-left: 1.25rem;\n}\n\n.card-header {\n  padding: 0.75rem 1.25rem;\n  margin-bottom: 0;\n  background-color: rgba(0, 0, 0, 0.03);\n  border-bottom: 1px solid rgba(0, 0, 0, 0.125);\n}\n\n.card-header:first-child {\n  border-radius: calc(0.25rem - 1px) calc(0.25rem - 1px) 0 0;\n}\n\n.card-header + .list-group .list-group-item:first-child {\n  border-top: 0;\n}\n\n.card-footer {\n  padding: 0.75rem 1.25rem;\n  background-color: rgba(0, 0, 0, 0.03);\n  border-top: 1px solid rgba(0, 0, 0, 0.125);\n}\n\n.card-footer:last-child {\n  border-radius: 0 0 calc(0.25rem - 1px) calc(0.25rem - 1px);\n}\n\n.card-header-tabs {\n  margin-right: -0.625rem;\n  margin-bottom: -0.75rem;\n  margin-left: -0.625rem;\n  border-bottom: 0;\n}\n\n.card-header-pills {\n  margin-right: -0.625rem;\n  margin-left: -0.625rem;\n}\n\n.card-img-overlay {\n  position: absolute;\n  top: 0;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  padding: 1.25rem;\n}\n\n.card-img {\n  width: 100%;\n  border-radius: calc(0.25rem - 1px);\n}\n\n.card-img-top {\n  width: 100%;\n  border-top-left-radius: calc(0.25rem - 1px);\n  border-top-right-radius: calc(0.25rem - 1px);\n}\n\n.card-img-bottom {\n  width: 100%;\n  border-bottom-right-radius: calc(0.25rem - 1px);\n  border-bottom-left-radius: calc(0.25rem - 1px);\n}\n\n.card-deck {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n}\n\n.card-deck .card {\n  margin-bottom: 15px;\n}\n\n@media (min-width: 576px) {\n  .card-deck {\n    -ms-flex-flow: row wrap;\n    flex-flow: row wrap;\n    margin-right: -15px;\n    margin-left: -15px;\n  }\n  .card-deck .card {\n    display: -ms-flexbox;\n    display: flex;\n    -ms-flex: 1 0 0%;\n    flex: 1 0 0%;\n    -ms-flex-direction: column;\n    flex-direction: column;\n    margin-right: 15px;\n    margin-bottom: 0;\n    margin-left: 15px;\n  }\n}\n\n.card-group {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n}\n\n.card-group > .card {\n  margin-bottom: 15px;\n}\n\n@media (min-width: 576px) {\n  .card-group {\n    -ms-flex-flow: row wrap;\n    flex-flow: row wrap;\n  }\n  .card-group > .card {\n    -ms-flex: 1 0 0%;\n    flex: 1 0 0%;\n    margin-bottom: 0;\n  }\n  .card-group > .card + .card {\n    margin-left: 0;\n    border-left: 0;\n  }\n  .card-group > .card:not(:last-child) {\n    border-top-right-radius: 0;\n    border-bottom-right-radius: 0;\n  }\n  .card-group > .card:not(:last-child) .card-img-top,\n  .card-group > .card:not(:last-child) .card-header {\n    border-top-right-radius: 0;\n  }\n  .card-group > .card:not(:last-child) .card-img-bottom,\n  .card-group > .card:not(:last-child) .card-footer {\n    border-bottom-right-radius: 0;\n  }\n  .card-group > .card:not(:first-child) {\n    border-top-left-radius: 0;\n    border-bottom-left-radius: 0;\n  }\n  .card-group > .card:not(:first-child) .card-img-top,\n  .card-group > .card:not(:first-child) .card-header {\n    border-top-left-radius: 0;\n  }\n  .card-group > .card:not(:first-child) .card-img-bottom,\n  .card-group > .card:not(:first-child) .card-footer {\n    border-bottom-left-radius: 0;\n  }\n}\n\n.card-columns .card {\n  margin-bottom: 0.75rem;\n}\n\n@media (min-width: 576px) {\n  .card-columns {\n    -webkit-column-count: 3;\n    -moz-column-count: 3;\n    column-count: 3;\n    -webkit-column-gap: 1.25rem;\n    -moz-column-gap: 1.25rem;\n    column-gap: 1.25rem;\n    orphans: 1;\n    widows: 1;\n  }\n  .card-columns .card {\n    display: inline-block;\n    width: 100%;\n  }\n}\n\n.accordion > .card {\n  overflow: hidden;\n}\n\n.accordion > .card:not(:first-of-type) .card-header:first-child {\n  border-radius: 0;\n}\n\n.accordion > .card:not(:first-of-type):not(:last-of-type) {\n  border-bottom: 0;\n  border-radius: 0;\n}\n\n.accordion > .card:first-of-type {\n  border-bottom: 0;\n  border-bottom-right-radius: 0;\n  border-bottom-left-radius: 0;\n}\n\n.accordion > .card:last-of-type {\n  border-top-left-radius: 0;\n  border-top-right-radius: 0;\n}\n\n.accordion > .card .card-header {\n  margin-bottom: -1px;\n}\n\n.breadcrumb {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-wrap: wrap;\n  flex-wrap: wrap;\n  padding: 0.75rem 1rem;\n  margin-bottom: 1rem;\n  list-style: none;\n  background-color: #e9ecef;\n  border-radius: 0.25rem;\n}\n\n.breadcrumb-item + .breadcrumb-item {\n  padding-left: 0.5rem;\n}\n\n.breadcrumb-item + .breadcrumb-item::before {\n  display: inline-block;\n  padding-right: 0.5rem;\n  color: #6c757d;\n  content: \"/\";\n}\n\n.breadcrumb-item + .breadcrumb-item:hover::before {\n  text-decoration: underline;\n}\n\n.breadcrumb-item + .breadcrumb-item:hover::before {\n  text-decoration: none;\n}\n\n.breadcrumb-item.active {\n  color: #6c757d;\n}\n\n.pagination {\n  display: -ms-flexbox;\n  display: flex;\n  padding-left: 0;\n  list-style: none;\n  border-radius: 0.25rem;\n}\n\n.page-link {\n  position: relative;\n  display: block;\n  padding: 0.5rem 0.75rem;\n  margin-left: -1px;\n  line-height: 1.25;\n  color: #007bff;\n  background-color: #fff;\n  border: 1px solid #dee2e6;\n}\n\n.page-link:hover {\n  z-index: 2;\n  color: #0056b3;\n  text-decoration: none;\n  background-color: #e9ecef;\n  border-color: #dee2e6;\n}\n\n.page-link:focus {\n  z-index: 2;\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.25);\n}\n\n.page-item:first-child .page-link {\n  margin-left: 0;\n  border-top-left-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n}\n\n.page-item:last-child .page-link {\n  border-top-right-radius: 0.25rem;\n  border-bottom-right-radius: 0.25rem;\n}\n\n.page-item.active .page-link {\n  z-index: 1;\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.page-item.disabled .page-link {\n  color: #6c757d;\n  pointer-events: none;\n  cursor: auto;\n  background-color: #fff;\n  border-color: #dee2e6;\n}\n\n.pagination-lg .page-link {\n  padding: 0.75rem 1.5rem;\n  font-size: 1.25rem;\n  line-height: 1.5;\n}\n\n.pagination-lg .page-item:first-child .page-link {\n  border-top-left-radius: 0.3rem;\n  border-bottom-left-radius: 0.3rem;\n}\n\n.pagination-lg .page-item:last-child .page-link {\n  border-top-right-radius: 0.3rem;\n  border-bottom-right-radius: 0.3rem;\n}\n\n.pagination-sm .page-link {\n  padding: 0.25rem 0.5rem;\n  font-size: 0.875rem;\n  line-height: 1.5;\n}\n\n.pagination-sm .page-item:first-child .page-link {\n  border-top-left-radius: 0.2rem;\n  border-bottom-left-radius: 0.2rem;\n}\n\n.pagination-sm .page-item:last-child .page-link {\n  border-top-right-radius: 0.2rem;\n  border-bottom-right-radius: 0.2rem;\n}\n\n.badge {\n  display: inline-block;\n  padding: 0.25em 0.4em;\n  font-size: 75%;\n  font-weight: 700;\n  line-height: 1;\n  text-align: center;\n  white-space: nowrap;\n  vertical-align: baseline;\n  border-radius: 0.25rem;\n  transition: color 0.15s ease-in-out, background-color 0.15s ease-in-out, border-color 0.15s ease-in-out, box-shadow 0.15s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .badge {\n    transition: none;\n  }\n}\n\na.badge:hover, a.badge:focus {\n  text-decoration: none;\n}\n\n.badge:empty {\n  display: none;\n}\n\n.btn .badge {\n  position: relative;\n  top: -1px;\n}\n\n.badge-pill {\n  padding-right: 0.6em;\n  padding-left: 0.6em;\n  border-radius: 10rem;\n}\n\n.badge-primary {\n  color: #fff;\n  background-color: #007bff;\n}\n\na.badge-primary:hover, a.badge-primary:focus {\n  color: #fff;\n  background-color: #0062cc;\n}\n\na.badge-primary:focus, a.badge-primary.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(0, 123, 255, 0.5);\n}\n\n.badge-secondary {\n  color: #fff;\n  background-color: #6c757d;\n}\n\na.badge-secondary:hover, a.badge-secondary:focus {\n  color: #fff;\n  background-color: #545b62;\n}\n\na.badge-secondary:focus, a.badge-secondary.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(108, 117, 125, 0.5);\n}\n\n.badge-success {\n  color: #fff;\n  background-color: #28a745;\n}\n\na.badge-success:hover, a.badge-success:focus {\n  color: #fff;\n  background-color: #1e7e34;\n}\n\na.badge-success:focus, a.badge-success.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(40, 167, 69, 0.5);\n}\n\n.badge-info {\n  color: #fff;\n  background-color: #17a2b8;\n}\n\na.badge-info:hover, a.badge-info:focus {\n  color: #fff;\n  background-color: #117a8b;\n}\n\na.badge-info:focus, a.badge-info.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(23, 162, 184, 0.5);\n}\n\n.badge-warning {\n  color: #212529;\n  background-color: #ffc107;\n}\n\na.badge-warning:hover, a.badge-warning:focus {\n  color: #212529;\n  background-color: #d39e00;\n}\n\na.badge-warning:focus, a.badge-warning.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(255, 193, 7, 0.5);\n}\n\n.badge-danger {\n  color: #fff;\n  background-color: #dc3545;\n}\n\na.badge-danger:hover, a.badge-danger:focus {\n  color: #fff;\n  background-color: #bd2130;\n}\n\na.badge-danger:focus, a.badge-danger.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(220, 53, 69, 0.5);\n}\n\n.badge-light {\n  color: #212529;\n  background-color: #f8f9fa;\n}\n\na.badge-light:hover, a.badge-light:focus {\n  color: #212529;\n  background-color: #dae0e5;\n}\n\na.badge-light:focus, a.badge-light.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(248, 249, 250, 0.5);\n}\n\n.badge-dark {\n  color: #fff;\n  background-color: #343a40;\n}\n\na.badge-dark:hover, a.badge-dark:focus {\n  color: #fff;\n  background-color: #1d2124;\n}\n\na.badge-dark:focus, a.badge-dark.focus {\n  outline: 0;\n  box-shadow: 0 0 0 0.2rem rgba(52, 58, 64, 0.5);\n}\n\n.jumbotron {\n  padding: 2rem 1rem;\n  margin-bottom: 2rem;\n  background-color: #e9ecef;\n  border-radius: 0.3rem;\n}\n\n@media (min-width: 576px) {\n  .jumbotron {\n    padding: 4rem 2rem;\n  }\n}\n\n.jumbotron-fluid {\n  padding-right: 0;\n  padding-left: 0;\n  border-radius: 0;\n}\n\n.alert {\n  position: relative;\n  padding: 0.75rem 1.25rem;\n  margin-bottom: 1rem;\n  border: 1px solid transparent;\n  border-radius: 0.25rem;\n}\n\n.alert-heading {\n  color: inherit;\n}\n\n.alert-link {\n  font-weight: 700;\n}\n\n.alert-dismissible {\n  padding-right: 4rem;\n}\n\n.alert-dismissible .close {\n  position: absolute;\n  top: 0;\n  right: 0;\n  padding: 0.75rem 1.25rem;\n  color: inherit;\n}\n\n.alert-primary {\n  color: #004085;\n  background-color: #cce5ff;\n  border-color: #b8daff;\n}\n\n.alert-primary hr {\n  border-top-color: #9fcdff;\n}\n\n.alert-primary .alert-link {\n  color: #002752;\n}\n\n.alert-secondary {\n  color: #383d41;\n  background-color: #e2e3e5;\n  border-color: #d6d8db;\n}\n\n.alert-secondary hr {\n  border-top-color: #c8cbcf;\n}\n\n.alert-secondary .alert-link {\n  color: #202326;\n}\n\n.alert-success {\n  color: #155724;\n  background-color: #d4edda;\n  border-color: #c3e6cb;\n}\n\n.alert-success hr {\n  border-top-color: #b1dfbb;\n}\n\n.alert-success .alert-link {\n  color: #0b2e13;\n}\n\n.alert-info {\n  color: #0c5460;\n  background-color: #d1ecf1;\n  border-color: #bee5eb;\n}\n\n.alert-info hr {\n  border-top-color: #abdde5;\n}\n\n.alert-info .alert-link {\n  color: #062c33;\n}\n\n.alert-warning {\n  color: #856404;\n  background-color: #fff3cd;\n  border-color: #ffeeba;\n}\n\n.alert-warning hr {\n  border-top-color: #ffe8a1;\n}\n\n.alert-warning .alert-link {\n  color: #533f03;\n}\n\n.alert-danger {\n  color: #721c24;\n  background-color: #f8d7da;\n  border-color: #f5c6cb;\n}\n\n.alert-danger hr {\n  border-top-color: #f1b0b7;\n}\n\n.alert-danger .alert-link {\n  color: #491217;\n}\n\n.alert-light {\n  color: #818182;\n  background-color: #fefefe;\n  border-color: #fdfdfe;\n}\n\n.alert-light hr {\n  border-top-color: #ececf6;\n}\n\n.alert-light .alert-link {\n  color: #686868;\n}\n\n.alert-dark {\n  color: #1b1e21;\n  background-color: #d6d8d9;\n  border-color: #c6c8ca;\n}\n\n.alert-dark hr {\n  border-top-color: #b9bbbe;\n}\n\n.alert-dark .alert-link {\n  color: #040505;\n}\n\n@-webkit-keyframes progress-bar-stripes {\n  from {\n    background-position: 1rem 0;\n  }\n  to {\n    background-position: 0 0;\n  }\n}\n\n@keyframes progress-bar-stripes {\n  from {\n    background-position: 1rem 0;\n  }\n  to {\n    background-position: 0 0;\n  }\n}\n\n.progress {\n  display: -ms-flexbox;\n  display: flex;\n  height: 1rem;\n  overflow: hidden;\n  font-size: 0.75rem;\n  background-color: #e9ecef;\n  border-radius: 0.25rem;\n}\n\n.progress-bar {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  -ms-flex-pack: center;\n  justify-content: center;\n  color: #fff;\n  text-align: center;\n  white-space: nowrap;\n  background-color: #007bff;\n  transition: width 0.6s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .progress-bar {\n    transition: none;\n  }\n}\n\n.progress-bar-striped {\n  background-image: linear-gradient(45deg, rgba(255, 255, 255, 0.15) 25%, transparent 25%, transparent 50%, rgba(255, 255, 255, 0.15) 50%, rgba(255, 255, 255, 0.15) 75%, transparent 75%, transparent);\n  background-size: 1rem 1rem;\n}\n\n.progress-bar-animated {\n  -webkit-animation: progress-bar-stripes 1s linear infinite;\n  animation: progress-bar-stripes 1s linear infinite;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .progress-bar-animated {\n    -webkit-animation: none;\n    animation: none;\n  }\n}\n\n.media {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: start;\n  align-items: flex-start;\n}\n\n.media-body {\n  -ms-flex: 1;\n  flex: 1;\n}\n\n.list-group {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  padding-left: 0;\n  margin-bottom: 0;\n}\n\n.list-group-item-action {\n  width: 100%;\n  color: #495057;\n  text-align: inherit;\n}\n\n.list-group-item-action:hover, .list-group-item-action:focus {\n  z-index: 1;\n  color: #495057;\n  text-decoration: none;\n  background-color: #f8f9fa;\n}\n\n.list-group-item-action:active {\n  color: #212529;\n  background-color: #e9ecef;\n}\n\n.list-group-item {\n  position: relative;\n  display: block;\n  padding: 0.75rem 1.25rem;\n  margin-bottom: -1px;\n  background-color: #fff;\n  border: 1px solid rgba(0, 0, 0, 0.125);\n}\n\n.list-group-item:first-child {\n  border-top-left-radius: 0.25rem;\n  border-top-right-radius: 0.25rem;\n}\n\n.list-group-item:last-child {\n  margin-bottom: 0;\n  border-bottom-right-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n}\n\n.list-group-item.disabled, .list-group-item:disabled {\n  color: #6c757d;\n  pointer-events: none;\n  background-color: #fff;\n}\n\n.list-group-item.active {\n  z-index: 2;\n  color: #fff;\n  background-color: #007bff;\n  border-color: #007bff;\n}\n\n.list-group-horizontal {\n  -ms-flex-direction: row;\n  flex-direction: row;\n}\n\n.list-group-horizontal .list-group-item {\n  margin-right: -1px;\n  margin-bottom: 0;\n}\n\n.list-group-horizontal .list-group-item:first-child {\n  border-top-left-radius: 0.25rem;\n  border-bottom-left-radius: 0.25rem;\n  border-top-right-radius: 0;\n}\n\n.list-group-horizontal .list-group-item:last-child {\n  margin-right: 0;\n  border-top-right-radius: 0.25rem;\n  border-bottom-right-radius: 0.25rem;\n  border-bottom-left-radius: 0;\n}\n\n@media (min-width: 576px) {\n  .list-group-horizontal-sm {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-sm .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-sm .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-sm .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n@media (min-width: 768px) {\n  .list-group-horizontal-md {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-md .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-md .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-md .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n@media (min-width: 992px) {\n  .list-group-horizontal-lg {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-lg .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-lg .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-lg .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n@media (min-width: 1200px) {\n  .list-group-horizontal-xl {\n    -ms-flex-direction: row;\n    flex-direction: row;\n  }\n  .list-group-horizontal-xl .list-group-item {\n    margin-right: -1px;\n    margin-bottom: 0;\n  }\n  .list-group-horizontal-xl .list-group-item:first-child {\n    border-top-left-radius: 0.25rem;\n    border-bottom-left-radius: 0.25rem;\n    border-top-right-radius: 0;\n  }\n  .list-group-horizontal-xl .list-group-item:last-child {\n    margin-right: 0;\n    border-top-right-radius: 0.25rem;\n    border-bottom-right-radius: 0.25rem;\n    border-bottom-left-radius: 0;\n  }\n}\n\n.list-group-flush .list-group-item {\n  border-right: 0;\n  border-left: 0;\n  border-radius: 0;\n}\n\n.list-group-flush .list-group-item:last-child {\n  margin-bottom: -1px;\n}\n\n.list-group-flush:first-child .list-group-item:first-child {\n  border-top: 0;\n}\n\n.list-group-flush:last-child .list-group-item:last-child {\n  margin-bottom: 0;\n  border-bottom: 0;\n}\n\n.list-group-item-primary {\n  color: #004085;\n  background-color: #b8daff;\n}\n\n.list-group-item-primary.list-group-item-action:hover, .list-group-item-primary.list-group-item-action:focus {\n  color: #004085;\n  background-color: #9fcdff;\n}\n\n.list-group-item-primary.list-group-item-action.active {\n  color: #fff;\n  background-color: #004085;\n  border-color: #004085;\n}\n\n.list-group-item-secondary {\n  color: #383d41;\n  background-color: #d6d8db;\n}\n\n.list-group-item-secondary.list-group-item-action:hover, .list-group-item-secondary.list-group-item-action:focus {\n  color: #383d41;\n  background-color: #c8cbcf;\n}\n\n.list-group-item-secondary.list-group-item-action.active {\n  color: #fff;\n  background-color: #383d41;\n  border-color: #383d41;\n}\n\n.list-group-item-success {\n  color: #155724;\n  background-color: #c3e6cb;\n}\n\n.list-group-item-success.list-group-item-action:hover, .list-group-item-success.list-group-item-action:focus {\n  color: #155724;\n  background-color: #b1dfbb;\n}\n\n.list-group-item-success.list-group-item-action.active {\n  color: #fff;\n  background-color: #155724;\n  border-color: #155724;\n}\n\n.list-group-item-info {\n  color: #0c5460;\n  background-color: #bee5eb;\n}\n\n.list-group-item-info.list-group-item-action:hover, .list-group-item-info.list-group-item-action:focus {\n  color: #0c5460;\n  background-color: #abdde5;\n}\n\n.list-group-item-info.list-group-item-action.active {\n  color: #fff;\n  background-color: #0c5460;\n  border-color: #0c5460;\n}\n\n.list-group-item-warning {\n  color: #856404;\n  background-color: #ffeeba;\n}\n\n.list-group-item-warning.list-group-item-action:hover, .list-group-item-warning.list-group-item-action:focus {\n  color: #856404;\n  background-color: #ffe8a1;\n}\n\n.list-group-item-warning.list-group-item-action.active {\n  color: #fff;\n  background-color: #856404;\n  border-color: #856404;\n}\n\n.list-group-item-danger {\n  color: #721c24;\n  background-color: #f5c6cb;\n}\n\n.list-group-item-danger.list-group-item-action:hover, .list-group-item-danger.list-group-item-action:focus {\n  color: #721c24;\n  background-color: #f1b0b7;\n}\n\n.list-group-item-danger.list-group-item-action.active {\n  color: #fff;\n  background-color: #721c24;\n  border-color: #721c24;\n}\n\n.list-group-item-light {\n  color: #818182;\n  background-color: #fdfdfe;\n}\n\n.list-group-item-light.list-group-item-action:hover, .list-group-item-light.list-group-item-action:focus {\n  color: #818182;\n  background-color: #ececf6;\n}\n\n.list-group-item-light.list-group-item-action.active {\n  color: #fff;\n  background-color: #818182;\n  border-color: #818182;\n}\n\n.list-group-item-dark {\n  color: #1b1e21;\n  background-color: #c6c8ca;\n}\n\n.list-group-item-dark.list-group-item-action:hover, .list-group-item-dark.list-group-item-action:focus {\n  color: #1b1e21;\n  background-color: #b9bbbe;\n}\n\n.list-group-item-dark.list-group-item-action.active {\n  color: #fff;\n  background-color: #1b1e21;\n  border-color: #1b1e21;\n}\n\n.close {\n  float: right;\n  font-size: 1.5rem;\n  font-weight: 700;\n  line-height: 1;\n  color: #000;\n  text-shadow: 0 1px 0 #fff;\n  opacity: .5;\n}\n\n.close:hover {\n  color: #000;\n  text-decoration: none;\n}\n\n.close:not(:disabled):not(.disabled):hover, .close:not(:disabled):not(.disabled):focus {\n  opacity: .75;\n}\n\nbutton.close {\n  padding: 0;\n  background-color: transparent;\n  border: 0;\n  -webkit-appearance: none;\n  -moz-appearance: none;\n  appearance: none;\n}\n\na.close.disabled {\n  pointer-events: none;\n}\n\n.toast {\n  max-width: 350px;\n  overflow: hidden;\n  font-size: 0.875rem;\n  background-color: rgba(255, 255, 255, 0.85);\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.1);\n  box-shadow: 0 0.25rem 0.75rem rgba(0, 0, 0, 0.1);\n  -webkit-backdrop-filter: blur(10px);\n  backdrop-filter: blur(10px);\n  opacity: 0;\n  border-radius: 0.25rem;\n}\n\n.toast:not(:last-child) {\n  margin-bottom: 0.75rem;\n}\n\n.toast.showing {\n  opacity: 1;\n}\n\n.toast.show {\n  display: block;\n  opacity: 1;\n}\n\n.toast.hide {\n  display: none;\n}\n\n.toast-header {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  padding: 0.25rem 0.75rem;\n  color: #6c757d;\n  background-color: rgba(255, 255, 255, 0.85);\n  background-clip: padding-box;\n  border-bottom: 1px solid rgba(0, 0, 0, 0.05);\n}\n\n.toast-body {\n  padding: 0.75rem;\n}\n\n.modal-open {\n  overflow: hidden;\n}\n\n.modal-open .modal {\n  overflow-x: hidden;\n  overflow-y: auto;\n}\n\n.modal {\n  position: fixed;\n  top: 0;\n  left: 0;\n  z-index: 1050;\n  display: none;\n  width: 100%;\n  height: 100%;\n  overflow: hidden;\n  outline: 0;\n}\n\n.modal-dialog {\n  position: relative;\n  width: auto;\n  margin: 0.5rem;\n  pointer-events: none;\n}\n\n.modal.fade .modal-dialog {\n  transition: -webkit-transform 0.3s ease-out;\n  transition: transform 0.3s ease-out;\n  transition: transform 0.3s ease-out, -webkit-transform 0.3s ease-out;\n  -webkit-transform: translate(0, -50px);\n  transform: translate(0, -50px);\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .modal.fade .modal-dialog {\n    transition: none;\n  }\n}\n\n.modal.show .modal-dialog {\n  -webkit-transform: none;\n  transform: none;\n}\n\n.modal-dialog-scrollable {\n  display: -ms-flexbox;\n  display: flex;\n  max-height: calc(100% - 1rem);\n}\n\n.modal-dialog-scrollable .modal-content {\n  max-height: calc(100vh - 1rem);\n  overflow: hidden;\n}\n\n.modal-dialog-scrollable .modal-header,\n.modal-dialog-scrollable .modal-footer {\n  -ms-flex-negative: 0;\n  flex-shrink: 0;\n}\n\n.modal-dialog-scrollable .modal-body {\n  overflow-y: auto;\n}\n\n.modal-dialog-centered {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  min-height: calc(100% - 1rem);\n}\n\n.modal-dialog-centered::before {\n  display: block;\n  height: calc(100vh - 1rem);\n  content: \"\";\n}\n\n.modal-dialog-centered.modal-dialog-scrollable {\n  -ms-flex-direction: column;\n  flex-direction: column;\n  -ms-flex-pack: center;\n  justify-content: center;\n  height: 100%;\n}\n\n.modal-dialog-centered.modal-dialog-scrollable .modal-content {\n  max-height: none;\n}\n\n.modal-dialog-centered.modal-dialog-scrollable::before {\n  content: none;\n}\n\n.modal-content {\n  position: relative;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-direction: column;\n  flex-direction: column;\n  width: 100%;\n  pointer-events: auto;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.2);\n  border-radius: 0.3rem;\n  outline: 0;\n}\n\n.modal-backdrop {\n  position: fixed;\n  top: 0;\n  left: 0;\n  z-index: 1040;\n  width: 100vw;\n  height: 100vh;\n  background-color: #000;\n}\n\n.modal-backdrop.fade {\n  opacity: 0;\n}\n\n.modal-backdrop.show {\n  opacity: 0.5;\n}\n\n.modal-header {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: start;\n  align-items: flex-start;\n  -ms-flex-pack: justify;\n  justify-content: space-between;\n  padding: 1rem 1rem;\n  border-bottom: 1px solid #dee2e6;\n  border-top-left-radius: 0.3rem;\n  border-top-right-radius: 0.3rem;\n}\n\n.modal-header .close {\n  padding: 1rem 1rem;\n  margin: -1rem -1rem -1rem auto;\n}\n\n.modal-title {\n  margin-bottom: 0;\n  line-height: 1.5;\n}\n\n.modal-body {\n  position: relative;\n  -ms-flex: 1 1 auto;\n  flex: 1 1 auto;\n  padding: 1rem;\n}\n\n.modal-footer {\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: end;\n  justify-content: flex-end;\n  padding: 1rem;\n  border-top: 1px solid #dee2e6;\n  border-bottom-right-radius: 0.3rem;\n  border-bottom-left-radius: 0.3rem;\n}\n\n.modal-footer > :not(:first-child) {\n  margin-left: .25rem;\n}\n\n.modal-footer > :not(:last-child) {\n  margin-right: .25rem;\n}\n\n.modal-scrollbar-measure {\n  position: absolute;\n  top: -9999px;\n  width: 50px;\n  height: 50px;\n  overflow: scroll;\n}\n\n@media (min-width: 576px) {\n  .modal-dialog {\n    max-width: 500px;\n    margin: 1.75rem auto;\n  }\n  .modal-dialog-scrollable {\n    max-height: calc(100% - 3.5rem);\n  }\n  .modal-dialog-scrollable .modal-content {\n    max-height: calc(100vh - 3.5rem);\n  }\n  .modal-dialog-centered {\n    min-height: calc(100% - 3.5rem);\n  }\n  .modal-dialog-centered::before {\n    height: calc(100vh - 3.5rem);\n  }\n  .modal-sm {\n    max-width: 300px;\n  }\n}\n\n@media (min-width: 992px) {\n  .modal-lg,\n  .modal-xl {\n    max-width: 800px;\n  }\n}\n\n@media (min-width: 1200px) {\n  .modal-xl {\n    max-width: 1140px;\n  }\n}\n\n.tooltip {\n  position: absolute;\n  z-index: 1070;\n  display: block;\n  margin: 0;\n  font-family: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  font-style: normal;\n  font-weight: 400;\n  line-height: 1.5;\n  text-align: left;\n  text-align: start;\n  text-decoration: none;\n  text-shadow: none;\n  text-transform: none;\n  letter-spacing: normal;\n  word-break: normal;\n  word-spacing: normal;\n  white-space: normal;\n  line-break: auto;\n  font-size: 0.875rem;\n  word-wrap: break-word;\n  opacity: 0;\n}\n\n.tooltip.show {\n  opacity: 0.9;\n}\n\n.tooltip .arrow {\n  position: absolute;\n  display: block;\n  width: 0.8rem;\n  height: 0.4rem;\n}\n\n.tooltip .arrow::before {\n  position: absolute;\n  content: \"\";\n  border-color: transparent;\n  border-style: solid;\n}\n\n.bs-tooltip-top, .bs-tooltip-auto[x-placement^=\"top\"] {\n  padding: 0.4rem 0;\n}\n\n.bs-tooltip-top .arrow, .bs-tooltip-auto[x-placement^=\"top\"] .arrow {\n  bottom: 0;\n}\n\n.bs-tooltip-top .arrow::before, .bs-tooltip-auto[x-placement^=\"top\"] .arrow::before {\n  top: 0;\n  border-width: 0.4rem 0.4rem 0;\n  border-top-color: #000;\n}\n\n.bs-tooltip-right, .bs-tooltip-auto[x-placement^=\"right\"] {\n  padding: 0 0.4rem;\n}\n\n.bs-tooltip-right .arrow, .bs-tooltip-auto[x-placement^=\"right\"] .arrow {\n  left: 0;\n  width: 0.4rem;\n  height: 0.8rem;\n}\n\n.bs-tooltip-right .arrow::before, .bs-tooltip-auto[x-placement^=\"right\"] .arrow::before {\n  right: 0;\n  border-width: 0.4rem 0.4rem 0.4rem 0;\n  border-right-color: #000;\n}\n\n.bs-tooltip-bottom, .bs-tooltip-auto[x-placement^=\"bottom\"] {\n  padding: 0.4rem 0;\n}\n\n.bs-tooltip-bottom .arrow, .bs-tooltip-auto[x-placement^=\"bottom\"] .arrow {\n  top: 0;\n}\n\n.bs-tooltip-bottom .arrow::before, .bs-tooltip-auto[x-placement^=\"bottom\"] .arrow::before {\n  bottom: 0;\n  border-width: 0 0.4rem 0.4rem;\n  border-bottom-color: #000;\n}\n\n.bs-tooltip-left, .bs-tooltip-auto[x-placement^=\"left\"] {\n  padding: 0 0.4rem;\n}\n\n.bs-tooltip-left .arrow, .bs-tooltip-auto[x-placement^=\"left\"] .arrow {\n  right: 0;\n  width: 0.4rem;\n  height: 0.8rem;\n}\n\n.bs-tooltip-left .arrow::before, .bs-tooltip-auto[x-placement^=\"left\"] .arrow::before {\n  left: 0;\n  border-width: 0.4rem 0 0.4rem 0.4rem;\n  border-left-color: #000;\n}\n\n.tooltip-inner {\n  max-width: 200px;\n  padding: 0.25rem 0.5rem;\n  color: #fff;\n  text-align: center;\n  background-color: #000;\n  border-radius: 0.25rem;\n}\n\n.popover {\n  position: absolute;\n  top: 0;\n  left: 0;\n  z-index: 1060;\n  display: block;\n  max-width: 276px;\n  font-family: -apple-system, BlinkMacSystemFont, \"Segoe UI\", Roboto, \"Helvetica Neue\", Arial, \"Noto Sans\", sans-serif, \"Apple Color Emoji\", \"Segoe UI Emoji\", \"Segoe UI Symbol\", \"Noto Color Emoji\";\n  font-style: normal;\n  font-weight: 400;\n  line-height: 1.5;\n  text-align: left;\n  text-align: start;\n  text-decoration: none;\n  text-shadow: none;\n  text-transform: none;\n  letter-spacing: normal;\n  word-break: normal;\n  word-spacing: normal;\n  white-space: normal;\n  line-break: auto;\n  font-size: 0.875rem;\n  word-wrap: break-word;\n  background-color: #fff;\n  background-clip: padding-box;\n  border: 1px solid rgba(0, 0, 0, 0.2);\n  border-radius: 0.3rem;\n}\n\n.popover .arrow {\n  position: absolute;\n  display: block;\n  width: 1rem;\n  height: 0.5rem;\n  margin: 0 0.3rem;\n}\n\n.popover .arrow::before, .popover .arrow::after {\n  position: absolute;\n  display: block;\n  content: \"\";\n  border-color: transparent;\n  border-style: solid;\n}\n\n.bs-popover-top, .bs-popover-auto[x-placement^=\"top\"] {\n  margin-bottom: 0.5rem;\n}\n\n.bs-popover-top > .arrow, .bs-popover-auto[x-placement^=\"top\"] > .arrow {\n  bottom: calc((0.5rem + 1px) * -1);\n}\n\n.bs-popover-top > .arrow::before, .bs-popover-auto[x-placement^=\"top\"] > .arrow::before {\n  bottom: 0;\n  border-width: 0.5rem 0.5rem 0;\n  border-top-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-top > .arrow::after, .bs-popover-auto[x-placement^=\"top\"] > .arrow::after {\n  bottom: 1px;\n  border-width: 0.5rem 0.5rem 0;\n  border-top-color: #fff;\n}\n\n.bs-popover-right, .bs-popover-auto[x-placement^=\"right\"] {\n  margin-left: 0.5rem;\n}\n\n.bs-popover-right > .arrow, .bs-popover-auto[x-placement^=\"right\"] > .arrow {\n  left: calc((0.5rem + 1px) * -1);\n  width: 0.5rem;\n  height: 1rem;\n  margin: 0.3rem 0;\n}\n\n.bs-popover-right > .arrow::before, .bs-popover-auto[x-placement^=\"right\"] > .arrow::before {\n  left: 0;\n  border-width: 0.5rem 0.5rem 0.5rem 0;\n  border-right-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-right > .arrow::after, .bs-popover-auto[x-placement^=\"right\"] > .arrow::after {\n  left: 1px;\n  border-width: 0.5rem 0.5rem 0.5rem 0;\n  border-right-color: #fff;\n}\n\n.bs-popover-bottom, .bs-popover-auto[x-placement^=\"bottom\"] {\n  margin-top: 0.5rem;\n}\n\n.bs-popover-bottom > .arrow, .bs-popover-auto[x-placement^=\"bottom\"] > .arrow {\n  top: calc((0.5rem + 1px) * -1);\n}\n\n.bs-popover-bottom > .arrow::before, .bs-popover-auto[x-placement^=\"bottom\"] > .arrow::before {\n  top: 0;\n  border-width: 0 0.5rem 0.5rem 0.5rem;\n  border-bottom-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-bottom > .arrow::after, .bs-popover-auto[x-placement^=\"bottom\"] > .arrow::after {\n  top: 1px;\n  border-width: 0 0.5rem 0.5rem 0.5rem;\n  border-bottom-color: #fff;\n}\n\n.bs-popover-bottom .popover-header::before, .bs-popover-auto[x-placement^=\"bottom\"] .popover-header::before {\n  position: absolute;\n  top: 0;\n  left: 50%;\n  display: block;\n  width: 1rem;\n  margin-left: -0.5rem;\n  content: \"\";\n  border-bottom: 1px solid #f7f7f7;\n}\n\n.bs-popover-left, .bs-popover-auto[x-placement^=\"left\"] {\n  margin-right: 0.5rem;\n}\n\n.bs-popover-left > .arrow, .bs-popover-auto[x-placement^=\"left\"] > .arrow {\n  right: calc((0.5rem + 1px) * -1);\n  width: 0.5rem;\n  height: 1rem;\n  margin: 0.3rem 0;\n}\n\n.bs-popover-left > .arrow::before, .bs-popover-auto[x-placement^=\"left\"] > .arrow::before {\n  right: 0;\n  border-width: 0.5rem 0 0.5rem 0.5rem;\n  border-left-color: rgba(0, 0, 0, 0.25);\n}\n\n.bs-popover-left > .arrow::after, .bs-popover-auto[x-placement^=\"left\"] > .arrow::after {\n  right: 1px;\n  border-width: 0.5rem 0 0.5rem 0.5rem;\n  border-left-color: #fff;\n}\n\n.popover-header {\n  padding: 0.5rem 0.75rem;\n  margin-bottom: 0;\n  font-size: 1rem;\n  background-color: #f7f7f7;\n  border-bottom: 1px solid #ebebeb;\n  border-top-left-radius: calc(0.3rem - 1px);\n  border-top-right-radius: calc(0.3rem - 1px);\n}\n\n.popover-header:empty {\n  display: none;\n}\n\n.popover-body {\n  padding: 0.5rem 0.75rem;\n  color: #212529;\n}\n\n.carousel {\n  position: relative;\n}\n\n.carousel.pointer-event {\n  -ms-touch-action: pan-y;\n  touch-action: pan-y;\n}\n\n.carousel-inner {\n  position: relative;\n  width: 100%;\n  overflow: hidden;\n}\n\n.carousel-inner::after {\n  display: block;\n  clear: both;\n  content: \"\";\n}\n\n.carousel-item {\n  position: relative;\n  display: none;\n  float: left;\n  width: 100%;\n  margin-right: -100%;\n  -webkit-backface-visibility: hidden;\n  backface-visibility: hidden;\n  transition: -webkit-transform 0.6s ease-in-out;\n  transition: transform 0.6s ease-in-out;\n  transition: transform 0.6s ease-in-out, -webkit-transform 0.6s ease-in-out;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-item {\n    transition: none;\n  }\n}\n\n.carousel-item.active,\n.carousel-item-next,\n.carousel-item-prev {\n  display: block;\n}\n\n.carousel-item-next:not(.carousel-item-left),\n.active.carousel-item-right {\n  -webkit-transform: translateX(100%);\n  transform: translateX(100%);\n}\n\n.carousel-item-prev:not(.carousel-item-right),\n.active.carousel-item-left {\n  -webkit-transform: translateX(-100%);\n  transform: translateX(-100%);\n}\n\n.carousel-fade .carousel-item {\n  opacity: 0;\n  transition-property: opacity;\n  -webkit-transform: none;\n  transform: none;\n}\n\n.carousel-fade .carousel-item.active,\n.carousel-fade .carousel-item-next.carousel-item-left,\n.carousel-fade .carousel-item-prev.carousel-item-right {\n  z-index: 1;\n  opacity: 1;\n}\n\n.carousel-fade .active.carousel-item-left,\n.carousel-fade .active.carousel-item-right {\n  z-index: 0;\n  opacity: 0;\n  transition: 0s 0.6s opacity;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-fade .active.carousel-item-left,\n  .carousel-fade .active.carousel-item-right {\n    transition: none;\n  }\n}\n\n.carousel-control-prev,\n.carousel-control-next {\n  position: absolute;\n  top: 0;\n  bottom: 0;\n  z-index: 1;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-align: center;\n  align-items: center;\n  -ms-flex-pack: center;\n  justify-content: center;\n  width: 15%;\n  color: #fff;\n  text-align: center;\n  opacity: 0.5;\n  transition: opacity 0.15s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-control-prev,\n  .carousel-control-next {\n    transition: none;\n  }\n}\n\n.carousel-control-prev:hover, .carousel-control-prev:focus,\n.carousel-control-next:hover,\n.carousel-control-next:focus {\n  color: #fff;\n  text-decoration: none;\n  outline: 0;\n  opacity: 0.9;\n}\n\n.carousel-control-prev {\n  left: 0;\n}\n\n.carousel-control-next {\n  right: 0;\n}\n\n.carousel-control-prev-icon,\n.carousel-control-next-icon {\n  display: inline-block;\n  width: 20px;\n  height: 20px;\n  background: no-repeat 50% / 100% 100%;\n}\n\n.carousel-control-prev-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23fff' viewBox='0 0 8 8'%3e%3cpath d='M5.25 0l-4 4 4 4 1.5-1.5-2.5-2.5 2.5-2.5-1.5-1.5z'/%3e%3c/svg%3e\");\n}\n\n.carousel-control-next-icon {\n  background-image: url(\"data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23fff' viewBox='0 0 8 8'%3e%3cpath d='M2.75 0l-1.5 1.5 2.5 2.5-2.5 2.5 1.5 1.5 4-4-4-4z'/%3e%3c/svg%3e\");\n}\n\n.carousel-indicators {\n  position: absolute;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  z-index: 15;\n  display: -ms-flexbox;\n  display: flex;\n  -ms-flex-pack: center;\n  justify-content: center;\n  padding-left: 0;\n  margin-right: 15%;\n  margin-left: 15%;\n  list-style: none;\n}\n\n.carousel-indicators li {\n  box-sizing: content-box;\n  -ms-flex: 0 1 auto;\n  flex: 0 1 auto;\n  width: 30px;\n  height: 3px;\n  margin-right: 3px;\n  margin-left: 3px;\n  text-indent: -999px;\n  cursor: pointer;\n  background-color: #fff;\n  background-clip: padding-box;\n  border-top: 10px solid transparent;\n  border-bottom: 10px solid transparent;\n  opacity: .5;\n  transition: opacity 0.6s ease;\n}\n\n@media (prefers-reduced-motion: reduce) {\n  .carousel-indicators li {\n    transition: none;\n  }\n}\n\n.carousel-indicators .active {\n  opacity: 1;\n}\n\n.carousel-caption {\n  position: absolute;\n  right: 15%;\n  bottom: 20px;\n  left: 15%;\n  z-index: 10;\n  padding-top: 20px;\n  padding-bottom: 20px;\n  color: #fff;\n  text-align: center;\n}\n\n@-webkit-keyframes spinner-border {\n  to {\n    -webkit-transform: rotate(360deg);\n    transform: rotate(360deg);\n  }\n}\n\n@keyframes spinner-border {\n  to {\n    -webkit-transform: rotate(360deg);\n    transform: rotate(360deg);\n  }\n}\n\n.spinner-border {\n  display: inline-block;\n  width: 2rem;\n  height: 2rem;\n  vertical-align: text-bottom;\n  border: 0.25em solid currentColor;\n  border-right-color: transparent;\n  border-radius: 50%;\n  -webkit-animation: spinner-border .75s linear infinite;\n  animation: spinner-border .75s linear infinite;\n}\n\n.spinner-border-sm {\n  width: 1rem;\n  height: 1rem;\n  border-width: 0.2em;\n}\n\n@-webkit-keyframes spinner-grow {\n  0% {\n    -webkit-transform: scale(0);\n    transform: scale(0);\n  }\n  50% {\n    opacity: 1;\n  }\n}\n\n@keyframes spinner-grow {\n  0% {\n    -webkit-transform: scale(0);\n    transform: scale(0);\n  }\n  50% {\n    opacity: 1;\n  }\n}\n\n.spinner-grow {\n  display: inline-block;\n  width: 2rem;\n  height: 2rem;\n  vertical-align: text-bottom;\n  background-color: currentColor;\n  border-radius: 50%;\n  opacity: 0;\n  -webkit-animation: spinner-grow .75s linear infinite;\n  animation: spinner-grow .75s linear infinite;\n}\n\n.spinner-grow-sm {\n  width: 1rem;\n  height: 1rem;\n}\n\n.align-baseline {\n  vertical-align: baseline !important;\n}\n\n.align-top {\n  vertical-align: top !important;\n}\n\n.align-middle {\n  vertical-align: middle !important;\n}\n\n.align-bottom {\n  vertical-align: bottom !important;\n}\n\n.align-text-bottom {\n  vertical-align: text-bottom !important;\n}\n\n.align-text-top {\n  vertical-align: text-top !important;\n}\n\n.bg-primary {\n  background-color: #007bff !important;\n}\n\na.bg-primary:hover, a.bg-primary:focus,\nbutton.bg-primary:hover,\nbutton.bg-primary:focus {\n  background-color: #0062cc !important;\n}\n\n.bg-secondary {\n  background-color: #6c757d !important;\n}\n\na.bg-secondary:hover, a.bg-secondary:focus,\nbutton.bg-secondary:hover,\nbutton.bg-secondary:focus {\n  background-color: #545b62 !important;\n}\n\n.bg-success {\n  background-color: #28a745 !important;\n}\n\na.bg-success:hover, a.bg-success:focus,\nbutton.bg-success:hover,\nbutton.bg-success:focus {\n  background-color: #1e7e34 !important;\n}\n\n.bg-info {\n  background-color: #17a2b8 !important;\n}\n\na.bg-info:hover, a.bg-info:focus,\nbutton.bg-info:hover,\nbutton.bg-info:focus {\n  background-color: #117a8b !important;\n}\n\n.bg-warning {\n  background-color: #ffc107 !important;\n}\n\na.bg-warning:hover, a.bg-warning:focus,\nbutton.bg-warning:hover,\nbutton.bg-warning:focus {\n  background-color: #d39e00 !important;\n}\n\n.bg-danger {\n  background-color: #dc3545 !important;\n}\n\na.bg-danger:hover, a.bg-danger:focus,\nbutton.bg-danger:hover,\nbutton.bg-danger:focus {\n  background-color: #bd2130 !important;\n}\n\n.bg-light {\n  background-color: #f8f9fa !important;\n}\n\na.bg-light:hover, a.bg-light:focus,\nbutton.bg-light:hover,\nbutton.bg-light:focus {\n  background-color: #dae0e5 !important;\n}\n\n.bg-dark {\n  background-color: #343a40 !important;\n}\n\na.bg-dark:hover, a.bg-dark:focus,\nbutton.bg-dark:hover,\nbutton.bg-dark:focus {\n  background-color: #1d2124 !important;\n}\n\n.bg-white {\n  background-color: #fff !important;\n}\n\n.bg-transparent {\n  background-color: transparent !important;\n}\n\n.border {\n  border: 1px solid #dee2e6 !important;\n}\n\n.border-top {\n  border-top: 1px solid #dee2e6 !important;\n}\n\n.border-right {\n  border-right: 1px solid #dee2e6 !important;\n}\n\n.border-bottom {\n  border-bottom: 1px solid #dee2e6 !important;\n}\n\n.border-left {\n  border-left: 1px solid #dee2e6 !important;\n}\n\n.border-0 {\n  border: 0 !important;\n}\n\n.border-top-0 {\n  border-top: 0 !important;\n}\n\n.border-right-0 {\n  border-right: 0 !important;\n}\n\n.border-bottom-0 {\n  border-bottom: 0 !important;\n}\n\n.border-left-0 {\n  border-left: 0 !important;\n}\n\n.border-primary {\n  border-color: #007bff !important;\n}\n\n.border-secondary {\n  border-color: #6c757d !important;\n}\n\n.border-success {\n  border-color: #28a745 !important;\n}\n\n.border-info {\n  border-color: #17a2b8 !important;\n}\n\n.border-warning {\n  border-color: #ffc107 !important;\n}\n\n.border-danger {\n  border-color: #dc3545 !important;\n}\n\n.border-light {\n  border-color: #f8f9fa !important;\n}\n\n.border-dark {\n  border-color: #343a40 !important;\n}\n\n.border-white {\n  border-color: #fff !important;\n}\n\n.rounded-sm {\n  border-radius: 0.2rem !important;\n}\n\n.rounded {\n  border-radius: 0.25rem !important;\n}\n\n.rounded-top {\n  border-top-left-radius: 0.25rem !important;\n  border-top-right-radius: 0.25rem !important;\n}\n\n.rounded-right {\n  border-top-right-radius: 0.25rem !important;\n  border-bottom-right-radius: 0.25rem !important;\n}\n\n.rounded-bottom {\n  border-bottom-right-radius: 0.25rem !important;\n  border-bottom-left-radius: 0.25rem !important;\n}\n\n.rounded-left {\n  border-top-left-radius: 0.25rem !important;\n  border-bottom-left-radius: 0.25rem !important;\n}\n\n.rounded-lg {\n  border-radius: 0.3rem !important;\n}\n\n.rounded-circle {\n  border-radius: 50% !important;\n}\n\n.rounded-pill {\n  border-radius: 50rem !important;\n}\n\n.rounded-0 {\n  border-radius: 0 !important;\n}\n\n.clearfix::after {\n  display: block;\n  clear: both;\n  content: \"\";\n}\n\n.d-none {\n  display: none !important;\n}\n\n.d-inline {\n  display: inline !important;\n}\n\n.d-inline-block {\n  display: inline-block !important;\n}\n\n.d-block {\n  display: block !important;\n}\n\n.d-table {\n  display: table !important;\n}\n\n.d-table-row {\n  display: table-row !important;\n}\n\n.d-table-cell {\n  display: table-cell !important;\n}\n\n.d-flex {\n  display: -ms-flexbox !important;\n  display: flex !important;\n}\n\n.d-inline-flex {\n  display: -ms-inline-flexbox !important;\n  display: inline-flex !important;\n}\n\n@media (min-width: 576px) {\n  .d-sm-none {\n    display: none !important;\n  }\n  .d-sm-inline {\n    display: inline !important;\n  }\n  .d-sm-inline-block {\n    display: inline-block !important;\n  }\n  .d-sm-block {\n    display: block !important;\n  }\n  .d-sm-table {\n    display: table !important;\n  }\n  .d-sm-table-row {\n    display: table-row !important;\n  }\n  .d-sm-table-cell {\n    display: table-cell !important;\n  }\n  .d-sm-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-sm-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .d-md-none {\n    display: none !important;\n  }\n  .d-md-inline {\n    display: inline !important;\n  }\n  .d-md-inline-block {\n    display: inline-block !important;\n  }\n  .d-md-block {\n    display: block !important;\n  }\n  .d-md-table {\n    display: table !important;\n  }\n  .d-md-table-row {\n    display: table-row !important;\n  }\n  .d-md-table-cell {\n    display: table-cell !important;\n  }\n  .d-md-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-md-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .d-lg-none {\n    display: none !important;\n  }\n  .d-lg-inline {\n    display: inline !important;\n  }\n  .d-lg-inline-block {\n    display: inline-block !important;\n  }\n  .d-lg-block {\n    display: block !important;\n  }\n  .d-lg-table {\n    display: table !important;\n  }\n  .d-lg-table-row {\n    display: table-row !important;\n  }\n  .d-lg-table-cell {\n    display: table-cell !important;\n  }\n  .d-lg-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-lg-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .d-xl-none {\n    display: none !important;\n  }\n  .d-xl-inline {\n    display: inline !important;\n  }\n  .d-xl-inline-block {\n    display: inline-block !important;\n  }\n  .d-xl-block {\n    display: block !important;\n  }\n  .d-xl-table {\n    display: table !important;\n  }\n  .d-xl-table-row {\n    display: table-row !important;\n  }\n  .d-xl-table-cell {\n    display: table-cell !important;\n  }\n  .d-xl-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-xl-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n@media print {\n  .d-print-none {\n    display: none !important;\n  }\n  .d-print-inline {\n    display: inline !important;\n  }\n  .d-print-inline-block {\n    display: inline-block !important;\n  }\n  .d-print-block {\n    display: block !important;\n  }\n  .d-print-table {\n    display: table !important;\n  }\n  .d-print-table-row {\n    display: table-row !important;\n  }\n  .d-print-table-cell {\n    display: table-cell !important;\n  }\n  .d-print-flex {\n    display: -ms-flexbox !important;\n    display: flex !important;\n  }\n  .d-print-inline-flex {\n    display: -ms-inline-flexbox !important;\n    display: inline-flex !important;\n  }\n}\n\n.embed-responsive {\n  position: relative;\n  display: block;\n  width: 100%;\n  padding: 0;\n  overflow: hidden;\n}\n\n.embed-responsive::before {\n  display: block;\n  content: \"\";\n}\n\n.embed-responsive .embed-responsive-item,\n.embed-responsive iframe,\n.embed-responsive embed,\n.embed-responsive object,\n.embed-responsive video {\n  position: absolute;\n  top: 0;\n  bottom: 0;\n  left: 0;\n  width: 100%;\n  height: 100%;\n  border: 0;\n}\n\n.embed-responsive-21by9::before {\n  padding-top: 42.857143%;\n}\n\n.embed-responsive-16by9::before {\n  padding-top: 56.25%;\n}\n\n.embed-responsive-4by3::before {\n  padding-top: 75%;\n}\n\n.embed-responsive-1by1::before {\n  padding-top: 100%;\n}\n\n.flex-row {\n  -ms-flex-direction: row !important;\n  flex-direction: row !important;\n}\n\n.flex-column {\n  -ms-flex-direction: column !important;\n  flex-direction: column !important;\n}\n\n.flex-row-reverse {\n  -ms-flex-direction: row-reverse !important;\n  flex-direction: row-reverse !important;\n}\n\n.flex-column-reverse {\n  -ms-flex-direction: column-reverse !important;\n  flex-direction: column-reverse !important;\n}\n\n.flex-wrap {\n  -ms-flex-wrap: wrap !important;\n  flex-wrap: wrap !important;\n}\n\n.flex-nowrap {\n  -ms-flex-wrap: nowrap !important;\n  flex-wrap: nowrap !important;\n}\n\n.flex-wrap-reverse {\n  -ms-flex-wrap: wrap-reverse !important;\n  flex-wrap: wrap-reverse !important;\n}\n\n.flex-fill {\n  -ms-flex: 1 1 auto !important;\n  flex: 1 1 auto !important;\n}\n\n.flex-grow-0 {\n  -ms-flex-positive: 0 !important;\n  flex-grow: 0 !important;\n}\n\n.flex-grow-1 {\n  -ms-flex-positive: 1 !important;\n  flex-grow: 1 !important;\n}\n\n.flex-shrink-0 {\n  -ms-flex-negative: 0 !important;\n  flex-shrink: 0 !important;\n}\n\n.flex-shrink-1 {\n  -ms-flex-negative: 1 !important;\n  flex-shrink: 1 !important;\n}\n\n.justify-content-start {\n  -ms-flex-pack: start !important;\n  justify-content: flex-start !important;\n}\n\n.justify-content-end {\n  -ms-flex-pack: end !important;\n  justify-content: flex-end !important;\n}\n\n.justify-content-center {\n  -ms-flex-pack: center !important;\n  justify-content: center !important;\n}\n\n.justify-content-between {\n  -ms-flex-pack: justify !important;\n  justify-content: space-between !important;\n}\n\n.justify-content-around {\n  -ms-flex-pack: distribute !important;\n  justify-content: space-around !important;\n}\n\n.align-items-start {\n  -ms-flex-align: start !important;\n  align-items: flex-start !important;\n}\n\n.align-items-end {\n  -ms-flex-align: end !important;\n  align-items: flex-end !important;\n}\n\n.align-items-center {\n  -ms-flex-align: center !important;\n  align-items: center !important;\n}\n\n.align-items-baseline {\n  -ms-flex-align: baseline !important;\n  align-items: baseline !important;\n}\n\n.align-items-stretch {\n  -ms-flex-align: stretch !important;\n  align-items: stretch !important;\n}\n\n.align-content-start {\n  -ms-flex-line-pack: start !important;\n  align-content: flex-start !important;\n}\n\n.align-content-end {\n  -ms-flex-line-pack: end !important;\n  align-content: flex-end !important;\n}\n\n.align-content-center {\n  -ms-flex-line-pack: center !important;\n  align-content: center !important;\n}\n\n.align-content-between {\n  -ms-flex-line-pack: justify !important;\n  align-content: space-between !important;\n}\n\n.align-content-around {\n  -ms-flex-line-pack: distribute !important;\n  align-content: space-around !important;\n}\n\n.align-content-stretch {\n  -ms-flex-line-pack: stretch !important;\n  align-content: stretch !important;\n}\n\n.align-self-auto {\n  -ms-flex-item-align: auto !important;\n  align-self: auto !important;\n}\n\n.align-self-start {\n  -ms-flex-item-align: start !important;\n  align-self: flex-start !important;\n}\n\n.align-self-end {\n  -ms-flex-item-align: end !important;\n  align-self: flex-end !important;\n}\n\n.align-self-center {\n  -ms-flex-item-align: center !important;\n  align-self: center !important;\n}\n\n.align-self-baseline {\n  -ms-flex-item-align: baseline !important;\n  align-self: baseline !important;\n}\n\n.align-self-stretch {\n  -ms-flex-item-align: stretch !important;\n  align-self: stretch !important;\n}\n\n@media (min-width: 576px) {\n  .flex-sm-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-sm-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-sm-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-sm-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-sm-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-sm-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-sm-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-sm-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-sm-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-sm-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-sm-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-sm-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-sm-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-sm-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-sm-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-sm-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-sm-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-sm-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-sm-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-sm-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-sm-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-sm-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-sm-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-sm-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-sm-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-sm-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-sm-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-sm-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-sm-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-sm-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-sm-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-sm-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-sm-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-sm-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .flex-md-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-md-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-md-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-md-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-md-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-md-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-md-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-md-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-md-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-md-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-md-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-md-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-md-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-md-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-md-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-md-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-md-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-md-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-md-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-md-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-md-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-md-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-md-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-md-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-md-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-md-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-md-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-md-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-md-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-md-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-md-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-md-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-md-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-md-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .flex-lg-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-lg-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-lg-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-lg-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-lg-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-lg-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-lg-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-lg-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-lg-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-lg-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-lg-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-lg-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-lg-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-lg-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-lg-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-lg-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-lg-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-lg-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-lg-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-lg-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-lg-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-lg-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-lg-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-lg-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-lg-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-lg-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-lg-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-lg-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-lg-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-lg-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-lg-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-lg-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-lg-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-lg-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .flex-xl-row {\n    -ms-flex-direction: row !important;\n    flex-direction: row !important;\n  }\n  .flex-xl-column {\n    -ms-flex-direction: column !important;\n    flex-direction: column !important;\n  }\n  .flex-xl-row-reverse {\n    -ms-flex-direction: row-reverse !important;\n    flex-direction: row-reverse !important;\n  }\n  .flex-xl-column-reverse {\n    -ms-flex-direction: column-reverse !important;\n    flex-direction: column-reverse !important;\n  }\n  .flex-xl-wrap {\n    -ms-flex-wrap: wrap !important;\n    flex-wrap: wrap !important;\n  }\n  .flex-xl-nowrap {\n    -ms-flex-wrap: nowrap !important;\n    flex-wrap: nowrap !important;\n  }\n  .flex-xl-wrap-reverse {\n    -ms-flex-wrap: wrap-reverse !important;\n    flex-wrap: wrap-reverse !important;\n  }\n  .flex-xl-fill {\n    -ms-flex: 1 1 auto !important;\n    flex: 1 1 auto !important;\n  }\n  .flex-xl-grow-0 {\n    -ms-flex-positive: 0 !important;\n    flex-grow: 0 !important;\n  }\n  .flex-xl-grow-1 {\n    -ms-flex-positive: 1 !important;\n    flex-grow: 1 !important;\n  }\n  .flex-xl-shrink-0 {\n    -ms-flex-negative: 0 !important;\n    flex-shrink: 0 !important;\n  }\n  .flex-xl-shrink-1 {\n    -ms-flex-negative: 1 !important;\n    flex-shrink: 1 !important;\n  }\n  .justify-content-xl-start {\n    -ms-flex-pack: start !important;\n    justify-content: flex-start !important;\n  }\n  .justify-content-xl-end {\n    -ms-flex-pack: end !important;\n    justify-content: flex-end !important;\n  }\n  .justify-content-xl-center {\n    -ms-flex-pack: center !important;\n    justify-content: center !important;\n  }\n  .justify-content-xl-between {\n    -ms-flex-pack: justify !important;\n    justify-content: space-between !important;\n  }\n  .justify-content-xl-around {\n    -ms-flex-pack: distribute !important;\n    justify-content: space-around !important;\n  }\n  .align-items-xl-start {\n    -ms-flex-align: start !important;\n    align-items: flex-start !important;\n  }\n  .align-items-xl-end {\n    -ms-flex-align: end !important;\n    align-items: flex-end !important;\n  }\n  .align-items-xl-center {\n    -ms-flex-align: center !important;\n    align-items: center !important;\n  }\n  .align-items-xl-baseline {\n    -ms-flex-align: baseline !important;\n    align-items: baseline !important;\n  }\n  .align-items-xl-stretch {\n    -ms-flex-align: stretch !important;\n    align-items: stretch !important;\n  }\n  .align-content-xl-start {\n    -ms-flex-line-pack: start !important;\n    align-content: flex-start !important;\n  }\n  .align-content-xl-end {\n    -ms-flex-line-pack: end !important;\n    align-content: flex-end !important;\n  }\n  .align-content-xl-center {\n    -ms-flex-line-pack: center !important;\n    align-content: center !important;\n  }\n  .align-content-xl-between {\n    -ms-flex-line-pack: justify !important;\n    align-content: space-between !important;\n  }\n  .align-content-xl-around {\n    -ms-flex-line-pack: distribute !important;\n    align-content: space-around !important;\n  }\n  .align-content-xl-stretch {\n    -ms-flex-line-pack: stretch !important;\n    align-content: stretch !important;\n  }\n  .align-self-xl-auto {\n    -ms-flex-item-align: auto !important;\n    align-self: auto !important;\n  }\n  .align-self-xl-start {\n    -ms-flex-item-align: start !important;\n    align-self: flex-start !important;\n  }\n  .align-self-xl-end {\n    -ms-flex-item-align: end !important;\n    align-self: flex-end !important;\n  }\n  .align-self-xl-center {\n    -ms-flex-item-align: center !important;\n    align-self: center !important;\n  }\n  .align-self-xl-baseline {\n    -ms-flex-item-align: baseline !important;\n    align-self: baseline !important;\n  }\n  .align-self-xl-stretch {\n    -ms-flex-item-align: stretch !important;\n    align-self: stretch !important;\n  }\n}\n\n.float-left {\n  float: left !important;\n}\n\n.float-right {\n  float: right !important;\n}\n\n.float-none {\n  float: none !important;\n}\n\n@media (min-width: 576px) {\n  .float-sm-left {\n    float: left !important;\n  }\n  .float-sm-right {\n    float: right !important;\n  }\n  .float-sm-none {\n    float: none !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .float-md-left {\n    float: left !important;\n  }\n  .float-md-right {\n    float: right !important;\n  }\n  .float-md-none {\n    float: none !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .float-lg-left {\n    float: left !important;\n  }\n  .float-lg-right {\n    float: right !important;\n  }\n  .float-lg-none {\n    float: none !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .float-xl-left {\n    float: left !important;\n  }\n  .float-xl-right {\n    float: right !important;\n  }\n  .float-xl-none {\n    float: none !important;\n  }\n}\n\n.overflow-auto {\n  overflow: auto !important;\n}\n\n.overflow-hidden {\n  overflow: hidden !important;\n}\n\n.position-static {\n  position: static !important;\n}\n\n.position-relative {\n  position: relative !important;\n}\n\n.position-absolute {\n  position: absolute !important;\n}\n\n.position-fixed {\n  position: fixed !important;\n}\n\n.position-sticky {\n  position: -webkit-sticky !important;\n  position: sticky !important;\n}\n\n.fixed-top {\n  position: fixed;\n  top: 0;\n  right: 0;\n  left: 0;\n  z-index: 1030;\n}\n\n.fixed-bottom {\n  position: fixed;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  z-index: 1030;\n}\n\n@supports ((position: -webkit-sticky) or (position: sticky)) {\n  .sticky-top {\n    position: -webkit-sticky;\n    position: sticky;\n    top: 0;\n    z-index: 1020;\n  }\n}\n\n.sr-only {\n  position: absolute;\n  width: 1px;\n  height: 1px;\n  padding: 0;\n  overflow: hidden;\n  clip: rect(0, 0, 0, 0);\n  white-space: nowrap;\n  border: 0;\n}\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  position: static;\n  width: auto;\n  height: auto;\n  overflow: visible;\n  clip: auto;\n  white-space: normal;\n}\n\n.shadow-sm {\n  box-shadow: 0 0.125rem 0.25rem rgba(0, 0, 0, 0.075) !important;\n}\n\n.shadow {\n  box-shadow: 0 0.5rem 1rem rgba(0, 0, 0, 0.15) !important;\n}\n\n.shadow-lg {\n  box-shadow: 0 1rem 3rem rgba(0, 0, 0, 0.175) !important;\n}\n\n.shadow-none {\n  box-shadow: none !important;\n}\n\n.w-25 {\n  width: 25% !important;\n}\n\n.w-50 {\n  width: 50% !important;\n}\n\n.w-75 {\n  width: 75% !important;\n}\n\n.w-100 {\n  width: 100% !important;\n}\n\n.w-auto {\n  width: auto !important;\n}\n\n.h-25 {\n  height: 25% !important;\n}\n\n.h-50 {\n  height: 50% !important;\n}\n\n.h-75 {\n  height: 75% !important;\n}\n\n.h-100 {\n  height: 100% !important;\n}\n\n.h-auto {\n  height: auto !important;\n}\n\n.mw-100 {\n  max-width: 100% !important;\n}\n\n.mh-100 {\n  max-height: 100% !important;\n}\n\n.min-vw-100 {\n  min-width: 100vw !important;\n}\n\n.min-vh-100 {\n  min-height: 100vh !important;\n}\n\n.vw-100 {\n  width: 100vw !important;\n}\n\n.vh-100 {\n  height: 100vh !important;\n}\n\n.stretched-link::after {\n  position: absolute;\n  top: 0;\n  right: 0;\n  bottom: 0;\n  left: 0;\n  z-index: 1;\n  pointer-events: auto;\n  content: \"\";\n  background-color: rgba(0, 0, 0, 0);\n}\n\n.m-0 {\n  margin: 0 !important;\n}\n\n.mt-0,\n.my-0 {\n  margin-top: 0 !important;\n}\n\n.mr-0,\n.mx-0 {\n  margin-right: 0 !important;\n}\n\n.mb-0,\n.my-0 {\n  margin-bottom: 0 !important;\n}\n\n.ml-0,\n.mx-0 {\n  margin-left: 0 !important;\n}\n\n.m-1 {\n  margin: 0.25rem !important;\n}\n\n.mt-1,\n.my-1 {\n  margin-top: 0.25rem !important;\n}\n\n.mr-1,\n.mx-1 {\n  margin-right: 0.25rem !important;\n}\n\n.mb-1,\n.my-1 {\n  margin-bottom: 0.25rem !important;\n}\n\n.ml-1,\n.mx-1 {\n  margin-left: 0.25rem !important;\n}\n\n.m-2 {\n  margin: 0.5rem !important;\n}\n\n.mt-2,\n.my-2 {\n  margin-top: 0.5rem !important;\n}\n\n.mr-2,\n.mx-2 {\n  margin-right: 0.5rem !important;\n}\n\n.mb-2,\n.my-2 {\n  margin-bottom: 0.5rem !important;\n}\n\n.ml-2,\n.mx-2 {\n  margin-left: 0.5rem !important;\n}\n\n.m-3 {\n  margin: 1rem !important;\n}\n\n.mt-3,\n.my-3 {\n  margin-top: 1rem !important;\n}\n\n.mr-3,\n.mx-3 {\n  margin-right: 1rem !important;\n}\n\n.mb-3,\n.my-3 {\n  margin-bottom: 1rem !important;\n}\n\n.ml-3,\n.mx-3 {\n  margin-left: 1rem !important;\n}\n\n.m-4 {\n  margin: 1.5rem !important;\n}\n\n.mt-4,\n.my-4 {\n  margin-top: 1.5rem !important;\n}\n\n.mr-4,\n.mx-4 {\n  margin-right: 1.5rem !important;\n}\n\n.mb-4,\n.my-4 {\n  margin-bottom: 1.5rem !important;\n}\n\n.ml-4,\n.mx-4 {\n  margin-left: 1.5rem !important;\n}\n\n.m-5 {\n  margin: 3rem !important;\n}\n\n.mt-5,\n.my-5 {\n  margin-top: 3rem !important;\n}\n\n.mr-5,\n.mx-5 {\n  margin-right: 3rem !important;\n}\n\n.mb-5,\n.my-5 {\n  margin-bottom: 3rem !important;\n}\n\n.ml-5,\n.mx-5 {\n  margin-left: 3rem !important;\n}\n\n.p-0 {\n  padding: 0 !important;\n}\n\n.pt-0,\n.py-0 {\n  padding-top: 0 !important;\n}\n\n.pr-0,\n.px-0 {\n  padding-right: 0 !important;\n}\n\n.pb-0,\n.py-0 {\n  padding-bottom: 0 !important;\n}\n\n.pl-0,\n.px-0 {\n  padding-left: 0 !important;\n}\n\n.p-1 {\n  padding: 0.25rem !important;\n}\n\n.pt-1,\n.py-1 {\n  padding-top: 0.25rem !important;\n}\n\n.pr-1,\n.px-1 {\n  padding-right: 0.25rem !important;\n}\n\n.pb-1,\n.py-1 {\n  padding-bottom: 0.25rem !important;\n}\n\n.pl-1,\n.px-1 {\n  padding-left: 0.25rem !important;\n}\n\n.p-2 {\n  padding: 0.5rem !important;\n}\n\n.pt-2,\n.py-2 {\n  padding-top: 0.5rem !important;\n}\n\n.pr-2,\n.px-2 {\n  padding-right: 0.5rem !important;\n}\n\n.pb-2,\n.py-2 {\n  padding-bottom: 0.5rem !important;\n}\n\n.pl-2,\n.px-2 {\n  padding-left: 0.5rem !important;\n}\n\n.p-3 {\n  padding: 1rem !important;\n}\n\n.pt-3,\n.py-3 {\n  padding-top: 1rem !important;\n}\n\n.pr-3,\n.px-3 {\n  padding-right: 1rem !important;\n}\n\n.pb-3,\n.py-3 {\n  padding-bottom: 1rem !important;\n}\n\n.pl-3,\n.px-3 {\n  padding-left: 1rem !important;\n}\n\n.p-4 {\n  padding: 1.5rem !important;\n}\n\n.pt-4,\n.py-4 {\n  padding-top: 1.5rem !important;\n}\n\n.pr-4,\n.px-4 {\n  padding-right: 1.5rem !important;\n}\n\n.pb-4,\n.py-4 {\n  padding-bottom: 1.5rem !important;\n}\n\n.pl-4,\n.px-4 {\n  padding-left: 1.5rem !important;\n}\n\n.p-5 {\n  padding: 3rem !important;\n}\n\n.pt-5,\n.py-5 {\n  padding-top: 3rem !important;\n}\n\n.pr-5,\n.px-5 {\n  padding-right: 3rem !important;\n}\n\n.pb-5,\n.py-5 {\n  padding-bottom: 3rem !important;\n}\n\n.pl-5,\n.px-5 {\n  padding-left: 3rem !important;\n}\n\n.m-n1 {\n  margin: -0.25rem !important;\n}\n\n.mt-n1,\n.my-n1 {\n  margin-top: -0.25rem !important;\n}\n\n.mr-n1,\n.mx-n1 {\n  margin-right: -0.25rem !important;\n}\n\n.mb-n1,\n.my-n1 {\n  margin-bottom: -0.25rem !important;\n}\n\n.ml-n1,\n.mx-n1 {\n  margin-left: -0.25rem !important;\n}\n\n.m-n2 {\n  margin: -0.5rem !important;\n}\n\n.mt-n2,\n.my-n2 {\n  margin-top: -0.5rem !important;\n}\n\n.mr-n2,\n.mx-n2 {\n  margin-right: -0.5rem !important;\n}\n\n.mb-n2,\n.my-n2 {\n  margin-bottom: -0.5rem !important;\n}\n\n.ml-n2,\n.mx-n2 {\n  margin-left: -0.5rem !important;\n}\n\n.m-n3 {\n  margin: -1rem !important;\n}\n\n.mt-n3,\n.my-n3 {\n  margin-top: -1rem !important;\n}\n\n.mr-n3,\n.mx-n3 {\n  margin-right: -1rem !important;\n}\n\n.mb-n3,\n.my-n3 {\n  margin-bottom: -1rem !important;\n}\n\n.ml-n3,\n.mx-n3 {\n  margin-left: -1rem !important;\n}\n\n.m-n4 {\n  margin: -1.5rem !important;\n}\n\n.mt-n4,\n.my-n4 {\n  margin-top: -1.5rem !important;\n}\n\n.mr-n4,\n.mx-n4 {\n  margin-right: -1.5rem !important;\n}\n\n.mb-n4,\n.my-n4 {\n  margin-bottom: -1.5rem !important;\n}\n\n.ml-n4,\n.mx-n4 {\n  margin-left: -1.5rem !important;\n}\n\n.m-n5 {\n  margin: -3rem !important;\n}\n\n.mt-n5,\n.my-n5 {\n  margin-top: -3rem !important;\n}\n\n.mr-n5,\n.mx-n5 {\n  margin-right: -3rem !important;\n}\n\n.mb-n5,\n.my-n5 {\n  margin-bottom: -3rem !important;\n}\n\n.ml-n5,\n.mx-n5 {\n  margin-left: -3rem !important;\n}\n\n.m-auto {\n  margin: auto !important;\n}\n\n.mt-auto,\n.my-auto {\n  margin-top: auto !important;\n}\n\n.mr-auto,\n.mx-auto {\n  margin-right: auto !important;\n}\n\n.mb-auto,\n.my-auto {\n  margin-bottom: auto !important;\n}\n\n.ml-auto,\n.mx-auto {\n  margin-left: auto !important;\n}\n\n@media (min-width: 576px) {\n  .m-sm-0 {\n    margin: 0 !important;\n  }\n  .mt-sm-0,\n  .my-sm-0 {\n    margin-top: 0 !important;\n  }\n  .mr-sm-0,\n  .mx-sm-0 {\n    margin-right: 0 !important;\n  }\n  .mb-sm-0,\n  .my-sm-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-sm-0,\n  .mx-sm-0 {\n    margin-left: 0 !important;\n  }\n  .m-sm-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-sm-1,\n  .my-sm-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-sm-1,\n  .mx-sm-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-sm-1,\n  .my-sm-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-sm-1,\n  .mx-sm-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-sm-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-sm-2,\n  .my-sm-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-sm-2,\n  .mx-sm-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-sm-2,\n  .my-sm-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-sm-2,\n  .mx-sm-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-sm-3 {\n    margin: 1rem !important;\n  }\n  .mt-sm-3,\n  .my-sm-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-sm-3,\n  .mx-sm-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-sm-3,\n  .my-sm-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-sm-3,\n  .mx-sm-3 {\n    margin-left: 1rem !important;\n  }\n  .m-sm-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-sm-4,\n  .my-sm-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-sm-4,\n  .mx-sm-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-sm-4,\n  .my-sm-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-sm-4,\n  .mx-sm-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-sm-5 {\n    margin: 3rem !important;\n  }\n  .mt-sm-5,\n  .my-sm-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-sm-5,\n  .mx-sm-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-sm-5,\n  .my-sm-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-sm-5,\n  .mx-sm-5 {\n    margin-left: 3rem !important;\n  }\n  .p-sm-0 {\n    padding: 0 !important;\n  }\n  .pt-sm-0,\n  .py-sm-0 {\n    padding-top: 0 !important;\n  }\n  .pr-sm-0,\n  .px-sm-0 {\n    padding-right: 0 !important;\n  }\n  .pb-sm-0,\n  .py-sm-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-sm-0,\n  .px-sm-0 {\n    padding-left: 0 !important;\n  }\n  .p-sm-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-sm-1,\n  .py-sm-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-sm-1,\n  .px-sm-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-sm-1,\n  .py-sm-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-sm-1,\n  .px-sm-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-sm-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-sm-2,\n  .py-sm-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-sm-2,\n  .px-sm-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-sm-2,\n  .py-sm-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-sm-2,\n  .px-sm-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-sm-3 {\n    padding: 1rem !important;\n  }\n  .pt-sm-3,\n  .py-sm-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-sm-3,\n  .px-sm-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-sm-3,\n  .py-sm-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-sm-3,\n  .px-sm-3 {\n    padding-left: 1rem !important;\n  }\n  .p-sm-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-sm-4,\n  .py-sm-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-sm-4,\n  .px-sm-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-sm-4,\n  .py-sm-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-sm-4,\n  .px-sm-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-sm-5 {\n    padding: 3rem !important;\n  }\n  .pt-sm-5,\n  .py-sm-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-sm-5,\n  .px-sm-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-sm-5,\n  .py-sm-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-sm-5,\n  .px-sm-5 {\n    padding-left: 3rem !important;\n  }\n  .m-sm-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-sm-n1,\n  .my-sm-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-sm-n1,\n  .mx-sm-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-sm-n1,\n  .my-sm-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-sm-n1,\n  .mx-sm-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-sm-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-sm-n2,\n  .my-sm-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-sm-n2,\n  .mx-sm-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-sm-n2,\n  .my-sm-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-sm-n2,\n  .mx-sm-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-sm-n3 {\n    margin: -1rem !important;\n  }\n  .mt-sm-n3,\n  .my-sm-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-sm-n3,\n  .mx-sm-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-sm-n3,\n  .my-sm-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-sm-n3,\n  .mx-sm-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-sm-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-sm-n4,\n  .my-sm-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-sm-n4,\n  .mx-sm-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-sm-n4,\n  .my-sm-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-sm-n4,\n  .mx-sm-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-sm-n5 {\n    margin: -3rem !important;\n  }\n  .mt-sm-n5,\n  .my-sm-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-sm-n5,\n  .mx-sm-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-sm-n5,\n  .my-sm-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-sm-n5,\n  .mx-sm-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-sm-auto {\n    margin: auto !important;\n  }\n  .mt-sm-auto,\n  .my-sm-auto {\n    margin-top: auto !important;\n  }\n  .mr-sm-auto,\n  .mx-sm-auto {\n    margin-right: auto !important;\n  }\n  .mb-sm-auto,\n  .my-sm-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-sm-auto,\n  .mx-sm-auto {\n    margin-left: auto !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .m-md-0 {\n    margin: 0 !important;\n  }\n  .mt-md-0,\n  .my-md-0 {\n    margin-top: 0 !important;\n  }\n  .mr-md-0,\n  .mx-md-0 {\n    margin-right: 0 !important;\n  }\n  .mb-md-0,\n  .my-md-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-md-0,\n  .mx-md-0 {\n    margin-left: 0 !important;\n  }\n  .m-md-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-md-1,\n  .my-md-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-md-1,\n  .mx-md-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-md-1,\n  .my-md-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-md-1,\n  .mx-md-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-md-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-md-2,\n  .my-md-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-md-2,\n  .mx-md-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-md-2,\n  .my-md-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-md-2,\n  .mx-md-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-md-3 {\n    margin: 1rem !important;\n  }\n  .mt-md-3,\n  .my-md-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-md-3,\n  .mx-md-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-md-3,\n  .my-md-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-md-3,\n  .mx-md-3 {\n    margin-left: 1rem !important;\n  }\n  .m-md-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-md-4,\n  .my-md-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-md-4,\n  .mx-md-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-md-4,\n  .my-md-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-md-4,\n  .mx-md-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-md-5 {\n    margin: 3rem !important;\n  }\n  .mt-md-5,\n  .my-md-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-md-5,\n  .mx-md-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-md-5,\n  .my-md-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-md-5,\n  .mx-md-5 {\n    margin-left: 3rem !important;\n  }\n  .p-md-0 {\n    padding: 0 !important;\n  }\n  .pt-md-0,\n  .py-md-0 {\n    padding-top: 0 !important;\n  }\n  .pr-md-0,\n  .px-md-0 {\n    padding-right: 0 !important;\n  }\n  .pb-md-0,\n  .py-md-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-md-0,\n  .px-md-0 {\n    padding-left: 0 !important;\n  }\n  .p-md-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-md-1,\n  .py-md-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-md-1,\n  .px-md-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-md-1,\n  .py-md-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-md-1,\n  .px-md-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-md-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-md-2,\n  .py-md-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-md-2,\n  .px-md-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-md-2,\n  .py-md-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-md-2,\n  .px-md-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-md-3 {\n    padding: 1rem !important;\n  }\n  .pt-md-3,\n  .py-md-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-md-3,\n  .px-md-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-md-3,\n  .py-md-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-md-3,\n  .px-md-3 {\n    padding-left: 1rem !important;\n  }\n  .p-md-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-md-4,\n  .py-md-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-md-4,\n  .px-md-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-md-4,\n  .py-md-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-md-4,\n  .px-md-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-md-5 {\n    padding: 3rem !important;\n  }\n  .pt-md-5,\n  .py-md-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-md-5,\n  .px-md-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-md-5,\n  .py-md-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-md-5,\n  .px-md-5 {\n    padding-left: 3rem !important;\n  }\n  .m-md-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-md-n1,\n  .my-md-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-md-n1,\n  .mx-md-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-md-n1,\n  .my-md-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-md-n1,\n  .mx-md-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-md-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-md-n2,\n  .my-md-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-md-n2,\n  .mx-md-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-md-n2,\n  .my-md-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-md-n2,\n  .mx-md-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-md-n3 {\n    margin: -1rem !important;\n  }\n  .mt-md-n3,\n  .my-md-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-md-n3,\n  .mx-md-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-md-n3,\n  .my-md-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-md-n3,\n  .mx-md-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-md-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-md-n4,\n  .my-md-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-md-n4,\n  .mx-md-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-md-n4,\n  .my-md-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-md-n4,\n  .mx-md-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-md-n5 {\n    margin: -3rem !important;\n  }\n  .mt-md-n5,\n  .my-md-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-md-n5,\n  .mx-md-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-md-n5,\n  .my-md-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-md-n5,\n  .mx-md-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-md-auto {\n    margin: auto !important;\n  }\n  .mt-md-auto,\n  .my-md-auto {\n    margin-top: auto !important;\n  }\n  .mr-md-auto,\n  .mx-md-auto {\n    margin-right: auto !important;\n  }\n  .mb-md-auto,\n  .my-md-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-md-auto,\n  .mx-md-auto {\n    margin-left: auto !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .m-lg-0 {\n    margin: 0 !important;\n  }\n  .mt-lg-0,\n  .my-lg-0 {\n    margin-top: 0 !important;\n  }\n  .mr-lg-0,\n  .mx-lg-0 {\n    margin-right: 0 !important;\n  }\n  .mb-lg-0,\n  .my-lg-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-lg-0,\n  .mx-lg-0 {\n    margin-left: 0 !important;\n  }\n  .m-lg-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-lg-1,\n  .my-lg-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-lg-1,\n  .mx-lg-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-lg-1,\n  .my-lg-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-lg-1,\n  .mx-lg-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-lg-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-lg-2,\n  .my-lg-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-lg-2,\n  .mx-lg-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-lg-2,\n  .my-lg-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-lg-2,\n  .mx-lg-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-lg-3 {\n    margin: 1rem !important;\n  }\n  .mt-lg-3,\n  .my-lg-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-lg-3,\n  .mx-lg-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-lg-3,\n  .my-lg-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-lg-3,\n  .mx-lg-3 {\n    margin-left: 1rem !important;\n  }\n  .m-lg-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-lg-4,\n  .my-lg-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-lg-4,\n  .mx-lg-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-lg-4,\n  .my-lg-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-lg-4,\n  .mx-lg-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-lg-5 {\n    margin: 3rem !important;\n  }\n  .mt-lg-5,\n  .my-lg-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-lg-5,\n  .mx-lg-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-lg-5,\n  .my-lg-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-lg-5,\n  .mx-lg-5 {\n    margin-left: 3rem !important;\n  }\n  .p-lg-0 {\n    padding: 0 !important;\n  }\n  .pt-lg-0,\n  .py-lg-0 {\n    padding-top: 0 !important;\n  }\n  .pr-lg-0,\n  .px-lg-0 {\n    padding-right: 0 !important;\n  }\n  .pb-lg-0,\n  .py-lg-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-lg-0,\n  .px-lg-0 {\n    padding-left: 0 !important;\n  }\n  .p-lg-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-lg-1,\n  .py-lg-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-lg-1,\n  .px-lg-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-lg-1,\n  .py-lg-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-lg-1,\n  .px-lg-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-lg-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-lg-2,\n  .py-lg-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-lg-2,\n  .px-lg-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-lg-2,\n  .py-lg-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-lg-2,\n  .px-lg-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-lg-3 {\n    padding: 1rem !important;\n  }\n  .pt-lg-3,\n  .py-lg-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-lg-3,\n  .px-lg-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-lg-3,\n  .py-lg-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-lg-3,\n  .px-lg-3 {\n    padding-left: 1rem !important;\n  }\n  .p-lg-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-lg-4,\n  .py-lg-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-lg-4,\n  .px-lg-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-lg-4,\n  .py-lg-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-lg-4,\n  .px-lg-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-lg-5 {\n    padding: 3rem !important;\n  }\n  .pt-lg-5,\n  .py-lg-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-lg-5,\n  .px-lg-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-lg-5,\n  .py-lg-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-lg-5,\n  .px-lg-5 {\n    padding-left: 3rem !important;\n  }\n  .m-lg-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-lg-n1,\n  .my-lg-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-lg-n1,\n  .mx-lg-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-lg-n1,\n  .my-lg-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-lg-n1,\n  .mx-lg-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-lg-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-lg-n2,\n  .my-lg-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-lg-n2,\n  .mx-lg-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-lg-n2,\n  .my-lg-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-lg-n2,\n  .mx-lg-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-lg-n3 {\n    margin: -1rem !important;\n  }\n  .mt-lg-n3,\n  .my-lg-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-lg-n3,\n  .mx-lg-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-lg-n3,\n  .my-lg-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-lg-n3,\n  .mx-lg-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-lg-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-lg-n4,\n  .my-lg-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-lg-n4,\n  .mx-lg-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-lg-n4,\n  .my-lg-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-lg-n4,\n  .mx-lg-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-lg-n5 {\n    margin: -3rem !important;\n  }\n  .mt-lg-n5,\n  .my-lg-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-lg-n5,\n  .mx-lg-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-lg-n5,\n  .my-lg-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-lg-n5,\n  .mx-lg-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-lg-auto {\n    margin: auto !important;\n  }\n  .mt-lg-auto,\n  .my-lg-auto {\n    margin-top: auto !important;\n  }\n  .mr-lg-auto,\n  .mx-lg-auto {\n    margin-right: auto !important;\n  }\n  .mb-lg-auto,\n  .my-lg-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-lg-auto,\n  .mx-lg-auto {\n    margin-left: auto !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .m-xl-0 {\n    margin: 0 !important;\n  }\n  .mt-xl-0,\n  .my-xl-0 {\n    margin-top: 0 !important;\n  }\n  .mr-xl-0,\n  .mx-xl-0 {\n    margin-right: 0 !important;\n  }\n  .mb-xl-0,\n  .my-xl-0 {\n    margin-bottom: 0 !important;\n  }\n  .ml-xl-0,\n  .mx-xl-0 {\n    margin-left: 0 !important;\n  }\n  .m-xl-1 {\n    margin: 0.25rem !important;\n  }\n  .mt-xl-1,\n  .my-xl-1 {\n    margin-top: 0.25rem !important;\n  }\n  .mr-xl-1,\n  .mx-xl-1 {\n    margin-right: 0.25rem !important;\n  }\n  .mb-xl-1,\n  .my-xl-1 {\n    margin-bottom: 0.25rem !important;\n  }\n  .ml-xl-1,\n  .mx-xl-1 {\n    margin-left: 0.25rem !important;\n  }\n  .m-xl-2 {\n    margin: 0.5rem !important;\n  }\n  .mt-xl-2,\n  .my-xl-2 {\n    margin-top: 0.5rem !important;\n  }\n  .mr-xl-2,\n  .mx-xl-2 {\n    margin-right: 0.5rem !important;\n  }\n  .mb-xl-2,\n  .my-xl-2 {\n    margin-bottom: 0.5rem !important;\n  }\n  .ml-xl-2,\n  .mx-xl-2 {\n    margin-left: 0.5rem !important;\n  }\n  .m-xl-3 {\n    margin: 1rem !important;\n  }\n  .mt-xl-3,\n  .my-xl-3 {\n    margin-top: 1rem !important;\n  }\n  .mr-xl-3,\n  .mx-xl-3 {\n    margin-right: 1rem !important;\n  }\n  .mb-xl-3,\n  .my-xl-3 {\n    margin-bottom: 1rem !important;\n  }\n  .ml-xl-3,\n  .mx-xl-3 {\n    margin-left: 1rem !important;\n  }\n  .m-xl-4 {\n    margin: 1.5rem !important;\n  }\n  .mt-xl-4,\n  .my-xl-4 {\n    margin-top: 1.5rem !important;\n  }\n  .mr-xl-4,\n  .mx-xl-4 {\n    margin-right: 1.5rem !important;\n  }\n  .mb-xl-4,\n  .my-xl-4 {\n    margin-bottom: 1.5rem !important;\n  }\n  .ml-xl-4,\n  .mx-xl-4 {\n    margin-left: 1.5rem !important;\n  }\n  .m-xl-5 {\n    margin: 3rem !important;\n  }\n  .mt-xl-5,\n  .my-xl-5 {\n    margin-top: 3rem !important;\n  }\n  .mr-xl-5,\n  .mx-xl-5 {\n    margin-right: 3rem !important;\n  }\n  .mb-xl-5,\n  .my-xl-5 {\n    margin-bottom: 3rem !important;\n  }\n  .ml-xl-5,\n  .mx-xl-5 {\n    margin-left: 3rem !important;\n  }\n  .p-xl-0 {\n    padding: 0 !important;\n  }\n  .pt-xl-0,\n  .py-xl-0 {\n    padding-top: 0 !important;\n  }\n  .pr-xl-0,\n  .px-xl-0 {\n    padding-right: 0 !important;\n  }\n  .pb-xl-0,\n  .py-xl-0 {\n    padding-bottom: 0 !important;\n  }\n  .pl-xl-0,\n  .px-xl-0 {\n    padding-left: 0 !important;\n  }\n  .p-xl-1 {\n    padding: 0.25rem !important;\n  }\n  .pt-xl-1,\n  .py-xl-1 {\n    padding-top: 0.25rem !important;\n  }\n  .pr-xl-1,\n  .px-xl-1 {\n    padding-right: 0.25rem !important;\n  }\n  .pb-xl-1,\n  .py-xl-1 {\n    padding-bottom: 0.25rem !important;\n  }\n  .pl-xl-1,\n  .px-xl-1 {\n    padding-left: 0.25rem !important;\n  }\n  .p-xl-2 {\n    padding: 0.5rem !important;\n  }\n  .pt-xl-2,\n  .py-xl-2 {\n    padding-top: 0.5rem !important;\n  }\n  .pr-xl-2,\n  .px-xl-2 {\n    padding-right: 0.5rem !important;\n  }\n  .pb-xl-2,\n  .py-xl-2 {\n    padding-bottom: 0.5rem !important;\n  }\n  .pl-xl-2,\n  .px-xl-2 {\n    padding-left: 0.5rem !important;\n  }\n  .p-xl-3 {\n    padding: 1rem !important;\n  }\n  .pt-xl-3,\n  .py-xl-3 {\n    padding-top: 1rem !important;\n  }\n  .pr-xl-3,\n  .px-xl-3 {\n    padding-right: 1rem !important;\n  }\n  .pb-xl-3,\n  .py-xl-3 {\n    padding-bottom: 1rem !important;\n  }\n  .pl-xl-3,\n  .px-xl-3 {\n    padding-left: 1rem !important;\n  }\n  .p-xl-4 {\n    padding: 1.5rem !important;\n  }\n  .pt-xl-4,\n  .py-xl-4 {\n    padding-top: 1.5rem !important;\n  }\n  .pr-xl-4,\n  .px-xl-4 {\n    padding-right: 1.5rem !important;\n  }\n  .pb-xl-4,\n  .py-xl-4 {\n    padding-bottom: 1.5rem !important;\n  }\n  .pl-xl-4,\n  .px-xl-4 {\n    padding-left: 1.5rem !important;\n  }\n  .p-xl-5 {\n    padding: 3rem !important;\n  }\n  .pt-xl-5,\n  .py-xl-5 {\n    padding-top: 3rem !important;\n  }\n  .pr-xl-5,\n  .px-xl-5 {\n    padding-right: 3rem !important;\n  }\n  .pb-xl-5,\n  .py-xl-5 {\n    padding-bottom: 3rem !important;\n  }\n  .pl-xl-5,\n  .px-xl-5 {\n    padding-left: 3rem !important;\n  }\n  .m-xl-n1 {\n    margin: -0.25rem !important;\n  }\n  .mt-xl-n1,\n  .my-xl-n1 {\n    margin-top: -0.25rem !important;\n  }\n  .mr-xl-n1,\n  .mx-xl-n1 {\n    margin-right: -0.25rem !important;\n  }\n  .mb-xl-n1,\n  .my-xl-n1 {\n    margin-bottom: -0.25rem !important;\n  }\n  .ml-xl-n1,\n  .mx-xl-n1 {\n    margin-left: -0.25rem !important;\n  }\n  .m-xl-n2 {\n    margin: -0.5rem !important;\n  }\n  .mt-xl-n2,\n  .my-xl-n2 {\n    margin-top: -0.5rem !important;\n  }\n  .mr-xl-n2,\n  .mx-xl-n2 {\n    margin-right: -0.5rem !important;\n  }\n  .mb-xl-n2,\n  .my-xl-n2 {\n    margin-bottom: -0.5rem !important;\n  }\n  .ml-xl-n2,\n  .mx-xl-n2 {\n    margin-left: -0.5rem !important;\n  }\n  .m-xl-n3 {\n    margin: -1rem !important;\n  }\n  .mt-xl-n3,\n  .my-xl-n3 {\n    margin-top: -1rem !important;\n  }\n  .mr-xl-n3,\n  .mx-xl-n3 {\n    margin-right: -1rem !important;\n  }\n  .mb-xl-n3,\n  .my-xl-n3 {\n    margin-bottom: -1rem !important;\n  }\n  .ml-xl-n3,\n  .mx-xl-n3 {\n    margin-left: -1rem !important;\n  }\n  .m-xl-n4 {\n    margin: -1.5rem !important;\n  }\n  .mt-xl-n4,\n  .my-xl-n4 {\n    margin-top: -1.5rem !important;\n  }\n  .mr-xl-n4,\n  .mx-xl-n4 {\n    margin-right: -1.5rem !important;\n  }\n  .mb-xl-n4,\n  .my-xl-n4 {\n    margin-bottom: -1.5rem !important;\n  }\n  .ml-xl-n4,\n  .mx-xl-n4 {\n    margin-left: -1.5rem !important;\n  }\n  .m-xl-n5 {\n    margin: -3rem !important;\n  }\n  .mt-xl-n5,\n  .my-xl-n5 {\n    margin-top: -3rem !important;\n  }\n  .mr-xl-n5,\n  .mx-xl-n5 {\n    margin-right: -3rem !important;\n  }\n  .mb-xl-n5,\n  .my-xl-n5 {\n    margin-bottom: -3rem !important;\n  }\n  .ml-xl-n5,\n  .mx-xl-n5 {\n    margin-left: -3rem !important;\n  }\n  .m-xl-auto {\n    margin: auto !important;\n  }\n  .mt-xl-auto,\n  .my-xl-auto {\n    margin-top: auto !important;\n  }\n  .mr-xl-auto,\n  .mx-xl-auto {\n    margin-right: auto !important;\n  }\n  .mb-xl-auto,\n  .my-xl-auto {\n    margin-bottom: auto !important;\n  }\n  .ml-xl-auto,\n  .mx-xl-auto {\n    margin-left: auto !important;\n  }\n}\n\n.text-monospace {\n  font-family: SFMono-Regular, Menlo, Monaco, Consolas, \"Liberation Mono\", \"Courier New\", monospace !important;\n}\n\n.text-justify {\n  text-align: justify !important;\n}\n\n.text-wrap {\n  white-space: normal !important;\n}\n\n.text-nowrap {\n  white-space: nowrap !important;\n}\n\n.text-truncate {\n  overflow: hidden;\n  text-overflow: ellipsis;\n  white-space: nowrap;\n}\n\n.text-left {\n  text-align: left !important;\n}\n\n.text-right {\n  text-align: right !important;\n}\n\n.text-center {\n  text-align: center !important;\n}\n\n@media (min-width: 576px) {\n  .text-sm-left {\n    text-align: left !important;\n  }\n  .text-sm-right {\n    text-align: right !important;\n  }\n  .text-sm-center {\n    text-align: center !important;\n  }\n}\n\n@media (min-width: 768px) {\n  .text-md-left {\n    text-align: left !important;\n  }\n  .text-md-right {\n    text-align: right !important;\n  }\n  .text-md-center {\n    text-align: center !important;\n  }\n}\n\n@media (min-width: 992px) {\n  .text-lg-left {\n    text-align: left !important;\n  }\n  .text-lg-right {\n    text-align: right !important;\n  }\n  .text-lg-center {\n    text-align: center !important;\n  }\n}\n\n@media (min-width: 1200px) {\n  .text-xl-left {\n    text-align: left !important;\n  }\n  .text-xl-right {\n    text-align: right !important;\n  }\n  .text-xl-center {\n    text-align: center !important;\n  }\n}\n\n.text-lowercase {\n  text-transform: lowercase !important;\n}\n\n.text-uppercase {\n  text-transform: uppercase !important;\n}\n\n.text-capitalize {\n  text-transform: capitalize !important;\n}\n\n.font-weight-light {\n  font-weight: 300 !important;\n}\n\n.font-weight-lighter {\n  font-weight: lighter !important;\n}\n\n.font-weight-normal {\n  font-weight: 400 !important;\n}\n\n.font-weight-bold {\n  font-weight: 700 !important;\n}\n\n.font-weight-bolder {\n  font-weight: bolder !important;\n}\n\n.font-italic {\n  font-style: italic !important;\n}\n\n.text-white {\n  color: #fff !important;\n}\n\n.text-primary {\n  color: #007bff !important;\n}\n\na.text-primary:hover, a.text-primary:focus {\n  color: #0056b3 !important;\n}\n\n.text-secondary {\n  color: #6c757d !important;\n}\n\na.text-secondary:hover, a.text-secondary:focus {\n  color: #494f54 !important;\n}\n\n.text-success {\n  color: #28a745 !important;\n}\n\na.text-success:hover, a.text-success:focus {\n  color: #19692c !important;\n}\n\n.text-info {\n  color: #17a2b8 !important;\n}\n\na.text-info:hover, a.text-info:focus {\n  color: #0f6674 !important;\n}\n\n.text-warning {\n  color: #ffc107 !important;\n}\n\na.text-warning:hover, a.text-warning:focus {\n  color: #ba8b00 !important;\n}\n\n.text-danger {\n  color: #dc3545 !important;\n}\n\na.text-danger:hover, a.text-danger:focus {\n  color: #a71d2a !important;\n}\n\n.text-light {\n  color: #f8f9fa !important;\n}\n\na.text-light:hover, a.text-light:focus {\n  color: #cbd3da !important;\n}\n\n.text-dark {\n  color: #343a40 !important;\n}\n\na.text-dark:hover, a.text-dark:focus {\n  color: #121416 !important;\n}\n\n.text-body {\n  color: #212529 !important;\n}\n\n.text-muted {\n  color: #6c757d !important;\n}\n\n.text-black-50 {\n  color: rgba(0, 0, 0, 0.5) !important;\n}\n\n.text-white-50 {\n  color: rgba(255, 255, 255, 0.5) !important;\n}\n\n.text-hide {\n  font: 0/0 a;\n  color: transparent;\n  text-shadow: none;\n  background-color: transparent;\n  border: 0;\n}\n\n.text-decoration-none {\n  text-decoration: none !important;\n}\n\n.text-break {\n  word-break: break-word !important;\n  overflow-wrap: break-word !important;\n}\n\n.text-reset {\n  color: inherit !important;\n}\n\n.visible {\n  visibility: visible !important;\n}\n\n.invisible {\n  visibility: hidden !important;\n}\n\n@media print {\n  *,\n  *::before,\n  *::after {\n    text-shadow: none !important;\n    box-shadow: none !important;\n  }\n  a:not(.btn) {\n    text-decoration: underline;\n  }\n  abbr[title]::after {\n    content: \" (\" attr(title) \")\";\n  }\n  pre {\n    white-space: pre-wrap !important;\n  }\n  pre,\n  blockquote {\n    border: 1px solid #adb5bd;\n    page-break-inside: avoid;\n  }\n  thead {\n    display: table-header-group;\n  }\n  tr,\n  img {\n    page-break-inside: avoid;\n  }\n  p,\n  h2,\n  h3 {\n    orphans: 3;\n    widows: 3;\n  }\n  h2,\n  h3 {\n    page-break-after: avoid;\n  }\n  @page {\n    size: a3;\n  }\n  body {\n    min-width: 992px !important;\n  }\n  .container {\n    min-width: 992px !important;\n  }\n  .navbar {\n    display: none;\n  }\n  .badge {\n    border: 1px solid #000;\n  }\n  .table {\n    border-collapse: collapse !important;\n  }\n  .table td,\n  .table th {\n    background-color: #fff !important;\n  }\n  .table-bordered th,\n  .table-bordered td {\n    border: 1px solid #dee2e6 !important;\n  }\n  .table-dark {\n    color: inherit;\n  }\n  .table-dark th,\n  .table-dark td,\n  .table-dark thead th,\n  .table-dark tbody + tbody {\n    border-color: #dee2e6;\n  }\n  .table .thead-dark th {\n    color: inherit;\n    border-color: #dee2e6;\n  }\n}\n/*# sourceMappingURL=bootstrap.css.map */"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/bootstrap/js/bootstrap.bundle.js",
    "content": "/*!\n  * Bootstrap v4.3.1 (https://getbootstrap.com/)\n  * Copyright 2011-2019 The Bootstrap Authors (https://github.com/twbs/bootstrap/graphs/contributors)\n  * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n  */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? factory(exports, require('jquery')) :\n  typeof define === 'function' && define.amd ? define(['exports', 'jquery'], factory) :\n  (global = global || self, factory(global.bootstrap = {}, global.jQuery));\n}(this, function (exports, $) { 'use strict';\n\n  $ = $ && $.hasOwnProperty('default') ? $['default'] : $;\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _inheritsLoose(subClass, superClass) {\n    subClass.prototype = Object.create(superClass.prototype);\n    subClass.prototype.constructor = subClass;\n    subClass.__proto__ = superClass;\n  }\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): util.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  /**\n   * ------------------------------------------------------------------------\n   * Private TransitionEnd Helpers\n   * ------------------------------------------------------------------------\n   */\n\n  var TRANSITION_END = 'transitionend';\n  var MAX_UID = 1000000;\n  var MILLISECONDS_MULTIPLIER = 1000; // Shoutout AngusCroll (https://goo.gl/pxwQGp)\n\n  function toType(obj) {\n    return {}.toString.call(obj).match(/\\s([a-z]+)/i)[1].toLowerCase();\n  }\n\n  function getSpecialTransitionEndEvent() {\n    return {\n      bindType: TRANSITION_END,\n      delegateType: TRANSITION_END,\n      handle: function handle(event) {\n        if ($(event.target).is(this)) {\n          return event.handleObj.handler.apply(this, arguments); // eslint-disable-line prefer-rest-params\n        }\n\n        return undefined; // eslint-disable-line no-undefined\n      }\n    };\n  }\n\n  function transitionEndEmulator(duration) {\n    var _this = this;\n\n    var called = false;\n    $(this).one(Util.TRANSITION_END, function () {\n      called = true;\n    });\n    setTimeout(function () {\n      if (!called) {\n        Util.triggerTransitionEnd(_this);\n      }\n    }, duration);\n    return this;\n  }\n\n  function setTransitionEndSupport() {\n    $.fn.emulateTransitionEnd = transitionEndEmulator;\n    $.event.special[Util.TRANSITION_END] = getSpecialTransitionEndEvent();\n  }\n  /**\n   * --------------------------------------------------------------------------\n   * Public Util Api\n   * --------------------------------------------------------------------------\n   */\n\n\n  var Util = {\n    TRANSITION_END: 'bsTransitionEnd',\n    getUID: function getUID(prefix) {\n      do {\n        // eslint-disable-next-line no-bitwise\n        prefix += ~~(Math.random() * MAX_UID); // \"~~\" acts like a faster Math.floor() here\n      } while (document.getElementById(prefix));\n\n      return prefix;\n    },\n    getSelectorFromElement: function getSelectorFromElement(element) {\n      var selector = element.getAttribute('data-target');\n\n      if (!selector || selector === '#') {\n        var hrefAttr = element.getAttribute('href');\n        selector = hrefAttr && hrefAttr !== '#' ? hrefAttr.trim() : '';\n      }\n\n      try {\n        return document.querySelector(selector) ? selector : null;\n      } catch (err) {\n        return null;\n      }\n    },\n    getTransitionDurationFromElement: function getTransitionDurationFromElement(element) {\n      if (!element) {\n        return 0;\n      } // Get transition-duration of the element\n\n\n      var transitionDuration = $(element).css('transition-duration');\n      var transitionDelay = $(element).css('transition-delay');\n      var floatTransitionDuration = parseFloat(transitionDuration);\n      var floatTransitionDelay = parseFloat(transitionDelay); // Return 0 if element or transition duration is not found\n\n      if (!floatTransitionDuration && !floatTransitionDelay) {\n        return 0;\n      } // If multiple durations are defined, take the first\n\n\n      transitionDuration = transitionDuration.split(',')[0];\n      transitionDelay = transitionDelay.split(',')[0];\n      return (parseFloat(transitionDuration) + parseFloat(transitionDelay)) * MILLISECONDS_MULTIPLIER;\n    },\n    reflow: function reflow(element) {\n      return element.offsetHeight;\n    },\n    triggerTransitionEnd: function triggerTransitionEnd(element) {\n      $(element).trigger(TRANSITION_END);\n    },\n    // TODO: Remove in v5\n    supportsTransitionEnd: function supportsTransitionEnd() {\n      return Boolean(TRANSITION_END);\n    },\n    isElement: function isElement(obj) {\n      return (obj[0] || obj).nodeType;\n    },\n    typeCheckConfig: function typeCheckConfig(componentName, config, configTypes) {\n      for (var property in configTypes) {\n        if (Object.prototype.hasOwnProperty.call(configTypes, property)) {\n          var expectedTypes = configTypes[property];\n          var value = config[property];\n          var valueType = value && Util.isElement(value) ? 'element' : toType(value);\n\n          if (!new RegExp(expectedTypes).test(valueType)) {\n            throw new Error(componentName.toUpperCase() + \": \" + (\"Option \\\"\" + property + \"\\\" provided type \\\"\" + valueType + \"\\\" \") + (\"but expected type \\\"\" + expectedTypes + \"\\\".\"));\n          }\n        }\n      }\n    },\n    findShadowRoot: function findShadowRoot(element) {\n      if (!document.documentElement.attachShadow) {\n        return null;\n      } // Can find the shadow root otherwise it'll return the document\n\n\n      if (typeof element.getRootNode === 'function') {\n        var root = element.getRootNode();\n        return root instanceof ShadowRoot ? root : null;\n      }\n\n      if (element instanceof ShadowRoot) {\n        return element;\n      } // when we don't find a shadow root\n\n\n      if (!element.parentNode) {\n        return null;\n      }\n\n      return Util.findShadowRoot(element.parentNode);\n    }\n  };\n  setTransitionEndSupport();\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME = 'alert';\n  var VERSION = '4.3.1';\n  var DATA_KEY = 'bs.alert';\n  var EVENT_KEY = \".\" + DATA_KEY;\n  var DATA_API_KEY = '.data-api';\n  var JQUERY_NO_CONFLICT = $.fn[NAME];\n  var Selector = {\n    DISMISS: '[data-dismiss=\"alert\"]'\n  };\n  var Event = {\n    CLOSE: \"close\" + EVENT_KEY,\n    CLOSED: \"closed\" + EVENT_KEY,\n    CLICK_DATA_API: \"click\" + EVENT_KEY + DATA_API_KEY\n  };\n  var ClassName = {\n    ALERT: 'alert',\n    FADE: 'fade',\n    SHOW: 'show'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Alert =\n  /*#__PURE__*/\n  function () {\n    function Alert(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Alert.prototype;\n\n    // Public\n    _proto.close = function close(element) {\n      var rootElement = this._element;\n\n      if (element) {\n        rootElement = this._getRootElement(element);\n      }\n\n      var customEvent = this._triggerCloseEvent(rootElement);\n\n      if (customEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._removeElement(rootElement);\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._getRootElement = function _getRootElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      var parent = false;\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      if (!parent) {\n        parent = $(element).closest(\".\" + ClassName.ALERT)[0];\n      }\n\n      return parent;\n    };\n\n    _proto._triggerCloseEvent = function _triggerCloseEvent(element) {\n      var closeEvent = $.Event(Event.CLOSE);\n      $(element).trigger(closeEvent);\n      return closeEvent;\n    };\n\n    _proto._removeElement = function _removeElement(element) {\n      var _this = this;\n\n      $(element).removeClass(ClassName.SHOW);\n\n      if (!$(element).hasClass(ClassName.FADE)) {\n        this._destroyElement(element);\n\n        return;\n      }\n\n      var transitionDuration = Util.getTransitionDurationFromElement(element);\n      $(element).one(Util.TRANSITION_END, function (event) {\n        return _this._destroyElement(element, event);\n      }).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto._destroyElement = function _destroyElement(element) {\n      $(element).detach().trigger(Event.CLOSED).remove();\n    } // Static\n    ;\n\n    Alert._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY);\n\n        if (!data) {\n          data = new Alert(this);\n          $element.data(DATA_KEY, data);\n        }\n\n        if (config === 'close') {\n          data[config](this);\n        }\n      });\n    };\n\n    Alert._handleDismiss = function _handleDismiss(alertInstance) {\n      return function (event) {\n        if (event) {\n          event.preventDefault();\n        }\n\n        alertInstance.close(this);\n      };\n    };\n\n    _createClass(Alert, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION;\n      }\n    }]);\n\n    return Alert;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event.CLICK_DATA_API, Selector.DISMISS, Alert._handleDismiss(new Alert()));\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME] = Alert._jQueryInterface;\n  $.fn[NAME].Constructor = Alert;\n\n  $.fn[NAME].noConflict = function () {\n    $.fn[NAME] = JQUERY_NO_CONFLICT;\n    return Alert._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$1 = 'button';\n  var VERSION$1 = '4.3.1';\n  var DATA_KEY$1 = 'bs.button';\n  var EVENT_KEY$1 = \".\" + DATA_KEY$1;\n  var DATA_API_KEY$1 = '.data-api';\n  var JQUERY_NO_CONFLICT$1 = $.fn[NAME$1];\n  var ClassName$1 = {\n    ACTIVE: 'active',\n    BUTTON: 'btn',\n    FOCUS: 'focus'\n  };\n  var Selector$1 = {\n    DATA_TOGGLE_CARROT: '[data-toggle^=\"button\"]',\n    DATA_TOGGLE: '[data-toggle=\"buttons\"]',\n    INPUT: 'input:not([type=\"hidden\"])',\n    ACTIVE: '.active',\n    BUTTON: '.btn'\n  };\n  var Event$1 = {\n    CLICK_DATA_API: \"click\" + EVENT_KEY$1 + DATA_API_KEY$1,\n    FOCUS_BLUR_DATA_API: \"focus\" + EVENT_KEY$1 + DATA_API_KEY$1 + \" \" + (\"blur\" + EVENT_KEY$1 + DATA_API_KEY$1)\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Button =\n  /*#__PURE__*/\n  function () {\n    function Button(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Button.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      var triggerChangeEvent = true;\n      var addAriaPressed = true;\n      var rootElement = $(this._element).closest(Selector$1.DATA_TOGGLE)[0];\n\n      if (rootElement) {\n        var input = this._element.querySelector(Selector$1.INPUT);\n\n        if (input) {\n          if (input.type === 'radio') {\n            if (input.checked && this._element.classList.contains(ClassName$1.ACTIVE)) {\n              triggerChangeEvent = false;\n            } else {\n              var activeElement = rootElement.querySelector(Selector$1.ACTIVE);\n\n              if (activeElement) {\n                $(activeElement).removeClass(ClassName$1.ACTIVE);\n              }\n            }\n          }\n\n          if (triggerChangeEvent) {\n            if (input.hasAttribute('disabled') || rootElement.hasAttribute('disabled') || input.classList.contains('disabled') || rootElement.classList.contains('disabled')) {\n              return;\n            }\n\n            input.checked = !this._element.classList.contains(ClassName$1.ACTIVE);\n            $(input).trigger('change');\n          }\n\n          input.focus();\n          addAriaPressed = false;\n        }\n      }\n\n      if (addAriaPressed) {\n        this._element.setAttribute('aria-pressed', !this._element.classList.contains(ClassName$1.ACTIVE));\n      }\n\n      if (triggerChangeEvent) {\n        $(this._element).toggleClass(ClassName$1.ACTIVE);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$1);\n      this._element = null;\n    } // Static\n    ;\n\n    Button._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$1);\n\n        if (!data) {\n          data = new Button(this);\n          $(this).data(DATA_KEY$1, data);\n        }\n\n        if (config === 'toggle') {\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Button, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$1;\n      }\n    }]);\n\n    return Button;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$1.CLICK_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    event.preventDefault();\n    var button = event.target;\n\n    if (!$(button).hasClass(ClassName$1.BUTTON)) {\n      button = $(button).closest(Selector$1.BUTTON);\n    }\n\n    Button._jQueryInterface.call($(button), 'toggle');\n  }).on(Event$1.FOCUS_BLUR_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    var button = $(event.target).closest(Selector$1.BUTTON)[0];\n    $(button).toggleClass(ClassName$1.FOCUS, /^focus(in)?$/.test(event.type));\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$1] = Button._jQueryInterface;\n  $.fn[NAME$1].Constructor = Button;\n\n  $.fn[NAME$1].noConflict = function () {\n    $.fn[NAME$1] = JQUERY_NO_CONFLICT$1;\n    return Button._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$2 = 'carousel';\n  var VERSION$2 = '4.3.1';\n  var DATA_KEY$2 = 'bs.carousel';\n  var EVENT_KEY$2 = \".\" + DATA_KEY$2;\n  var DATA_API_KEY$2 = '.data-api';\n  var JQUERY_NO_CONFLICT$2 = $.fn[NAME$2];\n  var ARROW_LEFT_KEYCODE = 37; // KeyboardEvent.which value for left arrow key\n\n  var ARROW_RIGHT_KEYCODE = 39; // KeyboardEvent.which value for right arrow key\n\n  var TOUCHEVENT_COMPAT_WAIT = 500; // Time for mouse compat events to fire after touch\n\n  var SWIPE_THRESHOLD = 40;\n  var Default = {\n    interval: 5000,\n    keyboard: true,\n    slide: false,\n    pause: 'hover',\n    wrap: true,\n    touch: true\n  };\n  var DefaultType = {\n    interval: '(number|boolean)',\n    keyboard: 'boolean',\n    slide: '(boolean|string)',\n    pause: '(string|boolean)',\n    wrap: 'boolean',\n    touch: 'boolean'\n  };\n  var Direction = {\n    NEXT: 'next',\n    PREV: 'prev',\n    LEFT: 'left',\n    RIGHT: 'right'\n  };\n  var Event$2 = {\n    SLIDE: \"slide\" + EVENT_KEY$2,\n    SLID: \"slid\" + EVENT_KEY$2,\n    KEYDOWN: \"keydown\" + EVENT_KEY$2,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$2,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$2,\n    TOUCHSTART: \"touchstart\" + EVENT_KEY$2,\n    TOUCHMOVE: \"touchmove\" + EVENT_KEY$2,\n    TOUCHEND: \"touchend\" + EVENT_KEY$2,\n    POINTERDOWN: \"pointerdown\" + EVENT_KEY$2,\n    POINTERUP: \"pointerup\" + EVENT_KEY$2,\n    DRAG_START: \"dragstart\" + EVENT_KEY$2,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$2 + DATA_API_KEY$2,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$2 + DATA_API_KEY$2\n  };\n  var ClassName$2 = {\n    CAROUSEL: 'carousel',\n    ACTIVE: 'active',\n    SLIDE: 'slide',\n    RIGHT: 'carousel-item-right',\n    LEFT: 'carousel-item-left',\n    NEXT: 'carousel-item-next',\n    PREV: 'carousel-item-prev',\n    ITEM: 'carousel-item',\n    POINTER_EVENT: 'pointer-event'\n  };\n  var Selector$2 = {\n    ACTIVE: '.active',\n    ACTIVE_ITEM: '.active.carousel-item',\n    ITEM: '.carousel-item',\n    ITEM_IMG: '.carousel-item img',\n    NEXT_PREV: '.carousel-item-next, .carousel-item-prev',\n    INDICATORS: '.carousel-indicators',\n    DATA_SLIDE: '[data-slide], [data-slide-to]',\n    DATA_RIDE: '[data-ride=\"carousel\"]'\n  };\n  var PointerType = {\n    TOUCH: 'touch',\n    PEN: 'pen'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Carousel =\n  /*#__PURE__*/\n  function () {\n    function Carousel(element, config) {\n      this._items = null;\n      this._interval = null;\n      this._activeElement = null;\n      this._isPaused = false;\n      this._isSliding = false;\n      this.touchTimeout = null;\n      this.touchStartX = 0;\n      this.touchDeltaX = 0;\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._indicatorsElement = this._element.querySelector(Selector$2.INDICATORS);\n      this._touchSupported = 'ontouchstart' in document.documentElement || navigator.maxTouchPoints > 0;\n      this._pointerEvent = Boolean(window.PointerEvent || window.MSPointerEvent);\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Carousel.prototype;\n\n    // Public\n    _proto.next = function next() {\n      if (!this._isSliding) {\n        this._slide(Direction.NEXT);\n      }\n    };\n\n    _proto.nextWhenVisible = function nextWhenVisible() {\n      // Don't call next when the page isn't visible\n      // or the carousel or its parent isn't visible\n      if (!document.hidden && $(this._element).is(':visible') && $(this._element).css('visibility') !== 'hidden') {\n        this.next();\n      }\n    };\n\n    _proto.prev = function prev() {\n      if (!this._isSliding) {\n        this._slide(Direction.PREV);\n      }\n    };\n\n    _proto.pause = function pause(event) {\n      if (!event) {\n        this._isPaused = true;\n      }\n\n      if (this._element.querySelector(Selector$2.NEXT_PREV)) {\n        Util.triggerTransitionEnd(this._element);\n        this.cycle(true);\n      }\n\n      clearInterval(this._interval);\n      this._interval = null;\n    };\n\n    _proto.cycle = function cycle(event) {\n      if (!event) {\n        this._isPaused = false;\n      }\n\n      if (this._interval) {\n        clearInterval(this._interval);\n        this._interval = null;\n      }\n\n      if (this._config.interval && !this._isPaused) {\n        this._interval = setInterval((document.visibilityState ? this.nextWhenVisible : this.next).bind(this), this._config.interval);\n      }\n    };\n\n    _proto.to = function to(index) {\n      var _this = this;\n\n      this._activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeIndex = this._getItemIndex(this._activeElement);\n\n      if (index > this._items.length - 1 || index < 0) {\n        return;\n      }\n\n      if (this._isSliding) {\n        $(this._element).one(Event$2.SLID, function () {\n          return _this.to(index);\n        });\n        return;\n      }\n\n      if (activeIndex === index) {\n        this.pause();\n        this.cycle();\n        return;\n      }\n\n      var direction = index > activeIndex ? Direction.NEXT : Direction.PREV;\n\n      this._slide(direction, this._items[index]);\n    };\n\n    _proto.dispose = function dispose() {\n      $(this._element).off(EVENT_KEY$2);\n      $.removeData(this._element, DATA_KEY$2);\n      this._items = null;\n      this._config = null;\n      this._element = null;\n      this._interval = null;\n      this._isPaused = null;\n      this._isSliding = null;\n      this._activeElement = null;\n      this._indicatorsElement = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default, config);\n      Util.typeCheckConfig(NAME$2, config, DefaultType);\n      return config;\n    };\n\n    _proto._handleSwipe = function _handleSwipe() {\n      var absDeltax = Math.abs(this.touchDeltaX);\n\n      if (absDeltax <= SWIPE_THRESHOLD) {\n        return;\n      }\n\n      var direction = absDeltax / this.touchDeltaX; // swipe left\n\n      if (direction > 0) {\n        this.prev();\n      } // swipe right\n\n\n      if (direction < 0) {\n        this.next();\n      }\n    };\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this2 = this;\n\n      if (this._config.keyboard) {\n        $(this._element).on(Event$2.KEYDOWN, function (event) {\n          return _this2._keydown(event);\n        });\n      }\n\n      if (this._config.pause === 'hover') {\n        $(this._element).on(Event$2.MOUSEENTER, function (event) {\n          return _this2.pause(event);\n        }).on(Event$2.MOUSELEAVE, function (event) {\n          return _this2.cycle(event);\n        });\n      }\n\n      if (this._config.touch) {\n        this._addTouchEventListeners();\n      }\n    };\n\n    _proto._addTouchEventListeners = function _addTouchEventListeners() {\n      var _this3 = this;\n\n      if (!this._touchSupported) {\n        return;\n      }\n\n      var start = function start(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchStartX = event.originalEvent.clientX;\n        } else if (!_this3._pointerEvent) {\n          _this3.touchStartX = event.originalEvent.touches[0].clientX;\n        }\n      };\n\n      var move = function move(event) {\n        // ensure swiping with one touch and not pinching\n        if (event.originalEvent.touches && event.originalEvent.touches.length > 1) {\n          _this3.touchDeltaX = 0;\n        } else {\n          _this3.touchDeltaX = event.originalEvent.touches[0].clientX - _this3.touchStartX;\n        }\n      };\n\n      var end = function end(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchDeltaX = event.originalEvent.clientX - _this3.touchStartX;\n        }\n\n        _this3._handleSwipe();\n\n        if (_this3._config.pause === 'hover') {\n          // If it's a touch-enabled device, mouseenter/leave are fired as\n          // part of the mouse compatibility events on first tap - the carousel\n          // would stop cycling until user tapped out of it;\n          // here, we listen for touchend, explicitly pause the carousel\n          // (as if it's the second time we tap on it, mouseenter compat event\n          // is NOT fired) and after a timeout (to allow for mouse compatibility\n          // events to fire) we explicitly restart cycling\n          _this3.pause();\n\n          if (_this3.touchTimeout) {\n            clearTimeout(_this3.touchTimeout);\n          }\n\n          _this3.touchTimeout = setTimeout(function (event) {\n            return _this3.cycle(event);\n          }, TOUCHEVENT_COMPAT_WAIT + _this3._config.interval);\n        }\n      };\n\n      $(this._element.querySelectorAll(Selector$2.ITEM_IMG)).on(Event$2.DRAG_START, function (e) {\n        return e.preventDefault();\n      });\n\n      if (this._pointerEvent) {\n        $(this._element).on(Event$2.POINTERDOWN, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.POINTERUP, function (event) {\n          return end(event);\n        });\n\n        this._element.classList.add(ClassName$2.POINTER_EVENT);\n      } else {\n        $(this._element).on(Event$2.TOUCHSTART, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.TOUCHMOVE, function (event) {\n          return move(event);\n        });\n        $(this._element).on(Event$2.TOUCHEND, function (event) {\n          return end(event);\n        });\n      }\n    };\n\n    _proto._keydown = function _keydown(event) {\n      if (/input|textarea/i.test(event.target.tagName)) {\n        return;\n      }\n\n      switch (event.which) {\n        case ARROW_LEFT_KEYCODE:\n          event.preventDefault();\n          this.prev();\n          break;\n\n        case ARROW_RIGHT_KEYCODE:\n          event.preventDefault();\n          this.next();\n          break;\n\n        default:\n      }\n    };\n\n    _proto._getItemIndex = function _getItemIndex(element) {\n      this._items = element && element.parentNode ? [].slice.call(element.parentNode.querySelectorAll(Selector$2.ITEM)) : [];\n      return this._items.indexOf(element);\n    };\n\n    _proto._getItemByDirection = function _getItemByDirection(direction, activeElement) {\n      var isNextDirection = direction === Direction.NEXT;\n      var isPrevDirection = direction === Direction.PREV;\n\n      var activeIndex = this._getItemIndex(activeElement);\n\n      var lastItemIndex = this._items.length - 1;\n      var isGoingToWrap = isPrevDirection && activeIndex === 0 || isNextDirection && activeIndex === lastItemIndex;\n\n      if (isGoingToWrap && !this._config.wrap) {\n        return activeElement;\n      }\n\n      var delta = direction === Direction.PREV ? -1 : 1;\n      var itemIndex = (activeIndex + delta) % this._items.length;\n      return itemIndex === -1 ? this._items[this._items.length - 1] : this._items[itemIndex];\n    };\n\n    _proto._triggerSlideEvent = function _triggerSlideEvent(relatedTarget, eventDirectionName) {\n      var targetIndex = this._getItemIndex(relatedTarget);\n\n      var fromIndex = this._getItemIndex(this._element.querySelector(Selector$2.ACTIVE_ITEM));\n\n      var slideEvent = $.Event(Event$2.SLIDE, {\n        relatedTarget: relatedTarget,\n        direction: eventDirectionName,\n        from: fromIndex,\n        to: targetIndex\n      });\n      $(this._element).trigger(slideEvent);\n      return slideEvent;\n    };\n\n    _proto._setActiveIndicatorElement = function _setActiveIndicatorElement(element) {\n      if (this._indicatorsElement) {\n        var indicators = [].slice.call(this._indicatorsElement.querySelectorAll(Selector$2.ACTIVE));\n        $(indicators).removeClass(ClassName$2.ACTIVE);\n\n        var nextIndicator = this._indicatorsElement.children[this._getItemIndex(element)];\n\n        if (nextIndicator) {\n          $(nextIndicator).addClass(ClassName$2.ACTIVE);\n        }\n      }\n    };\n\n    _proto._slide = function _slide(direction, element) {\n      var _this4 = this;\n\n      var activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeElementIndex = this._getItemIndex(activeElement);\n\n      var nextElement = element || activeElement && this._getItemByDirection(direction, activeElement);\n\n      var nextElementIndex = this._getItemIndex(nextElement);\n\n      var isCycling = Boolean(this._interval);\n      var directionalClassName;\n      var orderClassName;\n      var eventDirectionName;\n\n      if (direction === Direction.NEXT) {\n        directionalClassName = ClassName$2.LEFT;\n        orderClassName = ClassName$2.NEXT;\n        eventDirectionName = Direction.LEFT;\n      } else {\n        directionalClassName = ClassName$2.RIGHT;\n        orderClassName = ClassName$2.PREV;\n        eventDirectionName = Direction.RIGHT;\n      }\n\n      if (nextElement && $(nextElement).hasClass(ClassName$2.ACTIVE)) {\n        this._isSliding = false;\n        return;\n      }\n\n      var slideEvent = this._triggerSlideEvent(nextElement, eventDirectionName);\n\n      if (slideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (!activeElement || !nextElement) {\n        // Some weirdness is happening, so we bail\n        return;\n      }\n\n      this._isSliding = true;\n\n      if (isCycling) {\n        this.pause();\n      }\n\n      this._setActiveIndicatorElement(nextElement);\n\n      var slidEvent = $.Event(Event$2.SLID, {\n        relatedTarget: nextElement,\n        direction: eventDirectionName,\n        from: activeElementIndex,\n        to: nextElementIndex\n      });\n\n      if ($(this._element).hasClass(ClassName$2.SLIDE)) {\n        $(nextElement).addClass(orderClassName);\n        Util.reflow(nextElement);\n        $(activeElement).addClass(directionalClassName);\n        $(nextElement).addClass(directionalClassName);\n        var nextElementInterval = parseInt(nextElement.getAttribute('data-interval'), 10);\n\n        if (nextElementInterval) {\n          this._config.defaultInterval = this._config.defaultInterval || this._config.interval;\n          this._config.interval = nextElementInterval;\n        } else {\n          this._config.interval = this._config.defaultInterval || this._config.interval;\n        }\n\n        var transitionDuration = Util.getTransitionDurationFromElement(activeElement);\n        $(activeElement).one(Util.TRANSITION_END, function () {\n          $(nextElement).removeClass(directionalClassName + \" \" + orderClassName).addClass(ClassName$2.ACTIVE);\n          $(activeElement).removeClass(ClassName$2.ACTIVE + \" \" + orderClassName + \" \" + directionalClassName);\n          _this4._isSliding = false;\n          setTimeout(function () {\n            return $(_this4._element).trigger(slidEvent);\n          }, 0);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        $(activeElement).removeClass(ClassName$2.ACTIVE);\n        $(nextElement).addClass(ClassName$2.ACTIVE);\n        this._isSliding = false;\n        $(this._element).trigger(slidEvent);\n      }\n\n      if (isCycling) {\n        this.cycle();\n      }\n    } // Static\n    ;\n\n    Carousel._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$2);\n\n        var _config = _objectSpread({}, Default, $(this).data());\n\n        if (typeof config === 'object') {\n          _config = _objectSpread({}, _config, config);\n        }\n\n        var action = typeof config === 'string' ? config : _config.slide;\n\n        if (!data) {\n          data = new Carousel(this, _config);\n          $(this).data(DATA_KEY$2, data);\n        }\n\n        if (typeof config === 'number') {\n          data.to(config);\n        } else if (typeof action === 'string') {\n          if (typeof data[action] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + action + \"\\\"\");\n          }\n\n          data[action]();\n        } else if (_config.interval && _config.ride) {\n          data.pause();\n          data.cycle();\n        }\n      });\n    };\n\n    Carousel._dataApiClickHandler = function _dataApiClickHandler(event) {\n      var selector = Util.getSelectorFromElement(this);\n\n      if (!selector) {\n        return;\n      }\n\n      var target = $(selector)[0];\n\n      if (!target || !$(target).hasClass(ClassName$2.CAROUSEL)) {\n        return;\n      }\n\n      var config = _objectSpread({}, $(target).data(), $(this).data());\n\n      var slideIndex = this.getAttribute('data-slide-to');\n\n      if (slideIndex) {\n        config.interval = false;\n      }\n\n      Carousel._jQueryInterface.call($(target), config);\n\n      if (slideIndex) {\n        $(target).data(DATA_KEY$2).to(slideIndex);\n      }\n\n      event.preventDefault();\n    };\n\n    _createClass(Carousel, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$2;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default;\n      }\n    }]);\n\n    return Carousel;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$2.CLICK_DATA_API, Selector$2.DATA_SLIDE, Carousel._dataApiClickHandler);\n  $(window).on(Event$2.LOAD_DATA_API, function () {\n    var carousels = [].slice.call(document.querySelectorAll(Selector$2.DATA_RIDE));\n\n    for (var i = 0, len = carousels.length; i < len; i++) {\n      var $carousel = $(carousels[i]);\n\n      Carousel._jQueryInterface.call($carousel, $carousel.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$2] = Carousel._jQueryInterface;\n  $.fn[NAME$2].Constructor = Carousel;\n\n  $.fn[NAME$2].noConflict = function () {\n    $.fn[NAME$2] = JQUERY_NO_CONFLICT$2;\n    return Carousel._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$3 = 'collapse';\n  var VERSION$3 = '4.3.1';\n  var DATA_KEY$3 = 'bs.collapse';\n  var EVENT_KEY$3 = \".\" + DATA_KEY$3;\n  var DATA_API_KEY$3 = '.data-api';\n  var JQUERY_NO_CONFLICT$3 = $.fn[NAME$3];\n  var Default$1 = {\n    toggle: true,\n    parent: ''\n  };\n  var DefaultType$1 = {\n    toggle: 'boolean',\n    parent: '(string|element)'\n  };\n  var Event$3 = {\n    SHOW: \"show\" + EVENT_KEY$3,\n    SHOWN: \"shown\" + EVENT_KEY$3,\n    HIDE: \"hide\" + EVENT_KEY$3,\n    HIDDEN: \"hidden\" + EVENT_KEY$3,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$3 + DATA_API_KEY$3\n  };\n  var ClassName$3 = {\n    SHOW: 'show',\n    COLLAPSE: 'collapse',\n    COLLAPSING: 'collapsing',\n    COLLAPSED: 'collapsed'\n  };\n  var Dimension = {\n    WIDTH: 'width',\n    HEIGHT: 'height'\n  };\n  var Selector$3 = {\n    ACTIVES: '.show, .collapsing',\n    DATA_TOGGLE: '[data-toggle=\"collapse\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Collapse =\n  /*#__PURE__*/\n  function () {\n    function Collapse(element, config) {\n      this._isTransitioning = false;\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._triggerArray = [].slice.call(document.querySelectorAll(\"[data-toggle=\\\"collapse\\\"][href=\\\"#\" + element.id + \"\\\"],\" + (\"[data-toggle=\\\"collapse\\\"][data-target=\\\"#\" + element.id + \"\\\"]\")));\n      var toggleList = [].slice.call(document.querySelectorAll(Selector$3.DATA_TOGGLE));\n\n      for (var i = 0, len = toggleList.length; i < len; i++) {\n        var elem = toggleList[i];\n        var selector = Util.getSelectorFromElement(elem);\n        var filterElement = [].slice.call(document.querySelectorAll(selector)).filter(function (foundElem) {\n          return foundElem === element;\n        });\n\n        if (selector !== null && filterElement.length > 0) {\n          this._selector = selector;\n\n          this._triggerArray.push(elem);\n        }\n      }\n\n      this._parent = this._config.parent ? this._getParent() : null;\n\n      if (!this._config.parent) {\n        this._addAriaAndCollapsedClass(this._element, this._triggerArray);\n      }\n\n      if (this._config.toggle) {\n        this.toggle();\n      }\n    } // Getters\n\n\n    var _proto = Collapse.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if ($(this._element).hasClass(ClassName$3.SHOW)) {\n        this.hide();\n      } else {\n        this.show();\n      }\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._isTransitioning || $(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var actives;\n      var activesData;\n\n      if (this._parent) {\n        actives = [].slice.call(this._parent.querySelectorAll(Selector$3.ACTIVES)).filter(function (elem) {\n          if (typeof _this._config.parent === 'string') {\n            return elem.getAttribute('data-parent') === _this._config.parent;\n          }\n\n          return elem.classList.contains(ClassName$3.COLLAPSE);\n        });\n\n        if (actives.length === 0) {\n          actives = null;\n        }\n      }\n\n      if (actives) {\n        activesData = $(actives).not(this._selector).data(DATA_KEY$3);\n\n        if (activesData && activesData._isTransitioning) {\n          return;\n        }\n      }\n\n      var startEvent = $.Event(Event$3.SHOW);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (actives) {\n        Collapse._jQueryInterface.call($(actives).not(this._selector), 'hide');\n\n        if (!activesData) {\n          $(actives).data(DATA_KEY$3, null);\n        }\n      }\n\n      var dimension = this._getDimension();\n\n      $(this._element).removeClass(ClassName$3.COLLAPSE).addClass(ClassName$3.COLLAPSING);\n      this._element.style[dimension] = 0;\n\n      if (this._triggerArray.length) {\n        $(this._triggerArray).removeClass(ClassName$3.COLLAPSED).attr('aria-expanded', true);\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        $(_this._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).addClass(ClassName$3.SHOW);\n        _this._element.style[dimension] = '';\n\n        _this.setTransitioning(false);\n\n        $(_this._element).trigger(Event$3.SHOWN);\n      };\n\n      var capitalizedDimension = dimension[0].toUpperCase() + dimension.slice(1);\n      var scrollSize = \"scroll\" + capitalizedDimension;\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      this._element.style[dimension] = this._element[scrollSize] + \"px\";\n    };\n\n    _proto.hide = function hide() {\n      var _this2 = this;\n\n      if (this._isTransitioning || !$(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var startEvent = $.Event(Event$3.HIDE);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      var dimension = this._getDimension();\n\n      this._element.style[dimension] = this._element.getBoundingClientRect()[dimension] + \"px\";\n      Util.reflow(this._element);\n      $(this._element).addClass(ClassName$3.COLLAPSING).removeClass(ClassName$3.COLLAPSE).removeClass(ClassName$3.SHOW);\n      var triggerArrayLength = this._triggerArray.length;\n\n      if (triggerArrayLength > 0) {\n        for (var i = 0; i < triggerArrayLength; i++) {\n          var trigger = this._triggerArray[i];\n          var selector = Util.getSelectorFromElement(trigger);\n\n          if (selector !== null) {\n            var $elem = $([].slice.call(document.querySelectorAll(selector)));\n\n            if (!$elem.hasClass(ClassName$3.SHOW)) {\n              $(trigger).addClass(ClassName$3.COLLAPSED).attr('aria-expanded', false);\n            }\n          }\n        }\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        _this2.setTransitioning(false);\n\n        $(_this2._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).trigger(Event$3.HIDDEN);\n      };\n\n      this._element.style[dimension] = '';\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto.setTransitioning = function setTransitioning(isTransitioning) {\n      this._isTransitioning = isTransitioning;\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$3);\n      this._config = null;\n      this._parent = null;\n      this._element = null;\n      this._triggerArray = null;\n      this._isTransitioning = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$1, config);\n      config.toggle = Boolean(config.toggle); // Coerce string values\n\n      Util.typeCheckConfig(NAME$3, config, DefaultType$1);\n      return config;\n    };\n\n    _proto._getDimension = function _getDimension() {\n      var hasWidth = $(this._element).hasClass(Dimension.WIDTH);\n      return hasWidth ? Dimension.WIDTH : Dimension.HEIGHT;\n    };\n\n    _proto._getParent = function _getParent() {\n      var _this3 = this;\n\n      var parent;\n\n      if (Util.isElement(this._config.parent)) {\n        parent = this._config.parent; // It's a jQuery object\n\n        if (typeof this._config.parent.jquery !== 'undefined') {\n          parent = this._config.parent[0];\n        }\n      } else {\n        parent = document.querySelector(this._config.parent);\n      }\n\n      var selector = \"[data-toggle=\\\"collapse\\\"][data-parent=\\\"\" + this._config.parent + \"\\\"]\";\n      var children = [].slice.call(parent.querySelectorAll(selector));\n      $(children).each(function (i, element) {\n        _this3._addAriaAndCollapsedClass(Collapse._getTargetFromElement(element), [element]);\n      });\n      return parent;\n    };\n\n    _proto._addAriaAndCollapsedClass = function _addAriaAndCollapsedClass(element, triggerArray) {\n      var isOpen = $(element).hasClass(ClassName$3.SHOW);\n\n      if (triggerArray.length) {\n        $(triggerArray).toggleClass(ClassName$3.COLLAPSED, !isOpen).attr('aria-expanded', isOpen);\n      }\n    } // Static\n    ;\n\n    Collapse._getTargetFromElement = function _getTargetFromElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      return selector ? document.querySelector(selector) : null;\n    };\n\n    Collapse._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$3);\n\n        var _config = _objectSpread({}, Default$1, $this.data(), typeof config === 'object' && config ? config : {});\n\n        if (!data && _config.toggle && /show|hide/.test(config)) {\n          _config.toggle = false;\n        }\n\n        if (!data) {\n          data = new Collapse(this, _config);\n          $this.data(DATA_KEY$3, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Collapse, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$3;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$1;\n      }\n    }]);\n\n    return Collapse;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$3.CLICK_DATA_API, Selector$3.DATA_TOGGLE, function (event) {\n    // preventDefault only for <a> elements (which change the URL) not inside the collapsible element\n    if (event.currentTarget.tagName === 'A') {\n      event.preventDefault();\n    }\n\n    var $trigger = $(this);\n    var selector = Util.getSelectorFromElement(this);\n    var selectors = [].slice.call(document.querySelectorAll(selector));\n    $(selectors).each(function () {\n      var $target = $(this);\n      var data = $target.data(DATA_KEY$3);\n      var config = data ? 'toggle' : $trigger.data();\n\n      Collapse._jQueryInterface.call($target, config);\n    });\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$3] = Collapse._jQueryInterface;\n  $.fn[NAME$3].Constructor = Collapse;\n\n  $.fn[NAME$3].noConflict = function () {\n    $.fn[NAME$3] = JQUERY_NO_CONFLICT$3;\n    return Collapse._jQueryInterface;\n  };\n\n  /**!\n   * @fileOverview Kickass library to create and place poppers near their reference elements.\n   * @version 1.14.7\n   * @license\n   * Copyright (c) 2016 Federico Zivolo and contributors\n   *\n   * Permission is hereby granted, free of charge, to any person obtaining a copy\n   * of this software and associated documentation files (the \"Software\"), to deal\n   * in the Software without restriction, including without limitation the rights\n   * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell\n   * copies of the Software, and to permit persons to whom the Software is\n   * furnished to do so, subject to the following conditions:\n   *\n   * The above copyright notice and this permission notice shall be included in all\n   * copies or substantial portions of the Software.\n   *\n   * THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n   * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n   * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\n   * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\n   * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\n   * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\n   * SOFTWARE.\n   */\n  var isBrowser = typeof window !== 'undefined' && typeof document !== 'undefined';\n\n  var longerTimeoutBrowsers = ['Edge', 'Trident', 'Firefox'];\n  var timeoutDuration = 0;\n  for (var i = 0; i < longerTimeoutBrowsers.length; i += 1) {\n    if (isBrowser && navigator.userAgent.indexOf(longerTimeoutBrowsers[i]) >= 0) {\n      timeoutDuration = 1;\n      break;\n    }\n  }\n\n  function microtaskDebounce(fn) {\n    var called = false;\n    return function () {\n      if (called) {\n        return;\n      }\n      called = true;\n      window.Promise.resolve().then(function () {\n        called = false;\n        fn();\n      });\n    };\n  }\n\n  function taskDebounce(fn) {\n    var scheduled = false;\n    return function () {\n      if (!scheduled) {\n        scheduled = true;\n        setTimeout(function () {\n          scheduled = false;\n          fn();\n        }, timeoutDuration);\n      }\n    };\n  }\n\n  var supportsMicroTasks = isBrowser && window.Promise;\n\n  /**\n  * Create a debounced version of a method, that's asynchronously deferred\n  * but called in the minimum time possible.\n  *\n  * @method\n  * @memberof Popper.Utils\n  * @argument {Function} fn\n  * @returns {Function}\n  */\n  var debounce = supportsMicroTasks ? microtaskDebounce : taskDebounce;\n\n  /**\n   * Check if the given variable is a function\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Any} functionToCheck - variable to check\n   * @returns {Boolean} answer to: is a function?\n   */\n  function isFunction(functionToCheck) {\n    var getType = {};\n    return functionToCheck && getType.toString.call(functionToCheck) === '[object Function]';\n  }\n\n  /**\n   * Get CSS computed property of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Eement} element\n   * @argument {String} property\n   */\n  function getStyleComputedProperty(element, property) {\n    if (element.nodeType !== 1) {\n      return [];\n    }\n    // NOTE: 1 DOM access here\n    var window = element.ownerDocument.defaultView;\n    var css = window.getComputedStyle(element, null);\n    return property ? css[property] : css;\n  }\n\n  /**\n   * Returns the parentNode or the host of the element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} parent\n   */\n  function getParentNode(element) {\n    if (element.nodeName === 'HTML') {\n      return element;\n    }\n    return element.parentNode || element.host;\n  }\n\n  /**\n   * Returns the scrolling parent of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} scroll parent\n   */\n  function getScrollParent(element) {\n    // Return body, `getScroll` will take care to get the correct `scrollTop` from it\n    if (!element) {\n      return document.body;\n    }\n\n    switch (element.nodeName) {\n      case 'HTML':\n      case 'BODY':\n        return element.ownerDocument.body;\n      case '#document':\n        return element.body;\n    }\n\n    // Firefox want us to check `-x` and `-y` variations as well\n\n    var _getStyleComputedProp = getStyleComputedProperty(element),\n        overflow = _getStyleComputedProp.overflow,\n        overflowX = _getStyleComputedProp.overflowX,\n        overflowY = _getStyleComputedProp.overflowY;\n\n    if (/(auto|scroll|overlay)/.test(overflow + overflowY + overflowX)) {\n      return element;\n    }\n\n    return getScrollParent(getParentNode(element));\n  }\n\n  var isIE11 = isBrowser && !!(window.MSInputMethodContext && document.documentMode);\n  var isIE10 = isBrowser && /MSIE 10/.test(navigator.userAgent);\n\n  /**\n   * Determines if the browser is Internet Explorer\n   * @method\n   * @memberof Popper.Utils\n   * @param {Number} version to check\n   * @returns {Boolean} isIE\n   */\n  function isIE(version) {\n    if (version === 11) {\n      return isIE11;\n    }\n    if (version === 10) {\n      return isIE10;\n    }\n    return isIE11 || isIE10;\n  }\n\n  /**\n   * Returns the offset parent of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} offset parent\n   */\n  function getOffsetParent(element) {\n    if (!element) {\n      return document.documentElement;\n    }\n\n    var noOffsetParent = isIE(10) ? document.body : null;\n\n    // NOTE: 1 DOM access here\n    var offsetParent = element.offsetParent || null;\n    // Skip hidden elements which don't have an offsetParent\n    while (offsetParent === noOffsetParent && element.nextElementSibling) {\n      offsetParent = (element = element.nextElementSibling).offsetParent;\n    }\n\n    var nodeName = offsetParent && offsetParent.nodeName;\n\n    if (!nodeName || nodeName === 'BODY' || nodeName === 'HTML') {\n      return element ? element.ownerDocument.documentElement : document.documentElement;\n    }\n\n    // .offsetParent will return the closest TH, TD or TABLE in case\n    // no offsetParent is present, I hate this job...\n    if (['TH', 'TD', 'TABLE'].indexOf(offsetParent.nodeName) !== -1 && getStyleComputedProperty(offsetParent, 'position') === 'static') {\n      return getOffsetParent(offsetParent);\n    }\n\n    return offsetParent;\n  }\n\n  function isOffsetContainer(element) {\n    var nodeName = element.nodeName;\n\n    if (nodeName === 'BODY') {\n      return false;\n    }\n    return nodeName === 'HTML' || getOffsetParent(element.firstElementChild) === element;\n  }\n\n  /**\n   * Finds the root node (document, shadowDOM root) of the given element\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} node\n   * @returns {Element} root node\n   */\n  function getRoot(node) {\n    if (node.parentNode !== null) {\n      return getRoot(node.parentNode);\n    }\n\n    return node;\n  }\n\n  /**\n   * Finds the offset parent common to the two provided nodes\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element1\n   * @argument {Element} element2\n   * @returns {Element} common offset parent\n   */\n  function findCommonOffsetParent(element1, element2) {\n    // This check is needed to avoid errors in case one of the elements isn't defined for any reason\n    if (!element1 || !element1.nodeType || !element2 || !element2.nodeType) {\n      return document.documentElement;\n    }\n\n    // Here we make sure to give as \"start\" the element that comes first in the DOM\n    var order = element1.compareDocumentPosition(element2) & Node.DOCUMENT_POSITION_FOLLOWING;\n    var start = order ? element1 : element2;\n    var end = order ? element2 : element1;\n\n    // Get common ancestor container\n    var range = document.createRange();\n    range.setStart(start, 0);\n    range.setEnd(end, 0);\n    var commonAncestorContainer = range.commonAncestorContainer;\n\n    // Both nodes are inside #document\n\n    if (element1 !== commonAncestorContainer && element2 !== commonAncestorContainer || start.contains(end)) {\n      if (isOffsetContainer(commonAncestorContainer)) {\n        return commonAncestorContainer;\n      }\n\n      return getOffsetParent(commonAncestorContainer);\n    }\n\n    // one of the nodes is inside shadowDOM, find which one\n    var element1root = getRoot(element1);\n    if (element1root.host) {\n      return findCommonOffsetParent(element1root.host, element2);\n    } else {\n      return findCommonOffsetParent(element1, getRoot(element2).host);\n    }\n  }\n\n  /**\n   * Gets the scroll value of the given element in the given side (top and left)\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @argument {String} side `top` or `left`\n   * @returns {number} amount of scrolled pixels\n   */\n  function getScroll(element) {\n    var side = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : 'top';\n\n    var upperSide = side === 'top' ? 'scrollTop' : 'scrollLeft';\n    var nodeName = element.nodeName;\n\n    if (nodeName === 'BODY' || nodeName === 'HTML') {\n      var html = element.ownerDocument.documentElement;\n      var scrollingElement = element.ownerDocument.scrollingElement || html;\n      return scrollingElement[upperSide];\n    }\n\n    return element[upperSide];\n  }\n\n  /*\n   * Sum or subtract the element scroll values (left and top) from a given rect object\n   * @method\n   * @memberof Popper.Utils\n   * @param {Object} rect - Rect object you want to change\n   * @param {HTMLElement} element - The element from the function reads the scroll values\n   * @param {Boolean} subtract - set to true if you want to subtract the scroll values\n   * @return {Object} rect - The modifier rect object\n   */\n  function includeScroll(rect, element) {\n    var subtract = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false;\n\n    var scrollTop = getScroll(element, 'top');\n    var scrollLeft = getScroll(element, 'left');\n    var modifier = subtract ? -1 : 1;\n    rect.top += scrollTop * modifier;\n    rect.bottom += scrollTop * modifier;\n    rect.left += scrollLeft * modifier;\n    rect.right += scrollLeft * modifier;\n    return rect;\n  }\n\n  /*\n   * Helper to detect borders of a given element\n   * @method\n   * @memberof Popper.Utils\n   * @param {CSSStyleDeclaration} styles\n   * Result of `getStyleComputedProperty` on the given element\n   * @param {String} axis - `x` or `y`\n   * @return {number} borders - The borders size of the given axis\n   */\n\n  function getBordersSize(styles, axis) {\n    var sideA = axis === 'x' ? 'Left' : 'Top';\n    var sideB = sideA === 'Left' ? 'Right' : 'Bottom';\n\n    return parseFloat(styles['border' + sideA + 'Width'], 10) + parseFloat(styles['border' + sideB + 'Width'], 10);\n  }\n\n  function getSize(axis, body, html, computedStyle) {\n    return Math.max(body['offset' + axis], body['scroll' + axis], html['client' + axis], html['offset' + axis], html['scroll' + axis], isIE(10) ? parseInt(html['offset' + axis]) + parseInt(computedStyle['margin' + (axis === 'Height' ? 'Top' : 'Left')]) + parseInt(computedStyle['margin' + (axis === 'Height' ? 'Bottom' : 'Right')]) : 0);\n  }\n\n  function getWindowSizes(document) {\n    var body = document.body;\n    var html = document.documentElement;\n    var computedStyle = isIE(10) && getComputedStyle(html);\n\n    return {\n      height: getSize('Height', body, html, computedStyle),\n      width: getSize('Width', body, html, computedStyle)\n    };\n  }\n\n  var classCallCheck = function (instance, Constructor) {\n    if (!(instance instanceof Constructor)) {\n      throw new TypeError(\"Cannot call a class as a function\");\n    }\n  };\n\n  var createClass = function () {\n    function defineProperties(target, props) {\n      for (var i = 0; i < props.length; i++) {\n        var descriptor = props[i];\n        descriptor.enumerable = descriptor.enumerable || false;\n        descriptor.configurable = true;\n        if (\"value\" in descriptor) descriptor.writable = true;\n        Object.defineProperty(target, descriptor.key, descriptor);\n      }\n    }\n\n    return function (Constructor, protoProps, staticProps) {\n      if (protoProps) defineProperties(Constructor.prototype, protoProps);\n      if (staticProps) defineProperties(Constructor, staticProps);\n      return Constructor;\n    };\n  }();\n\n\n\n\n\n  var defineProperty = function (obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  };\n\n  var _extends = Object.assign || function (target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i];\n\n      for (var key in source) {\n        if (Object.prototype.hasOwnProperty.call(source, key)) {\n          target[key] = source[key];\n        }\n      }\n    }\n\n    return target;\n  };\n\n  /**\n   * Given element offsets, generate an output similar to getBoundingClientRect\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Object} offsets\n   * @returns {Object} ClientRect like output\n   */\n  function getClientRect(offsets) {\n    return _extends({}, offsets, {\n      right: offsets.left + offsets.width,\n      bottom: offsets.top + offsets.height\n    });\n  }\n\n  /**\n   * Get bounding client rect of given element\n   * @method\n   * @memberof Popper.Utils\n   * @param {HTMLElement} element\n   * @return {Object} client rect\n   */\n  function getBoundingClientRect(element) {\n    var rect = {};\n\n    // IE10 10 FIX: Please, don't ask, the element isn't\n    // considered in DOM in some circumstances...\n    // This isn't reproducible in IE10 compatibility mode of IE11\n    try {\n      if (isIE(10)) {\n        rect = element.getBoundingClientRect();\n        var scrollTop = getScroll(element, 'top');\n        var scrollLeft = getScroll(element, 'left');\n        rect.top += scrollTop;\n        rect.left += scrollLeft;\n        rect.bottom += scrollTop;\n        rect.right += scrollLeft;\n      } else {\n        rect = element.getBoundingClientRect();\n      }\n    } catch (e) {}\n\n    var result = {\n      left: rect.left,\n      top: rect.top,\n      width: rect.right - rect.left,\n      height: rect.bottom - rect.top\n    };\n\n    // subtract scrollbar size from sizes\n    var sizes = element.nodeName === 'HTML' ? getWindowSizes(element.ownerDocument) : {};\n    var width = sizes.width || element.clientWidth || result.right - result.left;\n    var height = sizes.height || element.clientHeight || result.bottom - result.top;\n\n    var horizScrollbar = element.offsetWidth - width;\n    var vertScrollbar = element.offsetHeight - height;\n\n    // if an hypothetical scrollbar is detected, we must be sure it's not a `border`\n    // we make this check conditional for performance reasons\n    if (horizScrollbar || vertScrollbar) {\n      var styles = getStyleComputedProperty(element);\n      horizScrollbar -= getBordersSize(styles, 'x');\n      vertScrollbar -= getBordersSize(styles, 'y');\n\n      result.width -= horizScrollbar;\n      result.height -= vertScrollbar;\n    }\n\n    return getClientRect(result);\n  }\n\n  function getOffsetRectRelativeToArbitraryNode(children, parent) {\n    var fixedPosition = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false;\n\n    var isIE10 = isIE(10);\n    var isHTML = parent.nodeName === 'HTML';\n    var childrenRect = getBoundingClientRect(children);\n    var parentRect = getBoundingClientRect(parent);\n    var scrollParent = getScrollParent(children);\n\n    var styles = getStyleComputedProperty(parent);\n    var borderTopWidth = parseFloat(styles.borderTopWidth, 10);\n    var borderLeftWidth = parseFloat(styles.borderLeftWidth, 10);\n\n    // In cases where the parent is fixed, we must ignore negative scroll in offset calc\n    if (fixedPosition && isHTML) {\n      parentRect.top = Math.max(parentRect.top, 0);\n      parentRect.left = Math.max(parentRect.left, 0);\n    }\n    var offsets = getClientRect({\n      top: childrenRect.top - parentRect.top - borderTopWidth,\n      left: childrenRect.left - parentRect.left - borderLeftWidth,\n      width: childrenRect.width,\n      height: childrenRect.height\n    });\n    offsets.marginTop = 0;\n    offsets.marginLeft = 0;\n\n    // Subtract margins of documentElement in case it's being used as parent\n    // we do this only on HTML because it's the only element that behaves\n    // differently when margins are applied to it. The margins are included in\n    // the box of the documentElement, in the other cases not.\n    if (!isIE10 && isHTML) {\n      var marginTop = parseFloat(styles.marginTop, 10);\n      var marginLeft = parseFloat(styles.marginLeft, 10);\n\n      offsets.top -= borderTopWidth - marginTop;\n      offsets.bottom -= borderTopWidth - marginTop;\n      offsets.left -= borderLeftWidth - marginLeft;\n      offsets.right -= borderLeftWidth - marginLeft;\n\n      // Attach marginTop and marginLeft because in some circumstances we may need them\n      offsets.marginTop = marginTop;\n      offsets.marginLeft = marginLeft;\n    }\n\n    if (isIE10 && !fixedPosition ? parent.contains(scrollParent) : parent === scrollParent && scrollParent.nodeName !== 'BODY') {\n      offsets = includeScroll(offsets, parent);\n    }\n\n    return offsets;\n  }\n\n  function getViewportOffsetRectRelativeToArtbitraryNode(element) {\n    var excludeScroll = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;\n\n    var html = element.ownerDocument.documentElement;\n    var relativeOffset = getOffsetRectRelativeToArbitraryNode(element, html);\n    var width = Math.max(html.clientWidth, window.innerWidth || 0);\n    var height = Math.max(html.clientHeight, window.innerHeight || 0);\n\n    var scrollTop = !excludeScroll ? getScroll(html) : 0;\n    var scrollLeft = !excludeScroll ? getScroll(html, 'left') : 0;\n\n    var offset = {\n      top: scrollTop - relativeOffset.top + relativeOffset.marginTop,\n      left: scrollLeft - relativeOffset.left + relativeOffset.marginLeft,\n      width: width,\n      height: height\n    };\n\n    return getClientRect(offset);\n  }\n\n  /**\n   * Check if the given element is fixed or is inside a fixed parent\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @argument {Element} customContainer\n   * @returns {Boolean} answer to \"isFixed?\"\n   */\n  function isFixed(element) {\n    var nodeName = element.nodeName;\n    if (nodeName === 'BODY' || nodeName === 'HTML') {\n      return false;\n    }\n    if (getStyleComputedProperty(element, 'position') === 'fixed') {\n      return true;\n    }\n    var parentNode = getParentNode(element);\n    if (!parentNode) {\n      return false;\n    }\n    return isFixed(parentNode);\n  }\n\n  /**\n   * Finds the first parent of an element that has a transformed property defined\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Element} first transformed parent or documentElement\n   */\n\n  function getFixedPositionOffsetParent(element) {\n    // This check is needed to avoid errors in case one of the elements isn't defined for any reason\n    if (!element || !element.parentElement || isIE()) {\n      return document.documentElement;\n    }\n    var el = element.parentElement;\n    while (el && getStyleComputedProperty(el, 'transform') === 'none') {\n      el = el.parentElement;\n    }\n    return el || document.documentElement;\n  }\n\n  /**\n   * Computed the boundaries limits and return them\n   * @method\n   * @memberof Popper.Utils\n   * @param {HTMLElement} popper\n   * @param {HTMLElement} reference\n   * @param {number} padding\n   * @param {HTMLElement} boundariesElement - Element used to define the boundaries\n   * @param {Boolean} fixedPosition - Is in fixed position mode\n   * @returns {Object} Coordinates of the boundaries\n   */\n  function getBoundaries(popper, reference, padding, boundariesElement) {\n    var fixedPosition = arguments.length > 4 && arguments[4] !== undefined ? arguments[4] : false;\n\n    // NOTE: 1 DOM access here\n\n    var boundaries = { top: 0, left: 0 };\n    var offsetParent = fixedPosition ? getFixedPositionOffsetParent(popper) : findCommonOffsetParent(popper, reference);\n\n    // Handle viewport case\n    if (boundariesElement === 'viewport') {\n      boundaries = getViewportOffsetRectRelativeToArtbitraryNode(offsetParent, fixedPosition);\n    } else {\n      // Handle other cases based on DOM element used as boundaries\n      var boundariesNode = void 0;\n      if (boundariesElement === 'scrollParent') {\n        boundariesNode = getScrollParent(getParentNode(reference));\n        if (boundariesNode.nodeName === 'BODY') {\n          boundariesNode = popper.ownerDocument.documentElement;\n        }\n      } else if (boundariesElement === 'window') {\n        boundariesNode = popper.ownerDocument.documentElement;\n      } else {\n        boundariesNode = boundariesElement;\n      }\n\n      var offsets = getOffsetRectRelativeToArbitraryNode(boundariesNode, offsetParent, fixedPosition);\n\n      // In case of HTML, we need a different computation\n      if (boundariesNode.nodeName === 'HTML' && !isFixed(offsetParent)) {\n        var _getWindowSizes = getWindowSizes(popper.ownerDocument),\n            height = _getWindowSizes.height,\n            width = _getWindowSizes.width;\n\n        boundaries.top += offsets.top - offsets.marginTop;\n        boundaries.bottom = height + offsets.top;\n        boundaries.left += offsets.left - offsets.marginLeft;\n        boundaries.right = width + offsets.left;\n      } else {\n        // for all the other DOM elements, this one is good\n        boundaries = offsets;\n      }\n    }\n\n    // Add paddings\n    padding = padding || 0;\n    var isPaddingNumber = typeof padding === 'number';\n    boundaries.left += isPaddingNumber ? padding : padding.left || 0;\n    boundaries.top += isPaddingNumber ? padding : padding.top || 0;\n    boundaries.right -= isPaddingNumber ? padding : padding.right || 0;\n    boundaries.bottom -= isPaddingNumber ? padding : padding.bottom || 0;\n\n    return boundaries;\n  }\n\n  function getArea(_ref) {\n    var width = _ref.width,\n        height = _ref.height;\n\n    return width * height;\n  }\n\n  /**\n   * Utility used to transform the `auto` placement to the placement with more\n   * available space.\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function computeAutoPlacement(placement, refRect, popper, reference, boundariesElement) {\n    var padding = arguments.length > 5 && arguments[5] !== undefined ? arguments[5] : 0;\n\n    if (placement.indexOf('auto') === -1) {\n      return placement;\n    }\n\n    var boundaries = getBoundaries(popper, reference, padding, boundariesElement);\n\n    var rects = {\n      top: {\n        width: boundaries.width,\n        height: refRect.top - boundaries.top\n      },\n      right: {\n        width: boundaries.right - refRect.right,\n        height: boundaries.height\n      },\n      bottom: {\n        width: boundaries.width,\n        height: boundaries.bottom - refRect.bottom\n      },\n      left: {\n        width: refRect.left - boundaries.left,\n        height: boundaries.height\n      }\n    };\n\n    var sortedAreas = Object.keys(rects).map(function (key) {\n      return _extends({\n        key: key\n      }, rects[key], {\n        area: getArea(rects[key])\n      });\n    }).sort(function (a, b) {\n      return b.area - a.area;\n    });\n\n    var filteredAreas = sortedAreas.filter(function (_ref2) {\n      var width = _ref2.width,\n          height = _ref2.height;\n      return width >= popper.clientWidth && height >= popper.clientHeight;\n    });\n\n    var computedPlacement = filteredAreas.length > 0 ? filteredAreas[0].key : sortedAreas[0].key;\n\n    var variation = placement.split('-')[1];\n\n    return computedPlacement + (variation ? '-' + variation : '');\n  }\n\n  /**\n   * Get offsets to the reference element\n   * @method\n   * @memberof Popper.Utils\n   * @param {Object} state\n   * @param {Element} popper - the popper element\n   * @param {Element} reference - the reference element (the popper will be relative to this)\n   * @param {Element} fixedPosition - is in fixed position mode\n   * @returns {Object} An object containing the offsets which will be applied to the popper\n   */\n  function getReferenceOffsets(state, popper, reference) {\n    var fixedPosition = arguments.length > 3 && arguments[3] !== undefined ? arguments[3] : null;\n\n    var commonOffsetParent = fixedPosition ? getFixedPositionOffsetParent(popper) : findCommonOffsetParent(popper, reference);\n    return getOffsetRectRelativeToArbitraryNode(reference, commonOffsetParent, fixedPosition);\n  }\n\n  /**\n   * Get the outer sizes of the given element (offset size + margins)\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element\n   * @returns {Object} object containing width and height properties\n   */\n  function getOuterSizes(element) {\n    var window = element.ownerDocument.defaultView;\n    var styles = window.getComputedStyle(element);\n    var x = parseFloat(styles.marginTop || 0) + parseFloat(styles.marginBottom || 0);\n    var y = parseFloat(styles.marginLeft || 0) + parseFloat(styles.marginRight || 0);\n    var result = {\n      width: element.offsetWidth + y,\n      height: element.offsetHeight + x\n    };\n    return result;\n  }\n\n  /**\n   * Get the opposite placement of the given one\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} placement\n   * @returns {String} flipped placement\n   */\n  function getOppositePlacement(placement) {\n    var hash = { left: 'right', right: 'left', bottom: 'top', top: 'bottom' };\n    return placement.replace(/left|right|bottom|top/g, function (matched) {\n      return hash[matched];\n    });\n  }\n\n  /**\n   * Get offsets to the popper\n   * @method\n   * @memberof Popper.Utils\n   * @param {Object} position - CSS position the Popper will get applied\n   * @param {HTMLElement} popper - the popper element\n   * @param {Object} referenceOffsets - the reference offsets (the popper will be relative to this)\n   * @param {String} placement - one of the valid placement options\n   * @returns {Object} popperOffsets - An object containing the offsets which will be applied to the popper\n   */\n  function getPopperOffsets(popper, referenceOffsets, placement) {\n    placement = placement.split('-')[0];\n\n    // Get popper node sizes\n    var popperRect = getOuterSizes(popper);\n\n    // Add position, width and height to our offsets object\n    var popperOffsets = {\n      width: popperRect.width,\n      height: popperRect.height\n    };\n\n    // depending by the popper placement we have to compute its offsets slightly differently\n    var isHoriz = ['right', 'left'].indexOf(placement) !== -1;\n    var mainSide = isHoriz ? 'top' : 'left';\n    var secondarySide = isHoriz ? 'left' : 'top';\n    var measurement = isHoriz ? 'height' : 'width';\n    var secondaryMeasurement = !isHoriz ? 'height' : 'width';\n\n    popperOffsets[mainSide] = referenceOffsets[mainSide] + referenceOffsets[measurement] / 2 - popperRect[measurement] / 2;\n    if (placement === secondarySide) {\n      popperOffsets[secondarySide] = referenceOffsets[secondarySide] - popperRect[secondaryMeasurement];\n    } else {\n      popperOffsets[secondarySide] = referenceOffsets[getOppositePlacement(secondarySide)];\n    }\n\n    return popperOffsets;\n  }\n\n  /**\n   * Mimics the `find` method of Array\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Array} arr\n   * @argument prop\n   * @argument value\n   * @returns index or -1\n   */\n  function find(arr, check) {\n    // use native find if supported\n    if (Array.prototype.find) {\n      return arr.find(check);\n    }\n\n    // use `filter` to obtain the same behavior of `find`\n    return arr.filter(check)[0];\n  }\n\n  /**\n   * Return the index of the matching object\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Array} arr\n   * @argument prop\n   * @argument value\n   * @returns index or -1\n   */\n  function findIndex(arr, prop, value) {\n    // use native findIndex if supported\n    if (Array.prototype.findIndex) {\n      return arr.findIndex(function (cur) {\n        return cur[prop] === value;\n      });\n    }\n\n    // use `find` + `indexOf` if `findIndex` isn't supported\n    var match = find(arr, function (obj) {\n      return obj[prop] === value;\n    });\n    return arr.indexOf(match);\n  }\n\n  /**\n   * Loop trough the list of modifiers and run them in order,\n   * each of them will then edit the data object.\n   * @method\n   * @memberof Popper.Utils\n   * @param {dataObject} data\n   * @param {Array} modifiers\n   * @param {String} ends - Optional modifier name used as stopper\n   * @returns {dataObject}\n   */\n  function runModifiers(modifiers, data, ends) {\n    var modifiersToRun = ends === undefined ? modifiers : modifiers.slice(0, findIndex(modifiers, 'name', ends));\n\n    modifiersToRun.forEach(function (modifier) {\n      if (modifier['function']) {\n        // eslint-disable-line dot-notation\n        console.warn('`modifier.function` is deprecated, use `modifier.fn`!');\n      }\n      var fn = modifier['function'] || modifier.fn; // eslint-disable-line dot-notation\n      if (modifier.enabled && isFunction(fn)) {\n        // Add properties to offsets to make them a complete clientRect object\n        // we do this before each modifier to make sure the previous one doesn't\n        // mess with these values\n        data.offsets.popper = getClientRect(data.offsets.popper);\n        data.offsets.reference = getClientRect(data.offsets.reference);\n\n        data = fn(data, modifier);\n      }\n    });\n\n    return data;\n  }\n\n  /**\n   * Updates the position of the popper, computing the new offsets and applying\n   * the new style.<br />\n   * Prefer `scheduleUpdate` over `update` because of performance reasons.\n   * @method\n   * @memberof Popper\n   */\n  function update() {\n    // if popper is destroyed, don't perform any further update\n    if (this.state.isDestroyed) {\n      return;\n    }\n\n    var data = {\n      instance: this,\n      styles: {},\n      arrowStyles: {},\n      attributes: {},\n      flipped: false,\n      offsets: {}\n    };\n\n    // compute reference element offsets\n    data.offsets.reference = getReferenceOffsets(this.state, this.popper, this.reference, this.options.positionFixed);\n\n    // compute auto placement, store placement inside the data object,\n    // modifiers will be able to edit `placement` if needed\n    // and refer to originalPlacement to know the original value\n    data.placement = computeAutoPlacement(this.options.placement, data.offsets.reference, this.popper, this.reference, this.options.modifiers.flip.boundariesElement, this.options.modifiers.flip.padding);\n\n    // store the computed placement inside `originalPlacement`\n    data.originalPlacement = data.placement;\n\n    data.positionFixed = this.options.positionFixed;\n\n    // compute the popper offsets\n    data.offsets.popper = getPopperOffsets(this.popper, data.offsets.reference, data.placement);\n\n    data.offsets.popper.position = this.options.positionFixed ? 'fixed' : 'absolute';\n\n    // run the modifiers\n    data = runModifiers(this.modifiers, data);\n\n    // the first `update` will call `onCreate` callback\n    // the other ones will call `onUpdate` callback\n    if (!this.state.isCreated) {\n      this.state.isCreated = true;\n      this.options.onCreate(data);\n    } else {\n      this.options.onUpdate(data);\n    }\n  }\n\n  /**\n   * Helper used to know if the given modifier is enabled.\n   * @method\n   * @memberof Popper.Utils\n   * @returns {Boolean}\n   */\n  function isModifierEnabled(modifiers, modifierName) {\n    return modifiers.some(function (_ref) {\n      var name = _ref.name,\n          enabled = _ref.enabled;\n      return enabled && name === modifierName;\n    });\n  }\n\n  /**\n   * Get the prefixed supported property name\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} property (camelCase)\n   * @returns {String} prefixed property (camelCase or PascalCase, depending on the vendor prefix)\n   */\n  function getSupportedPropertyName(property) {\n    var prefixes = [false, 'ms', 'Webkit', 'Moz', 'O'];\n    var upperProp = property.charAt(0).toUpperCase() + property.slice(1);\n\n    for (var i = 0; i < prefixes.length; i++) {\n      var prefix = prefixes[i];\n      var toCheck = prefix ? '' + prefix + upperProp : property;\n      if (typeof document.body.style[toCheck] !== 'undefined') {\n        return toCheck;\n      }\n    }\n    return null;\n  }\n\n  /**\n   * Destroys the popper.\n   * @method\n   * @memberof Popper\n   */\n  function destroy() {\n    this.state.isDestroyed = true;\n\n    // touch DOM only if `applyStyle` modifier is enabled\n    if (isModifierEnabled(this.modifiers, 'applyStyle')) {\n      this.popper.removeAttribute('x-placement');\n      this.popper.style.position = '';\n      this.popper.style.top = '';\n      this.popper.style.left = '';\n      this.popper.style.right = '';\n      this.popper.style.bottom = '';\n      this.popper.style.willChange = '';\n      this.popper.style[getSupportedPropertyName('transform')] = '';\n    }\n\n    this.disableEventListeners();\n\n    // remove the popper if user explicity asked for the deletion on destroy\n    // do not use `remove` because IE11 doesn't support it\n    if (this.options.removeOnDestroy) {\n      this.popper.parentNode.removeChild(this.popper);\n    }\n    return this;\n  }\n\n  /**\n   * Get the window associated with the element\n   * @argument {Element} element\n   * @returns {Window}\n   */\n  function getWindow(element) {\n    var ownerDocument = element.ownerDocument;\n    return ownerDocument ? ownerDocument.defaultView : window;\n  }\n\n  function attachToScrollParents(scrollParent, event, callback, scrollParents) {\n    var isBody = scrollParent.nodeName === 'BODY';\n    var target = isBody ? scrollParent.ownerDocument.defaultView : scrollParent;\n    target.addEventListener(event, callback, { passive: true });\n\n    if (!isBody) {\n      attachToScrollParents(getScrollParent(target.parentNode), event, callback, scrollParents);\n    }\n    scrollParents.push(target);\n  }\n\n  /**\n   * Setup needed event listeners used to update the popper position\n   * @method\n   * @memberof Popper.Utils\n   * @private\n   */\n  function setupEventListeners(reference, options, state, updateBound) {\n    // Resize event listener on window\n    state.updateBound = updateBound;\n    getWindow(reference).addEventListener('resize', state.updateBound, { passive: true });\n\n    // Scroll event listener on scroll parents\n    var scrollElement = getScrollParent(reference);\n    attachToScrollParents(scrollElement, 'scroll', state.updateBound, state.scrollParents);\n    state.scrollElement = scrollElement;\n    state.eventsEnabled = true;\n\n    return state;\n  }\n\n  /**\n   * It will add resize/scroll events and start recalculating\n   * position of the popper element when they are triggered.\n   * @method\n   * @memberof Popper\n   */\n  function enableEventListeners() {\n    if (!this.state.eventsEnabled) {\n      this.state = setupEventListeners(this.reference, this.options, this.state, this.scheduleUpdate);\n    }\n  }\n\n  /**\n   * Remove event listeners used to update the popper position\n   * @method\n   * @memberof Popper.Utils\n   * @private\n   */\n  function removeEventListeners(reference, state) {\n    // Remove resize event listener on window\n    getWindow(reference).removeEventListener('resize', state.updateBound);\n\n    // Remove scroll event listener on scroll parents\n    state.scrollParents.forEach(function (target) {\n      target.removeEventListener('scroll', state.updateBound);\n    });\n\n    // Reset state\n    state.updateBound = null;\n    state.scrollParents = [];\n    state.scrollElement = null;\n    state.eventsEnabled = false;\n    return state;\n  }\n\n  /**\n   * It will remove resize/scroll events and won't recalculate popper position\n   * when they are triggered. It also won't trigger `onUpdate` callback anymore,\n   * unless you call `update` method manually.\n   * @method\n   * @memberof Popper\n   */\n  function disableEventListeners() {\n    if (this.state.eventsEnabled) {\n      cancelAnimationFrame(this.scheduleUpdate);\n      this.state = removeEventListeners(this.reference, this.state);\n    }\n  }\n\n  /**\n   * Tells if a given input is a number\n   * @method\n   * @memberof Popper.Utils\n   * @param {*} input to check\n   * @return {Boolean}\n   */\n  function isNumeric(n) {\n    return n !== '' && !isNaN(parseFloat(n)) && isFinite(n);\n  }\n\n  /**\n   * Set the style to the given popper\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element - Element to apply the style to\n   * @argument {Object} styles\n   * Object with a list of properties and values which will be applied to the element\n   */\n  function setStyles(element, styles) {\n    Object.keys(styles).forEach(function (prop) {\n      var unit = '';\n      // add unit if the value is numeric and is one of the following\n      if (['width', 'height', 'top', 'right', 'bottom', 'left'].indexOf(prop) !== -1 && isNumeric(styles[prop])) {\n        unit = 'px';\n      }\n      element.style[prop] = styles[prop] + unit;\n    });\n  }\n\n  /**\n   * Set the attributes to the given popper\n   * @method\n   * @memberof Popper.Utils\n   * @argument {Element} element - Element to apply the attributes to\n   * @argument {Object} styles\n   * Object with a list of properties and values which will be applied to the element\n   */\n  function setAttributes(element, attributes) {\n    Object.keys(attributes).forEach(function (prop) {\n      var value = attributes[prop];\n      if (value !== false) {\n        element.setAttribute(prop, attributes[prop]);\n      } else {\n        element.removeAttribute(prop);\n      }\n    });\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} data.styles - List of style properties - values to apply to popper element\n   * @argument {Object} data.attributes - List of attribute properties - values to apply to popper element\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The same data object\n   */\n  function applyStyle(data) {\n    // any property present in `data.styles` will be applied to the popper,\n    // in this way we can make the 3rd party modifiers add custom styles to it\n    // Be aware, modifiers could override the properties defined in the previous\n    // lines of this modifier!\n    setStyles(data.instance.popper, data.styles);\n\n    // any property present in `data.attributes` will be applied to the popper,\n    // they will be set as HTML attributes of the element\n    setAttributes(data.instance.popper, data.attributes);\n\n    // if arrowElement is defined and arrowStyles has some properties\n    if (data.arrowElement && Object.keys(data.arrowStyles).length) {\n      setStyles(data.arrowElement, data.arrowStyles);\n    }\n\n    return data;\n  }\n\n  /**\n   * Set the x-placement attribute before everything else because it could be used\n   * to add margins to the popper margins needs to be calculated to get the\n   * correct popper offsets.\n   * @method\n   * @memberof Popper.modifiers\n   * @param {HTMLElement} reference - The reference element used to position the popper\n   * @param {HTMLElement} popper - The HTML element used as popper\n   * @param {Object} options - Popper.js options\n   */\n  function applyStyleOnLoad(reference, popper, options, modifierOptions, state) {\n    // compute reference element offsets\n    var referenceOffsets = getReferenceOffsets(state, popper, reference, options.positionFixed);\n\n    // compute auto placement, store placement inside the data object,\n    // modifiers will be able to edit `placement` if needed\n    // and refer to originalPlacement to know the original value\n    var placement = computeAutoPlacement(options.placement, referenceOffsets, popper, reference, options.modifiers.flip.boundariesElement, options.modifiers.flip.padding);\n\n    popper.setAttribute('x-placement', placement);\n\n    // Apply `position` to popper before anything else because\n    // without the position applied we can't guarantee correct computations\n    setStyles(popper, { position: options.positionFixed ? 'fixed' : 'absolute' });\n\n    return options;\n  }\n\n  /**\n   * @function\n   * @memberof Popper.Utils\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Boolean} shouldRound - If the offsets should be rounded at all\n   * @returns {Object} The popper's position offsets rounded\n   *\n   * The tale of pixel-perfect positioning. It's still not 100% perfect, but as\n   * good as it can be within reason.\n   * Discussion here: https://github.com/FezVrasta/popper.js/pull/715\n   *\n   * Low DPI screens cause a popper to be blurry if not using full pixels (Safari\n   * as well on High DPI screens).\n   *\n   * Firefox prefers no rounding for positioning and does not have blurriness on\n   * high DPI screens.\n   *\n   * Only horizontal placement and left/right values need to be considered.\n   */\n  function getRoundedOffsets(data, shouldRound) {\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n    var round = Math.round,\n        floor = Math.floor;\n\n    var noRound = function noRound(v) {\n      return v;\n    };\n\n    var referenceWidth = round(reference.width);\n    var popperWidth = round(popper.width);\n\n    var isVertical = ['left', 'right'].indexOf(data.placement) !== -1;\n    var isVariation = data.placement.indexOf('-') !== -1;\n    var sameWidthParity = referenceWidth % 2 === popperWidth % 2;\n    var bothOddWidth = referenceWidth % 2 === 1 && popperWidth % 2 === 1;\n\n    var horizontalToInteger = !shouldRound ? noRound : isVertical || isVariation || sameWidthParity ? round : floor;\n    var verticalToInteger = !shouldRound ? noRound : round;\n\n    return {\n      left: horizontalToInteger(bothOddWidth && !isVariation && shouldRound ? popper.left - 1 : popper.left),\n      top: verticalToInteger(popper.top),\n      bottom: verticalToInteger(popper.bottom),\n      right: horizontalToInteger(popper.right)\n    };\n  }\n\n  var isFirefox = isBrowser && /Firefox/i.test(navigator.userAgent);\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function computeStyle(data, options) {\n    var x = options.x,\n        y = options.y;\n    var popper = data.offsets.popper;\n\n    // Remove this legacy support in Popper.js v2\n\n    var legacyGpuAccelerationOption = find(data.instance.modifiers, function (modifier) {\n      return modifier.name === 'applyStyle';\n    }).gpuAcceleration;\n    if (legacyGpuAccelerationOption !== undefined) {\n      console.warn('WARNING: `gpuAcceleration` option moved to `computeStyle` modifier and will not be supported in future versions of Popper.js!');\n    }\n    var gpuAcceleration = legacyGpuAccelerationOption !== undefined ? legacyGpuAccelerationOption : options.gpuAcceleration;\n\n    var offsetParent = getOffsetParent(data.instance.popper);\n    var offsetParentRect = getBoundingClientRect(offsetParent);\n\n    // Styles\n    var styles = {\n      position: popper.position\n    };\n\n    var offsets = getRoundedOffsets(data, window.devicePixelRatio < 2 || !isFirefox);\n\n    var sideA = x === 'bottom' ? 'top' : 'bottom';\n    var sideB = y === 'right' ? 'left' : 'right';\n\n    // if gpuAcceleration is set to `true` and transform is supported,\n    //  we use `translate3d` to apply the position to the popper we\n    // automatically use the supported prefixed version if needed\n    var prefixedProperty = getSupportedPropertyName('transform');\n\n    // now, let's make a step back and look at this code closely (wtf?)\n    // If the content of the popper grows once it's been positioned, it\n    // may happen that the popper gets misplaced because of the new content\n    // overflowing its reference element\n    // To avoid this problem, we provide two options (x and y), which allow\n    // the consumer to define the offset origin.\n    // If we position a popper on top of a reference element, we can set\n    // `x` to `top` to make the popper grow towards its top instead of\n    // its bottom.\n    var left = void 0,\n        top = void 0;\n    if (sideA === 'bottom') {\n      // when offsetParent is <html> the positioning is relative to the bottom of the screen (excluding the scrollbar)\n      // and not the bottom of the html element\n      if (offsetParent.nodeName === 'HTML') {\n        top = -offsetParent.clientHeight + offsets.bottom;\n      } else {\n        top = -offsetParentRect.height + offsets.bottom;\n      }\n    } else {\n      top = offsets.top;\n    }\n    if (sideB === 'right') {\n      if (offsetParent.nodeName === 'HTML') {\n        left = -offsetParent.clientWidth + offsets.right;\n      } else {\n        left = -offsetParentRect.width + offsets.right;\n      }\n    } else {\n      left = offsets.left;\n    }\n    if (gpuAcceleration && prefixedProperty) {\n      styles[prefixedProperty] = 'translate3d(' + left + 'px, ' + top + 'px, 0)';\n      styles[sideA] = 0;\n      styles[sideB] = 0;\n      styles.willChange = 'transform';\n    } else {\n      // othwerise, we use the standard `top`, `left`, `bottom` and `right` properties\n      var invertTop = sideA === 'bottom' ? -1 : 1;\n      var invertLeft = sideB === 'right' ? -1 : 1;\n      styles[sideA] = top * invertTop;\n      styles[sideB] = left * invertLeft;\n      styles.willChange = sideA + ', ' + sideB;\n    }\n\n    // Attributes\n    var attributes = {\n      'x-placement': data.placement\n    };\n\n    // Update `data` attributes, styles and arrowStyles\n    data.attributes = _extends({}, attributes, data.attributes);\n    data.styles = _extends({}, styles, data.styles);\n    data.arrowStyles = _extends({}, data.offsets.arrow, data.arrowStyles);\n\n    return data;\n  }\n\n  /**\n   * Helper used to know if the given modifier depends from another one.<br />\n   * It checks if the needed modifier is listed and enabled.\n   * @method\n   * @memberof Popper.Utils\n   * @param {Array} modifiers - list of modifiers\n   * @param {String} requestingName - name of requesting modifier\n   * @param {String} requestedName - name of requested modifier\n   * @returns {Boolean}\n   */\n  function isModifierRequired(modifiers, requestingName, requestedName) {\n    var requesting = find(modifiers, function (_ref) {\n      var name = _ref.name;\n      return name === requestingName;\n    });\n\n    var isRequired = !!requesting && modifiers.some(function (modifier) {\n      return modifier.name === requestedName && modifier.enabled && modifier.order < requesting.order;\n    });\n\n    if (!isRequired) {\n      var _requesting = '`' + requestingName + '`';\n      var requested = '`' + requestedName + '`';\n      console.warn(requested + ' modifier is required by ' + _requesting + ' modifier in order to work, be sure to include it before ' + _requesting + '!');\n    }\n    return isRequired;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function arrow(data, options) {\n    var _data$offsets$arrow;\n\n    // arrow depends on keepTogether in order to work\n    if (!isModifierRequired(data.instance.modifiers, 'arrow', 'keepTogether')) {\n      return data;\n    }\n\n    var arrowElement = options.element;\n\n    // if arrowElement is a string, suppose it's a CSS selector\n    if (typeof arrowElement === 'string') {\n      arrowElement = data.instance.popper.querySelector(arrowElement);\n\n      // if arrowElement is not found, don't run the modifier\n      if (!arrowElement) {\n        return data;\n      }\n    } else {\n      // if the arrowElement isn't a query selector we must check that the\n      // provided DOM node is child of its popper node\n      if (!data.instance.popper.contains(arrowElement)) {\n        console.warn('WARNING: `arrow.element` must be child of its popper element!');\n        return data;\n      }\n    }\n\n    var placement = data.placement.split('-')[0];\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var isVertical = ['left', 'right'].indexOf(placement) !== -1;\n\n    var len = isVertical ? 'height' : 'width';\n    var sideCapitalized = isVertical ? 'Top' : 'Left';\n    var side = sideCapitalized.toLowerCase();\n    var altSide = isVertical ? 'left' : 'top';\n    var opSide = isVertical ? 'bottom' : 'right';\n    var arrowElementSize = getOuterSizes(arrowElement)[len];\n\n    //\n    // extends keepTogether behavior making sure the popper and its\n    // reference have enough pixels in conjunction\n    //\n\n    // top/left side\n    if (reference[opSide] - arrowElementSize < popper[side]) {\n      data.offsets.popper[side] -= popper[side] - (reference[opSide] - arrowElementSize);\n    }\n    // bottom/right side\n    if (reference[side] + arrowElementSize > popper[opSide]) {\n      data.offsets.popper[side] += reference[side] + arrowElementSize - popper[opSide];\n    }\n    data.offsets.popper = getClientRect(data.offsets.popper);\n\n    // compute center of the popper\n    var center = reference[side] + reference[len] / 2 - arrowElementSize / 2;\n\n    // Compute the sideValue using the updated popper offsets\n    // take popper margin in account because we don't have this info available\n    var css = getStyleComputedProperty(data.instance.popper);\n    var popperMarginSide = parseFloat(css['margin' + sideCapitalized], 10);\n    var popperBorderSide = parseFloat(css['border' + sideCapitalized + 'Width'], 10);\n    var sideValue = center - data.offsets.popper[side] - popperMarginSide - popperBorderSide;\n\n    // prevent arrowElement from being placed not contiguously to its popper\n    sideValue = Math.max(Math.min(popper[len] - arrowElementSize, sideValue), 0);\n\n    data.arrowElement = arrowElement;\n    data.offsets.arrow = (_data$offsets$arrow = {}, defineProperty(_data$offsets$arrow, side, Math.round(sideValue)), defineProperty(_data$offsets$arrow, altSide, ''), _data$offsets$arrow);\n\n    return data;\n  }\n\n  /**\n   * Get the opposite placement variation of the given one\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} placement variation\n   * @returns {String} flipped placement variation\n   */\n  function getOppositeVariation(variation) {\n    if (variation === 'end') {\n      return 'start';\n    } else if (variation === 'start') {\n      return 'end';\n    }\n    return variation;\n  }\n\n  /**\n   * List of accepted placements to use as values of the `placement` option.<br />\n   * Valid placements are:\n   * - `auto`\n   * - `top`\n   * - `right`\n   * - `bottom`\n   * - `left`\n   *\n   * Each placement can have a variation from this list:\n   * - `-start`\n   * - `-end`\n   *\n   * Variations are interpreted easily if you think of them as the left to right\n   * written languages. Horizontally (`top` and `bottom`), `start` is left and `end`\n   * is right.<br />\n   * Vertically (`left` and `right`), `start` is top and `end` is bottom.\n   *\n   * Some valid examples are:\n   * - `top-end` (on top of reference, right aligned)\n   * - `right-start` (on right of reference, top aligned)\n   * - `bottom` (on bottom, centered)\n   * - `auto-end` (on the side with more space available, alignment depends by placement)\n   *\n   * @static\n   * @type {Array}\n   * @enum {String}\n   * @readonly\n   * @method placements\n   * @memberof Popper\n   */\n  var placements = ['auto-start', 'auto', 'auto-end', 'top-start', 'top', 'top-end', 'right-start', 'right', 'right-end', 'bottom-end', 'bottom', 'bottom-start', 'left-end', 'left', 'left-start'];\n\n  // Get rid of `auto` `auto-start` and `auto-end`\n  var validPlacements = placements.slice(3);\n\n  /**\n   * Given an initial placement, returns all the subsequent placements\n   * clockwise (or counter-clockwise).\n   *\n   * @method\n   * @memberof Popper.Utils\n   * @argument {String} placement - A valid placement (it accepts variations)\n   * @argument {Boolean} counter - Set to true to walk the placements counterclockwise\n   * @returns {Array} placements including their variations\n   */\n  function clockwise(placement) {\n    var counter = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false;\n\n    var index = validPlacements.indexOf(placement);\n    var arr = validPlacements.slice(index + 1).concat(validPlacements.slice(0, index));\n    return counter ? arr.reverse() : arr;\n  }\n\n  var BEHAVIORS = {\n    FLIP: 'flip',\n    CLOCKWISE: 'clockwise',\n    COUNTERCLOCKWISE: 'counterclockwise'\n  };\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function flip(data, options) {\n    // if `inner` modifier is enabled, we can't use the `flip` modifier\n    if (isModifierEnabled(data.instance.modifiers, 'inner')) {\n      return data;\n    }\n\n    if (data.flipped && data.placement === data.originalPlacement) {\n      // seems like flip is trying to loop, probably there's not enough space on any of the flippable sides\n      return data;\n    }\n\n    var boundaries = getBoundaries(data.instance.popper, data.instance.reference, options.padding, options.boundariesElement, data.positionFixed);\n\n    var placement = data.placement.split('-')[0];\n    var placementOpposite = getOppositePlacement(placement);\n    var variation = data.placement.split('-')[1] || '';\n\n    var flipOrder = [];\n\n    switch (options.behavior) {\n      case BEHAVIORS.FLIP:\n        flipOrder = [placement, placementOpposite];\n        break;\n      case BEHAVIORS.CLOCKWISE:\n        flipOrder = clockwise(placement);\n        break;\n      case BEHAVIORS.COUNTERCLOCKWISE:\n        flipOrder = clockwise(placement, true);\n        break;\n      default:\n        flipOrder = options.behavior;\n    }\n\n    flipOrder.forEach(function (step, index) {\n      if (placement !== step || flipOrder.length === index + 1) {\n        return data;\n      }\n\n      placement = data.placement.split('-')[0];\n      placementOpposite = getOppositePlacement(placement);\n\n      var popperOffsets = data.offsets.popper;\n      var refOffsets = data.offsets.reference;\n\n      // using floor because the reference offsets may contain decimals we are not going to consider here\n      var floor = Math.floor;\n      var overlapsRef = placement === 'left' && floor(popperOffsets.right) > floor(refOffsets.left) || placement === 'right' && floor(popperOffsets.left) < floor(refOffsets.right) || placement === 'top' && floor(popperOffsets.bottom) > floor(refOffsets.top) || placement === 'bottom' && floor(popperOffsets.top) < floor(refOffsets.bottom);\n\n      var overflowsLeft = floor(popperOffsets.left) < floor(boundaries.left);\n      var overflowsRight = floor(popperOffsets.right) > floor(boundaries.right);\n      var overflowsTop = floor(popperOffsets.top) < floor(boundaries.top);\n      var overflowsBottom = floor(popperOffsets.bottom) > floor(boundaries.bottom);\n\n      var overflowsBoundaries = placement === 'left' && overflowsLeft || placement === 'right' && overflowsRight || placement === 'top' && overflowsTop || placement === 'bottom' && overflowsBottom;\n\n      // flip the variation if required\n      var isVertical = ['top', 'bottom'].indexOf(placement) !== -1;\n      var flippedVariation = !!options.flipVariations && (isVertical && variation === 'start' && overflowsLeft || isVertical && variation === 'end' && overflowsRight || !isVertical && variation === 'start' && overflowsTop || !isVertical && variation === 'end' && overflowsBottom);\n\n      if (overlapsRef || overflowsBoundaries || flippedVariation) {\n        // this boolean to detect any flip loop\n        data.flipped = true;\n\n        if (overlapsRef || overflowsBoundaries) {\n          placement = flipOrder[index + 1];\n        }\n\n        if (flippedVariation) {\n          variation = getOppositeVariation(variation);\n        }\n\n        data.placement = placement + (variation ? '-' + variation : '');\n\n        // this object contains `position`, we want to preserve it along with\n        // any additional property we may add in the future\n        data.offsets.popper = _extends({}, data.offsets.popper, getPopperOffsets(data.instance.popper, data.offsets.reference, data.placement));\n\n        data = runModifiers(data.instance.modifiers, data, 'flip');\n      }\n    });\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function keepTogether(data) {\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var placement = data.placement.split('-')[0];\n    var floor = Math.floor;\n    var isVertical = ['top', 'bottom'].indexOf(placement) !== -1;\n    var side = isVertical ? 'right' : 'bottom';\n    var opSide = isVertical ? 'left' : 'top';\n    var measurement = isVertical ? 'width' : 'height';\n\n    if (popper[side] < floor(reference[opSide])) {\n      data.offsets.popper[opSide] = floor(reference[opSide]) - popper[measurement];\n    }\n    if (popper[opSide] > floor(reference[side])) {\n      data.offsets.popper[opSide] = floor(reference[side]);\n    }\n\n    return data;\n  }\n\n  /**\n   * Converts a string containing value + unit into a px value number\n   * @function\n   * @memberof {modifiers~offset}\n   * @private\n   * @argument {String} str - Value + unit string\n   * @argument {String} measurement - `height` or `width`\n   * @argument {Object} popperOffsets\n   * @argument {Object} referenceOffsets\n   * @returns {Number|String}\n   * Value in pixels, or original string if no values were extracted\n   */\n  function toValue(str, measurement, popperOffsets, referenceOffsets) {\n    // separate value from unit\n    var split = str.match(/((?:\\-|\\+)?\\d*\\.?\\d*)(.*)/);\n    var value = +split[1];\n    var unit = split[2];\n\n    // If it's not a number it's an operator, I guess\n    if (!value) {\n      return str;\n    }\n\n    if (unit.indexOf('%') === 0) {\n      var element = void 0;\n      switch (unit) {\n        case '%p':\n          element = popperOffsets;\n          break;\n        case '%':\n        case '%r':\n        default:\n          element = referenceOffsets;\n      }\n\n      var rect = getClientRect(element);\n      return rect[measurement] / 100 * value;\n    } else if (unit === 'vh' || unit === 'vw') {\n      // if is a vh or vw, we calculate the size based on the viewport\n      var size = void 0;\n      if (unit === 'vh') {\n        size = Math.max(document.documentElement.clientHeight, window.innerHeight || 0);\n      } else {\n        size = Math.max(document.documentElement.clientWidth, window.innerWidth || 0);\n      }\n      return size / 100 * value;\n    } else {\n      // if is an explicit pixel unit, we get rid of the unit and keep the value\n      // if is an implicit unit, it's px, and we return just the value\n      return value;\n    }\n  }\n\n  /**\n   * Parse an `offset` string to extrapolate `x` and `y` numeric offsets.\n   * @function\n   * @memberof {modifiers~offset}\n   * @private\n   * @argument {String} offset\n   * @argument {Object} popperOffsets\n   * @argument {Object} referenceOffsets\n   * @argument {String} basePlacement\n   * @returns {Array} a two cells array with x and y offsets in numbers\n   */\n  function parseOffset(offset, popperOffsets, referenceOffsets, basePlacement) {\n    var offsets = [0, 0];\n\n    // Use height if placement is left or right and index is 0 otherwise use width\n    // in this way the first offset will use an axis and the second one\n    // will use the other one\n    var useHeight = ['right', 'left'].indexOf(basePlacement) !== -1;\n\n    // Split the offset string to obtain a list of values and operands\n    // The regex addresses values with the plus or minus sign in front (+10, -20, etc)\n    var fragments = offset.split(/(\\+|\\-)/).map(function (frag) {\n      return frag.trim();\n    });\n\n    // Detect if the offset string contains a pair of values or a single one\n    // they could be separated by comma or space\n    var divider = fragments.indexOf(find(fragments, function (frag) {\n      return frag.search(/,|\\s/) !== -1;\n    }));\n\n    if (fragments[divider] && fragments[divider].indexOf(',') === -1) {\n      console.warn('Offsets separated by white space(s) are deprecated, use a comma (,) instead.');\n    }\n\n    // If divider is found, we divide the list of values and operands to divide\n    // them by ofset X and Y.\n    var splitRegex = /\\s*,\\s*|\\s+/;\n    var ops = divider !== -1 ? [fragments.slice(0, divider).concat([fragments[divider].split(splitRegex)[0]]), [fragments[divider].split(splitRegex)[1]].concat(fragments.slice(divider + 1))] : [fragments];\n\n    // Convert the values with units to absolute pixels to allow our computations\n    ops = ops.map(function (op, index) {\n      // Most of the units rely on the orientation of the popper\n      var measurement = (index === 1 ? !useHeight : useHeight) ? 'height' : 'width';\n      var mergeWithPrevious = false;\n      return op\n      // This aggregates any `+` or `-` sign that aren't considered operators\n      // e.g.: 10 + +5 => [10, +, +5]\n      .reduce(function (a, b) {\n        if (a[a.length - 1] === '' && ['+', '-'].indexOf(b) !== -1) {\n          a[a.length - 1] = b;\n          mergeWithPrevious = true;\n          return a;\n        } else if (mergeWithPrevious) {\n          a[a.length - 1] += b;\n          mergeWithPrevious = false;\n          return a;\n        } else {\n          return a.concat(b);\n        }\n      }, [])\n      // Here we convert the string values into number values (in px)\n      .map(function (str) {\n        return toValue(str, measurement, popperOffsets, referenceOffsets);\n      });\n    });\n\n    // Loop trough the offsets arrays and execute the operations\n    ops.forEach(function (op, index) {\n      op.forEach(function (frag, index2) {\n        if (isNumeric(frag)) {\n          offsets[index] += frag * (op[index2 - 1] === '-' ? -1 : 1);\n        }\n      });\n    });\n    return offsets;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @argument {Number|String} options.offset=0\n   * The offset value as described in the modifier description\n   * @returns {Object} The data object, properly modified\n   */\n  function offset(data, _ref) {\n    var offset = _ref.offset;\n    var placement = data.placement,\n        _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var basePlacement = placement.split('-')[0];\n\n    var offsets = void 0;\n    if (isNumeric(+offset)) {\n      offsets = [+offset, 0];\n    } else {\n      offsets = parseOffset(offset, popper, reference, basePlacement);\n    }\n\n    if (basePlacement === 'left') {\n      popper.top += offsets[0];\n      popper.left -= offsets[1];\n    } else if (basePlacement === 'right') {\n      popper.top += offsets[0];\n      popper.left += offsets[1];\n    } else if (basePlacement === 'top') {\n      popper.left += offsets[0];\n      popper.top -= offsets[1];\n    } else if (basePlacement === 'bottom') {\n      popper.left += offsets[0];\n      popper.top += offsets[1];\n    }\n\n    data.popper = popper;\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function preventOverflow(data, options) {\n    var boundariesElement = options.boundariesElement || getOffsetParent(data.instance.popper);\n\n    // If offsetParent is the reference element, we really want to\n    // go one step up and use the next offsetParent as reference to\n    // avoid to make this modifier completely useless and look like broken\n    if (data.instance.reference === boundariesElement) {\n      boundariesElement = getOffsetParent(boundariesElement);\n    }\n\n    // NOTE: DOM access here\n    // resets the popper's position so that the document size can be calculated excluding\n    // the size of the popper element itself\n    var transformProp = getSupportedPropertyName('transform');\n    var popperStyles = data.instance.popper.style; // assignment to help minification\n    var top = popperStyles.top,\n        left = popperStyles.left,\n        transform = popperStyles[transformProp];\n\n    popperStyles.top = '';\n    popperStyles.left = '';\n    popperStyles[transformProp] = '';\n\n    var boundaries = getBoundaries(data.instance.popper, data.instance.reference, options.padding, boundariesElement, data.positionFixed);\n\n    // NOTE: DOM access here\n    // restores the original style properties after the offsets have been computed\n    popperStyles.top = top;\n    popperStyles.left = left;\n    popperStyles[transformProp] = transform;\n\n    options.boundaries = boundaries;\n\n    var order = options.priority;\n    var popper = data.offsets.popper;\n\n    var check = {\n      primary: function primary(placement) {\n        var value = popper[placement];\n        if (popper[placement] < boundaries[placement] && !options.escapeWithReference) {\n          value = Math.max(popper[placement], boundaries[placement]);\n        }\n        return defineProperty({}, placement, value);\n      },\n      secondary: function secondary(placement) {\n        var mainSide = placement === 'right' ? 'left' : 'top';\n        var value = popper[mainSide];\n        if (popper[placement] > boundaries[placement] && !options.escapeWithReference) {\n          value = Math.min(popper[mainSide], boundaries[placement] - (placement === 'right' ? popper.width : popper.height));\n        }\n        return defineProperty({}, mainSide, value);\n      }\n    };\n\n    order.forEach(function (placement) {\n      var side = ['left', 'top'].indexOf(placement) !== -1 ? 'primary' : 'secondary';\n      popper = _extends({}, popper, check[side](placement));\n    });\n\n    data.offsets.popper = popper;\n\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function shift(data) {\n    var placement = data.placement;\n    var basePlacement = placement.split('-')[0];\n    var shiftvariation = placement.split('-')[1];\n\n    // if shift shiftvariation is specified, run the modifier\n    if (shiftvariation) {\n      var _data$offsets = data.offsets,\n          reference = _data$offsets.reference,\n          popper = _data$offsets.popper;\n\n      var isVertical = ['bottom', 'top'].indexOf(basePlacement) !== -1;\n      var side = isVertical ? 'left' : 'top';\n      var measurement = isVertical ? 'width' : 'height';\n\n      var shiftOffsets = {\n        start: defineProperty({}, side, reference[side]),\n        end: defineProperty({}, side, reference[side] + reference[measurement] - popper[measurement])\n      };\n\n      data.offsets.popper = _extends({}, popper, shiftOffsets[shiftvariation]);\n    }\n\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by update method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function hide(data) {\n    if (!isModifierRequired(data.instance.modifiers, 'hide', 'preventOverflow')) {\n      return data;\n    }\n\n    var refRect = data.offsets.reference;\n    var bound = find(data.instance.modifiers, function (modifier) {\n      return modifier.name === 'preventOverflow';\n    }).boundaries;\n\n    if (refRect.bottom < bound.top || refRect.left > bound.right || refRect.top > bound.bottom || refRect.right < bound.left) {\n      // Avoid unnecessary DOM access if visibility hasn't changed\n      if (data.hide === true) {\n        return data;\n      }\n\n      data.hide = true;\n      data.attributes['x-out-of-boundaries'] = '';\n    } else {\n      // Avoid unnecessary DOM access if visibility hasn't changed\n      if (data.hide === false) {\n        return data;\n      }\n\n      data.hide = false;\n      data.attributes['x-out-of-boundaries'] = false;\n    }\n\n    return data;\n  }\n\n  /**\n   * @function\n   * @memberof Modifiers\n   * @argument {Object} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {Object} The data object, properly modified\n   */\n  function inner(data) {\n    var placement = data.placement;\n    var basePlacement = placement.split('-')[0];\n    var _data$offsets = data.offsets,\n        popper = _data$offsets.popper,\n        reference = _data$offsets.reference;\n\n    var isHoriz = ['left', 'right'].indexOf(basePlacement) !== -1;\n\n    var subtractLength = ['top', 'left'].indexOf(basePlacement) === -1;\n\n    popper[isHoriz ? 'left' : 'top'] = reference[basePlacement] - (subtractLength ? popper[isHoriz ? 'width' : 'height'] : 0);\n\n    data.placement = getOppositePlacement(placement);\n    data.offsets.popper = getClientRect(popper);\n\n    return data;\n  }\n\n  /**\n   * Modifier function, each modifier can have a function of this type assigned\n   * to its `fn` property.<br />\n   * These functions will be called on each update, this means that you must\n   * make sure they are performant enough to avoid performance bottlenecks.\n   *\n   * @function ModifierFn\n   * @argument {dataObject} data - The data object generated by `update` method\n   * @argument {Object} options - Modifiers configuration and options\n   * @returns {dataObject} The data object, properly modified\n   */\n\n  /**\n   * Modifiers are plugins used to alter the behavior of your poppers.<br />\n   * Popper.js uses a set of 9 modifiers to provide all the basic functionalities\n   * needed by the library.\n   *\n   * Usually you don't want to override the `order`, `fn` and `onLoad` props.\n   * All the other properties are configurations that could be tweaked.\n   * @namespace modifiers\n   */\n  var modifiers = {\n    /**\n     * Modifier used to shift the popper on the start or end of its reference\n     * element.<br />\n     * It will read the variation of the `placement` property.<br />\n     * It can be one either `-end` or `-start`.\n     * @memberof modifiers\n     * @inner\n     */\n    shift: {\n      /** @prop {number} order=100 - Index used to define the order of execution */\n      order: 100,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: shift\n    },\n\n    /**\n     * The `offset` modifier can shift your popper on both its axis.\n     *\n     * It accepts the following units:\n     * - `px` or unit-less, interpreted as pixels\n     * - `%` or `%r`, percentage relative to the length of the reference element\n     * - `%p`, percentage relative to the length of the popper element\n     * - `vw`, CSS viewport width unit\n     * - `vh`, CSS viewport height unit\n     *\n     * For length is intended the main axis relative to the placement of the popper.<br />\n     * This means that if the placement is `top` or `bottom`, the length will be the\n     * `width`. In case of `left` or `right`, it will be the `height`.\n     *\n     * You can provide a single value (as `Number` or `String`), or a pair of values\n     * as `String` divided by a comma or one (or more) white spaces.<br />\n     * The latter is a deprecated method because it leads to confusion and will be\n     * removed in v2.<br />\n     * Additionally, it accepts additions and subtractions between different units.\n     * Note that multiplications and divisions aren't supported.\n     *\n     * Valid examples are:\n     * ```\n     * 10\n     * '10%'\n     * '10, 10'\n     * '10%, 10'\n     * '10 + 10%'\n     * '10 - 5vh + 3%'\n     * '-10px + 5vh, 5px - 6%'\n     * ```\n     * > **NB**: If you desire to apply offsets to your poppers in a way that may make them overlap\n     * > with their reference element, unfortunately, you will have to disable the `flip` modifier.\n     * > You can read more on this at this [issue](https://github.com/FezVrasta/popper.js/issues/373).\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    offset: {\n      /** @prop {number} order=200 - Index used to define the order of execution */\n      order: 200,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: offset,\n      /** @prop {Number|String} offset=0\n       * The offset value as described in the modifier description\n       */\n      offset: 0\n    },\n\n    /**\n     * Modifier used to prevent the popper from being positioned outside the boundary.\n     *\n     * A scenario exists where the reference itself is not within the boundaries.<br />\n     * We can say it has \"escaped the boundaries\" — or just \"escaped\".<br />\n     * In this case we need to decide whether the popper should either:\n     *\n     * - detach from the reference and remain \"trapped\" in the boundaries, or\n     * - if it should ignore the boundary and \"escape with its reference\"\n     *\n     * When `escapeWithReference` is set to`true` and reference is completely\n     * outside its boundaries, the popper will overflow (or completely leave)\n     * the boundaries in order to remain attached to the edge of the reference.\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    preventOverflow: {\n      /** @prop {number} order=300 - Index used to define the order of execution */\n      order: 300,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: preventOverflow,\n      /**\n       * @prop {Array} [priority=['left','right','top','bottom']]\n       * Popper will try to prevent overflow following these priorities by default,\n       * then, it could overflow on the left and on top of the `boundariesElement`\n       */\n      priority: ['left', 'right', 'top', 'bottom'],\n      /**\n       * @prop {number} padding=5\n       * Amount of pixel used to define a minimum distance between the boundaries\n       * and the popper. This makes sure the popper always has a little padding\n       * between the edges of its container\n       */\n      padding: 5,\n      /**\n       * @prop {String|HTMLElement} boundariesElement='scrollParent'\n       * Boundaries used by the modifier. Can be `scrollParent`, `window`,\n       * `viewport` or any DOM element.\n       */\n      boundariesElement: 'scrollParent'\n    },\n\n    /**\n     * Modifier used to make sure the reference and its popper stay near each other\n     * without leaving any gap between the two. Especially useful when the arrow is\n     * enabled and you want to ensure that it points to its reference element.\n     * It cares only about the first axis. You can still have poppers with margin\n     * between the popper and its reference element.\n     * @memberof modifiers\n     * @inner\n     */\n    keepTogether: {\n      /** @prop {number} order=400 - Index used to define the order of execution */\n      order: 400,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: keepTogether\n    },\n\n    /**\n     * This modifier is used to move the `arrowElement` of the popper to make\n     * sure it is positioned between the reference element and its popper element.\n     * It will read the outer size of the `arrowElement` node to detect how many\n     * pixels of conjunction are needed.\n     *\n     * It has no effect if no `arrowElement` is provided.\n     * @memberof modifiers\n     * @inner\n     */\n    arrow: {\n      /** @prop {number} order=500 - Index used to define the order of execution */\n      order: 500,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: arrow,\n      /** @prop {String|HTMLElement} element='[x-arrow]' - Selector or node used as arrow */\n      element: '[x-arrow]'\n    },\n\n    /**\n     * Modifier used to flip the popper's placement when it starts to overlap its\n     * reference element.\n     *\n     * Requires the `preventOverflow` modifier before it in order to work.\n     *\n     * **NOTE:** this modifier will interrupt the current update cycle and will\n     * restart it if it detects the need to flip the placement.\n     * @memberof modifiers\n     * @inner\n     */\n    flip: {\n      /** @prop {number} order=600 - Index used to define the order of execution */\n      order: 600,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: flip,\n      /**\n       * @prop {String|Array} behavior='flip'\n       * The behavior used to change the popper's placement. It can be one of\n       * `flip`, `clockwise`, `counterclockwise` or an array with a list of valid\n       * placements (with optional variations)\n       */\n      behavior: 'flip',\n      /**\n       * @prop {number} padding=5\n       * The popper will flip if it hits the edges of the `boundariesElement`\n       */\n      padding: 5,\n      /**\n       * @prop {String|HTMLElement} boundariesElement='viewport'\n       * The element which will define the boundaries of the popper position.\n       * The popper will never be placed outside of the defined boundaries\n       * (except if `keepTogether` is enabled)\n       */\n      boundariesElement: 'viewport'\n    },\n\n    /**\n     * Modifier used to make the popper flow toward the inner of the reference element.\n     * By default, when this modifier is disabled, the popper will be placed outside\n     * the reference element.\n     * @memberof modifiers\n     * @inner\n     */\n    inner: {\n      /** @prop {number} order=700 - Index used to define the order of execution */\n      order: 700,\n      /** @prop {Boolean} enabled=false - Whether the modifier is enabled or not */\n      enabled: false,\n      /** @prop {ModifierFn} */\n      fn: inner\n    },\n\n    /**\n     * Modifier used to hide the popper when its reference element is outside of the\n     * popper boundaries. It will set a `x-out-of-boundaries` attribute which can\n     * be used to hide with a CSS selector the popper when its reference is\n     * out of boundaries.\n     *\n     * Requires the `preventOverflow` modifier before it in order to work.\n     * @memberof modifiers\n     * @inner\n     */\n    hide: {\n      /** @prop {number} order=800 - Index used to define the order of execution */\n      order: 800,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: hide\n    },\n\n    /**\n     * Computes the style that will be applied to the popper element to gets\n     * properly positioned.\n     *\n     * Note that this modifier will not touch the DOM, it just prepares the styles\n     * so that `applyStyle` modifier can apply it. This separation is useful\n     * in case you need to replace `applyStyle` with a custom implementation.\n     *\n     * This modifier has `850` as `order` value to maintain backward compatibility\n     * with previous versions of Popper.js. Expect the modifiers ordering method\n     * to change in future major versions of the library.\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    computeStyle: {\n      /** @prop {number} order=850 - Index used to define the order of execution */\n      order: 850,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: computeStyle,\n      /**\n       * @prop {Boolean} gpuAcceleration=true\n       * If true, it uses the CSS 3D transformation to position the popper.\n       * Otherwise, it will use the `top` and `left` properties\n       */\n      gpuAcceleration: true,\n      /**\n       * @prop {string} [x='bottom']\n       * Where to anchor the X axis (`bottom` or `top`). AKA X offset origin.\n       * Change this if your popper should grow in a direction different from `bottom`\n       */\n      x: 'bottom',\n      /**\n       * @prop {string} [x='left']\n       * Where to anchor the Y axis (`left` or `right`). AKA Y offset origin.\n       * Change this if your popper should grow in a direction different from `right`\n       */\n      y: 'right'\n    },\n\n    /**\n     * Applies the computed styles to the popper element.\n     *\n     * All the DOM manipulations are limited to this modifier. This is useful in case\n     * you want to integrate Popper.js inside a framework or view library and you\n     * want to delegate all the DOM manipulations to it.\n     *\n     * Note that if you disable this modifier, you must make sure the popper element\n     * has its position set to `absolute` before Popper.js can do its work!\n     *\n     * Just disable this modifier and define your own to achieve the desired effect.\n     *\n     * @memberof modifiers\n     * @inner\n     */\n    applyStyle: {\n      /** @prop {number} order=900 - Index used to define the order of execution */\n      order: 900,\n      /** @prop {Boolean} enabled=true - Whether the modifier is enabled or not */\n      enabled: true,\n      /** @prop {ModifierFn} */\n      fn: applyStyle,\n      /** @prop {Function} */\n      onLoad: applyStyleOnLoad,\n      /**\n       * @deprecated since version 1.10.0, the property moved to `computeStyle` modifier\n       * @prop {Boolean} gpuAcceleration=true\n       * If true, it uses the CSS 3D transformation to position the popper.\n       * Otherwise, it will use the `top` and `left` properties\n       */\n      gpuAcceleration: undefined\n    }\n  };\n\n  /**\n   * The `dataObject` is an object containing all the information used by Popper.js.\n   * This object is passed to modifiers and to the `onCreate` and `onUpdate` callbacks.\n   * @name dataObject\n   * @property {Object} data.instance The Popper.js instance\n   * @property {String} data.placement Placement applied to popper\n   * @property {String} data.originalPlacement Placement originally defined on init\n   * @property {Boolean} data.flipped True if popper has been flipped by flip modifier\n   * @property {Boolean} data.hide True if the reference element is out of boundaries, useful to know when to hide the popper\n   * @property {HTMLElement} data.arrowElement Node used as arrow by arrow modifier\n   * @property {Object} data.styles Any CSS property defined here will be applied to the popper. It expects the JavaScript nomenclature (eg. `marginBottom`)\n   * @property {Object} data.arrowStyles Any CSS property defined here will be applied to the popper arrow. It expects the JavaScript nomenclature (eg. `marginBottom`)\n   * @property {Object} data.boundaries Offsets of the popper boundaries\n   * @property {Object} data.offsets The measurements of popper, reference and arrow elements\n   * @property {Object} data.offsets.popper `top`, `left`, `width`, `height` values\n   * @property {Object} data.offsets.reference `top`, `left`, `width`, `height` values\n   * @property {Object} data.offsets.arrow] `top` and `left` offsets, only one of them will be different from 0\n   */\n\n  /**\n   * Default options provided to Popper.js constructor.<br />\n   * These can be overridden using the `options` argument of Popper.js.<br />\n   * To override an option, simply pass an object with the same\n   * structure of the `options` object, as the 3rd argument. For example:\n   * ```\n   * new Popper(ref, pop, {\n   *   modifiers: {\n   *     preventOverflow: { enabled: false }\n   *   }\n   * })\n   * ```\n   * @type {Object}\n   * @static\n   * @memberof Popper\n   */\n  var Defaults = {\n    /**\n     * Popper's placement.\n     * @prop {Popper.placements} placement='bottom'\n     */\n    placement: 'bottom',\n\n    /**\n     * Set this to true if you want popper to position it self in 'fixed' mode\n     * @prop {Boolean} positionFixed=false\n     */\n    positionFixed: false,\n\n    /**\n     * Whether events (resize, scroll) are initially enabled.\n     * @prop {Boolean} eventsEnabled=true\n     */\n    eventsEnabled: true,\n\n    /**\n     * Set to true if you want to automatically remove the popper when\n     * you call the `destroy` method.\n     * @prop {Boolean} removeOnDestroy=false\n     */\n    removeOnDestroy: false,\n\n    /**\n     * Callback called when the popper is created.<br />\n     * By default, it is set to no-op.<br />\n     * Access Popper.js instance with `data.instance`.\n     * @prop {onCreate}\n     */\n    onCreate: function onCreate() {},\n\n    /**\n     * Callback called when the popper is updated. This callback is not called\n     * on the initialization/creation of the popper, but only on subsequent\n     * updates.<br />\n     * By default, it is set to no-op.<br />\n     * Access Popper.js instance with `data.instance`.\n     * @prop {onUpdate}\n     */\n    onUpdate: function onUpdate() {},\n\n    /**\n     * List of modifiers used to modify the offsets before they are applied to the popper.\n     * They provide most of the functionalities of Popper.js.\n     * @prop {modifiers}\n     */\n    modifiers: modifiers\n  };\n\n  /**\n   * @callback onCreate\n   * @param {dataObject} data\n   */\n\n  /**\n   * @callback onUpdate\n   * @param {dataObject} data\n   */\n\n  // Utils\n  // Methods\n  var Popper = function () {\n    /**\n     * Creates a new Popper.js instance.\n     * @class Popper\n     * @param {HTMLElement|referenceObject} reference - The reference element used to position the popper\n     * @param {HTMLElement} popper - The HTML element used as the popper\n     * @param {Object} options - Your custom options to override the ones defined in [Defaults](#defaults)\n     * @return {Object} instance - The generated Popper.js instance\n     */\n    function Popper(reference, popper) {\n      var _this = this;\n\n      var options = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n      classCallCheck(this, Popper);\n\n      this.scheduleUpdate = function () {\n        return requestAnimationFrame(_this.update);\n      };\n\n      // make update() debounced, so that it only runs at most once-per-tick\n      this.update = debounce(this.update.bind(this));\n\n      // with {} we create a new object with the options inside it\n      this.options = _extends({}, Popper.Defaults, options);\n\n      // init state\n      this.state = {\n        isDestroyed: false,\n        isCreated: false,\n        scrollParents: []\n      };\n\n      // get reference and popper elements (allow jQuery wrappers)\n      this.reference = reference && reference.jquery ? reference[0] : reference;\n      this.popper = popper && popper.jquery ? popper[0] : popper;\n\n      // Deep merge modifiers options\n      this.options.modifiers = {};\n      Object.keys(_extends({}, Popper.Defaults.modifiers, options.modifiers)).forEach(function (name) {\n        _this.options.modifiers[name] = _extends({}, Popper.Defaults.modifiers[name] || {}, options.modifiers ? options.modifiers[name] : {});\n      });\n\n      // Refactoring modifiers' list (Object => Array)\n      this.modifiers = Object.keys(this.options.modifiers).map(function (name) {\n        return _extends({\n          name: name\n        }, _this.options.modifiers[name]);\n      })\n      // sort the modifiers by order\n      .sort(function (a, b) {\n        return a.order - b.order;\n      });\n\n      // modifiers have the ability to execute arbitrary code when Popper.js get inited\n      // such code is executed in the same order of its modifier\n      // they could add new properties to their options configuration\n      // BE AWARE: don't add options to `options.modifiers.name` but to `modifierOptions`!\n      this.modifiers.forEach(function (modifierOptions) {\n        if (modifierOptions.enabled && isFunction(modifierOptions.onLoad)) {\n          modifierOptions.onLoad(_this.reference, _this.popper, _this.options, modifierOptions, _this.state);\n        }\n      });\n\n      // fire the first update to position the popper in the right place\n      this.update();\n\n      var eventsEnabled = this.options.eventsEnabled;\n      if (eventsEnabled) {\n        // setup event listeners, they will take care of update the position in specific situations\n        this.enableEventListeners();\n      }\n\n      this.state.eventsEnabled = eventsEnabled;\n    }\n\n    // We can't use class properties because they don't get listed in the\n    // class prototype and break stuff like Sinon stubs\n\n\n    createClass(Popper, [{\n      key: 'update',\n      value: function update$$1() {\n        return update.call(this);\n      }\n    }, {\n      key: 'destroy',\n      value: function destroy$$1() {\n        return destroy.call(this);\n      }\n    }, {\n      key: 'enableEventListeners',\n      value: function enableEventListeners$$1() {\n        return enableEventListeners.call(this);\n      }\n    }, {\n      key: 'disableEventListeners',\n      value: function disableEventListeners$$1() {\n        return disableEventListeners.call(this);\n      }\n\n      /**\n       * Schedules an update. It will run on the next UI update available.\n       * @method scheduleUpdate\n       * @memberof Popper\n       */\n\n\n      /**\n       * Collection of utilities useful when writing custom modifiers.\n       * Starting from version 1.7, this method is available only if you\n       * include `popper-utils.js` before `popper.js`.\n       *\n       * **DEPRECATION**: This way to access PopperUtils is deprecated\n       * and will be removed in v2! Use the PopperUtils module directly instead.\n       * Due to the high instability of the methods contained in Utils, we can't\n       * guarantee them to follow semver. Use them at your own risk!\n       * @static\n       * @private\n       * @type {Object}\n       * @deprecated since version 1.8\n       * @member Utils\n       * @memberof Popper\n       */\n\n    }]);\n    return Popper;\n  }();\n\n  /**\n   * The `referenceObject` is an object that provides an interface compatible with Popper.js\n   * and lets you use it as replacement of a real DOM node.<br />\n   * You can use this method to position a popper relatively to a set of coordinates\n   * in case you don't have a DOM node to use as reference.\n   *\n   * ```\n   * new Popper(referenceObject, popperNode);\n   * ```\n   *\n   * NB: This feature isn't supported in Internet Explorer 10.\n   * @name referenceObject\n   * @property {Function} data.getBoundingClientRect\n   * A function that returns a set of coordinates compatible with the native `getBoundingClientRect` method.\n   * @property {number} data.clientWidth\n   * An ES6 getter that will return the width of the virtual reference element.\n   * @property {number} data.clientHeight\n   * An ES6 getter that will return the height of the virtual reference element.\n   */\n\n\n  Popper.Utils = (typeof window !== 'undefined' ? window : global).PopperUtils;\n  Popper.placements = placements;\n  Popper.Defaults = Defaults;\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$4 = 'dropdown';\n  var VERSION$4 = '4.3.1';\n  var DATA_KEY$4 = 'bs.dropdown';\n  var EVENT_KEY$4 = \".\" + DATA_KEY$4;\n  var DATA_API_KEY$4 = '.data-api';\n  var JQUERY_NO_CONFLICT$4 = $.fn[NAME$4];\n  var ESCAPE_KEYCODE = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var SPACE_KEYCODE = 32; // KeyboardEvent.which value for space key\n\n  var TAB_KEYCODE = 9; // KeyboardEvent.which value for tab key\n\n  var ARROW_UP_KEYCODE = 38; // KeyboardEvent.which value for up arrow key\n\n  var ARROW_DOWN_KEYCODE = 40; // KeyboardEvent.which value for down arrow key\n\n  var RIGHT_MOUSE_BUTTON_WHICH = 3; // MouseEvent.which value for the right button (assuming a right-handed mouse)\n\n  var REGEXP_KEYDOWN = new RegExp(ARROW_UP_KEYCODE + \"|\" + ARROW_DOWN_KEYCODE + \"|\" + ESCAPE_KEYCODE);\n  var Event$4 = {\n    HIDE: \"hide\" + EVENT_KEY$4,\n    HIDDEN: \"hidden\" + EVENT_KEY$4,\n    SHOW: \"show\" + EVENT_KEY$4,\n    SHOWN: \"shown\" + EVENT_KEY$4,\n    CLICK: \"click\" + EVENT_KEY$4,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYDOWN_DATA_API: \"keydown\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYUP_DATA_API: \"keyup\" + EVENT_KEY$4 + DATA_API_KEY$4\n  };\n  var ClassName$4 = {\n    DISABLED: 'disabled',\n    SHOW: 'show',\n    DROPUP: 'dropup',\n    DROPRIGHT: 'dropright',\n    DROPLEFT: 'dropleft',\n    MENURIGHT: 'dropdown-menu-right',\n    MENULEFT: 'dropdown-menu-left',\n    POSITION_STATIC: 'position-static'\n  };\n  var Selector$4 = {\n    DATA_TOGGLE: '[data-toggle=\"dropdown\"]',\n    FORM_CHILD: '.dropdown form',\n    MENU: '.dropdown-menu',\n    NAVBAR_NAV: '.navbar-nav',\n    VISIBLE_ITEMS: '.dropdown-menu .dropdown-item:not(.disabled):not(:disabled)'\n  };\n  var AttachmentMap = {\n    TOP: 'top-start',\n    TOPEND: 'top-end',\n    BOTTOM: 'bottom-start',\n    BOTTOMEND: 'bottom-end',\n    RIGHT: 'right-start',\n    RIGHTEND: 'right-end',\n    LEFT: 'left-start',\n    LEFTEND: 'left-end'\n  };\n  var Default$2 = {\n    offset: 0,\n    flip: true,\n    boundary: 'scrollParent',\n    reference: 'toggle',\n    display: 'dynamic'\n  };\n  var DefaultType$2 = {\n    offset: '(number|string|function)',\n    flip: 'boolean',\n    boundary: '(string|element)',\n    reference: '(string|element)',\n    display: 'string'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Dropdown =\n  /*#__PURE__*/\n  function () {\n    function Dropdown(element, config) {\n      this._element = element;\n      this._popper = null;\n      this._config = this._getConfig(config);\n      this._menu = this._getMenuElement();\n      this._inNavbar = this._detectNavbar();\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Dropdown.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      var isActive = $(this._menu).hasClass(ClassName$4.SHOW);\n\n      Dropdown._clearMenus();\n\n      if (isActive) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      } // Disable totally Popper.js for Dropdown in Navbar\n\n\n      if (!this._inNavbar) {\n        /**\n         * Check for Popper dependency\n         * Popper - https://popper.js.org\n         */\n        if (typeof Popper === 'undefined') {\n          throw new TypeError('Bootstrap\\'s dropdowns require Popper.js (https://popper.js.org/)');\n        }\n\n        var referenceElement = this._element;\n\n        if (this._config.reference === 'parent') {\n          referenceElement = parent;\n        } else if (Util.isElement(this._config.reference)) {\n          referenceElement = this._config.reference; // Check if it's jQuery element\n\n          if (typeof this._config.reference.jquery !== 'undefined') {\n            referenceElement = this._config.reference[0];\n          }\n        } // If boundary is not `scrollParent`, then set position to `static`\n        // to allow the menu to \"escape\" the scroll parent's boundaries\n        // https://github.com/twbs/bootstrap/issues/24251\n\n\n        if (this._config.boundary !== 'scrollParent') {\n          $(parent).addClass(ClassName$4.POSITION_STATIC);\n        }\n\n        this._popper = new Popper(referenceElement, this._menu, this._getPopperConfig());\n      } // If this is a touch-enabled device we add extra\n      // empty mouseover listeners to the body's immediate children;\n      // only needed because of broken event delegation on iOS\n      // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n\n      if ('ontouchstart' in document.documentElement && $(parent).closest(Selector$4.NAVBAR_NAV).length === 0) {\n        $(document.body).children().on('mouseover', null, $.noop);\n      }\n\n      this._element.focus();\n\n      this._element.setAttribute('aria-expanded', true);\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.show = function show() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || $(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.hide = function hide() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || !$(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$4);\n      $(this._element).off(EVENT_KEY$4);\n      this._element = null;\n      this._menu = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n\n        this._popper = null;\n      }\n    };\n\n    _proto.update = function update() {\n      this._inNavbar = this._detectNavbar();\n\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Private\n    ;\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this = this;\n\n      $(this._element).on(Event$4.CLICK, function (event) {\n        event.preventDefault();\n        event.stopPropagation();\n\n        _this.toggle();\n      });\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, this.constructor.Default, $(this._element).data(), config);\n      Util.typeCheckConfig(NAME$4, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._getMenuElement = function _getMenuElement() {\n      if (!this._menu) {\n        var parent = Dropdown._getParentFromElement(this._element);\n\n        if (parent) {\n          this._menu = parent.querySelector(Selector$4.MENU);\n        }\n      }\n\n      return this._menu;\n    };\n\n    _proto._getPlacement = function _getPlacement() {\n      var $parentDropdown = $(this._element.parentNode);\n      var placement = AttachmentMap.BOTTOM; // Handle dropup\n\n      if ($parentDropdown.hasClass(ClassName$4.DROPUP)) {\n        placement = AttachmentMap.TOP;\n\n        if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n          placement = AttachmentMap.TOPEND;\n        }\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPRIGHT)) {\n        placement = AttachmentMap.RIGHT;\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPLEFT)) {\n        placement = AttachmentMap.LEFT;\n      } else if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n        placement = AttachmentMap.BOTTOMEND;\n      }\n\n      return placement;\n    };\n\n    _proto._detectNavbar = function _detectNavbar() {\n      return $(this._element).closest('.navbar').length > 0;\n    };\n\n    _proto._getOffset = function _getOffset() {\n      var _this2 = this;\n\n      var offset = {};\n\n      if (typeof this._config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this2._config.offset(data.offsets, _this2._element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this._config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getPopperConfig = function _getPopperConfig() {\n      var popperConfig = {\n        placement: this._getPlacement(),\n        modifiers: {\n          offset: this._getOffset(),\n          flip: {\n            enabled: this._config.flip\n          },\n          preventOverflow: {\n            boundariesElement: this._config.boundary\n          }\n        } // Disable Popper.js if we have a static display\n\n      };\n\n      if (this._config.display === 'static') {\n        popperConfig.modifiers.applyStyle = {\n          enabled: false\n        };\n      }\n\n      return popperConfig;\n    } // Static\n    ;\n\n    Dropdown._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$4);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data) {\n          data = new Dropdown(this, _config);\n          $(this).data(DATA_KEY$4, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    Dropdown._clearMenus = function _clearMenus(event) {\n      if (event && (event.which === RIGHT_MOUSE_BUTTON_WHICH || event.type === 'keyup' && event.which !== TAB_KEYCODE)) {\n        return;\n      }\n\n      var toggles = [].slice.call(document.querySelectorAll(Selector$4.DATA_TOGGLE));\n\n      for (var i = 0, len = toggles.length; i < len; i++) {\n        var parent = Dropdown._getParentFromElement(toggles[i]);\n\n        var context = $(toggles[i]).data(DATA_KEY$4);\n        var relatedTarget = {\n          relatedTarget: toggles[i]\n        };\n\n        if (event && event.type === 'click') {\n          relatedTarget.clickEvent = event;\n        }\n\n        if (!context) {\n          continue;\n        }\n\n        var dropdownMenu = context._menu;\n\n        if (!$(parent).hasClass(ClassName$4.SHOW)) {\n          continue;\n        }\n\n        if (event && (event.type === 'click' && /input|textarea/i.test(event.target.tagName) || event.type === 'keyup' && event.which === TAB_KEYCODE) && $.contains(parent, event.target)) {\n          continue;\n        }\n\n        var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n        $(parent).trigger(hideEvent);\n\n        if (hideEvent.isDefaultPrevented()) {\n          continue;\n        } // If this is a touch-enabled device we remove the extra\n        // empty mouseover listeners we added for iOS support\n\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().off('mouseover', null, $.noop);\n        }\n\n        toggles[i].setAttribute('aria-expanded', 'false');\n        $(dropdownMenu).removeClass(ClassName$4.SHOW);\n        $(parent).removeClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n      }\n    };\n\n    Dropdown._getParentFromElement = function _getParentFromElement(element) {\n      var parent;\n      var selector = Util.getSelectorFromElement(element);\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      return parent || element.parentNode;\n    } // eslint-disable-next-line complexity\n    ;\n\n    Dropdown._dataApiKeydownHandler = function _dataApiKeydownHandler(event) {\n      // If not input/textarea:\n      //  - And not a key in REGEXP_KEYDOWN => not a dropdown command\n      // If input/textarea:\n      //  - If space key => not a dropdown command\n      //  - If key is other than escape\n      //    - If key is not up or down => not a dropdown command\n      //    - If trigger inside the menu => not a dropdown command\n      if (/input|textarea/i.test(event.target.tagName) ? event.which === SPACE_KEYCODE || event.which !== ESCAPE_KEYCODE && (event.which !== ARROW_DOWN_KEYCODE && event.which !== ARROW_UP_KEYCODE || $(event.target).closest(Selector$4.MENU).length) : !REGEXP_KEYDOWN.test(event.which)) {\n        return;\n      }\n\n      event.preventDefault();\n      event.stopPropagation();\n\n      if (this.disabled || $(this).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this);\n\n      var isActive = $(parent).hasClass(ClassName$4.SHOW);\n\n      if (!isActive || isActive && (event.which === ESCAPE_KEYCODE || event.which === SPACE_KEYCODE)) {\n        if (event.which === ESCAPE_KEYCODE) {\n          var toggle = parent.querySelector(Selector$4.DATA_TOGGLE);\n          $(toggle).trigger('focus');\n        }\n\n        $(this).trigger('click');\n        return;\n      }\n\n      var items = [].slice.call(parent.querySelectorAll(Selector$4.VISIBLE_ITEMS));\n\n      if (items.length === 0) {\n        return;\n      }\n\n      var index = items.indexOf(event.target);\n\n      if (event.which === ARROW_UP_KEYCODE && index > 0) {\n        // Up\n        index--;\n      }\n\n      if (event.which === ARROW_DOWN_KEYCODE && index < items.length - 1) {\n        // Down\n        index++;\n      }\n\n      if (index < 0) {\n        index = 0;\n      }\n\n      items[index].focus();\n    };\n\n    _createClass(Dropdown, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$4;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$2;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$2;\n      }\n    }]);\n\n    return Dropdown;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$4.KEYDOWN_DATA_API, Selector$4.DATA_TOGGLE, Dropdown._dataApiKeydownHandler).on(Event$4.KEYDOWN_DATA_API, Selector$4.MENU, Dropdown._dataApiKeydownHandler).on(Event$4.CLICK_DATA_API + \" \" + Event$4.KEYUP_DATA_API, Dropdown._clearMenus).on(Event$4.CLICK_DATA_API, Selector$4.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n    event.stopPropagation();\n\n    Dropdown._jQueryInterface.call($(this), 'toggle');\n  }).on(Event$4.CLICK_DATA_API, Selector$4.FORM_CHILD, function (e) {\n    e.stopPropagation();\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$4] = Dropdown._jQueryInterface;\n  $.fn[NAME$4].Constructor = Dropdown;\n\n  $.fn[NAME$4].noConflict = function () {\n    $.fn[NAME$4] = JQUERY_NO_CONFLICT$4;\n    return Dropdown._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$5 = 'modal';\n  var VERSION$5 = '4.3.1';\n  var DATA_KEY$5 = 'bs.modal';\n  var EVENT_KEY$5 = \".\" + DATA_KEY$5;\n  var DATA_API_KEY$5 = '.data-api';\n  var JQUERY_NO_CONFLICT$5 = $.fn[NAME$5];\n  var ESCAPE_KEYCODE$1 = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var Default$3 = {\n    backdrop: true,\n    keyboard: true,\n    focus: true,\n    show: true\n  };\n  var DefaultType$3 = {\n    backdrop: '(boolean|string)',\n    keyboard: 'boolean',\n    focus: 'boolean',\n    show: 'boolean'\n  };\n  var Event$5 = {\n    HIDE: \"hide\" + EVENT_KEY$5,\n    HIDDEN: \"hidden\" + EVENT_KEY$5,\n    SHOW: \"show\" + EVENT_KEY$5,\n    SHOWN: \"shown\" + EVENT_KEY$5,\n    FOCUSIN: \"focusin\" + EVENT_KEY$5,\n    RESIZE: \"resize\" + EVENT_KEY$5,\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$5,\n    KEYDOWN_DISMISS: \"keydown.dismiss\" + EVENT_KEY$5,\n    MOUSEUP_DISMISS: \"mouseup.dismiss\" + EVENT_KEY$5,\n    MOUSEDOWN_DISMISS: \"mousedown.dismiss\" + EVENT_KEY$5,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$5 + DATA_API_KEY$5\n  };\n  var ClassName$5 = {\n    SCROLLABLE: 'modal-dialog-scrollable',\n    SCROLLBAR_MEASURER: 'modal-scrollbar-measure',\n    BACKDROP: 'modal-backdrop',\n    OPEN: 'modal-open',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$5 = {\n    DIALOG: '.modal-dialog',\n    MODAL_BODY: '.modal-body',\n    DATA_TOGGLE: '[data-toggle=\"modal\"]',\n    DATA_DISMISS: '[data-dismiss=\"modal\"]',\n    FIXED_CONTENT: '.fixed-top, .fixed-bottom, .is-fixed, .sticky-top',\n    STICKY_CONTENT: '.sticky-top'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Modal =\n  /*#__PURE__*/\n  function () {\n    function Modal(element, config) {\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._dialog = element.querySelector(Selector$5.DIALOG);\n      this._backdrop = null;\n      this._isShown = false;\n      this._isBodyOverflowing = false;\n      this._ignoreBackdropClick = false;\n      this._isTransitioning = false;\n      this._scrollbarWidth = 0;\n    } // Getters\n\n\n    var _proto = Modal.prototype;\n\n    // Public\n    _proto.toggle = function toggle(relatedTarget) {\n      return this._isShown ? this.hide() : this.show(relatedTarget);\n    };\n\n    _proto.show = function show(relatedTarget) {\n      var _this = this;\n\n      if (this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      if ($(this._element).hasClass(ClassName$5.FADE)) {\n        this._isTransitioning = true;\n      }\n\n      var showEvent = $.Event(Event$5.SHOW, {\n        relatedTarget: relatedTarget\n      });\n      $(this._element).trigger(showEvent);\n\n      if (this._isShown || showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = true;\n\n      this._checkScrollbar();\n\n      this._setScrollbar();\n\n      this._adjustDialog();\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(this._element).on(Event$5.CLICK_DISMISS, Selector$5.DATA_DISMISS, function (event) {\n        return _this.hide(event);\n      });\n      $(this._dialog).on(Event$5.MOUSEDOWN_DISMISS, function () {\n        $(_this._element).one(Event$5.MOUSEUP_DISMISS, function (event) {\n          if ($(event.target).is(_this._element)) {\n            _this._ignoreBackdropClick = true;\n          }\n        });\n      });\n\n      this._showBackdrop(function () {\n        return _this._showElement(relatedTarget);\n      });\n    };\n\n    _proto.hide = function hide(event) {\n      var _this2 = this;\n\n      if (event) {\n        event.preventDefault();\n      }\n\n      if (!this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      var hideEvent = $.Event(Event$5.HIDE);\n      $(this._element).trigger(hideEvent);\n\n      if (!this._isShown || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = false;\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (transition) {\n        this._isTransitioning = true;\n      }\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(document).off(Event$5.FOCUSIN);\n      $(this._element).removeClass(ClassName$5.SHOW);\n      $(this._element).off(Event$5.CLICK_DISMISS);\n      $(this._dialog).off(Event$5.MOUSEDOWN_DISMISS);\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, function (event) {\n          return _this2._hideModal(event);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        this._hideModal();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      [window, this._element, this._dialog].forEach(function (htmlElement) {\n        return $(htmlElement).off(EVENT_KEY$5);\n      });\n      /**\n       * `document` has 2 events `Event.FOCUSIN` and `Event.CLICK_DATA_API`\n       * Do not move `document` in `htmlElements` array\n       * It will remove `Event.CLICK_DATA_API` event that should remain\n       */\n\n      $(document).off(Event$5.FOCUSIN);\n      $.removeData(this._element, DATA_KEY$5);\n      this._config = null;\n      this._element = null;\n      this._dialog = null;\n      this._backdrop = null;\n      this._isShown = null;\n      this._isBodyOverflowing = null;\n      this._ignoreBackdropClick = null;\n      this._isTransitioning = null;\n      this._scrollbarWidth = null;\n    };\n\n    _proto.handleUpdate = function handleUpdate() {\n      this._adjustDialog();\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$3, config);\n      Util.typeCheckConfig(NAME$5, config, DefaultType$3);\n      return config;\n    };\n\n    _proto._showElement = function _showElement(relatedTarget) {\n      var _this3 = this;\n\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (!this._element.parentNode || this._element.parentNode.nodeType !== Node.ELEMENT_NODE) {\n        // Don't move modal's DOM position\n        document.body.appendChild(this._element);\n      }\n\n      this._element.style.display = 'block';\n\n      this._element.removeAttribute('aria-hidden');\n\n      this._element.setAttribute('aria-modal', true);\n\n      if ($(this._dialog).hasClass(ClassName$5.SCROLLABLE)) {\n        this._dialog.querySelector(Selector$5.MODAL_BODY).scrollTop = 0;\n      } else {\n        this._element.scrollTop = 0;\n      }\n\n      if (transition) {\n        Util.reflow(this._element);\n      }\n\n      $(this._element).addClass(ClassName$5.SHOW);\n\n      if (this._config.focus) {\n        this._enforceFocus();\n      }\n\n      var shownEvent = $.Event(Event$5.SHOWN, {\n        relatedTarget: relatedTarget\n      });\n\n      var transitionComplete = function transitionComplete() {\n        if (_this3._config.focus) {\n          _this3._element.focus();\n        }\n\n        _this3._isTransitioning = false;\n        $(_this3._element).trigger(shownEvent);\n      };\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._dialog);\n        $(this._dialog).one(Util.TRANSITION_END, transitionComplete).emulateTransitionEnd(transitionDuration);\n      } else {\n        transitionComplete();\n      }\n    };\n\n    _proto._enforceFocus = function _enforceFocus() {\n      var _this4 = this;\n\n      $(document).off(Event$5.FOCUSIN) // Guard against infinite focus loop\n      .on(Event$5.FOCUSIN, function (event) {\n        if (document !== event.target && _this4._element !== event.target && $(_this4._element).has(event.target).length === 0) {\n          _this4._element.focus();\n        }\n      });\n    };\n\n    _proto._setEscapeEvent = function _setEscapeEvent() {\n      var _this5 = this;\n\n      if (this._isShown && this._config.keyboard) {\n        $(this._element).on(Event$5.KEYDOWN_DISMISS, function (event) {\n          if (event.which === ESCAPE_KEYCODE$1) {\n            event.preventDefault();\n\n            _this5.hide();\n          }\n        });\n      } else if (!this._isShown) {\n        $(this._element).off(Event$5.KEYDOWN_DISMISS);\n      }\n    };\n\n    _proto._setResizeEvent = function _setResizeEvent() {\n      var _this6 = this;\n\n      if (this._isShown) {\n        $(window).on(Event$5.RESIZE, function (event) {\n          return _this6.handleUpdate(event);\n        });\n      } else {\n        $(window).off(Event$5.RESIZE);\n      }\n    };\n\n    _proto._hideModal = function _hideModal() {\n      var _this7 = this;\n\n      this._element.style.display = 'none';\n\n      this._element.setAttribute('aria-hidden', true);\n\n      this._element.removeAttribute('aria-modal');\n\n      this._isTransitioning = false;\n\n      this._showBackdrop(function () {\n        $(document.body).removeClass(ClassName$5.OPEN);\n\n        _this7._resetAdjustments();\n\n        _this7._resetScrollbar();\n\n        $(_this7._element).trigger(Event$5.HIDDEN);\n      });\n    };\n\n    _proto._removeBackdrop = function _removeBackdrop() {\n      if (this._backdrop) {\n        $(this._backdrop).remove();\n        this._backdrop = null;\n      }\n    };\n\n    _proto._showBackdrop = function _showBackdrop(callback) {\n      var _this8 = this;\n\n      var animate = $(this._element).hasClass(ClassName$5.FADE) ? ClassName$5.FADE : '';\n\n      if (this._isShown && this._config.backdrop) {\n        this._backdrop = document.createElement('div');\n        this._backdrop.className = ClassName$5.BACKDROP;\n\n        if (animate) {\n          this._backdrop.classList.add(animate);\n        }\n\n        $(this._backdrop).appendTo(document.body);\n        $(this._element).on(Event$5.CLICK_DISMISS, function (event) {\n          if (_this8._ignoreBackdropClick) {\n            _this8._ignoreBackdropClick = false;\n            return;\n          }\n\n          if (event.target !== event.currentTarget) {\n            return;\n          }\n\n          if (_this8._config.backdrop === 'static') {\n            _this8._element.focus();\n          } else {\n            _this8.hide();\n          }\n        });\n\n        if (animate) {\n          Util.reflow(this._backdrop);\n        }\n\n        $(this._backdrop).addClass(ClassName$5.SHOW);\n\n        if (!callback) {\n          return;\n        }\n\n        if (!animate) {\n          callback();\n          return;\n        }\n\n        var backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n        $(this._backdrop).one(Util.TRANSITION_END, callback).emulateTransitionEnd(backdropTransitionDuration);\n      } else if (!this._isShown && this._backdrop) {\n        $(this._backdrop).removeClass(ClassName$5.SHOW);\n\n        var callbackRemove = function callbackRemove() {\n          _this8._removeBackdrop();\n\n          if (callback) {\n            callback();\n          }\n        };\n\n        if ($(this._element).hasClass(ClassName$5.FADE)) {\n          var _backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n\n          $(this._backdrop).one(Util.TRANSITION_END, callbackRemove).emulateTransitionEnd(_backdropTransitionDuration);\n        } else {\n          callbackRemove();\n        }\n      } else if (callback) {\n        callback();\n      }\n    } // ----------------------------------------------------------------------\n    // the following methods are used to handle overflowing modals\n    // todo (fat): these should probably be refactored out of modal.js\n    // ----------------------------------------------------------------------\n    ;\n\n    _proto._adjustDialog = function _adjustDialog() {\n      var isModalOverflowing = this._element.scrollHeight > document.documentElement.clientHeight;\n\n      if (!this._isBodyOverflowing && isModalOverflowing) {\n        this._element.style.paddingLeft = this._scrollbarWidth + \"px\";\n      }\n\n      if (this._isBodyOverflowing && !isModalOverflowing) {\n        this._element.style.paddingRight = this._scrollbarWidth + \"px\";\n      }\n    };\n\n    _proto._resetAdjustments = function _resetAdjustments() {\n      this._element.style.paddingLeft = '';\n      this._element.style.paddingRight = '';\n    };\n\n    _proto._checkScrollbar = function _checkScrollbar() {\n      var rect = document.body.getBoundingClientRect();\n      this._isBodyOverflowing = rect.left + rect.right < window.innerWidth;\n      this._scrollbarWidth = this._getScrollbarWidth();\n    };\n\n    _proto._setScrollbar = function _setScrollbar() {\n      var _this9 = this;\n\n      if (this._isBodyOverflowing) {\n        // Note: DOMNode.style.paddingRight returns the actual value or '' if not set\n        //   while $(DOMNode).css('padding-right') returns the calculated value or 0 if not set\n        var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n        var stickyContent = [].slice.call(document.querySelectorAll(Selector$5.STICKY_CONTENT)); // Adjust fixed content padding\n\n        $(fixedContent).each(function (index, element) {\n          var actualPadding = element.style.paddingRight;\n          var calculatedPadding = $(element).css('padding-right');\n          $(element).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + _this9._scrollbarWidth + \"px\");\n        }); // Adjust sticky content margin\n\n        $(stickyContent).each(function (index, element) {\n          var actualMargin = element.style.marginRight;\n          var calculatedMargin = $(element).css('margin-right');\n          $(element).data('margin-right', actualMargin).css('margin-right', parseFloat(calculatedMargin) - _this9._scrollbarWidth + \"px\");\n        }); // Adjust body padding\n\n        var actualPadding = document.body.style.paddingRight;\n        var calculatedPadding = $(document.body).css('padding-right');\n        $(document.body).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + this._scrollbarWidth + \"px\");\n      }\n\n      $(document.body).addClass(ClassName$5.OPEN);\n    };\n\n    _proto._resetScrollbar = function _resetScrollbar() {\n      // Restore fixed content padding\n      var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n      $(fixedContent).each(function (index, element) {\n        var padding = $(element).data('padding-right');\n        $(element).removeData('padding-right');\n        element.style.paddingRight = padding ? padding : '';\n      }); // Restore sticky content\n\n      var elements = [].slice.call(document.querySelectorAll(\"\" + Selector$5.STICKY_CONTENT));\n      $(elements).each(function (index, element) {\n        var margin = $(element).data('margin-right');\n\n        if (typeof margin !== 'undefined') {\n          $(element).css('margin-right', margin).removeData('margin-right');\n        }\n      }); // Restore body padding\n\n      var padding = $(document.body).data('padding-right');\n      $(document.body).removeData('padding-right');\n      document.body.style.paddingRight = padding ? padding : '';\n    };\n\n    _proto._getScrollbarWidth = function _getScrollbarWidth() {\n      // thx d.walsh\n      var scrollDiv = document.createElement('div');\n      scrollDiv.className = ClassName$5.SCROLLBAR_MEASURER;\n      document.body.appendChild(scrollDiv);\n      var scrollbarWidth = scrollDiv.getBoundingClientRect().width - scrollDiv.clientWidth;\n      document.body.removeChild(scrollDiv);\n      return scrollbarWidth;\n    } // Static\n    ;\n\n    Modal._jQueryInterface = function _jQueryInterface(config, relatedTarget) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$5);\n\n        var _config = _objectSpread({}, Default$3, $(this).data(), typeof config === 'object' && config ? config : {});\n\n        if (!data) {\n          data = new Modal(this, _config);\n          $(this).data(DATA_KEY$5, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](relatedTarget);\n        } else if (_config.show) {\n          data.show(relatedTarget);\n        }\n      });\n    };\n\n    _createClass(Modal, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$5;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$3;\n      }\n    }]);\n\n    return Modal;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$5.CLICK_DATA_API, Selector$5.DATA_TOGGLE, function (event) {\n    var _this10 = this;\n\n    var target;\n    var selector = Util.getSelectorFromElement(this);\n\n    if (selector) {\n      target = document.querySelector(selector);\n    }\n\n    var config = $(target).data(DATA_KEY$5) ? 'toggle' : _objectSpread({}, $(target).data(), $(this).data());\n\n    if (this.tagName === 'A' || this.tagName === 'AREA') {\n      event.preventDefault();\n    }\n\n    var $target = $(target).one(Event$5.SHOW, function (showEvent) {\n      if (showEvent.isDefaultPrevented()) {\n        // Only register focus restorer if modal will actually get shown\n        return;\n      }\n\n      $target.one(Event$5.HIDDEN, function () {\n        if ($(_this10).is(':visible')) {\n          _this10.focus();\n        }\n      });\n    });\n\n    Modal._jQueryInterface.call($(target), config, this);\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$5] = Modal._jQueryInterface;\n  $.fn[NAME$5].Constructor = Modal;\n\n  $.fn[NAME$5].noConflict = function () {\n    $.fn[NAME$5] = JQUERY_NO_CONFLICT$5;\n    return Modal._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): tools/sanitizer.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  var uriAttrs = ['background', 'cite', 'href', 'itemtype', 'longdesc', 'poster', 'src', 'xlink:href'];\n  var ARIA_ATTRIBUTE_PATTERN = /^aria-[\\w-]*$/i;\n  var DefaultWhitelist = {\n    // Global attributes allowed on any supplied element below.\n    '*': ['class', 'dir', 'id', 'lang', 'role', ARIA_ATTRIBUTE_PATTERN],\n    a: ['target', 'href', 'title', 'rel'],\n    area: [],\n    b: [],\n    br: [],\n    col: [],\n    code: [],\n    div: [],\n    em: [],\n    hr: [],\n    h1: [],\n    h2: [],\n    h3: [],\n    h4: [],\n    h5: [],\n    h6: [],\n    i: [],\n    img: ['src', 'alt', 'title', 'width', 'height'],\n    li: [],\n    ol: [],\n    p: [],\n    pre: [],\n    s: [],\n    small: [],\n    span: [],\n    sub: [],\n    sup: [],\n    strong: [],\n    u: [],\n    ul: []\n    /**\n     * A pattern that recognizes a commonly useful subset of URLs that are safe.\n     *\n     * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n     */\n\n  };\n  var SAFE_URL_PATTERN = /^(?:(?:https?|mailto|ftp|tel|file):|[^&:/?#]*(?:[/?#]|$))/gi;\n  /**\n   * A pattern that matches safe data URLs. Only matches image, video and audio types.\n   *\n   * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n   */\n\n  var DATA_URL_PATTERN = /^data:(?:image\\/(?:bmp|gif|jpeg|jpg|png|tiff|webp)|video\\/(?:mpeg|mp4|ogg|webm)|audio\\/(?:mp3|oga|ogg|opus));base64,[a-z0-9+/]+=*$/i;\n\n  function allowedAttribute(attr, allowedAttributeList) {\n    var attrName = attr.nodeName.toLowerCase();\n\n    if (allowedAttributeList.indexOf(attrName) !== -1) {\n      if (uriAttrs.indexOf(attrName) !== -1) {\n        return Boolean(attr.nodeValue.match(SAFE_URL_PATTERN) || attr.nodeValue.match(DATA_URL_PATTERN));\n      }\n\n      return true;\n    }\n\n    var regExp = allowedAttributeList.filter(function (attrRegex) {\n      return attrRegex instanceof RegExp;\n    }); // Check if a regular expression validates the attribute.\n\n    for (var i = 0, l = regExp.length; i < l; i++) {\n      if (attrName.match(regExp[i])) {\n        return true;\n      }\n    }\n\n    return false;\n  }\n\n  function sanitizeHtml(unsafeHtml, whiteList, sanitizeFn) {\n    if (unsafeHtml.length === 0) {\n      return unsafeHtml;\n    }\n\n    if (sanitizeFn && typeof sanitizeFn === 'function') {\n      return sanitizeFn(unsafeHtml);\n    }\n\n    var domParser = new window.DOMParser();\n    var createdDocument = domParser.parseFromString(unsafeHtml, 'text/html');\n    var whitelistKeys = Object.keys(whiteList);\n    var elements = [].slice.call(createdDocument.body.querySelectorAll('*'));\n\n    var _loop = function _loop(i, len) {\n      var el = elements[i];\n      var elName = el.nodeName.toLowerCase();\n\n      if (whitelistKeys.indexOf(el.nodeName.toLowerCase()) === -1) {\n        el.parentNode.removeChild(el);\n        return \"continue\";\n      }\n\n      var attributeList = [].slice.call(el.attributes);\n      var whitelistedAttributes = [].concat(whiteList['*'] || [], whiteList[elName] || []);\n      attributeList.forEach(function (attr) {\n        if (!allowedAttribute(attr, whitelistedAttributes)) {\n          el.removeAttribute(attr.nodeName);\n        }\n      });\n    };\n\n    for (var i = 0, len = elements.length; i < len; i++) {\n      var _ret = _loop(i, len);\n\n      if (_ret === \"continue\") continue;\n    }\n\n    return createdDocument.body.innerHTML;\n  }\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$6 = 'tooltip';\n  var VERSION$6 = '4.3.1';\n  var DATA_KEY$6 = 'bs.tooltip';\n  var EVENT_KEY$6 = \".\" + DATA_KEY$6;\n  var JQUERY_NO_CONFLICT$6 = $.fn[NAME$6];\n  var CLASS_PREFIX = 'bs-tooltip';\n  var BSCLS_PREFIX_REGEX = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX + \"\\\\S+\", 'g');\n  var DISALLOWED_ATTRIBUTES = ['sanitize', 'whiteList', 'sanitizeFn'];\n  var DefaultType$4 = {\n    animation: 'boolean',\n    template: 'string',\n    title: '(string|element|function)',\n    trigger: 'string',\n    delay: '(number|object)',\n    html: 'boolean',\n    selector: '(string|boolean)',\n    placement: '(string|function)',\n    offset: '(number|string|function)',\n    container: '(string|element|boolean)',\n    fallbackPlacement: '(string|array)',\n    boundary: '(string|element)',\n    sanitize: 'boolean',\n    sanitizeFn: '(null|function)',\n    whiteList: 'object'\n  };\n  var AttachmentMap$1 = {\n    AUTO: 'auto',\n    TOP: 'top',\n    RIGHT: 'right',\n    BOTTOM: 'bottom',\n    LEFT: 'left'\n  };\n  var Default$4 = {\n    animation: true,\n    template: '<div class=\"tooltip\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<div class=\"tooltip-inner\"></div></div>',\n    trigger: 'hover focus',\n    title: '',\n    delay: 0,\n    html: false,\n    selector: false,\n    placement: 'top',\n    offset: 0,\n    container: false,\n    fallbackPlacement: 'flip',\n    boundary: 'scrollParent',\n    sanitize: true,\n    sanitizeFn: null,\n    whiteList: DefaultWhitelist\n  };\n  var HoverState = {\n    SHOW: 'show',\n    OUT: 'out'\n  };\n  var Event$6 = {\n    HIDE: \"hide\" + EVENT_KEY$6,\n    HIDDEN: \"hidden\" + EVENT_KEY$6,\n    SHOW: \"show\" + EVENT_KEY$6,\n    SHOWN: \"shown\" + EVENT_KEY$6,\n    INSERTED: \"inserted\" + EVENT_KEY$6,\n    CLICK: \"click\" + EVENT_KEY$6,\n    FOCUSIN: \"focusin\" + EVENT_KEY$6,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$6,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$6,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$6\n  };\n  var ClassName$6 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$6 = {\n    TOOLTIP: '.tooltip',\n    TOOLTIP_INNER: '.tooltip-inner',\n    ARROW: '.arrow'\n  };\n  var Trigger = {\n    HOVER: 'hover',\n    FOCUS: 'focus',\n    CLICK: 'click',\n    MANUAL: 'manual'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tooltip =\n  /*#__PURE__*/\n  function () {\n    function Tooltip(element, config) {\n      /**\n       * Check for Popper dependency\n       * Popper - https://popper.js.org\n       */\n      if (typeof Popper === 'undefined') {\n        throw new TypeError('Bootstrap\\'s tooltips require Popper.js (https://popper.js.org/)');\n      } // private\n\n\n      this._isEnabled = true;\n      this._timeout = 0;\n      this._hoverState = '';\n      this._activeTrigger = {};\n      this._popper = null; // Protected\n\n      this.element = element;\n      this.config = this._getConfig(config);\n      this.tip = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Tooltip.prototype;\n\n    // Public\n    _proto.enable = function enable() {\n      this._isEnabled = true;\n    };\n\n    _proto.disable = function disable() {\n      this._isEnabled = false;\n    };\n\n    _proto.toggleEnabled = function toggleEnabled() {\n      this._isEnabled = !this._isEnabled;\n    };\n\n    _proto.toggle = function toggle(event) {\n      if (!this._isEnabled) {\n        return;\n      }\n\n      if (event) {\n        var dataKey = this.constructor.DATA_KEY;\n        var context = $(event.currentTarget).data(dataKey);\n\n        if (!context) {\n          context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n          $(event.currentTarget).data(dataKey, context);\n        }\n\n        context._activeTrigger.click = !context._activeTrigger.click;\n\n        if (context._isWithActiveTrigger()) {\n          context._enter(null, context);\n        } else {\n          context._leave(null, context);\n        }\n      } else {\n        if ($(this.getTipElement()).hasClass(ClassName$6.SHOW)) {\n          this._leave(null, this);\n\n          return;\n        }\n\n        this._enter(null, this);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      $.removeData(this.element, this.constructor.DATA_KEY);\n      $(this.element).off(this.constructor.EVENT_KEY);\n      $(this.element).closest('.modal').off('hide.bs.modal');\n\n      if (this.tip) {\n        $(this.tip).remove();\n      }\n\n      this._isEnabled = null;\n      this._timeout = null;\n      this._hoverState = null;\n      this._activeTrigger = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n      }\n\n      this._popper = null;\n      this.element = null;\n      this.config = null;\n      this.tip = null;\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if ($(this.element).css('display') === 'none') {\n        throw new Error('Please use show on visible elements');\n      }\n\n      var showEvent = $.Event(this.constructor.Event.SHOW);\n\n      if (this.isWithContent() && this._isEnabled) {\n        $(this.element).trigger(showEvent);\n        var shadowRoot = Util.findShadowRoot(this.element);\n        var isInTheDom = $.contains(shadowRoot !== null ? shadowRoot : this.element.ownerDocument.documentElement, this.element);\n\n        if (showEvent.isDefaultPrevented() || !isInTheDom) {\n          return;\n        }\n\n        var tip = this.getTipElement();\n        var tipId = Util.getUID(this.constructor.NAME);\n        tip.setAttribute('id', tipId);\n        this.element.setAttribute('aria-describedby', tipId);\n        this.setContent();\n\n        if (this.config.animation) {\n          $(tip).addClass(ClassName$6.FADE);\n        }\n\n        var placement = typeof this.config.placement === 'function' ? this.config.placement.call(this, tip, this.element) : this.config.placement;\n\n        var attachment = this._getAttachment(placement);\n\n        this.addAttachmentClass(attachment);\n\n        var container = this._getContainer();\n\n        $(tip).data(this.constructor.DATA_KEY, this);\n\n        if (!$.contains(this.element.ownerDocument.documentElement, this.tip)) {\n          $(tip).appendTo(container);\n        }\n\n        $(this.element).trigger(this.constructor.Event.INSERTED);\n        this._popper = new Popper(this.element, tip, {\n          placement: attachment,\n          modifiers: {\n            offset: this._getOffset(),\n            flip: {\n              behavior: this.config.fallbackPlacement\n            },\n            arrow: {\n              element: Selector$6.ARROW\n            },\n            preventOverflow: {\n              boundariesElement: this.config.boundary\n            }\n          },\n          onCreate: function onCreate(data) {\n            if (data.originalPlacement !== data.placement) {\n              _this._handlePopperPlacementChange(data);\n            }\n          },\n          onUpdate: function onUpdate(data) {\n            return _this._handlePopperPlacementChange(data);\n          }\n        });\n        $(tip).addClass(ClassName$6.SHOW); // If this is a touch-enabled device we add extra\n        // empty mouseover listeners to the body's immediate children;\n        // only needed because of broken event delegation on iOS\n        // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().on('mouseover', null, $.noop);\n        }\n\n        var complete = function complete() {\n          if (_this.config.animation) {\n            _this._fixTransition();\n          }\n\n          var prevHoverState = _this._hoverState;\n          _this._hoverState = null;\n          $(_this.element).trigger(_this.constructor.Event.SHOWN);\n\n          if (prevHoverState === HoverState.OUT) {\n            _this._leave(null, _this);\n          }\n        };\n\n        if ($(this.tip).hasClass(ClassName$6.FADE)) {\n          var transitionDuration = Util.getTransitionDurationFromElement(this.tip);\n          $(this.tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n        } else {\n          complete();\n        }\n      }\n    };\n\n    _proto.hide = function hide(callback) {\n      var _this2 = this;\n\n      var tip = this.getTipElement();\n      var hideEvent = $.Event(this.constructor.Event.HIDE);\n\n      var complete = function complete() {\n        if (_this2._hoverState !== HoverState.SHOW && tip.parentNode) {\n          tip.parentNode.removeChild(tip);\n        }\n\n        _this2._cleanTipClass();\n\n        _this2.element.removeAttribute('aria-describedby');\n\n        $(_this2.element).trigger(_this2.constructor.Event.HIDDEN);\n\n        if (_this2._popper !== null) {\n          _this2._popper.destroy();\n        }\n\n        if (callback) {\n          callback();\n        }\n      };\n\n      $(this.element).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.SHOW); // If this is a touch-enabled device we remove the extra\n      // empty mouseover listeners we added for iOS support\n\n      if ('ontouchstart' in document.documentElement) {\n        $(document.body).children().off('mouseover', null, $.noop);\n      }\n\n      this._activeTrigger[Trigger.CLICK] = false;\n      this._activeTrigger[Trigger.FOCUS] = false;\n      this._activeTrigger[Trigger.HOVER] = false;\n\n      if ($(this.tip).hasClass(ClassName$6.FADE)) {\n        var transitionDuration = Util.getTransitionDurationFromElement(tip);\n        $(tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n\n      this._hoverState = '';\n    };\n\n    _proto.update = function update() {\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Protected\n    ;\n\n    _proto.isWithContent = function isWithContent() {\n      return Boolean(this.getTitle());\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var tip = this.getTipElement();\n      this.setElementContent($(tip.querySelectorAll(Selector$6.TOOLTIP_INNER)), this.getTitle());\n      $(tip).removeClass(ClassName$6.FADE + \" \" + ClassName$6.SHOW);\n    };\n\n    _proto.setElementContent = function setElementContent($element, content) {\n      if (typeof content === 'object' && (content.nodeType || content.jquery)) {\n        // Content is a DOM node or a jQuery\n        if (this.config.html) {\n          if (!$(content).parent().is($element)) {\n            $element.empty().append(content);\n          }\n        } else {\n          $element.text($(content).text());\n        }\n\n        return;\n      }\n\n      if (this.config.html) {\n        if (this.config.sanitize) {\n          content = sanitizeHtml(content, this.config.whiteList, this.config.sanitizeFn);\n        }\n\n        $element.html(content);\n      } else {\n        $element.text(content);\n      }\n    };\n\n    _proto.getTitle = function getTitle() {\n      var title = this.element.getAttribute('data-original-title');\n\n      if (!title) {\n        title = typeof this.config.title === 'function' ? this.config.title.call(this.element) : this.config.title;\n      }\n\n      return title;\n    } // Private\n    ;\n\n    _proto._getOffset = function _getOffset() {\n      var _this3 = this;\n\n      var offset = {};\n\n      if (typeof this.config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this3.config.offset(data.offsets, _this3.element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this.config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getContainer = function _getContainer() {\n      if (this.config.container === false) {\n        return document.body;\n      }\n\n      if (Util.isElement(this.config.container)) {\n        return $(this.config.container);\n      }\n\n      return $(document).find(this.config.container);\n    };\n\n    _proto._getAttachment = function _getAttachment(placement) {\n      return AttachmentMap$1[placement.toUpperCase()];\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this4 = this;\n\n      var triggers = this.config.trigger.split(' ');\n      triggers.forEach(function (trigger) {\n        if (trigger === 'click') {\n          $(_this4.element).on(_this4.constructor.Event.CLICK, _this4.config.selector, function (event) {\n            return _this4.toggle(event);\n          });\n        } else if (trigger !== Trigger.MANUAL) {\n          var eventIn = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSEENTER : _this4.constructor.Event.FOCUSIN;\n          var eventOut = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSELEAVE : _this4.constructor.Event.FOCUSOUT;\n          $(_this4.element).on(eventIn, _this4.config.selector, function (event) {\n            return _this4._enter(event);\n          }).on(eventOut, _this4.config.selector, function (event) {\n            return _this4._leave(event);\n          });\n        }\n      });\n      $(this.element).closest('.modal').on('hide.bs.modal', function () {\n        if (_this4.element) {\n          _this4.hide();\n        }\n      });\n\n      if (this.config.selector) {\n        this.config = _objectSpread({}, this.config, {\n          trigger: 'manual',\n          selector: ''\n        });\n      } else {\n        this._fixTitle();\n      }\n    };\n\n    _proto._fixTitle = function _fixTitle() {\n      var titleType = typeof this.element.getAttribute('data-original-title');\n\n      if (this.element.getAttribute('title') || titleType !== 'string') {\n        this.element.setAttribute('data-original-title', this.element.getAttribute('title') || '');\n        this.element.setAttribute('title', '');\n      }\n    };\n\n    _proto._enter = function _enter(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusin' ? Trigger.FOCUS : Trigger.HOVER] = true;\n      }\n\n      if ($(context.getTipElement()).hasClass(ClassName$6.SHOW) || context._hoverState === HoverState.SHOW) {\n        context._hoverState = HoverState.SHOW;\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.SHOW;\n\n      if (!context.config.delay || !context.config.delay.show) {\n        context.show();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.SHOW) {\n          context.show();\n        }\n      }, context.config.delay.show);\n    };\n\n    _proto._leave = function _leave(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusout' ? Trigger.FOCUS : Trigger.HOVER] = false;\n      }\n\n      if (context._isWithActiveTrigger()) {\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.OUT;\n\n      if (!context.config.delay || !context.config.delay.hide) {\n        context.hide();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.OUT) {\n          context.hide();\n        }\n      }, context.config.delay.hide);\n    };\n\n    _proto._isWithActiveTrigger = function _isWithActiveTrigger() {\n      for (var trigger in this._activeTrigger) {\n        if (this._activeTrigger[trigger]) {\n          return true;\n        }\n      }\n\n      return false;\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      var dataAttributes = $(this.element).data();\n      Object.keys(dataAttributes).forEach(function (dataAttr) {\n        if (DISALLOWED_ATTRIBUTES.indexOf(dataAttr) !== -1) {\n          delete dataAttributes[dataAttr];\n        }\n      });\n      config = _objectSpread({}, this.constructor.Default, dataAttributes, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.delay === 'number') {\n        config.delay = {\n          show: config.delay,\n          hide: config.delay\n        };\n      }\n\n      if (typeof config.title === 'number') {\n        config.title = config.title.toString();\n      }\n\n      if (typeof config.content === 'number') {\n        config.content = config.content.toString();\n      }\n\n      Util.typeCheckConfig(NAME$6, config, this.constructor.DefaultType);\n\n      if (config.sanitize) {\n        config.template = sanitizeHtml(config.template, config.whiteList, config.sanitizeFn);\n      }\n\n      return config;\n    };\n\n    _proto._getDelegateConfig = function _getDelegateConfig() {\n      var config = {};\n\n      if (this.config) {\n        for (var key in this.config) {\n          if (this.constructor.Default[key] !== this.config[key]) {\n            config[key] = this.config[key];\n          }\n        }\n      }\n\n      return config;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX);\n\n      if (tabClass !== null && tabClass.length) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    };\n\n    _proto._handlePopperPlacementChange = function _handlePopperPlacementChange(popperData) {\n      var popperInstance = popperData.instance;\n      this.tip = popperInstance.popper;\n\n      this._cleanTipClass();\n\n      this.addAttachmentClass(this._getAttachment(popperData.placement));\n    };\n\n    _proto._fixTransition = function _fixTransition() {\n      var tip = this.getTipElement();\n      var initConfigAnimation = this.config.animation;\n\n      if (tip.getAttribute('x-placement') !== null) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.FADE);\n      this.config.animation = false;\n      this.hide();\n      this.show();\n      this.config.animation = initConfigAnimation;\n    } // Static\n    ;\n\n    Tooltip._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$6);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Tooltip(this, _config);\n          $(this).data(DATA_KEY$6, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tooltip, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$6;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$4;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$6;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$6;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$6;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$6;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$4;\n      }\n    }]);\n\n    return Tooltip;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$6] = Tooltip._jQueryInterface;\n  $.fn[NAME$6].Constructor = Tooltip;\n\n  $.fn[NAME$6].noConflict = function () {\n    $.fn[NAME$6] = JQUERY_NO_CONFLICT$6;\n    return Tooltip._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$7 = 'popover';\n  var VERSION$7 = '4.3.1';\n  var DATA_KEY$7 = 'bs.popover';\n  var EVENT_KEY$7 = \".\" + DATA_KEY$7;\n  var JQUERY_NO_CONFLICT$7 = $.fn[NAME$7];\n  var CLASS_PREFIX$1 = 'bs-popover';\n  var BSCLS_PREFIX_REGEX$1 = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX$1 + \"\\\\S+\", 'g');\n\n  var Default$5 = _objectSpread({}, Tooltip.Default, {\n    placement: 'right',\n    trigger: 'click',\n    content: '',\n    template: '<div class=\"popover\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<h3 class=\"popover-header\"></h3>' + '<div class=\"popover-body\"></div></div>'\n  });\n\n  var DefaultType$5 = _objectSpread({}, Tooltip.DefaultType, {\n    content: '(string|element|function)'\n  });\n\n  var ClassName$7 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$7 = {\n    TITLE: '.popover-header',\n    CONTENT: '.popover-body'\n  };\n  var Event$7 = {\n    HIDE: \"hide\" + EVENT_KEY$7,\n    HIDDEN: \"hidden\" + EVENT_KEY$7,\n    SHOW: \"show\" + EVENT_KEY$7,\n    SHOWN: \"shown\" + EVENT_KEY$7,\n    INSERTED: \"inserted\" + EVENT_KEY$7,\n    CLICK: \"click\" + EVENT_KEY$7,\n    FOCUSIN: \"focusin\" + EVENT_KEY$7,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$7,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$7,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$7\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Popover =\n  /*#__PURE__*/\n  function (_Tooltip) {\n    _inheritsLoose(Popover, _Tooltip);\n\n    function Popover() {\n      return _Tooltip.apply(this, arguments) || this;\n    }\n\n    var _proto = Popover.prototype;\n\n    // Overrides\n    _proto.isWithContent = function isWithContent() {\n      return this.getTitle() || this._getContent();\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX$1 + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var $tip = $(this.getTipElement()); // We use append for html objects to maintain js events\n\n      this.setElementContent($tip.find(Selector$7.TITLE), this.getTitle());\n\n      var content = this._getContent();\n\n      if (typeof content === 'function') {\n        content = content.call(this.element);\n      }\n\n      this.setElementContent($tip.find(Selector$7.CONTENT), content);\n      $tip.removeClass(ClassName$7.FADE + \" \" + ClassName$7.SHOW);\n    } // Private\n    ;\n\n    _proto._getContent = function _getContent() {\n      return this.element.getAttribute('data-content') || this.config.content;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX$1);\n\n      if (tabClass !== null && tabClass.length > 0) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    } // Static\n    ;\n\n    Popover._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$7);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Popover(this, _config);\n          $(this).data(DATA_KEY$7, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Popover, null, [{\n      key: \"VERSION\",\n      // Getters\n      get: function get() {\n        return VERSION$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$5;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$7;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$7;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$7;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$7;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$5;\n      }\n    }]);\n\n    return Popover;\n  }(Tooltip);\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$7] = Popover._jQueryInterface;\n  $.fn[NAME$7].Constructor = Popover;\n\n  $.fn[NAME$7].noConflict = function () {\n    $.fn[NAME$7] = JQUERY_NO_CONFLICT$7;\n    return Popover._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$8 = 'scrollspy';\n  var VERSION$8 = '4.3.1';\n  var DATA_KEY$8 = 'bs.scrollspy';\n  var EVENT_KEY$8 = \".\" + DATA_KEY$8;\n  var DATA_API_KEY$6 = '.data-api';\n  var JQUERY_NO_CONFLICT$8 = $.fn[NAME$8];\n  var Default$6 = {\n    offset: 10,\n    method: 'auto',\n    target: ''\n  };\n  var DefaultType$6 = {\n    offset: 'number',\n    method: 'string',\n    target: '(string|element)'\n  };\n  var Event$8 = {\n    ACTIVATE: \"activate\" + EVENT_KEY$8,\n    SCROLL: \"scroll\" + EVENT_KEY$8,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$8 + DATA_API_KEY$6\n  };\n  var ClassName$8 = {\n    DROPDOWN_ITEM: 'dropdown-item',\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active'\n  };\n  var Selector$8 = {\n    DATA_SPY: '[data-spy=\"scroll\"]',\n    ACTIVE: '.active',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    NAV_LINKS: '.nav-link',\n    NAV_ITEMS: '.nav-item',\n    LIST_ITEMS: '.list-group-item',\n    DROPDOWN: '.dropdown',\n    DROPDOWN_ITEMS: '.dropdown-item',\n    DROPDOWN_TOGGLE: '.dropdown-toggle'\n  };\n  var OffsetMethod = {\n    OFFSET: 'offset',\n    POSITION: 'position'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var ScrollSpy =\n  /*#__PURE__*/\n  function () {\n    function ScrollSpy(element, config) {\n      var _this = this;\n\n      this._element = element;\n      this._scrollElement = element.tagName === 'BODY' ? window : element;\n      this._config = this._getConfig(config);\n      this._selector = this._config.target + \" \" + Selector$8.NAV_LINKS + \",\" + (this._config.target + \" \" + Selector$8.LIST_ITEMS + \",\") + (this._config.target + \" \" + Selector$8.DROPDOWN_ITEMS);\n      this._offsets = [];\n      this._targets = [];\n      this._activeTarget = null;\n      this._scrollHeight = 0;\n      $(this._scrollElement).on(Event$8.SCROLL, function (event) {\n        return _this._process(event);\n      });\n      this.refresh();\n\n      this._process();\n    } // Getters\n\n\n    var _proto = ScrollSpy.prototype;\n\n    // Public\n    _proto.refresh = function refresh() {\n      var _this2 = this;\n\n      var autoMethod = this._scrollElement === this._scrollElement.window ? OffsetMethod.OFFSET : OffsetMethod.POSITION;\n      var offsetMethod = this._config.method === 'auto' ? autoMethod : this._config.method;\n      var offsetBase = offsetMethod === OffsetMethod.POSITION ? this._getScrollTop() : 0;\n      this._offsets = [];\n      this._targets = [];\n      this._scrollHeight = this._getScrollHeight();\n      var targets = [].slice.call(document.querySelectorAll(this._selector));\n      targets.map(function (element) {\n        var target;\n        var targetSelector = Util.getSelectorFromElement(element);\n\n        if (targetSelector) {\n          target = document.querySelector(targetSelector);\n        }\n\n        if (target) {\n          var targetBCR = target.getBoundingClientRect();\n\n          if (targetBCR.width || targetBCR.height) {\n            // TODO (fat): remove sketch reliance on jQuery position/offset\n            return [$(target)[offsetMethod]().top + offsetBase, targetSelector];\n          }\n        }\n\n        return null;\n      }).filter(function (item) {\n        return item;\n      }).sort(function (a, b) {\n        return a[0] - b[0];\n      }).forEach(function (item) {\n        _this2._offsets.push(item[0]);\n\n        _this2._targets.push(item[1]);\n      });\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$8);\n      $(this._scrollElement).off(EVENT_KEY$8);\n      this._element = null;\n      this._scrollElement = null;\n      this._config = null;\n      this._selector = null;\n      this._offsets = null;\n      this._targets = null;\n      this._activeTarget = null;\n      this._scrollHeight = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$6, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.target !== 'string') {\n        var id = $(config.target).attr('id');\n\n        if (!id) {\n          id = Util.getUID(NAME$8);\n          $(config.target).attr('id', id);\n        }\n\n        config.target = \"#\" + id;\n      }\n\n      Util.typeCheckConfig(NAME$8, config, DefaultType$6);\n      return config;\n    };\n\n    _proto._getScrollTop = function _getScrollTop() {\n      return this._scrollElement === window ? this._scrollElement.pageYOffset : this._scrollElement.scrollTop;\n    };\n\n    _proto._getScrollHeight = function _getScrollHeight() {\n      return this._scrollElement.scrollHeight || Math.max(document.body.scrollHeight, document.documentElement.scrollHeight);\n    };\n\n    _proto._getOffsetHeight = function _getOffsetHeight() {\n      return this._scrollElement === window ? window.innerHeight : this._scrollElement.getBoundingClientRect().height;\n    };\n\n    _proto._process = function _process() {\n      var scrollTop = this._getScrollTop() + this._config.offset;\n\n      var scrollHeight = this._getScrollHeight();\n\n      var maxScroll = this._config.offset + scrollHeight - this._getOffsetHeight();\n\n      if (this._scrollHeight !== scrollHeight) {\n        this.refresh();\n      }\n\n      if (scrollTop >= maxScroll) {\n        var target = this._targets[this._targets.length - 1];\n\n        if (this._activeTarget !== target) {\n          this._activate(target);\n        }\n\n        return;\n      }\n\n      if (this._activeTarget && scrollTop < this._offsets[0] && this._offsets[0] > 0) {\n        this._activeTarget = null;\n\n        this._clear();\n\n        return;\n      }\n\n      var offsetLength = this._offsets.length;\n\n      for (var i = offsetLength; i--;) {\n        var isActiveTarget = this._activeTarget !== this._targets[i] && scrollTop >= this._offsets[i] && (typeof this._offsets[i + 1] === 'undefined' || scrollTop < this._offsets[i + 1]);\n\n        if (isActiveTarget) {\n          this._activate(this._targets[i]);\n        }\n      }\n    };\n\n    _proto._activate = function _activate(target) {\n      this._activeTarget = target;\n\n      this._clear();\n\n      var queries = this._selector.split(',').map(function (selector) {\n        return selector + \"[data-target=\\\"\" + target + \"\\\"],\" + selector + \"[href=\\\"\" + target + \"\\\"]\";\n      });\n\n      var $link = $([].slice.call(document.querySelectorAll(queries.join(','))));\n\n      if ($link.hasClass(ClassName$8.DROPDOWN_ITEM)) {\n        $link.closest(Selector$8.DROPDOWN).find(Selector$8.DROPDOWN_TOGGLE).addClass(ClassName$8.ACTIVE);\n        $link.addClass(ClassName$8.ACTIVE);\n      } else {\n        // Set triggered link as active\n        $link.addClass(ClassName$8.ACTIVE); // Set triggered links parents as active\n        // With both <ul> and <nav> markup a parent is the previous sibling of any nav ancestor\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_LINKS + \", \" + Selector$8.LIST_ITEMS).addClass(ClassName$8.ACTIVE); // Handle special case when .nav-link is inside .nav-item\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_ITEMS).children(Selector$8.NAV_LINKS).addClass(ClassName$8.ACTIVE);\n      }\n\n      $(this._scrollElement).trigger(Event$8.ACTIVATE, {\n        relatedTarget: target\n      });\n    };\n\n    _proto._clear = function _clear() {\n      [].slice.call(document.querySelectorAll(this._selector)).filter(function (node) {\n        return node.classList.contains(ClassName$8.ACTIVE);\n      }).forEach(function (node) {\n        return node.classList.remove(ClassName$8.ACTIVE);\n      });\n    } // Static\n    ;\n\n    ScrollSpy._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$8);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new ScrollSpy(this, _config);\n          $(this).data(DATA_KEY$8, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(ScrollSpy, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$8;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$6;\n      }\n    }]);\n\n    return ScrollSpy;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(window).on(Event$8.LOAD_DATA_API, function () {\n    var scrollSpys = [].slice.call(document.querySelectorAll(Selector$8.DATA_SPY));\n    var scrollSpysLength = scrollSpys.length;\n\n    for (var i = scrollSpysLength; i--;) {\n      var $spy = $(scrollSpys[i]);\n\n      ScrollSpy._jQueryInterface.call($spy, $spy.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$8] = ScrollSpy._jQueryInterface;\n  $.fn[NAME$8].Constructor = ScrollSpy;\n\n  $.fn[NAME$8].noConflict = function () {\n    $.fn[NAME$8] = JQUERY_NO_CONFLICT$8;\n    return ScrollSpy._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$9 = 'tab';\n  var VERSION$9 = '4.3.1';\n  var DATA_KEY$9 = 'bs.tab';\n  var EVENT_KEY$9 = \".\" + DATA_KEY$9;\n  var DATA_API_KEY$7 = '.data-api';\n  var JQUERY_NO_CONFLICT$9 = $.fn[NAME$9];\n  var Event$9 = {\n    HIDE: \"hide\" + EVENT_KEY$9,\n    HIDDEN: \"hidden\" + EVENT_KEY$9,\n    SHOW: \"show\" + EVENT_KEY$9,\n    SHOWN: \"shown\" + EVENT_KEY$9,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$9 + DATA_API_KEY$7\n  };\n  var ClassName$9 = {\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active',\n    DISABLED: 'disabled',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$9 = {\n    DROPDOWN: '.dropdown',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    ACTIVE: '.active',\n    ACTIVE_UL: '> li > .active',\n    DATA_TOGGLE: '[data-toggle=\"tab\"], [data-toggle=\"pill\"], [data-toggle=\"list\"]',\n    DROPDOWN_TOGGLE: '.dropdown-toggle',\n    DROPDOWN_ACTIVE_CHILD: '> .dropdown-menu .active'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tab =\n  /*#__PURE__*/\n  function () {\n    function Tab(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Tab.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._element.parentNode && this._element.parentNode.nodeType === Node.ELEMENT_NODE && $(this._element).hasClass(ClassName$9.ACTIVE) || $(this._element).hasClass(ClassName$9.DISABLED)) {\n        return;\n      }\n\n      var target;\n      var previous;\n      var listElement = $(this._element).closest(Selector$9.NAV_LIST_GROUP)[0];\n      var selector = Util.getSelectorFromElement(this._element);\n\n      if (listElement) {\n        var itemSelector = listElement.nodeName === 'UL' || listElement.nodeName === 'OL' ? Selector$9.ACTIVE_UL : Selector$9.ACTIVE;\n        previous = $.makeArray($(listElement).find(itemSelector));\n        previous = previous[previous.length - 1];\n      }\n\n      var hideEvent = $.Event(Event$9.HIDE, {\n        relatedTarget: this._element\n      });\n      var showEvent = $.Event(Event$9.SHOW, {\n        relatedTarget: previous\n      });\n\n      if (previous) {\n        $(previous).trigger(hideEvent);\n      }\n\n      $(this._element).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented() || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (selector) {\n        target = document.querySelector(selector);\n      }\n\n      this._activate(this._element, listElement);\n\n      var complete = function complete() {\n        var hiddenEvent = $.Event(Event$9.HIDDEN, {\n          relatedTarget: _this._element\n        });\n        var shownEvent = $.Event(Event$9.SHOWN, {\n          relatedTarget: previous\n        });\n        $(previous).trigger(hiddenEvent);\n        $(_this._element).trigger(shownEvent);\n      };\n\n      if (target) {\n        this._activate(target, target.parentNode, complete);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$9);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._activate = function _activate(element, container, callback) {\n      var _this2 = this;\n\n      var activeElements = container && (container.nodeName === 'UL' || container.nodeName === 'OL') ? $(container).find(Selector$9.ACTIVE_UL) : $(container).children(Selector$9.ACTIVE);\n      var active = activeElements[0];\n      var isTransitioning = callback && active && $(active).hasClass(ClassName$9.FADE);\n\n      var complete = function complete() {\n        return _this2._transitionComplete(element, active, callback);\n      };\n\n      if (active && isTransitioning) {\n        var transitionDuration = Util.getTransitionDurationFromElement(active);\n        $(active).removeClass(ClassName$9.SHOW).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto._transitionComplete = function _transitionComplete(element, active, callback) {\n      if (active) {\n        $(active).removeClass(ClassName$9.ACTIVE);\n        var dropdownChild = $(active.parentNode).find(Selector$9.DROPDOWN_ACTIVE_CHILD)[0];\n\n        if (dropdownChild) {\n          $(dropdownChild).removeClass(ClassName$9.ACTIVE);\n        }\n\n        if (active.getAttribute('role') === 'tab') {\n          active.setAttribute('aria-selected', false);\n        }\n      }\n\n      $(element).addClass(ClassName$9.ACTIVE);\n\n      if (element.getAttribute('role') === 'tab') {\n        element.setAttribute('aria-selected', true);\n      }\n\n      Util.reflow(element);\n\n      if (element.classList.contains(ClassName$9.FADE)) {\n        element.classList.add(ClassName$9.SHOW);\n      }\n\n      if (element.parentNode && $(element.parentNode).hasClass(ClassName$9.DROPDOWN_MENU)) {\n        var dropdownElement = $(element).closest(Selector$9.DROPDOWN)[0];\n\n        if (dropdownElement) {\n          var dropdownToggleList = [].slice.call(dropdownElement.querySelectorAll(Selector$9.DROPDOWN_TOGGLE));\n          $(dropdownToggleList).addClass(ClassName$9.ACTIVE);\n        }\n\n        element.setAttribute('aria-expanded', true);\n      }\n\n      if (callback) {\n        callback();\n      }\n    } // Static\n    ;\n\n    Tab._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$9);\n\n        if (!data) {\n          data = new Tab(this);\n          $this.data(DATA_KEY$9, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tab, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$9;\n      }\n    }]);\n\n    return Tab;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$9.CLICK_DATA_API, Selector$9.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n\n    Tab._jQueryInterface.call($(this), 'show');\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$9] = Tab._jQueryInterface;\n  $.fn[NAME$9].Constructor = Tab;\n\n  $.fn[NAME$9].noConflict = function () {\n    $.fn[NAME$9] = JQUERY_NO_CONFLICT$9;\n    return Tab._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$a = 'toast';\n  var VERSION$a = '4.3.1';\n  var DATA_KEY$a = 'bs.toast';\n  var EVENT_KEY$a = \".\" + DATA_KEY$a;\n  var JQUERY_NO_CONFLICT$a = $.fn[NAME$a];\n  var Event$a = {\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$a,\n    HIDE: \"hide\" + EVENT_KEY$a,\n    HIDDEN: \"hidden\" + EVENT_KEY$a,\n    SHOW: \"show\" + EVENT_KEY$a,\n    SHOWN: \"shown\" + EVENT_KEY$a\n  };\n  var ClassName$a = {\n    FADE: 'fade',\n    HIDE: 'hide',\n    SHOW: 'show',\n    SHOWING: 'showing'\n  };\n  var DefaultType$7 = {\n    animation: 'boolean',\n    autohide: 'boolean',\n    delay: 'number'\n  };\n  var Default$7 = {\n    animation: true,\n    autohide: true,\n    delay: 500\n  };\n  var Selector$a = {\n    DATA_DISMISS: '[data-dismiss=\"toast\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Toast =\n  /*#__PURE__*/\n  function () {\n    function Toast(element, config) {\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._timeout = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Toast.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      $(this._element).trigger(Event$a.SHOW);\n\n      if (this._config.animation) {\n        this._element.classList.add(ClassName$a.FADE);\n      }\n\n      var complete = function complete() {\n        _this._element.classList.remove(ClassName$a.SHOWING);\n\n        _this._element.classList.add(ClassName$a.SHOW);\n\n        $(_this._element).trigger(Event$a.SHOWN);\n\n        if (_this._config.autohide) {\n          _this.hide();\n        }\n      };\n\n      this._element.classList.remove(ClassName$a.HIDE);\n\n      this._element.classList.add(ClassName$a.SHOWING);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.hide = function hide(withoutTimeout) {\n      var _this2 = this;\n\n      if (!this._element.classList.contains(ClassName$a.SHOW)) {\n        return;\n      }\n\n      $(this._element).trigger(Event$a.HIDE);\n\n      if (withoutTimeout) {\n        this._close();\n      } else {\n        this._timeout = setTimeout(function () {\n          _this2._close();\n        }, this._config.delay);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      this._timeout = null;\n\n      if (this._element.classList.contains(ClassName$a.SHOW)) {\n        this._element.classList.remove(ClassName$a.SHOW);\n      }\n\n      $(this._element).off(Event$a.CLICK_DISMISS);\n      $.removeData(this._element, DATA_KEY$a);\n      this._element = null;\n      this._config = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$7, $(this._element).data(), typeof config === 'object' && config ? config : {});\n      Util.typeCheckConfig(NAME$a, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this3 = this;\n\n      $(this._element).on(Event$a.CLICK_DISMISS, Selector$a.DATA_DISMISS, function () {\n        return _this3.hide(true);\n      });\n    };\n\n    _proto._close = function _close() {\n      var _this4 = this;\n\n      var complete = function complete() {\n        _this4._element.classList.add(ClassName$a.HIDE);\n\n        $(_this4._element).trigger(Event$a.HIDDEN);\n      };\n\n      this._element.classList.remove(ClassName$a.SHOW);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    } // Static\n    ;\n\n    Toast._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY$a);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new Toast(this, _config);\n          $element.data(DATA_KEY$a, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](this);\n        }\n      });\n    };\n\n    _createClass(Toast, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$a;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$7;\n      }\n    }]);\n\n    return Toast;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$a] = Toast._jQueryInterface;\n  $.fn[NAME$a].Constructor = Toast;\n\n  $.fn[NAME$a].noConflict = function () {\n    $.fn[NAME$a] = JQUERY_NO_CONFLICT$a;\n    return Toast._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): index.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n\n  (function () {\n    if (typeof $ === 'undefined') {\n      throw new TypeError('Bootstrap\\'s JavaScript requires jQuery. jQuery must be included before Bootstrap\\'s JavaScript.');\n    }\n\n    var version = $.fn.jquery.split(' ')[0].split('.');\n    var minMajor = 1;\n    var ltMajor = 2;\n    var minMinor = 9;\n    var minPatch = 1;\n    var maxMajor = 4;\n\n    if (version[0] < ltMajor && version[1] < minMinor || version[0] === minMajor && version[1] === minMinor && version[2] < minPatch || version[0] >= maxMajor) {\n      throw new Error('Bootstrap\\'s JavaScript requires at least jQuery v1.9.1 but less than v4.0.0');\n    }\n  })();\n\n  exports.Util = Util;\n  exports.Alert = Alert;\n  exports.Button = Button;\n  exports.Carousel = Carousel;\n  exports.Collapse = Collapse;\n  exports.Dropdown = Dropdown;\n  exports.Modal = Modal;\n  exports.Popover = Popover;\n  exports.Scrollspy = ScrollSpy;\n  exports.Tab = Tab;\n  exports.Toast = Toast;\n  exports.Tooltip = Tooltip;\n\n  Object.defineProperty(exports, '__esModule', { value: true });\n\n}));\n//# sourceMappingURL=bootstrap.bundle.js.map\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/bootstrap/js/bootstrap.js",
    "content": "/*!\n  * Bootstrap v4.3.1 (https://getbootstrap.com/)\n  * Copyright 2011-2019 The Bootstrap Authors (https://github.com/twbs/bootstrap/graphs/contributors)\n  * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n  */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? factory(exports, require('jquery'), require('popper.js')) :\n  typeof define === 'function' && define.amd ? define(['exports', 'jquery', 'popper.js'], factory) :\n  (global = global || self, factory(global.bootstrap = {}, global.jQuery, global.Popper));\n}(this, function (exports, $, Popper) { 'use strict';\n\n  $ = $ && $.hasOwnProperty('default') ? $['default'] : $;\n  Popper = Popper && Popper.hasOwnProperty('default') ? Popper['default'] : Popper;\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _inheritsLoose(subClass, superClass) {\n    subClass.prototype = Object.create(superClass.prototype);\n    subClass.prototype.constructor = subClass;\n    subClass.__proto__ = superClass;\n  }\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): util.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  /**\n   * ------------------------------------------------------------------------\n   * Private TransitionEnd Helpers\n   * ------------------------------------------------------------------------\n   */\n\n  var TRANSITION_END = 'transitionend';\n  var MAX_UID = 1000000;\n  var MILLISECONDS_MULTIPLIER = 1000; // Shoutout AngusCroll (https://goo.gl/pxwQGp)\n\n  function toType(obj) {\n    return {}.toString.call(obj).match(/\\s([a-z]+)/i)[1].toLowerCase();\n  }\n\n  function getSpecialTransitionEndEvent() {\n    return {\n      bindType: TRANSITION_END,\n      delegateType: TRANSITION_END,\n      handle: function handle(event) {\n        if ($(event.target).is(this)) {\n          return event.handleObj.handler.apply(this, arguments); // eslint-disable-line prefer-rest-params\n        }\n\n        return undefined; // eslint-disable-line no-undefined\n      }\n    };\n  }\n\n  function transitionEndEmulator(duration) {\n    var _this = this;\n\n    var called = false;\n    $(this).one(Util.TRANSITION_END, function () {\n      called = true;\n    });\n    setTimeout(function () {\n      if (!called) {\n        Util.triggerTransitionEnd(_this);\n      }\n    }, duration);\n    return this;\n  }\n\n  function setTransitionEndSupport() {\n    $.fn.emulateTransitionEnd = transitionEndEmulator;\n    $.event.special[Util.TRANSITION_END] = getSpecialTransitionEndEvent();\n  }\n  /**\n   * --------------------------------------------------------------------------\n   * Public Util Api\n   * --------------------------------------------------------------------------\n   */\n\n\n  var Util = {\n    TRANSITION_END: 'bsTransitionEnd',\n    getUID: function getUID(prefix) {\n      do {\n        // eslint-disable-next-line no-bitwise\n        prefix += ~~(Math.random() * MAX_UID); // \"~~\" acts like a faster Math.floor() here\n      } while (document.getElementById(prefix));\n\n      return prefix;\n    },\n    getSelectorFromElement: function getSelectorFromElement(element) {\n      var selector = element.getAttribute('data-target');\n\n      if (!selector || selector === '#') {\n        var hrefAttr = element.getAttribute('href');\n        selector = hrefAttr && hrefAttr !== '#' ? hrefAttr.trim() : '';\n      }\n\n      try {\n        return document.querySelector(selector) ? selector : null;\n      } catch (err) {\n        return null;\n      }\n    },\n    getTransitionDurationFromElement: function getTransitionDurationFromElement(element) {\n      if (!element) {\n        return 0;\n      } // Get transition-duration of the element\n\n\n      var transitionDuration = $(element).css('transition-duration');\n      var transitionDelay = $(element).css('transition-delay');\n      var floatTransitionDuration = parseFloat(transitionDuration);\n      var floatTransitionDelay = parseFloat(transitionDelay); // Return 0 if element or transition duration is not found\n\n      if (!floatTransitionDuration && !floatTransitionDelay) {\n        return 0;\n      } // If multiple durations are defined, take the first\n\n\n      transitionDuration = transitionDuration.split(',')[0];\n      transitionDelay = transitionDelay.split(',')[0];\n      return (parseFloat(transitionDuration) + parseFloat(transitionDelay)) * MILLISECONDS_MULTIPLIER;\n    },\n    reflow: function reflow(element) {\n      return element.offsetHeight;\n    },\n    triggerTransitionEnd: function triggerTransitionEnd(element) {\n      $(element).trigger(TRANSITION_END);\n    },\n    // TODO: Remove in v5\n    supportsTransitionEnd: function supportsTransitionEnd() {\n      return Boolean(TRANSITION_END);\n    },\n    isElement: function isElement(obj) {\n      return (obj[0] || obj).nodeType;\n    },\n    typeCheckConfig: function typeCheckConfig(componentName, config, configTypes) {\n      for (var property in configTypes) {\n        if (Object.prototype.hasOwnProperty.call(configTypes, property)) {\n          var expectedTypes = configTypes[property];\n          var value = config[property];\n          var valueType = value && Util.isElement(value) ? 'element' : toType(value);\n\n          if (!new RegExp(expectedTypes).test(valueType)) {\n            throw new Error(componentName.toUpperCase() + \": \" + (\"Option \\\"\" + property + \"\\\" provided type \\\"\" + valueType + \"\\\" \") + (\"but expected type \\\"\" + expectedTypes + \"\\\".\"));\n          }\n        }\n      }\n    },\n    findShadowRoot: function findShadowRoot(element) {\n      if (!document.documentElement.attachShadow) {\n        return null;\n      } // Can find the shadow root otherwise it'll return the document\n\n\n      if (typeof element.getRootNode === 'function') {\n        var root = element.getRootNode();\n        return root instanceof ShadowRoot ? root : null;\n      }\n\n      if (element instanceof ShadowRoot) {\n        return element;\n      } // when we don't find a shadow root\n\n\n      if (!element.parentNode) {\n        return null;\n      }\n\n      return Util.findShadowRoot(element.parentNode);\n    }\n  };\n  setTransitionEndSupport();\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME = 'alert';\n  var VERSION = '4.3.1';\n  var DATA_KEY = 'bs.alert';\n  var EVENT_KEY = \".\" + DATA_KEY;\n  var DATA_API_KEY = '.data-api';\n  var JQUERY_NO_CONFLICT = $.fn[NAME];\n  var Selector = {\n    DISMISS: '[data-dismiss=\"alert\"]'\n  };\n  var Event = {\n    CLOSE: \"close\" + EVENT_KEY,\n    CLOSED: \"closed\" + EVENT_KEY,\n    CLICK_DATA_API: \"click\" + EVENT_KEY + DATA_API_KEY\n  };\n  var ClassName = {\n    ALERT: 'alert',\n    FADE: 'fade',\n    SHOW: 'show'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Alert =\n  /*#__PURE__*/\n  function () {\n    function Alert(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Alert.prototype;\n\n    // Public\n    _proto.close = function close(element) {\n      var rootElement = this._element;\n\n      if (element) {\n        rootElement = this._getRootElement(element);\n      }\n\n      var customEvent = this._triggerCloseEvent(rootElement);\n\n      if (customEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._removeElement(rootElement);\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._getRootElement = function _getRootElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      var parent = false;\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      if (!parent) {\n        parent = $(element).closest(\".\" + ClassName.ALERT)[0];\n      }\n\n      return parent;\n    };\n\n    _proto._triggerCloseEvent = function _triggerCloseEvent(element) {\n      var closeEvent = $.Event(Event.CLOSE);\n      $(element).trigger(closeEvent);\n      return closeEvent;\n    };\n\n    _proto._removeElement = function _removeElement(element) {\n      var _this = this;\n\n      $(element).removeClass(ClassName.SHOW);\n\n      if (!$(element).hasClass(ClassName.FADE)) {\n        this._destroyElement(element);\n\n        return;\n      }\n\n      var transitionDuration = Util.getTransitionDurationFromElement(element);\n      $(element).one(Util.TRANSITION_END, function (event) {\n        return _this._destroyElement(element, event);\n      }).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto._destroyElement = function _destroyElement(element) {\n      $(element).detach().trigger(Event.CLOSED).remove();\n    } // Static\n    ;\n\n    Alert._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY);\n\n        if (!data) {\n          data = new Alert(this);\n          $element.data(DATA_KEY, data);\n        }\n\n        if (config === 'close') {\n          data[config](this);\n        }\n      });\n    };\n\n    Alert._handleDismiss = function _handleDismiss(alertInstance) {\n      return function (event) {\n        if (event) {\n          event.preventDefault();\n        }\n\n        alertInstance.close(this);\n      };\n    };\n\n    _createClass(Alert, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION;\n      }\n    }]);\n\n    return Alert;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event.CLICK_DATA_API, Selector.DISMISS, Alert._handleDismiss(new Alert()));\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME] = Alert._jQueryInterface;\n  $.fn[NAME].Constructor = Alert;\n\n  $.fn[NAME].noConflict = function () {\n    $.fn[NAME] = JQUERY_NO_CONFLICT;\n    return Alert._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$1 = 'button';\n  var VERSION$1 = '4.3.1';\n  var DATA_KEY$1 = 'bs.button';\n  var EVENT_KEY$1 = \".\" + DATA_KEY$1;\n  var DATA_API_KEY$1 = '.data-api';\n  var JQUERY_NO_CONFLICT$1 = $.fn[NAME$1];\n  var ClassName$1 = {\n    ACTIVE: 'active',\n    BUTTON: 'btn',\n    FOCUS: 'focus'\n  };\n  var Selector$1 = {\n    DATA_TOGGLE_CARROT: '[data-toggle^=\"button\"]',\n    DATA_TOGGLE: '[data-toggle=\"buttons\"]',\n    INPUT: 'input:not([type=\"hidden\"])',\n    ACTIVE: '.active',\n    BUTTON: '.btn'\n  };\n  var Event$1 = {\n    CLICK_DATA_API: \"click\" + EVENT_KEY$1 + DATA_API_KEY$1,\n    FOCUS_BLUR_DATA_API: \"focus\" + EVENT_KEY$1 + DATA_API_KEY$1 + \" \" + (\"blur\" + EVENT_KEY$1 + DATA_API_KEY$1)\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Button =\n  /*#__PURE__*/\n  function () {\n    function Button(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Button.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      var triggerChangeEvent = true;\n      var addAriaPressed = true;\n      var rootElement = $(this._element).closest(Selector$1.DATA_TOGGLE)[0];\n\n      if (rootElement) {\n        var input = this._element.querySelector(Selector$1.INPUT);\n\n        if (input) {\n          if (input.type === 'radio') {\n            if (input.checked && this._element.classList.contains(ClassName$1.ACTIVE)) {\n              triggerChangeEvent = false;\n            } else {\n              var activeElement = rootElement.querySelector(Selector$1.ACTIVE);\n\n              if (activeElement) {\n                $(activeElement).removeClass(ClassName$1.ACTIVE);\n              }\n            }\n          }\n\n          if (triggerChangeEvent) {\n            if (input.hasAttribute('disabled') || rootElement.hasAttribute('disabled') || input.classList.contains('disabled') || rootElement.classList.contains('disabled')) {\n              return;\n            }\n\n            input.checked = !this._element.classList.contains(ClassName$1.ACTIVE);\n            $(input).trigger('change');\n          }\n\n          input.focus();\n          addAriaPressed = false;\n        }\n      }\n\n      if (addAriaPressed) {\n        this._element.setAttribute('aria-pressed', !this._element.classList.contains(ClassName$1.ACTIVE));\n      }\n\n      if (triggerChangeEvent) {\n        $(this._element).toggleClass(ClassName$1.ACTIVE);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$1);\n      this._element = null;\n    } // Static\n    ;\n\n    Button._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$1);\n\n        if (!data) {\n          data = new Button(this);\n          $(this).data(DATA_KEY$1, data);\n        }\n\n        if (config === 'toggle') {\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Button, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$1;\n      }\n    }]);\n\n    return Button;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$1.CLICK_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    event.preventDefault();\n    var button = event.target;\n\n    if (!$(button).hasClass(ClassName$1.BUTTON)) {\n      button = $(button).closest(Selector$1.BUTTON);\n    }\n\n    Button._jQueryInterface.call($(button), 'toggle');\n  }).on(Event$1.FOCUS_BLUR_DATA_API, Selector$1.DATA_TOGGLE_CARROT, function (event) {\n    var button = $(event.target).closest(Selector$1.BUTTON)[0];\n    $(button).toggleClass(ClassName$1.FOCUS, /^focus(in)?$/.test(event.type));\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$1] = Button._jQueryInterface;\n  $.fn[NAME$1].Constructor = Button;\n\n  $.fn[NAME$1].noConflict = function () {\n    $.fn[NAME$1] = JQUERY_NO_CONFLICT$1;\n    return Button._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$2 = 'carousel';\n  var VERSION$2 = '4.3.1';\n  var DATA_KEY$2 = 'bs.carousel';\n  var EVENT_KEY$2 = \".\" + DATA_KEY$2;\n  var DATA_API_KEY$2 = '.data-api';\n  var JQUERY_NO_CONFLICT$2 = $.fn[NAME$2];\n  var ARROW_LEFT_KEYCODE = 37; // KeyboardEvent.which value for left arrow key\n\n  var ARROW_RIGHT_KEYCODE = 39; // KeyboardEvent.which value for right arrow key\n\n  var TOUCHEVENT_COMPAT_WAIT = 500; // Time for mouse compat events to fire after touch\n\n  var SWIPE_THRESHOLD = 40;\n  var Default = {\n    interval: 5000,\n    keyboard: true,\n    slide: false,\n    pause: 'hover',\n    wrap: true,\n    touch: true\n  };\n  var DefaultType = {\n    interval: '(number|boolean)',\n    keyboard: 'boolean',\n    slide: '(boolean|string)',\n    pause: '(string|boolean)',\n    wrap: 'boolean',\n    touch: 'boolean'\n  };\n  var Direction = {\n    NEXT: 'next',\n    PREV: 'prev',\n    LEFT: 'left',\n    RIGHT: 'right'\n  };\n  var Event$2 = {\n    SLIDE: \"slide\" + EVENT_KEY$2,\n    SLID: \"slid\" + EVENT_KEY$2,\n    KEYDOWN: \"keydown\" + EVENT_KEY$2,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$2,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$2,\n    TOUCHSTART: \"touchstart\" + EVENT_KEY$2,\n    TOUCHMOVE: \"touchmove\" + EVENT_KEY$2,\n    TOUCHEND: \"touchend\" + EVENT_KEY$2,\n    POINTERDOWN: \"pointerdown\" + EVENT_KEY$2,\n    POINTERUP: \"pointerup\" + EVENT_KEY$2,\n    DRAG_START: \"dragstart\" + EVENT_KEY$2,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$2 + DATA_API_KEY$2,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$2 + DATA_API_KEY$2\n  };\n  var ClassName$2 = {\n    CAROUSEL: 'carousel',\n    ACTIVE: 'active',\n    SLIDE: 'slide',\n    RIGHT: 'carousel-item-right',\n    LEFT: 'carousel-item-left',\n    NEXT: 'carousel-item-next',\n    PREV: 'carousel-item-prev',\n    ITEM: 'carousel-item',\n    POINTER_EVENT: 'pointer-event'\n  };\n  var Selector$2 = {\n    ACTIVE: '.active',\n    ACTIVE_ITEM: '.active.carousel-item',\n    ITEM: '.carousel-item',\n    ITEM_IMG: '.carousel-item img',\n    NEXT_PREV: '.carousel-item-next, .carousel-item-prev',\n    INDICATORS: '.carousel-indicators',\n    DATA_SLIDE: '[data-slide], [data-slide-to]',\n    DATA_RIDE: '[data-ride=\"carousel\"]'\n  };\n  var PointerType = {\n    TOUCH: 'touch',\n    PEN: 'pen'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Carousel =\n  /*#__PURE__*/\n  function () {\n    function Carousel(element, config) {\n      this._items = null;\n      this._interval = null;\n      this._activeElement = null;\n      this._isPaused = false;\n      this._isSliding = false;\n      this.touchTimeout = null;\n      this.touchStartX = 0;\n      this.touchDeltaX = 0;\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._indicatorsElement = this._element.querySelector(Selector$2.INDICATORS);\n      this._touchSupported = 'ontouchstart' in document.documentElement || navigator.maxTouchPoints > 0;\n      this._pointerEvent = Boolean(window.PointerEvent || window.MSPointerEvent);\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Carousel.prototype;\n\n    // Public\n    _proto.next = function next() {\n      if (!this._isSliding) {\n        this._slide(Direction.NEXT);\n      }\n    };\n\n    _proto.nextWhenVisible = function nextWhenVisible() {\n      // Don't call next when the page isn't visible\n      // or the carousel or its parent isn't visible\n      if (!document.hidden && $(this._element).is(':visible') && $(this._element).css('visibility') !== 'hidden') {\n        this.next();\n      }\n    };\n\n    _proto.prev = function prev() {\n      if (!this._isSliding) {\n        this._slide(Direction.PREV);\n      }\n    };\n\n    _proto.pause = function pause(event) {\n      if (!event) {\n        this._isPaused = true;\n      }\n\n      if (this._element.querySelector(Selector$2.NEXT_PREV)) {\n        Util.triggerTransitionEnd(this._element);\n        this.cycle(true);\n      }\n\n      clearInterval(this._interval);\n      this._interval = null;\n    };\n\n    _proto.cycle = function cycle(event) {\n      if (!event) {\n        this._isPaused = false;\n      }\n\n      if (this._interval) {\n        clearInterval(this._interval);\n        this._interval = null;\n      }\n\n      if (this._config.interval && !this._isPaused) {\n        this._interval = setInterval((document.visibilityState ? this.nextWhenVisible : this.next).bind(this), this._config.interval);\n      }\n    };\n\n    _proto.to = function to(index) {\n      var _this = this;\n\n      this._activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeIndex = this._getItemIndex(this._activeElement);\n\n      if (index > this._items.length - 1 || index < 0) {\n        return;\n      }\n\n      if (this._isSliding) {\n        $(this._element).one(Event$2.SLID, function () {\n          return _this.to(index);\n        });\n        return;\n      }\n\n      if (activeIndex === index) {\n        this.pause();\n        this.cycle();\n        return;\n      }\n\n      var direction = index > activeIndex ? Direction.NEXT : Direction.PREV;\n\n      this._slide(direction, this._items[index]);\n    };\n\n    _proto.dispose = function dispose() {\n      $(this._element).off(EVENT_KEY$2);\n      $.removeData(this._element, DATA_KEY$2);\n      this._items = null;\n      this._config = null;\n      this._element = null;\n      this._interval = null;\n      this._isPaused = null;\n      this._isSliding = null;\n      this._activeElement = null;\n      this._indicatorsElement = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default, config);\n      Util.typeCheckConfig(NAME$2, config, DefaultType);\n      return config;\n    };\n\n    _proto._handleSwipe = function _handleSwipe() {\n      var absDeltax = Math.abs(this.touchDeltaX);\n\n      if (absDeltax <= SWIPE_THRESHOLD) {\n        return;\n      }\n\n      var direction = absDeltax / this.touchDeltaX; // swipe left\n\n      if (direction > 0) {\n        this.prev();\n      } // swipe right\n\n\n      if (direction < 0) {\n        this.next();\n      }\n    };\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this2 = this;\n\n      if (this._config.keyboard) {\n        $(this._element).on(Event$2.KEYDOWN, function (event) {\n          return _this2._keydown(event);\n        });\n      }\n\n      if (this._config.pause === 'hover') {\n        $(this._element).on(Event$2.MOUSEENTER, function (event) {\n          return _this2.pause(event);\n        }).on(Event$2.MOUSELEAVE, function (event) {\n          return _this2.cycle(event);\n        });\n      }\n\n      if (this._config.touch) {\n        this._addTouchEventListeners();\n      }\n    };\n\n    _proto._addTouchEventListeners = function _addTouchEventListeners() {\n      var _this3 = this;\n\n      if (!this._touchSupported) {\n        return;\n      }\n\n      var start = function start(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchStartX = event.originalEvent.clientX;\n        } else if (!_this3._pointerEvent) {\n          _this3.touchStartX = event.originalEvent.touches[0].clientX;\n        }\n      };\n\n      var move = function move(event) {\n        // ensure swiping with one touch and not pinching\n        if (event.originalEvent.touches && event.originalEvent.touches.length > 1) {\n          _this3.touchDeltaX = 0;\n        } else {\n          _this3.touchDeltaX = event.originalEvent.touches[0].clientX - _this3.touchStartX;\n        }\n      };\n\n      var end = function end(event) {\n        if (_this3._pointerEvent && PointerType[event.originalEvent.pointerType.toUpperCase()]) {\n          _this3.touchDeltaX = event.originalEvent.clientX - _this3.touchStartX;\n        }\n\n        _this3._handleSwipe();\n\n        if (_this3._config.pause === 'hover') {\n          // If it's a touch-enabled device, mouseenter/leave are fired as\n          // part of the mouse compatibility events on first tap - the carousel\n          // would stop cycling until user tapped out of it;\n          // here, we listen for touchend, explicitly pause the carousel\n          // (as if it's the second time we tap on it, mouseenter compat event\n          // is NOT fired) and after a timeout (to allow for mouse compatibility\n          // events to fire) we explicitly restart cycling\n          _this3.pause();\n\n          if (_this3.touchTimeout) {\n            clearTimeout(_this3.touchTimeout);\n          }\n\n          _this3.touchTimeout = setTimeout(function (event) {\n            return _this3.cycle(event);\n          }, TOUCHEVENT_COMPAT_WAIT + _this3._config.interval);\n        }\n      };\n\n      $(this._element.querySelectorAll(Selector$2.ITEM_IMG)).on(Event$2.DRAG_START, function (e) {\n        return e.preventDefault();\n      });\n\n      if (this._pointerEvent) {\n        $(this._element).on(Event$2.POINTERDOWN, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.POINTERUP, function (event) {\n          return end(event);\n        });\n\n        this._element.classList.add(ClassName$2.POINTER_EVENT);\n      } else {\n        $(this._element).on(Event$2.TOUCHSTART, function (event) {\n          return start(event);\n        });\n        $(this._element).on(Event$2.TOUCHMOVE, function (event) {\n          return move(event);\n        });\n        $(this._element).on(Event$2.TOUCHEND, function (event) {\n          return end(event);\n        });\n      }\n    };\n\n    _proto._keydown = function _keydown(event) {\n      if (/input|textarea/i.test(event.target.tagName)) {\n        return;\n      }\n\n      switch (event.which) {\n        case ARROW_LEFT_KEYCODE:\n          event.preventDefault();\n          this.prev();\n          break;\n\n        case ARROW_RIGHT_KEYCODE:\n          event.preventDefault();\n          this.next();\n          break;\n\n        default:\n      }\n    };\n\n    _proto._getItemIndex = function _getItemIndex(element) {\n      this._items = element && element.parentNode ? [].slice.call(element.parentNode.querySelectorAll(Selector$2.ITEM)) : [];\n      return this._items.indexOf(element);\n    };\n\n    _proto._getItemByDirection = function _getItemByDirection(direction, activeElement) {\n      var isNextDirection = direction === Direction.NEXT;\n      var isPrevDirection = direction === Direction.PREV;\n\n      var activeIndex = this._getItemIndex(activeElement);\n\n      var lastItemIndex = this._items.length - 1;\n      var isGoingToWrap = isPrevDirection && activeIndex === 0 || isNextDirection && activeIndex === lastItemIndex;\n\n      if (isGoingToWrap && !this._config.wrap) {\n        return activeElement;\n      }\n\n      var delta = direction === Direction.PREV ? -1 : 1;\n      var itemIndex = (activeIndex + delta) % this._items.length;\n      return itemIndex === -1 ? this._items[this._items.length - 1] : this._items[itemIndex];\n    };\n\n    _proto._triggerSlideEvent = function _triggerSlideEvent(relatedTarget, eventDirectionName) {\n      var targetIndex = this._getItemIndex(relatedTarget);\n\n      var fromIndex = this._getItemIndex(this._element.querySelector(Selector$2.ACTIVE_ITEM));\n\n      var slideEvent = $.Event(Event$2.SLIDE, {\n        relatedTarget: relatedTarget,\n        direction: eventDirectionName,\n        from: fromIndex,\n        to: targetIndex\n      });\n      $(this._element).trigger(slideEvent);\n      return slideEvent;\n    };\n\n    _proto._setActiveIndicatorElement = function _setActiveIndicatorElement(element) {\n      if (this._indicatorsElement) {\n        var indicators = [].slice.call(this._indicatorsElement.querySelectorAll(Selector$2.ACTIVE));\n        $(indicators).removeClass(ClassName$2.ACTIVE);\n\n        var nextIndicator = this._indicatorsElement.children[this._getItemIndex(element)];\n\n        if (nextIndicator) {\n          $(nextIndicator).addClass(ClassName$2.ACTIVE);\n        }\n      }\n    };\n\n    _proto._slide = function _slide(direction, element) {\n      var _this4 = this;\n\n      var activeElement = this._element.querySelector(Selector$2.ACTIVE_ITEM);\n\n      var activeElementIndex = this._getItemIndex(activeElement);\n\n      var nextElement = element || activeElement && this._getItemByDirection(direction, activeElement);\n\n      var nextElementIndex = this._getItemIndex(nextElement);\n\n      var isCycling = Boolean(this._interval);\n      var directionalClassName;\n      var orderClassName;\n      var eventDirectionName;\n\n      if (direction === Direction.NEXT) {\n        directionalClassName = ClassName$2.LEFT;\n        orderClassName = ClassName$2.NEXT;\n        eventDirectionName = Direction.LEFT;\n      } else {\n        directionalClassName = ClassName$2.RIGHT;\n        orderClassName = ClassName$2.PREV;\n        eventDirectionName = Direction.RIGHT;\n      }\n\n      if (nextElement && $(nextElement).hasClass(ClassName$2.ACTIVE)) {\n        this._isSliding = false;\n        return;\n      }\n\n      var slideEvent = this._triggerSlideEvent(nextElement, eventDirectionName);\n\n      if (slideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (!activeElement || !nextElement) {\n        // Some weirdness is happening, so we bail\n        return;\n      }\n\n      this._isSliding = true;\n\n      if (isCycling) {\n        this.pause();\n      }\n\n      this._setActiveIndicatorElement(nextElement);\n\n      var slidEvent = $.Event(Event$2.SLID, {\n        relatedTarget: nextElement,\n        direction: eventDirectionName,\n        from: activeElementIndex,\n        to: nextElementIndex\n      });\n\n      if ($(this._element).hasClass(ClassName$2.SLIDE)) {\n        $(nextElement).addClass(orderClassName);\n        Util.reflow(nextElement);\n        $(activeElement).addClass(directionalClassName);\n        $(nextElement).addClass(directionalClassName);\n        var nextElementInterval = parseInt(nextElement.getAttribute('data-interval'), 10);\n\n        if (nextElementInterval) {\n          this._config.defaultInterval = this._config.defaultInterval || this._config.interval;\n          this._config.interval = nextElementInterval;\n        } else {\n          this._config.interval = this._config.defaultInterval || this._config.interval;\n        }\n\n        var transitionDuration = Util.getTransitionDurationFromElement(activeElement);\n        $(activeElement).one(Util.TRANSITION_END, function () {\n          $(nextElement).removeClass(directionalClassName + \" \" + orderClassName).addClass(ClassName$2.ACTIVE);\n          $(activeElement).removeClass(ClassName$2.ACTIVE + \" \" + orderClassName + \" \" + directionalClassName);\n          _this4._isSliding = false;\n          setTimeout(function () {\n            return $(_this4._element).trigger(slidEvent);\n          }, 0);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        $(activeElement).removeClass(ClassName$2.ACTIVE);\n        $(nextElement).addClass(ClassName$2.ACTIVE);\n        this._isSliding = false;\n        $(this._element).trigger(slidEvent);\n      }\n\n      if (isCycling) {\n        this.cycle();\n      }\n    } // Static\n    ;\n\n    Carousel._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$2);\n\n        var _config = _objectSpread({}, Default, $(this).data());\n\n        if (typeof config === 'object') {\n          _config = _objectSpread({}, _config, config);\n        }\n\n        var action = typeof config === 'string' ? config : _config.slide;\n\n        if (!data) {\n          data = new Carousel(this, _config);\n          $(this).data(DATA_KEY$2, data);\n        }\n\n        if (typeof config === 'number') {\n          data.to(config);\n        } else if (typeof action === 'string') {\n          if (typeof data[action] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + action + \"\\\"\");\n          }\n\n          data[action]();\n        } else if (_config.interval && _config.ride) {\n          data.pause();\n          data.cycle();\n        }\n      });\n    };\n\n    Carousel._dataApiClickHandler = function _dataApiClickHandler(event) {\n      var selector = Util.getSelectorFromElement(this);\n\n      if (!selector) {\n        return;\n      }\n\n      var target = $(selector)[0];\n\n      if (!target || !$(target).hasClass(ClassName$2.CAROUSEL)) {\n        return;\n      }\n\n      var config = _objectSpread({}, $(target).data(), $(this).data());\n\n      var slideIndex = this.getAttribute('data-slide-to');\n\n      if (slideIndex) {\n        config.interval = false;\n      }\n\n      Carousel._jQueryInterface.call($(target), config);\n\n      if (slideIndex) {\n        $(target).data(DATA_KEY$2).to(slideIndex);\n      }\n\n      event.preventDefault();\n    };\n\n    _createClass(Carousel, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$2;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default;\n      }\n    }]);\n\n    return Carousel;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$2.CLICK_DATA_API, Selector$2.DATA_SLIDE, Carousel._dataApiClickHandler);\n  $(window).on(Event$2.LOAD_DATA_API, function () {\n    var carousels = [].slice.call(document.querySelectorAll(Selector$2.DATA_RIDE));\n\n    for (var i = 0, len = carousels.length; i < len; i++) {\n      var $carousel = $(carousels[i]);\n\n      Carousel._jQueryInterface.call($carousel, $carousel.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$2] = Carousel._jQueryInterface;\n  $.fn[NAME$2].Constructor = Carousel;\n\n  $.fn[NAME$2].noConflict = function () {\n    $.fn[NAME$2] = JQUERY_NO_CONFLICT$2;\n    return Carousel._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$3 = 'collapse';\n  var VERSION$3 = '4.3.1';\n  var DATA_KEY$3 = 'bs.collapse';\n  var EVENT_KEY$3 = \".\" + DATA_KEY$3;\n  var DATA_API_KEY$3 = '.data-api';\n  var JQUERY_NO_CONFLICT$3 = $.fn[NAME$3];\n  var Default$1 = {\n    toggle: true,\n    parent: ''\n  };\n  var DefaultType$1 = {\n    toggle: 'boolean',\n    parent: '(string|element)'\n  };\n  var Event$3 = {\n    SHOW: \"show\" + EVENT_KEY$3,\n    SHOWN: \"shown\" + EVENT_KEY$3,\n    HIDE: \"hide\" + EVENT_KEY$3,\n    HIDDEN: \"hidden\" + EVENT_KEY$3,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$3 + DATA_API_KEY$3\n  };\n  var ClassName$3 = {\n    SHOW: 'show',\n    COLLAPSE: 'collapse',\n    COLLAPSING: 'collapsing',\n    COLLAPSED: 'collapsed'\n  };\n  var Dimension = {\n    WIDTH: 'width',\n    HEIGHT: 'height'\n  };\n  var Selector$3 = {\n    ACTIVES: '.show, .collapsing',\n    DATA_TOGGLE: '[data-toggle=\"collapse\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Collapse =\n  /*#__PURE__*/\n  function () {\n    function Collapse(element, config) {\n      this._isTransitioning = false;\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._triggerArray = [].slice.call(document.querySelectorAll(\"[data-toggle=\\\"collapse\\\"][href=\\\"#\" + element.id + \"\\\"],\" + (\"[data-toggle=\\\"collapse\\\"][data-target=\\\"#\" + element.id + \"\\\"]\")));\n      var toggleList = [].slice.call(document.querySelectorAll(Selector$3.DATA_TOGGLE));\n\n      for (var i = 0, len = toggleList.length; i < len; i++) {\n        var elem = toggleList[i];\n        var selector = Util.getSelectorFromElement(elem);\n        var filterElement = [].slice.call(document.querySelectorAll(selector)).filter(function (foundElem) {\n          return foundElem === element;\n        });\n\n        if (selector !== null && filterElement.length > 0) {\n          this._selector = selector;\n\n          this._triggerArray.push(elem);\n        }\n      }\n\n      this._parent = this._config.parent ? this._getParent() : null;\n\n      if (!this._config.parent) {\n        this._addAriaAndCollapsedClass(this._element, this._triggerArray);\n      }\n\n      if (this._config.toggle) {\n        this.toggle();\n      }\n    } // Getters\n\n\n    var _proto = Collapse.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if ($(this._element).hasClass(ClassName$3.SHOW)) {\n        this.hide();\n      } else {\n        this.show();\n      }\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._isTransitioning || $(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var actives;\n      var activesData;\n\n      if (this._parent) {\n        actives = [].slice.call(this._parent.querySelectorAll(Selector$3.ACTIVES)).filter(function (elem) {\n          if (typeof _this._config.parent === 'string') {\n            return elem.getAttribute('data-parent') === _this._config.parent;\n          }\n\n          return elem.classList.contains(ClassName$3.COLLAPSE);\n        });\n\n        if (actives.length === 0) {\n          actives = null;\n        }\n      }\n\n      if (actives) {\n        activesData = $(actives).not(this._selector).data(DATA_KEY$3);\n\n        if (activesData && activesData._isTransitioning) {\n          return;\n        }\n      }\n\n      var startEvent = $.Event(Event$3.SHOW);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (actives) {\n        Collapse._jQueryInterface.call($(actives).not(this._selector), 'hide');\n\n        if (!activesData) {\n          $(actives).data(DATA_KEY$3, null);\n        }\n      }\n\n      var dimension = this._getDimension();\n\n      $(this._element).removeClass(ClassName$3.COLLAPSE).addClass(ClassName$3.COLLAPSING);\n      this._element.style[dimension] = 0;\n\n      if (this._triggerArray.length) {\n        $(this._triggerArray).removeClass(ClassName$3.COLLAPSED).attr('aria-expanded', true);\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        $(_this._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).addClass(ClassName$3.SHOW);\n        _this._element.style[dimension] = '';\n\n        _this.setTransitioning(false);\n\n        $(_this._element).trigger(Event$3.SHOWN);\n      };\n\n      var capitalizedDimension = dimension[0].toUpperCase() + dimension.slice(1);\n      var scrollSize = \"scroll\" + capitalizedDimension;\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      this._element.style[dimension] = this._element[scrollSize] + \"px\";\n    };\n\n    _proto.hide = function hide() {\n      var _this2 = this;\n\n      if (this._isTransitioning || !$(this._element).hasClass(ClassName$3.SHOW)) {\n        return;\n      }\n\n      var startEvent = $.Event(Event$3.HIDE);\n      $(this._element).trigger(startEvent);\n\n      if (startEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      var dimension = this._getDimension();\n\n      this._element.style[dimension] = this._element.getBoundingClientRect()[dimension] + \"px\";\n      Util.reflow(this._element);\n      $(this._element).addClass(ClassName$3.COLLAPSING).removeClass(ClassName$3.COLLAPSE).removeClass(ClassName$3.SHOW);\n      var triggerArrayLength = this._triggerArray.length;\n\n      if (triggerArrayLength > 0) {\n        for (var i = 0; i < triggerArrayLength; i++) {\n          var trigger = this._triggerArray[i];\n          var selector = Util.getSelectorFromElement(trigger);\n\n          if (selector !== null) {\n            var $elem = $([].slice.call(document.querySelectorAll(selector)));\n\n            if (!$elem.hasClass(ClassName$3.SHOW)) {\n              $(trigger).addClass(ClassName$3.COLLAPSED).attr('aria-expanded', false);\n            }\n          }\n        }\n      }\n\n      this.setTransitioning(true);\n\n      var complete = function complete() {\n        _this2.setTransitioning(false);\n\n        $(_this2._element).removeClass(ClassName$3.COLLAPSING).addClass(ClassName$3.COLLAPSE).trigger(Event$3.HIDDEN);\n      };\n\n      this._element.style[dimension] = '';\n      var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n      $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n    };\n\n    _proto.setTransitioning = function setTransitioning(isTransitioning) {\n      this._isTransitioning = isTransitioning;\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$3);\n      this._config = null;\n      this._parent = null;\n      this._element = null;\n      this._triggerArray = null;\n      this._isTransitioning = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$1, config);\n      config.toggle = Boolean(config.toggle); // Coerce string values\n\n      Util.typeCheckConfig(NAME$3, config, DefaultType$1);\n      return config;\n    };\n\n    _proto._getDimension = function _getDimension() {\n      var hasWidth = $(this._element).hasClass(Dimension.WIDTH);\n      return hasWidth ? Dimension.WIDTH : Dimension.HEIGHT;\n    };\n\n    _proto._getParent = function _getParent() {\n      var _this3 = this;\n\n      var parent;\n\n      if (Util.isElement(this._config.parent)) {\n        parent = this._config.parent; // It's a jQuery object\n\n        if (typeof this._config.parent.jquery !== 'undefined') {\n          parent = this._config.parent[0];\n        }\n      } else {\n        parent = document.querySelector(this._config.parent);\n      }\n\n      var selector = \"[data-toggle=\\\"collapse\\\"][data-parent=\\\"\" + this._config.parent + \"\\\"]\";\n      var children = [].slice.call(parent.querySelectorAll(selector));\n      $(children).each(function (i, element) {\n        _this3._addAriaAndCollapsedClass(Collapse._getTargetFromElement(element), [element]);\n      });\n      return parent;\n    };\n\n    _proto._addAriaAndCollapsedClass = function _addAriaAndCollapsedClass(element, triggerArray) {\n      var isOpen = $(element).hasClass(ClassName$3.SHOW);\n\n      if (triggerArray.length) {\n        $(triggerArray).toggleClass(ClassName$3.COLLAPSED, !isOpen).attr('aria-expanded', isOpen);\n      }\n    } // Static\n    ;\n\n    Collapse._getTargetFromElement = function _getTargetFromElement(element) {\n      var selector = Util.getSelectorFromElement(element);\n      return selector ? document.querySelector(selector) : null;\n    };\n\n    Collapse._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$3);\n\n        var _config = _objectSpread({}, Default$1, $this.data(), typeof config === 'object' && config ? config : {});\n\n        if (!data && _config.toggle && /show|hide/.test(config)) {\n          _config.toggle = false;\n        }\n\n        if (!data) {\n          data = new Collapse(this, _config);\n          $this.data(DATA_KEY$3, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Collapse, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$3;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$1;\n      }\n    }]);\n\n    return Collapse;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$3.CLICK_DATA_API, Selector$3.DATA_TOGGLE, function (event) {\n    // preventDefault only for <a> elements (which change the URL) not inside the collapsible element\n    if (event.currentTarget.tagName === 'A') {\n      event.preventDefault();\n    }\n\n    var $trigger = $(this);\n    var selector = Util.getSelectorFromElement(this);\n    var selectors = [].slice.call(document.querySelectorAll(selector));\n    $(selectors).each(function () {\n      var $target = $(this);\n      var data = $target.data(DATA_KEY$3);\n      var config = data ? 'toggle' : $trigger.data();\n\n      Collapse._jQueryInterface.call($target, config);\n    });\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$3] = Collapse._jQueryInterface;\n  $.fn[NAME$3].Constructor = Collapse;\n\n  $.fn[NAME$3].noConflict = function () {\n    $.fn[NAME$3] = JQUERY_NO_CONFLICT$3;\n    return Collapse._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$4 = 'dropdown';\n  var VERSION$4 = '4.3.1';\n  var DATA_KEY$4 = 'bs.dropdown';\n  var EVENT_KEY$4 = \".\" + DATA_KEY$4;\n  var DATA_API_KEY$4 = '.data-api';\n  var JQUERY_NO_CONFLICT$4 = $.fn[NAME$4];\n  var ESCAPE_KEYCODE = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var SPACE_KEYCODE = 32; // KeyboardEvent.which value for space key\n\n  var TAB_KEYCODE = 9; // KeyboardEvent.which value for tab key\n\n  var ARROW_UP_KEYCODE = 38; // KeyboardEvent.which value for up arrow key\n\n  var ARROW_DOWN_KEYCODE = 40; // KeyboardEvent.which value for down arrow key\n\n  var RIGHT_MOUSE_BUTTON_WHICH = 3; // MouseEvent.which value for the right button (assuming a right-handed mouse)\n\n  var REGEXP_KEYDOWN = new RegExp(ARROW_UP_KEYCODE + \"|\" + ARROW_DOWN_KEYCODE + \"|\" + ESCAPE_KEYCODE);\n  var Event$4 = {\n    HIDE: \"hide\" + EVENT_KEY$4,\n    HIDDEN: \"hidden\" + EVENT_KEY$4,\n    SHOW: \"show\" + EVENT_KEY$4,\n    SHOWN: \"shown\" + EVENT_KEY$4,\n    CLICK: \"click\" + EVENT_KEY$4,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYDOWN_DATA_API: \"keydown\" + EVENT_KEY$4 + DATA_API_KEY$4,\n    KEYUP_DATA_API: \"keyup\" + EVENT_KEY$4 + DATA_API_KEY$4\n  };\n  var ClassName$4 = {\n    DISABLED: 'disabled',\n    SHOW: 'show',\n    DROPUP: 'dropup',\n    DROPRIGHT: 'dropright',\n    DROPLEFT: 'dropleft',\n    MENURIGHT: 'dropdown-menu-right',\n    MENULEFT: 'dropdown-menu-left',\n    POSITION_STATIC: 'position-static'\n  };\n  var Selector$4 = {\n    DATA_TOGGLE: '[data-toggle=\"dropdown\"]',\n    FORM_CHILD: '.dropdown form',\n    MENU: '.dropdown-menu',\n    NAVBAR_NAV: '.navbar-nav',\n    VISIBLE_ITEMS: '.dropdown-menu .dropdown-item:not(.disabled):not(:disabled)'\n  };\n  var AttachmentMap = {\n    TOP: 'top-start',\n    TOPEND: 'top-end',\n    BOTTOM: 'bottom-start',\n    BOTTOMEND: 'bottom-end',\n    RIGHT: 'right-start',\n    RIGHTEND: 'right-end',\n    LEFT: 'left-start',\n    LEFTEND: 'left-end'\n  };\n  var Default$2 = {\n    offset: 0,\n    flip: true,\n    boundary: 'scrollParent',\n    reference: 'toggle',\n    display: 'dynamic'\n  };\n  var DefaultType$2 = {\n    offset: '(number|string|function)',\n    flip: 'boolean',\n    boundary: '(string|element)',\n    reference: '(string|element)',\n    display: 'string'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Dropdown =\n  /*#__PURE__*/\n  function () {\n    function Dropdown(element, config) {\n      this._element = element;\n      this._popper = null;\n      this._config = this._getConfig(config);\n      this._menu = this._getMenuElement();\n      this._inNavbar = this._detectNavbar();\n\n      this._addEventListeners();\n    } // Getters\n\n\n    var _proto = Dropdown.prototype;\n\n    // Public\n    _proto.toggle = function toggle() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      var isActive = $(this._menu).hasClass(ClassName$4.SHOW);\n\n      Dropdown._clearMenus();\n\n      if (isActive) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      } // Disable totally Popper.js for Dropdown in Navbar\n\n\n      if (!this._inNavbar) {\n        /**\n         * Check for Popper dependency\n         * Popper - https://popper.js.org\n         */\n        if (typeof Popper === 'undefined') {\n          throw new TypeError('Bootstrap\\'s dropdowns require Popper.js (https://popper.js.org/)');\n        }\n\n        var referenceElement = this._element;\n\n        if (this._config.reference === 'parent') {\n          referenceElement = parent;\n        } else if (Util.isElement(this._config.reference)) {\n          referenceElement = this._config.reference; // Check if it's jQuery element\n\n          if (typeof this._config.reference.jquery !== 'undefined') {\n            referenceElement = this._config.reference[0];\n          }\n        } // If boundary is not `scrollParent`, then set position to `static`\n        // to allow the menu to \"escape\" the scroll parent's boundaries\n        // https://github.com/twbs/bootstrap/issues/24251\n\n\n        if (this._config.boundary !== 'scrollParent') {\n          $(parent).addClass(ClassName$4.POSITION_STATIC);\n        }\n\n        this._popper = new Popper(referenceElement, this._menu, this._getPopperConfig());\n      } // If this is a touch-enabled device we add extra\n      // empty mouseover listeners to the body's immediate children;\n      // only needed because of broken event delegation on iOS\n      // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n\n      if ('ontouchstart' in document.documentElement && $(parent).closest(Selector$4.NAVBAR_NAV).length === 0) {\n        $(document.body).children().on('mouseover', null, $.noop);\n      }\n\n      this._element.focus();\n\n      this._element.setAttribute('aria-expanded', true);\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.show = function show() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || $(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var showEvent = $.Event(Event$4.SHOW, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.SHOWN, relatedTarget));\n    };\n\n    _proto.hide = function hide() {\n      if (this._element.disabled || $(this._element).hasClass(ClassName$4.DISABLED) || !$(this._menu).hasClass(ClassName$4.SHOW)) {\n        return;\n      }\n\n      var relatedTarget = {\n        relatedTarget: this._element\n      };\n      var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n\n      var parent = Dropdown._getParentFromElement(this._element);\n\n      $(parent).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(this._menu).toggleClass(ClassName$4.SHOW);\n      $(parent).toggleClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$4);\n      $(this._element).off(EVENT_KEY$4);\n      this._element = null;\n      this._menu = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n\n        this._popper = null;\n      }\n    };\n\n    _proto.update = function update() {\n      this._inNavbar = this._detectNavbar();\n\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Private\n    ;\n\n    _proto._addEventListeners = function _addEventListeners() {\n      var _this = this;\n\n      $(this._element).on(Event$4.CLICK, function (event) {\n        event.preventDefault();\n        event.stopPropagation();\n\n        _this.toggle();\n      });\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, this.constructor.Default, $(this._element).data(), config);\n      Util.typeCheckConfig(NAME$4, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._getMenuElement = function _getMenuElement() {\n      if (!this._menu) {\n        var parent = Dropdown._getParentFromElement(this._element);\n\n        if (parent) {\n          this._menu = parent.querySelector(Selector$4.MENU);\n        }\n      }\n\n      return this._menu;\n    };\n\n    _proto._getPlacement = function _getPlacement() {\n      var $parentDropdown = $(this._element.parentNode);\n      var placement = AttachmentMap.BOTTOM; // Handle dropup\n\n      if ($parentDropdown.hasClass(ClassName$4.DROPUP)) {\n        placement = AttachmentMap.TOP;\n\n        if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n          placement = AttachmentMap.TOPEND;\n        }\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPRIGHT)) {\n        placement = AttachmentMap.RIGHT;\n      } else if ($parentDropdown.hasClass(ClassName$4.DROPLEFT)) {\n        placement = AttachmentMap.LEFT;\n      } else if ($(this._menu).hasClass(ClassName$4.MENURIGHT)) {\n        placement = AttachmentMap.BOTTOMEND;\n      }\n\n      return placement;\n    };\n\n    _proto._detectNavbar = function _detectNavbar() {\n      return $(this._element).closest('.navbar').length > 0;\n    };\n\n    _proto._getOffset = function _getOffset() {\n      var _this2 = this;\n\n      var offset = {};\n\n      if (typeof this._config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this2._config.offset(data.offsets, _this2._element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this._config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getPopperConfig = function _getPopperConfig() {\n      var popperConfig = {\n        placement: this._getPlacement(),\n        modifiers: {\n          offset: this._getOffset(),\n          flip: {\n            enabled: this._config.flip\n          },\n          preventOverflow: {\n            boundariesElement: this._config.boundary\n          }\n        } // Disable Popper.js if we have a static display\n\n      };\n\n      if (this._config.display === 'static') {\n        popperConfig.modifiers.applyStyle = {\n          enabled: false\n        };\n      }\n\n      return popperConfig;\n    } // Static\n    ;\n\n    Dropdown._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$4);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data) {\n          data = new Dropdown(this, _config);\n          $(this).data(DATA_KEY$4, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    Dropdown._clearMenus = function _clearMenus(event) {\n      if (event && (event.which === RIGHT_MOUSE_BUTTON_WHICH || event.type === 'keyup' && event.which !== TAB_KEYCODE)) {\n        return;\n      }\n\n      var toggles = [].slice.call(document.querySelectorAll(Selector$4.DATA_TOGGLE));\n\n      for (var i = 0, len = toggles.length; i < len; i++) {\n        var parent = Dropdown._getParentFromElement(toggles[i]);\n\n        var context = $(toggles[i]).data(DATA_KEY$4);\n        var relatedTarget = {\n          relatedTarget: toggles[i]\n        };\n\n        if (event && event.type === 'click') {\n          relatedTarget.clickEvent = event;\n        }\n\n        if (!context) {\n          continue;\n        }\n\n        var dropdownMenu = context._menu;\n\n        if (!$(parent).hasClass(ClassName$4.SHOW)) {\n          continue;\n        }\n\n        if (event && (event.type === 'click' && /input|textarea/i.test(event.target.tagName) || event.type === 'keyup' && event.which === TAB_KEYCODE) && $.contains(parent, event.target)) {\n          continue;\n        }\n\n        var hideEvent = $.Event(Event$4.HIDE, relatedTarget);\n        $(parent).trigger(hideEvent);\n\n        if (hideEvent.isDefaultPrevented()) {\n          continue;\n        } // If this is a touch-enabled device we remove the extra\n        // empty mouseover listeners we added for iOS support\n\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().off('mouseover', null, $.noop);\n        }\n\n        toggles[i].setAttribute('aria-expanded', 'false');\n        $(dropdownMenu).removeClass(ClassName$4.SHOW);\n        $(parent).removeClass(ClassName$4.SHOW).trigger($.Event(Event$4.HIDDEN, relatedTarget));\n      }\n    };\n\n    Dropdown._getParentFromElement = function _getParentFromElement(element) {\n      var parent;\n      var selector = Util.getSelectorFromElement(element);\n\n      if (selector) {\n        parent = document.querySelector(selector);\n      }\n\n      return parent || element.parentNode;\n    } // eslint-disable-next-line complexity\n    ;\n\n    Dropdown._dataApiKeydownHandler = function _dataApiKeydownHandler(event) {\n      // If not input/textarea:\n      //  - And not a key in REGEXP_KEYDOWN => not a dropdown command\n      // If input/textarea:\n      //  - If space key => not a dropdown command\n      //  - If key is other than escape\n      //    - If key is not up or down => not a dropdown command\n      //    - If trigger inside the menu => not a dropdown command\n      if (/input|textarea/i.test(event.target.tagName) ? event.which === SPACE_KEYCODE || event.which !== ESCAPE_KEYCODE && (event.which !== ARROW_DOWN_KEYCODE && event.which !== ARROW_UP_KEYCODE || $(event.target).closest(Selector$4.MENU).length) : !REGEXP_KEYDOWN.test(event.which)) {\n        return;\n      }\n\n      event.preventDefault();\n      event.stopPropagation();\n\n      if (this.disabled || $(this).hasClass(ClassName$4.DISABLED)) {\n        return;\n      }\n\n      var parent = Dropdown._getParentFromElement(this);\n\n      var isActive = $(parent).hasClass(ClassName$4.SHOW);\n\n      if (!isActive || isActive && (event.which === ESCAPE_KEYCODE || event.which === SPACE_KEYCODE)) {\n        if (event.which === ESCAPE_KEYCODE) {\n          var toggle = parent.querySelector(Selector$4.DATA_TOGGLE);\n          $(toggle).trigger('focus');\n        }\n\n        $(this).trigger('click');\n        return;\n      }\n\n      var items = [].slice.call(parent.querySelectorAll(Selector$4.VISIBLE_ITEMS));\n\n      if (items.length === 0) {\n        return;\n      }\n\n      var index = items.indexOf(event.target);\n\n      if (event.which === ARROW_UP_KEYCODE && index > 0) {\n        // Up\n        index--;\n      }\n\n      if (event.which === ARROW_DOWN_KEYCODE && index < items.length - 1) {\n        // Down\n        index++;\n      }\n\n      if (index < 0) {\n        index = 0;\n      }\n\n      items[index].focus();\n    };\n\n    _createClass(Dropdown, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$4;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$2;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$2;\n      }\n    }]);\n\n    return Dropdown;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$4.KEYDOWN_DATA_API, Selector$4.DATA_TOGGLE, Dropdown._dataApiKeydownHandler).on(Event$4.KEYDOWN_DATA_API, Selector$4.MENU, Dropdown._dataApiKeydownHandler).on(Event$4.CLICK_DATA_API + \" \" + Event$4.KEYUP_DATA_API, Dropdown._clearMenus).on(Event$4.CLICK_DATA_API, Selector$4.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n    event.stopPropagation();\n\n    Dropdown._jQueryInterface.call($(this), 'toggle');\n  }).on(Event$4.CLICK_DATA_API, Selector$4.FORM_CHILD, function (e) {\n    e.stopPropagation();\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$4] = Dropdown._jQueryInterface;\n  $.fn[NAME$4].Constructor = Dropdown;\n\n  $.fn[NAME$4].noConflict = function () {\n    $.fn[NAME$4] = JQUERY_NO_CONFLICT$4;\n    return Dropdown._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$5 = 'modal';\n  var VERSION$5 = '4.3.1';\n  var DATA_KEY$5 = 'bs.modal';\n  var EVENT_KEY$5 = \".\" + DATA_KEY$5;\n  var DATA_API_KEY$5 = '.data-api';\n  var JQUERY_NO_CONFLICT$5 = $.fn[NAME$5];\n  var ESCAPE_KEYCODE$1 = 27; // KeyboardEvent.which value for Escape (Esc) key\n\n  var Default$3 = {\n    backdrop: true,\n    keyboard: true,\n    focus: true,\n    show: true\n  };\n  var DefaultType$3 = {\n    backdrop: '(boolean|string)',\n    keyboard: 'boolean',\n    focus: 'boolean',\n    show: 'boolean'\n  };\n  var Event$5 = {\n    HIDE: \"hide\" + EVENT_KEY$5,\n    HIDDEN: \"hidden\" + EVENT_KEY$5,\n    SHOW: \"show\" + EVENT_KEY$5,\n    SHOWN: \"shown\" + EVENT_KEY$5,\n    FOCUSIN: \"focusin\" + EVENT_KEY$5,\n    RESIZE: \"resize\" + EVENT_KEY$5,\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$5,\n    KEYDOWN_DISMISS: \"keydown.dismiss\" + EVENT_KEY$5,\n    MOUSEUP_DISMISS: \"mouseup.dismiss\" + EVENT_KEY$5,\n    MOUSEDOWN_DISMISS: \"mousedown.dismiss\" + EVENT_KEY$5,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$5 + DATA_API_KEY$5\n  };\n  var ClassName$5 = {\n    SCROLLABLE: 'modal-dialog-scrollable',\n    SCROLLBAR_MEASURER: 'modal-scrollbar-measure',\n    BACKDROP: 'modal-backdrop',\n    OPEN: 'modal-open',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$5 = {\n    DIALOG: '.modal-dialog',\n    MODAL_BODY: '.modal-body',\n    DATA_TOGGLE: '[data-toggle=\"modal\"]',\n    DATA_DISMISS: '[data-dismiss=\"modal\"]',\n    FIXED_CONTENT: '.fixed-top, .fixed-bottom, .is-fixed, .sticky-top',\n    STICKY_CONTENT: '.sticky-top'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Modal =\n  /*#__PURE__*/\n  function () {\n    function Modal(element, config) {\n      this._config = this._getConfig(config);\n      this._element = element;\n      this._dialog = element.querySelector(Selector$5.DIALOG);\n      this._backdrop = null;\n      this._isShown = false;\n      this._isBodyOverflowing = false;\n      this._ignoreBackdropClick = false;\n      this._isTransitioning = false;\n      this._scrollbarWidth = 0;\n    } // Getters\n\n\n    var _proto = Modal.prototype;\n\n    // Public\n    _proto.toggle = function toggle(relatedTarget) {\n      return this._isShown ? this.hide() : this.show(relatedTarget);\n    };\n\n    _proto.show = function show(relatedTarget) {\n      var _this = this;\n\n      if (this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      if ($(this._element).hasClass(ClassName$5.FADE)) {\n        this._isTransitioning = true;\n      }\n\n      var showEvent = $.Event(Event$5.SHOW, {\n        relatedTarget: relatedTarget\n      });\n      $(this._element).trigger(showEvent);\n\n      if (this._isShown || showEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = true;\n\n      this._checkScrollbar();\n\n      this._setScrollbar();\n\n      this._adjustDialog();\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(this._element).on(Event$5.CLICK_DISMISS, Selector$5.DATA_DISMISS, function (event) {\n        return _this.hide(event);\n      });\n      $(this._dialog).on(Event$5.MOUSEDOWN_DISMISS, function () {\n        $(_this._element).one(Event$5.MOUSEUP_DISMISS, function (event) {\n          if ($(event.target).is(_this._element)) {\n            _this._ignoreBackdropClick = true;\n          }\n        });\n      });\n\n      this._showBackdrop(function () {\n        return _this._showElement(relatedTarget);\n      });\n    };\n\n    _proto.hide = function hide(event) {\n      var _this2 = this;\n\n      if (event) {\n        event.preventDefault();\n      }\n\n      if (!this._isShown || this._isTransitioning) {\n        return;\n      }\n\n      var hideEvent = $.Event(Event$5.HIDE);\n      $(this._element).trigger(hideEvent);\n\n      if (!this._isShown || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      this._isShown = false;\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (transition) {\n        this._isTransitioning = true;\n      }\n\n      this._setEscapeEvent();\n\n      this._setResizeEvent();\n\n      $(document).off(Event$5.FOCUSIN);\n      $(this._element).removeClass(ClassName$5.SHOW);\n      $(this._element).off(Event$5.CLICK_DISMISS);\n      $(this._dialog).off(Event$5.MOUSEDOWN_DISMISS);\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, function (event) {\n          return _this2._hideModal(event);\n        }).emulateTransitionEnd(transitionDuration);\n      } else {\n        this._hideModal();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      [window, this._element, this._dialog].forEach(function (htmlElement) {\n        return $(htmlElement).off(EVENT_KEY$5);\n      });\n      /**\n       * `document` has 2 events `Event.FOCUSIN` and `Event.CLICK_DATA_API`\n       * Do not move `document` in `htmlElements` array\n       * It will remove `Event.CLICK_DATA_API` event that should remain\n       */\n\n      $(document).off(Event$5.FOCUSIN);\n      $.removeData(this._element, DATA_KEY$5);\n      this._config = null;\n      this._element = null;\n      this._dialog = null;\n      this._backdrop = null;\n      this._isShown = null;\n      this._isBodyOverflowing = null;\n      this._ignoreBackdropClick = null;\n      this._isTransitioning = null;\n      this._scrollbarWidth = null;\n    };\n\n    _proto.handleUpdate = function handleUpdate() {\n      this._adjustDialog();\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$3, config);\n      Util.typeCheckConfig(NAME$5, config, DefaultType$3);\n      return config;\n    };\n\n    _proto._showElement = function _showElement(relatedTarget) {\n      var _this3 = this;\n\n      var transition = $(this._element).hasClass(ClassName$5.FADE);\n\n      if (!this._element.parentNode || this._element.parentNode.nodeType !== Node.ELEMENT_NODE) {\n        // Don't move modal's DOM position\n        document.body.appendChild(this._element);\n      }\n\n      this._element.style.display = 'block';\n\n      this._element.removeAttribute('aria-hidden');\n\n      this._element.setAttribute('aria-modal', true);\n\n      if ($(this._dialog).hasClass(ClassName$5.SCROLLABLE)) {\n        this._dialog.querySelector(Selector$5.MODAL_BODY).scrollTop = 0;\n      } else {\n        this._element.scrollTop = 0;\n      }\n\n      if (transition) {\n        Util.reflow(this._element);\n      }\n\n      $(this._element).addClass(ClassName$5.SHOW);\n\n      if (this._config.focus) {\n        this._enforceFocus();\n      }\n\n      var shownEvent = $.Event(Event$5.SHOWN, {\n        relatedTarget: relatedTarget\n      });\n\n      var transitionComplete = function transitionComplete() {\n        if (_this3._config.focus) {\n          _this3._element.focus();\n        }\n\n        _this3._isTransitioning = false;\n        $(_this3._element).trigger(shownEvent);\n      };\n\n      if (transition) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._dialog);\n        $(this._dialog).one(Util.TRANSITION_END, transitionComplete).emulateTransitionEnd(transitionDuration);\n      } else {\n        transitionComplete();\n      }\n    };\n\n    _proto._enforceFocus = function _enforceFocus() {\n      var _this4 = this;\n\n      $(document).off(Event$5.FOCUSIN) // Guard against infinite focus loop\n      .on(Event$5.FOCUSIN, function (event) {\n        if (document !== event.target && _this4._element !== event.target && $(_this4._element).has(event.target).length === 0) {\n          _this4._element.focus();\n        }\n      });\n    };\n\n    _proto._setEscapeEvent = function _setEscapeEvent() {\n      var _this5 = this;\n\n      if (this._isShown && this._config.keyboard) {\n        $(this._element).on(Event$5.KEYDOWN_DISMISS, function (event) {\n          if (event.which === ESCAPE_KEYCODE$1) {\n            event.preventDefault();\n\n            _this5.hide();\n          }\n        });\n      } else if (!this._isShown) {\n        $(this._element).off(Event$5.KEYDOWN_DISMISS);\n      }\n    };\n\n    _proto._setResizeEvent = function _setResizeEvent() {\n      var _this6 = this;\n\n      if (this._isShown) {\n        $(window).on(Event$5.RESIZE, function (event) {\n          return _this6.handleUpdate(event);\n        });\n      } else {\n        $(window).off(Event$5.RESIZE);\n      }\n    };\n\n    _proto._hideModal = function _hideModal() {\n      var _this7 = this;\n\n      this._element.style.display = 'none';\n\n      this._element.setAttribute('aria-hidden', true);\n\n      this._element.removeAttribute('aria-modal');\n\n      this._isTransitioning = false;\n\n      this._showBackdrop(function () {\n        $(document.body).removeClass(ClassName$5.OPEN);\n\n        _this7._resetAdjustments();\n\n        _this7._resetScrollbar();\n\n        $(_this7._element).trigger(Event$5.HIDDEN);\n      });\n    };\n\n    _proto._removeBackdrop = function _removeBackdrop() {\n      if (this._backdrop) {\n        $(this._backdrop).remove();\n        this._backdrop = null;\n      }\n    };\n\n    _proto._showBackdrop = function _showBackdrop(callback) {\n      var _this8 = this;\n\n      var animate = $(this._element).hasClass(ClassName$5.FADE) ? ClassName$5.FADE : '';\n\n      if (this._isShown && this._config.backdrop) {\n        this._backdrop = document.createElement('div');\n        this._backdrop.className = ClassName$5.BACKDROP;\n\n        if (animate) {\n          this._backdrop.classList.add(animate);\n        }\n\n        $(this._backdrop).appendTo(document.body);\n        $(this._element).on(Event$5.CLICK_DISMISS, function (event) {\n          if (_this8._ignoreBackdropClick) {\n            _this8._ignoreBackdropClick = false;\n            return;\n          }\n\n          if (event.target !== event.currentTarget) {\n            return;\n          }\n\n          if (_this8._config.backdrop === 'static') {\n            _this8._element.focus();\n          } else {\n            _this8.hide();\n          }\n        });\n\n        if (animate) {\n          Util.reflow(this._backdrop);\n        }\n\n        $(this._backdrop).addClass(ClassName$5.SHOW);\n\n        if (!callback) {\n          return;\n        }\n\n        if (!animate) {\n          callback();\n          return;\n        }\n\n        var backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n        $(this._backdrop).one(Util.TRANSITION_END, callback).emulateTransitionEnd(backdropTransitionDuration);\n      } else if (!this._isShown && this._backdrop) {\n        $(this._backdrop).removeClass(ClassName$5.SHOW);\n\n        var callbackRemove = function callbackRemove() {\n          _this8._removeBackdrop();\n\n          if (callback) {\n            callback();\n          }\n        };\n\n        if ($(this._element).hasClass(ClassName$5.FADE)) {\n          var _backdropTransitionDuration = Util.getTransitionDurationFromElement(this._backdrop);\n\n          $(this._backdrop).one(Util.TRANSITION_END, callbackRemove).emulateTransitionEnd(_backdropTransitionDuration);\n        } else {\n          callbackRemove();\n        }\n      } else if (callback) {\n        callback();\n      }\n    } // ----------------------------------------------------------------------\n    // the following methods are used to handle overflowing modals\n    // todo (fat): these should probably be refactored out of modal.js\n    // ----------------------------------------------------------------------\n    ;\n\n    _proto._adjustDialog = function _adjustDialog() {\n      var isModalOverflowing = this._element.scrollHeight > document.documentElement.clientHeight;\n\n      if (!this._isBodyOverflowing && isModalOverflowing) {\n        this._element.style.paddingLeft = this._scrollbarWidth + \"px\";\n      }\n\n      if (this._isBodyOverflowing && !isModalOverflowing) {\n        this._element.style.paddingRight = this._scrollbarWidth + \"px\";\n      }\n    };\n\n    _proto._resetAdjustments = function _resetAdjustments() {\n      this._element.style.paddingLeft = '';\n      this._element.style.paddingRight = '';\n    };\n\n    _proto._checkScrollbar = function _checkScrollbar() {\n      var rect = document.body.getBoundingClientRect();\n      this._isBodyOverflowing = rect.left + rect.right < window.innerWidth;\n      this._scrollbarWidth = this._getScrollbarWidth();\n    };\n\n    _proto._setScrollbar = function _setScrollbar() {\n      var _this9 = this;\n\n      if (this._isBodyOverflowing) {\n        // Note: DOMNode.style.paddingRight returns the actual value or '' if not set\n        //   while $(DOMNode).css('padding-right') returns the calculated value or 0 if not set\n        var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n        var stickyContent = [].slice.call(document.querySelectorAll(Selector$5.STICKY_CONTENT)); // Adjust fixed content padding\n\n        $(fixedContent).each(function (index, element) {\n          var actualPadding = element.style.paddingRight;\n          var calculatedPadding = $(element).css('padding-right');\n          $(element).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + _this9._scrollbarWidth + \"px\");\n        }); // Adjust sticky content margin\n\n        $(stickyContent).each(function (index, element) {\n          var actualMargin = element.style.marginRight;\n          var calculatedMargin = $(element).css('margin-right');\n          $(element).data('margin-right', actualMargin).css('margin-right', parseFloat(calculatedMargin) - _this9._scrollbarWidth + \"px\");\n        }); // Adjust body padding\n\n        var actualPadding = document.body.style.paddingRight;\n        var calculatedPadding = $(document.body).css('padding-right');\n        $(document.body).data('padding-right', actualPadding).css('padding-right', parseFloat(calculatedPadding) + this._scrollbarWidth + \"px\");\n      }\n\n      $(document.body).addClass(ClassName$5.OPEN);\n    };\n\n    _proto._resetScrollbar = function _resetScrollbar() {\n      // Restore fixed content padding\n      var fixedContent = [].slice.call(document.querySelectorAll(Selector$5.FIXED_CONTENT));\n      $(fixedContent).each(function (index, element) {\n        var padding = $(element).data('padding-right');\n        $(element).removeData('padding-right');\n        element.style.paddingRight = padding ? padding : '';\n      }); // Restore sticky content\n\n      var elements = [].slice.call(document.querySelectorAll(\"\" + Selector$5.STICKY_CONTENT));\n      $(elements).each(function (index, element) {\n        var margin = $(element).data('margin-right');\n\n        if (typeof margin !== 'undefined') {\n          $(element).css('margin-right', margin).removeData('margin-right');\n        }\n      }); // Restore body padding\n\n      var padding = $(document.body).data('padding-right');\n      $(document.body).removeData('padding-right');\n      document.body.style.paddingRight = padding ? padding : '';\n    };\n\n    _proto._getScrollbarWidth = function _getScrollbarWidth() {\n      // thx d.walsh\n      var scrollDiv = document.createElement('div');\n      scrollDiv.className = ClassName$5.SCROLLBAR_MEASURER;\n      document.body.appendChild(scrollDiv);\n      var scrollbarWidth = scrollDiv.getBoundingClientRect().width - scrollDiv.clientWidth;\n      document.body.removeChild(scrollDiv);\n      return scrollbarWidth;\n    } // Static\n    ;\n\n    Modal._jQueryInterface = function _jQueryInterface(config, relatedTarget) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$5);\n\n        var _config = _objectSpread({}, Default$3, $(this).data(), typeof config === 'object' && config ? config : {});\n\n        if (!data) {\n          data = new Modal(this, _config);\n          $(this).data(DATA_KEY$5, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](relatedTarget);\n        } else if (_config.show) {\n          data.show(relatedTarget);\n        }\n      });\n    };\n\n    _createClass(Modal, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$5;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$3;\n      }\n    }]);\n\n    return Modal;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$5.CLICK_DATA_API, Selector$5.DATA_TOGGLE, function (event) {\n    var _this10 = this;\n\n    var target;\n    var selector = Util.getSelectorFromElement(this);\n\n    if (selector) {\n      target = document.querySelector(selector);\n    }\n\n    var config = $(target).data(DATA_KEY$5) ? 'toggle' : _objectSpread({}, $(target).data(), $(this).data());\n\n    if (this.tagName === 'A' || this.tagName === 'AREA') {\n      event.preventDefault();\n    }\n\n    var $target = $(target).one(Event$5.SHOW, function (showEvent) {\n      if (showEvent.isDefaultPrevented()) {\n        // Only register focus restorer if modal will actually get shown\n        return;\n      }\n\n      $target.one(Event$5.HIDDEN, function () {\n        if ($(_this10).is(':visible')) {\n          _this10.focus();\n        }\n      });\n    });\n\n    Modal._jQueryInterface.call($(target), config, this);\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$5] = Modal._jQueryInterface;\n  $.fn[NAME$5].Constructor = Modal;\n\n  $.fn[NAME$5].noConflict = function () {\n    $.fn[NAME$5] = JQUERY_NO_CONFLICT$5;\n    return Modal._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): tools/sanitizer.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n  var uriAttrs = ['background', 'cite', 'href', 'itemtype', 'longdesc', 'poster', 'src', 'xlink:href'];\n  var ARIA_ATTRIBUTE_PATTERN = /^aria-[\\w-]*$/i;\n  var DefaultWhitelist = {\n    // Global attributes allowed on any supplied element below.\n    '*': ['class', 'dir', 'id', 'lang', 'role', ARIA_ATTRIBUTE_PATTERN],\n    a: ['target', 'href', 'title', 'rel'],\n    area: [],\n    b: [],\n    br: [],\n    col: [],\n    code: [],\n    div: [],\n    em: [],\n    hr: [],\n    h1: [],\n    h2: [],\n    h3: [],\n    h4: [],\n    h5: [],\n    h6: [],\n    i: [],\n    img: ['src', 'alt', 'title', 'width', 'height'],\n    li: [],\n    ol: [],\n    p: [],\n    pre: [],\n    s: [],\n    small: [],\n    span: [],\n    sub: [],\n    sup: [],\n    strong: [],\n    u: [],\n    ul: []\n    /**\n     * A pattern that recognizes a commonly useful subset of URLs that are safe.\n     *\n     * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n     */\n\n  };\n  var SAFE_URL_PATTERN = /^(?:(?:https?|mailto|ftp|tel|file):|[^&:/?#]*(?:[/?#]|$))/gi;\n  /**\n   * A pattern that matches safe data URLs. Only matches image, video and audio types.\n   *\n   * Shoutout to Angular 7 https://github.com/angular/angular/blob/7.2.4/packages/core/src/sanitization/url_sanitizer.ts\n   */\n\n  var DATA_URL_PATTERN = /^data:(?:image\\/(?:bmp|gif|jpeg|jpg|png|tiff|webp)|video\\/(?:mpeg|mp4|ogg|webm)|audio\\/(?:mp3|oga|ogg|opus));base64,[a-z0-9+/]+=*$/i;\n\n  function allowedAttribute(attr, allowedAttributeList) {\n    var attrName = attr.nodeName.toLowerCase();\n\n    if (allowedAttributeList.indexOf(attrName) !== -1) {\n      if (uriAttrs.indexOf(attrName) !== -1) {\n        return Boolean(attr.nodeValue.match(SAFE_URL_PATTERN) || attr.nodeValue.match(DATA_URL_PATTERN));\n      }\n\n      return true;\n    }\n\n    var regExp = allowedAttributeList.filter(function (attrRegex) {\n      return attrRegex instanceof RegExp;\n    }); // Check if a regular expression validates the attribute.\n\n    for (var i = 0, l = regExp.length; i < l; i++) {\n      if (attrName.match(regExp[i])) {\n        return true;\n      }\n    }\n\n    return false;\n  }\n\n  function sanitizeHtml(unsafeHtml, whiteList, sanitizeFn) {\n    if (unsafeHtml.length === 0) {\n      return unsafeHtml;\n    }\n\n    if (sanitizeFn && typeof sanitizeFn === 'function') {\n      return sanitizeFn(unsafeHtml);\n    }\n\n    var domParser = new window.DOMParser();\n    var createdDocument = domParser.parseFromString(unsafeHtml, 'text/html');\n    var whitelistKeys = Object.keys(whiteList);\n    var elements = [].slice.call(createdDocument.body.querySelectorAll('*'));\n\n    var _loop = function _loop(i, len) {\n      var el = elements[i];\n      var elName = el.nodeName.toLowerCase();\n\n      if (whitelistKeys.indexOf(el.nodeName.toLowerCase()) === -1) {\n        el.parentNode.removeChild(el);\n        return \"continue\";\n      }\n\n      var attributeList = [].slice.call(el.attributes);\n      var whitelistedAttributes = [].concat(whiteList['*'] || [], whiteList[elName] || []);\n      attributeList.forEach(function (attr) {\n        if (!allowedAttribute(attr, whitelistedAttributes)) {\n          el.removeAttribute(attr.nodeName);\n        }\n      });\n    };\n\n    for (var i = 0, len = elements.length; i < len; i++) {\n      var _ret = _loop(i, len);\n\n      if (_ret === \"continue\") continue;\n    }\n\n    return createdDocument.body.innerHTML;\n  }\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$6 = 'tooltip';\n  var VERSION$6 = '4.3.1';\n  var DATA_KEY$6 = 'bs.tooltip';\n  var EVENT_KEY$6 = \".\" + DATA_KEY$6;\n  var JQUERY_NO_CONFLICT$6 = $.fn[NAME$6];\n  var CLASS_PREFIX = 'bs-tooltip';\n  var BSCLS_PREFIX_REGEX = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX + \"\\\\S+\", 'g');\n  var DISALLOWED_ATTRIBUTES = ['sanitize', 'whiteList', 'sanitizeFn'];\n  var DefaultType$4 = {\n    animation: 'boolean',\n    template: 'string',\n    title: '(string|element|function)',\n    trigger: 'string',\n    delay: '(number|object)',\n    html: 'boolean',\n    selector: '(string|boolean)',\n    placement: '(string|function)',\n    offset: '(number|string|function)',\n    container: '(string|element|boolean)',\n    fallbackPlacement: '(string|array)',\n    boundary: '(string|element)',\n    sanitize: 'boolean',\n    sanitizeFn: '(null|function)',\n    whiteList: 'object'\n  };\n  var AttachmentMap$1 = {\n    AUTO: 'auto',\n    TOP: 'top',\n    RIGHT: 'right',\n    BOTTOM: 'bottom',\n    LEFT: 'left'\n  };\n  var Default$4 = {\n    animation: true,\n    template: '<div class=\"tooltip\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<div class=\"tooltip-inner\"></div></div>',\n    trigger: 'hover focus',\n    title: '',\n    delay: 0,\n    html: false,\n    selector: false,\n    placement: 'top',\n    offset: 0,\n    container: false,\n    fallbackPlacement: 'flip',\n    boundary: 'scrollParent',\n    sanitize: true,\n    sanitizeFn: null,\n    whiteList: DefaultWhitelist\n  };\n  var HoverState = {\n    SHOW: 'show',\n    OUT: 'out'\n  };\n  var Event$6 = {\n    HIDE: \"hide\" + EVENT_KEY$6,\n    HIDDEN: \"hidden\" + EVENT_KEY$6,\n    SHOW: \"show\" + EVENT_KEY$6,\n    SHOWN: \"shown\" + EVENT_KEY$6,\n    INSERTED: \"inserted\" + EVENT_KEY$6,\n    CLICK: \"click\" + EVENT_KEY$6,\n    FOCUSIN: \"focusin\" + EVENT_KEY$6,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$6,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$6,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$6\n  };\n  var ClassName$6 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$6 = {\n    TOOLTIP: '.tooltip',\n    TOOLTIP_INNER: '.tooltip-inner',\n    ARROW: '.arrow'\n  };\n  var Trigger = {\n    HOVER: 'hover',\n    FOCUS: 'focus',\n    CLICK: 'click',\n    MANUAL: 'manual'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tooltip =\n  /*#__PURE__*/\n  function () {\n    function Tooltip(element, config) {\n      /**\n       * Check for Popper dependency\n       * Popper - https://popper.js.org\n       */\n      if (typeof Popper === 'undefined') {\n        throw new TypeError('Bootstrap\\'s tooltips require Popper.js (https://popper.js.org/)');\n      } // private\n\n\n      this._isEnabled = true;\n      this._timeout = 0;\n      this._hoverState = '';\n      this._activeTrigger = {};\n      this._popper = null; // Protected\n\n      this.element = element;\n      this.config = this._getConfig(config);\n      this.tip = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Tooltip.prototype;\n\n    // Public\n    _proto.enable = function enable() {\n      this._isEnabled = true;\n    };\n\n    _proto.disable = function disable() {\n      this._isEnabled = false;\n    };\n\n    _proto.toggleEnabled = function toggleEnabled() {\n      this._isEnabled = !this._isEnabled;\n    };\n\n    _proto.toggle = function toggle(event) {\n      if (!this._isEnabled) {\n        return;\n      }\n\n      if (event) {\n        var dataKey = this.constructor.DATA_KEY;\n        var context = $(event.currentTarget).data(dataKey);\n\n        if (!context) {\n          context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n          $(event.currentTarget).data(dataKey, context);\n        }\n\n        context._activeTrigger.click = !context._activeTrigger.click;\n\n        if (context._isWithActiveTrigger()) {\n          context._enter(null, context);\n        } else {\n          context._leave(null, context);\n        }\n      } else {\n        if ($(this.getTipElement()).hasClass(ClassName$6.SHOW)) {\n          this._leave(null, this);\n\n          return;\n        }\n\n        this._enter(null, this);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      $.removeData(this.element, this.constructor.DATA_KEY);\n      $(this.element).off(this.constructor.EVENT_KEY);\n      $(this.element).closest('.modal').off('hide.bs.modal');\n\n      if (this.tip) {\n        $(this.tip).remove();\n      }\n\n      this._isEnabled = null;\n      this._timeout = null;\n      this._hoverState = null;\n      this._activeTrigger = null;\n\n      if (this._popper !== null) {\n        this._popper.destroy();\n      }\n\n      this._popper = null;\n      this.element = null;\n      this.config = null;\n      this.tip = null;\n    };\n\n    _proto.show = function show() {\n      var _this = this;\n\n      if ($(this.element).css('display') === 'none') {\n        throw new Error('Please use show on visible elements');\n      }\n\n      var showEvent = $.Event(this.constructor.Event.SHOW);\n\n      if (this.isWithContent() && this._isEnabled) {\n        $(this.element).trigger(showEvent);\n        var shadowRoot = Util.findShadowRoot(this.element);\n        var isInTheDom = $.contains(shadowRoot !== null ? shadowRoot : this.element.ownerDocument.documentElement, this.element);\n\n        if (showEvent.isDefaultPrevented() || !isInTheDom) {\n          return;\n        }\n\n        var tip = this.getTipElement();\n        var tipId = Util.getUID(this.constructor.NAME);\n        tip.setAttribute('id', tipId);\n        this.element.setAttribute('aria-describedby', tipId);\n        this.setContent();\n\n        if (this.config.animation) {\n          $(tip).addClass(ClassName$6.FADE);\n        }\n\n        var placement = typeof this.config.placement === 'function' ? this.config.placement.call(this, tip, this.element) : this.config.placement;\n\n        var attachment = this._getAttachment(placement);\n\n        this.addAttachmentClass(attachment);\n\n        var container = this._getContainer();\n\n        $(tip).data(this.constructor.DATA_KEY, this);\n\n        if (!$.contains(this.element.ownerDocument.documentElement, this.tip)) {\n          $(tip).appendTo(container);\n        }\n\n        $(this.element).trigger(this.constructor.Event.INSERTED);\n        this._popper = new Popper(this.element, tip, {\n          placement: attachment,\n          modifiers: {\n            offset: this._getOffset(),\n            flip: {\n              behavior: this.config.fallbackPlacement\n            },\n            arrow: {\n              element: Selector$6.ARROW\n            },\n            preventOverflow: {\n              boundariesElement: this.config.boundary\n            }\n          },\n          onCreate: function onCreate(data) {\n            if (data.originalPlacement !== data.placement) {\n              _this._handlePopperPlacementChange(data);\n            }\n          },\n          onUpdate: function onUpdate(data) {\n            return _this._handlePopperPlacementChange(data);\n          }\n        });\n        $(tip).addClass(ClassName$6.SHOW); // If this is a touch-enabled device we add extra\n        // empty mouseover listeners to the body's immediate children;\n        // only needed because of broken event delegation on iOS\n        // https://www.quirksmode.org/blog/archives/2014/02/mouse_event_bub.html\n\n        if ('ontouchstart' in document.documentElement) {\n          $(document.body).children().on('mouseover', null, $.noop);\n        }\n\n        var complete = function complete() {\n          if (_this.config.animation) {\n            _this._fixTransition();\n          }\n\n          var prevHoverState = _this._hoverState;\n          _this._hoverState = null;\n          $(_this.element).trigger(_this.constructor.Event.SHOWN);\n\n          if (prevHoverState === HoverState.OUT) {\n            _this._leave(null, _this);\n          }\n        };\n\n        if ($(this.tip).hasClass(ClassName$6.FADE)) {\n          var transitionDuration = Util.getTransitionDurationFromElement(this.tip);\n          $(this.tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n        } else {\n          complete();\n        }\n      }\n    };\n\n    _proto.hide = function hide(callback) {\n      var _this2 = this;\n\n      var tip = this.getTipElement();\n      var hideEvent = $.Event(this.constructor.Event.HIDE);\n\n      var complete = function complete() {\n        if (_this2._hoverState !== HoverState.SHOW && tip.parentNode) {\n          tip.parentNode.removeChild(tip);\n        }\n\n        _this2._cleanTipClass();\n\n        _this2.element.removeAttribute('aria-describedby');\n\n        $(_this2.element).trigger(_this2.constructor.Event.HIDDEN);\n\n        if (_this2._popper !== null) {\n          _this2._popper.destroy();\n        }\n\n        if (callback) {\n          callback();\n        }\n      };\n\n      $(this.element).trigger(hideEvent);\n\n      if (hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.SHOW); // If this is a touch-enabled device we remove the extra\n      // empty mouseover listeners we added for iOS support\n\n      if ('ontouchstart' in document.documentElement) {\n        $(document.body).children().off('mouseover', null, $.noop);\n      }\n\n      this._activeTrigger[Trigger.CLICK] = false;\n      this._activeTrigger[Trigger.FOCUS] = false;\n      this._activeTrigger[Trigger.HOVER] = false;\n\n      if ($(this.tip).hasClass(ClassName$6.FADE)) {\n        var transitionDuration = Util.getTransitionDurationFromElement(tip);\n        $(tip).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n\n      this._hoverState = '';\n    };\n\n    _proto.update = function update() {\n      if (this._popper !== null) {\n        this._popper.scheduleUpdate();\n      }\n    } // Protected\n    ;\n\n    _proto.isWithContent = function isWithContent() {\n      return Boolean(this.getTitle());\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var tip = this.getTipElement();\n      this.setElementContent($(tip.querySelectorAll(Selector$6.TOOLTIP_INNER)), this.getTitle());\n      $(tip).removeClass(ClassName$6.FADE + \" \" + ClassName$6.SHOW);\n    };\n\n    _proto.setElementContent = function setElementContent($element, content) {\n      if (typeof content === 'object' && (content.nodeType || content.jquery)) {\n        // Content is a DOM node or a jQuery\n        if (this.config.html) {\n          if (!$(content).parent().is($element)) {\n            $element.empty().append(content);\n          }\n        } else {\n          $element.text($(content).text());\n        }\n\n        return;\n      }\n\n      if (this.config.html) {\n        if (this.config.sanitize) {\n          content = sanitizeHtml(content, this.config.whiteList, this.config.sanitizeFn);\n        }\n\n        $element.html(content);\n      } else {\n        $element.text(content);\n      }\n    };\n\n    _proto.getTitle = function getTitle() {\n      var title = this.element.getAttribute('data-original-title');\n\n      if (!title) {\n        title = typeof this.config.title === 'function' ? this.config.title.call(this.element) : this.config.title;\n      }\n\n      return title;\n    } // Private\n    ;\n\n    _proto._getOffset = function _getOffset() {\n      var _this3 = this;\n\n      var offset = {};\n\n      if (typeof this.config.offset === 'function') {\n        offset.fn = function (data) {\n          data.offsets = _objectSpread({}, data.offsets, _this3.config.offset(data.offsets, _this3.element) || {});\n          return data;\n        };\n      } else {\n        offset.offset = this.config.offset;\n      }\n\n      return offset;\n    };\n\n    _proto._getContainer = function _getContainer() {\n      if (this.config.container === false) {\n        return document.body;\n      }\n\n      if (Util.isElement(this.config.container)) {\n        return $(this.config.container);\n      }\n\n      return $(document).find(this.config.container);\n    };\n\n    _proto._getAttachment = function _getAttachment(placement) {\n      return AttachmentMap$1[placement.toUpperCase()];\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this4 = this;\n\n      var triggers = this.config.trigger.split(' ');\n      triggers.forEach(function (trigger) {\n        if (trigger === 'click') {\n          $(_this4.element).on(_this4.constructor.Event.CLICK, _this4.config.selector, function (event) {\n            return _this4.toggle(event);\n          });\n        } else if (trigger !== Trigger.MANUAL) {\n          var eventIn = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSEENTER : _this4.constructor.Event.FOCUSIN;\n          var eventOut = trigger === Trigger.HOVER ? _this4.constructor.Event.MOUSELEAVE : _this4.constructor.Event.FOCUSOUT;\n          $(_this4.element).on(eventIn, _this4.config.selector, function (event) {\n            return _this4._enter(event);\n          }).on(eventOut, _this4.config.selector, function (event) {\n            return _this4._leave(event);\n          });\n        }\n      });\n      $(this.element).closest('.modal').on('hide.bs.modal', function () {\n        if (_this4.element) {\n          _this4.hide();\n        }\n      });\n\n      if (this.config.selector) {\n        this.config = _objectSpread({}, this.config, {\n          trigger: 'manual',\n          selector: ''\n        });\n      } else {\n        this._fixTitle();\n      }\n    };\n\n    _proto._fixTitle = function _fixTitle() {\n      var titleType = typeof this.element.getAttribute('data-original-title');\n\n      if (this.element.getAttribute('title') || titleType !== 'string') {\n        this.element.setAttribute('data-original-title', this.element.getAttribute('title') || '');\n        this.element.setAttribute('title', '');\n      }\n    };\n\n    _proto._enter = function _enter(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusin' ? Trigger.FOCUS : Trigger.HOVER] = true;\n      }\n\n      if ($(context.getTipElement()).hasClass(ClassName$6.SHOW) || context._hoverState === HoverState.SHOW) {\n        context._hoverState = HoverState.SHOW;\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.SHOW;\n\n      if (!context.config.delay || !context.config.delay.show) {\n        context.show();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.SHOW) {\n          context.show();\n        }\n      }, context.config.delay.show);\n    };\n\n    _proto._leave = function _leave(event, context) {\n      var dataKey = this.constructor.DATA_KEY;\n      context = context || $(event.currentTarget).data(dataKey);\n\n      if (!context) {\n        context = new this.constructor(event.currentTarget, this._getDelegateConfig());\n        $(event.currentTarget).data(dataKey, context);\n      }\n\n      if (event) {\n        context._activeTrigger[event.type === 'focusout' ? Trigger.FOCUS : Trigger.HOVER] = false;\n      }\n\n      if (context._isWithActiveTrigger()) {\n        return;\n      }\n\n      clearTimeout(context._timeout);\n      context._hoverState = HoverState.OUT;\n\n      if (!context.config.delay || !context.config.delay.hide) {\n        context.hide();\n        return;\n      }\n\n      context._timeout = setTimeout(function () {\n        if (context._hoverState === HoverState.OUT) {\n          context.hide();\n        }\n      }, context.config.delay.hide);\n    };\n\n    _proto._isWithActiveTrigger = function _isWithActiveTrigger() {\n      for (var trigger in this._activeTrigger) {\n        if (this._activeTrigger[trigger]) {\n          return true;\n        }\n      }\n\n      return false;\n    };\n\n    _proto._getConfig = function _getConfig(config) {\n      var dataAttributes = $(this.element).data();\n      Object.keys(dataAttributes).forEach(function (dataAttr) {\n        if (DISALLOWED_ATTRIBUTES.indexOf(dataAttr) !== -1) {\n          delete dataAttributes[dataAttr];\n        }\n      });\n      config = _objectSpread({}, this.constructor.Default, dataAttributes, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.delay === 'number') {\n        config.delay = {\n          show: config.delay,\n          hide: config.delay\n        };\n      }\n\n      if (typeof config.title === 'number') {\n        config.title = config.title.toString();\n      }\n\n      if (typeof config.content === 'number') {\n        config.content = config.content.toString();\n      }\n\n      Util.typeCheckConfig(NAME$6, config, this.constructor.DefaultType);\n\n      if (config.sanitize) {\n        config.template = sanitizeHtml(config.template, config.whiteList, config.sanitizeFn);\n      }\n\n      return config;\n    };\n\n    _proto._getDelegateConfig = function _getDelegateConfig() {\n      var config = {};\n\n      if (this.config) {\n        for (var key in this.config) {\n          if (this.constructor.Default[key] !== this.config[key]) {\n            config[key] = this.config[key];\n          }\n        }\n      }\n\n      return config;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX);\n\n      if (tabClass !== null && tabClass.length) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    };\n\n    _proto._handlePopperPlacementChange = function _handlePopperPlacementChange(popperData) {\n      var popperInstance = popperData.instance;\n      this.tip = popperInstance.popper;\n\n      this._cleanTipClass();\n\n      this.addAttachmentClass(this._getAttachment(popperData.placement));\n    };\n\n    _proto._fixTransition = function _fixTransition() {\n      var tip = this.getTipElement();\n      var initConfigAnimation = this.config.animation;\n\n      if (tip.getAttribute('x-placement') !== null) {\n        return;\n      }\n\n      $(tip).removeClass(ClassName$6.FADE);\n      this.config.animation = false;\n      this.hide();\n      this.show();\n      this.config.animation = initConfigAnimation;\n    } // Static\n    ;\n\n    Tooltip._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$6);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Tooltip(this, _config);\n          $(this).data(DATA_KEY$6, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tooltip, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$6;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$4;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$6;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$6;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$6;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$6;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$4;\n      }\n    }]);\n\n    return Tooltip;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$6] = Tooltip._jQueryInterface;\n  $.fn[NAME$6].Constructor = Tooltip;\n\n  $.fn[NAME$6].noConflict = function () {\n    $.fn[NAME$6] = JQUERY_NO_CONFLICT$6;\n    return Tooltip._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$7 = 'popover';\n  var VERSION$7 = '4.3.1';\n  var DATA_KEY$7 = 'bs.popover';\n  var EVENT_KEY$7 = \".\" + DATA_KEY$7;\n  var JQUERY_NO_CONFLICT$7 = $.fn[NAME$7];\n  var CLASS_PREFIX$1 = 'bs-popover';\n  var BSCLS_PREFIX_REGEX$1 = new RegExp(\"(^|\\\\s)\" + CLASS_PREFIX$1 + \"\\\\S+\", 'g');\n\n  var Default$5 = _objectSpread({}, Tooltip.Default, {\n    placement: 'right',\n    trigger: 'click',\n    content: '',\n    template: '<div class=\"popover\" role=\"tooltip\">' + '<div class=\"arrow\"></div>' + '<h3 class=\"popover-header\"></h3>' + '<div class=\"popover-body\"></div></div>'\n  });\n\n  var DefaultType$5 = _objectSpread({}, Tooltip.DefaultType, {\n    content: '(string|element|function)'\n  });\n\n  var ClassName$7 = {\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$7 = {\n    TITLE: '.popover-header',\n    CONTENT: '.popover-body'\n  };\n  var Event$7 = {\n    HIDE: \"hide\" + EVENT_KEY$7,\n    HIDDEN: \"hidden\" + EVENT_KEY$7,\n    SHOW: \"show\" + EVENT_KEY$7,\n    SHOWN: \"shown\" + EVENT_KEY$7,\n    INSERTED: \"inserted\" + EVENT_KEY$7,\n    CLICK: \"click\" + EVENT_KEY$7,\n    FOCUSIN: \"focusin\" + EVENT_KEY$7,\n    FOCUSOUT: \"focusout\" + EVENT_KEY$7,\n    MOUSEENTER: \"mouseenter\" + EVENT_KEY$7,\n    MOUSELEAVE: \"mouseleave\" + EVENT_KEY$7\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Popover =\n  /*#__PURE__*/\n  function (_Tooltip) {\n    _inheritsLoose(Popover, _Tooltip);\n\n    function Popover() {\n      return _Tooltip.apply(this, arguments) || this;\n    }\n\n    var _proto = Popover.prototype;\n\n    // Overrides\n    _proto.isWithContent = function isWithContent() {\n      return this.getTitle() || this._getContent();\n    };\n\n    _proto.addAttachmentClass = function addAttachmentClass(attachment) {\n      $(this.getTipElement()).addClass(CLASS_PREFIX$1 + \"-\" + attachment);\n    };\n\n    _proto.getTipElement = function getTipElement() {\n      this.tip = this.tip || $(this.config.template)[0];\n      return this.tip;\n    };\n\n    _proto.setContent = function setContent() {\n      var $tip = $(this.getTipElement()); // We use append for html objects to maintain js events\n\n      this.setElementContent($tip.find(Selector$7.TITLE), this.getTitle());\n\n      var content = this._getContent();\n\n      if (typeof content === 'function') {\n        content = content.call(this.element);\n      }\n\n      this.setElementContent($tip.find(Selector$7.CONTENT), content);\n      $tip.removeClass(ClassName$7.FADE + \" \" + ClassName$7.SHOW);\n    } // Private\n    ;\n\n    _proto._getContent = function _getContent() {\n      return this.element.getAttribute('data-content') || this.config.content;\n    };\n\n    _proto._cleanTipClass = function _cleanTipClass() {\n      var $tip = $(this.getTipElement());\n      var tabClass = $tip.attr('class').match(BSCLS_PREFIX_REGEX$1);\n\n      if (tabClass !== null && tabClass.length > 0) {\n        $tip.removeClass(tabClass.join(''));\n      }\n    } // Static\n    ;\n\n    Popover._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$7);\n\n        var _config = typeof config === 'object' ? config : null;\n\n        if (!data && /dispose|hide/.test(config)) {\n          return;\n        }\n\n        if (!data) {\n          data = new Popover(this, _config);\n          $(this).data(DATA_KEY$7, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Popover, null, [{\n      key: \"VERSION\",\n      // Getters\n      get: function get() {\n        return VERSION$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$5;\n      }\n    }, {\n      key: \"NAME\",\n      get: function get() {\n        return NAME$7;\n      }\n    }, {\n      key: \"DATA_KEY\",\n      get: function get() {\n        return DATA_KEY$7;\n      }\n    }, {\n      key: \"Event\",\n      get: function get() {\n        return Event$7;\n      }\n    }, {\n      key: \"EVENT_KEY\",\n      get: function get() {\n        return EVENT_KEY$7;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$5;\n      }\n    }]);\n\n    return Popover;\n  }(Tooltip);\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$7] = Popover._jQueryInterface;\n  $.fn[NAME$7].Constructor = Popover;\n\n  $.fn[NAME$7].noConflict = function () {\n    $.fn[NAME$7] = JQUERY_NO_CONFLICT$7;\n    return Popover._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$8 = 'scrollspy';\n  var VERSION$8 = '4.3.1';\n  var DATA_KEY$8 = 'bs.scrollspy';\n  var EVENT_KEY$8 = \".\" + DATA_KEY$8;\n  var DATA_API_KEY$6 = '.data-api';\n  var JQUERY_NO_CONFLICT$8 = $.fn[NAME$8];\n  var Default$6 = {\n    offset: 10,\n    method: 'auto',\n    target: ''\n  };\n  var DefaultType$6 = {\n    offset: 'number',\n    method: 'string',\n    target: '(string|element)'\n  };\n  var Event$8 = {\n    ACTIVATE: \"activate\" + EVENT_KEY$8,\n    SCROLL: \"scroll\" + EVENT_KEY$8,\n    LOAD_DATA_API: \"load\" + EVENT_KEY$8 + DATA_API_KEY$6\n  };\n  var ClassName$8 = {\n    DROPDOWN_ITEM: 'dropdown-item',\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active'\n  };\n  var Selector$8 = {\n    DATA_SPY: '[data-spy=\"scroll\"]',\n    ACTIVE: '.active',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    NAV_LINKS: '.nav-link',\n    NAV_ITEMS: '.nav-item',\n    LIST_ITEMS: '.list-group-item',\n    DROPDOWN: '.dropdown',\n    DROPDOWN_ITEMS: '.dropdown-item',\n    DROPDOWN_TOGGLE: '.dropdown-toggle'\n  };\n  var OffsetMethod = {\n    OFFSET: 'offset',\n    POSITION: 'position'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var ScrollSpy =\n  /*#__PURE__*/\n  function () {\n    function ScrollSpy(element, config) {\n      var _this = this;\n\n      this._element = element;\n      this._scrollElement = element.tagName === 'BODY' ? window : element;\n      this._config = this._getConfig(config);\n      this._selector = this._config.target + \" \" + Selector$8.NAV_LINKS + \",\" + (this._config.target + \" \" + Selector$8.LIST_ITEMS + \",\") + (this._config.target + \" \" + Selector$8.DROPDOWN_ITEMS);\n      this._offsets = [];\n      this._targets = [];\n      this._activeTarget = null;\n      this._scrollHeight = 0;\n      $(this._scrollElement).on(Event$8.SCROLL, function (event) {\n        return _this._process(event);\n      });\n      this.refresh();\n\n      this._process();\n    } // Getters\n\n\n    var _proto = ScrollSpy.prototype;\n\n    // Public\n    _proto.refresh = function refresh() {\n      var _this2 = this;\n\n      var autoMethod = this._scrollElement === this._scrollElement.window ? OffsetMethod.OFFSET : OffsetMethod.POSITION;\n      var offsetMethod = this._config.method === 'auto' ? autoMethod : this._config.method;\n      var offsetBase = offsetMethod === OffsetMethod.POSITION ? this._getScrollTop() : 0;\n      this._offsets = [];\n      this._targets = [];\n      this._scrollHeight = this._getScrollHeight();\n      var targets = [].slice.call(document.querySelectorAll(this._selector));\n      targets.map(function (element) {\n        var target;\n        var targetSelector = Util.getSelectorFromElement(element);\n\n        if (targetSelector) {\n          target = document.querySelector(targetSelector);\n        }\n\n        if (target) {\n          var targetBCR = target.getBoundingClientRect();\n\n          if (targetBCR.width || targetBCR.height) {\n            // TODO (fat): remove sketch reliance on jQuery position/offset\n            return [$(target)[offsetMethod]().top + offsetBase, targetSelector];\n          }\n        }\n\n        return null;\n      }).filter(function (item) {\n        return item;\n      }).sort(function (a, b) {\n        return a[0] - b[0];\n      }).forEach(function (item) {\n        _this2._offsets.push(item[0]);\n\n        _this2._targets.push(item[1]);\n      });\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$8);\n      $(this._scrollElement).off(EVENT_KEY$8);\n      this._element = null;\n      this._scrollElement = null;\n      this._config = null;\n      this._selector = null;\n      this._offsets = null;\n      this._targets = null;\n      this._activeTarget = null;\n      this._scrollHeight = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$6, typeof config === 'object' && config ? config : {});\n\n      if (typeof config.target !== 'string') {\n        var id = $(config.target).attr('id');\n\n        if (!id) {\n          id = Util.getUID(NAME$8);\n          $(config.target).attr('id', id);\n        }\n\n        config.target = \"#\" + id;\n      }\n\n      Util.typeCheckConfig(NAME$8, config, DefaultType$6);\n      return config;\n    };\n\n    _proto._getScrollTop = function _getScrollTop() {\n      return this._scrollElement === window ? this._scrollElement.pageYOffset : this._scrollElement.scrollTop;\n    };\n\n    _proto._getScrollHeight = function _getScrollHeight() {\n      return this._scrollElement.scrollHeight || Math.max(document.body.scrollHeight, document.documentElement.scrollHeight);\n    };\n\n    _proto._getOffsetHeight = function _getOffsetHeight() {\n      return this._scrollElement === window ? window.innerHeight : this._scrollElement.getBoundingClientRect().height;\n    };\n\n    _proto._process = function _process() {\n      var scrollTop = this._getScrollTop() + this._config.offset;\n\n      var scrollHeight = this._getScrollHeight();\n\n      var maxScroll = this._config.offset + scrollHeight - this._getOffsetHeight();\n\n      if (this._scrollHeight !== scrollHeight) {\n        this.refresh();\n      }\n\n      if (scrollTop >= maxScroll) {\n        var target = this._targets[this._targets.length - 1];\n\n        if (this._activeTarget !== target) {\n          this._activate(target);\n        }\n\n        return;\n      }\n\n      if (this._activeTarget && scrollTop < this._offsets[0] && this._offsets[0] > 0) {\n        this._activeTarget = null;\n\n        this._clear();\n\n        return;\n      }\n\n      var offsetLength = this._offsets.length;\n\n      for (var i = offsetLength; i--;) {\n        var isActiveTarget = this._activeTarget !== this._targets[i] && scrollTop >= this._offsets[i] && (typeof this._offsets[i + 1] === 'undefined' || scrollTop < this._offsets[i + 1]);\n\n        if (isActiveTarget) {\n          this._activate(this._targets[i]);\n        }\n      }\n    };\n\n    _proto._activate = function _activate(target) {\n      this._activeTarget = target;\n\n      this._clear();\n\n      var queries = this._selector.split(',').map(function (selector) {\n        return selector + \"[data-target=\\\"\" + target + \"\\\"],\" + selector + \"[href=\\\"\" + target + \"\\\"]\";\n      });\n\n      var $link = $([].slice.call(document.querySelectorAll(queries.join(','))));\n\n      if ($link.hasClass(ClassName$8.DROPDOWN_ITEM)) {\n        $link.closest(Selector$8.DROPDOWN).find(Selector$8.DROPDOWN_TOGGLE).addClass(ClassName$8.ACTIVE);\n        $link.addClass(ClassName$8.ACTIVE);\n      } else {\n        // Set triggered link as active\n        $link.addClass(ClassName$8.ACTIVE); // Set triggered links parents as active\n        // With both <ul> and <nav> markup a parent is the previous sibling of any nav ancestor\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_LINKS + \", \" + Selector$8.LIST_ITEMS).addClass(ClassName$8.ACTIVE); // Handle special case when .nav-link is inside .nav-item\n\n        $link.parents(Selector$8.NAV_LIST_GROUP).prev(Selector$8.NAV_ITEMS).children(Selector$8.NAV_LINKS).addClass(ClassName$8.ACTIVE);\n      }\n\n      $(this._scrollElement).trigger(Event$8.ACTIVATE, {\n        relatedTarget: target\n      });\n    };\n\n    _proto._clear = function _clear() {\n      [].slice.call(document.querySelectorAll(this._selector)).filter(function (node) {\n        return node.classList.contains(ClassName$8.ACTIVE);\n      }).forEach(function (node) {\n        return node.classList.remove(ClassName$8.ACTIVE);\n      });\n    } // Static\n    ;\n\n    ScrollSpy._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var data = $(this).data(DATA_KEY$8);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new ScrollSpy(this, _config);\n          $(this).data(DATA_KEY$8, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(ScrollSpy, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$8;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$6;\n      }\n    }]);\n\n    return ScrollSpy;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(window).on(Event$8.LOAD_DATA_API, function () {\n    var scrollSpys = [].slice.call(document.querySelectorAll(Selector$8.DATA_SPY));\n    var scrollSpysLength = scrollSpys.length;\n\n    for (var i = scrollSpysLength; i--;) {\n      var $spy = $(scrollSpys[i]);\n\n      ScrollSpy._jQueryInterface.call($spy, $spy.data());\n    }\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$8] = ScrollSpy._jQueryInterface;\n  $.fn[NAME$8].Constructor = ScrollSpy;\n\n  $.fn[NAME$8].noConflict = function () {\n    $.fn[NAME$8] = JQUERY_NO_CONFLICT$8;\n    return ScrollSpy._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$9 = 'tab';\n  var VERSION$9 = '4.3.1';\n  var DATA_KEY$9 = 'bs.tab';\n  var EVENT_KEY$9 = \".\" + DATA_KEY$9;\n  var DATA_API_KEY$7 = '.data-api';\n  var JQUERY_NO_CONFLICT$9 = $.fn[NAME$9];\n  var Event$9 = {\n    HIDE: \"hide\" + EVENT_KEY$9,\n    HIDDEN: \"hidden\" + EVENT_KEY$9,\n    SHOW: \"show\" + EVENT_KEY$9,\n    SHOWN: \"shown\" + EVENT_KEY$9,\n    CLICK_DATA_API: \"click\" + EVENT_KEY$9 + DATA_API_KEY$7\n  };\n  var ClassName$9 = {\n    DROPDOWN_MENU: 'dropdown-menu',\n    ACTIVE: 'active',\n    DISABLED: 'disabled',\n    FADE: 'fade',\n    SHOW: 'show'\n  };\n  var Selector$9 = {\n    DROPDOWN: '.dropdown',\n    NAV_LIST_GROUP: '.nav, .list-group',\n    ACTIVE: '.active',\n    ACTIVE_UL: '> li > .active',\n    DATA_TOGGLE: '[data-toggle=\"tab\"], [data-toggle=\"pill\"], [data-toggle=\"list\"]',\n    DROPDOWN_TOGGLE: '.dropdown-toggle',\n    DROPDOWN_ACTIVE_CHILD: '> .dropdown-menu .active'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Tab =\n  /*#__PURE__*/\n  function () {\n    function Tab(element) {\n      this._element = element;\n    } // Getters\n\n\n    var _proto = Tab.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      if (this._element.parentNode && this._element.parentNode.nodeType === Node.ELEMENT_NODE && $(this._element).hasClass(ClassName$9.ACTIVE) || $(this._element).hasClass(ClassName$9.DISABLED)) {\n        return;\n      }\n\n      var target;\n      var previous;\n      var listElement = $(this._element).closest(Selector$9.NAV_LIST_GROUP)[0];\n      var selector = Util.getSelectorFromElement(this._element);\n\n      if (listElement) {\n        var itemSelector = listElement.nodeName === 'UL' || listElement.nodeName === 'OL' ? Selector$9.ACTIVE_UL : Selector$9.ACTIVE;\n        previous = $.makeArray($(listElement).find(itemSelector));\n        previous = previous[previous.length - 1];\n      }\n\n      var hideEvent = $.Event(Event$9.HIDE, {\n        relatedTarget: this._element\n      });\n      var showEvent = $.Event(Event$9.SHOW, {\n        relatedTarget: previous\n      });\n\n      if (previous) {\n        $(previous).trigger(hideEvent);\n      }\n\n      $(this._element).trigger(showEvent);\n\n      if (showEvent.isDefaultPrevented() || hideEvent.isDefaultPrevented()) {\n        return;\n      }\n\n      if (selector) {\n        target = document.querySelector(selector);\n      }\n\n      this._activate(this._element, listElement);\n\n      var complete = function complete() {\n        var hiddenEvent = $.Event(Event$9.HIDDEN, {\n          relatedTarget: _this._element\n        });\n        var shownEvent = $.Event(Event$9.SHOWN, {\n          relatedTarget: previous\n        });\n        $(previous).trigger(hiddenEvent);\n        $(_this._element).trigger(shownEvent);\n      };\n\n      if (target) {\n        this._activate(target, target.parentNode, complete);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      $.removeData(this._element, DATA_KEY$9);\n      this._element = null;\n    } // Private\n    ;\n\n    _proto._activate = function _activate(element, container, callback) {\n      var _this2 = this;\n\n      var activeElements = container && (container.nodeName === 'UL' || container.nodeName === 'OL') ? $(container).find(Selector$9.ACTIVE_UL) : $(container).children(Selector$9.ACTIVE);\n      var active = activeElements[0];\n      var isTransitioning = callback && active && $(active).hasClass(ClassName$9.FADE);\n\n      var complete = function complete() {\n        return _this2._transitionComplete(element, active, callback);\n      };\n\n      if (active && isTransitioning) {\n        var transitionDuration = Util.getTransitionDurationFromElement(active);\n        $(active).removeClass(ClassName$9.SHOW).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto._transitionComplete = function _transitionComplete(element, active, callback) {\n      if (active) {\n        $(active).removeClass(ClassName$9.ACTIVE);\n        var dropdownChild = $(active.parentNode).find(Selector$9.DROPDOWN_ACTIVE_CHILD)[0];\n\n        if (dropdownChild) {\n          $(dropdownChild).removeClass(ClassName$9.ACTIVE);\n        }\n\n        if (active.getAttribute('role') === 'tab') {\n          active.setAttribute('aria-selected', false);\n        }\n      }\n\n      $(element).addClass(ClassName$9.ACTIVE);\n\n      if (element.getAttribute('role') === 'tab') {\n        element.setAttribute('aria-selected', true);\n      }\n\n      Util.reflow(element);\n\n      if (element.classList.contains(ClassName$9.FADE)) {\n        element.classList.add(ClassName$9.SHOW);\n      }\n\n      if (element.parentNode && $(element.parentNode).hasClass(ClassName$9.DROPDOWN_MENU)) {\n        var dropdownElement = $(element).closest(Selector$9.DROPDOWN)[0];\n\n        if (dropdownElement) {\n          var dropdownToggleList = [].slice.call(dropdownElement.querySelectorAll(Selector$9.DROPDOWN_TOGGLE));\n          $(dropdownToggleList).addClass(ClassName$9.ACTIVE);\n        }\n\n        element.setAttribute('aria-expanded', true);\n      }\n\n      if (callback) {\n        callback();\n      }\n    } // Static\n    ;\n\n    Tab._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $this = $(this);\n        var data = $this.data(DATA_KEY$9);\n\n        if (!data) {\n          data = new Tab(this);\n          $this.data(DATA_KEY$9, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config]();\n        }\n      });\n    };\n\n    _createClass(Tab, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$9;\n      }\n    }]);\n\n    return Tab;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * Data Api implementation\n   * ------------------------------------------------------------------------\n   */\n\n\n  $(document).on(Event$9.CLICK_DATA_API, Selector$9.DATA_TOGGLE, function (event) {\n    event.preventDefault();\n\n    Tab._jQueryInterface.call($(this), 'show');\n  });\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n  $.fn[NAME$9] = Tab._jQueryInterface;\n  $.fn[NAME$9].Constructor = Tab;\n\n  $.fn[NAME$9].noConflict = function () {\n    $.fn[NAME$9] = JQUERY_NO_CONFLICT$9;\n    return Tab._jQueryInterface;\n  };\n\n  /**\n   * ------------------------------------------------------------------------\n   * Constants\n   * ------------------------------------------------------------------------\n   */\n\n  var NAME$a = 'toast';\n  var VERSION$a = '4.3.1';\n  var DATA_KEY$a = 'bs.toast';\n  var EVENT_KEY$a = \".\" + DATA_KEY$a;\n  var JQUERY_NO_CONFLICT$a = $.fn[NAME$a];\n  var Event$a = {\n    CLICK_DISMISS: \"click.dismiss\" + EVENT_KEY$a,\n    HIDE: \"hide\" + EVENT_KEY$a,\n    HIDDEN: \"hidden\" + EVENT_KEY$a,\n    SHOW: \"show\" + EVENT_KEY$a,\n    SHOWN: \"shown\" + EVENT_KEY$a\n  };\n  var ClassName$a = {\n    FADE: 'fade',\n    HIDE: 'hide',\n    SHOW: 'show',\n    SHOWING: 'showing'\n  };\n  var DefaultType$7 = {\n    animation: 'boolean',\n    autohide: 'boolean',\n    delay: 'number'\n  };\n  var Default$7 = {\n    animation: true,\n    autohide: true,\n    delay: 500\n  };\n  var Selector$a = {\n    DATA_DISMISS: '[data-dismiss=\"toast\"]'\n    /**\n     * ------------------------------------------------------------------------\n     * Class Definition\n     * ------------------------------------------------------------------------\n     */\n\n  };\n\n  var Toast =\n  /*#__PURE__*/\n  function () {\n    function Toast(element, config) {\n      this._element = element;\n      this._config = this._getConfig(config);\n      this._timeout = null;\n\n      this._setListeners();\n    } // Getters\n\n\n    var _proto = Toast.prototype;\n\n    // Public\n    _proto.show = function show() {\n      var _this = this;\n\n      $(this._element).trigger(Event$a.SHOW);\n\n      if (this._config.animation) {\n        this._element.classList.add(ClassName$a.FADE);\n      }\n\n      var complete = function complete() {\n        _this._element.classList.remove(ClassName$a.SHOWING);\n\n        _this._element.classList.add(ClassName$a.SHOW);\n\n        $(_this._element).trigger(Event$a.SHOWN);\n\n        if (_this._config.autohide) {\n          _this.hide();\n        }\n      };\n\n      this._element.classList.remove(ClassName$a.HIDE);\n\n      this._element.classList.add(ClassName$a.SHOWING);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    };\n\n    _proto.hide = function hide(withoutTimeout) {\n      var _this2 = this;\n\n      if (!this._element.classList.contains(ClassName$a.SHOW)) {\n        return;\n      }\n\n      $(this._element).trigger(Event$a.HIDE);\n\n      if (withoutTimeout) {\n        this._close();\n      } else {\n        this._timeout = setTimeout(function () {\n          _this2._close();\n        }, this._config.delay);\n      }\n    };\n\n    _proto.dispose = function dispose() {\n      clearTimeout(this._timeout);\n      this._timeout = null;\n\n      if (this._element.classList.contains(ClassName$a.SHOW)) {\n        this._element.classList.remove(ClassName$a.SHOW);\n      }\n\n      $(this._element).off(Event$a.CLICK_DISMISS);\n      $.removeData(this._element, DATA_KEY$a);\n      this._element = null;\n      this._config = null;\n    } // Private\n    ;\n\n    _proto._getConfig = function _getConfig(config) {\n      config = _objectSpread({}, Default$7, $(this._element).data(), typeof config === 'object' && config ? config : {});\n      Util.typeCheckConfig(NAME$a, config, this.constructor.DefaultType);\n      return config;\n    };\n\n    _proto._setListeners = function _setListeners() {\n      var _this3 = this;\n\n      $(this._element).on(Event$a.CLICK_DISMISS, Selector$a.DATA_DISMISS, function () {\n        return _this3.hide(true);\n      });\n    };\n\n    _proto._close = function _close() {\n      var _this4 = this;\n\n      var complete = function complete() {\n        _this4._element.classList.add(ClassName$a.HIDE);\n\n        $(_this4._element).trigger(Event$a.HIDDEN);\n      };\n\n      this._element.classList.remove(ClassName$a.SHOW);\n\n      if (this._config.animation) {\n        var transitionDuration = Util.getTransitionDurationFromElement(this._element);\n        $(this._element).one(Util.TRANSITION_END, complete).emulateTransitionEnd(transitionDuration);\n      } else {\n        complete();\n      }\n    } // Static\n    ;\n\n    Toast._jQueryInterface = function _jQueryInterface(config) {\n      return this.each(function () {\n        var $element = $(this);\n        var data = $element.data(DATA_KEY$a);\n\n        var _config = typeof config === 'object' && config;\n\n        if (!data) {\n          data = new Toast(this, _config);\n          $element.data(DATA_KEY$a, data);\n        }\n\n        if (typeof config === 'string') {\n          if (typeof data[config] === 'undefined') {\n            throw new TypeError(\"No method named \\\"\" + config + \"\\\"\");\n          }\n\n          data[config](this);\n        }\n      });\n    };\n\n    _createClass(Toast, null, [{\n      key: \"VERSION\",\n      get: function get() {\n        return VERSION$a;\n      }\n    }, {\n      key: \"DefaultType\",\n      get: function get() {\n        return DefaultType$7;\n      }\n    }, {\n      key: \"Default\",\n      get: function get() {\n        return Default$7;\n      }\n    }]);\n\n    return Toast;\n  }();\n  /**\n   * ------------------------------------------------------------------------\n   * jQuery\n   * ------------------------------------------------------------------------\n   */\n\n\n  $.fn[NAME$a] = Toast._jQueryInterface;\n  $.fn[NAME$a].Constructor = Toast;\n\n  $.fn[NAME$a].noConflict = function () {\n    $.fn[NAME$a] = JQUERY_NO_CONFLICT$a;\n    return Toast._jQueryInterface;\n  };\n\n  /**\n   * --------------------------------------------------------------------------\n   * Bootstrap (v4.3.1): index.js\n   * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE)\n   * --------------------------------------------------------------------------\n   */\n\n  (function () {\n    if (typeof $ === 'undefined') {\n      throw new TypeError('Bootstrap\\'s JavaScript requires jQuery. jQuery must be included before Bootstrap\\'s JavaScript.');\n    }\n\n    var version = $.fn.jquery.split(' ')[0].split('.');\n    var minMajor = 1;\n    var ltMajor = 2;\n    var minMinor = 9;\n    var minPatch = 1;\n    var maxMajor = 4;\n\n    if (version[0] < ltMajor && version[1] < minMinor || version[0] === minMajor && version[1] === minMinor && version[2] < minPatch || version[0] >= maxMajor) {\n      throw new Error('Bootstrap\\'s JavaScript requires at least jQuery v1.9.1 but less than v4.0.0');\n    }\n  })();\n\n  exports.Util = Util;\n  exports.Alert = Alert;\n  exports.Button = Button;\n  exports.Carousel = Carousel;\n  exports.Collapse = Collapse;\n  exports.Dropdown = Dropdown;\n  exports.Modal = Modal;\n  exports.Popover = Popover;\n  exports.Scrollspy = ScrollSpy;\n  exports.Tab = Tab;\n  exports.Toast = Toast;\n  exports.Tooltip = Tooltip;\n\n  Object.defineProperty(exports, '__esModule', { value: true });\n\n}));\n//# sourceMappingURL=bootstrap.js.map\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/LICENSE.txt",
    "content": "Font Awesome Free License\n-------------------------\n\nFont Awesome Free is free, open source, and GPL friendly. You can use it for\ncommercial projects, open source projects, or really almost whatever you want.\nFull Font Awesome Free license: https://fontawesome.com/license/free.\n\n# Icons: CC BY 4.0 License (https://creativecommons.org/licenses/by/4.0/)\nIn the Font Awesome Free download, the CC BY 4.0 license applies to all icons\npackaged as SVG and JS file types.\n\n# Fonts: SIL OFL 1.1 License (https://scripts.sil.org/OFL)\nIn the Font Awesome Free download, the SIL OFL license applies to all icons\npackaged as web and desktop font files.\n\n# Code: MIT License (https://opensource.org/licenses/MIT)\nIn the Font Awesome Free download, the MIT license applies to all non-font and\nnon-icon files.\n\n# Attribution\nAttribution is required by MIT, SIL OFL, and CC BY licenses. Downloaded Font\nAwesome Free files already contain embedded comments with sufficient\nattribution, so you shouldn't need to do anything additional when using these\nfiles normally.\n\nWe've kept attribution comments terse, so we ask that you do not actively work\nto remove them from files, especially code. They're a great way for folks to\nlearn about Font Awesome.\n\n# Brand Icons\nAll brand icons are trademarks of their respective owners. The use of these\ntrademarks does not indicate endorsement of the trademark holder by Font\nAwesome, nor vice versa. **Please do not use brand logos for any purpose except\nto represent the company, product, or service to which they refer.**\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/all.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n.fa,\n.fas,\n.far,\n.fal,\n.fad,\n.fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1; }\n\n.fa-lg {\n  font-size: 1.33333em;\n  line-height: 0.75em;\n  vertical-align: -.0667em; }\n\n.fa-xs {\n  font-size: .75em; }\n\n.fa-sm {\n  font-size: .875em; }\n\n.fa-1x {\n  font-size: 1em; }\n\n.fa-2x {\n  font-size: 2em; }\n\n.fa-3x {\n  font-size: 3em; }\n\n.fa-4x {\n  font-size: 4em; }\n\n.fa-5x {\n  font-size: 5em; }\n\n.fa-6x {\n  font-size: 6em; }\n\n.fa-7x {\n  font-size: 7em; }\n\n.fa-8x {\n  font-size: 8em; }\n\n.fa-9x {\n  font-size: 9em; }\n\n.fa-10x {\n  font-size: 10em; }\n\n.fa-fw {\n  text-align: center;\n  width: 1.25em; }\n\n.fa-ul {\n  list-style-type: none;\n  margin-left: 2.5em;\n  padding-left: 0; }\n  .fa-ul > li {\n    position: relative; }\n\n.fa-li {\n  left: -2em;\n  position: absolute;\n  text-align: center;\n  width: 2em;\n  line-height: inherit; }\n\n.fa-border {\n  border: solid 0.08em #eee;\n  border-radius: .1em;\n  padding: .2em .25em .15em; }\n\n.fa-pull-left {\n  float: left; }\n\n.fa-pull-right {\n  float: right; }\n\n.fa.fa-pull-left,\n.fas.fa-pull-left,\n.far.fa-pull-left,\n.fal.fa-pull-left,\n.fab.fa-pull-left {\n  margin-right: .3em; }\n\n.fa.fa-pull-right,\n.fas.fa-pull-right,\n.far.fa-pull-right,\n.fal.fa-pull-right,\n.fab.fa-pull-right {\n  margin-left: .3em; }\n\n.fa-spin {\n  -webkit-animation: fa-spin 2s infinite linear;\n          animation: fa-spin 2s infinite linear; }\n\n.fa-pulse {\n  -webkit-animation: fa-spin 1s infinite steps(8);\n          animation: fa-spin 1s infinite steps(8); }\n\n@-webkit-keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n@keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n.fa-rotate-90 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)\";\n  -webkit-transform: rotate(90deg);\n          transform: rotate(90deg); }\n\n.fa-rotate-180 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)\";\n  -webkit-transform: rotate(180deg);\n          transform: rotate(180deg); }\n\n.fa-rotate-270 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)\";\n  -webkit-transform: rotate(270deg);\n          transform: rotate(270deg); }\n\n.fa-flip-horizontal {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)\";\n  -webkit-transform: scale(-1, 1);\n          transform: scale(-1, 1); }\n\n.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(1, -1);\n          transform: scale(1, -1); }\n\n.fa-flip-both, .fa-flip-horizontal.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(-1, -1);\n          transform: scale(-1, -1); }\n\n:root .fa-rotate-90,\n:root .fa-rotate-180,\n:root .fa-rotate-270,\n:root .fa-flip-horizontal,\n:root .fa-flip-vertical,\n:root .fa-flip-both {\n  -webkit-filter: none;\n          filter: none; }\n\n.fa-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: 2.5em; }\n\n.fa-stack-1x,\n.fa-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%; }\n\n.fa-stack-1x {\n  line-height: inherit; }\n\n.fa-stack-2x {\n  font-size: 2em; }\n\n.fa-inverse {\n  color: #fff; }\n\n/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\nreaders do not read off random characters that represent icons */\n.fa-500px:before {\n  content: \"\\f26e\"; }\n\n.fa-accessible-icon:before {\n  content: \"\\f368\"; }\n\n.fa-accusoft:before {\n  content: \"\\f369\"; }\n\n.fa-acquisitions-incorporated:before {\n  content: \"\\f6af\"; }\n\n.fa-ad:before {\n  content: \"\\f641\"; }\n\n.fa-address-book:before {\n  content: \"\\f2b9\"; }\n\n.fa-address-card:before {\n  content: \"\\f2bb\"; }\n\n.fa-adjust:before {\n  content: \"\\f042\"; }\n\n.fa-adn:before {\n  content: \"\\f170\"; }\n\n.fa-adobe:before {\n  content: \"\\f778\"; }\n\n.fa-adversal:before {\n  content: \"\\f36a\"; }\n\n.fa-affiliatetheme:before {\n  content: \"\\f36b\"; }\n\n.fa-air-freshener:before {\n  content: \"\\f5d0\"; }\n\n.fa-airbnb:before {\n  content: \"\\f834\"; }\n\n.fa-algolia:before {\n  content: \"\\f36c\"; }\n\n.fa-align-center:before {\n  content: \"\\f037\"; }\n\n.fa-align-justify:before {\n  content: \"\\f039\"; }\n\n.fa-align-left:before {\n  content: \"\\f036\"; }\n\n.fa-align-right:before {\n  content: \"\\f038\"; }\n\n.fa-alipay:before {\n  content: \"\\f642\"; }\n\n.fa-allergies:before {\n  content: \"\\f461\"; }\n\n.fa-amazon:before {\n  content: \"\\f270\"; }\n\n.fa-amazon-pay:before {\n  content: \"\\f42c\"; }\n\n.fa-ambulance:before {\n  content: \"\\f0f9\"; }\n\n.fa-american-sign-language-interpreting:before {\n  content: \"\\f2a3\"; }\n\n.fa-amilia:before {\n  content: \"\\f36d\"; }\n\n.fa-anchor:before {\n  content: \"\\f13d\"; }\n\n.fa-android:before {\n  content: \"\\f17b\"; }\n\n.fa-angellist:before {\n  content: \"\\f209\"; }\n\n.fa-angle-double-down:before {\n  content: \"\\f103\"; }\n\n.fa-angle-double-left:before {\n  content: \"\\f100\"; }\n\n.fa-angle-double-right:before {\n  content: \"\\f101\"; }\n\n.fa-angle-double-up:before {\n  content: \"\\f102\"; }\n\n.fa-angle-down:before {\n  content: \"\\f107\"; }\n\n.fa-angle-left:before {\n  content: \"\\f104\"; }\n\n.fa-angle-right:before {\n  content: \"\\f105\"; }\n\n.fa-angle-up:before {\n  content: \"\\f106\"; }\n\n.fa-angry:before {\n  content: \"\\f556\"; }\n\n.fa-angrycreative:before {\n  content: \"\\f36e\"; }\n\n.fa-angular:before {\n  content: \"\\f420\"; }\n\n.fa-ankh:before {\n  content: \"\\f644\"; }\n\n.fa-app-store:before {\n  content: \"\\f36f\"; }\n\n.fa-app-store-ios:before {\n  content: \"\\f370\"; }\n\n.fa-apper:before {\n  content: \"\\f371\"; }\n\n.fa-apple:before {\n  content: \"\\f179\"; }\n\n.fa-apple-alt:before {\n  content: \"\\f5d1\"; }\n\n.fa-apple-pay:before {\n  content: \"\\f415\"; }\n\n.fa-archive:before {\n  content: \"\\f187\"; }\n\n.fa-archway:before {\n  content: \"\\f557\"; }\n\n.fa-arrow-alt-circle-down:before {\n  content: \"\\f358\"; }\n\n.fa-arrow-alt-circle-left:before {\n  content: \"\\f359\"; }\n\n.fa-arrow-alt-circle-right:before {\n  content: \"\\f35a\"; }\n\n.fa-arrow-alt-circle-up:before {\n  content: \"\\f35b\"; }\n\n.fa-arrow-circle-down:before {\n  content: \"\\f0ab\"; }\n\n.fa-arrow-circle-left:before {\n  content: \"\\f0a8\"; }\n\n.fa-arrow-circle-right:before {\n  content: \"\\f0a9\"; }\n\n.fa-arrow-circle-up:before {\n  content: \"\\f0aa\"; }\n\n.fa-arrow-down:before {\n  content: \"\\f063\"; }\n\n.fa-arrow-left:before {\n  content: \"\\f060\"; }\n\n.fa-arrow-right:before {\n  content: \"\\f061\"; }\n\n.fa-arrow-up:before {\n  content: \"\\f062\"; }\n\n.fa-arrows-alt:before {\n  content: \"\\f0b2\"; }\n\n.fa-arrows-alt-h:before {\n  content: \"\\f337\"; }\n\n.fa-arrows-alt-v:before {\n  content: \"\\f338\"; }\n\n.fa-artstation:before {\n  content: \"\\f77a\"; }\n\n.fa-assistive-listening-systems:before {\n  content: \"\\f2a2\"; }\n\n.fa-asterisk:before {\n  content: \"\\f069\"; }\n\n.fa-asymmetrik:before {\n  content: \"\\f372\"; }\n\n.fa-at:before {\n  content: \"\\f1fa\"; }\n\n.fa-atlas:before {\n  content: \"\\f558\"; }\n\n.fa-atlassian:before {\n  content: \"\\f77b\"; }\n\n.fa-atom:before {\n  content: \"\\f5d2\"; }\n\n.fa-audible:before {\n  content: \"\\f373\"; }\n\n.fa-audio-description:before {\n  content: \"\\f29e\"; }\n\n.fa-autoprefixer:before {\n  content: \"\\f41c\"; }\n\n.fa-avianex:before {\n  content: \"\\f374\"; }\n\n.fa-aviato:before {\n  content: \"\\f421\"; }\n\n.fa-award:before {\n  content: \"\\f559\"; }\n\n.fa-aws:before {\n  content: \"\\f375\"; }\n\n.fa-baby:before {\n  content: \"\\f77c\"; }\n\n.fa-baby-carriage:before {\n  content: \"\\f77d\"; }\n\n.fa-backspace:before {\n  content: \"\\f55a\"; }\n\n.fa-backward:before {\n  content: \"\\f04a\"; }\n\n.fa-bacon:before {\n  content: \"\\f7e5\"; }\n\n.fa-balance-scale:before {\n  content: \"\\f24e\"; }\n\n.fa-balance-scale-left:before {\n  content: \"\\f515\"; }\n\n.fa-balance-scale-right:before {\n  content: \"\\f516\"; }\n\n.fa-ban:before {\n  content: \"\\f05e\"; }\n\n.fa-band-aid:before {\n  content: \"\\f462\"; }\n\n.fa-bandcamp:before {\n  content: \"\\f2d5\"; }\n\n.fa-barcode:before {\n  content: \"\\f02a\"; }\n\n.fa-bars:before {\n  content: \"\\f0c9\"; }\n\n.fa-baseball-ball:before {\n  content: \"\\f433\"; }\n\n.fa-basketball-ball:before {\n  content: \"\\f434\"; }\n\n.fa-bath:before {\n  content: \"\\f2cd\"; }\n\n.fa-battery-empty:before {\n  content: \"\\f244\"; }\n\n.fa-battery-full:before {\n  content: \"\\f240\"; }\n\n.fa-battery-half:before {\n  content: \"\\f242\"; }\n\n.fa-battery-quarter:before {\n  content: \"\\f243\"; }\n\n.fa-battery-three-quarters:before {\n  content: \"\\f241\"; }\n\n.fa-battle-net:before {\n  content: \"\\f835\"; }\n\n.fa-bed:before {\n  content: \"\\f236\"; }\n\n.fa-beer:before {\n  content: \"\\f0fc\"; }\n\n.fa-behance:before {\n  content: \"\\f1b4\"; }\n\n.fa-behance-square:before {\n  content: \"\\f1b5\"; }\n\n.fa-bell:before {\n  content: \"\\f0f3\"; }\n\n.fa-bell-slash:before {\n  content: \"\\f1f6\"; }\n\n.fa-bezier-curve:before {\n  content: \"\\f55b\"; }\n\n.fa-bible:before {\n  content: \"\\f647\"; }\n\n.fa-bicycle:before {\n  content: \"\\f206\"; }\n\n.fa-biking:before {\n  content: \"\\f84a\"; }\n\n.fa-bimobject:before {\n  content: \"\\f378\"; }\n\n.fa-binoculars:before {\n  content: \"\\f1e5\"; }\n\n.fa-biohazard:before {\n  content: \"\\f780\"; }\n\n.fa-birthday-cake:before {\n  content: \"\\f1fd\"; }\n\n.fa-bitbucket:before {\n  content: \"\\f171\"; }\n\n.fa-bitcoin:before {\n  content: \"\\f379\"; }\n\n.fa-bity:before {\n  content: \"\\f37a\"; }\n\n.fa-black-tie:before {\n  content: \"\\f27e\"; }\n\n.fa-blackberry:before {\n  content: \"\\f37b\"; }\n\n.fa-blender:before {\n  content: \"\\f517\"; }\n\n.fa-blender-phone:before {\n  content: \"\\f6b6\"; }\n\n.fa-blind:before {\n  content: \"\\f29d\"; }\n\n.fa-blog:before {\n  content: \"\\f781\"; }\n\n.fa-blogger:before {\n  content: \"\\f37c\"; }\n\n.fa-blogger-b:before {\n  content: \"\\f37d\"; }\n\n.fa-bluetooth:before {\n  content: \"\\f293\"; }\n\n.fa-bluetooth-b:before {\n  content: \"\\f294\"; }\n\n.fa-bold:before {\n  content: \"\\f032\"; }\n\n.fa-bolt:before {\n  content: \"\\f0e7\"; }\n\n.fa-bomb:before {\n  content: \"\\f1e2\"; }\n\n.fa-bone:before {\n  content: \"\\f5d7\"; }\n\n.fa-bong:before {\n  content: \"\\f55c\"; }\n\n.fa-book:before {\n  content: \"\\f02d\"; }\n\n.fa-book-dead:before {\n  content: \"\\f6b7\"; }\n\n.fa-book-medical:before {\n  content: \"\\f7e6\"; }\n\n.fa-book-open:before {\n  content: \"\\f518\"; }\n\n.fa-book-reader:before {\n  content: \"\\f5da\"; }\n\n.fa-bookmark:before {\n  content: \"\\f02e\"; }\n\n.fa-bootstrap:before {\n  content: \"\\f836\"; }\n\n.fa-border-all:before {\n  content: \"\\f84c\"; }\n\n.fa-border-none:before {\n  content: \"\\f850\"; }\n\n.fa-border-style:before {\n  content: \"\\f853\"; }\n\n.fa-bowling-ball:before {\n  content: \"\\f436\"; }\n\n.fa-box:before {\n  content: \"\\f466\"; }\n\n.fa-box-open:before {\n  content: \"\\f49e\"; }\n\n.fa-boxes:before {\n  content: \"\\f468\"; }\n\n.fa-braille:before {\n  content: \"\\f2a1\"; }\n\n.fa-brain:before {\n  content: \"\\f5dc\"; }\n\n.fa-bread-slice:before {\n  content: \"\\f7ec\"; }\n\n.fa-briefcase:before {\n  content: \"\\f0b1\"; }\n\n.fa-briefcase-medical:before {\n  content: \"\\f469\"; }\n\n.fa-broadcast-tower:before {\n  content: \"\\f519\"; }\n\n.fa-broom:before {\n  content: \"\\f51a\"; }\n\n.fa-brush:before {\n  content: \"\\f55d\"; }\n\n.fa-btc:before {\n  content: \"\\f15a\"; }\n\n.fa-buffer:before {\n  content: \"\\f837\"; }\n\n.fa-bug:before {\n  content: \"\\f188\"; }\n\n.fa-building:before {\n  content: \"\\f1ad\"; }\n\n.fa-bullhorn:before {\n  content: \"\\f0a1\"; }\n\n.fa-bullseye:before {\n  content: \"\\f140\"; }\n\n.fa-burn:before {\n  content: \"\\f46a\"; }\n\n.fa-buromobelexperte:before {\n  content: \"\\f37f\"; }\n\n.fa-bus:before {\n  content: \"\\f207\"; }\n\n.fa-bus-alt:before {\n  content: \"\\f55e\"; }\n\n.fa-business-time:before {\n  content: \"\\f64a\"; }\n\n.fa-buysellads:before {\n  content: \"\\f20d\"; }\n\n.fa-calculator:before {\n  content: \"\\f1ec\"; }\n\n.fa-calendar:before {\n  content: \"\\f133\"; }\n\n.fa-calendar-alt:before {\n  content: \"\\f073\"; }\n\n.fa-calendar-check:before {\n  content: \"\\f274\"; }\n\n.fa-calendar-day:before {\n  content: \"\\f783\"; }\n\n.fa-calendar-minus:before {\n  content: \"\\f272\"; }\n\n.fa-calendar-plus:before {\n  content: \"\\f271\"; }\n\n.fa-calendar-times:before {\n  content: \"\\f273\"; }\n\n.fa-calendar-week:before {\n  content: \"\\f784\"; }\n\n.fa-camera:before {\n  content: \"\\f030\"; }\n\n.fa-camera-retro:before {\n  content: \"\\f083\"; }\n\n.fa-campground:before {\n  content: \"\\f6bb\"; }\n\n.fa-canadian-maple-leaf:before {\n  content: \"\\f785\"; }\n\n.fa-candy-cane:before {\n  content: \"\\f786\"; }\n\n.fa-cannabis:before {\n  content: \"\\f55f\"; }\n\n.fa-capsules:before {\n  content: \"\\f46b\"; }\n\n.fa-car:before {\n  content: \"\\f1b9\"; }\n\n.fa-car-alt:before {\n  content: \"\\f5de\"; }\n\n.fa-car-battery:before {\n  content: \"\\f5df\"; }\n\n.fa-car-crash:before {\n  content: \"\\f5e1\"; }\n\n.fa-car-side:before {\n  content: \"\\f5e4\"; }\n\n.fa-caret-down:before {\n  content: \"\\f0d7\"; }\n\n.fa-caret-left:before {\n  content: \"\\f0d9\"; }\n\n.fa-caret-right:before {\n  content: \"\\f0da\"; }\n\n.fa-caret-square-down:before {\n  content: \"\\f150\"; }\n\n.fa-caret-square-left:before {\n  content: \"\\f191\"; }\n\n.fa-caret-square-right:before {\n  content: \"\\f152\"; }\n\n.fa-caret-square-up:before {\n  content: \"\\f151\"; }\n\n.fa-caret-up:before {\n  content: \"\\f0d8\"; }\n\n.fa-carrot:before {\n  content: \"\\f787\"; }\n\n.fa-cart-arrow-down:before {\n  content: \"\\f218\"; }\n\n.fa-cart-plus:before {\n  content: \"\\f217\"; }\n\n.fa-cash-register:before {\n  content: \"\\f788\"; }\n\n.fa-cat:before {\n  content: \"\\f6be\"; }\n\n.fa-cc-amazon-pay:before {\n  content: \"\\f42d\"; }\n\n.fa-cc-amex:before {\n  content: \"\\f1f3\"; }\n\n.fa-cc-apple-pay:before {\n  content: \"\\f416\"; }\n\n.fa-cc-diners-club:before {\n  content: \"\\f24c\"; }\n\n.fa-cc-discover:before {\n  content: \"\\f1f2\"; }\n\n.fa-cc-jcb:before {\n  content: \"\\f24b\"; }\n\n.fa-cc-mastercard:before {\n  content: \"\\f1f1\"; }\n\n.fa-cc-paypal:before {\n  content: \"\\f1f4\"; }\n\n.fa-cc-stripe:before {\n  content: \"\\f1f5\"; }\n\n.fa-cc-visa:before {\n  content: \"\\f1f0\"; }\n\n.fa-centercode:before {\n  content: \"\\f380\"; }\n\n.fa-centos:before {\n  content: \"\\f789\"; }\n\n.fa-certificate:before {\n  content: \"\\f0a3\"; }\n\n.fa-chair:before {\n  content: \"\\f6c0\"; }\n\n.fa-chalkboard:before {\n  content: \"\\f51b\"; }\n\n.fa-chalkboard-teacher:before {\n  content: \"\\f51c\"; }\n\n.fa-charging-station:before {\n  content: \"\\f5e7\"; }\n\n.fa-chart-area:before {\n  content: \"\\f1fe\"; }\n\n.fa-chart-bar:before {\n  content: \"\\f080\"; }\n\n.fa-chart-line:before {\n  content: \"\\f201\"; }\n\n.fa-chart-pie:before {\n  content: \"\\f200\"; }\n\n.fa-check:before {\n  content: \"\\f00c\"; }\n\n.fa-check-circle:before {\n  content: \"\\f058\"; }\n\n.fa-check-double:before {\n  content: \"\\f560\"; }\n\n.fa-check-square:before {\n  content: \"\\f14a\"; }\n\n.fa-cheese:before {\n  content: \"\\f7ef\"; }\n\n.fa-chess:before {\n  content: \"\\f439\"; }\n\n.fa-chess-bishop:before {\n  content: \"\\f43a\"; }\n\n.fa-chess-board:before {\n  content: \"\\f43c\"; }\n\n.fa-chess-king:before {\n  content: \"\\f43f\"; }\n\n.fa-chess-knight:before {\n  content: \"\\f441\"; }\n\n.fa-chess-pawn:before {\n  content: \"\\f443\"; }\n\n.fa-chess-queen:before {\n  content: \"\\f445\"; }\n\n.fa-chess-rook:before {\n  content: \"\\f447\"; }\n\n.fa-chevron-circle-down:before {\n  content: \"\\f13a\"; }\n\n.fa-chevron-circle-left:before {\n  content: \"\\f137\"; }\n\n.fa-chevron-circle-right:before {\n  content: \"\\f138\"; }\n\n.fa-chevron-circle-up:before {\n  content: \"\\f139\"; }\n\n.fa-chevron-down:before {\n  content: \"\\f078\"; }\n\n.fa-chevron-left:before {\n  content: \"\\f053\"; }\n\n.fa-chevron-right:before {\n  content: \"\\f054\"; }\n\n.fa-chevron-up:before {\n  content: \"\\f077\"; }\n\n.fa-child:before {\n  content: \"\\f1ae\"; }\n\n.fa-chrome:before {\n  content: \"\\f268\"; }\n\n.fa-chromecast:before {\n  content: \"\\f838\"; }\n\n.fa-church:before {\n  content: \"\\f51d\"; }\n\n.fa-circle:before {\n  content: \"\\f111\"; }\n\n.fa-circle-notch:before {\n  content: \"\\f1ce\"; }\n\n.fa-city:before {\n  content: \"\\f64f\"; }\n\n.fa-clinic-medical:before {\n  content: \"\\f7f2\"; }\n\n.fa-clipboard:before {\n  content: \"\\f328\"; }\n\n.fa-clipboard-check:before {\n  content: \"\\f46c\"; }\n\n.fa-clipboard-list:before {\n  content: \"\\f46d\"; }\n\n.fa-clock:before {\n  content: \"\\f017\"; }\n\n.fa-clone:before {\n  content: \"\\f24d\"; }\n\n.fa-closed-captioning:before {\n  content: \"\\f20a\"; }\n\n.fa-cloud:before {\n  content: \"\\f0c2\"; }\n\n.fa-cloud-download-alt:before {\n  content: \"\\f381\"; }\n\n.fa-cloud-meatball:before {\n  content: \"\\f73b\"; }\n\n.fa-cloud-moon:before {\n  content: \"\\f6c3\"; }\n\n.fa-cloud-moon-rain:before {\n  content: \"\\f73c\"; }\n\n.fa-cloud-rain:before {\n  content: \"\\f73d\"; }\n\n.fa-cloud-showers-heavy:before {\n  content: \"\\f740\"; }\n\n.fa-cloud-sun:before {\n  content: \"\\f6c4\"; }\n\n.fa-cloud-sun-rain:before {\n  content: \"\\f743\"; }\n\n.fa-cloud-upload-alt:before {\n  content: \"\\f382\"; }\n\n.fa-cloudscale:before {\n  content: \"\\f383\"; }\n\n.fa-cloudsmith:before {\n  content: \"\\f384\"; }\n\n.fa-cloudversify:before {\n  content: \"\\f385\"; }\n\n.fa-cocktail:before {\n  content: \"\\f561\"; }\n\n.fa-code:before {\n  content: \"\\f121\"; }\n\n.fa-code-branch:before {\n  content: \"\\f126\"; }\n\n.fa-codepen:before {\n  content: \"\\f1cb\"; }\n\n.fa-codiepie:before {\n  content: \"\\f284\"; }\n\n.fa-coffee:before {\n  content: \"\\f0f4\"; }\n\n.fa-cog:before {\n  content: \"\\f013\"; }\n\n.fa-cogs:before {\n  content: \"\\f085\"; }\n\n.fa-coins:before {\n  content: \"\\f51e\"; }\n\n.fa-columns:before {\n  content: \"\\f0db\"; }\n\n.fa-comment:before {\n  content: \"\\f075\"; }\n\n.fa-comment-alt:before {\n  content: \"\\f27a\"; }\n\n.fa-comment-dollar:before {\n  content: \"\\f651\"; }\n\n.fa-comment-dots:before {\n  content: \"\\f4ad\"; }\n\n.fa-comment-medical:before {\n  content: \"\\f7f5\"; }\n\n.fa-comment-slash:before {\n  content: \"\\f4b3\"; }\n\n.fa-comments:before {\n  content: \"\\f086\"; }\n\n.fa-comments-dollar:before {\n  content: \"\\f653\"; }\n\n.fa-compact-disc:before {\n  content: \"\\f51f\"; }\n\n.fa-compass:before {\n  content: \"\\f14e\"; }\n\n.fa-compress:before {\n  content: \"\\f066\"; }\n\n.fa-compress-arrows-alt:before {\n  content: \"\\f78c\"; }\n\n.fa-concierge-bell:before {\n  content: \"\\f562\"; }\n\n.fa-confluence:before {\n  content: \"\\f78d\"; }\n\n.fa-connectdevelop:before {\n  content: \"\\f20e\"; }\n\n.fa-contao:before {\n  content: \"\\f26d\"; }\n\n.fa-cookie:before {\n  content: \"\\f563\"; }\n\n.fa-cookie-bite:before {\n  content: \"\\f564\"; }\n\n.fa-copy:before {\n  content: \"\\f0c5\"; }\n\n.fa-copyright:before {\n  content: \"\\f1f9\"; }\n\n.fa-cotton-bureau:before {\n  content: \"\\f89e\"; }\n\n.fa-couch:before {\n  content: \"\\f4b8\"; }\n\n.fa-cpanel:before {\n  content: \"\\f388\"; }\n\n.fa-creative-commons:before {\n  content: \"\\f25e\"; }\n\n.fa-creative-commons-by:before {\n  content: \"\\f4e7\"; }\n\n.fa-creative-commons-nc:before {\n  content: \"\\f4e8\"; }\n\n.fa-creative-commons-nc-eu:before {\n  content: \"\\f4e9\"; }\n\n.fa-creative-commons-nc-jp:before {\n  content: \"\\f4ea\"; }\n\n.fa-creative-commons-nd:before {\n  content: \"\\f4eb\"; }\n\n.fa-creative-commons-pd:before {\n  content: \"\\f4ec\"; }\n\n.fa-creative-commons-pd-alt:before {\n  content: \"\\f4ed\"; }\n\n.fa-creative-commons-remix:before {\n  content: \"\\f4ee\"; }\n\n.fa-creative-commons-sa:before {\n  content: \"\\f4ef\"; }\n\n.fa-creative-commons-sampling:before {\n  content: \"\\f4f0\"; }\n\n.fa-creative-commons-sampling-plus:before {\n  content: \"\\f4f1\"; }\n\n.fa-creative-commons-share:before {\n  content: \"\\f4f2\"; }\n\n.fa-creative-commons-zero:before {\n  content: \"\\f4f3\"; }\n\n.fa-credit-card:before {\n  content: \"\\f09d\"; }\n\n.fa-critical-role:before {\n  content: \"\\f6c9\"; }\n\n.fa-crop:before {\n  content: \"\\f125\"; }\n\n.fa-crop-alt:before {\n  content: \"\\f565\"; }\n\n.fa-cross:before {\n  content: \"\\f654\"; }\n\n.fa-crosshairs:before {\n  content: \"\\f05b\"; }\n\n.fa-crow:before {\n  content: \"\\f520\"; }\n\n.fa-crown:before {\n  content: \"\\f521\"; }\n\n.fa-crutch:before {\n  content: \"\\f7f7\"; }\n\n.fa-css3:before {\n  content: \"\\f13c\"; }\n\n.fa-css3-alt:before {\n  content: \"\\f38b\"; }\n\n.fa-cube:before {\n  content: \"\\f1b2\"; }\n\n.fa-cubes:before {\n  content: \"\\f1b3\"; }\n\n.fa-cut:before {\n  content: \"\\f0c4\"; }\n\n.fa-cuttlefish:before {\n  content: \"\\f38c\"; }\n\n.fa-d-and-d:before {\n  content: \"\\f38d\"; }\n\n.fa-d-and-d-beyond:before {\n  content: \"\\f6ca\"; }\n\n.fa-dashcube:before {\n  content: \"\\f210\"; }\n\n.fa-database:before {\n  content: \"\\f1c0\"; }\n\n.fa-deaf:before {\n  content: \"\\f2a4\"; }\n\n.fa-delicious:before {\n  content: \"\\f1a5\"; }\n\n.fa-democrat:before {\n  content: \"\\f747\"; }\n\n.fa-deploydog:before {\n  content: \"\\f38e\"; }\n\n.fa-deskpro:before {\n  content: \"\\f38f\"; }\n\n.fa-desktop:before {\n  content: \"\\f108\"; }\n\n.fa-dev:before {\n  content: \"\\f6cc\"; }\n\n.fa-deviantart:before {\n  content: \"\\f1bd\"; }\n\n.fa-dharmachakra:before {\n  content: \"\\f655\"; }\n\n.fa-dhl:before {\n  content: \"\\f790\"; }\n\n.fa-diagnoses:before {\n  content: \"\\f470\"; }\n\n.fa-diaspora:before {\n  content: \"\\f791\"; }\n\n.fa-dice:before {\n  content: \"\\f522\"; }\n\n.fa-dice-d20:before {\n  content: \"\\f6cf\"; }\n\n.fa-dice-d6:before {\n  content: \"\\f6d1\"; }\n\n.fa-dice-five:before {\n  content: \"\\f523\"; }\n\n.fa-dice-four:before {\n  content: \"\\f524\"; }\n\n.fa-dice-one:before {\n  content: \"\\f525\"; }\n\n.fa-dice-six:before {\n  content: \"\\f526\"; }\n\n.fa-dice-three:before {\n  content: \"\\f527\"; }\n\n.fa-dice-two:before {\n  content: \"\\f528\"; }\n\n.fa-digg:before {\n  content: \"\\f1a6\"; }\n\n.fa-digital-ocean:before {\n  content: \"\\f391\"; }\n\n.fa-digital-tachograph:before {\n  content: \"\\f566\"; }\n\n.fa-directions:before {\n  content: \"\\f5eb\"; }\n\n.fa-discord:before {\n  content: \"\\f392\"; }\n\n.fa-discourse:before {\n  content: \"\\f393\"; }\n\n.fa-divide:before {\n  content: \"\\f529\"; }\n\n.fa-dizzy:before {\n  content: \"\\f567\"; }\n\n.fa-dna:before {\n  content: \"\\f471\"; }\n\n.fa-dochub:before {\n  content: \"\\f394\"; }\n\n.fa-docker:before {\n  content: \"\\f395\"; }\n\n.fa-dog:before {\n  content: \"\\f6d3\"; }\n\n.fa-dollar-sign:before {\n  content: \"\\f155\"; }\n\n.fa-dolly:before {\n  content: \"\\f472\"; }\n\n.fa-dolly-flatbed:before {\n  content: \"\\f474\"; }\n\n.fa-donate:before {\n  content: \"\\f4b9\"; }\n\n.fa-door-closed:before {\n  content: \"\\f52a\"; }\n\n.fa-door-open:before {\n  content: \"\\f52b\"; }\n\n.fa-dot-circle:before {\n  content: \"\\f192\"; }\n\n.fa-dove:before {\n  content: \"\\f4ba\"; }\n\n.fa-download:before {\n  content: \"\\f019\"; }\n\n.fa-draft2digital:before {\n  content: \"\\f396\"; }\n\n.fa-drafting-compass:before {\n  content: \"\\f568\"; }\n\n.fa-dragon:before {\n  content: \"\\f6d5\"; }\n\n.fa-draw-polygon:before {\n  content: \"\\f5ee\"; }\n\n.fa-dribbble:before {\n  content: \"\\f17d\"; }\n\n.fa-dribbble-square:before {\n  content: \"\\f397\"; }\n\n.fa-dropbox:before {\n  content: \"\\f16b\"; }\n\n.fa-drum:before {\n  content: \"\\f569\"; }\n\n.fa-drum-steelpan:before {\n  content: \"\\f56a\"; }\n\n.fa-drumstick-bite:before {\n  content: \"\\f6d7\"; }\n\n.fa-drupal:before {\n  content: \"\\f1a9\"; }\n\n.fa-dumbbell:before {\n  content: \"\\f44b\"; }\n\n.fa-dumpster:before {\n  content: \"\\f793\"; }\n\n.fa-dumpster-fire:before {\n  content: \"\\f794\"; }\n\n.fa-dungeon:before {\n  content: \"\\f6d9\"; }\n\n.fa-dyalog:before {\n  content: \"\\f399\"; }\n\n.fa-earlybirds:before {\n  content: \"\\f39a\"; }\n\n.fa-ebay:before {\n  content: \"\\f4f4\"; }\n\n.fa-edge:before {\n  content: \"\\f282\"; }\n\n.fa-edit:before {\n  content: \"\\f044\"; }\n\n.fa-egg:before {\n  content: \"\\f7fb\"; }\n\n.fa-eject:before {\n  content: \"\\f052\"; }\n\n.fa-elementor:before {\n  content: \"\\f430\"; }\n\n.fa-ellipsis-h:before {\n  content: \"\\f141\"; }\n\n.fa-ellipsis-v:before {\n  content: \"\\f142\"; }\n\n.fa-ello:before {\n  content: \"\\f5f1\"; }\n\n.fa-ember:before {\n  content: \"\\f423\"; }\n\n.fa-empire:before {\n  content: \"\\f1d1\"; }\n\n.fa-envelope:before {\n  content: \"\\f0e0\"; }\n\n.fa-envelope-open:before {\n  content: \"\\f2b6\"; }\n\n.fa-envelope-open-text:before {\n  content: \"\\f658\"; }\n\n.fa-envelope-square:before {\n  content: \"\\f199\"; }\n\n.fa-envira:before {\n  content: \"\\f299\"; }\n\n.fa-equals:before {\n  content: \"\\f52c\"; }\n\n.fa-eraser:before {\n  content: \"\\f12d\"; }\n\n.fa-erlang:before {\n  content: \"\\f39d\"; }\n\n.fa-ethereum:before {\n  content: \"\\f42e\"; }\n\n.fa-ethernet:before {\n  content: \"\\f796\"; }\n\n.fa-etsy:before {\n  content: \"\\f2d7\"; }\n\n.fa-euro-sign:before {\n  content: \"\\f153\"; }\n\n.fa-evernote:before {\n  content: \"\\f839\"; }\n\n.fa-exchange-alt:before {\n  content: \"\\f362\"; }\n\n.fa-exclamation:before {\n  content: \"\\f12a\"; }\n\n.fa-exclamation-circle:before {\n  content: \"\\f06a\"; }\n\n.fa-exclamation-triangle:before {\n  content: \"\\f071\"; }\n\n.fa-expand:before {\n  content: \"\\f065\"; }\n\n.fa-expand-arrows-alt:before {\n  content: \"\\f31e\"; }\n\n.fa-expeditedssl:before {\n  content: \"\\f23e\"; }\n\n.fa-external-link-alt:before {\n  content: \"\\f35d\"; }\n\n.fa-external-link-square-alt:before {\n  content: \"\\f360\"; }\n\n.fa-eye:before {\n  content: \"\\f06e\"; }\n\n.fa-eye-dropper:before {\n  content: \"\\f1fb\"; }\n\n.fa-eye-slash:before {\n  content: \"\\f070\"; }\n\n.fa-facebook:before {\n  content: \"\\f09a\"; }\n\n.fa-facebook-f:before {\n  content: \"\\f39e\"; }\n\n.fa-facebook-messenger:before {\n  content: \"\\f39f\"; }\n\n.fa-facebook-square:before {\n  content: \"\\f082\"; }\n\n.fa-fan:before {\n  content: \"\\f863\"; }\n\n.fa-fantasy-flight-games:before {\n  content: \"\\f6dc\"; }\n\n.fa-fast-backward:before {\n  content: \"\\f049\"; }\n\n.fa-fast-forward:before {\n  content: \"\\f050\"; }\n\n.fa-fax:before {\n  content: \"\\f1ac\"; }\n\n.fa-feather:before {\n  content: \"\\f52d\"; }\n\n.fa-feather-alt:before {\n  content: \"\\f56b\"; }\n\n.fa-fedex:before {\n  content: \"\\f797\"; }\n\n.fa-fedora:before {\n  content: \"\\f798\"; }\n\n.fa-female:before {\n  content: \"\\f182\"; }\n\n.fa-fighter-jet:before {\n  content: \"\\f0fb\"; }\n\n.fa-figma:before {\n  content: \"\\f799\"; }\n\n.fa-file:before {\n  content: \"\\f15b\"; }\n\n.fa-file-alt:before {\n  content: \"\\f15c\"; }\n\n.fa-file-archive:before {\n  content: \"\\f1c6\"; }\n\n.fa-file-audio:before {\n  content: \"\\f1c7\"; }\n\n.fa-file-code:before {\n  content: \"\\f1c9\"; }\n\n.fa-file-contract:before {\n  content: \"\\f56c\"; }\n\n.fa-file-csv:before {\n  content: \"\\f6dd\"; }\n\n.fa-file-download:before {\n  content: \"\\f56d\"; }\n\n.fa-file-excel:before {\n  content: \"\\f1c3\"; }\n\n.fa-file-export:before {\n  content: \"\\f56e\"; }\n\n.fa-file-image:before {\n  content: \"\\f1c5\"; }\n\n.fa-file-import:before {\n  content: \"\\f56f\"; }\n\n.fa-file-invoice:before {\n  content: \"\\f570\"; }\n\n.fa-file-invoice-dollar:before {\n  content: \"\\f571\"; }\n\n.fa-file-medical:before {\n  content: \"\\f477\"; }\n\n.fa-file-medical-alt:before {\n  content: \"\\f478\"; }\n\n.fa-file-pdf:before {\n  content: \"\\f1c1\"; }\n\n.fa-file-powerpoint:before {\n  content: \"\\f1c4\"; }\n\n.fa-file-prescription:before {\n  content: \"\\f572\"; }\n\n.fa-file-signature:before {\n  content: \"\\f573\"; }\n\n.fa-file-upload:before {\n  content: \"\\f574\"; }\n\n.fa-file-video:before {\n  content: \"\\f1c8\"; }\n\n.fa-file-word:before {\n  content: \"\\f1c2\"; }\n\n.fa-fill:before {\n  content: \"\\f575\"; }\n\n.fa-fill-drip:before {\n  content: \"\\f576\"; }\n\n.fa-film:before {\n  content: \"\\f008\"; }\n\n.fa-filter:before {\n  content: \"\\f0b0\"; }\n\n.fa-fingerprint:before {\n  content: \"\\f577\"; }\n\n.fa-fire:before {\n  content: \"\\f06d\"; }\n\n.fa-fire-alt:before {\n  content: \"\\f7e4\"; }\n\n.fa-fire-extinguisher:before {\n  content: \"\\f134\"; }\n\n.fa-firefox:before {\n  content: \"\\f269\"; }\n\n.fa-first-aid:before {\n  content: \"\\f479\"; }\n\n.fa-first-order:before {\n  content: \"\\f2b0\"; }\n\n.fa-first-order-alt:before {\n  content: \"\\f50a\"; }\n\n.fa-firstdraft:before {\n  content: \"\\f3a1\"; }\n\n.fa-fish:before {\n  content: \"\\f578\"; }\n\n.fa-fist-raised:before {\n  content: \"\\f6de\"; }\n\n.fa-flag:before {\n  content: \"\\f024\"; }\n\n.fa-flag-checkered:before {\n  content: \"\\f11e\"; }\n\n.fa-flag-usa:before {\n  content: \"\\f74d\"; }\n\n.fa-flask:before {\n  content: \"\\f0c3\"; }\n\n.fa-flickr:before {\n  content: \"\\f16e\"; }\n\n.fa-flipboard:before {\n  content: \"\\f44d\"; }\n\n.fa-flushed:before {\n  content: \"\\f579\"; }\n\n.fa-fly:before {\n  content: \"\\f417\"; }\n\n.fa-folder:before {\n  content: \"\\f07b\"; }\n\n.fa-folder-minus:before {\n  content: \"\\f65d\"; }\n\n.fa-folder-open:before {\n  content: \"\\f07c\"; }\n\n.fa-folder-plus:before {\n  content: \"\\f65e\"; }\n\n.fa-font:before {\n  content: \"\\f031\"; }\n\n.fa-font-awesome:before {\n  content: \"\\f2b4\"; }\n\n.fa-font-awesome-alt:before {\n  content: \"\\f35c\"; }\n\n.fa-font-awesome-flag:before {\n  content: \"\\f425\"; }\n\n.fa-font-awesome-logo-full:before {\n  content: \"\\f4e6\"; }\n\n.fa-fonticons:before {\n  content: \"\\f280\"; }\n\n.fa-fonticons-fi:before {\n  content: \"\\f3a2\"; }\n\n.fa-football-ball:before {\n  content: \"\\f44e\"; }\n\n.fa-fort-awesome:before {\n  content: \"\\f286\"; }\n\n.fa-fort-awesome-alt:before {\n  content: \"\\f3a3\"; }\n\n.fa-forumbee:before {\n  content: \"\\f211\"; }\n\n.fa-forward:before {\n  content: \"\\f04e\"; }\n\n.fa-foursquare:before {\n  content: \"\\f180\"; }\n\n.fa-free-code-camp:before {\n  content: \"\\f2c5\"; }\n\n.fa-freebsd:before {\n  content: \"\\f3a4\"; }\n\n.fa-frog:before {\n  content: \"\\f52e\"; }\n\n.fa-frown:before {\n  content: \"\\f119\"; }\n\n.fa-frown-open:before {\n  content: \"\\f57a\"; }\n\n.fa-fulcrum:before {\n  content: \"\\f50b\"; }\n\n.fa-funnel-dollar:before {\n  content: \"\\f662\"; }\n\n.fa-futbol:before {\n  content: \"\\f1e3\"; }\n\n.fa-galactic-republic:before {\n  content: \"\\f50c\"; }\n\n.fa-galactic-senate:before {\n  content: \"\\f50d\"; }\n\n.fa-gamepad:before {\n  content: \"\\f11b\"; }\n\n.fa-gas-pump:before {\n  content: \"\\f52f\"; }\n\n.fa-gavel:before {\n  content: \"\\f0e3\"; }\n\n.fa-gem:before {\n  content: \"\\f3a5\"; }\n\n.fa-genderless:before {\n  content: \"\\f22d\"; }\n\n.fa-get-pocket:before {\n  content: \"\\f265\"; }\n\n.fa-gg:before {\n  content: \"\\f260\"; }\n\n.fa-gg-circle:before {\n  content: \"\\f261\"; }\n\n.fa-ghost:before {\n  content: \"\\f6e2\"; }\n\n.fa-gift:before {\n  content: \"\\f06b\"; }\n\n.fa-gifts:before {\n  content: \"\\f79c\"; }\n\n.fa-git:before {\n  content: \"\\f1d3\"; }\n\n.fa-git-alt:before {\n  content: \"\\f841\"; }\n\n.fa-git-square:before {\n  content: \"\\f1d2\"; }\n\n.fa-github:before {\n  content: \"\\f09b\"; }\n\n.fa-github-alt:before {\n  content: \"\\f113\"; }\n\n.fa-github-square:before {\n  content: \"\\f092\"; }\n\n.fa-gitkraken:before {\n  content: \"\\f3a6\"; }\n\n.fa-gitlab:before {\n  content: \"\\f296\"; }\n\n.fa-gitter:before {\n  content: \"\\f426\"; }\n\n.fa-glass-cheers:before {\n  content: \"\\f79f\"; }\n\n.fa-glass-martini:before {\n  content: \"\\f000\"; }\n\n.fa-glass-martini-alt:before {\n  content: \"\\f57b\"; }\n\n.fa-glass-whiskey:before {\n  content: \"\\f7a0\"; }\n\n.fa-glasses:before {\n  content: \"\\f530\"; }\n\n.fa-glide:before {\n  content: \"\\f2a5\"; }\n\n.fa-glide-g:before {\n  content: \"\\f2a6\"; }\n\n.fa-globe:before {\n  content: \"\\f0ac\"; }\n\n.fa-globe-africa:before {\n  content: \"\\f57c\"; }\n\n.fa-globe-americas:before {\n  content: \"\\f57d\"; }\n\n.fa-globe-asia:before {\n  content: \"\\f57e\"; }\n\n.fa-globe-europe:before {\n  content: \"\\f7a2\"; }\n\n.fa-gofore:before {\n  content: \"\\f3a7\"; }\n\n.fa-golf-ball:before {\n  content: \"\\f450\"; }\n\n.fa-goodreads:before {\n  content: \"\\f3a8\"; }\n\n.fa-goodreads-g:before {\n  content: \"\\f3a9\"; }\n\n.fa-google:before {\n  content: \"\\f1a0\"; }\n\n.fa-google-drive:before {\n  content: \"\\f3aa\"; }\n\n.fa-google-play:before {\n  content: \"\\f3ab\"; }\n\n.fa-google-plus:before {\n  content: \"\\f2b3\"; }\n\n.fa-google-plus-g:before {\n  content: \"\\f0d5\"; }\n\n.fa-google-plus-square:before {\n  content: \"\\f0d4\"; }\n\n.fa-google-wallet:before {\n  content: \"\\f1ee\"; }\n\n.fa-gopuram:before {\n  content: \"\\f664\"; }\n\n.fa-graduation-cap:before {\n  content: \"\\f19d\"; }\n\n.fa-gratipay:before {\n  content: \"\\f184\"; }\n\n.fa-grav:before {\n  content: \"\\f2d6\"; }\n\n.fa-greater-than:before {\n  content: \"\\f531\"; }\n\n.fa-greater-than-equal:before {\n  content: \"\\f532\"; }\n\n.fa-grimace:before {\n  content: \"\\f57f\"; }\n\n.fa-grin:before {\n  content: \"\\f580\"; }\n\n.fa-grin-alt:before {\n  content: \"\\f581\"; }\n\n.fa-grin-beam:before {\n  content: \"\\f582\"; }\n\n.fa-grin-beam-sweat:before {\n  content: \"\\f583\"; }\n\n.fa-grin-hearts:before {\n  content: \"\\f584\"; }\n\n.fa-grin-squint:before {\n  content: \"\\f585\"; }\n\n.fa-grin-squint-tears:before {\n  content: \"\\f586\"; }\n\n.fa-grin-stars:before {\n  content: \"\\f587\"; }\n\n.fa-grin-tears:before {\n  content: \"\\f588\"; }\n\n.fa-grin-tongue:before {\n  content: \"\\f589\"; }\n\n.fa-grin-tongue-squint:before {\n  content: \"\\f58a\"; }\n\n.fa-grin-tongue-wink:before {\n  content: \"\\f58b\"; }\n\n.fa-grin-wink:before {\n  content: \"\\f58c\"; }\n\n.fa-grip-horizontal:before {\n  content: \"\\f58d\"; }\n\n.fa-grip-lines:before {\n  content: \"\\f7a4\"; }\n\n.fa-grip-lines-vertical:before {\n  content: \"\\f7a5\"; }\n\n.fa-grip-vertical:before {\n  content: \"\\f58e\"; }\n\n.fa-gripfire:before {\n  content: \"\\f3ac\"; }\n\n.fa-grunt:before {\n  content: \"\\f3ad\"; }\n\n.fa-guitar:before {\n  content: \"\\f7a6\"; }\n\n.fa-gulp:before {\n  content: \"\\f3ae\"; }\n\n.fa-h-square:before {\n  content: \"\\f0fd\"; }\n\n.fa-hacker-news:before {\n  content: \"\\f1d4\"; }\n\n.fa-hacker-news-square:before {\n  content: \"\\f3af\"; }\n\n.fa-hackerrank:before {\n  content: \"\\f5f7\"; }\n\n.fa-hamburger:before {\n  content: \"\\f805\"; }\n\n.fa-hammer:before {\n  content: \"\\f6e3\"; }\n\n.fa-hamsa:before {\n  content: \"\\f665\"; }\n\n.fa-hand-holding:before {\n  content: \"\\f4bd\"; }\n\n.fa-hand-holding-heart:before {\n  content: \"\\f4be\"; }\n\n.fa-hand-holding-usd:before {\n  content: \"\\f4c0\"; }\n\n.fa-hand-lizard:before {\n  content: \"\\f258\"; }\n\n.fa-hand-middle-finger:before {\n  content: \"\\f806\"; }\n\n.fa-hand-paper:before {\n  content: \"\\f256\"; }\n\n.fa-hand-peace:before {\n  content: \"\\f25b\"; }\n\n.fa-hand-point-down:before {\n  content: \"\\f0a7\"; }\n\n.fa-hand-point-left:before {\n  content: \"\\f0a5\"; }\n\n.fa-hand-point-right:before {\n  content: \"\\f0a4\"; }\n\n.fa-hand-point-up:before {\n  content: \"\\f0a6\"; }\n\n.fa-hand-pointer:before {\n  content: \"\\f25a\"; }\n\n.fa-hand-rock:before {\n  content: \"\\f255\"; }\n\n.fa-hand-scissors:before {\n  content: \"\\f257\"; }\n\n.fa-hand-spock:before {\n  content: \"\\f259\"; }\n\n.fa-hands:before {\n  content: \"\\f4c2\"; }\n\n.fa-hands-helping:before {\n  content: \"\\f4c4\"; }\n\n.fa-handshake:before {\n  content: \"\\f2b5\"; }\n\n.fa-hanukiah:before {\n  content: \"\\f6e6\"; }\n\n.fa-hard-hat:before {\n  content: \"\\f807\"; }\n\n.fa-hashtag:before {\n  content: \"\\f292\"; }\n\n.fa-hat-wizard:before {\n  content: \"\\f6e8\"; }\n\n.fa-haykal:before {\n  content: \"\\f666\"; }\n\n.fa-hdd:before {\n  content: \"\\f0a0\"; }\n\n.fa-heading:before {\n  content: \"\\f1dc\"; }\n\n.fa-headphones:before {\n  content: \"\\f025\"; }\n\n.fa-headphones-alt:before {\n  content: \"\\f58f\"; }\n\n.fa-headset:before {\n  content: \"\\f590\"; }\n\n.fa-heart:before {\n  content: \"\\f004\"; }\n\n.fa-heart-broken:before {\n  content: \"\\f7a9\"; }\n\n.fa-heartbeat:before {\n  content: \"\\f21e\"; }\n\n.fa-helicopter:before {\n  content: \"\\f533\"; }\n\n.fa-highlighter:before {\n  content: \"\\f591\"; }\n\n.fa-hiking:before {\n  content: \"\\f6ec\"; }\n\n.fa-hippo:before {\n  content: \"\\f6ed\"; }\n\n.fa-hips:before {\n  content: \"\\f452\"; }\n\n.fa-hire-a-helper:before {\n  content: \"\\f3b0\"; }\n\n.fa-history:before {\n  content: \"\\f1da\"; }\n\n.fa-hockey-puck:before {\n  content: \"\\f453\"; }\n\n.fa-holly-berry:before {\n  content: \"\\f7aa\"; }\n\n.fa-home:before {\n  content: \"\\f015\"; }\n\n.fa-hooli:before {\n  content: \"\\f427\"; }\n\n.fa-hornbill:before {\n  content: \"\\f592\"; }\n\n.fa-horse:before {\n  content: \"\\f6f0\"; }\n\n.fa-horse-head:before {\n  content: \"\\f7ab\"; }\n\n.fa-hospital:before {\n  content: \"\\f0f8\"; }\n\n.fa-hospital-alt:before {\n  content: \"\\f47d\"; }\n\n.fa-hospital-symbol:before {\n  content: \"\\f47e\"; }\n\n.fa-hot-tub:before {\n  content: \"\\f593\"; }\n\n.fa-hotdog:before {\n  content: \"\\f80f\"; }\n\n.fa-hotel:before {\n  content: \"\\f594\"; }\n\n.fa-hotjar:before {\n  content: \"\\f3b1\"; }\n\n.fa-hourglass:before {\n  content: \"\\f254\"; }\n\n.fa-hourglass-end:before {\n  content: \"\\f253\"; }\n\n.fa-hourglass-half:before {\n  content: \"\\f252\"; }\n\n.fa-hourglass-start:before {\n  content: \"\\f251\"; }\n\n.fa-house-damage:before {\n  content: \"\\f6f1\"; }\n\n.fa-houzz:before {\n  content: \"\\f27c\"; }\n\n.fa-hryvnia:before {\n  content: \"\\f6f2\"; }\n\n.fa-html5:before {\n  content: \"\\f13b\"; }\n\n.fa-hubspot:before {\n  content: \"\\f3b2\"; }\n\n.fa-i-cursor:before {\n  content: \"\\f246\"; }\n\n.fa-ice-cream:before {\n  content: \"\\f810\"; }\n\n.fa-icicles:before {\n  content: \"\\f7ad\"; }\n\n.fa-icons:before {\n  content: \"\\f86d\"; }\n\n.fa-id-badge:before {\n  content: \"\\f2c1\"; }\n\n.fa-id-card:before {\n  content: \"\\f2c2\"; }\n\n.fa-id-card-alt:before {\n  content: \"\\f47f\"; }\n\n.fa-igloo:before {\n  content: \"\\f7ae\"; }\n\n.fa-image:before {\n  content: \"\\f03e\"; }\n\n.fa-images:before {\n  content: \"\\f302\"; }\n\n.fa-imdb:before {\n  content: \"\\f2d8\"; }\n\n.fa-inbox:before {\n  content: \"\\f01c\"; }\n\n.fa-indent:before {\n  content: \"\\f03c\"; }\n\n.fa-industry:before {\n  content: \"\\f275\"; }\n\n.fa-infinity:before {\n  content: \"\\f534\"; }\n\n.fa-info:before {\n  content: \"\\f129\"; }\n\n.fa-info-circle:before {\n  content: \"\\f05a\"; }\n\n.fa-instagram:before {\n  content: \"\\f16d\"; }\n\n.fa-intercom:before {\n  content: \"\\f7af\"; }\n\n.fa-internet-explorer:before {\n  content: \"\\f26b\"; }\n\n.fa-invision:before {\n  content: \"\\f7b0\"; }\n\n.fa-ioxhost:before {\n  content: \"\\f208\"; }\n\n.fa-italic:before {\n  content: \"\\f033\"; }\n\n.fa-itch-io:before {\n  content: \"\\f83a\"; }\n\n.fa-itunes:before {\n  content: \"\\f3b4\"; }\n\n.fa-itunes-note:before {\n  content: \"\\f3b5\"; }\n\n.fa-java:before {\n  content: \"\\f4e4\"; }\n\n.fa-jedi:before {\n  content: \"\\f669\"; }\n\n.fa-jedi-order:before {\n  content: \"\\f50e\"; }\n\n.fa-jenkins:before {\n  content: \"\\f3b6\"; }\n\n.fa-jira:before {\n  content: \"\\f7b1\"; }\n\n.fa-joget:before {\n  content: \"\\f3b7\"; }\n\n.fa-joint:before {\n  content: \"\\f595\"; }\n\n.fa-joomla:before {\n  content: \"\\f1aa\"; }\n\n.fa-journal-whills:before {\n  content: \"\\f66a\"; }\n\n.fa-js:before {\n  content: \"\\f3b8\"; }\n\n.fa-js-square:before {\n  content: \"\\f3b9\"; }\n\n.fa-jsfiddle:before {\n  content: \"\\f1cc\"; }\n\n.fa-kaaba:before {\n  content: \"\\f66b\"; }\n\n.fa-kaggle:before {\n  content: \"\\f5fa\"; }\n\n.fa-key:before {\n  content: \"\\f084\"; }\n\n.fa-keybase:before {\n  content: \"\\f4f5\"; }\n\n.fa-keyboard:before {\n  content: \"\\f11c\"; }\n\n.fa-keycdn:before {\n  content: \"\\f3ba\"; }\n\n.fa-khanda:before {\n  content: \"\\f66d\"; }\n\n.fa-kickstarter:before {\n  content: \"\\f3bb\"; }\n\n.fa-kickstarter-k:before {\n  content: \"\\f3bc\"; }\n\n.fa-kiss:before {\n  content: \"\\f596\"; }\n\n.fa-kiss-beam:before {\n  content: \"\\f597\"; }\n\n.fa-kiss-wink-heart:before {\n  content: \"\\f598\"; }\n\n.fa-kiwi-bird:before {\n  content: \"\\f535\"; }\n\n.fa-korvue:before {\n  content: \"\\f42f\"; }\n\n.fa-landmark:before {\n  content: \"\\f66f\"; }\n\n.fa-language:before {\n  content: \"\\f1ab\"; }\n\n.fa-laptop:before {\n  content: \"\\f109\"; }\n\n.fa-laptop-code:before {\n  content: \"\\f5fc\"; }\n\n.fa-laptop-medical:before {\n  content: \"\\f812\"; }\n\n.fa-laravel:before {\n  content: \"\\f3bd\"; }\n\n.fa-lastfm:before {\n  content: \"\\f202\"; }\n\n.fa-lastfm-square:before {\n  content: \"\\f203\"; }\n\n.fa-laugh:before {\n  content: \"\\f599\"; }\n\n.fa-laugh-beam:before {\n  content: \"\\f59a\"; }\n\n.fa-laugh-squint:before {\n  content: \"\\f59b\"; }\n\n.fa-laugh-wink:before {\n  content: \"\\f59c\"; }\n\n.fa-layer-group:before {\n  content: \"\\f5fd\"; }\n\n.fa-leaf:before {\n  content: \"\\f06c\"; }\n\n.fa-leanpub:before {\n  content: \"\\f212\"; }\n\n.fa-lemon:before {\n  content: \"\\f094\"; }\n\n.fa-less:before {\n  content: \"\\f41d\"; }\n\n.fa-less-than:before {\n  content: \"\\f536\"; }\n\n.fa-less-than-equal:before {\n  content: \"\\f537\"; }\n\n.fa-level-down-alt:before {\n  content: \"\\f3be\"; }\n\n.fa-level-up-alt:before {\n  content: \"\\f3bf\"; }\n\n.fa-life-ring:before {\n  content: \"\\f1cd\"; }\n\n.fa-lightbulb:before {\n  content: \"\\f0eb\"; }\n\n.fa-line:before {\n  content: \"\\f3c0\"; }\n\n.fa-link:before {\n  content: \"\\f0c1\"; }\n\n.fa-linkedin:before {\n  content: \"\\f08c\"; }\n\n.fa-linkedin-in:before {\n  content: \"\\f0e1\"; }\n\n.fa-linode:before {\n  content: \"\\f2b8\"; }\n\n.fa-linux:before {\n  content: \"\\f17c\"; }\n\n.fa-lira-sign:before {\n  content: \"\\f195\"; }\n\n.fa-list:before {\n  content: \"\\f03a\"; }\n\n.fa-list-alt:before {\n  content: \"\\f022\"; }\n\n.fa-list-ol:before {\n  content: \"\\f0cb\"; }\n\n.fa-list-ul:before {\n  content: \"\\f0ca\"; }\n\n.fa-location-arrow:before {\n  content: \"\\f124\"; }\n\n.fa-lock:before {\n  content: \"\\f023\"; }\n\n.fa-lock-open:before {\n  content: \"\\f3c1\"; }\n\n.fa-long-arrow-alt-down:before {\n  content: \"\\f309\"; }\n\n.fa-long-arrow-alt-left:before {\n  content: \"\\f30a\"; }\n\n.fa-long-arrow-alt-right:before {\n  content: \"\\f30b\"; }\n\n.fa-long-arrow-alt-up:before {\n  content: \"\\f30c\"; }\n\n.fa-low-vision:before {\n  content: \"\\f2a8\"; }\n\n.fa-luggage-cart:before {\n  content: \"\\f59d\"; }\n\n.fa-lyft:before {\n  content: \"\\f3c3\"; }\n\n.fa-magento:before {\n  content: \"\\f3c4\"; }\n\n.fa-magic:before {\n  content: \"\\f0d0\"; }\n\n.fa-magnet:before {\n  content: \"\\f076\"; }\n\n.fa-mail-bulk:before {\n  content: \"\\f674\"; }\n\n.fa-mailchimp:before {\n  content: \"\\f59e\"; }\n\n.fa-male:before {\n  content: \"\\f183\"; }\n\n.fa-mandalorian:before {\n  content: \"\\f50f\"; }\n\n.fa-map:before {\n  content: \"\\f279\"; }\n\n.fa-map-marked:before {\n  content: \"\\f59f\"; }\n\n.fa-map-marked-alt:before {\n  content: \"\\f5a0\"; }\n\n.fa-map-marker:before {\n  content: \"\\f041\"; }\n\n.fa-map-marker-alt:before {\n  content: \"\\f3c5\"; }\n\n.fa-map-pin:before {\n  content: \"\\f276\"; }\n\n.fa-map-signs:before {\n  content: \"\\f277\"; }\n\n.fa-markdown:before {\n  content: \"\\f60f\"; }\n\n.fa-marker:before {\n  content: \"\\f5a1\"; }\n\n.fa-mars:before {\n  content: \"\\f222\"; }\n\n.fa-mars-double:before {\n  content: \"\\f227\"; }\n\n.fa-mars-stroke:before {\n  content: \"\\f229\"; }\n\n.fa-mars-stroke-h:before {\n  content: \"\\f22b\"; }\n\n.fa-mars-stroke-v:before {\n  content: \"\\f22a\"; }\n\n.fa-mask:before {\n  content: \"\\f6fa\"; }\n\n.fa-mastodon:before {\n  content: \"\\f4f6\"; }\n\n.fa-maxcdn:before {\n  content: \"\\f136\"; }\n\n.fa-medal:before {\n  content: \"\\f5a2\"; }\n\n.fa-medapps:before {\n  content: \"\\f3c6\"; }\n\n.fa-medium:before {\n  content: \"\\f23a\"; }\n\n.fa-medium-m:before {\n  content: \"\\f3c7\"; }\n\n.fa-medkit:before {\n  content: \"\\f0fa\"; }\n\n.fa-medrt:before {\n  content: \"\\f3c8\"; }\n\n.fa-meetup:before {\n  content: \"\\f2e0\"; }\n\n.fa-megaport:before {\n  content: \"\\f5a3\"; }\n\n.fa-meh:before {\n  content: \"\\f11a\"; }\n\n.fa-meh-blank:before {\n  content: \"\\f5a4\"; }\n\n.fa-meh-rolling-eyes:before {\n  content: \"\\f5a5\"; }\n\n.fa-memory:before {\n  content: \"\\f538\"; }\n\n.fa-mendeley:before {\n  content: \"\\f7b3\"; }\n\n.fa-menorah:before {\n  content: \"\\f676\"; }\n\n.fa-mercury:before {\n  content: \"\\f223\"; }\n\n.fa-meteor:before {\n  content: \"\\f753\"; }\n\n.fa-microchip:before {\n  content: \"\\f2db\"; }\n\n.fa-microphone:before {\n  content: \"\\f130\"; }\n\n.fa-microphone-alt:before {\n  content: \"\\f3c9\"; }\n\n.fa-microphone-alt-slash:before {\n  content: \"\\f539\"; }\n\n.fa-microphone-slash:before {\n  content: \"\\f131\"; }\n\n.fa-microscope:before {\n  content: \"\\f610\"; }\n\n.fa-microsoft:before {\n  content: \"\\f3ca\"; }\n\n.fa-minus:before {\n  content: \"\\f068\"; }\n\n.fa-minus-circle:before {\n  content: \"\\f056\"; }\n\n.fa-minus-square:before {\n  content: \"\\f146\"; }\n\n.fa-mitten:before {\n  content: \"\\f7b5\"; }\n\n.fa-mix:before {\n  content: \"\\f3cb\"; }\n\n.fa-mixcloud:before {\n  content: \"\\f289\"; }\n\n.fa-mizuni:before {\n  content: \"\\f3cc\"; }\n\n.fa-mobile:before {\n  content: \"\\f10b\"; }\n\n.fa-mobile-alt:before {\n  content: \"\\f3cd\"; }\n\n.fa-modx:before {\n  content: \"\\f285\"; }\n\n.fa-monero:before {\n  content: \"\\f3d0\"; }\n\n.fa-money-bill:before {\n  content: \"\\f0d6\"; }\n\n.fa-money-bill-alt:before {\n  content: \"\\f3d1\"; }\n\n.fa-money-bill-wave:before {\n  content: \"\\f53a\"; }\n\n.fa-money-bill-wave-alt:before {\n  content: \"\\f53b\"; }\n\n.fa-money-check:before {\n  content: \"\\f53c\"; }\n\n.fa-money-check-alt:before {\n  content: \"\\f53d\"; }\n\n.fa-monument:before {\n  content: \"\\f5a6\"; }\n\n.fa-moon:before {\n  content: \"\\f186\"; }\n\n.fa-mortar-pestle:before {\n  content: \"\\f5a7\"; }\n\n.fa-mosque:before {\n  content: \"\\f678\"; }\n\n.fa-motorcycle:before {\n  content: \"\\f21c\"; }\n\n.fa-mountain:before {\n  content: \"\\f6fc\"; }\n\n.fa-mouse-pointer:before {\n  content: \"\\f245\"; }\n\n.fa-mug-hot:before {\n  content: \"\\f7b6\"; }\n\n.fa-music:before {\n  content: \"\\f001\"; }\n\n.fa-napster:before {\n  content: \"\\f3d2\"; }\n\n.fa-neos:before {\n  content: \"\\f612\"; }\n\n.fa-network-wired:before {\n  content: \"\\f6ff\"; }\n\n.fa-neuter:before {\n  content: \"\\f22c\"; }\n\n.fa-newspaper:before {\n  content: \"\\f1ea\"; }\n\n.fa-nimblr:before {\n  content: \"\\f5a8\"; }\n\n.fa-node:before {\n  content: \"\\f419\"; }\n\n.fa-node-js:before {\n  content: \"\\f3d3\"; }\n\n.fa-not-equal:before {\n  content: \"\\f53e\"; }\n\n.fa-notes-medical:before {\n  content: \"\\f481\"; }\n\n.fa-npm:before {\n  content: \"\\f3d4\"; }\n\n.fa-ns8:before {\n  content: \"\\f3d5\"; }\n\n.fa-nutritionix:before {\n  content: \"\\f3d6\"; }\n\n.fa-object-group:before {\n  content: \"\\f247\"; }\n\n.fa-object-ungroup:before {\n  content: \"\\f248\"; }\n\n.fa-odnoklassniki:before {\n  content: \"\\f263\"; }\n\n.fa-odnoklassniki-square:before {\n  content: \"\\f264\"; }\n\n.fa-oil-can:before {\n  content: \"\\f613\"; }\n\n.fa-old-republic:before {\n  content: \"\\f510\"; }\n\n.fa-om:before {\n  content: \"\\f679\"; }\n\n.fa-opencart:before {\n  content: \"\\f23d\"; }\n\n.fa-openid:before {\n  content: \"\\f19b\"; }\n\n.fa-opera:before {\n  content: \"\\f26a\"; }\n\n.fa-optin-monster:before {\n  content: \"\\f23c\"; }\n\n.fa-osi:before {\n  content: \"\\f41a\"; }\n\n.fa-otter:before {\n  content: \"\\f700\"; }\n\n.fa-outdent:before {\n  content: \"\\f03b\"; }\n\n.fa-page4:before {\n  content: \"\\f3d7\"; }\n\n.fa-pagelines:before {\n  content: \"\\f18c\"; }\n\n.fa-pager:before {\n  content: \"\\f815\"; }\n\n.fa-paint-brush:before {\n  content: \"\\f1fc\"; }\n\n.fa-paint-roller:before {\n  content: \"\\f5aa\"; }\n\n.fa-palette:before {\n  content: \"\\f53f\"; }\n\n.fa-palfed:before {\n  content: \"\\f3d8\"; }\n\n.fa-pallet:before {\n  content: \"\\f482\"; }\n\n.fa-paper-plane:before {\n  content: \"\\f1d8\"; }\n\n.fa-paperclip:before {\n  content: \"\\f0c6\"; }\n\n.fa-parachute-box:before {\n  content: \"\\f4cd\"; }\n\n.fa-paragraph:before {\n  content: \"\\f1dd\"; }\n\n.fa-parking:before {\n  content: \"\\f540\"; }\n\n.fa-passport:before {\n  content: \"\\f5ab\"; }\n\n.fa-pastafarianism:before {\n  content: \"\\f67b\"; }\n\n.fa-paste:before {\n  content: \"\\f0ea\"; }\n\n.fa-patreon:before {\n  content: \"\\f3d9\"; }\n\n.fa-pause:before {\n  content: \"\\f04c\"; }\n\n.fa-pause-circle:before {\n  content: \"\\f28b\"; }\n\n.fa-paw:before {\n  content: \"\\f1b0\"; }\n\n.fa-paypal:before {\n  content: \"\\f1ed\"; }\n\n.fa-peace:before {\n  content: \"\\f67c\"; }\n\n.fa-pen:before {\n  content: \"\\f304\"; }\n\n.fa-pen-alt:before {\n  content: \"\\f305\"; }\n\n.fa-pen-fancy:before {\n  content: \"\\f5ac\"; }\n\n.fa-pen-nib:before {\n  content: \"\\f5ad\"; }\n\n.fa-pen-square:before {\n  content: \"\\f14b\"; }\n\n.fa-pencil-alt:before {\n  content: \"\\f303\"; }\n\n.fa-pencil-ruler:before {\n  content: \"\\f5ae\"; }\n\n.fa-penny-arcade:before {\n  content: \"\\f704\"; }\n\n.fa-people-carry:before {\n  content: \"\\f4ce\"; }\n\n.fa-pepper-hot:before {\n  content: \"\\f816\"; }\n\n.fa-percent:before {\n  content: \"\\f295\"; }\n\n.fa-percentage:before {\n  content: \"\\f541\"; }\n\n.fa-periscope:before {\n  content: \"\\f3da\"; }\n\n.fa-person-booth:before {\n  content: \"\\f756\"; }\n\n.fa-phabricator:before {\n  content: \"\\f3db\"; }\n\n.fa-phoenix-framework:before {\n  content: \"\\f3dc\"; }\n\n.fa-phoenix-squadron:before {\n  content: \"\\f511\"; }\n\n.fa-phone:before {\n  content: \"\\f095\"; }\n\n.fa-phone-alt:before {\n  content: \"\\f879\"; }\n\n.fa-phone-slash:before {\n  content: \"\\f3dd\"; }\n\n.fa-phone-square:before {\n  content: \"\\f098\"; }\n\n.fa-phone-square-alt:before {\n  content: \"\\f87b\"; }\n\n.fa-phone-volume:before {\n  content: \"\\f2a0\"; }\n\n.fa-photo-video:before {\n  content: \"\\f87c\"; }\n\n.fa-php:before {\n  content: \"\\f457\"; }\n\n.fa-pied-piper:before {\n  content: \"\\f2ae\"; }\n\n.fa-pied-piper-alt:before {\n  content: \"\\f1a8\"; }\n\n.fa-pied-piper-hat:before {\n  content: \"\\f4e5\"; }\n\n.fa-pied-piper-pp:before {\n  content: \"\\f1a7\"; }\n\n.fa-piggy-bank:before {\n  content: \"\\f4d3\"; }\n\n.fa-pills:before {\n  content: \"\\f484\"; }\n\n.fa-pinterest:before {\n  content: \"\\f0d2\"; }\n\n.fa-pinterest-p:before {\n  content: \"\\f231\"; }\n\n.fa-pinterest-square:before {\n  content: \"\\f0d3\"; }\n\n.fa-pizza-slice:before {\n  content: \"\\f818\"; }\n\n.fa-place-of-worship:before {\n  content: \"\\f67f\"; }\n\n.fa-plane:before {\n  content: \"\\f072\"; }\n\n.fa-plane-arrival:before {\n  content: \"\\f5af\"; }\n\n.fa-plane-departure:before {\n  content: \"\\f5b0\"; }\n\n.fa-play:before {\n  content: \"\\f04b\"; }\n\n.fa-play-circle:before {\n  content: \"\\f144\"; }\n\n.fa-playstation:before {\n  content: \"\\f3df\"; }\n\n.fa-plug:before {\n  content: \"\\f1e6\"; }\n\n.fa-plus:before {\n  content: \"\\f067\"; }\n\n.fa-plus-circle:before {\n  content: \"\\f055\"; }\n\n.fa-plus-square:before {\n  content: \"\\f0fe\"; }\n\n.fa-podcast:before {\n  content: \"\\f2ce\"; }\n\n.fa-poll:before {\n  content: \"\\f681\"; }\n\n.fa-poll-h:before {\n  content: \"\\f682\"; }\n\n.fa-poo:before {\n  content: \"\\f2fe\"; }\n\n.fa-poo-storm:before {\n  content: \"\\f75a\"; }\n\n.fa-poop:before {\n  content: \"\\f619\"; }\n\n.fa-portrait:before {\n  content: \"\\f3e0\"; }\n\n.fa-pound-sign:before {\n  content: \"\\f154\"; }\n\n.fa-power-off:before {\n  content: \"\\f011\"; }\n\n.fa-pray:before {\n  content: \"\\f683\"; }\n\n.fa-praying-hands:before {\n  content: \"\\f684\"; }\n\n.fa-prescription:before {\n  content: \"\\f5b1\"; }\n\n.fa-prescription-bottle:before {\n  content: \"\\f485\"; }\n\n.fa-prescription-bottle-alt:before {\n  content: \"\\f486\"; }\n\n.fa-print:before {\n  content: \"\\f02f\"; }\n\n.fa-procedures:before {\n  content: \"\\f487\"; }\n\n.fa-product-hunt:before {\n  content: \"\\f288\"; }\n\n.fa-project-diagram:before {\n  content: \"\\f542\"; }\n\n.fa-pushed:before {\n  content: \"\\f3e1\"; }\n\n.fa-puzzle-piece:before {\n  content: \"\\f12e\"; }\n\n.fa-python:before {\n  content: \"\\f3e2\"; }\n\n.fa-qq:before {\n  content: \"\\f1d6\"; }\n\n.fa-qrcode:before {\n  content: \"\\f029\"; }\n\n.fa-question:before {\n  content: \"\\f128\"; }\n\n.fa-question-circle:before {\n  content: \"\\f059\"; }\n\n.fa-quidditch:before {\n  content: \"\\f458\"; }\n\n.fa-quinscape:before {\n  content: \"\\f459\"; }\n\n.fa-quora:before {\n  content: \"\\f2c4\"; }\n\n.fa-quote-left:before {\n  content: \"\\f10d\"; }\n\n.fa-quote-right:before {\n  content: \"\\f10e\"; }\n\n.fa-quran:before {\n  content: \"\\f687\"; }\n\n.fa-r-project:before {\n  content: \"\\f4f7\"; }\n\n.fa-radiation:before {\n  content: \"\\f7b9\"; }\n\n.fa-radiation-alt:before {\n  content: \"\\f7ba\"; }\n\n.fa-rainbow:before {\n  content: \"\\f75b\"; }\n\n.fa-random:before {\n  content: \"\\f074\"; }\n\n.fa-raspberry-pi:before {\n  content: \"\\f7bb\"; }\n\n.fa-ravelry:before {\n  content: \"\\f2d9\"; }\n\n.fa-react:before {\n  content: \"\\f41b\"; }\n\n.fa-reacteurope:before {\n  content: \"\\f75d\"; }\n\n.fa-readme:before {\n  content: \"\\f4d5\"; }\n\n.fa-rebel:before {\n  content: \"\\f1d0\"; }\n\n.fa-receipt:before {\n  content: \"\\f543\"; }\n\n.fa-recycle:before {\n  content: \"\\f1b8\"; }\n\n.fa-red-river:before {\n  content: \"\\f3e3\"; }\n\n.fa-reddit:before {\n  content: \"\\f1a1\"; }\n\n.fa-reddit-alien:before {\n  content: \"\\f281\"; }\n\n.fa-reddit-square:before {\n  content: \"\\f1a2\"; }\n\n.fa-redhat:before {\n  content: \"\\f7bc\"; }\n\n.fa-redo:before {\n  content: \"\\f01e\"; }\n\n.fa-redo-alt:before {\n  content: \"\\f2f9\"; }\n\n.fa-registered:before {\n  content: \"\\f25d\"; }\n\n.fa-remove-format:before {\n  content: \"\\f87d\"; }\n\n.fa-renren:before {\n  content: \"\\f18b\"; }\n\n.fa-reply:before {\n  content: \"\\f3e5\"; }\n\n.fa-reply-all:before {\n  content: \"\\f122\"; }\n\n.fa-replyd:before {\n  content: \"\\f3e6\"; }\n\n.fa-republican:before {\n  content: \"\\f75e\"; }\n\n.fa-researchgate:before {\n  content: \"\\f4f8\"; }\n\n.fa-resolving:before {\n  content: \"\\f3e7\"; }\n\n.fa-restroom:before {\n  content: \"\\f7bd\"; }\n\n.fa-retweet:before {\n  content: \"\\f079\"; }\n\n.fa-rev:before {\n  content: \"\\f5b2\"; }\n\n.fa-ribbon:before {\n  content: \"\\f4d6\"; }\n\n.fa-ring:before {\n  content: \"\\f70b\"; }\n\n.fa-road:before {\n  content: \"\\f018\"; }\n\n.fa-robot:before {\n  content: \"\\f544\"; }\n\n.fa-rocket:before {\n  content: \"\\f135\"; }\n\n.fa-rocketchat:before {\n  content: \"\\f3e8\"; }\n\n.fa-rockrms:before {\n  content: \"\\f3e9\"; }\n\n.fa-route:before {\n  content: \"\\f4d7\"; }\n\n.fa-rss:before {\n  content: \"\\f09e\"; }\n\n.fa-rss-square:before {\n  content: \"\\f143\"; }\n\n.fa-ruble-sign:before {\n  content: \"\\f158\"; }\n\n.fa-ruler:before {\n  content: \"\\f545\"; }\n\n.fa-ruler-combined:before {\n  content: \"\\f546\"; }\n\n.fa-ruler-horizontal:before {\n  content: \"\\f547\"; }\n\n.fa-ruler-vertical:before {\n  content: \"\\f548\"; }\n\n.fa-running:before {\n  content: \"\\f70c\"; }\n\n.fa-rupee-sign:before {\n  content: \"\\f156\"; }\n\n.fa-sad-cry:before {\n  content: \"\\f5b3\"; }\n\n.fa-sad-tear:before {\n  content: \"\\f5b4\"; }\n\n.fa-safari:before {\n  content: \"\\f267\"; }\n\n.fa-salesforce:before {\n  content: \"\\f83b\"; }\n\n.fa-sass:before {\n  content: \"\\f41e\"; }\n\n.fa-satellite:before {\n  content: \"\\f7bf\"; }\n\n.fa-satellite-dish:before {\n  content: \"\\f7c0\"; }\n\n.fa-save:before {\n  content: \"\\f0c7\"; }\n\n.fa-schlix:before {\n  content: \"\\f3ea\"; }\n\n.fa-school:before {\n  content: \"\\f549\"; }\n\n.fa-screwdriver:before {\n  content: \"\\f54a\"; }\n\n.fa-scribd:before {\n  content: \"\\f28a\"; }\n\n.fa-scroll:before {\n  content: \"\\f70e\"; }\n\n.fa-sd-card:before {\n  content: \"\\f7c2\"; }\n\n.fa-search:before {\n  content: \"\\f002\"; }\n\n.fa-search-dollar:before {\n  content: \"\\f688\"; }\n\n.fa-search-location:before {\n  content: \"\\f689\"; }\n\n.fa-search-minus:before {\n  content: \"\\f010\"; }\n\n.fa-search-plus:before {\n  content: \"\\f00e\"; }\n\n.fa-searchengin:before {\n  content: \"\\f3eb\"; }\n\n.fa-seedling:before {\n  content: \"\\f4d8\"; }\n\n.fa-sellcast:before {\n  content: \"\\f2da\"; }\n\n.fa-sellsy:before {\n  content: \"\\f213\"; }\n\n.fa-server:before {\n  content: \"\\f233\"; }\n\n.fa-servicestack:before {\n  content: \"\\f3ec\"; }\n\n.fa-shapes:before {\n  content: \"\\f61f\"; }\n\n.fa-share:before {\n  content: \"\\f064\"; }\n\n.fa-share-alt:before {\n  content: \"\\f1e0\"; }\n\n.fa-share-alt-square:before {\n  content: \"\\f1e1\"; }\n\n.fa-share-square:before {\n  content: \"\\f14d\"; }\n\n.fa-shekel-sign:before {\n  content: \"\\f20b\"; }\n\n.fa-shield-alt:before {\n  content: \"\\f3ed\"; }\n\n.fa-ship:before {\n  content: \"\\f21a\"; }\n\n.fa-shipping-fast:before {\n  content: \"\\f48b\"; }\n\n.fa-shirtsinbulk:before {\n  content: \"\\f214\"; }\n\n.fa-shoe-prints:before {\n  content: \"\\f54b\"; }\n\n.fa-shopping-bag:before {\n  content: \"\\f290\"; }\n\n.fa-shopping-basket:before {\n  content: \"\\f291\"; }\n\n.fa-shopping-cart:before {\n  content: \"\\f07a\"; }\n\n.fa-shopware:before {\n  content: \"\\f5b5\"; }\n\n.fa-shower:before {\n  content: \"\\f2cc\"; }\n\n.fa-shuttle-van:before {\n  content: \"\\f5b6\"; }\n\n.fa-sign:before {\n  content: \"\\f4d9\"; }\n\n.fa-sign-in-alt:before {\n  content: \"\\f2f6\"; }\n\n.fa-sign-language:before {\n  content: \"\\f2a7\"; }\n\n.fa-sign-out-alt:before {\n  content: \"\\f2f5\"; }\n\n.fa-signal:before {\n  content: \"\\f012\"; }\n\n.fa-signature:before {\n  content: \"\\f5b7\"; }\n\n.fa-sim-card:before {\n  content: \"\\f7c4\"; }\n\n.fa-simplybuilt:before {\n  content: \"\\f215\"; }\n\n.fa-sistrix:before {\n  content: \"\\f3ee\"; }\n\n.fa-sitemap:before {\n  content: \"\\f0e8\"; }\n\n.fa-sith:before {\n  content: \"\\f512\"; }\n\n.fa-skating:before {\n  content: \"\\f7c5\"; }\n\n.fa-sketch:before {\n  content: \"\\f7c6\"; }\n\n.fa-skiing:before {\n  content: \"\\f7c9\"; }\n\n.fa-skiing-nordic:before {\n  content: \"\\f7ca\"; }\n\n.fa-skull:before {\n  content: \"\\f54c\"; }\n\n.fa-skull-crossbones:before {\n  content: \"\\f714\"; }\n\n.fa-skyatlas:before {\n  content: \"\\f216\"; }\n\n.fa-skype:before {\n  content: \"\\f17e\"; }\n\n.fa-slack:before {\n  content: \"\\f198\"; }\n\n.fa-slack-hash:before {\n  content: \"\\f3ef\"; }\n\n.fa-slash:before {\n  content: \"\\f715\"; }\n\n.fa-sleigh:before {\n  content: \"\\f7cc\"; }\n\n.fa-sliders-h:before {\n  content: \"\\f1de\"; }\n\n.fa-slideshare:before {\n  content: \"\\f1e7\"; }\n\n.fa-smile:before {\n  content: \"\\f118\"; }\n\n.fa-smile-beam:before {\n  content: \"\\f5b8\"; }\n\n.fa-smile-wink:before {\n  content: \"\\f4da\"; }\n\n.fa-smog:before {\n  content: \"\\f75f\"; }\n\n.fa-smoking:before {\n  content: \"\\f48d\"; }\n\n.fa-smoking-ban:before {\n  content: \"\\f54d\"; }\n\n.fa-sms:before {\n  content: \"\\f7cd\"; }\n\n.fa-snapchat:before {\n  content: \"\\f2ab\"; }\n\n.fa-snapchat-ghost:before {\n  content: \"\\f2ac\"; }\n\n.fa-snapchat-square:before {\n  content: \"\\f2ad\"; }\n\n.fa-snowboarding:before {\n  content: \"\\f7ce\"; }\n\n.fa-snowflake:before {\n  content: \"\\f2dc\"; }\n\n.fa-snowman:before {\n  content: \"\\f7d0\"; }\n\n.fa-snowplow:before {\n  content: \"\\f7d2\"; }\n\n.fa-socks:before {\n  content: \"\\f696\"; }\n\n.fa-solar-panel:before {\n  content: \"\\f5ba\"; }\n\n.fa-sort:before {\n  content: \"\\f0dc\"; }\n\n.fa-sort-alpha-down:before {\n  content: \"\\f15d\"; }\n\n.fa-sort-alpha-down-alt:before {\n  content: \"\\f881\"; }\n\n.fa-sort-alpha-up:before {\n  content: \"\\f15e\"; }\n\n.fa-sort-alpha-up-alt:before {\n  content: \"\\f882\"; }\n\n.fa-sort-amount-down:before {\n  content: \"\\f160\"; }\n\n.fa-sort-amount-down-alt:before {\n  content: \"\\f884\"; }\n\n.fa-sort-amount-up:before {\n  content: \"\\f161\"; }\n\n.fa-sort-amount-up-alt:before {\n  content: \"\\f885\"; }\n\n.fa-sort-down:before {\n  content: \"\\f0dd\"; }\n\n.fa-sort-numeric-down:before {\n  content: \"\\f162\"; }\n\n.fa-sort-numeric-down-alt:before {\n  content: \"\\f886\"; }\n\n.fa-sort-numeric-up:before {\n  content: \"\\f163\"; }\n\n.fa-sort-numeric-up-alt:before {\n  content: \"\\f887\"; }\n\n.fa-sort-up:before {\n  content: \"\\f0de\"; }\n\n.fa-soundcloud:before {\n  content: \"\\f1be\"; }\n\n.fa-sourcetree:before {\n  content: \"\\f7d3\"; }\n\n.fa-spa:before {\n  content: \"\\f5bb\"; }\n\n.fa-space-shuttle:before {\n  content: \"\\f197\"; }\n\n.fa-speakap:before {\n  content: \"\\f3f3\"; }\n\n.fa-speaker-deck:before {\n  content: \"\\f83c\"; }\n\n.fa-spell-check:before {\n  content: \"\\f891\"; }\n\n.fa-spider:before {\n  content: \"\\f717\"; }\n\n.fa-spinner:before {\n  content: \"\\f110\"; }\n\n.fa-splotch:before {\n  content: \"\\f5bc\"; }\n\n.fa-spotify:before {\n  content: \"\\f1bc\"; }\n\n.fa-spray-can:before {\n  content: \"\\f5bd\"; }\n\n.fa-square:before {\n  content: \"\\f0c8\"; }\n\n.fa-square-full:before {\n  content: \"\\f45c\"; }\n\n.fa-square-root-alt:before {\n  content: \"\\f698\"; }\n\n.fa-squarespace:before {\n  content: \"\\f5be\"; }\n\n.fa-stack-exchange:before {\n  content: \"\\f18d\"; }\n\n.fa-stack-overflow:before {\n  content: \"\\f16c\"; }\n\n.fa-stackpath:before {\n  content: \"\\f842\"; }\n\n.fa-stamp:before {\n  content: \"\\f5bf\"; }\n\n.fa-star:before {\n  content: \"\\f005\"; }\n\n.fa-star-and-crescent:before {\n  content: \"\\f699\"; }\n\n.fa-star-half:before {\n  content: \"\\f089\"; }\n\n.fa-star-half-alt:before {\n  content: \"\\f5c0\"; }\n\n.fa-star-of-david:before {\n  content: \"\\f69a\"; }\n\n.fa-star-of-life:before {\n  content: \"\\f621\"; }\n\n.fa-staylinked:before {\n  content: \"\\f3f5\"; }\n\n.fa-steam:before {\n  content: \"\\f1b6\"; }\n\n.fa-steam-square:before {\n  content: \"\\f1b7\"; }\n\n.fa-steam-symbol:before {\n  content: \"\\f3f6\"; }\n\n.fa-step-backward:before {\n  content: \"\\f048\"; }\n\n.fa-step-forward:before {\n  content: \"\\f051\"; }\n\n.fa-stethoscope:before {\n  content: \"\\f0f1\"; }\n\n.fa-sticker-mule:before {\n  content: \"\\f3f7\"; }\n\n.fa-sticky-note:before {\n  content: \"\\f249\"; }\n\n.fa-stop:before {\n  content: \"\\f04d\"; }\n\n.fa-stop-circle:before {\n  content: \"\\f28d\"; }\n\n.fa-stopwatch:before {\n  content: \"\\f2f2\"; }\n\n.fa-store:before {\n  content: \"\\f54e\"; }\n\n.fa-store-alt:before {\n  content: \"\\f54f\"; }\n\n.fa-strava:before {\n  content: \"\\f428\"; }\n\n.fa-stream:before {\n  content: \"\\f550\"; }\n\n.fa-street-view:before {\n  content: \"\\f21d\"; }\n\n.fa-strikethrough:before {\n  content: \"\\f0cc\"; }\n\n.fa-stripe:before {\n  content: \"\\f429\"; }\n\n.fa-stripe-s:before {\n  content: \"\\f42a\"; }\n\n.fa-stroopwafel:before {\n  content: \"\\f551\"; }\n\n.fa-studiovinari:before {\n  content: \"\\f3f8\"; }\n\n.fa-stumbleupon:before {\n  content: \"\\f1a4\"; }\n\n.fa-stumbleupon-circle:before {\n  content: \"\\f1a3\"; }\n\n.fa-subscript:before {\n  content: \"\\f12c\"; }\n\n.fa-subway:before {\n  content: \"\\f239\"; }\n\n.fa-suitcase:before {\n  content: \"\\f0f2\"; }\n\n.fa-suitcase-rolling:before {\n  content: \"\\f5c1\"; }\n\n.fa-sun:before {\n  content: \"\\f185\"; }\n\n.fa-superpowers:before {\n  content: \"\\f2dd\"; }\n\n.fa-superscript:before {\n  content: \"\\f12b\"; }\n\n.fa-supple:before {\n  content: \"\\f3f9\"; }\n\n.fa-surprise:before {\n  content: \"\\f5c2\"; }\n\n.fa-suse:before {\n  content: \"\\f7d6\"; }\n\n.fa-swatchbook:before {\n  content: \"\\f5c3\"; }\n\n.fa-swimmer:before {\n  content: \"\\f5c4\"; }\n\n.fa-swimming-pool:before {\n  content: \"\\f5c5\"; }\n\n.fa-symfony:before {\n  content: \"\\f83d\"; }\n\n.fa-synagogue:before {\n  content: \"\\f69b\"; }\n\n.fa-sync:before {\n  content: \"\\f021\"; }\n\n.fa-sync-alt:before {\n  content: \"\\f2f1\"; }\n\n.fa-syringe:before {\n  content: \"\\f48e\"; }\n\n.fa-table:before {\n  content: \"\\f0ce\"; }\n\n.fa-table-tennis:before {\n  content: \"\\f45d\"; }\n\n.fa-tablet:before {\n  content: \"\\f10a\"; }\n\n.fa-tablet-alt:before {\n  content: \"\\f3fa\"; }\n\n.fa-tablets:before {\n  content: \"\\f490\"; }\n\n.fa-tachometer-alt:before {\n  content: \"\\f3fd\"; }\n\n.fa-tag:before {\n  content: \"\\f02b\"; }\n\n.fa-tags:before {\n  content: \"\\f02c\"; }\n\n.fa-tape:before {\n  content: \"\\f4db\"; }\n\n.fa-tasks:before {\n  content: \"\\f0ae\"; }\n\n.fa-taxi:before {\n  content: \"\\f1ba\"; }\n\n.fa-teamspeak:before {\n  content: \"\\f4f9\"; }\n\n.fa-teeth:before {\n  content: \"\\f62e\"; }\n\n.fa-teeth-open:before {\n  content: \"\\f62f\"; }\n\n.fa-telegram:before {\n  content: \"\\f2c6\"; }\n\n.fa-telegram-plane:before {\n  content: \"\\f3fe\"; }\n\n.fa-temperature-high:before {\n  content: \"\\f769\"; }\n\n.fa-temperature-low:before {\n  content: \"\\f76b\"; }\n\n.fa-tencent-weibo:before {\n  content: \"\\f1d5\"; }\n\n.fa-tenge:before {\n  content: \"\\f7d7\"; }\n\n.fa-terminal:before {\n  content: \"\\f120\"; }\n\n.fa-text-height:before {\n  content: \"\\f034\"; }\n\n.fa-text-width:before {\n  content: \"\\f035\"; }\n\n.fa-th:before {\n  content: \"\\f00a\"; }\n\n.fa-th-large:before {\n  content: \"\\f009\"; }\n\n.fa-th-list:before {\n  content: \"\\f00b\"; }\n\n.fa-the-red-yeti:before {\n  content: \"\\f69d\"; }\n\n.fa-theater-masks:before {\n  content: \"\\f630\"; }\n\n.fa-themeco:before {\n  content: \"\\f5c6\"; }\n\n.fa-themeisle:before {\n  content: \"\\f2b2\"; }\n\n.fa-thermometer:before {\n  content: \"\\f491\"; }\n\n.fa-thermometer-empty:before {\n  content: \"\\f2cb\"; }\n\n.fa-thermometer-full:before {\n  content: \"\\f2c7\"; }\n\n.fa-thermometer-half:before {\n  content: \"\\f2c9\"; }\n\n.fa-thermometer-quarter:before {\n  content: \"\\f2ca\"; }\n\n.fa-thermometer-three-quarters:before {\n  content: \"\\f2c8\"; }\n\n.fa-think-peaks:before {\n  content: \"\\f731\"; }\n\n.fa-thumbs-down:before {\n  content: \"\\f165\"; }\n\n.fa-thumbs-up:before {\n  content: \"\\f164\"; }\n\n.fa-thumbtack:before {\n  content: \"\\f08d\"; }\n\n.fa-ticket-alt:before {\n  content: \"\\f3ff\"; }\n\n.fa-times:before {\n  content: \"\\f00d\"; }\n\n.fa-times-circle:before {\n  content: \"\\f057\"; }\n\n.fa-tint:before {\n  content: \"\\f043\"; }\n\n.fa-tint-slash:before {\n  content: \"\\f5c7\"; }\n\n.fa-tired:before {\n  content: \"\\f5c8\"; }\n\n.fa-toggle-off:before {\n  content: \"\\f204\"; }\n\n.fa-toggle-on:before {\n  content: \"\\f205\"; }\n\n.fa-toilet:before {\n  content: \"\\f7d8\"; }\n\n.fa-toilet-paper:before {\n  content: \"\\f71e\"; }\n\n.fa-toolbox:before {\n  content: \"\\f552\"; }\n\n.fa-tools:before {\n  content: \"\\f7d9\"; }\n\n.fa-tooth:before {\n  content: \"\\f5c9\"; }\n\n.fa-torah:before {\n  content: \"\\f6a0\"; }\n\n.fa-torii-gate:before {\n  content: \"\\f6a1\"; }\n\n.fa-tractor:before {\n  content: \"\\f722\"; }\n\n.fa-trade-federation:before {\n  content: \"\\f513\"; }\n\n.fa-trademark:before {\n  content: \"\\f25c\"; }\n\n.fa-traffic-light:before {\n  content: \"\\f637\"; }\n\n.fa-train:before {\n  content: \"\\f238\"; }\n\n.fa-tram:before {\n  content: \"\\f7da\"; }\n\n.fa-transgender:before {\n  content: \"\\f224\"; }\n\n.fa-transgender-alt:before {\n  content: \"\\f225\"; }\n\n.fa-trash:before {\n  content: \"\\f1f8\"; }\n\n.fa-trash-alt:before {\n  content: \"\\f2ed\"; }\n\n.fa-trash-restore:before {\n  content: \"\\f829\"; }\n\n.fa-trash-restore-alt:before {\n  content: \"\\f82a\"; }\n\n.fa-tree:before {\n  content: \"\\f1bb\"; }\n\n.fa-trello:before {\n  content: \"\\f181\"; }\n\n.fa-tripadvisor:before {\n  content: \"\\f262\"; }\n\n.fa-trophy:before {\n  content: \"\\f091\"; }\n\n.fa-truck:before {\n  content: \"\\f0d1\"; }\n\n.fa-truck-loading:before {\n  content: \"\\f4de\"; }\n\n.fa-truck-monster:before {\n  content: \"\\f63b\"; }\n\n.fa-truck-moving:before {\n  content: \"\\f4df\"; }\n\n.fa-truck-pickup:before {\n  content: \"\\f63c\"; }\n\n.fa-tshirt:before {\n  content: \"\\f553\"; }\n\n.fa-tty:before {\n  content: \"\\f1e4\"; }\n\n.fa-tumblr:before {\n  content: \"\\f173\"; }\n\n.fa-tumblr-square:before {\n  content: \"\\f174\"; }\n\n.fa-tv:before {\n  content: \"\\f26c\"; }\n\n.fa-twitch:before {\n  content: \"\\f1e8\"; }\n\n.fa-twitter:before {\n  content: \"\\f099\"; }\n\n.fa-twitter-square:before {\n  content: \"\\f081\"; }\n\n.fa-typo3:before {\n  content: \"\\f42b\"; }\n\n.fa-uber:before {\n  content: \"\\f402\"; }\n\n.fa-ubuntu:before {\n  content: \"\\f7df\"; }\n\n.fa-uikit:before {\n  content: \"\\f403\"; }\n\n.fa-umbrella:before {\n  content: \"\\f0e9\"; }\n\n.fa-umbrella-beach:before {\n  content: \"\\f5ca\"; }\n\n.fa-underline:before {\n  content: \"\\f0cd\"; }\n\n.fa-undo:before {\n  content: \"\\f0e2\"; }\n\n.fa-undo-alt:before {\n  content: \"\\f2ea\"; }\n\n.fa-uniregistry:before {\n  content: \"\\f404\"; }\n\n.fa-universal-access:before {\n  content: \"\\f29a\"; }\n\n.fa-university:before {\n  content: \"\\f19c\"; }\n\n.fa-unlink:before {\n  content: \"\\f127\"; }\n\n.fa-unlock:before {\n  content: \"\\f09c\"; }\n\n.fa-unlock-alt:before {\n  content: \"\\f13e\"; }\n\n.fa-untappd:before {\n  content: \"\\f405\"; }\n\n.fa-upload:before {\n  content: \"\\f093\"; }\n\n.fa-ups:before {\n  content: \"\\f7e0\"; }\n\n.fa-usb:before {\n  content: \"\\f287\"; }\n\n.fa-user:before {\n  content: \"\\f007\"; }\n\n.fa-user-alt:before {\n  content: \"\\f406\"; }\n\n.fa-user-alt-slash:before {\n  content: \"\\f4fa\"; }\n\n.fa-user-astronaut:before {\n  content: \"\\f4fb\"; }\n\n.fa-user-check:before {\n  content: \"\\f4fc\"; }\n\n.fa-user-circle:before {\n  content: \"\\f2bd\"; }\n\n.fa-user-clock:before {\n  content: \"\\f4fd\"; }\n\n.fa-user-cog:before {\n  content: \"\\f4fe\"; }\n\n.fa-user-edit:before {\n  content: \"\\f4ff\"; }\n\n.fa-user-friends:before {\n  content: \"\\f500\"; }\n\n.fa-user-graduate:before {\n  content: \"\\f501\"; }\n\n.fa-user-injured:before {\n  content: \"\\f728\"; }\n\n.fa-user-lock:before {\n  content: \"\\f502\"; }\n\n.fa-user-md:before {\n  content: \"\\f0f0\"; }\n\n.fa-user-minus:before {\n  content: \"\\f503\"; }\n\n.fa-user-ninja:before {\n  content: \"\\f504\"; }\n\n.fa-user-nurse:before {\n  content: \"\\f82f\"; }\n\n.fa-user-plus:before {\n  content: \"\\f234\"; }\n\n.fa-user-secret:before {\n  content: \"\\f21b\"; }\n\n.fa-user-shield:before {\n  content: \"\\f505\"; }\n\n.fa-user-slash:before {\n  content: \"\\f506\"; }\n\n.fa-user-tag:before {\n  content: \"\\f507\"; }\n\n.fa-user-tie:before {\n  content: \"\\f508\"; }\n\n.fa-user-times:before {\n  content: \"\\f235\"; }\n\n.fa-users:before {\n  content: \"\\f0c0\"; }\n\n.fa-users-cog:before {\n  content: \"\\f509\"; }\n\n.fa-usps:before {\n  content: \"\\f7e1\"; }\n\n.fa-ussunnah:before {\n  content: \"\\f407\"; }\n\n.fa-utensil-spoon:before {\n  content: \"\\f2e5\"; }\n\n.fa-utensils:before {\n  content: \"\\f2e7\"; }\n\n.fa-vaadin:before {\n  content: \"\\f408\"; }\n\n.fa-vector-square:before {\n  content: \"\\f5cb\"; }\n\n.fa-venus:before {\n  content: \"\\f221\"; }\n\n.fa-venus-double:before {\n  content: \"\\f226\"; }\n\n.fa-venus-mars:before {\n  content: \"\\f228\"; }\n\n.fa-viacoin:before {\n  content: \"\\f237\"; }\n\n.fa-viadeo:before {\n  content: \"\\f2a9\"; }\n\n.fa-viadeo-square:before {\n  content: \"\\f2aa\"; }\n\n.fa-vial:before {\n  content: \"\\f492\"; }\n\n.fa-vials:before {\n  content: \"\\f493\"; }\n\n.fa-viber:before {\n  content: \"\\f409\"; }\n\n.fa-video:before {\n  content: \"\\f03d\"; }\n\n.fa-video-slash:before {\n  content: \"\\f4e2\"; }\n\n.fa-vihara:before {\n  content: \"\\f6a7\"; }\n\n.fa-vimeo:before {\n  content: \"\\f40a\"; }\n\n.fa-vimeo-square:before {\n  content: \"\\f194\"; }\n\n.fa-vimeo-v:before {\n  content: \"\\f27d\"; }\n\n.fa-vine:before {\n  content: \"\\f1ca\"; }\n\n.fa-vk:before {\n  content: \"\\f189\"; }\n\n.fa-vnv:before {\n  content: \"\\f40b\"; }\n\n.fa-voicemail:before {\n  content: \"\\f897\"; }\n\n.fa-volleyball-ball:before {\n  content: \"\\f45f\"; }\n\n.fa-volume-down:before {\n  content: \"\\f027\"; }\n\n.fa-volume-mute:before {\n  content: \"\\f6a9\"; }\n\n.fa-volume-off:before {\n  content: \"\\f026\"; }\n\n.fa-volume-up:before {\n  content: \"\\f028\"; }\n\n.fa-vote-yea:before {\n  content: \"\\f772\"; }\n\n.fa-vr-cardboard:before {\n  content: \"\\f729\"; }\n\n.fa-vuejs:before {\n  content: \"\\f41f\"; }\n\n.fa-walking:before {\n  content: \"\\f554\"; }\n\n.fa-wallet:before {\n  content: \"\\f555\"; }\n\n.fa-warehouse:before {\n  content: \"\\f494\"; }\n\n.fa-water:before {\n  content: \"\\f773\"; }\n\n.fa-wave-square:before {\n  content: \"\\f83e\"; }\n\n.fa-waze:before {\n  content: \"\\f83f\"; }\n\n.fa-weebly:before {\n  content: \"\\f5cc\"; }\n\n.fa-weibo:before {\n  content: \"\\f18a\"; }\n\n.fa-weight:before {\n  content: \"\\f496\"; }\n\n.fa-weight-hanging:before {\n  content: \"\\f5cd\"; }\n\n.fa-weixin:before {\n  content: \"\\f1d7\"; }\n\n.fa-whatsapp:before {\n  content: \"\\f232\"; }\n\n.fa-whatsapp-square:before {\n  content: \"\\f40c\"; }\n\n.fa-wheelchair:before {\n  content: \"\\f193\"; }\n\n.fa-whmcs:before {\n  content: \"\\f40d\"; }\n\n.fa-wifi:before {\n  content: \"\\f1eb\"; }\n\n.fa-wikipedia-w:before {\n  content: \"\\f266\"; }\n\n.fa-wind:before {\n  content: \"\\f72e\"; }\n\n.fa-window-close:before {\n  content: \"\\f410\"; }\n\n.fa-window-maximize:before {\n  content: \"\\f2d0\"; }\n\n.fa-window-minimize:before {\n  content: \"\\f2d1\"; }\n\n.fa-window-restore:before {\n  content: \"\\f2d2\"; }\n\n.fa-windows:before {\n  content: \"\\f17a\"; }\n\n.fa-wine-bottle:before {\n  content: \"\\f72f\"; }\n\n.fa-wine-glass:before {\n  content: \"\\f4e3\"; }\n\n.fa-wine-glass-alt:before {\n  content: \"\\f5ce\"; }\n\n.fa-wix:before {\n  content: \"\\f5cf\"; }\n\n.fa-wizards-of-the-coast:before {\n  content: \"\\f730\"; }\n\n.fa-wolf-pack-battalion:before {\n  content: \"\\f514\"; }\n\n.fa-won-sign:before {\n  content: \"\\f159\"; }\n\n.fa-wordpress:before {\n  content: \"\\f19a\"; }\n\n.fa-wordpress-simple:before {\n  content: \"\\f411\"; }\n\n.fa-wpbeginner:before {\n  content: \"\\f297\"; }\n\n.fa-wpexplorer:before {\n  content: \"\\f2de\"; }\n\n.fa-wpforms:before {\n  content: \"\\f298\"; }\n\n.fa-wpressr:before {\n  content: \"\\f3e4\"; }\n\n.fa-wrench:before {\n  content: \"\\f0ad\"; }\n\n.fa-x-ray:before {\n  content: \"\\f497\"; }\n\n.fa-xbox:before {\n  content: \"\\f412\"; }\n\n.fa-xing:before {\n  content: \"\\f168\"; }\n\n.fa-xing-square:before {\n  content: \"\\f169\"; }\n\n.fa-y-combinator:before {\n  content: \"\\f23b\"; }\n\n.fa-yahoo:before {\n  content: \"\\f19e\"; }\n\n.fa-yammer:before {\n  content: \"\\f840\"; }\n\n.fa-yandex:before {\n  content: \"\\f413\"; }\n\n.fa-yandex-international:before {\n  content: \"\\f414\"; }\n\n.fa-yarn:before {\n  content: \"\\f7e3\"; }\n\n.fa-yelp:before {\n  content: \"\\f1e9\"; }\n\n.fa-yen-sign:before {\n  content: \"\\f157\"; }\n\n.fa-yin-yang:before {\n  content: \"\\f6ad\"; }\n\n.fa-yoast:before {\n  content: \"\\f2b1\"; }\n\n.fa-youtube:before {\n  content: \"\\f167\"; }\n\n.fa-youtube-square:before {\n  content: \"\\f431\"; }\n\n.fa-zhihu:before {\n  content: \"\\f63f\"; }\n\n.sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px; }\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  clip: auto;\n  height: auto;\n  margin: 0;\n  overflow: visible;\n  position: static;\n  width: auto; }\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: auto;\n  src: url(\"../webfonts/fa-brands-400.eot\");\n  src: url(\"../webfonts/fa-brands-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-brands-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-brands-400.woff\") format(\"woff\"), url(\"../webfonts/fa-brands-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-brands-400.svg#fontawesome\") format(\"svg\"); }\n\n.fab {\n  font-family: 'Font Awesome 5 Brands'; }\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: auto;\n  src: url(\"../webfonts/fa-regular-400.eot\");\n  src: url(\"../webfonts/fa-regular-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-regular-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-regular-400.woff\") format(\"woff\"), url(\"../webfonts/fa-regular-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-regular-400.svg#fontawesome\") format(\"svg\"); }\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: auto;\n  src: url(\"../webfonts/fa-solid-900.eot\");\n  src: url(\"../webfonts/fa-solid-900.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-solid-900.woff2\") format(\"woff2\"), url(\"../webfonts/fa-solid-900.woff\") format(\"woff\"), url(\"../webfonts/fa-solid-900.ttf\") format(\"truetype\"), url(\"../webfonts/fa-solid-900.svg#fontawesome\") format(\"svg\"); }\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/brands.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: auto;\n  src: url(\"../webfonts/fa-brands-400.eot\");\n  src: url(\"../webfonts/fa-brands-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-brands-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-brands-400.woff\") format(\"woff\"), url(\"../webfonts/fa-brands-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-brands-400.svg#fontawesome\") format(\"svg\"); }\n\n.fab {\n  font-family: 'Font Awesome 5 Brands'; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/fontawesome.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n.fa,\n.fas,\n.far,\n.fal,\n.fad,\n.fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1; }\n\n.fa-lg {\n  font-size: 1.33333em;\n  line-height: 0.75em;\n  vertical-align: -.0667em; }\n\n.fa-xs {\n  font-size: .75em; }\n\n.fa-sm {\n  font-size: .875em; }\n\n.fa-1x {\n  font-size: 1em; }\n\n.fa-2x {\n  font-size: 2em; }\n\n.fa-3x {\n  font-size: 3em; }\n\n.fa-4x {\n  font-size: 4em; }\n\n.fa-5x {\n  font-size: 5em; }\n\n.fa-6x {\n  font-size: 6em; }\n\n.fa-7x {\n  font-size: 7em; }\n\n.fa-8x {\n  font-size: 8em; }\n\n.fa-9x {\n  font-size: 9em; }\n\n.fa-10x {\n  font-size: 10em; }\n\n.fa-fw {\n  text-align: center;\n  width: 1.25em; }\n\n.fa-ul {\n  list-style-type: none;\n  margin-left: 2.5em;\n  padding-left: 0; }\n  .fa-ul > li {\n    position: relative; }\n\n.fa-li {\n  left: -2em;\n  position: absolute;\n  text-align: center;\n  width: 2em;\n  line-height: inherit; }\n\n.fa-border {\n  border: solid 0.08em #eee;\n  border-radius: .1em;\n  padding: .2em .25em .15em; }\n\n.fa-pull-left {\n  float: left; }\n\n.fa-pull-right {\n  float: right; }\n\n.fa.fa-pull-left,\n.fas.fa-pull-left,\n.far.fa-pull-left,\n.fal.fa-pull-left,\n.fab.fa-pull-left {\n  margin-right: .3em; }\n\n.fa.fa-pull-right,\n.fas.fa-pull-right,\n.far.fa-pull-right,\n.fal.fa-pull-right,\n.fab.fa-pull-right {\n  margin-left: .3em; }\n\n.fa-spin {\n  -webkit-animation: fa-spin 2s infinite linear;\n          animation: fa-spin 2s infinite linear; }\n\n.fa-pulse {\n  -webkit-animation: fa-spin 1s infinite steps(8);\n          animation: fa-spin 1s infinite steps(8); }\n\n@-webkit-keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n@keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n.fa-rotate-90 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)\";\n  -webkit-transform: rotate(90deg);\n          transform: rotate(90deg); }\n\n.fa-rotate-180 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)\";\n  -webkit-transform: rotate(180deg);\n          transform: rotate(180deg); }\n\n.fa-rotate-270 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)\";\n  -webkit-transform: rotate(270deg);\n          transform: rotate(270deg); }\n\n.fa-flip-horizontal {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)\";\n  -webkit-transform: scale(-1, 1);\n          transform: scale(-1, 1); }\n\n.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(1, -1);\n          transform: scale(1, -1); }\n\n.fa-flip-both, .fa-flip-horizontal.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(-1, -1);\n          transform: scale(-1, -1); }\n\n:root .fa-rotate-90,\n:root .fa-rotate-180,\n:root .fa-rotate-270,\n:root .fa-flip-horizontal,\n:root .fa-flip-vertical,\n:root .fa-flip-both {\n  -webkit-filter: none;\n          filter: none; }\n\n.fa-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: 2.5em; }\n\n.fa-stack-1x,\n.fa-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%; }\n\n.fa-stack-1x {\n  line-height: inherit; }\n\n.fa-stack-2x {\n  font-size: 2em; }\n\n.fa-inverse {\n  color: #fff; }\n\n/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\nreaders do not read off random characters that represent icons */\n.fa-500px:before {\n  content: \"\\f26e\"; }\n\n.fa-accessible-icon:before {\n  content: \"\\f368\"; }\n\n.fa-accusoft:before {\n  content: \"\\f369\"; }\n\n.fa-acquisitions-incorporated:before {\n  content: \"\\f6af\"; }\n\n.fa-ad:before {\n  content: \"\\f641\"; }\n\n.fa-address-book:before {\n  content: \"\\f2b9\"; }\n\n.fa-address-card:before {\n  content: \"\\f2bb\"; }\n\n.fa-adjust:before {\n  content: \"\\f042\"; }\n\n.fa-adn:before {\n  content: \"\\f170\"; }\n\n.fa-adobe:before {\n  content: \"\\f778\"; }\n\n.fa-adversal:before {\n  content: \"\\f36a\"; }\n\n.fa-affiliatetheme:before {\n  content: \"\\f36b\"; }\n\n.fa-air-freshener:before {\n  content: \"\\f5d0\"; }\n\n.fa-airbnb:before {\n  content: \"\\f834\"; }\n\n.fa-algolia:before {\n  content: \"\\f36c\"; }\n\n.fa-align-center:before {\n  content: \"\\f037\"; }\n\n.fa-align-justify:before {\n  content: \"\\f039\"; }\n\n.fa-align-left:before {\n  content: \"\\f036\"; }\n\n.fa-align-right:before {\n  content: \"\\f038\"; }\n\n.fa-alipay:before {\n  content: \"\\f642\"; }\n\n.fa-allergies:before {\n  content: \"\\f461\"; }\n\n.fa-amazon:before {\n  content: \"\\f270\"; }\n\n.fa-amazon-pay:before {\n  content: \"\\f42c\"; }\n\n.fa-ambulance:before {\n  content: \"\\f0f9\"; }\n\n.fa-american-sign-language-interpreting:before {\n  content: \"\\f2a3\"; }\n\n.fa-amilia:before {\n  content: \"\\f36d\"; }\n\n.fa-anchor:before {\n  content: \"\\f13d\"; }\n\n.fa-android:before {\n  content: \"\\f17b\"; }\n\n.fa-angellist:before {\n  content: \"\\f209\"; }\n\n.fa-angle-double-down:before {\n  content: \"\\f103\"; }\n\n.fa-angle-double-left:before {\n  content: \"\\f100\"; }\n\n.fa-angle-double-right:before {\n  content: \"\\f101\"; }\n\n.fa-angle-double-up:before {\n  content: \"\\f102\"; }\n\n.fa-angle-down:before {\n  content: \"\\f107\"; }\n\n.fa-angle-left:before {\n  content: \"\\f104\"; }\n\n.fa-angle-right:before {\n  content: \"\\f105\"; }\n\n.fa-angle-up:before {\n  content: \"\\f106\"; }\n\n.fa-angry:before {\n  content: \"\\f556\"; }\n\n.fa-angrycreative:before {\n  content: \"\\f36e\"; }\n\n.fa-angular:before {\n  content: \"\\f420\"; }\n\n.fa-ankh:before {\n  content: \"\\f644\"; }\n\n.fa-app-store:before {\n  content: \"\\f36f\"; }\n\n.fa-app-store-ios:before {\n  content: \"\\f370\"; }\n\n.fa-apper:before {\n  content: \"\\f371\"; }\n\n.fa-apple:before {\n  content: \"\\f179\"; }\n\n.fa-apple-alt:before {\n  content: \"\\f5d1\"; }\n\n.fa-apple-pay:before {\n  content: \"\\f415\"; }\n\n.fa-archive:before {\n  content: \"\\f187\"; }\n\n.fa-archway:before {\n  content: \"\\f557\"; }\n\n.fa-arrow-alt-circle-down:before {\n  content: \"\\f358\"; }\n\n.fa-arrow-alt-circle-left:before {\n  content: \"\\f359\"; }\n\n.fa-arrow-alt-circle-right:before {\n  content: \"\\f35a\"; }\n\n.fa-arrow-alt-circle-up:before {\n  content: \"\\f35b\"; }\n\n.fa-arrow-circle-down:before {\n  content: \"\\f0ab\"; }\n\n.fa-arrow-circle-left:before {\n  content: \"\\f0a8\"; }\n\n.fa-arrow-circle-right:before {\n  content: \"\\f0a9\"; }\n\n.fa-arrow-circle-up:before {\n  content: \"\\f0aa\"; }\n\n.fa-arrow-down:before {\n  content: \"\\f063\"; }\n\n.fa-arrow-left:before {\n  content: \"\\f060\"; }\n\n.fa-arrow-right:before {\n  content: \"\\f061\"; }\n\n.fa-arrow-up:before {\n  content: \"\\f062\"; }\n\n.fa-arrows-alt:before {\n  content: \"\\f0b2\"; }\n\n.fa-arrows-alt-h:before {\n  content: \"\\f337\"; }\n\n.fa-arrows-alt-v:before {\n  content: \"\\f338\"; }\n\n.fa-artstation:before {\n  content: \"\\f77a\"; }\n\n.fa-assistive-listening-systems:before {\n  content: \"\\f2a2\"; }\n\n.fa-asterisk:before {\n  content: \"\\f069\"; }\n\n.fa-asymmetrik:before {\n  content: \"\\f372\"; }\n\n.fa-at:before {\n  content: \"\\f1fa\"; }\n\n.fa-atlas:before {\n  content: \"\\f558\"; }\n\n.fa-atlassian:before {\n  content: \"\\f77b\"; }\n\n.fa-atom:before {\n  content: \"\\f5d2\"; }\n\n.fa-audible:before {\n  content: \"\\f373\"; }\n\n.fa-audio-description:before {\n  content: \"\\f29e\"; }\n\n.fa-autoprefixer:before {\n  content: \"\\f41c\"; }\n\n.fa-avianex:before {\n  content: \"\\f374\"; }\n\n.fa-aviato:before {\n  content: \"\\f421\"; }\n\n.fa-award:before {\n  content: \"\\f559\"; }\n\n.fa-aws:before {\n  content: \"\\f375\"; }\n\n.fa-baby:before {\n  content: \"\\f77c\"; }\n\n.fa-baby-carriage:before {\n  content: \"\\f77d\"; }\n\n.fa-backspace:before {\n  content: \"\\f55a\"; }\n\n.fa-backward:before {\n  content: \"\\f04a\"; }\n\n.fa-bacon:before {\n  content: \"\\f7e5\"; }\n\n.fa-balance-scale:before {\n  content: \"\\f24e\"; }\n\n.fa-balance-scale-left:before {\n  content: \"\\f515\"; }\n\n.fa-balance-scale-right:before {\n  content: \"\\f516\"; }\n\n.fa-ban:before {\n  content: \"\\f05e\"; }\n\n.fa-band-aid:before {\n  content: \"\\f462\"; }\n\n.fa-bandcamp:before {\n  content: \"\\f2d5\"; }\n\n.fa-barcode:before {\n  content: \"\\f02a\"; }\n\n.fa-bars:before {\n  content: \"\\f0c9\"; }\n\n.fa-baseball-ball:before {\n  content: \"\\f433\"; }\n\n.fa-basketball-ball:before {\n  content: \"\\f434\"; }\n\n.fa-bath:before {\n  content: \"\\f2cd\"; }\n\n.fa-battery-empty:before {\n  content: \"\\f244\"; }\n\n.fa-battery-full:before {\n  content: \"\\f240\"; }\n\n.fa-battery-half:before {\n  content: \"\\f242\"; }\n\n.fa-battery-quarter:before {\n  content: \"\\f243\"; }\n\n.fa-battery-three-quarters:before {\n  content: \"\\f241\"; }\n\n.fa-battle-net:before {\n  content: \"\\f835\"; }\n\n.fa-bed:before {\n  content: \"\\f236\"; }\n\n.fa-beer:before {\n  content: \"\\f0fc\"; }\n\n.fa-behance:before {\n  content: \"\\f1b4\"; }\n\n.fa-behance-square:before {\n  content: \"\\f1b5\"; }\n\n.fa-bell:before {\n  content: \"\\f0f3\"; }\n\n.fa-bell-slash:before {\n  content: \"\\f1f6\"; }\n\n.fa-bezier-curve:before {\n  content: \"\\f55b\"; }\n\n.fa-bible:before {\n  content: \"\\f647\"; }\n\n.fa-bicycle:before {\n  content: \"\\f206\"; }\n\n.fa-biking:before {\n  content: \"\\f84a\"; }\n\n.fa-bimobject:before {\n  content: \"\\f378\"; }\n\n.fa-binoculars:before {\n  content: \"\\f1e5\"; }\n\n.fa-biohazard:before {\n  content: \"\\f780\"; }\n\n.fa-birthday-cake:before {\n  content: \"\\f1fd\"; }\n\n.fa-bitbucket:before {\n  content: \"\\f171\"; }\n\n.fa-bitcoin:before {\n  content: \"\\f379\"; }\n\n.fa-bity:before {\n  content: \"\\f37a\"; }\n\n.fa-black-tie:before {\n  content: \"\\f27e\"; }\n\n.fa-blackberry:before {\n  content: \"\\f37b\"; }\n\n.fa-blender:before {\n  content: \"\\f517\"; }\n\n.fa-blender-phone:before {\n  content: \"\\f6b6\"; }\n\n.fa-blind:before {\n  content: \"\\f29d\"; }\n\n.fa-blog:before {\n  content: \"\\f781\"; }\n\n.fa-blogger:before {\n  content: \"\\f37c\"; }\n\n.fa-blogger-b:before {\n  content: \"\\f37d\"; }\n\n.fa-bluetooth:before {\n  content: \"\\f293\"; }\n\n.fa-bluetooth-b:before {\n  content: \"\\f294\"; }\n\n.fa-bold:before {\n  content: \"\\f032\"; }\n\n.fa-bolt:before {\n  content: \"\\f0e7\"; }\n\n.fa-bomb:before {\n  content: \"\\f1e2\"; }\n\n.fa-bone:before {\n  content: \"\\f5d7\"; }\n\n.fa-bong:before {\n  content: \"\\f55c\"; }\n\n.fa-book:before {\n  content: \"\\f02d\"; }\n\n.fa-book-dead:before {\n  content: \"\\f6b7\"; }\n\n.fa-book-medical:before {\n  content: \"\\f7e6\"; }\n\n.fa-book-open:before {\n  content: \"\\f518\"; }\n\n.fa-book-reader:before {\n  content: \"\\f5da\"; }\n\n.fa-bookmark:before {\n  content: \"\\f02e\"; }\n\n.fa-bootstrap:before {\n  content: \"\\f836\"; }\n\n.fa-border-all:before {\n  content: \"\\f84c\"; }\n\n.fa-border-none:before {\n  content: \"\\f850\"; }\n\n.fa-border-style:before {\n  content: \"\\f853\"; }\n\n.fa-bowling-ball:before {\n  content: \"\\f436\"; }\n\n.fa-box:before {\n  content: \"\\f466\"; }\n\n.fa-box-open:before {\n  content: \"\\f49e\"; }\n\n.fa-boxes:before {\n  content: \"\\f468\"; }\n\n.fa-braille:before {\n  content: \"\\f2a1\"; }\n\n.fa-brain:before {\n  content: \"\\f5dc\"; }\n\n.fa-bread-slice:before {\n  content: \"\\f7ec\"; }\n\n.fa-briefcase:before {\n  content: \"\\f0b1\"; }\n\n.fa-briefcase-medical:before {\n  content: \"\\f469\"; }\n\n.fa-broadcast-tower:before {\n  content: \"\\f519\"; }\n\n.fa-broom:before {\n  content: \"\\f51a\"; }\n\n.fa-brush:before {\n  content: \"\\f55d\"; }\n\n.fa-btc:before {\n  content: \"\\f15a\"; }\n\n.fa-buffer:before {\n  content: \"\\f837\"; }\n\n.fa-bug:before {\n  content: \"\\f188\"; }\n\n.fa-building:before {\n  content: \"\\f1ad\"; }\n\n.fa-bullhorn:before {\n  content: \"\\f0a1\"; }\n\n.fa-bullseye:before {\n  content: \"\\f140\"; }\n\n.fa-burn:before {\n  content: \"\\f46a\"; }\n\n.fa-buromobelexperte:before {\n  content: \"\\f37f\"; }\n\n.fa-bus:before {\n  content: \"\\f207\"; }\n\n.fa-bus-alt:before {\n  content: \"\\f55e\"; }\n\n.fa-business-time:before {\n  content: \"\\f64a\"; }\n\n.fa-buysellads:before {\n  content: \"\\f20d\"; }\n\n.fa-calculator:before {\n  content: \"\\f1ec\"; }\n\n.fa-calendar:before {\n  content: \"\\f133\"; }\n\n.fa-calendar-alt:before {\n  content: \"\\f073\"; }\n\n.fa-calendar-check:before {\n  content: \"\\f274\"; }\n\n.fa-calendar-day:before {\n  content: \"\\f783\"; }\n\n.fa-calendar-minus:before {\n  content: \"\\f272\"; }\n\n.fa-calendar-plus:before {\n  content: \"\\f271\"; }\n\n.fa-calendar-times:before {\n  content: \"\\f273\"; }\n\n.fa-calendar-week:before {\n  content: \"\\f784\"; }\n\n.fa-camera:before {\n  content: \"\\f030\"; }\n\n.fa-camera-retro:before {\n  content: \"\\f083\"; }\n\n.fa-campground:before {\n  content: \"\\f6bb\"; }\n\n.fa-canadian-maple-leaf:before {\n  content: \"\\f785\"; }\n\n.fa-candy-cane:before {\n  content: \"\\f786\"; }\n\n.fa-cannabis:before {\n  content: \"\\f55f\"; }\n\n.fa-capsules:before {\n  content: \"\\f46b\"; }\n\n.fa-car:before {\n  content: \"\\f1b9\"; }\n\n.fa-car-alt:before {\n  content: \"\\f5de\"; }\n\n.fa-car-battery:before {\n  content: \"\\f5df\"; }\n\n.fa-car-crash:before {\n  content: \"\\f5e1\"; }\n\n.fa-car-side:before {\n  content: \"\\f5e4\"; }\n\n.fa-caret-down:before {\n  content: \"\\f0d7\"; }\n\n.fa-caret-left:before {\n  content: \"\\f0d9\"; }\n\n.fa-caret-right:before {\n  content: \"\\f0da\"; }\n\n.fa-caret-square-down:before {\n  content: \"\\f150\"; }\n\n.fa-caret-square-left:before {\n  content: \"\\f191\"; }\n\n.fa-caret-square-right:before {\n  content: \"\\f152\"; }\n\n.fa-caret-square-up:before {\n  content: \"\\f151\"; }\n\n.fa-caret-up:before {\n  content: \"\\f0d8\"; }\n\n.fa-carrot:before {\n  content: \"\\f787\"; }\n\n.fa-cart-arrow-down:before {\n  content: \"\\f218\"; }\n\n.fa-cart-plus:before {\n  content: \"\\f217\"; }\n\n.fa-cash-register:before {\n  content: \"\\f788\"; }\n\n.fa-cat:before {\n  content: \"\\f6be\"; }\n\n.fa-cc-amazon-pay:before {\n  content: \"\\f42d\"; }\n\n.fa-cc-amex:before {\n  content: \"\\f1f3\"; }\n\n.fa-cc-apple-pay:before {\n  content: \"\\f416\"; }\n\n.fa-cc-diners-club:before {\n  content: \"\\f24c\"; }\n\n.fa-cc-discover:before {\n  content: \"\\f1f2\"; }\n\n.fa-cc-jcb:before {\n  content: \"\\f24b\"; }\n\n.fa-cc-mastercard:before {\n  content: \"\\f1f1\"; }\n\n.fa-cc-paypal:before {\n  content: \"\\f1f4\"; }\n\n.fa-cc-stripe:before {\n  content: \"\\f1f5\"; }\n\n.fa-cc-visa:before {\n  content: \"\\f1f0\"; }\n\n.fa-centercode:before {\n  content: \"\\f380\"; }\n\n.fa-centos:before {\n  content: \"\\f789\"; }\n\n.fa-certificate:before {\n  content: \"\\f0a3\"; }\n\n.fa-chair:before {\n  content: \"\\f6c0\"; }\n\n.fa-chalkboard:before {\n  content: \"\\f51b\"; }\n\n.fa-chalkboard-teacher:before {\n  content: \"\\f51c\"; }\n\n.fa-charging-station:before {\n  content: \"\\f5e7\"; }\n\n.fa-chart-area:before {\n  content: \"\\f1fe\"; }\n\n.fa-chart-bar:before {\n  content: \"\\f080\"; }\n\n.fa-chart-line:before {\n  content: \"\\f201\"; }\n\n.fa-chart-pie:before {\n  content: \"\\f200\"; }\n\n.fa-check:before {\n  content: \"\\f00c\"; }\n\n.fa-check-circle:before {\n  content: \"\\f058\"; }\n\n.fa-check-double:before {\n  content: \"\\f560\"; }\n\n.fa-check-square:before {\n  content: \"\\f14a\"; }\n\n.fa-cheese:before {\n  content: \"\\f7ef\"; }\n\n.fa-chess:before {\n  content: \"\\f439\"; }\n\n.fa-chess-bishop:before {\n  content: \"\\f43a\"; }\n\n.fa-chess-board:before {\n  content: \"\\f43c\"; }\n\n.fa-chess-king:before {\n  content: \"\\f43f\"; }\n\n.fa-chess-knight:before {\n  content: \"\\f441\"; }\n\n.fa-chess-pawn:before {\n  content: \"\\f443\"; }\n\n.fa-chess-queen:before {\n  content: \"\\f445\"; }\n\n.fa-chess-rook:before {\n  content: \"\\f447\"; }\n\n.fa-chevron-circle-down:before {\n  content: \"\\f13a\"; }\n\n.fa-chevron-circle-left:before {\n  content: \"\\f137\"; }\n\n.fa-chevron-circle-right:before {\n  content: \"\\f138\"; }\n\n.fa-chevron-circle-up:before {\n  content: \"\\f139\"; }\n\n.fa-chevron-down:before {\n  content: \"\\f078\"; }\n\n.fa-chevron-left:before {\n  content: \"\\f053\"; }\n\n.fa-chevron-right:before {\n  content: \"\\f054\"; }\n\n.fa-chevron-up:before {\n  content: \"\\f077\"; }\n\n.fa-child:before {\n  content: \"\\f1ae\"; }\n\n.fa-chrome:before {\n  content: \"\\f268\"; }\n\n.fa-chromecast:before {\n  content: \"\\f838\"; }\n\n.fa-church:before {\n  content: \"\\f51d\"; }\n\n.fa-circle:before {\n  content: \"\\f111\"; }\n\n.fa-circle-notch:before {\n  content: \"\\f1ce\"; }\n\n.fa-city:before {\n  content: \"\\f64f\"; }\n\n.fa-clinic-medical:before {\n  content: \"\\f7f2\"; }\n\n.fa-clipboard:before {\n  content: \"\\f328\"; }\n\n.fa-clipboard-check:before {\n  content: \"\\f46c\"; }\n\n.fa-clipboard-list:before {\n  content: \"\\f46d\"; }\n\n.fa-clock:before {\n  content: \"\\f017\"; }\n\n.fa-clone:before {\n  content: \"\\f24d\"; }\n\n.fa-closed-captioning:before {\n  content: \"\\f20a\"; }\n\n.fa-cloud:before {\n  content: \"\\f0c2\"; }\n\n.fa-cloud-download-alt:before {\n  content: \"\\f381\"; }\n\n.fa-cloud-meatball:before {\n  content: \"\\f73b\"; }\n\n.fa-cloud-moon:before {\n  content: \"\\f6c3\"; }\n\n.fa-cloud-moon-rain:before {\n  content: \"\\f73c\"; }\n\n.fa-cloud-rain:before {\n  content: \"\\f73d\"; }\n\n.fa-cloud-showers-heavy:before {\n  content: \"\\f740\"; }\n\n.fa-cloud-sun:before {\n  content: \"\\f6c4\"; }\n\n.fa-cloud-sun-rain:before {\n  content: \"\\f743\"; }\n\n.fa-cloud-upload-alt:before {\n  content: \"\\f382\"; }\n\n.fa-cloudscale:before {\n  content: \"\\f383\"; }\n\n.fa-cloudsmith:before {\n  content: \"\\f384\"; }\n\n.fa-cloudversify:before {\n  content: \"\\f385\"; }\n\n.fa-cocktail:before {\n  content: \"\\f561\"; }\n\n.fa-code:before {\n  content: \"\\f121\"; }\n\n.fa-code-branch:before {\n  content: \"\\f126\"; }\n\n.fa-codepen:before {\n  content: \"\\f1cb\"; }\n\n.fa-codiepie:before {\n  content: \"\\f284\"; }\n\n.fa-coffee:before {\n  content: \"\\f0f4\"; }\n\n.fa-cog:before {\n  content: \"\\f013\"; }\n\n.fa-cogs:before {\n  content: \"\\f085\"; }\n\n.fa-coins:before {\n  content: \"\\f51e\"; }\n\n.fa-columns:before {\n  content: \"\\f0db\"; }\n\n.fa-comment:before {\n  content: \"\\f075\"; }\n\n.fa-comment-alt:before {\n  content: \"\\f27a\"; }\n\n.fa-comment-dollar:before {\n  content: \"\\f651\"; }\n\n.fa-comment-dots:before {\n  content: \"\\f4ad\"; }\n\n.fa-comment-medical:before {\n  content: \"\\f7f5\"; }\n\n.fa-comment-slash:before {\n  content: \"\\f4b3\"; }\n\n.fa-comments:before {\n  content: \"\\f086\"; }\n\n.fa-comments-dollar:before {\n  content: \"\\f653\"; }\n\n.fa-compact-disc:before {\n  content: \"\\f51f\"; }\n\n.fa-compass:before {\n  content: \"\\f14e\"; }\n\n.fa-compress:before {\n  content: \"\\f066\"; }\n\n.fa-compress-arrows-alt:before {\n  content: \"\\f78c\"; }\n\n.fa-concierge-bell:before {\n  content: \"\\f562\"; }\n\n.fa-confluence:before {\n  content: \"\\f78d\"; }\n\n.fa-connectdevelop:before {\n  content: \"\\f20e\"; }\n\n.fa-contao:before {\n  content: \"\\f26d\"; }\n\n.fa-cookie:before {\n  content: \"\\f563\"; }\n\n.fa-cookie-bite:before {\n  content: \"\\f564\"; }\n\n.fa-copy:before {\n  content: \"\\f0c5\"; }\n\n.fa-copyright:before {\n  content: \"\\f1f9\"; }\n\n.fa-cotton-bureau:before {\n  content: \"\\f89e\"; }\n\n.fa-couch:before {\n  content: \"\\f4b8\"; }\n\n.fa-cpanel:before {\n  content: \"\\f388\"; }\n\n.fa-creative-commons:before {\n  content: \"\\f25e\"; }\n\n.fa-creative-commons-by:before {\n  content: \"\\f4e7\"; }\n\n.fa-creative-commons-nc:before {\n  content: \"\\f4e8\"; }\n\n.fa-creative-commons-nc-eu:before {\n  content: \"\\f4e9\"; }\n\n.fa-creative-commons-nc-jp:before {\n  content: \"\\f4ea\"; }\n\n.fa-creative-commons-nd:before {\n  content: \"\\f4eb\"; }\n\n.fa-creative-commons-pd:before {\n  content: \"\\f4ec\"; }\n\n.fa-creative-commons-pd-alt:before {\n  content: \"\\f4ed\"; }\n\n.fa-creative-commons-remix:before {\n  content: \"\\f4ee\"; }\n\n.fa-creative-commons-sa:before {\n  content: \"\\f4ef\"; }\n\n.fa-creative-commons-sampling:before {\n  content: \"\\f4f0\"; }\n\n.fa-creative-commons-sampling-plus:before {\n  content: \"\\f4f1\"; }\n\n.fa-creative-commons-share:before {\n  content: \"\\f4f2\"; }\n\n.fa-creative-commons-zero:before {\n  content: \"\\f4f3\"; }\n\n.fa-credit-card:before {\n  content: \"\\f09d\"; }\n\n.fa-critical-role:before {\n  content: \"\\f6c9\"; }\n\n.fa-crop:before {\n  content: \"\\f125\"; }\n\n.fa-crop-alt:before {\n  content: \"\\f565\"; }\n\n.fa-cross:before {\n  content: \"\\f654\"; }\n\n.fa-crosshairs:before {\n  content: \"\\f05b\"; }\n\n.fa-crow:before {\n  content: \"\\f520\"; }\n\n.fa-crown:before {\n  content: \"\\f521\"; }\n\n.fa-crutch:before {\n  content: \"\\f7f7\"; }\n\n.fa-css3:before {\n  content: \"\\f13c\"; }\n\n.fa-css3-alt:before {\n  content: \"\\f38b\"; }\n\n.fa-cube:before {\n  content: \"\\f1b2\"; }\n\n.fa-cubes:before {\n  content: \"\\f1b3\"; }\n\n.fa-cut:before {\n  content: \"\\f0c4\"; }\n\n.fa-cuttlefish:before {\n  content: \"\\f38c\"; }\n\n.fa-d-and-d:before {\n  content: \"\\f38d\"; }\n\n.fa-d-and-d-beyond:before {\n  content: \"\\f6ca\"; }\n\n.fa-dashcube:before {\n  content: \"\\f210\"; }\n\n.fa-database:before {\n  content: \"\\f1c0\"; }\n\n.fa-deaf:before {\n  content: \"\\f2a4\"; }\n\n.fa-delicious:before {\n  content: \"\\f1a5\"; }\n\n.fa-democrat:before {\n  content: \"\\f747\"; }\n\n.fa-deploydog:before {\n  content: \"\\f38e\"; }\n\n.fa-deskpro:before {\n  content: \"\\f38f\"; }\n\n.fa-desktop:before {\n  content: \"\\f108\"; }\n\n.fa-dev:before {\n  content: \"\\f6cc\"; }\n\n.fa-deviantart:before {\n  content: \"\\f1bd\"; }\n\n.fa-dharmachakra:before {\n  content: \"\\f655\"; }\n\n.fa-dhl:before {\n  content: \"\\f790\"; }\n\n.fa-diagnoses:before {\n  content: \"\\f470\"; }\n\n.fa-diaspora:before {\n  content: \"\\f791\"; }\n\n.fa-dice:before {\n  content: \"\\f522\"; }\n\n.fa-dice-d20:before {\n  content: \"\\f6cf\"; }\n\n.fa-dice-d6:before {\n  content: \"\\f6d1\"; }\n\n.fa-dice-five:before {\n  content: \"\\f523\"; }\n\n.fa-dice-four:before {\n  content: \"\\f524\"; }\n\n.fa-dice-one:before {\n  content: \"\\f525\"; }\n\n.fa-dice-six:before {\n  content: \"\\f526\"; }\n\n.fa-dice-three:before {\n  content: \"\\f527\"; }\n\n.fa-dice-two:before {\n  content: \"\\f528\"; }\n\n.fa-digg:before {\n  content: \"\\f1a6\"; }\n\n.fa-digital-ocean:before {\n  content: \"\\f391\"; }\n\n.fa-digital-tachograph:before {\n  content: \"\\f566\"; }\n\n.fa-directions:before {\n  content: \"\\f5eb\"; }\n\n.fa-discord:before {\n  content: \"\\f392\"; }\n\n.fa-discourse:before {\n  content: \"\\f393\"; }\n\n.fa-divide:before {\n  content: \"\\f529\"; }\n\n.fa-dizzy:before {\n  content: \"\\f567\"; }\n\n.fa-dna:before {\n  content: \"\\f471\"; }\n\n.fa-dochub:before {\n  content: \"\\f394\"; }\n\n.fa-docker:before {\n  content: \"\\f395\"; }\n\n.fa-dog:before {\n  content: \"\\f6d3\"; }\n\n.fa-dollar-sign:before {\n  content: \"\\f155\"; }\n\n.fa-dolly:before {\n  content: \"\\f472\"; }\n\n.fa-dolly-flatbed:before {\n  content: \"\\f474\"; }\n\n.fa-donate:before {\n  content: \"\\f4b9\"; }\n\n.fa-door-closed:before {\n  content: \"\\f52a\"; }\n\n.fa-door-open:before {\n  content: \"\\f52b\"; }\n\n.fa-dot-circle:before {\n  content: \"\\f192\"; }\n\n.fa-dove:before {\n  content: \"\\f4ba\"; }\n\n.fa-download:before {\n  content: \"\\f019\"; }\n\n.fa-draft2digital:before {\n  content: \"\\f396\"; }\n\n.fa-drafting-compass:before {\n  content: \"\\f568\"; }\n\n.fa-dragon:before {\n  content: \"\\f6d5\"; }\n\n.fa-draw-polygon:before {\n  content: \"\\f5ee\"; }\n\n.fa-dribbble:before {\n  content: \"\\f17d\"; }\n\n.fa-dribbble-square:before {\n  content: \"\\f397\"; }\n\n.fa-dropbox:before {\n  content: \"\\f16b\"; }\n\n.fa-drum:before {\n  content: \"\\f569\"; }\n\n.fa-drum-steelpan:before {\n  content: \"\\f56a\"; }\n\n.fa-drumstick-bite:before {\n  content: \"\\f6d7\"; }\n\n.fa-drupal:before {\n  content: \"\\f1a9\"; }\n\n.fa-dumbbell:before {\n  content: \"\\f44b\"; }\n\n.fa-dumpster:before {\n  content: \"\\f793\"; }\n\n.fa-dumpster-fire:before {\n  content: \"\\f794\"; }\n\n.fa-dungeon:before {\n  content: \"\\f6d9\"; }\n\n.fa-dyalog:before {\n  content: \"\\f399\"; }\n\n.fa-earlybirds:before {\n  content: \"\\f39a\"; }\n\n.fa-ebay:before {\n  content: \"\\f4f4\"; }\n\n.fa-edge:before {\n  content: \"\\f282\"; }\n\n.fa-edit:before {\n  content: \"\\f044\"; }\n\n.fa-egg:before {\n  content: \"\\f7fb\"; }\n\n.fa-eject:before {\n  content: \"\\f052\"; }\n\n.fa-elementor:before {\n  content: \"\\f430\"; }\n\n.fa-ellipsis-h:before {\n  content: \"\\f141\"; }\n\n.fa-ellipsis-v:before {\n  content: \"\\f142\"; }\n\n.fa-ello:before {\n  content: \"\\f5f1\"; }\n\n.fa-ember:before {\n  content: \"\\f423\"; }\n\n.fa-empire:before {\n  content: \"\\f1d1\"; }\n\n.fa-envelope:before {\n  content: \"\\f0e0\"; }\n\n.fa-envelope-open:before {\n  content: \"\\f2b6\"; }\n\n.fa-envelope-open-text:before {\n  content: \"\\f658\"; }\n\n.fa-envelope-square:before {\n  content: \"\\f199\"; }\n\n.fa-envira:before {\n  content: \"\\f299\"; }\n\n.fa-equals:before {\n  content: \"\\f52c\"; }\n\n.fa-eraser:before {\n  content: \"\\f12d\"; }\n\n.fa-erlang:before {\n  content: \"\\f39d\"; }\n\n.fa-ethereum:before {\n  content: \"\\f42e\"; }\n\n.fa-ethernet:before {\n  content: \"\\f796\"; }\n\n.fa-etsy:before {\n  content: \"\\f2d7\"; }\n\n.fa-euro-sign:before {\n  content: \"\\f153\"; }\n\n.fa-evernote:before {\n  content: \"\\f839\"; }\n\n.fa-exchange-alt:before {\n  content: \"\\f362\"; }\n\n.fa-exclamation:before {\n  content: \"\\f12a\"; }\n\n.fa-exclamation-circle:before {\n  content: \"\\f06a\"; }\n\n.fa-exclamation-triangle:before {\n  content: \"\\f071\"; }\n\n.fa-expand:before {\n  content: \"\\f065\"; }\n\n.fa-expand-arrows-alt:before {\n  content: \"\\f31e\"; }\n\n.fa-expeditedssl:before {\n  content: \"\\f23e\"; }\n\n.fa-external-link-alt:before {\n  content: \"\\f35d\"; }\n\n.fa-external-link-square-alt:before {\n  content: \"\\f360\"; }\n\n.fa-eye:before {\n  content: \"\\f06e\"; }\n\n.fa-eye-dropper:before {\n  content: \"\\f1fb\"; }\n\n.fa-eye-slash:before {\n  content: \"\\f070\"; }\n\n.fa-facebook:before {\n  content: \"\\f09a\"; }\n\n.fa-facebook-f:before {\n  content: \"\\f39e\"; }\n\n.fa-facebook-messenger:before {\n  content: \"\\f39f\"; }\n\n.fa-facebook-square:before {\n  content: \"\\f082\"; }\n\n.fa-fan:before {\n  content: \"\\f863\"; }\n\n.fa-fantasy-flight-games:before {\n  content: \"\\f6dc\"; }\n\n.fa-fast-backward:before {\n  content: \"\\f049\"; }\n\n.fa-fast-forward:before {\n  content: \"\\f050\"; }\n\n.fa-fax:before {\n  content: \"\\f1ac\"; }\n\n.fa-feather:before {\n  content: \"\\f52d\"; }\n\n.fa-feather-alt:before {\n  content: \"\\f56b\"; }\n\n.fa-fedex:before {\n  content: \"\\f797\"; }\n\n.fa-fedora:before {\n  content: \"\\f798\"; }\n\n.fa-female:before {\n  content: \"\\f182\"; }\n\n.fa-fighter-jet:before {\n  content: \"\\f0fb\"; }\n\n.fa-figma:before {\n  content: \"\\f799\"; }\n\n.fa-file:before {\n  content: \"\\f15b\"; }\n\n.fa-file-alt:before {\n  content: \"\\f15c\"; }\n\n.fa-file-archive:before {\n  content: \"\\f1c6\"; }\n\n.fa-file-audio:before {\n  content: \"\\f1c7\"; }\n\n.fa-file-code:before {\n  content: \"\\f1c9\"; }\n\n.fa-file-contract:before {\n  content: \"\\f56c\"; }\n\n.fa-file-csv:before {\n  content: \"\\f6dd\"; }\n\n.fa-file-download:before {\n  content: \"\\f56d\"; }\n\n.fa-file-excel:before {\n  content: \"\\f1c3\"; }\n\n.fa-file-export:before {\n  content: \"\\f56e\"; }\n\n.fa-file-image:before {\n  content: \"\\f1c5\"; }\n\n.fa-file-import:before {\n  content: \"\\f56f\"; }\n\n.fa-file-invoice:before {\n  content: \"\\f570\"; }\n\n.fa-file-invoice-dollar:before {\n  content: \"\\f571\"; }\n\n.fa-file-medical:before {\n  content: \"\\f477\"; }\n\n.fa-file-medical-alt:before {\n  content: \"\\f478\"; }\n\n.fa-file-pdf:before {\n  content: \"\\f1c1\"; }\n\n.fa-file-powerpoint:before {\n  content: \"\\f1c4\"; }\n\n.fa-file-prescription:before {\n  content: \"\\f572\"; }\n\n.fa-file-signature:before {\n  content: \"\\f573\"; }\n\n.fa-file-upload:before {\n  content: \"\\f574\"; }\n\n.fa-file-video:before {\n  content: \"\\f1c8\"; }\n\n.fa-file-word:before {\n  content: \"\\f1c2\"; }\n\n.fa-fill:before {\n  content: \"\\f575\"; }\n\n.fa-fill-drip:before {\n  content: \"\\f576\"; }\n\n.fa-film:before {\n  content: \"\\f008\"; }\n\n.fa-filter:before {\n  content: \"\\f0b0\"; }\n\n.fa-fingerprint:before {\n  content: \"\\f577\"; }\n\n.fa-fire:before {\n  content: \"\\f06d\"; }\n\n.fa-fire-alt:before {\n  content: \"\\f7e4\"; }\n\n.fa-fire-extinguisher:before {\n  content: \"\\f134\"; }\n\n.fa-firefox:before {\n  content: \"\\f269\"; }\n\n.fa-first-aid:before {\n  content: \"\\f479\"; }\n\n.fa-first-order:before {\n  content: \"\\f2b0\"; }\n\n.fa-first-order-alt:before {\n  content: \"\\f50a\"; }\n\n.fa-firstdraft:before {\n  content: \"\\f3a1\"; }\n\n.fa-fish:before {\n  content: \"\\f578\"; }\n\n.fa-fist-raised:before {\n  content: \"\\f6de\"; }\n\n.fa-flag:before {\n  content: \"\\f024\"; }\n\n.fa-flag-checkered:before {\n  content: \"\\f11e\"; }\n\n.fa-flag-usa:before {\n  content: \"\\f74d\"; }\n\n.fa-flask:before {\n  content: \"\\f0c3\"; }\n\n.fa-flickr:before {\n  content: \"\\f16e\"; }\n\n.fa-flipboard:before {\n  content: \"\\f44d\"; }\n\n.fa-flushed:before {\n  content: \"\\f579\"; }\n\n.fa-fly:before {\n  content: \"\\f417\"; }\n\n.fa-folder:before {\n  content: \"\\f07b\"; }\n\n.fa-folder-minus:before {\n  content: \"\\f65d\"; }\n\n.fa-folder-open:before {\n  content: \"\\f07c\"; }\n\n.fa-folder-plus:before {\n  content: \"\\f65e\"; }\n\n.fa-font:before {\n  content: \"\\f031\"; }\n\n.fa-font-awesome:before {\n  content: \"\\f2b4\"; }\n\n.fa-font-awesome-alt:before {\n  content: \"\\f35c\"; }\n\n.fa-font-awesome-flag:before {\n  content: \"\\f425\"; }\n\n.fa-font-awesome-logo-full:before {\n  content: \"\\f4e6\"; }\n\n.fa-fonticons:before {\n  content: \"\\f280\"; }\n\n.fa-fonticons-fi:before {\n  content: \"\\f3a2\"; }\n\n.fa-football-ball:before {\n  content: \"\\f44e\"; }\n\n.fa-fort-awesome:before {\n  content: \"\\f286\"; }\n\n.fa-fort-awesome-alt:before {\n  content: \"\\f3a3\"; }\n\n.fa-forumbee:before {\n  content: \"\\f211\"; }\n\n.fa-forward:before {\n  content: \"\\f04e\"; }\n\n.fa-foursquare:before {\n  content: \"\\f180\"; }\n\n.fa-free-code-camp:before {\n  content: \"\\f2c5\"; }\n\n.fa-freebsd:before {\n  content: \"\\f3a4\"; }\n\n.fa-frog:before {\n  content: \"\\f52e\"; }\n\n.fa-frown:before {\n  content: \"\\f119\"; }\n\n.fa-frown-open:before {\n  content: \"\\f57a\"; }\n\n.fa-fulcrum:before {\n  content: \"\\f50b\"; }\n\n.fa-funnel-dollar:before {\n  content: \"\\f662\"; }\n\n.fa-futbol:before {\n  content: \"\\f1e3\"; }\n\n.fa-galactic-republic:before {\n  content: \"\\f50c\"; }\n\n.fa-galactic-senate:before {\n  content: \"\\f50d\"; }\n\n.fa-gamepad:before {\n  content: \"\\f11b\"; }\n\n.fa-gas-pump:before {\n  content: \"\\f52f\"; }\n\n.fa-gavel:before {\n  content: \"\\f0e3\"; }\n\n.fa-gem:before {\n  content: \"\\f3a5\"; }\n\n.fa-genderless:before {\n  content: \"\\f22d\"; }\n\n.fa-get-pocket:before {\n  content: \"\\f265\"; }\n\n.fa-gg:before {\n  content: \"\\f260\"; }\n\n.fa-gg-circle:before {\n  content: \"\\f261\"; }\n\n.fa-ghost:before {\n  content: \"\\f6e2\"; }\n\n.fa-gift:before {\n  content: \"\\f06b\"; }\n\n.fa-gifts:before {\n  content: \"\\f79c\"; }\n\n.fa-git:before {\n  content: \"\\f1d3\"; }\n\n.fa-git-alt:before {\n  content: \"\\f841\"; }\n\n.fa-git-square:before {\n  content: \"\\f1d2\"; }\n\n.fa-github:before {\n  content: \"\\f09b\"; }\n\n.fa-github-alt:before {\n  content: \"\\f113\"; }\n\n.fa-github-square:before {\n  content: \"\\f092\"; }\n\n.fa-gitkraken:before {\n  content: \"\\f3a6\"; }\n\n.fa-gitlab:before {\n  content: \"\\f296\"; }\n\n.fa-gitter:before {\n  content: \"\\f426\"; }\n\n.fa-glass-cheers:before {\n  content: \"\\f79f\"; }\n\n.fa-glass-martini:before {\n  content: \"\\f000\"; }\n\n.fa-glass-martini-alt:before {\n  content: \"\\f57b\"; }\n\n.fa-glass-whiskey:before {\n  content: \"\\f7a0\"; }\n\n.fa-glasses:before {\n  content: \"\\f530\"; }\n\n.fa-glide:before {\n  content: \"\\f2a5\"; }\n\n.fa-glide-g:before {\n  content: \"\\f2a6\"; }\n\n.fa-globe:before {\n  content: \"\\f0ac\"; }\n\n.fa-globe-africa:before {\n  content: \"\\f57c\"; }\n\n.fa-globe-americas:before {\n  content: \"\\f57d\"; }\n\n.fa-globe-asia:before {\n  content: \"\\f57e\"; }\n\n.fa-globe-europe:before {\n  content: \"\\f7a2\"; }\n\n.fa-gofore:before {\n  content: \"\\f3a7\"; }\n\n.fa-golf-ball:before {\n  content: \"\\f450\"; }\n\n.fa-goodreads:before {\n  content: \"\\f3a8\"; }\n\n.fa-goodreads-g:before {\n  content: \"\\f3a9\"; }\n\n.fa-google:before {\n  content: \"\\f1a0\"; }\n\n.fa-google-drive:before {\n  content: \"\\f3aa\"; }\n\n.fa-google-play:before {\n  content: \"\\f3ab\"; }\n\n.fa-google-plus:before {\n  content: \"\\f2b3\"; }\n\n.fa-google-plus-g:before {\n  content: \"\\f0d5\"; }\n\n.fa-google-plus-square:before {\n  content: \"\\f0d4\"; }\n\n.fa-google-wallet:before {\n  content: \"\\f1ee\"; }\n\n.fa-gopuram:before {\n  content: \"\\f664\"; }\n\n.fa-graduation-cap:before {\n  content: \"\\f19d\"; }\n\n.fa-gratipay:before {\n  content: \"\\f184\"; }\n\n.fa-grav:before {\n  content: \"\\f2d6\"; }\n\n.fa-greater-than:before {\n  content: \"\\f531\"; }\n\n.fa-greater-than-equal:before {\n  content: \"\\f532\"; }\n\n.fa-grimace:before {\n  content: \"\\f57f\"; }\n\n.fa-grin:before {\n  content: \"\\f580\"; }\n\n.fa-grin-alt:before {\n  content: \"\\f581\"; }\n\n.fa-grin-beam:before {\n  content: \"\\f582\"; }\n\n.fa-grin-beam-sweat:before {\n  content: \"\\f583\"; }\n\n.fa-grin-hearts:before {\n  content: \"\\f584\"; }\n\n.fa-grin-squint:before {\n  content: \"\\f585\"; }\n\n.fa-grin-squint-tears:before {\n  content: \"\\f586\"; }\n\n.fa-grin-stars:before {\n  content: \"\\f587\"; }\n\n.fa-grin-tears:before {\n  content: \"\\f588\"; }\n\n.fa-grin-tongue:before {\n  content: \"\\f589\"; }\n\n.fa-grin-tongue-squint:before {\n  content: \"\\f58a\"; }\n\n.fa-grin-tongue-wink:before {\n  content: \"\\f58b\"; }\n\n.fa-grin-wink:before {\n  content: \"\\f58c\"; }\n\n.fa-grip-horizontal:before {\n  content: \"\\f58d\"; }\n\n.fa-grip-lines:before {\n  content: \"\\f7a4\"; }\n\n.fa-grip-lines-vertical:before {\n  content: \"\\f7a5\"; }\n\n.fa-grip-vertical:before {\n  content: \"\\f58e\"; }\n\n.fa-gripfire:before {\n  content: \"\\f3ac\"; }\n\n.fa-grunt:before {\n  content: \"\\f3ad\"; }\n\n.fa-guitar:before {\n  content: \"\\f7a6\"; }\n\n.fa-gulp:before {\n  content: \"\\f3ae\"; }\n\n.fa-h-square:before {\n  content: \"\\f0fd\"; }\n\n.fa-hacker-news:before {\n  content: \"\\f1d4\"; }\n\n.fa-hacker-news-square:before {\n  content: \"\\f3af\"; }\n\n.fa-hackerrank:before {\n  content: \"\\f5f7\"; }\n\n.fa-hamburger:before {\n  content: \"\\f805\"; }\n\n.fa-hammer:before {\n  content: \"\\f6e3\"; }\n\n.fa-hamsa:before {\n  content: \"\\f665\"; }\n\n.fa-hand-holding:before {\n  content: \"\\f4bd\"; }\n\n.fa-hand-holding-heart:before {\n  content: \"\\f4be\"; }\n\n.fa-hand-holding-usd:before {\n  content: \"\\f4c0\"; }\n\n.fa-hand-lizard:before {\n  content: \"\\f258\"; }\n\n.fa-hand-middle-finger:before {\n  content: \"\\f806\"; }\n\n.fa-hand-paper:before {\n  content: \"\\f256\"; }\n\n.fa-hand-peace:before {\n  content: \"\\f25b\"; }\n\n.fa-hand-point-down:before {\n  content: \"\\f0a7\"; }\n\n.fa-hand-point-left:before {\n  content: \"\\f0a5\"; }\n\n.fa-hand-point-right:before {\n  content: \"\\f0a4\"; }\n\n.fa-hand-point-up:before {\n  content: \"\\f0a6\"; }\n\n.fa-hand-pointer:before {\n  content: \"\\f25a\"; }\n\n.fa-hand-rock:before {\n  content: \"\\f255\"; }\n\n.fa-hand-scissors:before {\n  content: \"\\f257\"; }\n\n.fa-hand-spock:before {\n  content: \"\\f259\"; }\n\n.fa-hands:before {\n  content: \"\\f4c2\"; }\n\n.fa-hands-helping:before {\n  content: \"\\f4c4\"; }\n\n.fa-handshake:before {\n  content: \"\\f2b5\"; }\n\n.fa-hanukiah:before {\n  content: \"\\f6e6\"; }\n\n.fa-hard-hat:before {\n  content: \"\\f807\"; }\n\n.fa-hashtag:before {\n  content: \"\\f292\"; }\n\n.fa-hat-wizard:before {\n  content: \"\\f6e8\"; }\n\n.fa-haykal:before {\n  content: \"\\f666\"; }\n\n.fa-hdd:before {\n  content: \"\\f0a0\"; }\n\n.fa-heading:before {\n  content: \"\\f1dc\"; }\n\n.fa-headphones:before {\n  content: \"\\f025\"; }\n\n.fa-headphones-alt:before {\n  content: \"\\f58f\"; }\n\n.fa-headset:before {\n  content: \"\\f590\"; }\n\n.fa-heart:before {\n  content: \"\\f004\"; }\n\n.fa-heart-broken:before {\n  content: \"\\f7a9\"; }\n\n.fa-heartbeat:before {\n  content: \"\\f21e\"; }\n\n.fa-helicopter:before {\n  content: \"\\f533\"; }\n\n.fa-highlighter:before {\n  content: \"\\f591\"; }\n\n.fa-hiking:before {\n  content: \"\\f6ec\"; }\n\n.fa-hippo:before {\n  content: \"\\f6ed\"; }\n\n.fa-hips:before {\n  content: \"\\f452\"; }\n\n.fa-hire-a-helper:before {\n  content: \"\\f3b0\"; }\n\n.fa-history:before {\n  content: \"\\f1da\"; }\n\n.fa-hockey-puck:before {\n  content: \"\\f453\"; }\n\n.fa-holly-berry:before {\n  content: \"\\f7aa\"; }\n\n.fa-home:before {\n  content: \"\\f015\"; }\n\n.fa-hooli:before {\n  content: \"\\f427\"; }\n\n.fa-hornbill:before {\n  content: \"\\f592\"; }\n\n.fa-horse:before {\n  content: \"\\f6f0\"; }\n\n.fa-horse-head:before {\n  content: \"\\f7ab\"; }\n\n.fa-hospital:before {\n  content: \"\\f0f8\"; }\n\n.fa-hospital-alt:before {\n  content: \"\\f47d\"; }\n\n.fa-hospital-symbol:before {\n  content: \"\\f47e\"; }\n\n.fa-hot-tub:before {\n  content: \"\\f593\"; }\n\n.fa-hotdog:before {\n  content: \"\\f80f\"; }\n\n.fa-hotel:before {\n  content: \"\\f594\"; }\n\n.fa-hotjar:before {\n  content: \"\\f3b1\"; }\n\n.fa-hourglass:before {\n  content: \"\\f254\"; }\n\n.fa-hourglass-end:before {\n  content: \"\\f253\"; }\n\n.fa-hourglass-half:before {\n  content: \"\\f252\"; }\n\n.fa-hourglass-start:before {\n  content: \"\\f251\"; }\n\n.fa-house-damage:before {\n  content: \"\\f6f1\"; }\n\n.fa-houzz:before {\n  content: \"\\f27c\"; }\n\n.fa-hryvnia:before {\n  content: \"\\f6f2\"; }\n\n.fa-html5:before {\n  content: \"\\f13b\"; }\n\n.fa-hubspot:before {\n  content: \"\\f3b2\"; }\n\n.fa-i-cursor:before {\n  content: \"\\f246\"; }\n\n.fa-ice-cream:before {\n  content: \"\\f810\"; }\n\n.fa-icicles:before {\n  content: \"\\f7ad\"; }\n\n.fa-icons:before {\n  content: \"\\f86d\"; }\n\n.fa-id-badge:before {\n  content: \"\\f2c1\"; }\n\n.fa-id-card:before {\n  content: \"\\f2c2\"; }\n\n.fa-id-card-alt:before {\n  content: \"\\f47f\"; }\n\n.fa-igloo:before {\n  content: \"\\f7ae\"; }\n\n.fa-image:before {\n  content: \"\\f03e\"; }\n\n.fa-images:before {\n  content: \"\\f302\"; }\n\n.fa-imdb:before {\n  content: \"\\f2d8\"; }\n\n.fa-inbox:before {\n  content: \"\\f01c\"; }\n\n.fa-indent:before {\n  content: \"\\f03c\"; }\n\n.fa-industry:before {\n  content: \"\\f275\"; }\n\n.fa-infinity:before {\n  content: \"\\f534\"; }\n\n.fa-info:before {\n  content: \"\\f129\"; }\n\n.fa-info-circle:before {\n  content: \"\\f05a\"; }\n\n.fa-instagram:before {\n  content: \"\\f16d\"; }\n\n.fa-intercom:before {\n  content: \"\\f7af\"; }\n\n.fa-internet-explorer:before {\n  content: \"\\f26b\"; }\n\n.fa-invision:before {\n  content: \"\\f7b0\"; }\n\n.fa-ioxhost:before {\n  content: \"\\f208\"; }\n\n.fa-italic:before {\n  content: \"\\f033\"; }\n\n.fa-itch-io:before {\n  content: \"\\f83a\"; }\n\n.fa-itunes:before {\n  content: \"\\f3b4\"; }\n\n.fa-itunes-note:before {\n  content: \"\\f3b5\"; }\n\n.fa-java:before {\n  content: \"\\f4e4\"; }\n\n.fa-jedi:before {\n  content: \"\\f669\"; }\n\n.fa-jedi-order:before {\n  content: \"\\f50e\"; }\n\n.fa-jenkins:before {\n  content: \"\\f3b6\"; }\n\n.fa-jira:before {\n  content: \"\\f7b1\"; }\n\n.fa-joget:before {\n  content: \"\\f3b7\"; }\n\n.fa-joint:before {\n  content: \"\\f595\"; }\n\n.fa-joomla:before {\n  content: \"\\f1aa\"; }\n\n.fa-journal-whills:before {\n  content: \"\\f66a\"; }\n\n.fa-js:before {\n  content: \"\\f3b8\"; }\n\n.fa-js-square:before {\n  content: \"\\f3b9\"; }\n\n.fa-jsfiddle:before {\n  content: \"\\f1cc\"; }\n\n.fa-kaaba:before {\n  content: \"\\f66b\"; }\n\n.fa-kaggle:before {\n  content: \"\\f5fa\"; }\n\n.fa-key:before {\n  content: \"\\f084\"; }\n\n.fa-keybase:before {\n  content: \"\\f4f5\"; }\n\n.fa-keyboard:before {\n  content: \"\\f11c\"; }\n\n.fa-keycdn:before {\n  content: \"\\f3ba\"; }\n\n.fa-khanda:before {\n  content: \"\\f66d\"; }\n\n.fa-kickstarter:before {\n  content: \"\\f3bb\"; }\n\n.fa-kickstarter-k:before {\n  content: \"\\f3bc\"; }\n\n.fa-kiss:before {\n  content: \"\\f596\"; }\n\n.fa-kiss-beam:before {\n  content: \"\\f597\"; }\n\n.fa-kiss-wink-heart:before {\n  content: \"\\f598\"; }\n\n.fa-kiwi-bird:before {\n  content: \"\\f535\"; }\n\n.fa-korvue:before {\n  content: \"\\f42f\"; }\n\n.fa-landmark:before {\n  content: \"\\f66f\"; }\n\n.fa-language:before {\n  content: \"\\f1ab\"; }\n\n.fa-laptop:before {\n  content: \"\\f109\"; }\n\n.fa-laptop-code:before {\n  content: \"\\f5fc\"; }\n\n.fa-laptop-medical:before {\n  content: \"\\f812\"; }\n\n.fa-laravel:before {\n  content: \"\\f3bd\"; }\n\n.fa-lastfm:before {\n  content: \"\\f202\"; }\n\n.fa-lastfm-square:before {\n  content: \"\\f203\"; }\n\n.fa-laugh:before {\n  content: \"\\f599\"; }\n\n.fa-laugh-beam:before {\n  content: \"\\f59a\"; }\n\n.fa-laugh-squint:before {\n  content: \"\\f59b\"; }\n\n.fa-laugh-wink:before {\n  content: \"\\f59c\"; }\n\n.fa-layer-group:before {\n  content: \"\\f5fd\"; }\n\n.fa-leaf:before {\n  content: \"\\f06c\"; }\n\n.fa-leanpub:before {\n  content: \"\\f212\"; }\n\n.fa-lemon:before {\n  content: \"\\f094\"; }\n\n.fa-less:before {\n  content: \"\\f41d\"; }\n\n.fa-less-than:before {\n  content: \"\\f536\"; }\n\n.fa-less-than-equal:before {\n  content: \"\\f537\"; }\n\n.fa-level-down-alt:before {\n  content: \"\\f3be\"; }\n\n.fa-level-up-alt:before {\n  content: \"\\f3bf\"; }\n\n.fa-life-ring:before {\n  content: \"\\f1cd\"; }\n\n.fa-lightbulb:before {\n  content: \"\\f0eb\"; }\n\n.fa-line:before {\n  content: \"\\f3c0\"; }\n\n.fa-link:before {\n  content: \"\\f0c1\"; }\n\n.fa-linkedin:before {\n  content: \"\\f08c\"; }\n\n.fa-linkedin-in:before {\n  content: \"\\f0e1\"; }\n\n.fa-linode:before {\n  content: \"\\f2b8\"; }\n\n.fa-linux:before {\n  content: \"\\f17c\"; }\n\n.fa-lira-sign:before {\n  content: \"\\f195\"; }\n\n.fa-list:before {\n  content: \"\\f03a\"; }\n\n.fa-list-alt:before {\n  content: \"\\f022\"; }\n\n.fa-list-ol:before {\n  content: \"\\f0cb\"; }\n\n.fa-list-ul:before {\n  content: \"\\f0ca\"; }\n\n.fa-location-arrow:before {\n  content: \"\\f124\"; }\n\n.fa-lock:before {\n  content: \"\\f023\"; }\n\n.fa-lock-open:before {\n  content: \"\\f3c1\"; }\n\n.fa-long-arrow-alt-down:before {\n  content: \"\\f309\"; }\n\n.fa-long-arrow-alt-left:before {\n  content: \"\\f30a\"; }\n\n.fa-long-arrow-alt-right:before {\n  content: \"\\f30b\"; }\n\n.fa-long-arrow-alt-up:before {\n  content: \"\\f30c\"; }\n\n.fa-low-vision:before {\n  content: \"\\f2a8\"; }\n\n.fa-luggage-cart:before {\n  content: \"\\f59d\"; }\n\n.fa-lyft:before {\n  content: \"\\f3c3\"; }\n\n.fa-magento:before {\n  content: \"\\f3c4\"; }\n\n.fa-magic:before {\n  content: \"\\f0d0\"; }\n\n.fa-magnet:before {\n  content: \"\\f076\"; }\n\n.fa-mail-bulk:before {\n  content: \"\\f674\"; }\n\n.fa-mailchimp:before {\n  content: \"\\f59e\"; }\n\n.fa-male:before {\n  content: \"\\f183\"; }\n\n.fa-mandalorian:before {\n  content: \"\\f50f\"; }\n\n.fa-map:before {\n  content: \"\\f279\"; }\n\n.fa-map-marked:before {\n  content: \"\\f59f\"; }\n\n.fa-map-marked-alt:before {\n  content: \"\\f5a0\"; }\n\n.fa-map-marker:before {\n  content: \"\\f041\"; }\n\n.fa-map-marker-alt:before {\n  content: \"\\f3c5\"; }\n\n.fa-map-pin:before {\n  content: \"\\f276\"; }\n\n.fa-map-signs:before {\n  content: \"\\f277\"; }\n\n.fa-markdown:before {\n  content: \"\\f60f\"; }\n\n.fa-marker:before {\n  content: \"\\f5a1\"; }\n\n.fa-mars:before {\n  content: \"\\f222\"; }\n\n.fa-mars-double:before {\n  content: \"\\f227\"; }\n\n.fa-mars-stroke:before {\n  content: \"\\f229\"; }\n\n.fa-mars-stroke-h:before {\n  content: \"\\f22b\"; }\n\n.fa-mars-stroke-v:before {\n  content: \"\\f22a\"; }\n\n.fa-mask:before {\n  content: \"\\f6fa\"; }\n\n.fa-mastodon:before {\n  content: \"\\f4f6\"; }\n\n.fa-maxcdn:before {\n  content: \"\\f136\"; }\n\n.fa-medal:before {\n  content: \"\\f5a2\"; }\n\n.fa-medapps:before {\n  content: \"\\f3c6\"; }\n\n.fa-medium:before {\n  content: \"\\f23a\"; }\n\n.fa-medium-m:before {\n  content: \"\\f3c7\"; }\n\n.fa-medkit:before {\n  content: \"\\f0fa\"; }\n\n.fa-medrt:before {\n  content: \"\\f3c8\"; }\n\n.fa-meetup:before {\n  content: \"\\f2e0\"; }\n\n.fa-megaport:before {\n  content: \"\\f5a3\"; }\n\n.fa-meh:before {\n  content: \"\\f11a\"; }\n\n.fa-meh-blank:before {\n  content: \"\\f5a4\"; }\n\n.fa-meh-rolling-eyes:before {\n  content: \"\\f5a5\"; }\n\n.fa-memory:before {\n  content: \"\\f538\"; }\n\n.fa-mendeley:before {\n  content: \"\\f7b3\"; }\n\n.fa-menorah:before {\n  content: \"\\f676\"; }\n\n.fa-mercury:before {\n  content: \"\\f223\"; }\n\n.fa-meteor:before {\n  content: \"\\f753\"; }\n\n.fa-microchip:before {\n  content: \"\\f2db\"; }\n\n.fa-microphone:before {\n  content: \"\\f130\"; }\n\n.fa-microphone-alt:before {\n  content: \"\\f3c9\"; }\n\n.fa-microphone-alt-slash:before {\n  content: \"\\f539\"; }\n\n.fa-microphone-slash:before {\n  content: \"\\f131\"; }\n\n.fa-microscope:before {\n  content: \"\\f610\"; }\n\n.fa-microsoft:before {\n  content: \"\\f3ca\"; }\n\n.fa-minus:before {\n  content: \"\\f068\"; }\n\n.fa-minus-circle:before {\n  content: \"\\f056\"; }\n\n.fa-minus-square:before {\n  content: \"\\f146\"; }\n\n.fa-mitten:before {\n  content: \"\\f7b5\"; }\n\n.fa-mix:before {\n  content: \"\\f3cb\"; }\n\n.fa-mixcloud:before {\n  content: \"\\f289\"; }\n\n.fa-mizuni:before {\n  content: \"\\f3cc\"; }\n\n.fa-mobile:before {\n  content: \"\\f10b\"; }\n\n.fa-mobile-alt:before {\n  content: \"\\f3cd\"; }\n\n.fa-modx:before {\n  content: \"\\f285\"; }\n\n.fa-monero:before {\n  content: \"\\f3d0\"; }\n\n.fa-money-bill:before {\n  content: \"\\f0d6\"; }\n\n.fa-money-bill-alt:before {\n  content: \"\\f3d1\"; }\n\n.fa-money-bill-wave:before {\n  content: \"\\f53a\"; }\n\n.fa-money-bill-wave-alt:before {\n  content: \"\\f53b\"; }\n\n.fa-money-check:before {\n  content: \"\\f53c\"; }\n\n.fa-money-check-alt:before {\n  content: \"\\f53d\"; }\n\n.fa-monument:before {\n  content: \"\\f5a6\"; }\n\n.fa-moon:before {\n  content: \"\\f186\"; }\n\n.fa-mortar-pestle:before {\n  content: \"\\f5a7\"; }\n\n.fa-mosque:before {\n  content: \"\\f678\"; }\n\n.fa-motorcycle:before {\n  content: \"\\f21c\"; }\n\n.fa-mountain:before {\n  content: \"\\f6fc\"; }\n\n.fa-mouse-pointer:before {\n  content: \"\\f245\"; }\n\n.fa-mug-hot:before {\n  content: \"\\f7b6\"; }\n\n.fa-music:before {\n  content: \"\\f001\"; }\n\n.fa-napster:before {\n  content: \"\\f3d2\"; }\n\n.fa-neos:before {\n  content: \"\\f612\"; }\n\n.fa-network-wired:before {\n  content: \"\\f6ff\"; }\n\n.fa-neuter:before {\n  content: \"\\f22c\"; }\n\n.fa-newspaper:before {\n  content: \"\\f1ea\"; }\n\n.fa-nimblr:before {\n  content: \"\\f5a8\"; }\n\n.fa-node:before {\n  content: \"\\f419\"; }\n\n.fa-node-js:before {\n  content: \"\\f3d3\"; }\n\n.fa-not-equal:before {\n  content: \"\\f53e\"; }\n\n.fa-notes-medical:before {\n  content: \"\\f481\"; }\n\n.fa-npm:before {\n  content: \"\\f3d4\"; }\n\n.fa-ns8:before {\n  content: \"\\f3d5\"; }\n\n.fa-nutritionix:before {\n  content: \"\\f3d6\"; }\n\n.fa-object-group:before {\n  content: \"\\f247\"; }\n\n.fa-object-ungroup:before {\n  content: \"\\f248\"; }\n\n.fa-odnoklassniki:before {\n  content: \"\\f263\"; }\n\n.fa-odnoklassniki-square:before {\n  content: \"\\f264\"; }\n\n.fa-oil-can:before {\n  content: \"\\f613\"; }\n\n.fa-old-republic:before {\n  content: \"\\f510\"; }\n\n.fa-om:before {\n  content: \"\\f679\"; }\n\n.fa-opencart:before {\n  content: \"\\f23d\"; }\n\n.fa-openid:before {\n  content: \"\\f19b\"; }\n\n.fa-opera:before {\n  content: \"\\f26a\"; }\n\n.fa-optin-monster:before {\n  content: \"\\f23c\"; }\n\n.fa-osi:before {\n  content: \"\\f41a\"; }\n\n.fa-otter:before {\n  content: \"\\f700\"; }\n\n.fa-outdent:before {\n  content: \"\\f03b\"; }\n\n.fa-page4:before {\n  content: \"\\f3d7\"; }\n\n.fa-pagelines:before {\n  content: \"\\f18c\"; }\n\n.fa-pager:before {\n  content: \"\\f815\"; }\n\n.fa-paint-brush:before {\n  content: \"\\f1fc\"; }\n\n.fa-paint-roller:before {\n  content: \"\\f5aa\"; }\n\n.fa-palette:before {\n  content: \"\\f53f\"; }\n\n.fa-palfed:before {\n  content: \"\\f3d8\"; }\n\n.fa-pallet:before {\n  content: \"\\f482\"; }\n\n.fa-paper-plane:before {\n  content: \"\\f1d8\"; }\n\n.fa-paperclip:before {\n  content: \"\\f0c6\"; }\n\n.fa-parachute-box:before {\n  content: \"\\f4cd\"; }\n\n.fa-paragraph:before {\n  content: \"\\f1dd\"; }\n\n.fa-parking:before {\n  content: \"\\f540\"; }\n\n.fa-passport:before {\n  content: \"\\f5ab\"; }\n\n.fa-pastafarianism:before {\n  content: \"\\f67b\"; }\n\n.fa-paste:before {\n  content: \"\\f0ea\"; }\n\n.fa-patreon:before {\n  content: \"\\f3d9\"; }\n\n.fa-pause:before {\n  content: \"\\f04c\"; }\n\n.fa-pause-circle:before {\n  content: \"\\f28b\"; }\n\n.fa-paw:before {\n  content: \"\\f1b0\"; }\n\n.fa-paypal:before {\n  content: \"\\f1ed\"; }\n\n.fa-peace:before {\n  content: \"\\f67c\"; }\n\n.fa-pen:before {\n  content: \"\\f304\"; }\n\n.fa-pen-alt:before {\n  content: \"\\f305\"; }\n\n.fa-pen-fancy:before {\n  content: \"\\f5ac\"; }\n\n.fa-pen-nib:before {\n  content: \"\\f5ad\"; }\n\n.fa-pen-square:before {\n  content: \"\\f14b\"; }\n\n.fa-pencil-alt:before {\n  content: \"\\f303\"; }\n\n.fa-pencil-ruler:before {\n  content: \"\\f5ae\"; }\n\n.fa-penny-arcade:before {\n  content: \"\\f704\"; }\n\n.fa-people-carry:before {\n  content: \"\\f4ce\"; }\n\n.fa-pepper-hot:before {\n  content: \"\\f816\"; }\n\n.fa-percent:before {\n  content: \"\\f295\"; }\n\n.fa-percentage:before {\n  content: \"\\f541\"; }\n\n.fa-periscope:before {\n  content: \"\\f3da\"; }\n\n.fa-person-booth:before {\n  content: \"\\f756\"; }\n\n.fa-phabricator:before {\n  content: \"\\f3db\"; }\n\n.fa-phoenix-framework:before {\n  content: \"\\f3dc\"; }\n\n.fa-phoenix-squadron:before {\n  content: \"\\f511\"; }\n\n.fa-phone:before {\n  content: \"\\f095\"; }\n\n.fa-phone-alt:before {\n  content: \"\\f879\"; }\n\n.fa-phone-slash:before {\n  content: \"\\f3dd\"; }\n\n.fa-phone-square:before {\n  content: \"\\f098\"; }\n\n.fa-phone-square-alt:before {\n  content: \"\\f87b\"; }\n\n.fa-phone-volume:before {\n  content: \"\\f2a0\"; }\n\n.fa-photo-video:before {\n  content: \"\\f87c\"; }\n\n.fa-php:before {\n  content: \"\\f457\"; }\n\n.fa-pied-piper:before {\n  content: \"\\f2ae\"; }\n\n.fa-pied-piper-alt:before {\n  content: \"\\f1a8\"; }\n\n.fa-pied-piper-hat:before {\n  content: \"\\f4e5\"; }\n\n.fa-pied-piper-pp:before {\n  content: \"\\f1a7\"; }\n\n.fa-piggy-bank:before {\n  content: \"\\f4d3\"; }\n\n.fa-pills:before {\n  content: \"\\f484\"; }\n\n.fa-pinterest:before {\n  content: \"\\f0d2\"; }\n\n.fa-pinterest-p:before {\n  content: \"\\f231\"; }\n\n.fa-pinterest-square:before {\n  content: \"\\f0d3\"; }\n\n.fa-pizza-slice:before {\n  content: \"\\f818\"; }\n\n.fa-place-of-worship:before {\n  content: \"\\f67f\"; }\n\n.fa-plane:before {\n  content: \"\\f072\"; }\n\n.fa-plane-arrival:before {\n  content: \"\\f5af\"; }\n\n.fa-plane-departure:before {\n  content: \"\\f5b0\"; }\n\n.fa-play:before {\n  content: \"\\f04b\"; }\n\n.fa-play-circle:before {\n  content: \"\\f144\"; }\n\n.fa-playstation:before {\n  content: \"\\f3df\"; }\n\n.fa-plug:before {\n  content: \"\\f1e6\"; }\n\n.fa-plus:before {\n  content: \"\\f067\"; }\n\n.fa-plus-circle:before {\n  content: \"\\f055\"; }\n\n.fa-plus-square:before {\n  content: \"\\f0fe\"; }\n\n.fa-podcast:before {\n  content: \"\\f2ce\"; }\n\n.fa-poll:before {\n  content: \"\\f681\"; }\n\n.fa-poll-h:before {\n  content: \"\\f682\"; }\n\n.fa-poo:before {\n  content: \"\\f2fe\"; }\n\n.fa-poo-storm:before {\n  content: \"\\f75a\"; }\n\n.fa-poop:before {\n  content: \"\\f619\"; }\n\n.fa-portrait:before {\n  content: \"\\f3e0\"; }\n\n.fa-pound-sign:before {\n  content: \"\\f154\"; }\n\n.fa-power-off:before {\n  content: \"\\f011\"; }\n\n.fa-pray:before {\n  content: \"\\f683\"; }\n\n.fa-praying-hands:before {\n  content: \"\\f684\"; }\n\n.fa-prescription:before {\n  content: \"\\f5b1\"; }\n\n.fa-prescription-bottle:before {\n  content: \"\\f485\"; }\n\n.fa-prescription-bottle-alt:before {\n  content: \"\\f486\"; }\n\n.fa-print:before {\n  content: \"\\f02f\"; }\n\n.fa-procedures:before {\n  content: \"\\f487\"; }\n\n.fa-product-hunt:before {\n  content: \"\\f288\"; }\n\n.fa-project-diagram:before {\n  content: \"\\f542\"; }\n\n.fa-pushed:before {\n  content: \"\\f3e1\"; }\n\n.fa-puzzle-piece:before {\n  content: \"\\f12e\"; }\n\n.fa-python:before {\n  content: \"\\f3e2\"; }\n\n.fa-qq:before {\n  content: \"\\f1d6\"; }\n\n.fa-qrcode:before {\n  content: \"\\f029\"; }\n\n.fa-question:before {\n  content: \"\\f128\"; }\n\n.fa-question-circle:before {\n  content: \"\\f059\"; }\n\n.fa-quidditch:before {\n  content: \"\\f458\"; }\n\n.fa-quinscape:before {\n  content: \"\\f459\"; }\n\n.fa-quora:before {\n  content: \"\\f2c4\"; }\n\n.fa-quote-left:before {\n  content: \"\\f10d\"; }\n\n.fa-quote-right:before {\n  content: \"\\f10e\"; }\n\n.fa-quran:before {\n  content: \"\\f687\"; }\n\n.fa-r-project:before {\n  content: \"\\f4f7\"; }\n\n.fa-radiation:before {\n  content: \"\\f7b9\"; }\n\n.fa-radiation-alt:before {\n  content: \"\\f7ba\"; }\n\n.fa-rainbow:before {\n  content: \"\\f75b\"; }\n\n.fa-random:before {\n  content: \"\\f074\"; }\n\n.fa-raspberry-pi:before {\n  content: \"\\f7bb\"; }\n\n.fa-ravelry:before {\n  content: \"\\f2d9\"; }\n\n.fa-react:before {\n  content: \"\\f41b\"; }\n\n.fa-reacteurope:before {\n  content: \"\\f75d\"; }\n\n.fa-readme:before {\n  content: \"\\f4d5\"; }\n\n.fa-rebel:before {\n  content: \"\\f1d0\"; }\n\n.fa-receipt:before {\n  content: \"\\f543\"; }\n\n.fa-recycle:before {\n  content: \"\\f1b8\"; }\n\n.fa-red-river:before {\n  content: \"\\f3e3\"; }\n\n.fa-reddit:before {\n  content: \"\\f1a1\"; }\n\n.fa-reddit-alien:before {\n  content: \"\\f281\"; }\n\n.fa-reddit-square:before {\n  content: \"\\f1a2\"; }\n\n.fa-redhat:before {\n  content: \"\\f7bc\"; }\n\n.fa-redo:before {\n  content: \"\\f01e\"; }\n\n.fa-redo-alt:before {\n  content: \"\\f2f9\"; }\n\n.fa-registered:before {\n  content: \"\\f25d\"; }\n\n.fa-remove-format:before {\n  content: \"\\f87d\"; }\n\n.fa-renren:before {\n  content: \"\\f18b\"; }\n\n.fa-reply:before {\n  content: \"\\f3e5\"; }\n\n.fa-reply-all:before {\n  content: \"\\f122\"; }\n\n.fa-replyd:before {\n  content: \"\\f3e6\"; }\n\n.fa-republican:before {\n  content: \"\\f75e\"; }\n\n.fa-researchgate:before {\n  content: \"\\f4f8\"; }\n\n.fa-resolving:before {\n  content: \"\\f3e7\"; }\n\n.fa-restroom:before {\n  content: \"\\f7bd\"; }\n\n.fa-retweet:before {\n  content: \"\\f079\"; }\n\n.fa-rev:before {\n  content: \"\\f5b2\"; }\n\n.fa-ribbon:before {\n  content: \"\\f4d6\"; }\n\n.fa-ring:before {\n  content: \"\\f70b\"; }\n\n.fa-road:before {\n  content: \"\\f018\"; }\n\n.fa-robot:before {\n  content: \"\\f544\"; }\n\n.fa-rocket:before {\n  content: \"\\f135\"; }\n\n.fa-rocketchat:before {\n  content: \"\\f3e8\"; }\n\n.fa-rockrms:before {\n  content: \"\\f3e9\"; }\n\n.fa-route:before {\n  content: \"\\f4d7\"; }\n\n.fa-rss:before {\n  content: \"\\f09e\"; }\n\n.fa-rss-square:before {\n  content: \"\\f143\"; }\n\n.fa-ruble-sign:before {\n  content: \"\\f158\"; }\n\n.fa-ruler:before {\n  content: \"\\f545\"; }\n\n.fa-ruler-combined:before {\n  content: \"\\f546\"; }\n\n.fa-ruler-horizontal:before {\n  content: \"\\f547\"; }\n\n.fa-ruler-vertical:before {\n  content: \"\\f548\"; }\n\n.fa-running:before {\n  content: \"\\f70c\"; }\n\n.fa-rupee-sign:before {\n  content: \"\\f156\"; }\n\n.fa-sad-cry:before {\n  content: \"\\f5b3\"; }\n\n.fa-sad-tear:before {\n  content: \"\\f5b4\"; }\n\n.fa-safari:before {\n  content: \"\\f267\"; }\n\n.fa-salesforce:before {\n  content: \"\\f83b\"; }\n\n.fa-sass:before {\n  content: \"\\f41e\"; }\n\n.fa-satellite:before {\n  content: \"\\f7bf\"; }\n\n.fa-satellite-dish:before {\n  content: \"\\f7c0\"; }\n\n.fa-save:before {\n  content: \"\\f0c7\"; }\n\n.fa-schlix:before {\n  content: \"\\f3ea\"; }\n\n.fa-school:before {\n  content: \"\\f549\"; }\n\n.fa-screwdriver:before {\n  content: \"\\f54a\"; }\n\n.fa-scribd:before {\n  content: \"\\f28a\"; }\n\n.fa-scroll:before {\n  content: \"\\f70e\"; }\n\n.fa-sd-card:before {\n  content: \"\\f7c2\"; }\n\n.fa-search:before {\n  content: \"\\f002\"; }\n\n.fa-search-dollar:before {\n  content: \"\\f688\"; }\n\n.fa-search-location:before {\n  content: \"\\f689\"; }\n\n.fa-search-minus:before {\n  content: \"\\f010\"; }\n\n.fa-search-plus:before {\n  content: \"\\f00e\"; }\n\n.fa-searchengin:before {\n  content: \"\\f3eb\"; }\n\n.fa-seedling:before {\n  content: \"\\f4d8\"; }\n\n.fa-sellcast:before {\n  content: \"\\f2da\"; }\n\n.fa-sellsy:before {\n  content: \"\\f213\"; }\n\n.fa-server:before {\n  content: \"\\f233\"; }\n\n.fa-servicestack:before {\n  content: \"\\f3ec\"; }\n\n.fa-shapes:before {\n  content: \"\\f61f\"; }\n\n.fa-share:before {\n  content: \"\\f064\"; }\n\n.fa-share-alt:before {\n  content: \"\\f1e0\"; }\n\n.fa-share-alt-square:before {\n  content: \"\\f1e1\"; }\n\n.fa-share-square:before {\n  content: \"\\f14d\"; }\n\n.fa-shekel-sign:before {\n  content: \"\\f20b\"; }\n\n.fa-shield-alt:before {\n  content: \"\\f3ed\"; }\n\n.fa-ship:before {\n  content: \"\\f21a\"; }\n\n.fa-shipping-fast:before {\n  content: \"\\f48b\"; }\n\n.fa-shirtsinbulk:before {\n  content: \"\\f214\"; }\n\n.fa-shoe-prints:before {\n  content: \"\\f54b\"; }\n\n.fa-shopping-bag:before {\n  content: \"\\f290\"; }\n\n.fa-shopping-basket:before {\n  content: \"\\f291\"; }\n\n.fa-shopping-cart:before {\n  content: \"\\f07a\"; }\n\n.fa-shopware:before {\n  content: \"\\f5b5\"; }\n\n.fa-shower:before {\n  content: \"\\f2cc\"; }\n\n.fa-shuttle-van:before {\n  content: \"\\f5b6\"; }\n\n.fa-sign:before {\n  content: \"\\f4d9\"; }\n\n.fa-sign-in-alt:before {\n  content: \"\\f2f6\"; }\n\n.fa-sign-language:before {\n  content: \"\\f2a7\"; }\n\n.fa-sign-out-alt:before {\n  content: \"\\f2f5\"; }\n\n.fa-signal:before {\n  content: \"\\f012\"; }\n\n.fa-signature:before {\n  content: \"\\f5b7\"; }\n\n.fa-sim-card:before {\n  content: \"\\f7c4\"; }\n\n.fa-simplybuilt:before {\n  content: \"\\f215\"; }\n\n.fa-sistrix:before {\n  content: \"\\f3ee\"; }\n\n.fa-sitemap:before {\n  content: \"\\f0e8\"; }\n\n.fa-sith:before {\n  content: \"\\f512\"; }\n\n.fa-skating:before {\n  content: \"\\f7c5\"; }\n\n.fa-sketch:before {\n  content: \"\\f7c6\"; }\n\n.fa-skiing:before {\n  content: \"\\f7c9\"; }\n\n.fa-skiing-nordic:before {\n  content: \"\\f7ca\"; }\n\n.fa-skull:before {\n  content: \"\\f54c\"; }\n\n.fa-skull-crossbones:before {\n  content: \"\\f714\"; }\n\n.fa-skyatlas:before {\n  content: \"\\f216\"; }\n\n.fa-skype:before {\n  content: \"\\f17e\"; }\n\n.fa-slack:before {\n  content: \"\\f198\"; }\n\n.fa-slack-hash:before {\n  content: \"\\f3ef\"; }\n\n.fa-slash:before {\n  content: \"\\f715\"; }\n\n.fa-sleigh:before {\n  content: \"\\f7cc\"; }\n\n.fa-sliders-h:before {\n  content: \"\\f1de\"; }\n\n.fa-slideshare:before {\n  content: \"\\f1e7\"; }\n\n.fa-smile:before {\n  content: \"\\f118\"; }\n\n.fa-smile-beam:before {\n  content: \"\\f5b8\"; }\n\n.fa-smile-wink:before {\n  content: \"\\f4da\"; }\n\n.fa-smog:before {\n  content: \"\\f75f\"; }\n\n.fa-smoking:before {\n  content: \"\\f48d\"; }\n\n.fa-smoking-ban:before {\n  content: \"\\f54d\"; }\n\n.fa-sms:before {\n  content: \"\\f7cd\"; }\n\n.fa-snapchat:before {\n  content: \"\\f2ab\"; }\n\n.fa-snapchat-ghost:before {\n  content: \"\\f2ac\"; }\n\n.fa-snapchat-square:before {\n  content: \"\\f2ad\"; }\n\n.fa-snowboarding:before {\n  content: \"\\f7ce\"; }\n\n.fa-snowflake:before {\n  content: \"\\f2dc\"; }\n\n.fa-snowman:before {\n  content: \"\\f7d0\"; }\n\n.fa-snowplow:before {\n  content: \"\\f7d2\"; }\n\n.fa-socks:before {\n  content: \"\\f696\"; }\n\n.fa-solar-panel:before {\n  content: \"\\f5ba\"; }\n\n.fa-sort:before {\n  content: \"\\f0dc\"; }\n\n.fa-sort-alpha-down:before {\n  content: \"\\f15d\"; }\n\n.fa-sort-alpha-down-alt:before {\n  content: \"\\f881\"; }\n\n.fa-sort-alpha-up:before {\n  content: \"\\f15e\"; }\n\n.fa-sort-alpha-up-alt:before {\n  content: \"\\f882\"; }\n\n.fa-sort-amount-down:before {\n  content: \"\\f160\"; }\n\n.fa-sort-amount-down-alt:before {\n  content: \"\\f884\"; }\n\n.fa-sort-amount-up:before {\n  content: \"\\f161\"; }\n\n.fa-sort-amount-up-alt:before {\n  content: \"\\f885\"; }\n\n.fa-sort-down:before {\n  content: \"\\f0dd\"; }\n\n.fa-sort-numeric-down:before {\n  content: \"\\f162\"; }\n\n.fa-sort-numeric-down-alt:before {\n  content: \"\\f886\"; }\n\n.fa-sort-numeric-up:before {\n  content: \"\\f163\"; }\n\n.fa-sort-numeric-up-alt:before {\n  content: \"\\f887\"; }\n\n.fa-sort-up:before {\n  content: \"\\f0de\"; }\n\n.fa-soundcloud:before {\n  content: \"\\f1be\"; }\n\n.fa-sourcetree:before {\n  content: \"\\f7d3\"; }\n\n.fa-spa:before {\n  content: \"\\f5bb\"; }\n\n.fa-space-shuttle:before {\n  content: \"\\f197\"; }\n\n.fa-speakap:before {\n  content: \"\\f3f3\"; }\n\n.fa-speaker-deck:before {\n  content: \"\\f83c\"; }\n\n.fa-spell-check:before {\n  content: \"\\f891\"; }\n\n.fa-spider:before {\n  content: \"\\f717\"; }\n\n.fa-spinner:before {\n  content: \"\\f110\"; }\n\n.fa-splotch:before {\n  content: \"\\f5bc\"; }\n\n.fa-spotify:before {\n  content: \"\\f1bc\"; }\n\n.fa-spray-can:before {\n  content: \"\\f5bd\"; }\n\n.fa-square:before {\n  content: \"\\f0c8\"; }\n\n.fa-square-full:before {\n  content: \"\\f45c\"; }\n\n.fa-square-root-alt:before {\n  content: \"\\f698\"; }\n\n.fa-squarespace:before {\n  content: \"\\f5be\"; }\n\n.fa-stack-exchange:before {\n  content: \"\\f18d\"; }\n\n.fa-stack-overflow:before {\n  content: \"\\f16c\"; }\n\n.fa-stackpath:before {\n  content: \"\\f842\"; }\n\n.fa-stamp:before {\n  content: \"\\f5bf\"; }\n\n.fa-star:before {\n  content: \"\\f005\"; }\n\n.fa-star-and-crescent:before {\n  content: \"\\f699\"; }\n\n.fa-star-half:before {\n  content: \"\\f089\"; }\n\n.fa-star-half-alt:before {\n  content: \"\\f5c0\"; }\n\n.fa-star-of-david:before {\n  content: \"\\f69a\"; }\n\n.fa-star-of-life:before {\n  content: \"\\f621\"; }\n\n.fa-staylinked:before {\n  content: \"\\f3f5\"; }\n\n.fa-steam:before {\n  content: \"\\f1b6\"; }\n\n.fa-steam-square:before {\n  content: \"\\f1b7\"; }\n\n.fa-steam-symbol:before {\n  content: \"\\f3f6\"; }\n\n.fa-step-backward:before {\n  content: \"\\f048\"; }\n\n.fa-step-forward:before {\n  content: \"\\f051\"; }\n\n.fa-stethoscope:before {\n  content: \"\\f0f1\"; }\n\n.fa-sticker-mule:before {\n  content: \"\\f3f7\"; }\n\n.fa-sticky-note:before {\n  content: \"\\f249\"; }\n\n.fa-stop:before {\n  content: \"\\f04d\"; }\n\n.fa-stop-circle:before {\n  content: \"\\f28d\"; }\n\n.fa-stopwatch:before {\n  content: \"\\f2f2\"; }\n\n.fa-store:before {\n  content: \"\\f54e\"; }\n\n.fa-store-alt:before {\n  content: \"\\f54f\"; }\n\n.fa-strava:before {\n  content: \"\\f428\"; }\n\n.fa-stream:before {\n  content: \"\\f550\"; }\n\n.fa-street-view:before {\n  content: \"\\f21d\"; }\n\n.fa-strikethrough:before {\n  content: \"\\f0cc\"; }\n\n.fa-stripe:before {\n  content: \"\\f429\"; }\n\n.fa-stripe-s:before {\n  content: \"\\f42a\"; }\n\n.fa-stroopwafel:before {\n  content: \"\\f551\"; }\n\n.fa-studiovinari:before {\n  content: \"\\f3f8\"; }\n\n.fa-stumbleupon:before {\n  content: \"\\f1a4\"; }\n\n.fa-stumbleupon-circle:before {\n  content: \"\\f1a3\"; }\n\n.fa-subscript:before {\n  content: \"\\f12c\"; }\n\n.fa-subway:before {\n  content: \"\\f239\"; }\n\n.fa-suitcase:before {\n  content: \"\\f0f2\"; }\n\n.fa-suitcase-rolling:before {\n  content: \"\\f5c1\"; }\n\n.fa-sun:before {\n  content: \"\\f185\"; }\n\n.fa-superpowers:before {\n  content: \"\\f2dd\"; }\n\n.fa-superscript:before {\n  content: \"\\f12b\"; }\n\n.fa-supple:before {\n  content: \"\\f3f9\"; }\n\n.fa-surprise:before {\n  content: \"\\f5c2\"; }\n\n.fa-suse:before {\n  content: \"\\f7d6\"; }\n\n.fa-swatchbook:before {\n  content: \"\\f5c3\"; }\n\n.fa-swimmer:before {\n  content: \"\\f5c4\"; }\n\n.fa-swimming-pool:before {\n  content: \"\\f5c5\"; }\n\n.fa-symfony:before {\n  content: \"\\f83d\"; }\n\n.fa-synagogue:before {\n  content: \"\\f69b\"; }\n\n.fa-sync:before {\n  content: \"\\f021\"; }\n\n.fa-sync-alt:before {\n  content: \"\\f2f1\"; }\n\n.fa-syringe:before {\n  content: \"\\f48e\"; }\n\n.fa-table:before {\n  content: \"\\f0ce\"; }\n\n.fa-table-tennis:before {\n  content: \"\\f45d\"; }\n\n.fa-tablet:before {\n  content: \"\\f10a\"; }\n\n.fa-tablet-alt:before {\n  content: \"\\f3fa\"; }\n\n.fa-tablets:before {\n  content: \"\\f490\"; }\n\n.fa-tachometer-alt:before {\n  content: \"\\f3fd\"; }\n\n.fa-tag:before {\n  content: \"\\f02b\"; }\n\n.fa-tags:before {\n  content: \"\\f02c\"; }\n\n.fa-tape:before {\n  content: \"\\f4db\"; }\n\n.fa-tasks:before {\n  content: \"\\f0ae\"; }\n\n.fa-taxi:before {\n  content: \"\\f1ba\"; }\n\n.fa-teamspeak:before {\n  content: \"\\f4f9\"; }\n\n.fa-teeth:before {\n  content: \"\\f62e\"; }\n\n.fa-teeth-open:before {\n  content: \"\\f62f\"; }\n\n.fa-telegram:before {\n  content: \"\\f2c6\"; }\n\n.fa-telegram-plane:before {\n  content: \"\\f3fe\"; }\n\n.fa-temperature-high:before {\n  content: \"\\f769\"; }\n\n.fa-temperature-low:before {\n  content: \"\\f76b\"; }\n\n.fa-tencent-weibo:before {\n  content: \"\\f1d5\"; }\n\n.fa-tenge:before {\n  content: \"\\f7d7\"; }\n\n.fa-terminal:before {\n  content: \"\\f120\"; }\n\n.fa-text-height:before {\n  content: \"\\f034\"; }\n\n.fa-text-width:before {\n  content: \"\\f035\"; }\n\n.fa-th:before {\n  content: \"\\f00a\"; }\n\n.fa-th-large:before {\n  content: \"\\f009\"; }\n\n.fa-th-list:before {\n  content: \"\\f00b\"; }\n\n.fa-the-red-yeti:before {\n  content: \"\\f69d\"; }\n\n.fa-theater-masks:before {\n  content: \"\\f630\"; }\n\n.fa-themeco:before {\n  content: \"\\f5c6\"; }\n\n.fa-themeisle:before {\n  content: \"\\f2b2\"; }\n\n.fa-thermometer:before {\n  content: \"\\f491\"; }\n\n.fa-thermometer-empty:before {\n  content: \"\\f2cb\"; }\n\n.fa-thermometer-full:before {\n  content: \"\\f2c7\"; }\n\n.fa-thermometer-half:before {\n  content: \"\\f2c9\"; }\n\n.fa-thermometer-quarter:before {\n  content: \"\\f2ca\"; }\n\n.fa-thermometer-three-quarters:before {\n  content: \"\\f2c8\"; }\n\n.fa-think-peaks:before {\n  content: \"\\f731\"; }\n\n.fa-thumbs-down:before {\n  content: \"\\f165\"; }\n\n.fa-thumbs-up:before {\n  content: \"\\f164\"; }\n\n.fa-thumbtack:before {\n  content: \"\\f08d\"; }\n\n.fa-ticket-alt:before {\n  content: \"\\f3ff\"; }\n\n.fa-times:before {\n  content: \"\\f00d\"; }\n\n.fa-times-circle:before {\n  content: \"\\f057\"; }\n\n.fa-tint:before {\n  content: \"\\f043\"; }\n\n.fa-tint-slash:before {\n  content: \"\\f5c7\"; }\n\n.fa-tired:before {\n  content: \"\\f5c8\"; }\n\n.fa-toggle-off:before {\n  content: \"\\f204\"; }\n\n.fa-toggle-on:before {\n  content: \"\\f205\"; }\n\n.fa-toilet:before {\n  content: \"\\f7d8\"; }\n\n.fa-toilet-paper:before {\n  content: \"\\f71e\"; }\n\n.fa-toolbox:before {\n  content: \"\\f552\"; }\n\n.fa-tools:before {\n  content: \"\\f7d9\"; }\n\n.fa-tooth:before {\n  content: \"\\f5c9\"; }\n\n.fa-torah:before {\n  content: \"\\f6a0\"; }\n\n.fa-torii-gate:before {\n  content: \"\\f6a1\"; }\n\n.fa-tractor:before {\n  content: \"\\f722\"; }\n\n.fa-trade-federation:before {\n  content: \"\\f513\"; }\n\n.fa-trademark:before {\n  content: \"\\f25c\"; }\n\n.fa-traffic-light:before {\n  content: \"\\f637\"; }\n\n.fa-train:before {\n  content: \"\\f238\"; }\n\n.fa-tram:before {\n  content: \"\\f7da\"; }\n\n.fa-transgender:before {\n  content: \"\\f224\"; }\n\n.fa-transgender-alt:before {\n  content: \"\\f225\"; }\n\n.fa-trash:before {\n  content: \"\\f1f8\"; }\n\n.fa-trash-alt:before {\n  content: \"\\f2ed\"; }\n\n.fa-trash-restore:before {\n  content: \"\\f829\"; }\n\n.fa-trash-restore-alt:before {\n  content: \"\\f82a\"; }\n\n.fa-tree:before {\n  content: \"\\f1bb\"; }\n\n.fa-trello:before {\n  content: \"\\f181\"; }\n\n.fa-tripadvisor:before {\n  content: \"\\f262\"; }\n\n.fa-trophy:before {\n  content: \"\\f091\"; }\n\n.fa-truck:before {\n  content: \"\\f0d1\"; }\n\n.fa-truck-loading:before {\n  content: \"\\f4de\"; }\n\n.fa-truck-monster:before {\n  content: \"\\f63b\"; }\n\n.fa-truck-moving:before {\n  content: \"\\f4df\"; }\n\n.fa-truck-pickup:before {\n  content: \"\\f63c\"; }\n\n.fa-tshirt:before {\n  content: \"\\f553\"; }\n\n.fa-tty:before {\n  content: \"\\f1e4\"; }\n\n.fa-tumblr:before {\n  content: \"\\f173\"; }\n\n.fa-tumblr-square:before {\n  content: \"\\f174\"; }\n\n.fa-tv:before {\n  content: \"\\f26c\"; }\n\n.fa-twitch:before {\n  content: \"\\f1e8\"; }\n\n.fa-twitter:before {\n  content: \"\\f099\"; }\n\n.fa-twitter-square:before {\n  content: \"\\f081\"; }\n\n.fa-typo3:before {\n  content: \"\\f42b\"; }\n\n.fa-uber:before {\n  content: \"\\f402\"; }\n\n.fa-ubuntu:before {\n  content: \"\\f7df\"; }\n\n.fa-uikit:before {\n  content: \"\\f403\"; }\n\n.fa-umbrella:before {\n  content: \"\\f0e9\"; }\n\n.fa-umbrella-beach:before {\n  content: \"\\f5ca\"; }\n\n.fa-underline:before {\n  content: \"\\f0cd\"; }\n\n.fa-undo:before {\n  content: \"\\f0e2\"; }\n\n.fa-undo-alt:before {\n  content: \"\\f2ea\"; }\n\n.fa-uniregistry:before {\n  content: \"\\f404\"; }\n\n.fa-universal-access:before {\n  content: \"\\f29a\"; }\n\n.fa-university:before {\n  content: \"\\f19c\"; }\n\n.fa-unlink:before {\n  content: \"\\f127\"; }\n\n.fa-unlock:before {\n  content: \"\\f09c\"; }\n\n.fa-unlock-alt:before {\n  content: \"\\f13e\"; }\n\n.fa-untappd:before {\n  content: \"\\f405\"; }\n\n.fa-upload:before {\n  content: \"\\f093\"; }\n\n.fa-ups:before {\n  content: \"\\f7e0\"; }\n\n.fa-usb:before {\n  content: \"\\f287\"; }\n\n.fa-user:before {\n  content: \"\\f007\"; }\n\n.fa-user-alt:before {\n  content: \"\\f406\"; }\n\n.fa-user-alt-slash:before {\n  content: \"\\f4fa\"; }\n\n.fa-user-astronaut:before {\n  content: \"\\f4fb\"; }\n\n.fa-user-check:before {\n  content: \"\\f4fc\"; }\n\n.fa-user-circle:before {\n  content: \"\\f2bd\"; }\n\n.fa-user-clock:before {\n  content: \"\\f4fd\"; }\n\n.fa-user-cog:before {\n  content: \"\\f4fe\"; }\n\n.fa-user-edit:before {\n  content: \"\\f4ff\"; }\n\n.fa-user-friends:before {\n  content: \"\\f500\"; }\n\n.fa-user-graduate:before {\n  content: \"\\f501\"; }\n\n.fa-user-injured:before {\n  content: \"\\f728\"; }\n\n.fa-user-lock:before {\n  content: \"\\f502\"; }\n\n.fa-user-md:before {\n  content: \"\\f0f0\"; }\n\n.fa-user-minus:before {\n  content: \"\\f503\"; }\n\n.fa-user-ninja:before {\n  content: \"\\f504\"; }\n\n.fa-user-nurse:before {\n  content: \"\\f82f\"; }\n\n.fa-user-plus:before {\n  content: \"\\f234\"; }\n\n.fa-user-secret:before {\n  content: \"\\f21b\"; }\n\n.fa-user-shield:before {\n  content: \"\\f505\"; }\n\n.fa-user-slash:before {\n  content: \"\\f506\"; }\n\n.fa-user-tag:before {\n  content: \"\\f507\"; }\n\n.fa-user-tie:before {\n  content: \"\\f508\"; }\n\n.fa-user-times:before {\n  content: \"\\f235\"; }\n\n.fa-users:before {\n  content: \"\\f0c0\"; }\n\n.fa-users-cog:before {\n  content: \"\\f509\"; }\n\n.fa-usps:before {\n  content: \"\\f7e1\"; }\n\n.fa-ussunnah:before {\n  content: \"\\f407\"; }\n\n.fa-utensil-spoon:before {\n  content: \"\\f2e5\"; }\n\n.fa-utensils:before {\n  content: \"\\f2e7\"; }\n\n.fa-vaadin:before {\n  content: \"\\f408\"; }\n\n.fa-vector-square:before {\n  content: \"\\f5cb\"; }\n\n.fa-venus:before {\n  content: \"\\f221\"; }\n\n.fa-venus-double:before {\n  content: \"\\f226\"; }\n\n.fa-venus-mars:before {\n  content: \"\\f228\"; }\n\n.fa-viacoin:before {\n  content: \"\\f237\"; }\n\n.fa-viadeo:before {\n  content: \"\\f2a9\"; }\n\n.fa-viadeo-square:before {\n  content: \"\\f2aa\"; }\n\n.fa-vial:before {\n  content: \"\\f492\"; }\n\n.fa-vials:before {\n  content: \"\\f493\"; }\n\n.fa-viber:before {\n  content: \"\\f409\"; }\n\n.fa-video:before {\n  content: \"\\f03d\"; }\n\n.fa-video-slash:before {\n  content: \"\\f4e2\"; }\n\n.fa-vihara:before {\n  content: \"\\f6a7\"; }\n\n.fa-vimeo:before {\n  content: \"\\f40a\"; }\n\n.fa-vimeo-square:before {\n  content: \"\\f194\"; }\n\n.fa-vimeo-v:before {\n  content: \"\\f27d\"; }\n\n.fa-vine:before {\n  content: \"\\f1ca\"; }\n\n.fa-vk:before {\n  content: \"\\f189\"; }\n\n.fa-vnv:before {\n  content: \"\\f40b\"; }\n\n.fa-voicemail:before {\n  content: \"\\f897\"; }\n\n.fa-volleyball-ball:before {\n  content: \"\\f45f\"; }\n\n.fa-volume-down:before {\n  content: \"\\f027\"; }\n\n.fa-volume-mute:before {\n  content: \"\\f6a9\"; }\n\n.fa-volume-off:before {\n  content: \"\\f026\"; }\n\n.fa-volume-up:before {\n  content: \"\\f028\"; }\n\n.fa-vote-yea:before {\n  content: \"\\f772\"; }\n\n.fa-vr-cardboard:before {\n  content: \"\\f729\"; }\n\n.fa-vuejs:before {\n  content: \"\\f41f\"; }\n\n.fa-walking:before {\n  content: \"\\f554\"; }\n\n.fa-wallet:before {\n  content: \"\\f555\"; }\n\n.fa-warehouse:before {\n  content: \"\\f494\"; }\n\n.fa-water:before {\n  content: \"\\f773\"; }\n\n.fa-wave-square:before {\n  content: \"\\f83e\"; }\n\n.fa-waze:before {\n  content: \"\\f83f\"; }\n\n.fa-weebly:before {\n  content: \"\\f5cc\"; }\n\n.fa-weibo:before {\n  content: \"\\f18a\"; }\n\n.fa-weight:before {\n  content: \"\\f496\"; }\n\n.fa-weight-hanging:before {\n  content: \"\\f5cd\"; }\n\n.fa-weixin:before {\n  content: \"\\f1d7\"; }\n\n.fa-whatsapp:before {\n  content: \"\\f232\"; }\n\n.fa-whatsapp-square:before {\n  content: \"\\f40c\"; }\n\n.fa-wheelchair:before {\n  content: \"\\f193\"; }\n\n.fa-whmcs:before {\n  content: \"\\f40d\"; }\n\n.fa-wifi:before {\n  content: \"\\f1eb\"; }\n\n.fa-wikipedia-w:before {\n  content: \"\\f266\"; }\n\n.fa-wind:before {\n  content: \"\\f72e\"; }\n\n.fa-window-close:before {\n  content: \"\\f410\"; }\n\n.fa-window-maximize:before {\n  content: \"\\f2d0\"; }\n\n.fa-window-minimize:before {\n  content: \"\\f2d1\"; }\n\n.fa-window-restore:before {\n  content: \"\\f2d2\"; }\n\n.fa-windows:before {\n  content: \"\\f17a\"; }\n\n.fa-wine-bottle:before {\n  content: \"\\f72f\"; }\n\n.fa-wine-glass:before {\n  content: \"\\f4e3\"; }\n\n.fa-wine-glass-alt:before {\n  content: \"\\f5ce\"; }\n\n.fa-wix:before {\n  content: \"\\f5cf\"; }\n\n.fa-wizards-of-the-coast:before {\n  content: \"\\f730\"; }\n\n.fa-wolf-pack-battalion:before {\n  content: \"\\f514\"; }\n\n.fa-won-sign:before {\n  content: \"\\f159\"; }\n\n.fa-wordpress:before {\n  content: \"\\f19a\"; }\n\n.fa-wordpress-simple:before {\n  content: \"\\f411\"; }\n\n.fa-wpbeginner:before {\n  content: \"\\f297\"; }\n\n.fa-wpexplorer:before {\n  content: \"\\f2de\"; }\n\n.fa-wpforms:before {\n  content: \"\\f298\"; }\n\n.fa-wpressr:before {\n  content: \"\\f3e4\"; }\n\n.fa-wrench:before {\n  content: \"\\f0ad\"; }\n\n.fa-x-ray:before {\n  content: \"\\f497\"; }\n\n.fa-xbox:before {\n  content: \"\\f412\"; }\n\n.fa-xing:before {\n  content: \"\\f168\"; }\n\n.fa-xing-square:before {\n  content: \"\\f169\"; }\n\n.fa-y-combinator:before {\n  content: \"\\f23b\"; }\n\n.fa-yahoo:before {\n  content: \"\\f19e\"; }\n\n.fa-yammer:before {\n  content: \"\\f840\"; }\n\n.fa-yandex:before {\n  content: \"\\f413\"; }\n\n.fa-yandex-international:before {\n  content: \"\\f414\"; }\n\n.fa-yarn:before {\n  content: \"\\f7e3\"; }\n\n.fa-yelp:before {\n  content: \"\\f1e9\"; }\n\n.fa-yen-sign:before {\n  content: \"\\f157\"; }\n\n.fa-yin-yang:before {\n  content: \"\\f6ad\"; }\n\n.fa-yoast:before {\n  content: \"\\f2b1\"; }\n\n.fa-youtube:before {\n  content: \"\\f167\"; }\n\n.fa-youtube-square:before {\n  content: \"\\f431\"; }\n\n.fa-zhihu:before {\n  content: \"\\f63f\"; }\n\n.sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px; }\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  clip: auto;\n  height: auto;\n  margin: 0;\n  overflow: visible;\n  position: static;\n  width: auto; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/regular.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: auto;\n  src: url(\"../webfonts/fa-regular-400.eot\");\n  src: url(\"../webfonts/fa-regular-400.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-regular-400.woff2\") format(\"woff2\"), url(\"../webfonts/fa-regular-400.woff\") format(\"woff\"), url(\"../webfonts/fa-regular-400.ttf\") format(\"truetype\"), url(\"../webfonts/fa-regular-400.svg#fontawesome\") format(\"svg\"); }\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/solid.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: auto;\n  src: url(\"../webfonts/fa-solid-900.eot\");\n  src: url(\"../webfonts/fa-solid-900.eot?#iefix\") format(\"embedded-opentype\"), url(\"../webfonts/fa-solid-900.woff2\") format(\"woff2\"), url(\"../webfonts/fa-solid-900.woff\") format(\"woff\"), url(\"../webfonts/fa-solid-900.ttf\") format(\"truetype\"), url(\"../webfonts/fa-solid-900.svg#fontawesome\") format(\"svg\"); }\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/svg-with-js.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\nsvg:not(:root).svg-inline--fa {\n  overflow: visible; }\n\n.svg-inline--fa {\n  display: inline-block;\n  font-size: inherit;\n  height: 1em;\n  overflow: visible;\n  vertical-align: -.125em; }\n  .svg-inline--fa.fa-lg {\n    vertical-align: -.225em; }\n  .svg-inline--fa.fa-w-1 {\n    width: 0.0625em; }\n  .svg-inline--fa.fa-w-2 {\n    width: 0.125em; }\n  .svg-inline--fa.fa-w-3 {\n    width: 0.1875em; }\n  .svg-inline--fa.fa-w-4 {\n    width: 0.25em; }\n  .svg-inline--fa.fa-w-5 {\n    width: 0.3125em; }\n  .svg-inline--fa.fa-w-6 {\n    width: 0.375em; }\n  .svg-inline--fa.fa-w-7 {\n    width: 0.4375em; }\n  .svg-inline--fa.fa-w-8 {\n    width: 0.5em; }\n  .svg-inline--fa.fa-w-9 {\n    width: 0.5625em; }\n  .svg-inline--fa.fa-w-10 {\n    width: 0.625em; }\n  .svg-inline--fa.fa-w-11 {\n    width: 0.6875em; }\n  .svg-inline--fa.fa-w-12 {\n    width: 0.75em; }\n  .svg-inline--fa.fa-w-13 {\n    width: 0.8125em; }\n  .svg-inline--fa.fa-w-14 {\n    width: 0.875em; }\n  .svg-inline--fa.fa-w-15 {\n    width: 0.9375em; }\n  .svg-inline--fa.fa-w-16 {\n    width: 1em; }\n  .svg-inline--fa.fa-w-17 {\n    width: 1.0625em; }\n  .svg-inline--fa.fa-w-18 {\n    width: 1.125em; }\n  .svg-inline--fa.fa-w-19 {\n    width: 1.1875em; }\n  .svg-inline--fa.fa-w-20 {\n    width: 1.25em; }\n  .svg-inline--fa.fa-pull-left {\n    margin-right: .3em;\n    width: auto; }\n  .svg-inline--fa.fa-pull-right {\n    margin-left: .3em;\n    width: auto; }\n  .svg-inline--fa.fa-border {\n    height: 1.5em; }\n  .svg-inline--fa.fa-li {\n    width: 2em; }\n  .svg-inline--fa.fa-fw {\n    width: 1.25em; }\n\n.fa-layers svg.svg-inline--fa {\n  bottom: 0;\n  left: 0;\n  margin: auto;\n  position: absolute;\n  right: 0;\n  top: 0; }\n\n.fa-layers {\n  display: inline-block;\n  height: 1em;\n  position: relative;\n  text-align: center;\n  vertical-align: -.125em;\n  width: 1em; }\n  .fa-layers svg.svg-inline--fa {\n    -webkit-transform-origin: center center;\n            transform-origin: center center; }\n\n.fa-layers-text, .fa-layers-counter {\n  display: inline-block;\n  position: absolute;\n  text-align: center; }\n\n.fa-layers-text {\n  left: 50%;\n  top: 50%;\n  -webkit-transform: translate(-50%, -50%);\n          transform: translate(-50%, -50%);\n  -webkit-transform-origin: center center;\n          transform-origin: center center; }\n\n.fa-layers-counter {\n  background-color: #ff253a;\n  border-radius: 1em;\n  -webkit-box-sizing: border-box;\n          box-sizing: border-box;\n  color: #fff;\n  height: 1.5em;\n  line-height: 1;\n  max-width: 5em;\n  min-width: 1.5em;\n  overflow: hidden;\n  padding: .25em;\n  right: 0;\n  text-overflow: ellipsis;\n  top: 0;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: top right;\n          transform-origin: top right; }\n\n.fa-layers-bottom-right {\n  bottom: 0;\n  right: 0;\n  top: auto;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: bottom right;\n          transform-origin: bottom right; }\n\n.fa-layers-bottom-left {\n  bottom: 0;\n  left: 0;\n  right: auto;\n  top: auto;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: bottom left;\n          transform-origin: bottom left; }\n\n.fa-layers-top-right {\n  right: 0;\n  top: 0;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: top right;\n          transform-origin: top right; }\n\n.fa-layers-top-left {\n  left: 0;\n  right: auto;\n  top: 0;\n  -webkit-transform: scale(0.25);\n          transform: scale(0.25);\n  -webkit-transform-origin: top left;\n          transform-origin: top left; }\n\n.fa-lg {\n  font-size: 1.33333em;\n  line-height: 0.75em;\n  vertical-align: -.0667em; }\n\n.fa-xs {\n  font-size: .75em; }\n\n.fa-sm {\n  font-size: .875em; }\n\n.fa-1x {\n  font-size: 1em; }\n\n.fa-2x {\n  font-size: 2em; }\n\n.fa-3x {\n  font-size: 3em; }\n\n.fa-4x {\n  font-size: 4em; }\n\n.fa-5x {\n  font-size: 5em; }\n\n.fa-6x {\n  font-size: 6em; }\n\n.fa-7x {\n  font-size: 7em; }\n\n.fa-8x {\n  font-size: 8em; }\n\n.fa-9x {\n  font-size: 9em; }\n\n.fa-10x {\n  font-size: 10em; }\n\n.fa-fw {\n  text-align: center;\n  width: 1.25em; }\n\n.fa-ul {\n  list-style-type: none;\n  margin-left: 2.5em;\n  padding-left: 0; }\n  .fa-ul > li {\n    position: relative; }\n\n.fa-li {\n  left: -2em;\n  position: absolute;\n  text-align: center;\n  width: 2em;\n  line-height: inherit; }\n\n.fa-border {\n  border: solid 0.08em #eee;\n  border-radius: .1em;\n  padding: .2em .25em .15em; }\n\n.fa-pull-left {\n  float: left; }\n\n.fa-pull-right {\n  float: right; }\n\n.fa.fa-pull-left,\n.fas.fa-pull-left,\n.far.fa-pull-left,\n.fal.fa-pull-left,\n.fab.fa-pull-left {\n  margin-right: .3em; }\n\n.fa.fa-pull-right,\n.fas.fa-pull-right,\n.far.fa-pull-right,\n.fal.fa-pull-right,\n.fab.fa-pull-right {\n  margin-left: .3em; }\n\n.fa-spin {\n  -webkit-animation: fa-spin 2s infinite linear;\n          animation: fa-spin 2s infinite linear; }\n\n.fa-pulse {\n  -webkit-animation: fa-spin 1s infinite steps(8);\n          animation: fa-spin 1s infinite steps(8); }\n\n@-webkit-keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n@keyframes fa-spin {\n  0% {\n    -webkit-transform: rotate(0deg);\n            transform: rotate(0deg); }\n  100% {\n    -webkit-transform: rotate(360deg);\n            transform: rotate(360deg); } }\n\n.fa-rotate-90 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)\";\n  -webkit-transform: rotate(90deg);\n          transform: rotate(90deg); }\n\n.fa-rotate-180 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)\";\n  -webkit-transform: rotate(180deg);\n          transform: rotate(180deg); }\n\n.fa-rotate-270 {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)\";\n  -webkit-transform: rotate(270deg);\n          transform: rotate(270deg); }\n\n.fa-flip-horizontal {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)\";\n  -webkit-transform: scale(-1, 1);\n          transform: scale(-1, 1); }\n\n.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(1, -1);\n          transform: scale(1, -1); }\n\n.fa-flip-both, .fa-flip-horizontal.fa-flip-vertical {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)\";\n  -webkit-transform: scale(-1, -1);\n          transform: scale(-1, -1); }\n\n:root .fa-rotate-90,\n:root .fa-rotate-180,\n:root .fa-rotate-270,\n:root .fa-flip-horizontal,\n:root .fa-flip-vertical,\n:root .fa-flip-both {\n  -webkit-filter: none;\n          filter: none; }\n\n.fa-stack {\n  display: inline-block;\n  height: 2em;\n  position: relative;\n  width: 2.5em; }\n\n.fa-stack-1x,\n.fa-stack-2x {\n  bottom: 0;\n  left: 0;\n  margin: auto;\n  position: absolute;\n  right: 0;\n  top: 0; }\n\n.svg-inline--fa.fa-stack-1x {\n  height: 1em;\n  width: 1.25em; }\n\n.svg-inline--fa.fa-stack-2x {\n  height: 2em;\n  width: 2.5em; }\n\n.fa-inverse {\n  color: #fff; }\n\n.sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px; }\n\n.sr-only-focusable:active, .sr-only-focusable:focus {\n  clip: auto;\n  height: auto;\n  margin: 0;\n  overflow: visible;\n  position: static;\n  width: auto; }\n\n.svg-inline--fa .fa-primary {\n  fill: var(--fa-primary-color, currentColor);\n  opacity: 1;\n  opacity: var(--fa-primary-opacity, 1); }\n\n.svg-inline--fa .fa-secondary {\n  fill: var(--fa-secondary-color, currentColor);\n  opacity: 0.4;\n  opacity: var(--fa-secondary-opacity, 0.4); }\n\n.svg-inline--fa.fa-swap-opacity .fa-primary {\n  opacity: 0.4;\n  opacity: var(--fa-secondary-opacity, 0.4); }\n\n.svg-inline--fa.fa-swap-opacity .fa-secondary {\n  opacity: 1;\n  opacity: var(--fa-primary-opacity, 1); }\n\n.svg-inline--fa mask .fa-primary,\n.svg-inline--fa mask .fa-secondary {\n  fill: black; }\n\n.fad.fa-inverse {\n  color: #fff; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/css/v4-shims.css",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n.fa.fa-glass:before {\n  content: \"\\f000\"; }\n\n.fa.fa-meetup {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-star-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-o:before {\n  content: \"\\f005\"; }\n\n.fa.fa-remove:before {\n  content: \"\\f00d\"; }\n\n.fa.fa-close:before {\n  content: \"\\f00d\"; }\n\n.fa.fa-gear:before {\n  content: \"\\f013\"; }\n\n.fa.fa-trash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-trash-o:before {\n  content: \"\\f2ed\"; }\n\n.fa.fa-file-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-o:before {\n  content: \"\\f15b\"; }\n\n.fa.fa-clock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-clock-o:before {\n  content: \"\\f017\"; }\n\n.fa.fa-arrow-circle-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-down:before {\n  content: \"\\f358\"; }\n\n.fa.fa-arrow-circle-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-up:before {\n  content: \"\\f35b\"; }\n\n.fa.fa-play-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-play-circle-o:before {\n  content: \"\\f144\"; }\n\n.fa.fa-repeat:before {\n  content: \"\\f01e\"; }\n\n.fa.fa-rotate-right:before {\n  content: \"\\f01e\"; }\n\n.fa.fa-refresh:before {\n  content: \"\\f021\"; }\n\n.fa.fa-list-alt {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-dedent:before {\n  content: \"\\f03b\"; }\n\n.fa.fa-video-camera:before {\n  content: \"\\f03d\"; }\n\n.fa.fa-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-picture-o:before {\n  content: \"\\f03e\"; }\n\n.fa.fa-photo {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-photo:before {\n  content: \"\\f03e\"; }\n\n.fa.fa-image {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-image:before {\n  content: \"\\f03e\"; }\n\n.fa.fa-pencil:before {\n  content: \"\\f303\"; }\n\n.fa.fa-map-marker:before {\n  content: \"\\f3c5\"; }\n\n.fa.fa-pencil-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-pencil-square-o:before {\n  content: \"\\f044\"; }\n\n.fa.fa-share-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-share-square-o:before {\n  content: \"\\f14d\"; }\n\n.fa.fa-check-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-check-square-o:before {\n  content: \"\\f14a\"; }\n\n.fa.fa-arrows:before {\n  content: \"\\f0b2\"; }\n\n.fa.fa-times-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-times-circle-o:before {\n  content: \"\\f057\"; }\n\n.fa.fa-check-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-check-circle-o:before {\n  content: \"\\f058\"; }\n\n.fa.fa-mail-forward:before {\n  content: \"\\f064\"; }\n\n.fa.fa-eye {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-eye-slash {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-warning:before {\n  content: \"\\f071\"; }\n\n.fa.fa-calendar:before {\n  content: \"\\f073\"; }\n\n.fa.fa-arrows-v:before {\n  content: \"\\f338\"; }\n\n.fa.fa-arrows-h:before {\n  content: \"\\f337\"; }\n\n.fa.fa-bar-chart {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bar-chart:before {\n  content: \"\\f080\"; }\n\n.fa.fa-bar-chart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bar-chart-o:before {\n  content: \"\\f080\"; }\n\n.fa.fa-twitter-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gears:before {\n  content: \"\\f085\"; }\n\n.fa.fa-thumbs-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-thumbs-o-up:before {\n  content: \"\\f164\"; }\n\n.fa.fa-thumbs-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-thumbs-o-down:before {\n  content: \"\\f165\"; }\n\n.fa.fa-heart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-heart-o:before {\n  content: \"\\f004\"; }\n\n.fa.fa-sign-out:before {\n  content: \"\\f2f5\"; }\n\n.fa.fa-linkedin-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-linkedin-square:before {\n  content: \"\\f08c\"; }\n\n.fa.fa-thumb-tack:before {\n  content: \"\\f08d\"; }\n\n.fa.fa-external-link:before {\n  content: \"\\f35d\"; }\n\n.fa.fa-sign-in:before {\n  content: \"\\f2f6\"; }\n\n.fa.fa-github-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-lemon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-lemon-o:before {\n  content: \"\\f094\"; }\n\n.fa.fa-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-square-o:before {\n  content: \"\\f0c8\"; }\n\n.fa.fa-bookmark-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bookmark-o:before {\n  content: \"\\f02e\"; }\n\n.fa.fa-twitter {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook:before {\n  content: \"\\f39e\"; }\n\n.fa.fa-facebook-f {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook-f:before {\n  content: \"\\f39e\"; }\n\n.fa.fa-github {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-credit-card {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-feed:before {\n  content: \"\\f09e\"; }\n\n.fa.fa-hdd-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hdd-o:before {\n  content: \"\\f0a0\"; }\n\n.fa.fa-hand-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-right:before {\n  content: \"\\f0a4\"; }\n\n.fa.fa-hand-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-left:before {\n  content: \"\\f0a5\"; }\n\n.fa.fa-hand-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-up:before {\n  content: \"\\f0a6\"; }\n\n.fa.fa-hand-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-o-down:before {\n  content: \"\\f0a7\"; }\n\n.fa.fa-arrows-alt:before {\n  content: \"\\f31e\"; }\n\n.fa.fa-group:before {\n  content: \"\\f0c0\"; }\n\n.fa.fa-chain:before {\n  content: \"\\f0c1\"; }\n\n.fa.fa-scissors:before {\n  content: \"\\f0c4\"; }\n\n.fa.fa-files-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-files-o:before {\n  content: \"\\f0c5\"; }\n\n.fa.fa-floppy-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-floppy-o:before {\n  content: \"\\f0c7\"; }\n\n.fa.fa-navicon:before {\n  content: \"\\f0c9\"; }\n\n.fa.fa-reorder:before {\n  content: \"\\f0c9\"; }\n\n.fa.fa-pinterest {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pinterest-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus:before {\n  content: \"\\f0d5\"; }\n\n.fa.fa-money {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-money:before {\n  content: \"\\f3d1\"; }\n\n.fa.fa-unsorted:before {\n  content: \"\\f0dc\"; }\n\n.fa.fa-sort-desc:before {\n  content: \"\\f0dd\"; }\n\n.fa.fa-sort-asc:before {\n  content: \"\\f0de\"; }\n\n.fa.fa-linkedin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-linkedin:before {\n  content: \"\\f0e1\"; }\n\n.fa.fa-rotate-left:before {\n  content: \"\\f0e2\"; }\n\n.fa.fa-legal:before {\n  content: \"\\f0e3\"; }\n\n.fa.fa-tachometer:before {\n  content: \"\\f3fd\"; }\n\n.fa.fa-dashboard:before {\n  content: \"\\f3fd\"; }\n\n.fa.fa-comment-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-comment-o:before {\n  content: \"\\f075\"; }\n\n.fa.fa-comments-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-comments-o:before {\n  content: \"\\f086\"; }\n\n.fa.fa-flash:before {\n  content: \"\\f0e7\"; }\n\n.fa.fa-clipboard {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-paste {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-paste:before {\n  content: \"\\f328\"; }\n\n.fa.fa-lightbulb-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-lightbulb-o:before {\n  content: \"\\f0eb\"; }\n\n.fa.fa-exchange:before {\n  content: \"\\f362\"; }\n\n.fa.fa-cloud-download:before {\n  content: \"\\f381\"; }\n\n.fa.fa-cloud-upload:before {\n  content: \"\\f382\"; }\n\n.fa.fa-bell-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bell-o:before {\n  content: \"\\f0f3\"; }\n\n.fa.fa-cutlery:before {\n  content: \"\\f2e7\"; }\n\n.fa.fa-file-text-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-text-o:before {\n  content: \"\\f15c\"; }\n\n.fa.fa-building-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-building-o:before {\n  content: \"\\f1ad\"; }\n\n.fa.fa-hospital-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hospital-o:before {\n  content: \"\\f0f8\"; }\n\n.fa.fa-tablet:before {\n  content: \"\\f3fa\"; }\n\n.fa.fa-mobile:before {\n  content: \"\\f3cd\"; }\n\n.fa.fa-mobile-phone:before {\n  content: \"\\f3cd\"; }\n\n.fa.fa-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-circle-o:before {\n  content: \"\\f111\"; }\n\n.fa.fa-mail-reply:before {\n  content: \"\\f3e5\"; }\n\n.fa.fa-github-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-folder-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-folder-o:before {\n  content: \"\\f07b\"; }\n\n.fa.fa-folder-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-folder-open-o:before {\n  content: \"\\f07c\"; }\n\n.fa.fa-smile-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-smile-o:before {\n  content: \"\\f118\"; }\n\n.fa.fa-frown-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-frown-o:before {\n  content: \"\\f119\"; }\n\n.fa.fa-meh-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-meh-o:before {\n  content: \"\\f11a\"; }\n\n.fa.fa-keyboard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-keyboard-o:before {\n  content: \"\\f11c\"; }\n\n.fa.fa-flag-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-flag-o:before {\n  content: \"\\f024\"; }\n\n.fa.fa-mail-reply-all:before {\n  content: \"\\f122\"; }\n\n.fa.fa-star-half-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-half-o:before {\n  content: \"\\f089\"; }\n\n.fa.fa-star-half-empty {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-half-empty:before {\n  content: \"\\f089\"; }\n\n.fa.fa-star-half-full {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-star-half-full:before {\n  content: \"\\f089\"; }\n\n.fa.fa-code-fork:before {\n  content: \"\\f126\"; }\n\n.fa.fa-chain-broken:before {\n  content: \"\\f127\"; }\n\n.fa.fa-shield:before {\n  content: \"\\f3ed\"; }\n\n.fa.fa-calendar-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-o:before {\n  content: \"\\f133\"; }\n\n.fa.fa-maxcdn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-html5 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-css3 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ticket:before {\n  content: \"\\f3ff\"; }\n\n.fa.fa-minus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-minus-square-o:before {\n  content: \"\\f146\"; }\n\n.fa.fa-level-up:before {\n  content: \"\\f3bf\"; }\n\n.fa.fa-level-down:before {\n  content: \"\\f3be\"; }\n\n.fa.fa-pencil-square:before {\n  content: \"\\f14b\"; }\n\n.fa.fa-external-link-square:before {\n  content: \"\\f360\"; }\n\n.fa.fa-compass {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-down:before {\n  content: \"\\f150\"; }\n\n.fa.fa-toggle-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-down:before {\n  content: \"\\f150\"; }\n\n.fa.fa-caret-square-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-up:before {\n  content: \"\\f151\"; }\n\n.fa.fa-toggle-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-up:before {\n  content: \"\\f151\"; }\n\n.fa.fa-caret-square-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-right:before {\n  content: \"\\f152\"; }\n\n.fa.fa-toggle-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-right:before {\n  content: \"\\f152\"; }\n\n.fa.fa-eur:before {\n  content: \"\\f153\"; }\n\n.fa.fa-euro:before {\n  content: \"\\f153\"; }\n\n.fa.fa-gbp:before {\n  content: \"\\f154\"; }\n\n.fa.fa-usd:before {\n  content: \"\\f155\"; }\n\n.fa.fa-dollar:before {\n  content: \"\\f155\"; }\n\n.fa.fa-inr:before {\n  content: \"\\f156\"; }\n\n.fa.fa-rupee:before {\n  content: \"\\f156\"; }\n\n.fa.fa-jpy:before {\n  content: \"\\f157\"; }\n\n.fa.fa-cny:before {\n  content: \"\\f157\"; }\n\n.fa.fa-rmb:before {\n  content: \"\\f157\"; }\n\n.fa.fa-yen:before {\n  content: \"\\f157\"; }\n\n.fa.fa-rub:before {\n  content: \"\\f158\"; }\n\n.fa.fa-ruble:before {\n  content: \"\\f158\"; }\n\n.fa.fa-rouble:before {\n  content: \"\\f158\"; }\n\n.fa.fa-krw:before {\n  content: \"\\f159\"; }\n\n.fa.fa-won:before {\n  content: \"\\f159\"; }\n\n.fa.fa-btc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitcoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitcoin:before {\n  content: \"\\f15a\"; }\n\n.fa.fa-file-text:before {\n  content: \"\\f15c\"; }\n\n.fa.fa-sort-alpha-asc:before {\n  content: \"\\f15d\"; }\n\n.fa.fa-sort-alpha-desc:before {\n  content: \"\\f881\"; }\n\n.fa.fa-sort-amount-asc:before {\n  content: \"\\f160\"; }\n\n.fa.fa-sort-amount-desc:before {\n  content: \"\\f884\"; }\n\n.fa.fa-sort-numeric-asc:before {\n  content: \"\\f162\"; }\n\n.fa.fa-sort-numeric-desc:before {\n  content: \"\\f886\"; }\n\n.fa.fa-youtube-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-youtube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-xing {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-xing-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-youtube-play {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-youtube-play:before {\n  content: \"\\f167\"; }\n\n.fa.fa-dropbox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stack-overflow {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-instagram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-flickr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-adn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitbucket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitbucket-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bitbucket-square:before {\n  content: \"\\f171\"; }\n\n.fa.fa-tumblr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-tumblr-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-long-arrow-down:before {\n  content: \"\\f309\"; }\n\n.fa.fa-long-arrow-up:before {\n  content: \"\\f30c\"; }\n\n.fa.fa-long-arrow-left:before {\n  content: \"\\f30a\"; }\n\n.fa.fa-long-arrow-right:before {\n  content: \"\\f30b\"; }\n\n.fa.fa-apple {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-windows {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-android {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-linux {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-dribbble {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-skype {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-foursquare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-trello {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gratipay {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gittip {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gittip:before {\n  content: \"\\f184\"; }\n\n.fa.fa-sun-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-sun-o:before {\n  content: \"\\f185\"; }\n\n.fa.fa-moon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-moon-o:before {\n  content: \"\\f186\"; }\n\n.fa.fa-vk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-renren {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pagelines {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stack-exchange {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-right:before {\n  content: \"\\f35a\"; }\n\n.fa.fa-arrow-circle-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-arrow-circle-o-left:before {\n  content: \"\\f359\"; }\n\n.fa.fa-caret-square-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-caret-square-o-left:before {\n  content: \"\\f191\"; }\n\n.fa.fa-toggle-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-toggle-left:before {\n  content: \"\\f191\"; }\n\n.fa.fa-dot-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-dot-circle-o:before {\n  content: \"\\f192\"; }\n\n.fa.fa-vimeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-try:before {\n  content: \"\\f195\"; }\n\n.fa.fa-turkish-lira:before {\n  content: \"\\f195\"; }\n\n.fa.fa-plus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-plus-square-o:before {\n  content: \"\\f0fe\"; }\n\n.fa.fa-slack {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wordpress {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-openid {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-institution:before {\n  content: \"\\f19c\"; }\n\n.fa.fa-bank:before {\n  content: \"\\f19c\"; }\n\n.fa.fa-mortar-board:before {\n  content: \"\\f19d\"; }\n\n.fa.fa-yahoo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-reddit {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-reddit-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stumbleupon-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-stumbleupon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-delicious {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-digg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pied-piper-pp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pied-piper-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-drupal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-joomla {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-spoon:before {\n  content: \"\\f2e5\"; }\n\n.fa.fa-behance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-behance-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-steam {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-steam-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-automobile:before {\n  content: \"\\f1b9\"; }\n\n.fa.fa-cab:before {\n  content: \"\\f1ba\"; }\n\n.fa.fa-envelope-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-envelope-o:before {\n  content: \"\\f0e0\"; }\n\n.fa.fa-deviantart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-soundcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-file-pdf-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-pdf-o:before {\n  content: \"\\f1c1\"; }\n\n.fa.fa-file-word-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-word-o:before {\n  content: \"\\f1c2\"; }\n\n.fa.fa-file-excel-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-excel-o:before {\n  content: \"\\f1c3\"; }\n\n.fa.fa-file-powerpoint-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-powerpoint-o:before {\n  content: \"\\f1c4\"; }\n\n.fa.fa-file-image-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-image-o:before {\n  content: \"\\f1c5\"; }\n\n.fa.fa-file-photo-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-photo-o:before {\n  content: \"\\f1c5\"; }\n\n.fa.fa-file-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-picture-o:before {\n  content: \"\\f1c5\"; }\n\n.fa.fa-file-archive-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-archive-o:before {\n  content: \"\\f1c6\"; }\n\n.fa.fa-file-zip-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-zip-o:before {\n  content: \"\\f1c6\"; }\n\n.fa.fa-file-audio-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-audio-o:before {\n  content: \"\\f1c7\"; }\n\n.fa.fa-file-sound-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-sound-o:before {\n  content: \"\\f1c7\"; }\n\n.fa.fa-file-video-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-video-o:before {\n  content: \"\\f1c8\"; }\n\n.fa.fa-file-movie-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-movie-o:before {\n  content: \"\\f1c8\"; }\n\n.fa.fa-file-code-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-file-code-o:before {\n  content: \"\\f1c9\"; }\n\n.fa.fa-vine {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-codepen {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-jsfiddle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-life-ring {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-bouy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-bouy:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-life-buoy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-buoy:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-life-saver {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-life-saver:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-support {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-support:before {\n  content: \"\\f1cd\"; }\n\n.fa.fa-circle-o-notch:before {\n  content: \"\\f1ce\"; }\n\n.fa.fa-rebel {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ra {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ra:before {\n  content: \"\\f1d0\"; }\n\n.fa.fa-resistance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-resistance:before {\n  content: \"\\f1d0\"; }\n\n.fa.fa-empire {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ge:before {\n  content: \"\\f1d1\"; }\n\n.fa.fa-git-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-git {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-hacker-news {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-y-combinator-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-y-combinator-square:before {\n  content: \"\\f1d4\"; }\n\n.fa.fa-yc-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yc-square:before {\n  content: \"\\f1d4\"; }\n\n.fa.fa-tencent-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-qq {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-weixin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wechat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wechat:before {\n  content: \"\\f1d7\"; }\n\n.fa.fa-send:before {\n  content: \"\\f1d8\"; }\n\n.fa.fa-paper-plane-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-paper-plane-o:before {\n  content: \"\\f1d8\"; }\n\n.fa.fa-send-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-send-o:before {\n  content: \"\\f1d8\"; }\n\n.fa.fa-circle-thin {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-circle-thin:before {\n  content: \"\\f111\"; }\n\n.fa.fa-header:before {\n  content: \"\\f1dc\"; }\n\n.fa.fa-sliders:before {\n  content: \"\\f1de\"; }\n\n.fa.fa-futbol-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-futbol-o:before {\n  content: \"\\f1e3\"; }\n\n.fa.fa-soccer-ball-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-soccer-ball-o:before {\n  content: \"\\f1e3\"; }\n\n.fa.fa-slideshare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-twitch {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yelp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-newspaper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-newspaper-o:before {\n  content: \"\\f1ea\"; }\n\n.fa.fa-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-wallet {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-visa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-mastercard {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-discover {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-amex {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-stripe {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bell-slash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-bell-slash-o:before {\n  content: \"\\f1f6\"; }\n\n.fa.fa-trash:before {\n  content: \"\\f2ed\"; }\n\n.fa.fa-copyright {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-eyedropper:before {\n  content: \"\\f1fb\"; }\n\n.fa.fa-area-chart:before {\n  content: \"\\f1fe\"; }\n\n.fa.fa-pie-chart:before {\n  content: \"\\f200\"; }\n\n.fa.fa-line-chart:before {\n  content: \"\\f201\"; }\n\n.fa.fa-lastfm {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-lastfm-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ioxhost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-angellist {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-cc:before {\n  content: \"\\f20a\"; }\n\n.fa.fa-ils:before {\n  content: \"\\f20b\"; }\n\n.fa.fa-shekel:before {\n  content: \"\\f20b\"; }\n\n.fa.fa-sheqel:before {\n  content: \"\\f20b\"; }\n\n.fa.fa-meanpath {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-meanpath:before {\n  content: \"\\f2b4\"; }\n\n.fa.fa-buysellads {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-connectdevelop {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-dashcube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-forumbee {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-leanpub {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-sellsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-shirtsinbulk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-simplybuilt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-skyatlas {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-diamond {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-diamond:before {\n  content: \"\\f3a5\"; }\n\n.fa.fa-intersex:before {\n  content: \"\\f224\"; }\n\n.fa.fa-facebook-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-facebook-official:before {\n  content: \"\\f09a\"; }\n\n.fa.fa-pinterest-p {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-whatsapp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-hotel:before {\n  content: \"\\f236\"; }\n\n.fa.fa-viacoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-medium {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-y-combinator {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yc:before {\n  content: \"\\f23b\"; }\n\n.fa.fa-optin-monster {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-opencart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-expeditedssl {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-battery-4:before {\n  content: \"\\f240\"; }\n\n.fa.fa-battery:before {\n  content: \"\\f240\"; }\n\n.fa.fa-battery-3:before {\n  content: \"\\f241\"; }\n\n.fa.fa-battery-2:before {\n  content: \"\\f242\"; }\n\n.fa.fa-battery-1:before {\n  content: \"\\f243\"; }\n\n.fa.fa-battery-0:before {\n  content: \"\\f244\"; }\n\n.fa.fa-object-group {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-object-ungroup {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-sticky-note-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-sticky-note-o:before {\n  content: \"\\f249\"; }\n\n.fa.fa-cc-jcb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-cc-diners-club {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-clone {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hourglass-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hourglass-o:before {\n  content: \"\\f254\"; }\n\n.fa.fa-hourglass-1:before {\n  content: \"\\f251\"; }\n\n.fa.fa-hourglass-2:before {\n  content: \"\\f252\"; }\n\n.fa.fa-hourglass-3:before {\n  content: \"\\f253\"; }\n\n.fa.fa-hand-rock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-rock-o:before {\n  content: \"\\f255\"; }\n\n.fa.fa-hand-grab-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-grab-o:before {\n  content: \"\\f255\"; }\n\n.fa.fa-hand-paper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-paper-o:before {\n  content: \"\\f256\"; }\n\n.fa.fa-hand-stop-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-stop-o:before {\n  content: \"\\f256\"; }\n\n.fa.fa-hand-scissors-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-scissors-o:before {\n  content: \"\\f257\"; }\n\n.fa.fa-hand-lizard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-lizard-o:before {\n  content: \"\\f258\"; }\n\n.fa.fa-hand-spock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-spock-o:before {\n  content: \"\\f259\"; }\n\n.fa.fa-hand-pointer-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-pointer-o:before {\n  content: \"\\f25a\"; }\n\n.fa.fa-hand-peace-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-hand-peace-o:before {\n  content: \"\\f25b\"; }\n\n.fa.fa-registered {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-creative-commons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gg-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-tripadvisor {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-odnoklassniki {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-odnoklassniki-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-get-pocket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wikipedia-w {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-safari {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-chrome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-firefox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-opera {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-internet-explorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-television:before {\n  content: \"\\f26c\"; }\n\n.fa.fa-contao {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-500px {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-amazon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-calendar-plus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-plus-o:before {\n  content: \"\\f271\"; }\n\n.fa.fa-calendar-minus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-minus-o:before {\n  content: \"\\f272\"; }\n\n.fa.fa-calendar-times-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-times-o:before {\n  content: \"\\f273\"; }\n\n.fa.fa-calendar-check-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-calendar-check-o:before {\n  content: \"\\f274\"; }\n\n.fa.fa-map-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-map-o:before {\n  content: \"\\f279\"; }\n\n.fa.fa-commenting:before {\n  content: \"\\f4ad\"; }\n\n.fa.fa-commenting-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-commenting-o:before {\n  content: \"\\f4ad\"; }\n\n.fa.fa-houzz {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-vimeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-vimeo:before {\n  content: \"\\f27d\"; }\n\n.fa.fa-black-tie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fonticons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-reddit-alien {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-edge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-credit-card-alt:before {\n  content: \"\\f09d\"; }\n\n.fa.fa-codiepie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-modx {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fort-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-usb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-product-hunt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-mixcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-scribd {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pause-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-pause-circle-o:before {\n  content: \"\\f28b\"; }\n\n.fa.fa-stop-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-stop-circle-o:before {\n  content: \"\\f28d\"; }\n\n.fa.fa-bluetooth {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-bluetooth-b {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-gitlab {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wpbeginner {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wpforms {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-envira {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wheelchair-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wheelchair-alt:before {\n  content: \"\\f368\"; }\n\n.fa.fa-question-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-question-circle-o:before {\n  content: \"\\f059\"; }\n\n.fa.fa-volume-control-phone:before {\n  content: \"\\f2a0\"; }\n\n.fa.fa-asl-interpreting:before {\n  content: \"\\f2a3\"; }\n\n.fa.fa-deafness:before {\n  content: \"\\f2a4\"; }\n\n.fa.fa-hard-of-hearing:before {\n  content: \"\\f2a4\"; }\n\n.fa.fa-glide {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-glide-g {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-signing:before {\n  content: \"\\f2a7\"; }\n\n.fa.fa-viadeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-viadeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-snapchat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-snapchat-ghost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-snapchat-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-pied-piper {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-first-order {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-yoast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-themeisle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-official:before {\n  content: \"\\f2b3\"; }\n\n.fa.fa-google-plus-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-google-plus-circle:before {\n  content: \"\\f2b3\"; }\n\n.fa.fa-font-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-fa:before {\n  content: \"\\f2b4\"; }\n\n.fa.fa-handshake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-handshake-o:before {\n  content: \"\\f2b5\"; }\n\n.fa.fa-envelope-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-envelope-open-o:before {\n  content: \"\\f2b6\"; }\n\n.fa.fa-linode {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-address-book-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-address-book-o:before {\n  content: \"\\f2b9\"; }\n\n.fa.fa-vcard:before {\n  content: \"\\f2bb\"; }\n\n.fa.fa-address-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-address-card-o:before {\n  content: \"\\f2bb\"; }\n\n.fa.fa-vcard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-vcard-o:before {\n  content: \"\\f2bb\"; }\n\n.fa.fa-user-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-user-circle-o:before {\n  content: \"\\f2bd\"; }\n\n.fa.fa-user-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-user-o:before {\n  content: \"\\f007\"; }\n\n.fa.fa-id-badge {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-drivers-license:before {\n  content: \"\\f2c2\"; }\n\n.fa.fa-id-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-id-card-o:before {\n  content: \"\\f2c2\"; }\n\n.fa.fa-drivers-license-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-drivers-license-o:before {\n  content: \"\\f2c2\"; }\n\n.fa.fa-quora {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-free-code-camp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-telegram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-thermometer-4:before {\n  content: \"\\f2c7\"; }\n\n.fa.fa-thermometer:before {\n  content: \"\\f2c7\"; }\n\n.fa.fa-thermometer-3:before {\n  content: \"\\f2c8\"; }\n\n.fa.fa-thermometer-2:before {\n  content: \"\\f2c9\"; }\n\n.fa.fa-thermometer-1:before {\n  content: \"\\f2ca\"; }\n\n.fa.fa-thermometer-0:before {\n  content: \"\\f2cb\"; }\n\n.fa.fa-bathtub:before {\n  content: \"\\f2cd\"; }\n\n.fa.fa-s15:before {\n  content: \"\\f2cd\"; }\n\n.fa.fa-window-maximize {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-window-restore {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-times-rectangle:before {\n  content: \"\\f410\"; }\n\n.fa.fa-window-close-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-window-close-o:before {\n  content: \"\\f410\"; }\n\n.fa.fa-times-rectangle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-times-rectangle-o:before {\n  content: \"\\f410\"; }\n\n.fa.fa-bandcamp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-grav {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-etsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-imdb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-ravelry {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-eercast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-eercast:before {\n  content: \"\\f2da\"; }\n\n.fa.fa-snowflake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400; }\n\n.fa.fa-snowflake-o:before {\n  content: \"\\f2dc\"; }\n\n.fa.fa-superpowers {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-wpexplorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n\n.fa.fa-spotify {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/all.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"500px\": [448, 512, [], \"f26e\", \"M103.3 344.3c-6.5-14.2-6.9-18.3 7.4-23.1 25.6-8 8 9.2 43.2 49.2h.3v-93.9c1.2-50.2 44-92.2 97.7-92.2 53.9 0 97.7 43.5 97.7 96.8 0 63.4-60.8 113.2-128.5 93.3-10.5-4.2-2.1-31.7 8.5-28.6 53 0 89.4-10.1 89.4-64.4 0-61-77.1-89.6-116.9-44.6-23.5 26.4-17.6 42.1-17.6 157.6 50.7 31 118.3 22 160.4-20.1 24.8-24.8 38.5-58 38.5-93 0-35.2-13.8-68.2-38.8-93.3-24.8-24.8-57.8-38.5-93.3-38.5s-68.8 13.8-93.5 38.5c-.3.3-16 16.5-21.2 23.9l-.5.6c-3.3 4.7-6.3 9.1-20.1 6.1-6.9-1.7-14.3-5.8-14.3-11.8V20c0-5 3.9-10.5 10.5-10.5h241.3c8.3 0 8.3 11.6 8.3 15.1 0 3.9 0 15.1-8.3 15.1H130.3v132.9h.3c104.2-109.8 282.8-36 282.8 108.9 0 178.1-244.8 220.3-310.1 62.8zm63.3-260.8c-.5 4.2 4.6 24.5 14.6 20.6C306 56.6 384 144.5 390.6 144.5c4.8 0 22.8-15.3 14.3-22.8-93.2-89-234.5-57-238.3-38.2zM393 414.7C283 524.6 94 475.5 61 310.5c0-12.2-30.4-7.4-28.9 3.3 24 173.4 246 256.9 381.6 121.3 6.9-7.8-12.6-28.4-20.7-20.4zM213.6 306.6c0 4 4.3 7.3 5.5 8.5 3 3 6.1 4.4 8.5 4.4 3.8 0 2.6.2 22.3-19.5 19.6 19.3 19.1 19.5 22.3 19.5 5.4 0 18.5-10.4 10.7-18.2L265.6 284l18.2-18.2c6.3-6.8-10.1-21.8-16.2-15.7L249.7 268c-18.6-18.8-18.4-19.5-21.5-19.5-5 0-18 11.7-12.4 17.3L234 284c-18.1 17.9-20.4 19.2-20.4 22.6z\"],\n    \"accessible-icon\": [448, 512, [], \"f368\", \"M423.9 255.8L411 413.1c-3.3 40.7-63.9 35.1-60.6-4.9l10-122.5-41.1 2.3c10.1 20.7 15.8 43.9 15.8 68.5 0 41.2-16.1 78.7-42.3 106.5l-39.3-39.3c57.9-63.7 13.1-167.2-74-167.2-25.9 0-49.5 9.9-67.2 26L73 243.2c22-20.7 50.1-35.1 81.4-40.2l75.3-85.7-42.6-24.8-51.6 46c-30 26.8-70.6-18.5-40.5-45.4l68-60.7c9.8-8.8 24.1-10.2 35.5-3.6 0 0 139.3 80.9 139.5 81.1 16.2 10.1 20.7 36 6.1 52.6L285.7 229l106.1-5.9c18.5-1.1 33.6 14.4 32.1 32.7zm-64.9-154c28.1 0 50.9-22.8 50.9-50.9C409.9 22.8 387.1 0 359 0c-28.1 0-50.9 22.8-50.9 50.9 0 28.1 22.8 50.9 50.9 50.9zM179.6 456.5c-80.6 0-127.4-90.6-82.7-156.1l-39.7-39.7C36.4 287 24 320.3 24 356.4c0 130.7 150.7 201.4 251.4 122.5l-39.7-39.7c-16 10.9-35.3 17.3-56.1 17.3z\"],\n    \"accusoft\": [640, 512, [], \"f369\", \"M322.1 252v-1l-51.2-65.8s-12 1.6-25 15.1c-9 9.3-242.1 239.1-243.4 240.9-7 10 1.6 6.8 15.7 1.7.8 0 114.5-36.6 114.5-36.6.5-.6-.1-.1.6-.6-.4-5.1-.8-26.2-1-27.7-.6-5.2 2.2-6.9 7-8.9l92.6-33.8c.6-.8 88.5-81.7 90.2-83.3zm160.1 120.1c13.3 16.1 20.7 13.3 30.8 9.3 3.2-1.2 115.4-47.6 117.8-48.9 8-4.3-1.7-16.7-7.2-23.4-2.1-2.5-205.1-245.6-207.2-248.3-9.7-12.2-14.3-12.9-38.4-12.8-10.2 0-106.8.5-116.5.6-19.2.1-32.9-.3-19.2 16.9C250 75 476.5 365.2 482.2 372.1zm152.7 1.6c-2.3-.3-24.6-4.7-38-7.2 0 0-115 50.4-117.5 51.6-16 7.3-26.9-3.2-36.7-14.6l-57.1-74c-5.4-.9-60.4-9.6-65.3-9.3-3.1.2-9.6.8-14.4 2.9-4.9 2.1-145.2 52.8-150.2 54.7-5.1 2-11.4 3.6-11.1 7.6.2 2.5 2 2.6 4.6 3.5 2.7.8 300.9 67.6 308 69.1 15.6 3.3 38.5 10.5 53.6 1.7 2.1-1.2 123.8-76.4 125.8-77.8 5.4-4 4.3-6.8-1.7-8.2z\"],\n    \"acquisitions-incorporated\": [384, 512, [], \"f6af\", \"M357.45 468.2c-1.2-7.7-1.3-7.6-9.6-7.6-99.8.2-111.8-2.4-112.7-2.6-12.3-1.7-20.6-10.5-21-23.1-.1-1.6-.2-71.6-1-129.1-.1-4.7 1.6-6.4 5.9-7.5 12.5-3 24.9-6.1 37.3-9.7 4.3-1.3 6.8-.2 8.4 3.5 4.5 10.3 8.8 20.6 13.2 30.9 1.6 3.7.1 4.4-3.4 4.4-10-.2-20-.1-30.4-.1v27h116c-1.4-9.5-2.7-18.1-4-27.5-7 0-13.8.4-20.4-.1-22.6-1.6-18.3-4.4-84-158.6-8.8-20.1-27.9-62.1-36.5-89.2-4.4-14 5.5-25.4 18.9-26.6 18.6-1.7 37.5-1.6 56.2-2 20.6-.4 41.2-.4 61.8-.5 3.1 0 4-1.4 4.3-4.3 1.2-9.8 2.7-19.5 4-29.2.8-5.3 1.6-10.7 2.4-16.1L23.75 0c-3.6 0-5.3 1.1-4.6 5.3 2.2 13.2-.8.8 6.4 45.3 63.4 0 71.8.9 101.8.5 12.3-.2 37 3.5 37.7 22.1.4 11.4-1.1 11.3-32.6 87.4-53.8 129.8-50.7 120.3-67.3 161-1.7 4.1-3.6 5.2-7.6 5.2-8.5-.2-17-.3-25.4.1-1.9.1-5.2 1.8-5.5 3.2-1.5 8.1-2.2 16.3-3.2 24.9h114.3v-27.6c-6.9 0-33.5.4-35.3-2.9 5.3-12.3 10.4-24.4 15.7-36.7 16.3 4 31.9 7.8 47.6 11.7 3.4.9 4.6 3 4.6 6.8-.1 42.9.1 85.9.2 128.8 0 10.2-5.5 19.1-14.9 23.1-6.5 2.7-3.3 3.4-121.4 2.4-5.3 0-7.1 2-7.6 6.8-1.5 12.9-2.9 25.9-5 38.8-.8 5 1.3 5.7 5.3 5.7 183.2.6-30.7 0 337.1 0-2.5-15-4.4-29.4-6.6-43.7zm-174.9-205.7c-13.3-4.2-26.6-8.2-39.9-12.5a44.53 44.53 0 0 1-5.8-2.9c17.2-44.3 34.2-88.1 51.3-132.1 7.5 2.4 7.9-.8 9.4 0 9.3 22.5 18.1 60.1 27 82.8 6.6 16.7 13 33.5 19.7 50.9a35.78 35.78 0 0 1-3.9 2.1c-13.1 3.9-26.4 7.5-39.4 11.7a27.66 27.66 0 0 1-18.4 0z\"],\n    \"adn\": [496, 512, [], \"f170\", \"M248 167.5l64.9 98.8H183.1l64.9-98.8zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-99.8 82.7L248 115.5 99.8 338.7h30.4l33.6-51.7h168.6l33.6 51.7h30.2z\"],\n    \"adobe\": [512, 512, [], \"f778\", \"M315.5 64h170.9v384L315.5 64zm-119 0H25.6v384L196.5 64zM256 206.1L363.5 448h-73l-30.7-76.8h-78.7L256 206.1z\"],\n    \"adversal\": [512, 512, [], \"f36a\", \"M482.1 32H28.7C5.8 32 0 37.9 0 60.9v390.2C0 474.4 5.8 480 28.7 480h453.4c24.4 0 29.9-5.2 29.9-29.7V62.2c0-24.6-5.4-30.2-29.9-30.2zM178.4 220.3c-27.5-20.2-72.1-8.7-84.2 23.4-4.3 11.1-9.3 9.5-17.5 8.3-9.7-1.5-17.2-3.2-22.5-5.5-28.8-11.4 8.6-55.3 24.9-64.3 41.1-21.4 83.4-22.2 125.3-4.8 40.9 16.8 34.5 59.2 34.5 128.5 2.7 25.8-4.3 58.3 9.3 88.8 1.9 4.4.4 7.9-2.7 10.7-8.4 6.7-39.3 2.2-46.6-7.4-1.9-2.2-1.8-3.6-3.9-6.2-3.6-3.9-7.3-2.2-11.9 1-57.4 36.4-140.3 21.4-147-43.3-3.1-29.3 12.4-57.1 39.6-71 38.2-19.5 112.2-11.8 114-30.9 1.1-10.2-1.9-20.1-11.3-27.3zm286.7 222c0 15.1-11.1 9.9-17.8 9.9H52.4c-7.4 0-18.2 4.8-17.8-10.7.4-13.9 10.5-9.1 17.1-9.1 132.3-.4 264.5-.4 396.8 0 6.8 0 16.6-4.4 16.6 9.9zm3.8-340.5v291c0 5.7-.7 13.9-8.1 13.9-12.4-.4-27.5 7.1-36.1-5.6-5.8-8.7-7.8-4-12.4-1.2-53.4 29.7-128.1 7.1-144.4-85.2-6.1-33.4-.7-67.1 15.7-100 11.8-23.9 56.9-76.1 136.1-30.5v-71c0-26.2-.1-26.2 26-26.2 3.1 0 6.6.4 9.7 0 10.1-.8 13.6 4.4 13.6 14.3-.1.2-.1.3-.1.5zm-51.5 232.3c-19.5 47.6-72.9 43.3-90 5.2-15.1-33.3-15.5-68.2.4-101.5 16.3-34.1 59.7-35.7 81.5-4.8 20.6 28.8 14.9 84.6 8.1 101.1zm-294.8 35.3c-7.5-1.3-33-3.3-33.7-27.8-.4-13.9 7.8-23 19.8-25.8 24.4-5.9 49.3-9.9 73.7-14.7 8.9-2 7.4 4.4 7.8 9.5 1.4 33-26.1 59.2-67.6 58.8z\"],\n    \"affiliatetheme\": [512, 512, [], \"f36b\", \"M159.7 237.4C108.4 308.3 43.1 348.2 14 326.6-15.2 304.9 2.8 230 54.2 159.1c51.3-70.9 116.6-110.8 145.7-89.2 29.1 21.6 11.1 96.6-40.2 167.5zm351.2-57.3C437.1 303.5 319 367.8 246.4 323.7c-25-15.2-41.3-41.2-49-73.8-33.6 64.8-92.8 113.8-164.1 133.2 49.8 59.3 124.1 96.9 207 96.9 150 0 271.6-123.1 271.6-274.9.1-8.5-.3-16.8-1-25z\"],\n    \"airbnb\": [448, 512, [], \"f834\", \"M224 373.12c-25.24-31.67-40.08-59.43-45-83.18-22.55-88 112.61-88 90.06 0-5.45 24.25-20.29 52-45 83.18zm138.15 73.23c-42.06 18.31-83.67-10.88-119.3-50.47 103.9-130.07 46.11-200-18.85-200-54.92 0-85.16 46.51-73.28 100.5 6.93 29.19 25.23 62.39 54.43 99.5-32.53 36.05-60.55 52.69-85.15 54.92-50 7.43-89.11-41.06-71.3-91.09 15.1-39.16 111.72-231.18 115.87-241.56 15.75-30.07 25.56-57.4 59.38-57.4 32.34 0 43.4 25.94 60.37 59.87 36 70.62 89.35 177.48 114.84 239.09 13.17 33.07-1.37 71.29-37.01 86.64zm47-136.12C280.27 35.93 273.13 32 224 32c-45.52 0-64.87 31.67-84.66 72.79C33.18 317.1 22.89 347.19 22 349.81-3.22 419.14 48.74 480 111.63 480c21.71 0 60.61-6.06 112.37-62.4 58.68 63.78 101.26 62.4 112.37 62.4 62.89.05 114.85-60.86 89.61-130.19.02-3.89-16.82-38.9-16.82-39.58z\"],\n    \"algolia\": [448, 512, [], \"f36c\", \"M229.3 182.6c-49.3 0-89.2 39.9-89.2 89.2 0 49.3 39.9 89.2 89.2 89.2s89.2-39.9 89.2-89.2c0-49.3-40-89.2-89.2-89.2zm62.7 56.6l-58.9 30.6c-1.8.9-3.8-.4-3.8-2.3V201c0-1.5 1.3-2.7 2.7-2.6 26.2 1 48.9 15.7 61.1 37.1.7 1.3.2 3-1.1 3.7zM389.1 32H58.9C26.4 32 0 58.4 0 90.9V421c0 32.6 26.4 59 58.9 59H389c32.6 0 58.9-26.4 58.9-58.9V90.9C448 58.4 421.6 32 389.1 32zm-202.6 84.7c0-10.8 8.7-19.5 19.5-19.5h45.3c10.8 0 19.5 8.7 19.5 19.5v15.4c0 1.8-1.7 3-3.3 2.5-12.3-3.4-25.1-5.1-38.1-5.1-13.5 0-26.7 1.8-39.4 5.5-1.7.5-3.4-.8-3.4-2.5v-15.8zm-84.4 37l9.2-9.2c7.6-7.6 19.9-7.6 27.5 0l7.7 7.7c1.1 1.1 1 3-.3 4-6.2 4.5-12.1 9.4-17.6 14.9-5.4 5.4-10.4 11.3-14.8 17.4-1 1.3-2.9 1.5-4 .3l-7.7-7.7c-7.6-7.5-7.6-19.8 0-27.4zm127.2 244.8c-70 0-126.6-56.7-126.6-126.6s56.7-126.6 126.6-126.6c70 0 126.6 56.6 126.6 126.6 0 69.8-56.7 126.6-126.6 126.6z\"],\n    \"alipay\": [448, 512, [], \"f642\", \"M377.74 32H70.26C31.41 32 0 63.41 0 102.26v307.48C0 448.59 31.41 480 70.26 480h307.48c38.52 0 69.76-31.08 70.26-69.6-45.96-25.62-110.59-60.34-171.6-88.44-32.07 43.97-84.14 81-148.62 81-70.59 0-93.73-45.3-97.04-76.37-3.97-39.01 14.88-81.5 99.52-81.5 35.38 0 79.35 10.25 127.13 24.96 16.53-30.09 26.45-60.34 26.45-60.34h-178.2v-16.7h92.08v-31.24H88.28v-19.01h109.44V92.34h50.92v50.42h109.44v19.01H248.63v31.24h88.77s-15.21 46.62-38.35 90.92c48.93 16.7 100.01 36.04 148.62 52.74V102.26C447.83 63.57 416.43 32 377.74 32zM47.28 322.95c.99 20.17 10.25 53.73 69.93 53.73 52.07 0 92.58-39.68 117.87-72.9-44.63-18.68-84.48-31.41-109.44-31.41-67.45 0-79.35 33.06-78.36 50.58z\"],\n    \"amazon\": [448, 512, [], \"f270\", \"M257.2 162.7c-48.7 1.8-169.5 15.5-169.5 117.5 0 109.5 138.3 114 183.5 43.2 6.5 10.2 35.4 37.5 45.3 46.8l56.8-56S341 288.9 341 261.4V114.3C341 89 316.5 32 228.7 32 140.7 32 94 87 94 136.3l73.5 6.8c16.3-49.5 54.2-49.5 54.2-49.5 40.7-.1 35.5 29.8 35.5 69.1zm0 86.8c0 80-84.2 68-84.2 17.2 0-47.2 50.5-56.7 84.2-57.8v40.6zm136 163.5c-7.7 10-70 67-174.5 67S34.2 408.5 9.7 379c-6.8-7.7 1-11.3 5.5-8.3C88.5 415.2 203 488.5 387.7 401c7.5-3.7 13.3 2 5.5 12zm39.8 2.2c-6.5 15.8-16 26.8-21.2 31-5.5 4.5-9.5 2.7-6.5-3.8s19.3-46.5 12.7-55c-6.5-8.3-37-4.3-48-3.2-10.8 1-13 2-14-.3-2.3-5.7 21.7-15.5 37.5-17.5 15.7-1.8 41-.8 46 5.7 3.7 5.1 0 27.1-6.5 43.1z\"],\n    \"amazon-pay\": [640, 512, [], \"f42c\", \"M14 325.3c2.3-4.2 5.2-4.9 9.7-2.5 10.4 5.6 20.6 11.4 31.2 16.7a595.88 595.88 0 0 0 127.4 46.3 616.61 616.61 0 0 0 63.2 11.8 603.33 603.33 0 0 0 95 5.2c17.4-.4 34.8-1.8 52.1-3.8a603.66 603.66 0 0 0 163.3-42.8c2.9-1.2 5.9-2 9.1-1.2 6.7 1.8 9 9 4.1 13.9a70 70 0 0 1-9.6 7.4c-30.7 21.1-64.2 36.4-99.6 47.9a473.31 473.31 0 0 1-75.1 17.6 431 431 0 0 1-53.2 4.8 21.3 21.3 0 0 0-2.5.3H308a21.3 21.3 0 0 0-2.5-.3c-3.6-.2-7.2-.3-10.7-.4a426.3 426.3 0 0 1-50.4-5.3A448.4 448.4 0 0 1 164 420a443.33 443.33 0 0 1-145.6-87c-1.8-1.6-3-3.8-4.4-5.7zM172 65.1l-4.3.6a80.92 80.92 0 0 0-38 15.1c-2.4 1.7-4.6 3.5-7.1 5.4a4.29 4.29 0 0 1-.4-1.4c-.4-2.7-.8-5.5-1.3-8.2-.7-4.6-3-6.6-7.6-6.6h-11.5c-6.9 0-8.2 1.3-8.2 8.2v209.3c0 1 0 2 .1 3 .2 3 2 4.9 4.9 5 7 .1 14.1.1 21.1 0 2.9 0 4.7-2 5-5 .1-1 .1-2 .1-3v-72.4c1.1.9 1.7 1.4 2.2 1.9 17.9 14.9 38.5 19.8 61 15.4 20.4-4 34.6-16.5 43.8-34.9 7-13.9 9.9-28.7 10.3-44.1.5-17.1-1.2-33.9-8.1-49.8-8.5-19.6-22.6-32.5-43.9-36.9-3.2-.7-6.5-1-9.8-1.5-2.8-.1-5.5-.1-8.3-.1zM124.6 107a3.48 3.48 0 0 1 1.7-3.3c13.7-9.5 28.8-14.5 45.6-13.2 14.9 1.1 27.1 8.4 33.5 25.9 3.9 10.7 4.9 21.8 4.9 33 0 10.4-.8 20.6-4 30.6-6.8 21.3-22.4 29.4-42.6 28.5-14-.6-26.2-6-37.4-13.9a3.57 3.57 0 0 1-1.7-3.3c.1-14.1 0-28.1 0-42.2s.1-28 0-42.1zm205.7-41.9c-1 .1-2 .3-2.9.4a148 148 0 0 0-28.9 4.1c-6.1 1.6-12 3.8-17.9 5.8-3.6 1.2-5.4 3.8-5.3 7.7.1 3.3-.1 6.6 0 9.9.1 4.8 2.1 6.1 6.8 4.9 7.8-2 15.6-4.2 23.5-5.7 12.3-2.3 24.7-3.3 37.2-1.4 6.5 1 12.6 2.9 16.8 8.4 3.7 4.8 5.1 10.5 5.3 16.4.3 8.3.2 16.6.3 24.9a7.84 7.84 0 0 1-.2 1.4c-.5-.1-.9 0-1.3-.1a180.56 180.56 0 0 0-32-4.9c-11.3-.6-22.5.1-33.3 3.9-12.9 4.5-23.3 12.3-29.4 24.9-4.7 9.8-5.4 20.2-3.9 30.7 2 14 9 24.8 21.4 31.7 11.9 6.6 24.8 7.4 37.9 5.4 15.1-2.3 28.5-8.7 40.3-18.4a7.36 7.36 0 0 1 1.6-1.1c.6 3.8 1.1 7.4 1.8 11 .6 3.1 2.5 5.1 5.4 5.2 5.4.1 10.9.1 16.3 0a4.84 4.84 0 0 0 4.8-4.7 26.2 26.2 0 0 0 .1-2.8v-106a80 80 0 0 0-.9-12.9c-1.9-12.9-7.4-23.5-19-30.4-6.7-4-14.1-6-21.8-7.1-3.6-.5-7.2-.8-10.8-1.3-3.9.1-7.9.1-11.9.1zm35 127.7a3.33 3.33 0 0 1-1.5 3c-11.2 8.1-23.5 13.5-37.4 14.9-5.7.6-11.4.4-16.8-1.8a20.08 20.08 0 0 1-12.4-13.3 32.9 32.9 0 0 1-.1-19.4c2.5-8.3 8.4-13 16.4-15.6a61.33 61.33 0 0 1 24.8-2.2c8.4.7 16.6 2.3 25 3.4 1.6.2 2.1 1 2.1 2.6-.1 4.8 0 9.5 0 14.3s-.2 9.4-.1 14.1zm259.9 129.4c-1-5-4.8-6.9-9.1-8.3a88.42 88.42 0 0 0-21-3.9 147.32 147.32 0 0 0-39.2 1.9c-14.3 2.7-27.9 7.3-40 15.6a13.75 13.75 0 0 0-3.7 3.5 5.11 5.11 0 0 0-.5 4c.4 1.5 2.1 1.9 3.6 1.8a16.2 16.2 0 0 0 2.2-.1c7.8-.8 15.5-1.7 23.3-2.5 11.4-1.1 22.9-1.8 34.3-.9a71.64 71.64 0 0 1 14.4 2.7c5.1 1.4 7.4 5.2 7.6 10.4.4 8-1.4 15.7-3.5 23.3-4.1 15.4-10 30.3-15.8 45.1a17.6 17.6 0 0 0-1 3c-.5 2.9 1.2 4.8 4.1 4.1a10.56 10.56 0 0 0 4.8-2.5 145.91 145.91 0 0 0 12.7-13.4c12.8-16.4 20.3-35.3 24.7-55.6.8-3.6 1.4-7.3 2.1-10.9v-17.3zM493.1 199q-19.35-53.55-38.7-107.2c-2-5.7-4.2-11.3-6.3-16.9-1.1-2.9-3.2-4.8-6.4-4.8-7.6-.1-15.2-.2-22.9-.1-2.5 0-3.7 2-3.2 4.5a43.1 43.1 0 0 0 1.9 6.1q29.4 72.75 59.1 145.5c1.7 4.1 2.1 7.6.2 11.8-3.3 7.3-5.9 15-9.3 22.3-3 6.5-8 11.4-15.2 13.3a42.13 42.13 0 0 1-15.4 1.1c-2.5-.2-5-.8-7.5-1-3.4-.2-5.1 1.3-5.2 4.8q-.15 5 0 9.9c.1 5.5 2 8 7.4 8.9a108.18 108.18 0 0 0 16.9 2c17.1.4 30.7-6.5 39.5-21.4a131.63 131.63 0 0 0 9.2-18.4q35.55-89.7 70.6-179.6a26.62 26.62 0 0 0 1.6-5.5c.4-2.8-.9-4.4-3.7-4.4-6.6-.1-13.3 0-19.9 0a7.54 7.54 0 0 0-7.7 5.2c-.5 1.4-1.1 2.7-1.6 4.1l-34.8 100c-2.5 7.2-5.1 14.5-7.7 22.2-.4-1.1-.6-1.7-.9-2.4z\"],\n    \"amilia\": [448, 512, [], \"f36d\", \"M240.1 32c-61.9 0-131.5 16.9-184.2 55.4-5.1 3.1-9.1 9.2-7.2 19.4 1.1 5.1 5.1 27.4 10.2 39.6 4.1 10.2 14.2 10.2 20.3 6.1 32.5-22.3 96.5-47.7 152.3-47.7 57.9 0 58.9 28.4 58.9 73.1v38.5C203 227.7 78.2 251 46.7 264.2 11.2 280.5 16.3 357.7 16.3 376s15.2 104 124.9 104c47.8 0 113.7-20.7 153.3-42.1v25.4c0 3 2.1 8.2 6.1 9.1 3.1 1 50.7 2 59.9 2s62.5.3 66.5-.7c4.1-1 5.1-6.1 5.1-9.1V168c-.1-80.3-57.9-136-192-136zm50.2 348c-21.4 13.2-48.7 24.4-79.1 24.4-52.8 0-58.9-33.5-59-44.7 0-12.2-3-42.7 18.3-52.9 24.3-13.2 75.1-29.4 119.8-33.5z\"],\n    \"android\": [448, 512, [], \"f17b\", \"M89.6 204.5v115.8c0 15.4-12.1 27.7-27.5 27.7-15.3 0-30.1-12.4-30.1-27.7V204.5c0-15.1 14.8-27.5 30.1-27.5 15.1 0 27.5 12.4 27.5 27.5zm10.8 157c0 16.4 13.2 29.6 29.6 29.6h19.9l.3 61.1c0 36.9 55.2 36.6 55.2 0v-61.1h37.2v61.1c0 36.7 55.5 36.8 55.5 0v-61.1h20.2c16.2 0 29.4-13.2 29.4-29.6V182.1H100.4v179.4zm248-189.1H99.3c0-42.8 25.6-80 63.6-99.4l-19.1-35.3c-2.8-4.9 4.3-8 6.7-3.8l19.4 35.6c34.9-15.5 75-14.7 108.3 0L297.5 34c2.5-4.3 9.5-1.1 6.7 3.8L285.1 73c37.7 19.4 63.3 56.6 63.3 99.4zm-170.7-55.5c0-5.7-4.6-10.5-10.5-10.5-5.7 0-10.2 4.8-10.2 10.5s4.6 10.5 10.2 10.5c5.9 0 10.5-4.8 10.5-10.5zm113.4 0c0-5.7-4.6-10.5-10.2-10.5-5.9 0-10.5 4.8-10.5 10.5s4.6 10.5 10.5 10.5c5.6 0 10.2-4.8 10.2-10.5zm94.8 60.1c-15.1 0-27.5 12.1-27.5 27.5v115.8c0 15.4 12.4 27.7 27.5 27.7 15.4 0 30.1-12.4 30.1-27.7V204.5c0-15.4-14.8-27.5-30.1-27.5z\"],\n    \"angellist\": [448, 512, [], \"f209\", \"M347.1 215.4c11.7-32.6 45.4-126.9 45.4-157.1 0-26.6-15.7-48.9-43.7-48.9-44.6 0-84.6 131.7-97.1 163.1C242 144 196.6 0 156.6 0c-31.1 0-45.7 22.9-45.7 51.7 0 35.3 34.2 126.8 46.6 162-6.3-2.3-13.1-4.3-20-4.3-23.4 0-48.3 29.1-48.3 52.6 0 8.9 4.9 21.4 8 29.7-36.9 10-51.1 34.6-51.1 71.7C46 435.6 114.4 512 210.6 512c118 0 191.4-88.6 191.4-202.9 0-43.1-6.9-82-54.9-93.7zM311.7 108c4-12.3 21.1-64.3 37.1-64.3 8.6 0 10.9 8.9 10.9 16 0 19.1-38.6 124.6-47.1 148l-34-6 33.1-93.7zM142.3 48.3c0-11.9 14.5-45.7 46.3 47.1l34.6 100.3c-15.6-1.3-27.7-3-35.4 1.4-10.9-28.8-45.5-119.7-45.5-148.8zM140 244c29.3 0 67.1 94.6 67.1 107.4 0 5.1-4.9 11.4-10.6 11.4-20.9 0-76.9-76.9-76.9-97.7.1-7.7 12.7-21.1 20.4-21.1zm184.3 186.3c-29.1 32-66.3 48.6-109.7 48.6-59.4 0-106.3-32.6-128.9-88.3-17.1-43.4 3.8-68.3 20.6-68.3 11.4 0 54.3 60.3 54.3 73.1 0 4.9-7.7 8.3-11.7 8.3-16.1 0-22.4-15.5-51.1-51.4-29.7 29.7 20.5 86.9 58.3 86.9 26.1 0 43.1-24.2 38-42 3.7 0 8.3.3 11.7-.6 1.1 27.1 9.1 59.4 41.7 61.7 0-.9 2-7.1 2-7.4 0-17.4-10.6-32.6-10.6-50.3 0-28.3 21.7-55.7 43.7-71.7 8-6 17.7-9.7 27.1-13.1 9.7-3.7 20-8 27.4-15.4-1.1-11.2-5.7-21.1-16.9-21.1-27.7 0-120.6 4-120.6-39.7 0-6.7.1-13.1 17.4-13.1 32.3 0 114.3 8 138.3 29.1 18.1 16.1 24.3 113.2-31 174.7zm-98.6-126c9.7 3.1 19.7 4 29.7 6-7.4 5.4-14 12-20.3 19.1-2.8-8.5-6.2-16.8-9.4-25.1z\"],\n    \"angrycreative\": [640, 512, [], \"f36e\", \"M640 238.2l-3.2 28.2-34.5 2.3-2 18.1 34.5-2.3-3.2 28.2-34.4 2.2-2.3 20.1 34.4-2.2-3 26.1-64.7 4.1 12.7-113.2L527 365.2l-31.9 2-23.8-117.8 30.3-2 13.6 79.4 31.7-82.4 93.1-6.2zM426.8 371.5l28.3-1.8L468 249.6l-28.4 1.9-12.8 120zM162 388.1l-19.4-36-3.5 37.4-28.2 1.7 2.7-29.1c-11 18-32 34.3-56.9 35.8C23.9 399.9-3 377 .3 339.7c2.6-29.3 26.7-62.8 67.5-65.4 37.7-2.4 47.6 23.2 51.3 28.8l2.8-30.8 38.9-2.5c20.1-1.3 38.7 3.7 42.5 23.7l2.6-26.6 64.8-4.2-2.7 27.9-36.4 2.4-1.7 17.9 36.4-2.3-2.7 27.9-36.4 2.3-1.9 19.9 36.3-2.3-2.1 20.8 55-117.2 23.8-1.6L370.4 369l8.9-85.6-22.3 1.4 2.9-27.9 75-4.9-3 28-24.3 1.6-9.7 91.9-58 3.7-4.3-15.6-39.4 2.5-8 16.3-126.2 7.7zm-44.3-70.2l-26.4 1.7C84.6 307.2 76.9 303 65 303.8c-19 1.2-33.3 17.5-34.6 33.3-1.4 16 7.3 32.5 28.7 31.2 12.8-.8 21.3-8.6 28.9-18.9l27-1.7 2.7-29.8zm56.1-7.7c1.2-12.9-7.6-13.6-26.1-12.4l-2.7 28.5c14.2-.9 27.5-2.1 28.8-16.1zm21.1 70.8l5.8-60c-5 13.5-14.7 21.1-27.9 26.6l22.1 33.4zm135.4-45l-7.9-37.8-15.8 39.3 23.7-1.5zm-170.1-74.6l-4.3-17.5-39.6 2.6-8.1 18.2-31.9 2.1 57-121.9 23.9-1.6 30.7 102 9.9-104.7 27-1.8 37.8 63.6 6.5-66.6 28.5-1.9-4 41.2c7.4-13.5 22.9-44.7 63.6-47.5 40.5-2.8 52.4 29.3 53.4 30.3l3.3-32 39.3-2.7c12.7-.9 27.8.3 36.3 9.7l-4.4-11.9 32.2-2.2 12.9 43.2 23-45.7 31-2.2-43.6 78.4-4.8 44.3-28.4 1.9 4.8-44.3-15.8-43c1 22.3-9.2 40.1-32 49.6l25.2 38.8-36.4 2.4-19.2-36.8-4 38.3-28.4 1.9 3.3-31.5c-6.7 9.3-19.7 35.4-59.6 38-26.2 1.7-45.6-10.3-55.4-39.2l-4 40.3-25 1.6-37.6-63.3-6.3 66.2-56.8 3.7zm276.6-82.1c10.2-.7 17.5-2.1 21.6-4.3 4.5-2.4 7-6.4 7.6-12.1.6-5.3-.6-8.8-3.4-10.4-3.6-2.1-10.6-2.8-22.9-2l-2.9 28.8zM327.7 214c5.6 5.9 12.7 8.5 21.3 7.9 4.7-.3 9.1-1.8 13.3-4.1 5.5-3 10.6-8 15.1-14.3l-34.2 2.3 2.4-23.9 63.1-4.3 1.2-12-31.2 2.1c-4.1-3.7-7.8-6.6-11.1-8.1-4-1.7-8.1-2.8-12.2-2.5-8 .5-15.3 3.6-22 9.2-7.7 6.4-12 14.5-12.9 24.4-1.1 9.6 1.4 17.3 7.2 23.3zm-201.3 8.2l23.8-1.6-8.3-37.6-15.5 39.2z\"],\n    \"angular\": [448, 512, [], \"f420\", \"M185.7 268.1h76.2l-38.1-91.6-38.1 91.6zM223.8 32L16 106.4l31.8 275.7 176 97.9 176-97.9 31.8-275.7zM354 373.8h-48.6l-26.2-65.4H168.6l-26.2 65.4H93.7L223.8 81.5z\"],\n    \"app-store\": [512, 512, [], \"f36f\", \"M255.9 120.9l9.1-15.7c5.6-9.8 18.1-13.1 27.9-7.5 9.8 5.6 13.1 18.1 7.5 27.9l-87.5 151.5h63.3c20.5 0 32 24.1 23.1 40.8H113.8c-11.3 0-20.4-9.1-20.4-20.4 0-11.3 9.1-20.4 20.4-20.4h52l66.6-115.4-20.8-36.1c-5.6-9.8-2.3-22.2 7.5-27.9 9.8-5.6 22.2-2.3 27.9 7.5l8.9 15.7zm-78.7 218l-19.6 34c-5.6 9.8-18.1 13.1-27.9 7.5-9.8-5.6-13.1-18.1-7.5-27.9l14.6-25.2c16.4-5.1 29.8-1.2 40.4 11.6zm168.9-61.7h53.1c11.3 0 20.4 9.1 20.4 20.4 0 11.3-9.1 20.4-20.4 20.4h-29.5l19.9 34.5c5.6 9.8 2.3 22.2-7.5 27.9-9.8 5.6-22.2 2.3-27.9-7.5-33.5-58.1-58.7-101.6-75.4-130.6-17.1-29.5-4.9-59.1 7.2-69.1 13.4 23 33.4 57.7 60.1 104zM256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm216 248c0 118.7-96.1 216-216 216-118.7 0-216-96.1-216-216 0-118.7 96.1-216 216-216 118.7 0 216 96.1 216 216z\"],\n    \"app-store-ios\": [448, 512, [], \"f370\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM127 384.5c-5.5 9.6-17.8 12.8-27.3 7.3-9.6-5.5-12.8-17.8-7.3-27.3l14.3-24.7c16.1-4.9 29.3-1.1 39.6 11.4L127 384.5zm138.9-53.9H84c-11 0-20-9-20-20s9-20 20-20h51l65.4-113.2-20.5-35.4c-5.5-9.6-2.2-21.8 7.3-27.3 9.6-5.5 21.8-2.2 27.3 7.3l8.9 15.4 8.9-15.4c5.5-9.6 17.8-12.8 27.3-7.3 9.6 5.5 12.8 17.8 7.3 27.3l-85.8 148.6h62.1c20.2 0 31.5 23.7 22.7 40zm98.1 0h-29l19.6 33.9c5.5 9.6 2.2 21.8-7.3 27.3-9.6 5.5-21.8 2.2-27.3-7.3-32.9-56.9-57.5-99.7-74-128.1-16.7-29-4.8-58 7.1-67.8 13.1 22.7 32.7 56.7 58.9 102h52c11 0 20 9 20 20 0 11.1-9 20-20 20z\"],\n    \"apper\": [640, 512, [], \"f371\", \"M42.1 239.1c22.2 0 29 2.8 33.5 14.6h.8v-22.9c0-11.3-4.8-15.4-17.9-15.4-11.3 0-14.4 2.5-15.1 12.8H4.8c.3-13.9 1.5-19.1 5.8-24.4C17.9 195 29.5 192 56.7 192c33 0 47.1 5 53.9 18.9 2 4.3 4 15.6 4 23.7v76.3H76.3l1.3-19.1h-1c-5.3 15.6-13.6 20.4-35.5 20.4-30.3 0-41.1-10.1-41.1-37.3 0-25.2 12.3-35.8 42.1-35.8zm17.1 48.1c13.1 0 16.9-3 16.9-13.4 0-9.1-4.3-11.6-19.6-11.6-13.1 0-17.9 3-17.9 12.1-.1 10.4 3.7 12.9 20.6 12.9zm77.8-94.9h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.2 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3H137v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm57.9-60.7h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.3 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3h-39.5v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm53.8-3.8c0-25.4 3.3-37.8 12.3-45.8 8.8-8.1 22.2-11.3 45.1-11.3 42.8 0 55.7 12.8 55.7 55.7v11.1h-75.3c-.3 2-.3 4-.3 4.8 0 16.9 4.5 21.9 20.1 21.9 13.9 0 17.9-3 17.9-13.9h37.5v2.3c0 9.8-2.5 18.9-6.8 24.7-7.3 9.8-19.6 13.6-44.3 13.6-27.5 0-41.6-3.3-50.6-12.3-8.5-8.5-11.3-21.3-11.3-50.8zm76.4-11.6c-.3-1.8-.3-3.3-.3-3.8 0-12.3-3.3-14.6-19.6-14.6-14.4 0-17.1 3-18.1 15.1l-.3 3.3h38.3zm55.6-45.3h38.3l-1.8 19.9h.7c6.8-14.9 14.4-20.2 29.7-20.2 10.8 0 19.1 3.3 23.4 9.3 5.3 7.3 6.8 14.4 6.8 34 0 1.5 0 5 .2 9.3h-35c.3-1.8.3-3.3.3-4 0-15.4-2-19.4-10.3-19.4-6.3 0-10.8 3.3-13.1 9.3-1 3-1 4.3-1 12.3v68h-38.3V192.3z\"],\n    \"apple\": [384, 512, [], \"f179\", \"M318.7 268.7c-.2-36.7 16.4-64.4 50-84.8-18.8-26.9-47.2-41.7-84.7-44.6-35.5-2.8-74.3 20.7-88.5 20.7-15 0-49.4-19.7-76.4-19.7C63.3 141.2 4 184.8 4 273.5q0 39.3 14.4 81.2c12.8 36.7 59 126.7 107.2 125.2 25.2-.6 43-17.9 75.8-17.9 31.8 0 48.3 17.9 76.4 17.9 48.6-.7 90.4-82.5 102.6-119.3-65.2-30.7-61.7-90-61.7-91.9zm-56.6-164.2c27.3-32.4 24.8-61.9 24-72.5-24.1 1.4-52 16.4-67.9 34.9-17.5 19.8-27.8 44.3-25.6 71.9 26.1 2 49.9-11.4 69.5-34.3z\"],\n    \"apple-pay\": [640, 512, [], \"f415\", \"M116.9 158.5c-7.5 8.9-19.5 15.9-31.5 14.9-1.5-12 4.4-24.8 11.3-32.6 7.5-9.1 20.6-15.6 31.3-16.1 1.2 12.4-3.7 24.7-11.1 33.8m10.9 17.2c-17.4-1-32.3 9.9-40.5 9.9-8.4 0-21-9.4-34.8-9.1-17.9.3-34.5 10.4-43.6 26.5-18.8 32.3-4.9 80 13.3 106.3 8.9 13 19.5 27.3 33.5 26.8 13.3-.5 18.5-8.6 34.5-8.6 16.1 0 20.8 8.6 34.8 8.4 14.5-.3 23.6-13 32.5-26 10.1-14.8 14.3-29.1 14.5-29.9-.3-.3-28-10.9-28.3-42.9-.3-26.8 21.9-39.5 22.9-40.3-12.5-18.6-32-20.6-38.8-21.1m100.4-36.2v194.9h30.3v-66.6h41.9c38.3 0 65.1-26.3 65.1-64.3s-26.4-64-64.1-64h-73.2zm30.3 25.5h34.9c26.3 0 41.3 14 41.3 38.6s-15 38.8-41.4 38.8h-34.8V165zm162.2 170.9c19 0 36.6-9.6 44.6-24.9h.6v23.4h28v-97c0-28.1-22.5-46.3-57.1-46.3-32.1 0-55.9 18.4-56.8 43.6h27.3c2.3-12 13.4-19.9 28.6-19.9 18.5 0 28.9 8.6 28.9 24.5v10.8l-37.8 2.3c-35.1 2.1-54.1 16.5-54.1 41.5.1 25.2 19.7 42 47.8 42zm8.2-23.1c-16.1 0-26.4-7.8-26.4-19.6 0-12.3 9.9-19.4 28.8-20.5l33.6-2.1v11c0 18.2-15.5 31.2-36 31.2zm102.5 74.6c29.5 0 43.4-11.3 55.5-45.4L640 193h-30.8l-35.6 115.1h-.6L537.4 193h-31.6L557 334.9l-2.8 8.6c-4.6 14.6-12.1 20.3-25.5 20.3-2.4 0-7-.3-8.9-.5v23.4c1.8.4 9.3.7 11.6.7z\"],\n    \"artstation\": [512, 512, [], \"f77a\", \"M2 377.4l43 74.3A51.35 51.35 0 0 0 90.9 480h285.4l-59.2-102.6zM501.8 350L335.6 59.3A51.38 51.38 0 0 0 290.2 32h-88.4l257.3 447.6 40.7-70.5c1.9-3.2 21-29.7 2-59.1zM275 304.5l-115.5-200L44 304.5z\"],\n    \"asymmetrik\": [576, 512, [], \"f372\", \"M517.5 309.2c38.8-40 58.1-80 58.5-116.1.8-65.5-59.4-118.2-169.4-135C277.9 38.4 118.1 73.6 0 140.5 52 114 110.6 92.3 170.7 82.3c74.5-20.5 153-25.4 221.3-14.8C544.5 91.3 588.8 195 490.8 299.2c-10.2 10.8-22 21.1-35 30.6L304.9 103.4 114.7 388.9c-65.6-29.4-76.5-90.2-19.1-151.2 20.8-22.2 48.3-41.9 79.5-58.1 20-12.2 39.7-22.6 62-30.7-65.1 20.3-122.7 52.9-161.6 92.9-27.7 28.6-41.4 57.1-41.7 82.9-.5 35.1 23.4 65.1 68.4 83l-34.5 51.7h101.6l22-34.4c22.2 1 45.3 0 68.6-2.7l-22.8 37.1h135.5L340 406.3c18.6-5.3 36.9-11.5 54.5-18.7l45.9 71.8H542L468.6 349c18.5-12.1 35-25.5 48.9-39.8zm-187.6 80.5l-25-40.6-32.7 53.3c-23.4 3.5-46.7 5.1-69.2 4.4l101.9-159.3 78.7 123c-17.2 7.4-35.3 13.9-53.7 19.2z\"],\n    \"atlassian\": [512, 512, [], \"f77b\", \"M152.2 236.4c-7.7-8.2-19.7-7.7-24.8 2.8L1.6 490.2c-5 10 2.4 21.7 13.4 21.7h175c5.8.1 11-3.2 13.4-8.4 37.9-77.8 15.1-196.3-51.2-267.1zM244.4 8.1c-122.3 193.4-8.5 348.6 65 495.5 2.5 5.1 7.7 8.4 13.4 8.4H497c11.2 0 18.4-11.8 13.4-21.7 0 0-234.5-470.6-240.4-482.3-5.3-10.6-18.8-10.8-25.6.1z\"],\n    \"audible\": [640, 512, [], \"f373\", \"M640 199.9v54l-320 200L0 254v-54l320 200 320-200.1zm-194.5 72l47.1-29.4c-37.2-55.8-100.7-92.6-172.7-92.6-72 0-135.5 36.7-172.6 92.4h.3c2.5-2.3 5.1-4.5 7.7-6.7 89.7-74.4 219.4-58.1 290.2 36.3zm-220.1 18.8c16.9-11.9 36.5-18.7 57.4-18.7 34.4 0 65.2 18.4 86.4 47.6l45.4-28.4c-20.9-29.9-55.6-49.5-94.8-49.5-38.9 0-73.4 19.4-94.4 49zM103.6 161.1c131.8-104.3 318.2-76.4 417.5 62.1l.7 1 48.8-30.4C517.1 112.1 424.8 58.1 319.9 58.1c-103.5 0-196.6 53.5-250.5 135.6 9.9-10.5 22.7-23.5 34.2-32.6zm467 32.7z\"],\n    \"autoprefixer\": [640, 512, [], \"f41c\", \"M318.4 16l-161 480h77.5l25.4-81.4h119.5L405 496h77.5L318.4 16zm-40.3 341.9l41.2-130.4h1.5l40.9 130.4h-83.6zM640 405l-10-31.4L462.1 358l19.4 56.5L640 405zm-462.1-47L10 373.7 0 405l158.5 9.4 19.4-56.4z\"],\n    \"avianex\": [512, 512, [], \"f374\", \"M453.1 32h-312c-38.9 0-76.2 31.2-83.3 69.7L1.2 410.3C-5.9 448.8 19.9 480 58.9 480h312c38.9 0 76.2-31.2 83.3-69.7l56.7-308.5c7-38.6-18.8-69.8-57.8-69.8zm-58.2 347.3l-32 13.5-115.4-110c-14.7 10-29.2 19.5-41.7 27.1l22.1 64.2-17.9 12.7-40.6-61-52.4-48.1 15.7-15.4 58 31.1c9.3-10.5 20.8-22.6 32.8-34.9L203 228.9l-68.8-99.8 18.8-28.9 8.9-4.8L265 207.8l4.9 4.5c19.4-18.8 33.8-32.4 33.8-32.4 7.7-6.5 21.5-2.9 30.7 7.9 9 10.5 10.6 24.7 2.7 31.3-1.8 1.3-15.5 11.4-35.3 25.6l4.5 7.3 94.9 119.4-6.3 7.9z\"],\n    \"aviato\": [640, 512, [], \"f421\", \"M107.2 283.5l-19-41.8H36.1l-19 41.8H0l62.2-131.4 62.2 131.4h-17.2zm-45-98.1l-19.6 42.5h39.2l-19.6-42.5zm112.7 102.4l-62.2-131.4h17.1l45.1 96 45.1-96h17l-62.1 131.4zm80.6-4.3V156.4H271v127.1h-15.5zm209.1-115.6v115.6h-17.3V167.9h-41.2v-11.5h99.6v11.5h-41.1zM640 218.8c0 9.2-1.7 17.8-5.1 25.8-3.4 8-8.2 15.1-14.2 21.1-6 6-13.1 10.8-21.1 14.2-8 3.4-16.6 5.1-25.8 5.1s-17.8-1.7-25.8-5.1c-8-3.4-15.1-8.2-21.1-14.2-6-6-10.8-13-14.2-21.1-3.4-8-5.1-16.6-5.1-25.8s1.7-17.8 5.1-25.8c3.4-8 8.2-15.1 14.2-21.1 6-6 13-8.4 21.1-11.9 8-3.4 16.6-5.1 25.8-5.1s17.8 1.7 25.8 5.1c8 3.4 15.1 5.8 21.1 11.9 6 6 10.7 13.1 14.2 21.1 3.4 8 5.1 16.6 5.1 25.8zm-15.5 0c0-7.3-1.3-14-3.9-20.3-2.6-6.3-6.2-11.7-10.8-16.3-4.6-4.6-10-8.2-16.2-10.9-6.2-2.7-12.8-4-19.8-4s-13.6 1.3-19.8 4c-6.2 2.7-11.6 6.3-16.2 10.9-4.6 4.6-8.2 10-10.8 16.3-2.6 6.3-3.9 13.1-3.9 20.3 0 7.3 1.3 14 3.9 20.3 2.6 6.3 6.2 11.7 10.8 16.3 4.6 4.6 10 8.2 16.2 10.9 6.2 2.7 12.8 4 19.8 4s13.6-1.3 19.8-4c6.2-2.7 11.6-6.3 16.2-10.9 4.6-4.6 8.2-10 10.8-16.3 2.6-6.3 3.9-13.1 3.9-20.3zm-94.8 96.7v-6.3l88.9-10-242.9 13.4c.6-2.2 1.1-4.6 1.4-7.2.3-2 .5-4.2.6-6.5l64.8-8.1-64.9 1.9c0-.4-.1-.7-.1-1.1-2.8-17.2-25.5-23.7-25.5-23.7l-1.1-26.3h23.8l19 41.8h17.1L348.6 152l-62.2 131.4h17.1l19-41.8h23.6L345 268s-22.7 6.5-25.5 23.7c-.1.3-.1.7-.1 1.1l-64.9-1.9 64.8 8.1c.1 2.3.3 4.4.6 6.5.3 2.6.8 5 1.4 7.2L78.4 299.2l88.9 10v6.3c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4 0-6.2-4.6-11.3-10.5-12.2v-5.8l80.3 9v5.4c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-4.9l28.4 3.2v23.7h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9V323l38.3 4.3c8.1 11.4 19 13.6 19 13.6l-.1 6.7-5.1.2-.1 12.1h4.1l.1-5h5.2l.1 5h4.1l-.1-12.1-5.1-.2-.1-6.7s10.9-2.1 19-13.6l38.3-4.3v23.2h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9v-23.7l28.4-3.2v4.9c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-5.4l80.3-9v5.8c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4-.2-6.3-4.7-11.4-10.7-12.3zm-200.8-87.6l19.6-42.5 19.6 42.5h-17.9l-1.7-40.3-1.7 40.3h-17.9z\"],\n    \"aws\": [640, 512, [], \"f375\", \"M180.41 203.01c-.72 22.65 10.6 32.68 10.88 39.05a8.164 8.164 0 0 1-4.1 6.27l-12.8 8.96a10.66 10.66 0 0 1-5.63 1.92c-.43-.02-8.19 1.83-20.48-25.61a78.608 78.608 0 0 1-62.61 29.45c-16.28.89-60.4-9.24-58.13-56.21-1.59-38.28 34.06-62.06 70.93-60.05 7.1.02 21.6.37 46.99 6.27v-15.62c2.69-26.46-14.7-46.99-44.81-43.91-2.4.01-19.4-.5-45.84 10.11-7.36 3.38-8.3 2.82-10.75 2.82-7.41 0-4.36-21.48-2.94-24.2 5.21-6.4 35.86-18.35 65.94-18.18a76.857 76.857 0 0 1 55.69 17.28 70.285 70.285 0 0 1 17.67 52.36l-.01 69.29zM93.99 235.4c32.43-.47 46.16-19.97 49.29-30.47 2.46-10.05 2.05-16.41 2.05-27.4-9.67-2.32-23.59-4.85-39.56-4.87-15.15-1.14-42.82 5.63-41.74 32.26-1.24 16.79 11.12 31.4 29.96 30.48zm170.92 23.05c-7.86.72-11.52-4.86-12.68-10.37l-49.8-164.65c-.97-2.78-1.61-5.65-1.92-8.58a4.61 4.61 0 0 1 3.86-5.25c.24-.04-2.13 0 22.25 0 8.78-.88 11.64 6.03 12.55 10.37l35.72 140.83 33.16-140.83c.53-3.22 2.94-11.07 12.8-10.24h17.16c2.17-.18 11.11-.5 12.68 10.37l33.42 142.63L420.98 80.1c.48-2.18 2.72-11.37 12.68-10.37h19.72c.85-.13 6.15-.81 5.25 8.58-.43 1.85 3.41-10.66-52.75 169.9-1.15 5.51-4.82 11.09-12.68 10.37h-18.69c-10.94 1.15-12.51-9.66-12.68-10.75L328.67 110.7l-32.78 136.99c-.16 1.09-1.73 11.9-12.68 10.75h-18.3zm273.48 5.63c-5.88.01-33.92-.3-57.36-12.29a12.802 12.802 0 0 1-7.81-11.91v-10.75c0-8.45 6.2-6.9 8.83-5.89 10.04 4.06 16.48 7.14 28.81 9.6 36.65 7.53 52.77-2.3 56.72-4.48 13.15-7.81 14.19-25.68 5.25-34.95-10.48-8.79-15.48-9.12-53.13-21-4.64-1.29-43.7-13.61-43.79-52.36-.61-28.24 25.05-56.18 69.52-55.95 12.67-.01 46.43 4.13 55.57 15.62 1.35 2.09 2.02 4.55 1.92 7.04v10.11c0 4.44-1.62 6.66-4.87 6.66-7.71-.86-21.39-11.17-49.16-10.75-6.89-.36-39.89.91-38.41 24.97-.43 18.96 26.61 26.07 29.7 26.89 36.46 10.97 48.65 12.79 63.12 29.58 17.14 22.25 7.9 48.3 4.35 55.44-19.08 37.49-68.42 34.44-69.26 34.42zm40.2 104.86c-70.03 51.72-171.69 79.25-258.49 79.25A469.127 469.127 0 0 1 2.83 327.46c-6.53-5.89-.77-13.96 7.17-9.47a637.37 637.37 0 0 0 316.88 84.12 630.22 630.22 0 0 0 241.59-49.55c11.78-5 21.77 7.8 10.12 16.38zm29.19-33.29c-8.96-11.52-59.28-5.38-81.81-2.69-6.79.77-7.94-5.12-1.79-9.47 40.07-28.17 105.88-20.1 113.44-10.63 7.55 9.47-2.05 75.41-39.56 106.91-5.76 4.87-11.27 2.3-8.71-4.1 8.44-21.25 27.39-68.49 18.43-80.02z\"],\n    \"bandcamp\": [496, 512, [], \"f2d5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm48.2 326.1h-181L199.9 178h181l-84.7 156.1z\"],\n    \"battle-net\": [512, 512, [], \"f835\", \"M448.61 225.62c26.87.18 35.57-7.43 38.92-12.37 12.47-16.32-7.06-47.6-52.85-71.33 17.76-33.58 30.11-63.68 36.34-85.3 3.38-11.83 1.09-19 .45-20.25-1.72 10.52-15.85 48.46-48.2 100.05-25-11.22-56.52-20.1-93.77-23.8-8.94-16.94-34.88-63.86-60.48-88.93C252.18 7.14 238.7 1.07 228.18.22h-.05c-13.83-1.55-22.67 5.85-27.4 11-17.2 18.53-24.33 48.87-25 84.07-7.24-12.35-17.17-24.63-28.5-25.93h-.18c-20.66-3.48-38.39 29.22-36 81.29-38.36 1.38-71 5.75-93 11.23-9.9 2.45-16.22 7.27-17.76 9.72 1-.38 22.4-9.22 111.56-9.22 5.22 53 29.75 101.82 26 93.19-9.73 15.4-38.24 62.36-47.31 97.7-5.87 22.88-4.37 37.61.15 47.14 5.57 12.75 16.41 16.72 23.2 18.26 25 5.71 55.38-3.63 86.7-21.14-7.53 12.84-13.9 28.51-9.06 39.34 7.31 19.65 44.49 18.66 88.44-9.45 20.18 32.18 40.07 57.94 55.7 74.12a39.79 39.79 0 0 0 8.75 7.09c5.14 3.21 8.58 3.37 8.58 3.37-8.24-6.75-34-38-62.54-91.78 22.22-16 45.65-38.87 67.47-69.27 122.82 4.6 143.29-24.76 148-31.64 14.67-19.88 3.43-57.44-57.32-93.69zm-77.85 106.22c23.81-37.71 30.34-67.77 29.45-92.33 27.86 17.57 47.18 37.58 49.06 58.83 1.14 12.93-8.1 29.12-78.51 33.5zM216.9 387.69c9.76-6.23 19.53-13.12 29.2-20.49 6.68 13.33 13.6 26.1 20.6 38.19-40.6 21.86-68.84 12.76-49.8-17.7zm215-171.35c-10.29-5.34-21.16-10.34-32.38-15.05a722.459 722.459 0 0 0 22.74-36.9c39.06 24.1 45.9 53.18 9.64 51.95zM279.18 398c-5.51-11.35-11-23.5-16.5-36.44 43.25 1.27 62.42-18.73 63.28-20.41 0 .07-25 15.64-62.53 12.25a718.78 718.78 0 0 0 85.06-84q13.06-15.31 24.93-31.11c-.36-.29-1.54-3-16.51-12-51.7 60.27-102.34 98-132.75 115.92-20.59-11.18-40.84-31.78-55.71-61.49-20-39.92-30-82.39-31.57-116.07 12.3.91 25.27 2.17 38.85 3.88-22.29 36.8-14.39 63-13.47 64.23 0-.07-.95-29.17 20.14-59.57a695.23 695.23 0 0 0 44.67 152.84c.93-.38 1.84.88 18.67-8.25-26.33-74.47-33.76-138.17-34-173.43 20-12.42 48.18-19.8 81.63-17.81 44.57 2.67 86.36 15.25 116.32 30.71q-10.69 15.66-23.33 32.47C365.63 152 339.1 145.84 337.5 146c.11 0 25.9 14.07 41.52 47.22a717.63 717.63 0 0 0-115.34-31.71 646.608 646.608 0 0 0-39.39-6.05c-.07.45-1.81 1.85-2.16 20.33C300 190.28 358.78 215.68 389.36 233c.74 23.55-6.95 51.61-25.41 79.57-24.6 37.31-56.39 67.23-84.77 85.43zm27.4-287c-44.56-1.66-73.58 7.43-94.69 20.67 2-52.3 21.31-76.38 38.21-75.28C267 52.15 305 108.55 306.58 111zm-130.65 3.1c.48 12.11 1.59 24.62 3.21 37.28-14.55-.85-28.74-1.25-42.4-1.26-.08 3.24-.12-51 24.67-49.59h.09c5.76 1.09 10.63 6.88 14.43 13.57zm-28.06 162c20.76 39.7 43.3 60.57 65.25 72.31-46.79 24.76-77.53 20-84.92 4.51-.2-.21-11.13-15.3 19.67-76.81zm210.06 74.8\"],\n    \"behance\": [576, 512, [], \"f1b4\", \"M232 237.2c31.8-15.2 48.4-38.2 48.4-74 0-70.6-52.6-87.8-113.3-87.8H0v354.4h171.8c64.4 0 124.9-30.9 124.9-102.9 0-44.5-21.1-77.4-64.7-89.7zM77.9 135.9H151c28.1 0 53.4 7.9 53.4 40.5 0 30.1-19.7 42.2-47.5 42.2h-79v-82.7zm83.3 233.7H77.9V272h84.9c34.3 0 56 14.3 56 50.6 0 35.8-25.9 47-57.6 47zm358.5-240.7H376V94h143.7v34.9zM576 305.2c0-75.9-44.4-139.2-124.9-139.2-78.2 0-131.3 58.8-131.3 135.8 0 79.9 50.3 134.7 131.3 134.7 61.3 0 101-27.6 120.1-86.3H509c-6.7 21.9-34.3 33.5-55.7 33.5-41.3 0-63-24.2-63-65.3h185.1c.3-4.2.6-8.7.6-13.2zM390.4 274c2.3-33.7 24.7-54.8 58.5-54.8 35.4 0 53.2 20.8 56.2 54.8H390.4z\"],\n    \"behance-square\": [448, 512, [], \"f1b5\", \"M186.5 293c0 19.3-14 25.4-31.2 25.4h-45.1v-52.9h46c18.6.1 30.3 7.8 30.3 27.5zm-7.7-82.3c0-17.7-13.7-21.9-28.9-21.9h-39.6v44.8H153c15.1 0 25.8-6.6 25.8-22.9zm132.3 23.2c-18.3 0-30.5 11.4-31.7 29.7h62.2c-1.7-18.5-11.3-29.7-30.5-29.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM271.7 185h77.8v-18.9h-77.8V185zm-43 110.3c0-24.1-11.4-44.9-35-51.6 17.2-8.2 26.2-17.7 26.2-37 0-38.2-28.5-47.5-61.4-47.5H68v192h93.1c34.9-.2 67.6-16.9 67.6-55.9zM380 280.5c0-41.1-24.1-75.4-67.6-75.4-42.4 0-71.1 31.8-71.1 73.6 0 43.3 27.3 73 71.1 73 33.2 0 54.7-14.9 65.1-46.8h-33.7c-3.7 11.9-18.6 18.1-30.2 18.1-22.4 0-34.1-13.1-34.1-35.3h100.2c.1-2.3.3-4.8.3-7.2z\"],\n    \"bimobject\": [448, 512, [], \"f378\", \"M416 32H32C14.4 32 0 46.4 0 64v384c0 17.6 14.4 32 32 32h384c17.6 0 32-14.4 32-32V64c0-17.6-14.4-32-32-32zm-64 257.4c0 49.4-11.4 82.6-103.8 82.6h-16.9c-44.1 0-62.4-14.9-70.4-38.8h-.9V368H96V136h64v74.7h1.1c4.6-30.5 39.7-38.8 69.7-38.8h17.3c92.4 0 103.8 33.1 103.8 82.5v35zm-64-28.9v22.9c0 21.7-3.4 33.8-38.4 33.8h-45.3c-28.9 0-44.1-6.5-44.1-35.7v-19c0-29.3 15.2-35.7 44.1-35.7h45.3c35-.2 38.4 12 38.4 33.7z\"],\n    \"bitbucket\": [512, 512, [], \"f171\", \"M22.2 32A16 16 0 0 0 6 47.8a26.35 26.35 0 0 0 .2 2.8l67.9 412.1a21.77 21.77 0 0 0 21.3 18.2h325.7a16 16 0 0 0 16-13.4L505 50.7a16 16 0 0 0-13.2-18.3 24.58 24.58 0 0 0-2.8-.2L22.2 32zm285.9 297.8h-104l-28.1-147h157.3l-25.2 147z\"],\n    \"bitcoin\": [512, 512, [], \"f379\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-141.651-35.33c4.937-32.999-20.191-50.739-54.55-62.573l11.146-44.702-27.213-6.781-10.851 43.524c-7.154-1.783-14.502-3.464-21.803-5.13l10.929-43.81-27.198-6.781-11.153 44.686c-5.922-1.349-11.735-2.682-17.377-4.084l.031-.14-37.53-9.37-7.239 29.062s20.191 4.627 19.765 4.913c11.022 2.751 13.014 10.044 12.68 15.825l-12.696 50.925c.76.194 1.744.473 2.829.907-.907-.225-1.876-.473-2.876-.713l-17.796 71.338c-1.349 3.348-4.767 8.37-12.471 6.464.271.395-19.78-4.937-19.78-4.937l-13.51 31.147 35.414 8.827c6.588 1.651 13.045 3.379 19.4 5.006l-11.262 45.213 27.182 6.781 11.153-44.733a1038.209 1038.209 0 0 0 21.687 5.627l-11.115 44.523 27.213 6.781 11.262-45.128c46.404 8.781 81.299 5.239 95.986-36.727 11.836-33.79-.589-53.281-25.004-65.991 17.78-4.098 31.174-15.792 34.747-39.949zm-62.177 87.179c-8.41 33.79-65.308 15.523-83.755 10.943l14.944-59.899c18.446 4.603 77.6 13.717 68.811 48.956zm8.417-87.667c-7.673 30.736-55.031 15.12-70.393 11.292l13.548-54.327c15.363 3.828 64.836 10.973 56.845 43.035z\"],\n    \"bity\": [496, 512, [], \"f37a\", \"M78.4 67.2C173.8-22 324.5-24 421.5 71c14.3 14.1-6.4 37.1-22.4 21.5-84.8-82.4-215.8-80.3-298.9-3.2-16.3 15.1-36.5-8.3-21.8-22.1zm98.9 418.6c19.3 5.7 29.3-23.6 7.9-30C73 421.9 9.4 306.1 37.7 194.8c5-19.6-24.9-28.1-30.2-7.1-32.1 127.4 41.1 259.8 169.8 298.1zm148.1-2c121.9-40.2 192.9-166.9 164.4-291-4.5-19.7-34.9-13.8-30 7.9 24.2 107.7-37.1 217.9-143.2 253.4-21.2 7-10.4 36 8.8 29.7zm-62.9-79l.2-71.8c0-8.2-6.6-14.8-14.8-14.8-8.2 0-14.8 6.7-14.8 14.8l-.2 71.8c0 8.2 6.6 14.8 14.8 14.8s14.8-6.6 14.8-14.8zm71-269c2.1 90.9 4.7 131.9-85.5 132.5-92.5-.7-86.9-44.3-85.5-132.5 0-21.8-32.5-19.6-32.5 0v71.6c0 69.3 60.7 90.9 118 90.1 57.3.8 118-20.8 118-90.1v-71.6c0-19.6-32.5-21.8-32.5 0z\"],\n    \"black-tie\": [448, 512, [], \"f27e\", \"M0 32v448h448V32H0zm316.5 325.2L224 445.9l-92.5-88.7 64.5-184-64.5-86.6h184.9L252 173.2l64.5 184z\"],\n    \"blackberry\": [512, 512, [], \"f37b\", \"M166 116.9c0 23.4-16.4 49.1-72.5 49.1H23.4l21-88.8h67.8c42.1 0 53.8 23.3 53.8 39.7zm126.2-39.7h-67.8L205.7 166h70.1c53.8 0 70.1-25.7 70.1-49.1.1-16.4-11.6-39.7-53.7-39.7zM88.8 208.1H21L0 296.9h70.1c56.1 0 72.5-23.4 72.5-49.1 0-16.3-11.7-39.7-53.8-39.7zm180.1 0h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1 0-16.3-11.7-39.7-53.7-39.7zm189.3-53.8h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7zm-28 137.9h-67.8L343.7 381h70.1c56.1 0 70.1-23.4 70.1-49.1 0-16.3-11.6-39.7-53.7-39.7zM240.8 346H173l-18.7 88.8h70.1c56.1 0 70.1-25.7 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7z\"],\n    \"blogger\": [448, 512, [], \"f37c\", \"M162.4 196c4.8-4.9 6.2-5.1 36.4-5.1 27.2 0 28.1.1 32.1 2.1 5.8 2.9 8.3 7 8.3 13.6 0 5.9-2.4 10-7.6 13.4-2.8 1.8-4.5 1.9-31.1 2.1-16.4.1-29.5-.2-31.5-.8-10.3-2.9-14.1-17.7-6.6-25.3zm61.4 94.5c-53.9 0-55.8.2-60.2 4.1-3.5 3.1-5.7 9.4-5.1 13.9.7 4.7 4.8 10.1 9.2 12 2.2 1 14.1 1.7 56.3 1.2l47.9-.6 9.2-1.5c9-5.1 10.5-17.4 3.1-24.4-5.3-4.7-5-4.7-60.4-4.7zm223.4 130.1c-3.5 28.4-23 50.4-51.1 57.5-7.2 1.8-9.7 1.9-172.9 1.8-157.8 0-165.9-.1-172-1.8-8.4-2.2-15.6-5.5-22.3-10-5.6-3.8-13.9-11.8-17-16.4-3.8-5.6-8.2-15.3-10-22C.1 423 0 420.3 0 256.3 0 93.2 0 89.7 1.8 82.6 8.1 57.9 27.7 39 53 33.4c7.3-1.6 332.1-1.9 340-.3 21.2 4.3 37.9 17.1 47.6 36.4 7.7 15.3 7-1.5 7.3 180.6.2 115.8 0 164.5-.7 170.5zm-85.4-185.2c-1.1-5-4.2-9.6-7.7-11.5-1.1-.6-8-1.3-15.5-1.7-12.4-.6-13.8-.8-17.8-3.1-6.2-3.6-7.9-7.6-8-18.3 0-20.4-8.5-39.4-25.3-56.5-12-12.2-25.3-20.5-40.6-25.1-3.6-1.1-11.8-1.5-39.2-1.8-42.9-.5-52.5.4-67.1 6.2-27 10.7-46.3 33.4-53.4 62.4-1.3 5.4-1.6 14.2-1.9 64.3-.4 62.8 0 72.1 4 84.5 9.7 30.7 37.1 53.4 64.6 58.4 9.2 1.7 122.2 2.1 133.7.5 20.1-2.7 35.9-10.8 50.7-25.9 10.7-10.9 17.4-22.8 21.8-38.5 3.2-10.9 2.9-88.4 1.7-93.9z\"],\n    \"blogger-b\": [448, 512, [], \"f37d\", \"M446.6 222.7c-1.8-8-6.8-15.4-12.5-18.5-1.8-1-13-2.2-25-2.7-20.1-.9-22.3-1.3-28.7-5-10.1-5.9-12.8-12.3-12.9-29.5-.1-33-13.8-63.7-40.9-91.3-19.3-19.7-40.9-33-65.5-40.5-5.9-1.8-19.1-2.4-63.3-2.9-69.4-.8-84.8.6-108.4 10C45.9 59.5 14.7 96.1 3.3 142.9 1.2 151.7.7 165.8.2 246.8c-.6 101.5.1 116.4 6.4 136.5 15.6 49.6 59.9 86.3 104.4 94.3 14.8 2.7 197.3 3.3 216 .8 32.5-4.4 58-17.5 81.9-41.9 17.3-17.7 28.1-36.8 35.2-62.1 4.9-17.6 4.5-142.8 2.5-151.7zm-322.1-63.6c7.8-7.9 10-8.2 58.8-8.2 43.9 0 45.4.1 51.8 3.4 9.3 4.7 13.4 11.3 13.4 21.9 0 9.5-3.8 16.2-12.3 21.6-4.6 2.9-7.3 3.1-50.3 3.3-26.5.2-47.7-.4-50.8-1.2-16.6-4.7-22.8-28.5-10.6-40.8zm191.8 199.8l-14.9 2.4-77.5.9c-68.1.8-87.3-.4-90.9-2-7.1-3.1-13.8-11.7-14.9-19.4-1.1-7.3 2.6-17.3 8.2-22.4 7.1-6.4 10.2-6.6 97.3-6.7 89.6-.1 89.1-.1 97.6 7.8 12.1 11.3 9.5 31.2-4.9 39.4z\"],\n    \"bluetooth\": [448, 512, [], \"f293\", \"M292.6 171.1L249.7 214l-.3-86 43.2 43.1m-43.2 219.8l43.1-43.1-42.9-42.9-.2 86zM416 259.4C416 465 344.1 512 230.9 512S32 465 32 259.4 115.4 0 228.6 0 416 53.9 416 259.4zm-158.5 0l79.4-88.6L211.8 36.5v176.9L138 139.6l-27 26.9 92.7 93-92.7 93 26.9 26.9 73.8-73.8 2.3 170 127.4-127.5-83.9-88.7z\"],\n    \"bluetooth-b\": [320, 512, [], \"f294\", \"M196.48 260.023l92.626-103.333L143.125 0v206.33l-86.111-86.111-31.406 31.405 108.061 108.399L25.608 368.422l31.406 31.405 86.111-86.111L145.84 512l148.552-148.644-97.912-103.333zm40.86-102.996l-49.977 49.978-.338-100.295 50.315 50.317zM187.363 313.04l49.977 49.978-50.315 50.316.338-100.294z\"],\n    \"bootstrap\": [448, 512, [], \"f836\", \"M292.3 311.93c0 42.41-39.72 41.43-43.92 41.43h-80.89v-81.69h80.89c42.56 0 43.92 31.9 43.92 40.26zm-50.15-73.13c.67 0 38.44 1 38.44-36.31 0-15.52-3.51-35.87-38.44-35.87h-74.66v72.18h74.66zM448 106.67v298.66A74.89 74.89 0 0 1 373.33 480H74.67A74.89 74.89 0 0 1 0 405.33V106.67A74.89 74.89 0 0 1 74.67 32h298.66A74.89 74.89 0 0 1 448 106.67zM338.05 317.86c0-21.57-6.65-58.29-49.05-67.35v-.73c22.91-9.78 37.34-28.25 37.34-55.64 0-7 2-64.78-77.6-64.78h-127v261.33c128.23 0 139.87 1.68 163.6-5.71 14.21-4.42 52.71-17.98 52.71-67.12z\"],\n    \"btc\": [384, 512, [], \"f15a\", \"M310.204 242.638c27.73-14.18 45.377-39.39 41.28-81.3-5.358-57.351-52.458-76.573-114.85-81.929V0h-48.528v77.203c-12.605 0-25.525.315-38.444.63V0h-48.528v79.409c-17.842.539-38.622.276-97.37 0v51.678c38.314-.678 58.417-3.14 63.023 21.427v217.429c-2.925 19.492-18.524 16.685-53.255 16.071L3.765 443.68c88.481 0 97.37.315 97.37.315V512h48.528v-67.06c13.234.315 26.154.315 38.444.315V512h48.528v-68.005c81.299-4.412 135.647-24.894 142.895-101.467 5.671-61.446-23.32-88.862-69.326-99.89zM150.608 134.553c27.415 0 113.126-8.507 113.126 48.528 0 54.515-85.71 48.212-113.126 48.212v-96.74zm0 251.776V279.821c32.772 0 133.127-9.138 133.127 53.255-.001 60.186-100.355 53.253-133.127 53.253z\"],\n    \"buffer\": [448, 512, [], \"f837\", \"M427.84 380.67l-196.5 97.82a18.6 18.6 0 0 1-14.67 0L20.16 380.67c-4-2-4-5.28 0-7.29L67.22 350a18.65 18.65 0 0 1 14.69 0l134.76 67a18.51 18.51 0 0 0 14.67 0l134.76-67a18.62 18.62 0 0 1 14.68 0l47.06 23.43c4.05 1.96 4.05 5.24 0 7.24zm0-136.53l-47.06-23.43a18.62 18.62 0 0 0-14.68 0l-134.76 67.08a18.68 18.68 0 0 1-14.67 0L81.91 220.71a18.65 18.65 0 0 0-14.69 0l-47.06 23.43c-4 2-4 5.29 0 7.31l196.51 97.8a18.6 18.6 0 0 0 14.67 0l196.5-97.8c4.05-2.02 4.05-5.3 0-7.31zM20.16 130.42l196.5 90.29a20.08 20.08 0 0 0 14.67 0l196.51-90.29c4-1.86 4-4.89 0-6.74L231.33 33.4a19.88 19.88 0 0 0-14.67 0l-196.5 90.28c-4.05 1.85-4.05 4.88 0 6.74z\"],\n    \"buromobelexperte\": [448, 512, [], \"f37f\", \"M0 32v128h128V32H0zm120 120H8V40h112v112zm40-120v128h128V32H160zm120 120H168V40h112v112zm40-120v128h128V32H320zm120 120H328V40h112v112zM0 192v128h128V192H0zm120 120H8V200h112v112zm40-120v128h128V192H160zm120 120H168V200h112v112zm40-120v128h128V192H320zm120 120H328V200h112v112zM0 352v128h128V352H0zm120 120H8V360h112v112zm40-120v128h128V352H160zm120 120H168V360h112v112zm40-120v128h128V352H320z\"],\n    \"buysellads\": [448, 512, [], \"f20d\", \"M224 150.7l42.9 160.7h-85.8L224 150.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-65.3 325.3l-94.5-298.7H159.8L65.3 405.3H156l111.7-91.6 24.2 91.6h90.8z\"],\n    \"canadian-maple-leaf\": [512, 512, [], \"f785\", \"M383.8 351.7c2.5-2.5 105.2-92.4 105.2-92.4l-17.5-7.5c-10-4.9-7.4-11.5-5-17.4 2.4-7.6 20.1-67.3 20.1-67.3s-47.7 10-57.7 12.5c-7.5 2.4-10-2.5-12.5-7.5s-15-32.4-15-32.4-52.6 59.9-55.1 62.3c-10 7.5-20.1 0-17.6-10 0-10 27.6-129.6 27.6-129.6s-30.1 17.4-40.1 22.4c-7.5 5-12.6 5-17.6-5C293.5 72.3 255.9 0 255.9 0s-37.5 72.3-42.5 79.8c-5 10-10 10-17.6 5-10-5-40.1-22.4-40.1-22.4S183.3 182 183.3 192c2.5 10-7.5 17.5-17.6 10-2.5-2.5-55.1-62.3-55.1-62.3S98.1 167 95.6 172s-5 9.9-12.5 7.5C73 177 25.4 167 25.4 167s17.6 59.7 20.1 67.3c2.4 6 5 12.5-5 17.4L23 259.3s102.6 89.9 105.2 92.4c5.1 5 10 7.5 5.1 22.5-5.1 15-10.1 35.1-10.1 35.1s95.2-20.1 105.3-22.6c8.7-.9 18.3 2.5 18.3 12.5S241 512 241 512h30s-5.8-102.7-5.8-112.8 9.5-13.4 18.4-12.5c10 2.5 105.2 22.6 105.2 22.6s-5-20.1-10-35.1 0-17.5 5-22.5z\"],\n    \"cc-amazon-pay\": [576, 512, [], \"f42d\", \"M124.7 201.8c.1-11.8 0-23.5 0-35.3v-35.3c0-1.3.4-2 1.4-2.7 11.5-8 24.1-12.1 38.2-11.1 12.5.9 22.7 7 28.1 21.7 3.3 8.9 4.1 18.2 4.1 27.7 0 8.7-.7 17.3-3.4 25.6-5.7 17.8-18.7 24.7-35.7 23.9-11.7-.5-21.9-5-31.4-11.7-.9-.8-1.4-1.6-1.3-2.8zm154.9 14.6c4.6 1.8 9.3 2 14.1 1.5 11.6-1.2 21.9-5.7 31.3-12.5.9-.6 1.3-1.3 1.3-2.5-.1-3.9 0-7.9 0-11.8 0-4-.1-8 0-12 0-1.4-.4-2-1.8-2.2-7-.9-13.9-2.2-20.9-2.9-7-.6-14-.3-20.8 1.9-6.7 2.2-11.7 6.2-13.7 13.1-1.6 5.4-1.6 10.8.1 16.2 1.6 5.5 5.2 9.2 10.4 11.2zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zm-207.5 23.9c.4 1.7.9 3.4 1.6 5.1 16.5 40.6 32.9 81.3 49.5 121.9 1.4 3.5 1.7 6.4.2 9.9-2.8 6.2-4.9 12.6-7.8 18.7-2.6 5.5-6.7 9.5-12.7 11.2-4.2 1.1-8.5 1.3-12.9.9-2.1-.2-4.2-.7-6.3-.8-2.8-.2-4.2 1.1-4.3 4-.1 2.8-.1 5.6 0 8.3.1 4.6 1.6 6.7 6.2 7.5 4.7.8 9.4 1.6 14.2 1.7 14.3.3 25.7-5.4 33.1-17.9 2.9-4.9 5.6-10.1 7.7-15.4 19.8-50.1 39.5-100.3 59.2-150.5.6-1.5 1.1-3 1.3-4.6.4-2.4-.7-3.6-3.1-3.7-5.6-.1-11.1 0-16.7 0-3.1 0-5.3 1.4-6.4 4.3-.4 1.1-.9 2.3-1.3 3.4l-29.1 83.7c-2.1 6.1-4.2 12.1-6.5 18.6-.4-.9-.6-1.4-.8-1.9-10.8-29.9-21.6-59.9-32.4-89.8-1.7-4.7-3.5-9.5-5.3-14.2-.9-2.5-2.7-4-5.4-4-6.4-.1-12.8-.2-19.2-.1-2.2 0-3.3 1.6-2.8 3.7zM242.4 206c1.7 11.7 7.6 20.8 18 26.6 9.9 5.5 20.7 6.2 31.7 4.6 12.7-1.9 23.9-7.3 33.8-15.5.4-.3.8-.6 1.4-1 .5 3.2.9 6.2 1.5 9.2.5 2.6 2.1 4.3 4.5 4.4 4.6.1 9.1.1 13.7 0 2.3-.1 3.8-1.6 4-3.9.1-.8.1-1.6.1-2.3v-88.8c0-3.6-.2-7.2-.7-10.8-1.6-10.8-6.2-19.7-15.9-25.4-5.6-3.3-11.8-5-18.2-5.9-3-.4-6-.7-9.1-1.1h-10c-.8.1-1.6.3-2.5.3-8.2.4-16.3 1.4-24.2 3.5-5.1 1.3-10 3.2-15 4.9-3 1-4.5 3.2-4.4 6.5.1 2.8-.1 5.6 0 8.3.1 4.1 1.8 5.2 5.7 4.1 6.5-1.7 13.1-3.5 19.7-4.8 10.3-1.9 20.7-2.7 31.1-1.2 5.4.8 10.5 2.4 14.1 7 3.1 4 4.2 8.8 4.4 13.7.3 6.9.2 13.9.3 20.8 0 .4-.1.7-.2 1.2-.4 0-.8 0-1.1-.1-8.8-2.1-17.7-3.6-26.8-4.1-9.5-.5-18.9.1-27.9 3.2-10.8 3.8-19.5 10.3-24.6 20.8-4.1 8.3-4.6 17-3.4 25.8zM98.7 106.9v175.3c0 .8 0 1.7.1 2.5.2 2.5 1.7 4.1 4.1 4.2 5.9.1 11.8.1 17.7 0 2.5 0 4-1.7 4.1-4.1.1-.8.1-1.7.1-2.5v-60.7c.9.7 1.4 1.2 1.9 1.6 15 12.5 32.2 16.6 51.1 12.9 17.1-3.4 28.9-13.9 36.7-29.2 5.8-11.6 8.3-24.1 8.7-37 .5-14.3-1-28.4-6.8-41.7-7.1-16.4-18.9-27.3-36.7-30.9-2.7-.6-5.5-.8-8.2-1.2h-7c-1.2.2-2.4.3-3.6.5-11.7 1.4-22.3 5.8-31.8 12.7-2 1.4-3.9 3-5.9 4.5-.1-.5-.3-.8-.4-1.2-.4-2.3-.7-4.6-1.1-6.9-.6-3.9-2.5-5.5-6.4-5.6h-9.7c-5.9-.1-6.9 1-6.9 6.8zM493.6 339c-2.7-.7-5.1 0-7.6 1-43.9 18.4-89.5 30.2-136.8 35.8-14.5 1.7-29.1 2.8-43.7 3.2-26.6.7-53.2-.8-79.6-4.3-17.8-2.4-35.5-5.7-53-9.9-37-8.9-72.7-21.7-106.7-38.8-8.8-4.4-17.4-9.3-26.1-14-3.8-2.1-6.2-1.5-8.2 2.1v1.7c1.2 1.6 2.2 3.4 3.7 4.8 36 32.2 76.6 56.5 122 72.9 21.9 7.9 44.4 13.7 67.3 17.5 14 2.3 28 3.8 42.2 4.5 3 .1 6 .2 9 .4.7 0 1.4.2 2.1.3h17.7c.7-.1 1.4-.3 2.1-.3 14.9-.4 29.8-1.8 44.6-4 21.4-3.2 42.4-8.1 62.9-14.7 29.6-9.6 57.7-22.4 83.4-40.1 2.8-1.9 5.7-3.8 8-6.2 4.3-4.4 2.3-10.4-3.3-11.9zm50.4-27.7c-.8-4.2-4-5.8-7.6-7-5.7-1.9-11.6-2.8-17.6-3.3-11-.9-22-.4-32.8 1.6-12 2.2-23.4 6.1-33.5 13.1-1.2.8-2.4 1.8-3.1 3-.6.9-.7 2.3-.5 3.4.3 1.3 1.7 1.6 3 1.5.6 0 1.2 0 1.8-.1l19.5-2.1c9.6-.9 19.2-1.5 28.8-.8 4.1.3 8.1 1.2 12 2.2 4.3 1.1 6.2 4.4 6.4 8.7.3 6.7-1.2 13.1-2.9 19.5-3.5 12.9-8.3 25.4-13.3 37.8-.3.8-.7 1.7-.8 2.5-.4 2.5 1 4 3.4 3.5 1.4-.3 3-1.1 4-2.1 3.7-3.6 7.5-7.2 10.6-11.2 10.7-13.8 17-29.6 20.7-46.6.7-3 1.2-6.1 1.7-9.1.2-4.7.2-9.6.2-14.5z\"],\n    \"cc-amex\": [576, 512, [], \"f1f3\", \"M325.1 167.8c0-16.4-14.1-18.4-27.4-18.4l-39.1-.3v69.3H275v-25.1h18c18.4 0 14.5 10.3 14.8 25.1h16.6v-13.5c0-9.2-1.5-15.1-11-18.4 7.4-3 11.8-10.7 11.7-18.7zm-29.4 11.3H275v-15.3h21c5.1 0 10.7 1 10.7 7.4 0 6.6-5.3 7.9-11 7.9zM279 268.6h-52.7l-21 22.8-20.5-22.8h-66.5l-.1 69.3h65.4l21.3-23 20.4 23h32.2l.1-23.3c18.9 0 49.3 4.6 49.3-23.3 0-17.3-12.3-22.7-27.9-22.7zm-103.8 54.7h-40.6v-13.8h36.3v-14.1h-36.3v-12.5h41.7l17.9 20.2zm65.8 8.2l-25.3-28.1L241 276zm37.8-31h-21.2v-17.6h21.5c5.6 0 10.2 2.3 10.2 8.4 0 6.4-4.6 9.2-10.5 9.2zm-31.6-136.7v-14.6h-55.5v69.3h55.5v-14.3h-38.9v-13.8h37.8v-14.1h-37.8v-12.5zM576 255.4h-.2zm-194.6 31.9c0-16.4-14.1-18.7-27.1-18.7h-39.4l-.1 69.3h16.6l.1-25.3h17.6c11 0 14.8 2 14.8 13.8l-.1 11.5h16.6l.1-13.8c0-8.9-1.8-15.1-11-18.4 7.7-3.1 11.8-10.8 11.9-18.4zm-29.2 11.2h-20.7v-15.6h21c5.1 0 10.7 1 10.7 7.4 0 6.9-5.4 8.2-11 8.2zm-172.8-80v-69.3h-27.6l-19.7 47-21.7-47H83.3v65.7l-28.1-65.7H30.7L1 218.5h17.9l6.4-15.3h34.5l6.4 15.3H100v-54.2l24 54.2h14.6l24-54.2v54.2zM31.2 188.8l11.2-27.6 11.5 27.6zm477.4 158.9v-4.5c-10.8 5.6-3.9 4.5-156.7 4.5 0-25.2.1-23.9 0-25.2-1.7-.1-3.2-.1-9.4-.1 0 17.9-.1 6.8-.1 25.3h-39.6c0-12.1.1-15.3.1-29.2-10 6-22.8 6.4-34.3 6.2 0 14.7-.1 8.3-.1 23h-48.9c-5.1-5.7-2.7-3.1-15.4-17.4-3.2 3.5-12.8 13.9-16.1 17.4h-82v-92.3h83.1c5 5.6 2.8 3.1 15.5 17.2 3.2-3.5 12.2-13.4 15.7-17.2h58c9.8 0 18 1.9 24.3 5.6v-5.6c54.3 0 64.3-1.4 75.7 5.1v-5.1h78.2v5.2c11.4-6.9 19.6-5.2 64.9-5.2v5c10.3-5.9 16.6-5.2 54.3-5V80c0-26.5-21.5-48-48-48h-480c-26.5 0-48 21.5-48 48v109.8c9.4-21.9 19.7-46 23.1-53.9h39.7c4.3 10.1 1.6 3.7 9 21.1v-21.1h46c2.9 6.2 11.1 24 13.9 30 5.8-13.6 10.1-23.9 12.6-30h103c0-.1 11.5 0 11.6 0 43.7.2 53.6-.8 64.4 5.3v-5.3H363v9.3c7.6-6.1 17.9-9.3 30.7-9.3h27.6c0 .5 1.9.3 2.3.3H456c4.2 9.8 2.6 6 8.8 20.6v-20.6h43.3c4.9 8-1-1.8 11.2 18.4v-18.4h39.9v92h-41.6c-5.4-9-1.4-2.2-13.2-21.9v21.9h-52.8c-6.4-14.8-.1-.3-6.6-15.3h-19c-4.2 10-2.2 5.2-6.4 15.3h-26.8c-12.3 0-22.3-3-29.7-8.9v8.9h-66.5c-.3-13.9-.1-24.8-.1-24.8-1.8-.3-3.4-.2-9.8-.2v25.1H151.2v-11.4c-2.5 5.6-2.7 5.9-5.1 11.4h-29.5c-4-8.9-2.9-6.4-5.1-11.4v11.4H58.6c-4.2-10.1-2.2-5.3-6.4-15.3H33c-4.2 10-2.2 5.2-6.4 15.3H0V432c0 26.5 21.5 48 48 48h480.1c26.5 0 48-21.5 48-48v-90.4c-12.7 8.3-32.7 6.1-67.5 6.1zm36.3-64.5H575v-14.6h-32.9c-12.8 0-23.8 6.6-23.8 20.7 0 33 42.7 12.8 42.7 27.4 0 5.1-4.3 6.4-8.4 6.4h-32l-.1 14.8h32c8.4 0 17.6-1.8 22.5-8.9v-25.8c-10.5-13.8-39.3-1.3-39.3-13.5 0-5.8 4.6-6.5 9.2-6.5zm-57 39.8h-32.2l-.1 14.8h32.2c14.8 0 26.2-5.6 26.2-22 0-33.2-42.9-11.2-42.9-26.3 0-5.6 4.9-6.4 9.2-6.4h30.4v-14.6h-33.2c-12.8 0-23.5 6.6-23.5 20.7 0 33 42.7 12.5 42.7 27.4-.1 5.4-4.7 6.4-8.8 6.4zm-42.2-40.1v-14.3h-55.2l-.1 69.3h55.2l.1-14.3-38.6-.3v-13.8H445v-14.1h-37.8v-12.5zm-56.3-108.1c-.3.2-1.4 2.2-1.4 7.6 0 6 .9 7.7 1.1 7.9.2.1 1.1.5 3.4.5l7.3-16.9c-1.1 0-2.1-.1-3.1-.1-5.6 0-7 .7-7.3 1zm20.4-10.5h-.1zm-16.2-15.2c-23.5 0-34 12-34 35.3 0 22.2 10.2 34 33 34h19.2l6.4-15.3h34.3l6.6 15.3h33.7v-51.9l31.2 51.9h23.6v-69h-16.9v48.1l-29.1-48.1h-25.3v65.4l-27.9-65.4h-24.8l-23.5 54.5h-7.4c-13.3 0-16.1-8.1-16.1-19.9 0-23.8 15.7-20 33.1-19.7v-15.2zm42.1 12.1l11.2 27.6h-22.8zm-101.1-12v69.3h16.9v-69.3z\"],\n    \"cc-apple-pay\": [576, 512, [], \"f416\", \"M302.2 218.4c0 17.2-10.5 27.1-29 27.1h-24.3v-54.2h24.4c18.4 0 28.9 9.8 28.9 27.1zm47.5 62.6c0 8.3 7.2 13.7 18.5 13.7 14.4 0 25.2-9.1 25.2-21.9v-7.7l-23.5 1.5c-13.3.9-20.2 5.8-20.2 14.4zM576 79v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM127.8 197.2c8.4.7 16.8-4.2 22.1-10.4 5.2-6.4 8.6-15 7.7-23.7-7.4.3-16.6 4.9-21.9 11.3-4.8 5.5-8.9 14.4-7.9 22.8zm60.6 74.5c-.2-.2-19.6-7.6-19.8-30-.2-18.7 15.3-27.7 16-28.2-8.8-13-22.4-14.4-27.1-14.7-12.2-.7-22.6 6.9-28.4 6.9-5.9 0-14.7-6.6-24.3-6.4-12.5.2-24.2 7.3-30.5 18.6-13.1 22.6-3.4 56 9.3 74.4 6.2 9.1 13.7 19.1 23.5 18.7 9.3-.4 13-6 24.2-6 11.3 0 14.5 6 24.3 5.9 10.2-.2 16.5-9.1 22.8-18.2 6.9-10.4 9.8-20.4 10-21zm135.4-53.4c0-26.6-18.5-44.8-44.9-44.8h-51.2v136.4h21.2v-46.6h29.3c26.8 0 45.6-18.4 45.6-45zm90 23.7c0-19.7-15.8-32.4-40-32.4-22.5 0-39.1 12.9-39.7 30.5h19.1c1.6-8.4 9.4-13.9 20-13.9 13 0 20.2 6 20.2 17.2v7.5l-26.4 1.6c-24.6 1.5-37.9 11.6-37.9 29.1 0 17.7 13.7 29.4 33.4 29.4 13.3 0 25.6-6.7 31.2-17.4h.4V310h19.6v-68zM516 210.9h-21.5l-24.9 80.6h-.4l-24.9-80.6H422l35.9 99.3-1.9 6c-3.2 10.2-8.5 14.2-17.9 14.2-1.7 0-4.9-.2-6.2-.3v16.4c1.2.4 6.5.5 8.1.5 20.7 0 30.4-7.9 38.9-31.8L516 210.9z\"],\n    \"cc-diners-club\": [576, 512, [], \"f24c\", \"M239.7 79.9c-96.9 0-175.8 78.6-175.8 175.8 0 96.9 78.9 175.8 175.8 175.8 97.2 0 175.8-78.9 175.8-175.8 0-97.2-78.6-175.8-175.8-175.8zm-39.9 279.6c-41.7-15.9-71.4-56.4-71.4-103.8s29.7-87.9 71.4-104.1v207.9zm79.8.3V151.6c41.7 16.2 71.4 56.7 71.4 104.1s-29.7 87.9-71.4 104.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM329.7 448h-90.3c-106.2 0-193.8-85.5-193.8-190.2C45.6 143.2 133.2 64 239.4 64h90.3c105 0 200.7 79.2 200.7 193.8 0 104.7-95.7 190.2-200.7 190.2z\"],\n    \"cc-discover\": [576, 512, [], \"f1f2\", \"M520.4 196.1c0-7.9-5.5-12.1-15.6-12.1h-4.9v24.9h4.7c10.3 0 15.8-4.4 15.8-12.8zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-44.1 138.9c22.6 0 52.9-4.1 52.9 24.4 0 12.6-6.6 20.7-18.7 23.2l25.8 34.4h-19.6l-22.2-32.8h-2.2v32.8h-16zm-55.9.1h45.3v14H444v18.2h28.3V217H444v22.2h29.3V253H428zm-68.7 0l21.9 55.2 22.2-55.2h17.5l-35.5 84.2h-8.6l-35-84.2zm-55.9-3c24.7 0 44.6 20 44.6 44.6 0 24.7-20 44.6-44.6 44.6-24.7 0-44.6-20-44.6-44.6 0-24.7 20-44.6 44.6-44.6zm-49.3 6.1v19c-20.1-20.1-46.8-4.7-46.8 19 0 25 27.5 38.5 46.8 19.2v19c-29.7 14.3-63.3-5.7-63.3-38.2 0-31.2 33.1-53 63.3-38zm-97.2 66.3c11.4 0 22.4-15.3-3.3-24.4-15-5.5-20.2-11.4-20.2-22.7 0-23.2 30.6-31.4 49.7-14.3l-8.4 10.8c-10.4-11.6-24.9-6.2-24.9 2.5 0 4.4 2.7 6.9 12.3 10.3 18.2 6.6 23.6 12.5 23.6 25.6 0 29.5-38.8 37.4-56.6 11.3l10.3-9.9c3.7 7.1 9.9 10.8 17.5 10.8zM55.4 253H32v-82h23.4c26.1 0 44.1 17 44.1 41.1 0 18.5-13.2 40.9-44.1 40.9zm67.5 0h-16v-82h16zM544 433c0 8.2-6.8 15-15 15H128c189.6-35.6 382.7-139.2 416-160zM74.1 191.6c-5.2-4.9-11.6-6.6-21.9-6.6H48v54.2h4.2c10.3 0 17-2 21.9-6.4 5.7-5.2 8.9-12.8 8.9-20.7s-3.2-15.5-8.9-20.5z\"],\n    \"cc-jcb\": [576, 512, [], \"f24b\", \"M431.5 244.3V212c41.2 0 38.5.2 38.5.2 7.3 1.3 13.3 7.3 13.3 16 0 8.8-6 14.5-13.3 15.8-1.2.4-3.3.3-38.5.3zm42.8 20.2c-2.8-.7-3.3-.5-42.8-.5v35c39.6 0 40 .2 42.8-.5 7.5-1.5 13.5-8 13.5-17 0-8.7-6-15.5-13.5-17zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM182 192.3h-57c0 67.1 10.7 109.7-35.8 109.7-19.5 0-38.8-5.7-57.2-14.8v28c30 8.3 68 8.3 68 8.3 97.9 0 82-47.7 82-131.2zm178.5 4.5c-63.4-16-165-14.9-165 59.3 0 77.1 108.2 73.6 165 59.2V287C312.9 311.7 253 309 253 256s59.8-55.6 107.5-31.2v-28zM544 286.5c0-18.5-16.5-30.5-38-32v-.8c19.5-2.7 30.3-15.5 30.3-30.2 0-19-15.7-30-37-31 0 0 6.3-.3-120.3-.3v127.5h122.7c24.3.1 42.3-12.9 42.3-33.2z\"],\n    \"cc-mastercard\": [576, 512, [], \"f1f1\", \"M482.9 410.3c0 6.8-4.6 11.7-11.2 11.7-6.8 0-11.2-5.2-11.2-11.7 0-6.5 4.4-11.7 11.2-11.7 6.6 0 11.2 5.2 11.2 11.7zm-310.8-11.7c-7.1 0-11.2 5.2-11.2 11.7 0 6.5 4.1 11.7 11.2 11.7 6.5 0 10.9-4.9 10.9-11.7-.1-6.5-4.4-11.7-10.9-11.7zm117.5-.3c-5.4 0-8.7 3.5-9.5 8.7h19.1c-.9-5.7-4.4-8.7-9.6-8.7zm107.8.3c-6.8 0-10.9 5.2-10.9 11.7 0 6.5 4.1 11.7 10.9 11.7 6.8 0 11.2-4.9 11.2-11.7 0-6.5-4.4-11.7-11.2-11.7zm105.9 26.1c0 .3.3.5.3 1.1 0 .3-.3.5-.3 1.1-.3.3-.3.5-.5.8-.3.3-.5.5-1.1.5-.3.3-.5.3-1.1.3-.3 0-.5 0-1.1-.3-.3 0-.5-.3-.8-.5-.3-.3-.5-.5-.5-.8-.3-.5-.3-.8-.3-1.1 0-.5 0-.8.3-1.1 0-.5.3-.8.5-1.1.3-.3.5-.3.8-.5.5-.3.8-.3 1.1-.3.5 0 .8 0 1.1.3.5.3.8.3 1.1.5s.2.6.5 1.1zm-2.2 1.4c.5 0 .5-.3.8-.3.3-.3.3-.5.3-.8 0-.3 0-.5-.3-.8-.3 0-.5-.3-1.1-.3h-1.6v3.5h.8V426h.3l1.1 1.4h.8l-1.1-1.3zM576 81v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V81c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM64 220.6c0 76.5 62.1 138.5 138.5 138.5 27.2 0 53.9-8.2 76.5-23.1-72.9-59.3-72.4-171.2 0-230.5-22.6-15-49.3-23.1-76.5-23.1-76.4-.1-138.5 62-138.5 138.2zm224 108.8c70.5-55 70.2-162.2 0-217.5-70.2 55.3-70.5 162.6 0 217.5zm-142.3 76.3c0-8.7-5.7-14.4-14.7-14.7-4.6 0-9.5 1.4-12.8 6.5-2.4-4.1-6.5-6.5-12.2-6.5-3.8 0-7.6 1.4-10.6 5.4V392h-8.2v36.7h8.2c0-18.9-2.5-30.2 9-30.2 10.2 0 8.2 10.2 8.2 30.2h7.9c0-18.3-2.5-30.2 9-30.2 10.2 0 8.2 10 8.2 30.2h8.2v-23zm44.9-13.7h-7.9v4.4c-2.7-3.3-6.5-5.4-11.7-5.4-10.3 0-18.2 8.2-18.2 19.3 0 11.2 7.9 19.3 18.2 19.3 5.2 0 9-1.9 11.7-5.4v4.6h7.9V392zm40.5 25.6c0-15-22.9-8.2-22.9-15.2 0-5.7 11.9-4.8 18.5-1.1l3.3-6.5c-9.4-6.1-30.2-6-30.2 8.2 0 14.3 22.9 8.3 22.9 15 0 6.3-13.5 5.8-20.7.8l-3.5 6.3c11.2 7.6 32.6 6 32.6-7.5zm35.4 9.3l-2.2-6.8c-3.8 2.1-12.2 4.4-12.2-4.1v-16.6h13.1V392h-13.1v-11.2h-8.2V392h-7.6v7.3h7.6V416c0 17.6 17.3 14.4 22.6 10.9zm13.3-13.4h27.5c0-16.2-7.4-22.6-17.4-22.6-10.6 0-18.2 7.9-18.2 19.3 0 20.5 22.6 23.9 33.8 14.2l-3.8-6c-7.8 6.4-19.6 5.8-21.9-4.9zm59.1-21.5c-4.6-2-11.6-1.8-15.2 4.4V392h-8.2v36.7h8.2V408c0-11.6 9.5-10.1 12.8-8.4l2.4-7.6zm10.6 18.3c0-11.4 11.6-15.1 20.7-8.4l3.8-6.5c-11.6-9.1-32.7-4.1-32.7 15 0 19.8 22.4 23.8 32.7 15l-3.8-6.5c-9.2 6.5-20.7 2.6-20.7-8.6zm66.7-18.3H408v4.4c-8.3-11-29.9-4.8-29.9 13.9 0 19.2 22.4 24.7 29.9 13.9v4.6h8.2V392zm33.7 0c-2.4-1.2-11-2.9-15.2 4.4V392h-7.9v36.7h7.9V408c0-11 9-10.3 12.8-8.4l2.4-7.6zm40.3-14.9h-7.9v19.3c-8.2-10.9-29.9-5.1-29.9 13.9 0 19.4 22.5 24.6 29.9 13.9v4.6h7.9v-51.7zm7.6-75.1v4.6h.8V302h1.9v-.8h-4.6v.8h1.9zm6.6 123.8c0-.5 0-1.1-.3-1.6-.3-.3-.5-.8-.8-1.1-.3-.3-.8-.5-1.1-.8-.5 0-1.1-.3-1.6-.3-.3 0-.8.3-1.4.3-.5.3-.8.5-1.1.8-.5.3-.8.8-.8 1.1-.3.5-.3 1.1-.3 1.6 0 .3 0 .8.3 1.4 0 .3.3.8.8 1.1.3.3.5.5 1.1.8.5.3 1.1.3 1.4.3.5 0 1.1 0 1.6-.3.3-.3.8-.5 1.1-.8.3-.3.5-.8.8-1.1.3-.6.3-1.1.3-1.4zm3.2-124.7h-1.4l-1.6 3.5-1.6-3.5h-1.4v5.4h.8v-4.1l1.6 3.5h1.1l1.4-3.5v4.1h1.1v-5.4zm4.4-80.5c0-76.2-62.1-138.3-138.5-138.3-27.2 0-53.9 8.2-76.5 23.1 72.1 59.3 73.2 171.5 0 230.5 22.6 15 49.5 23.1 76.5 23.1 76.4.1 138.5-61.9 138.5-138.4z\"],\n    \"cc-paypal\": [576, 512, [], \"f1f4\", \"M186.3 258.2c0 12.2-9.7 21.5-22 21.5-9.2 0-16-5.2-16-15 0-12.2 9.5-22 21.7-22 9.3 0 16.3 5.7 16.3 15.5zM80.5 209.7h-4.7c-1.5 0-3 1-3.2 2.7l-4.3 26.7 8.2-.3c11 0 19.5-1.5 21.5-14.2 2.3-13.4-6.2-14.9-17.5-14.9zm284 0H360c-1.8 0-3 1-3.2 2.7l-4.2 26.7 8-.3c13 0 22-3 22-18-.1-10.6-9.6-11.1-18.1-11.1zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM128.3 215.4c0-21-16.2-28-34.7-28h-40c-2.5 0-5 2-5.2 4.7L32 294.2c-.3 2 1.2 4 3.2 4h19c2.7 0 5.2-2.9 5.5-5.7l4.5-26.6c1-7.2 13.2-4.7 18-4.7 28.6 0 46.1-17 46.1-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.2 8.2-5.8-8.5-14.2-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9 0 20.2-4.9 26.5-11.9-.5 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H200c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm40.5 97.9l63.7-92.6c.5-.5.5-1 .5-1.7 0-1.7-1.5-3.5-3.2-3.5h-19.2c-1.7 0-3.5 1-4.5 2.5l-26.5 39-11-37.5c-.8-2.2-3-4-5.5-4h-18.7c-1.7 0-3.2 1.8-3.2 3.5 0 1.2 19.5 56.8 21.2 62.1-2.7 3.8-20.5 28.6-20.5 31.6 0 1.8 1.5 3.2 3.2 3.2h19.2c1.8-.1 3.5-1.1 4.5-2.6zm159.3-106.7c0-21-16.2-28-34.7-28h-39.7c-2.7 0-5.2 2-5.5 4.7l-16.2 102c-.2 2 1.3 4 3.2 4h20.5c2 0 3.5-1.5 4-3.2l4.5-29c1-7.2 13.2-4.7 18-4.7 28.4 0 45.9-17 45.9-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.3 8.2-5.5-8.5-14-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9.3 0 20.5-4.9 26.5-11.9-.3 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H484c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm47.5-33.3c0-2-1.5-3.5-3.2-3.5h-18.5c-1.5 0-3 1.2-3.2 2.7l-16.2 104-.3.5c0 1.8 1.5 3.5 3.5 3.5h16.5c2.5 0 5-2.9 5.2-5.7L544 191.2v-.3zm-90 51.8c-12.2 0-21.7 9.7-21.7 22 0 9.7 7 15 16.2 15 12 0 21.7-9.2 21.7-21.5.1-9.8-6.9-15.5-16.2-15.5z\"],\n    \"cc-stripe\": [576, 512, [], \"f1f5\", \"M492.4 220.8c-8.9 0-18.7 6.7-18.7 22.7h36.7c0-16-9.3-22.7-18-22.7zM375 223.4c-8.2 0-13.3 2.9-17 7l.2 52.8c3.5 3.7 8.5 6.7 16.8 6.7 13.1 0 21.9-14.3 21.9-33.4 0-18.6-9-33.2-21.9-33.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM122.2 281.1c0 25.6-20.3 40.1-49.9 40.3-12.2 0-25.6-2.4-38.8-8.1v-33.9c12 6.4 27.1 11.3 38.9 11.3 7.9 0 13.6-2.1 13.6-8.7 0-17-54-10.6-54-49.9 0-25.2 19.2-40.2 48-40.2 11.8 0 23.5 1.8 35.3 6.5v33.4c-10.8-5.8-24.5-9.1-35.3-9.1-7.5 0-12.1 2.2-12.1 7.7 0 16 54.3 8.4 54.3 50.7zm68.8-56.6h-27V275c0 20.9 22.5 14.4 27 12.6v28.9c-4.7 2.6-13.3 4.7-24.9 4.7-21.1 0-36.9-15.5-36.9-36.5l.2-113.9 34.7-7.4v30.8H191zm74 2.4c-4.5-1.5-18.7-3.6-27.1 7.4v84.4h-35.5V194.2h30.7l2.2 10.5c8.3-15.3 24.9-12.2 29.6-10.5h.1zm44.1 91.8h-35.7V194.2h35.7zm0-142.9l-35.7 7.6v-28.9l35.7-7.6zm74.1 145.5c-12.4 0-20-5.3-25.1-9l-.1 40.2-35.5 7.5V194.2h31.3l1.8 8.8c4.9-4.5 13.9-11.1 27.8-11.1 24.9 0 48.4 22.5 48.4 63.8 0 45.1-23.2 65.5-48.6 65.6zm160.4-51.5h-69.5c1.6 16.6 13.8 21.5 27.6 21.5 14.1 0 25.2-3 34.9-7.9V312c-9.7 5.3-22.4 9.2-39.4 9.2-34.6 0-58.8-21.7-58.8-64.5 0-36.2 20.5-64.9 54.3-64.9 33.7 0 51.3 28.7 51.3 65.1 0 3.5-.3 10.9-.4 12.9z\"],\n    \"cc-visa\": [576, 512, [], \"f1f0\", \"M470.1 231.3s7.6 37.2 9.3 45H446c3.3-8.9 16-43.5 16-43.5-.2.3 3.3-9.1 5.3-14.9l2.8 13.4zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM152.5 331.2L215.7 176h-42.5l-39.3 106-4.3-21.5-14-71.4c-2.3-9.9-9.4-12.7-18.2-13.1H32.7l-.7 3.1c15.8 4 29.9 9.8 42.2 17.1l35.8 135h42.5zm94.4.2L272.1 176h-40.2l-25.1 155.4h40.1zm139.9-50.8c.2-17.7-10.6-31.2-33.7-42.3-14.1-7.1-22.7-11.9-22.7-19.2.2-6.6 7.3-13.4 23.1-13.4 13.1-.3 22.7 2.8 29.9 5.9l3.6 1.7 5.5-33.6c-7.9-3.1-20.5-6.6-36-6.6-39.7 0-67.6 21.2-67.8 51.4-.3 22.3 20 34.7 35.2 42.2 15.5 7.6 20.8 12.6 20.8 19.3-.2 10.4-12.6 15.2-24.1 15.2-16 0-24.6-2.5-37.7-8.3l-5.3-2.5-5.6 34.9c9.4 4.3 26.8 8.1 44.8 8.3 42.2.1 69.7-20.8 70-53zM528 331.4L495.6 176h-31.1c-9.6 0-16.9 2.8-21 12.9l-59.7 142.5H426s6.9-19.2 8.4-23.3H486c1.2 5.5 4.8 23.3 4.8 23.3H528z\"],\n    \"centercode\": [512, 512, [], \"f380\", \"M329.2 268.6c-3.8 35.2-35.4 60.6-70.6 56.8-35.2-3.8-60.6-35.4-56.8-70.6 3.8-35.2 35.4-60.6 70.6-56.8 35.1 3.8 60.6 35.4 56.8 70.6zm-85.8 235.1C96.7 496-8.2 365.5 10.1 224.3c11.2-86.6 65.8-156.9 139.1-192 161-77.1 349.7 37.4 354.7 216.6 4.1 147-118.4 262.2-260.5 254.8zm179.9-180c27.9-118-160.5-205.9-237.2-234.2-57.5 56.3-69.1 188.6-33.8 344.4 68.8 15.8 169.1-26.4 271-110.2z\"],\n    \"centos\": [448, 512, [], \"f789\", \"M289.6 97.5l31.6 31.7-76.3 76.5V97.5zm-162.4 31.7l76.3 76.5V97.5h-44.7zm41.5-41.6h44.7v127.9l10.8 10.8 10.8-10.8V87.6h44.7L224.2 32zm26.2 168.1l-10.8-10.8H55.5v-44.8L0 255.7l55.5 55.6v-44.8h128.6l10.8-10.8zm79.3-20.7h107.9v-44.8l-31.6-31.7zm173.3 20.7L392 200.1v44.8H264.3l-10.8 10.8 10.8 10.8H392v44.8l55.5-55.6zM65.4 176.2l32.5-31.7 90.3 90.5h15.3v-15.3l-90.3-90.5 31.6-31.7H65.4zm316.7-78.7h-78.5l31.6 31.7-90.3 90.5V235h15.3l90.3-90.5 31.6 31.7zM203.5 413.9V305.8l-76.3 76.5 31.6 31.7h44.7zM65.4 235h108.8l-76.3-76.5-32.5 31.7zm316.7 100.2l-31.6 31.7-90.3-90.5h-15.3v15.3l90.3 90.5-31.6 31.7h78.5zm0-58.8H274.2l76.3 76.5 31.6-31.7zm-60.9 105.8l-76.3-76.5v108.1h44.7zM97.9 352.9l76.3-76.5H65.4v44.8zm181.8 70.9H235V295.9l-10.8-10.8-10.8 10.8v127.9h-44.7l55.5 55.6zm-166.5-41.6l90.3-90.5v-15.3h-15.3l-90.3 90.5-32.5-31.7v78.7h79.4z\"],\n    \"chrome\": [496, 512, [], \"f268\", \"M131.5 217.5L55.1 100.1c47.6-59.2 119-91.8 192-92.1 42.3-.3 85.5 10.5 124.8 33.2 43.4 25.2 76.4 61.4 97.4 103L264 133.4c-58.1-3.4-113.4 29.3-132.5 84.1zm32.9 38.5c0 46.2 37.4 83.6 83.6 83.6s83.6-37.4 83.6-83.6-37.4-83.6-83.6-83.6-83.6 37.3-83.6 83.6zm314.9-89.2L339.6 174c37.9 44.3 38.5 108.2 6.6 157.2L234.1 503.6c46.5 2.5 94.4-7.7 137.8-32.9 107.4-62 150.9-192 107.4-303.9zM133.7 303.6L40.4 120.1C14.9 159.1 0 205.9 0 256c0 124 90.8 226.7 209.5 244.9l63.7-124.8c-57.6 10.8-113.2-20.8-139.5-72.5z\"],\n    \"chromecast\": [512, 512, [], \"f838\", \"M447.83 64H64a42.72 42.72 0 0 0-42.72 42.72v63.92H64v-63.92h383.83v298.56H298.64V448H448a42.72 42.72 0 0 0 42.72-42.72V106.72A42.72 42.72 0 0 0 448 64zM21.28 383.58v63.92h63.91a63.91 63.91 0 0 0-63.91-63.92zm0-85.28V341a106.63 106.63 0 0 1 106.64 106.66v.34h42.72a149.19 149.19 0 0 0-149-149.36h-.33zm0-85.27v42.72c106-.1 192 85.75 192.08 191.75v.5h42.72c-.46-129.46-105.34-234.27-234.8-234.64z\"],\n    \"cloudscale\": [448, 512, [], \"f383\", \"M318.1 154l-9.4 7.6c-22.5-19.3-51.5-33.6-83.3-33.6C153.8 128 96 188.8 96 260.3c0 6.6.4 13.1 1.4 19.4-2-56 41.8-97.4 92.6-97.4 24.2 0 46.2 9.4 62.6 24.7l-25.2 20.4c-8.3-.9-16.8 1.8-23.1 8.1-11.1 11-11.1 28.9 0 40 11.1 11 28.9 11 40 0 6.3-6.3 9-14.9 8.1-23.1l75.2-88.8c6.3-6.5-3.3-15.9-9.5-9.6zm-83.8 111.5c-5.6 5.5-14.6 5.5-20.2 0-5.6-5.6-5.6-14.6 0-20.2s14.6-5.6 20.2 0 5.6 14.7 0 20.2zM224 32C100.5 32 0 132.5 0 256s100.5 224 224 224 224-100.5 224-224S347.5 32 224 32zm0 384c-88.2 0-160-71.8-160-160S135.8 96 224 96s160 71.8 160 160-71.8 160-160 160z\"],\n    \"cloudsmith\": [332, 512, [], \"f384\", \"M332.5 419.9c0 46.4-37.6 84.1-84 84.1s-84-37.7-84-84.1 37.6-84 84-84 84 37.6 84 84zm-84-243.9c46.4 0 80-37.6 80-84s-33.6-84-80-84-88 37.6-88 84-29.6 76-76 76-84 41.6-84 88 37.6 80 84 80 84-33.6 84-80 33.6-80 80-80z\"],\n    \"cloudversify\": [616, 512, [], \"f385\", \"M148.6 304c8.2 68.5 67.4 115.5 146 111.3 51.2 43.3 136.8 45.8 186.4-5.6 69.2 1.1 118.5-44.6 131.5-99.5 14.8-62.5-18.2-132.5-92.1-155.1-33-88.1-131.4-101.5-186.5-85-57.3 17.3-84.3 53.2-99.3 109.7-7.8 2.7-26.5 8.9-45 24.1 11.7 0 15.2 8.9 15.2 19.5v20.4c0 10.7-8.7 19.5-19.5 19.5h-20.2c-10.7 0-19.5-6-19.5-16.7V240H98.8C95 240 88 244.3 88 251.9v40.4c0 6.4 5.3 11.8 11.7 11.8h48.9zm227.4 8c-10.7 46.3 21.7 72.4 55.3 86.8C324.1 432.6 259.7 348 296 288c-33.2 21.6-33.7 71.2-29.2 92.9-17.9-12.4-53.8-32.4-57.4-79.8-3-39.9 21.5-75.7 57-93.9C297 191.4 369.9 198.7 400 248c-14.1-48-53.8-70.1-101.8-74.8 30.9-30.7 64.4-50.3 114.2-43.7 69.8 9.3 133.2 82.8 67.7 150.5 35-16.3 48.7-54.4 47.5-76.9l10.5 19.6c11.8 22 15.2 47.6 9.4 72-9.2 39-40.6 68.8-79.7 76.5-32.1 6.3-83.1-5.1-91.8-59.2zM128 208H88.2c-8.9 0-16.2-7.3-16.2-16.2v-39.6c0-8.9 7.3-16.2 16.2-16.2H128c8.9 0 16.2 7.3 16.2 16.2v39.6c0 8.9-7.3 16.2-16.2 16.2zM10.1 168C4.5 168 0 163.5 0 157.9v-27.8c0-5.6 4.5-10.1 10.1-10.1h27.7c5.5 0 10.1 4.5 10.1 10.1v27.8c0 5.6-4.5 10.1-10.1 10.1H10.1zM168 142.7v-21.4c0-5.1 4.2-9.3 9.3-9.3h21.4c5.1 0 9.3 4.2 9.3 9.3v21.4c0 5.1-4.2 9.3-9.3 9.3h-21.4c-5.1 0-9.3-4.2-9.3-9.3zM56 235.5v25c0 6.3-5.1 11.5-11.4 11.5H19.4C13.1 272 8 266.8 8 260.5v-25c0-6.3 5.1-11.5 11.4-11.5h25.1c6.4 0 11.5 5.2 11.5 11.5z\"],\n    \"codepen\": [512, 512, [], \"f1cb\", \"M502.285 159.704l-234-156c-7.987-4.915-16.511-4.96-24.571 0l-234 156C3.714 163.703 0 170.847 0 177.989v155.999c0 7.143 3.714 14.286 9.715 18.286l234 156.022c7.987 4.915 16.511 4.96 24.571 0l234-156.022c6-3.999 9.715-11.143 9.715-18.286V177.989c-.001-7.142-3.715-14.286-9.716-18.285zM278 63.131l172.286 114.858-76.857 51.429L278 165.703V63.131zm-44 0v102.572l-95.429 63.715-76.857-51.429L234 63.131zM44 219.132l55.143 36.857L44 292.846v-73.714zm190 229.715L61.714 333.989l76.857-51.429L234 346.275v102.572zm22-140.858l-77.715-52 77.715-52 77.715 52-77.715 52zm22 140.858V346.275l95.429-63.715 76.857 51.429L278 448.847zm190-156.001l-55.143-36.857L468 219.132v73.714z\"],\n    \"codiepie\": [472, 512, [], \"f284\", \"M422.5 202.9c30.7 0 33.5 53.1-.3 53.1h-10.8v44.3h-26.6v-97.4h37.7zM472 352.6C429.9 444.5 350.4 504 248 504 111 504 0 393 0 256S111 8 248 8c97.4 0 172.8 53.7 218.2 138.4l-186 108.8L472 352.6zm-38.5 12.5l-60.3-30.7c-27.1 44.3-70.4 71.4-122.4 71.4-82.5 0-149.2-66.7-149.2-148.9 0-82.5 66.7-149.2 149.2-149.2 48.4 0 88.9 23.5 116.9 63.4l59.5-34.6c-40.7-62.6-104.7-100-179.2-100-121.2 0-219.5 98.3-219.5 219.5S126.8 475.5 248 475.5c78.6 0 146.5-42.1 185.5-110.4z\"],\n    \"confluence\": [512, 512, [], \"f78d\", \"M2.3 412.2c-4.5 7.6-2.1 17.5 5.5 22.2l105.9 65.2c7.7 4.7 17.7 2.4 22.4-5.3 0-.1.1-.2.1-.2 67.1-112.2 80.5-95.9 280.9-.7 8.1 3.9 17.8.4 21.7-7.7.1-.1.1-.3.2-.4l50.4-114.1c3.6-8.1-.1-17.6-8.1-21.3-22.2-10.4-66.2-31.2-105.9-50.3C127.5 179 44.6 345.3 2.3 412.2zm507.4-312.1c4.5-7.6 2.1-17.5-5.5-22.2L398.4 12.8c-7.5-5-17.6-3.1-22.6 4.4-.2.3-.4.6-.6 1-67.3 112.6-81.1 95.6-280.6.9-8.1-3.9-17.8-.4-21.7 7.7-.1.1-.1.3-.2.4L22.2 141.3c-3.6 8.1.1 17.6 8.1 21.3 22.2 10.4 66.3 31.2 106 50.4 248 120 330.8-45.4 373.4-112.9z\"],\n    \"connectdevelop\": [576, 512, [], \"f20e\", \"M550.5 241l-50.089-86.786c1.071-2.142 1.875-4.553 1.875-7.232 0-8.036-6.696-14.733-14.732-15.001l-55.447-95.893c.536-1.607 1.071-3.214 1.071-4.821 0-8.571-6.964-15.268-15.268-15.268-4.821 0-8.839 2.143-11.786 5.625H299.518C296.839 18.143 292.821 16 288 16s-8.839 2.143-11.518 5.625H170.411C167.464 18.143 163.447 16 158.625 16c-8.303 0-15.268 6.696-15.268 15.268 0 1.607.536 3.482 1.072 4.821l-55.983 97.233c-5.356 2.41-9.107 7.5-9.107 13.661 0 .535.268 1.071.268 1.607l-53.304 92.143c-7.232 1.339-12.59 7.5-12.59 15 0 7.232 5.089 13.393 12.054 15l55.179 95.358c-.536 1.607-.804 2.946-.804 4.821 0 7.232 5.089 13.393 12.054 14.732l51.697 89.732c-.536 1.607-1.071 3.482-1.071 5.357 0 8.571 6.964 15.268 15.268 15.268 4.821 0 8.839-2.143 11.518-5.357h106.875C279.161 493.857 283.447 496 288 496s8.839-2.143 11.518-5.357h107.143c2.678 2.946 6.696 4.821 10.982 4.821 8.571 0 15.268-6.964 15.268-15.268 0-1.607-.267-2.946-.803-4.285l51.697-90.268c6.964-1.339 12.054-7.5 12.054-14.732 0-1.607-.268-3.214-.804-4.821l54.911-95.358c6.964-1.339 12.322-7.5 12.322-15-.002-7.232-5.092-13.393-11.788-14.732zM153.535 450.732l-43.66-75.803h43.66v75.803zm0-83.839h-43.66c-.268-1.071-.804-2.142-1.339-3.214l44.999-47.41v50.624zm0-62.411l-50.357 53.304c-1.339-.536-2.679-1.34-4.018-1.607L43.447 259.75c.535-1.339.535-2.679.535-4.018s0-2.41-.268-3.482l51.965-90c2.679-.268 5.357-1.072 7.768-2.679l50.089 51.965v92.946zm0-102.322l-45.803-47.41c1.339-2.143 2.143-4.821 2.143-7.767 0-.268-.268-.804-.268-1.072l43.928-15.804v72.053zm0-80.625l-43.66 15.804 43.66-75.536v59.732zm326.519 39.108l.804 1.339L445.5 329.125l-63.75-67.232 98.036-101.518.268.268zM291.75 355.107l11.518 11.786H280.5l11.25-11.786zm-.268-11.25l-83.303-85.446 79.553-84.375 83.036 87.589-79.286 82.232zm5.357 5.893l79.286-82.232 67.5 71.25-5.892 28.125H313.714l-16.875-17.143zM410.411 44.393c1.071.536 2.142 1.072 3.482 1.34l57.857 100.714v.536c0 2.946.803 5.624 2.143 7.767L376.393 256l-83.035-87.589L410.411 44.393zm-9.107-2.143L287.732 162.518l-57.054-60.268 166.339-60h4.287zm-123.483 0c2.678 2.678 6.16 4.285 10.179 4.285s7.5-1.607 10.179-4.285h75L224.786 95.821 173.893 42.25h103.928zm-116.249 5.625l1.071-2.142a33.834 33.834 0 0 0 2.679-.804l51.161 53.84-54.911 19.821V47.875zm0 79.286l60.803-21.964 59.732 63.214-79.553 84.107-40.982-42.053v-83.304zm0 92.678L198 257.607l-36.428 38.304v-76.072zm0 87.858l42.053-44.464 82.768 85.982-17.143 17.678H161.572v-59.196zm6.964 162.053c-1.607-1.607-3.482-2.678-5.893-3.482l-1.071-1.607v-89.732h99.91l-91.607 94.821h-1.339zm129.911 0c-2.679-2.41-6.428-4.285-10.447-4.285s-7.767 1.875-10.447 4.285h-96.429l91.607-94.821h38.304l91.607 94.821H298.447zm120-11.786l-4.286 7.5c-1.339.268-2.41.803-3.482 1.339l-89.196-91.875h114.376l-17.412 83.036zm12.856-22.232l12.858-60.803h21.964l-34.822 60.803zm34.822-68.839h-20.357l4.553-21.16 17.143 18.214c-.535.803-1.071 1.874-1.339 2.946zm66.161-107.411l-55.447 96.697c-1.339.535-2.679 1.071-4.018 1.874l-20.625-21.964 34.554-163.928 45.803 79.286c-.267 1.339-.803 2.678-.803 4.285 0 1.339.268 2.411.536 3.75z\"],\n    \"contao\": [512, 512, [], \"f26d\", \"M45.4 305c14.4 67.1 26.4 129 68.2 175H34c-18.7 0-34-15.2-34-34V66c0-18.7 15.2-34 34-34h57.7C77.9 44.6 65.6 59.2 54.8 75.6c-45.4 70-27 146.8-9.4 229.4zM478 32h-90.2c21.4 21.4 39.2 49.5 52.7 84.1l-137.1 29.3c-14.9-29-37.8-53.3-82.6-43.9-24.6 5.3-41 19.3-48.3 34.6-8.8 18.7-13.2 39.8 8.2 140.3 21.1 100.2 33.7 117.7 49.5 131.2 12.9 11.1 33.4 17 58.3 11.7 44.5-9.4 55.7-40.7 57.4-73.2l137.4-29.6c3.2 71.5-18.7 125.2-57.4 163.6H478c18.7 0 34-15.2 34-34V66c0-18.8-15.2-34-34-34z\"],\n    \"cotton-bureau\": [512, 512, [], \"f89e\", \"M474.31 330.41c-23.66 91.85-94.23 144.59-201.9 148.35V429.6c0-48 26.41-74.39 74.39-74.39 62 0 99.2-37.2 99.2-99.21 0-61.37-36.53-98.28-97.38-99.06-33-69.32-146.5-64.65-177.24 0C110.52 157.72 74 194.63 74 256c0 62.13 37.27 99.41 99.4 99.41 48 0 74.55 26.23 74.55 74.39V479c-134.43-5-211.1-85.07-211.1-223 0-141.82 81.35-223.2 223.2-223.2 114.77 0 189.84 53.2 214.69 148.81H500C473.88 71.51 388.22 8 259.82 8 105 8 12 101.19 12 255.82 12 411.14 105.19 504.34 259.82 504c128.27 0 213.87-63.81 239.67-173.59zM357 182.33c41.37 3.45 64.2 29 64.2 73.67 0 48-26.43 74.41-74.4 74.41-28.61 0-49.33-9.59-61.59-27.33 83.06-16.55 75.59-99.67 71.79-120.75zm-81.68 97.36c-2.46-10.34-16.33-87 56.23-97 2.27 10.09 16.52 87.11-56.26 97zM260 132c28.61 0 49 9.67 61.44 27.61-28.36 5.48-49.36 20.59-61.59 43.45-12.23-22.86-33.23-38-61.6-43.45 12.41-17.69 33.27-27.35 61.57-27.35zm-71.52 50.72c73.17 10.57 58.91 86.81 56.49 97-72.41-9.84-59-86.95-56.25-97zM173.2 330.41c-48 0-74.4-26.4-74.4-74.41 0-44.36 22.86-70 64.22-73.67-6.75 37.2-1.38 106.53 71.65 120.75-12.14 17.63-32.84 27.3-61.14 27.3zm53.21 12.39A80.8 80.8 0 0 0 260 309.25c7.77 14.49 19.33 25.54 33.82 33.55a80.28 80.28 0 0 0-33.58 33.83c-8-14.5-19.07-26.23-33.56-33.83z\"],\n    \"cpanel\": [640, 512, [], \"f388\", \"M210.3 220.2c-5.6-24.8-26.9-41.2-51-41.2h-37c-7.1 0-12.5 4.5-14.3 10.9L73.1 320l24.7-.1c6.8 0 12.3-4.5 14.2-10.7l25.8-95.7h19.8c8.4 0 16.2 5.6 18.3 14.8 2.5 10.9-5.9 22.6-18.3 22.6h-10.3c-7 0-12.5 4.6-14.3 10.8l-6.4 23.8h32c37.2 0 58.3-36.2 51.7-65.3zm-156.5 28h18.6c6.9 0 12.4-4.4 14.3-10.9l6.2-23.6h-40C30 213.7 9 227.8 1.7 254.8-7 288.6 18.5 320 52 320h12.4l7.1-26.1c1.2-4.4-2.2-8.3-6.4-8.3H53.8c-24.7 0-24.9-37.4 0-37.4zm247.5-34.8h-77.9l-3.5 13.4c-2.4 9.6 4.5 18.5 14.2 18.5h57.5c4 0 2.4 4.3 2.1 5.3l-8.6 31.8c-.4 1.4-.9 5.3-5.5 5.3h-34.9c-5.3 0-5.3-7.9 0-7.9h21.6c6.8 0 12.3-4.6 14.2-10.8l3.5-13.2h-48.4c-39.2 0-43.6 63.8-.7 63.8l57.5.2c11.2 0 20.6-7.2 23.4-17.8l14-51.8c4.8-19.2-9.7-36.8-28.5-36.8zM633.1 179h-18.9c-4.9 0-9.2 3.2-10.4 7.9L568.2 320c20.7 0 39.8-13.8 44.9-34.5l26.5-98.2c1.2-4.3-2-8.3-6.5-8.3zm-236.3 34.7v.1h-48.3l-26.2 98c-1.2 4.4 2.2 8.3 6.4 8.3h18.9c4.8 0 9.2-3 10.4-7.8l17.2-64H395c12.5 0 21.4 11.8 18.1 23.4l-10.6 40c-1.2 4.3 1.9 8.3 6.4 8.3H428c4.6 0 9.1-2.9 10.3-7.8l8.8-33.1c9-33.1-15.9-65.4-50.3-65.4zm98.3 74.6c-3.6 0-6-3.4-5.1-6.7l8-30c.9-3.9 3.7-6 7.8-6h32.9c2.6 0 4.6 2.4 3.9 5.1l-.7 2.6c-.6 2-1.9 3-3.9 3h-21.6c-7 0-12.6 4.6-14.2 10.8l-3.5 13h53.4c10.5 0 20.3-6.6 23.2-17.6l3.2-12c4.9-19.1-9.3-36.8-28.3-36.8h-47.3c-17.9 0-33.8 12-38.6 29.6l-10.8 40c-5 17.7 8.3 36.7 28.3 36.7h66.7c6.8 0 12.3-4.5 14.2-10.7l5.7-21z\"],\n    \"creative-commons\": [496, 512, [], \"f25e\", \"M245.83 214.87l-33.22 17.28c-9.43-19.58-25.24-19.93-27.46-19.93-22.13 0-33.22 14.61-33.22 43.84 0 23.57 9.21 43.84 33.22 43.84 14.47 0 24.65-7.09 30.57-21.26l30.55 15.5c-6.17 11.51-25.69 38.98-65.1 38.98-22.6 0-73.96-10.32-73.96-77.05 0-58.69 43-77.06 72.63-77.06 30.72-.01 52.7 11.95 65.99 35.86zm143.05 0l-32.78 17.28c-9.5-19.77-25.72-19.93-27.9-19.93-22.14 0-33.22 14.61-33.22 43.84 0 23.55 9.23 43.84 33.22 43.84 14.45 0 24.65-7.09 30.54-21.26l31 15.5c-2.1 3.75-21.39 38.98-65.09 38.98-22.69 0-73.96-9.87-73.96-77.05 0-58.67 42.97-77.06 72.63-77.06 30.71-.01 52.58 11.95 65.56 35.86zM247.56 8.05C104.74 8.05 0 123.11 0 256.05c0 138.49 113.6 248 247.56 248 129.93 0 248.44-100.87 248.44-248 0-137.87-106.62-248-248.44-248zm.87 450.81c-112.54 0-203.7-93.04-203.7-202.81 0-105.42 85.43-203.27 203.72-203.27 112.53 0 202.82 89.46 202.82 203.26-.01 121.69-99.68 202.82-202.84 202.82z\"],\n    \"creative-commons-by\": [496, 512, [], \"f4e7\", \"M314.9 194.4v101.4h-28.3v120.5h-77.1V295.9h-28.3V194.4c0-4.4 1.6-8.2 4.6-11.3 3.1-3.1 6.9-4.7 11.3-4.7H299c4.1 0 7.8 1.6 11.1 4.7 3.1 3.2 4.8 6.9 4.8 11.3zm-101.5-63.7c0-23.3 11.5-35 34.5-35s34.5 11.7 34.5 35c0 23-11.5 34.5-34.5 34.5s-34.5-11.5-34.5-34.5zM247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3z\"],\n    \"creative-commons-nc\": [496, 512, [], \"f4e8\", \"M247.6 8C387.4 8 496 115.9 496 256c0 147.2-118.5 248-248.4 248C113.1 504 0 393.2 0 256 0 123.1 104.7 8 247.6 8zM55.8 189.1c-7.4 20.4-11.1 42.7-11.1 66.9 0 110.9 92.1 202.4 203.7 202.4 122.4 0 177.2-101.8 178.5-104.1l-93.4-41.6c-7.7 37.1-41.2 53-68.2 55.4v38.1h-28.8V368c-27.5-.3-52.6-10.2-75.3-29.7l34.1-34.5c31.7 29.4 86.4 31.8 86.4-2.2 0-6.2-2.2-11.2-6.6-15.1-14.2-6-1.8-.1-219.3-97.4zM248.4 52.3c-38.4 0-112.4 8.7-170.5 93l94.8 42.5c10-31.3 40.4-42.9 63.8-44.3v-38.1h28.8v38.1c22.7 1.2 43.4 8.9 62 23L295 199.7c-42.7-29.9-83.5-8-70 11.1 53.4 24.1 43.8 19.8 93 41.6l127.1 56.7c4.1-17.4 6.2-35.1 6.2-53.1 0-57-19.8-105-59.3-143.9-39.3-39.9-87.2-59.8-143.6-59.8z\"],\n    \"creative-commons-nc-eu\": [496, 512, [], \"f4e9\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.3 111.7 248 247.7 248C377.9 504 496 403.1 496 256 496 117 388.4 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-23.2 3.7-45.2 10.9-66l65.7 29.1h-4.7v29.5h23.3c0 6.2-.4 3.2-.4 19.5h-22.8v29.5h27c11.4 67 67.2 101.3 124.6 101.3 26.6 0 50.6-7.9 64.8-15.8l-10-46.1c-8.7 4.6-28.2 10.8-47.3 10.8-28.2 0-58.1-10.9-67.3-50.2h90.3l128.3 56.8c-1.5 2.1-56.2 104.3-178.8 104.3zm-16.7-190.6l-.5-.4.9.4h-.4zm77.2-19.5h3.7v-29.5h-70.3l-28.6-12.6c2.5-5.5 5.4-10.5 8.8-14.3 12.9-15.8 31.1-22.4 51.1-22.4 18.3 0 35.3 5.4 46.1 10l11.6-47.3c-15-6.6-37-12.4-62.3-12.4-39 0-72.2 15.8-95.9 42.3-5.3 6.1-9.8 12.9-13.9 20.1l-81.6-36.1c64.6-96.8 157.7-93.6 170.7-93.6 113 0 203 90.2 203 203.4 0 18.7-2.1 36.3-6.3 52.9l-136.1-60.5z\"],\n    \"creative-commons-nc-jp\": [496, 512, [], \"f4ea\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.4 111.8 248 247.7 248C377.9 504 496 403.2 496 256 496 117.2 388.5 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-21.1 3-41.2 9-60.3l127 56.5h-27.9v38.6h58.1l5.7 11.8v18.7h-63.8V360h63.8v56h61.7v-56h64.2v-35.7l81 36.1c-1.5 2.2-57.1 98.3-175.2 98.3zm87.6-137.3h-57.6v-18.7l2.9-5.6 54.7 24.3zm6.5-51.4v-17.8h-38.6l63-116H301l-43.4 96-23-10.2-39.6-85.7h-65.8l27.3 51-81.9-36.5c27.8-44.1 82.6-98.1 173.7-98.1 112.8 0 203 90 203 203.4 0 21-2.7 40.6-7.9 59l-101-45.1z\"],\n    \"creative-commons-nd\": [496, 512, [], \"f4eb\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm94 144.3v42.5H162.1V197h180.3zm0 79.8v42.5H162.1v-42.5h180.3z\"],\n    \"creative-commons-pd\": [496, 512, [], \"f4ec\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm0 449.5c-139.2 0-235.8-138-190.2-267.9l78.8 35.1c-2.1 10.5-3.3 21.5-3.3 32.9 0 99 73.9 126.9 120.4 126.9 22.9 0 53.5-6.7 79.4-29.5L297 311.1c-5.5 6.3-17.6 16.7-36.3 16.7-37.8 0-53.7-39.9-53.9-71.9 230.4 102.6 216.5 96.5 217.9 96.8-34.3 62.4-100.6 104.8-176.7 104.8zm194.2-150l-224-100c18.8-34 54.9-30.7 74.7-11l40.4-41.6c-27.1-23.3-58-27.5-78.1-27.5-47.4 0-80.9 20.5-100.7 51.6l-74.9-33.4c36.1-54.9 98.1-91.2 168.5-91.2 111.1 0 201.5 90.4 201.5 201.5 0 18-2.4 35.4-6.8 52-.3-.1-.4-.2-.6-.4z\"],\n    \"creative-commons-pd-alt\": [496, 512, [], \"f4ed\", \"M247.6 8C104.7 8 0 123.1 0 256c0 138.5 113.6 248 247.6 248C377.5 504 496 403.1 496 256 496 118.1 389.4 8 247.6 8zm.8 450.8c-112.5 0-203.7-93-203.7-202.8 0-105.4 85.5-203.3 203.7-203.3 112.6 0 202.9 89.5 202.8 203.3 0 121.7-99.6 202.8-202.8 202.8zM316.7 186h-53.2v137.2h53.2c21.4 0 70-5.1 70-68.6 0-63.4-48.6-68.6-70-68.6zm.8 108.5h-19.9v-79.7l19.4-.1c3.8 0 35-2.1 35 39.9 0 24.6-10.5 39.9-34.5 39.9zM203.7 186h-68.2v137.3h34.6V279h27c54.1 0 57.1-37.5 57.1-46.5 0-31-16.8-46.5-50.5-46.5zm-4.9 67.3h-29.2v-41.6h28.3c30.9 0 28.8 41.6.9 41.6z\"],\n    \"creative-commons-remix\": [496, 512, [], \"f4ee\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm161.7 207.7l4.9 2.2v70c-7.2 3.6-63.4 27.5-67.3 28.8-6.5-1.8-113.7-46.8-137.3-56.2l-64.2 26.6-63.3-27.5v-63.8l59.3-24.8c-.7-.7-.4 5-.4-70.4l67.3-29.7L361 178.5v61.6l49.1 20.3zm-70.4 81.5v-43.8h-.4v-1.8l-113.8-46.5V295l113.8 46.9v-.4l.4.4zm7.5-57.6l39.9-16.4-36.8-15.5-39 16.4 35.9 15.5zm52.3 38.1v-43L355.2 298v43.4l44.3-19z\"],\n    \"creative-commons-sa\": [496, 512, [], \"f4ef\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zM137.7 221c13-83.9 80.5-95.7 108.9-95.7 99.8 0 127.5 82.5 127.5 134.2 0 63.6-41 132.9-128.9 132.9-38.9 0-99.1-20-109.4-97h62.5c1.5 30.1 19.6 45.2 54.5 45.2 23.3 0 58-18.2 58-82.8 0-82.5-49.1-80.6-56.7-80.6-33.1 0-51.7 14.6-55.8 43.8h18.2l-49.2 49.2-49-49.2h19.4z\"],\n    \"creative-commons-sampling\": [496, 512, [], \"f4f0\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm3.6 53.2c2.8-.3 11.5 1 11.5 11.5l6.6 107.2 4.9-59.3c0-6 4.7-10.6 10.6-10.6 5.9 0 10.6 4.7 10.6 10.6 0 2.5-.5-5.7 5.7 81.5l5.8-64.2c.3-2.9 2.9-9.3 10.2-9.3 3.8 0 9.9 2.3 10.6 8.9l11.5 96.5 5.3-12.8c1.8-4.4 5.2-6.6 10.2-6.6h58v21.3h-50.9l-18.2 44.3c-3.9 9.9-19.5 9.1-20.8-3.1l-4-31.9-7.5 92.6c-.3 3-3 9.3-10.2 9.3-3 0-9.8-2.1-10.6-9.3 0-1.9.6 5.8-6.2-77.9l-5.3 72.2c-1.1 4.8-4.8 9.3-10.6 9.3-2.9 0-9.8-2-10.6-9.3 0-1.9.5 6.7-5.8-87.7l-5.8 94.8c0 6.3-3.6 12.4-10.6 12.4-5.2 0-10.6-4.1-10.6-12l-5.8-87.7c-5.8 92.5-5.3 84-5.3 85.9-1.1 4.8-4.8 9.3-10.6 9.3-3 0-9.8-2.1-10.6-9.3 0-.7-.4-1.1-.4-2.6l-6.2-88.6L182 348c-.7 6.5-6.7 9.3-10.6 9.3-5.8 0-9.6-4.1-10.6-8.9L149.7 272c-2 4-3.5 8.4-11.1 8.4H87.2v-21.3H132l13.7-27.9c4.4-9.9 18.2-7.2 19.9 2.7l3.1 20.4 8.4-97.9c0-6 4.8-10.6 10.6-10.6.5 0 10.6-.2 10.6 12.4l4.9 69.1 6.6-92.6c0-10.1 9.5-10.6 10.2-10.6.6 0 10.6.7 10.6 10.6l5.3 80.6 6.2-97.9c.1-1.1-.6-10.3 9.9-11.5z\"],\n    \"creative-commons-sampling-plus\": [496, 512, [], \"f4f1\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm107 205.6c-4.7 0-9 2.8-10.7 7.2l-4 9.5-11-92.8c-1.7-13.9-22-13.4-23.1.4l-4.3 51.4-5.2-68.8c-1.1-14.3-22.1-14.2-23.2 0l-3.5 44.9-5.9-94.3c-.9-14.5-22.3-14.4-23.2 0l-5.1 83.7-4.3-66.3c-.9-14.4-22.2-14.4-23.2 0l-5.3 80.2-4.1-57c-1.1-14.3-22-14.3-23.2-.2l-7.7 89.8-1.8-12.2c-1.7-11.4-17.1-13.6-22-3.3l-13.2 27.7H87.5v23.2h51.3c4.4 0 8.4-2.5 10.4-6.4l10.7 73.1c2 13.5 21.9 13 23.1-.7l3.8-43.6 5.7 78.3c1.1 14.4 22.3 14.2 23.2-.1l4.6-70.4 4.8 73.3c.9 14.4 22.3 14.4 23.2-.1l4.9-80.5 4.5 71.8c.9 14.3 22.1 14.5 23.2.2l4.6-58.6 4.9 64.4c1.1 14.3 22 14.2 23.1.1l6.8-83 2.7 22.3c1.4 11.8 17.7 14.1 22.3 3.1l18-43.4h50.5V258l-58.4.3zm-78 5.2h-21.9v21.9c0 4.1-3.3 7.5-7.5 7.5-4.1 0-7.5-3.3-7.5-7.5v-21.9h-21.9c-4.1 0-7.5-3.3-7.5-7.5 0-4.1 3.4-7.5 7.5-7.5h21.9v-21.9c0-4.1 3.4-7.5 7.5-7.5s7.5 3.3 7.5 7.5v21.9h21.9c4.1 0 7.5 3.3 7.5 7.5 0 4.1-3.4 7.5-7.5 7.5z\"],\n    \"creative-commons-share\": [496, 512, [], \"f4f2\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm101 132.4c7.8 0 13.7 6.1 13.7 13.7v182.5c0 7.7-6.1 13.7-13.7 13.7H214.3c-7.7 0-13.7-6-13.7-13.7v-54h-54c-7.8 0-13.7-6-13.7-13.7V131.1c0-8.2 6.6-12.7 12.4-13.7h136.4c7.7 0 13.7 6 13.7 13.7v54h54zM159.9 300.3h40.7V198.9c0-7.4 5.8-12.6 12-13.7h55.8v-40.3H159.9v155.4zm176.2-88.1H227.6v155.4h108.5V212.2z\"],\n    \"creative-commons-zero\": [496, 512, [], \"f4f3\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm-.4 60.5c-81.9 0-102.5 77.3-102.5 142.8 0 65.5 20.6 142.8 102.5 142.8S350.5 321.5 350.5 256c0-65.5-20.6-142.8-102.5-142.8zm0 53.9c3.3 0 6.4.5 9.2 1.2 5.9 5.1 8.8 12.1 3.1 21.9l-54.5 100.2c-1.7-12.7-1.9-25.1-1.9-34.4 0-28.8 2-88.9 44.1-88.9zm40.8 46.2c2.9 15.4 3.3 31.4 3.3 42.7 0 28.9-2 88.9-44.1 88.9-13.5 0-32.6-7.7-20.1-26.4l60.9-105.2z\"],\n    \"critical-role\": [448, 512, [], \"f6c9\", \"M225.82 0c.26.15 216.57 124.51 217.12 124.72 3 1.18 3.7 3.46 3.7 6.56q-.11 125.17 0 250.36a5.88 5.88 0 0 1-3.38 5.78c-21.37 12-207.86 118.29-218.93 124.58h-3C142 466.34 3.08 386.56 2.93 386.48a3.29 3.29 0 0 1-1.88-3.24c0-.87 0-225.94-.05-253.1a5 5 0 0 1 2.93-4.93C27.19 112.11 213.2 6 224.07 0zM215.4 20.42l-.22-.16Q118.06 75.55 21 130.87c0 .12.08.23.13.35l30.86 11.64c-7.71 6-8.32 6-10.65 5.13-.1 0-24.17-9.28-26.8-10v230.43c.88-1.41 64.07-110.91 64.13-111 1.62-2.82 3-1.92 9.12-1.52 1.4.09 1.48.22.78 1.42-41.19 71.33-36.4 63-67.48 116.94-.81 1.4-.61 1.13 1.25 1.13h186.5c1.44 0 1.69-.23 1.7-1.64v-8.88c0-1.34 2.36-.81-18.37-1-7.46-.07-14.14-3.22-21.38-12.7-7.38-9.66-14.62-19.43-21.85-29.21-2.28-3.08-3.45-2.38-16.76-2.38-1.75 0-1.78 0-1.76 1.82.29 26.21.15 25.27 1 32.66.52 4.37 2.16 4.2 9.69 4.81 3.14.26 3.88 4.08.52 4.92-1.57.39-31.6.51-33.67-.1a2.42 2.42 0 0 1 .3-4.73c3.29-.76 6.16.81 6.66-4.44 1.3-13.66 1.17-9 1.1-79.42 0-10.82-.35-12.58-5.36-13.55-1.22-.24-3.54-.16-4.69-.55-2.88-1-2-4.84 1.77-4.85 33.67 0 46.08-1.07 56.06 4.86 7.74 4.61 12 11.48 12.51 20.4.88 14.59-6.51 22.35-15 32.59a1.46 1.46 0 0 0 0 2.22c2.6 3.25 5 6.63 7.71 9.83 27.56 33.23 24.11 30.54 41.28 33.06.89.13 1-.42 1-1.15v-11c0-1 .32-1.43 1.41-1.26a72.37 72.37 0 0 0 23.58-.3c1.08-.15 1.5.2 1.48 1.33 0 .11.88 26.69.87 26.8-.05 1.52.67 1.62 1.89 1.62h186.71Q386.51 304.6 346 234.33c2.26-.66-.4 0 6.69-1.39 2-.39 2.05-.41 3.11 1.44 7.31 12.64 77.31 134 77.37 134.06V138c-1.72.5-103.3 38.72-105.76 39.68-1.08.42-1.55.2-1.91-.88-.63-1.9-1.34-3.76-2.09-5.62-.32-.79-.09-1.13.65-1.39.1 0 95.53-35.85 103-38.77-65.42-37.57-130.56-75-196-112.6l86.82 150.39-.28.33c-9.57-.9-10.46-1.6-11.8-3.94-1-1.69-73.5-127.71-82-142.16-9.1 14.67-83.56 146.21-85.37 146.32-2.93.17-5.88.08-9.25.08q43.25-74.74 86.18-149zm51.93 129.92a37.68 37.68 0 0 0 5.54-.85c1.69-.3 2.53.2 2.6 1.92 0 .11.07 19.06-.86 20.45s-1.88 1.22-2.6-.19c-5-9.69 6.22-9.66-39.12-12-.7 0-1 .23-1 .93 0 .13 3.72 122 3.73 122.11 0 .89.52 1.2 1.21 1.51a83.92 83.92 0 0 1 8.7 4.05c7.31 4.33 11.38 10.84 12.41 19.31 1.44 11.8-2.77 35.77-32.21 37.14-2.75.13-28.26 1.08-34.14-23.25-4.66-19.26 8.26-32.7 19.89-36.4a2.45 2.45 0 0 0 2-2.66c.1-5.63 3-107.1 3.71-121.35.05-1.08-.62-1.16-1.35-1.15-32.35.52-36.75-.34-40.22 8.52-2.42 6.18-4.14 1.32-3.95.23q1.59-9 3.31-18c.4-2.11 1.43-2.61 3.43-1.86 5.59 2.11 6.72 1.7 37.25 1.92 1.73 0 1.78-.08 1.82-1.85.68-27.49.58-22.59 1-29.55a2.69 2.69 0 0 0-1.63-2.8c-5.6-2.91-8.75-7.55-8.9-13.87-.35-14.81 17.72-21.67 27.38-11.51 6.84 7.19 5.8 18.91-2.45 24.15a4.35 4.35 0 0 0-2.22 4.34c0 .59-.11-4.31 1 30.05 0 .9.43 1.12 1.24 1.11.1 0 23-.09 34.47-.37zM68.27 141.7c19.84-4.51 32.68-.56 52.49 1.69 2.76.31 3.74 1.22 3.62 4-.21 5-1.16 22.33-1.24 23.15a2.65 2.65 0 0 1-1.63 2.34c-4.06 1.7-3.61-4.45-4-7.29-3.13-22.43-73.87-32.7-74.63 25.4-.31 23.92 17 53.63 54.08 50.88 27.24-2 19-20.19 24.84-20.47a2.72 2.72 0 0 1 3 3.36c-1.83 10.85-3.42 18.95-3.45 19.15-1.54 9.17-86.7 22.09-93.35-42.06-2.71-25.85 10.44-53.37 40.27-60.15zm80 87.67h-19.49a2.57 2.57 0 0 1-2.66-1.79c2.38-3.75 5.89.92 5.86-6.14-.08-25.75.21-38 .23-40.1 0-3.42-.53-4.65-3.32-4.94-7-.72-3.11-3.37-1.11-3.38 11.84-.1 22.62-.18 30.05.72 8.77 1.07 16.71 12.63 7.93 22.62-2 2.25-4 4.42-6.14 6.73.95 1.15 6.9 8.82 17.28 19.68 2.66 2.78 6.15 3.51 9.88 3.13a2.21 2.21 0 0 0 2.23-2.12c.3-3.42.26 4.73.45-40.58 0-5.65-.34-6.58-3.23-6.83-3.95-.35-4-2.26-.69-3.37l19.09-.09c.32 0 4.49.53 1 3.38 0 .05-.16 0-.24 0-3.61.26-3.94 1-4 4.62-.27 43.93.07 40.23.41 42.82.11.84.27 2.23 5.1 2.14 2.49 0 3.86 3.37 0 3.4-10.37.08-20.74 0-31.11.07-10.67 0-13.47-6.2-24.21-20.82-1.6-2.18-8.31-2.36-8.2-.37.88 16.47 0 17.78 4 17.67 4.75-.1 4.73 3.57.83 3.55zm275-10.15c-1.21 7.13.17 10.38-5.3 10.34-61.55-.42-47.82-.22-50.72-.31a18.4 18.4 0 0 1-3.63-.73c-2.53-.6 1.48-1.23-.38-5.6-1.43-3.37-2.78-6.78-4.11-10.19a1.94 1.94 0 0 0-2-1.44 138 138 0 0 0-14.58.07 2.23 2.23 0 0 0-1.62 1.06c-1.58 3.62-3.07 7.29-4.51 11-1.27 3.23 7.86 1.32 12.19 2.16 3 .57 4.53 3.72.66 3.73H322.9c-2.92 0-3.09-3.15-.74-3.21a6.3 6.3 0 0 0 5.92-3.47c1.5-3 2.8-6 4.11-9.09 18.18-42.14 17.06-40.17 18.42-41.61a1.83 1.83 0 0 1 3 0c2.93 3.34 18.4 44.71 23.62 51.92 2 2.7 5.74 2 6.36 2 3.61.13 4-1.11 4.13-4.29.09-1.87.08 1.17.07-41.24 0-4.46-2.36-3.74-5.55-4.27-.26 0-2.56-.63-.08-3.06.21-.2-.89-.24 21.7-.15 2.32 0 5.32 2.75-1.21 3.45a2.56 2.56 0 0 0-2.66 2.83c-.07 1.63-.19 38.89.29 41.21a3.06 3.06 0 0 0 3.23 2.43c13.25.43 14.92.44 16-3.41 1.67-5.78 4.13-2.52 3.73-.19zm-104.72 64.37c-4.24 0-4.42-3.39-.61-3.41 35.91-.16 28.11.38 37.19-.65 1.68-.19 2.38.24 2.25 1.89-.26 3.39-.64 6.78-1 10.16-.25 2.16-3.2 2.61-3.4-.15-.38-5.31-2.15-4.45-15.63-5.08-1.58-.07-1.64 0-1.64 1.52V304c0 1.65 0 1.6 1.62 1.47 3.12-.25 10.31.34 15.69-1.52.47-.16 3.3-1.79 3.07 1.76 0 .21-.76 10.35-1.18 11.39-.53 1.29-1.88 1.51-2.58.32-1.17-2 0-5.08-3.71-5.3-15.42-.9-12.91-2.55-12.91 6 0 12.25-.76 16.11 3.89 16.24 16.64.48 14.4 0 16.43-5.71.84-2.37 3.5-1.77 3.18.58-.44 3.21-.85 6.43-1.23 9.64 0 .36-.16 2.4-4.66 2.39-37.16-.08-34.54-.19-35.21-.31-2.72-.51-2.2-3 .22-3.45 1.1-.19 4 .54 4.16-2.56 2.44-56.22-.07-51.34-3.91-51.33zm-.41-109.52c2.46.61 3.13 1.76 2.95 4.65-.33 5.3-.34 9-.55 9.69-.66 2.23-3.15 2.12-3.34-.27-.38-4.81-3.05-7.82-7.57-9.15-26.28-7.73-32.81 15.46-27.17 30.22 5.88 15.41 22 15.92 28.86 13.78 5.92-1.85 5.88-6.5 6.91-7.58 1.23-1.3 2.25-1.84 3.12 1.1 0 .1.57 11.89-6 12.75-1.6.21-19.38 3.69-32.68-3.39-21-11.19-16.74-35.47-6.88-45.33 14-14.06 39.91-7.06 42.32-6.47zM289.8 280.14c3.28 0 3.66 3 .16 3.43-2.61.32-5-.42-5 5.46 0 2-.19 29.05.4 41.45.11 2.29 1.15 3.52 3.44 3.65 22 1.21 14.95-1.65 18.79-6.34 1.83-2.24 2.76.84 2.76 1.08.35 13.62-4 12.39-5.19 12.4l-38.16-.19c-1.93-.23-2.06-3-.42-3.38 2-.48 4.94.4 5.13-2.8 1-15.87.57-44.65.34-47.81-.27-3.77-2.8-3.27-5.68-3.71-2.47-.38-2-3.22.34-3.22 1.45-.02 17.97-.03 23.09-.02zm-31.63-57.79c.07 4.08 2.86 3.46 6 3.58 2.61.1 2.53 3.41-.07 3.43-6.48 0-13.7 0-21.61-.06-3.84 0-3.38-3.35 0-3.37 4.49 0 3.24 1.61 3.41-45.54 0-5.08-3.27-3.54-4.72-4.23-2.58-1.23-1.36-3.09.41-3.15 1.29 0 20.19-.41 21.17.21s1.87 1.65-.42 2.86c-1 .52-3.86-.28-4.15 2.47 0 .21-.82 1.63-.07 43.8zm-36.91 274.27a2.93 2.93 0 0 0 3.26 0c17-9.79 182-103.57 197.42-112.51-.14-.43 11.26-.18-181.52-.27-1.22 0-1.57.37-1.53 1.56 0 .1 1.25 44.51 1.22 50.38a28.33 28.33 0 0 1-1.36 7.71c-.55 1.83.38-.5-13.5 32.23-.73 1.72-1 2.21-2-.08-4.19-10.34-8.28-20.72-12.57-31a23.6 23.6 0 0 1-2-10.79c.16-2.46.8-16.12 1.51-48 0-1.95 0-2-2-2h-183c2.58 1.63 178.32 102.57 196 112.76zm-90.9-188.75c0 2.4.36 2.79 2.76 3 11.54 1.17 21 3.74 25.64-7.32 6-14.46 2.66-34.41-12.48-38.84-2-.59-16-2.76-15.94 1.51.05 8.04.01 11.61.02 41.65zm105.75-15.05c0 2.13 1.07 38.68 1.09 39.13.34 9.94-25.58 5.77-25.23-2.59.08-2 1.37-37.42 1.1-39.43-14.1 7.44-14.42 40.21 6.44 48.8a17.9 17.9 0 0 0 22.39-7.07c4.91-7.76 6.84-29.47-5.43-39a2.53 2.53 0 0 1-.36.12zm-12.28-198c-9.83 0-9.73 14.75-.07 14.87s10.1-14.88.07-14.91zm-80.15 103.83c0 1.8.41 2.4 2.17 2.58 13.62 1.39 12.51-11 12.16-13.36-1.69-11.22-14.38-10.2-14.35-7.81.05 4.5-.03 13.68.02 18.59zm212.32 6.4l-6.1-15.84c-2.16 5.48-4.16 10.57-6.23 15.84z\"],\n    \"css3\": [512, 512, [], \"f13c\", \"M480 32l-64 368-223.3 80L0 400l19.6-94.8h82l-8 40.6L210 390.2l134.1-44.4 18.8-97.1H29.5l16-82h333.7l10.5-52.7H56.3l16.3-82H480z\"],\n    \"css3-alt\": [384, 512, [], \"f38b\", \"M0 32l34.9 395.8L192 480l157.1-52.2L384 32H0zm313.1 80l-4.8 47.3L193 208.6l-.3.1h111.5l-12.8 146.6-98.2 28.7-98.8-29.2-6.4-73.9h48.9l3.2 38.3 52.6 13.3 54.7-15.4 3.7-61.6-166.3-.5v-.1l-.2.1-3.6-46.3L193.1 162l6.5-2.7H76.7L70.9 112h242.2z\"],\n    \"cuttlefish\": [440, 512, [], \"f38c\", \"M344 305.5c-17.5 31.6-57.4 54.5-96 54.5-56.6 0-104-47.4-104-104s47.4-104 104-104c38.6 0 78.5 22.9 96 54.5 13.7-50.9 41.7-93.3 87-117.8C385.7 39.1 320.5 8 248 8 111 8 0 119 0 256s111 248 248 248c72.5 0 137.7-31.1 183-80.7-45.3-24.5-73.3-66.9-87-117.8z\"],\n    \"d-and-d\": [576, 512, [], \"f38d\", \"M82.5 98.9c-.6-17.2 2-33.8 12.7-48.2.3 7.4 1.2 14.5 4.2 21.6 5.9-27.5 19.7-49.3 42.3-65.5-1.9 5.9-3.5 11.8-3 17.7 8.7-7.4 18.8-17.8 44.4-22.7 14.7-2.8 29.7-2 42.1 1 38.5 9.3 61 34.3 69.7 72.3 5.3 23.1.7 45-8.3 66.4-5.2 12.4-12 24.4-20.7 35.1-2-1.9-3.9-3.8-5.8-5.6-42.8-40.8-26.8-25.2-37.4-37.4-1.1-1.2-1-2.2-.1-3.6 8.3-13.5 11.8-28.2 10-44-1.1-9.8-4.3-18.9-11.3-26.2-14.5-15.3-39.2-15-53.5.6-11.4 12.5-14.1 27.4-10.9 43.6.2 1.3.4 2.7 0 3.9-3.4 13.7-4.6 27.6-2.5 41.6.1.5.1 1.1.1 1.6 0 .3-.1.5-.2 1.1-21.8-11-36-28.3-43.2-52.2-8.3 17.8-11.1 35.5-6.6 54.1-15.6-15.2-21.3-34.3-22-55.2zm469.6 123.2c-11.6-11.6-25-20.4-40.1-26.6-12.8-5.2-26-7.9-39.9-7.1-10 .6-19.6 3.1-29 6.4-2.5.9-5.1 1.6-7.7 2.2-4.9 1.2-7.3-3.1-4.7-6.8 3.2-4.6 3.4-4.2 15-12 .6-.4 1.2-.8 2.2-1.5h-2.5c-.6 0-1.2.2-1.9.3-19.3 3.3-30.7 15.5-48.9 29.6-10.4 8.1-13.8 3.8-12-.5 1.4-3.5 3.3-6.7 5.1-10 1-1.8 2.3-3.4 3.5-5.1-.2-.2-.5-.3-.7-.5-27 18.3-46.7 42.4-57.7 73.3.3.3.7.6 1 .9.3-.6.5-1.2.9-1.7 10.4-12.1 22.8-21.8 36.6-29.8 18.2-10.6 37.5-18.3 58.7-20.2 4.3-.4 8.7-.1 13.1-.1-1.8.7-3.5.9-5.3 1.1-18.5 2.4-35.5 9-51.5 18.5-30.2 17.9-54.5 42.2-75.1 70.4-.3.4-.4.9-.7 1.3 14.5 5.3 24 17.3 36.1 25.6.2-.1.3-.2.4-.4l1.2-2.7c12.2-26.9 27-52.3 46.7-74.5 16.7-18.8 38-25.3 62.5-20 5.9 1.3 11.4 4.4 17.2 6.8 2.3-1.4 5.1-3.2 8-4.7 8.4-4.3 17.4-7 26.7-9 14.7-3.1 29.5-4.9 44.5-1.3v-.5c-.5-.4-1.2-.8-1.7-1.4zM316.7 397.6c-39.4-33-22.8-19.5-42.7-35.6-.8.9 0-.2-1.9 3-11.2 19.1-25.5 35.3-44 47.6-10.3 6.8-21.5 11.8-34.1 11.8-21.6 0-38.2-9.5-49.4-27.8-12-19.5-13.3-40.7-8.2-62.6 7.8-33.8 30.1-55.2 38.6-64.3-18.7-6.2-33 1.7-46.4 13.9.8-13.9 4.3-26.2 11.8-37.3-24.3 10.6-45.9 25-64.8 43.9-.3-5.8 5.4-43.7 5.6-44.7.3-2.7-.6-5.3-3-7.4-24.2 24.7-44.5 51.8-56.1 84.6 7.4-5.9 14.9-11.4 23.6-16.2-8.3 22.3-19.6 52.8-7.8 101.1 4.6 19 11.9 36.8 24.1 52.3 2.9 3.7 6.3 6.9 9.5 10.3.2-.2.4-.3.6-.5-1.4-7-2.2-14.1-1.5-21.9 2.2 3.2 3.9 6 5.9 8.6 12.6 16 28.7 27.4 47.2 35.6 25 11.3 51.1 13.3 77.9 8.6 54.9-9.7 90.7-48.6 116-98.8 1-1.8.6-2.9-.9-4.2zm172-46.4c-9.5-3.1-22.2-4.2-28.7-2.9 9.9 4 14.1 6.6 18.8 12 12.6 14.4 10.4 34.7-5.4 45.6-11.7 8.1-24.9 10.5-38.9 9.1-1.2-.1-2.3-.4-3-.6 2.8-3.7 6-7 8.1-10.8 9.4-16.8 5.4-42.1-8.7-56.1-2.1-2.1-4.6-3.9-7-5.9-.3 1.3-.1 2.1.1 2.8 4.2 16.6-8.1 32.4-24.8 31.8-7.6-.3-13.9-3.8-19.6-8.5-19.5-16.1-39.1-32.1-58.5-48.3-5.9-4.9-12.5-8.1-20.1-8.7-4.6-.4-9.3-.6-13.9-.9-5.9-.4-8.8-2.8-10.4-8.4-.9-3.4-1.5-6.8-2.2-10.2-1.5-8.1-6.2-13-14.3-14.2-4.4-.7-8.9-1-13.3-1.5-13-1.4-19.8-7.4-22.6-20.3-5 11-1.6 22.4 7.3 29.9 4.5 3.8 9.3 7.3 13.8 11.2 4.6 3.8 7.4 8.7 7.9 14.8.4 4.7.8 9.5 1.8 14.1 2.2 10.6 8.9 18.4 17 25.1 16.5 13.7 33 27.3 49.5 41.1 17.9 15 13.9 32.8 13 56-.9 22.9 12.2 42.9 33.5 51.2 1 .4 2 .6 3.6 1.1-15.7-18.2-10.1-44.1.7-52.3.3 2.2.4 4.3.9 6.4 9.4 44.1 45.4 64.2 85 56.9 16-2.9 30.6-8.9 42.9-19.8 2-1.8 3.7-4.1 5.9-6.5-19.3 4.6-35.8.1-50.9-10.6.7-.3 1.3-.3 1.9-.3 21.3 1.8 40.6-3.4 57-17.4 19.5-16.6 26.6-42.9 17.4-66-8.3-20.1-23.6-32.3-43.8-38.9zM99.4 179.3c-5.3-9.2-13.2-15.6-22.1-21.3 13.7-.5 26.6.2 39.6 3.7-7-12.2-8.5-24.7-5-38.7 5.3 11.9 13.7 20.1 23.6 26.8 19.7 13.2 35.7 19.6 46.7 30.2 3.4 3.3 6.3 7.1 9.6 10.9-.8-2.1-1.4-4.1-2.2-6-5-10.6-13-18.6-22.6-25-1.8-1.2-2.8-2.5-3.4-4.5-3.3-12.5-3-25.1-.7-37.6 1-5.5 2.8-10.9 4.5-16.3.8-2.4 2.3-4.6 4-6.6.6 6.9 0 25.5 19.6 46 10.8 11.3 22.4 21.9 33.9 32.7 9 8.5 18.3 16.7 25.5 26.8 1.1 1.6 2.2 3.3 3.8 4.7-5-13-14.2-24.1-24.2-33.8-9.6-9.3-19.4-18.4-29.2-27.4-3.3-3-4.6-6.7-5.1-10.9-1.2-10.4 0-20.6 4.3-30.2.5-1 1.1-2 1.9-3.3.5 4.2.6 7.9 1.4 11.6 4.8 23.1 20.4 36.3 49.3 63.5 10 9.4 19.3 19.2 25.6 31.6 4.8 9.3 7.3 19 5.7 29.6-.1.6.5 1.7 1.1 2 6.2 2.6 10 6.9 9.7 14.3 7.7-2.6 12.5-8 16.4-14.5 4.2 20.2-9.1 50.3-27.2 58.7.4-4.5 5-23.4-16.5-27.7-6.8-1.3-12.8-1.3-22.9-2.1 4.7-9 10.4-20.6.5-22.4-24.9-4.6-52.8 1.9-57.8 4.6 8.2.4 16.3 1 23.5 3.3-2 6.5-4 12.7-5.8 18.9-1.9 6.5 2.1 14.6 9.3 9.6 1.2-.9 2.3-1.9 3.3-2.7-3.1 17.9-2.9 15.9-2.8 18.3.3 10.2 9.5 7.8 15.7 7.3-2.5 11.8-29.5 27.3-45.4 25.8 7-4.7 12.7-10.3 15.9-17.9-6.5.8-12.9 1.6-19.2 2.4l-.3-.9c4.7-3.4 8-7.8 10.2-13.1 8.7-21.1-3.6-38-25-39.9-9.1-.8-17.8.8-25.9 5.5 6.2-15.6 17.2-26.6 32.6-34.5-15.2-4.3-8.9-2.7-24.6-6.3 14.6-9.3 30.2-13.2 46.5-14.6-5.2-3.2-48.1-3.6-70.2 20.9 7.9 1.4 15.5 2.8 23.2 4.2-23.8 7-44 19.7-62.4 35.6 1.1-4.8 2.7-9.5 3.3-14.3.6-4.5.8-9.2.1-13.6-1.5-9.4-8.9-15.1-19.7-16.3-7.9-.9-15.6.1-23.3 1.3-.9.1-1.7.3-2.9 0 15.8-14.8 36-21.7 53.1-33.5 6-4.5 6.8-8.2 3-14.9zm128.4 26.8c3.3 16 12.6 25.5 23.8 24.3-4.6-11.3-12.1-19.5-23.8-24.3z\"],\n    \"d-and-d-beyond\": [640, 512, [], \"f6ca\", \"M313.8 241.5c13.8 0 21-10.1 24.8-17.9-1-1.1-5-4.2-7.4-6.6-2.4 4.3-8.2 10.7-13.9 10.7-10.2 0-15.4-14.7-3.2-26.6-.5-.2-4.3-1.8-8 2.4 0-3 1-5.1 2.1-6.6-3.5 1.3-9.8 5.6-11.4 7.9.2-5.8 1.6-7.5.6-9l-.2-.2s-8.5 5.6-9.3 14.7c0 0 1.1-1.6 2.1-1.9.6-.3 1.3 0 .6 1.9-.2.6-5.8 15.7 5.1 26-.6-1.6-1.9-7.6 2.4-1.9-.3.1 5.8 7.1 15.7 7.1zm52.4-21.1c0-4-4.9-4.4-5.6-4.5 2 3.9.9 7.5.2 9 2.5-.4 5.4-1.6 5.4-4.5zm10.3 5.2c0-6.4-6.2-11.4-13.5-10.7 8 1.3 5.6 13.8-5 11.4 3.7-2.6 3.2-9.9-1.3-12.5 1.4 4.2-3 8.2-7.4 4.6-2.4-1.9-8-6.6-10.6-8.6-2.4-2.1-5.5-1-6.6-1.8-1.3-1.1-.5-3.8-2.2-5-1.6-.8-3-.3-4.8-1-1.6-.6-2.7-1.9-2.6-3.5-2.5 4.4 3.4 6.3 4.5 8.5 1 1.9-.8 4.8 4 8.5 14.8 11.6 9.1 8 10.4 18.1.6 4.3 4.2 6.7 6.4 7.4-2.1-1.9-2.9-6.4 0-9.3 0 13.9 19.2 13.3 23.1 6.4-2.4 1.1-7-.2-9-1.9 7.7 1 14.2-4.1 14.6-10.6zm-39.4-18.4c2 .8 1.6.7 6.4 4.5 10.2-24.5 21.7-15.7 22-15.5 2.2-1.9 9.8-3.8 13.8-2.7-2.4-2.7-7.5-6.2-13.3-6.2-4.7 0-7.4 2.2-8 1.3-.8-1.4 3.2-3.4 3.2-3.4-5.4.2-9.6 6.7-11.2 5.9-1.1-.5 1.4-3.7 1.4-3.7-5.1 2.9-9.3 9.1-10.2 13 4.6-5.8 13.8-9.8 19.7-9-10.5.5-19.5 9.7-23.8 15.8zm242.5 51.9c-20.7 0-40 1.3-50.3 2.1l7.4 8.2v77.2l-7.4 8.2c10.4.8 30.9 2.1 51.6 2.1 42.1 0 59.1-20.7 59.1-48.9 0-29.3-23.2-48.9-60.4-48.9zm-15.1 75.6v-53.3c30.1-3.3 46.8 3.8 46.8 26.3 0 25.6-21.4 30.2-46.8 27zM301.6 181c-1-3.4-.2-6.9 1.1-9.4 1 3 2.6 6.4 7.5 9-.5-2.4-.2-5.6.5-8-1.4-5.4 2.1-9.9 6.4-9.9 6.9 0 8.5 8.8 4.7 14.4 2.1 3.2 5.5 5.6 7.7 7.8 3.2-3.7 5.5-9.5 5.5-13.8 0-8.2-5.5-15.9-16.7-16.5-20-.9-20.2 16.6-20 18.9.5 5.2 3.4 7.8 3.3 7.5zm-.4 6c-.5 1.8-7 3.7-10.2 6.9 4.8-1 7-.2 7.8 1.8.5 1.4-.2 3.4-.5 5.6 1.6-1.8 7-5.5 11-6.2-1-.3-3.4-.8-4.3-.8 2.9-3.4 9.3-4.5 12.8-3.7-2.2-.2-6.7 1.1-8.5 2.6 1.6.3 3 .6 4.3 1.1-2.1.8-4.8 3.4-5.8 6.1 7-5 13.1 5.2 7 8.2.8.2 2.7 0 3.5-.5-.3 1.1-1.9 3-3 3.4 2.9 0 7-1.9 8.2-4.6 0 0-1.8.6-2.6-.2s.3-4.3.3-4.3c-2.3 2.9-3.4-1.3-1.3-4.2-1-.3-3.5-.6-4.6-.5 3.2-1.1 10.4-1.8 11.2-.3.6 1.1-1 3.4-1 3.4 4-.5 8.3 1.1 6.7 5.1 2.9-1.4 5.5-5.9 4.8-10.4-.3 1-1.6 2.4-2.9 2.7.2-1.4-1-2.2-1.9-2.6 1.7-9.6-14.6-14.2-14.1-23.9-1 1.3-1.8 5-.8 7.1 2.7 3.2 8.7 6.7 10.1 12.2-2.6-6.4-15.1-11.4-14.6-20.2-1.6 1.6-2.6 7.8-1.3 11 2.4 1.4 4.5 3.8 4.8 6.1-2.2-5.1-11.4-6.1-13.9-12.2-.6 2.2-.3 5 1 6.7 0 0-2.2-.8-7-.6 1.7.6 5.1 3.5 4.8 5.2zm25.9 7.4c-2.7 0-3.5-2.1-4.2-4.3 3.3 1.3 4.2 4.3 4.2 4.3zm38.9 3.7l-1-.6c-1.1-1-2.9-1.4-4.7-1.4-2.9 0-5.8 1.3-7.5 3.4-.8.8-1.4 1.8-2.1 2.6v15.7c3.5 2.6 7.1-2.9 3-7.2 1.5.3 4.6 2.7 5.1 3.2 0 0 2.6-.5 5-.5 2.1 0 3.9.3 5.6 1.1V196c-1.1.5-2.2 1-2.7 1.4zM79.9 305.9c17.2-4.6 16.2-18 16.2-19.9 0-20.6-24.1-25-37-25H3l8.3 8.6v29.5H0l11.4 14.6V346L3 354.6c61.7 0 73.8 1.5 86.4-5.9 6.7-4 9.9-9.8 9.9-17.6 0-5.1 2.6-18.8-19.4-25.2zm-41.3-27.5c20 0 29.6-.8 29.6 9.1v3c0 12.1-19 8.8-29.6 8.8zm0 59.2V315c12.2 0 32.7-2.3 32.7 8.8v4.5h.2c0 11.2-12.5 9.3-32.9 9.3zm101.2-19.3l23.1.2v-.2l14.1-21.2h-37.2v-14.9h52.4l-14.1-21v-.2l-73.5.2 7.4 8.2v77.1l-7.4 8.2h81.2l14.1-21.2-60.1.2zm214.7-60.1c-73.9 0-77.5 99.3-.3 99.3 77.9 0 74.1-99.3.3-99.3zm-.3 77.5c-37.4 0-36.9-55.3.2-55.3 36.8.1 38.8 55.3-.2 55.3zm-91.3-8.3l44.1-66.2h-41.7l6.1 7.2-20.5 37.2h-.3l-21-37.2 6.4-7.2h-44.9l44.1 65.8.2 19.4-7.7 8.2h42.6l-7.2-8.2zm-28.4-151.3c1.6 1.3 2.9 2.4 2.9 6.6v38.8c0 4.2-.8 5.3-2.7 6.4-.1.1-7.5 4.5-7.9 4.6h35.1c10 0 17.4-1.5 26-8.6-.6-5 .2-9.5.8-12 0-.2-1.8 1.4-2.7 3.5 0-5.7 1.6-15.4 9.6-20.5-.1 0-3.7-.8-9 1.1 2-3.1 10-7.9 10.4-7.9-8.2-26-38-22.9-32.2-22.9-30.9 0-32.6.3-39.9-4 .1.8.5 8.2 9.6 14.9zm21.5 5.5c4.6 0 23.1-3.3 23.1 17.3 0 20.7-18.4 17.3-23.1 17.3zm228.9 79.6l7 8.3V312h-.3c-5.4-14.4-42.3-41.5-45.2-50.9h-31.6l7.4 8.5v76.9l-7.2 8.3h39l-7.4-8.2v-47.4h.3c3.7 10.6 44.5 42.9 48.5 55.6h21.3v-85.2l7.4-8.3zm-106.7-96.1c-32.2 0-32.8.2-39.9-4 .1.7.5 8.3 9.6 14.9 3.1 2 2.9 4.3 2.9 9.5 1.8-1.1 3.8-2.2 6.1-3-1.1 1.1-2.7 2.7-3.5 4.5 1-1.1 7.5-5.1 14.6-3.5-1.6.3-4 1.1-6.1 2.9.1 0 2.1-1.1 7.5-.3v-4.3c4.7 0 23.1-3.4 23.1 17.3 0 20.5-18.5 17.3-19.7 17.3 5.7 4.4 5.8 12 2.2 16.3h.3c33.4 0 36.7-27.3 36.7-34 0-3.8-1.1-32-33.8-33.6z\"],\n    \"dashcube\": [448, 512, [], \"f210\", \"M326.6 104H110.4c-51.1 0-91.2 43.3-91.2 93.5V427c0 50.5 40.1 85 91.2 85h227.2c51.1 0 91.2-34.5 91.2-85V0L326.6 104zM153.9 416.5c-17.7 0-32.4-15.1-32.4-32.8V240.8c0-17.7 14.7-32.5 32.4-32.5h140.7c17.7 0 32 14.8 32 32.5v123.5l51.1 52.3H153.9z\"],\n    \"delicious\": [448, 512, [], \"f1a5\", \"M446.5 68c-.4-1.5-.9-3-1.4-4.5-.9-2.5-2-4.8-3.3-7.1-1.4-2.4-3-4.8-4.7-6.9-2.1-2.5-4.4-4.8-6.9-6.8-1.1-.9-2.2-1.7-3.3-2.5-1.3-.9-2.6-1.7-4-2.4-1.8-1-3.6-1.8-5.5-2.5-1.7-.7-3.5-1.3-5.4-1.7-3.8-1-7.9-1.5-12-1.5H48C21.5 32 0 53.5 0 80v352c0 4.1.5 8.2 1.5 12 2 7.7 5.8 14.6 11 20.3 1 1.1 2.1 2.2 3.3 3.3 5.7 5.2 12.6 9 20.3 11 3.8 1 7.9 1.5 12 1.5h352c26.5 0 48-21.5 48-48V80c-.1-4.1-.6-8.2-1.6-12zM416 432c0 8.8-7.2 16-16 16H224V256H32V80c0-8.8 7.2-16 16-16h176v192h192z\"],\n    \"deploydog\": [512, 512, [], \"f38e\", \"M382.2 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.6 0-33.2 16.4-33.2 32.6zM188.5 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.7 0-33.2 16.4-33.2 32.6zM448 96c17.5 0 32 14.4 32 32v256c0 17.5-14.4 32-32 32H64c-17.5 0-32-14.4-32-32V128c0-17.5 14.4-32 32-32h384m0-32H64C28.8 64 0 92.8 0 128v256c0 35.2 28.8 64 64 64h384c35.2 0 64-28.8 64-64V128c0-35.2-28.8-64-64-64z\"],\n    \"deskpro\": [480, 512, [], \"f38f\", \"M205.9 512l31.1-38.4c12.3-.2 25.6-1.4 36.5-6.6 38.9-18.6 38.4-61.9 38.3-63.8-.1-5-.8-4.4-28.9-37.4H362c-.2 50.1-7.3 68.5-10.2 75.7-9.4 23.7-43.9 62.8-95.2 69.4-8.7 1.1-32.8 1.2-50.7 1.1zm200.4-167.7c38.6 0 58.5-13.6 73.7-30.9l-175.5-.3-17.4 31.3 119.2-.1zm-43.6-223.9v168.3h-73.5l-32.7 55.5H250c-52.3 0-58.1-56.5-58.3-58.9-1.2-13.2-21.3-11.6-20.1 1.8 1.4 15.8 8.8 40 26.4 57.1h-91c-25.5 0-110.8-26.8-107-114V16.9C0 .9 9.7.3 15 .1h82c.2 0 .3.1.5.1 4.3-.4 50.1-2.1 50.1 43.7 0 13.3 20.2 13.4 20.2 0 0-18.2-5.5-32.8-15.8-43.7h84.2c108.7-.4 126.5 79.4 126.5 120.2zm-132.5 56l64 29.3c13.3-45.5-42.2-71.7-64-29.3z\"],\n    \"dev\": [448, 512, [], \"f6cc\", \"M120.12 208.29c-3.88-2.9-7.77-4.35-11.65-4.35H91.03v104.47h17.45c3.88 0 7.77-1.45 11.65-4.35 3.88-2.9 5.82-7.25 5.82-13.06v-69.65c-.01-5.8-1.96-10.16-5.83-13.06zM404.1 32H43.9C19.7 32 .06 51.59 0 75.8v360.4C.06 460.41 19.7 480 43.9 480h360.2c24.21 0 43.84-19.59 43.9-43.8V75.8c-.06-24.21-19.7-43.8-43.9-43.8zM154.2 291.19c0 18.81-11.61 47.31-48.36 47.25h-46.4V172.98h47.38c35.44 0 47.36 28.46 47.37 47.28l.01 70.93zm100.68-88.66H201.6v38.42h32.57v29.57H201.6v38.41h53.29v29.57h-62.18c-11.16.29-20.44-8.53-20.72-19.69V193.7c-.27-11.15 8.56-20.41 19.71-20.69h63.19l-.01 29.52zm103.64 115.29c-13.2 30.75-36.85 24.63-47.44 0l-38.53-144.8h32.57l29.71 113.72 29.57-113.72h32.58l-38.46 144.8z\"],\n    \"deviantart\": [320, 512, [], \"f1bd\", \"M320 93.2l-98.2 179.1 7.4 9.5H320v127.7H159.1l-13.5 9.2-43.7 84c-.3 0-8.6 8.6-9.2 9.2H0v-93.2l93.2-179.4-7.4-9.2H0V102.5h156l13.5-9.2 43.7-84c.3 0 8.6-8.6 9.2-9.2H320v93.1z\"],\n    \"dhl\": [640, 512, [], \"f790\", \"M238 301.2h58.7L319 271h-58.7L238 301.2zM0 282.9v6.4h81.8l4.7-6.4H0zM172.9 271c-8.7 0-6-3.6-4.6-5.5 2.8-3.8 7.6-10.4 10.4-14.1 2.8-3.7 2.8-5.9-2.8-5.9h-51l-41.1 55.8h100.1c33.1 0 51.5-22.5 57.2-30.3h-68.2zm317.5-6.9l39.3-53.4h-62.2l-39.3 53.4h62.2zM95.3 271H0v6.4h90.6l4.7-6.4zm111-26.6c-2.8 3.8-7.5 10.4-10.3 14.2-1.4 2-4.1 5.5 4.6 5.5h45.6s7.3-10 13.5-18.4c8.4-11.4.7-35-29.2-35H112.6l-20.4 27.8h111.4c5.6 0 5.5 2.2 2.7 5.9zM0 301.2h73.1l4.7-6.4H0v6.4zm323 0h58.7L404 271h-58.7c-.1 0-22.3 30.2-22.3 30.2zm222 .1h95v-6.4h-90.3l-4.7 6.4zm22.3-30.3l-4.7 6.4H640V271h-72.7zm-13.5 18.3H640v-6.4h-81.5l-4.7 6.4zm-164.2-78.6l-22.5 30.6h-26.2l22.5-30.6h-58.7l-39.3 53.4H409l39.3-53.4h-58.7zm33.5 60.3s-4.3 5.9-6.4 8.7c-7.4 10-.9 21.6 23.2 21.6h94.3l22.3-30.3H423.1z\"],\n    \"diaspora\": [512, 512, [], \"f791\", \"M251.64 354.55c-1.4 0-88 119.9-88.7 119.9S76.34 414 76 413.25s86.6-125.7 86.6-127.4c0-2.2-129.6-44-137.6-47.1-1.3-.5 31.4-101.8 31.7-102.1.6-.7 144.4 47 145.5 47 .4 0 .9-.6 1-1.3.4-2 1-148.6 1.7-149.6.8-1.2 104.5-.7 105.1-.3 1.5 1 3.5 156.1 6.1 156.1 1.4 0 138.7-47 139.3-46.3.8.9 31.9 102.2 31.5 102.6-.9.9-140.2 47.1-140.6 48.8-.3 1.4 82.8 122.1 82.5 122.9s-85.5 63.5-86.3 63.5c-1-.2-89-125.5-90.9-125.5z\"],\n    \"digg\": [512, 512, [], \"f1a6\", \"M81.7 172.3H0v174.4h132.7V96h-51v76.3zm0 133.4H50.9v-92.3h30.8v92.3zm297.2-133.4v174.4h81.8v28.5h-81.8V416H512V172.3H378.9zm81.8 133.4h-30.8v-92.3h30.8v92.3zm-235.6 41h82.1v28.5h-82.1V416h133.3V172.3H225.1v174.4zm51.2-133.3h30.8v92.3h-30.8v-92.3zM153.3 96h51.3v51h-51.3V96zm0 76.3h51.3v174.4h-51.3V172.3z\"],\n    \"digital-ocean\": [512, 512, [], \"f391\", \"M87 481.8h73.7v-73.6H87zM25.4 346.6v61.6H87v-61.6zm466.2-169.7c-23-74.2-82.4-133.3-156.6-156.6C164.9-32.8 8 93.7 8 255.9h95.8c0-101.8 101-180.5 208.1-141.7 39.7 14.3 71.5 46.1 85.8 85.7 39.1 107-39.7 207.8-141.4 208v.3h-.3V504c162.6 0 288.8-156.8 235.6-327.1zm-235.3 231v-95.3h-95.6v95.6H256v-.3z\"],\n    \"discord\": [448, 512, [], \"f392\", \"M297.216 243.2c0 15.616-11.52 28.416-26.112 28.416-14.336 0-26.112-12.8-26.112-28.416s11.52-28.416 26.112-28.416c14.592 0 26.112 12.8 26.112 28.416zm-119.552-28.416c-14.592 0-26.112 12.8-26.112 28.416s11.776 28.416 26.112 28.416c14.592 0 26.112-12.8 26.112-28.416.256-15.616-11.52-28.416-26.112-28.416zM448 52.736V512c-64.494-56.994-43.868-38.128-118.784-107.776l13.568 47.36H52.48C23.552 451.584 0 428.032 0 398.848V52.736C0 23.552 23.552 0 52.48 0h343.04C424.448 0 448 23.552 448 52.736zm-72.96 242.688c0-82.432-36.864-149.248-36.864-149.248-36.864-27.648-71.936-26.88-71.936-26.88l-3.584 4.096c43.52 13.312 63.744 32.512 63.744 32.512-60.811-33.329-132.244-33.335-191.232-7.424-9.472 4.352-15.104 7.424-15.104 7.424s21.248-20.224 67.328-33.536l-2.56-3.072s-35.072-.768-71.936 26.88c0 0-36.864 66.816-36.864 149.248 0 0 21.504 37.12 78.08 38.912 0 0 9.472-11.52 17.152-21.248-32.512-9.728-44.8-30.208-44.8-30.208 3.766 2.636 9.976 6.053 10.496 6.4 43.21 24.198 104.588 32.126 159.744 8.96 8.96-3.328 18.944-8.192 29.44-15.104 0 0-12.8 20.992-46.336 30.464 7.68 9.728 16.896 20.736 16.896 20.736 56.576-1.792 78.336-38.912 78.336-38.912z\"],\n    \"discourse\": [448, 512, [], \"f393\", \"M225.9 32C103.3 32 0 130.5 0 252.1 0 256 .1 480 .1 480l225.8-.2c122.7 0 222.1-102.3 222.1-223.9C448 134.3 348.6 32 225.9 32zM224 384c-19.4 0-37.9-4.3-54.4-12.1L88.5 392l22.9-75c-9.8-18.1-15.4-38.9-15.4-61 0-70.7 57.3-128 128-128s128 57.3 128 128-57.3 128-128 128z\"],\n    \"dochub\": [416, 512, [], \"f394\", \"M397.9 160H256V19.6L397.9 160zM304 192v130c0 66.8-36.5 100.1-113.3 100.1H96V84.8h94.7c12 0 23.1.8 33.1 2.5v-84C212.9 1.1 201.4 0 189.2 0H0v512h189.2C329.7 512 400 447.4 400 318.1V192h-96z\"],\n    \"docker\": [640, 512, [], \"f395\", \"M349.9 236.3h-66.1v-59.4h66.1v59.4zm0-204.3h-66.1v60.7h66.1V32zm78.2 144.8H362v59.4h66.1v-59.4zm-156.3-72.1h-66.1v60.1h66.1v-60.1zm78.1 0h-66.1v60.1h66.1v-60.1zm276.8 100c-14.4-9.7-47.6-13.2-73.1-8.4-3.3-24-16.7-44.9-41.1-63.7l-14-9.3-9.3 14c-18.4 27.8-23.4 73.6-3.7 103.8-8.7 4.7-25.8 11.1-48.4 10.7H2.4c-8.7 50.8 5.8 116.8 44 162.1 37.1 43.9 92.7 66.2 165.4 66.2 157.4 0 273.9-72.5 328.4-204.2 21.4.4 67.6.1 91.3-45.2 1.5-2.5 6.6-13.2 8.5-17.1l-13.3-8.9zm-511.1-27.9h-66v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm-78.1-72.1h-66.1v60.1h66.1v-60.1z\"],\n    \"draft2digital\": [480, 512, [], \"f396\", \"M480 398.1l-144-82.2v64.7h-91.3c30.8-35 81.8-95.9 111.8-149.3 35.2-62.6 16.1-123.4-12.8-153.3-4.4-4.6-62.2-62.9-166-41.2-59.1 12.4-89.4 43.4-104.3 67.3-13.1 20.9-17 39.8-18.2 47.7-5.5 33 19.4 67.1 56.7 67.1 31.7 0 57.3-25.7 57.3-57.4 0-27.1-19.7-52.1-48-56.8 1.8-7.3 17.7-21.1 26.3-24.7 41.1-17.3 78 5.2 83.3 33.5 8.3 44.3-37.1 90.4-69.7 127.6C84.5 328.1 18.3 396.8 0 415.9l336-.1V480zM369.9 371l47.1 27.2-47.1 27.2zM134.2 161.4c0 12.4-10 22.4-22.4 22.4s-22.4-10-22.4-22.4 10-22.4 22.4-22.4 22.4 10.1 22.4 22.4zM82.5 380.5c25.6-27.4 97.7-104.7 150.8-169.9 35.1-43.1 40.3-82.4 28.4-112.7-7.4-18.8-17.5-30.2-24.3-35.7 45.3 2.1 68 23.4 82.2 38.3 0 0 42.4 48.2 5.8 113.3-37 65.9-110.9 147.5-128.5 166.7z\"],\n    \"dribbble\": [512, 512, [], \"f17d\", \"M256 8C119.252 8 8 119.252 8 256s111.252 248 248 248 248-111.252 248-248S392.748 8 256 8zm163.97 114.366c29.503 36.046 47.369 81.957 47.835 131.955-6.984-1.477-77.018-15.682-147.502-6.818-5.752-14.041-11.181-26.393-18.617-41.614 78.321-31.977 113.818-77.482 118.284-83.523zM396.421 97.87c-3.81 5.427-35.697 48.286-111.021 76.519-34.712-63.776-73.185-116.168-79.04-124.008 67.176-16.193 137.966 1.27 190.061 47.489zm-230.48-33.25c5.585 7.659 43.438 60.116 78.537 122.509-99.087 26.313-186.36 25.934-195.834 25.809C62.38 147.205 106.678 92.573 165.941 64.62zM44.17 256.323c0-2.166.043-4.322.108-6.473 9.268.19 111.92 1.513 217.706-30.146 6.064 11.868 11.857 23.915 17.174 35.949-76.599 21.575-146.194 83.527-180.531 142.306C64.794 360.405 44.17 310.73 44.17 256.323zm81.807 167.113c22.127-45.233 82.178-103.622 167.579-132.756 29.74 77.283 42.039 142.053 45.189 160.638-68.112 29.013-150.015 21.053-212.768-27.882zm248.38 8.489c-2.171-12.886-13.446-74.897-41.152-151.033 66.38-10.626 124.7 6.768 131.947 9.055-9.442 58.941-43.273 109.844-90.795 141.978z\"],\n    \"dribbble-square\": [448, 512, [], \"f397\", \"M90.2 228.2c8.9-42.4 37.4-77.7 75.7-95.7 3.6 4.9 28 38.8 50.7 79-64 17-120.3 16.8-126.4 16.7zM314.6 154c-33.6-29.8-79.3-41.1-122.6-30.6 3.8 5.1 28.6 38.9 51 80 48.6-18.3 69.1-45.9 71.6-49.4zM140.1 364c40.5 31.6 93.3 36.7 137.3 18-2-12-10-53.8-29.2-103.6-55.1 18.8-93.8 56.4-108.1 85.6zm98.8-108.2c-3.4-7.8-7.2-15.5-11.1-23.2C159.6 253 93.4 252.2 87.4 252c0 1.4-.1 2.8-.1 4.2 0 35.1 13.3 67.1 35.1 91.4 22.2-37.9 67.1-77.9 116.5-91.8zm34.9 16.3c17.9 49.1 25.1 89.1 26.5 97.4 30.7-20.7 52.5-53.6 58.6-91.6-4.6-1.5-42.3-12.7-85.1-5.8zm-20.3-48.4c4.8 9.8 8.3 17.8 12 26.8 45.5-5.7 90.7 3.4 95.2 4.4-.3-32.3-11.8-61.9-30.9-85.1-2.9 3.9-25.8 33.2-76.3 53.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 176c0-88.2-71.8-160-160-160S64 167.8 64 256s71.8 160 160 160 160-71.8 160-160z\"],\n    \"dropbox\": [528, 512, [], \"f16b\", \"M264.4 116.3l-132 84.3 132 84.3-132 84.3L0 284.1l132.3-84.3L0 116.3 132.3 32l132.1 84.3zM131.6 395.7l132-84.3 132 84.3-132 84.3-132-84.3zm132.8-111.6l132-84.3-132-83.6L395.7 32 528 116.3l-132.3 84.3L528 284.8l-132.3 84.3-131.3-85z\"],\n    \"drupal\": [448, 512, [], \"f1a9\", \"M319.5 114.7c-22.2-14-43.5-19.5-64.7-33.5-13-8.8-31.3-30-46.5-48.3-2.7 29.3-11.5 41.2-22 49.5-21.3 17-34.8 22.2-53.5 32.3C117 123 32 181.5 32 290.5 32 399.7 123.8 480 225.8 480 327.5 480 416 406 416 294c0-112.3-83-171-96.5-179.3zm2.5 325.6c-20.1 20.1-90.1 28.7-116.7 4.2-4.8-4.8.3-12 6.5-12 0 0 17 13.3 51.5 13.3 27 0 46-7.7 54.5-14 6.1-4.6 8.4 4.3 4.2 8.5zm-54.5-52.6c8.7-3.6 29-3.8 36.8 1.3 4.1 2.8 16.1 18.8 6.2 23.7-8.4 4.2-1.2-15.7-26.5-15.7-14.7 0-19.5 5.2-26.7 11-7 6-9.8 8-12.2 4.7-6-8.2 15.9-22.3 22.4-25zM360 405c-15.2-1-45.5-48.8-65-49.5-30.9-.9-104.1 80.7-161.3 42-38.8-26.6-14.6-104.8 51.8-105.2 49.5-.5 83.8 49 108.5 48.5 21.3-.3 61.8-41.8 81.8-41.8 48.7 0 23.3 109.3-15.8 106z\"],\n    \"dyalog\": [416, 512, [], \"f399\", \"M0 32v119.2h64V96h107.2C284.6 96 352 176.2 352 255.9 352 332 293.4 416 171.2 416H0v64h171.2C331.9 480 416 367.3 416 255.9c0-58.7-22.1-113.4-62.3-154.3C308.9 56 245.7 32 171.2 32H0z\"],\n    \"earlybirds\": [480, 512, [], \"f39a\", \"M313.2 47.5c1.2-13 21.3-14 36.6-8.7.9.3 26.2 9.7 19 15.2-27.9-7.4-56.4 18.2-55.6-6.5zm-201 6.9c30.7-8.1 62 20 61.1-7.1-1.3-14.2-23.4-15.3-40.2-9.6-1 .3-28.7 10.5-20.9 16.7zM319.4 160c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-159.7 0c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm318.5 163.2c-9.9 24-40.7 11-63.9-1.2-13.5 69.1-58.1 111.4-126.3 124.2.3.9-2-.1 24 1 33.6 1.4 63.8-3.1 97.4-8-19.8-13.8-11.4-37.1-9.8-38.1 1.4-.9 14.7 1.7 21.6 11.5 8.6-12.5 28.4-14.8 30.2-13.6 1.6 1.1 6.6 20.9-6.9 34.6 4.7-.9 8.2-1.6 9.8-2.1 2.6-.8 17.7 11.3 3.1 13.3-14.3 2.3-22.6 5.1-47.1 10.8-45.9 10.7-85.9 11.8-117.7 12.8l1 11.6c3.8 18.1-23.4 24.3-27.6 6.2.8 17.9-27.1 21.8-28.4-1l-.5 5.3c-.7 18.4-28.4 17.9-28.3-.6-7.5 13.5-28.1 6.8-26.4-8.5l1.2-12.4c-36.7.9-59.7 3.1-61.8 3.1-20.9 0-20.9-31.6 0-31.6 2.4 0 27.7 1.3 63.2 2.8-61.1-15.5-103.7-55-114.9-118.2-25 12.8-57.5 26.8-68.2.8-10.5-25.4 21.5-42.6 66.8-73.4.7-6.6 1.6-13.3 2.7-19.8-14.4-19.6-11.6-36.3-16.1-60.4-16.8 2.4-23.2-9.1-23.6-23.1.3-7.3 2.1-14.9 2.4-15.4 1.1-1.8 10.1-2 12.7-2.6 6-31.7 50.6-33.2 90.9-34.5 19.7-21.8 45.2-41.5 80.9-48.3C203.3 29 215.2 8.5 216.2 8c1.7-.8 21.2 4.3 26.3 23.2 5.2-8.8 18.3-11.4 19.6-10.7 1.1.6 6.4 15-4.9 25.9 40.3 3.5 72.2 24.7 96 50.7 36.1 1.5 71.8 5.9 77.1 34 2.7.6 11.6.8 12.7 2.6.3.5 2.1 8.1 2.4 15.4-.5 13.9-6.8 25.4-23.6 23.1-3.2 17.3-2.7 32.9-8.7 47.7 2.4 11.7 4 23.8 4.8 36.4 37 25.4 70.3 42.5 60.3 66.9zM207.4 159.9c.9-44-37.9-42.2-78.6-40.3-21.7 1-38.9 1.9-45.5 13.9-11.4 20.9 5.9 92.9 23.2 101.2 9.8 4.7 73.4 7.9 86.3-7.1 8.2-9.4 15-49.4 14.6-67.7zm52 58.3c-4.3-12.4-6-30.1-15.3-32.7-2-.5-9-.5-11 0-10 2.8-10.8 22.1-17 37.2 15.4 0 19.3 9.7 23.7 9.7 4.3 0 6.3-11.3 19.6-14.2zm135.7-84.7c-6.6-12.1-24.8-12.9-46.5-13.9-40.2-1.9-78.2-3.8-77.3 40.3-.5 18.3 5 58.3 13.2 67.8 13 14.9 76.6 11.8 86.3 7.1 15.8-7.6 36.5-78.9 24.3-101.3z\"],\n    \"ebay\": [640, 512, [], \"f4f4\", \"M606 189.5l-54.8 109.9-54.9-109.9h-37.5l10.9 20.6c-11.5-19-35.9-26-63.3-26-31.8 0-67.9 8.7-71.5 43.1h33.7c1.4-13.8 15.7-21.8 35-21.8 26 0 41 9.6 41 33v3.4c-12.7 0-28 .1-41.7.4-42.4.9-69.6 10-76.7 34.4 1-5.2 1.5-10.6 1.5-16.2 0-52.1-39.7-76.2-75.4-76.2-21.3 0-43 5.5-58.7 24.2v-80.6h-32.1v169.5c0 10.3-.6 22.9-1.1 33.1h31.5c.7-6.3 1.1-12.9 1.1-19.5 13.6 16.6 35.4 24.9 58.7 24.9 36.9 0 64.9-21.9 73.3-54.2-.5 2.8-.7 5.8-.7 9 0 24.1 21.1 45 60.6 45 26.6 0 45.8-5.7 61.9-25.5 0 6.6.3 13.3 1.1 20.2h29.8c-.7-8.2-1-17.5-1-26.8v-65.6c0-9.3-1.7-17.2-4.8-23.8l61.5 116.1-28.5 54.1h35.9L640 189.5zM243.7 313.8c-29.6 0-50.2-21.5-50.2-53.8 0-32.4 20.6-53.8 50.2-53.8 29.8 0 50.2 21.4 50.2 53.8 0 32.3-20.4 53.8-50.2 53.8zm200.9-47.3c0 30-17.9 48.4-51.6 48.4-25.1 0-35-13.4-35-25.8 0-19.1 18.1-24.4 47.2-25.3 13.1-.5 27.6-.6 39.4-.6zm-411.9 1.6h128.8v-8.5c0-51.7-33.1-75.4-78.4-75.4-56.8 0-83 30.8-83 77.6 0 42.5 25.3 74 82.5 74 31.4 0 68-11.7 74.4-46.1h-33.1c-12 35.8-87.7 36.7-91.2-21.6zm95-21.4H33.3c6.9-56.6 92.1-54.7 94.4 0z\"],\n    \"edge\": [512, 512, [], \"f282\", \"M25.714 228.163c.111-.162.23-.323.342-.485-.021.162-.045.323-.065.485h-.277zm460.572 15.508c0-44.032-7.754-84.465-28.801-122.405C416.498 47.879 343.912 8.001 258.893 8.001 118.962 7.724 40.617 113.214 26.056 227.679c42.429-61.312 117.073-121.376 220.375-124.966 0 0 109.666 0 99.419 104.957H169.997c6.369-37.386 18.554-58.986 34.339-78.926-75.048 34.893-121.85 96.096-120.742 188.315.83 71.448 50.124 144.836 120.743 171.976 83.357 31.847 192.776 7.2 240.132-21.324V363.307c-80.864 56.494-270.871 60.925-272.255-67.572h314.073v-52.064z\"],\n    \"elementor\": [448, 512, [], \"f430\", \"M425.6 32H22.4C10 32 0 42 0 54.4v403.2C0 470 10 480 22.4 480h403.2c12.4 0 22.4-10 22.4-22.4V54.4C448 42 438 32 425.6 32M164.3 355.5h-39.8v-199h39.8v199zm159.3 0H204.1v-39.8h119.5v39.8zm0-79.6H204.1v-39.8h119.5v39.8zm0-79.7H204.1v-39.8h119.5v39.8z\"],\n    \"ello\": [496, 512, [], \"f5f1\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm143.84 285.2C375.31 358.51 315.79 404.8 248 404.8s-127.31-46.29-143.84-111.6c-1.65-7.44 2.48-15.71 9.92-17.36 7.44-1.65 15.71 2.48 17.36 9.92 14.05 52.91 62 90.11 116.56 90.11s102.51-37.2 116.56-90.11c1.65-7.44 9.92-12.4 17.36-9.92 7.44 1.65 12.4 9.92 9.92 17.36z\"],\n    \"ember\": [640, 512, [], \"f423\", \"M639.9 254.6c-1.1-10.7-10.7-6.8-10.7-6.8s-15.6 12.1-29.3 10.7c-13.7-1.3-9.4-32-9.4-32s3-28.1-5.1-30.4c-8.1-2.4-18 7.3-18 7.3s-12.4 13.7-18.3 31.2l-1.6.5s1.9-30.6-.3-37.6c-1.6-3.5-16.4-3.2-18.8 3s-14.2 49.2-15 67.2c0 0-23.1 19.6-43.3 22.8s-25-9.4-25-9.4 54.8-15.3 52.9-59.1-44.2-27.6-49-24c-4.6 3.5-29.4 18.4-36.6 59.7-.2 1.4-.7 7.5-.7 7.5s-21.2 14.2-33 18c0 0 33-55.6-7.3-80.9-11.4-6.8-21.3-.5-27.2 5.3 13.6-17.3 46.4-64.2 36.9-105.2-5.8-24.4-18-27.1-29.2-23.1-17 6.7-23.5 16.7-23.5 16.7s-22 32-27.1 79.5-12.6 105.1-12.6 105.1-10.5 10.2-20.2 10.7-5.4-28.7-5.4-28.7 7.5-44.6 7-52.1-1.1-11.6-9.9-14.2c-8.9-2.7-18.5 8.6-18.5 8.6s-25.5 38.7-27.7 44.6l-1.3 2.4-1.3-1.6s18-52.7.8-53.5-28.5 18.8-28.5 18.8-19.6 32.8-20.4 36.5l-1.3-1.6s8.1-38.2 6.4-47.6c-1.6-9.4-10.5-7.5-10.5-7.5s-11.3-1.3-14.2 5.9-13.7 55.3-15 70.7c0 0-28.2 20.2-46.8 20.4-18.5.3-16.7-11.8-16.7-11.8s68-23.3 49.4-69.2c-8.3-11.8-18-15.5-31.7-15.3-13.7.3-30.3 8.6-41.3 33.3-5.3 11.8-6.8 23-7.8 31.5 0 0-12.3 2.4-18.8-2.9s-10 0-10 0-11.2 14-.1 18.3 28.1 6.1 28.1 6.1c1.6 7.5 6.2 19.5 19.6 29.7 20.2 15.3 58.8-1.3 58.8-1.3l15.9-8.8s.5 14.6 12.1 16.7 16.4 1 36.5-47.9c11.8-25 12.6-23.6 12.6-23.6l1.3-.3s-9.1 46.8-5.6 59.7C187.7 319.4 203 318 203 318s8.3 2.4 15-21.2 19.6-49.9 19.6-49.9h1.6s-5.6 48.1 3 63.7 30.9 5.3 30.9 5.3 15.6-7.8 18-10.2c0 0 18.5 15.8 44.6 12.9 58.3-11.5 79.1-25.9 79.1-25.9s10 24.4 41.1 26.7c35.5 2.7 54.8-18.6 54.8-18.6s-.3 13.5 12.1 18.6 20.7-22.8 20.7-22.8l20.7-57.2h1.9s1.1 37.3 21.5 43.2 47-13.7 47-13.7 6.4-3.5 5.3-14.3zm-578 5.3c.8-32 21.8-45.9 29-39 7.3 7 4.6 22-9.1 31.4-13.7 9.5-19.9 7.6-19.9 7.6zm272.8-123.8s19.1-49.7 23.6-25.5-40 96.2-40 96.2c.5-16.2 16.4-70.7 16.4-70.7zm22.8 138.4c-12.6 33-43.3 19.6-43.3 19.6s-3.5-11.8 6.4-44.9 33.3-20.2 33.3-20.2 16.2 12.4 3.6 45.5zm84.6-14.6s-3-10.5 8.1-30.6c11-20.2 19.6-9.1 19.6-9.1s9.4 10.2-1.3 25.5-26.4 14.2-26.4 14.2z\"],\n    \"empire\": [496, 512, [], \"f1d1\", \"M287.6 54.2c-10.8-2.2-22.1-3.3-33.5-3.6V32.4c78.1 2.2 146.1 44 184.6 106.6l-15.8 9.1c-6.1-9.7-12.7-18.8-20.2-27.1l-18 15.5c-26-29.6-61.4-50.7-101.9-58.4l4.8-23.9zM53.4 322.4l23-7.7c-6.4-18.3-10-38.2-10-58.7s3.3-40.4 9.7-58.7l-22.7-7.7c3.6-10.8 8.3-21.3 13.6-31l-15.8-9.1C34 181 24.1 217.5 24.1 256s10 75 27.1 106.6l15.8-9.1c-5.3-10-9.7-20.3-13.6-31.1zM213.1 434c-40.4-8-75.8-29.1-101.9-58.7l-18 15.8c-7.5-8.6-14.4-17.7-20.2-27.4l-16 9.4c38.5 62.3 106.8 104.3 184.9 106.6v-18.3c-11.3-.3-22.7-1.7-33.5-3.6l4.7-23.8zM93.3 120.9l18 15.5c26-29.6 61.4-50.7 101.9-58.4l-4.7-23.8c10.8-2.2 22.1-3.3 33.5-3.6V32.4C163.9 34.6 95.9 76.4 57.4 139l15.8 9.1c6-9.7 12.6-18.9 20.1-27.2zm309.4 270.2l-18-15.8c-26 29.6-61.4 50.7-101.9 58.7l4.7 23.8c-10.8 1.9-22.1 3.3-33.5 3.6v18.3c78.1-2.2 146.4-44.3 184.9-106.6l-16.1-9.4c-5.7 9.7-12.6 18.8-20.1 27.4zM496 256c0 137-111 248-248 248S0 393 0 256 111 8 248 8s248 111 248 248zm-12.2 0c0-130.1-105.7-235.8-235.8-235.8S12.2 125.9 12.2 256 117.9 491.8 248 491.8 483.8 386.1 483.8 256zm-39-106.6l-15.8 9.1c5.3 9.7 10 20.2 13.6 31l-22.7 7.7c6.4 18.3 9.7 38.2 9.7 58.7s-3.6 40.4-10 58.7l23 7.7c-3.9 10.8-8.3 21-13.6 31l15.8 9.1C462 331 471.9 294.5 471.9 256s-9.9-75-27.1-106.6zm-183 177.7c16.3-3.3 30.4-11.6 40.7-23.5l51.2 44.8c11.9-13.6 21.3-29.3 27.1-46.8l-64.2-22.1c2.5-7.5 3.9-15.2 3.9-23.5s-1.4-16.1-3.9-23.5l64.5-22.1c-6.1-17.4-15.5-33.2-27.4-46.8l-51.2 44.8c-10.2-11.9-24.4-20.5-40.7-23.8l13.3-66.4c-8.6-1.9-17.7-2.8-27.1-2.8-9.4 0-18.5.8-27.1 2.8l13.3 66.4c-16.3 3.3-30.4 11.9-40.7 23.8l-51.2-44.8c-11.9 13.6-21.3 29.3-27.4 46.8l64.5 22.1c-2.5 7.5-3.9 15.2-3.9 23.5s1.4 16.1 3.9 23.5l-64.2 22.1c5.8 17.4 15.2 33.2 27.1 46.8l51.2-44.8c10.2 11.9 24.4 20.2 40.7 23.5l-13.3 66.7c8.6 1.7 17.7 2.8 27.1 2.8 9.4 0 18.5-1.1 27.1-2.8l-13.3-66.7z\"],\n    \"envira\": [448, 512, [], \"f299\", \"M0 32c477.6 0 366.6 317.3 367.1 366.3L448 480h-26l-70.4-71.2c-39 4.2-124.4 34.5-214.4-37C47 300.3 52 214.7 0 32zm79.7 46c-49.7-23.5-5.2 9.2-5.2 9.2 45.2 31.2 66 73.7 90.2 119.9 31.5 60.2 79 139.7 144.2 167.7 65 28 34.2 12.5 6-8.5-28.2-21.2-68.2-87-91-130.2-31.7-60-61-118.6-144.2-158.1z\"],\n    \"erlang\": [640, 512, [], \"f39d\", \"M87.2 53.5H0v405h100.4c-49.7-52.6-78.8-125.3-78.7-212.1-.1-76.7 24-142.7 65.5-192.9zm238.2 9.7c-45.9.1-85.1 33.5-89.2 83.2h169.9c-1.1-49.7-34.5-83.1-80.7-83.2zm230.7-9.6h.3l-.1-.1zm.3 0c31.4 42.7 48.7 97.5 46.2 162.7.5 6 .5 11.7 0 24.1H230.2c-.2 109.7 38.9 194.9 138.6 195.3 68.5-.3 118-51 151.9-106.1l96.4 48.2c-17.4 30.9-36.5 57.8-57.9 80.8H640v-405z\"],\n    \"ethereum\": [320, 512, [], \"f42e\", \"M311.9 260.8L160 353.6 8 260.8 160 0l151.9 260.8zM160 383.4L8 290.6 160 512l152-221.4-152 92.8z\"],\n    \"etsy\": [384, 512, [], \"f2d7\", \"M384 348c-1.75 10.75-13.75 110-15.5 132-117.879-4.299-219.895-4.743-368.5 0v-25.5c45.457-8.948 60.627-8.019 61-35.25 1.793-72.322 3.524-244.143 0-322-1.029-28.46-12.13-26.765-61-36v-25.5c73.886 2.358 255.933 8.551 362.999-3.75-3.5 38.25-7.75 126.5-7.75 126.5H332C320.947 115.665 313.241 68 277.25 68h-137c-10.25 0-10.75 3.5-10.75 9.75V241.5c58 .5 88.5-2.5 88.5-2.5 29.77-.951 27.56-8.502 40.75-65.251h25.75c-4.407 101.351-3.91 61.829-1.75 160.25H257c-9.155-40.086-9.065-61.045-39.501-61.5 0 0-21.5-2-88-2v139c0 26 14.25 38.25 44.25 38.25H263c63.636 0 66.564-24.996 98.751-99.75H384z\"],\n    \"evernote\": [384, 512, [], \"f839\", \"M120.82 132.21c1.6 22.31-17.55 21.59-21.61 21.59-68.93 0-73.64-1-83.58 3.34-.56.22-.74 0-.37-.37L123.79 46.45c.38-.37.6-.22.38.37-4.35 9.99-3.35 15.09-3.35 85.39zm79 308c-14.68-37.08 13-76.93 52.52-76.62 17.49 0 22.6 23.21 7.95 31.42-6.19 3.3-24.95 1.74-25.14 19.2-.05 17.09 19.67 25 31.2 24.89A45.64 45.64 0 0 0 312 393.45v-.08c0-11.63-7.79-47.22-47.54-55.34-7.72-1.54-65-6.35-68.35-50.52-3.74 16.93-17.4 63.49-43.11 69.09-8.74 1.94-69.68 7.64-112.92-36.77 0 0-18.57-15.23-28.23-57.95-3.38-15.75-9.28-39.7-11.14-62 0-18 11.14-30.45 25.07-32.2 81 0 90 2.32 101-7.8 9.82-9.24 7.8-15.5 7.8-102.78 1-8.3 7.79-30.81 53.41-24.14 6 .86 31.91 4.18 37.48 30.64l64.26 11.15c20.43 3.71 70.94 7 80.6 57.94 22.66 121.09 8.91 238.46 7.8 238.46C362.15 485.53 267.06 480 267.06 480c-18.95-.23-54.25-9.4-67.27-39.83zm80.94-204.84c-1 1.92-2.2 6 .85 7 14.09 4.93 39.75 6.84 45.88 5.53 3.11-.25 3.05-4.43 2.48-6.65-3.53-21.85-40.83-26.5-49.24-5.92z\"],\n    \"expeditedssl\": [496, 512, [], \"f23e\", \"M248 43.4C130.6 43.4 35.4 138.6 35.4 256S130.6 468.6 248 468.6 460.6 373.4 460.6 256 365.4 43.4 248 43.4zm-97.4 132.9c0-53.7 43.7-97.4 97.4-97.4s97.4 43.7 97.4 97.4v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6c0-82.1-124-82.1-124 0v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6zM389.7 380c0 9.7-8 17.7-17.7 17.7H124c-9.7 0-17.7-8-17.7-17.7V238.3c0-9.7 8-17.7 17.7-17.7h248c9.7 0 17.7 8 17.7 17.7V380zm-248-137.3v132.9c0 2.5-1.9 4.4-4.4 4.4h-8.9c-2.5 0-4.4-1.9-4.4-4.4V242.7c0-2.5 1.9-4.4 4.4-4.4h8.9c2.5 0 4.4 1.9 4.4 4.4zm141.7 48.7c0 13-7.2 24.4-17.7 30.4v31.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-31.6c-10.5-6.1-17.7-17.4-17.7-30.4 0-19.7 15.8-35.4 35.4-35.4s35.5 15.8 35.5 35.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 478.3C121 486.3 17.7 383 17.7 256S121 25.7 248 25.7 478.3 129 478.3 256 375 486.3 248 486.3z\"],\n    \"facebook\": [512, 512, [], \"f09a\", \"M504 256C504 119 393 8 256 8S8 119 8 256c0 123.78 90.69 226.38 209.25 245V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.28c-30.8 0-40.41 19.12-40.41 38.73V256h68.78l-11 71.69h-57.78V501C413.31 482.38 504 379.78 504 256z\"],\n    \"facebook-f\": [320, 512, [], \"f39e\", \"M279.14 288l14.22-92.66h-88.91v-60.13c0-25.35 12.42-50.06 52.24-50.06h40.42V6.26S260.43 0 225.36 0c-73.22 0-121.08 44.38-121.08 124.72v70.62H22.89V288h81.39v224h100.17V288z\"],\n    \"facebook-messenger\": [512, 512, [], \"f39f\", \"M256.55 8C116.52 8 8 110.34 8 248.57c0 72.3 29.71 134.78 78.07 177.94 8.35 7.51 6.63 11.86 8.05 58.23A19.92 19.92 0 0 0 122 502.31c52.91-23.3 53.59-25.14 62.56-22.7C337.85 521.8 504 423.7 504 248.57 504 110.34 396.59 8 256.55 8zm149.24 185.13l-73 115.57a37.37 37.37 0 0 1-53.91 9.93l-58.08-43.47a15 15 0 0 0-18 0l-78.37 59.44c-10.46 7.93-24.16-4.6-17.11-15.67l73-115.57a37.36 37.36 0 0 1 53.91-9.93l58.06 43.46a15 15 0 0 0 18 0l78.41-59.38c10.44-7.98 24.14 4.54 17.09 15.62z\"],\n    \"facebook-square\": [448, 512, [], \"f082\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h137.25V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.27c-30.81 0-40.42 19.12-40.42 38.73V256h68.78l-11 71.69h-57.78V480H400a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48z\"],\n    \"fantasy-flight-games\": [512, 512, [], \"f6dc\", \"M256 32.86L32.86 256 256 479.14 479.14 256 256 32.86zM88.34 255.83c1.96-2 11.92-12.3 96.49-97.48 41.45-41.75 86.19-43.77 119.77-18.69 24.63 18.4 62.06 58.9 62.15 59 .68.74 1.07 2.86.58 3.38-11.27 11.84-22.68 23.54-33.5 34.69-34.21-32.31-40.52-38.24-48.51-43.95-17.77-12.69-41.4-10.13-56.98 5.1-2.17 2.13-1.79 3.43.12 5.35 2.94 2.95 28.1 28.33 35.09 35.78-11.95 11.6-23.66 22.97-35.69 34.66-12.02-12.54-24.48-25.53-36.54-38.11-21.39 21.09-41.69 41.11-61.85 60.99a42569.01 42569.01 0 0 1-41.13-40.72zm234.82 101.6c-35.49 35.43-78.09 38.14-106.99 20.47-22.08-13.5-39.38-32.08-72.93-66.84 12.05-12.37 23.79-24.42 35.37-36.31 33.02 31.91 37.06 36.01 44.68 42.09 18.48 14.74 42.52 13.67 59.32-1.8 3.68-3.39 3.69-3.64.14-7.24-10.59-10.73-21.19-21.44-31.77-32.18-1.32-1.34-3.03-2.48-.8-4.69 10.79-10.71 21.48-21.52 32.21-32.29.26-.26.65-.38 1.91-1.07 12.37 12.87 24.92 25.92 37.25 38.75 21.01-20.73 41.24-40.68 61.25-60.42 13.68 13.4 27.13 26.58 40.86 40.03-20.17 20.86-81.68 82.71-100.5 101.5zM256 0L0 256l256 256 256-256L256 0zM16 256L256 16l240 240-240 240L16 256z\"],\n    \"fedex\": [640, 512, [], \"f797\", \"M586 284.5l53.3-59.9h-62.4l-21.7 24.8-22.5-24.8H414v-16h56.1v-48.1H318.9V236h-.5c-9.6-11-21.5-14.8-35.4-14.8-28.4 0-49.8 19.4-57.3 44.9-18-59.4-97.4-57.6-121.9-14v-24.2H49v-26.2h60v-41.1H0V345h49v-77.5h48.9c-1.5 5.7-2.3 11.8-2.3 18.2 0 73.1 102.6 91.4 130.2 23.7h-42c-14.7 20.9-45.8 8.9-45.8-14.6h85.5c3.7 30.5 27.4 56.9 60.1 56.9 14.1 0 27-6.9 34.9-18.6h.5V345h212.2l22.1-25 22.3 25H640l-54-60.5zm-446.7-16.6c6.1-26.3 41.7-25.6 46.5 0h-46.5zm153.4 48.9c-34.6 0-34-62.8 0-62.8 32.6 0 34.5 62.8 0 62.8zm167.8 19.1h-94.4V169.4h95v30.2H405v33.9h55.5v28.1h-56.1v44.7h56.1v29.6zm-45.9-39.8v-24.4h56.1v-44l50.7 57-50.7 57v-45.6h-56.1zm138.6 10.3l-26.1 29.5H489l45.6-51.2-45.6-51.2h39.7l26.6 29.3 25.6-29.3h38.5l-45.4 51 46 51.4h-40.5l-26.3-29.5z\"],\n    \"fedora\": [448, 512, [], \"f798\", \"M225 32C101.3 31.7.8 131.7.4 255.4L0 425.7a53.6 53.6 0 0 0 53.6 53.9l170.2.4c123.7.3 224.3-99.7 224.6-223.4S348.7 32.3 225 32zm169.8 157.2L333 126.6c2.3-4.7 3.8-9.2 3.8-14.3v-1.6l55.2 56.1a101 101 0 0 1 2.8 22.4zM331 94.3a106.06 106.06 0 0 1 58.5 63.8l-54.3-54.6a26.48 26.48 0 0 0-4.2-9.2zM118.1 247.2a49.66 49.66 0 0 0-7.7 11.4l-8.5-8.5a85.78 85.78 0 0 1 16.2-2.9zM97 251.4l11.8 11.9-.9 8a34.74 34.74 0 0 0 2.4 12.5l-27-27.2a80.6 80.6 0 0 1 13.7-5.2zm-18.2 7.4l38.2 38.4a53.17 53.17 0 0 0-14.1 4.7L67.6 266a107 107 0 0 1 11.2-7.2zm-15.2 9.8l35.3 35.5a67.25 67.25 0 0 0-10.5 8.5L53.5 278a64.33 64.33 0 0 1 10.1-9.4zm-13.3 12.3l34.9 35a56.84 56.84 0 0 0-7.7 11.4l-35.8-35.9c2.8-3.8 5.7-7.2 8.6-10.5zm-11 14.3l36.4 36.6a48.29 48.29 0 0 0-3.6 15.2l-39.5-39.8a99.81 99.81 0 0 1 6.7-12zm-8.8 16.3l41.3 41.8a63.47 63.47 0 0 0 6.7 26.2L25.8 326c1.4-4.9 2.9-9.6 4.7-14.5zm-7.9 43l61.9 62.2a31.24 31.24 0 0 0-3.6 14.3v1.1l-55.4-55.7a88.27 88.27 0 0 1-2.9-21.9zm5.3 30.7l54.3 54.6a28.44 28.44 0 0 0 4.2 9.2 106.32 106.32 0 0 1-58.5-63.8zm-5.3-37a80.69 80.69 0 0 1 2.1-17l72.2 72.5a37.59 37.59 0 0 0-9.9 8.7zm253.3-51.8l-42.6-.1-.1 56c-.2 69.3-64.4 115.8-125.7 102.9-5.7 0-19.9-8.7-19.9-24.2a24.89 24.89 0 0 1 24.5-24.6c6.3 0 6.3 1.6 15.7 1.6a55.91 55.91 0 0 0 56.1-55.9l.1-47c0-4.5-4.5-9-8.9-9l-33.6-.1c-32.6-.1-32.5-49.4.1-49.3l42.6.1.1-56a105.18 105.18 0 0 1 105.6-105 86.35 86.35 0 0 1 20.2 2.3c11.2 1.8 19.9 11.9 19.9 24 0 15.5-14.9 27.8-30.3 23.9-27.4-5.9-65.9 14.4-66 54.9l-.1 47a8.94 8.94 0 0 0 8.9 9l33.6.1c32.5.2 32.4 49.5-.2 49.4zm23.5-.3a35.58 35.58 0 0 0 7.6-11.4l8.5 8.5a102 102 0 0 1-16.1 2.9zm21-4.2L308.6 280l.9-8.1a34.74 34.74 0 0 0-2.4-12.5l27 27.2a74.89 74.89 0 0 1-13.7 5.3zm18-7.4l-38-38.4c4.9-1.1 9.6-2.4 13.7-4.7l36.2 35.9c-3.8 2.5-7.9 5-11.9 7.2zm15.5-9.8l-35.3-35.5a61.06 61.06 0 0 0 10.5-8.5l34.9 35a124.56 124.56 0 0 1-10.1 9zm13.2-12.3l-34.9-35a63.18 63.18 0 0 0 7.7-11.4l35.8 35.9a130.28 130.28 0 0 1-8.6 10.5zm11-14.3l-36.4-36.6a48.29 48.29 0 0 0 3.6-15.2l39.5 39.8a87.72 87.72 0 0 1-6.7 12zm13.5-30.9a140.63 140.63 0 0 1-4.7 14.3L345.6 190a58.19 58.19 0 0 0-7.1-26.2zm1-5.6l-71.9-72.1a32 32 0 0 0 9.9-9.2l64.3 64.7a90.93 90.93 0 0 1-2.3 16.6z\"],\n    \"figma\": [384, 512, [], \"f799\", \"M277 170.7A85.35 85.35 0 0 0 277 0H106.3a85.3 85.3 0 0 0 0 170.6 85.35 85.35 0 0 0 0 170.7 85.35 85.35 0 1 0 85.3 85.4v-256zm0 0a85.3 85.3 0 1 0 85.3 85.3 85.31 85.31 0 0 0-85.3-85.3z\"],\n    \"firefox\": [480, 512, [], \"f269\", \"M478.1 235.3c-.7-4.5-1.4-7.1-1.4-7.1s-1.8 2-4.7 5.9c-.9-10.7-2.8-21.2-5.8-31.6-3.7-12.9-8.5-25.4-14.5-37.4-3.8-8-8.2-15.6-13.3-22.8-1.8-2.7-3.7-5.4-5.6-7.9-8.8-14.4-19-23.3-30.7-40-7.6-12.8-12.9-26.9-15.4-41.6-3.2 8.9-5.7 18-7.4 27.3-12.1-12.2-22.5-20.8-28.9-26.7C319.4 24.2 323 9.1 323 9.1S264.7 74.2 289.9 142c8.7 23 23.8 43.1 43.4 57.9 24.4 20.2 50.8 36 64.7 76.6-11.2-21.3-28.1-39.2-48.8-51.5 6.2 14.7 9.4 30.6 9.3 46.5 0 61-49.6 110.5-110.6 110.4-8.3 0-16.5-.9-24.5-2.8-9.5-1.8-18.7-4.9-27.4-9.3-12.9-7.8-24-18.1-32.8-30.3l-.2-.3 2 .7c4.6 1.6 9.2 2.8 14 3.7 18.7 4 38.3 1.7 55.6-6.6 17.5-9.7 28-16.9 36.6-14h.2c8.4 2.7 15-5.5 9-14-10.4-13.4-27.4-20-44.2-17-17.5 2.5-33.5 15-56.4 2.9-1.5-.8-2.9-1.6-4.3-2.5-1.6-.9 4.9 1.3 3.4.3-5-2.5-9.8-5.4-14.4-8.6-.3-.3 3.5 1.1 3.1.8-5.9-4-11-9.2-15-15.2-4.1-7.4-4.5-16.4-1-24.1 2.1-3.8 5.4-6.9 9.3-8.7 3 1.5 4.8 2.6 4.8 2.6s-1.3-2.5-2.1-3.8c.3-.1.5 0 .8-.2 2.6 1.1 8.3 4 11.4 5.8 2.1 1.1 3.8 2.7 5.2 4.7 0 0 1-.5.3-2.7-1.1-2.7-2.9-5-5.4-6.6h.2c2.3 1.2 4.5 2.6 6.6 4.1 1.9-4.4 2.8-9.2 2.6-14 .2-2.6-.2-5.3-1.1-7.8-.8-1.6.5-2.2 1.9-.5-.2-1.3-.7-2.5-1.2-3.7v-.1s.8-1.1 1.2-1.5c1-1 2.1-1.9 3.4-2.7 7.2-4.5 14.8-8.4 22.7-11.6 6.4-2.8 11.7-4.9 12.8-5.6 1.6-1 3.1-2.2 4.5-3.5 5.3-4.5 9-10.8 10.2-17.7.1-.9.2-1.8.3-2.8v-1.5c-.9-3.5-6.9-6.1-38.4-9.1-11.1-1.8-20-10.1-22.5-21.1v-.1c6-15.7 16.8-29.1 30.8-38.3.8-.7-3.2.2-2.4-.5 2.7-1.3 5.4-2.5 8.2-3.5 1.4-.6-6-3.4-12.6-2.7-4 .2-8 1.2-11.7 2.8 1.6-1.3 6.2-3.1 5.1-3.1-8.4 1.6-16.5 4.7-23.9 9 0-.8.1-1.5.5-2.2-5.9 2.5-11 6.5-15 11.5.1-.9.2-1.8.2-2.7-2.7 2-5.2 4.3-7.3 6.9l-.1.1c-17.4-6.7-36.3-8.3-54.6-4.7l-.2-.1h.2c-3.8-3.1-7.1-6.7-9.7-10.9l-.2.1-.4-.2c-1.2-1.8-2.4-3.8-3.7-6-.9-1.6-1.8-3.4-2.7-5.2 0-.1-.1-.2-.2-.2-.4 0-.6 1.7-.9 1.3v-.1c-3.2-8.3-4.7-17.2-4.4-26.2l-.2.1c-5.1 3.5-9 8.6-11.1 14.5-.9 2.1-1.6 3.3-2.2 4.5v-.5c.1-1.1.6-3.3.5-3.1s-.2.3-.3.4c-1.5 1.7-2.9 3.7-3.9 5.8-.9 1.9-1.7 3.9-2.3 5.9-.1.3 0-.3 0-1s.1-2 0-1.7l-.3.7c-6.7 14.9-10.9 30.8-12.4 47.1-.4 2.8-.6 5.6-.5 8.3v.2c-4.8 5.2-9 11-12.7 17.1-12.1 20.4-21.1 42.5-26.8 65.6 4-8.8 8.8-17.2 14.3-25.1C5.5 228.5 0 257.4 0 286.6c1.8-8.6 4.2-17 7-25.3-1.7 34.5 4.9 68.9 19.4 100.3 19.4 43.5 51.6 80 92.3 104.7 16.6 11.2 34.7 19.9 53.8 25.8 2.5.9 5.1 1.8 7.7 2.7-.8-.3-1.6-.7-2.4-1 22.6 6.8 46.2 10.3 69.8 10.3 83.7 0 111.3-31.9 113.8-35 4.1-3.7 7.5-8.2 9.9-13.3 1.6-.7 3.2-1.4 4.9-2.1l1-.5 1.9-.9c12.6-5.9 24.5-13.4 35.3-22.1 16.3-11.7 27.9-28.7 32.9-48.1 3-7.1 3.1-15 .4-22.2.9-1.4 1.7-2.8 2.7-4.3 18-28.9 28.2-61.9 29.6-95.9v-2.8c0-7.3-.6-14.5-1.9-21.6zm-299-97.6c-.4 1.1-.9 2.3-1.3 3.5.4-1.2.8-2.3 1.3-3.5z\"],\n    \"first-order\": [448, 512, [], \"f2b0\", \"M12.9 229.2c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4h-.2zM224 96.6c-7.1 0-14.6.6-21.4 1.7l3.7 67.4-22-64c-14.3 3.7-27.7 9.4-40 16.6l29.4 61.4-45.1-50.9c-11.4 8.9-21.7 19.1-30.6 30.9l50.6 45.4-61.1-29.7c-7.1 12.3-12.9 25.7-16.6 40l64.3 22.6-68-4c-.9 7.1-1.4 14.6-1.4 22s.6 14.6 1.4 21.7l67.7-4-64 22.6c3.7 14.3 9.4 27.7 16.6 40.3l61.1-29.7L97.7 352c8.9 11.7 19.1 22.3 30.9 30.9l44.9-50.9-29.5 61.4c12.3 7.4 25.7 13.1 40 16.9l22.3-64.6-4 68c7.1 1.1 14.6 1.7 21.7 1.7 7.4 0 14.6-.6 21.7-1.7l-4-68.6 22.6 65.1c14.3-4 27.7-9.4 40-16.9L274.9 332l44.9 50.9c11.7-8.9 22-19.1 30.6-30.9l-50.6-45.1 61.1 29.4c7.1-12.3 12.9-25.7 16.6-40.3l-64-22.3 67.4 4c1.1-7.1 1.4-14.3 1.4-21.7s-.3-14.9-1.4-22l-67.7 4 64-22.3c-3.7-14.3-9.1-28-16.6-40.3l-60.9 29.7 50.6-45.4c-8.9-11.7-19.1-22-30.6-30.9l-45.1 50.9 29.4-61.1c-12.3-7.4-25.7-13.1-40-16.9L241.7 166l4-67.7c-7.1-1.2-14.3-1.7-21.7-1.7zM443.4 128v256L224 512 4.6 384V128L224 0l219.4 128zm-17.1 10.3L224 20.9 21.7 138.3v235.1L224 491.1l202.3-117.7V138.3zM224 37.1l187.7 109.4v218.9L224 474.9 36.3 365.4V146.6L224 37.1zm0 50.9c-92.3 0-166.9 75.1-166.9 168 0 92.6 74.6 167.7 166.9 167.7 92 0 166.9-75.1 166.9-167.7 0-92.9-74.9-168-166.9-168z\"],\n    \"first-order-alt\": [496, 512, [], \"f50a\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 488.21C115.34 496.21 7.79 388.66 7.79 256S115.34 15.79 248 15.79 488.21 123.34 488.21 256 380.66 496.21 248 496.21zm0-459.92C126.66 36.29 28.29 134.66 28.29 256S126.66 475.71 248 475.71 467.71 377.34 467.71 256 369.34 36.29 248 36.29zm0 431.22c-116.81 0-211.51-94.69-211.51-211.51S131.19 44.49 248 44.49 459.51 139.19 459.51 256 364.81 467.51 248 467.51zm186.23-162.98a191.613 191.613 0 0 1-20.13 48.69l-74.13-35.88 61.48 54.82a193.515 193.515 0 0 1-37.2 37.29l-54.8-61.57 35.88 74.27a190.944 190.944 0 0 1-48.63 20.23l-27.29-78.47 4.79 82.93c-8.61 1.18-17.4 1.8-26.33 1.8s-17.72-.62-26.33-1.8l4.76-82.46-27.15 78.03a191.365 191.365 0 0 1-48.65-20.2l35.93-74.34-54.87 61.64a193.85 193.85 0 0 1-37.22-37.28l61.59-54.9-74.26 35.93a191.638 191.638 0 0 1-20.14-48.69l77.84-27.11-82.23 4.76c-1.16-8.57-1.78-17.32-1.78-26.21 0-9 .63-17.84 1.82-26.51l82.38 4.77-77.94-27.16a191.726 191.726 0 0 1 20.23-48.67l74.22 35.92-61.52-54.86a193.85 193.85 0 0 1 37.28-37.22l54.76 61.53-35.83-74.17a191.49 191.49 0 0 1 48.65-20.13l26.87 77.25-4.71-81.61c8.61-1.18 17.39-1.8 26.32-1.8s17.71.62 26.32 1.8l-4.74 82.16 27.05-77.76c17.27 4.5 33.6 11.35 48.63 20.17l-35.82 74.12 54.72-61.47a193.13 193.13 0 0 1 37.24 37.23l-61.45 54.77 74.12-35.86a191.515 191.515 0 0 1 20.2 48.65l-77.81 27.1 82.24-4.75c1.19 8.66 1.82 17.5 1.82 26.49 0 8.88-.61 17.63-1.78 26.19l-82.12-4.75 77.72 27.09z\"],\n    \"firstdraft\": [384, 512, [], \"f3a1\", \"M384 192h-64v128H192v128H0v-25.6h166.4v-128h128v-128H384V192zm-25.6 38.4v128h-128v128H64V512h192V384h128V230.4h-25.6zm25.6 192h-89.6V512H320v-64h64v-25.6zM0 0v384h128V256h128V128h128V0H0z\"],\n    \"flickr\": [448, 512, [], \"f16e\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM144.5 319c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5zm159 0c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5z\"],\n    \"flipboard\": [448, 512, [], \"f44d\", \"M0 32v448h448V32H0zm358.4 179.2h-89.6v89.6h-89.6v89.6H89.6V121.6h268.8v89.6z\"],\n    \"fly\": [384, 512, [], \"f417\", \"M197.8 427.8c12.9 11.7 33.7 33.3 33.2 50.7 0 .8-.1 1.6-.1 2.5-1.8 19.8-18.8 31.1-39.1 31-25-.1-39.9-16.8-38.7-35.8 1-16.2 20.5-36.7 32.4-47.6 2.3-2.1 2.7-2.7 5.6-3.6 3.4 0 3.9.3 6.7 2.8zM331.9 67.3c-16.3-25.7-38.6-40.6-63.3-52.1C243.1 4.5 214-.2 192 0c-44.1 0-71.2 13.2-81.1 17.3C57.3 45.2 26.5 87.2 28 158.6c7.1 82.2 97 176 155.8 233.8 1.7 1.6 4.5 4.5 6.2 5.1l3.3.1c2.1-.7 1.8-.5 3.5-2.1 52.3-49.2 140.7-145.8 155.9-215.7 7-39.2 3.1-72.5-20.8-112.5zM186.8 351.9c-28-51.1-65.2-130.7-69.3-189-3.4-47.5 11.4-131.2 69.3-136.7v325.7zM328.7 180c-16.4 56.8-77.3 128-118.9 170.3C237.6 298.4 275 217 277 158.4c1.6-45.9-9.8-105.8-48-131.4 88.8 18.3 115.5 98.1 99.7 153z\"],\n    \"font-awesome\": [448, 512, [], \"f2b4\", \"M397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm-45.4 284.3c0 4.2-3.6 6-7.8 7.8-16.7 7.2-34.6 13.7-53.8 13.7-26.9 0-39.4-16.7-71.7-16.7-23.3 0-47.8 8.4-67.5 17.3-1.2.6-2.4.6-3.6 1.2V385c0 1.8 0 3.6-.6 4.8v1.2c-2.4 8.4-10.2 14.3-19.1 14.3-11.3 0-20.3-9-20.3-20.3V166.4c-7.8-6-13.1-15.5-13.1-26.3 0-18.5 14.9-33.5 33.5-33.5 18.5 0 33.5 14.9 33.5 33.5 0 10.8-4.8 20.3-13.1 26.3v18.5c1.8-.6 3.6-1.2 5.4-2.4 18.5-7.8 40.6-14.3 61.5-14.3 22.7 0 40.6 6 60.9 13.7 4.2 1.8 8.4 2.4 13.1 2.4 22.7 0 47.8-16.1 53.8-16.1 4.8 0 9 3.6 9 7.8v140.3z\"],\n    \"font-awesome-alt\": [448, 512, [], \"f35c\", \"M339.3 171.2c-6 0-29.9 15.5-52.6 15.5-4.2 0-8.4-.6-12.5-2.4-19.7-7.8-37-13.7-59.1-13.7-20.3 0-41.8 6.6-59.7 13.7-1.8.6-3.6 1.2-4.8 1.8v-17.9c7.8-6 12.5-14.9 12.5-25.7 0-17.9-14.3-32.3-32.3-32.3s-32.3 14.3-32.3 32.3c0 10.2 4.8 19.7 12.5 25.7v212.1c0 10.8 9 19.7 19.7 19.7 9 0 16.1-6 18.5-13.7V385c.6-1.8.6-3 .6-4.8V336c1.2 0 2.4-.6 3-1.2 19.7-8.4 43-16.7 65.7-16.7 31.1 0 43 16.1 69.3 16.1 18.5 0 36.4-6.6 52-13.7 4.2-1.8 7.2-3.6 7.2-7.8V178.3c1.8-4.1-2.3-7.1-7.7-7.1zM397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm14.3 397.7c0 7.8-6.6 14.3-14.3 14.3H50.2c-7.8 0-14.3-6.6-14.3-14.3V82.2c0-7.8 6.6-14.3 14.3-14.3h347.6v-.1c7.8 0 14.3 6.6 14.3 14.3z\"],\n    \"font-awesome-flag\": [448, 512, [], \"f425\", \"M444.373 359.424c0 7.168-6.144 10.24-13.312 13.312-28.672 12.288-59.392 23.552-92.16 23.552-46.08 0-67.584-28.672-122.88-28.672-39.936 0-81.92 14.336-115.712 29.696-2.048 1.024-4.096 1.024-6.144 2.048v77.824c0 21.405-16.122 34.816-33.792 34.816-19.456 0-34.816-15.36-34.816-34.816V102.4C12.245 92.16 3.029 75.776 3.029 57.344 3.029 25.6 28.629 0 60.373 0s57.344 25.6 57.344 57.344c0 18.432-8.192 34.816-22.528 45.056v31.744c4.124-1.374 58.768-28.672 114.688-28.672 65.27 0 97.676 27.648 126.976 27.648 38.912 0 81.92-27.648 92.16-27.648 8.192 0 15.36 6.144 15.36 13.312v240.64z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"fonticons\": [448, 512, [], \"f280\", \"M0 32v448h448V32zm187 140.9c-18.4 0-19 9.9-19 27.4v23.3c0 2.4-3.5 4.4-.6 4.4h67.4l-11.1 37.3H168v112.9c0 5.8-2 6.7 3.2 7.3l43.5 4.1v25.1H84V389l21.3-2c5.2-.6 6.7-2.3 6.7-7.9V267.7c0-2.3-2.9-2.3-5.8-2.3H84V228h28v-21c0-49.6 26.5-70 77.3-70 34.1 0 64.7 8.2 64.7 52.8l-50.7 6.1c.3-18.7-4.4-23-16.3-23zm74.3 241.8v-25.1l20.4-2.6c5.2-.6 7.6-1.7 7.6-7.3V271.8c0-4.1-2.9-6.7-6.7-7.9l-24.2-6.4 6.7-29.5h80.2v151.7c0 5.8-2.6 6.4 2.9 7.3l15.7 2.6v25.1zm80.8-255.5l9 33.2-7.3 7.3-31.2-16.6-31.2 16.6-7.3-7.3 9-33.2-21.8-24.2 3.5-9.6h27.7l15.5-28h9.3l15.5 28h27.7l3.5 9.6z\"],\n    \"fonticons-fi\": [384, 512, [], \"f3a2\", \"M114.4 224h92.4l-15.2 51.2h-76.4V433c0 8-2.8 9.2 4.4 10l59.6 5.6V483H0v-35.2l29.2-2.8c7.2-.8 9.2-3.2 9.2-10.8V278.4c0-3.2-4-3.2-8-3.2H0V224h38.4v-28.8c0-68 36.4-96 106-96 46.8 0 88.8 11.2 88.8 72.4l-69.6 8.4c.4-25.6-6-31.6-22.4-31.6-25.2 0-26 13.6-26 37.6v32c0 3.2-4.8 6-.8 6zM384 483H243.2v-34.4l28-3.6c7.2-.8 10.4-2.4 10.4-10V287c0-5.6-4-9.2-9.2-10.8l-33.2-8.8 9.2-40.4h110v208c0 8-3.6 8.8 4 10l21.6 3.6V483zm-30-347.2l12.4 45.6-10 10-42.8-22.8-42.8 22.8-10-10 12.4-45.6-30-36.4 4.8-10h38L307.2 51H320l21.2 38.4h38l4.8 13.2-30 33.2z\"],\n    \"fort-awesome\": [512, 512, [], \"f286\", \"M489.2 287.9h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6V146.2c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-6-8-4.6-11.7-4.6v-38c8.3-2 17.1-3.4 25.7-3.4 10.9 0 20.9 4.3 31.4 4.3 4.6 0 27.7-1.1 27.7-8v-60c0-2.6-2-4.6-4.6-4.6-5.1 0-15.1 4.3-24 4.3-9.7 0-20.9-4.3-32.6-4.3-8 0-16 1.1-23.7 2.9v-4.9c5.4-2.6 9.1-8.3 9.1-14.3 0-20.7-31.4-20.8-31.4 0 0 6 3.7 11.7 9.1 14.3v111.7c-3.7 0-11.7-1.4-11.7 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32H128v-32c0-2.6-2-4.6-4.6-4.6H96c-2.6 0-4.6 2-4.6 4.6v178.3H54.8v-32c0-2.6-2-4.6-4.6-4.6H22.8c-2.6 0-4.6 2-4.6 4.6V512h182.9v-96c0-72.6 109.7-72.6 109.7 0v96h182.9V292.5c.1-2.6-1.9-4.6-4.5-4.6zm-288.1-4.5c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64zm146.4 0c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64z\"],\n    \"fort-awesome-alt\": [512, 512, [], \"f3a3\", \"M208 237.4h-22.2c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7H208c2.1 0 3.7-1.6 3.7-3.7v-51.7c0-2.1-1.6-3.7-3.7-3.7zm118.2 0H304c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7h22.2c2.1 0 3.7-1.6 3.7-3.7v-51.7c-.1-2.1-1.7-3.7-3.7-3.7zm132-125.1c-2.3-3.2-4.6-6.4-7.1-9.5-9.8-12.5-20.8-24-32.8-34.4-4.5-3.9-9.1-7.6-13.9-11.2-1.6-1.2-3.2-2.3-4.8-3.5C372 34.1 340.3 20 306 13c-16.2-3.3-32.9-5-50-5s-33.9 1.7-50 5c-34.3 7.1-66 21.2-93.3 40.8-1.6 1.1-3.2 2.3-4.8 3.5-4.8 3.6-9.4 7.3-13.9 11.2-3 2.6-5.9 5.3-8.8 8s-5.7 5.5-8.4 8.4c-5.5 5.7-10.7 11.8-15.6 18-2.4 3.1-4.8 6.3-7.1 9.5C25.2 153 8.3 202.5 8.3 256c0 2 .1 4 .1 6 .1.7.1 1.3.1 2 .1 1.3.1 2.7.2 4 0 .8.1 1.5.1 2.3 0 1.3.1 2.5.2 3.7.1.8.1 1.6.2 2.4.1 1.1.2 2.3.3 3.5 0 .8.1 1.6.2 2.4.1 1.2.3 2.4.4 3.6.1.8.2 1.5.3 2.3.1 1.3.3 2.6.5 3.9.1.6.2 1.3.3 1.9l.9 5.7c.1.6.2 1.1.3 1.7.3 1.3.5 2.7.8 4 .2.8.3 1.6.5 2.4.2 1 .5 2.1.7 3.2.2.9.4 1.7.6 2.6.2 1 .4 2 .7 3 .2.9.5 1.8.7 2.7.3 1 .5 1.9.8 2.9.3.9.5 1.8.8 2.7.2.9.5 1.9.8 2.8s.5 1.8.8 2.7c.3 1 .6 1.9.9 2.8.6 1.6 1.1 3.3 1.7 4.9.4 1 .7 1.9 1 2.8.3 1 .7 2 1.1 3 .3.8.6 1.5.9 2.3l1.2 3c.3.7.6 1.5.9 2.2.4 1 .9 2 1.3 3l.9 2.1c.5 1 .9 2 1.4 3 .3.7.6 1.3.9 2 .5 1 1 2.1 1.5 3.1.2.6.5 1.1.8 1.7.6 1.1 1.1 2.2 1.7 3.3.1.2.2.3.3.5 2.2 4.1 4.4 8.2 6.8 12.2.2.4.5.8.7 1.2.7 1.1 1.3 2.2 2 3.3.3.5.6.9.9 1.4.6 1.1 1.3 2.1 2 3.2.3.5.6.9.9 1.4.7 1.1 1.4 2.1 2.1 3.2.2.4.5.8.8 1.2.7 1.1 1.5 2.2 2.3 3.3.2.2.3.5.5.7 37.5 51.7 94.4 88.5 160 99.4.9.1 1.7.3 2.6.4 1 .2 2.1.4 3.1.5s1.9.3 2.8.4c1 .2 2 .3 3 .4.9.1 1.9.2 2.9.3s1.9.2 2.9.3 2.1.2 3.1.3c.9.1 1.8.1 2.7.2 1.1.1 2.3.1 3.4.2.8 0 1.7.1 2.5.1 1.3 0 2.6.1 3.9.1.7.1 1.4.1 2.1.1 2 .1 4 .1 6 .1s4-.1 6-.1c.7 0 1.4-.1 2.1-.1 1.3 0 2.6 0 3.9-.1.8 0 1.7-.1 2.5-.1 1.1-.1 2.3-.1 3.4-.2.9 0 1.8-.1 2.7-.2 1-.1 2.1-.2 3.1-.3s1.9-.2 2.9-.3c.9-.1 1.9-.2 2.9-.3s2-.3 3-.4 1.9-.3 2.8-.4c1-.2 2.1-.3 3.1-.5.9-.1 1.7-.3 2.6-.4 65.6-11 122.5-47.7 160.1-102.4.2-.2.3-.5.5-.7.8-1.1 1.5-2.2 2.3-3.3.2-.4.5-.8.8-1.2.7-1.1 1.4-2.1 2.1-3.2.3-.5.6-.9.9-1.4.6-1.1 1.3-2.1 2-3.2.3-.5.6-.9.9-1.4.7-1.1 1.3-2.2 2-3.3.2-.4.5-.8.7-1.2 2.4-4 4.6-8.1 6.8-12.2.1-.2.2-.3.3-.5.6-1.1 1.1-2.2 1.7-3.3.2-.6.5-1.1.8-1.7.5-1 1-2.1 1.5-3.1.3-.7.6-1.3.9-2 .5-1 1-2 1.4-3l.9-2.1c.5-1 .9-2 1.3-3 .3-.7.6-1.5.9-2.2l1.2-3c.3-.8.6-1.5.9-2.3.4-1 .7-2 1.1-3s.7-1.9 1-2.8c.6-1.6 1.2-3.3 1.7-4.9.3-1 .6-1.9.9-2.8s.5-1.8.8-2.7c.2-.9.5-1.9.8-2.8s.6-1.8.8-2.7c.3-1 .5-1.9.8-2.9.2-.9.5-1.8.7-2.7.2-1 .5-2 .7-3 .2-.9.4-1.7.6-2.6.2-1 .5-2.1.7-3.2.2-.8.3-1.6.5-2.4.3-1.3.6-2.7.8-4 .1-.6.2-1.1.3-1.7l.9-5.7c.1-.6.2-1.3.3-1.9.1-1.3.3-2.6.5-3.9.1-.8.2-1.5.3-2.3.1-1.2.3-2.4.4-3.6 0-.8.1-1.6.2-2.4.1-1.1.2-2.3.3-3.5.1-.8.1-1.6.2-2.4.1 1.7.1.5.2-.7 0-.8.1-1.5.1-2.3.1-1.3.2-2.7.2-4 .1-.7.1-1.3.1-2 .1-2 .1-4 .1-6 0-53.5-16.9-103-45.8-143.7zM448 371.5c-9.4 15.5-20.6 29.9-33.6 42.9-20.6 20.6-44.5 36.7-71.2 48-13.9 5.8-28.2 10.3-42.9 13.2v-75.8c0-58.6-88.6-58.6-88.6 0v75.8c-14.7-2.9-29-7.3-42.9-13.2-26.7-11.3-50.6-27.4-71.2-48-13-13-24.2-27.4-33.6-42.9v-71.3c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7V326h29.6V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7H208c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-4.8 6.5-3.7 9.5-3.7V88.1c-4.4-2-7.4-6.7-7.4-11.5 0-16.8 25.4-16.8 25.4 0 0 4.8-3 9.4-7.4 11.5V92c6.3-1.4 12.7-2.3 19.2-2.3 9.4 0 18.4 3.5 26.3 3.5 7.2 0 15.2-3.5 19.4-3.5 2.1 0 3.7 1.6 3.7 3.7v48.4c0 5.6-18.7 6.5-22.4 6.5-8.6 0-16.6-3.5-25.4-3.5-7 0-14.1 1.2-20.8 2.8v30.7c3 0 9.5-1.1 9.5 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v144h29.5v-25.8c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7z\"],\n    \"forumbee\": [448, 512, [], \"f211\", \"M5.8 309.7C2 292.7 0 275.5 0 258.3 0 135 99.8 35 223.1 35c16.6 0 33.3 2 49.3 5.5C149 87.5 51.9 186 5.8 309.7zm392.9-189.2C385 103 369 87.8 350.9 75.2c-149.6 44.3-266.3 162.1-309.7 312 12.5 18.1 28 35.6 45.2 49 43.1-151.3 161.2-271.7 312.3-315.7zm15.8 252.7c15.2-25.1 25.4-53.7 29.5-82.8-79.4 42.9-145 110.6-187.6 190.3 30-4.4 58.9-15.3 84.6-31.3 35 13.1 70.9 24.3 107 33.6-9.3-36.5-20.4-74.5-33.5-109.8zm29.7-145.5c-2.6-19.5-7.9-38.7-15.8-56.8C290.5 216.7 182 327.5 137.1 466c18.1 7.6 37 12.5 56.6 15.2C240 367.1 330.5 274.4 444.2 227.7z\"],\n    \"foursquare\": [368, 512, [], \"f180\", \"M323.1 3H49.9C12.4 3 0 31.3 0 49.1v433.8c0 20.3 12.1 27.7 18.2 30.1 6.2 2.5 22.8 4.6 32.9-7.1C180 356.5 182.2 354 182.2 354c3.1-3.4 3.4-3.1 6.8-3.1h83.4c35.1 0 40.6-25.2 44.3-39.7l48.6-243C373.8 25.8 363.1 3 323.1 3zm-16.3 73.8l-11.4 59.7c-1.2 6.5-9.5 13.2-16.9 13.2H172.1c-12 0-20.6 8.3-20.6 20.3v13c0 12 8.6 20.6 20.6 20.6h90.4c8.3 0 16.6 9.2 14.8 18.2-1.8 8.9-10.5 53.8-11.4 58.8-.9 4.9-6.8 13.5-16.9 13.5h-73.5c-13.5 0-17.2 1.8-26.5 12.6 0 0-8.9 11.4-89.5 108.3-.9.9-1.8.6-1.8-.3V75.9c0-7.7 6.8-16.6 16.6-16.6h219c8.2 0 15.6 7.7 13.5 17.5z\"],\n    \"free-code-camp\": [576, 512, [], \"f2c5\", \"M69.3 144.5c-41 68.5-36.4 163 1 227C92.5 409.7 120 423.9 120 438c0 6.8-6 13-12.8 13C87.7 451 8 375.5 8 253.2c0-111.5 78-186 97.1-186 6 0 14.9 4.8 14.9 11.1 0 12.7-28.3 28.6-50.7 66.2zm195.8 213.8c4.5 1.8 12.3 5.2 12.3-1.2 0-2.7-2.2-2.9-4.3-3.6-8.5-3.4-14-7.7-19.1-15.2-8.2-12.1-10.1-24.2-10.1-38.6 0-32.1 44.2-37.9 44.2-70 0-12.3-7.7-15.9-7.7-19.3 0-2.2.7-2.2 2.9-2.2 8 0 19.1 13.3 22.5 19.8 2.2 4.6 2.4 6 2.4 11.1 0 7-.7 14.2-.7 21.3 0 27 31.9 19.8 31.9 6.8 0-6-3.6-11.6-3.6-17.4 0-.7 0-1.2.7-1.2 3.4 0 9.4 7.7 11.1 10.1 5.8 8.9 8.5 20.8 8.5 31.4 0 32.4-29.5 49-29.5 56 0 1 2.9 7.7 12.1 1.9 29.7-15.1 53.1-47.6 53.1-89.8 0-33.6-8.7-57.7-32.1-82.6-3.9-4.1-16.4-16.9-22.5-16.9-8.2 0 7.2 18.6 7.2 31.2 0 7.2-4.8 12.3-12.3 12.3-11.6 0-14.5-25.4-15.9-33.3-5.8-33.8-12.8-58.2-46.4-74.1-10.4-5-36.5-11.8-36.5-2.2 0 2.4 2.7 4.1 4.6 5.1 9.2 5.6 19.6 21.4 19.6 38.2 0 46.1-57.7 88.2-57.7 136.2-.2 40.3 28.1 72.6 65.3 86.2zM470.4 67c-6 0-14.4 6.5-14.4 12.6 0 8.7 12.1 19.6 17.6 25.4 81.6 85.1 78.6 214.3 17.6 291-7 8.9-35.3 35.3-35.3 43.5 0 5.1 8.2 11.4 13.2 11.4 25.4 0 98.8-80.8 98.8-185.7C568 145.9 491.8 67 470.4 67zm-42.3 323.1H167c-9.4 0-15.5 7.5-15.5 16.4 0 8.5 7 15.5 15.5 15.5h261.1c9.4 0 11.9-7.5 11.9-16.4 0-8.5-3.5-15.5-11.9-15.5z\"],\n    \"freebsd\": [448, 512, [], \"f3a4\", \"M303.7 96.2c11.1-11.1 115.5-77 139.2-53.2 23.7 23.7-42.1 128.1-53.2 139.2-11.1 11.1-39.4.9-63.1-22.9-23.8-23.7-34.1-52-22.9-63.1zM109.9 68.1C73.6 47.5 22 24.6 5.6 41.1c-16.6 16.6 7.1 69.4 27.9 105.7 18.5-32.2 44.8-59.3 76.4-78.7zM406.7 174c3.3 11.3 2.7 20.7-2.7 26.1-20.3 20.3-87.5-27-109.3-70.1-18-32.3-11.1-53.4 14.9-48.7 5.7-3.6 12.3-7.6 19.6-11.6-29.8-15.5-63.6-24.3-99.5-24.3-119.1 0-215.6 96.5-215.6 215.6 0 119 96.5 215.6 215.6 215.6S445.3 380.1 445.3 261c0-38.4-10.1-74.5-27.7-105.8-3.9 7-7.6 13.3-10.9 18.8z\"],\n    \"fulcrum\": [320, 512, [], \"f50b\", \"M95.75 164.14l-35.38 43.55L25 164.14l35.38-43.55zM144.23 0l-20.54 198.18L72.72 256l51 57.82L144.23 512V300.89L103.15 256l41.08-44.89zm79.67 164.14l35.38 43.55 35.38-43.55-35.38-43.55zm-48.48 47L216.5 256l-41.08 44.89V512L196 313.82 247 256l-51-57.82L175.42 0z\"],\n    \"galactic-republic\": [496, 512, [], \"f50c\", \"M248 504C111.25 504 0 392.75 0 256S111.25 8 248 8s248 111.25 248 248-111.25 248-248 248zm0-479.47C120.37 24.53 16.53 128.37 16.53 256S120.37 487.47 248 487.47 479.47 383.63 479.47 256 375.63 24.53 248 24.53zm27.62 21.81v24.62a185.933 185.933 0 0 1 83.57 34.54l17.39-17.36c-28.75-22.06-63.3-36.89-100.96-41.8zm-55.37.07c-37.64 4.94-72.16 19.8-100.88 41.85l17.28 17.36h.08c24.07-17.84 52.55-30.06 83.52-34.67V46.41zm12.25 50.17v82.87c-10.04 2.03-19.42 5.94-27.67 11.42l-58.62-58.59-21.93 21.93 58.67 58.67c-5.47 8.23-9.45 17.59-11.47 27.62h-82.9v31h82.9c2.02 10.02 6.01 19.31 11.47 27.54l-58.67 58.69 21.93 21.93 58.62-58.62a77.873 77.873 0 0 0 27.67 11.47v82.9h31v-82.9c10.05-2.03 19.37-6.06 27.62-11.55l58.67 58.69 21.93-21.93-58.67-58.69c5.46-8.23 9.47-17.52 11.5-27.54h82.87v-31h-82.87c-2.02-10.02-6.03-19.38-11.5-27.62l58.67-58.67-21.93-21.93-58.67 58.67c-8.25-5.49-17.57-9.47-27.62-11.5V96.58h-31zm183.24 30.72l-17.36 17.36a186.337 186.337 0 0 1 34.67 83.67h24.62c-4.95-37.69-19.83-72.29-41.93-101.03zm-335.55.13c-22.06 28.72-36.91 63.26-41.85 100.91h24.65c4.6-30.96 16.76-59.45 34.59-83.52l-17.39-17.39zM38.34 283.67c4.92 37.64 19.75 72.18 41.8 100.9l17.36-17.39c-17.81-24.07-29.92-52.57-34.51-83.52H38.34zm394.7 0c-4.61 30.99-16.8 59.5-34.67 83.6l17.36 17.36c22.08-28.74 36.98-63.29 41.93-100.96h-24.62zM136.66 406.38l-17.36 17.36c28.73 22.09 63.3 36.98 100.96 41.93v-24.64c-30.99-4.63-59.53-16.79-83.6-34.65zm222.53.05c-24.09 17.84-52.58 30.08-83.57 34.67v24.57c37.67-4.92 72.21-19.79 100.96-41.85l-17.31-17.39h-.08z\"],\n    \"galactic-senate\": [512, 512, [], \"f50d\", \"M249.86 33.48v26.07C236.28 80.17 226 168.14 225.39 274.9c11.74-15.62 19.13-33.33 19.13-48.24v-16.88c-.03-5.32.75-10.53 2.19-15.65.65-2.14 1.39-4.08 2.62-5.82 1.23-1.75 3.43-3.79 6.68-3.79 3.24 0 5.45 2.05 6.68 3.79 1.23 1.75 1.97 3.68 2.62 5.82 1.44 5.12 2.22 10.33 2.19 15.65v16.88c0 14.91 7.39 32.62 19.13 48.24-.63-106.76-10.91-194.73-24.49-215.35V33.48h-12.28zm-26.34 147.77c-9.52 2.15-18.7 5.19-27.46 9.08 8.9 16.12 9.76 32.64 1.71 37.29-8 4.62-21.85-4.23-31.36-19.82-11.58 8.79-21.88 19.32-30.56 31.09 14.73 9.62 22.89 22.92 18.32 30.66-4.54 7.7-20.03 7.14-35.47-.96-5.78 13.25-9.75 27.51-11.65 42.42 9.68.18 18.67 2.38 26.18 6.04 17.78-.3 32.77-1.96 40.49-4.22 5.55-26.35 23.02-48.23 46.32-59.51.73-25.55 1.88-49.67 3.48-72.07zm64.96 0c1.59 22.4 2.75 46.52 3.47 72.07 23.29 11.28 40.77 33.16 46.32 59.51 7.72 2.26 22.71 3.92 40.49 4.22 7.51-3.66 16.5-5.85 26.18-6.04-1.9-14.91-5.86-29.17-11.65-42.42-15.44 8.1-30.93 8.66-35.47.96-4.57-7.74 3.6-21.05 18.32-30.66-8.68-11.77-18.98-22.3-30.56-31.09-9.51 15.59-23.36 24.44-31.36 19.82-8.05-4.65-7.19-21.16 1.71-37.29a147.49 147.49 0 0 0-27.45-9.08zm-32.48 8.6c-3.23 0-5.86 8.81-6.09 19.93h-.05v16.88c0 41.42-49.01 95.04-93.49 95.04-52 0-122.75-1.45-156.37 29.17v2.51c9.42 17.12 20.58 33.17 33.18 47.97C45.7 380.26 84.77 360.4 141.2 360c45.68 1.02 79.03 20.33 90.76 40.87.01.01-.01.04 0 .05 7.67 2.14 15.85 3.23 24.04 3.21 8.19.02 16.37-1.07 24.04-3.21.01-.01-.01-.04 0-.05 11.74-20.54 45.08-39.85 90.76-40.87 56.43.39 95.49 20.26 108.02 41.35 12.6-14.8 23.76-30.86 33.18-47.97v-2.51c-33.61-30.62-104.37-29.17-156.37-29.17-44.48 0-93.49-53.62-93.49-95.04v-16.88h-.05c-.23-11.12-2.86-19.93-6.09-19.93zm0 96.59c22.42 0 40.6 18.18 40.6 40.6s-18.18 40.65-40.6 40.65-40.6-18.23-40.6-40.65c0-22.42 18.18-40.6 40.6-40.6zm0 7.64c-18.19 0-32.96 14.77-32.96 32.96S237.81 360 256 360s32.96-14.77 32.96-32.96-14.77-32.96-32.96-32.96zm0 6.14c14.81 0 26.82 12.01 26.82 26.82s-12.01 26.82-26.82 26.82-26.82-12.01-26.82-26.82 12.01-26.82 26.82-26.82zm-114.8 66.67c-10.19.07-21.6.36-30.5 1.66.43 4.42 1.51 18.63 7.11 29.76 9.11-2.56 18.36-3.9 27.62-3.9 41.28.94 71.48 34.35 78.26 74.47l.11 4.7c10.4 1.91 21.19 2.94 32.21 2.94 11.03 0 21.81-1.02 32.21-2.94l.11-4.7c6.78-40.12 36.98-73.53 78.26-74.47 9.26 0 18.51 1.34 27.62 3.9 5.6-11.13 6.68-25.34 7.11-29.76-8.9-1.3-20.32-1.58-30.5-1.66-18.76.42-35.19 4.17-48.61 9.67-12.54 16.03-29.16 30.03-49.58 33.07-.09.02-.17.04-.27.05-.05.01-.11.04-.16.05-5.24 1.07-10.63 1.6-16.19 1.6-5.55 0-10.95-.53-16.19-1.6-.05-.01-.11-.04-.16-.05-.1-.02-.17-.04-.27-.05-20.42-3.03-37.03-17.04-49.58-33.07-13.42-5.49-29.86-9.25-48.61-9.67z\"],\n    \"get-pocket\": [448, 512, [], \"f265\", \"M407.6 64h-367C18.5 64 0 82.5 0 104.6v135.2C0 364.5 99.7 464 224.2 464c124 0 223.8-99.5 223.8-224.2V104.6c0-22.4-17.7-40.6-40.4-40.6zm-162 268.5c-12.4 11.8-31.4 11.1-42.4 0C89.5 223.6 88.3 227.4 88.3 209.3c0-16.9 13.8-30.7 30.7-30.7 17 0 16.1 3.8 105.2 89.3 90.6-86.9 88.6-89.3 105.5-89.3 16.9 0 30.7 13.8 30.7 30.7 0 17.8-2.9 15.7-114.8 123.2z\"],\n    \"gg\": [512, 512, [], \"f260\", \"M179.2 230.4l102.4 102.4-102.4 102.4L0 256 179.2 76.8l44.8 44.8-25.6 25.6-19.2-19.2-128 128 128 128 51.5-51.5-77.1-76.5 25.6-25.6zM332.8 76.8L230.4 179.2l102.4 102.4 25.6-25.6-77.1-76.5 51.5-51.5 128 128-128 128-19.2-19.2-25.6 25.6 44.8 44.8L512 256 332.8 76.8z\"],\n    \"gg-circle\": [512, 512, [], \"f261\", \"M257 8C120 8 9 119 9 256s111 248 248 248 248-111 248-248S394 8 257 8zm-49.5 374.8L81.8 257.1l125.7-125.7 35.2 35.4-24.2 24.2-11.1-11.1-77.2 77.2 77.2 77.2 26.6-26.6-53.1-52.9 24.4-24.4 77.2 77.2-75 75.2zm99-2.2l-35.2-35.2 24.1-24.4 11.1 11.1 77.2-77.2-77.2-77.2-26.5 26.5 53.1 52.9-24.4 24.4-77.2-77.2 75-75L432.2 255 306.5 380.6z\"],\n    \"git\": [512, 512, [], \"f1d3\", \"M216.29 158.39H137C97 147.9 6.51 150.63 6.51 233.18c0 30.09 15 51.23 35 61-25.1 23-37 33.85-37 49.21 0 11 4.47 21.14 17.89 26.81C8.13 383.61 0 393.35 0 411.65c0 32.11 28.05 50.82 101.63 50.82 70.75 0 111.79-26.42 111.79-73.18 0-58.66-45.16-56.5-151.63-63l13.43-21.55c27.27 7.58 118.7 10 118.7-67.89 0-18.7-7.73-31.71-15-41.07l37.41-2.84zm-63.42 241.9c0 32.06-104.89 32.1-104.89 2.43 0-8.14 5.27-15 10.57-21.54 77.71 5.3 94.32 3.37 94.32 19.11zm-50.81-134.58c-52.8 0-50.46-71.16 1.2-71.16 49.54 0 50.82 71.16-1.2 71.16zm133.3 100.51v-32.1c26.75-3.66 27.24-2 27.24-11V203.61c0-8.5-2.05-7.38-27.24-16.26l4.47-32.92H324v168.71c0 6.51.4 7.32 6.51 8.14l20.73 2.84v32.1zm52.45-244.31c-23.17 0-36.59-13.43-36.59-36.61s13.42-35.77 36.59-35.77c23.58 0 37 12.62 37 35.77s-13.42 36.61-37 36.61zM512 350.46c-17.49 8.53-43.1 16.26-66.28 16.26-48.38 0-66.67-19.5-66.67-65.46V194.75c0-5.42 1.05-4.06-31.71-4.06V154.5c35.78-4.07 50-22 54.47-66.27h38.63c0 65.83-1.34 61.81 3.26 61.81H501v40.65h-60.56v97.15c0 6.92-4.92 51.41 60.57 26.84z\"],\n    \"git-alt\": [448, 512, [], \"f841\", \"M439.55 236.05L244 40.45a28.87 28.87 0 0 0-40.81 0l-40.66 40.63 51.52 51.52c27.06-9.14 52.68 16.77 43.39 43.68l49.66 49.66c34.23-11.8 61.18 31 35.47 56.69-26.49 26.49-70.21-2.87-56-37.34L240.22 199v121.85c25.3 12.54 22.26 41.85 9.08 55a34.34 34.34 0 0 1-48.55 0c-17.57-17.6-11.07-46.91 11.25-56v-123c-20.8-8.51-24.6-30.74-18.64-45L142.57 101 8.45 235.14a28.86 28.86 0 0 0 0 40.81l195.61 195.6a28.86 28.86 0 0 0 40.8 0l194.69-194.69a28.86 28.86 0 0 0 0-40.81z\"],\n    \"git-square\": [448, 512, [], \"f1d2\", \"M100.59 334.24c48.57 3.31 58.95 2.11 58.95 11.94 0 20-65.55 20.06-65.55 1.52.01-5.09 3.29-9.4 6.6-13.46zm27.95-116.64c-32.29 0-33.75 44.47-.75 44.47 32.51 0 31.71-44.47.75-44.47zM448 80v352a48 48 0 0 1-48 48H48a48 48 0 0 1-48-48V80a48 48 0 0 1 48-48h352a48 48 0 0 1 48 48zm-227 69.31c0 14.49 8.38 22.88 22.86 22.88 14.74 0 23.13-8.39 23.13-22.88S258.62 127 243.88 127c-14.48 0-22.88 7.84-22.88 22.31zM199.18 195h-49.55c-25-6.55-81.56-4.85-81.56 46.75 0 18.8 9.4 32 21.85 38.11C74.23 294.23 66.8 301 66.8 310.6c0 6.87 2.79 13.22 11.18 16.76-8.9 8.4-14 14.48-14 25.92C64 373.35 81.53 385 127.52 385c44.22 0 69.87-16.51 69.87-45.73 0-36.67-28.23-35.32-94.77-39.38l8.38-13.43c17 4.74 74.19 6.23 74.19-42.43 0-11.69-4.83-19.82-9.4-25.67l23.38-1.78zm84.34 109.84l-13-1.78c-3.82-.51-4.07-1-4.07-5.09V192.52h-52.6l-2.79 20.57c15.75 5.55 17 4.86 17 10.17V298c0 5.62-.31 4.58-17 6.87v20.06h72.42zM384 315l-6.87-22.37c-40.93 15.37-37.85-12.41-37.85-16.73v-60.72h37.85v-25.41h-35.82c-2.87 0-2 2.52-2-38.63h-24.18c-2.79 27.7-11.68 38.88-34 41.42v22.62c20.47 0 19.82-.85 19.82 2.54v66.57c0 28.72 11.43 40.91 41.67 40.91 14.45 0 30.45-4.83 41.38-10.2z\"],\n    \"github\": [496, 512, [], \"f09b\", \"M165.9 397.4c0 2-2.3 3.6-5.2 3.6-3.3.3-5.6-1.3-5.6-3.6 0-2 2.3-3.6 5.2-3.6 3-.3 5.6 1.3 5.6 3.6zm-31.1-4.5c-.7 2 1.3 4.3 4.3 4.9 2.6 1 5.6 0 6.2-2s-1.3-4.3-4.3-5.2c-2.6-.7-5.5.3-6.2 2.3zm44.2-1.7c-2.9.7-4.9 2.6-4.6 4.9.3 2 2.9 3.3 5.9 2.6 2.9-.7 4.9-2.6 4.6-4.6-.3-1.9-3-3.2-5.9-2.9zM244.8 8C106.1 8 0 113.3 0 252c0 110.9 69.8 205.8 169.5 239.2 12.8 2.3 17.3-5.6 17.3-12.1 0-6.2-.3-40.4-.3-61.4 0 0-70 15-84.7-29.8 0 0-11.4-29.1-27.8-36.6 0 0-22.9-15.7 1.6-15.4 0 0 24.9 2 38.6 25.8 21.9 38.6 58.6 27.5 72.9 20.9 2.3-16 8.8-27.1 16-33.7-55.9-6.2-112.3-14.3-112.3-110.5 0-27.5 7.6-41.3 23.6-58.9-2.6-6.5-11.1-33.3 2.6-67.9 20.9-6.5 69 27 69 27 20-5.6 41.5-8.5 62.8-8.5s42.8 2.9 62.8 8.5c0 0 48.1-33.6 69-27 13.7 34.7 5.2 61.4 2.6 67.9 16 17.7 25.8 31.5 25.8 58.9 0 96.5-58.9 104.2-114.8 110.5 9.2 7.9 17 22.9 17 46.4 0 33.7-.3 75.4-.3 83.6 0 6.5 4.6 14.4 17.3 12.1C428.2 457.8 496 362.9 496 252 496 113.3 383.5 8 244.8 8zM97.2 352.9c-1.3 1-1 3.3.7 5.2 1.6 1.6 3.9 2.3 5.2 1 1.3-1 1-3.3-.7-5.2-1.6-1.6-3.9-2.3-5.2-1zm-10.8-8.1c-.7 1.3.3 2.9 2.3 3.9 1.6 1 3.6.7 4.3-.7.7-1.3-.3-2.9-2.3-3.9-2-.6-3.6-.3-4.3.7zm32.4 35.6c-1.6 1.3-1 4.3 1.3 6.2 2.3 2.3 5.2 2.6 6.5 1 1.3-1.3.7-4.3-1.3-6.2-2.2-2.3-5.2-2.6-6.5-1zm-11.4-14.7c-1.6 1-1.6 3.6 0 5.9 1.6 2.3 4.3 3.3 5.6 2.3 1.6-1.3 1.6-3.9 0-6.2-1.4-2.3-4-3.3-5.6-2z\"],\n    \"github-alt\": [480, 512, [], \"f113\", \"M186.1 328.7c0 20.9-10.9 55.1-36.7 55.1s-36.7-34.2-36.7-55.1 10.9-55.1 36.7-55.1 36.7 34.2 36.7 55.1zM480 278.2c0 31.9-3.2 65.7-17.5 95-37.9 76.6-142.1 74.8-216.7 74.8-75.8 0-186.2 2.7-225.6-74.8-14.6-29-20.2-63.1-20.2-95 0-41.9 13.9-81.5 41.5-113.6-5.2-15.8-7.7-32.4-7.7-48.8 0-21.5 4.9-32.3 14.6-51.8 45.3 0 74.3 9 108.8 36 29-6.9 58.8-10 88.7-10 27 0 54.2 2.9 80.4 9.2 34-26.7 63-35.2 107.8-35.2 9.8 19.5 14.6 30.3 14.6 51.8 0 16.4-2.6 32.7-7.7 48.2 27.5 32.4 39 72.3 39 114.2zm-64.3 50.5c0-43.9-26.7-82.6-73.5-82.6-18.9 0-37 3.4-56 6-14.9 2.3-29.8 3.2-45.1 3.2-15.2 0-30.1-.9-45.1-3.2-18.7-2.6-37-6-56-6-46.8 0-73.5 38.7-73.5 82.6 0 87.8 80.4 101.3 150.4 101.3h48.2c70.3 0 150.6-13.4 150.6-101.3zm-82.6-55.1c-25.8 0-36.7 34.2-36.7 55.1s10.9 55.1 36.7 55.1 36.7-34.2 36.7-55.1-10.9-55.1-36.7-55.1z\"],\n    \"github-square\": [448, 512, [], \"f092\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM277.3 415.7c-8.4 1.5-11.5-3.7-11.5-8 0-5.4.2-33 .2-55.3 0-15.6-5.2-25.5-11.3-30.7 37-4.1 76-9.2 76-73.1 0-18.2-6.5-27.3-17.1-39 1.7-4.3 7.4-22-1.7-45-13.9-4.3-45.7 17.9-45.7 17.9-13.2-3.7-27.5-5.6-41.6-5.6-14.1 0-28.4 1.9-41.6 5.6 0 0-31.8-22.2-45.7-17.9-9.1 22.9-3.5 40.6-1.7 45-10.6 11.7-15.6 20.8-15.6 39 0 63.6 37.3 69 74.3 73.1-4.8 4.3-9.1 11.7-10.6 22.3-9.5 4.3-33.8 11.7-48.3-13.9-9.1-15.8-25.5-17.1-25.5-17.1-16.2-.2-1.1 10.2-1.1 10.2 10.8 5 18.4 24.2 18.4 24.2 9.7 29.7 56.1 19.7 56.1 19.7 0 13.9.2 36.5.2 40.6 0 4.3-3 9.5-11.5 8-66-22.1-112.2-84.9-112.2-158.3 0-91.8 70.2-161.5 162-161.5S388 165.6 388 257.4c.1 73.4-44.7 136.3-110.7 158.3zm-98.1-61.1c-1.9.4-3.7-.4-3.9-1.7-.2-1.5 1.1-2.8 3-3.2 1.9-.2 3.7.6 3.9 1.9.3 1.3-1 2.6-3 3zm-9.5-.9c0 1.3-1.5 2.4-3.5 2.4-2.2.2-3.7-.9-3.7-2.4 0-1.3 1.5-2.4 3.5-2.4 1.9-.2 3.7.9 3.7 2.4zm-13.7-1.1c-.4 1.3-2.4 1.9-4.1 1.3-1.9-.4-3.2-1.9-2.8-3.2.4-1.3 2.4-1.9 4.1-1.5 2 .6 3.3 2.1 2.8 3.4zm-12.3-5.4c-.9 1.1-2.8.9-4.3-.6-1.5-1.3-1.9-3.2-.9-4.1.9-1.1 2.8-.9 4.3.6 1.3 1.3 1.8 3.3.9 4.1zm-9.1-9.1c-.9.6-2.6 0-3.7-1.5s-1.1-3.2 0-3.9c1.1-.9 2.8-.2 3.7 1.3 1.1 1.5 1.1 3.3 0 4.1zm-6.5-9.7c-.9.9-2.4.4-3.5-.6-1.1-1.3-1.3-2.8-.4-3.5.9-.9 2.4-.4 3.5.6 1.1 1.3 1.3 2.8.4 3.5zm-6.7-7.4c-.4.9-1.7 1.1-2.8.4-1.3-.6-1.9-1.7-1.5-2.6.4-.6 1.5-.9 2.8-.4 1.3.7 1.9 1.8 1.5 2.6z\"],\n    \"gitkraken\": [592, 512, [], \"f3a6\", \"M565.7 118.1c-2.3-6.1-9.3-9.2-15.3-6.6-5.7 2.4-8.5 8.9-6.3 14.6 10.9 29 16.9 60.5 16.9 93.3 0 134.6-100.3 245.7-230.2 262.7V358.4c7.9-1.5 15.5-3.6 23-6.2v104c106.7-25.9 185.9-122.1 185.9-236.8 0-91.8-50.8-171.8-125.8-213.3-5.7-3.2-13-.9-15.9 5-2.7 5.5-.6 12.2 4.7 15.1 67.9 37.6 113.9 110 113.9 193.2 0 93.3-57.9 173.1-139.8 205.4v-92.2c14.2-4.5 24.9-17.7 24.9-33.5 0-13.1-6.8-24.4-17.3-30.5 8.3-79.5 44.5-58.6 44.5-83.9V170c0-38-87.9-161.8-129-164.7-2.5-.2-5-.2-7.6 0C251.1 8.3 163.2 132 163.2 170v14.8c0 25.3 36.3 4.3 44.5 83.9-10.6 6.1-17.3 17.4-17.3 30.5 0 15.8 10.6 29 24.8 33.5v92.2c-81.9-32.2-139.8-112-139.8-205.4 0-83.1 46-155.5 113.9-193.2 5.4-3 7.4-9.6 4.7-15.1-2.9-5.9-10.1-8.2-15.9-5-75 41.5-125.8 121.5-125.8 213.3 0 114.7 79.2 210.8 185.9 236.8v-104c7.6 2.5 15.1 4.6 23 6.2v123.7C131.4 465.2 31 354.1 31 219.5c0-32.8 6-64.3 16.9-93.3 2.2-5.8-.6-12.2-6.3-14.6-6-2.6-13 .4-15.3 6.6C14.5 149.7 8 183.8 8 219.5c0 155.1 122.6 281.6 276.3 287.8V361.4c6.8.4 15 .5 23.4 0v145.8C461.4 501.1 584 374.6 584 219.5c0-35.7-6.5-69.8-18.3-101.4zM365.9 275.5c13 0 23.7 10.5 23.7 23.7 0 13.1-10.6 23.7-23.7 23.7-13 0-23.7-10.5-23.7-23.7 0-13.1 10.6-23.7 23.7-23.7zm-139.8 47.3c-13.2 0-23.7-10.7-23.7-23.7s10.5-23.7 23.7-23.7c13.1 0 23.7 10.6 23.7 23.7 0 13-10.5 23.7-23.7 23.7z\"],\n    \"gitlab\": [512, 512, [], \"f296\", \"M105.2 24.9c-3.1-8.9-15.7-8.9-18.9 0L29.8 199.7h132c-.1 0-56.6-174.8-56.6-174.8zM.9 287.7c-2.6 8 .3 16.9 7.1 22l247.9 184-226.2-294zm160.8-88l94.3 294 94.3-294zm349.4 88l-28.8-88-226.3 294 247.9-184c6.9-5.1 9.7-14 7.2-22zM425.7 24.9c-3.1-8.9-15.7-8.9-18.9 0l-56.6 174.8h132z\"],\n    \"gitter\": [384, 512, [], \"f426\", \"M66.4 322.5H16V0h50.4v322.5zM166.9 76.1h-50.4V512h50.4V76.1zm100.6 0h-50.4V512h50.4V76.1zM368 76h-50.4v247H368V76z\"],\n    \"glide\": [448, 512, [], \"f2a5\", \"M252.8 148.6c0 8.8-1.6 17.7-3.4 26.4-5.8 27.8-11.6 55.8-17.3 83.6-1.4 6.3-8.3 4.9-13.7 4.9-23.8 0-30.5-26-30.5-45.5 0-29.3 11.2-68.1 38.5-83.1 4.3-2.5 9.2-4.2 14.1-4.2 11.4 0 12.3 8.3 12.3 17.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 187c0-5.1-20.8-37.7-25.5-39.5-2.2-.9-7.2-2.3-9.6-2.3-23.1 0-38.7 10.5-58.2 21.5l-.5-.5c4.3-29.4 14.6-57.2 14.6-87.4 0-44.6-23.8-62.7-67.5-62.7-71.7 0-108 70.8-108 123.5 0 54.7 32 85 86.3 85 7.5 0 6.9-.6 6.9 2.3-10.5 80.3-56.5 82.9-56.5 58.9 0-24.4 28-36.5 28.3-38-.2-7.6-29.3-17.2-36.7-17.2-21.1 0-32.7 33-32.7 50.6 0 32.3 20.4 54.7 53.3 54.7 48.2 0 83.4-49.7 94.3-91.7 9.4-37.7 7-39.4 12.3-42.1 20-10.1 35.8-16.8 58.4-16.8 11.1 0 19 2.3 36.7 5.2 1.8.1 4.1-1.7 4.1-3.5z\"],\n    \"glide-g\": [448, 512, [], \"f2a6\", \"M407.1 211.2c-3.5-1.4-11.6-3.8-15.4-3.8-37.1 0-62.2 16.8-93.5 34.5l-.9-.9c7-47.3 23.5-91.9 23.5-140.4C320.8 29.1 282.6 0 212.4 0 97.3 0 39 113.7 39 198.4 39 286.3 90.3 335 177.6 335c12 0 11-1 11 3.8-16.9 128.9-90.8 133.1-90.8 94.6 0-39.2 45-58.6 45.5-61-.3-12.2-47-27.6-58.9-27.6-33.9.1-52.4 51.2-52.4 79.3C32 476 64.8 512 117.5 512c77.4 0 134-77.8 151.4-145.4 15.1-60.5 11.2-63.3 19.7-67.6 32.2-16.2 57.5-27 93.8-27 17.8 0 30.5 3.7 58.9 8.4 2.9 0 6.7-2.9 6.7-5.8 0-8-33.4-60.5-40.9-63.4zm-175.3-84.4c-9.3 44.7-18.6 89.6-27.8 134.3-2.3 10.2-13.3 7.8-22 7.8-38.3 0-49-41.8-49-73.1 0-47 18-109.3 61.8-133.4 7-4.1 14.8-6.7 22.6-6.7 18.6 0 20 13.3 20 28.7-.1 14.3-2.7 28.5-5.6 42.4z\"],\n    \"gofore\": [400, 512, [], \"f3a7\", \"M324 319.8h-13.2v34.7c-24.5 23.1-56.3 35.8-89.9 35.8-73.2 0-132.4-60.2-132.4-134.4 0-74.1 59.2-134.4 132.4-134.4 35.3 0 68.6 14 93.6 39.4l62.3-63.3C335 55.3 279.7 32 220.7 32 98 32 0 132.6 0 256c0 122.5 97 224 220.7 224 63.2 0 124.5-26.2 171-82.5-2-27.6-13.4-77.7-67.7-77.7zm-12.1-112.5H205.6v89H324c33.5 0 60.5 15.1 76 41.8v-30.6c0-65.2-40.4-100.2-88.1-100.2z\"],\n    \"goodreads\": [448, 512, [], \"f3a8\", \"M299.9 191.2c5.1 37.3-4.7 79-35.9 100.7-22.3 15.5-52.8 14.1-70.8 5.7-37.1-17.3-49.5-58.6-46.8-97.2 4.3-60.9 40.9-87.9 75.3-87.5 46.9-.2 71.8 31.8 78.2 78.3zM448 88v336c0 30.9-25.1 56-56 56H56c-30.9 0-56-25.1-56-56V88c0-30.9 25.1-56 56-56h336c30.9 0 56 25.1 56 56zM330 313.2s-.1-34-.1-217.3h-29v40.3c-.8.3-1.2-.5-1.6-1.2-9.6-20.7-35.9-46.3-76-46-51.9.4-87.2 31.2-100.6 77.8-4.3 14.9-5.8 30.1-5.5 45.6 1.7 77.9 45.1 117.8 112.4 115.2 28.9-1.1 54.5-17 69-45.2.5-1 1.1-1.9 1.7-2.9.2.1.4.1.6.2.3 3.8.2 30.7.1 34.5-.2 14.8-2 29.5-7.2 43.5-7.8 21-22.3 34.7-44.5 39.5-17.8 3.9-35.6 3.8-53.2-1.2-21.5-6.1-36.5-19-41.1-41.8-.3-1.6-1.3-1.3-2.3-1.3h-26.8c.8 10.6 3.2 20.3 8.5 29.2 24.2 40.5 82.7 48.5 128.2 37.4 49.9-12.3 67.3-54.9 67.4-106.3z\"],\n    \"goodreads-g\": [384, 512, [], \"f3a9\", \"M42.6 403.3h2.8c12.7 0 25.5 0 38.2.1 1.6 0 3.1-.4 3.6 2.1 7.1 34.9 30 54.6 62.9 63.9 26.9 7.6 54.1 7.8 81.3 1.8 33.8-7.4 56-28.3 68-60.4 8-21.5 10.7-43.8 11-66.5.1-5.8.3-47-.2-52.8l-.9-.3c-.8 1.5-1.7 2.9-2.5 4.4-22.1 43.1-61.3 67.4-105.4 69.1-103 4-169.4-57-172-176.2-.5-23.7 1.8-46.9 8.3-69.7C58.3 47.7 112.3.6 191.6 0c61.3-.4 101.5 38.7 116.2 70.3.5 1.1 1.3 2.3 2.4 1.9V10.6h44.3c0 280.3.1 332.2.1 332.2-.1 78.5-26.7 143.7-103 162.2-69.5 16.9-159 4.8-196-57.2-8-13.5-11.8-28.3-13-44.5zM188.9 36.5c-52.5-.5-108.5 40.7-115 133.8-4.1 59 14.8 122.2 71.5 148.6 27.6 12.9 74.3 15 108.3-8.7 47.6-33.2 62.7-97 54.8-154-9.7-71.1-47.8-120-119.6-119.7z\"],\n    \"google\": [488, 512, [], \"f1a0\", \"M488 261.8C488 403.3 391.1 504 248 504 110.8 504 0 393.2 0 256S110.8 8 248 8c66.8 0 123 24.5 166.3 64.9l-67.5 64.9C258.5 52.6 94.3 116.6 94.3 256c0 86.5 69.1 156.6 153.7 156.6 98.2 0 135-70.4 140.8-106.9H248v-85.3h236.1c2.3 12.7 3.9 24.9 3.9 41.4z\"],\n    \"google-drive\": [512, 512, [], \"f3aa\", \"M339 314.9L175.4 32h161.2l163.6 282.9H339zm-137.5 23.6L120.9 480h310.5L512 338.5H201.5zM154.1 67.4L0 338.5 80.6 480 237 208.8 154.1 67.4z\"],\n    \"google-play\": [512, 512, [], \"f3ab\", \"M325.3 234.3L104.6 13l280.8 161.2-60.1 60.1zM47 0C34 6.8 25.3 19.2 25.3 35.3v441.3c0 16.1 8.7 28.5 21.7 35.3l256.6-256L47 0zm425.2 225.6l-58.9-34.1-65.7 64.5 65.7 64.5 60.1-34.1c18-14.3 18-46.5-1.2-60.8zM104.6 499l280.8-161.2-60.1-60.1L104.6 499z\"],\n    \"google-plus\": [496, 512, [], \"f2b3\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm-70.7 372c-68.8 0-124-55.5-124-124s55.2-124 124-124c31.3 0 60.1 11 83 32.3l-33.6 32.6c-13.2-12.9-31.3-19.1-49.4-19.1-42.9 0-77.2 35.5-77.2 78.1s34.2 78.1 77.2 78.1c32.6 0 64.9-19.1 70.1-53.3h-70.1v-42.6h116.9c1.3 6.8 1.9 13.6 1.9 20.7 0 70.8-47.5 121.2-118.8 121.2zm230.2-106.2v35.5H372v-35.5h-35.5v-35.5H372v-35.5h35.5v35.5h35.2v35.5h-35.2z\"],\n    \"google-plus-g\": [640, 512, [], \"f0d5\", \"M386.061 228.496c1.834 9.692 3.143 19.384 3.143 31.956C389.204 370.205 315.599 448 204.8 448c-106.084 0-192-85.915-192-192s85.916-192 192-192c51.864 0 95.083 18.859 128.611 50.292l-52.126 50.03c-14.145-13.621-39.028-29.599-76.485-29.599-65.484 0-118.92 54.221-118.92 121.277 0 67.056 53.436 121.277 118.92 121.277 75.961 0 104.513-54.745 108.965-82.773H204.8v-66.009h181.261zm185.406 6.437V179.2h-56.001v55.733h-55.733v56.001h55.733v55.733h56.001v-55.733H627.2v-56.001h-55.733z\"],\n    \"google-plus-square\": [448, 512, [], \"f0d4\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM164 356c-55.3 0-100-44.7-100-100s44.7-100 100-100c27 0 49.5 9.8 67 26.2l-27.1 26.1c-7.4-7.1-20.3-15.4-39.8-15.4-34.1 0-61.9 28.2-61.9 63.2 0 34.9 27.8 63.2 61.9 63.2 39.6 0 54.4-28.5 56.8-43.1H164v-34.4h94.4c1 5 1.6 10.1 1.6 16.6 0 57.1-38.3 97.6-96 97.6zm220-81.8h-29v29h-29.2v-29h-29V245h29v-29H355v29h29v29.2z\"],\n    \"google-wallet\": [448, 512, [], \"f1ee\", \"M156.8 126.8c37.6 60.6 64.2 113.1 84.3 162.5-8.3 33.8-18.8 66.5-31.3 98.3-13.2-52.3-26.5-101.3-56-148.5 6.5-36.4 2.3-73.6 3-112.3zM109.3 200H16.1c-6.5 0-10.5 7.5-6.5 12.7C51.8 267 81.3 330.5 101.3 400h103.5c-16.2-69.7-38.7-133.7-82.5-193.5-3-4-8-6.5-13-6.5zm47.8-88c68.5 108 130 234.5 138.2 368H409c-12-138-68.4-265-143.2-368H157.1zm251.8-68.5c-1.8-6.8-8.2-11.5-15.2-11.5h-88.3c-5.3 0-9 5-7.8 10.3 13.2 46.5 22.3 95.5 26.5 146 48.2 86.2 79.7 178.3 90.6 270.8 15.8-60.5 25.3-133.5 25.3-203 0-73.6-12.1-145.1-31.1-212.6z\"],\n    \"gratipay\": [496, 512, [], \"f184\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm114.6 226.4l-113 152.7-112.7-152.7c-8.7-11.9-19.1-50.4 13.6-72 28.1-18.1 54.6-4.2 68.5 11.9 15.9 17.9 46.6 16.9 61.7 0 13.9-16.1 40.4-30 68.1-11.9 32.9 21.6 22.6 60 13.8 72z\"],\n    \"grav\": [512, 512, [], \"f2d6\", \"M301.1 212c4.4 4.4 4.4 11.9 0 16.3l-9.7 9.7c-4.4 4.7-11.9 4.7-16.6 0l-10.5-10.5c-4.4-4.7-4.4-11.9 0-16.6l9.7-9.7c4.4-4.4 11.9-4.4 16.6 0l10.5 10.8zm-30.2-19.7c3-3 3-7.8 0-10.5-2.8-3-7.5-3-10.5 0-2.8 2.8-2.8 7.5 0 10.5 3.1 2.8 7.8 2.8 10.5 0zm-26 5.3c-3 2.8-3 7.5 0 10.2 2.8 3 7.5 3 10.5 0 2.8-2.8 2.8-7.5 0-10.2-3-3-7.7-3-10.5 0zm72.5-13.3c-19.9-14.4-33.8-43.2-11.9-68.1 21.6-24.9 40.7-17.2 59.8.8 11.9 11.3 29.3 24.9 17.2 48.2-12.5 23.5-45.1 33.2-65.1 19.1zm47.7-44.5c-8.9-10-23.3 6.9-15.5 16.1 7.4 9 32.1 2.4 15.5-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-66.2 42.6c2.5-16.1-20.2-16.6-25.2-25.7-13.6-24.1-27.7-36.8-54.5-30.4 11.6-8 23.5-6.1 23.5-6.1.3-6.4 0-13-9.4-24.9 3.9-12.5.3-22.4.3-22.4 15.5-8.6 26.8-24.4 29.1-43.2 3.6-31-18.8-59.2-49.8-62.8-22.1-2.5-43.7 7.7-54.3 25.7-23.2 40.1 1.4 70.9 22.4 81.4-14.4-1.4-34.3-11.9-40.1-34.3-6.6-25.7 2.8-49.8 8.9-61.4 0 0-4.4-5.8-8-8.9 0 0-13.8 0-24.6 5.3 11.9-15.2 25.2-14.4 25.2-14.4 0-6.4-.6-14.9-3.6-21.6-5.4-11-23.8-12.9-31.7 2.8.1-.2.3-.4.4-.5-5 11.9-1.1 55.9 16.9 87.2-2.5 1.4-9.1 6.1-13 10-21.6 9.7-56.2 60.3-56.2 60.3-28.2 10.8-77.2 50.9-70.6 79.7.3 3 1.4 5.5 3 7.5-2.8 2.2-5.5 5-8.3 8.3-11.9 13.8-5.3 35.2 17.7 24.4 15.8-7.2 29.6-20.2 36.3-30.4 0 0-5.5-5-16.3-4.4 27.7-6.6 34.3-9.4 46.2-9.1 8 3.9 8-34.3 8-34.3 0-14.7-2.2-31-11.1-41.5 12.5 12.2 29.1 32.7 28 60.6-.8 18.3-15.2 23-15.2 23-9.1 16.6-43.2 65.9-30.4 106 0 0-9.7-14.9-10.2-22.1-17.4 19.4-46.5 52.3-24.6 64.5 26.6 14.7 108.8-88.6 126.2-142.3 34.6-20.8 55.4-47.3 63.9-65 22 43.5 95.3 94.5 101.1 59z\"],\n    \"gripfire\": [384, 512, [], \"f3ac\", \"M112.5 301.4c0-73.8 105.1-122.5 105.1-203 0-47.1-34-88-39.1-90.4.4 3.3.6 6.7.6 10C179.1 110.1 32 171.9 32 286.6c0 49.8 32.2 79.2 66.5 108.3 65.1 46.7 78.1 71.4 78.1 86.6 0 10.1-4.8 17-4.8 22.3 13.1-16.7 17.4-31.9 17.5-46.4 0-29.6-21.7-56.3-44.2-86.5-16-22.3-32.6-42.6-32.6-69.5zm205.3-39c-12.1-66.8-78-124.4-94.7-130.9l4 7.2c2.4 5.1 3.4 10.9 3.4 17.1 0 44.7-54.2 111.2-56.6 116.7-2.2 5.1-3.2 10.5-3.2 15.8 0 20.1 15.2 42.1 17.9 42.1 2.4 0 56.6-55.4 58.1-87.7 6.4 11.7 9.1 22.6 9.1 33.4 0 41.2-41.8 96.9-41.8 96.9 0 11.6 31.9 53.2 35.5 53.2 1 0 2.2-1.4 3.2-2.4 37.9-39.3 67.3-85 67.3-136.8 0-8-.7-16.2-2.2-24.6z\"],\n    \"grunt\": [384, 512, [], \"f3ad\", \"M61.3 189.3c-1.1 10 5.2 19.1 5.2 19.1.7-7.5 2.2-12.8 4-16.6.4 10.3 3.2 23.5 12.8 34.1 6.9 7.6 35.6 23.3 54.9 6.1 1 2.4 2.1 5.3 3 8.5 2.9 10.3-2.7 25.3-2.7 25.3s15.1-17.1 13.9-32.5c10.8-.5 21.4-8.4 21.1-19.5 0 0-18.9 10.4-35.5-8.8-9.7-11.2-40.9-42-83.1-31.8 4.3 1 8.9 2.4 13.5 4.1h-.1c-4.2 2-6.5 7.1-7 12zm28.3-1.8c19.5 11 37.4 25.7 44.9 37-5.7 3.3-21.7 10.4-38-1.7-10.3-7.6-9.8-26.2-6.9-35.3zm142.1 45.8c-1.2 15.5 13.9 32.5 13.9 32.5s-5.6-15-2.7-25.3c.9-3.2 2-6 3-8.5 19.3 17.3 48 1.5 54.8-6.1 9.6-10.6 12.3-23.8 12.8-34.1 1.8 3.8 3.4 9.1 4 16.6 0 0 6.4-9.1 5.2-19.1-.6-5-2.9-10-7-11.8h-.1c4.6-1.8 9.2-3.2 13.5-4.1-42.3-10.2-73.4 20.6-83.1 31.8-16.7 19.2-35.5 8.8-35.5 8.8-.2 10.9 10.4 18.9 21.2 19.3zm62.7-45.8c3 9.1 3.4 27.7-7 35.4-16.3 12.1-32.2 5-37.9 1.6 7.5-11.4 25.4-26 44.9-37zM160 418.5h-29.4c-5.5 0-8.2 1.6-9.5 2.9-1.9 2-2.2 4.7-.9 8.1 3.5 9.1 11.4 16.5 13.7 18.6 3.1 2.7 7.5 4.3 11.8 4.3 4.4 0 8.3-1.7 11-4.6 7.5-8.2 11.9-17.1 13-19.8.6-1.5 1.3-4.5-.9-6.8-1.8-1.8-4.7-2.7-8.8-2.7zm189.2-101.2c-2.4 17.9-13 33.8-24.6 43.7-3.1-22.7-3.7-55.5-3.7-62.4 0-14.7 9.5-24.5 12.2-26.1 2.5-1.5 5.4-3 8.3-4.6 18-9.6 40.4-21.6 40.4-43.7 0-16.2-9.3-23.2-15.4-27.8-.8-.6-1.5-1.1-2.2-1.7-2.1-1.7-3.7-3-4.3-4.4-4.4-9.8-3.6-34.2-1.7-37.6.6-.6 16.7-20.9 11.8-39.2-2-7.4-6.9-13.3-14.1-17-5.3-2.7-11.9-4.2-19.5-4.5-.1-2-.5-3.9-.9-5.9-.6-2.6-1.1-5.3-.9-8.1.4-4.7.8-9 2.2-11.3 8.4-13.3 28.8-17.6 29-17.6l12.3-2.4-8.1-9.5c-.1-.2-17.3-17.5-46.3-17.5-7.9 0-16 1.3-24.1 3.9-24.2 7.8-42.9 30.5-49.4 39.3-3.1-1-6.3-1.9-9.6-2.7-4.2-15.8 9-38.5 9-38.5s-13.6-3-33.7 15.2c-2.6-6.5-8.1-20.5-1.8-37.2C184.6 10.1 177.2 26 175 40.4c-7.6-5.4-6.7-23.1-7.2-27.6-7.5.9-29.2 21.9-28.2 48.3-2 .5-3.9 1.1-5.9 1.7-6.5-8.8-25.1-31.5-49.4-39.3-7.9-2.2-16-3.5-23.9-3.5-29 0-46.1 17.3-46.3 17.5L6 46.9l12.3 2.4c.2 0 20.6 4.3 29 17.6 1.4 2.2 1.8 6.6 2.2 11.3.2 2.8-.4 5.5-.9 8.1-.4 1.9-.8 3.9-.9 5.9-7.7.3-14.2 1.8-19.5 4.5-7.2 3.7-12.1 9.6-14.1 17-5 18.2 11.2 38.5 11.8 39.2 1.9 3.4 2.7 27.8-1.7 37.6-.6 1.4-2.2 2.7-4.3 4.4-.7.5-1.4 1.1-2.2 1.7-6.1 4.6-15.4 11.7-15.4 27.8 0 22.1 22.4 34.1 40.4 43.7 3 1.6 5.8 3.1 8.3 4.6 2.7 1.6 12.2 11.4 12.2 26.1 0 6.9-.6 39.7-3.7 62.4-11.6-9.9-22.2-25.9-24.6-43.8 0 0-29.2 22.6-20.6 70.8 5.2 29.5 23.2 46.1 47 54.7 8.8 19.1 29.4 45.7 67.3 49.6C143 504.3 163 512 192.2 512h.2c29.1 0 49.1-7.7 63.6-19.5 37.9-3.9 58.5-30.5 67.3-49.6 23.8-8.7 41.7-25.2 47-54.7 8.2-48.4-21.1-70.9-21.1-70.9zM305.7 37.7c5.6-1.8 11.6-2.7 17.7-2.7 11 0 19.9 3 24.7 5-3.1 1.4-6.4 3.2-9.7 5.3-2.4-.4-5.6-.8-9.2-.8-10.5 0-20.5 3.1-28.7 8.9-12.3 8.7-18 16.9-20.7 22.4-2.2-1.3-4.5-2.5-7.1-3.7-1.6-.8-3.1-1.5-4.7-2.2 6.1-9.1 19.9-26.5 37.7-32.2zm21 18.2c-.8 1-1.6 2.1-2.3 3.2-3.3 5.2-3.9 11.6-4.4 17.8-.5 6.4-1.1 12.5-4.4 17-4.2.8-8.1 1.7-11.5 2.7-2.3-3.1-5.6-7-10.5-11.2 1.4-4.8 5.5-16.1 13.5-22.5 5.6-4.3 12.2-6.7 19.6-7zM45.6 45.3c-3.3-2.2-6.6-4-9.7-5.3 4.8-2 13.7-5 24.7-5 6.1 0 12 .9 17.7 2.7 17.8 5.8 31.6 23.2 37.7 32.1-1.6.7-3.2 1.4-4.8 2.2-2.5 1.2-4.9 2.5-7.1 3.7-2.6-5.4-8.3-13.7-20.7-22.4-8.3-5.8-18.2-8.9-28.8-8.9-3.4.1-6.6.5-9 .9zm44.7 40.1c-4.9 4.2-8.3 8-10.5 11.2-3.4-.9-7.3-1.9-11.5-2.7C65 89.5 64.5 83.4 64 77c-.5-6.2-1.1-12.6-4.4-17.8-.7-1.1-1.5-2.2-2.3-3.2 7.4.3 14 2.6 19.5 7 8 6.3 12.1 17.6 13.5 22.4zM58.1 259.9c-2.7-1.6-5.6-3.1-8.4-4.6-14.9-8-30.2-16.3-30.2-30.5 0-11.1 4.3-14.6 8.9-18.2l.5-.4c.7-.6 1.4-1.2 2.2-1.8-.9 7.2-1.9 13.3-2.7 14.9 0 0 12.1-15 15.7-44.3 1.4-11.5-1.1-34.3-5.1-43 .2 4.9 0 9.8-.3 14.4-.4-.8-.8-1.6-1.3-2.2-3.2-4-11.8-17.5-9.4-26.6.9-3.5 3.1-6 6.7-7.8 3.8-1.9 8.8-2.9 15.1-2.9 12.3 0 25.9 3.7 32.9 6 25.1 8 55.4 30.9 64.1 37.7.2.2.4.3.4.3l5.6 3.9-3.5-5.8c-.2-.3-19.1-31.4-53.2-46.5 2-2.9 7.4-8.1 21.6-15.1 21.4-10.5 46.5-15.8 74.3-15.8 27.9 0 52.9 5.3 74.3 15.8 14.2 6.9 19.6 12.2 21.6 15.1-34 15.1-52.9 46.2-53.1 46.5l-3.5 5.8 5.6-3.9s.2-.1.4-.3c8.7-6.8 39-29.8 64.1-37.7 7-2.2 20.6-6 32.9-6 6.3 0 11.3 1 15.1 2.9 3.5 1.8 5.7 4.4 6.7 7.8 2.5 9.1-6.1 22.6-9.4 26.6-.5.6-.9 1.3-1.3 2.2-.3-4.6-.5-9.5-.3-14.4-4 8.8-6.5 31.5-5.1 43 3.6 29.3 15.7 44.3 15.7 44.3-.8-1.6-1.8-7.7-2.7-14.9.7.6 1.5 1.2 2.2 1.8l.5.4c4.6 3.7 8.9 7.1 8.9 18.2 0 14.2-15.4 22.5-30.2 30.5-2.9 1.5-5.7 3.1-8.4 4.6-8.7 5-18 16.7-19.1 34.2-.9 14.6.9 49.9 3.4 75.9-12.4 4.8-26.7 6.4-39.7 6.8-2-4.1-3.9-8.5-5.5-13.1-.7-2-19.6-51.1-26.4-62.2 5.5 39 17.5 73.7 23.5 89.6-3.5-.5-7.3-.7-11.7-.7h-117c-4.4 0-8.3.3-11.7.7 6-15.9 18.1-50.6 23.5-89.6-6.8 11.2-25.7 60.3-26.4 62.2-1.6 4.6-3.5 9-5.5 13.1-13-.4-27.2-2-39.7-6.8 2.5-26 4.3-61.2 3.4-75.9-.9-17.4-10.3-29.2-19-34.2zM34.8 404.6c-12.1-20-8.7-54.1-3.7-59.1 10.9 34.4 47.2 44.3 74.4 45.4-2.7 4.2-5.2 7.6-7 10l-1.4 1.4c-7.2 7.8-8.6 18.5-4.1 31.8-22.7-.1-46.3-9.8-58.2-29.5zm45.7 43.5c6 1.1 12.2 1.9 18.6 2.4 3.5 8 7.4 15.9 12.3 23.1-14.4-5.9-24.4-16-30.9-25.5zM192 498.2c-60.6-.1-78.3-45.8-84.9-64.7-3.7-10.5-3.4-18.2.9-23.1 2.9-3.3 9.5-7.2 24.6-7.2h118.8c15.1 0 21.8 3.9 24.6 7.2 4.2 4.8 4.5 12.6.9 23.1-6.6 18.8-24.3 64.6-84.9 64.7zm80.6-24.6c4.9-7.2 8.8-15.1 12.3-23.1 6.4-.5 12.6-1.3 18.6-2.4-6.5 9.5-16.5 19.6-30.9 25.5zm76.6-69c-12 19.7-35.6 29.3-58.1 29.7 4.5-13.3 3.1-24.1-4.1-31.8-.4-.5-.9-1-1.4-1.5-1.8-2.4-4.3-5.8-7-10 27.2-1.2 63.5-11 74.4-45.4 5 5 8.4 39.1-3.8 59zM191.9 187.7h.2c12.7-.1 27.2-17.8 27.2-17.8-9.9 6-18.8 8.1-27.3 8.3-8.5-.2-17.4-2.3-27.3-8.3 0 0 14.5 17.6 27.2 17.8zm61.7 230.7h-29.4c-4.2 0-7.2.9-8.9 2.7-2.2 2.3-1.5 5.2-.9 6.7 1 2.6 5.5 11.3 13 19.3 2.7 2.9 6.6 4.5 11 4.5s8.7-1.6 11.8-4.2c2.3-2 10.2-9.2 13.7-18.1 1.3-3.3 1-6-.9-7.9-1.3-1.3-4-2.9-9.4-3z\"],\n    \"gulp\": [256, 512, [], \"f3ae\", \"M209.8 391.1l-14.1 24.6-4.6 80.2c0 8.9-28.3 16.1-63.1 16.1s-63.1-7.2-63.1-16.1l-5.8-79.4-14.9-25.4c41.2 17.3 126 16.7 165.6 0zm-196-253.3l13.6 125.5c5.9-20 20.8-47 40-55.2 6.3-2.7 12.7-2.7 18.7.9 5.2 3 9.6 9.3 10.1 11.8 1.2 6.5-2 9.1-4.5 9.1-3 0-5.3-4.6-6.8-7.3-4.1-7.3-10.3-7.6-16.9-2.8-6.9 5-12.9 13.4-17.1 20.7-5.1 8.8-9.4 18.5-12 28.2-1.5 5.6-2.9 14.6-.6 19.9 1 2.2 2.5 3.6 4.9 3.6 5 0 12.3-6.6 15.8-10.1 4.5-4.5 10.3-11.5 12.5-16l5.2-15.5c2.6-6.8 9.9-5.6 9.9 0 0 10.2-3.7 13.6-10 34.7-5.8 19.5-7.6 25.8-7.6 25.8-.7 2.8-3.4 7.5-6.3 7.5-1.2 0-2.1-.4-2.6-1.2-1-1.4-.9-5.3-.8-6.3.2-3.2 6.3-22.2 7.3-25.2-2 2.2-4.1 4.4-6.4 6.6-5.4 5.1-14.1 11.8-21.5 11.8-3.4 0-5.6-.9-7.7-2.4l7.6 79.6c2 5 39.2 17.1 88.2 17.1 49.1 0 86.3-12.2 88.2-17.1l10.9-94.6c-5.7 5.2-12.3 11.6-19.6 14.8-5.4 2.3-17.4 3.8-17.4-5.7 0-5.2 9.1-14.8 14.4-21.5 1.4-1.7 4.7-5.9 4.7-8.1 0-2.9-6-2.2-11.7 2.5-3.2 2.7-6.2 6.3-8.7 9.7-4.3 6-6.6 11.2-8.5 15.5-6.2 14.2-4.1 8.6-9.1 22-5 13.3-4.2 11.8-5.2 14-.9 1.9-2.2 3.5-4 4.5-1.9 1-4.5.9-6.1-.3-.9-.6-1.3-1.9-1.3-3.7 0-.9.1-1.8.3-2.7 1.5-6.1 7.8-18.1 15-34.3 1.6-3.7 1-2.6.8-2.3-6.2 6-10.9 8.9-14.4 10.5-5.8 2.6-13 2.6-14.5-4.1-.1-.4-.1-.8-.2-1.2-11.8 9.2-24.3 11.7-20-8.1-4.6 8.2-12.6 14.9-22.4 14.9-4.1 0-7.1-1.4-8.6-5.1-2.3-5.5 1.3-14.9 4.6-23.8 1.7-4.5 4-9.9 7.1-16.2 1.6-3.4 4.2-5.4 7.6-4.5.6.2 1.1.4 1.6.7 2.6 1.8 1.6 4.5.3 7.2-3.8 7.5-7.1 13-9.3 20.8-.9 3.3-2 9 1.5 9 2.4 0 4.7-.8 6.9-2.4 4.6-3.4 8.3-8.5 11.1-13.5 2-3.6 4.4-8.3 5.6-12.3.5-1.7 1.1-3.3 1.8-4.8 1.1-2.5 2.6-5.1 5.2-5.1 1.3 0 2.4.5 3.2 1.5 1.7 2.2 1.3 4.5.4 6.9-2 5.6-4.7 10.6-6.9 16.7-1.3 3.5-2.7 8-2.7 11.7 0 3.4 3.7 2.6 6.8 1.2 2.4-1.1 4.8-2.8 6.8-4.5 1.2-4.9.9-3.8 26.4-68.2 1.3-3.3 3.7-4.7 6.1-4.7 1.2 0 2.2.4 3.2 1.1 1.7 1.3 1.7 4.1 1 6.2-.7 1.9-.6 1.3-4.5 10.5-5.2 12.1-8.6 20.8-13.2 31.9-1.9 4.6-7.7 18.9-8.7 22.3-.6 2.2-1.3 5.8 1 5.8 5.4 0 19.3-13.1 23.1-17 .2-.3.5-.4.9-.6.6-1.9 1.2-3.7 1.7-5.5 1.4-3.8 2.7-8.2 5.3-11.3.8-1 1.7-1.6 2.7-1.6 2.8 0 4.2 1.2 4.2 4 0 1.1-.7 5.1-1.1 6.2 1.4-1.5 2.9-3 4.5-4.5 15-13.9 25.7-6.8 25.7.2 0 7.4-8.9 17.7-13.8 23.4-1.6 1.9-4.9 5.4-5 6.4 0 1.3.9 1.8 2.2 1.8 2 0 6.4-3.5 8-4.7 5-3.9 11.8-9.9 16.6-14.1l14.8-136.8c-30.5 17.1-197.6 17.2-228.3.2zm229.7-8.5c0 21-231.2 21-231.2 0 0-8.8 51.8-15.9 115.6-15.9 9 0 17.8.1 26.3.4l12.6-48.7L228.1.6c1.4-1.4 5.8-.2 9.9 3.5s6.6 7.9 5.3 9.3l-.1.1L185.9 74l-10 40.7c39.9 2.6 67.6 8.1 67.6 14.6zm-69.4 4.6c0-.8-.9-1.5-2.5-2.1l-.2.8c0 1.3-5 2.4-11.1 2.4s-11.1-1.1-11.1-2.4c0-.1 0-.2.1-.3l.2-.7c-1.8.6-3 1.4-3 2.3 0 2.1 6.2 3.7 13.7 3.7 7.7.1 13.9-1.6 13.9-3.7z\"],\n    \"hacker-news\": [448, 512, [], \"f1d4\", \"M0 32v448h448V32H0zm21.2 197.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hacker-news-square\": [448, 512, [], \"f3af\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.2 229.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hackerrank\": [512, 512, [], \"f5f7\", \"M477.5 128C463 103.05 285.13 0 256.16 0S49.25 102.79 34.84 128s-14.49 230.8 0 256 192.38 128 221.32 128S463 409.08 477.49 384s14.51-231 .01-256zM316.13 414.22c-4 0-40.91-35.77-38-38.69.87-.87 6.26-1.48 17.55-1.83 0-26.23.59-68.59.94-86.32 0-2-.44-3.43-.44-5.85h-79.93c0 7.1-.46 36.2 1.37 72.88.23 4.54-1.58 6-5.74 5.94-10.13 0-20.27-.11-30.41-.08-4.1 0-5.87-1.53-5.74-6.11.92-33.44 3-84-.15-212.67v-3.17c-9.67-.35-16.38-1-17.26-1.84-2.92-2.92 34.54-38.69 38.49-38.69s41.17 35.78 38.27 38.69c-.87.87-7.9 1.49-16.77 1.84v3.16c-2.42 25.75-2 79.59-2.63 105.39h80.26c0-4.55.39-34.74-1.2-83.64-.1-3.39.95-5.17 4.21-5.2 11.07-.08 22.15-.13 33.23-.06 3.46 0 4.57 1.72 4.5 5.38C333 354.64 336 341.29 336 373.69c8.87.35 16.82 1 17.69 1.84 2.88 2.91-33.62 38.69-37.58 38.69z\"],\n    \"hips\": [640, 512, [], \"f452\", \"M251.6 157.6c0-1.9-.9-2.8-2.8-2.8h-40.9c-1.6 0-2.7 1.4-2.7 2.8v201.8c0 1.4 1.1 2.8 2.7 2.8h40.9c1.9 0 2.8-.9 2.8-2.8zM156.5 168c-16.1-11.8-36.3-17.9-60.3-18-18.1-.1-34.6 3.7-49.8 11.4V80.2c0-1.8-.9-2.7-2.8-2.7H2.7c-1.8 0-2.7.9-2.7 2.7v279.2c0 1.9.9 2.8 2.7 2.8h41c1.9 0 2.8-.9 2.8-2.8V223.3c0-.8-2.8-27 45.8-27 48.5 0 45.8 26.1 45.8 27v122.6c0 9 7.3 16.3 16.4 16.3h27.3c1.8 0 2.7-.9 2.7-2.8V223.3c0-23.4-9.3-41.8-28-55.3zm478.4 110.1c-6.8-15.7-18.4-27-34.9-34.1l-57.6-25.3c-8.6-3.6-9.2-11.2-2.6-16.1 7.4-5.5 44.3-13.9 84 6.8 1.7 1 4-.3 4-2.4v-44.7c0-1.3-.6-2.1-1.9-2.6-17.7-6.6-36.1-9.9-55.1-9.9-26.5 0-45.3 5.8-58.5 15.4-.5.4-28.4 20-22.7 53.7 3.4 19.6 15.8 34.2 37.2 43.6l53.6 23.5c11.6 5.1 15.2 13.3 12.2 21.2-3.7 9.1-13.2 13.6-36.5 13.6-24.3 0-44.7-8.9-58.4-19.1-2.1-1.4-4.4.2-4.4 2.3v34.4c0 10.4 4.9 17.3 14.6 20.7 15.6 5.5 31.6 8.2 48.2 8.2 12.7 0 25.8-1.2 36.3-4.3.7-.3 36-8.9 45.6-45.8 3.5-13.5 2.4-26.5-3.1-39.1zM376.2 149.8c-31.7 0-104.2 20.1-104.2 103.5v183.5c0 .8.6 2.7 2.7 2.7h40.9c1.9 0 2.8-.9 2.8-2.7V348c16.5 12.7 35.8 19.1 57.7 19.1 60.5 0 108.7-48.5 108.7-108.7.1-60.3-48.2-108.6-108.6-108.6zm0 170.9c-17.2 0-31.9-6.1-44-18.2-12.2-12.2-18.2-26.8-18.2-44 0-34.5 27.6-62.2 62.2-62.2 34.5 0 62.2 27.6 62.2 62.2.1 34.3-27.3 62.2-62.2 62.2zM228.3 72.5c-15.9 0-28.8 12.9-28.9 28.9 0 15.6 12.7 28.9 28.9 28.9s28.9-13.1 28.9-28.9c0-16.2-13-28.9-28.9-28.9z\"],\n    \"hire-a-helper\": [512, 512, [], \"f3b0\", \"M443.1 0H71.9C67.9 37.3 37.4 67.8 0 71.7v371.5c37.4 4.9 66 32.4 71.9 68.8h372.2c3-36.4 32.5-65.8 67.9-69.8V71.7c-36.4-5.9-65-35.3-68.9-71.7zm-37 404.9c-36.3 0-18.8-2-55.1-2-35.8 0-21 2-56.1 2-5.9 0-4.9-8.2 0-9.8 22.8-7.6 22.9-10.2 24.6-12.8 10.4-15.6 5.9-83 5.9-113 0-5.3-6.4-12.8-13.8-12.8H200.4c-7.4 0-13.8 7.5-13.8 12.8 0 30-4.5 97.4 5.9 113 1.7 2.5 1.8 5.2 24.6 12.8 4.9 1.6 6 9.8 0 9.8-35.1 0-20.3-2-56.1-2-36.3 0-18.8 2-55.1 2-7.9 0-5.8-10.8 0-10.8 10.2-3.4 13.5-3.5 21.7-13.8 7.7-12.9 7.9-44.4 7.9-127.8V151.3c0-22.2-12.2-28.3-28.6-32.4-8.8-2.2-4-11.8 1-11.8 36.5 0 20.6 2 57.1 2 32.7 0 16.5-2 49.2-2 3.3 0 8.5 8.3 1 10.8-4.9 1.6-27.6 3.7-27.6 39.3 0 45.6-.2 55.8 1 68.8 0 1.3 2.3 12.8 12.8 12.8h109.2c10.5 0 12.8-11.5 12.8-12.8 1.2-13 1-23.2 1-68.8 0-35.6-22.7-37.7-27.6-39.3-7.5-2.5-2.3-10.8 1-10.8 32.7 0 16.5 2 49.2 2 36.5 0 20.6-2 57.1-2 4.9 0 9.9 9.6 1 11.8-16.4 4.1-28.6 10.3-28.6 32.4v101.2c0 83.4.1 114.9 7.9 127.8 8.2 10.2 11.4 10.4 21.7 13.8 5.8 0 7.8 10.8 0 10.8z\"],\n    \"hooli\": [640, 512, [], \"f427\", \"M144.5 352l38.3.8c-13.2-4.6-26-10.2-38.3-16.8zm57.7-5.3v5.3l-19.4.8c36.5 12.5 69.9 14.2 94.7 7.2-19.9.2-45.8-2.6-75.3-13.3zm408.9-115.2c15.9 0 28.9-12.9 28.9-28.9s-12.9-24.5-28.9-24.5c-15.9 0-28.9 8.6-28.9 24.5s12.9 28.9 28.9 28.9zm-29 120.5H640V241.5h-57.9zm-73.7 0h57.9V156.7L508.4 184zm-31-119.4c-18.2-18.2-50.4-17.1-50.4-17.1s-32.3-1.1-50.4 17.1c-18.2 18.2-16.8 33.9-16.8 52.6s-1.4 34.3 16.8 52.5 50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.8-33.8 16.8-52.5-.1-18.8 1.3-34.5-16.8-52.6zm-39.8 71.9c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9zm-106.2-71.9c-18.2-18.2-50.4-17.1-50.4-17.1s-32.2-1.1-50.4 17.1c-1.9 1.9-3.7 3.9-5.3 6-38.2-29.6-72.5-46.5-102.1-61.1v-20.7l-22.5 10.6c-54.4-22.1-89-18.2-97.3.1 0 0-24.9 32.8 61.8 110.8V352h57.9v-28.6c-6.5-4.2-13-8.7-19.4-13.6-14.8-11.2-27.4-21.6-38.4-31.4v-31c13.1 14.7 30.5 31.4 53.4 50.3l4.5 3.6v-29.8c0-6.9 1.7-18.2 10.8-18.2s10.6 6.9 10.6 15V317c18 12.2 37.3 22.1 57.7 29.6v-93.9c0-18.7-13.4-37.4-40.6-37.4-15.8-.1-30.5 8.2-38.5 21.9v-54.3c41.9 20.9 83.9 46.5 99.9 58.3-10.2 14.6-9.3 28.1-9.3 43.7 0 18.7-1.4 34.3 16.8 52.5s50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.7-33.8 16.7-52.5 0-18.5 1.5-34.2-16.7-52.3zM65.2 184v63.3c-48.7-54.5-38.9-76-35.2-79.1 13.5-11.4 37.5-8 64.4 2.1zm226.5 120.5c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9z\"],\n    \"hornbill\": [512, 512, [], \"f592\", \"M76.38 370.3a37.8 37.8 0 1 1-32.07-32.42c-78.28-111.35 52-190.53 52-190.53-5.86 43-8.24 91.16-8.24 91.16-67.31 41.49.93 64.06 39.81 72.87a140.38 140.38 0 0 0 131.66 91.94c1.92 0 3.77-.21 5.67-.28l.11 18.86c-99.22 1.39-158.7-29.14-188.94-51.6zm108-327.7A37.57 37.57 0 0 0 181 21.45a37.95 37.95 0 1 0-31.17 54.22c-22.55 29.91-53.83 89.57-52.42 190l21.84-.15c0-.9-.14-1.77-.14-2.68A140.42 140.42 0 0 1 207 132.71c8-37.71 30.7-114.3 73.8-44.29 0 0 48.14 2.38 91.18 8.24 0 0-77.84-128-187.59-54.06zm304.19 134.17a37.94 37.94 0 1 0-53.84-28.7C403 126.13 344.89 99 251.28 100.33l.14 22.5c2.7-.15 5.39-.41 8.14-.41a140.37 140.37 0 0 1 130.49 88.76c39.1 9 105.06 31.58 38.46 72.54 0 0-2.34 48.13-8.21 91.16 0 0 133.45-81.16 49-194.61a37.45 37.45 0 0 0 19.31-3.5zM374.06 436.24c21.43-32.46 46.42-89.69 45.14-179.66l-19.52.14c.08 2.06.3 4.07.3 6.15a140.34 140.34 0 0 1-91.39 131.45c-8.85 38.95-31.44 106.66-72.77 39.49 0 0-48.12-2.34-91.19-8.22 0 0 79.92 131.34 191.9 51a37.5 37.5 0 0 0 3.64 14 37.93 37.93 0 1 0 33.89-54.29z\"],\n    \"hotjar\": [448, 512, [], \"f3b1\", \"M414.9 161.5C340.2 29 121.1 0 121.1 0S222.2 110.4 93 197.7C11.3 252.8-21 324.4 14 402.6c26.8 59.9 83.5 84.3 144.6 93.4-29.2-55.1-6.6-122.4-4.1-129.6 57.1 86.4 165 0 110.8-93.9 71 15.4 81.6 138.6 27.1 215.5 80.5-25.3 134.1-88.9 148.8-145.6 15.5-59.3 3.7-127.9-26.3-180.9z\"],\n    \"houzz\": [448, 512, [], \"f27c\", \"M275.9 330.7H171.3V480H17V32h109.5v104.5l305.1 85.6V480H275.9z\"],\n    \"html5\": [384, 512, [], \"f13b\", \"M0 32l34.9 395.8L191.5 480l157.6-52.2L384 32H0zm308.2 127.9H124.4l4.1 49.4h175.6l-13.6 148.4-97.9 27v.3h-1.1l-98.7-27.3-6-75.8h47.7L138 320l53.5 14.5 53.7-14.5 6-62.2H84.3L71.5 112.2h241.1l-4.4 47.7z\"],\n    \"hubspot\": [512, 512, [], \"f3b2\", \"M267.4 211.6c-25.1 23.7-40.8 57.3-40.8 94.6 0 29.3 9.7 56.3 26 78L203.1 434c-4.4-1.6-9.1-2.5-14-2.5-10.8 0-20.9 4.2-28.5 11.8-7.6 7.6-11.8 17.8-11.8 28.6s4.2 20.9 11.8 28.5c7.6 7.6 17.8 11.6 28.5 11.6 10.8 0 20.9-3.9 28.6-11.6 7.6-7.6 11.8-17.8 11.8-28.5 0-4.2-.6-8.2-1.9-12.1l50-50.2c22 16.9 49.4 26.9 79.3 26.9 71.9 0 130-58.3 130-130.2 0-65.2-47.7-119.2-110.2-128.7V116c17.5-7.4 28.2-23.8 28.2-42.9 0-26.1-20.9-47.9-47-47.9S311.2 47 311.2 73.1c0 19.1 10.7 35.5 28.2 42.9v61.2c-15.2 2.1-29.6 6.7-42.7 13.6-27.6-20.9-117.5-85.7-168.9-124.8 1.2-4.4 2-9 2-13.8C129.8 23.4 106.3 0 77.4 0 48.6 0 25.2 23.4 25.2 52.2c0 28.9 23.4 52.3 52.2 52.3 9.8 0 18.9-2.9 26.8-7.6l163.2 114.7zm89.5 163.6c-38.1 0-69-30.9-69-69s30.9-69 69-69 69 30.9 69 69-30.9 69-69 69z\"],\n    \"imdb\": [448, 512, [], \"f2d8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.3 229.2H21c.1-.1.2-.3.3-.4zM97 319.8H64V192h33zm113.2 0h-28.7v-86.4l-11.6 86.4h-20.6l-12.2-84.5v84.5h-29V192h42.8c3.3 19.8 6 39.9 8.7 59.9l7.6-59.9h43zm11.4 0V192h24.6c17.6 0 44.7-1.6 49 20.9 1.7 7.6 1.4 16.3 1.4 24.4 0 88.5 11.1 82.6-75 82.5zm160.9-29.2c0 15.7-2.4 30.9-22.2 30.9-9 0-15.2-3-20.9-9.8l-1.9 8.1h-29.8V192h31.7v41.7c6-6.5 12-9.2 20.9-9.2 21.4 0 22.2 12.8 22.2 30.1zM265 229.9c0-9.7 1.6-16-10.3-16v83.7c12.2.3 10.3-8.7 10.3-18.4zm85.5 26.1c0-5.4 1.1-12.7-6.2-12.7-6 0-4.9 8.9-4.9 12.7 0 .6-1.1 39.6 1.1 44.7.8 1.6 2.2 2.4 3.8 2.4 7.8 0 6.2-9 6.2-14.4z\"],\n    \"instagram\": [448, 512, [], \"f16d\", \"M224.1 141c-63.6 0-114.9 51.3-114.9 114.9s51.3 114.9 114.9 114.9S339 319.5 339 255.9 287.7 141 224.1 141zm0 189.6c-41.1 0-74.7-33.5-74.7-74.7s33.5-74.7 74.7-74.7 74.7 33.5 74.7 74.7-33.6 74.7-74.7 74.7zm146.4-194.3c0 14.9-12 26.8-26.8 26.8-14.9 0-26.8-12-26.8-26.8s12-26.8 26.8-26.8 26.8 12 26.8 26.8zm76.1 27.2c-1.7-35.9-9.9-67.7-36.2-93.9-26.2-26.2-58-34.4-93.9-36.2-37-2.1-147.9-2.1-184.9 0-35.8 1.7-67.6 9.9-93.9 36.1s-34.4 58-36.2 93.9c-2.1 37-2.1 147.9 0 184.9 1.7 35.9 9.9 67.7 36.2 93.9s58 34.4 93.9 36.2c37 2.1 147.9 2.1 184.9 0 35.9-1.7 67.7-9.9 93.9-36.2 26.2-26.2 34.4-58 36.2-93.9 2.1-37 2.1-147.8 0-184.8zM398.8 388c-7.8 19.6-22.9 34.7-42.6 42.6-29.5 11.7-99.5 9-132.1 9s-102.7 2.6-132.1-9c-19.6-7.8-34.7-22.9-42.6-42.6-11.7-29.5-9-99.5-9-132.1s-2.6-102.7 9-132.1c7.8-19.6 22.9-34.7 42.6-42.6 29.5-11.7 99.5-9 132.1-9s102.7-2.6 132.1 9c19.6 7.8 34.7 22.9 42.6 42.6 11.7 29.5 9 99.5 9 132.1s2.7 102.7-9 132.1z\"],\n    \"intercom\": [448, 512, [], \"f7af\", \"M392 32H56C25.1 32 0 57.1 0 88v336c0 30.9 25.1 56 56 56h336c30.9 0 56-25.1 56-56V88c0-30.9-25.1-56-56-56zm-108.3 82.1c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zm-74.6-7.5c0-19.8 29.9-19.8 29.9 0v216.5c0 19.8-29.9 19.8-29.9 0V106.6zm-74.7 7.5c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zM59.7 144c0-19.8 29.9-19.8 29.9 0v134.3c0 19.8-29.9 19.8-29.9 0V144zm323.4 227.8c-72.8 63-241.7 65.4-318.1 0-15-12.8 4.4-35.5 19.4-22.7 65.9 55.3 216.1 53.9 279.3 0 14.9-12.9 34.3 9.8 19.4 22.7zm5.2-93.5c0 19.8-29.9 19.8-29.9 0V144c0-19.8 29.9-19.8 29.9 0v134.3z\"],\n    \"internet-explorer\": [512, 512, [], \"f26b\", \"M483.049 159.706c10.855-24.575 21.424-60.438 21.424-87.871 0-72.722-79.641-98.371-209.673-38.577-107.632-7.181-211.221 73.67-237.098 186.457 30.852-34.862 78.271-82.298 121.977-101.158C125.404 166.85 79.128 228.002 43.992 291.725 23.246 329.651 0 390.94 0 436.747c0 98.575 92.854 86.5 180.251 42.006 31.423 15.43 66.559 15.573 101.695 15.573 97.124 0 184.249-54.294 216.814-146.022H377.927c-52.509 88.593-196.819 52.996-196.819-47.436H509.9c6.407-43.581-1.655-95.715-26.851-141.162zM64.559 346.877c17.711 51.15 53.703 95.871 100.266 123.304-88.741 48.94-173.267 29.096-100.266-123.304zm115.977-108.873c2-55.151 50.276-94.871 103.98-94.871 53.418 0 101.981 39.72 103.981 94.871H180.536zm184.536-187.6c21.425-10.287 48.563-22.003 72.558-22.003 31.422 0 54.274 21.717 54.274 53.722 0 20.003-7.427 49.007-14.569 67.867-26.28-42.292-65.986-81.584-112.263-99.586z\"],\n    \"invision\": [448, 512, [], \"f7b0\", \"M407.4 32H40.6C18.2 32 0 50.2 0 72.6v366.8C0 461.8 18.2 480 40.6 480h366.8c22.4 0 40.6-18.2 40.6-40.6V72.6c0-22.4-18.2-40.6-40.6-40.6zM176.1 145.6c.4 23.4-22.4 27.3-26.6 27.4-14.9 0-27.1-12-27.1-27 .1-35.2 53.1-35.5 53.7-.4zM332.8 377c-65.6 0-34.1-74-25-106.6 14.1-46.4-45.2-59-59.9.7l-25.8 103.3H177l8.1-32.5c-31.5 51.8-94.6 44.4-94.6-4.3.1-14.3.9-14 23-104.1H81.7l9.7-35.6h76.4c-33.6 133.7-32.6 126.9-32.9 138.2 0 20.9 40.9 13.5 57.4-23.2l19.8-79.4h-32.3l9.7-35.6h68.8l-8.9 40.5c40.5-75.5 127.9-47.8 101.8 38-14.2 51.1-14.6 50.7-14.9 58.8 0 15.5 17.5 22.6 31.8-16.9L386 325c-10.5 36.7-29.4 52-53.2 52z\"],\n    \"ioxhost\": [640, 512, [], \"f208\", \"M616 160h-67.3C511.2 70.7 422.9 8 320 8 183 8 72 119 72 256c0 16.4 1.6 32.5 4.7 48H24c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h67.3c37.5 89.3 125.8 152 228.7 152 137 0 248-111 248-248 0-16.4-1.6-32.5-4.7-48H616c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24zm-96 96c0 110.5-89.5 200-200 200-75.7 0-141.6-42-175.5-104H424c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24H125.8c-3.8-15.4-5.8-31.4-5.8-48 0-110.5 89.5-200 200-200 75.7 0 141.6 42 175.5 104H216c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h298.2c3.8 15.4 5.8 31.4 5.8 48zm-304-24h208c13.3 0 24 10.7 24 24 0 13.2-10.7 24-24 24H216c-13.3 0-24-10.7-24-24 0-13.2 10.7-24 24-24z\"],\n    \"itch-io\": [512, 512, [], \"f83a\", \"M71.92 34.77C50.2 47.67 7.4 96.84 7 109.73v21.34c0 27.06 25.29 50.84 48.25 50.84 27.57 0 50.54-22.85 50.54-50 0 27.12 22.18 50 49.76 50s49-22.85 49-50c0 27.12 23.59 50 51.16 50h.5c27.57 0 51.16-22.85 51.16-50 0 27.12 21.47 50 49 50s49.76-22.85 49.76-50c0 27.12 23 50 50.54 50 23 0 48.25-23.78 48.25-50.84v-21.34c-.4-12.9-43.2-62.07-64.92-75C372.56 32.4 325.76 32 256 32S91.14 33.1 71.92 34.77zm132.32 134.39c-22 38.4-77.9 38.71-99.85.25-13.17 23.14-43.17 32.07-56 27.66-3.87 40.15-13.67 237.13 17.73 269.15 80 18.67 302.08 18.12 379.76 0 31.65-32.27 21.32-232 17.75-269.15-12.92 4.44-42.88-4.6-56-27.66-22 38.52-77.85 38.1-99.85-.24-7.1 12.49-23.05 28.94-51.76 28.94a57.54 57.54 0 0 1-51.75-28.94zm-41.58 53.77c16.47 0 31.09 0 49.22 19.78a436.91 436.91 0 0 1 88.18 0C318.22 223 332.85 223 349.31 223c52.33 0 65.22 77.53 83.87 144.45 17.26 62.15-5.52 63.67-33.95 63.73-42.15-1.57-65.49-32.18-65.49-62.79-39.25 6.43-101.93 8.79-155.55 0 0 30.61-23.34 61.22-65.49 62.79-28.42-.06-51.2-1.58-33.94-63.73 18.67-67 31.56-144.45 83.88-144.45zM256 270.79s-44.38 40.77-52.35 55.21l29-1.17v25.32c0 1.55 21.34.16 23.33.16 11.65.54 23.31 1 23.31-.16v-25.28l29 1.17c-8-14.48-52.35-55.24-52.35-55.24z\"],\n    \"itunes\": [448, 512, [], \"f3b4\", \"M223.6 80.3C129 80.3 52.5 157 52.5 251.5S129 422.8 223.6 422.8s171.2-76.7 171.2-171.2c0-94.6-76.7-171.3-171.2-171.3zm79.4 240c-3.2 13.6-13.5 21.2-27.3 23.8-12.1 2.2-22.2 2.8-31.9-5-11.8-10-12-26.4-1.4-36.8 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 3.2-3.6 2.2-2 2.2-80.8 0-5.6-2.7-7.1-8.4-6.1-4 .7-91.9 17.1-91.9 17.1-5 1.1-6.7 2.6-6.7 8.3 0 116.1.5 110.8-1.2 118.5-2.1 9-7.6 15.8-14.9 19.6-8.3 4.6-23.4 6.6-31.4 5.2-21.4-4-28.9-28.7-14.4-42.9 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 5-5.7.9-127 2.6-133.7.4-2.6 1.5-4.8 3.5-6.4 2.1-1.7 5.8-2.7 6.7-2.7 101-19 113.3-21.4 115.1-21.4 5.7-.4 9 3 9 8.7-.1 170.6.4 161.4-1 167.6zM345.2 32H102.8C45.9 32 0 77.9 0 134.8v242.4C0 434.1 45.9 480 102.8 480h242.4c57 0 102.8-45.9 102.8-102.8V134.8C448 77.9 402.1 32 345.2 32zM223.6 444c-106.3 0-192.5-86.2-192.5-192.5S117.3 59 223.6 59s192.5 86.2 192.5 192.5S329.9 444 223.6 444z\"],\n    \"itunes-note\": [384, 512, [], \"f3b5\", \"M381.9 388.2c-6.4 27.4-27.2 42.8-55.1 48-24.5 4.5-44.9 5.6-64.5-10.2-23.9-20.1-24.2-53.4-2.7-74.4 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 6.4-7.2 4.4-4.1 4.4-163.2 0-11.2-5.5-14.3-17-12.3-8.2 1.4-185.7 34.6-185.7 34.6-10.2 2.2-13.4 5.2-13.4 16.7 0 234.7 1.1 223.9-2.5 239.5-4.2 18.2-15.4 31.9-30.2 39.5-16.8 9.3-47.2 13.4-63.4 10.4-43.2-8.1-58.4-58-29.1-86.6 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 10.1-11.5 1.8-256.6 5.2-270.2.8-5.2 3-9.6 7.1-12.9 4.2-3.5 11.8-5.5 13.4-5.5 204-38.2 228.9-43.1 232.4-43.1 11.5-.8 18.1 6 18.1 17.6.2 344.5 1.1 326-1.8 338.5z\"],\n    \"java\": [384, 512, [], \"f4e4\", \"M277.74 312.9c9.8-6.7 23.4-12.5 23.4-12.5s-38.7 7-77.2 10.2c-47.1 3.9-97.7 4.7-123.1 1.3-60.1-8 33-30.1 33-30.1s-36.1-2.4-80.6 19c-52.5 25.4 130 37 224.5 12.1zm-85.4-32.1c-19-42.7-83.1-80.2 0-145.8C296 53.2 242.84 0 242.84 0c21.5 84.5-75.6 110.1-110.7 162.6-23.9 35.9 11.7 74.4 60.2 118.2zm114.6-176.2c.1 0-175.2 43.8-91.5 140.2 24.7 28.4-6.5 54-6.5 54s62.7-32.4 33.9-72.9c-26.9-37.8-47.5-56.6 64.1-121.3zm-6.1 270.5a12.19 12.19 0 0 1-2 2.6c128.3-33.7 81.1-118.9 19.8-97.3a17.33 17.33 0 0 0-8.2 6.3 70.45 70.45 0 0 1 11-3c31-6.5 75.5 41.5-20.6 91.4zM348 437.4s14.5 11.9-15.9 21.2c-57.9 17.5-240.8 22.8-291.6.7-18.3-7.9 16-19 26.8-21.3 11.2-2.4 17.7-2 17.7-2-20.3-14.3-131.3 28.1-56.4 40.2C232.84 509.4 401 461.3 348 437.4zM124.44 396c-78.7 22 47.9 67.4 148.1 24.5a185.89 185.89 0 0 1-28.2-13.8c-44.7 8.5-65.4 9.1-106 4.5-33.5-3.8-13.9-15.2-13.9-15.2zm179.8 97.2c-78.7 14.8-175.8 13.1-233.3 3.6 0-.1 11.8 9.7 72.4 13.6 92.2 5.9 233.8-3.3 237.1-46.9 0 0-6.4 16.5-76.2 29.7zM260.64 353c-59.2 11.4-93.5 11.1-136.8 6.6-33.5-3.5-11.6-19.7-11.6-19.7-86.8 28.8 48.2 61.4 169.5 25.9a60.37 60.37 0 0 1-21.1-12.8z\"],\n    \"jedi-order\": [448, 512, [], \"f50e\", \"M398.5 373.6c95.9-122.1 17.2-233.1 17.2-233.1 45.4 85.8-41.4 170.5-41.4 170.5 105-171.5-60.5-271.5-60.5-271.5 96.9 72.7-10.1 190.7-10.1 190.7 85.8 158.4-68.6 230.1-68.6 230.1s-.4-16.9-2.2-85.7c4.3 4.5 34.5 36.2 34.5 36.2l-24.2-47.4 62.6-9.1-62.6-9.1 20.2-55.5-31.4 45.9c-2.2-87.7-7.8-305.1-7.9-306.9v-2.4 1-1 2.4c0 1-5.6 219-7.9 306.9l-31.4-45.9 20.2 55.5-62.6 9.1 62.6 9.1-24.2 47.4 34.5-36.2c-1.8 68.8-2.2 85.7-2.2 85.7s-154.4-71.7-68.6-230.1c0 0-107-118.1-10.1-190.7 0 0-165.5 99.9-60.5 271.5 0 0-86.8-84.8-41.4-170.5 0 0-78.7 111 17.2 233.1 0 0-26.2-16.1-49.4-77.7 0 0 16.9 183.3 222 185.7h4.1c205-2.4 222-185.7 222-185.7-23.6 61.5-49.9 77.7-49.9 77.7z\"],\n    \"jenkins\": [512, 512, [], \"f3b6\", \"M487.1 425c-1.4-11.2-19-23.1-28.2-31.9-5.1-5-29-23.1-30.4-29.9-1.4-6.6 9.7-21.5 13.3-28.9 5.1-10.7 8.8-23.7 11.3-32.6 18.8-66.1 20.7-156.9-6.2-211.2-10.2-20.6-38.6-49-56.4-62.5-42-31.7-119.6-35.3-170.1-16.6-14.1 5.2-27.8 9.8-40.1 17.1-33.1 19.4-68.3 32.5-78.1 71.6-24.2 10.8-31.5 41.8-30.3 77.8.2 7 4.1 15.8 2.7 22.4-.7 3.3-5.2 7.6-6.1 9.8-11.6 27.7-2.3 64 11.1 83.7 8.1 11.9 21.5 22.4 39.2 25.2.7 10.6 3.3 19.7 8.2 30.4 3.1 6.8 14.7 19 10.4 27.7-2.2 4.4-21 13.8-27.3 17.6C89 407.2 73.7 415 54.2 429c-12.6 9-32.3 10.2-29.2 31.1 2.1 14.1 10.1 31.6 14.7 45.8.7 2 1.4 4.1 2.1 6h422c4.9-15.3 9.7-30.9 14.6-47.2 3.4-11.4 10.2-27.8 8.7-39.7zM205.9 33.7c1.8-.5 3.4.7 4.9 2.4-.2 5.2-5.4 5.1-8.9 6.8-5.4 6.7-13.4 9.8-20 17.2-6.8 7.5-14.4 27.7-23.4 30-4.5 1.1-9.7-.8-13.6-.5-10.4.7-17.7 6-28.3 7.5 13.6-29.9 56.1-54 89.3-63.4zm-104.8 93.6c13.5-14.9 32.1-24.1 54.8-25.9 11.7 29.7-8.4 65-.9 97.6 2.3 9.9 10.2 25.4-2.4 25.7.3-28.3-34.8-46.3-61.3-29.6-1.8-21.5-4.9-51.7 9.8-67.8zm36.7 200.2c-1-4.1-2.7-12.9-2.3-15.1 1.6-8.7 17.1-12.5 11-24.7-11.3-.1-13.8 10.2-24.1 11.3-26.7 2.6-45.6-35.4-44.4-58.4 1-19.5 17.6-38.2 40.1-35.8 16 1.8 21.4 19.2 24.5 34.7 9.2.5 22.5-.4 26.9-7.6-.6-17.5-8.8-31.6-8.2-47.7 1-30.3 17.5-57.6 4.8-87.4 13.6-30.9 53.5-55.3 83.1-70 36.6-18.3 94.9-3.7 129.3 15.8 19.7 11.1 34.4 32.7 48.3 50.7-19.5-5.8-36.1 4.2-33.1 20.3 16.3-14.9 44.2-.2 52.5 16.4 7.9 15.8 7.8 39.3 9 62.8 2.9 57-10.4 115.9-39.1 157.1-7.7 11-14.1 23-24.9 30.6-26 18.2-65.4 34.7-99.2 23.4-44.7-15-65-44.8-89.5-78.8.7 18.7 13.8 34.1 26.8 48.4 11.3 12.5 25 26.6 39.7 32.4-12.3-2.9-31.1-3.8-36.2 7.2-28.6-1.9-55.1-4.8-68.7-24.2-10.6-15.4-21.4-41.4-26.3-61.4zm222 124.1c4.1-3 11.1-2.9 17.4-3.6-5.4-2.7-13-3.7-19.3-2.2-.1-4.2-2-6.8-3.2-10.2 10.6-3.8 35.5-28.5 49.6-20.3 6.7 3.9 9.5 26.2 10.1 37 .4 9-.8 18-4.5 22.8-18.8-.6-35.8-2.8-50.7-7 .9-6.1-1-12.1.6-16.5zm-17.2-20c-16.8.8-26-1.2-38.3-10.8.2-.8 1.4-.5 1.5-1.4 18 8 40.8-3.3 59-4.9-7.9 5.1-14.6 11.6-22.2 17.1zm-12.1 33.2c-1.6-9.4-3.5-12-2.8-20.2 25-16.6 29.7 28.6 2.8 20.2zM226 438.6c-11.6-.7-48.1-14-38.5-23.7 9.4 6.5 27.5 4.9 41.3 7.3.8 4.4-2.8 10.2-2.8 16.4zM57.7 497.1c-4.3-12.7-9.2-25.1-14.8-36.9 30.8-23.8 65.3-48.9 102.2-63.5 2.8-1.1 23.2 25.4 26.2 27.6 16.5 11.7 37 21 56.2 30.2 1.2 8.8 3.9 20.2 8.7 35.5.7 2.3 1.4 4.7 2.2 7.2H57.7zm240.6 5.7h-.8c.3-.2.5-.4.8-.5v.5zm7.5-5.7c2.1-1.4 4.3-2.8 6.4-4.3 1.1 1.4 2.2 2.8 3.2 4.3h-9.6zm15.1-24.7c-10.8 7.3-20.6 18.3-33.3 25.2-6 3.3-27 11.7-33.4 10.2-3.6-.8-3.9-5.3-5.4-9.5-3.1-9-10.1-23.4-10.8-37-.8-17.2-2.5-46 16-42.4 14.9 2.9 32.3 9.7 43.9 16.1 7.1 3.9 11.1 8.6 21.9 9.5-.1 1.4-.1 2.8-.2 4.3-5.9 3.9-15.3 3.8-21.8 7.1 9.5.4 17 2.7 23.5 5.9-.1 3.4-.3 7-.4 10.6zm53.4 24.7h-14c-.1-3.2-2.8-5.8-6.1-5.8s-5.9 2.6-6.1 5.8h-17.4c-2.8-4.4-5.7-8.6-8.9-12.5 2.1-2.2 4-4.7 6-6.9 9 3.7 14.8-4.9 21.7-4.2 7.9.8 14.2 11.7 25.4 11l-.6 12.6zm8.7 0c.2-4 .4-7.8.6-11.5 15.6-7.3 29 1.3 35.7 11.5H383zm83.4-37c-2.3 11.2-5.8 24-9.9 37.1-.2-.1-.4-.1-.6-.1H428c.6-1.1 1.2-2.2 1.9-3.3-2.6-6.1-9-8.7-10.9-15.5 12.1-22.7 6.5-93.4-24.2-78.5 4.3-6.3 15.6-11.5 20.8-19.3 13 10.4 20.8 20.3 33.2 31.4 6.8 6 20 13.3 21.4 23.1.8 5.5-2.6 18.9-3.8 25.1zM222.2 130.5c5.4-14.9 27.2-34.7 45-32 7.7 1.2 18 8.2 12.2 17.7-30.2-7-45.2 12.6-54.4 33.1-8.1-2-4.9-13.1-2.8-18.8zm184.1 63.1c8.2-3.6 22.4-.7 29.6-5.3-4.2-11.5-10.3-21.4-9.3-37.7.5 0 1 0 1.4.1 6.8 14.2 12.7 29.2 21.4 41.7-5.7 13.5-43.6 25.4-43.1 1.2zm20.4-43zm-117.2 45.7c-6.8-10.9-19-32.5-14.5-45.3 6.5 11.9 8.6 24.4 17.8 33.3 4.1 4 12.2 9 8.2 20.2-.9 2.7-7.8 8.6-11.7 9.7-14.4 4.3-47.9.9-36.6-17.1 11.9.7 27.9 7.8 36.8-.8zm27.3 70c3.8 6.6 1.4 18.7 12.1 20.6 20.2 3.4 43.6-12.3 58.1-17.8 9-15.2-.8-20.7-8.9-30.5-16.6-20-38.8-44.8-38-74.7 6.7-4.9 7.3 7.4 8.2 9.7 8.7 20.3 30.4 46.2 46.3 63.5 3.9 4.3 10.3 8.4 11 11.2 2.1 8.2-5.4 18-4.5 23.5-21.7 13.9-45.8 29.1-81.4 25.6-7.4-6.7-10.3-21.4-2.9-31.1zm-201.3-9.2c-6.8-3.9-8.4-21-16.4-21.4-11.4-.7-9.3 22.2-9.3 35.5-7.8-7.1-9.2-29.1-3.5-40.3-6.6-3.2-9.5 3.6-13.1 5.9 4.7-34.1 49.8-15.8 42.3 20.3zm299.6 28.8c-10.1 19.2-24.4 40.4-54 41-.6-6.2-1.1-15.6 0-19.4 22.7-2.2 36.6-13.7 54-21.6zm-141.9 12.4c18.9 9.9 53.6 11 79.3 10.2 1.4 5.6 1.3 12.6 1.4 19.4-33 1.8-72-6.4-80.7-29.6zm92.2 46.7c-1.7 4.3-5.3 9.3-9.8 11.1-12.1 4.9-45.6 8.7-62.4-.3-10.7-5.7-17.5-18.5-23.4-26-2.8-3.6-16.9-12.9-.2-12.9 13.1 32.7 58 29 95.8 28.1z\"],\n    \"jira\": [496, 512, [], \"f7b1\", \"M490 241.7C417.1 169 320.6 71.8 248.5 0 83 164.9 6 241.7 6 241.7c-7.9 7.9-7.9 20.7 0 28.7C138.8 402.7 67.8 331.9 248.5 512c379.4-378 15.7-16.7 241.5-241.7 8-7.9 8-20.7 0-28.6zm-241.5 90l-76-75.7 76-75.7 76 75.7-76 75.7z\"],\n    \"joget\": [496, 512, [], \"f3b7\", \"M378.1 45C337.6 19.9 292.6 8 248.2 8 165 8 83.8 49.9 36.9 125.9c-71.9 116.6-35.6 269.3 81 341.2s269.3 35.6 341.2-80.9c71.9-116.6 35.6-269.4-81-341.2zm51.8 323.2c-40.4 65.5-110.4 101.5-182 101.5-6.8 0-13.6-.4-20.4-1-9-13.6-19.9-33.3-23.7-42.4-5.7-13.7-27.2-45.6 31.2-67.1 51.7-19.1 176.7-16.5 208.8-17.6-4 9-8.6 17.9-13.9 26.6zm-200.8-86.3c-55.5-1.4-81.7-20.8-58.5-48.2s51.1-40.7 68.9-51.2c17.9-10.5 27.3-33.7-23.6-29.7C87.3 161.5 48.6 252.1 37.6 293c-8.8-49.7-.1-102.7 28.5-149.1C128 43.4 259.6 12.2 360.1 74.1c74.8 46.1 111.2 130.9 99.3 212.7-24.9-.5-179.3-3.6-230.3-4.9zm183.8-54.8c-22.7-6-57 11.3-86.7 27.2-29.7 15.8-31.1 8.2-31.1 8.2s40.2-28.1 50.7-34.5 31.9-14 13.4-24.6c-3.2-1.8-6.7-2.7-10.4-2.7-17.8 0-41.5 18.7-67.5 35.6-31.5 20.5-65.3 31.3-65.3 31.3l169.5-1.6 46.5-23.4s3.6-9.5-19.1-15.5z\"],\n    \"joomla\": [448, 512, [], \"f1aa\", \"M.6 92.1C.6 58.8 27.4 32 60.4 32c30 0 54.5 21.9 59.2 50.2 32.6-7.6 67.1.6 96.5 30l-44.3 44.3c-20.5-20.5-42.6-16.3-55.4-3.5-14.3 14.3-14.3 37.9 0 52.2l99.5 99.5-44 44.3c-87.7-87.2-49.7-49.7-99.8-99.7-26.8-26.5-35-64.8-24.8-98.9C20.4 144.6.6 120.7.6 92.1zm129.5 116.4l44.3 44.3c10-10 89.7-89.7 99.7-99.8 14.3-14.3 37.6-14.3 51.9 0 12.8 12.8 17 35-3.5 55.4l44 44.3c31.2-31.2 38.5-67.6 28.9-101.2 29.2-4.1 51.9-29.2 51.9-59.5 0-33.2-26.8-60.1-59.8-60.1-30.3 0-55.4 22.5-59.5 51.6-33.8-9.9-71.7-1.5-98.3 25.1-18.3 19.1-71.1 71.5-99.6 99.9zm266.3 152.2c8.2-32.7-.9-68.5-26.3-93.9-11.8-12.2 5 4.7-99.5-99.7l-44.3 44.3 99.7 99.7c14.3 14.3 14.3 37.6 0 51.9-12.8 12.8-35 17-55.4-3.5l-44 44.3c27.6 30.2 68 38.8 102.7 28 5.5 27.4 29.7 48.1 58.9 48.1 33 0 59.8-26.8 59.8-60.1 0-30.2-22.5-55-51.6-59.1zm-84.3-53.1l-44-44.3c-87 86.4-50.4 50.4-99.7 99.8-14.3 14.3-37.6 14.3-51.9 0-13.1-13.4-16.9-35.3 3.2-55.4l-44-44.3c-30.2 30.2-38 65.2-29.5 98.3-26.7 6-46.2 29.9-46.2 58.2C0 453.2 26.8 480 59.8 480c28.6 0 52.5-19.8 58.6-46.7 32.7 8.2 68.5-.6 94.2-26 32.1-32 12.2-12.4 99.5-99.7z\"],\n    \"js\": [448, 512, [], \"f3b8\", \"M0 32v448h448V32H0zm243.8 349.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"js-square\": [448, 512, [], \"f3b9\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM243.8 381.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"jsfiddle\": [576, 512, [], \"f1cc\", \"M510.634 237.462c-4.727-2.621-5.664-5.748-6.381-10.776-2.352-16.488-3.539-33.619-9.097-49.095-35.895-99.957-153.99-143.386-246.849-91.646-27.37 15.25-48.971 36.369-65.493 63.903-3.184-1.508-5.458-2.71-7.824-3.686-30.102-12.421-59.049-10.121-85.331 9.167-25.531 18.737-36.422 44.548-32.676 76.408.355 3.025-1.967 7.621-4.514 9.545-39.712 29.992-56.031 78.065-41.902 124.615 13.831 45.569 57.514 79.796 105.608 81.433 30.291 1.031 60.637.546 90.959.539 84.041-.021 168.09.531 252.12-.48 52.664-.634 96.108-36.873 108.212-87.293 11.54-48.074-11.144-97.3-56.832-122.634zm21.107 156.88c-18.23 22.432-42.343 35.253-71.28 35.65-56.874.781-113.767.23-170.652.23 0 .7-163.028.159-163.728.154-43.861-.332-76.739-19.766-95.175-59.995-18.902-41.245-4.004-90.848 34.186-116.106 9.182-6.073 12.505-11.566 10.096-23.136-5.49-26.361 4.453-47.956 26.42-62.981 22.987-15.723 47.422-16.146 72.034-3.083 10.269 5.45 14.607 11.564 22.198-2.527 14.222-26.399 34.557-46.727 60.671-61.294 97.46-54.366 228.37 7.568 230.24 132.697.122 8.15 2.412 12.428 9.848 15.894 57.56 26.829 74.456 96.122 35.142 144.497zm-87.789-80.499c-5.848 31.157-34.622 55.096-66.666 55.095-16.953-.001-32.058-6.545-44.079-17.705-27.697-25.713-71.141-74.98-95.937-93.387-20.056-14.888-41.99-12.333-60.272 3.782-49.996 44.071 15.859 121.775 67.063 77.188 4.548-3.96 7.84-9.543 12.744-12.844 8.184-5.509 20.766-.884 13.168 10.622-17.358 26.284-49.33 38.197-78.863 29.301-28.897-8.704-48.84-35.968-48.626-70.179 1.225-22.485 12.364-43.06 35.414-55.965 22.575-12.638 46.369-13.146 66.991 2.474C295.68 280.7 320.467 323.97 352.185 343.47c24.558 15.099 54.254 7.363 68.823-17.506 28.83-49.209-34.592-105.016-78.868-63.46-3.989 3.744-6.917 8.932-11.41 11.72-10.975 6.811-17.333-4.113-12.809-10.353 20.703-28.554 50.464-40.44 83.271-28.214 31.429 11.714 49.108 44.366 42.76 78.186z\"],\n    \"kaggle\": [320, 512, [], \"f5fa\", \"M304.2 501.5L158.4 320.3 298.2 185c2.6-2.7 1.7-10.5-5.3-10.5h-69.2c-3.5 0-7 1.8-10.5 5.3L80.9 313.5V7.5q0-7.5-7.5-7.5H21.5Q14 0 14 7.5v497q0 7.5 7.5 7.5h51.9q7.5 0 7.5-7.5v-109l30.8-29.3 110.5 140.6c3 3.5 6.5 5.3 10.5 5.3h66.9q5.25 0 6-3z\"],\n    \"keybase\": [448, 512, [], \"f4f5\", \"M286.17,419a18,18,0,1,0,18,18A18,18,0,0,0,286.17,419ZM398.09,271.4c-9.5-14.62-39.37-52.45-87.26-73.71q-9.1-4.06-18.38-7.27A78.43,78.43,0,0,0,244.57,86.29c-12.41-4.1-23.33-6-32.41-5.77-.6-2-1.89-11,9.4-35L198.66,32l-5.48,7.56c-8.69,12.06-16.92,23.55-24.34,34.89a51,51,0,0,0-8.29-1.25c-41.53-2.45-39-2.33-41.06-2.33-50.61,0-50.75,52.12-50.75,45.88l-2.36,36.68c-1.61,27,19.75,50.21,47.63,51.85l8.93.54a214,214,0,0,0-46.29,35.54C14,304.66,14,374,14,429.77v33.64l23.32-29.8a148.6,148.6,0,0,0,14.56,37.56c5.78,10.13,14.87,9.45,19.64,7.33,4.21-1.87,10-6.92,3.75-20.11a178.29,178.29,0,0,1-15.76-53.13l46.82-59.83L81.67,419.54c58.23-42.4,157.38-61.76,236.25-38.59,34.2,10.05,67.45.69,84.74-23.84.72-1,1.2-2.16,1.85-3.22a156.09,156.09,0,0,1,2.8,28.43c0,23.3-3.69,52.93-14.88,81.64-2.52,6.46,1.76,14.5,8.6,15.74,7.42,1.57,15.33-3.1,18.37-11.15C429,443,434,414,434,382.32,434,343.74,421,304.86,398.09,271.4ZM142.37,128.58l-15.7-.93-1.39,21.79,13.13.78a93,93,0,0,0,.32,19.57l-22.38-1.34a12.28,12.28,0,0,1-11.76-12.79L107,119c1-12.17,13.87-11.27,13.26-11.32l29.11,1.73A144.35,144.35,0,0,0,142.37,128.58ZM290.79,300.76a10.51,10.51,0,0,1-14.35-1.39l-9.68-11.49-34.42,27a8.09,8.09,0,0,1-11.13-1.08l-15.78-18.64a7.38,7.38,0,0,1,1.34-10.34l34.57-27.18L227.2,240.9l-17.09,13.45a7.75,7.75,0,0,1-10.59-1s-3.72-4.42-3.8-4.53a7.38,7.38,0,0,1,1.37-10.34L214,225.19s-18.51-22-18.6-22.14a9.56,9.56,0,0,1,1.74-13.42A10.38,10.38,0,0,1,211.44,191l81.09,96.32A9.58,9.58,0,0,1,290.79,300.76ZM187.44,419a18,18,0,1,0,18,18A18,18,0,0,0,187.44,419Z\"],\n    \"keycdn\": [512, 512, [], \"f3ba\", \"M63.8 409.3l60.5-59c32.1 42.8 71.1 66 126.6 67.4 30.5.7 60.3-7 86.4-22.4 5.1 5.3 18.5 19.5 20.9 22-32.2 20.7-69.6 31.1-108.1 30.2-43.3-1.1-84.6-16.7-117.7-44.4.3-.6-38.2 37.5-38.6 37.9 9.5 29.8-13.1 62.4-46.3 62.4C20.7 503.3 0 481.7 0 454.9c0-34.3 33.1-56.6 63.8-45.6zm354.9-252.4c19.1 31.3 29.6 67.4 28.7 104-1.1 44.8-19 87.5-48.6 121 .3.3 23.8 25.2 24.1 25.5 9.6-1.3 19.2 2 25.9 9.1 11.3 12 10.9 30.9-1.1 42.4-12 11.3-30.9 10.9-42.4-1.1-6.7-7-9.4-16.8-7.6-26.3-24.9-26.6-44.4-47.2-44.4-47.2 42.7-34.1 63.3-79.6 64.4-124.2.7-28.9-7.2-57.2-21.1-82.2l22.1-21zM104 53.1c6.7 7 9.4 16.8 7.6 26.3l45.9 48.1c-4.7 3.8-13.3 10.4-22.8 21.3-25.4 28.5-39.6 64.8-40.7 102.9-.7 28.9 6.1 57.2 20 82.4l-22 21.5C72.7 324 63.1 287.9 64.2 250.9c1-44.6 18.3-87.6 47.5-121.1l-25.3-26.4c-9.6 1.3-19.2-2-25.9-9.1-11.3-12-10.9-30.9 1.1-42.4C73.5 40.7 92.2 41 104 53.1zM464.9 8c26 0 47.1 22.4 47.1 48.3S490.9 104 464.9 104c-6.3.1-14-1.1-15.9-1.8l-62.9 59.7c-32.7-43.6-76.7-65.9-126.9-67.2-30.5-.7-60.3 6.8-86.2 22.4l-21.1-22C184.1 74.3 221.5 64 260 64.9c43.3 1.1 84.6 16.7 117.7 44.6l41.1-38.6c-1.5-4.7-2.2-9.6-2.2-14.5C416.5 29.7 438.9 8 464.9 8zM256.7 113.4c5.5 0 10.9.4 16.4 1.1 78.1 9.8 133.4 81.1 123.8 159.1-9.8 78.1-81.1 133.4-159.1 123.8-78.1-9.8-133.4-81.1-123.8-159.2 9.3-72.4 70.1-124.6 142.7-124.8zm-59 119.4c.6 22.7 12.2 41.8 32.4 52.2l-11 51.7h73.7l-11-51.7c20.1-10.9 32.1-29 32.4-52.2-.4-32.8-25.8-57.5-58.3-58.3-32.1.8-57.3 24.8-58.2 58.3zM256 160\"],\n    \"kickstarter\": [448, 512, [], \"f3bb\", \"M400 480H48c-26.4 0-48-21.6-48-48V80c0-26.4 21.6-48 48-48h352c26.4 0 48 21.6 48 48v352c0 26.4-21.6 48-48 48zM199.6 178.5c0-30.7-17.6-45.1-39.7-45.1-25.8 0-40 19.8-40 44.5v154.8c0 25.8 13.7 45.6 40.5 45.6 21.5 0 39.2-14 39.2-45.6v-41.8l60.6 75.7c12.3 14.9 39 16.8 55.8 0 14.6-15.1 14.8-36.8 4-50.4l-49.1-62.8 40.5-58.7c9.4-13.5 9.5-34.5-5.6-49.1-16.4-15.9-44.6-17.3-61.4 7l-44.8 64.7v-38.8z\"],\n    \"kickstarter-k\": [384, 512, [], \"f3bc\", \"M147.3 114.4c0-56.2-32.5-82.4-73.4-82.4C26.2 32 0 68.2 0 113.4v283c0 47.3 25.3 83.4 74.9 83.4 39.8 0 72.4-25.6 72.4-83.4v-76.5l112.1 138.3c22.7 27.2 72.1 30.7 103.2 0 27-27.6 27.3-67.4 7.4-92.2l-90.8-114.8 74.9-107.4c17.4-24.7 17.5-63.1-10.4-89.8-30.3-29-82.4-31.6-113.6 12.8L147.3 185v-70.6z\"],\n    \"korvue\": [446, 512, [], \"f42f\", \"M386.5 34h-327C26.8 34 0 60.8 0 93.5v327.1C0 453.2 26.8 480 59.5 480h327.1c33 0 59.5-26.8 59.5-59.5v-327C446 60.8 419.2 34 386.5 34zM87.1 120.8h96v116l61.8-116h110.9l-81.2 132H87.1v-132zm161.8 272.1l-65.7-113.6v113.6h-96V262.1h191.5l88.6 130.8H248.9z\"],\n    \"laravel\": [640, 512, [], \"f3bd\", \"M637.5 241.6c-4.2-4.8-62.8-78.1-73.1-90.5-10.3-12.4-15.4-10.2-21.7-9.3-6.4.9-80.5 13.4-89.1 14.8-8.6 1.5-14 4.9-8.7 12.3 4.7 6.6 53.4 75.7 64.2 90.9l-193.7 46.4L161.2 48.7c-6.1-9.1-7.4-12.3-21.4-11.6-14 .6-120.9 9.5-128.5 10.2-7.6.6-16 4-8.4 22s129 279.6 132.4 287.2c3.4 7.6 12.2 20 32.8 15 21.1-5.1 94.3-24.2 134.3-34.7 21.1 38.3 64.2 115.9 72.2 127 10.6 14.9 18 12.4 34.3 7.4 12.8-3.9 199.6-71.1 208-74.5 8.4-3.5 13.6-5.9 7.9-14.4-4.2-6.2-53.5-72.2-79.3-106.8 17.7-4.7 80.6-21.4 87.3-23.3 7.9-2 9-5.8 4.7-10.6zm-352.2 72c-2.3.5-110.8 26.5-116.6 27.8-5.8 1.3-5.8.7-6.5-1.3-.7-2-129-266.7-130.8-270-1.8-3.3-1.7-5.9 0-5.9s102.5-9 106-9.2c3.6-.2 3.2.6 4.5 2.8 0 0 142.2 245.4 144.6 249.7 2.6 4.3 1.1 5.6-1.2 6.1zm306 57.4c1.7 2.7 3.5 4.5-2 6.4-5.4 2-183.7 62.1-187.1 63.6-3.5 1.5-6.2 2-10.6-4.5s-62.4-106.8-62.4-106.8L518 280.6c4.7-1.5 6.2-2.5 9.2 2.2 2.9 4.8 62.4 85.5 64.1 88.2zm12.1-134.1c-4.2.9-73.6 18.1-73.6 18.1l-56.7-77.8c-1.6-2.3-2.9-4.5 1.1-5s68.4-12.2 71.3-12.8c2.9-.7 5.4-1.5 9 3.4 3.6 4.9 52.6 67 54.5 69.4 1.8 2.3-1.4 3.7-5.6 4.7z\"],\n    \"lastfm\": [512, 512, [], \"f202\", \"M225.8 367.1l-18.8-51s-30.5 34-76.2 34c-40.5 0-69.2-35.2-69.2-91.5 0-72.1 36.4-97.9 72.1-97.9 66.5 0 74.8 53.3 100.9 134.9 18.8 56.9 54 102.6 155.4 102.6 72.7 0 122-22.3 122-80.9 0-72.9-62.7-80.6-115-92.1-25.8-5.9-33.4-16.4-33.4-34 0-19.9 15.8-31.7 41.6-31.7 28.2 0 43.4 10.6 45.7 35.8l58.6-7c-4.7-52.8-41.1-74.5-100.9-74.5-52.8 0-104.4 19.9-104.4 83.9 0 39.9 19.4 65.1 68 76.8 44.9 10.6 79.8 13.8 79.8 45.7 0 21.7-21.1 30.5-61 30.5-59.2 0-83.9-31.1-97.9-73.9-32-96.8-43.6-163-161.3-163C45.7 113.8 0 168.3 0 261c0 89.1 45.7 137.2 127.9 137.2 66.2 0 97.9-31.1 97.9-31.1z\"],\n    \"lastfm-square\": [448, 512, [], \"f203\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-92.2 312.9c-63.4 0-85.4-28.6-97.1-64.1-16.3-51-21.5-84.3-63-84.3-22.4 0-45.1 16.1-45.1 61.2 0 35.2 18 57.2 43.3 57.2 28.6 0 47.6-21.3 47.6-21.3l11.7 31.9s-19.8 19.4-61.2 19.4c-51.3 0-79.9-30.1-79.9-85.8 0-57.9 28.6-92 82.5-92 73.5 0 80.8 41.4 100.8 101.9 8.8 26.8 24.2 46.2 61.2 46.2 24.9 0 38.1-5.5 38.1-19.1 0-19.9-21.8-22-49.9-28.6-30.4-7.3-42.5-23.1-42.5-48 0-40 32.3-52.4 65.2-52.4 37.4 0 60.1 13.6 63 46.6l-36.7 4.4c-1.5-15.8-11-22.4-28.6-22.4-16.1 0-26 7.3-26 19.8 0 11 4.8 17.6 20.9 21.3 32.7 7.1 71.8 12 71.8 57.5.1 36.7-30.7 50.6-76.1 50.6z\"],\n    \"leanpub\": [576, 512, [], \"f212\", \"M386.539 111.485l15.096 248.955-10.979-.275c-36.232-.824-71.64 8.783-102.657 27.997-31.016-19.214-66.424-27.997-102.657-27.997-45.564 0-82.07 10.705-123.516 27.723L93.117 129.6c28.546-11.803 61.484-18.115 92.226-18.115 41.173 0 73.836 13.175 102.657 42.544 27.723-28.271 59.013-41.721 98.539-42.544zM569.07 448c-25.526 0-47.485-5.215-70.542-15.645-34.31-15.645-69.993-24.978-107.871-24.978-38.977 0-74.934 12.901-102.657 40.623-27.723-27.723-63.68-40.623-102.657-40.623-37.878 0-73.561 9.333-107.871 24.978C55.239 442.236 32.731 448 8.303 448H6.93L49.475 98.859C88.726 76.626 136.486 64 181.775 64 218.83 64 256.984 71.685 288 93.095 319.016 71.685 357.17 64 394.225 64c45.289 0 93.049 12.626 132.3 34.859L569.07 448zm-43.368-44.741l-34.036-280.246c-30.742-13.999-67.248-21.41-101.009-21.41-38.428 0-74.385 12.077-102.657 38.702-28.272-26.625-64.228-38.702-102.657-38.702-33.761 0-70.267 7.411-101.009 21.41L50.298 403.259c47.211-19.487 82.894-33.486 135.045-33.486 37.604 0 70.817 9.606 102.657 29.644 31.84-20.038 65.052-29.644 102.657-29.644 52.151 0 87.834 13.999 135.045 33.486z\"],\n    \"less\": [640, 512, [], \"f41d\", \"M612.7 219c0-20.5 3.2-32.6 3.2-54.6 0-34.2-12.6-45.2-40.5-45.2h-20.5v24.2h6.3c14.2 0 17.3 4.7 17.3 22.1 0 16.3-1.6 32.6-1.6 51.5 0 24.2 7.9 33.6 23.6 37.3v1.6c-15.8 3.7-23.6 13.1-23.6 37.3 0 18.9 1.6 34.2 1.6 51.5 0 17.9-3.7 22.6-17.3 22.6v.5h-6.3V393h20.5c27.8 0 40.5-11 40.5-45.2 0-22.6-3.2-34.2-3.2-54.6 0-11 6.8-22.6 27.3-23.6v-27.3c-20.5-.7-27.3-12.3-27.3-23.3zm-105.6 32c-15.8-6.3-30.5-10-30.5-20.5 0-7.9 6.3-12.6 17.9-12.6s22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-21 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51s-22.5-41-43-47.8zm-358.9 59.4c-3.7 0-8.4-3.2-8.4-13.1V119.1H65.2c-28.4 0-41 11-41 45.2 0 22.6 3.2 35.2 3.2 54.6 0 11-6.8 22.6-27.3 23.6v27.3c20.5.5 27.3 12.1 27.3 23.1 0 19.4-3.2 31-3.2 53.6 0 34.2 12.6 45.2 40.5 45.2h20.5v-24.2h-6.3c-13.1 0-17.3-5.3-17.3-22.6s1.6-32.1 1.6-51.5c0-24.2-7.9-33.6-23.6-37.3v-1.6c15.8-3.7 23.6-13.1 23.6-37.3 0-18.9-1.6-34.2-1.6-51.5s3.7-22.1 17.3-22.1H93v150.8c0 32.1 11 53.1 43.1 53.1 10 0 17.9-1.6 23.6-3.7l-5.3-34.2c-3.1.8-4.6.8-6.2.8zM379.9 251c-16.3-6.3-31-10-31-20.5 0-7.9 6.3-12.6 17.9-12.6 11.6 0 22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-20.5 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51 .1-28.9-22.5-41-43-47.8zm-155-68.8c-38.4 0-75.1 32.1-74.1 82.5 0 52 34.2 82.5 79.3 82.5 18.9 0 39.9-6.8 56.2-17.9l-15.8-27.8c-11.6 6.8-22.6 10-34.2 10-21 0-37.3-10-41.5-34.2H290c.5-3.7 1.6-11 1.6-19.4.6-42.6-22.6-75.7-66.7-75.7zm-30 66.2c3.2-21 15.8-31 30.5-31 18.9 0 26.3 13.1 26.3 31h-56.8z\"],\n    \"line\": [448, 512, [], \"f3c0\", \"M272.1 204.2v71.1c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.1 0-2.1-.6-2.6-1.3l-32.6-44v42.2c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.8 0-3.2-1.4-3.2-3.2v-71.1c0-1.8 1.4-3.2 3.2-3.2H219c1 0 2.1.5 2.6 1.4l32.6 44v-42.2c0-1.8 1.4-3.2 3.2-3.2h11.4c1.8-.1 3.3 1.4 3.3 3.1zm-82-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 1.8 1.4 3.2 3.2 3.2h11.4c1.8 0 3.2-1.4 3.2-3.2v-71.1c0-1.7-1.4-3.2-3.2-3.2zm-27.5 59.6h-31.1v-56.4c0-1.8-1.4-3.2-3.2-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 .9.3 1.6.9 2.2.6.5 1.3.9 2.2.9h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.7-1.4-3.2-3.1-3.2zM332.1 201h-45.7c-1.7 0-3.2 1.4-3.2 3.2v71.1c0 1.7 1.4 3.2 3.2 3.2h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2V234c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2v-11.4c-.1-1.7-1.5-3.2-3.2-3.2zM448 113.7V399c-.1 44.8-36.8 81.1-81.7 81H81c-44.8-.1-81.1-36.9-81-81.7V113c.1-44.8 36.9-81.1 81.7-81H367c44.8.1 81.1 36.8 81 81.7zm-61.6 122.6c0-73-73.2-132.4-163.1-132.4-89.9 0-163.1 59.4-163.1 132.4 0 65.4 58 120.2 136.4 130.6 19.1 4.1 16.9 11.1 12.6 36.8-.7 4.1-3.3 16.1 14.1 8.8 17.4-7.3 93.9-55.3 128.2-94.7 23.6-26 34.9-52.3 34.9-81.5z\"],\n    \"linkedin\": [448, 512, [], \"f08c\", \"M416 32H31.9C14.3 32 0 46.5 0 64.3v383.4C0 465.5 14.3 480 31.9 480H416c17.6 0 32-14.5 32-32.3V64.3c0-17.8-14.4-32.3-32-32.3zM135.4 416H69V202.2h66.5V416zm-33.2-243c-21.3 0-38.5-17.3-38.5-38.5S80.9 96 102.2 96c21.2 0 38.5 17.3 38.5 38.5 0 21.3-17.2 38.5-38.5 38.5zm282.1 243h-66.4V312c0-24.8-.5-56.7-34.5-56.7-34.6 0-39.9 27-39.9 54.9V416h-66.4V202.2h63.7v29.2h.9c8.9-16.8 30.6-34.5 62.9-34.5 67.2 0 79.7 44.3 79.7 101.9V416z\"],\n    \"linkedin-in\": [448, 512, [], \"f0e1\", \"M100.28 448H7.4V148.9h92.88zM53.79 108.1C24.09 108.1 0 83.5 0 53.8a53.79 53.79 0 0 1 107.58 0c0 29.7-24.1 54.3-53.79 54.3zM447.9 448h-92.68V302.4c0-34.7-.7-79.2-48.29-79.2-48.29 0-55.69 37.7-55.69 76.7V448h-92.78V148.9h89.08v40.8h1.3c12.4-23.5 42.69-48.3 87.88-48.3 94 0 111.28 61.9 111.28 142.3V448z\"],\n    \"linode\": [448, 512, [], \"f2b8\", \"M437.4 226.3c-.3-.9-.9-1.4-1.4-2l-70-38.6c-.9-.6-2-.6-3.1 0l-58.9 36c-.9.6-1.4 1.7-1.4 2.6l-.9 31.4-24-16c-.9-.6-2.3-.6-3.1 0L240 260.9l-1.4-35.1c0-.9-.6-2-1.4-2.3l-36-24.3 33.7-17.4c1.1-.6 1.7-1.7 1.7-2.9l-5.7-132.3c0-.9-.9-2-1.7-2.6L138.6.3c-.9-.3-1.7-.3-2.3-.3L12.6 38.6c-1.4.6-2.3 2-2 3.7L38 175.4c.9 3.4 34 27.4 38.6 30.9l-26.9 12.9c-1.4.9-2 2.3-1.7 3.4l20.6 100.3c.6 2.9 23.7 23.1 27.1 26.3l-17.4 10.6c-.9.6-1.7 2-1.4 3.1 1.4 7.1 15.4 77.7 16.9 79.1l65.1 69.1c.6.6 1.4.6 2.3.9.6 0 1.1-.3 1.7-.6l83.7-66.9c.9-.6 1.1-1.4 1.1-2.3l-2-46 28 23.7c1.1.9 2.9.9 4 0l66.9-53.4c.9-.6 1.1-1.4 1.1-2.3l2.3-33.4 20.3 14c1.1.9 2.6.9 3.7 0l54.6-43.7c.6-.3 1.1-1.1 1.1-2 .9-6.5 10.3-70.8 9.7-72.8zm-204.8 4.8l4 92.6-90.6 61.2-14-96.6 100.6-57.2zm-7.7-180l5.4 126-106.6 55.4L104 97.7l120.9-46.6zM44 173.1L18 48l79.7 49.4 19.4 132.9L44 173.1zm30.6 147.8L55.7 230l70 58.3 13.7 93.4-64.8-60.8zm24.3 117.7l-13.7-67.1 61.7 60.9 9.7 67.4-57.7-61.2zm64.5 64.5l-10.6-70.9 85.7-61.4 3.1 70-78.2 62.3zm82-115.1c0-3.4.9-22.9-2-25.1l-24.3-20 22.3-14.9c2.3-1.7 1.1-5.7 1.1-8l29.4 22.6.6 68.3-27.1-22.9zm94.3-25.4l-60.9 48.6-.6-68.6 65.7-46.9-4.2 66.9zm27.7-25.7l-19.1-13.4 2-34c.3-.9-.3-2-1.1-2.6L308 259.7l.6-30 64.6 40.6-5.8 66.6zm54.6-39.8l-48.3 38.3 5.7-65.1 51.1-36.6-8.5 63.4z\"],\n    \"linux\": [448, 512, [], \"f17c\", \"M220.8 123.3c1 .5 1.8 1.7 3 1.7 1.1 0 2.8-.4 2.9-1.5.2-1.4-1.9-2.3-3.2-2.9-1.7-.7-3.9-1-5.5-.1-.4.2-.8.7-.6 1.1.3 1.3 2.3 1.1 3.4 1.7zm-21.9 1.7c1.2 0 2-1.2 3-1.7 1.1-.6 3.1-.4 3.5-1.6.2-.4-.2-.9-.6-1.1-1.6-.9-3.8-.6-5.5.1-1.3.6-3.4 1.5-3.2 2.9.1 1 1.8 1.5 2.8 1.4zM420 403.8c-3.6-4-5.3-11.6-7.2-19.7-1.8-8.1-3.9-16.8-10.5-22.4-1.3-1.1-2.6-2.1-4-2.9-1.3-.8-2.7-1.5-4.1-2 9.2-27.3 5.6-54.5-3.7-79.1-11.4-30.1-31.3-56.4-46.5-74.4-17.1-21.5-33.7-41.9-33.4-72C311.1 85.4 315.7.1 234.8 0 132.4-.2 158 103.4 156.9 135.2c-1.7 23.4-6.4 41.8-22.5 64.7-18.9 22.5-45.5 58.8-58.1 96.7-6 17.9-8.8 36.1-6.2 53.3-6.5 5.8-11.4 14.7-16.6 20.2-4.2 4.3-10.3 5.9-17 8.3s-14 6-18.5 14.5c-2.1 3.9-2.8 8.1-2.8 12.4 0 3.9.6 7.9 1.2 11.8 1.2 8.1 2.5 15.7.8 20.8-5.2 14.4-5.9 24.4-2.2 31.7 3.8 7.3 11.4 10.5 20.1 12.3 17.3 3.6 40.8 2.7 59.3 12.5 19.8 10.4 39.9 14.1 55.9 10.4 11.6-2.6 21.1-9.6 25.9-20.2 12.5-.1 26.3-5.4 48.3-6.6 14.9-1.2 33.6 5.3 55.1 4.1.6 2.3 1.4 4.6 2.5 6.7v.1c8.3 16.7 23.8 24.3 40.3 23 16.6-1.3 34.1-11 48.3-27.9 13.6-16.4 36-23.2 50.9-32.2 7.4-4.5 13.4-10.1 13.9-18.3.4-8.2-4.4-17.3-15.5-29.7zM223.7 87.3c9.8-22.2 34.2-21.8 44-.4 6.5 14.2 3.6 30.9-4.3 40.4-1.6-.8-5.9-2.6-12.6-4.9 1.1-1.2 3.1-2.7 3.9-4.6 4.8-11.8-.2-27-9.1-27.3-7.3-.5-13.9 10.8-11.8 23-4.1-2-9.4-3.5-13-4.4-1-6.9-.3-14.6 2.9-21.8zM183 75.8c10.1 0 20.8 14.2 19.1 33.5-3.5 1-7.1 2.5-10.2 4.6 1.2-8.9-3.3-20.1-9.6-19.6-8.4.7-9.8 21.2-1.8 28.1 1 .8 1.9-.2-5.9 5.5-15.6-14.6-10.5-52.1 8.4-52.1zm-13.6 60.7c6.2-4.6 13.6-10 14.1-10.5 4.7-4.4 13.5-14.2 27.9-14.2 7.1 0 15.6 2.3 25.9 8.9 6.3 4.1 11.3 4.4 22.6 9.3 8.4 3.5 13.7 9.7 10.5 18.2-2.6 7.1-11 14.4-22.7 18.1-11.1 3.6-19.8 16-38.2 14.9-3.9-.2-7-1-9.6-2.1-8-3.5-12.2-10.4-20-15-8.6-4.8-13.2-10.4-14.7-15.3-1.4-4.9 0-9 4.2-12.3zm3.3 334c-2.7 35.1-43.9 34.4-75.3 18-29.9-15.8-68.6-6.5-76.5-21.9-2.4-4.7-2.4-12.7 2.6-26.4v-.2c2.4-7.6.6-16-.6-23.9-1.2-7.8-1.8-15 .9-20 3.5-6.7 8.5-9.1 14.8-11.3 10.3-3.7 11.8-3.4 19.6-9.9 5.5-5.7 9.5-12.9 14.3-18 5.1-5.5 10-8.1 17.7-6.9 8.1 1.2 15.1 6.8 21.9 16l19.6 35.6c9.5 19.9 43.1 48.4 41 68.9zm-1.4-25.9c-4.1-6.6-9.6-13.6-14.4-19.6 7.1 0 14.2-2.2 16.7-8.9 2.3-6.2 0-14.9-7.4-24.9-13.5-18.2-38.3-32.5-38.3-32.5-13.5-8.4-21.1-18.7-24.6-29.9s-3-23.3-.3-35.2c5.2-22.9 18.6-45.2 27.2-59.2 2.3-1.7.8 3.2-8.7 20.8-8.5 16.1-24.4 53.3-2.6 82.4.6-20.7 5.5-41.8 13.8-61.5 12-27.4 37.3-74.9 39.3-112.7 1.1.8 4.6 3.2 6.2 4.1 4.6 2.7 8.1 6.7 12.6 10.3 12.4 10 28.5 9.2 42.4 1.2 6.2-3.5 11.2-7.5 15.9-9 9.9-3.1 17.8-8.6 22.3-15 7.7 30.4 25.7 74.3 37.2 95.7 6.1 11.4 18.3 35.5 23.6 64.6 3.3-.1 7 .4 10.9 1.4 13.8-35.7-11.7-74.2-23.3-84.9-4.7-4.6-4.9-6.6-2.6-6.5 12.6 11.2 29.2 33.7 35.2 59 2.8 11.6 3.3 23.7.4 35.7 16.4 6.8 35.9 17.9 30.7 34.8-2.2-.1-3.2 0-4.2 0 3.2-10.1-3.9-17.6-22.8-26.1-19.6-8.6-36-8.6-38.3 12.5-12.1 4.2-18.3 14.7-21.4 27.3-2.8 11.2-3.6 24.7-4.4 39.9-.5 7.7-3.6 18-6.8 29-32.1 22.9-76.7 32.9-114.3 7.2zm257.4-11.5c-.9 16.8-41.2 19.9-63.2 46.5-13.2 15.7-29.4 24.4-43.6 25.5s-26.5-4.8-33.7-19.3c-4.7-11.1-2.4-23.1 1.1-36.3 3.7-14.2 9.2-28.8 9.9-40.6.8-15.2 1.7-28.5 4.2-38.7 2.6-10.3 6.6-17.2 13.7-21.1.3-.2.7-.3 1-.5.8 13.2 7.3 26.6 18.8 29.5 12.6 3.3 30.7-7.5 38.4-16.3 9-.3 15.7-.9 22.6 5.1 9.9 8.5 7.1 30.3 17.1 41.6 10.6 11.6 14 19.5 13.7 24.6zM173.3 148.7c2 1.9 4.7 4.5 8 7.1 6.6 5.2 15.8 10.6 27.3 10.6 11.6 0 22.5-5.9 31.8-10.8 4.9-2.6 10.9-7 14.8-10.4s5.9-6.3 3.1-6.6-2.6 2.6-6 5.1c-4.4 3.2-9.7 7.4-13.9 9.8-7.4 4.2-19.5 10.2-29.9 10.2s-18.7-4.8-24.9-9.7c-3.1-2.5-5.7-5-7.7-6.9-1.5-1.4-1.9-4.6-4.3-4.9-1.4-.1-1.8 3.7 1.7 6.5z\"],\n    \"lyft\": [512, 512, [], \"f3c3\", \"M0 81.1h77.8v208.7c0 33.1 15 52.8 27.2 61-12.7 11.1-51.2 20.9-80.2-2.8C7.8 334 0 310.7 0 289V81.1zm485.9 173.5v-22h23.8v-76.8h-26.1c-10.1-46.3-51.2-80.7-100.3-80.7-56.6 0-102.7 46-102.7 102.7V357c16 2.3 35.4-.3 51.7-14 17.1-14 24.8-37.2 24.8-59v-6.7h38.8v-76.8h-38.8v-23.3c0-34.6 52.2-34.6 52.2 0v77.1c0 56.6 46 102.7 102.7 102.7v-76.5c-14.5 0-26.1-11.7-26.1-25.9zm-294.3-99v113c0 15.4-23.8 15.4-23.8 0v-113H91v132.7c0 23.8 8 54 45 63.9 37 9.8 58.2-10.6 58.2-10.6-2.1 13.4-14.5 23.3-34.9 25.3-15.5 1.6-35.2-3.6-45-7.8v70.3c25.1 7.5 51.5 9.8 77.6 4.7 47.1-9.1 76.8-48.4 76.8-100.8V155.1h-77.1v.5z\"],\n    \"magento\": [448, 512, [], \"f3c4\", \"M445.7 127.9V384l-63.4 36.5V164.7L223.8 73.1 65.2 164.7l.4 255.9L2.3 384V128.1L224.2 0l221.5 127.9zM255.6 420.5L224 438.9l-31.8-18.2v-256l-63.3 36.6.1 255.9 94.9 54.9 95.1-54.9v-256l-63.4-36.6v255.9z\"],\n    \"mailchimp\": [448, 512, [], \"f59e\", \"M330.61 243.52a36.15 36.15 0 0 1 9.3 0c1.66-3.83 1.95-10.43.45-17.61-2.23-10.67-5.25-17.14-11.48-16.13s-6.47 8.74-4.24 19.42c1.26 6 3.49 11.14 6 14.32zM277.05 252c4.47 2 7.2 3.26 8.28 2.13 1.89-1.94-3.48-9.39-12.12-13.09a31.44 31.44 0 0 0-30.61 3.68c-3 2.18-5.81 5.22-5.41 7.06.85 3.74 10-2.71 22.6-3.48 7-.44 12.8 1.75 17.26 3.71zm-9 5.13c-9.07 1.42-15 6.53-13.47 10.1.9.34 1.17.81 5.21-.81a37 37 0 0 1 18.72-1.95c2.92.34 4.31.52 4.94-.49 1.46-2.22-5.71-8-15.39-6.85zm54.17 17.1c3.38-6.87-10.9-13.93-14.3-7s10.92 13.88 14.32 6.97zm15.66-20.47c-7.66-.13-7.95 15.8-.26 15.93s7.98-15.81.28-15.96zm-218.79 78.9c-1.32.31-6 1.45-8.47-2.35-5.2-8 11.11-20.38 3-35.77-9.1-17.47-27.82-13.54-35.05-5.54-8.71 9.6-8.72 23.54-5 24.08 4.27.57 4.08-6.47 7.38-11.63a12.83 12.83 0 0 1 17.85-3.72c11.59 7.59 1.37 17.76 2.28 28.62 1.39 16.68 18.42 16.37 21.58 9a2.08 2.08 0 0 0-.2-2.33c.03.89.68-1.3-3.35-.39zm299.72-17.07c-3.35-11.73-2.57-9.22-6.78-20.52 2.45-3.67 15.29-24-3.07-43.25-10.4-10.92-33.9-16.54-41.1-18.54-1.5-11.39 4.65-58.7-21.52-83 20.79-21.55 33.76-45.29 33.73-65.65-.06-39.16-48.15-51-107.42-26.47l-12.55 5.33c-.06-.05-22.71-22.27-23.05-22.57C169.5-18-41.77 216.81 25.78 273.85l14.76 12.51a72.49 72.49 0 0 0-4.1 33.5c3.36 33.4 36 60.42 67.53 60.38 57.73 133.06 267.9 133.28 322.29 3 1.74-4.47 9.11-24.61 9.11-42.38s-10.09-25.27-16.53-25.27zm-316 48.16c-22.82-.61-47.46-21.15-49.91-45.51-6.17-61.31 74.26-75.27 84-12.33 4.54 29.64-4.67 58.49-34.12 57.81zM84.3 249.55C69.14 252.5 55.78 261.09 47.6 273c-4.88-4.07-14-12-15.59-15-13.01-24.85 14.24-73 33.3-100.21C112.42 90.56 186.19 39.68 220.36 48.91c5.55 1.57 23.94 22.89 23.94 22.89s-34.15 18.94-65.8 45.35c-42.66 32.85-74.89 80.59-94.2 132.4zM323.18 350.7s-35.74 5.3-69.51-7.07c6.21-20.16 27 6.1 96.4-13.81 15.29-4.38 35.37-13 51-25.35a102.85 102.85 0 0 1 7.12 24.28c3.66-.66 14.25-.52 11.44 18.1-3.29 19.87-11.73 36-25.93 50.84A106.86 106.86 0 0 1 362.55 421a132.45 132.45 0 0 1-20.34 8.58c-53.51 17.48-108.3-1.74-126-43a66.33 66.33 0 0 1-3.55-9.74c-7.53-27.2-1.14-59.83 18.84-80.37 1.23-1.31 2.48-2.85 2.48-4.79a8.45 8.45 0 0 0-1.92-4.54c-7-10.13-31.19-27.4-26.33-60.83 3.5-24 24.49-40.91 44.07-39.91l5 .29c8.48.5 15.89 1.59 22.88 1.88 11.69.5 22.2-1.19 34.64-11.56 4.2-3.5 7.57-6.54 13.26-7.51a17.45 17.45 0 0 1 13.6 2.24c10 6.64 11.4 22.73 11.92 34.49.29 6.72 1.1 23 1.38 27.63.63 10.67 3.43 12.17 9.11 14 3.19 1.05 6.15 1.83 10.51 3.06 13.21 3.71 21 7.48 26 12.31a16.38 16.38 0 0 1 4.74 9.29c1.56 11.37-8.82 25.4-36.31 38.16-46.71 21.68-93.68 14.45-100.48 13.68-20.15-2.71-31.63 23.32-19.55 41.15 22.64 33.41 122.4 20 151.37-21.35.69-1 .12-1.59-.73-1-41.77 28.58-97.06 38.21-128.46 26-4.77-1.85-14.73-6.44-15.94-16.67 43.6 13.49 71 .74 71 .74s2.03-2.79-.56-2.53zm-68.47-5.7zm-83.4-187.5c16.74-19.35 37.36-36.18 55.83-45.63a.73.73 0 0 1 1 1c-1.46 2.66-4.29 8.34-5.19 12.65a.75.75 0 0 0 1.16.79c11.49-7.83 31.48-16.22 49-17.3a.77.77 0 0 1 .52 1.38 41.86 41.86 0 0 0-7.71 7.74.75.75 0 0 0 .59 1.19c12.31.09 29.66 4.4 41 10.74.76.43.22 1.91-.64 1.72-69.55-15.94-123.08 18.53-134.5 26.83a.76.76 0 0 1-1-1.12z\"],\n    \"mandalorian\": [448, 512, [], \"f50f\", \"M232.27 511.89c-1-3.26-1.69-15.83-1.39-24.58.55-15.89 1-24.72 1.4-28.76.64-6.2 2.87-20.72 3.28-21.38.6-1 .4-27.87-.24-33.13-.31-2.58-.63-11.9-.69-20.73-.13-16.47-.53-20.12-2.73-24.76-1.1-2.32-1.23-3.84-1-11.43a92.38 92.38 0 0 0-.34-12.71c-2-13-3.46-27.7-3.25-33.9s.43-7.15 2.06-9.67c3.05-4.71 6.51-14 8.62-23.27 2.26-9.86 3.88-17.18 4.59-20.74a109.54 109.54 0 0 1 4.42-15.05c2.27-6.25 2.49-15.39.37-15.39-.3 0-1.38 1.22-2.41 2.71s-4.76 4.8-8.29 7.36c-8.37 6.08-11.7 9.39-12.66 12.58s-1 7.23-.16 7.76c.34.21 1.29 2.4 2.11 4.88a28.83 28.83 0 0 1 .72 15.36c-.39 1.77-1 5.47-1.46 8.23s-1 6.46-1.25 8.22a9.85 9.85 0 0 1-1.55 4.26c-1 1-1.14.91-2.05-.53a14.87 14.87 0 0 1-1.44-4.75c-.25-1.74-1.63-7.11-3.08-11.93-3.28-10.9-3.52-16.15-1-21a14.24 14.24 0 0 0 1.67-4.61c0-2.39-2.2-5.32-7.41-9.89-7-6.18-8.63-7.92-10.23-11.3-1.71-3.6-3.06-4.06-4.54-1.54-1.78 3-2.6 9.11-3 22l-.34 12.19 2 2.25c3.21 3.7 12.07 16.45 13.78 19.83 3.41 6.74 4.34 11.69 4.41 23.56s.95 22.75 2 24.71c.36.66.51 1.35.34 1.52s.41 2.09 1.29 4.27a38.14 38.14 0 0 1 2.06 9 91 91 0 0 0 1.71 10.37c2.23 9.56 2.77 14.08 2.39 20.14-.2 3.27-.53 11.07-.73 17.32-1.31 41.76-1.85 58-2 61.21-.12 2-.39 11.51-.6 21.07-.36 16.3-1.3 27.37-2.42 28.65-.64.73-8.07-4.91-12.52-9.49-3.75-3.87-4-4.79-2.83-9.95.7-3 2.26-18.29 3.33-32.62.36-4.78.81-10.5 1-12.71.83-9.37 1.66-20.35 2.61-34.78.56-8.46 1.33-16.44 1.72-17.73s.89-9.89 1.13-19.11l.43-16.77-2.26-4.3c-1.72-3.28-4.87-6.94-13.22-15.34-6-6.07-11.84-12.3-12.91-13.85l-1.95-2.81.75-10.9c1.09-15.71 1.1-48.57 0-59.06l-.89-8.7-3.28-4.52c-5.86-8.08-5.8-7.75-6.22-33.27-.1-6.07-.38-11.5-.63-12.06-.83-1.87-3.05-2.66-8.54-3.05-8.86-.62-11-1.9-23.85-14.55-6.15-6-12.34-12-13.75-13.19-2.81-2.42-2.79-2-.56-9.63l1.35-4.65-1.69-3a32.22 32.22 0 0 0-2.59-4.07c-1.33-1.51-5.5-10.89-6-13.49a4.24 4.24 0 0 1 .87-3.9c2.23-2.86 3.4-5.68 4.45-10.73 2.33-11.19 7.74-26.09 10.6-29.22 3.18-3.47 7.7-1 9.41 5 1.34 4.79 1.37 9.79.1 18.55a101.2 101.2 0 0 0-1 11.11c0 4 .19 4.69 2.25 7.39 3.33 4.37 7.73 7.41 15.2 10.52a18.67 18.67 0 0 1 4.72 2.85c11.17 10.72 18.62 16.18 22.95 16.85 5.18.8 8 4.54 10 13.39 1.31 5.65 4 11.14 5.46 11.14a9.38 9.38 0 0 0 3.33-1.39c2-1.22 2.25-1.73 2.25-4.18a132.88 132.88 0 0 0-2-17.84c-.37-1.66-.78-4.06-.93-5.35s-.61-3.85-1-5.69c-2.55-11.16-3.65-15.46-4.1-16-1.55-2-4.08-10.2-4.93-15.92-1.64-11.11-4-14.23-12.91-17.39A43.15 43.15 0 0 1 165.24 78c-1.15-1-4-3.22-6.35-5.06s-4.41-3.53-4.6-3.76a22.7 22.7 0 0 0-2.69-2c-6.24-4.22-8.84-7-11.26-12l-2.44-5-.22-13-.22-13 6.91-6.55c3.95-3.75 8.48-7.35 10.59-8.43 3.31-1.69 4.45-1.89 11.37-2 8.53-.19 10.12 0 11.66 1.56s1.36 6.4-.29 8.5a6.66 6.66 0 0 0-1.34 2.32c0 .58-2.61 4.91-5.42 9a30.39 30.39 0 0 0-2.37 6.82c20.44 13.39 21.55 3.77 14.07 29L194 66.92c3.11-8.66 6.47-17.26 8.61-26.22.29-7.63-12-4.19-15.4-8.68-2.33-5.93 3.13-14.18 6.06-19.2 1.6-2.34 6.62-4.7 8.82-4.15.88.22 4.16-.35 7.37-1.28a45.3 45.3 0 0 1 7.55-1.68 29.57 29.57 0 0 0 6-1.29c3.65-1.11 4.5-1.17 6.35-.4a29.54 29.54 0 0 0 5.82 1.36 18.18 18.18 0 0 1 6 1.91 22.67 22.67 0 0 0 5 2.17c2.51.68 3 .57 7.05-1.67l4.35-2.4L268.32 5c10.44-.4 10.81-.47 15.26-2.68L288.16 0l2.46 1.43c1.76 1 3.14 2.73 4.85 6 2.36 4.51 2.38 4.58 1.37 7.37-.88 2.44-.89 3.3-.1 6.39a35.76 35.76 0 0 0 2.1 5.91 13.55 13.55 0 0 1 1.31 4c.31 4.33 0 5.3-2.41 6.92-2.17 1.47-7 7.91-7 9.34a14.77 14.77 0 0 1-1.07 3c-5 11.51-6.76 13.56-14.26 17-9.2 4.2-12.3 5.19-16.21 5.19-3.1 0-4 .25-4.54 1.26a18.33 18.33 0 0 1-4.09 3.71 13.62 13.62 0 0 0-4.38 4.78 5.89 5.89 0 0 1-2.49 2.91 6.88 6.88 0 0 0-2.45 1.71 67.62 67.62 0 0 1-7 5.38c-3.33 2.34-6.87 5-7.87 6A7.27 7.27 0 0 1 224 100a5.76 5.76 0 0 0-2.13 1.65c-1.31 1.39-1.49 2.11-1.14 4.6a36.45 36.45 0 0 0 1.42 5.88c1.32 3.8 1.31 7.86 0 10.57s-.89 6.65 1.35 9.59c2 2.63 2.16 4.56.71 8.84a33.45 33.45 0 0 0-1.06 8.91c0 4.88.22 6.28 1.46 8.38s1.82 2.48 3.24 2.32c2-.23 2.3-1.05 4.71-12.12 2.18-10 3.71-11.92 13.76-17.08 2.94-1.51 7.46-4 10-5.44s6.79-3.69 9.37-4.91a40.09 40.09 0 0 0 15.22-11.67c7.11-8.79 10-16.22 12.85-33.3a18.37 18.37 0 0 1 2.86-7.73 20.39 20.39 0 0 0 2.89-7.31c1-5.3 2.85-9.08 5.58-11.51 4.7-4.18 6-1.09 4.59 10.87-.46 3.86-1.1 10.33-1.44 14.38l-.61 7.36 4.45 4.09 4.45 4.09.11 8.42c.06 4.63.47 9.53.92 10.89l.82 2.47-6.43 6.28c-8.54 8.33-12.88 13.93-16.76 21.61-1.77 3.49-3.74 7.11-4.38 8-2.18 3.11-6.46 13-8.76 20.26l-2.29 7.22-7 6.49c-3.83 3.57-8 7.25-9.17 8.17-3.05 2.32-4.26 5.15-4.26 10a14.62 14.62 0 0 0 1.59 7.26 42 42 0 0 1 2.09 4.83 9.28 9.28 0 0 0 1.57 2.89c1.4 1.59 1.92 16.12.83 23.22-.68 4.48-3.63 12-4.7 12-1.79 0-4.06 9.27-5.07 20.74-.18 2-.62 5.94-1 8.7s-1 10-1.35 16.05c-.77 12.22-.19 18.77 2 23.15 3.41 6.69.52 12.69-11 22.84l-4 3.49.07 5.19a40.81 40.81 0 0 0 1.14 8.87c4.61 16 4.73 16.92 4.38 37.13-.46 26.4-.26 40.27.63 44.15a61.31 61.31 0 0 1 1.08 7c.17 2 .66 5.33 1.08 7.36.47 2.26.78 11 .79 22.74v19.06l-1.81 2.63c-2.71 3.91-15.11 13.54-15.49 12.29zm29.53-45.11c-.18-.3-.33-6.87-.33-14.59 0-14.06-.89-27.54-2.26-34.45-.4-2-.81-9.7-.9-17.06-.15-11.93-1.4-24.37-2.64-26.38-.66-1.07-3-17.66-3-21.3 0-4.23 1-6 5.28-9.13s4.86-3.14 5.48-.72c.28 1.1 1.45 5.62 2.6 10 3.93 15.12 4.14 16.27 4.05 21.74-.1 5.78-.13 6.13-1.74 17.73-1 7.07-1.17 12.39-1 28.43.17 19.4-.64 35.73-2 41.27-.71 2.78-2.8 5.48-3.43 4.43zm-71-37.58a101 101 0 0 1-1.73-10.79 100.5 100.5 0 0 0-1.73-10.79 37.53 37.53 0 0 1-1-6.49c-.31-3.19-.91-7.46-1.33-9.48-1-4.79-3.35-19.35-3.42-21.07 0-.74-.34-4.05-.7-7.36-.67-6.21-.84-27.67-.22-28.29 1-1 6.63 2.76 11.33 7.43l5.28 5.25-.45 6.47c-.25 3.56-.6 10.23-.78 14.83s-.49 9.87-.67 11.71-.61 9.36-.94 16.72c-.79 17.41-1.94 31.29-2.65 32a.62.62 0 0 1-1-.14zm-87.18-266.59c21.07 12.79 17.84 14.15 28.49 17.66 13 4.29 18.87 7.13 23.15 16.87C111.6 233.28 86.25 255 78.55 268c-31 52-6 101.59 62.75 87.21-14.18 29.23-78 28.63-98.68-4.9-24.68-39.95-22.09-118.3 61-187.66zm210.79 179c56.66 6.88 82.32-37.74 46.54-89.23 0 0-26.87-29.34-64.28-68 3-15.45 9.49-32.12 30.57-53.82 89.2 63.51 92 141.61 92.46 149.36 4.3 70.64-78.7 91.18-105.29 61.71z\"],\n    \"markdown\": [640, 512, [], \"f60f\", \"M593.8 59.1H46.2C20.7 59.1 0 79.8 0 105.2v301.5c0 25.5 20.7 46.2 46.2 46.2h547.7c25.5 0 46.2-20.7 46.1-46.1V105.2c0-25.4-20.7-46.1-46.2-46.1zM338.5 360.6H277v-120l-61.5 76.9-61.5-76.9v120H92.3V151.4h61.5l61.5 76.9 61.5-76.9h61.5v209.2zm135.3 3.1L381.5 256H443V151.4h61.5V256H566z\"],\n    \"mastodon\": [448, 512, [], \"f4f6\", \"M433 179.11c0-97.2-63.71-125.7-63.71-125.7-62.52-28.7-228.56-28.4-290.48 0 0 0-63.72 28.5-63.72 125.7 0 115.7-6.6 259.4 105.63 289.1 40.51 10.7 75.32 13 103.33 11.4 50.81-2.8 79.32-18.1 79.32-18.1l-1.7-36.9s-36.31 11.4-77.12 10.1c-40.41-1.4-83-4.4-89.63-54a102.54 102.54 0 0 1-.9-13.9c85.63 20.9 158.65 9.1 178.75 6.7 56.12-6.7 105-41.3 111.23-72.9 9.8-49.8 9-121.5 9-121.5zm-75.12 125.2h-46.63v-114.2c0-49.7-64-51.6-64 6.9v62.5h-46.33V197c0-58.5-64-56.6-64-6.9v114.2H90.19c0-122.1-5.2-147.9 18.41-175 25.9-28.9 79.82-30.8 103.83 6.1l11.6 19.5 11.6-19.5c24.11-37.1 78.12-34.8 103.83-6.1 23.71 27.3 18.4 53 18.4 175z\"],\n    \"maxcdn\": [512, 512, [], \"f136\", \"M461.1 442.7h-97.4L415.6 200c2.3-10.2.9-19.5-4.4-25.7-5-6.1-13.7-9.6-24.2-9.6h-49.3l-59.5 278h-97.4l59.5-278h-83.4l-59.5 278H0l59.5-278-44.6-95.4H387c39.4 0 75.3 16.3 98.3 44.9 23.3 28.6 31.8 67.4 23.6 105.9l-47.8 222.6z\"],\n    \"medapps\": [320, 512, [], \"f3c6\", \"M118.3 238.4c3.5-12.5 6.9-33.6 13.2-33.6 8.3 1.8 9.6 23.4 18.6 36.6 4.6-23.5 5.3-85.1 14.1-86.7 9-.7 19.7 66.5 22 77.5 9.9 4.1 48.9 6.6 48.9 6.6 1.9 7.3-24 7.6-40 7.8-4.6 14.8-5.4 27.7-11.4 28-4.7.2-8.2-28.8-17.5-49.6l-9.4 65.5c-4.4 13-15.5-22.5-21.9-39.3-3.3-.1-62.4-1.6-47.6-7.8l31-5zM228 448c21.2 0 21.2-32 0-32H92c-21.2 0-21.2 32 0 32h136zm-24 64c21.2 0 21.2-32 0-32h-88c-21.2 0-21.2 32 0 32h88zm34.2-141.5c3.2-18.9 5.2-36.4 11.9-48.8 7.9-14.7 16.1-28.1 24-41 24.6-40.4 45.9-75.2 45.9-125.5C320 69.6 248.2 0 160 0S0 69.6 0 155.2c0 50.2 21.3 85.1 45.9 125.5 7.9 12.9 16 26.3 24 41 6.7 12.5 8.7 29.8 11.9 48.9 3.5 21 36.1 15.7 32.6-5.1-3.6-21.7-5.6-40.7-15.3-58.6C66.5 246.5 33 211.3 33 155.2 33 87.3 90 32 160 32s127 55.3 127 123.2c0 56.1-33.5 91.3-66.1 151.6-9.7 18-11.7 37.4-15.3 58.6-3.4 20.6 29 26.4 32.6 5.1z\"],\n    \"medium\": [448, 512, [], \"f23a\", \"M0 32v448h448V32H0zm372.2 106.1l-24 23c-2.1 1.6-3.1 4.2-2.7 6.7v169.3c-.4 2.6.6 5.2 2.7 6.7l23.5 23v5.1h-118V367l24.3-23.6c2.4-2.4 2.4-3.1 2.4-6.7V199.8l-67.6 171.6h-9.1L125 199.8v115c-.7 4.8 1 9.7 4.4 13.2l31.6 38.3v5.1H71.2v-5.1l31.6-38.3c3.4-3.5 4.9-8.4 4.1-13.2v-133c.4-3.7-1-7.3-3.8-9.8L75 138.1V133h87.3l67.4 148L289 133.1h83.2v5z\"],\n    \"medium-m\": [512, 512, [], \"f3c7\", \"M71.5 142.3c.6-5.9-1.7-11.8-6.1-15.8L20.3 72.1V64h140.2l108.4 237.7L364.2 64h133.7v8.1l-38.6 37c-3.3 2.5-5 6.7-4.3 10.8v272c-.7 4.1 1 8.3 4.3 10.8l37.7 37v8.1H307.3v-8.1l39.1-37.9c3.8-3.8 3.8-5 3.8-10.8V171.2L241.5 447.1h-14.7L100.4 171.2v184.9c-1.1 7.8 1.5 15.6 7 21.2l50.8 61.6v8.1h-144v-8L65 377.3c5.4-5.6 7.9-13.5 6.5-21.2V142.3z\"],\n    \"medrt\": [544, 512, [], \"f3c8\", \"M113.7 256c0 121.8 83.9 222.8 193.5 241.1-18.7 4.5-38.2 6.9-58.2 6.9C111.4 504 0 393 0 256S111.4 8 248.9 8c20.1 0 39.6 2.4 58.2 6.9C197.5 33.2 113.7 134.2 113.7 256m297.4 100.3c-77.7 55.4-179.6 47.5-240.4-14.6 5.5 14.1 12.7 27.7 21.7 40.5 61.6 88.2 182.4 109.3 269.7 47 87.3-62.3 108.1-184.3 46.5-272.6-9-12.9-19.3-24.3-30.5-34.2 37.4 78.8 10.7 178.5-67 233.9m-218.8-244c-1.4 1-2.7 2.1-4 3.1 64.3-17.8 135.9 4 178.9 60.5 35.7 47 42.9 106.6 24.4 158 56.7-56.2 67.6-142.1 22.3-201.8-50-65.5-149.1-74.4-221.6-19.8M296 224c-4.4 0-8-3.6-8-8v-40c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v40c0 4.4-3.6 8-8 8h-40c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h40c4.4 0 8 3.6 8 8v40c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-40c0-4.4 3.6-8 8-8h40c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8h-40z\"],\n    \"meetup\": [512, 512, [], \"f2e0\", \"M99 414.3c1.1 5.7-2.3 11.1-8 12.3-5.4 1.1-10.9-2.3-12-8-1.1-5.4 2.3-11.1 7.7-12.3 5.4-1.2 11.1 2.3 12.3 8zm143.1 71.4c-6.3 4.6-8 13.4-3.7 20 4.6 6.6 13.4 8.3 20 3.7 6.3-4.6 8-13.4 3.4-20-4.2-6.5-13.1-8.3-19.7-3.7zm-86-462.3c6.3-1.4 10.3-7.7 8.9-14-1.1-6.6-7.4-10.6-13.7-9.1-6.3 1.4-10.3 7.7-9.1 14 1.4 6.6 7.6 10.6 13.9 9.1zM34.4 226.3c-10-6.9-23.7-4.3-30.6 6-6.9 10-4.3 24 5.7 30.9 10 7.1 23.7 4.6 30.6-5.7 6.9-10.4 4.3-24.1-5.7-31.2zm272-170.9c10.6-6.3 13.7-20 7.7-30.3-6.3-10.6-19.7-14-30-7.7s-13.7 20-7.4 30.6c6 10.3 19.4 13.7 29.7 7.4zm-191.1 58c7.7-5.4 9.4-16 4.3-23.7s-15.7-9.4-23.1-4.3c-7.7 5.4-9.4 16-4.3 23.7 5.1 7.8 15.6 9.5 23.1 4.3zm372.3 156c-7.4 1.7-12.3 9.1-10.6 16.9 1.4 7.4 8.9 12.3 16.3 10.6 7.4-1.4 12.3-8.9 10.6-16.6-1.5-7.4-8.9-12.3-16.3-10.9zm39.7-56.8c-1.1-5.7-6.6-9.1-12-8-5.7 1.1-9.1 6.9-8 12.6 1.1 5.4 6.6 9.1 12.3 8 5.4-1.5 9.1-6.9 7.7-12.6zM447 138.9c-8.6 6-10.6 17.7-4.9 26.3 5.7 8.6 17.4 10.6 26 4.9 8.3-6 10.3-17.7 4.6-26.3-5.7-8.7-17.4-10.9-25.7-4.9zm-6.3 139.4c26.3 43.1 15.1 100-26.3 129.1-17.4 12.3-37.1 17.7-56.9 17.1-12 47.1-69.4 64.6-105.1 32.6-1.1.9-2.6 1.7-3.7 2.9-39.1 27.1-92.3 17.4-119.4-22.3-9.7-14.3-14.6-30.6-15.1-46.9-65.4-10.9-90-94-41.1-139.7-28.3-46.9.6-107.4 53.4-114.9C151.6 70 234.1 38.6 290.1 82c67.4-22.3 136.3 29.4 130.9 101.1 41.1 12.6 52.8 66.9 19.7 95.2zm-70 74.3c-3.1-20.6-40.9-4.6-43.1-27.1-3.1-32 43.7-101.1 40-128-3.4-24-19.4-29.1-33.4-29.4-13.4-.3-16.9 2-21.4 4.6-2.9 1.7-6.6 4.9-11.7-.3-6.3-6-11.1-11.7-19.4-12.9-12.3-2-17.7 2-26.6 9.7-3.4 2.9-12 12.9-20 9.1-3.4-1.7-15.4-7.7-24-11.4-16.3-7.1-40 4.6-48.6 20-12.9 22.9-38 113.1-41.7 125.1-8.6 26.6 10.9 48.6 36.9 47.1 11.1-.6 18.3-4.6 25.4-17.4 4-7.4 41.7-107.7 44.6-112.6 2-3.4 8.9-8 14.6-5.1 5.7 3.1 6.9 9.4 6 15.1-1.1 9.7-28 70.9-28.9 77.7-3.4 22.9 26.9 26.6 38.6 4 3.7-7.1 45.7-92.6 49.4-98.3 4.3-6.3 7.4-8.3 11.7-8 3.1 0 8.3.9 7.1 10.9-1.4 9.4-35.1 72.3-38.9 87.7-4.6 20.6 6.6 41.4 24.9 50.6 11.4 5.7 62.5 15.7 58.5-11.1zm5.7 92.3c-10.3 7.4-12.9 22-5.7 32.6 7.1 10.6 21.4 13.1 32 6 10.6-7.4 13.1-22 6-32.6-7.4-10.6-21.7-13.5-32.3-6z\"],\n    \"megaport\": [496, 512, [], \"f5a3\", \"M214.5 209.6v66.2l33.5 33.5 33.3-33.3v-66.4l-33.4-33.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm145.1 414.4L367 441.6l-26-19.2v-65.5l-33.4-33.4-33.4 33.4v65.5L248 441.6l-26.1-19.2v-65.5l-33.4-33.4-33.5 33.4v65.5l-26.1 19.2-26.1-19.2v-87l59.5-59.5V188l59.5-59.5V52.9l26.1-19.2L274 52.9v75.6l59.5 59.5v87.6l59.7 59.7v87.1z\"],\n    \"mendeley\": [640, 512, [], \"f7b3\", \"M624.6 325.2c-12.3-12.4-29.7-19.2-48.4-17.2-43.3-1-49.7-34.9-37.5-98.8 22.8-57.5-14.9-131.5-87.4-130.8-77.4.7-81.7 82-130.9 82-48.1 0-54-81.3-130.9-82-72.9-.8-110.1 73.3-87.4 130.8 12.2 63.9 5.8 97.8-37.5 98.8-21.2-2.3-37 6.5-53 22.5-19.9 19.7-19.3 94.8 42.6 102.6 47.1 5.9 81.6-42.9 61.2-87.8-47.3-103.7 185.9-106.1 146.5-8.2-.1.1-.2.2-.3.4-26.8 42.8 6.8 97.4 58.8 95.2 52.1 2.1 85.4-52.6 58.8-95.2-.1-.2-.2-.3-.3-.4-39.4-97.9 193.8-95.5 146.5 8.2-4.6 10-6.7 21.3-5.7 33 4.9 53.4 68.7 74.1 104.9 35.2 17.8-14.8 23.1-65.6 0-88.3zm-303.9-19.1h-.6c-43.4 0-62.8-37.5-62.8-62.8 0-34.7 28.2-62.8 62.8-62.8h.6c34.7 0 62.8 28.1 62.8 62.8 0 25-19.2 62.8-62.8 62.8z\"],\n    \"microsoft\": [448, 512, [], \"f3ca\", \"M0 32h214.6v214.6H0V32zm233.4 0H448v214.6H233.4V32zM0 265.4h214.6V480H0V265.4zm233.4 0H448V480H233.4V265.4z\"],\n    \"mix\": [448, 512, [], \"f3cb\", \"M0 64v348.9c0 56.2 88 58.1 88 0V174.3c7.9-52.9 88-50.4 88 6.5v175.3c0 57.9 96 58 96 0V240c5.3-54.7 88-52.5 88 4.3v23.8c0 59.9 88 56.6 88 0V64H0z\"],\n    \"mixcloud\": [640, 512, [], \"f289\", \"M424.43 219.729C416.124 134.727 344.135 68 256.919 68c-72.266 0-136.224 46.516-159.205 114.074-54.545 8.029-96.63 54.822-96.63 111.582 0 62.298 50.668 112.966 113.243 112.966h289.614c52.329 0 94.969-42.362 94.969-94.693 0-45.131-32.118-83.063-74.48-92.2zm-20.489 144.53H114.327c-39.04 0-70.881-31.564-70.881-70.604s31.841-70.604 70.881-70.604c18.827 0 36.548 7.475 49.838 20.766 19.963 19.963 50.133-10.227 30.18-30.18-14.675-14.398-32.672-24.365-52.053-29.349 19.935-44.3 64.79-73.926 114.628-73.926 69.496 0 125.979 56.483 125.979 125.702 0 13.568-2.215 26.857-6.369 39.594-8.943 27.517 32.133 38.939 40.147 13.29 2.769-8.306 4.984-16.889 6.369-25.472 19.381 7.476 33.502 26.303 33.502 48.453 0 28.795-23.535 52.33-52.607 52.33zm235.069-52.33c0 44.024-12.737 86.386-37.102 122.657-4.153 6.092-10.798 9.414-17.72 9.414-16.317 0-27.127-18.826-17.443-32.949 19.381-29.349 29.903-63.682 29.903-99.122s-10.521-69.773-29.903-98.845c-15.655-22.831 19.361-47.24 35.163-23.534 24.366 35.993 37.102 78.356 37.102 122.379zm-70.88 0c0 31.565-9.137 62.021-26.857 88.325-4.153 6.091-10.798 9.136-17.72 9.136-17.201 0-27.022-18.979-17.443-32.948 13.013-19.104 19.658-41.255 19.658-64.513 0-22.981-6.645-45.408-19.658-64.512-15.761-22.986 19.008-47.095 35.163-23.535 17.719 26.026 26.857 56.483 26.857 88.047z\"],\n    \"mizuni\": [496, 512, [], \"f3cc\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm-80 351.9c-31.4 10.6-58.8 27.3-80 48.2V136c0-22.1 17.9-40 40-40s40 17.9 40 40v223.9zm120-9.9c-12.9-2-26.2-3.1-39.8-3.1-13.8 0-27.2 1.1-40.2 3.1V136c0-22.1 17.9-40 40-40s40 17.9 40 40v214zm120 57.7c-21.2-20.8-48.6-37.4-80-48V136c0-22.1 17.9-40 40-40s40 17.9 40 40v271.7z\"],\n    \"modx\": [448, 512, [], \"f285\", \"M356 241.8l36.7 23.7V480l-133-83.8L356 241.8zM440 75H226.3l-23 37.8 153.5 96.5L440 75zm-89 142.8L55.2 32v214.5l46 29L351 217.8zM97 294.2L8 437h213.7l125-200.5L97 294.2z\"],\n    \"monero\": [496, 512, [], \"f3d0\", \"M352 384h108.4C417 455.9 338.1 504 248 504S79 455.9 35.6 384H144V256.2L248 361l104-105v128zM88 336V128l159.4 159.4L408 128v208h74.8c8.5-25.1 13.2-52 13.2-80C496 119 385 8 248 8S0 119 0 256c0 28 4.6 54.9 13.2 80H88z\"],\n    \"napster\": [496, 512, [], \"f3d2\", \"M298.3 373.6c-14.2 13.6-31.3 24.1-50.4 30.5-19-6.4-36.2-16.9-50.3-30.5h100.7zm44-199.6c20-16.9 43.6-29.2 69.6-36.2V299c0 219.4-328 217.6-328 .3V137.7c25.9 6.9 49.6 19.6 69.5 36.4 56.8-40 132.5-39.9 188.9-.1zm-208.8-58.5c64.4-60 164.3-60.1 228.9-.2-7.1 3.5-13.9 7.3-20.6 11.5-58.7-30.5-129.2-30.4-187.9.1-6.3-4-13.9-8.2-20.4-11.4zM43.8 93.2v69.3c-58.4 36.5-58.4 121.1.1 158.3 26.4 245.1 381.7 240.3 407.6 1.5l.3-1.7c58.7-36.3 58.9-121.7.2-158.2V93.2c-17.3.5-34 3-50.1 7.4-82-91.5-225.5-91.5-307.5.1-16.3-4.4-33.1-7-50.6-7.5zM259.2 352s36-.3 61.3-1.5c10.2-.5 21.1-4 25.5-6.5 26.3-15.1 25.4-39.2 26.2-47.4-79.5-.6-99.9-3.9-113 55.4zm-135.5-55.3c.8 8.2-.1 32.3 26.2 47.4 4.4 2.5 15.2 6 25.5 6.5 25.3 1.1 61.3 1.5 61.3 1.5-13.2-59.4-33.7-56.1-113-55.4zm169.1 123.4c-3.2-5.3-6.9-7.3-6.9-7.3-24.8 7.3-52.2 6.9-75.9 0 0 0-2.9 1.5-6.4 6.6-2.8 4.1-3.7 9.6-3.7 9.6 29.1 17.6 67.1 17.6 96.2 0-.1-.1-.3-4-3.3-8.9z\"],\n    \"neos\": [512, 512, [], \"f612\", \"M415.44 512h-95.11L212.12 357.46v91.1L125.69 512H28V29.82L68.47 0h108.05l123.74 176.13V63.45L386.69 0h97.69v461.5zM38.77 35.27V496l72-52.88V194l215.5 307.64h84.79l52.35-38.17h-78.27L69 13zm82.54 466.61l80-58.78v-101l-79.76-114.4v220.94L49 501.89h72.34zM80.63 10.77l310.6 442.57h82.37V10.77h-79.75v317.56L170.91 10.77zM311 191.65l72 102.81V15.93l-72 53v122.72z\"],\n    \"nimblr\": [384, 512, [], \"f5a8\", \"M246.6 299.29c15.57 0 27.15 11.46 27.15 27s-11.62 27-27.15 27c-15.7 0-27.15-11.57-27.15-27s11.55-27 27.15-27zM113 326.25c0-15.61 11.68-27 27.15-27s27.15 11.46 27.15 27-11.47 27-27.15 27c-15.44 0-27.15-11.31-27.15-27M191.76 159C157 159 89.45 178.77 59.25 227L14 0v335.48C14 433.13 93.61 512 191.76 512s177.76-78.95 177.76-176.52S290.13 159 191.76 159zm0 308.12c-73.27 0-132.51-58.9-132.51-131.59s59.24-131.59 132.51-131.59 132.51 58.86 132.51 131.54S265 467.07 191.76 467.07z\"],\n    \"node\": [640, 512, [], \"f419\", \"M316.3 452c-2.1 0-4.2-.6-6.1-1.6L291 439c-2.9-1.6-1.5-2.2-.5-2.5 3.8-1.3 4.6-1.6 8.7-4 .4-.2 1-.1 1.4.1l14.8 8.8c.5.3 1.3.3 1.8 0L375 408c.5-.3.9-.9.9-1.6v-66.7c0-.7-.3-1.3-.9-1.6l-57.8-33.3c-.5-.3-1.2-.3-1.8 0l-57.8 33.3c-.6.3-.9 1-.9 1.6v66.7c0 .6.4 1.2.9 1.5l15.8 9.1c8.6 4.3 13.9-.8 13.9-5.8v-65.9c0-.9.7-1.7 1.7-1.7h7.3c.9 0 1.7.7 1.7 1.7v65.9c0 11.5-6.2 18-17.1 18-3.3 0-6 0-13.3-3.6l-15.2-8.7c-3.7-2.2-6.1-6.2-6.1-10.5v-66.7c0-4.3 2.3-8.4 6.1-10.5l57.8-33.4c3.7-2.1 8.5-2.1 12.1 0l57.8 33.4c3.7 2.2 6.1 6.2 6.1 10.5v66.7c0 4.3-2.3 8.4-6.1 10.5l-57.8 33.4c-1.7 1.1-3.8 1.7-6 1.7zm46.7-65.8c0-12.5-8.4-15.8-26.2-18.2-18-2.4-19.8-3.6-19.8-7.8 0-3.5 1.5-8.1 14.8-8.1 11.9 0 16.3 2.6 18.1 10.6.2.8.8 1.3 1.6 1.3h7.5c.5 0 .9-.2 1.2-.5.3-.4.5-.8.4-1.3-1.2-13.8-10.3-20.2-28.8-20.2-16.5 0-26.3 7-26.3 18.6 0 12.7 9.8 16.1 25.6 17.7 18.9 1.9 20.4 4.6 20.4 8.3 0 6.5-5.2 9.2-17.4 9.2-15.3 0-18.7-3.8-19.8-11.4-.1-.8-.8-1.4-1.7-1.4h-7.5c-.9 0-1.7.7-1.7 1.7 0 9.7 5.3 21.3 30.6 21.3 18.5 0 29-7.2 29-19.8zm54.5-50.1c0 6.1-5 11.1-11.1 11.1s-11.1-5-11.1-11.1c0-6.3 5.2-11.1 11.1-11.1 6-.1 11.1 4.8 11.1 11.1zm-1.8 0c0-5.2-4.2-9.3-9.4-9.3-5.1 0-9.3 4.1-9.3 9.3 0 5.2 4.2 9.4 9.3 9.4 5.2-.1 9.4-4.3 9.4-9.4zm-4.5 6.2h-2.6c-.1-.6-.5-3.8-.5-3.9-.2-.7-.4-1.1-1.3-1.1h-2.2v5h-2.4v-12.5h4.3c1.5 0 4.4 0 4.4 3.3 0 2.3-1.5 2.8-2.4 3.1 1.7.1 1.8 1.2 2.1 2.8.1 1 .3 2.7.6 3.3zm-2.8-8.8c0-1.7-1.2-1.7-1.8-1.7h-2v3.5h1.9c1.6 0 1.9-1.1 1.9-1.8zM137.3 191c0-2.7-1.4-5.1-3.7-6.4l-61.3-35.3c-1-.6-2.2-.9-3.4-1h-.6c-1.2 0-2.3.4-3.4 1L3.7 184.6C1.4 185.9 0 188.4 0 191l.1 95c0 1.3.7 2.5 1.8 3.2 1.1.7 2.5.7 3.7 0L42 268.3c2.3-1.4 3.7-3.8 3.7-6.4v-44.4c0-2.6 1.4-5.1 3.7-6.4l15.5-8.9c1.2-.7 2.4-1 3.7-1 1.3 0 2.6.3 3.7 1l15.5 8.9c2.3 1.3 3.7 3.8 3.7 6.4v44.4c0 2.6 1.4 5.1 3.7 6.4l36.4 20.9c1.1.7 2.6.7 3.7 0 1.1-.6 1.8-1.9 1.8-3.2l.2-95zM472.5 87.3v176.4c0 2.6-1.4 5.1-3.7 6.4l-61.3 35.4c-2.3 1.3-5.1 1.3-7.4 0l-61.3-35.4c-2.3-1.3-3.7-3.8-3.7-6.4v-70.8c0-2.6 1.4-5.1 3.7-6.4l61.3-35.4c2.3-1.3 5.1-1.3 7.4 0l15.3 8.8c1.7 1 3.9-.3 3.9-2.2v-94c0-2.8 3-4.6 5.5-3.2l36.5 20.4c2.3 1.2 3.8 3.7 3.8 6.4zm-46 128.9c0-.7-.4-1.3-.9-1.6l-21-12.2c-.6-.3-1.3-.3-1.9 0l-21 12.2c-.6.3-.9.9-.9 1.6v24.3c0 .7.4 1.3.9 1.6l21 12.1c.6.3 1.3.3 1.8 0l21-12.1c.6-.3.9-.9.9-1.6v-24.3zm209.8-.7c2.3-1.3 3.7-3.8 3.7-6.4V192c0-2.6-1.4-5.1-3.7-6.4l-60.9-35.4c-2.3-1.3-5.1-1.3-7.4 0l-61.3 35.4c-2.3 1.3-3.7 3.8-3.7 6.4v70.8c0 2.7 1.4 5.1 3.7 6.4l60.9 34.7c2.2 1.3 5 1.3 7.3 0l36.8-20.5c2.5-1.4 2.5-5 0-6.4L550 241.6c-1.2-.7-1.9-1.9-1.9-3.2v-22.2c0-1.3.7-2.5 1.9-3.2l19.2-11.1c1.1-.7 2.6-.7 3.7 0l19.2 11.1c1.1.7 1.9 1.9 1.9 3.2v17.4c0 2.8 3.1 4.6 5.6 3.2l36.7-21.3zM559 219c-.4.3-.7.7-.7 1.2v13.6c0 .5.3 1 .7 1.2l11.8 6.8c.4.3 1 .3 1.4 0L584 235c.4-.3.7-.7.7-1.2v-13.6c0-.5-.3-1-.7-1.2l-11.8-6.8c-.4-.3-1-.3-1.4 0L559 219zm-254.2 43.5v-70.4c0-2.6-1.6-5.1-3.9-6.4l-61.1-35.2c-2.1-1.2-5-1.4-7.4 0l-61.1 35.2c-2.3 1.3-3.9 3.7-3.9 6.4v70.4c0 2.8 1.9 5.2 4 6.4l61.2 35.2c2.4 1.4 5.2 1.3 7.4 0l61-35.2c1.8-1 3.1-2.7 3.6-4.7.1-.5.2-1.1.2-1.7zm-74.3-124.9l-.8.5h1.1l-.3-.5zm76.2 130.2l-.4-.7v.9l.4-.2z\"],\n    \"node-js\": [448, 512, [], \"f3d3\", \"M224 508c-6.7 0-13.5-1.8-19.4-5.2l-61.7-36.5c-9.2-5.2-4.7-7-1.7-8 12.3-4.3 14.8-5.2 27.9-12.7 1.4-.8 3.2-.5 4.6.4l47.4 28.1c1.7 1 4.1 1 5.7 0l184.7-106.6c1.7-1 2.8-3 2.8-5V149.3c0-2.1-1.1-4-2.9-5.1L226.8 37.7c-1.7-1-4-1-5.7 0L36.6 144.3c-1.8 1-2.9 3-2.9 5.1v213.1c0 2 1.1 4 2.9 4.9l50.6 29.2c27.5 13.7 44.3-2.4 44.3-18.7V167.5c0-3 2.4-5.3 5.4-5.3h23.4c2.9 0 5.4 2.3 5.4 5.3V378c0 36.6-20 57.6-54.7 57.6-10.7 0-19.1 0-42.5-11.6l-48.4-27.9C8.1 389.2.7 376.3.7 362.4V149.3c0-13.8 7.4-26.8 19.4-33.7L204.6 9c11.7-6.6 27.2-6.6 38.8 0l184.7 106.7c12 6.9 19.4 19.8 19.4 33.7v213.1c0 13.8-7.4 26.7-19.4 33.7L243.4 502.8c-5.9 3.4-12.6 5.2-19.4 5.2zm149.1-210.1c0-39.9-27-50.5-83.7-58-57.4-7.6-63.2-11.5-63.2-24.9 0-11.1 4.9-25.9 47.4-25.9 37.9 0 51.9 8.2 57.7 33.8.5 2.4 2.7 4.2 5.2 4.2h24c1.5 0 2.9-.6 3.9-1.7s1.5-2.6 1.4-4.1c-3.7-44.1-33-64.6-92.2-64.6-52.7 0-84.1 22.2-84.1 59.5 0 40.4 31.3 51.6 81.8 56.6 60.5 5.9 65.2 14.8 65.2 26.7 0 20.6-16.6 29.4-55.5 29.4-48.9 0-59.6-12.3-63.2-36.6-.4-2.6-2.6-4.5-5.3-4.5h-23.9c-3 0-5.3 2.4-5.3 5.3 0 31.1 16.9 68.2 97.8 68.2 58.4-.1 92-23.2 92-63.4z\"],\n    \"npm\": [576, 512, [], \"f3d4\", \"M288 288h-32v-64h32v64zm288-128v192H288v32H160v-32H0V160h576zm-416 32H32v128h64v-96h32v96h32V192zm160 0H192v160h64v-32h64V192zm224 0H352v128h64v-96h32v96h32v-96h32v96h32V192z\"],\n    \"ns8\": [640, 512, [], \"f3d5\", \"M187.1 159.9l-34.2 113.7-54.5-113.7H49L0 320h44.9L76 213.5 126.6 320h56.9L232 159.9h-44.9zm452.5-.9c-2.9-18-23.9-28.1-42.1-31.3-44.6-7.8-101.9 16.3-88.5 58.8v.1c-43.8 8.7-74.3 26.8-94.2 48.2-3-9.8-13.6-16.6-34-16.6h-87.6c-9.3 0-12.9-2.3-11.5-7.4 1.6-5.5 1.9-6.8 3.7-12.2 2.1-6.4 7.8-7.1 13.3-7.1h133.5l9.7-31.5c-139.7 0-144.5-.5-160.1 1.2-12.3 1.3-23.5 4.8-30.6 15-6.8 9.9-14.4 35.6-17.6 47.1-5.4 19.4-.6 28.6 32.8 28.6h87.3c7.8 0 8.8 2.7 7.7 6.6-1.1 4.4-2.8 10-4.5 14.6-1.6 4.2-4.7 7.4-13.8 7.4H216.3L204.7 320c139.9 0 145.3-.6 160.9-2.3 6.6-.7 13-2.1 18.5-4.9.2 3.7.5 7.3 1.2 10.8 5.4 30.5 27.4 52.3 56.8 59.5 48.6 11.9 108.7-16.8 135.1-68 18.7-36.2 14.1-76.2-3.4-105.5h.1c29.6-5.9 70.3-22 65.7-50.6zM530.7 263.7c-5.9 29.5-36.6 47.8-61.6 43.9-30.9-4.8-38.5-39.5-14.1-64.8 16.2-16.8 45.2-24 68.5-26.9 6.7 14.1 10.3 32 7.2 47.8zm21.8-83.1c-4.2-6-9.8-18.5-2.5-26.3 6.7-7.2 20.9-10.1 31.8-7.7 15.3 3.4 19.7 15.9 4.9 24.4-10.7 6.1-23.6 8.1-34.2 9.6z\"],\n    \"nutritionix\": [400, 512, [], \"f3d6\", \"M88 8.1S221.4-.1 209 112.5c0 0 19.1-74.9 103-40.6 0 0-17.7 74-88 56 0 0 14.6-54.6 66.1-56.6 0 0-39.9-10.3-82.1 48.8 0 0-19.8-94.5-93.6-99.7 0 0 75.2 19.4 77.6 107.5 0 .1-106.4 7-104-119.8zm312 315.6c0 48.5-9.7 95.3-32 132.3-42.2 30.9-105 48-168 48-62.9 0-125.8-17.1-168-48C9.7 419 0 372.2 0 323.7 0 275.3 17.7 229 40 192c42.2-30.9 97.1-48.6 160-48.6 63 0 117.8 17.6 160 48.6 22.3 37 40 83.3 40 131.7zM120 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM192 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM264 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM336 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm24-39.6c-4.8-22.3-7.4-36.9-16-56-38.8-19.9-90.5-32-144-32S94.8 180.1 56 200c-8.8 19.5-11.2 33.9-16 56 42.2-7.9 98.7-14.8 160-14.8s117.8 6.9 160 14.8z\"],\n    \"odnoklassniki\": [320, 512, [], \"f263\", \"M275.1 334c-27.4 17.4-65.1 24.3-90 26.9l20.9 20.6 76.3 76.3c27.9 28.6-17.5 73.3-45.7 45.7-19.1-19.4-47.1-47.4-76.3-76.6L84 503.4c-28.2 27.5-73.6-17.6-45.4-45.7 19.4-19.4 47.1-47.4 76.3-76.3l20.6-20.6c-24.6-2.6-62.9-9.1-90.6-26.9-32.6-21-46.9-33.3-34.3-59 7.4-14.6 27.7-26.9 54.6-5.7 0 0 36.3 28.9 94.9 28.9s94.9-28.9 94.9-28.9c26.9-21.1 47.1-8.9 54.6 5.7 12.4 25.7-1.9 38-34.5 59.1zM30.3 129.7C30.3 58 88.6 0 160 0s129.7 58 129.7 129.7c0 71.4-58.3 129.4-129.7 129.4s-129.7-58-129.7-129.4zm66 0c0 35.1 28.6 63.7 63.7 63.7s63.7-28.6 63.7-63.7c0-35.4-28.6-64-63.7-64s-63.7 28.6-63.7 64z\"],\n    \"odnoklassniki-square\": [448, 512, [], \"f264\", \"M184.2 177.1c0-22.1 17.9-40 39.8-40s39.8 17.9 39.8 40c0 22-17.9 39.8-39.8 39.8s-39.8-17.9-39.8-39.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-305.1 97.1c0 44.6 36.4 80.9 81.1 80.9s81.1-36.2 81.1-80.9c0-44.8-36.4-81.1-81.1-81.1s-81.1 36.2-81.1 81.1zm174.5 90.7c-4.6-9.1-17.3-16.8-34.1-3.6 0 0-22.7 18-59.3 18s-59.3-18-59.3-18c-16.8-13.2-29.5-5.5-34.1 3.6-7.9 16.1 1.1 23.7 21.4 37 17.3 11.1 41.2 15.2 56.6 16.8l-12.9 12.9c-18.2 18-35.5 35.5-47.7 47.7-17.6 17.6 10.7 45.8 28.4 28.6l47.7-47.9c18.2 18.2 35.7 35.7 47.7 47.9 17.6 17.2 46-10.7 28.6-28.6l-47.7-47.7-13-12.9c15.5-1.6 39.1-5.9 56.2-16.8 20.4-13.3 29.3-21 21.5-37z\"],\n    \"old-republic\": [496, 512, [], \"f510\", \"M235.76 10.23c7.5-.31 15-.28 22.5-.09 3.61.14 7.2.4 10.79.73 4.92.27 9.79 1.03 14.67 1.62 2.93.43 5.83.98 8.75 1.46 7.9 1.33 15.67 3.28 23.39 5.4 12.24 3.47 24.19 7.92 35.76 13.21 26.56 12.24 50.94 29.21 71.63 49.88 20.03 20.09 36.72 43.55 48.89 69.19 1.13 2.59 2.44 5.1 3.47 7.74 2.81 6.43 5.39 12.97 7.58 19.63 4.14 12.33 7.34 24.99 9.42 37.83.57 3.14 1.04 6.3 1.4 9.47.55 3.83.94 7.69 1.18 11.56.83 8.34.84 16.73.77 25.1-.07 4.97-.26 9.94-.75 14.89-.24 3.38-.51 6.76-.98 10.12-.39 2.72-.63 5.46-1.11 8.17-.9 5.15-1.7 10.31-2.87 15.41-4.1 18.5-10.3 36.55-18.51 53.63-15.77 32.83-38.83 62.17-67.12 85.12a246.503 246.503 0 0 1-56.91 34.86c-6.21 2.68-12.46 5.25-18.87 7.41-3.51 1.16-7.01 2.38-10.57 3.39-6.62 1.88-13.29 3.64-20.04 5-4.66.91-9.34 1.73-14.03 2.48-5.25.66-10.5 1.44-15.79 1.74-6.69.66-13.41.84-20.12.81-6.82.03-13.65-.12-20.45-.79-3.29-.23-6.57-.5-9.83-.95-2.72-.39-5.46-.63-8.17-1.11-4.12-.72-8.25-1.37-12.35-2.22-4.25-.94-8.49-1.89-12.69-3.02-8.63-2.17-17.08-5.01-25.41-8.13-10.49-4.12-20.79-8.75-30.64-14.25-2.14-1.15-4.28-2.29-6.35-3.57-11.22-6.58-21.86-14.1-31.92-22.34-34.68-28.41-61.41-66.43-76.35-108.7-3.09-8.74-5.71-17.65-7.8-26.68-1.48-6.16-2.52-12.42-3.58-18.66-.4-2.35-.61-4.73-.95-7.09-.6-3.96-.75-7.96-1.17-11.94-.8-9.47-.71-18.99-.51-28.49.14-3.51.34-7.01.7-10.51.31-3.17.46-6.37.92-9.52.41-2.81.65-5.65 1.16-8.44.7-3.94 1.3-7.9 2.12-11.82 3.43-16.52 8.47-32.73 15.26-48.18 1.15-2.92 2.59-5.72 3.86-8.59 8.05-16.71 17.9-32.56 29.49-47.06 20-25.38 45.1-46.68 73.27-62.47 7.5-4.15 15.16-8.05 23.07-11.37 15.82-6.88 32.41-11.95 49.31-15.38 3.51-.67 7.04-1.24 10.56-1.85 2.62-.47 5.28-.7 7.91-1.08 3.53-.53 7.1-.68 10.65-1.04 2.46-.24 4.91-.36 7.36-.51m8.64 24.41c-9.23.1-18.43.99-27.57 2.23-7.3 1.08-14.53 2.6-21.71 4.3-13.91 3.5-27.48 8.34-40.46 14.42-10.46 4.99-20.59 10.7-30.18 17.22-4.18 2.92-8.4 5.8-12.34 9.03-5.08 3.97-9.98 8.17-14.68 12.59-2.51 2.24-4.81 4.7-7.22 7.06-28.22 28.79-48.44 65.39-57.5 104.69-2.04 8.44-3.54 17.02-4.44 25.65-1.1 8.89-1.44 17.85-1.41 26.8.11 7.14.38 14.28 1.22 21.37.62 7.12 1.87 14.16 3.2 21.18 1.07 4.65 2.03 9.32 3.33 13.91 6.29 23.38 16.5 45.7 30.07 65.75 8.64 12.98 18.78 24.93 29.98 35.77 16.28 15.82 35.05 29.04 55.34 39.22 7.28 3.52 14.66 6.87 22.27 9.63 5.04 1.76 10.06 3.57 15.22 4.98 11.26 3.23 22.77 5.6 34.39 7.06 2.91.29 5.81.61 8.72.9 13.82 1.08 27.74 1 41.54-.43 4.45-.6 8.92-.99 13.35-1.78 3.63-.67 7.28-1.25 10.87-2.1 4.13-.98 8.28-1.91 12.36-3.07 26.5-7.34 51.58-19.71 73.58-36.2 15.78-11.82 29.96-25.76 42.12-41.28 3.26-4.02 6.17-8.31 9.13-12.55 3.39-5.06 6.58-10.25 9.6-15.54 2.4-4.44 4.74-8.91 6.95-13.45 5.69-12.05 10.28-24.62 13.75-37.49 2.59-10.01 4.75-20.16 5.9-30.45 1.77-13.47 1.94-27.1 1.29-40.65-.29-3.89-.67-7.77-1-11.66-2.23-19.08-6.79-37.91-13.82-55.8-5.95-15.13-13.53-29.63-22.61-43.13-12.69-18.8-28.24-35.68-45.97-49.83-25.05-20-54.47-34.55-85.65-42.08-7.78-1.93-15.69-3.34-23.63-4.45-3.91-.59-7.85-.82-11.77-1.24-7.39-.57-14.81-.72-22.22-.58zM139.26 83.53c13.3-8.89 28.08-15.38 43.3-20.18-3.17 1.77-6.44 3.38-9.53 5.29-11.21 6.68-21.52 14.9-30.38 24.49-6.8 7.43-12.76 15.73-17.01 24.89-3.29 6.86-5.64 14.19-6.86 21.71-.93 4.85-1.3 9.81-1.17 14.75.13 13.66 4.44 27.08 11.29 38.82 5.92 10.22 13.63 19.33 22.36 27.26 4.85 4.36 10.24 8.09 14.95 12.6 2.26 2.19 4.49 4.42 6.43 6.91 2.62 3.31 4.89 6.99 5.99 11.1.9 3.02.66 6.2.69 9.31.02 4.1-.04 8.2.03 12.3.14 3.54-.02 7.09.11 10.63.08 2.38.02 4.76.05 7.14.16 5.77.06 11.53.15 17.3.11 2.91.02 5.82.13 8.74.03 1.63.13 3.28-.03 4.91-.91.12-1.82.18-2.73.16-10.99 0-21.88-2.63-31.95-6.93-6-2.7-11.81-5.89-17.09-9.83-5.75-4.19-11.09-8.96-15.79-14.31-6.53-7.24-11.98-15.39-16.62-23.95-1.07-2.03-2.24-4.02-3.18-6.12-1.16-2.64-2.62-5.14-3.67-7.82-4.05-9.68-6.57-19.94-8.08-30.31-.49-4.44-1.09-8.88-1.2-13.35-.7-15.73.84-31.55 4.67-46.82 2.12-8.15 4.77-16.18 8.31-23.83 6.32-14.2 15.34-27.18 26.3-38.19 6.28-6.2 13.13-11.84 20.53-16.67zm175.37-20.12c2.74.74 5.41 1.74 8.09 2.68 6.36 2.33 12.68 4.84 18.71 7.96 13.11 6.44 25.31 14.81 35.82 24.97 10.2 9.95 18.74 21.6 25.14 34.34 1.28 2.75 2.64 5.46 3.81 8.26 6.31 15.1 10 31.26 11.23 47.57.41 4.54.44 9.09.45 13.64.07 11.64-1.49 23.25-4.3 34.53-1.97 7.27-4.35 14.49-7.86 21.18-3.18 6.64-6.68 13.16-10.84 19.24-6.94 10.47-15.6 19.87-25.82 27.22-10.48 7.64-22.64 13.02-35.4 15.38-3.51.69-7.08 1.08-10.66 1.21-1.85.06-3.72.16-5.56-.1-.28-2.15 0-4.31-.01-6.46-.03-3.73.14-7.45.1-11.17.19-7.02.02-14.05.21-21.07.03-2.38-.03-4.76.03-7.14.17-5.07-.04-10.14.14-15.21.1-2.99-.24-6.04.51-8.96.66-2.5 1.78-4.86 3.09-7.08 4.46-7.31 11.06-12.96 17.68-18.26 5.38-4.18 10.47-8.77 15.02-13.84 7.68-8.37 14.17-17.88 18.78-28.27 2.5-5.93 4.52-12.1 5.55-18.46.86-4.37 1.06-8.83 1.01-13.27-.02-7.85-1.4-15.65-3.64-23.17-1.75-5.73-4.27-11.18-7.09-16.45-3.87-6.93-8.65-13.31-13.96-19.2-9.94-10.85-21.75-19.94-34.6-27.1-1.85-1.02-3.84-1.82-5.63-2.97zm-100.8 58.45c.98-1.18 1.99-2.33 3.12-3.38-.61.93-1.27 1.81-1.95 2.68-3.1 3.88-5.54 8.31-7.03 13.06-.87 3.27-1.68 6.6-1.73 10-.07 2.52-.08 5.07.32 7.57 1.13 7.63 4.33 14.85 8.77 21.12 2 2.7 4.25 5.27 6.92 7.33 1.62 1.27 3.53 2.09 5.34 3.05 3.11 1.68 6.32 3.23 9.07 5.48 2.67 2.09 4.55 5.33 4.4 8.79-.01 73.67 0 147.34-.01 221.02 0 1.35-.08 2.7.04 4.04.13 1.48.82 2.83 1.47 4.15.86 1.66 1.78 3.34 3.18 4.62.85.77 1.97 1.4 3.15 1.24 1.5-.2 2.66-1.35 3.45-2.57.96-1.51 1.68-3.16 2.28-4.85.76-2.13.44-4.42.54-6.63.14-4.03-.02-8.06.14-12.09.03-5.89.03-11.77.06-17.66.14-3.62.03-7.24.11-10.86.15-4.03-.02-8.06.14-12.09.03-5.99.03-11.98.07-17.97.14-3.62.02-7.24.11-10.86.14-3.93-.02-7.86.14-11.78.03-5.99.03-11.98.06-17.97.16-3.94-.01-7.88.19-11.82.29 1.44.13 2.92.22 4.38.19 3.61.42 7.23.76 10.84.32 3.44.44 6.89.86 10.32.37 3.1.51 6.22.95 9.31.57 4.09.87 8.21 1.54 12.29 1.46 9.04 2.83 18.11 5.09 26.99 1.13 4.82 2.4 9.61 4 14.3 2.54 7.9 5.72 15.67 10.31 22.62 1.73 2.64 3.87 4.98 6.1 7.21.27.25.55.51.88.71.6.25 1.31-.07 1.7-.57.71-.88 1.17-1.94 1.7-2.93 4.05-7.8 8.18-15.56 12.34-23.31.7-1.31 1.44-2.62 2.56-3.61 1.75-1.57 3.84-2.69 5.98-3.63 2.88-1.22 5.9-2.19 9.03-2.42 6.58-.62 13.11.75 19.56 1.85 3.69.58 7.4 1.17 11.13 1.41 3.74.1 7.48.05 11.21-.28 8.55-.92 16.99-2.96 24.94-6.25 5.3-2.24 10.46-4.83 15.31-7.93 11.46-7.21 21.46-16.57 30.04-27.01 1.17-1.42 2.25-2.9 3.46-4.28-1.2 3.24-2.67 6.37-4.16 9.48-1.25 2.9-2.84 5.61-4.27 8.42-5.16 9.63-11.02 18.91-17.75 27.52-4.03 5.21-8.53 10.05-13.33 14.57-6.64 6.05-14.07 11.37-22.43 14.76-8.21 3.37-17.31 4.63-26.09 3.29-3.56-.58-7.01-1.69-10.41-2.88-2.79-.97-5.39-2.38-8.03-3.69-3.43-1.71-6.64-3.81-9.71-6.08 2.71 3.06 5.69 5.86 8.7 8.61 4.27 3.76 8.74 7.31 13.63 10.23 3.98 2.45 8.29 4.4 12.84 5.51 1.46.37 2.96.46 4.45.6-1.25 1.1-2.63 2.04-3.99 2.98-9.61 6.54-20.01 11.86-30.69 16.43-20.86 8.7-43.17 13.97-65.74 15.34-4.66.24-9.32.36-13.98.36-4.98-.11-9.97-.13-14.92-.65-11.2-.76-22.29-2.73-33.17-5.43-10.35-2.71-20.55-6.12-30.3-10.55-8.71-3.86-17.12-8.42-24.99-13.79-1.83-1.31-3.74-2.53-5.37-4.08 6.6-1.19 13.03-3.39 18.99-6.48 5.74-2.86 10.99-6.66 15.63-11.07 2.24-2.19 4.29-4.59 6.19-7.09-3.43 2.13-6.93 4.15-10.62 5.78-4.41 2.16-9.07 3.77-13.81 5.02-5.73 1.52-11.74 1.73-17.61 1.14-8.13-.95-15.86-4.27-22.51-8.98-4.32-2.94-8.22-6.43-11.96-10.06-9.93-10.16-18.2-21.81-25.66-33.86-3.94-6.27-7.53-12.75-11.12-19.22-1.05-2.04-2.15-4.05-3.18-6.1 2.85 2.92 5.57 5.97 8.43 8.88 8.99 8.97 18.56 17.44 29.16 24.48 7.55 4.9 15.67 9.23 24.56 11.03 3.11.73 6.32.47 9.47.81 2.77.28 5.56.2 8.34.3 5.05.06 10.11.04 15.16-.16 3.65-.16 7.27-.66 10.89-1.09 2.07-.25 4.11-.71 6.14-1.2 3.88-.95 8.11-.96 11.83.61 4.76 1.85 8.44 5.64 11.38 9.71 2.16 3.02 4.06 6.22 5.66 9.58 1.16 2.43 2.46 4.79 3.55 7.26 1 2.24 2.15 4.42 3.42 6.52.67 1.02 1.4 2.15 2.62 2.55 1.06-.75 1.71-1.91 2.28-3.03 2.1-4.16 3.42-8.65 4.89-13.05 2.02-6.59 3.78-13.27 5.19-20.02 2.21-9.25 3.25-18.72 4.54-28.13.56-3.98.83-7.99 1.31-11.97.87-10.64 1.9-21.27 2.24-31.94.08-1.86.24-3.71.25-5.57.01-4.35.25-8.69.22-13.03-.01-2.38-.01-4.76 0-7.13.05-5.07-.2-10.14-.22-15.21-.2-6.61-.71-13.2-1.29-19.78-.73-5.88-1.55-11.78-3.12-17.51-2.05-7.75-5.59-15.03-9.8-21.82-3.16-5.07-6.79-9.88-11.09-14.03-3.88-3.86-8.58-7.08-13.94-8.45-1.5-.41-3.06-.45-4.59-.64.07-2.99.7-5.93 1.26-8.85 1.59-7.71 3.8-15.3 6.76-22.6 1.52-4.03 3.41-7.9 5.39-11.72 3.45-6.56 7.62-12.79 12.46-18.46zm31.27 1.7c.35-.06.71-.12 1.07-.19.19 1.79.09 3.58.1 5.37v38.13c-.01 1.74.13 3.49-.15 5.22-.36-.03-.71-.05-1.06-.05-.95-3.75-1.72-7.55-2.62-11.31-.38-1.53-.58-3.09-1.07-4.59-1.7-.24-3.43-.17-5.15-.2-5.06-.01-10.13 0-15.19-.01-1.66-.01-3.32.09-4.98-.03-.03-.39-.26-.91.16-1.18 1.28-.65 2.72-.88 4.06-1.35 3.43-1.14 6.88-2.16 10.31-3.31 1.39-.48 2.9-.72 4.16-1.54.04-.56.02-1.13-.05-1.68-1.23-.55-2.53-.87-3.81-1.28-3.13-1.03-6.29-1.96-9.41-3.02-1.79-.62-3.67-1-5.41-1.79-.03-.37-.07-.73-.11-1.09 5.09-.19 10.2.06 15.3-.12 3.36-.13 6.73.08 10.09-.07.12-.39.26-.77.37-1.16 1.08-4.94 2.33-9.83 3.39-14.75zm5.97-.2c.36.05.72.12 1.08.2.98 3.85 1.73 7.76 2.71 11.61.36 1.42.56 2.88 1.03 4.27 2.53.18 5.07-.01 7.61.05 5.16.12 10.33.12 15.49.07.76-.01 1.52.03 2.28.08-.04.36-.07.72-.1 1.08-1.82.83-3.78 1.25-5.67 1.89-3.73 1.23-7.48 2.39-11.22 3.57-.57.17-1.12.42-1.67.64-.15.55-.18 1.12-.12 1.69.87.48 1.82.81 2.77 1.09 4.88 1.52 9.73 3.14 14.63 4.6.38.13.78.27 1.13.49.4.27.23.79.15 1.18-1.66.13-3.31.03-4.97.04-5.17.01-10.33-.01-15.5.01-1.61.03-3.22-.02-4.82.21-.52 1.67-.72 3.42-1.17 5.11-.94 3.57-1.52 7.24-2.54 10.78-.36.01-.71.02-1.06.06-.29-1.73-.15-3.48-.15-5.22v-38.13c.02-1.78-.08-3.58.11-5.37zM65.05 168.33c1.12-2.15 2.08-4.4 3.37-6.46-1.82 7.56-2.91 15.27-3.62 23-.8 7.71-.85 15.49-.54 23.23 1.05 19.94 5.54 39.83 14.23 57.88 2.99 5.99 6.35 11.83 10.5 17.11 6.12 7.47 12.53 14.76 19.84 21.09 4.8 4.1 9.99 7.78 15.54 10.8 3.27 1.65 6.51 3.39 9.94 4.68 5.01 2.03 10.19 3.61 15.42 4.94 3.83.96 7.78 1.41 11.52 2.71 5 1.57 9.47 4.61 13.03 8.43 4.93 5.23 8.09 11.87 10.2 18.67.99 2.9 1.59 5.91 2.17 8.92.15.75.22 1.52.16 2.29-6.5 2.78-13.26 5.06-20.26 6.18-4.11.78-8.29.99-12.46 1.08-10.25.24-20.47-1.76-30.12-5.12-3.74-1.42-7.49-2.85-11.03-4.72-8.06-3.84-15.64-8.7-22.46-14.46-2.92-2.55-5.83-5.13-8.4-8.03-9.16-9.83-16.3-21.41-21.79-33.65-2.39-5.55-4.61-11.18-6.37-16.96-1.17-3.94-2.36-7.89-3.26-11.91-.75-2.94-1.22-5.95-1.87-8.92-.46-2.14-.69-4.32-1.03-6.48-.85-5.43-1.28-10.93-1.33-16.43.11-6.18.25-12.37 1.07-18.5.4-2.86.67-5.74 1.15-8.6.98-5.7 2.14-11.37 3.71-16.93 3.09-11.65 7.48-22.95 12.69-33.84zm363.73-6.44c1.1 1.66 1.91 3.48 2.78 5.26 2.1 4.45 4.24 8.9 6.02 13.49 7.61 18.76 12.3 38.79 13.04 59.05.02 1.76.07 3.52.11 5.29.13 9.57-1.27 19.09-3.18 28.45-.73 3.59-1.54 7.17-2.58 10.69-4.04 14.72-10 29-18.41 41.78-8.21 12.57-19.01 23.55-31.84 31.41-5.73 3.59-11.79 6.64-18.05 9.19-5.78 2.19-11.71 4.03-17.8 5.11-6.4 1.05-12.91 1.52-19.4 1.23-7.92-.48-15.78-2.07-23.21-4.85-1.94-.8-3.94-1.46-5.84-2.33-.21-1.51.25-2.99.53-4.46 1.16-5.74 3.03-11.36 5.7-16.58 2.37-4.51 5.52-8.65 9.46-11.9 2.43-2.05 5.24-3.61 8.16-4.83 3.58-1.5 7.47-1.97 11.24-2.83 7.23-1.71 14.37-3.93 21.15-7 10.35-4.65 19.71-11.38 27.65-19.46 1.59-1.61 3.23-3.18 4.74-4.87 3.37-3.76 6.71-7.57 9.85-11.53 7.48-10.07 12.82-21.59 16.71-33.48 1.58-5.3 3.21-10.6 4.21-16.05.63-2.87 1.04-5.78 1.52-8.68.87-6.09 1.59-12.22 1.68-18.38.12-6.65.14-13.32-.53-19.94-.73-7.99-1.87-15.96-3.71-23.78z\"],\n    \"opencart\": [640, 512, [], \"f23d\", \"M423.3 440.7c0 25.3-20.3 45.6-45.6 45.6s-45.8-20.3-45.8-45.6 20.6-45.8 45.8-45.8c25.4 0 45.6 20.5 45.6 45.8zm-253.9-45.8c-25.3 0-45.6 20.6-45.6 45.8s20.3 45.6 45.6 45.6 45.8-20.3 45.8-45.6-20.5-45.8-45.8-45.8zm291.7-270C158.9 124.9 81.9 112.1 0 25.7c34.4 51.7 53.3 148.9 373.1 144.2 333.3-5 130 86.1 70.8 188.9 186.7-166.7 319.4-233.9 17.2-233.9z\"],\n    \"openid\": [448, 512, [], \"f19b\", \"M271.5 432l-68 32C88.5 453.7 0 392.5 0 318.2c0-71.5 82.5-131 191.7-144.3v43c-71.5 12.5-124 53-124 101.3 0 51 58.5 93.3 135.7 103v-340l68-33.2v384zM448 291l-131.3-28.5 36.8-20.7c-19.5-11.5-43.5-20-70-24.8v-43c46.2 5.5 87.7 19.5 120.3 39.3l35-19.8L448 291z\"],\n    \"opera\": [496, 512, [], \"f26a\", \"M313.9 32.7c-170.2 0-252.6 223.8-147.5 355.1 36.5 45.4 88.6 75.6 147.5 75.6 36.3 0 70.3-11.1 99.4-30.4-43.8 39.2-101.9 63-165.3 63-3.9 0-8 0-11.9-.3C104.6 489.6 0 381.1 0 248 0 111 111 0 248 0h.8c63.1.3 120.7 24.1 164.4 63.1-29-19.4-63.1-30.4-99.3-30.4zm101.8 397.7c-40.9 24.7-90.7 23.6-132-5.8 56.2-20.5 97.7-91.6 97.7-176.6 0-84.7-41.2-155.8-97.4-176.6 41.8-29.2 91.2-30.3 132.9-5 105.9 98.7 105.5 265.7-1.2 364z\"],\n    \"optin-monster\": [576, 512, [], \"f23c\", \"M572.6 421.4c5.6-9.5 4.7-15.2-5.4-11.6-3-4.9-7-9.5-11.1-13.8 2.9-9.7-.7-14.2-10.8-9.2-4.6-3.2-10.3-6.5-15.9-9.2 0-15.1-11.6-11.6-17.6-5.7-10.4-1.5-18.7-.3-26.8 5.7.3-6.5.3-13 .3-19.7 12.6 0 40.2-11 45.9-36.2 1.4-6.8 1.6-13.8-.3-21.9-3-13.5-14.3-21.3-25.1-25.7-.8-5.9-7.6-14.3-14.9-15.9s-12.4 4.9-14.1 10.3c-8.5 0-19.2 2.8-21.1 8.4-5.4-.5-11.1-1.4-16.8-1.9 2.7-1.9 5.4-3.5 8.4-4.6 5.4-9.2 14.6-11.4 25.7-11.6V256c19.5-.5 43-5.9 53.8-18.1 12.7-13.8 14.6-37.3 12.4-55.1-2.4-17.3-9.7-37.6-24.6-48.1-8.4-5.9-21.6-.8-22.7 9.5-2.2 19.6 1.2 30-38.6 25.1-10.3-23.8-24.6-44.6-42.7-60C341 49.6 242.9 55.5 166.4 71.7c19.7 4.6 41.1 8.6 59.7 16.5-26.2 2.4-52.7 11.3-76.2 23.2-32.8 17-44 29.9-56.7 42.4 14.9-2.2 28.9-5.1 43.8-3.8-9.7 5.4-18.4 12.2-26.5 20-25.8.9-23.8-5.3-26.2-25.9-1.1-10.5-14.3-15.4-22.7-9.7-28.1 19.9-33.5 79.9-12.2 103.5 10.8 12.2 35.1 17.3 54.9 17.8-.3 1.1-.3 1.9-.3 2.7 10.8.5 19.5 2.7 24.6 11.6 3 1.1 5.7 2.7 8.1 4.6-5.4.5-11.1 1.4-16.5 1.9-3.3-6.6-13.7-8.1-21.1-8.1-1.6-5.7-6.5-12.2-14.1-10.3-6.8 1.9-14.1 10-14.9 15.9-22.5 9.5-30.1 26.8-25.1 47.6 5.3 24.8 33 36.2 45.9 36.2v19.7c-6.6-5-14.3-7.5-26.8-5.7-5.5-5.5-17.3-10.1-17.3 5.7-5.9 2.7-11.4 5.9-15.9 9.2-9.8-4.9-13.6-1.7-11.1 9.2-4.1 4.3-7.8 8.6-11.1 13.8-10.2-3.7-11 2.2-5.4 11.6-1.1 3.5-1.6 7-1.9 10.8-.5 31.6 44.6 64 73.5 65.1 17.3.5 34.6-8.4 43-23.5 113.2 4.9 226.7 4.1 340.2 0 8.1 15.1 25.4 24.3 42.7 23.5 29.2-1.1 74.3-33.5 73.5-65.1.2-3.7-.7-7.2-1.7-10.7zm-73.8-254c1.1-3 2.4-8.4 2.4-14.6 0-5.9 6.8-8.1 14.1-.8 11.1 11.6 14.9 40.5 13.8 51.1-4.1-13.6-13-29-30.3-35.7zm-4.6 6.7c19.5 6.2 28.6 27.6 29.7 48.9-1.1 2.7-3 5.4-4.9 7.6-5.7 5.9-15.4 10-26.2 12.2 4.3-21.3.3-47.3-12.7-63 4.9-.8 10.9-2.4 14.1-5.7zm-24.1 6.8c13.8 11.9 20 39.2 14.1 63.5-4.1.5-8.1.8-11.6.8-1.9-21.9-6.8-44-14.3-64.6 3.7.3 8.1.3 11.8.3zM47.5 203c-1.1-10.5 2.4-39.5 13.8-51.1 7-7.3 14.1-5.1 14.1.8 0 6.2 1.4 11.6 2.4 14.6-17.3 6.8-26.2 22.2-30.3 35.7zm9.7 27.6c-1.9-2.2-3.5-4.9-4.9-7.6 1.4-21.3 10.3-42.7 29.7-48.9 3.2 3.2 9.2 4.9 14.1 5.7-13 15.7-17 41.6-12.7 63-10.8-2.2-20.5-6-26.2-12.2zm47.9 14.6c-4.1 0-8.1-.3-12.7-.8-4.6-18.6-1.9-38.9 5.4-53v.3l12.2-5.1c4.9-1.9 9.7-3.8 14.9-4.9-10.7 19.7-17.4 41.3-19.8 63.5zm184-162.7c41.9 0 76.2 34 76.2 75.9 0 42.2-34.3 76.2-76.2 76.2s-76.2-34-76.2-76.2c0-41.8 34.3-75.9 76.2-75.9zm115.6 174.3c-.3 17.8-7 48.9-23 57-13.2 6.6-6.5-7.5-16.5-58.1 13.3.3 26.6.3 39.5 1.1zm-54-1.6c.8 4.9 3.8 40.3-1.6 41.9-11.6 3.5-40 4.3-51.1-1.1-4.1-3-4.6-35.9-4.3-41.1v.3c18.9-.3 38.1-.3 57 0zM278.3 309c-13 3.5-41.6 4.1-54.6-1.6-6.5-2.7-3.8-42.4-1.9-51.6 19.2-.5 38.4-.5 57.8-.8v.3c1.1 8.3 3.3 51.2-1.3 53.7zm-106.5-51.1c12.2-.8 24.6-1.4 36.8-1.6-2.4 15.4-3 43.5-4.9 52.2-1.1 6.8-4.3 6.8-9.7 4.3-21.9-9.8-27.6-35.2-22.2-54.9zm-35.4 31.3c7.8-1.1 15.7-1.9 23.5-2.7 1.6 6.2 3.8 11.9 7 17.6 10 17 44 35.7 45.1 7 6.2 14.9 40.8 12.2 54.9 10.8 15.7-1.4 23.8-1.4 26.8-14.3 12.4 4.3 30.8 4.1 44 3 11.3-.8 20.8-.5 24.6-8.9 1.1 5.1 1.9 11.6 4.6 16.8 10.8 21.3 37.3 1.4 46.8-31.6 8.6.8 17.6 1.9 26.5 2.7-.4 1.3-3.8 7.3 7.3 11.6-47.6 47-95.7 87.8-163.2 107-63.2-20.8-112.1-59.5-155.9-106.5 9.6-3.4 10.4-8.8 8-12.5zm-21.6 172.5c-3.8 17.8-21.9 29.7-39.7 28.9-19.2-.8-46.5-17-59.2-36.5-2.7-31.1 43.8-61.3 66.2-54.6 14.9 4.3 27.8 30.8 33.5 54 0 3-.3 5.7-.8 8.2zm-8.7-66c-.5-13.5-.5-27-.3-40.5h.3c2.7-1.6 5.7-3.8 7.8-6.5 6.5-1.6 13-5.1 15.1-9.2 3.3-7.1-7-7.5-5.4-12.4 2.7-1.1 5.7-2.2 7.8-3.5 29.2 29.2 58.6 56.5 97.3 77-36.8 11.3-72.4 27.6-105.9 47-1.2-18.6-7.7-35.9-16.7-51.9zm337.6 64.6c-103 3.5-206.2 4.1-309.4 0 0 .3 0 .3-.3.3v-.3h.3c35.1-21.6 72.2-39.2 112.4-50.8 11.6 5.1 23 9.5 34.9 13.2 2.2.8 2.2.8 4.3 0 14.3-4.1 28.4-9.2 42.2-15.4 41.5 11.7 78.8 31.7 115.6 53zm10.5-12.4c-35.9-19.5-73-35.9-111.9-47.6 38.1-20 71.9-47.3 103.5-76.7 2.2 1.4 4.6 2.4 7.6 3.2 0 .8.3 1.9.5 2.4-4.6 2.7-7.8 6.2-5.9 10.3 2.2 3.8 8.6 7.6 15.1 8.9 2.4 2.7 5.1 5.1 8.1 6.8 0 13.8-.3 27.6-.8 41.3l.3-.3c-9.3 15.9-15.5 37-16.5 51.7zm105.9 6.2c-12.7 19.5-40 35.7-59.2 36.5-19.3.9-40.5-13.2-40.5-37 5.7-23.2 18.9-49.7 33.5-54 22.7-6.9 69.2 23.4 66.2 54.5zM372.9 75.2c-3.8-72.1-100.8-79.7-126-23.5 44.6-24.3 90.3-15.7 126 23.5zM74.8 407.1c-15.7 1.6-49.5 25.4-49.5 43.2 0 11.6 15.7 19.5 32.2 14.9 12.2-3.2 31.1-17.6 35.9-27.3 6-11.6-3.7-32.7-18.6-30.8zm215.9-176.2c28.6 0 51.9-21.6 51.9-48.4 0-36.1-40.5-58.1-72.2-44.3 9.5 3 16.5 11.6 16.5 21.6 0 23.3-33.3 32-46.5 11.3-7.3 34.1 19.4 59.8 50.3 59.8zM68 474.1c.5 6.5 12.2 12.7 21.6 9.5 6.8-2.7 14.6-10.5 17.3-16.2 3-7-1.1-20-9.7-18.4-8.9 1.6-29.7 16.7-29.2 25.1zm433.2-67c-14.9-1.9-24.6 19.2-18.9 30.8 4.9 9.7 24.1 24.1 36.2 27.3 16.5 4.6 32.2-3.2 32.2-14.9 0-17.8-33.8-41.6-49.5-43.2zM478.8 449c-8.4-1.6-12.4 11.3-9.5 18.4 2.4 5.7 10.3 13.5 17.3 16.2 9.2 3.2 21.1-3 21.3-9.5.9-8.4-20.2-23.5-29.1-25.1z\"],\n    \"osi\": [512, 512, [], \"f41a\", \"M8 266.44C10.3 130.64 105.4 34 221.8 18.34c138.8-18.6 255.6 75.8 278 201.1 21.3 118.8-44 230-151.6 274-9.3 3.8-14.4 1.7-18-7.7q-26.7-69.45-53.4-139c-3.1-8.1-1-13.2 7-16.8 24.2-11 39.3-29.4 43.3-55.8a71.47 71.47 0 0 0-64.5-82.2c-39-3.4-71.8 23.7-77.5 59.7-5.2 33 11.1 63.7 41.9 77.7 9.6 4.4 11.5 8.6 7.8 18.4q-26.85 69.9-53.7 139.9c-2.6 6.9-8.3 9.3-15.5 6.5-52.6-20.3-101.4-61-130.8-119-24.9-49.2-25.2-87.7-26.8-108.7zm20.9-1.9c.4 6.6.6 14.3 1.3 22.1 6.3 71.9 49.6 143.5 131 183.1 3.2 1.5 4.4.8 5.6-2.3q22.35-58.65 45-117.3c1.3-3.3.6-4.8-2.4-6.7-31.6-19.9-47.3-48.5-45.6-86 1-21.6 9.3-40.5 23.8-56.3 30-32.7 77-39.8 115.5-17.6a91.64 91.64 0 0 1 45.2 90.4c-3.6 30.6-19.3 53.9-45.7 69.8-2.7 1.6-3.5 2.9-2.3 6q22.8 58.8 45.2 117.7c1.2 3.1 2.4 3.8 5.6 2.3 35.5-16.6 65.2-40.3 88.1-72 34.8-48.2 49.1-101.9 42.3-161-13.7-117.5-119.4-214.8-255.5-198-106.1 13-195.3 102.5-197.1 225.8z\"],\n    \"page4\": [496, 512, [], \"f3d7\", \"M248 504C111 504 0 393 0 256S111 8 248 8c20.9 0 41.3 2.6 60.7 7.5L42.3 392H248v112zm0-143.6V146.8L98.6 360.4H248zm96 31.6v92.7c45.7-19.2 84.5-51.7 111.4-92.7H344zm57.4-138.2l-21.2 8.4 21.2 8.3v-16.7zm-20.3 54.5c-6.7 0-8 6.3-8 12.9v7.7h16.2v-10c0-5.9-2.3-10.6-8.2-10.6zM496 256c0 37.3-8.2 72.7-23 104.4H344V27.3C433.3 64.8 496 153.1 496 256zM360.4 143.6h68.2V96h-13.9v32.6h-13.9V99h-13.9v29.6h-12.7V96h-13.9v47.6zm68.1 185.3H402v-11c0-15.4-5.6-25.2-20.9-25.2-15.4 0-20.7 10.6-20.7 25.9v25.3h68.2v-15zm0-103l-68.2 29.7V268l68.2 29.5v-16.6l-14.4-5.7v-26.5l14.4-5.9v-16.9zm-4.8-68.5h-35.6V184H402v-12.2h11c8.6 15.8 1.3 35.3-18.6 35.3-22.5 0-28.3-25.3-15.5-37.7l-11.6-10.6c-16.2 17.5-12.2 63.9 27.1 63.9 34 0 44.7-35.9 29.3-65.3z\"],\n    \"pagelines\": [384, 512, [], \"f18c\", \"M384 312.7c-55.1 136.7-187.1 54-187.1 54-40.5 81.8-107.4 134.4-184.6 134.7-16.1 0-16.6-24.4 0-24.4 64.4-.3 120.5-42.7 157.2-110.1-41.1 15.9-118.6 27.9-161.6-82.2 109-44.9 159.1 11.2 178.3 45.5 9.9-24.4 17-50.9 21.6-79.7 0 0-139.7 21.9-149.5-98.1 119.1-47.9 152.6 76.7 152.6 76.7 1.6-16.7 3.3-52.6 3.3-53.4 0 0-106.3-73.7-38.1-165.2 124.6 43 61.4 162.4 61.4 162.4.5 1.6.5 23.8 0 33.4 0 0 45.2-89 136.4-57.5-4.2 134-141.9 106.4-141.9 106.4-4.4 27.4-11.2 53.4-20 77.5 0 0 83-91.8 172-20z\"],\n    \"palfed\": [576, 512, [], \"f3d8\", \"M384.9 193.9c0-47.4-55.2-44.2-95.4-29.8-1.3 39.4-2.5 80.7-3 119.8.7 2.8 2.6 6.2 15.1 6.2 36.8 0 83.4-42.8 83.3-96.2zm-194.5 72.2c.2 0 6.5-2.7 11.2-2.7 26.6 0 20.7 44.1-14.4 44.1-21.5 0-37.1-18.1-37.1-43 0-42 42.9-95.6 100.7-126.5 1-12.4 3-22 10.5-28.2 11.2-9 26.6-3.5 29.5 11.1 72.2-22.2 135.2 1 135.2 72 0 77.9-79.3 152.6-140.1 138.2-.1 39.4.9 74.4 2.7 100v.2c.2 3.4.6 12.5-5.3 19.1-9.6 10.6-33.4 10-36.4-22.3-4.1-44.4.2-206.1 1.4-242.5-21.5 15-58.5 50.3-58.5 75.9.2 2.5.4 4 .6 4.6zM8 181.1s-.1 37.4 38.4 37.4h30l22.4 217.2s0 44.3 44.7 44.3h288.9s44.7-.4 44.7-44.3l22.4-217.2h30s38.4 1.2 38.4-37.4c0 0 .1-37.4-38.4-37.4h-30.1c-7.3-25.6-30.2-74.3-119.4-74.3h-28V50.3s-2.7-18.4-21.1-18.4h-85.8s-21.1 0-21.1 18.4v19.1h-28.1s-105 4.2-120.5 74.3h-29S8 142.5 8 181.1z\"],\n    \"patreon\": [512, 512, [], \"f3d9\", \"M512 194.8c0 101.3-82.4 183.8-183.8 183.8-101.7 0-184.4-82.4-184.4-183.8 0-101.6 82.7-184.3 184.4-184.3C429.6 10.5 512 93.2 512 194.8zM0 501.5h90v-491H0v491z\"],\n    \"paypal\": [384, 512, [], \"f1ed\", \"M111.4 295.9c-3.5 19.2-17.4 108.7-21.5 134-.3 1.8-1 2.5-3 2.5H12.3c-7.6 0-13.1-6.6-12.1-13.9L58.8 46.6c1.5-9.6 10.1-16.9 20-16.9 152.3 0 165.1-3.7 204 11.4 60.1 23.3 65.6 79.5 44 140.3-21.5 62.6-72.5 89.5-140.1 90.3-43.4.7-69.5-7-75.3 24.2zM357.1 152c-1.8-1.3-2.5-1.8-3 1.3-2 11.4-5.1 22.5-8.8 33.6-39.9 113.8-150.5 103.9-204.5 103.9-6.1 0-10.1 3.3-10.9 9.4-22.6 140.4-27.1 169.7-27.1 169.7-1 7.1 3.5 12.9 10.6 12.9h63.5c8.6 0 15.7-6.3 17.4-14.9.7-5.4-1.1 6.1 14.4-91.3 4.6-22 14.3-19.7 29.3-19.7 71 0 126.4-28.8 142.9-112.3 6.5-34.8 4.6-71.4-23.8-92.6z\"],\n    \"penny-arcade\": [640, 512, [], \"f704\", \"M421.91 164.27c-4.49 19.45-1.4 6.06-15.1 65.29l39.73-10.61c-22.34-49.61-17.29-38.41-24.63-54.68zm-206.09 51.11c-20.19 5.4-11.31 3.03-39.63 10.58l4.46 46.19c28.17-7.59 20.62-5.57 34.82-9.34 42.3-9.79 32.85-56.42.35-47.43zm326.16-26.19l-45.47-99.2c-5.69-12.37-19.46-18.84-32.62-15.33-70.27 18.75-38.72 10.32-135.59 36.23a27.618 27.618 0 0 0-18.89 17.41C144.26 113.27 0 153.75 0 226.67c0 33.5 30.67 67.11 80.9 95.37l1.74 17.88a27.891 27.891 0 0 0-17.77 28.67l4.3 44.48c1.39 14.31 13.43 25.21 27.8 25.2 5.18-.01-3.01 1.78 122.53-31.76 12.57-3.37 21.12-15.02 20.58-28.02 216.59 45.5 401.99-5.98 399.89-84.83.01-28.15-22.19-66.56-97.99-104.47zM255.14 298.3l-21.91 5.88-48.44 12.91 2.46 23.55 20.53-5.51 4.51 44.51-115.31 30.78-4.3-44.52 20.02-5.35-11.11-114.64-20.12 5.39-4.35-44.5c178.15-47.54 170.18-46.42 186.22-46.65 56.66-1.13 64.15 71.84 42.55 104.43a86.7 86.7 0 0 1-50.75 33.72zm199.18 16.62l-3.89-39.49 14.9-3.98-6.61-14.68-57.76 15.42-4.1 17.54 19.2-5.12 4.05 39.54-112.85 30.07-4.46-44.43 20.99-5.59 33.08-126.47-17.15 4.56-4.2-44.48c93.36-24.99 65.01-17.41 135.59-36.24l66.67 145.47 20.79-5.56 4.3 44.48-108.55 28.96z\"],\n    \"periscope\": [448, 512, [], \"f3da\", \"M370 63.6C331.4 22.6 280.5 0 226.6 0 111.9 0 18.5 96.2 18.5 214.4c0 75.1 57.8 159.8 82.7 192.7C137.8 455.5 192.6 512 226.6 512c41.6 0 112.9-94.2 120.9-105 24.6-33.1 82-118.3 82-192.6 0-56.5-21.1-110.1-59.5-150.8zM226.6 493.9c-42.5 0-190-167.3-190-279.4 0-107.4 83.9-196.3 190-196.3 100.8 0 184.7 89 184.7 196.3.1 112.1-147.4 279.4-184.7 279.4zM338 206.8c0 59.1-51.1 109.7-110.8 109.7-100.6 0-150.7-108.2-92.9-181.8v.4c0 24.5 20.1 44.4 44.8 44.4 24.7 0 44.8-19.9 44.8-44.4 0-18.2-11.1-33.8-26.9-40.7 76.6-19.2 141 39.3 141 112.4z\"],\n    \"phabricator\": [496, 512, [], \"f3db\", \"M323 262.1l-.1-13s21.7-19.8 21.1-21.2l-9.5-20c-.6-1.4-29.5-.5-29.5-.5l-9.4-9.3s.2-28.5-1.2-29.1l-20.1-9.2c-1.4-.6-20.7 21-20.7 21l-13.1-.2s-20.5-21.4-21.9-20.8l-20 8.3c-1.4.5.2 28.9.2 28.9l-9.1 9.1s-29.2-.9-29.7.4l-8.1 19.8c-.6 1.4 21 21 21 21l.1 12.9s-21.7 19.8-21.1 21.2l9.5 20c.6 1.4 29.5.5 29.5.5l9.4 9.3s-.2 31.8 1.2 32.3l20.1 8.3c1.4.6 20.7-23.5 20.7-23.5l13.1.2s20.5 23.8 21.8 23.3l20-7.5c1.4-.6-.2-32.1-.2-32.1l9.1-9.1s29.2.9 29.7-.5l8.1-19.8c.7-1.1-20.9-20.7-20.9-20.7zm-44.9-8.7c.7 17.1-12.8 31.6-30.1 32.4-17.3.8-32.1-12.5-32.8-29.6-.7-17.1 12.8-31.6 30.1-32.3 17.3-.8 32.1 12.5 32.8 29.5zm201.2-37.9l-97-97-.1.1c-75.1-73.3-195.4-72.8-269.8 1.6-50.9 51-27.8 27.9-95.7 95.3-22.3 22.3-22.3 58.7 0 81 69.9 69.4 46.4 46 97.4 97l.1-.1c75.1 73.3 195.4 72.9 269.8-1.6 51-50.9 27.9-27.9 95.3-95.3 22.3-22.3 22.3-58.7 0-81zM140.4 363.8c-59.6-59.5-59.6-156 0-215.5 59.5-59.6 156-59.5 215.6 0 59.5 59.5 59.6 156 0 215.6-59.6 59.5-156 59.4-215.6-.1z\"],\n    \"phoenix-framework\": [640, 512, [], \"f3dc\", \"M212.9 344.3c3.8-.1 22.8-1.4 25.6-2.2-2.4-2.6-43.6-1-68-49.6-4.3-8.6-7.5-17.6-6.4-27.6 2.9-25.5 32.9-30 52-18.5 36 21.6 63.3 91.3 113.7 97.5 37 4.5 84.6-17 108.2-45.4-.6-.1-.8-.2-1-.1-.4.1-.8.2-1.1.3-33.3 12.1-94.3 9.7-134.7-14.8-37.6-22.8-53.1-58.7-51.8-74.6 1.8-21.3 22.9-23.2 35.9-19.6 14.4 3.9 24.4 17.6 38.9 27.4 15.6 10.4 32.9 13.7 51.3 10.3 14.9-2.7 34.4-12.3 36.5-14.5-1.1-.1-1.8-.1-2.5-.2-6.2-.6-12.4-.8-18.5-1.7C279.8 194.5 262.1 47.4 138.5 37.9 94.2 34.5 39.1 46 2.2 72.9c-.8.6-1.5 1.2-2.2 1.8.1.2.1.3.2.5.8 0 1.6-.1 2.4-.2 6.3-1 12.5-.8 18.7.3 23.8 4.3 47.7 23.1 55.9 76.5 5.3 34.3-.7 50.8 8 86.1 19 77.1 91 107.6 127.7 106.4zM75.3 64.9c-.9-1-.9-1.2-1.3-2 12.1-2.6 24.2-4.1 36.6-4.8-1.1 14.7-22.2 21.3-35.3 6.8zm196.9 350.5c-42.8 1.2-92-26.7-123.5-61.4-4.6-5-16.8-20.2-18.6-23.4l.4-.4c6.6 4.1 25.7 18.6 54.8 27 24.2 7 48.1 6.3 71.6-3.3 22.7-9.3 41-.5 43.1 2.9-18.5 3.8-20.1 4.4-24 7.9-5.1 4.4-4.6 11.7 7 17.2 26.2 12.4 63-2.8 97.2 25.4 2.4 2 8.1 7.8 10.1 10.7-.1.2-.3.3-.4.5-4.8-1.5-16.4-7.5-40.2-9.3-24.7-2-46.3 5.3-77.5 6.2zm174.8-252c16.4-5.2 41.3-13.4 66.5-3.3 16.1 6.5 26.2 18.7 32.1 34.6 3.5 9.4 5.1 19.7 5.1 28.7-.2 0-.4 0-.6.1-.2-.4-.4-.9-.5-1.3-5-22-29.9-43.8-67.6-29.9-50.2 18.6-130.4 9.7-176.9-48-.7-.9-2.4-1.7-1.3-3.2.1-.2 2.1.6 3 1.3 18.1 13.4 38.3 21.9 60.3 26.2 30.5 6.1 54.6 2.9 79.9-5.2zm102.7 117.5c-32.4.2-33.8 50.1-103.6 64.4-18.2 3.7-38.7 4.6-44.9 4.2v-.4c2.8-1.5 14.7-2.6 29.7-16.6 7.9-7.3 15.3-15.1 22.8-22.9 19.5-20.2 41.4-42.2 81.9-39 23.1 1.8 29.3 8.2 36.1 12.7.3.2.4.5.7.9-.5 0-.7.1-.9 0-7-2.7-14.3-3.3-21.8-3.3zm-12.3-24.1c-.1.2-.1.4-.2.6-28.9-4.4-48-7.9-68.5 4-17 9.9-31.4 20.5-62 24.4-27.1 3.4-45.1 2.4-66.1-8-.3-.2-.6-.4-1-.6 0-.2.1-.3.1-.5 24.9 3.8 36.4 5.1 55.5-5.8 22.3-12.9 40.1-26.6 71.3-31 29.6-4.1 51.3 2.5 70.9 16.9zM268.6 97.3c-.6-.6-1.1-1.2-2.1-2.3 7.6 0 29.7-1.2 53.4 8.4 19.7 8 32.2 21 50.2 32.9 11.1 7.3 23.4 9.3 36.4 8.1 4.3-.4 8.5-1.2 12.8-1.7.4-.1.9 0 1.5.3-.6.4-1.2.9-1.8 1.2-8.1 4-16.7 6.3-25.6 7.1-26.1 2.6-50.3-3.7-73.4-15.4-19.3-9.9-36.4-22.9-51.4-38.6zM640 335.7c-3.5 3.1-22.7 11.6-42.7 5.3-12.3-3.9-19.5-14.9-31.6-24.1-10-7.6-20.9-7.9-28.1-8.4.6-.8.9-1.2 1.2-1.4 14.8-9.2 30.5-12.2 47.3-6.5 12.5 4.2 19.2 13.5 30.4 24.2 10.8 10.4 21 9.9 23.1 10.5.1-.1.2 0 .4.4zm-212.5 137c2.2 1.2 1.6 1.5 1.5 2-18.5-1.4-33.9-7.6-46.8-22.2-21.8-24.7-41.7-27.9-48.6-29.7.5-.2.8-.4 1.1-.4 13.1.1 26.1.7 38.9 3.9 25.3 6.4 35 25.4 41.6 35.3 3.2 4.8 7.3 8.3 12.3 11.1z\"],\n    \"phoenix-squadron\": [512, 512, [], \"f511\", \"M96 63.38C142.49 27.25 201.55 7.31 260.51 8.81c29.58-.38 59.11 5.37 86.91 15.33-24.13-4.63-49-6.34-73.38-2.45C231.17 27 191 48.84 162.21 80.87c5.67-1 10.78-3.67 16-5.86 18.14-7.87 37.49-13.26 57.23-14.83 19.74-2.13 39.64-.43 59.28 1.92-14.42 2.79-29.12 4.57-43 9.59-34.43 11.07-65.27 33.16-86.3 62.63-13.8 19.71-23.63 42.86-24.67 67.13-.35 16.49 5.22 34.81 19.83 44a53.27 53.27 0 0 0 37.52 6.74c15.45-2.46 30.07-8.64 43.6-16.33 11.52-6.82 22.67-14.55 32-24.25 3.79-3.22 2.53-8.45 2.62-12.79-2.12-.34-4.38-1.11-6.3.3a203 203 0 0 1-35.82 15.37c-20 6.17-42.16 8.46-62.1.78 12.79 1.73 26.06.31 37.74-5.44 20.23-9.72 36.81-25.2 54.44-38.77a526.57 526.57 0 0 1 88.9-55.31c25.71-12 52.94-22.78 81.57-24.12-15.63 13.72-32.15 26.52-46.78 41.38-14.51 14-27.46 29.5-40.11 45.18-3.52 4.6-8.95 6.94-13.58 10.16a150.7 150.7 0 0 0-51.89 60.1c-9.33 19.68-14.5 41.85-11.77 63.65 1.94 13.69 8.71 27.59 20.9 34.91 12.9 8 29.05 8.07 43.48 5.1 32.8-7.45 61.43-28.89 81-55.84 20.44-27.52 30.52-62.2 29.16-96.35-.52-7.5-1.57-15-1.66-22.49 8 19.48 14.82 39.71 16.65 60.83 2 14.28.75 28.76-1.62 42.9-1.91 11-5.67 21.51-7.78 32.43a165 165 0 0 0 39.34-81.07 183.64 183.64 0 0 0-14.21-104.64c20.78 32 32.34 69.58 35.71 107.48.49 12.73.49 25.51 0 38.23A243.21 243.21 0 0 1 482 371.34c-26.12 47.34-68 85.63-117.19 108-78.29 36.23-174.68 31.32-248-14.68A248.34 248.34 0 0 1 25.36 366 238.34 238.34 0 0 1 0 273.08v-31.34C3.93 172 40.87 105.82 96 63.38m222 80.33a79.13 79.13 0 0 0 16-4.48c5-1.77 9.24-5.94 10.32-11.22-8.96 4.99-17.98 9.92-26.32 15.7z\"],\n    \"php\": [640, 512, [], \"f457\", \"M320 104.5c171.4 0 303.2 72.2 303.2 151.5S491.3 407.5 320 407.5c-171.4 0-303.2-72.2-303.2-151.5S148.7 104.5 320 104.5m0-16.8C143.3 87.7 0 163 0 256s143.3 168.3 320 168.3S640 349 640 256 496.7 87.7 320 87.7zM218.2 242.5c-7.9 40.5-35.8 36.3-70.1 36.3l13.7-70.6c38 0 63.8-4.1 56.4 34.3zM97.4 350.3h36.7l8.7-44.8c41.1 0 66.6 3 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7h-70.7L97.4 350.3zm185.7-213.6h36.5l-8.7 44.8c31.5 0 60.7-2.3 74.8 10.7 14.8 13.6 7.7 31-8.3 113.1h-37c15.4-79.4 18.3-86 12.7-92-5.4-5.8-17.7-4.6-47.4-4.6l-18.8 96.6h-36.5l32.7-168.6zM505 242.5c-8 41.1-36.7 36.3-70.1 36.3l13.7-70.6c38.2 0 63.8-4.1 56.4 34.3zM384.2 350.3H421l8.7-44.8c43.2 0 67.1 2.5 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7H417l-32.8 168.7z\"],\n    \"pied-piper\": [448, 512, [], \"f2ae\", \"M32 419L0 479.2l.8-328C.8 85.3 54 32 120 32h327.2c-93 28.9-189.9 94.2-253.9 168.6C122.7 282 82.6 338 32 419M448 32S305.2 98.8 261.6 199.1c-23.2 53.6-28.9 118.1-71 158.6-28.9 27.8-69.8 38.2-105.3 56.3-23.2 12-66.4 40.5-84.9 66h328.4c66 0 119.3-53.3 119.3-119.2-.1 0-.1-328.8-.1-328.8z\"],\n    \"pied-piper-alt\": [576, 512, [], \"f1a8\", \"M244 246c-3.2-2-6.3-2.9-10.1-2.9-6.6 0-12.6 3.2-19.3 3.7l1.7 4.9zm135.9 197.9c-19 0-64.1 9.5-79.9 19.8l6.9 45.1c35.7 6.1 70.1 3.6 106-9.8-4.8-10-23.5-55.1-33-55.1zM340.8 177c6.6 2.8 11.5 9.2 22.7 22.1 2-1.4 7.5-5.2 7.5-8.6 0-4.9-11.8-13.2-13.2-23 11.2-5.7 25.2-6 37.6-8.9 68.1-16.4 116.3-52.9 146.8-116.7C548.3 29.3 554 16.1 554.6 2l-2 2.6c-28.4 50-33 63.2-81.3 100-31.9 24.4-69.2 40.2-106.6 54.6l-6.3-.3v-21.8c-19.6 1.6-19.7-14.6-31.6-23-18.7 20.6-31.6 40.8-58.9 51.1-12.7 4.8-19.6 10-25.9 21.8 34.9-16.4 91.2-13.5 98.8-10zM555.5 0l-.6 1.1-.3.9.6-.6zm-59.2 382.1c-33.9-56.9-75.3-118.4-150-115.5l-.3-6c-1.1-13.5 32.8 3.2 35.1-31l-14.4 7.2c-19.8-45.7-8.6-54.3-65.5-54.3-14.7 0-26.7 1.7-41.4 4.6 2.9 18.6 2.2 36.7-10.9 50.3l19.5 5.5c-1.7 3.2-2.9 6.3-2.9 9.8 0 21 42.8 2.9 42.8 33.6 0 18.4-36.8 60.1-54.9 60.1-8 0-53.7-50-53.4-60.1l.3-4.6 52.3-11.5c13-2.6 12.3-22.7-2.9-22.7-3.7 0-43.1 9.2-49.4 10.6-2-5.2-7.5-14.1-13.8-14.1-3.2 0-6.3 3.2-9.5 4-9.2 2.6-31 2.9-21.5 20.1L15.9 298.5c-5.5 1.1-8.9 6.3-8.9 11.8 0 6 5.5 10.9 11.5 10.9 8 0 131.3-28.4 147.4-32.2 2.6 3.2 4.6 6.3 7.8 8.6 20.1 14.4 59.8 85.9 76.4 85.9 24.1 0 58-22.4 71.3-41.9 3.2-4.3 6.9-7.5 12.4-6.9.6 13.8-31.6 34.2-33 43.7-1.4 10.2-1 35.2-.3 41.1 26.7 8.1 52-3.6 77.9-2.9 4.3-21 10.6-41.9 9.8-63.5l-.3-9.5c-1.4-34.2-10.9-38.5-34.8-58.6-1.1-1.1-2.6-2.6-3.7-4 2.2-1.4 1.1-1 4.6-1.7 88.5 0 56.3 183.6 111.5 229.9 33.1-15 72.5-27.9 103.5-47.2-29-25.6-52.6-45.7-72.7-79.9zm-196.2 46.1v27.2l11.8-3.4-2.9-23.8zm-68.7-150.4l24.1 61.2 21-13.8-31.3-50.9zm84.4 154.9l2 12.4c9-1.5 58.4-6.6 58.4-14.1 0-1.4-.6-3.2-.9-4.6-26.8 0-36.9 3.8-59.5 6.3z\"],\n    \"pied-piper-hat\": [640, 512, [], \"f4e5\", \"M640 24.9c-80.8 53.6-89.4 92.5-96.4 104.4-6.7 12.2-11.7 60.3-23.3 83.6-11.7 23.6-54.2 42.2-66.1 50-11.7 7.8-28.3 38.1-41.9 64.2-108.1-4.4-167.4 38.8-259.2 93.6 29.4-9.7 43.3-16.7 43.3-16.7 94.2-36 139.3-68.3 281.1-49.2 1.1 0 1.9.6 2.8.8 3.9 2.2 5.3 6.9 3.1 10.8l-53.9 95.8c-2.5 4.7-7.8 7.2-13.1 6.1-126.8-23.8-226.9 17.3-318.9 18.6C24.1 488 0 453.4 0 451.8c0-1.1.6-1.7 1.7-1.7 0 0 38.3 0 103.1-15.3C178.4 294.5 244 245.4 315.4 245.4c0 0 71.7 0 90.6 61.9 22.8-39.7 28.3-49.2 28.3-49.2 5.3-9.4 35-77.2 86.4-141.4 51.5-64 90.4-79.9 119.3-91.8z\"],\n    \"pied-piper-pp\": [448, 512, [], \"f1a7\", \"M205.3 174.6c0 21.1-14.2 38.1-31.7 38.1-7.1 0-12.8-1.2-17.2-3.7v-68c4.4-2.7 10.1-4.2 17.2-4.2 17.5 0 31.7 16.9 31.7 37.8zm52.6 67c-7.1 0-12.8 1.5-17.2 4.2v68c4.4 2.5 10.1 3.7 17.2 3.7 17.4 0 31.7-16.9 31.7-37.8 0-21.1-14.3-38.1-31.7-38.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM185 255.1c41 0 74.2-35.6 74.2-79.6 0-44-33.2-79.6-74.2-79.6-12 0-24.1 3.2-34.6 8.8h-45.7V311l51.8-10.1v-50.6c8.6 3.1 18.1 4.8 28.5 4.8zm158.4 25.3c0-44-33.2-79.6-73.9-79.6-3.2 0-6.4.2-9.6.7-3.7 12.5-10.1 23.8-19.2 33.4-13.8 15-32.2 23.8-51.8 24.8V416l51.8-10.1v-50.6c8.6 3.2 18.2 4.7 28.7 4.7 40.8 0 74-35.6 74-79.6z\"],\n    \"pinterest\": [496, 512, [], \"f0d2\", \"M496 256c0 137-111 248-248 248-25.6 0-50.2-3.9-73.4-11.1 10.1-16.5 25.2-43.5 30.8-65 3-11.6 15.4-59 15.4-59 8.1 15.4 31.7 28.5 56.8 28.5 74.8 0 128.7-68.8 128.7-154.3 0-81.9-66.9-143.2-152.9-143.2-107 0-163.9 71.8-163.9 150.1 0 36.4 19.4 81.7 50.3 96.1 4.7 2.2 7.2 1.2 8.3-3.3.8-3.4 5-20.3 6.9-28.1.6-2.5.3-4.7-1.7-7.1-10.1-12.5-18.3-35.3-18.3-56.6 0-54.7 41.4-107.6 112-107.6 60.9 0 103.6 41.5 103.6 100.9 0 67.1-33.9 113.6-78 113.6-24.3 0-42.6-20.1-36.7-44.8 7-29.5 20.5-61.3 20.5-82.6 0-19-10.2-34.9-31.4-34.9-24.9 0-44.9 25.7-44.9 60.2 0 22 7.4 36.8 7.4 36.8s-24.5 103.8-29 123.2c-5 21.4-3 51.6-.9 71.2C65.4 450.9 0 361.1 0 256 0 119 111 8 248 8s248 111 248 248z\"],\n    \"pinterest-p\": [384, 512, [], \"f231\", \"M204 6.5C101.4 6.5 0 74.9 0 185.6 0 256 39.6 296 63.6 296c9.9 0 15.6-27.6 15.6-35.4 0-9.3-23.7-29.1-23.7-67.8 0-80.4 61.2-137.4 140.4-137.4 68.1 0 118.5 38.7 118.5 109.8 0 53.1-21.3 152.7-90.3 152.7-24.9 0-46.2-18-46.2-43.8 0-37.8 26.4-74.4 26.4-113.4 0-66.2-93.9-54.2-93.9 25.8 0 16.8 2.1 35.4 9.6 50.7-13.8 59.4-42 147.9-42 209.1 0 18.9 2.7 37.5 4.5 56.4 3.4 3.8 1.7 3.4 6.9 1.5 50.4-69 48.6-82.5 71.4-172.8 12.3 23.4 44.1 36 69.3 36 106.2 0 153.9-103.5 153.9-196.8C384 71.3 298.2 6.5 204 6.5z\"],\n    \"pinterest-square\": [448, 512, [], \"f0d3\", \"M448 80v352c0 26.5-21.5 48-48 48H154.4c9.8-16.4 22.4-40 27.4-59.3 3-11.5 15.3-58.4 15.3-58.4 8 15.3 31.4 28.2 56.3 28.2 74.1 0 127.4-68.1 127.4-152.7 0-81.1-66.2-141.8-151.4-141.8-106 0-162.2 71.1-162.2 148.6 0 36 19.2 80.8 49.8 95.1 4.7 2.2 7.1 1.2 8.2-3.3.8-3.4 5-20.1 6.8-27.8.6-2.5.3-4.6-1.7-7-10.1-12.3-18.3-34.9-18.3-56 0-54.2 41-106.6 110.9-106.6 60.3 0 102.6 41.1 102.6 99.9 0 66.4-33.5 112.4-77.2 112.4-24.1 0-42.1-19.9-36.4-44.4 6.9-29.2 20.3-60.7 20.3-81.8 0-53-75.5-45.7-75.5 25 0 21.7 7.3 36.5 7.3 36.5-31.4 132.8-36.1 134.5-29.6 192.6l2.2.8H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48z\"],\n    \"playstation\": [576, 512, [], \"f3df\", \"M570.9 372.3c-11.3 14.2-38.8 24.3-38.8 24.3L327 470.2v-54.3l150.9-53.8c17.1-6.1 19.8-14.8 5.8-19.4-13.9-4.6-39.1-3.3-56.2 2.9L327 381.1v-56.4c23.2-7.8 47.1-13.6 75.7-16.8 40.9-4.5 90.9.6 130.2 15.5 44.2 14 49.2 34.7 38 48.9zm-224.4-92.5v-139c0-16.3-3-31.3-18.3-35.6-11.7-3.8-19 7.1-19 23.4v347.9l-93.8-29.8V32c39.9 7.4 98 24.9 129.2 35.4C424.1 94.7 451 128.7 451 205.2c0 74.5-46 102.8-104.5 74.6zM43.2 410.2c-45.4-12.8-53-39.5-32.3-54.8 19.1-14.2 51.7-24.9 51.7-24.9l134.5-47.8v54.5l-96.8 34.6c-17.1 6.1-19.7 14.8-5.8 19.4 13.9 4.6 39.1 3.3 56.2-2.9l46.4-16.9v48.8c-51.6 9.3-101.4 7.3-153.9-10z\"],\n    \"product-hunt\": [512, 512, [], \"f288\", \"M326.3 218.8c0 20.5-16.7 37.2-37.2 37.2h-70.3v-74.4h70.3c20.5 0 37.2 16.7 37.2 37.2zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-128.1-37.2c0-47.9-38.9-86.8-86.8-86.8H169.2v248h49.6v-74.4h70.3c47.9 0 86.8-38.9 86.8-86.8z\"],\n    \"pushed\": [432, 512, [], \"f3e1\", \"M407 111.9l-98.5-9 14-33.4c10.4-23.5-10.8-40.4-28.7-37L22.5 76.9c-15.1 2.7-26 18.3-21.4 36.6l105.1 348.3c6.5 21.3 36.7 24.2 47.7 7l35.3-80.8 235.2-231.3c16.4-16.8 4.3-42.9-17.4-44.8zM297.6 53.6c5.1-.7 7.5 2.5 5.2 7.4L286 100.9 108.6 84.6l189-31zM22.7 107.9c-3.1-5.1 1-10 6.1-9.1l248.7 22.7-96.9 230.7L22.7 107.9zM136 456.4c-2.6 4-7.9 3.1-9.4-1.2L43.5 179.7l127.7 197.6c-7 15-35.2 79.1-35.2 79.1zm272.8-314.5L210.1 337.3l89.7-213.7 106.4 9.7c4 1.1 5.7 5.3 2.6 8.6z\"],\n    \"python\": [448, 512, [], \"f3e2\", \"M439.8 200.5c-7.7-30.9-22.3-54.2-53.4-54.2h-40.1v47.4c0 36.8-31.2 67.8-66.8 67.8H172.7c-29.2 0-53.4 25-53.4 54.3v101.8c0 29 25.2 46 53.4 54.3 33.8 9.9 66.3 11.7 106.8 0 26.9-7.8 53.4-23.5 53.4-54.3v-40.7H226.2v-13.6h160.2c31.1 0 42.6-21.7 53.4-54.2 11.2-33.5 10.7-65.7 0-108.6zM286.2 404c11.1 0 20.1 9.1 20.1 20.3 0 11.3-9 20.4-20.1 20.4-11 0-20.1-9.2-20.1-20.4.1-11.3 9.1-20.3 20.1-20.3zM167.8 248.1h106.8c29.7 0 53.4-24.5 53.4-54.3V91.9c0-29-24.4-50.7-53.4-55.6-35.8-5.9-74.7-5.6-106.8.1-45.2 8-53.4 24.7-53.4 55.6v40.7h106.9v13.6h-147c-31.1 0-58.3 18.7-66.8 54.2-9.8 40.7-10.2 66.1 0 108.6 7.6 31.6 25.7 54.2 56.8 54.2H101v-48.8c0-35.3 30.5-66.4 66.8-66.4zm-6.7-142.6c-11.1 0-20.1-9.1-20.1-20.3.1-11.3 9-20.4 20.1-20.4 11 0 20.1 9.2 20.1 20.4s-9 20.3-20.1 20.3z\"],\n    \"qq\": [448, 512, [], \"f1d6\", \"M433.754 420.445c-11.526 1.393-44.86-52.741-44.86-52.741 0 31.345-16.136 72.247-51.051 101.786 16.842 5.192 54.843 19.167 45.803 34.421-7.316 12.343-125.51 7.881-159.632 4.037-34.122 3.844-152.316 8.306-159.632-4.037-9.045-15.25 28.918-29.214 45.783-34.415-34.92-29.539-51.059-70.445-51.059-101.792 0 0-33.334 54.134-44.859 52.741-5.37-.65-12.424-29.644 9.347-99.704 10.261-33.024 21.995-60.478 40.144-105.779C60.683 98.063 108.982.006 224 0c113.737.006 163.156 96.133 160.264 214.963 18.118 45.223 29.912 72.85 40.144 105.778 21.768 70.06 14.716 99.053 9.346 99.704z\"],\n    \"quinscape\": [512, 512, [], \"f459\", \"M313.6 474.6h-1a158.1 158.1 0 0 1 0-316.2c94.9 0 168.2 83.1 157 176.6 4 5.1 8.2 9.6 11.2 15.3 13.4-30.3 20.3-62.4 20.3-97.7C501.1 117.5 391.6 8 256.5 8S12 117.5 12 252.6s109.5 244.6 244.5 244.6a237.36 237.36 0 0 0 70.4-10.1c-5.2-3.5-8.9-8.1-13.3-12.5zm-.1-.1l.4.1zm78.4-168.9a99.2 99.2 0 1 0 99.2 99.2 99.18 99.18 0 0 0-99.2-99.2z\"],\n    \"quora\": [448, 512, [], \"f2c4\", \"M440.5 386.7h-29.3c-1.5 13.5-10.5 30.8-33 30.8-20.5 0-35.3-14.2-49.5-35.8 44.2-34.2 74.7-87.5 74.7-153C403.5 111.2 306.8 32 205 32 105.3 32 7.3 111.7 7.3 228.7c0 134.1 131.3 221.6 249 189C276 451.3 302 480 351.5 480c81.8 0 90.8-75.3 89-93.3zM297 329.2C277.5 300 253.3 277 205.5 277c-30.5 0-54.3 10-69 22.8l12.2 24.3c6.2-3 13-4 19.8-4 35.5 0 53.7 30.8 69.2 61.3-10 3-20.7 4.2-32.7 4.2-75 0-107.5-53-107.5-156.7C97.5 124.5 130 71 205 71c76.2 0 108.7 53.5 108.7 157.7.1 41.8-5.4 75.6-16.7 100.5z\"],\n    \"r-project\": [581, 512, [], \"f4f7\", \"M581 226.6C581 119.1 450.9 32 290.5 32S0 119.1 0 226.6C0 322.4 103.3 402 239.4 418.1V480h99.1v-61.5c24.3-2.7 47.6-7.4 69.4-13.9L448 480h112l-67.4-113.7c54.5-35.4 88.4-84.9 88.4-139.7zm-466.8 14.5c0-73.5 98.9-133 220.8-133s211.9 40.7 211.9 133c0 50.1-26.5 85-70.3 106.4-2.4-1.6-4.7-2.9-6.4-3.7-10.2-5.2-27.8-10.5-27.8-10.5s86.6-6.4 86.6-92.7-90.6-87.9-90.6-87.9h-199V361c-74.1-21.5-125.2-67.1-125.2-119.9zm225.1 38.3v-55.6c57.8 0 87.8-6.8 87.8 27.3 0 36.5-38.2 28.3-87.8 28.3zm-.9 72.5H365c10.8 0 18.9 11.7 24 19.2-16.1 1.9-33 2.8-50.6 2.9v-22.1z\"],\n    \"raspberry-pi\": [407, 512, [], \"f7bb\", \"M372 232.5l-3.7-6.5c.1-46.4-21.4-65.3-46.5-79.7 7.6-2 15.4-3.6 17.6-13.2 13.1-3.3 15.8-9.4 17.1-15.8 3.4-2.3 14.8-8.7 13.6-19.7 6.4-4.4 10-10.1 8.1-18.1 6.9-7.5 8.7-13.7 5.8-19.4 8.3-10.3 4.6-15.6 1.1-20.9 6.2-11.2.7-23.2-16.6-21.2-6.9-10.1-21.9-7.8-24.2-7.8-2.6-3.2-6-6-16.5-4.7-6.8-6.1-14.4-5-22.3-2.1-9.3-7.3-15.5-1.4-22.6.8C271.6.6 269 5.5 263.5 7.6c-12.3-2.6-16.1 3-22 8.9l-6.9-.1c-18.6 10.8-27.8 32.8-31.1 44.1-3.3-11.3-12.5-33.3-31.1-44.1l-6.9.1c-5.9-5.9-9.7-11.5-22-8.9-5.6-2-8.1-7-19.4-3.4-4.6-1.4-8.9-4.4-13.9-4.3-2.6.1-5.5 1-8.7 3.5-7.9-3-15.5-4-22.3 2.1-10.5-1.3-14 1.4-16.5 4.7-2.3 0-17.3-2.3-24.2 7.8C21.2 16 15.8 28 22 39.2c-3.5 5.4-7.2 10.7 1.1 20.9-2.9 5.7-1.1 11.9 5.8 19.4-1.8 8 1.8 13.7 8.1 18.1-1.2 11 10.2 17.4 13.6 19.7 1.3 6.4 4 12.4 17.1 15.8 2.2 9.5 10 11.2 17.6 13.2-25.1 14.4-46.6 33.3-46.5 79.7l-3.7 6.5c-28.8 17.2-54.7 72.7-14.2 117.7 2.6 14.1 7.1 24.2 11 35.4 5.9 45.2 44.5 66.3 54.6 68.8 14.9 11.2 30.8 21.8 52.2 29.2C159 504.2 181 512 203 512h1c22.1 0 44-7.8 64.2-28.4 21.5-7.4 37.3-18 52.2-29.2 10.2-2.5 48.7-23.6 54.6-68.8 3.9-11.2 8.4-21.3 11-35.4 40.6-45.1 14.7-100.5-14-117.7zm-22.2-8c-1.5 18.7-98.9-65.1-82.1-67.9 45.7-7.5 83.6 19.2 82.1 67.9zm-43 93.1c-24.5 15.8-59.8 5.6-78.8-22.8s-14.6-64.2 9.9-80c24.5-15.8 59.8-5.6 78.8 22.8s14.6 64.2-9.9 80zM238.9 29.3c.8 4.2 1.8 6.8 2.9 7.6 5.4-5.8 9.8-11.7 16.8-17.3 0 3.3-1.7 6.8 2.5 9.4 3.7-5 8.8-9.5 15.5-13.3-3.2 5.6-.6 7.3 1.2 9.6 5.1-4.4 10-8.8 19.4-12.3-2.6 3.1-6.2 6.2-2.4 9.8 5.3-3.3 10.6-6.6 23.1-8.9-2.8 3.1-8.7 6.3-5.1 9.4 6.6-2.5 14-4.4 22.1-5.4-3.9 3.2-7.1 6.3-3.9 8.8 7.1-2.2 16.9-5.1 26.4-2.6l-6 6.1c-.7.8 14.1.6 23.9.8-3.6 5-7.2 9.7-9.3 18.2 1 1 5.8.4 10.4 0-4.7 9.9-12.8 12.3-14.7 16.6 2.9 2.2 6.8 1.6 11.2.1-3.4 6.9-10.4 11.7-16 17.3 1.4 1 3.9 1.6 9.7.9-5.2 5.5-11.4 10.5-18.8 15 1.3 1.5 5.8 1.5 10 1.6-6.7 6.5-15.3 9.9-23.4 14.2 4 2.7 6.9 2.1 10 2.1-5.7 4.7-15.4 7.1-24.4 10 1.7 2.7 3.4 3.4 7.1 4.1-9.5 5.3-23.2 2.9-27 5.6.9 2.7 3.6 4.4 6.7 5.8-15.4.9-57.3-.6-65.4-32.3 15.7-17.3 44.4-37.5 93.7-62.6-38.4 12.8-73 30-102 53.5-34.3-15.9-10.8-55.9 5.8-71.8zm-34.4 114.6c24.2-.3 54.1 17.8 54 34.7-.1 15-21 27.1-53.8 26.9-32.1-.4-53.7-15.2-53.6-29.8 0-11.9 26.2-32.5 53.4-31.8zm-123-12.8c3.7-.7 5.4-1.5 7.1-4.1-9-2.8-18.7-5.3-24.4-10 3.1 0 6 .7 10-2.1-8.1-4.3-16.7-7.7-23.4-14.2 4.2-.1 8.7 0 10-1.6-7.4-4.5-13.6-9.5-18.8-15 5.8.7 8.3.1 9.7-.9-5.6-5.6-12.7-10.4-16-17.3 4.3 1.5 8.3 2 11.2-.1-1.9-4.2-10-6.7-14.7-16.6 4.6.4 9.4 1 10.4 0-2.1-8.5-5.8-13.3-9.3-18.2 9.8-.1 24.6 0 23.9-.8l-6-6.1c9.5-2.5 19.3.4 26.4 2.6 3.2-2.5-.1-5.6-3.9-8.8 8.1 1.1 15.4 2.9 22.1 5.4 3.5-3.1-2.3-6.3-5.1-9.4 12.5 2.3 17.8 5.6 23.1 8.9 3.8-3.6.2-6.7-2.4-9.8 9.4 3.4 14.3 7.9 19.4 12.3 1.7-2.3 4.4-4 1.2-9.6 6.7 3.8 11.8 8.3 15.5 13.3 4.1-2.6 2.5-6.2 2.5-9.4 7 5.6 11.4 11.5 16.8 17.3 1.1-.8 2-3.4 2.9-7.6 16.6 15.9 40.1 55.9 6 71.8-29-23.5-63.6-40.7-102-53.5 49.3 25 78 45.3 93.7 62.6-8 31.8-50 33.2-65.4 32.3 3.1-1.4 5.8-3.2 6.7-5.8-4-2.8-17.6-.4-27.2-5.6zm60.1 24.1c16.8 2.8-80.6 86.5-82.1 67.9-1.5-48.7 36.5-75.5 82.1-67.9zM38.2 342c-23.7-18.8-31.3-73.7 12.6-98.3 26.5-7 9 107.8-12.6 98.3zm91 98.2c-13.3 7.9-45.8 4.7-68.8-27.9-15.5-27.4-13.5-55.2-2.6-63.4 16.3-9.8 41.5 3.4 60.9 25.6 16.9 20 24.6 55.3 10.5 65.7zm-26.4-119.7c-24.5-15.8-28.9-51.6-9.9-80s54.3-38.6 78.8-22.8 28.9 51.6 9.9 80c-19.1 28.4-54.4 38.6-78.8 22.8zM205 496c-29.4 1.2-58.2-23.7-57.8-32.3-.4-12.7 35.8-22.6 59.3-22 23.7-1 55.6 7.5 55.7 18.9.5 11-28.8 35.9-57.2 35.4zm58.9-124.9c.2 29.7-26.2 53.8-58.8 54-32.6.2-59.2-23.8-59.4-53.4v-.6c-.2-29.7 26.2-53.8 58.8-54 32.6-.2 59.2 23.8 59.4 53.4v.6zm82.2 42.7c-25.3 34.6-59.6 35.9-72.3 26.3-13.3-12.4-3.2-50.9 15.1-72 20.9-23.3 43.3-38.5 58.9-26.6 10.5 10.3 16.7 49.1-1.7 72.3zm22.9-73.2c-21.5 9.4-39-105.3-12.6-98.3 43.9 24.7 36.3 79.6 12.6 98.3z\"],\n    \"ravelry\": [512, 512, [], \"f2d9\", \"M407.4 61.5C331.6 22.1 257.8 31 182.9 66c-11.3 5.2-15.5 10.6-19.9 19-10.3 19.2-16.2 37.4-19.9 52.7-21.2 25.6-36.4 56.1-43.3 89.9-10.6 18-20.9 41.4-23.1 71.4 0 0-.7 7.6-.5 7.9-35.3-4.6-76.2-27-76.2-27 9.1 14.5 61.3 32.3 76.3 37.9 0 0 1.7 98 64.5 131.2-11.3-17.2-13.3-20.2-13.3-20.2S94.8 369 100.4 324.7c.7 0 1.5.2 2.2.2 23.9 87.4 103.2 151.4 196.9 151.4 6.2 0 12.1-.2 18-.7 14 1.5 27.6.5 40.1-3.9 6.9-2.2 13.8-6.4 20.2-10.8 70.2-39.1 100.9-82 123.1-147.7 5.4-16 8.1-35.5 9.8-52.2 8.7-82.3-30.6-161.6-103.3-199.5zM138.8 163.2s-1.2 12.3-.7 19.7c-3.4 2.5-10.1 8.1-18.2 16.7 5.2-12.8 11.3-25.1 18.9-36.4zm-31.2 121.9c4.4-17.2 13.3-39.1 29.8-55.1 0 0 1.7 48 15.8 90.1l-41.4-6.9c-2.2-9.2-3.5-18.5-4.2-28.1zm7.9 42.8c14.8 3.2 34 7.6 43.1 9.1 27.3 76.8 108.3 124.3 108.3 124.3 1 .5 1.7.7 2.7 1-73.1-11.6-132.7-64.7-154.1-134.4zM386 444.1c-14.5 4.7-36.2 8.4-64.7 3.7 0 0-91.1-23.1-127.5-107.8 38.2.7 52.4-.2 78-3.9 39.4-5.7 79-16.2 115-33 11.8-5.4 11.1-19.4 9.6-29.8-2-12.8-11.1-12.1-21.4-4.7 0 0-82 58.6-189.8 53.7-18.7-32-26.8-110.8-26.8-110.8 41.4-35.2 83.2-59.6 168.4-52.4.2-6.4 3-27.1-20.4-28.1 0 0-93.5-11.1-146 33.5 2.5-16.5 5.9-29.3 11.1-39.4 34.2-30.8 79-49.5 128.3-49.5 106.4 0 193 87.1 193 194.5-.2 76-43.8 142-106.8 174z\"],\n    \"react\": [512, 512, [], \"f41b\", \"M418.2 177.2c-5.4-1.8-10.8-3.5-16.2-5.1.9-3.7 1.7-7.4 2.5-11.1 12.3-59.6 4.2-107.5-23.1-123.3-26.3-15.1-69.2.6-112.6 38.4-4.3 3.7-8.5 7.6-12.5 11.5-2.7-2.6-5.5-5.2-8.3-7.7-45.5-40.4-91.1-57.4-118.4-41.5-26.2 15.2-34 60.3-23 116.7 1.1 5.6 2.3 11.1 3.7 16.7-6.4 1.8-12.7 3.8-18.6 5.9C38.3 196.2 0 225.4 0 255.6c0 31.2 40.8 62.5 96.3 81.5 4.5 1.5 9 3 13.6 4.3-1.5 6-2.8 11.9-4 18-10.5 55.5-2.3 99.5 23.9 114.6 27 15.6 72.4-.4 116.6-39.1 3.5-3.1 7-6.3 10.5-9.7 4.4 4.3 9 8.4 13.6 12.4 42.8 36.8 85.1 51.7 111.2 36.6 27-15.6 35.8-62.9 24.4-120.5-.9-4.4-1.9-8.9-3-13.5 3.2-.9 6.3-1.9 9.4-2.9 57.7-19.1 99.5-50 99.5-81.7 0-30.3-39.4-59.7-93.8-78.4zM282.9 92.3c37.2-32.4 71.9-45.1 87.7-36 16.9 9.7 23.4 48.9 12.8 100.4-.7 3.4-1.4 6.7-2.3 10-22.2-5-44.7-8.6-67.3-10.6-13-18.6-27.2-36.4-42.6-53.1 3.9-3.7 7.7-7.2 11.7-10.7zM167.2 307.5c5.1 8.7 10.3 17.4 15.8 25.9-15.6-1.7-31.1-4.2-46.4-7.5 4.4-14.4 9.9-29.3 16.3-44.5 4.6 8.8 9.3 17.5 14.3 26.1zm-30.3-120.3c14.4-3.2 29.7-5.8 45.6-7.8-5.3 8.3-10.5 16.8-15.4 25.4-4.9 8.5-9.7 17.2-14.2 26-6.3-14.9-11.6-29.5-16-43.6zm27.4 68.9c6.6-13.8 13.8-27.3 21.4-40.6s15.8-26.2 24.4-38.9c15-1.1 30.3-1.7 45.9-1.7s31 .6 45.9 1.7c8.5 12.6 16.6 25.5 24.3 38.7s14.9 26.7 21.7 40.4c-6.7 13.8-13.9 27.4-21.6 40.8-7.6 13.3-15.7 26.2-24.2 39-14.9 1.1-30.4 1.6-46.1 1.6s-30.9-.5-45.6-1.4c-8.7-12.7-16.9-25.7-24.6-39s-14.8-26.8-21.5-40.6zm180.6 51.2c5.1-8.8 9.9-17.7 14.6-26.7 6.4 14.5 12 29.2 16.9 44.3-15.5 3.5-31.2 6.2-47 8 5.4-8.4 10.5-17 15.5-25.6zm14.4-76.5c-4.7-8.8-9.5-17.6-14.5-26.2-4.9-8.5-10-16.9-15.3-25.2 16.1 2 31.5 4.7 45.9 8-4.6 14.8-10 29.2-16.1 43.4zM256.2 118.3c10.5 11.4 20.4 23.4 29.6 35.8-19.8-.9-39.7-.9-59.5 0 9.8-12.9 19.9-24.9 29.9-35.8zM140.2 57c16.8-9.8 54.1 4.2 93.4 39 2.5 2.2 5 4.6 7.6 7-15.5 16.7-29.8 34.5-42.9 53.1-22.6 2-45 5.5-67.2 10.4-1.3-5.1-2.4-10.3-3.5-15.5-9.4-48.4-3.2-84.9 12.6-94zm-24.5 263.6c-4.2-1.2-8.3-2.5-12.4-3.9-21.3-6.7-45.5-17.3-63-31.2-10.1-7-16.9-17.8-18.8-29.9 0-18.3 31.6-41.7 77.2-57.6 5.7-2 11.5-3.8 17.3-5.5 6.8 21.7 15 43 24.5 63.6-9.6 20.9-17.9 42.5-24.8 64.5zm116.6 98c-16.5 15.1-35.6 27.1-56.4 35.3-11.1 5.3-23.9 5.8-35.3 1.3-15.9-9.2-22.5-44.5-13.5-92 1.1-5.6 2.3-11.2 3.7-16.7 22.4 4.8 45 8.1 67.9 9.8 13.2 18.7 27.7 36.6 43.2 53.4-3.2 3.1-6.4 6.1-9.6 8.9zm24.5-24.3c-10.2-11-20.4-23.2-30.3-36.3 9.6.4 19.5.6 29.5.6 10.3 0 20.4-.2 30.4-.7-9.2 12.7-19.1 24.8-29.6 36.4zm130.7 30c-.9 12.2-6.9 23.6-16.5 31.3-15.9 9.2-49.8-2.8-86.4-34.2-4.2-3.6-8.4-7.5-12.7-11.5 15.3-16.9 29.4-34.8 42.2-53.6 22.9-1.9 45.7-5.4 68.2-10.5 1 4.1 1.9 8.2 2.7 12.2 4.9 21.6 5.7 44.1 2.5 66.3zm18.2-107.5c-2.8.9-5.6 1.8-8.5 2.6-7-21.8-15.6-43.1-25.5-63.8 9.6-20.4 17.7-41.4 24.5-62.9 5.2 1.5 10.2 3.1 15 4.7 46.6 16 79.3 39.8 79.3 58 0 19.6-34.9 44.9-84.8 61.4zm-149.7-15c25.3 0 45.8-20.5 45.8-45.8s-20.5-45.8-45.8-45.8c-25.3 0-45.8 20.5-45.8 45.8s20.5 45.8 45.8 45.8z\"],\n    \"reacteurope\": [576, 512, [], \"f75d\", \"M250.6 211.74l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm63.7 0l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.2-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm-91.3 50.5h-3.4c-4.8 0-3.8 4-3.8 12.1 0 4.7-2.3 6.1-5.8 6.1s-5.8-1.4-5.8-6.1v-36.6c0-4.7 2.3-6.1 5.8-6.1s5.8 1.4 5.8 6.1c0 7.2-.7 10.5 3.8 10.5h3.4c4.7-.1 3.8-3.9 3.8-12.3 0-9.9-6.7-14.1-16.8-14.1h-.2c-10.1 0-16.8 4.2-16.8 14.1V276c0 10.4 6.7 14.1 16.8 14.1h.2c10.1 0 16.8-3.8 16.8-14.1 0-9.86 1.1-13.76-3.8-13.76zm-80.7 17.4h-14.7v-19.3H139c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-11.4v-18.3H142c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-21.7c-2.4-.1-3.7 1.3-3.7 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h21.9c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8zm-42-18.5c4.6-2 7.3-6 7.3-12.4v-11.9c0-10.1-6.7-14.1-16.8-14.1H77.4c-2.5 0-3.8 1.3-3.8 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5 0 3.8-1.3 3.8-3.8v-22.9h5.6l7.4 23.5a4.1 4.1 0 0 0 4.3 3.2h3.3c2.8 0 4-1.8 3.2-4.4zm-3.8-14c0 4.8-2.5 6.1-6.1 6.1h-5.8v-20.9h5.8c3.6 0 6.1 1.3 6.1 6.1zM176 226a3.82 3.82 0 0 0-4.2-3.4h-6.9a3.68 3.68 0 0 0-4 3.4l-11 59.2c-.5 2.7.9 4.1 3.4 4.1h3a3.74 3.74 0 0 0 4.1-3.5l1.8-11.3h12.2l1.8 11.3a3.74 3.74 0 0 0 4.1 3.5h3.5c2.6 0 3.9-1.4 3.4-4.1zm-12.3 39.3l4.7-29.7 4.7 29.7zm89.3 20.2v-53.2h7.5c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-25.8c-2.5 0-3.8 1.3-3.8 3.8v2.1c0 2.5 1.3 3.8 3.8 3.8h7.3v53.2c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5.04 3.8-1.3 3.8-3.76zm248-.8h-19.4V258h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9H501a1.81 1.81 0 0 0 2-1.9v-.8a1.84 1.84 0 0 0-2-1.96zm-93.1-62.9h-.8c-10.1 0-15.3 4.7-15.3 14.1V276c0 9.3 5.2 14.1 15.3 14.1h.8c10.1 0 15.3-4.8 15.3-14.1v-40.1c0-9.36-5.2-14.06-15.3-14.06zm10.2 52.4c-.1 8-3 11.1-10.5 11.1s-10.5-3.1-10.5-11.1v-36.6c0-7.9 3-11.1 10.5-11.1s10.5 3.2 10.5 11.1zm-46.5-14.5c6.1-1.6 9.2-6.1 9.2-13.3v-9.7c0-9.4-5.2-14.1-15.3-14.1h-13.7a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.9h11.6l10.4 27.2a2.32 2.32 0 0 0 2.3 1.5h1.5c1.4 0 2-1 1.5-2.3zm-6.4-3.9H355v-28.5h10.2c7.5 0 10.5 3.1 10.5 11.1v6.4c0 7.84-3 11.04-10.5 11.04zm85.9-33.1h-13.7a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.1h10.6c10.1 0 15.3-4.8 15.3-14.1v-10.5c0-9.4-5.2-14.1-15.3-14.1zm10.2 22.8c0 7.9-3 11.1-10.5 11.1h-10.2v-29.2h10.2c7.5-.1 10.5 3.1 10.5 11zM259.5 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm227.6-136.1a364.42 364.42 0 0 0-35.6-11.3c19.6-78 11.6-134.7-22.3-153.9C394.7-12.66 343.3 11 291 61.94q5.1 4.95 10.2 10.2c82.5-80 119.6-53.5 120.9-52.8 22.4 12.7 36 55.8 15.5 137.8a587.83 587.83 0 0 0-84.6-13C281.1 43.64 212.4 2 170.8 2 140 2 127 23 123.2 29.74c-18.1 32-13.3 84.2.1 133.8-70.5 20.3-120.7 54.1-120.3 95 .5 59.6 103.2 87.8 122.1 92.8-20.5 81.9-10.1 135.6 22.3 153.9 28 15.8 75.1 6 138.2-55.2q-5.1-4.95-10.2-10.2c-82.5 80-119.7 53.5-120.9 52.8-22.3-12.6-36-55.6-15.5-137.9 12.4 2.9 41.8 9.5 84.6 13 71.9 100.4 140.6 142 182.1 142 30.8 0 43.8-21 47.6-27.7 18-31.9 13.3-84.1-.1-133.8 152.3-43.8 156.2-130.2 33.9-176.3zM135.9 36.84c2.9-5.1 11.9-20.3 34.9-20.3 36.8 0 98.8 39.6 163.3 126.2a714 714 0 0 0-93.9.9 547.76 547.76 0 0 1 42.2-52.4Q277.3 86 272.2 81a598.25 598.25 0 0 0-50.7 64.2 569.69 569.69 0 0 0-84.4 14.6c-.2-1.4-24.3-82.2-1.2-123zm304.8 438.3c-2.9 5.1-11.8 20.3-34.9 20.3-36.7 0-98.7-39.4-163.3-126.2a695.38 695.38 0 0 0 93.9-.9 547.76 547.76 0 0 1-42.2 52.4q5.1 5.25 10.2 10.2a588.47 588.47 0 0 0 50.7-64.2c47.3-4.7 80.3-13.5 84.4-14.6 22.7 84.4 4.5 117 1.2 123zm9.1-138.6c-3.6-11.9-7.7-24.1-12.4-36.4a12.67 12.67 0 0 1-10.7-5.7l-.1.1a19.61 19.61 0 0 1-5.4 3.6c5.7 14.3 10.6 28.4 14.7 42.2a535.3 535.3 0 0 1-72 13c3.5-5.3 17.2-26.2 32.2-54.2a24.6 24.6 0 0 1-6-3.2c-1.1 1.2-3.6 4.2-10.9 4.2-6.2 11.2-17.4 30.9-33.9 55.2a711.91 711.91 0 0 1-112.4 1c-7.9-11.2-21.5-31.1-36.8-57.8a21 21 0 0 1-3-1.5c-1.9 1.6-3.9 3.2-12.6 3.2 6.3 11.2 17.5 30.7 33.8 54.6a548.81 548.81 0 0 1-72.2-11.7q5.85-21 14.1-42.9c-3.2 0-5.4.2-8.4-1a17.58 17.58 0 0 1-6.9 1c-4.9 13.4-9.1 26.5-12.7 39.4C-31.7 297-12.1 216 126.7 175.64c3.6 11.9 7.7 24.1 12.4 36.4 10.4 0 12.9 3.4 14.4 5.3a12 12 0 0 1 2.3-2.2c-5.8-14.7-10.9-29.2-15.2-43.3 7-1.8 32.4-8.4 72-13-15.9 24.3-26.7 43.9-32.8 55.3a14.22 14.22 0 0 1 6.4 8 23.42 23.42 0 0 1 10.2-8.4c6.5-11.7 17.9-31.9 34.8-56.9a711.72 711.72 0 0 1 112.4-1c31.5 44.6 28.9 48.1 42.5 64.5a21.42 21.42 0 0 1 10.4-7.4c-6.4-11.4-17.6-31-34.3-55.5 40.4 4.1 65 10 72.2 11.7-4 14.4-8.9 29.2-14.6 44.2a20.74 20.74 0 0 1 6.8 4.3l.1.1a12.72 12.72 0 0 1 8.9-5.6c4.9-13.4 9.2-26.6 12.8-39.5a359.71 359.71 0 0 1 34.5 11c106.1 39.9 74 87.9 72.6 90.4-19.8 35.1-80.1 55.2-105.7 62.5zm-114.4-114h-1.2a1.74 1.74 0 0 0-1.9 1.9v49.8c0 7.9-2.6 11.1-10.1 11.1s-10.1-3.1-10.1-11.1v-49.8a1.69 1.69 0 0 0-1.9-1.9H309a1.81 1.81 0 0 0-2 1.9v51.5c0 9.6 5 14.1 15.1 14.1h.4c10.1 0 15.1-4.6 15.1-14.1v-51.5a2 2 0 0 0-2.2-1.9zM321.7 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm-31.1 7.4l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm5.1-30.8h-19.4v-26.7h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h22.5a1.77 1.77 0 0 0 2-1.9v-.8a1.83 1.83 0 0 0-2-2.06zm-7.4-99.4L286 192l-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1z\"],\n    \"readme\": [576, 512, [], \"f4d5\", \"M528.3 46.5H388.5c-48.1 0-89.9 33.3-100.4 80.3-10.6-47-52.3-80.3-100.4-80.3H48c-26.5 0-48 21.5-48 48v245.8c0 26.5 21.5 48 48 48h89.7c102.2 0 132.7 24.4 147.3 75 .7 2.8 5.2 2.8 6 0 14.7-50.6 45.2-75 147.3-75H528c26.5 0 48-21.5 48-48V94.6c0-26.4-21.3-47.9-47.7-48.1zM242 311.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5V289c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V251zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm259.3 121.7c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5V228c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.8c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V190z\"],\n    \"rebel\": [512, 512, [], \"f1d0\", \"M256.5 504C117.2 504 9 387.8 13.2 249.9 16 170.7 56.4 97.7 129.7 49.5c.3 0 1.9-.6 1.1.8-5.8 5.5-111.3 129.8-14.1 226.4 49.8 49.5 90 2.5 90 2.5 38.5-50.1-.6-125.9-.6-125.9-10-24.9-45.7-40.1-45.7-40.1l28.8-31.8c24.4 10.5 43.2 38.7 43.2 38.7.8-29.6-21.9-61.4-21.9-61.4L255.1 8l44.3 50.1c-20.5 28.8-21.9 62.6-21.9 62.6 13.8-23 43.5-39.3 43.5-39.3l28.5 31.8c-27.4 8.9-45.4 39.9-45.4 39.9-15.8 28.5-27.1 89.4.6 127.3 32.4 44.6 87.7-2.8 87.7-2.8 102.7-91.9-10.5-225-10.5-225-6.1-5.5.8-2.8.8-2.8 50.1 36.5 114.6 84.4 116.2 204.8C500.9 400.2 399 504 256.5 504z\"],\n    \"red-river\": [448, 512, [], \"f3e3\", \"M353.2 32H94.8C42.4 32 0 74.4 0 126.8v258.4C0 437.6 42.4 480 94.8 480h258.4c52.4 0 94.8-42.4 94.8-94.8V126.8c0-52.4-42.4-94.8-94.8-94.8zM144.9 200.9v56.3c0 27-21.9 48.9-48.9 48.9V151.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9h-56.3c-12.3-.6-24.6 11.6-24 24zm176.3 72h-56.3c-12.3-.6-24.6 11.6-24 24v56.3c0 27-21.9 48.9-48.9 48.9V247.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9z\"],\n    \"reddit\": [512, 512, [], \"f1a1\", \"M201.5 305.5c-13.8 0-24.9-11.1-24.9-24.6 0-13.8 11.1-24.9 24.9-24.9 13.6 0 24.6 11.1 24.6 24.9 0 13.6-11.1 24.6-24.6 24.6zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-132.3-41.2c-9.4 0-17.7 3.9-23.8 10-22.4-15.5-52.6-25.5-86.1-26.6l17.4-78.3 55.4 12.5c0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.3 24.9-24.9s-11.1-24.9-24.9-24.9c-9.7 0-18 5.8-22.1 13.8l-61.2-13.6c-3-.8-6.1 1.4-6.9 4.4l-19.1 86.4c-33.2 1.4-63.1 11.3-85.5 26.8-6.1-6.4-14.7-10.2-24.1-10.2-34.9 0-46.3 46.9-14.4 62.8-1.1 5-1.7 10.2-1.7 15.5 0 52.6 59.2 95.2 132 95.2 73.1 0 132.3-42.6 132.3-95.2 0-5.3-.6-10.8-1.9-15.8 31.3-16 19.8-62.5-14.9-62.5zM302.8 331c-18.2 18.2-76.1 17.9-93.6 0-2.2-2.2-6.1-2.2-8.3 0-2.5 2.5-2.5 6.4 0 8.6 22.8 22.8 87.3 22.8 110.2 0 2.5-2.2 2.5-6.1 0-8.6-2.2-2.2-6.1-2.2-8.3 0zm7.7-75c-13.6 0-24.6 11.1-24.6 24.9 0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.1 24.9-24.6 0-13.8-11-24.9-24.9-24.9z\"],\n    \"reddit-alien\": [512, 512, [], \"f281\", \"M440.3 203.5c-15 0-28.2 6.2-37.9 15.9-35.7-24.7-83.8-40.6-137.1-42.3L293 52.3l88.2 19.8c0 21.6 17.6 39.2 39.2 39.2 22 0 39.7-18.1 39.7-39.7s-17.6-39.7-39.7-39.7c-15.4 0-28.7 9.3-35.3 22l-97.4-21.6c-4.9-1.3-9.7 2.2-11 7.1L246.3 177c-52.9 2.2-100.5 18.1-136.3 42.8-9.7-10.1-23.4-16.3-38.4-16.3-55.6 0-73.8 74.6-22.9 100.1-1.8 7.9-2.6 16.3-2.6 24.7 0 83.8 94.4 151.7 210.3 151.7 116.4 0 210.8-67.9 210.8-151.7 0-8.4-.9-17.2-3.1-25.1 49.9-25.6 31.5-99.7-23.8-99.7zM129.4 308.9c0-22 17.6-39.7 39.7-39.7 21.6 0 39.2 17.6 39.2 39.7 0 21.6-17.6 39.2-39.2 39.2-22 .1-39.7-17.6-39.7-39.2zm214.3 93.5c-36.4 36.4-139.1 36.4-175.5 0-4-3.5-4-9.7 0-13.7 3.5-3.5 9.7-3.5 13.2 0 27.8 28.5 120 29 149 0 3.5-3.5 9.7-3.5 13.2 0 4.1 4 4.1 10.2.1 13.7zm-.8-54.2c-21.6 0-39.2-17.6-39.2-39.2 0-22 17.6-39.7 39.2-39.7 22 0 39.7 17.6 39.7 39.7-.1 21.5-17.7 39.2-39.7 39.2z\"],\n    \"reddit-square\": [448, 512, [], \"f1a2\", \"M283.2 345.5c2.7 2.7 2.7 6.8 0 9.2-24.5 24.5-93.8 24.6-118.4 0-2.7-2.4-2.7-6.5 0-9.2 2.4-2.4 6.5-2.4 8.9 0 18.7 19.2 81 19.6 100.5 0 2.4-2.3 6.6-2.3 9 0zm-91.3-53.8c0-14.9-11.9-26.8-26.5-26.8-14.9 0-26.8 11.9-26.8 26.8 0 14.6 11.9 26.5 26.8 26.5 14.6 0 26.5-11.9 26.5-26.5zm90.7-26.8c-14.6 0-26.5 11.9-26.5 26.8 0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-11.9 26.8-26.5 0-14.9-11.9-26.8-26.8-26.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-99.7 140.6c-10.1 0-19 4.2-25.6 10.7-24.1-16.7-56.5-27.4-92.5-28.6l18.7-84.2 59.5 13.4c0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-12.2 26.8-26.8 0-14.6-11.9-26.8-26.8-26.8-10.4 0-19.3 6.2-23.8 14.9l-65.7-14.6c-3.3-.9-6.5 1.5-7.4 4.8l-20.5 92.8c-35.7 1.5-67.8 12.2-91.9 28.9-6.5-6.8-15.8-11-25.9-11-37.5 0-49.8 50.4-15.5 67.5-1.2 5.4-1.8 11-1.8 16.7 0 56.5 63.7 102.3 141.9 102.3 78.5 0 142.2-45.8 142.2-102.3 0-5.7-.6-11.6-2.1-17 33.6-17.2 21.2-67.2-16.1-67.2z\"],\n    \"redhat\": [512, 512, [], \"f7bc\", \"M341.52 285.56c33.65 0 82.34-6.94 82.34-47 .22-6.74.86-1.82-20.88-96.24-4.62-19.15-8.68-27.84-42.31-44.65-26.09-13.34-82.92-35.37-99.73-35.37-15.66 0-20.2 20.17-38.87 20.17-18 0-31.31-15.06-48.12-15.06-16.14 0-26.66 11-34.78 33.62-27.5 77.55-26.28 74.27-26.12 78.27 0 24.8 97.64 106.11 228.47 106.11M429 254.84c4.65 22 4.65 24.35 4.65 27.25 0 37.66-42.33 58.56-98 58.56-125.74.08-235.91-73.65-235.91-122.33a49.55 49.55 0 0 1 4.06-19.72C58.56 200.86 0 208.93 0 260.63c0 84.67 200.63 189 359.49 189 121.79 0 152.51-55.08 152.51-98.58 0-34.21-29.59-73.05-82.93-96.24\"],\n    \"renren\": [512, 512, [], \"f18b\", \"M214 169.1c0 110.4-61 205.4-147.6 247.4C30 373.2 8 317.7 8 256.6 8 133.9 97.1 32.2 214 12.5v156.6zM255 504c-42.9 0-83.3-11-118.5-30.4C193.7 437.5 239.9 382.9 255 319c15.5 63.9 61.7 118.5 118.8 154.7C338.7 493 298.3 504 255 504zm190.6-87.5C359 374.5 298 279.6 298 169.1V12.5c116.9 19.7 206 121.4 206 244.1 0 61.1-22 116.6-58.4 159.9z\"],\n    \"replyd\": [448, 512, [], \"f3e6\", \"M320 480H128C57.6 480 0 422.4 0 352V160C0 89.6 57.6 32 128 32h192c70.4 0 128 57.6 128 128v192c0 70.4-57.6 128-128 128zM193.4 273.2c-6.1-2-11.6-3.1-16.4-3.1-7.2 0-13.5 1.9-18.9 5.6-5.4 3.7-9.6 9-12.8 15.8h-1.1l-4.2-18.3h-28v138.9h36.1v-89.7c1.5-5.4 4.4-9.8 8.7-13.2 4.3-3.4 9.8-5.1 16.2-5.1 4.6 0 9.8 1 15.6 3.1l4.8-34zm115.2 103.4c-3.2 2.4-7.7 4.8-13.7 7.1-6 2.3-12.8 3.5-20.4 3.5-12.2 0-21.1-3-26.5-8.9-5.5-5.9-8.5-14.7-9-26.4h83.3c.9-4.8 1.6-9.4 2.1-13.9.5-4.4.7-8.6.7-12.5 0-10.7-1.6-19.7-4.7-26.9-3.2-7.2-7.3-13-12.5-17.2-5.2-4.3-11.1-7.3-17.8-9.2-6.7-1.8-13.5-2.8-20.6-2.8-21.1 0-37.5 6.1-49.2 18.3s-17.5 30.5-17.5 55c0 22.8 5.2 40.7 15.6 53.7 10.4 13.1 26.8 19.6 49.2 19.6 10.7 0 20.9-1.5 30.4-4.6 9.5-3.1 17.1-6.8 22.6-11.2l-12-23.6zm-21.8-70.3c3.8 5.4 5.3 13.1 4.6 23.1h-51.7c.9-9.4 3.7-17 8.2-22.6 4.5-5.6 11.5-8.5 21-8.5 8.2-.1 14.1 2.6 17.9 8zm79.9 2.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4s2 11.7 6.1 15.6zm0 100.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4 0 6.6 2 11.7 6.1 15.6z\"],\n    \"researchgate\": [448, 512, [], \"f4f8\", \"M0 32v448h448V32H0zm262.2 334.4c-6.6 3-33.2 6-50-14.2-9.2-10.6-25.3-33.3-42.2-63.6-8.9 0-14.7 0-21.4-.6v46.4c0 23.5 6 21.2 25.8 23.9v8.1c-6.9-.3-23.1-.8-35.6-.8-13.1 0-26.1.6-33.6.8v-8.1c15.5-2.9 22-1.3 22-23.9V225c0-22.6-6.4-21-22-23.9V193c25.8 1 53.1-.6 70.9-.6 31.7 0 55.9 14.4 55.9 45.6 0 21.1-16.7 42.2-39.2 47.5 13.6 24.2 30 45.6 42.2 58.9 7.2 7.8 17.2 14.7 27.2 14.7v7.3zm22.9-135c-23.3 0-32.2-15.7-32.2-32.2V167c0-12.2 8.8-30.4 34-30.4s30.4 17.9 30.4 17.9l-10.7 7.2s-5.5-12.5-19.7-12.5c-7.9 0-19.7 7.3-19.7 19.7v26.8c0 13.4 6.6 23.3 17.9 23.3 14.1 0 21.5-10.9 21.5-26.8h-17.9v-10.7h30.4c0 20.5 4.7 49.9-34 49.9zm-116.5 44.7c-9.4 0-13.6-.3-20-.8v-69.7c6.4-.6 15-.6 22.5-.6 23.3 0 37.2 12.2 37.2 34.5 0 21.9-15 36.6-39.7 36.6z\"],\n    \"resolving\": [496, 512, [], \"f3e7\", \"M281.2 278.2c46-13.3 49.6-23.5 44-43.4L314 195.5c-6.1-20.9-18.4-28.1-71.1-12.8L54.7 236.8l28.6 98.6 197.9-57.2zM248.5 8C131.4 8 33.2 88.7 7.2 197.5l221.9-63.9c34.8-10.2 54.2-11.7 79.3-8.2 36.3 6.1 52.7 25 61.4 55.2l10.7 37.8c8.2 28.1 1 50.6-23.5 73.6-19.4 17.4-31.2 24.5-61.4 33.2L203 351.8l220.4 27.1 9.7 34.2-48.1 13.3-286.8-37.3 23 80.2c36.8 22 80.3 34.7 126.3 34.7 137 0 248.5-111.4 248.5-248.3C497 119.4 385.5 8 248.5 8zM38.3 388.6L0 256.8c0 48.5 14.3 93.4 38.3 131.8z\"],\n    \"rev\": [448, 512, [], \"f5b2\", \"M289.67 274.89a65.57 65.57 0 1 1-65.56-65.56 65.64 65.64 0 0 1 65.56 65.56zm139.55-5.05h-.13a204.69 204.69 0 0 0-74.32-153l-45.38 26.2a157.07 157.07 0 0 1 71.81 131.84C381.2 361.5 310.73 432 224.11 432S67 361.5 67 274.88c0-81.88 63-149.27 143-156.43v39.12l108.77-62.79L210 32v38.32c-106.7 7.25-191 96-191 204.57 0 111.59 89.12 202.29 200.06 205v.11h210.16V269.84z\"],\n    \"rocketchat\": [576, 512, [], \"f3e8\", \"M486.41 107.57c-76.93-50.83-179.18-62.4-264.12-47.07C127.26-31.16 20.77 11 0 23.12c0 0 73.08 62.1 61.21 116.49-86.52 88.2-45.39 186.4 0 232.77C73.08 426.77 0 488.87 0 488.87c20.57 12.16 126.77 54.19 222.29-37 84.75 15.23 187 3.76 264.12-47.16 119.26-76.14 119.65-220.61 0-297.15zM294.18 404.22a339.53 339.53 0 0 1-88.11-11.37l-19.77 19.09a179.74 179.74 0 0 1-36.59 27.39A143.14 143.14 0 0 1 98 454.06c1-1.78 1.88-3.56 2.77-5.24q29.67-55 16-98.69c-32.53-25.61-52-58.34-52-94.13 0-82 102.74-148.43 229.41-148.43S523.59 174 523.59 256 420.85 404.22 294.18 404.22zM184.12 291.3a34.32 34.32 0 0 1-34.8-33.72c-.7-45.39 67.83-46.38 68.52-1.09v.51a34 34 0 0 1-33.72 34.32zm73.77-33.72c-.79-45.39 67.74-46.48 68.53-1.19v.61c.39 45.08-67.74 45.57-68.53.58zm143.38 33.72a34.33 34.33 0 0 1-34.81-33.72c-.69-45.39 67.84-46.38 68.53-1.09v.51a33.89 33.89 0 0 1-33.72 34.32z\"],\n    \"rockrms\": [496, 512, [], \"f3e9\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm157.4 419.5h-90l-112-131.3c-17.9-20.4-3.9-56.1 26.6-56.1h75.3l-84.6-99.3-84.3 98.9h-90L193.5 67.2c14.4-18.4 41.3-17.3 54.5 0l157.7 185.1c19 22.8 2 57.2-27.6 56.1-.6 0-74.2.2-74.2.2l101.5 118.9z\"],\n    \"safari\": [512, 512, [], \"f267\", \"M236.9 256.8c0-9.1 6.6-17.7 16.3-17.7 8.9 0 17.4 6.4 17.4 16.1 0 9.1-6.4 17.7-16.1 17.7-9 0-17.6-6.7-17.6-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-26.6 0c0-122.3-99.1-221.4-221.4-221.4S34.6 133.7 34.6 256 133.7 477.4 256 477.4 477.4 378.3 477.4 256zm-72.5 96.6c0 3.6 13 10.2 16.3 12.2-27.4 41.5-69.8 71.4-117.9 83.3l-4.4-18.5c-.3-2.5-1.9-2.8-4.2-2.8-1.9 0-3 2.8-2.8 4.2l4.4 18.8c-13.3 2.8-26.8 4.2-40.4 4.2-36.3 0-72-10.2-103-29.1 1.7-2.8 12.2-18 12.2-20.2 0-1.9-1.7-3.6-3.6-3.6-3.9 0-12.2 16.6-14.7 19.9-41.8-27.7-72-70.6-83.6-119.6l19.1-4.2c2.2-.6 2.8-2.2 2.8-4.2 0-1.9-2.8-3-4.4-2.8L62 294.5c-2.5-12.7-3.9-25.5-3.9-38.5 0-37.1 10.5-73.6 30.2-104.9 2.8 1.7 16.1 10.8 18.3 10.8 1.9 0 3.6-1.4 3.6-3.3 0-3.9-14.7-11.3-18-13.6 28.2-41.2 71.1-70.9 119.8-81.9l4.2 18.5c.6 2.2 2.2 2.8 4.2 2.8s3-2.8 2.8-4.4L219 61.7c12.2-2.2 24.6-3.6 37.1-3.6 37.1 0 73.3 10.5 104.9 30.2-1.9 2.8-10.8 15.8-10.8 18 0 1.9 1.4 3.6 3.3 3.6 3.9 0 11.3-14.4 13.3-17.7 41 27.7 70.3 70 81.7 118.2l-15.5 3.3c-2.5.6-2.8 2.2-2.8 4.4 0 1.9 2.8 3 4.2 2.8l15.8-3.6c2.5 12.7 3.9 25.7 3.9 38.7 0 36.3-10 72-28.8 102.7-2.8-1.4-14.4-9.7-16.6-9.7-2.1 0-3.8 1.7-3.8 3.6zm-33.2-242.2c-13 12.2-134.2 123.7-137.6 129.5l-96.6 160.5c12.7-11.9 134.2-124 137.3-129.3l96.9-160.7z\"],\n    \"salesforce\": [640, 512, [], \"f83b\", \"M248.89 245.64h-26.35c.69-5.16 3.32-14.12 13.64-14.12 6.75 0 11.97 3.82 12.71 14.12zm136.66-13.88c-.47 0-14.11-1.77-14.11 20s13.63 20 14.11 20c13 0 14.11-13.54 14.11-20 0-21.76-13.66-20-14.11-20zm-243.22 23.76a8.63 8.63 0 0 0-3.29 7.29c0 4.78 2.08 6.05 3.29 7.05 4.7 3.7 15.07 2.12 20.93.95v-16.94c-5.32-1.07-16.73-1.96-20.93 1.65zM640 232c0 87.58-80 154.39-165.36 136.43-18.37 33-70.73 70.75-132.2 41.63-41.16 96.05-177.89 92.18-213.81-5.17C8.91 428.78-50.19 266.52 53.36 205.61 18.61 126.18 76 32 167.67 32a124.24 124.24 0 0 1 98.56 48.7c20.7-21.4 49.4-34.81 81.15-34.81 42.34 0 79 23.52 98.8 58.57C539 63.78 640 132.69 640 232zm-519.55 31.8c0-11.76-11.69-15.17-17.87-17.17-5.27-2.11-13.41-3.51-13.41-8.94 0-9.46 17-6.66 25.17-2.12 0 0 1.17.71 1.64-.47.24-.7 2.36-6.58 2.59-7.29a1.13 1.13 0 0 0-.7-1.41c-12.33-7.63-40.7-8.51-40.7 12.7 0 12.46 11.49 15.44 17.88 17.17 4.72 1.58 13.17 3 13.17 8.7 0 4-3.53 7.06-9.17 7.06a31.76 31.76 0 0 1-19-6.35c-.47-.23-1.42-.71-1.65.71l-2.4 7.47c-.47.94.23 1.18.23 1.41 1.75 1.4 10.3 6.59 22.82 6.59 13.17 0 21.4-7.06 21.4-18.11zm32-42.58c-10.13 0-18.66 3.17-21.4 5.18a1 1 0 0 0-.24 1.41l2.59 7.06a1 1 0 0 0 1.18.7c.65 0 6.8-4 16.93-4 4 0 7.06.71 9.18 2.36 3.6 2.8 3.06 8.29 3.06 10.58-4.79-.3-19.11-3.44-29.41 3.76a16.92 16.92 0 0 0-7.34 14.54c0 5.9 1.51 10.4 6.59 14.35 12.24 8.16 36.28 2 38.1 1.41 1.58-.32 3.53-.66 3.53-1.88v-33.88c.04-4.61.32-21.64-22.78-21.64zM199 200.24a1.11 1.11 0 0 0-1.18-1.18H188a1.11 1.11 0 0 0-1.17 1.18v79a1.11 1.11 0 0 0 1.17 1.18h9.88a1.11 1.11 0 0 0 1.18-1.18zm55.75 28.93c-2.1-2.31-6.79-7.53-17.65-7.53-3.51 0-14.16.23-20.7 8.94-6.35 7.63-6.58 18.11-6.58 21.41 0 3.12.15 14.26 7.06 21.17 2.64 2.91 9.06 8.23 22.81 8.23 10.82 0 16.47-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.35-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.94-16.7h37.17a1.23 1.23 0 0 0 1.17-.94c-.29 0 2.07-14.7-6.09-24.23zm36.69 52.69c13.17 0 21.41-7.06 21.41-18.11 0-11.76-11.7-15.17-17.88-17.17-4.14-1.66-13.41-3.38-13.41-8.94 0-3.76 3.29-6.35 8.47-6.35a38.11 38.11 0 0 1 16.7 4.23s1.18.71 1.65-.47c.23-.7 2.35-6.58 2.58-7.29a1.13 1.13 0 0 0-.7-1.41c-7.91-4.9-16.74-4.94-20.23-4.94-12 0-20.46 7.29-20.46 17.64 0 12.46 11.48 15.44 17.87 17.17 6.11 2 13.17 3.26 13.17 8.7 0 4-3.52 7.06-9.17 7.06a31.8 31.8 0 0 1-19-6.35 1 1 0 0 0-1.65.71l-2.35 7.52c-.47.94.23 1.18.23 1.41 1.72 1.4 10.33 6.59 22.79 6.59zM357.09 224c0-.71-.24-1.18-1.18-1.18h-11.76c0-.14.94-8.94 4.47-12.47 4.16-4.15 11.76-1.64 12-1.64 1.17.47 1.41 0 1.64-.47l2.83-7.77c.7-.94 0-1.17-.24-1.41-5.09-2-17.35-2.87-24.46 4.24-5.48 5.48-7 13.92-8 19.52h-8.47a1.28 1.28 0 0 0-1.17 1.18l-1.42 7.76c0 .7.24 1.17 1.18 1.17h8.23c-8.51 47.9-8.75 50.21-10.35 55.52-1.08 3.62-3.29 6.9-5.88 7.76-.09 0-3.88 1.68-9.64-.24 0 0-.94-.47-1.41.71-.24.71-2.59 6.82-2.83 7.53s0 1.41.47 1.41c5.11 2 13 1.77 17.88 0 6.28-2.28 9.72-7.89 11.53-12.94 2.75-7.71 2.81-9.79 11.76-59.74h12.23a1.29 1.29 0 0 0 1.18-1.18zm53.39 16c-.56-1.68-5.1-18.11-25.17-18.11-15.25 0-23 10-25.16 18.11-1 3-3.18 14 0 23.52.09.3 4.41 18.12 25.16 18.12 14.95 0 22.9-9.61 25.17-18.12 3.21-9.61 1.01-20.52 0-23.52zm45.4-16.7c-5-1.65-16.62-1.9-22.11 5.41v-4.47a1.11 1.11 0 0 0-1.18-1.17h-9.4a1.11 1.11 0 0 0-1.18 1.17v55.28a1.12 1.12 0 0 0 1.18 1.18h9.64a1.12 1.12 0 0 0 1.18-1.18v-27.77c0-2.91.05-11.37 4.46-15.05 4.9-4.9 12-3.36 13.41-3.06a1.57 1.57 0 0 0 1.41-.94 74 74 0 0 0 3.06-8 1.16 1.16 0 0 0-.47-1.41zm46.81 54.1l-2.12-7.29c-.47-1.18-1.41-.71-1.41-.71-4.23 1.82-10.15 1.89-11.29 1.89-4.64 0-17.17-1.13-17.17-19.76 0-6.23 1.85-19.76 16.47-19.76a34.85 34.85 0 0 1 11.52 1.65s.94.47 1.18-.71c.94-2.59 1.64-4.47 2.59-7.53.23-.94-.47-1.17-.71-1.17-11.59-3.87-22.34-2.53-27.76 0-1.59.74-16.23 6.49-16.23 27.52 0 2.9-.58 30.11 28.94 30.11a44.45 44.45 0 0 0 15.52-2.83 1.3 1.3 0 0 0 .47-1.42zm53.87-39.52c-.8-3-5.37-16.23-22.35-16.23-16 0-23.52 10.11-25.64 18.59a38.58 38.58 0 0 0-1.65 11.76c0 25.87 18.84 29.4 29.88 29.4 10.82 0 16.46-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.36-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.93-16.7h37.16a1.25 1.25 0 0 0 1.18-.94c-.24-.01.94-7.07-1.41-15.54zm-23.29-6.35c-10.33 0-13 9-13.64 14.12H546c-.88-11.92-7.62-14.13-12.73-14.13z\"],\n    \"sass\": [640, 512, [], \"f41e\", \"M301.84 378.92c-.3.6-.6 1.08 0 0zm249.13-87a131.16 131.16 0 0 0-58 13.5c-5.9-11.9-12-22.3-13-30.1-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.3-6.7-24 2.5-25.29 5.9a122.83 122.83 0 0 0-5.3 19.1c-2.3 11.7-25.79 53.5-39.09 75.3-4.4-8.5-8.1-16-8.9-22-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.29-6.7-24 2.5-25.3 5.9-2.7 11.4-5.3 19.1-33.89 77.3-42.08 95.4c-4.2 9.2-7.8 16.6-10.4 21.6-.4.8-.7 1.3-.9 1.7.3-.5.5-1 .5-.8-2.2 4.3-3.5 6.7-3.5 6.7v.1c-1.7 3.2-3.6 6.1-4.5 6.1-.6 0-1.9-8.4.3-19.9 4.7-24.2 15.8-61.8 15.7-63.1-.1-.7 2.1-7.2-7.3-10.7-9.1-3.3-12.4 2.2-13.2 2.2s-1.4 2-1.4 2 10.1-42.4-19.39-42.4c-18.4 0-44 20.2-56.58 38.5-7.9 4.3-25 13.6-43 23.5-6.9 3.8-14 7.7-20.7 11.4-.5-.5-.9-1-1.4-1.5-35.79-38.2-101.87-65.2-99.07-116.5 1-18.7 7.5-67.8 127.07-127.4 98-48.8 176.35-35.4 189.84-5.6 19.4 42.5-41.89 121.6-143.66 133-38.79 4.3-59.18-10.7-64.28-16.3-5.3-5.9-6.1-6.2-8.1-5.1-3.3 1.8-1.2 7 0 10.1 3 7.9 15.5 21.9 36.79 28.9 18.7 6.1 64.18 9.5 119.17-11.8 61.78-23.8 109.87-90.1 95.77-145.6C386.52 18.32 293-.18 204.57 31.22c-52.69 18.7-109.67 48.1-150.66 86.4-48.69 45.6-56.48 85.3-53.28 101.9 11.39 58.9 92.57 97.3 125.06 125.7-1.6.9-3.1 1.7-4.5 2.5-16.29 8.1-78.18 40.5-93.67 74.7-17.5 38.8 2.9 66.6 16.29 70.4 41.79 11.6 84.58-9.3 107.57-43.6s20.2-79.1 9.6-99.5c-.1-.3-.3-.5-.4-.8 4.2-2.5 8.5-5 12.8-7.5 8.29-4.9 16.39-9.4 23.49-13.3-4 10.8-6.9 23.8-8.4 42.6-1.8 22 7.3 50.5 19.1 61.7 5.2 4.9 11.49 5 15.39 5 13.8 0 20-11.4 26.89-25 8.5-16.6 16-35.9 16-35.9s-9.4 52.2 16.3 52.2c9.39 0 18.79-12.1 23-18.3v.1s.2-.4.7-1.2c1-1.5 1.5-2.4 1.5-2.4v-.3c3.8-6.5 12.1-21.4 24.59-46 16.2-31.8 31.69-71.5 31.69-71.5a201.24 201.24 0 0 0 6.2 25.8c2.8 9.5 8.7 19.9 13.4 30-3.8 5.2-6.1 8.2-6.1 8.2a.31.31 0 0 0 .1.2c-3 4-6.4 8.3-9.9 12.5-12.79 15.2-28 32.6-30 37.6-2.4 5.9-1.8 10.3 2.8 13.7 3.4 2.6 9.4 3 15.69 2.5 11.5-.8 19.6-3.6 23.5-5.4a82.2 82.2 0 0 0 20.19-10.6c12.5-9.2 20.1-22.4 19.4-39.8-.4-9.6-3.5-19.2-7.3-28.2 1.1-1.6 2.3-3.3 3.4-5C434.8 301.72 450.1 270 450.1 270a201.24 201.24 0 0 0 6.2 25.8c2.4 8.1 7.09 17 11.39 25.7-18.59 15.1-30.09 32.6-34.09 44.1-7.4 21.3-1.6 30.9 9.3 33.1 4.9 1 11.9-1.3 17.1-3.5a79.46 79.46 0 0 0 21.59-11.1c12.5-9.2 24.59-22.1 23.79-39.6-.3-7.9-2.5-15.8-5.4-23.4 15.7-6.6 36.09-10.2 62.09-7.2 55.68 6.5 66.58 41.3 64.48 55.8s-13.8 22.6-17.7 25-5.1 3.3-4.8 5.1c.5 2.6 2.3 2.5 5.6 1.9 4.6-.8 29.19-11.8 30.29-38.7 1.6-34-31.09-71.4-89-71.1zm-429.18 144.7c-18.39 20.1-44.19 27.7-55.28 21.3C54.61 451 59.31 421.42 82 400c13.8-13 31.59-25 43.39-32.4 2.7-1.6 6.6-4 11.4-6.9.8-.5 1.2-.7 1.2-.7.9-.6 1.9-1.1 2.9-1.7 8.29 30.4.3 57.2-19.1 78.3zm134.36-91.4c-6.4 15.7-19.89 55.7-28.09 53.6-7-1.8-11.3-32.3-1.4-62.3 5-15.1 15.6-33.1 21.9-40.1 10.09-11.3 21.19-14.9 23.79-10.4 3.5 5.9-12.2 49.4-16.2 59.2zm111 53c-2.7 1.4-5.2 2.3-6.4 1.6-.9-.5 1.1-2.4 1.1-2.4s13.9-14.9 19.4-21.7c3.2-4 6.9-8.7 10.89-13.9 0 .5.1 1 .1 1.6-.13 17.9-17.32 30-25.12 34.8zm85.58-19.5c-2-1.4-1.7-6.1 5-20.7 2.6-5.7 8.59-15.3 19-24.5a36.18 36.18 0 0 1 1.9 10.8c-.1 22.5-16.2 30.9-25.89 34.4z\"],\n    \"schlix\": [448, 512, [], \"f3ea\", \"M350.5 157.7l-54.2-46.1 73.4-39 78.3 44.2-97.5 40.9zM192 122.1l45.7-28.2 34.7 34.6-55.4 29-25-35.4zm-65.1 6.6l31.9-22.1L176 135l-36.7 22.5-12.4-28.8zm-23.3 88.2l-8.8-34.8 29.6-18.3 13.1 35.3-33.9 17.8zm-21.2-83.7l23.9-18.1 8.9 24-26.7 18.3-6.1-24.2zM59 206.5l-3.6-28.4 22.3-15.5 6.1 28.7L59 206.5zm-30.6 16.6l20.8-12.8 3.3 33.4-22.9 12-1.2-32.6zM1.4 268l19.2-10.2.4 38.2-21 8.8L1.4 268zm59.1 59.3l-28.3 8.3-1.6-46.8 25.1-10.7 4.8 49.2zM99 263.2l-31.1 13-5.2-40.8L90.1 221l8.9 42.2zM123.2 377l-41.6 5.9-8.1-63.5 35.2-10.8 14.5 68.4zm28.5-139.9l21.2 57.1-46.2 13.6-13.7-54.1 38.7-16.6zm85.7 230.5l-70.9-3.3-24.3-95.8 55.2-8.6 40 107.7zm-84.9-279.7l42.2-22.4 28 45.9-50.8 21.3-19.4-44.8zm41 94.9l61.3-18.7 52.8 86.6-79.8 11.3-34.3-79.2zm51.4-85.6l67.3-28.8 65.5 65.4-88.6 26.2-44.2-62.8z\"],\n    \"scribd\": [384, 512, [], \"f28a\", \"M42.3 252.7c-16.1-19-24.7-45.9-24.8-79.9 0-100.4 75.2-153.1 167.2-153.1 98.6-1.6 156.8 49 184.3 70.6l-50.5 72.1-37.3-24.6 26.9-38.6c-36.5-24-79.4-36.5-123-35.8-50.7-.8-111.7 27.2-111.7 76.2 0 18.7 11.2 20.7 28.6 15.6 23.3-5.3 41.9.6 55.8 14 26.4 24.3 23.2 67.6-.7 91.9-29.2 29.5-85.2 27.3-114.8-8.4zm317.7 5.9c-15.5-18.8-38.9-29.4-63.2-28.6-38.1-2-71.1 28-70.5 67.2-.7 16.8 6 33 18.4 44.3 14.1 13.9 33 19.7 56.3 14.4 17.4-5.1 28.6-3.1 28.6 15.6 0 4.3-.5 8.5-1.4 12.7-16.7 40.9-59.5 64.4-121.4 64.4-51.9.2-102.4-16.4-144.1-47.3l33.7-39.4-35.6-27.4L0 406.3l15.4 13.8c52.5 46.8 120.4 72.5 190.7 72.2 51.4 0 94.4-10.5 133.6-44.1 57.1-51.4 54.2-149.2 20.3-189.6z\"],\n    \"searchengin\": [460, 512, [], \"f3eb\", \"M220.6 130.3l-67.2 28.2V43.2L98.7 233.5l54.7-24.2v130.3l67.2-209.3zm-83.2-96.7l-1.3 4.7-15.2 52.9C80.6 106.7 52 145.8 52 191.5c0 52.3 34.3 95.9 83.4 105.5v53.6C57.5 340.1 0 272.4 0 191.6c0-80.5 59.8-147.2 137.4-158zm311.4 447.2c-11.2 11.2-23.1 12.3-28.6 10.5-5.4-1.8-27.1-19.9-60.4-44.4-33.3-24.6-33.6-35.7-43-56.7-9.4-20.9-30.4-42.6-57.5-52.4l-9.7-14.7c-24.7 16.9-53 26.9-81.3 28.7l2.1-6.6 15.9-49.5c46.5-11.9 80.9-54 80.9-104.2 0-54.5-38.4-102.1-96-107.1V32.3C254.4 37.4 320 106.8 320 191.6c0 33.6-11.2 64.7-29 90.4l14.6 9.6c9.8 27.1 31.5 48 52.4 57.4s32.2 9.7 56.8 43c24.6 33.2 42.7 54.9 44.5 60.3s.7 17.3-10.5 28.5zm-9.9-17.9c0-4.4-3.6-8-8-8s-8 3.6-8 8 3.6 8 8 8 8-3.6 8-8z\"],\n    \"sellcast\": [448, 512, [], \"f2da\", \"M353.4 32H94.7C42.6 32 0 74.6 0 126.6v258.7C0 437.4 42.6 480 94.7 480h258.7c52.1 0 94.7-42.6 94.7-94.6V126.6c0-52-42.6-94.6-94.7-94.6zm-50 316.4c-27.9 48.2-89.9 64.9-138.2 37.2-22.9 39.8-54.9 8.6-42.3-13.2l15.7-27.2c5.9-10.3 19.2-13.9 29.5-7.9 18.6 10.8-.1-.1 18.5 10.7 27.6 15.9 63.4 6.3 79.4-21.3 15.9-27.6 6.3-63.4-21.3-79.4-17.8-10.2-.6-.4-18.6-10.6-24.6-14.2-3.4-51.9 21.6-37.5 18.6 10.8-.1-.1 18.5 10.7 48.4 28 65.1 90.3 37.2 138.5zm21.8-208.8c-17 29.5-16.3 28.8-19 31.5-6.5 6.5-16.3 8.7-26.5 3.6-18.6-10.8.1.1-18.5-10.7-27.6-15.9-63.4-6.3-79.4 21.3s-6.3 63.4 21.3 79.4c0 0 18.5 10.6 18.6 10.6 24.6 14.2 3.4 51.9-21.6 37.5-18.6-10.8.1.1-18.5-10.7-48.2-27.8-64.9-90.1-37.1-138.4 27.9-48.2 89.9-64.9 138.2-37.2l4.8-8.4c14.3-24.9 52-3.3 37.7 21.5z\"],\n    \"sellsy\": [640, 512, [], \"f213\", \"M539.71 237.308c3.064-12.257 4.29-24.821 4.29-37.384C544 107.382 468.618 32 376.076 32c-77.22 0-144.634 53.012-163.02 127.781-15.322-13.176-34.934-20.53-55.157-20.53-46.271 0-83.962 37.69-83.962 83.961 0 7.354.92 15.015 3.065 22.369-42.9 20.225-70.785 63.738-70.785 111.234C6.216 424.843 61.68 480 129.401 480h381.198c67.72 0 123.184-55.157 123.184-123.184.001-56.384-38.916-106.025-94.073-119.508zM199.88 401.554c0 8.274-7.048 15.321-15.321 15.321H153.61c-8.274 0-15.321-7.048-15.321-15.321V290.626c0-8.273 7.048-15.321 15.321-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v110.928zm89.477 0c0 8.274-7.048 15.321-15.322 15.321h-30.949c-8.274 0-15.321-7.048-15.321-15.321V270.096c0-8.274 7.048-15.321 15.321-15.321h30.949c8.274 0 15.322 7.048 15.322 15.321v131.458zm89.477 0c0 8.274-7.047 15.321-15.321 15.321h-30.949c-8.274 0-15.322-7.048-15.322-15.321V238.84c0-8.274 7.048-15.321 15.322-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v162.714zm87.027 0c0 8.274-7.048 15.321-15.322 15.321h-28.497c-8.274 0-15.321-7.048-15.321-15.321V176.941c0-8.579 7.047-15.628 15.321-15.628h28.497c8.274 0 15.322 7.048 15.322 15.628v224.613z\"],\n    \"servicestack\": [496, 512, [], \"f3ec\", \"M88 216c81.7 10.2 273.7 102.3 304 232H0c99.5-8.1 184.5-137 88-232zm32-152c32.3 35.6 47.7 83.9 46.4 133.6C249.3 231.3 373.7 321.3 400 448h96C455.3 231.9 222.8 79.5 120 64z\"],\n    \"shirtsinbulk\": [448, 512, [], \"f214\", \"M100 410.3l30.6 13.4 4.4-9.9-30.6-13.4zm39.4 17.5l30.6 13.4 4.4-9.9-30.6-13.4zm172.1-14l4.4 9.9 30.6-13.4-4.4-9.9zM179.1 445l30.3 13.7 4.4-9.9-30.3-13.4zM60.4 392.8L91 406.2l4.4-9.6-30.6-13.7zm211.4 38.5l4.4 9.9 30.6-13.4-4.4-9.9zm-39.3 17.5l4.4 9.9 30.6-13.7-4.4-9.6zm118.4-52.2l4.4 9.6 30.6-13.4-4.4-9.9zM170 46.6h-33.5v10.5H170zm-47.2 0H89.2v10.5h33.5zm-47.3 0H42.3v10.5h33.3zm141.5 0h-33.2v10.5H217zm94.5 0H278v10.5h33.5zm47.3 0h-33.5v10.5h33.5zm-94.6 0H231v10.5h33.2zm141.5 0h-33.3v10.5h33.3zM52.8 351.1H42v33.5h10.8zm70-215.9H89.2v10.5h33.5zm-70 10.6h22.8v-10.5H42v33.5h10.8zm168.9 228.6c50.5 0 91.3-40.8 91.3-91.3 0-50.2-40.8-91.3-91.3-91.3-50.2 0-91.3 41.1-91.3 91.3 0 50.5 41.1 91.3 91.3 91.3zm-48.2-111.1c0-25.4 29.5-31.8 49.6-31.8 16.9 0 29.2 5.8 44.3 12l-8.8 16.9h-.9c-6.4-9.9-24.8-13.1-35.6-13.1-9 0-29.8 1.8-29.8 14.9 0 21.6 78.5-10.2 78.5 37.9 0 25.4-31.5 31.2-51 31.2-18.1 0-32.4-2.9-47.2-12.2l9-18.4h.9c6.1 12.2 23.6 14.9 35.9 14.9 8.7 0 32.7-1.2 32.7-14.3 0-26.1-77.6 6.3-77.6-38zM52.8 178.4H42V212h10.8zm342.4 206.2H406v-33.5h-10.8zM52.8 307.9H42v33.5h10.8zM0 3.7v406l221.7 98.6L448 409.7V3.7zm418.8 387.1L222 476.5 29.2 390.8V120.7h389.7v270.1zm0-299.3H29.2V32.9h389.7v58.6zm-366 130.1H42v33.5h10.8zm0 43.2H42v33.5h10.8zM170 135.2h-33.5v10.5H170zm225.2 163.1H406v-33.5h-10.8zm0-43.2H406v-33.5h-10.8zM217 135.2h-33.2v10.5H217zM395.2 212H406v-33.5h-10.8zm0 129.5H406V308h-10.8zm-131-206.3H231v10.5h33.2zm47.3 0H278v10.5h33.5zm83.7 33.6H406v-33.5h-33.5v10.5h22.8zm-36.4-33.6h-33.5v10.5h33.5z\"],\n    \"shopware\": [512, 512, [], \"f5b5\", \"M403.5 455.41A246.17 246.17 0 0 1 256 504C118.81 504 8 393 8 256 8 118.81 119 8 256 8a247.39 247.39 0 0 1 165.7 63.5 3.57 3.57 0 0 1-2.86 6.18A418.62 418.62 0 0 0 362.13 74c-129.36 0-222.4 53.47-222.4 155.35 0 109 92.13 145.88 176.83 178.73 33.64 13 65.4 25.36 87 41.59a3.58 3.58 0 0 1 0 5.72zM503 233.09a3.64 3.64 0 0 0-1.27-2.44c-51.76-43-93.62-60.48-144.48-60.48-84.13 0-80.25 52.17-80.25 53.63 0 42.6 52.06 62 112.34 84.49 31.07 11.59 63.19 23.57 92.68 39.93a3.57 3.57 0 0 0 5-1.82A249 249 0 0 0 503 233.09z\"],\n    \"simplybuilt\": [512, 512, [], \"f215\", \"M481.2 64h-106c-14.5 0-26.6 11.8-26.6 26.3v39.6H163.3V90.3c0-14.5-12-26.3-26.6-26.3h-106C16.1 64 4.3 75.8 4.3 90.3v331.4c0 14.5 11.8 26.3 26.6 26.3h450.4c14.8 0 26.6-11.8 26.6-26.3V90.3c-.2-14.5-12-26.3-26.7-26.3zM149.8 355.8c-36.6 0-66.4-29.7-66.4-66.4 0-36.9 29.7-66.6 66.4-66.6 36.9 0 66.6 29.7 66.6 66.6 0 36.7-29.7 66.4-66.6 66.4zm212.4 0c-36.9 0-66.6-29.7-66.6-66.6 0-36.6 29.7-66.4 66.6-66.4 36.6 0 66.4 29.7 66.4 66.4 0 36.9-29.8 66.6-66.4 66.6z\"],\n    \"sistrix\": [448, 512, [], \"f3ee\", \"M448 449L301.2 300.2c20-27.9 31.9-62.2 31.9-99.2 0-93.1-74.7-168.9-166.5-168.9C74.7 32 0 107.8 0 200.9s74.7 168.9 166.5 168.9c39.8 0 76.3-14.2 105-37.9l146 148.1 30.5-31zM166.5 330.8c-70.6 0-128.1-58.3-128.1-129.9S95.9 71 166.5 71s128.1 58.3 128.1 129.9-57.4 129.9-128.1 129.9z\"],\n    \"sith\": [448, 512, [], \"f512\", \"M0 32l69.71 118.75-58.86-11.52 69.84 91.03a146.741 146.741 0 0 0 0 51.45l-69.84 91.03 58.86-11.52L0 480l118.75-69.71-11.52 58.86 91.03-69.84c17.02 3.04 34.47 3.04 51.48 0l91.03 69.84-11.52-58.86L448 480l-69.71-118.78 58.86 11.52-69.84-91.03c3.03-17.01 3.04-34.44 0-51.45l69.84-91.03-58.86 11.52L448 32l-118.75 69.71 11.52-58.9-91.06 69.87c-8.5-1.52-17.1-2.29-25.71-2.29s-17.21.78-25.71 2.29l-91.06-69.87 11.52 58.9L0 32zm224 99.78c31.8 0 63.6 12.12 87.85 36.37 48.5 48.5 48.49 127.21 0 175.7s-127.2 48.46-175.7-.03c-48.5-48.5-48.49-127.21 0-175.7 24.24-24.25 56.05-36.34 87.85-36.34zm0 36.66c-22.42 0-44.83 8.52-61.92 25.61-34.18 34.18-34.19 89.68 0 123.87s89.65 34.18 123.84 0c34.18-34.18 34.19-89.68 0-123.87-17.09-17.09-39.5-25.61-61.92-25.61z\"],\n    \"sketch\": [512, 512, [], \"f7c6\", \"M27.5 162.2L9 187.1h90.5l6.9-130.7-78.9 105.8zM396.3 45.7L267.7 32l135.7 147.2-7.1-133.5zM112.2 218.3l-11.2-22H9.9L234.8 458zm2-31.2h284l-81.5-88.5L256.3 33zm297.3 9.1L277.6 458l224.8-261.7h-90.9zM415.4 69L406 56.4l.9 17.3 6.1 113.4h90.3zM113.5 93.5l-4.6 85.6L244.7 32 116.1 45.7zm287.7 102.7h-290l42.4 82.9L256.3 480l144.9-283.8z\"],\n    \"skyatlas\": [640, 512, [], \"f216\", \"M640 329.3c0 65.9-52.5 114.4-117.5 114.4-165.9 0-196.6-249.7-359.7-249.7-146.9 0-147.1 212.2 5.6 212.2 42.5 0 90.9-17.8 125.3-42.5 5.6-4.1 16.9-16.3 22.8-16.3s10.9 5 10.9 10.9c0 7.8-13.1 19.1-18.7 24.1-40.9 35.6-100.3 61.2-154.7 61.2-83.4.1-154-59-154-144.9s67.5-149.1 152.8-149.1c185.3 0 222.5 245.9 361.9 245.9 99.9 0 94.8-139.7 3.4-139.7-17.5 0-35 11.6-46.9 11.6-8.4 0-15.9-7.2-15.9-15.6 0-11.6 5.3-23.7 5.3-36.3 0-66.6-50.9-114.7-116.9-114.7-53.1 0-80 36.9-88.8 36.9-6.2 0-11.2-5-11.2-11.2 0-5.6 4.1-10.3 7.8-14.4 25.3-28.8 64.7-43.7 102.8-43.7 79.4 0 139.1 58.4 139.1 137.8 0 6.9-.3 13.7-1.2 20.6 11.9-3.1 24.1-4.7 35.9-4.7 60.7 0 111.9 45.3 111.9 107.2z\"],\n    \"skype\": [448, 512, [], \"f17e\", \"M424.7 299.8c2.9-14 4.7-28.9 4.7-43.8 0-113.5-91.9-205.3-205.3-205.3-14.9 0-29.7 1.7-43.8 4.7C161.3 40.7 137.7 32 112 32 50.2 32 0 82.2 0 144c0 25.7 8.7 49.3 23.3 68.2-2.9 14-4.7 28.9-4.7 43.8 0 113.5 91.9 205.3 205.3 205.3 14.9 0 29.7-1.7 43.8-4.7 19 14.6 42.6 23.3 68.2 23.3 61.8 0 112-50.2 112-112 .1-25.6-8.6-49.2-23.2-68.1zm-194.6 91.5c-65.6 0-120.5-29.2-120.5-65 0-16 9-30.6 29.5-30.6 31.2 0 34.1 44.9 88.1 44.9 25.7 0 42.3-11.4 42.3-26.3 0-18.7-16-21.6-42-28-62.5-15.4-117.8-22-117.8-87.2 0-59.2 58.6-81.1 109.1-81.1 55.1 0 110.8 21.9 110.8 55.4 0 16.9-11.4 31.8-30.3 31.8-28.3 0-29.2-33.5-75-33.5-25.7 0-42 7-42 22.5 0 19.8 20.8 21.8 69.1 33 41.4 9.3 90.7 26.8 90.7 77.6 0 59.1-57.1 86.5-112 86.5z\"],\n    \"slack\": [448, 512, [], \"f198\", \"M94.12 315.1c0 25.9-21.16 47.06-47.06 47.06S0 341 0 315.1c0-25.9 21.16-47.06 47.06-47.06h47.06v47.06zm23.72 0c0-25.9 21.16-47.06 47.06-47.06s47.06 21.16 47.06 47.06v117.84c0 25.9-21.16 47.06-47.06 47.06s-47.06-21.16-47.06-47.06V315.1zm47.06-188.98c-25.9 0-47.06-21.16-47.06-47.06S139 32 164.9 32s47.06 21.16 47.06 47.06v47.06H164.9zm0 23.72c25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06H47.06C21.16 243.96 0 222.8 0 196.9s21.16-47.06 47.06-47.06H164.9zm188.98 47.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06h-47.06V196.9zm-23.72 0c0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06V79.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06V196.9zM283.1 385.88c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06v-47.06h47.06zm0-23.72c-25.9 0-47.06-21.16-47.06-47.06 0-25.9 21.16-47.06 47.06-47.06h117.84c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06H283.1z\"],\n    \"slack-hash\": [448, 512, [], \"f3ef\", \"M446.2 270.4c-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-30.3-90 45.4-15.1c19.1-6.2 29.1-26.8 23-45.9-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-93.4 31.2-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-45.3 15c-19.1 6.2-29.1 26.8-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l30.3 90L78 354.8c-19 6.2-29.1 26.9-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 93.6-31.3 15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 45.4-15.1c19-6 29.1-26.7 22.9-45.7zm-254.1 47.2l-30.3-90.2 93.5-31.3 30.3 90.2-93.5 31.3z\"],\n    \"slideshare\": [512, 512, [], \"f1e7\", \"M187.7 153.7c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7s61.7-26 61.7-57.7c0-32-27.7-57.7-61.7-57.7zm143.4 0c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7 34.3 0 61.7-26 61.7-57.7.1-32-27.4-57.7-61.7-57.7zm156.6 90l-6 4.3V49.7c0-27.4-20.6-49.7-46-49.7H76.6c-25.4 0-46 22.3-46 49.7V248c-2-1.4-4.3-2.9-6.3-4.3-15.1-10.6-25.1 4-16 17.7 18.3 22.6 53.1 50.3 106.3 72C58.3 525.1 252 555.7 248.9 457.5c0-.7.3-56.6.3-96.6 5.1 1.1 9.4 2.3 13.7 3.1 0 39.7.3 92.8.3 93.5-3.1 98.3 190.6 67.7 134.3-124 53.1-21.7 88-49.4 106.3-72 9.1-13.8-.9-28.3-16.1-17.8zm-30.5 19.2c-68.9 37.4-128.3 31.1-160.6 29.7-23.7-.9-32.6 9.1-33.7 24.9-10.3-7.7-18.6-15.5-20.3-17.1-5.1-5.4-13.7-8-27.1-7.7-31.7 1.1-89.7 7.4-157.4-28V72.3c0-34.9 8.9-45.7 40.6-45.7h317.7c30.3 0 40.9 12.9 40.9 45.7v190.6z\"],\n    \"snapchat\": [496, 512, [], \"f2ab\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm169.5 338.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C183.1 100 230.7 96 244.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"snapchat-ghost\": [512, 512, [], \"f2ac\", \"M510.846 392.673c-5.211 12.157-27.239 21.089-67.36 27.318-2.064 2.786-3.775 14.686-6.507 23.956-1.625 5.566-5.623 8.869-12.128 8.869l-.297-.005c-9.395 0-19.203-4.323-38.852-4.323-26.521 0-35.662 6.043-56.254 20.588-21.832 15.438-42.771 28.764-74.027 27.399-31.646 2.334-58.025-16.908-72.871-27.404-20.714-14.643-29.828-20.582-56.241-20.582-18.864 0-30.736 4.72-38.852 4.72-8.073 0-11.213-4.922-12.422-9.04-2.703-9.189-4.404-21.263-6.523-24.13-20.679-3.209-67.31-11.344-68.498-32.15a10.627 10.627 0 0 1 8.877-11.069c69.583-11.455 100.924-82.901 102.227-85.934.074-.176.155-.344.237-.515 3.713-7.537 4.544-13.849 2.463-18.753-5.05-11.896-26.872-16.164-36.053-19.796-23.715-9.366-27.015-20.128-25.612-27.504 2.437-12.836 21.725-20.735 33.002-15.453 8.919 4.181 16.843 6.297 23.547 6.297 5.022 0 8.212-1.204 9.96-2.171-2.043-35.936-7.101-87.29 5.687-115.969C158.122 21.304 229.705 15.42 250.826 15.42c.944 0 9.141-.089 10.11-.089 52.148 0 102.254 26.78 126.723 81.643 12.777 28.65 7.749 79.792 5.695 116.009 1.582.872 4.357 1.942 8.599 2.139 6.397-.286 13.815-2.389 22.069-6.257 6.085-2.846 14.406-2.461 20.48.058l.029.01c9.476 3.385 15.439 10.215 15.589 17.87.184 9.747-8.522 18.165-25.878 25.018-2.118.835-4.694 1.655-7.434 2.525-9.797 3.106-24.6 7.805-28.616 17.271-2.079 4.904-1.256 11.211 2.46 18.748.087.168.166.342.239.515 1.301 3.03 32.615 74.46 102.23 85.934 6.427 1.058 11.163 7.877 7.725 15.859z\"],\n    \"snapchat-square\": [448, 512, [], \"f2ad\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6.5 314.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C159.1 100 206.7 96 220.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"soundcloud\": [640, 512, [], \"f1be\", \"M111.4 256.3l5.8 65-5.8 68.3c-.3 2.5-2.2 4.4-4.4 4.4s-4.2-1.9-4.2-4.4l-5.6-68.3 5.6-65c0-2.2 1.9-4.2 4.2-4.2 2.2 0 4.1 2 4.4 4.2zm21.4-45.6c-2.8 0-4.7 2.2-5 5l-5 105.6 5 68.3c.3 2.8 2.2 5 5 5 2.5 0 4.7-2.2 4.7-5l5.8-68.3-5.8-105.6c0-2.8-2.2-5-4.7-5zm25.5-24.1c-3.1 0-5.3 2.2-5.6 5.3l-4.4 130 4.4 67.8c.3 3.1 2.5 5.3 5.6 5.3 2.8 0 5.3-2.2 5.3-5.3l5.3-67.8-5.3-130c0-3.1-2.5-5.3-5.3-5.3zM7.2 283.2c-1.4 0-2.2 1.1-2.5 2.5L0 321.3l4.7 35c.3 1.4 1.1 2.5 2.5 2.5s2.2-1.1 2.5-2.5l5.6-35-5.6-35.6c-.3-1.4-1.1-2.5-2.5-2.5zm23.6-21.9c-1.4 0-2.5 1.1-2.5 2.5l-6.4 57.5 6.4 56.1c0 1.7 1.1 2.8 2.5 2.8s2.5-1.1 2.8-2.5l7.2-56.4-7.2-57.5c-.3-1.4-1.4-2.5-2.8-2.5zm25.3-11.4c-1.7 0-3.1 1.4-3.3 3.3L47 321.3l5.8 65.8c.3 1.7 1.7 3.1 3.3 3.1 1.7 0 3.1-1.4 3.1-3.1l6.9-65.8-6.9-68.1c0-1.9-1.4-3.3-3.1-3.3zm25.3-2.2c-1.9 0-3.6 1.4-3.6 3.6l-5.8 70 5.8 67.8c0 2.2 1.7 3.6 3.6 3.6s3.6-1.4 3.9-3.6l6.4-67.8-6.4-70c-.3-2.2-2-3.6-3.9-3.6zm241.4-110.9c-1.1-.8-2.8-1.4-4.2-1.4-2.2 0-4.2.8-5.6 1.9-1.9 1.7-3.1 4.2-3.3 6.7v.8l-3.3 176.7 1.7 32.5 1.7 31.7c.3 4.7 4.2 8.6 8.9 8.6s8.6-3.9 8.6-8.6l3.9-64.2-3.9-177.5c-.4-3-2-5.8-4.5-7.2zm-26.7 15.3c-1.4-.8-2.8-1.4-4.4-1.4s-3.1.6-4.4 1.4c-2.2 1.4-3.6 3.9-3.6 6.7l-.3 1.7-2.8 160.8s0 .3 3.1 65.6v.3c0 1.7.6 3.3 1.7 4.7 1.7 1.9 3.9 3.1 6.4 3.1 2.2 0 4.2-1.1 5.6-2.5 1.7-1.4 2.5-3.3 2.5-5.6l.3-6.7 3.1-58.6-3.3-162.8c-.3-2.8-1.7-5.3-3.9-6.7zm-111.4 22.5c-3.1 0-5.8 2.8-5.8 6.1l-4.4 140.6 4.4 67.2c.3 3.3 2.8 5.8 5.8 5.8 3.3 0 5.8-2.5 6.1-5.8l5-67.2-5-140.6c-.2-3.3-2.7-6.1-6.1-6.1zm376.7 62.8c-10.8 0-21.1 2.2-30.6 6.1-6.4-70.8-65.8-126.4-138.3-126.4-17.8 0-35 3.3-50.3 9.4-6.1 2.2-7.8 4.4-7.8 9.2v249.7c0 5 3.9 8.6 8.6 9.2h218.3c43.3 0 78.6-35 78.6-78.3.1-43.6-35.2-78.9-78.5-78.9zm-296.7-60.3c-4.2 0-7.5 3.3-7.8 7.8l-3.3 136.7 3.3 65.6c.3 4.2 3.6 7.5 7.8 7.5 4.2 0 7.5-3.3 7.5-7.5l3.9-65.6-3.9-136.7c-.3-4.5-3.3-7.8-7.5-7.8zm-53.6-7.8c-3.3 0-6.4 3.1-6.4 6.7l-3.9 145.3 3.9 66.9c.3 3.6 3.1 6.4 6.4 6.4 3.6 0 6.4-2.8 6.7-6.4l4.4-66.9-4.4-145.3c-.3-3.6-3.1-6.7-6.7-6.7zm26.7 3.4c-3.9 0-6.9 3.1-6.9 6.9L227 321.3l3.9 66.4c.3 3.9 3.1 6.9 6.9 6.9s6.9-3.1 6.9-6.9l4.2-66.4-4.2-141.7c0-3.9-3-6.9-6.9-6.9z\"],\n    \"sourcetree\": [448, 512, [], \"f7d3\", \"M427.2 203c0-112.1-90.9-203-203-203C112.1-.2 21.2 90.6 21 202.6A202.86 202.86 0 0 0 161.5 396v101.7a14.3 14.3 0 0 0 14.3 14.3h96.4a14.3 14.3 0 0 0 14.3-14.3V396.1A203.18 203.18 0 0 0 427.2 203zm-271.6 0c0-90.8 137.3-90.8 137.3 0-.1 89.9-137.3 91-137.3 0z\"],\n    \"speakap\": [448, 512, [], \"f3f3\", \"M64 391.78C-15.41 303.59-8 167.42 80.64 87.64s224.8-73 304.21 15.24 72 224.36-16.64 304.14c-18.74 16.87 64 43.09 42 52.26-82.06 34.21-253.91 35-346.23-67.5zm213.31-211.6l38.5-40.86c-9.61-8.89-32-26.83-76.17-27.6-52.33-.91-95.86 28.3-96.77 80-.2 11.33.29 36.72 29.42 54.83 34.46 21.42 86.52 21.51 86 52.26-.37 21.28-26.42 25.81-38.59 25.6-3-.05-30.23-.46-47.61-24.62l-40 42.61c28.16 27 59 32.62 83.49 33.05 10.23.18 96.42.33 97.84-81 .28-15.81-2.07-39.72-28.86-56.59-34.36-21.64-85-19.45-84.43-49.75.41-23.25 31-25.37 37.53-25.26.43 0 26.62.26 39.62 17.37z\"],\n    \"speaker-deck\": [512, 512, [], \"f83c\", \"M213.86 296H100a100 100 0 0 1 0-200h132.84a40 40 0 0 1 0 80H98c-26.47 0-26.45 40 0 40h113.82a100 100 0 0 1 0 200H40a40 40 0 0 1 0-80h173.86c26.48 0 26.46-40 0-40zM298 416a120.21 120.21 0 0 0 51.11-80h64.55a19.83 19.83 0 0 0 19.66-20V196a19.83 19.83 0 0 0-19.66-20H296.42a60.77 60.77 0 0 0 0-80h136.93c43.44 0 78.65 35.82 78.65 80v160c0 44.18-35.21 80-78.65 80z\"],\n    \"spotify\": [496, 512, [], \"f1bc\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm100.7 364.9c-4.2 0-6.8-1.3-10.7-3.6-62.4-37.6-135-39.2-206.7-24.5-3.9 1-9 2.6-11.9 2.6-9.7 0-15.8-7.7-15.8-15.8 0-10.3 6.1-15.2 13.6-16.8 81.9-18.1 165.6-16.5 237 26.2 6.1 3.9 9.7 7.4 9.7 16.5s-7.1 15.4-15.2 15.4zm26.9-65.6c-5.2 0-8.7-2.3-12.3-4.2-62.5-37-155.7-51.9-238.6-29.4-4.8 1.3-7.4 2.6-11.9 2.6-10.7 0-19.4-8.7-19.4-19.4s5.2-17.8 15.5-20.7c27.8-7.8 56.2-13.6 97.8-13.6 64.9 0 127.6 16.1 177 45.5 8.1 4.8 11.3 11 11.3 19.7-.1 10.8-8.5 19.5-19.4 19.5zm31-76.2c-5.2 0-8.4-1.3-12.9-3.9-71.2-42.5-198.5-52.7-280.9-29.7-3.6 1-8.1 2.6-12.9 2.6-13.2 0-23.3-10.3-23.3-23.6 0-13.6 8.4-21.3 17.4-23.9 35.2-10.3 74.6-15.2 117.5-15.2 73 0 149.5 15.2 205.4 47.8 7.8 4.5 12.9 10.7 12.9 22.6 0 13.6-11 23.3-23.2 23.3z\"],\n    \"squarespace\": [512, 512, [], \"f5be\", \"M186.12 343.34c-9.65 9.65-9.65 25.29 0 34.94 9.65 9.65 25.29 9.65 34.94 0L378.24 221.1c19.29-19.29 50.57-19.29 69.86 0s19.29 50.57 0 69.86L293.95 445.1c19.27 19.29 50.53 19.31 69.82.04l.04-.04 119.25-119.24c38.59-38.59 38.59-101.14 0-139.72-38.59-38.59-101.15-38.59-139.72 0l-157.22 157.2zm244.53-104.8c-9.65-9.65-25.29-9.65-34.93 0l-157.2 157.18c-19.27 19.29-50.53 19.31-69.82.05l-.05-.05c-9.64-9.64-25.27-9.65-34.92-.01l-.01.01c-9.65 9.64-9.66 25.28-.02 34.93l.02.02c38.58 38.57 101.14 38.57 139.72 0l157.2-157.2c9.65-9.65 9.65-25.29.01-34.93zm-261.99 87.33l157.18-157.18c9.64-9.65 9.64-25.29 0-34.94-9.64-9.64-25.27-9.64-34.91 0L133.72 290.93c-19.28 19.29-50.56 19.3-69.85.01l-.01-.01c-19.29-19.28-19.31-50.54-.03-69.84l.03-.03L218.03 66.89c-19.28-19.29-50.55-19.3-69.85-.02l-.02.02L28.93 186.14c-38.58 38.59-38.58 101.14 0 139.72 38.6 38.59 101.13 38.59 139.73.01zm-87.33-52.4c9.64 9.64 25.27 9.64 34.91 0l157.21-157.19c19.28-19.29 50.55-19.3 69.84-.02l.02.02c9.65 9.65 25.29 9.65 34.93 0 9.65-9.65 9.65-25.29 0-34.93-38.59-38.59-101.13-38.59-139.72 0L81.33 238.54c-9.65 9.64-9.65 25.28-.01 34.93h.01z\"],\n    \"stack-exchange\": [448, 512, [], \"f18d\", \"M17.7 332.3h412.7v22c0 37.7-29.3 68-65.3 68h-19L259.3 512v-89.7H83c-36 0-65.3-30.3-65.3-68v-22zm0-23.6h412.7v-85H17.7v85zm0-109.4h412.7v-85H17.7v85zM365 0H83C47 0 17.7 30.3 17.7 67.7V90h412.7V67.7C430.3 30.3 401 0 365 0z\"],\n    \"stack-overflow\": [384, 512, [], \"f16c\", \"M290.7 311L95 269.7 86.8 309l195.7 41zm51-87L188.2 95.7l-25.5 30.8 153.5 128.3zm-31.2 39.7L129.2 179l-16.7 36.5L293.7 300zM262 32l-32 24 119.3 160.3 32-24zm20.5 328h-200v39.7h200zm39.7 80H42.7V320h-40v160h359.5V320h-40z\"],\n    \"stackpath\": [448, 512, [], \"f842\", \"M244.6 232.4c0 8.5-4.26 20.49-21.34 20.49h-19.61v-41.47h19.61c17.13 0 21.34 12.36 21.34 20.98zM448 32v448H0V32zM151.3 287.84c0-21.24-12.12-34.54-46.72-44.85-20.57-7.41-26-10.91-26-18.63s7-14.61 20.41-14.61c14.09 0 20.79 8.45 20.79 18.35h30.7l.19-.57c.5-19.57-15.06-41.65-51.12-41.65-23.37 0-52.55 10.75-52.55 38.29 0 19.4 9.25 31.29 50.74 44.37 17.26 6.15 21.91 10.4 21.91 19.48 0 15.2-19.13 14.23-19.47 14.23-20.4 0-25.65-9.1-25.65-21.9h-30.8l-.18.56c-.68 31.32 28.38 45.22 56.63 45.22 29.98 0 51.12-13.55 51.12-38.29zm125.38-55.63c0-25.3-18.43-45.46-53.42-45.46h-51.78v138.18h32.17v-47.36h19.61c30.25 0 53.42-15.95 53.42-45.36zM297.94 325L347 186.78h-31.09L268 325zm106.52-138.22h-31.09L325.46 325h29.94z\"],\n    \"staylinked\": [440, 512, [], \"f3f5\", \"M382.7 292.5l2.7 2.7-170-167.3c-3.5-3.5-9.7-3.7-13.8-.5L144.3 171c-4.2 3.2-4.6 8.7-1.1 12.2l68.1 64.3c3.6 3.5 9.9 3.7 14 .5l.1-.1c4.1-3.2 10.4-3 14 .5l84 81.3c3.6 3.5 3.2 9-.9 12.2l-93.2 74c-4.2 3.3-10.5 3.1-14.2-.4L63.2 268c-3.5-3.5-9.7-3.7-13.9-.5L3.5 302.4c-4.2 3.2-4.7 8.7-1.2 12.2L211 510.7s7.4 6.8 17.3-.8l198-163.9c4-3.2 4.4-8.7.7-12.2zm54.5-83.4L226.7 2.5c-1.5-1.2-8-5.5-16.3 1.1L3.6 165.7c-4.2 3.2-4.8 8.7-1.2 12.2l42.3 41.7 171.7 165.1c3.7 3.5 10.1 3.7 14.3.4l50.2-38.8-.3-.3 7.7-6c4.2-3.2 4.6-8.7.9-12.2l-57.1-54.4c-3.6-3.5-10-3.7-14.2-.5l-.1.1c-4.2 3.2-10.5 3.1-14.2-.4L109 180.8c-3.6-3.5-3.1-8.9 1.1-12.2l92.2-71.5c4.1-3.2 10.3-3 13.9.5l160.4 159c3.7 3.5 10 3.7 14.1.5l45.8-35.8c4.1-3.2 4.4-8.7.7-12.2z\"],\n    \"steam\": [496, 512, [], \"f1b6\", \"M496 256c0 137-111.2 248-248.4 248-113.8 0-209.6-76.3-239-180.4l95.2 39.3c6.4 32.1 34.9 56.4 68.9 56.4 39.2 0 71.9-32.4 70.2-73.5l84.5-60.2c52.1 1.3 95.8-40.9 95.8-93.5 0-51.6-42-93.5-93.7-93.5s-93.7 42-93.7 93.5v1.2L176.6 279c-15.5-.9-30.7 3.4-43.5 12.1L0 236.1C10.2 108.4 117.1 8 247.6 8 384.8 8 496 119 496 256zM155.7 384.3l-30.5-12.6a52.79 52.79 0 0 0 27.2 25.8c26.9 11.2 57.8-1.6 69-28.4 5.4-13 5.5-27.3.1-40.3-5.4-13-15.5-23.2-28.5-28.6-12.9-5.4-26.7-5.2-38.9-.6l31.5 13c19.8 8.2 29.2 30.9 20.9 50.7-8.3 19.9-31 29.2-50.8 21zm173.8-129.9c-34.4 0-62.4-28-62.4-62.3s28-62.3 62.4-62.3 62.4 28 62.4 62.3-27.9 62.3-62.4 62.3zm.1-15.6c25.9 0 46.9-21 46.9-46.8 0-25.9-21-46.8-46.9-46.8s-46.9 21-46.9 46.8c.1 25.8 21.1 46.8 46.9 46.8z\"],\n    \"steam-square\": [448, 512, [], \"f1b7\", \"M185.2 356.5c7.7-18.5-1-39.7-19.6-47.4l-29.5-12.2c11.4-4.3 24.3-4.5 36.4.5 12.2 5.1 21.6 14.6 26.7 26.7 5 12.2 5 25.6-.1 37.7-10.5 25.1-39.4 37-64.6 26.5-11.6-4.8-20.4-13.6-25.4-24.2l28.5 11.8c18.6 7.8 39.9-.9 47.6-19.4zM400 32H48C21.5 32 0 53.5 0 80v160.7l116.6 48.1c12-8.2 26.2-12.1 40.7-11.3l55.4-80.2v-1.1c0-48.2 39.3-87.5 87.6-87.5s87.6 39.3 87.6 87.5c0 49.2-40.9 88.7-89.6 87.5l-79 56.3c1.6 38.5-29.1 68.8-65.7 68.8-31.8 0-58.5-22.7-64.5-52.7L0 319.2V432c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-99.7 222.5c-32.2 0-58.4-26.1-58.4-58.3s26.2-58.3 58.4-58.3 58.4 26.2 58.4 58.3-26.2 58.3-58.4 58.3zm.1-14.6c24.2 0 43.9-19.6 43.9-43.8 0-24.2-19.6-43.8-43.9-43.8-24.2 0-43.9 19.6-43.9 43.8 0 24.2 19.7 43.8 43.9 43.8z\"],\n    \"steam-symbol\": [448, 512, [], \"f3f6\", \"M395.5 177.5c0 33.8-27.5 61-61 61-33.8 0-61-27.3-61-61s27.3-61 61-61c33.5 0 61 27.2 61 61zm52.5.2c0 63-51 113.8-113.7 113.8L225 371.3c-4 43-40.5 76.8-84.5 76.8-40.5 0-74.7-28.8-83-67L0 358V250.7L97.2 290c15.1-9.2 32.2-13.3 52-11.5l71-101.7c.5-62.3 51.5-112.8 114-112.8C397 64 448 115 448 177.7zM203 363c0-34.7-27.8-62.5-62.5-62.5-4.5 0-9 .5-13.5 1.5l26 10.5c25.5 10.2 38 39 27.7 64.5-10.2 25.5-39.2 38-64.7 27.5-10.2-4-20.5-8.3-30.7-12.2 10.5 19.7 31.2 33.2 55.2 33.2 34.7 0 62.5-27.8 62.5-62.5zm207.5-185.3c0-42-34.3-76.2-76.2-76.2-42.3 0-76.5 34.2-76.5 76.2 0 42.2 34.3 76.2 76.5 76.2 41.9.1 76.2-33.9 76.2-76.2z\"],\n    \"sticker-mule\": [576, 512, [], \"f3f7\", \"M561.7 199.6c-1.3.3.3 0 0 0zm-6.2-77.4c-7.7-22.3-5.1-7.2-13.4-36.9-1.6-6.5-3.6-14.5-6.2-20-4.4-8.7-4.6-7.5-4.6-9.5 0-5.3 30.7-45.3 19-46.9-5.7-.6-12.2 11.6-20.6 17-8.6 4.2-8 5-10.3 5-2.6 0-5.7-3-6.2-5-2-5.7 1.9-25.9-3.6-25.9-3.6 0-12.3 24.8-17 25.8-5.2 1.3-27.9-11.4-75.1 18-25.3 13.2-86.9 65.2-87 65.3-6.7 4.7-20 4.7-35.5 16-44.4 30.1-109.6 9.4-110.7 9-110.6-26.8-128-15.2-159 11.5-20.8 17.9-23.7 36.5-24.2 38.9-4.2 20.4 5.2 48.3 6.7 64.3 1.8 19.3-2.7 17.7 7.7 98.3.5 1 4.1 0 5.1 1.5 0 8.4-3.8 12.1-4.1 13-1.5 4.5-1.5 10.5 0 16 2.3 8.2 8.2 37.2 8.2 46.9 0 41.8.4 44 2.6 49.4 3.9 10 12.5 9.1 17 12 3.1 3.5-.5 8.5 1 12.5.5 2 3.6 4 6.2 5 9.2 3.6 27 .3 29.9-2.5 1.6-1.5.5-4.5 3.1-5 5.1 0 10.8-.5 14.4-2.5 5.1-2.5 4.1-6 1.5-10.5-.4-.8-7-13.3-9.8-16-2.1-2-5.1-3-7.2-4.5-5.8-4.9-10.3-19.4-10.3-19.5-4.6-19.4-10.3-46.3-4.1-66.8 4.6-17.2 39.5-87.7 39.6-87.8 4.1-6.5 17-11.5 27.3-7 6 1.9 19.3 22 65.4 30.9 47.9 8.7 97.4-2 112.2-2 2.8 2-1.9 13-.5 38.9 0 26.4-.4 13.7-4.1 29.9-2.2 9.7 3.4 23.2-1.5 46.9-1.4 9.8-9.9 32.7-8.2 43.4.5 1 1 2 1.5 3.5.5 4.5 1.5 8.5 4.6 10 7.3 3.6 12-3.5 9.8 11.5-.7 3.1-2.6 12 1.5 15 4.4 3.7 30.6 3.4 36.5.5 2.6-1.5 1.6-4.5 6.4-7.4 1.9-.9 11.3-.4 11.3-6.5.3-1.8-9.2-19.9-9.3-20-2.6-3.5-9.2-4.5-11.3-8-6.9-10.1-1.7-52.6.5-59.4 3-11 5.6-22.4 8.7-32.4 11-42.5 10.3-50.6 16.5-68.3.8-1.8 6.4-23.1 10.3-29.9 9.3-17 21.7-32.4 33.5-47.4 18-22.9 34-46.9 52-69.8 6.1-7 8.2-13.7 18-8 10.8 5.7 21.6 7 31.9 17 14.6 12.8 10.2 18.2 11.8 22.9 1.5 5 7.7 10.5 14.9 9.5 10.4-2 13-2.5 13.4-2.5 2.6-.5 5.7-5 7.2-8 3.1-5.5 7.2-9 7.2-16.5 0-7.7-.4-2.8-20.6-52.9z\"],\n    \"strava\": [384, 512, [], \"f428\", \"M158.4 0L7 292h89.2l62.2-116.1L220.1 292h88.5zm150.2 292l-43.9 88.2-44.6-88.2h-67.6l112.2 220 111.5-220z\"],\n    \"stripe\": [640, 512, [], \"f429\", \"M165 144.7l-43.3 9.2-.2 142.4c0 26.3 19.8 43.3 46.1 43.3 14.6 0 25.3-2.7 31.2-5.9v-33.8c-5.7 2.3-33.7 10.5-33.7-15.7V221h33.7v-37.8h-33.7zm89.1 51.6l-2.7-13.1H213v153.2h44.3V233.3c10.5-13.8 28.2-11.1 33.9-9.3v-40.8c-6-2.1-26.7-6-37.1 13.1zm92.3-72.3l-44.6 9.5v36.2l44.6-9.5zM44.9 228.3c0-6.9 5.8-9.6 15.1-9.7 13.5 0 30.7 4.1 44.2 11.4v-41.8c-14.7-5.8-29.4-8.1-44.1-8.1-36 0-60 18.8-60 50.2 0 49.2 67.5 41.2 67.5 62.4 0 8.2-7.1 10.9-17 10.9-14.7 0-33.7-6.1-48.6-14.2v40c16.5 7.1 33.2 10.1 48.5 10.1 36.9 0 62.3-15.8 62.3-47.8 0-52.9-67.9-43.4-67.9-63.4zM640 261.6c0-45.5-22-81.4-64.2-81.4s-67.9 35.9-67.9 81.1c0 53.5 30.3 78.2 73.5 78.2 21.2 0 37.1-4.8 49.2-11.5v-33.4c-12.1 6.1-26 9.8-43.6 9.8-17.3 0-32.5-6.1-34.5-26.9h86.9c.2-2.3.6-11.6.6-15.9zm-87.9-16.8c0-20 12.3-28.4 23.4-28.4 10.9 0 22.5 8.4 22.5 28.4zm-112.9-64.6c-17.4 0-28.6 8.2-34.8 13.9l-2.3-11H363v204.8l44.4-9.4.1-50.2c6.4 4.7 15.9 11.2 31.4 11.2 31.8 0 60.8-23.2 60.8-79.6.1-51.6-29.3-79.7-60.5-79.7zm-10.6 122.5c-10.4 0-16.6-3.8-20.9-8.4l-.3-66c4.6-5.1 11-8.8 21.2-8.8 16.2 0 27.4 18.2 27.4 41.4.1 23.9-10.9 41.8-27.4 41.8zm-126.7 33.7h44.6V183.2h-44.6z\"],\n    \"stripe-s\": [384, 512, [], \"f42a\", \"M155.3 154.6c0-22.3 18.6-30.9 48.4-30.9 43.4 0 98.5 13.3 141.9 36.7V26.1C298.3 7.2 251.1 0 203.8 0 88.1 0 11 60.4 11 161.4c0 157.9 216.8 132.3 216.8 200.4 0 26.4-22.9 34.9-54.7 34.9-47.2 0-108.2-19.5-156.1-45.5v128.5a396.09 396.09 0 0 0 156 32.4c118.6 0 200.3-51 200.3-153.6 0-170.2-218-139.7-218-203.9z\"],\n    \"studiovinari\": [512, 512, [], \"f3f8\", \"M480.3 187.7l4.2 28v28l-25.1 44.1-39.8 78.4-56.1 67.5-79.1 37.8-17.7 24.5-7.7 12-9.6 4s17.3-63.6 19.4-63.6c2.1 0 20.3.7 20.3.7l66.7-38.6-92.5 26.1-55.9 36.8-22.8 28-6.6 1.4 20.8-73.6 6.9-5.5 20.7 12.9 88.3-45.2 56.8-51.5 14.8-68.4-125.4 23.3 15.2-18.2-173.4-53.3 81.9-10.5-166-122.9L133.5 108 32.2 0l252.9 126.6-31.5-38L378 163 234.7 64l18.7 38.4-49.6-18.1L158.3 0l194.6 122L310 66.2l108 96.4 12-8.9-21-16.4 4.2-37.8L451 89.1l29.2 24.7 11.5 4.2-7 6.2 8.5 12-13.1 7.4-10.3 20.2 10.5 23.9z\"],\n    \"stumbleupon\": [512, 512, [], \"f1a4\", \"M502.9 266v69.7c0 62.1-50.3 112.4-112.4 112.4-61.8 0-112.4-49.8-112.4-111.3v-70.2l34.3 16 51.1-15.2V338c0 14.7 12 26.5 26.7 26.5S417 352.7 417 338v-72h85.9zm-224.7-58.2l34.3 16 51.1-15.2V173c0-60.5-51.1-109-112.1-109-60.8 0-112.1 48.2-112.1 108.2v162.4c0 14.9-12 26.7-26.7 26.7S86 349.5 86 334.6V266H0v69.7C0 397.7 50.3 448 112.4 448c61.6 0 112.4-49.5 112.4-110.8V176.9c0-14.7 12-26.7 26.7-26.7s26.7 12 26.7 26.7v30.9z\"],\n    \"stumbleupon-circle\": [496, 512, [], \"f1a3\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 177.5c-9.8 0-17.8 8-17.8 17.8v106.9c0 40.9-33.9 73.9-74.9 73.9-41.4 0-74.9-33.5-74.9-74.9v-46.5h57.3v45.8c0 10 8 17.8 17.8 17.8s17.8-7.9 17.8-17.8V200.1c0-40 34.2-72.1 74.7-72.1 40.7 0 74.7 32.3 74.7 72.6v23.7l-34.1 10.1-22.9-10.7v-20.6c.1-9.6-7.9-17.6-17.7-17.6zm167.6 123.6c0 41.4-33.5 74.9-74.9 74.9-41.2 0-74.9-33.2-74.9-74.2V263l22.9 10.7 34.1-10.1v47.1c0 9.8 8 17.6 17.8 17.6s17.8-7.9 17.8-17.6v-48h57.3c-.1 45.9-.1 46.4-.1 46.4z\"],\n    \"superpowers\": [448, 512, [], \"f2dd\", \"M448 32c-83.3 11-166.8 22-250 33-92 12.5-163.3 86.7-169 180-3.3 55.5 18 109.5 57.8 148.2L0 480c83.3-11 166.5-22 249.8-33 91.8-12.5 163.3-86.8 168.7-179.8 3.5-55.5-18-109.5-57.7-148.2L448 32zm-79.7 232.3c-4.2 79.5-74 139.2-152.8 134.5-79.5-4.7-140.7-71-136.3-151 4.5-79.2 74.3-139.3 153-134.5 79.3 4.7 140.5 71 136.1 151z\"],\n    \"supple\": [640, 512, [], \"f3f9\", \"M640 262.5c0 64.1-109 116.1-243.5 116.1-24.8 0-48.6-1.8-71.1-5 7.7.4 15.5.6 23.4.6 134.5 0 243.5-56.9 243.5-127.1 0-29.4-19.1-56.4-51.2-78 60 21.1 98.9 55.1 98.9 93.4zM47.7 227.9c-.1-70.2 108.8-127.3 243.3-127.6 7.9 0 15.6.2 23.3.5-22.5-3.2-46.3-4.9-71-4.9C108.8 96.3-.1 148.5 0 212.6c.1 38.3 39.1 72.3 99.3 93.3-32.3-21.5-51.5-48.6-51.6-78zm60.2 39.9s10.5 13.2 29.3 13.2c17.9 0 28.4-11.5 28.4-25.1 0-28-40.2-25.1-40.2-39.7 0-5.4 5.3-9.1 12.5-9.1 5.7 0 11.3 2.6 11.3 6.6v3.9h14.2v-7.9c0-12.1-15.4-16.8-25.4-16.8-16.5 0-28.5 10.2-28.5 24.1 0 26.6 40.2 25.4 40.2 39.9 0 6.6-5.8 10.1-12.3 10.1-11.9 0-20.7-10.1-20.7-10.1l-8.8 10.9zm120.8-73.6v54.4c0 11.3-7.1 17.8-17.8 17.8-10.7 0-17.8-6.5-17.8-17.7v-54.5h-15.8v55c0 18.9 13.4 31.9 33.7 31.9 20.1 0 33.4-13 33.4-31.9v-55h-15.7zm34.4 85.4h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.8-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5.1 14.7-14 14.7h-12.6zm57 43h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.7-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5 14.7-14 14.7h-12.6zm57.1 34.8c0 5.8 2.4 8.2 8.2 8.2h37.6c5.8 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-18.6c-1.7 0-2.6-1-2.6-2.6v-61.2c0-5.7-2.4-8.2-8.2-8.2H401v13.4h5.2c1.7 0 2.6 1 2.6 2.6v61.2zm63.4 0c0 5.8 2.4 8.2 8.2 8.2H519c5.7 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-19.7c-1.7 0-2.6-1-2.6-2.6v-20.3h27.7v-13.4H488v-22.4h19.2c1.7 0 2.6 1 2.6 2.6v5.2H524v-13c0-5.7-2.5-8.2-8.2-8.2h-51.6v13.4h7.8v63.9zm58.9-76v5.9h1.6v-5.9h2.7v-1.2h-7v1.2h2.7zm5.7-1.2v7.1h1.5v-5.7l2.3 5.7h1.3l2.3-5.7v5.7h1.5v-7.1h-2.3l-2.1 5.1-2.1-5.1h-2.4z\"],\n    \"suse\": [640, 512, [], \"f7d6\", \"M471.08 102.66s-.3 18.3-.3 20.3c-9.1-3-74.4-24.1-135.7-26.3-51.9-1.8-122.8-4.3-223 57.3-19.4 12.4-73.9 46.1-99.6 109.7C7 277-.12 307 7 335.06a111 111 0 0 0 16.5 35.7c17.4 25 46.6 41.6 78.1 44.4 44.4 3.9 78.1-16 90-53.3 8.2-25.8 0-63.6-31.5-82.9-25.6-15.7-53.3-12.1-69.2-1.6-13.9 9.2-21.8 23.5-21.6 39.2.3 27.8 24.3 42.6 41.5 42.6a49 49 0 0 0 15.8-2.7c6.5-1.8 13.3-6.5 13.3-14.9 0-12.1-11.6-14.8-16.8-13.9-2.9.5-4.5 2-11.8 2.4-2-.2-12-3.1-12-14V316c.2-12.3 13.2-18 25.5-16.9 32.3 2.8 47.7 40.7 28.5 65.7-18.3 23.7-76.6 23.2-99.7-20.4-26-49.2 12.7-111.2 87-98.4 33.2 5.7 83.6 35.5 102.4 104.3h45.9c-5.7-17.6-8.9-68.3 42.7-68.3 56.7 0 63.9 39.9 79.8 68.3H460c-12.8-18.3-21.7-38.7-18.9-55.8 5.6-33.8 39.7-18.4 82.4-17.4 66.5.4 102.1-27 103.1-28 3.7-3.1 6.5-15.8 7-17.7 1.3-5.1-3.2-2.4-3.2-2.4-8.7 5.2-30.5 15.2-50.9 15.6-25.3.5-76.2-25.4-81.6-28.2-.3-.4.1 1.2-11-25.5 88.4 58.3 118.3 40.5 145.2 21.7.8-.6 4.3-2.9 3.6-5.7-13.8-48.1-22.4-62.7-34.5-69.6-37-21.6-125-34.7-129.2-35.3.1-.1-.9-.3-.9.7zm60.4 72.8a37.54 37.54 0 0 1 38.9-36.3c33.4 1.2 48.8 42.3 24.4 65.2-24.2 22.7-64.4 4.6-63.3-28.9zm38.6-25.3a26.27 26.27 0 1 0 25.4 27.2 26.19 26.19 0 0 0-25.4-27.2zm4.3 28.8c-15.4 0-15.4-15.6 0-15.6s15.4 15.64 0 15.64z\"],\n    \"symfony\": [512, 512, [], \"f83d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm133.74 143.54c-11.47.41-19.4-6.45-19.77-16.87-.27-9.18 6.68-13.44 6.53-18.85-.23-6.55-10.16-6.82-12.87-6.67-39.78 1.29-48.59 57-58.89 113.85 21.43 3.15 36.65-.72 45.14-6.22 12-7.75-3.34-15.72-1.42-24.56 4-18.16 32.55-19 32 5.3-.36 17.86-25.92 41.81-77.6 35.7-10.76 59.52-18.35 115-58.2 161.72-29 34.46-58.4 39.82-71.58 40.26-24.65.85-41-12.31-41.58-29.84-.56-17 14.45-26.26 24.31-26.59 21.89-.75 30.12 25.67 14.88 34-12.09 9.71.11 12.61 2.05 12.55 10.42-.36 17.34-5.51 22.18-9 24-20 33.24-54.86 45.35-118.35 8.19-49.66 17-78 18.23-82-16.93-12.75-27.08-28.55-49.85-34.72-15.61-4.23-25.12-.63-31.81 7.83-7.92 10-5.29 23 2.37 30.7l12.63 14c15.51 17.93 24 31.87 20.8 50.62-5.06 29.93-40.72 52.9-82.88 39.94-36-11.11-42.7-36.56-38.38-50.62 7.51-24.15 42.36-11.72 34.62 13.6-2.79 8.6-4.92 8.68-6.28 13.07-4.56 14.77 41.85 28.4 51-1.39 4.47-14.52-5.3-21.71-22.25-39.85-28.47-31.75-16-65.49 2.95-79.67C204.23 140.13 251.94 197 262 205.29c37.17-109 100.53-105.46 102.43-105.53 25.16-.81 44.19 10.59 44.83 28.65.25 7.69-4.17 22.59-19.52 23.13z\"],\n    \"teamspeak\": [512, 512, [], \"f4f9\", \"M244.2 346.79c2.4-12.3-12-30-32.4-48.7-20.9-19.2-48.2-39.1-63.4-46.6-21.7-12-41.7-1.8-46.3 22.7-5 26.2 0 51.4 14.5 73.9 10.2 15.5 25.4 22.7 43.4 24 11.6.6 52.5 2.2 61.7-1 11.9-4.3 20.1-11.8 22.5-24.3zm205 20.8a5.22 5.22 0 0 0-8.3 2.4c-8 25.4-44.7 112.5-172.1 121.5-149.7 10.5 80.3 43.6 145.4-6.4 22.7-17.4 47.6-35 46.6-85.4-.4-10.1-4.9-26.69-11.6-32.1zm62-122.4c-.3-18.9-8.6-33.4-26-42.2-2.9-1.3-5-2.7-5.9-6.4A222.64 222.64 0 0 0 438.9 103c-1.1-1.5-3.5-3.2-2.2-5 8.5-11.5-.3-18-7-24.4Q321.4-31.11 177.4 13.09c-40.1 12.3-73.9 35.6-102 67.4-4 4.3-6.7 9.1-3 14.5 3 4 1.3 6.2-1 9.3C51.6 132 38.2 162.59 32.1 196c-.7 4.3-2.9 6-6.4 7.8-14.2 7-22.5 18.5-24.9 34L0 264.29v20.9c0 30.8 21 50.4 51.8 49 7.7-.3 11.7-4.3 12-11.5 2-77.5-2.4-95.4 3.7-125.8C92.1 72.39 234.3 5 345.3 65.39 411.4 102 445.7 159 447.6 234.79c.8 28.2 0 56.5 0 84.6 0 7 2.2 12.5 9.4 14.2 24.1 5 49.2-12 53.2-36.7 2.9-17.1 1-34.5 1-51.7zm-159.6 131.5c36.5 2.8 59.3-28.5 58.4-60.5-2.1-45.2-66.2-16.5-87.8-8-73.2 28.1-45 54.9-22.2 60.8z\"],\n    \"telegram\": [496, 512, [], \"f2c6\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm121.8 169.9l-40.7 191.8c-3 13.6-11.1 16.9-22.4 10.5l-62-45.7-29.9 28.8c-3.3 3.3-6.1 6.1-12.5 6.1l4.4-63.1 114.9-103.8c5-4.4-1.1-6.9-7.7-2.5l-142 89.4-61.2-19.1c-13.3-4.2-13.6-13.3 2.8-19.7l239.1-92.2c11.1-4 20.8 2.7 17.2 19.5z\"],\n    \"telegram-plane\": [448, 512, [], \"f3fe\", \"M446.7 98.6l-67.6 318.8c-5.1 22.5-18.4 28.1-37.3 17.5l-103-75.9-49.7 47.8c-5.5 5.5-10.1 10.1-20.7 10.1l7.4-104.9 190.9-172.5c8.3-7.4-1.8-11.5-12.9-4.1L117.8 284 16.2 252.2c-22.1-6.9-22.5-22.1 4.6-32.7L418.2 66.4c18.4-6.9 34.5 4.1 28.5 32.2z\"],\n    \"tencent-weibo\": [384, 512, [], \"f1d5\", \"M72.3 495.8c1.4 19.9-27.6 22.2-29.7 2.9C31 368.8 73.7 259.2 144 185.5c-15.6-34 9.2-77.1 50.6-77.1 30.3 0 55.1 24.6 55.1 55.1 0 44-49.5 70.8-86.9 45.1-65.7 71.3-101.4 169.8-90.5 287.2zM192 .1C66.1.1-12.3 134.3 43.7 242.4 52.4 259.8 79 246.9 70 229 23.7 136.4 91 29.8 192 29.8c75.4 0 136.9 61.4 136.9 136.9 0 90.8-86.9 153.9-167.7 133.1-19.1-4.1-25.6 24.4-6.6 29.1 110.7 23.2 204-60 204-162.3C358.6 74.7 284 .1 192 .1z\"],\n    \"the-red-yeti\": [512, 512, [], \"f69d\", \"M488.23 241.7l20.7 7.1c-9.6-23.9-23.9-37-31.7-44.8l7.1-18.2c.2 0 12.3-27.8-2.5-30.7-.6-11.3-6.6-27-18.4-27-7.6-10.6-17.7-12.3-30.7-5.9a122.2 122.2 0 0 0-25.3 16.5c-5.3-6.4-3 .4-3-29.8-37.1-24.3-45.4-11.7-74.8 3l.5.5a239.36 239.36 0 0 0-68.4-13.3c-5.5-8.7-18.6-19.1-25.1-25.1l24.8 7.1c-5.5-5.5-26.8-12.9-34.2-15.2 18.2-4.1 29.8-20.8 42.5-33-34.9-10.1-67.9-5.9-97.9 11.8l12-44.2L182 0c-31.6 24.2-33 41.9-33.7 45.5-.9-2.4-6.3-19.6-15.2-27a35.12 35.12 0 0 0-.5 25.3c3 8.4 5.9 14.8 8.4 18.9-16-3.3-28.3-4.9-49.2 0h-3.7l33 14.3a194.26 194.26 0 0 0-46.7 67.4l-1.7 8.4 1.7 1.7 7.6-4.7c-3.3 11.6-5.3 19.4-6.6 25.8a200.18 200.18 0 0 0-27.8 40.3c-15 1-31.8 10.8-40.3 14.3l3 3.4 28.8 1c-.5 1-.7 2.2-1.2 3.2-7.3 6.4-39.8 37.7-33 80.7l20.2-22.4c.5 1.7.7 3.4 1.2 5.2 0 25.5.4 89.6 64.9 150.5 43.6 40 96 60.2 157.5 60.2 121.7 0 223-87.3 223-211.5 6.8-9.7-1.2 3 16.7-25.1l13 14.3 2.5-.5A181.84 181.84 0 0 0 495 255a44.74 44.74 0 0 0-6.8-13.3zM398 111.2l-.5 21.9c5.5 18.1 16.9 17.2 22.4 17.2l-3.4-4.7 22.4-5.4a242.44 242.44 0 0 1-27 0c12.8-2.1 33.3-29 43-11.3 3.4 7.6 6.4 17.2 9.3 27.8l1.7-5.9a56.38 56.38 0 0 1-1.7-15.2c5.4.5 8.8 3.4 9.3 10.1.5 6.4 1.7 14.8 3.4 25.3l4.7-11.3c4.6 0 4.5-3.6-2.5 20.7-20.9-8.7-35.1-8.4-46.5-8.4l18.2-16c-25.3 8.2-33 10.8-54.8 20.9-1.1-5.4-5-13.5-16-19.9-3.2 3.8-2.8.9-.7 14.8h-2.5a62.32 62.32 0 0 0-8.4-23.1l4.2-3.4c8.4-7.1 11.8-14.3 10.6-21.9-.5-6.4-5.4-13.5-13.5-20.7 5.6-3.4 15.2-.4 28.3 8.5zm-39.6-10.1c2.7 1.9 11.4 5.4 18.9 17.2 4.2 8.4 4 9.8 3.4 11.1-.5 2.4-.5 4.3-3 7.1-1.7 2.5-5.4 4.7-11.8 7.6-7.6-13-16.5-23.6-27.8-31.2zM91 143.1l1.2-1.7c1.2-2.9 4.2-7.6 9.3-15.2l2.5-3.4-13 12.3 5.4-4.7-10.1 9.3-4.2 1.2c12.3-24.1 23.1-41.3 32.5-50.2 9.3-9.3 16-16 20.2-19.4l-6.4 1.2c-11.3-4.2-19.4-7.1-24.8-8.4 2.5-.5 3.7-.5 3.2-.5 10.3 0 17.5.5 20.9 1.2a52.35 52.35 0 0 0 16 2.5l.5-1.7-8.4-35.8 13.5 29a42.89 42.89 0 0 0 5.9-14.3c1.7-6.4 5.4-13 10.1-19.4s7.6-10.6 9.3-11.3a234.68 234.68 0 0 0-6.4 25.3l-1.7 7.1-.5 4.7 2.5 2.5C190.4 39.9 214 34 239.8 34.5l21.1.5c-11.8 13.5-27.8 21.9-48.5 24.8a201.26 201.26 0 0 1-23.4 2.9l-.2-.5-2.5-1.2a20.75 20.75 0 0 0-14 2c-2.5-.2-4.9-.5-7.1-.7l-2.5 1.7.5 1.2c2 .2 3.9.5 6.2.7l-2 3.4 3.4-.5-10.6 11.3c-4.2 3-5.4 6.4-4.2 9.3l5.4-3.4h1.2a39.4 39.4 0 0 1 25.3-15.2v-3c6.4.5 13 1 19.4 1.2 6.4 0 8.4.5 5.4 1.2a189.6 189.6 0 0 1 20.7 13.5c13.5 10.1 23.6 21.9 30 35.4 8.8 18.2 13.5 37.1 13.5 56.6a141.13 141.13 0 0 1-3 28.3 209.91 209.91 0 0 1-16 46l2.5.5c18.2-19.7 41.9-16 49.2-16l-6.4 5.9 22.4 17.7-1.7 30.7c-5.4-12.3-16.5-21.1-33-27.8 16.5 14.8 23.6 21.1 21.9 20.2-4.8-2.8-3.5-1.9-10.8-3.7 4.1 4.1 17.5 18.8 18.2 20.7l.2.2-.2.2c0 1.8 1.6-1.2-14 22.9-75.2-15.3-106.27-42.7-141.2-63.2l11.8 1.2c-11.8-18.5-15.6-17.7-38.4-26.1L149 225c-8.8-3-18.2-3-28.3.5l7.6-10.6-1.2-1.7c-14.9 4.3-19.8 9.2-22.6 11.3-1.1-5.5-2.8-12.4-12.3-28.8l-1.2 27-13.2-5c1.5-25.2 5.4-50.5 13.2-74.6zm276.5 330c-49.9 25-56.1 22.4-59 23.9-29.8-11.8-50.9-31.7-63.5-58.8l30 16.5c-9.8-9.3-18.3-16.5-38.4-44.3l11.8 23.1-17.7-7.6c14.2 21.1 23.5 51.7 66.6 73.5-120.8 24.2-199-72.1-200.9-74.3a262.57 262.57 0 0 0 35.4 24.8c3.4 1.7 7.1 2.5 10.1 1.2l-16-20.7c9.2 4.2 9.5 4.5 69.1 29-42.5-20.7-73.8-40.8-93.2-60.2-.5 6.4-1.2 10.1-1.2 10.1a80.25 80.25 0 0 1 20.7 26.6c-39-18.9-57.6-47.6-71.3-82.6 49.9 55.1 118.9 37.5 120.5 37.1 34.8 16.4 69.9 23.6 113.9 10.6 3.3 0 20.3 17 25.3 39.1l4.2-3-2.5-23.6c9 9 24.9 22.6 34.4 13-15.6-5.3-23.5-9.5-29.5-31.7 4.6 4.2 7.6 9 27.8 15l1.2-1.2-10.5-14.2c11.7-4.8-3.5 1 32-10.8 4.3 34.3 9 49.2.7 89.5zm115.3-214.4l-2.5.5 3 9.3c-3.5 5.9-23.7 44.3-71.6 79.7-39.5 29.8-76.6 39.1-80.9 40.3l-7.6-7.1-1.2 3 14.3 16-7.1-4.7 3.4 4.2h-1.2l-21.9-13.5 9.3 26.6-19-27.9-1.2 2.5 7.6 29c-6.1-8.2-21-32.6-56.8-39.6l32.5 21.2a214.82 214.82 0 0 1-93.2-6.4c-4.2-1.2-8.9-2.5-13.5-4.2l1.2-3-44.8-22.4 26.1 22.4c-57.7 9.1-113-25.4-126.4-83.4l-2.5-16.4-22.27 22.3c19.5-57.5 25.6-57.9 51.4-70.1-9.1-5.3-1.6-3.3-38.4-9.3 15.8-5.8 33-15.4 73 5.2a18.5 18.5 0 0 1 3.7-1.7c.6-3.2.4-.8 1-11.8 3.9 10 3.6 8.7 3 9.3l1.7.5c12.7-6.5 8.9-4.5 17-8.9l-5.4 13.5 22.3-5.8-8.4 8.4 2.5 2.5c4.5-1.8 30.3 3.4 40.8 16l-23.6-2.5c39.4 23 51.5 54 55.8 69.6l1.7-1.2c-2.8-22.3-12.4-33.9-16-40.1 4.2 5 39.2 34.6 110.4 46-11.3-.5-23.1 5.4-34.9 18.9l46.7-20.2-9.3 21.9c7.6-10.1 14.8-23.6 21.2-39.6v-.5l1.2-3-1.2 16c13.5-41.8 25.3-78.5 35.4-109.7l13.5-27.8v-2l-5.4-4.2h10.1l5.9 4.2 2.5-1.2-3.4-16 12.3 18.9 41.8-20.2-14.8 13 .5 2.9 17.7-.5a184 184 0 0 1 33 4.2l-23.6 2.5-1.2 3 26.6 23.1a254.21 254.21 0 0 1 27 32c-11.2-3.3-10.3-3.4-21.2-3.4l12.3 32.5zm-6.1-71.3l-3.9 13-14.3-11.8zm-254.8 7.1c1.7 10.6 4.7 17.7 8.8 21.9-9.3 6.6-27.5 13.9-46.5 16l.5 1.2a50.22 50.22 0 0 0 24.8-2.5l-7.1 13c4.2-1.7 10.1-7.1 17.7-14.8 11.9-5.5 12.7-5.1 20.2-16-12.7-6.4-15.7-13.7-18.4-18.8zm3.7-102.3c-6.4-3.4-10.6 3-12.3 18.9s2.5 29.5 11.8 39.6 18.2 10.6 26.1 3 3.4-23.6-11.3-47.7a39.57 39.57 0 0 0-14.27-13.8zm-4.7 46.3c5.4 2.2 10.5 1.9 12.3-10.6v-4.7l-1.2.5c-4.3-3.1-2.5-4.5-1.7-6.2l.5-.5c-.9-1.2-5-8.1-12.5 4.7-.5-13.5.5-21.9 3-24.8 1.2-2.5 4.7-1.2 11.3 4.2 6.4 5.4 11.3 16 15.2 32.5 6.5 28-19.8 26.2-26.9 4.9zm-45-5.5c1.6.3 9.3-1.1 9.3-14.8h-.5c-5.4-1.1-2.2-5.5-.7-5.9-1.7-3-3.4-4.2-5.4-4.7-8.1 0-11.6 12.7-8.1 21.2a7.51 7.51 0 0 0 5.43 4.2zM216 82.9l-2.5.5.5 3a48.94 48.94 0 0 1 26.1 5.9c-2.5-5.5-10-14.3-28.3-14.3l.5 2.5zm-71.8 49.4c21.7 16.8 16.5 21.4 46.5 23.6l-2.9-4.7a42.67 42.67 0 0 0 14.8-28.3c1.7-16-1.2-29.5-8.8-41.3l13-7.6a2.26 2.26 0 0 0-.5-1.7 14.21 14.21 0 0 0-13.5 1.7c-12.7 6.7-28 20.9-29 22.4-1.7 1.7-3.4 5.9-5.4 13.5a99.61 99.61 0 0 0-2.9 23.6c-4.7-8-10.5-6.4-19.9-5.9l7.1 7.6c-16.5 0-23.3 15.4-23.6 16 6.8 0 4.6-7.6 30-12.3-4.3-6.3-3.3-5-4.9-6.6zm18.7-18.7c1.2-7.6 3.4-13 6.4-17.2 5.4-6.4 10.6-10.1 16-11.8 4.2-1.7 7.1 1.2 10.1 9.3a72.14 72.14 0 0 1 3 25.3c-.5 9.3-3.4 17.2-8.4 23.1-2.9 3.4-5.4 5.9-6.4 7.6a39.21 39.21 0 0 1-11.3-.5l-7.1-3.4-5.4-6.4c.8-10 1.3-18.8 3.1-26zm42 56.1c-34.8 14.4-34.7 14-36.1 14.3-20.8 4.7-19-24.4-18.9-24.8l5.9-1.2-.5-2.5c-20.2-2.6-31 4.2-32.5 4.9.5.5 3 3.4 5.9 9.3 4.2-6.4 8.8-10.1 15.2-10.6a83.47 83.47 0 0 0 1.7 33.7c.1.5 2.6 17.4 27.5 24.1 11.3 3 27 1.2 48.9-5.4l-9.2.5c-4.2-14.8-6.4-24.8-5.9-29.5 11.3-8.8 21.9-11.3 30.7-7.6h2.5l-11.8-7.6-7.1.5c-5.9 1.2-12.3 4.2-19.4 8.4z\"],\n    \"themeco\": [448, 512, [], \"f5c6\", \"M202.9 8.43c9.9-5.73 26-5.82 35.95-.21L430 115.85c10 5.6 18 19.44 18 30.86V364c0 11.44-8.06 25.29-18 31L238.81 503.74c-9.93 5.66-26 5.57-35.85-.21L17.86 395.12C8 389.34 0 375.38 0 364V146.71c0-11.44 8-25.36 17.91-31.08zm-77.4 199.83c-15.94 0-31.89.14-47.83.14v101.45H96.8V280h28.7c49.71 0 49.56-71.74 0-71.74zm140.14 100.29l-30.73-34.64c37-7.51 34.8-65.23-10.87-65.51-16.09 0-32.17-.14-48.26-.14v101.59h19.13v-33.91h18.41l29.56 33.91h22.76zm-41.59-82.32c23.34 0 23.26 32.46 0 32.46h-29.13v-32.46zm-95.56-1.6c21.18 0 21.11 38.85 0 38.85H96.18v-38.84zm192.65-18.25c-68.46 0-71 105.8 0 105.8 69.48-.01 69.41-105.8 0-105.8zm0 17.39c44.12 0 44.8 70.86 0 70.86s-44.43-70.86 0-70.86z\"],\n    \"themeisle\": [512, 512, [], \"f2b2\", \"M208 88.286c0-10 6.286-21.714 17.715-21.714 11.142 0 17.714 11.714 17.714 21.714 0 10.285-6.572 21.714-17.714 21.714C214.286 110 208 98.571 208 88.286zm304 160c0 36.001-11.429 102.286-36.286 129.714-22.858 24.858-87.428 61.143-120.857 70.572l-1.143.286v32.571c0 16.286-12.572 30.571-29.143 30.571-10 0-19.429-5.714-24.572-14.286-5.427 8.572-14.856 14.286-24.856 14.286-10 0-19.429-5.714-24.858-14.286-5.142 8.572-14.571 14.286-24.57 14.286-10.286 0-19.429-5.714-24.858-14.286-5.143 8.572-14.571 14.286-24.571 14.286-18.857 0-29.429-15.714-29.429-32.857-16.286 12.285-35.715 19.428-56.571 19.428-22 0-43.429-8.285-60.286-22.857 10.285-.286 20.571-2.286 30.285-5.714-20.857-5.714-39.428-18.857-52-36.286 21.37 4.645 46.209 1.673 67.143-11.143-22-22-56.571-58.857-68.572-87.428C1.143 321.714 0 303.714 0 289.429c0-49.714 20.286-160 86.286-160 10.571 0 18.857 4.858 23.143 14.857a158.792 158.792 0 0 1 12-15.428c2-2.572 5.714-5.429 7.143-8.286 7.999-12.571 11.714-21.142 21.714-34C182.571 45.428 232 17.143 285.143 17.143c6 0 12 .285 17.714 1.143C313.714 6.571 328.857 0 344.572 0c14.571 0 29.714 6 40 16.286.857.858 1.428 2.286 1.428 3.428 0 3.714-10.285 13.429-12.857 16.286 4.286 1.429 15.714 6.858 15.714 12 0 2.857-2.857 5.143-4.571 7.143 31.429 27.714 49.429 67.143 56.286 108 4.286-5.143 10.285-8.572 17.143-8.572 10.571 0 20.857 7.144 28.571 14.001C507.143 187.143 512 221.714 512 248.286zM188 89.428c0 18.286 12.571 37.143 32.286 37.143 19.714 0 32.285-18.857 32.285-37.143 0-18-12.571-36.857-32.285-36.857-19.715 0-32.286 18.858-32.286 36.857zM237.714 194c0-19.714 3.714-39.143 8.571-58.286-52.039 79.534-13.531 184.571 68.858 184.571 21.428 0 42.571-7.714 60-20 2-7.429 3.714-14.857 3.714-22.572 0-14.286-6.286-21.428-20.572-21.428-4.571 0-9.143.857-13.429 1.714-63.343 12.668-107.142 3.669-107.142-63.999zm-41.142 254.858c0-11.143-8.858-20.857-20.286-20.857-11.429 0-20 9.715-20 20.857v32.571c0 11.143 8.571 21.142 20 21.142 11.428 0 20.286-9.715 20.286-21.142v-32.571zm49.143 0c0-11.143-8.572-20.857-20-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20-10 20-21.142v-32.571zm49.713 0c0-11.143-8.857-20.857-20.285-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20.285-9.715 20.285-21.142v-32.571zm49.715 0c0-11.143-8.857-20.857-20.286-20.857-11.428 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.858 21.142 20.286 21.142 11.429 0 20.286-10 20.286-21.142v-32.571zM421.714 286c-30.857 59.142-90.285 102.572-158.571 102.572-96.571 0-160.571-84.572-160.571-176.572 0-16.857 2-33.429 6-49.714-20 33.715-29.714 72.572-29.714 111.429 0 60.286 24.857 121.715 71.429 160.857 5.143-9.714 14.857-16.286 26-16.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.571-14.286 24.858-14.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.857-14.286 24.858-14.286 10 0 19.428 5.714 24.857 14.286 5.143-8.571 14.571-14.286 24.572-14.286 10.857 0 20.857 6.572 25.714 16 43.427-36.286 68.569-92 71.426-148.286zm10.572-99.714c0-53.714-34.571-105.714-92.572-105.714-30.285 0-58.571 15.143-78.857 36.857C240.862 183.812 233.41 254 302.286 254c28.805 0 97.357-28.538 84.286 36.857 28.857-26 45.714-65.714 45.714-104.571z\"],\n    \"think-peaks\": [576, 512, [], \"f731\", \"M465.4 409.4l87.1-150.2-32-.3-55.1 95L259.2 0 23 407.4l32 .3L259.2 55.6zm-355.3-44.1h32.1l117.4-202.5L463 511.9l32.5.1-235.8-404.6z\"],\n    \"trade-federation\": [496, 512, [], \"f513\", \"M248 8.8c-137 0-248 111-248 248s111 248 248 248 248-111 248-248-111-248-248-248zm0 482.8c-129.7 0-234.8-105.1-234.8-234.8S118.3 22 248 22s234.8 105.1 234.8 234.8S377.7 491.6 248 491.6zm155.1-328.5v-46.8H209.3V198H54.2l36.7 46h117.7v196.8h48.8V245h83.3v-47h-83.3v-34.8h145.7zm-73.3 45.1v23.9h-82.9v197.4h-26.8V232.1H96.3l-20.1-23.9h143.9v-80.6h171.8V152h-145v56.2zm-161.3-69l-12.4-20.7 2.1 23.8-23.5 5.4 23.3 5.4-2.1 24 12.3-20.5 22.2 9.5-15.7-18.1 15.8-18.1zm-29.6-19.7l9.3-11.5-12.7 5.9-8-12.4 1.7 13.9-14.3 3.8 13.7 2.7-.8 14.7 6.8-12.2 13.8 5.3zm165.4 145.2l-13.1 5.6-7.3-12.2 1.3 14.2-13.9 3.2 13.9 3.2-1.2 14.2 7.3-12.2 13.1 5.5-9.4-10.7zm106.9-77.2l-20.9 9.1-12-19.6 2.2 22.7-22.3 5.4 22.2 4.9-1.8 22.9 11.5-19.6 21.2 8.8-15.1-17zM248 29.9c-125.3 0-226.9 101.6-226.9 226.9S122.7 483.7 248 483.7s226.9-101.6 226.9-226.9S373.3 29.9 248 29.9zM342.6 196v51h-83.3v195.7h-52.7V245.9H89.9l-40-49.9h157.4v-81.6h197.8v50.7H259.4V196zM248 43.2c60.3 0 114.8 25 153.6 65.2H202.5V190H45.1C73.1 104.8 153.4 43.2 248 43.2zm0 427.1c-117.9 0-213.6-95.6-213.6-213.5 0-21.2 3.1-41.8 8.9-61.1L87.1 252h114.7v196.8h64.6V253h83.3v-62.7h-83.2v-19.2h145.6v-50.8c30.8 37 49.3 84.6 49.3 136.5.1 117.9-95.5 213.5-213.4 213.5zM178.8 275l-11-21.4 1.7 24.5-23.7 3.9 23.8 5.9-3.7 23.8 13-20.9 21.5 10.8-15.8-18.8 16.9-17.1z\"],\n    \"trello\": [448, 512, [], \"f181\", \"M392.3 32H56.1C25.1 32 0 57.1 0 88c-.1 0 0-4 0 336 0 30.9 25.1 56 56 56h336.2c30.8-.2 55.7-25.2 55.7-56V88c.1-30.8-24.8-55.8-55.6-56zM197 371.3c-.2 14.7-12.1 26.6-26.9 26.6H87.4c-14.8.1-26.9-11.8-27-26.6V117.1c0-14.8 12-26.9 26.9-26.9h82.9c14.8 0 26.9 12 26.9 26.9v254.2zm193.1-112c0 14.8-12 26.9-26.9 26.9h-81c-14.8 0-26.9-12-26.9-26.9V117.2c0-14.8 12-26.9 26.8-26.9h81.1c14.8 0 26.9 12 26.9 26.9v142.1z\"],\n    \"tripadvisor\": [576, 512, [], \"f262\", \"M166.4 280.521c0 13.236-10.73 23.966-23.966 23.966s-23.966-10.73-23.966-23.966 10.73-23.966 23.966-23.966 23.966 10.729 23.966 23.966zm264.962-23.956c-13.23 0-23.956 10.725-23.956 23.956 0 13.23 10.725 23.956 23.956 23.956 13.23 0 23.956-10.725 23.956-23.956-.001-13.231-10.726-23.956-23.956-23.956zm89.388 139.49c-62.667 49.104-153.276 38.109-202.379-24.559l-30.979 46.325-30.683-45.939c-48.277 60.39-135.622 71.891-197.885 26.055-64.058-47.158-77.759-137.316-30.601-201.374A186.762 186.762 0 0 0 0 139.416l90.286-.05a358.48 358.48 0 0 1 197.065-54.03 350.382 350.382 0 0 1 192.181 53.349l96.218.074a185.713 185.713 0 0 0-28.352 57.649c46.793 62.747 34.964 151.37-26.648 199.647zM259.366 281.761c-.007-63.557-51.535-115.075-115.092-115.068C80.717 166.7 29.2 218.228 29.206 281.785c.007 63.557 51.535 115.075 115.092 115.068 63.513-.075 114.984-51.539 115.068-115.052v-.04zm28.591-10.455c5.433-73.44 65.51-130.884 139.12-133.022a339.146 339.146 0 0 0-139.727-27.812 356.31 356.31 0 0 0-140.164 27.253c74.344 1.582 135.299 59.424 140.771 133.581zm251.706-28.767c-21.992-59.634-88.162-90.148-147.795-68.157-59.634 21.992-90.148 88.162-68.157 147.795v.032c22.038 59.607 88.198 90.091 147.827 68.113 59.615-22.004 90.113-88.162 68.125-147.783zm-326.039 37.975v.115c-.057 39.328-31.986 71.163-71.314 71.106-39.328-.057-71.163-31.986-71.106-71.314.057-39.328 31.986-71.163 71.314-71.106 39.259.116 71.042 31.94 71.106 71.199zm-24.512 0v-.084c-.051-25.784-20.994-46.645-46.778-46.594-25.784.051-46.645 20.994-46.594 46.777.051 25.784 20.994 46.645 46.777 46.594 25.726-.113 46.537-20.968 46.595-46.693zm313.423 0v.048c-.02 39.328-31.918 71.194-71.247 71.173s-71.194-31.918-71.173-71.247c.02-39.328 31.918-71.194 71.247-71.173 39.29.066 71.121 31.909 71.173 71.199zm-24.504-.008c-.009-25.784-20.918-46.679-46.702-46.67-25.784.009-46.679 20.918-46.67 46.702.009 25.784 20.918 46.678 46.702 46.67 25.765-.046 46.636-20.928 46.67-46.693v-.009z\"],\n    \"tumblr\": [320, 512, [], \"f173\", \"M309.8 480.3c-13.6 14.5-50 31.7-97.4 31.7-120.8 0-147-88.8-147-140.6v-144H17.9c-5.5 0-10-4.5-10-10v-68c0-7.2 4.5-13.6 11.3-16 62-21.8 81.5-76 84.3-117.1.8-11 6.5-16.3 16.1-16.3h70.9c5.5 0 10 4.5 10 10v115.2h83c5.5 0 10 4.4 10 9.9v81.7c0 5.5-4.5 10-10 10h-83.4V360c0 34.2 23.7 53.6 68 35.8 4.8-1.9 9-3.2 12.7-2.2 3.5.9 5.8 3.4 7.4 7.9l22 64.3c1.8 5 3.3 10.6-.4 14.5z\"],\n    \"tumblr-square\": [448, 512, [], \"f174\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-82.3 364.2c-8.5 9.1-31.2 19.8-60.9 19.8-75.5 0-91.9-55.5-91.9-87.9v-90h-29.7c-3.4 0-6.2-2.8-6.2-6.2v-42.5c0-4.5 2.8-8.5 7.1-10 38.8-13.7 50.9-47.5 52.7-73.2.5-6.9 4.1-10.2 10-10.2h44.3c3.4 0 6.2 2.8 6.2 6.2v72h51.9c3.4 0 6.2 2.8 6.2 6.2v51.1c0 3.4-2.8 6.2-6.2 6.2h-52.1V321c0 21.4 14.8 33.5 42.5 22.4 3-1.2 5.6-2 8-1.4 2.2.5 3.6 2.1 4.6 4.9l13.8 40.2c1 3.2 2 6.7-.3 9.1z\"],\n    \"twitch\": [448, 512, [], \"f1e8\", \"M40.1 32L10 108.9v314.3h107V480h60.2l56.8-56.8h87l117-117V32H40.1zm357.8 254.1L331 353H224l-56.8 56.8V353H76.9V72.1h321v214zM331 149v116.9h-40.1V149H331zm-107 0v116.9h-40.1V149H224z\"],\n    \"twitter\": [512, 512, [], \"f099\", \"M459.37 151.716c.325 4.548.325 9.097.325 13.645 0 138.72-105.583 298.558-298.558 298.558-59.452 0-114.68-17.219-161.137-47.106 8.447.974 16.568 1.299 25.34 1.299 49.055 0 94.213-16.568 130.274-44.832-46.132-.975-84.792-31.188-98.112-72.772 6.498.974 12.995 1.624 19.818 1.624 9.421 0 18.843-1.3 27.614-3.573-48.081-9.747-84.143-51.98-84.143-102.985v-1.299c13.969 7.797 30.214 12.67 47.431 13.319-28.264-18.843-46.781-51.005-46.781-87.391 0-19.492 5.197-37.36 14.294-52.954 51.655 63.675 129.3 105.258 216.365 109.807-1.624-7.797-2.599-15.918-2.599-24.04 0-57.828 46.782-104.934 104.934-104.934 30.213 0 57.502 12.67 76.67 33.137 23.715-4.548 46.456-13.32 66.599-25.34-7.798 24.366-24.366 44.833-46.132 57.827 21.117-2.273 41.584-8.122 60.426-16.243-14.292 20.791-32.161 39.308-52.628 54.253z\"],\n    \"twitter-square\": [448, 512, [], \"f081\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-48.9 158.8c.2 2.8.2 5.7.2 8.5 0 86.7-66 186.6-186.6 186.6-37.2 0-71.7-10.8-100.7-29.4 5.3.6 10.4.8 15.8.8 30.7 0 58.9-10.4 81.4-28-28.8-.6-53-19.5-61.3-45.5 10.1 1.5 19.2 1.5 29.6-1.2-30-6.1-52.5-32.5-52.5-64.4v-.8c8.7 4.9 18.9 7.9 29.6 8.3a65.447 65.447 0 0 1-29.2-54.6c0-12.2 3.2-23.4 8.9-33.1 32.3 39.8 80.8 65.8 135.2 68.6-9.3-44.5 24-80.6 64-80.6 18.9 0 35.9 7.9 47.9 20.7 14.8-2.8 29-8.3 41.6-15.8-4.9 15.2-15.2 28-28.8 36.1 13.2-1.4 26-5.1 37.8-10.2-8.9 13.1-20.1 24.7-32.9 34z\"],\n    \"typo3\": [448, 512, [], \"f42b\", \"M178.7 78.4c0-24.7 5.4-32.4 13.9-39.4-69.5 8.5-149.3 34-176.3 66.4-5.4 7.7-9.3 20.8-9.3 37.1C7 246 113.8 480 191.1 480c36.3 0 97.3-59.5 146.7-139-7 2.3-11.6 2.3-18.5 2.3-57.2 0-140.6-198.5-140.6-264.9zM301.5 32c-30.1 0-41.7 5.4-41.7 36.3 0 66.4 53.8 198.5 101.7 198.5 26.3 0 78.8-99.7 78.8-182.3 0-40.9-67-52.5-138.8-52.5z\"],\n    \"uber\": [448, 512, [], \"f402\", \"M414.1 32H33.9C15.2 32 0 47.2 0 65.9V446c0 18.8 15.2 34 33.9 34H414c18.7 0 33.9-15.2 33.9-33.9V65.9C448 47.2 432.8 32 414.1 32zM237.6 391.1C163 398.6 96.4 344.2 88.9 269.6h94.4V290c0 3.7 3 6.8 6.8 6.8H258c3.7 0 6.8-3 6.8-6.8v-67.9c0-3.7-3-6.8-6.8-6.8h-67.9c-3.7 0-6.8 3-6.8 6.8v20.4H88.9c7-69.4 65.4-122.2 135.1-122.2 69.7 0 128.1 52.8 135.1 122.2 7.5 74.5-46.9 141.1-121.5 148.6z\"],\n    \"ubuntu\": [496, 512, [], \"f7df\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm52.7 93c8.8-15.2 28.3-20.5 43.5-11.7 15.3 8.8 20.5 28.3 11.7 43.6-8.8 15.2-28.3 20.5-43.5 11.7-15.3-8.9-20.5-28.4-11.7-43.6zM87.4 287.9c-17.6 0-31.9-14.3-31.9-31.9 0-17.6 14.3-31.9 31.9-31.9 17.6 0 31.9 14.3 31.9 31.9 0 17.6-14.3 31.9-31.9 31.9zm28.1 3.1c22.3-17.9 22.4-51.9 0-69.9 8.6-32.8 29.1-60.7 56.5-79.1l23.7 39.6c-51.5 36.3-51.5 112.5 0 148.8L172 370c-27.4-18.3-47.8-46.3-56.5-79zm228.7 131.7c-15.3 8.8-34.7 3.6-43.5-11.7-8.8-15.3-3.6-34.8 11.7-43.6 15.2-8.8 34.7-3.6 43.5 11.7 8.8 15.3 3.6 34.8-11.7 43.6zm.3-69.5c-26.7-10.3-56.1 6.6-60.5 35-5.2 1.4-48.9 14.3-96.7-9.4l22.5-40.3c57 26.5 123.4-11.7 128.9-74.4l46.1.7c-2.3 34.5-17.3 65.5-40.3 88.4zm-5.9-105.3c-5.4-62-71.3-101.2-128.9-74.4l-22.5-40.3c47.9-23.7 91.5-10.8 96.7-9.4 4.4 28.3 33.8 45.3 60.5 35 23.1 22.9 38 53.9 40.2 88.5l-46 .6z\"],\n    \"uikit\": [448, 512, [], \"f403\", \"M443.9 128v256L218 512 0 384V169.7l87.6 45.1v117l133.5 75.5 135.8-75.5v-151l-101.1-57.6 87.6-53.1L443.9 128zM308.6 49.1L223.8 0l-88.6 54.8 86 47.3 87.4-53z\"],\n    \"uniregistry\": [384, 512, [], \"f404\", \"M192 480c39.5 0 76.2-11.8 106.8-32.2H85.3C115.8 468.2 152.5 480 192 480zm-89.1-193.1v-12.4H0v12.4c0 2.5 0 5 .1 7.4h103.1c-.2-2.4-.3-4.9-.3-7.4zm20.5 57H8.5c2.6 8.5 5.8 16.8 9.6 24.8h138.3c-12.9-5.7-24.1-14.2-33-24.8zm-17.7-34.7H1.3c.9 7.6 2.2 15 3.9 22.3h109.7c-4-6.9-7.2-14.4-9.2-22.3zm-2.8-69.3H0v17.3h102.9zm0-173.2H0v4.9h102.9zm0-34.7H0v2.5h102.9zm0 69.3H0v7.4h102.9zm0 104H0v14.8h102.9zm0-69.3H0v9.9h102.9zm0 34.6H0V183h102.9zm166.2 160.9h109.7c1.8-7.3 3.1-14.7 3.9-22.3H278.3c-2.1 7.9-5.2 15.4-9.2 22.3zm12-185.7H384V136H281.1zm0 37.2H384v-12.4H281.1zm0-74.3H384v-7.4H281.1zm0-76.7v2.5H384V32zm-203 410.9h227.7c11.8-8.7 22.7-18.6 32.2-29.7H44.9c9.6 11 21.4 21 33.2 29.7zm203-371.3H384v-4.9H281.1zm0 148.5H384v-14.8H281.1zM38.8 405.7h305.3c6.7-8.5 12.6-17.6 17.8-27.2H23c5.2 9.6 9.2 18.7 15.8 27.2zm188.8-37.1H367c3.7-8 5.8-16.2 8.5-24.8h-115c-8.8 10.7-20.1 19.2-32.9 24.8zm53.5-81.7c0 2.5-.1 5-.4 7.4h103.1c.1-2.5.2-4.9.2-7.4v-12.4H281.1zm0-29.7H384v-17.3H281.1z\"],\n    \"untappd\": [640, 512, [], \"f405\", \"M401.3 49.9c-79.8 160.1-84.6 152.5-87.9 173.2l-5.2 32.8c-1.9 12-6.6 23.5-13.7 33.4L145.6 497.1c-7.6 10.6-20.4 16.2-33.4 14.6-40.3-5-77.8-32.2-95.3-68.5-5.7-11.8-4.5-25.8 3.1-36.4l148.9-207.9c7.1-9.9 16.4-18 27.2-23.7l29.3-15.5c18.5-9.8 9.7-11.9 135.6-138.9 1-4.8 1-7.3 3.6-8 3-.7 6.6-1 6.3-4.6l-.4-4.6c-.2-1.9 1.3-3.6 3.2-3.6 4.5-.1 13.2 1.2 25.6 10 12.3 8.9 16.4 16.8 17.7 21.1.6 1.8-.6 3.7-2.4 4.2l-4.5 1.1c-3.4.9-2.5 4.4-2.3 7.4.1 2.8-2.3 3.6-6.5 6.1zM230.1 36.4c3.4.9 2.5 4.4 2.3 7.4-.2 2.7 2.1 3.5 6.4 6 7.9 15.9 15.3 30.5 22.2 44 .7 1.3 2.3 1.5 3.3.5 11.2-12 24.6-26.2 40.5-42.6 1.3-1.4 1.4-3.5.1-4.9-8-8.2-16.5-16.9-25.6-26.1-1-4.7-1-7.3-3.6-8-3-.8-6.6-1-6.3-4.6.3-3.3 1.4-8.1-2.8-8.2-4.5-.1-13.2 1.1-25.6 10-12.3 8.9-16.4 16.8-17.7 21.1-1.4 4.2 3.6 4.6 6.8 5.4zM620 406.7L471.2 198.8c-13.2-18.5-26.6-23.4-56.4-39.1-11.2-5.9-14.2-10.9-30.5-28.9-1-1.1-2.9-.9-3.6.5-46.3 88.8-47.1 82.8-49 94.8-1.7 10.7-1.3 20 .3 29.8 1.9 12 6.6 23.5 13.7 33.4l148.9 207.9c7.6 10.6 20.2 16.2 33.1 14.7 40.3-4.9 78-32 95.7-68.6 5.4-11.9 4.3-25.9-3.4-36.6z\"],\n    \"ups\": [384, 512, [], \"f7e0\", \"M103.2 303c-5.2 3.6-32.6 13.1-32.6-19V180H37.9v102.6c0 74.9 80.2 51.1 97.9 39V180h-32.6zM4 74.82v220.9c0 103.7 74.9 135.2 187.7 184.1 112.4-48.9 187.7-80.2 187.7-184.1V74.82c-116.3-61.6-281.8-49.6-375.4 0zm358.1 220.9c0 86.6-53.2 113.6-170.4 165.3-117.5-51.8-170.5-78.7-170.5-165.3v-126.4c102.3-93.8 231.6-100 340.9-89.8zm-209.6-107.4v212.8h32.7v-68.7c24.4 7.3 71.7-2.6 71.7-78.5 0-97.4-80.7-80.92-104.4-65.6zm32.7 117.3v-100.3c8.4-4.2 38.4-12.7 38.4 49.3 0 67.9-36.4 51.8-38.4 51zm79.1-86.4c.1 47.3 51.6 42.5 52.2 70.4.6 23.5-30.4 23-50.8 4.9v30.1c36.2 21.5 81.9 8.1 83.2-33.5 1.7-51.5-54.1-46.6-53.4-73.2.6-20.3 30.6-20.5 48.5-2.2v-28.4c-28.5-22-79.9-9.2-79.7 31.9z\"],\n    \"usb\": [640, 512, [], \"f287\", \"M641.5 256c0 3.1-1.7 6.1-4.5 7.5L547.9 317c-1.4.8-2.8 1.4-4.5 1.4-1.4 0-3.1-.3-4.5-1.1-2.8-1.7-4.5-4.5-4.5-7.8v-35.6H295.7c25.3 39.6 40.5 106.9 69.6 106.9H392V354c0-5 3.9-8.9 8.9-8.9H490c5 0 8.9 3.9 8.9 8.9v89.1c0 5-3.9 8.9-8.9 8.9h-89.1c-5 0-8.9-3.9-8.9-8.9v-26.7h-26.7c-75.4 0-81.1-142.5-124.7-142.5H140.3c-8.1 30.6-35.9 53.5-69 53.5C32 327.3 0 295.3 0 256s32-71.3 71.3-71.3c33.1 0 61 22.8 69 53.5 39.1 0 43.9 9.5 74.6-60.4C255 88.7 273 95.7 323.8 95.7c7.5-20.9 27-35.6 50.4-35.6 29.5 0 53.5 23.9 53.5 53.5s-23.9 53.5-53.5 53.5c-23.4 0-42.9-14.8-50.4-35.6H294c-29.1 0-44.3 67.4-69.6 106.9h310.1v-35.6c0-3.3 1.7-6.1 4.5-7.8 2.8-1.7 6.4-1.4 8.9.3l89.1 53.5c2.8 1.1 4.5 4.1 4.5 7.2z\"],\n    \"usps\": [576, 512, [], \"f7e1\", \"M460.3 241.7c25.8-41.3 15.2-48.8-11.7-48.8h-27c-.1 0-1.5-1.4-10.9 8-11.2 5.6-37.9 6.3-37.9 8.7 0 4.5 70.3-3.1 88.1 0 9.5 1.5-1.5 20.4-4.4 32-.5 4.5 2.4 2.3 3.8.1zm-112.1 22.6c64-21.3 97.3-23.9 102-26.2 4.4-2.9-4.4-6.6-26.2-5.8-51.7 2.2-137.6 37.1-172.6 53.9l-30.7-93.3h196.6c-2.7-28.2-152.9-22.6-337.9-22.6L27 415.8c196.4-97.3 258.9-130.3 321.2-151.5zM94.7 96c253.3 53.7 330 65.7 332.1 85.2 36.4 0 45.9 0 52.4 6.6 21.1 19.7-14.6 67.7-14.6 67.7-4.4 2.9-406.4 160.2-406.4 160.2h423.1L549 96z\"],\n    \"ussunnah\": [512, 512, [], \"f407\", \"M156.8 285.1l5.7 14.4h-8.2c-1.3-3.2-3.1-7.7-3.8-9.5-2.5-6.3-1.1-8.4 0-10 1.9-2.7 3.2-4.4 3.6-5.2 0 2.2.8 5.7 2.7 10.3zm297.3 18.8c-2.1 13.8-5.7 27.1-10.5 39.7l43 23.4-44.8-18.8c-5.3 13.2-12 25.6-19.9 37.2l34.2 30.2-36.8-26.4c-8.4 11.8-18 22.6-28.7 32.3l24.9 34.7-28.1-31.8c-11 9.6-23.1 18-36.1 25.1l15.7 37.2-19.3-35.3c-13.1 6.8-27 12.1-41.6 15.9l6.7 38.4-10.5-37.4c-14.3 3.4-29.2 5.3-44.5 5.4L256 512l-1.9-38.4c-15.3-.1-30.2-2-44.5-5.3L199 505.6l6.7-38.2c-14.6-3.7-28.6-9.1-41.7-15.8l-19.2 35.1 15.6-37c-13-7-25.2-15.4-36.2-25.1l-27.9 31.6 24.7-34.4c-10.7-9.7-20.4-20.5-28.8-32.3l-36.5 26.2 33.9-29.9c-7.9-11.6-14.6-24.1-20-37.3l-44.4 18.7L67.8 344c-4.8-12.7-8.4-26.1-10.5-39.9l-51 9 50.3-14.2c-1.1-8.5-1.7-17.1-1.7-25.9 0-4.7.2-9.4.5-14.1L0 256l56-2.8c1.3-13.1 3.8-25.8 7.5-38.1L6.4 199l58.9 10.4c4-12 9.1-23.5 15.2-34.4l-55.1-30 58.3 24.6C90 159 97.2 149.2 105.3 140L55.8 96.4l53.9 38.7c8.1-8.6 17-16.5 26.6-23.6l-40-55.6 45.6 51.6c9.5-6.6 19.7-12.3 30.3-17.2l-27.3-64.9 33.8 62.1c10.5-4.4 21.4-7.9 32.7-10.4L199 6.4l19.5 69.2c11-2.1 22.3-3.2 33.8-3.4L256 0l3.6 72.2c11.5.2 22.8 1.4 33.8 3.5L313 6.4l-12.4 70.7c11.3 2.6 22.2 6.1 32.6 10.5l33.9-62.2-27.4 65.1c10.6 4.9 20.7 10.7 30.2 17.2l45.8-51.8-40.1 55.9c9.5 7.1 18.4 15 26.5 23.6l54.2-38.9-49.7 43.9c8 9.1 15.2 18.9 21.5 29.4l58.7-24.7-55.5 30.2c6.1 10.9 11.1 22.3 15.1 34.3l59.3-10.4-57.5 16.2c3.7 12.2 6.2 24.9 7.5 37.9L512 256l-56 2.8c.3 4.6.5 9.3.5 14.1 0 8.7-.6 17.3-1.6 25.8l50.7 14.3-51.5-9.1zm-21.8-31c0-97.5-79-176.5-176.5-176.5s-176.5 79-176.5 176.5 79 176.5 176.5 176.5 176.5-79 176.5-176.5zm-24 0c0 84.3-68.3 152.6-152.6 152.6s-152.6-68.3-152.6-152.6 68.3-152.6 152.6-152.6 152.6 68.3 152.6 152.6zM195 241c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-40.7-19c0 2.1 1.3 3.8 3.6 5.1 3.5 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-19 0c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.4 6.8-9.6 10.9-9.6 12.6zm204.9 87.9c-8.4-3-8.7-6.8-8.7-15.6V182c-8.2 12.5-14.2 18.6-18 18.6 6.3 14.4 9.5 23.9 9.5 28.3v64.3c0 2.2-2.2 6.5-4.7 6.5h-18c-2.8-7.5-10.2-26.9-15.3-40.3-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3 2.6 6.7 6.4 16.5 7.9 20.2h-9.2c-3.9-10.4-9.6-25.4-11.8-31.1-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3.8 2 2.8 7.3 4.3 10.9H256c-1.5-4.1-5.6-14.6-8.4-22-2 2.5-7.2 9.2-10.7 13.7 2.5 1.6 4.3 3.6 5.2 6.3.2.6.5 1.4.6 1.7H225c-4.6-13.9-11.4-27.7-11.4-34.1 0-2.2.3-5.1 1.1-8.2-8.8 10.8-14 15.9-14 25 0 7.5 10.4 28.3 10.4 33.3 0 1.7-.5 3.3-1.4 4.9-9.6-12.7-15.5-20.7-18.8-20.7h-12l-11.2-28c-3.8-9.6-5.7-16-5.7-18.8 0-3.8.5-7.7 1.7-12.2-1 1.3-3.7 4.7-5.5 7.1-.8-2.1-3.1-7.7-4.6-11.5-2.1 2.5-7.5 9.1-11.2 13.6.9 2.3 3.3 8.1 4.9 12.2-2.5 3.3-9.1 11.8-13.6 17.7-4 5.3-5.8 13.3-2.7 21.8 2.5 6.7 2 7.9-1.7 14.1H191c5.5 0 14.3 14 15.5 22 13.2-16 15.4-19.6 16.8-21.6h107c3.9 0 7.2-1.9 9.9-5.8zm20.1-26.6V181.7c-9 12.5-15.9 18.6-20.7 18.6 7.1 14.4 10.7 23.9 10.7 28.3v66.3c0 17.5 8.6 20.4 24 20.4 8.1 0 12.5-.8 13.7-2.7-4.3-1.6-7.6-2.5-9.9-3.3-8.1-3.2-17.8-7.4-17.8-26z\"],\n    \"vaadin\": [448, 512, [], \"f408\", \"M224.5 140.7c1.5-17.6 4.9-52.7 49.8-52.7h98.6c20.7 0 32.1-7.8 32.1-21.6V54.1c0-12.2 9.3-22.1 21.5-22.1S448 41.9 448 54.1v36.5c0 42.9-21.5 62-66.8 62H280.7c-30.1 0-33 14.7-33 27.1 0 1.3-.1 2.5-.2 3.7-.7 12.3-10.9 22.2-23.4 22.2s-22.7-9.8-23.4-22.2c-.1-1.2-.2-2.4-.2-3.7 0-12.3-3-27.1-33-27.1H66.8c-45.3 0-66.8-19.1-66.8-62V54.1C0 41.9 9.4 32 21.6 32s21.5 9.9 21.5 22.1v12.3C43.1 80.2 54.5 88 75.2 88h98.6c44.8 0 48.3 35.1 49.8 52.7h.9zM224 456c11.5 0 21.4-7 25.7-16.3 1.1-1.8 97.1-169.6 98.2-171.4 11.9-19.6-3.2-44.3-27.2-44.3-13.9 0-23.3 6.4-29.8 20.3L224 362l-66.9-117.7c-6.4-13.9-15.9-20.3-29.8-20.3-24 0-39.1 24.6-27.2 44.3 1.1 1.9 97.1 169.6 98.2 171.4 4.3 9.3 14.2 16.3 25.7 16.3z\"],\n    \"viacoin\": [384, 512, [], \"f237\", \"M384 32h-64l-80.7 192h-94.5L64 32H0l48 112H0v48h68.5l13.8 32H0v48h102.8L192 480l89.2-208H384v-48h-82.3l13.8-32H384v-48h-48l48-112zM192 336l-27-64h54l-27 64z\"],\n    \"viadeo\": [448, 512, [], \"f2a9\", \"M276.2 150.5v.7C258.3 98.6 233.6 47.8 205.4 0c43.3 29.2 67 100 70.8 150.5zm32.7 121.7c7.6 18.2 11 37.5 11 57 0 77.7-57.8 141-137.8 139.4l3.8-.3c74.2-46.7 109.3-118.6 109.3-205.1 0-38.1-6.5-75.9-18.9-112 1 11.7 1 23.7 1 35.4 0 91.8-18.1 241.6-116.6 280C95 455.2 49.4 398 49.4 329.2c0-75.6 57.4-142.3 135.4-142.3 16.8 0 33.7 3.1 49.1 9.6 1.7-15.1 6.5-29.9 13.4-43.3-19.9-7.2-41.2-10.7-62.5-10.7-161.5 0-238.7 195.9-129.9 313.7 67.9 74.6 192 73.9 259.8 0 56.6-61.3 60.9-142.4 36.4-201-12.7 8-27.1 13.9-42.2 17zM418.1 11.7c-31 66.5-81.3 47.2-115.8 80.1-12.4 12-20.6 34-20.6 50.5 0 14.1 4.5 27.1 12 38.8 47.4-11 98.3-46 118.2-90.7-.7 5.5-4.8 14.4-7.2 19.2-20.3 35.7-64.6 65.6-99.7 84.9 14.8 14.4 33.7 25.8 55 25.8 79 0 110.1-134.6 58.1-208.6z\"],\n    \"viadeo-square\": [448, 512, [], \"f2aa\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM280.7 381.2c-42.4 46.2-120 46.6-162.4 0-68-73.6-19.8-196.1 81.2-196.1 13.3 0 26.6 2.1 39.1 6.7-4.3 8.4-7.3 17.6-8.4 27.1-9.7-4.1-20.2-6-30.7-6-48.8 0-84.6 41.7-84.6 88.9 0 43 28.5 78.7 69.5 85.9 61.5-24 72.9-117.6 72.9-175 0-7.3 0-14.8-.6-22.1-11.2-32.9-26.6-64.6-44.2-94.5 27.1 18.3 41.9 62.5 44.2 94.1v.4c7.7 22.5 11.8 46.2 11.8 70 0 54.1-21.9 99-68.3 128.2l-2.4.2c50 1 86.2-38.6 86.2-87.2 0-12.2-2.1-24.3-6.9-35.7 9.5-1.9 18.5-5.6 26.4-10.5 15.3 36.6 12.6 87.3-22.8 125.6zM309 233.7c-13.3 0-25.1-7.1-34.4-16.1 21.9-12 49.6-30.7 62.3-53 1.5-3 4.1-8.6 4.5-12-12.5 27.9-44.2 49.8-73.9 56.7-4.7-7.3-7.5-15.5-7.5-24.3 0-10.3 5.2-24.1 12.9-31.6 21.6-20.5 53-8.5 72.4-50 32.5 46.2 13.1 130.3-36.3 130.3z\"],\n    \"viber\": [512, 512, [], \"f409\", \"M444 49.9C431.3 38.2 379.9.9 265.3.4c0 0-135.1-8.1-200.9 52.3C27.8 89.3 14.9 143 13.5 209.5c-1.4 66.5-3.1 191.1 117 224.9h.1l-.1 51.6s-.8 20.9 13 25.1c16.6 5.2 26.4-10.7 42.3-27.8 8.7-9.4 20.7-23.2 29.8-33.7 82.2 6.9 145.3-8.9 152.5-11.2 16.6-5.4 110.5-17.4 125.7-142 15.8-128.6-7.6-209.8-49.8-246.5zM457.9 287c-12.9 104-89 110.6-103 115.1-6 1.9-61.5 15.7-131.2 11.2 0 0-52 62.7-68.2 79-5.3 5.3-11.1 4.8-11-5.7 0-6.9.4-85.7.4-85.7-.1 0-.1 0 0 0-101.8-28.2-95.8-134.3-94.7-189.8 1.1-55.5 11.6-101 42.6-131.6 55.7-50.5 170.4-43 170.4-43 96.9.4 143.3 29.6 154.1 39.4 35.7 30.6 53.9 103.8 40.6 211.1zm-139-80.8c.4 8.6-12.5 9.2-12.9.6-1.1-22-11.4-32.7-32.6-33.9-8.6-.5-7.8-13.4.7-12.9 27.9 1.5 43.4 17.5 44.8 46.2zm20.3 11.3c1-42.4-25.5-75.6-75.8-79.3-8.5-.6-7.6-13.5.9-12.9 58 4.2 88.9 44.1 87.8 92.5-.1 8.6-13.1 8.2-12.9-.3zm47 13.4c.1 8.6-12.9 8.7-12.9.1-.6-81.5-54.9-125.9-120.8-126.4-8.5-.1-8.5-12.9 0-12.9 73.7.5 133 51.4 133.7 139.2zM374.9 329v.2c-10.8 19-31 40-51.8 33.3l-.2-.3c-21.1-5.9-70.8-31.5-102.2-56.5-16.2-12.8-31-27.9-42.4-42.4-10.3-12.9-20.7-28.2-30.8-46.6-21.3-38.5-26-55.7-26-55.7-6.7-20.8 14.2-41 33.3-51.8h.2c9.2-4.8 18-3.2 23.9 3.9 0 0 12.4 14.8 17.7 22.1 5 6.8 11.7 17.7 15.2 23.8 6.1 10.9 2.3 22-3.7 26.6l-12 9.6c-6.1 4.9-5.3 14-5.3 14s17.8 67.3 84.3 84.3c0 0 9.1.8 14-5.3l9.6-12c4.6-6 15.7-9.8 26.6-3.7 14.7 8.3 33.4 21.2 45.8 32.9 7 5.7 8.6 14.4 3.8 23.6z\"],\n    \"vimeo\": [448, 512, [], \"f40a\", \"M403.2 32H44.8C20.1 32 0 52.1 0 76.8v358.4C0 459.9 20.1 480 44.8 480h358.4c24.7 0 44.8-20.1 44.8-44.8V76.8c0-24.7-20.1-44.8-44.8-44.8zM377 180.8c-1.4 31.5-23.4 74.7-66 129.4-44 57.2-81.3 85.8-111.7 85.8-18.9 0-34.8-17.4-47.9-52.3-25.5-93.3-36.4-148-57.4-148-2.4 0-10.9 5.1-25.4 15.2l-15.2-19.6c37.3-32.8 72.9-69.2 95.2-71.2 25.2-2.4 40.7 14.8 46.5 51.7 20.7 131.2 29.9 151 67.6 91.6 13.5-21.4 20.8-37.7 21.8-48.9 3.5-33.2-25.9-30.9-45.8-22.4 15.9-52.1 46.3-77.4 91.2-76 33.3.9 49 22.5 47.1 64.7z\"],\n    \"vimeo-square\": [448, 512, [], \"f194\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16.2 149.6c-1.4 31.1-23.2 73.8-65.3 127.9-43.5 56.5-80.3 84.8-110.4 84.8-18.7 0-34.4-17.2-47.3-51.6-25.2-92.3-35.9-146.4-56.7-146.4-2.4 0-10.8 5-25.1 15.1L64 192c36.9-32.4 72.1-68.4 94.1-70.4 24.9-2.4 40.2 14.6 46 51.1 20.5 129.6 29.6 149.2 66.8 90.5 13.4-21.2 20.6-37.2 21.5-48.3 3.4-32.8-25.6-30.6-45.2-22.2 15.7-51.5 45.8-76.5 90.1-75.1 32.9 1 48.4 22.4 46.5 64z\"],\n    \"vimeo-v\": [448, 512, [], \"f27d\", \"M447.8 153.6c-2 43.6-32.4 103.3-91.4 179.1-60.9 79.2-112.4 118.8-154.6 118.8-26.1 0-48.2-24.1-66.3-72.3C100.3 250 85.3 174.3 56.2 174.3c-3.4 0-15.1 7.1-35.2 21.1L0 168.2c51.6-45.3 100.9-95.7 131.8-98.5 34.9-3.4 56.3 20.5 64.4 71.5 28.7 181.5 41.4 208.9 93.6 126.7 18.7-29.6 28.8-52.1 30.2-67.6 4.8-45.9-35.8-42.8-63.3-31 22-72.1 64.1-107.1 126.2-105.1 45.8 1.2 67.5 31.1 64.9 89.4z\"],\n    \"vine\": [384, 512, [], \"f1ca\", \"M384 254.7v52.1c-18.4 4.2-36.9 6.1-52.1 6.1-36.9 77.4-103 143.8-125.1 156.2-14 7.9-27.1 8.4-42.7-.8C137 452 34.2 367.7 0 102.7h74.5C93.2 261.8 139 343.4 189.3 404.5c27.9-27.9 54.8-65.1 75.6-106.9-49.8-25.3-80.1-80.9-80.1-145.6 0-65.6 37.7-115.1 102.2-115.1 114.9 0 106.2 127.9 81.6 181.5 0 0-46.4 9.2-63.5-20.5 3.4-11.3 8.2-30.8 8.2-48.5 0-31.3-11.3-46.6-28.4-46.6-18.2 0-30.8 17.1-30.8 50 .1 79.2 59.4 118.7 129.9 101.9z\"],\n    \"vk\": [576, 512, [], \"f189\", \"M545 117.7c3.7-12.5 0-21.7-17.8-21.7h-58.9c-15 0-21.9 7.9-25.6 16.7 0 0-30 73.1-72.4 120.5-13.7 13.7-20 18.1-27.5 18.1-3.7 0-9.4-4.4-9.4-16.9V117.7c0-15-4.2-21.7-16.6-21.7h-92.6c-9.4 0-15 7-15 13.5 0 14.2 21.2 17.5 23.4 57.5v86.8c0 19-3.4 22.5-10.9 22.5-20 0-68.6-73.4-97.4-157.4-5.8-16.3-11.5-22.9-26.6-22.9H38.8c-16.8 0-20.2 7.9-20.2 16.7 0 15.6 20 93.1 93.1 195.5C160.4 378.1 229 416 291.4 416c37.5 0 42.1-8.4 42.1-22.9 0-66.8-3.4-73.1 15.4-73.1 8.7 0 23.7 4.4 58.7 38.1 40 40 46.6 57.9 69 57.9h58.9c16.8 0 25.3-8.4 20.4-25-11.2-34.9-86.9-106.7-90.3-111.5-8.7-11.2-6.2-16.2 0-26.2.1-.1 72-101.3 79.4-135.6z\"],\n    \"vnv\": [640, 512, [], \"f40b\", \"M104.9 352c-34.1 0-46.4-30.4-46.4-30.4L2.6 210.1S-7.8 192 13 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.7-74.5c5.6-9.5 8.4-18.1 18.8-18.1h32.8c20.8 0 10.4 18.1 10.4 18.1l-55.8 111.5S174.2 352 140 352h-35.1zm395 0c-34.1 0-46.4-30.4-46.4-30.4l-55.9-111.5S387.2 192 408 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.8-74.5c5.6-9.5 8.4-18.1 18.8-18.1H627c20.8 0 10.4 18.1 10.4 18.1l-55.9 111.5S569.3 352 535.1 352h-35.2zM337.6 192c34.1 0 46.4 30.4 46.4 30.4l55.9 111.5s10.4 18.1-10.4 18.1h-32.8c-10.4 0-13.2-8.7-18.8-18.1l-36.7-74.5s-5.2-13.1-21.1-13.1c-15.9 0-21.1 13.1-21.1 13.1l-36.7 74.5c-5.6 9.4-8.4 18.1-18.8 18.1h-32.9c-20.8 0-10.4-18.1-10.4-18.1l55.9-111.5s12.2-30.4 46.4-30.4h35.1z\"],\n    \"vuejs\": [448, 512, [], \"f41f\", \"M356.9 64.3H280l-56 88.6-48-88.6H0L224 448 448 64.3h-91.1zm-301.2 32h53.8L224 294.5 338.4 96.3h53.8L224 384.5 55.7 96.3z\"],\n    \"waze\": [512, 512, [], \"f83f\", \"M502.17 201.67C516.69 287.53 471.23 369.59 389 409.8c13 34.1-12.4 70.2-48.32 70.2a51.68 51.68 0 0 1-51.57-49c-6.44.19-64.2 0-76.33-.64A51.69 51.69 0 0 1 159 479.92c-33.86-1.36-57.95-34.84-47-67.92-37.21-13.11-72.54-34.87-99.62-70.8-13-17.28-.48-41.8 20.84-41.8 46.31 0 32.22-54.17 43.15-110.26C94.8 95.2 193.12 32 288.09 32c102.48 0 197.15 70.67 214.08 169.67zM373.51 388.28c42-19.18 81.33-56.71 96.29-102.14 40.48-123.09-64.15-228-181.71-228-83.45 0-170.32 55.42-186.07 136-9.53 48.91 5 131.35-68.75 131.35C58.21 358.6 91.6 378.11 127 389.54c24.66-21.8 63.87-15.47 79.83 14.34 14.22 1 79.19 1.18 87.9.82a51.69 51.69 0 0 1 78.78-16.42zM205.12 187.13c0-34.74 50.84-34.75 50.84 0s-50.84 34.74-50.84 0zm116.57 0c0-34.74 50.86-34.75 50.86 0s-50.86 34.75-50.86 0zm-122.61 70.69c-3.44-16.94 22.18-22.18 25.62-5.21l.06.28c4.14 21.42 29.85 44 64.12 43.07 35.68-.94 59.25-22.21 64.11-42.77 4.46-16.05 28.6-10.36 25.47 6-5.23 22.18-31.21 62-91.46 62.9-42.55 0-80.88-27.84-87.9-64.25z\"],\n    \"weebly\": [512, 512, [], \"f5cc\", \"M425.09 65.83c-39.88 0-73.28 25.73-83.66 64.33-18.16-58.06-65.5-64.33-84.95-64.33-19.78 0-66.8 6.28-85.28 64.33-10.38-38.6-43.45-64.33-83.66-64.33C38.59 65.83 0 99.72 0 143.03c0 28.96 4.18 33.27 77.17 233.48 22.37 60.57 67.77 69.35 92.74 69.35 39.23 0 70.04-19.46 85.93-53.98 15.89 34.83 46.69 54.29 85.93 54.29 24.97 0 70.36-9.1 92.74-69.67 76.55-208.65 77.5-205.58 77.5-227.2.63-48.32-36.01-83.47-86.92-83.47zm26.34 114.81l-65.57 176.44c-7.92 21.49-21.22 37.22-46.24 37.22-23.44 0-37.38-12.41-44.03-33.9l-39.28-117.42h-.95L216.08 360.4c-6.96 21.5-20.9 33.6-44.02 33.6-25.02 0-38.33-15.74-46.24-37.22L60.88 181.55c-5.38-14.83-7.92-23.91-7.92-34.5 0-16.34 15.84-29.36 38.33-29.36 18.69 0 31.99 11.8 36.11 29.05l44.03 139.82h.95l44.66-136.79c6.02-19.67 16.47-32.08 38.96-32.08s32.94 12.11 38.96 32.08l44.66 136.79h.95l44.03-139.82c4.12-17.25 17.42-29.05 36.11-29.05 22.17 0 38.33 13.32 38.33 35.71-.32 7.87-4.12 16.04-7.61 27.24z\"],\n    \"weibo\": [512, 512, [], \"f18a\", \"M407 177.6c7.6-24-13.4-46.8-37.4-41.7-22 4.8-28.8-28.1-7.1-32.8 50.1-10.9 92.3 37.1 76.5 84.8-6.8 21.2-38.8 10.8-32-10.3zM214.8 446.7C108.5 446.7 0 395.3 0 310.4c0-44.3 28-95.4 76.3-143.7C176 67 279.5 65.8 249.9 161c-4 13.1 12.3 5.7 12.3 6 79.5-33.6 140.5-16.8 114 51.4-3.7 9.4 1.1 10.9 8.3 13.1 135.7 42.3 34.8 215.2-169.7 215.2zm143.7-146.3c-5.4-55.7-78.5-94-163.4-85.7-84.8 8.6-148.8 60.3-143.4 116s78.5 94 163.4 85.7c84.8-8.6 148.8-60.3 143.4-116zM347.9 35.1c-25.9 5.6-16.8 43.7 8.3 38.3 72.3-15.2 134.8 52.8 111.7 124-7.4 24.2 29.1 37 37.4 12 31.9-99.8-55.1-195.9-157.4-174.3zm-78.5 311c-17.1 38.8-66.8 60-109.1 46.3-40.8-13.1-58-53.4-40.3-89.7 17.7-35.4 63.1-55.4 103.4-45.1 42 10.8 63.1 50.2 46 88.5zm-86.3-30c-12.9-5.4-30 .3-38 12.9-8.3 12.9-4.3 28 8.6 34 13.1 6 30.8.3 39.1-12.9 8-13.1 3.7-28.3-9.7-34zm32.6-13.4c-5.1-1.7-11.4.6-14.3 5.4-2.9 5.1-1.4 10.6 3.7 12.9 5.1 2 11.7-.3 14.6-5.4 2.8-5.2 1.1-10.9-4-12.9z\"],\n    \"weixin\": [576, 512, [], \"f1d7\", \"M385.2 167.6c6.4 0 12.6.3 18.8 1.1C387.4 90.3 303.3 32 207.7 32 100.5 32 13 104.8 13 197.4c0 53.4 29.3 97.5 77.9 131.6l-19.3 58.6 68-34.1c24.4 4.8 43.8 9.7 68.2 9.7 6.2 0 12.1-.3 18.3-.8-4-12.9-6.2-26.6-6.2-40.8-.1-84.9 72.9-154 165.3-154zm-104.5-52.9c14.5 0 24.2 9.7 24.2 24.4 0 14.5-9.7 24.2-24.2 24.2-14.8 0-29.3-9.7-29.3-24.2.1-14.7 14.6-24.4 29.3-24.4zm-136.4 48.6c-14.5 0-29.3-9.7-29.3-24.2 0-14.8 14.8-24.4 29.3-24.4 14.8 0 24.4 9.7 24.4 24.4 0 14.6-9.6 24.2-24.4 24.2zM563 319.4c0-77.9-77.9-141.3-165.4-141.3-92.7 0-165.4 63.4-165.4 141.3S305 460.7 397.6 460.7c19.3 0 38.9-5.1 58.6-9.9l53.4 29.3-14.8-48.6C534 402.1 563 363.2 563 319.4zm-219.1-24.5c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.8 0 24.4 9.7 24.4 19.3 0 10-9.7 19.6-24.4 19.6zm107.1 0c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.5 0 24.4 9.7 24.4 19.3.1 10-9.9 19.6-24.4 19.6z\"],\n    \"whatsapp\": [448, 512, [], \"f232\", \"M380.9 97.1C339 55.1 283.2 32 223.9 32c-122.4 0-222 99.6-222 222 0 39.1 10.2 77.3 29.6 111L0 480l117.7-30.9c32.4 17.7 68.9 27 106.1 27h.1c122.3 0 224.1-99.6 224.1-222 0-59.3-25.2-115-67.1-157zm-157 341.6c-33.2 0-65.7-8.9-94-25.7l-6.7-4-69.8 18.3L72 359.2l-4.4-7c-18.5-29.4-28.2-63.3-28.2-98.2 0-101.7 82.8-184.5 184.6-184.5 49.3 0 95.6 19.2 130.4 54.1 34.8 34.9 56.2 81.2 56.1 130.5 0 101.8-84.9 184.6-186.6 184.6zm101.2-138.2c-5.5-2.8-32.8-16.2-37.9-18-5.1-1.9-8.8-2.8-12.5 2.8-3.7 5.6-14.3 18-17.6 21.8-3.2 3.7-6.5 4.2-12 1.4-32.6-16.3-54-29.1-75.5-66-5.7-9.8 5.7-9.1 16.3-30.3 1.8-3.7.9-6.9-.5-9.7-1.4-2.8-12.5-30.1-17.1-41.2-4.5-10.8-9.1-9.3-12.5-9.5-3.2-.2-6.9-.2-10.6-.2-3.7 0-9.7 1.4-14.8 6.9-5.1 5.6-19.4 19-19.4 46.3 0 27.3 19.9 53.7 22.6 57.4 2.8 3.7 39.1 59.7 94.8 83.8 35.2 15.2 49 16.5 66.6 13.9 10.7-1.6 32.8-13.4 37.4-26.4 4.6-13 4.6-24.1 3.2-26.4-1.3-2.5-5-3.9-10.5-6.6z\"],\n    \"whatsapp-square\": [448, 512, [], \"f40c\", \"M224 122.8c-72.7 0-131.8 59.1-131.9 131.8 0 24.9 7 49.2 20.2 70.1l3.1 5-13.3 48.6 49.9-13.1 4.8 2.9c20.2 12 43.4 18.4 67.1 18.4h.1c72.6 0 133.3-59.1 133.3-131.8 0-35.2-15.2-68.3-40.1-93.2-25-25-58-38.7-93.2-38.7zm77.5 188.4c-3.3 9.3-19.1 17.7-26.7 18.8-12.6 1.9-22.4.9-47.5-9.9-39.7-17.2-65.7-57.2-67.7-59.8-2-2.6-16.2-21.5-16.2-41s10.2-29.1 13.9-33.1c3.6-4 7.9-5 10.6-5 2.6 0 5.3 0 7.6.1 2.4.1 5.7-.9 8.9 6.8 3.3 7.9 11.2 27.4 12.2 29.4s1.7 4.3.3 6.9c-7.6 15.2-15.7 14.6-11.6 21.6 15.3 26.3 30.6 35.4 53.9 47.1 4 2 6.3 1.7 8.6-1 2.3-2.6 9.9-11.6 12.5-15.5 2.6-4 5.3-3.3 8.9-2 3.6 1.3 23.1 10.9 27.1 12.9s6.6 3 7.6 4.6c.9 1.9.9 9.9-2.4 19.1zM400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM223.9 413.2c-26.6 0-52.7-6.7-75.8-19.3L64 416l22.5-82.2c-13.9-24-21.2-51.3-21.2-79.3C65.4 167.1 136.5 96 223.9 96c42.4 0 82.2 16.5 112.2 46.5 29.9 30 47.9 69.8 47.9 112.2 0 87.4-72.7 158.5-160.1 158.5z\"],\n    \"whmcs\": [448, 512, [], \"f40d\", \"M448 161v-21.3l-28.5-8.8-2.2-10.4 20.1-20.7L427 80.4l-29 7.5-7.2-7.5 7.5-28.2-19.1-11.6-21.3 21-10.7-3.2-7-26.4h-22.6l-6.2 26.4-12.1 3.2-19.7-21-19.4 11 8.1 27.7-8.1 8.4-28.5-7.5-11 19.1 20.7 21-2.9 10.4-28.5 7.8-.3 21.7 28.8 7.5 2.4 12.1-20.1 19.9 10.4 18.5 29.6-7.5 7.2 8.6-8.1 26.9 19.9 11.6 19.4-20.4 11.6 2.9 6.7 28.5 22.6.3 6.7-28.8 11.6-3.5 20.7 21.6 20.4-12.1-8.8-28 7.8-8.1 28.8 8.8 10.3-20.1-20.9-18.8 2.2-12.1 29.1-7zm-119.2 45.2c-31.3 0-56.8-25.4-56.8-56.8s25.4-56.8 56.8-56.8 56.8 25.4 56.8 56.8c0 31.5-25.4 56.8-56.8 56.8zm72.3 16.4l46.9 14.5V277l-55.1 13.4-4.1 22.7 38.9 35.3-19.2 37.9-54-16.7-14.6 15.2 16.7 52.5-38.3 22.7-38.9-40.5-21.7 6.6-12.6 54-42.4-.5-12.6-53.6-21.7-5.6-36.4 38.4-37.4-21.7 15.2-50.5-13.7-16.1-55.5 14.1-19.7-34.8 37.9-37.4-4.8-22.8-54-14.1.5-40.9L54 219.9l5.7-19.7-38.9-39.4L41.5 125l53.6 14.1 15.2-15.7-15.2-52 36.4-20.7 36.8 39.4L191 84l11.6-52H245l11.6 45.9L234 72l-6.3-1.7-3.3 5.7-11 19.1-3.3 5.6 4.6 4.6 17.2 17.4-.3 1-23.8 6.5-6.2 1.7-.1 6.4-.2 12.9C153.8 161.6 118 204 118 254.7c0 58.3 47.3 105.7 105.7 105.7 50.5 0 92.7-35.4 103.2-82.8l13.2.2 6.9.1 1.6-6.7 5.6-24 1.9-.6 17.1 17.8 4.7 4.9 5.8-3.4 20.4-12.1 5.8-3.5-2-6.5-6.8-21.2z\"],\n    \"wikipedia-w\": [640, 512, [], \"f266\", \"M640 51.2l-.3 12.2c-28.1.8-45 15.8-55.8 40.3-25 57.8-103.3 240-155.3 358.6H415l-81.9-193.1c-32.5 63.6-68.3 130-99.2 193.1-.3.3-15 0-15-.3C172 352.3 122.8 243.4 75.8 133.4 64.4 106.7 26.4 63.4.2 63.7c0-3.1-.3-10-.3-14.2h161.9v13.9c-19.2 1.1-52.8 13.3-43.3 34.2 21.9 49.7 103.6 240.3 125.6 288.6 15-29.7 57.8-109.2 75.3-142.8-13.9-28.3-58.6-133.9-72.8-160-9.7-17.8-36.1-19.4-55.8-19.7V49.8l142.5.3v13.1c-19.4.6-38.1 7.8-29.4 26.1 18.9 40 30.6 68.1 48.1 104.7 5.6-10.8 34.7-69.4 48.1-100.8 8.9-20.6-3.9-28.6-38.6-29.4.3-3.6 0-10.3.3-13.6 44.4-.3 111.1-.3 123.1-.6v13.6c-22.5.8-45.8 12.8-58.1 31.7l-59.2 122.8c6.4 16.1 63.3 142.8 69.2 156.7L559.2 91.8c-8.6-23.1-36.4-28.1-47.2-28.3V49.6l127.8 1.1.2.5z\"],\n    \"windows\": [448, 512, [], \"f17a\", \"M0 93.7l183.6-25.3v177.4H0V93.7zm0 324.6l183.6 25.3V268.4H0v149.9zm203.8 28L448 480V268.4H203.8v177.9zm0-380.6v180.1H448V32L203.8 65.7z\"],\n    \"wix\": [640, 512, [], \"f5cf\", \"M393.38 131.69c0 13.03 2.08 32.69-28.68 43.83-9.52 3.45-15.95 9.66-15.95 9.66 0-31 4.72-42.22 17.4-48.86 9.75-5.11 27.23-4.63 27.23-4.63zm-115.8 35.54l-34.24 132.66-28.48-108.57c-7.69-31.99-20.81-48.53-48.43-48.53-27.37 0-40.66 16.18-48.43 48.53L89.52 299.89 55.28 167.23C49.73 140.51 23.86 128.96 0 131.96l65.57 247.93s21.63 1.56 32.46-3.96c14.22-7.25 20.98-12.84 29.59-46.57 7.67-30.07 29.11-118.41 31.12-124.7 4.76-14.94 11.09-13.81 15.4 0 1.97 6.3 23.45 94.63 31.12 124.7 8.6 33.73 15.37 39.32 29.59 46.57 10.82 5.52 32.46 3.96 32.46 3.96l65.57-247.93c-24.42-3.07-49.82 8.93-55.3 35.27zm115.78 5.21s-4.1 6.34-13.46 11.57c-6.01 3.36-11.78 5.64-17.97 8.61-15.14 7.26-13.18 13.95-13.18 35.2v152.07s16.55 2.09 27.37-3.43c13.93-7.1 17.13-13.95 17.26-44.78V181.41l-.02.01v-8.98zm163.44 84.08L640 132.78s-35.11-5.98-52.5 9.85c-13.3 12.1-24.41 29.55-54.18 72.47-.47.73-6.25 10.54-13.07 0-29.29-42.23-40.8-60.29-54.18-72.47-17.39-15.83-52.5-9.85-52.5-9.85l83.2 123.74-82.97 123.36s36.57 4.62 53.95-11.21c11.49-10.46 17.58-20.37 52.51-70.72 6.81-10.52 12.57-.77 13.07 0 29.4 42.38 39.23 58.06 53.14 70.72 17.39 15.83 53.32 11.21 53.32 11.21L556.8 256.52z\"],\n    \"wizards-of-the-coast\": [640, 512, [], \"f730\", \"M219.19 345.69c-1.9 1.38-11.07 8.44-.26 23.57 4.64 6.42 14.11 12.79 21.73 6.55 6.5-4.88 7.35-12.92.26-23.04-5.47-7.76-14.28-12.88-21.73-7.08zm336.75 75.94c-.34 1.7-.55 1.67.79 0 2.09-4.19 4.19-10.21 4.98-19.9 3.14-38.49-40.33-71.49-101.34-78.03-54.73-6.02-124.38 9.17-188.8 60.49l-.26 1.57c2.62 4.98 4.98 10.74 3.4 21.21l.79.26c63.89-58.4 131.19-77.25 184.35-73.85 58.4 3.67 100.03 34.04 100.03 68.08-.01 9.96-2.63 15.72-3.94 20.17zM392.28 240.42c.79 7.07 4.19 10.21 9.17 10.47 5.5.26 9.43-2.62 10.47-6.55.79-3.4 2.09-29.85 2.09-29.85s-11.26 6.55-14.93 10.47c-3.66 3.68-7.33 8.39-6.8 15.46zm-50.02-151.1C137.75 89.32 13.1 226.8.79 241.2c-1.05.52-1.31.79.79 1.31 60.49 16.5 155.81 81.18 196.13 202.16l1.05.26c55.25-69.92 140.88-128.05 236.99-128.05 80.92 0 130.15 42.16 130.15 80.39 0 18.33-6.55 33.52-22.26 46.35 0 .96-.2.79.79.79 14.66-10.74 27.5-28.8 27.5-48.18 0-22.78-12.05-38.23-12.05-38.23 7.07 7.07 10.74 16.24 10.74 16.24 5.76-40.85 26.97-62.32 26.97-62.32-2.36-9.69-6.81-17.81-6.81-17.81 7.59 8.12 14.4 27.5 14.4 41.37 0 10.47-3.4 22.78-12.57 31.95l.26.52c8.12-4.98 16.5-16.76 16.5-37.97 0-15.71-4.71-25.92-4.71-25.92 5.76-5.24 11.26-9.17 15.97-11.78.79 3.4 2.09 9.69 2.36 14.93 0 1.05.79 1.83 1.05 0 .79-5.76-.26-16.24-.26-16.5 6.02-3.14 9.69-4.45 9.69-4.45C617.74 176 489.43 89.32 342.26 89.32zm-99.24 289.62c-11.06 8.99-24.2 4.08-30.64-4.19-7.45-9.58-6.76-24.09 4.19-32.47 14.85-11.35 27.08-.49 31.16 5.5.28.39 12.13 16.57-4.71 31.16zm2.09-136.43l9.43-17.81 11.78 70.96-12.57 6.02-24.62-28.8 14.14-26.71 3.67 4.45-1.83-8.11zm18.59 117.58l-.26-.26c2.05-4.1-2.5-6.61-17.54-31.69-1.31-2.36-3.14-2.88-4.45-2.62l-.26-.52c7.86-5.76 15.45-10.21 25.4-15.71l.52.26c1.31 1.83 2.09 2.88 3.4 4.71l-.26.52c-1.05-.26-2.36-.79-5.24.26-2.09.79-7.86 3.67-12.31 7.59v1.31c1.57 2.36 3.93 6.55 5.76 9.69h.26c10.05-6.28 7.56-4.55 11.52-7.86h.26c.52 1.83.52 1.83 1.83 5.5l-.26.26c-3.06.61-4.65.34-11.52 5.5v.26c9.46 17.02 11.01 16.75 12.57 15.97l.26.26c-2.34 1.59-6.27 4.21-9.68 6.57zm55.26-32.47c-3.14 1.57-6.02 2.88-9.95 4.98l-.26-.26c1.29-2.59 1.16-2.71-11.78-32.47l-.26-.26c-.15 0-8.9 3.65-9.95 7.33h-.52l-1.05-5.76.26-.52c7.29-4.56 25.53-11.64 27.76-12.57l.52.26 3.14 4.98-.26.52c-3.53-1.76-7.35.76-12.31 2.62v.26c12.31 32.01 12.67 30.64 14.66 30.64v.25zm44.77-16.5c-4.19 1.05-5.24 1.31-9.69 2.88l-.26-.26.52-4.45c-1.05-3.4-3.14-11.52-3.67-13.62l-.26-.26c-3.4.79-8.9 2.62-12.83 3.93l-.26.26c.79 2.62 3.14 9.95 4.19 13.88.79 2.36 1.83 2.88 2.88 3.14v.52c-3.67 1.05-7.07 2.62-10.21 3.93l-.26-.26c1.05-1.31 1.05-2.88.26-4.98-1.05-3.14-8.12-23.83-9.17-27.23-.52-1.83-1.57-3.14-2.62-3.14v-.52c3.14-1.05 6.02-2.09 10.74-3.4l.26.26-.26 4.71c1.31 3.93 2.36 7.59 3.14 9.69h.26c3.93-1.31 9.43-2.88 12.83-3.93l.26-.26-2.62-9.43c-.52-1.83-1.05-3.4-2.62-3.93v-.26c4.45-1.05 7.33-1.83 10.74-2.36l.26.26c-1.05 1.31-1.05 2.88-.52 4.45 1.57 6.28 4.71 20.43 6.28 26.45.54 2.62 1.85 3.41 2.63 3.93zm32.21-6.81l-.26.26c-4.71.52-14.14 2.36-22.52 4.19l-.26-.26.79-4.19c-1.57-7.86-3.4-18.59-4.98-26.19-.26-1.83-.79-2.88-2.62-3.67l.79-.52c9.17-1.57 20.16-2.36 24.88-2.62l.26.26c.52 2.36.79 3.14 1.57 5.5l-.26.26c-1.14-1.14-3.34-3.2-16.24-.79l-.26.26c.26 1.57 1.05 6.55 1.57 9.95l.26.26c9.52-1.68 4.76-.06 10.74-2.36h.26c0 1.57-.26 1.83-.26 5.24h-.26c-4.81-1.03-2.15-.9-10.21 0l-.26.26c.26 2.09 1.57 9.43 2.09 12.57l.26.26c1.15.38 14.21-.65 16.24-4.71h.26c-.53 2.38-1.05 4.21-1.58 6.04zm10.74-44.51c-4.45 2.36-8.12 2.88-11 2.88-.25.02-11.41 1.09-17.54-9.95-6.74-10.79-.98-25.2 5.5-31.69 8.8-8.12 23.35-10.1 28.54-17.02 8.03-10.33-13.04-22.31-29.59-5.76l-2.62-2.88 5.24-16.24c25.59-1.57 45.2-3.04 50.02 16.24.79 3.14 0 9.43-.26 12.05 0 2.62-1.83 18.85-2.09 23.04-.52 4.19-.79 18.33-.79 20.69.26 2.36.52 4.19 1.57 5.5 1.57 1.83 5.76 1.83 5.76 1.83l-.79 4.71c-11.82-1.07-10.28-.59-20.43-1.05-3.22-5.15-2.23-3.28-4.19-7.86 0 .01-4.19 3.94-7.33 5.51zm37.18 21.21c-6.35-10.58-19.82-7.16-21.73 5.5-2.63 17.08 14.3 19.79 20.69 10.21l.26.26c-.52 1.83-1.83 6.02-1.83 6.28l-.52.52c-10.3 6.87-28.5-2.5-25.66-18.59 1.94-10.87 14.44-18.93 28.8-9.95l.26.52c0 1.06-.27 3.41-.27 5.25zm5.77-87.73v-6.55c.69 0 19.65 3.28 27.76 7.33l-1.57 17.54s10.21-9.43 15.45-10.74c5.24-1.57 14.93 7.33 14.93 7.33l-11.26 11.26c-12.07-6.35-19.59-.08-20.69.79-5.29 38.72-8.6 42.17 4.45 46.09l-.52 4.71c-17.55-4.29-18.53-4.5-36.92-7.33l.79-4.71c7.25 0 7.48-5.32 7.59-6.81 0 0 4.98-53.16 4.98-55.25-.02-2.87-4.99-3.66-4.99-3.66zm10.99 114.44c-8.12-2.09-14.14-11-10.74-20.69 3.14-9.43 12.31-12.31 18.85-10.21 9.17 2.62 12.83 11.78 10.74 19.38-2.61 8.9-9.42 13.87-18.85 11.52zm42.16 9.69c-2.36-.52-7.07-2.36-8.64-2.88v-.26l1.57-1.83c.59-8.24.59-7.27.26-7.59-4.82-1.81-6.66-2.36-7.07-2.36-1.31 1.83-2.88 4.45-3.67 5.5l-.79 3.4v.26c-1.31-.26-3.93-1.31-6.02-1.57v-.26l2.62-1.83c3.4-4.71 9.95-14.14 13.88-20.16v-2.09l.52-.26c2.09.79 5.5 2.09 7.59 2.88.48.48.18-1.87-1.05 25.14-.24 1.81.02 2.6.8 3.91zm-4.71-89.82c11.25-18.27 30.76-16.19 34.04-3.4L539.7 198c2.34-6.25-2.82-9.9-4.45-11.26l1.83-3.67c12.22 10.37 16.38 13.97 22.52 20.43-25.91 73.07-30.76 80.81-24.62 84.32l-1.83 4.45c-6.37-3.35-8.9-4.42-17.81-8.64l2.09-6.81c-.26-.26-3.93 3.93-9.69 3.67-19.06-1.3-22.89-31.75-9.67-52.9zm29.33 79.34c0-5.71-6.34-7.89-7.86-5.24-1.31 2.09 1.05 4.98 2.88 8.38 1.57 2.62 2.62 6.28 1.05 9.43-2.64 6.34-12.4 5.31-15.45-.79 0-.7-.27.09 1.83-4.71l.79-.26c-.57 5.66 6.06 9.61 8.38 4.98 1.05-2.09-.52-5.5-2.09-8.38-1.57-2.62-3.67-6.28-1.83-9.69 2.72-5.06 11.25-4.47 14.66 2.36v.52l-2.36 3.4zm21.21 13.36c-1.96-3.27-.91-2.14-4.45-4.71h-.26c-2.36 4.19-5.76 10.47-8.64 16.24-1.31 2.36-1.05 3.4-.79 3.93l-.26.26-5.76-4.45.26-.26 2.09-1.31c3.14-5.76 6.55-12.05 9.17-17.02v-.26c-2.64-1.98-1.22-1.51-6.02-1.83v-.26l3.14-3.4h.26c3.67 2.36 9.95 6.81 12.31 8.9l.26.26-1.31 3.91zm27.23-44.26l-2.88-2.88c.79-2.36 1.83-4.98 2.09-7.59.75-9.74-11.52-11.84-11.52-4.98 0 4.98 7.86 19.38 7.86 27.76 0 10.21-5.76 15.71-13.88 16.5-8.38.79-20.16-10.47-20.16-10.47l4.98-14.4 2.88 2.09c-2.97 17.8 17.68 20.37 13.35 5.24-1.06-4.02-18.75-34.2 2.09-38.23 13.62-2.36 23.04 16.5 23.04 16.5l-7.85 10.46zm35.62-10.21c-11-30.38-60.49-127.53-191.95-129.62-53.42-1.05-94.27 15.45-132.76 37.97l85.63-9.17-91.39 20.69 25.14 19.64-3.93-16.5c7.5-1.71 39.15-8.45 66.77-8.9l-22.26 80.39c13.61-.7 18.97-8.98 19.64-22.78l4.98-1.05.26 26.71c-22.46 3.21-37.3 6.69-49.49 9.95l13.09-43.21-61.54-36.66 2.36 8.12 10.21 4.98c6.28 18.59 19.38 56.56 20.43 58.66 1.95 4.28 3.16 5.78 12.05 4.45l1.05 4.98c-16.08 4.86-23.66 7.61-39.02 14.4l-2.36-4.71c4.4-2.94 8.73-3.94 5.5-12.83-23.7-62.5-21.48-58.14-22.78-59.44l2.36-4.45 33.52 67.3c-3.84-11.87 1.68 1.69-32.99-78.82l-41.9 88.51 4.71-13.88-35.88-42.16 27.76 93.48-11.78 8.38C95 228.58 101.05 231.87 93.23 231.52c-5.5-.26-13.62 5.5-13.62 5.5L74.63 231c30.56-23.53 31.62-24.33 58.4-42.68l4.19 7.07s-5.76 4.19-7.86 7.07c-5.9 9.28 1.67 13.28 61.8 75.68l-18.85-58.92 39.8-10.21 25.66 30.64 4.45-12.31-4.98-24.62 13.09-3.4.52 3.14 3.67-10.47-94.27 29.33 11.26-4.98-13.62-42.42 17.28-9.17 30.11 36.14 28.54-13.09c-1.41-7.47-2.47-14.5-4.71-19.64l17.28 13.88 4.71-2.09-59.18-42.68 23.08 11.5c18.98-6.07 25.23-7.47 32.21-9.69l2.62 11c-12.55 12.55 1.43 16.82 6.55 19.38l-13.62-61.01 12.05 28.28c4.19-1.31 7.33-2.09 7.33-2.09l2.62 8.64s-3.14 1.05-6.28 2.09l8.9 20.95 33.78-65.73-20.69 61.01c42.42-24.09 81.44-36.66 131.98-35.88 67.04 1.05 167.33 40.85 199.8 139.83.78 2.1-.01 2.63-.79.27zM203.48 152.43s1.83-.52 4.19-1.31l9.43 7.59c-.4 0-3.44-.25-11.26 2.36l-2.36-8.64zm143.76 38.5c-1.57-.6-26.46-4.81-33.26 20.69l21.73 17.02 11.53-37.71zM318.43 67.07c-58.4 0-106.05 12.05-114.96 14.4v.79c8.38 2.09 14.4 4.19 21.21 11.78l1.57.26c6.55-1.83 48.97-13.88 110.24-13.88 180.16 0 301.67 116.79 301.67 223.37v9.95c0 1.31.79 2.62 1.05.52.52-2.09.79-8.64.79-19.64.26-83.79-96.63-227.55-321.57-227.55zm211.06 169.68c1.31-5.76 0-12.31-7.33-13.09-9.62-1.13-16.14 23.79-17.02 33.52-.79 5.5-1.31 14.93 6.02 14.93 4.68-.01 9.72-.91 18.33-35.36zm-61.53 42.95c-2.62-.79-9.43-.79-12.57 10.47-1.83 6.81.52 13.35 6.02 14.66 3.67 1.05 8.9.52 11.78-10.74 2.62-9.94-1.83-13.61-5.23-14.39zM491 300.65c1.83.52 3.14 1.05 5.76 1.83 0-1.83.52-8.38.79-12.05-1.05 1.31-5.5 8.12-6.55 9.95v.27z\"],\n    \"wolf-pack-battalion\": [512, 512, [], \"f514\", \"M267.73 471.53l10.56 15.84 5.28-12.32 5.28 7V512c21.06-7.92 21.11-66.86 25.51-97.21 4.62-31.89-.88-92.81 81.37-149.11-8.88-23.61-12-49.43-2.64-80.05C421 189 447 196.21 456.43 239.73l-30.35 8.36c11.15 23 17 46.76 13.2 72.14L412 313.18l-6.16 33.43-18.47-7-8.8 33.39-19.35-7 26.39 21.11 8.8-28.15L419 364.2l7-35.63 26.39 14.52c.25-20 7-58.06-8.8-84.45l26.39 5.28c4-22.07-2.38-39.21-7.92-56.74l22.43 9.68c-.44-25.07-29.94-56.79-61.58-58.5-20.22-1.09-56.74-25.17-54.1-51.9 2-19.87 17.45-42.62 43.11-49.7-44 36.51-9.68 67.3 5.28 73.46 4.4-11.44 17.54-69.08 0-130.2-40.39 22.87-89.65 65.1-93.2 147.79l-58 38.71-3.52 93.25L369.78 220l7 7-17.59 3.52-44 38.71-15.84-5.28-28.1 49.25-3.52 119.64 21.11 15.84-32.55 15.84-32.55-15.84 21.11-15.84-3.52-119.64-28.15-49.26-15.84 5.28-44-38.71-17.58-3.51 7-7 107.33 59.82-3.52-93.25-58.06-38.71C185 65.1 135.77 22.87 95.3 0c-17.54 61.12-4.4 118.76 0 130.2 15-6.16 49.26-36.95 5.28-73.46 25.66 7.08 41.15 29.83 43.11 49.7 2.63 26.74-33.88 50.81-54.1 51.9-31.65 1.72-61.15 33.44-61.59 58.51l22.43-9.68c-5.54 17.53-11.91 34.67-7.92 56.74l26.39-5.28c-15.76 26.39-9.05 64.43-8.8 84.45l26.39-14.52 7 35.63 24.63-5.28 8.8 28.15L153.35 366 134 373l-8.8-33.43-18.47 7-6.16-33.43-27.27 7c-3.82-25.38 2-49.1 13.2-72.14l-30.35-8.36c9.4-43.52 35.47-50.77 63.34-54.1 9.36 30.62 6.24 56.45-2.64 80.05 82.25 56.3 76.75 117.23 81.37 149.11 4.4 30.35 4.45 89.29 25.51 97.21v-29.83l5.28-7 5.28 12.32 10.56-15.84 11.44 21.11 11.43-21.1zm79.17-95L331.06 366c7.47-4.36 13.76-8.42 19.35-12.32-.6 7.22-.27 13.84-3.51 22.84zm28.15-49.26c-.4 10.94-.9 21.66-1.76 31.67-7.85-1.86-15.57-3.8-21.11-7 8.24-7.94 15.55-16.32 22.87-24.68zm24.63 5.28c0-13.43-2.05-24.21-5.28-33.43a235 235 0 0 1-18.47 27.27zm3.52-80.94c19.44 12.81 27.8 33.66 29.91 56.3-12.32-4.53-24.63-9.31-36.95-10.56 5.06-12 6.65-28.14 7-45.74zm-1.76-45.74c.81 14.3 1.84 28.82 1.76 42.23 19.22-8.11 29.78-9.72 44-14.08-10.61-18.96-27.2-25.53-45.76-28.16zM165.68 376.52L181.52 366c-7.47-4.36-13.76-8.42-19.35-12.32.6 7.26.27 13.88 3.51 22.88zm-28.15-49.26c.4 10.94.9 21.66 1.76 31.67 7.85-1.86 15.57-3.8 21.11-7-8.24-7.93-15.55-16.31-22.87-24.67zm-24.64 5.28c0-13.43 2-24.21 5.28-33.43a235 235 0 0 0 18.47 27.27zm-3.52-80.94c-19.44 12.81-27.8 33.66-29.91 56.3 12.32-4.53 24.63-9.31 37-10.56-5-12-6.65-28.14-7-45.74zm1.76-45.74c-.81 14.3-1.84 28.82-1.76 42.23-19.22-8.11-29.78-9.72-44-14.08 10.63-18.95 27.23-25.52 45.76-28.15z\"],\n    \"wordpress\": [512, 512, [], \"f19a\", \"M61.7 169.4l101.5 278C92.2 413 43.3 340.2 43.3 256c0-30.9 6.6-60.1 18.4-86.6zm337.9 75.9c0-26.3-9.4-44.5-17.5-58.7-10.8-17.5-20.9-32.4-20.9-49.9 0-19.6 14.8-37.8 35.7-37.8.9 0 1.8.1 2.8.2-37.9-34.7-88.3-55.9-143.7-55.9-74.3 0-139.7 38.1-177.8 95.9 5 .2 9.7.3 13.7.3 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l77.5 230.4L249.8 247l-33.1-90.8c-11.5-.7-22.3-2-22.3-2-11.5-.7-10.1-18.2 1.3-17.5 0 0 35.1 2.7 56 2.7 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l76.9 228.7 21.2-70.9c9-29.4 16-50.5 16-68.7zm-139.9 29.3l-63.8 185.5c19.1 5.6 39.2 8.7 60.1 8.7 24.8 0 48.5-4.3 70.6-12.1-.6-.9-1.1-1.9-1.5-2.9l-65.4-179.2zm183-120.7c.9 6.8 1.4 14 1.4 21.9 0 21.6-4 45.8-16.2 76.2l-65 187.9C426.2 403 468.7 334.5 468.7 256c0-37-9.4-71.8-26-102.1zM504 256c0 136.8-111.3 248-248 248C119.2 504 8 392.7 8 256 8 119.2 119.2 8 256 8c136.7 0 248 111.2 248 248zm-11.4 0c0-130.5-106.2-236.6-236.6-236.6C125.5 19.4 19.4 125.5 19.4 256S125.6 492.6 256 492.6c130.5 0 236.6-106.1 236.6-236.6z\"],\n    \"wordpress-simple\": [512, 512, [], \"f411\", \"M256 8C119.3 8 8 119.2 8 256c0 136.7 111.3 248 248 248s248-111.3 248-248C504 119.2 392.7 8 256 8zM33 256c0-32.3 6.9-63 19.3-90.7l106.4 291.4C84.3 420.5 33 344.2 33 256zm223 223c-21.9 0-43-3.2-63-9.1l66.9-194.4 68.5 187.8c.5 1.1 1 2.1 1.6 3.1-23.1 8.1-48 12.6-74 12.6zm30.7-327.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-21.9 0-58.7-2.8-58.7-2.8-12-.7-13.4 17.7-1.4 18.4 0 0 11.4 1.4 23.4 2.1l34.7 95.2L200.6 393l-81.2-241.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-4.2 0-9.1-.1-14.4-.3C109.6 73 178.1 33 256 33c58 0 110.9 22.2 150.6 58.5-1-.1-1.9-.2-2.9-.2-21.9 0-37.4 19.1-37.4 39.6 0 18.4 10.6 33.9 21.9 52.3 8.5 14.8 18.4 33.9 18.4 61.5 0 19.1-7.3 41.2-17 72.1l-22.2 74.3-80.7-239.6zm81.4 297.2l68.1-196.9c12.7-31.8 17-57.2 17-79.9 0-8.2-.5-15.8-1.5-22.9 17.4 31.8 27.3 68.2 27.3 107 0 82.3-44.6 154.1-110.9 192.7z\"],\n    \"wpbeginner\": [512, 512, [], \"f297\", \"M462.799 322.374C519.01 386.682 466.961 480 370.944 480c-39.602 0-78.824-17.687-100.142-50.04-6.887.356-22.702.356-29.59 0C219.848 462.381 180.588 480 141.069 480c-95.49 0-148.348-92.996-91.855-157.626C-29.925 190.523 80.479 32 256.006 32c175.632 0 285.87 158.626 206.793 290.374zm-339.647-82.972h41.529v-58.075h-41.529v58.075zm217.18 86.072v-23.839c-60.506 20.915-132.355 9.198-187.589-33.971l.246 24.897c51.101 46.367 131.746 57.875 187.343 32.913zm-150.753-86.072h166.058v-58.075H189.579v58.075z\"],\n    \"wpexplorer\": [512, 512, [], \"f2de\", \"M512 256c0 141.2-114.7 256-256 256C114.8 512 0 397.3 0 256S114.7 0 256 0s256 114.7 256 256zm-32 0c0-123.2-100.3-224-224-224C132.5 32 32 132.5 32 256s100.5 224 224 224 224-100.5 224-224zM160.9 124.6l86.9 37.1-37.1 86.9-86.9-37.1 37.1-86.9zm110 169.1l46.6 94h-14.6l-50-100-48.9 100h-14l51.1-106.9-22.3-9.4 6-14 68.6 29.1-6 14.3-16.5-7.1zm-11.8-116.3l68.6 29.4-29.4 68.3L230 246l29.1-68.6zm80.3 42.9l54.6 23.1-23.4 54.3-54.3-23.1 23.1-54.3z\"],\n    \"wpforms\": [448, 512, [], \"f298\", \"M448 75.2v361.7c0 24.3-19 43.2-43.2 43.2H43.2C19.3 480 0 461.4 0 436.8V75.2C0 51.1 18.8 32 43.2 32h361.7c24 0 43.1 18.8 43.1 43.2zm-37.3 361.6V75.2c0-3-2.6-5.8-5.8-5.8h-9.3L285.3 144 224 94.1 162.8 144 52.5 69.3h-9.3c-3.2 0-5.8 2.8-5.8 5.8v361.7c0 3 2.6 5.8 5.8 5.8h361.7c3.2.1 5.8-2.7 5.8-5.8zM150.2 186v37H76.7v-37h73.5zm0 74.4v37.3H76.7v-37.3h73.5zm11.1-147.3l54-43.7H96.8l64.5 43.7zm210 72.9v37h-196v-37h196zm0 74.4v37.3h-196v-37.3h196zm-84.6-147.3l64.5-43.7H232.8l53.9 43.7zM371.3 335v37.3h-99.4V335h99.4z\"],\n    \"wpressr\": [496, 512, [], \"f3e4\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm171.33 158.6c-15.18 34.51-30.37 69.02-45.63 103.5-2.44 5.51-6.89 8.24-12.97 8.24-23.02-.01-46.03.06-69.05-.05-5.12-.03-8.25 1.89-10.34 6.72-10.19 23.56-20.63 47-30.95 70.5-1.54 3.51-4.06 5.29-7.92 5.29-45.94-.01-91.87-.02-137.81 0-3.13 0-5.63-1.15-7.72-3.45-11.21-12.33-22.46-24.63-33.68-36.94-2.69-2.95-2.79-6.18-1.21-9.73 8.66-19.54 17.27-39.1 25.89-58.66 12.93-29.35 25.89-58.69 38.75-88.08 1.7-3.88 4.28-5.68 8.54-5.65 14.24.1 28.48.02 42.72.05 6.24.01 9.2 4.84 6.66 10.59-13.6 30.77-27.17 61.55-40.74 92.33-5.72 12.99-11.42 25.99-17.09 39-3.91 8.95 7.08 11.97 10.95 5.6.23-.37-1.42 4.18 30.01-67.69 1.36-3.1 3.41-4.4 6.77-4.39 15.21.08 30.43.02 45.64.04 5.56.01 7.91 3.64 5.66 8.75-8.33 18.96-16.71 37.9-24.98 56.89-4.98 11.43 8.08 12.49 11.28 5.33.04-.08 27.89-63.33 32.19-73.16 2.02-4.61 5.44-6.51 10.35-6.5 26.43.05 52.86 0 79.29.05 12.44.02 13.93-13.65 3.9-13.64-25.26.03-50.52.02-75.78.02-6.27 0-7.84-2.47-5.27-8.27 5.78-13.06 11.59-26.11 17.3-39.21 1.73-3.96 4.52-5.79 8.84-5.78 23.09.06 25.98.02 130.78.03 6.08-.01 8.03 2.79 5.62 8.27z\"],\n    \"xbox\": [512, 512, [], \"f412\", \"M369.9 318.2c44.3 54.3 64.7 98.8 54.4 118.7-7.9 15.1-56.7 44.6-92.6 55.9-29.6 9.3-68.4 13.3-100.4 10.2-38.2-3.7-76.9-17.4-110.1-39C93.3 445.8 87 438.3 87 423.4c0-29.9 32.9-82.3 89.2-142.1 32-33.9 76.5-73.7 81.4-72.6 9.4 2.1 84.3 75.1 112.3 109.5zM188.6 143.8c-29.7-26.9-58.1-53.9-86.4-63.4-15.2-5.1-16.3-4.8-28.7 8.1-29.2 30.4-53.5 79.7-60.3 122.4-5.4 34.2-6.1 43.8-4.2 60.5 5.6 50.5 17.3 85.4 40.5 120.9 9.5 14.6 12.1 17.3 9.3 9.9-4.2-11-.3-37.5 9.5-64 14.3-39 53.9-112.9 120.3-194.4zm311.6 63.5C483.3 127.3 432.7 77 425.6 77c-7.3 0-24.2 6.5-36 13.9-23.3 14.5-41 31.4-64.3 52.8C367.7 197 427.5 283.1 448.2 346c6.8 20.7 9.7 41.1 7.4 52.3-1.7 8.5-1.7 8.5 1.4 4.6 6.1-7.7 19.9-31.3 25.4-43.5 7.4-16.2 15-40.2 18.6-58.7 4.3-22.5 3.9-70.8-.8-93.4zM141.3 43C189 40.5 251 77.5 255.6 78.4c.7.1 10.4-4.2 21.6-9.7 63.9-31.1 94-25.8 107.4-25.2-63.9-39.3-152.7-50-233.9-11.7-23.4 11.1-24 11.9-9.4 11.2z\"],\n    \"xing\": [384, 512, [], \"f168\", \"M162.7 210c-1.8 3.3-25.2 44.4-70.1 123.5-4.9 8.3-10.8 12.5-17.7 12.5H9.8c-7.7 0-12.1-7.5-8.5-14.4l69-121.3c.2 0 .2-.1 0-.3l-43.9-75.6c-4.3-7.8.3-14.1 8.5-14.1H100c7.3 0 13.3 4.1 18 12.2l44.7 77.5zM382.6 46.1l-144 253v.3L330.2 466c3.9 7.1.2 14.1-8.5 14.1h-65.2c-7.6 0-13.6-4-18-12.2l-92.4-168.5c3.3-5.8 51.5-90.8 144.8-255.2 4.6-8.1 10.4-12.2 17.5-12.2h65.7c8 0 12.3 6.7 8.5 14.1z\"],\n    \"xing-square\": [448, 512, [], \"f169\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM140.4 320.2H93.8c-5.5 0-8.7-5.3-6-10.3l49.3-86.7c.1 0 .1-.1 0-.2l-31.4-54c-3-5.6.2-10.1 6-10.1h46.6c5.2 0 9.5 2.9 12.9 8.7l31.9 55.3c-1.3 2.3-18 31.7-50.1 88.2-3.5 6.2-7.7 9.1-12.6 9.1zm219.7-214.1L257.3 286.8v.2l65.5 119c2.8 5.1.1 10.1-6 10.1h-46.6c-5.5 0-9.7-2.9-12.9-8.7l-66-120.3c2.3-4.1 36.8-64.9 103.4-182.3 3.3-5.8 7.4-8.7 12.5-8.7h46.9c5.7-.1 8.8 4.7 6 10z\"],\n    \"y-combinator\": [448, 512, [], \"f23b\", \"M448 32v448H0V32h448zM236 287.5L313.5 142h-32.7L235 233c-4.7 9.3-9 18.3-12.8 26.8L210 233l-45.2-91h-35l76.7 143.8v94.5H236v-92.8z\"],\n    \"yahoo\": [448, 512, [], \"f19e\", \"M252 292l4 220c-12.7-2.2-23.5-3.9-32.3-3.9-8.4 0-19.2 1.7-32.3 3.9l4-220C140.4 197.2 85 95.2 21.4 0c11.9 3.1 23 3.9 33.2 3.9 9 0 20.4-.8 34.1-3.9 40.9 72.2 82.1 138.7 135 225.5C261 163.9 314.8 81.4 358.6 0c11.1 2.9 22 3.9 32.9 3.9 11.5 0 23.2-1 35-3.9C392.1 47.9 294.9 216.9 252 292z\"],\n    \"yammer\": [512, 512, [], \"f840\", \"M421.78 152.17A23.06 23.06 0 0 0 400.9 112c-.83.43-1.71.9-2.63 1.4-15.25 8.4-118.33 80.62-106.69 88.77s82.04-23.61 130.2-50zm0 217.17c-48.16-26.38-118.64-58.1-130.2-50s91.42 80.35 106.69 88.74c.92.51 1.8 1 2.63 1.41a23.07 23.07 0 0 0 20.88-40.15zM464.21 237c-.95 0-1.95-.06-3-.06-17.4 0-142.52 13.76-136.24 26.51s83.3 18.74 138.21 18.76a23 23 0 0 0 1-45.21zM31 96.65a24.88 24.88 0 0 1 46.14-18.4l81 205.06h1.21l77-203.53a23.52 23.52 0 0 1 44.45 15.27L171.2 368.44C152.65 415.66 134.08 448 77.91 448a139.67 139.67 0 0 1-23.81-1.95 21.31 21.31 0 0 1 6.9-41.77c.66.06 10.91.66 13.86.66 30.47 0 43.74-18.94 58.07-59.41z\"],\n    \"yandex\": [256, 512, [], \"f413\", \"M153.1 315.8L65.7 512H2l96-209.8c-45.1-22.9-75.2-64.4-75.2-141.1C22.7 53.7 90.8 0 171.7 0H254v512h-55.1V315.8h-45.8zm45.8-269.3h-29.4c-44.4 0-87.4 29.4-87.4 114.6 0 82.3 39.4 108.8 87.4 108.8h29.4V46.5z\"],\n    \"yandex-international\": [320, 512, [], \"f414\", \"M129.5 512V345.9L18.5 48h55.8l81.8 229.7L250.2 0h51.3L180.8 347.8V512h-51.3z\"],\n    \"yarn\": [496, 512, [], \"f7e3\", \"M393.9 345.2c-39 9.3-48.4 32.1-104 47.4 0 0-2.7 4-10.4 5.8-13.4 3.3-63.9 6-68.5 6.1-12.4.1-19.9-3.2-22-8.2-6.4-15.3 9.2-22 9.2-22-8.1-5-9-9.9-9.8-8.1-2.4 5.8-3.6 20.1-10.1 26.5-8.8 8.9-25.5 5.9-35.3.8-10.8-5.7.8-19.2.8-19.2s-5.8 3.4-10.5-3.6c-6-9.3-17.1-37.3 11.5-62-1.3-10.1-4.6-53.7 40.6-85.6 0 0-20.6-22.8-12.9-43.3 5-13.4 7-13.3 8.6-13.9 5.7-2.2 11.3-4.6 15.4-9.1 20.6-22.2 46.8-18 46.8-18s12.4-37.8 23.9-30.4c3.5 2.3 16.3 30.6 16.3 30.6s13.6-7.9 15.1-5c8.2 16 9.2 46.5 5.6 65.1-6.1 30.6-21.4 47.1-27.6 57.5-1.4 2.4 16.5 10 27.8 41.3 10.4 28.6 1.1 52.7 2.8 55.3.8 1.4 13.7.8 36.4-13.2 12.8-7.9 28.1-16.9 45.4-17 16.7-.5 17.6 19.2 4.9 22.2zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-79.3 75.2c-1.7-13.6-13.2-23-28-22.8-22 .3-40.5 11.7-52.8 19.2-4.8 3-8.9 5.2-12.4 6.8 3.1-44.5-22.5-73.1-28.7-79.4 7.8-11.3 18.4-27.8 23.4-53.2 4.3-21.7 3-55.5-6.9-74.5-1.6-3.1-7.4-11.2-21-7.4-9.7-20-13-22.1-15.6-23.8-1.1-.7-23.6-16.4-41.4 28-12.2.9-31.3 5.3-47.5 22.8-2 2.2-5.9 3.8-10.1 5.4h.1c-8.4 3-12.3 9.9-16.9 22.3-6.5 17.4.2 34.6 6.8 45.7-17.8 15.9-37 39.8-35.7 82.5-34 36-11.8 73-5.6 79.6-1.6 11.1 3.7 19.4 12 23.8 12.6 6.7 30.3 9.6 43.9 2.8 4.9 5.2 13.8 10.1 30 10.1 6.8 0 58-2.9 72.6-6.5 6.8-1.6 11.5-4.5 14.6-7.1 9.8-3.1 36.8-12.3 62.2-28.7 18-11.7 24.2-14.2 37.6-17.4 12.9-3.2 21-15.1 19.4-28.2z\"],\n    \"yelp\": [384, 512, [], \"f1e9\", \"M42.9 240.32l99.62 48.61c19.2 9.4 16.2 37.51-4.5 42.71L30.5 358.45a22.79 22.79 0 0 1-28.21-19.6 197.16 197.16 0 0 1 9-85.32 22.8 22.8 0 0 1 31.61-13.21zm44 239.25a199.45 199.45 0 0 0 79.42 32.11A22.78 22.78 0 0 0 192.94 490l3.9-110.82c.7-21.3-25.5-31.91-39.81-16.1l-74.21 82.4a22.82 22.82 0 0 0 4.09 34.09zm145.34-109.92l58.81 94a22.93 22.93 0 0 0 34 5.5 198.36 198.36 0 0 0 52.71-67.61A23 23 0 0 0 364.17 370l-105.42-34.26c-20.31-6.5-37.81 15.8-26.51 33.91zm148.33-132.23a197.44 197.44 0 0 0-50.41-69.31 22.85 22.85 0 0 0-34 4.4l-62 91.92c-11.9 17.7 4.7 40.61 25.2 34.71L366 268.63a23 23 0 0 0 14.61-31.21zM62.11 30.18a22.86 22.86 0 0 0-9.9 32l104.12 180.44c11.7 20.2 42.61 11.9 42.61-11.4V22.88a22.67 22.67 0 0 0-24.5-22.8 320.37 320.37 0 0 0-112.33 30.1z\"],\n    \"yoast\": [448, 512, [], \"f2b1\", \"M91.3 76h186l-7 18.9h-179c-39.7 0-71.9 31.6-71.9 70.3v205.4c0 35.4 24.9 70.3 84 70.3V460H91.3C41.2 460 0 419.8 0 370.5V165.2C0 115.9 40.7 76 91.3 76zm229.1-56h66.5C243.1 398.1 241.2 418.9 202.2 459.3c-20.8 21.6-49.3 31.7-78.3 32.7v-51.1c49.2-7.7 64.6-49.9 64.6-75.3 0-20.1.6-12.6-82.1-223.2h61.4L218.2 299 320.4 20zM448 161.5V460H234c6.6-9.6 10.7-16.3 12.1-19.4h182.5V161.5c0-32.5-17.1-51.9-48.2-62.9l6.7-17.6c41.7 13.6 60.9 43.1 60.9 80.5z\"],\n    \"youtube\": [576, 512, [], \"f167\", \"M549.655 124.083c-6.281-23.65-24.787-42.276-48.284-48.597C458.781 64 288 64 288 64S117.22 64 74.629 75.486c-23.497 6.322-42.003 24.947-48.284 48.597-11.412 42.867-11.412 132.305-11.412 132.305s0 89.438 11.412 132.305c6.281 23.65 24.787 41.5 48.284 47.821C117.22 448 288 448 288 448s170.78 0 213.371-11.486c23.497-6.321 42.003-24.171 48.284-47.821 11.412-42.867 11.412-132.305 11.412-132.305s0-89.438-11.412-132.305zm-317.51 213.508V175.185l142.739 81.205-142.739 81.201z\"],\n    \"youtube-square\": [448, 512, [], \"f431\", \"M186.8 202.1l95.2 54.1-95.2 54.1V202.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-42 176.3s0-59.6-7.6-88.2c-4.2-15.8-16.5-28.2-32.2-32.4C337.9 128 224 128 224 128s-113.9 0-142.2 7.7c-15.7 4.2-28 16.6-32.2 32.4-7.6 28.5-7.6 88.2-7.6 88.2s0 59.6 7.6 88.2c4.2 15.8 16.5 27.7 32.2 31.9C110.1 384 224 384 224 384s113.9 0 142.2-7.7c15.7-4.2 28-16.1 32.2-31.9 7.6-28.5 7.6-88.1 7.6-88.1z\"],\n    \"zhihu\": [640, 512, [], \"f63f\", \"M170.54 148.13v217.54l23.43.01 7.71 26.37 42.01-26.37h49.53V148.13H170.54zm97.75 193.93h-27.94l-27.9 17.51-5.08-17.47-11.9-.04V171.75h72.82v170.31zm-118.46-94.39H97.5c1.74-27.1 2.2-51.59 2.2-73.46h51.16s1.97-22.56-8.58-22.31h-88.5c3.49-13.12 7.87-26.66 13.12-40.67 0 0-24.07 0-32.27 21.57-3.39 8.9-13.21 43.14-30.7 78.12 5.89-.64 25.37-1.18 36.84-22.21 2.11-5.89 2.51-6.66 5.14-14.53h28.87c0 10.5-1.2 66.88-1.68 73.44H20.83c-11.74 0-15.56 23.62-15.56 23.62h65.58C66.45 321.1 42.83 363.12 0 396.34c20.49 5.85 40.91-.93 51-9.9 0 0 22.98-20.9 35.59-69.25l53.96 64.94s7.91-26.89-1.24-39.99c-7.58-8.92-28.06-33.06-36.79-41.81L87.9 311.95c4.36-13.98 6.99-27.55 7.87-40.67h61.65s-.09-23.62-7.59-23.62v.01zm412.02-1.6c20.83-25.64 44.98-58.57 44.98-58.57s-18.65-14.8-27.38-4.06c-6 8.15-36.83 48.2-36.83 48.2l19.23 14.43zm-150.09-59.09c-9.01-8.25-25.91 2.13-25.91 2.13s39.52 55.04 41.12 57.45l19.46-13.73s-25.67-37.61-34.66-45.86h-.01zM640 258.35c-19.78 0-130.91.93-131.06.93v-101c4.81 0 12.42-.4 22.85-1.2 40.88-2.41 70.13-4 87.77-4.81 0 0 12.22-27.19-.59-33.44-3.07-1.18-23.17 4.58-23.17 4.58s-165.22 16.49-232.36 18.05c1.6 8.82 7.62 17.08 15.78 19.55 13.31 3.48 22.69 1.7 49.15.89 24.83-1.6 43.68-2.43 56.51-2.43v99.81H351.41s2.82 22.31 25.51 22.85h107.94v70.92c0 13.97-11.19 21.99-24.48 21.12-14.08.11-26.08-1.15-41.69-1.81 1.99 3.97 6.33 14.39 19.31 21.84 9.88 4.81 16.17 6.57 26.02 6.57 29.56 0 45.67-17.28 44.89-45.31v-73.32h122.36c9.68 0 8.7-23.78 8.7-23.78l.03-.01z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fab', icons);\n  });\n\n}());\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-68 304H48V48h320v416zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H48V80h480v352zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2zM360 320h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-144c-33.6 0-65.2 14.8-86.8 40.6-8.5 10.2-7.1 25.3 3.1 33.8s25.3 7.2 33.8-3c24.8-29.7 75-29.7 99.8 0 8.1 9.7 23.2 11.9 33.8 3 10.2-8.5 11.5-23.6 3.1-33.8-21.6-25.8-53.2-40.6-86.8-40.6zm-48-72c10.3 0 19.9-6.7 23-17.1 3.8-12.7-3.4-26.1-16.1-29.9l-80-24c-12.8-3.9-26.1 3.4-29.9 16.1-3.8 12.7 3.4 26.1 16.1 29.9l28.2 8.5c-3.1 4.9-5.3 10.4-5.3 16.6 0 17.7 14.3 32 32 32s32-14.4 32-32.1zm199-54.9c-3.8-12.7-17.1-19.9-29.9-16.1l-80 24c-12.7 3.8-19.9 17.2-16.1 29.9 3.1 10.4 12.7 17.1 23 17.1 0 17.7 14.3 32 32 32s32-14.3 32-32c0-6.2-2.2-11.7-5.3-16.6l28.2-8.5c12.7-3.7 19.9-17.1 16.1-29.8z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm-32-316v116h-67c-10.7 0-16 12.9-8.5 20.5l99 99c4.7 4.7 12.3 4.7 17 0l99-99c7.6-7.6 2.2-20.5-8.5-20.5h-67V140c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M8 256c0 137 111 248 248 248s248-111 248-248S393 8 256 8 8 119 8 256zm448 0c0 110.5-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56s200 89.5 200 200zm-72-20v40c0 6.6-5.4 12-12 12H256v67c0 10.7-12.9 16-20.5 8.5l-99-99c-4.7-4.7-4.7-12.3 0-17l99-99c7.6-7.6 20.5-2.2 20.5 8.5v67h116c6.6 0 12 5.4 12 12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm72 20v-40c0-6.6 5.4-12 12-12h116v-67c0-10.7 12.9-16 20.5-8.5l99 99c4.7 4.7 4.7 12.3 0 17l-99 99c-7.6 7.6-20.5 2.2-20.5-8.5v-67H140c-6.6 0-12-5.4-12-12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M256 504c137 0 248-111 248-248S393 8 256 8 8 119 8 256s111 248 248 248zm0-448c110.5 0 200 89.5 200 200s-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56zm20 328h-40c-6.6 0-12-5.4-12-12V256h-67c-10.7 0-16-12.9-8.5-20.5l99-99c4.7-4.7 12.3-4.7 17 0l99 99c7.6 7.6 2.2 20.5-8.5 20.5h-67v116c0 6.6-5.4 12-12 12z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M439.39 362.29c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71zM67.53 368c21.22-27.97 44.42-74.33 44.53-159.42 0-.2-.06-.38-.06-.58 0-61.86 50.14-112 112-112s112 50.14 112 112c0 .2-.06.38-.06.58.11 85.1 23.31 131.46 44.53 159.42H67.53zM224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.99 471.02L36 3.51C29.1-2.01 19.03-.9 13.51 6l-10 12.49C-2.02 25.39-.9 35.46 6 40.98l598 467.51c6.9 5.52 16.96 4.4 22.49-2.49l10-12.49c5.52-6.9 4.41-16.97-2.5-22.49zM163.53 368c16.71-22.03 34.48-55.8 41.4-110.58l-45.47-35.55c-3.27 90.73-36.47 120.68-54.84 140.42-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h279.66l-61.4-48H163.53zM320 96c61.86 0 112 50.14 112 112 0 .2-.06.38-.06.58.02 16.84 1.16 31.77 2.79 45.73l59.53 46.54c-8.31-22.13-14.34-51.49-14.34-92.85 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-26.02 5.41-49.45 16.94-69.13 32.72l38.17 29.84C275 103.18 296.65 96 320 96zm0 416c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M336 0H48C21.49 0 0 21.49 0 48v464l192-112 192 112V48c0-26.51-21.49-48-48-48zm0 428.43l-144-84-144 84V54a6 6 0 0 1 6-6h276c3.314 0 6 2.683 6 5.996V428.43z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M128 148v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12zm140 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-128 96h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm128 0h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-76 84v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm76 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm180 124v36H0v-36c0-6.6 5.4-12 12-12h19.5V24c0-13.3 10.7-24 24-24h337c13.3 0 24 10.7 24 24v440H436c6.6 0 12 5.4 12 12zM79.5 463H192v-67c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v67h112.5V49L80 48l-.5 415z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M400 64h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V160h352v298c0 3.3-2.7 6-6 6z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M148 288h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm108-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 96v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96-260v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M400 64h-48V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H160V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V160h352v298a6 6 0 0 1-6 6zm-52.849-200.65L198.842 404.519c-4.705 4.667-12.303 4.637-16.971-.068l-75.091-75.699c-4.667-4.705-4.637-12.303.068-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l44.104 44.461 111.072-110.181c4.705-4.667 12.303-4.637 16.971.068l22.536 22.718c4.667 4.705 4.636 12.303-.069 16.97z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M124 328c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v24c0 6.6-5.4 12-12 12H124zm324-216v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M336 292v24c0 6.6-5.4 12-12 12h-76v76c0 6.6-5.4 12-12 12h-24c-6.6 0-12-5.4-12-12v-76h-76c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h76v-76c0-6.6 5.4-12 12-12h24c6.6 0 12 5.4 12 12v76h76c6.6 0 12 5.4 12 12zm112-180v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M311.7 374.7l-17 17c-4.7 4.7-12.3 4.7-17 0L224 337.9l-53.7 53.7c-4.7 4.7-12.3 4.7-17 0l-17-17c-4.7-4.7-4.7-12.3 0-17l53.7-53.7-53.7-53.7c-4.7-4.7-4.7-12.3 0-17l17-17c4.7-4.7 12.3-4.7 17 0l53.7 53.7 53.7-53.7c4.7-4.7 12.3-4.7 17 0l17 17c4.7 4.7 4.7 12.3 0 17L257.9 304l53.7 53.7c4.8 4.7 4.8 12.3.1 17zM448 112v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M125.1 208h197.8c10.7 0 16.1 13 8.5 20.5l-98.9 98.3c-4.7 4.7-12.2 4.7-16.9 0l-98.9-98.3c-7.7-7.5-2.3-20.5 8.4-20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M272 157.1v197.8c0 10.7-13 16.1-20.5 8.5l-98.3-98.9c-4.7-4.7-4.7-12.2 0-16.9l98.3-98.9c7.5-7.7 20.5-2.3 20.5 8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M176 354.9V157.1c0-10.7 13-16.1 20.5-8.5l98.3 98.9c4.7 4.7 4.7 12.2 0 16.9l-98.3 98.9c-7.5 7.7-20.5 2.3-20.5-8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M322.9 304H125.1c-10.7 0-16.1-13-8.5-20.5l98.9-98.3c4.7-4.7 12.2-4.7 16.9 0l98.9 98.3c7.7 7.5 2.3 20.5-8.4 20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M396.8 352h22.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-192 0h22.4c6.4 0 12.8-6.4 12.8-12.8V140.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h22.4c6.4 0 12.8-6.4 12.8-12.8V204.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zM496 400H48V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16zm-387.2-48h22.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 48c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m140.204 130.267l-22.536-22.718c-4.667-4.705-12.265-4.736-16.97-.068L215.346 303.697l-59.792-60.277c-4.667-4.705-12.265-4.736-16.97-.069l-22.719 22.536c-4.705 4.667-4.736 12.265-.068 16.971l90.781 91.516c4.667 4.705 12.265 4.736 16.97.068l172.589-171.204c4.704-4.668 4.734-12.266.067-16.971z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm0 400H48V80h352v352zm-35.864-241.724L191.547 361.48c-4.705 4.667-12.303 4.637-16.97-.068l-90.781-91.516c-4.667-4.705-4.637-12.303.069-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l59.792 60.277 141.352-140.216c4.705-4.667 12.303-4.637 16.97.068l22.536 22.718c4.667 4.706 4.637 12.304-.068 16.971z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm144 418c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h42v36c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-36h42c3.3 0 6 2.7 6 6z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm61.8-104.4l-84.9-61.7c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v141.7l66.8 48.6c5.4 3.9 6.5 11.4 2.6 16.8L334.6 349c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0H144c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h320c26.51 0 48-21.49 48-48v-48h48c26.51 0 48-21.49 48-48V48c0-26.51-21.49-48-48-48zM362 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h42v224c0 26.51 21.49 48 48 48h224v42a6 6 0 0 1-6 6zm96-96H150a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h308a6 6 0 0 1 6 6v308a6 6 0 0 1-6 6z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 336H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v276c0 3.3-2.7 6-6 6zm-211.1-85.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7zm190.4 0c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.9-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 220.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 7.1 5.8 12 12 12 2.4 0 4.9-.7 7.1-2.4L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zm16 352c0 8.8-7.2 16-16 16H288l-12.8 9.6L208 428v-60H64c-8.8 0-16-7.2-16-16V64c0-8.8 7.2-16 16-16h384c8.8 0 16 7.2 16 16v288z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M144 208c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zM256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M532 386.2c27.5-27.1 44-61.1 44-98.2 0-80-76.5-146.1-176.2-157.9C368.3 72.5 294.3 32 208 32 93.1 32 0 103.6 0 192c0 37 16.5 71 44 98.2-15.3 30.7-37.3 54.5-37.7 54.9-6.3 6.7-8.1 16.5-4.4 25 3.6 8.5 12 14 21.2 14 53.5 0 96.7-20.2 125.2-38.8 9.2 2.1 18.7 3.7 28.4 4.9C208.1 407.6 281.8 448 368 448c20.8 0 40.8-2.4 59.8-6.8C456.3 459.7 499.4 480 553 480c9.2 0 17.5-5.5 21.2-14 3.6-8.5 1.9-18.3-4.4-25-.4-.3-22.5-24.1-37.8-54.8zm-392.8-92.3L122.1 305c-14.1 9.1-28.5 16.3-43.1 21.4 2.7-4.7 5.4-9.7 8-14.8l15.5-31.1L77.7 256C64.2 242.6 48 220.7 48 192c0-60.7 73.3-112 160-112s160 51.3 160 112-73.3 112-160 112c-16.5 0-33-1.9-49-5.6l-19.8-4.5zM498.3 352l-24.7 24.4 15.5 31.1c2.6 5.1 5.3 10.1 8 14.8-14.6-5.1-29-12.3-43.1-21.4l-17.1-11.1-19.9 4.6c-16 3.7-32.5 5.6-49 5.6-54 0-102.2-20.1-131.3-49.7C338 339.5 416 272.9 416 192c0-3.4-.4-6.7-.7-10C479.7 196.5 528 238.8 528 288c0 28.7-16.2 50.6-29.7 64z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M347.94 129.86L203.6 195.83a31.938 31.938 0 0 0-15.77 15.77l-65.97 144.34c-7.61 16.65 9.54 33.81 26.2 26.2l144.34-65.97a31.938 31.938 0 0 0 15.77-15.77l65.97-144.34c7.61-16.66-9.54-33.81-26.2-26.2zm-77.36 148.72c-12.47 12.47-32.69 12.47-45.16 0-12.47-12.47-12.47-32.69 0-45.16 12.47-12.47 32.69-12.47 45.16 0 12.47 12.47 12.47 32.69 0 45.16zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M433.941 65.941l-51.882-51.882A48 48 0 0 0 348.118 0H176c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48v-48h80c26.51 0 48-21.49 48-48V99.882a48 48 0 0 0-14.059-33.941zM266 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h74v224c0 26.51 21.49 48 48 48h96v42a6 6 0 0 1-6 6zm128-96H182a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h106v88c0 13.255 10.745 24 24 24h88v202a6 6 0 0 1-6 6zm6-256h-64V48h9.632c1.591 0 3.117.632 4.243 1.757l48.368 48.368a6 6 0 0 1 1.757 4.243V112z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm107.351-101.064c-9.614 9.712-45.53 41.396-104.065 41.396-82.43 0-140.484-61.425-140.484-141.567 0-79.152 60.275-139.401 139.762-139.401 55.531 0 88.738 26.62 97.593 34.779a11.965 11.965 0 0 1 1.936 15.322l-18.155 28.113c-3.841 5.95-11.966 7.282-17.499 2.921-8.595-6.776-31.814-22.538-61.708-22.538-48.303 0-77.916 35.33-77.916 80.082 0 41.589 26.888 83.692 78.277 83.692 32.657 0 56.843-19.039 65.726-27.225 5.27-4.857 13.596-4.039 17.82 1.738l19.865 27.17a11.947 11.947 0 0 1-1.152 15.518z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M527.9 32H48.1C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48.1 48h479.8c26.6 0 48.1-21.5 48.1-48V80c0-26.5-21.5-48-48.1-48zM54.1 80h467.8c3.3 0 6 2.7 6 6v42H48.1V86c0-3.3 2.7-6 6-6zm467.8 352H54.1c-3.3 0-6-2.7-6-6V256h479.8v170c0 3.3-2.7 6-6 6zM192 332v40c0 6.6-5.4 12-12 12h-72c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12zm192 0v40c0 6.6-5.4 12-12 12H236c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-33.8-217.9c7.8-7.8 7.8-20.5 0-28.3L196.3 192l17.9-17.9c7.8-7.8 7.8-20.5 0-28.3-7.8-7.8-20.5-7.8-28.3 0L168 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.9 7.7 20.5 7.7 28.4-.2zm160-92.2c-7.8-7.8-20.5-7.8-28.3 0L328 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.8 7.8 20.5 7.8 28.3 0 7.8-7.8 7.8-20.5 0-28.3l-17.8-18 17.9-17.9c7.7-7.8 7.7-20.4 0-28.2zM248 272c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 56c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m0-48C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 168c-44.183 0-80 35.817-80 80s35.817 80 80 80 80-35.817 80-80-35.817-80-80-80z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.3 344.9l32-32c5-5 13.7-1.5 13.7 5.7V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h273.5c7.1 0 10.7 8.6 5.7 13.7l-32 32c-1.5 1.5-3.5 2.3-5.7 2.3H48v352h352V350.5c0-2.1.8-4.1 2.3-5.6zm156.6-201.8L296.3 405.7l-90.4 10c-26.2 2.9-48.5-19.2-45.6-45.6l10-90.4L432.9 17.1c22.9-22.9 59.9-22.9 82.7 0l43.2 43.2c22.9 22.9 22.9 60 .1 82.8zM460.1 174L402 115.9 216.2 301.8l-7.3 65.3 65.3-7.3L460.1 174zm64.8-79.7l-43.2-43.2c-4.1-4.1-10.8-4.1-14.8 0L436 82l58.1 58.1 30.9-30.9c4-4.2 4-10.8-.1-14.9z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm0 48v40.805c-22.422 18.259-58.168 46.651-134.587 106.49-16.841 13.247-50.201 45.072-73.413 44.701-23.208.375-56.579-31.459-73.413-44.701C106.18 199.465 70.425 171.067 48 152.805V112h416zM48 400V214.398c22.914 18.251 55.409 43.862 104.938 82.646 21.857 17.205 60.134 55.186 103.062 54.955 42.717.231 80.509-37.199 103.053-54.947 49.528-38.783 82.032-64.401 104.947-82.653V400H48z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M494.586 164.516c-4.697-3.883-111.723-89.95-135.251-108.657C337.231 38.191 299.437 0 256 0c-43.205 0-80.636 37.717-103.335 55.859-24.463 19.45-131.07 105.195-135.15 108.549A48.004 48.004 0 0 0 0 201.485V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V201.509a48 48 0 0 0-17.414-36.993zM464 458a6 6 0 0 1-6 6H54a6 6 0 0 1-6-6V204.347c0-1.813.816-3.526 2.226-4.665 15.87-12.814 108.793-87.554 132.364-106.293C200.755 78.88 232.398 48 256 48c23.693 0 55.857 31.369 73.41 45.389 23.573 18.741 116.503 93.493 132.366 106.316a5.99 5.99 0 0 1 2.224 4.663V458zm-31.991-187.704c4.249 5.159 3.465 12.795-1.745 16.981-28.975 23.283-59.274 47.597-70.929 56.863C336.636 362.283 299.205 400 256 400c-43.452 0-81.287-38.237-103.335-55.86-11.279-8.967-41.744-33.413-70.927-56.865-5.21-4.187-5.993-11.822-1.745-16.981l15.258-18.528c4.178-5.073 11.657-5.843 16.779-1.726 28.618 23.001 58.566 47.035 70.56 56.571C200.143 320.631 232.307 352 256 352c23.602 0 55.246-30.88 73.41-45.389 11.994-9.535 41.944-33.57 70.563-56.568 5.122-4.116 12.601-3.346 16.778 1.727l15.258 18.526z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M288 144a110.94 110.94 0 0 0-31.24 5 55.4 55.4 0 0 1 7.24 27 56 56 0 0 1-56 56 55.4 55.4 0 0 1-27-7.24A111.71 111.71 0 1 0 288 144zm284.52 97.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400c-98.65 0-189.09-55-237.93-144C98.91 167 189.34 112 288 112s189.09 55 237.93 144C477.1 345 386.66 400 288 400z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M634 471L36 3.51A16 16 0 0 0 13.51 6l-10 12.49A16 16 0 0 0 6 41l598 467.49a16 16 0 0 0 22.49-2.49l10-12.49A16 16 0 0 0 634 471zM296.79 146.47l134.79 105.38C429.36 191.91 380.48 144 320 144a112.26 112.26 0 0 0-23.21 2.47zm46.42 219.07L208.42 260.16C210.65 320.09 259.53 368 320 368a113 113 0 0 0 23.21-2.46zM320 112c98.65 0 189.09 55 237.93 144a285.53 285.53 0 0 1-44 60.2l37.74 29.5a333.7 333.7 0 0 0 52.9-75.11 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64c-36.7 0-71.71 7-104.63 18.81l46.41 36.29c18.94-4.3 38.34-7.1 58.22-7.1zm0 288c-98.65 0-189.08-55-237.93-144a285.47 285.47 0 0 1 44.05-60.19l-37.74-29.5a333.6 333.6 0 0 0-52.89 75.1 32.35 32.35 0 0 0 0 29.19C89.72 376.41 197.08 448 320 448c36.7 0 71.71-7.05 104.63-18.81l-46.41-36.28C359.28 397.2 339.89 400 320 400z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M288 248v28c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-28c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm-12 72H108c-6.6 0-12 5.4-12 12v28c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-28c0-6.6-5.4-12-12-12zm108-188.1V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V48C0 21.5 21.5 0 48 0h204.1C264.8 0 277 5.1 286 14.1L369.9 98c9 8.9 14.1 21.2 14.1 33.9zm-128-80V128h76.1L256 51.9zM336 464V176H232c-13.3 0-24-10.7-24-24V48H48v416h288z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M128.3 160v32h32v-32zm64-96h-32v32h32zm-64 32v32h32V96zm64 32h-32v32h32zm177.6-30.1L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h79.7v16h32V48H208v104c0 13.3 10.7 24 24 24h104zM194.2 265.7c-1.1-5.6-6-9.7-11.8-9.7h-22.1v-32h-32v32l-19.7 97.1C102 385.6 126.8 416 160 416c33.1 0 57.9-30.2 51.5-62.6zm-33.9 124.4c-17.9 0-32.4-12.1-32.4-27s14.5-27 32.4-27 32.4 12.1 32.4 27-14.5 27-32.4 27zm32-198.1h-32v32h32z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm144-76.024c0 10.691-12.926 16.045-20.485 8.485L136 360.486h-28c-6.627 0-12-5.373-12-12v-56c0-6.627 5.373-12 12-12h28l35.515-36.947c7.56-7.56 20.485-2.206 20.485 8.485v135.952zm41.201-47.13c9.051-9.297 9.06-24.133.001-33.439-22.149-22.752 12.235-56.246 34.395-33.481 27.198 27.94 27.212 72.444.001 100.401-21.793 22.386-56.947-10.315-34.397-33.481z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M149.9 349.1l-.2-.2-32.8-28.9 32.8-28.9c3.6-3.2 4-8.8.8-12.4l-.2-.2-17.4-18.6c-3.4-3.6-9-3.7-12.4-.4l-57.7 54.1c-3.7 3.5-3.7 9.4 0 12.8l57.7 54.1c1.6 1.5 3.8 2.4 6 2.4 2.4 0 4.8-1 6.4-2.8l17.4-18.6c3.3-3.5 3.1-9.1-.4-12.4zm220-251.2L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h160v104c0 13.3 10.7 24 24 24h104zM209.6 214c-4.7-1.4-9.5 1.3-10.9 6L144 408.1c-1.4 4.7 1.3 9.6 6 10.9l24.4 7.1c4.7 1.4 9.6-1.4 10.9-6L240 231.9c1.4-4.7-1.3-9.6-6-10.9zm24.5 76.9l.2.2 32.8 28.9-32.8 28.9c-3.6 3.2-4 8.8-.8 12.4l.2.2 17.4 18.6c3.3 3.5 8.9 3.7 12.4.4l57.7-54.1c3.7-3.5 3.7-9.4 0-12.8l-57.7-54.1c-3.5-3.3-9.1-3.2-12.4.4l-17.4 18.6c-3.3 3.5-3.1 9.1.4 12.4z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm212-240h-28.8c-4.4 0-8.4 2.4-10.5 6.3-18 33.1-22.2 42.4-28.6 57.7-13.9-29.1-6.9-17.3-28.6-57.7-2.1-3.9-6.2-6.3-10.6-6.3H124c-9.3 0-15 10-10.4 18l46.3 78-46.3 78c-4.7 8 1.1 18 10.4 18h28.9c4.4 0 8.4-2.4 10.5-6.3 21.7-40 23-45 28.6-57.7 14.9 30.2 5.9 15.9 28.6 57.7 2.1 3.9 6.2 6.3 10.6 6.3H260c9.3 0 15-10 10.4-18L224 320c.7-1.1 30.3-50.5 46.3-78 4.7-8-1.1-18-10.3-18z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm32-48h224V288l-23.5-23.5c-4.7-4.7-12.3-4.7-17 0L176 352l-39.5-39.5c-4.7-4.7-12.3-4.7-17 0L80 352v64zm48-240c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm250.2-143.7c-12.2-12-47-8.7-64.4-6.5-17.2-10.5-28.7-25-36.8-46.3 3.9-16.1 10.1-40.6 5.4-56-4.2-26.2-37.8-23.6-42.6-5.9-4.4 16.1-.4 38.5 7 67.1-10 23.9-24.9 56-35.4 74.4-20 10.3-47 26.2-51 46.2-3.3 15.8 26 55.2 76.1-31.2 22.4-7.4 46.8-16.5 68.4-20.1 18.9 10.2 41 17 55.8 17 25.5 0 28-28.2 17.5-38.7zm-198.1 77.8c5.1-13.7 24.5-29.5 30.4-35-19 30.3-30.4 35.7-30.4 35zm81.6-190.6c7.4 0 6.7 32.1 1.8 40.8-4.4-13.9-4.3-40.8-1.8-40.8zm-24.4 136.6c9.7-16.9 18-37 24.7-54.7 8.3 15.1 18.9 27.2 30.1 35.5-20.8 4.3-38.9 13.1-54.8 19.2zm131.6-5s-5 6-37.3-7.8c35.1-2.6 40.9 5.4 37.3 7.8z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm72-60V236c0-6.6 5.4-12 12-12h69.2c36.7 0 62.8 27 62.8 66.3 0 74.3-68.7 66.5-95.5 66.5V404c0 6.6-5.4 12-12 12H132c-6.6 0-12-5.4-12-12zm48.5-87.4h23c7.9 0 13.9-2.4 18.1-7.2 8.5-9.8 8.4-28.5.1-37.8-4.1-4.6-9.9-7-17.4-7h-23.9v52z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm228.687-211.303L224 305.374V268c0-11.046-8.954-20-20-20H100c-11.046 0-20 8.954-20 20v104c0 11.046 8.954 20 20 20h104c11.046 0 20-8.954 20-20v-37.374l52.687 52.674C286.704 397.318 304 390.28 304 375.986V264.011c0-14.311-17.309-21.319-27.313-11.314z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm220.1-208c-5.7 0-10.6 4-11.7 9.5-20.6 97.7-20.4 95.4-21 103.5-.2-1.2-.4-2.6-.7-4.3-.8-5.1.3.2-23.6-99.5-1.3-5.4-6.1-9.2-11.7-9.2h-13.3c-5.5 0-10.3 3.8-11.7 9.1-24.4 99-24 96.2-24.8 103.7-.1-1.1-.2-2.5-.5-4.2-.7-5.2-14.1-73.3-19.1-99-1.1-5.6-6-9.7-11.8-9.7h-16.8c-7.8 0-13.5 7.3-11.7 14.8 8 32.6 26.7 109.5 33.2 136 1.3 5.4 6.1 9.1 11.7 9.1h25.2c5.5 0 10.3-3.7 11.6-9.1l17.9-71.4c1.5-6.2 2.5-12 3-17.3l2.9 17.3c.1.4 12.6 50.5 17.9 71.4 1.3 5.3 6.1 9.1 11.6 9.1h24.7c5.5 0 10.3-3.7 11.6-9.1 20.8-81.9 30.2-119 34.5-136 1.9-7.6-3.8-14.9-11.6-14.9h-15.8z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M336.174 80c-49.132 0-93.305-32-161.913-32-31.301 0-58.303 6.482-80.721 15.168a48.04 48.04 0 0 0 2.142-20.727C93.067 19.575 74.167 1.594 51.201.104 23.242-1.71 0 20.431 0 48c0 17.764 9.657 33.262 24 41.562V496c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-83.443C109.869 395.28 143.259 384 199.826 384c49.132 0 93.305 32 161.913 32 58.479 0 101.972-22.617 128.548-39.981C503.846 367.161 512 352.051 512 335.855V95.937c0-34.459-35.264-57.768-66.904-44.117C409.193 67.309 371.641 80 336.174 80zM464 336c-21.783 15.412-60.824 32-102.261 32-59.945 0-102.002-32-161.913-32-43.361 0-96.379 9.403-127.826 24V128c21.784-15.412 60.824-32 102.261-32 59.945 0 102.002 32 161.913 32 43.271 0 96.32-17.366 127.826-32v240z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm96-312c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-112 24c0-44.2-35.8-80-80-80s-80 35.8-80 80 35.8 80 80 80 80-35.8 80-80zm-80 48c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm160 144H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-54.63-54.63c-6-6-14.14-9.37-22.63-9.37H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm0 272H48V112h140.12l54.63 54.63c6 6 14.14 9.37 22.63 9.37H464v224z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M527.9 224H480v-48c0-26.5-21.5-48-48-48H272l-64-64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h400c16.5 0 31.9-8.5 40.7-22.6l79.9-128c20-31.9-3-73.4-40.7-73.4zM48 118c0-3.3 2.7-6 6-6h134.1l64 64H426c3.3 0 6 2.7 6 6v42H152c-16.8 0-32.4 8.8-41.1 23.2L48 351.4zm400 282H72l77.2-128H528z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 128c-40.2 0-78 17.7-103.8 48.6-8.5 10.2-7.1 25.3 3.1 33.8 10.2 8.4 25.3 7.1 33.8-3.1 16.6-19.9 41-31.4 66.9-31.4s50.3 11.4 66.9 31.4c8.1 9.7 23.1 11.9 33.8 3.1 10.2-8.5 11.5-23.6 3.1-33.8C326 321.7 288.2 304 248 304z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-48-248c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 112c-35.6 0-88.8 21.3-95.8 61.2-2 11.8 9 21.5 20.5 18.1 31.2-9.6 59.4-15.3 75.3-15.3s44.1 5.7 75.3 15.3c11.4 3.5 22.5-6.3 20.5-18.1-7-39.9-60.2-61.2-95.8-61.2z\"],\n    \"futbol\": [496, 512, [], \"f1e3\", \"M483.8 179.4C449.8 74.6 352.6 8 248.1 8c-25.4 0-51.2 3.9-76.7 12.2C41.2 62.5-30.1 202.4 12.2 332.6 46.2 437.4 143.4 504 247.9 504c25.4 0 51.2-3.9 76.7-12.2 130.2-42.3 201.5-182.2 159.2-312.4zm-74.5 193.7l-52.2 6.4-43.7-60.9 24.4-75.2 71.1-22.1 38.9 36.4c-.2 30.7-7.4 61.1-21.7 89.2-4.7 9.3-10.7 17.8-16.8 26.2zm0-235.4l-10.4 53.1-70.7 22-64.2-46.5V92.5l47.4-26.2c39.2 13 73.4 38 97.9 71.4zM184.9 66.4L232 92.5v73.8l-64.2 46.5-70.6-22-10.1-52.5c24.3-33.4 57.9-58.6 97.8-71.9zM139 379.5L85.9 373c-14.4-20.1-37.3-59.6-37.8-115.3l39-36.4 71.1 22.2 24.3 74.3-43.5 61.7zm48.2 67l-22.4-48.1 43.6-61.7H287l44.3 61.7-22.4 48.1c-6.2 1.8-57.6 20.4-121.7 0z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M464 0H112c-4 0-7.8 2-10 5.4L2 152.6c-2.9 4.4-2.6 10.2.7 14.2l276 340.8c4.8 5.9 13.8 5.9 18.6 0l276-340.8c3.3-4.1 3.6-9.8.7-14.2L474.1 5.4C471.8 2 468.1 0 464 0zm-19.3 48l63.3 96h-68.4l-51.7-96h56.8zm-202.1 0h90.7l51.7 96H191l51.6-96zm-111.3 0h56.8l-51.7 96H68l63.3-96zm-43 144h51.4L208 352 88.3 192zm102.9 0h193.6L288 435.3 191.2 192zM368 352l68.2-160h51.4L368 352z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm16 16H152c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h192c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48zm-168 96h-24c-8.8 0-16-7.2-16-16v-8h40v24zm0-40h-40v-8c0-8.8 7.2-16 16-16h24v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm56 24c0 8.8-7.2 16-16 16h-24v-24h40v8zm0-24h-40v-24h24c8.8 0 16 7.2 16 16v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M200.3 248c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zm128 0c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-235.9-72.9c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3zm160 0c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3z\"],\n    \"grin-beam-sweat\": [496, 512, [], \"f583\", \"M440 160c29.5 0 53.3-26.3 53.3-58.7 0-25-31.7-75.5-46.2-97.3-3.6-5.3-10.7-5.3-14.2 0-14.5 21.8-46.2 72.3-46.2 97.3 0 32.4 23.8 58.7 53.3 58.7zM248 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zm105.3-52.9c-24.6 15.7-46 12.9-46.4 12.9 6.9 20.2 10.8 41.8 10.8 64.3 0 110.3-89.7 200-200 200S48 366.3 48 256 137.7 56 248 56c39.8 0 76.8 11.8 108 31.9 1.7-9.5 6.3-24.1 17.2-45.7C336.4 20.6 293.7 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-27-4.4-52.9-12.4-77.2zM168 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M353.6 304.6c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-152.8-48.9c4.5 1.2 9.2-1.5 10.5-6l19.4-69.9c5.6-20.3-7.4-41.1-28.8-44.5-18.6-3-36.4 9.8-41.5 27.9l-2 7.1-7.1-1.9c-18.2-4.7-38.2 4.3-44.9 22-7.7 20.2 3.8 41.9 24.2 47.2l70.2 18.1zm188.8-65.3c-6.7-17.6-26.7-26.7-44.9-22l-7.1 1.9-2-7.1c-5-18.1-22.8-30.9-41.5-27.9-21.4 3.4-34.4 24.2-28.8 44.5l19.4 69.9c1.2 4.5 5.9 7.2 10.5 6l70.2-18.2c20.4-5.3 31.9-26.9 24.2-47.1zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-234.7-40.8c3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3l-80-48c-5.1-3-11.4-1.9-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11.1.1 15.5zm242.9 2.5c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11-.1-15.5-3.8-4.4-10.2-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M117.1 384.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 479 124.3 420.8 128 395c.8-6.4-4.6-11.8-10.9-10.9zm-41.2-41.7C40.3 268 53 176.1 114.6 114.6 152.4 76.8 202.6 56 256 56c36.2 0 70.8 9.8 101.2 27.7 3.8-20.3 8-36.1 12-48.3C333.8 17.2 294.9 8 256 8 192.5 8 129.1 32.2 80.6 80.6c-74.1 74.1-91.3 183.4-52 274 12.2-4.1 27.7-8.3 47.3-12.2zm352.3-187.6c45 76.6 34.9 176.9-30.8 242.6-37.8 37.8-88 58.6-141.4 58.6-30.5 0-59.8-7-86.4-19.8-3.9 19.5-8 35-12.2 47.2 31.4 13.6 65 20.6 98.7 20.6 63.5 0 126.9-24.2 175.4-72.6 78.1-78.1 93.1-195.4 45.2-288.6-12.3 4-28.2 8.1-48.5 12zm-33.3-26.9c25.8-3.7 84-13.7 100.9-30.6 21.9-21.9 21.5-57.9-.9-80.3s-58.3-22.8-80.3-.9C397.7 33 387.7 91.2 384 117c-.8 6.4 4.6 11.8 10.9 10.9zm-187 108.3c-3-3-7.2-4.2-11.4-3.2L106 255.7c-5.7 1.4-9.5 6.7-9.1 12.6.5 5.8 5.1 10.5 10.9 11l52.3 4.8 4.8 52.3c.5 5.8 5.2 10.4 11 10.9h.9c5.5 0 10.3-3.7 11.7-9.1l22.6-90.5c1-4.2-.2-8.5-3.2-11.5zm39.7-25.1l90.5-22.6c5.7-1.4 9.5-6.7 9.1-12.6-.5-5.8-5.1-10.5-10.9-11l-52.3-4.8-4.8-52.3c-.5-5.8-5.2-10.4-11-10.9-5.6-.1-11.2 3.4-12.6 9.1L233 196.5c-1 4.1.2 8.4 3.2 11.4 5 5 11.3 3.2 11.4 3.2zm52 88.5c-29.1 29.1-59.7 52.9-83.9 65.4-9.2 4.8-10 17.5-1.7 23.4 38.9 27.7 107 6.2 143.7-30.6S416 253 388.3 214.1c-5.8-8.2-18.5-7.6-23.4 1.7-12.3 24.2-36.2 54.7-65.3 83.8z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-227.9-57.5c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.5 1.9-12.2-4.3-13.2l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6.1 34.9zm259.7-72.7l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6 34.9c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.6 1.8-12.2-4.4-13.2z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M117.1 256.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 351 124.3 292.8 128 267c.8-6.4-4.6-11.8-10.9-10.9zm506.7 30.6c-16.9-16.9-75.1-26.9-100.9-30.6-6.3-.9-11.7 4.5-10.8 10.8 3.7 25.8 13.7 84 30.6 100.9 21.9 21.9 57.9 21.5 80.3-.9 22.3-22.3 22.7-58.3.8-80.2zm-126.6 61.7C463.8 412.3 396.9 456 320 456c-76.9 0-143.8-43.7-177.2-107.6-12.5 37.4-25.2 43.9-28.3 46.5C159.1 460.7 234.5 504 320 504s160.9-43.3 205.5-109.1c-3.2-2.7-15.9-9.2-28.3-46.5zM122.7 224.5C137.9 129.2 220.5 56 320 56c99.5 0 182.1 73.2 197.3 168.5 2.1-.2 5.2-2.4 49.5 7C554.4 106 448.7 8 320 8S85.6 106 73.2 231.4c44.5-9.4 47.1-7.2 49.5-6.9zM320 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zM240 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zM168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zm36.9-281.1c-3.8-4.4-10.3-5.5-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zm-162.9 45.5l-80-48c-5-3-11.4-2-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M152 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm176-52c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M328 180c-25.69 0-55.88 16.92-59.86 42.12-1.75 11.22 11.5 18.24 19.83 10.84l9.55-8.48c14.81-13.19 46.16-13.19 60.97 0l9.55 8.48c8.48 7.43 21.56.25 19.83-10.84C383.88 196.92 353.69 180 328 180zm-160 60c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm185.55 64.64c-25.93 8.3-64.4 13.06-105.55 13.06s-79.62-4.75-105.55-13.06c-9.94-3.13-19.4 5.37-17.71 15.34C132.67 367.13 196.06 400 248 400s115.33-32.87 123.26-80.02c1.68-9.89-7.67-18.48-17.71-15.34zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M556.686 290.542L410.328 64.829C397.001 44.272 374.417 32 349.917 32H56C25.121 32 0 57.122 0 88v8c0 44.112 35.888 80 80 80h196.042l-18.333 48H144c-48.523 0-88 39.477-88 88 0 30.879 25.121 56 56 56h131.552c2.987 0 5.914.549 8.697 1.631L352 408.418V480h224V355.829c0-23.225-6.679-45.801-19.314-65.287zM528 432H400v-23.582c0-19.948-12.014-37.508-30.604-44.736l-99.751-38.788A71.733 71.733 0 0 0 243.552 320H112c-4.411 0-8-3.589-8-8 0-22.056 17.944-40 40-40h113.709c19.767 0 37.786-12.407 44.84-30.873l24.552-64.281c8.996-23.553-8.428-48.846-33.63-48.846H80c-17.645 0-32-14.355-32-32v-8c0-4.411 3.589-8 8-8h293.917c8.166 0 15.693 4.09 20.137 10.942l146.358 225.715A71.84 71.84 0 0 1 528 355.829V432z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M372.57 112.641v-10.825c0-43.612-40.52-76.691-83.039-65.546-25.629-49.5-94.09-47.45-117.982.747C130.269 26.456 89.144 57.945 89.144 102v126.13c-19.953-7.427-43.308-5.068-62.083 8.871-29.355 21.796-35.794 63.333-14.55 93.153L132.48 498.569a32 32 0 0 0 26.062 13.432h222.897c14.904 0 27.835-10.289 31.182-24.813l30.184-130.958A203.637 203.637 0 0 0 448 310.564V179c0-40.62-35.523-71.992-75.43-66.359zm27.427 197.922c0 11.731-1.334 23.469-3.965 34.886L368.707 464h-201.92L51.591 302.303c-14.439-20.27 15.023-42.776 29.394-22.605l27.128 38.079c8.995 12.626 29.031 6.287 29.031-9.283V102c0-25.645 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V67c0-25.663 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V101.125c0-25.672 36.57-24.81 36.57.691V256c0 8.837 7.163 16 16 16h6.857c8.837 0 16-7.163 16-16v-76.309c0-26.242 36.57-25.64 36.57-.691v131.563z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M362.146 191.976c-13.71-21.649-38.761-34.016-65.006-30.341V74c0-40.804-32.811-74-73.141-74-40.33 0-73.14 33.196-73.14 74L160 168l-18.679-78.85C126.578 50.843 83.85 32.11 46.209 47.208 8.735 62.238-9.571 104.963 5.008 142.85l55.757 144.927c-30.557 24.956-43.994 57.809-24.733 92.218l54.853 97.999C102.625 498.97 124.73 512 148.575 512h205.702c30.744 0 57.558-21.44 64.555-51.797l27.427-118.999a67.801 67.801 0 0 0 1.729-15.203L448 256c0-44.956-43.263-77.343-85.854-64.024zM399.987 326c0 1.488-.169 2.977-.502 4.423l-27.427 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H148.575c-6.486 0-12.542-3.621-15.805-9.449l-54.854-98c-4.557-8.141-2.619-18.668 4.508-24.488l26.647-21.764a16 16 0 0 0 4.812-18.139l-64.09-166.549C37.226 92.956 84.37 74.837 96.51 106.389l59.784 155.357A16 16 0 0 0 171.227 272h11.632c8.837 0 16-7.163 16-16V74c0-34.375 50.281-34.43 50.281 0v182c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16v-28c0-25.122 36.567-25.159 36.567 0v28c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16 0-25.12 36.567-25.16 36.567 0v70z\"],\n    \"hand-point-down\": [448, 512, [], \"f0a7\", \"M188.8 512c45.616 0 83.2-37.765 83.2-83.2v-35.647a93.148 93.148 0 0 0 22.064-7.929c22.006 2.507 44.978-3.503 62.791-15.985C409.342 368.1 448 331.841 448 269.299V248c0-60.063-40-98.512-40-127.2v-2.679c4.952-5.747 8-13.536 8-22.12V32c0-17.673-12.894-32-28.8-32H156.8C140.894 0 128 14.327 128 32v64c0 8.584 3.048 16.373 8 22.12v2.679c0 6.964-6.193 14.862-23.668 30.183l-.148.129-.146.131c-9.937 8.856-20.841 18.116-33.253 25.851C48.537 195.798 0 207.486 0 252.8c0 56.928 35.286 92 83.2 92 8.026 0 15.489-.814 22.4-2.176V428.8c0 45.099 38.101 83.2 83.2 83.2zm0-48c-18.7 0-35.2-16.775-35.2-35.2V270.4c-17.325 0-35.2 26.4-70.4 26.4-26.4 0-35.2-20.625-35.2-44 0-8.794 32.712-20.445 56.1-34.926 14.575-9.074 27.225-19.524 39.875-30.799 18.374-16.109 36.633-33.836 39.596-59.075h176.752C364.087 170.79 400 202.509 400 248v21.299c0 40.524-22.197 57.124-61.325 50.601-8.001 14.612-33.979 24.151-53.625 12.925-18.225 19.365-46.381 17.787-61.05 4.95V428.8c0 18.975-16.225 35.2-35.2 35.2zM328 64c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M0 220.8C0 266.416 37.765 304 83.2 304h35.647a93.148 93.148 0 0 0 7.929 22.064c-2.507 22.006 3.503 44.978 15.985 62.791C143.9 441.342 180.159 480 242.701 480H264c60.063 0 98.512-40 127.2-40h2.679c5.747 4.952 13.536 8 22.12 8h64c17.673 0 32-12.894 32-28.8V188.8c0-15.906-14.327-28.8-32-28.8h-64c-8.584 0-16.373 3.048-22.12 8H391.2c-6.964 0-14.862-6.193-30.183-23.668l-.129-.148-.131-.146c-8.856-9.937-18.116-20.841-25.851-33.253C316.202 80.537 304.514 32 259.2 32c-56.928 0-92 35.286-92 83.2 0 8.026.814 15.489 2.176 22.4H83.2C38.101 137.6 0 175.701 0 220.8zm48 0c0-18.7 16.775-35.2 35.2-35.2h158.4c0-17.325-26.4-35.2-26.4-70.4 0-26.4 20.625-35.2 44-35.2 8.794 0 20.445 32.712 34.926 56.1 9.074 14.575 19.524 27.225 30.799 39.875 16.109 18.374 33.836 36.633 59.075 39.596v176.752C341.21 396.087 309.491 432 264 432h-21.299c-40.524 0-57.124-22.197-50.601-61.325-14.612-8.001-24.151-33.979-12.925-53.625-19.365-18.225-17.787-46.381-4.95-61.05H83.2C64.225 256 48 239.775 48 220.8zM448 360c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M428.8 137.6h-86.177a115.52 115.52 0 0 0 2.176-22.4c0-47.914-35.072-83.2-92-83.2-45.314 0-57.002 48.537-75.707 78.784-7.735 12.413-16.994 23.317-25.851 33.253l-.131.146-.129.148C135.662 161.807 127.764 168 120.8 168h-2.679c-5.747-4.952-13.536-8-22.12-8H32c-17.673 0-32 12.894-32 28.8v230.4C0 435.106 14.327 448 32 448h64c8.584 0 16.373-3.048 22.12-8h2.679c28.688 0 67.137 40 127.2 40h21.299c62.542 0 98.8-38.658 99.94-91.145 12.482-17.813 18.491-40.785 15.985-62.791A93.148 93.148 0 0 0 393.152 304H428.8c45.435 0 83.2-37.584 83.2-83.2 0-45.099-38.101-83.2-83.2-83.2zm0 118.4h-91.026c12.837 14.669 14.415 42.825-4.95 61.05 11.227 19.646 1.687 45.624-12.925 53.625 6.524 39.128-10.076 61.325-50.6 61.325H248c-45.491 0-77.21-35.913-120-39.676V215.571c25.239-2.964 42.966-21.222 59.075-39.596 11.275-12.65 21.725-25.3 30.799-39.875C232.355 112.712 244.006 80 252.8 80c23.375 0 44 8.8 44 35.2 0 35.2-26.4 53.075-26.4 70.4h158.4c18.425 0 35.2 16.5 35.2 35.2 0 18.975-16.225 35.2-35.2 35.2zM88 384c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"hand-point-up\": [448, 512, [], \"f0a6\", \"M105.6 83.2v86.177a115.52 115.52 0 0 0-22.4-2.176c-47.914 0-83.2 35.072-83.2 92 0 45.314 48.537 57.002 78.784 75.707 12.413 7.735 23.317 16.994 33.253 25.851l.146.131.148.129C129.807 376.338 136 384.236 136 391.2v2.679c-4.952 5.747-8 13.536-8 22.12v64c0 17.673 12.894 32 28.8 32h230.4c15.906 0 28.8-14.327 28.8-32v-64c0-8.584-3.048-16.373-8-22.12V391.2c0-28.688 40-67.137 40-127.2v-21.299c0-62.542-38.658-98.8-91.145-99.94-17.813-12.482-40.785-18.491-62.791-15.985A93.148 93.148 0 0 0 272 118.847V83.2C272 37.765 234.416 0 188.8 0c-45.099 0-83.2 38.101-83.2 83.2zm118.4 0v91.026c14.669-12.837 42.825-14.415 61.05 4.95 19.646-11.227 45.624-1.687 53.625 12.925 39.128-6.524 61.325 10.076 61.325 50.6V264c0 45.491-35.913 77.21-39.676 120H183.571c-2.964-25.239-21.222-42.966-39.596-59.075-12.65-11.275-25.3-21.725-39.875-30.799C80.712 279.645 48 267.994 48 259.2c0-23.375 8.8-44 35.2-44 35.2 0 53.075 26.4 70.4 26.4V83.2c0-18.425 16.5-35.2 35.2-35.2 18.975 0 35.2 16.225 35.2 35.2zM352 424c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M358.182 179.361c-19.493-24.768-52.679-31.945-79.872-19.098-15.127-15.687-36.182-22.487-56.595-19.629V67c0-36.944-29.736-67-66.286-67S89.143 30.056 89.143 67v161.129c-19.909-7.41-43.272-5.094-62.083 8.872-29.355 21.795-35.793 63.333-14.55 93.152l109.699 154.001C134.632 501.59 154.741 512 176 512h178.286c30.802 0 57.574-21.5 64.557-51.797l27.429-118.999A67.873 67.873 0 0 0 448 326v-84c0-46.844-46.625-79.273-89.818-62.639zM80.985 279.697l27.126 38.079c8.995 12.626 29.031 6.287 29.031-9.283V67c0-25.12 36.571-25.16 36.571 0v175c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16v-35c0-25.12 36.571-25.16 36.571 0v35c0 8.836 7.163 16 16 16H272c8.837 0 16-7.164 16-16v-21c0-25.12 36.571-25.16 36.571 0v21c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16 0-25.121 36.571-25.16 36.571 0v84c0 1.488-.169 2.977-.502 4.423l-27.43 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H176c-5.769 0-11.263-2.878-14.697-7.697l-109.712-154c-14.406-20.223 14.994-42.818 29.394-22.606zM176.143 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.733 0-14-7.163-14-16zm75.428 0v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16zM327 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M408.864 79.052c-22.401-33.898-66.108-42.273-98.813-23.588-29.474-31.469-79.145-31.093-108.334-.022-47.16-27.02-108.71 5.055-110.671 60.806C44.846 105.407 0 140.001 0 187.429v56.953c0 32.741 14.28 63.954 39.18 85.634l97.71 85.081c4.252 3.702 3.11 5.573 3.11 32.903 0 17.673 14.327 32 32 32h252c17.673 0 32-14.327 32-32 0-23.513-1.015-30.745 3.982-42.37l42.835-99.656c6.094-14.177 9.183-29.172 9.183-44.568V146.963c0-52.839-54.314-88.662-103.136-67.911zM464 261.406a64.505 64.505 0 0 1-5.282 25.613l-42.835 99.655c-5.23 12.171-7.883 25.04-7.883 38.25V432H188v-10.286c0-16.37-7.14-31.977-19.59-42.817l-97.71-85.08C56.274 281.255 48 263.236 48 244.381v-56.953c0-33.208 52-33.537 52 .677v41.228a16 16 0 0 0 5.493 12.067l7 6.095A16 16 0 0 0 139 235.429V118.857c0-33.097 52-33.725 52 .677v26.751c0 8.836 7.164 16 16 16h7c8.836 0 16-7.164 16-16v-41.143c0-33.134 52-33.675 52 .677v40.466c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16v-27.429c0-33.03 52-33.78 52 .677v26.751c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16 0-33.146 52-33.613 52 .677v114.445z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M256 480l70-.013c5.114 0 10.231-.583 15.203-1.729l118.999-27.427C490.56 443.835 512 417.02 512 386.277V180.575c0-23.845-13.03-45.951-34.005-57.69l-97.999-54.853c-34.409-19.261-67.263-5.824-92.218 24.733L142.85 37.008c-37.887-14.579-80.612 3.727-95.642 41.201-15.098 37.642 3.635 80.37 41.942 95.112L168 192l-94-9.141c-40.804 0-74 32.811-74 73.14 0 40.33 33.196 73.141 74 73.141h87.635c-3.675 26.245 8.692 51.297 30.341 65.006C178.657 436.737 211.044 480 256 480zm0-48.013c-25.16 0-25.12-36.567 0-36.567 8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16h-28c-25.159 0-25.122-36.567 0-36.567h28c8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16H74c-34.43 0-34.375-50.281 0-50.281h182c8.837 0 16-7.163 16-16v-11.632a16 16 0 0 0-10.254-14.933L106.389 128.51c-31.552-12.14-13.432-59.283 19.222-46.717l166.549 64.091a16.001 16.001 0 0 0 18.139-4.812l21.764-26.647c5.82-7.127 16.348-9.064 24.488-4.508l98 54.854c5.828 3.263 9.449 9.318 9.449 15.805v205.701c0 8.491-5.994 15.804-14.576 17.782l-119.001 27.427a19.743 19.743 0 0 1-4.423.502h-70z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M21.096 381.79l129.092 121.513a32 32 0 0 0 21.932 8.698h237.6c14.17 0 26.653-9.319 30.68-22.904l31.815-107.313A115.955 115.955 0 0 0 477 348.811v-36.839c0-4.051.476-8.104 1.414-12.045l31.73-133.41c10.099-42.412-22.316-82.738-65.544-82.525-4.144-24.856-22.543-47.165-49.85-53.992-35.803-8.952-72.227 12.655-81.25 48.75L296.599 184 274.924 52.01c-8.286-36.07-44.303-58.572-80.304-50.296-29.616 6.804-50.138 32.389-51.882 61.295-42.637.831-73.455 40.563-64.071 81.844l31.04 136.508c-27.194-22.515-67.284-19.992-91.482 5.722-25.376 26.961-24.098 69.325 2.871 94.707zm32.068-61.811l.002-.001c7.219-7.672 19.241-7.98 26.856-.813l53.012 49.894C143.225 378.649 160 371.4 160 357.406v-69.479c0-1.193-.134-2.383-.397-3.546l-34.13-150.172c-5.596-24.617 31.502-32.86 37.054-8.421l30.399 133.757a16 16 0 0 0 15.603 12.454h8.604c10.276 0 17.894-9.567 15.594-19.583l-41.62-181.153c-5.623-24.469 31.39-33.076 37.035-8.508l45.22 196.828A16 16 0 0 0 288.956 272h13.217a16 16 0 0 0 15.522-12.119l42.372-169.49c6.104-24.422 42.962-15.159 36.865 9.217L358.805 252.12c-2.521 10.088 5.115 19.88 15.522 19.88h9.694a16 16 0 0 0 15.565-12.295L426.509 146.6c5.821-24.448 42.797-15.687 36.966 8.802L431.72 288.81a100.094 100.094 0 0 0-2.72 23.162v36.839c0 6.548-.943 13.051-2.805 19.328L397.775 464h-219.31L53.978 346.836c-7.629-7.18-7.994-19.229-.814-26.857z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M519.2 127.9l-47.6-47.6A56.252 56.252 0 0 0 432 64H205.2c-14.8 0-29.1 5.9-39.6 16.3L118 127.9H0v255.7h64c17.6 0 31.8-14.2 31.9-31.7h9.1l84.6 76.4c30.9 25.1 73.8 25.7 105.6 3.8 12.5 10.8 26 15.9 41.1 15.9 18.2 0 35.3-7.4 48.8-24 22.1 8.7 48.2 2.6 64-16.8l26.2-32.3c5.6-6.9 9.1-14.8 10.9-23h57.9c.1 17.5 14.4 31.7 31.9 31.7h64V127.9H519.2zM48 351.6c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16zm390-6.9l-26.1 32.2c-2.8 3.4-7.8 4-11.3 1.2l-23.9-19.4-30 36.5c-6 7.3-15 4.8-18 2.4l-36.8-31.5-15.6 19.2c-13.9 17.1-39.2 19.7-55.3 6.6l-97.3-88H96V175.8h41.9l61.7-61.6c2-.8 3.7-1.5 5.7-2.3H262l-38.7 35.5c-29.4 26.9-31.1 72.3-4.4 101.3 14.8 16.2 61.2 41.2 101.5 4.4l8.2-7.5 108.2 87.8c3.4 2.8 3.9 7.9 1.2 11.3zm106-40.8h-69.2c-2.3-2.8-4.9-5.4-7.7-7.7l-102.7-83.4 12.5-11.4c6.5-6 7-16.1 1-22.6L367 167.1c-6-6.5-16.1-6.9-22.6-1l-55.2 50.6c-9.5 8.7-25.7 9.4-34.6 0-9.3-9.9-8.5-25.1 1.2-33.9l65.6-60.1c7.4-6.8 17-10.5 27-10.5l83.7-.2c2.1 0 4.1.8 5.5 2.3l61.7 61.6H544v128zm48 47.7c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M567.403 235.642L462.323 84.589A48 48 0 0 0 422.919 64H153.081a48 48 0 0 0-39.404 20.589L8.597 235.642A48.001 48.001 0 0 0 0 263.054V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V263.054c0-9.801-3-19.366-8.597-27.412zM153.081 112h269.838l77.913 112H75.168l77.913-112zM528 400H48V272h480v128zm-32-64c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32zm-96 0c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M458.4 64.3C400.6 15.7 311.3 23 256 79.3 200.7 23 111.4 15.6 53.6 64.3-21.6 127.6-10.6 230.8 43 285.5l175.4 178.7c10 10.2 23.4 15.9 37.6 15.9 14.3 0 27.6-5.6 37.6-15.8L469 285.6c53.5-54.7 64.7-157.9-10.6-221.3zm-23.6 187.5L259.4 430.5c-2.4 2.4-4.4 2.4-6.8 0L77.2 251.8c-36.5-37.2-43.9-107.6 7.3-150.7 38.9-32.7 98.9-27.8 136.5 10.5l35 35.7 35-35.7c37.8-38.5 97.8-43.2 136.5-10.6 51.1 43.1 43.5 113.9 7.3 150.8z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M128 244v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12zm140 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm-76 84v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm76 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm180 124v36H0v-36c0-6.627 5.373-12 12-12h19.5V85.035C31.5 73.418 42.245 64 55.5 64H144V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v40h88.5c13.255 0 24 9.418 24 21.035V464H436c6.627 0 12 5.373 12 12zM79.5 463H192v-67c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v67h112.5V112H304v24c0 13.255-10.745 24-24 24H168c-13.255 0-24-10.745-24-24v-24H79.5v351zM266 64h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M368 48h4c6.627 0 12-5.373 12-12V12c0-6.627-5.373-12-12-12H12C5.373 0 0 5.373 0 12v24c0 6.627 5.373 12 12 12h4c0 80.564 32.188 165.807 97.18 208C47.899 298.381 16 383.9 16 464h-4c-6.627 0-12 5.373-12 12v24c0 6.627 5.373 12 12 12h360c6.627 0 12-5.373 12-12v-24c0-6.627-5.373-12-12-12h-4c0-80.564-32.188-165.807-97.18-208C336.102 213.619 368 128.1 368 48zM64 48h256c0 101.62-57.307 184-128 184S64 149.621 64 48zm256 416H64c0-101.62 57.308-184 128-184s128 82.38 128 184z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm0 464H48V48h288v416zM144 112h96c8.8 0 16-7.2 16-16s-7.2-16-16-16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16zm48 176c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H303.2c.9-4.5.8 3.6.8-22.4 0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6 0 26-.2 17.9.8 22.4H48V144h480v288zm-168-80h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm-168 96c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 336H54a6 6 0 0 1-6-6V118a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v276a6 6 0 0 1-6 6zM128 152c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zM96 352h320v-80l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L192 304l-39.515-39.515c-4.686-4.686-12.284-4.686-16.971 0L96 304v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v48H54a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6v-10h48zm42-336H150a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6V86a6 6 0 0 0-6-6zm6-48c26.51 0 48 21.49 48 48v256c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h384zM264 144c0 22.091-17.909 40-40 40s-40-17.909-40-40 17.909-40 40-40 40 17.909 40 40zm-72 96l39.515-39.515c4.686-4.686 12.284-4.686 16.971 0L288 240l103.515-103.515c4.686-4.686 12.284-4.686 16.971 0L480 208v80H192v-48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm8 336c0 4.411-3.589 8-8 8H48c-4.411 0-8-3.589-8-8V112c0-4.411 3.589-8 8-8h480c4.411 0 8 3.589 8 8v288zM170 270v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-336 82v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm384 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zM122 188v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-98 158v-16c0-6.627-5.373-12-12-12H180c-6.627 0-12 5.373-12 12v16c0 6.627 5.373 12 12 12h216c6.627 0 12-5.373 12-12z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm136 132c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M168 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm56-148c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zm24-156c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M304 308.5c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36 21.7-9.1 35.1-23.4 35.1-36.4zm70.5-83.5l9.5 8.5c3.8 3.3 9.3 4 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 5.8 3.1 11.2.7 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0zM136 208.5c0 17.7 14.3 32 32 32s32-14.3 32-32-14.3-32-32-32-32 14.3-32 32zm365.1 194c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zM334 436.3c-26.1 12.5-55.2 19.7-86 19.7-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200c0 22.1-3.7 43.3-10.4 63.2 9 6.4 17 14.2 22.6 23.9 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-2.5-7.3 4.3 17.2-13.4-46.8z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 224c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm-160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 152c-23.8 0-52.7 29.3-56 71.4-.7 8.6 10.8 11.9 14.9 4.5l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.1-42.1-32-71.4-55.8-71.4zm-201 75.9l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.6 8.5 10.9 11.9 15.1 4.5zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM343.6 196l33.6-40.3c8.6-10.3-3.8-24.8-15.4-18l-80 48c-7.8 4.7-7.8 15.9 0 20.6l80 48c11.5 6.8 24-7.6 15.4-18L343.6 196zm-209.4 58.3l80-48c7.8-4.7 7.8-15.9 0-20.6l-80-48c-11.6-6.9-24 7.7-15.4 18l33.6 40.3-33.6 40.3c-8.7 10.4 3.8 24.8 15.4 18zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6C68.8 359.6 48 309.4 48 256s20.8-103.6 58.6-141.4C144.4 76.8 194.6 56 248 56s103.6 20.8 141.4 58.6c37.8 37.8 58.6 88 58.6 141.4s-20.8 103.6-58.6 141.4zM328 164c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1zm-160 60c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M484.112 27.889C455.989-.233 416.108-8.057 387.059 8.865 347.604 31.848 223.504-41.111 91.196 91.197-41.277 223.672 31.923 347.472 8.866 387.058c-16.922 29.051-9.1 68.932 19.022 97.054 28.135 28.135 68.011 35.938 97.057 19.021 39.423-22.97 163.557 49.969 295.858-82.329 132.474-132.477 59.273-256.277 82.331-295.861 16.922-29.05 9.1-68.931-19.022-97.054zm-22.405 72.894c-38.8 66.609 45.6 165.635-74.845 286.08-120.44 120.443-219.475 36.048-286.076 74.843-22.679 13.207-64.035-27.241-50.493-50.488 38.8-66.609-45.6-165.635 74.845-286.08C245.573 4.702 344.616 89.086 411.219 50.292c22.73-13.24 64.005 27.288 50.488 50.491zm-169.861 8.736c1.37 10.96-6.404 20.957-17.365 22.327-54.846 6.855-135.779 87.787-142.635 142.635-1.373 10.989-11.399 18.734-22.326 17.365-10.961-1.37-18.735-11.366-17.365-22.326 9.162-73.286 104.167-168.215 177.365-177.365 10.953-1.368 20.956 6.403 22.326 17.364z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 504c136.967 0 248-111.033 248-248S392.967 8 256 8 8 119.033 8 256s111.033 248 248 248zm-103.398-76.72l53.411-53.411c31.806 13.506 68.128 13.522 99.974 0l53.411 53.411c-63.217 38.319-143.579 38.319-206.796 0zM336 256c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zm91.28 103.398l-53.411-53.411c13.505-31.806 13.522-68.128 0-99.974l53.411-53.411c38.319 63.217 38.319 143.579 0 206.796zM359.397 84.72l-53.411 53.411c-31.806-13.505-68.128-13.522-99.973 0L152.602 84.72c63.217-38.319 143.579-38.319 206.795 0zM84.72 152.602l53.411 53.411c-13.506 31.806-13.522 68.128 0 99.974L84.72 359.398c-38.319-63.217-38.319-143.579 0-206.796z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M176 80c-52.94 0-96 43.06-96 96 0 8.84 7.16 16 16 16s16-7.16 16-16c0-35.3 28.72-64 64-64 8.84 0 16-7.16 16-16s-7.16-16-16-16zM96.06 459.17c0 3.15.93 6.22 2.68 8.84l24.51 36.84c2.97 4.46 7.97 7.14 13.32 7.14h78.85c5.36 0 10.36-2.68 13.32-7.14l24.51-36.84c1.74-2.62 2.67-5.7 2.68-8.84l.05-43.18H96.02l.04 43.18zM176 0C73.72 0 0 82.97 0 176c0 44.37 16.45 84.85 43.56 115.78 16.64 18.99 42.74 58.8 52.42 92.16v.06h48v-.12c-.01-4.77-.72-9.51-2.15-14.07-5.59-17.81-22.82-64.77-62.17-109.67-20.54-23.43-31.52-53.15-31.61-84.14-.2-73.64 59.67-128 127.95-128 70.58 0 128 57.42 128 128 0 30.97-11.24 60.85-31.65 84.14-39.11 44.61-56.42 91.47-62.1 109.46a47.507 47.507 0 0 0-2.22 14.3v.1h48v-.05c9.68-33.37 35.78-73.18 52.42-92.16C335.55 260.85 352 220.37 352 176 352 78.8 273.2 0 176 0z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v340a6 6 0 0 1-6 6zm-42-92v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm-252 12c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36z\"],\n    \"map\": [576, 512, [], \"f279\", \"M560.02 32c-1.96 0-3.98.37-5.96 1.16L384.01 96H384L212 35.28A64.252 64.252 0 0 0 191.76 32c-6.69 0-13.37 1.05-19.81 3.14L20.12 87.95A32.006 32.006 0 0 0 0 117.66v346.32C0 473.17 7.53 480 15.99 480c1.96 0 3.97-.37 5.96-1.16L192 416l172 60.71a63.98 63.98 0 0 0 40.05.15l151.83-52.81A31.996 31.996 0 0 0 576 394.34V48.02c0-9.19-7.53-16.02-15.98-16.02zM224 90.42l128 45.19v285.97l-128-45.19V90.42zM48 418.05V129.07l128-44.53v286.2l-.64.23L48 418.05zm480-35.13l-128 44.53V141.26l.64-.24L528 93.95v288.97z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm8 144H160c-13.2 0-24 10.8-24 24s10.8 24 24 24h176c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm88-304c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm0 112c-22.1 0-40-17.9-40-40 0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40zm-104-40c0-39.8-32.2-72-72-72s-72 32.2-72 72 32.2 72 72 72 72-32.2 72-72zm-112 0c0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40s-40-17.9-40-40zm192 128H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M108 284c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h232c6.6 0 12 5.4 12 12v32c0 6.6-5.4 12-12 12H108zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M320 144c-53.02 0-96 50.14-96 112 0 61.85 42.98 112 96 112 53 0 96-50.13 96-112 0-61.86-42.98-112-96-112zm40 168c0 4.42-3.58 8-8 8h-64c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h16v-55.44l-.47.31a7.992 7.992 0 0 1-11.09-2.22l-8.88-13.31a7.992 7.992 0 0 1 2.22-11.09l15.33-10.22a23.99 23.99 0 0 1 13.31-4.03H328c4.42 0 8 3.58 8 8v88h16c4.42 0 8 3.58 8 8v16zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zm-16 272c-35.35 0-64 28.65-64 64H112c0-35.35-28.65-64-64-64V176c35.35 0 64-28.65 64-64h416c0 35.35 28.65 64 64 64v160z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M279.135 512c78.756 0 150.982-35.804 198.844-94.775 28.27-34.831-2.558-85.722-46.249-77.401-82.348 15.683-158.272-47.268-158.272-130.792 0-48.424 26.06-92.292 67.434-115.836 38.745-22.05 28.999-80.788-15.022-88.919A257.936 257.936 0 0 0 279.135 0c-141.36 0-256 114.575-256 256 0 141.36 114.576 256 256 256zm0-464c12.985 0 25.689 1.201 38.016 3.478-54.76 31.163-91.693 90.042-91.693 157.554 0 113.848 103.641 199.2 215.252 177.944C402.574 433.964 344.366 464 279.135 464c-114.875 0-208-93.125-208-208s93.125-208 208-208z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H112c-20.858 0-38.643 13.377-45.248 32H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h496c13.255 0 24-10.745 24-24V88c0-13.255-10.745-24-24-24zM48 392V144h16v248c0 4.411-3.589 8-8 8s-8-3.589-8-8zm480 8H111.422c.374-2.614.578-5.283.578-8V112h416v288zM172 280h136c6.627 0 12-5.373 12-12v-96c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v96c0 6.627 5.373 12 12 12zm28-80h80v40h-80v-40zm-40 140v-24c0-6.627 5.373-12 12-12h136c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H172c-6.627 0-12-5.373-12-12zm192 0v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0-144v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0 72v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M500 128c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v256H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V128h12zm-52-64h32v32h-32V64zM32 64h32v32H32V64zm32 384H32v-32h32v32zm416 0h-32v-32h32v32zm-40-64h-12c-6.627 0-12 5.373-12 12v12H96v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h12v256zm-36-192h-84v-52c0-6.628-5.373-12-12-12H108c-6.627 0-12 5.372-12 12v168c0 6.628 5.373 12 12 12h84v52c0 6.628 5.373 12 12 12h200c6.627 0 12-5.372 12-12V204c0-6.628-5.373-12-12-12zm-268-24h144v112H136V168zm240 176H232v-24h76c6.627 0 12-5.372 12-12v-76h56v112z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M564 224c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12h-88v-24h12c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v160H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h88v24h-12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V224h12zM352 64h32v32h-32V64zm0 256h32v32h-32v-32zM64 352H32v-32h32v32zm0-256H32V64h32v32zm32 216v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h12v160h-12c-6.627 0-12 5.373-12 12v12H96zm128 136h-32v-32h32v32zm280-64h-12c-6.627 0-12 5.373-12 12v12H256v-12c0-6.627-5.373-12-12-12h-12v-24h88v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12v-88h88v12c0 6.627 5.373 12 12 12h12v160zm40 64h-32v-32h32v32zm0-256h-32v-32h32v32z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M440 6.5L24 246.4c-34.4 19.9-31.1 70.8 5.7 85.9L144 379.6V464c0 46.4 59.2 65.5 86.6 28.6l43.8-59.1 111.9 46.2c5.9 2.4 12.1 3.6 18.3 3.6 8.2 0 16.3-2.1 23.6-6.2 12.8-7.2 21.6-20 23.9-34.5l59.4-387.2c6.1-40.1-36.9-68.8-71.5-48.9zM192 464v-64.6l36.6 15.1L192 464zm212.6-28.7l-153.8-63.5L391 169.5c10.7-15.5-9.5-33.5-23.7-21.2L155.8 332.6 48 288 464 48l-59.4 387.3z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm96-280v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16zm-112 0v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M371.7 238l-176-107c-15.8-8.8-35.7 2.5-35.7 21v208c0 18.4 19.8 29.8 35.7 21l176-101c16.4-9.1 16.4-32.8 0-42zM504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M352 240v32c0 6.6-5.4 12-12 12h-88v88c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-88h-88c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h88v-88c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v88h88c6.6 0 12 5.4 12 12zm96-160v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 448c-110.532 0-200-89.431-200-200 0-110.495 89.472-200 200-200 110.491 0 200 89.471 200 200 0 110.53-89.431 200-200 200zm107.244-255.2c0 67.052-72.421 68.084-72.421 92.863V300c0 6.627-5.373 12-12 12h-45.647c-6.627 0-12-5.373-12-12v-8.659c0-35.745 27.1-50.034 47.579-61.516 17.561-9.845 28.324-16.541 28.324-29.579 0-17.246-21.999-28.693-39.784-28.693-23.189 0-33.894 10.977-48.942 29.969-4.057 5.12-11.46 6.071-16.666 2.124l-27.824-21.098c-5.107-3.872-6.251-11.066-2.644-16.363C184.846 131.491 214.94 112 261.794 112c49.071 0 101.45 38.304 101.45 88.8zM298 368c0 23.159-18.841 42-42 42s-42-18.841-42-42 18.841-42 42-42 42 18.841 42 42z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm110.442-81.791c-53.046-96.284-50.25-91.468-53.271-96.085 24.267-13.879 39.482-41.563 39.482-73.176 0-52.503-30.247-85.252-101.498-85.252h-78.667c-6.617 0-12 5.383-12 12V380c0 6.617 5.383 12 12 12h38.568c6.617 0 12-5.383 12-12v-83.663h31.958l47.515 89.303a11.98 11.98 0 0 0 10.593 6.36h42.81c9.14 0 14.914-9.799 10.51-17.791zM256.933 239.906h-33.875v-64.14h27.377c32.417 0 38.929 12.133 38.929 31.709-.001 20.913-11.518 32.431-32.431 32.431z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm144 386.4V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v151.4C315.5 447 282.8 456 248 456s-67.5-9-96-24.6V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v114.4c-34.6-36-56-84.7-56-138.4 0-110.3 89.7-200 200-200s200 89.7 200 200c0 53.7-21.4 102.5-56 138.4zM205.8 234.5c4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.3 7.9 4.8 13.7 1.6zM344 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.5 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm-96 92c-30.9 0-56 28.7-56 64s25.1 64 56 64 56-28.7 56-64-25.1-64-56-64z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm8-152c-13.2 0-24 10.8-24 24s10.8 24 24 24c23.8 0 46.3 10.5 61.6 28.8 8.1 9.8 23.2 11.9 33.8 3.1 10.2-8.5 11.6-23.6 3.1-33.8C330 320.8 294.1 304 256 304zm-88-64c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-165.6 98.8C151 290.1 126 325.4 126 342.9c0 22.7 18.8 41.1 42 41.1s42-18.4 42-41.1c0-17.5-25-52.8-36.4-68.1-2.8-3.7-8.4-3.7-11.2 0z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM272 80v80H144V80h128zm122 352H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h42v104c0 13.255 10.745 24 24 24h176c13.255 0 24-10.745 24-24V83.882l78.243 78.243a6 6 0 0 1 1.757 4.243V426a6 6 0 0 1-6 6zM224 232c-48.523 0-88 39.477-88 88s39.477 88 88 88 88-39.477 88-88-39.477-88-88-88zm0 128c-22.056 0-40-17.944-40-40s17.944-40 40-40 40 17.944 40 40-17.944 40-40 40z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M561.938 158.06L417.94 14.092C387.926-15.922 336 5.097 336 48.032v57.198c-42.45 1.88-84.03 6.55-120.76 17.99-35.17 10.95-63.07 27.58-82.91 49.42C108.22 199.2 96 232.6 96 271.94c0 61.697 33.178 112.455 84.87 144.76 37.546 23.508 85.248-12.651 71.02-55.74-15.515-47.119-17.156-70.923 84.11-78.76V336c0 42.993 51.968 63.913 81.94 33.94l143.998-144c18.75-18.74 18.75-49.14 0-67.88zM384 336V232.16C255.309 234.082 166.492 255.35 206.31 376 176.79 357.55 144 324.08 144 271.94c0-109.334 129.14-118.947 240-119.85V48l144 144-144 144zm24.74 84.493a82.658 82.658 0 0 0 20.974-9.303c7.976-4.952 18.286.826 18.286 10.214V464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h132c6.627 0 12 5.373 12 12v4.486c0 4.917-2.987 9.369-7.569 11.152-13.702 5.331-26.396 11.537-38.05 18.585a12.138 12.138 0 0 1-6.28 1.777H54a6 6 0 0 0-6 6v340a6 6 0 0 0 6 6h340a6 6 0 0 0 6-6v-25.966c0-5.37 3.579-10.059 8.74-11.541z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm4 72.6c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.1-8.4-25.3-7.1-33.8 3.1z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm84-143.4c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.6-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.2-8.4-25.3-7.1-33.8 3.1zM136.5 211c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.4 1.1 7.4-.5 9.3-3.7l9.5-17zM328 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm117.8-146.4c-10.2-8.5-25.3-7.1-33.8 3.1-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-60c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.1 355.2l-39.2-23 34.1-9.3c8.4-2.3 13.4-11.1 11.1-19.6l-4.1-15.5c-2.2-8.5-10.9-13.6-19.3-11.3L343 298.2 271.2 256l71.9-42.2 79.7 21.7c8.4 2.3 17-2.8 19.3-11.3l4.1-15.5c2.2-8.5-2.7-17.3-11.1-19.6l-34.1-9.3 39.2-23c7.5-4.4 10.1-14.2 5.8-21.9l-7.9-13.9c-4.3-7.7-14-10.3-21.5-5.9l-39.2 23 9.1-34.7c2.2-8.5-2.7-17.3-11.1-19.6l-15.2-4.1c-8.4-2.3-17 2.8-19.3 11.3l-21.3 81-71.9 42.2v-84.5L306 70.4c6.1-6.2 6.1-16.4 0-22.6l-11.1-11.3c-6.1-6.2-16.1-6.2-22.2 0l-24.9 25.4V16c0-8.8-7-16-15.7-16h-15.7c-8.7 0-15.7 7.2-15.7 16v46.1l-24.9-25.4c-6.1-6.2-16.1-6.2-22.2 0L142.1 48c-6.1 6.2-6.1 16.4 0 22.6l58.3 59.3v84.5l-71.9-42.2-21.3-81c-2.2-8.5-10.9-13.6-19.3-11.3L72.7 84c-8.4 2.3-13.4 11.1-11.1 19.6l9.1 34.7-39.2-23c-7.5-4.4-17.1-1.8-21.5 5.9l-7.9 13.9c-4.3 7.7-1.8 17.4 5.8 21.9l39.2 23-34.1 9.1c-8.4 2.3-13.4 11.1-11.1 19.6L6 224.2c2.2 8.5 10.9 13.6 19.3 11.3l79.7-21.7 71.9 42.2-71.9 42.2-79.7-21.7c-8.4-2.3-17 2.8-19.3 11.3l-4.1 15.5c-2.2 8.5 2.7 17.3 11.1 19.6l34.1 9.3-39.2 23c-7.5 4.4-10.1 14.2-5.8 21.9L10 391c4.3 7.7 14 10.3 21.5 5.9l39.2-23-9.1 34.7c-2.2 8.5 2.7 17.3 11.1 19.6l15.2 4.1c8.4 2.3 17-2.8 19.3-11.3l21.3-81 71.9-42.2v84.5l-58.3 59.3c-6.1 6.2-6.1 16.4 0 22.6l11.1 11.3c6.1 6.2 16.1 6.2 22.2 0l24.9-25.4V496c0 8.8 7 16 15.7 16h15.7c8.7 0 15.7-7.2 15.7-16v-46.1l24.9 25.4c6.1 6.2 16.1 6.2 22.2 0l11.1-11.3c6.1-6.2 6.1-16.4 0-22.6l-58.3-59.3v-84.5l71.9 42.2 21.3 81c2.2 8.5 10.9 13.6 19.3 11.3L375 428c8.4-2.3 13.4-11.1 11.1-19.6l-9.1-34.7 39.2 23c7.5 4.4 17.1 1.8 21.5-5.9l7.9-13.9c4.6-7.5 2.1-17.3-5.5-21.7z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h340c3.3 0 6 2.7 6 6v340c0 3.3-2.7 6-6 6z\"],\n    \"star\": [576, 512, [], \"f005\", \"M528.1 171.5L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6zM388.6 312.3l23.7 138.4L288 385.4l-124.3 65.3 23.7-138.4-100.6-98 139-20.2 62.2-126 62.2 126 139 20.2-100.6 98z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 385.3l-124.3 65.4 23.7-138.4-100.6-98 139-20.2 62.2-126V0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6v-54.3z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M448 348.106V80c0-26.51-21.49-48-48-48H48C21.49 32 0 53.49 0 80v351.988c0 26.51 21.49 48 48 48h268.118a48 48 0 0 0 33.941-14.059l83.882-83.882A48 48 0 0 0 448 348.106zm-128 80v-76.118h76.118L320 428.106zM400 80v223.988H296c-13.255 0-24 10.745-24 24v104H48V80h352z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm296-80v160c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M494.2 221.9l-59.8-40.5 13.7-71c2.6-13.2-1.6-26.8-11.1-36.4-9.6-9.5-23.2-13.7-36.2-11.1l-70.9 13.7-40.4-59.9c-15.1-22.3-51.9-22.3-67 0l-40.4 59.9-70.8-13.7C98 60.4 84.5 64.5 75 74.1c-9.5 9.6-13.7 23.1-11.1 36.3l13.7 71-59.8 40.5C6.6 229.5 0 242 0 255.5s6.7 26 17.8 33.5l59.8 40.5-13.7 71c-2.6 13.2 1.6 26.8 11.1 36.3 9.5 9.5 22.9 13.7 36.3 11.1l70.8-13.7 40.4 59.9C230 505.3 242.6 512 256 512s26-6.7 33.5-17.8l40.4-59.9 70.9 13.7c13.4 2.7 26.8-1.6 36.3-11.1 9.5-9.5 13.6-23.1 11.1-36.3l-13.7-71 59.8-40.5c11.1-7.5 17.8-20.1 17.8-33.5-.1-13.6-6.7-26.1-17.9-33.7zm-112.9 85.6l17.6 91.2-91-17.6L256 458l-51.9-77-90.9 17.6 17.6-91.2-76.8-52 76.8-52-17.6-91.2 91 17.6L256 53l51.9 76.9 91-17.6-17.6 91.1 76.8 52-76.8 52.1zM256 152c-57.3 0-104 46.7-104 104s46.7 104 104 104 104-46.7 104-104-46.7-104-104-104zm0 160c-30.9 0-56-25.1-56-56s25.1-56 56-56 56 25.1 56 56-25.1 56-56 56z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-176c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm-48-72c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M466.27 225.31c4.674-22.647.864-44.538-8.99-62.99 2.958-23.868-4.021-48.565-17.34-66.99C438.986 39.423 404.117 0 327 0c-7 0-15 .01-22.22.01C201.195.01 168.997 40 128 40h-10.845c-5.64-4.975-13.042-8-21.155-8H32C14.327 32 0 46.327 0 64v240c0 17.673 14.327 32 32 32h64c11.842 0 22.175-6.438 27.708-16h7.052c19.146 16.953 46.013 60.653 68.76 83.4 13.667 13.667 10.153 108.6 71.76 108.6 57.58 0 95.27-31.936 95.27-104.73 0-18.41-3.93-33.73-8.85-46.54h36.48c48.602 0 85.82-41.565 85.82-85.58 0-19.15-4.96-34.99-13.73-49.84zM64 296c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm330.18 16.73H290.19c0 37.82 28.36 55.37 28.36 94.54 0 23.75 0 56.73-47.27 56.73-18.91-18.91-9.46-66.18-37.82-94.54C206.9 342.89 167.28 272 138.92 272H128V85.83c53.611 0 100.001-37.82 171.64-37.82h37.82c35.512 0 60.82 17.12 53.12 65.9 15.2 8.16 26.5 36.44 13.94 57.57 21.581 20.384 18.699 51.065 5.21 65.62 9.45 0 22.36 18.91 22.27 37.81-.09 18.91-16.71 37.82-37.82 37.82z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M466.27 286.69C475.04 271.84 480 256 480 236.85c0-44.015-37.218-85.58-85.82-85.58H357.7c4.92-12.81 8.85-28.13 8.85-46.54C366.55 31.936 328.86 0 271.28 0c-61.607 0-58.093 94.933-71.76 108.6-22.747 22.747-49.615 66.447-68.76 83.4H32c-17.673 0-32 14.327-32 32v240c0 17.673 14.327 32 32 32h64c14.893 0 27.408-10.174 30.978-23.95 44.509 1.001 75.06 39.94 177.802 39.94 7.22 0 15.22.01 22.22.01 77.117 0 111.986-39.423 112.94-95.33 13.319-18.425 20.299-43.122 17.34-66.99 9.854-18.452 13.664-40.343 8.99-62.99zm-61.75 53.83c12.56 21.13 1.26 49.41-13.94 57.57 7.7 48.78-17.608 65.9-53.12 65.9h-37.82c-71.639 0-118.029-37.82-171.64-37.82V240h10.92c28.36 0 67.98-70.89 94.54-97.46 28.36-28.36 18.91-75.63 37.82-94.54 47.27 0 47.27 32.98 47.27 56.73 0 39.17-28.36 56.72-28.36 94.54h103.99c21.11 0 37.73 18.91 37.82 37.82.09 18.9-12.82 37.81-22.27 37.81 13.489 14.555 16.371 45.236-5.21 65.62zM88 432c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm101.8-262.2L295.6 256l62.2 62.2c4.7 4.7 4.7 12.3 0 17l-22.6 22.6c-4.7 4.7-12.3 4.7-17 0L256 295.6l-62.2 62.2c-4.7 4.7-12.3 4.7-17 0l-22.6-22.6c-4.7-4.7-4.7-12.3 0-17l62.2-62.2-62.2-62.2c-4.7-4.7-4.7-12.3 0-17l22.6-22.6c4.7-4.7 12.3-4.7 17 0l62.2 62.2 62.2-62.2c4.7-4.7 12.3-4.7 17 0l22.6 22.6c4.7 4.7 4.7 12.3 0 17z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm129.1-303.8c-3.8-4.4-10.3-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.8 1.6 15.3-2.5 3.8-4.5 3.9-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zM220 208c0-4.2-2.2-8.1-5.8-10.3l-80-48c-5-3-11.5-1.9-15.3 2.5-3.8 4.5-3.9 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.5 4.1 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3zm28 64c-45.4 0-100.9 38.3-107.8 93.3-1.5 11.8 6.9 21.6 15.5 17.9C178.4 373.5 212 368 248 368s69.6 5.5 92.3 15.2c8.5 3.7 17-6 15.5-17.9-6.9-55-62.4-93.3-107.8-93.3z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M268 416h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12zM432 80h-82.41l-34-56.7A48 48 0 0 0 274.41 0H173.59a48 48 0 0 0-41.16 23.3L98.41 80H16A16 16 0 0 0 0 96v16a16 16 0 0 0 16 16h16v336a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128h16a16 16 0 0 0 16-16V96a16 16 0 0 0-16-16zM171.84 50.91A6 6 0 0 1 177 48h94a6 6 0 0 1 5.15 2.91L293.61 80H154.39zM368 464H80V128h288zm-212-48h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12z\"],\n    \"user\": [448, 512, [], \"f007\", \"M313.6 304c-28.7 0-42.5 16-89.6 16-47.1 0-60.8-16-89.6-16C60.2 304 0 364.2 0 438.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-25.6c0-74.2-60.2-134.4-134.4-134.4zM400 464H48v-25.6c0-47.6 38.8-86.4 86.4-86.4 14.6 0 38.3 16 89.6 16 51.7 0 74.9-16 89.6-16 47.6 0 86.4 38.8 86.4 86.4V464zM224 288c79.5 0 144-64.5 144-144S303.5 0 224 0 80 64.5 80 144s64.5 144 144 144zm0-240c52.9 0 96 43.1 96 96s-43.1 96-96 96-96-43.1-96-96 43.1-96 96-96z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 104c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96zm0 144c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-240C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-49.7 0-95.1-18.3-130.1-48.4 14.9-23 40.4-38.6 69.6-39.5 20.8 6.4 40.6 9.6 60.5 9.6s39.7-3.1 60.5-9.6c29.2 1 54.7 16.5 69.6 39.5-35 30.1-80.4 48.4-130.1 48.4zm162.7-84.1c-24.4-31.4-62.1-51.9-105.1-51.9-10.2 0-26 9.6-57.6 9.6-31.5 0-47.4-9.6-57.6-9.6-42.9 0-80.6 20.5-105.1 51.9C61.9 339.2 48 299.2 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 43.2-13.9 83.2-37.3 115.9z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v340zM356.5 194.6L295.1 256l61.4 61.4c4.6 4.6 4.6 12.1 0 16.8l-22.3 22.3c-4.6 4.6-12.1 4.6-16.8 0L256 295.1l-61.4 61.4c-4.6 4.6-12.1 4.6-16.8 0l-22.3-22.3c-4.6-4.6-4.6-12.1 0-16.8l61.4-61.4-61.4-61.4c-4.6-4.6-4.6-12.1 0-16.8l22.3-22.3c4.6-4.6 12.1-4.6 16.8 0l61.4 61.4 61.4-61.4c4.6-4.6 12.1-4.6 16.8 0l22.3 22.3c4.7 4.6 4.7 12.1 0 16.8z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V192h416v234z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M480 480H32c-17.7 0-32-14.3-32-32s14.3-32 32-32h448c17.7 0 32 14.3 32 32s-14.3 32-32 32z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M464 0H144c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v320c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h48c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-96 464H48V256h320v208zm96-96h-48V144c0-26.5-21.5-48-48-48H144V48h320v320z\"]\n  };\n\n  bunker(function () {\n    defineIcons('far', icons);\n  });\n\n}());\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"ad\": [512, 512, [], \"f641\", \"M157.52 272h36.96L176 218.78 157.52 272zM352 256c-13.23 0-24 10.77-24 24s10.77 24 24 24 24-10.77 24-24-10.77-24-24-24zM464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM250.58 352h-16.94c-6.81 0-12.88-4.32-15.12-10.75L211.15 320h-70.29l-7.38 21.25A16 16 0 0 1 118.36 352h-16.94c-11.01 0-18.73-10.85-15.12-21.25L140 176.12A23.995 23.995 0 0 1 162.67 160h26.66A23.99 23.99 0 0 1 212 176.13l53.69 154.62c3.61 10.4-4.11 21.25-15.11 21.25zM424 336c0 8.84-7.16 16-16 16h-16c-4.85 0-9.04-2.27-11.98-5.68-8.62 3.66-18.09 5.68-28.02 5.68-39.7 0-72-32.3-72-72s32.3-72 72-72c8.46 0 16.46 1.73 24 4.42V176c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v160z\"],\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-228-32c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H118.4C106 384 96 375.4 96 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-352 96c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H86.4C74 384 64 375.4 64 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2zM512 312c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"adjust\": [512, 512, [], \"f042\", \"M8 256c0 136.966 111.033 248 248 248s248-111.034 248-248S392.966 8 256 8 8 119.033 8 256zm248 184V72c101.705 0 184 82.311 184 184 0 101.705-82.311 184-184 184z\"],\n    \"air-freshener\": [384, 512, [], \"f5d0\", \"M378.94 321.41L284.7 224h49.22c15.3 0 23.66-16.6 13.86-27.53L234.45 69.96c3.43-6.61 5.55-14 5.55-21.96 0-26.51-21.49-48-48-48s-48 21.49-48 48c0 7.96 2.12 15.35 5.55 21.96L36.22 196.47C26.42 207.4 34.78 224 50.08 224H99.3L5.06 321.41C-6.69 333.56 3.34 352 21.7 352H160v32H48c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h288c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16H224v-32h138.3c18.36 0 28.39-18.44 16.64-30.59zM192 31.98c8.85 0 16.02 7.17 16.02 16.02 0 8.84-7.17 16.02-16.02 16.02S175.98 56.84 175.98 48c0-8.85 7.17-16.02 16.02-16.02zM304 432v32H80v-32h224z\"],\n    \"align-center\": [448, 512, [], \"f037\", \"M432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM108.1 96h231.81A12.09 12.09 0 0 0 352 83.9V44.09A12.09 12.09 0 0 0 339.91 32H108.1A12.09 12.09 0 0 0 96 44.09V83.9A12.1 12.1 0 0 0 108.1 96zm231.81 256A12.09 12.09 0 0 0 352 339.9v-39.81A12.09 12.09 0 0 0 339.91 288H108.1A12.09 12.09 0 0 0 96 300.09v39.81a12.1 12.1 0 0 0 12.1 12.1z\"],\n    \"align-justify\": [448, 512, [], \"f039\", \"M432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"align-left\": [448, 512, [], \"f036\", \"M12.83 352h262.34A12.82 12.82 0 0 0 288 339.17v-38.34A12.82 12.82 0 0 0 275.17 288H12.83A12.82 12.82 0 0 0 0 300.83v38.34A12.82 12.82 0 0 0 12.83 352zm0-256h262.34A12.82 12.82 0 0 0 288 83.17V44.83A12.82 12.82 0 0 0 275.17 32H12.83A12.82 12.82 0 0 0 0 44.83v38.34A12.82 12.82 0 0 0 12.83 96zM432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"align-right\": [448, 512, [], \"f038\", \"M16 224h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm416 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-384H172.83A12.82 12.82 0 0 0 160 44.83v38.34A12.82 12.82 0 0 0 172.83 96h262.34A12.82 12.82 0 0 0 448 83.17V44.83A12.82 12.82 0 0 0 435.17 32zm0 256H172.83A12.82 12.82 0 0 0 160 300.83v38.34A12.82 12.82 0 0 0 172.83 352h262.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288z\"],\n    \"allergies\": [448, 512, [], \"f461\", \"M416 112c-17.6 0-32 14.4-32 32v72c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32s-32 14.4-32 32v152c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V32c0-17.6-14.4-32-32-32s-32 14.4-32 32v184c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32S96 46.4 96 64v241l-23.6-32.5c-13-17.9-38-21.8-55.9-8.8s-21.8 38-8.8 55.9l125.6 172.7c9 12.4 23.5 19.8 38.8 19.8h197.6c22.3 0 41.6-15.3 46.7-37l26.5-112.7c3.2-13.7 4.9-28.3 5.1-42.3V144c0-17.6-14.4-32-32-32zM176 416c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 32c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32-128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"ambulance\": [640, 512, [], \"f0f9\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm144-248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm176 248c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"american-sign-language-interpreting\": [640, 512, [], \"f2a3\", \"M290.547 189.039c-20.295-10.149-44.147-11.199-64.739-3.89 42.606 0 71.208 20.475 85.578 50.576 8.576 17.899-5.148 38.071-23.617 38.071 18.429 0 32.211 20.136 23.617 38.071-14.725 30.846-46.123 50.854-80.298 50.854-.557 0-94.471-8.615-94.471-8.615l-66.406 33.347c-9.384 4.693-19.815.379-23.895-7.781L1.86 290.747c-4.167-8.615-1.111-18.897 6.946-23.621l58.072-33.069L108 159.861c6.39-57.245 34.731-109.767 79.743-146.726 11.391-9.448 28.341-7.781 37.51 3.613 9.446 11.394 7.78 28.067-3.612 37.516-12.503 10.559-23.618 22.509-32.509 35.57 21.672-14.729 46.679-24.732 74.186-28.067 14.725-1.945 28.063 8.336 29.73 23.065 1.945 14.728-8.336 28.067-23.062 29.734-16.116 1.945-31.12 7.503-44.178 15.284 26.114-5.713 58.712-3.138 88.079 11.115 13.336 6.669 18.893 22.509 12.224 35.848-6.389 13.06-22.504 18.617-35.564 12.226zm-27.229 69.472c-6.112-12.505-18.338-20.286-32.231-20.286a35.46 35.46 0 0 0-35.565 35.57c0 21.428 17.808 35.57 35.565 35.57 13.893 0 26.119-7.781 32.231-20.286 4.446-9.449 13.614-15.006 23.339-15.284-9.725-.277-18.893-5.835-23.339-15.284zm374.821-37.237c4.168 8.615 1.111 18.897-6.946 23.621l-58.071 33.069L532 352.16c-6.39 57.245-34.731 109.767-79.743 146.726-10.932 9.112-27.799 8.144-37.51-3.613-9.446-11.394-7.78-28.067 3.613-37.516 12.503-10.559 23.617-22.509 32.508-35.57-21.672 14.729-46.679 24.732-74.186 28.067-10.021 2.506-27.552-5.643-29.73-23.065-1.945-14.728 8.336-28.067 23.062-29.734 16.116-1.946 31.12-7.503 44.178-15.284-26.114 5.713-58.712 3.138-88.079-11.115-13.336-6.669-18.893-22.509-12.224-35.848 6.389-13.061 22.505-18.619 35.565-12.227 20.295 10.149 44.147 11.199 64.739 3.89-42.606 0-71.208-20.475-85.578-50.576-8.576-17.899 5.148-38.071 23.617-38.071-18.429 0-32.211-20.136-23.617-38.071 14.033-29.396 44.039-50.887 81.966-50.854l92.803 8.615 66.406-33.347c9.408-4.704 19.828-.354 23.894 7.781l44.455 88.926zm-229.227-18.618c-13.893 0-26.119 7.781-32.231 20.286-4.446 9.449-13.614 15.006-23.339 15.284 9.725.278 18.893 5.836 23.339 15.284 6.112 12.505 18.338 20.286 32.231 20.286a35.46 35.46 0 0 0 35.565-35.57c0-21.429-17.808-35.57-35.565-35.57z\"],\n    \"anchor\": [576, 512, [], \"f13d\", \"M12.971 352h32.394C67.172 454.735 181.944 512 288 512c106.229 0 220.853-57.38 242.635-160h32.394c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0l-67.029 67.029c-7.56 7.56-2.206 20.485 8.485 20.485h35.146c-20.29 54.317-84.963 86.588-144.117 94.015V256h52c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-52v-5.47c37.281-13.178 63.995-48.725 64-90.518C384.005 43.772 341.605.738 289.37.01 235.723-.739 192 42.525 192 96c0 41.798 26.716 77.35 64 90.53V192h-52c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v190.015c-58.936-7.399-123.82-39.679-144.117-94.015h35.146c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0L4.485 331.515C-3.074 339.074 2.28 352 12.971 352zM288 64c17.645 0 32 14.355 32 32s-14.355 32-32 32-32-14.355-32-32 14.355-32 32-32z\"],\n    \"angle-double-down\": [320, 512, [], \"f103\", \"M143 256.3L7 120.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0L313 86.3c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.4 9.5-24.6 9.5-34 .1zm34 192l136-136c9.4-9.4 9.4-24.6 0-33.9l-22.6-22.6c-9.4-9.4-24.6-9.4-33.9 0L160 352.1l-96.4-96.4c-9.4-9.4-24.6-9.4-33.9 0L7 278.3c-9.4 9.4-9.4 24.6 0 33.9l136 136c9.4 9.5 24.6 9.5 34 .1z\"],\n    \"angle-double-left\": [448, 512, [], \"f100\", \"M223.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L319.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L393.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34zm-192 34l136 136c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9L127.9 256l96.4-96.4c9.4-9.4 9.4-24.6 0-33.9L201.7 103c-9.4-9.4-24.6-9.4-33.9 0l-136 136c-9.5 9.4-9.5 24.6-.1 34z\"],\n    \"angle-double-right\": [448, 512, [], \"f101\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34zm192-34l-136-136c-9.4-9.4-24.6-9.4-33.9 0l-22.6 22.6c-9.4 9.4-9.4 24.6 0 33.9l96.4 96.4-96.4 96.4c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l136-136c9.4-9.2 9.4-24.4 0-33.8z\"],\n    \"angle-double-up\": [320, 512, [], \"f102\", \"M177 255.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 351.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 425.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1zm-34-192L7 199.7c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l96.4-96.4 96.4 96.4c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9l-136-136c-9.2-9.4-24.4-9.4-33.8 0z\"],\n    \"angle-down\": [320, 512, [], \"f107\", \"M143 352.3L7 216.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.2 9.4-24.4 9.4-33.8 0z\"],\n    \"angle-left\": [256, 512, [], \"f104\", \"M31.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L127.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L201.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34z\"],\n    \"angle-right\": [256, 512, [], \"f105\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34z\"],\n    \"angle-up\": [320, 512, [], \"f106\", \"M177 159.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 255.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 329.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 240c0-9.3 4.1-17.5 10.5-23.4l-31-9.3c-8.5-2.5-13.3-11.5-10.7-19.9 2.5-8.5 11.4-13.2 19.9-10.7l80 24c8.5 2.5 13.3 11.5 10.7 19.9-2.1 6.9-8.4 11.4-15.3 11.4-.5 0-1.1-.2-1.7-.2.7 2.7 1.7 5.3 1.7 8.2 0 17.7-14.3 32-32 32S136 257.7 136 240zm168 154.2c-27.8-33.4-84.2-33.4-112.1 0-13.5 16.3-38.2-4.2-24.6-20.5 20-24 49.4-37.8 80.6-37.8s60.6 13.8 80.6 37.8c13.8 16.5-11.1 36.6-24.5 20.5zm76.6-186.9l-31 9.3c6.3 5.8 10.5 14.1 10.5 23.4 0 17.7-14.3 32-32 32s-32-14.3-32-32c0-2.9.9-5.6 1.7-8.2-.6.1-1.1.2-1.7.2-6.9 0-13.2-4.5-15.3-11.4-2.5-8.5 2.3-17.4 10.7-19.9l80-24c8.4-2.5 17.4 2.3 19.9 10.7 2.5 8.5-2.3 17.4-10.8 19.9z\"],\n    \"ankh\": [320, 512, [], \"f644\", \"M296 256h-44.62C272.46 222.01 288 181.65 288 144 288 55.63 230.69 0 160 0S32 55.63 32 144c0 37.65 15.54 78.01 36.62 112H24c-13.25 0-24 10.74-24 24v32c0 13.25 10.75 24 24 24h96v152c0 13.25 10.75 24 24 24h32c13.25 0 24-10.75 24-24V336h96c13.25 0 24-10.75 24-24v-32c0-13.26-10.75-24-24-24zM160 80c29.61 0 48 24.52 48 64 0 34.66-27.14 78.14-48 100.87-20.86-22.72-48-66.21-48-100.87 0-39.48 18.39-64 48-64z\"],\n    \"apple-alt\": [448, 512, [], \"f5d1\", \"M350.85 129c25.97 4.67 47.27 18.67 63.92 42 14.65 20.67 24.64 46.67 29.96 78 4.67 28.67 4.32 57.33-1 86-7.99 47.33-23.97 87-47.94 119-28.64 38.67-64.59 58-107.87 58-10.66 0-22.3-3.33-34.96-10-8.66-5.33-18.31-8-28.97-8s-20.3 2.67-28.97 8c-12.66 6.67-24.3 10-34.96 10-43.28 0-79.23-19.33-107.87-58-23.97-32-39.95-71.67-47.94-119-5.32-28.67-5.67-57.33-1-86 5.32-31.33 15.31-57.33 29.96-78 16.65-23.33 37.95-37.33 63.92-42 15.98-2.67 37.95-.33 65.92 7 23.97 6.67 44.28 14.67 60.93 24 16.65-9.33 36.96-17.33 60.93-24 27.98-7.33 49.96-9.67 65.94-7zm-54.94-41c-9.32 8.67-21.65 15-36.96 19-10.66 3.33-22.3 5-34.96 5l-14.98-1c-1.33-9.33-1.33-20 0-32 2.67-24 10.32-42.33 22.97-55 9.32-8.67 21.65-15 36.96-19 10.66-3.33 22.3-5 34.96-5l14.98 1 1 15c0 12.67-1.67 24.33-4.99 35-3.99 15.33-10.31 27.67-18.98 37z\"],\n    \"archive\": [512, 512, [], \"f187\", \"M32 448c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V160H32v288zm160-212c0-6.6 5.4-12 12-12h104c6.6 0 12 5.4 12 12v8c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-8zM480 32H32C14.3 32 0 46.3 0 64v48c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16V64c0-17.7-14.3-32-32-32z\"],\n    \"archway\": [576, 512, [], \"f557\", \"M560 448h-16V96H32v352H16.02c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16H176c8.84 0 16-7.16 16-16V320c0-53.02 42.98-96 96-96s96 42.98 96 96l.02 160v16c0 8.84 7.16 16 16 16H560c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm0-448H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h544c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM212 140v116h-70.9c-10.7 0-16.1 13-8.5 20.5l114.9 114.3c4.7 4.7 12.2 4.7 16.9 0l114.9-114.3c7.6-7.6 2.2-20.5-8.5-20.5H300V140c0-6.6-5.4-12-12-12h-64c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm116-292H256v-70.9c0-10.7-13-16.1-20.5-8.5L121.2 247.5c-4.7 4.7-4.7 12.2 0 16.9l114.3 114.9c7.6 7.6 20.5 2.2 20.5-8.5V300h116c6.6 0 12-5.4 12-12v-64c0-6.6-5.4-12-12-12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zM140 300h116v70.9c0 10.7 13 16.1 20.5 8.5l114.3-114.9c4.7-4.7 4.7-12.2 0-16.9l-114.3-115c-7.6-7.6-20.5-2.2-20.5 8.5V212H140c-6.6 0-12 5.4-12 12v64c0 6.6 5.4 12 12 12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm292 116V256h70.9c10.7 0 16.1-13 8.5-20.5L264.5 121.2c-4.7-4.7-12.2-4.7-16.9 0l-115 114.3c-7.6 7.6-2.2 20.5 8.5 20.5H212v116c0 6.6 5.4 12 12 12h64c6.6 0 12-5.4 12-12z\"],\n    \"arrow-circle-down\": [512, 512, [], \"f0ab\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-143.6-28.9L288 302.6V120c0-13.3-10.7-24-24-24h-16c-13.3 0-24 10.7-24 24v182.6l-72.4-75.5c-9.3-9.7-24.8-9.9-34.3-.4l-10.9 11c-9.4 9.4-9.4 24.6 0 33.9L239 404.3c9.4 9.4 24.6 9.4 33.9 0l132.7-132.7c9.4-9.4 9.4-24.6 0-33.9l-10.9-11c-9.5-9.5-25-9.3-34.3.4z\"],\n    \"arrow-circle-left\": [512, 512, [], \"f0a8\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm28.9-143.6L209.4 288H392c13.3 0 24-10.7 24-24v-16c0-13.3-10.7-24-24-24H209.4l75.5-72.4c9.7-9.3 9.9-24.8.4-34.3l-11-10.9c-9.4-9.4-24.6-9.4-33.9 0L107.7 239c-9.4 9.4-9.4 24.6 0 33.9l132.7 132.7c9.4 9.4 24.6 9.4 33.9 0l11-10.9c9.5-9.5 9.3-25-.4-34.3z\"],\n    \"arrow-circle-right\": [512, 512, [], \"f0a9\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm-28.9 143.6l75.5 72.4H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h182.6l-75.5 72.4c-9.7 9.3-9.9 24.8-.4 34.3l11 10.9c9.4 9.4 24.6 9.4 33.9 0L404.3 273c9.4-9.4 9.4-24.6 0-33.9L271.6 106.3c-9.4-9.4-24.6-9.4-33.9 0l-11 10.9c-9.5 9.6-9.3 25.1.4 34.4z\"],\n    \"arrow-circle-up\": [512, 512, [], \"f0aa\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm143.6 28.9l72.4-75.5V392c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24V209.4l72.4 75.5c9.3 9.7 24.8 9.9 34.3.4l10.9-11c9.4-9.4 9.4-24.6 0-33.9L273 107.7c-9.4-9.4-24.6-9.4-33.9 0L106.3 240.4c-9.4 9.4-9.4 24.6 0 33.9l10.9 11c9.6 9.5 25.1 9.3 34.4-.4z\"],\n    \"arrow-down\": [448, 512, [], \"f063\", \"M413.1 222.5l22.2 22.2c9.4 9.4 9.4 24.6 0 33.9L241 473c-9.4 9.4-24.6 9.4-33.9 0L12.7 278.6c-9.4-9.4-9.4-24.6 0-33.9l22.2-22.2c9.5-9.5 25-9.3 34.3.4L184 343.4V56c0-13.3 10.7-24 24-24h32c13.3 0 24 10.7 24 24v287.4l114.8-120.5c9.3-9.8 24.8-10 34.3-.4z\"],\n    \"arrow-left\": [448, 512, [], \"f060\", \"M257.5 445.1l-22.2 22.2c-9.4 9.4-24.6 9.4-33.9 0L7 273c-9.4-9.4-9.4-24.6 0-33.9L201.4 44.7c9.4-9.4 24.6-9.4 33.9 0l22.2 22.2c9.5 9.5 9.3 25-.4 34.3L136.6 216H424c13.3 0 24 10.7 24 24v32c0 13.3-10.7 24-24 24H136.6l120.5 114.8c9.8 9.3 10 24.8.4 34.3z\"],\n    \"arrow-right\": [448, 512, [], \"f061\", \"M190.5 66.9l22.2-22.2c9.4-9.4 24.6-9.4 33.9 0L441 239c9.4 9.4 9.4 24.6 0 33.9L246.6 467.3c-9.4 9.4-24.6 9.4-33.9 0l-22.2-22.2c-9.5-9.5-9.3-25 .4-34.3L311.4 296H24c-13.3 0-24-10.7-24-24v-32c0-13.3 10.7-24 24-24h287.4L190.9 101.2c-9.8-9.3-10-24.8-.4-34.3z\"],\n    \"arrow-up\": [448, 512, [], \"f062\", \"M34.9 289.5l-22.2-22.2c-9.4-9.4-9.4-24.6 0-33.9L207 39c9.4-9.4 24.6-9.4 33.9 0l194.3 194.3c9.4 9.4 9.4 24.6 0 33.9L413 289.4c-9.5 9.5-25 9.3-34.3-.4L264 168.6V456c0 13.3-10.7 24-24 24h-32c-13.3 0-24-10.7-24-24V168.6L69.2 289.1c-9.3 9.8-24.8 10-34.3.4z\"],\n    \"arrows-alt\": [512, 512, [], \"f0b2\", \"M352.201 425.775l-79.196 79.196c-9.373 9.373-24.568 9.373-33.941 0l-79.196-79.196c-15.119-15.119-4.411-40.971 16.971-40.97h51.162L228 284H127.196v51.162c0 21.382-25.851 32.09-40.971 16.971L7.029 272.937c-9.373-9.373-9.373-24.569 0-33.941L86.225 159.8c15.119-15.119 40.971-4.411 40.971 16.971V228H228V127.196h-51.23c-21.382 0-32.09-25.851-16.971-40.971l79.196-79.196c9.373-9.373 24.568-9.373 33.941 0l79.196 79.196c15.119 15.119 4.411 40.971-16.971 40.971h-51.162V228h100.804v-51.162c0-21.382 25.851-32.09 40.97-16.971l79.196 79.196c9.373 9.373 9.373 24.569 0 33.941L425.773 352.2c-15.119 15.119-40.971 4.411-40.97-16.971V284H284v100.804h51.23c21.382 0 32.09 25.851 16.971 40.971z\"],\n    \"arrows-alt-h\": [512, 512, [], \"f337\", \"M377.941 169.941V216H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.568 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296h243.882v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.568 0-33.941l-86.059-86.059c-15.119-15.12-40.971-4.412-40.971 16.97z\"],\n    \"arrows-alt-v\": [256, 512, [], \"f338\", \"M214.059 377.941H168V134.059h46.059c21.382 0 32.09-25.851 16.971-40.971L144.971 7.029c-9.373-9.373-24.568-9.373-33.941 0L24.971 93.088c-15.119 15.119-4.411 40.971 16.971 40.971H88v243.882H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.568 9.373 33.941 0l86.059-86.059c15.12-15.119 4.412-40.971-16.97-40.971z\"],\n    \"assistive-listening-systems\": [512, 512, [], \"f2a2\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm-80 236c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zM32 448c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm480-187.993c0-1.518-.012-3.025-.045-4.531C510.076 140.525 436.157 38.47 327.994 1.511c-14.633-4.998-30.549 2.809-35.55 17.442-5 14.633 2.81 30.549 17.442 35.55 85.906 29.354 144.61 110.513 146.077 201.953l.003.188c.026 1.118.033 2.236.033 3.363 0 15.464 12.536 28 28 28s28.001-12.536 28.001-28zM152.971 439.029l-80-80L39.03 392.97l80 80 33.941-33.941z\"],\n    \"asterisk\": [512, 512, [], \"f069\", \"M478.21 334.093L336 256l142.21-78.093c11.795-6.477 15.961-21.384 9.232-33.037l-19.48-33.741c-6.728-11.653-21.72-15.499-33.227-8.523L296 186.718l3.475-162.204C299.763 11.061 288.937 0 275.48 0h-38.96c-13.456 0-24.283 11.061-23.994 24.514L216 186.718 77.265 102.607c-11.506-6.976-26.499-3.13-33.227 8.523l-19.48 33.741c-6.728 11.653-2.562 26.56 9.233 33.037L176 256 33.79 334.093c-11.795 6.477-15.961 21.384-9.232 33.037l19.48 33.741c6.728 11.653 21.721 15.499 33.227 8.523L216 325.282l-3.475 162.204C212.237 500.939 223.064 512 236.52 512h38.961c13.456 0 24.283-11.061 23.995-24.514L296 325.282l138.735 84.111c11.506 6.976 26.499 3.13 33.227-8.523l19.48-33.741c6.728-11.653 2.563-26.559-9.232-33.036z\"],\n    \"at\": [512, 512, [], \"f1fa\", \"M256 8C118.941 8 8 118.919 8 256c0 137.059 110.919 248 248 248 48.154 0 95.342-14.14 135.408-40.223 12.005-7.815 14.625-24.288 5.552-35.372l-10.177-12.433c-7.671-9.371-21.179-11.667-31.373-5.129C325.92 429.757 291.314 440 256 440c-101.458 0-184-82.542-184-184S154.542 72 256 72c100.139 0 184 57.619 184 160 0 38.786-21.093 79.742-58.17 83.693-17.349-.454-16.91-12.857-13.476-30.024l23.433-121.11C394.653 149.75 383.308 136 368.225 136h-44.981a13.518 13.518 0 0 0-13.432 11.993l-.01.092c-14.697-17.901-40.448-21.775-59.971-21.775-74.58 0-137.831 62.234-137.831 151.46 0 65.303 36.785 105.87 96 105.87 26.984 0 57.369-15.637 74.991-38.333 9.522 34.104 40.613 34.103 70.71 34.103C462.609 379.41 504 307.798 504 232 504 95.653 394.023 8 256 8zm-21.68 304.43c-22.249 0-36.07-15.623-36.07-40.771 0-44.993 30.779-72.729 58.63-72.729 22.292 0 35.601 15.241 35.601 40.77 0 45.061-33.875 72.73-58.161 72.73z\"],\n    \"atlas\": [448, 512, [], \"f558\", \"M318.38 208h-39.09c-1.49 27.03-6.54 51.35-14.21 70.41 27.71-13.24 48.02-39.19 53.3-70.41zm0-32c-5.29-31.22-25.59-57.17-53.3-70.41 7.68 19.06 12.72 43.38 14.21 70.41h39.09zM224 97.31c-7.69 7.45-20.77 34.42-23.43 78.69h46.87c-2.67-44.26-15.75-71.24-23.44-78.69zm-41.08 8.28c-27.71 13.24-48.02 39.19-53.3 70.41h39.09c1.49-27.03 6.53-51.35 14.21-70.41zm0 172.82c-7.68-19.06-12.72-43.38-14.21-70.41h-39.09c5.28 31.22 25.59 57.17 53.3 70.41zM247.43 208h-46.87c2.66 44.26 15.74 71.24 23.43 78.69 7.7-7.45 20.78-34.43 23.44-78.69zM448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM224 64c70.69 0 128 57.31 128 128s-57.31 128-128 128S96 262.69 96 192 153.31 64 224 64zm160 384H96c-19.2 0-32-12.8-32-32s16-32 32-32h288v64z\"],\n    \"atom\": [448, 512, [], \"f5d2\", \"M413.03 256c40.13-54.89 41.51-98.62 25.14-128-10.91-19.52-40.54-50.73-116.33-41.88C300.36 34.89 267.64 0 224 0s-76.36 34.89-97.84 86.12C50.43 77.34 20.73 108.48 9.83 128c-16.38 29.4-15 73.09 25.14 128-40.13 54.89-41.51 98.62-25.14 128 29.21 52.34 101.68 43.58 116.33 41.88C147.63 477.1 180.36 512 224 512s76.37-34.9 97.84-86.12c14.64 1.7 87.11 10.46 116.33-41.88 16.38-29.4 15-73.09-25.14-128zM63.38 352c-4.03-7.21-.19-24.8 14.95-48.29 6.96 6.53 14.2 12.89 21.87 19.18 1.71 13.71 4 27.08 6.76 40.08-24.56.89-39.89-4.37-43.58-10.97zm36.82-162.88c-7.66 6.29-14.9 12.65-21.87 19.18-15.13-23.5-18.97-41.09-14.95-48.3 3.41-6.14 16.39-11.47 37.92-11.47 1.71 0 3.87.3 5.69.37a472.191 472.191 0 0 0-6.79 40.22zM224 64c9.47 0 22.2 13.52 33.86 37.26-11.19 3.7-22.44 8-33.86 12.86-11.42-4.86-22.67-9.16-33.86-12.86C201.8 77.52 214.53 64 224 64zm0 384c-9.47 0-22.2-13.52-33.86-37.26 11.19-3.7 22.44-8 33.86-12.86 11.42 4.86 22.67 9.16 33.86 12.86C246.2 434.48 233.47 448 224 448zm62.5-157.33c-26.7 19.08-46.14 29.33-62.5 37.48-16.35-8.14-35.8-18.41-62.5-37.48-1.99-27.79-1.99-41.54 0-69.33 26.67-19.05 46.13-29.32 62.5-37.48 16.39 8.17 35.86 18.44 62.5 37.48 1.98 27.78 1.99 41.53 0 69.33zM384.62 352c-3.67 6.62-19 11.82-43.58 10.95 2.76-13 5.05-26.37 6.76-40.06 7.66-6.29 14.9-12.65 21.87-19.18 15.13 23.49 18.97 41.08 14.95 48.29zm-14.95-143.71c-6.96-6.53-14.2-12.89-21.87-19.18a473.535 473.535 0 0 0-6.79-40.22c1.82-.07 3.97-.37 5.69-.37 21.52 0 34.51 5.34 37.92 11.47 4.02 7.22.18 24.81-14.95 48.3zM224 224c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"audio-description\": [512, 512, [], \"f29e\", \"M162.925 238.709l8.822 30.655h-25.606l9.041-30.652c1.277-4.421 2.651-9.994 3.872-15.245 1.22 5.251 2.594 10.823 3.871 15.242zm166.474-32.099h-14.523v98.781h14.523c29.776 0 46.175-17.678 46.175-49.776 0-32.239-17.49-49.005-46.175-49.005zM512 112v288c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48zM245.459 336.139l-57.097-168A12.001 12.001 0 0 0 177 160h-35.894a12.001 12.001 0 0 0-11.362 8.139l-57.097 168C70.003 343.922 75.789 352 84.009 352h29.133a12 12 0 0 0 11.535-8.693l8.574-29.906h51.367l8.793 29.977A12 12 0 0 0 204.926 352h29.172c8.22 0 14.006-8.078 11.361-15.861zm184.701-80.525c0-58.977-37.919-95.614-98.96-95.614h-57.366c-6.627 0-12 5.373-12 12v168c0 6.627 5.373 12 12 12H331.2c61.041 0 98.96-36.933 98.96-96.386z\"],\n    \"award\": [384, 512, [], \"f559\", \"M97.12 362.63c-8.69-8.69-4.16-6.24-25.12-11.85-9.51-2.55-17.87-7.45-25.43-13.32L1.2 448.7c-4.39 10.77 3.81 22.47 15.43 22.03l52.69-2.01L105.56 507c8 8.44 22.04 5.81 26.43-4.96l52.05-127.62c-10.84 6.04-22.87 9.58-35.31 9.58-19.5 0-37.82-7.59-51.61-21.37zM382.8 448.7l-45.37-111.24c-7.56 5.88-15.92 10.77-25.43 13.32-21.07 5.64-16.45 3.18-25.12 11.85-13.79 13.78-32.12 21.37-51.62 21.37-12.44 0-24.47-3.55-35.31-9.58L252 502.04c4.39 10.77 18.44 13.4 26.43 4.96l36.25-38.28 52.69 2.01c11.62.44 19.82-11.27 15.43-22.03zM263 340c15.28-15.55 17.03-14.21 38.79-20.14 13.89-3.79 24.75-14.84 28.47-28.98 7.48-28.4 5.54-24.97 25.95-45.75 10.17-10.35 14.14-25.44 10.42-39.58-7.47-28.38-7.48-24.42 0-52.83 3.72-14.14-.25-29.23-10.42-39.58-20.41-20.78-18.47-17.36-25.95-45.75-3.72-14.14-14.58-25.19-28.47-28.98-27.88-7.61-24.52-5.62-44.95-26.41-10.17-10.35-25-14.4-38.89-10.61-27.87 7.6-23.98 7.61-51.9 0-13.89-3.79-28.72.25-38.89 10.61-20.41 20.78-17.05 18.8-44.94 26.41-13.89 3.79-24.75 14.84-28.47 28.98-7.47 28.39-5.54 24.97-25.95 45.75-10.17 10.35-14.15 25.44-10.42 39.58 7.47 28.36 7.48 24.4 0 52.82-3.72 14.14.25 29.23 10.42 39.59 20.41 20.78 18.47 17.35 25.95 45.75 3.72 14.14 14.58 25.19 28.47 28.98C104.6 325.96 106.27 325 121 340c13.23 13.47 33.84 15.88 49.74 5.82a39.676 39.676 0 0 1 42.53 0c15.89 10.06 36.5 7.65 49.73-5.82zM97.66 175.96c0-53.03 42.24-96.02 94.34-96.02s94.34 42.99 94.34 96.02-42.24 96.02-94.34 96.02-94.34-42.99-94.34-96.02z\"],\n    \"baby\": [384, 512, [], \"f77c\", \"M192 160c44.2 0 80-35.8 80-80S236.2 0 192 0s-80 35.8-80 80 35.8 80 80 80zm-53.4 248.8l25.6-32-61.5-51.2L56.8 383c-11.4 14.2-11.7 34.4-.8 49l48 64c7.9 10.5 19.9 16 32 16 8.3 0 16.8-2.6 24-8 17.7-13.2 21.2-38.3 8-56l-29.4-39.2zm142.7-83.2l-61.5 51.2 25.6 32L216 448c-13.2 17.7-9.7 42.8 8 56 7.2 5.4 15.6 8 24 8 12.2 0 24.2-5.5 32-16l48-64c10.9-14.6 10.6-34.8-.8-49l-45.9-57.4zM376.7 145c-12.7-18.1-37.6-22.4-55.7-9.8l-40.6 28.5c-52.7 37-124.2 37-176.8 0L63 135.3C44.9 122.6 20 127 7.3 145-5.4 163.1-1 188 17 200.7l40.6 28.5c17 11.9 35.4 20.9 54.4 27.9V288h160v-30.8c19-7 37.4-16 54.4-27.9l40.6-28.5c18.1-12.8 22.4-37.7 9.7-55.8z\"],\n    \"baby-carriage\": [512, 512, [], \"f77d\", \"M144.8 17c-11.3-17.8-37.2-22.8-54-9.4C35.3 51.9 0 118 0 192h256L144.8 17zM496 96h-48c-35.3 0-64 28.7-64 64v64H0c0 50.6 23 96.4 60.3 130.7C25.7 363.6 0 394.7 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-8.9-1.8-17.2-4.4-25.2 21.6 5.9 44.6 9.2 68.4 9.2s46.9-3.3 68.4-9.2c-2.7 8-4.4 16.3-4.4 25.2 0 44.2 35.8 80 80 80s80-35.8 80-80c0-37.3-25.7-68.4-60.3-77.3C425 320.4 448 274.6 448 224v-64h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM80 464c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm320-32c0 17.6-14.4 32-32 32s-32-14.4-32-32 14.4-32 32-32 32 14.4 32 32z\"],\n    \"backspace\": [640, 512, [], \"f55a\", \"M576 64H205.26A63.97 63.97 0 0 0 160 82.75L9.37 233.37c-12.5 12.5-12.5 32.76 0 45.25L160 429.25c12 12 28.28 18.75 45.25 18.75H576c35.35 0 64-28.65 64-64V128c0-35.35-28.65-64-64-64zm-84.69 254.06c6.25 6.25 6.25 16.38 0 22.63l-22.62 22.62c-6.25 6.25-16.38 6.25-22.63 0L384 301.25l-62.06 62.06c-6.25 6.25-16.38 6.25-22.63 0l-22.62-22.62c-6.25-6.25-6.25-16.38 0-22.63L338.75 256l-62.06-62.06c-6.25-6.25-6.25-16.38 0-22.63l22.62-22.62c6.25-6.25 16.38-6.25 22.63 0L384 210.75l62.06-62.06c6.25-6.25 16.38-6.25 22.63 0l22.62 22.62c6.25 6.25 6.25 16.38 0 22.63L429.25 256l62.06 62.06z\"],\n    \"backward\": [512, 512, [], \"f04a\", \"M11.5 280.6l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2zm256 0l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2z\"],\n    \"bacon\": [576, 512, [], \"f7e5\", \"M218.92 336.39c34.89-34.89 44.2-59.7 54.05-86 10.61-28.29 21.59-57.54 61.37-97.34s69.05-50.77 97.35-61.38c23.88-9 46.64-17.68 76.79-45.37L470.81 8.91a31 31 0 0 0-40.18-2.83c-13.64 10.1-25.15 14.39-41 20.3C247 79.52 209.26 191.29 200.65 214.1c-29.75 78.83-89.55 94.68-98.72 98.09-24.86 9.26-54.73 20.38-91.07 50.36C-3 374-3.63 395 9.07 407.61l35.76 35.51C80 410.52 107 400.15 133 390.39c26.27-9.84 51.06-19.12 85.92-54zm348-232l-35.75-35.51c-35.19 32.63-62.18 43-88.25 52.79-26.26 9.85-51.06 19.16-85.95 54s-44.19 59.69-54 86C292.33 290 281.34 319.22 241.55 359s-69 50.73-97.3 61.32c-23.86 9-46.61 17.66-76.72 45.33l37.68 37.43a31 31 0 0 0 40.18 2.82c13.6-10.06 25.09-14.34 40.94-20.24 142.2-53 180-164.1 188.94-187.69C405 219.18 464.8 203.3 474 199.86c24.87-9.27 54.74-20.4 91.11-50.41 13.89-11.4 14.52-32.45 1.82-45.05z\"],\n    \"balance-scale\": [640, 512, [], \"f24e\", \"M256 336h-.02c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0C-2.06 328.75.02 320.33.02 336H0c0 44.18 57.31 80 128 80s128-35.82 128-80zM128 176l72 144H56l72-144zm511.98 160c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 320l72-144 72 144H440zm88 128H352V153.25c23.51-10.29 41.16-31.48 46.39-57.25H528c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H383.64C369.04 12.68 346.09 0 320 0s-49.04 12.68-63.64 32H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h129.61c5.23 25.76 22.87 46.96 46.39 57.25V448H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"balance-scale-left\": [640, 512, [], \"f515\", \"M528 448H352V153.25c20.42-8.94 36.1-26.22 43.38-47.47l132-44.26c8.38-2.81 12.89-11.88 10.08-20.26l-10.17-30.34C524.48 2.54 515.41-1.97 507.03.84L389.11 40.37C375.3 16.36 349.69 0 320 0c-44.18 0-80 35.82-80 80 0 3.43.59 6.71 1.01 10.03l-128.39 43.05c-8.38 2.81-12.89 11.88-10.08 20.26l10.17 30.34c2.81 8.38 11.88 12.89 20.26 10.08l142.05-47.63c4.07 2.77 8.43 5.12 12.99 7.12V496c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16v-32c-.01-8.84-7.17-16-16.01-16zm111.98-144c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 288l72-144 72 144H440zm-269.07-37.51c-17.65-35.29-68.19-35.36-85.87 0C-2.06 424.75.02 416.33.02 432H0c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-16.18 1.34-8.73-85.05-181.51zM56 416l72-144 72 144H56z\"],\n    \"balance-scale-right\": [640, 512, [], \"f516\", \"M96 464v32c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16V153.25c4.56-2 8.92-4.35 12.99-7.12l142.05 47.63c8.38 2.81 17.45-1.71 20.26-10.08l10.17-30.34c2.81-8.38-1.71-17.45-10.08-20.26l-128.4-43.05c.42-3.32 1.01-6.6 1.01-10.03 0-44.18-35.82-80-80-80-29.69 0-55.3 16.36-69.11 40.37L132.96.83c-8.38-2.81-17.45 1.71-20.26 10.08l-10.17 30.34c-2.81 8.38 1.71 17.45 10.08 20.26l132 44.26c7.28 21.25 22.96 38.54 43.38 47.47V448H112c-8.84 0-16 7.16-16 16zM0 304c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0C-1.32 295.27.02 287.82.02 304H0zm56-16l72-144 72 144H56zm328.02 144H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0-86.38 172.78-85.04 165.33-85.04 181.51zM440 416l72-144 72 144H440z\"],\n    \"ban\": [512, 512, [], \"f05e\", \"M256 8C119.034 8 8 119.033 8 256s111.034 248 248 248 248-111.034 248-248S392.967 8 256 8zm130.108 117.892c65.448 65.448 70 165.481 20.677 235.637L150.47 105.216c70.204-49.356 170.226-44.735 235.638 20.676zM125.892 386.108c-65.448-65.448-70-165.481-20.677-235.637L361.53 406.784c-70.203 49.356-170.226 44.736-235.638-20.676z\"],\n    \"band-aid\": [640, 512, [], \"f462\", \"M0 160v192c0 35.3 28.7 64 64 64h96V96H64c-35.3 0-64 28.7-64 64zm576-64h-96v320h96c35.3 0 64-28.7 64-64V160c0-35.3-28.7-64-64-64zM192 416h256V96H192v320zm176-232c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24z\"],\n    \"barcode\": [512, 512, [], \"f02a\", \"M0 448V64h18v384H0zm26.857-.273V64H36v383.727h-9.143zm27.143 0V64h8.857v383.727H54zm44.857 0V64h8.857v383.727h-8.857zm36 0V64h17.714v383.727h-17.714zm44.857 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm35.715 0V64h18v383.727h-18zm44.857 0V64h18v383.727h-18zm35.999 0V64h18.001v383.727h-18.001zm36.001 0V64h18.001v383.727h-18.001zm26.857 0V64h18v383.727h-18zm45.143 0V64h26.857v383.727h-26.857zm35.714 0V64h9.143v383.727H476zm18 .273V64h18v384h-18z\"],\n    \"bars\": [448, 512, [], \"f0c9\", \"M16 132h416c8.837 0 16-7.163 16-16V76c0-8.837-7.163-16-16-16H16C7.163 60 0 67.163 0 76v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16z\"],\n    \"baseball-ball\": [496, 512, [], \"f433\", \"M368.5 363.9l28.8-13.9c11.1 22.9 26 43.2 44.1 60.9 34-42.5 54.5-96.3 54.5-154.9 0-58.5-20.4-112.2-54.2-154.6-17.8 17.3-32.6 37.1-43.6 59.5l-28.7-14.1c12.8-26 30-49 50.8-69C375.6 34.7 315 8 248 8 181.1 8 120.5 34.6 75.9 77.7c20.7 19.9 37.9 42.9 50.7 68.8l-28.7 14.1c-11-22.3-25.7-42.1-43.5-59.4C20.4 143.7 0 197.4 0 256c0 58.6 20.4 112.3 54.4 154.7 18.2-17.7 33.2-38 44.3-61l28.8 13.9c-12.9 26.7-30.3 50.3-51.5 70.7 44.5 43.1 105.1 69.7 172 69.7 66.8 0 127.3-26.5 171.9-69.5-21.1-20.4-38.5-43.9-51.4-70.6zm-228.3-32l-30.5-9.8c14.9-46.4 12.7-93.8-.6-134l30.4-10c15 45.6 18 99.9.7 153.8zm216.3-153.4l30.4 10c-13.2 40.1-15.5 87.5-.6 134l-30.5 9.8c-17.3-54-14.3-108.3.7-153.8z\"],\n    \"basketball-ball\": [496, 512, [], \"f434\", \"M212.3 10.3c-43.8 6.3-86.2 24.1-122.2 53.8l77.4 77.4c27.8-35.8 43.3-81.2 44.8-131.2zM248 222L405.9 64.1c-42.4-35-93.6-53.5-145.5-56.1-1.2 63.9-21.5 122.3-58.7 167.7L248 222zM56.1 98.1c-29.7 36-47.5 78.4-53.8 122.2 50-1.5 95.5-17 131.2-44.8L56.1 98.1zm272.2 204.2c45.3-37.1 103.7-57.4 167.7-58.7-2.6-51.9-21.1-103.1-56.1-145.5L282 256l46.3 46.3zM248 290L90.1 447.9c42.4 34.9 93.6 53.5 145.5 56.1 1.3-64 21.6-122.4 58.7-167.7L248 290zm191.9 123.9c29.7-36 47.5-78.4 53.8-122.2-50.1 1.6-95.5 17.1-131.2 44.8l77.4 77.4zM167.7 209.7C122.3 246.9 63.9 267.3 0 268.4c2.6 51.9 21.1 103.1 56.1 145.5L214 256l-46.3-46.3zm116 292c43.8-6.3 86.2-24.1 122.2-53.8l-77.4-77.4c-27.7 35.7-43.2 81.2-44.8 131.2z\"],\n    \"bath\": [512, 512, [], \"f2cd\", \"M488 256H80V112c0-17.645 14.355-32 32-32 11.351 0 21.332 5.945 27.015 14.88-16.492 25.207-14.687 59.576 6.838 83.035-4.176 4.713-4.021 11.916.491 16.428l11.314 11.314c4.686 4.686 12.284 4.686 16.971 0l95.03-95.029c4.686-4.686 4.686-12.284 0-16.971l-11.314-11.314c-4.512-4.512-11.715-4.666-16.428-.491-17.949-16.469-42.294-21.429-64.178-15.365C163.281 45.667 139.212 32 112 32c-44.112 0-80 35.888-80 80v144h-8c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h8v32c0 28.43 12.362 53.969 32 71.547V456c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-8h256v8c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-32.453c19.638-17.578 32-43.117 32-71.547v-32h8c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"battery-empty\": [640, 512, [], \"f244\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48z\"],\n    \"battery-full\": [640, 512, [], \"f240\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-48 96H96v128h416V192z\"],\n    \"battery-half\": [640, 512, [], \"f242\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-240 96H96v128h224V192z\"],\n    \"battery-quarter\": [640, 512, [], \"f243\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-336 96H96v128h128V192z\"],\n    \"battery-three-quarters\": [640, 512, [], \"f241\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-144 96H96v128h320V192z\"],\n    \"bed\": [640, 512, [], \"f236\", \"M176 256c44.11 0 80-35.89 80-80s-35.89-80-80-80-80 35.89-80 80 35.89 80 80 80zm352-128H304c-8.84 0-16 7.16-16 16v144H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v352c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h512v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V240c0-61.86-50.14-112-112-112z\"],\n    \"beer\": [448, 512, [], \"f0fc\", \"M368 96h-48V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24v-42.11l80.606-35.977C429.396 365.063 448 336.388 448 304.86V176c0-44.112-35.888-80-80-80zm16 208.86a16.018 16.018 0 0 1-9.479 14.611L320 343.805V160h48c8.822 0 16 7.178 16 16v128.86zM208 384c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16zm-96 0c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64zm215.39-149.71c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.82 458.1l-90.62-70.05c.19-1.38.8-2.66.8-4.06.05-7.55-2.61-15.27-8.61-21.71-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-40.33 8.38-74.66 31.07-97.59 62.57L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.35 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.42-6.97 4.17-17.02-2.81-22.45zM157.23 251.54c-8.61 67.96-36.41 93.33-52.62 110.75-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h241.92L157.23 251.54zM320 512c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bezier-curve\": [640, 512, [], \"f55b\", \"M368 32h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM208 88h-84.75C113.75 64.56 90.84 48 64 48 28.66 48 0 76.65 0 112s28.66 64 64 64c26.84 0 49.75-16.56 59.25-40h79.73c-55.37 32.52-95.86 87.32-109.54 152h49.4c11.3-41.61 36.77-77.21 71.04-101.56-3.7-8.08-5.88-16.99-5.88-26.44V88zm-48 232H64c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zM576 48c-26.84 0-49.75 16.56-59.25 40H432v72c0 9.45-2.19 18.36-5.88 26.44 34.27 24.35 59.74 59.95 71.04 101.56h49.4c-13.68-64.68-54.17-119.48-109.54-152h79.73c9.5 23.44 32.41 40 59.25 40 35.34 0 64-28.65 64-64s-28.66-64-64-64zm0 272h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"bible\": [448, 512, [], \"f647\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM144 144c0-8.84 7.16-16 16-16h48V80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v48h48c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-48v112c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V192h-48c-8.84 0-16-7.16-16-16v-32zm236.8 304H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"bicycle\": [640, 512, [], \"f206\", \"M512.509 192.001c-16.373-.064-32.03 2.955-46.436 8.495l-77.68-125.153A24 24 0 0 0 368.001 64h-64c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h50.649l14.896 24H256.002v-16c0-8.837-7.163-16-16-16h-87.459c-13.441 0-24.777 10.999-24.536 24.437.232 13.044 10.876 23.563 23.995 23.563h48.726l-29.417 47.52c-13.433-4.83-27.904-7.483-42.992-7.52C58.094 191.83.412 249.012.002 319.236-.413 390.279 57.055 448 128.002 448c59.642 0 109.758-40.793 123.967-96h52.033a24 24 0 0 0 20.406-11.367L410.37 201.77l14.938 24.067c-25.455 23.448-41.385 57.081-41.307 94.437.145 68.833 57.899 127.051 126.729 127.719 70.606.685 128.181-55.803 129.255-125.996 1.086-70.941-56.526-129.72-127.476-129.996zM186.75 265.772c9.727 10.529 16.673 23.661 19.642 38.228h-43.306l23.664-38.228zM128.002 400c-44.112 0-80-35.888-80-80s35.888-80 80-80c5.869 0 11.586.653 17.099 1.859l-45.505 73.509C89.715 331.327 101.213 352 120.002 352h81.3c-12.37 28.225-40.562 48-73.3 48zm162.63-96h-35.624c-3.96-31.756-19.556-59.894-42.383-80.026L237.371 184h127.547l-74.286 120zm217.057 95.886c-41.036-2.165-74.049-35.692-75.627-76.755-.812-21.121 6.633-40.518 19.335-55.263l44.433 71.586c4.66 7.508 14.524 9.816 22.032 5.156l13.594-8.437c7.508-4.66 9.817-14.524 5.156-22.032l-44.468-71.643a79.901 79.901 0 0 1 19.858-2.497c44.112 0 80 35.888 80 80-.001 45.54-38.252 82.316-84.313 79.885z\"],\n    \"biking\": [640, 512, [], \"f84a\", \"M400 96a48 48 0 1 0-48-48 48 48 0 0 0 48 48zm-4 121a31.9 31.9 0 0 0 20 7h64a32 32 0 0 0 0-64h-52.78L356 103a31.94 31.94 0 0 0-40.81.68l-112 96a32 32 0 0 0 3.08 50.92L288 305.12V416a32 32 0 0 0 64 0V288a32 32 0 0 0-14.25-26.62l-41.36-27.57 58.25-49.92zm116 39a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64zM128 256a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64z\"],\n    \"binoculars\": [512, 512, [], \"f1e5\", \"M416 48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v48h96V48zM63.91 159.99C61.4 253.84 3.46 274.22 0 404v44c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V288h32V128H95.84c-17.63 0-31.45 14.37-31.93 31.99zm384.18 0c-.48-17.62-14.3-31.99-31.93-31.99H320v160h32v160c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-44c-3.46-129.78-61.4-150.16-63.91-244.01zM176 32h-64c-8.84 0-16 7.16-16 16v48h96V48c0-8.84-7.16-16-16-16zm48 256h64V128h-64v160z\"],\n    \"biohazard\": [576, 512, [], \"f780\", \"M287.9 112c18.6 0 36.2 3.8 52.8 9.6 13.3-10.3 23.6-24.3 29.5-40.7-25.2-10.9-53-17-82.2-17-29.1 0-56.9 6-82.1 16.9 5.9 16.4 16.2 30.4 29.5 40.7 16.5-5.7 34-9.5 52.5-9.5zM163.6 438.7c12-11.8 20.4-26.4 24.5-42.4-32.9-26.4-54.8-65.3-58.9-109.6-8.5-2.8-17.2-4.6-26.4-4.6-7.6 0-15.2 1-22.5 3.1 4.1 62.8 35.8 118 83.3 153.5zm224.2-42.6c4.1 16 12.5 30.7 24.5 42.5 47.4-35.5 79.1-90.7 83-153.5-7.2-2-14.7-3-22.2-3-9.2 0-18 1.9-26.6 4.7-4.1 44.2-26 82.9-58.7 109.3zm113.5-205c-17.6-10.4-36.3-16.6-55.3-19.9 6-17.7 10-36.4 10-56.2 0-41-14.5-80.8-41-112.2-2.5-3-6.6-3.7-10-1.8-3.3 1.9-4.8 6-3.6 9.7 4.5 13.8 6.6 26.3 6.6 38.5 0 67.8-53.8 122.9-120 122.9S168 117 168 49.2c0-12.1 2.2-24.7 6.6-38.5 1.2-3.7-.3-7.8-3.6-9.7-3.4-1.9-7.5-1.2-10 1.8C134.6 34.2 120 74 120 115c0 19.8 3.9 38.5 10 56.2-18.9 3.3-37.7 9.5-55.3 19.9-34.6 20.5-61 53.3-74.3 92.4-1.3 3.7.2 7.7 3.5 9.8 3.3 2 7.5 1.3 10-1.6 9.4-10.8 19-19.1 29.2-25.1 57.3-33.9 130.8-13.7 163.9 45 33.1 58.7 13.4 134-43.9 167.9-10.2 6.1-22 10.4-35.8 13.4-3.7.8-6.4 4.2-6.4 8.1.1 4 2.7 7.3 6.5 8 39.7 7.8 80.6.8 115.2-19.7 18-10.6 32.9-24.5 45.3-40.1 12.4 15.6 27.3 29.5 45.3 40.1 34.6 20.5 75.5 27.5 115.2 19.7 3.8-.7 6.4-4 6.5-8 0-3.9-2.6-7.3-6.4-8.1-13.9-2.9-25.6-7.3-35.8-13.4-57.3-33.9-77-109.2-43.9-167.9s106.6-78.9 163.9-45c10.2 6.1 19.8 14.3 29.2 25.1 2.5 2.9 6.7 3.6 10 1.6s4.8-6.1 3.5-9.8c-13.1-39.1-39.5-72-74.1-92.4zm-213.4 129c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"birthday-cake\": [448, 512, [], \"f1fd\", \"M448 384c-28.02 0-31.26-32-74.5-32-43.43 0-46.825 32-74.75 32-27.695 0-31.454-32-74.75-32-42.842 0-47.218 32-74.5 32-28.148 0-31.202-32-74.75-32-43.547 0-46.653 32-74.75 32v-80c0-26.5 21.5-48 48-48h16V112h64v144h64V112h64v144h64V112h64v144h16c26.5 0 48 21.5 48 48v80zm0 128H0v-96c43.356 0 46.767-32 74.75-32 27.951 0 31.253 32 74.75 32 42.843 0 47.217-32 74.5-32 28.148 0 31.201 32 74.75 32 43.357 0 46.767-32 74.75-32 27.488 0 31.252 32 74.5 32v96zM96 96c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40z\"],\n    \"blender\": [512, 512, [], \"f517\", \"M416 384H160c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-128 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm40-416h166.54L512 0H48C21.49 0 0 21.49 0 48v160c0 26.51 21.49 48 48 48h103.27l8.73 96h256l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H328c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM64 192V64h69.82l11.64 128H64z\"],\n    \"blender-phone\": [576, 512, [], \"f6b6\", \"M392 64h166.54L576 0H192v352h288l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H392c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM158.8 335.01l-25.78-63.26c-2.78-6.81-9.8-10.99-17.24-10.26l-45.03 4.42c-17.28-46.94-17.65-99.78 0-147.72l45.03 4.42c7.43.73 14.46-3.46 17.24-10.26l25.78-63.26c3.02-7.39.2-15.85-6.68-20.07l-39.28-24.1C98.51-3.87 80.09-.5 68.95 11.97c-92.57 103.6-92 259.55 2.1 362.49 9.87 10.8 29.12 12.48 41.65 4.8l39.41-24.18c6.89-4.22 9.7-12.67 6.69-20.07zM480 384H192c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-144 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"blind\": [384, 512, [], \"f29d\", \"M380.15 510.837a8 8 0 0 1-10.989-2.687l-125.33-206.427a31.923 31.923 0 0 0 12.958-9.485l126.048 207.608a8 8 0 0 1-2.687 10.991zM142.803 314.338l-32.54 89.485 36.12 88.285c6.693 16.36 25.377 24.192 41.733 17.501 16.357-6.692 24.193-25.376 17.501-41.734l-62.814-153.537zM96 88c24.301 0 44-19.699 44-44S120.301 0 96 0 52 19.699 52 44s19.699 44 44 44zm154.837 169.128l-120-152c-4.733-5.995-11.75-9.108-18.837-9.112V96H80v.026c-7.146.003-14.217 3.161-18.944 9.24L0 183.766v95.694c0 13.455 11.011 24.791 24.464 24.536C37.505 303.748 48 293.1 48 280v-79.766l16-20.571v140.698L9.927 469.055c-6.04 16.609 2.528 34.969 19.138 41.009 16.602 6.039 34.968-2.524 41.009-19.138L136 309.638V202.441l-31.406-39.816a4 4 0 1 1 6.269-4.971l102.3 129.217c9.145 11.584 24.368 11.339 33.708 3.965 10.41-8.216 12.159-23.334 3.966-33.708z\"],\n    \"blog\": [512, 512, [], \"f781\", \"M172.2 226.8c-14.6-2.9-28.2 8.9-28.2 23.8V301c0 10.2 7.1 18.4 16.7 22 18.2 6.8 31.3 24.4 31.3 45 0 26.5-21.5 48-48 48s-48-21.5-48-48V120c0-13.3-10.7-24-24-24H24c-13.3 0-24 10.7-24 24v248c0 89.5 82.1 160.2 175 140.7 54.4-11.4 98.3-55.4 109.7-109.7 17.4-82.9-37-157.2-112.5-172.2zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"bold\": [384, 512, [], \"f032\", \"M333.49 238a122 122 0 0 0 27-65.21C367.87 96.49 308 32 233.42 32H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h31.87v288H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h209.32c70.8 0 134.14-51.75 141-122.4 4.74-48.45-16.39-92.06-50.83-119.6zM145.66 112h87.76a48 48 0 0 1 0 96h-87.76zm87.76 288h-87.76V288h87.76a56 56 0 0 1 0 112z\"],\n    \"bolt\": [320, 512, [], \"f0e7\", \"M296 160H180.6l42.6-129.8C227.2 15 215.7 0 200 0H56C44 0 33.8 8.9 32.2 20.8l-32 240C-1.7 275.2 9.5 288 24 288h118.7L96.6 482.5c-3.6 15.2 8 29.5 23.3 29.5 8.4 0 16.4-4.4 20.8-12l176-304c9.3-15.9-2.2-36-20.7-36z\"],\n    \"bomb\": [512, 512, [], \"f1e2\", \"M440.5 88.5l-52 52L415 167c9.4 9.4 9.4 24.6 0 33.9l-17.4 17.4c11.8 26.1 18.4 55.1 18.4 85.6 0 114.9-93.1 208-208 208S0 418.9 0 304 93.1 96 208 96c30.5 0 59.5 6.6 85.6 18.4L311 97c9.4-9.4 24.6-9.4 33.9 0l26.5 26.5 52-52 17.1 17zM500 60h-24c-6.6 0-12 5.4-12 12s5.4 12 12 12h24c6.6 0 12-5.4 12-12s-5.4-12-12-12zM440 0c-6.6 0-12 5.4-12 12v24c0 6.6 5.4 12 12 12s12-5.4 12-12V12c0-6.6-5.4-12-12-12zm33.9 55l17-17c4.7-4.7 4.7-12.3 0-17-4.7-4.7-12.3-4.7-17 0l-17 17c-4.7 4.7-4.7 12.3 0 17 4.8 4.7 12.4 4.7 17 0zm-67.8 0c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17zm67.8 34c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17zM112 272c0-35.3 28.7-64 64-64 8.8 0 16-7.2 16-16s-7.2-16-16-16c-52.9 0-96 43.1-96 96 0 8.8 7.2 16 16 16s16-7.2 16-16z\"],\n    \"bone\": [640, 512, [], \"f5d7\", \"M598.88 244.56c25.2-12.6 41.12-38.36 41.12-66.53v-7.64C640 129.3 606.7 96 565.61 96c-32.02 0-60.44 20.49-70.57 50.86-7.68 23.03-11.6 45.14-38.11 45.14H183.06c-27.38 0-31.58-25.54-38.11-45.14C134.83 116.49 106.4 96 74.39 96 33.3 96 0 129.3 0 170.39v7.64c0 28.17 15.92 53.93 41.12 66.53 9.43 4.71 9.43 18.17 0 22.88C15.92 280.04 0 305.8 0 333.97v7.64C0 382.7 33.3 416 74.38 416c32.02 0 60.44-20.49 70.57-50.86 7.68-23.03 11.6-45.14 38.11-45.14h273.87c27.38 0 31.58 25.54 38.11 45.14C505.17 395.51 533.6 416 565.61 416c41.08 0 74.38-33.3 74.38-74.39v-7.64c0-28.18-15.92-53.93-41.12-66.53-9.42-4.71-9.42-18.17.01-22.88z\"],\n    \"bong\": [448, 512, [], \"f55c\", \"M302.5 512c23.18 0 44.43-12.58 56-32.66C374.69 451.26 384 418.75 384 384c0-36.12-10.08-69.81-27.44-98.62L400 241.94l9.38 9.38c6.25 6.25 16.38 6.25 22.63 0l11.3-11.32c6.25-6.25 6.25-16.38 0-22.63l-52.69-52.69c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l9.38 9.38-39.41 39.41c-11.56-11.37-24.53-21.33-38.65-29.51V63.74l15.97-.02c8.82-.01 15.97-7.16 15.98-15.98l.04-31.72C320 7.17 312.82-.01 303.97 0L80.03.26c-8.82.01-15.97 7.16-15.98 15.98l-.04 31.73c-.01 8.85 7.17 16.02 16.02 16.01L96 63.96v153.93C38.67 251.1 0 312.97 0 384c0 34.75 9.31 67.27 25.5 95.34C37.08 499.42 58.33 512 81.5 512h221zM120.06 259.43L144 245.56V63.91l96-.11v181.76l23.94 13.87c24.81 14.37 44.12 35.73 56.56 60.57h-257c12.45-24.84 31.75-46.2 56.56-60.57z\"],\n    \"book\": [448, 512, [], \"f02d\", \"M448 360V24c0-13.3-10.7-24-24-24H96C43 0 0 43 0 96v320c0 53 43 96 96 96h328c13.3 0 24-10.7 24-24v-16c0-7.5-3.5-14.3-8.9-18.7-4.2-15.4-4.2-59.3 0-74.7 5.4-4.3 8.9-11.1 8.9-18.6zM128 134c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm0 64c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm253.4 250H96c-17.7 0-32-14.3-32-32 0-17.6 14.4-32 32-32h285.4c-1.9 17.1-1.9 46.9 0 64z\"],\n    \"book-dead\": [448, 512, [], \"f6b7\", \"M272 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm176 222.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM240 56c44.2 0 80 28.7 80 64 0 20.9-12.7 39.2-32 50.9V184c0 8.8-7.2 16-16 16h-64c-8.8 0-16-7.2-16-16v-13.1c-19.3-11.7-32-30-32-50.9 0-35.3 35.8-64 80-64zM124.8 223.3l6.3-14.7c1.7-4.1 6.4-5.9 10.5-4.2l98.3 42.1 98.4-42.1c4.1-1.7 8.8.1 10.5 4.2l6.3 14.7c1.7 4.1-.1 8.8-4.2 10.5L280.6 264l70.3 30.1c4.1 1.7 5.9 6.4 4.2 10.5l-6.3 14.7c-1.7 4.1-6.4 5.9-10.5 4.2L240 281.4l-98.3 42.2c-4.1 1.7-8.8-.1-10.5-4.2l-6.3-14.7c-1.7-4.1.1-8.8 4.2-10.5l70.4-30.1-70.5-30.3c-4.1-1.7-5.9-6.4-4.2-10.5zm256 224.7H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8zM208 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16z\"],\n    \"book-medical\": [448, 512, [], \"f7e6\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16q0-9.6-9.6-19.2c-3.2-16-3.2-60.8 0-73.6q9.6-4.8 9.6-19.2zM144 168a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8v48a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8zm236.8 280H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8z\"],\n    \"book-open\": [576, 512, [], \"f518\", \"M542.22 32.05c-54.8 3.11-163.72 14.43-230.96 55.59-4.64 2.84-7.27 7.89-7.27 13.17v363.87c0 11.55 12.63 18.85 23.28 13.49 69.18-34.82 169.23-44.32 218.7-46.92 16.89-.89 30.02-14.43 30.02-30.66V62.75c.01-17.71-15.35-31.74-33.77-30.7zM264.73 87.64C197.5 46.48 88.58 35.17 33.78 32.05 15.36 31.01 0 45.04 0 62.75V400.6c0 16.24 13.13 29.78 30.02 30.66 49.49 2.6 149.59 12.11 218.77 46.95 10.62 5.35 23.21-1.94 23.21-13.46V100.63c0-5.29-2.62-10.14-7.27-12.99z\"],\n    \"book-reader\": [512, 512, [], \"f5da\", \"M352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96 42.98 96 96 96 96-42.98 96-96zM233.59 241.1c-59.33-36.32-155.43-46.3-203.79-49.05C13.55 191.13 0 203.51 0 219.14v222.8c0 14.33 11.59 26.28 26.49 27.05 43.66 2.29 131.99 10.68 193.04 41.43 9.37 4.72 20.48-1.71 20.48-11.87V252.56c-.01-4.67-2.32-8.95-6.42-11.46zm248.61-49.05c-48.35 2.74-144.46 12.73-203.78 49.05-4.1 2.51-6.41 6.96-6.41 11.63v245.79c0 10.19 11.14 16.63 20.54 11.9 61.04-30.72 149.32-39.11 192.97-41.4 14.9-.78 26.49-12.73 26.49-27.06V219.14c-.01-15.63-13.56-28.01-29.81-27.09z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M0 512V48C0 21.49 21.49 0 48 0h288c26.51 0 48 21.49 48 48v464L192 400 0 512z\"],\n    \"border-all\": [448, 512, [], \"f84c\", \"M416 32H32A32 32 0 0 0 0 64v384a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V64a32 32 0 0 0-32-32zm-32 64v128H256V96zm-192 0v128H64V96zM64 416V288h128v128zm192 0V288h128v128z\"],\n    \"border-none\": [448, 512, [], \"f850\", \"M240 224h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-288 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM240 320h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-384h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM48 224H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"border-style\": [448, 512, [], \"f853\", \"M240 416h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm192 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H32A32 32 0 0 0 0 64v400a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V96h368a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"bowling-ball\": [496, 512, [], \"f436\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM120 192c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64-96c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm48 144c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"box\": [512, 512, [], \"f466\", \"M509.5 184.6L458.9 32.8C452.4 13.2 434.1 0 413.4 0H272v192h238.7c-.4-2.5-.4-5-1.2-7.4zM240 0H98.6c-20.7 0-39 13.2-45.5 32.8L2.5 184.6c-.8 2.4-.8 4.9-1.2 7.4H240V0zM0 224v240c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V224H0z\"],\n    \"box-open\": [640, 512, [], \"f49e\", \"M425.7 256c-16.9 0-32.8-9-41.4-23.4L320 126l-64.2 106.6c-8.7 14.5-24.6 23.5-41.5 23.5-4.5 0-9-.6-13.3-1.9L64 215v178c0 14.7 10 27.5 24.2 31l216.2 54.1c10.2 2.5 20.9 2.5 31 0L551.8 424c14.2-3.6 24.2-16.4 24.2-31V215l-137 39.1c-4.3 1.3-8.8 1.9-13.3 1.9zm212.6-112.2L586.8 41c-3.1-6.2-9.8-9.8-16.7-8.9L320 64l91.7 152.1c3.8 6.3 11.4 9.3 18.5 7.3l197.9-56.5c9.9-2.9 14.7-13.9 10.2-23.1zM53.2 41L1.7 143.8c-4.6 9.2.3 20.2 10.1 23l197.9 56.5c7.1 2 14.7-1 18.5-7.3L320 64 69.8 32.1c-6.9-.8-13.5 2.7-16.6 8.9z\"],\n    \"boxes\": [576, 512, [], \"f468\", \"M560 288h-80v96l-32-21.3-32 21.3v-96h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16zm-384-64h224c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16h-80v96l-32-21.3L256 96V0h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16zm64 64h-80v96l-32-21.3L96 384v-96H16c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16z\"],\n    \"braille\": [640, 512, [], \"f2a1\", \"M128 256c0 35.346-28.654 64-64 64S0 291.346 0 256s28.654-64 64-64 64 28.654 64 64zM64 384c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352C28.654 32 0 60.654 0 96s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm224 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-320c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"brain\": [576, 512, [], \"f5dc\", \"M208 0c-29.9 0-54.7 20.5-61.8 48.2-.8 0-1.4-.2-2.2-.2-35.3 0-64 28.7-64 64 0 4.8.6 9.5 1.7 14C52.5 138 32 166.6 32 200c0 12.6 3.2 24.3 8.3 34.9C16.3 248.7 0 274.3 0 304c0 33.3 20.4 61.9 49.4 73.9-.9 4.6-1.4 9.3-1.4 14.1 0 39.8 32.2 72 72 72 4.1 0 8.1-.5 12-1.2 9.6 28.5 36.2 49.2 68 49.2 39.8 0 72-32.2 72-72V64c0-35.3-28.7-64-64-64zm368 304c0-29.7-16.3-55.3-40.3-69.1 5.2-10.6 8.3-22.3 8.3-34.9 0-33.4-20.5-62-49.7-74 1-4.5 1.7-9.2 1.7-14 0-35.3-28.7-64-64-64-.8 0-1.5.2-2.2.2C422.7 20.5 397.9 0 368 0c-35.3 0-64 28.6-64 64v376c0 39.8 32.2 72 72 72 31.8 0 58.4-20.7 68-49.2 3.9.7 7.9 1.2 12 1.2 39.8 0 72-32.2 72-72 0-4.8-.5-9.5-1.4-14.1 29-12 49.4-40.6 49.4-73.9z\"],\n    \"bread-slice\": [576, 512, [], \"f7ec\", \"M288 0C108 0 0 93.4 0 169.14 0 199.44 24.24 224 64 224v256c0 17.67 16.12 32 36 32h376c19.88 0 36-14.33 36-32V224c39.76 0 64-24.56 64-54.86C576 93.4 468 0 288 0z\"],\n    \"briefcase\": [512, 512, [], \"f0b1\", \"M320 336c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h416c25.6 0 48-22.4 48-48V288H320v48zm144-208h-80V80c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h512v-80c0-25.6-22.4-48-48-48zm-144 0H192V96h128v32z\"],\n    \"briefcase-medical\": [512, 512, [], \"f469\", \"M464 128h-80V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V176c0-26.5-21.5-48-48-48zM192 96h128v32H192V96zm160 248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48z\"],\n    \"broadcast-tower\": [640, 512, [], \"f519\", \"M150.94 192h33.73c11.01 0 18.61-10.83 14.86-21.18-4.93-13.58-7.55-27.98-7.55-42.82s2.62-29.24 7.55-42.82C203.29 74.83 195.68 64 184.67 64h-33.73c-7.01 0-13.46 4.49-15.41 11.23C130.64 92.21 128 109.88 128 128c0 18.12 2.64 35.79 7.54 52.76 1.94 6.74 8.39 11.24 15.4 11.24zM89.92 23.34C95.56 12.72 87.97 0 75.96 0H40.63c-6.27 0-12.14 3.59-14.74 9.31C9.4 45.54 0 85.65 0 128c0 24.75 3.12 68.33 26.69 118.86 2.62 5.63 8.42 9.14 14.61 9.14h34.84c12.02 0 19.61-12.74 13.95-23.37-49.78-93.32-16.71-178.15-.17-209.29zM614.06 9.29C611.46 3.58 605.6 0 599.33 0h-35.42c-11.98 0-19.66 12.66-14.02 23.25 18.27 34.29 48.42 119.42.28 209.23-5.72 10.68 1.8 23.52 13.91 23.52h35.23c6.27 0 12.13-3.58 14.73-9.29C630.57 210.48 640 170.36 640 128s-9.42-82.48-25.94-118.71zM489.06 64h-33.73c-11.01 0-18.61 10.83-14.86 21.18 4.93 13.58 7.55 27.98 7.55 42.82s-2.62 29.24-7.55 42.82c-3.76 10.35 3.85 21.18 14.86 21.18h33.73c7.02 0 13.46-4.49 15.41-11.24 4.9-16.97 7.53-34.64 7.53-52.76 0-18.12-2.64-35.79-7.54-52.76-1.94-6.75-8.39-11.24-15.4-11.24zm-116.3 100.12c7.05-10.29 11.2-22.71 11.2-36.12 0-35.35-28.63-64-63.96-64-35.32 0-63.96 28.65-63.96 64 0 13.41 4.15 25.83 11.2 36.12l-130.5 313.41c-3.4 8.15.46 17.52 8.61 20.92l29.51 12.31c8.15 3.4 17.52-.46 20.91-8.61L244.96 384h150.07l49.2 118.15c3.4 8.16 12.76 12.01 20.91 8.61l29.51-12.31c8.15-3.4 12-12.77 8.61-20.92l-130.5-313.41zM271.62 320L320 203.81 368.38 320h-96.76z\"],\n    \"broom\": [640, 512, [], \"f51a\", \"M256.47 216.77l86.73 109.18s-16.6 102.36-76.57 150.12C206.66 523.85 0 510.19 0 510.19s3.8-23.14 11-55.43l94.62-112.17c3.97-4.7-.87-11.62-6.65-9.5l-60.4 22.09c14.44-41.66 32.72-80.04 54.6-97.47 59.97-47.76 163.3-40.94 163.3-40.94zM636.53 31.03l-19.86-25c-5.49-6.9-15.52-8.05-22.41-2.56l-232.48 177.8-34.14-42.97c-5.09-6.41-15.14-5.21-18.59 2.21l-25.33 54.55 86.73 109.18 58.8-12.45c8-1.69 11.42-11.2 6.34-17.6l-34.09-42.92 232.48-177.8c6.89-5.48 8.04-15.53 2.55-22.44z\"],\n    \"brush\": [384, 512, [], \"f55d\", \"M352 0H32C14.33 0 0 14.33 0 32v224h384V32c0-17.67-14.33-32-32-32zM0 320c0 35.35 28.66 64 64 64h64v64c0 35.35 28.66 64 64 64s64-28.65 64-64v-64h64c35.34 0 64-28.65 64-64v-32H0v32zm192 104c13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24s-24-10.75-24-24c0-13.26 10.75-24 24-24z\"],\n    \"bug\": [512, 512, [], \"f188\", \"M511.988 288.9c-.478 17.43-15.217 31.1-32.653 31.1H424v16c0 21.864-4.882 42.584-13.6 61.145l60.228 60.228c12.496 12.497 12.496 32.758 0 45.255-12.498 12.497-32.759 12.496-45.256 0l-54.736-54.736C345.886 467.965 314.351 480 280 480V236c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v244c-34.351 0-65.886-12.035-90.636-32.108l-54.736 54.736c-12.498 12.497-32.759 12.496-45.256 0-12.496-12.497-12.496-32.758 0-45.255l60.228-60.228C92.882 378.584 88 357.864 88 336v-16H32.666C15.23 320 .491 306.33.013 288.9-.484 270.816 14.028 256 32 256h56v-58.745l-46.628-46.628c-12.496-12.497-12.496-32.758 0-45.255 12.498-12.497 32.758-12.497 45.256 0L141.255 160h229.489l54.627-54.627c12.498-12.497 32.758-12.497 45.256 0 12.496 12.497 12.496 32.758 0 45.255L424 197.255V256h56c17.972 0 32.484 14.816 31.988 32.9zM257 0c-61.856 0-112 50.144-112 112h224C369 50.144 318.856 0 257 0z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M436 480h-20V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v456H12c-6.627 0-12 5.373-12 12v20h448v-20c0-6.627-5.373-12-12-12zM128 76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76zm0 96c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40zm52 148h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12zm76 160h-64v-84c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v84zm64-172c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40z\"],\n    \"bullhorn\": [576, 512, [], \"f0a1\", \"M576 240c0-23.63-12.95-44.04-32-55.12V32.01C544 23.26 537.02 0 512 0c-7.12 0-14.19 2.38-19.98 7.02l-85.03 68.03C364.28 109.19 310.66 128 256 128H64c-35.35 0-64 28.65-64 64v96c0 35.35 28.65 64 64 64h33.7c-1.39 10.48-2.18 21.14-2.18 32 0 39.77 9.26 77.35 25.56 110.94 5.19 10.69 16.52 17.06 28.4 17.06h74.28c26.05 0 41.69-29.84 25.9-50.56-16.4-21.52-26.15-48.36-26.15-77.44 0-11.11 1.62-21.79 4.41-32H256c54.66 0 108.28 18.81 150.98 52.95l85.03 68.03a32.023 32.023 0 0 0 19.98 7.02c24.92 0 32-22.78 32-32V295.13C563.05 284.04 576 263.63 576 240zm-96 141.42l-33.05-26.44C392.95 311.78 325.12 288 256 288v-96c69.12 0 136.95-23.78 190.95-66.98L480 98.58v282.84z\"],\n    \"bullseye\": [496, 512, [], \"f140\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 432c-101.69 0-184-82.29-184-184 0-101.69 82.29-184 184-184 101.69 0 184 82.29 184 184 0 101.69-82.29 184-184 184zm0-312c-70.69 0-128 57.31-128 128s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm0 192c-35.29 0-64-28.71-64-64s28.71-64 64-64 64 28.71 64 64-28.71 64-64 64z\"],\n    \"burn\": [384, 512, [], \"f46a\", \"M192 0C79.7 101.3 0 220.9 0 300.5 0 425 79 512 192 512s192-87 192-211.5c0-79.9-80.2-199.6-192-300.5zm0 448c-56.5 0-96-39-96-94.8 0-13.5 4.6-61.5 96-161.2 91.4 99.7 96 147.7 96 161.2 0 55.8-39.5 94.8-96 94.8z\"],\n    \"bus\": [512, 512, [], \"f207\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM112 400c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm16-112c-17.67 0-32-14.33-32-32V128c0-17.67 14.33-32 32-32h256c17.67 0 32 14.33 32 32v128c0 17.67-14.33 32-32 32H128zm272 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"bus-alt\": [512, 512, [], \"f55e\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM160 72c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H168c-4.42 0-8-3.58-8-8V72zm-48 328c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128-112H128c-17.67 0-32-14.33-32-32v-96c0-17.67 14.33-32 32-32h112v160zm32 0V128h112c17.67 0 32 14.33 32 32v96c0 17.67-14.33 32-32 32H272zm128 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"business-time\": [640, 512, [], \"f64a\", \"M496 224c-79.59 0-144 64.41-144 144s64.41 144 144 144 144-64.41 144-144-64.41-144-144-144zm64 150.29c0 5.34-4.37 9.71-9.71 9.71h-60.57c-5.34 0-9.71-4.37-9.71-9.71v-76.57c0-5.34 4.37-9.71 9.71-9.71h12.57c5.34 0 9.71 4.37 9.71 9.71V352h38.29c5.34 0 9.71 4.37 9.71 9.71v12.58zM496 192c5.4 0 10.72.33 16 .81V144c0-25.6-22.4-48-48-48h-80V48c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h395.12c28.6-20.09 63.35-32 100.88-32zM320 96H192V64h128v32zm6.82 224H208c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h291.43C327.1 423.96 320 396.82 320 368c0-16.66 2.48-32.72 6.82-48z\"],\n    \"calculator\": [448, 512, [], \"f1ec\", \"M400 0H48C22.4 0 0 22.4 0 48v416c0 25.6 22.4 48 48 48h352c25.6 0 48-22.4 48-48V48c0-25.6-22.4-48-48-48zM128 435.2c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8V268.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v166.4zm0-256c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8V76.8C64 70.4 70.4 64 76.8 64h294.4c6.4 0 12.8 6.4 12.8 12.8v102.4z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm436-44v-36c0-26.5-21.5-48-48-48h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v36c0 6.6 5.4 12 12 12h424c6.6 0 12-5.4 12-12z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm320-196c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM192 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM64 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M436 160H12c-6.627 0-12-5.373-12-12v-36c0-26.51 21.49-48 48-48h48V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h128V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h48c26.51 0 48 21.49 48 48v36c0 6.627-5.373 12-12 12zM12 192h424c6.627 0 12 5.373 12 12v260c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V204c0-6.627 5.373-12 12-12zm333.296 95.947l-28.169-28.398c-4.667-4.705-12.265-4.736-16.97-.068L194.12 364.665l-45.98-46.352c-4.667-4.705-12.266-4.736-16.971-.068l-28.397 28.17c-4.705 4.667-4.736 12.265-.068 16.97l82.601 83.269c4.667 4.705 12.265 4.736 16.97.068l142.953-141.805c4.705-4.667 4.736-12.265.068-16.97z\"],\n    \"calendar-day\": [448, 512, [], \"f783\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h96c8.8 0 16 7.2 16 16v96c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-96zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm304 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H132c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h184z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm316 140c0-6.6-5.4-12-12-12h-60v-60c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v60h-60c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h60v60c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-60h60c6.6 0 12-5.4 12-12v-40z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm257.3 160l48.1-48.1c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0L224 306.7l-48.1-48.1c-4.7-4.7-12.3-4.7-17 0l-28.3 28.3c-4.7 4.7-4.7 12.3 0 17l48.1 48.1-48.1 48.1c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l48.1-48.1 48.1 48.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L269.3 352z\"],\n    \"calendar-week\": [448, 512, [], \"f784\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h288c8.8 0 16 7.2 16 16v64c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-64zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"camera\": [512, 512, [], \"f030\", \"M512 144v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V144c0-26.5 21.5-48 48-48h88l12.3-32.9c7-18.7 24.9-31.1 44.9-31.1h125.5c20 0 37.9 12.4 44.9 31.1L376 96h88c26.5 0 48 21.5 48 48zM376 288c0-66.2-53.8-120-120-120s-120 53.8-120 120 53.8 120 120 120 120-53.8 120-120zm-32 0c0 48.5-39.5 88-88 88s-88-39.5-88-88 39.5-88 88-88 88 39.5 88 88z\"],\n    \"camera-retro\": [512, 512, [], \"f083\", \"M48 32C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48H48zm0 32h106c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H38c-3.3 0-6-2.7-6-6V80c0-8.8 7.2-16 16-16zm426 96H38c-3.3 0-6-2.7-6-6v-36c0-3.3 2.7-6 6-6h138l30.2-45.3c1.1-1.7 3-2.7 5-2.7H464c8.8 0 16 7.2 16 16v74c0 3.3-2.7 6-6 6zM256 424c-66.2 0-120-53.8-120-120s53.8-120 120-120 120 53.8 120 120-53.8 120-120 120zm0-208c-48.5 0-88 39.5-88 88s39.5 88 88 88 88-39.5 88-88-39.5-88-88-88zm-48 104c-8.8 0-16-7.2-16-16 0-35.3 28.7-64 64-64 8.8 0 16 7.2 16 16s-7.2 16-16 16c-17.6 0-32 14.4-32 32 0 8.8-7.2 16-16 16z\"],\n    \"campground\": [640, 512, [], \"f6bb\", \"M624 448h-24.68L359.54 117.75l53.41-73.55c5.19-7.15 3.61-17.16-3.54-22.35l-25.9-18.79c-7.15-5.19-17.15-3.61-22.35 3.55L320 63.3 278.83 6.6c-5.19-7.15-15.2-8.74-22.35-3.55l-25.88 18.8c-7.15 5.19-8.74 15.2-3.54 22.35l53.41 73.55L40.68 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM320 288l116.36 160H203.64L320 288z\"],\n    \"candy-cane\": [512, 512, [], \"f786\", \"M497.5 92C469.6 33.1 411.8 0 352.4 0c-27.9 0-56.2 7.3-81.8 22.6L243.1 39c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5l27.5-16.4c5.1-3.1 10.8-4.5 16.4-4.5 10.9 0 21.5 5.6 27.5 15.6 9.1 15.1 4.1 34.8-11 43.9L15.6 397.6c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5L428.6 301c71.7-42.9 104.6-133.5 68.9-209zm-177.7 13l-2.5 1.5L296.8 45c9.7-4.7 19.8-8.1 30.3-10.2l20.6 61.8c-9.8.8-19.4 3.3-27.9 8.4zM145.9 431.8l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm107.5-63.9l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zM364.3 302l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm20.4-197.3l46-46c8.4 6.5 16 14.1 22.6 22.6L407.6 127c-5.7-9.3-13.7-16.9-22.9-22.3zm82.1 107.8l-59.5-19.8c3.2-5.3 5.8-10.9 7.4-17.1 1.1-4.5 1.7-9.1 1.8-13.6l60.4 20.1c-2.1 10.4-5.5 20.6-10.1 30.4z\"],\n    \"cannabis\": [512, 512, [], \"f55f\", \"M503.47 360.25c-1.56-.82-32.39-16.89-76.78-25.81 64.25-75.12 84.05-161.67 84.93-165.64 1.18-5.33-.44-10.9-4.3-14.77-3.03-3.04-7.12-4.7-11.32-4.7-1.14 0-2.29.12-3.44.38-3.88.85-86.54 19.59-160.58 79.76.01-1.46.01-2.93.01-4.4 0-118.79-59.98-213.72-62.53-217.7A15.973 15.973 0 0 0 256 0c-5.45 0-10.53 2.78-13.47 7.37-2.55 3.98-62.53 98.91-62.53 217.7 0 1.47.01 2.94.01 4.4-74.03-60.16-156.69-78.9-160.58-79.76-1.14-.25-2.29-.38-3.44-.38-4.2 0-8.29 1.66-11.32 4.7A15.986 15.986 0 0 0 .38 168.8c.88 3.97 20.68 90.52 84.93 165.64-44.39 8.92-75.21 24.99-76.78 25.81a16.003 16.003 0 0 0-.02 28.29c2.45 1.29 60.76 31.72 133.49 31.72 6.14 0 11.96-.1 17.5-.31-11.37 22.23-16.52 38.31-16.81 39.22-1.8 5.68-.29 11.89 3.91 16.11a16.019 16.019 0 0 0 16.1 3.99c1.83-.57 37.72-11.99 77.3-39.29V504c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-64.01c39.58 27.3 75.47 38.71 77.3 39.29a16.019 16.019 0 0 0 16.1-3.99c4.2-4.22 5.71-10.43 3.91-16.11-.29-.91-5.45-16.99-16.81-39.22 5.54.21 11.37.31 17.5.31 72.72 0 131.04-30.43 133.49-31.72 5.24-2.78 8.52-8.22 8.51-14.15-.01-5.94-3.29-11.39-8.53-14.15z\"],\n    \"capsules\": [576, 512, [], \"f46b\", \"M555.3 300.1L424.2 112.8C401.9 81 366.4 64 330.4 64c-22.6 0-45.5 6.7-65.5 20.7-19.7 13.8-33.7 32.8-41.5 53.8C220.5 79.2 172 32 112 32 50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V218.9c3.3 8.6 7.3 17.1 12.8 25L368 431.2c22.2 31.8 57.7 48.8 93.8 48.8 22.7 0 45.5-6.7 65.5-20.7 51.7-36.2 64.2-107.5 28-159.2zM160 256H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm194.8 44.9l-65.6-93.7c-7.7-11-10.7-24.4-8.3-37.6 2.3-13.2 9.7-24.8 20.7-32.5 8.5-6 18.5-9.1 28.8-9.1 16.5 0 31.9 8 41.3 21.5l65.6 93.7-82.5 57.7z\"],\n    \"car\": [512, 512, [], \"f1b9\", \"M499.99 176h-59.87l-16.64-41.6C406.38 91.63 365.57 64 319.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4L71.87 176H12.01C4.2 176-1.53 183.34.37 190.91l6 24C7.7 220.25 12.5 224 18.01 224h20.07C24.65 235.73 16 252.78 16 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-19.22-8.65-36.27-22.07-48H494c5.51 0 10.31-3.75 11.64-9.09l6-24c1.89-7.57-3.84-14.91-11.65-14.91zm-352.06-17.83c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L384 208H128l19.93-49.83zM96 319.8c-19.2 0-32-12.76-32-31.9S76.8 256 96 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S396.8 256 416 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-alt\": [480, 512, [], \"f5de\", \"M438.66 212.33l-11.24-28.1-19.93-49.83C390.38 91.63 349.57 64 303.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4l-19.93 49.83-11.24 28.1C17.22 221.5 0 244.66 0 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-27.34-17.22-50.5-41.34-59.67zm-306.73-54.16c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L368 208H112l19.93-49.83zM80 319.8c-19.2 0-32-12.76-32-31.9S60.8 256 80 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S380.8 256 400 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-battery\": [512, 512, [], \"f5df\", \"M480 128h-32V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v48H192V80c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v48H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zM192 264c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm256 0c0 4.42-3.58 8-8 8h-40v40c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-40h-40c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h40v-40c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v40h40c4.42 0 8 3.58 8 8v16z\"],\n    \"car-crash\": [640, 512, [], \"f5e1\", \"M143.25 220.81l-12.42 46.37c-3.01 11.25-3.63 22.89-2.41 34.39l-35.2 28.98c-6.57 5.41-16.31-.43-14.62-8.77l15.44-76.68c1.06-5.26-2.66-10.28-8-10.79l-77.86-7.55c-8.47-.82-11.23-11.83-4.14-16.54l65.15-43.3c4.46-2.97 5.38-9.15 1.98-13.29L21.46 93.22c-5.41-6.57.43-16.3 8.78-14.62l76.68 15.44c5.26 1.06 10.28-2.66 10.8-8l7.55-77.86c.82-8.48 11.83-11.23 16.55-4.14l43.3 65.14c2.97 4.46 9.15 5.38 13.29 1.98l60.4-49.71c6.57-5.41 16.3.43 14.62 8.77L262.1 86.38c-2.71 3.05-5.43 6.09-7.91 9.4l-32.15 42.97-10.71 14.32c-32.73 8.76-59.18 34.53-68.08 67.74zm494.57 132.51l-12.42 46.36c-3.13 11.68-9.38 21.61-17.55 29.36a66.876 66.876 0 0 1-8.76 7l-13.99 52.23c-1.14 4.27-3.1 8.1-5.65 11.38-7.67 9.84-20.74 14.68-33.54 11.25L515 502.62c-17.07-4.57-27.2-22.12-22.63-39.19l8.28-30.91-247.28-66.26-8.28 30.91c-4.57 17.07-22.12 27.2-39.19 22.63l-30.91-8.28c-12.8-3.43-21.7-14.16-23.42-26.51-.57-4.12-.35-8.42.79-12.68l13.99-52.23a66.62 66.62 0 0 1-4.09-10.45c-3.2-10.79-3.65-22.52-.52-34.2l12.42-46.37c5.31-19.8 19.36-34.83 36.89-42.21a64.336 64.336 0 0 1 18.49-4.72l18.13-24.23 32.15-42.97c3.45-4.61 7.19-8.9 11.2-12.84 8-7.89 17.03-14.44 26.74-19.51 4.86-2.54 9.89-4.71 15.05-6.49 10.33-3.58 21.19-5.63 32.24-6.04 11.05-.41 22.31.82 33.43 3.8l122.68 32.87c11.12 2.98 21.48 7.54 30.85 13.43a111.11 111.11 0 0 1 34.69 34.5c8.82 13.88 14.64 29.84 16.68 46.99l6.36 53.29 3.59 30.05a64.49 64.49 0 0 1 22.74 29.93c4.39 11.88 5.29 25.19 1.75 38.39zM255.58 234.34c-18.55-4.97-34.21 4.04-39.17 22.53-4.96 18.49 4.11 34.12 22.65 39.09 18.55 4.97 45.54 15.51 50.49-2.98 4.96-18.49-15.43-53.67-33.97-58.64zm290.61 28.17l-6.36-53.29c-.58-4.87-1.89-9.53-3.82-13.86-5.8-12.99-17.2-23.01-31.42-26.82l-122.68-32.87a48.008 48.008 0 0 0-50.86 17.61l-32.15 42.97 172 46.08 75.29 20.18zm18.49 54.65c-18.55-4.97-53.8 15.31-58.75 33.79-4.95 18.49 23.69 22.86 42.24 27.83 18.55 4.97 34.21-4.04 39.17-22.53 4.95-18.48-4.11-34.12-22.66-39.09z\"],\n    \"car-side\": [640, 512, [], \"f5e4\", \"M544 192h-16L419.22 56.02A64.025 64.025 0 0 0 369.24 32H155.33c-26.17 0-49.7 15.93-59.42 40.23L48 194.26C20.44 201.4 0 226.21 0 256v112c0 8.84 7.16 16 16 16h48c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h48c8.84 0 16-7.16 16-16v-80c0-53.02-42.98-96-96-96zM160 432c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm72-240H116.93l38.4-96H232v96zm48 0V96h89.24l76.8 96H280zm200 240c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"caret-down\": [320, 512, [], \"f0d7\", \"M31.3 192h257.3c17.8 0 26.7 21.5 14.1 34.1L174.1 354.8c-7.8 7.8-20.5 7.8-28.3 0L17.2 226.1C4.6 213.5 13.5 192 31.3 192z\"],\n    \"caret-left\": [192, 512, [], \"f0d9\", \"M192 127.338v257.324c0 17.818-21.543 26.741-34.142 14.142L29.196 270.142c-7.81-7.81-7.81-20.474 0-28.284l128.662-128.662c12.599-12.6 34.142-3.676 34.142 14.142z\"],\n    \"caret-right\": [192, 512, [], \"f0da\", \"M0 384.662V127.338c0-17.818 21.543-26.741 34.142-14.142l128.662 128.662c7.81 7.81 7.81 20.474 0 28.284L34.142 398.804C21.543 411.404 0 402.48 0 384.662z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM92.5 220.5l123 123c4.7 4.7 12.3 4.7 17 0l123-123c7.6-7.6 2.2-20.5-8.5-20.5H101c-10.7 0-16.1 12.9-8.5 20.5z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM259.515 124.485l-123.03 123.03c-4.686 4.686-4.686 12.284 0 16.971l123.029 123.029c7.56 7.56 20.485 2.206 20.485-8.485V132.971c.001-10.691-12.925-16.045-20.484-8.486z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M48 32h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48zm140.485 355.515l123.029-123.029c4.686-4.686 4.686-12.284 0-16.971l-123.029-123.03c-7.56-7.56-20.485-2.206-20.485 8.485v246.059c0 10.691 12.926 16.045 20.485 8.486z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M0 432V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48zm355.515-140.485l-123.03-123.03c-4.686-4.686-12.284-4.686-16.971 0L92.485 291.515c-7.56 7.56-2.206 20.485 8.485 20.485h246.059c10.691 0 16.045-12.926 8.486-20.485z\"],\n    \"caret-up\": [320, 512, [], \"f0d8\", \"M288.662 352H31.338c-17.818 0-26.741-21.543-14.142-34.142l128.662-128.662c7.81-7.81 20.474-7.81 28.284 0l128.662 128.662c12.6 12.599 3.676 34.142-14.142 34.142z\"],\n    \"carrot\": [512, 512, [], \"f787\", \"M298.2 156.6c-52.7-25.7-114.5-10.5-150.2 32.8l55.2 55.2c6.3 6.3 6.3 16.4 0 22.6-3.1 3.1-7.2 4.7-11.3 4.7s-8.2-1.6-11.3-4.7L130.4 217 2.3 479.7c-2.9 6-3.1 13.3 0 19.7 5.4 11.1 18.9 15.7 30 10.3l133.6-65.2-49.2-49.2c-6.3-6.2-6.3-16.4 0-22.6 6.3-6.2 16.4-6.2 22.6 0l57 57 102-49.8c24-11.7 44.5-31.3 57.1-57.1 30.1-61.7 4.5-136.1-57.2-166.2zm92.1-34.9C409.8 81 399.7 32.9 360 0c-50.3 41.7-52.5 107.5-7.9 151.9l8 8c44.4 44.6 110.3 42.4 151.9-7.9-32.9-39.7-81-49.8-121.7-30.3z\"],\n    \"cart-arrow-down\": [576, 512, [], \"f218\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM403.029 192H360v-60c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v60h-43.029c-10.691 0-16.045 12.926-8.485 20.485l67.029 67.029c4.686 4.686 12.284 4.686 16.971 0l67.029-67.029c7.559-7.559 2.205-20.485-8.486-20.485z\"],\n    \"cart-plus\": [576, 512, [], \"f217\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM408 168h-48v-40c0-8.837-7.163-16-16-16h-16c-8.837 0-16 7.163-16 16v40h-48c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h48v40c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-40h48c8.837 0 16-7.163 16-16v-16c0-8.837-7.163-16-16-16z\"],\n    \"cash-register\": [512, 512, [], \"f788\", \"M511.1 378.8l-26.7-160c-2.6-15.4-15.9-26.7-31.6-26.7H208v-64h96c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h96v64H59.1c-15.6 0-29 11.3-31.6 26.7L.8 378.7c-.6 3.5-.9 7-.9 10.5V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-90.7c.1-3.5-.2-7-.8-10.5zM280 248c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16zm-32 64h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16zm-32-80c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16zM80 80V48h192v32H80zm40 200h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16zm16 64v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16zm216 112c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16zm24-112c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16zm48-80c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16z\"],\n    \"cat\": [512, 512, [], \"f6be\", \"M290.59 192c-20.18 0-106.82 1.98-162.59 85.95V192c0-52.94-43.06-96-96-96-17.67 0-32 14.33-32 32s14.33 32 32 32c17.64 0 32 14.36 32 32v256c0 35.3 28.7 64 64 64h176c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-32l128-96v144c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V289.86c-10.29 2.67-20.89 4.54-32 4.54-61.81 0-113.52-44.05-125.41-102.4zM448 96h-64l-64-64v134.4c0 53.02 42.98 96 96 96s96-42.98 96-96V32l-64 64zm-72 80c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm80 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"certificate\": [512, 512, [], \"f0a3\", \"M458.622 255.92l45.985-45.005c13.708-12.977 7.316-36.039-10.664-40.339l-62.65-15.99 17.661-62.015c4.991-17.838-11.829-34.663-29.661-29.671l-61.994 17.667-15.984-62.671C337.085.197 313.765-6.276 300.99 7.228L256 53.57 211.011 7.229c-12.63-13.351-36.047-7.234-40.325 10.668l-15.984 62.671-61.995-17.667C74.87 57.907 58.056 74.738 63.046 92.572l17.661 62.015-62.65 15.99C.069 174.878-6.31 197.944 7.392 210.915l45.985 45.005-45.985 45.004c-13.708 12.977-7.316 36.039 10.664 40.339l62.65 15.99-17.661 62.015c-4.991 17.838 11.829 34.663 29.661 29.671l61.994-17.667 15.984 62.671c4.439 18.575 27.696 24.018 40.325 10.668L256 458.61l44.989 46.001c12.5 13.488 35.987 7.486 40.325-10.668l15.984-62.671 61.994 17.667c17.836 4.994 34.651-11.837 29.661-29.671l-17.661-62.015 62.65-15.99c17.987-4.302 24.366-27.367 10.664-40.339l-45.984-45.004z\"],\n    \"chair\": [448, 512, [], \"f6c0\", \"M112 128c0-29.5 16.2-55 40-68.9V256h48V48h48v208h48V59.1c23.8 13.9 40 39.4 40 68.9v128h48V128C384 57.3 326.7 0 256 0h-64C121.3 0 64 57.3 64 128v128h48zm334.3 213.9l-10.7-32c-4.4-13.1-16.6-21.9-30.4-21.9H42.7c-13.8 0-26 8.8-30.4 21.9l-10.7 32C-5.2 362.6 10.2 384 32 384v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384h256v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384c21.8 0 37.2-21.4 30.3-42.1z\"],\n    \"chalkboard\": [640, 512, [], \"f51b\", \"M96 64h448v352h64V40c0-22.06-17.94-40-40-40H72C49.94 0 32 17.94 32 40v376h64V64zm528 384H480v-64H288v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chalkboard-teacher\": [640, 512, [], \"f51c\", \"M208 352c-2.39 0-4.78.35-7.06 1.09C187.98 357.3 174.35 360 160 360c-14.35 0-27.98-2.7-40.95-6.91-2.28-.74-4.66-1.09-7.05-1.09C49.94 352-.33 402.48 0 464.62.14 490.88 21.73 512 48 512h224c26.27 0 47.86-21.12 48-47.38.33-62.14-49.94-112.62-112-112.62zm-48-32c53.02 0 96-42.98 96-96s-42.98-96-96-96-96 42.98-96 96 42.98 96 96 96zM592 0H208c-26.47 0-48 22.25-48 49.59V96c23.42 0 45.1 6.78 64 17.8V64h352v288h-64v-64H384v64h-76.24c19.1 16.69 33.12 38.73 39.69 64H592c26.47 0 48-22.25 48-49.59V49.59C640 22.25 618.47 0 592 0z\"],\n    \"charging-station\": [576, 512, [], \"f5e7\", \"M336 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h320c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm208-320V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-32V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-16c-8.84 0-16 7.16-16 16v32c0 35.76 23.62 65.69 56 75.93v118.49c0 13.95-9.5 26.92-23.26 29.19C431.22 402.5 416 388.99 416 372v-28c0-48.6-39.4-88-88-88h-8V64c0-35.35-28.65-64-64-64H96C60.65 0 32 28.65 32 64v352h288V304h8c22.09 0 40 17.91 40 40v24.61c0 39.67 28.92 75.16 68.41 79.01C481.71 452.05 520 416.41 520 372V251.93c32.38-10.24 56-40.17 56-75.93v-32c0-8.84-7.16-16-16-16h-16zm-283.91 47.76l-93.7 139c-2.2 3.33-6.21 5.24-10.39 5.24-7.67 0-13.47-6.28-11.67-12.92L167.35 224H108c-7.25 0-12.85-5.59-11.89-11.89l16-107C112.9 99.9 117.98 96 124 96h68c7.88 0 13.62 6.54 11.6 13.21L192 160h57.7c9.24 0 15.01 8.78 10.39 15.76z\"],\n    \"chart-area\": [512, 512, [], \"f1fe\", \"M500 384c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v308h436zM372.7 159.5L288 216l-85.3-113.7c-5.1-6.8-15.5-6.3-19.9 1L96 248v104h384l-89.9-187.8c-3.2-6.5-11.4-8.7-17.4-4.7z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M332.8 320h38.4c6.4 0 12.8-6.4 12.8-12.8V172.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V76.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-288 0h38.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zM496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chart-line\": [512, 512, [], \"f201\", \"M496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM464 96H345.94c-21.38 0-32.09 25.85-16.97 40.97l32.4 32.4L288 242.75l-73.37-73.37c-12.5-12.5-32.76-12.5-45.25 0l-68.69 68.69c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L192 237.25l73.37 73.37c12.5 12.5 32.76 12.5 45.25 0l96-96 32.4 32.4c15.12 15.12 40.97 4.41 40.97-16.97V112c.01-8.84-7.15-16-15.99-16z\"],\n    \"chart-pie\": [544, 512, [], \"f200\", \"M527.79 288H290.5l158.03 158.03c6.04 6.04 15.98 6.53 22.19.68 38.7-36.46 65.32-85.61 73.13-140.86 1.34-9.46-6.51-17.85-16.06-17.85zm-15.83-64.8C503.72 103.74 408.26 8.28 288.8.04 279.68-.59 272 7.1 272 16.24V240h223.77c9.14 0 16.82-7.68 16.19-16.8zM224 288V50.71c0-9.55-8.39-17.4-17.84-16.06C86.99 51.49-4.1 155.6.14 280.37 4.5 408.51 114.83 513.59 243.03 511.98c50.4-.63 96.97-16.87 135.26-44.03 7.9-5.6 8.42-17.23 1.57-24.08L224 288z\"],\n    \"check\": [512, 512, [], \"f00c\", \"M173.898 439.404l-166.4-166.4c-9.997-9.997-9.997-26.206 0-36.204l36.203-36.204c9.997-9.998 26.207-9.998 36.204 0L192 312.69 432.095 72.596c9.997-9.997 26.207-9.997 36.204 0l36.203 36.204c9.997 9.997 9.997 26.206 0 36.204l-294.4 294.401c-9.998 9.997-26.207 9.997-36.204-.001z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM227.314 387.314l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.249-16.379-6.249-22.628 0L216 308.118l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.249 16.379 6.249 22.628.001z\"],\n    \"check-double\": [512, 512, [], \"f560\", \"M505 174.8l-39.6-39.6c-9.4-9.4-24.6-9.4-33.9 0L192 374.7 80.6 263.2c-9.4-9.4-24.6-9.4-33.9 0L7 302.9c-9.4 9.4-9.4 24.6 0 34L175 505c9.4 9.4 24.6 9.4 33.9 0l296-296.2c9.4-9.5 9.4-24.7.1-34zm-324.3 106c6.2 6.3 16.4 6.3 22.6 0l208-208.2c6.2-6.3 6.2-16.4 0-22.6L366.1 4.7c-6.2-6.3-16.4-6.3-22.6 0L192 156.2l-55.4-55.5c-6.2-6.3-16.4-6.3-22.6 0L68.7 146c-6.2 6.3-6.2 16.4 0 22.6l112 112.2z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zm-204.686-98.059l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.248-16.379-6.249-22.628 0L184 302.745l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.25 16.379 6.25 22.628.001z\"],\n    \"cheese\": [512, 512, [], \"f7ef\", \"M0 288v160a32 32 0 0 0 32 32h448a32 32 0 0 0 32-32V288zM299.83 32a32 32 0 0 0-21.13 7L0 256h512c0-119.89-94-217.8-212.17-224z\"],\n    \"chess\": [512, 512, [], \"f439\", \"M74 208H64a16 16 0 0 0-16 16v16a16 16 0 0 0 16 16h15.94A535.78 535.78 0 0 1 64 384h128a535.78 535.78 0 0 1-15.94-128H192a16 16 0 0 0 16-16v-16a16 16 0 0 0-16-16h-10l33.89-90.38a16 16 0 0 0-15-21.62H144V64h24a8 8 0 0 0 8-8V40a8 8 0 0 0-8-8h-24V8a8 8 0 0 0-8-8h-16a8 8 0 0 0-8 8v24H88a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h24v32H55.09a16 16 0 0 0-15 21.62zm173.16 251.58L224 448v-16a16 16 0 0 0-16-16H48a16 16 0 0 0-16 16v16L8.85 459.58A16 16 0 0 0 0 473.89V496a16 16 0 0 0 16 16h224a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31zm92.77-157.78l-3.29 82.2h126.72l-3.29-82.21 24.6-20.79A32 32 0 0 0 496 256.54V198a6 6 0 0 0-6-6h-26.38a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H373.1a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H310a6 6 0 0 0-6 6v58.6a32 32 0 0 0 11.36 24.4zM384 304a16 16 0 0 1 32 0v32h-32zm119.16 155.58L480 448v-16a16 16 0 0 0-16-16H336a16 16 0 0 0-16 16v16l-23.15 11.58a16 16 0 0 0-8.85 14.31V496a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31z\"],\n    \"chess-bishop\": [320, 512, [], \"f43a\", \"M8 287.88c0 51.64 22.14 73.83 56 84.6V416h192v-43.52c33.86-10.77 56-33 56-84.6 0-30.61-10.73-67.1-26.69-102.56L185 285.65a8 8 0 0 1-11.31 0l-11.31-11.31a8 8 0 0 1 0-11.31L270.27 155.1c-20.8-37.91-46.47-72.1-70.87-92.59C213.4 59.09 224 47.05 224 32a32 32 0 0 0-32-32h-64a32 32 0 0 0-32 32c0 15 10.6 27.09 24.6 30.51C67.81 106.8 8 214.5 8 287.88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-board\": [512, 512, [], \"f43c\", \"M255.9.2h-64v64h64zM0 64.17v64h64v-64zM128 .2H64v64h64zm64 255.9v64h64v-64zM0 192.12v64h64v-64zM383.85.2h-64v64h64zm128 0h-64v64h64zM128 256.1H64v64h64zM511.8 448v-64h-64v64zm0-128v-64h-64v64zM383.85 512h64v-64h-64zm128-319.88v-64h-64v64zM128 512h64v-64h-64zM0 512h64v-64H0zm255.9 0h64v-64h-64zM0 320.07v64h64v-64zm319.88-191.92v-64h-64v64zm-64 128h64v-64h-64zm-64 128v64h64v-64zm128-64h64v-64h-64zm0-127.95h64v-64h-64zm0 191.93v64h64v-64zM64 384.05v64h64v-64zm128-255.9v-64h-64v64zm191.92 255.9h64v-64h-64zm-128-191.93v-64h-64v64zm128-127.95v64h64v-64zm-128 255.9v64h64v-64zm-64-127.95H128v64h64zm191.92 64h64v-64h-64zM128 128.15H64v64h64zm0 191.92v64h64v-64z\"],\n    \"chess-king\": [448, 512, [], \"f43f\", \"M400 448H48a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm16-288H256v-48h40a8 8 0 0 0 8-8V56a8 8 0 0 0-8-8h-40V8a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v40h-40a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8h40v48H32a32 32 0 0 0-30.52 41.54L74.56 416h298.88l73.08-214.46A32 32 0 0 0 416 160z\"],\n    \"chess-knight\": [384, 512, [], \"f441\", \"M19 272.47l40.63 18.06a32 32 0 0 0 24.88.47l12.78-5.12a32 32 0 0 0 18.76-20.5l9.22-30.65a24 24 0 0 1 12.55-15.65L159.94 208v50.33a48 48 0 0 1-26.53 42.94l-57.22 28.65A80 80 0 0 0 32 401.48V416h319.86V224c0-106-85.92-192-191.92-192H12A12 12 0 0 0 0 44a16.9 16.9 0 0 0 1.79 7.58L16 80l-9 9a24 24 0 0 0-7 17v137.21a32 32 0 0 0 19 29.26zM52 128a20 20 0 1 1-20 20 20 20 0 0 1 20-20zm316 320H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-pawn\": [320, 512, [], \"f443\", \"M105.1 224H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h16v5.49c0 44-4.14 86.6-24 122.51h176c-19.89-35.91-24-78.51-24-122.51V288h16a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-25.1c29.39-18.38 49.1-50.78 49.1-88a104 104 0 0 0-208 0c0 37.22 19.71 69.62 49.1 88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-queen\": [512, 512, [], \"f445\", \"M256 112a56 56 0 1 0-56-56 56 56 0 0 0 56 56zm176 336H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm72.87-263.84l-28.51-15.92c-7.44-5-16.91-2.46-22.29 4.68a47.59 47.59 0 0 1-47.23 18.23C383.7 186.86 368 164.93 368 141.4a13.4 13.4 0 0 0-13.4-13.4h-38.77c-6 0-11.61 4-12.86 9.91a48 48 0 0 1-93.94 0c-1.25-5.92-6.82-9.91-12.86-9.91H157.4a13.4 13.4 0 0 0-13.4 13.4c0 25.69-19 48.75-44.67 50.49a47.5 47.5 0 0 1-41.54-19.15c-5.28-7.09-14.73-9.45-22.09-4.54l-28.57 16a16 16 0 0 0-5.44 20.47L104.24 416h303.52l102.55-211.37a16 16 0 0 0-5.44-20.47z\"],\n    \"chess-rook\": [384, 512, [], \"f447\", \"M368 32h-56a16 16 0 0 0-16 16v48h-48V48a16 16 0 0 0-16-16h-80a16 16 0 0 0-16 16v48H88.1V48a16 16 0 0 0-16-16H16A16 16 0 0 0 0 48v176l64 32c0 48.33-1.54 95-13.21 160h282.42C321.54 351 320 303.72 320 256l64-32V48a16 16 0 0 0-16-16zM224 320h-64v-64a32 32 0 0 1 64 0zm144 128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chevron-circle-down\": [512, 512, [], \"f13a\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM273 369.9l135.5-135.5c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L256 285.1 154.4 183.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L239 369.9c9.4 9.4 24.6 9.4 34 0z\"],\n    \"chevron-circle-left\": [512, 512, [], \"f137\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zM142.1 273l135.5 135.5c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L226.9 256l101.6-101.6c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L142.1 239c-9.4 9.4-9.4 24.6 0 34z\"],\n    \"chevron-circle-right\": [512, 512, [], \"f138\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm113.9 231L234.4 103.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L285.1 256 183.5 357.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L369.9 273c9.4-9.4 9.4-24.6 0-34z\"],\n    \"chevron-circle-up\": [512, 512, [], \"f139\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm231-113.9L103.5 277.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L256 226.9l101.6 101.6c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L273 142.1c-9.4-9.4-24.6-9.4-34 0z\"],\n    \"chevron-down\": [448, 512, [], \"f078\", \"M207.029 381.476L12.686 187.132c-9.373-9.373-9.373-24.569 0-33.941l22.667-22.667c9.357-9.357 24.522-9.375 33.901-.04L224 284.505l154.745-154.021c9.379-9.335 24.544-9.317 33.901.04l22.667 22.667c9.373 9.373 9.373 24.569 0 33.941L240.971 381.476c-9.373 9.372-24.569 9.372-33.942 0z\"],\n    \"chevron-left\": [320, 512, [], \"f053\", \"M34.52 239.03L228.87 44.69c9.37-9.37 24.57-9.37 33.94 0l22.67 22.67c9.36 9.36 9.37 24.52.04 33.9L131.49 256l154.02 154.75c9.34 9.38 9.32 24.54-.04 33.9l-22.67 22.67c-9.37 9.37-24.57 9.37-33.94 0L34.52 272.97c-9.37-9.37-9.37-24.57 0-33.94z\"],\n    \"chevron-right\": [320, 512, [], \"f054\", \"M285.476 272.971L91.132 467.314c-9.373 9.373-24.569 9.373-33.941 0l-22.667-22.667c-9.357-9.357-9.375-24.522-.04-33.901L188.505 256 34.484 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L285.475 239.03c9.373 9.372 9.373 24.568.001 33.941z\"],\n    \"chevron-up\": [448, 512, [], \"f077\", \"M240.971 130.524l194.343 194.343c9.373 9.373 9.373 24.569 0 33.941l-22.667 22.667c-9.357 9.357-24.522 9.375-33.901.04L224 227.495 69.255 381.516c-9.379 9.335-24.544 9.317-33.901-.04l-22.667-22.667c-9.373-9.373-9.373-24.569 0-33.941L207.03 130.525c9.372-9.373 24.568-9.373 33.941-.001z\"],\n    \"child\": [384, 512, [], \"f1ae\", \"M120 72c0-39.765 32.235-72 72-72s72 32.235 72 72c0 39.764-32.235 72-72 72s-72-32.236-72-72zm254.627 1.373c-12.496-12.497-32.758-12.497-45.254 0L242.745 160H141.254L54.627 73.373c-12.496-12.497-32.758-12.497-45.254 0-12.497 12.497-12.497 32.758 0 45.255L104 213.254V480c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V368h16v112c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V213.254l94.627-94.627c12.497-12.497 12.497-32.757 0-45.254z\"],\n    \"church\": [640, 512, [], \"f51d\", \"M464.46 246.68L352 179.2V128h48c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-48V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v48h-48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v51.2l-112.46 67.48A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.65-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.54A32.024 32.024 0 0 0 0 395.96zm620.61-29.42L512 320v192h112c8.84 0 16-7.16 16-16V395.96c0-12.8-7.63-24.37-19.39-29.42z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8z\"],\n    \"circle-notch\": [512, 512, [], \"f1ce\", \"M288 39.056v16.659c0 10.804 7.281 20.159 17.686 23.066C383.204 100.434 440 171.518 440 256c0 101.689-82.295 184-184 184-101.689 0-184-82.295-184-184 0-84.47 56.786-155.564 134.312-177.219C216.719 75.874 224 66.517 224 55.712V39.064c0-15.709-14.834-27.153-30.046-23.234C86.603 43.482 7.394 141.206 8.003 257.332c.72 137.052 111.477 246.956 248.531 246.667C393.255 503.711 504 392.788 504 256c0-115.633-79.14-212.779-186.211-240.236C302.678 11.889 288 23.456 288 39.056z\"],\n    \"city\": [640, 512, [], \"f64f\", \"M616 192H480V24c0-13.26-10.74-24-24-24H312c-13.26 0-24 10.74-24 24v72h-64V16c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v80h-64V16c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v80H24c-13.26 0-24 10.74-24 24v360c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V216c0-13.26-10.75-24-24-24zM128 404c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm128 192c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12V76c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 288c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40z\"],\n    \"clinic-medical\": [576, 512, [], \"f7f2\", \"M288 115L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2zm96 261a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8zm186.69-139.72l-255.94-226a39.85 39.85 0 0 0-53.45 0l-256 226a16 16 0 0 0-1.21 22.6L25.5 282.7a16 16 0 0 0 22.6 1.21L277.42 81.63a16 16 0 0 1 21.17 0L527.91 283.9a16 16 0 0 0 22.6-1.21l21.4-23.82a16 16 0 0 0-1.22-22.59z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M384 112v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h80c0-35.29 28.71-64 64-64s64 28.71 64 64h80c26.51 0 48 21.49 48 48zM192 40c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24m96 114v-20a6 6 0 0 0-6-6H102a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h180a6 6 0 0 0 6-6z\"],\n    \"clipboard-check\": [384, 512, [], \"f46c\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm121.2 231.8l-143 141.8c-4.7 4.7-12.3 4.6-17-.1l-82.6-83.3c-4.7-4.7-4.6-12.3.1-17L99.1 285c4.7-4.7 12.3-4.6 17 .1l46 46.4 106-105.2c4.7-4.7 12.3-4.6 17 .1l28.2 28.4c4.7 4.8 4.6 12.3-.1 17z\"],\n    \"clipboard-list\": [384, 512, [], \"f46d\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM96 424c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm96-192c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm128 368c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm57.1 350.1L224.9 294c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v137.7l63.5 46.2c5.4 3.9 6.5 11.4 2.6 16.8l-28.2 38.8c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48H176c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h288M176 416c-44.112 0-80-35.888-80-80V128H48c-26.51 0-48 21.49-48 48v288c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48v-48H176z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM218.1 287.7c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2.1 48 51.1 70.5 92.3 32.6zm190.4 0c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.5 56.9-172.7 32.1-172.7-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 222.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6z\"],\n    \"cloud\": [640, 512, [], \"f0c2\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4z\"],\n    \"cloud-download-alt\": [640, 512, [], \"f381\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zm-132.9 88.7L299.3 420.7c-6.2 6.2-16.4 6.2-22.6 0L171.3 315.3c-10.1-10.1-2.9-27.3 11.3-27.3H248V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v112h65.4c14.2 0 21.4 17.2 11.3 27.3z\"],\n    \"cloud-meatball\": [512, 512, [], \"f73b\", \"M48 352c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm416 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm-119 11.1c4.6-14.5 1.6-30.8-9.8-42.3-11.5-11.5-27.8-14.4-42.3-9.9-7-13.5-20.7-23-36.9-23s-29.9 9.5-36.9 23c-14.5-4.6-30.8-1.6-42.3 9.9-11.5 11.5-14.4 27.8-9.9 42.3-13.5 7-23 20.7-23 36.9s9.5 29.9 23 36.9c-4.6 14.5-1.6 30.8 9.9 42.3 8.2 8.2 18.9 12.3 29.7 12.3 4.3 0 8.5-1.1 12.6-2.5 7 13.5 20.7 23 36.9 23s29.9-9.5 36.9-23c4.1 1.3 8.3 2.5 12.6 2.5 10.8 0 21.5-4.1 29.7-12.3 11.5-11.5 14.4-27.8 9.8-42.3 13.5-7 23-20.7 23-36.9s-9.5-29.9-23-36.9zM512 224c0-53-43-96-96-96-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h43.4c3.6-8 8.4-15.4 14.8-21.8 13.5-13.5 31.5-21.1 50.8-21.3 13.5-13.2 31.7-20.9 51-20.9s37.5 7.7 51 20.9c19.3.2 37.3 7.8 50.8 21.3 6.4 6.4 11.3 13.8 14.8 21.8H416c53 0 96-43 96-96z\"],\n    \"cloud-moon\": [576, 512, [], \"f6c3\", \"M342.8 352.7c5.7-9.6 9.2-20.7 9.2-32.7 0-35.3-28.7-64-64-64-17.2 0-32.8 6.9-44.3 17.9-16.3-29.6-47.5-49.9-83.7-49.9-53 0-96 43-96 96 0 2 .5 3.8.6 5.7C27.1 338.8 0 374.1 0 416c0 53 43 96 96 96h240c44.2 0 80-35.8 80-80 0-41.9-32.3-75.8-73.2-79.3zm222.5-54.3c-93.1 17.7-178.5-53.7-178.5-147.7 0-54.2 29-104 76.1-130.8 7.3-4.1 5.4-15.1-2.8-16.7C448.4 1.1 436.7 0 425 0 319.1 0 233.1 85.9 233.1 192c0 8.5.7 16.8 1.8 25 5.9 4.3 11.6 8.9 16.7 14.2 11.4-4.7 23.7-7.2 36.4-7.2 52.9 0 96 43.1 96 96 0 3.6-.2 7.2-.6 10.7 23.6 10.8 42.4 29.5 53.5 52.6 54.4-3.4 103.7-29.3 137.1-70.4 5.3-6.5-.5-16.1-8.7-14.5z\"],\n    \"cloud-moon-rain\": [576, 512, [], \"f73c\", \"M350.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C27.6 232.9 0 265.2 0 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm217.4-1.7c-70.4 13.3-135-40.3-135-110.8 0-40.6 21.9-78 57.5-98.1 5.5-3.1 4.1-11.4-2.1-12.5C479.6.8 470.7 0 461.8 0c-77.9 0-141.1 61.2-144.4 137.9 26.7 11.9 48.2 33.8 58.9 61.7 37.1 14.3 64 47.4 70.2 86.8 5.1.5 10 1.5 15.2 1.5 44.7 0 85.6-20.2 112.6-53.3 4.2-4.8-.2-12-6.4-10.8zM364.5 418.1c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-rain\": [512, 512, [], \"f73d\", \"M416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96zM88 374.2c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0z\"],\n    \"cloud-showers-heavy\": [512, 512, [], \"f740\", \"M183.9 370.1c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-192 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm384 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zM416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.2 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96z\"],\n    \"cloud-sun\": [640, 512, [], \"f6c4\", \"M575.2 325.7c.2-1.9.8-3.7.8-5.6 0-35.3-28.7-64-64-64-12.6 0-24.2 3.8-34.1 10-17.6-38.8-56.5-66-101.9-66-61.8 0-112 50.1-112 112 0 3 .7 5.8.9 8.7-49.6 3.7-88.9 44.7-88.9 95.3 0 53 43 96 96 96h272c53 0 96-43 96-96 0-42.1-27.2-77.4-64.8-90.4zm-430.4-22.6c-43.7-43.7-43.7-114.7 0-158.3 43.7-43.7 114.7-43.7 158.4 0 9.7 9.7 16.9 20.9 22.3 32.7 9.8-3.7 20.1-6 30.7-7.5L386 81.1c4-11.9-7.3-23.1-19.2-19.2L279 91.2 237.5 8.4C232-2.8 216-2.8 210.4 8.4L169 91.2 81.1 61.9C69.3 58 58 69.3 61.9 81.1l29.3 87.8-82.8 41.5c-11.2 5.6-11.2 21.5 0 27.1l82.8 41.4-29.3 87.8c-4 11.9 7.3 23.1 19.2 19.2l76.1-25.3c6.1-12.4 14-23.7 23.6-33.5-13.1-5.4-25.4-13.4-36-24zm-4.8-79.2c0 40.8 29.3 74.8 67.9 82.3 8-4.7 16.3-8.8 25.2-11.7 5.4-44.3 31-82.5 67.4-105C287.3 160.4 258 140 224 140c-46.3 0-84 37.6-84 83.9z\"],\n    \"cloud-sun-rain\": [576, 512, [], \"f743\", \"M510.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C187.6 233 160 265.2 160 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm-386.4 34.4c-37.4-37.4-37.4-98.3 0-135.8 34.6-34.6 89.1-36.8 126.7-7.4 20-12.9 43.6-20.7 69.2-20.7.7 0 1.3.2 2 .2l8.9-26.7c3.4-10.2-6.3-19.8-16.5-16.4l-75.3 25.1-35.5-71c-4.8-9.6-18.5-9.6-23.3 0l-35.5 71-75.3-25.1c-10.2-3.4-19.8 6.3-16.4 16.5l25.1 75.3-71 35.5c-9.6 4.8-9.6 18.5 0 23.3l71 35.5-25.1 75.3c-3.4 10.2 6.3 19.8 16.5 16.5l59.2-19.7c-.2-2.4-.7-4.7-.7-7.2 0-12.5 2.3-24.5 6.2-35.9-3.6-2.7-7.1-5.2-10.2-8.3zm69.8-58c4.3-24.5 15.8-46.4 31.9-64-9.8-6.2-21.4-9.9-33.8-9.9-35.3 0-64 28.7-64 64 0 18.7 8.2 35.4 21.1 47.1 11.3-15.9 26.6-28.9 44.8-37.2zm330.6 216.2c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-upload-alt\": [640, 512, [], \"f382\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zM393.4 288H328v112c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V288h-65.4c-14.3 0-21.4-17.2-11.3-27.3l105.4-105.4c6.2-6.2 16.4-6.2 22.6 0l105.4 105.4c10.1 10.1 2.9 27.3-11.3 27.3z\"],\n    \"cocktail\": [576, 512, [], \"f561\", \"M296 464h-56V338.78l168.74-168.73c15.52-15.52 4.53-42.05-17.42-42.05H24.68c-21.95 0-32.94 26.53-17.42 42.05L176 338.78V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM432 0c-62.61 0-115.35 40.2-135.18 96h52.54c16.65-28.55 47.27-48 82.64-48 52.93 0 96 43.06 96 96s-43.07 96-96 96c-14.04 0-27.29-3.2-39.32-8.64l-35.26 35.26C379.23 279.92 404.59 288 432 288c79.53 0 144-64.47 144-144S511.53 0 432 0z\"],\n    \"code\": [640, 512, [], \"f121\", \"M278.9 511.5l-61-17.7c-6.4-1.8-10-8.5-8.2-14.9L346.2 8.7c1.8-6.4 8.5-10 14.9-8.2l61 17.7c6.4 1.8 10 8.5 8.2 14.9L293.8 503.3c-1.9 6.4-8.5 10.1-14.9 8.2zm-114-112.2l43.5-46.4c4.6-4.9 4.3-12.7-.8-17.2L117 256l90.6-79.7c5.1-4.5 5.5-12.3.8-17.2l-43.5-46.4c-4.5-4.8-12.1-5.1-17-.5L3.8 247.2c-5.1 4.7-5.1 12.8 0 17.5l144.1 135.1c4.9 4.6 12.5 4.4 17-.5zm327.2.6l144.1-135.1c5.1-4.7 5.1-12.8 0-17.5L492.1 112.1c-4.8-4.5-12.4-4.3-17 .5L431.6 159c-4.6 4.9-4.3 12.7.8 17.2L523 256l-90.6 79.7c-5.1 4.5-5.5 12.3-.8 17.2l43.5 46.4c4.5 4.9 12.1 5.1 17 .6z\"],\n    \"code-branch\": [384, 512, [], \"f126\", \"M384 144c0-44.2-35.8-80-80-80s-80 35.8-80 80c0 36.4 24.3 67.1 57.5 76.8-.6 16.1-4.2 28.5-11 36.9-15.4 19.2-49.3 22.4-85.2 25.7-28.2 2.6-57.4 5.4-81.3 16.9v-144c32.5-10.2 56-40.5 56-76.3 0-44.2-35.8-80-80-80S0 35.8 0 80c0 35.8 23.5 66.1 56 76.3v199.3C23.5 365.9 0 396.2 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-34-21.2-63.1-51.2-74.6 3.1-5.2 7.8-9.8 14.9-13.4 16.2-8.2 40.4-10.4 66.1-12.8 42.2-3.9 90-8.4 118.2-43.4 14-17.4 21.1-39.8 21.6-67.9 31.6-10.8 54.4-40.7 54.4-75.9zM80 64c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16zm0 384c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm224-320c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16z\"],\n    \"coffee\": [640, 512, [], \"f0f4\", \"M192 384h192c53 0 96-43 96-96h32c70.6 0 128-57.4 128-128S582.6 32 512 32H120c-13.3 0-24 10.7-24 24v232c0 53 43 96 96 96zM512 96c35.3 0 64 28.7 64 64s-28.7 64-64 64h-32V96h32zm47.7 384H48.3c-47.6 0-61-64-36-64h583.3c25 0 11.8 64-35.9 64z\"],\n    \"cog\": [512, 512, [], \"f013\", \"M487.4 315.7l-42.6-24.6c4.3-23.2 4.3-47 0-70.2l42.6-24.6c4.9-2.8 7.1-8.6 5.5-14-11.1-35.6-30-67.8-54.7-94.6-3.8-4.1-10-5.1-14.8-2.3L380.8 110c-17.9-15.4-38.5-27.3-60.8-35.1V25.8c0-5.6-3.9-10.5-9.4-11.7-36.7-8.2-74.3-7.8-109.2 0-5.5 1.2-9.4 6.1-9.4 11.7V75c-22.2 7.9-42.8 19.8-60.8 35.1L88.7 85.5c-4.9-2.8-11-1.9-14.8 2.3-24.7 26.7-43.6 58.9-54.7 94.6-1.7 5.4.6 11.2 5.5 14L67.3 221c-4.3 23.2-4.3 47 0 70.2l-42.6 24.6c-4.9 2.8-7.1 8.6-5.5 14 11.1 35.6 30 67.8 54.7 94.6 3.8 4.1 10 5.1 14.8 2.3l42.6-24.6c17.9 15.4 38.5 27.3 60.8 35.1v49.2c0 5.6 3.9 10.5 9.4 11.7 36.7 8.2 74.3 7.8 109.2 0 5.5-1.2 9.4-6.1 9.4-11.7v-49.2c22.2-7.9 42.8-19.8 60.8-35.1l42.6 24.6c4.9 2.8 11 1.9 14.8-2.3 24.7-26.7 43.6-58.9 54.7-94.6 1.5-5.5-.7-11.3-5.6-14.1zM256 336c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"cogs\": [640, 512, [], \"f085\", \"M512.1 191l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0L552 6.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zm-10.5-58.8c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.7-82.4 14.3-52.8 52.8zM386.3 286.1l33.7 16.8c10.1 5.8 14.5 18.1 10.5 29.1-8.9 24.2-26.4 46.4-42.6 65.8-7.4 8.9-20.2 11.1-30.3 5.3l-29.1-16.8c-16 13.7-34.6 24.6-54.9 31.7v33.6c0 11.6-8.3 21.6-19.7 23.6-24.6 4.2-50.4 4.4-75.9 0-11.5-2-20-11.9-20-23.6V418c-20.3-7.2-38.9-18-54.9-31.7L74 403c-10 5.8-22.9 3.6-30.3-5.3-16.2-19.4-33.3-41.6-42.2-65.7-4-10.9.4-23.2 10.5-29.1l33.3-16.8c-3.9-20.9-3.9-42.4 0-63.4L12 205.8c-10.1-5.8-14.6-18.1-10.5-29 8.9-24.2 26-46.4 42.2-65.8 7.4-8.9 20.2-11.1 30.3-5.3l29.1 16.8c16-13.7 34.6-24.6 54.9-31.7V57.1c0-11.5 8.2-21.5 19.6-23.5 24.6-4.2 50.5-4.4 76-.1 11.5 2 20 11.9 20 23.6v33.6c20.3 7.2 38.9 18 54.9 31.7l29.1-16.8c10-5.8 22.9-3.6 30.3 5.3 16.2 19.4 33.2 41.6 42.1 65.8 4 10.9.1 23.2-10 29.1l-33.7 16.8c3.9 21 3.9 42.5 0 63.5zm-117.6 21.1c59.2-77-28.7-164.9-105.7-105.7-59.2 77 28.7 164.9 105.7 105.7zm243.4 182.7l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0l8.2-14.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zM501.6 431c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.6-82.4 14.3-52.8 52.8z\"],\n    \"coins\": [512, 512, [], \"f51e\", \"M0 405.3V448c0 35.3 86 64 192 64s192-28.7 192-64v-42.7C342.7 434.4 267.2 448 192 448S41.3 434.4 0 405.3zM320 128c106 0 192-28.7 192-64S426 0 320 0 128 28.7 128 64s86 64 192 64zM0 300.4V352c0 35.3 86 64 192 64s192-28.7 192-64v-51.6c-41.3 34-116.9 51.6-192 51.6S41.3 334.4 0 300.4zm416 11c57.3-11.1 96-31.7 96-55.4v-42.7c-23.2 16.4-57.3 27.6-96 34.5v63.6zM192 160C86 160 0 195.8 0 240s86 80 192 80 192-35.8 192-80-86-80-192-80zm219.3 56.3c60-10.8 100.7-32 100.7-56.3v-42.7c-35.5 25.1-96.5 38.6-160.7 41.8 29.5 14.3 51.2 33.5 60 57.2z\"],\n    \"columns\": [512, 512, [], \"f0db\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64V160h160v256zm224 0H288V160h160v256z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 9.8 11.2 15.5 19.1 9.7L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64z\"],\n    \"comment-dollar\": [512, 512, [], \"f651\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95.01 57.02 130.74C44.46 421.05 2.7 465.97 2.2 466.5A7.995 7.995 0 0 0 8 480c66.26 0 115.99-31.75 140.6-51.38C181.29 440.93 217.59 448 256 448c141.38 0 256-93.12 256-208S397.38 32 256 32zm24 302.44V352c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-17.73c-11.42-1.35-22.28-5.19-31.78-11.46-6.22-4.11-6.82-13.11-1.55-18.38l17.52-17.52c3.74-3.74 9.31-4.24 14.11-2.03 3.18 1.46 6.66 2.22 10.26 2.22h32.78c4.66 0 8.44-3.78 8.44-8.42 0-3.75-2.52-7.08-6.12-8.11l-50.07-14.3c-22.25-6.35-40.01-24.71-42.91-47.67-4.05-32.07 19.03-59.43 49.32-63.05V128c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v17.73c11.42 1.35 22.28 5.19 31.78 11.46 6.22 4.11 6.82 13.11 1.55 18.38l-17.52 17.52c-3.74 3.74-9.31 4.24-14.11 2.03a24.516 24.516 0 0 0-10.26-2.22h-32.78c-4.66 0-8.44 3.78-8.44 8.42 0 3.75 2.52 7.08 6.12 8.11l50.07 14.3c22.25 6.36 40.01 24.71 42.91 47.67 4.05 32.06-19.03 59.42-49.32 63.04z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128 272c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"comment-medical\": [512, 512, [], \"f7f5\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95 57 130.74C44.46 421.05 2.7 466 2.2 466.5A8 8 0 0 0 8 480c66.26 0 116-31.75 140.6-51.38A304.66 304.66 0 0 0 256 448c141.39 0 256-93.12 256-208S397.39 32 256 32zm96 232a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8z\"],\n    \"comment-slash\": [640, 512, [], \"f4b3\", \"M64 240c0 49.6 21.4 95 57 130.7-12.6 50.3-54.3 95.2-54.8 95.8-2.2 2.3-2.8 5.7-1.5 8.7 1.3 2.9 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 27.4 0 53.7-3.6 78.4-10L72.9 186.4c-5.6 17.1-8.9 35-8.9 53.6zm569.8 218.1l-114.4-88.4C554.6 334.1 576 289.2 576 240c0-114.9-114.6-208-256-208-65.1 0-124.2 20.1-169.4 52.7L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M416 192c0-88.4-93.1-160-208-160S0 103.6 0 192c0 34.3 14.1 65.9 38 92-13.4 30.2-35.5 54.2-35.8 54.5-2.2 2.3-2.8 5.7-1.5 8.7S4.8 352 8 352c36.6 0 66.9-12.3 88.7-25 32.2 15.7 70.3 25 111.3 25 114.9 0 208-71.6 208-160zm122 220c23.9-26 38-57.7 38-92 0-66.9-53.5-124.2-129.3-148.1.9 6.6 1.3 13.3 1.3 20.1 0 105.9-107.7 192-240 192-10.8 0-21.3-.8-31.7-1.9C207.8 439.6 281.8 480 368 480c41 0 79.1-9.2 111.3-25 21.8 12.7 52.1 25 88.7 25 3.2 0 6.1-1.9 7.3-4.8 1.3-2.9.7-6.3-1.5-8.7-.3-.3-22.4-24.2-35.8-54.5z\"],\n    \"comments-dollar\": [576, 512, [], \"f653\", \"M416 192c0-88.37-93.12-160-208-160S0 103.63 0 192c0 34.27 14.13 65.95 37.97 91.98C24.61 314.22 2.52 338.16 2.2 338.5A7.995 7.995 0 0 0 8 352c36.58 0 66.93-12.25 88.73-24.98C128.93 342.76 167.02 352 208 352c114.88 0 208-71.63 208-160zm-224 96v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V96c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07V288c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm346.01 123.99C561.87 385.96 576 354.27 576 320c0-66.94-53.49-124.2-129.33-148.07.86 6.6 1.33 13.29 1.33 20.07 0 105.87-107.66 192-240 192-10.78 0-21.32-.77-31.73-1.88C207.8 439.63 281.77 480 368 480c40.98 0 79.07-9.24 111.27-24.98C501.07 467.75 531.42 480 568 480c3.2 0 6.09-1.91 7.34-4.84 1.27-2.94.66-6.34-1.55-8.67-.31-.33-22.42-24.24-35.78-54.5z\"],\n    \"compact-disc\": [496, 512, [], \"f51f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 256H56c0-105.9 86.1-192 192-192v32c-88.2 0-160 71.8-160 160zm160 96c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96zm0-128c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M225.38 233.37c-12.5 12.5-12.5 32.76 0 45.25 12.49 12.5 32.76 12.5 45.25 0 12.5-12.5 12.5-32.76 0-45.25-12.5-12.49-32.76-12.49-45.25 0zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm126.14 148.05L308.17 300.4a31.938 31.938 0 0 1-15.77 15.77l-144.34 65.97c-16.65 7.61-33.81-9.55-26.2-26.2l65.98-144.35a31.938 31.938 0 0 1 15.77-15.77l144.34-65.97c16.65-7.6 33.8 9.55 26.19 26.2z\"],\n    \"compress\": [448, 512, [], \"f066\", \"M436 192H312c-13.3 0-24-10.7-24-24V44c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v84h84c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm-276-24V44c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v84H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24zm0 300V344c0-13.3-10.7-24-24-24H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-84h84c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H312c-13.3 0-24 10.7-24 24v124c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"compress-arrows-alt\": [512, 512, [], \"f78c\", \"M200 288H88c-21.4 0-32.1 25.8-17 41l32.9 31-99.2 99.3c-6.2 6.2-6.2 16.4 0 22.6l25.4 25.4c6.2 6.2 16.4 6.2 22.6 0L152 408l31.1 33c15.1 15.1 40.9 4.4 40.9-17V312c0-13.3-10.7-24-24-24zm112-64h112c21.4 0 32.1-25.9 17-41l-33-31 99.3-99.3c6.2-6.2 6.2-16.4 0-22.6L481.9 4.7c-6.2-6.2-16.4-6.2-22.6 0L360 104l-31.1-33C313.8 55.9 288 66.6 288 88v112c0 13.3 10.7 24 24 24zm96 136l33-31.1c15.1-15.1 4.4-40.9-17-40.9H312c-13.3 0-24 10.7-24 24v112c0 21.4 25.9 32.1 41 17l31-32.9 99.3 99.3c6.2 6.2 16.4 6.2 22.6 0l25.4-25.4c6.2-6.2 6.2-16.4 0-22.6L408 360zM183 71.1L152 104 52.7 4.7c-6.2-6.2-16.4-6.2-22.6 0L4.7 30.1c-6.2 6.2-6.2 16.4 0 22.6L104 152l-33 31.1C55.9 198.2 66.6 224 88 224h112c13.3 0 24-10.7 24-24V88c0-21.3-25.9-32-41-16.9z\"],\n    \"concierge-bell\": [512, 512, [], \"f562\", \"M288 130.54V112h16c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h16v18.54C115.49 146.11 32 239.18 32 352h448c0-112.82-83.49-205.89-192-221.46zM496 384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"cookie\": [512, 512, [], \"f563\", \"M510.37 254.79l-12.08-76.26a132.493 132.493 0 0 0-37.16-72.95l-54.76-54.75c-19.73-19.72-45.18-32.7-72.71-37.05l-76.7-12.15c-27.51-4.36-55.69.11-80.52 12.76L107.32 49.6a132.25 132.25 0 0 0-57.79 57.8l-35.1 68.88a132.602 132.602 0 0 0-12.82 80.94l12.08 76.27a132.493 132.493 0 0 0 37.16 72.95l54.76 54.75a132.087 132.087 0 0 0 72.71 37.05l76.7 12.14c27.51 4.36 55.69-.11 80.52-12.75l69.12-35.21a132.302 132.302 0 0 0 57.79-57.8l35.1-68.87c12.71-24.96 17.2-53.3 12.82-80.96zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"cookie-bite\": [512, 512, [], \"f564\", \"M510.52 255.82c-69.97-.85-126.47-57.69-126.47-127.86-70.17 0-127-56.49-127.86-126.45-27.26-4.14-55.13.3-79.72 12.82l-69.13 35.22a132.221 132.221 0 0 0-57.79 57.81l-35.1 68.88a132.645 132.645 0 0 0-12.82 80.95l12.08 76.27a132.521 132.521 0 0 0 37.16 72.96l54.77 54.76a132.036 132.036 0 0 0 72.71 37.06l76.71 12.15c27.51 4.36 55.7-.11 80.53-12.76l69.13-35.21a132.273 132.273 0 0 0 57.79-57.81l35.1-68.88c12.56-24.64 17.01-52.58 12.91-79.91zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M320 448v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V120c0-13.255 10.745-24 24-24h72v296c0 30.879 25.121 56 56 56h168zm0-344V0H152c-13.255 0-24 10.745-24 24v368c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24V128H344c-13.2 0-24-10.8-24-24zm120.971-31.029L375.029 7.029A24 24 0 0 0 358.059 0H352v96h96v-6.059a24 24 0 0 0-7.029-16.97z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm117.134 346.753c-1.592 1.867-39.776 45.731-109.851 45.731-84.692 0-144.484-63.26-144.484-145.567 0-81.303 62.004-143.401 143.762-143.401 66.957 0 101.965 37.315 103.422 38.904a12 12 0 0 1 1.238 14.623l-22.38 34.655c-4.049 6.267-12.774 7.351-18.234 2.295-.233-.214-26.529-23.88-61.88-23.88-46.116 0-73.916 33.575-73.916 76.082 0 39.602 25.514 79.692 74.277 79.692 38.697 0 65.28-28.338 65.544-28.625 5.132-5.565 14.059-5.033 18.508 1.053l24.547 33.572a12.001 12.001 0 0 1-.553 14.866z\"],\n    \"couch\": [640, 512, [], \"f4b8\", \"M160 224v64h320v-64c0-35.3 28.7-64 64-64h32c0-53-43-96-96-96H160c-53 0-96 43-96 96h32c35.3 0 64 28.7 64 64zm416-32h-32c-17.7 0-32 14.3-32 32v96H128v-96c0-17.7-14.3-32-32-32H64c-35.3 0-64 28.7-64 64 0 23.6 13 44 32 55.1V432c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-16h384v16c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V311.1c19-11.1 32-31.5 32-55.1 0-35.3-28.7-64-64-64z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V256H0v176zm192-68c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-40zm-128 0c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM576 80v48H0V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48z\"],\n    \"crop\": [512, 512, [], \"f125\", \"M488 352h-40V109.25l59.31-59.31c6.25-6.25 6.25-16.38 0-22.63L484.69 4.69c-6.25-6.25-16.38-6.25-22.63 0L402.75 64H192v96h114.75L160 306.75V24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v264c0 13.25 10.75 24 24 24h232v-96H205.25L352 205.25V488c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"crop-alt\": [512, 512, [], \"f565\", \"M488 352h-40V96c0-17.67-14.33-32-32-32H192v96h160v328c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24zM160 24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v256c0 17.67 14.33 32 32 32h224v-96H160V24z\"],\n    \"cross\": [384, 512, [], \"f654\", \"M352 128h-96V32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h96v224c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V256h96c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"crosshairs\": [512, 512, [], \"f05b\", \"M500 224h-30.364C455.724 130.325 381.675 56.276 288 42.364V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v30.364C130.325 56.276 56.276 130.325 42.364 224H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h30.364C56.276 381.675 130.325 455.724 224 469.636V500c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-30.364C381.675 455.724 455.724 381.675 469.636 288H500c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zM288 404.634V364c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40.634C165.826 392.232 119.783 346.243 107.366 288H148c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40.634C119.768 165.826 165.757 119.783 224 107.366V148c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40.634C346.174 119.768 392.217 165.757 404.634 224H364c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40.634C392.232 346.174 346.243 392.217 288 404.634zM288 256c0 17.673-14.327 32-32 32s-32-14.327-32-32c0-17.673 14.327-32 32-32s32 14.327 32 32z\"],\n    \"crow\": [640, 512, [], \"f520\", \"M544 32h-16.36C513.04 12.68 490.09 0 464 0c-44.18 0-80 35.82-80 80v20.98L12.09 393.57A30.216 30.216 0 0 0 0 417.74c0 22.46 23.64 37.07 43.73 27.03L165.27 384h96.49l44.41 120.1c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38L312.94 384H352c1.91 0 3.76-.23 5.66-.29l44.51 120.38c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38l-41.24-111.53C485.74 352.8 544 279.26 544 192v-80l96-16c0-35.35-42.98-64-96-64zm-80 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"crown\": [640, 512, [], \"f521\", \"M528 448H112c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h416c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm64-320c-26.5 0-48 21.5-48 48 0 7.1 1.6 13.7 4.4 19.8L476 239.2c-15.4 9.2-35.3 4-44.2-11.6L350.3 85C361 76.2 368 63 368 48c0-26.5-21.5-48-48-48s-48 21.5-48 48c0 15 7 28.2 17.7 37l-81.5 142.6c-8.9 15.6-28.9 20.8-44.2 11.6l-72.3-43.4c2.7-6 4.4-12.7 4.4-19.8 0-26.5-21.5-48-48-48S0 149.5 0 176s21.5 48 48 48c2.6 0 5.2-.4 7.7-.8L128 416h384l72.3-192.8c2.5.4 5.1.8 7.7.8 26.5 0 48-21.5 48-48s-21.5-48-48-48z\"],\n    \"crutch\": [512, 512, [], \"f7f7\", \"M507.31 185.71l-181-181a16 16 0 0 0-22.62 0L281 27.31a16 16 0 0 0 0 22.63l181 181a16 16 0 0 0 22.63 0l22.62-22.63a16 16 0 0 0 .06-22.6zm-179.54 66.41l-67.89-67.89 55.1-55.1-45.25-45.25-109.67 109.67a96.08 96.08 0 0 0-25.67 46.29L106.65 360.1l-102 102a16 16 0 0 0 0 22.63l22.62 22.62a16 16 0 0 0 22.63 0l102-102 120.25-27.75a95.88 95.88 0 0 0 46.29-25.65l109.68-109.68L382.87 197zm-54.57 54.57a32 32 0 0 1-15.45 8.54l-79.3 18.32 18.3-79.3a32.22 32.22 0 0 1 8.56-15.45l9.31-9.31 67.89 67.89z\"],\n    \"cube\": [512, 512, [], \"f1b2\", \"M239.1 6.3l-208 78c-18.7 7-31.1 25-31.1 45v225.1c0 18.2 10.3 34.8 26.5 42.9l208 104c13.5 6.8 29.4 6.8 42.9 0l208-104c16.3-8.1 26.5-24.8 26.5-42.9V129.3c0-20-12.4-37.9-31.1-44.9l-208-78C262 2.2 250 2.2 239.1 6.3zM256 68.4l192 72v1.1l-192 78-192-78v-1.1l192-72zm32 356V275.5l160-65v133.9l-160 80z\"],\n    \"cubes\": [512, 512, [], \"f1b3\", \"M488.6 250.2L392 214V105.5c0-15-9.3-28.4-23.4-33.7l-100-37.5c-8.1-3.1-17.1-3.1-25.3 0l-100 37.5c-14.1 5.3-23.4 18.7-23.4 33.7V214l-96.6 36.2C9.3 255.5 0 268.9 0 283.9V394c0 13.6 7.7 26.1 19.9 32.2l100 50c10.1 5.1 22.1 5.1 32.2 0l103.9-52 103.9 52c10.1 5.1 22.1 5.1 32.2 0l100-50c12.2-6.1 19.9-18.6 19.9-32.2V283.9c0-15-9.3-28.4-23.4-33.7zM358 214.8l-85 31.9v-68.2l85-37v73.3zM154 104.1l102-38.2 102 38.2v.6l-102 41.4-102-41.4v-.6zm84 291.1l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6zm240 112l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6z\"],\n    \"cut\": [448, 512, [], \"f0c4\", \"M278.06 256L444.48 89.57c4.69-4.69 4.69-12.29 0-16.97-32.8-32.8-85.99-32.8-118.79 0L210.18 188.12l-24.86-24.86c4.31-10.92 6.68-22.81 6.68-35.26 0-53.02-42.98-96-96-96S0 74.98 0 128s42.98 96 96 96c4.54 0 8.99-.32 13.36-.93L142.29 256l-32.93 32.93c-4.37-.61-8.83-.93-13.36-.93-53.02 0-96 42.98-96 96s42.98 96 96 96 96-42.98 96-96c0-12.45-2.37-24.34-6.68-35.26l24.86-24.86L325.69 439.4c32.8 32.8 85.99 32.8 118.79 0 4.69-4.68 4.69-12.28 0-16.97L278.06 256zM96 160c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32zm0 256c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"database\": [448, 512, [], \"f1c0\", \"M448 73.143v45.714C448 159.143 347.667 192 224 192S0 159.143 0 118.857V73.143C0 32.857 100.333 0 224 0s224 32.857 224 73.143zM448 176v102.857C448 319.143 347.667 352 224 352S0 319.143 0 278.857V176c48.125 33.143 136.208 48.572 224 48.572S399.874 209.143 448 176zm0 160v102.857C448 479.143 347.667 512 224 512S0 479.143 0 438.857V336c48.125 33.143 136.208 48.572 224 48.572S399.874 369.143 448 336z\"],\n    \"deaf\": [512, 512, [], \"f2a4\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm268.485-52.201L480.2 3.515c-4.687-4.686-12.284-4.686-16.971 0L376.2 90.544c-4.686 4.686-4.686 12.284 0 16.971l28.285 28.285c4.686 4.686 12.284 4.686 16.97 0l87.03-87.029c4.687-4.688 4.687-12.286 0-16.972zM168.97 314.745c-4.686-4.686-12.284-4.686-16.97 0L3.515 463.23c-4.686 4.686-4.686 12.284 0 16.971L31.8 508.485c4.687 4.686 12.284 4.686 16.971 0L197.256 360c4.686-4.686 4.686-12.284 0-16.971l-28.286-28.284z\"],\n    \"democrat\": [640, 512, [], \"f747\", \"M637.3 256.9l-19.6-29.4c-28.2-42.3-75.3-67.5-126.1-67.5H256l-81.2-81.2c20.1-20.1 22.6-51.1 7.5-73.9-3.4-5.2-10.8-5.9-15.2-1.5l-41.8 41.8L82.4 2.4c-3.6-3.6-9.6-3-12.4 1.2-12.3 18.6-10.3 44 6.1 60.4 3.3 3.3 7.3 5.3 11.3 7.5-2.2 1.7-4.7 3.1-6.4 5.4L6.4 176.2c-7.3 9.7-8.4 22.7-3 33.5l14.3 28.6c5.4 10.8 16.5 17.7 28.6 17.7h31c8.5 0 16.6-3.4 22.6-9.4L138 212l54 108h352v-77.8c16.2 12.2 18.3 17.6 40.1 50.3 4.9 7.4 14.8 9.3 22.2 4.4l26.6-17.7c7.3-5 9.3-14.9 4.4-22.3zm-341.1-13.6l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L256 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L368 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L480 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zM192 496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80h160v80c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V352H192v144z\"],\n    \"desktop\": [576, 512, [], \"f108\", \"M528 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h192l-16 48h-72c-13.3 0-24 10.7-24 24s10.7 24 24 24h272c13.3 0 24-10.7 24-24s-10.7-24-24-24h-72l-16-48h192c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h448v288z\"],\n    \"dharmachakra\": [512, 512, [], \"f655\", \"M495 225.06l-17.22 1.08c-5.27-39.49-20.79-75.64-43.86-105.84l12.95-11.43c6.92-6.11 7.25-16.79.73-23.31L426.44 64.4c-6.53-6.53-17.21-6.19-23.31.73L391.7 78.07c-30.2-23.06-66.35-38.58-105.83-43.86L286.94 17c.58-9.21-6.74-17-15.97-17h-29.94c-9.23 0-16.54 7.79-15.97 17l1.08 17.22c-39.49 5.27-75.64 20.79-105.83 43.86l-11.43-12.95c-6.11-6.92-16.79-7.25-23.31-.73L64.4 85.56c-6.53 6.53-6.19 17.21.73 23.31l12.95 11.43c-23.06 30.2-38.58 66.35-43.86 105.84L17 225.06c-9.21-.58-17 6.74-17 15.97v29.94c0 9.23 7.79 16.54 17 15.97l17.22-1.08c5.27 39.49 20.79 75.64 43.86 105.83l-12.95 11.43c-6.92 6.11-7.25 16.79-.73 23.31l21.17 21.17c6.53 6.53 17.21 6.19 23.31-.73l11.43-12.95c30.2 23.06 66.35 38.58 105.84 43.86L225.06 495c-.58 9.21 6.74 17 15.97 17h29.94c9.23 0 16.54-7.79 15.97-17l-1.08-17.22c39.49-5.27 75.64-20.79 105.84-43.86l11.43 12.95c6.11 6.92 16.79 7.25 23.31.73l21.17-21.17c6.53-6.53 6.19-17.21-.73-23.31l-12.95-11.43c23.06-30.2 38.58-66.35 43.86-105.83l17.22 1.08c9.21.58 17-6.74 17-15.97v-29.94c-.01-9.23-7.8-16.54-17.01-15.97zM281.84 98.61c24.81 4.07 47.63 13.66 67.23 27.78l-42.62 48.29c-8.73-5.44-18.32-9.54-28.62-11.95l4.01-64.12zm-51.68 0l4.01 64.12c-10.29 2.41-19.89 6.52-28.62 11.95l-42.62-48.29c19.6-14.12 42.42-23.71 67.23-27.78zm-103.77 64.33l48.3 42.61c-5.44 8.73-9.54 18.33-11.96 28.62l-64.12-4.01c4.07-24.81 13.66-47.62 27.78-67.22zm-27.78 118.9l64.12-4.01c2.41 10.29 6.52 19.89 11.95 28.62l-48.29 42.62c-14.12-19.6-23.71-42.42-27.78-67.23zm131.55 131.55c-24.81-4.07-47.63-13.66-67.23-27.78l42.61-48.3c8.73 5.44 18.33 9.54 28.62 11.96l-4 64.12zM256 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm25.84 125.39l-4.01-64.12c10.29-2.41 19.89-6.52 28.62-11.96l42.61 48.3c-19.6 14.12-42.41 23.71-67.22 27.78zm103.77-64.33l-48.29-42.62c5.44-8.73 9.54-18.32 11.95-28.62l64.12 4.01c-4.07 24.82-13.66 47.64-27.78 67.23zm-36.34-114.89c-2.41-10.29-6.52-19.89-11.96-28.62l48.3-42.61c14.12 19.6 23.71 42.42 27.78 67.23l-64.12 4z\"],\n    \"diagnoses\": [640, 512, [], \"f470\", \"M496 256c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm-176-80c48.5 0 88-39.5 88-88S368.5 0 320 0s-88 39.5-88 88 39.5 88 88 88zM59.8 364c10.2 15.3 29.3 17.8 42.9 9.8 16.2-9.6 56.2-31.7 105.3-48.6V416h224v-90.7c49.1 16.8 89.1 39 105.3 48.6 13.6 8 32.7 5.3 42.9-9.8l17.8-26.7c8.8-13.2 7.6-34.6-10-45.1-11.9-7.1-29.7-17-51.1-27.4-28.1 46.1-99.4 17.8-87.7-35.1C409.3 217.2 365.1 208 320 208c-57 0-112.9 14.5-160 32.2-.2 40.2-47.6 63.3-79.2 36-11.2 6-21.3 11.6-28.7 16-17.6 10.5-18.8 31.8-10 45.1L59.8 364zM368 344c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-160 8c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm512 192H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dice\": [640, 512, [], \"f522\", \"M592 192H473.26c12.69 29.59 7.12 65.2-17 89.32L320 417.58V464c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48V240c0-26.51-21.49-48-48-48zM480 376c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm-46.37-186.7L258.7 14.37c-19.16-19.16-50.23-19.16-69.39 0L14.37 189.3c-19.16 19.16-19.16 50.23 0 69.39L189.3 433.63c19.16 19.16 50.23 19.16 69.39 0L433.63 258.7c19.16-19.17 19.16-50.24 0-69.4zM96 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"dice-d20\": [480, 512, [], \"f6cf\", \"M106.75 215.06L1.2 370.95c-3.08 5 .1 11.5 5.93 12.14l208.26 22.07-108.64-190.1zM7.41 315.43L82.7 193.08 6.06 147.1c-2.67-1.6-6.06.32-6.06 3.43v162.81c0 4.03 5.29 5.53 7.41 2.09zM18.25 423.6l194.4 87.66c5.3 2.45 11.35-1.43 11.35-7.26v-65.67l-203.55-22.3c-4.45-.5-6.23 5.59-2.2 7.57zm81.22-257.78L179.4 22.88c4.34-7.06-3.59-15.25-10.78-11.14L17.81 110.35c-2.47 1.62-2.39 5.26.13 6.78l81.53 48.69zM240 176h109.21L253.63 7.62C250.5 2.54 245.25 0 240 0s-10.5 2.54-13.63 7.62L130.79 176H240zm233.94-28.9l-76.64 45.99 75.29 122.35c2.11 3.44 7.41 1.94 7.41-2.1V150.53c0-3.11-3.39-5.03-6.06-3.43zm-93.41 18.72l81.53-48.7c2.53-1.52 2.6-5.16.13-6.78l-150.81-98.6c-7.19-4.11-15.12 4.08-10.78 11.14l79.93 142.94zm79.02 250.21L256 438.32v65.67c0 5.84 6.05 9.71 11.35 7.26l194.4-87.66c4.03-1.97 2.25-8.06-2.2-7.56zm-86.3-200.97l-108.63 190.1 208.26-22.07c5.83-.65 9.01-7.14 5.93-12.14L373.25 215.06zM240 208H139.57L240 383.75 340.43 208H240z\"],\n    \"dice-d6\": [448, 512, [], \"f6d1\", \"M422.19 109.95L256.21 9.07c-19.91-12.1-44.52-12.1-64.43 0L25.81 109.95c-5.32 3.23-5.29 11.27.06 14.46L224 242.55l198.14-118.14c5.35-3.19 5.38-11.22.05-14.46zm13.84 44.63L240 271.46v223.82c0 12.88 13.39 20.91 24.05 14.43l152.16-92.48c19.68-11.96 31.79-33.94 31.79-57.7v-197.7c0-6.41-6.64-10.43-11.97-7.25zM0 161.83v197.7c0 23.77 12.11 45.74 31.79 57.7l152.16 92.47c10.67 6.48 24.05-1.54 24.05-14.43V271.46L11.97 154.58C6.64 151.4 0 155.42 0 161.83z\"],\n    \"dice-five\": [448, 512, [], \"f523\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-four\": [448, 512, [], \"f524\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-one\": [448, 512, [], \"f525\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM224 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-six\": [448, 512, [], \"f526\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-three\": [448, 512, [], \"f527\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-two\": [448, 512, [], \"f528\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"digital-tachograph\": [640, 512, [], \"f566\", \"M608 96H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128c0-17.67-14.33-32-32-32zM304 352c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8zM72 288v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H80c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm40-64c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-48c0-8.84 7.16-16 16-16h208c8.84 0 16 7.16 16 16v48zm272 128c0 4.42-3.58 8-8 8H344c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8z\"],\n    \"directions\": [512, 512, [], \"f5eb\", \"M502.61 233.32L278.68 9.39c-12.52-12.52-32.83-12.52-45.36 0L9.39 233.32c-12.52 12.53-12.52 32.83 0 45.36l223.93 223.93c12.52 12.53 32.83 12.53 45.36 0l223.93-223.93c12.52-12.53 12.52-32.83 0-45.36zm-100.98 12.56l-84.21 77.73c-5.12 4.73-13.43 1.1-13.43-5.88V264h-96v64c0 4.42-3.58 8-8 8h-32c-4.42 0-8-3.58-8-8v-80c0-17.67 14.33-32 32-32h112v-53.73c0-6.97 8.3-10.61 13.43-5.88l84.21 77.73c3.43 3.17 3.43 8.59 0 11.76z\"],\n    \"divide\": [448, 512, [], \"f529\", \"M224 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm0-192c35.35 0 64-28.65 64-64s-28.65-64-64-64-64 28.65-64 64 28.65 64 64 64zm192 48H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-96 206.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L174.6 192l28.7 28.7c15.2 15.2-7.9 37.4-22.6 22.6L152 214.6zM248 416c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm147.3-195.3c15.2 15.2-7.9 37.4-22.6 22.6L344 214.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L366.6 192l28.7 28.7z\"],\n    \"dna\": [448, 512, [], \"f471\", \"M.1 494.1c-1.1 9.5 6.3 17.8 15.9 17.8l32.3.1c8.1 0 14.9-5.9 16-13.9.7-4.9 1.8-11.1 3.4-18.1H380c1.6 6.9 2.9 13.2 3.5 18.1 1.1 8 7.9 14 16 13.9l32.3-.1c9.6 0 17.1-8.3 15.9-17.8-4.6-37.9-25.6-129-118.9-207.7-17.6 12.4-37.1 24.2-58.5 35.4 6.2 4.6 11.4 9.4 17 14.2H159.7c21.3-18.1 47-35.6 78.7-51.4C410.5 199.1 442.1 65.8 447.9 17.9 449 8.4 441.6.1 432 .1L399.6 0c-8.1 0-14.9 5.9-16 13.9-.7 4.9-1.8 11.1-3.4 18.1H67.8c-1.6-7-2.7-13.1-3.4-18.1-1.1-8-7.9-14-16-13.9L16.1.1C6.5.1-1 8.4.1 17.9 5.3 60.8 31.4 171.8 160 256 31.5 340.2 5.3 451.2.1 494.1zM224 219.6c-25.1-13.7-46.4-28.4-64.3-43.6h128.5c-17.8 15.2-39.1 30-64.2 43.6zM355.1 96c-5.8 10.4-12.8 21.1-21 32H114c-8.3-10.9-15.3-21.6-21-32h262.1zM92.9 416c5.8-10.4 12.8-21.1 21-32h219.4c8.3 10.9 15.4 21.6 21.2 32H92.9z\"],\n    \"dog\": [512, 512, [], \"f6d3\", \"M496 96h-64l-7.16-14.31A32 32 0 0 0 396.22 64H342.6l-27.28-27.28C305.23 26.64 288 33.78 288 48.03v149.84l128 45.71V208h32c35.35 0 64-28.65 64-64v-32c0-8.84-7.16-16-16-16zm-112 48c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM96 224c-17.64 0-32-14.36-32-32 0-17.67-14.33-32-32-32S0 174.33 0 192c0 41.66 26.83 76.85 64 90.1V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V384h160v112c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V277.55L266.05 224H96z\"],\n    \"dollar-sign\": [288, 512, [], \"f155\", \"M209.2 233.4l-108-31.6C88.7 198.2 80 186.5 80 173.5c0-16.3 13.2-29.5 29.5-29.5h66.3c12.2 0 24.2 3.7 34.2 10.5 6.1 4.1 14.3 3.1 19.5-2l34.8-34c7.1-6.9 6.1-18.4-1.8-24.5C238 74.8 207.4 64.1 176 64V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48h-2.5C45.8 64-5.4 118.7.5 183.6c4.2 46.1 39.4 83.6 83.8 96.6l102.5 30c12.5 3.7 21.2 15.3 21.2 28.3 0 16.3-13.2 29.5-29.5 29.5h-66.3C100 368 88 364.3 78 357.5c-6.1-4.1-14.3-3.1-19.5 2l-34.8 34c-7.1 6.9-6.1 18.4 1.8 24.5 24.5 19.2 55.1 29.9 86.5 30v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48.2c46.6-.9 90.3-28.6 105.7-72.7 21.5-61.6-14.6-124.8-72.5-141.7z\"],\n    \"dolly\": [576, 512, [], \"f472\", \"M294.2 277.7c18 5 34.7 13.4 49.5 24.7l161.5-53.8c8.4-2.8 12.9-11.9 10.1-20.2L454.9 47.2c-2.8-8.4-11.9-12.9-20.2-10.1l-61.1 20.4 33.1 99.4L346 177l-33.1-99.4-61.6 20.5c-8.4 2.8-12.9 11.9-10.1 20.2l53 159.4zm281 48.7L565 296c-2.8-8.4-11.9-12.9-20.2-10.1l-213.5 71.2c-17.2-22-43.6-36.4-73.5-37L158.4 21.9C154 8.8 141.8 0 128 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h88.9l92.2 276.7c-26.1 20.4-41.7 53.6-36 90.5 6.1 39.4 37.9 72.3 77.3 79.2 60.2 10.7 112.3-34.8 113.4-92.6l213.3-71.2c8.3-2.8 12.9-11.8 10.1-20.2zM256 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"dolly-flatbed\": [640, 512, [], \"f474\", \"M208 320h384c8.8 0 16-7.2 16-16V48c0-8.8-7.2-16-16-16H448v128l-48-32-48 32V32H208c-8.8 0-16 7.2-16 16v256c0 8.8 7.2 16 16 16zm416 64H128V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h82.9c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H451c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H624c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"donate\": [512, 512, [], \"f4b9\", \"M256 416c114.9 0 208-93.1 208-208S370.9 0 256 0 48 93.1 48 208s93.1 208 208 208zM233.8 97.4V80.6c0-9.2 7.4-16.6 16.6-16.6h11.1c9.2 0 16.6 7.4 16.6 16.6v17c15.5.8 30.5 6.1 43 15.4 5.6 4.1 6.2 12.3 1.2 17.1L306 145.6c-3.8 3.7-9.5 3.8-14 1-5.4-3.4-11.4-5.1-17.8-5.1h-38.9c-9 0-16.3 8.2-16.3 18.3 0 8.2 5 15.5 12.1 17.6l62.3 18.7c25.7 7.7 43.7 32.4 43.7 60.1 0 34-26.4 61.5-59.1 62.4v16.8c0 9.2-7.4 16.6-16.6 16.6h-11.1c-9.2 0-16.6-7.4-16.6-16.6v-17c-15.5-.8-30.5-6.1-43-15.4-5.6-4.1-6.2-12.3-1.2-17.1l16.3-15.5c3.8-3.7 9.5-3.8 14-1 5.4 3.4 11.4 5.1 17.8 5.1h38.9c9 0 16.3-8.2 16.3-18.3 0-8.2-5-15.5-12.1-17.6l-62.3-18.7c-25.7-7.7-43.7-32.4-43.7-60.1.1-34 26.4-61.5 59.1-62.4zM480 352h-32.5c-19.6 26-44.6 47.7-73 64h63.8c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8h63.8c-28.4-16.3-53.3-38-73-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32z\"],\n    \"door-closed\": [640, 512, [], \"f52a\", \"M624 448H512V50.8C512 22.78 490.47 0 464 0H175.99c-26.47 0-48 22.78-48 50.8V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM415.99 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32c.01 17.67-14.32 32-32 32z\"],\n    \"door-open\": [640, 512, [], \"f52b\", \"M624 448h-80V113.45C544 86.19 522.47 64 496 64H384v64h96v384h144c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM312.24 1.01l-192 49.74C105.99 54.44 96 67.7 96 82.92V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h336V33.18c0-21.58-19.56-37.41-39.76-32.17zM264 288c-13.25 0-24-14.33-24-32s10.75-32 24-32 24 14.33 24 32-10.75 32-24 32z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm80 248c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80z\"],\n    \"dove\": [512, 512, [], \"f4ba\", \"M288 167.2v-28.1c-28.2-36.3-47.1-79.3-54.1-125.2-2.1-13.5-19-18.8-27.8-8.3-21.1 24.9-37.7 54.1-48.9 86.5 34.2 38.3 80 64.6 130.8 75.1zM400 64c-44.2 0-80 35.9-80 80.1v59.4C215.6 197.3 127 133 87 41.8c-5.5-12.5-23.2-13.2-29-.9C41.4 76 32 115.2 32 156.6c0 70.8 34.1 136.9 85.1 185.9 13.2 12.7 26.1 23.2 38.9 32.8l-143.9 36C1.4 414-3.4 426.4 2.6 435.7 20 462.6 63 508.2 155.8 512c8 .3 16-2.6 22.1-7.9l65.2-56.1H320c88.4 0 160-71.5 160-159.9V128l32-64H400zm0 96.1c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"download\": [512, 512, [], \"f019\", \"M216 0h80c13.3 0 24 10.7 24 24v168h87.7c17.8 0 26.7 21.5 14.1 34.1L269.7 378.3c-7.5 7.5-19.8 7.5-27.3 0L90.1 226.1c-12.6-12.6-3.7-34.1 14.1-34.1H192V24c0-13.3 10.7-24 24-24zm296 376v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h146.7l49 49c20.1 20.1 52.5 20.1 72.6 0l49-49H488c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"drafting-compass\": [512, 512, [], \"f568\", \"M457.01 344.42c-25.05 20.33-52.63 37.18-82.54 49.05l54.38 94.19 53.95 23.04c9.81 4.19 20.89-2.21 22.17-12.8l7.02-58.25-54.98-95.23zm42.49-94.56c4.86-7.67 1.89-17.99-6.05-22.39l-28.07-15.57c-7.48-4.15-16.61-1.46-21.26 5.72C403.01 281.15 332.25 320 256 320c-23.93 0-47.23-4.25-69.41-11.53l67.36-116.68c.7.02 1.34.21 2.04.21s1.35-.19 2.04-.21l51.09 88.5c31.23-8.96 59.56-25.75 82.61-48.92l-51.79-89.71C347.39 128.03 352 112.63 352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96c0 16.63 4.61 32.03 12.05 45.66l-68.3 118.31c-12.55-11.61-23.96-24.59-33.68-39-4.79-7.1-13.97-9.62-21.38-5.33l-27.75 16.07c-7.85 4.54-10.63 14.9-5.64 22.47 15.57 23.64 34.69 44.21 55.98 62.02L0 439.66l7.02 58.25c1.28 10.59 12.36 16.99 22.17 12.8l53.95-23.04 70.8-122.63C186.13 377.28 220.62 384 256 384c99.05 0 190.88-51.01 243.5-134.14zM256 64c17.67 0 32 14.33 32 32s-14.33 32-32 32-32-14.33-32-32 14.33-32 32-32z\"],\n    \"dragon\": [640, 512, [], \"f6d5\", \"M18.32 255.78L192 223.96l-91.28 68.69c-10.08 10.08-2.94 27.31 11.31 27.31h222.7c-9.44-26.4-14.73-54.47-14.73-83.38v-42.27l-119.73-87.6c-23.82-15.88-55.29-14.01-77.06 4.59L5.81 227.64c-12.38 10.33-3.45 30.42 12.51 28.14zm556.87 34.1l-100.66-50.31A47.992 47.992 0 0 1 448 196.65v-36.69h64l28.09 22.63c6 6 14.14 9.37 22.63 9.37h30.97a32 32 0 0 0 28.62-17.69l14.31-28.62a32.005 32.005 0 0 0-3.02-33.51l-74.53-99.38C553.02 4.7 543.54 0 533.47 0H296.02c-7.13 0-10.7 8.57-5.66 13.61L352 63.96 292.42 88.8c-5.9 2.95-5.9 11.36 0 14.31L352 127.96v108.62c0 72.08 36.03 139.39 96 179.38-195.59 6.81-344.56 41.01-434.1 60.91C5.78 478.67 0 485.88 0 494.2 0 504 7.95 512 17.76 512h499.08c63.29.01 119.61-47.56 122.99-110.76 2.52-47.28-22.73-90.4-64.64-111.36zM489.18 66.25l45.65 11.41c-2.75 10.91-12.47 18.89-24.13 18.26-12.96-.71-25.85-12.53-21.52-29.67z\"],\n    \"draw-polygon\": [448, 512, [], \"f5ee\", \"M384 352c-.35 0-.67.1-1.02.1l-39.2-65.32c5.07-9.17 8.22-19.56 8.22-30.78s-3.14-21.61-8.22-30.78l39.2-65.32c.35.01.67.1 1.02.1 35.35 0 64-28.65 64-64s-28.65-64-64-64c-23.63 0-44.04 12.95-55.12 32H119.12C108.04 44.95 87.63 32 64 32 28.65 32 0 60.65 0 96c0 23.63 12.95 44.04 32 55.12v209.75C12.95 371.96 0 392.37 0 416c0 35.35 28.65 64 64 64 23.63 0 44.04-12.95 55.12-32h209.75c11.09 19.05 31.49 32 55.12 32 35.35 0 64-28.65 64-64 .01-35.35-28.64-64-63.99-64zm-288 8.88V151.12A63.825 63.825 0 0 0 119.12 128h208.36l-38.46 64.1c-.35-.01-.67-.1-1.02-.1-35.35 0-64 28.65-64 64s28.65 64 64 64c.35 0 .67-.1 1.02-.1l38.46 64.1H119.12A63.748 63.748 0 0 0 96 360.88zM272 256c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zM400 96c0 8.82-7.18 16-16 16s-16-7.18-16-16 7.18-16 16-16 16 7.18 16 16zM64 80c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zM48 416c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zm336 16c-8.82 0-16-7.18-16-16s7.18-16 16-16 16 7.18 16 16-7.18 16-16 16z\"],\n    \"drum\": [576, 512, [], \"f569\", \"M458.08 120.88l102.39-61.43c15.16-9.09 20.06-28.75 10.97-43.91C562.34.39 542.7-4.53 527.53 4.57l-160.69 96.41A629.32 629.32 0 0 0 288 96C128.94 96 0 153.31 0 224v160.83c0 30.46 24.03 58.4 64 80.37v-96.37c0-17.6 14.4-32 32-32s32 14.4 32 32v122.41c37.4 11.13 81 18.44 128 20.75V400.84c0-17.6 14.4-32 32-32s32 14.4 32 32V512c47-2.31 90.6-9.62 128-20.75V368.84c0-17.6 14.4-32 32-32s32 14.4 32 32v96.37c39.97-21.97 64-49.91 64-80.37V224.01c-.01-42.38-46.54-79.84-117.92-103.13zM288 304c-132.55 0-240-35.82-240-80s107.45-80 240-80c2.34 0 4.62.1 6.94.12l-87.41 52.44c-15.16 9.09-20.06 28.75-10.97 43.91 9.56 15.93 29.51 19.61 43.91 10.97l162.71-97.62C477.55 167.41 528 193.74 528 224.01 528 268.19 420.54 304 288 304z\"],\n    \"drum-steelpan\": [576, 512, [], \"f56a\", \"M288 32C128.94 32 0 89.31 0 160v192c0 70.69 128.94 128 288 128s288-57.31 288-128V160c0-70.69-128.94-128-288-128zm-82.99 158.36c-4.45 16.61-14.54 30.57-28.31 40.48C100.23 217.46 48 190.78 48 160c0-30.16 50.11-56.39 124.04-70.03l25.6 44.34c9.86 17.09 12.48 36.99 7.37 56.05zM288 240c-21.08 0-41.41-1-60.89-2.7 8.06-26.13 32.15-45.3 60.89-45.3s52.83 19.17 60.89 45.3C329.41 239 309.08 240 288 240zm64-144c0 35.29-28.71 64-64 64s-64-28.71-64-64V82.96c20.4-1.88 41.8-2.96 64-2.96s43.6 1.08 64 2.96V96zm46.93 134.9c-13.81-9.91-23.94-23.9-28.4-40.54-5.11-19.06-2.49-38.96 7.38-56.04l25.65-44.42C477.72 103.5 528 129.79 528 160c0 30.83-52.4 57.54-129.07 70.9z\"],\n    \"drumstick-bite\": [512, 512, [], \"f6d7\", \"M462.8 49.57a169.44 169.44 0 0 0-239.5 0C187.82 85 160.13 128 160.13 192v85.83l-40.62 40.59c-9.7 9.69-24 11.07-36.78 6a60.33 60.33 0 0 0-65 98.72C33 438.39 54.24 442.7 73.85 438.21c-4.5 19.6-.18 40.83 15.1 56.1a60.35 60.35 0 0 0 98.8-65c-5.09-12.73-3.72-27 6-36.75L234.36 352h85.89a187.87 187.87 0 0 0 61.89-10c-39.64-43.89-39.83-110.23 1.05-151.07 34.38-34.36 86.76-39.46 128.74-16.8 1.3-44.96-14.81-90.28-49.13-124.56z\"],\n    \"dumbbell\": [640, 512, [], \"f44b\", \"M104 96H56c-13.3 0-24 10.7-24 24v104H8c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h24v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm528 128h-24V120c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v272c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h24c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zM456 32h-48c-13.3 0-24 10.7-24 24v168H256V56c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v400c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h128v168c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24z\"],\n    \"dumpster\": [576, 512, [], \"f793\", \"M560 160c10.4 0 18-9.8 15.5-19.9l-24-96C549.7 37 543.3 32 536 32h-98.9l25.6 128H560zM272 32H171.5l-25.6 128H272V32zm132.5 0H304v128h126.1L404.5 32zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm544 64h-20l4-32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h320v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16l20-160h28c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dumpster-fire\": [640, 512, [], \"f794\", \"M418.7 104.1l.2-.2-14.4-72H304v128h60.8c16.2-19.3 34.2-38.2 53.9-55.8zM272 32H171.5l-25.6 128H272V32zm189.3 72.1c18.2 16.3 35.5 33.7 51.1 51.5 5.7-5.6 11.4-11.1 17.3-16.3l21.3-19 21.3 19c1.1.9 2.1 2.1 3.1 3.1-.1-.8.2-1.5 0-2.3l-24-96C549.7 37 543.3 32 536 32h-98.9l12.3 61.5 11.9 10.6zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm324.6 32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208.8c-30.2-33.7-48.8-77.9-48.8-126.4 0-35.9 19.9-82.9 52.6-129.6zm210.5-28.8c-14.9 13.3-28.3 27.2-40.2 41.2-19.5-25.8-43.6-52-71-76.4-70.2 62.7-120 144.3-120 193.6 0 87.5 71.6 158.4 160 158.4s160-70.9 160-158.4c.1-36.6-37-112.2-88.8-158.4zm-18.6 229.4c-14.7 10.7-32.9 17-52.5 17-49 0-88.9-33.5-88.9-88 0-27.1 16.5-51 49.4-91.9 4.7 5.6 67.1 88.1 67.1 88.1l39.8-47c2.8 4.8 5.4 9.5 7.7 14 18.6 36.7 10.8 83.6-22.6 107.8z\"],\n    \"dungeon\": [512, 512, [], \"f6d9\", \"M128.73 195.32l-82.81-51.76c-8.04-5.02-18.99-2.17-22.93 6.45A254.19 254.19 0 0 0 .54 239.28C-.05 248.37 7.59 256 16.69 256h97.13c7.96 0 14.08-6.25 15.01-14.16 1.09-9.33 3.24-18.33 6.24-26.94 2.56-7.34.25-15.46-6.34-19.58zM319.03 8C298.86 2.82 277.77 0 256 0s-42.86 2.82-63.03 8c-9.17 2.35-13.91 12.6-10.39 21.39l37.47 104.03A16.003 16.003 0 0 0 235.1 144h41.8c6.75 0 12.77-4.23 15.05-10.58l37.47-104.03c3.52-8.79-1.22-19.03-10.39-21.39zM112 288H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm77.31-283.67l-36.32-90.8c-3.53-8.83-14.13-12.99-22.42-8.31a257.308 257.308 0 0 0-71.61 59.89c-6.06 7.32-3.85 18.48 4.22 23.52l82.93 51.83c6.51 4.07 14.66 2.62 20.11-2.79 5.18-5.15 10.79-9.85 16.79-14.05 6.28-4.41 9.15-12.17 6.3-19.29zM398.18 256h97.13c9.1 0 16.74-7.63 16.15-16.72a254.135 254.135 0 0 0-22.45-89.27c-3.94-8.62-14.89-11.47-22.93-6.45l-82.81 51.76c-6.59 4.12-8.9 12.24-6.34 19.58 3.01 8.61 5.15 17.62 6.24 26.94.93 7.91 7.05 14.16 15.01 14.16zm54.85-162.89a257.308 257.308 0 0 0-71.61-59.89c-8.28-4.68-18.88-.52-22.42 8.31l-36.32 90.8c-2.85 7.12.02 14.88 6.3 19.28 6 4.2 11.61 8.9 16.79 14.05 5.44 5.41 13.6 6.86 20.11 2.79l82.93-51.83c8.07-5.03 10.29-16.19 4.22-23.51zM496 288h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zM240 177.62V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V177.62c-5.23-.89-10.52-1.62-16-1.62s-10.77.73-16 1.62zm-64 41.51V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V189.36c-12.78 7.45-23.84 17.47-32 29.77zm128-29.77V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V219.13c-8.16-12.3-19.22-22.32-32-29.77z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.6 83.2l90.2 90.2c3.8 3.8 3.8 10 0 13.8L274.4 405.6l-92.8 10.3c-12.4 1.4-22.9-9.1-21.5-21.5l10.3-92.8L388.8 83.2c3.8-3.8 10-3.8 13.8 0zm162-22.9l-48.8-48.8c-15.2-15.2-39.9-15.2-55.2 0l-35.4 35.4c-3.8 3.8-3.8 10 0 13.8l90.2 90.2c3.8 3.8 10 3.8 13.8 0l35.4-35.4c15.2-15.3 15.2-40 0-55.2zM384 346.2V448H64V128h229.8c3.2 0 6.2-1.3 8.5-3.5l40-40c7.6-7.6 2.2-20.5-8.5-20.5H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V306.2c0-10.7-12.9-16-20.5-8.5l-40 40c-2.2 2.3-3.5 5.3-3.5 8.5z\"],\n    \"egg\": [384, 512, [], \"f7fb\", \"M192 0C86 0 0 214 0 320s86 192 192 192 192-86 192-192S298 0 192 0z\"],\n    \"eject\": [448, 512, [], \"f052\", \"M448 384v64c0 17.673-14.327 32-32 32H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h384c17.673 0 32 14.327 32 32zM48.053 320h351.886c41.651 0 63.581-49.674 35.383-80.435L259.383 47.558c-19.014-20.743-51.751-20.744-70.767 0L12.67 239.565C-15.475 270.268 6.324 320 48.053 320z\"],\n    \"ellipsis-h\": [512, 512, [], \"f141\", \"M328 256c0 39.8-32.2 72-72 72s-72-32.2-72-72 32.2-72 72-72 72 32.2 72 72zm104-72c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm-352 0c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72z\"],\n    \"ellipsis-v\": [192, 512, [], \"f142\", \"M96 184c39.8 0 72 32.2 72 72s-32.2 72-72 72-72-32.2-72-72 32.2-72 72-72zM24 80c0 39.8 32.2 72 72 72s72-32.2 72-72S135.8 8 96 8 24 40.2 24 80zm0 352c0 39.8 32.2 72 72 72s72-32.2 72-72-32.2-72-72-72-72 32.2-72 72z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M502.3 190.8c3.9-3.1 9.7-.2 9.7 4.7V400c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V195.6c0-5 5.7-7.8 9.7-4.7 22.4 17.4 52.1 39.5 154.1 113.6 21.1 15.4 56.7 47.8 92.2 47.6 35.7.3 72-32.8 92.3-47.6 102-74.1 131.6-96.3 154-113.7zM256 320c23.2.4 56.6-29.2 73.4-41.4 132.7-96.3 142.8-104.7 173.4-128.7 5.8-4.5 9.2-11.5 9.2-18.9v-19c0-26.5-21.5-48-48-48H48C21.5 64 0 85.5 0 112v19c0 7.4 3.4 14.3 9.2 18.9 30.6 23.9 40.7 32.4 173.4 128.7 16.8 12.2 50.2 41.8 73.4 41.4z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M512 464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V200.724a48 48 0 0 1 18.387-37.776c24.913-19.529 45.501-35.365 164.2-121.511C199.412 29.17 232.797-.347 256 .003c23.198-.354 56.596 29.172 73.413 41.433 118.687 86.137 139.303 101.995 164.2 121.512A48 48 0 0 1 512 200.724V464zm-65.666-196.605c-2.563-3.728-7.7-4.595-11.339-1.907-22.845 16.873-55.462 40.705-105.582 77.079-16.825 12.266-50.21 41.781-73.413 41.43-23.211.344-56.559-29.143-73.413-41.43-50.114-36.37-82.734-60.204-105.582-77.079-3.639-2.688-8.776-1.821-11.339 1.907l-9.072 13.196a7.998 7.998 0 0 0 1.839 10.967c22.887 16.899 55.454 40.69 105.303 76.868 20.274 14.781 56.524 47.813 92.264 47.573 35.724.242 71.961-32.771 92.263-47.573 49.85-36.179 82.418-59.97 105.303-76.868a7.998 7.998 0 0 0 1.839-10.967l-9.071-13.196z\"],\n    \"envelope-open-text\": [512, 512, [], \"f658\", \"M176 216h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16zm-16 80c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16zm96 121.13c-16.42 0-32.84-5.06-46.86-15.19L0 250.86V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V250.86L302.86 401.94c-14.02 10.12-30.44 15.19-46.86 15.19zm237.61-254.18c-8.85-6.94-17.24-13.47-29.61-22.81V96c0-26.51-21.49-48-48-48h-77.55c-3.04-2.2-5.87-4.26-9.04-6.56C312.6 29.17 279.2-.35 256 0c-23.2-.35-56.59 29.17-73.41 41.44-3.17 2.3-6 4.36-9.04 6.56H96c-26.51 0-48 21.49-48 48v44.14c-12.37 9.33-20.76 15.87-29.61 22.81A47.995 47.995 0 0 0 0 200.72v10.65l96 69.35V96h320v184.72l96-69.35v-10.65c0-14.74-6.78-28.67-18.39-37.77z\"],\n    \"envelope-square\": [448, 512, [], \"f199\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM178.117 262.104C87.429 196.287 88.353 196.121 64 177.167V152c0-13.255 10.745-24 24-24h272c13.255 0 24 10.745 24 24v25.167c-24.371 18.969-23.434 19.124-114.117 84.938-10.5 7.655-31.392 26.12-45.883 25.894-14.503.218-35.367-18.227-45.883-25.895zM384 217.775V360c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V217.775c13.958 10.794 33.329 25.236 95.303 70.214 14.162 10.341 37.975 32.145 64.694 32.01 26.887.134 51.037-22.041 64.72-32.025 61.958-44.965 81.325-59.406 95.283-70.199z\"],\n    \"equals\": [448, 512, [], \"f52c\", \"M416 304H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32zm0-192H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"eraser\": [512, 512, [], \"f12d\", \"M497.941 273.941c18.745-18.745 18.745-49.137 0-67.882l-160-160c-18.745-18.745-49.136-18.746-67.883 0l-256 256c-18.745 18.745-18.745 49.137 0 67.882l96 96A48.004 48.004 0 0 0 144 480h356c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H355.883l142.058-142.059zm-302.627-62.627l137.373 137.373L265.373 416H150.628l-80-80 124.686-124.686z\"],\n    \"ethernet\": [512, 512, [], \"f796\", \"M496 192h-48v-48c0-8.8-7.2-16-16-16h-48V80c0-8.8-7.2-16-16-16H144c-8.8 0-16 7.2-16 16v48H80c-8.8 0-16 7.2-16 16v48H16c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16h80V320h32v128h64V320h32v128h64V320h32v128h64V320h32v128h80c8.8 0 16-7.2 16-16V208c0-8.8-7.2-16-16-16z\"],\n    \"euro-sign\": [320, 512, [], \"f153\", \"M310.706 413.765c-1.314-6.63-7.835-10.872-14.424-9.369-10.692 2.439-27.422 5.413-45.426 5.413-56.763 0-101.929-34.79-121.461-85.449h113.689a12 12 0 0 0 11.708-9.369l6.373-28.36c1.686-7.502-4.019-14.631-11.708-14.631H115.22c-1.21-14.328-1.414-28.287.137-42.245H261.95a12 12 0 0 0 11.723-9.434l6.512-29.755c1.638-7.484-4.061-14.566-11.723-14.566H130.184c20.633-44.991 62.69-75.03 117.619-75.03 14.486 0 28.564 2.25 37.851 4.145 6.216 1.268 12.347-2.498 14.002-8.623l11.991-44.368c1.822-6.741-2.465-13.616-9.326-14.917C290.217 34.912 270.71 32 249.635 32 152.451 32 74.03 92.252 45.075 176H12c-6.627 0-12 5.373-12 12v29.755c0 6.627 5.373 12 12 12h21.569c-1.009 13.607-1.181 29.287-.181 42.245H12c-6.627 0-12 5.373-12 12v28.36c0 6.627 5.373 12 12 12h30.114C67.139 414.692 145.264 480 249.635 480c26.301 0 48.562-4.544 61.101-7.788 6.167-1.595 10.027-7.708 8.788-13.957l-8.818-44.49z\"],\n    \"exchange-alt\": [512, 512, [], \"f362\", \"M0 168v-16c0-13.255 10.745-24 24-24h360V80c0-21.367 25.899-32.042 40.971-16.971l80 80c9.372 9.373 9.372 24.569 0 33.941l-80 80C409.956 271.982 384 261.456 384 240v-48H24c-13.255 0-24-10.745-24-24zm488 152H128v-48c0-21.314-25.862-32.08-40.971-16.971l-80 80c-9.372 9.373-9.372 24.569 0 33.941l80 80C102.057 463.997 128 453.437 128 432v-48h360c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"exclamation\": [192, 512, [], \"f12a\", \"M176 432c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zM25.26 25.199l13.6 272C39.499 309.972 50.041 320 62.83 320h66.34c12.789 0 23.331-10.028 23.97-22.801l13.6-272C167.425 11.49 156.496 0 142.77 0H49.23C35.504 0 24.575 11.49 25.26 25.199z\"],\n    \"exclamation-circle\": [512, 512, [], \"f06a\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zm-248 50c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"exclamation-triangle\": [576, 512, [], \"f071\", \"M569.517 440.013C587.975 472.007 564.806 512 527.94 512H48.054c-36.937 0-59.999-40.055-41.577-71.987L246.423 23.985c18.467-32.009 64.72-31.951 83.154 0l239.94 416.028zM288 354c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"expand\": [448, 512, [], \"f065\", \"M0 180V56c0-13.3 10.7-24 24-24h124c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H64v84c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12zM288 44v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V56c0-13.3-10.7-24-24-24H300c-6.6 0-12 5.4-12 12zm148 276h-40c-6.6 0-12 5.4-12 12v84h-84c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24V332c0-6.6-5.4-12-12-12zM160 468v-40c0-6.6-5.4-12-12-12H64v-84c0-6.6-5.4-12-12-12H12c-6.6 0-12 5.4-12 12v124c0 13.3 10.7 24 24 24h124c6.6 0 12-5.4 12-12z\"],\n    \"expand-arrows-alt\": [448, 512, [], \"f31e\", \"M448 344v112a23.94 23.94 0 0 1-24 24H312c-21.39 0-32.09-25.9-17-41l36.2-36.2L224 295.6 116.77 402.9 153 439c15.09 15.1 4.39 41-17 41H24a23.94 23.94 0 0 1-24-24V344c0-21.4 25.89-32.1 41-17l36.19 36.2L184.46 256 77.18 148.7 41 185c-15.1 15.1-41 4.4-41-17V56a23.94 23.94 0 0 1 24-24h112c21.39 0 32.09 25.9 17 41l-36.2 36.2L224 216.4l107.23-107.3L295 73c-15.09-15.1-4.39-41 17-41h112a23.94 23.94 0 0 1 24 24v112c0 21.4-25.89 32.1-41 17l-36.19-36.2L263.54 256l107.28 107.3L407 327.1c15.1-15.2 41-4.5 41 16.9z\"],\n    \"external-link-alt\": [576, 512, [], \"f35d\", \"M576 24v127.984c0 21.461-25.96 31.98-40.971 16.971l-35.707-35.709-243.523 243.523c-9.373 9.373-24.568 9.373-33.941 0l-22.627-22.627c-9.373-9.373-9.373-24.569 0-33.941L442.756 76.676l-35.703-35.705C391.982 25.9 402.656 0 424.024 0H552c13.255 0 24 10.745 24 24zM407.029 270.794l-16 16A23.999 23.999 0 0 0 384 303.765V448H64V128h264a24.003 24.003 0 0 0 16.97-7.029l16-16C376.089 89.851 365.381 64 344 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V287.764c0-21.382-25.852-32.09-40.971-16.97z\"],\n    \"external-link-square-alt\": [448, 512, [], \"f360\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-88 16H248.029c-21.313 0-32.08 25.861-16.971 40.971l31.984 31.987L67.515 364.485c-4.686 4.686-4.686 12.284 0 16.971l31.029 31.029c4.687 4.686 12.285 4.686 16.971 0l195.526-195.526 31.988 31.991C358.058 263.977 384 253.425 384 231.979V120c0-13.255-10.745-24-24-24z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M572.52 241.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400a144 144 0 1 1 144-144 143.93 143.93 0 0 1-144 144zm0-240a95.31 95.31 0 0 0-25.31 3.79 47.85 47.85 0 0 1-66.9 66.9A95.78 95.78 0 1 0 288 160z\"],\n    \"eye-dropper\": [512, 512, [], \"f1fb\", \"M50.75 333.25c-12 12-18.75 28.28-18.75 45.26V424L0 480l32 32 56-32h45.49c16.97 0 33.25-6.74 45.25-18.74l126.64-126.62-128-128L50.75 333.25zM483.88 28.12c-37.47-37.5-98.28-37.5-135.75 0l-77.09 77.09-13.1-13.1c-9.44-9.44-24.65-9.31-33.94 0l-40.97 40.97c-9.37 9.37-9.37 24.57 0 33.94l161.94 161.94c9.44 9.44 24.65 9.31 33.94 0L419.88 288c9.37-9.37 9.37-24.57 0-33.94l-13.1-13.1 77.09-77.09c37.51-37.48 37.51-98.26.01-135.75z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M320 400c-75.85 0-137.25-58.71-142.9-133.11L72.2 185.82c-13.79 17.3-26.48 35.59-36.72 55.59a32.35 32.35 0 0 0 0 29.19C89.71 376.41 197.07 448 320 448c26.91 0 52.87-4 77.89-10.46L346 397.39a144.13 144.13 0 0 1-26 2.61zm313.82 58.1l-110.55-85.44a331.25 331.25 0 0 0 81.25-102.07 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64a308.15 308.15 0 0 0-147.32 37.7L45.46 3.37A16 16 0 0 0 23 6.18L3.37 31.45A16 16 0 0 0 6.18 53.9l588.36 454.73a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zm-183.72-142l-39.3-30.38A94.75 94.75 0 0 0 416 256a94.76 94.76 0 0 0-121.31-92.21A47.65 47.65 0 0 1 304 192a46.64 46.64 0 0 1-1.54 10l-73.61-56.89A142.31 142.31 0 0 1 320 112a143.92 143.92 0 0 1 144 144c0 21.63-5.29 41.79-13.9 60.11z\"],\n    \"fan\": [512, 512, [], \"f863\", \"M352.57 128c-28.09 0-54.09 4.52-77.06 12.86l12.41-123.11C289 7.31 279.81-1.18 269.33.13 189.63 10.13 128 77.64 128 159.43c0 28.09 4.52 54.09 12.86 77.06L17.75 224.08C7.31 223-1.18 232.19.13 242.67c10 79.7 77.51 141.33 159.3 141.33 28.09 0 54.09-4.52 77.06-12.86l-12.41 123.11c-1.05 10.43 8.11 18.93 18.59 17.62 79.7-10 141.33-77.51 141.33-159.3 0-28.09-4.52-54.09-12.86-77.06l123.11 12.41c10.44 1.05 18.93-8.11 17.62-18.59-10-79.7-77.51-141.33-159.3-141.33zM256 288a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"fast-backward\": [512, 512, [], \"f049\", \"M0 436V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v151.9L235.5 71.4C256.1 54.3 288 68.6 288 96v131.9L459.5 71.4C480.1 54.3 512 68.6 512 96v320c0 27.4-31.9 41.7-52.5 24.6L288 285.3V416c0 27.4-31.9 41.7-52.5 24.6L64 285.3V436c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12z\"],\n    \"fast-forward\": [512, 512, [], \"f050\", \"M512 76v360c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V284.1L276.5 440.6c-20.6 17.2-52.5 2.8-52.5-24.6V284.1L52.5 440.6C31.9 457.8 0 443.4 0 416V96c0-27.4 31.9-41.7 52.5-24.6L224 226.8V96c0-27.4 31.9-41.7 52.5-24.6L448 226.8V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12z\"],\n    \"fax\": [512, 512, [], \"f1ac\", \"M64 128H32c-17.67 0-32 14.33-32 32v320c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zm416 32V77.25c0-8.49-3.37-16.62-9.37-22.63L425.37 9.37c-6-6-14.14-9.37-22.63-9.37H160c-17.67 0-32 14.33-32 32v448c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zM288 432c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm128 128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm16-112H176V48h208v32c0 8.84 7.16 16 16 16h32v96z\"],\n    \"feather\": [512, 512, [], \"f52d\", \"M467.14 44.84c-62.55-62.48-161.67-64.78-252.28 25.73-78.61 78.52-60.98 60.92-85.75 85.66-60.46 60.39-70.39 150.83-63.64 211.17l178.44-178.25c6.26-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.6 9.37 33.98 0l66.1-66.03C159.42 454.65 279 457.11 353.95 384h-98.19l147.57-49.14c49.99-49.93 36.38-36.18 46.31-46.86h-97.78l131.54-43.8c45.44-74.46 34.31-148.84-16.26-199.36z\"],\n    \"feather-alt\": [512, 512, [], \"f56b\", \"M512 0C460.22 3.56 96.44 38.2 71.01 287.61c-3.09 26.66-4.84 53.44-5.99 80.24l178.87-178.69c6.25-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.59 9.37 33.98 0l57.13-57.07c42.09-.14 84.15-2.53 125.96-7.36 53.48-5.44 97.02-26.47 132.58-56.54H255.74l146.79-48.88c11.25-14.89 21.37-30.71 30.45-47.12h-81.14l106.54-53.21C500.29 132.86 510.19 26.26 512 0z\"],\n    \"female\": [256, 512, [], \"f182\", \"M128 0c35.346 0 64 28.654 64 64s-28.654 64-64 64c-35.346 0-64-28.654-64-64S92.654 0 128 0m119.283 354.179l-48-192A24 24 0 0 0 176 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H80a24 24 0 0 0-23.283 18.179l-48 192C4.935 369.305 16.383 384 32 384h56v104c0 13.255 10.745 24 24 24h32c13.255 0 24-10.745 24-24V384h56c15.591 0 27.071-14.671 23.283-29.821z\"],\n    \"fighter-jet\": [640, 512, [], \"f0fb\", \"M544 224l-128-16-48-16h-24L227.158 44h39.509C278.333 44 288 41.375 288 38s-9.667-6-21.333-6H152v12h16v164h-48l-66.667-80H18.667L8 138.667V208h8v16h48v2.666l-64 8v42.667l64 8V288H16v16H8v69.333L18.667 384h34.667L120 304h48v164h-16v12h114.667c11.667 0 21.333-2.625 21.333-6s-9.667-6-21.333-6h-39.509L344 320h24l48-16 128-16c96-21.333 96-26.583 96-32 0-5.417 0-10.667-96-32z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm160-14.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 236c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-64c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-72v8c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm96-114.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zM128.4 336c-17.9 0-32.4 12.1-32.4 27 0 15 14.6 27 32.5 27s32.4-12.1 32.4-27-14.6-27-32.5-27zM224 136V0h-63.6v32h-32V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM95.9 32h32v32h-32zm32.3 384c-33.2 0-58-30.4-51.4-62.9L96.4 256v-32h32v-32h-32v-32h32v-32h-32V96h32V64h32v32h-32v32h32v32h-32v32h32v32h-32v32h22.1c5.7 0 10.7 4.1 11.8 9.7l17.3 87.7c6.4 32.4-18.4 62.6-51.4 62.6z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-64 268c0 10.7-12.9 16-20.5 8.5L104 376H76c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h28l35.5-36.5c7.6-7.6 20.5-2.2 20.5 8.5v136zm33.2-47.6c9.1-9.3 9.1-24.1 0-33.4-22.1-22.8 12.2-56.2 34.4-33.5 27.2 27.9 27.2 72.4 0 100.4-21.8 22.3-56.9-10.4-34.4-33.5zm86-117.1c54.4 55.9 54.4 144.8 0 200.8-21.8 22.4-57-10.3-34.4-33.5 36.2-37.2 36.3-96.5 0-133.8-22.1-22.8 12.3-56.3 34.4-33.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zM123.206 400.505a5.4 5.4 0 0 1-7.633.246l-64.866-60.812a5.4 5.4 0 0 1 0-7.879l64.866-60.812a5.4 5.4 0 0 1 7.633.246l19.579 20.885a5.4 5.4 0 0 1-.372 7.747L101.65 336l40.763 35.874a5.4 5.4 0 0 1 .372 7.747l-19.579 20.884zm51.295 50.479l-27.453-7.97a5.402 5.402 0 0 1-3.681-6.692l61.44-211.626a5.402 5.402 0 0 1 6.692-3.681l27.452 7.97a5.4 5.4 0 0 1 3.68 6.692l-61.44 211.626a5.397 5.397 0 0 1-6.69 3.681zm160.792-111.045l-64.866 60.812a5.4 5.4 0 0 1-7.633-.246l-19.58-20.885a5.4 5.4 0 0 1 .372-7.747L284.35 336l-40.763-35.874a5.4 5.4 0 0 1-.372-7.747l19.58-20.885a5.4 5.4 0 0 1 7.633-.246l64.866 60.812a5.4 5.4 0 0 1-.001 7.879z\"],\n    \"file-contract\": [384, 512, [], \"f56c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm192.81 248H304c8.84 0 16 7.16 16 16s-7.16 16-16 16h-47.19c-16.45 0-31.27-9.14-38.64-23.86-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34a15.986 15.986 0 0 1-14.31 8.84c-.38 0-.75-.02-1.14-.05-6.45-.45-12-4.75-14.03-10.89L144 354.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.77-16.19 54.05-9.7 66 14.16 2.02 4.06 5.96 6.5 10.16 6.5zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-csv\": [384, 512, [], \"f6dd\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-96 144c0 4.42-3.58 8-8 8h-8c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h8c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-8c-26.51 0-48-21.49-48-48v-32c0-26.51 21.49-48 48-48h8c4.42 0 8 3.58 8 8v16zm44.27 104H160c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h12.27c5.95 0 10.41-3.5 10.41-6.62 0-1.3-.75-2.66-2.12-3.84l-21.89-18.77c-8.47-7.22-13.33-17.48-13.33-28.14 0-21.3 19.02-38.62 42.41-38.62H200c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-12.27c-5.95 0-10.41 3.5-10.41 6.62 0 1.3.75 2.66 2.12 3.84l21.89 18.77c8.47 7.22 13.33 17.48 13.33 28.14.01 21.29-19 38.62-42.39 38.62zM256 264v20.8c0 20.27 5.7 40.17 16 56.88 10.3-16.7 16-36.61 16-56.88V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v20.8c0 35.48-12.88 68.89-36.28 94.09-3.02 3.25-7.27 5.11-11.72 5.11s-8.7-1.86-11.72-5.11c-23.4-25.2-36.28-58.61-36.28-94.09V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8zm121-159L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-download\": [384, 512, [], \"f56d\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm76.45 211.36l-96.42 95.7c-6.65 6.61-17.39 6.61-24.04 0l-96.42-95.7C73.42 337.29 80.54 320 94.82 320H160v-80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v80h65.18c14.28 0 21.4 17.29 11.27 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm60.1 106.5L224 336l60.1 93.5c5.1 8-.6 18.5-10.1 18.5h-34.9c-4.4 0-8.5-2.4-10.6-6.3C208.9 405.5 192 373 192 373c-6.4 14.8-10 20-36.6 68.8-2.1 3.9-6.1 6.3-10.5 6.3H110c-9.5 0-15.2-10.5-10.1-18.5l60.3-93.5-60.3-93.5c-5.2-8 .6-18.5 10.1-18.5h34.8c4.4 0 8.5 2.4 10.6 6.3 26.1 48.8 20 33.6 36.6 68.5 0 0 6.1-11.7 36.6-68.5 2.1-3.9 6.2-6.3 10.6-6.3H274c9.5-.1 15.2 10.4 10.1 18.4zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-export\": [576, 512, [], \"f56e\", \"M384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128zM571 308l-95.7-96.4c-10.1-10.1-27.4-3-27.4 11.3V288h-64v64h64v65.2c0 14.3 17.3 21.4 27.4 11.3L571 332c6.6-6.6 6.6-17.4 0-24zm-379 28v-32c0-8.8 7.2-16 16-16h176V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V352H208c-8.8 0-16-7.2-16-16z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M384 121.941V128H256V0h6.059a24 24 0 0 1 16.97 7.029l97.941 97.941a24.002 24.002 0 0 1 7.03 16.971zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zm-135.455 16c26.51 0 48 21.49 48 48s-21.49 48-48 48-48-21.49-48-48 21.491-48 48-48zm208 240h-256l.485-48.485L104.545 328c4.686-4.686 11.799-4.201 16.485.485L160.545 368 264.06 264.485c4.686-4.686 12.284-4.686 16.971 0L320.545 304v112z\"],\n    \"file-import\": [512, 512, [], \"f56f\", \"M16 288c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h112v-64zm489-183L407.1 7c-4.5-4.5-10.6-7-17-7H384v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H152c-13.3 0-24 10.7-24 24v264h128v-65.2c0-14.3 17.3-21.4 27.4-11.3L379 308c6.6 6.7 6.6 17.4 0 24l-95.7 96.4c-10.1 10.1-27.4 3-27.4-11.3V352H128v136c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H376c-13.2 0-24-10.8-24-24z\"],\n    \"file-invoice\": [384, 512, [], \"f570\", \"M288 256H96v64h192v-64zm89-151L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm256 304c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-200v96c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-96c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16z\"],\n    \"file-invoice-dollar\": [384, 512, [], \"f571\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 80v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8zm144 263.88V440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-24.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V232c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v24.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07z\"],\n    \"file-medical\": [384, 512, [], \"f477\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 160v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8z\"],\n    \"file-medical-alt\": [448, 512, [], \"f478\", \"M288 136V0H88C74.7 0 64 10.7 64 24v232H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h140.9c3 0 5.8 1.7 7.2 4.4l19.9 39.8 56.8-113.7c2.9-5.9 11.4-5.9 14.3 0l34.7 69.5H352c8.8 0 16 7.2 16 16s-7.2 16-16 16h-89.9L240 275.8l-56.8 113.7c-2.9 5.9-11.4 5.9-14.3 0L134.1 320H64v168c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H312c-13.2 0-24-10.8-24-24zm153-31L343.1 7c-4.5-4.5-10.6-7-17-7H320v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M181.9 256.1c-5-16-4.9-46.9-2-46.9 8.4 0 7.6 36.9 2 46.9zm-1.7 47.2c-7.7 20.2-17.3 43.3-28.4 62.7 18.3-7 39-17.2 62.9-21.9-12.7-9.6-24.9-23.4-34.5-40.8zM86.1 428.1c0 .8 13.2-5.4 34.9-40.2-6.7 6.3-29.1 24.5-34.9 40.2zM248 160h136v328c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V24C0 10.7 10.7 0 24 0h200v136c0 13.2 10.8 24 24 24zm-8 171.8c-20-12.2-33.3-29-42.7-53.8 4.5-18.5 11.6-46.6 6.2-64.2-4.7-29.4-42.4-26.5-47.8-6.8-5 18.3-.4 44.1 8.1 77-11.6 27.6-28.7 64.6-40.8 85.8-.1 0-.1.1-.2.1-27.1 13.9-73.6 44.5-54.5 68 5.6 6.9 16 10 21.5 10 17.9 0 35.7-18 61.1-61.8 25.8-8.5 54.1-19.1 79-23.2 21.7 11.8 47.1 19.5 64 19.5 29.2 0 31.2-32 19.7-43.4-13.9-13.6-54.3-9.7-73.6-7.2zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-74.1 255.3c4.1-2.7-2.5-11.9-42.8-9 37.1 15.8 42.8 9 42.8 9z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M193.7 271.2c8.8 0 15.5 2.7 20.3 8.1 9.6 10.9 9.8 32.7-.2 44.1-4.9 5.6-11.9 8.5-21.1 8.5h-26.9v-60.7h27.9zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm53 165.2c0 90.3-88.8 77.6-111.1 77.6V436c0 6.6-5.4 12-12 12h-30.8c-6.6 0-12-5.4-12-12V236.2c0-6.6 5.4-12 12-12h81c44.5 0 72.9 32.8 72.9 77z\"],\n    \"file-prescription\": [384, 512, [], \"f572\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm68.53 179.48l11.31 11.31c6.25 6.25 6.25 16.38 0 22.63l-29.9 29.9L304 409.38c6.25 6.25 6.25 16.38 0 22.63l-11.31 11.31c-6.25 6.25-16.38 6.25-22.63 0L240 413.25l-30.06 30.06c-6.25 6.25-16.38 6.25-22.63 0L176 432c-6.25-6.25-6.25-16.38 0-22.63l30.06-30.06L146.74 320H128v48c0 8.84-7.16 16-16 16H96c-8.84 0-16-7.16-16-16V208c0-8.84 7.16-16 16-16h80c35.35 0 64 28.65 64 64 0 24.22-13.62 45.05-33.46 55.92L240 345.38l29.9-29.9c6.25-6.25 16.38-6.25 22.63 0zM176 272h-48v-32h48c8.82 0 16 7.18 16 16s-7.18 16-16 16zm208-150.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-signature\": [576, 512, [], \"f573\", \"M218.17 424.14c-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34c-6.37 12.78-25.03 11.37-29.48-2.09L144 386.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.75-16.19 54.06-9.7 66 14.16 1.89 3.78 5.49 5.95 9.36 6.26v-82.12l128-127.09V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24v-40l-128-.11c-16.12-.31-30.58-9.28-37.83-23.75zM384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1zm-96 225.06V416h68.99l161.68-162.78-67.88-67.88L288 346.96zm280.54-179.63l-31.87-31.87c-9.94-9.94-26.07-9.94-36.01 0l-27.25 27.25 67.88 67.88 27.25-27.25c9.95-9.94 9.95-26.07 0-36.01z\"],\n    \"file-upload\": [384, 512, [], \"f574\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm65.18 216.01H224v80c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-80H94.82c-14.28 0-21.41-17.29-11.27-27.36l96.42-95.7c6.65-6.61 17.39-6.61 24.04 0l96.42 95.7c10.15 10.07 3.03 27.36-11.25 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM224 136V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248c-13.2 0-24-10.8-24-24zm96 144.016v111.963c0 21.445-25.943 31.998-40.971 16.971L224 353.941V392c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V280c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v38.059l55.029-55.013c15.011-15.01 40.971-4.491 40.971 16.97z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm57.1 120H305c7.7 0 13.4 7.1 11.7 14.7l-38 168c-1.2 5.5-6.1 9.3-11.7 9.3h-38c-5.5 0-10.3-3.8-11.6-9.1-25.8-103.5-20.8-81.2-25.6-110.5h-.5c-1.1 14.3-2.4 17.4-25.6 110.5-1.3 5.3-6.1 9.1-11.6 9.1H117c-5.6 0-10.5-3.9-11.7-9.4l-37.8-168c-1.7-7.5 4-14.6 11.7-14.6h24.5c5.7 0 10.7 4 11.8 9.7 15.6 78 20.1 109.5 21 122.2 1.6-10.2 7.3-32.7 29.4-122.7 1.3-5.4 6.1-9.1 11.7-9.1h29.1c5.6 0 10.4 3.8 11.7 9.2 24 100.4 28.8 124 29.6 129.4-.2-11.2-2.6-17.8 21.6-129.2 1-5.6 5.9-9.5 11.5-9.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"fill\": [512, 512, [], \"f575\", \"M502.63 217.06L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.77c-6.24-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.63l86.19 86.18-94.76 94.76c-37.49 37.49-37.49 98.26 0 135.75l117.19 117.19c18.75 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.88-28.12l221.57-221.57c12.49-12.5 12.49-32.76 0-45.26zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.61 58.6c12.49 12.49 32.75 12.49 45.24 0 12.49-12.49 12.49-32.75 0-45.24l-58.61-58.6 58.95-58.95 162.45 162.44-48.35 48.34z\"],\n    \"fill-drip\": [576, 512, [], \"f576\", \"M512 320s-64 92.65-64 128c0 35.35 28.66 64 64 64s64-28.65 64-64-64-128-64-128zm-9.37-102.94L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.76c-6.25-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.62l86.19 86.18-94.76 94.76c-37.49 37.48-37.49 98.26 0 135.75l117.19 117.19c18.74 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.87-28.12l221.57-221.57c12.5-12.5 12.5-32.75.01-45.25zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.6 58.6c12.49 12.49 32.75 12.49 45.24 0s12.49-32.75 0-45.24l-58.6-58.6 58.95-58.95 162.44 162.44-48.34 48.34z\"],\n    \"film\": [512, 512, [], \"f008\", \"M488 64h-8v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V64H96v20c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12V64h-8C10.7 64 0 74.7 0 88v336c0 13.3 10.7 24 24 24h8v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h320v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h8c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24zM96 372c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm272 208c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm0-168c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm112 152c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"filter\": [512, 512, [], \"f0b0\", \"M487.976 0H24.028C2.71 0-8.047 25.866 7.058 40.971L192 225.941V432c0 7.831 3.821 15.17 10.237 19.662l80 55.98C298.02 518.69 320 507.493 320 487.98V225.941l184.947-184.97C520.021 25.896 509.338 0 487.976 0z\"],\n    \"fingerprint\": [512, 512, [], \"f577\", \"M256.12 245.96c-13.25 0-24 10.74-24 24 1.14 72.25-8.14 141.9-27.7 211.55-2.73 9.72 2.15 30.49 23.12 30.49 10.48 0 20.11-6.92 23.09-17.52 13.53-47.91 31.04-125.41 29.48-224.52.01-13.25-10.73-24-23.99-24zm-.86-81.73C194 164.16 151.25 211.3 152.1 265.32c.75 47.94-3.75 95.91-13.37 142.55-2.69 12.98 5.67 25.69 18.64 28.36 13.05 2.67 25.67-5.66 28.36-18.64 10.34-50.09 15.17-101.58 14.37-153.02-.41-25.95 19.92-52.49 54.45-52.34 31.31.47 57.15 25.34 57.62 55.47.77 48.05-2.81 96.33-10.61 143.55-2.17 13.06 6.69 25.42 19.76 27.58 19.97 3.33 26.81-15.1 27.58-19.77 8.28-50.03 12.06-101.21 11.27-152.11-.88-55.8-47.94-101.88-104.91-102.72zm-110.69-19.78c-10.3-8.34-25.37-6.8-33.76 3.48-25.62 31.5-39.39 71.28-38.75 112 .59 37.58-2.47 75.27-9.11 112.05-2.34 13.05 6.31 25.53 19.36 27.89 20.11 3.5 27.07-14.81 27.89-19.36 7.19-39.84 10.5-80.66 9.86-121.33-.47-29.88 9.2-57.88 28-80.97 8.35-10.28 6.79-25.39-3.49-33.76zm109.47-62.33c-15.41-.41-30.87 1.44-45.78 4.97-12.89 3.06-20.87 15.98-17.83 28.89 3.06 12.89 16 20.83 28.89 17.83 11.05-2.61 22.47-3.77 34-3.69 75.43 1.13 137.73 61.5 138.88 134.58.59 37.88-1.28 76.11-5.58 113.63-1.5 13.17 7.95 25.08 21.11 26.58 16.72 1.95 25.51-11.88 26.58-21.11a929.06 929.06 0 0 0 5.89-119.85c-1.56-98.75-85.07-180.33-186.16-181.83zm252.07 121.45c-2.86-12.92-15.51-21.2-28.61-18.27-12.94 2.86-21.12 15.66-18.26 28.61 4.71 21.41 4.91 37.41 4.7 61.6-.11 13.27 10.55 24.09 23.8 24.2h.2c13.17 0 23.89-10.61 24-23.8.18-22.18.4-44.11-5.83-72.34zm-40.12-90.72C417.29 43.46 337.6 1.29 252.81.02 183.02-.82 118.47 24.91 70.46 72.94 24.09 119.37-.9 181.04.14 246.65l-.12 21.47c-.39 13.25 10.03 24.31 23.28 24.69.23.02.48.02.72.02 12.92 0 23.59-10.3 23.97-23.3l.16-23.64c-.83-52.5 19.16-101.86 56.28-139 38.76-38.8 91.34-59.67 147.68-58.86 69.45 1.03 134.73 35.56 174.62 92.39 7.61 10.86 22.56 13.45 33.42 5.86 10.84-7.62 13.46-22.59 5.84-33.43z\"],\n    \"fire\": [384, 512, [], \"f06d\", \"M216 23.86c0-23.8-30.65-32.77-44.15-13.04C48 191.85 224 200 224 288c0 35.63-29.11 64.46-64.85 63.99-35.17-.45-63.15-29.77-63.15-64.94v-85.51c0-21.7-26.47-32.23-41.43-16.5C27.8 213.16 0 261.33 0 320c0 105.87 86.13 192 192 192s192-86.13 192-192c0-170.29-168-193-168-296.14z\"],\n    \"fire-alt\": [448, 512, [], \"f7e4\", \"M323.56 51.2c-20.8 19.3-39.58 39.59-56.22 59.97C240.08 73.62 206.28 35.53 168 0 69.74 91.17 0 209.96 0 281.6 0 408.85 100.29 512 224 512s224-103.15 224-230.4c0-53.27-51.98-163.14-124.44-230.4zm-19.47 340.65C282.43 407.01 255.72 416 226.86 416 154.71 416 96 368.26 96 290.75c0-38.61 24.31-72.63 72.79-130.75 6.93 7.98 98.83 125.34 98.83 125.34l58.63-66.88c4.14 6.85 7.91 13.55 11.27 19.97 27.35 52.19 15.81 118.97-33.43 153.42z\"],\n    \"fire-extinguisher\": [448, 512, [], \"f134\", \"M434.027 26.329l-168 28C254.693 56.218 256 67.8 256 72h-58.332C208.353 36.108 181.446 0 144 0c-39.435 0-66.368 39.676-52.228 76.203-52.039 13.051-75.381 54.213-90.049 90.884-4.923 12.307 1.063 26.274 13.37 31.197 12.317 4.926 26.279-1.075 31.196-13.37C75.058 112.99 106.964 120 168 120v27.076c-41.543 10.862-72 49.235-72 94.129V488c0 13.255 10.745 24 24 24h144c13.255 0 24-10.745 24-24V240c0-44.731-30.596-82.312-72-92.97V120h40c0 2.974-1.703 15.716 10.027 17.671l168 28C441.342 166.89 448 161.25 448 153.834V38.166c0-7.416-6.658-13.056-13.973-11.837zM144 72c-8.822 0-16-7.178-16-16s7.178-16 16-16 16 7.178 16 16-7.178 16-16 16z\"],\n    \"first-aid\": [576, 512, [], \"f479\", \"M0 80v352c0 26.5 21.5 48 48 48h48V32H48C21.5 32 0 53.5 0 80zm128 400h320V32H128v448zm64-248c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48zM528 32h-48v448h48c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"fish\": [576, 512, [], \"f578\", \"M327.1 96c-89.97 0-168.54 54.77-212.27 101.63L27.5 131.58c-12.13-9.18-30.24.6-27.14 14.66L24.54 256 .35 365.77c-3.1 14.06 15.01 23.83 27.14 14.66l87.33-66.05C158.55 361.23 237.13 416 327.1 416 464.56 416 576 288 576 256S464.56 96 327.1 96zm87.43 184c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24 13.26 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"fist-raised\": [384, 512, [], \"f6de\", \"M255.98 160V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v146.93c5.02-1.78 10.34-2.93 15.97-2.93h48.03zm128 95.99c-.01-35.34-28.66-63.99-63.99-63.99H207.85c-8.78 0-15.9 7.07-15.9 15.85v.56c0 26.27 21.3 47.59 47.57 47.59h35.26c9.68 0 13.2 3.58 13.2 8v16.2c0 4.29-3.59 7.78-7.88 8-44.52 2.28-64.16 24.71-96.05 72.55l-6.31 9.47a7.994 7.994 0 0 1-11.09 2.22l-13.31-8.88a7.994 7.994 0 0 1-2.22-11.09l6.31-9.47c15.73-23.6 30.2-43.26 47.31-58.08-17.27-5.51-31.4-18.12-38.87-34.45-6.59 3.41-13.96 5.52-21.87 5.52h-32c-12.34 0-23.49-4.81-32-12.48C71.48 251.19 60.33 256 48 256H16c-5.64 0-10.97-1.15-16-2.95v77.93c0 33.95 13.48 66.5 37.49 90.51L63.99 448v64h255.98v-63.96l35.91-35.92A96.035 96.035 0 0 0 384 344.21l-.02-88.22zm-32.01-90.09V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v112h32c11.28 0 21.94 2.31 32 5.9zM16 224h32c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v128c0 8.84 7.16 16 16 16zm95.99 0h32c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v160c0 8.84 7.16 16 16 16z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M349.565 98.783C295.978 98.783 251.721 64 184.348 64c-24.955 0-47.309 4.384-68.045 12.013a55.947 55.947 0 0 0 3.586-23.562C118.117 24.015 94.806 1.206 66.338.048 34.345-1.254 8 24.296 8 56c0 19.026 9.497 35.825 24 45.945V488c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-94.4c28.311-12.064 63.582-22.122 114.435-22.122 53.588 0 97.844 34.783 165.217 34.783 48.169 0 86.667-16.294 122.505-40.858C506.84 359.452 512 349.571 512 339.045v-243.1c0-23.393-24.269-38.87-45.485-29.016-34.338 15.948-76.454 31.854-116.95 31.854z\"],\n    \"flag-checkered\": [512, 512, [], \"f11e\", \"M243.2 189.9V258c26.1 5.9 49.3 15.6 73.6 22.3v-68.2c-26-5.8-49.4-15.5-73.6-22.2zm223.3-123c-34.3 15.9-76.5 31.9-117 31.9C296 98.8 251.7 64 184.3 64c-25 0-47.3 4.4-68 12 2.8-7.3 4.1-15.2 3.6-23.6C118.1 24 94.8 1.2 66.3 0 34.3-1.3 8 24.3 8 56c0 19 9.5 35.8 24 45.9V488c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24v-94.4c28.3-12.1 63.6-22.1 114.4-22.1 53.6 0 97.8 34.8 165.2 34.8 48.2 0 86.7-16.3 122.5-40.9 8.7-6 13.8-15.8 13.8-26.4V95.9c.1-23.3-24.2-38.8-45.4-29zM169.6 325.5c-25.8 2.7-50 8.2-73.6 16.6v-70.5c26.2-9.3 47.5-15 73.6-17.4zM464 191c-23.6 9.8-46.3 19.5-73.6 23.9V286c24.8-3.4 51.4-11.8 73.6-26v70.5c-25.1 16.1-48.5 24.7-73.6 27.1V286c-27 3.7-47.9 1.5-73.6-5.6v67.4c-23.9-7.4-47.3-16.7-73.6-21.3V258c-19.7-4.4-40.8-6.8-73.6-3.8v-70c-22.4 3.1-44.6 10.2-73.6 20.9v-70.5c33.2-12.2 50.1-19.8 73.6-22v71.6c27-3.7 48.4-1.3 73.6 5.7v-67.4c23.7 7.4 47.2 16.7 73.6 21.3v68.4c23.7 5.3 47.6 6.9 73.6 2.7V143c27-4.8 52.3-13.6 73.6-22.5z\"],\n    \"flag-usa\": [512, 512, [], \"f74d\", \"M32 0C14.3 0 0 14.3 0 32v464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32C64 14.3 49.7 0 32 0zm267.9 303.6c-57.2-15.1-111.7-28.8-203.9 11.1V384c185.7-92.2 221.7 53.3 397.5-23.1 11.4-5 18.5-16.5 18.5-28.8v-36c-43.6 17.3-80.2 24.1-112.1 24.1-37.4-.1-68.9-8.4-100-16.6zm0-96c-57.2-15.1-111.7-28.8-203.9 11.1v61.5c94.8-37.6 154.6-22.7 212.1-7.6 57.2 15.1 111.7 28.8 203.9-11.1V200c-43.6 17.3-80.2 24.1-112.1 24.1-37.4 0-68.9-8.3-100-16.5zm9.5-125.9c51.8 15.6 97.4 29 202.6-20.1V30.8c0-25.1-26.8-38.1-49.4-26.6C291.3 91.5 305.4-62.2 96 32.4v151.9c94.8-37.5 154.6-22.7 212.1-7.6 57.2 15 111.7 28.7 203.9-11.1V96.7c-53.6 23.5-93.3 31.4-126.1 31.4s-59-7.8-85.7-15.9c-4-1.2-8.1-2.4-12.1-3.5V75.5c7.2 2 14.3 4.1 21.3 6.2zM160 128.1c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16-7.2 16-16 16zm0-55.8c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm64 47.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm0-55.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16z\"],\n    \"flask\": [448, 512, [], \"f0c3\", \"M437.2 403.5L320 215V64h8c13.3 0 24-10.7 24-24V24c0-13.3-10.7-24-24-24H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h8v151L10.8 403.5C-18.5 450.6 15.3 512 70.9 512h306.2c55.7 0 89.4-61.5 60.1-108.5zM137.9 320l48.2-77.6c3.7-5.2 5.8-11.6 5.8-18.4V64h64v160c0 6.9 2.2 13.2 5.8 18.4l48.2 77.6h-172z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M344 200c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-192 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM80 224c0-39.8 32.2-72 72-72s72 32.2 72 72-32.2 72-72 72-72-32.2-72-72zm232 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-104c-39.8 0-72-32.2-72-72s32.2-72 72-72 72 32.2 72 72-32.2 72-72 72z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48z\"],\n    \"folder-minus\": [512, 512, [], \"f65d\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16H160c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h192c8.84 0 16 7.16 16 16v16z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M572.694 292.093L500.27 416.248A63.997 63.997 0 0 1 444.989 448H45.025c-18.523 0-30.064-20.093-20.731-36.093l72.424-124.155A64 64 0 0 1 152 256h399.964c18.523 0 30.064 20.093 20.73 36.093zM152 224h328v-48c0-26.51-21.49-48-48-48H272l-64-64H48C21.49 64 0 85.49 0 112v278.046l69.077-118.418C86.214 242.25 117.989 224 152 224z\"],\n    \"folder-plus\": [512, 512, [], \"f65e\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16h-72v72c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-72h-72c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h72v-72c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v72h72c8.84 0 16 7.16 16 16v16z\"],\n    \"font\": [448, 512, [], \"f031\", \"M432 416h-23.41L277.88 53.69A32 32 0 0 0 247.58 32h-47.16a32 32 0 0 0-30.3 21.69L39.41 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-19.58l23.3-64h152.56l23.3 64H304a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM176.85 272L224 142.51 271.15 272z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"football-ball\": [496, 512, [], \"f44e\", \"M481.5 60.3c-4.8-18.2-19.1-32.5-37.3-37.4C420.3 16.5 383 8.9 339.4 8L496 164.8c-.8-43.5-8.2-80.6-14.5-104.5zm-467 391.4c4.8 18.2 19.1 32.5 37.3 37.4 23.9 6.4 61.2 14 104.8 14.9L0 347.2c.8 43.5 8.2 80.6 14.5 104.5zM4.2 283.4L220.4 500c132.5-19.4 248.8-118.7 271.5-271.4L275.6 12C143.1 31.4 26.8 130.7 4.2 283.4zm317.3-123.6c3.1-3.1 8.2-3.1 11.3 0l11.3 11.3c3.1 3.1 3.1 8.2 0 11.3l-28.3 28.3 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-22.6 22.7 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L248 278.6l-22.6 22.6 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-28.3 28.3c-3.1 3.1-8.2 3.1-11.3 0l-11.3-11.3c-3.1-3.1-3.1-8.2 0-11.3l28.3-28.3-28.3-28.2c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 28.3-28.5z\"],\n    \"forward\": [512, 512, [], \"f04e\", \"M500.5 231.4l-192-160C287.9 54.3 256 68.6 256 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2zm-256 0l-192-160C31.9 54.3 0 68.6 0 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2z\"],\n    \"frog\": [576, 512, [], \"f52e\", \"M446.53 97.43C439.67 60.23 407.19 32 368 32c-39.23 0-71.72 28.29-78.54 65.54C126.75 112.96-.5 250.12 0 416.98.11 451.9 29.08 480 64 480h304c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-79.49l35.8-48.33c24.14-36.23 10.35-88.28-33.71-106.6-23.89-9.93-51.55-4.65-72.24 10.88l-32.76 24.59c-7.06 5.31-17.09 3.91-22.41-3.19-5.3-7.08-3.88-17.11 3.19-22.41l34.78-26.09c36.84-27.66 88.28-27.62 125.13 0 10.87 8.15 45.87 39.06 40.8 93.21L469.62 480H560c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-53.63l-98.52-104.68 154.44-86.65A58.16 58.16 0 0 0 576 189.94c0-21.4-11.72-40.95-30.48-51.23-40.56-22.22-98.99-41.28-98.99-41.28zM368 136c-13.26 0-24-10.75-24-24 0-13.26 10.74-24 24-24 13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm170.2 218.2C315.8 367.4 282.9 352 248 352s-67.8 15.4-90.2 42.2c-13.5 16.3-38.1-4.2-24.6-20.5C161.7 339.6 203.6 320 248 320s86.3 19.6 114.7 53.8c13.6 16.2-11 36.7-24.5 20.4z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm187.3 183.3c-31.2-9.6-59.4-15.3-75.3-15.3s-44.1 5.7-75.3 15.3c-11.5 3.5-22.5-6.3-20.5-18.1 7-40 60.1-61.2 95.8-61.2s88.8 21.3 95.8 61.2c2 11.9-9.1 21.6-20.5 18.1zM328 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"funnel-dollar\": [640, 512, [], \"f662\", \"M433.46 165.94l101.2-111.87C554.61 34.12 540.48 0 512.26 0H31.74C3.52 0-10.61 34.12 9.34 54.07L192 256v155.92c0 12.59 5.93 24.44 16 32l79.99 60c20.86 15.64 48.47 6.97 59.22-13.57C310.8 455.38 288 406.35 288 352c0-89.79 62.05-165.17 145.46-186.06zM480 192c-88.37 0-160 71.63-160 160s71.63 160 160 160 160-71.63 160-160-71.63-160-160-160zm16 239.88V448c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V256c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.04 44.44-42.67 45.07z\"],\n    \"futbol\": [512, 512, [], \"f1e3\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-48 0l-.003-.282-26.064 22.741-62.679-58.5 16.454-84.355 34.303 3.072c-24.889-34.216-60.004-60.089-100.709-73.141l13.651 31.939L256 139l-74.953-41.525 13.651-31.939c-40.631 13.028-75.78 38.87-100.709 73.141l34.565-3.073 16.192 84.355-62.678 58.5-26.064-22.741-.003.282c0 43.015 13.497 83.952 38.472 117.991l7.704-33.897 85.138 10.447 36.301 77.826-29.902 17.786c40.202 13.122 84.29 13.148 124.572 0l-29.902-17.786 36.301-77.826 85.138-10.447 7.704 33.897C442.503 339.952 456 299.015 456 256zm-248.102 69.571l-29.894-91.312L256 177.732l77.996 56.527-29.622 91.312h-96.476z\"],\n    \"gamepad\": [640, 512, [], \"f11b\", \"M480 96H160C71.6 96 0 167.6 0 256s71.6 160 160 160c44.8 0 85.2-18.4 114.2-48h91.5c29 29.6 69.5 48 114.2 48 88.4 0 160-71.6 160-160S568.4 96 480 96zM256 276c0 6.6-5.4 12-12 12h-52v52c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-52H76c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h52v-52c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h52c6.6 0 12 5.4 12 12v40zm184 68c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-80c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"gas-pump\": [512, 512, [], \"f52f\", \"M336 448H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm157.2-340.7l-81-81c-6.2-6.2-16.4-6.2-22.6 0l-11.3 11.3c-6.2 6.2-6.2 16.4 0 22.6L416 97.9V160c0 28.1 20.9 51.3 48 55.2V376c0 13.2-10.8 24-24 24s-24-10.8-24-24v-32c0-48.6-39.4-88-88-88h-8V64c0-35.3-28.7-64-64-64H96C60.7 0 32 28.7 32 64v352h288V304h8c22.1 0 40 17.9 40 40v27.8c0 37.7 27 72 64.5 75.9 43 4.3 79.5-29.5 79.5-71.7V152.6c0-17-6.8-33.3-18.8-45.3zM256 192H96V64h160v128z\"],\n    \"gavel\": [512, 512, [], \"f0e3\", \"M504.971 199.362l-22.627-22.627c-9.373-9.373-24.569-9.373-33.941 0l-5.657 5.657L329.608 69.255l5.657-5.657c9.373-9.373 9.373-24.569 0-33.941L312.638 7.029c-9.373-9.373-24.569-9.373-33.941 0L154.246 131.48c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l5.657-5.657 39.598 39.598-81.04 81.04-5.657-5.657c-12.497-12.497-32.758-12.497-45.255 0L9.373 412.118c-12.497 12.497-12.497 32.758 0 45.255l45.255 45.255c12.497 12.497 32.758 12.497 45.255 0l114.745-114.745c12.497-12.497 12.497-32.758 0-45.255l-5.657-5.657 81.04-81.04 39.598 39.598-5.657 5.657c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l124.451-124.451c9.372-9.372 9.372-24.568 0-33.941z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M485.5 0L576 160H474.9L405.7 0h79.8zm-128 0l69.2 160H149.3L218.5 0h139zm-267 0h79.8l-69.2 160H0L90.5 0zM0 192h100.7l123 251.7c1.5 3.1-2.7 5.9-5 3.3L0 192zm148.2 0h279.6l-137 318.2c-1 2.4-4.5 2.4-5.5 0L148.2 192zm204.1 251.7l123-251.7H576L357.3 446.9c-2.3 2.7-6.5-.1-5-3.2z\"],\n    \"genderless\": [288, 512, [], \"f22d\", \"M144 176c44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80 35.9-80 80-80m0-64C64.5 112 0 176.5 0 256s64.5 144 144 144 144-64.5 144-144-64.5-144-144-144z\"],\n    \"ghost\": [384, 512, [], \"f6e2\", \"M186.1.09C81.01 3.24 0 94.92 0 200.05v263.92c0 14.26 17.23 21.39 27.31 11.31l24.92-18.53c6.66-4.95 16-3.99 21.51 2.21l42.95 48.35c6.25 6.25 16.38 6.25 22.63 0l40.72-45.85c6.37-7.17 17.56-7.17 23.92 0l40.72 45.85c6.25 6.25 16.38 6.25 22.63 0l42.95-48.35c5.51-6.2 14.85-7.17 21.51-2.21l24.92 18.53c10.08 10.08 27.31 2.94 27.31-11.31V192C384 84 294.83-3.17 186.1.09zM128 224c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128 0c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"gift\": [512, 512, [], \"f06b\", \"M32 448c0 17.7 14.3 32 32 32h160V320H32v128zm256 32h160c17.7 0 32-14.3 32-32V320H288v160zm192-320h-42.1c6.2-12.1 10.1-25.5 10.1-40 0-48.5-39.5-88-88-88-41.6 0-68.5 21.3-103 68.3-34.5-47-61.4-68.3-103-68.3-48.5 0-88 39.5-88 88 0 14.5 3.8 27.9 10.1 40H32c-17.7 0-32 14.3-32 32v80c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-80c0-17.7-14.3-32-32-32zm-326.1 0c-22.1 0-40-17.9-40-40s17.9-40 40-40c19.9 0 34.6 3.3 86.1 80h-86.1zm206.1 0h-86.1c51.4-76.5 65.7-80 86.1-80 22.1 0 40 17.9 40 40s-17.9 40-40 40z\"],\n    \"gifts\": [640, 512, [], \"f79c\", \"M240.6 194.1c1.9-30.8 17.3-61.2 44-79.8C279.4 103.5 268.7 96 256 96h-29.4l30.7-22c7.2-5.1 8.9-15.1 3.7-22.3l-9.3-13c-5.1-7.2-15.1-8.9-22.3-3.7l-32 22.9 11.5-30.6c3.1-8.3-1.1-17.5-9.4-20.6l-15-5.6c-8.3-3.1-17.5 1.1-20.6 9.4l-19.9 53-19.9-53.1C121 2.1 111.8-2.1 103.5 1l-15 5.6C80.2 9.7 76 19 79.2 27.2l11.5 30.6L58.6 35c-7.2-5.1-17.2-3.5-22.3 3.7l-9.3 13c-5.1 7.2-3.5 17.2 3.7 22.3l30.7 22H32c-17.7 0-32 14.3-32 32v352c0 17.7 14.3 32 32 32h168.9c-5.5-9.5-8.9-20.3-8.9-32V256c0-29.9 20.8-55 48.6-61.9zM224 480c0 17.7 14.3 32 32 32h160V384H224v96zm224 32h160c17.7 0 32-14.3 32-32v-96H448v128zm160-288h-20.4c2.6-7.6 4.4-15.5 4.4-23.8 0-35.5-27-72.2-72.1-72.2-48.1 0-75.9 47.7-87.9 75.3-12.1-27.6-39.9-75.3-87.9-75.3-45.1 0-72.1 36.7-72.1 72.2 0 8.3 1.7 16.2 4.4 23.8H256c-17.7 0-32 14.3-32 32v96h192V224h15.3l.7-.2.7.2H448v128h192v-96c0-17.7-14.3-32-32-32zm-272 0c-2.7-1.4-5.1-3-7.2-4.8-7.3-6.4-8.8-13.8-8.8-19 0-9.7 6.4-24.2 24.1-24.2 18.7 0 35.6 27.4 44.5 48H336zm199.2-4.8c-2.1 1.8-4.5 3.4-7.2 4.8h-52.6c8.8-20.3 25.8-48 44.5-48 17.7 0 24.1 14.5 24.1 24.2 0 5.2-1.5 12.6-8.8 19z\"],\n    \"glass-cheers\": [640, 512, [], \"f79f\", \"M639.4 433.6c-8.4-20.4-31.8-30.1-52.2-21.6l-22.1 9.2-38.7-101.9c47.9-35 64.8-100.3 34.5-152.8L474.3 16c-8-13.9-25.1-19.7-40-13.6L320 49.8 205.7 2.4c-14.9-6.2-32-.3-40 13.6L79.1 166.5C48.9 219 65.7 284.3 113.6 319.2L74.9 421.1l-22.1-9.2c-20.4-8.5-43.7 1.2-52.2 21.6-1.7 4.1.2 8.8 4.3 10.5l162.3 67.4c4.1 1.7 8.7-.2 10.4-4.3 8.4-20.4-1.2-43.8-21.6-52.3l-22.1-9.2L173.3 342c4.4.5 8.8 1.3 13.1 1.3 51.7 0 99.4-33.1 113.4-85.3l20.2-75.4 20.2 75.4c14 52.2 61.7 85.3 113.4 85.3 4.3 0 8.7-.8 13.1-1.3L506 445.6l-22.1 9.2c-20.4 8.5-30.1 31.9-21.6 52.3 1.7 4.1 6.4 6 10.4 4.3L635.1 444c4-1.7 6-6.3 4.3-10.4zM275.9 162.1l-112.1-46.5 36.5-63.4 94.5 39.2-18.9 70.7zm88.2 0l-18.9-70.7 94.5-39.2 36.5 63.4-112.1 46.5z\"],\n    \"glass-martini\": [512, 512, [], \"f000\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6z\"],\n    \"glass-martini-alt\": [512, 512, [], \"f57b\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6zM443.77 48l-48 48H116.24l-48-48h375.53z\"],\n    \"glass-whiskey\": [512, 512, [], \"f7a0\", \"M480 32H32C12.5 32-2.4 49.2.3 68.5l56 356.5c4.5 31.5 31.5 54.9 63.4 54.9h273c31.8 0 58.9-23.4 63.4-54.9l55.6-356.5C514.4 49.2 499.5 32 480 32zm-37.4 64l-30 192h-313L69.4 96h373.2z\"],\n    \"glasses\": [576, 512, [], \"f530\", \"M574.1 280.37L528.75 98.66c-5.91-23.7-21.59-44.05-43-55.81-21.44-11.73-46.97-14.11-70.19-6.33l-15.25 5.08c-8.39 2.79-12.92 11.86-10.12 20.24l5.06 15.18c2.79 8.38 11.85 12.91 20.23 10.12l13.18-4.39c10.87-3.62 23-3.57 33.16 1.73 10.29 5.37 17.57 14.56 20.37 25.82l38.46 153.82c-22.19-6.81-49.79-12.46-81.2-12.46-34.77 0-73.98 7.02-114.85 26.74h-73.18c-40.87-19.74-80.08-26.75-114.86-26.75-31.42 0-59.02 5.65-81.21 12.46l38.46-153.83c2.79-11.25 10.09-20.45 20.38-25.81 10.16-5.3 22.28-5.35 33.15-1.73l13.17 4.39c8.38 2.79 17.44-1.74 20.23-10.12l5.06-15.18c2.8-8.38-1.73-17.45-10.12-20.24l-15.25-5.08c-23.22-7.78-48.75-5.41-70.19 6.33-21.41 11.77-37.09 32.11-43 55.8L1.9 280.37A64.218 64.218 0 0 0 0 295.86v70.25C0 429.01 51.58 480 115.2 480h37.12c60.28 0 110.37-45.94 114.88-105.37l2.93-38.63h35.75l2.93 38.63C313.31 434.06 363.4 480 423.68 480h37.12c63.62 0 115.2-50.99 115.2-113.88v-70.25c0-5.23-.64-10.43-1.9-15.5zm-370.72 89.42c-1.97 25.91-24.4 46.21-51.06 46.21H115.2C86.97 416 64 393.62 64 366.11v-37.54c18.12-6.49 43.42-12.92 72.58-12.92 23.86 0 47.26 4.33 69.93 12.92l-3.13 41.22zM512 366.12c0 27.51-22.97 49.88-51.2 49.88h-37.12c-26.67 0-49.1-20.3-51.06-46.21l-3.13-41.22c22.67-8.59 46.08-12.92 69.95-12.92 29.12 0 54.43 6.44 72.55 12.93v37.54z\"],\n    \"globe\": [496, 512, [], \"f0ac\", \"M336.5 160C322 70.7 287.8 8 248 8s-74 62.7-88.5 152h177zM152 256c0 22.2 1.2 43.5 3.3 64h185.3c2.1-20.5 3.3-41.8 3.3-64s-1.2-43.5-3.3-64H155.3c-2.1 20.5-3.3 41.8-3.3 64zm324.7-96c-28.6-67.9-86.5-120.4-158-141.6 24.4 33.8 41.2 84.7 50 141.6h108zM177.2 18.4C105.8 39.6 47.8 92.1 19.3 160h108c8.7-56.9 25.5-107.8 49.9-141.6zM487.4 192H372.7c2.1 21 3.3 42.5 3.3 64s-1.2 43-3.3 64h114.6c5.5-20.5 8.6-41.8 8.6-64s-3.1-43.5-8.5-64zM120 256c0-21.5 1.2-43 3.3-64H8.6C3.2 212.5 0 233.8 0 256s3.2 43.5 8.6 64h114.6c-2-21-3.2-42.5-3.2-64zm39.5 96c14.5 89.3 48.7 152 88.5 152s74-62.7 88.5-152h-177zm159.3 141.6c71.4-21.2 129.4-73.7 158-141.6h-108c-8.8 56.9-25.6 107.8-50 141.6zM19.3 352c28.6 67.9 86.5 120.4 158 141.6-24.4-33.8-41.2-84.7-50-141.6h-108z\"],\n    \"globe-africa\": [496, 512, [], \"f57c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm160 215.5v6.93c0 5.87-3.32 11.24-8.57 13.86l-15.39 7.7a15.485 15.485 0 0 1-15.53-.97l-18.21-12.14a15.52 15.52 0 0 0-13.5-1.81l-2.65.88c-9.7 3.23-13.66 14.79-7.99 23.3l13.24 19.86c2.87 4.31 7.71 6.9 12.89 6.9h8.21c8.56 0 15.5 6.94 15.5 15.5v11.34c0 3.35-1.09 6.62-3.1 9.3l-18.74 24.98c-1.42 1.9-2.39 4.1-2.83 6.43l-4.3 22.83c-.62 3.29-2.29 6.29-4.76 8.56a159.608 159.608 0 0 0-25 29.16l-13.03 19.55a27.756 27.756 0 0 1-23.09 12.36c-10.51 0-20.12-5.94-24.82-15.34a78.902 78.902 0 0 1-8.33-35.29V367.5c0-8.56-6.94-15.5-15.5-15.5h-25.88c-14.49 0-28.38-5.76-38.63-16a54.659 54.659 0 0 1-16-38.63v-14.06c0-17.19 8.1-33.38 21.85-43.7l27.58-20.69a54.663 54.663 0 0 1 32.78-10.93h.89c8.48 0 16.85 1.97 24.43 5.77l14.72 7.36c3.68 1.84 7.93 2.14 11.83.84l47.31-15.77c6.33-2.11 10.6-8.03 10.6-14.7 0-8.56-6.94-15.5-15.5-15.5h-10.09c-4.11 0-8.05-1.63-10.96-4.54l-6.92-6.92a15.493 15.493 0 0 0-10.96-4.54H199.5c-8.56 0-15.5-6.94-15.5-15.5v-4.4c0-7.11 4.84-13.31 11.74-15.04l14.45-3.61c3.74-.94 7-3.23 9.14-6.44l8.08-12.11c2.87-4.31 7.71-6.9 12.89-6.9h24.21c8.56 0 15.5-6.94 15.5-15.5v-21.7C359.23 71.63 422.86 131.02 441.93 208H423.5c-8.56 0-15.5 6.94-15.5 15.5z\"],\n    \"globe-americas\": [496, 512, [], \"f57d\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm82.29 357.6c-3.9 3.88-7.99 7.95-11.31 11.28-2.99 3-5.1 6.7-6.17 10.71-1.51 5.66-2.73 11.38-4.77 16.87l-17.39 46.85c-13.76 3-28 4.69-42.65 4.69v-27.38c1.69-12.62-7.64-36.26-22.63-51.25-6-6-9.37-14.14-9.37-22.63v-32.01c0-11.64-6.27-22.34-16.46-27.97-14.37-7.95-34.81-19.06-48.81-26.11-11.48-5.78-22.1-13.14-31.65-21.75l-.8-.72a114.792 114.792 0 0 1-18.06-20.74c-9.38-13.77-24.66-36.42-34.59-51.14 20.47-45.5 57.36-82.04 103.2-101.89l24.01 12.01C203.48 89.74 216 82.01 216 70.11v-11.3c7.99-1.29 16.12-2.11 24.39-2.42l28.3 28.3c6.25 6.25 6.25 16.38 0 22.63L264 112l-10.34 10.34c-3.12 3.12-3.12 8.19 0 11.31l4.69 4.69c3.12 3.12 3.12 8.19 0 11.31l-8 8a8.008 8.008 0 0 1-5.66 2.34h-8.99c-2.08 0-4.08.81-5.58 2.27l-9.92 9.65a8.008 8.008 0 0 0-1.58 9.31l15.59 31.19c2.66 5.32-1.21 11.58-7.15 11.58h-5.64c-1.93 0-3.79-.7-5.24-1.96l-9.28-8.06a16.017 16.017 0 0 0-15.55-3.1l-31.17 10.39a11.95 11.95 0 0 0-8.17 11.34c0 4.53 2.56 8.66 6.61 10.69l11.08 5.54c9.41 4.71 19.79 7.16 30.31 7.16s22.59 27.29 32 32h66.75c8.49 0 16.62 3.37 22.63 9.37l13.69 13.69a30.503 30.503 0 0 1 8.93 21.57 46.536 46.536 0 0 1-13.72 32.98zM417 274.25c-5.79-1.45-10.84-5-14.15-9.97l-17.98-26.97a23.97 23.97 0 0 1 0-26.62l19.59-29.38c2.32-3.47 5.5-6.29 9.24-8.15l12.98-6.49C440.2 193.59 448 223.87 448 256c0 8.67-.74 17.16-1.82 25.54L417 274.25z\"],\n    \"globe-asia\": [496, 512, [], \"f57e\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm-11.34 240.23c-2.89 4.82-8.1 7.77-13.72 7.77h-.31c-4.24 0-8.31 1.69-11.31 4.69l-5.66 5.66c-3.12 3.12-3.12 8.19 0 11.31l5.66 5.66c3 3 4.69 7.07 4.69 11.31V304c0 8.84-7.16 16-16 16h-6.11c-6.06 0-11.6-3.42-14.31-8.85l-22.62-45.23c-2.44-4.88-8.95-5.94-12.81-2.08l-19.47 19.46c-3 3-7.07 4.69-11.31 4.69H50.81C49.12 277.55 48 266.92 48 256c0-110.28 89.72-200 200-200 21.51 0 42.2 3.51 61.63 9.82l-50.16 38.53c-5.11 3.41-4.63 11.06.86 13.81l10.83 5.41c5.42 2.71 8.84 8.25 8.84 14.31V216c0 4.42-3.58 8-8 8h-3.06c-3.03 0-5.8-1.71-7.15-4.42-1.56-3.12-5.96-3.29-7.76-.3l-17.37 28.95zM408 358.43c0 4.24-1.69 8.31-4.69 11.31l-9.57 9.57c-3 3-7.07 4.69-11.31 4.69h-15.16c-4.24 0-8.31-1.69-11.31-4.69l-13.01-13.01a26.767 26.767 0 0 0-25.42-7.04l-21.27 5.32c-1.27.32-2.57.48-3.88.48h-10.34c-4.24 0-8.31-1.69-11.31-4.69l-11.91-11.91a8.008 8.008 0 0 1-2.34-5.66v-10.2c0-3.27 1.99-6.21 5.03-7.43l39.34-15.74c1.98-.79 3.86-1.82 5.59-3.05l23.71-16.89a7.978 7.978 0 0 1 4.64-1.48h12.09c3.23 0 6.15 1.94 7.39 4.93l5.35 12.85a4 4 0 0 0 3.69 2.46h3.8c1.78 0 3.35-1.18 3.84-2.88l4.2-14.47c.5-1.71 2.06-2.88 3.84-2.88h6.06c2.21 0 4 1.79 4 4v12.93c0 2.12.84 4.16 2.34 5.66l11.91 11.91c3 3 4.69 7.07 4.69 11.31v24.6z\"],\n    \"globe-europe\": [496, 512, [], \"f7a2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm200 248c0 22.5-3.9 44.2-10.8 64.4h-20.3c-4.3 0-8.4-1.7-11.4-4.8l-32-32.6c-4.5-4.6-4.5-12.1.1-16.7l12.5-12.5v-8.7c0-3-1.2-5.9-3.3-8l-9.4-9.4c-2.1-2.1-5-3.3-8-3.3h-16c-6.2 0-11.3-5.1-11.3-11.3 0-3 1.2-5.9 3.3-8l9.4-9.4c2.1-2.1 5-3.3 8-3.3h32c6.2 0 11.3-5.1 11.3-11.3v-9.4c0-6.2-5.1-11.3-11.3-11.3h-36.7c-8.8 0-16 7.2-16 16v4.5c0 6.9-4.4 13-10.9 15.2l-31.6 10.5c-3.3 1.1-5.5 4.1-5.5 7.6v2.2c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8s-3.6-8-8-8H247c-3 0-5.8 1.7-7.2 4.4l-9.4 18.7c-2.7 5.4-8.2 8.8-14.3 8.8H194c-8.8 0-16-7.2-16-16V199c0-4.2 1.7-8.3 4.7-11.3l20.1-20.1c4.6-4.6 7.2-10.9 7.2-17.5 0-3.4 2.2-6.5 5.5-7.6l40-13.3c1.7-.6 3.2-1.5 4.4-2.7l26.8-26.8c2.1-2.1 3.3-5 3.3-8 0-6.2-5.1-11.3-11.3-11.3H258l-16 16v8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-20c0-2.5 1.2-4.9 3.2-6.4l28.9-21.7c1.9-.1 3.8-.3 5.7-.3C358.3 56 448 145.7 448 256zM130.1 149.1c0-3 1.2-5.9 3.3-8l25.4-25.4c2.1-2.1 5-3.3 8-3.3 6.2 0 11.3 5.1 11.3 11.3v16c0 3-1.2 5.9-3.3 8l-9.4 9.4c-2.1 2.1-5 3.3-8 3.3h-16c-6.2 0-11.3-5.1-11.3-11.3zm128 306.4v-7.1c0-8.8-7.2-16-16-16h-20.2c-10.8 0-26.7-5.3-35.4-11.8l-22.2-16.7c-11.5-8.6-18.2-22.1-18.2-36.4v-23.9c0-16 8.4-30.8 22.1-39l42.9-25.7c7.1-4.2 15.2-6.5 23.4-6.5h31.2c10.9 0 21.4 3.9 29.6 10.9l43.2 37.1h18.3c8.5 0 16.6 3.4 22.6 9.4l17.3 17.3c3.4 3.4 8.1 5.3 12.9 5.3H423c-32.4 58.9-93.8 99.5-164.9 103.1z\"],\n    \"golf-ball\": [416, 512, [], \"f450\", \"M96 416h224c0 17.7-14.3 32-32 32h-16c-17.7 0-32 14.3-32 32v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-20c0-17.7-14.3-32-32-32h-16c-17.7 0-32-14.3-32-32zm320-208c0 74.2-39 139.2-97.5 176h-221C39 347.2 0 282.2 0 208 0 93.1 93.1 0 208 0s208 93.1 208 208zm-180.1 43.9c18.3 0 33.1-14.8 33.1-33.1 0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1zm49.1 46.9c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1zm64-64c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1z\"],\n    \"gopuram\": [512, 512, [], \"f664\", \"M496 352h-16V240c0-8.8-7.2-16-16-16h-16v-80c0-8.8-7.2-16-16-16h-16V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16S96 7.2 96 16v112H80c-8.8 0-16 7.2-16 16v80H48c-8.8 0-16 7.2-16 16v112H16c-8.8 0-16 7.2-16 16v128c0 8.8 7.2 16 16 16h80V352h32V224h32v-96h32v96h-32v128h-32v160h80v-80c0-8.8 7.2-16 16-16h64c8.8 0 16 7.2 16 16v80h80V352h-32V224h-32v-96h32v96h32v128h32v160h80c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zM232 176c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v48h-48zm56 176h-64v-64c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16z\"],\n    \"graduation-cap\": [640, 512, [], \"f19d\", \"M622.34 153.2L343.4 67.5c-15.2-4.67-31.6-4.67-46.79 0L17.66 153.2c-23.54 7.23-23.54 38.36 0 45.59l48.63 14.94c-10.67 13.19-17.23 29.28-17.88 46.9C38.78 266.15 32 276.11 32 288c0 10.78 5.68 19.85 13.86 25.65L20.33 428.53C18.11 438.52 25.71 448 35.94 448h56.11c10.24 0 17.84-9.48 15.62-19.47L82.14 313.65C90.32 307.85 96 298.78 96 288c0-11.57-6.47-21.25-15.66-26.87.76-15.02 8.44-28.3 20.69-36.72L296.6 284.5c9.06 2.78 26.44 6.25 46.79 0l278.95-85.7c23.55-7.24 23.55-38.36 0-45.6zM352.79 315.09c-28.53 8.76-52.84 3.92-65.59 0l-145.02-44.55L128 384c0 35.35 85.96 64 192 64s192-28.65 192-64l-14.18-113.47-145.03 44.56z\"],\n    \"greater-than\": [384, 512, [], \"f531\", \"M365.52 209.85L59.22 67.01c-16.06-7.49-35.15-.54-42.64 15.52L3.01 111.61c-7.49 16.06-.54 35.15 15.52 42.64L236.96 256.1 18.49 357.99C2.47 365.46-4.46 384.5 3.01 400.52l13.52 29C24 445.54 43.04 452.47 59.06 445l306.47-142.91a32.003 32.003 0 0 0 18.48-29v-34.23c-.01-12.45-7.21-23.76-18.49-29.01z\"],\n    \"greater-than-equal\": [448, 512, [], \"f532\", \"M55.22 107.69l175.56 68.09-175.44 68.05c-18.39 6.03-27.88 24.39-21.2 41l12.09 30.08c6.68 16.61 26.99 25.19 45.38 19.15L393.02 214.2c13.77-4.52 22.98-16.61 22.98-30.17v-15.96c0-13.56-9.21-25.65-22.98-30.17L91.3 17.92c-18.29-6-38.51 2.53-45.15 19.06L34.12 66.9c-6.64 16.53 2.81 34.79 21.1 40.79zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM144 400h-8c-17.7 0-32-14.3-32-32v-8h40v40zm0-56h-40v-8c0-17.7 14.3-32 32-32h8v40zm-8-136c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm72 192h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm-8-104c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64 128c0 17.7-14.3 32-32 32h-8v-40h40v8zm0-24h-40v-40h8c17.7 0 32 14.3 32 32v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm80 256c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm63.7 128.7c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zm-160 0c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 144c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam-sweat\": [504, 512, [], \"f583\", \"M456 128c26.5 0 48-21 48-47 0-20-28.5-60.4-41.6-77.8-3.2-4.3-9.6-4.3-12.8 0C436.5 20.6 408 61 408 81c0 26 21.5 47 48 47zm0 32c-44.1 0-80-35.4-80-79 0-4.4.3-14.2 8.1-32.2C345 23.1 298.3 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-35.1-7.4-68.4-20.5-98.6-6.3 1.5-12.7 2.6-19.5 2.6zm-128-8c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM90.4 183.6c6.7-17.6 26.7-26.7 44.9-21.9l7.1 1.9 2-7.1c5-18.1 22.8-30.9 41.5-27.9 21.4 3.4 34.4 24.2 28.8 44.5L195.3 243c-1.2 4.5-5.9 7.2-10.5 6l-70.2-18.2c-20.4-5.4-31.9-27-24.2-47.2zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm133.4-201.3l-70.2 18.2c-4.5 1.2-9.2-1.5-10.5-6L281.3 173c-5.6-20.3 7.4-41.1 28.8-44.5 18.6-3 36.4 9.8 41.5 27.9l2 7.1 7.1-1.9c18.2-4.7 38.2 4.3 44.9 21.9 7.7 20.3-3.8 41.9-24.2 47.2z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M409.6 111.9c22.6-3.2 73.5-12 88.3-26.8 19.2-19.2 18.9-50.6-.7-70.2S446-5 426.9 14.2c-14.8 14.8-23.5 65.7-26.8 88.3-.8 5.5 3.9 10.2 9.5 9.4zM102.4 400.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm311.7-256.5c-33 3.9-48.6-25.1-45.7-45.7 3.4-24 7.4-42.1 11.5-56.5C285.1-13.4 161.8-.5 80.6 80.6-.5 161.7-13.4 285 41.4 379.9c14.4-4.1 32.4-8 56.5-11.5 33.2-3.9 48.6 25.2 45.7 45.7-3.4 24-7.4 42.1-11.5 56.5 94.8 54.8 218.1 41.9 299.3-39.2s94-204.4 39.2-299.3c-14.4 4.1-32.5 8-56.5 11.5zM255.7 106c3.3-13.2 22.4-11.5 23.6 1.8l4.8 52.3 52.3 4.8c13.4 1.2 14.9 20.3 1.8 23.6l-90.5 22.6c-8.9 2.2-16.7-5.9-14.5-14.5l22.5-90.6zm-90.9 230.3L160 284l-52.3-4.8c-13.4-1.2-14.9-20.3-1.8-23.6l90.5-22.6c8.8-2.2 16.7 5.8 14.5 14.5L188.3 338c-3.1 13.2-22.2 11.7-23.5-1.7zm215.7 44.2c-29.3 29.3-75.7 50.4-116.7 50.4-18.9 0-36.6-4.5-51-14.7-9.8-6.9-8.7-21.8 2-27.2 28.3-14.6 63.9-42.4 97.8-76.3s61.7-69.6 76.3-97.8c5.4-10.5 20.2-11.9 27.3-2 32.3 45.3 7.1 124.7-35.7 167.6z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM94.6 168.9l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.2 1 8.9 8.6 4.3 13.2l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L152 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.6-4.7-1.9-12.3 4.3-13.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm157.7-249.9l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L344 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.5-4.6-1.9-12.2 4.3-13.2l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.3.9 9 8.5 4.4 13.1z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M102.4 256.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm523.4 26.8c-14.8-14.8-65.7-23.5-88.3-26.8-5.5-.8-10.3 3.9-9.5 9.5 3.2 22.6 12 73.5 26.8 88.3 19.2 19.2 50.6 18.9 70.2-.7s20-51.2.8-70.3zm-129.4-12.8c-3.8-26.6 19.1-49.5 45.7-45.7 8.9 1.3 16.8 2.7 24.3 4.1C552.7 104.5 447.7 8 320 8S87.3 104.5 73.6 228.5c7.5-1.4 15.4-2.8 24.3-4.1 33.2-3.9 48.6 25.3 45.7 45.7-11.8 82.3-29.9 100.4-35.8 106.4-.9.9-2 1.6-3 2.5 42.7 74.6 123 125 215.2 125s172.5-50.4 215.2-125.1c-1-.9-2.1-1.5-3-2.5-5.9-5.9-24-24-35.8-106.3zM400 152c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.7 9.2-21.6 20.7-17.9C227.1 330.5 272 336 320 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-34.9 134.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M293.1 374.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-33.8 210.3l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.7 4.7 7.7 15.9 0 20.6zm163 30c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.8-4.7-7.8-15.9 0-20.6l80-48c11.7-6.9 23.9 7.7 15.4 18L343.6 208l33.6 40.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M344 184c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-56 225l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L112 233c-8.5 7.4-21.6.3-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c1.6 11.1-11.6 18.2-20 10.8zm152 39c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm-50.9 102.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm168 25l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.6 11-11.5 18.2-20 10.8zm-243.1 87.8C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6 20.7 17.9-9.2 55-83.2 93.3-143.8 93.3s-134.5-38.3-143.8-93.3c-2-11.9 9.3-21.6 20.7-17.9z\"],\n    \"grip-horizontal\": [448, 512, [], \"f58d\", \"M96 288H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM96 96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"grip-lines\": [512, 512, [], \"f7a4\", \"M496 288H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-128H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"grip-lines-vertical\": [256, 512, [], \"f7a5\", \"M96 496V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16zm128 0V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16z\"],\n    \"grip-vertical\": [320, 512, [], \"f58e\", \"M96 32H32C14.33 32 0 46.33 0 64v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM288 32h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"guitar\": [512, 512, [], \"f7a6\", \"M502.6 54.6L457.4 9.4c-12.5-12.5-32.8-12.5-45.3 0l-67.9 67.9c-12.5 12.5-12.5 32.8 0 45.3L290 176.7c-45.4-29-100.4-28.9-133.5 4.2-9.7 9.7-16.4 21.2-20.5 33.9-6.1 18.8-23.5 33.1-42.7 34.9-24 2.3-46.3 11.6-63.4 28.8C-16.3 324.6-8 407.6 48.2 463.8c56.2 56.2 139.2 64.4 185.3 18.3 17.2-17.1 26.5-39.4 28.8-63.5 1.8-19.1 16.1-36.6 34.9-42.7 12.7-4.1 24.2-10.8 33.9-20.5 33.1-33.1 33.1-88.1 4.2-133.5l54.2-54.2c12.5 12.5 32.8 12.5 45.3 0l67.9-67.9c12.4-12.4 12.4-32.7-.1-45.2zM208 352c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"h-square\": [448, 512, [], \"f0fd\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-112 48h-32c-8.837 0-16 7.163-16 16v80H160v-80c0-8.837-7.163-16-16-16h-32c-8.837 0-16 7.163-16 16v224c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16v-80h128v80c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16V144c0-8.837-7.163-16-16-16z\"],\n    \"hamburger\": [512, 512, [], \"f805\", \"M464 256H48a48 48 0 0 0 0 96h416a48 48 0 0 0 0-96zm16 128H32a16 16 0 0 0-16 16v16a64 64 0 0 0 64 64h352a64 64 0 0 0 64-64v-16a16 16 0 0 0-16-16zM58.64 224h394.72c34.57 0 54.62-43.9 34.82-75.88C448 83.2 359.55 32.1 256 32c-103.54.1-192 51.2-232.18 116.11C4 180.09 24.07 224 58.64 224zM384 112a16 16 0 1 1-16 16 16 16 0 0 1 16-16zM256 80a16 16 0 1 1-16 16 16 16 0 0 1 16-16zm-128 32a16 16 0 1 1-16 16 16 16 0 0 1 16-16z\"],\n    \"hammer\": [576, 512, [], \"f6e3\", \"M571.31 193.94l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31-28.9-28.9c5.63-21.31.36-44.9-16.35-61.61l-45.25-45.25c-62.48-62.48-163.79-62.48-226.28 0l90.51 45.25v18.75c0 16.97 6.74 33.25 18.75 45.25l49.14 49.14c16.71 16.71 40.3 21.98 61.61 16.35l28.9 28.9-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l90.51-90.51c6.23-6.24 6.23-16.37-.02-22.62zm-286.72-15.2c-3.7-3.7-6.84-7.79-9.85-11.95L19.64 404.96c-25.57 23.88-26.26 64.19-1.53 88.93s65.05 24.05 88.93-1.53l238.13-255.07c-3.96-2.91-7.9-5.87-11.44-9.41l-49.14-49.14z\"],\n    \"hamsa\": [512, 512, [], \"f665\", \"M509.34 307.25C504.28 295.56 492.75 288 480 288h-64V80c0-22-18-40-40-40s-40 18-40 40v134c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V40c0-22-18-40-40-40s-40 18-40 40v174c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V80c0-22-18-40-40-40S96 58 96 80v208H32c-12.75 0-24.28 7.56-29.34 19.25a31.966 31.966 0 0 0 5.94 34.58l102.69 110.03C146.97 490.08 199.69 512 256 512s109.03-21.92 144.72-60.14L503.4 341.83a31.966 31.966 0 0 0 5.94-34.58zM256 416c-53.02 0-96-64-96-64s42.98-64 96-64 96 64 96 64-42.98 64-96 64zm0-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"hand-holding\": [576, 512, [], \"f4bd\", \"M565.3 328.1c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-heart\": [576, 512, [], \"f4be\", \"M275.3 250.5c7 7.4 18.4 7.4 25.5 0l108.9-114.2c31.6-33.2 29.8-88.2-5.6-118.8-30.8-26.7-76.7-21.9-104.9 7.7L288 36.9l-11.1-11.6C248.7-4.4 202.8-9.2 172 17.5c-35.3 30.6-37.2 85.6-5.6 118.8l108.9 114.2zm290 77.6c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-usd\": [544, 512, [], \"f4c0\", \"M257.6 144.3l50 14.3c3.6 1 6.1 4.4 6.1 8.1 0 4.6-3.8 8.4-8.4 8.4h-32.8c-3.6 0-7.1-.8-10.3-2.2-4.8-2.2-10.4-1.7-14.1 2l-17.5 17.5c-5.3 5.3-4.7 14.3 1.5 18.4 9.5 6.3 20.3 10.1 31.8 11.5V240c0 8.8 7.2 16 16 16h16c8.8 0 16-7.2 16-16v-17.6c30.3-3.6 53.3-31 49.3-63-2.9-23-20.7-41.3-42.9-47.7l-50-14.3c-3.6-1-6.1-4.4-6.1-8.1 0-4.6 3.8-8.4 8.4-8.4h32.8c3.6 0 7.1.8 10.3 2.2 4.8 2.2 10.4 1.7 14.1-2l17.5-17.5c5.3-5.3 4.7-14.3-1.5-18.4-9.5-6.3-20.3-10.1-31.8-11.5V16c0-8.8-7.2-16-16-16h-16c-8.8 0-16 7.2-16 16v17.6c-30.3 3.6-53.3 31-49.3 63 2.9 23 20.7 41.3 42.9 47.7zm276.3 183.8c-11.2-10.7-28.5-10-40.3 0L406.4 402c-10.7 9.1-24 14-37.8 14H256.9c-8.3 0-15.1-7.2-15.1-16s6.8-16 15.1-16h73.9c15.1 0 29-10.9 31.4-26.6 3.1-20-11.5-37.4-29.8-37.4H181.3c-25.5 0-50.2 9.3-69.9 26.3L67.5 384H15.1C6.8 384 0 391.2 0 400v96c0 8.8 6.8 16 15.1 16H352c13.7 0 27-4.9 37.8-14l142.8-121c14.4-12.1 15.5-35.3 1.3-48.9z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M384 480h192V363.778a95.998 95.998 0 0 0-14.833-51.263L398.127 54.368A48 48 0 0 0 357.544 32H24C10.745 32 0 42.745 0 56v16c0 30.928 25.072 56 56 56h229.981c12.844 0 21.556 13.067 16.615 24.923l-21.41 51.385A32 32 0 0 1 251.648 224H128c-35.346 0-64 28.654-64 64v8c0 13.255 10.745 24 24 24h147.406a47.995 47.995 0 0 1 25.692 7.455l111.748 70.811A24.001 24.001 0 0 1 384 418.539V480z\"],\n    \"hand-middle-finger\": [512, 512, [], \"f806\", \"M479.93 317.12a37.33 37.33 0 0 0-28.28-36.19L416 272v-49.59c0-11.44-9.69-21.29-23.15-23.54l-38.4-6.4C336.63 189.5 320 200.86 320 216v32a8 8 0 0 1-16 0V50c0-26.28-20.25-49.2-46.52-50A48 48 0 0 0 208 48v200a8 8 0 0 1-16 0v-32c0-15.15-16.63-26.51-34.45-23.54l-30.68 5.12c-18 3-30.87 16.12-30.87 31.38V376a8 8 0 0 1-16 0v-76l-27.36 15A37.34 37.34 0 0 0 32 348.4v73.47a37.31 37.31 0 0 0 10.93 26.39l30.93 30.93A112 112 0 0 0 153.05 512h215A112 112 0 0 0 480 400z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M408.781 128.007C386.356 127.578 368 146.36 368 168.79V256h-8V79.79c0-22.43-18.356-41.212-40.781-40.783C297.488 39.423 280 57.169 280 79v177h-8V40.79C272 18.36 253.644-.422 231.219.007 209.488.423 192 18.169 192 40v216h-8V80.79c0-22.43-18.356-41.212-40.781-40.783C121.488 40.423 104 58.169 104 80v235.992l-31.648-43.519c-12.993-17.866-38.009-21.817-55.877-8.823-17.865 12.994-21.815 38.01-8.822 55.877l125.601 172.705A48 48 0 0 0 172.073 512h197.59c22.274 0 41.622-15.324 46.724-37.006l26.508-112.66a192.011 192.011 0 0 0 5.104-43.975V168c.001-21.831-17.487-39.577-39.218-39.993z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M408 216c-22.092 0-40 17.909-40 40h-8v-32c0-22.091-17.908-40-40-40s-40 17.909-40 40v32h-8V48c0-26.51-21.49-48-48-48s-48 21.49-48 48v208h-13.572L92.688 78.449C82.994 53.774 55.134 41.63 30.461 51.324 5.787 61.017-6.356 88.877 3.337 113.551l74.765 190.342-31.09 24.872c-15.381 12.306-19.515 33.978-9.741 51.081l64 112A39.998 39.998 0 0 0 136 512h240c18.562 0 34.686-12.77 38.937-30.838l32-136A39.97 39.97 0 0 0 448 336v-80c0-22.091-17.908-40-40-40z\"],\n    \"hand-point-down\": [384, 512, [], \"f0a7\", \"M91.826 467.2V317.966c-8.248 5.841-16.558 10.57-24.918 14.153C35.098 345.752-.014 322.222 0 288c.008-18.616 10.897-32.203 29.092-40 28.286-12.122 64.329-78.648 77.323-107.534 7.956-17.857 25.479-28.453 43.845-28.464l.001-.002h171.526c11.812 0 21.897 8.596 23.703 20.269 7.25 46.837 38.483 61.76 38.315 123.731-.007 2.724.195 13.254.195 16 0 50.654-22.122 81.574-71.263 72.6-9.297 18.597-39.486 30.738-62.315 16.45-21.177 24.645-53.896 22.639-70.944 6.299V467.2c0 24.15-20.201 44.8-43.826 44.8-23.283 0-43.826-21.35-43.826-44.8zM112 72V24c0-13.255 10.745-24 24-24h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24zm212-24c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M44.8 155.826h149.234c-5.841-8.248-10.57-16.558-14.153-24.918C166.248 99.098 189.778 63.986 224 64c18.616.008 32.203 10.897 40 29.092 12.122 28.286 78.648 64.329 107.534 77.323 17.857 7.956 28.453 25.479 28.464 43.845l.002.001v171.526c0 11.812-8.596 21.897-20.269 23.703-46.837 7.25-61.76 38.483-123.731 38.315-2.724-.007-13.254.195-16 .195-50.654 0-81.574-22.122-72.6-71.263-18.597-9.297-30.738-39.486-16.45-62.315-24.645-21.177-22.639-53.896-6.299-70.944H44.8c-24.15 0-44.8-20.201-44.8-43.826 0-23.283 21.35-43.826 44.8-43.826zM440 176h48c13.255 0 24 10.745 24 24v192c0 13.255-10.745 24-24 24h-48c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24zm24 212c11.046 0 20-8.954 20-20s-8.954-20-20-20-20 8.954-20 20 8.954 20 20 20z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M512 199.652c0 23.625-20.65 43.826-44.8 43.826h-99.851c16.34 17.048 18.346 49.766-6.299 70.944 14.288 22.829 2.147 53.017-16.45 62.315C353.574 425.878 322.654 448 272 448c-2.746 0-13.276-.203-16-.195-61.971.168-76.894-31.065-123.731-38.315C120.596 407.683 112 397.599 112 385.786V214.261l.002-.001c.011-18.366 10.607-35.889 28.464-43.845 28.886-12.994 95.413-49.038 107.534-77.323 7.797-18.194 21.384-29.084 40-29.092 34.222-.014 57.752 35.098 44.119 66.908-3.583 8.359-8.312 16.67-14.153 24.918H467.2c23.45 0 44.8 20.543 44.8 43.826zM96 200v192c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24h48c13.255 0 24 10.745 24 24zM68 368c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-up\": [384, 512, [], \"f0a6\", \"M135.652 0c23.625 0 43.826 20.65 43.826 44.8v99.851c17.048-16.34 49.766-18.346 70.944 6.299 22.829-14.288 53.017-2.147 62.315 16.45C361.878 158.426 384 189.346 384 240c0 2.746-.203 13.276-.195 16 .168 61.971-31.065 76.894-38.315 123.731C343.683 391.404 333.599 400 321.786 400H150.261l-.001-.002c-18.366-.011-35.889-10.607-43.845-28.464C93.421 342.648 57.377 276.122 29.092 264 10.897 256.203.008 242.616 0 224c-.014-34.222 35.098-57.752 66.908-44.119 8.359 3.583 16.67 8.312 24.918 14.153V44.8c0-23.45 20.543-44.8 43.826-44.8zM136 416h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24v-48c0-13.255 10.745-24 24-24zm168 28c-11.046 0-20 8.954-20 20s8.954 20 20 20 20-8.954 20-20-8.954-20-20-20z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M448 240v96c0 3.084-.356 6.159-1.063 9.162l-32 136C410.686 499.23 394.562 512 376 512H168a40.004 40.004 0 0 1-32.35-16.473l-127.997-176c-12.993-17.866-9.043-42.883 8.822-55.876 17.867-12.994 42.884-9.043 55.877 8.823L104 315.992V40c0-22.091 17.908-40 40-40s40 17.909 40 40v200h8v-40c0-22.091 17.908-40 40-40s40 17.909 40 40v40h8v-24c0-22.091 17.908-40 40-40s40 17.909 40 40v24h8c0-22.091 17.908-40 40-40s40 17.909 40 40zm-256 80h-8v96h8v-96zm88 0h-8v96h8v-96zm88 0h-8v96h8v-96z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M464.8 80c-26.9-.4-48.8 21.2-48.8 48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v32h-8V80.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v136l-8-7.1v-48.1c0-26.3-20.9-48.3-47.2-48.8C21.9 127.6 0 149.2 0 176v66.4c0 27.4 11.7 53.5 32.2 71.8l111.7 99.3c10.2 9.1 16.1 22.2 16.1 35.9v6.7c0 13.3 10.7 24 24 24h240c13.3 0 24-10.7 24-24v-2.9c0-12.8 2.6-25.5 7.5-37.3l49-116.3c5-11.8 7.5-24.5 7.5-37.3V128.8c0-26.3-20.9-48.4-47.2-48.8z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M216 440c0-22.092 17.909-40 40-40v-8h-32c-22.091 0-40-17.908-40-40s17.909-40 40-40h32v-8H48c-26.51 0-48-21.49-48-48s21.49-48 48-48h208v-13.572l-177.551-69.74c-24.674-9.694-36.818-37.555-27.125-62.228 9.693-24.674 37.554-36.817 62.228-27.124l190.342 74.765 24.872-31.09c12.306-15.381 33.978-19.515 51.081-9.741l112 64A40.002 40.002 0 0 1 512 168v240c0 18.562-12.77 34.686-30.838 38.937l-136 32A39.982 39.982 0 0 1 336 480h-80c-22.091 0-40-17.908-40-40z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M481.3 97.1c-21.5-5.1-43.1 8.2-48.2 29.6L402.3 256h-11.1l43.6-174.3c5.4-21.4-7.7-43.1-29.1-48.5s-43.1 7.7-48.5 29.1L308.8 256h-15.1L242 31.1c-5-21.6-26.4-35-48-30.1-21.5 4.9-35 26.4-30 47.9l47.6 207h-9.8L167 103.1c-4.9-21.5-26.3-35-47.9-30.1-21.5 4.9-35 26.3-30.1 47.9l39 171.6v79.4l-60.6-57c-16.1-15.1-41.4-14.4-56.5 1.7s-14.4 41.4 1.7 56.5L146.3 499c8.9 8.4 20.7 13 32.9 13h216.7c21.3 0 40-14 46-34.4l26.2-88.3c2.6-8.9 4-18 4-27.3v-42c0-7.5.9-15 2.6-22.2L511 145.3c5-21.5-8.3-43.1-29.7-48.2z\"],\n    \"hands\": [640, 512, [], \"f4c2\", \"M204.8 230.4c-10.6-14.1-30.7-17-44.8-6.4-14.1 10.6-17 30.7-6.4 44.8l38.1 50.8c4.8 6.4 4.1 15.3-1.5 20.9l-12.8 12.8c-6.7 6.7-17.6 6.2-23.6-1.1L64 244.4V96c0-17.7-14.3-32-32-32S0 78.3 0 96v218.4c0 10.9 3.7 21.5 10.5 30l104.1 134.3c5 6.5 8.4 13.9 10.4 21.7 1.8 6.9 8.1 11.6 15.3 11.6H272c8.8 0 16-7.2 16-16V384c0-27.7-9-54.6-25.6-76.8l-57.6-76.8zM608 64c-17.7 0-32 14.3-32 32v148.4l-89.8 107.8c-6 7.2-17 7.7-23.6 1.1l-12.8-12.8c-5.6-5.6-6.3-14.5-1.5-20.9l38.1-50.8c10.6-14.1 7.7-34.2-6.4-44.8-14.1-10.6-34.2-7.7-44.8 6.4l-57.6 76.8C361 329.4 352 356.3 352 384v112c0 8.8 7.2 16 16 16h131.7c7.1 0 13.5-4.7 15.3-11.6 2-7.8 5.4-15.2 10.4-21.7l104.1-134.3c6.8-8.5 10.5-19.1 10.5-30V96c0-17.7-14.3-32-32-32z\"],\n    \"hands-helping\": [640, 512, [], \"f4c4\", \"M488 192H336v56c0 39.7-32.3 72-72 72s-72-32.3-72-72V126.4l-64.9 39C107.8 176.9 96 197.8 96 220.2v47.3l-80 46.2C.7 322.5-4.6 342.1 4.3 357.4l80 138.6c8.8 15.3 28.4 20.5 43.7 11.7L231.4 448H368c35.3 0 64-28.7 64-64h16c17.7 0 32-14.3 32-32v-64h8c13.3 0 24-10.7 24-24v-48c0-13.3-10.7-24-24-24zm147.7-37.4L555.7 16C546.9.7 527.3-4.5 512 4.3L408.6 64H306.4c-12 0-23.7 3.4-33.9 9.7L239 94.6c-9.4 5.8-15 16.1-15 27.1V248c0 22.1 17.9 40 40 40s40-17.9 40-40v-88h184c30.9 0 56 25.1 56 56v28.5l80-46.2c15.3-8.9 20.5-28.4 11.7-43.7z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M434.7 64h-85.9c-8 0-15.7 3-21.6 8.4l-98.3 90c-.1.1-.2.3-.3.4-16.6 15.6-16.3 40.5-2.1 56 12.7 13.9 39.4 17.6 56.1 2.7.1-.1.3-.1.4-.2l79.9-73.2c6.5-5.9 16.7-5.5 22.6 1 6 6.5 5.5 16.6-1 22.6l-26.1 23.9L504 313.8c2.9 2.4 5.5 5 7.9 7.7V128l-54.6-54.6c-5.9-6-14.1-9.4-22.6-9.4zM544 128.2v223.9c0 17.7 14.3 32 32 32h64V128.2h-96zm48 223.9c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM0 384h64c17.7 0 32-14.3 32-32V128.2H0V384zm48-63.9c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16c0-8.9 7.2-16 16-16zm435.9 18.6L334.6 217.5l-30 27.5c-29.7 27.1-75.2 24.5-101.7-4.4-26.9-29.4-24.8-74.9 4.4-101.7L289.1 64h-83.8c-8.5 0-16.6 3.4-22.6 9.4L128 128v223.9h18.3l90.5 81.9c27.4 22.3 67.7 18.1 90-9.3l.2-.2 17.9 15.5c15.9 13 39.4 10.5 52.3-5.4l31.4-38.6 5.4 4.4c13.7 11.1 33.9 9.1 45-4.7l9.5-11.7c11.2-13.8 9.1-33.9-4.6-45.1z\"],\n    \"hanukiah\": [640, 512, [], \"f6e6\", \"M232 160c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm-64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm224 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm88 8c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v120h32V168zm-440-8c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm520 0h-32c-8.84 0-16 7.16-16 16v112c0 17.67-14.33 32-32 32H352V128c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v192H96c-17.67 0-32-14.33-32-32V176c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v112c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V176c0-8.84-7.16-16-16-16zm-16-32c13.25 0 24-11.94 24-26.67S608 48 608 48s-24 38.61-24 53.33S594.75 128 608 128zm-576 0c13.25 0 24-11.94 24-26.67S32 48 32 48 8 86.61 8 101.33 18.75 128 32 128zm288-48c13.25 0 24-11.94 24-26.67S320 0 320 0s-24 38.61-24 53.33S306.75 80 320 80zm-208 48c13.25 0 24-11.94 24-26.67S112 48 112 48s-24 38.61-24 53.33S98.75 128 112 128zm64 0c13.25 0 24-11.94 24-26.67S176 48 176 48s-24 38.61-24 53.33S162.75 128 176 128zm64 0c13.25 0 24-11.94 24-26.67S240 48 240 48s-24 38.61-24 53.33S226.75 128 240 128zm160 0c13.25 0 24-11.94 24-26.67S400 48 400 48s-24 38.61-24 53.33S386.75 128 400 128zm64 0c13.25 0 24-11.94 24-26.67S464 48 464 48s-24 38.61-24 53.33S450.75 128 464 128zm64 0c13.25 0 24-11.94 24-26.67S528 48 528 48s-24 38.61-24 53.33S514.75 128 528 128z\"],\n    \"hard-hat\": [512, 512, [], \"f807\", \"M480 288c0-80.25-49.28-148.92-119.19-177.62L320 192V80a16 16 0 0 0-16-16h-96a16 16 0 0 0-16 16v112l-40.81-81.62C81.28 139.08 32 207.75 32 288v64h448zm16 96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"hashtag\": [448, 512, [], \"f292\", \"M440.667 182.109l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l14.623-81.891C377.123 38.754 371.468 32 363.997 32h-40.632a12 12 0 0 0-11.813 9.891L296.175 128H197.54l14.623-81.891C213.477 38.754 207.822 32 200.35 32h-40.632a12 12 0 0 0-11.813 9.891L132.528 128H53.432a12 12 0 0 0-11.813 9.891l-7.143 40C33.163 185.246 38.818 192 46.289 192h74.81L98.242 320H19.146a12 12 0 0 0-11.813 9.891l-7.143 40C-1.123 377.246 4.532 384 12.003 384h74.81L72.19 465.891C70.877 473.246 76.532 480 84.003 480h40.632a12 12 0 0 0 11.813-9.891L151.826 384h98.634l-14.623 81.891C234.523 473.246 240.178 480 247.65 480h40.632a12 12 0 0 0 11.813-9.891L315.472 384h79.096a12 12 0 0 0 11.813-9.891l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l22.857-128h79.096a12 12 0 0 0 11.813-9.891zM261.889 320h-98.634l22.857-128h98.634l-22.857 128z\"],\n    \"hat-wizard\": [512, 512, [], \"f6e8\", \"M496 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-304-64l-64-32 64-32 32-64 32 64 64 32-64 32-16 32h208l-86.41-201.63a63.955 63.955 0 0 1-1.89-45.45L416 0 228.42 107.19a127.989 127.989 0 0 0-53.46 59.15L64 416h144l-16-32zm64-224l16-32 16 32 32 16-32 16-16 32-16-32-32-16 32-16z\"],\n    \"haykal\": [512, 512, [], \"f666\", \"M496.25 202.52l-110-15.44 41.82-104.34c6.67-16.64-11.6-32.18-26.59-22.63L307.44 120 273.35 12.82C270.64 4.27 263.32 0 256 0c-7.32 0-14.64 4.27-17.35 12.82l-34.09 107.19-94.04-59.89c-14.99-9.55-33.25 5.99-26.59 22.63l41.82 104.34-110 15.43c-17.54 2.46-21.68 26.27-6.03 34.67l98.16 52.66-74.48 83.54c-10.92 12.25-1.72 30.93 13.29 30.93 1.31 0 2.67-.14 4.07-.45l108.57-23.65-4.11 112.55c-.43 11.65 8.87 19.22 18.41 19.22 5.15 0 10.39-2.21 14.2-7.18l68.18-88.9 68.18 88.9c3.81 4.97 9.04 7.18 14.2 7.18 9.54 0 18.84-7.57 18.41-19.22l-4.11-112.55 108.57 23.65c17.36 3.76 29.21-17.2 17.35-30.49l-74.48-83.54 98.16-52.66c15.64-8.39 11.5-32.2-6.04-34.66zM338.51 311.68l-51.89-11.3 1.97 53.79L256 311.68l-32.59 42.49 1.96-53.79-51.89 11.3 35.6-39.93-46.92-25.17 52.57-7.38-19.99-49.87 44.95 28.62L256 166.72l16.29 51.23 44.95-28.62-19.99 49.87 52.57 7.38-46.92 25.17 35.61 39.93z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M576 304v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48zm-48-80a79.557 79.557 0 0 1 30.777 6.165L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L17.223 230.165A79.557 79.557 0 0 1 48 224h480zm-48 96c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm-96 0c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"heading\": [512, 512, [], \"f1dc\", \"M448 96v320h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H320a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V288H160v128h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H32a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V96H32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16h-32v128h192V96h-32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16z\"],\n    \"headphones\": [512, 512, [], \"f025\", \"M256 32C114.52 32 0 146.496 0 288v48a32 32 0 0 0 17.689 28.622l14.383 7.191C34.083 431.903 83.421 480 144 480h24c13.255 0 24-10.745 24-24V280c0-13.255-10.745-24-24-24h-24c-31.342 0-59.671 12.879-80 33.627V288c0-105.869 86.131-192 192-192s192 86.131 192 192v1.627C427.671 268.879 399.342 256 368 256h-24c-13.255 0-24 10.745-24 24v176c0 13.255 10.745 24 24 24h24c60.579 0 109.917-48.098 111.928-108.187l14.382-7.191A32 32 0 0 0 512 336v-48c0-141.479-114.496-256-256-256z\"],\n    \"headphones-alt\": [512, 512, [], \"f58f\", \"M160 288h-16c-35.35 0-64 28.7-64 64.12v63.76c0 35.41 28.65 64.12 64 64.12h16c17.67 0 32-14.36 32-32.06V320.06c0-17.71-14.33-32.06-32-32.06zm208 0h-16c-17.67 0-32 14.35-32 32.06v127.88c0 17.7 14.33 32.06 32 32.06h16c35.35 0 64-28.71 64-64.12v-63.76c0-35.41-28.65-64.12-64-64.12zM256 32C112.91 32 4.57 151.13 0 288v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288c0-114.67 93.33-207.8 208-207.82 114.67.02 208 93.15 208 207.82v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288C507.43 151.13 399.09 32 256 32z\"],\n    \"headset\": [512, 512, [], \"f590\", \"M192 208c0-17.67-14.33-32-32-32h-16c-35.35 0-64 28.65-64 64v48c0 35.35 28.65 64 64 64h16c17.67 0 32-14.33 32-32V208zm176 144c35.35 0 64-28.65 64-64v-48c0-35.35-28.65-64-64-64h-16c-17.67 0-32 14.33-32 32v112c0 17.67 14.33 32 32 32h16zM256 0C113.18 0 4.58 118.83 0 256v16c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-16c0-114.69 93.31-208 208-208s208 93.31 208 208h-.12c.08 2.43.12 165.72.12 165.72 0 23.35-18.93 42.28-42.28 42.28H320c0-26.51-21.49-48-48-48h-32c-26.51 0-48 21.49-48 48s21.49 48 48 48h181.72c49.86 0 90.28-40.42 90.28-90.28V256C507.42 118.83 398.82 0 256 0z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M462.3 62.6C407.5 15.9 326 24.3 275.7 76.2L256 96.5l-19.7-20.3C186.1 24.3 104.5 15.9 49.7 62.6c-62.8 53.6-66.1 149.8-9.9 207.9l193.5 199.8c12.5 12.9 32.8 12.9 45.3 0l193.5-199.8c56.3-58.1 53-154.3-9.8-207.9z\"],\n    \"heart-broken\": [512, 512, [], \"f7a9\", \"M473.7 73.8l-2.4-2.5c-46-47-118-51.7-169.6-14.8L336 159.9l-96 64 48 128-144-144 96-64-28.6-86.5C159.7 19.6 87 24 40.7 71.4l-2.4 2.4C-10.4 123.6-12.5 202.9 31 256l212.1 218.6c7.1 7.3 18.6 7.3 25.7 0L481 255.9c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"heartbeat\": [512, 512, [], \"f21e\", \"M320.2 243.8l-49.7 99.4c-6 12.1-23.4 11.7-28.9-.6l-56.9-126.3-30 71.7H60.6l182.5 186.5c7.1 7.3 18.6 7.3 25.7 0L451.4 288H342.3l-22.1-44.2zM473.7 73.9l-2.4-2.5c-51.5-52.6-135.8-52.6-187.4 0L256 100l-27.9-28.5c-51.5-52.7-135.9-52.7-187.4 0l-2.4 2.4C-10.4 123.7-12.5 203 31 256h102.4l35.9-86.2c5.4-12.9 23.6-13.2 29.4-.4l58.2 129.3 49-97.9c5.9-11.8 22.7-11.8 28.6 0l27.6 55.2H481c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"helicopter\": [640, 512, [], \"f533\", \"M304 384h272c17.67 0 32-14.33 32-32 0-123.71-100.29-224-224-224V64h176c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H144c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h176v64H112L68.8 70.4C65.78 66.37 61.03 64 56 64H16.01C5.6 64-2.04 73.78.49 83.88L32 192l160 64 86.4 115.2A31.992 31.992 0 0 0 304 384zm112-188.49C478.55 208.3 528.03 257.44 540.79 320H416V195.51zm219.37 263.3l-22.15-22.2c-6.25-6.26-16.24-6.1-22.64.01-7.09 6.77-13.84 11.25-24.64 11.25H240c-8.84 0-16 7.18-16 16.03v32.06c0 8.85 7.16 16.03 16 16.03h325.94c14.88 0 35.3-.47 68.45-29.52 7.02-6.14 7.57-17.05.98-23.66z\"],\n    \"highlighter\": [544, 512, [], \"f591\", \"M0 479.98L99.92 512l35.45-35.45-67.04-67.04L0 479.98zm124.61-240.01a36.592 36.592 0 0 0-10.79 38.1l13.05 42.83-50.93 50.94 96.23 96.23 50.86-50.86 42.74 13.08c13.73 4.2 28.65-.01 38.15-10.78l35.55-41.64-173.34-173.34-41.52 35.44zm403.31-160.7l-63.2-63.2c-20.49-20.49-53.38-21.52-75.12-2.35L190.55 183.68l169.77 169.78L530.27 154.4c19.18-21.74 18.15-54.63-2.35-75.13z\"],\n    \"hiking\": [384, 512, [], \"f6ec\", \"M80.95 472.23c-4.28 17.16 6.14 34.53 23.28 38.81 2.61.66 5.22.95 7.8.95 14.33 0 27.37-9.7 31.02-24.23l25.24-100.97-52.78-52.78-34.56 138.22zm14.89-196.12L137 117c2.19-8.42-3.14-16.95-11.92-19.06-43.88-10.52-88.35 15.07-99.32 57.17L.49 253.24c-2.19 8.42 3.14 16.95 11.92 19.06l63.56 15.25c8.79 2.1 17.68-3.02 19.87-11.44zM368 160h-16c-8.84 0-16 7.16-16 16v16h-34.75l-46.78-46.78C243.38 134.11 228.61 128 212.91 128c-27.02 0-50.47 18.3-57.03 44.52l-26.92 107.72a32.012 32.012 0 0 0 8.42 30.39L224 397.25V480c0 17.67 14.33 32 32 32s32-14.33 32-32v-82.75c0-17.09-6.66-33.16-18.75-45.25l-46.82-46.82c.15-.5.49-.89.62-1.41l19.89-79.57 22.43 22.43c6 6 14.14 9.38 22.62 9.38h48v240c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V176c.01-8.84-7.15-16-15.99-16zM240 96c26.51 0 48-21.49 48-48S266.51 0 240 0s-48 21.49-48 48 21.49 48 48 48z\"],\n    \"hippo\": [640, 512, [], \"f6ed\", \"M581.12 96.2c-27.67-.15-52.5 17.58-76.6 26.62C489.98 88.27 455.83 64 416 64c-11.28 0-21.95 2.3-32 5.88V56c0-13.26-10.75-24-24-24h-16c-13.25 0-24 10.74-24 24v48.98C286.01 79.58 241.24 64 192 64 85.96 64 0 135.64 0 224v240c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16v-70.79C128.35 407.57 166.72 416 208 416s79.65-8.43 112-22.79V464c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V288h128v32c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-32c17.67 0 32-14.33 32-32v-92.02c0-34.09-24.79-67.59-58.88-67.78zM448 176c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"history\": [512, 512, [], \"f1da\", \"M504 255.531c.253 136.64-111.18 248.372-247.82 248.468-59.015.042-113.223-20.53-155.822-54.911-11.077-8.94-11.905-25.541-1.839-35.607l11.267-11.267c8.609-8.609 22.353-9.551 31.891-1.984C173.062 425.135 212.781 440 256 440c101.705 0 184-82.311 184-184 0-101.705-82.311-184-184-184-48.814 0-93.149 18.969-126.068 49.932l50.754 50.754c10.08 10.08 2.941 27.314-11.313 27.314H24c-8.837 0-16-7.163-16-16V38.627c0-14.254 17.234-21.393 27.314-11.314l49.372 49.372C129.209 34.136 189.552 8 256 8c136.81 0 247.747 110.78 248 247.531zm-180.912 78.784l9.823-12.63c8.138-10.463 6.253-25.542-4.21-33.679L288 256.349V152c0-13.255-10.745-24-24-24h-16c-13.255 0-24 10.745-24 24v135.651l65.409 50.874c10.463 8.137 25.541 6.253 33.679-4.21z\"],\n    \"hockey-puck\": [512, 512, [], \"f453\", \"M0 160c0-53 114.6-96 256-96s256 43 256 96-114.6 96-256 96S0 213 0 160zm0 82.2V352c0 53 114.6 96 256 96s256-43 256-96V242.2c-113.4 82.3-398.5 82.4-512 0z\"],\n    \"holly-berry\": [448, 512, [], \"f7aa\", \"M144 192c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm112-48c0 26.5 21.5 48 48 48s48-21.5 48-48-21.5-48-48-48-48 21.5-48 48zm-32-48c26.5 0 48-21.5 48-48S250.5 0 224 0s-48 21.5-48 48 21.5 48 48 48zm-16.2 139.1c.1-12.4-13.1-20.1-23.8-13.7-34.3 20.3-71.4 32.7-108.7 36.2-9.7.9-15.6 11.3-11.6 20.2 6.2 13.9 11.1 28.6 14.7 43.8 3.6 15.2-5.3 30.6-20.2 35.1-14.9 4.5-30.1 7.6-45.3 9.1-9.7 1-15.7 11.3-11.7 20.2 15 32.8 22.9 69.5 23 107.7.1 14.4 15.2 23.1 27.6 16 33.2-19 68.9-30.5 104.8-33.9 9.7-.9 15.6-11.3 11.6-20.2-6.2-13.9-11.1-28.6-14.7-43.8-3.6-15.2 5.3-30.6 20.2-35.1 14.9-4.5 30.1-7.6 45.3-9.1 9.7-1 15.7-11.3 11.7-20.2-15.5-34.2-23.3-72.5-22.9-112.3zM435 365.6c-15.2-1.6-30.3-4.7-45.3-9.1-14.9-4.5-23.8-19.9-20.2-35.1 3.6-15.2 8.5-29.8 14.7-43.8 4-8.9-1.9-19.3-11.6-20.2-37.3-3.5-74.4-15.9-108.7-36.2-10.7-6.3-23.9 1.4-23.8 13.7 0 1.6-.2 3.2-.2 4.9.2 33.3 7 65.7 19.9 94 5.7 12.4 5.2 26.6-.6 38.9 4.9 1.2 9.9 2.2 14.8 3.7 14.9 4.5 23.8 19.9 20.2 35.1-3.6 15.2-8.5 29.8-14.7 43.8-4 8.9 1.9 19.3 11.6 20.2 35.9 3.4 71.6 14.9 104.8 33.9 12.5 7.1 27.6-1.6 27.6-16 .2-38.2 8-75 23-107.7 4.3-8.7-1.8-19.1-11.5-20.1z\"],\n    \"home\": [576, 512, [], \"f015\", \"M280.37 148.26L96 300.11V464a16 16 0 0 0 16 16l112.06-.29a16 16 0 0 0 15.92-16V368a16 16 0 0 1 16-16h64a16 16 0 0 1 16 16v95.64a16 16 0 0 0 16 16.05L464 480a16 16 0 0 0 16-16V300L295.67 148.26a12.19 12.19 0 0 0-15.3 0zM571.6 251.47L488 182.56V44.05a12 12 0 0 0-12-12h-56a12 12 0 0 0-12 12v72.61L318.47 43a48 48 0 0 0-61 0L4.34 251.47a12 12 0 0 0-1.6 16.9l25.5 31A12 12 0 0 0 45.15 301l235.22-193.74a12.19 12.19 0 0 1 15.3 0L530.9 301a12 12 0 0 0 16.9-1.6l25.5-31a12 12 0 0 0-1.7-16.93z\"],\n    \"horse\": [576, 512, [], \"f6f0\", \"M575.92 76.6c-.01-8.13-3.02-15.87-8.58-21.8-3.78-4.03-8.58-9.12-13.69-14.5 11.06-6.84 19.5-17.49 22.18-30.66C576.85 4.68 572.96 0 567.9 0H447.92c-70.69 0-128 57.31-128 128H160c-28.84 0-54.4 12.98-72 33.11V160c-48.53 0-88 39.47-88 88v56c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-56c0-13.22 6.87-24.39 16.78-31.68-.21 2.58-.78 5.05-.78 7.68 0 27.64 11.84 52.36 30.54 69.88l-25.72 68.6a63.945 63.945 0 0 0-2.16 37.99l24.85 99.41A15.982 15.982 0 0 0 107.02 512h65.96c10.41 0 18.05-9.78 15.52-19.88l-26.31-105.26 23.84-63.59L320 345.6V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V318.22c19.74-20.19 32-47.75 32-78.22 0-.22-.07-.42-.08-.64V136.89l16 7.11 18.9 37.7c7.45 14.87 25.05 21.55 40.49 15.37l32.55-13.02a31.997 31.997 0 0 0 20.12-29.74l-.06-77.71zm-64 19.4c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"horse-head\": [512, 512, [], \"f7ab\", \"M509.8 332.5l-69.9-164.3c-14.9-41.2-50.4-71-93-79.2 18-10.6 46.3-35.9 34.2-82.3-1.3-5-7.1-7.9-12-6.1L166.9 76.3C35.9 123.4 0 238.9 0 398.8V480c0 17.7 14.3 32 32 32h236.2c23.8 0 39.3-25 28.6-46.3L256 384v-.7c-45.6-3.5-84.6-30.7-104.3-69.6-1.6-3.1-.9-6.9 1.6-9.3l12.1-12.1c3.9-3.9 10.6-2.7 12.9 2.4 14.8 33.7 48.2 57.4 87.4 57.4 17.2 0 33-5.1 46.8-13.2l46 63.9c6 8.4 15.7 13.3 26 13.3h50.3c8.5 0 16.6-3.4 22.6-9.4l45.3-39.8c8.9-9.1 11.7-22.6 7.1-34.4zM328 224c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M448 492v20H0v-20c0-6.627 5.373-12 12-12h20V120c0-13.255 10.745-24 24-24h88V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v72h88c13.255 0 24 10.745 24 24v360h20c6.627 0 12 5.373 12 12zM308 192h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-168 64h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm104 128h-40c-6.627 0-12 5.373-12 12v84h64v-84c0-6.627-5.373-12-12-12zm64-96h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-116 12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40zM182 96h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6z\"],\n    \"hospital-alt\": [576, 512, [], \"f47d\", \"M544 96H416V32c0-17.7-14.3-32-32-32H192c-17.7 0-32 14.3-32 32v64H32c-17.7 0-32 14.3-32 32v368c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16V128c0-17.7-14.3-32-32-32zM160 436c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm160 128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm16-170c0 3.3-2.7 6-6 6h-26v26c0 3.3-2.7 6-6 6h-20c-3.3 0-6-2.7-6-6v-26h-26c-3.3 0-6-2.7-6-6v-20c0-3.3 2.7-6 6-6h26V86c0-3.3 2.7-6 6-6h20c3.3 0 6 2.7 6 6v26h26c3.3 0 6 2.7 6 6v20zm144 298c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"hospital-symbol\": [512, 512, [], \"f47e\", \"M256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm112 376c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-88h-96v88c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8V136c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v88h96v-88c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v240z\"],\n    \"hot-tub\": [512, 512, [], \"f593\", \"M414.21 177.65c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C378.96 6.14 372.22 0 364.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zm-108 0c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C270.96 6.14 264.22 0 256.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zM480 256H256l-110.93-83.2a63.99 63.99 0 0 0-38.4-12.8H64c-35.35 0-64 28.65-64 64v224c0 35.35 28.65 64 64 64h384c35.35 0 64-28.65 64-64V288c0-17.67-14.33-32-32-32zM128 440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zM64 128c35.35 0 64-28.65 64-64S99.35 0 64 0 0 28.65 0 64s28.65 64 64 64z\"],\n    \"hotdog\": [512, 512, [], \"f80f\", \"M488.56 23.44a80 80 0 0 0-113.12 0l-352 352a80 80 0 1 0 113.12 113.12l352-352a80 80 0 0 0 0-113.12zm-49.93 95.19c-19.6 19.59-37.52 22.67-51.93 25.14C373.76 146 364.4 147.6 352 160s-14 21.76-16.23 34.71c-2.48 14.4-5.55 32.33-25.15 51.92s-37.52 22.67-51.92 25.15C245.75 274 236.4 275.6 224 288s-14 21.75-16.23 34.7c-2.47 14.4-5.54 32.33-25.14 51.92s-37.53 22.68-51.93 25.15C117.76 402 108.4 403.6 96 416a16 16 0 0 1-22.63-22.63c19.6-19.59 37.52-22.67 51.92-25.14 13-2.22 22.3-3.82 34.71-16.23s14-21.75 16.22-34.7c2.48-14.4 5.55-32.33 25.15-51.92s37.52-22.67 51.92-25.14c13-2.22 22.3-3.83 34.7-16.23s14-21.76 16.24-34.71c2.47-14.4 5.54-32.33 25.14-51.92s37.52-22.68 51.92-25.15C394.24 110 403.59 108.41 416 96a16 16 0 0 1 22.63 22.63zM31.44 322.18L322.18 31.44l-11.54-11.55c-25-25-63.85-26.66-86.79-3.72L16.17 223.85c-22.94 22.94-21.27 61.79 3.72 86.78zm449.12-132.36L189.82 480.56l11.54 11.55c25 25 63.85 26.66 86.79 3.72l207.68-207.68c22.94-22.94 21.27-61.79-3.72-86.79z\"],\n    \"hotel\": [576, 512, [], \"f594\", \"M560 64c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h15.98v384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h240v-80c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16v80h240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-16V64h16zm-304 44.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm0 96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm-128-96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zM179.2 256h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8zM192 384c0-53.02 42.98-96 96-96s96 42.98 96 96H192zm256-140.8c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-96c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64z\"],\n    \"hourglass-end\": [384, 512, [], \"f253\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64zM192 208c-57.787 0-104-66.518-104-144h208c0 77.945-46.51 144-104 144z\"],\n    \"hourglass-half\": [384, 512, [], \"f252\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-75.078 384H99.08c17.059-46.797 52.096-80 92.92-80 40.821 0 75.862 33.196 92.922 80zm.019-256H99.078C91.988 108.548 88 86.748 88 64h208c0 22.805-3.987 44.587-11.059 64z\"],\n    \"hourglass-start\": [384, 512, [], \"f251\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-64 448H88c0-77.458 46.204-144 104-144 57.786 0 104 66.517 104 144z\"],\n    \"house-damage\": [576, 512, [], \"f6f1\", \"M288 114.96L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496c0 8.84 7.16 16 16 16h149.23L192 439.19l104.11-64-60.16-119.22L384 392.75l-104.11 64L319.81 512H496c8.84 0 16-7.16 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2L288 114.96zm282.69 121.32L512 184.45V48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v51.69L314.75 10.31C307.12 3.45 297.56.01 288 0s-19.1 3.41-26.7 10.27L5.31 236.28c-6.57 5.91-7.12 16.02-1.21 22.6l21.4 23.82c5.9 6.57 16.02 7.12 22.6 1.21L277.42 81.63c6.05-5.33 15.12-5.33 21.17 0L527.91 283.9c6.57 5.9 16.69 5.36 22.6-1.21l21.4-23.82c5.9-6.57 5.36-16.69-1.22-22.59z\"],\n    \"hryvnia\": [384, 512, [], \"f6f2\", \"M368 240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-41.86c13.41-28.63 13.74-63.33-4.13-94.05C303.34 49.84 267.1 32 229.96 32h-78.82c-24.32 0-47.86 8.53-66.54 24.09L72.83 65.9c-10.18 8.49-11.56 23.62-3.07 33.8l20.49 24.59c8.49 10.19 23.62 11.56 33.81 3.07l11.73-9.78c4.32-3.6 9.77-5.57 15.39-5.57h83.62c11.69 0 21.2 9.52 21.2 21.2 0 5.91-2.48 11.58-6.81 15.58L219.7 176H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h134.37l-34.67 32H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h41.86c-13.41 28.63-13.74 63.33 4.13 94.05C80.66 462.15 116.9 480 154.04 480h78.82c24.32 0 47.86-8.53 66.54-24.09l11.77-9.81c10.18-8.49 11.56-23.62 3.07-33.8l-20.49-24.59c-8.49-10.19-23.62-11.56-33.81-3.07l-11.75 9.8a23.992 23.992 0 0 1-15.36 5.56H149.2c-11.69 0-21.2-9.52-21.2-21.2 0-5.91 2.48-11.58 6.81-15.58L164.3 336H368c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H233.63l34.67-32H368z\"],\n    \"i-cursor\": [256, 512, [], \"f246\", \"M256 52.048V12.065C256 5.496 250.726.148 244.158.066 211.621-.344 166.469.011 128 37.959 90.266.736 46.979-.114 11.913.114 5.318.157 0 5.519 0 12.114v39.645c0 6.687 5.458 12.078 12.145 11.998C38.111 63.447 96 67.243 96 112.182V224H60c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h36v112c0 44.932-56.075 48.031-83.95 47.959C5.404 447.942 0 453.306 0 459.952v39.983c0 6.569 5.274 11.917 11.842 11.999 32.537.409 77.689.054 116.158-37.894 37.734 37.223 81.021 38.073 116.087 37.845 6.595-.043 11.913-5.405 11.913-12V460.24c0-6.687-5.458-12.078-12.145-11.998C217.889 448.553 160 444.939 160 400V288h36c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-36V112.182c0-44.932 56.075-48.213 83.95-48.142 6.646.018 12.05-5.346 12.05-11.992z\"],\n    \"ice-cream\": [448, 512, [], \"f810\", \"M368 160h-.94a144 144 0 1 0-286.12 0H80a48 48 0 0 0 0 96h288a48 48 0 0 0 0-96zM195.38 493.69a31.52 31.52 0 0 0 57.24 0L352 288H96z\"],\n    \"icicles\": [512, 512, [], \"f7ad\", \"M511.4 37.9C515.1 18.2 500 0 480 0H32C10.6 0-4.8 20.7 1.4 41.2l87.1 273.4c2.5 7.2 12.7 7.2 15.1 0L140 190.5l44.2 187.3c1.9 8.3 13.7 8.3 15.6 0l46.5-196.9 34.1 133.4c2.3 7.6 13 7.6 15.3 0l45.8-172.5 66.7 363.8c1.7 8.6 14 8.6 15.7 0l87.5-467.7z\"],\n    \"icons\": [512, 512, [], \"f86d\", \"M116.65 219.35a15.68 15.68 0 0 0 22.65 0l96.75-99.83c28.15-29 26.5-77.1-4.91-103.88C203.75-7.7 163-3.5 137.86 22.44L128 32.58l-9.85-10.14C93.05-3.5 52.25-7.7 24.86 15.64c-31.41 26.78-33 74.85-5 103.88zm143.92 100.49h-48l-7.08-14.24a27.39 27.39 0 0 0-25.66-17.78h-71.71a27.39 27.39 0 0 0-25.66 17.78l-7 14.24h-48A27.45 27.45 0 0 0 0 347.3v137.25A27.44 27.44 0 0 0 27.43 512h233.14A27.45 27.45 0 0 0 288 484.55V347.3a27.45 27.45 0 0 0-27.43-27.46zM144 468a52 52 0 1 1 52-52 52 52 0 0 1-52 52zm355.4-115.9h-60.58l22.36-50.75c2.1-6.65-3.93-13.21-12.18-13.21h-75.59c-6.3 0-11.66 3.9-12.5 9.1l-16.8 106.93c-1 6.3 4.88 11.89 12.5 11.89h62.31l-24.2 83c-1.89 6.65 4.2 12.9 12.23 12.9a13.26 13.26 0 0 0 10.92-5.25l92.4-138.91c4.88-6.91-1.16-15.7-10.87-15.7zM478.08.33L329.51 23.17C314.87 25.42 304 38.92 304 54.83V161.6a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V99.66l112-17.22v47.18a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V32c0-19.48-16-34.42-33.92-31.67z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM144 32h96c8.8 0 16 7.2 16 16s-7.2 16-16 16h-96c-8.8 0-16-7.2-16-16s7.2-16 16-16zm48 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 416 80 407.4 80 396.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v16h576V80c0-26.5-21.5-48-48-48zM0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V128H0v304zm352-232c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zM176 192c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zM67.1 396.2C75.5 370.5 99.6 352 128 352h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.9-5.2 19.8-15.6 19.8H82.7c-10.4 0-18.8-10-15.6-19.8z\"],\n    \"id-card-alt\": [576, 512, [], \"f47f\", \"M528 64H384v96H192V64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM288 224c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm93.3 224H194.7c-10.4 0-18.8-10-15.6-19.8 8.3-25.6 32.4-44.2 60.9-44.2h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.8-5.2 19.8-15.6 19.8zM352 32c0-17.7-14.3-32-32-32h-64c-17.7 0-32 14.3-32 32v96h128V32z\"],\n    \"igloo\": [576, 512, [], \"f7ae\", \"M320 33.9c-10.5-1.2-21.2-1.9-32-1.9-99.8 0-187.8 50.8-239.4 128H320V33.9zM96 192H30.3C11.1 230.6 0 274 0 320h96V192zM352 39.4V160h175.4C487.2 99.9 424.8 55.9 352 39.4zM480 320h96c0-46-11.1-89.4-30.3-128H480v128zm-64 64v96h128c17.7 0 32-14.3 32-32v-96H411.5c2.6 10.3 4.5 20.9 4.5 32zm32-192H128v128h49.8c22.2-38.1 63-64 110.2-64s88 25.9 110.2 64H448V192zM0 448c0 17.7 14.3 32 32 32h128v-96c0-11.1 1.9-21.7 4.5-32H0v96zm288-160c-53 0-96 43-96 96v96h192v-96c0-53-43-96-96-96z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM112 120c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56zM64 384h384V272l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L208 320l-55.515-55.515c-4.686-4.686-12.284-4.686-16.971 0L64 336v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v208c0 44.112 35.888 80 80 80h336zm96-80V80c0-26.51-21.49-48-48-48H144c-26.51 0-48 21.49-48 48v256c0 26.51 21.49 48 48 48h384c26.51 0 48-21.49 48-48zM256 128c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-96 144l55.515-55.515c4.686-4.686 12.284-4.686 16.971 0L272 256l135.515-135.515c4.686-4.686 12.284-4.686 16.971 0L512 208v112H160v-48z\"],\n    \"inbox\": [576, 512, [], \"f01c\", \"M567.938 243.908L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L8.062 243.908A47.994 47.994 0 0 0 0 270.533V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V270.533a47.994 47.994 0 0 0-8.062-26.625zM162.252 128h251.497l85.333 128H376l-32 64H232l-32-64H76.918l85.334-128z\"],\n    \"indent\": [448, 512, [], \"f03c\", \"M27.31 363.3l96-96a16 16 0 0 0 0-22.62l-96-96C17.27 138.66 0 145.78 0 160v192c0 14.31 17.33 21.3 27.31 11.3zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"industry\": [512, 512, [], \"f275\", \"M475.115 163.781L336 252.309v-68.28c0-18.916-20.931-30.399-36.885-20.248L160 252.309V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h464c13.255 0 24-10.745 24-24V184.029c0-18.917-20.931-30.399-36.885-20.248z\"],\n    \"infinity\": [640, 512, [], \"f534\", \"M471.1 96C405 96 353.3 137.3 320 174.6 286.7 137.3 235 96 168.9 96 75.8 96 0 167.8 0 256s75.8 160 168.9 160c66.1 0 117.8-41.3 151.1-78.6 33.3 37.3 85 78.6 151.1 78.6 93.1 0 168.9-71.8 168.9-160S564.2 96 471.1 96zM168.9 320c-40.2 0-72.9-28.7-72.9-64s32.7-64 72.9-64c38.2 0 73.4 36.1 94 64-20.4 27.6-55.9 64-94 64zm302.2 0c-38.2 0-73.4-36.1-94-64 20.4-27.6 55.9-64 94-64 40.2 0 72.9 28.7 72.9 64s-32.7 64-72.9 64z\"],\n    \"info\": [192, 512, [], \"f129\", \"M20 424.229h20V279.771H20c-11.046 0-20-8.954-20-20V212c0-11.046 8.954-20 20-20h112c11.046 0 20 8.954 20 20v212.229h20c11.046 0 20 8.954 20 20V492c0 11.046-8.954 20-20 20H20c-11.046 0-20-8.954-20-20v-47.771c0-11.046 8.954-20 20-20zM96 0C56.235 0 24 32.235 24 72s32.235 72 72 72 72-32.235 72-72S135.764 0 96 0z\"],\n    \"info-circle\": [512, 512, [], \"f05a\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 110c23.196 0 42 18.804 42 42s-18.804 42-42 42-42-18.804-42-42 18.804-42 42-42zm56 254c0 6.627-5.373 12-12 12h-88c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h12v-64h-12c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h64c6.627 0 12 5.373 12 12v100h12c6.627 0 12 5.373 12 12v24z\"],\n    \"italic\": [320, 512, [], \"f033\", \"M320 48v32a16 16 0 0 1-16 16h-62.76l-80 320H208a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h62.76l80-320H112a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h192a16 16 0 0 1 16 16z\"],\n    \"jedi\": [544, 512, [], \"f669\", \"M479.99 352l58.88-58.87c3.29-16.8 5.13-34.12 5.13-51.86 0-5.81-.68-11.51-1.05-17.27H496l41.25-41.24c-14.5-64.79-52.43-123.05-107.91-162.27-2.77-1.96-5.97-2.99-9.25-2.99-5.37 0-10.41 2.71-13.49 7.24-3.05 4.49-3.64 9.99-1.61 15.09 6.55 16.46 9.86 33.73 9.86 51.31 0 45.12-21.03 86.57-57.69 113.73-4.02 2.98-6.46 7.5-6.7 12.4-.24 4.92 1.76 9.66 5.49 13.03 32.93 29.75 47.35 73.51 38.57 117.07-9.74 48.35-48.84 87.1-97.31 96.5l-2.5-65.34L321.88 397c2.98 2.06 7.39 1.69 10.02-.8a8.002 8.002 0 0 0 1.34-9.92l-20.11-33.73 42.07-8.72c3.7-.75 6.38-4.05 6.38-7.83 0-3.77-2.69-7.06-6.38-7.83l-42.07-8.73 20.13-33.77c1.92-3.23 1.34-7.31-1.38-9.91-2.7-2.55-6.97-2.89-10-.8l-30.39 20.67L279.96 7.7a7.964 7.964 0 0 0-8-7.7c-4.33 0-7.84 3.38-8 7.67l-11.52 287.97-30.39-20.66c-3.14-2.12-7.27-1.83-10 .78-2.72 2.59-3.3 6.67-1.36 9.94l20.11 33.73-42.07 8.73c-3.7.75-6.38 4.05-6.38 7.83s2.67 7.08 6.38 7.83l42.07 8.72-20.13 33.77c-1.92 3.23-1.34 7.33 1.39 9.94 2.59 2.45 7.03 2.75 10 .75l27.16-18.48-2.5 65.26c-56.94-11.64-99.89-61.89-99.89-121.92 0-35.08 14.62-67.6 41.17-91.58 3.72-3.36 5.72-8.11 5.48-13.01-.24-4.9-2.68-9.41-6.69-12.38-36.67-27.16-57.71-68.62-57.71-113.74 0-17.56 3.31-34.81 9.84-51.26 2.02-5.09 1.43-10.59-1.62-15.09-3.08-4.54-8.13-7.25-13.51-7.25-3.3 0-6.5 1.04-9.27 3-55.87 39.52-93.6 97.37-107.97 162.07L47.93 224H.72c-.63 9.92-.97 19.91-.5 29.99.62 13.43 2.54 26.53 5.11 39.41l58.6 58.6H24.02c41.25 90.23 131.13 154.94 235.1 159.71 4.3.2 8.59.29 12.85.29 110.34 0 205.35-65.83 247.98-160h-39.96z\"],\n    \"joint\": [640, 512, [], \"f595\", \"M444.34 181.1c22.38 15.68 35.66 41.16 35.66 68.59V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-43.24-21.01-83.41-56.34-108.06C463.85 125.02 448 99.34 448 70.31V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v66.4c0 43.69 24.56 81.63 60.34 106.7zM194.97 358.98C126.03 370.07 59.69 394.69 0 432c83.65 52.28 180.3 80 278.94 80h88.57L254.79 380.49c-14.74-17.2-37.45-25.11-59.82-21.51zM553.28 87.09c-5.67-3.8-9.28-9.96-9.28-16.78V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v62.31c0 22.02 10.17 43.41 28.64 55.39C550.79 153.04 576 199.54 576 249.69V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-65.44-32.41-126.19-86.72-162.6zM360.89 352.05c-34.4.06-86.81.15-88.21.17l117.8 137.43A63.987 63.987 0 0 0 439.07 512h88.45L409.57 374.4a63.955 63.955 0 0 0-48.68-22.35zM616 352H432l117.99 137.65A63.987 63.987 0 0 0 598.58 512H616c13.25 0 24-10.75 24-24V376c0-13.26-10.75-24-24-24z\"],\n    \"journal-whills\": [448, 512, [], \"f66a\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM133.08 144.39l21.26 21.26c1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34c3.12-3.12 3.12-8.19 0-11.31l-26.42-26.42c10-20.9 26.24-37.97 46.37-49.26C179.62 88.4 176 99.74 176 112c0 19.96 9.33 37.57 23.66 49.31C190.01 171.37 184 184.96 184 200c0 26.94 19.04 49.4 44.38 54.76l1.36-32.71-10.37 7.04c-.69.45-1.47.69-2.25.69-1 0-1.98-.38-2.75-1.09a4.006 4.006 0 0 1-.69-4.95l8.54-14.31-17.91-3.72c-1.86-.39-3.19-2.03-3.19-3.92s1.33-3.53 3.19-3.92l17.91-3.72-8.54-14.31c-.95-1.61-.67-3.67.69-4.95 1.36-1.3 3.44-1.44 5-.41l12.01 8.16L236 71.83c.09-2.14 1.86-3.83 4-3.83s3.91 1.69 4 3.83l4.68 112.29 14.2-9.65a4.067 4.067 0 0 1 5 .41 4.006 4.006 0 0 1 .69 4.95l-8.54 14.31 17.91 3.72c1.86.39 3.19 2.03 3.19 3.92s-1.33 3.53-3.19 3.92l-17.91 3.72 8.54 14.31c.95 1.61.67 3.67-.69 4.95-.77.72-1.77 1.09-2.75 1.09-.78 0-1.56-.23-2.25-.69l-12.68-8.62 1.43 34.28C276.96 249.4 296 226.94 296 200c0-15.04-6.01-28.63-15.66-38.69C294.67 149.57 304 131.96 304 112c0-12.26-3.62-23.6-9.6-33.33 20.13 11.28 36.37 28.36 46.37 49.26l-26.42 26.42c-3.12 3.12-3.12 8.19 0 11.31 1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34l21.26-21.26c2.97 10.08 5.07 20.55 5.07 31.6 0 .52-.14.99-.15 1.51l-37.11 32.47a7.975 7.975 0 0 0-.75 11.28 7.97 7.97 0 0 0 6.02 2.73c1.88 0 3.75-.66 5.27-1.98l23.59-20.64C337.32 250.96 293.09 288 240 288s-97.32-37.04-108.86-86.62l23.59 20.64A7.957 7.957 0 0 0 160 224c2.22 0 4.44-.92 6.02-2.73 2.92-3.33 2.58-8.38-.75-11.28l-37.11-32.47c-.01-.52-.15-.99-.15-1.51-.01-11.06 2.09-21.53 5.07-31.62zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"kaaba\": [576, 512, [], \"f66b\", \"M554.12 83.51L318.36 4.93a95.962 95.962 0 0 0-60.71 0L21.88 83.51A32.006 32.006 0 0 0 0 113.87v49.01l265.02-79.51c15.03-4.5 30.92-4.5 45.98 0l265 79.51v-49.01c0-13.77-8.81-26-21.88-30.36zm-279.9 30.52L0 196.3v228.38c0 15 10.42 27.98 25.06 31.24l242.12 53.8a95.937 95.937 0 0 0 41.65 0l242.12-53.8c14.64-3.25 25.06-16.24 25.06-31.24V196.29l-274.2-82.26c-9.04-2.72-18.59-2.72-27.59 0zM128 230.11c0 3.61-2.41 6.77-5.89 7.72l-80 21.82C37.02 261.03 32 257.2 32 251.93v-16.58c0-3.61 2.41-6.77 5.89-7.72l80-21.82c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm144-39.28c0 3.61-2.41 6.77-5.89 7.72l-96 26.18c-5.09 1.39-10.11-2.44-10.11-7.72v-16.58c0-3.61 2.41-6.77 5.89-7.72l96-26.18c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm176 22.7c0-5.28 5.02-9.11 10.11-7.72l80 21.82c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-80-21.82a7.997 7.997 0 0 1-5.89-7.72v-16.58zm-144-39.27c0-5.28 5.02-9.11 10.11-7.72l96 26.18c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-96-26.18a7.997 7.997 0 0 1-5.89-7.72v-16.58z\"],\n    \"key\": [512, 512, [], \"f084\", \"M512 176.001C512 273.203 433.202 352 336 352c-11.22 0-22.19-1.062-32.827-3.069l-24.012 27.014A23.999 23.999 0 0 1 261.223 384H224v40c0 13.255-10.745 24-24 24h-40v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-78.059c0-6.365 2.529-12.47 7.029-16.971l161.802-161.802C163.108 213.814 160 195.271 160 176 160 78.798 238.797.001 335.999 0 433.488-.001 512 78.511 512 176.001zM336 128c0 26.51 21.49 48 48 48s48-21.49 48-48-21.49-48-48-48-48 21.49-48 48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM128 180v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"khanda\": [512, 512, [], \"f66d\", \"M415.81 66c-6.37-3.5-14.37-2.33-19.36 3.02a15.974 15.974 0 0 0-1.91 19.52c16.49 26.16 25.2 56.39 25.2 87.41-.19 53.25-26.77 102.69-71.27 132.41l-76.63 53.35v-20.1l44.05-36.09c3.92-4.2 5-10.09 2.81-15.28L310.85 273c33.84-19.26 56.94-55.25 56.94-96.99 0-40.79-22.02-76.13-54.59-95.71l5.22-11.44c2.34-5.53.93-11.83-3.57-16.04L255.86 0l-58.99 52.81c-4.5 4.21-5.9 10.51-3.57 16.04l5.22 11.44c-32.57 19.58-54.59 54.93-54.59 95.72 0 41.75 23.09 77.73 56.94 96.99l-7.85 17.24c-2.19 5.18-1.1 11.07 2.81 15.28l44.05 36.09v19.9l-76.59-53.33C119.02 278.62 92.44 229.19 92.26 176c0-31.08 8.71-61.31 25.2-87.47 3.87-6.16 2.4-13.77-2.59-19.08-5-5.34-13.68-6.2-20.02-2.7C16.32 109.6-22.3 205.3 13.36 295.99c7.07 17.99 17.89 34.38 30.46 49.06l55.97 65.36c4.87 5.69 13.04 7.24 19.65 3.72l79.35-42.23L228 392.23l-47.08 32.78c-1.67-.37-3.23-1.01-5.01-1.01-13.25 0-23.99 10.74-23.99 24 0 13.25 10.74 24 23.99 24 12.1 0 21.69-9.11 23.33-20.76l40.63-28.28v29.95c-9.39 5.57-15.99 15.38-15.99 27.1 0 17.67 14.32 32 31.98 32s31.98-14.33 31.98-32c0-11.71-6.61-21.52-15.99-27.1v-30.15l40.91 28.48C314.41 462.89 324 472 336.09 472c13.25 0 23.99-10.75 23.99-24 0-13.26-10.74-24-23.99-24-1.78 0-3.34.64-5.01 1.01L284 392.23l29.21-20.34 79.35 42.23c6.61 3.52 14.78 1.97 19.65-3.71l52.51-61.31c18.87-22.02 34-47.5 41.25-75.59 21.62-83.66-16.45-167.27-90.16-207.51zm-95.99 110c0 22.3-11.49 41.92-28.83 53.38l-5.65-12.41c-8.75-24.52-8.75-51.04 0-75.56l7.83-17.18c16.07 11.65 26.65 30.45 26.65 51.77zm-127.93 0c0-21.32 10.58-40.12 26.66-51.76l7.83 17.18c8.75 24.52 8.75 51.03 0 75.56l-5.65 12.41c-17.34-11.46-28.84-31.09-28.84-53.39z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm136 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm24-156c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-39 219.9l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5zM304 396c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm65-168.1l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M501.1 402.5c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zm-177.6-4c-5.6-20.3-2.3-42 9-59.7 29.7-46.3 98.7-45.5 127.8 4.3 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-.3-.7-23.9-84.6-23.9-84.6zM168 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm120 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-5.7-12.3 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.8-3.7-4.6-16.6 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C274.6 368.7 288 383 288 396zm16-179c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S400 181 404 206.2c1.7 11.1-11.3 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 217z\"],\n    \"kiwi-bird\": [576, 512, [], \"f535\", \"M575.81 217.98C572.64 157.41 518.28 112 457.63 112h-9.37c-52.82 0-104.25-16.25-147.74-46.24-41.99-28.96-96.04-41.62-153.21-28.7C129.3 41.12-.08 78.24 0 224c.04 70.95 38.68 132.8 95.99 166.01V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-54.26c15.36 3.96 31.4 6.26 48 6.26 5.44 0 10.68-.73 16-1.18V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-59.43c14.24-5.06 27.88-11.39 40.34-19.51C342.07 355.25 393.86 336 448.46 336c25.48 0 16.01-.31 23.05-.78l74.41 136.44c2.86 5.23 8.3 8.34 14.05 8.34 1.31 0 2.64-.16 3.95-.5 7.09-1.8 12.05-8.19 12.05-15.5 0 0 .14-240.24-.16-246.02zM463.97 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm80 153.25l-39.86-73.08c15.12-5.83 28.73-14.6 39.86-25.98v99.06z\"],\n    \"landmark\": [512, 512, [], \"f66f\", \"M501.62 92.11L267.24 2.04a31.958 31.958 0 0 0-22.47 0L10.38 92.11A16.001 16.001 0 0 0 0 107.09V144c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-36.91c0-6.67-4.14-12.64-10.38-14.98zM64 192v160H48c-8.84 0-16 7.16-16 16v48h448v-48c0-8.84-7.16-16-16-16h-16V192h-64v160h-96V192h-64v160h-96V192H64zm432 256H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"language\": [640, 512, [], \"f1ab\", \"M152.1 236.2c-3.5-12.1-7.8-33.2-7.8-33.2h-.5s-4.3 21.1-7.8 33.2l-11.1 37.5H163zM616 96H336v320h280c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm-24 120c0 6.6-5.4 12-12 12h-11.4c-6.9 23.6-21.7 47.4-42.7 69.9 8.4 6.4 17.1 12.5 26.1 18 5.5 3.4 7.3 10.5 4.1 16.2l-7.9 13.9c-3.4 5.9-10.9 7.8-16.7 4.3-12.6-7.8-24.5-16.1-35.4-24.9-10.9 8.7-22.7 17.1-35.4 24.9-5.8 3.5-13.3 1.6-16.7-4.3l-7.9-13.9c-3.2-5.6-1.4-12.8 4.2-16.2 9.3-5.7 18-11.7 26.1-18-7.9-8.4-14.9-17-21-25.7-4-5.7-2.2-13.6 3.7-17.1l6.5-3.9 7.3-4.3c5.4-3.2 12.4-1.7 16 3.4 5 7 10.8 14 17.4 20.9 13.5-14.2 23.8-28.9 30-43.2H412c-6.6 0-12-5.4-12-12v-16c0-6.6 5.4-12 12-12h64v-16c0-6.6 5.4-12 12-12h16c6.6 0 12 5.4 12 12v16h64c6.6 0 12 5.4 12 12zM0 120v272c0 13.3 10.7 24 24 24h280V96H24c-13.3 0-24 10.7-24 24zm58.9 216.1L116.4 167c1.7-4.9 6.2-8.1 11.4-8.1h32.5c5.1 0 9.7 3.3 11.4 8.1l57.5 169.1c2.6 7.8-3.1 15.9-11.4 15.9h-22.9a12 12 0 0 1-11.5-8.6l-9.4-31.9h-60.2l-9.1 31.8c-1.5 5.1-6.2 8.7-11.5 8.7H70.3c-8.2 0-14-8.1-11.4-15.9z\"],\n    \"laptop\": [640, 512, [], \"f109\", \"M624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-code\": [640, 512, [], \"f5fc\", \"M255.03 261.65c6.25 6.25 16.38 6.25 22.63 0l11.31-11.31c6.25-6.25 6.25-16.38 0-22.63L253.25 192l35.71-35.72c6.25-6.25 6.25-16.38 0-22.63l-11.31-11.31c-6.25-6.25-16.38-6.25-22.63 0l-58.34 58.34c-6.25 6.25-6.25 16.38 0 22.63l58.35 58.34zm96.01-11.3l11.31 11.31c6.25 6.25 16.38 6.25 22.63 0l58.34-58.34c6.25-6.25 6.25-16.38 0-22.63l-58.34-58.34c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63L386.75 192l-35.71 35.72c-6.25 6.25-6.25 16.38 0 22.63zM624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-medical\": [640, 512, [], \"f812\", \"M232 224h56v56a8 8 0 0 0 8 8h48a8 8 0 0 0 8-8v-56h56a8 8 0 0 0 8-8v-48a8 8 0 0 0-8-8h-56v-56a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v56h-56a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8zM576 48a48.14 48.14 0 0 0-48-48H112a48.14 48.14 0 0 0-48 48v336h512zm-64 272H128V64h384zm112 96H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33-17.47-32.77-32H16a16 16 0 0 0-16 16v16a64.19 64.19 0 0 0 64 64h512a64.19 64.19 0 0 0 64-64v-16a16 16 0 0 0-16-16z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 152c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm88 272h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18-8.9 71-69.5 126-142.9 126z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm24 199.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.8 4.1-15.1-4.5zm-160 0c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 161.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 180l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm20.1 198.1c4-25.2 34.2-42.1 59.9-42.1s55.9 16.9 59.9 42.1c1.7 11.1-11.4 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 217c-8.4 7.4-21.6.3-19.9-10.9zM168 160c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm230.9 146C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"layer-group\": [512, 512, [], \"f5fd\", \"M12.41 148.02l232.94 105.67c6.8 3.09 14.49 3.09 21.29 0l232.94-105.67c16.55-7.51 16.55-32.52 0-40.03L266.65 2.31a25.607 25.607 0 0 0-21.29 0L12.41 107.98c-16.55 7.51-16.55 32.53 0 40.04zm487.18 88.28l-58.09-26.33-161.64 73.27c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.51 209.97l-58.1 26.33c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 276.3c16.55-7.5 16.55-32.5 0-40zm0 127.8l-57.87-26.23-161.86 73.37c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.29 337.87 12.41 364.1c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 404.1c16.55-7.5 16.55-32.5 0-40z\"],\n    \"leaf\": [576, 512, [], \"f06c\", \"M546.2 9.7c-5.6-12.5-21.6-13-28.3-1.2C486.9 62.4 431.4 96 368 96h-80C182 96 96 182 96 288c0 7 .8 13.7 1.5 20.5C161.3 262.8 253.4 224 384 224c8.8 0 16 7.2 16 16s-7.2 16-16 16C132.6 256 26 410.1 2.4 468c-6.6 16.3 1.2 34.9 17.5 41.6 16.4 6.8 35-1.1 41.8-17.3 1.5-3.6 20.9-47.9 71.9-90.6 32.4 43.9 94 85.8 174.9 77.2C465.5 467.5 576 326.7 576 154.3c0-50.2-10.8-102.2-29.8-144.6z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M489.038 22.963C465.944-.13 434.648-5.93 413.947 6.129c-58.906 34.312-181.25-53.077-321.073 86.746S40.441 355.041 6.129 413.945c-12.059 20.702-6.26 51.999 16.833 75.093 23.095 23.095 54.392 28.891 75.095 16.832 58.901-34.31 181.246 53.079 321.068-86.743S471.56 156.96 505.871 98.056c12.059-20.702 6.261-51.999-16.833-75.093zM243.881 95.522c-58.189 14.547-133.808 90.155-148.358 148.358-1.817 7.27-8.342 12.124-15.511 12.124-1.284 0-2.59-.156-3.893-.481-8.572-2.144-13.784-10.83-11.642-19.403C81.901 166.427 166.316 81.93 236.119 64.478c8.575-2.143 17.261 3.069 19.403 11.642s-3.069 17.259-11.641 19.402z\"],\n    \"less-than\": [384, 512, [], \"f536\", \"M365.46 357.74L147.04 255.89l218.47-101.88c16.02-7.47 22.95-26.51 15.48-42.53l-13.52-29C360 66.46 340.96 59.53 324.94 67L18.48 209.91a32.014 32.014 0 0 0-18.48 29v34.24c0 12.44 7.21 23.75 18.48 29l306.31 142.83c16.06 7.49 35.15.54 42.64-15.52l13.56-29.08c7.49-16.06.54-35.15-15.53-42.64z\"],\n    \"less-than-equal\": [448, 512, [], \"f537\", \"M54.98 214.2l301.41 119.87c18.39 6.03 38.71-2.54 45.38-19.15l12.09-30.08c6.68-16.61-2.82-34.97-21.21-41l-175.44-68.05 175.56-68.09c18.29-6 27.74-24.27 21.1-40.79l-12.03-29.92c-6.64-16.53-26.86-25.06-45.15-19.06L54.98 137.89C41.21 142.41 32 154.5 32 168.07v15.96c0 13.56 9.21 25.65 22.98 30.17zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"level-down-alt\": [320, 512, [], \"f3be\", \"M313.553 392.331L209.587 504.334c-9.485 10.214-25.676 10.229-35.174 0L70.438 392.331C56.232 377.031 67.062 352 88.025 352H152V80H68.024a11.996 11.996 0 0 1-8.485-3.515l-56-56C-4.021 12.926 1.333 0 12.024 0H208c13.255 0 24 10.745 24 24v328h63.966c20.878 0 31.851 24.969 17.587 40.331z\"],\n    \"level-up-alt\": [320, 512, [], \"f3bf\", \"M313.553 119.669L209.587 7.666c-9.485-10.214-25.676-10.229-35.174 0L70.438 119.669C56.232 134.969 67.062 160 88.025 160H152v272H68.024a11.996 11.996 0 0 0-8.485 3.515l-56 56C-4.021 499.074 1.333 512 12.024 512H208c13.255 0 24-10.745 24-24V160h63.966c20.878 0 31.851-24.969 17.587-40.331z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm173.696 119.559l-63.399 63.399c-10.987-18.559-26.67-34.252-45.255-45.255l63.399-63.399a218.396 218.396 0 0 1 45.255 45.255zM256 352c-53.019 0-96-42.981-96-96s42.981-96 96-96 96 42.981 96 96-42.981 96-96 96zM127.559 82.304l63.399 63.399c-18.559 10.987-34.252 26.67-45.255 45.255l-63.399-63.399a218.372 218.372 0 0 1 45.255-45.255zM82.304 384.441l63.399-63.399c10.987 18.559 26.67 34.252 45.255 45.255l-63.399 63.399a218.396 218.396 0 0 1-45.255-45.255zm302.137 45.255l-63.399-63.399c18.559-10.987 34.252-26.67 45.255-45.255l63.399 63.399a218.403 218.403 0 0 1-45.255 45.255z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M96.06 454.35c.01 6.29 1.87 12.45 5.36 17.69l17.09 25.69a31.99 31.99 0 0 0 26.64 14.28h61.71a31.99 31.99 0 0 0 26.64-14.28l17.09-25.69a31.989 31.989 0 0 0 5.36-17.69l.04-38.35H96.01l.05 38.35zM0 176c0 44.37 16.45 84.85 43.56 115.78 16.52 18.85 42.36 58.23 52.21 91.45.04.26.07.52.11.78h160.24c.04-.26.07-.51.11-.78 9.85-33.22 35.69-72.6 52.21-91.45C335.55 260.85 352 220.37 352 176 352 78.61 272.91-.3 175.45 0 73.44.31 0 82.97 0 176zm176-80c-44.11 0-80 35.89-80 80 0 8.84-7.16 16-16 16s-16-7.16-16-16c0-61.76 50.24-112 112-112 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"link\": [512, 512, [], \"f0c1\", \"M326.612 185.391c59.747 59.809 58.927 155.698.36 214.59-.11.12-.24.25-.36.37l-67.2 67.2c-59.27 59.27-155.699 59.262-214.96 0-59.27-59.26-59.27-155.7 0-214.96l37.106-37.106c9.84-9.84 26.786-3.3 27.294 10.606.648 17.722 3.826 35.527 9.69 52.721 1.986 5.822.567 12.262-3.783 16.612l-13.087 13.087c-28.026 28.026-28.905 73.66-1.155 101.96 28.024 28.579 74.086 28.749 102.325.51l67.2-67.19c28.191-28.191 28.073-73.757 0-101.83-3.701-3.694-7.429-6.564-10.341-8.569a16.037 16.037 0 0 1-6.947-12.606c-.396-10.567 3.348-21.456 11.698-29.806l21.054-21.055c5.521-5.521 14.182-6.199 20.584-1.731a152.482 152.482 0 0 1 20.522 17.197zM467.547 44.449c-59.261-59.262-155.69-59.27-214.96 0l-67.2 67.2c-.12.12-.25.25-.36.37-58.566 58.892-59.387 154.781.36 214.59a152.454 152.454 0 0 0 20.521 17.196c6.402 4.468 15.064 3.789 20.584-1.731l21.054-21.055c8.35-8.35 12.094-19.239 11.698-29.806a16.037 16.037 0 0 0-6.947-12.606c-2.912-2.005-6.64-4.875-10.341-8.569-28.073-28.073-28.191-73.639 0-101.83l67.2-67.19c28.239-28.239 74.3-28.069 102.325.51 27.75 28.3 26.872 73.934-1.155 101.96l-13.087 13.087c-4.35 4.35-5.769 10.79-3.783 16.612 5.864 17.194 9.042 34.999 9.69 52.721.509 13.906 17.454 20.446 27.294 10.606l37.106-37.106c59.271-59.259 59.271-155.699.001-214.959z\"],\n    \"lira-sign\": [384, 512, [], \"f195\", \"M371.994 256h-48.019C317.64 256 312 260.912 312 267.246 312 368 230.179 416 144 416V256.781l134.603-29.912A12 12 0 0 0 288 215.155v-40.976c0-7.677-7.109-13.38-14.603-11.714L144 191.219V160.78l134.603-29.912A12 12 0 0 0 288 119.154V78.179c0-7.677-7.109-13.38-14.603-11.714L144 95.219V44c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v68.997L9.397 125.131A12 12 0 0 0 0 136.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 178.558v30.439L9.397 221.131A12 12 0 0 0 0 232.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 274.558V468c0 6.627 5.373 12 12 12h79.583c134.091 0 223.255-77.834 228.408-211.592.261-6.782-5.211-12.408-11.997-12.408z\"],\n    \"list\": [512, 512, [], \"f03a\", \"M80 368H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm0-320H16A16 16 0 0 0 0 64v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16V64a16 16 0 0 0-16-16zm0 160H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm416 176H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM128 120c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm288-136v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12z\"],\n    \"list-ol\": [512, 512, [], \"f0cb\", \"M61.77 401l17.5-20.15a19.92 19.92 0 0 0 5.07-14.19v-3.31C84.34 356 80.5 352 73 352H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h22.83a157.41 157.41 0 0 0-11 12.31l-5.61 7c-4 5.07-5.25 10.13-2.8 14.88l1.05 1.93c3 5.76 6.29 7.88 12.25 7.88h4.73c10.33 0 15.94 2.44 15.94 9.09 0 4.72-4.2 8.22-14.36 8.22a41.54 41.54 0 0 1-15.47-3.12c-6.49-3.88-11.74-3.5-15.6 3.12l-5.59 9.31c-3.72 6.13-3.19 11.72 2.63 15.94 7.71 4.69 20.38 9.44 37 9.44 34.16 0 48.5-22.75 48.5-44.12-.03-14.38-9.12-29.76-28.73-34.88zM496 224H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h64a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H64V40a8 8 0 0 0-8-8H32a8 8 0 0 0-7.14 4.42l-8 16A8 8 0 0 0 24 64h8v64H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8zm-3.91 160H80a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H41.32c3.29-10.29 48.34-18.68 48.34-56.44 0-29.06-25-39.56-44.47-39.56-21.36 0-33.8 10-40.46 18.75-4.37 5.59-3 10.84 2.8 15.37l8.58 6.88c5.61 4.56 11 2.47 16.12-2.44a13.44 13.44 0 0 1 9.46-3.84c3.33 0 9.28 1.56 9.28 8.75C51 248.19 0 257.31 0 304.59v4C0 316 5.08 320 12.09 320z\"],\n    \"list-ul\": [512, 512, [], \"f0ca\", \"M48 48a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm448 16H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"location-arrow\": [512, 512, [], \"f124\", \"M444.52 3.52L28.74 195.42c-47.97 22.39-31.98 92.75 19.19 92.75h175.91v175.91c0 51.17 70.36 67.17 92.75 19.19l191.9-415.78c15.99-38.39-25.59-79.97-63.97-63.97z\"],\n    \"lock\": [448, 512, [], \"f023\", \"M400 224h-24v-72C376 68.2 307.8 0 224 0S72 68.2 72 152v72H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48zm-104 0H152v-72c0-39.7 32.3-72 72-72s72 32.3 72 72v72z\"],\n    \"lock-open\": [576, 512, [], \"f3c1\", \"M423.5 0C339.5.3 272 69.5 272 153.5V224H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48h-48v-71.1c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v80c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-80C576 68 507.5-.3 423.5 0z\"],\n    \"long-arrow-alt-down\": [256, 512, [], \"f309\", \"M168 345.941V44c0-6.627-5.373-12-12-12h-56c-6.627 0-12 5.373-12 12v301.941H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.569 9.373 33.941 0l86.059-86.059c15.119-15.119 4.411-40.971-16.971-40.971H168z\"],\n    \"long-arrow-alt-left\": [448, 512, [], \"f30a\", \"M134.059 296H436c6.627 0 12-5.373 12-12v-56c0-6.627-5.373-12-12-12H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.569 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296z\"],\n    \"long-arrow-alt-right\": [448, 512, [], \"f30b\", \"M313.941 216H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h301.941v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.569 0-33.941l-86.059-86.059c-15.119-15.119-40.971-4.411-40.971 16.971V216z\"],\n    \"long-arrow-alt-up\": [256, 512, [], \"f30c\", \"M88 166.059V468c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12V166.059h46.059c21.382 0 32.09-25.851 16.971-40.971l-86.059-86.059c-9.373-9.373-24.569-9.373-33.941 0l-86.059 86.059c-15.119 15.119-4.411 40.971 16.971 40.971H88z\"],\n    \"low-vision\": [576, 512, [], \"f2a8\", \"M569.344 231.631C512.96 135.949 407.81 72 288 72c-28.468 0-56.102 3.619-82.451 10.409L152.778 10.24c-7.601-10.858-22.564-13.5-33.423-5.9l-13.114 9.178c-10.86 7.601-13.502 22.566-5.9 33.426l43.131 58.395C89.449 131.73 40.228 174.683 6.682 231.581c-.01.017-.023.033-.034.05-8.765 14.875-8.964 33.528 0 48.739 38.5 65.332 99.742 115.862 172.859 141.349L55.316 244.302A272.194 272.194 0 0 1 83.61 208.39l119.4 170.58h.01l40.63 58.04a330.055 330.055 0 0 0 78.94 1.17l-189.98-271.4a277.628 277.628 0 0 1 38.777-21.563l251.836 356.544c7.601 10.858 22.564 13.499 33.423 5.9l13.114-9.178c10.86-7.601 13.502-22.567 5.9-33.426l-43.12-58.377-.007-.009c57.161-27.978 104.835-72.04 136.81-126.301a47.938 47.938 0 0 0 .001-48.739zM390.026 345.94l-19.066-27.23c24.682-32.567 27.711-76.353 8.8-111.68v.03c0 23.65-19.17 42.82-42.82 42.82-23.828 0-42.82-19.349-42.82-42.82 0-23.65 19.17-42.82 42.82-42.82h.03c-24.75-13.249-53.522-15.643-79.51-7.68l-19.068-27.237C253.758 123.306 270.488 120 288 120c75.162 0 136 60.826 136 136 0 34.504-12.833 65.975-33.974 89.94z\"],\n    \"luggage-cart\": [640, 512, [], \"f59d\", \"M224 320h32V96h-32c-17.67 0-32 14.33-32 32v160c0 17.67 14.33 32 32 32zm352-32V128c0-17.67-14.33-32-32-32h-32v224h32c17.67 0 32-14.33 32-32zm48 96H128V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h48v368c0 8.84 7.16 16 16 16h82.94c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16h197.88c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM480 96V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v272h192V96zm-48 0h-96V48h96v48z\"],\n    \"magic\": [512, 512, [], \"f0d0\", \"M224 96l16-32 32-16-32-16-16-32-16 32-32 16 32 16 16 32zM80 160l26.66-53.33L160 80l-53.34-26.67L80 0 53.34 53.33 0 80l53.34 26.67L80 160zm352 128l-26.66 53.33L352 368l53.34 26.67L432 448l26.66-53.33L512 368l-53.34-26.67L432 288zm70.62-193.77L417.77 9.38C411.53 3.12 403.34 0 395.15 0c-8.19 0-16.38 3.12-22.63 9.38L9.38 372.52c-12.5 12.5-12.5 32.76 0 45.25l84.85 84.85c6.25 6.25 14.44 9.37 22.62 9.37 8.19 0 16.38-3.12 22.63-9.37l363.14-363.15c12.5-12.48 12.5-32.75 0-45.24zM359.45 203.46l-50.91-50.91 86.6-86.6 50.91 50.91-86.6 86.6z\"],\n    \"magnet\": [512, 512, [], \"f076\", \"M164.07 148.1H12a12 12 0 0 1-12-12v-80a36 36 0 0 1 36-36h104a36 36 0 0 1 36 36v80a11.89 11.89 0 0 1-11.93 12zm347.93-12V56a36 36 0 0 0-36-36H372a36 36 0 0 0-36 36v80a12 12 0 0 0 12 12h152a11.89 11.89 0 0 0 12-11.9zm-164 44a12 12 0 0 0-12 12v52c0 128.1-160 127.9-160 0v-52a12 12 0 0 0-12-12H12.1a12 12 0 0 0-12 12.1c.1 21.4.6 40.3 0 53.3 0 150.6 136.17 246.6 256.75 246.6s255-96 255-246.7c-.6-12.8-.2-33 0-53.2a12 12 0 0 0-12-12.1z\"],\n    \"mail-bulk\": [576, 512, [], \"f674\", \"M160 448c-25.6 0-51.2-22.4-64-32-64-44.8-83.2-60.8-96-70.4V480c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V345.6c-12.8 9.6-32 25.6-96 70.4-12.8 9.6-38.4 32-64 32zm128-192H32c-17.67 0-32 14.33-32 32v16c25.6 19.2 22.4 19.2 115.2 86.4 9.6 6.4 28.8 25.6 44.8 25.6s35.2-19.2 44.8-22.4c92.8-67.2 89.6-67.2 115.2-86.4V288c0-17.67-14.33-32-32-32zm256-96H224c-17.67 0-32 14.33-32 32v32h96c33.21 0 60.59 25.42 63.71 57.82l.29-.22V416h192c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zm-32 128h-64v-64h64v64zm-352-96c0-35.29 28.71-64 64-64h224V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v192h96v-32z\"],\n    \"male\": [192, 512, [], \"f183\", \"M96 0c35.346 0 64 28.654 64 64s-28.654 64-64 64-64-28.654-64-64S60.654 0 96 0m48 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H48c-26.51 0-48 21.49-48 48v136c0 13.255 10.745 24 24 24h16v136c0 13.255 10.745 24 24 24h64c13.255 0 24-10.745 24-24V352h16c13.255 0 24-10.745 24-24V192c0-26.51-21.49-48-48-48z\"],\n    \"map\": [576, 512, [], \"f279\", \"M0 117.66v346.32c0 11.32 11.43 19.06 21.94 14.86L160 416V32L20.12 87.95A32.006 32.006 0 0 0 0 117.66zM192 416l192 64V96L192 32v384zM554.06 33.16L416 96v384l139.88-55.95A31.996 31.996 0 0 0 576 394.34V48.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked\": [576, 512, [], \"f59f\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked-alt\": [576, 512, [], \"f5a0\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zm0 168c-23.2 0-42-18.8-42-42s18.8-42 42-42 42 18.8 42 42-18.8 42-42 42zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marker\": [384, 512, [], \"f041\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0z\"],\n    \"map-marker-alt\": [384, 512, [], \"f3c5\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0zM192 272c44.183 0 80-35.817 80-80s-35.817-80-80-80-80 35.817-80 80 35.817 80 80 80z\"],\n    \"map-pin\": [288, 512, [], \"f276\", \"M112 316.94v156.69l22.02 33.02c4.75 7.12 15.22 7.12 19.97 0L176 473.63V316.94c-10.39 1.92-21.06 3.06-32 3.06s-21.61-1.14-32-3.06zM144 0C64.47 0 0 64.47 0 144s64.47 144 144 144 144-64.47 144-144S223.53 0 144 0zm0 76c-37.5 0-68 30.5-68 68 0 6.62-5.38 12-12 12s-12-5.38-12-12c0-50.73 41.28-92 92-92 6.62 0 12 5.38 12 12s-5.38 12-12 12z\"],\n    \"map-signs\": [512, 512, [], \"f277\", \"M507.31 84.69L464 41.37c-6-6-14.14-9.37-22.63-9.37H288V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v16H56c-13.25 0-24 10.75-24 24v80c0 13.25 10.75 24 24 24h385.37c8.49 0 16.62-3.37 22.63-9.37l43.31-43.31c6.25-6.26 6.25-16.38 0-22.63zM224 496c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V384h-64v112zm232-272H288v-32h-64v32H70.63c-8.49 0-16.62 3.37-22.63 9.37L4.69 276.69c-6.25 6.25-6.25 16.38 0 22.63L48 342.63c6 6 14.14 9.37 22.63 9.37H456c13.25 0 24-10.75 24-24v-80c0-13.25-10.75-24-24-24z\"],\n    \"marker\": [512, 512, [], \"f5a1\", \"M93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l75.4-75.4-128.02-128.02-75.4 75.4zM485.49 26.51c-35.35-35.35-92.67-35.35-128.02 0l-21.76 21.76-36.56-36.55c-15.62-15.62-40.95-15.62-56.56 0L138.47 115.84c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0l87.15-87.15 19.59 19.59L191.98 192 320 320.02l165.49-165.49c35.35-35.35 35.35-92.66 0-128.02z\"],\n    \"mars\": [384, 512, [], \"f222\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c0-6.6-5.4-12-12-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-double\": [512, 512, [], \"f227\", \"M340 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C198.5 72.1 172.2 64 144 64 64.5 64 0 128.5 0 208s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.5 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 288c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80zm356-128.1h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7c-18.2-11.4-39-18.9-61.5-21.3-2.1 21.8-8.2 43.3-18.4 63.3 1.1 0 2.2-.1 3.2-.1 44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80c0-1.1 0-2.2.1-3.2-20 10.2-41.5 16.4-63.3 18.4C168.4 455.6 229.6 512 304 512c79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12v-79c0-6.7-5.4-12.1-12-12.1z\"],\n    \"mars-stroke\": [384, 512, [], \"f229\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-17.5 17.5-14.1-14.1c-4.7-4.7-12.3-4.7-17 0L224.5 133c-4.7 4.7-4.7 12.3 0 17l14.1 14.1-18 18c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l18-18 14.1 14.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L329.2 164l17.5-17.5 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c-.1-6.6-5.5-12-12.1-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-stroke-h\": [480, 512, [], \"f22b\", \"M476.2 247.5l-55.9-55.9c-7.6-7.6-20.5-2.2-20.5 8.5V224H376v-20c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v20h-27.6c-5.8-25.6-18.7-49.9-38.6-69.8C189.6 98 98.4 98 42.2 154.2c-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 19.9-19.9 32.8-44.2 38.6-69.8H312v20c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-20h23.9v23.9c0 10.7 12.9 16 20.5 8.5l55.9-55.9c4.6-4.7 4.6-12.3-.1-17zm-275.6 65.1c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mars-stroke-v\": [288, 512, [], \"f22a\", \"M245.8 234.2c-19.9-19.9-44.2-32.8-69.8-38.6v-25.4h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V81.4h23.9c10.7 0 16-12.9 8.5-20.5L152.5 5.1c-4.7-4.7-12.3-4.7-17 0L79.6 61c-7.6 7.6-2.2 20.5 8.5 20.5H112v24.7H92c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h20v25.4c-25.6 5.8-49.9 18.7-69.8 38.6-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 56.3-56.2 56.3-147.4 0-203.6zm-45.2 158.4c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mask\": [640, 512, [], \"f6fa\", \"M320.67 64c-442.6 0-357.57 384-158.46 384 39.9 0 77.47-20.69 101.42-55.86l25.73-37.79c15.66-22.99 46.97-22.99 62.63 0l25.73 37.79C401.66 427.31 439.23 448 479.13 448c189.86 0 290.63-384-158.46-384zM184 308.36c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05zm272 0c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05z\"],\n    \"medal\": [512, 512, [], \"f5a2\", \"M223.75 130.75L154.62 15.54A31.997 31.997 0 0 0 127.18 0H16.03C3.08 0-4.5 14.57 2.92 25.18l111.27 158.96c29.72-27.77 67.52-46.83 109.56-53.39zM495.97 0H384.82c-11.24 0-21.66 5.9-27.44 15.54l-69.13 115.21c42.04 6.56 79.84 25.62 109.56 53.38L509.08 25.18C516.5 14.57 508.92 0 495.97 0zM256 160c-97.2 0-176 78.8-176 176s78.8 176 176 176 176-78.8 176-176-78.8-176-176-176zm92.52 157.26l-37.93 36.96 8.97 52.22c1.6 9.36-8.26 16.51-16.65 12.09L256 393.88l-46.9 24.65c-8.4 4.45-18.25-2.74-16.65-12.09l8.97-52.22-37.93-36.96c-6.82-6.64-3.05-18.23 6.35-19.59l52.43-7.64 23.43-47.52c2.11-4.28 6.19-6.39 10.28-6.39 4.11 0 8.22 2.14 10.33 6.39l23.43 47.52 52.43 7.64c9.4 1.36 13.17 12.95 6.35 19.59z\"],\n    \"medkit\": [512, 512, [], \"f0fa\", \"M96 480h320V128h-32V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v48H96v352zm96-384h128v32H192V96zm320 80v256c0 26.51-21.49 48-48 48h-16V128h16c26.51 0 48 21.49 48 48zM64 480H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v352zm288-208v32c0 8.837-7.163 16-16 16h-48v48c0 8.837-7.163 16-16 16h-32c-8.837 0-16-7.163-16-16v-48h-48c-8.837 0-16-7.163-16-16v-32c0-8.837 7.163-16 16-16h48v-48c0-8.837 7.163-16 16-16h32c8.837 0 16 7.163 16 16v48h48c8.837 0 16 7.163 16 16z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm176 192H152c-21.2 0-21.2-32 0-32h192c21.2 0 21.2 32 0 32zm-16-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 224c0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64s-64-28.7-64-64zm224 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-112c-35.3 0-64-28.7-64-64 0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64z\"],\n    \"memory\": [640, 512, [], \"f538\", \"M640 130.94V96c0-17.67-14.33-32-32-32H32C14.33 64 0 78.33 0 96v34.94c18.6 6.61 32 24.19 32 45.06s-13.4 38.45-32 45.06V320h640v-98.94c-18.6-6.61-32-24.19-32-45.06s13.4-38.45 32-45.06zM224 256h-64V128h64v128zm128 0h-64V128h64v128zm128 0h-64V128h64v128zM0 448h64v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h64v-96H0v96z\"],\n    \"menorah\": [640, 512, [], \"f676\", \"M144 128h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm192 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm80-32c17.67 0 32-14.33 32-32S608 0 608 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S512 0 512 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S416 0 416 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S320 0 320 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S224 0 224 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S128 0 128 0 96 46.33 96 64s14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S32 0 32 0 0 46.33 0 64s14.33 32 32 32zm544 192c0 17.67-14.33 32-32 32H352V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v176H96c-17.67 0-32-14.33-32-32V144c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v144c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v144z\"],\n    \"mercury\": [288, 512, [], \"f223\", \"M288 208c0-44.2-19.9-83.7-51.2-110.1 2.5-1.8 4.9-3.8 7.2-5.8 24.7-21.2 39.8-48.8 43.2-78.8.9-7.1-4.7-13.3-11.9-13.3h-40.5C229 0 224.1 4.1 223 9.8c-2.4 12.5-9.6 24.3-20.7 33.8C187 56.8 166.3 64 144 64s-43-7.2-58.4-20.4C74.5 34.1 67.4 22.3 64.9 9.8 63.8 4.1 58.9 0 53.2 0H12.7C5.5 0-.1 6.2.8 13.3 4.2 43.4 19.2 71 44 92.2c2.3 2 4.7 3.9 7.2 5.8C19.9 124.3 0 163.8 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"meteor\": [512, 512, [], \"f753\", \"M491.2.7C452.5 12.3 379.4 35 303.5 62c-2.1-7-4-13.5-5.6-18.6-3-9.7-13.9-14.2-22.9-9.5C232.6 56 122.2 116.5 60.6 176.4c-1.1 1-2.5 2-3.5 3C19 217.4 0 267.3 0 317.2 0 367 19 416.9 57 455c38 38 87.9 57.1 137.8 57 49.9 0 99.8-19 137.9-57.1 1-1 2-2.4 3-3.5 59.8-61.6 120.4-172.1 142.5-214.4 4.7-9 .2-19.9-9.5-22.9-5.2-1.6-11.6-3.5-18.6-5.6 27-76 49.7-149 61.3-187.7C515 8.4 503.6-3 491.2.7zM192 448c-70.7 0-128-57.3-128-128s57.3-128 128-128 128 57.3 128 128-57.3 128-128 128zm-32-192c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm48 96c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16z\"],\n    \"microchip\": [512, 512, [], \"f2db\", \"M416 48v416c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h224c26.51 0 48 21.49 48 48zm96 58v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42V88h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zM30 376h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6z\"],\n    \"microphone\": [352, 512, [], \"f130\", \"M176 352c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96zm160-160h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16z\"],\n    \"microphone-alt\": [352, 512, [], \"f3c9\", \"M336 192h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16zM176 352c53.02 0 96-42.98 96-96h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96z\"],\n    \"microphone-alt-slash\": [640, 512, [], \"f539\", \"M633.82 458.1L476.26 336.33C488.74 312.21 496 284.98 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67h-43.67l-41.4-32H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.78c11.71-1.62 23.1-4.28 33.96-8.08l-50.4-38.96c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microphone-slash\": [640, 512, [], \"f131\", \"M633.82 458.1l-157.8-121.96C488.61 312.13 496 285.01 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67V96c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.77c11.66-1.6 22.85-4.54 33.67-8.31l-50.11-38.73c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microscope\": [512, 512, [], \"f610\", \"M160 320h12v16c0 8.84 7.16 16 16 16h40c8.84 0 16-7.16 16-16v-16h12c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32V16c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v16c-17.67 0-32 14.33-32 32v224c0 17.67 14.33 32 32 32zm304 128h-1.29C493.24 413.99 512 369.2 512 320c0-105.88-86.12-192-192-192v64c70.58 0 128 57.42 128 128s-57.42 128-128 128H48c-26.51 0-48 21.49-48 48 0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48zm-360-32h208c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8H104c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8z\"],\n    \"minus\": [448, 512, [], \"f068\", \"M416 208H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"minus-circle\": [512, 512, [], \"f056\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zM124 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H124z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM92 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H92z\"],\n    \"mitten\": [448, 512, [], \"f7b5\", \"M368 416H48c-8.8 0-16 7.2-16 16v64c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16zm57-209.1c-27.2-22.6-67.5-19-90.1 8.2l-20.9 25-29.6-128.4c-18-77.5-95.4-125.9-172.8-108C34.2 21.6-14.2 98.9 3.7 176.4L51.6 384h309l72.5-87c22.7-27.2 19-67.5-8.1-90.1z\"],\n    \"mobile\": [320, 512, [], \"f10b\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"mobile-alt\": [320, 512, [], \"f3cd\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm112-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v312z\"],\n    \"money-bill\": [640, 512, [], \"f0d6\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 176c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 48h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M352 288h-16v-88c0-4.42-3.58-8-8-8h-13.58c-4.74 0-9.37 1.4-13.31 4.03l-15.33 10.22a7.994 7.994 0 0 0-2.22 11.09l8.88 13.31a7.994 7.994 0 0 0 11.09 2.22l.47-.31V288h-16c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8h64c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 192c-53.02 0-96-50.15-96-112 0-61.86 42.98-112 96-112s96 50.14 96 112c0 61.87-43 112-96 112zm272 32h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-wave\": [640, 512, [], \"f53a\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM48 132.22c20.12 5.04 41.12 7.57 62.72 8.93C104.84 170.54 79 192.69 48 192.69v-60.47zm0 285v-47.78c34.37 0 62.18 27.27 63.71 61.4-22.53-1.81-43.59-6.31-63.71-13.62zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 27.78c-17.52-4.39-35.71-6.85-54.32-8.44 5.87-26.08 27.5-45.88 54.32-49.28v57.72zm0-236.11c-30.89-3.91-54.86-29.7-55.81-61.55 19.54 2.17 38.09 6.23 55.81 12.66v48.89z\"],\n    \"money-bill-wave-alt\": [640, 512, [], \"f53b\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96z\"],\n    \"money-check\": [640, 512, [], \"f53c\", \"M0 448c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128H0v320zm448-208c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-32zm0 120c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H456c-4.42 0-8-3.58-8-8v-16zM64 264c0-4.42 3.58-8 8-8h304c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm0 96c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zM624 32H16C7.16 32 0 39.16 0 48v48h640V48c0-8.84-7.16-16-16-16z\"],\n    \"money-check-alt\": [640, 512, [], \"f53d\", \"M608 32H32C14.33 32 0 46.33 0 64v384c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM176 327.88V344c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V152c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07zM416 312c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm160 0c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h272c4.42 0 8 3.58 8 8v16z\"],\n    \"monument\": [384, 512, [], \"f5a6\", \"M368 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h352c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-78.86-347.26a31.97 31.97 0 0 0-9.21-19.44L203.31 4.69c-6.25-6.25-16.38-6.25-22.63 0l-76.6 76.61a31.97 31.97 0 0 0-9.21 19.44L64 416h256l-30.86-315.26zM240 307.2c0 6.4-6.4 12.8-12.8 12.8h-70.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h70.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M283.211 512c78.962 0 151.079-35.925 198.857-94.792 7.068-8.708-.639-21.43-11.562-19.35-124.203 23.654-238.262-71.576-238.262-196.954 0-72.222 38.662-138.635 101.498-174.394 9.686-5.512 7.25-20.197-3.756-22.23A258.156 258.156 0 0 0 283.211 0c-141.309 0-256 114.511-256 256 0 141.309 114.511 256 256 256z\"],\n    \"mortar-pestle\": [512, 512, [], \"f5a7\", \"M501.54 60.91c17.22-17.22 12.51-46.25-9.27-57.14a35.696 35.696 0 0 0-37.37 3.37L251.09 160h151.37l99.08-99.09zM496 192H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c0 80.98 50.2 150.11 121.13 178.32-12.76 16.87-21.72 36.8-24.95 58.69-1.46 9.92 6.04 18.98 16.07 18.98h223.5c10.03 0 17.53-9.06 16.07-18.98-3.22-21.89-12.18-41.82-24.95-58.69C429.8 406.11 480 336.98 480 256h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"mosque\": [640, 512, [], \"f678\", \"M0 480c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V160H0v320zm579.16-192c17.86-17.39 28.84-37.34 28.84-58.91 0-52.86-41.79-93.79-87.92-122.9-41.94-26.47-80.63-57.77-111.96-96.22L400 0l-8.12 9.97c-31.33 38.45-70.01 69.76-111.96 96.22C233.79 135.3 192 176.23 192 229.09c0 21.57 10.98 41.52 28.84 58.91h358.32zM608 320H192c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h32v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h64v-72c0-48 48-72 48-72s48 24 48 72v72h64v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h32c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM64 0S0 32 0 96v32h128V96c0-64-64-96-64-96z\"],\n    \"motorcycle\": [640, 512, [], \"f21c\", \"M512.9 192c-14.9-.1-29.1 2.3-42.4 6.9L437.6 144H520c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24h-45.3c-6.8 0-13.3 2.9-17.8 7.9l-37.5 41.7-22.8-38C392.2 68.4 384.4 64 376 64h-80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h66.4l19.2 32H227.9c-17.7-23.1-44.9-40-99.9-40H72.5C59 104 47.7 115 48 128.5c.2 13 10.9 23.5 24 23.5h56c24.5 0 38.7 10.9 47.8 24.8l-11.3 20.5c-13-3.9-26.9-5.7-41.3-5.2C55.9 194.5 1.6 249.6 0 317c-1.6 72.1 56.3 131 128 131 59.6 0 109.7-40.8 124-96h84.2c13.7 0 24.6-11.4 24-25.1-2.1-47.1 17.5-93.7 56.2-125l12.5 20.8c-27.6 23.7-45.1 58.9-44.8 98.2.5 69.6 57.2 126.5 126.8 127.1 71.6.7 129.8-57.5 129.2-129.1-.7-69.6-57.6-126.4-127.2-126.9zM128 400c-44.1 0-80-35.9-80-80s35.9-80 80-80c4.2 0 8.4.3 12.5 1L99 316.4c-8.8 16 2.8 35.6 21 35.6h81.3c-12.4 28.2-40.6 48-73.3 48zm463.9-75.6c-2.2 40.6-35 73.4-75.5 75.5-46.1 2.5-84.4-34.3-84.4-79.9 0-21.4 8.4-40.8 22.1-55.1l49.4 82.4c4.5 7.6 14.4 10 22 5.5l13.7-8.2c7.6-4.5 10-14.4 5.5-22l-48.6-80.9c5.2-1.1 10.5-1.6 15.9-1.6 45.6-.1 82.3 38.2 79.9 84.3z\"],\n    \"mountain\": [640, 512, [], \"f6fc\", \"M634.92 462.7l-288-448C341.03 5.54 330.89 0 320 0s-21.03 5.54-26.92 14.7l-288 448a32.001 32.001 0 0 0-1.17 32.64A32.004 32.004 0 0 0 32 512h576c11.71 0 22.48-6.39 28.09-16.67a31.983 31.983 0 0 0-1.17-32.63zM320 91.18L405.39 224H320l-64 64-38.06-38.06L320 91.18z\"],\n    \"mouse-pointer\": [320, 512, [], \"f245\", \"M302.189 329.126H196.105l55.831 135.993c3.889 9.428-.555 19.999-9.444 23.999l-49.165 21.427c-9.165 4-19.443-.571-23.332-9.714l-53.053-129.136-86.664 89.138C18.729 472.71 0 463.554 0 447.977V18.299C0 1.899 19.921-6.096 30.277 5.443l284.412 292.542c11.472 11.179 3.007 31.141-12.5 31.141z\"],\n    \"mug-hot\": [512, 512, [], \"f7b6\", \"M127.1 146.5c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C111.8 5.9 105 0 96.8 0H80.4C70.6 0 63 8.5 64.1 18c3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zm112 0c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C223.8 5.9 217 0 208.8 0h-16.4c-9.8 0-17.5 8.5-16.3 18 3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zM400 192H32c-17.7 0-32 14.3-32 32v192c0 53 43 96 96 96h192c53 0 96-43 96-96h16c61.8 0 112-50.2 112-112s-50.2-112-112-112zm0 160h-16v-96h16c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"music\": [512, 512, [], \"f001\", \"M511.99 32.01c0-21.71-21.1-37.01-41.6-30.51L150.4 96c-13.3 4.2-22.4 16.5-22.4 30.5v261.42c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64V214.31l256-75.02v184.63c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64l-.01-351.99z\"],\n    \"network-wired\": [640, 512, [], \"f6ff\", \"M640 264v-16c0-8.84-7.16-16-16-16H344v-40h72c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H224c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h72v40H16c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h104v40H64c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h304v40h-56c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h104c8.84 0 16-7.16 16-16zM256 128V64h128v64H256zm-64 320H96v-64h96v64zm352 0h-96v-64h96v64z\"],\n    \"neuter\": [288, 512, [], \"f22c\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V468c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V316.4c64.1-14.5 112-71.9 112-140.4zm-144 80c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H88c-13.255 0-24 10.745-24 24v8H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h472c26.51 0 48-21.49 48-48V88c0-13.255-10.745-24-24-24zM56 400a8 8 0 0 1-8-8V144h16v248a8 8 0 0 1-8 8zm236-16H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm-208-96H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm0-96H140c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h360c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12z\"],\n    \"not-equal\": [448, 512, [], \"f53e\", \"M416 208c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32h-23.88l51.87-66.81c5.37-7.02 4.04-17.06-2.97-22.43L415.61 3.3c-7.02-5.38-17.06-4.04-22.44 2.97L311.09 112H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h204.56l-74.53 96H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h55.49l-51.87 66.81c-5.37 7.01-4.04 17.05 2.97 22.43L64 508.7c7.02 5.38 17.06 4.04 22.43-2.97L168.52 400H416c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32H243.05l74.53-96H416z\"],\n    \"notes-medical\": [384, 512, [], \"f481\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm96 304c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm0-192c0 4.4-3.6 8-8 8H104c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M480 128V96h20c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v20H64V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v40c0 6.627 5.373 12 12 12h20v320H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-20h384v20c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-20V128zM96 276V140c0-6.627 5.373-12 12-12h168c6.627 0 12 5.373 12 12v136c0 6.627-5.373 12-12 12H108c-6.627 0-12-5.373-12-12zm320 96c0 6.627-5.373 12-12 12H236c-6.627 0-12-5.373-12-12v-52h72c13.255 0 24-10.745 24-24v-72h84c6.627 0 12 5.373 12 12v136z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M64 320v26a6 6 0 0 1-6 6H6a6 6 0 0 1-6-6v-52a6 6 0 0 1 6-6h26V96H6a6 6 0 0 1-6-6V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v26h288V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-26v192h26a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-52a6 6 0 0 1-6-6v-26H64zm480-64v-32h26a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-52a6 6 0 0 0-6 6v26H408v72h8c13.255 0 24 10.745 24 24v64c0 13.255-10.745 24-24 24h-64c-13.255 0-24-10.745-24-24v-8H192v72h-26a6 6 0 0 0-6 6v52a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-26h288v26a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-26V256z\"],\n    \"oil-can\": [640, 512, [], \"f613\", \"M629.8 160.31L416 224l-50.49-25.24a64.07 64.07 0 0 0-28.62-6.76H280v-48h56c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h56v48h-56L37.72 166.86a31.9 31.9 0 0 0-5.79-.53C14.67 166.33 0 180.36 0 198.34v94.95c0 15.46 11.06 28.72 26.28 31.48L96 337.46V384c0 17.67 14.33 32 32 32h274.63c8.55 0 16.75-3.42 22.76-9.51l212.26-214.75c1.5-1.5 2.34-3.54 2.34-5.66V168c.01-5.31-5.08-9.15-10.19-7.69zM96 288.67l-48-8.73v-62.43l48 8.73v62.43zm453.33 84.66c0 23.56 19.1 42.67 42.67 42.67s42.67-19.1 42.67-42.67S592 288 592 288s-42.67 61.77-42.67 85.33z\"],\n    \"om\": [512, 512, [], \"f679\", \"M360.6 60.94a10.43 10.43 0 0 0 14.76 0l21.57-21.56a10.43 10.43 0 0 0 0-14.76L375.35 3.06c-4.08-4.07-10.68-4.07-14.76 0l-21.57 21.56a10.43 10.43 0 0 0 0 14.76l21.58 21.56zM412.11 192c-26.69 0-51.77 10.39-70.64 29.25l-24.25 24.25c-6.78 6.77-15.78 10.5-25.38 10.5H245c10.54-22.1 14.17-48.11 7.73-75.23-10.1-42.55-46.36-76.11-89.52-83.19-36.15-5.93-70.9 5.04-96.01 28.78-7.36 6.96-6.97 18.85 1.12 24.93l26.15 19.63c5.72 4.3 13.66 4.32 19.2-.21 8.45-6.9 19.02-10.71 30.27-10.71 26.47 0 48.01 21.53 48.01 48s-21.54 48-48.01 48h-31.9c-11.96 0-19.74 12.58-14.39 23.28l16.09 32.17c2.53 5.06 7.6 8.1 13.17 8.55h33.03c35.3 0 64.01 28.7 64.01 64s-28.71 64-64.01 64c-96.02 0-122.35-54.02-145.15-92.03-4.53-7.55-14.77-3.58-14.79 5.22C-.09 416 41.13 512 159.94 512c70.59 0 128.02-57.42 128.02-128 0-23.42-6.78-45.1-17.81-64h21.69c26.69 0 51.77-10.39 70.64-29.25l24.25-24.25c6.78-6.77 15.78-10.5 25.38-10.5 19.78 0 35.88 16.09 35.88 35.88V392c0 13.23-18.77 24-32.01 24-39.4 0-66.67-24.24-81.82-42.89-4.77-5.87-14.2-2.54-14.2 5.02V416s0 64 96.02 64c48.54 0 96.02-39.47 96.02-88V291.88c0-55.08-44.8-99.88-99.89-99.88zm42.18-124.73c-85.55 65.12-169.05 2.75-172.58.05-6.02-4.62-14.44-4.38-20.14.55-5.74 4.92-7.27 13.17-3.66 19.8 1.61 2.95 40.37 72.34 118.8 72.34 79.92 0 98.78-31.36 101.75-37.66 1.02-2.12 1.53-4.47 1.53-6.83V80c0-13.22-15.14-20.69-25.7-12.73z\"],\n    \"otter\": [640, 512, [], \"f700\", \"M608 32h-32l-13.25-13.25A63.97 63.97 0 0 0 517.49 0H497c-11.14 0-22.08 2.91-31.75 8.43L312 96h-56C149.96 96 64 181.96 64 288v1.61c0 32.75-16 62.14-39.56 84.89-18.19 17.58-28.1 43.68-23.19 71.8 6.76 38.8 42.9 65.7 82.28 65.7H192c17.67 0 32-14.33 32-32s-14.33-32-32-32H80c-8.83 0-16-7.17-16-16s7.17-16 16-16h224c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-64l149.49-80.5L448 416h80c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-28.22l-55.11-110.21L521.14 192H544c53.02 0 96-42.98 96-96V64c0-17.67-14.33-32-32-32zm-96 16c8.84 0 16 7.16 16 16s-7.16 16-16 16-16-7.16-16-16 7.16-16 16-16zm32 96h-34.96L407.2 198.84l-13.77-27.55L512 112h77.05c-6.62 18.58-24.22 32-45.05 32z\"],\n    \"outdent\": [448, 512, [], \"f03b\", \"M100.69 363.29c10 10 27.31 2.93 27.31-11.31V160c0-14.32-17.33-21.31-27.31-11.31l-96 96a16 16 0 0 0 0 22.62zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"pager\": [512, 512, [], \"f815\", \"M448 64H64a64 64 0 0 0-64 64v256a64 64 0 0 0 64 64h384a64 64 0 0 0 64-64V128a64 64 0 0 0-64-64zM160 368H80a16 16 0 0 1-16-16v-16a16 16 0 0 1 16-16h80zm128-16a16 16 0 0 1-16 16h-80v-48h80a16 16 0 0 1 16 16zm160-128a32 32 0 0 1-32 32H96a32 32 0 0 1-32-32v-64a32 32 0 0 1 32-32h320a32 32 0 0 1 32 32z\"],\n    \"paint-brush\": [512, 512, [], \"f1fc\", \"M167.02 309.34c-40.12 2.58-76.53 17.86-97.19 72.3-2.35 6.21-8 9.98-14.59 9.98-11.11 0-45.46-27.67-55.25-34.35C0 439.62 37.93 512 128 512c75.86 0 128-43.77 128-120.19 0-3.11-.65-6.08-.97-9.13l-88.01-73.34zM457.89 0c-15.16 0-29.37 6.71-40.21 16.45C213.27 199.05 192 203.34 192 257.09c0 13.7 3.25 26.76 8.73 38.7l63.82 53.18c7.21 1.8 14.64 3.03 22.39 3.03 62.11 0 98.11-45.47 211.16-256.46 7.38-14.35 13.9-29.85 13.9-45.99C512 20.64 486 0 457.89 0z\"],\n    \"paint-roller\": [512, 512, [], \"f5aa\", \"M416 128V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32zm32-64v128c0 17.67-14.33 32-32 32H256c-35.35 0-64 28.65-64 64v32c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32v-32h160c53.02 0 96-42.98 96-96v-64c0-35.35-28.65-64-64-64z\"],\n    \"palette\": [512, 512, [], \"f53f\", \"M204.3 5C104.9 24.4 24.8 104.3 5.2 203.4c-37 187 131.7 326.4 258.8 306.7 41.2-6.4 61.4-54.6 42.5-91.7-23.1-45.4 9.9-98.4 60.9-98.4h79.7c35.8 0 64.8-29.6 64.9-65.3C511.5 97.1 368.1-26.9 204.3 5zM96 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm32-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128-64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"pallet\": [640, 512, [], \"f482\", \"M144 256h352c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H384v128l-64-32-64 32V0H144c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16zm480 128c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h48v64H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16h-48v-64h48zm-336 64H128v-64h160v64zm224 0H352v-64h160v64z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M476 3.2L12.5 270.6c-18.1 10.4-15.8 35.6 2.2 43.2L121 358.4l287.3-253.2c5.5-4.9 13.3 2.6 8.6 8.3L176 407v80.5c0 23.6 28.5 32.9 42.5 15.8L282 426l124.6 52.2c14.2 6 30.4-2.9 33-18.2l72-432C515 7.8 493.3-6.8 476 3.2z\"],\n    \"paperclip\": [448, 512, [], \"f0c6\", \"M43.246 466.142c-58.43-60.289-57.341-157.511 1.386-217.581L254.392 34c44.316-45.332 116.351-45.336 160.671 0 43.89 44.894 43.943 117.329 0 162.276L232.214 383.128c-29.855 30.537-78.633 30.111-107.982-.998-28.275-29.97-27.368-77.473 1.452-106.953l143.743-146.835c6.182-6.314 16.312-6.422 22.626-.241l22.861 22.379c6.315 6.182 6.422 16.312.241 22.626L171.427 319.927c-4.932 5.045-5.236 13.428-.648 18.292 4.372 4.634 11.245 4.711 15.688.165l182.849-186.851c19.613-20.062 19.613-52.725-.011-72.798-19.189-19.627-49.957-19.637-69.154 0L90.39 293.295c-34.763 35.56-35.299 93.12-1.191 128.313 34.01 35.093 88.985 35.137 123.058.286l172.06-175.999c6.177-6.319 16.307-6.433 22.626-.256l22.877 22.364c6.319 6.177 6.434 16.307.256 22.626l-172.06 175.998c-59.576 60.938-155.943 60.216-214.77-.485z\"],\n    \"parachute-box\": [512, 512, [], \"f4cd\", \"M511.9 175c-9.1-75.6-78.4-132.4-158.3-158.7C390 55.7 416 116.9 416 192h28.1L327.5 321.5c-2.5-.6-4.8-1.5-7.5-1.5h-48V192h112C384 76.8 315.1 0 256 0S128 76.8 128 192h112v128h-48c-2.7 0-5 .9-7.5 1.5L67.9 192H96c0-75.1 26-136.3 62.4-175.7C78.5 42.7 9.2 99.5.1 175c-1.1 9.1 6.8 17 16 17h8.7l136.7 151.9c-.7 2.6-1.6 5.2-1.6 8.1v128c0 17.7 14.3 32 32 32h128c17.7 0 32-14.3 32-32V352c0-2.9-.9-5.4-1.6-8.1L487.1 192h8.7c9.3 0 17.2-7.8 16.1-17z\"],\n    \"paragraph\": [448, 512, [], \"f1dd\", \"M448 48v32a16 16 0 0 1-16 16h-48v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V96h-32v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V352h-32a160 160 0 0 1 0-320h240a16 16 0 0 1 16 16z\"],\n    \"parking\": [448, 512, [], \"f540\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM240 320h-48v48c0 8.8-7.2 16-16 16h-32c-8.8 0-16-7.2-16-16V144c0-8.8 7.2-16 16-16h96c52.9 0 96 43.1 96 96s-43.1 96-96 96zm0-128h-48v64h48c17.6 0 32-14.4 32-32s-14.4-32-32-32z\"],\n    \"passport\": [448, 512, [], \"f5ab\", \"M129.62 176h39.09c1.49-27.03 6.54-51.35 14.21-70.41-27.71 13.24-48.02 39.19-53.3 70.41zm0 32c5.29 31.22 25.59 57.17 53.3 70.41-7.68-19.06-12.72-43.38-14.21-70.41h-39.09zM224 286.69c7.69-7.45 20.77-34.42 23.43-78.69h-46.87c2.67 44.26 15.75 71.24 23.44 78.69zM200.57 176h46.87c-2.66-44.26-15.74-71.24-23.43-78.69-7.7 7.45-20.78 34.43-23.44 78.69zm64.51 102.41c27.71-13.24 48.02-39.19 53.3-70.41h-39.09c-1.49 27.03-6.53 51.35-14.21 70.41zM416 0H64C28.65 0 0 28.65 0 64v384c0 35.35 28.65 64 64 64h352c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32zm-80 416H112c-8.8 0-16-7.2-16-16s7.2-16 16-16h224c8.8 0 16 7.2 16 16s-7.2 16-16 16zm-112-96c-70.69 0-128-57.31-128-128S153.31 64 224 64s128 57.31 128 128-57.31 128-128 128zm41.08-214.41c7.68 19.06 12.72 43.38 14.21 70.41h39.09c-5.28-31.22-25.59-57.17-53.3-70.41z\"],\n    \"pastafarianism\": [640, 512, [], \"f67b\", \"M624.54 347.67c-32.7-12.52-57.36 4.25-75.37 16.45-17.06 11.53-23.25 14.42-31.41 11.36-8.12-3.09-10.83-9.38-15.89-29.38-3.33-13.15-7.44-29.32-17.95-42.65 2.24-2.91 4.43-5.79 6.38-8.57C500.47 304.45 513.71 312 532 312c33.95 0 50.87-25.78 62.06-42.83 10.59-16.14 15-21.17 21.94-21.17 13.25 0 24-10.75 24-24s-10.75-24-24-24c-33.95 0-50.87 25.78-62.06 42.83-10.6 16.14-15 21.17-21.94 21.17-17.31 0-37.48-61.43-97.26-101.91l17.25-34.5C485.43 125.5 512 97.98 512 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 13.02 3.94 25.1 10.62 35.21l-18.15 36.3c-16.98-4.6-35.6-7.51-56.46-7.51s-39.49 2.91-56.46 7.51l-18.15-36.3C252.06 89.1 256 77.02 256 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 33.98 26.56 61.5 60.02 63.6l17.25 34.5C145.68 202.44 125.15 264 108 264c-6.94 0-11.34-5.03-21.94-21.17C74.88 225.78 57.96 200 24 200c-13.25 0-24 10.75-24 24s10.75 24 24 24c6.94 0 11.34 5.03 21.94 21.17C57.13 286.22 74.05 312 108 312c18.29 0 31.53-7.55 41.7-17.11 1.95 2.79 4.14 5.66 6.38 8.57-10.51 13.33-14.62 29.5-17.95 42.65-5.06 20-7.77 26.28-15.89 29.38-8.11 3.06-14.33.17-31.41-11.36-18.03-12.2-42.72-28.92-75.37-16.45-12.39 4.72-18.59 18.58-13.87 30.97 4.72 12.41 18.61 18.61 30.97 13.88 8.16-3.09 14.34-.19 31.39 11.36 13.55 9.16 30.83 20.86 52.42 20.84 7.17 0 14.83-1.28 22.97-4.39 32.66-12.44 39.98-41.33 45.33-62.44 2.21-8.72 3.99-14.49 5.95-18.87 16.62 13.61 36.95 25.88 61.64 34.17-9.96 37-32.18 90.8-60.26 90.8-13.25 0-24 10.75-24 24s10.75 24 24 24c66.74 0 97.05-88.63 107.42-129.14 6.69.6 13.42 1.14 20.58 1.14s13.89-.54 20.58-1.14C350.95 423.37 381.26 512 448 512c13.25 0 24-10.75 24-24s-10.75-24-24-24c-27.94 0-50.21-53.81-60.22-90.81 24.69-8.29 45-20.56 61.62-34.16 1.96 4.38 3.74 10.15 5.95 18.87 5.34 21.11 12.67 50 45.33 62.44 8.14 3.11 15.8 4.39 22.97 4.39 21.59 0 38.87-11.69 52.42-20.84 17.05-11.55 23.28-14.45 31.39-11.36 12.39 4.75 26.27-1.47 30.97-13.88 4.71-12.4-1.49-26.26-13.89-30.98zM448 48c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zm-256 0c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16z\"],\n    \"paste\": [448, 512, [], \"f0ea\", \"M128 184c0-30.879 25.122-56 56-56h136V56c0-13.255-10.745-24-24-24h-80.61C204.306 12.89 183.637 0 160 0s-44.306 12.89-55.39 32H24C10.745 32 0 42.745 0 56v336c0 13.255 10.745 24 24 24h104V184zm32-144c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24zm184 248h104v200c0 13.255-10.745 24-24 24H184c-13.255 0-24-10.745-24-24V184c0-13.255 10.745-24 24-24h136v104c0 13.2 10.8 24 24 24zm104-38.059V256h-96v-96h6.059a24 24 0 0 1 16.97 7.029l65.941 65.941a24.002 24.002 0 0 1 7.03 16.971z\"],\n    \"pause\": [448, 512, [], \"f04c\", \"M144 479H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h96c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zm304-48V79c0-26.5-21.5-48-48-48h-96c-26.5 0-48 21.5-48 48v352c0 26.5 21.5 48 48 48h96c26.5 0 48-21.5 48-48z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm-16 328c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160zm112 0c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160z\"],\n    \"paw\": [512, 512, [], \"f1b0\", \"M256 224c-79.41 0-192 122.76-192 200.25 0 34.9 26.81 55.75 71.74 55.75 48.84 0 81.09-25.08 120.26-25.08 39.51 0 71.85 25.08 120.26 25.08 44.93 0 71.74-20.85 71.74-55.75C448 346.76 335.41 224 256 224zm-147.28-12.61c-10.4-34.65-42.44-57.09-71.56-50.13-29.12 6.96-44.29 40.69-33.89 75.34 10.4 34.65 42.44 57.09 71.56 50.13 29.12-6.96 44.29-40.69 33.89-75.34zm84.72-20.78c30.94-8.14 46.42-49.94 34.58-93.36s-46.52-72.01-77.46-63.87-46.42 49.94-34.58 93.36c11.84 43.42 46.53 72.02 77.46 63.87zm281.39-29.34c-29.12-6.96-61.15 15.48-71.56 50.13-10.4 34.65 4.77 68.38 33.89 75.34 29.12 6.96 61.15-15.48 71.56-50.13 10.4-34.65-4.77-68.38-33.89-75.34zm-156.27 29.34c30.94 8.14 65.62-20.45 77.46-63.87 11.84-43.42-3.64-85.21-34.58-93.36s-65.62 20.45-77.46 63.87c-11.84 43.42 3.64 85.22 34.58 93.36z\"],\n    \"peace\": [496, 512, [], \"f67c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm184 248c0 31.93-8.2 61.97-22.57 88.17L280 240.63V74.97c86.23 15.21 152 90.5 152 181.03zM216 437.03c-33.86-5.97-64.49-21.2-89.29-43.02L216 322.57v114.46zm64-114.46L369.29 394c-24.8 21.82-55.43 37.05-89.29 43.02V322.57zm-64-247.6v165.66L86.57 344.17C72.2 317.97 64 287.93 64 256c0-90.53 65.77-165.82 152-181.03z\"],\n    \"pen\": [512, 512, [], \"f304\", \"M290.74 93.24l128.02 128.02-277.99 277.99-114.14 12.6C11.35 513.54-1.56 500.62.14 485.34l12.7-114.22 277.9-277.88zm207.2-19.06l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.76 18.75-49.16 0-67.91z\"],\n    \"pen-alt\": [512, 512, [], \"f305\", \"M497.94 74.17l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91zm-246.8-20.53c-15.62-15.62-40.94-15.62-56.56 0L75.8 172.43c-6.25 6.25-6.25 16.38 0 22.62l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l101.82-101.82 22.63 22.62L93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l196.79-196.79-82.77-82.77-84.85-84.85z\"],\n    \"pen-fancy\": [512, 512, [], \"f5ac\", \"M79.18 282.94a32.005 32.005 0 0 0-20.24 20.24L0 480l4.69 4.69 92.89-92.89c-.66-2.56-1.57-5.03-1.57-7.8 0-17.67 14.33-32 32-32s32 14.33 32 32-14.33 32-32 32c-2.77 0-5.24-.91-7.8-1.57l-92.89 92.89L32 512l176.82-58.94a31.983 31.983 0 0 0 20.24-20.24l33.07-84.07-98.88-98.88-84.07 33.07zM369.25 28.32L186.14 227.81l97.85 97.85 199.49-183.11C568.4 67.48 443.73-55.94 369.25 28.32z\"],\n    \"pen-nib\": [512, 512, [], \"f5ad\", \"M136.6 138.79a64.003 64.003 0 0 0-43.31 41.35L0 460l14.69 14.69L164.8 324.58c-2.99-6.26-4.8-13.18-4.8-20.58 0-26.51 21.49-48 48-48s48 21.49 48 48-21.49 48-48 48c-7.4 0-14.32-1.81-20.58-4.8L37.31 497.31 52 512l279.86-93.29a64.003 64.003 0 0 0 41.35-43.31L416 224 288 96l-151.4 42.79zm361.34-64.62l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91z\"],\n    \"pen-square\": [448, 512, [], \"f14b\", \"M400 480H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zM238.1 177.9L102.4 313.6l-6.3 57.1c-.8 7.6 5.6 14.1 13.3 13.3l57.1-6.3L302.2 242c2.3-2.3 2.3-6.1 0-8.5L246.7 178c-2.5-2.4-6.3-2.4-8.6-.1zM345 165.1L314.9 135c-9.4-9.4-24.6-9.4-33.9 0l-23.1 23.1c-2.3 2.3-2.3 6.1 0 8.5l55.5 55.5c2.3 2.3 6.1 2.3 8.5 0L345 199c9.3-9.3 9.3-24.5 0-33.9z\"],\n    \"pencil-alt\": [512, 512, [], \"f303\", \"M497.9 142.1l-46.1 46.1c-4.7 4.7-12.3 4.7-17 0l-111-111c-4.7-4.7-4.7-12.3 0-17l46.1-46.1c18.7-18.7 49.1-18.7 67.9 0l60.1 60.1c18.8 18.7 18.8 49.1 0 67.9zM284.2 99.8L21.6 362.4.4 483.9c-2.9 16.4 11.4 30.6 27.8 27.8l121.5-21.3 262.6-262.6c4.7-4.7 4.7-12.3 0-17l-111-111c-4.8-4.7-12.4-4.7-17.1 0zM124.1 339.9c-5.5-5.5-5.5-14.3 0-19.8l154-154c5.5-5.5 14.3-5.5 19.8 0s5.5 14.3 0 19.8l-154 154c-5.5 5.5-14.3 5.5-19.8 0zM88 424h48v36.3l-64.5 11.3-31.1-31.1L51.7 376H88v48z\"],\n    \"pencil-ruler\": [512, 512, [], \"f5ae\", \"M109.46 244.04l134.58-134.56-44.12-44.12-61.68 61.68a7.919 7.919 0 0 1-11.21 0l-11.21-11.21c-3.1-3.1-3.1-8.12 0-11.21l61.68-61.68-33.64-33.65C131.47-3.1 111.39-3.1 99 9.29L9.29 99c-12.38 12.39-12.39 32.47 0 44.86l100.17 100.18zm388.47-116.8c18.76-18.76 18.75-49.17 0-67.93l-45.25-45.25c-18.76-18.76-49.18-18.76-67.95 0l-46.02 46.01 113.2 113.2 46.02-46.03zM316.08 82.71l-297 296.96L.32 487.11c-2.53 14.49 10.09 27.11 24.59 24.56l107.45-18.84L429.28 195.9 316.08 82.71zm186.63 285.43l-33.64-33.64-61.68 61.68c-3.1 3.1-8.12 3.1-11.21 0l-11.21-11.21c-3.09-3.1-3.09-8.12 0-11.21l61.68-61.68-44.14-44.14L267.93 402.5l100.21 100.2c12.39 12.39 32.47 12.39 44.86 0l89.71-89.7c12.39-12.39 12.39-32.47 0-44.86z\"],\n    \"people-carry\": [640, 512, [], \"f4ce\", \"M128 96c26.5 0 48-21.5 48-48S154.5 0 128 0 80 21.5 80 48s21.5 48 48 48zm384 0c26.5 0 48-21.5 48-48S538.5 0 512 0s-48 21.5-48 48 21.5 48 48 48zm125.7 372.1l-44-110-41.1 46.4-2 18.2 27.7 69.2c5 12.5 17 20.1 29.7 20.1 4 0 8-.7 11.9-2.3 16.4-6.6 24.4-25.2 17.8-41.6zm-34.2-209.8L585 178.1c-4.6-20-18.6-36.8-37.5-44.9-18.5-8-39-6.7-56.1 3.3-22.7 13.4-39.7 34.5-48.1 59.4L432 229.8 416 240v-96c0-8.8-7.2-16-16-16H240c-8.8 0-16 7.2-16 16v96l-16.1-10.2-11.3-33.9c-8.3-25-25.4-46-48.1-59.4-17.2-10-37.6-11.3-56.1-3.3-18.9 8.1-32.9 24.9-37.5 44.9l-18.4 80.2c-4.6 20 .7 41.2 14.4 56.7l67.2 75.9 10.1 92.6C130 499.8 143.8 512 160 512c1.2 0 2.3-.1 3.5-.2 17.6-1.9 30.2-17.7 28.3-35.3l-10.1-92.8c-1.5-13-6.9-25.1-15.6-35l-43.3-49 17.6-70.3 6.8 20.4c4.1 12.5 11.9 23.4 24.5 32.6l51.1 32.5c4.6 2.9 12.1 4.6 17.2 5h160c5.1-.4 12.6-2.1 17.2-5l51.1-32.5c12.6-9.2 20.4-20 24.5-32.6l6.8-20.4 17.6 70.3-43.3 49c-8.7 9.9-14.1 22-15.6 35l-10.1 92.8c-1.9 17.6 10.8 33.4 28.3 35.3 1.2.1 2.3.2 3.5.2 16.1 0 30-12.1 31.8-28.5l10.1-92.6 67.2-75.9c13.6-15.5 19-36.7 14.4-56.7zM46.3 358.1l-44 110c-6.6 16.4 1.4 35 17.8 41.6 16.8 6.6 35.1-1.7 41.6-17.8l27.7-69.2-2-18.2-41.1-46.4z\"],\n    \"pepper-hot\": [512, 512, [], \"f816\", \"M330.67 263.12V173.4l-52.75-24.22C219.44 218.76 197.58 400 56 400a56 56 0 0 0 0 112c212.64 0 370.65-122.87 419.18-210.34l-37.05-38.54zm131.09-128.37C493.92 74.91 477.18 26.48 458.62 3a8 8 0 0 0-11.93-.59l-22.9 23a8.06 8.06 0 0 0-.89 10.23c6.86 10.36 17.05 35.1-1.4 72.32A142.85 142.85 0 0 0 364.34 96c-28 0-54 8.54-76.34 22.59l74.67 34.29v78.24h89.09L506.44 288c3.26-12.62 5.56-25.63 5.56-39.31a154 154 0 0 0-50.24-113.94z\"],\n    \"percent\": [448, 512, [], \"f295\", \"M112 224c61.9 0 112-50.1 112-112S173.9 0 112 0 0 50.1 0 112s50.1 112 112 112zm0-160c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48 21.5-48 48-48zm224 224c-61.9 0-112 50.1-112 112s50.1 112 112 112 112-50.1 112-112-50.1-112-112-112zm0 160c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zM392.3.2l31.6-.1c19.4-.1 30.9 21.8 19.7 37.8L77.4 501.6a23.95 23.95 0 0 1-19.6 10.2l-33.4.1c-19.5 0-30.9-21.9-19.7-37.8l368-463.7C377.2 4 384.5.2 392.3.2z\"],\n    \"percentage\": [384, 512, [], \"f541\", \"M109.25 173.25c24.99-24.99 24.99-65.52 0-90.51-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 25 25 65.52 25 90.51 0zm256 165.49c-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 24.99 24.99 65.52 24.99 90.51 0 25-24.99 25-65.51 0-90.51zm-1.94-231.43l-22.62-22.62c-12.5-12.5-32.76-12.5-45.25 0L20.69 359.44c-12.5 12.5-12.5 32.76 0 45.25l22.62 22.62c12.5 12.5 32.76 12.5 45.25 0l274.75-274.75c12.5-12.49 12.5-32.75 0-45.25z\"],\n    \"person-booth\": [576, 512, [], \"f756\", \"M192 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320h-64v176zm32-272h-50.9l-45.2-45.3C115.8 166.6 99.7 160 82.7 160H64c-17.1 0-33.2 6.7-45.3 18.8C6.7 190.9 0 207 0 224.1L.2 320 0 480c0 17.7 14.3 32 31.9 32 17.6 0 32-14.3 32-32l.1-100.7c.9.5 1.6 1.3 2.5 1.7l29.1 43v56c0 17.7 14.3 32 32 32s32-14.3 32-32v-56.5c0-9.9-2.3-19.8-6.7-28.6l-41.2-61.3V253l20.9 20.9c9.1 9.1 21.1 14.1 33.9 14.1H224c17.7 0 32-14.3 32-32s-14.3-32-32-32zM64 128c26.5 0 48-21.5 48-48S90.5 32 64 32 16 53.5 16 80s21.5 48 48 48zm224-96l31.5 223.1-30.9 154.6c-4.3 21.6 13 38.3 31.4 38.3 15.2 0 28-9.1 32.3-30.4.9 16.9 14.6 30.4 31.7 30.4 17.7 0 32-14.3 32-32 0 17.7 14.3 32 32 32s32-14.3 32-32V0H288v32zm-96 0v160h64V0h-32c-17.7 0-32 14.3-32 32zM544 0h-32v496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32c0-17.7-14.3-32-32-32z\"],\n    \"phone\": [512, 512, [], \"f095\", \"M493.4 24.6l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-36 76.7-98.9 140.5-177.2 177.2l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48C3.9 366.5-2 378.1.6 389.4l24 104C27.1 504.2 36.7 512 48 512c256.1 0 464-207.5 464-464 0-11.2-7.7-20.9-18.6-23.4z\"],\n    \"phone-alt\": [512, 512, [], \"f879\", \"M497.39 361.8l-112-48a24 24 0 0 0-28 6.9l-49.6 60.6A370.66 370.66 0 0 1 130.6 204.11l60.6-49.6a23.94 23.94 0 0 0 6.9-28l-48-112A24.16 24.16 0 0 0 122.6.61l-104 24A24 24 0 0 0 0 48c0 256.5 207.9 464 464 464a24 24 0 0 0 23.4-18.6l24-104a24.29 24.29 0 0 0-14.01-27.6z\"],\n    \"phone-slash\": [640, 512, [], \"f3dd\", \"M268.2 381.4l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48c-10.7 4.6-16.5 16.1-13.9 27.5l24 104c2.5 10.8 12.1 18.6 23.4 18.6 100.7 0 193.7-32.4 269.7-86.9l-80-61.8c-10.9 6.5-22.1 12.7-33.6 18.1zm365.6 76.7L475.1 335.5C537.9 256.4 576 156.9 576 48c0-11.2-7.7-20.9-18.6-23.4l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-12.2 26.1-27.9 50.3-46 72.8L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"phone-square\": [448, 512, [], \"f098\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM94 416c-7.033 0-13.057-4.873-14.616-11.627l-14.998-65a15 15 0 0 1 8.707-17.16l69.998-29.999a15 15 0 0 1 17.518 4.289l30.997 37.885c48.944-22.963 88.297-62.858 110.781-110.78l-37.886-30.997a15.001 15.001 0 0 1-4.289-17.518l30-69.998a15 15 0 0 1 17.16-8.707l65 14.998A14.997 14.997 0 0 1 384 126c0 160.292-129.945 290-290 290z\"],\n    \"phone-square-alt\": [448, 512, [], \"f87b\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h352a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48zm-16.39 307.37l-15 65A15 15 0 0 1 354 416C194 416 64 286.29 64 126a15.7 15.7 0 0 1 11.63-14.61l65-15A18.23 18.23 0 0 1 144 96a16.27 16.27 0 0 1 13.79 9.09l30 70A17.9 17.9 0 0 1 189 181a17 17 0 0 1-5.5 11.61l-37.89 31a231.91 231.91 0 0 0 110.78 110.78l31-37.89A17 17 0 0 1 299 291a17.85 17.85 0 0 1 5.91 1.21l70 30A16.25 16.25 0 0 1 384 336a17.41 17.41 0 0 1-.39 3.37z\"],\n    \"phone-volume\": [384, 512, [], \"f2a0\", \"M97.333 506.966c-129.874-129.874-129.681-340.252 0-469.933 5.698-5.698 14.527-6.632 21.263-2.422l64.817 40.513a17.187 17.187 0 0 1 6.849 20.958l-32.408 81.021a17.188 17.188 0 0 1-17.669 10.719l-55.81-5.58c-21.051 58.261-20.612 122.471 0 179.515l55.811-5.581a17.188 17.188 0 0 1 17.669 10.719l32.408 81.022a17.188 17.188 0 0 1-6.849 20.958l-64.817 40.513a17.19 17.19 0 0 1-21.264-2.422zM247.126 95.473c11.832 20.047 11.832 45.008 0 65.055-3.95 6.693-13.108 7.959-18.718 2.581l-5.975-5.726c-3.911-3.748-4.793-9.622-2.261-14.41a32.063 32.063 0 0 0 0-29.945c-2.533-4.788-1.65-10.662 2.261-14.41l5.975-5.726c5.61-5.378 14.768-4.112 18.718 2.581zm91.787-91.187c60.14 71.604 60.092 175.882 0 247.428-4.474 5.327-12.53 5.746-17.552.933l-5.798-5.557c-4.56-4.371-4.977-11.529-.93-16.379 49.687-59.538 49.646-145.933 0-205.422-4.047-4.85-3.631-12.008.93-16.379l5.798-5.557c5.022-4.813 13.078-4.394 17.552.933zm-45.972 44.941c36.05 46.322 36.108 111.149 0 157.546-4.39 5.641-12.697 6.251-17.856 1.304l-5.818-5.579c-4.4-4.219-4.998-11.095-1.285-15.931 26.536-34.564 26.534-82.572 0-117.134-3.713-4.836-3.115-11.711 1.285-15.931l5.818-5.579c5.159-4.947 13.466-4.337 17.856 1.304z\"],\n    \"photo-video\": [640, 512, [], \"f87c\", \"M608 0H160a32 32 0 0 0-32 32v96h160V64h192v320h128a32 32 0 0 0 32-32V32a32 32 0 0 0-32-32zM232 103a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm352 208a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm-168 57H32a32 32 0 0 0-32 32v288a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V192a32 32 0 0 0-32-32zM96 224a32 32 0 1 1-32 32 32 32 0 0 1 32-32zm288 224H64v-32l64-64 32 32 128-128 96 96z\"],\n    \"piggy-bank\": [576, 512, [], \"f4d3\", \"M560 224h-29.5c-8.8-20-21.6-37.7-37.4-52.5L512 96h-32c-29.4 0-55.4 13.5-73 34.3-7.6-1.1-15.1-2.3-23-2.3H256c-77.4 0-141.9 55-156.8 128H56c-14.8 0-26.5-13.5-23.5-28.8C34.7 215.8 45.4 208 57 208h1c3.3 0 6-2.7 6-6v-20c0-3.3-2.7-6-6-6-28.5 0-53.9 20.4-57.5 48.6C-3.9 258.8 22.7 288 56 288h40c0 52.2 25.4 98.1 64 127.3V496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-48h128v48c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80.7c11.8-8.9 22.3-19.4 31.3-31.3H560c8.8 0 16-7.2 16-16V240c0-8.8-7.2-16-16-16zm-128 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM256 96h128c5.4 0 10.7.4 15.9.8 0-.3.1-.5.1-.8 0-53-43-96-96-96s-96 43-96 96c0 2.1.5 4.1.6 6.2 15.2-3.9 31-6.2 47.4-6.2z\"],\n    \"pills\": [576, 512, [], \"f484\", \"M112 32C50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V144c0-61.9-50.1-112-112-112zm48 224H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm139.7-29.7c-3.5-3.5-9.4-3.1-12.3.8-45.3 62.5-40.4 150.1 15.9 206.4 56.3 56.3 143.9 61.2 206.4 15.9 4-2.9 4.3-8.8.8-12.3L299.7 226.3zm229.8-19c-56.3-56.3-143.9-61.2-206.4-15.9-4 2.9-4.3 8.8-.8 12.3l210.8 210.8c3.5 3.5 9.4 3.1 12.3-.8 45.3-62.6 40.5-150.1-15.9-206.4z\"],\n    \"pizza-slice\": [512, 512, [], \"f818\", \"M158.87.15c-16.16-1.52-31.2 8.42-35.33 24.12l-14.81 56.27c187.62 5.49 314.54 130.61 322.48 317l56.94-15.78c15.72-4.36 25.49-19.68 23.62-35.9C490.89 165.08 340.78 17.32 158.87.15zm-58.47 112L.55 491.64a16.21 16.21 0 0 0 20 19.75l379-105.1c-4.27-174.89-123.08-292.14-299.15-294.1zM128 416a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm48-152a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm104 104a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"place-of-worship\": [640, 512, [], \"f67f\", \"M620.61 366.55L512 320v192h112c8.84 0 16-7.16 16-16V395.96a32 32 0 0 0-19.39-29.41zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.55A32 32 0 0 0 0 395.96zm464.46-149.28L416 217.6V102.63c0-8.49-3.37-16.62-9.38-22.63L331.31 4.69c-6.25-6.25-16.38-6.25-22.62 0L233.38 80c-6 6-9.38 14.14-9.38 22.63V217.6l-48.46 29.08A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.66-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44z\"],\n    \"plane\": [576, 512, [], \"f072\", \"M480 192H365.71L260.61 8.06A16.014 16.014 0 0 0 246.71 0h-65.5c-10.63 0-18.3 10.17-15.38 20.39L214.86 192H112l-43.2-57.6c-3.02-4.03-7.77-6.4-12.8-6.4H16.01C5.6 128-2.04 137.78.49 147.88L32 256 .49 364.12C-2.04 374.22 5.6 384 16.01 384H56c5.04 0 9.78-2.37 12.8-6.4L112 320h102.86l-49.03 171.6c-2.92 10.22 4.75 20.4 15.38 20.4h65.5c5.74 0 11.04-3.08 13.89-8.06L365.71 320H480c35.35 0 96-28.65 96-64s-60.65-64-96-64z\"],\n    \"plane-arrival\": [640, 512, [], \"f5af\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM44.81 205.66l88.74 80a62.607 62.607 0 0 0 25.47 13.93l287.6 78.35c26.48 7.21 54.56 8.72 81 1.36 29.67-8.27 43.44-21.21 47.25-35.71 3.83-14.5-1.73-32.71-23.37-54.96-19.28-19.82-44.35-32.79-70.83-40l-97.51-26.56L282.8 30.22c-1.51-5.81-5.95-10.35-11.66-11.91L206.05.58c-10.56-2.88-20.9 5.32-20.71 16.44l47.92 164.21-102.2-27.84-27.59-67.88c-1.93-4.89-6.01-8.57-11.02-9.93L52.72 64.75c-10.34-2.82-20.53 5-20.72 15.88l.23 101.78c.19 8.91 6.03 17.34 12.58 23.25z\"],\n    \"plane-departure\": [640, 512, [], \"f5b0\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM80.55 341.27c6.28 6.84 15.1 10.72 24.33 10.71l130.54-.18a65.62 65.62 0 0 0 29.64-7.12l290.96-147.65c26.74-13.57 50.71-32.94 67.02-58.31 18.31-28.48 20.3-49.09 13.07-63.65-7.21-14.57-24.74-25.27-58.25-27.45-29.85-1.94-59.54 5.92-86.28 19.48l-98.51 49.99-218.7-82.06a17.799 17.799 0 0 0-18-1.11L90.62 67.29c-10.67 5.41-13.25 19.65-5.17 28.53l156.22 98.1-103.21 52.38-72.35-36.47a17.804 17.804 0 0 0-16.07.02L9.91 230.22c-10.44 5.3-13.19 19.12-5.57 28.08l76.21 82.97z\"],\n    \"play\": [448, 512, [], \"f04b\", \"M424.4 214.7L72.4 6.6C43.8-10.3 0 6.1 0 47.9V464c0 37.5 40.7 60.1 72.4 41.3l352-208c31.4-18.5 31.5-64.1 0-82.6z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm115.7 272l-176 101c-15.8 8.8-35.7-2.5-35.7-21V152c0-18.4 19.8-29.8 35.7-21l176 107c16.4 9.2 16.4 32.9 0 42z\"],\n    \"plug\": [384, 512, [], \"f1e6\", \"M256 144V32c0-17.673 14.327-32 32-32s32 14.327 32 32v112h-64zm112 16H16c-8.837 0-16 7.163-16 16v32c0 8.837 7.163 16 16 16h16v32c0 77.406 54.969 141.971 128 156.796V512h64v-99.204c73.031-14.825 128-79.39 128-156.796v-32h16c8.837 0 16-7.163 16-16v-32c0-8.837-7.163-16-16-16zm-240-16V32c0-17.673-14.327-32-32-32S64 14.327 64 32v112h64z\"],\n    \"plus\": [448, 512, [], \"f067\", \"M416 208H272V64c0-17.67-14.33-32-32-32h-32c-17.67 0-32 14.33-32 32v144H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h144v144c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V304h144c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"plus-circle\": [512, 512, [], \"f055\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm144 276c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92h-92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-32 252c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92H92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"podcast\": [448, 512, [], \"f2ce\", \"M267.429 488.563C262.286 507.573 242.858 512 224 512c-18.857 0-38.286-4.427-43.428-23.437C172.927 460.134 160 388.898 160 355.75c0-35.156 31.142-43.75 64-43.75s64 8.594 64 43.75c0 32.949-12.871 104.179-20.571 132.813zM156.867 288.554c-18.693-18.308-29.958-44.173-28.784-72.599 2.054-49.724 42.395-89.956 92.124-91.881C274.862 121.958 320 165.807 320 220c0 26.827-11.064 51.116-28.866 68.552-2.675 2.62-2.401 6.986.628 9.187 9.312 6.765 16.46 15.343 21.234 25.363 1.741 3.654 6.497 4.66 9.449 1.891 28.826-27.043 46.553-65.783 45.511-108.565-1.855-76.206-63.595-138.208-139.793-140.369C146.869 73.753 80 139.215 80 220c0 41.361 17.532 78.7 45.55 104.989 2.953 2.771 7.711 1.77 9.453-1.887 4.774-10.021 11.923-18.598 21.235-25.363 3.029-2.2 3.304-6.566.629-9.185zM224 0C100.204 0 0 100.185 0 224c0 89.992 52.602 165.647 125.739 201.408 4.333 2.118 9.267-1.544 8.535-6.31-2.382-15.512-4.342-30.946-5.406-44.339-.146-1.836-1.149-3.486-2.678-4.512-47.4-31.806-78.564-86.016-78.187-147.347.592-96.237 79.29-174.648 175.529-174.899C320.793 47.747 400 126.797 400 224c0 61.932-32.158 116.49-80.65 147.867-.999 14.037-3.069 30.588-5.624 47.23-.732 4.767 4.203 8.429 8.535 6.31C395.227 389.727 448 314.187 448 224 448 100.205 347.815 0 224 0zm0 160c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64z\"],\n    \"poll\": [448, 512, [], \"f681\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM160 368c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V240c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v128zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V144c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v224zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-64c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v64z\"],\n    \"poll-h\": [448, 512, [], \"f682\", \"M448 432V80c0-26.5-21.5-48-48-48H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48zM112 192c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h128c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-64z\"],\n    \"poo\": [512, 512, [], \"f2fe\", \"M451.4 369.1C468.7 356 480 335.4 480 312c0-39.8-32.2-72-72-72h-14.1c13.4-11.7 22.1-28.8 22.1-48 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C250.3 14.6 256 30.6 256 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 19.2 8.7 36.3 22.1 48H104c-39.8 0-72 32.2-72 72 0 23.4 11.3 44 28.6 57.1C26.3 374.6 0 404.1 0 440c0 39.8 32.2 72 72 72h368c39.8 0 72-32.2 72-72 0-35.9-26.3-65.4-60.6-70.9zM192 256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm159.5 139C341 422.9 293 448 256 448s-85-25.1-95.5-53c-2-5.3 2-11 7.8-11h175.4c5.8 0 9.8 5.7 7.8 11zM320 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"poo-storm\": [448, 512, [], \"f75a\", \"M308 336h-57.7l17.3-64.9c2-7.6-3.7-15.1-11.6-15.1h-68c-6 0-11.1 4.5-11.9 10.4l-16 120c-1 7.2 4.6 13.6 11.9 13.6h59.3l-23 97.2c-1.8 7.6 4 14.8 11.7 14.8 4.2 0 8.2-2.2 10.4-6l88-152c4.6-8-1.2-18-10.4-18zm66.4-111.3c5.9-9.6 9.6-20.6 9.6-32.7 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C218.3 14.6 224 30.6 224 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 12.1 3.7 23.1 9.6 32.7C32.6 228 0 262.2 0 304c0 44 36 80 80 80h48.3c.1-.6 0-1.2 0-1.8l16-120c3-21.8 21.7-38.2 43.7-38.2h68c13.8 0 26.5 6.3 34.9 17.2s11.2 24.8 7.6 38.1l-6.6 24.7h16c15.7 0 30.3 8.4 38.1 22 7.8 13.6 7.8 30.5 0 44l-8.1 14h30c44 0 80-36 80-80 .1-41.8-32.5-76-73.5-79.3z\"],\n    \"poop\": [512, 512, [], \"f619\", \"M451.36 369.14C468.66 355.99 480 335.41 480 312c0-39.77-32.24-72-72-72h-14.07c13.42-11.73 22.07-28.78 22.07-48 0-35.35-28.65-64-64-64h-5.88c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96-5.17 0-10.15.74-15.11 1.52C250.31 14.64 256 30.62 256 48c0 44.18-35.82 80-80 80h-16c-35.35 0-64 28.65-64 64 0 19.22 8.65 36.27 22.07 48H104c-39.76 0-72 32.23-72 72 0 23.41 11.34 43.99 28.64 57.14C26.31 374.62 0 404.12 0 440c0 39.76 32.24 72 72 72h368c39.76 0 72-32.24 72-72 0-35.88-26.31-65.38-60.64-70.86z\"],\n    \"portrait\": [384, 512, [], \"f3e0\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM192 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 384 80 375.4 80 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"pound-sign\": [320, 512, [], \"f154\", \"M308 352h-45.495c-6.627 0-12 5.373-12 12v50.848H128V288h84c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-84v-63.556c0-32.266 24.562-57.086 61.792-57.086 23.658 0 45.878 11.505 57.652 18.849 5.151 3.213 11.888 2.051 15.688-2.685l28.493-35.513c4.233-5.276 3.279-13.005-2.119-17.081C273.124 54.56 236.576 32 187.931 32 106.026 32 48 84.742 48 157.961V224H20c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h28v128H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h296c6.627 0 12-5.373 12-12V364c0-6.627-5.373-12-12-12z\"],\n    \"power-off\": [512, 512, [], \"f011\", \"M400 54.1c63 45 104 118.6 104 201.9 0 136.8-110.8 247.7-247.5 248C120 504.3 8.2 393 8 256.4 7.9 173.1 48.9 99.3 111.8 54.2c11.7-8.3 28-4.8 35 7.7L162.6 90c5.9 10.5 3.1 23.8-6.6 31-41.5 30.8-68 79.6-68 134.9-.1 92.3 74.5 168.1 168 168.1 91.6 0 168.6-74.2 168-169.1-.3-51.8-24.7-101.8-68.1-134-9.7-7.2-12.4-20.5-6.5-30.9l15.8-28.1c7-12.4 23.2-16.1 34.8-7.8zM296 264V24c0-13.3-10.7-24-24-24h-32c-13.3 0-24 10.7-24 24v240c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24z\"],\n    \"pray\": [384, 512, [], \"f683\", \"M256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-30.63 169.75c14.06 16.72 39 19.09 55.97 5.22l88-72.02c17.09-13.98 19.59-39.19 5.62-56.28-13.97-17.11-39.19-19.59-56.31-5.62l-57.44 47-38.91-46.31c-15.44-18.39-39.22-27.92-64-25.33-24.19 2.48-45.25 16.27-56.37 36.92l-49.37 92.03c-23.4 43.64-8.69 96.37 34.19 123.75L131.56 432H40c-22.09 0-40 17.91-40 40s17.91 40 40 40h208c34.08 0 53.77-42.79 28.28-68.28L166.42 333.86l34.8-64.87 24.15 28.76z\"],\n    \"praying-hands\": [640, 512, [], \"f684\", \"M272 191.91c-17.6 0-32 14.4-32 32v80c0 8.84-7.16 16-16 16s-16-7.16-16-16v-76.55c0-17.39 4.72-34.47 13.69-49.39l77.75-129.59c9.09-15.16 4.19-34.81-10.97-43.91-14.45-8.67-32.72-4.3-42.3 9.21-.2.23-.62.21-.79.48l-117.26 175.9C117.56 205.9 112 224.31 112 243.29v80.23l-90.12 30.04A31.974 31.974 0 0 0 0 383.91v96c0 10.82 8.52 32 32 32 2.69 0 5.41-.34 8.06-1.03l179.19-46.62C269.16 449.99 304 403.8 304 351.91v-128c0-17.6-14.4-32-32-32zm346.12 161.73L528 323.6v-80.23c0-18.98-5.56-37.39-16.12-53.23L394.62 14.25c-.18-.27-.59-.24-.79-.48-9.58-13.51-27.85-17.88-42.3-9.21-15.16 9.09-20.06 28.75-10.97 43.91l77.75 129.59c8.97 14.92 13.69 32 13.69 49.39V304c0 8.84-7.16 16-16 16s-16-7.16-16-16v-80c0-17.6-14.4-32-32-32s-32 14.4-32 32v128c0 51.89 34.84 98.08 84.75 112.34l179.19 46.62c2.66.69 5.38 1.03 8.06 1.03 23.48 0 32-21.18 32-32v-96c0-13.77-8.81-25.99-21.88-30.35z\"],\n    \"prescription\": [384, 512, [], \"f5b1\", \"M301.26 352l78.06-78.06c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0L256 306.74l-83.96-83.96C219.31 216.8 256 176.89 256 128c0-53.02-42.98-96-96-96H16C7.16 32 0 39.16 0 48v256c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-80h18.75l128 128-78.06 78.06c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0L256 397.25l78.06 78.06c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63L301.26 352zM64 96h96c17.64 0 32 14.36 32 32s-14.36 32-32 32H64V96z\"],\n    \"prescription-bottle\": [384, 512, [], \"f485\", \"M32 192h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v64zM360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24z\"],\n    \"prescription-bottle-alt\": [384, 512, [], \"f486\", \"M360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24zM32 480c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v352zm64-184c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48z\"],\n    \"print\": [512, 512, [], \"f02f\", \"M448 192V77.25c0-8.49-3.37-16.62-9.37-22.63L393.37 9.37c-6-6-14.14-9.37-22.63-9.37H96C78.33 0 64 14.33 64 32v160c-35.35 0-64 28.65-64 64v112c0 8.84 7.16 16 16 16h48v96c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-96h48c8.84 0 16-7.16 16-16V256c0-35.35-28.65-64-64-64zm-64 256H128v-96h256v96zm0-224H128V64h192v48c0 8.84 7.16 16 16 16h48v96zm48 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"procedures\": [640, 512, [], \"f487\", \"M528 224H272c-8.8 0-16 7.2-16 16v144H64V144c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v352c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48h512v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V336c0-61.9-50.1-112-112-112zM136 96h126.1l27.6 55.2c5.9 11.8 22.7 11.8 28.6 0L368 51.8 390.1 96H512c8.8 0 16-7.2 16-16s-7.2-16-16-16H409.9L382.3 8.8C376.4-3 359.6-3 353.7 8.8L304 108.2l-19.9-39.8c-1.4-2.7-4.1-4.4-7.2-4.4H136c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm24 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"project-diagram\": [640, 512, [], \"f542\", \"M384 320H256c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM192 32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v128c0 17.67 14.33 32 32 32h95.72l73.16 128.04C211.98 300.98 232.4 288 256 288h.28L192 175.51V128h224V64H192V32zM608 0H480c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32z\"],\n    \"puzzle-piece\": [576, 512, [], \"f12e\", \"M519.442 288.651c-41.519 0-59.5 31.593-82.058 31.593C377.409 320.244 432 144 432 144s-196.288 80-196.288-3.297c0-35.827 36.288-46.25 36.288-85.985C272 19.216 243.885 0 210.539 0c-34.654 0-66.366 18.891-66.366 56.346 0 41.364 31.711 59.277 31.711 81.75C175.885 207.719 0 166.758 0 166.758v333.237s178.635 41.047 178.635-28.662c0-22.473-40-40.107-40-81.471 0-37.456 29.25-56.346 63.577-56.346 33.673 0 61.788 19.216 61.788 54.717 0 39.735-36.288 50.158-36.288 85.985 0 60.803 129.675 25.73 181.23 25.73 0 0-34.725-120.101 25.827-120.101 35.962 0 46.423 36.152 86.308 36.152C556.712 416 576 387.99 576 354.443c0-34.199-18.962-65.792-56.558-65.792z\"],\n    \"qrcode\": [448, 512, [], \"f029\", \"M0 224h192V32H0v192zM64 96h64v64H64V96zm192-64v192h192V32H256zm128 128h-64V96h64v64zM0 480h192V288H0v192zm64-128h64v64H64v-64zm352-64h32v128h-96v-32h-32v96h-64V288h96v32h64v-32zm0 160h32v32h-32v-32zm-64 0h32v32h-32v-32z\"],\n    \"question\": [384, 512, [], \"f128\", \"M202.021 0C122.202 0 70.503 32.703 29.914 91.026c-7.363 10.58-5.093 25.086 5.178 32.874l43.138 32.709c10.373 7.865 25.132 6.026 33.253-4.148 25.049-31.381 43.63-49.449 82.757-49.449 30.764 0 68.816 19.799 68.816 49.631 0 22.552-18.617 34.134-48.993 51.164-35.423 19.86-82.299 44.576-82.299 106.405V320c0 13.255 10.745 24 24 24h72.471c13.255 0 24-10.745 24-24v-5.773c0-42.86 125.268-44.645 125.268-160.627C377.504 66.256 286.902 0 202.021 0zM192 373.459c-38.196 0-69.271 31.075-69.271 69.271 0 38.195 31.075 69.27 69.271 69.27s69.271-31.075 69.271-69.271-31.075-69.27-69.271-69.27z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zM262.655 90c-54.497 0-89.255 22.957-116.549 63.758-3.536 5.286-2.353 12.415 2.715 16.258l34.699 26.31c5.205 3.947 12.621 3.008 16.665-2.122 17.864-22.658 30.113-35.797 57.303-35.797 20.429 0 45.698 13.148 45.698 32.958 0 14.976-12.363 22.667-32.534 33.976C247.128 238.528 216 254.941 216 296v4c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12v-1.333c0-28.462 83.186-29.647 83.186-106.667 0-58.002-60.165-102-116.531-102zM256 338c-25.365 0-46 20.635-46 46 0 25.364 20.635 46 46 46s46-20.636 46-46c0-25.365-20.635-46-46-46z\"],\n    \"quidditch\": [640, 512, [], \"f458\", \"M256.5 216.8L343.2 326s-16.6 102.4-76.6 150.1C206.7 523.8 0 510.2 0 510.2s3.8-23.1 11-55.4l94.6-112.2c4-4.7-.9-11.6-6.6-9.5l-60.4 22.1c14.4-41.7 32.7-80 54.6-97.5 59.9-47.8 163.3-40.9 163.3-40.9zm238 135c-44 0-79.8 35.8-79.8 79.9 0 44.1 35.7 79.9 79.8 79.9 44.1 0 79.8-35.8 79.8-79.9 0-44.2-35.8-79.9-79.8-79.9zM636.5 31L616.7 6c-5.5-6.9-15.5-8-22.4-2.6L361.8 181.3l-34.1-43c-5.1-6.4-15.1-5.2-18.6 2.2l-25.3 54.6 86.7 109.2 58.8-12.4c8-1.7 11.4-11.2 6.3-17.6l-34.1-42.9L634 53.5c6.9-5.5 8-15.6 2.5-22.5z\"],\n    \"quote-left\": [512, 512, [], \"f10d\", \"M464 256h-80v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8c-88.4 0-160 71.6-160 160v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zm-288 0H96v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8C71.6 32 0 103.6 0 192v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"quote-right\": [512, 512, [], \"f10e\", \"M464 32H336c-26.5 0-48 21.5-48 48v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48zm-288 0H48C21.5 32 0 53.5 0 80v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48z\"],\n    \"quran\": [448, 512, [], \"f687\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM301.08 145.82c.6-1.21 1.76-1.82 2.92-1.82s2.32.61 2.92 1.82l11.18 22.65 25 3.63c2.67.39 3.74 3.67 1.81 5.56l-18.09 17.63 4.27 24.89c.36 2.11-1.31 3.82-3.21 3.82-.5 0-1.02-.12-1.52-.38L304 211.87l-22.36 11.75c-.5.26-1.02.38-1.52.38-1.9 0-3.57-1.71-3.21-3.82l4.27-24.89-18.09-17.63c-1.94-1.89-.87-5.17 1.81-5.56l24.99-3.63 11.19-22.65zm-57.89-69.01c13.67 0 27.26 2.49 40.38 7.41a6.775 6.775 0 1 1-2.38 13.12c-.67 0-3.09-.21-4.13-.21-52.31 0-94.86 42.55-94.86 94.86 0 52.3 42.55 94.86 94.86 94.86 1.03 0 3.48-.21 4.13-.21 3.93 0 6.8 3.14 6.8 6.78 0 2.98-1.94 5.51-4.62 6.42-13.07 4.87-26.59 7.34-40.19 7.34C179.67 307.19 128 255.51 128 192c0-63.52 51.67-115.19 115.19-115.19zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"radiation\": [496, 512, [], \"f7b9\", \"M328.2 255.8h151.6c9.1 0 16.8-7.7 16.2-16.8-5.1-75.8-44.4-142.2-102.5-184.2-7.4-5.3-17.9-2.9-22.7 4.8L290.4 188c22.6 14.3 37.8 39.2 37.8 67.8zm-37.8 67.7c-12.3 7.7-26.8 12.4-42.4 12.4-15.6 0-30-4.7-42.4-12.4L125.2 452c-4.8 7.7-2.4 18.1 5.6 22.4C165.7 493.2 205.6 504 248 504s82.3-10.8 117.2-29.6c8-4.3 10.4-14.8 5.6-22.4l-80.4-128.5zM248 303.8c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm-231.8-48h151.6c0-28.6 15.2-53.5 37.8-67.7L125.2 59.7c-4.8-7.7-15.3-10.2-22.7-4.8C44.4 96.9 5.1 163.3 0 239.1c-.6 9 7.1 16.7 16.2 16.7z\"],\n    \"radiation-alt\": [496, 512, [], \"f7ba\", \"M312 256h79.1c9.2 0 16.9-7.7 16-16.8-4.6-43.6-27-81.8-59.5-107.8-7.6-6.1-18.8-4.5-24 3.8L281.9 202c18 11.2 30.1 31.2 30.1 54zm-97.8 54.1L172.4 377c-4.9 7.8-2.4 18.4 5.8 22.5 21.1 10.4 44.7 16.5 69.8 16.5s48.7-6.1 69.9-16.5c8.2-4.1 10.6-14.7 5.8-22.5l-41.8-66.9c-9.8 6.2-21.4 9.9-33.8 9.9s-24.1-3.7-33.9-9.9zM104.9 256H184c0-22.8 12.1-42.8 30.2-54.1l-41.7-66.8c-5.2-8.3-16.4-9.9-24-3.8-32.6 26-54.9 64.2-59.5 107.8-1.1 9.2 6.7 16.9 15.9 16.9zM248 504c137 0 248-111 248-248S385 8 248 8 0 119 0 256s111 248 248 248zm0-432c101.5 0 184 82.5 184 184s-82.5 184-184 184S64 357.5 64 256 146.5 72 248 72zm0 216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"rainbow\": [576, 512, [], \"f75b\", \"M268.3 32.7C115.4 42.9 0 176.9 0 330.2V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C64 186.8 180.9 80.3 317.5 97.9 430.4 112.4 512 214 512 327.8V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-165.3-140-298.6-307.7-287.3zm-5.6 96.9C166 142 96 229.1 96 326.7V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-74.8 64.5-134.8 140.8-127.4 66.5 6.5 115.2 66.2 115.2 133.1V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-114.2-100.2-205.4-217.3-190.4zm6.2 96.3c-45.6 8.9-76.9 51.5-76.9 97.9V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-17.6 14.3-32 32-32s32 14.4 32 32v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-59.2-53.8-106-115.1-94.1z\"],\n    \"random\": [512, 512, [], \"f074\", \"M504.971 359.029c9.373 9.373 9.373 24.569 0 33.941l-80 79.984c-15.01 15.01-40.971 4.49-40.971-16.971V416h-58.785a12.004 12.004 0 0 1-8.773-3.812l-70.556-75.596 53.333-57.143L352 336h32v-39.981c0-21.438 25.943-31.998 40.971-16.971l80 79.981zM12 176h84l52.781 56.551 53.333-57.143-70.556-75.596A11.999 11.999 0 0 0 122.785 96H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12zm372 0v39.984c0 21.46 25.961 31.98 40.971 16.971l80-79.984c9.373-9.373 9.373-24.569 0-33.941l-80-79.981C409.943 24.021 384 34.582 384 56.019V96h-58.785a12.004 12.004 0 0 0-8.773 3.812L96 336H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h110.785c3.326 0 6.503-1.381 8.773-3.812L352 176h32z\"],\n    \"receipt\": [384, 512, [], \"f543\", \"M358.4 3.2L320 48 265.6 3.2a15.9 15.9 0 0 0-19.2 0L192 48 137.6 3.2a15.9 15.9 0 0 0-19.2 0L64 48 25.6 3.2C15-4.7 0 2.8 0 16v480c0 13.2 15 20.7 25.6 12.8L64 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L192 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L320 464l38.4 44.8c10.5 7.9 25.6.4 25.6-12.8V16c0-13.2-15-20.7-25.6-12.8zM320 360c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16z\"],\n    \"recycle\": [512, 512, [], \"f1b8\", \"M184.561 261.903c3.232 13.997-12.123 24.635-24.068 17.168l-40.736-25.455-50.867 81.402C55.606 356.273 70.96 384 96.012 384H148c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12H96.115c-75.334 0-121.302-83.048-81.408-146.88l50.822-81.388-40.725-25.448c-12.081-7.547-8.966-25.961 4.879-29.158l110.237-25.45c8.611-1.988 17.201 3.381 19.189 11.99l25.452 110.237zm98.561-182.915l41.289 66.076-40.74 25.457c-12.051 7.528-9 25.953 4.879 29.158l110.237 25.45c8.672 1.999 17.215-3.438 19.189-11.99l25.45-110.237c3.197-13.844-11.99-24.719-24.068-17.168l-40.687 25.424-41.263-66.082c-37.521-60.033-125.209-60.171-162.816 0l-17.963 28.766c-3.51 5.62-1.8 13.021 3.82 16.533l33.919 21.195c5.62 3.512 13.024 1.803 16.536-3.817l17.961-28.743c12.712-20.341 41.973-19.676 54.257-.022zM497.288 301.12l-27.515-44.065c-3.511-5.623-10.916-7.334-16.538-3.821l-33.861 21.159c-5.62 3.512-7.33 10.915-3.818 16.536l27.564 44.112c13.257 21.211-2.057 48.96-27.136 48.96H320V336.02c0-14.213-17.242-21.383-27.313-11.313l-80 79.981c-6.249 6.248-6.249 16.379 0 22.627l80 79.989C302.689 517.308 320 510.3 320 495.989V448h95.88c75.274 0 121.335-82.997 81.408-146.88z\"],\n    \"redo\": [512, 512, [], \"f01e\", \"M500.33 0h-47.41a12 12 0 0 0-12 12.57l4 82.76A247.42 247.42 0 0 0 256 8C119.34 8 7.9 119.53 8 256.19 8.1 393.07 119.1 504 256 504a247.1 247.1 0 0 0 166.18-63.91 12 12 0 0 0 .48-17.43l-34-34a12 12 0 0 0-16.38-.55A176 176 0 1 1 402.1 157.8l-101.53-4.87a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12h200.33a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12z\"],\n    \"redo-alt\": [512, 512, [], \"f2f9\", \"M256.455 8c66.269.119 126.437 26.233 170.859 68.685l35.715-35.715C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.75c-30.864-28.899-70.801-44.907-113.23-45.273-92.398-.798-170.283 73.977-169.484 169.442C88.764 348.009 162.184 424 256 424c41.127 0 79.997-14.678 110.629-41.556 4.743-4.161 11.906-3.908 16.368.553l39.662 39.662c4.872 4.872 4.631 12.815-.482 17.433C378.202 479.813 319.926 504 256 504 119.034 504 8.001 392.967 8 256.002 7.999 119.193 119.646 7.755 256.455 8z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M285.363 207.475c0 18.6-9.831 28.431-28.431 28.431h-29.876v-56.14h23.378c28.668 0 34.929 8.773 34.929 27.709zM504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM363.411 360.414c-46.729-84.825-43.299-78.636-44.702-80.98 23.432-15.172 37.945-42.979 37.945-74.486 0-54.244-31.5-89.252-105.498-89.252h-70.667c-13.255 0-24 10.745-24 24V372c0 13.255 10.745 24 24 24h22.567c13.255 0 24-10.745 24-24v-71.663h25.556l44.129 82.937a24.001 24.001 0 0 0 21.188 12.727h24.464c18.261-.001 29.829-19.591 21.018-35.587z\"],\n    \"remove-format\": [640, 512, [], \"f87d\", \"M336 416h-11.17l9.26-27.77L267 336.4 240.49 416H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm297.82 42.1L377 259.59 426.17 112H544v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16H176a16 16 0 0 0-16 16v43.9L45.46 3.38A16 16 0 0 0 23 6.19L3.37 31.46a16 16 0 0 0 2.81 22.45l588.36 454.72a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zM309.91 207.76L224 141.36V112h117.83z\"],\n    \"reply\": [512, 512, [], \"f3e5\", \"M8.309 189.836L184.313 37.851C199.719 24.546 224 35.347 224 56.015v80.053c160.629 1.839 288 34.032 288 186.258 0 61.441-39.581 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 45.344-145.012-21.507-183.51-176.59-185.742V360c0 20.7-24.3 31.453-39.687 18.164l-176.004-152c-11.071-9.562-11.086-26.753 0-36.328z\"],\n    \"reply-all\": [576, 512, [], \"f122\", \"M136.309 189.836L312.313 37.851C327.72 24.546 352 35.348 352 56.015v82.763c129.182 10.231 224 52.212 224 183.548 0 61.441-39.582 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 38.512-123.162-3.922-169.482-112.59-182.015v84.175c0 20.701-24.3 31.453-39.687 18.164L136.309 226.164c-11.071-9.561-11.086-26.753 0-36.328zm-128 36.328L184.313 378.15C199.7 391.439 224 380.687 224 359.986v-15.818l-108.606-93.785A55.96 55.96 0 0 1 96 207.998a55.953 55.953 0 0 1 19.393-42.38L224 71.832V56.015c0-20.667-24.28-31.469-39.687-18.164L8.309 189.836c-11.086 9.575-11.071 26.767 0 36.328z\"],\n    \"republican\": [640, 512, [], \"f75e\", \"M544 192c0-88.4-71.6-160-160-160H160C71.6 32 0 103.6 0 192v64h544v-64zm-367.7-21.6l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L128 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L272 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L416 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zM624 320h-32c-8.8 0-16 7.2-16 16v64c0 8.8-7.2 16-16 16s-16-7.2-16-16V288H0v176c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16v-80h192v80c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16V352h32v43.3c0 41.8 30 80.1 71.6 84.3 47.8 4.9 88.4-32.7 88.4-79.6v-64c0-8.8-7.2-16-16-16z\"],\n    \"restroom\": [640, 512, [], \"f7bd\", \"M128 128c35.3 0 64-28.7 64-64S163.3 0 128 0 64 28.7 64 64s28.7 64 64 64zm384 0c35.3 0 64-28.7 64-64S547.3 0 512 0s-64 28.7-64 64 28.7 64 64 64zm127.3 226.5l-45.6-185.8c-3.3-13.5-15.5-23-29.8-24.2-15 9.7-32.8 15.5-52 15.5-19.2 0-37-5.8-52-15.5-14.3 1.2-26.5 10.7-29.8 24.2l-45.6 185.8C381 369.6 393 384 409.2 384H464v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V384h54.8c16.2 0 28.2-14.4 24.5-29.5zM336 0h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zM180.1 144.4c-15 9.8-32.9 15.6-52.1 15.6-19.2 0-37.1-5.8-52.1-15.6C51.3 146.5 32 166.9 32 192v136c0 13.3 10.7 24 24 24h8v136c0 13.3 10.7 24 24 24h80c13.3 0 24-10.7 24-24V352h8c13.3 0 24-10.7 24-24V192c0-25.1-19.3-45.5-43.9-47.6z\"],\n    \"retweet\": [640, 512, [], \"f079\", \"M629.657 343.598L528.971 444.284c-9.373 9.372-24.568 9.372-33.941 0L394.343 343.598c-9.373-9.373-9.373-24.569 0-33.941l10.823-10.823c9.562-9.562 25.133-9.34 34.419.492L480 342.118V160H292.451a24.005 24.005 0 0 1-16.971-7.029l-16-16C244.361 121.851 255.069 96 276.451 96H520c13.255 0 24 10.745 24 24v222.118l40.416-42.792c9.285-9.831 24.856-10.054 34.419-.492l10.823 10.823c9.372 9.372 9.372 24.569-.001 33.941zm-265.138 15.431A23.999 23.999 0 0 0 347.548 352H160V169.881l40.416 42.792c9.286 9.831 24.856 10.054 34.419.491l10.822-10.822c9.373-9.373 9.373-24.569 0-33.941L144.971 67.716c-9.373-9.373-24.569-9.373-33.941 0L10.343 168.402c-9.373 9.373-9.373 24.569 0 33.941l10.822 10.822c9.562 9.562 25.133 9.34 34.419-.491L96 169.881V392c0 13.255 10.745 24 24 24h243.549c21.382 0 32.09-25.851 16.971-40.971l-16.001-16z\"],\n    \"ribbon\": [448, 512, [], \"f4d6\", \"M6.1 444.3c-9.6 10.8-7.5 27.6 4.5 35.7l68.8 27.9c9.9 6.7 23.3 5 31.3-3.8l91.8-101.9-79.2-87.9-117.2 130zm435.8 0s-292-324.6-295.4-330.1c15.4-8.4 40.2-17.9 77.5-17.9s62.1 9.5 77.5 17.9c-3.3 5.6-56 64.6-56 64.6l79.1 87.7 34.2-38c28.7-31.9 33.3-78.6 11.4-115.5l-43.7-73.5c-4.3-7.2-9.9-13.3-16.8-18-40.7-27.6-127.4-29.7-171.4 0-6.9 4.7-12.5 10.8-16.8 18l-43.6 73.2c-1.5 2.5-37.1 62.2 11.5 116L337.5 504c8 8.9 21.4 10.5 31.3 3.8l68.8-27.9c11.9-8 14-24.8 4.3-35.6z\"],\n    \"ring\": [512, 512, [], \"f70b\", \"M256 64C110.06 64 0 125.91 0 208v98.13C0 384.48 114.62 448 256 448s256-63.52 256-141.87V208c0-82.09-110.06-144-256-144zm0 64c106.04 0 192 35.82 192 80 0 9.26-3.97 18.12-10.91 26.39C392.15 208.21 328.23 192 256 192s-136.15 16.21-181.09 42.39C67.97 226.12 64 217.26 64 208c0-44.18 85.96-80 192-80zM120.43 264.64C155.04 249.93 201.64 240 256 240s100.96 9.93 135.57 24.64C356.84 279.07 308.93 288 256 288s-100.84-8.93-135.57-23.36z\"],\n    \"road\": [576, 512, [], \"f018\", \"M573.19 402.67l-139.79-320C428.43 71.29 417.6 64 405.68 64h-97.59l2.45 23.16c.5 4.72-3.21 8.84-7.96 8.84h-29.16c-4.75 0-8.46-4.12-7.96-8.84L267.91 64h-97.59c-11.93 0-22.76 7.29-27.73 18.67L2.8 402.67C-6.45 423.86 8.31 448 30.54 448h196.84l10.31-97.68c.86-8.14 7.72-14.32 15.91-14.32h68.8c8.19 0 15.05 6.18 15.91 14.32L348.62 448h196.84c22.23 0 36.99-24.14 27.73-45.33zM260.4 135.16a8 8 0 0 1 7.96-7.16h39.29c4.09 0 7.53 3.09 7.96 7.16l4.6 43.58c.75 7.09-4.81 13.26-11.93 13.26h-40.54c-7.13 0-12.68-6.17-11.93-13.26l4.59-43.58zM315.64 304h-55.29c-9.5 0-16.91-8.23-15.91-17.68l5.07-48c.86-8.14 7.72-14.32 15.91-14.32h45.15c8.19 0 15.05 6.18 15.91 14.32l5.07 48c1 9.45-6.41 17.68-15.91 17.68z\"],\n    \"robot\": [640, 512, [], \"f544\", \"M0 256v128c0 17.7 14.3 32 32 32h32V224H32c-17.7 0-32 14.3-32 32zM464 96H352V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v64H176c-44.2 0-80 35.8-80 80v272c0 35.3 28.7 64 64 64h320c35.3 0 64-28.7 64-64V176c0-44.2-35.8-80-80-80zM256 416h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm128 120h-64v-32h64v32zm96 0h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm192-72h-32v192h32c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32z\"],\n    \"rocket\": [512, 512, [], \"f135\", \"M505.05 19.1a15.89 15.89 0 0 0-12.2-12.2C460.65 0 435.46 0 410.36 0c-103.2 0-165.1 55.2-211.29 128H94.87A48 48 0 0 0 52 154.49l-49.42 98.8A24 24 0 0 0 24.07 288h103.77l-22.47 22.47a32 32 0 0 0 0 45.25l50.9 50.91a32 32 0 0 0 45.26 0L224 384.16V488a24 24 0 0 0 34.7 21.49l98.7-49.39a47.91 47.91 0 0 0 26.5-42.9V312.79c72.59-46.3 128-108.4 128-211.09.1-25.2.1-50.4-6.85-82.6zM384 168a40 40 0 1 1 40-40 40 40 0 0 1-40 40z\"],\n    \"route\": [512, 512, [], \"f4d7\", \"M416 320h-96c-17.6 0-32-14.4-32-32s14.4-32 32-32h96s96-107 96-160-43-96-96-96-96 43-96 96c0 25.5 22.2 63.4 45.3 96H320c-52.9 0-96 43.1-96 96s43.1 96 96 96h96c17.6 0 32 14.4 32 32s-14.4 32-32 32H185.5c-16 24.8-33.8 47.7-47.3 64H416c52.9 0 96-43.1 96-96s-43.1-96-96-96zm0-256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM96 256c-53 0-96 43-96 96s96 160 96 160 96-107 96-160-43-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"rss\": [448, 512, [], \"f09e\", \"M128.081 415.959c0 35.369-28.672 64.041-64.041 64.041S0 451.328 0 415.959s28.672-64.041 64.041-64.041 64.04 28.673 64.04 64.041zm175.66 47.25c-8.354-154.6-132.185-278.587-286.95-286.95C7.656 175.765 0 183.105 0 192.253v48.069c0 8.415 6.49 15.472 14.887 16.018 111.832 7.284 201.473 96.702 208.772 208.772.547 8.397 7.604 14.887 16.018 14.887h48.069c9.149.001 16.489-7.655 15.995-16.79zm144.249.288C439.596 229.677 251.465 40.445 16.503 32.01 7.473 31.686 0 38.981 0 48.016v48.068c0 8.625 6.835 15.645 15.453 15.999 191.179 7.839 344.627 161.316 352.465 352.465.353 8.618 7.373 15.453 15.999 15.453h48.068c9.034-.001 16.329-7.474 16.005-16.504z\"],\n    \"rss-square\": [448, 512, [], \"f143\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM112 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm157.533 0h-34.335c-6.011 0-11.051-4.636-11.442-10.634-5.214-80.05-69.243-143.92-149.123-149.123-5.997-.39-10.633-5.431-10.633-11.441v-34.335c0-6.535 5.468-11.777 11.994-11.425 110.546 5.974 198.997 94.536 204.964 204.964.352 6.526-4.89 11.994-11.425 11.994zm103.027 0h-34.334c-6.161 0-11.175-4.882-11.427-11.038-5.598-136.535-115.204-246.161-251.76-251.76C68.882 152.949 64 147.935 64 141.774V107.44c0-6.454 5.338-11.664 11.787-11.432 167.83 6.025 302.21 141.191 308.205 308.205.232 6.449-4.978 11.787-11.432 11.787z\"],\n    \"ruble-sign\": [384, 512, [], \"f158\", \"M239.36 320C324.48 320 384 260.542 384 175.071S324.48 32 239.36 32H76c-6.627 0-12 5.373-12 12v206.632H12c-6.627 0-12 5.373-12 12V308c0 6.627 5.373 12 12 12h52v32H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v52c0 6.627 5.373 12 12 12h58.56c6.627 0 12-5.373 12-12v-52H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H146.56v-32h92.8zm-92.8-219.252h78.72c46.72 0 74.88 29.11 74.88 74.323 0 45.832-28.16 75.561-76.16 75.561h-77.44V100.748z\"],\n    \"ruler\": [640, 512, [], \"f545\", \"M635.7 167.2L556.1 31.7c-8.8-15-28.3-20.1-43.5-11.5l-69 39.1L503.3 161c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L416 75l-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L333.2 122 278 153.3 337.8 255c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-59.7-101.7-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-27.9-47.5-55.2 31.3 59.7 101.7c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L84.9 262.9l-69 39.1C.7 310.7-4.6 329.8 4.2 344.8l79.6 135.6c8.8 15 28.3 20.1 43.5 11.5L624.1 210c15.2-8.6 20.4-27.8 11.6-42.8z\"],\n    \"ruler-combined\": [512, 512, [], \"f546\", \"M160 288h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56v-64h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56V96h-56c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8h56V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 2.77.91 5.24 1.57 7.8L160 329.38V288zm320 64h-32v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-41.37L24.2 510.43c2.56.66 5.04 1.57 7.8 1.57h448c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"ruler-horizontal\": [576, 512, [], \"f547\", \"M544 128h-48v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8H88c-4.42 0-8-3.58-8-8v-88H32c-17.67 0-32 14.33-32 32v192c0 17.67 14.33 32 32 32h512c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32z\"],\n    \"ruler-vertical\": [256, 512, [], \"f548\", \"M168 416c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 17.67 14.33 32 32 32h192c17.67 0 32-14.33 32-32v-64h-88z\"],\n    \"running\": [416, 512, [], \"f70c\", \"M272 96c26.51 0 48-21.49 48-48S298.51 0 272 0s-48 21.49-48 48 21.49 48 48 48zM113.69 317.47l-14.8 34.52H32c-17.67 0-32 14.33-32 32s14.33 32 32 32h77.45c19.25 0 36.58-11.44 44.11-29.09l8.79-20.52-10.67-6.3c-17.32-10.23-30.06-25.37-37.99-42.61zM384 223.99h-44.03l-26.06-53.25c-12.5-25.55-35.45-44.23-61.78-50.94l-71.08-21.14c-28.3-6.8-57.77-.55-80.84 17.14l-39.67 30.41c-14.03 10.75-16.69 30.83-5.92 44.86s30.84 16.66 44.86 5.92l39.69-30.41c7.67-5.89 17.44-8 25.27-6.14l14.7 4.37-37.46 87.39c-12.62 29.48-1.31 64.01 26.3 80.31l84.98 50.17-27.47 87.73c-5.28 16.86 4.11 34.81 20.97 40.09 3.19 1 6.41 1.48 9.58 1.48 13.61 0 26.23-8.77 30.52-22.45l31.64-101.06c5.91-20.77-2.89-43.08-21.64-54.39l-61.24-36.14 31.31-78.28 20.27 41.43c8 16.34 24.92 26.89 43.11 26.89H384c17.67 0 32-14.33 32-32s-14.33-31.99-32-31.99z\"],\n    \"rupee-sign\": [320, 512, [], \"f156\", \"M308 96c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v44.748c0 6.627 5.373 12 12 12h85.28c27.308 0 48.261 9.958 60.97 27.252H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h158.757c-6.217 36.086-32.961 58.632-74.757 58.632H12c-6.627 0-12 5.373-12 12v53.012c0 3.349 1.4 6.546 3.861 8.818l165.052 152.356a12.001 12.001 0 0 0 8.139 3.182h82.562c10.924 0 16.166-13.408 8.139-20.818L116.871 319.906c76.499-2.34 131.144-53.395 138.318-127.906H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-58.69c-3.486-11.541-8.28-22.246-14.252-32H308z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256c0 90.1 48.2 168.7 120 212.1V288c0-8.8 7.2-16 16-16s16 7.2 16 16v196.7c29.5 12.4 62 19.3 96 19.3s66.5-6.9 96-19.3V288c0-8.8 7.2-16 16-16s16 7.2 16 16v180.1C447.8 424.7 496 346 496 256 496 119 385 8 248 8zm-65.5 216.5c-14.8-13.2-46.2-13.2-61 0L112 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c.8 5-1.7 10-6.1 12.4-5.8 3.1-11.2.7-13.7-1.6l-9.7-8.5zM248 416c-26.5 0-48-28.7-48-64s21.5-64 48-64 48 28.7 48 64-21.5 64-48 64zm149.8-181.5c-5.8 3.1-11.2.7-13.7-1.6l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S400 197 404 222.2c.6 4.9-1.8 9.9-6.2 12.3z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM152 416c-26.5 0-48-21-48-47 0-20 28.5-60.4 41.6-77.8 3.2-4.3 9.6-4.3 12.8 0C171.5 308.6 200 349 200 369c0 26-21.5 47-48 47zm16-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm170.2 154.2C315.8 367.4 282.9 352 248 352c-21.2 0-21.2-32 0-32 44.4 0 86.3 19.6 114.7 53.8 13.8 16.4-11.2 36.5-24.5 20.4z\"],\n    \"satellite\": [512, 512, [], \"f7bf\", \"M502.7 265l-80.3-80.4 47.8-47.9c13.1-13.1 13.1-34.4 0-47.5l-47.5-47.5c-13.1-13.1-34.4-13.1-47.5 0l-47.8 47.9-80.3-80.3C240.8 3.1 232.7 0 224.5 0S208.2 3.1 202 9.3L105.3 106c-12.4 12.4-12.4 32.6 0 45.1l80.3 80.4-9.8 9.8C122.1 217 59.6 218.6 7.3 246.7c-8.5 4.6-9.6 16.4-2.8 23.2L112 377.4l-17.8 17.8c-2.6-.7-5-1.6-7.8-1.6-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32c0-2.8-.9-5.2-1.6-7.8l17.8-17.8 107.5 107.5c6.8 6.8 18.7 5.7 23.2-2.8 28.1-52.3 29.7-114.8 5.4-168.5l9.9-9.9 80.3 80.4c6.2 6.2 14.4 9.3 22.5 9.3s16.3-3.1 22.5-9.3l96.7-96.7c12.5-12.4 12.5-32.6.1-45zm-352-136.5l73.8-73.8 68.9 68.9-73.8 73.8-68.9-68.9zm232.8 232.8l-68.9-68.9 73.8-73.8 68.9 68.9-73.8 73.8z\"],\n    \"satellite-dish\": [512, 512, [], \"f7c0\", \"M188.8 345.9l27.4-27.4c2.6.7 5 1.6 7.8 1.6 17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32c0 2.8.9 5.2 1.6 7.8l-27.4 27.4L49.4 206.5c-7.3-7.3-20.1-6.1-25 3-41.8 77.8-29.9 176.7 35.7 242.3 65.6 65.6 164.6 77.5 242.3 35.7 9.2-4.9 10.4-17.7 3-25L188.8 345.9zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM224 416c-35.346 0-64-28.654-64-64 0-35.346 28.654-64 64-64s64 28.654 64 64c0 35.346-28.654 64-64 64zm96-304.52V212c0 6.627-5.373 12-12 12H76c-6.627 0-12-5.373-12-12V108c0-6.627 5.373-12 12-12h228.52c3.183 0 6.235 1.264 8.485 3.515l3.48 3.48A11.996 11.996 0 0 1 320 111.48z\"],\n    \"school\": [640, 512, [], \"f549\", \"M0 224v272c0 8.84 7.16 16 16 16h80V192H32c-17.67 0-32 14.33-32 32zm360-48h-24v-40c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v64c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zm137.75-63.96l-160-106.67a32.02 32.02 0 0 0-35.5 0l-160 106.67A32.002 32.002 0 0 0 128 138.66V512h128V368c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v144h128V138.67c0-10.7-5.35-20.7-14.25-26.63zM320 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm288-64h-64v320h80c8.84 0 16-7.16 16-16V224c0-17.67-14.33-32-32-32z\"],\n    \"screwdriver\": [512, 512, [], \"f54a\", \"M448 0L320 96v62.06l-83.03 83.03c6.79 4.25 13.27 9.06 19.07 14.87 5.8 5.8 10.62 12.28 14.87 19.07L353.94 192H416l96-128-64-64zM128 278.59L10.92 395.67c-14.55 14.55-14.55 38.15 0 52.71l52.7 52.7c14.56 14.56 38.15 14.56 52.71 0L233.41 384c29.11-29.11 29.11-76.3 0-105.41s-76.3-29.11-105.41 0z\"],\n    \"scroll\": [640, 512, [], \"f70e\", \"M48 0C21.53 0 0 21.53 0 48v64c0 8.84 7.16 16 16 16h80V48C96 21.53 74.47 0 48 0zm208 412.57V352h288V96c0-52.94-43.06-96-96-96H111.59C121.74 13.41 128 29.92 128 48v368c0 38.87 34.65 69.65 74.75 63.12C234.22 474 256 444.46 256 412.57zM288 384v32c0 52.93-43.06 96-96 96h336c61.86 0 112-50.14 112-112 0-8.84-7.16-16-16-16H288z\"],\n    \"sd-card\": [384, 512, [], \"f7c2\", \"M320 0H128L0 128v320c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zM160 160h-48V64h48v96zm80 0h-48V64h48v96zm80 0h-48V64h48v96z\"],\n    \"search\": [512, 512, [], \"f002\", \"M505 442.7L405.3 343c-4.5-4.5-10.6-7-17-7H372c27.6-35.3 44-79.7 44-128C416 93.1 322.9 0 208 0S0 93.1 0 208s93.1 208 208 208c48.3 0 92.7-16.4 128-44v16.3c0 6.4 2.5 12.5 7 17l99.7 99.7c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.6.1-34zM208 336c-70.7 0-128-57.2-128-128 0-70.7 57.2-128 128-128 70.7 0 128 57.2 128 128 0 70.7-57.2 128-128 128z\"],\n    \"search-dollar\": [512, 512, [], \"f688\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm27.11-152.54l-45.01-13.5c-5.16-1.55-8.77-6.78-8.77-12.73 0-7.27 5.3-13.19 11.8-13.19h28.11c4.56 0 8.96 1.29 12.82 3.72 3.24 2.03 7.36 1.91 10.13-.73l11.75-11.21c3.53-3.37 3.33-9.21-.57-12.14-9.1-6.83-20.08-10.77-31.37-11.35V112c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v16.12c-23.63.63-42.68 20.55-42.68 45.07 0 19.97 12.99 37.81 31.58 43.39l45.01 13.5c5.16 1.55 8.77 6.78 8.77 12.73 0 7.27-5.3 13.19-11.8 13.19h-28.1c-4.56 0-8.96-1.29-12.82-3.72-3.24-2.03-7.36-1.91-10.13.73l-11.75 11.21c-3.53 3.37-3.33 9.21.57 12.14 9.1 6.83 20.08 10.77 31.37 11.35V304c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-16.12c23.63-.63 42.68-20.54 42.68-45.07 0-19.97-12.99-37.81-31.59-43.39z\"],\n    \"search-location\": [512, 512, [], \"f689\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm.02-239.96c-40.78 0-73.84 33.05-73.84 73.83 0 32.96 48.26 93.05 66.75 114.86a9.24 9.24 0 0 0 14.18 0c18.49-21.81 66.75-81.89 66.75-114.86 0-40.78-33.06-73.83-73.84-73.83zm0 96c-13.26 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"search-minus\": [512, 512, [], \"f010\", \"M304 192v32c0 6.6-5.4 12-12 12H124c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"search-plus\": [512, 512, [], \"f00e\", \"M304 192v32c0 6.6-5.4 12-12 12h-56v56c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-56h-56c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h56v-56c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v56h56c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"seedling\": [512, 512, [], \"f4d8\", \"M64 96H0c0 123.7 100.3 224 224 224v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C288 196.3 187.7 96 64 96zm384-64c-84.2 0-157.4 46.5-195.7 115.2 27.7 30.2 48.2 66.9 59 107.6C424 243.1 512 147.9 512 32h-64z\"],\n    \"server\": [512, 512, [], \"f233\", \"M480 160H32c-17.673 0-32-14.327-32-32V64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24z\"],\n    \"shapes\": [512, 512, [], \"f61f\", \"M512 320v160c0 17.67-14.33 32-32 32H320c-17.67 0-32-14.33-32-32V320c0-17.67 14.33-32 32-32h160c17.67 0 32 14.33 32 32zm-384-64C57.31 256 0 313.31 0 384s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm351.03-32c25.34 0 41.18-26.67 28.51-48L412.51 16c-12.67-21.33-44.35-21.33-57.02 0l-95.03 160c-12.67 21.33 3.17 48 28.51 48h190.06z\"],\n    \"share\": [512, 512, [], \"f064\", \"M503.691 189.836L327.687 37.851C312.281 24.546 288 35.347 288 56.015v80.053C127.371 137.907 0 170.1 0 322.326c0 61.441 39.581 122.309 83.333 154.132 13.653 9.931 33.111-2.533 28.077-18.631C66.066 312.814 132.917 274.316 288 272.085V360c0 20.7 24.3 31.453 39.687 18.164l176.004-152c11.071-9.562 11.086-26.753 0-36.328z\"],\n    \"share-alt\": [448, 512, [], \"f1e0\", \"M352 320c-22.608 0-43.387 7.819-59.79 20.895l-102.486-64.054a96.551 96.551 0 0 0 0-41.683l102.486-64.054C308.613 184.181 329.392 192 352 192c53.019 0 96-42.981 96-96S405.019 0 352 0s-96 42.981-96 96c0 7.158.79 14.13 2.276 20.841L155.79 180.895C139.387 167.819 118.608 160 96 160c-53.019 0-96 42.981-96 96s42.981 96 96 96c22.608 0 43.387-7.819 59.79-20.895l102.486 64.054A96.301 96.301 0 0 0 256 416c0 53.019 42.981 96 96 96s96-42.981 96-96-42.981-96-96-96z\"],\n    \"share-alt-square\": [448, 512, [], \"f1e1\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zM304 296c-14.562 0-27.823 5.561-37.783 14.671l-67.958-40.775a56.339 56.339 0 0 0 0-27.793l67.958-40.775C276.177 210.439 289.438 216 304 216c30.928 0 56-25.072 56-56s-25.072-56-56-56-56 25.072-56 56c0 4.797.605 9.453 1.74 13.897l-67.958 40.775C171.823 205.561 158.562 200 144 200c-30.928 0-56 25.072-56 56s25.072 56 56 56c14.562 0 27.823-5.561 37.783-14.671l67.958 40.775a56.088 56.088 0 0 0-1.74 13.897c0 30.928 25.072 56 56 56s56-25.072 56-56C360 321.072 334.928 296 304 296z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M568.482 177.448L424.479 313.433C409.3 327.768 384 317.14 384 295.985v-71.963c-144.575.97-205.566 35.113-164.775 171.353 4.483 14.973-12.846 26.567-25.006 17.33C155.252 383.105 120 326.488 120 269.339c0-143.937 117.599-172.5 264-173.312V24.012c0-21.174 25.317-31.768 40.479-17.448l144.003 135.988c10.02 9.463 10.028 25.425 0 34.896zM384 379.128V448H64V128h50.916a11.99 11.99 0 0 0 8.648-3.693c14.953-15.568 32.237-27.89 51.014-37.676C185.708 80.83 181.584 64 169.033 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48v-88.806c0-8.288-8.197-14.066-16.011-11.302a71.83 71.83 0 0 1-34.189 3.377c-7.27-1.046-13.8 4.514-13.8 11.859z\"],\n    \"shekel-sign\": [448, 512, [], \"f20b\", \"M248 168v168c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V168c0-75.11-60.89-136-136-136H24C10.75 32 0 42.74 0 56v408c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112h112c30.93 0 56 25.07 56 56zM432 32h-48c-8.84 0-16 7.16-16 16v296c0 30.93-25.07 56-56 56H200V176c0-8.84-7.16-16-16-16h-48c-8.84 0-16 7.16-16 16v280c0 13.25 10.75 24 24 24h168c75.11 0 136-60.89 136-136V48c0-8.84-7.16-16-16-16z\"],\n    \"shield-alt\": [512, 512, [], \"f3ed\", \"M466.5 83.7l-192-80a48.15 48.15 0 0 0-36.9 0l-192 80C27.7 91.1 16 108.6 16 128c0 198.5 114.5 335.7 221.5 380.3 11.8 4.9 25.1 4.9 36.9 0C360.1 472.6 496 349.3 496 128c0-19.4-11.7-36.9-29.5-44.3zM256.1 446.3l-.1-381 175.9 73.3c-3.3 151.4-82.1 261.1-175.8 307.7z\"],\n    \"ship\": [640, 512, [], \"f21a\", \"M496.616 372.639l70.012-70.012c16.899-16.9 9.942-45.771-12.836-53.092L512 236.102V96c0-17.673-14.327-32-32-32h-64V24c0-13.255-10.745-24-24-24H248c-13.255 0-24 10.745-24 24v40h-64c-17.673 0-32 14.327-32 32v140.102l-41.792 13.433c-22.753 7.313-29.754 36.173-12.836 53.092l70.012 70.012C125.828 416.287 85.587 448 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24 61.023 0 107.499-20.61 143.258-59.396C181.677 487.432 216.021 512 256 512h128c39.979 0 74.323-24.568 88.742-59.396C508.495 491.384 554.968 512 616 512c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24-60.817 0-101.542-31.001-119.384-75.361zM192 128h256v87.531l-118.208-37.995a31.995 31.995 0 0 0-19.584 0L192 215.531V128z\"],\n    \"shipping-fast\": [640, 512, [], \"f48b\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H112C85.5 0 64 21.5 64 48v48H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h272c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H40c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H64v128c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"shoe-prints\": [640, 512, [], \"f54b\", \"M192 160h32V32h-32c-35.35 0-64 28.65-64 64s28.65 64 64 64zM0 416c0 35.35 28.65 64 64 64h32V352H64c-35.35 0-64 28.65-64 64zm337.46-128c-34.91 0-76.16 13.12-104.73 32-24.79 16.38-44.52 32-104.73 32v128l57.53 15.97c26.21 7.28 53.01 13.12 80.31 15.05 32.69 2.31 65.6.67 97.58-6.2C472.9 481.3 512 429.22 512 384c0-64-84.18-96-174.54-96zM491.42 7.19C459.44.32 426.53-1.33 393.84.99c-27.3 1.93-54.1 7.77-80.31 15.04L256 32v128c60.2 0 79.94 15.62 104.73 32 28.57 18.88 69.82 32 104.73 32C555.82 224 640 192 640 128c0-45.22-39.1-97.3-148.58-120.81z\"],\n    \"shopping-bag\": [448, 512, [], \"f290\", \"M352 160v-32C352 57.42 294.579 0 224 0 153.42 0 96 57.42 96 128v32H0v272c0 44.183 35.817 80 80 80h288c44.183 0 80-35.817 80-80V160h-96zm-192-32c0-35.29 28.71-64 64-64s64 28.71 64 64v32H160v-32zm160 120c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm-192 0c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24z\"],\n    \"shopping-basket\": [576, 512, [], \"f291\", \"M576 216v16c0 13.255-10.745 24-24 24h-8l-26.113 182.788C514.509 462.435 494.257 480 470.37 480H105.63c-23.887 0-44.139-17.565-47.518-41.212L32 256h-8c-13.255 0-24-10.745-24-24v-16c0-13.255 10.745-24 24-24h67.341l106.78-146.821c10.395-14.292 30.407-17.453 44.701-7.058 14.293 10.395 17.453 30.408 7.058 44.701L170.477 192h235.046L326.12 82.821c-10.395-14.292-7.234-34.306 7.059-44.701 14.291-10.395 34.306-7.235 44.701 7.058L484.659 192H552c13.255 0 24 10.745 24 24zM312 392V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm112 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm-224 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24z\"],\n    \"shopping-cart\": [576, 512, [], \"f07a\", \"M528.12 301.319l47.273-208C578.806 78.301 567.391 64 551.99 64H159.208l-9.166-44.81C147.758 8.021 137.93 0 126.529 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24h69.883l70.248 343.435C147.325 417.1 136 435.222 136 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-15.674-6.447-29.835-16.824-40h209.647C430.447 426.165 424 440.326 424 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-22.172-12.888-41.332-31.579-50.405l5.517-24.276c3.413-15.018-8.002-29.319-23.403-29.319H218.117l-6.545-32h293.145c11.206 0 20.92-7.754 23.403-18.681z\"],\n    \"shower\": [512, 512, [], \"f2cc\", \"M389.66 135.6L231.6 293.66c-9.37 9.37-24.57 9.37-33.94 0l-11.32-11.32c-9.37-9.37-9.37-24.57 0-33.94l.11-.11c-34.03-40.21-35.16-98.94-3.39-140.38-11.97-7.55-26.14-11.91-41.3-11.91C98.88 96 64 130.88 64 173.76V480H0V173.76C0 95.59 63.59 32 141.76 32c36.93 0 70.61 14.2 95.86 37.42 35.9-11.51 76.5-4.5 106.67 21.03l.11-.11c9.37-9.37 24.57-9.37 33.94 0l11.32 11.32c9.37 9.37 9.37 24.57 0 33.94zM384 208c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm48-16c8.837 0 16 7.163 16 16s-7.163 16-16 16-16-7.163-16-16 7.163-16 16-16zm80 16c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-128 32c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-96 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm64 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16z\"],\n    \"shuttle-van\": [640, 512, [], \"f5b6\", \"M628.88 210.65L494.39 49.27A48.01 48.01 0 0 0 457.52 32H32C14.33 32 0 46.33 0 64v288c0 17.67 14.33 32 32 32h32c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h32c17.67 0 32-14.33 32-32V241.38c0-11.23-3.94-22.1-11.12-30.73zM64 192V96h96v96H64zm96 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm160-240h-96V96h96v96zm160 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-96-240V96h66.02l80 96H384z\"],\n    \"sign\": [512, 512, [], \"f4d9\", \"M496 64H128V16c0-8.8-7.2-16-16-16H80c-8.8 0-16 7.2-16 16v48H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V128h368c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16zM160 384h320V160H160v224z\"],\n    \"sign-in-alt\": [512, 512, [], \"f2f6\", \"M416 448h-84c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h84c17.7 0 32-14.3 32-32V160c0-17.7-14.3-32-32-32h-84c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h84c53 0 96 43 96 96v192c0 53-43 96-96 96zm-47-201L201 79c-15-15-41-4.5-41 17v96H24c-13.3 0-24 10.7-24 24v96c0 13.3 10.7 24 24 24h136v96c0 21.5 26 32 41 17l168-168c9.3-9.4 9.3-24.6 0-34z\"],\n    \"sign-language\": [448, 512, [], \"f2a7\", \"M91.434 483.987c-.307-16.018 13.109-29.129 29.13-29.129h62.293v-5.714H56.993c-16.021 0-29.437-13.111-29.13-29.129C28.16 404.491 40.835 392 56.428 392h126.429v-5.714H29.136c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h154.286v-5.714H57.707c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h168.566l-31.085-22.606c-12.762-9.281-15.583-27.149-6.302-39.912 9.281-12.761 27.15-15.582 39.912-6.302l123.361 89.715a34.287 34.287 0 0 1 14.12 27.728v141.136c0 15.91-10.946 29.73-26.433 33.374l-80.471 18.934a137.16 137.16 0 0 1-31.411 3.646H120c-15.593-.001-28.269-12.492-28.566-28.014zm73.249-225.701h36.423l-11.187-8.136c-18.579-13.511-20.313-40.887-3.17-56.536l-13.004-16.7c-9.843-12.641-28.43-15.171-40.88-5.088-12.065 9.771-14.133 27.447-4.553 39.75l36.371 46.71zm283.298-2.103l-5.003-152.452c-.518-15.771-13.722-28.136-29.493-27.619-15.773.518-28.137 13.722-27.619 29.493l1.262 38.415L283.565 11.019c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l76.889 98.745-4.509 3.511-94.79-121.734c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l94.443 121.288-4.509 3.511-77.675-99.754c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l52.053 66.849c12.497-8.257 29.055-8.285 41.69.904l123.36 89.714c10.904 7.93 17.415 20.715 17.415 34.198v16.999l61.064-47.549a34.285 34.285 0 0 0 13.202-28.177z\"],\n    \"sign-out-alt\": [512, 512, [], \"f2f5\", \"M497 273L329 441c-15 15-41 4.5-41-17v-96H152c-13.3 0-24-10.7-24-24v-96c0-13.3 10.7-24 24-24h136V88c0-21.4 25.9-32 41-17l168 168c9.3 9.4 9.3 24.6 0 34zM192 436v-40c0-6.6-5.4-12-12-12H96c-17.7 0-32-14.3-32-32V160c0-17.7 14.3-32 32-32h84c6.6 0 12-5.4 12-12V76c0-6.6-5.4-12-12-12H96c-53 0-96 43-96 96v192c0 53 43 96 96 96h84c6.6 0 12-5.4 12-12z\"],\n    \"signal\": [640, 512, [], \"f012\", \"M216 288h-48c-8.84 0-16 7.16-16 16v192c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V304c0-8.84-7.16-16-16-16zM88 384H40c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16zm256-192h-48c-8.84 0-16 7.16-16 16v288c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V208c0-8.84-7.16-16-16-16zm128-96h-48c-8.84 0-16 7.16-16 16v384c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112c0-8.84-7.16-16-16-16zM600 0h-48c-8.84 0-16 7.16-16 16v480c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"signature\": [640, 512, [], \"f5b7\", \"M623.2 192c-51.8 3.5-125.7 54.7-163.1 71.5-29.1 13.1-54.2 24.4-76.1 24.4-22.6 0-26-16.2-21.3-51.9 1.1-8 11.7-79.2-42.7-76.1-25.1 1.5-64.3 24.8-169.5 126L192 182.2c30.4-75.9-53.2-151.5-129.7-102.8L7.4 116.3C0 121-2.2 130.9 2.5 138.4l17.2 27c4.7 7.5 14.6 9.7 22.1 4.9l58-38.9c18.4-11.7 40.7 7.2 32.7 27.1L34.3 404.1C27.5 421 37 448 64 448c8.3 0 16.5-3.2 22.6-9.4 42.2-42.2 154.7-150.7 211.2-195.8-2.2 28.5-2.1 58.9 20.6 83.8 15.3 16.8 37.3 25.3 65.5 25.3 35.6 0 68-14.6 102.3-30 33-14.8 99-62.6 138.4-65.8 8.5-.7 15.2-7.3 15.2-15.8v-32.1c.2-9.1-7.5-16.8-16.6-16.2z\"],\n    \"sim-card\": [384, 512, [], \"f7c4\", \"M0 64v384c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V128L256 0H64C28.7 0 0 28.7 0 64zm224 192h-64v-64h64v64zm96 0h-64v-64h32c17.7 0 32 14.3 32 32v32zm-64 128h64v32c0 17.7-14.3 32-32 32h-32v-64zm-96 0h64v64h-64v-64zm-96 0h64v64H96c-17.7 0-32-14.3-32-32v-32zm0-96h256v64H64v-64zm0-64c0-17.7 14.3-32 32-32h32v64H64v-32z\"],\n    \"sitemap\": [640, 512, [], \"f0e8\", \"M128 352H32c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm-24-80h192v48h48v-48h192v48h48v-57.59c0-21.17-17.23-38.41-38.41-38.41H344v-64h40c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H256c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h40v64H94.41C73.23 224 56 241.23 56 262.41V320h48v-48zm264 80h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm240 0h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"skating\": [448, 512, [], \"f7c5\", \"M400 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm0 448c-8.8 0-16 7.2-16 16s-7.2 16-16 16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16h96c26.5 0 48-21.5 48-48 0-8.8-7.2-16-16-16zm-282.2 8.6c-6.2 6.2-16.4 6.3-22.6 0l-67.9-67.9c-6.2-6.2-16.4-6.2-22.6 0s-6.2 16.4 0 22.6l67.9 67.9c9.4 9.4 21.7 14 34 14s24.6-4.7 33.9-14c6.2-6.2 6.2-16.4 0-22.6s-16.4-6.3-22.7 0zm56.1-179.8l-93.7 93.7c-12.5 12.5-12.5 32.8 0 45.2 6.2 6.2 14.4 9.4 22.6 9.4s16.4-3.1 22.6-9.4l91.9-91.9-30.2-30.2c-5-5-9.4-10.7-13.2-16.8zM128 160h105.5l-20.1 17.2c-13.5 11.5-21.6 28.4-22.3 46.1-.7 17.8 6.1 35.2 18.7 47.7l78.2 78.2V432c0 17.7 14.3 32 32 32s32-14.3 32-32v-89.4c0-12.6-5.1-25-14.1-33.9l-61-61c.5-.4 1.2-.6 1.7-1.1l82.3-82.3c11.5-11.5 14.9-28.6 8.7-43.6-6.2-15-20.7-24.7-37-24.7H128c-17.7 0-32 14.3-32 32s14.3 32 32 32z\"],\n    \"skiing\": [512, 512, [], \"f7c9\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm73 356.1c-9.4-9.4-24.6-9.4-33.9 0-12.1 12.1-30.5 15.4-45.1 8.7l-135.8-70.2 49.2-73.8c12.7-19 10.2-44.5-6-60.6L293 215.7l-107-53.1c-2.9 19.9 3.4 40 17.7 54.4l75.1 75.2-45.9 68.8L35 258.7c-11.7-6-26.2-1.5-32.3 10.3-6.1 11.8-1.5 26.3 10.3 32.3l391.9 202.5c11.9 5.5 24.5 8.1 37.1 8.1 23.2 0 46-9 63-26 9.3-9.3 9.3-24.5 0-33.8zM120 91.6l-11.5 22.5c14.4 7.3 31.2 4.9 42.8-4.8l47.2 23.4c-.1.1-.1.2-.2.3l114.5 56.8 32.4-13 6.4 19.1c4 12.1 12.6 22 24 27.7l58.1 29c15.9 7.9 35 1.5 42.9-14.3 7.9-15.8 1.5-35-14.3-42.9l-52.1-26.1-17.1-51.2c-8.1-24.2-40.9-56.6-84.5-39.2l-81.2 32.5-62.5-31c.3-14.5-7.2-28.6-20.9-35.6l-11.1 21.7h-.2l-34.4-7c-1.8-.4-3.7.2-5 1.7-1.9 2.2-1.7 5.5.5 7.4l26.2 23z\"],\n    \"skiing-nordic\": [576, 512, [], \"f7ca\", \"M336 96c26.5 0 48-21.5 48-48S362.5 0 336 0s-48 21.5-48 48 21.5 48 48 48zm216 320c-13.2 0-24 10.7-24 24 0 13.2-10.8 24-24 24h-69.5L460 285.6c11.7-4.7 20.1-16.2 20.1-29.6 0-17.7-14.3-32-32-32h-44L378 170.8c-12.5-25.5-35.5-44.2-61.8-50.9L245 98.7c-28.3-6.8-57.8-.5-80.8 17.1l-39.7 30.4c-14 10.7-16.7 30.8-5.9 44.9.7.9 1.7 1.3 2.4 2.1L66.9 464H24c-13.2 0-24 10.7-24 24s10.8 24 24 24h480c39.7 0 72-32.3 72-72 0-13.2-10.8-24-24-24zm-260.5 48h-96.9l43.1-91-22-13c-12.1-7.2-21.9-16.9-29.5-27.8L123.7 464H99.5l52.3-261.4c4.1-1 8.1-2.9 11.7-5.6l39.7-30.4c7.7-5.9 17.4-8 25.3-6.1l14.7 4.4-37.5 87.4c-12.6 29.5-1.3 64 26.3 80.3l85 50.2-25.5 81.2zm110.6 0h-43.6l23.6-75.5c5.9-20.8-2.9-43.1-21.6-54.4L299.3 298l31.3-78.3 20.3 41.4c8 16.3 24.9 26.9 43.1 26.9h33.3l-25.2 176z\"],\n    \"skull\": [512, 512, [], \"f54c\", \"M256 0C114.6 0 0 100.3 0 224c0 70.1 36.9 132.6 94.5 173.7 9.6 6.9 15.2 18.1 13.5 29.9l-9.4 66.2c-1.4 9.6 6 18.2 15.7 18.2H192v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h64v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h77.7c9.7 0 17.1-8.6 15.7-18.2l-9.4-66.2c-1.7-11.7 3.8-23 13.5-29.9C475.1 356.6 512 294.1 512 224 512 100.3 397.4 0 256 0zm-96 320c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm192 0c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64z\"],\n    \"skull-crossbones\": [448, 512, [], \"f714\", \"M439.15 453.06L297.17 384l141.99-69.06c7.9-3.95 11.11-13.56 7.15-21.46L432 264.85c-3.95-7.9-13.56-11.11-21.47-7.16L224 348.41 37.47 257.69c-7.9-3.95-17.51-.75-21.47 7.16L1.69 293.48c-3.95 7.9-.75 17.51 7.15 21.46L150.83 384 8.85 453.06c-7.9 3.95-11.11 13.56-7.15 21.47l14.31 28.63c3.95 7.9 13.56 11.11 21.47 7.15L224 419.59l186.53 90.72c7.9 3.95 17.51.75 21.47-7.15l14.31-28.63c3.95-7.91.74-17.52-7.16-21.47zM150 237.28l-5.48 25.87c-2.67 12.62 5.42 24.85 16.45 24.85h126.08c11.03 0 19.12-12.23 16.45-24.85l-5.5-25.87c41.78-22.41 70-62.75 70-109.28C368 57.31 303.53 0 224 0S80 57.31 80 128c0 46.53 28.22 86.87 70 109.28zM280 112c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32zm-112 0c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32z\"],\n    \"slash\": [640, 512, [], \"f715\", \"M594.53 508.63L6.18 53.9c-6.97-5.42-8.23-15.47-2.81-22.45L23.01 6.18C28.43-.8 38.49-2.06 45.47 3.37L633.82 458.1c6.97 5.42 8.23 15.47 2.81 22.45l-19.64 25.27c-5.42 6.98-15.48 8.23-22.46 2.81z\"],\n    \"sleigh\": [640, 512, [], \"f7cc\", \"M612.7 350.7l-9.3-7.4c-6.9-5.5-17-4.4-22.5 2.5l-10 12.5c-5.5 6.9-4.4 17 2.5 22.5l9.3 7.4c5.9 4.7 9.2 11.7 9.2 19.2 0 13.6-11 24.6-24.6 24.6H48c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h516c39 0 73.7-29.3 75.9-68.3 1.4-23.8-8.7-46.3-27.2-61zM32 224c0 59.6 40.9 109.2 96 123.5V400h64v-48h192v48h64v-48c53 0 96-43 96-96v-96c17.7 0 32-14.3 32-32s-14.3-32-32-32h-96v64c0 35.3-28.7 64-64 64h-20.7c-65.8 0-125.9-37.2-155.3-96-29.4-58.8-89.6-96-155.3-96H32C14.3 32 0 46.3 0 64s14.3 32 32 32v128z\"],\n    \"sliders-h\": [512, 512, [], \"f1de\", \"M496 384H160v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h80v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h336c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160h-80v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h336v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h80c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160H288V48c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h208v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm194.8 170.2C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.6-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.4-16.2 38.1 4.2 24.6 20.5z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM112 223.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zm250.8 122.8C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.3 24.6 20.5zm6.2-118.3l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.6 8.6-11 11.9-15.1 4.5z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm158.5 16.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.7 11.1-11.4 18.3-19.8 10.8l-9.7-8.5zM157.8 325.8C180.2 352.7 213 368 248 368s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.2 24.6 20.5C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11.2-36.7 24.6-20.4z\"],\n    \"smog\": [640, 512, [], \"f75f\", \"M624 368H80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm-480 96H16c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h128c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm416 0H224c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h336c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zM144 288h156.1c22.5 19.7 51.6 32 83.9 32s61.3-12.3 83.9-32H528c61.9 0 112-50.1 112-112S589.9 64 528 64c-18 0-34.7 4.6-49.7 12.1C454 31 406.8 0 352 0c-41 0-77.8 17.3-104 44.8C221.8 17.3 185 0 144 0 64.5 0 0 64.5 0 144s64.5 144 144 144z\"],\n    \"smoking\": [640, 512, [], \"f48d\", \"M632 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8zM553.3 87.1c-5.7-3.8-9.3-10-9.3-16.8V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v62.3c0 22 10.2 43.4 28.6 55.4 42.2 27.3 67.4 73.8 67.4 124V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-65.5-32.4-126.2-86.7-162.6zM432 352H48c-26.5 0-48 21.5-48 48v64c0 26.5 21.5 48 48 48h384c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zm-32 112H224v-64h176v64zm87.7-322.4C463.8 125 448 99.3 448 70.3V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v66.4c0 43.7 24.6 81.6 60.3 106.7 22.4 15.7 35.7 41.2 35.7 68.6V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-43.3-21-83.4-56.3-108.1zM536 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8z\"],\n    \"smoking-ban\": [512, 512, [], \"f54d\", \"M96 304c0 8.8 7.2 16 16 16h117.5l-96-96H112c-8.8 0-16 7.2-16 16v64zM256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm0 448c-105.9 0-192-86.1-192-192 0-41.4 13.3-79.7 35.7-111.1l267.4 267.4C335.7 434.7 297.4 448 256 448zm45.2-192H384v32h-50.8l-32-32zm111.1 111.1L365.2 320H400c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16H269.2L144.9 99.7C176.3 77.3 214.6 64 256 64c105.9 0 192 86.1 192 192 0 41.4-13.3 79.7-35.7 111.1zM320.6 128c-15.6 0-28.6-11.2-31.4-25.9-.7-3.6-4-6.1-7.7-6.1h-16.2c-5 0-8.7 4.5-8 9.4 4.6 30.9 31.2 54.6 63.3 54.6 15.6 0 28.6 11.2 31.4 25.9.7 3.6 4 6.1 7.7 6.1h16.2c5 0 8.7-4.5 8-9.4-4.6-30.9-31.2-54.6-63.3-54.6z\"],\n    \"sms\": [512, 512, [], \"f7cd\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7 1.3 3 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128.2 304H116c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H156c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-19 38.6-42.4 38.6zm191.8-8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-68.2l-24.8 55.8c-2.9 5.9-11.4 5.9-14.3 0L224 227.8V296c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V192c0-8.8 7.2-16 16-16h16c6.1 0 11.6 3.4 14.3 8.8l17.7 35.4 17.7-35.4c2.7-5.4 8.3-8.8 14.3-8.8h16c8.8 0 16 7.2 16 16v104zm48.3 8H356c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H396c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-18.9 38.6-42.3 38.6z\"],\n    \"snowboarding\": [512, 512, [], \"f7ce\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm28.8 153.6c5.8 4.3 12.5 6.4 19.2 6.4 9.7 0 19.3-4.4 25.6-12.8 10.6-14.1 7.8-34.2-6.4-44.8l-111.4-83.5c-13.8-10.3-29.1-18.4-45.4-23.8l-63.7-21.2-26.1-52.1C244.7 2 225.5-4.4 209.7 3.5c-15.8 7.9-22.2 27.1-14.3 42.9l29.1 58.1c5.7 11.4 15.6 19.9 27.7 24l16.4 5.5-41.2 20.6c-21.8 10.9-35.4 32.8-35.4 57.2v53.1l-74.1 24.7c-16.8 5.6-25.8 23.7-20.2 40.5 1.7 5.2 4.9 9.4 8.7 12.9l-38.7-14.1c-9.7-3.5-17.4-10.6-21.8-20-5.6-12-19.9-17.2-31.9-11.6s-17.2 19.9-11.6 31.9c9.8 21 27.1 36.9 48.9 44.8l364.8 132.7c9.7 3.5 19.7 5.3 29.7 5.3 12.5 0 24.9-2.7 36.5-8.2 12-5.6 17.2-19.9 11.6-31.9S474 454.7 462 460.3c-9.3 4.4-19.8 4.8-29.5 1.3l-90.8-33.1c8.7-4.1 15.6-11.8 17.8-21.9l21.9-102c3.9-18.2-3.2-37.2-18.1-48.4l-52-39 66-30.5 83.5 62.9zm-144.4 51.7l-19.7 92c-1.5 7.1-.1 13.9 2.8 20l-169.4-61.6c2.7-.2 5.4-.4 8-1.3l85-28.4c19.6-6.5 32.8-24.8 32.8-45.5V256l60.5 45.3z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.3 345.2l-33.8-19.5 26-7c8.2-2.2 13.1-10.7 10.9-18.9l-4-14.9c-2.2-8.2-10.7-13.1-18.9-10.9l-70.8 19-63.9-37 63.8-36.9 70.8 19c8.2 2.2 16.7-2.7 18.9-10.9l4-14.9c2.2-8.2-2.7-16.7-10.9-18.9l-26-7 33.8-19.5c7.4-4.3 9.9-13.7 5.7-21.1L430.4 119c-4.3-7.4-13.7-9.9-21.1-5.7l-33.8 19.5 7-26c2.2-8.2-2.7-16.7-10.9-18.9l-14.9-4c-8.2-2.2-16.7 2.7-18.9 10.9l-19 70.8-62.8 36.2v-77.5l53.7-53.7c6.2-6.2 6.2-16.4 0-22.6l-11.3-11.3c-6.2-6.2-16.4-6.2-22.6 0L256 56.4V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v40.4l-19.7-19.7c-6.2-6.2-16.4-6.2-22.6 0L138.3 48c-6.3 6.2-6.3 16.4 0 22.6l53.7 53.7v77.5l-62.8-36.2-19-70.8c-2.2-8.2-10.7-13.1-18.9-10.9l-14.9 4c-8.2 2.2-13.1 10.7-10.9 18.9l7 26-33.8-19.5c-7.4-4.3-16.8-1.7-21.1 5.7L2.1 145.7c-4.3 7.4-1.7 16.8 5.7 21.1l33.8 19.5-26 7c-8.3 2.2-13.2 10.7-11 19l4 14.9c2.2 8.2 10.7 13.1 18.9 10.9l70.8-19 63.8 36.9-63.8 36.9-70.8-19c-8.2-2.2-16.7 2.7-18.9 10.9l-4 14.9c-2.2 8.2 2.7 16.7 10.9 18.9l26 7-33.8 19.6c-7.4 4.3-9.9 13.7-5.7 21.1l15.5 26.8c4.3 7.4 13.7 9.9 21.1 5.7l33.8-19.5-7 26c-2.2 8.2 2.7 16.7 10.9 18.9l14.9 4c8.2 2.2 16.7-2.7 18.9-10.9l19-70.8 62.8-36.2v77.5l-53.7 53.7c-6.3 6.2-6.3 16.4 0 22.6l11.3 11.3c6.2 6.2 16.4 6.2 22.6 0l19.7-19.7V496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-40.4l19.7 19.7c6.2 6.2 16.4 6.2 22.6 0l11.3-11.3c6.2-6.2 6.2-16.4 0-22.6L256 387.7v-77.5l62.8 36.2 19 70.8c2.2 8.2 10.7 13.1 18.9 10.9l14.9-4c8.2-2.2 13.1-10.7 10.9-18.9l-7-26 33.8 19.5c7.4 4.3 16.8 1.7 21.1-5.7l15.5-26.8c4.3-7.3 1.8-16.8-5.6-21z\"],\n    \"snowman\": [512, 512, [], \"f7d0\", \"M510.9 152.3l-5.9-14.5c-3.3-8-12.6-11.9-20.8-8.7L456 140.6v-29c0-8.6-7.2-15.6-16-15.6h-16c-8.8 0-16 7-16 15.6v46.9c0 .5.3 1 .3 1.5l-56.4 23c-5.9-10-13.3-18.9-22-26.6 13.6-16.6 22-37.4 22-60.5 0-53-43-96-96-96s-96 43-96 96c0 23.1 8.5 43.9 22 60.5-8.7 7.7-16 16.6-22 26.6l-56.4-23c.1-.5.3-1 .3-1.5v-46.9C104 103 96.8 96 88 96H72c-8.8 0-16 7-16 15.6v29l-28.1-11.5c-8.2-3.2-17.5.7-20.8 8.7l-5.9 14.5c-3.3 8 .7 17.1 8.9 20.3l135.2 55.2c-.4 4-1.2 8-1.2 12.2 0 10.1 1.7 19.6 4.2 28.9C120.9 296.4 104 334.2 104 376c0 54 28.4 100.9 70.8 127.8 9.3 5.9 20.3 8.2 31.3 8.2h99.2c13.3 0 26.3-4.1 37.2-11.7 46.5-32.3 74.4-89.4 62.9-152.6-5.5-30.2-20.5-57.6-41.6-79 2.5-9.2 4.2-18.7 4.2-28.7 0-4.2-.8-8.1-1.2-12.2L502 172.6c8.1-3.1 12.1-12.2 8.9-20.3zM224 96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 272c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-88s-16-23.2-16-32 7.2-16 16-16 16 7.2 16 16-16 32-16 32zm32-56c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"snowplow\": [640, 512, [], \"f7d2\", \"M120 376c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm238.6 49.4c-14.5-14.5-22.6-34.1-22.6-54.6V269.2c0-20.5 8.1-40.1 22.6-54.6l36.7-36.7c6.2-6.2 6.2-16.4 0-22.6l-22.6-22.6c-6.2-6.2-16.4-6.2-22.6 0l-36.7 36.7c-26.5 26.5-41.4 62.4-41.4 99.9V288h-64v-50.9c0-8.7-1.8-17.2-5.2-25.2L364.5 29.1C356.9 11.4 339.6 0 320.3 0H176c-26.5 0-48 21.5-48 48v112h-16c-26.5 0-48 21.5-48 48v91.2C26.3 317.2 0 355.4 0 400c0 61.9 50.1 112 112 112h256c61.9 0 112-50.1 112-112 0-17.3-4.2-33.4-11.2-48H512v18.7c0 37.5 14.9 73.4 41.4 99.9l36.7 36.7c6.2 6.2 16.4 6.2 22.6 0l22.6-22.6c6.2-6.2 6.2-16.4 0-22.6l-36.7-36.7zM192 64h117.8l68.6 160H256l-64-64V64zm176 384H112c-26.5 0-48-21.5-48-48s21.5-48 48-48h256c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"socks\": [512, 512, [], \"f696\", \"M214.66 311.01L288 256V96H128v176l-86.65 64.61c-39.4 29.56-53.86 84.42-29.21 127.06C30.39 495.25 63.27 512 96.08 512c20.03 0 40.25-6.25 57.52-19.2l21.86-16.39c-29.85-55.38-13.54-125.84 39.2-165.4zM288 32c0-11.05 3.07-21.3 8.02-30.38C293.4.92 290.85 0 288 0H160c-17.67 0-32 14.33-32 32v32h160V32zM480 0H352c-17.67 0-32 14.33-32 32v32h192V32c0-17.67-14.33-32-32-32zM320 272l-86.13 64.61c-39.4 29.56-53.86 84.42-29.21 127.06 18.25 31.58 50.61 48.33 83.42 48.33 20.03 0 40.25-6.25 57.52-19.2l115.2-86.4A127.997 127.997 0 0 0 512 304V96H320v176z\"],\n    \"solar-panel\": [640, 512, [], \"f5ba\", \"M431.98 448.01l-47.97.05V416h-128v32.21l-47.98.05c-8.82.01-15.97 7.16-15.98 15.99l-.05 31.73c-.01 8.85 7.17 16.03 16.02 16.02l223.96-.26c8.82-.01 15.97-7.16 15.98-15.98l.04-31.73c.01-8.85-7.17-16.03-16.02-16.02zM585.2 26.74C582.58 11.31 568.99 0 553.06 0H86.93C71 0 57.41 11.31 54.79 26.74-3.32 369.16.04 348.08.03 352c-.03 17.32 14.29 32 32.6 32h574.74c18.23 0 32.51-14.56 32.59-31.79.02-4.08 3.35 16.95-54.76-325.47zM259.83 64h120.33l9.77 96H250.06l9.77-96zm-75.17 256H71.09L90.1 208h105.97l-11.41 112zm16.29-160H98.24l16.29-96h96.19l-9.77 96zm32.82 160l11.4-112h149.65l11.4 112H233.77zm195.5-256h96.19l16.29 96H439.04l-9.77-96zm26.06 256l-11.4-112H549.9l19.01 112H455.33z\"],\n    \"sort\": [320, 512, [], \"f0dc\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41zm255-105L177 64c-9.4-9.4-24.6-9.4-33.9 0L24 183c-15.1 15.1-4.4 41 17 41h238c21.4 0 32.1-25.9 17-41z\"],\n    \"sort-alpha-down\": [448, 512, [], \"f15d\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm240-64H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-down-alt\": [448, 512, [], \"f881\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm112-128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-alpha-up\": [448, 512, [], \"f15e\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm400 128H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-up-alt\": [448, 512, [], \"f882\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm272 64h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-amount-down\": [512, 512, [], \"f160\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-128-64h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm256-192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-down-alt\": [512, 512, [], \"f884\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm-64 0h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-amount-up\": [512, 512, [], \"f161\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.77 160 16 160zm416 0H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-up-alt\": [512, 512, [], \"f885\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.39-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160z\"],\n    \"sort-down\": [320, 512, [], \"f0dd\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41z\"],\n    \"sort-numeric-down\": [448, 512, [], \"f162\", \"M304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zm26.15 162.91a79 79 0 0 0-55 54.17c-14.25 51.05 21.21 97.77 68.85 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zm-176-4h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-numeric-down-alt\": [448, 512, [], \"f886\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm224 64h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-numeric-up\": [448, 512, [], \"f163\", \"M330.17 258.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zM304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zM107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31z\"],\n    \"sort-numeric-up-alt\": [448, 512, [], \"f887\", \"M107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31zM400 416h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-up\": [320, 512, [], \"f0de\", \"M279 224H41c-21.4 0-32.1-25.9-17-41L143 64c9.4-9.4 24.6-9.4 33.9 0l119 119c15.2 15.1 4.5 41-16.9 41z\"],\n    \"spa\": [576, 512, [], \"f5bb\", \"M568.25 192c-29.04.13-135.01 6.16-213.84 83-33.12 29.63-53.36 63.3-66.41 94.86-13.05-31.56-33.29-65.23-66.41-94.86-78.83-76.84-184.8-82.87-213.84-83-4.41-.02-7.79 3.4-7.75 7.82.23 27.92 7.14 126.14 88.77 199.3C172.79 480.94 256 480 288 480s115.19.95 199.23-80.88c81.64-73.17 88.54-171.38 88.77-199.3.04-4.42-3.34-7.84-7.75-7.82zM287.98 302.6c12.82-18.85 27.6-35.78 44.09-50.52 19.09-18.61 39.58-33.3 60.26-45.18-16.44-70.5-51.72-133.05-96.73-172.22-4.11-3.58-11.02-3.58-15.14 0-44.99 39.14-80.27 101.63-96.74 172.07 20.37 11.7 40.5 26.14 59.22 44.39a282.768 282.768 0 0 1 45.04 51.46z\"],\n    \"space-shuttle\": [640, 512, [], \"f197\", \"M592.604 208.244C559.735 192.836 515.777 184 472 184H186.327c-4.952-6.555-10.585-11.978-16.72-16H376C229.157 137.747 219.403 32 96.003 32H96v128H80V32c-26.51 0-48 28.654-48 64v64c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v16c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v64c0 35.346 21.49 64 48 64V352h16v128h.003c123.4 0 133.154-105.747 279.997-136H169.606c6.135-4.022 11.768-9.445 16.72-16H472c43.777 0 87.735-8.836 120.604-24.244C622.282 289.845 640 271.992 640 256s-17.718-33.845-47.396-47.756zM488 296a8 8 0 0 1-8-8v-64a8 8 0 0 1 8-8c31.909 0 31.942 80 0 80z\"],\n    \"spell-check\": [576, 512, [], \"f891\", \"M272 256h91.36c43.2 0 82-32.2 84.51-75.34a79.82 79.82 0 0 0-25.26-63.07 79.81 79.81 0 0 0 9.06-44.91C427.9 30.57 389.3 0 347 0h-75a16 16 0 0 0-16 16v224a16 16 0 0 0 16 16zm40-200h40a24 24 0 0 1 0 48h-40zm0 96h56a24 24 0 0 1 0 48h-56zM155.12 22.25A32 32 0 0 0 124.64 0H99.36a32 32 0 0 0-30.48 22.25L.59 235.73A16 16 0 0 0 16 256h24.93a16 16 0 0 0 15.42-11.73L68.29 208h87.42l11.94 36.27A16 16 0 0 0 183.07 256H208a16 16 0 0 0 15.42-20.27zM89.37 144L112 75.3l22.63 68.7zm482 132.48l-45.21-45.3a15.88 15.88 0 0 0-22.59 0l-151.5 151.5-55.41-55.5a15.88 15.88 0 0 0-22.59 0l-45.3 45.3a16 16 0 0 0 0 22.59l112 112.21a15.89 15.89 0 0 0 22.6 0l208-208.21a16 16 0 0 0-.02-22.59z\"],\n    \"spider\": [576, 512, [], \"f717\", \"M151.17 167.35L177.1 176h4.67l5.22-26.12c.72-3.58 1.8-7.58 3.21-11.79l-20.29-40.58 23.8-71.39c2.79-8.38-1.73-17.44-10.12-20.24L168.42.82c-8.38-2.8-17.45 1.73-20.24 10.12l-25.89 77.68a32.04 32.04 0 0 0 1.73 24.43l27.15 54.3zm422.14 182.03l-52.75-79.12a32.002 32.002 0 0 0-26.62-14.25H416l68.99-24.36a32.03 32.03 0 0 0 16.51-12.61l53.6-80.41c4.9-7.35 2.91-17.29-4.44-22.19l-13.31-8.88c-7.35-4.9-17.29-2.91-22.19 4.44l-50.56 75.83L404.1 208H368l-10.37-51.85C355.44 145.18 340.26 96 288 96c-52.26 0-67.44 49.18-69.63 60.15L208 208h-36.1l-60.49-20.17L60.84 112c-4.9-7.35-14.83-9.34-22.19-4.44l-13.31 8.88c-7.35 4.9-9.34 14.83-4.44 22.19l53.6 80.41a32.03 32.03 0 0 0 16.51 12.61L160 256H82.06a32.02 32.02 0 0 0-26.63 14.25L2.69 349.38c-4.9 7.35-2.92 17.29 4.44 22.19l13.31 8.88c7.35 4.9 17.29 2.91 22.19-4.44l48-72h47.06l-60.83 97.33A31.988 31.988 0 0 0 72 418.3V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-73.11l74.08-118.53c-1.01 14.05-2.08 28.11-2.08 42.21C192 399.64 232.76 448 288 448s96-48.36 96-101.43c0-14.1-1.08-28.16-2.08-42.21L456 422.89V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-77.71c0-6-1.69-11.88-4.86-16.96L438.31 304h47.06l48 72c4.9 7.35 14.84 9.34 22.19 4.44l13.31-8.88c7.36-4.9 9.34-14.83 4.44-22.18zM406.09 97.51l-20.29 40.58c1.41 4.21 2.49 8.21 3.21 11.79l5.22 26.12h4.67l25.93-8.65 27.15-54.3a31.995 31.995 0 0 0 1.73-24.43l-25.89-77.68C425.03 2.56 415.96-1.98 407.58.82l-15.17 5.06c-8.38 2.8-12.91 11.86-10.12 20.24l23.8 71.39z\"],\n    \"spinner\": [512, 512, [], \"f110\", \"M304 48c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-48 368c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm208-208c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zM96 256c0-26.51-21.49-48-48-48S0 229.49 0 256s21.49 48 48 48 48-21.49 48-48zm12.922 99.078c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.491-48-48-48zm294.156 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.49-48-48-48zM108.922 60.922c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.491-48-48-48z\"],\n    \"splotch\": [512, 512, [], \"f5bc\", \"M472.29 195.89l-67.06-22.95c-19.28-6.6-33.54-20.92-38.14-38.3L351.1 74.19c-11.58-43.77-76.57-57.13-109.98-22.62l-46.14 47.67c-13.26 13.71-33.54 20.93-54.2 19.31l-71.88-5.62c-52.05-4.07-86.93 44.88-59.03 82.83l38.54 52.42c11.08 15.07 12.82 33.86 4.64 50.24L24.62 355.4c-20.59 41.25 22.84 84.87 73.49 73.81l69.96-15.28c20.11-4.39 41.45 0 57.07 11.73l54.32 40.83c39.32 29.56 101.04 7.57 104.45-37.22l4.7-61.86c1.35-17.79 12.8-33.86 30.63-42.99l62-31.74c44.88-22.96 39.59-80.17-8.95-96.79z\"],\n    \"spray-can\": [512, 512, [], \"f5bd\", \"M224 32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96h128V32zm256 96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-256 32H96c-53.02 0-96 42.98-96 96v224c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V256c0-53.02-42.98-96-96-96zm-64 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zM480 96c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm-96 32c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-96-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 0c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 192c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"square-full\": [512, 512, [], \"f45c\", \"M512 512H0V0h512v512z\"],\n    \"square-root-alt\": [576, 512, [], \"f698\", \"M571.31 251.31l-22.62-22.62c-6.25-6.25-16.38-6.25-22.63 0L480 274.75l-46.06-46.06c-6.25-6.25-16.38-6.25-22.63 0l-22.62 22.62c-6.25 6.25-6.25 16.38 0 22.63L434.75 320l-46.06 46.06c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L480 365.25l46.06 46.06c6.25 6.25 16.38 6.25 22.63 0l22.62-22.62c6.25-6.25 6.25-16.38 0-22.63L525.25 320l46.06-46.06c6.25-6.25 6.25-16.38 0-22.63zM552 0H307.65c-14.54 0-27.26 9.8-30.95 23.87l-84.79 322.8-58.41-106.1A32.008 32.008 0 0 0 105.47 224H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h43.62l88.88 163.73C168.99 503.5 186.3 512 204.94 512c17.27 0 44.44-9 54.28-41.48L357.03 96H552c13.25 0 24-10.75 24-24V24c0-13.26-10.75-24-24-24z\"],\n    \"stamp\": [512, 512, [], \"f5bf\", \"M32 512h448v-64H32v64zm384-256h-66.56c-16.26 0-29.44-13.18-29.44-29.44v-9.46c0-27.37 8.88-53.41 21.46-77.72 9.11-17.61 12.9-38.39 9.05-60.42-6.77-38.78-38.47-70.7-77.26-77.45C212.62-9.04 160 37.33 160 96c0 14.16 3.12 27.54 8.69 39.58C182.02 164.43 192 194.7 192 226.49v.07c0 16.26-13.18 29.44-29.44 29.44H96c-53.02 0-96 42.98-96 96v32c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-32c0-53.02-42.98-96-96-96z\"],\n    \"star\": [576, 512, [], \"f005\", \"M259.3 17.8L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0z\"],\n    \"star-and-crescent\": [512, 512, [], \"f699\", \"M340.47 466.36c-1.45 0-6.89.46-9.18.46-116.25 0-210.82-94.57-210.82-210.82S215.04 45.18 331.29 45.18c2.32 0 7.7.46 9.18.46 7.13 0 13.33-5.03 14.75-12.07 1.46-7.25-2.55-14.49-9.47-17.09C316.58 5.54 286.39 0 256 0 114.84 0 0 114.84 0 256s114.84 256 256 256c30.23 0 60.28-5.49 89.32-16.32 5.96-2.02 10.28-7.64 10.28-14.26 0-8.09-6.39-15.06-15.13-15.06zm162.99-252.5l-76.38-11.1-34.16-69.21c-1.83-3.7-5.38-5.55-8.93-5.55s-7.1 1.85-8.93 5.55l-34.16 69.21-76.38 11.1c-8.17 1.18-11.43 11.22-5.52 16.99l55.27 53.87-13.05 76.07c-1.11 6.44 4.01 11.66 9.81 11.66 1.53 0 3.11-.36 4.64-1.17L384 335.37l68.31 35.91c1.53.8 3.11 1.17 4.64 1.17 5.8 0 10.92-5.23 9.81-11.66l-13.05-76.07 55.27-53.87c5.91-5.77 2.65-15.81-5.52-16.99z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6V0z\"],\n    \"star-half-alt\": [536, 512, [], \"f5c0\", \"M508.55 171.51L362.18 150.2 296.77 17.81C290.89 5.98 279.42 0 267.95 0c-11.4 0-22.79 5.9-28.69 17.81l-65.43 132.38-146.38 21.29c-26.25 3.8-36.77 36.09-17.74 54.59l105.89 103-25.06 145.48C86.98 495.33 103.57 512 122.15 512c4.93 0 10-1.17 14.87-3.75l130.95-68.68 130.94 68.7c4.86 2.55 9.92 3.71 14.83 3.71 18.6 0 35.22-16.61 31.66-37.4l-25.03-145.49 105.91-102.98c19.04-18.5 8.52-50.8-17.73-54.6zm-121.74 123.2l-18.12 17.62 4.28 24.88 19.52 113.45-102.13-53.59-22.38-11.74.03-317.19 51.03 103.29 11.18 22.63 25.01 3.64 114.23 16.63-82.65 80.38z\"],\n    \"star-of-david\": [464, 512, [], \"f69a\", \"M405.68 256l53.21-89.39C473.3 142.4 455.48 112 426.88 112H319.96l-55.95-93.98C256.86 6.01 244.43 0 232 0s-24.86 6.01-32.01 18.02L144.04 112H37.11c-28.6 0-46.42 30.4-32.01 54.61L58.32 256 5.1 345.39C-9.31 369.6 8.51 400 37.11 400h106.93l55.95 93.98C207.14 505.99 219.57 512 232 512s24.86-6.01 32.01-18.02L319.96 400h106.93c28.6 0 46.42-30.4 32.01-54.61L405.68 256zm-12.78-88l-19.8 33.26L353.3 168h39.6zm-52.39 88l-52.39 88H175.88l-52.39-88 52.38-88h112.25l52.39 88zM232 73.72L254.79 112h-45.57L232 73.72zM71.1 168h39.6l-19.8 33.26L71.1 168zm0 176l19.8-33.26L110.7 344H71.1zM232 438.28L209.21 400h45.57L232 438.28zM353.29 344l19.8-33.26L392.9 344h-39.61z\"],\n    \"star-of-life\": [480, 512, [], \"f621\", \"M471.99 334.43L336.06 256l135.93-78.43c7.66-4.42 10.28-14.2 5.86-21.86l-32.02-55.43c-4.42-7.65-14.21-10.28-21.87-5.86l-135.93 78.43V16c0-8.84-7.17-16-16.01-16h-64.04c-8.84 0-16.01 7.16-16.01 16v156.86L56.04 94.43c-7.66-4.42-17.45-1.79-21.87 5.86L2.15 155.71c-4.42 7.65-1.8 17.44 5.86 21.86L143.94 256 8.01 334.43c-7.66 4.42-10.28 14.21-5.86 21.86l32.02 55.43c4.42 7.65 14.21 10.27 21.87 5.86l135.93-78.43V496c0 8.84 7.17 16 16.01 16h64.04c8.84 0 16.01-7.16 16.01-16V339.14l135.93 78.43c7.66 4.42 17.45 1.8 21.87-5.86l32.02-55.43c4.42-7.65 1.8-17.43-5.86-21.85z\"],\n    \"step-backward\": [448, 512, [], \"f048\", \"M64 468V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v176.4l195.5-181C352.1 22.3 384 36.6 384 64v384c0 27.4-31.9 41.7-52.5 24.6L136 292.7V468c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12z\"],\n    \"step-forward\": [448, 512, [], \"f051\", \"M384 44v424c0 6.6-5.4 12-12 12h-48c-6.6 0-12-5.4-12-12V291.6l-195.5 181C95.9 489.7 64 475.4 64 448V64c0-27.4 31.9-41.7 52.5-24.6L312 219.3V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12z\"],\n    \"stethoscope\": [512, 512, [], \"f0f1\", \"M447.1 112c-34.2.5-62.3 28.4-63 62.6-.5 24.3 12.5 45.6 32 56.8V344c0 57.3-50.2 104-112 104-60 0-109.2-44.1-111.9-99.2C265 333.8 320 269.2 320 192V36.6c0-11.4-8.1-21.3-19.3-23.5L237.8.5c-13-2.6-25.6 5.8-28.2 18.8L206.4 35c-2.6 13 5.8 25.6 18.8 28.2l30.7 6.1v121.4c0 52.9-42.2 96.7-95.1 97.2-53.4.5-96.9-42.7-96.9-96V69.4l30.7-6.1c13-2.6 21.4-15.2 18.8-28.2l-3.1-15.7C107.7 6.4 95.1-2 82.1.6L19.3 13C8.1 15.3 0 25.1 0 36.6V192c0 77.3 55.1 142 128.1 156.8C130.7 439.2 208.6 512 304 512c97 0 176-75.4 176-168V231.4c19.1-11.1 32-31.7 32-55.4 0-35.7-29.2-64.5-64.9-64zm.9 80c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M312 320h136V56c0-13.3-10.7-24-24-24H24C10.7 32 0 42.7 0 56v400c0 13.3 10.7 24 24 24h264V344c0-13.2 10.8-24 24-24zm129 55l-98 98c-4.5 4.5-10.6 7-17 7h-6V352h128v6.1c0 6.3-2.5 12.4-7 16.9z\"],\n    \"stop\": [448, 512, [], \"f04d\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm96 328c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16v160z\"],\n    \"stopwatch\": [448, 512, [], \"f2f2\", \"M432 304c0 114.9-93.1 208-208 208S16 418.9 16 304c0-104 76.3-190.2 176-205.5V64h-28c-6.6 0-12-5.4-12-12V12c0-6.6 5.4-12 12-12h120c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-28v34.5c37.5 5.8 71.7 21.6 99.7 44.6l27.5-27.5c4.7-4.7 12.3-4.7 17 0l28.3 28.3c4.7 4.7 4.7 12.3 0 17l-29.4 29.4-.6.6C419.7 223.3 432 262.2 432 304zm-176 36V188.5c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12V340c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"store\": [616, 512, [], \"f54e\", \"M602 118.6L537.1 15C531.3 5.7 521 0 510 0H106C95 0 84.7 5.7 78.9 15L14 118.6c-33.5 53.5-3.8 127.9 58.8 136.4 4.5.6 9.1.9 13.7.9 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18.1 20.1 44.3 33.1 73.8 33.1 4.7 0 9.2-.3 13.7-.9 62.8-8.4 92.6-82.8 59-136.4zM529.5 288c-10 0-19.9-1.5-29.5-3.8V384H116v-99.8c-9.6 2.2-19.5 3.8-29.5 3.8-6 0-12.1-.4-18-1.2-5.6-.8-11.1-2.1-16.4-3.6V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32V283.2c-5.4 1.6-10.8 2.9-16.4 3.6-6.1.8-12.1 1.2-18.2 1.2z\"],\n    \"store-alt\": [640, 512, [], \"f54f\", \"M320 384H128V224H64v256c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V224h-64v160zm314.6-241.8l-85.3-128c-6-8.9-16-14.2-26.7-14.2H117.4c-10.7 0-20.7 5.3-26.6 14.2l-85.3 128c-14.2 21.3 1 49.8 26.6 49.8H608c25.5 0 40.7-28.5 26.6-49.8zM512 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V224h-64v272z\"],\n    \"stream\": [512, 512, [], \"f550\", \"M16 128h416c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H16C7.16 32 0 39.16 0 48v64c0 8.84 7.16 16 16 16zm480 80H80c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm-64 176H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16z\"],\n    \"street-view\": [512, 512, [], \"f21d\", \"M367.9 329.76c-4.62 5.3-9.78 10.1-15.9 13.65v22.94c66.52 9.34 112 28.05 112 49.65 0 30.93-93.12 56-208 56S48 446.93 48 416c0-21.6 45.48-40.3 112-49.65v-22.94c-6.12-3.55-11.28-8.35-15.9-13.65C58.87 345.34 0 378.05 0 416c0 53.02 114.62 96 256 96s256-42.98 256-96c0-37.95-58.87-70.66-144.1-86.24zM256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-64 192v96c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-96c17.67 0 32-14.33 32-32v-96c0-26.51-21.49-48-48-48h-11.8c-11.07 5.03-23.26 8-36.2 8s-25.13-2.97-36.2-8H208c-26.51 0-48 21.49-48 48v96c0 17.67 14.33 32 32 32z\"],\n    \"strikethrough\": [512, 512, [], \"f0cc\", \"M496 224H293.9l-87.17-26.83A43.55 43.55 0 0 1 219.55 112h66.79A49.89 49.89 0 0 1 331 139.58a16 16 0 0 0 21.46 7.15l42.94-21.47a16 16 0 0 0 7.16-21.46l-.53-1A128 128 0 0 0 287.51 32h-68a123.68 123.68 0 0 0-123 135.64c2 20.89 10.1 39.83 21.78 56.36H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-180.24 96A43 43 0 0 1 336 356.45 43.59 43.59 0 0 1 292.45 400h-66.79A49.89 49.89 0 0 1 181 372.42a16 16 0 0 0-21.46-7.15l-42.94 21.47a16 16 0 0 0-7.16 21.46l.53 1A128 128 0 0 0 224.49 480h68a123.68 123.68 0 0 0 123-135.64 114.25 114.25 0 0 0-5.34-24.36z\"],\n    \"stroopwafel\": [512, 512, [], \"f551\", \"M188.12 210.74L142.86 256l45.25 45.25L233.37 256l-45.25-45.26zm113.13-22.62L256 142.86l-45.25 45.25L256 233.37l45.25-45.25zm-90.5 135.76L256 369.14l45.26-45.26L256 278.63l-45.25 45.25zM256 0C114.62 0 0 114.62 0 256s114.62 256 256 256 256-114.62 256-256S397.38 0 256 0zm186.68 295.6l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-28.29-28.29-45.25 45.25 33.94 33.94 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-33.94-33.94-45.26 45.26 28.29 28.29c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0L256 414.39l-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l28.29-28.29-45.25-45.26-33.94 33.94 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 33.94-33.94-45.25-45.25-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0L69.32 295.6c-3.12-3.12-3.12-8.19 0-11.31L97.61 256l-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l28.29 28.29 45.25-45.26-33.94-33.94-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 33.94 33.94 45.26-45.25-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0L256 97.61l28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-28.29 28.29 45.26 45.25 33.94-33.94-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-33.94 33.94 45.25 45.26 28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31L414.39 256l28.29 28.28a8.015 8.015 0 0 1 0 11.32zM278.63 256l45.26 45.25L369.14 256l-45.25-45.26L278.63 256z\"],\n    \"subscript\": [512, 512, [], \"f12c\", \"M496 448h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 352h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"subway\": [448, 512, [], \"f239\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zM200 232V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm200 0V120c0-13.255-10.745-24-24-24H272c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm-48 56c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm-256 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"suitcase\": [512, 512, [], \"f0f2\", \"M128 480h256V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v400zm64-384h128v32H192V96zm320 80v256c0 26.5-21.5 48-48 48h-48V128h48c26.5 0 48 21.5 48 48zM96 480H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h48v352z\"],\n    \"suitcase-rolling\": [384, 512, [], \"f5c1\", \"M336 160H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h16v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h128v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h16c26.51 0 48-21.49 48-48V208c0-26.51-21.49-48-48-48zm-16 216c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zM144 48h96v80h48V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v80h48V48z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M256 160c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm246.4 80.5l-94.7-47.3 33.5-100.4c4.5-13.6-8.4-26.5-21.9-21.9l-100.4 33.5-47.4-94.8c-6.4-12.8-24.6-12.8-31 0l-47.3 94.7L92.7 70.8c-13.6-4.5-26.5 8.4-21.9 21.9l33.5 100.4-94.7 47.4c-12.8 6.4-12.8 24.6 0 31l94.7 47.3-33.5 100.5c-4.5 13.6 8.4 26.5 21.9 21.9l100.4-33.5 47.3 94.7c6.4 12.8 24.6 12.8 31 0l47.3-94.7 100.4 33.5c13.6 4.5 26.5-8.4 21.9-21.9l-33.5-100.4 94.7-47.3c13-6.5 13-24.7.2-31.1zm-155.9 106c-49.9 49.9-131.1 49.9-181 0-49.9-49.9-49.9-131.1 0-181 49.9-49.9 131.1-49.9 181 0 49.9 49.9 49.9 131.1 0 181z\"],\n    \"superscript\": [512, 512, [], \"f12b\", \"M496 160h-16V16a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 64h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm112 208c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm80-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"swatchbook\": [511, 512, [], \"f5c3\", \"M479.06 320H372.29L186.15 506.51c-2.06 2.07-4.49 3.58-6.67 5.49h299.58c17.64 0 31.94-14.33 31.94-32V352c0-17.67-14.3-32-31.94-32zm-44.5-152.9l-90.33-90.51c-12.47-12.5-32.69-12.5-45.17 0l-75.5 75.65V416c0 2.96-.67 5.73-.87 8.64l211.87-212.28c12.47-12.5 12.47-32.77 0-45.26zM191.62 32c0-17.67-14.3-32-31.94-32H31.94C14.3 0 0 14.33 0 32v384c0 53.02 42.9 96 95.81 96s95.81-42.98 95.81-96V32zM95.81 440c-13.23 0-23.95-10.75-23.95-24 0-13.26 10.73-24 23.95-24s23.95 10.74 23.95 24c.01 13.25-10.72 24-23.95 24zm31.94-184H63.88v-64h63.88v64zm0-128H63.88V64h63.88v64z\"],\n    \"swimmer\": [640, 512, [], \"f5c4\", \"M189.61 310.58c3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c16.02-14.77 34.5-22.58 53.46-22.58h16.3c18.96 0 37.45 7.81 53.46 22.58 3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c14.86-13.71 31.88-21.12 49.39-22.16l-112.84-80.6 18-12.86c3.64-2.58 8.28-3.52 12.62-2.61l100.35 21.53c25.91 5.53 51.44-10.97 57-36.88 5.55-25.92-10.95-51.44-36.88-57L437.68 98.47c-30.73-6.58-63.02.12-88.56 18.38l-80.02 57.17c-10.38 7.39-19.36 16.44-26.72 26.94L173.75 299c5.47 3.23 10.82 6.93 15.86 11.58zM624 352h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 343.58 442.04 352 416 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 343.58 250.04 352 224 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 343.58 58.04 352 32 352H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-512-96c44.18 0 80-35.82 80-80s-35.82-80-80-80-80 35.82-80 80 35.82 80 80 80z\"],\n    \"swimming-pool\": [640, 512, [], \"f5c5\", \"M624 416h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 407.58 442.04 416 416 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 407.58 250.04 416 224 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 407.58 58.04 416 32 416H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-400-32v-96h192v96c19.12 0 30.86-6.16 34.39-9.42 9.17-8.46 19.2-14.34 29.61-18.07V128c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v96H224v-96c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v228.5c10.41 3.73 20.44 9.62 29.61 18.07 3.53 3.27 15.27 9.43 34.39 9.43z\"],\n    \"synagogue\": [640, 512, [], \"f69b\", \"M70 196.51L6.67 268.29A26.643 26.643 0 0 0 0 285.93V512h128V239.58l-38-43.07c-5.31-6.01-14.69-6.01-20 0zm563.33 71.78L570 196.51c-5.31-6.02-14.69-6.02-20 0l-38 43.07V512h128V285.93c0-6.5-2.37-12.77-6.67-17.64zM339.99 7.01c-11.69-9.35-28.29-9.35-39.98 0l-128 102.4A32.005 32.005 0 0 0 160 134.4V512h96v-92.57c0-31.88 21.78-61.43 53.25-66.55C349.34 346.35 384 377.13 384 416v96h96V134.4c0-9.72-4.42-18.92-12.01-24.99l-128-102.4zm52.07 215.55c1.98 3.15-.29 7.24-4 7.24h-38.94L324 269.79c-1.85 2.95-6.15 2.95-8 0l-25.12-39.98h-38.94c-3.72 0-5.98-4.09-4-7.24l19.2-30.56-19.2-30.56c-1.98-3.15.29-7.24 4-7.24h38.94l25.12-40c1.85-2.95 6.15-2.95 8 0l25.12 39.98h38.95c3.71 0 5.98 4.09 4 7.24L372.87 192l19.19 30.56z\"],\n    \"sync\": [512, 512, [], \"f021\", \"M440.65 12.57l4 82.77A247.16 247.16 0 0 0 255.83 8C134.73 8 33.91 94.92 12.29 209.82A12 12 0 0 0 24.09 224h49.05a12 12 0 0 0 11.67-9.26 175.91 175.91 0 0 1 317-56.94l-101.46-4.86a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12H500a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12h-47.37a12 12 0 0 0-11.98 12.57zM255.83 432a175.61 175.61 0 0 1-146-77.8l101.8 4.87a12 12 0 0 0 12.57-12v-47.4a12 12 0 0 0-12-12H12a12 12 0 0 0-12 12V500a12 12 0 0 0 12 12h47.35a12 12 0 0 0 12-12.6l-4.15-82.57A247.17 247.17 0 0 0 255.83 504c121.11 0 221.93-86.92 243.55-201.82a12 12 0 0 0-11.8-14.18h-49.05a12 12 0 0 0-11.67 9.26A175.86 175.86 0 0 1 255.83 432z\"],\n    \"sync-alt\": [512, 512, [], \"f2f1\", \"M370.72 133.28C339.458 104.008 298.888 87.962 255.848 88c-77.458.068-144.328 53.178-162.791 126.85-1.344 5.363-6.122 9.15-11.651 9.15H24.103c-7.498 0-13.194-6.807-11.807-14.176C33.933 94.924 134.813 8 256 8c66.448 0 126.791 26.136 171.315 68.685L463.03 40.97C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.749zM32 296h134.059c21.382 0 32.09 25.851 16.971 40.971l-41.75 41.75c31.262 29.273 71.835 45.319 114.876 45.28 77.418-.07 144.315-53.144 162.787-126.849 1.344-5.363 6.122-9.15 11.651-9.15h57.304c7.498 0 13.194 6.807 11.807 14.176C478.067 417.076 377.187 504 256 504c-66.448 0-126.791-26.136-171.315-68.685L48.97 471.03C33.851 486.149 8 475.441 8 454.059V320c0-13.255 10.745-24 24-24z\"],\n    \"syringe\": [512, 512, [], \"f48e\", \"M201.5 174.8l55.7 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-55.7-55.8-45.3 45.3 55.8 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L111 265.2l-26.4 26.4c-17.3 17.3-25.6 41.1-23 65.4l7.1 63.6L2.3 487c-3.1 3.1-3.1 8.2 0 11.3l11.3 11.3c3.1 3.1 8.2 3.1 11.3 0l66.3-66.3 63.6 7.1c23.9 2.6 47.9-5.4 65.4-23l181.9-181.9-135.7-135.7-64.9 65zm308.2-93.3L430.5 2.3c-3.1-3.1-8.2-3.1-11.3 0l-11.3 11.3c-3.1 3.1-3.1 8.2 0 11.3l28.3 28.3-45.3 45.3-56.6-56.6-17-17c-3.1-3.1-8.2-3.1-11.3 0l-33.9 33.9c-3.1 3.1-3.1 8.2 0 11.3l17 17L424.8 223l17 17c3.1 3.1 8.2 3.1 11.3 0l33.9-34c3.1-3.1 3.1-8.2 0-11.3l-73.5-73.5 45.3-45.3 28.3 28.3c3.1 3.1 8.2 3.1 11.3 0l11.3-11.3c3.1-3.2 3.1-8.2 0-11.4z\"],\n    \"table\": [512, 512, [], \"f0ce\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64v-96h160v96zm0-160H64v-96h160v96zm224 160H288v-96h160v96zm0-160H288v-96h160v96z\"],\n    \"table-tennis\": [512, 512, [], \"f45d\", \"M496.2 296.5C527.7 218.7 512 126.2 449 63.1 365.1-21 229-21 145.1 63.1l-56 56.1 211.5 211.5c46.1-62.1 131.5-77.4 195.6-34.2zm-217.9 79.7L57.9 155.9c-27.3 45.3-21.7 105 17.3 144.1l34.5 34.6L6.7 424c-8.6 7.5-9.1 20.7-1 28.8l53.4 53.5c8 8.1 21.2 7.6 28.7-1L177.1 402l35.7 35.7c19.7 19.7 44.6 30.5 70.3 33.3-7.1-17-11-35.6-11-55.1-.1-13.8 2.5-27 6.2-39.7zM416 320c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96z\"],\n    \"tablet\": [448, 512, [], \"f10a\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"tablet-alt\": [448, 512, [], \"f3fa\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm176-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h328c6.6 0 12 5.4 12 12v312z\"],\n    \"tablets\": [640, 512, [], \"f490\", \"M160 192C78.9 192 12.5 250.5.1 326.7c-.8 4.8 3.3 9.3 8.3 9.3h303.3c5 0 9.1-4.5 8.3-9.3C307.5 250.5 241.1 192 160 192zm151.6 176H8.4c-5 0-9.1 4.5-8.3 9.3C12.5 453.5 78.9 512 160 512s147.5-58.5 159.9-134.7c.8-4.8-3.3-9.3-8.3-9.3zM593.4 46.6c-56.5-56.5-144.2-61.4-206.9-16-4 2.9-4.3 8.9-.8 12.3L597 254.3c3.5 3.5 9.5 3.2 12.3-.8 45.5-62.7 40.6-150.4-15.9-206.9zM363 65.7c-3.5-3.5-9.5-3.2-12.3.8-45.4 62.7-40.5 150.4 15.9 206.9 56.5 56.5 144.2 61.4 206.9 15.9 4-2.9 4.3-8.9.8-12.3L363 65.7z\"],\n    \"tachometer-alt\": [576, 512, [], \"f3fd\", \"M288 32C128.94 32 0 160.94 0 320c0 52.8 14.25 102.26 39.06 144.8 5.61 9.62 16.3 15.2 27.44 15.2h443c11.14 0 21.83-5.58 27.44-15.2C561.75 422.26 576 372.8 576 320c0-159.06-128.94-288-288-288zm0 64c14.71 0 26.58 10.13 30.32 23.65-1.11 2.26-2.64 4.23-3.45 6.67l-9.22 27.67c-5.13 3.49-10.97 6.01-17.64 6.01-17.67 0-32-14.33-32-32S270.33 96 288 96zM96 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm48-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm246.77-72.41l-61.33 184C343.13 347.33 352 364.54 352 384c0 11.72-3.38 22.55-8.88 32H232.88c-5.5-9.45-8.88-20.28-8.88-32 0-33.94 26.5-61.43 59.9-63.59l61.34-184.01c4.17-12.56 17.73-19.45 30.36-15.17 12.57 4.19 19.35 17.79 15.17 30.36zm14.66 57.2l15.52-46.55c3.47-1.29 7.13-2.23 11.05-2.23 17.67 0 32 14.33 32 32s-14.33 32-32 32c-11.38-.01-20.89-6.28-26.57-15.22zM480 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"tag\": [512, 512, [], \"f02b\", \"M0 252.118V48C0 21.49 21.49 0 48 0h204.118a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882L293.823 497.941c-18.745 18.745-49.137 18.745-67.882 0L14.059 286.059A48 48 0 0 1 0 252.118zM112 64c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"tags\": [640, 512, [], \"f02c\", \"M497.941 225.941L286.059 14.059A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v204.118a48 48 0 0 0 14.059 33.941l211.882 211.882c18.744 18.745 49.136 18.746 67.882 0l204.118-204.118c18.745-18.745 18.745-49.137 0-67.882zM112 160c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm513.941 133.823L421.823 497.941c-18.745 18.745-49.137 18.745-67.882 0l-.36-.36L527.64 323.522c16.999-16.999 26.36-39.6 26.36-63.64s-9.362-46.641-26.36-63.64L331.397 0h48.721a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882z\"],\n    \"tape\": [640, 512, [], \"f4db\", \"M224 192c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm400 224H380.6c41.5-40.7 67.4-97.3 67.4-160 0-123.7-100.3-224-224-224S0 132.3 0 256s100.3 224 224 224h400c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400-64c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96z\"],\n    \"tasks\": [512, 512, [], \"f0ae\", \"M139.61 35.5a12 12 0 0 0-17 0L58.93 98.81l-22.7-22.12a12 12 0 0 0-17 0L3.53 92.41a12 12 0 0 0 0 17l47.59 47.4a12.78 12.78 0 0 0 17.61 0l15.59-15.62L156.52 69a12.09 12.09 0 0 0 .09-17zm0 159.19a12 12 0 0 0-17 0l-63.68 63.72-22.7-22.1a12 12 0 0 0-17 0L3.53 252a12 12 0 0 0 0 17L51 316.5a12.77 12.77 0 0 0 17.6 0l15.7-15.69 72.2-72.22a12 12 0 0 0 .09-16.9zM64 368c-26.49 0-48.59 21.5-48.59 48S37.53 464 64 464a48 48 0 0 0 0-96zm432 16H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"taxi\": [512, 512, [], \"f1ba\", \"M462 241.64l-22-84.84c-9.6-35.2-41.6-60.8-76.8-60.8H352V64c0-17.67-14.33-32-32-32H192c-17.67 0-32 14.33-32 32v32h-11.2c-35.2 0-67.2 25.6-76.8 60.8l-22 84.84C21.41 248.04 0 273.47 0 304v48c0 23.63 12.95 44.04 32 55.12V448c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-40.88c19.05-11.09 32-31.5 32-55.12v-48c0-30.53-21.41-55.96-50-62.36zM96 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm20.55-112l17.2-66.36c2.23-8.16 9.59-13.64 15.06-13.64h214.4c5.47 0 12.83 5.48 14.85 12.86L395.45 240h-278.9zM416 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"teeth\": [640, 512, [], \"f62e\", \"M544 0H96C42.98 0 0 42.98 0 96v320c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96zM160 368c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm128 128c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64z\"],\n    \"teeth-open\": [640, 512, [], \"f62f\", \"M544 0H96C42.98 0 0 42.98 0 96v64c0 35.35 28.66 64 64 64h512c35.34 0 64-28.65 64-64V96c0-53.02-42.98-96-96-96zM160 176c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm128 0c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm0 144H64c-35.34 0-64 28.65-64 64v32c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96v-32c0-35.35-28.66-64-64-64zm-416 80c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32zm144-8c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm144 0c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm128 8c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32z\"],\n    \"temperature-high\": [512, 512, [], \"f769\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V112c0-8.8-7.2-16-16-16s-16 7.2-16 16v210.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"temperature-low\": [512, 512, [], \"f76b\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V304c0-8.8-7.2-16-16-16s-16 7.2-16 16v18.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"tenge\": [384, 512, [], \"f7d7\", \"M372 160H12c-6.6 0-12 5.4-12 12v56c0 6.6 5.4 12 12 12h140v228c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12V240h140c6.6 0 12-5.4 12-12v-56c0-6.6-5.4-12-12-12zm0-128H12C5.4 32 0 37.4 0 44v56c0 6.6 5.4 12 12 12h360c6.6 0 12-5.4 12-12V44c0-6.6-5.4-12-12-12z\"],\n    \"terminal\": [640, 512, [], \"f120\", \"M257.981 272.971L63.638 467.314c-9.373 9.373-24.569 9.373-33.941 0L7.029 444.647c-9.357-9.357-9.375-24.522-.04-33.901L161.011 256 6.99 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L257.981 239.03c9.373 9.372 9.373 24.568 0 33.941zM640 456v-32c0-13.255-10.745-24-24-24H312c-13.255 0-24 10.745-24 24v32c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24z\"],\n    \"text-height\": [576, 512, [], \"f034\", \"M304 32H16A16 16 0 0 0 0 48v96a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32h56v304H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h160a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-40V112h56v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm256 336h-48V144h48c14.31 0 21.33-17.31 11.31-27.31l-80-80a16 16 0 0 0-22.62 0l-80 80C379.36 126 384.36 144 400 144h48v224h-48c-14.31 0-21.32 17.31-11.31 27.31l80 80a16 16 0 0 0 22.62 0l80-80C580.64 386 575.64 368 560 368z\"],\n    \"text-width\": [448, 512, [], \"f035\", \"M432 32H16A16 16 0 0 0 0 48v80a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-16h120v112h-24a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-24V112h120v16a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm-68.69 260.69C354 283.36 336 288.36 336 304v48H112v-48c0-14.31-17.31-21.32-27.31-11.31l-80 80a16 16 0 0 0 0 22.62l80 80C94 484.64 112 479.64 112 464v-48h224v48c0 14.31 17.31 21.33 27.31 11.31l80-80a16 16 0 0 0 0-22.62z\"],\n    \"th\": [512, 512, [], \"f00a\", \"M149.333 56v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zm181.334 240v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm32-240v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24zm-32 80V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm-205.334 56H24c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm386.667-56H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm0 160H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zM181.333 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24z\"],\n    \"th-large\": [512, 512, [], \"f009\", \"M296 32h192c13.255 0 24 10.745 24 24v160c0 13.255-10.745 24-24 24H296c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24zm-80 0H24C10.745 32 0 42.745 0 56v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zM0 296v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm296 184h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H296c-13.255 0-24 10.745-24 24v160c0 13.255 10.745 24 24 24z\"],\n    \"th-list\": [512, 512, [], \"f00b\", \"M149.333 216v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-80c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zM125.333 32H24C10.745 32 0 42.745 0 56v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zm80 448H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm-24-424v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24zm24 264H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24z\"],\n    \"theater-masks\": [640, 512, [], \"f630\", \"M206.86 245.15c-35.88 10.45-59.95 41.2-57.53 74.1 11.4-12.72 28.81-23.7 49.9-30.92l7.63-43.18zM95.81 295L64.08 115.49c-.29-1.62.28-2.62.24-2.65 57.76-32.06 123.12-49.01 189.01-49.01 1.61 0 3.23.17 4.85.19 13.95-13.47 31.73-22.83 51.59-26 18.89-3.02 38.05-4.55 57.18-5.32-9.99-13.95-24.48-24.23-41.77-27C301.27 1.89 277.24 0 253.32 0 176.66 0 101.02 19.42 33.2 57.06 9.03 70.48-3.92 98.48 1.05 126.58l31.73 179.51c14.23 80.52 136.33 142.08 204.45 142.08 3.59 0 6.75-.46 10.01-.8-13.52-17.08-28.94-40.48-39.5-67.58-47.61-12.98-106.06-51.62-111.93-84.79zm97.55-137.46c-.73-4.12-2.23-7.87-4.07-11.4-8.25 8.91-20.67 15.75-35.32 18.32-14.65 2.58-28.67.4-39.48-5.17-.52 3.94-.64 7.98.09 12.1 3.84 21.7 24.58 36.19 46.34 32.37 21.75-3.82 36.28-24.52 32.44-46.22zM606.8 120.9c-88.98-49.38-191.43-67.41-291.98-51.35-27.31 4.36-49.08 26.26-54.04 54.36l-31.73 179.51c-15.39 87.05 95.28 196.27 158.31 207.35 63.03 11.09 204.47-53.79 219.86-140.84l31.73-179.51c4.97-28.11-7.98-56.11-32.15-69.52zm-273.24 96.8c3.84-21.7 24.58-36.19 46.34-32.36 21.76 3.83 36.28 24.52 32.45 46.22-.73 4.12-2.23 7.87-4.07 11.4-8.25-8.91-20.67-15.75-35.32-18.32-14.65-2.58-28.67-.4-39.48 5.17-.53-3.95-.65-7.99.08-12.11zm70.47 198.76c-55.68-9.79-93.52-59.27-89.04-112.9 20.6 25.54 56.21 46.17 99.49 53.78 43.28 7.61 83.82.37 111.93-16.6-14.18 51.94-66.71 85.51-122.38 75.72zm130.3-151.34c-8.25-8.91-20.68-15.75-35.33-18.32-14.65-2.58-28.67-.4-39.48 5.17-.52-3.94-.64-7.98.09-12.1 3.84-21.7 24.58-36.19 46.34-32.37 21.75 3.83 36.28 24.52 32.45 46.22-.73 4.13-2.23 7.88-4.07 11.4z\"],\n    \"thermometer\": [512, 512, [], \"f491\", \"M476.8 20.4c-37.5-30.7-95.5-26.3-131.9 10.2l-45.7 46 50.5 50.5c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.4-50.5-45.1 45.4 50.3 50.4c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L209 167.4l-45.1 45.4L214 263c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.1-50.2L96 281.1V382L7 471c-9.4 9.4-9.4 24.6 0 33.9 9.4 9.4 24.6 9.4 33.9 0l89-89h99.9L484 162.6c34.9-34.9 42.2-101.5-7.2-142.2z\"],\n    \"thermometer-empty\": [256, 512, [], \"f2cb\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-35.346 28.654-64 64-64s64 28.654 64 64zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-full\": [256, 512, [], \"f2c7\", \"M224 96c0-53.019-42.981-96-96-96S32 42.981 32 96v203.347C12.225 321.756.166 351.136.002 383.333c-.359 70.303 56.787 128.176 127.089 128.664.299.002.61.003.909.003 70.698 0 128-57.304 128-128 0-32.459-12.088-62.09-32-84.653V96zm-96 368l-.576-.002c-43.86-.304-79.647-36.544-79.423-80.42.173-33.98 19.266-51.652 31.999-66.08V96c0-26.467 21.533-48 48-48s48 21.533 48 48v221.498c12.63 14.312 32 32.164 32 66.502 0 44.112-35.888 80-80 80zm64-80c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V96c0-17.673 14.327-32 32-32s32 14.327 32 32v232.583c19.124 11.068 32 31.732 32 55.417z\"],\n    \"thermometer-half\": [256, 512, [], \"f2c9\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V224c0-17.673 14.327-32 32-32s32 14.327 32 32v104.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-quarter\": [256, 512, [], \"f2ca\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V288c0-17.673 14.327-32 32-32s32 14.327 32 32v40.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-three-quarters\": [256, 512, [], \"f2c8\", \"M192 384c0 35.346-28.654 64-64 64-35.346 0-64-28.654-64-64 0-23.685 12.876-44.349 32-55.417V160c0-17.673 14.327-32 32-32s32 14.327 32 32v168.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M0 56v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56zm40 200c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24zm272 256c-20.183 0-29.485-39.293-33.931-57.795-5.206-21.666-10.589-44.07-25.393-58.902-32.469-32.524-49.503-73.967-89.117-113.111a11.98 11.98 0 0 1-3.558-8.521V59.901c0-6.541 5.243-11.878 11.783-11.998 15.831-.29 36.694-9.079 52.651-16.178C256.189 17.598 295.709.017 343.995 0h2.844c42.777 0 93.363.413 113.774 29.737 8.392 12.057 10.446 27.034 6.148 44.632 16.312 17.053 25.063 48.863 16.382 74.757 17.544 23.432 19.143 56.132 9.308 79.469l.11.11c11.893 11.949 19.523 31.259 19.439 49.197-.156 30.352-26.157 58.098-59.553 58.098H350.723C358.03 364.34 384 388.132 384 430.548 384 504 336 512 312 512z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M104 224H24c-13.255 0-24 10.745-24 24v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V248c0-13.255-10.745-24-24-24zM64 472c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zM384 81.452c0 42.416-25.97 66.208-33.277 94.548h101.723c33.397 0 59.397 27.746 59.553 58.098.084 17.938-7.546 37.249-19.439 49.197l-.11.11c9.836 23.337 8.237 56.037-9.308 79.469 8.681 25.895-.069 57.704-16.382 74.757 4.298 17.598 2.244 32.575-6.148 44.632C440.202 511.587 389.616 512 346.839 512l-2.845-.001c-48.287-.017-87.806-17.598-119.56-31.725-15.957-7.099-36.821-15.887-52.651-16.178-6.54-.12-11.783-5.457-11.783-11.998v-213.77c0-3.2 1.282-6.271 3.558-8.521 39.614-39.144 56.648-80.587 89.117-113.111 14.804-14.832 20.188-37.236 25.393-58.902C282.515 39.293 291.817 0 312 0c24 0 72 8 72 81.452z\"],\n    \"thumbtack\": [384, 512, [], \"f08d\", \"M298.028 214.267L285.793 96H328c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v48c0 13.255 10.745 24 24 24h42.207L85.972 214.267C37.465 236.82 0 277.261 0 328c0 13.255 10.745 24 24 24h136v104.007c0 1.242.289 2.467.845 3.578l24 48c2.941 5.882 11.364 5.893 14.311 0l24-48a8.008 8.008 0 0 0 .845-3.578V352h136c13.255 0 24-10.745 24-24-.001-51.183-37.983-91.42-85.973-113.733z\"],\n    \"ticket-alt\": [576, 512, [], \"f3ff\", \"M128 160h320v192H128V160zm400 96c0 26.51 21.49 48 48 48v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c26.51 0 48-21.49 48-48s-21.49-48-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v96c-26.51 0-48 21.49-48 48zm-48-104c0-13.255-10.745-24-24-24H120c-13.255 0-24 10.745-24 24v208c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V152z\"],\n    \"times\": [352, 512, [], \"f00d\", \"M242.72 256l100.07-100.07c12.28-12.28 12.28-32.19 0-44.48l-22.24-22.24c-12.28-12.28-32.19-12.28-44.48 0L176 189.28 75.93 89.21c-12.28-12.28-32.19-12.28-44.48 0L9.21 111.45c-12.28 12.28-12.28 32.19 0 44.48L109.28 256 9.21 356.07c-12.28 12.28-12.28 32.19 0 44.48l22.24 22.24c12.28 12.28 32.2 12.28 44.48 0L176 322.72l100.07 100.07c12.28 12.28 32.2 12.28 44.48 0l22.24-22.24c12.28-12.28 12.28-32.19 0-44.48L242.72 256z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm121.6 313.1c4.7 4.7 4.7 12.3 0 17L338 377.6c-4.7 4.7-12.3 4.7-17 0L256 312l-65.1 65.6c-4.7 4.7-12.3 4.7-17 0L134.4 338c-4.7-4.7-4.7-12.3 0-17l65.6-65-65.6-65.1c-4.7-4.7-4.7-12.3 0-17l39.6-39.6c4.7-4.7 12.3-4.7 17 0l65 65.7 65.1-65.6c4.7-4.7 12.3-4.7 17 0l39.6 39.6c4.7 4.7 4.7 12.3 0 17L312 256l65.6 65.1z\"],\n    \"tint\": [352, 512, [], \"f043\", \"M205.22 22.09c-7.94-28.78-49.44-30.12-58.44 0C100.01 179.85 0 222.72 0 333.91 0 432.35 78.72 512 176 512s176-79.65 176-178.09c0-111.75-99.79-153.34-146.78-311.82zM176 448c-61.75 0-112-50.25-112-112 0-8.84 7.16-16 16-16s16 7.16 16 16c0 44.11 35.89 80 80 80 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"tint-slash\": [640, 512, [], \"f5c7\", \"M633.82 458.1L494.97 350.78c.52-5.57 1.03-11.16 1.03-16.87 0-111.76-99.79-153.34-146.78-311.82-7.94-28.78-49.44-30.12-58.44 0-15.52 52.34-36.87 91.96-58.49 125.68L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM144 333.91C144 432.35 222.72 512 320 512c44.71 0 85.37-16.96 116.4-44.7L162.72 255.78c-11.41 23.5-18.72 48.35-18.72 78.13z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 288c51.9 0 115.3 43.8 123.2 106.7 1.7 13.6-8 24.6-17.7 20.4-25.9-11.1-64.4-17.4-105.5-17.4s-79.6 6.3-105.5 17.4c-9.8 4.2-19.4-7-17.7-20.4C132.7 331.8 196.1 288 248 288z\"],\n    \"toggle-off\": [576, 512, [], \"f204\", \"M384 64H192C85.961 64 0 149.961 0 256s85.961 192 192 192h192c106.039 0 192-85.961 192-192S490.039 64 384 64zM64 256c0-70.741 57.249-128 128-128 70.741 0 128 57.249 128 128 0 70.741-57.249 128-128 128-70.741 0-128-57.249-128-128zm320 128h-48.905c65.217-72.858 65.236-183.12 0-256H384c70.741 0 128 57.249 128 128 0 70.74-57.249 128-128 128z\"],\n    \"toggle-on\": [576, 512, [], \"f205\", \"M384 64H192C86 64 0 150 0 256s86 192 192 192h192c106 0 192-86 192-192S490 64 384 64zm0 320c-70.8 0-128-57.3-128-128 0-70.8 57.3-128 128-128 70.8 0 128 57.3 128 128 0 70.8-57.3 128-128 128z\"],\n    \"toilet\": [384, 512, [], \"f7d8\", \"M368 48c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v16c0 8.8 7.2 16 16 16h16v156.7C11.8 214.8 0 226.9 0 240c0 67.2 34.6 126.2 86.8 160.5l-21.4 70.2C59.1 491.2 74.5 512 96 512h192c21.5 0 36.9-20.8 30.6-41.3l-21.4-70.2C349.4 366.2 384 307.2 384 240c0-13.1-11.8-25.2-32-35.3V48h16zM80 72c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H88c-4.4 0-8-3.6-8-8V72zm112 200c-77.1 0-139.6-14.3-139.6-32s62.5-32 139.6-32 139.6 14.3 139.6 32-62.5 32-139.6 32z\"],\n    \"toilet-paper\": [576, 512, [], \"f71e\", \"M128 0C74.98 0 32 85.96 32 192v172.07c0 41.12-9.8 62.77-31.17 126.87C-2.62 501.3 5.09 512 16.01 512h280.92c13.77 0 26-8.81 30.36-21.88 12.83-38.48 24.71-72.4 24.71-126.05V192c0-83.6 23.67-153.52 60.44-192H128zM96 224c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM480 0c-53.02 0-96 85.96-96 192s42.98 192 96 192 96-85.96 96-192S533.02 0 480 0zm0 256c-17.67 0-32-28.65-32-64s14.33-64 32-64 32 28.65 32 64-14.33 64-32 64z\"],\n    \"toolbox\": [512, 512, [], \"f552\", \"M502.63 214.63l-45.25-45.25c-6-6-14.14-9.37-22.63-9.37H384V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v80H77.25c-8.49 0-16.62 3.37-22.63 9.37L9.37 214.63c-6 6-9.37 14.14-9.37 22.63V320h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-82.75c0-8.48-3.37-16.62-9.37-22.62zM320 160H192V96h128v64zm64 208c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H192v16c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H0v96c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-96H384v16z\"],\n    \"tools\": [512, 512, [], \"f7d9\", \"M501.1 395.7L384 278.6c-23.1-23.1-57.6-27.6-85.4-13.9L192 158.1V96L64 0 0 64l96 128h62.1l106.6 106.6c-13.6 27.8-9.2 62.3 13.9 85.4l117.1 117.1c14.6 14.6 38.2 14.6 52.7 0l52.7-52.7c14.5-14.6 14.5-38.2 0-52.7zM331.7 225c28.3 0 54.9 11 74.9 31l19.4 19.4c15.8-6.9 30.8-16.5 43.8-29.5 37.1-37.1 49.7-89.3 37.9-136.7-2.2-9-13.5-12.1-20.1-5.5l-74.4 74.4-67.9-11.3L334 98.9l74.4-74.4c6.6-6.6 3.4-17.9-5.7-20.2-47.4-11.7-99.6.9-136.6 37.9-28.5 28.5-41.9 66.1-41.2 103.6l82.1 82.1c8.1-1.9 16.5-2.9 24.7-2.9zm-103.9 82l-56.7-56.7L18.7 402.8c-25 25-25 65.5 0 90.5s65.5 25 90.5 0l123.6-123.6c-7.6-19.9-9.9-41.6-5-62.7zM64 472c-13.2 0-24-10.8-24-24 0-13.3 10.7-24 24-24s24 10.7 24 24c0 13.2-10.7 24-24 24z\"],\n    \"tooth\": [448, 512, [], \"f5c9\", \"M443.98 96.25c-11.01-45.22-47.11-82.06-92.01-93.72-32.19-8.36-63 5.1-89.14 24.33-3.25 2.39-6.96 3.73-10.5 5.48l28.32 18.21c7.42 4.77 9.58 14.67 4.8 22.11-4.46 6.95-14.27 9.86-22.11 4.8L162.83 12.84c-20.7-10.85-43.38-16.4-66.81-10.31-44.9 11.67-81 48.5-92.01 93.72-10.13 41.62-.42 80.81 21.5 110.43 23.36 31.57 32.68 68.66 36.29 107.35 4.4 47.16 10.33 94.16 20.94 140.32l7.8 33.95c3.19 13.87 15.49 23.7 29.67 23.7 13.97 0 26.15-9.55 29.54-23.16l34.47-138.42c4.56-18.32 20.96-31.16 39.76-31.16s35.2 12.85 39.76 31.16l34.47 138.42c3.39 13.61 15.57 23.16 29.54 23.16 14.18 0 26.48-9.83 29.67-23.7l7.8-33.95c10.61-46.15 16.53-93.16 20.94-140.32 3.61-38.7 12.93-75.78 36.29-107.35 21.95-29.61 31.66-68.8 21.53-110.43z\"],\n    \"torah\": [640, 512, [], \"f6a0\", \"M320.05 366.48l17.72-29.64h-35.46zm99.21-166H382.4l18.46 30.82zM48 0C21.49 0 0 14.33 0 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32C96 14.33 74.51 0 48 0zm172.74 311.5h36.85l-18.46-30.82zm161.71 0h36.86l-18.45-30.8zM128 464h384V48H128zm66.77-278.13a21.22 21.22 0 0 1 18.48-10.71h59.45l29.13-48.71a21.13 21.13 0 0 1 18.22-10.37A20.76 20.76 0 0 1 338 126.29l29.25 48.86h59.52a21.12 21.12 0 0 1 18.1 32L415.63 256 445 305a20.69 20.69 0 0 1 .24 21.12 21.25 21.25 0 0 1-18.48 10.72h-59.47l-29.13 48.7a21.13 21.13 0 0 1-18.16 10.4 20.79 20.79 0 0 1-18-10.22l-29.25-48.88h-59.5a21.11 21.11 0 0 1-18.1-32L224.36 256 195 207a20.7 20.7 0 0 1-.23-21.13zM592 0c-26.51 0-48 14.33-48 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32c0-17.67-21.49-32-48-32zM320 145.53l-17.78 29.62h35.46zm-62.45 55h-36.81l18.44 30.8zm29.58 111h65.79L386.09 256l-33.23-55.52h-65.79L253.9 256z\"],\n    \"torii-gate\": [512, 512, [], \"f6a1\", \"M376.45 32h-240.9A303.17 303.17 0 0 1 0 0v96c0 17.67 14.33 32 32 32h32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h256v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h48c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-48v-64h32c17.67 0 32-14.33 32-32V0a303.17 303.17 0 0 1-135.55 32zM128 128h96v64h-96v-64zm256 64h-96v-64h96v64z\"],\n    \"tractor\": [640, 512, [], \"f722\", \"M528 336c-48.6 0-88 39.4-88 88s39.4 88 88 88 88-39.4 88-88-39.4-88-88-88zm0 112c-13.23 0-24-10.77-24-24s10.77-24 24-24 24 10.77 24 24-10.77 24-24 24zm80-288h-64v-40.2c0-14.12 4.7-27.76 13.15-38.84 4.42-5.8 3.55-14.06-1.32-19.49L534.2 37.3c-6.66-7.45-18.32-6.92-24.7.78C490.58 60.9 480 89.81 480 119.8V160H377.67L321.58 29.14A47.914 47.914 0 0 0 277.45 0H144c-26.47 0-48 21.53-48 48v146.52c-8.63-6.73-20.96-6.46-28.89 1.47L36 227.1c-8.59 8.59-8.59 22.52 0 31.11l5.06 5.06c-4.99 9.26-8.96 18.82-11.91 28.72H22c-12.15 0-22 9.85-22 22v44c0 12.15 9.85 22 22 22h7.14c2.96 9.91 6.92 19.46 11.91 28.73l-5.06 5.06c-8.59 8.59-8.59 22.52 0 31.11L67.1 476c8.59 8.59 22.52 8.59 31.11 0l5.06-5.06c9.26 4.99 18.82 8.96 28.72 11.91V490c0 12.15 9.85 22 22 22h44c12.15 0 22-9.85 22-22v-7.14c9.9-2.95 19.46-6.92 28.72-11.91l5.06 5.06c8.59 8.59 22.52 8.59 31.11 0l31.11-31.11c8.59-8.59 8.59-22.52 0-31.11l-5.06-5.06c4.99-9.26 8.96-18.82 11.91-28.72H330c12.15 0 22-9.85 22-22v-6h80.54c21.91-28.99 56.32-48 95.46-48 18.64 0 36.07 4.61 51.8 12.2l50.82-50.82c6-6 9.37-14.14 9.37-22.63V192c.01-17.67-14.32-32-31.99-32zM176 416c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm22-256h-38V64h106.89l41.15 96H198z\"],\n    \"trademark\": [640, 512, [], \"f25c\", \"M260.6 96H12c-6.6 0-12 5.4-12 12v43.1c0 6.6 5.4 12 12 12h85.1V404c0 6.6 5.4 12 12 12h54.3c6.6 0 12-5.4 12-12V163.1h85.1c6.6 0 12-5.4 12-12V108c.1-6.6-5.3-12-11.9-12zM640 403l-24-296c-.5-6.2-5.7-11-12-11h-65.4c-5.1 0-9.7 3.3-11.3 8.1l-43.8 127.1c-7.2 20.6-16.1 52.8-16.1 52.8h-.9s-8.9-32.2-16.1-52.8l-43.8-127.1c-1.7-4.8-6.2-8.1-11.3-8.1h-65.4c-6.2 0-11.4 4.8-12 11l-24.4 296c-.6 7 4.9 13 12 13H360c6.3 0 11.5-4.9 12-11.2l9.1-132.9c1.8-24.2 0-53.7 0-53.7h.9s10.7 33.6 17.9 53.7l30.7 84.7c1.7 4.7 6.2 7.9 11.3 7.9h50.3c5.1 0 9.6-3.2 11.3-7.9l30.7-84.7c7.2-20.1 17.9-53.7 17.9-53.7h.9s-1.8 29.5 0 53.7l9.1 132.9c.4 6.3 5.7 11.2 12 11.2H628c7 0 12.5-6 12-13z\"],\n    \"traffic-light\": [384, 512, [], \"f637\", \"M384 192h-64v-37.88c37.2-13.22 64-48.38 64-90.12h-64V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v32H0c0 41.74 26.8 76.9 64 90.12V192H0c0 41.74 26.8 76.9 64 90.12V320H0c0 42.84 28.25 78.69 66.99 91.05C79.42 468.72 130.6 512 192 512s112.58-43.28 125.01-100.95C355.75 398.69 384 362.84 384 320h-64v-37.88c37.2-13.22 64-48.38 64-90.12zM192 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"train\": [448, 512, [], \"f238\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zm-48 136V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24zm-176 64c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56z\"],\n    \"tram\": [512, 512, [], \"f7da\", \"M288 64c17.7 0 32-14.3 32-32S305.7 0 288 0s-32 14.3-32 32 14.3 32 32 32zm223.5-12.1c-2.3-8.6-11-13.6-19.6-11.3l-480 128c-8.5 2.3-13.6 11-11.3 19.6C2.5 195.3 8.9 200 16 200c1.4 0 2.8-.2 4.1-.5L240 140.8V224H64c-17.7 0-32 14.3-32 32v224c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32H272v-91.7l228.1-60.8c8.6-2.3 13.6-11.1 11.4-19.6zM176 384H80v-96h96v96zm160-96h96v96h-96v-96zm-32 0v96h-96v-96h96zM192 96c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"transgender\": [384, 512, [], \"f224\", \"M372 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C198.5 104.1 172.2 96 144 96 64.5 96 0 160.5 0 240c0 68.5 47.9 125.9 112 140.4V408H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM144 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"transgender-alt\": [480, 512, [], \"f225\", \"M468 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C294.5 104.1 268.2 96 240 96c-28.2 0-54.5 8.1-76.7 22.1l-16.5-16.5 19.8-19.8c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0l-19.8 19.8-19-19 16.9-16.9C107.1 12.9 101.7 0 91 0H12C5.4 0 0 5.4 0 12v79c0 10.7 12.9 16 20.5 8.5l16.9-16.9 19 19-19.8 19.8c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l19.8-19.8 16.5 16.5C104.1 185.5 96 211.8 96 240c0 68.5 47.9 125.9 112 140.4V408h-36c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM240 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"trash\": [448, 512, [], \"f1f8\", \"M432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm272-256a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore\": [448, 512, [], \"f829\", \"M53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32zm70.11-175.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore-alt\": [448, 512, [], \"f82a\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm91.31-172.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"tree\": [384, 512, [], \"f1bb\", \"M378.31 378.49L298.42 288h30.63c9.01 0 16.98-5 20.78-13.06 3.8-8.04 2.55-17.26-3.28-24.05L268.42 160h28.89c9.1 0 17.3-5.35 20.86-13.61 3.52-8.13 1.86-17.59-4.24-24.08L203.66 4.83c-6.03-6.45-17.28-6.45-23.32 0L70.06 122.31c-6.1 6.49-7.75 15.95-4.24 24.08C69.38 154.65 77.59 160 86.69 160h28.89l-78.14 90.91c-5.81 6.78-7.06 15.99-3.27 24.04C37.97 283 45.93 288 54.95 288h30.63L5.69 378.49c-6 6.79-7.36 16.09-3.56 24.26 3.75 8.05 12 13.25 21.01 13.25H160v24.45l-30.29 48.4c-5.32 10.64 2.42 23.16 14.31 23.16h95.96c11.89 0 19.63-12.52 14.31-23.16L224 440.45V416h136.86c9.01 0 17.26-5.2 21.01-13.25 3.8-8.17 2.44-17.47-3.56-24.26z\"],\n    \"trophy\": [576, 512, [], \"f091\", \"M552 64H448V24c0-13.3-10.7-24-24-24H152c-13.3 0-24 10.7-24 24v40H24C10.7 64 0 74.7 0 88v56c0 35.7 22.5 72.4 61.9 100.7 31.5 22.7 69.8 37.1 110 41.7C203.3 338.5 240 360 240 360v72h-48c-35.3 0-64 20.7-64 56v12c0 6.6 5.4 12 12 12h296c6.6 0 12-5.4 12-12v-12c0-35.3-28.7-56-64-56h-48v-72s36.7-21.5 68.1-73.6c40.3-4.6 78.6-19 110-41.7 39.3-28.3 61.9-65 61.9-100.7V88c0-13.3-10.7-24-24-24zM99.3 192.8C74.9 175.2 64 155.6 64 144v-16h64.2c1 32.6 5.8 61.2 12.8 86.2-15.1-5.2-29.2-12.4-41.7-21.4zM512 144c0 16.1-17.7 36.1-35.3 48.8-12.5 9-26.7 16.2-41.8 21.4 7-25 11.8-53.6 12.8-86.2H512v16z\"],\n    \"truck\": [640, 512, [], \"f0d1\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"truck-loading\": [640, 512, [], \"f4de\", \"M50.2 375.6c2.3 8.5 11.1 13.6 19.6 11.3l216.4-58c8.5-2.3 13.6-11.1 11.3-19.6l-49.7-185.5c-2.3-8.5-11.1-13.6-19.6-11.3L151 133.3l24.8 92.7-61.8 16.5-24.8-92.7-77.3 20.7C3.4 172.8-1.7 181.6.6 190.1l49.6 185.5zM384 0c-17.7 0-32 14.3-32 32v323.6L5.9 450c-4.3 1.2-6.8 5.6-5.6 9.8l12.6 46.3c1.2 4.3 5.6 6.8 9.8 5.6l393.7-107.4C418.8 464.1 467.6 512 528 512c61.9 0 112-50.1 112-112V0H384zm144 448c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"truck-monster\": [640, 512, [], \"f63b\", \"M624 224h-16v-64c0-17.67-14.33-32-32-32h-73.6L419.22 24.02A64.025 64.025 0 0 0 369.24 0H256c-17.67 0-32 14.33-32 32v96H48c-8.84 0-16 7.16-16 16v80H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16.72c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64h65.45c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-336-96V64h81.24l51.2 64H288zm304 224h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 512 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67A110.85 110.85 0 0 0 373.2 352H368c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32c-.02-8.84-7.18-16-16.02-16zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-208-80h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 192 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0L58.18 304.8c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67a110.85 110.85 0 0 0-8.65 20.89H48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32C288 359.16 280.84 352 272 352zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"truck-moving\": [640, 512, [], \"f4df\", \"M621.3 237.3l-58.5-58.5c-12-12-28.3-18.7-45.3-18.7H480V64c0-17.7-14.3-32-32-32H32C14.3 32 0 46.3 0 64v336c0 44.2 35.8 80 80 80 26.3 0 49.4-12.9 64-32.4 14.6 19.6 37.7 32.4 64 32.4 44.2 0 80-35.8 80-80 0-5.5-.6-10.8-1.6-16h163.2c-1.1 5.2-1.6 10.5-1.6 16 0 44.2 35.8 80 80 80s80-35.8 80-80c0-5.5-.6-10.8-1.6-16H624c8.8 0 16-7.2 16-16v-85.5c0-17-6.7-33.2-18.7-45.2zM80 432c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm128 0c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm272-224h37.5c4.3 0 8.3 1.7 11.3 4.7l43.3 43.3H480v-48zm48 224c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32z\"],\n    \"truck-pickup\": [640, 512, [], \"f63c\", \"M624 288h-16v-64c0-17.67-14.33-32-32-32h-48L419.22 56.02A64.025 64.025 0 0 0 369.24 32H256c-17.67 0-32 14.33-32 32v128H64c-17.67 0-32 14.33-32 32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h49.61c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16h67.23c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM288 96h81.24l76.8 96H288V96zM176 416c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm288 0c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"tshirt\": [640, 512, [], \"f553\", \"M631.2 96.5L436.5 0C416.4 27.8 371.9 47.2 320 47.2S223.6 27.8 203.5 0L8.8 96.5c-7.9 4-11.1 13.6-7.2 21.5l57.2 114.5c4 7.9 13.6 11.1 21.5 7.2l56.6-27.7c10.6-5.2 23 2.5 23 14.4V480c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V226.3c0-11.8 12.4-19.6 23-14.4l56.6 27.7c7.9 4 17.5.8 21.5-7.2L638.3 118c4-7.9.8-17.6-7.1-21.5z\"],\n    \"tty\": [512, 512, [], \"f1e4\", \"M5.37 103.822c138.532-138.532 362.936-138.326 501.262 0 6.078 6.078 7.074 15.496 2.583 22.681l-43.214 69.138a18.332 18.332 0 0 1-22.356 7.305l-86.422-34.569a18.335 18.335 0 0 1-11.434-18.846L351.741 90c-62.145-22.454-130.636-21.986-191.483 0l5.953 59.532a18.331 18.331 0 0 1-11.434 18.846l-86.423 34.568a18.334 18.334 0 0 1-22.356-7.305L2.787 126.502a18.333 18.333 0 0 1 2.583-22.68zM96 308v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H92c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zM96 500v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H140c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"tv\": [640, 512, [], \"f26c\", \"M592 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h245.1v32h-160c-17.7 0-32 14.3-32 32s14.3 32 32 32h384c17.7 0 32-14.3 32-32s-14.3-32-32-32h-160v-32H592c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h512v288z\"],\n    \"umbrella\": [576, 512, [], \"f0e9\", \"M575.7 280.8C547.1 144.5 437.3 62.6 320 49.9V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v17.9C138.3 62.6 29.5 144.5.3 280.8c-2.2 10.1 8.5 21.3 18.7 11.4 52-55 107.7-52.4 158.6 37 5.3 9.5 14.9 8.6 19.7 0 20.2-35.4 44.9-73.2 90.7-73.2 58.5 0 88.2 68.8 90.7 73.2 4.8 8.6 14.4 9.5 19.7 0 51-89.5 107.1-91.4 158.6-37 10.3 10 20.9-1.3 18.7-11.4zM256 301.7V432c0 8.8-7.2 16-16 16-7.8 0-13.2-5.3-15.1-10.7-5.9-16.7-24.1-25.4-40.8-19.5-16.7 5.9-25.4 24.2-19.5 40.8 11.2 31.9 41.6 53.3 75.4 53.3 44.1 0 80-35.9 80-80V301.6c-9.1-7.9-19.8-13.6-32-13.6-12.3.1-22.4 4.8-32 13.7z\"],\n    \"umbrella-beach\": [640, 512, [], \"f5ca\", \"M115.38 136.9l102.11 37.18c35.19-81.54 86.21-144.29 139-173.7-95.88-4.89-188.78 36.96-248.53 111.8-6.69 8.4-2.66 21.05 7.42 24.72zm132.25 48.16l238.48 86.83c35.76-121.38 18.7-231.66-42.63-253.98-7.4-2.7-15.13-4-23.09-4-58.02.01-128.27 69.17-172.76 171.15zM521.48 60.5c6.22 16.3 10.83 34.6 13.2 55.19 5.74 49.89-1.42 108.23-18.95 166.98l102.62 37.36c10.09 3.67 21.31-3.43 21.57-14.17 2.32-95.69-41.91-187.44-118.44-245.36zM560 447.98H321.06L386 269.5l-60.14-21.9-72.9 200.37H16c-8.84 0-16 7.16-16 16.01v32.01C0 504.83 7.16 512 16 512h544c8.84 0 16-7.17 16-16.01v-32.01c0-8.84-7.16-16-16-16z\"],\n    \"underline\": [448, 512, [], \"f0cd\", \"M32 64h32v160c0 88.22 71.78 160 160 160s160-71.78 160-160V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H272a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32v160a80 80 0 0 1-160 0V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm400 384H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"undo\": [512, 512, [], \"f0e2\", \"M212.333 224.333H12c-6.627 0-12-5.373-12-12V12C0 5.373 5.373 0 12 0h48c6.627 0 12 5.373 12 12v78.112C117.773 39.279 184.26 7.47 258.175 8.007c136.906.994 246.448 111.623 246.157 248.532C504.041 393.258 393.12 504 256.333 504c-64.089 0-122.496-24.313-166.51-64.215-5.099-4.622-5.334-12.554-.467-17.42l33.967-33.967c4.474-4.474 11.662-4.717 16.401-.525C170.76 415.336 211.58 432 256.333 432c97.268 0 176-78.716 176-176 0-97.267-78.716-176-176-176-58.496 0-110.28 28.476-142.274 72.333h98.274c6.627 0 12 5.373 12 12v48c0 6.627-5.373 12-12 12z\"],\n    \"undo-alt\": [512, 512, [], \"f2ea\", \"M255.545 8c-66.269.119-126.438 26.233-170.86 68.685L48.971 40.971C33.851 25.851 8 36.559 8 57.941V192c0 13.255 10.745 24 24 24h134.059c21.382 0 32.09-25.851 16.971-40.971l-41.75-41.75c30.864-28.899 70.801-44.907 113.23-45.273 92.398-.798 170.283 73.977 169.484 169.442C423.236 348.009 349.816 424 256 424c-41.127 0-79.997-14.678-110.63-41.556-4.743-4.161-11.906-3.908-16.368.553L89.34 422.659c-4.872 4.872-4.631 12.815.482 17.433C133.798 479.813 192.074 504 256 504c136.966 0 247.999-111.033 248-247.998C504.001 119.193 392.354 7.755 255.545 8z\"],\n    \"universal-access\": [512, 512, [], \"f29a\", \"M256 48c114.953 0 208 93.029 208 208 0 114.953-93.029 208-208 208-114.953 0-208-93.029-208-208 0-114.953 93.029-208 208-208m0-40C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 56C149.961 64 64 149.961 64 256s85.961 192 192 192 192-85.961 192-192S362.039 64 256 64zm0 44c19.882 0 36 16.118 36 36s-16.118 36-36 36-36-16.118-36-36 16.118-36 36-36zm117.741 98.023c-28.712 6.779-55.511 12.748-82.14 15.807.851 101.023 12.306 123.052 25.037 155.621 3.617 9.26-.957 19.698-10.217 23.315-9.261 3.617-19.699-.957-23.316-10.217-8.705-22.308-17.086-40.636-22.261-78.549h-9.686c-5.167 37.851-13.534 56.208-22.262 78.549-3.615 9.255-14.05 13.836-23.315 10.217-9.26-3.617-13.834-14.056-10.217-23.315 12.713-32.541 24.185-54.541 25.037-155.621-26.629-3.058-53.428-9.027-82.141-15.807-8.6-2.031-13.926-10.648-11.895-19.249s10.647-13.926 19.249-11.895c96.686 22.829 124.283 22.783 220.775 0 8.599-2.03 17.218 3.294 19.249 11.895 2.029 8.601-3.297 17.219-11.897 19.249z\"],\n    \"university\": [512, 512, [], \"f19c\", \"M496 128v16a8 8 0 0 1-8 8h-24v12c0 6.627-5.373 12-12 12H60c-6.627 0-12-5.373-12-12v-12H24a8 8 0 0 1-8-8v-16a8 8 0 0 1 4.941-7.392l232-88a7.996 7.996 0 0 1 6.118 0l232 88A8 8 0 0 1 496 128zm-24 304H40c-13.255 0-24 10.745-24 24v16a8 8 0 0 0 8 8h464a8 8 0 0 0 8-8v-16c0-13.255-10.745-24-24-24zM96 192v192H60c-6.627 0-12 5.373-12 12v20h416v-20c0-6.627-5.373-12-12-12h-36V192h-64v192h-64V192h-64v192h-64V192H96z\"],\n    \"unlink\": [512, 512, [], \"f127\", \"M304.083 405.907c4.686 4.686 4.686 12.284 0 16.971l-44.674 44.674c-59.263 59.262-155.693 59.266-214.961 0-59.264-59.265-59.264-155.696 0-214.96l44.675-44.675c4.686-4.686 12.284-4.686 16.971 0l39.598 39.598c4.686 4.686 4.686 12.284 0 16.971l-44.675 44.674c-28.072 28.073-28.072 73.75 0 101.823 28.072 28.072 73.75 28.073 101.824 0l44.674-44.674c4.686-4.686 12.284-4.686 16.971 0l39.597 39.598zm-56.568-260.216c4.686 4.686 12.284 4.686 16.971 0l44.674-44.674c28.072-28.075 73.75-28.073 101.824 0 28.072 28.073 28.072 73.75 0 101.823l-44.675 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.598 39.598c4.686 4.686 12.284 4.686 16.971 0l44.675-44.675c59.265-59.265 59.265-155.695 0-214.96-59.266-59.264-155.695-59.264-214.961 0l-44.674 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.597 39.598zm234.828 359.28l22.627-22.627c9.373-9.373 9.373-24.569 0-33.941L63.598 7.029c-9.373-9.373-24.569-9.373-33.941 0L7.029 29.657c-9.373 9.373-9.373 24.569 0 33.941l441.373 441.373c9.373 9.372 24.569 9.372 33.941 0z\"],\n    \"unlock\": [448, 512, [], \"f09c\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"unlock-alt\": [448, 512, [], \"f13e\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zM264 408c0 22.1-17.9 40-40 40s-40-17.9-40-40v-48c0-22.1 17.9-40 40-40s40 17.9 40 40v48z\"],\n    \"upload\": [512, 512, [], \"f093\", \"M296 384h-80c-13.3 0-24-10.7-24-24V192h-87.7c-17.8 0-26.7-21.5-14.1-34.1L242.3 5.7c7.5-7.5 19.8-7.5 27.3 0l152.2 152.2c12.6 12.6 3.7 34.1-14.1 34.1H320v168c0 13.3-10.7 24-24 24zm216-8v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h136v8c0 30.9 25.1 56 56 56h80c30.9 0 56-25.1 56-56v-8h136c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"user\": [448, 512, [], \"f007\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-alt\": [512, 512, [], \"f406\", \"M256 288c79.5 0 144-64.5 144-144S335.5 0 256 0 112 64.5 112 144s64.5 144 144 144zm128 32h-55.1c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16H128C57.3 320 0 377.3 0 448v16c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-16c0-70.7-57.3-128-128-128z\"],\n    \"user-alt-slash\": [640, 512, [], \"f4fa\", \"M633.8 458.1L389.6 269.3C433.8 244.7 464 198.1 464 144 464 64.5 399.5 0 320 0c-67.1 0-123 46.1-139 108.2L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM198.4 320C124.2 320 64 380.2 64 454.4v9.6c0 26.5 21.5 48 48 48h382.2L245.8 320h-47.4z\"],\n    \"user-astronaut\": [448, 512, [], \"f4fb\", \"M64 224h13.5c24.7 56.5 80.9 96 146.5 96s121.8-39.5 146.5-96H384c8.8 0 16-7.2 16-16v-96c0-8.8-7.2-16-16-16h-13.5C345.8 39.5 289.6 0 224 0S102.2 39.5 77.5 96H64c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16zm40-88c0-22.1 21.5-40 48-40h144c26.5 0 48 17.9 48 40v24c0 53-43 96-96 96h-48c-53 0-96-43-96-96v-24zm72 72l12-36 36-12-36-12-12-36-12 36-36 12 36 12 12 36zm151.6 113.4C297.7 340.7 262.2 352 224 352s-73.7-11.3-103.6-30.6C52.9 328.5 0 385 0 454.4v9.6c0 26.5 21.5 48 48 48h80v-64c0-17.7 14.3-32 32-32h128c17.7 0 32 14.3 32 32v64h80c26.5 0 48-21.5 48-48v-9.6c0-69.4-52.9-125.9-120.4-133zM272 448c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-96 0c-8.8 0-16 7.2-16 16v48h32v-48c0-8.8-7.2-16-16-16z\"],\n    \"user-check\": [640, 512, [], \"f4fc\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4zm323-128.4l-27.8-28.1c-4.6-4.7-12.1-4.7-16.8-.1l-104.8 104-45.5-45.8c-4.6-4.7-12.1-4.7-16.8-.1l-28.1 27.9c-4.7 4.6-4.7 12.1-.1 16.8l81.7 82.3c4.6 4.7 12.1 4.7 16.8.1l141.3-140.2c4.6-4.7 4.7-12.2.1-16.8z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 96c48.6 0 88 39.4 88 88s-39.4 88-88 88-88-39.4-88-88 39.4-88 88-88zm0 344c-58.7 0-111.3-26.6-146.5-68.2 18.8-35.4 55.6-59.8 98.5-59.8 2.4 0 4.8.4 7.1 1.1 13 4.2 26.6 6.9 40.9 6.9 14.3 0 28-2.7 40.9-6.9 2.3-.7 4.7-1.1 7.1-1.1 42.9 0 79.7 24.4 98.5 59.8C359.3 421.4 306.7 448 248 448z\"],\n    \"user-clock\": [640, 512, [], \"f4fd\", \"M496 224c-79.6 0-144 64.4-144 144s64.4 144 144 144 144-64.4 144-144-64.4-144-144-144zm64 150.3c0 5.3-4.4 9.7-9.7 9.7h-60.6c-5.3 0-9.7-4.4-9.7-9.7v-76.6c0-5.3 4.4-9.7 9.7-9.7h12.6c5.3 0 9.7 4.4 9.7 9.7V352h38.3c5.3 0 9.7 4.4 9.7 9.7v12.6zM320 368c0-27.8 6.7-54.1 18.2-77.5-8-1.5-16.2-2.5-24.6-2.5h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h347.1c-45.3-31.9-75.1-84.5-75.1-144zm-96-112c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128z\"],\n    \"user-cog\": [640, 512, [], \"f4fe\", \"M610.5 373.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 400.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm201.2 226.5c-2.3-1.2-4.6-2.6-6.8-3.9l-7.9 4.6c-6 3.4-12.8 5.3-19.6 5.3-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-5.5-17.7 1.9-36.4 17.9-45.7l7.9-4.6c-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-16-9.2-23.4-28-17.9-45.7.9-2.9 2.2-5.8 3.2-8.7-3.8-.3-7.5-1.2-11.4-1.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c10.1 0 19.5-3.2 27.2-8.5-1.2-3.8-2-7.7-2-11.8v-9.2z\"],\n    \"user-edit\": [640, 512, [], \"f4ff\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h274.9c-2.4-6.8-3.4-14-2.6-21.3l6.8-60.9 1.2-11.1 7.9-7.9 77.3-77.3c-24.5-27.7-60-45.5-99.9-45.5zm45.3 145.3l-6.8 61c-1.1 10.2 7.5 18.8 17.6 17.6l60.9-6.8 137.9-137.9-71.7-71.7-137.9 137.8zM633 268.9L595.1 231c-9.3-9.3-24.5-9.3-33.8 0l-37.8 37.8-4.1 4.1 71.8 71.7 41.8-41.8c9.3-9.4 9.3-24.5 0-33.9z\"],\n    \"user-friends\": [640, 512, [], \"f500\", \"M192 256c61.9 0 112-50.1 112-112S253.9 32 192 32 80 82.1 80 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C51.6 288 0 339.6 0 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zM480 256c53 0 96-43 96-96s-43-96-96-96-96 43-96 96 43 96 96 96zm48 32h-3.8c-13.9 4.8-28.6 8-44.2 8s-30.3-3.2-44.2-8H432c-20.4 0-39.2 5.9-55.7 15.4 24.4 26.3 39.7 61.2 39.7 99.8v38.4c0 2.2-.5 4.3-.6 6.4H592c26.5 0 48-21.5 48-48 0-61.9-50.1-112-112-112z\"],\n    \"user-graduate\": [448, 512, [], \"f501\", \"M319.4 320.6L224 416l-95.4-95.4C57.1 323.7 0 382.2 0 454.4v9.6c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-9.6c0-72.2-57.1-130.7-128.6-133.8zM13.6 79.8l6.4 1.5v58.4c-7 4.2-12 11.5-12 20.3 0 8.4 4.6 15.4 11.1 19.7L3.5 242c-1.7 6.9 2.1 14 7.6 14h41.8c5.5 0 9.3-7.1 7.6-14l-15.6-62.3C51.4 175.4 56 168.4 56 160c0-8.8-5-16.1-12-20.3V87.1l66 15.9c-8.6 17.2-14 36.4-14 57 0 70.7 57.3 128 128 128s128-57.3 128-128c0-20.6-5.3-39.8-14-57l96.3-23.2c18.2-4.4 18.2-27.1 0-31.5l-190.4-46c-13-3.1-26.7-3.1-39.7 0L13.6 48.2c-18.1 4.4-18.1 27.2 0 31.6z\"],\n    \"user-injured\": [448, 512, [], \"f728\", \"M277.37 11.98C261.08 4.47 243.11 0 224 0c-53.69 0-99.5 33.13-118.51 80h81.19l90.69-68.02zM342.51 80c-7.9-19.47-20.67-36.2-36.49-49.52L239.99 80h102.52zM224 256c70.69 0 128-57.31 128-128 0-5.48-.95-10.7-1.61-16H97.61c-.67 5.3-1.61 10.52-1.61 16 0 70.69 57.31 128 128 128zM80 299.7V512h128.26l-98.45-221.52A132.835 132.835 0 0 0 80 299.7zM0 464c0 26.51 21.49 48 48 48V320.24C18.88 344.89 0 381.26 0 422.4V464zm256-48h-55.38l42.67 96H256c26.47 0 48-21.53 48-48s-21.53-48-48-48zm57.6-128h-16.71c-22.24 10.18-46.88 16-72.89 16s-50.65-5.82-72.89-16h-7.37l42.67 96H256c44.11 0 80 35.89 80 80 0 18.08-6.26 34.59-16.41 48H400c26.51 0 48-21.49 48-48v-41.6c0-74.23-60.17-134.4-134.4-134.4z\"],\n    \"user-lock\": [640, 512, [], \"f502\", \"M224 256A128 128 0 1 0 96 128a128 128 0 0 0 128 128zm96 64a63.08 63.08 0 0 1 8.1-30.5c-4.8-.5-9.5-1.5-14.5-1.5h-16.7a174.08 174.08 0 0 1-145.8 0h-16.7A134.43 134.43 0 0 0 0 422.4V464a48 48 0 0 0 48 48h280.9a63.54 63.54 0 0 1-8.9-32zm288-32h-32v-80a80 80 0 0 0-160 0v80h-32a32 32 0 0 0-32 32v160a32 32 0 0 0 32 32h224a32 32 0 0 0 32-32V320a32 32 0 0 0-32-32zM496 432a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm32-144h-64v-80a32 32 0 0 1 64 0z\"],\n    \"user-md\": [448, 512, [], \"f0f0\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zM104 424c0 13.3 10.7 24 24 24s24-10.7 24-24-10.7-24-24-24-24 10.7-24 24zm216-135.4v49c36.5 7.4 64 39.8 64 78.4v41.7c0 7.6-5.4 14.2-12.9 15.7l-32.2 6.4c-4.3.9-8.5-1.9-9.4-6.3l-3.1-15.7c-.9-4.3 1.9-8.6 6.3-9.4l19.3-3.9V416c0-62.8-96-65.1-96 1.9v26.7l19.3 3.9c4.3.9 7.1 5.1 6.3 9.4l-3.1 15.7c-.9 4.3-5.1 7.1-9.4 6.3l-31.2-4.2c-7.9-1.1-13.8-7.8-13.8-15.9V416c0-38.6 27.5-70.9 64-78.4v-45.2c-2.2.7-4.4 1.1-6.6 1.9-18 6.3-37.3 9.8-57.4 9.8s-39.4-3.5-57.4-9.8c-7.4-2.6-14.9-4.2-22.6-5.2v81.6c23.1 6.9 40 28.1 40 53.4 0 30.9-25.1 56-56 56s-56-25.1-56-56c0-25.3 16.9-46.5 40-53.4v-80.4C48.5 301 0 355.8 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-72-56.8-130.3-128-133.8z\"],\n    \"user-minus\": [640, 512, [], \"f503\", \"M624 208H432c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h192c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-ninja\": [448, 512, [], \"f504\", \"M325.4 289.2L224 390.6 122.6 289.2C54 295.3 0 352.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-70.2-54-127.1-122.6-133.2zM32 192c27.3 0 51.8-11.5 69.2-29.7 15.1 53.9 64 93.7 122.8 93.7 70.7 0 128-57.3 128-128S294.7 0 224 0c-50.4 0-93.6 29.4-114.5 71.8C92.1 47.8 64 32 32 32c0 33.4 17.1 62.8 43.1 80-26 17.2-43.1 46.6-43.1 80zm144-96h96c17.7 0 32 14.3 32 32H144c0-17.7 14.3-32 32-32z\"],\n    \"user-nurse\": [448, 512, [], \"f82f\", \"M57.78 288h82.36c22.51 19.68 51.62 32 83.86 32s61.35-12.32 83.86-32h82.36a16 16 0 0 0 14.28-23.18c-15.23-29.85-31.28-62.23-42.15-95.54C354.78 146.09 352 121.59 352 97.2V48L224 0 96 48v49.2c0 24.39-2.75 48.89-10.33 72.08C74.78 202.59 58.73 235 43.5 264.82A16 16 0 0 0 57.78 288zM184 71.67a5 5 0 0 1 5-5h21.67V45a5 5 0 0 1 5-5h16.66a5 5 0 0 1 5 5v21.67H259a5 5 0 0 1 5 5v16.66a5 5 0 0 1-5 5h-21.67V115a5 5 0 0 1-5 5h-16.66a5 5 0 0 1-5-5V93.33H189a5 5 0 0 1-5-5zM144 160h160v32a80 80 0 0 1-160 0zm175.41 160L224 415.39 128.59 320C57.1 323.1 0 381.6 0 453.79A58.21 58.21 0 0 0 58.21 512h331.58A58.21 58.21 0 0 0 448 453.79C448 381.6 390.9 323.1 319.41 320z\"],\n    \"user-plus\": [640, 512, [], \"f234\", \"M624 208h-64v-64c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v64h-64c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h64v64c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-64h64c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-secret\": [448, 512, [], \"f21b\", \"M383.9 308.3l23.9-62.6c4-10.5-3.7-21.7-15-21.7h-58.5c11-18.9 17.8-40.6 17.8-64v-.3c39.2-7.8 64-19.1 64-31.7 0-13.3-27.3-25.1-70.1-33-9.2-32.8-27-65.8-40.6-82.8-9.5-11.9-25.9-15.6-39.5-8.8l-27.6 13.8c-9 4.5-19.6 4.5-28.6 0L182.1 3.4c-13.6-6.8-30-3.1-39.5 8.8-13.5 17-31.4 50-40.6 82.8-42.7 7.9-70 19.7-70 33 0 12.6 24.8 23.9 64 31.7v.3c0 23.4 6.8 45.1 17.8 64H56.3c-11.5 0-19.2 11.7-14.7 22.3l25.8 60.2C27.3 329.8 0 372.7 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-48.4-25.8-90.4-64.1-114.1zM176 480l-41.6-192 49.6 32 24 40-32 120zm96 0l-32-120 24-40 49.6-32L272 480zm41.7-298.5c-3.9 11.9-7 24.6-16.5 33.4-10.1 9.3-48 22.4-64-25-2.8-8.4-15.4-8.4-18.3 0-17 50.2-56 32.4-64 25-9.5-8.8-12.7-21.5-16.5-33.4-.8-2.5-6.3-5.7-6.3-5.8v-10.8c28.3 3.6 61 5.8 96 5.8s67.7-2.1 96-5.8v10.8c-.1.1-5.6 3.2-6.4 5.8z\"],\n    \"user-shield\": [640, 512, [], \"f505\", \"M622.3 271.1l-115.2-45c-4.1-1.6-12.6-3.7-22.2 0l-115.2 45c-10.7 4.2-17.7 14-17.7 24.9 0 111.6 68.7 188.8 132.9 213.9 9.6 3.7 18 1.6 22.2 0C558.4 489.9 640 420.5 640 296c0-10.9-7-20.7-17.7-24.9zM496 462.4V273.3l95.5 37.3c-5.6 87.1-60.9 135.4-95.5 151.8zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm96 40c0-2.5.8-4.8 1.1-7.2-2.5-.1-4.9-.8-7.5-.8h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c6.8 0 13.3-1.5 19.2-4-54-42.9-99.2-116.7-99.2-212z\"],\n    \"user-slash\": [640, 512, [], \"f506\", \"M633.8 458.1L362.3 248.3C412.1 230.7 448 183.8 448 128 448 57.3 390.7 0 320 0c-67.1 0-121.5 51.8-126.9 117.4L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM96 422.4V464c0 26.5 21.5 48 48 48h350.2L207.4 290.3C144.2 301.3 96 356 96 422.4z\"],\n    \"user-tag\": [640, 512, [], \"f507\", \"M630.6 364.9l-90.3-90.2c-12-12-28.3-18.7-45.3-18.7h-79.3c-17.7 0-32 14.3-32 32v79.2c0 17 6.7 33.2 18.7 45.2l90.3 90.2c12.5 12.5 32.8 12.5 45.3 0l92.5-92.5c12.6-12.5 12.6-32.7.1-45.2zm-182.8-21c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24c0 13.2-10.7 24-24 24zm-223.8-88c70.7 0 128-57.3 128-128C352 57.3 294.7 0 224 0S96 57.3 96 128c0 70.6 57.3 127.9 128 127.9zm127.8 111.2V294c-12.2-3.6-24.9-6.2-38.2-6.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 287.9 0 348.1 0 422.3v41.6c0 26.5 21.5 48 48 48h352c15.5 0 29.1-7.5 37.9-18.9l-58-58c-18.1-18.1-28.1-42.2-28.1-67.9z\"],\n    \"user-tie\": [448, 512, [], \"f508\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm95.8 32.6L272 480l-32-136 32-56h-96l32 56-32 136-47.8-191.4C56.9 292 0 350.3 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-72.1-56.9-130.4-128.2-133.8z\"],\n    \"user-times\": [640, 512, [], \"f235\", \"M589.6 240l45.6-45.6c6.3-6.3 6.3-16.5 0-22.8l-22.8-22.8c-6.3-6.3-16.5-6.3-22.8 0L544 194.4l-45.6-45.6c-6.3-6.3-16.5-6.3-22.8 0l-22.8 22.8c-6.3 6.3-6.3 16.5 0 22.8l45.6 45.6-45.6 45.6c-6.3 6.3-6.3 16.5 0 22.8l22.8 22.8c6.3 6.3 16.5 6.3 22.8 0l45.6-45.6 45.6 45.6c6.3 6.3 16.5 6.3 22.8 0l22.8-22.8c6.3-6.3 6.3-16.5 0-22.8L589.6 240zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"users\": [640, 512, [], \"f0c0\", \"M96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm448 0c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm32 32h-64c-17.6 0-33.5 7.1-45.1 18.6 40.3 22.1 68.9 62 75.1 109.4h66c17.7 0 32-14.3 32-32v-32c0-35.3-28.7-64-64-64zm-256 0c61.9 0 112-50.1 112-112S381.9 32 320 32 208 82.1 208 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zm-223.7-13.4C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"users-cog\": [640, 512, [], \"f509\", \"M610.5 341.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 368.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm224 32c1.9 0 3.7-.5 5.6-.6 8.3-21.7 20.5-42.1 36.3-59.2 7.4-8 17.9-12.6 28.9-12.6 6.9 0 13.7 1.8 19.6 5.3l7.9 4.6c.8-.5 1.6-.9 2.4-1.4 7-14.6 11.2-30.8 11.2-48 0-61.9-50.1-112-112-112S208 82.1 208 144c0 61.9 50.1 112 112 112zm105.2 194.5c-2.3-1.2-4.6-2.6-6.8-3.9-8.2 4.8-15.3 9.8-27.5 9.8-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-10.7-34.5 24.9-49.7 25.8-50.3-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-3.8-2.2-7-5-9.8-8.1-3.3.2-6.5.6-9.8.6-24.6 0-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h255.4c-3.7-6-6.2-12.8-6.2-20.3v-9.2zM173.1 274.6C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"utensil-spoon\": [512, 512, [], \"f2e5\", \"M480.1 31.9c-55-55.1-164.9-34.5-227.8 28.5-49.3 49.3-55.1 110-28.8 160.4L9 413.2c-11.6 10.5-12.1 28.5-1 39.5L59.3 504c11 11 29.1 10.5 39.5-1.1l192.4-214.4c50.4 26.3 111.1 20.5 160.4-28.8 63-62.9 83.6-172.8 28.5-227.8z\"],\n    \"utensils\": [416, 512, [], \"f2e7\", \"M207.9 15.2c.8 4.7 16.1 94.5 16.1 128.8 0 52.3-27.8 89.6-68.9 104.6L168 486.7c.7 13.7-10.2 25.3-24 25.3H80c-13.7 0-24.7-11.5-24-25.3l12.9-238.1C27.7 233.6 0 196.2 0 144 0 109.6 15.3 19.9 16.1 15.2 19.3-5.1 61.4-5.4 64 16.3v141.2c1.3 3.4 15.1 3.2 16 0 1.4-25.3 7.9-139.2 8-141.8 3.3-20.8 44.7-20.8 47.9 0 .2 2.7 6.6 116.5 8 141.8.9 3.2 14.8 3.4 16 0V16.3c2.6-21.6 44.8-21.4 48-1.1zm119.2 285.7l-15 185.1c-1.2 14 9.9 26 23.9 26h56c13.3 0 24-10.7 24-24V24c0-13.2-10.7-24-24-24-82.5 0-221.4 178.5-64.9 300.9z\"],\n    \"vector-square\": [512, 512, [], \"f5cb\", \"M512 128V32c0-17.67-14.33-32-32-32h-96c-17.67 0-32 14.33-32 32H160c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32v192c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32h192c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32V160c17.67 0 32-14.33 32-32zm-96-64h32v32h-32V64zM64 64h32v32H64V64zm32 384H64v-32h32v32zm352 0h-32v-32h32v32zm-32-96h-32c-17.67 0-32 14.33-32 32v32H160v-32c0-17.67-14.33-32-32-32H96V160h32c17.67 0 32-14.33 32-32V96h192v32c0 17.67 14.33 32 32 32h32v192z\"],\n    \"venus\": [288, 512, [], \"f221\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"venus-double\": [512, 512, [], \"f226\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80zm336 140.4V368h36c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-36v36c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-36h-36c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h36v-51.6c-21.2-4.8-40.6-14.3-57.2-27.3 14-16.7 25-36 32.1-57.1 14.5 14.8 34.7 24 57.1 24 44.1 0 80-35.9 80-80s-35.9-80-80-80c-22.3 0-42.6 9.2-57.1 24-7.1-21.1-18-40.4-32.1-57.1C303.4 43.6 334.3 32 368 32c79.5 0 144 64.5 144 144 0 68.5-47.9 125.9-112 140.4z\"],\n    \"venus-mars\": [576, 512, [], \"f228\", \"M564 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C422.5 72.1 396.2 64 368 64c-33.7 0-64.6 11.6-89.2 30.9 14 16.7 25 36 32.1 57.1 14.5-14.8 34.7-24 57.1-24 44.1 0 80 35.9 80 80s-35.9 80-80 80c-22.3 0-42.6-9.2-57.1-24-7.1 21.1-18 40.4-32.1 57.1 24.5 19.4 55.5 30.9 89.2 30.9 79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 64C64.5 64 0 128.5 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.6 112-71.9 112-140.4 0-79.5-64.5-144-144-144zm0 224c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"vial\": [480, 512, [], \"f492\", \"M477.7 186.1L309.5 18.3c-3.1-3.1-8.2-3.1-11.3 0l-34 33.9c-3.1 3.1-3.1 8.2 0 11.3l11.2 11.1L33 316.5c-38.8 38.7-45.1 102-9.4 143.5 20.6 24 49.5 36 78.4 35.9 26.4 0 52.8-10 72.9-30.1l246.3-245.7 11.2 11.1c3.1 3.1 8.2 3.1 11.3 0l34-33.9c3.1-3 3.1-8.1 0-11.2zM318 256H161l148-147.7 78.5 78.3L318 256z\"],\n    \"vials\": [640, 512, [], \"f493\", \"M72 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H72c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64zm480 384H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM360 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64z\"],\n    \"video\": [576, 512, [], \"f03d\", \"M336.2 64H47.8C21.4 64 0 85.4 0 111.8v288.4C0 426.6 21.4 448 47.8 448h288.4c26.4 0 47.8-21.4 47.8-47.8V111.8c0-26.4-21.4-47.8-47.8-47.8zm189.4 37.7L416 177.3v157.4l109.6 75.5c21.2 14.6 50.4-.3 50.4-25.8V127.5c0-25.4-29.1-40.4-50.4-25.8z\"],\n    \"video-slash\": [640, 512, [], \"f4e2\", \"M633.8 458.1l-55-42.5c15.4-1.4 29.2-13.7 29.2-31.1v-257c0-25.5-29.1-40.4-50.4-25.8L448 177.3v137.2l-32-24.7v-178c0-26.4-21.4-47.8-47.8-47.8H123.9L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4L42.7 82 416 370.6l178.5 138c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.5-6.9 4.2-17-2.8-22.4zM32 400.2c0 26.4 21.4 47.8 47.8 47.8h288.4c11.2 0 21.4-4 29.6-10.5L32 154.7v245.5z\"],\n    \"vihara\": [640, 512, [], \"f6a7\", \"M632.88 400.71L544 352v-64l55.16-17.69c11.79-5.9 11.79-22.72 0-28.62L480 192v-64l27.31-16.3c7.72-7.72 5.61-20.74-4.16-25.62L320 0 136.85 86.07c-9.77 4.88-11.88 17.9-4.16 25.62L160 128v64L40.84 241.69c-11.79 5.9-11.79 22.72 0 28.62L96 288v64L7.12 400.71c-5.42 3.62-7.7 9.63-7 15.29.62 5.01 3.57 9.75 8.72 12.33L64 448v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48l55.15-19.67c5.16-2.58 8.1-7.32 8.72-12.33.71-5.67-1.57-11.68-6.99-15.29zM224 128h192v64H224v-64zm-64 224v-64h320v64H160z\"],\n    \"voicemail\": [640, 512, [], \"f897\", \"M496 128a144 144 0 0 0-119.74 224H263.74A144 144 0 1 0 144 416h352a144 144 0 0 0 0-288zM64 272a80 80 0 1 1 80 80 80 80 0 0 1-80-80zm432 80a80 80 0 1 1 80-80 80 80 0 0 1-80 80z\"],\n    \"volleyball-ball\": [512, 512, [], \"f45f\", \"M231.39 243.48a285.56 285.56 0 0 0-22.7-105.7c-90.8 42.4-157.5 122.4-180.3 216.8a249 249 0 0 0 56.9 81.1 333.87 333.87 0 0 1 146.1-192.2zm-36.9-134.4a284.23 284.23 0 0 0-57.4-70.7c-91 49.8-144.8 152.9-125 262.2 33.4-83.1 98.4-152 182.4-191.5zm187.6 165.1c8.6-99.8-27.3-197.5-97.5-264.4-14.7-1.7-51.6-5.5-98.9 8.5A333.87 333.87 0 0 1 279.19 241a285 285 0 0 0 102.9 33.18zm-124.7 9.5a286.33 286.33 0 0 0-80.2 72.6c82 57.3 184.5 75.1 277.5 47.8a247.15 247.15 0 0 0 42.2-89.9 336.1 336.1 0 0 1-80.9 10.4c-54.6-.1-108.9-14.1-158.6-40.9zm-98.3 99.7c-15.2 26-25.7 54.4-32.1 84.2a247.07 247.07 0 0 0 289-22.1c-112.9 16.1-203.3-24.8-256.9-62.1zm180.3-360.6c55.3 70.4 82.5 161.2 74.6 253.6a286.59 286.59 0 0 0 89.7-14.2c0-2 .3-4 .3-6 0-107.8-68.7-199.1-164.6-233.4z\"],\n    \"volume-down\": [384, 512, [], \"f027\", \"M215.03 72.04L126.06 161H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V89.02c0-21.47-25.96-31.98-40.97-16.98zm123.2 108.08c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 229.28 336 242.62 336 257c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.87z\"],\n    \"volume-mute\": [512, 512, [], \"f6a9\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zM461.64 256l45.64-45.64c6.3-6.3 6.3-16.52 0-22.82l-22.82-22.82c-6.3-6.3-16.52-6.3-22.82 0L416 210.36l-45.64-45.64c-6.3-6.3-16.52-6.3-22.82 0l-22.82 22.82c-6.3 6.3-6.3 16.52 0 22.82L370.36 256l-45.63 45.63c-6.3 6.3-6.3 16.52 0 22.82l22.82 22.82c6.3 6.3 16.52 6.3 22.82 0L416 301.64l45.64 45.64c6.3 6.3 16.52 6.3 22.82 0l22.82-22.82c6.3-6.3 6.3-16.52 0-22.82L461.64 256z\"],\n    \"volume-off\": [256, 512, [], \"f026\", \"M215 71l-89 89H24a24 24 0 0 0-24 24v144a24 24 0 0 0 24 24h102.06L215 441c15 15 41 4.47 41-17V88c0-21.47-26-32-41-17z\"],\n    \"volume-up\": [576, 512, [], \"f028\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zm233.32-51.08c-11.17-7.33-26.18-4.24-33.51 6.95-7.34 11.17-4.22 26.18 6.95 33.51 66.27 43.49 105.82 116.6 105.82 195.58 0 78.98-39.55 152.09-105.82 195.58-11.17 7.32-14.29 22.34-6.95 33.5 7.04 10.71 21.93 14.56 33.51 6.95C528.27 439.58 576 351.33 576 256S528.27 72.43 448.35 19.97zM480 256c0-63.53-32.06-121.94-85.77-156.24-11.19-7.14-26.03-3.82-33.12 7.46s-3.78 26.21 7.41 33.36C408.27 165.97 432 209.11 432 256s-23.73 90.03-63.48 115.42c-11.19 7.14-14.5 22.07-7.41 33.36 6.51 10.36 21.12 15.14 33.12 7.46C447.94 377.94 480 319.54 480 256zm-141.77-76.87c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 228.28 336 241.63 336 256c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.86z\"],\n    \"vote-yea\": [640, 512, [], \"f772\", \"M608 320h-64v64h22.4c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8H96v-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h576c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32zm-96 64V64.3c0-17.9-14.5-32.3-32.3-32.3H160.4C142.5 32 128 46.5 128 64.3V384h384zM211.2 202l25.5-25.3c4.2-4.2 11-4.2 15.2.1l41.3 41.6 95.2-94.4c4.2-4.2 11-4.2 15.2.1l25.3 25.5c4.2 4.2 4.2 11-.1 15.2L300.5 292c-4.2 4.2-11 4.2-15.2-.1l-74.1-74.7c-4.3-4.2-4.2-11 0-15.2z\"],\n    \"vr-cardboard\": [640, 512, [], \"f729\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h160.22c25.19 0 48.03-14.77 58.36-37.74l27.74-61.64C286.21 331.08 302.35 320 320 320s33.79 11.08 41.68 28.62l27.74 61.64C399.75 433.23 422.6 448 447.78 448H608c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM160 304c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64zm320 0c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64z\"],\n    \"walking\": [320, 512, [], \"f554\", \"M208 96c26.5 0 48-21.5 48-48S234.5 0 208 0s-48 21.5-48 48 21.5 48 48 48zm94.5 149.1l-23.3-11.8-9.7-29.4c-14.7-44.6-55.7-75.8-102.2-75.9-36-.1-55.9 10.1-93.3 25.2-21.6 8.7-39.3 25.2-49.7 46.2L17.6 213c-7.8 15.8-1.5 35 14.2 42.9 15.6 7.9 34.6 1.5 42.5-14.3L81 228c3.5-7 9.3-12.5 16.5-15.4l26.8-10.8-15.2 60.7c-5.2 20.8.4 42.9 14.9 58.8l59.9 65.4c7.2 7.9 12.3 17.4 14.9 27.7l18.3 73.3c4.3 17.1 21.7 27.6 38.8 23.3 17.1-4.3 27.6-21.7 23.3-38.8l-22.2-89c-2.6-10.3-7.7-19.9-14.9-27.7l-45.5-49.7 17.2-68.7 5.5 16.5c5.3 16.1 16.7 29.4 31.7 37l23.3 11.8c15.6 7.9 34.6 1.5 42.5-14.3 7.7-15.7 1.4-35.1-14.3-43zM73.6 385.8c-3.2 8.1-8 15.4-14.2 21.5l-50 50.1c-12.5 12.5-12.5 32.8 0 45.3s32.7 12.5 45.2 0l59.4-59.4c6.1-6.1 10.9-13.4 14.2-21.5l13.5-33.8c-55.3-60.3-38.7-41.8-47.4-53.7l-20.7 51.5z\"],\n    \"wallet\": [512, 512, [], \"f555\", \"M461.2 128H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h384c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h397.2c28.02 0 50.8-21.53 50.8-48V176c0-26.47-22.78-48-50.8-48zM416 336c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"warehouse\": [640, 512, [], \"f494\", \"M504 352H136.4c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0 96H136.1c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8h368c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0-192H136.6c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm106.5-139L338.4 3.7a48.15 48.15 0 0 0-36.9 0L29.5 117C11.7 124.5 0 141.9 0 161.3V504c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V256c0-17.6 14.6-32 32.6-32h382.8c18 0 32.6 14.4 32.6 32v248c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V161.3c0-19.4-11.7-36.8-29.5-44.3z\"],\n    \"water\": [576, 512, [], \"f773\", \"M562.1 383.9c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144C540.6 93.4 520 85.4 504.2 73 490.1 61.9 470 61.7 456 73c-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3z\"],\n    \"wave-square\": [640, 512, [], \"f83e\", \"M476 480H324a36 36 0 0 1-36-36V96h-96v156a36 36 0 0 1-36 36H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h112V68a36 36 0 0 1 36-36h152a36 36 0 0 1 36 36v348h96V260a36 36 0 0 1 36-36h140a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H512v156a36 36 0 0 1-36 36z\"],\n    \"weight\": [512, 512, [], \"f496\", \"M448 64h-25.98C438.44 92.28 448 125.01 448 160c0 105.87-86.13 192-192 192S64 265.87 64 160c0-34.99 9.56-67.72 25.98-96H64C28.71 64 0 92.71 0 128v320c0 35.29 28.71 64 64 64h384c35.29 0 64-28.71 64-64V128c0-35.29-28.71-64-64-64zM256 320c88.37 0 160-71.63 160-160S344.37 0 256 0 96 71.63 96 160s71.63 160 160 160zm-.3-151.94l33.58-78.36c3.5-8.17 12.94-11.92 21.03-8.41 8.12 3.48 11.88 12.89 8.41 21l-33.67 78.55C291.73 188 296 197.45 296 208c0 22.09-17.91 40-40 40s-40-17.91-40-40c0-21.98 17.76-39.77 39.7-39.94z\"],\n    \"weight-hanging\": [512, 512, [], \"f5cd\", \"M510.28 445.86l-73.03-292.13c-3.8-15.19-16.44-25.72-30.87-25.72h-60.25c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96s-96 42.98-96 96c0 11.28 2.3 21.95 5.88 32h-60.25c-14.43 0-27.08 10.54-30.87 25.72L1.72 445.86C-6.61 479.17 16.38 512 48.03 512h415.95c31.64 0 54.63-32.83 46.3-66.14zM256 128c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"wheelchair\": [512, 512, [], \"f193\", \"M496.101 385.669l14.227 28.663c3.929 7.915.697 17.516-7.218 21.445l-65.465 32.886c-16.049 7.967-35.556 1.194-43.189-15.055L331.679 320H192c-15.925 0-29.426-11.71-31.679-27.475C126.433 55.308 128.38 70.044 128 64c0-36.358 30.318-65.635 67.052-63.929 33.271 1.545 60.048 28.905 60.925 62.201.868 32.933-23.152 60.423-54.608 65.039l4.67 32.69H336c8.837 0 16 7.163 16 16v32c0 8.837-7.163 16-16 16H215.182l4.572 32H352a32 32 0 0 1 28.962 18.392L438.477 396.8l36.178-18.349c7.915-3.929 17.517-.697 21.446 7.218zM311.358 352h-24.506c-7.788 54.204-54.528 96-110.852 96-61.757 0-112-50.243-112-112 0-41.505 22.694-77.809 56.324-97.156-3.712-25.965-6.844-47.86-9.488-66.333C45.956 198.464 0 261.963 0 336c0 97.047 78.953 176 176 176 71.87 0 133.806-43.308 161.11-105.192L311.358 352z\"],\n    \"wifi\": [640, 512, [], \"f1eb\", \"M634.91 154.88C457.74-8.99 182.19-8.93 5.09 154.88c-6.66 6.16-6.79 16.59-.35 22.98l34.24 33.97c6.14 6.1 16.02 6.23 22.4.38 145.92-133.68 371.3-133.71 517.25 0 6.38 5.85 16.26 5.71 22.4-.38l34.24-33.97c6.43-6.39 6.3-16.82-.36-22.98zM320 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm202.67-83.59c-115.26-101.93-290.21-101.82-405.34 0-6.9 6.1-7.12 16.69-.57 23.15l34.44 33.99c6 5.92 15.66 6.32 22.05.8 83.95-72.57 209.74-72.41 293.49 0 6.39 5.52 16.05 5.13 22.05-.8l34.44-33.99c6.56-6.46 6.33-17.06-.56-23.15z\"],\n    \"wind\": [512, 512, [], \"f72e\", \"M156.7 256H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h142.2c15.9 0 30.8 10.9 33.4 26.6 3.3 20-12.1 37.4-31.6 37.4-14.1 0-26.1-9.2-30.4-21.9-2.1-6.3-8.6-10.1-15.2-10.1H81.6c-9.8 0-17.7 8.8-15.9 18.4 8.6 44.1 47.6 77.6 94.2 77.6 57.1 0 102.7-50.1 95.2-108.6C249 291 205.4 256 156.7 256zM16 224h336c59.7 0 106.8-54.8 93.8-116.7-7.6-36.2-36.9-65.5-73.1-73.1-55.4-11.6-105.1 24.9-114.9 75.5-1.9 9.6 6.1 18.3 15.8 18.3h32.8c6.7 0 13.1-3.8 15.2-10.1C325.9 105.2 337.9 96 352 96c19.4 0 34.9 17.4 31.6 37.4-2.6 15.7-17.4 26.6-33.4 26.6H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16zm384 32H243.7c19.3 16.6 33.2 38.8 39.8 64H400c26.5 0 48 21.5 48 48s-21.5 48-48 48c-17.9 0-33.3-9.9-41.6-24.4-2.9-5-8.7-7.6-14.5-7.6h-33.8c-10.9 0-19 10.8-15.3 21.1 17.8 50.6 70.5 84.8 129.4 72.3 41.2-8.7 75.1-41.6 84.7-82.7C526 321.5 470.5 256 400 256z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-83.6 290.5c4.8 4.8 4.8 12.6 0 17.4l-40.5 40.5c-4.8 4.8-12.6 4.8-17.4 0L256 313.3l-66.5 67.1c-4.8 4.8-12.6 4.8-17.4 0l-40.5-40.5c-4.8-4.8-4.8-12.6 0-17.4l67.1-66.5-67.1-66.5c-4.8-4.8-4.8-12.6 0-17.4l40.5-40.5c4.8-4.8 12.6-4.8 17.4 0l66.5 67.1 66.5-67.1c4.8-4.8 12.6-4.8 17.4 0l40.5 40.5c4.8 4.8 4.8 12.6 0 17.4L313.3 256l67.1 66.5z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16 160H64v-84c0-6.6 5.4-12 12-12h360c6.6 0 12 5.4 12 12v84z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M464 352H48c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M512 48v288c0 26.5-21.5 48-48 48h-48V176c0-44.1-35.9-80-80-80H128V48c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zM384 176v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zm-68 28c0-6.6-5.4-12-12-12H76c-6.6 0-12 5.4-12 12v52h252v-52z\"],\n    \"wine-bottle\": [512, 512, [], \"f72f\", \"M507.31 72.57L439.43 4.69c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l-76.67 76.67c-46.58-19.7-102.4-10.73-140.37 27.23L18.75 312.23c-24.99 24.99-24.99 65.52 0 90.51l90.51 90.51c24.99 24.99 65.52 24.99 90.51 0l158.39-158.39c37.96-37.96 46.93-93.79 27.23-140.37l76.67-76.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.24-6.24 6.24-16.37-.01-22.62zM179.22 423.29l-90.51-90.51 122.04-122.04 90.51 90.51-122.04 122.04z\"],\n    \"wine-glass\": [288, 512, [], \"f4e3\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40z\"],\n    \"wine-glass-alt\": [288, 512, [], \"f5ce\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM61.75 48h164.5l7.17 80H54.58l7.17-80z\"],\n    \"won-sign\": [576, 512, [], \"f159\", \"M564 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-48l18.6-80.6c1.7-7.5-4-14.7-11.7-14.7h-46.1c-5.7 0-10.6 4-11.7 9.5L450.7 128H340.8l-19.7-86c-1.3-5.5-6.1-9.3-11.7-9.3h-44c-5.6 0-10.4 3.8-11.7 9.3l-20 86H125l-17.5-85.7c-1.1-5.6-6.1-9.6-11.8-9.6H53.6c-7.7 0-13.4 7.1-11.7 14.6L60 128H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h62.3l7.2 32H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h83.9l40.9 182.6c1.2 5.5 6.1 9.4 11.7 9.4h56.8c5.6 0 10.4-3.9 11.7-9.3L259.3 288h55.1l42.4 182.7c1.3 5.4 6.1 9.3 11.7 9.3h56.8c5.6 0 10.4-3.9 11.7-9.3L479.1 288H564c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-70.1l7.4-32zM183.8 342c-6.2 25.8-6.8 47.2-7.3 47.2h-1.1s-1.7-22-6.8-47.2l-11-54h38.8zm27.5-118h-66.8l-6.5-32h80.8zm62.9 0l2-8.6c1.9-8 3.5-16 4.8-23.4h11.8c1.3 7.4 2.9 15.4 4.8 23.4l2 8.6zm130.9 118c-5.1 25.2-6.8 47.2-6.8 47.2h-1.1c-.6 0-1.1-21.4-7.3-47.2l-12.4-54h39.1zm25.2-118h-67.4l-7.3-32h81.6z\"],\n    \"wrench\": [512, 512, [], \"f0ad\", \"M507.73 109.1c-2.24-9.03-13.54-12.09-20.12-5.51l-74.36 74.36-67.88-11.31-11.31-67.88 74.36-74.36c6.62-6.62 3.43-17.9-5.66-20.16-47.38-11.74-99.55.91-136.58 37.93-39.64 39.64-50.55 97.1-34.05 147.2L18.74 402.76c-24.99 24.99-24.99 65.51 0 90.5 24.99 24.99 65.51 24.99 90.5 0l213.21-213.21c50.12 16.71 107.47 5.68 147.37-34.22 37.07-37.07 49.7-89.32 37.91-136.73zM64 472c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"x-ray\": [640, 512, [], \"f497\", \"M240 384c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm160 32c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zM624 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zm0 448h-48V96H64v352H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM480 248c0 4.4-3.6 8-8 8H336v32h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h64c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48v-16h-64v16c0 26.5-21.5 48-48 48s-48-21.5-48-48 21.5-48 48-48h64v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-32H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h136v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-24c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v24h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h136c4.4 0 8 3.6 8 8v16z\"],\n    \"yen-sign\": [384, 512, [], \"f157\", \"M351.2 32h-65.3c-4.6 0-8.8 2.6-10.8 6.7l-55.4 113.2c-14.5 34.7-27.1 71.9-27.1 71.9h-1.3s-12.6-37.2-27.1-71.9L108.8 38.7c-2-4.1-6.2-6.7-10.8-6.7H32.8c-9.1 0-14.8 9.7-10.6 17.6L102.3 200H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h88.2l19.8 37.2V320H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h108v92c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12v-92h108c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12H232v-26.8l19.8-37.2H340c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12h-58.3l80.1-150.4c4.3-7.9-1.5-17.6-10.6-17.6z\"],\n    \"yin-yang\": [496, 512, [], \"f6ad\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 376c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-128c-53.02 0-96 42.98-96 96s42.98 96 96 96c-106.04 0-192-85.96-192-192S141.96 64 248 64c53.02 0 96 42.98 96 96s-42.98 96-96 96zm0-128c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fas', icons);\n  });\n\n}());\n(function () {\n  'use strict';\n\n  function _typeof(obj) {\n    if (typeof Symbol === \"function\" && typeof Symbol.iterator === \"symbol\") {\n      _typeof = function (obj) {\n        return typeof obj;\n      };\n    } else {\n      _typeof = function (obj) {\n        return obj && typeof Symbol === \"function\" && obj.constructor === Symbol && obj !== Symbol.prototype ? \"symbol\" : typeof obj;\n      };\n    }\n\n    return _typeof(obj);\n  }\n\n  function _classCallCheck(instance, Constructor) {\n    if (!(instance instanceof Constructor)) {\n      throw new TypeError(\"Cannot call a class as a function\");\n    }\n  }\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _slicedToArray(arr, i) {\n    return _arrayWithHoles(arr) || _iterableToArrayLimit(arr, i) || _nonIterableRest();\n  }\n\n  function _toConsumableArray(arr) {\n    return _arrayWithoutHoles(arr) || _iterableToArray(arr) || _nonIterableSpread();\n  }\n\n  function _arrayWithoutHoles(arr) {\n    if (Array.isArray(arr)) {\n      for (var i = 0, arr2 = new Array(arr.length); i < arr.length; i++) arr2[i] = arr[i];\n\n      return arr2;\n    }\n  }\n\n  function _arrayWithHoles(arr) {\n    if (Array.isArray(arr)) return arr;\n  }\n\n  function _iterableToArray(iter) {\n    if (Symbol.iterator in Object(iter) || Object.prototype.toString.call(iter) === \"[object Arguments]\") return Array.from(iter);\n  }\n\n  function _iterableToArrayLimit(arr, i) {\n    var _arr = [];\n    var _n = true;\n    var _d = false;\n    var _e = undefined;\n\n    try {\n      for (var _i = arr[Symbol.iterator](), _s; !(_n = (_s = _i.next()).done); _n = true) {\n        _arr.push(_s.value);\n\n        if (i && _arr.length === i) break;\n      }\n    } catch (err) {\n      _d = true;\n      _e = err;\n    } finally {\n      try {\n        if (!_n && _i[\"return\"] != null) _i[\"return\"]();\n      } finally {\n        if (_d) throw _e;\n      }\n    }\n\n    return _arr;\n  }\n\n  function _nonIterableSpread() {\n    throw new TypeError(\"Invalid attempt to spread non-iterable instance\");\n  }\n\n  function _nonIterableRest() {\n    throw new TypeError(\"Invalid attempt to destructure non-iterable instance\");\n  }\n\n  var noop = function noop() {};\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n  var _MUTATION_OBSERVER = null;\n  var _PERFORMANCE = {\n    mark: noop,\n    measure: noop\n  };\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n    if (typeof MutationObserver !== 'undefined') _MUTATION_OBSERVER = MutationObserver;\n    if (typeof performance !== 'undefined') _PERFORMANCE = performance;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var MUTATION_OBSERVER = _MUTATION_OBSERVER;\n  var PERFORMANCE = _PERFORMANCE;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var UNITS_IN_GRID = 16;\n  var DEFAULT_FAMILY_PREFIX = 'fa';\n  var DEFAULT_REPLACEMENT_CLASS = 'svg-inline--fa';\n  var DATA_FA_I2SVG = 'data-fa-i2svg';\n  var DATA_FA_PSEUDO_ELEMENT = 'data-fa-pseudo-element';\n  var DATA_FA_PSEUDO_ELEMENT_PENDING = 'data-fa-pseudo-element-pending';\n  var DATA_PREFIX = 'data-prefix';\n  var DATA_ICON = 'data-icon';\n  var HTML_CLASS_I2SVG_BASE_CLASS = 'fontawesome-i2svg';\n  var MUTATION_APPROACH_ASYNC = 'async';\n  var TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS = ['HTML', 'HEAD', 'STYLE', 'SCRIPT'];\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n  var PREFIX_TO_STYLE = {\n    'fas': 'solid',\n    'far': 'regular',\n    'fal': 'light',\n    'fad': 'duotone',\n    'fab': 'brands',\n    'fa': 'solid'\n  };\n  var STYLE_TO_PREFIX = {\n    'solid': 'fas',\n    'regular': 'far',\n    'light': 'fal',\n    'duotone': 'fad',\n    'brands': 'fab'\n  };\n  var LAYERS_TEXT_CLASSNAME = 'fa-layers-text';\n  var FONT_FAMILY_PATTERN = /Font Awesome 5 (Solid|Regular|Light|Duotone|Brands|Free|Pro)/;\n  var FONT_WEIGHT_TO_PREFIX = {\n    '900': 'fas',\n    '400': 'far',\n    'normal': 'far',\n    '300': 'fal'\n  };\n  var oneToTen = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10];\n  var oneToTwenty = oneToTen.concat([11, 12, 13, 14, 15, 16, 17, 18, 19, 20]);\n  var ATTRIBUTES_WATCHED_FOR_MUTATION = ['class', 'data-prefix', 'data-icon', 'data-fa-transform', 'data-fa-mask'];\n  var DUOTONE_CLASSES = {\n    GROUP: 'group',\n    SWAP_OPACITY: 'swap-opacity',\n    PRIMARY: 'primary',\n    SECONDARY: 'secondary'\n  };\n  var RESERVED_CLASSES = ['xs', 'sm', 'lg', 'fw', 'ul', 'li', 'border', 'pull-left', 'pull-right', 'spin', 'pulse', 'rotate-90', 'rotate-180', 'rotate-270', 'flip-horizontal', 'flip-vertical', 'flip-both', 'stack', 'stack-1x', 'stack-2x', 'inverse', 'layers', 'layers-text', 'layers-counter', DUOTONE_CLASSES.GROUP, DUOTONE_CLASSES.SWAP_OPACITY, DUOTONE_CLASSES.PRIMARY, DUOTONE_CLASSES.SECONDARY].concat(oneToTen.map(function (n) {\n    return \"\".concat(n, \"x\");\n  })).concat(oneToTwenty.map(function (n) {\n    return \"w-\".concat(n);\n  }));\n\n  var initial = WINDOW.FontAwesomeConfig || {};\n\n  function getAttrConfig(attr) {\n    var element = DOCUMENT.querySelector('script[' + attr + ']');\n\n    if (element) {\n      return element.getAttribute(attr);\n    }\n  }\n\n  function coerce(val) {\n    // Getting an empty string will occur if the attribute is set on the HTML tag but without a value\n    // We'll assume that this is an indication that it should be toggled to true\n    // For example <script data-search-pseudo-elements src=\"...\"></script>\n    if (val === '') return true;\n    if (val === 'false') return false;\n    if (val === 'true') return true;\n    return val;\n  }\n\n  if (DOCUMENT && typeof DOCUMENT.querySelector === 'function') {\n    var attrs = [['data-family-prefix', 'familyPrefix'], ['data-replacement-class', 'replacementClass'], ['data-auto-replace-svg', 'autoReplaceSvg'], ['data-auto-add-css', 'autoAddCss'], ['data-auto-a11y', 'autoA11y'], ['data-search-pseudo-elements', 'searchPseudoElements'], ['data-observe-mutations', 'observeMutations'], ['data-mutate-approach', 'mutateApproach'], ['data-keep-original-source', 'keepOriginalSource'], ['data-measure-performance', 'measurePerformance'], ['data-show-missing-icons', 'showMissingIcons']];\n    attrs.forEach(function (_ref) {\n      var _ref2 = _slicedToArray(_ref, 2),\n          attr = _ref2[0],\n          key = _ref2[1];\n\n      var val = coerce(getAttrConfig(attr));\n\n      if (val !== undefined && val !== null) {\n        initial[key] = val;\n      }\n    });\n  }\n\n  var _default = {\n    familyPrefix: DEFAULT_FAMILY_PREFIX,\n    replacementClass: DEFAULT_REPLACEMENT_CLASS,\n    autoReplaceSvg: true,\n    autoAddCss: true,\n    autoA11y: true,\n    searchPseudoElements: false,\n    observeMutations: true,\n    mutateApproach: 'async',\n    keepOriginalSource: true,\n    measurePerformance: false,\n    showMissingIcons: true\n  };\n\n  var _config = _objectSpread({}, _default, initial);\n\n  if (!_config.autoReplaceSvg) _config.observeMutations = false;\n\n  var config = _objectSpread({}, _config);\n\n  WINDOW.FontAwesomeConfig = config;\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  var functions = [];\n\n  var listener = function listener() {\n    DOCUMENT.removeEventListener('DOMContentLoaded', listener);\n    loaded = 1;\n    functions.map(function (fn) {\n      return fn();\n    });\n  };\n\n  var loaded = false;\n\n  if (IS_DOM) {\n    loaded = (DOCUMENT.documentElement.doScroll ? /^loaded|^c/ : /^loaded|^i|^c/).test(DOCUMENT.readyState);\n    if (!loaded) DOCUMENT.addEventListener('DOMContentLoaded', listener);\n  }\n\n  function domready (fn) {\n    if (!IS_DOM) return;\n    loaded ? setTimeout(fn, 0) : functions.push(fn);\n  }\n\n  var PENDING = 'pending';\n  var SETTLED = 'settled';\n  var FULFILLED = 'fulfilled';\n  var REJECTED = 'rejected';\n\n  var NOOP = function NOOP() {};\n\n  var isNode = typeof global !== 'undefined' && typeof global.process !== 'undefined' && typeof global.process.emit === 'function';\n  var asyncSetTimer = typeof setImmediate === 'undefined' ? setTimeout : setImmediate;\n  var asyncQueue = [];\n  var asyncTimer;\n\n  function asyncFlush() {\n    // run promise callbacks\n    for (var i = 0; i < asyncQueue.length; i++) {\n      asyncQueue[i][0](asyncQueue[i][1]);\n    } // reset async asyncQueue\n\n\n    asyncQueue = [];\n    asyncTimer = false;\n  }\n\n  function asyncCall(callback, arg) {\n    asyncQueue.push([callback, arg]);\n\n    if (!asyncTimer) {\n      asyncTimer = true;\n      asyncSetTimer(asyncFlush, 0);\n    }\n  }\n\n  function invokeResolver(resolver, promise) {\n    function resolvePromise(value) {\n      resolve(promise, value);\n    }\n\n    function rejectPromise(reason) {\n      reject(promise, reason);\n    }\n\n    try {\n      resolver(resolvePromise, rejectPromise);\n    } catch (e) {\n      rejectPromise(e);\n    }\n  }\n\n  function invokeCallback(subscriber) {\n    var owner = subscriber.owner;\n    var settled = owner._state;\n    var value = owner._data;\n    var callback = subscriber[settled];\n    var promise = subscriber.then;\n\n    if (typeof callback === 'function') {\n      settled = FULFILLED;\n\n      try {\n        value = callback(value);\n      } catch (e) {\n        reject(promise, e);\n      }\n    }\n\n    if (!handleThenable(promise, value)) {\n      if (settled === FULFILLED) {\n        resolve(promise, value);\n      }\n\n      if (settled === REJECTED) {\n        reject(promise, value);\n      }\n    }\n  }\n\n  function handleThenable(promise, value) {\n    var resolved;\n\n    try {\n      if (promise === value) {\n        throw new TypeError('A promises callback cannot return that same promise.');\n      }\n\n      if (value && (typeof value === 'function' || _typeof(value) === 'object')) {\n        // then should be retrieved only once\n        var then = value.then;\n\n        if (typeof then === 'function') {\n          then.call(value, function (val) {\n            if (!resolved) {\n              resolved = true;\n\n              if (value === val) {\n                fulfill(promise, val);\n              } else {\n                resolve(promise, val);\n              }\n            }\n          }, function (reason) {\n            if (!resolved) {\n              resolved = true;\n              reject(promise, reason);\n            }\n          });\n          return true;\n        }\n      }\n    } catch (e) {\n      if (!resolved) {\n        reject(promise, e);\n      }\n\n      return true;\n    }\n\n    return false;\n  }\n\n  function resolve(promise, value) {\n    if (promise === value || !handleThenable(promise, value)) {\n      fulfill(promise, value);\n    }\n  }\n\n  function fulfill(promise, value) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = value;\n      asyncCall(publishFulfillment, promise);\n    }\n  }\n\n  function reject(promise, reason) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = reason;\n      asyncCall(publishRejection, promise);\n    }\n  }\n\n  function publish(promise) {\n    promise._then = promise._then.forEach(invokeCallback);\n  }\n\n  function publishFulfillment(promise) {\n    promise._state = FULFILLED;\n    publish(promise);\n  }\n\n  function publishRejection(promise) {\n    promise._state = REJECTED;\n    publish(promise);\n\n    if (!promise._handled && isNode) {\n      global.process.emit('unhandledRejection', promise._data, promise);\n    }\n  }\n\n  function notifyRejectionHandled(promise) {\n    global.process.emit('rejectionHandled', promise);\n  }\n  /**\n   * @class\n   */\n\n\n  function P(resolver) {\n    if (typeof resolver !== 'function') {\n      throw new TypeError('Promise resolver ' + resolver + ' is not a function');\n    }\n\n    if (this instanceof P === false) {\n      throw new TypeError('Failed to construct \\'Promise\\': Please use the \\'new\\' operator, this object constructor cannot be called as a function.');\n    }\n\n    this._then = [];\n    invokeResolver(resolver, this);\n  }\n\n  P.prototype = {\n    constructor: P,\n    _state: PENDING,\n    _then: null,\n    _data: undefined,\n    _handled: false,\n    then: function then(onFulfillment, onRejection) {\n      var subscriber = {\n        owner: this,\n        then: new this.constructor(NOOP),\n        fulfilled: onFulfillment,\n        rejected: onRejection\n      };\n\n      if ((onRejection || onFulfillment) && !this._handled) {\n        this._handled = true;\n\n        if (this._state === REJECTED && isNode) {\n          asyncCall(notifyRejectionHandled, this);\n        }\n      }\n\n      if (this._state === FULFILLED || this._state === REJECTED) {\n        // already resolved, call callback async\n        asyncCall(invokeCallback, subscriber);\n      } else {\n        // subscribe\n        this._then.push(subscriber);\n      }\n\n      return subscriber.then;\n    },\n    catch: function _catch(onRejection) {\n      return this.then(null, onRejection);\n    }\n  };\n\n  P.all = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.all().');\n    }\n\n    return new P(function (resolve, reject) {\n      var results = [];\n      var remaining = 0;\n\n      function resolver(index) {\n        remaining++;\n        return function (value) {\n          results[index] = value;\n\n          if (! --remaining) {\n            resolve(results);\n          }\n        };\n      }\n\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolver(i), reject);\n        } else {\n          results[i] = promise;\n        }\n      }\n\n      if (!remaining) {\n        resolve(results);\n      }\n    });\n  };\n\n  P.race = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.race().');\n    }\n\n    return new P(function (resolve, reject) {\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolve, reject);\n        } else {\n          resolve(promise);\n        }\n      }\n    });\n  };\n\n  P.resolve = function (value) {\n    if (value && _typeof(value) === 'object' && value.constructor === P) {\n      return value;\n    }\n\n    return new P(function (resolve) {\n      resolve(value);\n    });\n  };\n\n  P.reject = function (reason) {\n    return new P(function (resolve, reject) {\n      reject(reason);\n    });\n  };\n\n  var picked = typeof Promise === 'function' ? Promise : P;\n\n  var d = UNITS_IN_GRID;\n  var meaninglessTransform = {\n    size: 16,\n    x: 0,\n    y: 0,\n    rotate: 0,\n    flipX: false,\n    flipY: false\n  };\n\n  function isReserved(name) {\n    return ~RESERVED_CLASSES.indexOf(name);\n  }\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n  function insertCss(css) {\n    if (!css || !IS_DOM) {\n      return;\n    }\n\n    var style = DOCUMENT.createElement('style');\n    style.setAttribute('type', 'text/css');\n    style.innerHTML = css;\n    var headChildren = DOCUMENT.head.childNodes;\n    var beforeChild = null;\n\n    for (var i = headChildren.length - 1; i > -1; i--) {\n      var child = headChildren[i];\n      var tagName = (child.tagName || '').toUpperCase();\n\n      if (['STYLE', 'LINK'].indexOf(tagName) > -1) {\n        beforeChild = child;\n      }\n    }\n\n    DOCUMENT.head.insertBefore(style, beforeChild);\n    return css;\n  }\n  var idPool = '0123456789abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ';\n  function nextUniqueId() {\n    var size = 12;\n    var id = '';\n\n    while (size-- > 0) {\n      id += idPool[Math.random() * 62 | 0];\n    }\n\n    return id;\n  }\n  function toArray(obj) {\n    var array = [];\n\n    for (var i = (obj || []).length >>> 0; i--;) {\n      array[i] = obj[i];\n    }\n\n    return array;\n  }\n  function classArray(node) {\n    if (node.classList) {\n      return toArray(node.classList);\n    } else {\n      return (node.getAttribute('class') || '').split(' ').filter(function (i) {\n        return i;\n      });\n    }\n  }\n  function getIconName(familyPrefix, cls) {\n    var parts = cls.split('-');\n    var prefix = parts[0];\n    var iconName = parts.slice(1).join('-');\n\n    if (prefix === familyPrefix && iconName !== '' && !isReserved(iconName)) {\n      return iconName;\n    } else {\n      return null;\n    }\n  }\n  function htmlEscape(str) {\n    return \"\".concat(str).replace(/&/g, '&amp;').replace(/\"/g, '&quot;').replace(/'/g, '&#39;').replace(/</g, '&lt;').replace(/>/g, '&gt;');\n  }\n  function joinAttributes(attributes) {\n    return Object.keys(attributes || {}).reduce(function (acc, attributeName) {\n      return acc + \"\".concat(attributeName, \"=\\\"\").concat(htmlEscape(attributes[attributeName]), \"\\\" \");\n    }, '').trim();\n  }\n  function joinStyles(styles) {\n    return Object.keys(styles || {}).reduce(function (acc, styleName) {\n      return acc + \"\".concat(styleName, \": \").concat(styles[styleName], \";\");\n    }, '');\n  }\n  function transformIsMeaningful(transform) {\n    return transform.size !== meaninglessTransform.size || transform.x !== meaninglessTransform.x || transform.y !== meaninglessTransform.y || transform.rotate !== meaninglessTransform.rotate || transform.flipX || transform.flipY;\n  }\n  function transformForSvg(_ref) {\n    var transform = _ref.transform,\n        containerWidth = _ref.containerWidth,\n        iconWidth = _ref.iconWidth;\n    var outer = {\n      transform: \"translate(\".concat(containerWidth / 2, \" 256)\")\n    };\n    var innerTranslate = \"translate(\".concat(transform.x * 32, \", \").concat(transform.y * 32, \") \");\n    var innerScale = \"scale(\".concat(transform.size / 16 * (transform.flipX ? -1 : 1), \", \").concat(transform.size / 16 * (transform.flipY ? -1 : 1), \") \");\n    var innerRotate = \"rotate(\".concat(transform.rotate, \" 0 0)\");\n    var inner = {\n      transform: \"\".concat(innerTranslate, \" \").concat(innerScale, \" \").concat(innerRotate)\n    };\n    var path = {\n      transform: \"translate(\".concat(iconWidth / 2 * -1, \" -256)\")\n    };\n    return {\n      outer: outer,\n      inner: inner,\n      path: path\n    };\n  }\n  function transformForCss(_ref2) {\n    var transform = _ref2.transform,\n        _ref2$width = _ref2.width,\n        width = _ref2$width === void 0 ? UNITS_IN_GRID : _ref2$width,\n        _ref2$height = _ref2.height,\n        height = _ref2$height === void 0 ? UNITS_IN_GRID : _ref2$height,\n        _ref2$startCentered = _ref2.startCentered,\n        startCentered = _ref2$startCentered === void 0 ? false : _ref2$startCentered;\n    var val = '';\n\n    if (startCentered && IS_IE) {\n      val += \"translate(\".concat(transform.x / d - width / 2, \"em, \").concat(transform.y / d - height / 2, \"em) \");\n    } else if (startCentered) {\n      val += \"translate(calc(-50% + \".concat(transform.x / d, \"em), calc(-50% + \").concat(transform.y / d, \"em)) \");\n    } else {\n      val += \"translate(\".concat(transform.x / d, \"em, \").concat(transform.y / d, \"em) \");\n    }\n\n    val += \"scale(\".concat(transform.size / d * (transform.flipX ? -1 : 1), \", \").concat(transform.size / d * (transform.flipY ? -1 : 1), \") \");\n    val += \"rotate(\".concat(transform.rotate, \"deg) \");\n    return val;\n  }\n\n  var ALL_SPACE = {\n    x: 0,\n    y: 0,\n    width: '100%',\n    height: '100%'\n  };\n\n  function fillBlack(abstract) {\n    var force = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : true;\n\n    if (abstract.attributes && (abstract.attributes.fill || force)) {\n      abstract.attributes.fill = 'black';\n    }\n\n    return abstract;\n  }\n\n  function deGroup(abstract) {\n    if (abstract.tag === 'g') {\n      return abstract.children;\n    } else {\n      return [abstract];\n    }\n  }\n\n  function makeIconMasking (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        mask = _ref.mask,\n        transform = _ref.transform;\n    var mainWidth = main.width,\n        mainPath = main.icon;\n    var maskWidth = mask.width,\n        maskPath = mask.icon;\n    var trans = transformForSvg({\n      transform: transform,\n      containerWidth: maskWidth,\n      iconWidth: mainWidth\n    });\n    var maskRect = {\n      tag: 'rect',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        fill: 'white'\n      })\n    };\n    var maskInnerGroupChildrenMixin = mainPath.children ? {\n      children: mainPath.children.map(fillBlack)\n    } : {};\n    var maskInnerGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.inner),\n      children: [fillBlack(_objectSpread({\n        tag: mainPath.tag,\n        attributes: _objectSpread({}, mainPath.attributes, trans.path)\n      }, maskInnerGroupChildrenMixin))]\n    };\n    var maskOuterGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.outer),\n      children: [maskInnerGroup]\n    };\n    var maskId = \"mask-\".concat(nextUniqueId());\n    var clipId = \"clip-\".concat(nextUniqueId());\n    var maskTag = {\n      tag: 'mask',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        id: maskId,\n        maskUnits: 'userSpaceOnUse',\n        maskContentUnits: 'userSpaceOnUse'\n      }),\n      children: [maskRect, maskOuterGroup]\n    };\n    var defs = {\n      tag: 'defs',\n      children: [{\n        tag: 'clipPath',\n        attributes: {\n          id: clipId\n        },\n        children: deGroup(maskPath)\n      }, maskTag]\n    };\n    children.push(defs, {\n      tag: 'rect',\n      attributes: _objectSpread({\n        fill: 'currentColor',\n        'clip-path': \"url(#\".concat(clipId, \")\"),\n        mask: \"url(#\".concat(maskId, \")\")\n      }, ALL_SPACE)\n    });\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function makeIconStandard (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        transform = _ref.transform,\n        styles = _ref.styles;\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    if (transformIsMeaningful(transform)) {\n      var trans = transformForSvg({\n        transform: transform,\n        containerWidth: main.width,\n        iconWidth: main.width\n      });\n      children.push({\n        tag: 'g',\n        attributes: _objectSpread({}, trans.outer),\n        children: [{\n          tag: 'g',\n          attributes: _objectSpread({}, trans.inner),\n          children: [{\n            tag: main.icon.tag,\n            children: main.icon.children,\n            attributes: _objectSpread({}, main.icon.attributes, trans.path)\n          }]\n        }]\n      });\n    } else {\n      children.push(main.icon);\n    }\n\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function asIcon (_ref) {\n    var children = _ref.children,\n        main = _ref.main,\n        mask = _ref.mask,\n        attributes = _ref.attributes,\n        styles = _ref.styles,\n        transform = _ref.transform;\n\n    if (transformIsMeaningful(transform) && main.found && !mask.found) {\n      var width = main.width,\n          height = main.height;\n      var offset = {\n        x: width / height / 2,\n        y: 0.5\n      };\n      attributes['style'] = joinStyles(_objectSpread({}, styles, {\n        'transform-origin': \"\".concat(offset.x + transform.x / 16, \"em \").concat(offset.y + transform.y / 16, \"em\")\n      }));\n    }\n\n    return [{\n      tag: 'svg',\n      attributes: attributes,\n      children: children\n    }];\n  }\n\n  function asSymbol (_ref) {\n    var prefix = _ref.prefix,\n        iconName = _ref.iconName,\n        children = _ref.children,\n        attributes = _ref.attributes,\n        symbol = _ref.symbol;\n    var id = symbol === true ? \"\".concat(prefix, \"-\").concat(config.familyPrefix, \"-\").concat(iconName) : symbol;\n    return [{\n      tag: 'svg',\n      attributes: {\n        style: 'display: none;'\n      },\n      children: [{\n        tag: 'symbol',\n        attributes: _objectSpread({}, attributes, {\n          id: id\n        }),\n        children: children\n      }]\n    }];\n  }\n\n  function makeInlineSvgAbstract(params) {\n    var _params$icons = params.icons,\n        main = _params$icons.main,\n        mask = _params$icons.mask,\n        prefix = params.prefix,\n        iconName = params.iconName,\n        transform = params.transform,\n        symbol = params.symbol,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable = params.watchable,\n        watchable = _params$watchable === void 0 ? false : _params$watchable;\n\n    var _ref = mask.found ? mask : main,\n        width = _ref.width,\n        height = _ref.height;\n\n    var widthClass = \"fa-w-\".concat(Math.ceil(width / height * 16));\n    var attrClass = [config.replacementClass, iconName ? \"\".concat(config.familyPrefix, \"-\").concat(iconName) : '', widthClass].filter(function (c) {\n      return extra.classes.indexOf(c) === -1;\n    }).concat(extra.classes).join(' ');\n    var content = {\n      children: [],\n      attributes: _objectSpread({}, extra.attributes, {\n        'data-prefix': prefix,\n        'data-icon': iconName,\n        'class': attrClass,\n        'role': extra.attributes.role || 'img',\n        'xmlns': 'http://www.w3.org/2000/svg',\n        'viewBox': \"0 0 \".concat(width, \" \").concat(height)\n      })\n    };\n\n    if (watchable) {\n      content.attributes[DATA_FA_I2SVG] = '';\n    }\n\n    if (title) content.children.push({\n      tag: 'title',\n      attributes: {\n        id: content.attributes['aria-labelledby'] || \"title-\".concat(nextUniqueId())\n      },\n      children: [title]\n    });\n\n    var args = _objectSpread({}, content, {\n      prefix: prefix,\n      iconName: iconName,\n      main: main,\n      mask: mask,\n      transform: transform,\n      symbol: symbol,\n      styles: extra.styles\n    });\n\n    var _ref2 = mask.found && main.found ? makeIconMasking(args) : makeIconStandard(args),\n        children = _ref2.children,\n        attributes = _ref2.attributes;\n\n    args.children = children;\n    args.attributes = attributes;\n\n    if (symbol) {\n      return asSymbol(args);\n    } else {\n      return asIcon(args);\n    }\n  }\n  function makeLayersTextAbstract(params) {\n    var content = params.content,\n        width = params.width,\n        height = params.height,\n        transform = params.transform,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable2 = params.watchable,\n        watchable = _params$watchable2 === void 0 ? false : _params$watchable2;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    if (watchable) {\n      attributes[DATA_FA_I2SVG] = '';\n    }\n\n    var styles = _objectSpread({}, extra.styles);\n\n    if (transformIsMeaningful(transform)) {\n      styles['transform'] = transformForCss({\n        transform: transform,\n        startCentered: true,\n        width: width,\n        height: height\n      });\n      styles['-webkit-transform'] = styles['transform'];\n    }\n\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n  function makeLayersCounterAbstract(params) {\n    var content = params.content,\n        title = params.title,\n        extra = params.extra;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    var styleString = joinStyles(extra.styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n\n  var noop$1 = function noop() {};\n\n  var p = config.measurePerformance && PERFORMANCE && PERFORMANCE.mark && PERFORMANCE.measure ? PERFORMANCE : {\n    mark: noop$1,\n    measure: noop$1\n  };\n  var preamble = \"FA \\\"5.10.2\\\"\";\n\n  var begin = function begin(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" begins\"));\n    return function () {\n      return end(name);\n    };\n  };\n\n  var end = function end(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" ends\"));\n    p.measure(\"\".concat(preamble, \" \").concat(name), \"\".concat(preamble, \" \").concat(name, \" begins\"), \"\".concat(preamble, \" \").concat(name, \" ends\"));\n  };\n\n  var perf = {\n    begin: begin,\n    end: end\n  };\n\n  /**\n   * Internal helper to bind a function known to have 4 arguments\n   * to a given context.\n   */\n\n  var bindInternal4 = function bindInternal4(func, thisContext) {\n    return function (a, b, c, d) {\n      return func.call(thisContext, a, b, c, d);\n    };\n  };\n\n  /**\n   * # Reduce\n   *\n   * A fast object `.reduce()` implementation.\n   *\n   * @param  {Object}   subject      The object to reduce over.\n   * @param  {Function} fn           The reducer function.\n   * @param  {mixed}    initialValue The initial value for the reducer, defaults to subject[0].\n   * @param  {Object}   thisContext  The context for the reducer.\n   * @return {mixed}                 The final result.\n   */\n\n\n  var reduce = function fastReduceObject(subject, fn, initialValue, thisContext) {\n    var keys = Object.keys(subject),\n        length = keys.length,\n        iterator = thisContext !== undefined ? bindInternal4(fn, thisContext) : fn,\n        i,\n        key,\n        result;\n\n    if (initialValue === undefined) {\n      i = 1;\n      result = subject[keys[0]];\n    } else {\n      i = 0;\n      result = initialValue;\n    }\n\n    for (; i < length; i++) {\n      key = keys[i];\n      result = iterator(result, subject[key], key, subject);\n    }\n\n    return result;\n  };\n\n  function toHex(unicode) {\n    var result = '';\n\n    for (var i = 0; i < unicode.length; i++) {\n      var hex = unicode.charCodeAt(i).toString(16);\n      result += ('000' + hex).slice(-4);\n    }\n\n    return result;\n  }\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var styles = namespace.styles,\n      shims = namespace.shims;\n  var _byUnicode = {};\n  var _byLigature = {};\n  var _byOldName = {};\n  var build = function build() {\n    var lookup = function lookup(reducer) {\n      return reduce(styles, function (o, style, prefix) {\n        o[prefix] = reduce(style, reducer, {});\n        return o;\n      }, {});\n    };\n\n    _byUnicode = lookup(function (acc, icon, iconName) {\n      if (icon[3]) {\n        acc[icon[3]] = iconName;\n      }\n\n      return acc;\n    });\n    _byLigature = lookup(function (acc, icon, iconName) {\n      var ligatures = icon[2];\n      acc[iconName] = iconName;\n      ligatures.forEach(function (ligature) {\n        acc[ligature] = iconName;\n      });\n      return acc;\n    });\n    var hasRegular = 'far' in styles;\n    _byOldName = reduce(shims, function (acc, shim) {\n      var oldName = shim[0];\n      var prefix = shim[1];\n      var iconName = shim[2];\n\n      if (prefix === 'far' && !hasRegular) {\n        prefix = 'fas';\n      }\n\n      acc[oldName] = {\n        prefix: prefix,\n        iconName: iconName\n      };\n      return acc;\n    }, {});\n  };\n  build();\n  function byUnicode(prefix, unicode) {\n    return (_byUnicode[prefix] || {})[unicode];\n  }\n  function byLigature(prefix, ligature) {\n    return (_byLigature[prefix] || {})[ligature];\n  }\n  function byOldName(name) {\n    return _byOldName[name] || {\n      prefix: null,\n      iconName: null\n    };\n  }\n\n  var styles$1 = namespace.styles;\n  var emptyCanonicalIcon = function emptyCanonicalIcon() {\n    return {\n      prefix: null,\n      iconName: null,\n      rest: []\n    };\n  };\n  function getCanonicalIcon(values) {\n    return values.reduce(function (acc, cls) {\n      var iconName = getIconName(config.familyPrefix, cls);\n\n      if (styles$1[cls]) {\n        acc.prefix = cls;\n      } else if (config.autoFetchSvg && ['fas', 'far', 'fal', 'fad', 'fab', 'fa'].indexOf(cls) > -1) {\n        acc.prefix = cls;\n      } else if (iconName) {\n        var shim = acc.prefix === 'fa' ? byOldName(iconName) : {};\n        acc.iconName = shim.iconName || iconName;\n        acc.prefix = shim.prefix || acc.prefix;\n      } else if (cls !== config.replacementClass && cls.indexOf('fa-w-') !== 0) {\n        acc.rest.push(cls);\n      }\n\n      return acc;\n    }, emptyCanonicalIcon());\n  }\n  function iconFromMapping(mapping, prefix, iconName) {\n    if (mapping && mapping[prefix] && mapping[prefix][iconName]) {\n      return {\n        prefix: prefix,\n        iconName: iconName,\n        icon: mapping[prefix][iconName]\n      };\n    }\n  }\n\n  function toHtml(abstractNodes) {\n    var tag = abstractNodes.tag,\n        _abstractNodes$attrib = abstractNodes.attributes,\n        attributes = _abstractNodes$attrib === void 0 ? {} : _abstractNodes$attrib,\n        _abstractNodes$childr = abstractNodes.children,\n        children = _abstractNodes$childr === void 0 ? [] : _abstractNodes$childr;\n\n    if (typeof abstractNodes === 'string') {\n      return htmlEscape(abstractNodes);\n    } else {\n      return \"<\".concat(tag, \" \").concat(joinAttributes(attributes), \">\").concat(children.map(toHtml).join(''), \"</\").concat(tag, \">\");\n    }\n  }\n\n  var noop$2 = function noop() {};\n\n  function isWatched(node) {\n    var i2svg = node.getAttribute ? node.getAttribute(DATA_FA_I2SVG) : null;\n    return typeof i2svg === 'string';\n  }\n\n  function getMutator() {\n    if (config.autoReplaceSvg === true) {\n      return mutators.replace;\n    }\n\n    var mutator = mutators[config.autoReplaceSvg];\n    return mutator || mutators.replace;\n  }\n\n  var mutators = {\n    replace: function replace(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1];\n      var newOuterHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n\n      if (node.parentNode && node.outerHTML) {\n        node.outerHTML = newOuterHTML + (config.keepOriginalSource && node.tagName.toLowerCase() !== 'svg' ? \"<!-- \".concat(node.outerHTML, \" -->\") : '');\n      } else if (node.parentNode) {\n        var newNode = document.createElement('span');\n        node.parentNode.replaceChild(newNode, node);\n        newNode.outerHTML = newOuterHTML;\n      }\n    },\n    nest: function nest(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1]; // If we already have a replaced node we do not want to continue nesting within it.\n      // Short-circuit to the standard replacement\n\n      if (~classArray(node).indexOf(config.replacementClass)) {\n        return mutators.replace(mutation);\n      }\n\n      var forSvg = new RegExp(\"\".concat(config.familyPrefix, \"-.*\"));\n      delete abstract[0].attributes.style;\n      var splitClasses = abstract[0].attributes.class.split(' ').reduce(function (acc, cls) {\n        if (cls === config.replacementClass || cls.match(forSvg)) {\n          acc.toSvg.push(cls);\n        } else {\n          acc.toNode.push(cls);\n        }\n\n        return acc;\n      }, {\n        toNode: [],\n        toSvg: []\n      });\n      abstract[0].attributes.class = splitClasses.toSvg.join(' ');\n      var newInnerHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n      node.setAttribute('class', splitClasses.toNode.join(' '));\n      node.setAttribute(DATA_FA_I2SVG, '');\n      node.innerHTML = newInnerHTML;\n    }\n  };\n\n  function performOperationSync(op) {\n    op();\n  }\n\n  function perform(mutations, callback) {\n    var callbackFunction = typeof callback === 'function' ? callback : noop$2;\n\n    if (mutations.length === 0) {\n      callbackFunction();\n    } else {\n      var frame = performOperationSync;\n\n      if (config.mutateApproach === MUTATION_APPROACH_ASYNC) {\n        frame = WINDOW.requestAnimationFrame || performOperationSync;\n      }\n\n      frame(function () {\n        var mutator = getMutator();\n        var mark = perf.begin('mutate');\n        mutations.map(mutator);\n        mark();\n        callbackFunction();\n      });\n    }\n  }\n  var disabled = false;\n  function disableObservation() {\n    disabled = true;\n  }\n  function enableObservation() {\n    disabled = false;\n  }\n  var mo = null;\n  function observe(options) {\n    if (!MUTATION_OBSERVER) {\n      return;\n    }\n\n    if (!config.observeMutations) {\n      return;\n    }\n\n    var treeCallback = options.treeCallback,\n        nodeCallback = options.nodeCallback,\n        pseudoElementsCallback = options.pseudoElementsCallback,\n        _options$observeMutat = options.observeMutationsRoot,\n        observeMutationsRoot = _options$observeMutat === void 0 ? DOCUMENT : _options$observeMutat;\n    mo = new MUTATION_OBSERVER(function (objects) {\n      if (disabled) return;\n      toArray(objects).forEach(function (mutationRecord) {\n        if (mutationRecord.type === 'childList' && mutationRecord.addedNodes.length > 0 && !isWatched(mutationRecord.addedNodes[0])) {\n          if (config.searchPseudoElements) {\n            pseudoElementsCallback(mutationRecord.target);\n          }\n\n          treeCallback(mutationRecord.target);\n        }\n\n        if (mutationRecord.type === 'attributes' && mutationRecord.target.parentNode && config.searchPseudoElements) {\n          pseudoElementsCallback(mutationRecord.target.parentNode);\n        }\n\n        if (mutationRecord.type === 'attributes' && isWatched(mutationRecord.target) && ~ATTRIBUTES_WATCHED_FOR_MUTATION.indexOf(mutationRecord.attributeName)) {\n          if (mutationRecord.attributeName === 'class') {\n            var _getCanonicalIcon = getCanonicalIcon(classArray(mutationRecord.target)),\n                prefix = _getCanonicalIcon.prefix,\n                iconName = _getCanonicalIcon.iconName;\n\n            if (prefix) mutationRecord.target.setAttribute('data-prefix', prefix);\n            if (iconName) mutationRecord.target.setAttribute('data-icon', iconName);\n          } else {\n            nodeCallback(mutationRecord.target);\n          }\n        }\n      });\n    });\n    if (!IS_DOM) return;\n    mo.observe(observeMutationsRoot, {\n      childList: true,\n      attributes: true,\n      characterData: true,\n      subtree: true\n    });\n  }\n  function disconnect() {\n    if (!mo) return;\n    mo.disconnect();\n  }\n\n  function styleParser (node) {\n    var style = node.getAttribute('style');\n    var val = [];\n\n    if (style) {\n      val = style.split(';').reduce(function (acc, style) {\n        var styles = style.split(':');\n        var prop = styles[0];\n        var value = styles.slice(1);\n\n        if (prop && value.length > 0) {\n          acc[prop] = value.join(':').trim();\n        }\n\n        return acc;\n      }, {});\n    }\n\n    return val;\n  }\n\n  function classParser (node) {\n    var existingPrefix = node.getAttribute('data-prefix');\n    var existingIconName = node.getAttribute('data-icon');\n    var innerText = node.innerText !== undefined ? node.innerText.trim() : '';\n    var val = getCanonicalIcon(classArray(node));\n\n    if (existingPrefix && existingIconName) {\n      val.prefix = existingPrefix;\n      val.iconName = existingIconName;\n    }\n\n    if (val.prefix && innerText.length > 1) {\n      val.iconName = byLigature(val.prefix, node.innerText);\n    } else if (val.prefix && innerText.length === 1) {\n      val.iconName = byUnicode(val.prefix, toHex(node.innerText));\n    }\n\n    return val;\n  }\n\n  var parseTransformString = function parseTransformString(transformString) {\n    var transform = {\n      size: 16,\n      x: 0,\n      y: 0,\n      flipX: false,\n      flipY: false,\n      rotate: 0\n    };\n\n    if (!transformString) {\n      return transform;\n    } else {\n      return transformString.toLowerCase().split(' ').reduce(function (acc, n) {\n        var parts = n.toLowerCase().split('-');\n        var first = parts[0];\n        var rest = parts.slice(1).join('-');\n\n        if (first && rest === 'h') {\n          acc.flipX = true;\n          return acc;\n        }\n\n        if (first && rest === 'v') {\n          acc.flipY = true;\n          return acc;\n        }\n\n        rest = parseFloat(rest);\n\n        if (isNaN(rest)) {\n          return acc;\n        }\n\n        switch (first) {\n          case 'grow':\n            acc.size = acc.size + rest;\n            break;\n\n          case 'shrink':\n            acc.size = acc.size - rest;\n            break;\n\n          case 'left':\n            acc.x = acc.x - rest;\n            break;\n\n          case 'right':\n            acc.x = acc.x + rest;\n            break;\n\n          case 'up':\n            acc.y = acc.y - rest;\n            break;\n\n          case 'down':\n            acc.y = acc.y + rest;\n            break;\n\n          case 'rotate':\n            acc.rotate = acc.rotate + rest;\n            break;\n        }\n\n        return acc;\n      }, transform);\n    }\n  };\n  function transformParser (node) {\n    return parseTransformString(node.getAttribute('data-fa-transform'));\n  }\n\n  function symbolParser (node) {\n    var symbol = node.getAttribute('data-fa-symbol');\n    return symbol === null ? false : symbol === '' ? true : symbol;\n  }\n\n  function attributesParser (node) {\n    var extraAttributes = toArray(node.attributes).reduce(function (acc, attr) {\n      if (acc.name !== 'class' && acc.name !== 'style') {\n        acc[attr.name] = attr.value;\n      }\n\n      return acc;\n    }, {});\n    var title = node.getAttribute('title');\n\n    if (config.autoA11y) {\n      if (title) {\n        extraAttributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n      } else {\n        extraAttributes['aria-hidden'] = 'true';\n        extraAttributes['focusable'] = 'false';\n      }\n    }\n\n    return extraAttributes;\n  }\n\n  function maskParser (node) {\n    var mask = node.getAttribute('data-fa-mask');\n\n    if (!mask) {\n      return emptyCanonicalIcon();\n    } else {\n      return getCanonicalIcon(mask.split(' ').map(function (i) {\n        return i.trim();\n      }));\n    }\n  }\n\n  function blankMeta() {\n    return {\n      iconName: null,\n      title: null,\n      prefix: null,\n      transform: meaninglessTransform,\n      symbol: false,\n      mask: null,\n      extra: {\n        classes: [],\n        styles: {},\n        attributes: {}\n      }\n    };\n  }\n  function parseMeta(node) {\n    var _classParser = classParser(node),\n        iconName = _classParser.iconName,\n        prefix = _classParser.prefix,\n        extraClasses = _classParser.rest;\n\n    var extraStyles = styleParser(node);\n    var transform = transformParser(node);\n    var symbol = symbolParser(node);\n    var extraAttributes = attributesParser(node);\n    var mask = maskParser(node);\n    return {\n      iconName: iconName,\n      title: node.getAttribute('title'),\n      prefix: prefix,\n      transform: transform,\n      symbol: symbol,\n      mask: mask,\n      extra: {\n        classes: extraClasses,\n        styles: extraStyles,\n        attributes: extraAttributes\n      }\n    };\n  }\n\n  function MissingIcon(error) {\n    this.name = 'MissingIcon';\n    this.message = error || 'Icon unavailable';\n    this.stack = new Error().stack;\n  }\n  MissingIcon.prototype = Object.create(Error.prototype);\n  MissingIcon.prototype.constructor = MissingIcon;\n\n  var FILL = {\n    fill: 'currentColor'\n  };\n  var ANIMATION_BASE = {\n    attributeType: 'XML',\n    repeatCount: 'indefinite',\n    dur: '2s'\n  };\n  var RING = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      d: 'M156.5,447.7l-12.6,29.5c-18.7-9.5-35.9-21.2-51.5-34.9l22.7-22.7C127.6,430.5,141.5,440,156.5,447.7z M40.6,272H8.5 c1.4,21.2,5.4,41.7,11.7,61.1L50,321.2C45.1,305.5,41.8,289,40.6,272z M40.6,240c1.4-18.8,5.2-37,11.1-54.1l-29.5-12.6 C14.7,194.3,10,216.7,8.5,240H40.6z M64.3,156.5c7.8-14.9,17.2-28.8,28.1-41.5L69.7,92.3c-13.7,15.6-25.5,32.8-34.9,51.5 L64.3,156.5z M397,419.6c-13.9,12-29.4,22.3-46.1,30.4l11.9,29.8c20.7-9.9,39.8-22.6,56.9-37.6L397,419.6z M115,92.4 c13.9-12,29.4-22.3,46.1-30.4l-11.9-29.8c-20.7,9.9-39.8,22.6-56.8,37.6L115,92.4z M447.7,355.5c-7.8,14.9-17.2,28.8-28.1,41.5 l22.7,22.7c13.7-15.6,25.5-32.9,34.9-51.5L447.7,355.5z M471.4,272c-1.4,18.8-5.2,37-11.1,54.1l29.5,12.6 c7.5-21.1,12.2-43.5,13.6-66.8H471.4z M321.2,462c-15.7,5-32.2,8.2-49.2,9.4v32.1c21.2-1.4,41.7-5.4,61.1-11.7L321.2,462z M240,471.4c-18.8-1.4-37-5.2-54.1-11.1l-12.6,29.5c21.1,7.5,43.5,12.2,66.8,13.6V471.4z M462,190.8c5,15.7,8.2,32.2,9.4,49.2h32.1 c-1.4-21.2-5.4-41.7-11.7-61.1L462,190.8z M92.4,397c-12-13.9-22.3-29.4-30.4-46.1l-29.8,11.9c9.9,20.7,22.6,39.8,37.6,56.9 L92.4,397z M272,40.6c18.8,1.4,36.9,5.2,54.1,11.1l12.6-29.5C317.7,14.7,295.3,10,272,8.5V40.6z M190.8,50 c15.7-5,32.2-8.2,49.2-9.4V8.5c-21.2,1.4-41.7,5.4-61.1,11.7L190.8,50z M442.3,92.3L419.6,115c12,13.9,22.3,29.4,30.5,46.1 l29.8-11.9C470,128.5,457.3,109.4,442.3,92.3z M397,92.4l22.7-22.7c-15.6-13.7-32.8-25.5-51.5-34.9l-12.6,29.5 C370.4,72.1,384.4,81.5,397,92.4z'\n    })\n  };\n\n  var OPACITY_ANIMATE = _objectSpread({}, ANIMATION_BASE, {\n    attributeName: 'opacity'\n  });\n\n  var DOT = {\n    tag: 'circle',\n    attributes: _objectSpread({}, FILL, {\n      cx: '256',\n      cy: '364',\n      r: '28'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, ANIMATION_BASE, {\n        attributeName: 'r',\n        values: '28;14;28;28;14;28;'\n      })\n    }, {\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;1;1;0;1;'\n      })\n    }]\n  };\n  var QUESTION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '1',\n      d: 'M263.7,312h-16c-6.6,0-12-5.4-12-12c0-71,77.4-63.9,77.4-107.8c0-20-17.8-40.2-57.4-40.2c-29.1,0-44.3,9.6-59.2,28.7 c-3.9,5-11.1,6-16.2,2.4l-13.1-9.2c-5.6-3.9-6.9-11.8-2.6-17.2c21.2-27.2,46.4-44.7,91.2-44.7c52.3,0,97.4,29.8,97.4,80.2 c0,67.6-77.4,63.5-77.4,107.8C275.7,306.6,270.3,312,263.7,312z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;0;0;0;1;'\n      })\n    }]\n  };\n  var EXCLAMATION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '0',\n      d: 'M232.5,134.5l7,168c0.3,6.4,5.6,11.5,12,11.5h9c6.4,0,11.7-5.1,12-11.5l7-168c0.3-6.8-5.2-12.5-12-12.5h-23 C237.7,122,232.2,127.7,232.5,134.5z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '0;0;1;1;0;0;'\n      })\n    }]\n  };\n  var missing = {\n    tag: 'g',\n    children: [RING, DOT, QUESTION, EXCLAMATION]\n  };\n\n  var styles$2 = namespace.styles;\n  function asFoundIcon(icon) {\n    var width = icon[0];\n    var height = icon[1];\n\n    var _icon$slice = icon.slice(4),\n        _icon$slice2 = _slicedToArray(_icon$slice, 1),\n        vectorData = _icon$slice2[0];\n\n    var element = null;\n\n    if (Array.isArray(vectorData)) {\n      element = {\n        tag: 'g',\n        attributes: {\n          class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.GROUP)\n        },\n        children: [{\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.SECONDARY),\n            fill: 'currentColor',\n            d: vectorData[0]\n          }\n        }, {\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.PRIMARY),\n            fill: 'currentColor',\n            d: vectorData[1]\n          }\n        }]\n      };\n    } else {\n      element = {\n        tag: 'path',\n        attributes: {\n          fill: 'currentColor',\n          d: vectorData\n        }\n      };\n    }\n\n    return {\n      found: true,\n      width: width,\n      height: height,\n      icon: element\n    };\n  }\n  function findIcon(iconName, prefix) {\n    return new picked(function (resolve, reject) {\n      var val = {\n        found: false,\n        width: 512,\n        height: 512,\n        icon: missing\n      };\n\n      if (iconName && prefix && styles$2[prefix] && styles$2[prefix][iconName]) {\n        var icon = styles$2[prefix][iconName];\n        return resolve(asFoundIcon(icon));\n      }\n\n      if (iconName && prefix && !config.showMissingIcons) {\n        reject(new MissingIcon(\"Icon is missing for prefix \".concat(prefix, \" with icon name \").concat(iconName)));\n      } else {\n        resolve(val);\n      }\n    });\n  }\n\n  var styles$3 = namespace.styles;\n\n  function generateSvgReplacementMutation(node, nodeMeta) {\n    var iconName = nodeMeta.iconName,\n        title = nodeMeta.title,\n        prefix = nodeMeta.prefix,\n        transform = nodeMeta.transform,\n        symbol = nodeMeta.symbol,\n        mask = nodeMeta.mask,\n        extra = nodeMeta.extra;\n    return new picked(function (resolve, reject) {\n      picked.all([findIcon(iconName, prefix), findIcon(mask.iconName, mask.prefix)]).then(function (_ref) {\n        var _ref2 = _slicedToArray(_ref, 2),\n            main = _ref2[0],\n            mask = _ref2[1];\n\n        resolve([node, makeInlineSvgAbstract({\n          icons: {\n            main: main,\n            mask: mask\n          },\n          prefix: prefix,\n          iconName: iconName,\n          transform: transform,\n          symbol: symbol,\n          mask: mask,\n          title: title,\n          extra: extra,\n          watchable: true\n        })]);\n      });\n    });\n  }\n\n  function generateLayersText(node, nodeMeta) {\n    var title = nodeMeta.title,\n        transform = nodeMeta.transform,\n        extra = nodeMeta.extra;\n    var width = null;\n    var height = null;\n\n    if (IS_IE) {\n      var computedFontSize = parseInt(getComputedStyle(node).fontSize, 10);\n      var boundingClientRect = node.getBoundingClientRect();\n      width = boundingClientRect.width / computedFontSize;\n      height = boundingClientRect.height / computedFontSize;\n    }\n\n    if (config.autoA11y && !title) {\n      extra.attributes['aria-hidden'] = 'true';\n    }\n\n    return picked.resolve([node, makeLayersTextAbstract({\n      content: node.innerHTML,\n      width: width,\n      height: height,\n      transform: transform,\n      title: title,\n      extra: extra,\n      watchable: true\n    })]);\n  }\n\n  function generateMutation(node) {\n    var nodeMeta = parseMeta(node);\n\n    if (~nodeMeta.extra.classes.indexOf(LAYERS_TEXT_CLASSNAME)) {\n      return generateLayersText(node, nodeMeta);\n    } else {\n      return generateSvgReplacementMutation(node, nodeMeta);\n    }\n  }\n\n  function onTree(root) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    if (!IS_DOM) return;\n    var htmlClassList = DOCUMENT.documentElement.classList;\n\n    var hclAdd = function hclAdd(suffix) {\n      return htmlClassList.add(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var hclRemove = function hclRemove(suffix) {\n      return htmlClassList.remove(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var prefixes = config.autoFetchSvg ? Object.keys(PREFIX_TO_STYLE) : Object.keys(styles$3);\n    var prefixesDomQuery = [\".\".concat(LAYERS_TEXT_CLASSNAME, \":not([\").concat(DATA_FA_I2SVG, \"])\")].concat(prefixes.map(function (p) {\n      return \".\".concat(p, \":not([\").concat(DATA_FA_I2SVG, \"])\");\n    })).join(', ');\n\n    if (prefixesDomQuery.length === 0) {\n      return;\n    }\n\n    var candidates = [];\n\n    try {\n      candidates = toArray(root.querySelectorAll(prefixesDomQuery));\n    } catch (e) {// noop\n    }\n\n    if (candidates.length > 0) {\n      hclAdd('pending');\n      hclRemove('complete');\n    } else {\n      return;\n    }\n\n    var mark = perf.begin('onTree');\n    var mutations = candidates.reduce(function (acc, node) {\n      try {\n        var mutation = generateMutation(node);\n\n        if (mutation) {\n          acc.push(mutation);\n        }\n      } catch (e) {\n        if (!PRODUCTION) {\n          if (e instanceof MissingIcon) {\n            console.error(e);\n          }\n        }\n      }\n\n      return acc;\n    }, []);\n    return new picked(function (resolve, reject) {\n      picked.all(mutations).then(function (resolvedMutations) {\n        perform(resolvedMutations, function () {\n          hclAdd('active');\n          hclAdd('complete');\n          hclRemove('pending');\n          if (typeof callback === 'function') callback();\n          mark();\n          resolve();\n        });\n      }).catch(function () {\n        mark();\n        reject();\n      });\n    });\n  }\n  function onNode(node) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    generateMutation(node).then(function (mutation) {\n      if (mutation) {\n        perform([mutation], callback);\n      }\n    });\n  }\n\n  function replaceForPosition(node, position) {\n    var pendingAttribute = \"\".concat(DATA_FA_PSEUDO_ELEMENT_PENDING).concat(position.replace(':', '-'));\n    return new picked(function (resolve, reject) {\n      if (node.getAttribute(pendingAttribute) !== null) {\n        // This node is already being processed\n        return resolve();\n      }\n\n      var children = toArray(node.children);\n      var alreadyProcessedPseudoElement = children.filter(function (c) {\n        return c.getAttribute(DATA_FA_PSEUDO_ELEMENT) === position;\n      })[0];\n      var styles = WINDOW.getComputedStyle(node, position);\n      var fontFamily = styles.getPropertyValue('font-family').match(FONT_FAMILY_PATTERN);\n      var fontWeight = styles.getPropertyValue('font-weight');\n\n      if (alreadyProcessedPseudoElement && !fontFamily) {\n        // If we've already processed it but the current computed style does not result in a font-family,\n        // that probably means that a class name that was previously present to make the icon has been\n        // removed. So we now should delete the icon.\n        node.removeChild(alreadyProcessedPseudoElement);\n        return resolve();\n      } else if (fontFamily) {\n        var content = styles.getPropertyValue('content');\n        var prefix = ~['Solid', 'Regular', 'Light', 'Duotone', 'Brands'].indexOf(fontFamily[1]) ? STYLE_TO_PREFIX[fontFamily[1].toLowerCase()] : FONT_WEIGHT_TO_PREFIX[fontWeight];\n        var hexValue = toHex(content.length === 3 ? content.substr(1, 1) : content);\n        var iconName = byUnicode(prefix, hexValue);\n        var iconIdentifier = iconName; // Only convert the pseudo element in this :before/:after position into an icon if we haven't\n        // already done so with the same prefix and iconName\n\n        if (iconName && (!alreadyProcessedPseudoElement || alreadyProcessedPseudoElement.getAttribute(DATA_PREFIX) !== prefix || alreadyProcessedPseudoElement.getAttribute(DATA_ICON) !== iconIdentifier)) {\n          node.setAttribute(pendingAttribute, iconIdentifier);\n\n          if (alreadyProcessedPseudoElement) {\n            // Delete the old one, since we're replacing it with a new one\n            node.removeChild(alreadyProcessedPseudoElement);\n          }\n\n          var meta = blankMeta();\n          var extra = meta.extra;\n          extra.attributes[DATA_FA_PSEUDO_ELEMENT] = position;\n          findIcon(iconName, prefix).then(function (main) {\n            var abstract = makeInlineSvgAbstract(_objectSpread({}, meta, {\n              icons: {\n                main: main,\n                mask: emptyCanonicalIcon()\n              },\n              prefix: prefix,\n              iconName: iconIdentifier,\n              extra: extra,\n              watchable: true\n            }));\n            var element = DOCUMENT.createElement('svg');\n\n            if (position === ':before') {\n              node.insertBefore(element, node.firstChild);\n            } else {\n              node.appendChild(element);\n            }\n\n            element.outerHTML = abstract.map(function (a) {\n              return toHtml(a);\n            }).join('\\n');\n            node.removeAttribute(pendingAttribute);\n            resolve();\n          }).catch(reject);\n        } else {\n          resolve();\n        }\n      } else {\n        resolve();\n      }\n    });\n  }\n\n  function replace(node) {\n    return picked.all([replaceForPosition(node, ':before'), replaceForPosition(node, ':after')]);\n  }\n\n  function processable(node) {\n    return node.parentNode !== document.head && !~TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS.indexOf(node.tagName.toUpperCase()) && !node.getAttribute(DATA_FA_PSEUDO_ELEMENT) && (!node.parentNode || node.parentNode.tagName !== 'svg');\n  }\n\n  function searchPseudoElements (root) {\n    if (!IS_DOM) return;\n    return new picked(function (resolve, reject) {\n      var operations = toArray(root.querySelectorAll('*')).filter(processable).map(replace);\n      var end = perf.begin('searchPseudoElements');\n      disableObservation();\n      picked.all(operations).then(function () {\n        end();\n        enableObservation();\n        resolve();\n      }).catch(function () {\n        end();\n        enableObservation();\n        reject();\n      });\n    });\n  }\n\n  var baseStyles = \"svg:not(:root).svg-inline--fa{overflow:visible}.svg-inline--fa{display:inline-block;font-size:inherit;height:1em;overflow:visible;vertical-align:-.125em}.svg-inline--fa.fa-lg{vertical-align:-.225em}.svg-inline--fa.fa-w-1{width:.0625em}.svg-inline--fa.fa-w-2{width:.125em}.svg-inline--fa.fa-w-3{width:.1875em}.svg-inline--fa.fa-w-4{width:.25em}.svg-inline--fa.fa-w-5{width:.3125em}.svg-inline--fa.fa-w-6{width:.375em}.svg-inline--fa.fa-w-7{width:.4375em}.svg-inline--fa.fa-w-8{width:.5em}.svg-inline--fa.fa-w-9{width:.5625em}.svg-inline--fa.fa-w-10{width:.625em}.svg-inline--fa.fa-w-11{width:.6875em}.svg-inline--fa.fa-w-12{width:.75em}.svg-inline--fa.fa-w-13{width:.8125em}.svg-inline--fa.fa-w-14{width:.875em}.svg-inline--fa.fa-w-15{width:.9375em}.svg-inline--fa.fa-w-16{width:1em}.svg-inline--fa.fa-w-17{width:1.0625em}.svg-inline--fa.fa-w-18{width:1.125em}.svg-inline--fa.fa-w-19{width:1.1875em}.svg-inline--fa.fa-w-20{width:1.25em}.svg-inline--fa.fa-pull-left{margin-right:.3em;width:auto}.svg-inline--fa.fa-pull-right{margin-left:.3em;width:auto}.svg-inline--fa.fa-border{height:1.5em}.svg-inline--fa.fa-li{width:2em}.svg-inline--fa.fa-fw{width:1.25em}.fa-layers svg.svg-inline--fa{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.fa-layers{display:inline-block;height:1em;position:relative;text-align:center;vertical-align:-.125em;width:1em}.fa-layers svg.svg-inline--fa{-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter,.fa-layers-text{display:inline-block;position:absolute;text-align:center}.fa-layers-text{left:50%;top:50%;-webkit-transform:translate(-50%,-50%);transform:translate(-50%,-50%);-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter{background-color:#ff253a;border-radius:1em;-webkit-box-sizing:border-box;box-sizing:border-box;color:#fff;height:1.5em;line-height:1;max-width:5em;min-width:1.5em;overflow:hidden;padding:.25em;right:0;text-overflow:ellipsis;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-bottom-right{bottom:0;right:0;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom right;transform-origin:bottom right}.fa-layers-bottom-left{bottom:0;left:0;right:auto;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom left;transform-origin:bottom left}.fa-layers-top-right{right:0;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-top-left{left:0;right:auto;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top left;transform-origin:top left}.fa-lg{font-size:1.3333333333em;line-height:.75em;vertical-align:-.0667em}.fa-xs{font-size:.75em}.fa-sm{font-size:.875em}.fa-1x{font-size:1em}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-6x{font-size:6em}.fa-7x{font-size:7em}.fa-8x{font-size:8em}.fa-9x{font-size:9em}.fa-10x{font-size:10em}.fa-fw{text-align:center;width:1.25em}.fa-ul{list-style-type:none;margin-left:2.5em;padding-left:0}.fa-ul>li{position:relative}.fa-li{left:-2em;position:absolute;text-align:center;width:2em;line-height:inherit}.fa-border{border:solid .08em #eee;border-radius:.1em;padding:.2em .25em .15em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left,.fab.fa-pull-left,.fal.fa-pull-left,.far.fa-pull-left,.fas.fa-pull-left{margin-right:.3em}.fa.fa-pull-right,.fab.fa-pull-right,.fal.fa-pull-right,.far.fa-pull-right,.fas.fa-pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s infinite linear;animation:fa-spin 2s infinite linear}.fa-pulse{-webkit-animation:fa-spin 1s infinite steps(8);animation:fa-spin 1s infinite steps(8)}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}.fa-rotate-90{-webkit-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{-webkit-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{-webkit-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{-webkit-transform:scale(-1,1);transform:scale(-1,1)}.fa-flip-vertical{-webkit-transform:scale(1,-1);transform:scale(1,-1)}.fa-flip-both,.fa-flip-horizontal.fa-flip-vertical{-webkit-transform:scale(-1,-1);transform:scale(-1,-1)}:root .fa-flip-both,:root .fa-flip-horizontal,:root .fa-flip-vertical,:root .fa-rotate-180,:root .fa-rotate-270,:root .fa-rotate-90{-webkit-filter:none;filter:none}.fa-stack{display:inline-block;height:2em;position:relative;width:2.5em}.fa-stack-1x,.fa-stack-2x{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.svg-inline--fa.fa-stack-1x{height:1em;width:1.25em}.svg-inline--fa.fa-stack-2x{height:2em;width:2.5em}.fa-inverse{color:#fff}.sr-only{border:0;clip:rect(0,0,0,0);height:1px;margin:-1px;overflow:hidden;padding:0;position:absolute;width:1px}.sr-only-focusable:active,.sr-only-focusable:focus{clip:auto;height:auto;margin:0;overflow:visible;position:static;width:auto}.svg-inline--fa .fa-primary{fill:var(--fa-primary-color,currentColor);opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa .fa-secondary{fill:var(--fa-secondary-color,currentColor);opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-primary{opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-secondary{opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa mask .fa-primary,.svg-inline--fa mask .fa-secondary{fill:#000}.fad.fa-inverse{color:#fff}\";\n\n  function css () {\n    var dfp = DEFAULT_FAMILY_PREFIX;\n    var drc = DEFAULT_REPLACEMENT_CLASS;\n    var fp = config.familyPrefix;\n    var rc = config.replacementClass;\n    var s = baseStyles;\n\n    if (fp !== dfp || rc !== drc) {\n      var dPatt = new RegExp(\"\\\\.\".concat(dfp, \"\\\\-\"), 'g');\n      var customPropPatt = new RegExp(\"\\\\--\".concat(dfp, \"\\\\-\"), 'g');\n      var rPatt = new RegExp(\"\\\\.\".concat(drc), 'g');\n      s = s.replace(dPatt, \".\".concat(fp, \"-\")).replace(customPropPatt, \"--\".concat(fp, \"-\")).replace(rPatt, \".\".concat(rc));\n    }\n\n    return s;\n  }\n\n  var Library =\n  /*#__PURE__*/\n  function () {\n    function Library() {\n      _classCallCheck(this, Library);\n\n      this.definitions = {};\n    }\n\n    _createClass(Library, [{\n      key: \"add\",\n      value: function add() {\n        var _this = this;\n\n        for (var _len = arguments.length, definitions = new Array(_len), _key = 0; _key < _len; _key++) {\n          definitions[_key] = arguments[_key];\n        }\n\n        var additions = definitions.reduce(this._pullDefinitions, {});\n        Object.keys(additions).forEach(function (key) {\n          _this.definitions[key] = _objectSpread({}, _this.definitions[key] || {}, additions[key]);\n          defineIcons(key, additions[key]);\n          build();\n        });\n      }\n    }, {\n      key: \"reset\",\n      value: function reset() {\n        this.definitions = {};\n      }\n    }, {\n      key: \"_pullDefinitions\",\n      value: function _pullDefinitions(additions, definition) {\n        var normalized = definition.prefix && definition.iconName && definition.icon ? {\n          0: definition\n        } : definition;\n        Object.keys(normalized).map(function (key) {\n          var _normalized$key = normalized[key],\n              prefix = _normalized$key.prefix,\n              iconName = _normalized$key.iconName,\n              icon = _normalized$key.icon;\n          if (!additions[prefix]) additions[prefix] = {};\n          additions[prefix][iconName] = icon;\n        });\n        return additions;\n      }\n    }]);\n\n    return Library;\n  }();\n\n  function ensureCss() {\n    if (config.autoAddCss && !_cssInserted) {\n      insertCss(css());\n\n      _cssInserted = true;\n    }\n  }\n\n  function apiObject(val, abstractCreator) {\n    Object.defineProperty(val, 'abstract', {\n      get: abstractCreator\n    });\n    Object.defineProperty(val, 'html', {\n      get: function get() {\n        return val.abstract.map(function (a) {\n          return toHtml(a);\n        });\n      }\n    });\n    Object.defineProperty(val, 'node', {\n      get: function get() {\n        if (!IS_DOM) return;\n        var container = DOCUMENT.createElement('div');\n        container.innerHTML = val.html;\n        return container.children;\n      }\n    });\n    return val;\n  }\n\n  function findIconDefinition(iconLookup) {\n    var _iconLookup$prefix = iconLookup.prefix,\n        prefix = _iconLookup$prefix === void 0 ? 'fa' : _iconLookup$prefix,\n        iconName = iconLookup.iconName;\n    if (!iconName) return;\n    return iconFromMapping(library.definitions, prefix, iconName) || iconFromMapping(namespace.styles, prefix, iconName);\n  }\n\n  function resolveIcons(next) {\n    return function (maybeIconDefinition) {\n      var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n      var iconDefinition = (maybeIconDefinition || {}).icon ? maybeIconDefinition : findIconDefinition(maybeIconDefinition || {});\n      var mask = params.mask;\n\n      if (mask) {\n        mask = (mask || {}).icon ? mask : findIconDefinition(mask || {});\n      }\n\n      return next(iconDefinition, _objectSpread({}, params, {\n        mask: mask\n      }));\n    };\n  }\n\n  var library = new Library();\n  var noAuto = function noAuto() {\n    config.autoReplaceSvg = false;\n    config.observeMutations = false;\n    disconnect();\n  };\n  var _cssInserted = false;\n  var dom = {\n    i2svg: function i2svg() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n\n      if (IS_DOM) {\n        ensureCss();\n        var _params$node = params.node,\n            node = _params$node === void 0 ? DOCUMENT : _params$node,\n            _params$callback = params.callback,\n            callback = _params$callback === void 0 ? function () {} : _params$callback;\n\n        if (config.searchPseudoElements) {\n          searchPseudoElements(node);\n        }\n\n        return onTree(node, callback);\n      } else {\n        return picked.reject('Operation requires a DOM of some kind.');\n      }\n    },\n    css: css,\n    insertCss: function insertCss$$1() {\n      if (!_cssInserted) {\n        insertCss(css());\n\n        _cssInserted = true;\n      }\n    },\n    watch: function watch() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n      var autoReplaceSvgRoot = params.autoReplaceSvgRoot,\n          observeMutationsRoot = params.observeMutationsRoot;\n\n      if (config.autoReplaceSvg === false) {\n        config.autoReplaceSvg = true;\n      }\n\n      config.observeMutations = true;\n      domready(function () {\n        autoReplace({\n          autoReplaceSvgRoot: autoReplaceSvgRoot\n        });\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements,\n          observeMutationsRoot: observeMutationsRoot\n        });\n      });\n    }\n  };\n  var parse = {\n    transform: function transform(transformString) {\n      return parseTransformString(transformString);\n    }\n  };\n  var icon = resolveIcons(function (iconDefinition) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform = params.transform,\n        transform = _params$transform === void 0 ? meaninglessTransform : _params$transform,\n        _params$symbol = params.symbol,\n        symbol = _params$symbol === void 0 ? false : _params$symbol,\n        _params$mask = params.mask,\n        mask = _params$mask === void 0 ? null : _params$mask,\n        _params$title = params.title,\n        title = _params$title === void 0 ? null : _params$title,\n        _params$classes = params.classes,\n        classes = _params$classes === void 0 ? [] : _params$classes,\n        _params$attributes = params.attributes,\n        attributes = _params$attributes === void 0 ? {} : _params$attributes,\n        _params$styles = params.styles,\n        styles = _params$styles === void 0 ? {} : _params$styles;\n    if (!iconDefinition) return;\n    var prefix = iconDefinition.prefix,\n        iconName = iconDefinition.iconName,\n        icon = iconDefinition.icon;\n    return apiObject(_objectSpread({\n      type: 'icon'\n    }, iconDefinition), function () {\n      ensureCss();\n\n      if (config.autoA11y) {\n        if (title) {\n          attributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n        } else {\n          attributes['aria-hidden'] = 'true';\n          attributes['focusable'] = 'false';\n        }\n      }\n\n      return makeInlineSvgAbstract({\n        icons: {\n          main: asFoundIcon(icon),\n          mask: mask ? asFoundIcon(mask.icon) : {\n            found: false,\n            width: null,\n            height: null,\n            icon: {}\n          }\n        },\n        prefix: prefix,\n        iconName: iconName,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        symbol: symbol,\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: classes\n        }\n      });\n    });\n  });\n  var text = function text(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform2 = params.transform,\n        transform = _params$transform2 === void 0 ? meaninglessTransform : _params$transform2,\n        _params$title2 = params.title,\n        title = _params$title2 === void 0 ? null : _params$title2,\n        _params$classes2 = params.classes,\n        classes = _params$classes2 === void 0 ? [] : _params$classes2,\n        _params$attributes2 = params.attributes,\n        attributes = _params$attributes2 === void 0 ? {} : _params$attributes2,\n        _params$styles2 = params.styles,\n        styles = _params$styles2 === void 0 ? {} : _params$styles2;\n    return apiObject({\n      type: 'text',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersTextAbstract({\n        content: content,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-text\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var counter = function counter(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$title3 = params.title,\n        title = _params$title3 === void 0 ? null : _params$title3,\n        _params$classes3 = params.classes,\n        classes = _params$classes3 === void 0 ? [] : _params$classes3,\n        _params$attributes3 = params.attributes,\n        attributes = _params$attributes3 === void 0 ? {} : _params$attributes3,\n        _params$styles3 = params.styles,\n        styles = _params$styles3 === void 0 ? {} : _params$styles3;\n    return apiObject({\n      type: 'counter',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersCounterAbstract({\n        content: content.toString(),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-counter\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var layer = function layer(assembler) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$classes4 = params.classes,\n        classes = _params$classes4 === void 0 ? [] : _params$classes4;\n    return apiObject({\n      type: 'layer'\n    }, function () {\n      ensureCss();\n      var children = [];\n      assembler(function (args) {\n        Array.isArray(args) ? args.map(function (a) {\n          children = children.concat(a.abstract);\n        }) : children = children.concat(args.abstract);\n      });\n      return [{\n        tag: 'span',\n        attributes: {\n          class: [\"\".concat(config.familyPrefix, \"-layers\")].concat(_toConsumableArray(classes)).join(' ')\n        },\n        children: children\n      }];\n    });\n  };\n  var api = {\n    noAuto: noAuto,\n    config: config,\n    dom: dom,\n    library: library,\n    parse: parse,\n    findIconDefinition: findIconDefinition,\n    icon: icon,\n    text: text,\n    counter: counter,\n    layer: layer,\n    toHtml: toHtml\n  };\n\n  var autoReplace = function autoReplace() {\n    var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n    var _params$autoReplaceSv = params.autoReplaceSvgRoot,\n        autoReplaceSvgRoot = _params$autoReplaceSv === void 0 ? DOCUMENT : _params$autoReplaceSv;\n    if ((Object.keys(namespace.styles).length > 0 || config.autoFetchSvg) && IS_DOM && config.autoReplaceSvg) api.dom.i2svg({\n      node: autoReplaceSvgRoot\n    });\n  };\n\n  function bootstrap() {\n    if (IS_BROWSER) {\n      if (!WINDOW.FontAwesome) {\n        WINDOW.FontAwesome = api;\n      }\n\n      domready(function () {\n        autoReplace();\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements\n        });\n      });\n    }\n\n    namespace.hooks = _objectSpread({}, namespace.hooks, {\n      addPack: function addPack(prefix, icons) {\n        namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, icons);\n        build();\n        autoReplace();\n      },\n      addShims: function addShims(shims) {\n        var _namespace$shims;\n\n        (_namespace$shims = namespace.shims).push.apply(_namespace$shims, _toConsumableArray(shims));\n\n        build();\n        autoReplace();\n      }\n    });\n  }\n\n  bunker(bootstrap);\n\n}());\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/brands.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"500px\": [448, 512, [], \"f26e\", \"M103.3 344.3c-6.5-14.2-6.9-18.3 7.4-23.1 25.6-8 8 9.2 43.2 49.2h.3v-93.9c1.2-50.2 44-92.2 97.7-92.2 53.9 0 97.7 43.5 97.7 96.8 0 63.4-60.8 113.2-128.5 93.3-10.5-4.2-2.1-31.7 8.5-28.6 53 0 89.4-10.1 89.4-64.4 0-61-77.1-89.6-116.9-44.6-23.5 26.4-17.6 42.1-17.6 157.6 50.7 31 118.3 22 160.4-20.1 24.8-24.8 38.5-58 38.5-93 0-35.2-13.8-68.2-38.8-93.3-24.8-24.8-57.8-38.5-93.3-38.5s-68.8 13.8-93.5 38.5c-.3.3-16 16.5-21.2 23.9l-.5.6c-3.3 4.7-6.3 9.1-20.1 6.1-6.9-1.7-14.3-5.8-14.3-11.8V20c0-5 3.9-10.5 10.5-10.5h241.3c8.3 0 8.3 11.6 8.3 15.1 0 3.9 0 15.1-8.3 15.1H130.3v132.9h.3c104.2-109.8 282.8-36 282.8 108.9 0 178.1-244.8 220.3-310.1 62.8zm63.3-260.8c-.5 4.2 4.6 24.5 14.6 20.6C306 56.6 384 144.5 390.6 144.5c4.8 0 22.8-15.3 14.3-22.8-93.2-89-234.5-57-238.3-38.2zM393 414.7C283 524.6 94 475.5 61 310.5c0-12.2-30.4-7.4-28.9 3.3 24 173.4 246 256.9 381.6 121.3 6.9-7.8-12.6-28.4-20.7-20.4zM213.6 306.6c0 4 4.3 7.3 5.5 8.5 3 3 6.1 4.4 8.5 4.4 3.8 0 2.6.2 22.3-19.5 19.6 19.3 19.1 19.5 22.3 19.5 5.4 0 18.5-10.4 10.7-18.2L265.6 284l18.2-18.2c6.3-6.8-10.1-21.8-16.2-15.7L249.7 268c-18.6-18.8-18.4-19.5-21.5-19.5-5 0-18 11.7-12.4 17.3L234 284c-18.1 17.9-20.4 19.2-20.4 22.6z\"],\n    \"accessible-icon\": [448, 512, [], \"f368\", \"M423.9 255.8L411 413.1c-3.3 40.7-63.9 35.1-60.6-4.9l10-122.5-41.1 2.3c10.1 20.7 15.8 43.9 15.8 68.5 0 41.2-16.1 78.7-42.3 106.5l-39.3-39.3c57.9-63.7 13.1-167.2-74-167.2-25.9 0-49.5 9.9-67.2 26L73 243.2c22-20.7 50.1-35.1 81.4-40.2l75.3-85.7-42.6-24.8-51.6 46c-30 26.8-70.6-18.5-40.5-45.4l68-60.7c9.8-8.8 24.1-10.2 35.5-3.6 0 0 139.3 80.9 139.5 81.1 16.2 10.1 20.7 36 6.1 52.6L285.7 229l106.1-5.9c18.5-1.1 33.6 14.4 32.1 32.7zm-64.9-154c28.1 0 50.9-22.8 50.9-50.9C409.9 22.8 387.1 0 359 0c-28.1 0-50.9 22.8-50.9 50.9 0 28.1 22.8 50.9 50.9 50.9zM179.6 456.5c-80.6 0-127.4-90.6-82.7-156.1l-39.7-39.7C36.4 287 24 320.3 24 356.4c0 130.7 150.7 201.4 251.4 122.5l-39.7-39.7c-16 10.9-35.3 17.3-56.1 17.3z\"],\n    \"accusoft\": [640, 512, [], \"f369\", \"M322.1 252v-1l-51.2-65.8s-12 1.6-25 15.1c-9 9.3-242.1 239.1-243.4 240.9-7 10 1.6 6.8 15.7 1.7.8 0 114.5-36.6 114.5-36.6.5-.6-.1-.1.6-.6-.4-5.1-.8-26.2-1-27.7-.6-5.2 2.2-6.9 7-8.9l92.6-33.8c.6-.8 88.5-81.7 90.2-83.3zm160.1 120.1c13.3 16.1 20.7 13.3 30.8 9.3 3.2-1.2 115.4-47.6 117.8-48.9 8-4.3-1.7-16.7-7.2-23.4-2.1-2.5-205.1-245.6-207.2-248.3-9.7-12.2-14.3-12.9-38.4-12.8-10.2 0-106.8.5-116.5.6-19.2.1-32.9-.3-19.2 16.9C250 75 476.5 365.2 482.2 372.1zm152.7 1.6c-2.3-.3-24.6-4.7-38-7.2 0 0-115 50.4-117.5 51.6-16 7.3-26.9-3.2-36.7-14.6l-57.1-74c-5.4-.9-60.4-9.6-65.3-9.3-3.1.2-9.6.8-14.4 2.9-4.9 2.1-145.2 52.8-150.2 54.7-5.1 2-11.4 3.6-11.1 7.6.2 2.5 2 2.6 4.6 3.5 2.7.8 300.9 67.6 308 69.1 15.6 3.3 38.5 10.5 53.6 1.7 2.1-1.2 123.8-76.4 125.8-77.8 5.4-4 4.3-6.8-1.7-8.2z\"],\n    \"acquisitions-incorporated\": [384, 512, [], \"f6af\", \"M357.45 468.2c-1.2-7.7-1.3-7.6-9.6-7.6-99.8.2-111.8-2.4-112.7-2.6-12.3-1.7-20.6-10.5-21-23.1-.1-1.6-.2-71.6-1-129.1-.1-4.7 1.6-6.4 5.9-7.5 12.5-3 24.9-6.1 37.3-9.7 4.3-1.3 6.8-.2 8.4 3.5 4.5 10.3 8.8 20.6 13.2 30.9 1.6 3.7.1 4.4-3.4 4.4-10-.2-20-.1-30.4-.1v27h116c-1.4-9.5-2.7-18.1-4-27.5-7 0-13.8.4-20.4-.1-22.6-1.6-18.3-4.4-84-158.6-8.8-20.1-27.9-62.1-36.5-89.2-4.4-14 5.5-25.4 18.9-26.6 18.6-1.7 37.5-1.6 56.2-2 20.6-.4 41.2-.4 61.8-.5 3.1 0 4-1.4 4.3-4.3 1.2-9.8 2.7-19.5 4-29.2.8-5.3 1.6-10.7 2.4-16.1L23.75 0c-3.6 0-5.3 1.1-4.6 5.3 2.2 13.2-.8.8 6.4 45.3 63.4 0 71.8.9 101.8.5 12.3-.2 37 3.5 37.7 22.1.4 11.4-1.1 11.3-32.6 87.4-53.8 129.8-50.7 120.3-67.3 161-1.7 4.1-3.6 5.2-7.6 5.2-8.5-.2-17-.3-25.4.1-1.9.1-5.2 1.8-5.5 3.2-1.5 8.1-2.2 16.3-3.2 24.9h114.3v-27.6c-6.9 0-33.5.4-35.3-2.9 5.3-12.3 10.4-24.4 15.7-36.7 16.3 4 31.9 7.8 47.6 11.7 3.4.9 4.6 3 4.6 6.8-.1 42.9.1 85.9.2 128.8 0 10.2-5.5 19.1-14.9 23.1-6.5 2.7-3.3 3.4-121.4 2.4-5.3 0-7.1 2-7.6 6.8-1.5 12.9-2.9 25.9-5 38.8-.8 5 1.3 5.7 5.3 5.7 183.2.6-30.7 0 337.1 0-2.5-15-4.4-29.4-6.6-43.7zm-174.9-205.7c-13.3-4.2-26.6-8.2-39.9-12.5a44.53 44.53 0 0 1-5.8-2.9c17.2-44.3 34.2-88.1 51.3-132.1 7.5 2.4 7.9-.8 9.4 0 9.3 22.5 18.1 60.1 27 82.8 6.6 16.7 13 33.5 19.7 50.9a35.78 35.78 0 0 1-3.9 2.1c-13.1 3.9-26.4 7.5-39.4 11.7a27.66 27.66 0 0 1-18.4 0z\"],\n    \"adn\": [496, 512, [], \"f170\", \"M248 167.5l64.9 98.8H183.1l64.9-98.8zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-99.8 82.7L248 115.5 99.8 338.7h30.4l33.6-51.7h168.6l33.6 51.7h30.2z\"],\n    \"adobe\": [512, 512, [], \"f778\", \"M315.5 64h170.9v384L315.5 64zm-119 0H25.6v384L196.5 64zM256 206.1L363.5 448h-73l-30.7-76.8h-78.7L256 206.1z\"],\n    \"adversal\": [512, 512, [], \"f36a\", \"M482.1 32H28.7C5.8 32 0 37.9 0 60.9v390.2C0 474.4 5.8 480 28.7 480h453.4c24.4 0 29.9-5.2 29.9-29.7V62.2c0-24.6-5.4-30.2-29.9-30.2zM178.4 220.3c-27.5-20.2-72.1-8.7-84.2 23.4-4.3 11.1-9.3 9.5-17.5 8.3-9.7-1.5-17.2-3.2-22.5-5.5-28.8-11.4 8.6-55.3 24.9-64.3 41.1-21.4 83.4-22.2 125.3-4.8 40.9 16.8 34.5 59.2 34.5 128.5 2.7 25.8-4.3 58.3 9.3 88.8 1.9 4.4.4 7.9-2.7 10.7-8.4 6.7-39.3 2.2-46.6-7.4-1.9-2.2-1.8-3.6-3.9-6.2-3.6-3.9-7.3-2.2-11.9 1-57.4 36.4-140.3 21.4-147-43.3-3.1-29.3 12.4-57.1 39.6-71 38.2-19.5 112.2-11.8 114-30.9 1.1-10.2-1.9-20.1-11.3-27.3zm286.7 222c0 15.1-11.1 9.9-17.8 9.9H52.4c-7.4 0-18.2 4.8-17.8-10.7.4-13.9 10.5-9.1 17.1-9.1 132.3-.4 264.5-.4 396.8 0 6.8 0 16.6-4.4 16.6 9.9zm3.8-340.5v291c0 5.7-.7 13.9-8.1 13.9-12.4-.4-27.5 7.1-36.1-5.6-5.8-8.7-7.8-4-12.4-1.2-53.4 29.7-128.1 7.1-144.4-85.2-6.1-33.4-.7-67.1 15.7-100 11.8-23.9 56.9-76.1 136.1-30.5v-71c0-26.2-.1-26.2 26-26.2 3.1 0 6.6.4 9.7 0 10.1-.8 13.6 4.4 13.6 14.3-.1.2-.1.3-.1.5zm-51.5 232.3c-19.5 47.6-72.9 43.3-90 5.2-15.1-33.3-15.5-68.2.4-101.5 16.3-34.1 59.7-35.7 81.5-4.8 20.6 28.8 14.9 84.6 8.1 101.1zm-294.8 35.3c-7.5-1.3-33-3.3-33.7-27.8-.4-13.9 7.8-23 19.8-25.8 24.4-5.9 49.3-9.9 73.7-14.7 8.9-2 7.4 4.4 7.8 9.5 1.4 33-26.1 59.2-67.6 58.8z\"],\n    \"affiliatetheme\": [512, 512, [], \"f36b\", \"M159.7 237.4C108.4 308.3 43.1 348.2 14 326.6-15.2 304.9 2.8 230 54.2 159.1c51.3-70.9 116.6-110.8 145.7-89.2 29.1 21.6 11.1 96.6-40.2 167.5zm351.2-57.3C437.1 303.5 319 367.8 246.4 323.7c-25-15.2-41.3-41.2-49-73.8-33.6 64.8-92.8 113.8-164.1 133.2 49.8 59.3 124.1 96.9 207 96.9 150 0 271.6-123.1 271.6-274.9.1-8.5-.3-16.8-1-25z\"],\n    \"airbnb\": [448, 512, [], \"f834\", \"M224 373.12c-25.24-31.67-40.08-59.43-45-83.18-22.55-88 112.61-88 90.06 0-5.45 24.25-20.29 52-45 83.18zm138.15 73.23c-42.06 18.31-83.67-10.88-119.3-50.47 103.9-130.07 46.11-200-18.85-200-54.92 0-85.16 46.51-73.28 100.5 6.93 29.19 25.23 62.39 54.43 99.5-32.53 36.05-60.55 52.69-85.15 54.92-50 7.43-89.11-41.06-71.3-91.09 15.1-39.16 111.72-231.18 115.87-241.56 15.75-30.07 25.56-57.4 59.38-57.4 32.34 0 43.4 25.94 60.37 59.87 36 70.62 89.35 177.48 114.84 239.09 13.17 33.07-1.37 71.29-37.01 86.64zm47-136.12C280.27 35.93 273.13 32 224 32c-45.52 0-64.87 31.67-84.66 72.79C33.18 317.1 22.89 347.19 22 349.81-3.22 419.14 48.74 480 111.63 480c21.71 0 60.61-6.06 112.37-62.4 58.68 63.78 101.26 62.4 112.37 62.4 62.89.05 114.85-60.86 89.61-130.19.02-3.89-16.82-38.9-16.82-39.58z\"],\n    \"algolia\": [448, 512, [], \"f36c\", \"M229.3 182.6c-49.3 0-89.2 39.9-89.2 89.2 0 49.3 39.9 89.2 89.2 89.2s89.2-39.9 89.2-89.2c0-49.3-40-89.2-89.2-89.2zm62.7 56.6l-58.9 30.6c-1.8.9-3.8-.4-3.8-2.3V201c0-1.5 1.3-2.7 2.7-2.6 26.2 1 48.9 15.7 61.1 37.1.7 1.3.2 3-1.1 3.7zM389.1 32H58.9C26.4 32 0 58.4 0 90.9V421c0 32.6 26.4 59 58.9 59H389c32.6 0 58.9-26.4 58.9-58.9V90.9C448 58.4 421.6 32 389.1 32zm-202.6 84.7c0-10.8 8.7-19.5 19.5-19.5h45.3c10.8 0 19.5 8.7 19.5 19.5v15.4c0 1.8-1.7 3-3.3 2.5-12.3-3.4-25.1-5.1-38.1-5.1-13.5 0-26.7 1.8-39.4 5.5-1.7.5-3.4-.8-3.4-2.5v-15.8zm-84.4 37l9.2-9.2c7.6-7.6 19.9-7.6 27.5 0l7.7 7.7c1.1 1.1 1 3-.3 4-6.2 4.5-12.1 9.4-17.6 14.9-5.4 5.4-10.4 11.3-14.8 17.4-1 1.3-2.9 1.5-4 .3l-7.7-7.7c-7.6-7.5-7.6-19.8 0-27.4zm127.2 244.8c-70 0-126.6-56.7-126.6-126.6s56.7-126.6 126.6-126.6c70 0 126.6 56.6 126.6 126.6 0 69.8-56.7 126.6-126.6 126.6z\"],\n    \"alipay\": [448, 512, [], \"f642\", \"M377.74 32H70.26C31.41 32 0 63.41 0 102.26v307.48C0 448.59 31.41 480 70.26 480h307.48c38.52 0 69.76-31.08 70.26-69.6-45.96-25.62-110.59-60.34-171.6-88.44-32.07 43.97-84.14 81-148.62 81-70.59 0-93.73-45.3-97.04-76.37-3.97-39.01 14.88-81.5 99.52-81.5 35.38 0 79.35 10.25 127.13 24.96 16.53-30.09 26.45-60.34 26.45-60.34h-178.2v-16.7h92.08v-31.24H88.28v-19.01h109.44V92.34h50.92v50.42h109.44v19.01H248.63v31.24h88.77s-15.21 46.62-38.35 90.92c48.93 16.7 100.01 36.04 148.62 52.74V102.26C447.83 63.57 416.43 32 377.74 32zM47.28 322.95c.99 20.17 10.25 53.73 69.93 53.73 52.07 0 92.58-39.68 117.87-72.9-44.63-18.68-84.48-31.41-109.44-31.41-67.45 0-79.35 33.06-78.36 50.58z\"],\n    \"amazon\": [448, 512, [], \"f270\", \"M257.2 162.7c-48.7 1.8-169.5 15.5-169.5 117.5 0 109.5 138.3 114 183.5 43.2 6.5 10.2 35.4 37.5 45.3 46.8l56.8-56S341 288.9 341 261.4V114.3C341 89 316.5 32 228.7 32 140.7 32 94 87 94 136.3l73.5 6.8c16.3-49.5 54.2-49.5 54.2-49.5 40.7-.1 35.5 29.8 35.5 69.1zm0 86.8c0 80-84.2 68-84.2 17.2 0-47.2 50.5-56.7 84.2-57.8v40.6zm136 163.5c-7.7 10-70 67-174.5 67S34.2 408.5 9.7 379c-6.8-7.7 1-11.3 5.5-8.3C88.5 415.2 203 488.5 387.7 401c7.5-3.7 13.3 2 5.5 12zm39.8 2.2c-6.5 15.8-16 26.8-21.2 31-5.5 4.5-9.5 2.7-6.5-3.8s19.3-46.5 12.7-55c-6.5-8.3-37-4.3-48-3.2-10.8 1-13 2-14-.3-2.3-5.7 21.7-15.5 37.5-17.5 15.7-1.8 41-.8 46 5.7 3.7 5.1 0 27.1-6.5 43.1z\"],\n    \"amazon-pay\": [640, 512, [], \"f42c\", \"M14 325.3c2.3-4.2 5.2-4.9 9.7-2.5 10.4 5.6 20.6 11.4 31.2 16.7a595.88 595.88 0 0 0 127.4 46.3 616.61 616.61 0 0 0 63.2 11.8 603.33 603.33 0 0 0 95 5.2c17.4-.4 34.8-1.8 52.1-3.8a603.66 603.66 0 0 0 163.3-42.8c2.9-1.2 5.9-2 9.1-1.2 6.7 1.8 9 9 4.1 13.9a70 70 0 0 1-9.6 7.4c-30.7 21.1-64.2 36.4-99.6 47.9a473.31 473.31 0 0 1-75.1 17.6 431 431 0 0 1-53.2 4.8 21.3 21.3 0 0 0-2.5.3H308a21.3 21.3 0 0 0-2.5-.3c-3.6-.2-7.2-.3-10.7-.4a426.3 426.3 0 0 1-50.4-5.3A448.4 448.4 0 0 1 164 420a443.33 443.33 0 0 1-145.6-87c-1.8-1.6-3-3.8-4.4-5.7zM172 65.1l-4.3.6a80.92 80.92 0 0 0-38 15.1c-2.4 1.7-4.6 3.5-7.1 5.4a4.29 4.29 0 0 1-.4-1.4c-.4-2.7-.8-5.5-1.3-8.2-.7-4.6-3-6.6-7.6-6.6h-11.5c-6.9 0-8.2 1.3-8.2 8.2v209.3c0 1 0 2 .1 3 .2 3 2 4.9 4.9 5 7 .1 14.1.1 21.1 0 2.9 0 4.7-2 5-5 .1-1 .1-2 .1-3v-72.4c1.1.9 1.7 1.4 2.2 1.9 17.9 14.9 38.5 19.8 61 15.4 20.4-4 34.6-16.5 43.8-34.9 7-13.9 9.9-28.7 10.3-44.1.5-17.1-1.2-33.9-8.1-49.8-8.5-19.6-22.6-32.5-43.9-36.9-3.2-.7-6.5-1-9.8-1.5-2.8-.1-5.5-.1-8.3-.1zM124.6 107a3.48 3.48 0 0 1 1.7-3.3c13.7-9.5 28.8-14.5 45.6-13.2 14.9 1.1 27.1 8.4 33.5 25.9 3.9 10.7 4.9 21.8 4.9 33 0 10.4-.8 20.6-4 30.6-6.8 21.3-22.4 29.4-42.6 28.5-14-.6-26.2-6-37.4-13.9a3.57 3.57 0 0 1-1.7-3.3c.1-14.1 0-28.1 0-42.2s.1-28 0-42.1zm205.7-41.9c-1 .1-2 .3-2.9.4a148 148 0 0 0-28.9 4.1c-6.1 1.6-12 3.8-17.9 5.8-3.6 1.2-5.4 3.8-5.3 7.7.1 3.3-.1 6.6 0 9.9.1 4.8 2.1 6.1 6.8 4.9 7.8-2 15.6-4.2 23.5-5.7 12.3-2.3 24.7-3.3 37.2-1.4 6.5 1 12.6 2.9 16.8 8.4 3.7 4.8 5.1 10.5 5.3 16.4.3 8.3.2 16.6.3 24.9a7.84 7.84 0 0 1-.2 1.4c-.5-.1-.9 0-1.3-.1a180.56 180.56 0 0 0-32-4.9c-11.3-.6-22.5.1-33.3 3.9-12.9 4.5-23.3 12.3-29.4 24.9-4.7 9.8-5.4 20.2-3.9 30.7 2 14 9 24.8 21.4 31.7 11.9 6.6 24.8 7.4 37.9 5.4 15.1-2.3 28.5-8.7 40.3-18.4a7.36 7.36 0 0 1 1.6-1.1c.6 3.8 1.1 7.4 1.8 11 .6 3.1 2.5 5.1 5.4 5.2 5.4.1 10.9.1 16.3 0a4.84 4.84 0 0 0 4.8-4.7 26.2 26.2 0 0 0 .1-2.8v-106a80 80 0 0 0-.9-12.9c-1.9-12.9-7.4-23.5-19-30.4-6.7-4-14.1-6-21.8-7.1-3.6-.5-7.2-.8-10.8-1.3-3.9.1-7.9.1-11.9.1zm35 127.7a3.33 3.33 0 0 1-1.5 3c-11.2 8.1-23.5 13.5-37.4 14.9-5.7.6-11.4.4-16.8-1.8a20.08 20.08 0 0 1-12.4-13.3 32.9 32.9 0 0 1-.1-19.4c2.5-8.3 8.4-13 16.4-15.6a61.33 61.33 0 0 1 24.8-2.2c8.4.7 16.6 2.3 25 3.4 1.6.2 2.1 1 2.1 2.6-.1 4.8 0 9.5 0 14.3s-.2 9.4-.1 14.1zm259.9 129.4c-1-5-4.8-6.9-9.1-8.3a88.42 88.42 0 0 0-21-3.9 147.32 147.32 0 0 0-39.2 1.9c-14.3 2.7-27.9 7.3-40 15.6a13.75 13.75 0 0 0-3.7 3.5 5.11 5.11 0 0 0-.5 4c.4 1.5 2.1 1.9 3.6 1.8a16.2 16.2 0 0 0 2.2-.1c7.8-.8 15.5-1.7 23.3-2.5 11.4-1.1 22.9-1.8 34.3-.9a71.64 71.64 0 0 1 14.4 2.7c5.1 1.4 7.4 5.2 7.6 10.4.4 8-1.4 15.7-3.5 23.3-4.1 15.4-10 30.3-15.8 45.1a17.6 17.6 0 0 0-1 3c-.5 2.9 1.2 4.8 4.1 4.1a10.56 10.56 0 0 0 4.8-2.5 145.91 145.91 0 0 0 12.7-13.4c12.8-16.4 20.3-35.3 24.7-55.6.8-3.6 1.4-7.3 2.1-10.9v-17.3zM493.1 199q-19.35-53.55-38.7-107.2c-2-5.7-4.2-11.3-6.3-16.9-1.1-2.9-3.2-4.8-6.4-4.8-7.6-.1-15.2-.2-22.9-.1-2.5 0-3.7 2-3.2 4.5a43.1 43.1 0 0 0 1.9 6.1q29.4 72.75 59.1 145.5c1.7 4.1 2.1 7.6.2 11.8-3.3 7.3-5.9 15-9.3 22.3-3 6.5-8 11.4-15.2 13.3a42.13 42.13 0 0 1-15.4 1.1c-2.5-.2-5-.8-7.5-1-3.4-.2-5.1 1.3-5.2 4.8q-.15 5 0 9.9c.1 5.5 2 8 7.4 8.9a108.18 108.18 0 0 0 16.9 2c17.1.4 30.7-6.5 39.5-21.4a131.63 131.63 0 0 0 9.2-18.4q35.55-89.7 70.6-179.6a26.62 26.62 0 0 0 1.6-5.5c.4-2.8-.9-4.4-3.7-4.4-6.6-.1-13.3 0-19.9 0a7.54 7.54 0 0 0-7.7 5.2c-.5 1.4-1.1 2.7-1.6 4.1l-34.8 100c-2.5 7.2-5.1 14.5-7.7 22.2-.4-1.1-.6-1.7-.9-2.4z\"],\n    \"amilia\": [448, 512, [], \"f36d\", \"M240.1 32c-61.9 0-131.5 16.9-184.2 55.4-5.1 3.1-9.1 9.2-7.2 19.4 1.1 5.1 5.1 27.4 10.2 39.6 4.1 10.2 14.2 10.2 20.3 6.1 32.5-22.3 96.5-47.7 152.3-47.7 57.9 0 58.9 28.4 58.9 73.1v38.5C203 227.7 78.2 251 46.7 264.2 11.2 280.5 16.3 357.7 16.3 376s15.2 104 124.9 104c47.8 0 113.7-20.7 153.3-42.1v25.4c0 3 2.1 8.2 6.1 9.1 3.1 1 50.7 2 59.9 2s62.5.3 66.5-.7c4.1-1 5.1-6.1 5.1-9.1V168c-.1-80.3-57.9-136-192-136zm50.2 348c-21.4 13.2-48.7 24.4-79.1 24.4-52.8 0-58.9-33.5-59-44.7 0-12.2-3-42.7 18.3-52.9 24.3-13.2 75.1-29.4 119.8-33.5z\"],\n    \"android\": [448, 512, [], \"f17b\", \"M89.6 204.5v115.8c0 15.4-12.1 27.7-27.5 27.7-15.3 0-30.1-12.4-30.1-27.7V204.5c0-15.1 14.8-27.5 30.1-27.5 15.1 0 27.5 12.4 27.5 27.5zm10.8 157c0 16.4 13.2 29.6 29.6 29.6h19.9l.3 61.1c0 36.9 55.2 36.6 55.2 0v-61.1h37.2v61.1c0 36.7 55.5 36.8 55.5 0v-61.1h20.2c16.2 0 29.4-13.2 29.4-29.6V182.1H100.4v179.4zm248-189.1H99.3c0-42.8 25.6-80 63.6-99.4l-19.1-35.3c-2.8-4.9 4.3-8 6.7-3.8l19.4 35.6c34.9-15.5 75-14.7 108.3 0L297.5 34c2.5-4.3 9.5-1.1 6.7 3.8L285.1 73c37.7 19.4 63.3 56.6 63.3 99.4zm-170.7-55.5c0-5.7-4.6-10.5-10.5-10.5-5.7 0-10.2 4.8-10.2 10.5s4.6 10.5 10.2 10.5c5.9 0 10.5-4.8 10.5-10.5zm113.4 0c0-5.7-4.6-10.5-10.2-10.5-5.9 0-10.5 4.8-10.5 10.5s4.6 10.5 10.5 10.5c5.6 0 10.2-4.8 10.2-10.5zm94.8 60.1c-15.1 0-27.5 12.1-27.5 27.5v115.8c0 15.4 12.4 27.7 27.5 27.7 15.4 0 30.1-12.4 30.1-27.7V204.5c0-15.4-14.8-27.5-30.1-27.5z\"],\n    \"angellist\": [448, 512, [], \"f209\", \"M347.1 215.4c11.7-32.6 45.4-126.9 45.4-157.1 0-26.6-15.7-48.9-43.7-48.9-44.6 0-84.6 131.7-97.1 163.1C242 144 196.6 0 156.6 0c-31.1 0-45.7 22.9-45.7 51.7 0 35.3 34.2 126.8 46.6 162-6.3-2.3-13.1-4.3-20-4.3-23.4 0-48.3 29.1-48.3 52.6 0 8.9 4.9 21.4 8 29.7-36.9 10-51.1 34.6-51.1 71.7C46 435.6 114.4 512 210.6 512c118 0 191.4-88.6 191.4-202.9 0-43.1-6.9-82-54.9-93.7zM311.7 108c4-12.3 21.1-64.3 37.1-64.3 8.6 0 10.9 8.9 10.9 16 0 19.1-38.6 124.6-47.1 148l-34-6 33.1-93.7zM142.3 48.3c0-11.9 14.5-45.7 46.3 47.1l34.6 100.3c-15.6-1.3-27.7-3-35.4 1.4-10.9-28.8-45.5-119.7-45.5-148.8zM140 244c29.3 0 67.1 94.6 67.1 107.4 0 5.1-4.9 11.4-10.6 11.4-20.9 0-76.9-76.9-76.9-97.7.1-7.7 12.7-21.1 20.4-21.1zm184.3 186.3c-29.1 32-66.3 48.6-109.7 48.6-59.4 0-106.3-32.6-128.9-88.3-17.1-43.4 3.8-68.3 20.6-68.3 11.4 0 54.3 60.3 54.3 73.1 0 4.9-7.7 8.3-11.7 8.3-16.1 0-22.4-15.5-51.1-51.4-29.7 29.7 20.5 86.9 58.3 86.9 26.1 0 43.1-24.2 38-42 3.7 0 8.3.3 11.7-.6 1.1 27.1 9.1 59.4 41.7 61.7 0-.9 2-7.1 2-7.4 0-17.4-10.6-32.6-10.6-50.3 0-28.3 21.7-55.7 43.7-71.7 8-6 17.7-9.7 27.1-13.1 9.7-3.7 20-8 27.4-15.4-1.1-11.2-5.7-21.1-16.9-21.1-27.7 0-120.6 4-120.6-39.7 0-6.7.1-13.1 17.4-13.1 32.3 0 114.3 8 138.3 29.1 18.1 16.1 24.3 113.2-31 174.7zm-98.6-126c9.7 3.1 19.7 4 29.7 6-7.4 5.4-14 12-20.3 19.1-2.8-8.5-6.2-16.8-9.4-25.1z\"],\n    \"angrycreative\": [640, 512, [], \"f36e\", \"M640 238.2l-3.2 28.2-34.5 2.3-2 18.1 34.5-2.3-3.2 28.2-34.4 2.2-2.3 20.1 34.4-2.2-3 26.1-64.7 4.1 12.7-113.2L527 365.2l-31.9 2-23.8-117.8 30.3-2 13.6 79.4 31.7-82.4 93.1-6.2zM426.8 371.5l28.3-1.8L468 249.6l-28.4 1.9-12.8 120zM162 388.1l-19.4-36-3.5 37.4-28.2 1.7 2.7-29.1c-11 18-32 34.3-56.9 35.8C23.9 399.9-3 377 .3 339.7c2.6-29.3 26.7-62.8 67.5-65.4 37.7-2.4 47.6 23.2 51.3 28.8l2.8-30.8 38.9-2.5c20.1-1.3 38.7 3.7 42.5 23.7l2.6-26.6 64.8-4.2-2.7 27.9-36.4 2.4-1.7 17.9 36.4-2.3-2.7 27.9-36.4 2.3-1.9 19.9 36.3-2.3-2.1 20.8 55-117.2 23.8-1.6L370.4 369l8.9-85.6-22.3 1.4 2.9-27.9 75-4.9-3 28-24.3 1.6-9.7 91.9-58 3.7-4.3-15.6-39.4 2.5-8 16.3-126.2 7.7zm-44.3-70.2l-26.4 1.7C84.6 307.2 76.9 303 65 303.8c-19 1.2-33.3 17.5-34.6 33.3-1.4 16 7.3 32.5 28.7 31.2 12.8-.8 21.3-8.6 28.9-18.9l27-1.7 2.7-29.8zm56.1-7.7c1.2-12.9-7.6-13.6-26.1-12.4l-2.7 28.5c14.2-.9 27.5-2.1 28.8-16.1zm21.1 70.8l5.8-60c-5 13.5-14.7 21.1-27.9 26.6l22.1 33.4zm135.4-45l-7.9-37.8-15.8 39.3 23.7-1.5zm-170.1-74.6l-4.3-17.5-39.6 2.6-8.1 18.2-31.9 2.1 57-121.9 23.9-1.6 30.7 102 9.9-104.7 27-1.8 37.8 63.6 6.5-66.6 28.5-1.9-4 41.2c7.4-13.5 22.9-44.7 63.6-47.5 40.5-2.8 52.4 29.3 53.4 30.3l3.3-32 39.3-2.7c12.7-.9 27.8.3 36.3 9.7l-4.4-11.9 32.2-2.2 12.9 43.2 23-45.7 31-2.2-43.6 78.4-4.8 44.3-28.4 1.9 4.8-44.3-15.8-43c1 22.3-9.2 40.1-32 49.6l25.2 38.8-36.4 2.4-19.2-36.8-4 38.3-28.4 1.9 3.3-31.5c-6.7 9.3-19.7 35.4-59.6 38-26.2 1.7-45.6-10.3-55.4-39.2l-4 40.3-25 1.6-37.6-63.3-6.3 66.2-56.8 3.7zm276.6-82.1c10.2-.7 17.5-2.1 21.6-4.3 4.5-2.4 7-6.4 7.6-12.1.6-5.3-.6-8.8-3.4-10.4-3.6-2.1-10.6-2.8-22.9-2l-2.9 28.8zM327.7 214c5.6 5.9 12.7 8.5 21.3 7.9 4.7-.3 9.1-1.8 13.3-4.1 5.5-3 10.6-8 15.1-14.3l-34.2 2.3 2.4-23.9 63.1-4.3 1.2-12-31.2 2.1c-4.1-3.7-7.8-6.6-11.1-8.1-4-1.7-8.1-2.8-12.2-2.5-8 .5-15.3 3.6-22 9.2-7.7 6.4-12 14.5-12.9 24.4-1.1 9.6 1.4 17.3 7.2 23.3zm-201.3 8.2l23.8-1.6-8.3-37.6-15.5 39.2z\"],\n    \"angular\": [448, 512, [], \"f420\", \"M185.7 268.1h76.2l-38.1-91.6-38.1 91.6zM223.8 32L16 106.4l31.8 275.7 176 97.9 176-97.9 31.8-275.7zM354 373.8h-48.6l-26.2-65.4H168.6l-26.2 65.4H93.7L223.8 81.5z\"],\n    \"app-store\": [512, 512, [], \"f36f\", \"M255.9 120.9l9.1-15.7c5.6-9.8 18.1-13.1 27.9-7.5 9.8 5.6 13.1 18.1 7.5 27.9l-87.5 151.5h63.3c20.5 0 32 24.1 23.1 40.8H113.8c-11.3 0-20.4-9.1-20.4-20.4 0-11.3 9.1-20.4 20.4-20.4h52l66.6-115.4-20.8-36.1c-5.6-9.8-2.3-22.2 7.5-27.9 9.8-5.6 22.2-2.3 27.9 7.5l8.9 15.7zm-78.7 218l-19.6 34c-5.6 9.8-18.1 13.1-27.9 7.5-9.8-5.6-13.1-18.1-7.5-27.9l14.6-25.2c16.4-5.1 29.8-1.2 40.4 11.6zm168.9-61.7h53.1c11.3 0 20.4 9.1 20.4 20.4 0 11.3-9.1 20.4-20.4 20.4h-29.5l19.9 34.5c5.6 9.8 2.3 22.2-7.5 27.9-9.8 5.6-22.2 2.3-27.9-7.5-33.5-58.1-58.7-101.6-75.4-130.6-17.1-29.5-4.9-59.1 7.2-69.1 13.4 23 33.4 57.7 60.1 104zM256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm216 248c0 118.7-96.1 216-216 216-118.7 0-216-96.1-216-216 0-118.7 96.1-216 216-216 118.7 0 216 96.1 216 216z\"],\n    \"app-store-ios\": [448, 512, [], \"f370\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM127 384.5c-5.5 9.6-17.8 12.8-27.3 7.3-9.6-5.5-12.8-17.8-7.3-27.3l14.3-24.7c16.1-4.9 29.3-1.1 39.6 11.4L127 384.5zm138.9-53.9H84c-11 0-20-9-20-20s9-20 20-20h51l65.4-113.2-20.5-35.4c-5.5-9.6-2.2-21.8 7.3-27.3 9.6-5.5 21.8-2.2 27.3 7.3l8.9 15.4 8.9-15.4c5.5-9.6 17.8-12.8 27.3-7.3 9.6 5.5 12.8 17.8 7.3 27.3l-85.8 148.6h62.1c20.2 0 31.5 23.7 22.7 40zm98.1 0h-29l19.6 33.9c5.5 9.6 2.2 21.8-7.3 27.3-9.6 5.5-21.8 2.2-27.3-7.3-32.9-56.9-57.5-99.7-74-128.1-16.7-29-4.8-58 7.1-67.8 13.1 22.7 32.7 56.7 58.9 102h52c11 0 20 9 20 20 0 11.1-9 20-20 20z\"],\n    \"apper\": [640, 512, [], \"f371\", \"M42.1 239.1c22.2 0 29 2.8 33.5 14.6h.8v-22.9c0-11.3-4.8-15.4-17.9-15.4-11.3 0-14.4 2.5-15.1 12.8H4.8c.3-13.9 1.5-19.1 5.8-24.4C17.9 195 29.5 192 56.7 192c33 0 47.1 5 53.9 18.9 2 4.3 4 15.6 4 23.7v76.3H76.3l1.3-19.1h-1c-5.3 15.6-13.6 20.4-35.5 20.4-30.3 0-41.1-10.1-41.1-37.3 0-25.2 12.3-35.8 42.1-35.8zm17.1 48.1c13.1 0 16.9-3 16.9-13.4 0-9.1-4.3-11.6-19.6-11.6-13.1 0-17.9 3-17.9 12.1-.1 10.4 3.7 12.9 20.6 12.9zm77.8-94.9h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.2 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3H137v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm57.9-60.7h38.3l-1.5 20.6h.8c9.1-17.1 15.9-20.9 37.5-20.9 14.4 0 24.7 3 31.5 9.1 9.8 8.6 12.8 20.4 12.8 48.1 0 30-3 43.1-12.1 52.9-6.8 7.3-16.4 10.1-33.3 10.1-20.4 0-29.2-5.5-33.8-21.2h-.8v70.3h-39.5v-169zm80.9 60.7c0-27.5-3.3-32.5-20.7-32.5-16.9 0-20.7 5-20.7 28.7 0 28 3.5 33.5 21.2 33.5 16.4 0 20.2-5.6 20.2-29.7zm53.8-3.8c0-25.4 3.3-37.8 12.3-45.8 8.8-8.1 22.2-11.3 45.1-11.3 42.8 0 55.7 12.8 55.7 55.7v11.1h-75.3c-.3 2-.3 4-.3 4.8 0 16.9 4.5 21.9 20.1 21.9 13.9 0 17.9-3 17.9-13.9h37.5v2.3c0 9.8-2.5 18.9-6.8 24.7-7.3 9.8-19.6 13.6-44.3 13.6-27.5 0-41.6-3.3-50.6-12.3-8.5-8.5-11.3-21.3-11.3-50.8zm76.4-11.6c-.3-1.8-.3-3.3-.3-3.8 0-12.3-3.3-14.6-19.6-14.6-14.4 0-17.1 3-18.1 15.1l-.3 3.3h38.3zm55.6-45.3h38.3l-1.8 19.9h.7c6.8-14.9 14.4-20.2 29.7-20.2 10.8 0 19.1 3.3 23.4 9.3 5.3 7.3 6.8 14.4 6.8 34 0 1.5 0 5 .2 9.3h-35c.3-1.8.3-3.3.3-4 0-15.4-2-19.4-10.3-19.4-6.3 0-10.8 3.3-13.1 9.3-1 3-1 4.3-1 12.3v68h-38.3V192.3z\"],\n    \"apple\": [384, 512, [], \"f179\", \"M318.7 268.7c-.2-36.7 16.4-64.4 50-84.8-18.8-26.9-47.2-41.7-84.7-44.6-35.5-2.8-74.3 20.7-88.5 20.7-15 0-49.4-19.7-76.4-19.7C63.3 141.2 4 184.8 4 273.5q0 39.3 14.4 81.2c12.8 36.7 59 126.7 107.2 125.2 25.2-.6 43-17.9 75.8-17.9 31.8 0 48.3 17.9 76.4 17.9 48.6-.7 90.4-82.5 102.6-119.3-65.2-30.7-61.7-90-61.7-91.9zm-56.6-164.2c27.3-32.4 24.8-61.9 24-72.5-24.1 1.4-52 16.4-67.9 34.9-17.5 19.8-27.8 44.3-25.6 71.9 26.1 2 49.9-11.4 69.5-34.3z\"],\n    \"apple-pay\": [640, 512, [], \"f415\", \"M116.9 158.5c-7.5 8.9-19.5 15.9-31.5 14.9-1.5-12 4.4-24.8 11.3-32.6 7.5-9.1 20.6-15.6 31.3-16.1 1.2 12.4-3.7 24.7-11.1 33.8m10.9 17.2c-17.4-1-32.3 9.9-40.5 9.9-8.4 0-21-9.4-34.8-9.1-17.9.3-34.5 10.4-43.6 26.5-18.8 32.3-4.9 80 13.3 106.3 8.9 13 19.5 27.3 33.5 26.8 13.3-.5 18.5-8.6 34.5-8.6 16.1 0 20.8 8.6 34.8 8.4 14.5-.3 23.6-13 32.5-26 10.1-14.8 14.3-29.1 14.5-29.9-.3-.3-28-10.9-28.3-42.9-.3-26.8 21.9-39.5 22.9-40.3-12.5-18.6-32-20.6-38.8-21.1m100.4-36.2v194.9h30.3v-66.6h41.9c38.3 0 65.1-26.3 65.1-64.3s-26.4-64-64.1-64h-73.2zm30.3 25.5h34.9c26.3 0 41.3 14 41.3 38.6s-15 38.8-41.4 38.8h-34.8V165zm162.2 170.9c19 0 36.6-9.6 44.6-24.9h.6v23.4h28v-97c0-28.1-22.5-46.3-57.1-46.3-32.1 0-55.9 18.4-56.8 43.6h27.3c2.3-12 13.4-19.9 28.6-19.9 18.5 0 28.9 8.6 28.9 24.5v10.8l-37.8 2.3c-35.1 2.1-54.1 16.5-54.1 41.5.1 25.2 19.7 42 47.8 42zm8.2-23.1c-16.1 0-26.4-7.8-26.4-19.6 0-12.3 9.9-19.4 28.8-20.5l33.6-2.1v11c0 18.2-15.5 31.2-36 31.2zm102.5 74.6c29.5 0 43.4-11.3 55.5-45.4L640 193h-30.8l-35.6 115.1h-.6L537.4 193h-31.6L557 334.9l-2.8 8.6c-4.6 14.6-12.1 20.3-25.5 20.3-2.4 0-7-.3-8.9-.5v23.4c1.8.4 9.3.7 11.6.7z\"],\n    \"artstation\": [512, 512, [], \"f77a\", \"M2 377.4l43 74.3A51.35 51.35 0 0 0 90.9 480h285.4l-59.2-102.6zM501.8 350L335.6 59.3A51.38 51.38 0 0 0 290.2 32h-88.4l257.3 447.6 40.7-70.5c1.9-3.2 21-29.7 2-59.1zM275 304.5l-115.5-200L44 304.5z\"],\n    \"asymmetrik\": [576, 512, [], \"f372\", \"M517.5 309.2c38.8-40 58.1-80 58.5-116.1.8-65.5-59.4-118.2-169.4-135C277.9 38.4 118.1 73.6 0 140.5 52 114 110.6 92.3 170.7 82.3c74.5-20.5 153-25.4 221.3-14.8C544.5 91.3 588.8 195 490.8 299.2c-10.2 10.8-22 21.1-35 30.6L304.9 103.4 114.7 388.9c-65.6-29.4-76.5-90.2-19.1-151.2 20.8-22.2 48.3-41.9 79.5-58.1 20-12.2 39.7-22.6 62-30.7-65.1 20.3-122.7 52.9-161.6 92.9-27.7 28.6-41.4 57.1-41.7 82.9-.5 35.1 23.4 65.1 68.4 83l-34.5 51.7h101.6l22-34.4c22.2 1 45.3 0 68.6-2.7l-22.8 37.1h135.5L340 406.3c18.6-5.3 36.9-11.5 54.5-18.7l45.9 71.8H542L468.6 349c18.5-12.1 35-25.5 48.9-39.8zm-187.6 80.5l-25-40.6-32.7 53.3c-23.4 3.5-46.7 5.1-69.2 4.4l101.9-159.3 78.7 123c-17.2 7.4-35.3 13.9-53.7 19.2z\"],\n    \"atlassian\": [512, 512, [], \"f77b\", \"M152.2 236.4c-7.7-8.2-19.7-7.7-24.8 2.8L1.6 490.2c-5 10 2.4 21.7 13.4 21.7h175c5.8.1 11-3.2 13.4-8.4 37.9-77.8 15.1-196.3-51.2-267.1zM244.4 8.1c-122.3 193.4-8.5 348.6 65 495.5 2.5 5.1 7.7 8.4 13.4 8.4H497c11.2 0 18.4-11.8 13.4-21.7 0 0-234.5-470.6-240.4-482.3-5.3-10.6-18.8-10.8-25.6.1z\"],\n    \"audible\": [640, 512, [], \"f373\", \"M640 199.9v54l-320 200L0 254v-54l320 200 320-200.1zm-194.5 72l47.1-29.4c-37.2-55.8-100.7-92.6-172.7-92.6-72 0-135.5 36.7-172.6 92.4h.3c2.5-2.3 5.1-4.5 7.7-6.7 89.7-74.4 219.4-58.1 290.2 36.3zm-220.1 18.8c16.9-11.9 36.5-18.7 57.4-18.7 34.4 0 65.2 18.4 86.4 47.6l45.4-28.4c-20.9-29.9-55.6-49.5-94.8-49.5-38.9 0-73.4 19.4-94.4 49zM103.6 161.1c131.8-104.3 318.2-76.4 417.5 62.1l.7 1 48.8-30.4C517.1 112.1 424.8 58.1 319.9 58.1c-103.5 0-196.6 53.5-250.5 135.6 9.9-10.5 22.7-23.5 34.2-32.6zm467 32.7z\"],\n    \"autoprefixer\": [640, 512, [], \"f41c\", \"M318.4 16l-161 480h77.5l25.4-81.4h119.5L405 496h77.5L318.4 16zm-40.3 341.9l41.2-130.4h1.5l40.9 130.4h-83.6zM640 405l-10-31.4L462.1 358l19.4 56.5L640 405zm-462.1-47L10 373.7 0 405l158.5 9.4 19.4-56.4z\"],\n    \"avianex\": [512, 512, [], \"f374\", \"M453.1 32h-312c-38.9 0-76.2 31.2-83.3 69.7L1.2 410.3C-5.9 448.8 19.9 480 58.9 480h312c38.9 0 76.2-31.2 83.3-69.7l56.7-308.5c7-38.6-18.8-69.8-57.8-69.8zm-58.2 347.3l-32 13.5-115.4-110c-14.7 10-29.2 19.5-41.7 27.1l22.1 64.2-17.9 12.7-40.6-61-52.4-48.1 15.7-15.4 58 31.1c9.3-10.5 20.8-22.6 32.8-34.9L203 228.9l-68.8-99.8 18.8-28.9 8.9-4.8L265 207.8l4.9 4.5c19.4-18.8 33.8-32.4 33.8-32.4 7.7-6.5 21.5-2.9 30.7 7.9 9 10.5 10.6 24.7 2.7 31.3-1.8 1.3-15.5 11.4-35.3 25.6l4.5 7.3 94.9 119.4-6.3 7.9z\"],\n    \"aviato\": [640, 512, [], \"f421\", \"M107.2 283.5l-19-41.8H36.1l-19 41.8H0l62.2-131.4 62.2 131.4h-17.2zm-45-98.1l-19.6 42.5h39.2l-19.6-42.5zm112.7 102.4l-62.2-131.4h17.1l45.1 96 45.1-96h17l-62.1 131.4zm80.6-4.3V156.4H271v127.1h-15.5zm209.1-115.6v115.6h-17.3V167.9h-41.2v-11.5h99.6v11.5h-41.1zM640 218.8c0 9.2-1.7 17.8-5.1 25.8-3.4 8-8.2 15.1-14.2 21.1-6 6-13.1 10.8-21.1 14.2-8 3.4-16.6 5.1-25.8 5.1s-17.8-1.7-25.8-5.1c-8-3.4-15.1-8.2-21.1-14.2-6-6-10.8-13-14.2-21.1-3.4-8-5.1-16.6-5.1-25.8s1.7-17.8 5.1-25.8c3.4-8 8.2-15.1 14.2-21.1 6-6 13-8.4 21.1-11.9 8-3.4 16.6-5.1 25.8-5.1s17.8 1.7 25.8 5.1c8 3.4 15.1 5.8 21.1 11.9 6 6 10.7 13.1 14.2 21.1 3.4 8 5.1 16.6 5.1 25.8zm-15.5 0c0-7.3-1.3-14-3.9-20.3-2.6-6.3-6.2-11.7-10.8-16.3-4.6-4.6-10-8.2-16.2-10.9-6.2-2.7-12.8-4-19.8-4s-13.6 1.3-19.8 4c-6.2 2.7-11.6 6.3-16.2 10.9-4.6 4.6-8.2 10-10.8 16.3-2.6 6.3-3.9 13.1-3.9 20.3 0 7.3 1.3 14 3.9 20.3 2.6 6.3 6.2 11.7 10.8 16.3 4.6 4.6 10 8.2 16.2 10.9 6.2 2.7 12.8 4 19.8 4s13.6-1.3 19.8-4c6.2-2.7 11.6-6.3 16.2-10.9 4.6-4.6 8.2-10 10.8-16.3 2.6-6.3 3.9-13.1 3.9-20.3zm-94.8 96.7v-6.3l88.9-10-242.9 13.4c.6-2.2 1.1-4.6 1.4-7.2.3-2 .5-4.2.6-6.5l64.8-8.1-64.9 1.9c0-.4-.1-.7-.1-1.1-2.8-17.2-25.5-23.7-25.5-23.7l-1.1-26.3h23.8l19 41.8h17.1L348.6 152l-62.2 131.4h17.1l19-41.8h23.6L345 268s-22.7 6.5-25.5 23.7c-.1.3-.1.7-.1 1.1l-64.9-1.9 64.8 8.1c.1 2.3.3 4.4.6 6.5.3 2.6.8 5 1.4 7.2L78.4 299.2l88.9 10v6.3c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4 0-6.2-4.6-11.3-10.5-12.2v-5.8l80.3 9v5.4c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-4.9l28.4 3.2v23.7h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9V323l38.3 4.3c8.1 11.4 19 13.6 19 13.6l-.1 6.7-5.1.2-.1 12.1h4.1l.1-5h5.2l.1 5h4.1l-.1-12.1-5.1-.2-.1-6.7s10.9-2.1 19-13.6l38.3-4.3v23.2h-5.9V360h5.9v-6.6h5v6.6h5.9v-13.8h-5.9v-23.7l28.4-3.2v4.9c-5.7 1.1-9.9 6.2-9.9 12.1 0 6.8 5.6 10.2 12.4 10.2 6.8 0 12.4-3.4 12.4-10.2 0-6-4.3-11-9.9-12.1v-5.4l80.3-9v5.8c-5.9.9-10.5 6-10.5 12.2 0 6.8 5.6 12.4 12.4 12.4 6.8 0 12.4-5.6 12.4-12.4-.2-6.3-4.7-11.4-10.7-12.3zm-200.8-87.6l19.6-42.5 19.6 42.5h-17.9l-1.7-40.3-1.7 40.3h-17.9z\"],\n    \"aws\": [640, 512, [], \"f375\", \"M180.41 203.01c-.72 22.65 10.6 32.68 10.88 39.05a8.164 8.164 0 0 1-4.1 6.27l-12.8 8.96a10.66 10.66 0 0 1-5.63 1.92c-.43-.02-8.19 1.83-20.48-25.61a78.608 78.608 0 0 1-62.61 29.45c-16.28.89-60.4-9.24-58.13-56.21-1.59-38.28 34.06-62.06 70.93-60.05 7.1.02 21.6.37 46.99 6.27v-15.62c2.69-26.46-14.7-46.99-44.81-43.91-2.4.01-19.4-.5-45.84 10.11-7.36 3.38-8.3 2.82-10.75 2.82-7.41 0-4.36-21.48-2.94-24.2 5.21-6.4 35.86-18.35 65.94-18.18a76.857 76.857 0 0 1 55.69 17.28 70.285 70.285 0 0 1 17.67 52.36l-.01 69.29zM93.99 235.4c32.43-.47 46.16-19.97 49.29-30.47 2.46-10.05 2.05-16.41 2.05-27.4-9.67-2.32-23.59-4.85-39.56-4.87-15.15-1.14-42.82 5.63-41.74 32.26-1.24 16.79 11.12 31.4 29.96 30.48zm170.92 23.05c-7.86.72-11.52-4.86-12.68-10.37l-49.8-164.65c-.97-2.78-1.61-5.65-1.92-8.58a4.61 4.61 0 0 1 3.86-5.25c.24-.04-2.13 0 22.25 0 8.78-.88 11.64 6.03 12.55 10.37l35.72 140.83 33.16-140.83c.53-3.22 2.94-11.07 12.8-10.24h17.16c2.17-.18 11.11-.5 12.68 10.37l33.42 142.63L420.98 80.1c.48-2.18 2.72-11.37 12.68-10.37h19.72c.85-.13 6.15-.81 5.25 8.58-.43 1.85 3.41-10.66-52.75 169.9-1.15 5.51-4.82 11.09-12.68 10.37h-18.69c-10.94 1.15-12.51-9.66-12.68-10.75L328.67 110.7l-32.78 136.99c-.16 1.09-1.73 11.9-12.68 10.75h-18.3zm273.48 5.63c-5.88.01-33.92-.3-57.36-12.29a12.802 12.802 0 0 1-7.81-11.91v-10.75c0-8.45 6.2-6.9 8.83-5.89 10.04 4.06 16.48 7.14 28.81 9.6 36.65 7.53 52.77-2.3 56.72-4.48 13.15-7.81 14.19-25.68 5.25-34.95-10.48-8.79-15.48-9.12-53.13-21-4.64-1.29-43.7-13.61-43.79-52.36-.61-28.24 25.05-56.18 69.52-55.95 12.67-.01 46.43 4.13 55.57 15.62 1.35 2.09 2.02 4.55 1.92 7.04v10.11c0 4.44-1.62 6.66-4.87 6.66-7.71-.86-21.39-11.17-49.16-10.75-6.89-.36-39.89.91-38.41 24.97-.43 18.96 26.61 26.07 29.7 26.89 36.46 10.97 48.65 12.79 63.12 29.58 17.14 22.25 7.9 48.3 4.35 55.44-19.08 37.49-68.42 34.44-69.26 34.42zm40.2 104.86c-70.03 51.72-171.69 79.25-258.49 79.25A469.127 469.127 0 0 1 2.83 327.46c-6.53-5.89-.77-13.96 7.17-9.47a637.37 637.37 0 0 0 316.88 84.12 630.22 630.22 0 0 0 241.59-49.55c11.78-5 21.77 7.8 10.12 16.38zm29.19-33.29c-8.96-11.52-59.28-5.38-81.81-2.69-6.79.77-7.94-5.12-1.79-9.47 40.07-28.17 105.88-20.1 113.44-10.63 7.55 9.47-2.05 75.41-39.56 106.91-5.76 4.87-11.27 2.3-8.71-4.1 8.44-21.25 27.39-68.49 18.43-80.02z\"],\n    \"bandcamp\": [496, 512, [], \"f2d5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm48.2 326.1h-181L199.9 178h181l-84.7 156.1z\"],\n    \"battle-net\": [512, 512, [], \"f835\", \"M448.61 225.62c26.87.18 35.57-7.43 38.92-12.37 12.47-16.32-7.06-47.6-52.85-71.33 17.76-33.58 30.11-63.68 36.34-85.3 3.38-11.83 1.09-19 .45-20.25-1.72 10.52-15.85 48.46-48.2 100.05-25-11.22-56.52-20.1-93.77-23.8-8.94-16.94-34.88-63.86-60.48-88.93C252.18 7.14 238.7 1.07 228.18.22h-.05c-13.83-1.55-22.67 5.85-27.4 11-17.2 18.53-24.33 48.87-25 84.07-7.24-12.35-17.17-24.63-28.5-25.93h-.18c-20.66-3.48-38.39 29.22-36 81.29-38.36 1.38-71 5.75-93 11.23-9.9 2.45-16.22 7.27-17.76 9.72 1-.38 22.4-9.22 111.56-9.22 5.22 53 29.75 101.82 26 93.19-9.73 15.4-38.24 62.36-47.31 97.7-5.87 22.88-4.37 37.61.15 47.14 5.57 12.75 16.41 16.72 23.2 18.26 25 5.71 55.38-3.63 86.7-21.14-7.53 12.84-13.9 28.51-9.06 39.34 7.31 19.65 44.49 18.66 88.44-9.45 20.18 32.18 40.07 57.94 55.7 74.12a39.79 39.79 0 0 0 8.75 7.09c5.14 3.21 8.58 3.37 8.58 3.37-8.24-6.75-34-38-62.54-91.78 22.22-16 45.65-38.87 67.47-69.27 122.82 4.6 143.29-24.76 148-31.64 14.67-19.88 3.43-57.44-57.32-93.69zm-77.85 106.22c23.81-37.71 30.34-67.77 29.45-92.33 27.86 17.57 47.18 37.58 49.06 58.83 1.14 12.93-8.1 29.12-78.51 33.5zM216.9 387.69c9.76-6.23 19.53-13.12 29.2-20.49 6.68 13.33 13.6 26.1 20.6 38.19-40.6 21.86-68.84 12.76-49.8-17.7zm215-171.35c-10.29-5.34-21.16-10.34-32.38-15.05a722.459 722.459 0 0 0 22.74-36.9c39.06 24.1 45.9 53.18 9.64 51.95zM279.18 398c-5.51-11.35-11-23.5-16.5-36.44 43.25 1.27 62.42-18.73 63.28-20.41 0 .07-25 15.64-62.53 12.25a718.78 718.78 0 0 0 85.06-84q13.06-15.31 24.93-31.11c-.36-.29-1.54-3-16.51-12-51.7 60.27-102.34 98-132.75 115.92-20.59-11.18-40.84-31.78-55.71-61.49-20-39.92-30-82.39-31.57-116.07 12.3.91 25.27 2.17 38.85 3.88-22.29 36.8-14.39 63-13.47 64.23 0-.07-.95-29.17 20.14-59.57a695.23 695.23 0 0 0 44.67 152.84c.93-.38 1.84.88 18.67-8.25-26.33-74.47-33.76-138.17-34-173.43 20-12.42 48.18-19.8 81.63-17.81 44.57 2.67 86.36 15.25 116.32 30.71q-10.69 15.66-23.33 32.47C365.63 152 339.1 145.84 337.5 146c.11 0 25.9 14.07 41.52 47.22a717.63 717.63 0 0 0-115.34-31.71 646.608 646.608 0 0 0-39.39-6.05c-.07.45-1.81 1.85-2.16 20.33C300 190.28 358.78 215.68 389.36 233c.74 23.55-6.95 51.61-25.41 79.57-24.6 37.31-56.39 67.23-84.77 85.43zm27.4-287c-44.56-1.66-73.58 7.43-94.69 20.67 2-52.3 21.31-76.38 38.21-75.28C267 52.15 305 108.55 306.58 111zm-130.65 3.1c.48 12.11 1.59 24.62 3.21 37.28-14.55-.85-28.74-1.25-42.4-1.26-.08 3.24-.12-51 24.67-49.59h.09c5.76 1.09 10.63 6.88 14.43 13.57zm-28.06 162c20.76 39.7 43.3 60.57 65.25 72.31-46.79 24.76-77.53 20-84.92 4.51-.2-.21-11.13-15.3 19.67-76.81zm210.06 74.8\"],\n    \"behance\": [576, 512, [], \"f1b4\", \"M232 237.2c31.8-15.2 48.4-38.2 48.4-74 0-70.6-52.6-87.8-113.3-87.8H0v354.4h171.8c64.4 0 124.9-30.9 124.9-102.9 0-44.5-21.1-77.4-64.7-89.7zM77.9 135.9H151c28.1 0 53.4 7.9 53.4 40.5 0 30.1-19.7 42.2-47.5 42.2h-79v-82.7zm83.3 233.7H77.9V272h84.9c34.3 0 56 14.3 56 50.6 0 35.8-25.9 47-57.6 47zm358.5-240.7H376V94h143.7v34.9zM576 305.2c0-75.9-44.4-139.2-124.9-139.2-78.2 0-131.3 58.8-131.3 135.8 0 79.9 50.3 134.7 131.3 134.7 61.3 0 101-27.6 120.1-86.3H509c-6.7 21.9-34.3 33.5-55.7 33.5-41.3 0-63-24.2-63-65.3h185.1c.3-4.2.6-8.7.6-13.2zM390.4 274c2.3-33.7 24.7-54.8 58.5-54.8 35.4 0 53.2 20.8 56.2 54.8H390.4z\"],\n    \"behance-square\": [448, 512, [], \"f1b5\", \"M186.5 293c0 19.3-14 25.4-31.2 25.4h-45.1v-52.9h46c18.6.1 30.3 7.8 30.3 27.5zm-7.7-82.3c0-17.7-13.7-21.9-28.9-21.9h-39.6v44.8H153c15.1 0 25.8-6.6 25.8-22.9zm132.3 23.2c-18.3 0-30.5 11.4-31.7 29.7h62.2c-1.7-18.5-11.3-29.7-30.5-29.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM271.7 185h77.8v-18.9h-77.8V185zm-43 110.3c0-24.1-11.4-44.9-35-51.6 17.2-8.2 26.2-17.7 26.2-37 0-38.2-28.5-47.5-61.4-47.5H68v192h93.1c34.9-.2 67.6-16.9 67.6-55.9zM380 280.5c0-41.1-24.1-75.4-67.6-75.4-42.4 0-71.1 31.8-71.1 73.6 0 43.3 27.3 73 71.1 73 33.2 0 54.7-14.9 65.1-46.8h-33.7c-3.7 11.9-18.6 18.1-30.2 18.1-22.4 0-34.1-13.1-34.1-35.3h100.2c.1-2.3.3-4.8.3-7.2z\"],\n    \"bimobject\": [448, 512, [], \"f378\", \"M416 32H32C14.4 32 0 46.4 0 64v384c0 17.6 14.4 32 32 32h384c17.6 0 32-14.4 32-32V64c0-17.6-14.4-32-32-32zm-64 257.4c0 49.4-11.4 82.6-103.8 82.6h-16.9c-44.1 0-62.4-14.9-70.4-38.8h-.9V368H96V136h64v74.7h1.1c4.6-30.5 39.7-38.8 69.7-38.8h17.3c92.4 0 103.8 33.1 103.8 82.5v35zm-64-28.9v22.9c0 21.7-3.4 33.8-38.4 33.8h-45.3c-28.9 0-44.1-6.5-44.1-35.7v-19c0-29.3 15.2-35.7 44.1-35.7h45.3c35-.2 38.4 12 38.4 33.7z\"],\n    \"bitbucket\": [512, 512, [], \"f171\", \"M22.2 32A16 16 0 0 0 6 47.8a26.35 26.35 0 0 0 .2 2.8l67.9 412.1a21.77 21.77 0 0 0 21.3 18.2h325.7a16 16 0 0 0 16-13.4L505 50.7a16 16 0 0 0-13.2-18.3 24.58 24.58 0 0 0-2.8-.2L22.2 32zm285.9 297.8h-104l-28.1-147h157.3l-25.2 147z\"],\n    \"bitcoin\": [512, 512, [], \"f379\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-141.651-35.33c4.937-32.999-20.191-50.739-54.55-62.573l11.146-44.702-27.213-6.781-10.851 43.524c-7.154-1.783-14.502-3.464-21.803-5.13l10.929-43.81-27.198-6.781-11.153 44.686c-5.922-1.349-11.735-2.682-17.377-4.084l.031-.14-37.53-9.37-7.239 29.062s20.191 4.627 19.765 4.913c11.022 2.751 13.014 10.044 12.68 15.825l-12.696 50.925c.76.194 1.744.473 2.829.907-.907-.225-1.876-.473-2.876-.713l-17.796 71.338c-1.349 3.348-4.767 8.37-12.471 6.464.271.395-19.78-4.937-19.78-4.937l-13.51 31.147 35.414 8.827c6.588 1.651 13.045 3.379 19.4 5.006l-11.262 45.213 27.182 6.781 11.153-44.733a1038.209 1038.209 0 0 0 21.687 5.627l-11.115 44.523 27.213 6.781 11.262-45.128c46.404 8.781 81.299 5.239 95.986-36.727 11.836-33.79-.589-53.281-25.004-65.991 17.78-4.098 31.174-15.792 34.747-39.949zm-62.177 87.179c-8.41 33.79-65.308 15.523-83.755 10.943l14.944-59.899c18.446 4.603 77.6 13.717 68.811 48.956zm8.417-87.667c-7.673 30.736-55.031 15.12-70.393 11.292l13.548-54.327c15.363 3.828 64.836 10.973 56.845 43.035z\"],\n    \"bity\": [496, 512, [], \"f37a\", \"M78.4 67.2C173.8-22 324.5-24 421.5 71c14.3 14.1-6.4 37.1-22.4 21.5-84.8-82.4-215.8-80.3-298.9-3.2-16.3 15.1-36.5-8.3-21.8-22.1zm98.9 418.6c19.3 5.7 29.3-23.6 7.9-30C73 421.9 9.4 306.1 37.7 194.8c5-19.6-24.9-28.1-30.2-7.1-32.1 127.4 41.1 259.8 169.8 298.1zm148.1-2c121.9-40.2 192.9-166.9 164.4-291-4.5-19.7-34.9-13.8-30 7.9 24.2 107.7-37.1 217.9-143.2 253.4-21.2 7-10.4 36 8.8 29.7zm-62.9-79l.2-71.8c0-8.2-6.6-14.8-14.8-14.8-8.2 0-14.8 6.7-14.8 14.8l-.2 71.8c0 8.2 6.6 14.8 14.8 14.8s14.8-6.6 14.8-14.8zm71-269c2.1 90.9 4.7 131.9-85.5 132.5-92.5-.7-86.9-44.3-85.5-132.5 0-21.8-32.5-19.6-32.5 0v71.6c0 69.3 60.7 90.9 118 90.1 57.3.8 118-20.8 118-90.1v-71.6c0-19.6-32.5-21.8-32.5 0z\"],\n    \"black-tie\": [448, 512, [], \"f27e\", \"M0 32v448h448V32H0zm316.5 325.2L224 445.9l-92.5-88.7 64.5-184-64.5-86.6h184.9L252 173.2l64.5 184z\"],\n    \"blackberry\": [512, 512, [], \"f37b\", \"M166 116.9c0 23.4-16.4 49.1-72.5 49.1H23.4l21-88.8h67.8c42.1 0 53.8 23.3 53.8 39.7zm126.2-39.7h-67.8L205.7 166h70.1c53.8 0 70.1-25.7 70.1-49.1.1-16.4-11.6-39.7-53.7-39.7zM88.8 208.1H21L0 296.9h70.1c56.1 0 72.5-23.4 72.5-49.1 0-16.3-11.7-39.7-53.8-39.7zm180.1 0h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1 0-16.3-11.7-39.7-53.7-39.7zm189.3-53.8h-67.8l-18.7 88.8h70.1c53.8 0 70.1-23.4 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7zm-28 137.9h-67.8L343.7 381h70.1c56.1 0 70.1-23.4 70.1-49.1 0-16.3-11.6-39.7-53.7-39.7zM240.8 346H173l-18.7 88.8h70.1c56.1 0 70.1-25.7 70.1-49.1.1-16.3-11.6-39.7-53.7-39.7z\"],\n    \"blogger\": [448, 512, [], \"f37c\", \"M162.4 196c4.8-4.9 6.2-5.1 36.4-5.1 27.2 0 28.1.1 32.1 2.1 5.8 2.9 8.3 7 8.3 13.6 0 5.9-2.4 10-7.6 13.4-2.8 1.8-4.5 1.9-31.1 2.1-16.4.1-29.5-.2-31.5-.8-10.3-2.9-14.1-17.7-6.6-25.3zm61.4 94.5c-53.9 0-55.8.2-60.2 4.1-3.5 3.1-5.7 9.4-5.1 13.9.7 4.7 4.8 10.1 9.2 12 2.2 1 14.1 1.7 56.3 1.2l47.9-.6 9.2-1.5c9-5.1 10.5-17.4 3.1-24.4-5.3-4.7-5-4.7-60.4-4.7zm223.4 130.1c-3.5 28.4-23 50.4-51.1 57.5-7.2 1.8-9.7 1.9-172.9 1.8-157.8 0-165.9-.1-172-1.8-8.4-2.2-15.6-5.5-22.3-10-5.6-3.8-13.9-11.8-17-16.4-3.8-5.6-8.2-15.3-10-22C.1 423 0 420.3 0 256.3 0 93.2 0 89.7 1.8 82.6 8.1 57.9 27.7 39 53 33.4c7.3-1.6 332.1-1.9 340-.3 21.2 4.3 37.9 17.1 47.6 36.4 7.7 15.3 7-1.5 7.3 180.6.2 115.8 0 164.5-.7 170.5zm-85.4-185.2c-1.1-5-4.2-9.6-7.7-11.5-1.1-.6-8-1.3-15.5-1.7-12.4-.6-13.8-.8-17.8-3.1-6.2-3.6-7.9-7.6-8-18.3 0-20.4-8.5-39.4-25.3-56.5-12-12.2-25.3-20.5-40.6-25.1-3.6-1.1-11.8-1.5-39.2-1.8-42.9-.5-52.5.4-67.1 6.2-27 10.7-46.3 33.4-53.4 62.4-1.3 5.4-1.6 14.2-1.9 64.3-.4 62.8 0 72.1 4 84.5 9.7 30.7 37.1 53.4 64.6 58.4 9.2 1.7 122.2 2.1 133.7.5 20.1-2.7 35.9-10.8 50.7-25.9 10.7-10.9 17.4-22.8 21.8-38.5 3.2-10.9 2.9-88.4 1.7-93.9z\"],\n    \"blogger-b\": [448, 512, [], \"f37d\", \"M446.6 222.7c-1.8-8-6.8-15.4-12.5-18.5-1.8-1-13-2.2-25-2.7-20.1-.9-22.3-1.3-28.7-5-10.1-5.9-12.8-12.3-12.9-29.5-.1-33-13.8-63.7-40.9-91.3-19.3-19.7-40.9-33-65.5-40.5-5.9-1.8-19.1-2.4-63.3-2.9-69.4-.8-84.8.6-108.4 10C45.9 59.5 14.7 96.1 3.3 142.9 1.2 151.7.7 165.8.2 246.8c-.6 101.5.1 116.4 6.4 136.5 15.6 49.6 59.9 86.3 104.4 94.3 14.8 2.7 197.3 3.3 216 .8 32.5-4.4 58-17.5 81.9-41.9 17.3-17.7 28.1-36.8 35.2-62.1 4.9-17.6 4.5-142.8 2.5-151.7zm-322.1-63.6c7.8-7.9 10-8.2 58.8-8.2 43.9 0 45.4.1 51.8 3.4 9.3 4.7 13.4 11.3 13.4 21.9 0 9.5-3.8 16.2-12.3 21.6-4.6 2.9-7.3 3.1-50.3 3.3-26.5.2-47.7-.4-50.8-1.2-16.6-4.7-22.8-28.5-10.6-40.8zm191.8 199.8l-14.9 2.4-77.5.9c-68.1.8-87.3-.4-90.9-2-7.1-3.1-13.8-11.7-14.9-19.4-1.1-7.3 2.6-17.3 8.2-22.4 7.1-6.4 10.2-6.6 97.3-6.7 89.6-.1 89.1-.1 97.6 7.8 12.1 11.3 9.5 31.2-4.9 39.4z\"],\n    \"bluetooth\": [448, 512, [], \"f293\", \"M292.6 171.1L249.7 214l-.3-86 43.2 43.1m-43.2 219.8l43.1-43.1-42.9-42.9-.2 86zM416 259.4C416 465 344.1 512 230.9 512S32 465 32 259.4 115.4 0 228.6 0 416 53.9 416 259.4zm-158.5 0l79.4-88.6L211.8 36.5v176.9L138 139.6l-27 26.9 92.7 93-92.7 93 26.9 26.9 73.8-73.8 2.3 170 127.4-127.5-83.9-88.7z\"],\n    \"bluetooth-b\": [320, 512, [], \"f294\", \"M196.48 260.023l92.626-103.333L143.125 0v206.33l-86.111-86.111-31.406 31.405 108.061 108.399L25.608 368.422l31.406 31.405 86.111-86.111L145.84 512l148.552-148.644-97.912-103.333zm40.86-102.996l-49.977 49.978-.338-100.295 50.315 50.317zM187.363 313.04l49.977 49.978-50.315 50.316.338-100.294z\"],\n    \"bootstrap\": [448, 512, [], \"f836\", \"M292.3 311.93c0 42.41-39.72 41.43-43.92 41.43h-80.89v-81.69h80.89c42.56 0 43.92 31.9 43.92 40.26zm-50.15-73.13c.67 0 38.44 1 38.44-36.31 0-15.52-3.51-35.87-38.44-35.87h-74.66v72.18h74.66zM448 106.67v298.66A74.89 74.89 0 0 1 373.33 480H74.67A74.89 74.89 0 0 1 0 405.33V106.67A74.89 74.89 0 0 1 74.67 32h298.66A74.89 74.89 0 0 1 448 106.67zM338.05 317.86c0-21.57-6.65-58.29-49.05-67.35v-.73c22.91-9.78 37.34-28.25 37.34-55.64 0-7 2-64.78-77.6-64.78h-127v261.33c128.23 0 139.87 1.68 163.6-5.71 14.21-4.42 52.71-17.98 52.71-67.12z\"],\n    \"btc\": [384, 512, [], \"f15a\", \"M310.204 242.638c27.73-14.18 45.377-39.39 41.28-81.3-5.358-57.351-52.458-76.573-114.85-81.929V0h-48.528v77.203c-12.605 0-25.525.315-38.444.63V0h-48.528v79.409c-17.842.539-38.622.276-97.37 0v51.678c38.314-.678 58.417-3.14 63.023 21.427v217.429c-2.925 19.492-18.524 16.685-53.255 16.071L3.765 443.68c88.481 0 97.37.315 97.37.315V512h48.528v-67.06c13.234.315 26.154.315 38.444.315V512h48.528v-68.005c81.299-4.412 135.647-24.894 142.895-101.467 5.671-61.446-23.32-88.862-69.326-99.89zM150.608 134.553c27.415 0 113.126-8.507 113.126 48.528 0 54.515-85.71 48.212-113.126 48.212v-96.74zm0 251.776V279.821c32.772 0 133.127-9.138 133.127 53.255-.001 60.186-100.355 53.253-133.127 53.253z\"],\n    \"buffer\": [448, 512, [], \"f837\", \"M427.84 380.67l-196.5 97.82a18.6 18.6 0 0 1-14.67 0L20.16 380.67c-4-2-4-5.28 0-7.29L67.22 350a18.65 18.65 0 0 1 14.69 0l134.76 67a18.51 18.51 0 0 0 14.67 0l134.76-67a18.62 18.62 0 0 1 14.68 0l47.06 23.43c4.05 1.96 4.05 5.24 0 7.24zm0-136.53l-47.06-23.43a18.62 18.62 0 0 0-14.68 0l-134.76 67.08a18.68 18.68 0 0 1-14.67 0L81.91 220.71a18.65 18.65 0 0 0-14.69 0l-47.06 23.43c-4 2-4 5.29 0 7.31l196.51 97.8a18.6 18.6 0 0 0 14.67 0l196.5-97.8c4.05-2.02 4.05-5.3 0-7.31zM20.16 130.42l196.5 90.29a20.08 20.08 0 0 0 14.67 0l196.51-90.29c4-1.86 4-4.89 0-6.74L231.33 33.4a19.88 19.88 0 0 0-14.67 0l-196.5 90.28c-4.05 1.85-4.05 4.88 0 6.74z\"],\n    \"buromobelexperte\": [448, 512, [], \"f37f\", \"M0 32v128h128V32H0zm120 120H8V40h112v112zm40-120v128h128V32H160zm120 120H168V40h112v112zm40-120v128h128V32H320zm120 120H328V40h112v112zM0 192v128h128V192H0zm120 120H8V200h112v112zm40-120v128h128V192H160zm120 120H168V200h112v112zm40-120v128h128V192H320zm120 120H328V200h112v112zM0 352v128h128V352H0zm120 120H8V360h112v112zm40-120v128h128V352H160zm120 120H168V360h112v112zm40-120v128h128V352H320z\"],\n    \"buysellads\": [448, 512, [], \"f20d\", \"M224 150.7l42.9 160.7h-85.8L224 150.7zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-65.3 325.3l-94.5-298.7H159.8L65.3 405.3H156l111.7-91.6 24.2 91.6h90.8z\"],\n    \"canadian-maple-leaf\": [512, 512, [], \"f785\", \"M383.8 351.7c2.5-2.5 105.2-92.4 105.2-92.4l-17.5-7.5c-10-4.9-7.4-11.5-5-17.4 2.4-7.6 20.1-67.3 20.1-67.3s-47.7 10-57.7 12.5c-7.5 2.4-10-2.5-12.5-7.5s-15-32.4-15-32.4-52.6 59.9-55.1 62.3c-10 7.5-20.1 0-17.6-10 0-10 27.6-129.6 27.6-129.6s-30.1 17.4-40.1 22.4c-7.5 5-12.6 5-17.6-5C293.5 72.3 255.9 0 255.9 0s-37.5 72.3-42.5 79.8c-5 10-10 10-17.6 5-10-5-40.1-22.4-40.1-22.4S183.3 182 183.3 192c2.5 10-7.5 17.5-17.6 10-2.5-2.5-55.1-62.3-55.1-62.3S98.1 167 95.6 172s-5 9.9-12.5 7.5C73 177 25.4 167 25.4 167s17.6 59.7 20.1 67.3c2.4 6 5 12.5-5 17.4L23 259.3s102.6 89.9 105.2 92.4c5.1 5 10 7.5 5.1 22.5-5.1 15-10.1 35.1-10.1 35.1s95.2-20.1 105.3-22.6c8.7-.9 18.3 2.5 18.3 12.5S241 512 241 512h30s-5.8-102.7-5.8-112.8 9.5-13.4 18.4-12.5c10 2.5 105.2 22.6 105.2 22.6s-5-20.1-10-35.1 0-17.5 5-22.5z\"],\n    \"cc-amazon-pay\": [576, 512, [], \"f42d\", \"M124.7 201.8c.1-11.8 0-23.5 0-35.3v-35.3c0-1.3.4-2 1.4-2.7 11.5-8 24.1-12.1 38.2-11.1 12.5.9 22.7 7 28.1 21.7 3.3 8.9 4.1 18.2 4.1 27.7 0 8.7-.7 17.3-3.4 25.6-5.7 17.8-18.7 24.7-35.7 23.9-11.7-.5-21.9-5-31.4-11.7-.9-.8-1.4-1.6-1.3-2.8zm154.9 14.6c4.6 1.8 9.3 2 14.1 1.5 11.6-1.2 21.9-5.7 31.3-12.5.9-.6 1.3-1.3 1.3-2.5-.1-3.9 0-7.9 0-11.8 0-4-.1-8 0-12 0-1.4-.4-2-1.8-2.2-7-.9-13.9-2.2-20.9-2.9-7-.6-14-.3-20.8 1.9-6.7 2.2-11.7 6.2-13.7 13.1-1.6 5.4-1.6 10.8.1 16.2 1.6 5.5 5.2 9.2 10.4 11.2zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zm-207.5 23.9c.4 1.7.9 3.4 1.6 5.1 16.5 40.6 32.9 81.3 49.5 121.9 1.4 3.5 1.7 6.4.2 9.9-2.8 6.2-4.9 12.6-7.8 18.7-2.6 5.5-6.7 9.5-12.7 11.2-4.2 1.1-8.5 1.3-12.9.9-2.1-.2-4.2-.7-6.3-.8-2.8-.2-4.2 1.1-4.3 4-.1 2.8-.1 5.6 0 8.3.1 4.6 1.6 6.7 6.2 7.5 4.7.8 9.4 1.6 14.2 1.7 14.3.3 25.7-5.4 33.1-17.9 2.9-4.9 5.6-10.1 7.7-15.4 19.8-50.1 39.5-100.3 59.2-150.5.6-1.5 1.1-3 1.3-4.6.4-2.4-.7-3.6-3.1-3.7-5.6-.1-11.1 0-16.7 0-3.1 0-5.3 1.4-6.4 4.3-.4 1.1-.9 2.3-1.3 3.4l-29.1 83.7c-2.1 6.1-4.2 12.1-6.5 18.6-.4-.9-.6-1.4-.8-1.9-10.8-29.9-21.6-59.9-32.4-89.8-1.7-4.7-3.5-9.5-5.3-14.2-.9-2.5-2.7-4-5.4-4-6.4-.1-12.8-.2-19.2-.1-2.2 0-3.3 1.6-2.8 3.7zM242.4 206c1.7 11.7 7.6 20.8 18 26.6 9.9 5.5 20.7 6.2 31.7 4.6 12.7-1.9 23.9-7.3 33.8-15.5.4-.3.8-.6 1.4-1 .5 3.2.9 6.2 1.5 9.2.5 2.6 2.1 4.3 4.5 4.4 4.6.1 9.1.1 13.7 0 2.3-.1 3.8-1.6 4-3.9.1-.8.1-1.6.1-2.3v-88.8c0-3.6-.2-7.2-.7-10.8-1.6-10.8-6.2-19.7-15.9-25.4-5.6-3.3-11.8-5-18.2-5.9-3-.4-6-.7-9.1-1.1h-10c-.8.1-1.6.3-2.5.3-8.2.4-16.3 1.4-24.2 3.5-5.1 1.3-10 3.2-15 4.9-3 1-4.5 3.2-4.4 6.5.1 2.8-.1 5.6 0 8.3.1 4.1 1.8 5.2 5.7 4.1 6.5-1.7 13.1-3.5 19.7-4.8 10.3-1.9 20.7-2.7 31.1-1.2 5.4.8 10.5 2.4 14.1 7 3.1 4 4.2 8.8 4.4 13.7.3 6.9.2 13.9.3 20.8 0 .4-.1.7-.2 1.2-.4 0-.8 0-1.1-.1-8.8-2.1-17.7-3.6-26.8-4.1-9.5-.5-18.9.1-27.9 3.2-10.8 3.8-19.5 10.3-24.6 20.8-4.1 8.3-4.6 17-3.4 25.8zM98.7 106.9v175.3c0 .8 0 1.7.1 2.5.2 2.5 1.7 4.1 4.1 4.2 5.9.1 11.8.1 17.7 0 2.5 0 4-1.7 4.1-4.1.1-.8.1-1.7.1-2.5v-60.7c.9.7 1.4 1.2 1.9 1.6 15 12.5 32.2 16.6 51.1 12.9 17.1-3.4 28.9-13.9 36.7-29.2 5.8-11.6 8.3-24.1 8.7-37 .5-14.3-1-28.4-6.8-41.7-7.1-16.4-18.9-27.3-36.7-30.9-2.7-.6-5.5-.8-8.2-1.2h-7c-1.2.2-2.4.3-3.6.5-11.7 1.4-22.3 5.8-31.8 12.7-2 1.4-3.9 3-5.9 4.5-.1-.5-.3-.8-.4-1.2-.4-2.3-.7-4.6-1.1-6.9-.6-3.9-2.5-5.5-6.4-5.6h-9.7c-5.9-.1-6.9 1-6.9 6.8zM493.6 339c-2.7-.7-5.1 0-7.6 1-43.9 18.4-89.5 30.2-136.8 35.8-14.5 1.7-29.1 2.8-43.7 3.2-26.6.7-53.2-.8-79.6-4.3-17.8-2.4-35.5-5.7-53-9.9-37-8.9-72.7-21.7-106.7-38.8-8.8-4.4-17.4-9.3-26.1-14-3.8-2.1-6.2-1.5-8.2 2.1v1.7c1.2 1.6 2.2 3.4 3.7 4.8 36 32.2 76.6 56.5 122 72.9 21.9 7.9 44.4 13.7 67.3 17.5 14 2.3 28 3.8 42.2 4.5 3 .1 6 .2 9 .4.7 0 1.4.2 2.1.3h17.7c.7-.1 1.4-.3 2.1-.3 14.9-.4 29.8-1.8 44.6-4 21.4-3.2 42.4-8.1 62.9-14.7 29.6-9.6 57.7-22.4 83.4-40.1 2.8-1.9 5.7-3.8 8-6.2 4.3-4.4 2.3-10.4-3.3-11.9zm50.4-27.7c-.8-4.2-4-5.8-7.6-7-5.7-1.9-11.6-2.8-17.6-3.3-11-.9-22-.4-32.8 1.6-12 2.2-23.4 6.1-33.5 13.1-1.2.8-2.4 1.8-3.1 3-.6.9-.7 2.3-.5 3.4.3 1.3 1.7 1.6 3 1.5.6 0 1.2 0 1.8-.1l19.5-2.1c9.6-.9 19.2-1.5 28.8-.8 4.1.3 8.1 1.2 12 2.2 4.3 1.1 6.2 4.4 6.4 8.7.3 6.7-1.2 13.1-2.9 19.5-3.5 12.9-8.3 25.4-13.3 37.8-.3.8-.7 1.7-.8 2.5-.4 2.5 1 4 3.4 3.5 1.4-.3 3-1.1 4-2.1 3.7-3.6 7.5-7.2 10.6-11.2 10.7-13.8 17-29.6 20.7-46.6.7-3 1.2-6.1 1.7-9.1.2-4.7.2-9.6.2-14.5z\"],\n    \"cc-amex\": [576, 512, [], \"f1f3\", \"M325.1 167.8c0-16.4-14.1-18.4-27.4-18.4l-39.1-.3v69.3H275v-25.1h18c18.4 0 14.5 10.3 14.8 25.1h16.6v-13.5c0-9.2-1.5-15.1-11-18.4 7.4-3 11.8-10.7 11.7-18.7zm-29.4 11.3H275v-15.3h21c5.1 0 10.7 1 10.7 7.4 0 6.6-5.3 7.9-11 7.9zM279 268.6h-52.7l-21 22.8-20.5-22.8h-66.5l-.1 69.3h65.4l21.3-23 20.4 23h32.2l.1-23.3c18.9 0 49.3 4.6 49.3-23.3 0-17.3-12.3-22.7-27.9-22.7zm-103.8 54.7h-40.6v-13.8h36.3v-14.1h-36.3v-12.5h41.7l17.9 20.2zm65.8 8.2l-25.3-28.1L241 276zm37.8-31h-21.2v-17.6h21.5c5.6 0 10.2 2.3 10.2 8.4 0 6.4-4.6 9.2-10.5 9.2zm-31.6-136.7v-14.6h-55.5v69.3h55.5v-14.3h-38.9v-13.8h37.8v-14.1h-37.8v-12.5zM576 255.4h-.2zm-194.6 31.9c0-16.4-14.1-18.7-27.1-18.7h-39.4l-.1 69.3h16.6l.1-25.3h17.6c11 0 14.8 2 14.8 13.8l-.1 11.5h16.6l.1-13.8c0-8.9-1.8-15.1-11-18.4 7.7-3.1 11.8-10.8 11.9-18.4zm-29.2 11.2h-20.7v-15.6h21c5.1 0 10.7 1 10.7 7.4 0 6.9-5.4 8.2-11 8.2zm-172.8-80v-69.3h-27.6l-19.7 47-21.7-47H83.3v65.7l-28.1-65.7H30.7L1 218.5h17.9l6.4-15.3h34.5l6.4 15.3H100v-54.2l24 54.2h14.6l24-54.2v54.2zM31.2 188.8l11.2-27.6 11.5 27.6zm477.4 158.9v-4.5c-10.8 5.6-3.9 4.5-156.7 4.5 0-25.2.1-23.9 0-25.2-1.7-.1-3.2-.1-9.4-.1 0 17.9-.1 6.8-.1 25.3h-39.6c0-12.1.1-15.3.1-29.2-10 6-22.8 6.4-34.3 6.2 0 14.7-.1 8.3-.1 23h-48.9c-5.1-5.7-2.7-3.1-15.4-17.4-3.2 3.5-12.8 13.9-16.1 17.4h-82v-92.3h83.1c5 5.6 2.8 3.1 15.5 17.2 3.2-3.5 12.2-13.4 15.7-17.2h58c9.8 0 18 1.9 24.3 5.6v-5.6c54.3 0 64.3-1.4 75.7 5.1v-5.1h78.2v5.2c11.4-6.9 19.6-5.2 64.9-5.2v5c10.3-5.9 16.6-5.2 54.3-5V80c0-26.5-21.5-48-48-48h-480c-26.5 0-48 21.5-48 48v109.8c9.4-21.9 19.7-46 23.1-53.9h39.7c4.3 10.1 1.6 3.7 9 21.1v-21.1h46c2.9 6.2 11.1 24 13.9 30 5.8-13.6 10.1-23.9 12.6-30h103c0-.1 11.5 0 11.6 0 43.7.2 53.6-.8 64.4 5.3v-5.3H363v9.3c7.6-6.1 17.9-9.3 30.7-9.3h27.6c0 .5 1.9.3 2.3.3H456c4.2 9.8 2.6 6 8.8 20.6v-20.6h43.3c4.9 8-1-1.8 11.2 18.4v-18.4h39.9v92h-41.6c-5.4-9-1.4-2.2-13.2-21.9v21.9h-52.8c-6.4-14.8-.1-.3-6.6-15.3h-19c-4.2 10-2.2 5.2-6.4 15.3h-26.8c-12.3 0-22.3-3-29.7-8.9v8.9h-66.5c-.3-13.9-.1-24.8-.1-24.8-1.8-.3-3.4-.2-9.8-.2v25.1H151.2v-11.4c-2.5 5.6-2.7 5.9-5.1 11.4h-29.5c-4-8.9-2.9-6.4-5.1-11.4v11.4H58.6c-4.2-10.1-2.2-5.3-6.4-15.3H33c-4.2 10-2.2 5.2-6.4 15.3H0V432c0 26.5 21.5 48 48 48h480.1c26.5 0 48-21.5 48-48v-90.4c-12.7 8.3-32.7 6.1-67.5 6.1zm36.3-64.5H575v-14.6h-32.9c-12.8 0-23.8 6.6-23.8 20.7 0 33 42.7 12.8 42.7 27.4 0 5.1-4.3 6.4-8.4 6.4h-32l-.1 14.8h32c8.4 0 17.6-1.8 22.5-8.9v-25.8c-10.5-13.8-39.3-1.3-39.3-13.5 0-5.8 4.6-6.5 9.2-6.5zm-57 39.8h-32.2l-.1 14.8h32.2c14.8 0 26.2-5.6 26.2-22 0-33.2-42.9-11.2-42.9-26.3 0-5.6 4.9-6.4 9.2-6.4h30.4v-14.6h-33.2c-12.8 0-23.5 6.6-23.5 20.7 0 33 42.7 12.5 42.7 27.4-.1 5.4-4.7 6.4-8.8 6.4zm-42.2-40.1v-14.3h-55.2l-.1 69.3h55.2l.1-14.3-38.6-.3v-13.8H445v-14.1h-37.8v-12.5zm-56.3-108.1c-.3.2-1.4 2.2-1.4 7.6 0 6 .9 7.7 1.1 7.9.2.1 1.1.5 3.4.5l7.3-16.9c-1.1 0-2.1-.1-3.1-.1-5.6 0-7 .7-7.3 1zm20.4-10.5h-.1zm-16.2-15.2c-23.5 0-34 12-34 35.3 0 22.2 10.2 34 33 34h19.2l6.4-15.3h34.3l6.6 15.3h33.7v-51.9l31.2 51.9h23.6v-69h-16.9v48.1l-29.1-48.1h-25.3v65.4l-27.9-65.4h-24.8l-23.5 54.5h-7.4c-13.3 0-16.1-8.1-16.1-19.9 0-23.8 15.7-20 33.1-19.7v-15.2zm42.1 12.1l11.2 27.6h-22.8zm-101.1-12v69.3h16.9v-69.3z\"],\n    \"cc-apple-pay\": [576, 512, [], \"f416\", \"M302.2 218.4c0 17.2-10.5 27.1-29 27.1h-24.3v-54.2h24.4c18.4 0 28.9 9.8 28.9 27.1zm47.5 62.6c0 8.3 7.2 13.7 18.5 13.7 14.4 0 25.2-9.1 25.2-21.9v-7.7l-23.5 1.5c-13.3.9-20.2 5.8-20.2 14.4zM576 79v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM127.8 197.2c8.4.7 16.8-4.2 22.1-10.4 5.2-6.4 8.6-15 7.7-23.7-7.4.3-16.6 4.9-21.9 11.3-4.8 5.5-8.9 14.4-7.9 22.8zm60.6 74.5c-.2-.2-19.6-7.6-19.8-30-.2-18.7 15.3-27.7 16-28.2-8.8-13-22.4-14.4-27.1-14.7-12.2-.7-22.6 6.9-28.4 6.9-5.9 0-14.7-6.6-24.3-6.4-12.5.2-24.2 7.3-30.5 18.6-13.1 22.6-3.4 56 9.3 74.4 6.2 9.1 13.7 19.1 23.5 18.7 9.3-.4 13-6 24.2-6 11.3 0 14.5 6 24.3 5.9 10.2-.2 16.5-9.1 22.8-18.2 6.9-10.4 9.8-20.4 10-21zm135.4-53.4c0-26.6-18.5-44.8-44.9-44.8h-51.2v136.4h21.2v-46.6h29.3c26.8 0 45.6-18.4 45.6-45zm90 23.7c0-19.7-15.8-32.4-40-32.4-22.5 0-39.1 12.9-39.7 30.5h19.1c1.6-8.4 9.4-13.9 20-13.9 13 0 20.2 6 20.2 17.2v7.5l-26.4 1.6c-24.6 1.5-37.9 11.6-37.9 29.1 0 17.7 13.7 29.4 33.4 29.4 13.3 0 25.6-6.7 31.2-17.4h.4V310h19.6v-68zM516 210.9h-21.5l-24.9 80.6h-.4l-24.9-80.6H422l35.9 99.3-1.9 6c-3.2 10.2-8.5 14.2-17.9 14.2-1.7 0-4.9-.2-6.2-.3v16.4c1.2.4 6.5.5 8.1.5 20.7 0 30.4-7.9 38.9-31.8L516 210.9z\"],\n    \"cc-diners-club\": [576, 512, [], \"f24c\", \"M239.7 79.9c-96.9 0-175.8 78.6-175.8 175.8 0 96.9 78.9 175.8 175.8 175.8 97.2 0 175.8-78.9 175.8-175.8 0-97.2-78.6-175.8-175.8-175.8zm-39.9 279.6c-41.7-15.9-71.4-56.4-71.4-103.8s29.7-87.9 71.4-104.1v207.9zm79.8.3V151.6c41.7 16.2 71.4 56.7 71.4 104.1s-29.7 87.9-71.4 104.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM329.7 448h-90.3c-106.2 0-193.8-85.5-193.8-190.2C45.6 143.2 133.2 64 239.4 64h90.3c105 0 200.7 79.2 200.7 193.8 0 104.7-95.7 190.2-200.7 190.2z\"],\n    \"cc-discover\": [576, 512, [], \"f1f2\", \"M520.4 196.1c0-7.9-5.5-12.1-15.6-12.1h-4.9v24.9h4.7c10.3 0 15.8-4.4 15.8-12.8zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-44.1 138.9c22.6 0 52.9-4.1 52.9 24.4 0 12.6-6.6 20.7-18.7 23.2l25.8 34.4h-19.6l-22.2-32.8h-2.2v32.8h-16zm-55.9.1h45.3v14H444v18.2h28.3V217H444v22.2h29.3V253H428zm-68.7 0l21.9 55.2 22.2-55.2h17.5l-35.5 84.2h-8.6l-35-84.2zm-55.9-3c24.7 0 44.6 20 44.6 44.6 0 24.7-20 44.6-44.6 44.6-24.7 0-44.6-20-44.6-44.6 0-24.7 20-44.6 44.6-44.6zm-49.3 6.1v19c-20.1-20.1-46.8-4.7-46.8 19 0 25 27.5 38.5 46.8 19.2v19c-29.7 14.3-63.3-5.7-63.3-38.2 0-31.2 33.1-53 63.3-38zm-97.2 66.3c11.4 0 22.4-15.3-3.3-24.4-15-5.5-20.2-11.4-20.2-22.7 0-23.2 30.6-31.4 49.7-14.3l-8.4 10.8c-10.4-11.6-24.9-6.2-24.9 2.5 0 4.4 2.7 6.9 12.3 10.3 18.2 6.6 23.6 12.5 23.6 25.6 0 29.5-38.8 37.4-56.6 11.3l10.3-9.9c3.7 7.1 9.9 10.8 17.5 10.8zM55.4 253H32v-82h23.4c26.1 0 44.1 17 44.1 41.1 0 18.5-13.2 40.9-44.1 40.9zm67.5 0h-16v-82h16zM544 433c0 8.2-6.8 15-15 15H128c189.6-35.6 382.7-139.2 416-160zM74.1 191.6c-5.2-4.9-11.6-6.6-21.9-6.6H48v54.2h4.2c10.3 0 17-2 21.9-6.4 5.7-5.2 8.9-12.8 8.9-20.7s-3.2-15.5-8.9-20.5z\"],\n    \"cc-jcb\": [576, 512, [], \"f24b\", \"M431.5 244.3V212c41.2 0 38.5.2 38.5.2 7.3 1.3 13.3 7.3 13.3 16 0 8.8-6 14.5-13.3 15.8-1.2.4-3.3.3-38.5.3zm42.8 20.2c-2.8-.7-3.3-.5-42.8-.5v35c39.6 0 40 .2 42.8-.5 7.5-1.5 13.5-8 13.5-17 0-8.7-6-15.5-13.5-17zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM182 192.3h-57c0 67.1 10.7 109.7-35.8 109.7-19.5 0-38.8-5.7-57.2-14.8v28c30 8.3 68 8.3 68 8.3 97.9 0 82-47.7 82-131.2zm178.5 4.5c-63.4-16-165-14.9-165 59.3 0 77.1 108.2 73.6 165 59.2V287C312.9 311.7 253 309 253 256s59.8-55.6 107.5-31.2v-28zM544 286.5c0-18.5-16.5-30.5-38-32v-.8c19.5-2.7 30.3-15.5 30.3-30.2 0-19-15.7-30-37-31 0 0 6.3-.3-120.3-.3v127.5h122.7c24.3.1 42.3-12.9 42.3-33.2z\"],\n    \"cc-mastercard\": [576, 512, [], \"f1f1\", \"M482.9 410.3c0 6.8-4.6 11.7-11.2 11.7-6.8 0-11.2-5.2-11.2-11.7 0-6.5 4.4-11.7 11.2-11.7 6.6 0 11.2 5.2 11.2 11.7zm-310.8-11.7c-7.1 0-11.2 5.2-11.2 11.7 0 6.5 4.1 11.7 11.2 11.7 6.5 0 10.9-4.9 10.9-11.7-.1-6.5-4.4-11.7-10.9-11.7zm117.5-.3c-5.4 0-8.7 3.5-9.5 8.7h19.1c-.9-5.7-4.4-8.7-9.6-8.7zm107.8.3c-6.8 0-10.9 5.2-10.9 11.7 0 6.5 4.1 11.7 10.9 11.7 6.8 0 11.2-4.9 11.2-11.7 0-6.5-4.4-11.7-11.2-11.7zm105.9 26.1c0 .3.3.5.3 1.1 0 .3-.3.5-.3 1.1-.3.3-.3.5-.5.8-.3.3-.5.5-1.1.5-.3.3-.5.3-1.1.3-.3 0-.5 0-1.1-.3-.3 0-.5-.3-.8-.5-.3-.3-.5-.5-.5-.8-.3-.5-.3-.8-.3-1.1 0-.5 0-.8.3-1.1 0-.5.3-.8.5-1.1.3-.3.5-.3.8-.5.5-.3.8-.3 1.1-.3.5 0 .8 0 1.1.3.5.3.8.3 1.1.5s.2.6.5 1.1zm-2.2 1.4c.5 0 .5-.3.8-.3.3-.3.3-.5.3-.8 0-.3 0-.5-.3-.8-.3 0-.5-.3-1.1-.3h-1.6v3.5h.8V426h.3l1.1 1.4h.8l-1.1-1.3zM576 81v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V81c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM64 220.6c0 76.5 62.1 138.5 138.5 138.5 27.2 0 53.9-8.2 76.5-23.1-72.9-59.3-72.4-171.2 0-230.5-22.6-15-49.3-23.1-76.5-23.1-76.4-.1-138.5 62-138.5 138.2zm224 108.8c70.5-55 70.2-162.2 0-217.5-70.2 55.3-70.5 162.6 0 217.5zm-142.3 76.3c0-8.7-5.7-14.4-14.7-14.7-4.6 0-9.5 1.4-12.8 6.5-2.4-4.1-6.5-6.5-12.2-6.5-3.8 0-7.6 1.4-10.6 5.4V392h-8.2v36.7h8.2c0-18.9-2.5-30.2 9-30.2 10.2 0 8.2 10.2 8.2 30.2h7.9c0-18.3-2.5-30.2 9-30.2 10.2 0 8.2 10 8.2 30.2h8.2v-23zm44.9-13.7h-7.9v4.4c-2.7-3.3-6.5-5.4-11.7-5.4-10.3 0-18.2 8.2-18.2 19.3 0 11.2 7.9 19.3 18.2 19.3 5.2 0 9-1.9 11.7-5.4v4.6h7.9V392zm40.5 25.6c0-15-22.9-8.2-22.9-15.2 0-5.7 11.9-4.8 18.5-1.1l3.3-6.5c-9.4-6.1-30.2-6-30.2 8.2 0 14.3 22.9 8.3 22.9 15 0 6.3-13.5 5.8-20.7.8l-3.5 6.3c11.2 7.6 32.6 6 32.6-7.5zm35.4 9.3l-2.2-6.8c-3.8 2.1-12.2 4.4-12.2-4.1v-16.6h13.1V392h-13.1v-11.2h-8.2V392h-7.6v7.3h7.6V416c0 17.6 17.3 14.4 22.6 10.9zm13.3-13.4h27.5c0-16.2-7.4-22.6-17.4-22.6-10.6 0-18.2 7.9-18.2 19.3 0 20.5 22.6 23.9 33.8 14.2l-3.8-6c-7.8 6.4-19.6 5.8-21.9-4.9zm59.1-21.5c-4.6-2-11.6-1.8-15.2 4.4V392h-8.2v36.7h8.2V408c0-11.6 9.5-10.1 12.8-8.4l2.4-7.6zm10.6 18.3c0-11.4 11.6-15.1 20.7-8.4l3.8-6.5c-11.6-9.1-32.7-4.1-32.7 15 0 19.8 22.4 23.8 32.7 15l-3.8-6.5c-9.2 6.5-20.7 2.6-20.7-8.6zm66.7-18.3H408v4.4c-8.3-11-29.9-4.8-29.9 13.9 0 19.2 22.4 24.7 29.9 13.9v4.6h8.2V392zm33.7 0c-2.4-1.2-11-2.9-15.2 4.4V392h-7.9v36.7h7.9V408c0-11 9-10.3 12.8-8.4l2.4-7.6zm40.3-14.9h-7.9v19.3c-8.2-10.9-29.9-5.1-29.9 13.9 0 19.4 22.5 24.6 29.9 13.9v4.6h7.9v-51.7zm7.6-75.1v4.6h.8V302h1.9v-.8h-4.6v.8h1.9zm6.6 123.8c0-.5 0-1.1-.3-1.6-.3-.3-.5-.8-.8-1.1-.3-.3-.8-.5-1.1-.8-.5 0-1.1-.3-1.6-.3-.3 0-.8.3-1.4.3-.5.3-.8.5-1.1.8-.5.3-.8.8-.8 1.1-.3.5-.3 1.1-.3 1.6 0 .3 0 .8.3 1.4 0 .3.3.8.8 1.1.3.3.5.5 1.1.8.5.3 1.1.3 1.4.3.5 0 1.1 0 1.6-.3.3-.3.8-.5 1.1-.8.3-.3.5-.8.8-1.1.3-.6.3-1.1.3-1.4zm3.2-124.7h-1.4l-1.6 3.5-1.6-3.5h-1.4v5.4h.8v-4.1l1.6 3.5h1.1l1.4-3.5v4.1h1.1v-5.4zm4.4-80.5c0-76.2-62.1-138.3-138.5-138.3-27.2 0-53.9 8.2-76.5 23.1 72.1 59.3 73.2 171.5 0 230.5 22.6 15 49.5 23.1 76.5 23.1 76.4.1 138.5-61.9 138.5-138.4z\"],\n    \"cc-paypal\": [576, 512, [], \"f1f4\", \"M186.3 258.2c0 12.2-9.7 21.5-22 21.5-9.2 0-16-5.2-16-15 0-12.2 9.5-22 21.7-22 9.3 0 16.3 5.7 16.3 15.5zM80.5 209.7h-4.7c-1.5 0-3 1-3.2 2.7l-4.3 26.7 8.2-.3c11 0 19.5-1.5 21.5-14.2 2.3-13.4-6.2-14.9-17.5-14.9zm284 0H360c-1.8 0-3 1-3.2 2.7l-4.2 26.7 8-.3c13 0 22-3 22-18-.1-10.6-9.6-11.1-18.1-11.1zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM128.3 215.4c0-21-16.2-28-34.7-28h-40c-2.5 0-5 2-5.2 4.7L32 294.2c-.3 2 1.2 4 3.2 4h19c2.7 0 5.2-2.9 5.5-5.7l4.5-26.6c1-7.2 13.2-4.7 18-4.7 28.6 0 46.1-17 46.1-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.2 8.2-5.8-8.5-14.2-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9 0 20.2-4.9 26.5-11.9-.5 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H200c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm40.5 97.9l63.7-92.6c.5-.5.5-1 .5-1.7 0-1.7-1.5-3.5-3.2-3.5h-19.2c-1.7 0-3.5 1-4.5 2.5l-26.5 39-11-37.5c-.8-2.2-3-4-5.5-4h-18.7c-1.7 0-3.2 1.8-3.2 3.5 0 1.2 19.5 56.8 21.2 62.1-2.7 3.8-20.5 28.6-20.5 31.6 0 1.8 1.5 3.2 3.2 3.2h19.2c1.8-.1 3.5-1.1 4.5-2.6zm159.3-106.7c0-21-16.2-28-34.7-28h-39.7c-2.7 0-5.2 2-5.5 4.7l-16.2 102c-.2 2 1.3 4 3.2 4h20.5c2 0 3.5-1.5 4-3.2l4.5-29c1-7.2 13.2-4.7 18-4.7 28.4 0 45.9-17 45.9-45.8zm84.2 8.8h-19c-3.8 0-4 5.5-4.3 8.2-5.5-8.5-14-10-23.7-10-24.5 0-43.2 21.5-43.2 45.2 0 19.5 12.2 32.2 31.7 32.2 9.3 0 20.5-4.9 26.5-11.9-.3 1.5-1 4.7-1 6.2 0 2.3 1 4 3.2 4H484c2.7 0 5-2.9 5.5-5.7l10.2-64.3c.3-1.9-1.2-3.9-3.2-3.9zm47.5-33.3c0-2-1.5-3.5-3.2-3.5h-18.5c-1.5 0-3 1.2-3.2 2.7l-16.2 104-.3.5c0 1.8 1.5 3.5 3.5 3.5h16.5c2.5 0 5-2.9 5.2-5.7L544 191.2v-.3zm-90 51.8c-12.2 0-21.7 9.7-21.7 22 0 9.7 7 15 16.2 15 12 0 21.7-9.2 21.7-21.5.1-9.8-6.9-15.5-16.2-15.5z\"],\n    \"cc-stripe\": [576, 512, [], \"f1f5\", \"M492.4 220.8c-8.9 0-18.7 6.7-18.7 22.7h36.7c0-16-9.3-22.7-18-22.7zM375 223.4c-8.2 0-13.3 2.9-17 7l.2 52.8c3.5 3.7 8.5 6.7 16.8 6.7 13.1 0 21.9-14.3 21.9-33.4 0-18.6-9-33.2-21.9-33.1zM528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM122.2 281.1c0 25.6-20.3 40.1-49.9 40.3-12.2 0-25.6-2.4-38.8-8.1v-33.9c12 6.4 27.1 11.3 38.9 11.3 7.9 0 13.6-2.1 13.6-8.7 0-17-54-10.6-54-49.9 0-25.2 19.2-40.2 48-40.2 11.8 0 23.5 1.8 35.3 6.5v33.4c-10.8-5.8-24.5-9.1-35.3-9.1-7.5 0-12.1 2.2-12.1 7.7 0 16 54.3 8.4 54.3 50.7zm68.8-56.6h-27V275c0 20.9 22.5 14.4 27 12.6v28.9c-4.7 2.6-13.3 4.7-24.9 4.7-21.1 0-36.9-15.5-36.9-36.5l.2-113.9 34.7-7.4v30.8H191zm74 2.4c-4.5-1.5-18.7-3.6-27.1 7.4v84.4h-35.5V194.2h30.7l2.2 10.5c8.3-15.3 24.9-12.2 29.6-10.5h.1zm44.1 91.8h-35.7V194.2h35.7zm0-142.9l-35.7 7.6v-28.9l35.7-7.6zm74.1 145.5c-12.4 0-20-5.3-25.1-9l-.1 40.2-35.5 7.5V194.2h31.3l1.8 8.8c4.9-4.5 13.9-11.1 27.8-11.1 24.9 0 48.4 22.5 48.4 63.8 0 45.1-23.2 65.5-48.6 65.6zm160.4-51.5h-69.5c1.6 16.6 13.8 21.5 27.6 21.5 14.1 0 25.2-3 34.9-7.9V312c-9.7 5.3-22.4 9.2-39.4 9.2-34.6 0-58.8-21.7-58.8-64.5 0-36.2 20.5-64.9 54.3-64.9 33.7 0 51.3 28.7 51.3 65.1 0 3.5-.3 10.9-.4 12.9z\"],\n    \"cc-visa\": [576, 512, [], \"f1f0\", \"M470.1 231.3s7.6 37.2 9.3 45H446c3.3-8.9 16-43.5 16-43.5-.2.3 3.3-9.1 5.3-14.9l2.8 13.4zM576 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48zM152.5 331.2L215.7 176h-42.5l-39.3 106-4.3-21.5-14-71.4c-2.3-9.9-9.4-12.7-18.2-13.1H32.7l-.7 3.1c15.8 4 29.9 9.8 42.2 17.1l35.8 135h42.5zm94.4.2L272.1 176h-40.2l-25.1 155.4h40.1zm139.9-50.8c.2-17.7-10.6-31.2-33.7-42.3-14.1-7.1-22.7-11.9-22.7-19.2.2-6.6 7.3-13.4 23.1-13.4 13.1-.3 22.7 2.8 29.9 5.9l3.6 1.7 5.5-33.6c-7.9-3.1-20.5-6.6-36-6.6-39.7 0-67.6 21.2-67.8 51.4-.3 22.3 20 34.7 35.2 42.2 15.5 7.6 20.8 12.6 20.8 19.3-.2 10.4-12.6 15.2-24.1 15.2-16 0-24.6-2.5-37.7-8.3l-5.3-2.5-5.6 34.9c9.4 4.3 26.8 8.1 44.8 8.3 42.2.1 69.7-20.8 70-53zM528 331.4L495.6 176h-31.1c-9.6 0-16.9 2.8-21 12.9l-59.7 142.5H426s6.9-19.2 8.4-23.3H486c1.2 5.5 4.8 23.3 4.8 23.3H528z\"],\n    \"centercode\": [512, 512, [], \"f380\", \"M329.2 268.6c-3.8 35.2-35.4 60.6-70.6 56.8-35.2-3.8-60.6-35.4-56.8-70.6 3.8-35.2 35.4-60.6 70.6-56.8 35.1 3.8 60.6 35.4 56.8 70.6zm-85.8 235.1C96.7 496-8.2 365.5 10.1 224.3c11.2-86.6 65.8-156.9 139.1-192 161-77.1 349.7 37.4 354.7 216.6 4.1 147-118.4 262.2-260.5 254.8zm179.9-180c27.9-118-160.5-205.9-237.2-234.2-57.5 56.3-69.1 188.6-33.8 344.4 68.8 15.8 169.1-26.4 271-110.2z\"],\n    \"centos\": [448, 512, [], \"f789\", \"M289.6 97.5l31.6 31.7-76.3 76.5V97.5zm-162.4 31.7l76.3 76.5V97.5h-44.7zm41.5-41.6h44.7v127.9l10.8 10.8 10.8-10.8V87.6h44.7L224.2 32zm26.2 168.1l-10.8-10.8H55.5v-44.8L0 255.7l55.5 55.6v-44.8h128.6l10.8-10.8zm79.3-20.7h107.9v-44.8l-31.6-31.7zm173.3 20.7L392 200.1v44.8H264.3l-10.8 10.8 10.8 10.8H392v44.8l55.5-55.6zM65.4 176.2l32.5-31.7 90.3 90.5h15.3v-15.3l-90.3-90.5 31.6-31.7H65.4zm316.7-78.7h-78.5l31.6 31.7-90.3 90.5V235h15.3l90.3-90.5 31.6 31.7zM203.5 413.9V305.8l-76.3 76.5 31.6 31.7h44.7zM65.4 235h108.8l-76.3-76.5-32.5 31.7zm316.7 100.2l-31.6 31.7-90.3-90.5h-15.3v15.3l90.3 90.5-31.6 31.7h78.5zm0-58.8H274.2l76.3 76.5 31.6-31.7zm-60.9 105.8l-76.3-76.5v108.1h44.7zM97.9 352.9l76.3-76.5H65.4v44.8zm181.8 70.9H235V295.9l-10.8-10.8-10.8 10.8v127.9h-44.7l55.5 55.6zm-166.5-41.6l90.3-90.5v-15.3h-15.3l-90.3 90.5-32.5-31.7v78.7h79.4z\"],\n    \"chrome\": [496, 512, [], \"f268\", \"M131.5 217.5L55.1 100.1c47.6-59.2 119-91.8 192-92.1 42.3-.3 85.5 10.5 124.8 33.2 43.4 25.2 76.4 61.4 97.4 103L264 133.4c-58.1-3.4-113.4 29.3-132.5 84.1zm32.9 38.5c0 46.2 37.4 83.6 83.6 83.6s83.6-37.4 83.6-83.6-37.4-83.6-83.6-83.6-83.6 37.3-83.6 83.6zm314.9-89.2L339.6 174c37.9 44.3 38.5 108.2 6.6 157.2L234.1 503.6c46.5 2.5 94.4-7.7 137.8-32.9 107.4-62 150.9-192 107.4-303.9zM133.7 303.6L40.4 120.1C14.9 159.1 0 205.9 0 256c0 124 90.8 226.7 209.5 244.9l63.7-124.8c-57.6 10.8-113.2-20.8-139.5-72.5z\"],\n    \"chromecast\": [512, 512, [], \"f838\", \"M447.83 64H64a42.72 42.72 0 0 0-42.72 42.72v63.92H64v-63.92h383.83v298.56H298.64V448H448a42.72 42.72 0 0 0 42.72-42.72V106.72A42.72 42.72 0 0 0 448 64zM21.28 383.58v63.92h63.91a63.91 63.91 0 0 0-63.91-63.92zm0-85.28V341a106.63 106.63 0 0 1 106.64 106.66v.34h42.72a149.19 149.19 0 0 0-149-149.36h-.33zm0-85.27v42.72c106-.1 192 85.75 192.08 191.75v.5h42.72c-.46-129.46-105.34-234.27-234.8-234.64z\"],\n    \"cloudscale\": [448, 512, [], \"f383\", \"M318.1 154l-9.4 7.6c-22.5-19.3-51.5-33.6-83.3-33.6C153.8 128 96 188.8 96 260.3c0 6.6.4 13.1 1.4 19.4-2-56 41.8-97.4 92.6-97.4 24.2 0 46.2 9.4 62.6 24.7l-25.2 20.4c-8.3-.9-16.8 1.8-23.1 8.1-11.1 11-11.1 28.9 0 40 11.1 11 28.9 11 40 0 6.3-6.3 9-14.9 8.1-23.1l75.2-88.8c6.3-6.5-3.3-15.9-9.5-9.6zm-83.8 111.5c-5.6 5.5-14.6 5.5-20.2 0-5.6-5.6-5.6-14.6 0-20.2s14.6-5.6 20.2 0 5.6 14.7 0 20.2zM224 32C100.5 32 0 132.5 0 256s100.5 224 224 224 224-100.5 224-224S347.5 32 224 32zm0 384c-88.2 0-160-71.8-160-160S135.8 96 224 96s160 71.8 160 160-71.8 160-160 160z\"],\n    \"cloudsmith\": [332, 512, [], \"f384\", \"M332.5 419.9c0 46.4-37.6 84.1-84 84.1s-84-37.7-84-84.1 37.6-84 84-84 84 37.6 84 84zm-84-243.9c46.4 0 80-37.6 80-84s-33.6-84-80-84-88 37.6-88 84-29.6 76-76 76-84 41.6-84 88 37.6 80 84 80 84-33.6 84-80 33.6-80 80-80z\"],\n    \"cloudversify\": [616, 512, [], \"f385\", \"M148.6 304c8.2 68.5 67.4 115.5 146 111.3 51.2 43.3 136.8 45.8 186.4-5.6 69.2 1.1 118.5-44.6 131.5-99.5 14.8-62.5-18.2-132.5-92.1-155.1-33-88.1-131.4-101.5-186.5-85-57.3 17.3-84.3 53.2-99.3 109.7-7.8 2.7-26.5 8.9-45 24.1 11.7 0 15.2 8.9 15.2 19.5v20.4c0 10.7-8.7 19.5-19.5 19.5h-20.2c-10.7 0-19.5-6-19.5-16.7V240H98.8C95 240 88 244.3 88 251.9v40.4c0 6.4 5.3 11.8 11.7 11.8h48.9zm227.4 8c-10.7 46.3 21.7 72.4 55.3 86.8C324.1 432.6 259.7 348 296 288c-33.2 21.6-33.7 71.2-29.2 92.9-17.9-12.4-53.8-32.4-57.4-79.8-3-39.9 21.5-75.7 57-93.9C297 191.4 369.9 198.7 400 248c-14.1-48-53.8-70.1-101.8-74.8 30.9-30.7 64.4-50.3 114.2-43.7 69.8 9.3 133.2 82.8 67.7 150.5 35-16.3 48.7-54.4 47.5-76.9l10.5 19.6c11.8 22 15.2 47.6 9.4 72-9.2 39-40.6 68.8-79.7 76.5-32.1 6.3-83.1-5.1-91.8-59.2zM128 208H88.2c-8.9 0-16.2-7.3-16.2-16.2v-39.6c0-8.9 7.3-16.2 16.2-16.2H128c8.9 0 16.2 7.3 16.2 16.2v39.6c0 8.9-7.3 16.2-16.2 16.2zM10.1 168C4.5 168 0 163.5 0 157.9v-27.8c0-5.6 4.5-10.1 10.1-10.1h27.7c5.5 0 10.1 4.5 10.1 10.1v27.8c0 5.6-4.5 10.1-10.1 10.1H10.1zM168 142.7v-21.4c0-5.1 4.2-9.3 9.3-9.3h21.4c5.1 0 9.3 4.2 9.3 9.3v21.4c0 5.1-4.2 9.3-9.3 9.3h-21.4c-5.1 0-9.3-4.2-9.3-9.3zM56 235.5v25c0 6.3-5.1 11.5-11.4 11.5H19.4C13.1 272 8 266.8 8 260.5v-25c0-6.3 5.1-11.5 11.4-11.5h25.1c6.4 0 11.5 5.2 11.5 11.5z\"],\n    \"codepen\": [512, 512, [], \"f1cb\", \"M502.285 159.704l-234-156c-7.987-4.915-16.511-4.96-24.571 0l-234 156C3.714 163.703 0 170.847 0 177.989v155.999c0 7.143 3.714 14.286 9.715 18.286l234 156.022c7.987 4.915 16.511 4.96 24.571 0l234-156.022c6-3.999 9.715-11.143 9.715-18.286V177.989c-.001-7.142-3.715-14.286-9.716-18.285zM278 63.131l172.286 114.858-76.857 51.429L278 165.703V63.131zm-44 0v102.572l-95.429 63.715-76.857-51.429L234 63.131zM44 219.132l55.143 36.857L44 292.846v-73.714zm190 229.715L61.714 333.989l76.857-51.429L234 346.275v102.572zm22-140.858l-77.715-52 77.715-52 77.715 52-77.715 52zm22 140.858V346.275l95.429-63.715 76.857 51.429L278 448.847zm190-156.001l-55.143-36.857L468 219.132v73.714z\"],\n    \"codiepie\": [472, 512, [], \"f284\", \"M422.5 202.9c30.7 0 33.5 53.1-.3 53.1h-10.8v44.3h-26.6v-97.4h37.7zM472 352.6C429.9 444.5 350.4 504 248 504 111 504 0 393 0 256S111 8 248 8c97.4 0 172.8 53.7 218.2 138.4l-186 108.8L472 352.6zm-38.5 12.5l-60.3-30.7c-27.1 44.3-70.4 71.4-122.4 71.4-82.5 0-149.2-66.7-149.2-148.9 0-82.5 66.7-149.2 149.2-149.2 48.4 0 88.9 23.5 116.9 63.4l59.5-34.6c-40.7-62.6-104.7-100-179.2-100-121.2 0-219.5 98.3-219.5 219.5S126.8 475.5 248 475.5c78.6 0 146.5-42.1 185.5-110.4z\"],\n    \"confluence\": [512, 512, [], \"f78d\", \"M2.3 412.2c-4.5 7.6-2.1 17.5 5.5 22.2l105.9 65.2c7.7 4.7 17.7 2.4 22.4-5.3 0-.1.1-.2.1-.2 67.1-112.2 80.5-95.9 280.9-.7 8.1 3.9 17.8.4 21.7-7.7.1-.1.1-.3.2-.4l50.4-114.1c3.6-8.1-.1-17.6-8.1-21.3-22.2-10.4-66.2-31.2-105.9-50.3C127.5 179 44.6 345.3 2.3 412.2zm507.4-312.1c4.5-7.6 2.1-17.5-5.5-22.2L398.4 12.8c-7.5-5-17.6-3.1-22.6 4.4-.2.3-.4.6-.6 1-67.3 112.6-81.1 95.6-280.6.9-8.1-3.9-17.8-.4-21.7 7.7-.1.1-.1.3-.2.4L22.2 141.3c-3.6 8.1.1 17.6 8.1 21.3 22.2 10.4 66.3 31.2 106 50.4 248 120 330.8-45.4 373.4-112.9z\"],\n    \"connectdevelop\": [576, 512, [], \"f20e\", \"M550.5 241l-50.089-86.786c1.071-2.142 1.875-4.553 1.875-7.232 0-8.036-6.696-14.733-14.732-15.001l-55.447-95.893c.536-1.607 1.071-3.214 1.071-4.821 0-8.571-6.964-15.268-15.268-15.268-4.821 0-8.839 2.143-11.786 5.625H299.518C296.839 18.143 292.821 16 288 16s-8.839 2.143-11.518 5.625H170.411C167.464 18.143 163.447 16 158.625 16c-8.303 0-15.268 6.696-15.268 15.268 0 1.607.536 3.482 1.072 4.821l-55.983 97.233c-5.356 2.41-9.107 7.5-9.107 13.661 0 .535.268 1.071.268 1.607l-53.304 92.143c-7.232 1.339-12.59 7.5-12.59 15 0 7.232 5.089 13.393 12.054 15l55.179 95.358c-.536 1.607-.804 2.946-.804 4.821 0 7.232 5.089 13.393 12.054 14.732l51.697 89.732c-.536 1.607-1.071 3.482-1.071 5.357 0 8.571 6.964 15.268 15.268 15.268 4.821 0 8.839-2.143 11.518-5.357h106.875C279.161 493.857 283.447 496 288 496s8.839-2.143 11.518-5.357h107.143c2.678 2.946 6.696 4.821 10.982 4.821 8.571 0 15.268-6.964 15.268-15.268 0-1.607-.267-2.946-.803-4.285l51.697-90.268c6.964-1.339 12.054-7.5 12.054-14.732 0-1.607-.268-3.214-.804-4.821l54.911-95.358c6.964-1.339 12.322-7.5 12.322-15-.002-7.232-5.092-13.393-11.788-14.732zM153.535 450.732l-43.66-75.803h43.66v75.803zm0-83.839h-43.66c-.268-1.071-.804-2.142-1.339-3.214l44.999-47.41v50.624zm0-62.411l-50.357 53.304c-1.339-.536-2.679-1.34-4.018-1.607L43.447 259.75c.535-1.339.535-2.679.535-4.018s0-2.41-.268-3.482l51.965-90c2.679-.268 5.357-1.072 7.768-2.679l50.089 51.965v92.946zm0-102.322l-45.803-47.41c1.339-2.143 2.143-4.821 2.143-7.767 0-.268-.268-.804-.268-1.072l43.928-15.804v72.053zm0-80.625l-43.66 15.804 43.66-75.536v59.732zm326.519 39.108l.804 1.339L445.5 329.125l-63.75-67.232 98.036-101.518.268.268zM291.75 355.107l11.518 11.786H280.5l11.25-11.786zm-.268-11.25l-83.303-85.446 79.553-84.375 83.036 87.589-79.286 82.232zm5.357 5.893l79.286-82.232 67.5 71.25-5.892 28.125H313.714l-16.875-17.143zM410.411 44.393c1.071.536 2.142 1.072 3.482 1.34l57.857 100.714v.536c0 2.946.803 5.624 2.143 7.767L376.393 256l-83.035-87.589L410.411 44.393zm-9.107-2.143L287.732 162.518l-57.054-60.268 166.339-60h4.287zm-123.483 0c2.678 2.678 6.16 4.285 10.179 4.285s7.5-1.607 10.179-4.285h75L224.786 95.821 173.893 42.25h103.928zm-116.249 5.625l1.071-2.142a33.834 33.834 0 0 0 2.679-.804l51.161 53.84-54.911 19.821V47.875zm0 79.286l60.803-21.964 59.732 63.214-79.553 84.107-40.982-42.053v-83.304zm0 92.678L198 257.607l-36.428 38.304v-76.072zm0 87.858l42.053-44.464 82.768 85.982-17.143 17.678H161.572v-59.196zm6.964 162.053c-1.607-1.607-3.482-2.678-5.893-3.482l-1.071-1.607v-89.732h99.91l-91.607 94.821h-1.339zm129.911 0c-2.679-2.41-6.428-4.285-10.447-4.285s-7.767 1.875-10.447 4.285h-96.429l91.607-94.821h38.304l91.607 94.821H298.447zm120-11.786l-4.286 7.5c-1.339.268-2.41.803-3.482 1.339l-89.196-91.875h114.376l-17.412 83.036zm12.856-22.232l12.858-60.803h21.964l-34.822 60.803zm34.822-68.839h-20.357l4.553-21.16 17.143 18.214c-.535.803-1.071 1.874-1.339 2.946zm66.161-107.411l-55.447 96.697c-1.339.535-2.679 1.071-4.018 1.874l-20.625-21.964 34.554-163.928 45.803 79.286c-.267 1.339-.803 2.678-.803 4.285 0 1.339.268 2.411.536 3.75z\"],\n    \"contao\": [512, 512, [], \"f26d\", \"M45.4 305c14.4 67.1 26.4 129 68.2 175H34c-18.7 0-34-15.2-34-34V66c0-18.7 15.2-34 34-34h57.7C77.9 44.6 65.6 59.2 54.8 75.6c-45.4 70-27 146.8-9.4 229.4zM478 32h-90.2c21.4 21.4 39.2 49.5 52.7 84.1l-137.1 29.3c-14.9-29-37.8-53.3-82.6-43.9-24.6 5.3-41 19.3-48.3 34.6-8.8 18.7-13.2 39.8 8.2 140.3 21.1 100.2 33.7 117.7 49.5 131.2 12.9 11.1 33.4 17 58.3 11.7 44.5-9.4 55.7-40.7 57.4-73.2l137.4-29.6c3.2 71.5-18.7 125.2-57.4 163.6H478c18.7 0 34-15.2 34-34V66c0-18.8-15.2-34-34-34z\"],\n    \"cotton-bureau\": [512, 512, [], \"f89e\", \"M474.31 330.41c-23.66 91.85-94.23 144.59-201.9 148.35V429.6c0-48 26.41-74.39 74.39-74.39 62 0 99.2-37.2 99.2-99.21 0-61.37-36.53-98.28-97.38-99.06-33-69.32-146.5-64.65-177.24 0C110.52 157.72 74 194.63 74 256c0 62.13 37.27 99.41 99.4 99.41 48 0 74.55 26.23 74.55 74.39V479c-134.43-5-211.1-85.07-211.1-223 0-141.82 81.35-223.2 223.2-223.2 114.77 0 189.84 53.2 214.69 148.81H500C473.88 71.51 388.22 8 259.82 8 105 8 12 101.19 12 255.82 12 411.14 105.19 504.34 259.82 504c128.27 0 213.87-63.81 239.67-173.59zM357 182.33c41.37 3.45 64.2 29 64.2 73.67 0 48-26.43 74.41-74.4 74.41-28.61 0-49.33-9.59-61.59-27.33 83.06-16.55 75.59-99.67 71.79-120.75zm-81.68 97.36c-2.46-10.34-16.33-87 56.23-97 2.27 10.09 16.52 87.11-56.26 97zM260 132c28.61 0 49 9.67 61.44 27.61-28.36 5.48-49.36 20.59-61.59 43.45-12.23-22.86-33.23-38-61.6-43.45 12.41-17.69 33.27-27.35 61.57-27.35zm-71.52 50.72c73.17 10.57 58.91 86.81 56.49 97-72.41-9.84-59-86.95-56.25-97zM173.2 330.41c-48 0-74.4-26.4-74.4-74.41 0-44.36 22.86-70 64.22-73.67-6.75 37.2-1.38 106.53 71.65 120.75-12.14 17.63-32.84 27.3-61.14 27.3zm53.21 12.39A80.8 80.8 0 0 0 260 309.25c7.77 14.49 19.33 25.54 33.82 33.55a80.28 80.28 0 0 0-33.58 33.83c-8-14.5-19.07-26.23-33.56-33.83z\"],\n    \"cpanel\": [640, 512, [], \"f388\", \"M210.3 220.2c-5.6-24.8-26.9-41.2-51-41.2h-37c-7.1 0-12.5 4.5-14.3 10.9L73.1 320l24.7-.1c6.8 0 12.3-4.5 14.2-10.7l25.8-95.7h19.8c8.4 0 16.2 5.6 18.3 14.8 2.5 10.9-5.9 22.6-18.3 22.6h-10.3c-7 0-12.5 4.6-14.3 10.8l-6.4 23.8h32c37.2 0 58.3-36.2 51.7-65.3zm-156.5 28h18.6c6.9 0 12.4-4.4 14.3-10.9l6.2-23.6h-40C30 213.7 9 227.8 1.7 254.8-7 288.6 18.5 320 52 320h12.4l7.1-26.1c1.2-4.4-2.2-8.3-6.4-8.3H53.8c-24.7 0-24.9-37.4 0-37.4zm247.5-34.8h-77.9l-3.5 13.4c-2.4 9.6 4.5 18.5 14.2 18.5h57.5c4 0 2.4 4.3 2.1 5.3l-8.6 31.8c-.4 1.4-.9 5.3-5.5 5.3h-34.9c-5.3 0-5.3-7.9 0-7.9h21.6c6.8 0 12.3-4.6 14.2-10.8l3.5-13.2h-48.4c-39.2 0-43.6 63.8-.7 63.8l57.5.2c11.2 0 20.6-7.2 23.4-17.8l14-51.8c4.8-19.2-9.7-36.8-28.5-36.8zM633.1 179h-18.9c-4.9 0-9.2 3.2-10.4 7.9L568.2 320c20.7 0 39.8-13.8 44.9-34.5l26.5-98.2c1.2-4.3-2-8.3-6.5-8.3zm-236.3 34.7v.1h-48.3l-26.2 98c-1.2 4.4 2.2 8.3 6.4 8.3h18.9c4.8 0 9.2-3 10.4-7.8l17.2-64H395c12.5 0 21.4 11.8 18.1 23.4l-10.6 40c-1.2 4.3 1.9 8.3 6.4 8.3H428c4.6 0 9.1-2.9 10.3-7.8l8.8-33.1c9-33.1-15.9-65.4-50.3-65.4zm98.3 74.6c-3.6 0-6-3.4-5.1-6.7l8-30c.9-3.9 3.7-6 7.8-6h32.9c2.6 0 4.6 2.4 3.9 5.1l-.7 2.6c-.6 2-1.9 3-3.9 3h-21.6c-7 0-12.6 4.6-14.2 10.8l-3.5 13h53.4c10.5 0 20.3-6.6 23.2-17.6l3.2-12c4.9-19.1-9.3-36.8-28.3-36.8h-47.3c-17.9 0-33.8 12-38.6 29.6l-10.8 40c-5 17.7 8.3 36.7 28.3 36.7h66.7c6.8 0 12.3-4.5 14.2-10.7l5.7-21z\"],\n    \"creative-commons\": [496, 512, [], \"f25e\", \"M245.83 214.87l-33.22 17.28c-9.43-19.58-25.24-19.93-27.46-19.93-22.13 0-33.22 14.61-33.22 43.84 0 23.57 9.21 43.84 33.22 43.84 14.47 0 24.65-7.09 30.57-21.26l30.55 15.5c-6.17 11.51-25.69 38.98-65.1 38.98-22.6 0-73.96-10.32-73.96-77.05 0-58.69 43-77.06 72.63-77.06 30.72-.01 52.7 11.95 65.99 35.86zm143.05 0l-32.78 17.28c-9.5-19.77-25.72-19.93-27.9-19.93-22.14 0-33.22 14.61-33.22 43.84 0 23.55 9.23 43.84 33.22 43.84 14.45 0 24.65-7.09 30.54-21.26l31 15.5c-2.1 3.75-21.39 38.98-65.09 38.98-22.69 0-73.96-9.87-73.96-77.05 0-58.67 42.97-77.06 72.63-77.06 30.71-.01 52.58 11.95 65.56 35.86zM247.56 8.05C104.74 8.05 0 123.11 0 256.05c0 138.49 113.6 248 247.56 248 129.93 0 248.44-100.87 248.44-248 0-137.87-106.62-248-248.44-248zm.87 450.81c-112.54 0-203.7-93.04-203.7-202.81 0-105.42 85.43-203.27 203.72-203.27 112.53 0 202.82 89.46 202.82 203.26-.01 121.69-99.68 202.82-202.84 202.82z\"],\n    \"creative-commons-by\": [496, 512, [], \"f4e7\", \"M314.9 194.4v101.4h-28.3v120.5h-77.1V295.9h-28.3V194.4c0-4.4 1.6-8.2 4.6-11.3 3.1-3.1 6.9-4.7 11.3-4.7H299c4.1 0 7.8 1.6 11.1 4.7 3.1 3.2 4.8 6.9 4.8 11.3zm-101.5-63.7c0-23.3 11.5-35 34.5-35s34.5 11.7 34.5 35c0 23-11.5 34.5-34.5 34.5s-34.5-11.5-34.5-34.5zM247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3z\"],\n    \"creative-commons-nc\": [496, 512, [], \"f4e8\", \"M247.6 8C387.4 8 496 115.9 496 256c0 147.2-118.5 248-248.4 248C113.1 504 0 393.2 0 256 0 123.1 104.7 8 247.6 8zM55.8 189.1c-7.4 20.4-11.1 42.7-11.1 66.9 0 110.9 92.1 202.4 203.7 202.4 122.4 0 177.2-101.8 178.5-104.1l-93.4-41.6c-7.7 37.1-41.2 53-68.2 55.4v38.1h-28.8V368c-27.5-.3-52.6-10.2-75.3-29.7l34.1-34.5c31.7 29.4 86.4 31.8 86.4-2.2 0-6.2-2.2-11.2-6.6-15.1-14.2-6-1.8-.1-219.3-97.4zM248.4 52.3c-38.4 0-112.4 8.7-170.5 93l94.8 42.5c10-31.3 40.4-42.9 63.8-44.3v-38.1h28.8v38.1c22.7 1.2 43.4 8.9 62 23L295 199.7c-42.7-29.9-83.5-8-70 11.1 53.4 24.1 43.8 19.8 93 41.6l127.1 56.7c4.1-17.4 6.2-35.1 6.2-53.1 0-57-19.8-105-59.3-143.9-39.3-39.9-87.2-59.8-143.6-59.8z\"],\n    \"creative-commons-nc-eu\": [496, 512, [], \"f4e9\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.3 111.7 248 247.7 248C377.9 504 496 403.1 496 256 496 117 388.4 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-23.2 3.7-45.2 10.9-66l65.7 29.1h-4.7v29.5h23.3c0 6.2-.4 3.2-.4 19.5h-22.8v29.5h27c11.4 67 67.2 101.3 124.6 101.3 26.6 0 50.6-7.9 64.8-15.8l-10-46.1c-8.7 4.6-28.2 10.8-47.3 10.8-28.2 0-58.1-10.9-67.3-50.2h90.3l128.3 56.8c-1.5 2.1-56.2 104.3-178.8 104.3zm-16.7-190.6l-.5-.4.9.4h-.4zm77.2-19.5h3.7v-29.5h-70.3l-28.6-12.6c2.5-5.5 5.4-10.5 8.8-14.3 12.9-15.8 31.1-22.4 51.1-22.4 18.3 0 35.3 5.4 46.1 10l11.6-47.3c-15-6.6-37-12.4-62.3-12.4-39 0-72.2 15.8-95.9 42.3-5.3 6.1-9.8 12.9-13.9 20.1l-81.6-36.1c64.6-96.8 157.7-93.6 170.7-93.6 113 0 203 90.2 203 203.4 0 18.7-2.1 36.3-6.3 52.9l-136.1-60.5z\"],\n    \"creative-commons-nc-jp\": [496, 512, [], \"f4ea\", \"M247.7 8C103.6 8 0 124.8 0 256c0 136.4 111.8 248 247.7 248C377.9 504 496 403.2 496 256 496 117.2 388.5 8 247.7 8zm.6 450.7c-112 0-203.6-92.5-203.6-202.7 0-21.1 3-41.2 9-60.3l127 56.5h-27.9v38.6h58.1l5.7 11.8v18.7h-63.8V360h63.8v56h61.7v-56h64.2v-35.7l81 36.1c-1.5 2.2-57.1 98.3-175.2 98.3zm87.6-137.3h-57.6v-18.7l2.9-5.6 54.7 24.3zm6.5-51.4v-17.8h-38.6l63-116H301l-43.4 96-23-10.2-39.6-85.7h-65.8l27.3 51-81.9-36.5c27.8-44.1 82.6-98.1 173.7-98.1 112.8 0 203 90 203 203.4 0 21-2.7 40.6-7.9 59l-101-45.1z\"],\n    \"creative-commons-nd\": [496, 512, [], \"f4eb\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm94 144.3v42.5H162.1V197h180.3zm0 79.8v42.5H162.1v-42.5h180.3z\"],\n    \"creative-commons-pd\": [496, 512, [], \"f4ec\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm0 449.5c-139.2 0-235.8-138-190.2-267.9l78.8 35.1c-2.1 10.5-3.3 21.5-3.3 32.9 0 99 73.9 126.9 120.4 126.9 22.9 0 53.5-6.7 79.4-29.5L297 311.1c-5.5 6.3-17.6 16.7-36.3 16.7-37.8 0-53.7-39.9-53.9-71.9 230.4 102.6 216.5 96.5 217.9 96.8-34.3 62.4-100.6 104.8-176.7 104.8zm194.2-150l-224-100c18.8-34 54.9-30.7 74.7-11l40.4-41.6c-27.1-23.3-58-27.5-78.1-27.5-47.4 0-80.9 20.5-100.7 51.6l-74.9-33.4c36.1-54.9 98.1-91.2 168.5-91.2 111.1 0 201.5 90.4 201.5 201.5 0 18-2.4 35.4-6.8 52-.3-.1-.4-.2-.6-.4z\"],\n    \"creative-commons-pd-alt\": [496, 512, [], \"f4ed\", \"M247.6 8C104.7 8 0 123.1 0 256c0 138.5 113.6 248 247.6 248C377.5 504 496 403.1 496 256 496 118.1 389.4 8 247.6 8zm.8 450.8c-112.5 0-203.7-93-203.7-202.8 0-105.4 85.5-203.3 203.7-203.3 112.6 0 202.9 89.5 202.8 203.3 0 121.7-99.6 202.8-202.8 202.8zM316.7 186h-53.2v137.2h53.2c21.4 0 70-5.1 70-68.6 0-63.4-48.6-68.6-70-68.6zm.8 108.5h-19.9v-79.7l19.4-.1c3.8 0 35-2.1 35 39.9 0 24.6-10.5 39.9-34.5 39.9zM203.7 186h-68.2v137.3h34.6V279h27c54.1 0 57.1-37.5 57.1-46.5 0-31-16.8-46.5-50.5-46.5zm-4.9 67.3h-29.2v-41.6h28.3c30.9 0 28.8 41.6.9 41.6z\"],\n    \"creative-commons-remix\": [496, 512, [], \"f4ee\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm161.7 207.7l4.9 2.2v70c-7.2 3.6-63.4 27.5-67.3 28.8-6.5-1.8-113.7-46.8-137.3-56.2l-64.2 26.6-63.3-27.5v-63.8l59.3-24.8c-.7-.7-.4 5-.4-70.4l67.3-29.7L361 178.5v61.6l49.1 20.3zm-70.4 81.5v-43.8h-.4v-1.8l-113.8-46.5V295l113.8 46.9v-.4l.4.4zm7.5-57.6l39.9-16.4-36.8-15.5-39 16.4 35.9 15.5zm52.3 38.1v-43L355.2 298v43.4l44.3-19z\"],\n    \"creative-commons-sa\": [496, 512, [], \"f4ef\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zM137.7 221c13-83.9 80.5-95.7 108.9-95.7 99.8 0 127.5 82.5 127.5 134.2 0 63.6-41 132.9-128.9 132.9-38.9 0-99.1-20-109.4-97h62.5c1.5 30.1 19.6 45.2 54.5 45.2 23.3 0 58-18.2 58-82.8 0-82.5-49.1-80.6-56.7-80.6-33.1 0-51.7 14.6-55.8 43.8h18.2l-49.2 49.2-49-49.2h19.4z\"],\n    \"creative-commons-sampling\": [496, 512, [], \"f4f0\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm3.6 53.2c2.8-.3 11.5 1 11.5 11.5l6.6 107.2 4.9-59.3c0-6 4.7-10.6 10.6-10.6 5.9 0 10.6 4.7 10.6 10.6 0 2.5-.5-5.7 5.7 81.5l5.8-64.2c.3-2.9 2.9-9.3 10.2-9.3 3.8 0 9.9 2.3 10.6 8.9l11.5 96.5 5.3-12.8c1.8-4.4 5.2-6.6 10.2-6.6h58v21.3h-50.9l-18.2 44.3c-3.9 9.9-19.5 9.1-20.8-3.1l-4-31.9-7.5 92.6c-.3 3-3 9.3-10.2 9.3-3 0-9.8-2.1-10.6-9.3 0-1.9.6 5.8-6.2-77.9l-5.3 72.2c-1.1 4.8-4.8 9.3-10.6 9.3-2.9 0-9.8-2-10.6-9.3 0-1.9.5 6.7-5.8-87.7l-5.8 94.8c0 6.3-3.6 12.4-10.6 12.4-5.2 0-10.6-4.1-10.6-12l-5.8-87.7c-5.8 92.5-5.3 84-5.3 85.9-1.1 4.8-4.8 9.3-10.6 9.3-3 0-9.8-2.1-10.6-9.3 0-.7-.4-1.1-.4-2.6l-6.2-88.6L182 348c-.7 6.5-6.7 9.3-10.6 9.3-5.8 0-9.6-4.1-10.6-8.9L149.7 272c-2 4-3.5 8.4-11.1 8.4H87.2v-21.3H132l13.7-27.9c4.4-9.9 18.2-7.2 19.9 2.7l3.1 20.4 8.4-97.9c0-6 4.8-10.6 10.6-10.6.5 0 10.6-.2 10.6 12.4l4.9 69.1 6.6-92.6c0-10.1 9.5-10.6 10.2-10.6.6 0 10.6.7 10.6 10.6l5.3 80.6 6.2-97.9c.1-1.1-.6-10.3 9.9-11.5z\"],\n    \"creative-commons-sampling-plus\": [496, 512, [], \"f4f1\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm107 205.6c-4.7 0-9 2.8-10.7 7.2l-4 9.5-11-92.8c-1.7-13.9-22-13.4-23.1.4l-4.3 51.4-5.2-68.8c-1.1-14.3-22.1-14.2-23.2 0l-3.5 44.9-5.9-94.3c-.9-14.5-22.3-14.4-23.2 0l-5.1 83.7-4.3-66.3c-.9-14.4-22.2-14.4-23.2 0l-5.3 80.2-4.1-57c-1.1-14.3-22-14.3-23.2-.2l-7.7 89.8-1.8-12.2c-1.7-11.4-17.1-13.6-22-3.3l-13.2 27.7H87.5v23.2h51.3c4.4 0 8.4-2.5 10.4-6.4l10.7 73.1c2 13.5 21.9 13 23.1-.7l3.8-43.6 5.7 78.3c1.1 14.4 22.3 14.2 23.2-.1l4.6-70.4 4.8 73.3c.9 14.4 22.3 14.4 23.2-.1l4.9-80.5 4.5 71.8c.9 14.3 22.1 14.5 23.2.2l4.6-58.6 4.9 64.4c1.1 14.3 22 14.2 23.1.1l6.8-83 2.7 22.3c1.4 11.8 17.7 14.1 22.3 3.1l18-43.4h50.5V258l-58.4.3zm-78 5.2h-21.9v21.9c0 4.1-3.3 7.5-7.5 7.5-4.1 0-7.5-3.3-7.5-7.5v-21.9h-21.9c-4.1 0-7.5-3.3-7.5-7.5 0-4.1 3.4-7.5 7.5-7.5h21.9v-21.9c0-4.1 3.4-7.5 7.5-7.5s7.5 3.3 7.5 7.5v21.9h21.9c4.1 0 7.5 3.3 7.5 7.5 0 4.1-3.4 7.5-7.5 7.5z\"],\n    \"creative-commons-share\": [496, 512, [], \"f4f2\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm101 132.4c7.8 0 13.7 6.1 13.7 13.7v182.5c0 7.7-6.1 13.7-13.7 13.7H214.3c-7.7 0-13.7-6-13.7-13.7v-54h-54c-7.8 0-13.7-6-13.7-13.7V131.1c0-8.2 6.6-12.7 12.4-13.7h136.4c7.7 0 13.7 6 13.7 13.7v54h54zM159.9 300.3h40.7V198.9c0-7.4 5.8-12.6 12-13.7h55.8v-40.3H159.9v155.4zm176.2-88.1H227.6v155.4h108.5V212.2z\"],\n    \"creative-commons-zero\": [496, 512, [], \"f4f3\", \"M247.6 8C389.4 8 496 118.1 496 256c0 147.1-118.5 248-248.4 248C113.6 504 0 394.5 0 256 0 123.1 104.7 8 247.6 8zm.8 44.7C130.2 52.7 44.7 150.6 44.7 256c0 109.8 91.2 202.8 203.7 202.8 103.2 0 202.8-81.1 202.8-202.8.1-113.8-90.2-203.3-202.8-203.3zm-.4 60.5c-81.9 0-102.5 77.3-102.5 142.8 0 65.5 20.6 142.8 102.5 142.8S350.5 321.5 350.5 256c0-65.5-20.6-142.8-102.5-142.8zm0 53.9c3.3 0 6.4.5 9.2 1.2 5.9 5.1 8.8 12.1 3.1 21.9l-54.5 100.2c-1.7-12.7-1.9-25.1-1.9-34.4 0-28.8 2-88.9 44.1-88.9zm40.8 46.2c2.9 15.4 3.3 31.4 3.3 42.7 0 28.9-2 88.9-44.1 88.9-13.5 0-32.6-7.7-20.1-26.4l60.9-105.2z\"],\n    \"critical-role\": [448, 512, [], \"f6c9\", \"M225.82 0c.26.15 216.57 124.51 217.12 124.72 3 1.18 3.7 3.46 3.7 6.56q-.11 125.17 0 250.36a5.88 5.88 0 0 1-3.38 5.78c-21.37 12-207.86 118.29-218.93 124.58h-3C142 466.34 3.08 386.56 2.93 386.48a3.29 3.29 0 0 1-1.88-3.24c0-.87 0-225.94-.05-253.1a5 5 0 0 1 2.93-4.93C27.19 112.11 213.2 6 224.07 0zM215.4 20.42l-.22-.16Q118.06 75.55 21 130.87c0 .12.08.23.13.35l30.86 11.64c-7.71 6-8.32 6-10.65 5.13-.1 0-24.17-9.28-26.8-10v230.43c.88-1.41 64.07-110.91 64.13-111 1.62-2.82 3-1.92 9.12-1.52 1.4.09 1.48.22.78 1.42-41.19 71.33-36.4 63-67.48 116.94-.81 1.4-.61 1.13 1.25 1.13h186.5c1.44 0 1.69-.23 1.7-1.64v-8.88c0-1.34 2.36-.81-18.37-1-7.46-.07-14.14-3.22-21.38-12.7-7.38-9.66-14.62-19.43-21.85-29.21-2.28-3.08-3.45-2.38-16.76-2.38-1.75 0-1.78 0-1.76 1.82.29 26.21.15 25.27 1 32.66.52 4.37 2.16 4.2 9.69 4.81 3.14.26 3.88 4.08.52 4.92-1.57.39-31.6.51-33.67-.1a2.42 2.42 0 0 1 .3-4.73c3.29-.76 6.16.81 6.66-4.44 1.3-13.66 1.17-9 1.1-79.42 0-10.82-.35-12.58-5.36-13.55-1.22-.24-3.54-.16-4.69-.55-2.88-1-2-4.84 1.77-4.85 33.67 0 46.08-1.07 56.06 4.86 7.74 4.61 12 11.48 12.51 20.4.88 14.59-6.51 22.35-15 32.59a1.46 1.46 0 0 0 0 2.22c2.6 3.25 5 6.63 7.71 9.83 27.56 33.23 24.11 30.54 41.28 33.06.89.13 1-.42 1-1.15v-11c0-1 .32-1.43 1.41-1.26a72.37 72.37 0 0 0 23.58-.3c1.08-.15 1.5.2 1.48 1.33 0 .11.88 26.69.87 26.8-.05 1.52.67 1.62 1.89 1.62h186.71Q386.51 304.6 346 234.33c2.26-.66-.4 0 6.69-1.39 2-.39 2.05-.41 3.11 1.44 7.31 12.64 77.31 134 77.37 134.06V138c-1.72.5-103.3 38.72-105.76 39.68-1.08.42-1.55.2-1.91-.88-.63-1.9-1.34-3.76-2.09-5.62-.32-.79-.09-1.13.65-1.39.1 0 95.53-35.85 103-38.77-65.42-37.57-130.56-75-196-112.6l86.82 150.39-.28.33c-9.57-.9-10.46-1.6-11.8-3.94-1-1.69-73.5-127.71-82-142.16-9.1 14.67-83.56 146.21-85.37 146.32-2.93.17-5.88.08-9.25.08q43.25-74.74 86.18-149zm51.93 129.92a37.68 37.68 0 0 0 5.54-.85c1.69-.3 2.53.2 2.6 1.92 0 .11.07 19.06-.86 20.45s-1.88 1.22-2.6-.19c-5-9.69 6.22-9.66-39.12-12-.7 0-1 .23-1 .93 0 .13 3.72 122 3.73 122.11 0 .89.52 1.2 1.21 1.51a83.92 83.92 0 0 1 8.7 4.05c7.31 4.33 11.38 10.84 12.41 19.31 1.44 11.8-2.77 35.77-32.21 37.14-2.75.13-28.26 1.08-34.14-23.25-4.66-19.26 8.26-32.7 19.89-36.4a2.45 2.45 0 0 0 2-2.66c.1-5.63 3-107.1 3.71-121.35.05-1.08-.62-1.16-1.35-1.15-32.35.52-36.75-.34-40.22 8.52-2.42 6.18-4.14 1.32-3.95.23q1.59-9 3.31-18c.4-2.11 1.43-2.61 3.43-1.86 5.59 2.11 6.72 1.7 37.25 1.92 1.73 0 1.78-.08 1.82-1.85.68-27.49.58-22.59 1-29.55a2.69 2.69 0 0 0-1.63-2.8c-5.6-2.91-8.75-7.55-8.9-13.87-.35-14.81 17.72-21.67 27.38-11.51 6.84 7.19 5.8 18.91-2.45 24.15a4.35 4.35 0 0 0-2.22 4.34c0 .59-.11-4.31 1 30.05 0 .9.43 1.12 1.24 1.11.1 0 23-.09 34.47-.37zM68.27 141.7c19.84-4.51 32.68-.56 52.49 1.69 2.76.31 3.74 1.22 3.62 4-.21 5-1.16 22.33-1.24 23.15a2.65 2.65 0 0 1-1.63 2.34c-4.06 1.7-3.61-4.45-4-7.29-3.13-22.43-73.87-32.7-74.63 25.4-.31 23.92 17 53.63 54.08 50.88 27.24-2 19-20.19 24.84-20.47a2.72 2.72 0 0 1 3 3.36c-1.83 10.85-3.42 18.95-3.45 19.15-1.54 9.17-86.7 22.09-93.35-42.06-2.71-25.85 10.44-53.37 40.27-60.15zm80 87.67h-19.49a2.57 2.57 0 0 1-2.66-1.79c2.38-3.75 5.89.92 5.86-6.14-.08-25.75.21-38 .23-40.1 0-3.42-.53-4.65-3.32-4.94-7-.72-3.11-3.37-1.11-3.38 11.84-.1 22.62-.18 30.05.72 8.77 1.07 16.71 12.63 7.93 22.62-2 2.25-4 4.42-6.14 6.73.95 1.15 6.9 8.82 17.28 19.68 2.66 2.78 6.15 3.51 9.88 3.13a2.21 2.21 0 0 0 2.23-2.12c.3-3.42.26 4.73.45-40.58 0-5.65-.34-6.58-3.23-6.83-3.95-.35-4-2.26-.69-3.37l19.09-.09c.32 0 4.49.53 1 3.38 0 .05-.16 0-.24 0-3.61.26-3.94 1-4 4.62-.27 43.93.07 40.23.41 42.82.11.84.27 2.23 5.1 2.14 2.49 0 3.86 3.37 0 3.4-10.37.08-20.74 0-31.11.07-10.67 0-13.47-6.2-24.21-20.82-1.6-2.18-8.31-2.36-8.2-.37.88 16.47 0 17.78 4 17.67 4.75-.1 4.73 3.57.83 3.55zm275-10.15c-1.21 7.13.17 10.38-5.3 10.34-61.55-.42-47.82-.22-50.72-.31a18.4 18.4 0 0 1-3.63-.73c-2.53-.6 1.48-1.23-.38-5.6-1.43-3.37-2.78-6.78-4.11-10.19a1.94 1.94 0 0 0-2-1.44 138 138 0 0 0-14.58.07 2.23 2.23 0 0 0-1.62 1.06c-1.58 3.62-3.07 7.29-4.51 11-1.27 3.23 7.86 1.32 12.19 2.16 3 .57 4.53 3.72.66 3.73H322.9c-2.92 0-3.09-3.15-.74-3.21a6.3 6.3 0 0 0 5.92-3.47c1.5-3 2.8-6 4.11-9.09 18.18-42.14 17.06-40.17 18.42-41.61a1.83 1.83 0 0 1 3 0c2.93 3.34 18.4 44.71 23.62 51.92 2 2.7 5.74 2 6.36 2 3.61.13 4-1.11 4.13-4.29.09-1.87.08 1.17.07-41.24 0-4.46-2.36-3.74-5.55-4.27-.26 0-2.56-.63-.08-3.06.21-.2-.89-.24 21.7-.15 2.32 0 5.32 2.75-1.21 3.45a2.56 2.56 0 0 0-2.66 2.83c-.07 1.63-.19 38.89.29 41.21a3.06 3.06 0 0 0 3.23 2.43c13.25.43 14.92.44 16-3.41 1.67-5.78 4.13-2.52 3.73-.19zm-104.72 64.37c-4.24 0-4.42-3.39-.61-3.41 35.91-.16 28.11.38 37.19-.65 1.68-.19 2.38.24 2.25 1.89-.26 3.39-.64 6.78-1 10.16-.25 2.16-3.2 2.61-3.4-.15-.38-5.31-2.15-4.45-15.63-5.08-1.58-.07-1.64 0-1.64 1.52V304c0 1.65 0 1.6 1.62 1.47 3.12-.25 10.31.34 15.69-1.52.47-.16 3.3-1.79 3.07 1.76 0 .21-.76 10.35-1.18 11.39-.53 1.29-1.88 1.51-2.58.32-1.17-2 0-5.08-3.71-5.3-15.42-.9-12.91-2.55-12.91 6 0 12.25-.76 16.11 3.89 16.24 16.64.48 14.4 0 16.43-5.71.84-2.37 3.5-1.77 3.18.58-.44 3.21-.85 6.43-1.23 9.64 0 .36-.16 2.4-4.66 2.39-37.16-.08-34.54-.19-35.21-.31-2.72-.51-2.2-3 .22-3.45 1.1-.19 4 .54 4.16-2.56 2.44-56.22-.07-51.34-3.91-51.33zm-.41-109.52c2.46.61 3.13 1.76 2.95 4.65-.33 5.3-.34 9-.55 9.69-.66 2.23-3.15 2.12-3.34-.27-.38-4.81-3.05-7.82-7.57-9.15-26.28-7.73-32.81 15.46-27.17 30.22 5.88 15.41 22 15.92 28.86 13.78 5.92-1.85 5.88-6.5 6.91-7.58 1.23-1.3 2.25-1.84 3.12 1.1 0 .1.57 11.89-6 12.75-1.6.21-19.38 3.69-32.68-3.39-21-11.19-16.74-35.47-6.88-45.33 14-14.06 39.91-7.06 42.32-6.47zM289.8 280.14c3.28 0 3.66 3 .16 3.43-2.61.32-5-.42-5 5.46 0 2-.19 29.05.4 41.45.11 2.29 1.15 3.52 3.44 3.65 22 1.21 14.95-1.65 18.79-6.34 1.83-2.24 2.76.84 2.76 1.08.35 13.62-4 12.39-5.19 12.4l-38.16-.19c-1.93-.23-2.06-3-.42-3.38 2-.48 4.94.4 5.13-2.8 1-15.87.57-44.65.34-47.81-.27-3.77-2.8-3.27-5.68-3.71-2.47-.38-2-3.22.34-3.22 1.45-.02 17.97-.03 23.09-.02zm-31.63-57.79c.07 4.08 2.86 3.46 6 3.58 2.61.1 2.53 3.41-.07 3.43-6.48 0-13.7 0-21.61-.06-3.84 0-3.38-3.35 0-3.37 4.49 0 3.24 1.61 3.41-45.54 0-5.08-3.27-3.54-4.72-4.23-2.58-1.23-1.36-3.09.41-3.15 1.29 0 20.19-.41 21.17.21s1.87 1.65-.42 2.86c-1 .52-3.86-.28-4.15 2.47 0 .21-.82 1.63-.07 43.8zm-36.91 274.27a2.93 2.93 0 0 0 3.26 0c17-9.79 182-103.57 197.42-112.51-.14-.43 11.26-.18-181.52-.27-1.22 0-1.57.37-1.53 1.56 0 .1 1.25 44.51 1.22 50.38a28.33 28.33 0 0 1-1.36 7.71c-.55 1.83.38-.5-13.5 32.23-.73 1.72-1 2.21-2-.08-4.19-10.34-8.28-20.72-12.57-31a23.6 23.6 0 0 1-2-10.79c.16-2.46.8-16.12 1.51-48 0-1.95 0-2-2-2h-183c2.58 1.63 178.32 102.57 196 112.76zm-90.9-188.75c0 2.4.36 2.79 2.76 3 11.54 1.17 21 3.74 25.64-7.32 6-14.46 2.66-34.41-12.48-38.84-2-.59-16-2.76-15.94 1.51.05 8.04.01 11.61.02 41.65zm105.75-15.05c0 2.13 1.07 38.68 1.09 39.13.34 9.94-25.58 5.77-25.23-2.59.08-2 1.37-37.42 1.1-39.43-14.1 7.44-14.42 40.21 6.44 48.8a17.9 17.9 0 0 0 22.39-7.07c4.91-7.76 6.84-29.47-5.43-39a2.53 2.53 0 0 1-.36.12zm-12.28-198c-9.83 0-9.73 14.75-.07 14.87s10.1-14.88.07-14.91zm-80.15 103.83c0 1.8.41 2.4 2.17 2.58 13.62 1.39 12.51-11 12.16-13.36-1.69-11.22-14.38-10.2-14.35-7.81.05 4.5-.03 13.68.02 18.59zm212.32 6.4l-6.1-15.84c-2.16 5.48-4.16 10.57-6.23 15.84z\"],\n    \"css3\": [512, 512, [], \"f13c\", \"M480 32l-64 368-223.3 80L0 400l19.6-94.8h82l-8 40.6L210 390.2l134.1-44.4 18.8-97.1H29.5l16-82h333.7l10.5-52.7H56.3l16.3-82H480z\"],\n    \"css3-alt\": [384, 512, [], \"f38b\", \"M0 32l34.9 395.8L192 480l157.1-52.2L384 32H0zm313.1 80l-4.8 47.3L193 208.6l-.3.1h111.5l-12.8 146.6-98.2 28.7-98.8-29.2-6.4-73.9h48.9l3.2 38.3 52.6 13.3 54.7-15.4 3.7-61.6-166.3-.5v-.1l-.2.1-3.6-46.3L193.1 162l6.5-2.7H76.7L70.9 112h242.2z\"],\n    \"cuttlefish\": [440, 512, [], \"f38c\", \"M344 305.5c-17.5 31.6-57.4 54.5-96 54.5-56.6 0-104-47.4-104-104s47.4-104 104-104c38.6 0 78.5 22.9 96 54.5 13.7-50.9 41.7-93.3 87-117.8C385.7 39.1 320.5 8 248 8 111 8 0 119 0 256s111 248 248 248c72.5 0 137.7-31.1 183-80.7-45.3-24.5-73.3-66.9-87-117.8z\"],\n    \"d-and-d\": [576, 512, [], \"f38d\", \"M82.5 98.9c-.6-17.2 2-33.8 12.7-48.2.3 7.4 1.2 14.5 4.2 21.6 5.9-27.5 19.7-49.3 42.3-65.5-1.9 5.9-3.5 11.8-3 17.7 8.7-7.4 18.8-17.8 44.4-22.7 14.7-2.8 29.7-2 42.1 1 38.5 9.3 61 34.3 69.7 72.3 5.3 23.1.7 45-8.3 66.4-5.2 12.4-12 24.4-20.7 35.1-2-1.9-3.9-3.8-5.8-5.6-42.8-40.8-26.8-25.2-37.4-37.4-1.1-1.2-1-2.2-.1-3.6 8.3-13.5 11.8-28.2 10-44-1.1-9.8-4.3-18.9-11.3-26.2-14.5-15.3-39.2-15-53.5.6-11.4 12.5-14.1 27.4-10.9 43.6.2 1.3.4 2.7 0 3.9-3.4 13.7-4.6 27.6-2.5 41.6.1.5.1 1.1.1 1.6 0 .3-.1.5-.2 1.1-21.8-11-36-28.3-43.2-52.2-8.3 17.8-11.1 35.5-6.6 54.1-15.6-15.2-21.3-34.3-22-55.2zm469.6 123.2c-11.6-11.6-25-20.4-40.1-26.6-12.8-5.2-26-7.9-39.9-7.1-10 .6-19.6 3.1-29 6.4-2.5.9-5.1 1.6-7.7 2.2-4.9 1.2-7.3-3.1-4.7-6.8 3.2-4.6 3.4-4.2 15-12 .6-.4 1.2-.8 2.2-1.5h-2.5c-.6 0-1.2.2-1.9.3-19.3 3.3-30.7 15.5-48.9 29.6-10.4 8.1-13.8 3.8-12-.5 1.4-3.5 3.3-6.7 5.1-10 1-1.8 2.3-3.4 3.5-5.1-.2-.2-.5-.3-.7-.5-27 18.3-46.7 42.4-57.7 73.3.3.3.7.6 1 .9.3-.6.5-1.2.9-1.7 10.4-12.1 22.8-21.8 36.6-29.8 18.2-10.6 37.5-18.3 58.7-20.2 4.3-.4 8.7-.1 13.1-.1-1.8.7-3.5.9-5.3 1.1-18.5 2.4-35.5 9-51.5 18.5-30.2 17.9-54.5 42.2-75.1 70.4-.3.4-.4.9-.7 1.3 14.5 5.3 24 17.3 36.1 25.6.2-.1.3-.2.4-.4l1.2-2.7c12.2-26.9 27-52.3 46.7-74.5 16.7-18.8 38-25.3 62.5-20 5.9 1.3 11.4 4.4 17.2 6.8 2.3-1.4 5.1-3.2 8-4.7 8.4-4.3 17.4-7 26.7-9 14.7-3.1 29.5-4.9 44.5-1.3v-.5c-.5-.4-1.2-.8-1.7-1.4zM316.7 397.6c-39.4-33-22.8-19.5-42.7-35.6-.8.9 0-.2-1.9 3-11.2 19.1-25.5 35.3-44 47.6-10.3 6.8-21.5 11.8-34.1 11.8-21.6 0-38.2-9.5-49.4-27.8-12-19.5-13.3-40.7-8.2-62.6 7.8-33.8 30.1-55.2 38.6-64.3-18.7-6.2-33 1.7-46.4 13.9.8-13.9 4.3-26.2 11.8-37.3-24.3 10.6-45.9 25-64.8 43.9-.3-5.8 5.4-43.7 5.6-44.7.3-2.7-.6-5.3-3-7.4-24.2 24.7-44.5 51.8-56.1 84.6 7.4-5.9 14.9-11.4 23.6-16.2-8.3 22.3-19.6 52.8-7.8 101.1 4.6 19 11.9 36.8 24.1 52.3 2.9 3.7 6.3 6.9 9.5 10.3.2-.2.4-.3.6-.5-1.4-7-2.2-14.1-1.5-21.9 2.2 3.2 3.9 6 5.9 8.6 12.6 16 28.7 27.4 47.2 35.6 25 11.3 51.1 13.3 77.9 8.6 54.9-9.7 90.7-48.6 116-98.8 1-1.8.6-2.9-.9-4.2zm172-46.4c-9.5-3.1-22.2-4.2-28.7-2.9 9.9 4 14.1 6.6 18.8 12 12.6 14.4 10.4 34.7-5.4 45.6-11.7 8.1-24.9 10.5-38.9 9.1-1.2-.1-2.3-.4-3-.6 2.8-3.7 6-7 8.1-10.8 9.4-16.8 5.4-42.1-8.7-56.1-2.1-2.1-4.6-3.9-7-5.9-.3 1.3-.1 2.1.1 2.8 4.2 16.6-8.1 32.4-24.8 31.8-7.6-.3-13.9-3.8-19.6-8.5-19.5-16.1-39.1-32.1-58.5-48.3-5.9-4.9-12.5-8.1-20.1-8.7-4.6-.4-9.3-.6-13.9-.9-5.9-.4-8.8-2.8-10.4-8.4-.9-3.4-1.5-6.8-2.2-10.2-1.5-8.1-6.2-13-14.3-14.2-4.4-.7-8.9-1-13.3-1.5-13-1.4-19.8-7.4-22.6-20.3-5 11-1.6 22.4 7.3 29.9 4.5 3.8 9.3 7.3 13.8 11.2 4.6 3.8 7.4 8.7 7.9 14.8.4 4.7.8 9.5 1.8 14.1 2.2 10.6 8.9 18.4 17 25.1 16.5 13.7 33 27.3 49.5 41.1 17.9 15 13.9 32.8 13 56-.9 22.9 12.2 42.9 33.5 51.2 1 .4 2 .6 3.6 1.1-15.7-18.2-10.1-44.1.7-52.3.3 2.2.4 4.3.9 6.4 9.4 44.1 45.4 64.2 85 56.9 16-2.9 30.6-8.9 42.9-19.8 2-1.8 3.7-4.1 5.9-6.5-19.3 4.6-35.8.1-50.9-10.6.7-.3 1.3-.3 1.9-.3 21.3 1.8 40.6-3.4 57-17.4 19.5-16.6 26.6-42.9 17.4-66-8.3-20.1-23.6-32.3-43.8-38.9zM99.4 179.3c-5.3-9.2-13.2-15.6-22.1-21.3 13.7-.5 26.6.2 39.6 3.7-7-12.2-8.5-24.7-5-38.7 5.3 11.9 13.7 20.1 23.6 26.8 19.7 13.2 35.7 19.6 46.7 30.2 3.4 3.3 6.3 7.1 9.6 10.9-.8-2.1-1.4-4.1-2.2-6-5-10.6-13-18.6-22.6-25-1.8-1.2-2.8-2.5-3.4-4.5-3.3-12.5-3-25.1-.7-37.6 1-5.5 2.8-10.9 4.5-16.3.8-2.4 2.3-4.6 4-6.6.6 6.9 0 25.5 19.6 46 10.8 11.3 22.4 21.9 33.9 32.7 9 8.5 18.3 16.7 25.5 26.8 1.1 1.6 2.2 3.3 3.8 4.7-5-13-14.2-24.1-24.2-33.8-9.6-9.3-19.4-18.4-29.2-27.4-3.3-3-4.6-6.7-5.1-10.9-1.2-10.4 0-20.6 4.3-30.2.5-1 1.1-2 1.9-3.3.5 4.2.6 7.9 1.4 11.6 4.8 23.1 20.4 36.3 49.3 63.5 10 9.4 19.3 19.2 25.6 31.6 4.8 9.3 7.3 19 5.7 29.6-.1.6.5 1.7 1.1 2 6.2 2.6 10 6.9 9.7 14.3 7.7-2.6 12.5-8 16.4-14.5 4.2 20.2-9.1 50.3-27.2 58.7.4-4.5 5-23.4-16.5-27.7-6.8-1.3-12.8-1.3-22.9-2.1 4.7-9 10.4-20.6.5-22.4-24.9-4.6-52.8 1.9-57.8 4.6 8.2.4 16.3 1 23.5 3.3-2 6.5-4 12.7-5.8 18.9-1.9 6.5 2.1 14.6 9.3 9.6 1.2-.9 2.3-1.9 3.3-2.7-3.1 17.9-2.9 15.9-2.8 18.3.3 10.2 9.5 7.8 15.7 7.3-2.5 11.8-29.5 27.3-45.4 25.8 7-4.7 12.7-10.3 15.9-17.9-6.5.8-12.9 1.6-19.2 2.4l-.3-.9c4.7-3.4 8-7.8 10.2-13.1 8.7-21.1-3.6-38-25-39.9-9.1-.8-17.8.8-25.9 5.5 6.2-15.6 17.2-26.6 32.6-34.5-15.2-4.3-8.9-2.7-24.6-6.3 14.6-9.3 30.2-13.2 46.5-14.6-5.2-3.2-48.1-3.6-70.2 20.9 7.9 1.4 15.5 2.8 23.2 4.2-23.8 7-44 19.7-62.4 35.6 1.1-4.8 2.7-9.5 3.3-14.3.6-4.5.8-9.2.1-13.6-1.5-9.4-8.9-15.1-19.7-16.3-7.9-.9-15.6.1-23.3 1.3-.9.1-1.7.3-2.9 0 15.8-14.8 36-21.7 53.1-33.5 6-4.5 6.8-8.2 3-14.9zm128.4 26.8c3.3 16 12.6 25.5 23.8 24.3-4.6-11.3-12.1-19.5-23.8-24.3z\"],\n    \"d-and-d-beyond\": [640, 512, [], \"f6ca\", \"M313.8 241.5c13.8 0 21-10.1 24.8-17.9-1-1.1-5-4.2-7.4-6.6-2.4 4.3-8.2 10.7-13.9 10.7-10.2 0-15.4-14.7-3.2-26.6-.5-.2-4.3-1.8-8 2.4 0-3 1-5.1 2.1-6.6-3.5 1.3-9.8 5.6-11.4 7.9.2-5.8 1.6-7.5.6-9l-.2-.2s-8.5 5.6-9.3 14.7c0 0 1.1-1.6 2.1-1.9.6-.3 1.3 0 .6 1.9-.2.6-5.8 15.7 5.1 26-.6-1.6-1.9-7.6 2.4-1.9-.3.1 5.8 7.1 15.7 7.1zm52.4-21.1c0-4-4.9-4.4-5.6-4.5 2 3.9.9 7.5.2 9 2.5-.4 5.4-1.6 5.4-4.5zm10.3 5.2c0-6.4-6.2-11.4-13.5-10.7 8 1.3 5.6 13.8-5 11.4 3.7-2.6 3.2-9.9-1.3-12.5 1.4 4.2-3 8.2-7.4 4.6-2.4-1.9-8-6.6-10.6-8.6-2.4-2.1-5.5-1-6.6-1.8-1.3-1.1-.5-3.8-2.2-5-1.6-.8-3-.3-4.8-1-1.6-.6-2.7-1.9-2.6-3.5-2.5 4.4 3.4 6.3 4.5 8.5 1 1.9-.8 4.8 4 8.5 14.8 11.6 9.1 8 10.4 18.1.6 4.3 4.2 6.7 6.4 7.4-2.1-1.9-2.9-6.4 0-9.3 0 13.9 19.2 13.3 23.1 6.4-2.4 1.1-7-.2-9-1.9 7.7 1 14.2-4.1 14.6-10.6zm-39.4-18.4c2 .8 1.6.7 6.4 4.5 10.2-24.5 21.7-15.7 22-15.5 2.2-1.9 9.8-3.8 13.8-2.7-2.4-2.7-7.5-6.2-13.3-6.2-4.7 0-7.4 2.2-8 1.3-.8-1.4 3.2-3.4 3.2-3.4-5.4.2-9.6 6.7-11.2 5.9-1.1-.5 1.4-3.7 1.4-3.7-5.1 2.9-9.3 9.1-10.2 13 4.6-5.8 13.8-9.8 19.7-9-10.5.5-19.5 9.7-23.8 15.8zm242.5 51.9c-20.7 0-40 1.3-50.3 2.1l7.4 8.2v77.2l-7.4 8.2c10.4.8 30.9 2.1 51.6 2.1 42.1 0 59.1-20.7 59.1-48.9 0-29.3-23.2-48.9-60.4-48.9zm-15.1 75.6v-53.3c30.1-3.3 46.8 3.8 46.8 26.3 0 25.6-21.4 30.2-46.8 27zM301.6 181c-1-3.4-.2-6.9 1.1-9.4 1 3 2.6 6.4 7.5 9-.5-2.4-.2-5.6.5-8-1.4-5.4 2.1-9.9 6.4-9.9 6.9 0 8.5 8.8 4.7 14.4 2.1 3.2 5.5 5.6 7.7 7.8 3.2-3.7 5.5-9.5 5.5-13.8 0-8.2-5.5-15.9-16.7-16.5-20-.9-20.2 16.6-20 18.9.5 5.2 3.4 7.8 3.3 7.5zm-.4 6c-.5 1.8-7 3.7-10.2 6.9 4.8-1 7-.2 7.8 1.8.5 1.4-.2 3.4-.5 5.6 1.6-1.8 7-5.5 11-6.2-1-.3-3.4-.8-4.3-.8 2.9-3.4 9.3-4.5 12.8-3.7-2.2-.2-6.7 1.1-8.5 2.6 1.6.3 3 .6 4.3 1.1-2.1.8-4.8 3.4-5.8 6.1 7-5 13.1 5.2 7 8.2.8.2 2.7 0 3.5-.5-.3 1.1-1.9 3-3 3.4 2.9 0 7-1.9 8.2-4.6 0 0-1.8.6-2.6-.2s.3-4.3.3-4.3c-2.3 2.9-3.4-1.3-1.3-4.2-1-.3-3.5-.6-4.6-.5 3.2-1.1 10.4-1.8 11.2-.3.6 1.1-1 3.4-1 3.4 4-.5 8.3 1.1 6.7 5.1 2.9-1.4 5.5-5.9 4.8-10.4-.3 1-1.6 2.4-2.9 2.7.2-1.4-1-2.2-1.9-2.6 1.7-9.6-14.6-14.2-14.1-23.9-1 1.3-1.8 5-.8 7.1 2.7 3.2 8.7 6.7 10.1 12.2-2.6-6.4-15.1-11.4-14.6-20.2-1.6 1.6-2.6 7.8-1.3 11 2.4 1.4 4.5 3.8 4.8 6.1-2.2-5.1-11.4-6.1-13.9-12.2-.6 2.2-.3 5 1 6.7 0 0-2.2-.8-7-.6 1.7.6 5.1 3.5 4.8 5.2zm25.9 7.4c-2.7 0-3.5-2.1-4.2-4.3 3.3 1.3 4.2 4.3 4.2 4.3zm38.9 3.7l-1-.6c-1.1-1-2.9-1.4-4.7-1.4-2.9 0-5.8 1.3-7.5 3.4-.8.8-1.4 1.8-2.1 2.6v15.7c3.5 2.6 7.1-2.9 3-7.2 1.5.3 4.6 2.7 5.1 3.2 0 0 2.6-.5 5-.5 2.1 0 3.9.3 5.6 1.1V196c-1.1.5-2.2 1-2.7 1.4zM79.9 305.9c17.2-4.6 16.2-18 16.2-19.9 0-20.6-24.1-25-37-25H3l8.3 8.6v29.5H0l11.4 14.6V346L3 354.6c61.7 0 73.8 1.5 86.4-5.9 6.7-4 9.9-9.8 9.9-17.6 0-5.1 2.6-18.8-19.4-25.2zm-41.3-27.5c20 0 29.6-.8 29.6 9.1v3c0 12.1-19 8.8-29.6 8.8zm0 59.2V315c12.2 0 32.7-2.3 32.7 8.8v4.5h.2c0 11.2-12.5 9.3-32.9 9.3zm101.2-19.3l23.1.2v-.2l14.1-21.2h-37.2v-14.9h52.4l-14.1-21v-.2l-73.5.2 7.4 8.2v77.1l-7.4 8.2h81.2l14.1-21.2-60.1.2zm214.7-60.1c-73.9 0-77.5 99.3-.3 99.3 77.9 0 74.1-99.3.3-99.3zm-.3 77.5c-37.4 0-36.9-55.3.2-55.3 36.8.1 38.8 55.3-.2 55.3zm-91.3-8.3l44.1-66.2h-41.7l6.1 7.2-20.5 37.2h-.3l-21-37.2 6.4-7.2h-44.9l44.1 65.8.2 19.4-7.7 8.2h42.6l-7.2-8.2zm-28.4-151.3c1.6 1.3 2.9 2.4 2.9 6.6v38.8c0 4.2-.8 5.3-2.7 6.4-.1.1-7.5 4.5-7.9 4.6h35.1c10 0 17.4-1.5 26-8.6-.6-5 .2-9.5.8-12 0-.2-1.8 1.4-2.7 3.5 0-5.7 1.6-15.4 9.6-20.5-.1 0-3.7-.8-9 1.1 2-3.1 10-7.9 10.4-7.9-8.2-26-38-22.9-32.2-22.9-30.9 0-32.6.3-39.9-4 .1.8.5 8.2 9.6 14.9zm21.5 5.5c4.6 0 23.1-3.3 23.1 17.3 0 20.7-18.4 17.3-23.1 17.3zm228.9 79.6l7 8.3V312h-.3c-5.4-14.4-42.3-41.5-45.2-50.9h-31.6l7.4 8.5v76.9l-7.2 8.3h39l-7.4-8.2v-47.4h.3c3.7 10.6 44.5 42.9 48.5 55.6h21.3v-85.2l7.4-8.3zm-106.7-96.1c-32.2 0-32.8.2-39.9-4 .1.7.5 8.3 9.6 14.9 3.1 2 2.9 4.3 2.9 9.5 1.8-1.1 3.8-2.2 6.1-3-1.1 1.1-2.7 2.7-3.5 4.5 1-1.1 7.5-5.1 14.6-3.5-1.6.3-4 1.1-6.1 2.9.1 0 2.1-1.1 7.5-.3v-4.3c4.7 0 23.1-3.4 23.1 17.3 0 20.5-18.5 17.3-19.7 17.3 5.7 4.4 5.8 12 2.2 16.3h.3c33.4 0 36.7-27.3 36.7-34 0-3.8-1.1-32-33.8-33.6z\"],\n    \"dashcube\": [448, 512, [], \"f210\", \"M326.6 104H110.4c-51.1 0-91.2 43.3-91.2 93.5V427c0 50.5 40.1 85 91.2 85h227.2c51.1 0 91.2-34.5 91.2-85V0L326.6 104zM153.9 416.5c-17.7 0-32.4-15.1-32.4-32.8V240.8c0-17.7 14.7-32.5 32.4-32.5h140.7c17.7 0 32 14.8 32 32.5v123.5l51.1 52.3H153.9z\"],\n    \"delicious\": [448, 512, [], \"f1a5\", \"M446.5 68c-.4-1.5-.9-3-1.4-4.5-.9-2.5-2-4.8-3.3-7.1-1.4-2.4-3-4.8-4.7-6.9-2.1-2.5-4.4-4.8-6.9-6.8-1.1-.9-2.2-1.7-3.3-2.5-1.3-.9-2.6-1.7-4-2.4-1.8-1-3.6-1.8-5.5-2.5-1.7-.7-3.5-1.3-5.4-1.7-3.8-1-7.9-1.5-12-1.5H48C21.5 32 0 53.5 0 80v352c0 4.1.5 8.2 1.5 12 2 7.7 5.8 14.6 11 20.3 1 1.1 2.1 2.2 3.3 3.3 5.7 5.2 12.6 9 20.3 11 3.8 1 7.9 1.5 12 1.5h352c26.5 0 48-21.5 48-48V80c-.1-4.1-.6-8.2-1.6-12zM416 432c0 8.8-7.2 16-16 16H224V256H32V80c0-8.8 7.2-16 16-16h176v192h192z\"],\n    \"deploydog\": [512, 512, [], \"f38e\", \"M382.2 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.6 0-33.2 16.4-33.2 32.6zM188.5 136h51.7v239.6h-51.7v-20.7c-19.8 24.8-52.8 24.1-73.8 14.7-26.2-11.7-44.3-38.1-44.3-71.8 0-29.8 14.8-57.9 43.3-70.8 20.2-9.1 52.7-10.6 74.8 12.9V136zm-64.7 161.8c0 18.2 13.6 33.5 33.2 33.5 19.8 0 33.2-16.4 33.2-32.9 0-17.1-13.7-33.2-33.2-33.2-19.7 0-33.2 16.4-33.2 32.6zM448 96c17.5 0 32 14.4 32 32v256c0 17.5-14.4 32-32 32H64c-17.5 0-32-14.4-32-32V128c0-17.5 14.4-32 32-32h384m0-32H64C28.8 64 0 92.8 0 128v256c0 35.2 28.8 64 64 64h384c35.2 0 64-28.8 64-64V128c0-35.2-28.8-64-64-64z\"],\n    \"deskpro\": [480, 512, [], \"f38f\", \"M205.9 512l31.1-38.4c12.3-.2 25.6-1.4 36.5-6.6 38.9-18.6 38.4-61.9 38.3-63.8-.1-5-.8-4.4-28.9-37.4H362c-.2 50.1-7.3 68.5-10.2 75.7-9.4 23.7-43.9 62.8-95.2 69.4-8.7 1.1-32.8 1.2-50.7 1.1zm200.4-167.7c38.6 0 58.5-13.6 73.7-30.9l-175.5-.3-17.4 31.3 119.2-.1zm-43.6-223.9v168.3h-73.5l-32.7 55.5H250c-52.3 0-58.1-56.5-58.3-58.9-1.2-13.2-21.3-11.6-20.1 1.8 1.4 15.8 8.8 40 26.4 57.1h-91c-25.5 0-110.8-26.8-107-114V16.9C0 .9 9.7.3 15 .1h82c.2 0 .3.1.5.1 4.3-.4 50.1-2.1 50.1 43.7 0 13.3 20.2 13.4 20.2 0 0-18.2-5.5-32.8-15.8-43.7h84.2c108.7-.4 126.5 79.4 126.5 120.2zm-132.5 56l64 29.3c13.3-45.5-42.2-71.7-64-29.3z\"],\n    \"dev\": [448, 512, [], \"f6cc\", \"M120.12 208.29c-3.88-2.9-7.77-4.35-11.65-4.35H91.03v104.47h17.45c3.88 0 7.77-1.45 11.65-4.35 3.88-2.9 5.82-7.25 5.82-13.06v-69.65c-.01-5.8-1.96-10.16-5.83-13.06zM404.1 32H43.9C19.7 32 .06 51.59 0 75.8v360.4C.06 460.41 19.7 480 43.9 480h360.2c24.21 0 43.84-19.59 43.9-43.8V75.8c-.06-24.21-19.7-43.8-43.9-43.8zM154.2 291.19c0 18.81-11.61 47.31-48.36 47.25h-46.4V172.98h47.38c35.44 0 47.36 28.46 47.37 47.28l.01 70.93zm100.68-88.66H201.6v38.42h32.57v29.57H201.6v38.41h53.29v29.57h-62.18c-11.16.29-20.44-8.53-20.72-19.69V193.7c-.27-11.15 8.56-20.41 19.71-20.69h63.19l-.01 29.52zm103.64 115.29c-13.2 30.75-36.85 24.63-47.44 0l-38.53-144.8h32.57l29.71 113.72 29.57-113.72h32.58l-38.46 144.8z\"],\n    \"deviantart\": [320, 512, [], \"f1bd\", \"M320 93.2l-98.2 179.1 7.4 9.5H320v127.7H159.1l-13.5 9.2-43.7 84c-.3 0-8.6 8.6-9.2 9.2H0v-93.2l93.2-179.4-7.4-9.2H0V102.5h156l13.5-9.2 43.7-84c.3 0 8.6-8.6 9.2-9.2H320v93.1z\"],\n    \"dhl\": [640, 512, [], \"f790\", \"M238 301.2h58.7L319 271h-58.7L238 301.2zM0 282.9v6.4h81.8l4.7-6.4H0zM172.9 271c-8.7 0-6-3.6-4.6-5.5 2.8-3.8 7.6-10.4 10.4-14.1 2.8-3.7 2.8-5.9-2.8-5.9h-51l-41.1 55.8h100.1c33.1 0 51.5-22.5 57.2-30.3h-68.2zm317.5-6.9l39.3-53.4h-62.2l-39.3 53.4h62.2zM95.3 271H0v6.4h90.6l4.7-6.4zm111-26.6c-2.8 3.8-7.5 10.4-10.3 14.2-1.4 2-4.1 5.5 4.6 5.5h45.6s7.3-10 13.5-18.4c8.4-11.4.7-35-29.2-35H112.6l-20.4 27.8h111.4c5.6 0 5.5 2.2 2.7 5.9zM0 301.2h73.1l4.7-6.4H0v6.4zm323 0h58.7L404 271h-58.7c-.1 0-22.3 30.2-22.3 30.2zm222 .1h95v-6.4h-90.3l-4.7 6.4zm22.3-30.3l-4.7 6.4H640V271h-72.7zm-13.5 18.3H640v-6.4h-81.5l-4.7 6.4zm-164.2-78.6l-22.5 30.6h-26.2l22.5-30.6h-58.7l-39.3 53.4H409l39.3-53.4h-58.7zm33.5 60.3s-4.3 5.9-6.4 8.7c-7.4 10-.9 21.6 23.2 21.6h94.3l22.3-30.3H423.1z\"],\n    \"diaspora\": [512, 512, [], \"f791\", \"M251.64 354.55c-1.4 0-88 119.9-88.7 119.9S76.34 414 76 413.25s86.6-125.7 86.6-127.4c0-2.2-129.6-44-137.6-47.1-1.3-.5 31.4-101.8 31.7-102.1.6-.7 144.4 47 145.5 47 .4 0 .9-.6 1-1.3.4-2 1-148.6 1.7-149.6.8-1.2 104.5-.7 105.1-.3 1.5 1 3.5 156.1 6.1 156.1 1.4 0 138.7-47 139.3-46.3.8.9 31.9 102.2 31.5 102.6-.9.9-140.2 47.1-140.6 48.8-.3 1.4 82.8 122.1 82.5 122.9s-85.5 63.5-86.3 63.5c-1-.2-89-125.5-90.9-125.5z\"],\n    \"digg\": [512, 512, [], \"f1a6\", \"M81.7 172.3H0v174.4h132.7V96h-51v76.3zm0 133.4H50.9v-92.3h30.8v92.3zm297.2-133.4v174.4h81.8v28.5h-81.8V416H512V172.3H378.9zm81.8 133.4h-30.8v-92.3h30.8v92.3zm-235.6 41h82.1v28.5h-82.1V416h133.3V172.3H225.1v174.4zm51.2-133.3h30.8v92.3h-30.8v-92.3zM153.3 96h51.3v51h-51.3V96zm0 76.3h51.3v174.4h-51.3V172.3z\"],\n    \"digital-ocean\": [512, 512, [], \"f391\", \"M87 481.8h73.7v-73.6H87zM25.4 346.6v61.6H87v-61.6zm466.2-169.7c-23-74.2-82.4-133.3-156.6-156.6C164.9-32.8 8 93.7 8 255.9h95.8c0-101.8 101-180.5 208.1-141.7 39.7 14.3 71.5 46.1 85.8 85.7 39.1 107-39.7 207.8-141.4 208v.3h-.3V504c162.6 0 288.8-156.8 235.6-327.1zm-235.3 231v-95.3h-95.6v95.6H256v-.3z\"],\n    \"discord\": [448, 512, [], \"f392\", \"M297.216 243.2c0 15.616-11.52 28.416-26.112 28.416-14.336 0-26.112-12.8-26.112-28.416s11.52-28.416 26.112-28.416c14.592 0 26.112 12.8 26.112 28.416zm-119.552-28.416c-14.592 0-26.112 12.8-26.112 28.416s11.776 28.416 26.112 28.416c14.592 0 26.112-12.8 26.112-28.416.256-15.616-11.52-28.416-26.112-28.416zM448 52.736V512c-64.494-56.994-43.868-38.128-118.784-107.776l13.568 47.36H52.48C23.552 451.584 0 428.032 0 398.848V52.736C0 23.552 23.552 0 52.48 0h343.04C424.448 0 448 23.552 448 52.736zm-72.96 242.688c0-82.432-36.864-149.248-36.864-149.248-36.864-27.648-71.936-26.88-71.936-26.88l-3.584 4.096c43.52 13.312 63.744 32.512 63.744 32.512-60.811-33.329-132.244-33.335-191.232-7.424-9.472 4.352-15.104 7.424-15.104 7.424s21.248-20.224 67.328-33.536l-2.56-3.072s-35.072-.768-71.936 26.88c0 0-36.864 66.816-36.864 149.248 0 0 21.504 37.12 78.08 38.912 0 0 9.472-11.52 17.152-21.248-32.512-9.728-44.8-30.208-44.8-30.208 3.766 2.636 9.976 6.053 10.496 6.4 43.21 24.198 104.588 32.126 159.744 8.96 8.96-3.328 18.944-8.192 29.44-15.104 0 0-12.8 20.992-46.336 30.464 7.68 9.728 16.896 20.736 16.896 20.736 56.576-1.792 78.336-38.912 78.336-38.912z\"],\n    \"discourse\": [448, 512, [], \"f393\", \"M225.9 32C103.3 32 0 130.5 0 252.1 0 256 .1 480 .1 480l225.8-.2c122.7 0 222.1-102.3 222.1-223.9C448 134.3 348.6 32 225.9 32zM224 384c-19.4 0-37.9-4.3-54.4-12.1L88.5 392l22.9-75c-9.8-18.1-15.4-38.9-15.4-61 0-70.7 57.3-128 128-128s128 57.3 128 128-57.3 128-128 128z\"],\n    \"dochub\": [416, 512, [], \"f394\", \"M397.9 160H256V19.6L397.9 160zM304 192v130c0 66.8-36.5 100.1-113.3 100.1H96V84.8h94.7c12 0 23.1.8 33.1 2.5v-84C212.9 1.1 201.4 0 189.2 0H0v512h189.2C329.7 512 400 447.4 400 318.1V192h-96z\"],\n    \"docker\": [640, 512, [], \"f395\", \"M349.9 236.3h-66.1v-59.4h66.1v59.4zm0-204.3h-66.1v60.7h66.1V32zm78.2 144.8H362v59.4h66.1v-59.4zm-156.3-72.1h-66.1v60.1h66.1v-60.1zm78.1 0h-66.1v60.1h66.1v-60.1zm276.8 100c-14.4-9.7-47.6-13.2-73.1-8.4-3.3-24-16.7-44.9-41.1-63.7l-14-9.3-9.3 14c-18.4 27.8-23.4 73.6-3.7 103.8-8.7 4.7-25.8 11.1-48.4 10.7H2.4c-8.7 50.8 5.8 116.8 44 162.1 37.1 43.9 92.7 66.2 165.4 66.2 157.4 0 273.9-72.5 328.4-204.2 21.4.4 67.6.1 91.3-45.2 1.5-2.5 6.6-13.2 8.5-17.1l-13.3-8.9zm-511.1-27.9h-66v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm78.1 0h-66.1v59.4h66.1v-59.4zm-78.1-72.1h-66.1v60.1h66.1v-60.1z\"],\n    \"draft2digital\": [480, 512, [], \"f396\", \"M480 398.1l-144-82.2v64.7h-91.3c30.8-35 81.8-95.9 111.8-149.3 35.2-62.6 16.1-123.4-12.8-153.3-4.4-4.6-62.2-62.9-166-41.2-59.1 12.4-89.4 43.4-104.3 67.3-13.1 20.9-17 39.8-18.2 47.7-5.5 33 19.4 67.1 56.7 67.1 31.7 0 57.3-25.7 57.3-57.4 0-27.1-19.7-52.1-48-56.8 1.8-7.3 17.7-21.1 26.3-24.7 41.1-17.3 78 5.2 83.3 33.5 8.3 44.3-37.1 90.4-69.7 127.6C84.5 328.1 18.3 396.8 0 415.9l336-.1V480zM369.9 371l47.1 27.2-47.1 27.2zM134.2 161.4c0 12.4-10 22.4-22.4 22.4s-22.4-10-22.4-22.4 10-22.4 22.4-22.4 22.4 10.1 22.4 22.4zM82.5 380.5c25.6-27.4 97.7-104.7 150.8-169.9 35.1-43.1 40.3-82.4 28.4-112.7-7.4-18.8-17.5-30.2-24.3-35.7 45.3 2.1 68 23.4 82.2 38.3 0 0 42.4 48.2 5.8 113.3-37 65.9-110.9 147.5-128.5 166.7z\"],\n    \"dribbble\": [512, 512, [], \"f17d\", \"M256 8C119.252 8 8 119.252 8 256s111.252 248 248 248 248-111.252 248-248S392.748 8 256 8zm163.97 114.366c29.503 36.046 47.369 81.957 47.835 131.955-6.984-1.477-77.018-15.682-147.502-6.818-5.752-14.041-11.181-26.393-18.617-41.614 78.321-31.977 113.818-77.482 118.284-83.523zM396.421 97.87c-3.81 5.427-35.697 48.286-111.021 76.519-34.712-63.776-73.185-116.168-79.04-124.008 67.176-16.193 137.966 1.27 190.061 47.489zm-230.48-33.25c5.585 7.659 43.438 60.116 78.537 122.509-99.087 26.313-186.36 25.934-195.834 25.809C62.38 147.205 106.678 92.573 165.941 64.62zM44.17 256.323c0-2.166.043-4.322.108-6.473 9.268.19 111.92 1.513 217.706-30.146 6.064 11.868 11.857 23.915 17.174 35.949-76.599 21.575-146.194 83.527-180.531 142.306C64.794 360.405 44.17 310.73 44.17 256.323zm81.807 167.113c22.127-45.233 82.178-103.622 167.579-132.756 29.74 77.283 42.039 142.053 45.189 160.638-68.112 29.013-150.015 21.053-212.768-27.882zm248.38 8.489c-2.171-12.886-13.446-74.897-41.152-151.033 66.38-10.626 124.7 6.768 131.947 9.055-9.442 58.941-43.273 109.844-90.795 141.978z\"],\n    \"dribbble-square\": [448, 512, [], \"f397\", \"M90.2 228.2c8.9-42.4 37.4-77.7 75.7-95.7 3.6 4.9 28 38.8 50.7 79-64 17-120.3 16.8-126.4 16.7zM314.6 154c-33.6-29.8-79.3-41.1-122.6-30.6 3.8 5.1 28.6 38.9 51 80 48.6-18.3 69.1-45.9 71.6-49.4zM140.1 364c40.5 31.6 93.3 36.7 137.3 18-2-12-10-53.8-29.2-103.6-55.1 18.8-93.8 56.4-108.1 85.6zm98.8-108.2c-3.4-7.8-7.2-15.5-11.1-23.2C159.6 253 93.4 252.2 87.4 252c0 1.4-.1 2.8-.1 4.2 0 35.1 13.3 67.1 35.1 91.4 22.2-37.9 67.1-77.9 116.5-91.8zm34.9 16.3c17.9 49.1 25.1 89.1 26.5 97.4 30.7-20.7 52.5-53.6 58.6-91.6-4.6-1.5-42.3-12.7-85.1-5.8zm-20.3-48.4c4.8 9.8 8.3 17.8 12 26.8 45.5-5.7 90.7 3.4 95.2 4.4-.3-32.3-11.8-61.9-30.9-85.1-2.9 3.9-25.8 33.2-76.3 53.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 176c0-88.2-71.8-160-160-160S64 167.8 64 256s71.8 160 160 160 160-71.8 160-160z\"],\n    \"dropbox\": [528, 512, [], \"f16b\", \"M264.4 116.3l-132 84.3 132 84.3-132 84.3L0 284.1l132.3-84.3L0 116.3 132.3 32l132.1 84.3zM131.6 395.7l132-84.3 132 84.3-132 84.3-132-84.3zm132.8-111.6l132-84.3-132-83.6L395.7 32 528 116.3l-132.3 84.3L528 284.8l-132.3 84.3-131.3-85z\"],\n    \"drupal\": [448, 512, [], \"f1a9\", \"M319.5 114.7c-22.2-14-43.5-19.5-64.7-33.5-13-8.8-31.3-30-46.5-48.3-2.7 29.3-11.5 41.2-22 49.5-21.3 17-34.8 22.2-53.5 32.3C117 123 32 181.5 32 290.5 32 399.7 123.8 480 225.8 480 327.5 480 416 406 416 294c0-112.3-83-171-96.5-179.3zm2.5 325.6c-20.1 20.1-90.1 28.7-116.7 4.2-4.8-4.8.3-12 6.5-12 0 0 17 13.3 51.5 13.3 27 0 46-7.7 54.5-14 6.1-4.6 8.4 4.3 4.2 8.5zm-54.5-52.6c8.7-3.6 29-3.8 36.8 1.3 4.1 2.8 16.1 18.8 6.2 23.7-8.4 4.2-1.2-15.7-26.5-15.7-14.7 0-19.5 5.2-26.7 11-7 6-9.8 8-12.2 4.7-6-8.2 15.9-22.3 22.4-25zM360 405c-15.2-1-45.5-48.8-65-49.5-30.9-.9-104.1 80.7-161.3 42-38.8-26.6-14.6-104.8 51.8-105.2 49.5-.5 83.8 49 108.5 48.5 21.3-.3 61.8-41.8 81.8-41.8 48.7 0 23.3 109.3-15.8 106z\"],\n    \"dyalog\": [416, 512, [], \"f399\", \"M0 32v119.2h64V96h107.2C284.6 96 352 176.2 352 255.9 352 332 293.4 416 171.2 416H0v64h171.2C331.9 480 416 367.3 416 255.9c0-58.7-22.1-113.4-62.3-154.3C308.9 56 245.7 32 171.2 32H0z\"],\n    \"earlybirds\": [480, 512, [], \"f39a\", \"M313.2 47.5c1.2-13 21.3-14 36.6-8.7.9.3 26.2 9.7 19 15.2-27.9-7.4-56.4 18.2-55.6-6.5zm-201 6.9c30.7-8.1 62 20 61.1-7.1-1.3-14.2-23.4-15.3-40.2-9.6-1 .3-28.7 10.5-20.9 16.7zM319.4 160c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-159.7 0c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm318.5 163.2c-9.9 24-40.7 11-63.9-1.2-13.5 69.1-58.1 111.4-126.3 124.2.3.9-2-.1 24 1 33.6 1.4 63.8-3.1 97.4-8-19.8-13.8-11.4-37.1-9.8-38.1 1.4-.9 14.7 1.7 21.6 11.5 8.6-12.5 28.4-14.8 30.2-13.6 1.6 1.1 6.6 20.9-6.9 34.6 4.7-.9 8.2-1.6 9.8-2.1 2.6-.8 17.7 11.3 3.1 13.3-14.3 2.3-22.6 5.1-47.1 10.8-45.9 10.7-85.9 11.8-117.7 12.8l1 11.6c3.8 18.1-23.4 24.3-27.6 6.2.8 17.9-27.1 21.8-28.4-1l-.5 5.3c-.7 18.4-28.4 17.9-28.3-.6-7.5 13.5-28.1 6.8-26.4-8.5l1.2-12.4c-36.7.9-59.7 3.1-61.8 3.1-20.9 0-20.9-31.6 0-31.6 2.4 0 27.7 1.3 63.2 2.8-61.1-15.5-103.7-55-114.9-118.2-25 12.8-57.5 26.8-68.2.8-10.5-25.4 21.5-42.6 66.8-73.4.7-6.6 1.6-13.3 2.7-19.8-14.4-19.6-11.6-36.3-16.1-60.4-16.8 2.4-23.2-9.1-23.6-23.1.3-7.3 2.1-14.9 2.4-15.4 1.1-1.8 10.1-2 12.7-2.6 6-31.7 50.6-33.2 90.9-34.5 19.7-21.8 45.2-41.5 80.9-48.3C203.3 29 215.2 8.5 216.2 8c1.7-.8 21.2 4.3 26.3 23.2 5.2-8.8 18.3-11.4 19.6-10.7 1.1.6 6.4 15-4.9 25.9 40.3 3.5 72.2 24.7 96 50.7 36.1 1.5 71.8 5.9 77.1 34 2.7.6 11.6.8 12.7 2.6.3.5 2.1 8.1 2.4 15.4-.5 13.9-6.8 25.4-23.6 23.1-3.2 17.3-2.7 32.9-8.7 47.7 2.4 11.7 4 23.8 4.8 36.4 37 25.4 70.3 42.5 60.3 66.9zM207.4 159.9c.9-44-37.9-42.2-78.6-40.3-21.7 1-38.9 1.9-45.5 13.9-11.4 20.9 5.9 92.9 23.2 101.2 9.8 4.7 73.4 7.9 86.3-7.1 8.2-9.4 15-49.4 14.6-67.7zm52 58.3c-4.3-12.4-6-30.1-15.3-32.7-2-.5-9-.5-11 0-10 2.8-10.8 22.1-17 37.2 15.4 0 19.3 9.7 23.7 9.7 4.3 0 6.3-11.3 19.6-14.2zm135.7-84.7c-6.6-12.1-24.8-12.9-46.5-13.9-40.2-1.9-78.2-3.8-77.3 40.3-.5 18.3 5 58.3 13.2 67.8 13 14.9 76.6 11.8 86.3 7.1 15.8-7.6 36.5-78.9 24.3-101.3z\"],\n    \"ebay\": [640, 512, [], \"f4f4\", \"M606 189.5l-54.8 109.9-54.9-109.9h-37.5l10.9 20.6c-11.5-19-35.9-26-63.3-26-31.8 0-67.9 8.7-71.5 43.1h33.7c1.4-13.8 15.7-21.8 35-21.8 26 0 41 9.6 41 33v3.4c-12.7 0-28 .1-41.7.4-42.4.9-69.6 10-76.7 34.4 1-5.2 1.5-10.6 1.5-16.2 0-52.1-39.7-76.2-75.4-76.2-21.3 0-43 5.5-58.7 24.2v-80.6h-32.1v169.5c0 10.3-.6 22.9-1.1 33.1h31.5c.7-6.3 1.1-12.9 1.1-19.5 13.6 16.6 35.4 24.9 58.7 24.9 36.9 0 64.9-21.9 73.3-54.2-.5 2.8-.7 5.8-.7 9 0 24.1 21.1 45 60.6 45 26.6 0 45.8-5.7 61.9-25.5 0 6.6.3 13.3 1.1 20.2h29.8c-.7-8.2-1-17.5-1-26.8v-65.6c0-9.3-1.7-17.2-4.8-23.8l61.5 116.1-28.5 54.1h35.9L640 189.5zM243.7 313.8c-29.6 0-50.2-21.5-50.2-53.8 0-32.4 20.6-53.8 50.2-53.8 29.8 0 50.2 21.4 50.2 53.8 0 32.3-20.4 53.8-50.2 53.8zm200.9-47.3c0 30-17.9 48.4-51.6 48.4-25.1 0-35-13.4-35-25.8 0-19.1 18.1-24.4 47.2-25.3 13.1-.5 27.6-.6 39.4-.6zm-411.9 1.6h128.8v-8.5c0-51.7-33.1-75.4-78.4-75.4-56.8 0-83 30.8-83 77.6 0 42.5 25.3 74 82.5 74 31.4 0 68-11.7 74.4-46.1h-33.1c-12 35.8-87.7 36.7-91.2-21.6zm95-21.4H33.3c6.9-56.6 92.1-54.7 94.4 0z\"],\n    \"edge\": [512, 512, [], \"f282\", \"M25.714 228.163c.111-.162.23-.323.342-.485-.021.162-.045.323-.065.485h-.277zm460.572 15.508c0-44.032-7.754-84.465-28.801-122.405C416.498 47.879 343.912 8.001 258.893 8.001 118.962 7.724 40.617 113.214 26.056 227.679c42.429-61.312 117.073-121.376 220.375-124.966 0 0 109.666 0 99.419 104.957H169.997c6.369-37.386 18.554-58.986 34.339-78.926-75.048 34.893-121.85 96.096-120.742 188.315.83 71.448 50.124 144.836 120.743 171.976 83.357 31.847 192.776 7.2 240.132-21.324V363.307c-80.864 56.494-270.871 60.925-272.255-67.572h314.073v-52.064z\"],\n    \"elementor\": [448, 512, [], \"f430\", \"M425.6 32H22.4C10 32 0 42 0 54.4v403.2C0 470 10 480 22.4 480h403.2c12.4 0 22.4-10 22.4-22.4V54.4C448 42 438 32 425.6 32M164.3 355.5h-39.8v-199h39.8v199zm159.3 0H204.1v-39.8h119.5v39.8zm0-79.6H204.1v-39.8h119.5v39.8zm0-79.7H204.1v-39.8h119.5v39.8z\"],\n    \"ello\": [496, 512, [], \"f5f1\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm143.84 285.2C375.31 358.51 315.79 404.8 248 404.8s-127.31-46.29-143.84-111.6c-1.65-7.44 2.48-15.71 9.92-17.36 7.44-1.65 15.71 2.48 17.36 9.92 14.05 52.91 62 90.11 116.56 90.11s102.51-37.2 116.56-90.11c1.65-7.44 9.92-12.4 17.36-9.92 7.44 1.65 12.4 9.92 9.92 17.36z\"],\n    \"ember\": [640, 512, [], \"f423\", \"M639.9 254.6c-1.1-10.7-10.7-6.8-10.7-6.8s-15.6 12.1-29.3 10.7c-13.7-1.3-9.4-32-9.4-32s3-28.1-5.1-30.4c-8.1-2.4-18 7.3-18 7.3s-12.4 13.7-18.3 31.2l-1.6.5s1.9-30.6-.3-37.6c-1.6-3.5-16.4-3.2-18.8 3s-14.2 49.2-15 67.2c0 0-23.1 19.6-43.3 22.8s-25-9.4-25-9.4 54.8-15.3 52.9-59.1-44.2-27.6-49-24c-4.6 3.5-29.4 18.4-36.6 59.7-.2 1.4-.7 7.5-.7 7.5s-21.2 14.2-33 18c0 0 33-55.6-7.3-80.9-11.4-6.8-21.3-.5-27.2 5.3 13.6-17.3 46.4-64.2 36.9-105.2-5.8-24.4-18-27.1-29.2-23.1-17 6.7-23.5 16.7-23.5 16.7s-22 32-27.1 79.5-12.6 105.1-12.6 105.1-10.5 10.2-20.2 10.7-5.4-28.7-5.4-28.7 7.5-44.6 7-52.1-1.1-11.6-9.9-14.2c-8.9-2.7-18.5 8.6-18.5 8.6s-25.5 38.7-27.7 44.6l-1.3 2.4-1.3-1.6s18-52.7.8-53.5-28.5 18.8-28.5 18.8-19.6 32.8-20.4 36.5l-1.3-1.6s8.1-38.2 6.4-47.6c-1.6-9.4-10.5-7.5-10.5-7.5s-11.3-1.3-14.2 5.9-13.7 55.3-15 70.7c0 0-28.2 20.2-46.8 20.4-18.5.3-16.7-11.8-16.7-11.8s68-23.3 49.4-69.2c-8.3-11.8-18-15.5-31.7-15.3-13.7.3-30.3 8.6-41.3 33.3-5.3 11.8-6.8 23-7.8 31.5 0 0-12.3 2.4-18.8-2.9s-10 0-10 0-11.2 14-.1 18.3 28.1 6.1 28.1 6.1c1.6 7.5 6.2 19.5 19.6 29.7 20.2 15.3 58.8-1.3 58.8-1.3l15.9-8.8s.5 14.6 12.1 16.7 16.4 1 36.5-47.9c11.8-25 12.6-23.6 12.6-23.6l1.3-.3s-9.1 46.8-5.6 59.7C187.7 319.4 203 318 203 318s8.3 2.4 15-21.2 19.6-49.9 19.6-49.9h1.6s-5.6 48.1 3 63.7 30.9 5.3 30.9 5.3 15.6-7.8 18-10.2c0 0 18.5 15.8 44.6 12.9 58.3-11.5 79.1-25.9 79.1-25.9s10 24.4 41.1 26.7c35.5 2.7 54.8-18.6 54.8-18.6s-.3 13.5 12.1 18.6 20.7-22.8 20.7-22.8l20.7-57.2h1.9s1.1 37.3 21.5 43.2 47-13.7 47-13.7 6.4-3.5 5.3-14.3zm-578 5.3c.8-32 21.8-45.9 29-39 7.3 7 4.6 22-9.1 31.4-13.7 9.5-19.9 7.6-19.9 7.6zm272.8-123.8s19.1-49.7 23.6-25.5-40 96.2-40 96.2c.5-16.2 16.4-70.7 16.4-70.7zm22.8 138.4c-12.6 33-43.3 19.6-43.3 19.6s-3.5-11.8 6.4-44.9 33.3-20.2 33.3-20.2 16.2 12.4 3.6 45.5zm84.6-14.6s-3-10.5 8.1-30.6c11-20.2 19.6-9.1 19.6-9.1s9.4 10.2-1.3 25.5-26.4 14.2-26.4 14.2z\"],\n    \"empire\": [496, 512, [], \"f1d1\", \"M287.6 54.2c-10.8-2.2-22.1-3.3-33.5-3.6V32.4c78.1 2.2 146.1 44 184.6 106.6l-15.8 9.1c-6.1-9.7-12.7-18.8-20.2-27.1l-18 15.5c-26-29.6-61.4-50.7-101.9-58.4l4.8-23.9zM53.4 322.4l23-7.7c-6.4-18.3-10-38.2-10-58.7s3.3-40.4 9.7-58.7l-22.7-7.7c3.6-10.8 8.3-21.3 13.6-31l-15.8-9.1C34 181 24.1 217.5 24.1 256s10 75 27.1 106.6l15.8-9.1c-5.3-10-9.7-20.3-13.6-31.1zM213.1 434c-40.4-8-75.8-29.1-101.9-58.7l-18 15.8c-7.5-8.6-14.4-17.7-20.2-27.4l-16 9.4c38.5 62.3 106.8 104.3 184.9 106.6v-18.3c-11.3-.3-22.7-1.7-33.5-3.6l4.7-23.8zM93.3 120.9l18 15.5c26-29.6 61.4-50.7 101.9-58.4l-4.7-23.8c10.8-2.2 22.1-3.3 33.5-3.6V32.4C163.9 34.6 95.9 76.4 57.4 139l15.8 9.1c6-9.7 12.6-18.9 20.1-27.2zm309.4 270.2l-18-15.8c-26 29.6-61.4 50.7-101.9 58.7l4.7 23.8c-10.8 1.9-22.1 3.3-33.5 3.6v18.3c78.1-2.2 146.4-44.3 184.9-106.6l-16.1-9.4c-5.7 9.7-12.6 18.8-20.1 27.4zM496 256c0 137-111 248-248 248S0 393 0 256 111 8 248 8s248 111 248 248zm-12.2 0c0-130.1-105.7-235.8-235.8-235.8S12.2 125.9 12.2 256 117.9 491.8 248 491.8 483.8 386.1 483.8 256zm-39-106.6l-15.8 9.1c5.3 9.7 10 20.2 13.6 31l-22.7 7.7c6.4 18.3 9.7 38.2 9.7 58.7s-3.6 40.4-10 58.7l23 7.7c-3.9 10.8-8.3 21-13.6 31l15.8 9.1C462 331 471.9 294.5 471.9 256s-9.9-75-27.1-106.6zm-183 177.7c16.3-3.3 30.4-11.6 40.7-23.5l51.2 44.8c11.9-13.6 21.3-29.3 27.1-46.8l-64.2-22.1c2.5-7.5 3.9-15.2 3.9-23.5s-1.4-16.1-3.9-23.5l64.5-22.1c-6.1-17.4-15.5-33.2-27.4-46.8l-51.2 44.8c-10.2-11.9-24.4-20.5-40.7-23.8l13.3-66.4c-8.6-1.9-17.7-2.8-27.1-2.8-9.4 0-18.5.8-27.1 2.8l13.3 66.4c-16.3 3.3-30.4 11.9-40.7 23.8l-51.2-44.8c-11.9 13.6-21.3 29.3-27.4 46.8l64.5 22.1c-2.5 7.5-3.9 15.2-3.9 23.5s1.4 16.1 3.9 23.5l-64.2 22.1c5.8 17.4 15.2 33.2 27.1 46.8l51.2-44.8c10.2 11.9 24.4 20.2 40.7 23.5l-13.3 66.7c8.6 1.7 17.7 2.8 27.1 2.8 9.4 0 18.5-1.1 27.1-2.8l-13.3-66.7z\"],\n    \"envira\": [448, 512, [], \"f299\", \"M0 32c477.6 0 366.6 317.3 367.1 366.3L448 480h-26l-70.4-71.2c-39 4.2-124.4 34.5-214.4-37C47 300.3 52 214.7 0 32zm79.7 46c-49.7-23.5-5.2 9.2-5.2 9.2 45.2 31.2 66 73.7 90.2 119.9 31.5 60.2 79 139.7 144.2 167.7 65 28 34.2 12.5 6-8.5-28.2-21.2-68.2-87-91-130.2-31.7-60-61-118.6-144.2-158.1z\"],\n    \"erlang\": [640, 512, [], \"f39d\", \"M87.2 53.5H0v405h100.4c-49.7-52.6-78.8-125.3-78.7-212.1-.1-76.7 24-142.7 65.5-192.9zm238.2 9.7c-45.9.1-85.1 33.5-89.2 83.2h169.9c-1.1-49.7-34.5-83.1-80.7-83.2zm230.7-9.6h.3l-.1-.1zm.3 0c31.4 42.7 48.7 97.5 46.2 162.7.5 6 .5 11.7 0 24.1H230.2c-.2 109.7 38.9 194.9 138.6 195.3 68.5-.3 118-51 151.9-106.1l96.4 48.2c-17.4 30.9-36.5 57.8-57.9 80.8H640v-405z\"],\n    \"ethereum\": [320, 512, [], \"f42e\", \"M311.9 260.8L160 353.6 8 260.8 160 0l151.9 260.8zM160 383.4L8 290.6 160 512l152-221.4-152 92.8z\"],\n    \"etsy\": [384, 512, [], \"f2d7\", \"M384 348c-1.75 10.75-13.75 110-15.5 132-117.879-4.299-219.895-4.743-368.5 0v-25.5c45.457-8.948 60.627-8.019 61-35.25 1.793-72.322 3.524-244.143 0-322-1.029-28.46-12.13-26.765-61-36v-25.5c73.886 2.358 255.933 8.551 362.999-3.75-3.5 38.25-7.75 126.5-7.75 126.5H332C320.947 115.665 313.241 68 277.25 68h-137c-10.25 0-10.75 3.5-10.75 9.75V241.5c58 .5 88.5-2.5 88.5-2.5 29.77-.951 27.56-8.502 40.75-65.251h25.75c-4.407 101.351-3.91 61.829-1.75 160.25H257c-9.155-40.086-9.065-61.045-39.501-61.5 0 0-21.5-2-88-2v139c0 26 14.25 38.25 44.25 38.25H263c63.636 0 66.564-24.996 98.751-99.75H384z\"],\n    \"evernote\": [384, 512, [], \"f839\", \"M120.82 132.21c1.6 22.31-17.55 21.59-21.61 21.59-68.93 0-73.64-1-83.58 3.34-.56.22-.74 0-.37-.37L123.79 46.45c.38-.37.6-.22.38.37-4.35 9.99-3.35 15.09-3.35 85.39zm79 308c-14.68-37.08 13-76.93 52.52-76.62 17.49 0 22.6 23.21 7.95 31.42-6.19 3.3-24.95 1.74-25.14 19.2-.05 17.09 19.67 25 31.2 24.89A45.64 45.64 0 0 0 312 393.45v-.08c0-11.63-7.79-47.22-47.54-55.34-7.72-1.54-65-6.35-68.35-50.52-3.74 16.93-17.4 63.49-43.11 69.09-8.74 1.94-69.68 7.64-112.92-36.77 0 0-18.57-15.23-28.23-57.95-3.38-15.75-9.28-39.7-11.14-62 0-18 11.14-30.45 25.07-32.2 81 0 90 2.32 101-7.8 9.82-9.24 7.8-15.5 7.8-102.78 1-8.3 7.79-30.81 53.41-24.14 6 .86 31.91 4.18 37.48 30.64l64.26 11.15c20.43 3.71 70.94 7 80.6 57.94 22.66 121.09 8.91 238.46 7.8 238.46C362.15 485.53 267.06 480 267.06 480c-18.95-.23-54.25-9.4-67.27-39.83zm80.94-204.84c-1 1.92-2.2 6 .85 7 14.09 4.93 39.75 6.84 45.88 5.53 3.11-.25 3.05-4.43 2.48-6.65-3.53-21.85-40.83-26.5-49.24-5.92z\"],\n    \"expeditedssl\": [496, 512, [], \"f23e\", \"M248 43.4C130.6 43.4 35.4 138.6 35.4 256S130.6 468.6 248 468.6 460.6 373.4 460.6 256 365.4 43.4 248 43.4zm-97.4 132.9c0-53.7 43.7-97.4 97.4-97.4s97.4 43.7 97.4 97.4v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6c0-82.1-124-82.1-124 0v26.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-26.6zM389.7 380c0 9.7-8 17.7-17.7 17.7H124c-9.7 0-17.7-8-17.7-17.7V238.3c0-9.7 8-17.7 17.7-17.7h248c9.7 0 17.7 8 17.7 17.7V380zm-248-137.3v132.9c0 2.5-1.9 4.4-4.4 4.4h-8.9c-2.5 0-4.4-1.9-4.4-4.4V242.7c0-2.5 1.9-4.4 4.4-4.4h8.9c2.5 0 4.4 1.9 4.4 4.4zm141.7 48.7c0 13-7.2 24.4-17.7 30.4v31.6c0 5-3.9 8.9-8.9 8.9h-17.7c-5 0-8.9-3.9-8.9-8.9v-31.6c-10.5-6.1-17.7-17.4-17.7-30.4 0-19.7 15.8-35.4 35.4-35.4s35.5 15.8 35.5 35.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 478.3C121 486.3 17.7 383 17.7 256S121 25.7 248 25.7 478.3 129 478.3 256 375 486.3 248 486.3z\"],\n    \"facebook\": [512, 512, [], \"f09a\", \"M504 256C504 119 393 8 256 8S8 119 8 256c0 123.78 90.69 226.38 209.25 245V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.28c-30.8 0-40.41 19.12-40.41 38.73V256h68.78l-11 71.69h-57.78V501C413.31 482.38 504 379.78 504 256z\"],\n    \"facebook-f\": [320, 512, [], \"f39e\", \"M279.14 288l14.22-92.66h-88.91v-60.13c0-25.35 12.42-50.06 52.24-50.06h40.42V6.26S260.43 0 225.36 0c-73.22 0-121.08 44.38-121.08 124.72v70.62H22.89V288h81.39v224h100.17V288z\"],\n    \"facebook-messenger\": [512, 512, [], \"f39f\", \"M256.55 8C116.52 8 8 110.34 8 248.57c0 72.3 29.71 134.78 78.07 177.94 8.35 7.51 6.63 11.86 8.05 58.23A19.92 19.92 0 0 0 122 502.31c52.91-23.3 53.59-25.14 62.56-22.7C337.85 521.8 504 423.7 504 248.57 504 110.34 396.59 8 256.55 8zm149.24 185.13l-73 115.57a37.37 37.37 0 0 1-53.91 9.93l-58.08-43.47a15 15 0 0 0-18 0l-78.37 59.44c-10.46 7.93-24.16-4.6-17.11-15.67l73-115.57a37.36 37.36 0 0 1 53.91-9.93l58.06 43.46a15 15 0 0 0 18 0l78.41-59.38c10.44-7.98 24.14 4.54 17.09 15.62z\"],\n    \"facebook-square\": [448, 512, [], \"f082\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h137.25V327.69h-63V256h63v-54.64c0-62.15 37-96.48 93.67-96.48 27.14 0 55.52 4.84 55.52 4.84v61h-31.27c-30.81 0-40.42 19.12-40.42 38.73V256h68.78l-11 71.69h-57.78V480H400a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48z\"],\n    \"fantasy-flight-games\": [512, 512, [], \"f6dc\", \"M256 32.86L32.86 256 256 479.14 479.14 256 256 32.86zM88.34 255.83c1.96-2 11.92-12.3 96.49-97.48 41.45-41.75 86.19-43.77 119.77-18.69 24.63 18.4 62.06 58.9 62.15 59 .68.74 1.07 2.86.58 3.38-11.27 11.84-22.68 23.54-33.5 34.69-34.21-32.31-40.52-38.24-48.51-43.95-17.77-12.69-41.4-10.13-56.98 5.1-2.17 2.13-1.79 3.43.12 5.35 2.94 2.95 28.1 28.33 35.09 35.78-11.95 11.6-23.66 22.97-35.69 34.66-12.02-12.54-24.48-25.53-36.54-38.11-21.39 21.09-41.69 41.11-61.85 60.99a42569.01 42569.01 0 0 1-41.13-40.72zm234.82 101.6c-35.49 35.43-78.09 38.14-106.99 20.47-22.08-13.5-39.38-32.08-72.93-66.84 12.05-12.37 23.79-24.42 35.37-36.31 33.02 31.91 37.06 36.01 44.68 42.09 18.48 14.74 42.52 13.67 59.32-1.8 3.68-3.39 3.69-3.64.14-7.24-10.59-10.73-21.19-21.44-31.77-32.18-1.32-1.34-3.03-2.48-.8-4.69 10.79-10.71 21.48-21.52 32.21-32.29.26-.26.65-.38 1.91-1.07 12.37 12.87 24.92 25.92 37.25 38.75 21.01-20.73 41.24-40.68 61.25-60.42 13.68 13.4 27.13 26.58 40.86 40.03-20.17 20.86-81.68 82.71-100.5 101.5zM256 0L0 256l256 256 256-256L256 0zM16 256L256 16l240 240-240 240L16 256z\"],\n    \"fedex\": [640, 512, [], \"f797\", \"M586 284.5l53.3-59.9h-62.4l-21.7 24.8-22.5-24.8H414v-16h56.1v-48.1H318.9V236h-.5c-9.6-11-21.5-14.8-35.4-14.8-28.4 0-49.8 19.4-57.3 44.9-18-59.4-97.4-57.6-121.9-14v-24.2H49v-26.2h60v-41.1H0V345h49v-77.5h48.9c-1.5 5.7-2.3 11.8-2.3 18.2 0 73.1 102.6 91.4 130.2 23.7h-42c-14.7 20.9-45.8 8.9-45.8-14.6h85.5c3.7 30.5 27.4 56.9 60.1 56.9 14.1 0 27-6.9 34.9-18.6h.5V345h212.2l22.1-25 22.3 25H640l-54-60.5zm-446.7-16.6c6.1-26.3 41.7-25.6 46.5 0h-46.5zm153.4 48.9c-34.6 0-34-62.8 0-62.8 32.6 0 34.5 62.8 0 62.8zm167.8 19.1h-94.4V169.4h95v30.2H405v33.9h55.5v28.1h-56.1v44.7h56.1v29.6zm-45.9-39.8v-24.4h56.1v-44l50.7 57-50.7 57v-45.6h-56.1zm138.6 10.3l-26.1 29.5H489l45.6-51.2-45.6-51.2h39.7l26.6 29.3 25.6-29.3h38.5l-45.4 51 46 51.4h-40.5l-26.3-29.5z\"],\n    \"fedora\": [448, 512, [], \"f798\", \"M225 32C101.3 31.7.8 131.7.4 255.4L0 425.7a53.6 53.6 0 0 0 53.6 53.9l170.2.4c123.7.3 224.3-99.7 224.6-223.4S348.7 32.3 225 32zm169.8 157.2L333 126.6c2.3-4.7 3.8-9.2 3.8-14.3v-1.6l55.2 56.1a101 101 0 0 1 2.8 22.4zM331 94.3a106.06 106.06 0 0 1 58.5 63.8l-54.3-54.6a26.48 26.48 0 0 0-4.2-9.2zM118.1 247.2a49.66 49.66 0 0 0-7.7 11.4l-8.5-8.5a85.78 85.78 0 0 1 16.2-2.9zM97 251.4l11.8 11.9-.9 8a34.74 34.74 0 0 0 2.4 12.5l-27-27.2a80.6 80.6 0 0 1 13.7-5.2zm-18.2 7.4l38.2 38.4a53.17 53.17 0 0 0-14.1 4.7L67.6 266a107 107 0 0 1 11.2-7.2zm-15.2 9.8l35.3 35.5a67.25 67.25 0 0 0-10.5 8.5L53.5 278a64.33 64.33 0 0 1 10.1-9.4zm-13.3 12.3l34.9 35a56.84 56.84 0 0 0-7.7 11.4l-35.8-35.9c2.8-3.8 5.7-7.2 8.6-10.5zm-11 14.3l36.4 36.6a48.29 48.29 0 0 0-3.6 15.2l-39.5-39.8a99.81 99.81 0 0 1 6.7-12zm-8.8 16.3l41.3 41.8a63.47 63.47 0 0 0 6.7 26.2L25.8 326c1.4-4.9 2.9-9.6 4.7-14.5zm-7.9 43l61.9 62.2a31.24 31.24 0 0 0-3.6 14.3v1.1l-55.4-55.7a88.27 88.27 0 0 1-2.9-21.9zm5.3 30.7l54.3 54.6a28.44 28.44 0 0 0 4.2 9.2 106.32 106.32 0 0 1-58.5-63.8zm-5.3-37a80.69 80.69 0 0 1 2.1-17l72.2 72.5a37.59 37.59 0 0 0-9.9 8.7zm253.3-51.8l-42.6-.1-.1 56c-.2 69.3-64.4 115.8-125.7 102.9-5.7 0-19.9-8.7-19.9-24.2a24.89 24.89 0 0 1 24.5-24.6c6.3 0 6.3 1.6 15.7 1.6a55.91 55.91 0 0 0 56.1-55.9l.1-47c0-4.5-4.5-9-8.9-9l-33.6-.1c-32.6-.1-32.5-49.4.1-49.3l42.6.1.1-56a105.18 105.18 0 0 1 105.6-105 86.35 86.35 0 0 1 20.2 2.3c11.2 1.8 19.9 11.9 19.9 24 0 15.5-14.9 27.8-30.3 23.9-27.4-5.9-65.9 14.4-66 54.9l-.1 47a8.94 8.94 0 0 0 8.9 9l33.6.1c32.5.2 32.4 49.5-.2 49.4zm23.5-.3a35.58 35.58 0 0 0 7.6-11.4l8.5 8.5a102 102 0 0 1-16.1 2.9zm21-4.2L308.6 280l.9-8.1a34.74 34.74 0 0 0-2.4-12.5l27 27.2a74.89 74.89 0 0 1-13.7 5.3zm18-7.4l-38-38.4c4.9-1.1 9.6-2.4 13.7-4.7l36.2 35.9c-3.8 2.5-7.9 5-11.9 7.2zm15.5-9.8l-35.3-35.5a61.06 61.06 0 0 0 10.5-8.5l34.9 35a124.56 124.56 0 0 1-10.1 9zm13.2-12.3l-34.9-35a63.18 63.18 0 0 0 7.7-11.4l35.8 35.9a130.28 130.28 0 0 1-8.6 10.5zm11-14.3l-36.4-36.6a48.29 48.29 0 0 0 3.6-15.2l39.5 39.8a87.72 87.72 0 0 1-6.7 12zm13.5-30.9a140.63 140.63 0 0 1-4.7 14.3L345.6 190a58.19 58.19 0 0 0-7.1-26.2zm1-5.6l-71.9-72.1a32 32 0 0 0 9.9-9.2l64.3 64.7a90.93 90.93 0 0 1-2.3 16.6z\"],\n    \"figma\": [384, 512, [], \"f799\", \"M277 170.7A85.35 85.35 0 0 0 277 0H106.3a85.3 85.3 0 0 0 0 170.6 85.35 85.35 0 0 0 0 170.7 85.35 85.35 0 1 0 85.3 85.4v-256zm0 0a85.3 85.3 0 1 0 85.3 85.3 85.31 85.31 0 0 0-85.3-85.3z\"],\n    \"firefox\": [480, 512, [], \"f269\", \"M478.1 235.3c-.7-4.5-1.4-7.1-1.4-7.1s-1.8 2-4.7 5.9c-.9-10.7-2.8-21.2-5.8-31.6-3.7-12.9-8.5-25.4-14.5-37.4-3.8-8-8.2-15.6-13.3-22.8-1.8-2.7-3.7-5.4-5.6-7.9-8.8-14.4-19-23.3-30.7-40-7.6-12.8-12.9-26.9-15.4-41.6-3.2 8.9-5.7 18-7.4 27.3-12.1-12.2-22.5-20.8-28.9-26.7C319.4 24.2 323 9.1 323 9.1S264.7 74.2 289.9 142c8.7 23 23.8 43.1 43.4 57.9 24.4 20.2 50.8 36 64.7 76.6-11.2-21.3-28.1-39.2-48.8-51.5 6.2 14.7 9.4 30.6 9.3 46.5 0 61-49.6 110.5-110.6 110.4-8.3 0-16.5-.9-24.5-2.8-9.5-1.8-18.7-4.9-27.4-9.3-12.9-7.8-24-18.1-32.8-30.3l-.2-.3 2 .7c4.6 1.6 9.2 2.8 14 3.7 18.7 4 38.3 1.7 55.6-6.6 17.5-9.7 28-16.9 36.6-14h.2c8.4 2.7 15-5.5 9-14-10.4-13.4-27.4-20-44.2-17-17.5 2.5-33.5 15-56.4 2.9-1.5-.8-2.9-1.6-4.3-2.5-1.6-.9 4.9 1.3 3.4.3-5-2.5-9.8-5.4-14.4-8.6-.3-.3 3.5 1.1 3.1.8-5.9-4-11-9.2-15-15.2-4.1-7.4-4.5-16.4-1-24.1 2.1-3.8 5.4-6.9 9.3-8.7 3 1.5 4.8 2.6 4.8 2.6s-1.3-2.5-2.1-3.8c.3-.1.5 0 .8-.2 2.6 1.1 8.3 4 11.4 5.8 2.1 1.1 3.8 2.7 5.2 4.7 0 0 1-.5.3-2.7-1.1-2.7-2.9-5-5.4-6.6h.2c2.3 1.2 4.5 2.6 6.6 4.1 1.9-4.4 2.8-9.2 2.6-14 .2-2.6-.2-5.3-1.1-7.8-.8-1.6.5-2.2 1.9-.5-.2-1.3-.7-2.5-1.2-3.7v-.1s.8-1.1 1.2-1.5c1-1 2.1-1.9 3.4-2.7 7.2-4.5 14.8-8.4 22.7-11.6 6.4-2.8 11.7-4.9 12.8-5.6 1.6-1 3.1-2.2 4.5-3.5 5.3-4.5 9-10.8 10.2-17.7.1-.9.2-1.8.3-2.8v-1.5c-.9-3.5-6.9-6.1-38.4-9.1-11.1-1.8-20-10.1-22.5-21.1v-.1c6-15.7 16.8-29.1 30.8-38.3.8-.7-3.2.2-2.4-.5 2.7-1.3 5.4-2.5 8.2-3.5 1.4-.6-6-3.4-12.6-2.7-4 .2-8 1.2-11.7 2.8 1.6-1.3 6.2-3.1 5.1-3.1-8.4 1.6-16.5 4.7-23.9 9 0-.8.1-1.5.5-2.2-5.9 2.5-11 6.5-15 11.5.1-.9.2-1.8.2-2.7-2.7 2-5.2 4.3-7.3 6.9l-.1.1c-17.4-6.7-36.3-8.3-54.6-4.7l-.2-.1h.2c-3.8-3.1-7.1-6.7-9.7-10.9l-.2.1-.4-.2c-1.2-1.8-2.4-3.8-3.7-6-.9-1.6-1.8-3.4-2.7-5.2 0-.1-.1-.2-.2-.2-.4 0-.6 1.7-.9 1.3v-.1c-3.2-8.3-4.7-17.2-4.4-26.2l-.2.1c-5.1 3.5-9 8.6-11.1 14.5-.9 2.1-1.6 3.3-2.2 4.5v-.5c.1-1.1.6-3.3.5-3.1s-.2.3-.3.4c-1.5 1.7-2.9 3.7-3.9 5.8-.9 1.9-1.7 3.9-2.3 5.9-.1.3 0-.3 0-1s.1-2 0-1.7l-.3.7c-6.7 14.9-10.9 30.8-12.4 47.1-.4 2.8-.6 5.6-.5 8.3v.2c-4.8 5.2-9 11-12.7 17.1-12.1 20.4-21.1 42.5-26.8 65.6 4-8.8 8.8-17.2 14.3-25.1C5.5 228.5 0 257.4 0 286.6c1.8-8.6 4.2-17 7-25.3-1.7 34.5 4.9 68.9 19.4 100.3 19.4 43.5 51.6 80 92.3 104.7 16.6 11.2 34.7 19.9 53.8 25.8 2.5.9 5.1 1.8 7.7 2.7-.8-.3-1.6-.7-2.4-1 22.6 6.8 46.2 10.3 69.8 10.3 83.7 0 111.3-31.9 113.8-35 4.1-3.7 7.5-8.2 9.9-13.3 1.6-.7 3.2-1.4 4.9-2.1l1-.5 1.9-.9c12.6-5.9 24.5-13.4 35.3-22.1 16.3-11.7 27.9-28.7 32.9-48.1 3-7.1 3.1-15 .4-22.2.9-1.4 1.7-2.8 2.7-4.3 18-28.9 28.2-61.9 29.6-95.9v-2.8c0-7.3-.6-14.5-1.9-21.6zm-299-97.6c-.4 1.1-.9 2.3-1.3 3.5.4-1.2.8-2.3 1.3-3.5z\"],\n    \"first-order\": [448, 512, [], \"f2b0\", \"M12.9 229.2c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4h-.2zM224 96.6c-7.1 0-14.6.6-21.4 1.7l3.7 67.4-22-64c-14.3 3.7-27.7 9.4-40 16.6l29.4 61.4-45.1-50.9c-11.4 8.9-21.7 19.1-30.6 30.9l50.6 45.4-61.1-29.7c-7.1 12.3-12.9 25.7-16.6 40l64.3 22.6-68-4c-.9 7.1-1.4 14.6-1.4 22s.6 14.6 1.4 21.7l67.7-4-64 22.6c3.7 14.3 9.4 27.7 16.6 40.3l61.1-29.7L97.7 352c8.9 11.7 19.1 22.3 30.9 30.9l44.9-50.9-29.5 61.4c12.3 7.4 25.7 13.1 40 16.9l22.3-64.6-4 68c7.1 1.1 14.6 1.7 21.7 1.7 7.4 0 14.6-.6 21.7-1.7l-4-68.6 22.6 65.1c14.3-4 27.7-9.4 40-16.9L274.9 332l44.9 50.9c11.7-8.9 22-19.1 30.6-30.9l-50.6-45.1 61.1 29.4c7.1-12.3 12.9-25.7 16.6-40.3l-64-22.3 67.4 4c1.1-7.1 1.4-14.3 1.4-21.7s-.3-14.9-1.4-22l-67.7 4 64-22.3c-3.7-14.3-9.1-28-16.6-40.3l-60.9 29.7 50.6-45.4c-8.9-11.7-19.1-22-30.6-30.9l-45.1 50.9 29.4-61.1c-12.3-7.4-25.7-13.1-40-16.9L241.7 166l4-67.7c-7.1-1.2-14.3-1.7-21.7-1.7zM443.4 128v256L224 512 4.6 384V128L224 0l219.4 128zm-17.1 10.3L224 20.9 21.7 138.3v235.1L224 491.1l202.3-117.7V138.3zM224 37.1l187.7 109.4v218.9L224 474.9 36.3 365.4V146.6L224 37.1zm0 50.9c-92.3 0-166.9 75.1-166.9 168 0 92.6 74.6 167.7 166.9 167.7 92 0 166.9-75.1 166.9-167.7 0-92.9-74.9-168-166.9-168z\"],\n    \"first-order-alt\": [496, 512, [], \"f50a\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 488.21C115.34 496.21 7.79 388.66 7.79 256S115.34 15.79 248 15.79 488.21 123.34 488.21 256 380.66 496.21 248 496.21zm0-459.92C126.66 36.29 28.29 134.66 28.29 256S126.66 475.71 248 475.71 467.71 377.34 467.71 256 369.34 36.29 248 36.29zm0 431.22c-116.81 0-211.51-94.69-211.51-211.51S131.19 44.49 248 44.49 459.51 139.19 459.51 256 364.81 467.51 248 467.51zm186.23-162.98a191.613 191.613 0 0 1-20.13 48.69l-74.13-35.88 61.48 54.82a193.515 193.515 0 0 1-37.2 37.29l-54.8-61.57 35.88 74.27a190.944 190.944 0 0 1-48.63 20.23l-27.29-78.47 4.79 82.93c-8.61 1.18-17.4 1.8-26.33 1.8s-17.72-.62-26.33-1.8l4.76-82.46-27.15 78.03a191.365 191.365 0 0 1-48.65-20.2l35.93-74.34-54.87 61.64a193.85 193.85 0 0 1-37.22-37.28l61.59-54.9-74.26 35.93a191.638 191.638 0 0 1-20.14-48.69l77.84-27.11-82.23 4.76c-1.16-8.57-1.78-17.32-1.78-26.21 0-9 .63-17.84 1.82-26.51l82.38 4.77-77.94-27.16a191.726 191.726 0 0 1 20.23-48.67l74.22 35.92-61.52-54.86a193.85 193.85 0 0 1 37.28-37.22l54.76 61.53-35.83-74.17a191.49 191.49 0 0 1 48.65-20.13l26.87 77.25-4.71-81.61c8.61-1.18 17.39-1.8 26.32-1.8s17.71.62 26.32 1.8l-4.74 82.16 27.05-77.76c17.27 4.5 33.6 11.35 48.63 20.17l-35.82 74.12 54.72-61.47a193.13 193.13 0 0 1 37.24 37.23l-61.45 54.77 74.12-35.86a191.515 191.515 0 0 1 20.2 48.65l-77.81 27.1 82.24-4.75c1.19 8.66 1.82 17.5 1.82 26.49 0 8.88-.61 17.63-1.78 26.19l-82.12-4.75 77.72 27.09z\"],\n    \"firstdraft\": [384, 512, [], \"f3a1\", \"M384 192h-64v128H192v128H0v-25.6h166.4v-128h128v-128H384V192zm-25.6 38.4v128h-128v128H64V512h192V384h128V230.4h-25.6zm25.6 192h-89.6V512H320v-64h64v-25.6zM0 0v384h128V256h128V128h128V0H0z\"],\n    \"flickr\": [448, 512, [], \"f16e\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM144.5 319c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5zm159 0c-35.1 0-63.5-28.4-63.5-63.5s28.4-63.5 63.5-63.5 63.5 28.4 63.5 63.5-28.4 63.5-63.5 63.5z\"],\n    \"flipboard\": [448, 512, [], \"f44d\", \"M0 32v448h448V32H0zm358.4 179.2h-89.6v89.6h-89.6v89.6H89.6V121.6h268.8v89.6z\"],\n    \"fly\": [384, 512, [], \"f417\", \"M197.8 427.8c12.9 11.7 33.7 33.3 33.2 50.7 0 .8-.1 1.6-.1 2.5-1.8 19.8-18.8 31.1-39.1 31-25-.1-39.9-16.8-38.7-35.8 1-16.2 20.5-36.7 32.4-47.6 2.3-2.1 2.7-2.7 5.6-3.6 3.4 0 3.9.3 6.7 2.8zM331.9 67.3c-16.3-25.7-38.6-40.6-63.3-52.1C243.1 4.5 214-.2 192 0c-44.1 0-71.2 13.2-81.1 17.3C57.3 45.2 26.5 87.2 28 158.6c7.1 82.2 97 176 155.8 233.8 1.7 1.6 4.5 4.5 6.2 5.1l3.3.1c2.1-.7 1.8-.5 3.5-2.1 52.3-49.2 140.7-145.8 155.9-215.7 7-39.2 3.1-72.5-20.8-112.5zM186.8 351.9c-28-51.1-65.2-130.7-69.3-189-3.4-47.5 11.4-131.2 69.3-136.7v325.7zM328.7 180c-16.4 56.8-77.3 128-118.9 170.3C237.6 298.4 275 217 277 158.4c1.6-45.9-9.8-105.8-48-131.4 88.8 18.3 115.5 98.1 99.7 153z\"],\n    \"font-awesome\": [448, 512, [], \"f2b4\", \"M397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm-45.4 284.3c0 4.2-3.6 6-7.8 7.8-16.7 7.2-34.6 13.7-53.8 13.7-26.9 0-39.4-16.7-71.7-16.7-23.3 0-47.8 8.4-67.5 17.3-1.2.6-2.4.6-3.6 1.2V385c0 1.8 0 3.6-.6 4.8v1.2c-2.4 8.4-10.2 14.3-19.1 14.3-11.3 0-20.3-9-20.3-20.3V166.4c-7.8-6-13.1-15.5-13.1-26.3 0-18.5 14.9-33.5 33.5-33.5 18.5 0 33.5 14.9 33.5 33.5 0 10.8-4.8 20.3-13.1 26.3v18.5c1.8-.6 3.6-1.2 5.4-2.4 18.5-7.8 40.6-14.3 61.5-14.3 22.7 0 40.6 6 60.9 13.7 4.2 1.8 8.4 2.4 13.1 2.4 22.7 0 47.8-16.1 53.8-16.1 4.8 0 9 3.6 9 7.8v140.3z\"],\n    \"font-awesome-alt\": [448, 512, [], \"f35c\", \"M339.3 171.2c-6 0-29.9 15.5-52.6 15.5-4.2 0-8.4-.6-12.5-2.4-19.7-7.8-37-13.7-59.1-13.7-20.3 0-41.8 6.6-59.7 13.7-1.8.6-3.6 1.2-4.8 1.8v-17.9c7.8-6 12.5-14.9 12.5-25.7 0-17.9-14.3-32.3-32.3-32.3s-32.3 14.3-32.3 32.3c0 10.2 4.8 19.7 12.5 25.7v212.1c0 10.8 9 19.7 19.7 19.7 9 0 16.1-6 18.5-13.7V385c.6-1.8.6-3 .6-4.8V336c1.2 0 2.4-.6 3-1.2 19.7-8.4 43-16.7 65.7-16.7 31.1 0 43 16.1 69.3 16.1 18.5 0 36.4-6.6 52-13.7 4.2-1.8 7.2-3.6 7.2-7.8V178.3c1.8-4.1-2.3-7.1-7.7-7.1zM397.8 32H50.2C22.7 32 0 54.7 0 82.2v347.6C0 457.3 22.7 480 50.2 480h347.6c27.5 0 50.2-22.7 50.2-50.2V82.2c0-27.5-22.7-50.2-50.2-50.2zm14.3 397.7c0 7.8-6.6 14.3-14.3 14.3H50.2c-7.8 0-14.3-6.6-14.3-14.3V82.2c0-7.8 6.6-14.3 14.3-14.3h347.6v-.1c7.8 0 14.3 6.6 14.3 14.3z\"],\n    \"font-awesome-flag\": [448, 512, [], \"f425\", \"M444.373 359.424c0 7.168-6.144 10.24-13.312 13.312-28.672 12.288-59.392 23.552-92.16 23.552-46.08 0-67.584-28.672-122.88-28.672-39.936 0-81.92 14.336-115.712 29.696-2.048 1.024-4.096 1.024-6.144 2.048v77.824c0 21.405-16.122 34.816-33.792 34.816-19.456 0-34.816-15.36-34.816-34.816V102.4C12.245 92.16 3.029 75.776 3.029 57.344 3.029 25.6 28.629 0 60.373 0s57.344 25.6 57.344 57.344c0 18.432-8.192 34.816-22.528 45.056v31.744c4.124-1.374 58.768-28.672 114.688-28.672 65.27 0 97.676 27.648 126.976 27.648 38.912 0 81.92-27.648 92.16-27.648 8.192 0 15.36 6.144 15.36 13.312v240.64z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"fonticons\": [448, 512, [], \"f280\", \"M0 32v448h448V32zm187 140.9c-18.4 0-19 9.9-19 27.4v23.3c0 2.4-3.5 4.4-.6 4.4h67.4l-11.1 37.3H168v112.9c0 5.8-2 6.7 3.2 7.3l43.5 4.1v25.1H84V389l21.3-2c5.2-.6 6.7-2.3 6.7-7.9V267.7c0-2.3-2.9-2.3-5.8-2.3H84V228h28v-21c0-49.6 26.5-70 77.3-70 34.1 0 64.7 8.2 64.7 52.8l-50.7 6.1c.3-18.7-4.4-23-16.3-23zm74.3 241.8v-25.1l20.4-2.6c5.2-.6 7.6-1.7 7.6-7.3V271.8c0-4.1-2.9-6.7-6.7-7.9l-24.2-6.4 6.7-29.5h80.2v151.7c0 5.8-2.6 6.4 2.9 7.3l15.7 2.6v25.1zm80.8-255.5l9 33.2-7.3 7.3-31.2-16.6-31.2 16.6-7.3-7.3 9-33.2-21.8-24.2 3.5-9.6h27.7l15.5-28h9.3l15.5 28h27.7l3.5 9.6z\"],\n    \"fonticons-fi\": [384, 512, [], \"f3a2\", \"M114.4 224h92.4l-15.2 51.2h-76.4V433c0 8-2.8 9.2 4.4 10l59.6 5.6V483H0v-35.2l29.2-2.8c7.2-.8 9.2-3.2 9.2-10.8V278.4c0-3.2-4-3.2-8-3.2H0V224h38.4v-28.8c0-68 36.4-96 106-96 46.8 0 88.8 11.2 88.8 72.4l-69.6 8.4c.4-25.6-6-31.6-22.4-31.6-25.2 0-26 13.6-26 37.6v32c0 3.2-4.8 6-.8 6zM384 483H243.2v-34.4l28-3.6c7.2-.8 10.4-2.4 10.4-10V287c0-5.6-4-9.2-9.2-10.8l-33.2-8.8 9.2-40.4h110v208c0 8-3.6 8.8 4 10l21.6 3.6V483zm-30-347.2l12.4 45.6-10 10-42.8-22.8-42.8 22.8-10-10 12.4-45.6-30-36.4 4.8-10h38L307.2 51H320l21.2 38.4h38l4.8 13.2-30 33.2z\"],\n    \"fort-awesome\": [512, 512, [], \"f286\", \"M489.2 287.9h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6V146.2c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32h-36.6v-32c0-6-8-4.6-11.7-4.6v-38c8.3-2 17.1-3.4 25.7-3.4 10.9 0 20.9 4.3 31.4 4.3 4.6 0 27.7-1.1 27.7-8v-60c0-2.6-2-4.6-4.6-4.6-5.1 0-15.1 4.3-24 4.3-9.7 0-20.9-4.3-32.6-4.3-8 0-16 1.1-23.7 2.9v-4.9c5.4-2.6 9.1-8.3 9.1-14.3 0-20.7-31.4-20.8-31.4 0 0 6 3.7 11.7 9.1 14.3v111.7c-3.7 0-11.7-1.4-11.7 4.6v32h-36.6v-32c0-2.6-2-4.6-4.6-4.6h-27.4c-2.6 0-4.6 2-4.6 4.6v32H128v-32c0-2.6-2-4.6-4.6-4.6H96c-2.6 0-4.6 2-4.6 4.6v178.3H54.8v-32c0-2.6-2-4.6-4.6-4.6H22.8c-2.6 0-4.6 2-4.6 4.6V512h182.9v-96c0-72.6 109.7-72.6 109.7 0v96h182.9V292.5c.1-2.6-1.9-4.6-4.5-4.6zm-288.1-4.5c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64zm146.4 0c0 2.6-2 4.6-4.6 4.6h-27.4c-2.6 0-4.6-2-4.6-4.6v-64c0-2.6 2-4.6 4.6-4.6h27.4c2.6 0 4.6 2 4.6 4.6v64z\"],\n    \"fort-awesome-alt\": [512, 512, [], \"f3a3\", \"M208 237.4h-22.2c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7H208c2.1 0 3.7-1.6 3.7-3.7v-51.7c0-2.1-1.6-3.7-3.7-3.7zm118.2 0H304c-2.1 0-3.7 1.6-3.7 3.7v51.7c0 2.1 1.6 3.7 3.7 3.7h22.2c2.1 0 3.7-1.6 3.7-3.7v-51.7c-.1-2.1-1.7-3.7-3.7-3.7zm132-125.1c-2.3-3.2-4.6-6.4-7.1-9.5-9.8-12.5-20.8-24-32.8-34.4-4.5-3.9-9.1-7.6-13.9-11.2-1.6-1.2-3.2-2.3-4.8-3.5C372 34.1 340.3 20 306 13c-16.2-3.3-32.9-5-50-5s-33.9 1.7-50 5c-34.3 7.1-66 21.2-93.3 40.8-1.6 1.1-3.2 2.3-4.8 3.5-4.8 3.6-9.4 7.3-13.9 11.2-3 2.6-5.9 5.3-8.8 8s-5.7 5.5-8.4 8.4c-5.5 5.7-10.7 11.8-15.6 18-2.4 3.1-4.8 6.3-7.1 9.5C25.2 153 8.3 202.5 8.3 256c0 2 .1 4 .1 6 .1.7.1 1.3.1 2 .1 1.3.1 2.7.2 4 0 .8.1 1.5.1 2.3 0 1.3.1 2.5.2 3.7.1.8.1 1.6.2 2.4.1 1.1.2 2.3.3 3.5 0 .8.1 1.6.2 2.4.1 1.2.3 2.4.4 3.6.1.8.2 1.5.3 2.3.1 1.3.3 2.6.5 3.9.1.6.2 1.3.3 1.9l.9 5.7c.1.6.2 1.1.3 1.7.3 1.3.5 2.7.8 4 .2.8.3 1.6.5 2.4.2 1 .5 2.1.7 3.2.2.9.4 1.7.6 2.6.2 1 .4 2 .7 3 .2.9.5 1.8.7 2.7.3 1 .5 1.9.8 2.9.3.9.5 1.8.8 2.7.2.9.5 1.9.8 2.8s.5 1.8.8 2.7c.3 1 .6 1.9.9 2.8.6 1.6 1.1 3.3 1.7 4.9.4 1 .7 1.9 1 2.8.3 1 .7 2 1.1 3 .3.8.6 1.5.9 2.3l1.2 3c.3.7.6 1.5.9 2.2.4 1 .9 2 1.3 3l.9 2.1c.5 1 .9 2 1.4 3 .3.7.6 1.3.9 2 .5 1 1 2.1 1.5 3.1.2.6.5 1.1.8 1.7.6 1.1 1.1 2.2 1.7 3.3.1.2.2.3.3.5 2.2 4.1 4.4 8.2 6.8 12.2.2.4.5.8.7 1.2.7 1.1 1.3 2.2 2 3.3.3.5.6.9.9 1.4.6 1.1 1.3 2.1 2 3.2.3.5.6.9.9 1.4.7 1.1 1.4 2.1 2.1 3.2.2.4.5.8.8 1.2.7 1.1 1.5 2.2 2.3 3.3.2.2.3.5.5.7 37.5 51.7 94.4 88.5 160 99.4.9.1 1.7.3 2.6.4 1 .2 2.1.4 3.1.5s1.9.3 2.8.4c1 .2 2 .3 3 .4.9.1 1.9.2 2.9.3s1.9.2 2.9.3 2.1.2 3.1.3c.9.1 1.8.1 2.7.2 1.1.1 2.3.1 3.4.2.8 0 1.7.1 2.5.1 1.3 0 2.6.1 3.9.1.7.1 1.4.1 2.1.1 2 .1 4 .1 6 .1s4-.1 6-.1c.7 0 1.4-.1 2.1-.1 1.3 0 2.6 0 3.9-.1.8 0 1.7-.1 2.5-.1 1.1-.1 2.3-.1 3.4-.2.9 0 1.8-.1 2.7-.2 1-.1 2.1-.2 3.1-.3s1.9-.2 2.9-.3c.9-.1 1.9-.2 2.9-.3s2-.3 3-.4 1.9-.3 2.8-.4c1-.2 2.1-.3 3.1-.5.9-.1 1.7-.3 2.6-.4 65.6-11 122.5-47.7 160.1-102.4.2-.2.3-.5.5-.7.8-1.1 1.5-2.2 2.3-3.3.2-.4.5-.8.8-1.2.7-1.1 1.4-2.1 2.1-3.2.3-.5.6-.9.9-1.4.6-1.1 1.3-2.1 2-3.2.3-.5.6-.9.9-1.4.7-1.1 1.3-2.2 2-3.3.2-.4.5-.8.7-1.2 2.4-4 4.6-8.1 6.8-12.2.1-.2.2-.3.3-.5.6-1.1 1.1-2.2 1.7-3.3.2-.6.5-1.1.8-1.7.5-1 1-2.1 1.5-3.1.3-.7.6-1.3.9-2 .5-1 1-2 1.4-3l.9-2.1c.5-1 .9-2 1.3-3 .3-.7.6-1.5.9-2.2l1.2-3c.3-.8.6-1.5.9-2.3.4-1 .7-2 1.1-3s.7-1.9 1-2.8c.6-1.6 1.2-3.3 1.7-4.9.3-1 .6-1.9.9-2.8s.5-1.8.8-2.7c.2-.9.5-1.9.8-2.8s.6-1.8.8-2.7c.3-1 .5-1.9.8-2.9.2-.9.5-1.8.7-2.7.2-1 .5-2 .7-3 .2-.9.4-1.7.6-2.6.2-1 .5-2.1.7-3.2.2-.8.3-1.6.5-2.4.3-1.3.6-2.7.8-4 .1-.6.2-1.1.3-1.7l.9-5.7c.1-.6.2-1.3.3-1.9.1-1.3.3-2.6.5-3.9.1-.8.2-1.5.3-2.3.1-1.2.3-2.4.4-3.6 0-.8.1-1.6.2-2.4.1-1.1.2-2.3.3-3.5.1-.8.1-1.6.2-2.4.1 1.7.1.5.2-.7 0-.8.1-1.5.1-2.3.1-1.3.2-2.7.2-4 .1-.7.1-1.3.1-2 .1-2 .1-4 .1-6 0-53.5-16.9-103-45.8-143.7zM448 371.5c-9.4 15.5-20.6 29.9-33.6 42.9-20.6 20.6-44.5 36.7-71.2 48-13.9 5.8-28.2 10.3-42.9 13.2v-75.8c0-58.6-88.6-58.6-88.6 0v75.8c-14.7-2.9-29-7.3-42.9-13.2-26.7-11.3-50.6-27.4-71.2-48-13-13-24.2-27.4-33.6-42.9v-71.3c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7V326h29.6V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7H208c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-4.8 6.5-3.7 9.5-3.7V88.1c-4.4-2-7.4-6.7-7.4-11.5 0-16.8 25.4-16.8 25.4 0 0 4.8-3 9.4-7.4 11.5V92c6.3-1.4 12.7-2.3 19.2-2.3 9.4 0 18.4 3.5 26.3 3.5 7.2 0 15.2-3.5 19.4-3.5 2.1 0 3.7 1.6 3.7 3.7v48.4c0 5.6-18.7 6.5-22.4 6.5-8.6 0-16.6-3.5-25.4-3.5-7 0-14.1 1.2-20.8 2.8v30.7c3 0 9.5-1.1 9.5 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7v25.9h29.5V182c0-2.1 1.6-3.7 3.7-3.7h22.1c2.1 0 3.7 1.6 3.7 3.7v144h29.5v-25.8c0-2.1 1.6-3.7 3.7-3.7h22.2c2.1 0 3.7 1.6 3.7 3.7z\"],\n    \"forumbee\": [448, 512, [], \"f211\", \"M5.8 309.7C2 292.7 0 275.5 0 258.3 0 135 99.8 35 223.1 35c16.6 0 33.3 2 49.3 5.5C149 87.5 51.9 186 5.8 309.7zm392.9-189.2C385 103 369 87.8 350.9 75.2c-149.6 44.3-266.3 162.1-309.7 312 12.5 18.1 28 35.6 45.2 49 43.1-151.3 161.2-271.7 312.3-315.7zm15.8 252.7c15.2-25.1 25.4-53.7 29.5-82.8-79.4 42.9-145 110.6-187.6 190.3 30-4.4 58.9-15.3 84.6-31.3 35 13.1 70.9 24.3 107 33.6-9.3-36.5-20.4-74.5-33.5-109.8zm29.7-145.5c-2.6-19.5-7.9-38.7-15.8-56.8C290.5 216.7 182 327.5 137.1 466c18.1 7.6 37 12.5 56.6 15.2C240 367.1 330.5 274.4 444.2 227.7z\"],\n    \"foursquare\": [368, 512, [], \"f180\", \"M323.1 3H49.9C12.4 3 0 31.3 0 49.1v433.8c0 20.3 12.1 27.7 18.2 30.1 6.2 2.5 22.8 4.6 32.9-7.1C180 356.5 182.2 354 182.2 354c3.1-3.4 3.4-3.1 6.8-3.1h83.4c35.1 0 40.6-25.2 44.3-39.7l48.6-243C373.8 25.8 363.1 3 323.1 3zm-16.3 73.8l-11.4 59.7c-1.2 6.5-9.5 13.2-16.9 13.2H172.1c-12 0-20.6 8.3-20.6 20.3v13c0 12 8.6 20.6 20.6 20.6h90.4c8.3 0 16.6 9.2 14.8 18.2-1.8 8.9-10.5 53.8-11.4 58.8-.9 4.9-6.8 13.5-16.9 13.5h-73.5c-13.5 0-17.2 1.8-26.5 12.6 0 0-8.9 11.4-89.5 108.3-.9.9-1.8.6-1.8-.3V75.9c0-7.7 6.8-16.6 16.6-16.6h219c8.2 0 15.6 7.7 13.5 17.5z\"],\n    \"free-code-camp\": [576, 512, [], \"f2c5\", \"M69.3 144.5c-41 68.5-36.4 163 1 227C92.5 409.7 120 423.9 120 438c0 6.8-6 13-12.8 13C87.7 451 8 375.5 8 253.2c0-111.5 78-186 97.1-186 6 0 14.9 4.8 14.9 11.1 0 12.7-28.3 28.6-50.7 66.2zm195.8 213.8c4.5 1.8 12.3 5.2 12.3-1.2 0-2.7-2.2-2.9-4.3-3.6-8.5-3.4-14-7.7-19.1-15.2-8.2-12.1-10.1-24.2-10.1-38.6 0-32.1 44.2-37.9 44.2-70 0-12.3-7.7-15.9-7.7-19.3 0-2.2.7-2.2 2.9-2.2 8 0 19.1 13.3 22.5 19.8 2.2 4.6 2.4 6 2.4 11.1 0 7-.7 14.2-.7 21.3 0 27 31.9 19.8 31.9 6.8 0-6-3.6-11.6-3.6-17.4 0-.7 0-1.2.7-1.2 3.4 0 9.4 7.7 11.1 10.1 5.8 8.9 8.5 20.8 8.5 31.4 0 32.4-29.5 49-29.5 56 0 1 2.9 7.7 12.1 1.9 29.7-15.1 53.1-47.6 53.1-89.8 0-33.6-8.7-57.7-32.1-82.6-3.9-4.1-16.4-16.9-22.5-16.9-8.2 0 7.2 18.6 7.2 31.2 0 7.2-4.8 12.3-12.3 12.3-11.6 0-14.5-25.4-15.9-33.3-5.8-33.8-12.8-58.2-46.4-74.1-10.4-5-36.5-11.8-36.5-2.2 0 2.4 2.7 4.1 4.6 5.1 9.2 5.6 19.6 21.4 19.6 38.2 0 46.1-57.7 88.2-57.7 136.2-.2 40.3 28.1 72.6 65.3 86.2zM470.4 67c-6 0-14.4 6.5-14.4 12.6 0 8.7 12.1 19.6 17.6 25.4 81.6 85.1 78.6 214.3 17.6 291-7 8.9-35.3 35.3-35.3 43.5 0 5.1 8.2 11.4 13.2 11.4 25.4 0 98.8-80.8 98.8-185.7C568 145.9 491.8 67 470.4 67zm-42.3 323.1H167c-9.4 0-15.5 7.5-15.5 16.4 0 8.5 7 15.5 15.5 15.5h261.1c9.4 0 11.9-7.5 11.9-16.4 0-8.5-3.5-15.5-11.9-15.5z\"],\n    \"freebsd\": [448, 512, [], \"f3a4\", \"M303.7 96.2c11.1-11.1 115.5-77 139.2-53.2 23.7 23.7-42.1 128.1-53.2 139.2-11.1 11.1-39.4.9-63.1-22.9-23.8-23.7-34.1-52-22.9-63.1zM109.9 68.1C73.6 47.5 22 24.6 5.6 41.1c-16.6 16.6 7.1 69.4 27.9 105.7 18.5-32.2 44.8-59.3 76.4-78.7zM406.7 174c3.3 11.3 2.7 20.7-2.7 26.1-20.3 20.3-87.5-27-109.3-70.1-18-32.3-11.1-53.4 14.9-48.7 5.7-3.6 12.3-7.6 19.6-11.6-29.8-15.5-63.6-24.3-99.5-24.3-119.1 0-215.6 96.5-215.6 215.6 0 119 96.5 215.6 215.6 215.6S445.3 380.1 445.3 261c0-38.4-10.1-74.5-27.7-105.8-3.9 7-7.6 13.3-10.9 18.8z\"],\n    \"fulcrum\": [320, 512, [], \"f50b\", \"M95.75 164.14l-35.38 43.55L25 164.14l35.38-43.55zM144.23 0l-20.54 198.18L72.72 256l51 57.82L144.23 512V300.89L103.15 256l41.08-44.89zm79.67 164.14l35.38 43.55 35.38-43.55-35.38-43.55zm-48.48 47L216.5 256l-41.08 44.89V512L196 313.82 247 256l-51-57.82L175.42 0z\"],\n    \"galactic-republic\": [496, 512, [], \"f50c\", \"M248 504C111.25 504 0 392.75 0 256S111.25 8 248 8s248 111.25 248 248-111.25 248-248 248zm0-479.47C120.37 24.53 16.53 128.37 16.53 256S120.37 487.47 248 487.47 479.47 383.63 479.47 256 375.63 24.53 248 24.53zm27.62 21.81v24.62a185.933 185.933 0 0 1 83.57 34.54l17.39-17.36c-28.75-22.06-63.3-36.89-100.96-41.8zm-55.37.07c-37.64 4.94-72.16 19.8-100.88 41.85l17.28 17.36h.08c24.07-17.84 52.55-30.06 83.52-34.67V46.41zm12.25 50.17v82.87c-10.04 2.03-19.42 5.94-27.67 11.42l-58.62-58.59-21.93 21.93 58.67 58.67c-5.47 8.23-9.45 17.59-11.47 27.62h-82.9v31h82.9c2.02 10.02 6.01 19.31 11.47 27.54l-58.67 58.69 21.93 21.93 58.62-58.62a77.873 77.873 0 0 0 27.67 11.47v82.9h31v-82.9c10.05-2.03 19.37-6.06 27.62-11.55l58.67 58.69 21.93-21.93-58.67-58.69c5.46-8.23 9.47-17.52 11.5-27.54h82.87v-31h-82.87c-2.02-10.02-6.03-19.38-11.5-27.62l58.67-58.67-21.93-21.93-58.67 58.67c-8.25-5.49-17.57-9.47-27.62-11.5V96.58h-31zm183.24 30.72l-17.36 17.36a186.337 186.337 0 0 1 34.67 83.67h24.62c-4.95-37.69-19.83-72.29-41.93-101.03zm-335.55.13c-22.06 28.72-36.91 63.26-41.85 100.91h24.65c4.6-30.96 16.76-59.45 34.59-83.52l-17.39-17.39zM38.34 283.67c4.92 37.64 19.75 72.18 41.8 100.9l17.36-17.39c-17.81-24.07-29.92-52.57-34.51-83.52H38.34zm394.7 0c-4.61 30.99-16.8 59.5-34.67 83.6l17.36 17.36c22.08-28.74 36.98-63.29 41.93-100.96h-24.62zM136.66 406.38l-17.36 17.36c28.73 22.09 63.3 36.98 100.96 41.93v-24.64c-30.99-4.63-59.53-16.79-83.6-34.65zm222.53.05c-24.09 17.84-52.58 30.08-83.57 34.67v24.57c37.67-4.92 72.21-19.79 100.96-41.85l-17.31-17.39h-.08z\"],\n    \"galactic-senate\": [512, 512, [], \"f50d\", \"M249.86 33.48v26.07C236.28 80.17 226 168.14 225.39 274.9c11.74-15.62 19.13-33.33 19.13-48.24v-16.88c-.03-5.32.75-10.53 2.19-15.65.65-2.14 1.39-4.08 2.62-5.82 1.23-1.75 3.43-3.79 6.68-3.79 3.24 0 5.45 2.05 6.68 3.79 1.23 1.75 1.97 3.68 2.62 5.82 1.44 5.12 2.22 10.33 2.19 15.65v16.88c0 14.91 7.39 32.62 19.13 48.24-.63-106.76-10.91-194.73-24.49-215.35V33.48h-12.28zm-26.34 147.77c-9.52 2.15-18.7 5.19-27.46 9.08 8.9 16.12 9.76 32.64 1.71 37.29-8 4.62-21.85-4.23-31.36-19.82-11.58 8.79-21.88 19.32-30.56 31.09 14.73 9.62 22.89 22.92 18.32 30.66-4.54 7.7-20.03 7.14-35.47-.96-5.78 13.25-9.75 27.51-11.65 42.42 9.68.18 18.67 2.38 26.18 6.04 17.78-.3 32.77-1.96 40.49-4.22 5.55-26.35 23.02-48.23 46.32-59.51.73-25.55 1.88-49.67 3.48-72.07zm64.96 0c1.59 22.4 2.75 46.52 3.47 72.07 23.29 11.28 40.77 33.16 46.32 59.51 7.72 2.26 22.71 3.92 40.49 4.22 7.51-3.66 16.5-5.85 26.18-6.04-1.9-14.91-5.86-29.17-11.65-42.42-15.44 8.1-30.93 8.66-35.47.96-4.57-7.74 3.6-21.05 18.32-30.66-8.68-11.77-18.98-22.3-30.56-31.09-9.51 15.59-23.36 24.44-31.36 19.82-8.05-4.65-7.19-21.16 1.71-37.29a147.49 147.49 0 0 0-27.45-9.08zm-32.48 8.6c-3.23 0-5.86 8.81-6.09 19.93h-.05v16.88c0 41.42-49.01 95.04-93.49 95.04-52 0-122.75-1.45-156.37 29.17v2.51c9.42 17.12 20.58 33.17 33.18 47.97C45.7 380.26 84.77 360.4 141.2 360c45.68 1.02 79.03 20.33 90.76 40.87.01.01-.01.04 0 .05 7.67 2.14 15.85 3.23 24.04 3.21 8.19.02 16.37-1.07 24.04-3.21.01-.01-.01-.04 0-.05 11.74-20.54 45.08-39.85 90.76-40.87 56.43.39 95.49 20.26 108.02 41.35 12.6-14.8 23.76-30.86 33.18-47.97v-2.51c-33.61-30.62-104.37-29.17-156.37-29.17-44.48 0-93.49-53.62-93.49-95.04v-16.88h-.05c-.23-11.12-2.86-19.93-6.09-19.93zm0 96.59c22.42 0 40.6 18.18 40.6 40.6s-18.18 40.65-40.6 40.65-40.6-18.23-40.6-40.65c0-22.42 18.18-40.6 40.6-40.6zm0 7.64c-18.19 0-32.96 14.77-32.96 32.96S237.81 360 256 360s32.96-14.77 32.96-32.96-14.77-32.96-32.96-32.96zm0 6.14c14.81 0 26.82 12.01 26.82 26.82s-12.01 26.82-26.82 26.82-26.82-12.01-26.82-26.82 12.01-26.82 26.82-26.82zm-114.8 66.67c-10.19.07-21.6.36-30.5 1.66.43 4.42 1.51 18.63 7.11 29.76 9.11-2.56 18.36-3.9 27.62-3.9 41.28.94 71.48 34.35 78.26 74.47l.11 4.7c10.4 1.91 21.19 2.94 32.21 2.94 11.03 0 21.81-1.02 32.21-2.94l.11-4.7c6.78-40.12 36.98-73.53 78.26-74.47 9.26 0 18.51 1.34 27.62 3.9 5.6-11.13 6.68-25.34 7.11-29.76-8.9-1.3-20.32-1.58-30.5-1.66-18.76.42-35.19 4.17-48.61 9.67-12.54 16.03-29.16 30.03-49.58 33.07-.09.02-.17.04-.27.05-.05.01-.11.04-.16.05-5.24 1.07-10.63 1.6-16.19 1.6-5.55 0-10.95-.53-16.19-1.6-.05-.01-.11-.04-.16-.05-.1-.02-.17-.04-.27-.05-20.42-3.03-37.03-17.04-49.58-33.07-13.42-5.49-29.86-9.25-48.61-9.67z\"],\n    \"get-pocket\": [448, 512, [], \"f265\", \"M407.6 64h-367C18.5 64 0 82.5 0 104.6v135.2C0 364.5 99.7 464 224.2 464c124 0 223.8-99.5 223.8-224.2V104.6c0-22.4-17.7-40.6-40.4-40.6zm-162 268.5c-12.4 11.8-31.4 11.1-42.4 0C89.5 223.6 88.3 227.4 88.3 209.3c0-16.9 13.8-30.7 30.7-30.7 17 0 16.1 3.8 105.2 89.3 90.6-86.9 88.6-89.3 105.5-89.3 16.9 0 30.7 13.8 30.7 30.7 0 17.8-2.9 15.7-114.8 123.2z\"],\n    \"gg\": [512, 512, [], \"f260\", \"M179.2 230.4l102.4 102.4-102.4 102.4L0 256 179.2 76.8l44.8 44.8-25.6 25.6-19.2-19.2-128 128 128 128 51.5-51.5-77.1-76.5 25.6-25.6zM332.8 76.8L230.4 179.2l102.4 102.4 25.6-25.6-77.1-76.5 51.5-51.5 128 128-128 128-19.2-19.2-25.6 25.6 44.8 44.8L512 256 332.8 76.8z\"],\n    \"gg-circle\": [512, 512, [], \"f261\", \"M257 8C120 8 9 119 9 256s111 248 248 248 248-111 248-248S394 8 257 8zm-49.5 374.8L81.8 257.1l125.7-125.7 35.2 35.4-24.2 24.2-11.1-11.1-77.2 77.2 77.2 77.2 26.6-26.6-53.1-52.9 24.4-24.4 77.2 77.2-75 75.2zm99-2.2l-35.2-35.2 24.1-24.4 11.1 11.1 77.2-77.2-77.2-77.2-26.5 26.5 53.1 52.9-24.4 24.4-77.2-77.2 75-75L432.2 255 306.5 380.6z\"],\n    \"git\": [512, 512, [], \"f1d3\", \"M216.29 158.39H137C97 147.9 6.51 150.63 6.51 233.18c0 30.09 15 51.23 35 61-25.1 23-37 33.85-37 49.21 0 11 4.47 21.14 17.89 26.81C8.13 383.61 0 393.35 0 411.65c0 32.11 28.05 50.82 101.63 50.82 70.75 0 111.79-26.42 111.79-73.18 0-58.66-45.16-56.5-151.63-63l13.43-21.55c27.27 7.58 118.7 10 118.7-67.89 0-18.7-7.73-31.71-15-41.07l37.41-2.84zm-63.42 241.9c0 32.06-104.89 32.1-104.89 2.43 0-8.14 5.27-15 10.57-21.54 77.71 5.3 94.32 3.37 94.32 19.11zm-50.81-134.58c-52.8 0-50.46-71.16 1.2-71.16 49.54 0 50.82 71.16-1.2 71.16zm133.3 100.51v-32.1c26.75-3.66 27.24-2 27.24-11V203.61c0-8.5-2.05-7.38-27.24-16.26l4.47-32.92H324v168.71c0 6.51.4 7.32 6.51 8.14l20.73 2.84v32.1zm52.45-244.31c-23.17 0-36.59-13.43-36.59-36.61s13.42-35.77 36.59-35.77c23.58 0 37 12.62 37 35.77s-13.42 36.61-37 36.61zM512 350.46c-17.49 8.53-43.1 16.26-66.28 16.26-48.38 0-66.67-19.5-66.67-65.46V194.75c0-5.42 1.05-4.06-31.71-4.06V154.5c35.78-4.07 50-22 54.47-66.27h38.63c0 65.83-1.34 61.81 3.26 61.81H501v40.65h-60.56v97.15c0 6.92-4.92 51.41 60.57 26.84z\"],\n    \"git-alt\": [448, 512, [], \"f841\", \"M439.55 236.05L244 40.45a28.87 28.87 0 0 0-40.81 0l-40.66 40.63 51.52 51.52c27.06-9.14 52.68 16.77 43.39 43.68l49.66 49.66c34.23-11.8 61.18 31 35.47 56.69-26.49 26.49-70.21-2.87-56-37.34L240.22 199v121.85c25.3 12.54 22.26 41.85 9.08 55a34.34 34.34 0 0 1-48.55 0c-17.57-17.6-11.07-46.91 11.25-56v-123c-20.8-8.51-24.6-30.74-18.64-45L142.57 101 8.45 235.14a28.86 28.86 0 0 0 0 40.81l195.61 195.6a28.86 28.86 0 0 0 40.8 0l194.69-194.69a28.86 28.86 0 0 0 0-40.81z\"],\n    \"git-square\": [448, 512, [], \"f1d2\", \"M100.59 334.24c48.57 3.31 58.95 2.11 58.95 11.94 0 20-65.55 20.06-65.55 1.52.01-5.09 3.29-9.4 6.6-13.46zm27.95-116.64c-32.29 0-33.75 44.47-.75 44.47 32.51 0 31.71-44.47.75-44.47zM448 80v352a48 48 0 0 1-48 48H48a48 48 0 0 1-48-48V80a48 48 0 0 1 48-48h352a48 48 0 0 1 48 48zm-227 69.31c0 14.49 8.38 22.88 22.86 22.88 14.74 0 23.13-8.39 23.13-22.88S258.62 127 243.88 127c-14.48 0-22.88 7.84-22.88 22.31zM199.18 195h-49.55c-25-6.55-81.56-4.85-81.56 46.75 0 18.8 9.4 32 21.85 38.11C74.23 294.23 66.8 301 66.8 310.6c0 6.87 2.79 13.22 11.18 16.76-8.9 8.4-14 14.48-14 25.92C64 373.35 81.53 385 127.52 385c44.22 0 69.87-16.51 69.87-45.73 0-36.67-28.23-35.32-94.77-39.38l8.38-13.43c17 4.74 74.19 6.23 74.19-42.43 0-11.69-4.83-19.82-9.4-25.67l23.38-1.78zm84.34 109.84l-13-1.78c-3.82-.51-4.07-1-4.07-5.09V192.52h-52.6l-2.79 20.57c15.75 5.55 17 4.86 17 10.17V298c0 5.62-.31 4.58-17 6.87v20.06h72.42zM384 315l-6.87-22.37c-40.93 15.37-37.85-12.41-37.85-16.73v-60.72h37.85v-25.41h-35.82c-2.87 0-2 2.52-2-38.63h-24.18c-2.79 27.7-11.68 38.88-34 41.42v22.62c20.47 0 19.82-.85 19.82 2.54v66.57c0 28.72 11.43 40.91 41.67 40.91 14.45 0 30.45-4.83 41.38-10.2z\"],\n    \"github\": [496, 512, [], \"f09b\", \"M165.9 397.4c0 2-2.3 3.6-5.2 3.6-3.3.3-5.6-1.3-5.6-3.6 0-2 2.3-3.6 5.2-3.6 3-.3 5.6 1.3 5.6 3.6zm-31.1-4.5c-.7 2 1.3 4.3 4.3 4.9 2.6 1 5.6 0 6.2-2s-1.3-4.3-4.3-5.2c-2.6-.7-5.5.3-6.2 2.3zm44.2-1.7c-2.9.7-4.9 2.6-4.6 4.9.3 2 2.9 3.3 5.9 2.6 2.9-.7 4.9-2.6 4.6-4.6-.3-1.9-3-3.2-5.9-2.9zM244.8 8C106.1 8 0 113.3 0 252c0 110.9 69.8 205.8 169.5 239.2 12.8 2.3 17.3-5.6 17.3-12.1 0-6.2-.3-40.4-.3-61.4 0 0-70 15-84.7-29.8 0 0-11.4-29.1-27.8-36.6 0 0-22.9-15.7 1.6-15.4 0 0 24.9 2 38.6 25.8 21.9 38.6 58.6 27.5 72.9 20.9 2.3-16 8.8-27.1 16-33.7-55.9-6.2-112.3-14.3-112.3-110.5 0-27.5 7.6-41.3 23.6-58.9-2.6-6.5-11.1-33.3 2.6-67.9 20.9-6.5 69 27 69 27 20-5.6 41.5-8.5 62.8-8.5s42.8 2.9 62.8 8.5c0 0 48.1-33.6 69-27 13.7 34.7 5.2 61.4 2.6 67.9 16 17.7 25.8 31.5 25.8 58.9 0 96.5-58.9 104.2-114.8 110.5 9.2 7.9 17 22.9 17 46.4 0 33.7-.3 75.4-.3 83.6 0 6.5 4.6 14.4 17.3 12.1C428.2 457.8 496 362.9 496 252 496 113.3 383.5 8 244.8 8zM97.2 352.9c-1.3 1-1 3.3.7 5.2 1.6 1.6 3.9 2.3 5.2 1 1.3-1 1-3.3-.7-5.2-1.6-1.6-3.9-2.3-5.2-1zm-10.8-8.1c-.7 1.3.3 2.9 2.3 3.9 1.6 1 3.6.7 4.3-.7.7-1.3-.3-2.9-2.3-3.9-2-.6-3.6-.3-4.3.7zm32.4 35.6c-1.6 1.3-1 4.3 1.3 6.2 2.3 2.3 5.2 2.6 6.5 1 1.3-1.3.7-4.3-1.3-6.2-2.2-2.3-5.2-2.6-6.5-1zm-11.4-14.7c-1.6 1-1.6 3.6 0 5.9 1.6 2.3 4.3 3.3 5.6 2.3 1.6-1.3 1.6-3.9 0-6.2-1.4-2.3-4-3.3-5.6-2z\"],\n    \"github-alt\": [480, 512, [], \"f113\", \"M186.1 328.7c0 20.9-10.9 55.1-36.7 55.1s-36.7-34.2-36.7-55.1 10.9-55.1 36.7-55.1 36.7 34.2 36.7 55.1zM480 278.2c0 31.9-3.2 65.7-17.5 95-37.9 76.6-142.1 74.8-216.7 74.8-75.8 0-186.2 2.7-225.6-74.8-14.6-29-20.2-63.1-20.2-95 0-41.9 13.9-81.5 41.5-113.6-5.2-15.8-7.7-32.4-7.7-48.8 0-21.5 4.9-32.3 14.6-51.8 45.3 0 74.3 9 108.8 36 29-6.9 58.8-10 88.7-10 27 0 54.2 2.9 80.4 9.2 34-26.7 63-35.2 107.8-35.2 9.8 19.5 14.6 30.3 14.6 51.8 0 16.4-2.6 32.7-7.7 48.2 27.5 32.4 39 72.3 39 114.2zm-64.3 50.5c0-43.9-26.7-82.6-73.5-82.6-18.9 0-37 3.4-56 6-14.9 2.3-29.8 3.2-45.1 3.2-15.2 0-30.1-.9-45.1-3.2-18.7-2.6-37-6-56-6-46.8 0-73.5 38.7-73.5 82.6 0 87.8 80.4 101.3 150.4 101.3h48.2c70.3 0 150.6-13.4 150.6-101.3zm-82.6-55.1c-25.8 0-36.7 34.2-36.7 55.1s10.9 55.1 36.7 55.1 36.7-34.2 36.7-55.1-10.9-55.1-36.7-55.1z\"],\n    \"github-square\": [448, 512, [], \"f092\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM277.3 415.7c-8.4 1.5-11.5-3.7-11.5-8 0-5.4.2-33 .2-55.3 0-15.6-5.2-25.5-11.3-30.7 37-4.1 76-9.2 76-73.1 0-18.2-6.5-27.3-17.1-39 1.7-4.3 7.4-22-1.7-45-13.9-4.3-45.7 17.9-45.7 17.9-13.2-3.7-27.5-5.6-41.6-5.6-14.1 0-28.4 1.9-41.6 5.6 0 0-31.8-22.2-45.7-17.9-9.1 22.9-3.5 40.6-1.7 45-10.6 11.7-15.6 20.8-15.6 39 0 63.6 37.3 69 74.3 73.1-4.8 4.3-9.1 11.7-10.6 22.3-9.5 4.3-33.8 11.7-48.3-13.9-9.1-15.8-25.5-17.1-25.5-17.1-16.2-.2-1.1 10.2-1.1 10.2 10.8 5 18.4 24.2 18.4 24.2 9.7 29.7 56.1 19.7 56.1 19.7 0 13.9.2 36.5.2 40.6 0 4.3-3 9.5-11.5 8-66-22.1-112.2-84.9-112.2-158.3 0-91.8 70.2-161.5 162-161.5S388 165.6 388 257.4c.1 73.4-44.7 136.3-110.7 158.3zm-98.1-61.1c-1.9.4-3.7-.4-3.9-1.7-.2-1.5 1.1-2.8 3-3.2 1.9-.2 3.7.6 3.9 1.9.3 1.3-1 2.6-3 3zm-9.5-.9c0 1.3-1.5 2.4-3.5 2.4-2.2.2-3.7-.9-3.7-2.4 0-1.3 1.5-2.4 3.5-2.4 1.9-.2 3.7.9 3.7 2.4zm-13.7-1.1c-.4 1.3-2.4 1.9-4.1 1.3-1.9-.4-3.2-1.9-2.8-3.2.4-1.3 2.4-1.9 4.1-1.5 2 .6 3.3 2.1 2.8 3.4zm-12.3-5.4c-.9 1.1-2.8.9-4.3-.6-1.5-1.3-1.9-3.2-.9-4.1.9-1.1 2.8-.9 4.3.6 1.3 1.3 1.8 3.3.9 4.1zm-9.1-9.1c-.9.6-2.6 0-3.7-1.5s-1.1-3.2 0-3.9c1.1-.9 2.8-.2 3.7 1.3 1.1 1.5 1.1 3.3 0 4.1zm-6.5-9.7c-.9.9-2.4.4-3.5-.6-1.1-1.3-1.3-2.8-.4-3.5.9-.9 2.4-.4 3.5.6 1.1 1.3 1.3 2.8.4 3.5zm-6.7-7.4c-.4.9-1.7 1.1-2.8.4-1.3-.6-1.9-1.7-1.5-2.6.4-.6 1.5-.9 2.8-.4 1.3.7 1.9 1.8 1.5 2.6z\"],\n    \"gitkraken\": [592, 512, [], \"f3a6\", \"M565.7 118.1c-2.3-6.1-9.3-9.2-15.3-6.6-5.7 2.4-8.5 8.9-6.3 14.6 10.9 29 16.9 60.5 16.9 93.3 0 134.6-100.3 245.7-230.2 262.7V358.4c7.9-1.5 15.5-3.6 23-6.2v104c106.7-25.9 185.9-122.1 185.9-236.8 0-91.8-50.8-171.8-125.8-213.3-5.7-3.2-13-.9-15.9 5-2.7 5.5-.6 12.2 4.7 15.1 67.9 37.6 113.9 110 113.9 193.2 0 93.3-57.9 173.1-139.8 205.4v-92.2c14.2-4.5 24.9-17.7 24.9-33.5 0-13.1-6.8-24.4-17.3-30.5 8.3-79.5 44.5-58.6 44.5-83.9V170c0-38-87.9-161.8-129-164.7-2.5-.2-5-.2-7.6 0C251.1 8.3 163.2 132 163.2 170v14.8c0 25.3 36.3 4.3 44.5 83.9-10.6 6.1-17.3 17.4-17.3 30.5 0 15.8 10.6 29 24.8 33.5v92.2c-81.9-32.2-139.8-112-139.8-205.4 0-83.1 46-155.5 113.9-193.2 5.4-3 7.4-9.6 4.7-15.1-2.9-5.9-10.1-8.2-15.9-5-75 41.5-125.8 121.5-125.8 213.3 0 114.7 79.2 210.8 185.9 236.8v-104c7.6 2.5 15.1 4.6 23 6.2v123.7C131.4 465.2 31 354.1 31 219.5c0-32.8 6-64.3 16.9-93.3 2.2-5.8-.6-12.2-6.3-14.6-6-2.6-13 .4-15.3 6.6C14.5 149.7 8 183.8 8 219.5c0 155.1 122.6 281.6 276.3 287.8V361.4c6.8.4 15 .5 23.4 0v145.8C461.4 501.1 584 374.6 584 219.5c0-35.7-6.5-69.8-18.3-101.4zM365.9 275.5c13 0 23.7 10.5 23.7 23.7 0 13.1-10.6 23.7-23.7 23.7-13 0-23.7-10.5-23.7-23.7 0-13.1 10.6-23.7 23.7-23.7zm-139.8 47.3c-13.2 0-23.7-10.7-23.7-23.7s10.5-23.7 23.7-23.7c13.1 0 23.7 10.6 23.7 23.7 0 13-10.5 23.7-23.7 23.7z\"],\n    \"gitlab\": [512, 512, [], \"f296\", \"M105.2 24.9c-3.1-8.9-15.7-8.9-18.9 0L29.8 199.7h132c-.1 0-56.6-174.8-56.6-174.8zM.9 287.7c-2.6 8 .3 16.9 7.1 22l247.9 184-226.2-294zm160.8-88l94.3 294 94.3-294zm349.4 88l-28.8-88-226.3 294 247.9-184c6.9-5.1 9.7-14 7.2-22zM425.7 24.9c-3.1-8.9-15.7-8.9-18.9 0l-56.6 174.8h132z\"],\n    \"gitter\": [384, 512, [], \"f426\", \"M66.4 322.5H16V0h50.4v322.5zM166.9 76.1h-50.4V512h50.4V76.1zm100.6 0h-50.4V512h50.4V76.1zM368 76h-50.4v247H368V76z\"],\n    \"glide\": [448, 512, [], \"f2a5\", \"M252.8 148.6c0 8.8-1.6 17.7-3.4 26.4-5.8 27.8-11.6 55.8-17.3 83.6-1.4 6.3-8.3 4.9-13.7 4.9-23.8 0-30.5-26-30.5-45.5 0-29.3 11.2-68.1 38.5-83.1 4.3-2.5 9.2-4.2 14.1-4.2 11.4 0 12.3 8.3 12.3 17.9zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-64 187c0-5.1-20.8-37.7-25.5-39.5-2.2-.9-7.2-2.3-9.6-2.3-23.1 0-38.7 10.5-58.2 21.5l-.5-.5c4.3-29.4 14.6-57.2 14.6-87.4 0-44.6-23.8-62.7-67.5-62.7-71.7 0-108 70.8-108 123.5 0 54.7 32 85 86.3 85 7.5 0 6.9-.6 6.9 2.3-10.5 80.3-56.5 82.9-56.5 58.9 0-24.4 28-36.5 28.3-38-.2-7.6-29.3-17.2-36.7-17.2-21.1 0-32.7 33-32.7 50.6 0 32.3 20.4 54.7 53.3 54.7 48.2 0 83.4-49.7 94.3-91.7 9.4-37.7 7-39.4 12.3-42.1 20-10.1 35.8-16.8 58.4-16.8 11.1 0 19 2.3 36.7 5.2 1.8.1 4.1-1.7 4.1-3.5z\"],\n    \"glide-g\": [448, 512, [], \"f2a6\", \"M407.1 211.2c-3.5-1.4-11.6-3.8-15.4-3.8-37.1 0-62.2 16.8-93.5 34.5l-.9-.9c7-47.3 23.5-91.9 23.5-140.4C320.8 29.1 282.6 0 212.4 0 97.3 0 39 113.7 39 198.4 39 286.3 90.3 335 177.6 335c12 0 11-1 11 3.8-16.9 128.9-90.8 133.1-90.8 94.6 0-39.2 45-58.6 45.5-61-.3-12.2-47-27.6-58.9-27.6-33.9.1-52.4 51.2-52.4 79.3C32 476 64.8 512 117.5 512c77.4 0 134-77.8 151.4-145.4 15.1-60.5 11.2-63.3 19.7-67.6 32.2-16.2 57.5-27 93.8-27 17.8 0 30.5 3.7 58.9 8.4 2.9 0 6.7-2.9 6.7-5.8 0-8-33.4-60.5-40.9-63.4zm-175.3-84.4c-9.3 44.7-18.6 89.6-27.8 134.3-2.3 10.2-13.3 7.8-22 7.8-38.3 0-49-41.8-49-73.1 0-47 18-109.3 61.8-133.4 7-4.1 14.8-6.7 22.6-6.7 18.6 0 20 13.3 20 28.7-.1 14.3-2.7 28.5-5.6 42.4z\"],\n    \"gofore\": [400, 512, [], \"f3a7\", \"M324 319.8h-13.2v34.7c-24.5 23.1-56.3 35.8-89.9 35.8-73.2 0-132.4-60.2-132.4-134.4 0-74.1 59.2-134.4 132.4-134.4 35.3 0 68.6 14 93.6 39.4l62.3-63.3C335 55.3 279.7 32 220.7 32 98 32 0 132.6 0 256c0 122.5 97 224 220.7 224 63.2 0 124.5-26.2 171-82.5-2-27.6-13.4-77.7-67.7-77.7zm-12.1-112.5H205.6v89H324c33.5 0 60.5 15.1 76 41.8v-30.6c0-65.2-40.4-100.2-88.1-100.2z\"],\n    \"goodreads\": [448, 512, [], \"f3a8\", \"M299.9 191.2c5.1 37.3-4.7 79-35.9 100.7-22.3 15.5-52.8 14.1-70.8 5.7-37.1-17.3-49.5-58.6-46.8-97.2 4.3-60.9 40.9-87.9 75.3-87.5 46.9-.2 71.8 31.8 78.2 78.3zM448 88v336c0 30.9-25.1 56-56 56H56c-30.9 0-56-25.1-56-56V88c0-30.9 25.1-56 56-56h336c30.9 0 56 25.1 56 56zM330 313.2s-.1-34-.1-217.3h-29v40.3c-.8.3-1.2-.5-1.6-1.2-9.6-20.7-35.9-46.3-76-46-51.9.4-87.2 31.2-100.6 77.8-4.3 14.9-5.8 30.1-5.5 45.6 1.7 77.9 45.1 117.8 112.4 115.2 28.9-1.1 54.5-17 69-45.2.5-1 1.1-1.9 1.7-2.9.2.1.4.1.6.2.3 3.8.2 30.7.1 34.5-.2 14.8-2 29.5-7.2 43.5-7.8 21-22.3 34.7-44.5 39.5-17.8 3.9-35.6 3.8-53.2-1.2-21.5-6.1-36.5-19-41.1-41.8-.3-1.6-1.3-1.3-2.3-1.3h-26.8c.8 10.6 3.2 20.3 8.5 29.2 24.2 40.5 82.7 48.5 128.2 37.4 49.9-12.3 67.3-54.9 67.4-106.3z\"],\n    \"goodreads-g\": [384, 512, [], \"f3a9\", \"M42.6 403.3h2.8c12.7 0 25.5 0 38.2.1 1.6 0 3.1-.4 3.6 2.1 7.1 34.9 30 54.6 62.9 63.9 26.9 7.6 54.1 7.8 81.3 1.8 33.8-7.4 56-28.3 68-60.4 8-21.5 10.7-43.8 11-66.5.1-5.8.3-47-.2-52.8l-.9-.3c-.8 1.5-1.7 2.9-2.5 4.4-22.1 43.1-61.3 67.4-105.4 69.1-103 4-169.4-57-172-176.2-.5-23.7 1.8-46.9 8.3-69.7C58.3 47.7 112.3.6 191.6 0c61.3-.4 101.5 38.7 116.2 70.3.5 1.1 1.3 2.3 2.4 1.9V10.6h44.3c0 280.3.1 332.2.1 332.2-.1 78.5-26.7 143.7-103 162.2-69.5 16.9-159 4.8-196-57.2-8-13.5-11.8-28.3-13-44.5zM188.9 36.5c-52.5-.5-108.5 40.7-115 133.8-4.1 59 14.8 122.2 71.5 148.6 27.6 12.9 74.3 15 108.3-8.7 47.6-33.2 62.7-97 54.8-154-9.7-71.1-47.8-120-119.6-119.7z\"],\n    \"google\": [488, 512, [], \"f1a0\", \"M488 261.8C488 403.3 391.1 504 248 504 110.8 504 0 393.2 0 256S110.8 8 248 8c66.8 0 123 24.5 166.3 64.9l-67.5 64.9C258.5 52.6 94.3 116.6 94.3 256c0 86.5 69.1 156.6 153.7 156.6 98.2 0 135-70.4 140.8-106.9H248v-85.3h236.1c2.3 12.7 3.9 24.9 3.9 41.4z\"],\n    \"google-drive\": [512, 512, [], \"f3aa\", \"M339 314.9L175.4 32h161.2l163.6 282.9H339zm-137.5 23.6L120.9 480h310.5L512 338.5H201.5zM154.1 67.4L0 338.5 80.6 480 237 208.8 154.1 67.4z\"],\n    \"google-play\": [512, 512, [], \"f3ab\", \"M325.3 234.3L104.6 13l280.8 161.2-60.1 60.1zM47 0C34 6.8 25.3 19.2 25.3 35.3v441.3c0 16.1 8.7 28.5 21.7 35.3l256.6-256L47 0zm425.2 225.6l-58.9-34.1-65.7 64.5 65.7 64.5 60.1-34.1c18-14.3 18-46.5-1.2-60.8zM104.6 499l280.8-161.2-60.1-60.1L104.6 499z\"],\n    \"google-plus\": [496, 512, [], \"f2b3\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm-70.7 372c-68.8 0-124-55.5-124-124s55.2-124 124-124c31.3 0 60.1 11 83 32.3l-33.6 32.6c-13.2-12.9-31.3-19.1-49.4-19.1-42.9 0-77.2 35.5-77.2 78.1s34.2 78.1 77.2 78.1c32.6 0 64.9-19.1 70.1-53.3h-70.1v-42.6h116.9c1.3 6.8 1.9 13.6 1.9 20.7 0 70.8-47.5 121.2-118.8 121.2zm230.2-106.2v35.5H372v-35.5h-35.5v-35.5H372v-35.5h35.5v35.5h35.2v35.5h-35.2z\"],\n    \"google-plus-g\": [640, 512, [], \"f0d5\", \"M386.061 228.496c1.834 9.692 3.143 19.384 3.143 31.956C389.204 370.205 315.599 448 204.8 448c-106.084 0-192-85.915-192-192s85.916-192 192-192c51.864 0 95.083 18.859 128.611 50.292l-52.126 50.03c-14.145-13.621-39.028-29.599-76.485-29.599-65.484 0-118.92 54.221-118.92 121.277 0 67.056 53.436 121.277 118.92 121.277 75.961 0 104.513-54.745 108.965-82.773H204.8v-66.009h181.261zm185.406 6.437V179.2h-56.001v55.733h-55.733v56.001h55.733v55.733h56.001v-55.733H627.2v-56.001h-55.733z\"],\n    \"google-plus-square\": [448, 512, [], \"f0d4\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM164 356c-55.3 0-100-44.7-100-100s44.7-100 100-100c27 0 49.5 9.8 67 26.2l-27.1 26.1c-7.4-7.1-20.3-15.4-39.8-15.4-34.1 0-61.9 28.2-61.9 63.2 0 34.9 27.8 63.2 61.9 63.2 39.6 0 54.4-28.5 56.8-43.1H164v-34.4h94.4c1 5 1.6 10.1 1.6 16.6 0 57.1-38.3 97.6-96 97.6zm220-81.8h-29v29h-29.2v-29h-29V245h29v-29H355v29h29v29.2z\"],\n    \"google-wallet\": [448, 512, [], \"f1ee\", \"M156.8 126.8c37.6 60.6 64.2 113.1 84.3 162.5-8.3 33.8-18.8 66.5-31.3 98.3-13.2-52.3-26.5-101.3-56-148.5 6.5-36.4 2.3-73.6 3-112.3zM109.3 200H16.1c-6.5 0-10.5 7.5-6.5 12.7C51.8 267 81.3 330.5 101.3 400h103.5c-16.2-69.7-38.7-133.7-82.5-193.5-3-4-8-6.5-13-6.5zm47.8-88c68.5 108 130 234.5 138.2 368H409c-12-138-68.4-265-143.2-368H157.1zm251.8-68.5c-1.8-6.8-8.2-11.5-15.2-11.5h-88.3c-5.3 0-9 5-7.8 10.3 13.2 46.5 22.3 95.5 26.5 146 48.2 86.2 79.7 178.3 90.6 270.8 15.8-60.5 25.3-133.5 25.3-203 0-73.6-12.1-145.1-31.1-212.6z\"],\n    \"gratipay\": [496, 512, [], \"f184\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm114.6 226.4l-113 152.7-112.7-152.7c-8.7-11.9-19.1-50.4 13.6-72 28.1-18.1 54.6-4.2 68.5 11.9 15.9 17.9 46.6 16.9 61.7 0 13.9-16.1 40.4-30 68.1-11.9 32.9 21.6 22.6 60 13.8 72z\"],\n    \"grav\": [512, 512, [], \"f2d6\", \"M301.1 212c4.4 4.4 4.4 11.9 0 16.3l-9.7 9.7c-4.4 4.7-11.9 4.7-16.6 0l-10.5-10.5c-4.4-4.7-4.4-11.9 0-16.6l9.7-9.7c4.4-4.4 11.9-4.4 16.6 0l10.5 10.8zm-30.2-19.7c3-3 3-7.8 0-10.5-2.8-3-7.5-3-10.5 0-2.8 2.8-2.8 7.5 0 10.5 3.1 2.8 7.8 2.8 10.5 0zm-26 5.3c-3 2.8-3 7.5 0 10.2 2.8 3 7.5 3 10.5 0 2.8-2.8 2.8-7.5 0-10.2-3-3-7.7-3-10.5 0zm72.5-13.3c-19.9-14.4-33.8-43.2-11.9-68.1 21.6-24.9 40.7-17.2 59.8.8 11.9 11.3 29.3 24.9 17.2 48.2-12.5 23.5-45.1 33.2-65.1 19.1zm47.7-44.5c-8.9-10-23.3 6.9-15.5 16.1 7.4 9 32.1 2.4 15.5-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-66.2 42.6c2.5-16.1-20.2-16.6-25.2-25.7-13.6-24.1-27.7-36.8-54.5-30.4 11.6-8 23.5-6.1 23.5-6.1.3-6.4 0-13-9.4-24.9 3.9-12.5.3-22.4.3-22.4 15.5-8.6 26.8-24.4 29.1-43.2 3.6-31-18.8-59.2-49.8-62.8-22.1-2.5-43.7 7.7-54.3 25.7-23.2 40.1 1.4 70.9 22.4 81.4-14.4-1.4-34.3-11.9-40.1-34.3-6.6-25.7 2.8-49.8 8.9-61.4 0 0-4.4-5.8-8-8.9 0 0-13.8 0-24.6 5.3 11.9-15.2 25.2-14.4 25.2-14.4 0-6.4-.6-14.9-3.6-21.6-5.4-11-23.8-12.9-31.7 2.8.1-.2.3-.4.4-.5-5 11.9-1.1 55.9 16.9 87.2-2.5 1.4-9.1 6.1-13 10-21.6 9.7-56.2 60.3-56.2 60.3-28.2 10.8-77.2 50.9-70.6 79.7.3 3 1.4 5.5 3 7.5-2.8 2.2-5.5 5-8.3 8.3-11.9 13.8-5.3 35.2 17.7 24.4 15.8-7.2 29.6-20.2 36.3-30.4 0 0-5.5-5-16.3-4.4 27.7-6.6 34.3-9.4 46.2-9.1 8 3.9 8-34.3 8-34.3 0-14.7-2.2-31-11.1-41.5 12.5 12.2 29.1 32.7 28 60.6-.8 18.3-15.2 23-15.2 23-9.1 16.6-43.2 65.9-30.4 106 0 0-9.7-14.9-10.2-22.1-17.4 19.4-46.5 52.3-24.6 64.5 26.6 14.7 108.8-88.6 126.2-142.3 34.6-20.8 55.4-47.3 63.9-65 22 43.5 95.3 94.5 101.1 59z\"],\n    \"gripfire\": [384, 512, [], \"f3ac\", \"M112.5 301.4c0-73.8 105.1-122.5 105.1-203 0-47.1-34-88-39.1-90.4.4 3.3.6 6.7.6 10C179.1 110.1 32 171.9 32 286.6c0 49.8 32.2 79.2 66.5 108.3 65.1 46.7 78.1 71.4 78.1 86.6 0 10.1-4.8 17-4.8 22.3 13.1-16.7 17.4-31.9 17.5-46.4 0-29.6-21.7-56.3-44.2-86.5-16-22.3-32.6-42.6-32.6-69.5zm205.3-39c-12.1-66.8-78-124.4-94.7-130.9l4 7.2c2.4 5.1 3.4 10.9 3.4 17.1 0 44.7-54.2 111.2-56.6 116.7-2.2 5.1-3.2 10.5-3.2 15.8 0 20.1 15.2 42.1 17.9 42.1 2.4 0 56.6-55.4 58.1-87.7 6.4 11.7 9.1 22.6 9.1 33.4 0 41.2-41.8 96.9-41.8 96.9 0 11.6 31.9 53.2 35.5 53.2 1 0 2.2-1.4 3.2-2.4 37.9-39.3 67.3-85 67.3-136.8 0-8-.7-16.2-2.2-24.6z\"],\n    \"grunt\": [384, 512, [], \"f3ad\", \"M61.3 189.3c-1.1 10 5.2 19.1 5.2 19.1.7-7.5 2.2-12.8 4-16.6.4 10.3 3.2 23.5 12.8 34.1 6.9 7.6 35.6 23.3 54.9 6.1 1 2.4 2.1 5.3 3 8.5 2.9 10.3-2.7 25.3-2.7 25.3s15.1-17.1 13.9-32.5c10.8-.5 21.4-8.4 21.1-19.5 0 0-18.9 10.4-35.5-8.8-9.7-11.2-40.9-42-83.1-31.8 4.3 1 8.9 2.4 13.5 4.1h-.1c-4.2 2-6.5 7.1-7 12zm28.3-1.8c19.5 11 37.4 25.7 44.9 37-5.7 3.3-21.7 10.4-38-1.7-10.3-7.6-9.8-26.2-6.9-35.3zm142.1 45.8c-1.2 15.5 13.9 32.5 13.9 32.5s-5.6-15-2.7-25.3c.9-3.2 2-6 3-8.5 19.3 17.3 48 1.5 54.8-6.1 9.6-10.6 12.3-23.8 12.8-34.1 1.8 3.8 3.4 9.1 4 16.6 0 0 6.4-9.1 5.2-19.1-.6-5-2.9-10-7-11.8h-.1c4.6-1.8 9.2-3.2 13.5-4.1-42.3-10.2-73.4 20.6-83.1 31.8-16.7 19.2-35.5 8.8-35.5 8.8-.2 10.9 10.4 18.9 21.2 19.3zm62.7-45.8c3 9.1 3.4 27.7-7 35.4-16.3 12.1-32.2 5-37.9 1.6 7.5-11.4 25.4-26 44.9-37zM160 418.5h-29.4c-5.5 0-8.2 1.6-9.5 2.9-1.9 2-2.2 4.7-.9 8.1 3.5 9.1 11.4 16.5 13.7 18.6 3.1 2.7 7.5 4.3 11.8 4.3 4.4 0 8.3-1.7 11-4.6 7.5-8.2 11.9-17.1 13-19.8.6-1.5 1.3-4.5-.9-6.8-1.8-1.8-4.7-2.7-8.8-2.7zm189.2-101.2c-2.4 17.9-13 33.8-24.6 43.7-3.1-22.7-3.7-55.5-3.7-62.4 0-14.7 9.5-24.5 12.2-26.1 2.5-1.5 5.4-3 8.3-4.6 18-9.6 40.4-21.6 40.4-43.7 0-16.2-9.3-23.2-15.4-27.8-.8-.6-1.5-1.1-2.2-1.7-2.1-1.7-3.7-3-4.3-4.4-4.4-9.8-3.6-34.2-1.7-37.6.6-.6 16.7-20.9 11.8-39.2-2-7.4-6.9-13.3-14.1-17-5.3-2.7-11.9-4.2-19.5-4.5-.1-2-.5-3.9-.9-5.9-.6-2.6-1.1-5.3-.9-8.1.4-4.7.8-9 2.2-11.3 8.4-13.3 28.8-17.6 29-17.6l12.3-2.4-8.1-9.5c-.1-.2-17.3-17.5-46.3-17.5-7.9 0-16 1.3-24.1 3.9-24.2 7.8-42.9 30.5-49.4 39.3-3.1-1-6.3-1.9-9.6-2.7-4.2-15.8 9-38.5 9-38.5s-13.6-3-33.7 15.2c-2.6-6.5-8.1-20.5-1.8-37.2C184.6 10.1 177.2 26 175 40.4c-7.6-5.4-6.7-23.1-7.2-27.6-7.5.9-29.2 21.9-28.2 48.3-2 .5-3.9 1.1-5.9 1.7-6.5-8.8-25.1-31.5-49.4-39.3-7.9-2.2-16-3.5-23.9-3.5-29 0-46.1 17.3-46.3 17.5L6 46.9l12.3 2.4c.2 0 20.6 4.3 29 17.6 1.4 2.2 1.8 6.6 2.2 11.3.2 2.8-.4 5.5-.9 8.1-.4 1.9-.8 3.9-.9 5.9-7.7.3-14.2 1.8-19.5 4.5-7.2 3.7-12.1 9.6-14.1 17-5 18.2 11.2 38.5 11.8 39.2 1.9 3.4 2.7 27.8-1.7 37.6-.6 1.4-2.2 2.7-4.3 4.4-.7.5-1.4 1.1-2.2 1.7-6.1 4.6-15.4 11.7-15.4 27.8 0 22.1 22.4 34.1 40.4 43.7 3 1.6 5.8 3.1 8.3 4.6 2.7 1.6 12.2 11.4 12.2 26.1 0 6.9-.6 39.7-3.7 62.4-11.6-9.9-22.2-25.9-24.6-43.8 0 0-29.2 22.6-20.6 70.8 5.2 29.5 23.2 46.1 47 54.7 8.8 19.1 29.4 45.7 67.3 49.6C143 504.3 163 512 192.2 512h.2c29.1 0 49.1-7.7 63.6-19.5 37.9-3.9 58.5-30.5 67.3-49.6 23.8-8.7 41.7-25.2 47-54.7 8.2-48.4-21.1-70.9-21.1-70.9zM305.7 37.7c5.6-1.8 11.6-2.7 17.7-2.7 11 0 19.9 3 24.7 5-3.1 1.4-6.4 3.2-9.7 5.3-2.4-.4-5.6-.8-9.2-.8-10.5 0-20.5 3.1-28.7 8.9-12.3 8.7-18 16.9-20.7 22.4-2.2-1.3-4.5-2.5-7.1-3.7-1.6-.8-3.1-1.5-4.7-2.2 6.1-9.1 19.9-26.5 37.7-32.2zm21 18.2c-.8 1-1.6 2.1-2.3 3.2-3.3 5.2-3.9 11.6-4.4 17.8-.5 6.4-1.1 12.5-4.4 17-4.2.8-8.1 1.7-11.5 2.7-2.3-3.1-5.6-7-10.5-11.2 1.4-4.8 5.5-16.1 13.5-22.5 5.6-4.3 12.2-6.7 19.6-7zM45.6 45.3c-3.3-2.2-6.6-4-9.7-5.3 4.8-2 13.7-5 24.7-5 6.1 0 12 .9 17.7 2.7 17.8 5.8 31.6 23.2 37.7 32.1-1.6.7-3.2 1.4-4.8 2.2-2.5 1.2-4.9 2.5-7.1 3.7-2.6-5.4-8.3-13.7-20.7-22.4-8.3-5.8-18.2-8.9-28.8-8.9-3.4.1-6.6.5-9 .9zm44.7 40.1c-4.9 4.2-8.3 8-10.5 11.2-3.4-.9-7.3-1.9-11.5-2.7C65 89.5 64.5 83.4 64 77c-.5-6.2-1.1-12.6-4.4-17.8-.7-1.1-1.5-2.2-2.3-3.2 7.4.3 14 2.6 19.5 7 8 6.3 12.1 17.6 13.5 22.4zM58.1 259.9c-2.7-1.6-5.6-3.1-8.4-4.6-14.9-8-30.2-16.3-30.2-30.5 0-11.1 4.3-14.6 8.9-18.2l.5-.4c.7-.6 1.4-1.2 2.2-1.8-.9 7.2-1.9 13.3-2.7 14.9 0 0 12.1-15 15.7-44.3 1.4-11.5-1.1-34.3-5.1-43 .2 4.9 0 9.8-.3 14.4-.4-.8-.8-1.6-1.3-2.2-3.2-4-11.8-17.5-9.4-26.6.9-3.5 3.1-6 6.7-7.8 3.8-1.9 8.8-2.9 15.1-2.9 12.3 0 25.9 3.7 32.9 6 25.1 8 55.4 30.9 64.1 37.7.2.2.4.3.4.3l5.6 3.9-3.5-5.8c-.2-.3-19.1-31.4-53.2-46.5 2-2.9 7.4-8.1 21.6-15.1 21.4-10.5 46.5-15.8 74.3-15.8 27.9 0 52.9 5.3 74.3 15.8 14.2 6.9 19.6 12.2 21.6 15.1-34 15.1-52.9 46.2-53.1 46.5l-3.5 5.8 5.6-3.9s.2-.1.4-.3c8.7-6.8 39-29.8 64.1-37.7 7-2.2 20.6-6 32.9-6 6.3 0 11.3 1 15.1 2.9 3.5 1.8 5.7 4.4 6.7 7.8 2.5 9.1-6.1 22.6-9.4 26.6-.5.6-.9 1.3-1.3 2.2-.3-4.6-.5-9.5-.3-14.4-4 8.8-6.5 31.5-5.1 43 3.6 29.3 15.7 44.3 15.7 44.3-.8-1.6-1.8-7.7-2.7-14.9.7.6 1.5 1.2 2.2 1.8l.5.4c4.6 3.7 8.9 7.1 8.9 18.2 0 14.2-15.4 22.5-30.2 30.5-2.9 1.5-5.7 3.1-8.4 4.6-8.7 5-18 16.7-19.1 34.2-.9 14.6.9 49.9 3.4 75.9-12.4 4.8-26.7 6.4-39.7 6.8-2-4.1-3.9-8.5-5.5-13.1-.7-2-19.6-51.1-26.4-62.2 5.5 39 17.5 73.7 23.5 89.6-3.5-.5-7.3-.7-11.7-.7h-117c-4.4 0-8.3.3-11.7.7 6-15.9 18.1-50.6 23.5-89.6-6.8 11.2-25.7 60.3-26.4 62.2-1.6 4.6-3.5 9-5.5 13.1-13-.4-27.2-2-39.7-6.8 2.5-26 4.3-61.2 3.4-75.9-.9-17.4-10.3-29.2-19-34.2zM34.8 404.6c-12.1-20-8.7-54.1-3.7-59.1 10.9 34.4 47.2 44.3 74.4 45.4-2.7 4.2-5.2 7.6-7 10l-1.4 1.4c-7.2 7.8-8.6 18.5-4.1 31.8-22.7-.1-46.3-9.8-58.2-29.5zm45.7 43.5c6 1.1 12.2 1.9 18.6 2.4 3.5 8 7.4 15.9 12.3 23.1-14.4-5.9-24.4-16-30.9-25.5zM192 498.2c-60.6-.1-78.3-45.8-84.9-64.7-3.7-10.5-3.4-18.2.9-23.1 2.9-3.3 9.5-7.2 24.6-7.2h118.8c15.1 0 21.8 3.9 24.6 7.2 4.2 4.8 4.5 12.6.9 23.1-6.6 18.8-24.3 64.6-84.9 64.7zm80.6-24.6c4.9-7.2 8.8-15.1 12.3-23.1 6.4-.5 12.6-1.3 18.6-2.4-6.5 9.5-16.5 19.6-30.9 25.5zm76.6-69c-12 19.7-35.6 29.3-58.1 29.7 4.5-13.3 3.1-24.1-4.1-31.8-.4-.5-.9-1-1.4-1.5-1.8-2.4-4.3-5.8-7-10 27.2-1.2 63.5-11 74.4-45.4 5 5 8.4 39.1-3.8 59zM191.9 187.7h.2c12.7-.1 27.2-17.8 27.2-17.8-9.9 6-18.8 8.1-27.3 8.3-8.5-.2-17.4-2.3-27.3-8.3 0 0 14.5 17.6 27.2 17.8zm61.7 230.7h-29.4c-4.2 0-7.2.9-8.9 2.7-2.2 2.3-1.5 5.2-.9 6.7 1 2.6 5.5 11.3 13 19.3 2.7 2.9 6.6 4.5 11 4.5s8.7-1.6 11.8-4.2c2.3-2 10.2-9.2 13.7-18.1 1.3-3.3 1-6-.9-7.9-1.3-1.3-4-2.9-9.4-3z\"],\n    \"gulp\": [256, 512, [], \"f3ae\", \"M209.8 391.1l-14.1 24.6-4.6 80.2c0 8.9-28.3 16.1-63.1 16.1s-63.1-7.2-63.1-16.1l-5.8-79.4-14.9-25.4c41.2 17.3 126 16.7 165.6 0zm-196-253.3l13.6 125.5c5.9-20 20.8-47 40-55.2 6.3-2.7 12.7-2.7 18.7.9 5.2 3 9.6 9.3 10.1 11.8 1.2 6.5-2 9.1-4.5 9.1-3 0-5.3-4.6-6.8-7.3-4.1-7.3-10.3-7.6-16.9-2.8-6.9 5-12.9 13.4-17.1 20.7-5.1 8.8-9.4 18.5-12 28.2-1.5 5.6-2.9 14.6-.6 19.9 1 2.2 2.5 3.6 4.9 3.6 5 0 12.3-6.6 15.8-10.1 4.5-4.5 10.3-11.5 12.5-16l5.2-15.5c2.6-6.8 9.9-5.6 9.9 0 0 10.2-3.7 13.6-10 34.7-5.8 19.5-7.6 25.8-7.6 25.8-.7 2.8-3.4 7.5-6.3 7.5-1.2 0-2.1-.4-2.6-1.2-1-1.4-.9-5.3-.8-6.3.2-3.2 6.3-22.2 7.3-25.2-2 2.2-4.1 4.4-6.4 6.6-5.4 5.1-14.1 11.8-21.5 11.8-3.4 0-5.6-.9-7.7-2.4l7.6 79.6c2 5 39.2 17.1 88.2 17.1 49.1 0 86.3-12.2 88.2-17.1l10.9-94.6c-5.7 5.2-12.3 11.6-19.6 14.8-5.4 2.3-17.4 3.8-17.4-5.7 0-5.2 9.1-14.8 14.4-21.5 1.4-1.7 4.7-5.9 4.7-8.1 0-2.9-6-2.2-11.7 2.5-3.2 2.7-6.2 6.3-8.7 9.7-4.3 6-6.6 11.2-8.5 15.5-6.2 14.2-4.1 8.6-9.1 22-5 13.3-4.2 11.8-5.2 14-.9 1.9-2.2 3.5-4 4.5-1.9 1-4.5.9-6.1-.3-.9-.6-1.3-1.9-1.3-3.7 0-.9.1-1.8.3-2.7 1.5-6.1 7.8-18.1 15-34.3 1.6-3.7 1-2.6.8-2.3-6.2 6-10.9 8.9-14.4 10.5-5.8 2.6-13 2.6-14.5-4.1-.1-.4-.1-.8-.2-1.2-11.8 9.2-24.3 11.7-20-8.1-4.6 8.2-12.6 14.9-22.4 14.9-4.1 0-7.1-1.4-8.6-5.1-2.3-5.5 1.3-14.9 4.6-23.8 1.7-4.5 4-9.9 7.1-16.2 1.6-3.4 4.2-5.4 7.6-4.5.6.2 1.1.4 1.6.7 2.6 1.8 1.6 4.5.3 7.2-3.8 7.5-7.1 13-9.3 20.8-.9 3.3-2 9 1.5 9 2.4 0 4.7-.8 6.9-2.4 4.6-3.4 8.3-8.5 11.1-13.5 2-3.6 4.4-8.3 5.6-12.3.5-1.7 1.1-3.3 1.8-4.8 1.1-2.5 2.6-5.1 5.2-5.1 1.3 0 2.4.5 3.2 1.5 1.7 2.2 1.3 4.5.4 6.9-2 5.6-4.7 10.6-6.9 16.7-1.3 3.5-2.7 8-2.7 11.7 0 3.4 3.7 2.6 6.8 1.2 2.4-1.1 4.8-2.8 6.8-4.5 1.2-4.9.9-3.8 26.4-68.2 1.3-3.3 3.7-4.7 6.1-4.7 1.2 0 2.2.4 3.2 1.1 1.7 1.3 1.7 4.1 1 6.2-.7 1.9-.6 1.3-4.5 10.5-5.2 12.1-8.6 20.8-13.2 31.9-1.9 4.6-7.7 18.9-8.7 22.3-.6 2.2-1.3 5.8 1 5.8 5.4 0 19.3-13.1 23.1-17 .2-.3.5-.4.9-.6.6-1.9 1.2-3.7 1.7-5.5 1.4-3.8 2.7-8.2 5.3-11.3.8-1 1.7-1.6 2.7-1.6 2.8 0 4.2 1.2 4.2 4 0 1.1-.7 5.1-1.1 6.2 1.4-1.5 2.9-3 4.5-4.5 15-13.9 25.7-6.8 25.7.2 0 7.4-8.9 17.7-13.8 23.4-1.6 1.9-4.9 5.4-5 6.4 0 1.3.9 1.8 2.2 1.8 2 0 6.4-3.5 8-4.7 5-3.9 11.8-9.9 16.6-14.1l14.8-136.8c-30.5 17.1-197.6 17.2-228.3.2zm229.7-8.5c0 21-231.2 21-231.2 0 0-8.8 51.8-15.9 115.6-15.9 9 0 17.8.1 26.3.4l12.6-48.7L228.1.6c1.4-1.4 5.8-.2 9.9 3.5s6.6 7.9 5.3 9.3l-.1.1L185.9 74l-10 40.7c39.9 2.6 67.6 8.1 67.6 14.6zm-69.4 4.6c0-.8-.9-1.5-2.5-2.1l-.2.8c0 1.3-5 2.4-11.1 2.4s-11.1-1.1-11.1-2.4c0-.1 0-.2.1-.3l.2-.7c-1.8.6-3 1.4-3 2.3 0 2.1 6.2 3.7 13.7 3.7 7.7.1 13.9-1.6 13.9-3.7z\"],\n    \"hacker-news\": [448, 512, [], \"f1d4\", \"M0 32v448h448V32H0zm21.2 197.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hacker-news-square\": [448, 512, [], \"f3af\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.2 229.2H21c.1-.1.2-.3.3-.4 0 .1 0 .3-.1.4zm218 53.9V384h-31.4V281.3L128 128h37.3c52.5 98.3 49.2 101.2 59.3 125.6 12.3-27 5.8-24.4 60.6-125.6H320l-80.8 155.1z\"],\n    \"hackerrank\": [512, 512, [], \"f5f7\", \"M477.5 128C463 103.05 285.13 0 256.16 0S49.25 102.79 34.84 128s-14.49 230.8 0 256 192.38 128 221.32 128S463 409.08 477.49 384s14.51-231 .01-256zM316.13 414.22c-4 0-40.91-35.77-38-38.69.87-.87 6.26-1.48 17.55-1.83 0-26.23.59-68.59.94-86.32 0-2-.44-3.43-.44-5.85h-79.93c0 7.1-.46 36.2 1.37 72.88.23 4.54-1.58 6-5.74 5.94-10.13 0-20.27-.11-30.41-.08-4.1 0-5.87-1.53-5.74-6.11.92-33.44 3-84-.15-212.67v-3.17c-9.67-.35-16.38-1-17.26-1.84-2.92-2.92 34.54-38.69 38.49-38.69s41.17 35.78 38.27 38.69c-.87.87-7.9 1.49-16.77 1.84v3.16c-2.42 25.75-2 79.59-2.63 105.39h80.26c0-4.55.39-34.74-1.2-83.64-.1-3.39.95-5.17 4.21-5.2 11.07-.08 22.15-.13 33.23-.06 3.46 0 4.57 1.72 4.5 5.38C333 354.64 336 341.29 336 373.69c8.87.35 16.82 1 17.69 1.84 2.88 2.91-33.62 38.69-37.58 38.69z\"],\n    \"hips\": [640, 512, [], \"f452\", \"M251.6 157.6c0-1.9-.9-2.8-2.8-2.8h-40.9c-1.6 0-2.7 1.4-2.7 2.8v201.8c0 1.4 1.1 2.8 2.7 2.8h40.9c1.9 0 2.8-.9 2.8-2.8zM156.5 168c-16.1-11.8-36.3-17.9-60.3-18-18.1-.1-34.6 3.7-49.8 11.4V80.2c0-1.8-.9-2.7-2.8-2.7H2.7c-1.8 0-2.7.9-2.7 2.7v279.2c0 1.9.9 2.8 2.7 2.8h41c1.9 0 2.8-.9 2.8-2.8V223.3c0-.8-2.8-27 45.8-27 48.5 0 45.8 26.1 45.8 27v122.6c0 9 7.3 16.3 16.4 16.3h27.3c1.8 0 2.7-.9 2.7-2.8V223.3c0-23.4-9.3-41.8-28-55.3zm478.4 110.1c-6.8-15.7-18.4-27-34.9-34.1l-57.6-25.3c-8.6-3.6-9.2-11.2-2.6-16.1 7.4-5.5 44.3-13.9 84 6.8 1.7 1 4-.3 4-2.4v-44.7c0-1.3-.6-2.1-1.9-2.6-17.7-6.6-36.1-9.9-55.1-9.9-26.5 0-45.3 5.8-58.5 15.4-.5.4-28.4 20-22.7 53.7 3.4 19.6 15.8 34.2 37.2 43.6l53.6 23.5c11.6 5.1 15.2 13.3 12.2 21.2-3.7 9.1-13.2 13.6-36.5 13.6-24.3 0-44.7-8.9-58.4-19.1-2.1-1.4-4.4.2-4.4 2.3v34.4c0 10.4 4.9 17.3 14.6 20.7 15.6 5.5 31.6 8.2 48.2 8.2 12.7 0 25.8-1.2 36.3-4.3.7-.3 36-8.9 45.6-45.8 3.5-13.5 2.4-26.5-3.1-39.1zM376.2 149.8c-31.7 0-104.2 20.1-104.2 103.5v183.5c0 .8.6 2.7 2.7 2.7h40.9c1.9 0 2.8-.9 2.8-2.7V348c16.5 12.7 35.8 19.1 57.7 19.1 60.5 0 108.7-48.5 108.7-108.7.1-60.3-48.2-108.6-108.6-108.6zm0 170.9c-17.2 0-31.9-6.1-44-18.2-12.2-12.2-18.2-26.8-18.2-44 0-34.5 27.6-62.2 62.2-62.2 34.5 0 62.2 27.6 62.2 62.2.1 34.3-27.3 62.2-62.2 62.2zM228.3 72.5c-15.9 0-28.8 12.9-28.9 28.9 0 15.6 12.7 28.9 28.9 28.9s28.9-13.1 28.9-28.9c0-16.2-13-28.9-28.9-28.9z\"],\n    \"hire-a-helper\": [512, 512, [], \"f3b0\", \"M443.1 0H71.9C67.9 37.3 37.4 67.8 0 71.7v371.5c37.4 4.9 66 32.4 71.9 68.8h372.2c3-36.4 32.5-65.8 67.9-69.8V71.7c-36.4-5.9-65-35.3-68.9-71.7zm-37 404.9c-36.3 0-18.8-2-55.1-2-35.8 0-21 2-56.1 2-5.9 0-4.9-8.2 0-9.8 22.8-7.6 22.9-10.2 24.6-12.8 10.4-15.6 5.9-83 5.9-113 0-5.3-6.4-12.8-13.8-12.8H200.4c-7.4 0-13.8 7.5-13.8 12.8 0 30-4.5 97.4 5.9 113 1.7 2.5 1.8 5.2 24.6 12.8 4.9 1.6 6 9.8 0 9.8-35.1 0-20.3-2-56.1-2-36.3 0-18.8 2-55.1 2-7.9 0-5.8-10.8 0-10.8 10.2-3.4 13.5-3.5 21.7-13.8 7.7-12.9 7.9-44.4 7.9-127.8V151.3c0-22.2-12.2-28.3-28.6-32.4-8.8-2.2-4-11.8 1-11.8 36.5 0 20.6 2 57.1 2 32.7 0 16.5-2 49.2-2 3.3 0 8.5 8.3 1 10.8-4.9 1.6-27.6 3.7-27.6 39.3 0 45.6-.2 55.8 1 68.8 0 1.3 2.3 12.8 12.8 12.8h109.2c10.5 0 12.8-11.5 12.8-12.8 1.2-13 1-23.2 1-68.8 0-35.6-22.7-37.7-27.6-39.3-7.5-2.5-2.3-10.8 1-10.8 32.7 0 16.5 2 49.2 2 36.5 0 20.6-2 57.1-2 4.9 0 9.9 9.6 1 11.8-16.4 4.1-28.6 10.3-28.6 32.4v101.2c0 83.4.1 114.9 7.9 127.8 8.2 10.2 11.4 10.4 21.7 13.8 5.8 0 7.8 10.8 0 10.8z\"],\n    \"hooli\": [640, 512, [], \"f427\", \"M144.5 352l38.3.8c-13.2-4.6-26-10.2-38.3-16.8zm57.7-5.3v5.3l-19.4.8c36.5 12.5 69.9 14.2 94.7 7.2-19.9.2-45.8-2.6-75.3-13.3zm408.9-115.2c15.9 0 28.9-12.9 28.9-28.9s-12.9-24.5-28.9-24.5c-15.9 0-28.9 8.6-28.9 24.5s12.9 28.9 28.9 28.9zm-29 120.5H640V241.5h-57.9zm-73.7 0h57.9V156.7L508.4 184zm-31-119.4c-18.2-18.2-50.4-17.1-50.4-17.1s-32.3-1.1-50.4 17.1c-18.2 18.2-16.8 33.9-16.8 52.6s-1.4 34.3 16.8 52.5 50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.8-33.8 16.8-52.5-.1-18.8 1.3-34.5-16.8-52.6zm-39.8 71.9c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9zm-106.2-71.9c-18.2-18.2-50.4-17.1-50.4-17.1s-32.2-1.1-50.4 17.1c-1.9 1.9-3.7 3.9-5.3 6-38.2-29.6-72.5-46.5-102.1-61.1v-20.7l-22.5 10.6c-54.4-22.1-89-18.2-97.3.1 0 0-24.9 32.8 61.8 110.8V352h57.9v-28.6c-6.5-4.2-13-8.7-19.4-13.6-14.8-11.2-27.4-21.6-38.4-31.4v-31c13.1 14.7 30.5 31.4 53.4 50.3l4.5 3.6v-29.8c0-6.9 1.7-18.2 10.8-18.2s10.6 6.9 10.6 15V317c18 12.2 37.3 22.1 57.7 29.6v-93.9c0-18.7-13.4-37.4-40.6-37.4-15.8-.1-30.5 8.2-38.5 21.9v-54.3c41.9 20.9 83.9 46.5 99.9 58.3-10.2 14.6-9.3 28.1-9.3 43.7 0 18.7-1.4 34.3 16.8 52.5s50.4 17.1 50.4 17.1 32.3 1.1 50.4-17.1c18.2-18.2 16.7-33.8 16.7-52.5 0-18.5 1.5-34.2-16.7-52.3zM65.2 184v63.3c-48.7-54.5-38.9-76-35.2-79.1 13.5-11.4 37.5-8 64.4 2.1zm226.5 120.5c0 3.6-1.8 12.5-10.7 12.5s-10.7-8.9-10.7-12.5v-40.4c0-8.7 7.3-10.9 10.7-10.9s10.7 2.1 10.7 10.9z\"],\n    \"hornbill\": [512, 512, [], \"f592\", \"M76.38 370.3a37.8 37.8 0 1 1-32.07-32.42c-78.28-111.35 52-190.53 52-190.53-5.86 43-8.24 91.16-8.24 91.16-67.31 41.49.93 64.06 39.81 72.87a140.38 140.38 0 0 0 131.66 91.94c1.92 0 3.77-.21 5.67-.28l.11 18.86c-99.22 1.39-158.7-29.14-188.94-51.6zm108-327.7A37.57 37.57 0 0 0 181 21.45a37.95 37.95 0 1 0-31.17 54.22c-22.55 29.91-53.83 89.57-52.42 190l21.84-.15c0-.9-.14-1.77-.14-2.68A140.42 140.42 0 0 1 207 132.71c8-37.71 30.7-114.3 73.8-44.29 0 0 48.14 2.38 91.18 8.24 0 0-77.84-128-187.59-54.06zm304.19 134.17a37.94 37.94 0 1 0-53.84-28.7C403 126.13 344.89 99 251.28 100.33l.14 22.5c2.7-.15 5.39-.41 8.14-.41a140.37 140.37 0 0 1 130.49 88.76c39.1 9 105.06 31.58 38.46 72.54 0 0-2.34 48.13-8.21 91.16 0 0 133.45-81.16 49-194.61a37.45 37.45 0 0 0 19.31-3.5zM374.06 436.24c21.43-32.46 46.42-89.69 45.14-179.66l-19.52.14c.08 2.06.3 4.07.3 6.15a140.34 140.34 0 0 1-91.39 131.45c-8.85 38.95-31.44 106.66-72.77 39.49 0 0-48.12-2.34-91.19-8.22 0 0 79.92 131.34 191.9 51a37.5 37.5 0 0 0 3.64 14 37.93 37.93 0 1 0 33.89-54.29z\"],\n    \"hotjar\": [448, 512, [], \"f3b1\", \"M414.9 161.5C340.2 29 121.1 0 121.1 0S222.2 110.4 93 197.7C11.3 252.8-21 324.4 14 402.6c26.8 59.9 83.5 84.3 144.6 93.4-29.2-55.1-6.6-122.4-4.1-129.6 57.1 86.4 165 0 110.8-93.9 71 15.4 81.6 138.6 27.1 215.5 80.5-25.3 134.1-88.9 148.8-145.6 15.5-59.3 3.7-127.9-26.3-180.9z\"],\n    \"houzz\": [448, 512, [], \"f27c\", \"M275.9 330.7H171.3V480H17V32h109.5v104.5l305.1 85.6V480H275.9z\"],\n    \"html5\": [384, 512, [], \"f13b\", \"M0 32l34.9 395.8L191.5 480l157.6-52.2L384 32H0zm308.2 127.9H124.4l4.1 49.4h175.6l-13.6 148.4-97.9 27v.3h-1.1l-98.7-27.3-6-75.8h47.7L138 320l53.5 14.5 53.7-14.5 6-62.2H84.3L71.5 112.2h241.1l-4.4 47.7z\"],\n    \"hubspot\": [512, 512, [], \"f3b2\", \"M267.4 211.6c-25.1 23.7-40.8 57.3-40.8 94.6 0 29.3 9.7 56.3 26 78L203.1 434c-4.4-1.6-9.1-2.5-14-2.5-10.8 0-20.9 4.2-28.5 11.8-7.6 7.6-11.8 17.8-11.8 28.6s4.2 20.9 11.8 28.5c7.6 7.6 17.8 11.6 28.5 11.6 10.8 0 20.9-3.9 28.6-11.6 7.6-7.6 11.8-17.8 11.8-28.5 0-4.2-.6-8.2-1.9-12.1l50-50.2c22 16.9 49.4 26.9 79.3 26.9 71.9 0 130-58.3 130-130.2 0-65.2-47.7-119.2-110.2-128.7V116c17.5-7.4 28.2-23.8 28.2-42.9 0-26.1-20.9-47.9-47-47.9S311.2 47 311.2 73.1c0 19.1 10.7 35.5 28.2 42.9v61.2c-15.2 2.1-29.6 6.7-42.7 13.6-27.6-20.9-117.5-85.7-168.9-124.8 1.2-4.4 2-9 2-13.8C129.8 23.4 106.3 0 77.4 0 48.6 0 25.2 23.4 25.2 52.2c0 28.9 23.4 52.3 52.2 52.3 9.8 0 18.9-2.9 26.8-7.6l163.2 114.7zm89.5 163.6c-38.1 0-69-30.9-69-69s30.9-69 69-69 69 30.9 69 69-30.9 69-69 69z\"],\n    \"imdb\": [448, 512, [], \"f2d8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM21.3 229.2H21c.1-.1.2-.3.3-.4zM97 319.8H64V192h33zm113.2 0h-28.7v-86.4l-11.6 86.4h-20.6l-12.2-84.5v84.5h-29V192h42.8c3.3 19.8 6 39.9 8.7 59.9l7.6-59.9h43zm11.4 0V192h24.6c17.6 0 44.7-1.6 49 20.9 1.7 7.6 1.4 16.3 1.4 24.4 0 88.5 11.1 82.6-75 82.5zm160.9-29.2c0 15.7-2.4 30.9-22.2 30.9-9 0-15.2-3-20.9-9.8l-1.9 8.1h-29.8V192h31.7v41.7c6-6.5 12-9.2 20.9-9.2 21.4 0 22.2 12.8 22.2 30.1zM265 229.9c0-9.7 1.6-16-10.3-16v83.7c12.2.3 10.3-8.7 10.3-18.4zm85.5 26.1c0-5.4 1.1-12.7-6.2-12.7-6 0-4.9 8.9-4.9 12.7 0 .6-1.1 39.6 1.1 44.7.8 1.6 2.2 2.4 3.8 2.4 7.8 0 6.2-9 6.2-14.4z\"],\n    \"instagram\": [448, 512, [], \"f16d\", \"M224.1 141c-63.6 0-114.9 51.3-114.9 114.9s51.3 114.9 114.9 114.9S339 319.5 339 255.9 287.7 141 224.1 141zm0 189.6c-41.1 0-74.7-33.5-74.7-74.7s33.5-74.7 74.7-74.7 74.7 33.5 74.7 74.7-33.6 74.7-74.7 74.7zm146.4-194.3c0 14.9-12 26.8-26.8 26.8-14.9 0-26.8-12-26.8-26.8s12-26.8 26.8-26.8 26.8 12 26.8 26.8zm76.1 27.2c-1.7-35.9-9.9-67.7-36.2-93.9-26.2-26.2-58-34.4-93.9-36.2-37-2.1-147.9-2.1-184.9 0-35.8 1.7-67.6 9.9-93.9 36.1s-34.4 58-36.2 93.9c-2.1 37-2.1 147.9 0 184.9 1.7 35.9 9.9 67.7 36.2 93.9s58 34.4 93.9 36.2c37 2.1 147.9 2.1 184.9 0 35.9-1.7 67.7-9.9 93.9-36.2 26.2-26.2 34.4-58 36.2-93.9 2.1-37 2.1-147.8 0-184.8zM398.8 388c-7.8 19.6-22.9 34.7-42.6 42.6-29.5 11.7-99.5 9-132.1 9s-102.7 2.6-132.1-9c-19.6-7.8-34.7-22.9-42.6-42.6-11.7-29.5-9-99.5-9-132.1s-2.6-102.7 9-132.1c7.8-19.6 22.9-34.7 42.6-42.6 29.5-11.7 99.5-9 132.1-9s102.7-2.6 132.1 9c19.6 7.8 34.7 22.9 42.6 42.6 11.7 29.5 9 99.5 9 132.1s2.7 102.7-9 132.1z\"],\n    \"intercom\": [448, 512, [], \"f7af\", \"M392 32H56C25.1 32 0 57.1 0 88v336c0 30.9 25.1 56 56 56h336c30.9 0 56-25.1 56-56V88c0-30.9-25.1-56-56-56zm-108.3 82.1c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zm-74.6-7.5c0-19.8 29.9-19.8 29.9 0v216.5c0 19.8-29.9 19.8-29.9 0V106.6zm-74.7 7.5c0-19.8 29.9-19.8 29.9 0v199.5c0 19.8-29.9 19.8-29.9 0V114.1zM59.7 144c0-19.8 29.9-19.8 29.9 0v134.3c0 19.8-29.9 19.8-29.9 0V144zm323.4 227.8c-72.8 63-241.7 65.4-318.1 0-15-12.8 4.4-35.5 19.4-22.7 65.9 55.3 216.1 53.9 279.3 0 14.9-12.9 34.3 9.8 19.4 22.7zm5.2-93.5c0 19.8-29.9 19.8-29.9 0V144c0-19.8 29.9-19.8 29.9 0v134.3z\"],\n    \"internet-explorer\": [512, 512, [], \"f26b\", \"M483.049 159.706c10.855-24.575 21.424-60.438 21.424-87.871 0-72.722-79.641-98.371-209.673-38.577-107.632-7.181-211.221 73.67-237.098 186.457 30.852-34.862 78.271-82.298 121.977-101.158C125.404 166.85 79.128 228.002 43.992 291.725 23.246 329.651 0 390.94 0 436.747c0 98.575 92.854 86.5 180.251 42.006 31.423 15.43 66.559 15.573 101.695 15.573 97.124 0 184.249-54.294 216.814-146.022H377.927c-52.509 88.593-196.819 52.996-196.819-47.436H509.9c6.407-43.581-1.655-95.715-26.851-141.162zM64.559 346.877c17.711 51.15 53.703 95.871 100.266 123.304-88.741 48.94-173.267 29.096-100.266-123.304zm115.977-108.873c2-55.151 50.276-94.871 103.98-94.871 53.418 0 101.981 39.72 103.981 94.871H180.536zm184.536-187.6c21.425-10.287 48.563-22.003 72.558-22.003 31.422 0 54.274 21.717 54.274 53.722 0 20.003-7.427 49.007-14.569 67.867-26.28-42.292-65.986-81.584-112.263-99.586z\"],\n    \"invision\": [448, 512, [], \"f7b0\", \"M407.4 32H40.6C18.2 32 0 50.2 0 72.6v366.8C0 461.8 18.2 480 40.6 480h366.8c22.4 0 40.6-18.2 40.6-40.6V72.6c0-22.4-18.2-40.6-40.6-40.6zM176.1 145.6c.4 23.4-22.4 27.3-26.6 27.4-14.9 0-27.1-12-27.1-27 .1-35.2 53.1-35.5 53.7-.4zM332.8 377c-65.6 0-34.1-74-25-106.6 14.1-46.4-45.2-59-59.9.7l-25.8 103.3H177l8.1-32.5c-31.5 51.8-94.6 44.4-94.6-4.3.1-14.3.9-14 23-104.1H81.7l9.7-35.6h76.4c-33.6 133.7-32.6 126.9-32.9 138.2 0 20.9 40.9 13.5 57.4-23.2l19.8-79.4h-32.3l9.7-35.6h68.8l-8.9 40.5c40.5-75.5 127.9-47.8 101.8 38-14.2 51.1-14.6 50.7-14.9 58.8 0 15.5 17.5 22.6 31.8-16.9L386 325c-10.5 36.7-29.4 52-53.2 52z\"],\n    \"ioxhost\": [640, 512, [], \"f208\", \"M616 160h-67.3C511.2 70.7 422.9 8 320 8 183 8 72 119 72 256c0 16.4 1.6 32.5 4.7 48H24c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h67.3c37.5 89.3 125.8 152 228.7 152 137 0 248-111 248-248 0-16.4-1.6-32.5-4.7-48H616c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24zm-96 96c0 110.5-89.5 200-200 200-75.7 0-141.6-42-175.5-104H424c13.3 0 24-10.8 24-24 0-13.3-10.7-24-24-24H125.8c-3.8-15.4-5.8-31.4-5.8-48 0-110.5 89.5-200 200-200 75.7 0 141.6 42 175.5 104H216c-13.3 0-24 10.8-24 24 0 13.3 10.7 24 24 24h298.2c3.8 15.4 5.8 31.4 5.8 48zm-304-24h208c13.3 0 24 10.7 24 24 0 13.2-10.7 24-24 24H216c-13.3 0-24-10.7-24-24 0-13.2 10.7-24 24-24z\"],\n    \"itch-io\": [512, 512, [], \"f83a\", \"M71.92 34.77C50.2 47.67 7.4 96.84 7 109.73v21.34c0 27.06 25.29 50.84 48.25 50.84 27.57 0 50.54-22.85 50.54-50 0 27.12 22.18 50 49.76 50s49-22.85 49-50c0 27.12 23.59 50 51.16 50h.5c27.57 0 51.16-22.85 51.16-50 0 27.12 21.47 50 49 50s49.76-22.85 49.76-50c0 27.12 23 50 50.54 50 23 0 48.25-23.78 48.25-50.84v-21.34c-.4-12.9-43.2-62.07-64.92-75C372.56 32.4 325.76 32 256 32S91.14 33.1 71.92 34.77zm132.32 134.39c-22 38.4-77.9 38.71-99.85.25-13.17 23.14-43.17 32.07-56 27.66-3.87 40.15-13.67 237.13 17.73 269.15 80 18.67 302.08 18.12 379.76 0 31.65-32.27 21.32-232 17.75-269.15-12.92 4.44-42.88-4.6-56-27.66-22 38.52-77.85 38.1-99.85-.24-7.1 12.49-23.05 28.94-51.76 28.94a57.54 57.54 0 0 1-51.75-28.94zm-41.58 53.77c16.47 0 31.09 0 49.22 19.78a436.91 436.91 0 0 1 88.18 0C318.22 223 332.85 223 349.31 223c52.33 0 65.22 77.53 83.87 144.45 17.26 62.15-5.52 63.67-33.95 63.73-42.15-1.57-65.49-32.18-65.49-62.79-39.25 6.43-101.93 8.79-155.55 0 0 30.61-23.34 61.22-65.49 62.79-28.42-.06-51.2-1.58-33.94-63.73 18.67-67 31.56-144.45 83.88-144.45zM256 270.79s-44.38 40.77-52.35 55.21l29-1.17v25.32c0 1.55 21.34.16 23.33.16 11.65.54 23.31 1 23.31-.16v-25.28l29 1.17c-8-14.48-52.35-55.24-52.35-55.24z\"],\n    \"itunes\": [448, 512, [], \"f3b4\", \"M223.6 80.3C129 80.3 52.5 157 52.5 251.5S129 422.8 223.6 422.8s171.2-76.7 171.2-171.2c0-94.6-76.7-171.3-171.2-171.3zm79.4 240c-3.2 13.6-13.5 21.2-27.3 23.8-12.1 2.2-22.2 2.8-31.9-5-11.8-10-12-26.4-1.4-36.8 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 3.2-3.6 2.2-2 2.2-80.8 0-5.6-2.7-7.1-8.4-6.1-4 .7-91.9 17.1-91.9 17.1-5 1.1-6.7 2.6-6.7 8.3 0 116.1.5 110.8-1.2 118.5-2.1 9-7.6 15.8-14.9 19.6-8.3 4.6-23.4 6.6-31.4 5.2-21.4-4-28.9-28.7-14.4-42.9 8.4-8 20.3-9.6 38-12.8 3-.5 5.6-1.2 7.7-3.7 5-5.7.9-127 2.6-133.7.4-2.6 1.5-4.8 3.5-6.4 2.1-1.7 5.8-2.7 6.7-2.7 101-19 113.3-21.4 115.1-21.4 5.7-.4 9 3 9 8.7-.1 170.6.4 161.4-1 167.6zM345.2 32H102.8C45.9 32 0 77.9 0 134.8v242.4C0 434.1 45.9 480 102.8 480h242.4c57 0 102.8-45.9 102.8-102.8V134.8C448 77.9 402.1 32 345.2 32zM223.6 444c-106.3 0-192.5-86.2-192.5-192.5S117.3 59 223.6 59s192.5 86.2 192.5 192.5S329.9 444 223.6 444z\"],\n    \"itunes-note\": [384, 512, [], \"f3b5\", \"M381.9 388.2c-6.4 27.4-27.2 42.8-55.1 48-24.5 4.5-44.9 5.6-64.5-10.2-23.9-20.1-24.2-53.4-2.7-74.4 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 6.4-7.2 4.4-4.1 4.4-163.2 0-11.2-5.5-14.3-17-12.3-8.2 1.4-185.7 34.6-185.7 34.6-10.2 2.2-13.4 5.2-13.4 16.7 0 234.7 1.1 223.9-2.5 239.5-4.2 18.2-15.4 31.9-30.2 39.5-16.8 9.3-47.2 13.4-63.4 10.4-43.2-8.1-58.4-58-29.1-86.6 17-16.2 40.9-19.5 76.8-25.8 6-1.1 11.2-2.5 15.6-7.4 10.1-11.5 1.8-256.6 5.2-270.2.8-5.2 3-9.6 7.1-12.9 4.2-3.5 11.8-5.5 13.4-5.5 204-38.2 228.9-43.1 232.4-43.1 11.5-.8 18.1 6 18.1 17.6.2 344.5 1.1 326-1.8 338.5z\"],\n    \"java\": [384, 512, [], \"f4e4\", \"M277.74 312.9c9.8-6.7 23.4-12.5 23.4-12.5s-38.7 7-77.2 10.2c-47.1 3.9-97.7 4.7-123.1 1.3-60.1-8 33-30.1 33-30.1s-36.1-2.4-80.6 19c-52.5 25.4 130 37 224.5 12.1zm-85.4-32.1c-19-42.7-83.1-80.2 0-145.8C296 53.2 242.84 0 242.84 0c21.5 84.5-75.6 110.1-110.7 162.6-23.9 35.9 11.7 74.4 60.2 118.2zm114.6-176.2c.1 0-175.2 43.8-91.5 140.2 24.7 28.4-6.5 54-6.5 54s62.7-32.4 33.9-72.9c-26.9-37.8-47.5-56.6 64.1-121.3zm-6.1 270.5a12.19 12.19 0 0 1-2 2.6c128.3-33.7 81.1-118.9 19.8-97.3a17.33 17.33 0 0 0-8.2 6.3 70.45 70.45 0 0 1 11-3c31-6.5 75.5 41.5-20.6 91.4zM348 437.4s14.5 11.9-15.9 21.2c-57.9 17.5-240.8 22.8-291.6.7-18.3-7.9 16-19 26.8-21.3 11.2-2.4 17.7-2 17.7-2-20.3-14.3-131.3 28.1-56.4 40.2C232.84 509.4 401 461.3 348 437.4zM124.44 396c-78.7 22 47.9 67.4 148.1 24.5a185.89 185.89 0 0 1-28.2-13.8c-44.7 8.5-65.4 9.1-106 4.5-33.5-3.8-13.9-15.2-13.9-15.2zm179.8 97.2c-78.7 14.8-175.8 13.1-233.3 3.6 0-.1 11.8 9.7 72.4 13.6 92.2 5.9 233.8-3.3 237.1-46.9 0 0-6.4 16.5-76.2 29.7zM260.64 353c-59.2 11.4-93.5 11.1-136.8 6.6-33.5-3.5-11.6-19.7-11.6-19.7-86.8 28.8 48.2 61.4 169.5 25.9a60.37 60.37 0 0 1-21.1-12.8z\"],\n    \"jedi-order\": [448, 512, [], \"f50e\", \"M398.5 373.6c95.9-122.1 17.2-233.1 17.2-233.1 45.4 85.8-41.4 170.5-41.4 170.5 105-171.5-60.5-271.5-60.5-271.5 96.9 72.7-10.1 190.7-10.1 190.7 85.8 158.4-68.6 230.1-68.6 230.1s-.4-16.9-2.2-85.7c4.3 4.5 34.5 36.2 34.5 36.2l-24.2-47.4 62.6-9.1-62.6-9.1 20.2-55.5-31.4 45.9c-2.2-87.7-7.8-305.1-7.9-306.9v-2.4 1-1 2.4c0 1-5.6 219-7.9 306.9l-31.4-45.9 20.2 55.5-62.6 9.1 62.6 9.1-24.2 47.4 34.5-36.2c-1.8 68.8-2.2 85.7-2.2 85.7s-154.4-71.7-68.6-230.1c0 0-107-118.1-10.1-190.7 0 0-165.5 99.9-60.5 271.5 0 0-86.8-84.8-41.4-170.5 0 0-78.7 111 17.2 233.1 0 0-26.2-16.1-49.4-77.7 0 0 16.9 183.3 222 185.7h4.1c205-2.4 222-185.7 222-185.7-23.6 61.5-49.9 77.7-49.9 77.7z\"],\n    \"jenkins\": [512, 512, [], \"f3b6\", \"M487.1 425c-1.4-11.2-19-23.1-28.2-31.9-5.1-5-29-23.1-30.4-29.9-1.4-6.6 9.7-21.5 13.3-28.9 5.1-10.7 8.8-23.7 11.3-32.6 18.8-66.1 20.7-156.9-6.2-211.2-10.2-20.6-38.6-49-56.4-62.5-42-31.7-119.6-35.3-170.1-16.6-14.1 5.2-27.8 9.8-40.1 17.1-33.1 19.4-68.3 32.5-78.1 71.6-24.2 10.8-31.5 41.8-30.3 77.8.2 7 4.1 15.8 2.7 22.4-.7 3.3-5.2 7.6-6.1 9.8-11.6 27.7-2.3 64 11.1 83.7 8.1 11.9 21.5 22.4 39.2 25.2.7 10.6 3.3 19.7 8.2 30.4 3.1 6.8 14.7 19 10.4 27.7-2.2 4.4-21 13.8-27.3 17.6C89 407.2 73.7 415 54.2 429c-12.6 9-32.3 10.2-29.2 31.1 2.1 14.1 10.1 31.6 14.7 45.8.7 2 1.4 4.1 2.1 6h422c4.9-15.3 9.7-30.9 14.6-47.2 3.4-11.4 10.2-27.8 8.7-39.7zM205.9 33.7c1.8-.5 3.4.7 4.9 2.4-.2 5.2-5.4 5.1-8.9 6.8-5.4 6.7-13.4 9.8-20 17.2-6.8 7.5-14.4 27.7-23.4 30-4.5 1.1-9.7-.8-13.6-.5-10.4.7-17.7 6-28.3 7.5 13.6-29.9 56.1-54 89.3-63.4zm-104.8 93.6c13.5-14.9 32.1-24.1 54.8-25.9 11.7 29.7-8.4 65-.9 97.6 2.3 9.9 10.2 25.4-2.4 25.7.3-28.3-34.8-46.3-61.3-29.6-1.8-21.5-4.9-51.7 9.8-67.8zm36.7 200.2c-1-4.1-2.7-12.9-2.3-15.1 1.6-8.7 17.1-12.5 11-24.7-11.3-.1-13.8 10.2-24.1 11.3-26.7 2.6-45.6-35.4-44.4-58.4 1-19.5 17.6-38.2 40.1-35.8 16 1.8 21.4 19.2 24.5 34.7 9.2.5 22.5-.4 26.9-7.6-.6-17.5-8.8-31.6-8.2-47.7 1-30.3 17.5-57.6 4.8-87.4 13.6-30.9 53.5-55.3 83.1-70 36.6-18.3 94.9-3.7 129.3 15.8 19.7 11.1 34.4 32.7 48.3 50.7-19.5-5.8-36.1 4.2-33.1 20.3 16.3-14.9 44.2-.2 52.5 16.4 7.9 15.8 7.8 39.3 9 62.8 2.9 57-10.4 115.9-39.1 157.1-7.7 11-14.1 23-24.9 30.6-26 18.2-65.4 34.7-99.2 23.4-44.7-15-65-44.8-89.5-78.8.7 18.7 13.8 34.1 26.8 48.4 11.3 12.5 25 26.6 39.7 32.4-12.3-2.9-31.1-3.8-36.2 7.2-28.6-1.9-55.1-4.8-68.7-24.2-10.6-15.4-21.4-41.4-26.3-61.4zm222 124.1c4.1-3 11.1-2.9 17.4-3.6-5.4-2.7-13-3.7-19.3-2.2-.1-4.2-2-6.8-3.2-10.2 10.6-3.8 35.5-28.5 49.6-20.3 6.7 3.9 9.5 26.2 10.1 37 .4 9-.8 18-4.5 22.8-18.8-.6-35.8-2.8-50.7-7 .9-6.1-1-12.1.6-16.5zm-17.2-20c-16.8.8-26-1.2-38.3-10.8.2-.8 1.4-.5 1.5-1.4 18 8 40.8-3.3 59-4.9-7.9 5.1-14.6 11.6-22.2 17.1zm-12.1 33.2c-1.6-9.4-3.5-12-2.8-20.2 25-16.6 29.7 28.6 2.8 20.2zM226 438.6c-11.6-.7-48.1-14-38.5-23.7 9.4 6.5 27.5 4.9 41.3 7.3.8 4.4-2.8 10.2-2.8 16.4zM57.7 497.1c-4.3-12.7-9.2-25.1-14.8-36.9 30.8-23.8 65.3-48.9 102.2-63.5 2.8-1.1 23.2 25.4 26.2 27.6 16.5 11.7 37 21 56.2 30.2 1.2 8.8 3.9 20.2 8.7 35.5.7 2.3 1.4 4.7 2.2 7.2H57.7zm240.6 5.7h-.8c.3-.2.5-.4.8-.5v.5zm7.5-5.7c2.1-1.4 4.3-2.8 6.4-4.3 1.1 1.4 2.2 2.8 3.2 4.3h-9.6zm15.1-24.7c-10.8 7.3-20.6 18.3-33.3 25.2-6 3.3-27 11.7-33.4 10.2-3.6-.8-3.9-5.3-5.4-9.5-3.1-9-10.1-23.4-10.8-37-.8-17.2-2.5-46 16-42.4 14.9 2.9 32.3 9.7 43.9 16.1 7.1 3.9 11.1 8.6 21.9 9.5-.1 1.4-.1 2.8-.2 4.3-5.9 3.9-15.3 3.8-21.8 7.1 9.5.4 17 2.7 23.5 5.9-.1 3.4-.3 7-.4 10.6zm53.4 24.7h-14c-.1-3.2-2.8-5.8-6.1-5.8s-5.9 2.6-6.1 5.8h-17.4c-2.8-4.4-5.7-8.6-8.9-12.5 2.1-2.2 4-4.7 6-6.9 9 3.7 14.8-4.9 21.7-4.2 7.9.8 14.2 11.7 25.4 11l-.6 12.6zm8.7 0c.2-4 .4-7.8.6-11.5 15.6-7.3 29 1.3 35.7 11.5H383zm83.4-37c-2.3 11.2-5.8 24-9.9 37.1-.2-.1-.4-.1-.6-.1H428c.6-1.1 1.2-2.2 1.9-3.3-2.6-6.1-9-8.7-10.9-15.5 12.1-22.7 6.5-93.4-24.2-78.5 4.3-6.3 15.6-11.5 20.8-19.3 13 10.4 20.8 20.3 33.2 31.4 6.8 6 20 13.3 21.4 23.1.8 5.5-2.6 18.9-3.8 25.1zM222.2 130.5c5.4-14.9 27.2-34.7 45-32 7.7 1.2 18 8.2 12.2 17.7-30.2-7-45.2 12.6-54.4 33.1-8.1-2-4.9-13.1-2.8-18.8zm184.1 63.1c8.2-3.6 22.4-.7 29.6-5.3-4.2-11.5-10.3-21.4-9.3-37.7.5 0 1 0 1.4.1 6.8 14.2 12.7 29.2 21.4 41.7-5.7 13.5-43.6 25.4-43.1 1.2zm20.4-43zm-117.2 45.7c-6.8-10.9-19-32.5-14.5-45.3 6.5 11.9 8.6 24.4 17.8 33.3 4.1 4 12.2 9 8.2 20.2-.9 2.7-7.8 8.6-11.7 9.7-14.4 4.3-47.9.9-36.6-17.1 11.9.7 27.9 7.8 36.8-.8zm27.3 70c3.8 6.6 1.4 18.7 12.1 20.6 20.2 3.4 43.6-12.3 58.1-17.8 9-15.2-.8-20.7-8.9-30.5-16.6-20-38.8-44.8-38-74.7 6.7-4.9 7.3 7.4 8.2 9.7 8.7 20.3 30.4 46.2 46.3 63.5 3.9 4.3 10.3 8.4 11 11.2 2.1 8.2-5.4 18-4.5 23.5-21.7 13.9-45.8 29.1-81.4 25.6-7.4-6.7-10.3-21.4-2.9-31.1zm-201.3-9.2c-6.8-3.9-8.4-21-16.4-21.4-11.4-.7-9.3 22.2-9.3 35.5-7.8-7.1-9.2-29.1-3.5-40.3-6.6-3.2-9.5 3.6-13.1 5.9 4.7-34.1 49.8-15.8 42.3 20.3zm299.6 28.8c-10.1 19.2-24.4 40.4-54 41-.6-6.2-1.1-15.6 0-19.4 22.7-2.2 36.6-13.7 54-21.6zm-141.9 12.4c18.9 9.9 53.6 11 79.3 10.2 1.4 5.6 1.3 12.6 1.4 19.4-33 1.8-72-6.4-80.7-29.6zm92.2 46.7c-1.7 4.3-5.3 9.3-9.8 11.1-12.1 4.9-45.6 8.7-62.4-.3-10.7-5.7-17.5-18.5-23.4-26-2.8-3.6-16.9-12.9-.2-12.9 13.1 32.7 58 29 95.8 28.1z\"],\n    \"jira\": [496, 512, [], \"f7b1\", \"M490 241.7C417.1 169 320.6 71.8 248.5 0 83 164.9 6 241.7 6 241.7c-7.9 7.9-7.9 20.7 0 28.7C138.8 402.7 67.8 331.9 248.5 512c379.4-378 15.7-16.7 241.5-241.7 8-7.9 8-20.7 0-28.6zm-241.5 90l-76-75.7 76-75.7 76 75.7-76 75.7z\"],\n    \"joget\": [496, 512, [], \"f3b7\", \"M378.1 45C337.6 19.9 292.6 8 248.2 8 165 8 83.8 49.9 36.9 125.9c-71.9 116.6-35.6 269.3 81 341.2s269.3 35.6 341.2-80.9c71.9-116.6 35.6-269.4-81-341.2zm51.8 323.2c-40.4 65.5-110.4 101.5-182 101.5-6.8 0-13.6-.4-20.4-1-9-13.6-19.9-33.3-23.7-42.4-5.7-13.7-27.2-45.6 31.2-67.1 51.7-19.1 176.7-16.5 208.8-17.6-4 9-8.6 17.9-13.9 26.6zm-200.8-86.3c-55.5-1.4-81.7-20.8-58.5-48.2s51.1-40.7 68.9-51.2c17.9-10.5 27.3-33.7-23.6-29.7C87.3 161.5 48.6 252.1 37.6 293c-8.8-49.7-.1-102.7 28.5-149.1C128 43.4 259.6 12.2 360.1 74.1c74.8 46.1 111.2 130.9 99.3 212.7-24.9-.5-179.3-3.6-230.3-4.9zm183.8-54.8c-22.7-6-57 11.3-86.7 27.2-29.7 15.8-31.1 8.2-31.1 8.2s40.2-28.1 50.7-34.5 31.9-14 13.4-24.6c-3.2-1.8-6.7-2.7-10.4-2.7-17.8 0-41.5 18.7-67.5 35.6-31.5 20.5-65.3 31.3-65.3 31.3l169.5-1.6 46.5-23.4s3.6-9.5-19.1-15.5z\"],\n    \"joomla\": [448, 512, [], \"f1aa\", \"M.6 92.1C.6 58.8 27.4 32 60.4 32c30 0 54.5 21.9 59.2 50.2 32.6-7.6 67.1.6 96.5 30l-44.3 44.3c-20.5-20.5-42.6-16.3-55.4-3.5-14.3 14.3-14.3 37.9 0 52.2l99.5 99.5-44 44.3c-87.7-87.2-49.7-49.7-99.8-99.7-26.8-26.5-35-64.8-24.8-98.9C20.4 144.6.6 120.7.6 92.1zm129.5 116.4l44.3 44.3c10-10 89.7-89.7 99.7-99.8 14.3-14.3 37.6-14.3 51.9 0 12.8 12.8 17 35-3.5 55.4l44 44.3c31.2-31.2 38.5-67.6 28.9-101.2 29.2-4.1 51.9-29.2 51.9-59.5 0-33.2-26.8-60.1-59.8-60.1-30.3 0-55.4 22.5-59.5 51.6-33.8-9.9-71.7-1.5-98.3 25.1-18.3 19.1-71.1 71.5-99.6 99.9zm266.3 152.2c8.2-32.7-.9-68.5-26.3-93.9-11.8-12.2 5 4.7-99.5-99.7l-44.3 44.3 99.7 99.7c14.3 14.3 14.3 37.6 0 51.9-12.8 12.8-35 17-55.4-3.5l-44 44.3c27.6 30.2 68 38.8 102.7 28 5.5 27.4 29.7 48.1 58.9 48.1 33 0 59.8-26.8 59.8-60.1 0-30.2-22.5-55-51.6-59.1zm-84.3-53.1l-44-44.3c-87 86.4-50.4 50.4-99.7 99.8-14.3 14.3-37.6 14.3-51.9 0-13.1-13.4-16.9-35.3 3.2-55.4l-44-44.3c-30.2 30.2-38 65.2-29.5 98.3-26.7 6-46.2 29.9-46.2 58.2C0 453.2 26.8 480 59.8 480c28.6 0 52.5-19.8 58.6-46.7 32.7 8.2 68.5-.6 94.2-26 32.1-32 12.2-12.4 99.5-99.7z\"],\n    \"js\": [448, 512, [], \"f3b8\", \"M0 32v448h448V32H0zm243.8 349.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"js-square\": [448, 512, [], \"f3b9\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM243.8 381.4c0 43.6-25.6 63.5-62.9 63.5-33.7 0-53.2-17.4-63.2-38.5l34.3-20.7c6.6 11.7 12.6 21.6 27.1 21.6 13.8 0 22.6-5.4 22.6-26.5V237.7h42.1v143.7zm99.6 63.5c-39.1 0-64.4-18.6-76.7-43l34.3-19.8c9 14.7 20.8 25.6 41.5 25.6 17.4 0 28.6-8.7 28.6-20.8 0-14.4-11.4-19.5-30.7-28l-10.5-4.5c-30.4-12.9-50.5-29.2-50.5-63.5 0-31.6 24.1-55.6 61.6-55.6 26.8 0 46 9.3 59.8 33.7L368 290c-7.2-12.9-15-18-27.1-18-12.3 0-20.1 7.8-20.1 18 0 12.6 7.8 17.7 25.9 25.6l10.5 4.5c35.8 15.3 55.9 31 55.9 66.2 0 37.8-29.8 58.6-69.7 58.6z\"],\n    \"jsfiddle\": [576, 512, [], \"f1cc\", \"M510.634 237.462c-4.727-2.621-5.664-5.748-6.381-10.776-2.352-16.488-3.539-33.619-9.097-49.095-35.895-99.957-153.99-143.386-246.849-91.646-27.37 15.25-48.971 36.369-65.493 63.903-3.184-1.508-5.458-2.71-7.824-3.686-30.102-12.421-59.049-10.121-85.331 9.167-25.531 18.737-36.422 44.548-32.676 76.408.355 3.025-1.967 7.621-4.514 9.545-39.712 29.992-56.031 78.065-41.902 124.615 13.831 45.569 57.514 79.796 105.608 81.433 30.291 1.031 60.637.546 90.959.539 84.041-.021 168.09.531 252.12-.48 52.664-.634 96.108-36.873 108.212-87.293 11.54-48.074-11.144-97.3-56.832-122.634zm21.107 156.88c-18.23 22.432-42.343 35.253-71.28 35.65-56.874.781-113.767.23-170.652.23 0 .7-163.028.159-163.728.154-43.861-.332-76.739-19.766-95.175-59.995-18.902-41.245-4.004-90.848 34.186-116.106 9.182-6.073 12.505-11.566 10.096-23.136-5.49-26.361 4.453-47.956 26.42-62.981 22.987-15.723 47.422-16.146 72.034-3.083 10.269 5.45 14.607 11.564 22.198-2.527 14.222-26.399 34.557-46.727 60.671-61.294 97.46-54.366 228.37 7.568 230.24 132.697.122 8.15 2.412 12.428 9.848 15.894 57.56 26.829 74.456 96.122 35.142 144.497zm-87.789-80.499c-5.848 31.157-34.622 55.096-66.666 55.095-16.953-.001-32.058-6.545-44.079-17.705-27.697-25.713-71.141-74.98-95.937-93.387-20.056-14.888-41.99-12.333-60.272 3.782-49.996 44.071 15.859 121.775 67.063 77.188 4.548-3.96 7.84-9.543 12.744-12.844 8.184-5.509 20.766-.884 13.168 10.622-17.358 26.284-49.33 38.197-78.863 29.301-28.897-8.704-48.84-35.968-48.626-70.179 1.225-22.485 12.364-43.06 35.414-55.965 22.575-12.638 46.369-13.146 66.991 2.474C295.68 280.7 320.467 323.97 352.185 343.47c24.558 15.099 54.254 7.363 68.823-17.506 28.83-49.209-34.592-105.016-78.868-63.46-3.989 3.744-6.917 8.932-11.41 11.72-10.975 6.811-17.333-4.113-12.809-10.353 20.703-28.554 50.464-40.44 83.271-28.214 31.429 11.714 49.108 44.366 42.76 78.186z\"],\n    \"kaggle\": [320, 512, [], \"f5fa\", \"M304.2 501.5L158.4 320.3 298.2 185c2.6-2.7 1.7-10.5-5.3-10.5h-69.2c-3.5 0-7 1.8-10.5 5.3L80.9 313.5V7.5q0-7.5-7.5-7.5H21.5Q14 0 14 7.5v497q0 7.5 7.5 7.5h51.9q7.5 0 7.5-7.5v-109l30.8-29.3 110.5 140.6c3 3.5 6.5 5.3 10.5 5.3h66.9q5.25 0 6-3z\"],\n    \"keybase\": [448, 512, [], \"f4f5\", \"M286.17,419a18,18,0,1,0,18,18A18,18,0,0,0,286.17,419ZM398.09,271.4c-9.5-14.62-39.37-52.45-87.26-73.71q-9.1-4.06-18.38-7.27A78.43,78.43,0,0,0,244.57,86.29c-12.41-4.1-23.33-6-32.41-5.77-.6-2-1.89-11,9.4-35L198.66,32l-5.48,7.56c-8.69,12.06-16.92,23.55-24.34,34.89a51,51,0,0,0-8.29-1.25c-41.53-2.45-39-2.33-41.06-2.33-50.61,0-50.75,52.12-50.75,45.88l-2.36,36.68c-1.61,27,19.75,50.21,47.63,51.85l8.93.54a214,214,0,0,0-46.29,35.54C14,304.66,14,374,14,429.77v33.64l23.32-29.8a148.6,148.6,0,0,0,14.56,37.56c5.78,10.13,14.87,9.45,19.64,7.33,4.21-1.87,10-6.92,3.75-20.11a178.29,178.29,0,0,1-15.76-53.13l46.82-59.83L81.67,419.54c58.23-42.4,157.38-61.76,236.25-38.59,34.2,10.05,67.45.69,84.74-23.84.72-1,1.2-2.16,1.85-3.22a156.09,156.09,0,0,1,2.8,28.43c0,23.3-3.69,52.93-14.88,81.64-2.52,6.46,1.76,14.5,8.6,15.74,7.42,1.57,15.33-3.1,18.37-11.15C429,443,434,414,434,382.32,434,343.74,421,304.86,398.09,271.4ZM142.37,128.58l-15.7-.93-1.39,21.79,13.13.78a93,93,0,0,0,.32,19.57l-22.38-1.34a12.28,12.28,0,0,1-11.76-12.79L107,119c1-12.17,13.87-11.27,13.26-11.32l29.11,1.73A144.35,144.35,0,0,0,142.37,128.58ZM290.79,300.76a10.51,10.51,0,0,1-14.35-1.39l-9.68-11.49-34.42,27a8.09,8.09,0,0,1-11.13-1.08l-15.78-18.64a7.38,7.38,0,0,1,1.34-10.34l34.57-27.18L227.2,240.9l-17.09,13.45a7.75,7.75,0,0,1-10.59-1s-3.72-4.42-3.8-4.53a7.38,7.38,0,0,1,1.37-10.34L214,225.19s-18.51-22-18.6-22.14a9.56,9.56,0,0,1,1.74-13.42A10.38,10.38,0,0,1,211.44,191l81.09,96.32A9.58,9.58,0,0,1,290.79,300.76ZM187.44,419a18,18,0,1,0,18,18A18,18,0,0,0,187.44,419Z\"],\n    \"keycdn\": [512, 512, [], \"f3ba\", \"M63.8 409.3l60.5-59c32.1 42.8 71.1 66 126.6 67.4 30.5.7 60.3-7 86.4-22.4 5.1 5.3 18.5 19.5 20.9 22-32.2 20.7-69.6 31.1-108.1 30.2-43.3-1.1-84.6-16.7-117.7-44.4.3-.6-38.2 37.5-38.6 37.9 9.5 29.8-13.1 62.4-46.3 62.4C20.7 503.3 0 481.7 0 454.9c0-34.3 33.1-56.6 63.8-45.6zm354.9-252.4c19.1 31.3 29.6 67.4 28.7 104-1.1 44.8-19 87.5-48.6 121 .3.3 23.8 25.2 24.1 25.5 9.6-1.3 19.2 2 25.9 9.1 11.3 12 10.9 30.9-1.1 42.4-12 11.3-30.9 10.9-42.4-1.1-6.7-7-9.4-16.8-7.6-26.3-24.9-26.6-44.4-47.2-44.4-47.2 42.7-34.1 63.3-79.6 64.4-124.2.7-28.9-7.2-57.2-21.1-82.2l22.1-21zM104 53.1c6.7 7 9.4 16.8 7.6 26.3l45.9 48.1c-4.7 3.8-13.3 10.4-22.8 21.3-25.4 28.5-39.6 64.8-40.7 102.9-.7 28.9 6.1 57.2 20 82.4l-22 21.5C72.7 324 63.1 287.9 64.2 250.9c1-44.6 18.3-87.6 47.5-121.1l-25.3-26.4c-9.6 1.3-19.2-2-25.9-9.1-11.3-12-10.9-30.9 1.1-42.4C73.5 40.7 92.2 41 104 53.1zM464.9 8c26 0 47.1 22.4 47.1 48.3S490.9 104 464.9 104c-6.3.1-14-1.1-15.9-1.8l-62.9 59.7c-32.7-43.6-76.7-65.9-126.9-67.2-30.5-.7-60.3 6.8-86.2 22.4l-21.1-22C184.1 74.3 221.5 64 260 64.9c43.3 1.1 84.6 16.7 117.7 44.6l41.1-38.6c-1.5-4.7-2.2-9.6-2.2-14.5C416.5 29.7 438.9 8 464.9 8zM256.7 113.4c5.5 0 10.9.4 16.4 1.1 78.1 9.8 133.4 81.1 123.8 159.1-9.8 78.1-81.1 133.4-159.1 123.8-78.1-9.8-133.4-81.1-123.8-159.2 9.3-72.4 70.1-124.6 142.7-124.8zm-59 119.4c.6 22.7 12.2 41.8 32.4 52.2l-11 51.7h73.7l-11-51.7c20.1-10.9 32.1-29 32.4-52.2-.4-32.8-25.8-57.5-58.3-58.3-32.1.8-57.3 24.8-58.2 58.3zM256 160\"],\n    \"kickstarter\": [448, 512, [], \"f3bb\", \"M400 480H48c-26.4 0-48-21.6-48-48V80c0-26.4 21.6-48 48-48h352c26.4 0 48 21.6 48 48v352c0 26.4-21.6 48-48 48zM199.6 178.5c0-30.7-17.6-45.1-39.7-45.1-25.8 0-40 19.8-40 44.5v154.8c0 25.8 13.7 45.6 40.5 45.6 21.5 0 39.2-14 39.2-45.6v-41.8l60.6 75.7c12.3 14.9 39 16.8 55.8 0 14.6-15.1 14.8-36.8 4-50.4l-49.1-62.8 40.5-58.7c9.4-13.5 9.5-34.5-5.6-49.1-16.4-15.9-44.6-17.3-61.4 7l-44.8 64.7v-38.8z\"],\n    \"kickstarter-k\": [384, 512, [], \"f3bc\", \"M147.3 114.4c0-56.2-32.5-82.4-73.4-82.4C26.2 32 0 68.2 0 113.4v283c0 47.3 25.3 83.4 74.9 83.4 39.8 0 72.4-25.6 72.4-83.4v-76.5l112.1 138.3c22.7 27.2 72.1 30.7 103.2 0 27-27.6 27.3-67.4 7.4-92.2l-90.8-114.8 74.9-107.4c17.4-24.7 17.5-63.1-10.4-89.8-30.3-29-82.4-31.6-113.6 12.8L147.3 185v-70.6z\"],\n    \"korvue\": [446, 512, [], \"f42f\", \"M386.5 34h-327C26.8 34 0 60.8 0 93.5v327.1C0 453.2 26.8 480 59.5 480h327.1c33 0 59.5-26.8 59.5-59.5v-327C446 60.8 419.2 34 386.5 34zM87.1 120.8h96v116l61.8-116h110.9l-81.2 132H87.1v-132zm161.8 272.1l-65.7-113.6v113.6h-96V262.1h191.5l88.6 130.8H248.9z\"],\n    \"laravel\": [640, 512, [], \"f3bd\", \"M637.5 241.6c-4.2-4.8-62.8-78.1-73.1-90.5-10.3-12.4-15.4-10.2-21.7-9.3-6.4.9-80.5 13.4-89.1 14.8-8.6 1.5-14 4.9-8.7 12.3 4.7 6.6 53.4 75.7 64.2 90.9l-193.7 46.4L161.2 48.7c-6.1-9.1-7.4-12.3-21.4-11.6-14 .6-120.9 9.5-128.5 10.2-7.6.6-16 4-8.4 22s129 279.6 132.4 287.2c3.4 7.6 12.2 20 32.8 15 21.1-5.1 94.3-24.2 134.3-34.7 21.1 38.3 64.2 115.9 72.2 127 10.6 14.9 18 12.4 34.3 7.4 12.8-3.9 199.6-71.1 208-74.5 8.4-3.5 13.6-5.9 7.9-14.4-4.2-6.2-53.5-72.2-79.3-106.8 17.7-4.7 80.6-21.4 87.3-23.3 7.9-2 9-5.8 4.7-10.6zm-352.2 72c-2.3.5-110.8 26.5-116.6 27.8-5.8 1.3-5.8.7-6.5-1.3-.7-2-129-266.7-130.8-270-1.8-3.3-1.7-5.9 0-5.9s102.5-9 106-9.2c3.6-.2 3.2.6 4.5 2.8 0 0 142.2 245.4 144.6 249.7 2.6 4.3 1.1 5.6-1.2 6.1zm306 57.4c1.7 2.7 3.5 4.5-2 6.4-5.4 2-183.7 62.1-187.1 63.6-3.5 1.5-6.2 2-10.6-4.5s-62.4-106.8-62.4-106.8L518 280.6c4.7-1.5 6.2-2.5 9.2 2.2 2.9 4.8 62.4 85.5 64.1 88.2zm12.1-134.1c-4.2.9-73.6 18.1-73.6 18.1l-56.7-77.8c-1.6-2.3-2.9-4.5 1.1-5s68.4-12.2 71.3-12.8c2.9-.7 5.4-1.5 9 3.4 3.6 4.9 52.6 67 54.5 69.4 1.8 2.3-1.4 3.7-5.6 4.7z\"],\n    \"lastfm\": [512, 512, [], \"f202\", \"M225.8 367.1l-18.8-51s-30.5 34-76.2 34c-40.5 0-69.2-35.2-69.2-91.5 0-72.1 36.4-97.9 72.1-97.9 66.5 0 74.8 53.3 100.9 134.9 18.8 56.9 54 102.6 155.4 102.6 72.7 0 122-22.3 122-80.9 0-72.9-62.7-80.6-115-92.1-25.8-5.9-33.4-16.4-33.4-34 0-19.9 15.8-31.7 41.6-31.7 28.2 0 43.4 10.6 45.7 35.8l58.6-7c-4.7-52.8-41.1-74.5-100.9-74.5-52.8 0-104.4 19.9-104.4 83.9 0 39.9 19.4 65.1 68 76.8 44.9 10.6 79.8 13.8 79.8 45.7 0 21.7-21.1 30.5-61 30.5-59.2 0-83.9-31.1-97.9-73.9-32-96.8-43.6-163-161.3-163C45.7 113.8 0 168.3 0 261c0 89.1 45.7 137.2 127.9 137.2 66.2 0 97.9-31.1 97.9-31.1z\"],\n    \"lastfm-square\": [448, 512, [], \"f203\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-92.2 312.9c-63.4 0-85.4-28.6-97.1-64.1-16.3-51-21.5-84.3-63-84.3-22.4 0-45.1 16.1-45.1 61.2 0 35.2 18 57.2 43.3 57.2 28.6 0 47.6-21.3 47.6-21.3l11.7 31.9s-19.8 19.4-61.2 19.4c-51.3 0-79.9-30.1-79.9-85.8 0-57.9 28.6-92 82.5-92 73.5 0 80.8 41.4 100.8 101.9 8.8 26.8 24.2 46.2 61.2 46.2 24.9 0 38.1-5.5 38.1-19.1 0-19.9-21.8-22-49.9-28.6-30.4-7.3-42.5-23.1-42.5-48 0-40 32.3-52.4 65.2-52.4 37.4 0 60.1 13.6 63 46.6l-36.7 4.4c-1.5-15.8-11-22.4-28.6-22.4-16.1 0-26 7.3-26 19.8 0 11 4.8 17.6 20.9 21.3 32.7 7.1 71.8 12 71.8 57.5.1 36.7-30.7 50.6-76.1 50.6z\"],\n    \"leanpub\": [576, 512, [], \"f212\", \"M386.539 111.485l15.096 248.955-10.979-.275c-36.232-.824-71.64 8.783-102.657 27.997-31.016-19.214-66.424-27.997-102.657-27.997-45.564 0-82.07 10.705-123.516 27.723L93.117 129.6c28.546-11.803 61.484-18.115 92.226-18.115 41.173 0 73.836 13.175 102.657 42.544 27.723-28.271 59.013-41.721 98.539-42.544zM569.07 448c-25.526 0-47.485-5.215-70.542-15.645-34.31-15.645-69.993-24.978-107.871-24.978-38.977 0-74.934 12.901-102.657 40.623-27.723-27.723-63.68-40.623-102.657-40.623-37.878 0-73.561 9.333-107.871 24.978C55.239 442.236 32.731 448 8.303 448H6.93L49.475 98.859C88.726 76.626 136.486 64 181.775 64 218.83 64 256.984 71.685 288 93.095 319.016 71.685 357.17 64 394.225 64c45.289 0 93.049 12.626 132.3 34.859L569.07 448zm-43.368-44.741l-34.036-280.246c-30.742-13.999-67.248-21.41-101.009-21.41-38.428 0-74.385 12.077-102.657 38.702-28.272-26.625-64.228-38.702-102.657-38.702-33.761 0-70.267 7.411-101.009 21.41L50.298 403.259c47.211-19.487 82.894-33.486 135.045-33.486 37.604 0 70.817 9.606 102.657 29.644 31.84-20.038 65.052-29.644 102.657-29.644 52.151 0 87.834 13.999 135.045 33.486z\"],\n    \"less\": [640, 512, [], \"f41d\", \"M612.7 219c0-20.5 3.2-32.6 3.2-54.6 0-34.2-12.6-45.2-40.5-45.2h-20.5v24.2h6.3c14.2 0 17.3 4.7 17.3 22.1 0 16.3-1.6 32.6-1.6 51.5 0 24.2 7.9 33.6 23.6 37.3v1.6c-15.8 3.7-23.6 13.1-23.6 37.3 0 18.9 1.6 34.2 1.6 51.5 0 17.9-3.7 22.6-17.3 22.6v.5h-6.3V393h20.5c27.8 0 40.5-11 40.5-45.2 0-22.6-3.2-34.2-3.2-54.6 0-11 6.8-22.6 27.3-23.6v-27.3c-20.5-.7-27.3-12.3-27.3-23.3zm-105.6 32c-15.8-6.3-30.5-10-30.5-20.5 0-7.9 6.3-12.6 17.9-12.6s22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-21 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51s-22.5-41-43-47.8zm-358.9 59.4c-3.7 0-8.4-3.2-8.4-13.1V119.1H65.2c-28.4 0-41 11-41 45.2 0 22.6 3.2 35.2 3.2 54.6 0 11-6.8 22.6-27.3 23.6v27.3c20.5.5 27.3 12.1 27.3 23.1 0 19.4-3.2 31-3.2 53.6 0 34.2 12.6 45.2 40.5 45.2h20.5v-24.2h-6.3c-13.1 0-17.3-5.3-17.3-22.6s1.6-32.1 1.6-51.5c0-24.2-7.9-33.6-23.6-37.3v-1.6c15.8-3.7 23.6-13.1 23.6-37.3 0-18.9-1.6-34.2-1.6-51.5s3.7-22.1 17.3-22.1H93v150.8c0 32.1 11 53.1 43.1 53.1 10 0 17.9-1.6 23.6-3.7l-5.3-34.2c-3.1.8-4.6.8-6.2.8zM379.9 251c-16.3-6.3-31-10-31-20.5 0-7.9 6.3-12.6 17.9-12.6 11.6 0 22.1 4.7 33.6 13.1l21-27.8c-13.1-10-31-20.5-55.2-20.5-35.7 0-59.9 20.5-59.9 49.4 0 25.7 22.6 38.9 41.5 46.2 16.3 6.3 32.1 11.6 32.1 22.1 0 7.9-6.3 13.1-20.5 13.1-13.1 0-26.3-5.3-40.5-16.3l-20.5 30.5c15.8 13.1 39.9 22.1 59.9 22.1 42 0 64.6-22.1 64.6-51 .1-28.9-22.5-41-43-47.8zm-155-68.8c-38.4 0-75.1 32.1-74.1 82.5 0 52 34.2 82.5 79.3 82.5 18.9 0 39.9-6.8 56.2-17.9l-15.8-27.8c-11.6 6.8-22.6 10-34.2 10-21 0-37.3-10-41.5-34.2H290c.5-3.7 1.6-11 1.6-19.4.6-42.6-22.6-75.7-66.7-75.7zm-30 66.2c3.2-21 15.8-31 30.5-31 18.9 0 26.3 13.1 26.3 31h-56.8z\"],\n    \"line\": [448, 512, [], \"f3c0\", \"M272.1 204.2v71.1c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.1 0-2.1-.6-2.6-1.3l-32.6-44v42.2c0 1.8-1.4 3.2-3.2 3.2h-11.4c-1.8 0-3.2-1.4-3.2-3.2v-71.1c0-1.8 1.4-3.2 3.2-3.2H219c1 0 2.1.5 2.6 1.4l32.6 44v-42.2c0-1.8 1.4-3.2 3.2-3.2h11.4c1.8-.1 3.3 1.4 3.3 3.1zm-82-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 1.8 1.4 3.2 3.2 3.2h11.4c1.8 0 3.2-1.4 3.2-3.2v-71.1c0-1.7-1.4-3.2-3.2-3.2zm-27.5 59.6h-31.1v-56.4c0-1.8-1.4-3.2-3.2-3.2h-11.4c-1.8 0-3.2 1.4-3.2 3.2v71.1c0 .9.3 1.6.9 2.2.6.5 1.3.9 2.2.9h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.7-1.4-3.2-3.1-3.2zM332.1 201h-45.7c-1.7 0-3.2 1.4-3.2 3.2v71.1c0 1.7 1.4 3.2 3.2 3.2h45.7c1.8 0 3.2-1.4 3.2-3.2v-11.4c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2V234c0-1.8-1.4-3.2-3.2-3.2H301v-12h31.1c1.8 0 3.2-1.4 3.2-3.2v-11.4c-.1-1.7-1.5-3.2-3.2-3.2zM448 113.7V399c-.1 44.8-36.8 81.1-81.7 81H81c-44.8-.1-81.1-36.9-81-81.7V113c.1-44.8 36.9-81.1 81.7-81H367c44.8.1 81.1 36.8 81 81.7zm-61.6 122.6c0-73-73.2-132.4-163.1-132.4-89.9 0-163.1 59.4-163.1 132.4 0 65.4 58 120.2 136.4 130.6 19.1 4.1 16.9 11.1 12.6 36.8-.7 4.1-3.3 16.1 14.1 8.8 17.4-7.3 93.9-55.3 128.2-94.7 23.6-26 34.9-52.3 34.9-81.5z\"],\n    \"linkedin\": [448, 512, [], \"f08c\", \"M416 32H31.9C14.3 32 0 46.5 0 64.3v383.4C0 465.5 14.3 480 31.9 480H416c17.6 0 32-14.5 32-32.3V64.3c0-17.8-14.4-32.3-32-32.3zM135.4 416H69V202.2h66.5V416zm-33.2-243c-21.3 0-38.5-17.3-38.5-38.5S80.9 96 102.2 96c21.2 0 38.5 17.3 38.5 38.5 0 21.3-17.2 38.5-38.5 38.5zm282.1 243h-66.4V312c0-24.8-.5-56.7-34.5-56.7-34.6 0-39.9 27-39.9 54.9V416h-66.4V202.2h63.7v29.2h.9c8.9-16.8 30.6-34.5 62.9-34.5 67.2 0 79.7 44.3 79.7 101.9V416z\"],\n    \"linkedin-in\": [448, 512, [], \"f0e1\", \"M100.28 448H7.4V148.9h92.88zM53.79 108.1C24.09 108.1 0 83.5 0 53.8a53.79 53.79 0 0 1 107.58 0c0 29.7-24.1 54.3-53.79 54.3zM447.9 448h-92.68V302.4c0-34.7-.7-79.2-48.29-79.2-48.29 0-55.69 37.7-55.69 76.7V448h-92.78V148.9h89.08v40.8h1.3c12.4-23.5 42.69-48.3 87.88-48.3 94 0 111.28 61.9 111.28 142.3V448z\"],\n    \"linode\": [448, 512, [], \"f2b8\", \"M437.4 226.3c-.3-.9-.9-1.4-1.4-2l-70-38.6c-.9-.6-2-.6-3.1 0l-58.9 36c-.9.6-1.4 1.7-1.4 2.6l-.9 31.4-24-16c-.9-.6-2.3-.6-3.1 0L240 260.9l-1.4-35.1c0-.9-.6-2-1.4-2.3l-36-24.3 33.7-17.4c1.1-.6 1.7-1.7 1.7-2.9l-5.7-132.3c0-.9-.9-2-1.7-2.6L138.6.3c-.9-.3-1.7-.3-2.3-.3L12.6 38.6c-1.4.6-2.3 2-2 3.7L38 175.4c.9 3.4 34 27.4 38.6 30.9l-26.9 12.9c-1.4.9-2 2.3-1.7 3.4l20.6 100.3c.6 2.9 23.7 23.1 27.1 26.3l-17.4 10.6c-.9.6-1.7 2-1.4 3.1 1.4 7.1 15.4 77.7 16.9 79.1l65.1 69.1c.6.6 1.4.6 2.3.9.6 0 1.1-.3 1.7-.6l83.7-66.9c.9-.6 1.1-1.4 1.1-2.3l-2-46 28 23.7c1.1.9 2.9.9 4 0l66.9-53.4c.9-.6 1.1-1.4 1.1-2.3l2.3-33.4 20.3 14c1.1.9 2.6.9 3.7 0l54.6-43.7c.6-.3 1.1-1.1 1.1-2 .9-6.5 10.3-70.8 9.7-72.8zm-204.8 4.8l4 92.6-90.6 61.2-14-96.6 100.6-57.2zm-7.7-180l5.4 126-106.6 55.4L104 97.7l120.9-46.6zM44 173.1L18 48l79.7 49.4 19.4 132.9L44 173.1zm30.6 147.8L55.7 230l70 58.3 13.7 93.4-64.8-60.8zm24.3 117.7l-13.7-67.1 61.7 60.9 9.7 67.4-57.7-61.2zm64.5 64.5l-10.6-70.9 85.7-61.4 3.1 70-78.2 62.3zm82-115.1c0-3.4.9-22.9-2-25.1l-24.3-20 22.3-14.9c2.3-1.7 1.1-5.7 1.1-8l29.4 22.6.6 68.3-27.1-22.9zm94.3-25.4l-60.9 48.6-.6-68.6 65.7-46.9-4.2 66.9zm27.7-25.7l-19.1-13.4 2-34c.3-.9-.3-2-1.1-2.6L308 259.7l.6-30 64.6 40.6-5.8 66.6zm54.6-39.8l-48.3 38.3 5.7-65.1 51.1-36.6-8.5 63.4z\"],\n    \"linux\": [448, 512, [], \"f17c\", \"M220.8 123.3c1 .5 1.8 1.7 3 1.7 1.1 0 2.8-.4 2.9-1.5.2-1.4-1.9-2.3-3.2-2.9-1.7-.7-3.9-1-5.5-.1-.4.2-.8.7-.6 1.1.3 1.3 2.3 1.1 3.4 1.7zm-21.9 1.7c1.2 0 2-1.2 3-1.7 1.1-.6 3.1-.4 3.5-1.6.2-.4-.2-.9-.6-1.1-1.6-.9-3.8-.6-5.5.1-1.3.6-3.4 1.5-3.2 2.9.1 1 1.8 1.5 2.8 1.4zM420 403.8c-3.6-4-5.3-11.6-7.2-19.7-1.8-8.1-3.9-16.8-10.5-22.4-1.3-1.1-2.6-2.1-4-2.9-1.3-.8-2.7-1.5-4.1-2 9.2-27.3 5.6-54.5-3.7-79.1-11.4-30.1-31.3-56.4-46.5-74.4-17.1-21.5-33.7-41.9-33.4-72C311.1 85.4 315.7.1 234.8 0 132.4-.2 158 103.4 156.9 135.2c-1.7 23.4-6.4 41.8-22.5 64.7-18.9 22.5-45.5 58.8-58.1 96.7-6 17.9-8.8 36.1-6.2 53.3-6.5 5.8-11.4 14.7-16.6 20.2-4.2 4.3-10.3 5.9-17 8.3s-14 6-18.5 14.5c-2.1 3.9-2.8 8.1-2.8 12.4 0 3.9.6 7.9 1.2 11.8 1.2 8.1 2.5 15.7.8 20.8-5.2 14.4-5.9 24.4-2.2 31.7 3.8 7.3 11.4 10.5 20.1 12.3 17.3 3.6 40.8 2.7 59.3 12.5 19.8 10.4 39.9 14.1 55.9 10.4 11.6-2.6 21.1-9.6 25.9-20.2 12.5-.1 26.3-5.4 48.3-6.6 14.9-1.2 33.6 5.3 55.1 4.1.6 2.3 1.4 4.6 2.5 6.7v.1c8.3 16.7 23.8 24.3 40.3 23 16.6-1.3 34.1-11 48.3-27.9 13.6-16.4 36-23.2 50.9-32.2 7.4-4.5 13.4-10.1 13.9-18.3.4-8.2-4.4-17.3-15.5-29.7zM223.7 87.3c9.8-22.2 34.2-21.8 44-.4 6.5 14.2 3.6 30.9-4.3 40.4-1.6-.8-5.9-2.6-12.6-4.9 1.1-1.2 3.1-2.7 3.9-4.6 4.8-11.8-.2-27-9.1-27.3-7.3-.5-13.9 10.8-11.8 23-4.1-2-9.4-3.5-13-4.4-1-6.9-.3-14.6 2.9-21.8zM183 75.8c10.1 0 20.8 14.2 19.1 33.5-3.5 1-7.1 2.5-10.2 4.6 1.2-8.9-3.3-20.1-9.6-19.6-8.4.7-9.8 21.2-1.8 28.1 1 .8 1.9-.2-5.9 5.5-15.6-14.6-10.5-52.1 8.4-52.1zm-13.6 60.7c6.2-4.6 13.6-10 14.1-10.5 4.7-4.4 13.5-14.2 27.9-14.2 7.1 0 15.6 2.3 25.9 8.9 6.3 4.1 11.3 4.4 22.6 9.3 8.4 3.5 13.7 9.7 10.5 18.2-2.6 7.1-11 14.4-22.7 18.1-11.1 3.6-19.8 16-38.2 14.9-3.9-.2-7-1-9.6-2.1-8-3.5-12.2-10.4-20-15-8.6-4.8-13.2-10.4-14.7-15.3-1.4-4.9 0-9 4.2-12.3zm3.3 334c-2.7 35.1-43.9 34.4-75.3 18-29.9-15.8-68.6-6.5-76.5-21.9-2.4-4.7-2.4-12.7 2.6-26.4v-.2c2.4-7.6.6-16-.6-23.9-1.2-7.8-1.8-15 .9-20 3.5-6.7 8.5-9.1 14.8-11.3 10.3-3.7 11.8-3.4 19.6-9.9 5.5-5.7 9.5-12.9 14.3-18 5.1-5.5 10-8.1 17.7-6.9 8.1 1.2 15.1 6.8 21.9 16l19.6 35.6c9.5 19.9 43.1 48.4 41 68.9zm-1.4-25.9c-4.1-6.6-9.6-13.6-14.4-19.6 7.1 0 14.2-2.2 16.7-8.9 2.3-6.2 0-14.9-7.4-24.9-13.5-18.2-38.3-32.5-38.3-32.5-13.5-8.4-21.1-18.7-24.6-29.9s-3-23.3-.3-35.2c5.2-22.9 18.6-45.2 27.2-59.2 2.3-1.7.8 3.2-8.7 20.8-8.5 16.1-24.4 53.3-2.6 82.4.6-20.7 5.5-41.8 13.8-61.5 12-27.4 37.3-74.9 39.3-112.7 1.1.8 4.6 3.2 6.2 4.1 4.6 2.7 8.1 6.7 12.6 10.3 12.4 10 28.5 9.2 42.4 1.2 6.2-3.5 11.2-7.5 15.9-9 9.9-3.1 17.8-8.6 22.3-15 7.7 30.4 25.7 74.3 37.2 95.7 6.1 11.4 18.3 35.5 23.6 64.6 3.3-.1 7 .4 10.9 1.4 13.8-35.7-11.7-74.2-23.3-84.9-4.7-4.6-4.9-6.6-2.6-6.5 12.6 11.2 29.2 33.7 35.2 59 2.8 11.6 3.3 23.7.4 35.7 16.4 6.8 35.9 17.9 30.7 34.8-2.2-.1-3.2 0-4.2 0 3.2-10.1-3.9-17.6-22.8-26.1-19.6-8.6-36-8.6-38.3 12.5-12.1 4.2-18.3 14.7-21.4 27.3-2.8 11.2-3.6 24.7-4.4 39.9-.5 7.7-3.6 18-6.8 29-32.1 22.9-76.7 32.9-114.3 7.2zm257.4-11.5c-.9 16.8-41.2 19.9-63.2 46.5-13.2 15.7-29.4 24.4-43.6 25.5s-26.5-4.8-33.7-19.3c-4.7-11.1-2.4-23.1 1.1-36.3 3.7-14.2 9.2-28.8 9.9-40.6.8-15.2 1.7-28.5 4.2-38.7 2.6-10.3 6.6-17.2 13.7-21.1.3-.2.7-.3 1-.5.8 13.2 7.3 26.6 18.8 29.5 12.6 3.3 30.7-7.5 38.4-16.3 9-.3 15.7-.9 22.6 5.1 9.9 8.5 7.1 30.3 17.1 41.6 10.6 11.6 14 19.5 13.7 24.6zM173.3 148.7c2 1.9 4.7 4.5 8 7.1 6.6 5.2 15.8 10.6 27.3 10.6 11.6 0 22.5-5.9 31.8-10.8 4.9-2.6 10.9-7 14.8-10.4s5.9-6.3 3.1-6.6-2.6 2.6-6 5.1c-4.4 3.2-9.7 7.4-13.9 9.8-7.4 4.2-19.5 10.2-29.9 10.2s-18.7-4.8-24.9-9.7c-3.1-2.5-5.7-5-7.7-6.9-1.5-1.4-1.9-4.6-4.3-4.9-1.4-.1-1.8 3.7 1.7 6.5z\"],\n    \"lyft\": [512, 512, [], \"f3c3\", \"M0 81.1h77.8v208.7c0 33.1 15 52.8 27.2 61-12.7 11.1-51.2 20.9-80.2-2.8C7.8 334 0 310.7 0 289V81.1zm485.9 173.5v-22h23.8v-76.8h-26.1c-10.1-46.3-51.2-80.7-100.3-80.7-56.6 0-102.7 46-102.7 102.7V357c16 2.3 35.4-.3 51.7-14 17.1-14 24.8-37.2 24.8-59v-6.7h38.8v-76.8h-38.8v-23.3c0-34.6 52.2-34.6 52.2 0v77.1c0 56.6 46 102.7 102.7 102.7v-76.5c-14.5 0-26.1-11.7-26.1-25.9zm-294.3-99v113c0 15.4-23.8 15.4-23.8 0v-113H91v132.7c0 23.8 8 54 45 63.9 37 9.8 58.2-10.6 58.2-10.6-2.1 13.4-14.5 23.3-34.9 25.3-15.5 1.6-35.2-3.6-45-7.8v70.3c25.1 7.5 51.5 9.8 77.6 4.7 47.1-9.1 76.8-48.4 76.8-100.8V155.1h-77.1v.5z\"],\n    \"magento\": [448, 512, [], \"f3c4\", \"M445.7 127.9V384l-63.4 36.5V164.7L223.8 73.1 65.2 164.7l.4 255.9L2.3 384V128.1L224.2 0l221.5 127.9zM255.6 420.5L224 438.9l-31.8-18.2v-256l-63.3 36.6.1 255.9 94.9 54.9 95.1-54.9v-256l-63.4-36.6v255.9z\"],\n    \"mailchimp\": [448, 512, [], \"f59e\", \"M330.61 243.52a36.15 36.15 0 0 1 9.3 0c1.66-3.83 1.95-10.43.45-17.61-2.23-10.67-5.25-17.14-11.48-16.13s-6.47 8.74-4.24 19.42c1.26 6 3.49 11.14 6 14.32zM277.05 252c4.47 2 7.2 3.26 8.28 2.13 1.89-1.94-3.48-9.39-12.12-13.09a31.44 31.44 0 0 0-30.61 3.68c-3 2.18-5.81 5.22-5.41 7.06.85 3.74 10-2.71 22.6-3.48 7-.44 12.8 1.75 17.26 3.71zm-9 5.13c-9.07 1.42-15 6.53-13.47 10.1.9.34 1.17.81 5.21-.81a37 37 0 0 1 18.72-1.95c2.92.34 4.31.52 4.94-.49 1.46-2.22-5.71-8-15.39-6.85zm54.17 17.1c3.38-6.87-10.9-13.93-14.3-7s10.92 13.88 14.32 6.97zm15.66-20.47c-7.66-.13-7.95 15.8-.26 15.93s7.98-15.81.28-15.96zm-218.79 78.9c-1.32.31-6 1.45-8.47-2.35-5.2-8 11.11-20.38 3-35.77-9.1-17.47-27.82-13.54-35.05-5.54-8.71 9.6-8.72 23.54-5 24.08 4.27.57 4.08-6.47 7.38-11.63a12.83 12.83 0 0 1 17.85-3.72c11.59 7.59 1.37 17.76 2.28 28.62 1.39 16.68 18.42 16.37 21.58 9a2.08 2.08 0 0 0-.2-2.33c.03.89.68-1.3-3.35-.39zm299.72-17.07c-3.35-11.73-2.57-9.22-6.78-20.52 2.45-3.67 15.29-24-3.07-43.25-10.4-10.92-33.9-16.54-41.1-18.54-1.5-11.39 4.65-58.7-21.52-83 20.79-21.55 33.76-45.29 33.73-65.65-.06-39.16-48.15-51-107.42-26.47l-12.55 5.33c-.06-.05-22.71-22.27-23.05-22.57C169.5-18-41.77 216.81 25.78 273.85l14.76 12.51a72.49 72.49 0 0 0-4.1 33.5c3.36 33.4 36 60.42 67.53 60.38 57.73 133.06 267.9 133.28 322.29 3 1.74-4.47 9.11-24.61 9.11-42.38s-10.09-25.27-16.53-25.27zm-316 48.16c-22.82-.61-47.46-21.15-49.91-45.51-6.17-61.31 74.26-75.27 84-12.33 4.54 29.64-4.67 58.49-34.12 57.81zM84.3 249.55C69.14 252.5 55.78 261.09 47.6 273c-4.88-4.07-14-12-15.59-15-13.01-24.85 14.24-73 33.3-100.21C112.42 90.56 186.19 39.68 220.36 48.91c5.55 1.57 23.94 22.89 23.94 22.89s-34.15 18.94-65.8 45.35c-42.66 32.85-74.89 80.59-94.2 132.4zM323.18 350.7s-35.74 5.3-69.51-7.07c6.21-20.16 27 6.1 96.4-13.81 15.29-4.38 35.37-13 51-25.35a102.85 102.85 0 0 1 7.12 24.28c3.66-.66 14.25-.52 11.44 18.1-3.29 19.87-11.73 36-25.93 50.84A106.86 106.86 0 0 1 362.55 421a132.45 132.45 0 0 1-20.34 8.58c-53.51 17.48-108.3-1.74-126-43a66.33 66.33 0 0 1-3.55-9.74c-7.53-27.2-1.14-59.83 18.84-80.37 1.23-1.31 2.48-2.85 2.48-4.79a8.45 8.45 0 0 0-1.92-4.54c-7-10.13-31.19-27.4-26.33-60.83 3.5-24 24.49-40.91 44.07-39.91l5 .29c8.48.5 15.89 1.59 22.88 1.88 11.69.5 22.2-1.19 34.64-11.56 4.2-3.5 7.57-6.54 13.26-7.51a17.45 17.45 0 0 1 13.6 2.24c10 6.64 11.4 22.73 11.92 34.49.29 6.72 1.1 23 1.38 27.63.63 10.67 3.43 12.17 9.11 14 3.19 1.05 6.15 1.83 10.51 3.06 13.21 3.71 21 7.48 26 12.31a16.38 16.38 0 0 1 4.74 9.29c1.56 11.37-8.82 25.4-36.31 38.16-46.71 21.68-93.68 14.45-100.48 13.68-20.15-2.71-31.63 23.32-19.55 41.15 22.64 33.41 122.4 20 151.37-21.35.69-1 .12-1.59-.73-1-41.77 28.58-97.06 38.21-128.46 26-4.77-1.85-14.73-6.44-15.94-16.67 43.6 13.49 71 .74 71 .74s2.03-2.79-.56-2.53zm-68.47-5.7zm-83.4-187.5c16.74-19.35 37.36-36.18 55.83-45.63a.73.73 0 0 1 1 1c-1.46 2.66-4.29 8.34-5.19 12.65a.75.75 0 0 0 1.16.79c11.49-7.83 31.48-16.22 49-17.3a.77.77 0 0 1 .52 1.38 41.86 41.86 0 0 0-7.71 7.74.75.75 0 0 0 .59 1.19c12.31.09 29.66 4.4 41 10.74.76.43.22 1.91-.64 1.72-69.55-15.94-123.08 18.53-134.5 26.83a.76.76 0 0 1-1-1.12z\"],\n    \"mandalorian\": [448, 512, [], \"f50f\", \"M232.27 511.89c-1-3.26-1.69-15.83-1.39-24.58.55-15.89 1-24.72 1.4-28.76.64-6.2 2.87-20.72 3.28-21.38.6-1 .4-27.87-.24-33.13-.31-2.58-.63-11.9-.69-20.73-.13-16.47-.53-20.12-2.73-24.76-1.1-2.32-1.23-3.84-1-11.43a92.38 92.38 0 0 0-.34-12.71c-2-13-3.46-27.7-3.25-33.9s.43-7.15 2.06-9.67c3.05-4.71 6.51-14 8.62-23.27 2.26-9.86 3.88-17.18 4.59-20.74a109.54 109.54 0 0 1 4.42-15.05c2.27-6.25 2.49-15.39.37-15.39-.3 0-1.38 1.22-2.41 2.71s-4.76 4.8-8.29 7.36c-8.37 6.08-11.7 9.39-12.66 12.58s-1 7.23-.16 7.76c.34.21 1.29 2.4 2.11 4.88a28.83 28.83 0 0 1 .72 15.36c-.39 1.77-1 5.47-1.46 8.23s-1 6.46-1.25 8.22a9.85 9.85 0 0 1-1.55 4.26c-1 1-1.14.91-2.05-.53a14.87 14.87 0 0 1-1.44-4.75c-.25-1.74-1.63-7.11-3.08-11.93-3.28-10.9-3.52-16.15-1-21a14.24 14.24 0 0 0 1.67-4.61c0-2.39-2.2-5.32-7.41-9.89-7-6.18-8.63-7.92-10.23-11.3-1.71-3.6-3.06-4.06-4.54-1.54-1.78 3-2.6 9.11-3 22l-.34 12.19 2 2.25c3.21 3.7 12.07 16.45 13.78 19.83 3.41 6.74 4.34 11.69 4.41 23.56s.95 22.75 2 24.71c.36.66.51 1.35.34 1.52s.41 2.09 1.29 4.27a38.14 38.14 0 0 1 2.06 9 91 91 0 0 0 1.71 10.37c2.23 9.56 2.77 14.08 2.39 20.14-.2 3.27-.53 11.07-.73 17.32-1.31 41.76-1.85 58-2 61.21-.12 2-.39 11.51-.6 21.07-.36 16.3-1.3 27.37-2.42 28.65-.64.73-8.07-4.91-12.52-9.49-3.75-3.87-4-4.79-2.83-9.95.7-3 2.26-18.29 3.33-32.62.36-4.78.81-10.5 1-12.71.83-9.37 1.66-20.35 2.61-34.78.56-8.46 1.33-16.44 1.72-17.73s.89-9.89 1.13-19.11l.43-16.77-2.26-4.3c-1.72-3.28-4.87-6.94-13.22-15.34-6-6.07-11.84-12.3-12.91-13.85l-1.95-2.81.75-10.9c1.09-15.71 1.1-48.57 0-59.06l-.89-8.7-3.28-4.52c-5.86-8.08-5.8-7.75-6.22-33.27-.1-6.07-.38-11.5-.63-12.06-.83-1.87-3.05-2.66-8.54-3.05-8.86-.62-11-1.9-23.85-14.55-6.15-6-12.34-12-13.75-13.19-2.81-2.42-2.79-2-.56-9.63l1.35-4.65-1.69-3a32.22 32.22 0 0 0-2.59-4.07c-1.33-1.51-5.5-10.89-6-13.49a4.24 4.24 0 0 1 .87-3.9c2.23-2.86 3.4-5.68 4.45-10.73 2.33-11.19 7.74-26.09 10.6-29.22 3.18-3.47 7.7-1 9.41 5 1.34 4.79 1.37 9.79.1 18.55a101.2 101.2 0 0 0-1 11.11c0 4 .19 4.69 2.25 7.39 3.33 4.37 7.73 7.41 15.2 10.52a18.67 18.67 0 0 1 4.72 2.85c11.17 10.72 18.62 16.18 22.95 16.85 5.18.8 8 4.54 10 13.39 1.31 5.65 4 11.14 5.46 11.14a9.38 9.38 0 0 0 3.33-1.39c2-1.22 2.25-1.73 2.25-4.18a132.88 132.88 0 0 0-2-17.84c-.37-1.66-.78-4.06-.93-5.35s-.61-3.85-1-5.69c-2.55-11.16-3.65-15.46-4.1-16-1.55-2-4.08-10.2-4.93-15.92-1.64-11.11-4-14.23-12.91-17.39A43.15 43.15 0 0 1 165.24 78c-1.15-1-4-3.22-6.35-5.06s-4.41-3.53-4.6-3.76a22.7 22.7 0 0 0-2.69-2c-6.24-4.22-8.84-7-11.26-12l-2.44-5-.22-13-.22-13 6.91-6.55c3.95-3.75 8.48-7.35 10.59-8.43 3.31-1.69 4.45-1.89 11.37-2 8.53-.19 10.12 0 11.66 1.56s1.36 6.4-.29 8.5a6.66 6.66 0 0 0-1.34 2.32c0 .58-2.61 4.91-5.42 9a30.39 30.39 0 0 0-2.37 6.82c20.44 13.39 21.55 3.77 14.07 29L194 66.92c3.11-8.66 6.47-17.26 8.61-26.22.29-7.63-12-4.19-15.4-8.68-2.33-5.93 3.13-14.18 6.06-19.2 1.6-2.34 6.62-4.7 8.82-4.15.88.22 4.16-.35 7.37-1.28a45.3 45.3 0 0 1 7.55-1.68 29.57 29.57 0 0 0 6-1.29c3.65-1.11 4.5-1.17 6.35-.4a29.54 29.54 0 0 0 5.82 1.36 18.18 18.18 0 0 1 6 1.91 22.67 22.67 0 0 0 5 2.17c2.51.68 3 .57 7.05-1.67l4.35-2.4L268.32 5c10.44-.4 10.81-.47 15.26-2.68L288.16 0l2.46 1.43c1.76 1 3.14 2.73 4.85 6 2.36 4.51 2.38 4.58 1.37 7.37-.88 2.44-.89 3.3-.1 6.39a35.76 35.76 0 0 0 2.1 5.91 13.55 13.55 0 0 1 1.31 4c.31 4.33 0 5.3-2.41 6.92-2.17 1.47-7 7.91-7 9.34a14.77 14.77 0 0 1-1.07 3c-5 11.51-6.76 13.56-14.26 17-9.2 4.2-12.3 5.19-16.21 5.19-3.1 0-4 .25-4.54 1.26a18.33 18.33 0 0 1-4.09 3.71 13.62 13.62 0 0 0-4.38 4.78 5.89 5.89 0 0 1-2.49 2.91 6.88 6.88 0 0 0-2.45 1.71 67.62 67.62 0 0 1-7 5.38c-3.33 2.34-6.87 5-7.87 6A7.27 7.27 0 0 1 224 100a5.76 5.76 0 0 0-2.13 1.65c-1.31 1.39-1.49 2.11-1.14 4.6a36.45 36.45 0 0 0 1.42 5.88c1.32 3.8 1.31 7.86 0 10.57s-.89 6.65 1.35 9.59c2 2.63 2.16 4.56.71 8.84a33.45 33.45 0 0 0-1.06 8.91c0 4.88.22 6.28 1.46 8.38s1.82 2.48 3.24 2.32c2-.23 2.3-1.05 4.71-12.12 2.18-10 3.71-11.92 13.76-17.08 2.94-1.51 7.46-4 10-5.44s6.79-3.69 9.37-4.91a40.09 40.09 0 0 0 15.22-11.67c7.11-8.79 10-16.22 12.85-33.3a18.37 18.37 0 0 1 2.86-7.73 20.39 20.39 0 0 0 2.89-7.31c1-5.3 2.85-9.08 5.58-11.51 4.7-4.18 6-1.09 4.59 10.87-.46 3.86-1.1 10.33-1.44 14.38l-.61 7.36 4.45 4.09 4.45 4.09.11 8.42c.06 4.63.47 9.53.92 10.89l.82 2.47-6.43 6.28c-8.54 8.33-12.88 13.93-16.76 21.61-1.77 3.49-3.74 7.11-4.38 8-2.18 3.11-6.46 13-8.76 20.26l-2.29 7.22-7 6.49c-3.83 3.57-8 7.25-9.17 8.17-3.05 2.32-4.26 5.15-4.26 10a14.62 14.62 0 0 0 1.59 7.26 42 42 0 0 1 2.09 4.83 9.28 9.28 0 0 0 1.57 2.89c1.4 1.59 1.92 16.12.83 23.22-.68 4.48-3.63 12-4.7 12-1.79 0-4.06 9.27-5.07 20.74-.18 2-.62 5.94-1 8.7s-1 10-1.35 16.05c-.77 12.22-.19 18.77 2 23.15 3.41 6.69.52 12.69-11 22.84l-4 3.49.07 5.19a40.81 40.81 0 0 0 1.14 8.87c4.61 16 4.73 16.92 4.38 37.13-.46 26.4-.26 40.27.63 44.15a61.31 61.31 0 0 1 1.08 7c.17 2 .66 5.33 1.08 7.36.47 2.26.78 11 .79 22.74v19.06l-1.81 2.63c-2.71 3.91-15.11 13.54-15.49 12.29zm29.53-45.11c-.18-.3-.33-6.87-.33-14.59 0-14.06-.89-27.54-2.26-34.45-.4-2-.81-9.7-.9-17.06-.15-11.93-1.4-24.37-2.64-26.38-.66-1.07-3-17.66-3-21.3 0-4.23 1-6 5.28-9.13s4.86-3.14 5.48-.72c.28 1.1 1.45 5.62 2.6 10 3.93 15.12 4.14 16.27 4.05 21.74-.1 5.78-.13 6.13-1.74 17.73-1 7.07-1.17 12.39-1 28.43.17 19.4-.64 35.73-2 41.27-.71 2.78-2.8 5.48-3.43 4.43zm-71-37.58a101 101 0 0 1-1.73-10.79 100.5 100.5 0 0 0-1.73-10.79 37.53 37.53 0 0 1-1-6.49c-.31-3.19-.91-7.46-1.33-9.48-1-4.79-3.35-19.35-3.42-21.07 0-.74-.34-4.05-.7-7.36-.67-6.21-.84-27.67-.22-28.29 1-1 6.63 2.76 11.33 7.43l5.28 5.25-.45 6.47c-.25 3.56-.6 10.23-.78 14.83s-.49 9.87-.67 11.71-.61 9.36-.94 16.72c-.79 17.41-1.94 31.29-2.65 32a.62.62 0 0 1-1-.14zm-87.18-266.59c21.07 12.79 17.84 14.15 28.49 17.66 13 4.29 18.87 7.13 23.15 16.87C111.6 233.28 86.25 255 78.55 268c-31 52-6 101.59 62.75 87.21-14.18 29.23-78 28.63-98.68-4.9-24.68-39.95-22.09-118.3 61-187.66zm210.79 179c56.66 6.88 82.32-37.74 46.54-89.23 0 0-26.87-29.34-64.28-68 3-15.45 9.49-32.12 30.57-53.82 89.2 63.51 92 141.61 92.46 149.36 4.3 70.64-78.7 91.18-105.29 61.71z\"],\n    \"markdown\": [640, 512, [], \"f60f\", \"M593.8 59.1H46.2C20.7 59.1 0 79.8 0 105.2v301.5c0 25.5 20.7 46.2 46.2 46.2h547.7c25.5 0 46.2-20.7 46.1-46.1V105.2c0-25.4-20.7-46.1-46.2-46.1zM338.5 360.6H277v-120l-61.5 76.9-61.5-76.9v120H92.3V151.4h61.5l61.5 76.9 61.5-76.9h61.5v209.2zm135.3 3.1L381.5 256H443V151.4h61.5V256H566z\"],\n    \"mastodon\": [448, 512, [], \"f4f6\", \"M433 179.11c0-97.2-63.71-125.7-63.71-125.7-62.52-28.7-228.56-28.4-290.48 0 0 0-63.72 28.5-63.72 125.7 0 115.7-6.6 259.4 105.63 289.1 40.51 10.7 75.32 13 103.33 11.4 50.81-2.8 79.32-18.1 79.32-18.1l-1.7-36.9s-36.31 11.4-77.12 10.1c-40.41-1.4-83-4.4-89.63-54a102.54 102.54 0 0 1-.9-13.9c85.63 20.9 158.65 9.1 178.75 6.7 56.12-6.7 105-41.3 111.23-72.9 9.8-49.8 9-121.5 9-121.5zm-75.12 125.2h-46.63v-114.2c0-49.7-64-51.6-64 6.9v62.5h-46.33V197c0-58.5-64-56.6-64-6.9v114.2H90.19c0-122.1-5.2-147.9 18.41-175 25.9-28.9 79.82-30.8 103.83 6.1l11.6 19.5 11.6-19.5c24.11-37.1 78.12-34.8 103.83-6.1 23.71 27.3 18.4 53 18.4 175z\"],\n    \"maxcdn\": [512, 512, [], \"f136\", \"M461.1 442.7h-97.4L415.6 200c2.3-10.2.9-19.5-4.4-25.7-5-6.1-13.7-9.6-24.2-9.6h-49.3l-59.5 278h-97.4l59.5-278h-83.4l-59.5 278H0l59.5-278-44.6-95.4H387c39.4 0 75.3 16.3 98.3 44.9 23.3 28.6 31.8 67.4 23.6 105.9l-47.8 222.6z\"],\n    \"medapps\": [320, 512, [], \"f3c6\", \"M118.3 238.4c3.5-12.5 6.9-33.6 13.2-33.6 8.3 1.8 9.6 23.4 18.6 36.6 4.6-23.5 5.3-85.1 14.1-86.7 9-.7 19.7 66.5 22 77.5 9.9 4.1 48.9 6.6 48.9 6.6 1.9 7.3-24 7.6-40 7.8-4.6 14.8-5.4 27.7-11.4 28-4.7.2-8.2-28.8-17.5-49.6l-9.4 65.5c-4.4 13-15.5-22.5-21.9-39.3-3.3-.1-62.4-1.6-47.6-7.8l31-5zM228 448c21.2 0 21.2-32 0-32H92c-21.2 0-21.2 32 0 32h136zm-24 64c21.2 0 21.2-32 0-32h-88c-21.2 0-21.2 32 0 32h88zm34.2-141.5c3.2-18.9 5.2-36.4 11.9-48.8 7.9-14.7 16.1-28.1 24-41 24.6-40.4 45.9-75.2 45.9-125.5C320 69.6 248.2 0 160 0S0 69.6 0 155.2c0 50.2 21.3 85.1 45.9 125.5 7.9 12.9 16 26.3 24 41 6.7 12.5 8.7 29.8 11.9 48.9 3.5 21 36.1 15.7 32.6-5.1-3.6-21.7-5.6-40.7-15.3-58.6C66.5 246.5 33 211.3 33 155.2 33 87.3 90 32 160 32s127 55.3 127 123.2c0 56.1-33.5 91.3-66.1 151.6-9.7 18-11.7 37.4-15.3 58.6-3.4 20.6 29 26.4 32.6 5.1z\"],\n    \"medium\": [448, 512, [], \"f23a\", \"M0 32v448h448V32H0zm372.2 106.1l-24 23c-2.1 1.6-3.1 4.2-2.7 6.7v169.3c-.4 2.6.6 5.2 2.7 6.7l23.5 23v5.1h-118V367l24.3-23.6c2.4-2.4 2.4-3.1 2.4-6.7V199.8l-67.6 171.6h-9.1L125 199.8v115c-.7 4.8 1 9.7 4.4 13.2l31.6 38.3v5.1H71.2v-5.1l31.6-38.3c3.4-3.5 4.9-8.4 4.1-13.2v-133c.4-3.7-1-7.3-3.8-9.8L75 138.1V133h87.3l67.4 148L289 133.1h83.2v5z\"],\n    \"medium-m\": [512, 512, [], \"f3c7\", \"M71.5 142.3c.6-5.9-1.7-11.8-6.1-15.8L20.3 72.1V64h140.2l108.4 237.7L364.2 64h133.7v8.1l-38.6 37c-3.3 2.5-5 6.7-4.3 10.8v272c-.7 4.1 1 8.3 4.3 10.8l37.7 37v8.1H307.3v-8.1l39.1-37.9c3.8-3.8 3.8-5 3.8-10.8V171.2L241.5 447.1h-14.7L100.4 171.2v184.9c-1.1 7.8 1.5 15.6 7 21.2l50.8 61.6v8.1h-144v-8L65 377.3c5.4-5.6 7.9-13.5 6.5-21.2V142.3z\"],\n    \"medrt\": [544, 512, [], \"f3c8\", \"M113.7 256c0 121.8 83.9 222.8 193.5 241.1-18.7 4.5-38.2 6.9-58.2 6.9C111.4 504 0 393 0 256S111.4 8 248.9 8c20.1 0 39.6 2.4 58.2 6.9C197.5 33.2 113.7 134.2 113.7 256m297.4 100.3c-77.7 55.4-179.6 47.5-240.4-14.6 5.5 14.1 12.7 27.7 21.7 40.5 61.6 88.2 182.4 109.3 269.7 47 87.3-62.3 108.1-184.3 46.5-272.6-9-12.9-19.3-24.3-30.5-34.2 37.4 78.8 10.7 178.5-67 233.9m-218.8-244c-1.4 1-2.7 2.1-4 3.1 64.3-17.8 135.9 4 178.9 60.5 35.7 47 42.9 106.6 24.4 158 56.7-56.2 67.6-142.1 22.3-201.8-50-65.5-149.1-74.4-221.6-19.8M296 224c-4.4 0-8-3.6-8-8v-40c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v40c0 4.4-3.6 8-8 8h-40c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h40c4.4 0 8 3.6 8 8v40c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-40c0-4.4 3.6-8 8-8h40c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8h-40z\"],\n    \"meetup\": [512, 512, [], \"f2e0\", \"M99 414.3c1.1 5.7-2.3 11.1-8 12.3-5.4 1.1-10.9-2.3-12-8-1.1-5.4 2.3-11.1 7.7-12.3 5.4-1.2 11.1 2.3 12.3 8zm143.1 71.4c-6.3 4.6-8 13.4-3.7 20 4.6 6.6 13.4 8.3 20 3.7 6.3-4.6 8-13.4 3.4-20-4.2-6.5-13.1-8.3-19.7-3.7zm-86-462.3c6.3-1.4 10.3-7.7 8.9-14-1.1-6.6-7.4-10.6-13.7-9.1-6.3 1.4-10.3 7.7-9.1 14 1.4 6.6 7.6 10.6 13.9 9.1zM34.4 226.3c-10-6.9-23.7-4.3-30.6 6-6.9 10-4.3 24 5.7 30.9 10 7.1 23.7 4.6 30.6-5.7 6.9-10.4 4.3-24.1-5.7-31.2zm272-170.9c10.6-6.3 13.7-20 7.7-30.3-6.3-10.6-19.7-14-30-7.7s-13.7 20-7.4 30.6c6 10.3 19.4 13.7 29.7 7.4zm-191.1 58c7.7-5.4 9.4-16 4.3-23.7s-15.7-9.4-23.1-4.3c-7.7 5.4-9.4 16-4.3 23.7 5.1 7.8 15.6 9.5 23.1 4.3zm372.3 156c-7.4 1.7-12.3 9.1-10.6 16.9 1.4 7.4 8.9 12.3 16.3 10.6 7.4-1.4 12.3-8.9 10.6-16.6-1.5-7.4-8.9-12.3-16.3-10.9zm39.7-56.8c-1.1-5.7-6.6-9.1-12-8-5.7 1.1-9.1 6.9-8 12.6 1.1 5.4 6.6 9.1 12.3 8 5.4-1.5 9.1-6.9 7.7-12.6zM447 138.9c-8.6 6-10.6 17.7-4.9 26.3 5.7 8.6 17.4 10.6 26 4.9 8.3-6 10.3-17.7 4.6-26.3-5.7-8.7-17.4-10.9-25.7-4.9zm-6.3 139.4c26.3 43.1 15.1 100-26.3 129.1-17.4 12.3-37.1 17.7-56.9 17.1-12 47.1-69.4 64.6-105.1 32.6-1.1.9-2.6 1.7-3.7 2.9-39.1 27.1-92.3 17.4-119.4-22.3-9.7-14.3-14.6-30.6-15.1-46.9-65.4-10.9-90-94-41.1-139.7-28.3-46.9.6-107.4 53.4-114.9C151.6 70 234.1 38.6 290.1 82c67.4-22.3 136.3 29.4 130.9 101.1 41.1 12.6 52.8 66.9 19.7 95.2zm-70 74.3c-3.1-20.6-40.9-4.6-43.1-27.1-3.1-32 43.7-101.1 40-128-3.4-24-19.4-29.1-33.4-29.4-13.4-.3-16.9 2-21.4 4.6-2.9 1.7-6.6 4.9-11.7-.3-6.3-6-11.1-11.7-19.4-12.9-12.3-2-17.7 2-26.6 9.7-3.4 2.9-12 12.9-20 9.1-3.4-1.7-15.4-7.7-24-11.4-16.3-7.1-40 4.6-48.6 20-12.9 22.9-38 113.1-41.7 125.1-8.6 26.6 10.9 48.6 36.9 47.1 11.1-.6 18.3-4.6 25.4-17.4 4-7.4 41.7-107.7 44.6-112.6 2-3.4 8.9-8 14.6-5.1 5.7 3.1 6.9 9.4 6 15.1-1.1 9.7-28 70.9-28.9 77.7-3.4 22.9 26.9 26.6 38.6 4 3.7-7.1 45.7-92.6 49.4-98.3 4.3-6.3 7.4-8.3 11.7-8 3.1 0 8.3.9 7.1 10.9-1.4 9.4-35.1 72.3-38.9 87.7-4.6 20.6 6.6 41.4 24.9 50.6 11.4 5.7 62.5 15.7 58.5-11.1zm5.7 92.3c-10.3 7.4-12.9 22-5.7 32.6 7.1 10.6 21.4 13.1 32 6 10.6-7.4 13.1-22 6-32.6-7.4-10.6-21.7-13.5-32.3-6z\"],\n    \"megaport\": [496, 512, [], \"f5a3\", \"M214.5 209.6v66.2l33.5 33.5 33.3-33.3v-66.4l-33.4-33.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm145.1 414.4L367 441.6l-26-19.2v-65.5l-33.4-33.4-33.4 33.4v65.5L248 441.6l-26.1-19.2v-65.5l-33.4-33.4-33.5 33.4v65.5l-26.1 19.2-26.1-19.2v-87l59.5-59.5V188l59.5-59.5V52.9l26.1-19.2L274 52.9v75.6l59.5 59.5v87.6l59.7 59.7v87.1z\"],\n    \"mendeley\": [640, 512, [], \"f7b3\", \"M624.6 325.2c-12.3-12.4-29.7-19.2-48.4-17.2-43.3-1-49.7-34.9-37.5-98.8 22.8-57.5-14.9-131.5-87.4-130.8-77.4.7-81.7 82-130.9 82-48.1 0-54-81.3-130.9-82-72.9-.8-110.1 73.3-87.4 130.8 12.2 63.9 5.8 97.8-37.5 98.8-21.2-2.3-37 6.5-53 22.5-19.9 19.7-19.3 94.8 42.6 102.6 47.1 5.9 81.6-42.9 61.2-87.8-47.3-103.7 185.9-106.1 146.5-8.2-.1.1-.2.2-.3.4-26.8 42.8 6.8 97.4 58.8 95.2 52.1 2.1 85.4-52.6 58.8-95.2-.1-.2-.2-.3-.3-.4-39.4-97.9 193.8-95.5 146.5 8.2-4.6 10-6.7 21.3-5.7 33 4.9 53.4 68.7 74.1 104.9 35.2 17.8-14.8 23.1-65.6 0-88.3zm-303.9-19.1h-.6c-43.4 0-62.8-37.5-62.8-62.8 0-34.7 28.2-62.8 62.8-62.8h.6c34.7 0 62.8 28.1 62.8 62.8 0 25-19.2 62.8-62.8 62.8z\"],\n    \"microsoft\": [448, 512, [], \"f3ca\", \"M0 32h214.6v214.6H0V32zm233.4 0H448v214.6H233.4V32zM0 265.4h214.6V480H0V265.4zm233.4 0H448V480H233.4V265.4z\"],\n    \"mix\": [448, 512, [], \"f3cb\", \"M0 64v348.9c0 56.2 88 58.1 88 0V174.3c7.9-52.9 88-50.4 88 6.5v175.3c0 57.9 96 58 96 0V240c5.3-54.7 88-52.5 88 4.3v23.8c0 59.9 88 56.6 88 0V64H0z\"],\n    \"mixcloud\": [640, 512, [], \"f289\", \"M424.43 219.729C416.124 134.727 344.135 68 256.919 68c-72.266 0-136.224 46.516-159.205 114.074-54.545 8.029-96.63 54.822-96.63 111.582 0 62.298 50.668 112.966 113.243 112.966h289.614c52.329 0 94.969-42.362 94.969-94.693 0-45.131-32.118-83.063-74.48-92.2zm-20.489 144.53H114.327c-39.04 0-70.881-31.564-70.881-70.604s31.841-70.604 70.881-70.604c18.827 0 36.548 7.475 49.838 20.766 19.963 19.963 50.133-10.227 30.18-30.18-14.675-14.398-32.672-24.365-52.053-29.349 19.935-44.3 64.79-73.926 114.628-73.926 69.496 0 125.979 56.483 125.979 125.702 0 13.568-2.215 26.857-6.369 39.594-8.943 27.517 32.133 38.939 40.147 13.29 2.769-8.306 4.984-16.889 6.369-25.472 19.381 7.476 33.502 26.303 33.502 48.453 0 28.795-23.535 52.33-52.607 52.33zm235.069-52.33c0 44.024-12.737 86.386-37.102 122.657-4.153 6.092-10.798 9.414-17.72 9.414-16.317 0-27.127-18.826-17.443-32.949 19.381-29.349 29.903-63.682 29.903-99.122s-10.521-69.773-29.903-98.845c-15.655-22.831 19.361-47.24 35.163-23.534 24.366 35.993 37.102 78.356 37.102 122.379zm-70.88 0c0 31.565-9.137 62.021-26.857 88.325-4.153 6.091-10.798 9.136-17.72 9.136-17.201 0-27.022-18.979-17.443-32.948 13.013-19.104 19.658-41.255 19.658-64.513 0-22.981-6.645-45.408-19.658-64.512-15.761-22.986 19.008-47.095 35.163-23.535 17.719 26.026 26.857 56.483 26.857 88.047z\"],\n    \"mizuni\": [496, 512, [], \"f3cc\", \"M248 8C111 8 0 119.1 0 256c0 137 111 248 248 248s248-111 248-248C496 119.1 385 8 248 8zm-80 351.9c-31.4 10.6-58.8 27.3-80 48.2V136c0-22.1 17.9-40 40-40s40 17.9 40 40v223.9zm120-9.9c-12.9-2-26.2-3.1-39.8-3.1-13.8 0-27.2 1.1-40.2 3.1V136c0-22.1 17.9-40 40-40s40 17.9 40 40v214zm120 57.7c-21.2-20.8-48.6-37.4-80-48V136c0-22.1 17.9-40 40-40s40 17.9 40 40v271.7z\"],\n    \"modx\": [448, 512, [], \"f285\", \"M356 241.8l36.7 23.7V480l-133-83.8L356 241.8zM440 75H226.3l-23 37.8 153.5 96.5L440 75zm-89 142.8L55.2 32v214.5l46 29L351 217.8zM97 294.2L8 437h213.7l125-200.5L97 294.2z\"],\n    \"monero\": [496, 512, [], \"f3d0\", \"M352 384h108.4C417 455.9 338.1 504 248 504S79 455.9 35.6 384H144V256.2L248 361l104-105v128zM88 336V128l159.4 159.4L408 128v208h74.8c8.5-25.1 13.2-52 13.2-80C496 119 385 8 248 8S0 119 0 256c0 28 4.6 54.9 13.2 80H88z\"],\n    \"napster\": [496, 512, [], \"f3d2\", \"M298.3 373.6c-14.2 13.6-31.3 24.1-50.4 30.5-19-6.4-36.2-16.9-50.3-30.5h100.7zm44-199.6c20-16.9 43.6-29.2 69.6-36.2V299c0 219.4-328 217.6-328 .3V137.7c25.9 6.9 49.6 19.6 69.5 36.4 56.8-40 132.5-39.9 188.9-.1zm-208.8-58.5c64.4-60 164.3-60.1 228.9-.2-7.1 3.5-13.9 7.3-20.6 11.5-58.7-30.5-129.2-30.4-187.9.1-6.3-4-13.9-8.2-20.4-11.4zM43.8 93.2v69.3c-58.4 36.5-58.4 121.1.1 158.3 26.4 245.1 381.7 240.3 407.6 1.5l.3-1.7c58.7-36.3 58.9-121.7.2-158.2V93.2c-17.3.5-34 3-50.1 7.4-82-91.5-225.5-91.5-307.5.1-16.3-4.4-33.1-7-50.6-7.5zM259.2 352s36-.3 61.3-1.5c10.2-.5 21.1-4 25.5-6.5 26.3-15.1 25.4-39.2 26.2-47.4-79.5-.6-99.9-3.9-113 55.4zm-135.5-55.3c.8 8.2-.1 32.3 26.2 47.4 4.4 2.5 15.2 6 25.5 6.5 25.3 1.1 61.3 1.5 61.3 1.5-13.2-59.4-33.7-56.1-113-55.4zm169.1 123.4c-3.2-5.3-6.9-7.3-6.9-7.3-24.8 7.3-52.2 6.9-75.9 0 0 0-2.9 1.5-6.4 6.6-2.8 4.1-3.7 9.6-3.7 9.6 29.1 17.6 67.1 17.6 96.2 0-.1-.1-.3-4-3.3-8.9z\"],\n    \"neos\": [512, 512, [], \"f612\", \"M415.44 512h-95.11L212.12 357.46v91.1L125.69 512H28V29.82L68.47 0h108.05l123.74 176.13V63.45L386.69 0h97.69v461.5zM38.77 35.27V496l72-52.88V194l215.5 307.64h84.79l52.35-38.17h-78.27L69 13zm82.54 466.61l80-58.78v-101l-79.76-114.4v220.94L49 501.89h72.34zM80.63 10.77l310.6 442.57h82.37V10.77h-79.75v317.56L170.91 10.77zM311 191.65l72 102.81V15.93l-72 53v122.72z\"],\n    \"nimblr\": [384, 512, [], \"f5a8\", \"M246.6 299.29c15.57 0 27.15 11.46 27.15 27s-11.62 27-27.15 27c-15.7 0-27.15-11.57-27.15-27s11.55-27 27.15-27zM113 326.25c0-15.61 11.68-27 27.15-27s27.15 11.46 27.15 27-11.47 27-27.15 27c-15.44 0-27.15-11.31-27.15-27M191.76 159C157 159 89.45 178.77 59.25 227L14 0v335.48C14 433.13 93.61 512 191.76 512s177.76-78.95 177.76-176.52S290.13 159 191.76 159zm0 308.12c-73.27 0-132.51-58.9-132.51-131.59s59.24-131.59 132.51-131.59 132.51 58.86 132.51 131.54S265 467.07 191.76 467.07z\"],\n    \"node\": [640, 512, [], \"f419\", \"M316.3 452c-2.1 0-4.2-.6-6.1-1.6L291 439c-2.9-1.6-1.5-2.2-.5-2.5 3.8-1.3 4.6-1.6 8.7-4 .4-.2 1-.1 1.4.1l14.8 8.8c.5.3 1.3.3 1.8 0L375 408c.5-.3.9-.9.9-1.6v-66.7c0-.7-.3-1.3-.9-1.6l-57.8-33.3c-.5-.3-1.2-.3-1.8 0l-57.8 33.3c-.6.3-.9 1-.9 1.6v66.7c0 .6.4 1.2.9 1.5l15.8 9.1c8.6 4.3 13.9-.8 13.9-5.8v-65.9c0-.9.7-1.7 1.7-1.7h7.3c.9 0 1.7.7 1.7 1.7v65.9c0 11.5-6.2 18-17.1 18-3.3 0-6 0-13.3-3.6l-15.2-8.7c-3.7-2.2-6.1-6.2-6.1-10.5v-66.7c0-4.3 2.3-8.4 6.1-10.5l57.8-33.4c3.7-2.1 8.5-2.1 12.1 0l57.8 33.4c3.7 2.2 6.1 6.2 6.1 10.5v66.7c0 4.3-2.3 8.4-6.1 10.5l-57.8 33.4c-1.7 1.1-3.8 1.7-6 1.7zm46.7-65.8c0-12.5-8.4-15.8-26.2-18.2-18-2.4-19.8-3.6-19.8-7.8 0-3.5 1.5-8.1 14.8-8.1 11.9 0 16.3 2.6 18.1 10.6.2.8.8 1.3 1.6 1.3h7.5c.5 0 .9-.2 1.2-.5.3-.4.5-.8.4-1.3-1.2-13.8-10.3-20.2-28.8-20.2-16.5 0-26.3 7-26.3 18.6 0 12.7 9.8 16.1 25.6 17.7 18.9 1.9 20.4 4.6 20.4 8.3 0 6.5-5.2 9.2-17.4 9.2-15.3 0-18.7-3.8-19.8-11.4-.1-.8-.8-1.4-1.7-1.4h-7.5c-.9 0-1.7.7-1.7 1.7 0 9.7 5.3 21.3 30.6 21.3 18.5 0 29-7.2 29-19.8zm54.5-50.1c0 6.1-5 11.1-11.1 11.1s-11.1-5-11.1-11.1c0-6.3 5.2-11.1 11.1-11.1 6-.1 11.1 4.8 11.1 11.1zm-1.8 0c0-5.2-4.2-9.3-9.4-9.3-5.1 0-9.3 4.1-9.3 9.3 0 5.2 4.2 9.4 9.3 9.4 5.2-.1 9.4-4.3 9.4-9.4zm-4.5 6.2h-2.6c-.1-.6-.5-3.8-.5-3.9-.2-.7-.4-1.1-1.3-1.1h-2.2v5h-2.4v-12.5h4.3c1.5 0 4.4 0 4.4 3.3 0 2.3-1.5 2.8-2.4 3.1 1.7.1 1.8 1.2 2.1 2.8.1 1 .3 2.7.6 3.3zm-2.8-8.8c0-1.7-1.2-1.7-1.8-1.7h-2v3.5h1.9c1.6 0 1.9-1.1 1.9-1.8zM137.3 191c0-2.7-1.4-5.1-3.7-6.4l-61.3-35.3c-1-.6-2.2-.9-3.4-1h-.6c-1.2 0-2.3.4-3.4 1L3.7 184.6C1.4 185.9 0 188.4 0 191l.1 95c0 1.3.7 2.5 1.8 3.2 1.1.7 2.5.7 3.7 0L42 268.3c2.3-1.4 3.7-3.8 3.7-6.4v-44.4c0-2.6 1.4-5.1 3.7-6.4l15.5-8.9c1.2-.7 2.4-1 3.7-1 1.3 0 2.6.3 3.7 1l15.5 8.9c2.3 1.3 3.7 3.8 3.7 6.4v44.4c0 2.6 1.4 5.1 3.7 6.4l36.4 20.9c1.1.7 2.6.7 3.7 0 1.1-.6 1.8-1.9 1.8-3.2l.2-95zM472.5 87.3v176.4c0 2.6-1.4 5.1-3.7 6.4l-61.3 35.4c-2.3 1.3-5.1 1.3-7.4 0l-61.3-35.4c-2.3-1.3-3.7-3.8-3.7-6.4v-70.8c0-2.6 1.4-5.1 3.7-6.4l61.3-35.4c2.3-1.3 5.1-1.3 7.4 0l15.3 8.8c1.7 1 3.9-.3 3.9-2.2v-94c0-2.8 3-4.6 5.5-3.2l36.5 20.4c2.3 1.2 3.8 3.7 3.8 6.4zm-46 128.9c0-.7-.4-1.3-.9-1.6l-21-12.2c-.6-.3-1.3-.3-1.9 0l-21 12.2c-.6.3-.9.9-.9 1.6v24.3c0 .7.4 1.3.9 1.6l21 12.1c.6.3 1.3.3 1.8 0l21-12.1c.6-.3.9-.9.9-1.6v-24.3zm209.8-.7c2.3-1.3 3.7-3.8 3.7-6.4V192c0-2.6-1.4-5.1-3.7-6.4l-60.9-35.4c-2.3-1.3-5.1-1.3-7.4 0l-61.3 35.4c-2.3 1.3-3.7 3.8-3.7 6.4v70.8c0 2.7 1.4 5.1 3.7 6.4l60.9 34.7c2.2 1.3 5 1.3 7.3 0l36.8-20.5c2.5-1.4 2.5-5 0-6.4L550 241.6c-1.2-.7-1.9-1.9-1.9-3.2v-22.2c0-1.3.7-2.5 1.9-3.2l19.2-11.1c1.1-.7 2.6-.7 3.7 0l19.2 11.1c1.1.7 1.9 1.9 1.9 3.2v17.4c0 2.8 3.1 4.6 5.6 3.2l36.7-21.3zM559 219c-.4.3-.7.7-.7 1.2v13.6c0 .5.3 1 .7 1.2l11.8 6.8c.4.3 1 .3 1.4 0L584 235c.4-.3.7-.7.7-1.2v-13.6c0-.5-.3-1-.7-1.2l-11.8-6.8c-.4-.3-1-.3-1.4 0L559 219zm-254.2 43.5v-70.4c0-2.6-1.6-5.1-3.9-6.4l-61.1-35.2c-2.1-1.2-5-1.4-7.4 0l-61.1 35.2c-2.3 1.3-3.9 3.7-3.9 6.4v70.4c0 2.8 1.9 5.2 4 6.4l61.2 35.2c2.4 1.4 5.2 1.3 7.4 0l61-35.2c1.8-1 3.1-2.7 3.6-4.7.1-.5.2-1.1.2-1.7zm-74.3-124.9l-.8.5h1.1l-.3-.5zm76.2 130.2l-.4-.7v.9l.4-.2z\"],\n    \"node-js\": [448, 512, [], \"f3d3\", \"M224 508c-6.7 0-13.5-1.8-19.4-5.2l-61.7-36.5c-9.2-5.2-4.7-7-1.7-8 12.3-4.3 14.8-5.2 27.9-12.7 1.4-.8 3.2-.5 4.6.4l47.4 28.1c1.7 1 4.1 1 5.7 0l184.7-106.6c1.7-1 2.8-3 2.8-5V149.3c0-2.1-1.1-4-2.9-5.1L226.8 37.7c-1.7-1-4-1-5.7 0L36.6 144.3c-1.8 1-2.9 3-2.9 5.1v213.1c0 2 1.1 4 2.9 4.9l50.6 29.2c27.5 13.7 44.3-2.4 44.3-18.7V167.5c0-3 2.4-5.3 5.4-5.3h23.4c2.9 0 5.4 2.3 5.4 5.3V378c0 36.6-20 57.6-54.7 57.6-10.7 0-19.1 0-42.5-11.6l-48.4-27.9C8.1 389.2.7 376.3.7 362.4V149.3c0-13.8 7.4-26.8 19.4-33.7L204.6 9c11.7-6.6 27.2-6.6 38.8 0l184.7 106.7c12 6.9 19.4 19.8 19.4 33.7v213.1c0 13.8-7.4 26.7-19.4 33.7L243.4 502.8c-5.9 3.4-12.6 5.2-19.4 5.2zm149.1-210.1c0-39.9-27-50.5-83.7-58-57.4-7.6-63.2-11.5-63.2-24.9 0-11.1 4.9-25.9 47.4-25.9 37.9 0 51.9 8.2 57.7 33.8.5 2.4 2.7 4.2 5.2 4.2h24c1.5 0 2.9-.6 3.9-1.7s1.5-2.6 1.4-4.1c-3.7-44.1-33-64.6-92.2-64.6-52.7 0-84.1 22.2-84.1 59.5 0 40.4 31.3 51.6 81.8 56.6 60.5 5.9 65.2 14.8 65.2 26.7 0 20.6-16.6 29.4-55.5 29.4-48.9 0-59.6-12.3-63.2-36.6-.4-2.6-2.6-4.5-5.3-4.5h-23.9c-3 0-5.3 2.4-5.3 5.3 0 31.1 16.9 68.2 97.8 68.2 58.4-.1 92-23.2 92-63.4z\"],\n    \"npm\": [576, 512, [], \"f3d4\", \"M288 288h-32v-64h32v64zm288-128v192H288v32H160v-32H0V160h576zm-416 32H32v128h64v-96h32v96h32V192zm160 0H192v160h64v-32h64V192zm224 0H352v128h64v-96h32v96h32v-96h32v96h32V192z\"],\n    \"ns8\": [640, 512, [], \"f3d5\", \"M187.1 159.9l-34.2 113.7-54.5-113.7H49L0 320h44.9L76 213.5 126.6 320h56.9L232 159.9h-44.9zm452.5-.9c-2.9-18-23.9-28.1-42.1-31.3-44.6-7.8-101.9 16.3-88.5 58.8v.1c-43.8 8.7-74.3 26.8-94.2 48.2-3-9.8-13.6-16.6-34-16.6h-87.6c-9.3 0-12.9-2.3-11.5-7.4 1.6-5.5 1.9-6.8 3.7-12.2 2.1-6.4 7.8-7.1 13.3-7.1h133.5l9.7-31.5c-139.7 0-144.5-.5-160.1 1.2-12.3 1.3-23.5 4.8-30.6 15-6.8 9.9-14.4 35.6-17.6 47.1-5.4 19.4-.6 28.6 32.8 28.6h87.3c7.8 0 8.8 2.7 7.7 6.6-1.1 4.4-2.8 10-4.5 14.6-1.6 4.2-4.7 7.4-13.8 7.4H216.3L204.7 320c139.9 0 145.3-.6 160.9-2.3 6.6-.7 13-2.1 18.5-4.9.2 3.7.5 7.3 1.2 10.8 5.4 30.5 27.4 52.3 56.8 59.5 48.6 11.9 108.7-16.8 135.1-68 18.7-36.2 14.1-76.2-3.4-105.5h.1c29.6-5.9 70.3-22 65.7-50.6zM530.7 263.7c-5.9 29.5-36.6 47.8-61.6 43.9-30.9-4.8-38.5-39.5-14.1-64.8 16.2-16.8 45.2-24 68.5-26.9 6.7 14.1 10.3 32 7.2 47.8zm21.8-83.1c-4.2-6-9.8-18.5-2.5-26.3 6.7-7.2 20.9-10.1 31.8-7.7 15.3 3.4 19.7 15.9 4.9 24.4-10.7 6.1-23.6 8.1-34.2 9.6z\"],\n    \"nutritionix\": [400, 512, [], \"f3d6\", \"M88 8.1S221.4-.1 209 112.5c0 0 19.1-74.9 103-40.6 0 0-17.7 74-88 56 0 0 14.6-54.6 66.1-56.6 0 0-39.9-10.3-82.1 48.8 0 0-19.8-94.5-93.6-99.7 0 0 75.2 19.4 77.6 107.5 0 .1-106.4 7-104-119.8zm312 315.6c0 48.5-9.7 95.3-32 132.3-42.2 30.9-105 48-168 48-62.9 0-125.8-17.1-168-48C9.7 419 0 372.2 0 323.7 0 275.3 17.7 229 40 192c42.2-30.9 97.1-48.6 160-48.6 63 0 117.8 17.6 160 48.6 22.3 37 40 83.3 40 131.7zM120 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM192 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM264 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zM336 428c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm0-66.2c0-15.5-12.5-28-28-28s-28 12.5-28 28 12.5 28 28 28 28-12.5 28-28zm24-39.6c-4.8-22.3-7.4-36.9-16-56-38.8-19.9-90.5-32-144-32S94.8 180.1 56 200c-8.8 19.5-11.2 33.9-16 56 42.2-7.9 98.7-14.8 160-14.8s117.8 6.9 160 14.8z\"],\n    \"odnoklassniki\": [320, 512, [], \"f263\", \"M275.1 334c-27.4 17.4-65.1 24.3-90 26.9l20.9 20.6 76.3 76.3c27.9 28.6-17.5 73.3-45.7 45.7-19.1-19.4-47.1-47.4-76.3-76.6L84 503.4c-28.2 27.5-73.6-17.6-45.4-45.7 19.4-19.4 47.1-47.4 76.3-76.3l20.6-20.6c-24.6-2.6-62.9-9.1-90.6-26.9-32.6-21-46.9-33.3-34.3-59 7.4-14.6 27.7-26.9 54.6-5.7 0 0 36.3 28.9 94.9 28.9s94.9-28.9 94.9-28.9c26.9-21.1 47.1-8.9 54.6 5.7 12.4 25.7-1.9 38-34.5 59.1zM30.3 129.7C30.3 58 88.6 0 160 0s129.7 58 129.7 129.7c0 71.4-58.3 129.4-129.7 129.4s-129.7-58-129.7-129.4zm66 0c0 35.1 28.6 63.7 63.7 63.7s63.7-28.6 63.7-63.7c0-35.4-28.6-64-63.7-64s-63.7 28.6-63.7 64z\"],\n    \"odnoklassniki-square\": [448, 512, [], \"f264\", \"M184.2 177.1c0-22.1 17.9-40 39.8-40s39.8 17.9 39.8 40c0 22-17.9 39.8-39.8 39.8s-39.8-17.9-39.8-39.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-305.1 97.1c0 44.6 36.4 80.9 81.1 80.9s81.1-36.2 81.1-80.9c0-44.8-36.4-81.1-81.1-81.1s-81.1 36.2-81.1 81.1zm174.5 90.7c-4.6-9.1-17.3-16.8-34.1-3.6 0 0-22.7 18-59.3 18s-59.3-18-59.3-18c-16.8-13.2-29.5-5.5-34.1 3.6-7.9 16.1 1.1 23.7 21.4 37 17.3 11.1 41.2 15.2 56.6 16.8l-12.9 12.9c-18.2 18-35.5 35.5-47.7 47.7-17.6 17.6 10.7 45.8 28.4 28.6l47.7-47.9c18.2 18.2 35.7 35.7 47.7 47.9 17.6 17.2 46-10.7 28.6-28.6l-47.7-47.7-13-12.9c15.5-1.6 39.1-5.9 56.2-16.8 20.4-13.3 29.3-21 21.5-37z\"],\n    \"old-republic\": [496, 512, [], \"f510\", \"M235.76 10.23c7.5-.31 15-.28 22.5-.09 3.61.14 7.2.4 10.79.73 4.92.27 9.79 1.03 14.67 1.62 2.93.43 5.83.98 8.75 1.46 7.9 1.33 15.67 3.28 23.39 5.4 12.24 3.47 24.19 7.92 35.76 13.21 26.56 12.24 50.94 29.21 71.63 49.88 20.03 20.09 36.72 43.55 48.89 69.19 1.13 2.59 2.44 5.1 3.47 7.74 2.81 6.43 5.39 12.97 7.58 19.63 4.14 12.33 7.34 24.99 9.42 37.83.57 3.14 1.04 6.3 1.4 9.47.55 3.83.94 7.69 1.18 11.56.83 8.34.84 16.73.77 25.1-.07 4.97-.26 9.94-.75 14.89-.24 3.38-.51 6.76-.98 10.12-.39 2.72-.63 5.46-1.11 8.17-.9 5.15-1.7 10.31-2.87 15.41-4.1 18.5-10.3 36.55-18.51 53.63-15.77 32.83-38.83 62.17-67.12 85.12a246.503 246.503 0 0 1-56.91 34.86c-6.21 2.68-12.46 5.25-18.87 7.41-3.51 1.16-7.01 2.38-10.57 3.39-6.62 1.88-13.29 3.64-20.04 5-4.66.91-9.34 1.73-14.03 2.48-5.25.66-10.5 1.44-15.79 1.74-6.69.66-13.41.84-20.12.81-6.82.03-13.65-.12-20.45-.79-3.29-.23-6.57-.5-9.83-.95-2.72-.39-5.46-.63-8.17-1.11-4.12-.72-8.25-1.37-12.35-2.22-4.25-.94-8.49-1.89-12.69-3.02-8.63-2.17-17.08-5.01-25.41-8.13-10.49-4.12-20.79-8.75-30.64-14.25-2.14-1.15-4.28-2.29-6.35-3.57-11.22-6.58-21.86-14.1-31.92-22.34-34.68-28.41-61.41-66.43-76.35-108.7-3.09-8.74-5.71-17.65-7.8-26.68-1.48-6.16-2.52-12.42-3.58-18.66-.4-2.35-.61-4.73-.95-7.09-.6-3.96-.75-7.96-1.17-11.94-.8-9.47-.71-18.99-.51-28.49.14-3.51.34-7.01.7-10.51.31-3.17.46-6.37.92-9.52.41-2.81.65-5.65 1.16-8.44.7-3.94 1.3-7.9 2.12-11.82 3.43-16.52 8.47-32.73 15.26-48.18 1.15-2.92 2.59-5.72 3.86-8.59 8.05-16.71 17.9-32.56 29.49-47.06 20-25.38 45.1-46.68 73.27-62.47 7.5-4.15 15.16-8.05 23.07-11.37 15.82-6.88 32.41-11.95 49.31-15.38 3.51-.67 7.04-1.24 10.56-1.85 2.62-.47 5.28-.7 7.91-1.08 3.53-.53 7.1-.68 10.65-1.04 2.46-.24 4.91-.36 7.36-.51m8.64 24.41c-9.23.1-18.43.99-27.57 2.23-7.3 1.08-14.53 2.6-21.71 4.3-13.91 3.5-27.48 8.34-40.46 14.42-10.46 4.99-20.59 10.7-30.18 17.22-4.18 2.92-8.4 5.8-12.34 9.03-5.08 3.97-9.98 8.17-14.68 12.59-2.51 2.24-4.81 4.7-7.22 7.06-28.22 28.79-48.44 65.39-57.5 104.69-2.04 8.44-3.54 17.02-4.44 25.65-1.1 8.89-1.44 17.85-1.41 26.8.11 7.14.38 14.28 1.22 21.37.62 7.12 1.87 14.16 3.2 21.18 1.07 4.65 2.03 9.32 3.33 13.91 6.29 23.38 16.5 45.7 30.07 65.75 8.64 12.98 18.78 24.93 29.98 35.77 16.28 15.82 35.05 29.04 55.34 39.22 7.28 3.52 14.66 6.87 22.27 9.63 5.04 1.76 10.06 3.57 15.22 4.98 11.26 3.23 22.77 5.6 34.39 7.06 2.91.29 5.81.61 8.72.9 13.82 1.08 27.74 1 41.54-.43 4.45-.6 8.92-.99 13.35-1.78 3.63-.67 7.28-1.25 10.87-2.1 4.13-.98 8.28-1.91 12.36-3.07 26.5-7.34 51.58-19.71 73.58-36.2 15.78-11.82 29.96-25.76 42.12-41.28 3.26-4.02 6.17-8.31 9.13-12.55 3.39-5.06 6.58-10.25 9.6-15.54 2.4-4.44 4.74-8.91 6.95-13.45 5.69-12.05 10.28-24.62 13.75-37.49 2.59-10.01 4.75-20.16 5.9-30.45 1.77-13.47 1.94-27.1 1.29-40.65-.29-3.89-.67-7.77-1-11.66-2.23-19.08-6.79-37.91-13.82-55.8-5.95-15.13-13.53-29.63-22.61-43.13-12.69-18.8-28.24-35.68-45.97-49.83-25.05-20-54.47-34.55-85.65-42.08-7.78-1.93-15.69-3.34-23.63-4.45-3.91-.59-7.85-.82-11.77-1.24-7.39-.57-14.81-.72-22.22-.58zM139.26 83.53c13.3-8.89 28.08-15.38 43.3-20.18-3.17 1.77-6.44 3.38-9.53 5.29-11.21 6.68-21.52 14.9-30.38 24.49-6.8 7.43-12.76 15.73-17.01 24.89-3.29 6.86-5.64 14.19-6.86 21.71-.93 4.85-1.3 9.81-1.17 14.75.13 13.66 4.44 27.08 11.29 38.82 5.92 10.22 13.63 19.33 22.36 27.26 4.85 4.36 10.24 8.09 14.95 12.6 2.26 2.19 4.49 4.42 6.43 6.91 2.62 3.31 4.89 6.99 5.99 11.1.9 3.02.66 6.2.69 9.31.02 4.1-.04 8.2.03 12.3.14 3.54-.02 7.09.11 10.63.08 2.38.02 4.76.05 7.14.16 5.77.06 11.53.15 17.3.11 2.91.02 5.82.13 8.74.03 1.63.13 3.28-.03 4.91-.91.12-1.82.18-2.73.16-10.99 0-21.88-2.63-31.95-6.93-6-2.7-11.81-5.89-17.09-9.83-5.75-4.19-11.09-8.96-15.79-14.31-6.53-7.24-11.98-15.39-16.62-23.95-1.07-2.03-2.24-4.02-3.18-6.12-1.16-2.64-2.62-5.14-3.67-7.82-4.05-9.68-6.57-19.94-8.08-30.31-.49-4.44-1.09-8.88-1.2-13.35-.7-15.73.84-31.55 4.67-46.82 2.12-8.15 4.77-16.18 8.31-23.83 6.32-14.2 15.34-27.18 26.3-38.19 6.28-6.2 13.13-11.84 20.53-16.67zm175.37-20.12c2.74.74 5.41 1.74 8.09 2.68 6.36 2.33 12.68 4.84 18.71 7.96 13.11 6.44 25.31 14.81 35.82 24.97 10.2 9.95 18.74 21.6 25.14 34.34 1.28 2.75 2.64 5.46 3.81 8.26 6.31 15.1 10 31.26 11.23 47.57.41 4.54.44 9.09.45 13.64.07 11.64-1.49 23.25-4.3 34.53-1.97 7.27-4.35 14.49-7.86 21.18-3.18 6.64-6.68 13.16-10.84 19.24-6.94 10.47-15.6 19.87-25.82 27.22-10.48 7.64-22.64 13.02-35.4 15.38-3.51.69-7.08 1.08-10.66 1.21-1.85.06-3.72.16-5.56-.1-.28-2.15 0-4.31-.01-6.46-.03-3.73.14-7.45.1-11.17.19-7.02.02-14.05.21-21.07.03-2.38-.03-4.76.03-7.14.17-5.07-.04-10.14.14-15.21.1-2.99-.24-6.04.51-8.96.66-2.5 1.78-4.86 3.09-7.08 4.46-7.31 11.06-12.96 17.68-18.26 5.38-4.18 10.47-8.77 15.02-13.84 7.68-8.37 14.17-17.88 18.78-28.27 2.5-5.93 4.52-12.1 5.55-18.46.86-4.37 1.06-8.83 1.01-13.27-.02-7.85-1.4-15.65-3.64-23.17-1.75-5.73-4.27-11.18-7.09-16.45-3.87-6.93-8.65-13.31-13.96-19.2-9.94-10.85-21.75-19.94-34.6-27.1-1.85-1.02-3.84-1.82-5.63-2.97zm-100.8 58.45c.98-1.18 1.99-2.33 3.12-3.38-.61.93-1.27 1.81-1.95 2.68-3.1 3.88-5.54 8.31-7.03 13.06-.87 3.27-1.68 6.6-1.73 10-.07 2.52-.08 5.07.32 7.57 1.13 7.63 4.33 14.85 8.77 21.12 2 2.7 4.25 5.27 6.92 7.33 1.62 1.27 3.53 2.09 5.34 3.05 3.11 1.68 6.32 3.23 9.07 5.48 2.67 2.09 4.55 5.33 4.4 8.79-.01 73.67 0 147.34-.01 221.02 0 1.35-.08 2.7.04 4.04.13 1.48.82 2.83 1.47 4.15.86 1.66 1.78 3.34 3.18 4.62.85.77 1.97 1.4 3.15 1.24 1.5-.2 2.66-1.35 3.45-2.57.96-1.51 1.68-3.16 2.28-4.85.76-2.13.44-4.42.54-6.63.14-4.03-.02-8.06.14-12.09.03-5.89.03-11.77.06-17.66.14-3.62.03-7.24.11-10.86.15-4.03-.02-8.06.14-12.09.03-5.99.03-11.98.07-17.97.14-3.62.02-7.24.11-10.86.14-3.93-.02-7.86.14-11.78.03-5.99.03-11.98.06-17.97.16-3.94-.01-7.88.19-11.82.29 1.44.13 2.92.22 4.38.19 3.61.42 7.23.76 10.84.32 3.44.44 6.89.86 10.32.37 3.1.51 6.22.95 9.31.57 4.09.87 8.21 1.54 12.29 1.46 9.04 2.83 18.11 5.09 26.99 1.13 4.82 2.4 9.61 4 14.3 2.54 7.9 5.72 15.67 10.31 22.62 1.73 2.64 3.87 4.98 6.1 7.21.27.25.55.51.88.71.6.25 1.31-.07 1.7-.57.71-.88 1.17-1.94 1.7-2.93 4.05-7.8 8.18-15.56 12.34-23.31.7-1.31 1.44-2.62 2.56-3.61 1.75-1.57 3.84-2.69 5.98-3.63 2.88-1.22 5.9-2.19 9.03-2.42 6.58-.62 13.11.75 19.56 1.85 3.69.58 7.4 1.17 11.13 1.41 3.74.1 7.48.05 11.21-.28 8.55-.92 16.99-2.96 24.94-6.25 5.3-2.24 10.46-4.83 15.31-7.93 11.46-7.21 21.46-16.57 30.04-27.01 1.17-1.42 2.25-2.9 3.46-4.28-1.2 3.24-2.67 6.37-4.16 9.48-1.25 2.9-2.84 5.61-4.27 8.42-5.16 9.63-11.02 18.91-17.75 27.52-4.03 5.21-8.53 10.05-13.33 14.57-6.64 6.05-14.07 11.37-22.43 14.76-8.21 3.37-17.31 4.63-26.09 3.29-3.56-.58-7.01-1.69-10.41-2.88-2.79-.97-5.39-2.38-8.03-3.69-3.43-1.71-6.64-3.81-9.71-6.08 2.71 3.06 5.69 5.86 8.7 8.61 4.27 3.76 8.74 7.31 13.63 10.23 3.98 2.45 8.29 4.4 12.84 5.51 1.46.37 2.96.46 4.45.6-1.25 1.1-2.63 2.04-3.99 2.98-9.61 6.54-20.01 11.86-30.69 16.43-20.86 8.7-43.17 13.97-65.74 15.34-4.66.24-9.32.36-13.98.36-4.98-.11-9.97-.13-14.92-.65-11.2-.76-22.29-2.73-33.17-5.43-10.35-2.71-20.55-6.12-30.3-10.55-8.71-3.86-17.12-8.42-24.99-13.79-1.83-1.31-3.74-2.53-5.37-4.08 6.6-1.19 13.03-3.39 18.99-6.48 5.74-2.86 10.99-6.66 15.63-11.07 2.24-2.19 4.29-4.59 6.19-7.09-3.43 2.13-6.93 4.15-10.62 5.78-4.41 2.16-9.07 3.77-13.81 5.02-5.73 1.52-11.74 1.73-17.61 1.14-8.13-.95-15.86-4.27-22.51-8.98-4.32-2.94-8.22-6.43-11.96-10.06-9.93-10.16-18.2-21.81-25.66-33.86-3.94-6.27-7.53-12.75-11.12-19.22-1.05-2.04-2.15-4.05-3.18-6.1 2.85 2.92 5.57 5.97 8.43 8.88 8.99 8.97 18.56 17.44 29.16 24.48 7.55 4.9 15.67 9.23 24.56 11.03 3.11.73 6.32.47 9.47.81 2.77.28 5.56.2 8.34.3 5.05.06 10.11.04 15.16-.16 3.65-.16 7.27-.66 10.89-1.09 2.07-.25 4.11-.71 6.14-1.2 3.88-.95 8.11-.96 11.83.61 4.76 1.85 8.44 5.64 11.38 9.71 2.16 3.02 4.06 6.22 5.66 9.58 1.16 2.43 2.46 4.79 3.55 7.26 1 2.24 2.15 4.42 3.42 6.52.67 1.02 1.4 2.15 2.62 2.55 1.06-.75 1.71-1.91 2.28-3.03 2.1-4.16 3.42-8.65 4.89-13.05 2.02-6.59 3.78-13.27 5.19-20.02 2.21-9.25 3.25-18.72 4.54-28.13.56-3.98.83-7.99 1.31-11.97.87-10.64 1.9-21.27 2.24-31.94.08-1.86.24-3.71.25-5.57.01-4.35.25-8.69.22-13.03-.01-2.38-.01-4.76 0-7.13.05-5.07-.2-10.14-.22-15.21-.2-6.61-.71-13.2-1.29-19.78-.73-5.88-1.55-11.78-3.12-17.51-2.05-7.75-5.59-15.03-9.8-21.82-3.16-5.07-6.79-9.88-11.09-14.03-3.88-3.86-8.58-7.08-13.94-8.45-1.5-.41-3.06-.45-4.59-.64.07-2.99.7-5.93 1.26-8.85 1.59-7.71 3.8-15.3 6.76-22.6 1.52-4.03 3.41-7.9 5.39-11.72 3.45-6.56 7.62-12.79 12.46-18.46zm31.27 1.7c.35-.06.71-.12 1.07-.19.19 1.79.09 3.58.1 5.37v38.13c-.01 1.74.13 3.49-.15 5.22-.36-.03-.71-.05-1.06-.05-.95-3.75-1.72-7.55-2.62-11.31-.38-1.53-.58-3.09-1.07-4.59-1.7-.24-3.43-.17-5.15-.2-5.06-.01-10.13 0-15.19-.01-1.66-.01-3.32.09-4.98-.03-.03-.39-.26-.91.16-1.18 1.28-.65 2.72-.88 4.06-1.35 3.43-1.14 6.88-2.16 10.31-3.31 1.39-.48 2.9-.72 4.16-1.54.04-.56.02-1.13-.05-1.68-1.23-.55-2.53-.87-3.81-1.28-3.13-1.03-6.29-1.96-9.41-3.02-1.79-.62-3.67-1-5.41-1.79-.03-.37-.07-.73-.11-1.09 5.09-.19 10.2.06 15.3-.12 3.36-.13 6.73.08 10.09-.07.12-.39.26-.77.37-1.16 1.08-4.94 2.33-9.83 3.39-14.75zm5.97-.2c.36.05.72.12 1.08.2.98 3.85 1.73 7.76 2.71 11.61.36 1.42.56 2.88 1.03 4.27 2.53.18 5.07-.01 7.61.05 5.16.12 10.33.12 15.49.07.76-.01 1.52.03 2.28.08-.04.36-.07.72-.1 1.08-1.82.83-3.78 1.25-5.67 1.89-3.73 1.23-7.48 2.39-11.22 3.57-.57.17-1.12.42-1.67.64-.15.55-.18 1.12-.12 1.69.87.48 1.82.81 2.77 1.09 4.88 1.52 9.73 3.14 14.63 4.6.38.13.78.27 1.13.49.4.27.23.79.15 1.18-1.66.13-3.31.03-4.97.04-5.17.01-10.33-.01-15.5.01-1.61.03-3.22-.02-4.82.21-.52 1.67-.72 3.42-1.17 5.11-.94 3.57-1.52 7.24-2.54 10.78-.36.01-.71.02-1.06.06-.29-1.73-.15-3.48-.15-5.22v-38.13c.02-1.78-.08-3.58.11-5.37zM65.05 168.33c1.12-2.15 2.08-4.4 3.37-6.46-1.82 7.56-2.91 15.27-3.62 23-.8 7.71-.85 15.49-.54 23.23 1.05 19.94 5.54 39.83 14.23 57.88 2.99 5.99 6.35 11.83 10.5 17.11 6.12 7.47 12.53 14.76 19.84 21.09 4.8 4.1 9.99 7.78 15.54 10.8 3.27 1.65 6.51 3.39 9.94 4.68 5.01 2.03 10.19 3.61 15.42 4.94 3.83.96 7.78 1.41 11.52 2.71 5 1.57 9.47 4.61 13.03 8.43 4.93 5.23 8.09 11.87 10.2 18.67.99 2.9 1.59 5.91 2.17 8.92.15.75.22 1.52.16 2.29-6.5 2.78-13.26 5.06-20.26 6.18-4.11.78-8.29.99-12.46 1.08-10.25.24-20.47-1.76-30.12-5.12-3.74-1.42-7.49-2.85-11.03-4.72-8.06-3.84-15.64-8.7-22.46-14.46-2.92-2.55-5.83-5.13-8.4-8.03-9.16-9.83-16.3-21.41-21.79-33.65-2.39-5.55-4.61-11.18-6.37-16.96-1.17-3.94-2.36-7.89-3.26-11.91-.75-2.94-1.22-5.95-1.87-8.92-.46-2.14-.69-4.32-1.03-6.48-.85-5.43-1.28-10.93-1.33-16.43.11-6.18.25-12.37 1.07-18.5.4-2.86.67-5.74 1.15-8.6.98-5.7 2.14-11.37 3.71-16.93 3.09-11.65 7.48-22.95 12.69-33.84zm363.73-6.44c1.1 1.66 1.91 3.48 2.78 5.26 2.1 4.45 4.24 8.9 6.02 13.49 7.61 18.76 12.3 38.79 13.04 59.05.02 1.76.07 3.52.11 5.29.13 9.57-1.27 19.09-3.18 28.45-.73 3.59-1.54 7.17-2.58 10.69-4.04 14.72-10 29-18.41 41.78-8.21 12.57-19.01 23.55-31.84 31.41-5.73 3.59-11.79 6.64-18.05 9.19-5.78 2.19-11.71 4.03-17.8 5.11-6.4 1.05-12.91 1.52-19.4 1.23-7.92-.48-15.78-2.07-23.21-4.85-1.94-.8-3.94-1.46-5.84-2.33-.21-1.51.25-2.99.53-4.46 1.16-5.74 3.03-11.36 5.7-16.58 2.37-4.51 5.52-8.65 9.46-11.9 2.43-2.05 5.24-3.61 8.16-4.83 3.58-1.5 7.47-1.97 11.24-2.83 7.23-1.71 14.37-3.93 21.15-7 10.35-4.65 19.71-11.38 27.65-19.46 1.59-1.61 3.23-3.18 4.74-4.87 3.37-3.76 6.71-7.57 9.85-11.53 7.48-10.07 12.82-21.59 16.71-33.48 1.58-5.3 3.21-10.6 4.21-16.05.63-2.87 1.04-5.78 1.52-8.68.87-6.09 1.59-12.22 1.68-18.38.12-6.65.14-13.32-.53-19.94-.73-7.99-1.87-15.96-3.71-23.78z\"],\n    \"opencart\": [640, 512, [], \"f23d\", \"M423.3 440.7c0 25.3-20.3 45.6-45.6 45.6s-45.8-20.3-45.8-45.6 20.6-45.8 45.8-45.8c25.4 0 45.6 20.5 45.6 45.8zm-253.9-45.8c-25.3 0-45.6 20.6-45.6 45.8s20.3 45.6 45.6 45.6 45.8-20.3 45.8-45.6-20.5-45.8-45.8-45.8zm291.7-270C158.9 124.9 81.9 112.1 0 25.7c34.4 51.7 53.3 148.9 373.1 144.2 333.3-5 130 86.1 70.8 188.9 186.7-166.7 319.4-233.9 17.2-233.9z\"],\n    \"openid\": [448, 512, [], \"f19b\", \"M271.5 432l-68 32C88.5 453.7 0 392.5 0 318.2c0-71.5 82.5-131 191.7-144.3v43c-71.5 12.5-124 53-124 101.3 0 51 58.5 93.3 135.7 103v-340l68-33.2v384zM448 291l-131.3-28.5 36.8-20.7c-19.5-11.5-43.5-20-70-24.8v-43c46.2 5.5 87.7 19.5 120.3 39.3l35-19.8L448 291z\"],\n    \"opera\": [496, 512, [], \"f26a\", \"M313.9 32.7c-170.2 0-252.6 223.8-147.5 355.1 36.5 45.4 88.6 75.6 147.5 75.6 36.3 0 70.3-11.1 99.4-30.4-43.8 39.2-101.9 63-165.3 63-3.9 0-8 0-11.9-.3C104.6 489.6 0 381.1 0 248 0 111 111 0 248 0h.8c63.1.3 120.7 24.1 164.4 63.1-29-19.4-63.1-30.4-99.3-30.4zm101.8 397.7c-40.9 24.7-90.7 23.6-132-5.8 56.2-20.5 97.7-91.6 97.7-176.6 0-84.7-41.2-155.8-97.4-176.6 41.8-29.2 91.2-30.3 132.9-5 105.9 98.7 105.5 265.7-1.2 364z\"],\n    \"optin-monster\": [576, 512, [], \"f23c\", \"M572.6 421.4c5.6-9.5 4.7-15.2-5.4-11.6-3-4.9-7-9.5-11.1-13.8 2.9-9.7-.7-14.2-10.8-9.2-4.6-3.2-10.3-6.5-15.9-9.2 0-15.1-11.6-11.6-17.6-5.7-10.4-1.5-18.7-.3-26.8 5.7.3-6.5.3-13 .3-19.7 12.6 0 40.2-11 45.9-36.2 1.4-6.8 1.6-13.8-.3-21.9-3-13.5-14.3-21.3-25.1-25.7-.8-5.9-7.6-14.3-14.9-15.9s-12.4 4.9-14.1 10.3c-8.5 0-19.2 2.8-21.1 8.4-5.4-.5-11.1-1.4-16.8-1.9 2.7-1.9 5.4-3.5 8.4-4.6 5.4-9.2 14.6-11.4 25.7-11.6V256c19.5-.5 43-5.9 53.8-18.1 12.7-13.8 14.6-37.3 12.4-55.1-2.4-17.3-9.7-37.6-24.6-48.1-8.4-5.9-21.6-.8-22.7 9.5-2.2 19.6 1.2 30-38.6 25.1-10.3-23.8-24.6-44.6-42.7-60C341 49.6 242.9 55.5 166.4 71.7c19.7 4.6 41.1 8.6 59.7 16.5-26.2 2.4-52.7 11.3-76.2 23.2-32.8 17-44 29.9-56.7 42.4 14.9-2.2 28.9-5.1 43.8-3.8-9.7 5.4-18.4 12.2-26.5 20-25.8.9-23.8-5.3-26.2-25.9-1.1-10.5-14.3-15.4-22.7-9.7-28.1 19.9-33.5 79.9-12.2 103.5 10.8 12.2 35.1 17.3 54.9 17.8-.3 1.1-.3 1.9-.3 2.7 10.8.5 19.5 2.7 24.6 11.6 3 1.1 5.7 2.7 8.1 4.6-5.4.5-11.1 1.4-16.5 1.9-3.3-6.6-13.7-8.1-21.1-8.1-1.6-5.7-6.5-12.2-14.1-10.3-6.8 1.9-14.1 10-14.9 15.9-22.5 9.5-30.1 26.8-25.1 47.6 5.3 24.8 33 36.2 45.9 36.2v19.7c-6.6-5-14.3-7.5-26.8-5.7-5.5-5.5-17.3-10.1-17.3 5.7-5.9 2.7-11.4 5.9-15.9 9.2-9.8-4.9-13.6-1.7-11.1 9.2-4.1 4.3-7.8 8.6-11.1 13.8-10.2-3.7-11 2.2-5.4 11.6-1.1 3.5-1.6 7-1.9 10.8-.5 31.6 44.6 64 73.5 65.1 17.3.5 34.6-8.4 43-23.5 113.2 4.9 226.7 4.1 340.2 0 8.1 15.1 25.4 24.3 42.7 23.5 29.2-1.1 74.3-33.5 73.5-65.1.2-3.7-.7-7.2-1.7-10.7zm-73.8-254c1.1-3 2.4-8.4 2.4-14.6 0-5.9 6.8-8.1 14.1-.8 11.1 11.6 14.9 40.5 13.8 51.1-4.1-13.6-13-29-30.3-35.7zm-4.6 6.7c19.5 6.2 28.6 27.6 29.7 48.9-1.1 2.7-3 5.4-4.9 7.6-5.7 5.9-15.4 10-26.2 12.2 4.3-21.3.3-47.3-12.7-63 4.9-.8 10.9-2.4 14.1-5.7zm-24.1 6.8c13.8 11.9 20 39.2 14.1 63.5-4.1.5-8.1.8-11.6.8-1.9-21.9-6.8-44-14.3-64.6 3.7.3 8.1.3 11.8.3zM47.5 203c-1.1-10.5 2.4-39.5 13.8-51.1 7-7.3 14.1-5.1 14.1.8 0 6.2 1.4 11.6 2.4 14.6-17.3 6.8-26.2 22.2-30.3 35.7zm9.7 27.6c-1.9-2.2-3.5-4.9-4.9-7.6 1.4-21.3 10.3-42.7 29.7-48.9 3.2 3.2 9.2 4.9 14.1 5.7-13 15.7-17 41.6-12.7 63-10.8-2.2-20.5-6-26.2-12.2zm47.9 14.6c-4.1 0-8.1-.3-12.7-.8-4.6-18.6-1.9-38.9 5.4-53v.3l12.2-5.1c4.9-1.9 9.7-3.8 14.9-4.9-10.7 19.7-17.4 41.3-19.8 63.5zm184-162.7c41.9 0 76.2 34 76.2 75.9 0 42.2-34.3 76.2-76.2 76.2s-76.2-34-76.2-76.2c0-41.8 34.3-75.9 76.2-75.9zm115.6 174.3c-.3 17.8-7 48.9-23 57-13.2 6.6-6.5-7.5-16.5-58.1 13.3.3 26.6.3 39.5 1.1zm-54-1.6c.8 4.9 3.8 40.3-1.6 41.9-11.6 3.5-40 4.3-51.1-1.1-4.1-3-4.6-35.9-4.3-41.1v.3c18.9-.3 38.1-.3 57 0zM278.3 309c-13 3.5-41.6 4.1-54.6-1.6-6.5-2.7-3.8-42.4-1.9-51.6 19.2-.5 38.4-.5 57.8-.8v.3c1.1 8.3 3.3 51.2-1.3 53.7zm-106.5-51.1c12.2-.8 24.6-1.4 36.8-1.6-2.4 15.4-3 43.5-4.9 52.2-1.1 6.8-4.3 6.8-9.7 4.3-21.9-9.8-27.6-35.2-22.2-54.9zm-35.4 31.3c7.8-1.1 15.7-1.9 23.5-2.7 1.6 6.2 3.8 11.9 7 17.6 10 17 44 35.7 45.1 7 6.2 14.9 40.8 12.2 54.9 10.8 15.7-1.4 23.8-1.4 26.8-14.3 12.4 4.3 30.8 4.1 44 3 11.3-.8 20.8-.5 24.6-8.9 1.1 5.1 1.9 11.6 4.6 16.8 10.8 21.3 37.3 1.4 46.8-31.6 8.6.8 17.6 1.9 26.5 2.7-.4 1.3-3.8 7.3 7.3 11.6-47.6 47-95.7 87.8-163.2 107-63.2-20.8-112.1-59.5-155.9-106.5 9.6-3.4 10.4-8.8 8-12.5zm-21.6 172.5c-3.8 17.8-21.9 29.7-39.7 28.9-19.2-.8-46.5-17-59.2-36.5-2.7-31.1 43.8-61.3 66.2-54.6 14.9 4.3 27.8 30.8 33.5 54 0 3-.3 5.7-.8 8.2zm-8.7-66c-.5-13.5-.5-27-.3-40.5h.3c2.7-1.6 5.7-3.8 7.8-6.5 6.5-1.6 13-5.1 15.1-9.2 3.3-7.1-7-7.5-5.4-12.4 2.7-1.1 5.7-2.2 7.8-3.5 29.2 29.2 58.6 56.5 97.3 77-36.8 11.3-72.4 27.6-105.9 47-1.2-18.6-7.7-35.9-16.7-51.9zm337.6 64.6c-103 3.5-206.2 4.1-309.4 0 0 .3 0 .3-.3.3v-.3h.3c35.1-21.6 72.2-39.2 112.4-50.8 11.6 5.1 23 9.5 34.9 13.2 2.2.8 2.2.8 4.3 0 14.3-4.1 28.4-9.2 42.2-15.4 41.5 11.7 78.8 31.7 115.6 53zm10.5-12.4c-35.9-19.5-73-35.9-111.9-47.6 38.1-20 71.9-47.3 103.5-76.7 2.2 1.4 4.6 2.4 7.6 3.2 0 .8.3 1.9.5 2.4-4.6 2.7-7.8 6.2-5.9 10.3 2.2 3.8 8.6 7.6 15.1 8.9 2.4 2.7 5.1 5.1 8.1 6.8 0 13.8-.3 27.6-.8 41.3l.3-.3c-9.3 15.9-15.5 37-16.5 51.7zm105.9 6.2c-12.7 19.5-40 35.7-59.2 36.5-19.3.9-40.5-13.2-40.5-37 5.7-23.2 18.9-49.7 33.5-54 22.7-6.9 69.2 23.4 66.2 54.5zM372.9 75.2c-3.8-72.1-100.8-79.7-126-23.5 44.6-24.3 90.3-15.7 126 23.5zM74.8 407.1c-15.7 1.6-49.5 25.4-49.5 43.2 0 11.6 15.7 19.5 32.2 14.9 12.2-3.2 31.1-17.6 35.9-27.3 6-11.6-3.7-32.7-18.6-30.8zm215.9-176.2c28.6 0 51.9-21.6 51.9-48.4 0-36.1-40.5-58.1-72.2-44.3 9.5 3 16.5 11.6 16.5 21.6 0 23.3-33.3 32-46.5 11.3-7.3 34.1 19.4 59.8 50.3 59.8zM68 474.1c.5 6.5 12.2 12.7 21.6 9.5 6.8-2.7 14.6-10.5 17.3-16.2 3-7-1.1-20-9.7-18.4-8.9 1.6-29.7 16.7-29.2 25.1zm433.2-67c-14.9-1.9-24.6 19.2-18.9 30.8 4.9 9.7 24.1 24.1 36.2 27.3 16.5 4.6 32.2-3.2 32.2-14.9 0-17.8-33.8-41.6-49.5-43.2zM478.8 449c-8.4-1.6-12.4 11.3-9.5 18.4 2.4 5.7 10.3 13.5 17.3 16.2 9.2 3.2 21.1-3 21.3-9.5.9-8.4-20.2-23.5-29.1-25.1z\"],\n    \"osi\": [512, 512, [], \"f41a\", \"M8 266.44C10.3 130.64 105.4 34 221.8 18.34c138.8-18.6 255.6 75.8 278 201.1 21.3 118.8-44 230-151.6 274-9.3 3.8-14.4 1.7-18-7.7q-26.7-69.45-53.4-139c-3.1-8.1-1-13.2 7-16.8 24.2-11 39.3-29.4 43.3-55.8a71.47 71.47 0 0 0-64.5-82.2c-39-3.4-71.8 23.7-77.5 59.7-5.2 33 11.1 63.7 41.9 77.7 9.6 4.4 11.5 8.6 7.8 18.4q-26.85 69.9-53.7 139.9c-2.6 6.9-8.3 9.3-15.5 6.5-52.6-20.3-101.4-61-130.8-119-24.9-49.2-25.2-87.7-26.8-108.7zm20.9-1.9c.4 6.6.6 14.3 1.3 22.1 6.3 71.9 49.6 143.5 131 183.1 3.2 1.5 4.4.8 5.6-2.3q22.35-58.65 45-117.3c1.3-3.3.6-4.8-2.4-6.7-31.6-19.9-47.3-48.5-45.6-86 1-21.6 9.3-40.5 23.8-56.3 30-32.7 77-39.8 115.5-17.6a91.64 91.64 0 0 1 45.2 90.4c-3.6 30.6-19.3 53.9-45.7 69.8-2.7 1.6-3.5 2.9-2.3 6q22.8 58.8 45.2 117.7c1.2 3.1 2.4 3.8 5.6 2.3 35.5-16.6 65.2-40.3 88.1-72 34.8-48.2 49.1-101.9 42.3-161-13.7-117.5-119.4-214.8-255.5-198-106.1 13-195.3 102.5-197.1 225.8z\"],\n    \"page4\": [496, 512, [], \"f3d7\", \"M248 504C111 504 0 393 0 256S111 8 248 8c20.9 0 41.3 2.6 60.7 7.5L42.3 392H248v112zm0-143.6V146.8L98.6 360.4H248zm96 31.6v92.7c45.7-19.2 84.5-51.7 111.4-92.7H344zm57.4-138.2l-21.2 8.4 21.2 8.3v-16.7zm-20.3 54.5c-6.7 0-8 6.3-8 12.9v7.7h16.2v-10c0-5.9-2.3-10.6-8.2-10.6zM496 256c0 37.3-8.2 72.7-23 104.4H344V27.3C433.3 64.8 496 153.1 496 256zM360.4 143.6h68.2V96h-13.9v32.6h-13.9V99h-13.9v29.6h-12.7V96h-13.9v47.6zm68.1 185.3H402v-11c0-15.4-5.6-25.2-20.9-25.2-15.4 0-20.7 10.6-20.7 25.9v25.3h68.2v-15zm0-103l-68.2 29.7V268l68.2 29.5v-16.6l-14.4-5.7v-26.5l14.4-5.9v-16.9zm-4.8-68.5h-35.6V184H402v-12.2h11c8.6 15.8 1.3 35.3-18.6 35.3-22.5 0-28.3-25.3-15.5-37.7l-11.6-10.6c-16.2 17.5-12.2 63.9 27.1 63.9 34 0 44.7-35.9 29.3-65.3z\"],\n    \"pagelines\": [384, 512, [], \"f18c\", \"M384 312.7c-55.1 136.7-187.1 54-187.1 54-40.5 81.8-107.4 134.4-184.6 134.7-16.1 0-16.6-24.4 0-24.4 64.4-.3 120.5-42.7 157.2-110.1-41.1 15.9-118.6 27.9-161.6-82.2 109-44.9 159.1 11.2 178.3 45.5 9.9-24.4 17-50.9 21.6-79.7 0 0-139.7 21.9-149.5-98.1 119.1-47.9 152.6 76.7 152.6 76.7 1.6-16.7 3.3-52.6 3.3-53.4 0 0-106.3-73.7-38.1-165.2 124.6 43 61.4 162.4 61.4 162.4.5 1.6.5 23.8 0 33.4 0 0 45.2-89 136.4-57.5-4.2 134-141.9 106.4-141.9 106.4-4.4 27.4-11.2 53.4-20 77.5 0 0 83-91.8 172-20z\"],\n    \"palfed\": [576, 512, [], \"f3d8\", \"M384.9 193.9c0-47.4-55.2-44.2-95.4-29.8-1.3 39.4-2.5 80.7-3 119.8.7 2.8 2.6 6.2 15.1 6.2 36.8 0 83.4-42.8 83.3-96.2zm-194.5 72.2c.2 0 6.5-2.7 11.2-2.7 26.6 0 20.7 44.1-14.4 44.1-21.5 0-37.1-18.1-37.1-43 0-42 42.9-95.6 100.7-126.5 1-12.4 3-22 10.5-28.2 11.2-9 26.6-3.5 29.5 11.1 72.2-22.2 135.2 1 135.2 72 0 77.9-79.3 152.6-140.1 138.2-.1 39.4.9 74.4 2.7 100v.2c.2 3.4.6 12.5-5.3 19.1-9.6 10.6-33.4 10-36.4-22.3-4.1-44.4.2-206.1 1.4-242.5-21.5 15-58.5 50.3-58.5 75.9.2 2.5.4 4 .6 4.6zM8 181.1s-.1 37.4 38.4 37.4h30l22.4 217.2s0 44.3 44.7 44.3h288.9s44.7-.4 44.7-44.3l22.4-217.2h30s38.4 1.2 38.4-37.4c0 0 .1-37.4-38.4-37.4h-30.1c-7.3-25.6-30.2-74.3-119.4-74.3h-28V50.3s-2.7-18.4-21.1-18.4h-85.8s-21.1 0-21.1 18.4v19.1h-28.1s-105 4.2-120.5 74.3h-29S8 142.5 8 181.1z\"],\n    \"patreon\": [512, 512, [], \"f3d9\", \"M512 194.8c0 101.3-82.4 183.8-183.8 183.8-101.7 0-184.4-82.4-184.4-183.8 0-101.6 82.7-184.3 184.4-184.3C429.6 10.5 512 93.2 512 194.8zM0 501.5h90v-491H0v491z\"],\n    \"paypal\": [384, 512, [], \"f1ed\", \"M111.4 295.9c-3.5 19.2-17.4 108.7-21.5 134-.3 1.8-1 2.5-3 2.5H12.3c-7.6 0-13.1-6.6-12.1-13.9L58.8 46.6c1.5-9.6 10.1-16.9 20-16.9 152.3 0 165.1-3.7 204 11.4 60.1 23.3 65.6 79.5 44 140.3-21.5 62.6-72.5 89.5-140.1 90.3-43.4.7-69.5-7-75.3 24.2zM357.1 152c-1.8-1.3-2.5-1.8-3 1.3-2 11.4-5.1 22.5-8.8 33.6-39.9 113.8-150.5 103.9-204.5 103.9-6.1 0-10.1 3.3-10.9 9.4-22.6 140.4-27.1 169.7-27.1 169.7-1 7.1 3.5 12.9 10.6 12.9h63.5c8.6 0 15.7-6.3 17.4-14.9.7-5.4-1.1 6.1 14.4-91.3 4.6-22 14.3-19.7 29.3-19.7 71 0 126.4-28.8 142.9-112.3 6.5-34.8 4.6-71.4-23.8-92.6z\"],\n    \"penny-arcade\": [640, 512, [], \"f704\", \"M421.91 164.27c-4.49 19.45-1.4 6.06-15.1 65.29l39.73-10.61c-22.34-49.61-17.29-38.41-24.63-54.68zm-206.09 51.11c-20.19 5.4-11.31 3.03-39.63 10.58l4.46 46.19c28.17-7.59 20.62-5.57 34.82-9.34 42.3-9.79 32.85-56.42.35-47.43zm326.16-26.19l-45.47-99.2c-5.69-12.37-19.46-18.84-32.62-15.33-70.27 18.75-38.72 10.32-135.59 36.23a27.618 27.618 0 0 0-18.89 17.41C144.26 113.27 0 153.75 0 226.67c0 33.5 30.67 67.11 80.9 95.37l1.74 17.88a27.891 27.891 0 0 0-17.77 28.67l4.3 44.48c1.39 14.31 13.43 25.21 27.8 25.2 5.18-.01-3.01 1.78 122.53-31.76 12.57-3.37 21.12-15.02 20.58-28.02 216.59 45.5 401.99-5.98 399.89-84.83.01-28.15-22.19-66.56-97.99-104.47zM255.14 298.3l-21.91 5.88-48.44 12.91 2.46 23.55 20.53-5.51 4.51 44.51-115.31 30.78-4.3-44.52 20.02-5.35-11.11-114.64-20.12 5.39-4.35-44.5c178.15-47.54 170.18-46.42 186.22-46.65 56.66-1.13 64.15 71.84 42.55 104.43a86.7 86.7 0 0 1-50.75 33.72zm199.18 16.62l-3.89-39.49 14.9-3.98-6.61-14.68-57.76 15.42-4.1 17.54 19.2-5.12 4.05 39.54-112.85 30.07-4.46-44.43 20.99-5.59 33.08-126.47-17.15 4.56-4.2-44.48c93.36-24.99 65.01-17.41 135.59-36.24l66.67 145.47 20.79-5.56 4.3 44.48-108.55 28.96z\"],\n    \"periscope\": [448, 512, [], \"f3da\", \"M370 63.6C331.4 22.6 280.5 0 226.6 0 111.9 0 18.5 96.2 18.5 214.4c0 75.1 57.8 159.8 82.7 192.7C137.8 455.5 192.6 512 226.6 512c41.6 0 112.9-94.2 120.9-105 24.6-33.1 82-118.3 82-192.6 0-56.5-21.1-110.1-59.5-150.8zM226.6 493.9c-42.5 0-190-167.3-190-279.4 0-107.4 83.9-196.3 190-196.3 100.8 0 184.7 89 184.7 196.3.1 112.1-147.4 279.4-184.7 279.4zM338 206.8c0 59.1-51.1 109.7-110.8 109.7-100.6 0-150.7-108.2-92.9-181.8v.4c0 24.5 20.1 44.4 44.8 44.4 24.7 0 44.8-19.9 44.8-44.4 0-18.2-11.1-33.8-26.9-40.7 76.6-19.2 141 39.3 141 112.4z\"],\n    \"phabricator\": [496, 512, [], \"f3db\", \"M323 262.1l-.1-13s21.7-19.8 21.1-21.2l-9.5-20c-.6-1.4-29.5-.5-29.5-.5l-9.4-9.3s.2-28.5-1.2-29.1l-20.1-9.2c-1.4-.6-20.7 21-20.7 21l-13.1-.2s-20.5-21.4-21.9-20.8l-20 8.3c-1.4.5.2 28.9.2 28.9l-9.1 9.1s-29.2-.9-29.7.4l-8.1 19.8c-.6 1.4 21 21 21 21l.1 12.9s-21.7 19.8-21.1 21.2l9.5 20c.6 1.4 29.5.5 29.5.5l9.4 9.3s-.2 31.8 1.2 32.3l20.1 8.3c1.4.6 20.7-23.5 20.7-23.5l13.1.2s20.5 23.8 21.8 23.3l20-7.5c1.4-.6-.2-32.1-.2-32.1l9.1-9.1s29.2.9 29.7-.5l8.1-19.8c.7-1.1-20.9-20.7-20.9-20.7zm-44.9-8.7c.7 17.1-12.8 31.6-30.1 32.4-17.3.8-32.1-12.5-32.8-29.6-.7-17.1 12.8-31.6 30.1-32.3 17.3-.8 32.1 12.5 32.8 29.5zm201.2-37.9l-97-97-.1.1c-75.1-73.3-195.4-72.8-269.8 1.6-50.9 51-27.8 27.9-95.7 95.3-22.3 22.3-22.3 58.7 0 81 69.9 69.4 46.4 46 97.4 97l.1-.1c75.1 73.3 195.4 72.9 269.8-1.6 51-50.9 27.9-27.9 95.3-95.3 22.3-22.3 22.3-58.7 0-81zM140.4 363.8c-59.6-59.5-59.6-156 0-215.5 59.5-59.6 156-59.5 215.6 0 59.5 59.5 59.6 156 0 215.6-59.6 59.5-156 59.4-215.6-.1z\"],\n    \"phoenix-framework\": [640, 512, [], \"f3dc\", \"M212.9 344.3c3.8-.1 22.8-1.4 25.6-2.2-2.4-2.6-43.6-1-68-49.6-4.3-8.6-7.5-17.6-6.4-27.6 2.9-25.5 32.9-30 52-18.5 36 21.6 63.3 91.3 113.7 97.5 37 4.5 84.6-17 108.2-45.4-.6-.1-.8-.2-1-.1-.4.1-.8.2-1.1.3-33.3 12.1-94.3 9.7-134.7-14.8-37.6-22.8-53.1-58.7-51.8-74.6 1.8-21.3 22.9-23.2 35.9-19.6 14.4 3.9 24.4 17.6 38.9 27.4 15.6 10.4 32.9 13.7 51.3 10.3 14.9-2.7 34.4-12.3 36.5-14.5-1.1-.1-1.8-.1-2.5-.2-6.2-.6-12.4-.8-18.5-1.7C279.8 194.5 262.1 47.4 138.5 37.9 94.2 34.5 39.1 46 2.2 72.9c-.8.6-1.5 1.2-2.2 1.8.1.2.1.3.2.5.8 0 1.6-.1 2.4-.2 6.3-1 12.5-.8 18.7.3 23.8 4.3 47.7 23.1 55.9 76.5 5.3 34.3-.7 50.8 8 86.1 19 77.1 91 107.6 127.7 106.4zM75.3 64.9c-.9-1-.9-1.2-1.3-2 12.1-2.6 24.2-4.1 36.6-4.8-1.1 14.7-22.2 21.3-35.3 6.8zm196.9 350.5c-42.8 1.2-92-26.7-123.5-61.4-4.6-5-16.8-20.2-18.6-23.4l.4-.4c6.6 4.1 25.7 18.6 54.8 27 24.2 7 48.1 6.3 71.6-3.3 22.7-9.3 41-.5 43.1 2.9-18.5 3.8-20.1 4.4-24 7.9-5.1 4.4-4.6 11.7 7 17.2 26.2 12.4 63-2.8 97.2 25.4 2.4 2 8.1 7.8 10.1 10.7-.1.2-.3.3-.4.5-4.8-1.5-16.4-7.5-40.2-9.3-24.7-2-46.3 5.3-77.5 6.2zm174.8-252c16.4-5.2 41.3-13.4 66.5-3.3 16.1 6.5 26.2 18.7 32.1 34.6 3.5 9.4 5.1 19.7 5.1 28.7-.2 0-.4 0-.6.1-.2-.4-.4-.9-.5-1.3-5-22-29.9-43.8-67.6-29.9-50.2 18.6-130.4 9.7-176.9-48-.7-.9-2.4-1.7-1.3-3.2.1-.2 2.1.6 3 1.3 18.1 13.4 38.3 21.9 60.3 26.2 30.5 6.1 54.6 2.9 79.9-5.2zm102.7 117.5c-32.4.2-33.8 50.1-103.6 64.4-18.2 3.7-38.7 4.6-44.9 4.2v-.4c2.8-1.5 14.7-2.6 29.7-16.6 7.9-7.3 15.3-15.1 22.8-22.9 19.5-20.2 41.4-42.2 81.9-39 23.1 1.8 29.3 8.2 36.1 12.7.3.2.4.5.7.9-.5 0-.7.1-.9 0-7-2.7-14.3-3.3-21.8-3.3zm-12.3-24.1c-.1.2-.1.4-.2.6-28.9-4.4-48-7.9-68.5 4-17 9.9-31.4 20.5-62 24.4-27.1 3.4-45.1 2.4-66.1-8-.3-.2-.6-.4-1-.6 0-.2.1-.3.1-.5 24.9 3.8 36.4 5.1 55.5-5.8 22.3-12.9 40.1-26.6 71.3-31 29.6-4.1 51.3 2.5 70.9 16.9zM268.6 97.3c-.6-.6-1.1-1.2-2.1-2.3 7.6 0 29.7-1.2 53.4 8.4 19.7 8 32.2 21 50.2 32.9 11.1 7.3 23.4 9.3 36.4 8.1 4.3-.4 8.5-1.2 12.8-1.7.4-.1.9 0 1.5.3-.6.4-1.2.9-1.8 1.2-8.1 4-16.7 6.3-25.6 7.1-26.1 2.6-50.3-3.7-73.4-15.4-19.3-9.9-36.4-22.9-51.4-38.6zM640 335.7c-3.5 3.1-22.7 11.6-42.7 5.3-12.3-3.9-19.5-14.9-31.6-24.1-10-7.6-20.9-7.9-28.1-8.4.6-.8.9-1.2 1.2-1.4 14.8-9.2 30.5-12.2 47.3-6.5 12.5 4.2 19.2 13.5 30.4 24.2 10.8 10.4 21 9.9 23.1 10.5.1-.1.2 0 .4.4zm-212.5 137c2.2 1.2 1.6 1.5 1.5 2-18.5-1.4-33.9-7.6-46.8-22.2-21.8-24.7-41.7-27.9-48.6-29.7.5-.2.8-.4 1.1-.4 13.1.1 26.1.7 38.9 3.9 25.3 6.4 35 25.4 41.6 35.3 3.2 4.8 7.3 8.3 12.3 11.1z\"],\n    \"phoenix-squadron\": [512, 512, [], \"f511\", \"M96 63.38C142.49 27.25 201.55 7.31 260.51 8.81c29.58-.38 59.11 5.37 86.91 15.33-24.13-4.63-49-6.34-73.38-2.45C231.17 27 191 48.84 162.21 80.87c5.67-1 10.78-3.67 16-5.86 18.14-7.87 37.49-13.26 57.23-14.83 19.74-2.13 39.64-.43 59.28 1.92-14.42 2.79-29.12 4.57-43 9.59-34.43 11.07-65.27 33.16-86.3 62.63-13.8 19.71-23.63 42.86-24.67 67.13-.35 16.49 5.22 34.81 19.83 44a53.27 53.27 0 0 0 37.52 6.74c15.45-2.46 30.07-8.64 43.6-16.33 11.52-6.82 22.67-14.55 32-24.25 3.79-3.22 2.53-8.45 2.62-12.79-2.12-.34-4.38-1.11-6.3.3a203 203 0 0 1-35.82 15.37c-20 6.17-42.16 8.46-62.1.78 12.79 1.73 26.06.31 37.74-5.44 20.23-9.72 36.81-25.2 54.44-38.77a526.57 526.57 0 0 1 88.9-55.31c25.71-12 52.94-22.78 81.57-24.12-15.63 13.72-32.15 26.52-46.78 41.38-14.51 14-27.46 29.5-40.11 45.18-3.52 4.6-8.95 6.94-13.58 10.16a150.7 150.7 0 0 0-51.89 60.1c-9.33 19.68-14.5 41.85-11.77 63.65 1.94 13.69 8.71 27.59 20.9 34.91 12.9 8 29.05 8.07 43.48 5.1 32.8-7.45 61.43-28.89 81-55.84 20.44-27.52 30.52-62.2 29.16-96.35-.52-7.5-1.57-15-1.66-22.49 8 19.48 14.82 39.71 16.65 60.83 2 14.28.75 28.76-1.62 42.9-1.91 11-5.67 21.51-7.78 32.43a165 165 0 0 0 39.34-81.07 183.64 183.64 0 0 0-14.21-104.64c20.78 32 32.34 69.58 35.71 107.48.49 12.73.49 25.51 0 38.23A243.21 243.21 0 0 1 482 371.34c-26.12 47.34-68 85.63-117.19 108-78.29 36.23-174.68 31.32-248-14.68A248.34 248.34 0 0 1 25.36 366 238.34 238.34 0 0 1 0 273.08v-31.34C3.93 172 40.87 105.82 96 63.38m222 80.33a79.13 79.13 0 0 0 16-4.48c5-1.77 9.24-5.94 10.32-11.22-8.96 4.99-17.98 9.92-26.32 15.7z\"],\n    \"php\": [640, 512, [], \"f457\", \"M320 104.5c171.4 0 303.2 72.2 303.2 151.5S491.3 407.5 320 407.5c-171.4 0-303.2-72.2-303.2-151.5S148.7 104.5 320 104.5m0-16.8C143.3 87.7 0 163 0 256s143.3 168.3 320 168.3S640 349 640 256 496.7 87.7 320 87.7zM218.2 242.5c-7.9 40.5-35.8 36.3-70.1 36.3l13.7-70.6c38 0 63.8-4.1 56.4 34.3zM97.4 350.3h36.7l8.7-44.8c41.1 0 66.6 3 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7h-70.7L97.4 350.3zm185.7-213.6h36.5l-8.7 44.8c31.5 0 60.7-2.3 74.8 10.7 14.8 13.6 7.7 31-8.3 113.1h-37c15.4-79.4 18.3-86 12.7-92-5.4-5.8-17.7-4.6-47.4-4.6l-18.8 96.6h-36.5l32.7-168.6zM505 242.5c-8 41.1-36.7 36.3-70.1 36.3l13.7-70.6c38.2 0 63.8-4.1 56.4 34.3zM384.2 350.3H421l8.7-44.8c43.2 0 67.1 2.5 90.2-19.1 26.1-24 32.9-66.7 14.3-88.1-9.7-11.2-25.3-16.7-46.5-16.7H417l-32.8 168.7z\"],\n    \"pied-piper\": [448, 512, [], \"f2ae\", \"M32 419L0 479.2l.8-328C.8 85.3 54 32 120 32h327.2c-93 28.9-189.9 94.2-253.9 168.6C122.7 282 82.6 338 32 419M448 32S305.2 98.8 261.6 199.1c-23.2 53.6-28.9 118.1-71 158.6-28.9 27.8-69.8 38.2-105.3 56.3-23.2 12-66.4 40.5-84.9 66h328.4c66 0 119.3-53.3 119.3-119.2-.1 0-.1-328.8-.1-328.8z\"],\n    \"pied-piper-alt\": [576, 512, [], \"f1a8\", \"M244 246c-3.2-2-6.3-2.9-10.1-2.9-6.6 0-12.6 3.2-19.3 3.7l1.7 4.9zm135.9 197.9c-19 0-64.1 9.5-79.9 19.8l6.9 45.1c35.7 6.1 70.1 3.6 106-9.8-4.8-10-23.5-55.1-33-55.1zM340.8 177c6.6 2.8 11.5 9.2 22.7 22.1 2-1.4 7.5-5.2 7.5-8.6 0-4.9-11.8-13.2-13.2-23 11.2-5.7 25.2-6 37.6-8.9 68.1-16.4 116.3-52.9 146.8-116.7C548.3 29.3 554 16.1 554.6 2l-2 2.6c-28.4 50-33 63.2-81.3 100-31.9 24.4-69.2 40.2-106.6 54.6l-6.3-.3v-21.8c-19.6 1.6-19.7-14.6-31.6-23-18.7 20.6-31.6 40.8-58.9 51.1-12.7 4.8-19.6 10-25.9 21.8 34.9-16.4 91.2-13.5 98.8-10zM555.5 0l-.6 1.1-.3.9.6-.6zm-59.2 382.1c-33.9-56.9-75.3-118.4-150-115.5l-.3-6c-1.1-13.5 32.8 3.2 35.1-31l-14.4 7.2c-19.8-45.7-8.6-54.3-65.5-54.3-14.7 0-26.7 1.7-41.4 4.6 2.9 18.6 2.2 36.7-10.9 50.3l19.5 5.5c-1.7 3.2-2.9 6.3-2.9 9.8 0 21 42.8 2.9 42.8 33.6 0 18.4-36.8 60.1-54.9 60.1-8 0-53.7-50-53.4-60.1l.3-4.6 52.3-11.5c13-2.6 12.3-22.7-2.9-22.7-3.7 0-43.1 9.2-49.4 10.6-2-5.2-7.5-14.1-13.8-14.1-3.2 0-6.3 3.2-9.5 4-9.2 2.6-31 2.9-21.5 20.1L15.9 298.5c-5.5 1.1-8.9 6.3-8.9 11.8 0 6 5.5 10.9 11.5 10.9 8 0 131.3-28.4 147.4-32.2 2.6 3.2 4.6 6.3 7.8 8.6 20.1 14.4 59.8 85.9 76.4 85.9 24.1 0 58-22.4 71.3-41.9 3.2-4.3 6.9-7.5 12.4-6.9.6 13.8-31.6 34.2-33 43.7-1.4 10.2-1 35.2-.3 41.1 26.7 8.1 52-3.6 77.9-2.9 4.3-21 10.6-41.9 9.8-63.5l-.3-9.5c-1.4-34.2-10.9-38.5-34.8-58.6-1.1-1.1-2.6-2.6-3.7-4 2.2-1.4 1.1-1 4.6-1.7 88.5 0 56.3 183.6 111.5 229.9 33.1-15 72.5-27.9 103.5-47.2-29-25.6-52.6-45.7-72.7-79.9zm-196.2 46.1v27.2l11.8-3.4-2.9-23.8zm-68.7-150.4l24.1 61.2 21-13.8-31.3-50.9zm84.4 154.9l2 12.4c9-1.5 58.4-6.6 58.4-14.1 0-1.4-.6-3.2-.9-4.6-26.8 0-36.9 3.8-59.5 6.3z\"],\n    \"pied-piper-hat\": [640, 512, [], \"f4e5\", \"M640 24.9c-80.8 53.6-89.4 92.5-96.4 104.4-6.7 12.2-11.7 60.3-23.3 83.6-11.7 23.6-54.2 42.2-66.1 50-11.7 7.8-28.3 38.1-41.9 64.2-108.1-4.4-167.4 38.8-259.2 93.6 29.4-9.7 43.3-16.7 43.3-16.7 94.2-36 139.3-68.3 281.1-49.2 1.1 0 1.9.6 2.8.8 3.9 2.2 5.3 6.9 3.1 10.8l-53.9 95.8c-2.5 4.7-7.8 7.2-13.1 6.1-126.8-23.8-226.9 17.3-318.9 18.6C24.1 488 0 453.4 0 451.8c0-1.1.6-1.7 1.7-1.7 0 0 38.3 0 103.1-15.3C178.4 294.5 244 245.4 315.4 245.4c0 0 71.7 0 90.6 61.9 22.8-39.7 28.3-49.2 28.3-49.2 5.3-9.4 35-77.2 86.4-141.4 51.5-64 90.4-79.9 119.3-91.8z\"],\n    \"pied-piper-pp\": [448, 512, [], \"f1a7\", \"M205.3 174.6c0 21.1-14.2 38.1-31.7 38.1-7.1 0-12.8-1.2-17.2-3.7v-68c4.4-2.7 10.1-4.2 17.2-4.2 17.5 0 31.7 16.9 31.7 37.8zm52.6 67c-7.1 0-12.8 1.5-17.2 4.2v68c4.4 2.5 10.1 3.7 17.2 3.7 17.4 0 31.7-16.9 31.7-37.8 0-21.1-14.3-38.1-31.7-38.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM185 255.1c41 0 74.2-35.6 74.2-79.6 0-44-33.2-79.6-74.2-79.6-12 0-24.1 3.2-34.6 8.8h-45.7V311l51.8-10.1v-50.6c8.6 3.1 18.1 4.8 28.5 4.8zm158.4 25.3c0-44-33.2-79.6-73.9-79.6-3.2 0-6.4.2-9.6.7-3.7 12.5-10.1 23.8-19.2 33.4-13.8 15-32.2 23.8-51.8 24.8V416l51.8-10.1v-50.6c8.6 3.2 18.2 4.7 28.7 4.7 40.8 0 74-35.6 74-79.6z\"],\n    \"pinterest\": [496, 512, [], \"f0d2\", \"M496 256c0 137-111 248-248 248-25.6 0-50.2-3.9-73.4-11.1 10.1-16.5 25.2-43.5 30.8-65 3-11.6 15.4-59 15.4-59 8.1 15.4 31.7 28.5 56.8 28.5 74.8 0 128.7-68.8 128.7-154.3 0-81.9-66.9-143.2-152.9-143.2-107 0-163.9 71.8-163.9 150.1 0 36.4 19.4 81.7 50.3 96.1 4.7 2.2 7.2 1.2 8.3-3.3.8-3.4 5-20.3 6.9-28.1.6-2.5.3-4.7-1.7-7.1-10.1-12.5-18.3-35.3-18.3-56.6 0-54.7 41.4-107.6 112-107.6 60.9 0 103.6 41.5 103.6 100.9 0 67.1-33.9 113.6-78 113.6-24.3 0-42.6-20.1-36.7-44.8 7-29.5 20.5-61.3 20.5-82.6 0-19-10.2-34.9-31.4-34.9-24.9 0-44.9 25.7-44.9 60.2 0 22 7.4 36.8 7.4 36.8s-24.5 103.8-29 123.2c-5 21.4-3 51.6-.9 71.2C65.4 450.9 0 361.1 0 256 0 119 111 8 248 8s248 111 248 248z\"],\n    \"pinterest-p\": [384, 512, [], \"f231\", \"M204 6.5C101.4 6.5 0 74.9 0 185.6 0 256 39.6 296 63.6 296c9.9 0 15.6-27.6 15.6-35.4 0-9.3-23.7-29.1-23.7-67.8 0-80.4 61.2-137.4 140.4-137.4 68.1 0 118.5 38.7 118.5 109.8 0 53.1-21.3 152.7-90.3 152.7-24.9 0-46.2-18-46.2-43.8 0-37.8 26.4-74.4 26.4-113.4 0-66.2-93.9-54.2-93.9 25.8 0 16.8 2.1 35.4 9.6 50.7-13.8 59.4-42 147.9-42 209.1 0 18.9 2.7 37.5 4.5 56.4 3.4 3.8 1.7 3.4 6.9 1.5 50.4-69 48.6-82.5 71.4-172.8 12.3 23.4 44.1 36 69.3 36 106.2 0 153.9-103.5 153.9-196.8C384 71.3 298.2 6.5 204 6.5z\"],\n    \"pinterest-square\": [448, 512, [], \"f0d3\", \"M448 80v352c0 26.5-21.5 48-48 48H154.4c9.8-16.4 22.4-40 27.4-59.3 3-11.5 15.3-58.4 15.3-58.4 8 15.3 31.4 28.2 56.3 28.2 74.1 0 127.4-68.1 127.4-152.7 0-81.1-66.2-141.8-151.4-141.8-106 0-162.2 71.1-162.2 148.6 0 36 19.2 80.8 49.8 95.1 4.7 2.2 7.1 1.2 8.2-3.3.8-3.4 5-20.1 6.8-27.8.6-2.5.3-4.6-1.7-7-10.1-12.3-18.3-34.9-18.3-56 0-54.2 41-106.6 110.9-106.6 60.3 0 102.6 41.1 102.6 99.9 0 66.4-33.5 112.4-77.2 112.4-24.1 0-42.1-19.9-36.4-44.4 6.9-29.2 20.3-60.7 20.3-81.8 0-53-75.5-45.7-75.5 25 0 21.7 7.3 36.5 7.3 36.5-31.4 132.8-36.1 134.5-29.6 192.6l2.2.8H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48z\"],\n    \"playstation\": [576, 512, [], \"f3df\", \"M570.9 372.3c-11.3 14.2-38.8 24.3-38.8 24.3L327 470.2v-54.3l150.9-53.8c17.1-6.1 19.8-14.8 5.8-19.4-13.9-4.6-39.1-3.3-56.2 2.9L327 381.1v-56.4c23.2-7.8 47.1-13.6 75.7-16.8 40.9-4.5 90.9.6 130.2 15.5 44.2 14 49.2 34.7 38 48.9zm-224.4-92.5v-139c0-16.3-3-31.3-18.3-35.6-11.7-3.8-19 7.1-19 23.4v347.9l-93.8-29.8V32c39.9 7.4 98 24.9 129.2 35.4C424.1 94.7 451 128.7 451 205.2c0 74.5-46 102.8-104.5 74.6zM43.2 410.2c-45.4-12.8-53-39.5-32.3-54.8 19.1-14.2 51.7-24.9 51.7-24.9l134.5-47.8v54.5l-96.8 34.6c-17.1 6.1-19.7 14.8-5.8 19.4 13.9 4.6 39.1 3.3 56.2-2.9l46.4-16.9v48.8c-51.6 9.3-101.4 7.3-153.9-10z\"],\n    \"product-hunt\": [512, 512, [], \"f288\", \"M326.3 218.8c0 20.5-16.7 37.2-37.2 37.2h-70.3v-74.4h70.3c20.5 0 37.2 16.7 37.2 37.2zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-128.1-37.2c0-47.9-38.9-86.8-86.8-86.8H169.2v248h49.6v-74.4h70.3c47.9 0 86.8-38.9 86.8-86.8z\"],\n    \"pushed\": [432, 512, [], \"f3e1\", \"M407 111.9l-98.5-9 14-33.4c10.4-23.5-10.8-40.4-28.7-37L22.5 76.9c-15.1 2.7-26 18.3-21.4 36.6l105.1 348.3c6.5 21.3 36.7 24.2 47.7 7l35.3-80.8 235.2-231.3c16.4-16.8 4.3-42.9-17.4-44.8zM297.6 53.6c5.1-.7 7.5 2.5 5.2 7.4L286 100.9 108.6 84.6l189-31zM22.7 107.9c-3.1-5.1 1-10 6.1-9.1l248.7 22.7-96.9 230.7L22.7 107.9zM136 456.4c-2.6 4-7.9 3.1-9.4-1.2L43.5 179.7l127.7 197.6c-7 15-35.2 79.1-35.2 79.1zm272.8-314.5L210.1 337.3l89.7-213.7 106.4 9.7c4 1.1 5.7 5.3 2.6 8.6z\"],\n    \"python\": [448, 512, [], \"f3e2\", \"M439.8 200.5c-7.7-30.9-22.3-54.2-53.4-54.2h-40.1v47.4c0 36.8-31.2 67.8-66.8 67.8H172.7c-29.2 0-53.4 25-53.4 54.3v101.8c0 29 25.2 46 53.4 54.3 33.8 9.9 66.3 11.7 106.8 0 26.9-7.8 53.4-23.5 53.4-54.3v-40.7H226.2v-13.6h160.2c31.1 0 42.6-21.7 53.4-54.2 11.2-33.5 10.7-65.7 0-108.6zM286.2 404c11.1 0 20.1 9.1 20.1 20.3 0 11.3-9 20.4-20.1 20.4-11 0-20.1-9.2-20.1-20.4.1-11.3 9.1-20.3 20.1-20.3zM167.8 248.1h106.8c29.7 0 53.4-24.5 53.4-54.3V91.9c0-29-24.4-50.7-53.4-55.6-35.8-5.9-74.7-5.6-106.8.1-45.2 8-53.4 24.7-53.4 55.6v40.7h106.9v13.6h-147c-31.1 0-58.3 18.7-66.8 54.2-9.8 40.7-10.2 66.1 0 108.6 7.6 31.6 25.7 54.2 56.8 54.2H101v-48.8c0-35.3 30.5-66.4 66.8-66.4zm-6.7-142.6c-11.1 0-20.1-9.1-20.1-20.3.1-11.3 9-20.4 20.1-20.4 11 0 20.1 9.2 20.1 20.4s-9 20.3-20.1 20.3z\"],\n    \"qq\": [448, 512, [], \"f1d6\", \"M433.754 420.445c-11.526 1.393-44.86-52.741-44.86-52.741 0 31.345-16.136 72.247-51.051 101.786 16.842 5.192 54.843 19.167 45.803 34.421-7.316 12.343-125.51 7.881-159.632 4.037-34.122 3.844-152.316 8.306-159.632-4.037-9.045-15.25 28.918-29.214 45.783-34.415-34.92-29.539-51.059-70.445-51.059-101.792 0 0-33.334 54.134-44.859 52.741-5.37-.65-12.424-29.644 9.347-99.704 10.261-33.024 21.995-60.478 40.144-105.779C60.683 98.063 108.982.006 224 0c113.737.006 163.156 96.133 160.264 214.963 18.118 45.223 29.912 72.85 40.144 105.778 21.768 70.06 14.716 99.053 9.346 99.704z\"],\n    \"quinscape\": [512, 512, [], \"f459\", \"M313.6 474.6h-1a158.1 158.1 0 0 1 0-316.2c94.9 0 168.2 83.1 157 176.6 4 5.1 8.2 9.6 11.2 15.3 13.4-30.3 20.3-62.4 20.3-97.7C501.1 117.5 391.6 8 256.5 8S12 117.5 12 252.6s109.5 244.6 244.5 244.6a237.36 237.36 0 0 0 70.4-10.1c-5.2-3.5-8.9-8.1-13.3-12.5zm-.1-.1l.4.1zm78.4-168.9a99.2 99.2 0 1 0 99.2 99.2 99.18 99.18 0 0 0-99.2-99.2z\"],\n    \"quora\": [448, 512, [], \"f2c4\", \"M440.5 386.7h-29.3c-1.5 13.5-10.5 30.8-33 30.8-20.5 0-35.3-14.2-49.5-35.8 44.2-34.2 74.7-87.5 74.7-153C403.5 111.2 306.8 32 205 32 105.3 32 7.3 111.7 7.3 228.7c0 134.1 131.3 221.6 249 189C276 451.3 302 480 351.5 480c81.8 0 90.8-75.3 89-93.3zM297 329.2C277.5 300 253.3 277 205.5 277c-30.5 0-54.3 10-69 22.8l12.2 24.3c6.2-3 13-4 19.8-4 35.5 0 53.7 30.8 69.2 61.3-10 3-20.7 4.2-32.7 4.2-75 0-107.5-53-107.5-156.7C97.5 124.5 130 71 205 71c76.2 0 108.7 53.5 108.7 157.7.1 41.8-5.4 75.6-16.7 100.5z\"],\n    \"r-project\": [581, 512, [], \"f4f7\", \"M581 226.6C581 119.1 450.9 32 290.5 32S0 119.1 0 226.6C0 322.4 103.3 402 239.4 418.1V480h99.1v-61.5c24.3-2.7 47.6-7.4 69.4-13.9L448 480h112l-67.4-113.7c54.5-35.4 88.4-84.9 88.4-139.7zm-466.8 14.5c0-73.5 98.9-133 220.8-133s211.9 40.7 211.9 133c0 50.1-26.5 85-70.3 106.4-2.4-1.6-4.7-2.9-6.4-3.7-10.2-5.2-27.8-10.5-27.8-10.5s86.6-6.4 86.6-92.7-90.6-87.9-90.6-87.9h-199V361c-74.1-21.5-125.2-67.1-125.2-119.9zm225.1 38.3v-55.6c57.8 0 87.8-6.8 87.8 27.3 0 36.5-38.2 28.3-87.8 28.3zm-.9 72.5H365c10.8 0 18.9 11.7 24 19.2-16.1 1.9-33 2.8-50.6 2.9v-22.1z\"],\n    \"raspberry-pi\": [407, 512, [], \"f7bb\", \"M372 232.5l-3.7-6.5c.1-46.4-21.4-65.3-46.5-79.7 7.6-2 15.4-3.6 17.6-13.2 13.1-3.3 15.8-9.4 17.1-15.8 3.4-2.3 14.8-8.7 13.6-19.7 6.4-4.4 10-10.1 8.1-18.1 6.9-7.5 8.7-13.7 5.8-19.4 8.3-10.3 4.6-15.6 1.1-20.9 6.2-11.2.7-23.2-16.6-21.2-6.9-10.1-21.9-7.8-24.2-7.8-2.6-3.2-6-6-16.5-4.7-6.8-6.1-14.4-5-22.3-2.1-9.3-7.3-15.5-1.4-22.6.8C271.6.6 269 5.5 263.5 7.6c-12.3-2.6-16.1 3-22 8.9l-6.9-.1c-18.6 10.8-27.8 32.8-31.1 44.1-3.3-11.3-12.5-33.3-31.1-44.1l-6.9.1c-5.9-5.9-9.7-11.5-22-8.9-5.6-2-8.1-7-19.4-3.4-4.6-1.4-8.9-4.4-13.9-4.3-2.6.1-5.5 1-8.7 3.5-7.9-3-15.5-4-22.3 2.1-10.5-1.3-14 1.4-16.5 4.7-2.3 0-17.3-2.3-24.2 7.8C21.2 16 15.8 28 22 39.2c-3.5 5.4-7.2 10.7 1.1 20.9-2.9 5.7-1.1 11.9 5.8 19.4-1.8 8 1.8 13.7 8.1 18.1-1.2 11 10.2 17.4 13.6 19.7 1.3 6.4 4 12.4 17.1 15.8 2.2 9.5 10 11.2 17.6 13.2-25.1 14.4-46.6 33.3-46.5 79.7l-3.7 6.5c-28.8 17.2-54.7 72.7-14.2 117.7 2.6 14.1 7.1 24.2 11 35.4 5.9 45.2 44.5 66.3 54.6 68.8 14.9 11.2 30.8 21.8 52.2 29.2C159 504.2 181 512 203 512h1c22.1 0 44-7.8 64.2-28.4 21.5-7.4 37.3-18 52.2-29.2 10.2-2.5 48.7-23.6 54.6-68.8 3.9-11.2 8.4-21.3 11-35.4 40.6-45.1 14.7-100.5-14-117.7zm-22.2-8c-1.5 18.7-98.9-65.1-82.1-67.9 45.7-7.5 83.6 19.2 82.1 67.9zm-43 93.1c-24.5 15.8-59.8 5.6-78.8-22.8s-14.6-64.2 9.9-80c24.5-15.8 59.8-5.6 78.8 22.8s14.6 64.2-9.9 80zM238.9 29.3c.8 4.2 1.8 6.8 2.9 7.6 5.4-5.8 9.8-11.7 16.8-17.3 0 3.3-1.7 6.8 2.5 9.4 3.7-5 8.8-9.5 15.5-13.3-3.2 5.6-.6 7.3 1.2 9.6 5.1-4.4 10-8.8 19.4-12.3-2.6 3.1-6.2 6.2-2.4 9.8 5.3-3.3 10.6-6.6 23.1-8.9-2.8 3.1-8.7 6.3-5.1 9.4 6.6-2.5 14-4.4 22.1-5.4-3.9 3.2-7.1 6.3-3.9 8.8 7.1-2.2 16.9-5.1 26.4-2.6l-6 6.1c-.7.8 14.1.6 23.9.8-3.6 5-7.2 9.7-9.3 18.2 1 1 5.8.4 10.4 0-4.7 9.9-12.8 12.3-14.7 16.6 2.9 2.2 6.8 1.6 11.2.1-3.4 6.9-10.4 11.7-16 17.3 1.4 1 3.9 1.6 9.7.9-5.2 5.5-11.4 10.5-18.8 15 1.3 1.5 5.8 1.5 10 1.6-6.7 6.5-15.3 9.9-23.4 14.2 4 2.7 6.9 2.1 10 2.1-5.7 4.7-15.4 7.1-24.4 10 1.7 2.7 3.4 3.4 7.1 4.1-9.5 5.3-23.2 2.9-27 5.6.9 2.7 3.6 4.4 6.7 5.8-15.4.9-57.3-.6-65.4-32.3 15.7-17.3 44.4-37.5 93.7-62.6-38.4 12.8-73 30-102 53.5-34.3-15.9-10.8-55.9 5.8-71.8zm-34.4 114.6c24.2-.3 54.1 17.8 54 34.7-.1 15-21 27.1-53.8 26.9-32.1-.4-53.7-15.2-53.6-29.8 0-11.9 26.2-32.5 53.4-31.8zm-123-12.8c3.7-.7 5.4-1.5 7.1-4.1-9-2.8-18.7-5.3-24.4-10 3.1 0 6 .7 10-2.1-8.1-4.3-16.7-7.7-23.4-14.2 4.2-.1 8.7 0 10-1.6-7.4-4.5-13.6-9.5-18.8-15 5.8.7 8.3.1 9.7-.9-5.6-5.6-12.7-10.4-16-17.3 4.3 1.5 8.3 2 11.2-.1-1.9-4.2-10-6.7-14.7-16.6 4.6.4 9.4 1 10.4 0-2.1-8.5-5.8-13.3-9.3-18.2 9.8-.1 24.6 0 23.9-.8l-6-6.1c9.5-2.5 19.3.4 26.4 2.6 3.2-2.5-.1-5.6-3.9-8.8 8.1 1.1 15.4 2.9 22.1 5.4 3.5-3.1-2.3-6.3-5.1-9.4 12.5 2.3 17.8 5.6 23.1 8.9 3.8-3.6.2-6.7-2.4-9.8 9.4 3.4 14.3 7.9 19.4 12.3 1.7-2.3 4.4-4 1.2-9.6 6.7 3.8 11.8 8.3 15.5 13.3 4.1-2.6 2.5-6.2 2.5-9.4 7 5.6 11.4 11.5 16.8 17.3 1.1-.8 2-3.4 2.9-7.6 16.6 15.9 40.1 55.9 6 71.8-29-23.5-63.6-40.7-102-53.5 49.3 25 78 45.3 93.7 62.6-8 31.8-50 33.2-65.4 32.3 3.1-1.4 5.8-3.2 6.7-5.8-4-2.8-17.6-.4-27.2-5.6zm60.1 24.1c16.8 2.8-80.6 86.5-82.1 67.9-1.5-48.7 36.5-75.5 82.1-67.9zM38.2 342c-23.7-18.8-31.3-73.7 12.6-98.3 26.5-7 9 107.8-12.6 98.3zm91 98.2c-13.3 7.9-45.8 4.7-68.8-27.9-15.5-27.4-13.5-55.2-2.6-63.4 16.3-9.8 41.5 3.4 60.9 25.6 16.9 20 24.6 55.3 10.5 65.7zm-26.4-119.7c-24.5-15.8-28.9-51.6-9.9-80s54.3-38.6 78.8-22.8 28.9 51.6 9.9 80c-19.1 28.4-54.4 38.6-78.8 22.8zM205 496c-29.4 1.2-58.2-23.7-57.8-32.3-.4-12.7 35.8-22.6 59.3-22 23.7-1 55.6 7.5 55.7 18.9.5 11-28.8 35.9-57.2 35.4zm58.9-124.9c.2 29.7-26.2 53.8-58.8 54-32.6.2-59.2-23.8-59.4-53.4v-.6c-.2-29.7 26.2-53.8 58.8-54 32.6-.2 59.2 23.8 59.4 53.4v.6zm82.2 42.7c-25.3 34.6-59.6 35.9-72.3 26.3-13.3-12.4-3.2-50.9 15.1-72 20.9-23.3 43.3-38.5 58.9-26.6 10.5 10.3 16.7 49.1-1.7 72.3zm22.9-73.2c-21.5 9.4-39-105.3-12.6-98.3 43.9 24.7 36.3 79.6 12.6 98.3z\"],\n    \"ravelry\": [512, 512, [], \"f2d9\", \"M407.4 61.5C331.6 22.1 257.8 31 182.9 66c-11.3 5.2-15.5 10.6-19.9 19-10.3 19.2-16.2 37.4-19.9 52.7-21.2 25.6-36.4 56.1-43.3 89.9-10.6 18-20.9 41.4-23.1 71.4 0 0-.7 7.6-.5 7.9-35.3-4.6-76.2-27-76.2-27 9.1 14.5 61.3 32.3 76.3 37.9 0 0 1.7 98 64.5 131.2-11.3-17.2-13.3-20.2-13.3-20.2S94.8 369 100.4 324.7c.7 0 1.5.2 2.2.2 23.9 87.4 103.2 151.4 196.9 151.4 6.2 0 12.1-.2 18-.7 14 1.5 27.6.5 40.1-3.9 6.9-2.2 13.8-6.4 20.2-10.8 70.2-39.1 100.9-82 123.1-147.7 5.4-16 8.1-35.5 9.8-52.2 8.7-82.3-30.6-161.6-103.3-199.5zM138.8 163.2s-1.2 12.3-.7 19.7c-3.4 2.5-10.1 8.1-18.2 16.7 5.2-12.8 11.3-25.1 18.9-36.4zm-31.2 121.9c4.4-17.2 13.3-39.1 29.8-55.1 0 0 1.7 48 15.8 90.1l-41.4-6.9c-2.2-9.2-3.5-18.5-4.2-28.1zm7.9 42.8c14.8 3.2 34 7.6 43.1 9.1 27.3 76.8 108.3 124.3 108.3 124.3 1 .5 1.7.7 2.7 1-73.1-11.6-132.7-64.7-154.1-134.4zM386 444.1c-14.5 4.7-36.2 8.4-64.7 3.7 0 0-91.1-23.1-127.5-107.8 38.2.7 52.4-.2 78-3.9 39.4-5.7 79-16.2 115-33 11.8-5.4 11.1-19.4 9.6-29.8-2-12.8-11.1-12.1-21.4-4.7 0 0-82 58.6-189.8 53.7-18.7-32-26.8-110.8-26.8-110.8 41.4-35.2 83.2-59.6 168.4-52.4.2-6.4 3-27.1-20.4-28.1 0 0-93.5-11.1-146 33.5 2.5-16.5 5.9-29.3 11.1-39.4 34.2-30.8 79-49.5 128.3-49.5 106.4 0 193 87.1 193 194.5-.2 76-43.8 142-106.8 174z\"],\n    \"react\": [512, 512, [], \"f41b\", \"M418.2 177.2c-5.4-1.8-10.8-3.5-16.2-5.1.9-3.7 1.7-7.4 2.5-11.1 12.3-59.6 4.2-107.5-23.1-123.3-26.3-15.1-69.2.6-112.6 38.4-4.3 3.7-8.5 7.6-12.5 11.5-2.7-2.6-5.5-5.2-8.3-7.7-45.5-40.4-91.1-57.4-118.4-41.5-26.2 15.2-34 60.3-23 116.7 1.1 5.6 2.3 11.1 3.7 16.7-6.4 1.8-12.7 3.8-18.6 5.9C38.3 196.2 0 225.4 0 255.6c0 31.2 40.8 62.5 96.3 81.5 4.5 1.5 9 3 13.6 4.3-1.5 6-2.8 11.9-4 18-10.5 55.5-2.3 99.5 23.9 114.6 27 15.6 72.4-.4 116.6-39.1 3.5-3.1 7-6.3 10.5-9.7 4.4 4.3 9 8.4 13.6 12.4 42.8 36.8 85.1 51.7 111.2 36.6 27-15.6 35.8-62.9 24.4-120.5-.9-4.4-1.9-8.9-3-13.5 3.2-.9 6.3-1.9 9.4-2.9 57.7-19.1 99.5-50 99.5-81.7 0-30.3-39.4-59.7-93.8-78.4zM282.9 92.3c37.2-32.4 71.9-45.1 87.7-36 16.9 9.7 23.4 48.9 12.8 100.4-.7 3.4-1.4 6.7-2.3 10-22.2-5-44.7-8.6-67.3-10.6-13-18.6-27.2-36.4-42.6-53.1 3.9-3.7 7.7-7.2 11.7-10.7zM167.2 307.5c5.1 8.7 10.3 17.4 15.8 25.9-15.6-1.7-31.1-4.2-46.4-7.5 4.4-14.4 9.9-29.3 16.3-44.5 4.6 8.8 9.3 17.5 14.3 26.1zm-30.3-120.3c14.4-3.2 29.7-5.8 45.6-7.8-5.3 8.3-10.5 16.8-15.4 25.4-4.9 8.5-9.7 17.2-14.2 26-6.3-14.9-11.6-29.5-16-43.6zm27.4 68.9c6.6-13.8 13.8-27.3 21.4-40.6s15.8-26.2 24.4-38.9c15-1.1 30.3-1.7 45.9-1.7s31 .6 45.9 1.7c8.5 12.6 16.6 25.5 24.3 38.7s14.9 26.7 21.7 40.4c-6.7 13.8-13.9 27.4-21.6 40.8-7.6 13.3-15.7 26.2-24.2 39-14.9 1.1-30.4 1.6-46.1 1.6s-30.9-.5-45.6-1.4c-8.7-12.7-16.9-25.7-24.6-39s-14.8-26.8-21.5-40.6zm180.6 51.2c5.1-8.8 9.9-17.7 14.6-26.7 6.4 14.5 12 29.2 16.9 44.3-15.5 3.5-31.2 6.2-47 8 5.4-8.4 10.5-17 15.5-25.6zm14.4-76.5c-4.7-8.8-9.5-17.6-14.5-26.2-4.9-8.5-10-16.9-15.3-25.2 16.1 2 31.5 4.7 45.9 8-4.6 14.8-10 29.2-16.1 43.4zM256.2 118.3c10.5 11.4 20.4 23.4 29.6 35.8-19.8-.9-39.7-.9-59.5 0 9.8-12.9 19.9-24.9 29.9-35.8zM140.2 57c16.8-9.8 54.1 4.2 93.4 39 2.5 2.2 5 4.6 7.6 7-15.5 16.7-29.8 34.5-42.9 53.1-22.6 2-45 5.5-67.2 10.4-1.3-5.1-2.4-10.3-3.5-15.5-9.4-48.4-3.2-84.9 12.6-94zm-24.5 263.6c-4.2-1.2-8.3-2.5-12.4-3.9-21.3-6.7-45.5-17.3-63-31.2-10.1-7-16.9-17.8-18.8-29.9 0-18.3 31.6-41.7 77.2-57.6 5.7-2 11.5-3.8 17.3-5.5 6.8 21.7 15 43 24.5 63.6-9.6 20.9-17.9 42.5-24.8 64.5zm116.6 98c-16.5 15.1-35.6 27.1-56.4 35.3-11.1 5.3-23.9 5.8-35.3 1.3-15.9-9.2-22.5-44.5-13.5-92 1.1-5.6 2.3-11.2 3.7-16.7 22.4 4.8 45 8.1 67.9 9.8 13.2 18.7 27.7 36.6 43.2 53.4-3.2 3.1-6.4 6.1-9.6 8.9zm24.5-24.3c-10.2-11-20.4-23.2-30.3-36.3 9.6.4 19.5.6 29.5.6 10.3 0 20.4-.2 30.4-.7-9.2 12.7-19.1 24.8-29.6 36.4zm130.7 30c-.9 12.2-6.9 23.6-16.5 31.3-15.9 9.2-49.8-2.8-86.4-34.2-4.2-3.6-8.4-7.5-12.7-11.5 15.3-16.9 29.4-34.8 42.2-53.6 22.9-1.9 45.7-5.4 68.2-10.5 1 4.1 1.9 8.2 2.7 12.2 4.9 21.6 5.7 44.1 2.5 66.3zm18.2-107.5c-2.8.9-5.6 1.8-8.5 2.6-7-21.8-15.6-43.1-25.5-63.8 9.6-20.4 17.7-41.4 24.5-62.9 5.2 1.5 10.2 3.1 15 4.7 46.6 16 79.3 39.8 79.3 58 0 19.6-34.9 44.9-84.8 61.4zm-149.7-15c25.3 0 45.8-20.5 45.8-45.8s-20.5-45.8-45.8-45.8c-25.3 0-45.8 20.5-45.8 45.8s20.5 45.8 45.8 45.8z\"],\n    \"reacteurope\": [576, 512, [], \"f75d\", \"M250.6 211.74l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm63.7 0l5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.2-.1-2.3-6.8-2.3 6.8-7.2.1 5.7 4.3zm-91.3 50.5h-3.4c-4.8 0-3.8 4-3.8 12.1 0 4.7-2.3 6.1-5.8 6.1s-5.8-1.4-5.8-6.1v-36.6c0-4.7 2.3-6.1 5.8-6.1s5.8 1.4 5.8 6.1c0 7.2-.7 10.5 3.8 10.5h3.4c4.7-.1 3.8-3.9 3.8-12.3 0-9.9-6.7-14.1-16.8-14.1h-.2c-10.1 0-16.8 4.2-16.8 14.1V276c0 10.4 6.7 14.1 16.8 14.1h.2c10.1 0 16.8-3.8 16.8-14.1 0-9.86 1.1-13.76-3.8-13.76zm-80.7 17.4h-14.7v-19.3H139c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-11.4v-18.3H142c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-21.7c-2.4-.1-3.7 1.3-3.7 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h21.9c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8zm-42-18.5c4.6-2 7.3-6 7.3-12.4v-11.9c0-10.1-6.7-14.1-16.8-14.1H77.4c-2.5 0-3.8 1.3-3.8 3.8v59.1c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5 0 3.8-1.3 3.8-3.8v-22.9h5.6l7.4 23.5a4.1 4.1 0 0 0 4.3 3.2h3.3c2.8 0 4-1.8 3.2-4.4zm-3.8-14c0 4.8-2.5 6.1-6.1 6.1h-5.8v-20.9h5.8c3.6 0 6.1 1.3 6.1 6.1zM176 226a3.82 3.82 0 0 0-4.2-3.4h-6.9a3.68 3.68 0 0 0-4 3.4l-11 59.2c-.5 2.7.9 4.1 3.4 4.1h3a3.74 3.74 0 0 0 4.1-3.5l1.8-11.3h12.2l1.8 11.3a3.74 3.74 0 0 0 4.1 3.5h3.5c2.6 0 3.9-1.4 3.4-4.1zm-12.3 39.3l4.7-29.7 4.7 29.7zm89.3 20.2v-53.2h7.5c2.5 0 3.8-1.3 3.8-3.8v-2.1c0-2.5-1.3-3.8-3.8-3.8h-25.8c-2.5 0-3.8 1.3-3.8 3.8v2.1c0 2.5 1.3 3.8 3.8 3.8h7.3v53.2c0 2.5 1.3 3.8 3.8 3.8h3.4c2.5.04 3.8-1.3 3.8-3.76zm248-.8h-19.4V258h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9H501a1.81 1.81 0 0 0 2-1.9v-.8a1.84 1.84 0 0 0-2-1.96zm-93.1-62.9h-.8c-10.1 0-15.3 4.7-15.3 14.1V276c0 9.3 5.2 14.1 15.3 14.1h.8c10.1 0 15.3-4.8 15.3-14.1v-40.1c0-9.36-5.2-14.06-15.3-14.06zm10.2 52.4c-.1 8-3 11.1-10.5 11.1s-10.5-3.1-10.5-11.1v-36.6c0-7.9 3-11.1 10.5-11.1s10.5 3.2 10.5 11.1zm-46.5-14.5c6.1-1.6 9.2-6.1 9.2-13.3v-9.7c0-9.4-5.2-14.1-15.3-14.1h-13.7a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.9h11.6l10.4 27.2a2.32 2.32 0 0 0 2.3 1.5h1.5c1.4 0 2-1 1.5-2.3zm-6.4-3.9H355v-28.5h10.2c7.5 0 10.5 3.1 10.5 11.1v6.4c0 7.84-3 11.04-10.5 11.04zm85.9-33.1h-13.7a1.62 1.62 0 0 0-2 1.8v63a1.81 1.81 0 0 0 2 1.9h1.2a1.74 1.74 0 0 0 1.9-1.9v-26.1h10.6c10.1 0 15.3-4.8 15.3-14.1v-10.5c0-9.4-5.2-14.1-15.3-14.1zm10.2 22.8c0 7.9-3 11.1-10.5 11.1h-10.2v-29.2h10.2c7.5-.1 10.5 3.1 10.5 11zM259.5 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm227.6-136.1a364.42 364.42 0 0 0-35.6-11.3c19.6-78 11.6-134.7-22.3-153.9C394.7-12.66 343.3 11 291 61.94q5.1 4.95 10.2 10.2c82.5-80 119.6-53.5 120.9-52.8 22.4 12.7 36 55.8 15.5 137.8a587.83 587.83 0 0 0-84.6-13C281.1 43.64 212.4 2 170.8 2 140 2 127 23 123.2 29.74c-18.1 32-13.3 84.2.1 133.8-70.5 20.3-120.7 54.1-120.3 95 .5 59.6 103.2 87.8 122.1 92.8-20.5 81.9-10.1 135.6 22.3 153.9 28 15.8 75.1 6 138.2-55.2q-5.1-4.95-10.2-10.2c-82.5 80-119.7 53.5-120.9 52.8-22.3-12.6-36-55.6-15.5-137.9 12.4 2.9 41.8 9.5 84.6 13 71.9 100.4 140.6 142 182.1 142 30.8 0 43.8-21 47.6-27.7 18-31.9 13.3-84.1-.1-133.8 152.3-43.8 156.2-130.2 33.9-176.3zM135.9 36.84c2.9-5.1 11.9-20.3 34.9-20.3 36.8 0 98.8 39.6 163.3 126.2a714 714 0 0 0-93.9.9 547.76 547.76 0 0 1 42.2-52.4Q277.3 86 272.2 81a598.25 598.25 0 0 0-50.7 64.2 569.69 569.69 0 0 0-84.4 14.6c-.2-1.4-24.3-82.2-1.2-123zm304.8 438.3c-2.9 5.1-11.8 20.3-34.9 20.3-36.7 0-98.7-39.4-163.3-126.2a695.38 695.38 0 0 0 93.9-.9 547.76 547.76 0 0 1-42.2 52.4q5.1 5.25 10.2 10.2a588.47 588.47 0 0 0 50.7-64.2c47.3-4.7 80.3-13.5 84.4-14.6 22.7 84.4 4.5 117 1.2 123zm9.1-138.6c-3.6-11.9-7.7-24.1-12.4-36.4a12.67 12.67 0 0 1-10.7-5.7l-.1.1a19.61 19.61 0 0 1-5.4 3.6c5.7 14.3 10.6 28.4 14.7 42.2a535.3 535.3 0 0 1-72 13c3.5-5.3 17.2-26.2 32.2-54.2a24.6 24.6 0 0 1-6-3.2c-1.1 1.2-3.6 4.2-10.9 4.2-6.2 11.2-17.4 30.9-33.9 55.2a711.91 711.91 0 0 1-112.4 1c-7.9-11.2-21.5-31.1-36.8-57.8a21 21 0 0 1-3-1.5c-1.9 1.6-3.9 3.2-12.6 3.2 6.3 11.2 17.5 30.7 33.8 54.6a548.81 548.81 0 0 1-72.2-11.7q5.85-21 14.1-42.9c-3.2 0-5.4.2-8.4-1a17.58 17.58 0 0 1-6.9 1c-4.9 13.4-9.1 26.5-12.7 39.4C-31.7 297-12.1 216 126.7 175.64c3.6 11.9 7.7 24.1 12.4 36.4 10.4 0 12.9 3.4 14.4 5.3a12 12 0 0 1 2.3-2.2c-5.8-14.7-10.9-29.2-15.2-43.3 7-1.8 32.4-8.4 72-13-15.9 24.3-26.7 43.9-32.8 55.3a14.22 14.22 0 0 1 6.4 8 23.42 23.42 0 0 1 10.2-8.4c6.5-11.7 17.9-31.9 34.8-56.9a711.72 711.72 0 0 1 112.4-1c31.5 44.6 28.9 48.1 42.5 64.5a21.42 21.42 0 0 1 10.4-7.4c-6.4-11.4-17.6-31-34.3-55.5 40.4 4.1 65 10 72.2 11.7-4 14.4-8.9 29.2-14.6 44.2a20.74 20.74 0 0 1 6.8 4.3l.1.1a12.72 12.72 0 0 1 8.9-5.6c4.9-13.4 9.2-26.6 12.8-39.5a359.71 359.71 0 0 1 34.5 11c106.1 39.9 74 87.9 72.6 90.4-19.8 35.1-80.1 55.2-105.7 62.5zm-114.4-114h-1.2a1.74 1.74 0 0 0-1.9 1.9v49.8c0 7.9-2.6 11.1-10.1 11.1s-10.1-3.1-10.1-11.1v-49.8a1.69 1.69 0 0 0-1.9-1.9H309a1.81 1.81 0 0 0-2 1.9v51.5c0 9.6 5 14.1 15.1 14.1h.4c10.1 0 15.1-4.6 15.1-14.1v-51.5a2 2 0 0 0-2.2-1.9zM321.7 308l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm-31.1 7.4l-2.3-6.8-2.3 6.8-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3zm5.1-30.8h-19.4v-26.7h16.1a1.89 1.89 0 0 0 2-2v-.8a1.89 1.89 0 0 0-2-2h-16.1v-25.8h19.1a1.89 1.89 0 0 0 2-2v-.8a1.77 1.77 0 0 0-2-1.9h-22.2a1.81 1.81 0 0 0-2 1.9v63a1.81 1.81 0 0 0 2 1.9h22.5a1.77 1.77 0 0 0 2-1.9v-.8a1.83 1.83 0 0 0-2-2.06zm-7.4-99.4L286 192l-7.1.1 5.7 4.3-2.1 6.8 5.8-4.1 5.8 4.1-2.1-6.8 5.7-4.3-7.1-.1z\"],\n    \"readme\": [576, 512, [], \"f4d5\", \"M528.3 46.5H388.5c-48.1 0-89.9 33.3-100.4 80.3-10.6-47-52.3-80.3-100.4-80.3H48c-26.5 0-48 21.5-48 48v245.8c0 26.5 21.5 48 48 48h89.7c102.2 0 132.7 24.4 147.3 75 .7 2.8 5.2 2.8 6 0 14.7-50.6 45.2-75 147.3-75H528c26.5 0 48-21.5 48-48V94.6c0-26.4-21.3-47.9-47.7-48.1zM242 311.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5V289c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V251zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H78.2c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm259.3 121.7c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.9c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5V228c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5v22.9zm0-60.9c0 1.9-1.5 3.5-3.5 3.5H337.5c-1.9 0-3.5-1.5-3.5-3.5v-22.8c0-1.9 1.5-3.5 3.5-3.5h160.4c1.9 0 3.5 1.5 3.5 3.5V190z\"],\n    \"rebel\": [512, 512, [], \"f1d0\", \"M256.5 504C117.2 504 9 387.8 13.2 249.9 16 170.7 56.4 97.7 129.7 49.5c.3 0 1.9-.6 1.1.8-5.8 5.5-111.3 129.8-14.1 226.4 49.8 49.5 90 2.5 90 2.5 38.5-50.1-.6-125.9-.6-125.9-10-24.9-45.7-40.1-45.7-40.1l28.8-31.8c24.4 10.5 43.2 38.7 43.2 38.7.8-29.6-21.9-61.4-21.9-61.4L255.1 8l44.3 50.1c-20.5 28.8-21.9 62.6-21.9 62.6 13.8-23 43.5-39.3 43.5-39.3l28.5 31.8c-27.4 8.9-45.4 39.9-45.4 39.9-15.8 28.5-27.1 89.4.6 127.3 32.4 44.6 87.7-2.8 87.7-2.8 102.7-91.9-10.5-225-10.5-225-6.1-5.5.8-2.8.8-2.8 50.1 36.5 114.6 84.4 116.2 204.8C500.9 400.2 399 504 256.5 504z\"],\n    \"red-river\": [448, 512, [], \"f3e3\", \"M353.2 32H94.8C42.4 32 0 74.4 0 126.8v258.4C0 437.6 42.4 480 94.8 480h258.4c52.4 0 94.8-42.4 94.8-94.8V126.8c0-52.4-42.4-94.8-94.8-94.8zM144.9 200.9v56.3c0 27-21.9 48.9-48.9 48.9V151.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9h-56.3c-12.3-.6-24.6 11.6-24 24zm176.3 72h-56.3c-12.3-.6-24.6 11.6-24 24v56.3c0 27-21.9 48.9-48.9 48.9V247.9c0-13.2 10.7-23.9 23.9-23.9h154.2c0 27-21.9 48.9-48.9 48.9z\"],\n    \"reddit\": [512, 512, [], \"f1a1\", \"M201.5 305.5c-13.8 0-24.9-11.1-24.9-24.6 0-13.8 11.1-24.9 24.9-24.9 13.6 0 24.6 11.1 24.6 24.9 0 13.6-11.1 24.6-24.6 24.6zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-132.3-41.2c-9.4 0-17.7 3.9-23.8 10-22.4-15.5-52.6-25.5-86.1-26.6l17.4-78.3 55.4 12.5c0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.3 24.9-24.9s-11.1-24.9-24.9-24.9c-9.7 0-18 5.8-22.1 13.8l-61.2-13.6c-3-.8-6.1 1.4-6.9 4.4l-19.1 86.4c-33.2 1.4-63.1 11.3-85.5 26.8-6.1-6.4-14.7-10.2-24.1-10.2-34.9 0-46.3 46.9-14.4 62.8-1.1 5-1.7 10.2-1.7 15.5 0 52.6 59.2 95.2 132 95.2 73.1 0 132.3-42.6 132.3-95.2 0-5.3-.6-10.8-1.9-15.8 31.3-16 19.8-62.5-14.9-62.5zM302.8 331c-18.2 18.2-76.1 17.9-93.6 0-2.2-2.2-6.1-2.2-8.3 0-2.5 2.5-2.5 6.4 0 8.6 22.8 22.8 87.3 22.8 110.2 0 2.5-2.2 2.5-6.1 0-8.6-2.2-2.2-6.1-2.2-8.3 0zm7.7-75c-13.6 0-24.6 11.1-24.6 24.9 0 13.6 11.1 24.6 24.6 24.6 13.8 0 24.9-11.1 24.9-24.6 0-13.8-11-24.9-24.9-24.9z\"],\n    \"reddit-alien\": [512, 512, [], \"f281\", \"M440.3 203.5c-15 0-28.2 6.2-37.9 15.9-35.7-24.7-83.8-40.6-137.1-42.3L293 52.3l88.2 19.8c0 21.6 17.6 39.2 39.2 39.2 22 0 39.7-18.1 39.7-39.7s-17.6-39.7-39.7-39.7c-15.4 0-28.7 9.3-35.3 22l-97.4-21.6c-4.9-1.3-9.7 2.2-11 7.1L246.3 177c-52.9 2.2-100.5 18.1-136.3 42.8-9.7-10.1-23.4-16.3-38.4-16.3-55.6 0-73.8 74.6-22.9 100.1-1.8 7.9-2.6 16.3-2.6 24.7 0 83.8 94.4 151.7 210.3 151.7 116.4 0 210.8-67.9 210.8-151.7 0-8.4-.9-17.2-3.1-25.1 49.9-25.6 31.5-99.7-23.8-99.7zM129.4 308.9c0-22 17.6-39.7 39.7-39.7 21.6 0 39.2 17.6 39.2 39.7 0 21.6-17.6 39.2-39.2 39.2-22 .1-39.7-17.6-39.7-39.2zm214.3 93.5c-36.4 36.4-139.1 36.4-175.5 0-4-3.5-4-9.7 0-13.7 3.5-3.5 9.7-3.5 13.2 0 27.8 28.5 120 29 149 0 3.5-3.5 9.7-3.5 13.2 0 4.1 4 4.1 10.2.1 13.7zm-.8-54.2c-21.6 0-39.2-17.6-39.2-39.2 0-22 17.6-39.7 39.2-39.7 22 0 39.7 17.6 39.7 39.7-.1 21.5-17.7 39.2-39.7 39.2z\"],\n    \"reddit-square\": [448, 512, [], \"f1a2\", \"M283.2 345.5c2.7 2.7 2.7 6.8 0 9.2-24.5 24.5-93.8 24.6-118.4 0-2.7-2.4-2.7-6.5 0-9.2 2.4-2.4 6.5-2.4 8.9 0 18.7 19.2 81 19.6 100.5 0 2.4-2.3 6.6-2.3 9 0zm-91.3-53.8c0-14.9-11.9-26.8-26.5-26.8-14.9 0-26.8 11.9-26.8 26.8 0 14.6 11.9 26.5 26.8 26.5 14.6 0 26.5-11.9 26.5-26.5zm90.7-26.8c-14.6 0-26.5 11.9-26.5 26.8 0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-11.9 26.8-26.5 0-14.9-11.9-26.8-26.8-26.8zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-99.7 140.6c-10.1 0-19 4.2-25.6 10.7-24.1-16.7-56.5-27.4-92.5-28.6l18.7-84.2 59.5 13.4c0 14.6 11.9 26.5 26.5 26.5 14.9 0 26.8-12.2 26.8-26.8 0-14.6-11.9-26.8-26.8-26.8-10.4 0-19.3 6.2-23.8 14.9l-65.7-14.6c-3.3-.9-6.5 1.5-7.4 4.8l-20.5 92.8c-35.7 1.5-67.8 12.2-91.9 28.9-6.5-6.8-15.8-11-25.9-11-37.5 0-49.8 50.4-15.5 67.5-1.2 5.4-1.8 11-1.8 16.7 0 56.5 63.7 102.3 141.9 102.3 78.5 0 142.2-45.8 142.2-102.3 0-5.7-.6-11.6-2.1-17 33.6-17.2 21.2-67.2-16.1-67.2z\"],\n    \"redhat\": [512, 512, [], \"f7bc\", \"M341.52 285.56c33.65 0 82.34-6.94 82.34-47 .22-6.74.86-1.82-20.88-96.24-4.62-19.15-8.68-27.84-42.31-44.65-26.09-13.34-82.92-35.37-99.73-35.37-15.66 0-20.2 20.17-38.87 20.17-18 0-31.31-15.06-48.12-15.06-16.14 0-26.66 11-34.78 33.62-27.5 77.55-26.28 74.27-26.12 78.27 0 24.8 97.64 106.11 228.47 106.11M429 254.84c4.65 22 4.65 24.35 4.65 27.25 0 37.66-42.33 58.56-98 58.56-125.74.08-235.91-73.65-235.91-122.33a49.55 49.55 0 0 1 4.06-19.72C58.56 200.86 0 208.93 0 260.63c0 84.67 200.63 189 359.49 189 121.79 0 152.51-55.08 152.51-98.58 0-34.21-29.59-73.05-82.93-96.24\"],\n    \"renren\": [512, 512, [], \"f18b\", \"M214 169.1c0 110.4-61 205.4-147.6 247.4C30 373.2 8 317.7 8 256.6 8 133.9 97.1 32.2 214 12.5v156.6zM255 504c-42.9 0-83.3-11-118.5-30.4C193.7 437.5 239.9 382.9 255 319c15.5 63.9 61.7 118.5 118.8 154.7C338.7 493 298.3 504 255 504zm190.6-87.5C359 374.5 298 279.6 298 169.1V12.5c116.9 19.7 206 121.4 206 244.1 0 61.1-22 116.6-58.4 159.9z\"],\n    \"replyd\": [448, 512, [], \"f3e6\", \"M320 480H128C57.6 480 0 422.4 0 352V160C0 89.6 57.6 32 128 32h192c70.4 0 128 57.6 128 128v192c0 70.4-57.6 128-128 128zM193.4 273.2c-6.1-2-11.6-3.1-16.4-3.1-7.2 0-13.5 1.9-18.9 5.6-5.4 3.7-9.6 9-12.8 15.8h-1.1l-4.2-18.3h-28v138.9h36.1v-89.7c1.5-5.4 4.4-9.8 8.7-13.2 4.3-3.4 9.8-5.1 16.2-5.1 4.6 0 9.8 1 15.6 3.1l4.8-34zm115.2 103.4c-3.2 2.4-7.7 4.8-13.7 7.1-6 2.3-12.8 3.5-20.4 3.5-12.2 0-21.1-3-26.5-8.9-5.5-5.9-8.5-14.7-9-26.4h83.3c.9-4.8 1.6-9.4 2.1-13.9.5-4.4.7-8.6.7-12.5 0-10.7-1.6-19.7-4.7-26.9-3.2-7.2-7.3-13-12.5-17.2-5.2-4.3-11.1-7.3-17.8-9.2-6.7-1.8-13.5-2.8-20.6-2.8-21.1 0-37.5 6.1-49.2 18.3s-17.5 30.5-17.5 55c0 22.8 5.2 40.7 15.6 53.7 10.4 13.1 26.8 19.6 49.2 19.6 10.7 0 20.9-1.5 30.4-4.6 9.5-3.1 17.1-6.8 22.6-11.2l-12-23.6zm-21.8-70.3c3.8 5.4 5.3 13.1 4.6 23.1h-51.7c.9-9.4 3.7-17 8.2-22.6 4.5-5.6 11.5-8.5 21-8.5 8.2-.1 14.1 2.6 17.9 8zm79.9 2.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4s2 11.7 6.1 15.6zm0 100.5c4.1 3.9 9.4 5.8 16.1 5.8 7 0 12.6-1.9 16.7-5.8s6.1-9.1 6.1-15.6-2-11.6-6.1-15.4c-4.1-3.8-9.6-5.7-16.7-5.7-6.7 0-12 1.9-16.1 5.7-4.1 3.8-6.1 8.9-6.1 15.4 0 6.6 2 11.7 6.1 15.6z\"],\n    \"researchgate\": [448, 512, [], \"f4f8\", \"M0 32v448h448V32H0zm262.2 334.4c-6.6 3-33.2 6-50-14.2-9.2-10.6-25.3-33.3-42.2-63.6-8.9 0-14.7 0-21.4-.6v46.4c0 23.5 6 21.2 25.8 23.9v8.1c-6.9-.3-23.1-.8-35.6-.8-13.1 0-26.1.6-33.6.8v-8.1c15.5-2.9 22-1.3 22-23.9V225c0-22.6-6.4-21-22-23.9V193c25.8 1 53.1-.6 70.9-.6 31.7 0 55.9 14.4 55.9 45.6 0 21.1-16.7 42.2-39.2 47.5 13.6 24.2 30 45.6 42.2 58.9 7.2 7.8 17.2 14.7 27.2 14.7v7.3zm22.9-135c-23.3 0-32.2-15.7-32.2-32.2V167c0-12.2 8.8-30.4 34-30.4s30.4 17.9 30.4 17.9l-10.7 7.2s-5.5-12.5-19.7-12.5c-7.9 0-19.7 7.3-19.7 19.7v26.8c0 13.4 6.6 23.3 17.9 23.3 14.1 0 21.5-10.9 21.5-26.8h-17.9v-10.7h30.4c0 20.5 4.7 49.9-34 49.9zm-116.5 44.7c-9.4 0-13.6-.3-20-.8v-69.7c6.4-.6 15-.6 22.5-.6 23.3 0 37.2 12.2 37.2 34.5 0 21.9-15 36.6-39.7 36.6z\"],\n    \"resolving\": [496, 512, [], \"f3e7\", \"M281.2 278.2c46-13.3 49.6-23.5 44-43.4L314 195.5c-6.1-20.9-18.4-28.1-71.1-12.8L54.7 236.8l28.6 98.6 197.9-57.2zM248.5 8C131.4 8 33.2 88.7 7.2 197.5l221.9-63.9c34.8-10.2 54.2-11.7 79.3-8.2 36.3 6.1 52.7 25 61.4 55.2l10.7 37.8c8.2 28.1 1 50.6-23.5 73.6-19.4 17.4-31.2 24.5-61.4 33.2L203 351.8l220.4 27.1 9.7 34.2-48.1 13.3-286.8-37.3 23 80.2c36.8 22 80.3 34.7 126.3 34.7 137 0 248.5-111.4 248.5-248.3C497 119.4 385.5 8 248.5 8zM38.3 388.6L0 256.8c0 48.5 14.3 93.4 38.3 131.8z\"],\n    \"rev\": [448, 512, [], \"f5b2\", \"M289.67 274.89a65.57 65.57 0 1 1-65.56-65.56 65.64 65.64 0 0 1 65.56 65.56zm139.55-5.05h-.13a204.69 204.69 0 0 0-74.32-153l-45.38 26.2a157.07 157.07 0 0 1 71.81 131.84C381.2 361.5 310.73 432 224.11 432S67 361.5 67 274.88c0-81.88 63-149.27 143-156.43v39.12l108.77-62.79L210 32v38.32c-106.7 7.25-191 96-191 204.57 0 111.59 89.12 202.29 200.06 205v.11h210.16V269.84z\"],\n    \"rocketchat\": [576, 512, [], \"f3e8\", \"M486.41 107.57c-76.93-50.83-179.18-62.4-264.12-47.07C127.26-31.16 20.77 11 0 23.12c0 0 73.08 62.1 61.21 116.49-86.52 88.2-45.39 186.4 0 232.77C73.08 426.77 0 488.87 0 488.87c20.57 12.16 126.77 54.19 222.29-37 84.75 15.23 187 3.76 264.12-47.16 119.26-76.14 119.65-220.61 0-297.15zM294.18 404.22a339.53 339.53 0 0 1-88.11-11.37l-19.77 19.09a179.74 179.74 0 0 1-36.59 27.39A143.14 143.14 0 0 1 98 454.06c1-1.78 1.88-3.56 2.77-5.24q29.67-55 16-98.69c-32.53-25.61-52-58.34-52-94.13 0-82 102.74-148.43 229.41-148.43S523.59 174 523.59 256 420.85 404.22 294.18 404.22zM184.12 291.3a34.32 34.32 0 0 1-34.8-33.72c-.7-45.39 67.83-46.38 68.52-1.09v.51a34 34 0 0 1-33.72 34.32zm73.77-33.72c-.79-45.39 67.74-46.48 68.53-1.19v.61c.39 45.08-67.74 45.57-68.53.58zm143.38 33.72a34.33 34.33 0 0 1-34.81-33.72c-.69-45.39 67.84-46.38 68.53-1.09v.51a33.89 33.89 0 0 1-33.72 34.32z\"],\n    \"rockrms\": [496, 512, [], \"f3e9\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm157.4 419.5h-90l-112-131.3c-17.9-20.4-3.9-56.1 26.6-56.1h75.3l-84.6-99.3-84.3 98.9h-90L193.5 67.2c14.4-18.4 41.3-17.3 54.5 0l157.7 185.1c19 22.8 2 57.2-27.6 56.1-.6 0-74.2.2-74.2.2l101.5 118.9z\"],\n    \"safari\": [512, 512, [], \"f267\", \"M236.9 256.8c0-9.1 6.6-17.7 16.3-17.7 8.9 0 17.4 6.4 17.4 16.1 0 9.1-6.4 17.7-16.1 17.7-9 0-17.6-6.7-17.6-16.1zM504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-26.6 0c0-122.3-99.1-221.4-221.4-221.4S34.6 133.7 34.6 256 133.7 477.4 256 477.4 477.4 378.3 477.4 256zm-72.5 96.6c0 3.6 13 10.2 16.3 12.2-27.4 41.5-69.8 71.4-117.9 83.3l-4.4-18.5c-.3-2.5-1.9-2.8-4.2-2.8-1.9 0-3 2.8-2.8 4.2l4.4 18.8c-13.3 2.8-26.8 4.2-40.4 4.2-36.3 0-72-10.2-103-29.1 1.7-2.8 12.2-18 12.2-20.2 0-1.9-1.7-3.6-3.6-3.6-3.9 0-12.2 16.6-14.7 19.9-41.8-27.7-72-70.6-83.6-119.6l19.1-4.2c2.2-.6 2.8-2.2 2.8-4.2 0-1.9-2.8-3-4.4-2.8L62 294.5c-2.5-12.7-3.9-25.5-3.9-38.5 0-37.1 10.5-73.6 30.2-104.9 2.8 1.7 16.1 10.8 18.3 10.8 1.9 0 3.6-1.4 3.6-3.3 0-3.9-14.7-11.3-18-13.6 28.2-41.2 71.1-70.9 119.8-81.9l4.2 18.5c.6 2.2 2.2 2.8 4.2 2.8s3-2.8 2.8-4.4L219 61.7c12.2-2.2 24.6-3.6 37.1-3.6 37.1 0 73.3 10.5 104.9 30.2-1.9 2.8-10.8 15.8-10.8 18 0 1.9 1.4 3.6 3.3 3.6 3.9 0 11.3-14.4 13.3-17.7 41 27.7 70.3 70 81.7 118.2l-15.5 3.3c-2.5.6-2.8 2.2-2.8 4.4 0 1.9 2.8 3 4.2 2.8l15.8-3.6c2.5 12.7 3.9 25.7 3.9 38.7 0 36.3-10 72-28.8 102.7-2.8-1.4-14.4-9.7-16.6-9.7-2.1 0-3.8 1.7-3.8 3.6zm-33.2-242.2c-13 12.2-134.2 123.7-137.6 129.5l-96.6 160.5c12.7-11.9 134.2-124 137.3-129.3l96.9-160.7z\"],\n    \"salesforce\": [640, 512, [], \"f83b\", \"M248.89 245.64h-26.35c.69-5.16 3.32-14.12 13.64-14.12 6.75 0 11.97 3.82 12.71 14.12zm136.66-13.88c-.47 0-14.11-1.77-14.11 20s13.63 20 14.11 20c13 0 14.11-13.54 14.11-20 0-21.76-13.66-20-14.11-20zm-243.22 23.76a8.63 8.63 0 0 0-3.29 7.29c0 4.78 2.08 6.05 3.29 7.05 4.7 3.7 15.07 2.12 20.93.95v-16.94c-5.32-1.07-16.73-1.96-20.93 1.65zM640 232c0 87.58-80 154.39-165.36 136.43-18.37 33-70.73 70.75-132.2 41.63-41.16 96.05-177.89 92.18-213.81-5.17C8.91 428.78-50.19 266.52 53.36 205.61 18.61 126.18 76 32 167.67 32a124.24 124.24 0 0 1 98.56 48.7c20.7-21.4 49.4-34.81 81.15-34.81 42.34 0 79 23.52 98.8 58.57C539 63.78 640 132.69 640 232zm-519.55 31.8c0-11.76-11.69-15.17-17.87-17.17-5.27-2.11-13.41-3.51-13.41-8.94 0-9.46 17-6.66 25.17-2.12 0 0 1.17.71 1.64-.47.24-.7 2.36-6.58 2.59-7.29a1.13 1.13 0 0 0-.7-1.41c-12.33-7.63-40.7-8.51-40.7 12.7 0 12.46 11.49 15.44 17.88 17.17 4.72 1.58 13.17 3 13.17 8.7 0 4-3.53 7.06-9.17 7.06a31.76 31.76 0 0 1-19-6.35c-.47-.23-1.42-.71-1.65.71l-2.4 7.47c-.47.94.23 1.18.23 1.41 1.75 1.4 10.3 6.59 22.82 6.59 13.17 0 21.4-7.06 21.4-18.11zm32-42.58c-10.13 0-18.66 3.17-21.4 5.18a1 1 0 0 0-.24 1.41l2.59 7.06a1 1 0 0 0 1.18.7c.65 0 6.8-4 16.93-4 4 0 7.06.71 9.18 2.36 3.6 2.8 3.06 8.29 3.06 10.58-4.79-.3-19.11-3.44-29.41 3.76a16.92 16.92 0 0 0-7.34 14.54c0 5.9 1.51 10.4 6.59 14.35 12.24 8.16 36.28 2 38.1 1.41 1.58-.32 3.53-.66 3.53-1.88v-33.88c.04-4.61.32-21.64-22.78-21.64zM199 200.24a1.11 1.11 0 0 0-1.18-1.18H188a1.11 1.11 0 0 0-1.17 1.18v79a1.11 1.11 0 0 0 1.17 1.18h9.88a1.11 1.11 0 0 0 1.18-1.18zm55.75 28.93c-2.1-2.31-6.79-7.53-17.65-7.53-3.51 0-14.16.23-20.7 8.94-6.35 7.63-6.58 18.11-6.58 21.41 0 3.12.15 14.26 7.06 21.17 2.64 2.91 9.06 8.23 22.81 8.23 10.82 0 16.47-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.35-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.94-16.7h37.17a1.23 1.23 0 0 0 1.17-.94c-.29 0 2.07-14.7-6.09-24.23zm36.69 52.69c13.17 0 21.41-7.06 21.41-18.11 0-11.76-11.7-15.17-17.88-17.17-4.14-1.66-13.41-3.38-13.41-8.94 0-3.76 3.29-6.35 8.47-6.35a38.11 38.11 0 0 1 16.7 4.23s1.18.71 1.65-.47c.23-.7 2.35-6.58 2.58-7.29a1.13 1.13 0 0 0-.7-1.41c-7.91-4.9-16.74-4.94-20.23-4.94-12 0-20.46 7.29-20.46 17.64 0 12.46 11.48 15.44 17.87 17.17 6.11 2 13.17 3.26 13.17 8.7 0 4-3.52 7.06-9.17 7.06a31.8 31.8 0 0 1-19-6.35 1 1 0 0 0-1.65.71l-2.35 7.52c-.47.94.23 1.18.23 1.41 1.72 1.4 10.33 6.59 22.79 6.59zM357.09 224c0-.71-.24-1.18-1.18-1.18h-11.76c0-.14.94-8.94 4.47-12.47 4.16-4.15 11.76-1.64 12-1.64 1.17.47 1.41 0 1.64-.47l2.83-7.77c.7-.94 0-1.17-.24-1.41-5.09-2-17.35-2.87-24.46 4.24-5.48 5.48-7 13.92-8 19.52h-8.47a1.28 1.28 0 0 0-1.17 1.18l-1.42 7.76c0 .7.24 1.17 1.18 1.17h8.23c-8.51 47.9-8.75 50.21-10.35 55.52-1.08 3.62-3.29 6.9-5.88 7.76-.09 0-3.88 1.68-9.64-.24 0 0-.94-.47-1.41.71-.24.71-2.59 6.82-2.83 7.53s0 1.41.47 1.41c5.11 2 13 1.77 17.88 0 6.28-2.28 9.72-7.89 11.53-12.94 2.75-7.71 2.81-9.79 11.76-59.74h12.23a1.29 1.29 0 0 0 1.18-1.18zm53.39 16c-.56-1.68-5.1-18.11-25.17-18.11-15.25 0-23 10-25.16 18.11-1 3-3.18 14 0 23.52.09.3 4.41 18.12 25.16 18.12 14.95 0 22.9-9.61 25.17-18.12 3.21-9.61 1.01-20.52 0-23.52zm45.4-16.7c-5-1.65-16.62-1.9-22.11 5.41v-4.47a1.11 1.11 0 0 0-1.18-1.17h-9.4a1.11 1.11 0 0 0-1.18 1.17v55.28a1.12 1.12 0 0 0 1.18 1.18h9.64a1.12 1.12 0 0 0 1.18-1.18v-27.77c0-2.91.05-11.37 4.46-15.05 4.9-4.9 12-3.36 13.41-3.06a1.57 1.57 0 0 0 1.41-.94 74 74 0 0 0 3.06-8 1.16 1.16 0 0 0-.47-1.41zm46.81 54.1l-2.12-7.29c-.47-1.18-1.41-.71-1.41-.71-4.23 1.82-10.15 1.89-11.29 1.89-4.64 0-17.17-1.13-17.17-19.76 0-6.23 1.85-19.76 16.47-19.76a34.85 34.85 0 0 1 11.52 1.65s.94.47 1.18-.71c.94-2.59 1.64-4.47 2.59-7.53.23-.94-.47-1.17-.71-1.17-11.59-3.87-22.34-2.53-27.76 0-1.59.74-16.23 6.49-16.23 27.52 0 2.9-.58 30.11 28.94 30.11a44.45 44.45 0 0 0 15.52-2.83 1.3 1.3 0 0 0 .47-1.42zm53.87-39.52c-.8-3-5.37-16.23-22.35-16.23-16 0-23.52 10.11-25.64 18.59a38.58 38.58 0 0 0-1.65 11.76c0 25.87 18.84 29.4 29.88 29.4 10.82 0 16.46-2.35 18.58-3.76.47-.24.71-.71.24-1.88l-2.36-6.83a1.26 1.26 0 0 0-1.41-.7c-2.59.94-6.35 2.82-15.29 2.82-17.42 0-16.85-14.74-16.93-16.7h37.16a1.25 1.25 0 0 0 1.18-.94c-.24-.01.94-7.07-1.41-15.54zm-23.29-6.35c-10.33 0-13 9-13.64 14.12H546c-.88-11.92-7.62-14.13-12.73-14.13z\"],\n    \"sass\": [640, 512, [], \"f41e\", \"M301.84 378.92c-.3.6-.6 1.08 0 0zm249.13-87a131.16 131.16 0 0 0-58 13.5c-5.9-11.9-12-22.3-13-30.1-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.3-6.7-24 2.5-25.29 5.9a122.83 122.83 0 0 0-5.3 19.1c-2.3 11.7-25.79 53.5-39.09 75.3-4.4-8.5-8.1-16-8.9-22-1.2-9.1-2.5-14.5-1.1-25.3s7.7-26.1 7.6-27.2-1.4-6.6-14.29-6.7-24 2.5-25.3 5.9-2.7 11.4-5.3 19.1-33.89 77.3-42.08 95.4c-4.2 9.2-7.8 16.6-10.4 21.6-.4.8-.7 1.3-.9 1.7.3-.5.5-1 .5-.8-2.2 4.3-3.5 6.7-3.5 6.7v.1c-1.7 3.2-3.6 6.1-4.5 6.1-.6 0-1.9-8.4.3-19.9 4.7-24.2 15.8-61.8 15.7-63.1-.1-.7 2.1-7.2-7.3-10.7-9.1-3.3-12.4 2.2-13.2 2.2s-1.4 2-1.4 2 10.1-42.4-19.39-42.4c-18.4 0-44 20.2-56.58 38.5-7.9 4.3-25 13.6-43 23.5-6.9 3.8-14 7.7-20.7 11.4-.5-.5-.9-1-1.4-1.5-35.79-38.2-101.87-65.2-99.07-116.5 1-18.7 7.5-67.8 127.07-127.4 98-48.8 176.35-35.4 189.84-5.6 19.4 42.5-41.89 121.6-143.66 133-38.79 4.3-59.18-10.7-64.28-16.3-5.3-5.9-6.1-6.2-8.1-5.1-3.3 1.8-1.2 7 0 10.1 3 7.9 15.5 21.9 36.79 28.9 18.7 6.1 64.18 9.5 119.17-11.8 61.78-23.8 109.87-90.1 95.77-145.6C386.52 18.32 293-.18 204.57 31.22c-52.69 18.7-109.67 48.1-150.66 86.4-48.69 45.6-56.48 85.3-53.28 101.9 11.39 58.9 92.57 97.3 125.06 125.7-1.6.9-3.1 1.7-4.5 2.5-16.29 8.1-78.18 40.5-93.67 74.7-17.5 38.8 2.9 66.6 16.29 70.4 41.79 11.6 84.58-9.3 107.57-43.6s20.2-79.1 9.6-99.5c-.1-.3-.3-.5-.4-.8 4.2-2.5 8.5-5 12.8-7.5 8.29-4.9 16.39-9.4 23.49-13.3-4 10.8-6.9 23.8-8.4 42.6-1.8 22 7.3 50.5 19.1 61.7 5.2 4.9 11.49 5 15.39 5 13.8 0 20-11.4 26.89-25 8.5-16.6 16-35.9 16-35.9s-9.4 52.2 16.3 52.2c9.39 0 18.79-12.1 23-18.3v.1s.2-.4.7-1.2c1-1.5 1.5-2.4 1.5-2.4v-.3c3.8-6.5 12.1-21.4 24.59-46 16.2-31.8 31.69-71.5 31.69-71.5a201.24 201.24 0 0 0 6.2 25.8c2.8 9.5 8.7 19.9 13.4 30-3.8 5.2-6.1 8.2-6.1 8.2a.31.31 0 0 0 .1.2c-3 4-6.4 8.3-9.9 12.5-12.79 15.2-28 32.6-30 37.6-2.4 5.9-1.8 10.3 2.8 13.7 3.4 2.6 9.4 3 15.69 2.5 11.5-.8 19.6-3.6 23.5-5.4a82.2 82.2 0 0 0 20.19-10.6c12.5-9.2 20.1-22.4 19.4-39.8-.4-9.6-3.5-19.2-7.3-28.2 1.1-1.6 2.3-3.3 3.4-5C434.8 301.72 450.1 270 450.1 270a201.24 201.24 0 0 0 6.2 25.8c2.4 8.1 7.09 17 11.39 25.7-18.59 15.1-30.09 32.6-34.09 44.1-7.4 21.3-1.6 30.9 9.3 33.1 4.9 1 11.9-1.3 17.1-3.5a79.46 79.46 0 0 0 21.59-11.1c12.5-9.2 24.59-22.1 23.79-39.6-.3-7.9-2.5-15.8-5.4-23.4 15.7-6.6 36.09-10.2 62.09-7.2 55.68 6.5 66.58 41.3 64.48 55.8s-13.8 22.6-17.7 25-5.1 3.3-4.8 5.1c.5 2.6 2.3 2.5 5.6 1.9 4.6-.8 29.19-11.8 30.29-38.7 1.6-34-31.09-71.4-89-71.1zm-429.18 144.7c-18.39 20.1-44.19 27.7-55.28 21.3C54.61 451 59.31 421.42 82 400c13.8-13 31.59-25 43.39-32.4 2.7-1.6 6.6-4 11.4-6.9.8-.5 1.2-.7 1.2-.7.9-.6 1.9-1.1 2.9-1.7 8.29 30.4.3 57.2-19.1 78.3zm134.36-91.4c-6.4 15.7-19.89 55.7-28.09 53.6-7-1.8-11.3-32.3-1.4-62.3 5-15.1 15.6-33.1 21.9-40.1 10.09-11.3 21.19-14.9 23.79-10.4 3.5 5.9-12.2 49.4-16.2 59.2zm111 53c-2.7 1.4-5.2 2.3-6.4 1.6-.9-.5 1.1-2.4 1.1-2.4s13.9-14.9 19.4-21.7c3.2-4 6.9-8.7 10.89-13.9 0 .5.1 1 .1 1.6-.13 17.9-17.32 30-25.12 34.8zm85.58-19.5c-2-1.4-1.7-6.1 5-20.7 2.6-5.7 8.59-15.3 19-24.5a36.18 36.18 0 0 1 1.9 10.8c-.1 22.5-16.2 30.9-25.89 34.4z\"],\n    \"schlix\": [448, 512, [], \"f3ea\", \"M350.5 157.7l-54.2-46.1 73.4-39 78.3 44.2-97.5 40.9zM192 122.1l45.7-28.2 34.7 34.6-55.4 29-25-35.4zm-65.1 6.6l31.9-22.1L176 135l-36.7 22.5-12.4-28.8zm-23.3 88.2l-8.8-34.8 29.6-18.3 13.1 35.3-33.9 17.8zm-21.2-83.7l23.9-18.1 8.9 24-26.7 18.3-6.1-24.2zM59 206.5l-3.6-28.4 22.3-15.5 6.1 28.7L59 206.5zm-30.6 16.6l20.8-12.8 3.3 33.4-22.9 12-1.2-32.6zM1.4 268l19.2-10.2.4 38.2-21 8.8L1.4 268zm59.1 59.3l-28.3 8.3-1.6-46.8 25.1-10.7 4.8 49.2zM99 263.2l-31.1 13-5.2-40.8L90.1 221l8.9 42.2zM123.2 377l-41.6 5.9-8.1-63.5 35.2-10.8 14.5 68.4zm28.5-139.9l21.2 57.1-46.2 13.6-13.7-54.1 38.7-16.6zm85.7 230.5l-70.9-3.3-24.3-95.8 55.2-8.6 40 107.7zm-84.9-279.7l42.2-22.4 28 45.9-50.8 21.3-19.4-44.8zm41 94.9l61.3-18.7 52.8 86.6-79.8 11.3-34.3-79.2zm51.4-85.6l67.3-28.8 65.5 65.4-88.6 26.2-44.2-62.8z\"],\n    \"scribd\": [384, 512, [], \"f28a\", \"M42.3 252.7c-16.1-19-24.7-45.9-24.8-79.9 0-100.4 75.2-153.1 167.2-153.1 98.6-1.6 156.8 49 184.3 70.6l-50.5 72.1-37.3-24.6 26.9-38.6c-36.5-24-79.4-36.5-123-35.8-50.7-.8-111.7 27.2-111.7 76.2 0 18.7 11.2 20.7 28.6 15.6 23.3-5.3 41.9.6 55.8 14 26.4 24.3 23.2 67.6-.7 91.9-29.2 29.5-85.2 27.3-114.8-8.4zm317.7 5.9c-15.5-18.8-38.9-29.4-63.2-28.6-38.1-2-71.1 28-70.5 67.2-.7 16.8 6 33 18.4 44.3 14.1 13.9 33 19.7 56.3 14.4 17.4-5.1 28.6-3.1 28.6 15.6 0 4.3-.5 8.5-1.4 12.7-16.7 40.9-59.5 64.4-121.4 64.4-51.9.2-102.4-16.4-144.1-47.3l33.7-39.4-35.6-27.4L0 406.3l15.4 13.8c52.5 46.8 120.4 72.5 190.7 72.2 51.4 0 94.4-10.5 133.6-44.1 57.1-51.4 54.2-149.2 20.3-189.6z\"],\n    \"searchengin\": [460, 512, [], \"f3eb\", \"M220.6 130.3l-67.2 28.2V43.2L98.7 233.5l54.7-24.2v130.3l67.2-209.3zm-83.2-96.7l-1.3 4.7-15.2 52.9C80.6 106.7 52 145.8 52 191.5c0 52.3 34.3 95.9 83.4 105.5v53.6C57.5 340.1 0 272.4 0 191.6c0-80.5 59.8-147.2 137.4-158zm311.4 447.2c-11.2 11.2-23.1 12.3-28.6 10.5-5.4-1.8-27.1-19.9-60.4-44.4-33.3-24.6-33.6-35.7-43-56.7-9.4-20.9-30.4-42.6-57.5-52.4l-9.7-14.7c-24.7 16.9-53 26.9-81.3 28.7l2.1-6.6 15.9-49.5c46.5-11.9 80.9-54 80.9-104.2 0-54.5-38.4-102.1-96-107.1V32.3C254.4 37.4 320 106.8 320 191.6c0 33.6-11.2 64.7-29 90.4l14.6 9.6c9.8 27.1 31.5 48 52.4 57.4s32.2 9.7 56.8 43c24.6 33.2 42.7 54.9 44.5 60.3s.7 17.3-10.5 28.5zm-9.9-17.9c0-4.4-3.6-8-8-8s-8 3.6-8 8 3.6 8 8 8 8-3.6 8-8z\"],\n    \"sellcast\": [448, 512, [], \"f2da\", \"M353.4 32H94.7C42.6 32 0 74.6 0 126.6v258.7C0 437.4 42.6 480 94.7 480h258.7c52.1 0 94.7-42.6 94.7-94.6V126.6c0-52-42.6-94.6-94.7-94.6zm-50 316.4c-27.9 48.2-89.9 64.9-138.2 37.2-22.9 39.8-54.9 8.6-42.3-13.2l15.7-27.2c5.9-10.3 19.2-13.9 29.5-7.9 18.6 10.8-.1-.1 18.5 10.7 27.6 15.9 63.4 6.3 79.4-21.3 15.9-27.6 6.3-63.4-21.3-79.4-17.8-10.2-.6-.4-18.6-10.6-24.6-14.2-3.4-51.9 21.6-37.5 18.6 10.8-.1-.1 18.5 10.7 48.4 28 65.1 90.3 37.2 138.5zm21.8-208.8c-17 29.5-16.3 28.8-19 31.5-6.5 6.5-16.3 8.7-26.5 3.6-18.6-10.8.1.1-18.5-10.7-27.6-15.9-63.4-6.3-79.4 21.3s-6.3 63.4 21.3 79.4c0 0 18.5 10.6 18.6 10.6 24.6 14.2 3.4 51.9-21.6 37.5-18.6-10.8.1.1-18.5-10.7-48.2-27.8-64.9-90.1-37.1-138.4 27.9-48.2 89.9-64.9 138.2-37.2l4.8-8.4c14.3-24.9 52-3.3 37.7 21.5z\"],\n    \"sellsy\": [640, 512, [], \"f213\", \"M539.71 237.308c3.064-12.257 4.29-24.821 4.29-37.384C544 107.382 468.618 32 376.076 32c-77.22 0-144.634 53.012-163.02 127.781-15.322-13.176-34.934-20.53-55.157-20.53-46.271 0-83.962 37.69-83.962 83.961 0 7.354.92 15.015 3.065 22.369-42.9 20.225-70.785 63.738-70.785 111.234C6.216 424.843 61.68 480 129.401 480h381.198c67.72 0 123.184-55.157 123.184-123.184.001-56.384-38.916-106.025-94.073-119.508zM199.88 401.554c0 8.274-7.048 15.321-15.321 15.321H153.61c-8.274 0-15.321-7.048-15.321-15.321V290.626c0-8.273 7.048-15.321 15.321-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v110.928zm89.477 0c0 8.274-7.048 15.321-15.322 15.321h-30.949c-8.274 0-15.321-7.048-15.321-15.321V270.096c0-8.274 7.048-15.321 15.321-15.321h30.949c8.274 0 15.322 7.048 15.322 15.321v131.458zm89.477 0c0 8.274-7.047 15.321-15.321 15.321h-30.949c-8.274 0-15.322-7.048-15.322-15.321V238.84c0-8.274 7.048-15.321 15.322-15.321h30.949c8.274 0 15.321 7.048 15.321 15.321v162.714zm87.027 0c0 8.274-7.048 15.321-15.322 15.321h-28.497c-8.274 0-15.321-7.048-15.321-15.321V176.941c0-8.579 7.047-15.628 15.321-15.628h28.497c8.274 0 15.322 7.048 15.322 15.628v224.613z\"],\n    \"servicestack\": [496, 512, [], \"f3ec\", \"M88 216c81.7 10.2 273.7 102.3 304 232H0c99.5-8.1 184.5-137 88-232zm32-152c32.3 35.6 47.7 83.9 46.4 133.6C249.3 231.3 373.7 321.3 400 448h96C455.3 231.9 222.8 79.5 120 64z\"],\n    \"shirtsinbulk\": [448, 512, [], \"f214\", \"M100 410.3l30.6 13.4 4.4-9.9-30.6-13.4zm39.4 17.5l30.6 13.4 4.4-9.9-30.6-13.4zm172.1-14l4.4 9.9 30.6-13.4-4.4-9.9zM179.1 445l30.3 13.7 4.4-9.9-30.3-13.4zM60.4 392.8L91 406.2l4.4-9.6-30.6-13.7zm211.4 38.5l4.4 9.9 30.6-13.4-4.4-9.9zm-39.3 17.5l4.4 9.9 30.6-13.7-4.4-9.6zm118.4-52.2l4.4 9.6 30.6-13.4-4.4-9.9zM170 46.6h-33.5v10.5H170zm-47.2 0H89.2v10.5h33.5zm-47.3 0H42.3v10.5h33.3zm141.5 0h-33.2v10.5H217zm94.5 0H278v10.5h33.5zm47.3 0h-33.5v10.5h33.5zm-94.6 0H231v10.5h33.2zm141.5 0h-33.3v10.5h33.3zM52.8 351.1H42v33.5h10.8zm70-215.9H89.2v10.5h33.5zm-70 10.6h22.8v-10.5H42v33.5h10.8zm168.9 228.6c50.5 0 91.3-40.8 91.3-91.3 0-50.2-40.8-91.3-91.3-91.3-50.2 0-91.3 41.1-91.3 91.3 0 50.5 41.1 91.3 91.3 91.3zm-48.2-111.1c0-25.4 29.5-31.8 49.6-31.8 16.9 0 29.2 5.8 44.3 12l-8.8 16.9h-.9c-6.4-9.9-24.8-13.1-35.6-13.1-9 0-29.8 1.8-29.8 14.9 0 21.6 78.5-10.2 78.5 37.9 0 25.4-31.5 31.2-51 31.2-18.1 0-32.4-2.9-47.2-12.2l9-18.4h.9c6.1 12.2 23.6 14.9 35.9 14.9 8.7 0 32.7-1.2 32.7-14.3 0-26.1-77.6 6.3-77.6-38zM52.8 178.4H42V212h10.8zm342.4 206.2H406v-33.5h-10.8zM52.8 307.9H42v33.5h10.8zM0 3.7v406l221.7 98.6L448 409.7V3.7zm418.8 387.1L222 476.5 29.2 390.8V120.7h389.7v270.1zm0-299.3H29.2V32.9h389.7v58.6zm-366 130.1H42v33.5h10.8zm0 43.2H42v33.5h10.8zM170 135.2h-33.5v10.5H170zm225.2 163.1H406v-33.5h-10.8zm0-43.2H406v-33.5h-10.8zM217 135.2h-33.2v10.5H217zM395.2 212H406v-33.5h-10.8zm0 129.5H406V308h-10.8zm-131-206.3H231v10.5h33.2zm47.3 0H278v10.5h33.5zm83.7 33.6H406v-33.5h-33.5v10.5h22.8zm-36.4-33.6h-33.5v10.5h33.5z\"],\n    \"shopware\": [512, 512, [], \"f5b5\", \"M403.5 455.41A246.17 246.17 0 0 1 256 504C118.81 504 8 393 8 256 8 118.81 119 8 256 8a247.39 247.39 0 0 1 165.7 63.5 3.57 3.57 0 0 1-2.86 6.18A418.62 418.62 0 0 0 362.13 74c-129.36 0-222.4 53.47-222.4 155.35 0 109 92.13 145.88 176.83 178.73 33.64 13 65.4 25.36 87 41.59a3.58 3.58 0 0 1 0 5.72zM503 233.09a3.64 3.64 0 0 0-1.27-2.44c-51.76-43-93.62-60.48-144.48-60.48-84.13 0-80.25 52.17-80.25 53.63 0 42.6 52.06 62 112.34 84.49 31.07 11.59 63.19 23.57 92.68 39.93a3.57 3.57 0 0 0 5-1.82A249 249 0 0 0 503 233.09z\"],\n    \"simplybuilt\": [512, 512, [], \"f215\", \"M481.2 64h-106c-14.5 0-26.6 11.8-26.6 26.3v39.6H163.3V90.3c0-14.5-12-26.3-26.6-26.3h-106C16.1 64 4.3 75.8 4.3 90.3v331.4c0 14.5 11.8 26.3 26.6 26.3h450.4c14.8 0 26.6-11.8 26.6-26.3V90.3c-.2-14.5-12-26.3-26.7-26.3zM149.8 355.8c-36.6 0-66.4-29.7-66.4-66.4 0-36.9 29.7-66.6 66.4-66.6 36.9 0 66.6 29.7 66.6 66.6 0 36.7-29.7 66.4-66.6 66.4zm212.4 0c-36.9 0-66.6-29.7-66.6-66.6 0-36.6 29.7-66.4 66.6-66.4 36.6 0 66.4 29.7 66.4 66.4 0 36.9-29.8 66.6-66.4 66.6z\"],\n    \"sistrix\": [448, 512, [], \"f3ee\", \"M448 449L301.2 300.2c20-27.9 31.9-62.2 31.9-99.2 0-93.1-74.7-168.9-166.5-168.9C74.7 32 0 107.8 0 200.9s74.7 168.9 166.5 168.9c39.8 0 76.3-14.2 105-37.9l146 148.1 30.5-31zM166.5 330.8c-70.6 0-128.1-58.3-128.1-129.9S95.9 71 166.5 71s128.1 58.3 128.1 129.9-57.4 129.9-128.1 129.9z\"],\n    \"sith\": [448, 512, [], \"f512\", \"M0 32l69.71 118.75-58.86-11.52 69.84 91.03a146.741 146.741 0 0 0 0 51.45l-69.84 91.03 58.86-11.52L0 480l118.75-69.71-11.52 58.86 91.03-69.84c17.02 3.04 34.47 3.04 51.48 0l91.03 69.84-11.52-58.86L448 480l-69.71-118.78 58.86 11.52-69.84-91.03c3.03-17.01 3.04-34.44 0-51.45l69.84-91.03-58.86 11.52L448 32l-118.75 69.71 11.52-58.9-91.06 69.87c-8.5-1.52-17.1-2.29-25.71-2.29s-17.21.78-25.71 2.29l-91.06-69.87 11.52 58.9L0 32zm224 99.78c31.8 0 63.6 12.12 87.85 36.37 48.5 48.5 48.49 127.21 0 175.7s-127.2 48.46-175.7-.03c-48.5-48.5-48.49-127.21 0-175.7 24.24-24.25 56.05-36.34 87.85-36.34zm0 36.66c-22.42 0-44.83 8.52-61.92 25.61-34.18 34.18-34.19 89.68 0 123.87s89.65 34.18 123.84 0c34.18-34.18 34.19-89.68 0-123.87-17.09-17.09-39.5-25.61-61.92-25.61z\"],\n    \"sketch\": [512, 512, [], \"f7c6\", \"M27.5 162.2L9 187.1h90.5l6.9-130.7-78.9 105.8zM396.3 45.7L267.7 32l135.7 147.2-7.1-133.5zM112.2 218.3l-11.2-22H9.9L234.8 458zm2-31.2h284l-81.5-88.5L256.3 33zm297.3 9.1L277.6 458l224.8-261.7h-90.9zM415.4 69L406 56.4l.9 17.3 6.1 113.4h90.3zM113.5 93.5l-4.6 85.6L244.7 32 116.1 45.7zm287.7 102.7h-290l42.4 82.9L256.3 480l144.9-283.8z\"],\n    \"skyatlas\": [640, 512, [], \"f216\", \"M640 329.3c0 65.9-52.5 114.4-117.5 114.4-165.9 0-196.6-249.7-359.7-249.7-146.9 0-147.1 212.2 5.6 212.2 42.5 0 90.9-17.8 125.3-42.5 5.6-4.1 16.9-16.3 22.8-16.3s10.9 5 10.9 10.9c0 7.8-13.1 19.1-18.7 24.1-40.9 35.6-100.3 61.2-154.7 61.2-83.4.1-154-59-154-144.9s67.5-149.1 152.8-149.1c185.3 0 222.5 245.9 361.9 245.9 99.9 0 94.8-139.7 3.4-139.7-17.5 0-35 11.6-46.9 11.6-8.4 0-15.9-7.2-15.9-15.6 0-11.6 5.3-23.7 5.3-36.3 0-66.6-50.9-114.7-116.9-114.7-53.1 0-80 36.9-88.8 36.9-6.2 0-11.2-5-11.2-11.2 0-5.6 4.1-10.3 7.8-14.4 25.3-28.8 64.7-43.7 102.8-43.7 79.4 0 139.1 58.4 139.1 137.8 0 6.9-.3 13.7-1.2 20.6 11.9-3.1 24.1-4.7 35.9-4.7 60.7 0 111.9 45.3 111.9 107.2z\"],\n    \"skype\": [448, 512, [], \"f17e\", \"M424.7 299.8c2.9-14 4.7-28.9 4.7-43.8 0-113.5-91.9-205.3-205.3-205.3-14.9 0-29.7 1.7-43.8 4.7C161.3 40.7 137.7 32 112 32 50.2 32 0 82.2 0 144c0 25.7 8.7 49.3 23.3 68.2-2.9 14-4.7 28.9-4.7 43.8 0 113.5 91.9 205.3 205.3 205.3 14.9 0 29.7-1.7 43.8-4.7 19 14.6 42.6 23.3 68.2 23.3 61.8 0 112-50.2 112-112 .1-25.6-8.6-49.2-23.2-68.1zm-194.6 91.5c-65.6 0-120.5-29.2-120.5-65 0-16 9-30.6 29.5-30.6 31.2 0 34.1 44.9 88.1 44.9 25.7 0 42.3-11.4 42.3-26.3 0-18.7-16-21.6-42-28-62.5-15.4-117.8-22-117.8-87.2 0-59.2 58.6-81.1 109.1-81.1 55.1 0 110.8 21.9 110.8 55.4 0 16.9-11.4 31.8-30.3 31.8-28.3 0-29.2-33.5-75-33.5-25.7 0-42 7-42 22.5 0 19.8 20.8 21.8 69.1 33 41.4 9.3 90.7 26.8 90.7 77.6 0 59.1-57.1 86.5-112 86.5z\"],\n    \"slack\": [448, 512, [], \"f198\", \"M94.12 315.1c0 25.9-21.16 47.06-47.06 47.06S0 341 0 315.1c0-25.9 21.16-47.06 47.06-47.06h47.06v47.06zm23.72 0c0-25.9 21.16-47.06 47.06-47.06s47.06 21.16 47.06 47.06v117.84c0 25.9-21.16 47.06-47.06 47.06s-47.06-21.16-47.06-47.06V315.1zm47.06-188.98c-25.9 0-47.06-21.16-47.06-47.06S139 32 164.9 32s47.06 21.16 47.06 47.06v47.06H164.9zm0 23.72c25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06H47.06C21.16 243.96 0 222.8 0 196.9s21.16-47.06 47.06-47.06H164.9zm188.98 47.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06s-21.16 47.06-47.06 47.06h-47.06V196.9zm-23.72 0c0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06V79.06c0-25.9 21.16-47.06 47.06-47.06 25.9 0 47.06 21.16 47.06 47.06V196.9zM283.1 385.88c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06-25.9 0-47.06-21.16-47.06-47.06v-47.06h47.06zm0-23.72c-25.9 0-47.06-21.16-47.06-47.06 0-25.9 21.16-47.06 47.06-47.06h117.84c25.9 0 47.06 21.16 47.06 47.06 0 25.9-21.16 47.06-47.06 47.06H283.1z\"],\n    \"slack-hash\": [448, 512, [], \"f3ef\", \"M446.2 270.4c-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-30.3-90 45.4-15.1c19.1-6.2 29.1-26.8 23-45.9-6.2-19-26.9-29.1-46-22.9l-45.4 15.1-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-93.4 31.2-15.7-47c-6.2-19-26.9-29.1-46-22.9-19.1 6.2-29.1 26.8-23 45.9l15.7 47-45.3 15c-19.1 6.2-29.1 26.8-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l30.3 90L78 354.8c-19 6.2-29.1 26.9-23 45.9 5 14.5 19.1 24 33.6 24.6 6.8 1 12-1.6 57.7-16.8l15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 93.6-31.3 15.7 47c5.9 16.9 24.7 29 46 22.9 19.1-6.2 29.1-26.8 23-45.9l-15.7-47 45.4-15.1c19-6 29.1-26.7 22.9-45.7zm-254.1 47.2l-30.3-90.2 93.5-31.3 30.3 90.2-93.5 31.3z\"],\n    \"slideshare\": [512, 512, [], \"f1e7\", \"M187.7 153.7c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7s61.7-26 61.7-57.7c0-32-27.7-57.7-61.7-57.7zm143.4 0c-34 0-61.7 25.7-61.7 57.7 0 31.7 27.7 57.7 61.7 57.7 34.3 0 61.7-26 61.7-57.7.1-32-27.4-57.7-61.7-57.7zm156.6 90l-6 4.3V49.7c0-27.4-20.6-49.7-46-49.7H76.6c-25.4 0-46 22.3-46 49.7V248c-2-1.4-4.3-2.9-6.3-4.3-15.1-10.6-25.1 4-16 17.7 18.3 22.6 53.1 50.3 106.3 72C58.3 525.1 252 555.7 248.9 457.5c0-.7.3-56.6.3-96.6 5.1 1.1 9.4 2.3 13.7 3.1 0 39.7.3 92.8.3 93.5-3.1 98.3 190.6 67.7 134.3-124 53.1-21.7 88-49.4 106.3-72 9.1-13.8-.9-28.3-16.1-17.8zm-30.5 19.2c-68.9 37.4-128.3 31.1-160.6 29.7-23.7-.9-32.6 9.1-33.7 24.9-10.3-7.7-18.6-15.5-20.3-17.1-5.1-5.4-13.7-8-27.1-7.7-31.7 1.1-89.7 7.4-157.4-28V72.3c0-34.9 8.9-45.7 40.6-45.7h317.7c30.3 0 40.9 12.9 40.9 45.7v190.6z\"],\n    \"snapchat\": [496, 512, [], \"f2ab\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm169.5 338.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C183.1 100 230.7 96 244.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"snapchat-ghost\": [512, 512, [], \"f2ac\", \"M510.846 392.673c-5.211 12.157-27.239 21.089-67.36 27.318-2.064 2.786-3.775 14.686-6.507 23.956-1.625 5.566-5.623 8.869-12.128 8.869l-.297-.005c-9.395 0-19.203-4.323-38.852-4.323-26.521 0-35.662 6.043-56.254 20.588-21.832 15.438-42.771 28.764-74.027 27.399-31.646 2.334-58.025-16.908-72.871-27.404-20.714-14.643-29.828-20.582-56.241-20.582-18.864 0-30.736 4.72-38.852 4.72-8.073 0-11.213-4.922-12.422-9.04-2.703-9.189-4.404-21.263-6.523-24.13-20.679-3.209-67.31-11.344-68.498-32.15a10.627 10.627 0 0 1 8.877-11.069c69.583-11.455 100.924-82.901 102.227-85.934.074-.176.155-.344.237-.515 3.713-7.537 4.544-13.849 2.463-18.753-5.05-11.896-26.872-16.164-36.053-19.796-23.715-9.366-27.015-20.128-25.612-27.504 2.437-12.836 21.725-20.735 33.002-15.453 8.919 4.181 16.843 6.297 23.547 6.297 5.022 0 8.212-1.204 9.96-2.171-2.043-35.936-7.101-87.29 5.687-115.969C158.122 21.304 229.705 15.42 250.826 15.42c.944 0 9.141-.089 10.11-.089 52.148 0 102.254 26.78 126.723 81.643 12.777 28.65 7.749 79.792 5.695 116.009 1.582.872 4.357 1.942 8.599 2.139 6.397-.286 13.815-2.389 22.069-6.257 6.085-2.846 14.406-2.461 20.48.058l.029.01c9.476 3.385 15.439 10.215 15.589 17.87.184 9.747-8.522 18.165-25.878 25.018-2.118.835-4.694 1.655-7.434 2.525-9.797 3.106-24.6 7.805-28.616 17.271-2.079 4.904-1.256 11.211 2.46 18.748.087.168.166.342.239.515 1.301 3.03 32.615 74.46 102.23 85.934 6.427 1.058 11.163 7.877 7.725 15.859z\"],\n    \"snapchat-square\": [448, 512, [], \"f2ad\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6.5 314.9c-3.5 8.1-18.1 14-44.8 18.2-1.4 1.9-2.5 9.8-4.3 15.9-1.1 3.7-3.7 5.9-8.1 5.9h-.2c-6.2 0-12.8-2.9-25.8-2.9-17.6 0-23.7 4-37.4 13.7-14.5 10.3-28.4 19.1-49.2 18.2-21 1.6-38.6-11.2-48.5-18.2-13.8-9.7-19.8-13.7-37.4-13.7-12.5 0-20.4 3.1-25.8 3.1-5.4 0-7.5-3.3-8.3-6-1.8-6.1-2.9-14.1-4.3-16-13.8-2.1-44.8-7.5-45.5-21.4-.2-3.6 2.3-6.8 5.9-7.4 46.3-7.6 67.1-55.1 68-57.1 0-.1.1-.2.2-.3 2.5-5 3-9.2 1.6-12.5-3.4-7.9-17.9-10.7-24-13.2-15.8-6.2-18-13.4-17-18.3 1.6-8.5 14.4-13.8 21.9-10.3 5.9 2.8 11.2 4.2 15.7 4.2 3.3 0 5.5-.8 6.6-1.4-1.4-23.9-4.7-58 3.8-77.1C159.1 100 206.7 96 220.7 96c.6 0 6.1-.1 6.7-.1 34.7 0 68 17.8 84.3 54.3 8.5 19.1 5.2 53.1 3.8 77.1 1.1.6 2.9 1.3 5.7 1.4 4.3-.2 9.2-1.6 14.7-4.2 4-1.9 9.6-1.6 13.6 0 6.3 2.3 10.3 6.8 10.4 11.9.1 6.5-5.7 12.1-17.2 16.6-1.4.6-3.1 1.1-4.9 1.7-6.5 2.1-16.4 5.2-19 11.5-1.4 3.3-.8 7.5 1.6 12.5.1.1.1.2.2.3.9 2 21.7 49.5 68 57.1 4 1 7.1 5.5 4.9 10.8z\"],\n    \"soundcloud\": [640, 512, [], \"f1be\", \"M111.4 256.3l5.8 65-5.8 68.3c-.3 2.5-2.2 4.4-4.4 4.4s-4.2-1.9-4.2-4.4l-5.6-68.3 5.6-65c0-2.2 1.9-4.2 4.2-4.2 2.2 0 4.1 2 4.4 4.2zm21.4-45.6c-2.8 0-4.7 2.2-5 5l-5 105.6 5 68.3c.3 2.8 2.2 5 5 5 2.5 0 4.7-2.2 4.7-5l5.8-68.3-5.8-105.6c0-2.8-2.2-5-4.7-5zm25.5-24.1c-3.1 0-5.3 2.2-5.6 5.3l-4.4 130 4.4 67.8c.3 3.1 2.5 5.3 5.6 5.3 2.8 0 5.3-2.2 5.3-5.3l5.3-67.8-5.3-130c0-3.1-2.5-5.3-5.3-5.3zM7.2 283.2c-1.4 0-2.2 1.1-2.5 2.5L0 321.3l4.7 35c.3 1.4 1.1 2.5 2.5 2.5s2.2-1.1 2.5-2.5l5.6-35-5.6-35.6c-.3-1.4-1.1-2.5-2.5-2.5zm23.6-21.9c-1.4 0-2.5 1.1-2.5 2.5l-6.4 57.5 6.4 56.1c0 1.7 1.1 2.8 2.5 2.8s2.5-1.1 2.8-2.5l7.2-56.4-7.2-57.5c-.3-1.4-1.4-2.5-2.8-2.5zm25.3-11.4c-1.7 0-3.1 1.4-3.3 3.3L47 321.3l5.8 65.8c.3 1.7 1.7 3.1 3.3 3.1 1.7 0 3.1-1.4 3.1-3.1l6.9-65.8-6.9-68.1c0-1.9-1.4-3.3-3.1-3.3zm25.3-2.2c-1.9 0-3.6 1.4-3.6 3.6l-5.8 70 5.8 67.8c0 2.2 1.7 3.6 3.6 3.6s3.6-1.4 3.9-3.6l6.4-67.8-6.4-70c-.3-2.2-2-3.6-3.9-3.6zm241.4-110.9c-1.1-.8-2.8-1.4-4.2-1.4-2.2 0-4.2.8-5.6 1.9-1.9 1.7-3.1 4.2-3.3 6.7v.8l-3.3 176.7 1.7 32.5 1.7 31.7c.3 4.7 4.2 8.6 8.9 8.6s8.6-3.9 8.6-8.6l3.9-64.2-3.9-177.5c-.4-3-2-5.8-4.5-7.2zm-26.7 15.3c-1.4-.8-2.8-1.4-4.4-1.4s-3.1.6-4.4 1.4c-2.2 1.4-3.6 3.9-3.6 6.7l-.3 1.7-2.8 160.8s0 .3 3.1 65.6v.3c0 1.7.6 3.3 1.7 4.7 1.7 1.9 3.9 3.1 6.4 3.1 2.2 0 4.2-1.1 5.6-2.5 1.7-1.4 2.5-3.3 2.5-5.6l.3-6.7 3.1-58.6-3.3-162.8c-.3-2.8-1.7-5.3-3.9-6.7zm-111.4 22.5c-3.1 0-5.8 2.8-5.8 6.1l-4.4 140.6 4.4 67.2c.3 3.3 2.8 5.8 5.8 5.8 3.3 0 5.8-2.5 6.1-5.8l5-67.2-5-140.6c-.2-3.3-2.7-6.1-6.1-6.1zm376.7 62.8c-10.8 0-21.1 2.2-30.6 6.1-6.4-70.8-65.8-126.4-138.3-126.4-17.8 0-35 3.3-50.3 9.4-6.1 2.2-7.8 4.4-7.8 9.2v249.7c0 5 3.9 8.6 8.6 9.2h218.3c43.3 0 78.6-35 78.6-78.3.1-43.6-35.2-78.9-78.5-78.9zm-296.7-60.3c-4.2 0-7.5 3.3-7.8 7.8l-3.3 136.7 3.3 65.6c.3 4.2 3.6 7.5 7.8 7.5 4.2 0 7.5-3.3 7.5-7.5l3.9-65.6-3.9-136.7c-.3-4.5-3.3-7.8-7.5-7.8zm-53.6-7.8c-3.3 0-6.4 3.1-6.4 6.7l-3.9 145.3 3.9 66.9c.3 3.6 3.1 6.4 6.4 6.4 3.6 0 6.4-2.8 6.7-6.4l4.4-66.9-4.4-145.3c-.3-3.6-3.1-6.7-6.7-6.7zm26.7 3.4c-3.9 0-6.9 3.1-6.9 6.9L227 321.3l3.9 66.4c.3 3.9 3.1 6.9 6.9 6.9s6.9-3.1 6.9-6.9l4.2-66.4-4.2-141.7c0-3.9-3-6.9-6.9-6.9z\"],\n    \"sourcetree\": [448, 512, [], \"f7d3\", \"M427.2 203c0-112.1-90.9-203-203-203C112.1-.2 21.2 90.6 21 202.6A202.86 202.86 0 0 0 161.5 396v101.7a14.3 14.3 0 0 0 14.3 14.3h96.4a14.3 14.3 0 0 0 14.3-14.3V396.1A203.18 203.18 0 0 0 427.2 203zm-271.6 0c0-90.8 137.3-90.8 137.3 0-.1 89.9-137.3 91-137.3 0z\"],\n    \"speakap\": [448, 512, [], \"f3f3\", \"M64 391.78C-15.41 303.59-8 167.42 80.64 87.64s224.8-73 304.21 15.24 72 224.36-16.64 304.14c-18.74 16.87 64 43.09 42 52.26-82.06 34.21-253.91 35-346.23-67.5zm213.31-211.6l38.5-40.86c-9.61-8.89-32-26.83-76.17-27.6-52.33-.91-95.86 28.3-96.77 80-.2 11.33.29 36.72 29.42 54.83 34.46 21.42 86.52 21.51 86 52.26-.37 21.28-26.42 25.81-38.59 25.6-3-.05-30.23-.46-47.61-24.62l-40 42.61c28.16 27 59 32.62 83.49 33.05 10.23.18 96.42.33 97.84-81 .28-15.81-2.07-39.72-28.86-56.59-34.36-21.64-85-19.45-84.43-49.75.41-23.25 31-25.37 37.53-25.26.43 0 26.62.26 39.62 17.37z\"],\n    \"speaker-deck\": [512, 512, [], \"f83c\", \"M213.86 296H100a100 100 0 0 1 0-200h132.84a40 40 0 0 1 0 80H98c-26.47 0-26.45 40 0 40h113.82a100 100 0 0 1 0 200H40a40 40 0 0 1 0-80h173.86c26.48 0 26.46-40 0-40zM298 416a120.21 120.21 0 0 0 51.11-80h64.55a19.83 19.83 0 0 0 19.66-20V196a19.83 19.83 0 0 0-19.66-20H296.42a60.77 60.77 0 0 0 0-80h136.93c43.44 0 78.65 35.82 78.65 80v160c0 44.18-35.21 80-78.65 80z\"],\n    \"spotify\": [496, 512, [], \"f1bc\", \"M248 8C111.1 8 0 119.1 0 256s111.1 248 248 248 248-111.1 248-248S384.9 8 248 8zm100.7 364.9c-4.2 0-6.8-1.3-10.7-3.6-62.4-37.6-135-39.2-206.7-24.5-3.9 1-9 2.6-11.9 2.6-9.7 0-15.8-7.7-15.8-15.8 0-10.3 6.1-15.2 13.6-16.8 81.9-18.1 165.6-16.5 237 26.2 6.1 3.9 9.7 7.4 9.7 16.5s-7.1 15.4-15.2 15.4zm26.9-65.6c-5.2 0-8.7-2.3-12.3-4.2-62.5-37-155.7-51.9-238.6-29.4-4.8 1.3-7.4 2.6-11.9 2.6-10.7 0-19.4-8.7-19.4-19.4s5.2-17.8 15.5-20.7c27.8-7.8 56.2-13.6 97.8-13.6 64.9 0 127.6 16.1 177 45.5 8.1 4.8 11.3 11 11.3 19.7-.1 10.8-8.5 19.5-19.4 19.5zm31-76.2c-5.2 0-8.4-1.3-12.9-3.9-71.2-42.5-198.5-52.7-280.9-29.7-3.6 1-8.1 2.6-12.9 2.6-13.2 0-23.3-10.3-23.3-23.6 0-13.6 8.4-21.3 17.4-23.9 35.2-10.3 74.6-15.2 117.5-15.2 73 0 149.5 15.2 205.4 47.8 7.8 4.5 12.9 10.7 12.9 22.6 0 13.6-11 23.3-23.2 23.3z\"],\n    \"squarespace\": [512, 512, [], \"f5be\", \"M186.12 343.34c-9.65 9.65-9.65 25.29 0 34.94 9.65 9.65 25.29 9.65 34.94 0L378.24 221.1c19.29-19.29 50.57-19.29 69.86 0s19.29 50.57 0 69.86L293.95 445.1c19.27 19.29 50.53 19.31 69.82.04l.04-.04 119.25-119.24c38.59-38.59 38.59-101.14 0-139.72-38.59-38.59-101.15-38.59-139.72 0l-157.22 157.2zm244.53-104.8c-9.65-9.65-25.29-9.65-34.93 0l-157.2 157.18c-19.27 19.29-50.53 19.31-69.82.05l-.05-.05c-9.64-9.64-25.27-9.65-34.92-.01l-.01.01c-9.65 9.64-9.66 25.28-.02 34.93l.02.02c38.58 38.57 101.14 38.57 139.72 0l157.2-157.2c9.65-9.65 9.65-25.29.01-34.93zm-261.99 87.33l157.18-157.18c9.64-9.65 9.64-25.29 0-34.94-9.64-9.64-25.27-9.64-34.91 0L133.72 290.93c-19.28 19.29-50.56 19.3-69.85.01l-.01-.01c-19.29-19.28-19.31-50.54-.03-69.84l.03-.03L218.03 66.89c-19.28-19.29-50.55-19.3-69.85-.02l-.02.02L28.93 186.14c-38.58 38.59-38.58 101.14 0 139.72 38.6 38.59 101.13 38.59 139.73.01zm-87.33-52.4c9.64 9.64 25.27 9.64 34.91 0l157.21-157.19c19.28-19.29 50.55-19.3 69.84-.02l.02.02c9.65 9.65 25.29 9.65 34.93 0 9.65-9.65 9.65-25.29 0-34.93-38.59-38.59-101.13-38.59-139.72 0L81.33 238.54c-9.65 9.64-9.65 25.28-.01 34.93h.01z\"],\n    \"stack-exchange\": [448, 512, [], \"f18d\", \"M17.7 332.3h412.7v22c0 37.7-29.3 68-65.3 68h-19L259.3 512v-89.7H83c-36 0-65.3-30.3-65.3-68v-22zm0-23.6h412.7v-85H17.7v85zm0-109.4h412.7v-85H17.7v85zM365 0H83C47 0 17.7 30.3 17.7 67.7V90h412.7V67.7C430.3 30.3 401 0 365 0z\"],\n    \"stack-overflow\": [384, 512, [], \"f16c\", \"M290.7 311L95 269.7 86.8 309l195.7 41zm51-87L188.2 95.7l-25.5 30.8 153.5 128.3zm-31.2 39.7L129.2 179l-16.7 36.5L293.7 300zM262 32l-32 24 119.3 160.3 32-24zm20.5 328h-200v39.7h200zm39.7 80H42.7V320h-40v160h359.5V320h-40z\"],\n    \"stackpath\": [448, 512, [], \"f842\", \"M244.6 232.4c0 8.5-4.26 20.49-21.34 20.49h-19.61v-41.47h19.61c17.13 0 21.34 12.36 21.34 20.98zM448 32v448H0V32zM151.3 287.84c0-21.24-12.12-34.54-46.72-44.85-20.57-7.41-26-10.91-26-18.63s7-14.61 20.41-14.61c14.09 0 20.79 8.45 20.79 18.35h30.7l.19-.57c.5-19.57-15.06-41.65-51.12-41.65-23.37 0-52.55 10.75-52.55 38.29 0 19.4 9.25 31.29 50.74 44.37 17.26 6.15 21.91 10.4 21.91 19.48 0 15.2-19.13 14.23-19.47 14.23-20.4 0-25.65-9.1-25.65-21.9h-30.8l-.18.56c-.68 31.32 28.38 45.22 56.63 45.22 29.98 0 51.12-13.55 51.12-38.29zm125.38-55.63c0-25.3-18.43-45.46-53.42-45.46h-51.78v138.18h32.17v-47.36h19.61c30.25 0 53.42-15.95 53.42-45.36zM297.94 325L347 186.78h-31.09L268 325zm106.52-138.22h-31.09L325.46 325h29.94z\"],\n    \"staylinked\": [440, 512, [], \"f3f5\", \"M382.7 292.5l2.7 2.7-170-167.3c-3.5-3.5-9.7-3.7-13.8-.5L144.3 171c-4.2 3.2-4.6 8.7-1.1 12.2l68.1 64.3c3.6 3.5 9.9 3.7 14 .5l.1-.1c4.1-3.2 10.4-3 14 .5l84 81.3c3.6 3.5 3.2 9-.9 12.2l-93.2 74c-4.2 3.3-10.5 3.1-14.2-.4L63.2 268c-3.5-3.5-9.7-3.7-13.9-.5L3.5 302.4c-4.2 3.2-4.7 8.7-1.2 12.2L211 510.7s7.4 6.8 17.3-.8l198-163.9c4-3.2 4.4-8.7.7-12.2zm54.5-83.4L226.7 2.5c-1.5-1.2-8-5.5-16.3 1.1L3.6 165.7c-4.2 3.2-4.8 8.7-1.2 12.2l42.3 41.7 171.7 165.1c3.7 3.5 10.1 3.7 14.3.4l50.2-38.8-.3-.3 7.7-6c4.2-3.2 4.6-8.7.9-12.2l-57.1-54.4c-3.6-3.5-10-3.7-14.2-.5l-.1.1c-4.2 3.2-10.5 3.1-14.2-.4L109 180.8c-3.6-3.5-3.1-8.9 1.1-12.2l92.2-71.5c4.1-3.2 10.3-3 13.9.5l160.4 159c3.7 3.5 10 3.7 14.1.5l45.8-35.8c4.1-3.2 4.4-8.7.7-12.2z\"],\n    \"steam\": [496, 512, [], \"f1b6\", \"M496 256c0 137-111.2 248-248.4 248-113.8 0-209.6-76.3-239-180.4l95.2 39.3c6.4 32.1 34.9 56.4 68.9 56.4 39.2 0 71.9-32.4 70.2-73.5l84.5-60.2c52.1 1.3 95.8-40.9 95.8-93.5 0-51.6-42-93.5-93.7-93.5s-93.7 42-93.7 93.5v1.2L176.6 279c-15.5-.9-30.7 3.4-43.5 12.1L0 236.1C10.2 108.4 117.1 8 247.6 8 384.8 8 496 119 496 256zM155.7 384.3l-30.5-12.6a52.79 52.79 0 0 0 27.2 25.8c26.9 11.2 57.8-1.6 69-28.4 5.4-13 5.5-27.3.1-40.3-5.4-13-15.5-23.2-28.5-28.6-12.9-5.4-26.7-5.2-38.9-.6l31.5 13c19.8 8.2 29.2 30.9 20.9 50.7-8.3 19.9-31 29.2-50.8 21zm173.8-129.9c-34.4 0-62.4-28-62.4-62.3s28-62.3 62.4-62.3 62.4 28 62.4 62.3-27.9 62.3-62.4 62.3zm.1-15.6c25.9 0 46.9-21 46.9-46.8 0-25.9-21-46.8-46.9-46.8s-46.9 21-46.9 46.8c.1 25.8 21.1 46.8 46.9 46.8z\"],\n    \"steam-square\": [448, 512, [], \"f1b7\", \"M185.2 356.5c7.7-18.5-1-39.7-19.6-47.4l-29.5-12.2c11.4-4.3 24.3-4.5 36.4.5 12.2 5.1 21.6 14.6 26.7 26.7 5 12.2 5 25.6-.1 37.7-10.5 25.1-39.4 37-64.6 26.5-11.6-4.8-20.4-13.6-25.4-24.2l28.5 11.8c18.6 7.8 39.9-.9 47.6-19.4zM400 32H48C21.5 32 0 53.5 0 80v160.7l116.6 48.1c12-8.2 26.2-12.1 40.7-11.3l55.4-80.2v-1.1c0-48.2 39.3-87.5 87.6-87.5s87.6 39.3 87.6 87.5c0 49.2-40.9 88.7-89.6 87.5l-79 56.3c1.6 38.5-29.1 68.8-65.7 68.8-31.8 0-58.5-22.7-64.5-52.7L0 319.2V432c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-99.7 222.5c-32.2 0-58.4-26.1-58.4-58.3s26.2-58.3 58.4-58.3 58.4 26.2 58.4 58.3-26.2 58.3-58.4 58.3zm.1-14.6c24.2 0 43.9-19.6 43.9-43.8 0-24.2-19.6-43.8-43.9-43.8-24.2 0-43.9 19.6-43.9 43.8 0 24.2 19.7 43.8 43.9 43.8z\"],\n    \"steam-symbol\": [448, 512, [], \"f3f6\", \"M395.5 177.5c0 33.8-27.5 61-61 61-33.8 0-61-27.3-61-61s27.3-61 61-61c33.5 0 61 27.2 61 61zm52.5.2c0 63-51 113.8-113.7 113.8L225 371.3c-4 43-40.5 76.8-84.5 76.8-40.5 0-74.7-28.8-83-67L0 358V250.7L97.2 290c15.1-9.2 32.2-13.3 52-11.5l71-101.7c.5-62.3 51.5-112.8 114-112.8C397 64 448 115 448 177.7zM203 363c0-34.7-27.8-62.5-62.5-62.5-4.5 0-9 .5-13.5 1.5l26 10.5c25.5 10.2 38 39 27.7 64.5-10.2 25.5-39.2 38-64.7 27.5-10.2-4-20.5-8.3-30.7-12.2 10.5 19.7 31.2 33.2 55.2 33.2 34.7 0 62.5-27.8 62.5-62.5zm207.5-185.3c0-42-34.3-76.2-76.2-76.2-42.3 0-76.5 34.2-76.5 76.2 0 42.2 34.3 76.2 76.5 76.2 41.9.1 76.2-33.9 76.2-76.2z\"],\n    \"sticker-mule\": [576, 512, [], \"f3f7\", \"M561.7 199.6c-1.3.3.3 0 0 0zm-6.2-77.4c-7.7-22.3-5.1-7.2-13.4-36.9-1.6-6.5-3.6-14.5-6.2-20-4.4-8.7-4.6-7.5-4.6-9.5 0-5.3 30.7-45.3 19-46.9-5.7-.6-12.2 11.6-20.6 17-8.6 4.2-8 5-10.3 5-2.6 0-5.7-3-6.2-5-2-5.7 1.9-25.9-3.6-25.9-3.6 0-12.3 24.8-17 25.8-5.2 1.3-27.9-11.4-75.1 18-25.3 13.2-86.9 65.2-87 65.3-6.7 4.7-20 4.7-35.5 16-44.4 30.1-109.6 9.4-110.7 9-110.6-26.8-128-15.2-159 11.5-20.8 17.9-23.7 36.5-24.2 38.9-4.2 20.4 5.2 48.3 6.7 64.3 1.8 19.3-2.7 17.7 7.7 98.3.5 1 4.1 0 5.1 1.5 0 8.4-3.8 12.1-4.1 13-1.5 4.5-1.5 10.5 0 16 2.3 8.2 8.2 37.2 8.2 46.9 0 41.8.4 44 2.6 49.4 3.9 10 12.5 9.1 17 12 3.1 3.5-.5 8.5 1 12.5.5 2 3.6 4 6.2 5 9.2 3.6 27 .3 29.9-2.5 1.6-1.5.5-4.5 3.1-5 5.1 0 10.8-.5 14.4-2.5 5.1-2.5 4.1-6 1.5-10.5-.4-.8-7-13.3-9.8-16-2.1-2-5.1-3-7.2-4.5-5.8-4.9-10.3-19.4-10.3-19.5-4.6-19.4-10.3-46.3-4.1-66.8 4.6-17.2 39.5-87.7 39.6-87.8 4.1-6.5 17-11.5 27.3-7 6 1.9 19.3 22 65.4 30.9 47.9 8.7 97.4-2 112.2-2 2.8 2-1.9 13-.5 38.9 0 26.4-.4 13.7-4.1 29.9-2.2 9.7 3.4 23.2-1.5 46.9-1.4 9.8-9.9 32.7-8.2 43.4.5 1 1 2 1.5 3.5.5 4.5 1.5 8.5 4.6 10 7.3 3.6 12-3.5 9.8 11.5-.7 3.1-2.6 12 1.5 15 4.4 3.7 30.6 3.4 36.5.5 2.6-1.5 1.6-4.5 6.4-7.4 1.9-.9 11.3-.4 11.3-6.5.3-1.8-9.2-19.9-9.3-20-2.6-3.5-9.2-4.5-11.3-8-6.9-10.1-1.7-52.6.5-59.4 3-11 5.6-22.4 8.7-32.4 11-42.5 10.3-50.6 16.5-68.3.8-1.8 6.4-23.1 10.3-29.9 9.3-17 21.7-32.4 33.5-47.4 18-22.9 34-46.9 52-69.8 6.1-7 8.2-13.7 18-8 10.8 5.7 21.6 7 31.9 17 14.6 12.8 10.2 18.2 11.8 22.9 1.5 5 7.7 10.5 14.9 9.5 10.4-2 13-2.5 13.4-2.5 2.6-.5 5.7-5 7.2-8 3.1-5.5 7.2-9 7.2-16.5 0-7.7-.4-2.8-20.6-52.9z\"],\n    \"strava\": [384, 512, [], \"f428\", \"M158.4 0L7 292h89.2l62.2-116.1L220.1 292h88.5zm150.2 292l-43.9 88.2-44.6-88.2h-67.6l112.2 220 111.5-220z\"],\n    \"stripe\": [640, 512, [], \"f429\", \"M165 144.7l-43.3 9.2-.2 142.4c0 26.3 19.8 43.3 46.1 43.3 14.6 0 25.3-2.7 31.2-5.9v-33.8c-5.7 2.3-33.7 10.5-33.7-15.7V221h33.7v-37.8h-33.7zm89.1 51.6l-2.7-13.1H213v153.2h44.3V233.3c10.5-13.8 28.2-11.1 33.9-9.3v-40.8c-6-2.1-26.7-6-37.1 13.1zm92.3-72.3l-44.6 9.5v36.2l44.6-9.5zM44.9 228.3c0-6.9 5.8-9.6 15.1-9.7 13.5 0 30.7 4.1 44.2 11.4v-41.8c-14.7-5.8-29.4-8.1-44.1-8.1-36 0-60 18.8-60 50.2 0 49.2 67.5 41.2 67.5 62.4 0 8.2-7.1 10.9-17 10.9-14.7 0-33.7-6.1-48.6-14.2v40c16.5 7.1 33.2 10.1 48.5 10.1 36.9 0 62.3-15.8 62.3-47.8 0-52.9-67.9-43.4-67.9-63.4zM640 261.6c0-45.5-22-81.4-64.2-81.4s-67.9 35.9-67.9 81.1c0 53.5 30.3 78.2 73.5 78.2 21.2 0 37.1-4.8 49.2-11.5v-33.4c-12.1 6.1-26 9.8-43.6 9.8-17.3 0-32.5-6.1-34.5-26.9h86.9c.2-2.3.6-11.6.6-15.9zm-87.9-16.8c0-20 12.3-28.4 23.4-28.4 10.9 0 22.5 8.4 22.5 28.4zm-112.9-64.6c-17.4 0-28.6 8.2-34.8 13.9l-2.3-11H363v204.8l44.4-9.4.1-50.2c6.4 4.7 15.9 11.2 31.4 11.2 31.8 0 60.8-23.2 60.8-79.6.1-51.6-29.3-79.7-60.5-79.7zm-10.6 122.5c-10.4 0-16.6-3.8-20.9-8.4l-.3-66c4.6-5.1 11-8.8 21.2-8.8 16.2 0 27.4 18.2 27.4 41.4.1 23.9-10.9 41.8-27.4 41.8zm-126.7 33.7h44.6V183.2h-44.6z\"],\n    \"stripe-s\": [384, 512, [], \"f42a\", \"M155.3 154.6c0-22.3 18.6-30.9 48.4-30.9 43.4 0 98.5 13.3 141.9 36.7V26.1C298.3 7.2 251.1 0 203.8 0 88.1 0 11 60.4 11 161.4c0 157.9 216.8 132.3 216.8 200.4 0 26.4-22.9 34.9-54.7 34.9-47.2 0-108.2-19.5-156.1-45.5v128.5a396.09 396.09 0 0 0 156 32.4c118.6 0 200.3-51 200.3-153.6 0-170.2-218-139.7-218-203.9z\"],\n    \"studiovinari\": [512, 512, [], \"f3f8\", \"M480.3 187.7l4.2 28v28l-25.1 44.1-39.8 78.4-56.1 67.5-79.1 37.8-17.7 24.5-7.7 12-9.6 4s17.3-63.6 19.4-63.6c2.1 0 20.3.7 20.3.7l66.7-38.6-92.5 26.1-55.9 36.8-22.8 28-6.6 1.4 20.8-73.6 6.9-5.5 20.7 12.9 88.3-45.2 56.8-51.5 14.8-68.4-125.4 23.3 15.2-18.2-173.4-53.3 81.9-10.5-166-122.9L133.5 108 32.2 0l252.9 126.6-31.5-38L378 163 234.7 64l18.7 38.4-49.6-18.1L158.3 0l194.6 122L310 66.2l108 96.4 12-8.9-21-16.4 4.2-37.8L451 89.1l29.2 24.7 11.5 4.2-7 6.2 8.5 12-13.1 7.4-10.3 20.2 10.5 23.9z\"],\n    \"stumbleupon\": [512, 512, [], \"f1a4\", \"M502.9 266v69.7c0 62.1-50.3 112.4-112.4 112.4-61.8 0-112.4-49.8-112.4-111.3v-70.2l34.3 16 51.1-15.2V338c0 14.7 12 26.5 26.7 26.5S417 352.7 417 338v-72h85.9zm-224.7-58.2l34.3 16 51.1-15.2V173c0-60.5-51.1-109-112.1-109-60.8 0-112.1 48.2-112.1 108.2v162.4c0 14.9-12 26.7-26.7 26.7S86 349.5 86 334.6V266H0v69.7C0 397.7 50.3 448 112.4 448c61.6 0 112.4-49.5 112.4-110.8V176.9c0-14.7 12-26.7 26.7-26.7s26.7 12 26.7 26.7v30.9z\"],\n    \"stumbleupon-circle\": [496, 512, [], \"f1a3\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 177.5c-9.8 0-17.8 8-17.8 17.8v106.9c0 40.9-33.9 73.9-74.9 73.9-41.4 0-74.9-33.5-74.9-74.9v-46.5h57.3v45.8c0 10 8 17.8 17.8 17.8s17.8-7.9 17.8-17.8V200.1c0-40 34.2-72.1 74.7-72.1 40.7 0 74.7 32.3 74.7 72.6v23.7l-34.1 10.1-22.9-10.7v-20.6c.1-9.6-7.9-17.6-17.7-17.6zm167.6 123.6c0 41.4-33.5 74.9-74.9 74.9-41.2 0-74.9-33.2-74.9-74.2V263l22.9 10.7 34.1-10.1v47.1c0 9.8 8 17.6 17.8 17.6s17.8-7.9 17.8-17.6v-48h57.3c-.1 45.9-.1 46.4-.1 46.4z\"],\n    \"superpowers\": [448, 512, [], \"f2dd\", \"M448 32c-83.3 11-166.8 22-250 33-92 12.5-163.3 86.7-169 180-3.3 55.5 18 109.5 57.8 148.2L0 480c83.3-11 166.5-22 249.8-33 91.8-12.5 163.3-86.8 168.7-179.8 3.5-55.5-18-109.5-57.7-148.2L448 32zm-79.7 232.3c-4.2 79.5-74 139.2-152.8 134.5-79.5-4.7-140.7-71-136.3-151 4.5-79.2 74.3-139.3 153-134.5 79.3 4.7 140.5 71 136.1 151z\"],\n    \"supple\": [640, 512, [], \"f3f9\", \"M640 262.5c0 64.1-109 116.1-243.5 116.1-24.8 0-48.6-1.8-71.1-5 7.7.4 15.5.6 23.4.6 134.5 0 243.5-56.9 243.5-127.1 0-29.4-19.1-56.4-51.2-78 60 21.1 98.9 55.1 98.9 93.4zM47.7 227.9c-.1-70.2 108.8-127.3 243.3-127.6 7.9 0 15.6.2 23.3.5-22.5-3.2-46.3-4.9-71-4.9C108.8 96.3-.1 148.5 0 212.6c.1 38.3 39.1 72.3 99.3 93.3-32.3-21.5-51.5-48.6-51.6-78zm60.2 39.9s10.5 13.2 29.3 13.2c17.9 0 28.4-11.5 28.4-25.1 0-28-40.2-25.1-40.2-39.7 0-5.4 5.3-9.1 12.5-9.1 5.7 0 11.3 2.6 11.3 6.6v3.9h14.2v-7.9c0-12.1-15.4-16.8-25.4-16.8-16.5 0-28.5 10.2-28.5 24.1 0 26.6 40.2 25.4 40.2 39.9 0 6.6-5.8 10.1-12.3 10.1-11.9 0-20.7-10.1-20.7-10.1l-8.8 10.9zm120.8-73.6v54.4c0 11.3-7.1 17.8-17.8 17.8-10.7 0-17.8-6.5-17.8-17.7v-54.5h-15.8v55c0 18.9 13.4 31.9 33.7 31.9 20.1 0 33.4-13 33.4-31.9v-55h-15.7zm34.4 85.4h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.8-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5.1 14.7-14 14.7h-12.6zm57 43h15.8v-29.5h15.5c16 0 27.2-11.5 27.2-28.1s-11.2-27.8-27.2-27.8h-39.1v13.4h7.8v72zm15.7-43v-29.1h12.9c8.7 0 13.7 5.7 13.7 14.4 0 8.9-5 14.7-14 14.7h-12.6zm57.1 34.8c0 5.8 2.4 8.2 8.2 8.2h37.6c5.8 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-18.6c-1.7 0-2.6-1-2.6-2.6v-61.2c0-5.7-2.4-8.2-8.2-8.2H401v13.4h5.2c1.7 0 2.6 1 2.6 2.6v61.2zm63.4 0c0 5.8 2.4 8.2 8.2 8.2H519c5.7 0 8.2-2.4 8.2-8.2v-13h-14.3v5.2c0 1.7-1 2.6-2.6 2.6h-19.7c-1.7 0-2.6-1-2.6-2.6v-20.3h27.7v-13.4H488v-22.4h19.2c1.7 0 2.6 1 2.6 2.6v5.2H524v-13c0-5.7-2.5-8.2-8.2-8.2h-51.6v13.4h7.8v63.9zm58.9-76v5.9h1.6v-5.9h2.7v-1.2h-7v1.2h2.7zm5.7-1.2v7.1h1.5v-5.7l2.3 5.7h1.3l2.3-5.7v5.7h1.5v-7.1h-2.3l-2.1 5.1-2.1-5.1h-2.4z\"],\n    \"suse\": [640, 512, [], \"f7d6\", \"M471.08 102.66s-.3 18.3-.3 20.3c-9.1-3-74.4-24.1-135.7-26.3-51.9-1.8-122.8-4.3-223 57.3-19.4 12.4-73.9 46.1-99.6 109.7C7 277-.12 307 7 335.06a111 111 0 0 0 16.5 35.7c17.4 25 46.6 41.6 78.1 44.4 44.4 3.9 78.1-16 90-53.3 8.2-25.8 0-63.6-31.5-82.9-25.6-15.7-53.3-12.1-69.2-1.6-13.9 9.2-21.8 23.5-21.6 39.2.3 27.8 24.3 42.6 41.5 42.6a49 49 0 0 0 15.8-2.7c6.5-1.8 13.3-6.5 13.3-14.9 0-12.1-11.6-14.8-16.8-13.9-2.9.5-4.5 2-11.8 2.4-2-.2-12-3.1-12-14V316c.2-12.3 13.2-18 25.5-16.9 32.3 2.8 47.7 40.7 28.5 65.7-18.3 23.7-76.6 23.2-99.7-20.4-26-49.2 12.7-111.2 87-98.4 33.2 5.7 83.6 35.5 102.4 104.3h45.9c-5.7-17.6-8.9-68.3 42.7-68.3 56.7 0 63.9 39.9 79.8 68.3H460c-12.8-18.3-21.7-38.7-18.9-55.8 5.6-33.8 39.7-18.4 82.4-17.4 66.5.4 102.1-27 103.1-28 3.7-3.1 6.5-15.8 7-17.7 1.3-5.1-3.2-2.4-3.2-2.4-8.7 5.2-30.5 15.2-50.9 15.6-25.3.5-76.2-25.4-81.6-28.2-.3-.4.1 1.2-11-25.5 88.4 58.3 118.3 40.5 145.2 21.7.8-.6 4.3-2.9 3.6-5.7-13.8-48.1-22.4-62.7-34.5-69.6-37-21.6-125-34.7-129.2-35.3.1-.1-.9-.3-.9.7zm60.4 72.8a37.54 37.54 0 0 1 38.9-36.3c33.4 1.2 48.8 42.3 24.4 65.2-24.2 22.7-64.4 4.6-63.3-28.9zm38.6-25.3a26.27 26.27 0 1 0 25.4 27.2 26.19 26.19 0 0 0-25.4-27.2zm4.3 28.8c-15.4 0-15.4-15.6 0-15.6s15.4 15.64 0 15.64z\"],\n    \"symfony\": [512, 512, [], \"f83d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm133.74 143.54c-11.47.41-19.4-6.45-19.77-16.87-.27-9.18 6.68-13.44 6.53-18.85-.23-6.55-10.16-6.82-12.87-6.67-39.78 1.29-48.59 57-58.89 113.85 21.43 3.15 36.65-.72 45.14-6.22 12-7.75-3.34-15.72-1.42-24.56 4-18.16 32.55-19 32 5.3-.36 17.86-25.92 41.81-77.6 35.7-10.76 59.52-18.35 115-58.2 161.72-29 34.46-58.4 39.82-71.58 40.26-24.65.85-41-12.31-41.58-29.84-.56-17 14.45-26.26 24.31-26.59 21.89-.75 30.12 25.67 14.88 34-12.09 9.71.11 12.61 2.05 12.55 10.42-.36 17.34-5.51 22.18-9 24-20 33.24-54.86 45.35-118.35 8.19-49.66 17-78 18.23-82-16.93-12.75-27.08-28.55-49.85-34.72-15.61-4.23-25.12-.63-31.81 7.83-7.92 10-5.29 23 2.37 30.7l12.63 14c15.51 17.93 24 31.87 20.8 50.62-5.06 29.93-40.72 52.9-82.88 39.94-36-11.11-42.7-36.56-38.38-50.62 7.51-24.15 42.36-11.72 34.62 13.6-2.79 8.6-4.92 8.68-6.28 13.07-4.56 14.77 41.85 28.4 51-1.39 4.47-14.52-5.3-21.71-22.25-39.85-28.47-31.75-16-65.49 2.95-79.67C204.23 140.13 251.94 197 262 205.29c37.17-109 100.53-105.46 102.43-105.53 25.16-.81 44.19 10.59 44.83 28.65.25 7.69-4.17 22.59-19.52 23.13z\"],\n    \"teamspeak\": [512, 512, [], \"f4f9\", \"M244.2 346.79c2.4-12.3-12-30-32.4-48.7-20.9-19.2-48.2-39.1-63.4-46.6-21.7-12-41.7-1.8-46.3 22.7-5 26.2 0 51.4 14.5 73.9 10.2 15.5 25.4 22.7 43.4 24 11.6.6 52.5 2.2 61.7-1 11.9-4.3 20.1-11.8 22.5-24.3zm205 20.8a5.22 5.22 0 0 0-8.3 2.4c-8 25.4-44.7 112.5-172.1 121.5-149.7 10.5 80.3 43.6 145.4-6.4 22.7-17.4 47.6-35 46.6-85.4-.4-10.1-4.9-26.69-11.6-32.1zm62-122.4c-.3-18.9-8.6-33.4-26-42.2-2.9-1.3-5-2.7-5.9-6.4A222.64 222.64 0 0 0 438.9 103c-1.1-1.5-3.5-3.2-2.2-5 8.5-11.5-.3-18-7-24.4Q321.4-31.11 177.4 13.09c-40.1 12.3-73.9 35.6-102 67.4-4 4.3-6.7 9.1-3 14.5 3 4 1.3 6.2-1 9.3C51.6 132 38.2 162.59 32.1 196c-.7 4.3-2.9 6-6.4 7.8-14.2 7-22.5 18.5-24.9 34L0 264.29v20.9c0 30.8 21 50.4 51.8 49 7.7-.3 11.7-4.3 12-11.5 2-77.5-2.4-95.4 3.7-125.8C92.1 72.39 234.3 5 345.3 65.39 411.4 102 445.7 159 447.6 234.79c.8 28.2 0 56.5 0 84.6 0 7 2.2 12.5 9.4 14.2 24.1 5 49.2-12 53.2-36.7 2.9-17.1 1-34.5 1-51.7zm-159.6 131.5c36.5 2.8 59.3-28.5 58.4-60.5-2.1-45.2-66.2-16.5-87.8-8-73.2 28.1-45 54.9-22.2 60.8z\"],\n    \"telegram\": [496, 512, [], \"f2c6\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm121.8 169.9l-40.7 191.8c-3 13.6-11.1 16.9-22.4 10.5l-62-45.7-29.9 28.8c-3.3 3.3-6.1 6.1-12.5 6.1l4.4-63.1 114.9-103.8c5-4.4-1.1-6.9-7.7-2.5l-142 89.4-61.2-19.1c-13.3-4.2-13.6-13.3 2.8-19.7l239.1-92.2c11.1-4 20.8 2.7 17.2 19.5z\"],\n    \"telegram-plane\": [448, 512, [], \"f3fe\", \"M446.7 98.6l-67.6 318.8c-5.1 22.5-18.4 28.1-37.3 17.5l-103-75.9-49.7 47.8c-5.5 5.5-10.1 10.1-20.7 10.1l7.4-104.9 190.9-172.5c8.3-7.4-1.8-11.5-12.9-4.1L117.8 284 16.2 252.2c-22.1-6.9-22.5-22.1 4.6-32.7L418.2 66.4c18.4-6.9 34.5 4.1 28.5 32.2z\"],\n    \"tencent-weibo\": [384, 512, [], \"f1d5\", \"M72.3 495.8c1.4 19.9-27.6 22.2-29.7 2.9C31 368.8 73.7 259.2 144 185.5c-15.6-34 9.2-77.1 50.6-77.1 30.3 0 55.1 24.6 55.1 55.1 0 44-49.5 70.8-86.9 45.1-65.7 71.3-101.4 169.8-90.5 287.2zM192 .1C66.1.1-12.3 134.3 43.7 242.4 52.4 259.8 79 246.9 70 229 23.7 136.4 91 29.8 192 29.8c75.4 0 136.9 61.4 136.9 136.9 0 90.8-86.9 153.9-167.7 133.1-19.1-4.1-25.6 24.4-6.6 29.1 110.7 23.2 204-60 204-162.3C358.6 74.7 284 .1 192 .1z\"],\n    \"the-red-yeti\": [512, 512, [], \"f69d\", \"M488.23 241.7l20.7 7.1c-9.6-23.9-23.9-37-31.7-44.8l7.1-18.2c.2 0 12.3-27.8-2.5-30.7-.6-11.3-6.6-27-18.4-27-7.6-10.6-17.7-12.3-30.7-5.9a122.2 122.2 0 0 0-25.3 16.5c-5.3-6.4-3 .4-3-29.8-37.1-24.3-45.4-11.7-74.8 3l.5.5a239.36 239.36 0 0 0-68.4-13.3c-5.5-8.7-18.6-19.1-25.1-25.1l24.8 7.1c-5.5-5.5-26.8-12.9-34.2-15.2 18.2-4.1 29.8-20.8 42.5-33-34.9-10.1-67.9-5.9-97.9 11.8l12-44.2L182 0c-31.6 24.2-33 41.9-33.7 45.5-.9-2.4-6.3-19.6-15.2-27a35.12 35.12 0 0 0-.5 25.3c3 8.4 5.9 14.8 8.4 18.9-16-3.3-28.3-4.9-49.2 0h-3.7l33 14.3a194.26 194.26 0 0 0-46.7 67.4l-1.7 8.4 1.7 1.7 7.6-4.7c-3.3 11.6-5.3 19.4-6.6 25.8a200.18 200.18 0 0 0-27.8 40.3c-15 1-31.8 10.8-40.3 14.3l3 3.4 28.8 1c-.5 1-.7 2.2-1.2 3.2-7.3 6.4-39.8 37.7-33 80.7l20.2-22.4c.5 1.7.7 3.4 1.2 5.2 0 25.5.4 89.6 64.9 150.5 43.6 40 96 60.2 157.5 60.2 121.7 0 223-87.3 223-211.5 6.8-9.7-1.2 3 16.7-25.1l13 14.3 2.5-.5A181.84 181.84 0 0 0 495 255a44.74 44.74 0 0 0-6.8-13.3zM398 111.2l-.5 21.9c5.5 18.1 16.9 17.2 22.4 17.2l-3.4-4.7 22.4-5.4a242.44 242.44 0 0 1-27 0c12.8-2.1 33.3-29 43-11.3 3.4 7.6 6.4 17.2 9.3 27.8l1.7-5.9a56.38 56.38 0 0 1-1.7-15.2c5.4.5 8.8 3.4 9.3 10.1.5 6.4 1.7 14.8 3.4 25.3l4.7-11.3c4.6 0 4.5-3.6-2.5 20.7-20.9-8.7-35.1-8.4-46.5-8.4l18.2-16c-25.3 8.2-33 10.8-54.8 20.9-1.1-5.4-5-13.5-16-19.9-3.2 3.8-2.8.9-.7 14.8h-2.5a62.32 62.32 0 0 0-8.4-23.1l4.2-3.4c8.4-7.1 11.8-14.3 10.6-21.9-.5-6.4-5.4-13.5-13.5-20.7 5.6-3.4 15.2-.4 28.3 8.5zm-39.6-10.1c2.7 1.9 11.4 5.4 18.9 17.2 4.2 8.4 4 9.8 3.4 11.1-.5 2.4-.5 4.3-3 7.1-1.7 2.5-5.4 4.7-11.8 7.6-7.6-13-16.5-23.6-27.8-31.2zM91 143.1l1.2-1.7c1.2-2.9 4.2-7.6 9.3-15.2l2.5-3.4-13 12.3 5.4-4.7-10.1 9.3-4.2 1.2c12.3-24.1 23.1-41.3 32.5-50.2 9.3-9.3 16-16 20.2-19.4l-6.4 1.2c-11.3-4.2-19.4-7.1-24.8-8.4 2.5-.5 3.7-.5 3.2-.5 10.3 0 17.5.5 20.9 1.2a52.35 52.35 0 0 0 16 2.5l.5-1.7-8.4-35.8 13.5 29a42.89 42.89 0 0 0 5.9-14.3c1.7-6.4 5.4-13 10.1-19.4s7.6-10.6 9.3-11.3a234.68 234.68 0 0 0-6.4 25.3l-1.7 7.1-.5 4.7 2.5 2.5C190.4 39.9 214 34 239.8 34.5l21.1.5c-11.8 13.5-27.8 21.9-48.5 24.8a201.26 201.26 0 0 1-23.4 2.9l-.2-.5-2.5-1.2a20.75 20.75 0 0 0-14 2c-2.5-.2-4.9-.5-7.1-.7l-2.5 1.7.5 1.2c2 .2 3.9.5 6.2.7l-2 3.4 3.4-.5-10.6 11.3c-4.2 3-5.4 6.4-4.2 9.3l5.4-3.4h1.2a39.4 39.4 0 0 1 25.3-15.2v-3c6.4.5 13 1 19.4 1.2 6.4 0 8.4.5 5.4 1.2a189.6 189.6 0 0 1 20.7 13.5c13.5 10.1 23.6 21.9 30 35.4 8.8 18.2 13.5 37.1 13.5 56.6a141.13 141.13 0 0 1-3 28.3 209.91 209.91 0 0 1-16 46l2.5.5c18.2-19.7 41.9-16 49.2-16l-6.4 5.9 22.4 17.7-1.7 30.7c-5.4-12.3-16.5-21.1-33-27.8 16.5 14.8 23.6 21.1 21.9 20.2-4.8-2.8-3.5-1.9-10.8-3.7 4.1 4.1 17.5 18.8 18.2 20.7l.2.2-.2.2c0 1.8 1.6-1.2-14 22.9-75.2-15.3-106.27-42.7-141.2-63.2l11.8 1.2c-11.8-18.5-15.6-17.7-38.4-26.1L149 225c-8.8-3-18.2-3-28.3.5l7.6-10.6-1.2-1.7c-14.9 4.3-19.8 9.2-22.6 11.3-1.1-5.5-2.8-12.4-12.3-28.8l-1.2 27-13.2-5c1.5-25.2 5.4-50.5 13.2-74.6zm276.5 330c-49.9 25-56.1 22.4-59 23.9-29.8-11.8-50.9-31.7-63.5-58.8l30 16.5c-9.8-9.3-18.3-16.5-38.4-44.3l11.8 23.1-17.7-7.6c14.2 21.1 23.5 51.7 66.6 73.5-120.8 24.2-199-72.1-200.9-74.3a262.57 262.57 0 0 0 35.4 24.8c3.4 1.7 7.1 2.5 10.1 1.2l-16-20.7c9.2 4.2 9.5 4.5 69.1 29-42.5-20.7-73.8-40.8-93.2-60.2-.5 6.4-1.2 10.1-1.2 10.1a80.25 80.25 0 0 1 20.7 26.6c-39-18.9-57.6-47.6-71.3-82.6 49.9 55.1 118.9 37.5 120.5 37.1 34.8 16.4 69.9 23.6 113.9 10.6 3.3 0 20.3 17 25.3 39.1l4.2-3-2.5-23.6c9 9 24.9 22.6 34.4 13-15.6-5.3-23.5-9.5-29.5-31.7 4.6 4.2 7.6 9 27.8 15l1.2-1.2-10.5-14.2c11.7-4.8-3.5 1 32-10.8 4.3 34.3 9 49.2.7 89.5zm115.3-214.4l-2.5.5 3 9.3c-3.5 5.9-23.7 44.3-71.6 79.7-39.5 29.8-76.6 39.1-80.9 40.3l-7.6-7.1-1.2 3 14.3 16-7.1-4.7 3.4 4.2h-1.2l-21.9-13.5 9.3 26.6-19-27.9-1.2 2.5 7.6 29c-6.1-8.2-21-32.6-56.8-39.6l32.5 21.2a214.82 214.82 0 0 1-93.2-6.4c-4.2-1.2-8.9-2.5-13.5-4.2l1.2-3-44.8-22.4 26.1 22.4c-57.7 9.1-113-25.4-126.4-83.4l-2.5-16.4-22.27 22.3c19.5-57.5 25.6-57.9 51.4-70.1-9.1-5.3-1.6-3.3-38.4-9.3 15.8-5.8 33-15.4 73 5.2a18.5 18.5 0 0 1 3.7-1.7c.6-3.2.4-.8 1-11.8 3.9 10 3.6 8.7 3 9.3l1.7.5c12.7-6.5 8.9-4.5 17-8.9l-5.4 13.5 22.3-5.8-8.4 8.4 2.5 2.5c4.5-1.8 30.3 3.4 40.8 16l-23.6-2.5c39.4 23 51.5 54 55.8 69.6l1.7-1.2c-2.8-22.3-12.4-33.9-16-40.1 4.2 5 39.2 34.6 110.4 46-11.3-.5-23.1 5.4-34.9 18.9l46.7-20.2-9.3 21.9c7.6-10.1 14.8-23.6 21.2-39.6v-.5l1.2-3-1.2 16c13.5-41.8 25.3-78.5 35.4-109.7l13.5-27.8v-2l-5.4-4.2h10.1l5.9 4.2 2.5-1.2-3.4-16 12.3 18.9 41.8-20.2-14.8 13 .5 2.9 17.7-.5a184 184 0 0 1 33 4.2l-23.6 2.5-1.2 3 26.6 23.1a254.21 254.21 0 0 1 27 32c-11.2-3.3-10.3-3.4-21.2-3.4l12.3 32.5zm-6.1-71.3l-3.9 13-14.3-11.8zm-254.8 7.1c1.7 10.6 4.7 17.7 8.8 21.9-9.3 6.6-27.5 13.9-46.5 16l.5 1.2a50.22 50.22 0 0 0 24.8-2.5l-7.1 13c4.2-1.7 10.1-7.1 17.7-14.8 11.9-5.5 12.7-5.1 20.2-16-12.7-6.4-15.7-13.7-18.4-18.8zm3.7-102.3c-6.4-3.4-10.6 3-12.3 18.9s2.5 29.5 11.8 39.6 18.2 10.6 26.1 3 3.4-23.6-11.3-47.7a39.57 39.57 0 0 0-14.27-13.8zm-4.7 46.3c5.4 2.2 10.5 1.9 12.3-10.6v-4.7l-1.2.5c-4.3-3.1-2.5-4.5-1.7-6.2l.5-.5c-.9-1.2-5-8.1-12.5 4.7-.5-13.5.5-21.9 3-24.8 1.2-2.5 4.7-1.2 11.3 4.2 6.4 5.4 11.3 16 15.2 32.5 6.5 28-19.8 26.2-26.9 4.9zm-45-5.5c1.6.3 9.3-1.1 9.3-14.8h-.5c-5.4-1.1-2.2-5.5-.7-5.9-1.7-3-3.4-4.2-5.4-4.7-8.1 0-11.6 12.7-8.1 21.2a7.51 7.51 0 0 0 5.43 4.2zM216 82.9l-2.5.5.5 3a48.94 48.94 0 0 1 26.1 5.9c-2.5-5.5-10-14.3-28.3-14.3l.5 2.5zm-71.8 49.4c21.7 16.8 16.5 21.4 46.5 23.6l-2.9-4.7a42.67 42.67 0 0 0 14.8-28.3c1.7-16-1.2-29.5-8.8-41.3l13-7.6a2.26 2.26 0 0 0-.5-1.7 14.21 14.21 0 0 0-13.5 1.7c-12.7 6.7-28 20.9-29 22.4-1.7 1.7-3.4 5.9-5.4 13.5a99.61 99.61 0 0 0-2.9 23.6c-4.7-8-10.5-6.4-19.9-5.9l7.1 7.6c-16.5 0-23.3 15.4-23.6 16 6.8 0 4.6-7.6 30-12.3-4.3-6.3-3.3-5-4.9-6.6zm18.7-18.7c1.2-7.6 3.4-13 6.4-17.2 5.4-6.4 10.6-10.1 16-11.8 4.2-1.7 7.1 1.2 10.1 9.3a72.14 72.14 0 0 1 3 25.3c-.5 9.3-3.4 17.2-8.4 23.1-2.9 3.4-5.4 5.9-6.4 7.6a39.21 39.21 0 0 1-11.3-.5l-7.1-3.4-5.4-6.4c.8-10 1.3-18.8 3.1-26zm42 56.1c-34.8 14.4-34.7 14-36.1 14.3-20.8 4.7-19-24.4-18.9-24.8l5.9-1.2-.5-2.5c-20.2-2.6-31 4.2-32.5 4.9.5.5 3 3.4 5.9 9.3 4.2-6.4 8.8-10.1 15.2-10.6a83.47 83.47 0 0 0 1.7 33.7c.1.5 2.6 17.4 27.5 24.1 11.3 3 27 1.2 48.9-5.4l-9.2.5c-4.2-14.8-6.4-24.8-5.9-29.5 11.3-8.8 21.9-11.3 30.7-7.6h2.5l-11.8-7.6-7.1.5c-5.9 1.2-12.3 4.2-19.4 8.4z\"],\n    \"themeco\": [448, 512, [], \"f5c6\", \"M202.9 8.43c9.9-5.73 26-5.82 35.95-.21L430 115.85c10 5.6 18 19.44 18 30.86V364c0 11.44-8.06 25.29-18 31L238.81 503.74c-9.93 5.66-26 5.57-35.85-.21L17.86 395.12C8 389.34 0 375.38 0 364V146.71c0-11.44 8-25.36 17.91-31.08zm-77.4 199.83c-15.94 0-31.89.14-47.83.14v101.45H96.8V280h28.7c49.71 0 49.56-71.74 0-71.74zm140.14 100.29l-30.73-34.64c37-7.51 34.8-65.23-10.87-65.51-16.09 0-32.17-.14-48.26-.14v101.59h19.13v-33.91h18.41l29.56 33.91h22.76zm-41.59-82.32c23.34 0 23.26 32.46 0 32.46h-29.13v-32.46zm-95.56-1.6c21.18 0 21.11 38.85 0 38.85H96.18v-38.84zm192.65-18.25c-68.46 0-71 105.8 0 105.8 69.48-.01 69.41-105.8 0-105.8zm0 17.39c44.12 0 44.8 70.86 0 70.86s-44.43-70.86 0-70.86z\"],\n    \"themeisle\": [512, 512, [], \"f2b2\", \"M208 88.286c0-10 6.286-21.714 17.715-21.714 11.142 0 17.714 11.714 17.714 21.714 0 10.285-6.572 21.714-17.714 21.714C214.286 110 208 98.571 208 88.286zm304 160c0 36.001-11.429 102.286-36.286 129.714-22.858 24.858-87.428 61.143-120.857 70.572l-1.143.286v32.571c0 16.286-12.572 30.571-29.143 30.571-10 0-19.429-5.714-24.572-14.286-5.427 8.572-14.856 14.286-24.856 14.286-10 0-19.429-5.714-24.858-14.286-5.142 8.572-14.571 14.286-24.57 14.286-10.286 0-19.429-5.714-24.858-14.286-5.143 8.572-14.571 14.286-24.571 14.286-18.857 0-29.429-15.714-29.429-32.857-16.286 12.285-35.715 19.428-56.571 19.428-22 0-43.429-8.285-60.286-22.857 10.285-.286 20.571-2.286 30.285-5.714-20.857-5.714-39.428-18.857-52-36.286 21.37 4.645 46.209 1.673 67.143-11.143-22-22-56.571-58.857-68.572-87.428C1.143 321.714 0 303.714 0 289.429c0-49.714 20.286-160 86.286-160 10.571 0 18.857 4.858 23.143 14.857a158.792 158.792 0 0 1 12-15.428c2-2.572 5.714-5.429 7.143-8.286 7.999-12.571 11.714-21.142 21.714-34C182.571 45.428 232 17.143 285.143 17.143c6 0 12 .285 17.714 1.143C313.714 6.571 328.857 0 344.572 0c14.571 0 29.714 6 40 16.286.857.858 1.428 2.286 1.428 3.428 0 3.714-10.285 13.429-12.857 16.286 4.286 1.429 15.714 6.858 15.714 12 0 2.857-2.857 5.143-4.571 7.143 31.429 27.714 49.429 67.143 56.286 108 4.286-5.143 10.285-8.572 17.143-8.572 10.571 0 20.857 7.144 28.571 14.001C507.143 187.143 512 221.714 512 248.286zM188 89.428c0 18.286 12.571 37.143 32.286 37.143 19.714 0 32.285-18.857 32.285-37.143 0-18-12.571-36.857-32.285-36.857-19.715 0-32.286 18.858-32.286 36.857zM237.714 194c0-19.714 3.714-39.143 8.571-58.286-52.039 79.534-13.531 184.571 68.858 184.571 21.428 0 42.571-7.714 60-20 2-7.429 3.714-14.857 3.714-22.572 0-14.286-6.286-21.428-20.572-21.428-4.571 0-9.143.857-13.429 1.714-63.343 12.668-107.142 3.669-107.142-63.999zm-41.142 254.858c0-11.143-8.858-20.857-20.286-20.857-11.429 0-20 9.715-20 20.857v32.571c0 11.143 8.571 21.142 20 21.142 11.428 0 20.286-9.715 20.286-21.142v-32.571zm49.143 0c0-11.143-8.572-20.857-20-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20-10 20-21.142v-32.571zm49.713 0c0-11.143-8.857-20.857-20.285-20.857-11.429 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.857 21.142 20.286 21.142 11.428 0 20.285-9.715 20.285-21.142v-32.571zm49.715 0c0-11.143-8.857-20.857-20.286-20.857-11.428 0-20.286 9.715-20.286 20.857v32.571c0 11.143 8.858 21.142 20.286 21.142 11.429 0 20.286-10 20.286-21.142v-32.571zM421.714 286c-30.857 59.142-90.285 102.572-158.571 102.572-96.571 0-160.571-84.572-160.571-176.572 0-16.857 2-33.429 6-49.714-20 33.715-29.714 72.572-29.714 111.429 0 60.286 24.857 121.715 71.429 160.857 5.143-9.714 14.857-16.286 26-16.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.571-14.286 24.858-14.286 10 0 19.428 5.714 24.571 14.286 5.429-8.571 14.857-14.286 24.858-14.286 10 0 19.428 5.714 24.857 14.286 5.143-8.571 14.571-14.286 24.572-14.286 10.857 0 20.857 6.572 25.714 16 43.427-36.286 68.569-92 71.426-148.286zm10.572-99.714c0-53.714-34.571-105.714-92.572-105.714-30.285 0-58.571 15.143-78.857 36.857C240.862 183.812 233.41 254 302.286 254c28.805 0 97.357-28.538 84.286 36.857 28.857-26 45.714-65.714 45.714-104.571z\"],\n    \"think-peaks\": [576, 512, [], \"f731\", \"M465.4 409.4l87.1-150.2-32-.3-55.1 95L259.2 0 23 407.4l32 .3L259.2 55.6zm-355.3-44.1h32.1l117.4-202.5L463 511.9l32.5.1-235.8-404.6z\"],\n    \"trade-federation\": [496, 512, [], \"f513\", \"M248 8.8c-137 0-248 111-248 248s111 248 248 248 248-111 248-248-111-248-248-248zm0 482.8c-129.7 0-234.8-105.1-234.8-234.8S118.3 22 248 22s234.8 105.1 234.8 234.8S377.7 491.6 248 491.6zm155.1-328.5v-46.8H209.3V198H54.2l36.7 46h117.7v196.8h48.8V245h83.3v-47h-83.3v-34.8h145.7zm-73.3 45.1v23.9h-82.9v197.4h-26.8V232.1H96.3l-20.1-23.9h143.9v-80.6h171.8V152h-145v56.2zm-161.3-69l-12.4-20.7 2.1 23.8-23.5 5.4 23.3 5.4-2.1 24 12.3-20.5 22.2 9.5-15.7-18.1 15.8-18.1zm-29.6-19.7l9.3-11.5-12.7 5.9-8-12.4 1.7 13.9-14.3 3.8 13.7 2.7-.8 14.7 6.8-12.2 13.8 5.3zm165.4 145.2l-13.1 5.6-7.3-12.2 1.3 14.2-13.9 3.2 13.9 3.2-1.2 14.2 7.3-12.2 13.1 5.5-9.4-10.7zm106.9-77.2l-20.9 9.1-12-19.6 2.2 22.7-22.3 5.4 22.2 4.9-1.8 22.9 11.5-19.6 21.2 8.8-15.1-17zM248 29.9c-125.3 0-226.9 101.6-226.9 226.9S122.7 483.7 248 483.7s226.9-101.6 226.9-226.9S373.3 29.9 248 29.9zM342.6 196v51h-83.3v195.7h-52.7V245.9H89.9l-40-49.9h157.4v-81.6h197.8v50.7H259.4V196zM248 43.2c60.3 0 114.8 25 153.6 65.2H202.5V190H45.1C73.1 104.8 153.4 43.2 248 43.2zm0 427.1c-117.9 0-213.6-95.6-213.6-213.5 0-21.2 3.1-41.8 8.9-61.1L87.1 252h114.7v196.8h64.6V253h83.3v-62.7h-83.2v-19.2h145.6v-50.8c30.8 37 49.3 84.6 49.3 136.5.1 117.9-95.5 213.5-213.4 213.5zM178.8 275l-11-21.4 1.7 24.5-23.7 3.9 23.8 5.9-3.7 23.8 13-20.9 21.5 10.8-15.8-18.8 16.9-17.1z\"],\n    \"trello\": [448, 512, [], \"f181\", \"M392.3 32H56.1C25.1 32 0 57.1 0 88c-.1 0 0-4 0 336 0 30.9 25.1 56 56 56h336.2c30.8-.2 55.7-25.2 55.7-56V88c.1-30.8-24.8-55.8-55.6-56zM197 371.3c-.2 14.7-12.1 26.6-26.9 26.6H87.4c-14.8.1-26.9-11.8-27-26.6V117.1c0-14.8 12-26.9 26.9-26.9h82.9c14.8 0 26.9 12 26.9 26.9v254.2zm193.1-112c0 14.8-12 26.9-26.9 26.9h-81c-14.8 0-26.9-12-26.9-26.9V117.2c0-14.8 12-26.9 26.8-26.9h81.1c14.8 0 26.9 12 26.9 26.9v142.1z\"],\n    \"tripadvisor\": [576, 512, [], \"f262\", \"M166.4 280.521c0 13.236-10.73 23.966-23.966 23.966s-23.966-10.73-23.966-23.966 10.73-23.966 23.966-23.966 23.966 10.729 23.966 23.966zm264.962-23.956c-13.23 0-23.956 10.725-23.956 23.956 0 13.23 10.725 23.956 23.956 23.956 13.23 0 23.956-10.725 23.956-23.956-.001-13.231-10.726-23.956-23.956-23.956zm89.388 139.49c-62.667 49.104-153.276 38.109-202.379-24.559l-30.979 46.325-30.683-45.939c-48.277 60.39-135.622 71.891-197.885 26.055-64.058-47.158-77.759-137.316-30.601-201.374A186.762 186.762 0 0 0 0 139.416l90.286-.05a358.48 358.48 0 0 1 197.065-54.03 350.382 350.382 0 0 1 192.181 53.349l96.218.074a185.713 185.713 0 0 0-28.352 57.649c46.793 62.747 34.964 151.37-26.648 199.647zM259.366 281.761c-.007-63.557-51.535-115.075-115.092-115.068C80.717 166.7 29.2 218.228 29.206 281.785c.007 63.557 51.535 115.075 115.092 115.068 63.513-.075 114.984-51.539 115.068-115.052v-.04zm28.591-10.455c5.433-73.44 65.51-130.884 139.12-133.022a339.146 339.146 0 0 0-139.727-27.812 356.31 356.31 0 0 0-140.164 27.253c74.344 1.582 135.299 59.424 140.771 133.581zm251.706-28.767c-21.992-59.634-88.162-90.148-147.795-68.157-59.634 21.992-90.148 88.162-68.157 147.795v.032c22.038 59.607 88.198 90.091 147.827 68.113 59.615-22.004 90.113-88.162 68.125-147.783zm-326.039 37.975v.115c-.057 39.328-31.986 71.163-71.314 71.106-39.328-.057-71.163-31.986-71.106-71.314.057-39.328 31.986-71.163 71.314-71.106 39.259.116 71.042 31.94 71.106 71.199zm-24.512 0v-.084c-.051-25.784-20.994-46.645-46.778-46.594-25.784.051-46.645 20.994-46.594 46.777.051 25.784 20.994 46.645 46.777 46.594 25.726-.113 46.537-20.968 46.595-46.693zm313.423 0v.048c-.02 39.328-31.918 71.194-71.247 71.173s-71.194-31.918-71.173-71.247c.02-39.328 31.918-71.194 71.247-71.173 39.29.066 71.121 31.909 71.173 71.199zm-24.504-.008c-.009-25.784-20.918-46.679-46.702-46.67-25.784.009-46.679 20.918-46.67 46.702.009 25.784 20.918 46.678 46.702 46.67 25.765-.046 46.636-20.928 46.67-46.693v-.009z\"],\n    \"tumblr\": [320, 512, [], \"f173\", \"M309.8 480.3c-13.6 14.5-50 31.7-97.4 31.7-120.8 0-147-88.8-147-140.6v-144H17.9c-5.5 0-10-4.5-10-10v-68c0-7.2 4.5-13.6 11.3-16 62-21.8 81.5-76 84.3-117.1.8-11 6.5-16.3 16.1-16.3h70.9c5.5 0 10 4.5 10 10v115.2h83c5.5 0 10 4.4 10 9.9v81.7c0 5.5-4.5 10-10 10h-83.4V360c0 34.2 23.7 53.6 68 35.8 4.8-1.9 9-3.2 12.7-2.2 3.5.9 5.8 3.4 7.4 7.9l22 64.3c1.8 5 3.3 10.6-.4 14.5z\"],\n    \"tumblr-square\": [448, 512, [], \"f174\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-82.3 364.2c-8.5 9.1-31.2 19.8-60.9 19.8-75.5 0-91.9-55.5-91.9-87.9v-90h-29.7c-3.4 0-6.2-2.8-6.2-6.2v-42.5c0-4.5 2.8-8.5 7.1-10 38.8-13.7 50.9-47.5 52.7-73.2.5-6.9 4.1-10.2 10-10.2h44.3c3.4 0 6.2 2.8 6.2 6.2v72h51.9c3.4 0 6.2 2.8 6.2 6.2v51.1c0 3.4-2.8 6.2-6.2 6.2h-52.1V321c0 21.4 14.8 33.5 42.5 22.4 3-1.2 5.6-2 8-1.4 2.2.5 3.6 2.1 4.6 4.9l13.8 40.2c1 3.2 2 6.7-.3 9.1z\"],\n    \"twitch\": [448, 512, [], \"f1e8\", \"M40.1 32L10 108.9v314.3h107V480h60.2l56.8-56.8h87l117-117V32H40.1zm357.8 254.1L331 353H224l-56.8 56.8V353H76.9V72.1h321v214zM331 149v116.9h-40.1V149H331zm-107 0v116.9h-40.1V149H224z\"],\n    \"twitter\": [512, 512, [], \"f099\", \"M459.37 151.716c.325 4.548.325 9.097.325 13.645 0 138.72-105.583 298.558-298.558 298.558-59.452 0-114.68-17.219-161.137-47.106 8.447.974 16.568 1.299 25.34 1.299 49.055 0 94.213-16.568 130.274-44.832-46.132-.975-84.792-31.188-98.112-72.772 6.498.974 12.995 1.624 19.818 1.624 9.421 0 18.843-1.3 27.614-3.573-48.081-9.747-84.143-51.98-84.143-102.985v-1.299c13.969 7.797 30.214 12.67 47.431 13.319-28.264-18.843-46.781-51.005-46.781-87.391 0-19.492 5.197-37.36 14.294-52.954 51.655 63.675 129.3 105.258 216.365 109.807-1.624-7.797-2.599-15.918-2.599-24.04 0-57.828 46.782-104.934 104.934-104.934 30.213 0 57.502 12.67 76.67 33.137 23.715-4.548 46.456-13.32 66.599-25.34-7.798 24.366-24.366 44.833-46.132 57.827 21.117-2.273 41.584-8.122 60.426-16.243-14.292 20.791-32.161 39.308-52.628 54.253z\"],\n    \"twitter-square\": [448, 512, [], \"f081\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-48.9 158.8c.2 2.8.2 5.7.2 8.5 0 86.7-66 186.6-186.6 186.6-37.2 0-71.7-10.8-100.7-29.4 5.3.6 10.4.8 15.8.8 30.7 0 58.9-10.4 81.4-28-28.8-.6-53-19.5-61.3-45.5 10.1 1.5 19.2 1.5 29.6-1.2-30-6.1-52.5-32.5-52.5-64.4v-.8c8.7 4.9 18.9 7.9 29.6 8.3a65.447 65.447 0 0 1-29.2-54.6c0-12.2 3.2-23.4 8.9-33.1 32.3 39.8 80.8 65.8 135.2 68.6-9.3-44.5 24-80.6 64-80.6 18.9 0 35.9 7.9 47.9 20.7 14.8-2.8 29-8.3 41.6-15.8-4.9 15.2-15.2 28-28.8 36.1 13.2-1.4 26-5.1 37.8-10.2-8.9 13.1-20.1 24.7-32.9 34z\"],\n    \"typo3\": [448, 512, [], \"f42b\", \"M178.7 78.4c0-24.7 5.4-32.4 13.9-39.4-69.5 8.5-149.3 34-176.3 66.4-5.4 7.7-9.3 20.8-9.3 37.1C7 246 113.8 480 191.1 480c36.3 0 97.3-59.5 146.7-139-7 2.3-11.6 2.3-18.5 2.3-57.2 0-140.6-198.5-140.6-264.9zM301.5 32c-30.1 0-41.7 5.4-41.7 36.3 0 66.4 53.8 198.5 101.7 198.5 26.3 0 78.8-99.7 78.8-182.3 0-40.9-67-52.5-138.8-52.5z\"],\n    \"uber\": [448, 512, [], \"f402\", \"M414.1 32H33.9C15.2 32 0 47.2 0 65.9V446c0 18.8 15.2 34 33.9 34H414c18.7 0 33.9-15.2 33.9-33.9V65.9C448 47.2 432.8 32 414.1 32zM237.6 391.1C163 398.6 96.4 344.2 88.9 269.6h94.4V290c0 3.7 3 6.8 6.8 6.8H258c3.7 0 6.8-3 6.8-6.8v-67.9c0-3.7-3-6.8-6.8-6.8h-67.9c-3.7 0-6.8 3-6.8 6.8v20.4H88.9c7-69.4 65.4-122.2 135.1-122.2 69.7 0 128.1 52.8 135.1 122.2 7.5 74.5-46.9 141.1-121.5 148.6z\"],\n    \"ubuntu\": [496, 512, [], \"f7df\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm52.7 93c8.8-15.2 28.3-20.5 43.5-11.7 15.3 8.8 20.5 28.3 11.7 43.6-8.8 15.2-28.3 20.5-43.5 11.7-15.3-8.9-20.5-28.4-11.7-43.6zM87.4 287.9c-17.6 0-31.9-14.3-31.9-31.9 0-17.6 14.3-31.9 31.9-31.9 17.6 0 31.9 14.3 31.9 31.9 0 17.6-14.3 31.9-31.9 31.9zm28.1 3.1c22.3-17.9 22.4-51.9 0-69.9 8.6-32.8 29.1-60.7 56.5-79.1l23.7 39.6c-51.5 36.3-51.5 112.5 0 148.8L172 370c-27.4-18.3-47.8-46.3-56.5-79zm228.7 131.7c-15.3 8.8-34.7 3.6-43.5-11.7-8.8-15.3-3.6-34.8 11.7-43.6 15.2-8.8 34.7-3.6 43.5 11.7 8.8 15.3 3.6 34.8-11.7 43.6zm.3-69.5c-26.7-10.3-56.1 6.6-60.5 35-5.2 1.4-48.9 14.3-96.7-9.4l22.5-40.3c57 26.5 123.4-11.7 128.9-74.4l46.1.7c-2.3 34.5-17.3 65.5-40.3 88.4zm-5.9-105.3c-5.4-62-71.3-101.2-128.9-74.4l-22.5-40.3c47.9-23.7 91.5-10.8 96.7-9.4 4.4 28.3 33.8 45.3 60.5 35 23.1 22.9 38 53.9 40.2 88.5l-46 .6z\"],\n    \"uikit\": [448, 512, [], \"f403\", \"M443.9 128v256L218 512 0 384V169.7l87.6 45.1v117l133.5 75.5 135.8-75.5v-151l-101.1-57.6 87.6-53.1L443.9 128zM308.6 49.1L223.8 0l-88.6 54.8 86 47.3 87.4-53z\"],\n    \"uniregistry\": [384, 512, [], \"f404\", \"M192 480c39.5 0 76.2-11.8 106.8-32.2H85.3C115.8 468.2 152.5 480 192 480zm-89.1-193.1v-12.4H0v12.4c0 2.5 0 5 .1 7.4h103.1c-.2-2.4-.3-4.9-.3-7.4zm20.5 57H8.5c2.6 8.5 5.8 16.8 9.6 24.8h138.3c-12.9-5.7-24.1-14.2-33-24.8zm-17.7-34.7H1.3c.9 7.6 2.2 15 3.9 22.3h109.7c-4-6.9-7.2-14.4-9.2-22.3zm-2.8-69.3H0v17.3h102.9zm0-173.2H0v4.9h102.9zm0-34.7H0v2.5h102.9zm0 69.3H0v7.4h102.9zm0 104H0v14.8h102.9zm0-69.3H0v9.9h102.9zm0 34.6H0V183h102.9zm166.2 160.9h109.7c1.8-7.3 3.1-14.7 3.9-22.3H278.3c-2.1 7.9-5.2 15.4-9.2 22.3zm12-185.7H384V136H281.1zm0 37.2H384v-12.4H281.1zm0-74.3H384v-7.4H281.1zm0-76.7v2.5H384V32zm-203 410.9h227.7c11.8-8.7 22.7-18.6 32.2-29.7H44.9c9.6 11 21.4 21 33.2 29.7zm203-371.3H384v-4.9H281.1zm0 148.5H384v-14.8H281.1zM38.8 405.7h305.3c6.7-8.5 12.6-17.6 17.8-27.2H23c5.2 9.6 9.2 18.7 15.8 27.2zm188.8-37.1H367c3.7-8 5.8-16.2 8.5-24.8h-115c-8.8 10.7-20.1 19.2-32.9 24.8zm53.5-81.7c0 2.5-.1 5-.4 7.4h103.1c.1-2.5.2-4.9.2-7.4v-12.4H281.1zm0-29.7H384v-17.3H281.1z\"],\n    \"untappd\": [640, 512, [], \"f405\", \"M401.3 49.9c-79.8 160.1-84.6 152.5-87.9 173.2l-5.2 32.8c-1.9 12-6.6 23.5-13.7 33.4L145.6 497.1c-7.6 10.6-20.4 16.2-33.4 14.6-40.3-5-77.8-32.2-95.3-68.5-5.7-11.8-4.5-25.8 3.1-36.4l148.9-207.9c7.1-9.9 16.4-18 27.2-23.7l29.3-15.5c18.5-9.8 9.7-11.9 135.6-138.9 1-4.8 1-7.3 3.6-8 3-.7 6.6-1 6.3-4.6l-.4-4.6c-.2-1.9 1.3-3.6 3.2-3.6 4.5-.1 13.2 1.2 25.6 10 12.3 8.9 16.4 16.8 17.7 21.1.6 1.8-.6 3.7-2.4 4.2l-4.5 1.1c-3.4.9-2.5 4.4-2.3 7.4.1 2.8-2.3 3.6-6.5 6.1zM230.1 36.4c3.4.9 2.5 4.4 2.3 7.4-.2 2.7 2.1 3.5 6.4 6 7.9 15.9 15.3 30.5 22.2 44 .7 1.3 2.3 1.5 3.3.5 11.2-12 24.6-26.2 40.5-42.6 1.3-1.4 1.4-3.5.1-4.9-8-8.2-16.5-16.9-25.6-26.1-1-4.7-1-7.3-3.6-8-3-.8-6.6-1-6.3-4.6.3-3.3 1.4-8.1-2.8-8.2-4.5-.1-13.2 1.1-25.6 10-12.3 8.9-16.4 16.8-17.7 21.1-1.4 4.2 3.6 4.6 6.8 5.4zM620 406.7L471.2 198.8c-13.2-18.5-26.6-23.4-56.4-39.1-11.2-5.9-14.2-10.9-30.5-28.9-1-1.1-2.9-.9-3.6.5-46.3 88.8-47.1 82.8-49 94.8-1.7 10.7-1.3 20 .3 29.8 1.9 12 6.6 23.5 13.7 33.4l148.9 207.9c7.6 10.6 20.2 16.2 33.1 14.7 40.3-4.9 78-32 95.7-68.6 5.4-11.9 4.3-25.9-3.4-36.6z\"],\n    \"ups\": [384, 512, [], \"f7e0\", \"M103.2 303c-5.2 3.6-32.6 13.1-32.6-19V180H37.9v102.6c0 74.9 80.2 51.1 97.9 39V180h-32.6zM4 74.82v220.9c0 103.7 74.9 135.2 187.7 184.1 112.4-48.9 187.7-80.2 187.7-184.1V74.82c-116.3-61.6-281.8-49.6-375.4 0zm358.1 220.9c0 86.6-53.2 113.6-170.4 165.3-117.5-51.8-170.5-78.7-170.5-165.3v-126.4c102.3-93.8 231.6-100 340.9-89.8zm-209.6-107.4v212.8h32.7v-68.7c24.4 7.3 71.7-2.6 71.7-78.5 0-97.4-80.7-80.92-104.4-65.6zm32.7 117.3v-100.3c8.4-4.2 38.4-12.7 38.4 49.3 0 67.9-36.4 51.8-38.4 51zm79.1-86.4c.1 47.3 51.6 42.5 52.2 70.4.6 23.5-30.4 23-50.8 4.9v30.1c36.2 21.5 81.9 8.1 83.2-33.5 1.7-51.5-54.1-46.6-53.4-73.2.6-20.3 30.6-20.5 48.5-2.2v-28.4c-28.5-22-79.9-9.2-79.7 31.9z\"],\n    \"usb\": [640, 512, [], \"f287\", \"M641.5 256c0 3.1-1.7 6.1-4.5 7.5L547.9 317c-1.4.8-2.8 1.4-4.5 1.4-1.4 0-3.1-.3-4.5-1.1-2.8-1.7-4.5-4.5-4.5-7.8v-35.6H295.7c25.3 39.6 40.5 106.9 69.6 106.9H392V354c0-5 3.9-8.9 8.9-8.9H490c5 0 8.9 3.9 8.9 8.9v89.1c0 5-3.9 8.9-8.9 8.9h-89.1c-5 0-8.9-3.9-8.9-8.9v-26.7h-26.7c-75.4 0-81.1-142.5-124.7-142.5H140.3c-8.1 30.6-35.9 53.5-69 53.5C32 327.3 0 295.3 0 256s32-71.3 71.3-71.3c33.1 0 61 22.8 69 53.5 39.1 0 43.9 9.5 74.6-60.4C255 88.7 273 95.7 323.8 95.7c7.5-20.9 27-35.6 50.4-35.6 29.5 0 53.5 23.9 53.5 53.5s-23.9 53.5-53.5 53.5c-23.4 0-42.9-14.8-50.4-35.6H294c-29.1 0-44.3 67.4-69.6 106.9h310.1v-35.6c0-3.3 1.7-6.1 4.5-7.8 2.8-1.7 6.4-1.4 8.9.3l89.1 53.5c2.8 1.1 4.5 4.1 4.5 7.2z\"],\n    \"usps\": [576, 512, [], \"f7e1\", \"M460.3 241.7c25.8-41.3 15.2-48.8-11.7-48.8h-27c-.1 0-1.5-1.4-10.9 8-11.2 5.6-37.9 6.3-37.9 8.7 0 4.5 70.3-3.1 88.1 0 9.5 1.5-1.5 20.4-4.4 32-.5 4.5 2.4 2.3 3.8.1zm-112.1 22.6c64-21.3 97.3-23.9 102-26.2 4.4-2.9-4.4-6.6-26.2-5.8-51.7 2.2-137.6 37.1-172.6 53.9l-30.7-93.3h196.6c-2.7-28.2-152.9-22.6-337.9-22.6L27 415.8c196.4-97.3 258.9-130.3 321.2-151.5zM94.7 96c253.3 53.7 330 65.7 332.1 85.2 36.4 0 45.9 0 52.4 6.6 21.1 19.7-14.6 67.7-14.6 67.7-4.4 2.9-406.4 160.2-406.4 160.2h423.1L549 96z\"],\n    \"ussunnah\": [512, 512, [], \"f407\", \"M156.8 285.1l5.7 14.4h-8.2c-1.3-3.2-3.1-7.7-3.8-9.5-2.5-6.3-1.1-8.4 0-10 1.9-2.7 3.2-4.4 3.6-5.2 0 2.2.8 5.7 2.7 10.3zm297.3 18.8c-2.1 13.8-5.7 27.1-10.5 39.7l43 23.4-44.8-18.8c-5.3 13.2-12 25.6-19.9 37.2l34.2 30.2-36.8-26.4c-8.4 11.8-18 22.6-28.7 32.3l24.9 34.7-28.1-31.8c-11 9.6-23.1 18-36.1 25.1l15.7 37.2-19.3-35.3c-13.1 6.8-27 12.1-41.6 15.9l6.7 38.4-10.5-37.4c-14.3 3.4-29.2 5.3-44.5 5.4L256 512l-1.9-38.4c-15.3-.1-30.2-2-44.5-5.3L199 505.6l6.7-38.2c-14.6-3.7-28.6-9.1-41.7-15.8l-19.2 35.1 15.6-37c-13-7-25.2-15.4-36.2-25.1l-27.9 31.6 24.7-34.4c-10.7-9.7-20.4-20.5-28.8-32.3l-36.5 26.2 33.9-29.9c-7.9-11.6-14.6-24.1-20-37.3l-44.4 18.7L67.8 344c-4.8-12.7-8.4-26.1-10.5-39.9l-51 9 50.3-14.2c-1.1-8.5-1.7-17.1-1.7-25.9 0-4.7.2-9.4.5-14.1L0 256l56-2.8c1.3-13.1 3.8-25.8 7.5-38.1L6.4 199l58.9 10.4c4-12 9.1-23.5 15.2-34.4l-55.1-30 58.3 24.6C90 159 97.2 149.2 105.3 140L55.8 96.4l53.9 38.7c8.1-8.6 17-16.5 26.6-23.6l-40-55.6 45.6 51.6c9.5-6.6 19.7-12.3 30.3-17.2l-27.3-64.9 33.8 62.1c10.5-4.4 21.4-7.9 32.7-10.4L199 6.4l19.5 69.2c11-2.1 22.3-3.2 33.8-3.4L256 0l3.6 72.2c11.5.2 22.8 1.4 33.8 3.5L313 6.4l-12.4 70.7c11.3 2.6 22.2 6.1 32.6 10.5l33.9-62.2-27.4 65.1c10.6 4.9 20.7 10.7 30.2 17.2l45.8-51.8-40.1 55.9c9.5 7.1 18.4 15 26.5 23.6l54.2-38.9-49.7 43.9c8 9.1 15.2 18.9 21.5 29.4l58.7-24.7-55.5 30.2c6.1 10.9 11.1 22.3 15.1 34.3l59.3-10.4-57.5 16.2c3.7 12.2 6.2 24.9 7.5 37.9L512 256l-56 2.8c.3 4.6.5 9.3.5 14.1 0 8.7-.6 17.3-1.6 25.8l50.7 14.3-51.5-9.1zm-21.8-31c0-97.5-79-176.5-176.5-176.5s-176.5 79-176.5 176.5 79 176.5 176.5 176.5 176.5-79 176.5-176.5zm-24 0c0 84.3-68.3 152.6-152.6 152.6s-152.6-68.3-152.6-152.6 68.3-152.6 152.6-152.6 152.6 68.3 152.6 152.6zM195 241c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-40.7-19c0 2.1 1.3 3.8 3.6 5.1 3.5 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.5 6.8-9.6 10.9-9.6 12.6zm-19 0c0 2.1 1.3 3.8 3.6 5.1 3.3 1.9 6.2 4.6 8.2 8.2 2.8-5.7 4.3-9.5 4.3-11.2 0-2.2-1.1-4.4-3.2-7-2.1-2.5-3.2-5.2-3.3-7.7-6.4 6.8-9.6 10.9-9.6 12.6zm204.9 87.9c-8.4-3-8.7-6.8-8.7-15.6V182c-8.2 12.5-14.2 18.6-18 18.6 6.3 14.4 9.5 23.9 9.5 28.3v64.3c0 2.2-2.2 6.5-4.7 6.5h-18c-2.8-7.5-10.2-26.9-15.3-40.3-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3 2.6 6.7 6.4 16.5 7.9 20.2h-9.2c-3.9-10.4-9.6-25.4-11.8-31.1-2 2.5-7.2 9.2-10.7 13.7 2.4 1.6 4.1 3.6 5.2 6.3.8 2 2.8 7.3 4.3 10.9H256c-1.5-4.1-5.6-14.6-8.4-22-2 2.5-7.2 9.2-10.7 13.7 2.5 1.6 4.3 3.6 5.2 6.3.2.6.5 1.4.6 1.7H225c-4.6-13.9-11.4-27.7-11.4-34.1 0-2.2.3-5.1 1.1-8.2-8.8 10.8-14 15.9-14 25 0 7.5 10.4 28.3 10.4 33.3 0 1.7-.5 3.3-1.4 4.9-9.6-12.7-15.5-20.7-18.8-20.7h-12l-11.2-28c-3.8-9.6-5.7-16-5.7-18.8 0-3.8.5-7.7 1.7-12.2-1 1.3-3.7 4.7-5.5 7.1-.8-2.1-3.1-7.7-4.6-11.5-2.1 2.5-7.5 9.1-11.2 13.6.9 2.3 3.3 8.1 4.9 12.2-2.5 3.3-9.1 11.8-13.6 17.7-4 5.3-5.8 13.3-2.7 21.8 2.5 6.7 2 7.9-1.7 14.1H191c5.5 0 14.3 14 15.5 22 13.2-16 15.4-19.6 16.8-21.6h107c3.9 0 7.2-1.9 9.9-5.8zm20.1-26.6V181.7c-9 12.5-15.9 18.6-20.7 18.6 7.1 14.4 10.7 23.9 10.7 28.3v66.3c0 17.5 8.6 20.4 24 20.4 8.1 0 12.5-.8 13.7-2.7-4.3-1.6-7.6-2.5-9.9-3.3-8.1-3.2-17.8-7.4-17.8-26z\"],\n    \"vaadin\": [448, 512, [], \"f408\", \"M224.5 140.7c1.5-17.6 4.9-52.7 49.8-52.7h98.6c20.7 0 32.1-7.8 32.1-21.6V54.1c0-12.2 9.3-22.1 21.5-22.1S448 41.9 448 54.1v36.5c0 42.9-21.5 62-66.8 62H280.7c-30.1 0-33 14.7-33 27.1 0 1.3-.1 2.5-.2 3.7-.7 12.3-10.9 22.2-23.4 22.2s-22.7-9.8-23.4-22.2c-.1-1.2-.2-2.4-.2-3.7 0-12.3-3-27.1-33-27.1H66.8c-45.3 0-66.8-19.1-66.8-62V54.1C0 41.9 9.4 32 21.6 32s21.5 9.9 21.5 22.1v12.3C43.1 80.2 54.5 88 75.2 88h98.6c44.8 0 48.3 35.1 49.8 52.7h.9zM224 456c11.5 0 21.4-7 25.7-16.3 1.1-1.8 97.1-169.6 98.2-171.4 11.9-19.6-3.2-44.3-27.2-44.3-13.9 0-23.3 6.4-29.8 20.3L224 362l-66.9-117.7c-6.4-13.9-15.9-20.3-29.8-20.3-24 0-39.1 24.6-27.2 44.3 1.1 1.9 97.1 169.6 98.2 171.4 4.3 9.3 14.2 16.3 25.7 16.3z\"],\n    \"viacoin\": [384, 512, [], \"f237\", \"M384 32h-64l-80.7 192h-94.5L64 32H0l48 112H0v48h68.5l13.8 32H0v48h102.8L192 480l89.2-208H384v-48h-82.3l13.8-32H384v-48h-48l48-112zM192 336l-27-64h54l-27 64z\"],\n    \"viadeo\": [448, 512, [], \"f2a9\", \"M276.2 150.5v.7C258.3 98.6 233.6 47.8 205.4 0c43.3 29.2 67 100 70.8 150.5zm32.7 121.7c7.6 18.2 11 37.5 11 57 0 77.7-57.8 141-137.8 139.4l3.8-.3c74.2-46.7 109.3-118.6 109.3-205.1 0-38.1-6.5-75.9-18.9-112 1 11.7 1 23.7 1 35.4 0 91.8-18.1 241.6-116.6 280C95 455.2 49.4 398 49.4 329.2c0-75.6 57.4-142.3 135.4-142.3 16.8 0 33.7 3.1 49.1 9.6 1.7-15.1 6.5-29.9 13.4-43.3-19.9-7.2-41.2-10.7-62.5-10.7-161.5 0-238.7 195.9-129.9 313.7 67.9 74.6 192 73.9 259.8 0 56.6-61.3 60.9-142.4 36.4-201-12.7 8-27.1 13.9-42.2 17zM418.1 11.7c-31 66.5-81.3 47.2-115.8 80.1-12.4 12-20.6 34-20.6 50.5 0 14.1 4.5 27.1 12 38.8 47.4-11 98.3-46 118.2-90.7-.7 5.5-4.8 14.4-7.2 19.2-20.3 35.7-64.6 65.6-99.7 84.9 14.8 14.4 33.7 25.8 55 25.8 79 0 110.1-134.6 58.1-208.6z\"],\n    \"viadeo-square\": [448, 512, [], \"f2aa\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM280.7 381.2c-42.4 46.2-120 46.6-162.4 0-68-73.6-19.8-196.1 81.2-196.1 13.3 0 26.6 2.1 39.1 6.7-4.3 8.4-7.3 17.6-8.4 27.1-9.7-4.1-20.2-6-30.7-6-48.8 0-84.6 41.7-84.6 88.9 0 43 28.5 78.7 69.5 85.9 61.5-24 72.9-117.6 72.9-175 0-7.3 0-14.8-.6-22.1-11.2-32.9-26.6-64.6-44.2-94.5 27.1 18.3 41.9 62.5 44.2 94.1v.4c7.7 22.5 11.8 46.2 11.8 70 0 54.1-21.9 99-68.3 128.2l-2.4.2c50 1 86.2-38.6 86.2-87.2 0-12.2-2.1-24.3-6.9-35.7 9.5-1.9 18.5-5.6 26.4-10.5 15.3 36.6 12.6 87.3-22.8 125.6zM309 233.7c-13.3 0-25.1-7.1-34.4-16.1 21.9-12 49.6-30.7 62.3-53 1.5-3 4.1-8.6 4.5-12-12.5 27.9-44.2 49.8-73.9 56.7-4.7-7.3-7.5-15.5-7.5-24.3 0-10.3 5.2-24.1 12.9-31.6 21.6-20.5 53-8.5 72.4-50 32.5 46.2 13.1 130.3-36.3 130.3z\"],\n    \"viber\": [512, 512, [], \"f409\", \"M444 49.9C431.3 38.2 379.9.9 265.3.4c0 0-135.1-8.1-200.9 52.3C27.8 89.3 14.9 143 13.5 209.5c-1.4 66.5-3.1 191.1 117 224.9h.1l-.1 51.6s-.8 20.9 13 25.1c16.6 5.2 26.4-10.7 42.3-27.8 8.7-9.4 20.7-23.2 29.8-33.7 82.2 6.9 145.3-8.9 152.5-11.2 16.6-5.4 110.5-17.4 125.7-142 15.8-128.6-7.6-209.8-49.8-246.5zM457.9 287c-12.9 104-89 110.6-103 115.1-6 1.9-61.5 15.7-131.2 11.2 0 0-52 62.7-68.2 79-5.3 5.3-11.1 4.8-11-5.7 0-6.9.4-85.7.4-85.7-.1 0-.1 0 0 0-101.8-28.2-95.8-134.3-94.7-189.8 1.1-55.5 11.6-101 42.6-131.6 55.7-50.5 170.4-43 170.4-43 96.9.4 143.3 29.6 154.1 39.4 35.7 30.6 53.9 103.8 40.6 211.1zm-139-80.8c.4 8.6-12.5 9.2-12.9.6-1.1-22-11.4-32.7-32.6-33.9-8.6-.5-7.8-13.4.7-12.9 27.9 1.5 43.4 17.5 44.8 46.2zm20.3 11.3c1-42.4-25.5-75.6-75.8-79.3-8.5-.6-7.6-13.5.9-12.9 58 4.2 88.9 44.1 87.8 92.5-.1 8.6-13.1 8.2-12.9-.3zm47 13.4c.1 8.6-12.9 8.7-12.9.1-.6-81.5-54.9-125.9-120.8-126.4-8.5-.1-8.5-12.9 0-12.9 73.7.5 133 51.4 133.7 139.2zM374.9 329v.2c-10.8 19-31 40-51.8 33.3l-.2-.3c-21.1-5.9-70.8-31.5-102.2-56.5-16.2-12.8-31-27.9-42.4-42.4-10.3-12.9-20.7-28.2-30.8-46.6-21.3-38.5-26-55.7-26-55.7-6.7-20.8 14.2-41 33.3-51.8h.2c9.2-4.8 18-3.2 23.9 3.9 0 0 12.4 14.8 17.7 22.1 5 6.8 11.7 17.7 15.2 23.8 6.1 10.9 2.3 22-3.7 26.6l-12 9.6c-6.1 4.9-5.3 14-5.3 14s17.8 67.3 84.3 84.3c0 0 9.1.8 14-5.3l9.6-12c4.6-6 15.7-9.8 26.6-3.7 14.7 8.3 33.4 21.2 45.8 32.9 7 5.7 8.6 14.4 3.8 23.6z\"],\n    \"vimeo\": [448, 512, [], \"f40a\", \"M403.2 32H44.8C20.1 32 0 52.1 0 76.8v358.4C0 459.9 20.1 480 44.8 480h358.4c24.7 0 44.8-20.1 44.8-44.8V76.8c0-24.7-20.1-44.8-44.8-44.8zM377 180.8c-1.4 31.5-23.4 74.7-66 129.4-44 57.2-81.3 85.8-111.7 85.8-18.9 0-34.8-17.4-47.9-52.3-25.5-93.3-36.4-148-57.4-148-2.4 0-10.9 5.1-25.4 15.2l-15.2-19.6c37.3-32.8 72.9-69.2 95.2-71.2 25.2-2.4 40.7 14.8 46.5 51.7 20.7 131.2 29.9 151 67.6 91.6 13.5-21.4 20.8-37.7 21.8-48.9 3.5-33.2-25.9-30.9-45.8-22.4 15.9-52.1 46.3-77.4 91.2-76 33.3.9 49 22.5 47.1 64.7z\"],\n    \"vimeo-square\": [448, 512, [], \"f194\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16.2 149.6c-1.4 31.1-23.2 73.8-65.3 127.9-43.5 56.5-80.3 84.8-110.4 84.8-18.7 0-34.4-17.2-47.3-51.6-25.2-92.3-35.9-146.4-56.7-146.4-2.4 0-10.8 5-25.1 15.1L64 192c36.9-32.4 72.1-68.4 94.1-70.4 24.9-2.4 40.2 14.6 46 51.1 20.5 129.6 29.6 149.2 66.8 90.5 13.4-21.2 20.6-37.2 21.5-48.3 3.4-32.8-25.6-30.6-45.2-22.2 15.7-51.5 45.8-76.5 90.1-75.1 32.9 1 48.4 22.4 46.5 64z\"],\n    \"vimeo-v\": [448, 512, [], \"f27d\", \"M447.8 153.6c-2 43.6-32.4 103.3-91.4 179.1-60.9 79.2-112.4 118.8-154.6 118.8-26.1 0-48.2-24.1-66.3-72.3C100.3 250 85.3 174.3 56.2 174.3c-3.4 0-15.1 7.1-35.2 21.1L0 168.2c51.6-45.3 100.9-95.7 131.8-98.5 34.9-3.4 56.3 20.5 64.4 71.5 28.7 181.5 41.4 208.9 93.6 126.7 18.7-29.6 28.8-52.1 30.2-67.6 4.8-45.9-35.8-42.8-63.3-31 22-72.1 64.1-107.1 126.2-105.1 45.8 1.2 67.5 31.1 64.9 89.4z\"],\n    \"vine\": [384, 512, [], \"f1ca\", \"M384 254.7v52.1c-18.4 4.2-36.9 6.1-52.1 6.1-36.9 77.4-103 143.8-125.1 156.2-14 7.9-27.1 8.4-42.7-.8C137 452 34.2 367.7 0 102.7h74.5C93.2 261.8 139 343.4 189.3 404.5c27.9-27.9 54.8-65.1 75.6-106.9-49.8-25.3-80.1-80.9-80.1-145.6 0-65.6 37.7-115.1 102.2-115.1 114.9 0 106.2 127.9 81.6 181.5 0 0-46.4 9.2-63.5-20.5 3.4-11.3 8.2-30.8 8.2-48.5 0-31.3-11.3-46.6-28.4-46.6-18.2 0-30.8 17.1-30.8 50 .1 79.2 59.4 118.7 129.9 101.9z\"],\n    \"vk\": [576, 512, [], \"f189\", \"M545 117.7c3.7-12.5 0-21.7-17.8-21.7h-58.9c-15 0-21.9 7.9-25.6 16.7 0 0-30 73.1-72.4 120.5-13.7 13.7-20 18.1-27.5 18.1-3.7 0-9.4-4.4-9.4-16.9V117.7c0-15-4.2-21.7-16.6-21.7h-92.6c-9.4 0-15 7-15 13.5 0 14.2 21.2 17.5 23.4 57.5v86.8c0 19-3.4 22.5-10.9 22.5-20 0-68.6-73.4-97.4-157.4-5.8-16.3-11.5-22.9-26.6-22.9H38.8c-16.8 0-20.2 7.9-20.2 16.7 0 15.6 20 93.1 93.1 195.5C160.4 378.1 229 416 291.4 416c37.5 0 42.1-8.4 42.1-22.9 0-66.8-3.4-73.1 15.4-73.1 8.7 0 23.7 4.4 58.7 38.1 40 40 46.6 57.9 69 57.9h58.9c16.8 0 25.3-8.4 20.4-25-11.2-34.9-86.9-106.7-90.3-111.5-8.7-11.2-6.2-16.2 0-26.2.1-.1 72-101.3 79.4-135.6z\"],\n    \"vnv\": [640, 512, [], \"f40b\", \"M104.9 352c-34.1 0-46.4-30.4-46.4-30.4L2.6 210.1S-7.8 192 13 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.7-74.5c5.6-9.5 8.4-18.1 18.8-18.1h32.8c20.8 0 10.4 18.1 10.4 18.1l-55.8 111.5S174.2 352 140 352h-35.1zm395 0c-34.1 0-46.4-30.4-46.4-30.4l-55.9-111.5S387.2 192 408 192h32.8c10.4 0 13.2 8.7 18.8 18.1l36.7 74.5s5.2 13.1 21.1 13.1 21.1-13.1 21.1-13.1l36.8-74.5c5.6-9.5 8.4-18.1 18.8-18.1H627c20.8 0 10.4 18.1 10.4 18.1l-55.9 111.5S569.3 352 535.1 352h-35.2zM337.6 192c34.1 0 46.4 30.4 46.4 30.4l55.9 111.5s10.4 18.1-10.4 18.1h-32.8c-10.4 0-13.2-8.7-18.8-18.1l-36.7-74.5s-5.2-13.1-21.1-13.1c-15.9 0-21.1 13.1-21.1 13.1l-36.7 74.5c-5.6 9.4-8.4 18.1-18.8 18.1h-32.9c-20.8 0-10.4-18.1-10.4-18.1l55.9-111.5s12.2-30.4 46.4-30.4h35.1z\"],\n    \"vuejs\": [448, 512, [], \"f41f\", \"M356.9 64.3H280l-56 88.6-48-88.6H0L224 448 448 64.3h-91.1zm-301.2 32h53.8L224 294.5 338.4 96.3h53.8L224 384.5 55.7 96.3z\"],\n    \"waze\": [512, 512, [], \"f83f\", \"M502.17 201.67C516.69 287.53 471.23 369.59 389 409.8c13 34.1-12.4 70.2-48.32 70.2a51.68 51.68 0 0 1-51.57-49c-6.44.19-64.2 0-76.33-.64A51.69 51.69 0 0 1 159 479.92c-33.86-1.36-57.95-34.84-47-67.92-37.21-13.11-72.54-34.87-99.62-70.8-13-17.28-.48-41.8 20.84-41.8 46.31 0 32.22-54.17 43.15-110.26C94.8 95.2 193.12 32 288.09 32c102.48 0 197.15 70.67 214.08 169.67zM373.51 388.28c42-19.18 81.33-56.71 96.29-102.14 40.48-123.09-64.15-228-181.71-228-83.45 0-170.32 55.42-186.07 136-9.53 48.91 5 131.35-68.75 131.35C58.21 358.6 91.6 378.11 127 389.54c24.66-21.8 63.87-15.47 79.83 14.34 14.22 1 79.19 1.18 87.9.82a51.69 51.69 0 0 1 78.78-16.42zM205.12 187.13c0-34.74 50.84-34.75 50.84 0s-50.84 34.74-50.84 0zm116.57 0c0-34.74 50.86-34.75 50.86 0s-50.86 34.75-50.86 0zm-122.61 70.69c-3.44-16.94 22.18-22.18 25.62-5.21l.06.28c4.14 21.42 29.85 44 64.12 43.07 35.68-.94 59.25-22.21 64.11-42.77 4.46-16.05 28.6-10.36 25.47 6-5.23 22.18-31.21 62-91.46 62.9-42.55 0-80.88-27.84-87.9-64.25z\"],\n    \"weebly\": [512, 512, [], \"f5cc\", \"M425.09 65.83c-39.88 0-73.28 25.73-83.66 64.33-18.16-58.06-65.5-64.33-84.95-64.33-19.78 0-66.8 6.28-85.28 64.33-10.38-38.6-43.45-64.33-83.66-64.33C38.59 65.83 0 99.72 0 143.03c0 28.96 4.18 33.27 77.17 233.48 22.37 60.57 67.77 69.35 92.74 69.35 39.23 0 70.04-19.46 85.93-53.98 15.89 34.83 46.69 54.29 85.93 54.29 24.97 0 70.36-9.1 92.74-69.67 76.55-208.65 77.5-205.58 77.5-227.2.63-48.32-36.01-83.47-86.92-83.47zm26.34 114.81l-65.57 176.44c-7.92 21.49-21.22 37.22-46.24 37.22-23.44 0-37.38-12.41-44.03-33.9l-39.28-117.42h-.95L216.08 360.4c-6.96 21.5-20.9 33.6-44.02 33.6-25.02 0-38.33-15.74-46.24-37.22L60.88 181.55c-5.38-14.83-7.92-23.91-7.92-34.5 0-16.34 15.84-29.36 38.33-29.36 18.69 0 31.99 11.8 36.11 29.05l44.03 139.82h.95l44.66-136.79c6.02-19.67 16.47-32.08 38.96-32.08s32.94 12.11 38.96 32.08l44.66 136.79h.95l44.03-139.82c4.12-17.25 17.42-29.05 36.11-29.05 22.17 0 38.33 13.32 38.33 35.71-.32 7.87-4.12 16.04-7.61 27.24z\"],\n    \"weibo\": [512, 512, [], \"f18a\", \"M407 177.6c7.6-24-13.4-46.8-37.4-41.7-22 4.8-28.8-28.1-7.1-32.8 50.1-10.9 92.3 37.1 76.5 84.8-6.8 21.2-38.8 10.8-32-10.3zM214.8 446.7C108.5 446.7 0 395.3 0 310.4c0-44.3 28-95.4 76.3-143.7C176 67 279.5 65.8 249.9 161c-4 13.1 12.3 5.7 12.3 6 79.5-33.6 140.5-16.8 114 51.4-3.7 9.4 1.1 10.9 8.3 13.1 135.7 42.3 34.8 215.2-169.7 215.2zm143.7-146.3c-5.4-55.7-78.5-94-163.4-85.7-84.8 8.6-148.8 60.3-143.4 116s78.5 94 163.4 85.7c84.8-8.6 148.8-60.3 143.4-116zM347.9 35.1c-25.9 5.6-16.8 43.7 8.3 38.3 72.3-15.2 134.8 52.8 111.7 124-7.4 24.2 29.1 37 37.4 12 31.9-99.8-55.1-195.9-157.4-174.3zm-78.5 311c-17.1 38.8-66.8 60-109.1 46.3-40.8-13.1-58-53.4-40.3-89.7 17.7-35.4 63.1-55.4 103.4-45.1 42 10.8 63.1 50.2 46 88.5zm-86.3-30c-12.9-5.4-30 .3-38 12.9-8.3 12.9-4.3 28 8.6 34 13.1 6 30.8.3 39.1-12.9 8-13.1 3.7-28.3-9.7-34zm32.6-13.4c-5.1-1.7-11.4.6-14.3 5.4-2.9 5.1-1.4 10.6 3.7 12.9 5.1 2 11.7-.3 14.6-5.4 2.8-5.2 1.1-10.9-4-12.9z\"],\n    \"weixin\": [576, 512, [], \"f1d7\", \"M385.2 167.6c6.4 0 12.6.3 18.8 1.1C387.4 90.3 303.3 32 207.7 32 100.5 32 13 104.8 13 197.4c0 53.4 29.3 97.5 77.9 131.6l-19.3 58.6 68-34.1c24.4 4.8 43.8 9.7 68.2 9.7 6.2 0 12.1-.3 18.3-.8-4-12.9-6.2-26.6-6.2-40.8-.1-84.9 72.9-154 165.3-154zm-104.5-52.9c14.5 0 24.2 9.7 24.2 24.4 0 14.5-9.7 24.2-24.2 24.2-14.8 0-29.3-9.7-29.3-24.2.1-14.7 14.6-24.4 29.3-24.4zm-136.4 48.6c-14.5 0-29.3-9.7-29.3-24.2 0-14.8 14.8-24.4 29.3-24.4 14.8 0 24.4 9.7 24.4 24.4 0 14.6-9.6 24.2-24.4 24.2zM563 319.4c0-77.9-77.9-141.3-165.4-141.3-92.7 0-165.4 63.4-165.4 141.3S305 460.7 397.6 460.7c19.3 0 38.9-5.1 58.6-9.9l53.4 29.3-14.8-48.6C534 402.1 563 363.2 563 319.4zm-219.1-24.5c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.8 0 24.4 9.7 24.4 19.3 0 10-9.7 19.6-24.4 19.6zm107.1 0c-9.7 0-19.3-9.7-19.3-19.6 0-9.7 9.7-19.3 19.3-19.3 14.5 0 24.4 9.7 24.4 19.3.1 10-9.9 19.6-24.4 19.6z\"],\n    \"whatsapp\": [448, 512, [], \"f232\", \"M380.9 97.1C339 55.1 283.2 32 223.9 32c-122.4 0-222 99.6-222 222 0 39.1 10.2 77.3 29.6 111L0 480l117.7-30.9c32.4 17.7 68.9 27 106.1 27h.1c122.3 0 224.1-99.6 224.1-222 0-59.3-25.2-115-67.1-157zm-157 341.6c-33.2 0-65.7-8.9-94-25.7l-6.7-4-69.8 18.3L72 359.2l-4.4-7c-18.5-29.4-28.2-63.3-28.2-98.2 0-101.7 82.8-184.5 184.6-184.5 49.3 0 95.6 19.2 130.4 54.1 34.8 34.9 56.2 81.2 56.1 130.5 0 101.8-84.9 184.6-186.6 184.6zm101.2-138.2c-5.5-2.8-32.8-16.2-37.9-18-5.1-1.9-8.8-2.8-12.5 2.8-3.7 5.6-14.3 18-17.6 21.8-3.2 3.7-6.5 4.2-12 1.4-32.6-16.3-54-29.1-75.5-66-5.7-9.8 5.7-9.1 16.3-30.3 1.8-3.7.9-6.9-.5-9.7-1.4-2.8-12.5-30.1-17.1-41.2-4.5-10.8-9.1-9.3-12.5-9.5-3.2-.2-6.9-.2-10.6-.2-3.7 0-9.7 1.4-14.8 6.9-5.1 5.6-19.4 19-19.4 46.3 0 27.3 19.9 53.7 22.6 57.4 2.8 3.7 39.1 59.7 94.8 83.8 35.2 15.2 49 16.5 66.6 13.9 10.7-1.6 32.8-13.4 37.4-26.4 4.6-13 4.6-24.1 3.2-26.4-1.3-2.5-5-3.9-10.5-6.6z\"],\n    \"whatsapp-square\": [448, 512, [], \"f40c\", \"M224 122.8c-72.7 0-131.8 59.1-131.9 131.8 0 24.9 7 49.2 20.2 70.1l3.1 5-13.3 48.6 49.9-13.1 4.8 2.9c20.2 12 43.4 18.4 67.1 18.4h.1c72.6 0 133.3-59.1 133.3-131.8 0-35.2-15.2-68.3-40.1-93.2-25-25-58-38.7-93.2-38.7zm77.5 188.4c-3.3 9.3-19.1 17.7-26.7 18.8-12.6 1.9-22.4.9-47.5-9.9-39.7-17.2-65.7-57.2-67.7-59.8-2-2.6-16.2-21.5-16.2-41s10.2-29.1 13.9-33.1c3.6-4 7.9-5 10.6-5 2.6 0 5.3 0 7.6.1 2.4.1 5.7-.9 8.9 6.8 3.3 7.9 11.2 27.4 12.2 29.4s1.7 4.3.3 6.9c-7.6 15.2-15.7 14.6-11.6 21.6 15.3 26.3 30.6 35.4 53.9 47.1 4 2 6.3 1.7 8.6-1 2.3-2.6 9.9-11.6 12.5-15.5 2.6-4 5.3-3.3 8.9-2 3.6 1.3 23.1 10.9 27.1 12.9s6.6 3 7.6 4.6c.9 1.9.9 9.9-2.4 19.1zM400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM223.9 413.2c-26.6 0-52.7-6.7-75.8-19.3L64 416l22.5-82.2c-13.9-24-21.2-51.3-21.2-79.3C65.4 167.1 136.5 96 223.9 96c42.4 0 82.2 16.5 112.2 46.5 29.9 30 47.9 69.8 47.9 112.2 0 87.4-72.7 158.5-160.1 158.5z\"],\n    \"whmcs\": [448, 512, [], \"f40d\", \"M448 161v-21.3l-28.5-8.8-2.2-10.4 20.1-20.7L427 80.4l-29 7.5-7.2-7.5 7.5-28.2-19.1-11.6-21.3 21-10.7-3.2-7-26.4h-22.6l-6.2 26.4-12.1 3.2-19.7-21-19.4 11 8.1 27.7-8.1 8.4-28.5-7.5-11 19.1 20.7 21-2.9 10.4-28.5 7.8-.3 21.7 28.8 7.5 2.4 12.1-20.1 19.9 10.4 18.5 29.6-7.5 7.2 8.6-8.1 26.9 19.9 11.6 19.4-20.4 11.6 2.9 6.7 28.5 22.6.3 6.7-28.8 11.6-3.5 20.7 21.6 20.4-12.1-8.8-28 7.8-8.1 28.8 8.8 10.3-20.1-20.9-18.8 2.2-12.1 29.1-7zm-119.2 45.2c-31.3 0-56.8-25.4-56.8-56.8s25.4-56.8 56.8-56.8 56.8 25.4 56.8 56.8c0 31.5-25.4 56.8-56.8 56.8zm72.3 16.4l46.9 14.5V277l-55.1 13.4-4.1 22.7 38.9 35.3-19.2 37.9-54-16.7-14.6 15.2 16.7 52.5-38.3 22.7-38.9-40.5-21.7 6.6-12.6 54-42.4-.5-12.6-53.6-21.7-5.6-36.4 38.4-37.4-21.7 15.2-50.5-13.7-16.1-55.5 14.1-19.7-34.8 37.9-37.4-4.8-22.8-54-14.1.5-40.9L54 219.9l5.7-19.7-38.9-39.4L41.5 125l53.6 14.1 15.2-15.7-15.2-52 36.4-20.7 36.8 39.4L191 84l11.6-52H245l11.6 45.9L234 72l-6.3-1.7-3.3 5.7-11 19.1-3.3 5.6 4.6 4.6 17.2 17.4-.3 1-23.8 6.5-6.2 1.7-.1 6.4-.2 12.9C153.8 161.6 118 204 118 254.7c0 58.3 47.3 105.7 105.7 105.7 50.5 0 92.7-35.4 103.2-82.8l13.2.2 6.9.1 1.6-6.7 5.6-24 1.9-.6 17.1 17.8 4.7 4.9 5.8-3.4 20.4-12.1 5.8-3.5-2-6.5-6.8-21.2z\"],\n    \"wikipedia-w\": [640, 512, [], \"f266\", \"M640 51.2l-.3 12.2c-28.1.8-45 15.8-55.8 40.3-25 57.8-103.3 240-155.3 358.6H415l-81.9-193.1c-32.5 63.6-68.3 130-99.2 193.1-.3.3-15 0-15-.3C172 352.3 122.8 243.4 75.8 133.4 64.4 106.7 26.4 63.4.2 63.7c0-3.1-.3-10-.3-14.2h161.9v13.9c-19.2 1.1-52.8 13.3-43.3 34.2 21.9 49.7 103.6 240.3 125.6 288.6 15-29.7 57.8-109.2 75.3-142.8-13.9-28.3-58.6-133.9-72.8-160-9.7-17.8-36.1-19.4-55.8-19.7V49.8l142.5.3v13.1c-19.4.6-38.1 7.8-29.4 26.1 18.9 40 30.6 68.1 48.1 104.7 5.6-10.8 34.7-69.4 48.1-100.8 8.9-20.6-3.9-28.6-38.6-29.4.3-3.6 0-10.3.3-13.6 44.4-.3 111.1-.3 123.1-.6v13.6c-22.5.8-45.8 12.8-58.1 31.7l-59.2 122.8c6.4 16.1 63.3 142.8 69.2 156.7L559.2 91.8c-8.6-23.1-36.4-28.1-47.2-28.3V49.6l127.8 1.1.2.5z\"],\n    \"windows\": [448, 512, [], \"f17a\", \"M0 93.7l183.6-25.3v177.4H0V93.7zm0 324.6l183.6 25.3V268.4H0v149.9zm203.8 28L448 480V268.4H203.8v177.9zm0-380.6v180.1H448V32L203.8 65.7z\"],\n    \"wix\": [640, 512, [], \"f5cf\", \"M393.38 131.69c0 13.03 2.08 32.69-28.68 43.83-9.52 3.45-15.95 9.66-15.95 9.66 0-31 4.72-42.22 17.4-48.86 9.75-5.11 27.23-4.63 27.23-4.63zm-115.8 35.54l-34.24 132.66-28.48-108.57c-7.69-31.99-20.81-48.53-48.43-48.53-27.37 0-40.66 16.18-48.43 48.53L89.52 299.89 55.28 167.23C49.73 140.51 23.86 128.96 0 131.96l65.57 247.93s21.63 1.56 32.46-3.96c14.22-7.25 20.98-12.84 29.59-46.57 7.67-30.07 29.11-118.41 31.12-124.7 4.76-14.94 11.09-13.81 15.4 0 1.97 6.3 23.45 94.63 31.12 124.7 8.6 33.73 15.37 39.32 29.59 46.57 10.82 5.52 32.46 3.96 32.46 3.96l65.57-247.93c-24.42-3.07-49.82 8.93-55.3 35.27zm115.78 5.21s-4.1 6.34-13.46 11.57c-6.01 3.36-11.78 5.64-17.97 8.61-15.14 7.26-13.18 13.95-13.18 35.2v152.07s16.55 2.09 27.37-3.43c13.93-7.1 17.13-13.95 17.26-44.78V181.41l-.02.01v-8.98zm163.44 84.08L640 132.78s-35.11-5.98-52.5 9.85c-13.3 12.1-24.41 29.55-54.18 72.47-.47.73-6.25 10.54-13.07 0-29.29-42.23-40.8-60.29-54.18-72.47-17.39-15.83-52.5-9.85-52.5-9.85l83.2 123.74-82.97 123.36s36.57 4.62 53.95-11.21c11.49-10.46 17.58-20.37 52.51-70.72 6.81-10.52 12.57-.77 13.07 0 29.4 42.38 39.23 58.06 53.14 70.72 17.39 15.83 53.32 11.21 53.32 11.21L556.8 256.52z\"],\n    \"wizards-of-the-coast\": [640, 512, [], \"f730\", \"M219.19 345.69c-1.9 1.38-11.07 8.44-.26 23.57 4.64 6.42 14.11 12.79 21.73 6.55 6.5-4.88 7.35-12.92.26-23.04-5.47-7.76-14.28-12.88-21.73-7.08zm336.75 75.94c-.34 1.7-.55 1.67.79 0 2.09-4.19 4.19-10.21 4.98-19.9 3.14-38.49-40.33-71.49-101.34-78.03-54.73-6.02-124.38 9.17-188.8 60.49l-.26 1.57c2.62 4.98 4.98 10.74 3.4 21.21l.79.26c63.89-58.4 131.19-77.25 184.35-73.85 58.4 3.67 100.03 34.04 100.03 68.08-.01 9.96-2.63 15.72-3.94 20.17zM392.28 240.42c.79 7.07 4.19 10.21 9.17 10.47 5.5.26 9.43-2.62 10.47-6.55.79-3.4 2.09-29.85 2.09-29.85s-11.26 6.55-14.93 10.47c-3.66 3.68-7.33 8.39-6.8 15.46zm-50.02-151.1C137.75 89.32 13.1 226.8.79 241.2c-1.05.52-1.31.79.79 1.31 60.49 16.5 155.81 81.18 196.13 202.16l1.05.26c55.25-69.92 140.88-128.05 236.99-128.05 80.92 0 130.15 42.16 130.15 80.39 0 18.33-6.55 33.52-22.26 46.35 0 .96-.2.79.79.79 14.66-10.74 27.5-28.8 27.5-48.18 0-22.78-12.05-38.23-12.05-38.23 7.07 7.07 10.74 16.24 10.74 16.24 5.76-40.85 26.97-62.32 26.97-62.32-2.36-9.69-6.81-17.81-6.81-17.81 7.59 8.12 14.4 27.5 14.4 41.37 0 10.47-3.4 22.78-12.57 31.95l.26.52c8.12-4.98 16.5-16.76 16.5-37.97 0-15.71-4.71-25.92-4.71-25.92 5.76-5.24 11.26-9.17 15.97-11.78.79 3.4 2.09 9.69 2.36 14.93 0 1.05.79 1.83 1.05 0 .79-5.76-.26-16.24-.26-16.5 6.02-3.14 9.69-4.45 9.69-4.45C617.74 176 489.43 89.32 342.26 89.32zm-99.24 289.62c-11.06 8.99-24.2 4.08-30.64-4.19-7.45-9.58-6.76-24.09 4.19-32.47 14.85-11.35 27.08-.49 31.16 5.5.28.39 12.13 16.57-4.71 31.16zm2.09-136.43l9.43-17.81 11.78 70.96-12.57 6.02-24.62-28.8 14.14-26.71 3.67 4.45-1.83-8.11zm18.59 117.58l-.26-.26c2.05-4.1-2.5-6.61-17.54-31.69-1.31-2.36-3.14-2.88-4.45-2.62l-.26-.52c7.86-5.76 15.45-10.21 25.4-15.71l.52.26c1.31 1.83 2.09 2.88 3.4 4.71l-.26.52c-1.05-.26-2.36-.79-5.24.26-2.09.79-7.86 3.67-12.31 7.59v1.31c1.57 2.36 3.93 6.55 5.76 9.69h.26c10.05-6.28 7.56-4.55 11.52-7.86h.26c.52 1.83.52 1.83 1.83 5.5l-.26.26c-3.06.61-4.65.34-11.52 5.5v.26c9.46 17.02 11.01 16.75 12.57 15.97l.26.26c-2.34 1.59-6.27 4.21-9.68 6.57zm55.26-32.47c-3.14 1.57-6.02 2.88-9.95 4.98l-.26-.26c1.29-2.59 1.16-2.71-11.78-32.47l-.26-.26c-.15 0-8.9 3.65-9.95 7.33h-.52l-1.05-5.76.26-.52c7.29-4.56 25.53-11.64 27.76-12.57l.52.26 3.14 4.98-.26.52c-3.53-1.76-7.35.76-12.31 2.62v.26c12.31 32.01 12.67 30.64 14.66 30.64v.25zm44.77-16.5c-4.19 1.05-5.24 1.31-9.69 2.88l-.26-.26.52-4.45c-1.05-3.4-3.14-11.52-3.67-13.62l-.26-.26c-3.4.79-8.9 2.62-12.83 3.93l-.26.26c.79 2.62 3.14 9.95 4.19 13.88.79 2.36 1.83 2.88 2.88 3.14v.52c-3.67 1.05-7.07 2.62-10.21 3.93l-.26-.26c1.05-1.31 1.05-2.88.26-4.98-1.05-3.14-8.12-23.83-9.17-27.23-.52-1.83-1.57-3.14-2.62-3.14v-.52c3.14-1.05 6.02-2.09 10.74-3.4l.26.26-.26 4.71c1.31 3.93 2.36 7.59 3.14 9.69h.26c3.93-1.31 9.43-2.88 12.83-3.93l.26-.26-2.62-9.43c-.52-1.83-1.05-3.4-2.62-3.93v-.26c4.45-1.05 7.33-1.83 10.74-2.36l.26.26c-1.05 1.31-1.05 2.88-.52 4.45 1.57 6.28 4.71 20.43 6.28 26.45.54 2.62 1.85 3.41 2.63 3.93zm32.21-6.81l-.26.26c-4.71.52-14.14 2.36-22.52 4.19l-.26-.26.79-4.19c-1.57-7.86-3.4-18.59-4.98-26.19-.26-1.83-.79-2.88-2.62-3.67l.79-.52c9.17-1.57 20.16-2.36 24.88-2.62l.26.26c.52 2.36.79 3.14 1.57 5.5l-.26.26c-1.14-1.14-3.34-3.2-16.24-.79l-.26.26c.26 1.57 1.05 6.55 1.57 9.95l.26.26c9.52-1.68 4.76-.06 10.74-2.36h.26c0 1.57-.26 1.83-.26 5.24h-.26c-4.81-1.03-2.15-.9-10.21 0l-.26.26c.26 2.09 1.57 9.43 2.09 12.57l.26.26c1.15.38 14.21-.65 16.24-4.71h.26c-.53 2.38-1.05 4.21-1.58 6.04zm10.74-44.51c-4.45 2.36-8.12 2.88-11 2.88-.25.02-11.41 1.09-17.54-9.95-6.74-10.79-.98-25.2 5.5-31.69 8.8-8.12 23.35-10.1 28.54-17.02 8.03-10.33-13.04-22.31-29.59-5.76l-2.62-2.88 5.24-16.24c25.59-1.57 45.2-3.04 50.02 16.24.79 3.14 0 9.43-.26 12.05 0 2.62-1.83 18.85-2.09 23.04-.52 4.19-.79 18.33-.79 20.69.26 2.36.52 4.19 1.57 5.5 1.57 1.83 5.76 1.83 5.76 1.83l-.79 4.71c-11.82-1.07-10.28-.59-20.43-1.05-3.22-5.15-2.23-3.28-4.19-7.86 0 .01-4.19 3.94-7.33 5.51zm37.18 21.21c-6.35-10.58-19.82-7.16-21.73 5.5-2.63 17.08 14.3 19.79 20.69 10.21l.26.26c-.52 1.83-1.83 6.02-1.83 6.28l-.52.52c-10.3 6.87-28.5-2.5-25.66-18.59 1.94-10.87 14.44-18.93 28.8-9.95l.26.52c0 1.06-.27 3.41-.27 5.25zm5.77-87.73v-6.55c.69 0 19.65 3.28 27.76 7.33l-1.57 17.54s10.21-9.43 15.45-10.74c5.24-1.57 14.93 7.33 14.93 7.33l-11.26 11.26c-12.07-6.35-19.59-.08-20.69.79-5.29 38.72-8.6 42.17 4.45 46.09l-.52 4.71c-17.55-4.29-18.53-4.5-36.92-7.33l.79-4.71c7.25 0 7.48-5.32 7.59-6.81 0 0 4.98-53.16 4.98-55.25-.02-2.87-4.99-3.66-4.99-3.66zm10.99 114.44c-8.12-2.09-14.14-11-10.74-20.69 3.14-9.43 12.31-12.31 18.85-10.21 9.17 2.62 12.83 11.78 10.74 19.38-2.61 8.9-9.42 13.87-18.85 11.52zm42.16 9.69c-2.36-.52-7.07-2.36-8.64-2.88v-.26l1.57-1.83c.59-8.24.59-7.27.26-7.59-4.82-1.81-6.66-2.36-7.07-2.36-1.31 1.83-2.88 4.45-3.67 5.5l-.79 3.4v.26c-1.31-.26-3.93-1.31-6.02-1.57v-.26l2.62-1.83c3.4-4.71 9.95-14.14 13.88-20.16v-2.09l.52-.26c2.09.79 5.5 2.09 7.59 2.88.48.48.18-1.87-1.05 25.14-.24 1.81.02 2.6.8 3.91zm-4.71-89.82c11.25-18.27 30.76-16.19 34.04-3.4L539.7 198c2.34-6.25-2.82-9.9-4.45-11.26l1.83-3.67c12.22 10.37 16.38 13.97 22.52 20.43-25.91 73.07-30.76 80.81-24.62 84.32l-1.83 4.45c-6.37-3.35-8.9-4.42-17.81-8.64l2.09-6.81c-.26-.26-3.93 3.93-9.69 3.67-19.06-1.3-22.89-31.75-9.67-52.9zm29.33 79.34c0-5.71-6.34-7.89-7.86-5.24-1.31 2.09 1.05 4.98 2.88 8.38 1.57 2.62 2.62 6.28 1.05 9.43-2.64 6.34-12.4 5.31-15.45-.79 0-.7-.27.09 1.83-4.71l.79-.26c-.57 5.66 6.06 9.61 8.38 4.98 1.05-2.09-.52-5.5-2.09-8.38-1.57-2.62-3.67-6.28-1.83-9.69 2.72-5.06 11.25-4.47 14.66 2.36v.52l-2.36 3.4zm21.21 13.36c-1.96-3.27-.91-2.14-4.45-4.71h-.26c-2.36 4.19-5.76 10.47-8.64 16.24-1.31 2.36-1.05 3.4-.79 3.93l-.26.26-5.76-4.45.26-.26 2.09-1.31c3.14-5.76 6.55-12.05 9.17-17.02v-.26c-2.64-1.98-1.22-1.51-6.02-1.83v-.26l3.14-3.4h.26c3.67 2.36 9.95 6.81 12.31 8.9l.26.26-1.31 3.91zm27.23-44.26l-2.88-2.88c.79-2.36 1.83-4.98 2.09-7.59.75-9.74-11.52-11.84-11.52-4.98 0 4.98 7.86 19.38 7.86 27.76 0 10.21-5.76 15.71-13.88 16.5-8.38.79-20.16-10.47-20.16-10.47l4.98-14.4 2.88 2.09c-2.97 17.8 17.68 20.37 13.35 5.24-1.06-4.02-18.75-34.2 2.09-38.23 13.62-2.36 23.04 16.5 23.04 16.5l-7.85 10.46zm35.62-10.21c-11-30.38-60.49-127.53-191.95-129.62-53.42-1.05-94.27 15.45-132.76 37.97l85.63-9.17-91.39 20.69 25.14 19.64-3.93-16.5c7.5-1.71 39.15-8.45 66.77-8.9l-22.26 80.39c13.61-.7 18.97-8.98 19.64-22.78l4.98-1.05.26 26.71c-22.46 3.21-37.3 6.69-49.49 9.95l13.09-43.21-61.54-36.66 2.36 8.12 10.21 4.98c6.28 18.59 19.38 56.56 20.43 58.66 1.95 4.28 3.16 5.78 12.05 4.45l1.05 4.98c-16.08 4.86-23.66 7.61-39.02 14.4l-2.36-4.71c4.4-2.94 8.73-3.94 5.5-12.83-23.7-62.5-21.48-58.14-22.78-59.44l2.36-4.45 33.52 67.3c-3.84-11.87 1.68 1.69-32.99-78.82l-41.9 88.51 4.71-13.88-35.88-42.16 27.76 93.48-11.78 8.38C95 228.58 101.05 231.87 93.23 231.52c-5.5-.26-13.62 5.5-13.62 5.5L74.63 231c30.56-23.53 31.62-24.33 58.4-42.68l4.19 7.07s-5.76 4.19-7.86 7.07c-5.9 9.28 1.67 13.28 61.8 75.68l-18.85-58.92 39.8-10.21 25.66 30.64 4.45-12.31-4.98-24.62 13.09-3.4.52 3.14 3.67-10.47-94.27 29.33 11.26-4.98-13.62-42.42 17.28-9.17 30.11 36.14 28.54-13.09c-1.41-7.47-2.47-14.5-4.71-19.64l17.28 13.88 4.71-2.09-59.18-42.68 23.08 11.5c18.98-6.07 25.23-7.47 32.21-9.69l2.62 11c-12.55 12.55 1.43 16.82 6.55 19.38l-13.62-61.01 12.05 28.28c4.19-1.31 7.33-2.09 7.33-2.09l2.62 8.64s-3.14 1.05-6.28 2.09l8.9 20.95 33.78-65.73-20.69 61.01c42.42-24.09 81.44-36.66 131.98-35.88 67.04 1.05 167.33 40.85 199.8 139.83.78 2.1-.01 2.63-.79.27zM203.48 152.43s1.83-.52 4.19-1.31l9.43 7.59c-.4 0-3.44-.25-11.26 2.36l-2.36-8.64zm143.76 38.5c-1.57-.6-26.46-4.81-33.26 20.69l21.73 17.02 11.53-37.71zM318.43 67.07c-58.4 0-106.05 12.05-114.96 14.4v.79c8.38 2.09 14.4 4.19 21.21 11.78l1.57.26c6.55-1.83 48.97-13.88 110.24-13.88 180.16 0 301.67 116.79 301.67 223.37v9.95c0 1.31.79 2.62 1.05.52.52-2.09.79-8.64.79-19.64.26-83.79-96.63-227.55-321.57-227.55zm211.06 169.68c1.31-5.76 0-12.31-7.33-13.09-9.62-1.13-16.14 23.79-17.02 33.52-.79 5.5-1.31 14.93 6.02 14.93 4.68-.01 9.72-.91 18.33-35.36zm-61.53 42.95c-2.62-.79-9.43-.79-12.57 10.47-1.83 6.81.52 13.35 6.02 14.66 3.67 1.05 8.9.52 11.78-10.74 2.62-9.94-1.83-13.61-5.23-14.39zM491 300.65c1.83.52 3.14 1.05 5.76 1.83 0-1.83.52-8.38.79-12.05-1.05 1.31-5.5 8.12-6.55 9.95v.27z\"],\n    \"wolf-pack-battalion\": [512, 512, [], \"f514\", \"M267.73 471.53l10.56 15.84 5.28-12.32 5.28 7V512c21.06-7.92 21.11-66.86 25.51-97.21 4.62-31.89-.88-92.81 81.37-149.11-8.88-23.61-12-49.43-2.64-80.05C421 189 447 196.21 456.43 239.73l-30.35 8.36c11.15 23 17 46.76 13.2 72.14L412 313.18l-6.16 33.43-18.47-7-8.8 33.39-19.35-7 26.39 21.11 8.8-28.15L419 364.2l7-35.63 26.39 14.52c.25-20 7-58.06-8.8-84.45l26.39 5.28c4-22.07-2.38-39.21-7.92-56.74l22.43 9.68c-.44-25.07-29.94-56.79-61.58-58.5-20.22-1.09-56.74-25.17-54.1-51.9 2-19.87 17.45-42.62 43.11-49.7-44 36.51-9.68 67.3 5.28 73.46 4.4-11.44 17.54-69.08 0-130.2-40.39 22.87-89.65 65.1-93.2 147.79l-58 38.71-3.52 93.25L369.78 220l7 7-17.59 3.52-44 38.71-15.84-5.28-28.1 49.25-3.52 119.64 21.11 15.84-32.55 15.84-32.55-15.84 21.11-15.84-3.52-119.64-28.15-49.26-15.84 5.28-44-38.71-17.58-3.51 7-7 107.33 59.82-3.52-93.25-58.06-38.71C185 65.1 135.77 22.87 95.3 0c-17.54 61.12-4.4 118.76 0 130.2 15-6.16 49.26-36.95 5.28-73.46 25.66 7.08 41.15 29.83 43.11 49.7 2.63 26.74-33.88 50.81-54.1 51.9-31.65 1.72-61.15 33.44-61.59 58.51l22.43-9.68c-5.54 17.53-11.91 34.67-7.92 56.74l26.39-5.28c-15.76 26.39-9.05 64.43-8.8 84.45l26.39-14.52 7 35.63 24.63-5.28 8.8 28.15L153.35 366 134 373l-8.8-33.43-18.47 7-6.16-33.43-27.27 7c-3.82-25.38 2-49.1 13.2-72.14l-30.35-8.36c9.4-43.52 35.47-50.77 63.34-54.1 9.36 30.62 6.24 56.45-2.64 80.05 82.25 56.3 76.75 117.23 81.37 149.11 4.4 30.35 4.45 89.29 25.51 97.21v-29.83l5.28-7 5.28 12.32 10.56-15.84 11.44 21.11 11.43-21.1zm79.17-95L331.06 366c7.47-4.36 13.76-8.42 19.35-12.32-.6 7.22-.27 13.84-3.51 22.84zm28.15-49.26c-.4 10.94-.9 21.66-1.76 31.67-7.85-1.86-15.57-3.8-21.11-7 8.24-7.94 15.55-16.32 22.87-24.68zm24.63 5.28c0-13.43-2.05-24.21-5.28-33.43a235 235 0 0 1-18.47 27.27zm3.52-80.94c19.44 12.81 27.8 33.66 29.91 56.3-12.32-4.53-24.63-9.31-36.95-10.56 5.06-12 6.65-28.14 7-45.74zm-1.76-45.74c.81 14.3 1.84 28.82 1.76 42.23 19.22-8.11 29.78-9.72 44-14.08-10.61-18.96-27.2-25.53-45.76-28.16zM165.68 376.52L181.52 366c-7.47-4.36-13.76-8.42-19.35-12.32.6 7.26.27 13.88 3.51 22.88zm-28.15-49.26c.4 10.94.9 21.66 1.76 31.67 7.85-1.86 15.57-3.8 21.11-7-8.24-7.93-15.55-16.31-22.87-24.67zm-24.64 5.28c0-13.43 2-24.21 5.28-33.43a235 235 0 0 0 18.47 27.27zm-3.52-80.94c-19.44 12.81-27.8 33.66-29.91 56.3 12.32-4.53 24.63-9.31 37-10.56-5-12-6.65-28.14-7-45.74zm1.76-45.74c-.81 14.3-1.84 28.82-1.76 42.23-19.22-8.11-29.78-9.72-44-14.08 10.63-18.95 27.23-25.52 45.76-28.15z\"],\n    \"wordpress\": [512, 512, [], \"f19a\", \"M61.7 169.4l101.5 278C92.2 413 43.3 340.2 43.3 256c0-30.9 6.6-60.1 18.4-86.6zm337.9 75.9c0-26.3-9.4-44.5-17.5-58.7-10.8-17.5-20.9-32.4-20.9-49.9 0-19.6 14.8-37.8 35.7-37.8.9 0 1.8.1 2.8.2-37.9-34.7-88.3-55.9-143.7-55.9-74.3 0-139.7 38.1-177.8 95.9 5 .2 9.7.3 13.7.3 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l77.5 230.4L249.8 247l-33.1-90.8c-11.5-.7-22.3-2-22.3-2-11.5-.7-10.1-18.2 1.3-17.5 0 0 35.1 2.7 56 2.7 22.2 0 56.7-2.7 56.7-2.7 11.5-.7 12.8 16.2 1.4 17.5 0 0-11.5 1.3-24.3 2l76.9 228.7 21.2-70.9c9-29.4 16-50.5 16-68.7zm-139.9 29.3l-63.8 185.5c19.1 5.6 39.2 8.7 60.1 8.7 24.8 0 48.5-4.3 70.6-12.1-.6-.9-1.1-1.9-1.5-2.9l-65.4-179.2zm183-120.7c.9 6.8 1.4 14 1.4 21.9 0 21.6-4 45.8-16.2 76.2l-65 187.9C426.2 403 468.7 334.5 468.7 256c0-37-9.4-71.8-26-102.1zM504 256c0 136.8-111.3 248-248 248C119.2 504 8 392.7 8 256 8 119.2 119.2 8 256 8c136.7 0 248 111.2 248 248zm-11.4 0c0-130.5-106.2-236.6-236.6-236.6C125.5 19.4 19.4 125.5 19.4 256S125.6 492.6 256 492.6c130.5 0 236.6-106.1 236.6-236.6z\"],\n    \"wordpress-simple\": [512, 512, [], \"f411\", \"M256 8C119.3 8 8 119.2 8 256c0 136.7 111.3 248 248 248s248-111.3 248-248C504 119.2 392.7 8 256 8zM33 256c0-32.3 6.9-63 19.3-90.7l106.4 291.4C84.3 420.5 33 344.2 33 256zm223 223c-21.9 0-43-3.2-63-9.1l66.9-194.4 68.5 187.8c.5 1.1 1 2.1 1.6 3.1-23.1 8.1-48 12.6-74 12.6zm30.7-327.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-21.9 0-58.7-2.8-58.7-2.8-12-.7-13.4 17.7-1.4 18.4 0 0 11.4 1.4 23.4 2.1l34.7 95.2L200.6 393l-81.2-241.5c13.4-.7 25.5-2.1 25.5-2.1 12-1.4 10.6-19.1-1.4-18.4 0 0-36.1 2.8-59.4 2.8-4.2 0-9.1-.1-14.4-.3C109.6 73 178.1 33 256 33c58 0 110.9 22.2 150.6 58.5-1-.1-1.9-.2-2.9-.2-21.9 0-37.4 19.1-37.4 39.6 0 18.4 10.6 33.9 21.9 52.3 8.5 14.8 18.4 33.9 18.4 61.5 0 19.1-7.3 41.2-17 72.1l-22.2 74.3-80.7-239.6zm81.4 297.2l68.1-196.9c12.7-31.8 17-57.2 17-79.9 0-8.2-.5-15.8-1.5-22.9 17.4 31.8 27.3 68.2 27.3 107 0 82.3-44.6 154.1-110.9 192.7z\"],\n    \"wpbeginner\": [512, 512, [], \"f297\", \"M462.799 322.374C519.01 386.682 466.961 480 370.944 480c-39.602 0-78.824-17.687-100.142-50.04-6.887.356-22.702.356-29.59 0C219.848 462.381 180.588 480 141.069 480c-95.49 0-148.348-92.996-91.855-157.626C-29.925 190.523 80.479 32 256.006 32c175.632 0 285.87 158.626 206.793 290.374zm-339.647-82.972h41.529v-58.075h-41.529v58.075zm217.18 86.072v-23.839c-60.506 20.915-132.355 9.198-187.589-33.971l.246 24.897c51.101 46.367 131.746 57.875 187.343 32.913zm-150.753-86.072h166.058v-58.075H189.579v58.075z\"],\n    \"wpexplorer\": [512, 512, [], \"f2de\", \"M512 256c0 141.2-114.7 256-256 256C114.8 512 0 397.3 0 256S114.7 0 256 0s256 114.7 256 256zm-32 0c0-123.2-100.3-224-224-224C132.5 32 32 132.5 32 256s100.5 224 224 224 224-100.5 224-224zM160.9 124.6l86.9 37.1-37.1 86.9-86.9-37.1 37.1-86.9zm110 169.1l46.6 94h-14.6l-50-100-48.9 100h-14l51.1-106.9-22.3-9.4 6-14 68.6 29.1-6 14.3-16.5-7.1zm-11.8-116.3l68.6 29.4-29.4 68.3L230 246l29.1-68.6zm80.3 42.9l54.6 23.1-23.4 54.3-54.3-23.1 23.1-54.3z\"],\n    \"wpforms\": [448, 512, [], \"f298\", \"M448 75.2v361.7c0 24.3-19 43.2-43.2 43.2H43.2C19.3 480 0 461.4 0 436.8V75.2C0 51.1 18.8 32 43.2 32h361.7c24 0 43.1 18.8 43.1 43.2zm-37.3 361.6V75.2c0-3-2.6-5.8-5.8-5.8h-9.3L285.3 144 224 94.1 162.8 144 52.5 69.3h-9.3c-3.2 0-5.8 2.8-5.8 5.8v361.7c0 3 2.6 5.8 5.8 5.8h361.7c3.2.1 5.8-2.7 5.8-5.8zM150.2 186v37H76.7v-37h73.5zm0 74.4v37.3H76.7v-37.3h73.5zm11.1-147.3l54-43.7H96.8l64.5 43.7zm210 72.9v37h-196v-37h196zm0 74.4v37.3h-196v-37.3h196zm-84.6-147.3l64.5-43.7H232.8l53.9 43.7zM371.3 335v37.3h-99.4V335h99.4z\"],\n    \"wpressr\": [496, 512, [], \"f3e4\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm171.33 158.6c-15.18 34.51-30.37 69.02-45.63 103.5-2.44 5.51-6.89 8.24-12.97 8.24-23.02-.01-46.03.06-69.05-.05-5.12-.03-8.25 1.89-10.34 6.72-10.19 23.56-20.63 47-30.95 70.5-1.54 3.51-4.06 5.29-7.92 5.29-45.94-.01-91.87-.02-137.81 0-3.13 0-5.63-1.15-7.72-3.45-11.21-12.33-22.46-24.63-33.68-36.94-2.69-2.95-2.79-6.18-1.21-9.73 8.66-19.54 17.27-39.1 25.89-58.66 12.93-29.35 25.89-58.69 38.75-88.08 1.7-3.88 4.28-5.68 8.54-5.65 14.24.1 28.48.02 42.72.05 6.24.01 9.2 4.84 6.66 10.59-13.6 30.77-27.17 61.55-40.74 92.33-5.72 12.99-11.42 25.99-17.09 39-3.91 8.95 7.08 11.97 10.95 5.6.23-.37-1.42 4.18 30.01-67.69 1.36-3.1 3.41-4.4 6.77-4.39 15.21.08 30.43.02 45.64.04 5.56.01 7.91 3.64 5.66 8.75-8.33 18.96-16.71 37.9-24.98 56.89-4.98 11.43 8.08 12.49 11.28 5.33.04-.08 27.89-63.33 32.19-73.16 2.02-4.61 5.44-6.51 10.35-6.5 26.43.05 52.86 0 79.29.05 12.44.02 13.93-13.65 3.9-13.64-25.26.03-50.52.02-75.78.02-6.27 0-7.84-2.47-5.27-8.27 5.78-13.06 11.59-26.11 17.3-39.21 1.73-3.96 4.52-5.79 8.84-5.78 23.09.06 25.98.02 130.78.03 6.08-.01 8.03 2.79 5.62 8.27z\"],\n    \"xbox\": [512, 512, [], \"f412\", \"M369.9 318.2c44.3 54.3 64.7 98.8 54.4 118.7-7.9 15.1-56.7 44.6-92.6 55.9-29.6 9.3-68.4 13.3-100.4 10.2-38.2-3.7-76.9-17.4-110.1-39C93.3 445.8 87 438.3 87 423.4c0-29.9 32.9-82.3 89.2-142.1 32-33.9 76.5-73.7 81.4-72.6 9.4 2.1 84.3 75.1 112.3 109.5zM188.6 143.8c-29.7-26.9-58.1-53.9-86.4-63.4-15.2-5.1-16.3-4.8-28.7 8.1-29.2 30.4-53.5 79.7-60.3 122.4-5.4 34.2-6.1 43.8-4.2 60.5 5.6 50.5 17.3 85.4 40.5 120.9 9.5 14.6 12.1 17.3 9.3 9.9-4.2-11-.3-37.5 9.5-64 14.3-39 53.9-112.9 120.3-194.4zm311.6 63.5C483.3 127.3 432.7 77 425.6 77c-7.3 0-24.2 6.5-36 13.9-23.3 14.5-41 31.4-64.3 52.8C367.7 197 427.5 283.1 448.2 346c6.8 20.7 9.7 41.1 7.4 52.3-1.7 8.5-1.7 8.5 1.4 4.6 6.1-7.7 19.9-31.3 25.4-43.5 7.4-16.2 15-40.2 18.6-58.7 4.3-22.5 3.9-70.8-.8-93.4zM141.3 43C189 40.5 251 77.5 255.6 78.4c.7.1 10.4-4.2 21.6-9.7 63.9-31.1 94-25.8 107.4-25.2-63.9-39.3-152.7-50-233.9-11.7-23.4 11.1-24 11.9-9.4 11.2z\"],\n    \"xing\": [384, 512, [], \"f168\", \"M162.7 210c-1.8 3.3-25.2 44.4-70.1 123.5-4.9 8.3-10.8 12.5-17.7 12.5H9.8c-7.7 0-12.1-7.5-8.5-14.4l69-121.3c.2 0 .2-.1 0-.3l-43.9-75.6c-4.3-7.8.3-14.1 8.5-14.1H100c7.3 0 13.3 4.1 18 12.2l44.7 77.5zM382.6 46.1l-144 253v.3L330.2 466c3.9 7.1.2 14.1-8.5 14.1h-65.2c-7.6 0-13.6-4-18-12.2l-92.4-168.5c3.3-5.8 51.5-90.8 144.8-255.2 4.6-8.1 10.4-12.2 17.5-12.2h65.7c8 0 12.3 6.7 8.5 14.1z\"],\n    \"xing-square\": [448, 512, [], \"f169\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM140.4 320.2H93.8c-5.5 0-8.7-5.3-6-10.3l49.3-86.7c.1 0 .1-.1 0-.2l-31.4-54c-3-5.6.2-10.1 6-10.1h46.6c5.2 0 9.5 2.9 12.9 8.7l31.9 55.3c-1.3 2.3-18 31.7-50.1 88.2-3.5 6.2-7.7 9.1-12.6 9.1zm219.7-214.1L257.3 286.8v.2l65.5 119c2.8 5.1.1 10.1-6 10.1h-46.6c-5.5 0-9.7-2.9-12.9-8.7l-66-120.3c2.3-4.1 36.8-64.9 103.4-182.3 3.3-5.8 7.4-8.7 12.5-8.7h46.9c5.7-.1 8.8 4.7 6 10z\"],\n    \"y-combinator\": [448, 512, [], \"f23b\", \"M448 32v448H0V32h448zM236 287.5L313.5 142h-32.7L235 233c-4.7 9.3-9 18.3-12.8 26.8L210 233l-45.2-91h-35l76.7 143.8v94.5H236v-92.8z\"],\n    \"yahoo\": [448, 512, [], \"f19e\", \"M252 292l4 220c-12.7-2.2-23.5-3.9-32.3-3.9-8.4 0-19.2 1.7-32.3 3.9l4-220C140.4 197.2 85 95.2 21.4 0c11.9 3.1 23 3.9 33.2 3.9 9 0 20.4-.8 34.1-3.9 40.9 72.2 82.1 138.7 135 225.5C261 163.9 314.8 81.4 358.6 0c11.1 2.9 22 3.9 32.9 3.9 11.5 0 23.2-1 35-3.9C392.1 47.9 294.9 216.9 252 292z\"],\n    \"yammer\": [512, 512, [], \"f840\", \"M421.78 152.17A23.06 23.06 0 0 0 400.9 112c-.83.43-1.71.9-2.63 1.4-15.25 8.4-118.33 80.62-106.69 88.77s82.04-23.61 130.2-50zm0 217.17c-48.16-26.38-118.64-58.1-130.2-50s91.42 80.35 106.69 88.74c.92.51 1.8 1 2.63 1.41a23.07 23.07 0 0 0 20.88-40.15zM464.21 237c-.95 0-1.95-.06-3-.06-17.4 0-142.52 13.76-136.24 26.51s83.3 18.74 138.21 18.76a23 23 0 0 0 1-45.21zM31 96.65a24.88 24.88 0 0 1 46.14-18.4l81 205.06h1.21l77-203.53a23.52 23.52 0 0 1 44.45 15.27L171.2 368.44C152.65 415.66 134.08 448 77.91 448a139.67 139.67 0 0 1-23.81-1.95 21.31 21.31 0 0 1 6.9-41.77c.66.06 10.91.66 13.86.66 30.47 0 43.74-18.94 58.07-59.41z\"],\n    \"yandex\": [256, 512, [], \"f413\", \"M153.1 315.8L65.7 512H2l96-209.8c-45.1-22.9-75.2-64.4-75.2-141.1C22.7 53.7 90.8 0 171.7 0H254v512h-55.1V315.8h-45.8zm45.8-269.3h-29.4c-44.4 0-87.4 29.4-87.4 114.6 0 82.3 39.4 108.8 87.4 108.8h29.4V46.5z\"],\n    \"yandex-international\": [320, 512, [], \"f414\", \"M129.5 512V345.9L18.5 48h55.8l81.8 229.7L250.2 0h51.3L180.8 347.8V512h-51.3z\"],\n    \"yarn\": [496, 512, [], \"f7e3\", \"M393.9 345.2c-39 9.3-48.4 32.1-104 47.4 0 0-2.7 4-10.4 5.8-13.4 3.3-63.9 6-68.5 6.1-12.4.1-19.9-3.2-22-8.2-6.4-15.3 9.2-22 9.2-22-8.1-5-9-9.9-9.8-8.1-2.4 5.8-3.6 20.1-10.1 26.5-8.8 8.9-25.5 5.9-35.3.8-10.8-5.7.8-19.2.8-19.2s-5.8 3.4-10.5-3.6c-6-9.3-17.1-37.3 11.5-62-1.3-10.1-4.6-53.7 40.6-85.6 0 0-20.6-22.8-12.9-43.3 5-13.4 7-13.3 8.6-13.9 5.7-2.2 11.3-4.6 15.4-9.1 20.6-22.2 46.8-18 46.8-18s12.4-37.8 23.9-30.4c3.5 2.3 16.3 30.6 16.3 30.6s13.6-7.9 15.1-5c8.2 16 9.2 46.5 5.6 65.1-6.1 30.6-21.4 47.1-27.6 57.5-1.4 2.4 16.5 10 27.8 41.3 10.4 28.6 1.1 52.7 2.8 55.3.8 1.4 13.7.8 36.4-13.2 12.8-7.9 28.1-16.9 45.4-17 16.7-.5 17.6 19.2 4.9 22.2zM496 256c0 136.9-111.1 248-248 248S0 392.9 0 256 111.1 8 248 8s248 111.1 248 248zm-79.3 75.2c-1.7-13.6-13.2-23-28-22.8-22 .3-40.5 11.7-52.8 19.2-4.8 3-8.9 5.2-12.4 6.8 3.1-44.5-22.5-73.1-28.7-79.4 7.8-11.3 18.4-27.8 23.4-53.2 4.3-21.7 3-55.5-6.9-74.5-1.6-3.1-7.4-11.2-21-7.4-9.7-20-13-22.1-15.6-23.8-1.1-.7-23.6-16.4-41.4 28-12.2.9-31.3 5.3-47.5 22.8-2 2.2-5.9 3.8-10.1 5.4h.1c-8.4 3-12.3 9.9-16.9 22.3-6.5 17.4.2 34.6 6.8 45.7-17.8 15.9-37 39.8-35.7 82.5-34 36-11.8 73-5.6 79.6-1.6 11.1 3.7 19.4 12 23.8 12.6 6.7 30.3 9.6 43.9 2.8 4.9 5.2 13.8 10.1 30 10.1 6.8 0 58-2.9 72.6-6.5 6.8-1.6 11.5-4.5 14.6-7.1 9.8-3.1 36.8-12.3 62.2-28.7 18-11.7 24.2-14.2 37.6-17.4 12.9-3.2 21-15.1 19.4-28.2z\"],\n    \"yelp\": [384, 512, [], \"f1e9\", \"M42.9 240.32l99.62 48.61c19.2 9.4 16.2 37.51-4.5 42.71L30.5 358.45a22.79 22.79 0 0 1-28.21-19.6 197.16 197.16 0 0 1 9-85.32 22.8 22.8 0 0 1 31.61-13.21zm44 239.25a199.45 199.45 0 0 0 79.42 32.11A22.78 22.78 0 0 0 192.94 490l3.9-110.82c.7-21.3-25.5-31.91-39.81-16.1l-74.21 82.4a22.82 22.82 0 0 0 4.09 34.09zm145.34-109.92l58.81 94a22.93 22.93 0 0 0 34 5.5 198.36 198.36 0 0 0 52.71-67.61A23 23 0 0 0 364.17 370l-105.42-34.26c-20.31-6.5-37.81 15.8-26.51 33.91zm148.33-132.23a197.44 197.44 0 0 0-50.41-69.31 22.85 22.85 0 0 0-34 4.4l-62 91.92c-11.9 17.7 4.7 40.61 25.2 34.71L366 268.63a23 23 0 0 0 14.61-31.21zM62.11 30.18a22.86 22.86 0 0 0-9.9 32l104.12 180.44c11.7 20.2 42.61 11.9 42.61-11.4V22.88a22.67 22.67 0 0 0-24.5-22.8 320.37 320.37 0 0 0-112.33 30.1z\"],\n    \"yoast\": [448, 512, [], \"f2b1\", \"M91.3 76h186l-7 18.9h-179c-39.7 0-71.9 31.6-71.9 70.3v205.4c0 35.4 24.9 70.3 84 70.3V460H91.3C41.2 460 0 419.8 0 370.5V165.2C0 115.9 40.7 76 91.3 76zm229.1-56h66.5C243.1 398.1 241.2 418.9 202.2 459.3c-20.8 21.6-49.3 31.7-78.3 32.7v-51.1c49.2-7.7 64.6-49.9 64.6-75.3 0-20.1.6-12.6-82.1-223.2h61.4L218.2 299 320.4 20zM448 161.5V460H234c6.6-9.6 10.7-16.3 12.1-19.4h182.5V161.5c0-32.5-17.1-51.9-48.2-62.9l6.7-17.6c41.7 13.6 60.9 43.1 60.9 80.5z\"],\n    \"youtube\": [576, 512, [], \"f167\", \"M549.655 124.083c-6.281-23.65-24.787-42.276-48.284-48.597C458.781 64 288 64 288 64S117.22 64 74.629 75.486c-23.497 6.322-42.003 24.947-48.284 48.597-11.412 42.867-11.412 132.305-11.412 132.305s0 89.438 11.412 132.305c6.281 23.65 24.787 41.5 48.284 47.821C117.22 448 288 448 288 448s170.78 0 213.371-11.486c23.497-6.321 42.003-24.171 48.284-47.821 11.412-42.867 11.412-132.305 11.412-132.305s0-89.438-11.412-132.305zm-317.51 213.508V175.185l142.739 81.205-142.739 81.201z\"],\n    \"youtube-square\": [448, 512, [], \"f431\", \"M186.8 202.1l95.2 54.1-95.2 54.1V202.1zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-42 176.3s0-59.6-7.6-88.2c-4.2-15.8-16.5-28.2-32.2-32.4C337.9 128 224 128 224 128s-113.9 0-142.2 7.7c-15.7 4.2-28 16.6-32.2 32.4-7.6 28.5-7.6 88.2-7.6 88.2s0 59.6 7.6 88.2c4.2 15.8 16.5 27.7 32.2 31.9C110.1 384 224 384 224 384s113.9 0 142.2-7.7c15.7-4.2 28-16.1 32.2-31.9 7.6-28.5 7.6-88.1 7.6-88.1z\"],\n    \"zhihu\": [640, 512, [], \"f63f\", \"M170.54 148.13v217.54l23.43.01 7.71 26.37 42.01-26.37h49.53V148.13H170.54zm97.75 193.93h-27.94l-27.9 17.51-5.08-17.47-11.9-.04V171.75h72.82v170.31zm-118.46-94.39H97.5c1.74-27.1 2.2-51.59 2.2-73.46h51.16s1.97-22.56-8.58-22.31h-88.5c3.49-13.12 7.87-26.66 13.12-40.67 0 0-24.07 0-32.27 21.57-3.39 8.9-13.21 43.14-30.7 78.12 5.89-.64 25.37-1.18 36.84-22.21 2.11-5.89 2.51-6.66 5.14-14.53h28.87c0 10.5-1.2 66.88-1.68 73.44H20.83c-11.74 0-15.56 23.62-15.56 23.62h65.58C66.45 321.1 42.83 363.12 0 396.34c20.49 5.85 40.91-.93 51-9.9 0 0 22.98-20.9 35.59-69.25l53.96 64.94s7.91-26.89-1.24-39.99c-7.58-8.92-28.06-33.06-36.79-41.81L87.9 311.95c4.36-13.98 6.99-27.55 7.87-40.67h61.65s-.09-23.62-7.59-23.62v.01zm412.02-1.6c20.83-25.64 44.98-58.57 44.98-58.57s-18.65-14.8-27.38-4.06c-6 8.15-36.83 48.2-36.83 48.2l19.23 14.43zm-150.09-59.09c-9.01-8.25-25.91 2.13-25.91 2.13s39.52 55.04 41.12 57.45l19.46-13.73s-25.67-37.61-34.66-45.86h-.01zM640 258.35c-19.78 0-130.91.93-131.06.93v-101c4.81 0 12.42-.4 22.85-1.2 40.88-2.41 70.13-4 87.77-4.81 0 0 12.22-27.19-.59-33.44-3.07-1.18-23.17 4.58-23.17 4.58s-165.22 16.49-232.36 18.05c1.6 8.82 7.62 17.08 15.78 19.55 13.31 3.48 22.69 1.7 49.15.89 24.83-1.6 43.68-2.43 56.51-2.43v99.81H351.41s2.82 22.31 25.51 22.85h107.94v70.92c0 13.97-11.19 21.99-24.48 21.12-14.08.11-26.08-1.15-41.69-1.81 1.99 3.97 6.33 14.39 19.31 21.84 9.88 4.81 16.17 6.57 26.02 6.57 29.56 0 45.67-17.28 44.89-45.31v-73.32h122.36c9.68 0 8.7-23.78 8.7-23.78l.03-.01z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fab', icons);\n  });\n\n}());\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/conflict-detection.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? factory(exports) :\n  typeof define === 'function' && define.amd ? define(['exports'], factory) :\n  (factory((global['fontawesome-free-conflict-detection'] = {})));\n}(this, (function (exports) { 'use strict';\n\n  function _typeof(obj) {\n    if (typeof Symbol === \"function\" && typeof Symbol.iterator === \"symbol\") {\n      _typeof = function (obj) {\n        return typeof obj;\n      };\n    } else {\n      _typeof = function (obj) {\n        return obj && typeof Symbol === \"function\" && obj.constructor === Symbol && obj !== Symbol.prototype ? \"symbol\" : typeof obj;\n      };\n    }\n\n    return _typeof(obj);\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var functions = [];\n\n  var listener = function listener() {\n    DOCUMENT.removeEventListener('DOMContentLoaded', listener);\n    loaded = 1;\n    functions.map(function (fn) {\n      return fn();\n    });\n  };\n\n  var loaded = false;\n\n  if (IS_DOM) {\n    loaded = (DOCUMENT.documentElement.doScroll ? /^loaded|^c/ : /^loaded|^i|^c/).test(DOCUMENT.readyState);\n    if (!loaded) DOCUMENT.addEventListener('DOMContentLoaded', listener);\n  }\n\n  function domready (fn) {\n    if (!IS_DOM) return;\n    loaded ? setTimeout(fn, 0) : functions.push(fn);\n  }\n\n  function report (_ref) {\n    var nodesTested = _ref.nodesTested,\n        nodesFound = _ref.nodesFound;\n    var timedOutTests = {};\n\n    for (var key in nodesFound) {\n      if (!(nodesTested.conflict[key] || nodesTested.noConflict[key])) {\n        timedOutTests[key] = nodesFound[key];\n      }\n    }\n\n    var conflictsCount = Object.keys(nodesTested.conflict).length;\n\n    if (conflictsCount > 0) {\n      console.info(\"%cConflict\".concat(conflictsCount > 1 ? 's' : '', \" found:\"), 'color: darkred; font-size: large');\n      var data = {};\n\n      for (var _key in nodesTested.conflict) {\n        var item = nodesTested.conflict[_key];\n        data[_key] = {\n          'tagName': item.tagName,\n          'src/href': item.src || item.href || 'n/a',\n          'innerText excerpt': item.innerText && item.innerText !== '' ? item.innerText.slice(0, 200) + '...' : '(empty)'\n        };\n      }\n\n      console.table(data);\n    }\n\n    var noConflictsCount = Object.keys(nodesTested.noConflict).length;\n\n    if (noConflictsCount > 0) {\n      console.info(\"%cNo conflict\".concat(noConflictsCount > 1 ? 's' : '', \" found with \").concat(noConflictsCount == 1 ? 'this' : 'these', \":\"), 'color: green; font-size: large');\n      var _data = {};\n\n      for (var _key2 in nodesTested.noConflict) {\n        var _item = nodesTested.noConflict[_key2];\n        _data[_key2] = {\n          'tagName': _item.tagName,\n          'src/href': _item.src || _item.href || 'n/a',\n          'innerText excerpt': _item.innerText && _item.innerText !== '' ? _item.innerText.slice(0, 200) + '...' : '(empty)'\n        };\n      }\n\n      console.table(_data);\n    }\n\n    var timeOutCount = Object.keys(timedOutTests).length;\n\n    if (timeOutCount > 0) {\n      console.info(\"%cLeftovers--we timed out before collecting test results for \".concat(timeOutCount == 1 ? 'this' : 'these', \":\"), 'color: blue; font-size: large');\n      var _data2 = {};\n\n      for (var _key3 in timedOutTests) {\n        var _item2 = timedOutTests[_key3];\n        _data2[_key3] = {\n          'tagName': _item2.tagName,\n          'src/href': _item2.src || _item2.href || 'n/a',\n          'innerText excerpt': _item2.innerText && _item2.innerText !== '' ? _item2.innerText.slice(0, 200) + '...' : '(empty)'\n        };\n      }\n\n      console.table(_data2);\n    }\n  }\n\n  var commonjsGlobal = typeof window !== 'undefined' ? window : typeof global !== 'undefined' ? global : typeof self !== 'undefined' ? self : {};\n\n  function createCommonjsModule(fn, module) {\n  \treturn module = { exports: {} }, fn(module, module.exports), module.exports;\n  }\n\n  var md5 = createCommonjsModule(function (module) {\n\n    (function ($) {\n      /**\n       * Add integers, wrapping at 2^32.\n       * This uses 16-bit operations internally to work around bugs in interpreters.\n       *\n       * @param {number} x First integer\n       * @param {number} y Second integer\n       * @returns {number} Sum\n       */\n\n      function safeAdd(x, y) {\n        var lsw = (x & 0xffff) + (y & 0xffff);\n        var msw = (x >> 16) + (y >> 16) + (lsw >> 16);\n        return msw << 16 | lsw & 0xffff;\n      }\n      /**\n       * Bitwise rotate a 32-bit number to the left.\n       *\n       * @param {number} num 32-bit number\n       * @param {number} cnt Rotation count\n       * @returns {number} Rotated number\n       */\n\n\n      function bitRotateLeft(num, cnt) {\n        return num << cnt | num >>> 32 - cnt;\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} q q\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5cmn(q, a, b, x, s, t) {\n        return safeAdd(bitRotateLeft(safeAdd(safeAdd(a, q), safeAdd(x, t)), s), b);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5ff(a, b, c, d, x, s, t) {\n        return md5cmn(b & c | ~b & d, a, b, x, s, t);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5gg(a, b, c, d, x, s, t) {\n        return md5cmn(b & d | c & ~d, a, b, x, s, t);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5hh(a, b, c, d, x, s, t) {\n        return md5cmn(b ^ c ^ d, a, b, x, s, t);\n      }\n      /**\n       * Basic operation the algorithm uses.\n       *\n       * @param {number} a a\n       * @param {number} b b\n       * @param {number} c c\n       * @param {number} d d\n       * @param {number} x x\n       * @param {number} s s\n       * @param {number} t t\n       * @returns {number} Result\n       */\n\n\n      function md5ii(a, b, c, d, x, s, t) {\n        return md5cmn(c ^ (b | ~d), a, b, x, s, t);\n      }\n      /**\n       * Calculate the MD5 of an array of little-endian words, and a bit length.\n       *\n       * @param {Array} x Array of little-endian words\n       * @param {number} len Bit length\n       * @returns {Array<number>} MD5 Array\n       */\n\n\n      function binlMD5(x, len) {\n        /* append padding */\n        x[len >> 5] |= 0x80 << len % 32;\n        x[(len + 64 >>> 9 << 4) + 14] = len;\n        var i;\n        var olda;\n        var oldb;\n        var oldc;\n        var oldd;\n        var a = 1732584193;\n        var b = -271733879;\n        var c = -1732584194;\n        var d = 271733878;\n\n        for (i = 0; i < x.length; i += 16) {\n          olda = a;\n          oldb = b;\n          oldc = c;\n          oldd = d;\n          a = md5ff(a, b, c, d, x[i], 7, -680876936);\n          d = md5ff(d, a, b, c, x[i + 1], 12, -389564586);\n          c = md5ff(c, d, a, b, x[i + 2], 17, 606105819);\n          b = md5ff(b, c, d, a, x[i + 3], 22, -1044525330);\n          a = md5ff(a, b, c, d, x[i + 4], 7, -176418897);\n          d = md5ff(d, a, b, c, x[i + 5], 12, 1200080426);\n          c = md5ff(c, d, a, b, x[i + 6], 17, -1473231341);\n          b = md5ff(b, c, d, a, x[i + 7], 22, -45705983);\n          a = md5ff(a, b, c, d, x[i + 8], 7, 1770035416);\n          d = md5ff(d, a, b, c, x[i + 9], 12, -1958414417);\n          c = md5ff(c, d, a, b, x[i + 10], 17, -42063);\n          b = md5ff(b, c, d, a, x[i + 11], 22, -1990404162);\n          a = md5ff(a, b, c, d, x[i + 12], 7, 1804603682);\n          d = md5ff(d, a, b, c, x[i + 13], 12, -40341101);\n          c = md5ff(c, d, a, b, x[i + 14], 17, -1502002290);\n          b = md5ff(b, c, d, a, x[i + 15], 22, 1236535329);\n          a = md5gg(a, b, c, d, x[i + 1], 5, -165796510);\n          d = md5gg(d, a, b, c, x[i + 6], 9, -1069501632);\n          c = md5gg(c, d, a, b, x[i + 11], 14, 643717713);\n          b = md5gg(b, c, d, a, x[i], 20, -373897302);\n          a = md5gg(a, b, c, d, x[i + 5], 5, -701558691);\n          d = md5gg(d, a, b, c, x[i + 10], 9, 38016083);\n          c = md5gg(c, d, a, b, x[i + 15], 14, -660478335);\n          b = md5gg(b, c, d, a, x[i + 4], 20, -405537848);\n          a = md5gg(a, b, c, d, x[i + 9], 5, 568446438);\n          d = md5gg(d, a, b, c, x[i + 14], 9, -1019803690);\n          c = md5gg(c, d, a, b, x[i + 3], 14, -187363961);\n          b = md5gg(b, c, d, a, x[i + 8], 20, 1163531501);\n          a = md5gg(a, b, c, d, x[i + 13], 5, -1444681467);\n          d = md5gg(d, a, b, c, x[i + 2], 9, -51403784);\n          c = md5gg(c, d, a, b, x[i + 7], 14, 1735328473);\n          b = md5gg(b, c, d, a, x[i + 12], 20, -1926607734);\n          a = md5hh(a, b, c, d, x[i + 5], 4, -378558);\n          d = md5hh(d, a, b, c, x[i + 8], 11, -2022574463);\n          c = md5hh(c, d, a, b, x[i + 11], 16, 1839030562);\n          b = md5hh(b, c, d, a, x[i + 14], 23, -35309556);\n          a = md5hh(a, b, c, d, x[i + 1], 4, -1530992060);\n          d = md5hh(d, a, b, c, x[i + 4], 11, 1272893353);\n          c = md5hh(c, d, a, b, x[i + 7], 16, -155497632);\n          b = md5hh(b, c, d, a, x[i + 10], 23, -1094730640);\n          a = md5hh(a, b, c, d, x[i + 13], 4, 681279174);\n          d = md5hh(d, a, b, c, x[i], 11, -358537222);\n          c = md5hh(c, d, a, b, x[i + 3], 16, -722521979);\n          b = md5hh(b, c, d, a, x[i + 6], 23, 76029189);\n          a = md5hh(a, b, c, d, x[i + 9], 4, -640364487);\n          d = md5hh(d, a, b, c, x[i + 12], 11, -421815835);\n          c = md5hh(c, d, a, b, x[i + 15], 16, 530742520);\n          b = md5hh(b, c, d, a, x[i + 2], 23, -995338651);\n          a = md5ii(a, b, c, d, x[i], 6, -198630844);\n          d = md5ii(d, a, b, c, x[i + 7], 10, 1126891415);\n          c = md5ii(c, d, a, b, x[i + 14], 15, -1416354905);\n          b = md5ii(b, c, d, a, x[i + 5], 21, -57434055);\n          a = md5ii(a, b, c, d, x[i + 12], 6, 1700485571);\n          d = md5ii(d, a, b, c, x[i + 3], 10, -1894986606);\n          c = md5ii(c, d, a, b, x[i + 10], 15, -1051523);\n          b = md5ii(b, c, d, a, x[i + 1], 21, -2054922799);\n          a = md5ii(a, b, c, d, x[i + 8], 6, 1873313359);\n          d = md5ii(d, a, b, c, x[i + 15], 10, -30611744);\n          c = md5ii(c, d, a, b, x[i + 6], 15, -1560198380);\n          b = md5ii(b, c, d, a, x[i + 13], 21, 1309151649);\n          a = md5ii(a, b, c, d, x[i + 4], 6, -145523070);\n          d = md5ii(d, a, b, c, x[i + 11], 10, -1120210379);\n          c = md5ii(c, d, a, b, x[i + 2], 15, 718787259);\n          b = md5ii(b, c, d, a, x[i + 9], 21, -343485551);\n          a = safeAdd(a, olda);\n          b = safeAdd(b, oldb);\n          c = safeAdd(c, oldc);\n          d = safeAdd(d, oldd);\n        }\n\n        return [a, b, c, d];\n      }\n      /**\n       * Convert an array of little-endian words to a string\n       *\n       * @param {Array<number>} input MD5 Array\n       * @returns {string} MD5 string\n       */\n\n\n      function binl2rstr(input) {\n        var i;\n        var output = '';\n        var length32 = input.length * 32;\n\n        for (i = 0; i < length32; i += 8) {\n          output += String.fromCharCode(input[i >> 5] >>> i % 32 & 0xff);\n        }\n\n        return output;\n      }\n      /**\n       * Convert a raw string to an array of little-endian words\n       * Characters >255 have their high-byte silently ignored.\n       *\n       * @param {string} input Raw input string\n       * @returns {Array<number>} Array of little-endian words\n       */\n\n\n      function rstr2binl(input) {\n        var i;\n        var output = [];\n        output[(input.length >> 2) - 1] = undefined;\n\n        for (i = 0; i < output.length; i += 1) {\n          output[i] = 0;\n        }\n\n        var length8 = input.length * 8;\n\n        for (i = 0; i < length8; i += 8) {\n          output[i >> 5] |= (input.charCodeAt(i / 8) & 0xff) << i % 32;\n        }\n\n        return output;\n      }\n      /**\n       * Calculate the MD5 of a raw string\n       *\n       * @param {string} s Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rstrMD5(s) {\n        return binl2rstr(binlMD5(rstr2binl(s), s.length * 8));\n      }\n      /**\n       * Calculates the HMAC-MD5 of a key and some data (raw strings)\n       *\n       * @param {string} key HMAC key\n       * @param {string} data Raw input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rstrHMACMD5(key, data) {\n        var i;\n        var bkey = rstr2binl(key);\n        var ipad = [];\n        var opad = [];\n        var hash;\n        ipad[15] = opad[15] = undefined;\n\n        if (bkey.length > 16) {\n          bkey = binlMD5(bkey, key.length * 8);\n        }\n\n        for (i = 0; i < 16; i += 1) {\n          ipad[i] = bkey[i] ^ 0x36363636;\n          opad[i] = bkey[i] ^ 0x5c5c5c5c;\n        }\n\n        hash = binlMD5(ipad.concat(rstr2binl(data)), 512 + data.length * 8);\n        return binl2rstr(binlMD5(opad.concat(hash), 512 + 128));\n      }\n      /**\n       * Convert a raw string to a hex string\n       *\n       * @param {string} input Raw input string\n       * @returns {string} Hex encoded string\n       */\n\n\n      function rstr2hex(input) {\n        var hexTab = '0123456789abcdef';\n        var output = '';\n        var x;\n        var i;\n\n        for (i = 0; i < input.length; i += 1) {\n          x = input.charCodeAt(i);\n          output += hexTab.charAt(x >>> 4 & 0x0f) + hexTab.charAt(x & 0x0f);\n        }\n\n        return output;\n      }\n      /**\n       * Encode a string as UTF-8\n       *\n       * @param {string} input Input string\n       * @returns {string} UTF8 string\n       */\n\n\n      function str2rstrUTF8(input) {\n        return unescape(encodeURIComponent(input));\n      }\n      /**\n       * Encodes input string as raw MD5 string\n       *\n       * @param {string} s Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rawMD5(s) {\n        return rstrMD5(str2rstrUTF8(s));\n      }\n      /**\n       * Encodes input string as Hex encoded string\n       *\n       * @param {string} s Input string\n       * @returns {string} Hex encoded string\n       */\n\n\n      function hexMD5(s) {\n        return rstr2hex(rawMD5(s));\n      }\n      /**\n       * Calculates the raw HMAC-MD5 for the given key and data\n       *\n       * @param {string} k HMAC key\n       * @param {string} d Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function rawHMACMD5(k, d) {\n        return rstrHMACMD5(str2rstrUTF8(k), str2rstrUTF8(d));\n      }\n      /**\n       * Calculates the Hex encoded HMAC-MD5 for the given key and data\n       *\n       * @param {string} k HMAC key\n       * @param {string} d Input string\n       * @returns {string} Raw MD5 string\n       */\n\n\n      function hexHMACMD5(k, d) {\n        return rstr2hex(rawHMACMD5(k, d));\n      }\n      /**\n       * Calculates MD5 value for a given string.\n       * If a key is provided, calculates the HMAC-MD5 value.\n       * Returns a Hex encoded string unless the raw argument is given.\n       *\n       * @param {string} string Input string\n       * @param {string} [key] HMAC key\n       * @param {boolean} raw Raw oytput switch\n       * @returns {string} MD5 output\n       */\n\n\n      function md5(string, key, raw) {\n        if (!key) {\n          if (!raw) {\n            return hexMD5(string);\n          }\n\n          return rawMD5(string);\n        }\n\n        if (!raw) {\n          return hexHMACMD5(key, string);\n        }\n\n        return rawHMACMD5(key, string);\n      }\n\n      if (module.exports) {\n        module.exports = md5;\n      } else {\n        $.md5 = md5;\n      }\n    })(commonjsGlobal);\n  });\n\n  function md5ForNode(node) {\n    if (null === node || 'object' !== _typeof(node)) return undefined;\n\n    if (node.src) {\n      return md5(node.src);\n    } else if (node.href) {\n      return md5(node.href);\n    } else if (node.innerText && '' !== node.innerText) {\n      // eslint-disable-line yoda\n      return md5(node.innerText);\n    } else {\n      return undefined;\n    }\n  }\n\n  var diagScriptId = 'fa-kits-diag';\n  var nodeUnderTestId = 'fa-kits-node-under-test';\n  var md5Attr = 'data-md5';\n  var detectionIgnoreAttr = 'data-fa-detection-ignore';\n  var timeoutAttr = 'data-fa-detection-timeout';\n  var resultsCollectionMaxWaitAttr = 'data-fa-detection-results-collection-max-wait';\n\n  function pollUntil(_ref) {\n    var _ref$fn = _ref.fn,\n        fn = _ref$fn === void 0 ? function () {\n      return true;\n    } : _ref$fn,\n        _ref$initialDuration = _ref.initialDuration,\n        initialDuration = _ref$initialDuration === void 0 ? 1 : _ref$initialDuration,\n        _ref$maxDuration = _ref.maxDuration,\n        maxDuration = _ref$maxDuration === void 0 ? WINDOW.FontAwesomeDetection.timeout : _ref$maxDuration,\n        _ref$showProgress = _ref.showProgress,\n        showProgress = _ref$showProgress === void 0 ? false : _ref$showProgress,\n        progressIndicator = _ref.progressIndicator;\n    return new Promise(function (resolve, reject) {\n      // eslint-disable-line compat/compat\n      function poll(duration, cumulativeDuration) {\n        setTimeout(function () {\n          var result = fn();\n\n          if (showProgress) {\n            console.info(progressIndicator);\n          }\n\n          if (!!result) {\n            // eslint-disable-line no-extra-boolean-cast\n            resolve(result);\n          } else {\n            var nextDuration = 250;\n            var nextCumulativeDuration = nextDuration + cumulativeDuration;\n\n            if (nextCumulativeDuration <= maxDuration) {\n              poll(nextDuration, nextCumulativeDuration);\n            } else {\n              reject('timeout'); // eslint-disable-line prefer-promise-reject-errors\n            }\n          }\n        }, duration);\n      }\n\n      poll(initialDuration, 0);\n    });\n  }\n\n  function detectWebfontConflicts() {\n    var linkTags = Array.from(DOCUMENT.getElementsByTagName('link')).filter(function (t) {\n      return !t.hasAttribute(detectionIgnoreAttr);\n    });\n    var styleTags = Array.from(DOCUMENT.getElementsByTagName('style')).filter(function (t) {\n      if (t.hasAttribute(detectionIgnoreAttr)) {\n        return false;\n      } // If the browser has loaded the FA5 CSS, let's not test that <style> element.\n      // Its enough that we'll be testing for traces of the corresponding JS being loaded, and testing\n      // this <style> would only produce a false negative anyway.\n\n\n      if (WINDOW.FontAwesomeConfig && t.innerText.match(new RegExp(\"svg:not\\\\(:root\\\\)\\\\.\".concat(WINDOW.FontAwesomeConfig.replacementClass)))) {\n        return false;\n      }\n\n      return true;\n    });\n\n    function runDiag(scriptOrLinkTag, md5) {\n      var diagFrame = DOCUMENT.createElement('iframe'); // Using \"visibility: hidden; position: absolute\" instead of \"display: none;\" because\n      // Firefox will not return the expected results for getComputedStyle if our iframe has display: none.\n\n      diagFrame.setAttribute('style', 'visibility: hidden; position: absolute; height: 0; width: 0;');\n      var testIconId = 'fa-test-icon-' + md5;\n      var iTag = DOCUMENT.createElement('i');\n      iTag.setAttribute('class', 'fa fa-coffee');\n      iTag.setAttribute('id', testIconId);\n      var diagScript = DOCUMENT.createElement('script');\n      diagScript.setAttribute('id', diagScriptId); // WARNING: this function will be toString()'d and assigned to innerText of the diag script\n      // element that we'll be putting into a diagnostic iframe.\n      // That means that this code won't compile until after the outer script has run and injected\n      // this code into the iframe. There are some compile time errors that might occur there.\n      // For example, using single line (double-slash) comments like this one inside that function\n      // will probably cause it to choke. Chrome will show an error like this:\n      // Uncaught SyntaxError: Unexpected end of input\n\n      var diagScriptFun = function diagScriptFun(nodeUnderTestId, testIconId, md5, parentOrigin) {\n        parent.FontAwesomeDetection.__pollUntil({\n          fn: function fn() {\n            var iEl = document.getElementById(testIconId);\n            var computedStyle = window.getComputedStyle(iEl);\n            var fontFamily = computedStyle.getPropertyValue('font-family');\n\n            if (!!fontFamily.match(/FontAwesome/) || !!fontFamily.match(/Font Awesome 5/)) {\n              return true;\n            } else {\n              return false;\n            }\n          }\n        }).then(function () {\n          var node = document.getElementById(nodeUnderTestId);\n          parent.postMessage({\n            type: 'fontawesome-conflict',\n            technology: 'webfont',\n            href: node.href,\n            innerText: node.innerText,\n            tagName: node.tagName,\n            md5: md5\n          }, parentOrigin);\n        }).catch(function (e) {\n          var node = document.getElementById(nodeUnderTestId);\n\n          if (e === 'timeout') {\n            parent.postMessage({\n              type: 'no-conflict',\n              technology: 'webfont',\n              href: node.src,\n              innerText: node.innerText,\n              tagName: node.tagName,\n              md5: md5\n            }, parentOrigin);\n          } else {\n            console.error(e);\n          }\n        });\n      };\n\n      var parentOrigin = WINDOW.location.origin === 'file://' ? '*' : WINDOW.location.origin;\n      diagScript.innerText = \"(\".concat(diagScriptFun.toString(), \")('\").concat(nodeUnderTestId, \"', '\").concat(testIconId || 'foo', \"', '\").concat(md5, \"', '\").concat(parentOrigin, \"');\");\n\n      diagFrame.onload = function () {\n        diagFrame.contentDocument.head.appendChild(diagScript);\n        diagFrame.contentDocument.head.appendChild(scriptOrLinkTag);\n        diagFrame.contentDocument.body.appendChild(iTag);\n      };\n\n      domready(function () {\n        return DOCUMENT.body.appendChild(diagFrame);\n      });\n    }\n\n    var cssByMD5 = {};\n\n    for (var i = 0; i < linkTags.length; i++) {\n      var linkUnderTest = DOCUMENT.createElement('link');\n      linkUnderTest.setAttribute('id', nodeUnderTestId);\n      linkUnderTest.setAttribute('href', linkTags[i].href);\n      linkUnderTest.setAttribute('rel', linkTags[i].rel);\n      var md5ForLink = md5ForNode(linkTags[i]);\n      linkUnderTest.setAttribute(md5Attr, md5ForLink);\n      cssByMD5[md5ForLink] = linkTags[i];\n      runDiag(linkUnderTest, md5ForLink);\n    }\n\n    for (var _i = 0; _i < styleTags.length; _i++) {\n      var styleUnderTest = DOCUMENT.createElement('style');\n      styleUnderTest.setAttribute('id', nodeUnderTestId);\n      var md5ForStyle = md5ForNode(styleTags[_i]);\n      styleUnderTest.setAttribute(md5Attr, md5ForStyle);\n      styleUnderTest.innerText = styleTags[_i].innerText;\n      cssByMD5[md5ForStyle] = styleTags[_i];\n      runDiag(styleUnderTest, md5ForStyle);\n    }\n\n    return cssByMD5;\n  }\n\n  function detectSvgConflicts(currentScript) {\n    var scripts = Array.from(DOCUMENT.scripts).filter(function (t) {\n      return !t.hasAttribute(detectionIgnoreAttr) && t !== currentScript;\n    });\n    var scriptsByMD5 = {};\n\n    var _loop = function _loop(scriptIdx) {\n      var diagFrame = DOCUMENT.createElement('iframe');\n      diagFrame.setAttribute('style', 'display:none;');\n      var scriptUnderTest = DOCUMENT.createElement('script');\n      scriptUnderTest.setAttribute('id', nodeUnderTestId);\n      var md5ForScript = md5ForNode(scripts[scriptIdx]);\n      scriptUnderTest.setAttribute(md5Attr, md5ForScript);\n      scriptsByMD5[md5ForScript] = scripts[scriptIdx];\n\n      if (scripts[scriptIdx].src !== '') {\n        scriptUnderTest.src = scripts[scriptIdx].src;\n      }\n\n      if (scripts[scriptIdx].innerText !== '') {\n        scriptUnderTest.innerText = scripts[scriptIdx].innerText;\n      }\n\n      scriptUnderTest.async = true;\n      var diagScript = DOCUMENT.createElement('script');\n      diagScript.setAttribute('id', diagScriptId);\n      var parentOrigin = WINDOW.location.origin === 'file://' ? '*' : WINDOW.location.origin;\n\n      var diagScriptFun = function diagScriptFun(nodeUnderTestId, md5, parentOrigin) {\n        parent.FontAwesomeDetection.__pollUntil({\n          fn: function fn() {\n            return !!window.FontAwesomeConfig;\n          }\n        }).then(function () {\n          var scriptNode = document.getElementById(nodeUnderTestId);\n          parent.postMessage({\n            type: 'fontawesome-conflict',\n            technology: 'js',\n            src: scriptNode.src,\n            innerText: scriptNode.innerText,\n            tagName: scriptNode.tagName,\n            md5: md5\n          }, parentOrigin);\n        }).catch(function (e) {\n          var scriptNode = document.getElementById(nodeUnderTestId);\n\n          if (e === 'timeout') {\n            parent.postMessage({\n              type: 'no-conflict',\n              src: scriptNode.src,\n              innerText: scriptNode.innerText,\n              tagName: scriptNode.tagName,\n              md5: md5\n            }, parentOrigin);\n          } else {\n            console.error(e);\n          }\n        });\n      };\n\n      diagScript.innerText = \"(\".concat(diagScriptFun.toString(), \")('\").concat(nodeUnderTestId, \"', '\").concat(md5ForScript, \"', '\").concat(parentOrigin, \"');\");\n\n      diagFrame.onload = function () {\n        diagFrame.contentDocument.head.appendChild(diagScript);\n        diagFrame.contentDocument.head.appendChild(scriptUnderTest);\n      };\n\n      domready(function () {\n        return DOCUMENT.body.appendChild(diagFrame);\n      });\n    };\n\n    for (var scriptIdx = 0; scriptIdx < scripts.length; scriptIdx++) {\n      _loop(scriptIdx);\n    }\n\n    return scriptsByMD5;\n  }\n\n  function setDoneResults(_ref2) {\n    var nodesTested = _ref2.nodesTested,\n        nodesFound = _ref2.nodesFound;\n    WINDOW.FontAwesomeDetection = WINDOW.FontAwesomeDetection || {};\n    WINDOW.FontAwesomeDetection.nodesTested = nodesTested;\n    WINDOW.FontAwesomeDetection.nodesFound = nodesFound;\n    WINDOW.FontAwesomeDetection.detectionDone = true;\n  }\n\n  function conflictDetection() {\n    var report$$1 = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : function () {};\n    var nodesTested = {\n      conflict: {},\n      noConflict: {}\n    };\n\n    WINDOW.onmessage = function (e) {\n      if (WINDOW.location.origin === 'file://' || e.origin === WINDOW.location.origin) {\n        if (e && e.data) {\n          if (e.data.type === 'fontawesome-conflict') {\n            nodesTested.conflict[e.data.md5] = e.data;\n          } else if (e.data.type === 'no-conflict') {\n            nodesTested.noConflict[e.data.md5] = e.data;\n          }\n        }\n      }\n    };\n\n    var scriptsToTest = detectSvgConflicts(DOCUMENT.currentScript);\n    var cssToTest = detectWebfontConflicts();\n\n    var nodesFound = _objectSpread({}, scriptsToTest, cssToTest);\n\n    var testCount = Object.keys(scriptsToTest).length + Object.keys(cssToTest).length; // The resultsCollectionMaxWait allows for the time between when the tests running under\n    // child iframes call postMessage with their results, and when the parent window\n    // receives and handles those events with window.onmessage.\n    // Making it configurable allows us to test the scenario where this timeout is exceeded.\n    // Naming it something very different from \"timeout\" is to help avoid the potential ambiguity between\n    // these two timeout-related settings.\n\n    var masterTimeout = WINDOW.FontAwesomeDetection.timeout + WINDOW.FontAwesomeDetection.resultsCollectionMaxWait;\n    console.group('Font Awesome Detector');\n\n    if (testCount === 0) {\n      console.info('%cAll Good!', 'color: green; font-size: large');\n      console.info('We didn\\'t find anything that needs testing for conflicts. Ergo, no conflicts.');\n    } else {\n      console.info(\"Testing \".concat(testCount, \" possible conflicts.\"));\n      console.info(\"We'll wait about \".concat(Math.round(WINDOW.FontAwesomeDetection.timeout / 10) / 100, \" seconds while testing these and\\n\") + \"then up to another \".concat(Math.round(WINDOW.FontAwesomeDetection.resultsCollectionMaxWait / 10) / 100, \" to allow the browser time\\n\") + \"to accumulate the results. But we'll probably be outta here way before then.\\n\\n\");\n      console.info(\"You can adjust those durations by assigning values to these attributes on the <script> element that loads this detection:\");\n      console.info(\"\\t%c\".concat(timeoutAttr, \"%c: milliseconds to wait for each test before deciding whether it's a conflict.\"), 'font-weight: bold;', 'font-size: normal;');\n      console.info(\"\\t%c\".concat(resultsCollectionMaxWaitAttr, \"%c: milliseconds to wait for the browser to accumulate test results before giving up.\"), 'font-weight: bold;', 'font-size: normal;');\n      pollUntil({\n        // Give this overall timer a little extra cushion\n        maxDuration: masterTimeout,\n        showProgress: true,\n        progressIndicator: 'waiting...',\n        fn: function fn() {\n          return Object.keys(nodesTested.conflict).length + Object.keys(nodesTested.noConflict).length >= testCount;\n        }\n      }).then(function () {\n        console.info('DONE!');\n        setDoneResults({\n          nodesTested: nodesTested,\n          nodesFound: nodesFound\n        });\n        report$$1({\n          nodesTested: nodesTested,\n          nodesFound: nodesFound\n        });\n        console.groupEnd();\n      }).catch(function (e) {\n        if (e === 'timeout') {\n          console.info('TIME OUT! We waited until we got tired. Here\\'s what we found:');\n          setDoneResults({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n          report$$1({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n        } else {\n          console.info('Whoops! We hit an error:', e);\n          console.info('Here\\'s what we\\'d found up until that error:');\n          setDoneResults({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n          report$$1({\n            nodesTested: nodesTested,\n            nodesFound: nodesFound\n          });\n        }\n\n        console.groupEnd();\n      });\n    }\n  } // Allow clients to access, and in some cases, override some properties\n\n  var initialConfig = WINDOW.FontAwesomeDetection || {}; // These can be overridden\n\n  var _default = {\n    report: report,\n    timeout: +(DOCUMENT.currentScript.getAttribute(timeoutAttr) || \"2000\"),\n    resultsCollectionMaxWait: +(DOCUMENT.currentScript.getAttribute(resultsCollectionMaxWaitAttr) || \"5000\")\n  };\n\n  var _config = _objectSpread({}, _default, initialConfig, {\n    // These cannot be overridden\n    __pollUntil: pollUntil,\n    md5ForNode: md5ForNode,\n    detectionDone: false,\n    nodesTested: null,\n    nodesFound: null\n  });\n\n  WINDOW.FontAwesomeDetection = _config;\n\n  var PRODUCTION = function () {\n    try {\n      return process.env.NODE_ENV === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  bunker(function () {\n    if (IS_BROWSER && IS_DOM) {\n      conflictDetection(window.FontAwesomeDetection.report);\n    }\n  });\n\n  exports.conflictDetection = conflictDetection;\n\n  Object.defineProperty(exports, '__esModule', { value: true });\n\n})));\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/fontawesome.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  function _typeof(obj) {\n    if (typeof Symbol === \"function\" && typeof Symbol.iterator === \"symbol\") {\n      _typeof = function (obj) {\n        return typeof obj;\n      };\n    } else {\n      _typeof = function (obj) {\n        return obj && typeof Symbol === \"function\" && obj.constructor === Symbol && obj !== Symbol.prototype ? \"symbol\" : typeof obj;\n      };\n    }\n\n    return _typeof(obj);\n  }\n\n  function _classCallCheck(instance, Constructor) {\n    if (!(instance instanceof Constructor)) {\n      throw new TypeError(\"Cannot call a class as a function\");\n    }\n  }\n\n  function _defineProperties(target, props) {\n    for (var i = 0; i < props.length; i++) {\n      var descriptor = props[i];\n      descriptor.enumerable = descriptor.enumerable || false;\n      descriptor.configurable = true;\n      if (\"value\" in descriptor) descriptor.writable = true;\n      Object.defineProperty(target, descriptor.key, descriptor);\n    }\n  }\n\n  function _createClass(Constructor, protoProps, staticProps) {\n    if (protoProps) _defineProperties(Constructor.prototype, protoProps);\n    if (staticProps) _defineProperties(Constructor, staticProps);\n    return Constructor;\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  function _slicedToArray(arr, i) {\n    return _arrayWithHoles(arr) || _iterableToArrayLimit(arr, i) || _nonIterableRest();\n  }\n\n  function _toConsumableArray(arr) {\n    return _arrayWithoutHoles(arr) || _iterableToArray(arr) || _nonIterableSpread();\n  }\n\n  function _arrayWithoutHoles(arr) {\n    if (Array.isArray(arr)) {\n      for (var i = 0, arr2 = new Array(arr.length); i < arr.length; i++) arr2[i] = arr[i];\n\n      return arr2;\n    }\n  }\n\n  function _arrayWithHoles(arr) {\n    if (Array.isArray(arr)) return arr;\n  }\n\n  function _iterableToArray(iter) {\n    if (Symbol.iterator in Object(iter) || Object.prototype.toString.call(iter) === \"[object Arguments]\") return Array.from(iter);\n  }\n\n  function _iterableToArrayLimit(arr, i) {\n    var _arr = [];\n    var _n = true;\n    var _d = false;\n    var _e = undefined;\n\n    try {\n      for (var _i = arr[Symbol.iterator](), _s; !(_n = (_s = _i.next()).done); _n = true) {\n        _arr.push(_s.value);\n\n        if (i && _arr.length === i) break;\n      }\n    } catch (err) {\n      _d = true;\n      _e = err;\n    } finally {\n      try {\n        if (!_n && _i[\"return\"] != null) _i[\"return\"]();\n      } finally {\n        if (_d) throw _e;\n      }\n    }\n\n    return _arr;\n  }\n\n  function _nonIterableSpread() {\n    throw new TypeError(\"Invalid attempt to spread non-iterable instance\");\n  }\n\n  function _nonIterableRest() {\n    throw new TypeError(\"Invalid attempt to destructure non-iterable instance\");\n  }\n\n  var noop = function noop() {};\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n  var _MUTATION_OBSERVER = null;\n  var _PERFORMANCE = {\n    mark: noop,\n    measure: noop\n  };\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n    if (typeof MutationObserver !== 'undefined') _MUTATION_OBSERVER = MutationObserver;\n    if (typeof performance !== 'undefined') _PERFORMANCE = performance;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var MUTATION_OBSERVER = _MUTATION_OBSERVER;\n  var PERFORMANCE = _PERFORMANCE;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var UNITS_IN_GRID = 16;\n  var DEFAULT_FAMILY_PREFIX = 'fa';\n  var DEFAULT_REPLACEMENT_CLASS = 'svg-inline--fa';\n  var DATA_FA_I2SVG = 'data-fa-i2svg';\n  var DATA_FA_PSEUDO_ELEMENT = 'data-fa-pseudo-element';\n  var DATA_FA_PSEUDO_ELEMENT_PENDING = 'data-fa-pseudo-element-pending';\n  var DATA_PREFIX = 'data-prefix';\n  var DATA_ICON = 'data-icon';\n  var HTML_CLASS_I2SVG_BASE_CLASS = 'fontawesome-i2svg';\n  var MUTATION_APPROACH_ASYNC = 'async';\n  var TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS = ['HTML', 'HEAD', 'STYLE', 'SCRIPT'];\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n  var PREFIX_TO_STYLE = {\n    'fas': 'solid',\n    'far': 'regular',\n    'fal': 'light',\n    'fad': 'duotone',\n    'fab': 'brands',\n    'fa': 'solid'\n  };\n  var STYLE_TO_PREFIX = {\n    'solid': 'fas',\n    'regular': 'far',\n    'light': 'fal',\n    'duotone': 'fad',\n    'brands': 'fab'\n  };\n  var LAYERS_TEXT_CLASSNAME = 'fa-layers-text';\n  var FONT_FAMILY_PATTERN = /Font Awesome 5 (Solid|Regular|Light|Duotone|Brands|Free|Pro)/;\n  var FONT_WEIGHT_TO_PREFIX = {\n    '900': 'fas',\n    '400': 'far',\n    'normal': 'far',\n    '300': 'fal'\n  };\n  var oneToTen = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10];\n  var oneToTwenty = oneToTen.concat([11, 12, 13, 14, 15, 16, 17, 18, 19, 20]);\n  var ATTRIBUTES_WATCHED_FOR_MUTATION = ['class', 'data-prefix', 'data-icon', 'data-fa-transform', 'data-fa-mask'];\n  var DUOTONE_CLASSES = {\n    GROUP: 'group',\n    SWAP_OPACITY: 'swap-opacity',\n    PRIMARY: 'primary',\n    SECONDARY: 'secondary'\n  };\n  var RESERVED_CLASSES = ['xs', 'sm', 'lg', 'fw', 'ul', 'li', 'border', 'pull-left', 'pull-right', 'spin', 'pulse', 'rotate-90', 'rotate-180', 'rotate-270', 'flip-horizontal', 'flip-vertical', 'flip-both', 'stack', 'stack-1x', 'stack-2x', 'inverse', 'layers', 'layers-text', 'layers-counter', DUOTONE_CLASSES.GROUP, DUOTONE_CLASSES.SWAP_OPACITY, DUOTONE_CLASSES.PRIMARY, DUOTONE_CLASSES.SECONDARY].concat(oneToTen.map(function (n) {\n    return \"\".concat(n, \"x\");\n  })).concat(oneToTwenty.map(function (n) {\n    return \"w-\".concat(n);\n  }));\n\n  var initial = WINDOW.FontAwesomeConfig || {};\n\n  function getAttrConfig(attr) {\n    var element = DOCUMENT.querySelector('script[' + attr + ']');\n\n    if (element) {\n      return element.getAttribute(attr);\n    }\n  }\n\n  function coerce(val) {\n    // Getting an empty string will occur if the attribute is set on the HTML tag but without a value\n    // We'll assume that this is an indication that it should be toggled to true\n    // For example <script data-search-pseudo-elements src=\"...\"></script>\n    if (val === '') return true;\n    if (val === 'false') return false;\n    if (val === 'true') return true;\n    return val;\n  }\n\n  if (DOCUMENT && typeof DOCUMENT.querySelector === 'function') {\n    var attrs = [['data-family-prefix', 'familyPrefix'], ['data-replacement-class', 'replacementClass'], ['data-auto-replace-svg', 'autoReplaceSvg'], ['data-auto-add-css', 'autoAddCss'], ['data-auto-a11y', 'autoA11y'], ['data-search-pseudo-elements', 'searchPseudoElements'], ['data-observe-mutations', 'observeMutations'], ['data-mutate-approach', 'mutateApproach'], ['data-keep-original-source', 'keepOriginalSource'], ['data-measure-performance', 'measurePerformance'], ['data-show-missing-icons', 'showMissingIcons']];\n    attrs.forEach(function (_ref) {\n      var _ref2 = _slicedToArray(_ref, 2),\n          attr = _ref2[0],\n          key = _ref2[1];\n\n      var val = coerce(getAttrConfig(attr));\n\n      if (val !== undefined && val !== null) {\n        initial[key] = val;\n      }\n    });\n  }\n\n  var _default = {\n    familyPrefix: DEFAULT_FAMILY_PREFIX,\n    replacementClass: DEFAULT_REPLACEMENT_CLASS,\n    autoReplaceSvg: true,\n    autoAddCss: true,\n    autoA11y: true,\n    searchPseudoElements: false,\n    observeMutations: true,\n    mutateApproach: 'async',\n    keepOriginalSource: true,\n    measurePerformance: false,\n    showMissingIcons: true\n  };\n\n  var _config = _objectSpread({}, _default, initial);\n\n  if (!_config.autoReplaceSvg) _config.observeMutations = false;\n\n  var config = _objectSpread({}, _config);\n\n  WINDOW.FontAwesomeConfig = config;\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  var functions = [];\n\n  var listener = function listener() {\n    DOCUMENT.removeEventListener('DOMContentLoaded', listener);\n    loaded = 1;\n    functions.map(function (fn) {\n      return fn();\n    });\n  };\n\n  var loaded = false;\n\n  if (IS_DOM) {\n    loaded = (DOCUMENT.documentElement.doScroll ? /^loaded|^c/ : /^loaded|^i|^c/).test(DOCUMENT.readyState);\n    if (!loaded) DOCUMENT.addEventListener('DOMContentLoaded', listener);\n  }\n\n  function domready (fn) {\n    if (!IS_DOM) return;\n    loaded ? setTimeout(fn, 0) : functions.push(fn);\n  }\n\n  var PENDING = 'pending';\n  var SETTLED = 'settled';\n  var FULFILLED = 'fulfilled';\n  var REJECTED = 'rejected';\n\n  var NOOP = function NOOP() {};\n\n  var isNode = typeof global !== 'undefined' && typeof global.process !== 'undefined' && typeof global.process.emit === 'function';\n  var asyncSetTimer = typeof setImmediate === 'undefined' ? setTimeout : setImmediate;\n  var asyncQueue = [];\n  var asyncTimer;\n\n  function asyncFlush() {\n    // run promise callbacks\n    for (var i = 0; i < asyncQueue.length; i++) {\n      asyncQueue[i][0](asyncQueue[i][1]);\n    } // reset async asyncQueue\n\n\n    asyncQueue = [];\n    asyncTimer = false;\n  }\n\n  function asyncCall(callback, arg) {\n    asyncQueue.push([callback, arg]);\n\n    if (!asyncTimer) {\n      asyncTimer = true;\n      asyncSetTimer(asyncFlush, 0);\n    }\n  }\n\n  function invokeResolver(resolver, promise) {\n    function resolvePromise(value) {\n      resolve(promise, value);\n    }\n\n    function rejectPromise(reason) {\n      reject(promise, reason);\n    }\n\n    try {\n      resolver(resolvePromise, rejectPromise);\n    } catch (e) {\n      rejectPromise(e);\n    }\n  }\n\n  function invokeCallback(subscriber) {\n    var owner = subscriber.owner;\n    var settled = owner._state;\n    var value = owner._data;\n    var callback = subscriber[settled];\n    var promise = subscriber.then;\n\n    if (typeof callback === 'function') {\n      settled = FULFILLED;\n\n      try {\n        value = callback(value);\n      } catch (e) {\n        reject(promise, e);\n      }\n    }\n\n    if (!handleThenable(promise, value)) {\n      if (settled === FULFILLED) {\n        resolve(promise, value);\n      }\n\n      if (settled === REJECTED) {\n        reject(promise, value);\n      }\n    }\n  }\n\n  function handleThenable(promise, value) {\n    var resolved;\n\n    try {\n      if (promise === value) {\n        throw new TypeError('A promises callback cannot return that same promise.');\n      }\n\n      if (value && (typeof value === 'function' || _typeof(value) === 'object')) {\n        // then should be retrieved only once\n        var then = value.then;\n\n        if (typeof then === 'function') {\n          then.call(value, function (val) {\n            if (!resolved) {\n              resolved = true;\n\n              if (value === val) {\n                fulfill(promise, val);\n              } else {\n                resolve(promise, val);\n              }\n            }\n          }, function (reason) {\n            if (!resolved) {\n              resolved = true;\n              reject(promise, reason);\n            }\n          });\n          return true;\n        }\n      }\n    } catch (e) {\n      if (!resolved) {\n        reject(promise, e);\n      }\n\n      return true;\n    }\n\n    return false;\n  }\n\n  function resolve(promise, value) {\n    if (promise === value || !handleThenable(promise, value)) {\n      fulfill(promise, value);\n    }\n  }\n\n  function fulfill(promise, value) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = value;\n      asyncCall(publishFulfillment, promise);\n    }\n  }\n\n  function reject(promise, reason) {\n    if (promise._state === PENDING) {\n      promise._state = SETTLED;\n      promise._data = reason;\n      asyncCall(publishRejection, promise);\n    }\n  }\n\n  function publish(promise) {\n    promise._then = promise._then.forEach(invokeCallback);\n  }\n\n  function publishFulfillment(promise) {\n    promise._state = FULFILLED;\n    publish(promise);\n  }\n\n  function publishRejection(promise) {\n    promise._state = REJECTED;\n    publish(promise);\n\n    if (!promise._handled && isNode) {\n      global.process.emit('unhandledRejection', promise._data, promise);\n    }\n  }\n\n  function notifyRejectionHandled(promise) {\n    global.process.emit('rejectionHandled', promise);\n  }\n  /**\n   * @class\n   */\n\n\n  function P(resolver) {\n    if (typeof resolver !== 'function') {\n      throw new TypeError('Promise resolver ' + resolver + ' is not a function');\n    }\n\n    if (this instanceof P === false) {\n      throw new TypeError('Failed to construct \\'Promise\\': Please use the \\'new\\' operator, this object constructor cannot be called as a function.');\n    }\n\n    this._then = [];\n    invokeResolver(resolver, this);\n  }\n\n  P.prototype = {\n    constructor: P,\n    _state: PENDING,\n    _then: null,\n    _data: undefined,\n    _handled: false,\n    then: function then(onFulfillment, onRejection) {\n      var subscriber = {\n        owner: this,\n        then: new this.constructor(NOOP),\n        fulfilled: onFulfillment,\n        rejected: onRejection\n      };\n\n      if ((onRejection || onFulfillment) && !this._handled) {\n        this._handled = true;\n\n        if (this._state === REJECTED && isNode) {\n          asyncCall(notifyRejectionHandled, this);\n        }\n      }\n\n      if (this._state === FULFILLED || this._state === REJECTED) {\n        // already resolved, call callback async\n        asyncCall(invokeCallback, subscriber);\n      } else {\n        // subscribe\n        this._then.push(subscriber);\n      }\n\n      return subscriber.then;\n    },\n    catch: function _catch(onRejection) {\n      return this.then(null, onRejection);\n    }\n  };\n\n  P.all = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.all().');\n    }\n\n    return new P(function (resolve, reject) {\n      var results = [];\n      var remaining = 0;\n\n      function resolver(index) {\n        remaining++;\n        return function (value) {\n          results[index] = value;\n\n          if (! --remaining) {\n            resolve(results);\n          }\n        };\n      }\n\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolver(i), reject);\n        } else {\n          results[i] = promise;\n        }\n      }\n\n      if (!remaining) {\n        resolve(results);\n      }\n    });\n  };\n\n  P.race = function (promises) {\n    if (!Array.isArray(promises)) {\n      throw new TypeError('You must pass an array to Promise.race().');\n    }\n\n    return new P(function (resolve, reject) {\n      for (var i = 0, promise; i < promises.length; i++) {\n        promise = promises[i];\n\n        if (promise && typeof promise.then === 'function') {\n          promise.then(resolve, reject);\n        } else {\n          resolve(promise);\n        }\n      }\n    });\n  };\n\n  P.resolve = function (value) {\n    if (value && _typeof(value) === 'object' && value.constructor === P) {\n      return value;\n    }\n\n    return new P(function (resolve) {\n      resolve(value);\n    });\n  };\n\n  P.reject = function (reason) {\n    return new P(function (resolve, reject) {\n      reject(reason);\n    });\n  };\n\n  var picked = typeof Promise === 'function' ? Promise : P;\n\n  var d = UNITS_IN_GRID;\n  var meaninglessTransform = {\n    size: 16,\n    x: 0,\n    y: 0,\n    rotate: 0,\n    flipX: false,\n    flipY: false\n  };\n\n  function isReserved(name) {\n    return ~RESERVED_CLASSES.indexOf(name);\n  }\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n  function insertCss(css) {\n    if (!css || !IS_DOM) {\n      return;\n    }\n\n    var style = DOCUMENT.createElement('style');\n    style.setAttribute('type', 'text/css');\n    style.innerHTML = css;\n    var headChildren = DOCUMENT.head.childNodes;\n    var beforeChild = null;\n\n    for (var i = headChildren.length - 1; i > -1; i--) {\n      var child = headChildren[i];\n      var tagName = (child.tagName || '').toUpperCase();\n\n      if (['STYLE', 'LINK'].indexOf(tagName) > -1) {\n        beforeChild = child;\n      }\n    }\n\n    DOCUMENT.head.insertBefore(style, beforeChild);\n    return css;\n  }\n  var idPool = '0123456789abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ';\n  function nextUniqueId() {\n    var size = 12;\n    var id = '';\n\n    while (size-- > 0) {\n      id += idPool[Math.random() * 62 | 0];\n    }\n\n    return id;\n  }\n  function toArray(obj) {\n    var array = [];\n\n    for (var i = (obj || []).length >>> 0; i--;) {\n      array[i] = obj[i];\n    }\n\n    return array;\n  }\n  function classArray(node) {\n    if (node.classList) {\n      return toArray(node.classList);\n    } else {\n      return (node.getAttribute('class') || '').split(' ').filter(function (i) {\n        return i;\n      });\n    }\n  }\n  function getIconName(familyPrefix, cls) {\n    var parts = cls.split('-');\n    var prefix = parts[0];\n    var iconName = parts.slice(1).join('-');\n\n    if (prefix === familyPrefix && iconName !== '' && !isReserved(iconName)) {\n      return iconName;\n    } else {\n      return null;\n    }\n  }\n  function htmlEscape(str) {\n    return \"\".concat(str).replace(/&/g, '&amp;').replace(/\"/g, '&quot;').replace(/'/g, '&#39;').replace(/</g, '&lt;').replace(/>/g, '&gt;');\n  }\n  function joinAttributes(attributes) {\n    return Object.keys(attributes || {}).reduce(function (acc, attributeName) {\n      return acc + \"\".concat(attributeName, \"=\\\"\").concat(htmlEscape(attributes[attributeName]), \"\\\" \");\n    }, '').trim();\n  }\n  function joinStyles(styles) {\n    return Object.keys(styles || {}).reduce(function (acc, styleName) {\n      return acc + \"\".concat(styleName, \": \").concat(styles[styleName], \";\");\n    }, '');\n  }\n  function transformIsMeaningful(transform) {\n    return transform.size !== meaninglessTransform.size || transform.x !== meaninglessTransform.x || transform.y !== meaninglessTransform.y || transform.rotate !== meaninglessTransform.rotate || transform.flipX || transform.flipY;\n  }\n  function transformForSvg(_ref) {\n    var transform = _ref.transform,\n        containerWidth = _ref.containerWidth,\n        iconWidth = _ref.iconWidth;\n    var outer = {\n      transform: \"translate(\".concat(containerWidth / 2, \" 256)\")\n    };\n    var innerTranslate = \"translate(\".concat(transform.x * 32, \", \").concat(transform.y * 32, \") \");\n    var innerScale = \"scale(\".concat(transform.size / 16 * (transform.flipX ? -1 : 1), \", \").concat(transform.size / 16 * (transform.flipY ? -1 : 1), \") \");\n    var innerRotate = \"rotate(\".concat(transform.rotate, \" 0 0)\");\n    var inner = {\n      transform: \"\".concat(innerTranslate, \" \").concat(innerScale, \" \").concat(innerRotate)\n    };\n    var path = {\n      transform: \"translate(\".concat(iconWidth / 2 * -1, \" -256)\")\n    };\n    return {\n      outer: outer,\n      inner: inner,\n      path: path\n    };\n  }\n  function transformForCss(_ref2) {\n    var transform = _ref2.transform,\n        _ref2$width = _ref2.width,\n        width = _ref2$width === void 0 ? UNITS_IN_GRID : _ref2$width,\n        _ref2$height = _ref2.height,\n        height = _ref2$height === void 0 ? UNITS_IN_GRID : _ref2$height,\n        _ref2$startCentered = _ref2.startCentered,\n        startCentered = _ref2$startCentered === void 0 ? false : _ref2$startCentered;\n    var val = '';\n\n    if (startCentered && IS_IE) {\n      val += \"translate(\".concat(transform.x / d - width / 2, \"em, \").concat(transform.y / d - height / 2, \"em) \");\n    } else if (startCentered) {\n      val += \"translate(calc(-50% + \".concat(transform.x / d, \"em), calc(-50% + \").concat(transform.y / d, \"em)) \");\n    } else {\n      val += \"translate(\".concat(transform.x / d, \"em, \").concat(transform.y / d, \"em) \");\n    }\n\n    val += \"scale(\".concat(transform.size / d * (transform.flipX ? -1 : 1), \", \").concat(transform.size / d * (transform.flipY ? -1 : 1), \") \");\n    val += \"rotate(\".concat(transform.rotate, \"deg) \");\n    return val;\n  }\n\n  var ALL_SPACE = {\n    x: 0,\n    y: 0,\n    width: '100%',\n    height: '100%'\n  };\n\n  function fillBlack(abstract) {\n    var force = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : true;\n\n    if (abstract.attributes && (abstract.attributes.fill || force)) {\n      abstract.attributes.fill = 'black';\n    }\n\n    return abstract;\n  }\n\n  function deGroup(abstract) {\n    if (abstract.tag === 'g') {\n      return abstract.children;\n    } else {\n      return [abstract];\n    }\n  }\n\n  function makeIconMasking (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        mask = _ref.mask,\n        transform = _ref.transform;\n    var mainWidth = main.width,\n        mainPath = main.icon;\n    var maskWidth = mask.width,\n        maskPath = mask.icon;\n    var trans = transformForSvg({\n      transform: transform,\n      containerWidth: maskWidth,\n      iconWidth: mainWidth\n    });\n    var maskRect = {\n      tag: 'rect',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        fill: 'white'\n      })\n    };\n    var maskInnerGroupChildrenMixin = mainPath.children ? {\n      children: mainPath.children.map(fillBlack)\n    } : {};\n    var maskInnerGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.inner),\n      children: [fillBlack(_objectSpread({\n        tag: mainPath.tag,\n        attributes: _objectSpread({}, mainPath.attributes, trans.path)\n      }, maskInnerGroupChildrenMixin))]\n    };\n    var maskOuterGroup = {\n      tag: 'g',\n      attributes: _objectSpread({}, trans.outer),\n      children: [maskInnerGroup]\n    };\n    var maskId = \"mask-\".concat(nextUniqueId());\n    var clipId = \"clip-\".concat(nextUniqueId());\n    var maskTag = {\n      tag: 'mask',\n      attributes: _objectSpread({}, ALL_SPACE, {\n        id: maskId,\n        maskUnits: 'userSpaceOnUse',\n        maskContentUnits: 'userSpaceOnUse'\n      }),\n      children: [maskRect, maskOuterGroup]\n    };\n    var defs = {\n      tag: 'defs',\n      children: [{\n        tag: 'clipPath',\n        attributes: {\n          id: clipId\n        },\n        children: deGroup(maskPath)\n      }, maskTag]\n    };\n    children.push(defs, {\n      tag: 'rect',\n      attributes: _objectSpread({\n        fill: 'currentColor',\n        'clip-path': \"url(#\".concat(clipId, \")\"),\n        mask: \"url(#\".concat(maskId, \")\")\n      }, ALL_SPACE)\n    });\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function makeIconStandard (_ref) {\n    var children = _ref.children,\n        attributes = _ref.attributes,\n        main = _ref.main,\n        transform = _ref.transform,\n        styles = _ref.styles;\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    if (transformIsMeaningful(transform)) {\n      var trans = transformForSvg({\n        transform: transform,\n        containerWidth: main.width,\n        iconWidth: main.width\n      });\n      children.push({\n        tag: 'g',\n        attributes: _objectSpread({}, trans.outer),\n        children: [{\n          tag: 'g',\n          attributes: _objectSpread({}, trans.inner),\n          children: [{\n            tag: main.icon.tag,\n            children: main.icon.children,\n            attributes: _objectSpread({}, main.icon.attributes, trans.path)\n          }]\n        }]\n      });\n    } else {\n      children.push(main.icon);\n    }\n\n    return {\n      children: children,\n      attributes: attributes\n    };\n  }\n\n  function asIcon (_ref) {\n    var children = _ref.children,\n        main = _ref.main,\n        mask = _ref.mask,\n        attributes = _ref.attributes,\n        styles = _ref.styles,\n        transform = _ref.transform;\n\n    if (transformIsMeaningful(transform) && main.found && !mask.found) {\n      var width = main.width,\n          height = main.height;\n      var offset = {\n        x: width / height / 2,\n        y: 0.5\n      };\n      attributes['style'] = joinStyles(_objectSpread({}, styles, {\n        'transform-origin': \"\".concat(offset.x + transform.x / 16, \"em \").concat(offset.y + transform.y / 16, \"em\")\n      }));\n    }\n\n    return [{\n      tag: 'svg',\n      attributes: attributes,\n      children: children\n    }];\n  }\n\n  function asSymbol (_ref) {\n    var prefix = _ref.prefix,\n        iconName = _ref.iconName,\n        children = _ref.children,\n        attributes = _ref.attributes,\n        symbol = _ref.symbol;\n    var id = symbol === true ? \"\".concat(prefix, \"-\").concat(config.familyPrefix, \"-\").concat(iconName) : symbol;\n    return [{\n      tag: 'svg',\n      attributes: {\n        style: 'display: none;'\n      },\n      children: [{\n        tag: 'symbol',\n        attributes: _objectSpread({}, attributes, {\n          id: id\n        }),\n        children: children\n      }]\n    }];\n  }\n\n  function makeInlineSvgAbstract(params) {\n    var _params$icons = params.icons,\n        main = _params$icons.main,\n        mask = _params$icons.mask,\n        prefix = params.prefix,\n        iconName = params.iconName,\n        transform = params.transform,\n        symbol = params.symbol,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable = params.watchable,\n        watchable = _params$watchable === void 0 ? false : _params$watchable;\n\n    var _ref = mask.found ? mask : main,\n        width = _ref.width,\n        height = _ref.height;\n\n    var widthClass = \"fa-w-\".concat(Math.ceil(width / height * 16));\n    var attrClass = [config.replacementClass, iconName ? \"\".concat(config.familyPrefix, \"-\").concat(iconName) : '', widthClass].filter(function (c) {\n      return extra.classes.indexOf(c) === -1;\n    }).concat(extra.classes).join(' ');\n    var content = {\n      children: [],\n      attributes: _objectSpread({}, extra.attributes, {\n        'data-prefix': prefix,\n        'data-icon': iconName,\n        'class': attrClass,\n        'role': extra.attributes.role || 'img',\n        'xmlns': 'http://www.w3.org/2000/svg',\n        'viewBox': \"0 0 \".concat(width, \" \").concat(height)\n      })\n    };\n\n    if (watchable) {\n      content.attributes[DATA_FA_I2SVG] = '';\n    }\n\n    if (title) content.children.push({\n      tag: 'title',\n      attributes: {\n        id: content.attributes['aria-labelledby'] || \"title-\".concat(nextUniqueId())\n      },\n      children: [title]\n    });\n\n    var args = _objectSpread({}, content, {\n      prefix: prefix,\n      iconName: iconName,\n      main: main,\n      mask: mask,\n      transform: transform,\n      symbol: symbol,\n      styles: extra.styles\n    });\n\n    var _ref2 = mask.found && main.found ? makeIconMasking(args) : makeIconStandard(args),\n        children = _ref2.children,\n        attributes = _ref2.attributes;\n\n    args.children = children;\n    args.attributes = attributes;\n\n    if (symbol) {\n      return asSymbol(args);\n    } else {\n      return asIcon(args);\n    }\n  }\n  function makeLayersTextAbstract(params) {\n    var content = params.content,\n        width = params.width,\n        height = params.height,\n        transform = params.transform,\n        title = params.title,\n        extra = params.extra,\n        _params$watchable2 = params.watchable,\n        watchable = _params$watchable2 === void 0 ? false : _params$watchable2;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    if (watchable) {\n      attributes[DATA_FA_I2SVG] = '';\n    }\n\n    var styles = _objectSpread({}, extra.styles);\n\n    if (transformIsMeaningful(transform)) {\n      styles['transform'] = transformForCss({\n        transform: transform,\n        startCentered: true,\n        width: width,\n        height: height\n      });\n      styles['-webkit-transform'] = styles['transform'];\n    }\n\n    var styleString = joinStyles(styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n  function makeLayersCounterAbstract(params) {\n    var content = params.content,\n        title = params.title,\n        extra = params.extra;\n\n    var attributes = _objectSpread({}, extra.attributes, title ? {\n      'title': title\n    } : {}, {\n      'class': extra.classes.join(' ')\n    });\n\n    var styleString = joinStyles(extra.styles);\n\n    if (styleString.length > 0) {\n      attributes['style'] = styleString;\n    }\n\n    var val = [];\n    val.push({\n      tag: 'span',\n      attributes: attributes,\n      children: [content]\n    });\n\n    if (title) {\n      val.push({\n        tag: 'span',\n        attributes: {\n          class: 'sr-only'\n        },\n        children: [title]\n      });\n    }\n\n    return val;\n  }\n\n  var noop$1 = function noop() {};\n\n  var p = config.measurePerformance && PERFORMANCE && PERFORMANCE.mark && PERFORMANCE.measure ? PERFORMANCE : {\n    mark: noop$1,\n    measure: noop$1\n  };\n  var preamble = \"FA \\\"5.10.2\\\"\";\n\n  var begin = function begin(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" begins\"));\n    return function () {\n      return end(name);\n    };\n  };\n\n  var end = function end(name) {\n    p.mark(\"\".concat(preamble, \" \").concat(name, \" ends\"));\n    p.measure(\"\".concat(preamble, \" \").concat(name), \"\".concat(preamble, \" \").concat(name, \" begins\"), \"\".concat(preamble, \" \").concat(name, \" ends\"));\n  };\n\n  var perf = {\n    begin: begin,\n    end: end\n  };\n\n  /**\n   * Internal helper to bind a function known to have 4 arguments\n   * to a given context.\n   */\n\n  var bindInternal4 = function bindInternal4(func, thisContext) {\n    return function (a, b, c, d) {\n      return func.call(thisContext, a, b, c, d);\n    };\n  };\n\n  /**\n   * # Reduce\n   *\n   * A fast object `.reduce()` implementation.\n   *\n   * @param  {Object}   subject      The object to reduce over.\n   * @param  {Function} fn           The reducer function.\n   * @param  {mixed}    initialValue The initial value for the reducer, defaults to subject[0].\n   * @param  {Object}   thisContext  The context for the reducer.\n   * @return {mixed}                 The final result.\n   */\n\n\n  var reduce = function fastReduceObject(subject, fn, initialValue, thisContext) {\n    var keys = Object.keys(subject),\n        length = keys.length,\n        iterator = thisContext !== undefined ? bindInternal4(fn, thisContext) : fn,\n        i,\n        key,\n        result;\n\n    if (initialValue === undefined) {\n      i = 1;\n      result = subject[keys[0]];\n    } else {\n      i = 0;\n      result = initialValue;\n    }\n\n    for (; i < length; i++) {\n      key = keys[i];\n      result = iterator(result, subject[key], key, subject);\n    }\n\n    return result;\n  };\n\n  function toHex(unicode) {\n    var result = '';\n\n    for (var i = 0; i < unicode.length; i++) {\n      var hex = unicode.charCodeAt(i).toString(16);\n      result += ('000' + hex).slice(-4);\n    }\n\n    return result;\n  }\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var styles = namespace.styles,\n      shims = namespace.shims;\n  var _byUnicode = {};\n  var _byLigature = {};\n  var _byOldName = {};\n  var build = function build() {\n    var lookup = function lookup(reducer) {\n      return reduce(styles, function (o, style, prefix) {\n        o[prefix] = reduce(style, reducer, {});\n        return o;\n      }, {});\n    };\n\n    _byUnicode = lookup(function (acc, icon, iconName) {\n      if (icon[3]) {\n        acc[icon[3]] = iconName;\n      }\n\n      return acc;\n    });\n    _byLigature = lookup(function (acc, icon, iconName) {\n      var ligatures = icon[2];\n      acc[iconName] = iconName;\n      ligatures.forEach(function (ligature) {\n        acc[ligature] = iconName;\n      });\n      return acc;\n    });\n    var hasRegular = 'far' in styles;\n    _byOldName = reduce(shims, function (acc, shim) {\n      var oldName = shim[0];\n      var prefix = shim[1];\n      var iconName = shim[2];\n\n      if (prefix === 'far' && !hasRegular) {\n        prefix = 'fas';\n      }\n\n      acc[oldName] = {\n        prefix: prefix,\n        iconName: iconName\n      };\n      return acc;\n    }, {});\n  };\n  build();\n  function byUnicode(prefix, unicode) {\n    return (_byUnicode[prefix] || {})[unicode];\n  }\n  function byLigature(prefix, ligature) {\n    return (_byLigature[prefix] || {})[ligature];\n  }\n  function byOldName(name) {\n    return _byOldName[name] || {\n      prefix: null,\n      iconName: null\n    };\n  }\n\n  var styles$1 = namespace.styles;\n  var emptyCanonicalIcon = function emptyCanonicalIcon() {\n    return {\n      prefix: null,\n      iconName: null,\n      rest: []\n    };\n  };\n  function getCanonicalIcon(values) {\n    return values.reduce(function (acc, cls) {\n      var iconName = getIconName(config.familyPrefix, cls);\n\n      if (styles$1[cls]) {\n        acc.prefix = cls;\n      } else if (config.autoFetchSvg && ['fas', 'far', 'fal', 'fad', 'fab', 'fa'].indexOf(cls) > -1) {\n        acc.prefix = cls;\n      } else if (iconName) {\n        var shim = acc.prefix === 'fa' ? byOldName(iconName) : {};\n        acc.iconName = shim.iconName || iconName;\n        acc.prefix = shim.prefix || acc.prefix;\n      } else if (cls !== config.replacementClass && cls.indexOf('fa-w-') !== 0) {\n        acc.rest.push(cls);\n      }\n\n      return acc;\n    }, emptyCanonicalIcon());\n  }\n  function iconFromMapping(mapping, prefix, iconName) {\n    if (mapping && mapping[prefix] && mapping[prefix][iconName]) {\n      return {\n        prefix: prefix,\n        iconName: iconName,\n        icon: mapping[prefix][iconName]\n      };\n    }\n  }\n\n  function toHtml(abstractNodes) {\n    var tag = abstractNodes.tag,\n        _abstractNodes$attrib = abstractNodes.attributes,\n        attributes = _abstractNodes$attrib === void 0 ? {} : _abstractNodes$attrib,\n        _abstractNodes$childr = abstractNodes.children,\n        children = _abstractNodes$childr === void 0 ? [] : _abstractNodes$childr;\n\n    if (typeof abstractNodes === 'string') {\n      return htmlEscape(abstractNodes);\n    } else {\n      return \"<\".concat(tag, \" \").concat(joinAttributes(attributes), \">\").concat(children.map(toHtml).join(''), \"</\").concat(tag, \">\");\n    }\n  }\n\n  var noop$2 = function noop() {};\n\n  function isWatched(node) {\n    var i2svg = node.getAttribute ? node.getAttribute(DATA_FA_I2SVG) : null;\n    return typeof i2svg === 'string';\n  }\n\n  function getMutator() {\n    if (config.autoReplaceSvg === true) {\n      return mutators.replace;\n    }\n\n    var mutator = mutators[config.autoReplaceSvg];\n    return mutator || mutators.replace;\n  }\n\n  var mutators = {\n    replace: function replace(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1];\n      var newOuterHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n\n      if (node.parentNode && node.outerHTML) {\n        node.outerHTML = newOuterHTML + (config.keepOriginalSource && node.tagName.toLowerCase() !== 'svg' ? \"<!-- \".concat(node.outerHTML, \" -->\") : '');\n      } else if (node.parentNode) {\n        var newNode = document.createElement('span');\n        node.parentNode.replaceChild(newNode, node);\n        newNode.outerHTML = newOuterHTML;\n      }\n    },\n    nest: function nest(mutation) {\n      var node = mutation[0];\n      var abstract = mutation[1]; // If we already have a replaced node we do not want to continue nesting within it.\n      // Short-circuit to the standard replacement\n\n      if (~classArray(node).indexOf(config.replacementClass)) {\n        return mutators.replace(mutation);\n      }\n\n      var forSvg = new RegExp(\"\".concat(config.familyPrefix, \"-.*\"));\n      delete abstract[0].attributes.style;\n      var splitClasses = abstract[0].attributes.class.split(' ').reduce(function (acc, cls) {\n        if (cls === config.replacementClass || cls.match(forSvg)) {\n          acc.toSvg.push(cls);\n        } else {\n          acc.toNode.push(cls);\n        }\n\n        return acc;\n      }, {\n        toNode: [],\n        toSvg: []\n      });\n      abstract[0].attributes.class = splitClasses.toSvg.join(' ');\n      var newInnerHTML = abstract.map(function (a) {\n        return toHtml(a);\n      }).join('\\n');\n      node.setAttribute('class', splitClasses.toNode.join(' '));\n      node.setAttribute(DATA_FA_I2SVG, '');\n      node.innerHTML = newInnerHTML;\n    }\n  };\n\n  function performOperationSync(op) {\n    op();\n  }\n\n  function perform(mutations, callback) {\n    var callbackFunction = typeof callback === 'function' ? callback : noop$2;\n\n    if (mutations.length === 0) {\n      callbackFunction();\n    } else {\n      var frame = performOperationSync;\n\n      if (config.mutateApproach === MUTATION_APPROACH_ASYNC) {\n        frame = WINDOW.requestAnimationFrame || performOperationSync;\n      }\n\n      frame(function () {\n        var mutator = getMutator();\n        var mark = perf.begin('mutate');\n        mutations.map(mutator);\n        mark();\n        callbackFunction();\n      });\n    }\n  }\n  var disabled = false;\n  function disableObservation() {\n    disabled = true;\n  }\n  function enableObservation() {\n    disabled = false;\n  }\n  var mo = null;\n  function observe(options) {\n    if (!MUTATION_OBSERVER) {\n      return;\n    }\n\n    if (!config.observeMutations) {\n      return;\n    }\n\n    var treeCallback = options.treeCallback,\n        nodeCallback = options.nodeCallback,\n        pseudoElementsCallback = options.pseudoElementsCallback,\n        _options$observeMutat = options.observeMutationsRoot,\n        observeMutationsRoot = _options$observeMutat === void 0 ? DOCUMENT : _options$observeMutat;\n    mo = new MUTATION_OBSERVER(function (objects) {\n      if (disabled) return;\n      toArray(objects).forEach(function (mutationRecord) {\n        if (mutationRecord.type === 'childList' && mutationRecord.addedNodes.length > 0 && !isWatched(mutationRecord.addedNodes[0])) {\n          if (config.searchPseudoElements) {\n            pseudoElementsCallback(mutationRecord.target);\n          }\n\n          treeCallback(mutationRecord.target);\n        }\n\n        if (mutationRecord.type === 'attributes' && mutationRecord.target.parentNode && config.searchPseudoElements) {\n          pseudoElementsCallback(mutationRecord.target.parentNode);\n        }\n\n        if (mutationRecord.type === 'attributes' && isWatched(mutationRecord.target) && ~ATTRIBUTES_WATCHED_FOR_MUTATION.indexOf(mutationRecord.attributeName)) {\n          if (mutationRecord.attributeName === 'class') {\n            var _getCanonicalIcon = getCanonicalIcon(classArray(mutationRecord.target)),\n                prefix = _getCanonicalIcon.prefix,\n                iconName = _getCanonicalIcon.iconName;\n\n            if (prefix) mutationRecord.target.setAttribute('data-prefix', prefix);\n            if (iconName) mutationRecord.target.setAttribute('data-icon', iconName);\n          } else {\n            nodeCallback(mutationRecord.target);\n          }\n        }\n      });\n    });\n    if (!IS_DOM) return;\n    mo.observe(observeMutationsRoot, {\n      childList: true,\n      attributes: true,\n      characterData: true,\n      subtree: true\n    });\n  }\n  function disconnect() {\n    if (!mo) return;\n    mo.disconnect();\n  }\n\n  function styleParser (node) {\n    var style = node.getAttribute('style');\n    var val = [];\n\n    if (style) {\n      val = style.split(';').reduce(function (acc, style) {\n        var styles = style.split(':');\n        var prop = styles[0];\n        var value = styles.slice(1);\n\n        if (prop && value.length > 0) {\n          acc[prop] = value.join(':').trim();\n        }\n\n        return acc;\n      }, {});\n    }\n\n    return val;\n  }\n\n  function classParser (node) {\n    var existingPrefix = node.getAttribute('data-prefix');\n    var existingIconName = node.getAttribute('data-icon');\n    var innerText = node.innerText !== undefined ? node.innerText.trim() : '';\n    var val = getCanonicalIcon(classArray(node));\n\n    if (existingPrefix && existingIconName) {\n      val.prefix = existingPrefix;\n      val.iconName = existingIconName;\n    }\n\n    if (val.prefix && innerText.length > 1) {\n      val.iconName = byLigature(val.prefix, node.innerText);\n    } else if (val.prefix && innerText.length === 1) {\n      val.iconName = byUnicode(val.prefix, toHex(node.innerText));\n    }\n\n    return val;\n  }\n\n  var parseTransformString = function parseTransformString(transformString) {\n    var transform = {\n      size: 16,\n      x: 0,\n      y: 0,\n      flipX: false,\n      flipY: false,\n      rotate: 0\n    };\n\n    if (!transformString) {\n      return transform;\n    } else {\n      return transformString.toLowerCase().split(' ').reduce(function (acc, n) {\n        var parts = n.toLowerCase().split('-');\n        var first = parts[0];\n        var rest = parts.slice(1).join('-');\n\n        if (first && rest === 'h') {\n          acc.flipX = true;\n          return acc;\n        }\n\n        if (first && rest === 'v') {\n          acc.flipY = true;\n          return acc;\n        }\n\n        rest = parseFloat(rest);\n\n        if (isNaN(rest)) {\n          return acc;\n        }\n\n        switch (first) {\n          case 'grow':\n            acc.size = acc.size + rest;\n            break;\n\n          case 'shrink':\n            acc.size = acc.size - rest;\n            break;\n\n          case 'left':\n            acc.x = acc.x - rest;\n            break;\n\n          case 'right':\n            acc.x = acc.x + rest;\n            break;\n\n          case 'up':\n            acc.y = acc.y - rest;\n            break;\n\n          case 'down':\n            acc.y = acc.y + rest;\n            break;\n\n          case 'rotate':\n            acc.rotate = acc.rotate + rest;\n            break;\n        }\n\n        return acc;\n      }, transform);\n    }\n  };\n  function transformParser (node) {\n    return parseTransformString(node.getAttribute('data-fa-transform'));\n  }\n\n  function symbolParser (node) {\n    var symbol = node.getAttribute('data-fa-symbol');\n    return symbol === null ? false : symbol === '' ? true : symbol;\n  }\n\n  function attributesParser (node) {\n    var extraAttributes = toArray(node.attributes).reduce(function (acc, attr) {\n      if (acc.name !== 'class' && acc.name !== 'style') {\n        acc[attr.name] = attr.value;\n      }\n\n      return acc;\n    }, {});\n    var title = node.getAttribute('title');\n\n    if (config.autoA11y) {\n      if (title) {\n        extraAttributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n      } else {\n        extraAttributes['aria-hidden'] = 'true';\n        extraAttributes['focusable'] = 'false';\n      }\n    }\n\n    return extraAttributes;\n  }\n\n  function maskParser (node) {\n    var mask = node.getAttribute('data-fa-mask');\n\n    if (!mask) {\n      return emptyCanonicalIcon();\n    } else {\n      return getCanonicalIcon(mask.split(' ').map(function (i) {\n        return i.trim();\n      }));\n    }\n  }\n\n  function blankMeta() {\n    return {\n      iconName: null,\n      title: null,\n      prefix: null,\n      transform: meaninglessTransform,\n      symbol: false,\n      mask: null,\n      extra: {\n        classes: [],\n        styles: {},\n        attributes: {}\n      }\n    };\n  }\n  function parseMeta(node) {\n    var _classParser = classParser(node),\n        iconName = _classParser.iconName,\n        prefix = _classParser.prefix,\n        extraClasses = _classParser.rest;\n\n    var extraStyles = styleParser(node);\n    var transform = transformParser(node);\n    var symbol = symbolParser(node);\n    var extraAttributes = attributesParser(node);\n    var mask = maskParser(node);\n    return {\n      iconName: iconName,\n      title: node.getAttribute('title'),\n      prefix: prefix,\n      transform: transform,\n      symbol: symbol,\n      mask: mask,\n      extra: {\n        classes: extraClasses,\n        styles: extraStyles,\n        attributes: extraAttributes\n      }\n    };\n  }\n\n  function MissingIcon(error) {\n    this.name = 'MissingIcon';\n    this.message = error || 'Icon unavailable';\n    this.stack = new Error().stack;\n  }\n  MissingIcon.prototype = Object.create(Error.prototype);\n  MissingIcon.prototype.constructor = MissingIcon;\n\n  var FILL = {\n    fill: 'currentColor'\n  };\n  var ANIMATION_BASE = {\n    attributeType: 'XML',\n    repeatCount: 'indefinite',\n    dur: '2s'\n  };\n  var RING = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      d: 'M156.5,447.7l-12.6,29.5c-18.7-9.5-35.9-21.2-51.5-34.9l22.7-22.7C127.6,430.5,141.5,440,156.5,447.7z M40.6,272H8.5 c1.4,21.2,5.4,41.7,11.7,61.1L50,321.2C45.1,305.5,41.8,289,40.6,272z M40.6,240c1.4-18.8,5.2-37,11.1-54.1l-29.5-12.6 C14.7,194.3,10,216.7,8.5,240H40.6z M64.3,156.5c7.8-14.9,17.2-28.8,28.1-41.5L69.7,92.3c-13.7,15.6-25.5,32.8-34.9,51.5 L64.3,156.5z M397,419.6c-13.9,12-29.4,22.3-46.1,30.4l11.9,29.8c20.7-9.9,39.8-22.6,56.9-37.6L397,419.6z M115,92.4 c13.9-12,29.4-22.3,46.1-30.4l-11.9-29.8c-20.7,9.9-39.8,22.6-56.8,37.6L115,92.4z M447.7,355.5c-7.8,14.9-17.2,28.8-28.1,41.5 l22.7,22.7c13.7-15.6,25.5-32.9,34.9-51.5L447.7,355.5z M471.4,272c-1.4,18.8-5.2,37-11.1,54.1l29.5,12.6 c7.5-21.1,12.2-43.5,13.6-66.8H471.4z M321.2,462c-15.7,5-32.2,8.2-49.2,9.4v32.1c21.2-1.4,41.7-5.4,61.1-11.7L321.2,462z M240,471.4c-18.8-1.4-37-5.2-54.1-11.1l-12.6,29.5c21.1,7.5,43.5,12.2,66.8,13.6V471.4z M462,190.8c5,15.7,8.2,32.2,9.4,49.2h32.1 c-1.4-21.2-5.4-41.7-11.7-61.1L462,190.8z M92.4,397c-12-13.9-22.3-29.4-30.4-46.1l-29.8,11.9c9.9,20.7,22.6,39.8,37.6,56.9 L92.4,397z M272,40.6c18.8,1.4,36.9,5.2,54.1,11.1l12.6-29.5C317.7,14.7,295.3,10,272,8.5V40.6z M190.8,50 c15.7-5,32.2-8.2,49.2-9.4V8.5c-21.2,1.4-41.7,5.4-61.1,11.7L190.8,50z M442.3,92.3L419.6,115c12,13.9,22.3,29.4,30.5,46.1 l29.8-11.9C470,128.5,457.3,109.4,442.3,92.3z M397,92.4l22.7-22.7c-15.6-13.7-32.8-25.5-51.5-34.9l-12.6,29.5 C370.4,72.1,384.4,81.5,397,92.4z'\n    })\n  };\n\n  var OPACITY_ANIMATE = _objectSpread({}, ANIMATION_BASE, {\n    attributeName: 'opacity'\n  });\n\n  var DOT = {\n    tag: 'circle',\n    attributes: _objectSpread({}, FILL, {\n      cx: '256',\n      cy: '364',\n      r: '28'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, ANIMATION_BASE, {\n        attributeName: 'r',\n        values: '28;14;28;28;14;28;'\n      })\n    }, {\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;1;1;0;1;'\n      })\n    }]\n  };\n  var QUESTION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '1',\n      d: 'M263.7,312h-16c-6.6,0-12-5.4-12-12c0-71,77.4-63.9,77.4-107.8c0-20-17.8-40.2-57.4-40.2c-29.1,0-44.3,9.6-59.2,28.7 c-3.9,5-11.1,6-16.2,2.4l-13.1-9.2c-5.6-3.9-6.9-11.8-2.6-17.2c21.2-27.2,46.4-44.7,91.2-44.7c52.3,0,97.4,29.8,97.4,80.2 c0,67.6-77.4,63.5-77.4,107.8C275.7,306.6,270.3,312,263.7,312z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '1;0;0;0;0;1;'\n      })\n    }]\n  };\n  var EXCLAMATION = {\n    tag: 'path',\n    attributes: _objectSpread({}, FILL, {\n      opacity: '0',\n      d: 'M232.5,134.5l7,168c0.3,6.4,5.6,11.5,12,11.5h9c6.4,0,11.7-5.1,12-11.5l7-168c0.3-6.8-5.2-12.5-12-12.5h-23 C237.7,122,232.2,127.7,232.5,134.5z'\n    }),\n    children: [{\n      tag: 'animate',\n      attributes: _objectSpread({}, OPACITY_ANIMATE, {\n        values: '0;0;1;1;0;0;'\n      })\n    }]\n  };\n  var missing = {\n    tag: 'g',\n    children: [RING, DOT, QUESTION, EXCLAMATION]\n  };\n\n  var styles$2 = namespace.styles;\n  function asFoundIcon(icon) {\n    var width = icon[0];\n    var height = icon[1];\n\n    var _icon$slice = icon.slice(4),\n        _icon$slice2 = _slicedToArray(_icon$slice, 1),\n        vectorData = _icon$slice2[0];\n\n    var element = null;\n\n    if (Array.isArray(vectorData)) {\n      element = {\n        tag: 'g',\n        attributes: {\n          class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.GROUP)\n        },\n        children: [{\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.SECONDARY),\n            fill: 'currentColor',\n            d: vectorData[0]\n          }\n        }, {\n          tag: 'path',\n          attributes: {\n            class: \"\".concat(config.familyPrefix, \"-\").concat(DUOTONE_CLASSES.PRIMARY),\n            fill: 'currentColor',\n            d: vectorData[1]\n          }\n        }]\n      };\n    } else {\n      element = {\n        tag: 'path',\n        attributes: {\n          fill: 'currentColor',\n          d: vectorData\n        }\n      };\n    }\n\n    return {\n      found: true,\n      width: width,\n      height: height,\n      icon: element\n    };\n  }\n  function findIcon(iconName, prefix) {\n    return new picked(function (resolve, reject) {\n      var val = {\n        found: false,\n        width: 512,\n        height: 512,\n        icon: missing\n      };\n\n      if (iconName && prefix && styles$2[prefix] && styles$2[prefix][iconName]) {\n        var icon = styles$2[prefix][iconName];\n        return resolve(asFoundIcon(icon));\n      }\n\n      if (iconName && prefix && !config.showMissingIcons) {\n        reject(new MissingIcon(\"Icon is missing for prefix \".concat(prefix, \" with icon name \").concat(iconName)));\n      } else {\n        resolve(val);\n      }\n    });\n  }\n\n  var styles$3 = namespace.styles;\n\n  function generateSvgReplacementMutation(node, nodeMeta) {\n    var iconName = nodeMeta.iconName,\n        title = nodeMeta.title,\n        prefix = nodeMeta.prefix,\n        transform = nodeMeta.transform,\n        symbol = nodeMeta.symbol,\n        mask = nodeMeta.mask,\n        extra = nodeMeta.extra;\n    return new picked(function (resolve, reject) {\n      picked.all([findIcon(iconName, prefix), findIcon(mask.iconName, mask.prefix)]).then(function (_ref) {\n        var _ref2 = _slicedToArray(_ref, 2),\n            main = _ref2[0],\n            mask = _ref2[1];\n\n        resolve([node, makeInlineSvgAbstract({\n          icons: {\n            main: main,\n            mask: mask\n          },\n          prefix: prefix,\n          iconName: iconName,\n          transform: transform,\n          symbol: symbol,\n          mask: mask,\n          title: title,\n          extra: extra,\n          watchable: true\n        })]);\n      });\n    });\n  }\n\n  function generateLayersText(node, nodeMeta) {\n    var title = nodeMeta.title,\n        transform = nodeMeta.transform,\n        extra = nodeMeta.extra;\n    var width = null;\n    var height = null;\n\n    if (IS_IE) {\n      var computedFontSize = parseInt(getComputedStyle(node).fontSize, 10);\n      var boundingClientRect = node.getBoundingClientRect();\n      width = boundingClientRect.width / computedFontSize;\n      height = boundingClientRect.height / computedFontSize;\n    }\n\n    if (config.autoA11y && !title) {\n      extra.attributes['aria-hidden'] = 'true';\n    }\n\n    return picked.resolve([node, makeLayersTextAbstract({\n      content: node.innerHTML,\n      width: width,\n      height: height,\n      transform: transform,\n      title: title,\n      extra: extra,\n      watchable: true\n    })]);\n  }\n\n  function generateMutation(node) {\n    var nodeMeta = parseMeta(node);\n\n    if (~nodeMeta.extra.classes.indexOf(LAYERS_TEXT_CLASSNAME)) {\n      return generateLayersText(node, nodeMeta);\n    } else {\n      return generateSvgReplacementMutation(node, nodeMeta);\n    }\n  }\n\n  function onTree(root) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    if (!IS_DOM) return;\n    var htmlClassList = DOCUMENT.documentElement.classList;\n\n    var hclAdd = function hclAdd(suffix) {\n      return htmlClassList.add(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var hclRemove = function hclRemove(suffix) {\n      return htmlClassList.remove(\"\".concat(HTML_CLASS_I2SVG_BASE_CLASS, \"-\").concat(suffix));\n    };\n\n    var prefixes = config.autoFetchSvg ? Object.keys(PREFIX_TO_STYLE) : Object.keys(styles$3);\n    var prefixesDomQuery = [\".\".concat(LAYERS_TEXT_CLASSNAME, \":not([\").concat(DATA_FA_I2SVG, \"])\")].concat(prefixes.map(function (p) {\n      return \".\".concat(p, \":not([\").concat(DATA_FA_I2SVG, \"])\");\n    })).join(', ');\n\n    if (prefixesDomQuery.length === 0) {\n      return;\n    }\n\n    var candidates = [];\n\n    try {\n      candidates = toArray(root.querySelectorAll(prefixesDomQuery));\n    } catch (e) {// noop\n    }\n\n    if (candidates.length > 0) {\n      hclAdd('pending');\n      hclRemove('complete');\n    } else {\n      return;\n    }\n\n    var mark = perf.begin('onTree');\n    var mutations = candidates.reduce(function (acc, node) {\n      try {\n        var mutation = generateMutation(node);\n\n        if (mutation) {\n          acc.push(mutation);\n        }\n      } catch (e) {\n        if (!PRODUCTION) {\n          if (e instanceof MissingIcon) {\n            console.error(e);\n          }\n        }\n      }\n\n      return acc;\n    }, []);\n    return new picked(function (resolve, reject) {\n      picked.all(mutations).then(function (resolvedMutations) {\n        perform(resolvedMutations, function () {\n          hclAdd('active');\n          hclAdd('complete');\n          hclRemove('pending');\n          if (typeof callback === 'function') callback();\n          mark();\n          resolve();\n        });\n      }).catch(function () {\n        mark();\n        reject();\n      });\n    });\n  }\n  function onNode(node) {\n    var callback = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : null;\n    generateMutation(node).then(function (mutation) {\n      if (mutation) {\n        perform([mutation], callback);\n      }\n    });\n  }\n\n  function replaceForPosition(node, position) {\n    var pendingAttribute = \"\".concat(DATA_FA_PSEUDO_ELEMENT_PENDING).concat(position.replace(':', '-'));\n    return new picked(function (resolve, reject) {\n      if (node.getAttribute(pendingAttribute) !== null) {\n        // This node is already being processed\n        return resolve();\n      }\n\n      var children = toArray(node.children);\n      var alreadyProcessedPseudoElement = children.filter(function (c) {\n        return c.getAttribute(DATA_FA_PSEUDO_ELEMENT) === position;\n      })[0];\n      var styles = WINDOW.getComputedStyle(node, position);\n      var fontFamily = styles.getPropertyValue('font-family').match(FONT_FAMILY_PATTERN);\n      var fontWeight = styles.getPropertyValue('font-weight');\n\n      if (alreadyProcessedPseudoElement && !fontFamily) {\n        // If we've already processed it but the current computed style does not result in a font-family,\n        // that probably means that a class name that was previously present to make the icon has been\n        // removed. So we now should delete the icon.\n        node.removeChild(alreadyProcessedPseudoElement);\n        return resolve();\n      } else if (fontFamily) {\n        var content = styles.getPropertyValue('content');\n        var prefix = ~['Solid', 'Regular', 'Light', 'Duotone', 'Brands'].indexOf(fontFamily[1]) ? STYLE_TO_PREFIX[fontFamily[1].toLowerCase()] : FONT_WEIGHT_TO_PREFIX[fontWeight];\n        var hexValue = toHex(content.length === 3 ? content.substr(1, 1) : content);\n        var iconName = byUnicode(prefix, hexValue);\n        var iconIdentifier = iconName; // Only convert the pseudo element in this :before/:after position into an icon if we haven't\n        // already done so with the same prefix and iconName\n\n        if (iconName && (!alreadyProcessedPseudoElement || alreadyProcessedPseudoElement.getAttribute(DATA_PREFIX) !== prefix || alreadyProcessedPseudoElement.getAttribute(DATA_ICON) !== iconIdentifier)) {\n          node.setAttribute(pendingAttribute, iconIdentifier);\n\n          if (alreadyProcessedPseudoElement) {\n            // Delete the old one, since we're replacing it with a new one\n            node.removeChild(alreadyProcessedPseudoElement);\n          }\n\n          var meta = blankMeta();\n          var extra = meta.extra;\n          extra.attributes[DATA_FA_PSEUDO_ELEMENT] = position;\n          findIcon(iconName, prefix).then(function (main) {\n            var abstract = makeInlineSvgAbstract(_objectSpread({}, meta, {\n              icons: {\n                main: main,\n                mask: emptyCanonicalIcon()\n              },\n              prefix: prefix,\n              iconName: iconIdentifier,\n              extra: extra,\n              watchable: true\n            }));\n            var element = DOCUMENT.createElement('svg');\n\n            if (position === ':before') {\n              node.insertBefore(element, node.firstChild);\n            } else {\n              node.appendChild(element);\n            }\n\n            element.outerHTML = abstract.map(function (a) {\n              return toHtml(a);\n            }).join('\\n');\n            node.removeAttribute(pendingAttribute);\n            resolve();\n          }).catch(reject);\n        } else {\n          resolve();\n        }\n      } else {\n        resolve();\n      }\n    });\n  }\n\n  function replace(node) {\n    return picked.all([replaceForPosition(node, ':before'), replaceForPosition(node, ':after')]);\n  }\n\n  function processable(node) {\n    return node.parentNode !== document.head && !~TAGNAMES_TO_SKIP_FOR_PSEUDOELEMENTS.indexOf(node.tagName.toUpperCase()) && !node.getAttribute(DATA_FA_PSEUDO_ELEMENT) && (!node.parentNode || node.parentNode.tagName !== 'svg');\n  }\n\n  function searchPseudoElements (root) {\n    if (!IS_DOM) return;\n    return new picked(function (resolve, reject) {\n      var operations = toArray(root.querySelectorAll('*')).filter(processable).map(replace);\n      var end = perf.begin('searchPseudoElements');\n      disableObservation();\n      picked.all(operations).then(function () {\n        end();\n        enableObservation();\n        resolve();\n      }).catch(function () {\n        end();\n        enableObservation();\n        reject();\n      });\n    });\n  }\n\n  var baseStyles = \"svg:not(:root).svg-inline--fa{overflow:visible}.svg-inline--fa{display:inline-block;font-size:inherit;height:1em;overflow:visible;vertical-align:-.125em}.svg-inline--fa.fa-lg{vertical-align:-.225em}.svg-inline--fa.fa-w-1{width:.0625em}.svg-inline--fa.fa-w-2{width:.125em}.svg-inline--fa.fa-w-3{width:.1875em}.svg-inline--fa.fa-w-4{width:.25em}.svg-inline--fa.fa-w-5{width:.3125em}.svg-inline--fa.fa-w-6{width:.375em}.svg-inline--fa.fa-w-7{width:.4375em}.svg-inline--fa.fa-w-8{width:.5em}.svg-inline--fa.fa-w-9{width:.5625em}.svg-inline--fa.fa-w-10{width:.625em}.svg-inline--fa.fa-w-11{width:.6875em}.svg-inline--fa.fa-w-12{width:.75em}.svg-inline--fa.fa-w-13{width:.8125em}.svg-inline--fa.fa-w-14{width:.875em}.svg-inline--fa.fa-w-15{width:.9375em}.svg-inline--fa.fa-w-16{width:1em}.svg-inline--fa.fa-w-17{width:1.0625em}.svg-inline--fa.fa-w-18{width:1.125em}.svg-inline--fa.fa-w-19{width:1.1875em}.svg-inline--fa.fa-w-20{width:1.25em}.svg-inline--fa.fa-pull-left{margin-right:.3em;width:auto}.svg-inline--fa.fa-pull-right{margin-left:.3em;width:auto}.svg-inline--fa.fa-border{height:1.5em}.svg-inline--fa.fa-li{width:2em}.svg-inline--fa.fa-fw{width:1.25em}.fa-layers svg.svg-inline--fa{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.fa-layers{display:inline-block;height:1em;position:relative;text-align:center;vertical-align:-.125em;width:1em}.fa-layers svg.svg-inline--fa{-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter,.fa-layers-text{display:inline-block;position:absolute;text-align:center}.fa-layers-text{left:50%;top:50%;-webkit-transform:translate(-50%,-50%);transform:translate(-50%,-50%);-webkit-transform-origin:center center;transform-origin:center center}.fa-layers-counter{background-color:#ff253a;border-radius:1em;-webkit-box-sizing:border-box;box-sizing:border-box;color:#fff;height:1.5em;line-height:1;max-width:5em;min-width:1.5em;overflow:hidden;padding:.25em;right:0;text-overflow:ellipsis;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-bottom-right{bottom:0;right:0;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom right;transform-origin:bottom right}.fa-layers-bottom-left{bottom:0;left:0;right:auto;top:auto;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:bottom left;transform-origin:bottom left}.fa-layers-top-right{right:0;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top right;transform-origin:top right}.fa-layers-top-left{left:0;right:auto;top:0;-webkit-transform:scale(.25);transform:scale(.25);-webkit-transform-origin:top left;transform-origin:top left}.fa-lg{font-size:1.3333333333em;line-height:.75em;vertical-align:-.0667em}.fa-xs{font-size:.75em}.fa-sm{font-size:.875em}.fa-1x{font-size:1em}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-6x{font-size:6em}.fa-7x{font-size:7em}.fa-8x{font-size:8em}.fa-9x{font-size:9em}.fa-10x{font-size:10em}.fa-fw{text-align:center;width:1.25em}.fa-ul{list-style-type:none;margin-left:2.5em;padding-left:0}.fa-ul>li{position:relative}.fa-li{left:-2em;position:absolute;text-align:center;width:2em;line-height:inherit}.fa-border{border:solid .08em #eee;border-radius:.1em;padding:.2em .25em .15em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left,.fab.fa-pull-left,.fal.fa-pull-left,.far.fa-pull-left,.fas.fa-pull-left{margin-right:.3em}.fa.fa-pull-right,.fab.fa-pull-right,.fal.fa-pull-right,.far.fa-pull-right,.fas.fa-pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s infinite linear;animation:fa-spin 2s infinite linear}.fa-pulse{-webkit-animation:fa-spin 1s infinite steps(8);animation:fa-spin 1s infinite steps(8)}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0);transform:rotate(0)}100%{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}.fa-rotate-90{-webkit-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{-webkit-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{-webkit-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{-webkit-transform:scale(-1,1);transform:scale(-1,1)}.fa-flip-vertical{-webkit-transform:scale(1,-1);transform:scale(1,-1)}.fa-flip-both,.fa-flip-horizontal.fa-flip-vertical{-webkit-transform:scale(-1,-1);transform:scale(-1,-1)}:root .fa-flip-both,:root .fa-flip-horizontal,:root .fa-flip-vertical,:root .fa-rotate-180,:root .fa-rotate-270,:root .fa-rotate-90{-webkit-filter:none;filter:none}.fa-stack{display:inline-block;height:2em;position:relative;width:2.5em}.fa-stack-1x,.fa-stack-2x{bottom:0;left:0;margin:auto;position:absolute;right:0;top:0}.svg-inline--fa.fa-stack-1x{height:1em;width:1.25em}.svg-inline--fa.fa-stack-2x{height:2em;width:2.5em}.fa-inverse{color:#fff}.sr-only{border:0;clip:rect(0,0,0,0);height:1px;margin:-1px;overflow:hidden;padding:0;position:absolute;width:1px}.sr-only-focusable:active,.sr-only-focusable:focus{clip:auto;height:auto;margin:0;overflow:visible;position:static;width:auto}.svg-inline--fa .fa-primary{fill:var(--fa-primary-color,currentColor);opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa .fa-secondary{fill:var(--fa-secondary-color,currentColor);opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-primary{opacity:.4;opacity:var(--fa-secondary-opacity,.4)}.svg-inline--fa.fa-swap-opacity .fa-secondary{opacity:1;opacity:var(--fa-primary-opacity,1)}.svg-inline--fa mask .fa-primary,.svg-inline--fa mask .fa-secondary{fill:#000}.fad.fa-inverse{color:#fff}\";\n\n  function css () {\n    var dfp = DEFAULT_FAMILY_PREFIX;\n    var drc = DEFAULT_REPLACEMENT_CLASS;\n    var fp = config.familyPrefix;\n    var rc = config.replacementClass;\n    var s = baseStyles;\n\n    if (fp !== dfp || rc !== drc) {\n      var dPatt = new RegExp(\"\\\\.\".concat(dfp, \"\\\\-\"), 'g');\n      var customPropPatt = new RegExp(\"\\\\--\".concat(dfp, \"\\\\-\"), 'g');\n      var rPatt = new RegExp(\"\\\\.\".concat(drc), 'g');\n      s = s.replace(dPatt, \".\".concat(fp, \"-\")).replace(customPropPatt, \"--\".concat(fp, \"-\")).replace(rPatt, \".\".concat(rc));\n    }\n\n    return s;\n  }\n\n  var Library =\n  /*#__PURE__*/\n  function () {\n    function Library() {\n      _classCallCheck(this, Library);\n\n      this.definitions = {};\n    }\n\n    _createClass(Library, [{\n      key: \"add\",\n      value: function add() {\n        var _this = this;\n\n        for (var _len = arguments.length, definitions = new Array(_len), _key = 0; _key < _len; _key++) {\n          definitions[_key] = arguments[_key];\n        }\n\n        var additions = definitions.reduce(this._pullDefinitions, {});\n        Object.keys(additions).forEach(function (key) {\n          _this.definitions[key] = _objectSpread({}, _this.definitions[key] || {}, additions[key]);\n          defineIcons(key, additions[key]);\n          build();\n        });\n      }\n    }, {\n      key: \"reset\",\n      value: function reset() {\n        this.definitions = {};\n      }\n    }, {\n      key: \"_pullDefinitions\",\n      value: function _pullDefinitions(additions, definition) {\n        var normalized = definition.prefix && definition.iconName && definition.icon ? {\n          0: definition\n        } : definition;\n        Object.keys(normalized).map(function (key) {\n          var _normalized$key = normalized[key],\n              prefix = _normalized$key.prefix,\n              iconName = _normalized$key.iconName,\n              icon = _normalized$key.icon;\n          if (!additions[prefix]) additions[prefix] = {};\n          additions[prefix][iconName] = icon;\n        });\n        return additions;\n      }\n    }]);\n\n    return Library;\n  }();\n\n  function ensureCss() {\n    if (config.autoAddCss && !_cssInserted) {\n      insertCss(css());\n\n      _cssInserted = true;\n    }\n  }\n\n  function apiObject(val, abstractCreator) {\n    Object.defineProperty(val, 'abstract', {\n      get: abstractCreator\n    });\n    Object.defineProperty(val, 'html', {\n      get: function get() {\n        return val.abstract.map(function (a) {\n          return toHtml(a);\n        });\n      }\n    });\n    Object.defineProperty(val, 'node', {\n      get: function get() {\n        if (!IS_DOM) return;\n        var container = DOCUMENT.createElement('div');\n        container.innerHTML = val.html;\n        return container.children;\n      }\n    });\n    return val;\n  }\n\n  function findIconDefinition(iconLookup) {\n    var _iconLookup$prefix = iconLookup.prefix,\n        prefix = _iconLookup$prefix === void 0 ? 'fa' : _iconLookup$prefix,\n        iconName = iconLookup.iconName;\n    if (!iconName) return;\n    return iconFromMapping(library.definitions, prefix, iconName) || iconFromMapping(namespace.styles, prefix, iconName);\n  }\n\n  function resolveIcons(next) {\n    return function (maybeIconDefinition) {\n      var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n      var iconDefinition = (maybeIconDefinition || {}).icon ? maybeIconDefinition : findIconDefinition(maybeIconDefinition || {});\n      var mask = params.mask;\n\n      if (mask) {\n        mask = (mask || {}).icon ? mask : findIconDefinition(mask || {});\n      }\n\n      return next(iconDefinition, _objectSpread({}, params, {\n        mask: mask\n      }));\n    };\n  }\n\n  var library = new Library();\n  var noAuto = function noAuto() {\n    config.autoReplaceSvg = false;\n    config.observeMutations = false;\n    disconnect();\n  };\n  var _cssInserted = false;\n  var dom = {\n    i2svg: function i2svg() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n\n      if (IS_DOM) {\n        ensureCss();\n        var _params$node = params.node,\n            node = _params$node === void 0 ? DOCUMENT : _params$node,\n            _params$callback = params.callback,\n            callback = _params$callback === void 0 ? function () {} : _params$callback;\n\n        if (config.searchPseudoElements) {\n          searchPseudoElements(node);\n        }\n\n        return onTree(node, callback);\n      } else {\n        return picked.reject('Operation requires a DOM of some kind.');\n      }\n    },\n    css: css,\n    insertCss: function insertCss$$1() {\n      if (!_cssInserted) {\n        insertCss(css());\n\n        _cssInserted = true;\n      }\n    },\n    watch: function watch() {\n      var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n      var autoReplaceSvgRoot = params.autoReplaceSvgRoot,\n          observeMutationsRoot = params.observeMutationsRoot;\n\n      if (config.autoReplaceSvg === false) {\n        config.autoReplaceSvg = true;\n      }\n\n      config.observeMutations = true;\n      domready(function () {\n        autoReplace({\n          autoReplaceSvgRoot: autoReplaceSvgRoot\n        });\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements,\n          observeMutationsRoot: observeMutationsRoot\n        });\n      });\n    }\n  };\n  var parse = {\n    transform: function transform(transformString) {\n      return parseTransformString(transformString);\n    }\n  };\n  var icon = resolveIcons(function (iconDefinition) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform = params.transform,\n        transform = _params$transform === void 0 ? meaninglessTransform : _params$transform,\n        _params$symbol = params.symbol,\n        symbol = _params$symbol === void 0 ? false : _params$symbol,\n        _params$mask = params.mask,\n        mask = _params$mask === void 0 ? null : _params$mask,\n        _params$title = params.title,\n        title = _params$title === void 0 ? null : _params$title,\n        _params$classes = params.classes,\n        classes = _params$classes === void 0 ? [] : _params$classes,\n        _params$attributes = params.attributes,\n        attributes = _params$attributes === void 0 ? {} : _params$attributes,\n        _params$styles = params.styles,\n        styles = _params$styles === void 0 ? {} : _params$styles;\n    if (!iconDefinition) return;\n    var prefix = iconDefinition.prefix,\n        iconName = iconDefinition.iconName,\n        icon = iconDefinition.icon;\n    return apiObject(_objectSpread({\n      type: 'icon'\n    }, iconDefinition), function () {\n      ensureCss();\n\n      if (config.autoA11y) {\n        if (title) {\n          attributes['aria-labelledby'] = \"\".concat(config.replacementClass, \"-title-\").concat(nextUniqueId());\n        } else {\n          attributes['aria-hidden'] = 'true';\n          attributes['focusable'] = 'false';\n        }\n      }\n\n      return makeInlineSvgAbstract({\n        icons: {\n          main: asFoundIcon(icon),\n          mask: mask ? asFoundIcon(mask.icon) : {\n            found: false,\n            width: null,\n            height: null,\n            icon: {}\n          }\n        },\n        prefix: prefix,\n        iconName: iconName,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        symbol: symbol,\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: classes\n        }\n      });\n    });\n  });\n  var text = function text(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$transform2 = params.transform,\n        transform = _params$transform2 === void 0 ? meaninglessTransform : _params$transform2,\n        _params$title2 = params.title,\n        title = _params$title2 === void 0 ? null : _params$title2,\n        _params$classes2 = params.classes,\n        classes = _params$classes2 === void 0 ? [] : _params$classes2,\n        _params$attributes2 = params.attributes,\n        attributes = _params$attributes2 === void 0 ? {} : _params$attributes2,\n        _params$styles2 = params.styles,\n        styles = _params$styles2 === void 0 ? {} : _params$styles2;\n    return apiObject({\n      type: 'text',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersTextAbstract({\n        content: content,\n        transform: _objectSpread({}, meaninglessTransform, transform),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-text\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var counter = function counter(content) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$title3 = params.title,\n        title = _params$title3 === void 0 ? null : _params$title3,\n        _params$classes3 = params.classes,\n        classes = _params$classes3 === void 0 ? [] : _params$classes3,\n        _params$attributes3 = params.attributes,\n        attributes = _params$attributes3 === void 0 ? {} : _params$attributes3,\n        _params$styles3 = params.styles,\n        styles = _params$styles3 === void 0 ? {} : _params$styles3;\n    return apiObject({\n      type: 'counter',\n      content: content\n    }, function () {\n      ensureCss();\n      return makeLayersCounterAbstract({\n        content: content.toString(),\n        title: title,\n        extra: {\n          attributes: attributes,\n          styles: styles,\n          classes: [\"\".concat(config.familyPrefix, \"-layers-counter\")].concat(_toConsumableArray(classes))\n        }\n      });\n    });\n  };\n  var layer = function layer(assembler) {\n    var params = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {};\n    var _params$classes4 = params.classes,\n        classes = _params$classes4 === void 0 ? [] : _params$classes4;\n    return apiObject({\n      type: 'layer'\n    }, function () {\n      ensureCss();\n      var children = [];\n      assembler(function (args) {\n        Array.isArray(args) ? args.map(function (a) {\n          children = children.concat(a.abstract);\n        }) : children = children.concat(args.abstract);\n      });\n      return [{\n        tag: 'span',\n        attributes: {\n          class: [\"\".concat(config.familyPrefix, \"-layers\")].concat(_toConsumableArray(classes)).join(' ')\n        },\n        children: children\n      }];\n    });\n  };\n  var api = {\n    noAuto: noAuto,\n    config: config,\n    dom: dom,\n    library: library,\n    parse: parse,\n    findIconDefinition: findIconDefinition,\n    icon: icon,\n    text: text,\n    counter: counter,\n    layer: layer,\n    toHtml: toHtml\n  };\n\n  var autoReplace = function autoReplace() {\n    var params = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : {};\n    var _params$autoReplaceSv = params.autoReplaceSvgRoot,\n        autoReplaceSvgRoot = _params$autoReplaceSv === void 0 ? DOCUMENT : _params$autoReplaceSv;\n    if ((Object.keys(namespace.styles).length > 0 || config.autoFetchSvg) && IS_DOM && config.autoReplaceSvg) api.dom.i2svg({\n      node: autoReplaceSvgRoot\n    });\n  };\n\n  function bootstrap() {\n    if (IS_BROWSER) {\n      if (!WINDOW.FontAwesome) {\n        WINDOW.FontAwesome = api;\n      }\n\n      domready(function () {\n        autoReplace();\n        observe({\n          treeCallback: onTree,\n          nodeCallback: onNode,\n          pseudoElementsCallback: searchPseudoElements\n        });\n      });\n    }\n\n    namespace.hooks = _objectSpread({}, namespace.hooks, {\n      addPack: function addPack(prefix, icons) {\n        namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, icons);\n        build();\n        autoReplace();\n      },\n      addShims: function addShims(shims) {\n        var _namespace$shims;\n\n        (_namespace$shims = namespace.shims).push.apply(_namespace$shims, _toConsumableArray(shims));\n\n        build();\n        autoReplace();\n      }\n    });\n  }\n\n  bunker(bootstrap);\n\n}());\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/regular.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-68 304H48V48h320v416zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H48V80h480v352zM208 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2zM360 320h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-144c-33.6 0-65.2 14.8-86.8 40.6-8.5 10.2-7.1 25.3 3.1 33.8s25.3 7.2 33.8-3c24.8-29.7 75-29.7 99.8 0 8.1 9.7 23.2 11.9 33.8 3 10.2-8.5 11.5-23.6 3.1-33.8-21.6-25.8-53.2-40.6-86.8-40.6zm-48-72c10.3 0 19.9-6.7 23-17.1 3.8-12.7-3.4-26.1-16.1-29.9l-80-24c-12.8-3.9-26.1 3.4-29.9 16.1-3.8 12.7 3.4 26.1 16.1 29.9l28.2 8.5c-3.1 4.9-5.3 10.4-5.3 16.6 0 17.7 14.3 32 32 32s32-14.4 32-32.1zm199-54.9c-3.8-12.7-17.1-19.9-29.9-16.1l-80 24c-12.7 3.8-19.9 17.2-16.1 29.9 3.1 10.4 12.7 17.1 23 17.1 0 17.7 14.3 32 32 32s32-14.3 32-32c0-6.2-2.2-11.7-5.3-16.6l28.2-8.5c12.7-3.7 19.9-17.1 16.1-29.8z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm-32-316v116h-67c-10.7 0-16 12.9-8.5 20.5l99 99c4.7 4.7 12.3 4.7 17 0l99-99c7.6-7.6 2.2-20.5-8.5-20.5h-67V140c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M8 256c0 137 111 248 248 248s248-111 248-248S393 8 256 8 8 119 8 256zm448 0c0 110.5-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56s200 89.5 200 200zm-72-20v40c0 6.6-5.4 12-12 12H256v67c0 10.7-12.9 16-20.5 8.5l-99-99c-4.7-4.7-4.7-12.3 0-17l99-99c7.6-7.6 20.5-2.2 20.5 8.5v67h116c6.6 0 12 5.4 12 12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm72 20v-40c0-6.6 5.4-12 12-12h116v-67c0-10.7 12.9-16 20.5-8.5l99 99c4.7 4.7 4.7 12.3 0 17l-99 99c-7.6 7.6-20.5 2.2-20.5-8.5v-67H140c-6.6 0-12-5.4-12-12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M256 504c137 0 248-111 248-248S393 8 256 8 8 119 8 256s111 248 248 248zm0-448c110.5 0 200 89.5 200 200s-89.5 200-200 200S56 366.5 56 256 145.5 56 256 56zm20 328h-40c-6.6 0-12-5.4-12-12V256h-67c-10.7 0-16-12.9-8.5-20.5l99-99c4.7-4.7 12.3-4.7 17 0l99 99c7.6 7.6 2.2 20.5-8.5 20.5h-67v116c0 6.6-5.4 12-12 12z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M439.39 362.29c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71zM67.53 368c21.22-27.97 44.42-74.33 44.53-159.42 0-.2-.06-.38-.06-.58 0-61.86 50.14-112 112-112s112 50.14 112 112c0 .2-.06.38-.06.58.11 85.1 23.31 131.46 44.53 159.42H67.53zM224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.99 471.02L36 3.51C29.1-2.01 19.03-.9 13.51 6l-10 12.49C-2.02 25.39-.9 35.46 6 40.98l598 467.51c6.9 5.52 16.96 4.4 22.49-2.49l10-12.49c5.52-6.9 4.41-16.97-2.5-22.49zM163.53 368c16.71-22.03 34.48-55.8 41.4-110.58l-45.47-35.55c-3.27 90.73-36.47 120.68-54.84 140.42-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h279.66l-61.4-48H163.53zM320 96c61.86 0 112 50.14 112 112 0 .2-.06.38-.06.58.02 16.84 1.16 31.77 2.79 45.73l59.53 46.54c-8.31-22.13-14.34-51.49-14.34-92.85 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-26.02 5.41-49.45 16.94-69.13 32.72l38.17 29.84C275 103.18 296.65 96 320 96zm0 416c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M336 0H48C21.49 0 0 21.49 0 48v464l192-112 192 112V48c0-26.51-21.49-48-48-48zm0 428.43l-144-84-144 84V54a6 6 0 0 1 6-6h276c3.314 0 6 2.683 6 5.996V428.43z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M128 148v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12zm140 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-128 96h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm128 0h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm-76 84v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm76 12h40c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12zm180 124v36H0v-36c0-6.6 5.4-12 12-12h19.5V24c0-13.3 10.7-24 24-24h337c13.3 0 24 10.7 24 24v440H436c6.6 0 12 5.4 12 12zM79.5 463H192v-67c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v67h112.5V49L80 48l-.5 415z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M400 64h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V160h352v298c0 3.3-2.7 6-6 6z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M148 288h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm108-12v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 96v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm-96 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-40c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm96-260v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M400 64h-48V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H160V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v52H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V160h352v298a6 6 0 0 1-6 6zm-52.849-200.65L198.842 404.519c-4.705 4.667-12.303 4.637-16.971-.068l-75.091-75.699c-4.667-4.705-4.637-12.303.068-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l44.104 44.461 111.072-110.181c4.705-4.667 12.303-4.637 16.971.068l22.536 22.718c4.667 4.705 4.636 12.303-.069 16.97z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M124 328c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v24c0 6.6-5.4 12-12 12H124zm324-216v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M336 292v24c0 6.6-5.4 12-12 12h-76v76c0 6.6-5.4 12-12 12h-24c-6.6 0-12-5.4-12-12v-76h-76c-6.6 0-12-5.4-12-12v-24c0-6.6 5.4-12 12-12h76v-76c0-6.6 5.4-12 12-12h24c6.6 0 12 5.4 12 12v76h76c6.6 0 12 5.4 12 12zm112-180v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M311.7 374.7l-17 17c-4.7 4.7-12.3 4.7-17 0L224 337.9l-53.7 53.7c-4.7 4.7-12.3 4.7-17 0l-17-17c-4.7-4.7-4.7-12.3 0-17l53.7-53.7-53.7-53.7c-4.7-4.7-4.7-12.3 0-17l17-17c4.7-4.7 12.3-4.7 17 0l53.7 53.7 53.7-53.7c4.7-4.7 12.3-4.7 17 0l17 17c4.7 4.7 4.7 12.3 0 17L257.9 304l53.7 53.7c4.8 4.7 4.8 12.3.1 17zM448 112v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48zm-48 346V160H48v298c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M125.1 208h197.8c10.7 0 16.1 13 8.5 20.5l-98.9 98.3c-4.7 4.7-12.2 4.7-16.9 0l-98.9-98.3c-7.7-7.5-2.3-20.5 8.4-20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M272 157.1v197.8c0 10.7-13 16.1-20.5 8.5l-98.3-98.9c-4.7-4.7-4.7-12.2 0-16.9l98.3-98.9c7.5-7.7 20.5-2.3 20.5 8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M176 354.9V157.1c0-10.7 13-16.1 20.5-8.5l98.3 98.9c4.7 4.7 4.7 12.2 0 16.9l-98.3 98.9c-7.5 7.7-20.5 2.3-20.5-8.4zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M322.9 304H125.1c-10.7 0-16.1-13-8.5-20.5l98.9-98.3c4.7-4.7 12.2-4.7 16.9 0l98.9 98.3c7.7 7.5 2.3 20.5-8.4 20.5zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M396.8 352h22.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-192 0h22.4c6.4 0 12.8-6.4 12.8-12.8V140.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h22.4c6.4 0 12.8-6.4 12.8-12.8V204.8c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zM496 400H48V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16zm-387.2-48h22.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-22.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 48c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m140.204 130.267l-22.536-22.718c-4.667-4.705-12.265-4.736-16.97-.068L215.346 303.697l-59.792-60.277c-4.667-4.705-12.265-4.736-16.97-.069l-22.719 22.536c-4.705 4.667-4.736 12.265-.068 16.971l90.781 91.516c4.667 4.705 12.265 4.736 16.97.068l172.589-171.204c4.704-4.668 4.734-12.266.067-16.971z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm0 400H48V80h352v352zm-35.864-241.724L191.547 361.48c-4.705 4.667-12.303 4.637-16.97-.068l-90.781-91.516c-4.667-4.705-4.637-12.303.069-16.971l22.719-22.536c4.705-4.667 12.303-4.637 16.97.069l59.792 60.277 141.352-140.216c4.705-4.667 12.303-4.637 16.97.068l22.536 22.718c4.667 4.706 4.637 12.304-.068 16.971z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm144 418c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h42v36c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-36h42c3.3 0 6 2.7 6 6z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm61.8-104.4l-84.9-61.7c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v141.7l66.8 48.6c5.4 3.9 6.5 11.4 2.6 16.8L334.6 349c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0H144c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h320c26.51 0 48-21.49 48-48v-48h48c26.51 0 48-21.49 48-48V48c0-26.51-21.49-48-48-48zM362 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h42v224c0 26.51 21.49 48 48 48h224v42a6 6 0 0 1-6 6zm96-96H150a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h308a6 6 0 0 1 6 6v308a6 6 0 0 1-6 6z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zm-6 336H54c-3.3 0-6-2.7-6-6V118c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v276c0 3.3-2.7 6-6 6zm-211.1-85.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7zm190.4 0c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.9-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 220.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6 2.8-2.5 7.1-2.1 9.2.9l19.6 27.7z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 7.1 5.8 12 12 12 2.4 0 4.9-.7 7.1-2.4L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zm16 352c0 8.8-7.2 16-16 16H288l-12.8 9.6L208 428v-60H64c-8.8 0-16-7.2-16-16V64c0-8.8 7.2-16 16-16h384c8.8 0 16 7.2 16 16v288z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M144 208c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm112 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zM256 32C114.6 32 0 125.1 0 240c0 47.6 19.9 91.2 52.9 126.3C38 405.7 7 439.1 6.5 439.5c-6.6 7-8.4 17.2-4.6 26S14.4 480 24 480c61.5 0 110-25.7 139.1-46.3C192 442.8 223.2 448 256 448c141.4 0 256-93.1 256-208S397.4 32 256 32zm0 368c-26.7 0-53.1-4.1-78.4-12.1l-22.7-7.2-19.5 13.8c-14.3 10.1-33.9 21.4-57.5 29 7.3-12.1 14.4-25.7 19.9-40.2l10.6-28.1-20.6-21.8C69.7 314.1 48 282.2 48 240c0-88.2 93.3-160 208-160s208 71.8 208 160-93.3 160-208 160z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M532 386.2c27.5-27.1 44-61.1 44-98.2 0-80-76.5-146.1-176.2-157.9C368.3 72.5 294.3 32 208 32 93.1 32 0 103.6 0 192c0 37 16.5 71 44 98.2-15.3 30.7-37.3 54.5-37.7 54.9-6.3 6.7-8.1 16.5-4.4 25 3.6 8.5 12 14 21.2 14 53.5 0 96.7-20.2 125.2-38.8 9.2 2.1 18.7 3.7 28.4 4.9C208.1 407.6 281.8 448 368 448c20.8 0 40.8-2.4 59.8-6.8C456.3 459.7 499.4 480 553 480c9.2 0 17.5-5.5 21.2-14 3.6-8.5 1.9-18.3-4.4-25-.4-.3-22.5-24.1-37.8-54.8zm-392.8-92.3L122.1 305c-14.1 9.1-28.5 16.3-43.1 21.4 2.7-4.7 5.4-9.7 8-14.8l15.5-31.1L77.7 256C64.2 242.6 48 220.7 48 192c0-60.7 73.3-112 160-112s160 51.3 160 112-73.3 112-160 112c-16.5 0-33-1.9-49-5.6l-19.8-4.5zM498.3 352l-24.7 24.4 15.5 31.1c2.6 5.1 5.3 10.1 8 14.8-14.6-5.1-29-12.3-43.1-21.4l-17.1-11.1-19.9 4.6c-16 3.7-32.5 5.6-49 5.6-54 0-102.2-20.1-131.3-49.7C338 339.5 416 272.9 416 192c0-3.4-.4-6.7-.7-10C479.7 196.5 528 238.8 528 288c0 28.7-16.2 50.6-29.7 64z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M347.94 129.86L203.6 195.83a31.938 31.938 0 0 0-15.77 15.77l-65.97 144.34c-7.61 16.65 9.54 33.81 26.2 26.2l144.34-65.97a31.938 31.938 0 0 0 15.77-15.77l65.97-144.34c7.61-16.66-9.54-33.81-26.2-26.2zm-77.36 148.72c-12.47 12.47-32.69 12.47-45.16 0-12.47-12.47-12.47-32.69 0-45.16 12.47-12.47 32.69-12.47 45.16 0 12.47 12.47 12.47 32.69 0 45.16zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M433.941 65.941l-51.882-51.882A48 48 0 0 0 348.118 0H176c-26.51 0-48 21.49-48 48v48H48c-26.51 0-48 21.49-48 48v320c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48v-48h80c26.51 0 48-21.49 48-48V99.882a48 48 0 0 0-14.059-33.941zM266 464H54a6 6 0 0 1-6-6V150a6 6 0 0 1 6-6h74v224c0 26.51 21.49 48 48 48h96v42a6 6 0 0 1-6 6zm128-96H182a6 6 0 0 1-6-6V54a6 6 0 0 1 6-6h106v88c0 13.255 10.745 24 24 24h88v202a6 6 0 0 1-6 6zm6-256h-64V48h9.632c1.591 0 3.117.632 4.243 1.757l48.368 48.368a6 6 0 0 1 1.757 4.243V112z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm107.351-101.064c-9.614 9.712-45.53 41.396-104.065 41.396-82.43 0-140.484-61.425-140.484-141.567 0-79.152 60.275-139.401 139.762-139.401 55.531 0 88.738 26.62 97.593 34.779a11.965 11.965 0 0 1 1.936 15.322l-18.155 28.113c-3.841 5.95-11.966 7.282-17.499 2.921-8.595-6.776-31.814-22.538-61.708-22.538-48.303 0-77.916 35.33-77.916 80.082 0 41.589 26.888 83.692 78.277 83.692 32.657 0 56.843-19.039 65.726-27.225 5.27-4.857 13.596-4.039 17.82 1.738l19.865 27.17a11.947 11.947 0 0 1-1.152 15.518z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M527.9 32H48.1C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48.1 48h479.8c26.6 0 48.1-21.5 48.1-48V80c0-26.5-21.5-48-48.1-48zM54.1 80h467.8c3.3 0 6 2.7 6 6v42H48.1V86c0-3.3 2.7-6 6-6zm467.8 352H54.1c-3.3 0-6-2.7-6-6V256h479.8v170c0 3.3-2.7 6-6 6zM192 332v40c0 6.6-5.4 12-12 12h-72c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12zm192 0v40c0 6.6-5.4 12-12 12H236c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-33.8-217.9c7.8-7.8 7.8-20.5 0-28.3L196.3 192l17.9-17.9c7.8-7.8 7.8-20.5 0-28.3-7.8-7.8-20.5-7.8-28.3 0L168 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.9 7.7 20.5 7.7 28.4-.2zm160-92.2c-7.8-7.8-20.5-7.8-28.3 0L328 163.7l-17.8-17.8c-7.8-7.8-20.5-7.8-28.3 0-7.8 7.8-7.8 20.5 0 28.3l17.9 17.9-17.9 17.9c-7.8 7.8-7.8 20.5 0 28.3 7.8 7.8 20.5 7.8 28.3 0l17.8-17.8 17.8 17.8c7.8 7.8 20.5 7.8 28.3 0 7.8-7.8 7.8-20.5 0-28.3l-17.8-18 17.9-17.9c7.7-7.8 7.7-20.4 0-28.2zM248 272c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 56c110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200-110.532 0-200-89.451-200-200 0-110.532 89.451-200 200-200m0-48C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 168c-44.183 0-80 35.817-80 80s35.817 80 80 80 80-35.817 80-80-35.817-80-80-80z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.3 344.9l32-32c5-5 13.7-1.5 13.7 5.7V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V112c0-26.5 21.5-48 48-48h273.5c7.1 0 10.7 8.6 5.7 13.7l-32 32c-1.5 1.5-3.5 2.3-5.7 2.3H48v352h352V350.5c0-2.1.8-4.1 2.3-5.6zm156.6-201.8L296.3 405.7l-90.4 10c-26.2 2.9-48.5-19.2-45.6-45.6l10-90.4L432.9 17.1c22.9-22.9 59.9-22.9 82.7 0l43.2 43.2c22.9 22.9 22.9 60 .1 82.8zM460.1 174L402 115.9 216.2 301.8l-7.3 65.3 65.3-7.3L460.1 174zm64.8-79.7l-43.2-43.2c-4.1-4.1-10.8-4.1-14.8 0L436 82l58.1 58.1 30.9-30.9c4-4.2 4-10.8-.1-14.9z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm0 48v40.805c-22.422 18.259-58.168 46.651-134.587 106.49-16.841 13.247-50.201 45.072-73.413 44.701-23.208.375-56.579-31.459-73.413-44.701C106.18 199.465 70.425 171.067 48 152.805V112h416zM48 400V214.398c22.914 18.251 55.409 43.862 104.938 82.646 21.857 17.205 60.134 55.186 103.062 54.955 42.717.231 80.509-37.199 103.053-54.947 49.528-38.783 82.032-64.401 104.947-82.653V400H48z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M494.586 164.516c-4.697-3.883-111.723-89.95-135.251-108.657C337.231 38.191 299.437 0 256 0c-43.205 0-80.636 37.717-103.335 55.859-24.463 19.45-131.07 105.195-135.15 108.549A48.004 48.004 0 0 0 0 201.485V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V201.509a48 48 0 0 0-17.414-36.993zM464 458a6 6 0 0 1-6 6H54a6 6 0 0 1-6-6V204.347c0-1.813.816-3.526 2.226-4.665 15.87-12.814 108.793-87.554 132.364-106.293C200.755 78.88 232.398 48 256 48c23.693 0 55.857 31.369 73.41 45.389 23.573 18.741 116.503 93.493 132.366 106.316a5.99 5.99 0 0 1 2.224 4.663V458zm-31.991-187.704c4.249 5.159 3.465 12.795-1.745 16.981-28.975 23.283-59.274 47.597-70.929 56.863C336.636 362.283 299.205 400 256 400c-43.452 0-81.287-38.237-103.335-55.86-11.279-8.967-41.744-33.413-70.927-56.865-5.21-4.187-5.993-11.822-1.745-16.981l15.258-18.528c4.178-5.073 11.657-5.843 16.779-1.726 28.618 23.001 58.566 47.035 70.56 56.571C200.143 320.631 232.307 352 256 352c23.602 0 55.246-30.88 73.41-45.389 11.994-9.535 41.944-33.57 70.563-56.568 5.122-4.116 12.601-3.346 16.778 1.727l15.258 18.526z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M288 144a110.94 110.94 0 0 0-31.24 5 55.4 55.4 0 0 1 7.24 27 56 56 0 0 1-56 56 55.4 55.4 0 0 1-27-7.24A111.71 111.71 0 1 0 288 144zm284.52 97.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400c-98.65 0-189.09-55-237.93-144C98.91 167 189.34 112 288 112s189.09 55 237.93 144C477.1 345 386.66 400 288 400z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M634 471L36 3.51A16 16 0 0 0 13.51 6l-10 12.49A16 16 0 0 0 6 41l598 467.49a16 16 0 0 0 22.49-2.49l10-12.49A16 16 0 0 0 634 471zM296.79 146.47l134.79 105.38C429.36 191.91 380.48 144 320 144a112.26 112.26 0 0 0-23.21 2.47zm46.42 219.07L208.42 260.16C210.65 320.09 259.53 368 320 368a113 113 0 0 0 23.21-2.46zM320 112c98.65 0 189.09 55 237.93 144a285.53 285.53 0 0 1-44 60.2l37.74 29.5a333.7 333.7 0 0 0 52.9-75.11 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64c-36.7 0-71.71 7-104.63 18.81l46.41 36.29c18.94-4.3 38.34-7.1 58.22-7.1zm0 288c-98.65 0-189.08-55-237.93-144a285.47 285.47 0 0 1 44.05-60.19l-37.74-29.5a333.6 333.6 0 0 0-52.89 75.1 32.35 32.35 0 0 0 0 29.19C89.72 376.41 197.08 448 320 448c36.7 0 71.71-7.05 104.63-18.81l-46.41-36.28C359.28 397.2 339.89 400 320 400z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M288 248v28c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-28c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm-12 72H108c-6.6 0-12 5.4-12 12v28c0 6.6 5.4 12 12 12h168c6.6 0 12-5.4 12-12v-28c0-6.6-5.4-12-12-12zm108-188.1V464c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V48C0 21.5 21.5 0 48 0h204.1C264.8 0 277 5.1 286 14.1L369.9 98c9 8.9 14.1 21.2 14.1 33.9zm-128-80V128h76.1L256 51.9zM336 464V176H232c-13.3 0-24-10.7-24-24V48H48v416h288z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M128.3 160v32h32v-32zm64-96h-32v32h32zm-64 32v32h32V96zm64 32h-32v32h32zm177.6-30.1L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h79.7v16h32V48H208v104c0 13.3 10.7 24 24 24h104zM194.2 265.7c-1.1-5.6-6-9.7-11.8-9.7h-22.1v-32h-32v32l-19.7 97.1C102 385.6 126.8 416 160 416c33.1 0 57.9-30.2 51.5-62.6zm-33.9 124.4c-17.9 0-32.4-12.1-32.4-27s14.5-27 32.4-27 32.4 12.1 32.4 27-14.5 27-32.4 27zm32-198.1h-32v32h32z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm144-76.024c0 10.691-12.926 16.045-20.485 8.485L136 360.486h-28c-6.627 0-12-5.373-12-12v-56c0-6.627 5.373-12 12-12h28l35.515-36.947c7.56-7.56 20.485-2.206 20.485 8.485v135.952zm41.201-47.13c9.051-9.297 9.06-24.133.001-33.439-22.149-22.752 12.235-56.246 34.395-33.481 27.198 27.94 27.212 72.444.001 100.401-21.793 22.386-56.947-10.315-34.397-33.481z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M149.9 349.1l-.2-.2-32.8-28.9 32.8-28.9c3.6-3.2 4-8.8.8-12.4l-.2-.2-17.4-18.6c-3.4-3.6-9-3.7-12.4-.4l-57.7 54.1c-3.7 3.5-3.7 9.4 0 12.8l57.7 54.1c1.6 1.5 3.8 2.4 6 2.4 2.4 0 4.8-1 6.4-2.8l17.4-18.6c3.3-3.5 3.1-9.1-.4-12.4zm220-251.2L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM256 51.9l76.1 76.1H256zM336 464H48V48h160v104c0 13.3 10.7 24 24 24h104zM209.6 214c-4.7-1.4-9.5 1.3-10.9 6L144 408.1c-1.4 4.7 1.3 9.6 6 10.9l24.4 7.1c4.7 1.4 9.6-1.4 10.9-6L240 231.9c1.4-4.7-1.3-9.6-6-10.9zm24.5 76.9l.2.2 32.8 28.9-32.8 28.9c-3.6 3.2-4 8.8-.8 12.4l.2.2 17.4 18.6c3.3 3.5 8.9 3.7 12.4.4l57.7-54.1c3.7-3.5 3.7-9.4 0-12.8l-57.7-54.1c-3.5-3.3-9.1-3.2-12.4.4l-17.4 18.6c-3.3 3.5-3.1 9.1.4 12.4z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm212-240h-28.8c-4.4 0-8.4 2.4-10.5 6.3-18 33.1-22.2 42.4-28.6 57.7-13.9-29.1-6.9-17.3-28.6-57.7-2.1-3.9-6.2-6.3-10.6-6.3H124c-9.3 0-15 10-10.4 18l46.3 78-46.3 78c-4.7 8 1.1 18 10.4 18h28.9c4.4 0 8.4-2.4 10.5-6.3 21.7-40 23-45 28.6-57.7 14.9 30.2 5.9 15.9 28.6 57.7 2.1 3.9 6.2 6.3 10.6 6.3H260c9.3 0 15-10 10.4-18L224 320c.7-1.1 30.3-50.5 46.3-78 4.7-8-1.1-18-10.3-18z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm32-48h224V288l-23.5-23.5c-4.7-4.7-12.3-4.7-17 0L176 352l-39.5-39.5c-4.7-4.7-12.3-4.7-17 0L80 352v64zm48-240c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm250.2-143.7c-12.2-12-47-8.7-64.4-6.5-17.2-10.5-28.7-25-36.8-46.3 3.9-16.1 10.1-40.6 5.4-56-4.2-26.2-37.8-23.6-42.6-5.9-4.4 16.1-.4 38.5 7 67.1-10 23.9-24.9 56-35.4 74.4-20 10.3-47 26.2-51 46.2-3.3 15.8 26 55.2 76.1-31.2 22.4-7.4 46.8-16.5 68.4-20.1 18.9 10.2 41 17 55.8 17 25.5 0 28-28.2 17.5-38.7zm-198.1 77.8c5.1-13.7 24.5-29.5 30.4-35-19 30.3-30.4 35.7-30.4 35zm81.6-190.6c7.4 0 6.7 32.1 1.8 40.8-4.4-13.9-4.3-40.8-1.8-40.8zm-24.4 136.6c9.7-16.9 18-37 24.7-54.7 8.3 15.1 18.9 27.2 30.1 35.5-20.8 4.3-38.9 13.1-54.8 19.2zm131.6-5s-5 6-37.3-7.8c35.1-2.6 40.9 5.4 37.3 7.8z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm72-60V236c0-6.6 5.4-12 12-12h69.2c36.7 0 62.8 27 62.8 66.3 0 74.3-68.7 66.5-95.5 66.5V404c0 6.6-5.4 12-12 12H132c-6.6 0-12-5.4-12-12zm48.5-87.4h23c7.9 0 13.9-2.4 18.1-7.2 8.5-9.8 8.4-28.5.1-37.8-4.1-4.6-9.9-7-17.4-7h-23.9v52z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M369.941 97.941l-83.882-83.882A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v416c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48V131.882a48 48 0 0 0-14.059-33.941zM332.118 128H256V51.882L332.118 128zM48 464V48h160v104c0 13.255 10.745 24 24 24h104v288H48zm228.687-211.303L224 305.374V268c0-11.046-8.954-20-20-20H100c-11.046 0-20 8.954-20 20v104c0 11.046 8.954 20 20 20h104c11.046 0 20-8.954 20-20v-37.374l52.687 52.674C286.704 397.318 304 390.28 304 375.986V264.011c0-14.311-17.309-21.319-27.313-11.314z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M369.9 97.9L286 14C277 5 264.8-.1 252.1-.1H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V131.9c0-12.7-5.1-25-14.1-34zM332.1 128H256V51.9l76.1 76.1zM48 464V48h160v104c0 13.3 10.7 24 24 24h104v288H48zm220.1-208c-5.7 0-10.6 4-11.7 9.5-20.6 97.7-20.4 95.4-21 103.5-.2-1.2-.4-2.6-.7-4.3-.8-5.1.3.2-23.6-99.5-1.3-5.4-6.1-9.2-11.7-9.2h-13.3c-5.5 0-10.3 3.8-11.7 9.1-24.4 99-24 96.2-24.8 103.7-.1-1.1-.2-2.5-.5-4.2-.7-5.2-14.1-73.3-19.1-99-1.1-5.6-6-9.7-11.8-9.7h-16.8c-7.8 0-13.5 7.3-11.7 14.8 8 32.6 26.7 109.5 33.2 136 1.3 5.4 6.1 9.1 11.7 9.1h25.2c5.5 0 10.3-3.7 11.6-9.1l17.9-71.4c1.5-6.2 2.5-12 3-17.3l2.9 17.3c.1.4 12.6 50.5 17.9 71.4 1.3 5.3 6.1 9.1 11.6 9.1h24.7c5.5 0 10.3-3.7 11.6-9.1 20.8-81.9 30.2-119 34.5-136 1.9-7.6-3.8-14.9-11.6-14.9h-15.8z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M336.174 80c-49.132 0-93.305-32-161.913-32-31.301 0-58.303 6.482-80.721 15.168a48.04 48.04 0 0 0 2.142-20.727C93.067 19.575 74.167 1.594 51.201.104 23.242-1.71 0 20.431 0 48c0 17.764 9.657 33.262 24 41.562V496c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-83.443C109.869 395.28 143.259 384 199.826 384c49.132 0 93.305 32 161.913 32 58.479 0 101.972-22.617 128.548-39.981C503.846 367.161 512 352.051 512 335.855V95.937c0-34.459-35.264-57.768-66.904-44.117C409.193 67.309 371.641 80 336.174 80zM464 336c-21.783 15.412-60.824 32-102.261 32-59.945 0-102.002-32-161.913-32-43.361 0-96.379 9.403-127.826 24V128c21.784-15.412 60.824-32 102.261-32 59.945 0 102.002 32 161.913 32 43.271 0 96.32-17.366 127.826-32v240z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm96-312c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-112 24c0-44.2-35.8-80-80-80s-80 35.8-80 80 35.8 80 80 80 80-35.8 80-80zm-80 48c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm160 144H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-54.63-54.63c-6-6-14.14-9.37-22.63-9.37H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm0 272H48V112h140.12l54.63 54.63c6 6 14.14 9.37 22.63 9.37H464v224z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M527.9 224H480v-48c0-26.5-21.5-48-48-48H272l-64-64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h400c16.5 0 31.9-8.5 40.7-22.6l79.9-128c20-31.9-3-73.4-40.7-73.4zM48 118c0-3.3 2.7-6 6-6h134.1l64 64H426c3.3 0 6 2.7 6 6v42H152c-16.8 0-32.4 8.8-41.1 23.2L48 351.4zm400 282H72l77.2-128H528z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 128c-40.2 0-78 17.7-103.8 48.6-8.5 10.2-7.1 25.3 3.1 33.8 10.2 8.4 25.3 7.1 33.8-3.1 16.6-19.9 41-31.4 66.9-31.4s50.3 11.4 66.9 31.4c8.1 9.7 23.1 11.9 33.8 3.1 10.2-8.5 11.5-23.6 3.1-33.8C326 321.7 288.2 304 248 304z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-48-248c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-80 112c-35.6 0-88.8 21.3-95.8 61.2-2 11.8 9 21.5 20.5 18.1 31.2-9.6 59.4-15.3 75.3-15.3s44.1 5.7 75.3 15.3c11.4 3.5 22.5-6.3 20.5-18.1-7-39.9-60.2-61.2-95.8-61.2z\"],\n    \"futbol\": [496, 512, [], \"f1e3\", \"M483.8 179.4C449.8 74.6 352.6 8 248.1 8c-25.4 0-51.2 3.9-76.7 12.2C41.2 62.5-30.1 202.4 12.2 332.6 46.2 437.4 143.4 504 247.9 504c25.4 0 51.2-3.9 76.7-12.2 130.2-42.3 201.5-182.2 159.2-312.4zm-74.5 193.7l-52.2 6.4-43.7-60.9 24.4-75.2 71.1-22.1 38.9 36.4c-.2 30.7-7.4 61.1-21.7 89.2-4.7 9.3-10.7 17.8-16.8 26.2zm0-235.4l-10.4 53.1-70.7 22-64.2-46.5V92.5l47.4-26.2c39.2 13 73.4 38 97.9 71.4zM184.9 66.4L232 92.5v73.8l-64.2 46.5-70.6-22-10.1-52.5c24.3-33.4 57.9-58.6 97.8-71.9zM139 379.5L85.9 373c-14.4-20.1-37.3-59.6-37.8-115.3l39-36.4 71.1 22.2 24.3 74.3-43.5 61.7zm48.2 67l-22.4-48.1 43.6-61.7H287l44.3 61.7-22.4 48.1c-6.2 1.8-57.6 20.4-121.7 0z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M464 0H112c-4 0-7.8 2-10 5.4L2 152.6c-2.9 4.4-2.6 10.2.7 14.2l276 340.8c4.8 5.9 13.8 5.9 18.6 0l276-340.8c3.3-4.1 3.6-9.8.7-14.2L474.1 5.4C471.8 2 468.1 0 464 0zm-19.3 48l63.3 96h-68.4l-51.7-96h56.8zm-202.1 0h90.7l51.7 96H191l51.6-96zm-111.3 0h56.8l-51.7 96H68l63.3-96zm-43 144h51.4L208 352 88.3 192zm102.9 0h193.6L288 435.3 191.2 192zM368 352l68.2-160h51.4L368 352z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm16 16H152c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h192c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48zm-168 96h-24c-8.8 0-16-7.2-16-16v-8h40v24zm0-40h-40v-8c0-8.8 7.2-16 16-16h24v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm64 40h-48v-24h48v24zm0-40h-48v-24h48v24zm56 24c0 8.8-7.2 16-16 16h-24v-24h40v8zm0-24h-40v-24h24c8.8 0 16 7.2 16 16v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M200.3 248c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zm128 0c12.4-18.7 15.1-37.3 15.7-56-.5-18.7-3.3-37.3-15.7-56-8-12-25.1-11.4-32.7 0-12.4 18.7-15.1 37.3-15.7 56 .5 18.7 3.3 37.3 15.7 56 8.1 12 25.2 11.4 32.7 0zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-235.9-72.9c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3zm160 0c3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3z\"],\n    \"grin-beam-sweat\": [496, 512, [], \"f583\", \"M440 160c29.5 0 53.3-26.3 53.3-58.7 0-25-31.7-75.5-46.2-97.3-3.6-5.3-10.7-5.3-14.2 0-14.5 21.8-46.2 72.3-46.2 97.3 0 32.4 23.8 58.7 53.3 58.7zM248 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zm105.3-52.9c-24.6 15.7-46 12.9-46.4 12.9 6.9 20.2 10.8 41.8 10.8 64.3 0 110.3-89.7 200-200 200S48 366.3 48 256 137.7 56 248 56c39.8 0 76.8 11.8 108 31.9 1.7-9.5 6.3-24.1 17.2-45.7C336.4 20.6 293.7 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-27-4.4-52.9-12.4-77.2zM168 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M353.6 304.6c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-152.8-48.9c4.5 1.2 9.2-1.5 10.5-6l19.4-69.9c5.6-20.3-7.4-41.1-28.8-44.5-18.6-3-36.4 9.8-41.5 27.9l-2 7.1-7.1-1.9c-18.2-4.7-38.2 4.3-44.9 22-7.7 20.2 3.8 41.9 24.2 47.2l70.2 18.1zm188.8-65.3c-6.7-17.6-26.7-26.7-44.9-22l-7.1 1.9-2-7.1c-5-18.1-22.8-30.9-41.5-27.9-21.4 3.4-34.4 24.2-28.8 44.5l19.4 69.9c1.2 4.5 5.9 7.2 10.5 6l70.2-18.2c20.4-5.3 31.9-26.9 24.2-47.1zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.4-17.7 15.3 7.9 47.1 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-234.7-40.8c3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3l-80-48c-5.1-3-11.4-1.9-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11.1.1 15.5zm242.9 2.5c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11-.1-15.5-3.8-4.4-10.2-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M117.1 384.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 479 124.3 420.8 128 395c.8-6.4-4.6-11.8-10.9-10.9zm-41.2-41.7C40.3 268 53 176.1 114.6 114.6 152.4 76.8 202.6 56 256 56c36.2 0 70.8 9.8 101.2 27.7 3.8-20.3 8-36.1 12-48.3C333.8 17.2 294.9 8 256 8 192.5 8 129.1 32.2 80.6 80.6c-74.1 74.1-91.3 183.4-52 274 12.2-4.1 27.7-8.3 47.3-12.2zm352.3-187.6c45 76.6 34.9 176.9-30.8 242.6-37.8 37.8-88 58.6-141.4 58.6-30.5 0-59.8-7-86.4-19.8-3.9 19.5-8 35-12.2 47.2 31.4 13.6 65 20.6 98.7 20.6 63.5 0 126.9-24.2 175.4-72.6 78.1-78.1 93.1-195.4 45.2-288.6-12.3 4-28.2 8.1-48.5 12zm-33.3-26.9c25.8-3.7 84-13.7 100.9-30.6 21.9-21.9 21.5-57.9-.9-80.3s-58.3-22.8-80.3-.9C397.7 33 387.7 91.2 384 117c-.8 6.4 4.6 11.8 10.9 10.9zm-187 108.3c-3-3-7.2-4.2-11.4-3.2L106 255.7c-5.7 1.4-9.5 6.7-9.1 12.6.5 5.8 5.1 10.5 10.9 11l52.3 4.8 4.8 52.3c.5 5.8 5.2 10.4 11 10.9h.9c5.5 0 10.3-3.7 11.7-9.1l22.6-90.5c1-4.2-.2-8.5-3.2-11.5zm39.7-25.1l90.5-22.6c5.7-1.4 9.5-6.7 9.1-12.6-.5-5.8-5.1-10.5-10.9-11l-52.3-4.8-4.8-52.3c-.5-5.8-5.2-10.4-11-10.9-5.6-.1-11.2 3.4-12.6 9.1L233 196.5c-1 4.1.2 8.4 3.2 11.4 5 5 11.3 3.2 11.4 3.2zm52 88.5c-29.1 29.1-59.7 52.9-83.9 65.4-9.2 4.8-10 17.5-1.7 23.4 38.9 27.7 107 6.2 143.7-30.6S416 253 388.3 214.1c-5.8-8.2-18.5-7.6-23.4 1.7-12.3 24.2-36.2 54.7-65.3 83.8z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm105.6-151.4c-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 7.9 47.2 71.3 80 123.3 80s115.3-32.9 123.3-80c1.6-9.8-7.7-18.4-17.7-15.3zm-227.9-57.5c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.5 1.9-12.2-4.3-13.2l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6.1 34.9zm259.7-72.7l-34.9-5-15.5-31.6c-2.9-5.8-11-5.8-13.9 0l-15.5 31.6-34.9 5c-6.2.9-8.9 8.6-4.3 13.2l25.4 24.6-6 34.9c-1 6.2 5.4 11 11 7.9l31.3-16.3 31.3 16.3c5.6 3.1 12-1.7 11-7.9l-6-34.9 25.4-24.6c4.5-4.6 1.8-12.2-4.4-13.2z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M117.1 256.1c-25.8 3.7-84 13.7-100.9 30.6-21.9 21.9-21.5 57.9.9 80.3s58.3 22.8 80.3.9C114.3 351 124.3 292.8 128 267c.8-6.4-4.6-11.8-10.9-10.9zm506.7 30.6c-16.9-16.9-75.1-26.9-100.9-30.6-6.3-.9-11.7 4.5-10.8 10.8 3.7 25.8 13.7 84 30.6 100.9 21.9 21.9 57.9 21.5 80.3-.9 22.3-22.3 22.7-58.3.8-80.2zm-126.6 61.7C463.8 412.3 396.9 456 320 456c-76.9 0-143.8-43.7-177.2-107.6-12.5 37.4-25.2 43.9-28.3 46.5C159.1 460.7 234.5 504 320 504s160.9-43.3 205.5-109.1c-3.2-2.7-15.9-9.2-28.3-46.5zM122.7 224.5C137.9 129.2 220.5 56 320 56c99.5 0 182.1 73.2 197.3 168.5 2.1-.2 5.2-2.4 49.5 7C554.4 106 448.7 8 320 8S85.6 106 73.2 231.4c44.5-9.4 47.1-7.2 49.5-6.9zM320 400c51.9 0 115.3-32.9 123.3-80 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.8-3.1-19.4 5.3-17.7 15.3 8 47.1 71.4 80 123.3 80zm130.3-168.3c3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.6 6.2 4.6 9.3 3.7zM240 189.4c12.3 0 23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.8 19.2-21.6 31.5-21.6z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zM168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3zm36.9-281.1c-3.8-4.4-10.3-5.5-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.7 1.7 15.3-2.5 3.8-4.5 3.8-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zm-162.9 45.5l-80-48c-5-3-11.4-2-15.3 2.5-3.8 4.5-3.8 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.6 4.2 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3s-2.2-8.1-5.8-10.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M152 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm176-52c-44.2 0-80 35.8-80 80s35.8 80 80 80 80-35.8 80-80-35.8-80-80-80zm0 128c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-72c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm64 400c0 35.6-29.1 64.5-64.9 64-35.1-.5-63.1-29.8-63.1-65v-42.8l17.7-8.8c15-7.5 31.5 1.7 34.9 16.5l2.8 12.1c2.1 9.2 15.2 9.2 17.3 0l2.8-12.1c3.4-14.8 19.8-24.1 34.9-16.5l17.7 8.8V408zm28.2 25.3c2.2-8.1 3.8-16.5 3.8-25.3v-43.5c14.2-12.4 24.4-27.5 27.3-44.5 1.7-9.9-7.7-18.5-17.7-15.3-25.9 8.3-64.4 13.1-105.6 13.1s-79.6-4.8-105.6-13.1c-9.9-3.1-19.4 5.3-17.7 15.3 2.9 17 13.1 32.1 27.3 44.5V408c0 8.8 1.6 17.2 3.8 25.3C91.8 399.9 48 333 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 77-43.8 143.9-107.8 177.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M328 180c-25.69 0-55.88 16.92-59.86 42.12-1.75 11.22 11.5 18.24 19.83 10.84l9.55-8.48c14.81-13.19 46.16-13.19 60.97 0l9.55 8.48c8.48 7.43 21.56.25 19.83-10.84C383.88 196.92 353.69 180 328 180zm-160 60c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm185.55 64.64c-25.93 8.3-64.4 13.06-105.55 13.06s-79.62-4.75-105.55-13.06c-9.94-3.13-19.4 5.37-17.71 15.34C132.67 367.13 196.06 400 248 400s115.33-32.87 123.26-80.02c1.68-9.89-7.67-18.48-17.71-15.34zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 448c-110.28 0-200-89.72-200-200S137.72 56 248 56s200 89.72 200 200-89.72 200-200 200z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M556.686 290.542L410.328 64.829C397.001 44.272 374.417 32 349.917 32H56C25.121 32 0 57.122 0 88v8c0 44.112 35.888 80 80 80h196.042l-18.333 48H144c-48.523 0-88 39.477-88 88 0 30.879 25.121 56 56 56h131.552c2.987 0 5.914.549 8.697 1.631L352 408.418V480h224V355.829c0-23.225-6.679-45.801-19.314-65.287zM528 432H400v-23.582c0-19.948-12.014-37.508-30.604-44.736l-99.751-38.788A71.733 71.733 0 0 0 243.552 320H112c-4.411 0-8-3.589-8-8 0-22.056 17.944-40 40-40h113.709c19.767 0 37.786-12.407 44.84-30.873l24.552-64.281c8.996-23.553-8.428-48.846-33.63-48.846H80c-17.645 0-32-14.355-32-32v-8c0-4.411 3.589-8 8-8h293.917c8.166 0 15.693 4.09 20.137 10.942l146.358 225.715A71.84 71.84 0 0 1 528 355.829V432z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M372.57 112.641v-10.825c0-43.612-40.52-76.691-83.039-65.546-25.629-49.5-94.09-47.45-117.982.747C130.269 26.456 89.144 57.945 89.144 102v126.13c-19.953-7.427-43.308-5.068-62.083 8.871-29.355 21.796-35.794 63.333-14.55 93.153L132.48 498.569a32 32 0 0 0 26.062 13.432h222.897c14.904 0 27.835-10.289 31.182-24.813l30.184-130.958A203.637 203.637 0 0 0 448 310.564V179c0-40.62-35.523-71.992-75.43-66.359zm27.427 197.922c0 11.731-1.334 23.469-3.965 34.886L368.707 464h-201.92L51.591 302.303c-14.439-20.27 15.023-42.776 29.394-22.605l27.128 38.079c8.995 12.626 29.031 6.287 29.031-9.283V102c0-25.645 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V67c0-25.663 36.571-24.81 36.571.691V256c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16V101.125c0-25.672 36.57-24.81 36.57.691V256c0 8.837 7.163 16 16 16h6.857c8.837 0 16-7.163 16-16v-76.309c0-26.242 36.57-25.64 36.57-.691v131.563z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M362.146 191.976c-13.71-21.649-38.761-34.016-65.006-30.341V74c0-40.804-32.811-74-73.141-74-40.33 0-73.14 33.196-73.14 74L160 168l-18.679-78.85C126.578 50.843 83.85 32.11 46.209 47.208 8.735 62.238-9.571 104.963 5.008 142.85l55.757 144.927c-30.557 24.956-43.994 57.809-24.733 92.218l54.853 97.999C102.625 498.97 124.73 512 148.575 512h205.702c30.744 0 57.558-21.44 64.555-51.797l27.427-118.999a67.801 67.801 0 0 0 1.729-15.203L448 256c0-44.956-43.263-77.343-85.854-64.024zM399.987 326c0 1.488-.169 2.977-.502 4.423l-27.427 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H148.575c-6.486 0-12.542-3.621-15.805-9.449l-54.854-98c-4.557-8.141-2.619-18.668 4.508-24.488l26.647-21.764a16 16 0 0 0 4.812-18.139l-64.09-166.549C37.226 92.956 84.37 74.837 96.51 106.389l59.784 155.357A16 16 0 0 0 171.227 272h11.632c8.837 0 16-7.163 16-16V74c0-34.375 50.281-34.43 50.281 0v182c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16v-28c0-25.122 36.567-25.159 36.567 0v28c0 8.837 7.163 16 16 16h6.856c8.837 0 16-7.163 16-16 0-25.12 36.567-25.16 36.567 0v70z\"],\n    \"hand-point-down\": [448, 512, [], \"f0a7\", \"M188.8 512c45.616 0 83.2-37.765 83.2-83.2v-35.647a93.148 93.148 0 0 0 22.064-7.929c22.006 2.507 44.978-3.503 62.791-15.985C409.342 368.1 448 331.841 448 269.299V248c0-60.063-40-98.512-40-127.2v-2.679c4.952-5.747 8-13.536 8-22.12V32c0-17.673-12.894-32-28.8-32H156.8C140.894 0 128 14.327 128 32v64c0 8.584 3.048 16.373 8 22.12v2.679c0 6.964-6.193 14.862-23.668 30.183l-.148.129-.146.131c-9.937 8.856-20.841 18.116-33.253 25.851C48.537 195.798 0 207.486 0 252.8c0 56.928 35.286 92 83.2 92 8.026 0 15.489-.814 22.4-2.176V428.8c0 45.099 38.101 83.2 83.2 83.2zm0-48c-18.7 0-35.2-16.775-35.2-35.2V270.4c-17.325 0-35.2 26.4-70.4 26.4-26.4 0-35.2-20.625-35.2-44 0-8.794 32.712-20.445 56.1-34.926 14.575-9.074 27.225-19.524 39.875-30.799 18.374-16.109 36.633-33.836 39.596-59.075h176.752C364.087 170.79 400 202.509 400 248v21.299c0 40.524-22.197 57.124-61.325 50.601-8.001 14.612-33.979 24.151-53.625 12.925-18.225 19.365-46.381 17.787-61.05 4.95V428.8c0 18.975-16.225 35.2-35.2 35.2zM328 64c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M0 220.8C0 266.416 37.765 304 83.2 304h35.647a93.148 93.148 0 0 0 7.929 22.064c-2.507 22.006 3.503 44.978 15.985 62.791C143.9 441.342 180.159 480 242.701 480H264c60.063 0 98.512-40 127.2-40h2.679c5.747 4.952 13.536 8 22.12 8h64c17.673 0 32-12.894 32-28.8V188.8c0-15.906-14.327-28.8-32-28.8h-64c-8.584 0-16.373 3.048-22.12 8H391.2c-6.964 0-14.862-6.193-30.183-23.668l-.129-.148-.131-.146c-8.856-9.937-18.116-20.841-25.851-33.253C316.202 80.537 304.514 32 259.2 32c-56.928 0-92 35.286-92 83.2 0 8.026.814 15.489 2.176 22.4H83.2C38.101 137.6 0 175.701 0 220.8zm48 0c0-18.7 16.775-35.2 35.2-35.2h158.4c0-17.325-26.4-35.2-26.4-70.4 0-26.4 20.625-35.2 44-35.2 8.794 0 20.445 32.712 34.926 56.1 9.074 14.575 19.524 27.225 30.799 39.875 16.109 18.374 33.836 36.633 59.075 39.596v176.752C341.21 396.087 309.491 432 264 432h-21.299c-40.524 0-57.124-22.197-50.601-61.325-14.612-8.001-24.151-33.979-12.925-53.625-19.365-18.225-17.787-46.381-4.95-61.05H83.2C64.225 256 48 239.775 48 220.8zM448 360c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M428.8 137.6h-86.177a115.52 115.52 0 0 0 2.176-22.4c0-47.914-35.072-83.2-92-83.2-45.314 0-57.002 48.537-75.707 78.784-7.735 12.413-16.994 23.317-25.851 33.253l-.131.146-.129.148C135.662 161.807 127.764 168 120.8 168h-2.679c-5.747-4.952-13.536-8-22.12-8H32c-17.673 0-32 12.894-32 28.8v230.4C0 435.106 14.327 448 32 448h64c8.584 0 16.373-3.048 22.12-8h2.679c28.688 0 67.137 40 127.2 40h21.299c62.542 0 98.8-38.658 99.94-91.145 12.482-17.813 18.491-40.785 15.985-62.791A93.148 93.148 0 0 0 393.152 304H428.8c45.435 0 83.2-37.584 83.2-83.2 0-45.099-38.101-83.2-83.2-83.2zm0 118.4h-91.026c12.837 14.669 14.415 42.825-4.95 61.05 11.227 19.646 1.687 45.624-12.925 53.625 6.524 39.128-10.076 61.325-50.6 61.325H248c-45.491 0-77.21-35.913-120-39.676V215.571c25.239-2.964 42.966-21.222 59.075-39.596 11.275-12.65 21.725-25.3 30.799-39.875C232.355 112.712 244.006 80 252.8 80c23.375 0 44 8.8 44 35.2 0 35.2-26.4 53.075-26.4 70.4h158.4c18.425 0 35.2 16.5 35.2 35.2 0 18.975-16.225 35.2-35.2 35.2zM88 384c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"hand-point-up\": [448, 512, [], \"f0a6\", \"M105.6 83.2v86.177a115.52 115.52 0 0 0-22.4-2.176c-47.914 0-83.2 35.072-83.2 92 0 45.314 48.537 57.002 78.784 75.707 12.413 7.735 23.317 16.994 33.253 25.851l.146.131.148.129C129.807 376.338 136 384.236 136 391.2v2.679c-4.952 5.747-8 13.536-8 22.12v64c0 17.673 12.894 32 28.8 32h230.4c15.906 0 28.8-14.327 28.8-32v-64c0-8.584-3.048-16.373-8-22.12V391.2c0-28.688 40-67.137 40-127.2v-21.299c0-62.542-38.658-98.8-91.145-99.94-17.813-12.482-40.785-18.491-62.791-15.985A93.148 93.148 0 0 0 272 118.847V83.2C272 37.765 234.416 0 188.8 0c-45.099 0-83.2 38.101-83.2 83.2zm118.4 0v91.026c14.669-12.837 42.825-14.415 61.05 4.95 19.646-11.227 45.624-1.687 53.625 12.925 39.128-6.524 61.325 10.076 61.325 50.6V264c0 45.491-35.913 77.21-39.676 120H183.571c-2.964-25.239-21.222-42.966-39.596-59.075-12.65-11.275-25.3-21.725-39.875-30.799C80.712 279.645 48 267.994 48 259.2c0-23.375 8.8-44 35.2-44 35.2 0 53.075 26.4 70.4 26.4V83.2c0-18.425 16.5-35.2 35.2-35.2 18.975 0 35.2 16.225 35.2 35.2zM352 424c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M358.182 179.361c-19.493-24.768-52.679-31.945-79.872-19.098-15.127-15.687-36.182-22.487-56.595-19.629V67c0-36.944-29.736-67-66.286-67S89.143 30.056 89.143 67v161.129c-19.909-7.41-43.272-5.094-62.083 8.872-29.355 21.795-35.793 63.333-14.55 93.152l109.699 154.001C134.632 501.59 154.741 512 176 512h178.286c30.802 0 57.574-21.5 64.557-51.797l27.429-118.999A67.873 67.873 0 0 0 448 326v-84c0-46.844-46.625-79.273-89.818-62.639zM80.985 279.697l27.126 38.079c8.995 12.626 29.031 6.287 29.031-9.283V67c0-25.12 36.571-25.16 36.571 0v175c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16v-35c0-25.12 36.571-25.16 36.571 0v35c0 8.836 7.163 16 16 16H272c8.837 0 16-7.164 16-16v-21c0-25.12 36.571-25.16 36.571 0v21c0 8.836 7.163 16 16 16h6.857c8.837 0 16-7.164 16-16 0-25.121 36.571-25.16 36.571 0v84c0 1.488-.169 2.977-.502 4.423l-27.43 119.001c-1.978 8.582-9.29 14.576-17.782 14.576H176c-5.769 0-11.263-2.878-14.697-7.697l-109.712-154c-14.406-20.223 14.994-42.818 29.394-22.606zM176.143 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.733 0-14-7.163-14-16zm75.428 0v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16zM327 400v-96c0-8.837 6.268-16 14-16h6c7.732 0 14 7.163 14 16v96c0 8.837-6.268 16-14 16h-6c-7.732 0-14-7.163-14-16z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M408.864 79.052c-22.401-33.898-66.108-42.273-98.813-23.588-29.474-31.469-79.145-31.093-108.334-.022-47.16-27.02-108.71 5.055-110.671 60.806C44.846 105.407 0 140.001 0 187.429v56.953c0 32.741 14.28 63.954 39.18 85.634l97.71 85.081c4.252 3.702 3.11 5.573 3.11 32.903 0 17.673 14.327 32 32 32h252c17.673 0 32-14.327 32-32 0-23.513-1.015-30.745 3.982-42.37l42.835-99.656c6.094-14.177 9.183-29.172 9.183-44.568V146.963c0-52.839-54.314-88.662-103.136-67.911zM464 261.406a64.505 64.505 0 0 1-5.282 25.613l-42.835 99.655c-5.23 12.171-7.883 25.04-7.883 38.25V432H188v-10.286c0-16.37-7.14-31.977-19.59-42.817l-97.71-85.08C56.274 281.255 48 263.236 48 244.381v-56.953c0-33.208 52-33.537 52 .677v41.228a16 16 0 0 0 5.493 12.067l7 6.095A16 16 0 0 0 139 235.429V118.857c0-33.097 52-33.725 52 .677v26.751c0 8.836 7.164 16 16 16h7c8.836 0 16-7.164 16-16v-41.143c0-33.134 52-33.675 52 .677v40.466c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16v-27.429c0-33.03 52-33.78 52 .677v26.751c0 8.836 7.163 16 16 16h7c8.837 0 16-7.164 16-16 0-33.146 52-33.613 52 .677v114.445z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M256 480l70-.013c5.114 0 10.231-.583 15.203-1.729l118.999-27.427C490.56 443.835 512 417.02 512 386.277V180.575c0-23.845-13.03-45.951-34.005-57.69l-97.999-54.853c-34.409-19.261-67.263-5.824-92.218 24.733L142.85 37.008c-37.887-14.579-80.612 3.727-95.642 41.201-15.098 37.642 3.635 80.37 41.942 95.112L168 192l-94-9.141c-40.804 0-74 32.811-74 73.14 0 40.33 33.196 73.141 74 73.141h87.635c-3.675 26.245 8.692 51.297 30.341 65.006C178.657 436.737 211.044 480 256 480zm0-48.013c-25.16 0-25.12-36.567 0-36.567 8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16h-28c-25.159 0-25.122-36.567 0-36.567h28c8.837 0 16-7.163 16-16v-6.856c0-8.837-7.163-16-16-16H74c-34.43 0-34.375-50.281 0-50.281h182c8.837 0 16-7.163 16-16v-11.632a16 16 0 0 0-10.254-14.933L106.389 128.51c-31.552-12.14-13.432-59.283 19.222-46.717l166.549 64.091a16.001 16.001 0 0 0 18.139-4.812l21.764-26.647c5.82-7.127 16.348-9.064 24.488-4.508l98 54.854c5.828 3.263 9.449 9.318 9.449 15.805v205.701c0 8.491-5.994 15.804-14.576 17.782l-119.001 27.427a19.743 19.743 0 0 1-4.423.502h-70z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M21.096 381.79l129.092 121.513a32 32 0 0 0 21.932 8.698h237.6c14.17 0 26.653-9.319 30.68-22.904l31.815-107.313A115.955 115.955 0 0 0 477 348.811v-36.839c0-4.051.476-8.104 1.414-12.045l31.73-133.41c10.099-42.412-22.316-82.738-65.544-82.525-4.144-24.856-22.543-47.165-49.85-53.992-35.803-8.952-72.227 12.655-81.25 48.75L296.599 184 274.924 52.01c-8.286-36.07-44.303-58.572-80.304-50.296-29.616 6.804-50.138 32.389-51.882 61.295-42.637.831-73.455 40.563-64.071 81.844l31.04 136.508c-27.194-22.515-67.284-19.992-91.482 5.722-25.376 26.961-24.098 69.325 2.871 94.707zm32.068-61.811l.002-.001c7.219-7.672 19.241-7.98 26.856-.813l53.012 49.894C143.225 378.649 160 371.4 160 357.406v-69.479c0-1.193-.134-2.383-.397-3.546l-34.13-150.172c-5.596-24.617 31.502-32.86 37.054-8.421l30.399 133.757a16 16 0 0 0 15.603 12.454h8.604c10.276 0 17.894-9.567 15.594-19.583l-41.62-181.153c-5.623-24.469 31.39-33.076 37.035-8.508l45.22 196.828A16 16 0 0 0 288.956 272h13.217a16 16 0 0 0 15.522-12.119l42.372-169.49c6.104-24.422 42.962-15.159 36.865 9.217L358.805 252.12c-2.521 10.088 5.115 19.88 15.522 19.88h9.694a16 16 0 0 0 15.565-12.295L426.509 146.6c5.821-24.448 42.797-15.687 36.966 8.802L431.72 288.81a100.094 100.094 0 0 0-2.72 23.162v36.839c0 6.548-.943 13.051-2.805 19.328L397.775 464h-219.31L53.978 346.836c-7.629-7.18-7.994-19.229-.814-26.857z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M519.2 127.9l-47.6-47.6A56.252 56.252 0 0 0 432 64H205.2c-14.8 0-29.1 5.9-39.6 16.3L118 127.9H0v255.7h64c17.6 0 31.8-14.2 31.9-31.7h9.1l84.6 76.4c30.9 25.1 73.8 25.7 105.6 3.8 12.5 10.8 26 15.9 41.1 15.9 18.2 0 35.3-7.4 48.8-24 22.1 8.7 48.2 2.6 64-16.8l26.2-32.3c5.6-6.9 9.1-14.8 10.9-23h57.9c.1 17.5 14.4 31.7 31.9 31.7h64V127.9H519.2zM48 351.6c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16zm390-6.9l-26.1 32.2c-2.8 3.4-7.8 4-11.3 1.2l-23.9-19.4-30 36.5c-6 7.3-15 4.8-18 2.4l-36.8-31.5-15.6 19.2c-13.9 17.1-39.2 19.7-55.3 6.6l-97.3-88H96V175.8h41.9l61.7-61.6c2-.8 3.7-1.5 5.7-2.3H262l-38.7 35.5c-29.4 26.9-31.1 72.3-4.4 101.3 14.8 16.2 61.2 41.2 101.5 4.4l8.2-7.5 108.2 87.8c3.4 2.8 3.9 7.9 1.2 11.3zm106-40.8h-69.2c-2.3-2.8-4.9-5.4-7.7-7.7l-102.7-83.4 12.5-11.4c6.5-6 7-16.1 1-22.6L367 167.1c-6-6.5-16.1-6.9-22.6-1l-55.2 50.6c-9.5 8.7-25.7 9.4-34.6 0-9.3-9.9-8.5-25.1 1.2-33.9l65.6-60.1c7.4-6.8 17-10.5 27-10.5l83.7-.2c2.1 0 4.1.8 5.5 2.3l61.7 61.6H544v128zm48 47.7c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16c0 8.9-7.2 16-16 16z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M567.403 235.642L462.323 84.589A48 48 0 0 0 422.919 64H153.081a48 48 0 0 0-39.404 20.589L8.597 235.642A48.001 48.001 0 0 0 0 263.054V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V263.054c0-9.801-3-19.366-8.597-27.412zM153.081 112h269.838l77.913 112H75.168l77.913-112zM528 400H48V272h480v128zm-32-64c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32zm-96 0c0 17.673-14.327 32-32 32s-32-14.327-32-32 14.327-32 32-32 32 14.327 32 32z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M458.4 64.3C400.6 15.7 311.3 23 256 79.3 200.7 23 111.4 15.6 53.6 64.3-21.6 127.6-10.6 230.8 43 285.5l175.4 178.7c10 10.2 23.4 15.9 37.6 15.9 14.3 0 27.6-5.6 37.6-15.8L469 285.6c53.5-54.7 64.7-157.9-10.6-221.3zm-23.6 187.5L259.4 430.5c-2.4 2.4-4.4 2.4-6.8 0L77.2 251.8c-36.5-37.2-43.9-107.6 7.3-150.7 38.9-32.7 98.9-27.8 136.5 10.5l35 35.7 35-35.7c37.8-38.5 97.8-43.2 136.5-10.6 51.1 43.1 43.5 113.9 7.3 150.8z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M128 244v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12zm140 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm-76 84v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm76 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm180 124v36H0v-36c0-6.627 5.373-12 12-12h19.5V85.035C31.5 73.418 42.245 64 55.5 64H144V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v40h88.5c13.255 0 24 9.418 24 21.035V464H436c6.627 0 12 5.373 12 12zM79.5 463H192v-67c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v67h112.5V112H304v24c0 13.255-10.745 24-24 24H168c-13.255 0-24-10.745-24-24v-24H79.5v351zM266 64h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M368 48h4c6.627 0 12-5.373 12-12V12c0-6.627-5.373-12-12-12H12C5.373 0 0 5.373 0 12v24c0 6.627 5.373 12 12 12h4c0 80.564 32.188 165.807 97.18 208C47.899 298.381 16 383.9 16 464h-4c-6.627 0-12 5.373-12 12v24c0 6.627 5.373 12 12 12h360c6.627 0 12-5.373 12-12v-24c0-6.627-5.373-12-12-12h-4c0-80.564-32.188-165.807-97.18-208C336.102 213.619 368 128.1 368 48zM64 48h256c0 101.62-57.307 184-128 184S64 149.621 64 48zm256 416H64c0-101.62 57.308-184 128-184s128 82.38 128 184z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm0 464H48V48h288v416zM144 112h96c8.8 0 16-7.2 16-16s-7.2-16-16-16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16zm48 176c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm-89.6 128h179.2c12.4 0 22.4-8.6 22.4-19.2v-19.2c0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6v19.2c0 10.6 10 19.2 22.4 19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 400H303.2c.9-4.5.8 3.6.8-22.4 0-31.8-30.1-57.6-67.2-57.6-10.8 0-18.7 8-44.8 8-26.9 0-33.4-8-44.8-8-37.1 0-67.2 25.8-67.2 57.6 0 26-.2 17.9.8 22.4H48V144h480v288zm-168-80h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm0-64h112c4.4 0 8-3.6 8-8v-16c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm-168 96c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm-6 336H54a6 6 0 0 1-6-6V118a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v276a6 6 0 0 1-6 6zM128 152c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zM96 352h320v-80l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L192 304l-39.515-39.515c-4.686-4.686-12.284-4.686-16.971 0L96 304v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v48H54a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6v-10h48zm42-336H150a6 6 0 0 0-6 6v244a6 6 0 0 0 6 6h372a6 6 0 0 0 6-6V86a6 6 0 0 0-6-6zm6-48c26.51 0 48 21.49 48 48v256c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h384zM264 144c0 22.091-17.909 40-40 40s-40-17.909-40-40 17.909-40 40-40 40 17.909 40 40zm-72 96l39.515-39.515c4.686-4.686 12.284-4.686 16.971 0L288 240l103.515-103.515c4.686-4.686 12.284-4.686 16.971 0L480 208v80H192v-48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V112c0-26.51-21.49-48-48-48zm8 336c0 4.411-3.589 8-8 8H48c-4.411 0-8-3.589-8-8V112c0-4.411 3.589-8 8-8h480c4.411 0 8 3.589 8 8v288zM170 270v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-336 82v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm384 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zM122 188v-28c0-6.627-5.373-12-12-12H82c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm96 0v-28c0-6.627-5.373-12-12-12h-28c-6.627 0-12 5.373-12 12v28c0 6.627 5.373 12 12 12h28c6.627 0 12-5.373 12-12zm-98 158v-16c0-6.627-5.373-12-12-12H180c-6.627 0-12 5.373-12 12v16c0 6.627 5.373 12 12 12h216c6.627 0 12-5.373 12-12z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M168 176c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm136 132c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M168 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm56-148c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36C290.6 335.3 304 321 304 308zm24-156c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2 7.2 5.6 8.3 3.5 1 7.5-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 5.9-4.5 5.6-8.3-3.1-42.1-32-71.4-55.8-71.4z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M304 308.5c0-19.2-28.8-41.5-71.5-44-3.8-.4-7.4 2.4-8.2 6.2-.9 3.8 1.1 7.7 4.7 9.2l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-5.7 2.4-6 12.2 0 14.8l16.9 7.2c13 5.5 20.8 13.5 20.8 21.5s-7.8 16-20.7 21.5l-17 7.2c-3.6 1.5-5.6 5.4-4.7 9.2.8 3.6 4.1 6.2 7.8 6.2h.5c42.8-2.5 71.5-24.8 71.5-44 0-13-13.4-27.3-35.2-36 21.7-9.1 35.1-23.4 35.1-36.4zm70.5-83.5l9.5 8.5c3.8 3.3 9.3 4 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 5.8 3.1 11.2.7 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0zM136 208.5c0 17.7 14.3 32 32 32s32-14.3 32-32-14.3-32-32-32-32 14.3-32 32zm365.1 194c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zM334 436.3c-26.1 12.5-55.2 19.7-86 19.7-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200c0 22.1-3.7 43.3-10.4 63.2 9 6.4 17 14.2 22.6 23.9 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-2.5-7.3 4.3 17.2-13.4-46.8z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 224c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm-160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM328 152c-23.8 0-52.7 29.3-56 71.4-.7 8.6 10.8 11.9 14.9 4.5l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.1-42.1-32-71.4-55.8-71.4zm-201 75.9l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c4.1 7.4 15.6 4 14.9-4.5-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.6 8.5 10.9 11.9 15.1 4.5zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6S48 309.4 48 256s20.8-103.6 58.6-141.4S194.6 56 248 56s103.6 20.8 141.4 58.6S448 202.6 448 256s-20.8 103.6-58.6 141.4zM343.6 196l33.6-40.3c8.6-10.3-3.8-24.8-15.4-18l-80 48c-7.8 4.7-7.8 15.9 0 20.6l80 48c11.5 6.8 24-7.6 15.4-18L343.6 196zm-209.4 58.3l80-48c7.8-4.7 7.8-15.9 0-20.6l-80-48c-11.6-6.9-24 7.7-15.4 18l33.6 40.3-33.6 40.3c-8.7 10.4 3.8 24.8 15.4 18zM362.4 288H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm141.4 389.4c-37.8 37.8-88 58.6-141.4 58.6s-103.6-20.8-141.4-58.6C68.8 359.6 48 309.4 48 256s20.8-103.6 58.6-141.4C144.4 76.8 194.6 56 248 56s103.6 20.8 141.4 58.6c37.8 37.8 58.6 88 58.6 141.4s-20.8 103.6-58.6 141.4zM328 164c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1zm-160 60c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm194.4 64H133.6c-8.2 0-14.5 7-13.5 15 7.5 59.2 58.9 105 121.1 105h13.6c62.2 0 113.6-45.8 121.1-105 1-8-5.3-15-13.5-15z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M484.112 27.889C455.989-.233 416.108-8.057 387.059 8.865 347.604 31.848 223.504-41.111 91.196 91.197-41.277 223.672 31.923 347.472 8.866 387.058c-16.922 29.051-9.1 68.932 19.022 97.054 28.135 28.135 68.011 35.938 97.057 19.021 39.423-22.97 163.557 49.969 295.858-82.329 132.474-132.477 59.273-256.277 82.331-295.861 16.922-29.05 9.1-68.931-19.022-97.054zm-22.405 72.894c-38.8 66.609 45.6 165.635-74.845 286.08-120.44 120.443-219.475 36.048-286.076 74.843-22.679 13.207-64.035-27.241-50.493-50.488 38.8-66.609-45.6-165.635 74.845-286.08C245.573 4.702 344.616 89.086 411.219 50.292c22.73-13.24 64.005 27.288 50.488 50.491zm-169.861 8.736c1.37 10.96-6.404 20.957-17.365 22.327-54.846 6.855-135.779 87.787-142.635 142.635-1.373 10.989-11.399 18.734-22.326 17.365-10.961-1.37-18.735-11.366-17.365-22.326 9.162-73.286 104.167-168.215 177.365-177.365 10.953-1.368 20.956 6.403 22.326 17.364z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 504c136.967 0 248-111.033 248-248S392.967 8 256 8 8 119.033 8 256s111.033 248 248 248zm-103.398-76.72l53.411-53.411c31.806 13.506 68.128 13.522 99.974 0l53.411 53.411c-63.217 38.319-143.579 38.319-206.796 0zM336 256c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zm91.28 103.398l-53.411-53.411c13.505-31.806 13.522-68.128 0-99.974l53.411-53.411c38.319 63.217 38.319 143.579 0 206.796zM359.397 84.72l-53.411 53.411c-31.806-13.505-68.128-13.522-99.973 0L152.602 84.72c63.217-38.319 143.579-38.319 206.795 0zM84.72 152.602l53.411 53.411c-13.506 31.806-13.522 68.128 0 99.974L84.72 359.398c-38.319-63.217-38.319-143.579 0-206.796z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M176 80c-52.94 0-96 43.06-96 96 0 8.84 7.16 16 16 16s16-7.16 16-16c0-35.3 28.72-64 64-64 8.84 0 16-7.16 16-16s-7.16-16-16-16zM96.06 459.17c0 3.15.93 6.22 2.68 8.84l24.51 36.84c2.97 4.46 7.97 7.14 13.32 7.14h78.85c5.36 0 10.36-2.68 13.32-7.14l24.51-36.84c1.74-2.62 2.67-5.7 2.68-8.84l.05-43.18H96.02l.04 43.18zM176 0C73.72 0 0 82.97 0 176c0 44.37 16.45 84.85 43.56 115.78 16.64 18.99 42.74 58.8 52.42 92.16v.06h48v-.12c-.01-4.77-.72-9.51-2.15-14.07-5.59-17.81-22.82-64.77-62.17-109.67-20.54-23.43-31.52-53.15-31.61-84.14-.2-73.64 59.67-128 127.95-128 70.58 0 128 57.42 128 128 0 30.97-11.24 60.85-31.65 84.14-39.11 44.61-56.42 91.47-62.1 109.46a47.507 47.507 0 0 0-2.22 14.3v.1h48v-.05c9.68-33.37 35.78-73.18 52.42-92.16C335.55 260.85 352 220.37 352 176 352 78.8 273.2 0 176 0z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zm-6 400H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h404a6 6 0 0 1 6 6v340a6 6 0 0 1-6 6zm-42-92v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm0-96v24c0 6.627-5.373 12-12 12H204c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h200c6.627 0 12 5.373 12 12zm-252 12c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36zm0 96c0 19.882-16.118 36-36 36s-36-16.118-36-36 16.118-36 36-36 36 16.118 36 36z\"],\n    \"map\": [576, 512, [], \"f279\", \"M560.02 32c-1.96 0-3.98.37-5.96 1.16L384.01 96H384L212 35.28A64.252 64.252 0 0 0 191.76 32c-6.69 0-13.37 1.05-19.81 3.14L20.12 87.95A32.006 32.006 0 0 0 0 117.66v346.32C0 473.17 7.53 480 15.99 480c1.96 0 3.97-.37 5.96-1.16L192 416l172 60.71a63.98 63.98 0 0 0 40.05.15l151.83-52.81A31.996 31.996 0 0 0 576 394.34V48.02c0-9.19-7.53-16.02-15.98-16.02zM224 90.42l128 45.19v285.97l-128-45.19V90.42zM48 418.05V129.07l128-44.53v286.2l-.64.23L48 418.05zm480-35.13l-128 44.53V141.26l.64-.24L528 93.95v288.97z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm8 144H160c-13.2 0-24 10.8-24 24s10.8 24 24 24h176c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-280c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm160 0c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm88-304c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm0 112c-22.1 0-40-17.9-40-40 0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40zm-104-40c0-39.8-32.2-72-72-72s-72 32.2-72 72 32.2 72 72 72 72-32.2 72-72zm-112 0c0-13.6 7.3-25.1 17.7-32.3-1 2.6-1.7 5.3-1.7 8.3 0 13.3 10.7 24 24 24s24-10.7 24-24c0-2.9-.7-5.7-1.7-8.3 10.4 7.2 17.7 18.7 17.7 32.3 0 22.1-17.9 40-40 40s-40-17.9-40-40zm192 128H184c-13.2 0-24 10.8-24 24s10.8 24 24 24h128c13.2 0 24-10.8 24-24s-10.8-24-24-24z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M108 284c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h232c6.6 0 12 5.4 12 12v32c0 6.6-5.4 12-12 12H108zM448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M320 144c-53.02 0-96 50.14-96 112 0 61.85 42.98 112 96 112 53 0 96-50.13 96-112 0-61.86-42.98-112-96-112zm40 168c0 4.42-3.58 8-8 8h-64c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h16v-55.44l-.47.31a7.992 7.992 0 0 1-11.09-2.22l-8.88-13.31a7.992 7.992 0 0 1 2.22-11.09l15.33-10.22a23.99 23.99 0 0 1 13.31-4.03H328c4.42 0 8 3.58 8 8v88h16c4.42 0 8 3.58 8 8v16zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zm-16 272c-35.35 0-64 28.65-64 64H112c0-35.35-28.65-64-64-64V176c35.35 0 64-28.65 64-64h416c0 35.35 28.65 64 64 64v160z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M279.135 512c78.756 0 150.982-35.804 198.844-94.775 28.27-34.831-2.558-85.722-46.249-77.401-82.348 15.683-158.272-47.268-158.272-130.792 0-48.424 26.06-92.292 67.434-115.836 38.745-22.05 28.999-80.788-15.022-88.919A257.936 257.936 0 0 0 279.135 0c-141.36 0-256 114.575-256 256 0 141.36 114.576 256 256 256zm0-464c12.985 0 25.689 1.201 38.016 3.478-54.76 31.163-91.693 90.042-91.693 157.554 0 113.848 103.641 199.2 215.252 177.944C402.574 433.964 344.366 464 279.135 464c-114.875 0-208-93.125-208-208s93.125-208 208-208z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H112c-20.858 0-38.643 13.377-45.248 32H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h496c13.255 0 24-10.745 24-24V88c0-13.255-10.745-24-24-24zM48 392V144h16v248c0 4.411-3.589 8-8 8s-8-3.589-8-8zm480 8H111.422c.374-2.614.578-5.283.578-8V112h416v288zM172 280h136c6.627 0 12-5.373 12-12v-96c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v96c0 6.627 5.373 12 12 12zm28-80h80v40h-80v-40zm-40 140v-24c0-6.627 5.373-12 12-12h136c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H172c-6.627 0-12-5.373-12-12zm192 0v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0-144v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12zm0 72v-24c0-6.627 5.373-12 12-12h104c6.627 0 12 5.373 12 12v24c0 6.627-5.373 12-12 12H364c-6.627 0-12-5.373-12-12z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M500 128c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v256H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V128h12zm-52-64h32v32h-32V64zM32 64h32v32H32V64zm32 384H32v-32h32v32zm416 0h-32v-32h32v32zm-40-64h-12c-6.627 0-12 5.373-12 12v12H96v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h320v12c0 6.627 5.373 12 12 12h12v256zm-36-192h-84v-52c0-6.628-5.373-12-12-12H108c-6.627 0-12 5.372-12 12v168c0 6.628 5.373 12 12 12h84v52c0 6.628 5.373 12 12 12h200c6.627 0 12-5.372 12-12V204c0-6.628-5.373-12-12-12zm-268-24h144v112H136V168zm240 176H232v-24h76c6.627 0 12-5.372 12-12v-76h56v112z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M564 224c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12h-88v-24h12c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-72c-6.627 0-12 5.373-12 12v12H96V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v72c0 6.627 5.373 12 12 12h12v160H12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h88v24h-12c-6.627 0-12 5.373-12 12v72c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12V224h12zM352 64h32v32h-32V64zm0 256h32v32h-32v-32zM64 352H32v-32h32v32zm0-256H32V64h32v32zm32 216v-12c0-6.627-5.373-12-12-12H72V128h12c6.627 0 12-5.373 12-12v-12h224v12c0 6.627 5.373 12 12 12h12v160h-12c-6.627 0-12 5.373-12 12v12H96zm128 136h-32v-32h32v32zm280-64h-12c-6.627 0-12 5.373-12 12v12H256v-12c0-6.627-5.373-12-12-12h-12v-24h88v12c0 6.627 5.373 12 12 12h72c6.627 0 12-5.373 12-12v-72c0-6.627-5.373-12-12-12h-12v-88h88v12c0 6.627 5.373 12 12 12h12v160zm40 64h-32v-32h32v32zm0-256h-32v-32h32v32z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M440 6.5L24 246.4c-34.4 19.9-31.1 70.8 5.7 85.9L144 379.6V464c0 46.4 59.2 65.5 86.6 28.6l43.8-59.1 111.9 46.2c5.9 2.4 12.1 3.6 18.3 3.6 8.2 0 16.3-2.1 23.6-6.2 12.8-7.2 21.6-20 23.9-34.5l59.4-387.2c6.1-40.1-36.9-68.8-71.5-48.9zM192 464v-64.6l36.6 15.1L192 464zm212.6-28.7l-153.8-63.5L391 169.5c10.7-15.5-9.5-33.5-23.7-21.2L155.8 332.6 48 288 464 48l-59.4 387.3z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm96-280v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16zm-112 0v160c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M371.7 238l-176-107c-15.8-8.8-35.7 2.5-35.7 21v208c0 18.4 19.8 29.8 35.7 21l176-101c16.4-9.1 16.4-32.8 0-42zM504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M352 240v32c0 6.6-5.4 12-12 12h-88v88c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-88h-88c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h88v-88c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v88h88c6.6 0 12 5.4 12 12zm96-160v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zm-48 346V86c0-3.3-2.7-6-6-6H54c-3.3 0-6 2.7-6 6v340c0 3.3 2.7 6 6 6h340c3.3 0 6-2.7 6-6z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 448c-110.532 0-200-89.431-200-200 0-110.495 89.472-200 200-200 110.491 0 200 89.471 200 200 0 110.53-89.431 200-200 200zm107.244-255.2c0 67.052-72.421 68.084-72.421 92.863V300c0 6.627-5.373 12-12 12h-45.647c-6.627 0-12-5.373-12-12v-8.659c0-35.745 27.1-50.034 47.579-61.516 17.561-9.845 28.324-16.541 28.324-29.579 0-17.246-21.999-28.693-39.784-28.693-23.189 0-33.894 10.977-48.942 29.969-4.057 5.12-11.46 6.071-16.666 2.124l-27.824-21.098c-5.107-3.872-6.251-11.066-2.644-16.363C184.846 131.491 214.94 112 261.794 112c49.071 0 101.45 38.304 101.45 88.8zM298 368c0 23.159-18.841 42-42 42s-42-18.841-42-42 18.841-42 42-42 42 18.841 42 42z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 448c-110.532 0-200-89.451-200-200 0-110.531 89.451-200 200-200 110.532 0 200 89.451 200 200 0 110.532-89.451 200-200 200zm110.442-81.791c-53.046-96.284-50.25-91.468-53.271-96.085 24.267-13.879 39.482-41.563 39.482-73.176 0-52.503-30.247-85.252-101.498-85.252h-78.667c-6.617 0-12 5.383-12 12V380c0 6.617 5.383 12 12 12h38.568c6.617 0 12-5.383 12-12v-83.663h31.958l47.515 89.303a11.98 11.98 0 0 0 10.593 6.36h42.81c9.14 0 14.914-9.799 10.51-17.791zM256.933 239.906h-33.875v-64.14h27.377c32.417 0 38.929 12.133 38.929 31.709-.001 20.913-11.518 32.431-32.431 32.431z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm144 386.4V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v151.4C315.5 447 282.8 456 248 456s-67.5-9-96-24.6V280c0-13.2-10.8-24-24-24s-24 10.8-24 24v114.4c-34.6-36-56-84.7-56-138.4 0-110.3 89.7-200 200-200s200 89.7 200 200c0 53.7-21.4 102.5-56 138.4zM205.8 234.5c4.4-2.4 6.9-7.4 6.1-12.4-4-25.2-34.2-42.1-59.8-42.1s-55.9 16.9-59.8 42.1c-.8 5 1.7 10 6.1 12.4 4.4 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.3 7.9 4.8 13.7 1.6zM344 180c-25.7 0-55.9 16.9-59.8 42.1-.8 5 1.7 10 6.1 12.4 4.5 2.4 9.9 1.8 13.7-1.6l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c2.5 2.2 8 4.7 13.7 1.6 4.4-2.4 6.9-7.4 6.1-12.4-3.9-25.2-34.1-42.1-59.8-42.1zm-96 92c-30.9 0-56 28.7-56 64s25.1 64 56 64 56-28.7 56-64-25.1-64-56-64z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm8-152c-13.2 0-24 10.8-24 24s10.8 24 24 24c23.8 0 46.3 10.5 61.6 28.8 8.1 9.8 23.2 11.9 33.8 3.1 10.2-8.5 11.6-23.6 3.1-33.8C330 320.8 294.1 304 256 304zm-88-64c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-64c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm-165.6 98.8C151 290.1 126 325.4 126 342.9c0 22.7 18.8 41.1 42 41.1s42-18.4 42-41.1c0-17.5-25-52.8-36.4-68.1-2.8-3.7-8.4-3.7-11.2 0z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM272 80v80H144V80h128zm122 352H54a6 6 0 0 1-6-6V86a6 6 0 0 1 6-6h42v104c0 13.255 10.745 24 24 24h176c13.255 0 24-10.745 24-24V83.882l78.243 78.243a6 6 0 0 1 1.757 4.243V426a6 6 0 0 1-6 6zM224 232c-48.523 0-88 39.477-88 88s39.477 88 88 88 88-39.477 88-88-39.477-88-88-88zm0 128c-22.056 0-40-17.944-40-40s17.944-40 40-40 40 17.944 40 40-17.944 40-40 40z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M561.938 158.06L417.94 14.092C387.926-15.922 336 5.097 336 48.032v57.198c-42.45 1.88-84.03 6.55-120.76 17.99-35.17 10.95-63.07 27.58-82.91 49.42C108.22 199.2 96 232.6 96 271.94c0 61.697 33.178 112.455 84.87 144.76 37.546 23.508 85.248-12.651 71.02-55.74-15.515-47.119-17.156-70.923 84.11-78.76V336c0 42.993 51.968 63.913 81.94 33.94l143.998-144c18.75-18.74 18.75-49.14 0-67.88zM384 336V232.16C255.309 234.082 166.492 255.35 206.31 376 176.79 357.55 144 324.08 144 271.94c0-109.334 129.14-118.947 240-119.85V48l144 144-144 144zm24.74 84.493a82.658 82.658 0 0 0 20.974-9.303c7.976-4.952 18.286.826 18.286 10.214V464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h132c6.627 0 12 5.373 12 12v4.486c0 4.917-2.987 9.369-7.569 11.152-13.702 5.331-26.396 11.537-38.05 18.585a12.138 12.138 0 0 1-6.28 1.777H54a6 6 0 0 0-6 6v340a6 6 0 0 0 6 6h340a6 6 0 0 0 6-6v-25.966c0-5.37 3.579-10.059 8.74-11.541z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm-80-216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160 0c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm4 72.6c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.1-8.4-25.3-7.1-33.8 3.1z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm84-143.4c-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.6-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8-10.2-8.4-25.3-7.1-33.8 3.1zM136.5 211c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4s-52.7 29.3-56 71.4c-.3 3.7 2.1 7.2 5.7 8.3 3.4 1.1 7.4-.5 9.3-3.7l9.5-17zM328 152c-23.8 0-52.7 29.3-56 71.4-.3 3.7 2.1 7.2 5.7 8.3 3.5 1.1 7.4-.5 9.3-3.7l9.5-17c7.7-13.7 19.2-21.6 31.5-21.6s23.8 7.9 31.5 21.6l9.5 17c2.1 3.7 6.2 4.7 9.3 3.7 3.6-1.1 6-4.5 5.7-8.3-3.3-42.1-32.2-71.4-56-71.4z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm117.8-146.4c-10.2-8.5-25.3-7.1-33.8 3.1-20.8 25-51.5 39.4-84 39.4s-63.2-14.3-84-39.4c-8.5-10.2-23.7-11.5-33.8-3.1-10.2 8.5-11.5 23.6-3.1 33.8 30 36 74.1 56.6 120.9 56.6s90.9-20.6 120.9-56.6c8.5-10.2 7.1-25.3-3.1-33.8zM168 240c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32zm160-60c-25.7 0-55.9 16.9-59.9 42.1-1.7 11.2 11.5 18.2 19.8 10.8l9.5-8.5c14.8-13.2 46.2-13.2 61 0l9.5 8.5c8.5 7.4 21.6.3 19.8-10.8-3.8-25.2-34-42.1-59.7-42.1z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.1 355.2l-39.2-23 34.1-9.3c8.4-2.3 13.4-11.1 11.1-19.6l-4.1-15.5c-2.2-8.5-10.9-13.6-19.3-11.3L343 298.2 271.2 256l71.9-42.2 79.7 21.7c8.4 2.3 17-2.8 19.3-11.3l4.1-15.5c2.2-8.5-2.7-17.3-11.1-19.6l-34.1-9.3 39.2-23c7.5-4.4 10.1-14.2 5.8-21.9l-7.9-13.9c-4.3-7.7-14-10.3-21.5-5.9l-39.2 23 9.1-34.7c2.2-8.5-2.7-17.3-11.1-19.6l-15.2-4.1c-8.4-2.3-17 2.8-19.3 11.3l-21.3 81-71.9 42.2v-84.5L306 70.4c6.1-6.2 6.1-16.4 0-22.6l-11.1-11.3c-6.1-6.2-16.1-6.2-22.2 0l-24.9 25.4V16c0-8.8-7-16-15.7-16h-15.7c-8.7 0-15.7 7.2-15.7 16v46.1l-24.9-25.4c-6.1-6.2-16.1-6.2-22.2 0L142.1 48c-6.1 6.2-6.1 16.4 0 22.6l58.3 59.3v84.5l-71.9-42.2-21.3-81c-2.2-8.5-10.9-13.6-19.3-11.3L72.7 84c-8.4 2.3-13.4 11.1-11.1 19.6l9.1 34.7-39.2-23c-7.5-4.4-17.1-1.8-21.5 5.9l-7.9 13.9c-4.3 7.7-1.8 17.4 5.8 21.9l39.2 23-34.1 9.1c-8.4 2.3-13.4 11.1-11.1 19.6L6 224.2c2.2 8.5 10.9 13.6 19.3 11.3l79.7-21.7 71.9 42.2-71.9 42.2-79.7-21.7c-8.4-2.3-17 2.8-19.3 11.3l-4.1 15.5c-2.2 8.5 2.7 17.3 11.1 19.6l34.1 9.3-39.2 23c-7.5 4.4-10.1 14.2-5.8 21.9L10 391c4.3 7.7 14 10.3 21.5 5.9l39.2-23-9.1 34.7c-2.2 8.5 2.7 17.3 11.1 19.6l15.2 4.1c8.4 2.3 17-2.8 19.3-11.3l21.3-81 71.9-42.2v84.5l-58.3 59.3c-6.1 6.2-6.1 16.4 0 22.6l11.1 11.3c6.1 6.2 16.1 6.2 22.2 0l24.9-25.4V496c0 8.8 7 16 15.7 16h15.7c8.7 0 15.7-7.2 15.7-16v-46.1l24.9 25.4c6.1 6.2 16.1 6.2 22.2 0l11.1-11.3c6.1-6.2 6.1-16.4 0-22.6l-58.3-59.3v-84.5l71.9 42.2 21.3 81c2.2 8.5 10.9 13.6 19.3 11.3L375 428c8.4-2.3 13.4-11.1 11.1-19.6l-9.1-34.7 39.2 23c7.5 4.4 17.1 1.8 21.5-5.9l7.9-13.9c4.6-7.5 2.1-17.3-5.5-21.7z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-6 400H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h340c3.3 0 6 2.7 6 6v340c0 3.3-2.7 6-6 6z\"],\n    \"star\": [576, 512, [], \"f005\", \"M528.1 171.5L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6zM388.6 312.3l23.7 138.4L288 385.4l-124.3 65.3 23.7-138.4-100.6-98 139-20.2 62.2-126 62.2 126 139 20.2-100.6 98z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 385.3l-124.3 65.4 23.7-138.4-100.6-98 139-20.2 62.2-126V0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6v-54.3z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M448 348.106V80c0-26.51-21.49-48-48-48H48C21.49 32 0 53.49 0 80v351.988c0 26.51 21.49 48 48 48h268.118a48 48 0 0 0 33.941-14.059l83.882-83.882A48 48 0 0 0 448 348.106zm-128 80v-76.118h76.118L320 428.106zM400 80v223.988H296c-13.255 0-24 10.745-24 24v104H48V80h352z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M504 256C504 119 393 8 256 8S8 119 8 256s111 248 248 248 248-111 248-248zm-448 0c0-110.5 89.5-200 200-200s200 89.5 200 200-89.5 200-200 200S56 366.5 56 256zm296-80v160c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M494.2 221.9l-59.8-40.5 13.7-71c2.6-13.2-1.6-26.8-11.1-36.4-9.6-9.5-23.2-13.7-36.2-11.1l-70.9 13.7-40.4-59.9c-15.1-22.3-51.9-22.3-67 0l-40.4 59.9-70.8-13.7C98 60.4 84.5 64.5 75 74.1c-9.5 9.6-13.7 23.1-11.1 36.3l13.7 71-59.8 40.5C6.6 229.5 0 242 0 255.5s6.7 26 17.8 33.5l59.8 40.5-13.7 71c-2.6 13.2 1.6 26.8 11.1 36.3 9.5 9.5 22.9 13.7 36.3 11.1l70.8-13.7 40.4 59.9C230 505.3 242.6 512 256 512s26-6.7 33.5-17.8l40.4-59.9 70.9 13.7c13.4 2.7 26.8-1.6 36.3-11.1 9.5-9.5 13.6-23.1 11.1-36.3l-13.7-71 59.8-40.5c11.1-7.5 17.8-20.1 17.8-33.5-.1-13.6-6.7-26.1-17.9-33.7zm-112.9 85.6l17.6 91.2-91-17.6L256 458l-51.9-77-90.9 17.6 17.6-91.2-76.8-52 76.8-52-17.6-91.2 91 17.6L256 53l51.9 76.9 91-17.6-17.6 91.1 76.8 52-76.8 52.1zM256 152c-57.3 0-104 46.7-104 104s46.7 104 104 104 104-46.7 104-104-46.7-104-104-104zm0 160c-30.9 0-56-25.1-56-56s25.1-56 56-56 56 25.1 56 56-25.1 56-56 56z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm0-176c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm-48-72c0-17.7-14.3-32-32-32s-32 14.3-32 32 14.3 32 32 32 32-14.3 32-32zm128-32c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M466.27 225.31c4.674-22.647.864-44.538-8.99-62.99 2.958-23.868-4.021-48.565-17.34-66.99C438.986 39.423 404.117 0 327 0c-7 0-15 .01-22.22.01C201.195.01 168.997 40 128 40h-10.845c-5.64-4.975-13.042-8-21.155-8H32C14.327 32 0 46.327 0 64v240c0 17.673 14.327 32 32 32h64c11.842 0 22.175-6.438 27.708-16h7.052c19.146 16.953 46.013 60.653 68.76 83.4 13.667 13.667 10.153 108.6 71.76 108.6 57.58 0 95.27-31.936 95.27-104.73 0-18.41-3.93-33.73-8.85-46.54h36.48c48.602 0 85.82-41.565 85.82-85.58 0-19.15-4.96-34.99-13.73-49.84zM64 296c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm330.18 16.73H290.19c0 37.82 28.36 55.37 28.36 94.54 0 23.75 0 56.73-47.27 56.73-18.91-18.91-9.46-66.18-37.82-94.54C206.9 342.89 167.28 272 138.92 272H128V85.83c53.611 0 100.001-37.82 171.64-37.82h37.82c35.512 0 60.82 17.12 53.12 65.9 15.2 8.16 26.5 36.44 13.94 57.57 21.581 20.384 18.699 51.065 5.21 65.62 9.45 0 22.36 18.91 22.27 37.81-.09 18.91-16.71 37.82-37.82 37.82z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M466.27 286.69C475.04 271.84 480 256 480 236.85c0-44.015-37.218-85.58-85.82-85.58H357.7c4.92-12.81 8.85-28.13 8.85-46.54C366.55 31.936 328.86 0 271.28 0c-61.607 0-58.093 94.933-71.76 108.6-22.747 22.747-49.615 66.447-68.76 83.4H32c-17.673 0-32 14.327-32 32v240c0 17.673 14.327 32 32 32h64c14.893 0 27.408-10.174 30.978-23.95 44.509 1.001 75.06 39.94 177.802 39.94 7.22 0 15.22.01 22.22.01 77.117 0 111.986-39.423 112.94-95.33 13.319-18.425 20.299-43.122 17.34-66.99 9.854-18.452 13.664-40.343 8.99-62.99zm-61.75 53.83c12.56 21.13 1.26 49.41-13.94 57.57 7.7 48.78-17.608 65.9-53.12 65.9h-37.82c-71.639 0-118.029-37.82-171.64-37.82V240h10.92c28.36 0 67.98-70.89 94.54-97.46 28.36-28.36 18.91-75.63 37.82-94.54 47.27 0 47.27 32.98 47.27 56.73 0 39.17-28.36 56.72-28.36 94.54h103.99c21.11 0 37.73 18.91 37.82 37.82.09 18.9-12.82 37.81-22.27 37.81 13.489 14.555 16.371 45.236-5.21 65.62zM88 432c0 13.255-10.745 24-24 24s-24-10.745-24-24 10.745-24 24-24 24 10.745 24 24z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm0 448c-110.5 0-200-89.5-200-200S145.5 56 256 56s200 89.5 200 200-89.5 200-200 200zm101.8-262.2L295.6 256l62.2 62.2c4.7 4.7 4.7 12.3 0 17l-22.6 22.6c-4.7 4.7-12.3 4.7-17 0L256 295.6l-62.2 62.2c-4.7 4.7-12.3 4.7-17 0l-22.6-22.6c-4.7-4.7-4.7-12.3 0-17l62.2-62.2-62.2-62.2c-4.7-4.7-4.7-12.3 0-17l22.6-22.6c4.7-4.7 12.3-4.7 17 0l62.2 62.2 62.2-62.2c4.7-4.7 12.3-4.7 17 0l22.6 22.6c4.7 4.7 4.7 12.3 0 17z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-110.3 0-200-89.7-200-200S137.7 56 248 56s200 89.7 200 200-89.7 200-200 200zm129.1-303.8c-3.8-4.4-10.3-5.4-15.3-2.5l-80 48c-3.6 2.2-5.8 6.1-5.8 10.3s2.2 8.1 5.8 10.3l80 48c5.4 3.2 11.8 1.6 15.3-2.5 3.8-4.5 3.9-11 .1-15.5L343.6 208l33.6-40.3c3.8-4.5 3.7-11.1-.1-15.5zM220 208c0-4.2-2.2-8.1-5.8-10.3l-80-48c-5-3-11.5-1.9-15.3 2.5-3.8 4.5-3.9 11-.1 15.5l33.6 40.3-33.6 40.3c-3.8 4.5-3.7 11 .1 15.5 3.5 4.1 9.9 5.7 15.3 2.5l80-48c3.6-2.2 5.8-6.1 5.8-10.3zm28 64c-45.4 0-100.9 38.3-107.8 93.3-1.5 11.8 6.9 21.6 15.5 17.9C178.4 373.5 212 368 248 368s69.6 5.5 92.3 15.2c8.5 3.7 17-6 15.5-17.9-6.9-55-62.4-93.3-107.8-93.3z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M268 416h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12zM432 80h-82.41l-34-56.7A48 48 0 0 0 274.41 0H173.59a48 48 0 0 0-41.16 23.3L98.41 80H16A16 16 0 0 0 0 96v16a16 16 0 0 0 16 16h16v336a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128h16a16 16 0 0 0 16-16V96a16 16 0 0 0-16-16zM171.84 50.91A6 6 0 0 1 177 48h94a6 6 0 0 1 5.15 2.91L293.61 80H154.39zM368 464H80V128h288zm-212-48h24a12 12 0 0 0 12-12V188a12 12 0 0 0-12-12h-24a12 12 0 0 0-12 12v216a12 12 0 0 0 12 12z\"],\n    \"user\": [448, 512, [], \"f007\", \"M313.6 304c-28.7 0-42.5 16-89.6 16-47.1 0-60.8-16-89.6-16C60.2 304 0 364.2 0 438.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-25.6c0-74.2-60.2-134.4-134.4-134.4zM400 464H48v-25.6c0-47.6 38.8-86.4 86.4-86.4 14.6 0 38.3 16 89.6 16 51.7 0 74.9-16 89.6-16 47.6 0 86.4 38.8 86.4 86.4V464zM224 288c79.5 0 144-64.5 144-144S303.5 0 224 0 80 64.5 80 144s64.5 144 144 144zm0-240c52.9 0 96 43.1 96 96s-43.1 96-96 96-96-43.1-96-96 43.1-96 96-96z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 104c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96zm0 144c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm0-240C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 448c-49.7 0-95.1-18.3-130.1-48.4 14.9-23 40.4-38.6 69.6-39.5 20.8 6.4 40.6 9.6 60.5 9.6s39.7-3.1 60.5-9.6c29.2 1 54.7 16.5 69.6 39.5-35 30.1-80.4 48.4-130.1 48.4zm162.7-84.1c-24.4-31.4-62.1-51.9-105.1-51.9-10.2 0-26 9.6-57.6 9.6-31.5 0-47.4-9.6-57.6-9.6-42.9 0-80.6 20.5-105.1 51.9C61.9 339.2 48 299.2 48 256c0-110.3 89.7-200 200-200s200 89.7 200 200c0 43.2-13.9 83.2-37.3 115.9z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V86c0-3.3 2.7-6 6-6h404c3.3 0 6 2.7 6 6v340zM356.5 194.6L295.1 256l61.4 61.4c4.6 4.6 4.6 12.1 0 16.8l-22.3 22.3c-4.6 4.6-12.1 4.6-16.8 0L256 295.1l-61.4 61.4c-4.6 4.6-12.1 4.6-16.8 0l-22.3-22.3c-4.6-4.6-4.6-12.1 0-16.8l61.4-61.4-61.4-61.4c-4.6-4.6-4.6-12.1 0-16.8l22.3-22.3c4.6-4.6 12.1-4.6 16.8 0l61.4 61.4 61.4-61.4c4.6-4.6 12.1-4.6 16.8 0l22.3 22.3c4.7 4.6 4.7 12.1 0 16.8z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm0 394c0 3.3-2.7 6-6 6H54c-3.3 0-6-2.7-6-6V192h416v234z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M480 480H32c-17.7 0-32-14.3-32-32s14.3-32 32-32h448c17.7 0 32 14.3 32 32s-14.3 32-32 32z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M464 0H144c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v320c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h48c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-96 464H48V256h320v208zm96-96h-48V144c0-26.5-21.5-48-48-48H144V48h320v320z\"]\n  };\n\n  bunker(function () {\n    defineIcons('far', icons);\n  });\n\n}());\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/solid.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function () {\n  'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return \"production\" === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  function _defineProperty(obj, key, value) {\n    if (key in obj) {\n      Object.defineProperty(obj, key, {\n        value: value,\n        enumerable: true,\n        configurable: true,\n        writable: true\n      });\n    } else {\n      obj[key] = value;\n    }\n\n    return obj;\n  }\n\n  function _objectSpread(target) {\n    for (var i = 1; i < arguments.length; i++) {\n      var source = arguments[i] != null ? arguments[i] : {};\n      var ownKeys = Object.keys(source);\n\n      if (typeof Object.getOwnPropertySymbols === 'function') {\n        ownKeys = ownKeys.concat(Object.getOwnPropertySymbols(source).filter(function (sym) {\n          return Object.getOwnPropertyDescriptor(source, sym).enumerable;\n        }));\n      }\n\n      ownKeys.forEach(function (key) {\n        _defineProperty(target, key, source[key]);\n      });\n    }\n\n    return target;\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  function defineIcons(prefix, icons) {\n    var params = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : {};\n    var _params$skipHooks = params.skipHooks,\n        skipHooks = _params$skipHooks === void 0 ? false : _params$skipHooks;\n    var normalized = Object.keys(icons).reduce(function (acc, iconName) {\n      var icon = icons[iconName];\n      var expanded = !!icon.icon;\n\n      if (expanded) {\n        acc[icon.iconName] = icon.icon;\n      } else {\n        acc[iconName] = icon;\n      }\n\n      return acc;\n    }, {});\n\n    if (typeof namespace.hooks.addPack === 'function' && !skipHooks) {\n      namespace.hooks.addPack(prefix, normalized);\n    } else {\n      namespace.styles[prefix] = _objectSpread({}, namespace.styles[prefix] || {}, normalized);\n    }\n    /**\n     * Font Awesome 4 used the prefix of `fa` for all icons. With the introduction\n     * of new styles we needed to differentiate between them. Prefix `fa` is now an alias\n     * for `fas` so we'll easy the upgrade process for our users by automatically defining\n     * this as well.\n     */\n\n\n    if (prefix === 'fas') {\n      defineIcons('fa', icons);\n    }\n  }\n\n  var icons = {\n    \"ad\": [512, 512, [], \"f641\", \"M157.52 272h36.96L176 218.78 157.52 272zM352 256c-13.23 0-24 10.77-24 24s10.77 24 24 24 24-10.77 24-24-10.77-24-24-24zM464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM250.58 352h-16.94c-6.81 0-12.88-4.32-15.12-10.75L211.15 320h-70.29l-7.38 21.25A16 16 0 0 1 118.36 352h-16.94c-11.01 0-18.73-10.85-15.12-21.25L140 176.12A23.995 23.995 0 0 1 162.67 160h26.66A23.99 23.99 0 0 1 212 176.13l53.69 154.62c3.61 10.4-4.11 21.25-15.11 21.25zM424 336c0 8.84-7.16 16-16 16h-16c-4.85 0-9.04-2.27-11.98-5.68-8.62 3.66-18.09 5.68-28.02 5.68-39.7 0-72-32.3-72-72s32.3-72 72-72c8.46 0 16.46 1.73 24 4.42V176c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v160z\"],\n    \"address-book\": [448, 512, [], \"f2b9\", \"M436 160c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h320c26.5 0 48-21.5 48-48v-48h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20v-64h20zm-228-32c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H118.4C106 384 96 375.4 96 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"address-card\": [576, 512, [], \"f2bb\", \"M528 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-352 96c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H86.4C74 384 64 375.4 64 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2zM512 312c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-64c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"adjust\": [512, 512, [], \"f042\", \"M8 256c0 136.966 111.033 248 248 248s248-111.034 248-248S392.966 8 256 8 8 119.033 8 256zm248 184V72c101.705 0 184 82.311 184 184 0 101.705-82.311 184-184 184z\"],\n    \"air-freshener\": [384, 512, [], \"f5d0\", \"M378.94 321.41L284.7 224h49.22c15.3 0 23.66-16.6 13.86-27.53L234.45 69.96c3.43-6.61 5.55-14 5.55-21.96 0-26.51-21.49-48-48-48s-48 21.49-48 48c0 7.96 2.12 15.35 5.55 21.96L36.22 196.47C26.42 207.4 34.78 224 50.08 224H99.3L5.06 321.41C-6.69 333.56 3.34 352 21.7 352H160v32H48c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h288c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16H224v-32h138.3c18.36 0 28.39-18.44 16.64-30.59zM192 31.98c8.85 0 16.02 7.17 16.02 16.02 0 8.84-7.17 16.02-16.02 16.02S175.98 56.84 175.98 48c0-8.85 7.17-16.02 16.02-16.02zM304 432v32H80v-32h224z\"],\n    \"align-center\": [448, 512, [], \"f037\", \"M432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM108.1 96h231.81A12.09 12.09 0 0 0 352 83.9V44.09A12.09 12.09 0 0 0 339.91 32H108.1A12.09 12.09 0 0 0 96 44.09V83.9A12.1 12.1 0 0 0 108.1 96zm231.81 256A12.09 12.09 0 0 0 352 339.9v-39.81A12.09 12.09 0 0 0 339.91 288H108.1A12.09 12.09 0 0 0 96 300.09v39.81a12.1 12.1 0 0 0 12.1 12.1z\"],\n    \"align-justify\": [448, 512, [], \"f039\", \"M432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-128H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"align-left\": [448, 512, [], \"f036\", \"M12.83 352h262.34A12.82 12.82 0 0 0 288 339.17v-38.34A12.82 12.82 0 0 0 275.17 288H12.83A12.82 12.82 0 0 0 0 300.83v38.34A12.82 12.82 0 0 0 12.83 352zm0-256h262.34A12.82 12.82 0 0 0 288 83.17V44.83A12.82 12.82 0 0 0 275.17 32H12.83A12.82 12.82 0 0 0 0 44.83v38.34A12.82 12.82 0 0 0 12.83 96zM432 160H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 256H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"align-right\": [448, 512, [], \"f038\", \"M16 224h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm416 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-384H172.83A12.82 12.82 0 0 0 160 44.83v38.34A12.82 12.82 0 0 0 172.83 96h262.34A12.82 12.82 0 0 0 448 83.17V44.83A12.82 12.82 0 0 0 435.17 32zm0 256H172.83A12.82 12.82 0 0 0 160 300.83v38.34A12.82 12.82 0 0 0 172.83 352h262.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288z\"],\n    \"allergies\": [448, 512, [], \"f461\", \"M416 112c-17.6 0-32 14.4-32 32v72c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32s-32 14.4-32 32v152c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V32c0-17.6-14.4-32-32-32s-32 14.4-32 32v184c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V64c0-17.6-14.4-32-32-32S96 46.4 96 64v241l-23.6-32.5c-13-17.9-38-21.8-55.9-8.8s-21.8 38-8.8 55.9l125.6 172.7c9 12.4 23.5 19.8 38.8 19.8h197.6c22.3 0 41.6-15.3 46.7-37l26.5-112.7c3.2-13.7 4.9-28.3 5.1-42.3V144c0-17.6-14.4-32-32-32zM176 416c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm64 32c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32-128c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"ambulance\": [640, 512, [], \"f0f9\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm144-248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm176 248c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"american-sign-language-interpreting\": [640, 512, [], \"f2a3\", \"M290.547 189.039c-20.295-10.149-44.147-11.199-64.739-3.89 42.606 0 71.208 20.475 85.578 50.576 8.576 17.899-5.148 38.071-23.617 38.071 18.429 0 32.211 20.136 23.617 38.071-14.725 30.846-46.123 50.854-80.298 50.854-.557 0-94.471-8.615-94.471-8.615l-66.406 33.347c-9.384 4.693-19.815.379-23.895-7.781L1.86 290.747c-4.167-8.615-1.111-18.897 6.946-23.621l58.072-33.069L108 159.861c6.39-57.245 34.731-109.767 79.743-146.726 11.391-9.448 28.341-7.781 37.51 3.613 9.446 11.394 7.78 28.067-3.612 37.516-12.503 10.559-23.618 22.509-32.509 35.57 21.672-14.729 46.679-24.732 74.186-28.067 14.725-1.945 28.063 8.336 29.73 23.065 1.945 14.728-8.336 28.067-23.062 29.734-16.116 1.945-31.12 7.503-44.178 15.284 26.114-5.713 58.712-3.138 88.079 11.115 13.336 6.669 18.893 22.509 12.224 35.848-6.389 13.06-22.504 18.617-35.564 12.226zm-27.229 69.472c-6.112-12.505-18.338-20.286-32.231-20.286a35.46 35.46 0 0 0-35.565 35.57c0 21.428 17.808 35.57 35.565 35.57 13.893 0 26.119-7.781 32.231-20.286 4.446-9.449 13.614-15.006 23.339-15.284-9.725-.277-18.893-5.835-23.339-15.284zm374.821-37.237c4.168 8.615 1.111 18.897-6.946 23.621l-58.071 33.069L532 352.16c-6.39 57.245-34.731 109.767-79.743 146.726-10.932 9.112-27.799 8.144-37.51-3.613-9.446-11.394-7.78-28.067 3.613-37.516 12.503-10.559 23.617-22.509 32.508-35.57-21.672 14.729-46.679 24.732-74.186 28.067-10.021 2.506-27.552-5.643-29.73-23.065-1.945-14.728 8.336-28.067 23.062-29.734 16.116-1.946 31.12-7.503 44.178-15.284-26.114 5.713-58.712 3.138-88.079-11.115-13.336-6.669-18.893-22.509-12.224-35.848 6.389-13.061 22.505-18.619 35.565-12.227 20.295 10.149 44.147 11.199 64.739 3.89-42.606 0-71.208-20.475-85.578-50.576-8.576-17.899 5.148-38.071 23.617-38.071-18.429 0-32.211-20.136-23.617-38.071 14.033-29.396 44.039-50.887 81.966-50.854l92.803 8.615 66.406-33.347c9.408-4.704 19.828-.354 23.894 7.781l44.455 88.926zm-229.227-18.618c-13.893 0-26.119 7.781-32.231 20.286-4.446 9.449-13.614 15.006-23.339 15.284 9.725.278 18.893 5.836 23.339 15.284 6.112 12.505 18.338 20.286 32.231 20.286a35.46 35.46 0 0 0 35.565-35.57c0-21.429-17.808-35.57-35.565-35.57z\"],\n    \"anchor\": [576, 512, [], \"f13d\", \"M12.971 352h32.394C67.172 454.735 181.944 512 288 512c106.229 0 220.853-57.38 242.635-160h32.394c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0l-67.029 67.029c-7.56 7.56-2.206 20.485 8.485 20.485h35.146c-20.29 54.317-84.963 86.588-144.117 94.015V256h52c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-52v-5.47c37.281-13.178 63.995-48.725 64-90.518C384.005 43.772 341.605.738 289.37.01 235.723-.739 192 42.525 192 96c0 41.798 26.716 77.35 64 90.53V192h-52c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v190.015c-58.936-7.399-123.82-39.679-144.117-94.015h35.146c10.691 0 16.045-12.926 8.485-20.485l-67.029-67.029c-4.686-4.686-12.284-4.686-16.971 0L4.485 331.515C-3.074 339.074 2.28 352 12.971 352zM288 64c17.645 0 32 14.355 32 32s-14.355 32-32 32-32-14.355-32-32 14.355-32 32-32z\"],\n    \"angle-double-down\": [320, 512, [], \"f103\", \"M143 256.3L7 120.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0L313 86.3c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.4 9.5-24.6 9.5-34 .1zm34 192l136-136c9.4-9.4 9.4-24.6 0-33.9l-22.6-22.6c-9.4-9.4-24.6-9.4-33.9 0L160 352.1l-96.4-96.4c-9.4-9.4-24.6-9.4-33.9 0L7 278.3c-9.4 9.4-9.4 24.6 0 33.9l136 136c9.4 9.5 24.6 9.5 34 .1z\"],\n    \"angle-double-left\": [448, 512, [], \"f100\", \"M223.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L319.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L393.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34zm-192 34l136 136c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9L127.9 256l96.4-96.4c9.4-9.4 9.4-24.6 0-33.9L201.7 103c-9.4-9.4-24.6-9.4-33.9 0l-136 136c-9.5 9.4-9.5 24.6-.1 34z\"],\n    \"angle-double-right\": [448, 512, [], \"f101\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34zm192-34l-136-136c-9.4-9.4-24.6-9.4-33.9 0l-22.6 22.6c-9.4 9.4-9.4 24.6 0 33.9l96.4 96.4-96.4 96.4c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l136-136c9.4-9.2 9.4-24.4 0-33.8z\"],\n    \"angle-double-up\": [320, 512, [], \"f102\", \"M177 255.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 351.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 425.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1zm-34-192L7 199.7c-9.4 9.4-9.4 24.6 0 33.9l22.6 22.6c9.4 9.4 24.6 9.4 33.9 0l96.4-96.4 96.4 96.4c9.4 9.4 24.6 9.4 33.9 0l22.6-22.6c9.4-9.4 9.4-24.6 0-33.9l-136-136c-9.2-9.4-24.4-9.4-33.8 0z\"],\n    \"angle-down\": [320, 512, [], \"f107\", \"M143 352.3L7 216.3c-9.4-9.4-9.4-24.6 0-33.9l22.6-22.6c9.4-9.4 24.6-9.4 33.9 0l96.4 96.4 96.4-96.4c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9l-136 136c-9.2 9.4-24.4 9.4-33.8 0z\"],\n    \"angle-left\": [256, 512, [], \"f104\", \"M31.7 239l136-136c9.4-9.4 24.6-9.4 33.9 0l22.6 22.6c9.4 9.4 9.4 24.6 0 33.9L127.9 256l96.4 96.4c9.4 9.4 9.4 24.6 0 33.9L201.7 409c-9.4 9.4-24.6 9.4-33.9 0l-136-136c-9.5-9.4-9.5-24.6-.1-34z\"],\n    \"angle-right\": [256, 512, [], \"f105\", \"M224.3 273l-136 136c-9.4 9.4-24.6 9.4-33.9 0l-22.6-22.6c-9.4-9.4-9.4-24.6 0-33.9l96.4-96.4-96.4-96.4c-9.4-9.4-9.4-24.6 0-33.9L54.3 103c9.4-9.4 24.6-9.4 33.9 0l136 136c9.5 9.4 9.5 24.6.1 34z\"],\n    \"angle-up\": [320, 512, [], \"f106\", \"M177 159.7l136 136c9.4 9.4 9.4 24.6 0 33.9l-22.6 22.6c-9.4 9.4-24.6 9.4-33.9 0L160 255.9l-96.4 96.4c-9.4 9.4-24.6 9.4-33.9 0L7 329.7c-9.4-9.4-9.4-24.6 0-33.9l136-136c9.4-9.5 24.6-9.5 34-.1z\"],\n    \"angry\": [496, 512, [], \"f556\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 240c0-9.3 4.1-17.5 10.5-23.4l-31-9.3c-8.5-2.5-13.3-11.5-10.7-19.9 2.5-8.5 11.4-13.2 19.9-10.7l80 24c8.5 2.5 13.3 11.5 10.7 19.9-2.1 6.9-8.4 11.4-15.3 11.4-.5 0-1.1-.2-1.7-.2.7 2.7 1.7 5.3 1.7 8.2 0 17.7-14.3 32-32 32S136 257.7 136 240zm168 154.2c-27.8-33.4-84.2-33.4-112.1 0-13.5 16.3-38.2-4.2-24.6-20.5 20-24 49.4-37.8 80.6-37.8s60.6 13.8 80.6 37.8c13.8 16.5-11.1 36.6-24.5 20.5zm76.6-186.9l-31 9.3c6.3 5.8 10.5 14.1 10.5 23.4 0 17.7-14.3 32-32 32s-32-14.3-32-32c0-2.9.9-5.6 1.7-8.2-.6.1-1.1.2-1.7.2-6.9 0-13.2-4.5-15.3-11.4-2.5-8.5 2.3-17.4 10.7-19.9l80-24c8.4-2.5 17.4 2.3 19.9 10.7 2.5 8.5-2.3 17.4-10.8 19.9z\"],\n    \"ankh\": [320, 512, [], \"f644\", \"M296 256h-44.62C272.46 222.01 288 181.65 288 144 288 55.63 230.69 0 160 0S32 55.63 32 144c0 37.65 15.54 78.01 36.62 112H24c-13.25 0-24 10.74-24 24v32c0 13.25 10.75 24 24 24h96v152c0 13.25 10.75 24 24 24h32c13.25 0 24-10.75 24-24V336h96c13.25 0 24-10.75 24-24v-32c0-13.26-10.75-24-24-24zM160 80c29.61 0 48 24.52 48 64 0 34.66-27.14 78.14-48 100.87-20.86-22.72-48-66.21-48-100.87 0-39.48 18.39-64 48-64z\"],\n    \"apple-alt\": [448, 512, [], \"f5d1\", \"M350.85 129c25.97 4.67 47.27 18.67 63.92 42 14.65 20.67 24.64 46.67 29.96 78 4.67 28.67 4.32 57.33-1 86-7.99 47.33-23.97 87-47.94 119-28.64 38.67-64.59 58-107.87 58-10.66 0-22.3-3.33-34.96-10-8.66-5.33-18.31-8-28.97-8s-20.3 2.67-28.97 8c-12.66 6.67-24.3 10-34.96 10-43.28 0-79.23-19.33-107.87-58-23.97-32-39.95-71.67-47.94-119-5.32-28.67-5.67-57.33-1-86 5.32-31.33 15.31-57.33 29.96-78 16.65-23.33 37.95-37.33 63.92-42 15.98-2.67 37.95-.33 65.92 7 23.97 6.67 44.28 14.67 60.93 24 16.65-9.33 36.96-17.33 60.93-24 27.98-7.33 49.96-9.67 65.94-7zm-54.94-41c-9.32 8.67-21.65 15-36.96 19-10.66 3.33-22.3 5-34.96 5l-14.98-1c-1.33-9.33-1.33-20 0-32 2.67-24 10.32-42.33 22.97-55 9.32-8.67 21.65-15 36.96-19 10.66-3.33 22.3-5 34.96-5l14.98 1 1 15c0 12.67-1.67 24.33-4.99 35-3.99 15.33-10.31 27.67-18.98 37z\"],\n    \"archive\": [512, 512, [], \"f187\", \"M32 448c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V160H32v288zm160-212c0-6.6 5.4-12 12-12h104c6.6 0 12 5.4 12 12v8c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-8zM480 32H32C14.3 32 0 46.3 0 64v48c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16V64c0-17.7-14.3-32-32-32z\"],\n    \"archway\": [576, 512, [], \"f557\", \"M560 448h-16V96H32v352H16.02c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16H176c8.84 0 16-7.16 16-16V320c0-53.02 42.98-96 96-96s96 42.98 96 96l.02 160v16c0 8.84 7.16 16 16 16H560c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm0-448H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h544c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"arrow-alt-circle-down\": [512, 512, [], \"f358\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM212 140v116h-70.9c-10.7 0-16.1 13-8.5 20.5l114.9 114.3c4.7 4.7 12.2 4.7 16.9 0l114.9-114.3c7.6-7.6 2.2-20.5-8.5-20.5H300V140c0-6.6-5.4-12-12-12h-64c-6.6 0-12 5.4-12 12z\"],\n    \"arrow-alt-circle-left\": [512, 512, [], \"f359\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm116-292H256v-70.9c0-10.7-13-16.1-20.5-8.5L121.2 247.5c-4.7 4.7-4.7 12.2 0 16.9l114.3 114.9c7.6 7.6 20.5 2.2 20.5-8.5V300h116c6.6 0 12-5.4 12-12v-64c0-6.6-5.4-12-12-12z\"],\n    \"arrow-alt-circle-right\": [512, 512, [], \"f35a\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zM140 300h116v70.9c0 10.7 13 16.1 20.5 8.5l114.3-114.9c4.7-4.7 4.7-12.2 0-16.9l-114.3-115c-7.6-7.6-20.5-2.2-20.5 8.5V212H140c-6.6 0-12 5.4-12 12v64c0 6.6 5.4 12 12 12z\"],\n    \"arrow-alt-circle-up\": [512, 512, [], \"f35b\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm292 116V256h70.9c10.7 0 16.1-13 8.5-20.5L264.5 121.2c-4.7-4.7-12.2-4.7-16.9 0l-115 114.3c-7.6 7.6-2.2 20.5 8.5 20.5H212v116c0 6.6 5.4 12 12 12h64c6.6 0 12-5.4 12-12z\"],\n    \"arrow-circle-down\": [512, 512, [], \"f0ab\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zm-143.6-28.9L288 302.6V120c0-13.3-10.7-24-24-24h-16c-13.3 0-24 10.7-24 24v182.6l-72.4-75.5c-9.3-9.7-24.8-9.9-34.3-.4l-10.9 11c-9.4 9.4-9.4 24.6 0 33.9L239 404.3c9.4 9.4 24.6 9.4 33.9 0l132.7-132.7c9.4-9.4 9.4-24.6 0-33.9l-10.9-11c-9.5-9.5-25-9.3-34.3.4z\"],\n    \"arrow-circle-left\": [512, 512, [], \"f0a8\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zm28.9-143.6L209.4 288H392c13.3 0 24-10.7 24-24v-16c0-13.3-10.7-24-24-24H209.4l75.5-72.4c9.7-9.3 9.9-24.8.4-34.3l-11-10.9c-9.4-9.4-24.6-9.4-33.9 0L107.7 239c-9.4 9.4-9.4 24.6 0 33.9l132.7 132.7c9.4 9.4 24.6 9.4 33.9 0l11-10.9c9.5-9.5 9.3-25-.4-34.3z\"],\n    \"arrow-circle-right\": [512, 512, [], \"f0a9\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm-28.9 143.6l75.5 72.4H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h182.6l-75.5 72.4c-9.7 9.3-9.9 24.8-.4 34.3l11 10.9c9.4 9.4 24.6 9.4 33.9 0L404.3 273c9.4-9.4 9.4-24.6 0-33.9L271.6 106.3c-9.4-9.4-24.6-9.4-33.9 0l-11 10.9c-9.5 9.6-9.3 25.1.4 34.4z\"],\n    \"arrow-circle-up\": [512, 512, [], \"f0aa\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm143.6 28.9l72.4-75.5V392c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24V209.4l72.4 75.5c9.3 9.7 24.8 9.9 34.3.4l10.9-11c9.4-9.4 9.4-24.6 0-33.9L273 107.7c-9.4-9.4-24.6-9.4-33.9 0L106.3 240.4c-9.4 9.4-9.4 24.6 0 33.9l10.9 11c9.6 9.5 25.1 9.3 34.4-.4z\"],\n    \"arrow-down\": [448, 512, [], \"f063\", \"M413.1 222.5l22.2 22.2c9.4 9.4 9.4 24.6 0 33.9L241 473c-9.4 9.4-24.6 9.4-33.9 0L12.7 278.6c-9.4-9.4-9.4-24.6 0-33.9l22.2-22.2c9.5-9.5 25-9.3 34.3.4L184 343.4V56c0-13.3 10.7-24 24-24h32c13.3 0 24 10.7 24 24v287.4l114.8-120.5c9.3-9.8 24.8-10 34.3-.4z\"],\n    \"arrow-left\": [448, 512, [], \"f060\", \"M257.5 445.1l-22.2 22.2c-9.4 9.4-24.6 9.4-33.9 0L7 273c-9.4-9.4-9.4-24.6 0-33.9L201.4 44.7c9.4-9.4 24.6-9.4 33.9 0l22.2 22.2c9.5 9.5 9.3 25-.4 34.3L136.6 216H424c13.3 0 24 10.7 24 24v32c0 13.3-10.7 24-24 24H136.6l120.5 114.8c9.8 9.3 10 24.8.4 34.3z\"],\n    \"arrow-right\": [448, 512, [], \"f061\", \"M190.5 66.9l22.2-22.2c9.4-9.4 24.6-9.4 33.9 0L441 239c9.4 9.4 9.4 24.6 0 33.9L246.6 467.3c-9.4 9.4-24.6 9.4-33.9 0l-22.2-22.2c-9.5-9.5-9.3-25 .4-34.3L311.4 296H24c-13.3 0-24-10.7-24-24v-32c0-13.3 10.7-24 24-24h287.4L190.9 101.2c-9.8-9.3-10-24.8-.4-34.3z\"],\n    \"arrow-up\": [448, 512, [], \"f062\", \"M34.9 289.5l-22.2-22.2c-9.4-9.4-9.4-24.6 0-33.9L207 39c9.4-9.4 24.6-9.4 33.9 0l194.3 194.3c9.4 9.4 9.4 24.6 0 33.9L413 289.4c-9.5 9.5-25 9.3-34.3-.4L264 168.6V456c0 13.3-10.7 24-24 24h-32c-13.3 0-24-10.7-24-24V168.6L69.2 289.1c-9.3 9.8-24.8 10-34.3.4z\"],\n    \"arrows-alt\": [512, 512, [], \"f0b2\", \"M352.201 425.775l-79.196 79.196c-9.373 9.373-24.568 9.373-33.941 0l-79.196-79.196c-15.119-15.119-4.411-40.971 16.971-40.97h51.162L228 284H127.196v51.162c0 21.382-25.851 32.09-40.971 16.971L7.029 272.937c-9.373-9.373-9.373-24.569 0-33.941L86.225 159.8c15.119-15.119 40.971-4.411 40.971 16.971V228H228V127.196h-51.23c-21.382 0-32.09-25.851-16.971-40.971l79.196-79.196c9.373-9.373 24.568-9.373 33.941 0l79.196 79.196c15.119 15.119 4.411 40.971-16.971 40.971h-51.162V228h100.804v-51.162c0-21.382 25.851-32.09 40.97-16.971l79.196 79.196c9.373 9.373 9.373 24.569 0 33.941L425.773 352.2c-15.119 15.119-40.971 4.411-40.97-16.971V284H284v100.804h51.23c21.382 0 32.09 25.851 16.971 40.971z\"],\n    \"arrows-alt-h\": [512, 512, [], \"f337\", \"M377.941 169.941V216H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.568 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296h243.882v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.568 0-33.941l-86.059-86.059c-15.119-15.12-40.971-4.412-40.971 16.97z\"],\n    \"arrows-alt-v\": [256, 512, [], \"f338\", \"M214.059 377.941H168V134.059h46.059c21.382 0 32.09-25.851 16.971-40.971L144.971 7.029c-9.373-9.373-24.568-9.373-33.941 0L24.971 93.088c-15.119 15.119-4.411 40.971 16.971 40.971H88v243.882H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.568 9.373 33.941 0l86.059-86.059c15.12-15.119 4.412-40.971-16.97-40.971z\"],\n    \"assistive-listening-systems\": [512, 512, [], \"f2a2\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm-80 236c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zM32 448c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm480-187.993c0-1.518-.012-3.025-.045-4.531C510.076 140.525 436.157 38.47 327.994 1.511c-14.633-4.998-30.549 2.809-35.55 17.442-5 14.633 2.81 30.549 17.442 35.55 85.906 29.354 144.61 110.513 146.077 201.953l.003.188c.026 1.118.033 2.236.033 3.363 0 15.464 12.536 28 28 28s28.001-12.536 28.001-28zM152.971 439.029l-80-80L39.03 392.97l80 80 33.941-33.941z\"],\n    \"asterisk\": [512, 512, [], \"f069\", \"M478.21 334.093L336 256l142.21-78.093c11.795-6.477 15.961-21.384 9.232-33.037l-19.48-33.741c-6.728-11.653-21.72-15.499-33.227-8.523L296 186.718l3.475-162.204C299.763 11.061 288.937 0 275.48 0h-38.96c-13.456 0-24.283 11.061-23.994 24.514L216 186.718 77.265 102.607c-11.506-6.976-26.499-3.13-33.227 8.523l-19.48 33.741c-6.728 11.653-2.562 26.56 9.233 33.037L176 256 33.79 334.093c-11.795 6.477-15.961 21.384-9.232 33.037l19.48 33.741c6.728 11.653 21.721 15.499 33.227 8.523L216 325.282l-3.475 162.204C212.237 500.939 223.064 512 236.52 512h38.961c13.456 0 24.283-11.061 23.995-24.514L296 325.282l138.735 84.111c11.506 6.976 26.499 3.13 33.227-8.523l19.48-33.741c6.728-11.653 2.563-26.559-9.232-33.036z\"],\n    \"at\": [512, 512, [], \"f1fa\", \"M256 8C118.941 8 8 118.919 8 256c0 137.059 110.919 248 248 248 48.154 0 95.342-14.14 135.408-40.223 12.005-7.815 14.625-24.288 5.552-35.372l-10.177-12.433c-7.671-9.371-21.179-11.667-31.373-5.129C325.92 429.757 291.314 440 256 440c-101.458 0-184-82.542-184-184S154.542 72 256 72c100.139 0 184 57.619 184 160 0 38.786-21.093 79.742-58.17 83.693-17.349-.454-16.91-12.857-13.476-30.024l23.433-121.11C394.653 149.75 383.308 136 368.225 136h-44.981a13.518 13.518 0 0 0-13.432 11.993l-.01.092c-14.697-17.901-40.448-21.775-59.971-21.775-74.58 0-137.831 62.234-137.831 151.46 0 65.303 36.785 105.87 96 105.87 26.984 0 57.369-15.637 74.991-38.333 9.522 34.104 40.613 34.103 70.71 34.103C462.609 379.41 504 307.798 504 232 504 95.653 394.023 8 256 8zm-21.68 304.43c-22.249 0-36.07-15.623-36.07-40.771 0-44.993 30.779-72.729 58.63-72.729 22.292 0 35.601 15.241 35.601 40.77 0 45.061-33.875 72.73-58.161 72.73z\"],\n    \"atlas\": [448, 512, [], \"f558\", \"M318.38 208h-39.09c-1.49 27.03-6.54 51.35-14.21 70.41 27.71-13.24 48.02-39.19 53.3-70.41zm0-32c-5.29-31.22-25.59-57.17-53.3-70.41 7.68 19.06 12.72 43.38 14.21 70.41h39.09zM224 97.31c-7.69 7.45-20.77 34.42-23.43 78.69h46.87c-2.67-44.26-15.75-71.24-23.44-78.69zm-41.08 8.28c-27.71 13.24-48.02 39.19-53.3 70.41h39.09c1.49-27.03 6.53-51.35 14.21-70.41zm0 172.82c-7.68-19.06-12.72-43.38-14.21-70.41h-39.09c5.28 31.22 25.59 57.17 53.3 70.41zM247.43 208h-46.87c2.66 44.26 15.74 71.24 23.43 78.69 7.7-7.45 20.78-34.43 23.44-78.69zM448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM224 64c70.69 0 128 57.31 128 128s-57.31 128-128 128S96 262.69 96 192 153.31 64 224 64zm160 384H96c-19.2 0-32-12.8-32-32s16-32 32-32h288v64z\"],\n    \"atom\": [448, 512, [], \"f5d2\", \"M413.03 256c40.13-54.89 41.51-98.62 25.14-128-10.91-19.52-40.54-50.73-116.33-41.88C300.36 34.89 267.64 0 224 0s-76.36 34.89-97.84 86.12C50.43 77.34 20.73 108.48 9.83 128c-16.38 29.4-15 73.09 25.14 128-40.13 54.89-41.51 98.62-25.14 128 29.21 52.34 101.68 43.58 116.33 41.88C147.63 477.1 180.36 512 224 512s76.37-34.9 97.84-86.12c14.64 1.7 87.11 10.46 116.33-41.88 16.38-29.4 15-73.09-25.14-128zM63.38 352c-4.03-7.21-.19-24.8 14.95-48.29 6.96 6.53 14.2 12.89 21.87 19.18 1.71 13.71 4 27.08 6.76 40.08-24.56.89-39.89-4.37-43.58-10.97zm36.82-162.88c-7.66 6.29-14.9 12.65-21.87 19.18-15.13-23.5-18.97-41.09-14.95-48.3 3.41-6.14 16.39-11.47 37.92-11.47 1.71 0 3.87.3 5.69.37a472.191 472.191 0 0 0-6.79 40.22zM224 64c9.47 0 22.2 13.52 33.86 37.26-11.19 3.7-22.44 8-33.86 12.86-11.42-4.86-22.67-9.16-33.86-12.86C201.8 77.52 214.53 64 224 64zm0 384c-9.47 0-22.2-13.52-33.86-37.26 11.19-3.7 22.44-8 33.86-12.86 11.42 4.86 22.67 9.16 33.86 12.86C246.2 434.48 233.47 448 224 448zm62.5-157.33c-26.7 19.08-46.14 29.33-62.5 37.48-16.35-8.14-35.8-18.41-62.5-37.48-1.99-27.79-1.99-41.54 0-69.33 26.67-19.05 46.13-29.32 62.5-37.48 16.39 8.17 35.86 18.44 62.5 37.48 1.98 27.78 1.99 41.53 0 69.33zM384.62 352c-3.67 6.62-19 11.82-43.58 10.95 2.76-13 5.05-26.37 6.76-40.06 7.66-6.29 14.9-12.65 21.87-19.18 15.13 23.49 18.97 41.08 14.95 48.29zm-14.95-143.71c-6.96-6.53-14.2-12.89-21.87-19.18a473.535 473.535 0 0 0-6.79-40.22c1.82-.07 3.97-.37 5.69-.37 21.52 0 34.51 5.34 37.92 11.47 4.02 7.22.18 24.81-14.95 48.3zM224 224c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"audio-description\": [512, 512, [], \"f29e\", \"M162.925 238.709l8.822 30.655h-25.606l9.041-30.652c1.277-4.421 2.651-9.994 3.872-15.245 1.22 5.251 2.594 10.823 3.871 15.242zm166.474-32.099h-14.523v98.781h14.523c29.776 0 46.175-17.678 46.175-49.776 0-32.239-17.49-49.005-46.175-49.005zM512 112v288c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48zM245.459 336.139l-57.097-168A12.001 12.001 0 0 0 177 160h-35.894a12.001 12.001 0 0 0-11.362 8.139l-57.097 168C70.003 343.922 75.789 352 84.009 352h29.133a12 12 0 0 0 11.535-8.693l8.574-29.906h51.367l8.793 29.977A12 12 0 0 0 204.926 352h29.172c8.22 0 14.006-8.078 11.361-15.861zm184.701-80.525c0-58.977-37.919-95.614-98.96-95.614h-57.366c-6.627 0-12 5.373-12 12v168c0 6.627 5.373 12 12 12H331.2c61.041 0 98.96-36.933 98.96-96.386z\"],\n    \"award\": [384, 512, [], \"f559\", \"M97.12 362.63c-8.69-8.69-4.16-6.24-25.12-11.85-9.51-2.55-17.87-7.45-25.43-13.32L1.2 448.7c-4.39 10.77 3.81 22.47 15.43 22.03l52.69-2.01L105.56 507c8 8.44 22.04 5.81 26.43-4.96l52.05-127.62c-10.84 6.04-22.87 9.58-35.31 9.58-19.5 0-37.82-7.59-51.61-21.37zM382.8 448.7l-45.37-111.24c-7.56 5.88-15.92 10.77-25.43 13.32-21.07 5.64-16.45 3.18-25.12 11.85-13.79 13.78-32.12 21.37-51.62 21.37-12.44 0-24.47-3.55-35.31-9.58L252 502.04c4.39 10.77 18.44 13.4 26.43 4.96l36.25-38.28 52.69 2.01c11.62.44 19.82-11.27 15.43-22.03zM263 340c15.28-15.55 17.03-14.21 38.79-20.14 13.89-3.79 24.75-14.84 28.47-28.98 7.48-28.4 5.54-24.97 25.95-45.75 10.17-10.35 14.14-25.44 10.42-39.58-7.47-28.38-7.48-24.42 0-52.83 3.72-14.14-.25-29.23-10.42-39.58-20.41-20.78-18.47-17.36-25.95-45.75-3.72-14.14-14.58-25.19-28.47-28.98-27.88-7.61-24.52-5.62-44.95-26.41-10.17-10.35-25-14.4-38.89-10.61-27.87 7.6-23.98 7.61-51.9 0-13.89-3.79-28.72.25-38.89 10.61-20.41 20.78-17.05 18.8-44.94 26.41-13.89 3.79-24.75 14.84-28.47 28.98-7.47 28.39-5.54 24.97-25.95 45.75-10.17 10.35-14.15 25.44-10.42 39.58 7.47 28.36 7.48 24.4 0 52.82-3.72 14.14.25 29.23 10.42 39.59 20.41 20.78 18.47 17.35 25.95 45.75 3.72 14.14 14.58 25.19 28.47 28.98C104.6 325.96 106.27 325 121 340c13.23 13.47 33.84 15.88 49.74 5.82a39.676 39.676 0 0 1 42.53 0c15.89 10.06 36.5 7.65 49.73-5.82zM97.66 175.96c0-53.03 42.24-96.02 94.34-96.02s94.34 42.99 94.34 96.02-42.24 96.02-94.34 96.02-94.34-42.99-94.34-96.02z\"],\n    \"baby\": [384, 512, [], \"f77c\", \"M192 160c44.2 0 80-35.8 80-80S236.2 0 192 0s-80 35.8-80 80 35.8 80 80 80zm-53.4 248.8l25.6-32-61.5-51.2L56.8 383c-11.4 14.2-11.7 34.4-.8 49l48 64c7.9 10.5 19.9 16 32 16 8.3 0 16.8-2.6 24-8 17.7-13.2 21.2-38.3 8-56l-29.4-39.2zm142.7-83.2l-61.5 51.2 25.6 32L216 448c-13.2 17.7-9.7 42.8 8 56 7.2 5.4 15.6 8 24 8 12.2 0 24.2-5.5 32-16l48-64c10.9-14.6 10.6-34.8-.8-49l-45.9-57.4zM376.7 145c-12.7-18.1-37.6-22.4-55.7-9.8l-40.6 28.5c-52.7 37-124.2 37-176.8 0L63 135.3C44.9 122.6 20 127 7.3 145-5.4 163.1-1 188 17 200.7l40.6 28.5c17 11.9 35.4 20.9 54.4 27.9V288h160v-30.8c19-7 37.4-16 54.4-27.9l40.6-28.5c18.1-12.8 22.4-37.7 9.7-55.8z\"],\n    \"baby-carriage\": [512, 512, [], \"f77d\", \"M144.8 17c-11.3-17.8-37.2-22.8-54-9.4C35.3 51.9 0 118 0 192h256L144.8 17zM496 96h-48c-35.3 0-64 28.7-64 64v64H0c0 50.6 23 96.4 60.3 130.7C25.7 363.6 0 394.7 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-8.9-1.8-17.2-4.4-25.2 21.6 5.9 44.6 9.2 68.4 9.2s46.9-3.3 68.4-9.2c-2.7 8-4.4 16.3-4.4 25.2 0 44.2 35.8 80 80 80s80-35.8 80-80c0-37.3-25.7-68.4-60.3-77.3C425 320.4 448 274.6 448 224v-64h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM80 464c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm320-32c0 17.6-14.4 32-32 32s-32-14.4-32-32 14.4-32 32-32 32 14.4 32 32z\"],\n    \"backspace\": [640, 512, [], \"f55a\", \"M576 64H205.26A63.97 63.97 0 0 0 160 82.75L9.37 233.37c-12.5 12.5-12.5 32.76 0 45.25L160 429.25c12 12 28.28 18.75 45.25 18.75H576c35.35 0 64-28.65 64-64V128c0-35.35-28.65-64-64-64zm-84.69 254.06c6.25 6.25 6.25 16.38 0 22.63l-22.62 22.62c-6.25 6.25-16.38 6.25-22.63 0L384 301.25l-62.06 62.06c-6.25 6.25-16.38 6.25-22.63 0l-22.62-22.62c-6.25-6.25-6.25-16.38 0-22.63L338.75 256l-62.06-62.06c-6.25-6.25-6.25-16.38 0-22.63l22.62-22.62c6.25-6.25 16.38-6.25 22.63 0L384 210.75l62.06-62.06c6.25-6.25 16.38-6.25 22.63 0l22.62 22.62c6.25 6.25 6.25 16.38 0 22.63L429.25 256l62.06 62.06z\"],\n    \"backward\": [512, 512, [], \"f04a\", \"M11.5 280.6l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2zm256 0l192 160c20.6 17.2 52.5 2.8 52.5-24.6V96c0-27.4-31.9-41.8-52.5-24.6l-192 160c-15.3 12.8-15.3 36.4 0 49.2z\"],\n    \"bacon\": [576, 512, [], \"f7e5\", \"M218.92 336.39c34.89-34.89 44.2-59.7 54.05-86 10.61-28.29 21.59-57.54 61.37-97.34s69.05-50.77 97.35-61.38c23.88-9 46.64-17.68 76.79-45.37L470.81 8.91a31 31 0 0 0-40.18-2.83c-13.64 10.1-25.15 14.39-41 20.3C247 79.52 209.26 191.29 200.65 214.1c-29.75 78.83-89.55 94.68-98.72 98.09-24.86 9.26-54.73 20.38-91.07 50.36C-3 374-3.63 395 9.07 407.61l35.76 35.51C80 410.52 107 400.15 133 390.39c26.27-9.84 51.06-19.12 85.92-54zm348-232l-35.75-35.51c-35.19 32.63-62.18 43-88.25 52.79-26.26 9.85-51.06 19.16-85.95 54s-44.19 59.69-54 86C292.33 290 281.34 319.22 241.55 359s-69 50.73-97.3 61.32c-23.86 9-46.61 17.66-76.72 45.33l37.68 37.43a31 31 0 0 0 40.18 2.82c13.6-10.06 25.09-14.34 40.94-20.24 142.2-53 180-164.1 188.94-187.69C405 219.18 464.8 203.3 474 199.86c24.87-9.27 54.74-20.4 91.11-50.41 13.89-11.4 14.52-32.45 1.82-45.05z\"],\n    \"balance-scale\": [640, 512, [], \"f24e\", \"M256 336h-.02c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0C-2.06 328.75.02 320.33.02 336H0c0 44.18 57.31 80 128 80s128-35.82 128-80zM128 176l72 144H56l72-144zm511.98 160c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 320l72-144 72 144H440zm88 128H352V153.25c23.51-10.29 41.16-31.48 46.39-57.25H528c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H383.64C369.04 12.68 346.09 0 320 0s-49.04 12.68-63.64 32H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h129.61c5.23 25.76 22.87 46.96 46.39 57.25V448H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"balance-scale-left\": [640, 512, [], \"f515\", \"M528 448H352V153.25c20.42-8.94 36.1-26.22 43.38-47.47l132-44.26c8.38-2.81 12.89-11.88 10.08-20.26l-10.17-30.34C524.48 2.54 515.41-1.97 507.03.84L389.11 40.37C375.3 16.36 349.69 0 320 0c-44.18 0-80 35.82-80 80 0 3.43.59 6.71 1.01 10.03l-128.39 43.05c-8.38 2.81-12.89 11.88-10.08 20.26l10.17 30.34c2.81 8.38 11.88 12.89 20.26 10.08l142.05-47.63c4.07 2.77 8.43 5.12 12.99 7.12V496c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16v-32c-.01-8.84-7.17-16-16.01-16zm111.98-144c0-16.18 1.34-8.73-85.05-181.51-17.65-35.29-68.19-35.36-85.87 0-87.12 174.26-85.04 165.84-85.04 181.51H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02zM440 288l72-144 72 144H440zm-269.07-37.51c-17.65-35.29-68.19-35.36-85.87 0C-2.06 424.75.02 416.33.02 432H0c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-16.18 1.34-8.73-85.05-181.51zM56 416l72-144 72 144H56z\"],\n    \"balance-scale-right\": [640, 512, [], \"f516\", \"M96 464v32c0 8.84 7.16 16 16 16h224c8.84 0 16-7.16 16-16V153.25c4.56-2 8.92-4.35 12.99-7.12l142.05 47.63c8.38 2.81 17.45-1.71 20.26-10.08l10.17-30.34c2.81-8.38-1.71-17.45-10.08-20.26l-128.4-43.05c.42-3.32 1.01-6.6 1.01-10.03 0-44.18-35.82-80-80-80-29.69 0-55.3 16.36-69.11 40.37L132.96.83c-8.38-2.81-17.45 1.71-20.26 10.08l-10.17 30.34c-2.81 8.38 1.71 17.45 10.08 20.26l132 44.26c7.28 21.25 22.96 38.54 43.38 47.47V448H112c-8.84 0-16 7.16-16 16zM0 304c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0C-1.32 295.27.02 287.82.02 304H0zm56-16l72-144 72 144H56zm328.02 144H384c0 44.18 57.31 80 128 80s128-35.82 128-80h-.02c0-15.67 2.08-7.25-85.05-181.51-17.68-35.36-68.22-35.29-85.87 0-86.38 172.78-85.04 165.33-85.04 181.51zM440 416l72-144 72 144H440z\"],\n    \"ban\": [512, 512, [], \"f05e\", \"M256 8C119.034 8 8 119.033 8 256s111.034 248 248 248 248-111.034 248-248S392.967 8 256 8zm130.108 117.892c65.448 65.448 70 165.481 20.677 235.637L150.47 105.216c70.204-49.356 170.226-44.735 235.638 20.676zM125.892 386.108c-65.448-65.448-70-165.481-20.677-235.637L361.53 406.784c-70.203 49.356-170.226 44.736-235.638-20.676z\"],\n    \"band-aid\": [640, 512, [], \"f462\", \"M0 160v192c0 35.3 28.7 64 64 64h96V96H64c-35.3 0-64 28.7-64 64zm576-64h-96v320h96c35.3 0 64-28.7 64-64V160c0-35.3-28.7-64-64-64zM192 416h256V96H192v320zm176-232c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm0 96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24z\"],\n    \"barcode\": [512, 512, [], \"f02a\", \"M0 448V64h18v384H0zm26.857-.273V64H36v383.727h-9.143zm27.143 0V64h8.857v383.727H54zm44.857 0V64h8.857v383.727h-8.857zm36 0V64h17.714v383.727h-17.714zm44.857 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm18 0V64h8.857v383.727h-8.857zm35.715 0V64h18v383.727h-18zm44.857 0V64h18v383.727h-18zm35.999 0V64h18.001v383.727h-18.001zm36.001 0V64h18.001v383.727h-18.001zm26.857 0V64h18v383.727h-18zm45.143 0V64h26.857v383.727h-26.857zm35.714 0V64h9.143v383.727H476zm18 .273V64h18v384h-18z\"],\n    \"bars\": [448, 512, [], \"f0c9\", \"M16 132h416c8.837 0 16-7.163 16-16V76c0-8.837-7.163-16-16-16H16C7.163 60 0 67.163 0 76v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16zm0 160h416c8.837 0 16-7.163 16-16v-40c0-8.837-7.163-16-16-16H16c-8.837 0-16 7.163-16 16v40c0 8.837 7.163 16 16 16z\"],\n    \"baseball-ball\": [496, 512, [], \"f433\", \"M368.5 363.9l28.8-13.9c11.1 22.9 26 43.2 44.1 60.9 34-42.5 54.5-96.3 54.5-154.9 0-58.5-20.4-112.2-54.2-154.6-17.8 17.3-32.6 37.1-43.6 59.5l-28.7-14.1c12.8-26 30-49 50.8-69C375.6 34.7 315 8 248 8 181.1 8 120.5 34.6 75.9 77.7c20.7 19.9 37.9 42.9 50.7 68.8l-28.7 14.1c-11-22.3-25.7-42.1-43.5-59.4C20.4 143.7 0 197.4 0 256c0 58.6 20.4 112.3 54.4 154.7 18.2-17.7 33.2-38 44.3-61l28.8 13.9c-12.9 26.7-30.3 50.3-51.5 70.7 44.5 43.1 105.1 69.7 172 69.7 66.8 0 127.3-26.5 171.9-69.5-21.1-20.4-38.5-43.9-51.4-70.6zm-228.3-32l-30.5-9.8c14.9-46.4 12.7-93.8-.6-134l30.4-10c15 45.6 18 99.9.7 153.8zm216.3-153.4l30.4 10c-13.2 40.1-15.5 87.5-.6 134l-30.5 9.8c-17.3-54-14.3-108.3.7-153.8z\"],\n    \"basketball-ball\": [496, 512, [], \"f434\", \"M212.3 10.3c-43.8 6.3-86.2 24.1-122.2 53.8l77.4 77.4c27.8-35.8 43.3-81.2 44.8-131.2zM248 222L405.9 64.1c-42.4-35-93.6-53.5-145.5-56.1-1.2 63.9-21.5 122.3-58.7 167.7L248 222zM56.1 98.1c-29.7 36-47.5 78.4-53.8 122.2 50-1.5 95.5-17 131.2-44.8L56.1 98.1zm272.2 204.2c45.3-37.1 103.7-57.4 167.7-58.7-2.6-51.9-21.1-103.1-56.1-145.5L282 256l46.3 46.3zM248 290L90.1 447.9c42.4 34.9 93.6 53.5 145.5 56.1 1.3-64 21.6-122.4 58.7-167.7L248 290zm191.9 123.9c29.7-36 47.5-78.4 53.8-122.2-50.1 1.6-95.5 17.1-131.2 44.8l77.4 77.4zM167.7 209.7C122.3 246.9 63.9 267.3 0 268.4c2.6 51.9 21.1 103.1 56.1 145.5L214 256l-46.3-46.3zm116 292c43.8-6.3 86.2-24.1 122.2-53.8l-77.4-77.4c-27.7 35.7-43.2 81.2-44.8 131.2z\"],\n    \"bath\": [512, 512, [], \"f2cd\", \"M488 256H80V112c0-17.645 14.355-32 32-32 11.351 0 21.332 5.945 27.015 14.88-16.492 25.207-14.687 59.576 6.838 83.035-4.176 4.713-4.021 11.916.491 16.428l11.314 11.314c4.686 4.686 12.284 4.686 16.971 0l95.03-95.029c4.686-4.686 4.686-12.284 0-16.971l-11.314-11.314c-4.512-4.512-11.715-4.666-16.428-.491-17.949-16.469-42.294-21.429-64.178-15.365C163.281 45.667 139.212 32 112 32c-44.112 0-80 35.888-80 80v144h-8c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h8v32c0 28.43 12.362 53.969 32 71.547V456c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-8h256v8c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-32.453c19.638-17.578 32-43.117 32-71.547v-32h8c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"battery-empty\": [640, 512, [], \"f244\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48z\"],\n    \"battery-full\": [640, 512, [], \"f240\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-48 96H96v128h416V192z\"],\n    \"battery-half\": [640, 512, [], \"f242\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-240 96H96v128h224V192z\"],\n    \"battery-quarter\": [640, 512, [], \"f243\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-336 96H96v128h128V192z\"],\n    \"battery-three-quarters\": [640, 512, [], \"f241\", \"M544 160v64h32v64h-32v64H64V160h480m16-64H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h512c26.51 0 48-21.49 48-48v-16h8c13.255 0 24-10.745 24-24V184c0-13.255-10.745-24-24-24h-8v-16c0-26.51-21.49-48-48-48zm-144 96H96v128h320V192z\"],\n    \"bed\": [640, 512, [], \"f236\", \"M176 256c44.11 0 80-35.89 80-80s-35.89-80-80-80-80 35.89-80 80 35.89 80 80 80zm352-128H304c-8.84 0-16 7.16-16 16v144H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v352c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h512v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V240c0-61.86-50.14-112-112-112z\"],\n    \"beer\": [448, 512, [], \"f0fc\", \"M368 96h-48V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24v-42.11l80.606-35.977C429.396 365.063 448 336.388 448 304.86V176c0-44.112-35.888-80-80-80zm16 208.86a16.018 16.018 0 0 1-9.479 14.611L320 343.805V160h48c8.822 0 16 7.178 16 16v128.86zM208 384c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16zm-96 0c-8.836 0-16-7.164-16-16V144c0-8.836 7.164-16 16-16s16 7.164 16 16v224c0 8.836-7.164 16-16 16z\"],\n    \"bell\": [448, 512, [], \"f0f3\", \"M224 512c35.32 0 63.97-28.65 63.97-64H160.03c0 35.35 28.65 64 63.97 64zm215.39-149.71c-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84C118.56 68.1 64.08 130.3 64.08 208c0 102.3-36.15 133.53-55.47 154.29-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h383.8c19.12 0 32-15.6 32.1-32 .05-7.55-2.61-15.27-8.61-21.71z\"],\n    \"bell-slash\": [640, 512, [], \"f1f6\", \"M633.82 458.1l-90.62-70.05c.19-1.38.8-2.66.8-4.06.05-7.55-2.61-15.27-8.61-21.71-19.32-20.76-55.47-51.99-55.47-154.29 0-77.7-54.48-139.9-127.94-155.16V32c0-17.67-14.32-32-31.98-32s-31.98 14.33-31.98 32v20.84c-40.33 8.38-74.66 31.07-97.59 62.57L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.35 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.42-6.97 4.17-17.02-2.81-22.45zM157.23 251.54c-8.61 67.96-36.41 93.33-52.62 110.75-6 6.45-8.66 14.16-8.61 21.71.11 16.4 12.98 32 32.1 32h241.92L157.23 251.54zM320 512c35.32 0 63.97-28.65 63.97-64H256.03c0 35.35 28.65 64 63.97 64z\"],\n    \"bezier-curve\": [640, 512, [], \"f55b\", \"M368 32h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM208 88h-84.75C113.75 64.56 90.84 48 64 48 28.66 48 0 76.65 0 112s28.66 64 64 64c26.84 0 49.75-16.56 59.25-40h79.73c-55.37 32.52-95.86 87.32-109.54 152h49.4c11.3-41.61 36.77-77.21 71.04-101.56-3.7-8.08-5.88-16.99-5.88-26.44V88zm-48 232H64c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zM576 48c-26.84 0-49.75 16.56-59.25 40H432v72c0 9.45-2.19 18.36-5.88 26.44 34.27 24.35 59.74 59.95 71.04 101.56h49.4c-13.68-64.68-54.17-119.48-109.54-152h79.73c9.5 23.44 32.41 40 59.25 40 35.34 0 64-28.65 64-64s-28.66-64-64-64zm0 272h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"bible\": [448, 512, [], \"f647\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM144 144c0-8.84 7.16-16 16-16h48V80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v48h48c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-48v112c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V192h-48c-8.84 0-16-7.16-16-16v-32zm236.8 304H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"bicycle\": [640, 512, [], \"f206\", \"M512.509 192.001c-16.373-.064-32.03 2.955-46.436 8.495l-77.68-125.153A24 24 0 0 0 368.001 64h-64c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h50.649l14.896 24H256.002v-16c0-8.837-7.163-16-16-16h-87.459c-13.441 0-24.777 10.999-24.536 24.437.232 13.044 10.876 23.563 23.995 23.563h48.726l-29.417 47.52c-13.433-4.83-27.904-7.483-42.992-7.52C58.094 191.83.412 249.012.002 319.236-.413 390.279 57.055 448 128.002 448c59.642 0 109.758-40.793 123.967-96h52.033a24 24 0 0 0 20.406-11.367L410.37 201.77l14.938 24.067c-25.455 23.448-41.385 57.081-41.307 94.437.145 68.833 57.899 127.051 126.729 127.719 70.606.685 128.181-55.803 129.255-125.996 1.086-70.941-56.526-129.72-127.476-129.996zM186.75 265.772c9.727 10.529 16.673 23.661 19.642 38.228h-43.306l23.664-38.228zM128.002 400c-44.112 0-80-35.888-80-80s35.888-80 80-80c5.869 0 11.586.653 17.099 1.859l-45.505 73.509C89.715 331.327 101.213 352 120.002 352h81.3c-12.37 28.225-40.562 48-73.3 48zm162.63-96h-35.624c-3.96-31.756-19.556-59.894-42.383-80.026L237.371 184h127.547l-74.286 120zm217.057 95.886c-41.036-2.165-74.049-35.692-75.627-76.755-.812-21.121 6.633-40.518 19.335-55.263l44.433 71.586c4.66 7.508 14.524 9.816 22.032 5.156l13.594-8.437c7.508-4.66 9.817-14.524 5.156-22.032l-44.468-71.643a79.901 79.901 0 0 1 19.858-2.497c44.112 0 80 35.888 80 80-.001 45.54-38.252 82.316-84.313 79.885z\"],\n    \"biking\": [640, 512, [], \"f84a\", \"M400 96a48 48 0 1 0-48-48 48 48 0 0 0 48 48zm-4 121a31.9 31.9 0 0 0 20 7h64a32 32 0 0 0 0-64h-52.78L356 103a31.94 31.94 0 0 0-40.81.68l-112 96a32 32 0 0 0 3.08 50.92L288 305.12V416a32 32 0 0 0 64 0V288a32 32 0 0 0-14.25-26.62l-41.36-27.57 58.25-49.92zm116 39a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64zM128 256a128 128 0 1 0 128 128 128 128 0 0 0-128-128zm0 192a64 64 0 1 1 64-64 64 64 0 0 1-64 64z\"],\n    \"binoculars\": [512, 512, [], \"f1e5\", \"M416 48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v48h96V48zM63.91 159.99C61.4 253.84 3.46 274.22 0 404v44c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32V288h32V128H95.84c-17.63 0-31.45 14.37-31.93 31.99zm384.18 0c-.48-17.62-14.3-31.99-31.93-31.99H320v160h32v160c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-44c-3.46-129.78-61.4-150.16-63.91-244.01zM176 32h-64c-8.84 0-16 7.16-16 16v48h96V48c0-8.84-7.16-16-16-16zm48 256h64V128h-64v160z\"],\n    \"biohazard\": [576, 512, [], \"f780\", \"M287.9 112c18.6 0 36.2 3.8 52.8 9.6 13.3-10.3 23.6-24.3 29.5-40.7-25.2-10.9-53-17-82.2-17-29.1 0-56.9 6-82.1 16.9 5.9 16.4 16.2 30.4 29.5 40.7 16.5-5.7 34-9.5 52.5-9.5zM163.6 438.7c12-11.8 20.4-26.4 24.5-42.4-32.9-26.4-54.8-65.3-58.9-109.6-8.5-2.8-17.2-4.6-26.4-4.6-7.6 0-15.2 1-22.5 3.1 4.1 62.8 35.8 118 83.3 153.5zm224.2-42.6c4.1 16 12.5 30.7 24.5 42.5 47.4-35.5 79.1-90.7 83-153.5-7.2-2-14.7-3-22.2-3-9.2 0-18 1.9-26.6 4.7-4.1 44.2-26 82.9-58.7 109.3zm113.5-205c-17.6-10.4-36.3-16.6-55.3-19.9 6-17.7 10-36.4 10-56.2 0-41-14.5-80.8-41-112.2-2.5-3-6.6-3.7-10-1.8-3.3 1.9-4.8 6-3.6 9.7 4.5 13.8 6.6 26.3 6.6 38.5 0 67.8-53.8 122.9-120 122.9S168 117 168 49.2c0-12.1 2.2-24.7 6.6-38.5 1.2-3.7-.3-7.8-3.6-9.7-3.4-1.9-7.5-1.2-10 1.8C134.6 34.2 120 74 120 115c0 19.8 3.9 38.5 10 56.2-18.9 3.3-37.7 9.5-55.3 19.9-34.6 20.5-61 53.3-74.3 92.4-1.3 3.7.2 7.7 3.5 9.8 3.3 2 7.5 1.3 10-1.6 9.4-10.8 19-19.1 29.2-25.1 57.3-33.9 130.8-13.7 163.9 45 33.1 58.7 13.4 134-43.9 167.9-10.2 6.1-22 10.4-35.8 13.4-3.7.8-6.4 4.2-6.4 8.1.1 4 2.7 7.3 6.5 8 39.7 7.8 80.6.8 115.2-19.7 18-10.6 32.9-24.5 45.3-40.1 12.4 15.6 27.3 29.5 45.3 40.1 34.6 20.5 75.5 27.5 115.2 19.7 3.8-.7 6.4-4 6.5-8 0-3.9-2.6-7.3-6.4-8.1-13.9-2.9-25.6-7.3-35.8-13.4-57.3-33.9-77-109.2-43.9-167.9s106.6-78.9 163.9-45c10.2 6.1 19.8 14.3 29.2 25.1 2.5 2.9 6.7 3.6 10 1.6s4.8-6.1 3.5-9.8c-13.1-39.1-39.5-72-74.1-92.4zm-213.4 129c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"birthday-cake\": [448, 512, [], \"f1fd\", \"M448 384c-28.02 0-31.26-32-74.5-32-43.43 0-46.825 32-74.75 32-27.695 0-31.454-32-74.75-32-42.842 0-47.218 32-74.5 32-28.148 0-31.202-32-74.75-32-43.547 0-46.653 32-74.75 32v-80c0-26.5 21.5-48 48-48h16V112h64v144h64V112h64v144h64V112h64v144h16c26.5 0 48 21.5 48 48v80zm0 128H0v-96c43.356 0 46.767-32 74.75-32 27.951 0 31.253 32 74.75 32 42.843 0 47.217-32 74.5-32 28.148 0 31.201 32 74.75 32 43.357 0 46.767-32 74.75-32 27.488 0 31.252 32 74.5 32v96zM96 96c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40zm128 0c-17.75 0-32-14.25-32-32 0-31 32-23 32-64 12 0 32 29.5 32 56s-14.25 40-32 40z\"],\n    \"blender\": [512, 512, [], \"f517\", \"M416 384H160c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-128 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm40-416h166.54L512 0H48C21.49 0 0 21.49 0 48v160c0 26.51 21.49 48 48 48h103.27l8.73 96h256l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H328c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H328c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM64 192V64h69.82l11.64 128H64z\"],\n    \"blender-phone\": [576, 512, [], \"f6b6\", \"M392 64h166.54L576 0H192v352h288l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h114.18l17.46-64H392c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h140.36l17.46-64H392c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8zM158.8 335.01l-25.78-63.26c-2.78-6.81-9.8-10.99-17.24-10.26l-45.03 4.42c-17.28-46.94-17.65-99.78 0-147.72l45.03 4.42c7.43.73 14.46-3.46 17.24-10.26l25.78-63.26c3.02-7.39.2-15.85-6.68-20.07l-39.28-24.1C98.51-3.87 80.09-.5 68.95 11.97c-92.57 103.6-92 259.55 2.1 362.49 9.87 10.8 29.12 12.48 41.65 4.8l39.41-24.18c6.89-4.22 9.7-12.67 6.69-20.07zM480 384H192c-35.35 0-64 28.65-64 64v32c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32v-32c0-35.35-28.65-64-64-64zm-144 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"blind\": [384, 512, [], \"f29d\", \"M380.15 510.837a8 8 0 0 1-10.989-2.687l-125.33-206.427a31.923 31.923 0 0 0 12.958-9.485l126.048 207.608a8 8 0 0 1-2.687 10.991zM142.803 314.338l-32.54 89.485 36.12 88.285c6.693 16.36 25.377 24.192 41.733 17.501 16.357-6.692 24.193-25.376 17.501-41.734l-62.814-153.537zM96 88c24.301 0 44-19.699 44-44S120.301 0 96 0 52 19.699 52 44s19.699 44 44 44zm154.837 169.128l-120-152c-4.733-5.995-11.75-9.108-18.837-9.112V96H80v.026c-7.146.003-14.217 3.161-18.944 9.24L0 183.766v95.694c0 13.455 11.011 24.791 24.464 24.536C37.505 303.748 48 293.1 48 280v-79.766l16-20.571v140.698L9.927 469.055c-6.04 16.609 2.528 34.969 19.138 41.009 16.602 6.039 34.968-2.524 41.009-19.138L136 309.638V202.441l-31.406-39.816a4 4 0 1 1 6.269-4.971l102.3 129.217c9.145 11.584 24.368 11.339 33.708 3.965 10.41-8.216 12.159-23.334 3.966-33.708z\"],\n    \"blog\": [512, 512, [], \"f781\", \"M172.2 226.8c-14.6-2.9-28.2 8.9-28.2 23.8V301c0 10.2 7.1 18.4 16.7 22 18.2 6.8 31.3 24.4 31.3 45 0 26.5-21.5 48-48 48s-48-21.5-48-48V120c0-13.3-10.7-24-24-24H24c-13.3 0-24 10.7-24 24v248c0 89.5 82.1 160.2 175 140.7 54.4-11.4 98.3-55.4 109.7-109.7 17.4-82.9-37-157.2-112.5-172.2zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"bold\": [384, 512, [], \"f032\", \"M333.49 238a122 122 0 0 0 27-65.21C367.87 96.49 308 32 233.42 32H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h31.87v288H34a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h209.32c70.8 0 134.14-51.75 141-122.4 4.74-48.45-16.39-92.06-50.83-119.6zM145.66 112h87.76a48 48 0 0 1 0 96h-87.76zm87.76 288h-87.76V288h87.76a56 56 0 0 1 0 112z\"],\n    \"bolt\": [320, 512, [], \"f0e7\", \"M296 160H180.6l42.6-129.8C227.2 15 215.7 0 200 0H56C44 0 33.8 8.9 32.2 20.8l-32 240C-1.7 275.2 9.5 288 24 288h118.7L96.6 482.5c-3.6 15.2 8 29.5 23.3 29.5 8.4 0 16.4-4.4 20.8-12l176-304c9.3-15.9-2.2-36-20.7-36z\"],\n    \"bomb\": [512, 512, [], \"f1e2\", \"M440.5 88.5l-52 52L415 167c9.4 9.4 9.4 24.6 0 33.9l-17.4 17.4c11.8 26.1 18.4 55.1 18.4 85.6 0 114.9-93.1 208-208 208S0 418.9 0 304 93.1 96 208 96c30.5 0 59.5 6.6 85.6 18.4L311 97c9.4-9.4 24.6-9.4 33.9 0l26.5 26.5 52-52 17.1 17zM500 60h-24c-6.6 0-12 5.4-12 12s5.4 12 12 12h24c6.6 0 12-5.4 12-12s-5.4-12-12-12zM440 0c-6.6 0-12 5.4-12 12v24c0 6.6 5.4 12 12 12s12-5.4 12-12V12c0-6.6-5.4-12-12-12zm33.9 55l17-17c4.7-4.7 4.7-12.3 0-17-4.7-4.7-12.3-4.7-17 0l-17 17c-4.7 4.7-4.7 12.3 0 17 4.8 4.7 12.4 4.7 17 0zm-67.8 0c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17zm67.8 34c-4.7-4.7-12.3-4.7-17 0-4.7 4.7-4.7 12.3 0 17l17 17c4.7 4.7 12.3 4.7 17 0 4.7-4.7 4.7-12.3 0-17l-17-17zM112 272c0-35.3 28.7-64 64-64 8.8 0 16-7.2 16-16s-7.2-16-16-16c-52.9 0-96 43.1-96 96 0 8.8 7.2 16 16 16s16-7.2 16-16z\"],\n    \"bone\": [640, 512, [], \"f5d7\", \"M598.88 244.56c25.2-12.6 41.12-38.36 41.12-66.53v-7.64C640 129.3 606.7 96 565.61 96c-32.02 0-60.44 20.49-70.57 50.86-7.68 23.03-11.6 45.14-38.11 45.14H183.06c-27.38 0-31.58-25.54-38.11-45.14C134.83 116.49 106.4 96 74.39 96 33.3 96 0 129.3 0 170.39v7.64c0 28.17 15.92 53.93 41.12 66.53 9.43 4.71 9.43 18.17 0 22.88C15.92 280.04 0 305.8 0 333.97v7.64C0 382.7 33.3 416 74.38 416c32.02 0 60.44-20.49 70.57-50.86 7.68-23.03 11.6-45.14 38.11-45.14h273.87c27.38 0 31.58 25.54 38.11 45.14C505.17 395.51 533.6 416 565.61 416c41.08 0 74.38-33.3 74.38-74.39v-7.64c0-28.18-15.92-53.93-41.12-66.53-9.42-4.71-9.42-18.17.01-22.88z\"],\n    \"bong\": [448, 512, [], \"f55c\", \"M302.5 512c23.18 0 44.43-12.58 56-32.66C374.69 451.26 384 418.75 384 384c0-36.12-10.08-69.81-27.44-98.62L400 241.94l9.38 9.38c6.25 6.25 16.38 6.25 22.63 0l11.3-11.32c6.25-6.25 6.25-16.38 0-22.63l-52.69-52.69c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l9.38 9.38-39.41 39.41c-11.56-11.37-24.53-21.33-38.65-29.51V63.74l15.97-.02c8.82-.01 15.97-7.16 15.98-15.98l.04-31.72C320 7.17 312.82-.01 303.97 0L80.03.26c-8.82.01-15.97 7.16-15.98 15.98l-.04 31.73c-.01 8.85 7.17 16.02 16.02 16.01L96 63.96v153.93C38.67 251.1 0 312.97 0 384c0 34.75 9.31 67.27 25.5 95.34C37.08 499.42 58.33 512 81.5 512h221zM120.06 259.43L144 245.56V63.91l96-.11v181.76l23.94 13.87c24.81 14.37 44.12 35.73 56.56 60.57h-257c12.45-24.84 31.75-46.2 56.56-60.57z\"],\n    \"book\": [448, 512, [], \"f02d\", \"M448 360V24c0-13.3-10.7-24-24-24H96C43 0 0 43 0 96v320c0 53 43 96 96 96h328c13.3 0 24-10.7 24-24v-16c0-7.5-3.5-14.3-8.9-18.7-4.2-15.4-4.2-59.3 0-74.7 5.4-4.3 8.9-11.1 8.9-18.6zM128 134c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm0 64c0-3.3 2.7-6 6-6h212c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H134c-3.3 0-6-2.7-6-6v-20zm253.4 250H96c-17.7 0-32-14.3-32-32 0-17.6 14.4-32 32-32h285.4c-1.9 17.1-1.9 46.9 0 64z\"],\n    \"book-dead\": [448, 512, [], \"f6b7\", \"M272 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm176 222.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM240 56c44.2 0 80 28.7 80 64 0 20.9-12.7 39.2-32 50.9V184c0 8.8-7.2 16-16 16h-64c-8.8 0-16-7.2-16-16v-13.1c-19.3-11.7-32-30-32-50.9 0-35.3 35.8-64 80-64zM124.8 223.3l6.3-14.7c1.7-4.1 6.4-5.9 10.5-4.2l98.3 42.1 98.4-42.1c4.1-1.7 8.8.1 10.5 4.2l6.3 14.7c1.7 4.1-.1 8.8-4.2 10.5L280.6 264l70.3 30.1c4.1 1.7 5.9 6.4 4.2 10.5l-6.3 14.7c-1.7 4.1-6.4 5.9-10.5 4.2L240 281.4l-98.3 42.2c-4.1 1.7-8.8-.1-10.5-4.2l-6.3-14.7c-1.7-4.1.1-8.8 4.2-10.5l70.4-30.1-70.5-30.3c-4.1-1.7-5.9-6.4-4.2-10.5zm256 224.7H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8zM208 136c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16z\"],\n    \"book-medical\": [448, 512, [], \"f7e6\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16q0-9.6-9.6-19.2c-3.2-16-3.2-60.8 0-73.6q9.6-4.8 9.6-19.2zM144 168a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8v48a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8zm236.8 280H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8z\"],\n    \"book-open\": [576, 512, [], \"f518\", \"M542.22 32.05c-54.8 3.11-163.72 14.43-230.96 55.59-4.64 2.84-7.27 7.89-7.27 13.17v363.87c0 11.55 12.63 18.85 23.28 13.49 69.18-34.82 169.23-44.32 218.7-46.92 16.89-.89 30.02-14.43 30.02-30.66V62.75c.01-17.71-15.35-31.74-33.77-30.7zM264.73 87.64C197.5 46.48 88.58 35.17 33.78 32.05 15.36 31.01 0 45.04 0 62.75V400.6c0 16.24 13.13 29.78 30.02 30.66 49.49 2.6 149.59 12.11 218.77 46.95 10.62 5.35 23.21-1.94 23.21-13.46V100.63c0-5.29-2.62-10.14-7.27-12.99z\"],\n    \"book-reader\": [512, 512, [], \"f5da\", \"M352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96 42.98 96 96 96 96-42.98 96-96zM233.59 241.1c-59.33-36.32-155.43-46.3-203.79-49.05C13.55 191.13 0 203.51 0 219.14v222.8c0 14.33 11.59 26.28 26.49 27.05 43.66 2.29 131.99 10.68 193.04 41.43 9.37 4.72 20.48-1.71 20.48-11.87V252.56c-.01-4.67-2.32-8.95-6.42-11.46zm248.61-49.05c-48.35 2.74-144.46 12.73-203.78 49.05-4.1 2.51-6.41 6.96-6.41 11.63v245.79c0 10.19 11.14 16.63 20.54 11.9 61.04-30.72 149.32-39.11 192.97-41.4 14.9-.78 26.49-12.73 26.49-27.06V219.14c-.01-15.63-13.56-28.01-29.81-27.09z\"],\n    \"bookmark\": [384, 512, [], \"f02e\", \"M0 512V48C0 21.49 21.49 0 48 0h288c26.51 0 48 21.49 48 48v464L192 400 0 512z\"],\n    \"border-all\": [448, 512, [], \"f84c\", \"M416 32H32A32 32 0 0 0 0 64v384a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V64a32 32 0 0 0-32-32zm-32 64v128H256V96zm-192 0v128H64V96zM64 416V288h128v128zm192 0V288h128v128z\"],\n    \"border-none\": [448, 512, [], \"f850\", \"M240 224h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-288 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM240 320h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-384h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM48 224H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-192H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"border-style\": [448, 512, [], \"f853\", \"M240 416h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-96 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm192 0h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm96-192h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0 96h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-288h-32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-96H32A32 32 0 0 0 0 64v400a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V96h368a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"bowling-ball\": [496, 512, [], \"f436\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM120 192c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64-96c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm48 144c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"box\": [512, 512, [], \"f466\", \"M509.5 184.6L458.9 32.8C452.4 13.2 434.1 0 413.4 0H272v192h238.7c-.4-2.5-.4-5-1.2-7.4zM240 0H98.6c-20.7 0-39 13.2-45.5 32.8L2.5 184.6c-.8 2.4-.8 4.9-1.2 7.4H240V0zM0 224v240c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V224H0z\"],\n    \"box-open\": [640, 512, [], \"f49e\", \"M425.7 256c-16.9 0-32.8-9-41.4-23.4L320 126l-64.2 106.6c-8.7 14.5-24.6 23.5-41.5 23.5-4.5 0-9-.6-13.3-1.9L64 215v178c0 14.7 10 27.5 24.2 31l216.2 54.1c10.2 2.5 20.9 2.5 31 0L551.8 424c14.2-3.6 24.2-16.4 24.2-31V215l-137 39.1c-4.3 1.3-8.8 1.9-13.3 1.9zm212.6-112.2L586.8 41c-3.1-6.2-9.8-9.8-16.7-8.9L320 64l91.7 152.1c3.8 6.3 11.4 9.3 18.5 7.3l197.9-56.5c9.9-2.9 14.7-13.9 10.2-23.1zM53.2 41L1.7 143.8c-4.6 9.2.3 20.2 10.1 23l197.9 56.5c7.1 2 14.7-1 18.5-7.3L320 64 69.8 32.1c-6.9-.8-13.5 2.7-16.6 8.9z\"],\n    \"boxes\": [576, 512, [], \"f468\", \"M560 288h-80v96l-32-21.3-32 21.3v-96h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16zm-384-64h224c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16h-80v96l-32-21.3L256 96V0h-80c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16zm64 64h-80v96l-32-21.3L96 384v-96H16c-8.8 0-16 7.2-16 16v192c0 8.8 7.2 16 16 16h224c8.8 0 16-7.2 16-16V304c0-8.8-7.2-16-16-16z\"],\n    \"braille\": [640, 512, [], \"f2a1\", \"M128 256c0 35.346-28.654 64-64 64S0 291.346 0 256s28.654-64 64-64 64 28.654 64 64zM64 384c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352C28.654 32 0 60.654 0 96s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm224 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-352c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64zm160 192c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0 160c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm0-320c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"brain\": [576, 512, [], \"f5dc\", \"M208 0c-29.9 0-54.7 20.5-61.8 48.2-.8 0-1.4-.2-2.2-.2-35.3 0-64 28.7-64 64 0 4.8.6 9.5 1.7 14C52.5 138 32 166.6 32 200c0 12.6 3.2 24.3 8.3 34.9C16.3 248.7 0 274.3 0 304c0 33.3 20.4 61.9 49.4 73.9-.9 4.6-1.4 9.3-1.4 14.1 0 39.8 32.2 72 72 72 4.1 0 8.1-.5 12-1.2 9.6 28.5 36.2 49.2 68 49.2 39.8 0 72-32.2 72-72V64c0-35.3-28.7-64-64-64zm368 304c0-29.7-16.3-55.3-40.3-69.1 5.2-10.6 8.3-22.3 8.3-34.9 0-33.4-20.5-62-49.7-74 1-4.5 1.7-9.2 1.7-14 0-35.3-28.7-64-64-64-.8 0-1.5.2-2.2.2C422.7 20.5 397.9 0 368 0c-35.3 0-64 28.6-64 64v376c0 39.8 32.2 72 72 72 31.8 0 58.4-20.7 68-49.2 3.9.7 7.9 1.2 12 1.2 39.8 0 72-32.2 72-72 0-4.8-.5-9.5-1.4-14.1 29-12 49.4-40.6 49.4-73.9z\"],\n    \"bread-slice\": [576, 512, [], \"f7ec\", \"M288 0C108 0 0 93.4 0 169.14 0 199.44 24.24 224 64 224v256c0 17.67 16.12 32 36 32h376c19.88 0 36-14.33 36-32V224c39.76 0 64-24.56 64-54.86C576 93.4 468 0 288 0z\"],\n    \"briefcase\": [512, 512, [], \"f0b1\", \"M320 336c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h416c25.6 0 48-22.4 48-48V288H320v48zm144-208h-80V80c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h512v-80c0-25.6-22.4-48-48-48zm-144 0H192V96h128v32z\"],\n    \"briefcase-medical\": [512, 512, [], \"f469\", \"M464 128h-80V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v48H48c-26.5 0-48 21.5-48 48v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V176c0-26.5-21.5-48-48-48zM192 96h128v32H192V96zm160 248c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48z\"],\n    \"broadcast-tower\": [640, 512, [], \"f519\", \"M150.94 192h33.73c11.01 0 18.61-10.83 14.86-21.18-4.93-13.58-7.55-27.98-7.55-42.82s2.62-29.24 7.55-42.82C203.29 74.83 195.68 64 184.67 64h-33.73c-7.01 0-13.46 4.49-15.41 11.23C130.64 92.21 128 109.88 128 128c0 18.12 2.64 35.79 7.54 52.76 1.94 6.74 8.39 11.24 15.4 11.24zM89.92 23.34C95.56 12.72 87.97 0 75.96 0H40.63c-6.27 0-12.14 3.59-14.74 9.31C9.4 45.54 0 85.65 0 128c0 24.75 3.12 68.33 26.69 118.86 2.62 5.63 8.42 9.14 14.61 9.14h34.84c12.02 0 19.61-12.74 13.95-23.37-49.78-93.32-16.71-178.15-.17-209.29zM614.06 9.29C611.46 3.58 605.6 0 599.33 0h-35.42c-11.98 0-19.66 12.66-14.02 23.25 18.27 34.29 48.42 119.42.28 209.23-5.72 10.68 1.8 23.52 13.91 23.52h35.23c6.27 0 12.13-3.58 14.73-9.29C630.57 210.48 640 170.36 640 128s-9.42-82.48-25.94-118.71zM489.06 64h-33.73c-11.01 0-18.61 10.83-14.86 21.18 4.93 13.58 7.55 27.98 7.55 42.82s-2.62 29.24-7.55 42.82c-3.76 10.35 3.85 21.18 14.86 21.18h33.73c7.02 0 13.46-4.49 15.41-11.24 4.9-16.97 7.53-34.64 7.53-52.76 0-18.12-2.64-35.79-7.54-52.76-1.94-6.75-8.39-11.24-15.4-11.24zm-116.3 100.12c7.05-10.29 11.2-22.71 11.2-36.12 0-35.35-28.63-64-63.96-64-35.32 0-63.96 28.65-63.96 64 0 13.41 4.15 25.83 11.2 36.12l-130.5 313.41c-3.4 8.15.46 17.52 8.61 20.92l29.51 12.31c8.15 3.4 17.52-.46 20.91-8.61L244.96 384h150.07l49.2 118.15c3.4 8.16 12.76 12.01 20.91 8.61l29.51-12.31c8.15-3.4 12-12.77 8.61-20.92l-130.5-313.41zM271.62 320L320 203.81 368.38 320h-96.76z\"],\n    \"broom\": [640, 512, [], \"f51a\", \"M256.47 216.77l86.73 109.18s-16.6 102.36-76.57 150.12C206.66 523.85 0 510.19 0 510.19s3.8-23.14 11-55.43l94.62-112.17c3.97-4.7-.87-11.62-6.65-9.5l-60.4 22.09c14.44-41.66 32.72-80.04 54.6-97.47 59.97-47.76 163.3-40.94 163.3-40.94zM636.53 31.03l-19.86-25c-5.49-6.9-15.52-8.05-22.41-2.56l-232.48 177.8-34.14-42.97c-5.09-6.41-15.14-5.21-18.59 2.21l-25.33 54.55 86.73 109.18 58.8-12.45c8-1.69 11.42-11.2 6.34-17.6l-34.09-42.92 232.48-177.8c6.89-5.48 8.04-15.53 2.55-22.44z\"],\n    \"brush\": [384, 512, [], \"f55d\", \"M352 0H32C14.33 0 0 14.33 0 32v224h384V32c0-17.67-14.33-32-32-32zM0 320c0 35.35 28.66 64 64 64h64v64c0 35.35 28.66 64 64 64s64-28.65 64-64v-64h64c35.34 0 64-28.65 64-64v-32H0v32zm192 104c13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24s-24-10.75-24-24c0-13.26 10.75-24 24-24z\"],\n    \"bug\": [512, 512, [], \"f188\", \"M511.988 288.9c-.478 17.43-15.217 31.1-32.653 31.1H424v16c0 21.864-4.882 42.584-13.6 61.145l60.228 60.228c12.496 12.497 12.496 32.758 0 45.255-12.498 12.497-32.759 12.496-45.256 0l-54.736-54.736C345.886 467.965 314.351 480 280 480V236c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v244c-34.351 0-65.886-12.035-90.636-32.108l-54.736 54.736c-12.498 12.497-32.759 12.496-45.256 0-12.496-12.497-12.496-32.758 0-45.255l60.228-60.228C92.882 378.584 88 357.864 88 336v-16H32.666C15.23 320 .491 306.33.013 288.9-.484 270.816 14.028 256 32 256h56v-58.745l-46.628-46.628c-12.496-12.497-12.496-32.758 0-45.255 12.498-12.497 32.758-12.497 45.256 0L141.255 160h229.489l54.627-54.627c12.498-12.497 32.758-12.497 45.256 0 12.496 12.497 12.496 32.758 0 45.255L424 197.255V256h56c17.972 0 32.484 14.816 31.988 32.9zM257 0c-61.856 0-112 50.144-112 112h224C369 50.144 318.856 0 257 0z\"],\n    \"building\": [448, 512, [], \"f1ad\", \"M436 480h-20V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v456H12c-6.627 0-12 5.373-12 12v20h448v-20c0-6.627-5.373-12-12-12zM128 76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76zm0 96c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40zm52 148h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12zm76 160h-64v-84c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v84zm64-172c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40zm0-96c0 6.627-5.373 12-12 12h-40c-6.627 0-12-5.373-12-12V76c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v40z\"],\n    \"bullhorn\": [576, 512, [], \"f0a1\", \"M576 240c0-23.63-12.95-44.04-32-55.12V32.01C544 23.26 537.02 0 512 0c-7.12 0-14.19 2.38-19.98 7.02l-85.03 68.03C364.28 109.19 310.66 128 256 128H64c-35.35 0-64 28.65-64 64v96c0 35.35 28.65 64 64 64h33.7c-1.39 10.48-2.18 21.14-2.18 32 0 39.77 9.26 77.35 25.56 110.94 5.19 10.69 16.52 17.06 28.4 17.06h74.28c26.05 0 41.69-29.84 25.9-50.56-16.4-21.52-26.15-48.36-26.15-77.44 0-11.11 1.62-21.79 4.41-32H256c54.66 0 108.28 18.81 150.98 52.95l85.03 68.03a32.023 32.023 0 0 0 19.98 7.02c24.92 0 32-22.78 32-32V295.13C563.05 284.04 576 263.63 576 240zm-96 141.42l-33.05-26.44C392.95 311.78 325.12 288 256 288v-96c69.12 0 136.95-23.78 190.95-66.98L480 98.58v282.84z\"],\n    \"bullseye\": [496, 512, [], \"f140\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 432c-101.69 0-184-82.29-184-184 0-101.69 82.29-184 184-184 101.69 0 184 82.29 184 184 0 101.69-82.29 184-184 184zm0-312c-70.69 0-128 57.31-128 128s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm0 192c-35.29 0-64-28.71-64-64s28.71-64 64-64 64 28.71 64 64-28.71 64-64 64z\"],\n    \"burn\": [384, 512, [], \"f46a\", \"M192 0C79.7 101.3 0 220.9 0 300.5 0 425 79 512 192 512s192-87 192-211.5c0-79.9-80.2-199.6-192-300.5zm0 448c-56.5 0-96-39-96-94.8 0-13.5 4.6-61.5 96-161.2 91.4 99.7 96 147.7 96 161.2 0 55.8-39.5 94.8-96 94.8z\"],\n    \"bus\": [512, 512, [], \"f207\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM112 400c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm16-112c-17.67 0-32-14.33-32-32V128c0-17.67 14.33-32 32-32h256c17.67 0 32 14.33 32 32v128c0 17.67-14.33 32-32 32H128zm272 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"bus-alt\": [512, 512, [], \"f55e\", \"M488 128h-8V80c0-44.8-99.2-80-224-80S32 35.2 32 80v48h-8c-13.25 0-24 10.74-24 24v80c0 13.25 10.75 24 24 24h8v160c0 17.67 14.33 32 32 32v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h192v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h6.4c16 0 25.6-12.8 25.6-25.6V256h8c13.25 0 24-10.75 24-24v-80c0-13.26-10.75-24-24-24zM160 72c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H168c-4.42 0-8-3.58-8-8V72zm-48 328c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128-112H128c-17.67 0-32-14.33-32-32v-96c0-17.67 14.33-32 32-32h112v160zm32 0V128h112c17.67 0 32 14.33 32 32v96c0 17.67-14.33 32-32 32H272zm128 112c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"business-time\": [640, 512, [], \"f64a\", \"M496 224c-79.59 0-144 64.41-144 144s64.41 144 144 144 144-64.41 144-144-64.41-144-144-144zm64 150.29c0 5.34-4.37 9.71-9.71 9.71h-60.57c-5.34 0-9.71-4.37-9.71-9.71v-76.57c0-5.34 4.37-9.71 9.71-9.71h12.57c5.34 0 9.71 4.37 9.71 9.71V352h38.29c5.34 0 9.71 4.37 9.71 9.71v12.58zM496 192c5.4 0 10.72.33 16 .81V144c0-25.6-22.4-48-48-48h-80V48c0-25.6-22.4-48-48-48H176c-25.6 0-48 22.4-48 48v48H48c-25.6 0-48 22.4-48 48v80h395.12c28.6-20.09 63.35-32 100.88-32zM320 96H192V64h128v32zm6.82 224H208c-8.84 0-16-7.16-16-16v-48H0v144c0 25.6 22.4 48 48 48h291.43C327.1 423.96 320 396.82 320 368c0-16.66 2.48-32.72 6.82-48z\"],\n    \"calculator\": [448, 512, [], \"f1ec\", \"M400 0H48C22.4 0 0 22.4 0 48v416c0 25.6 22.4 48 48 48h352c25.6 0 48-22.4 48-48V48c0-25.6-22.4-48-48-48zM128 435.2c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm128 128c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8V268.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v166.4zm0-256c0 6.4-6.4 12.8-12.8 12.8H76.8c-6.4 0-12.8-6.4-12.8-12.8V76.8C64 70.4 70.4 64 76.8 64h294.4c6.4 0 12.8 6.4 12.8 12.8v102.4z\"],\n    \"calendar\": [448, 512, [], \"f133\", \"M12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm436-44v-36c0-26.5-21.5-48-48-48h-48V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H160V12c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v52H48C21.5 64 0 85.5 0 112v36c0 6.6 5.4 12 12 12h424c6.6 0 12-5.4 12-12z\"],\n    \"calendar-alt\": [448, 512, [], \"f073\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm320-196c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM192 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40zM64 268c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zm0 128c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-check\": [448, 512, [], \"f274\", \"M436 160H12c-6.627 0-12-5.373-12-12v-36c0-26.51 21.49-48 48-48h48V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h128V12c0-6.627 5.373-12 12-12h40c6.627 0 12 5.373 12 12v52h48c26.51 0 48 21.49 48 48v36c0 6.627-5.373 12-12 12zM12 192h424c6.627 0 12 5.373 12 12v260c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V204c0-6.627 5.373-12 12-12zm333.296 95.947l-28.169-28.398c-4.667-4.705-12.265-4.736-16.97-.068L194.12 364.665l-45.98-46.352c-4.667-4.705-12.266-4.736-16.971-.068l-28.397 28.17c-4.705 4.667-4.736 12.265-.068 16.97l82.601 83.269c4.667 4.705 12.265 4.736 16.97.068l142.953-141.805c4.705-4.667 4.736-12.265.068-16.97z\"],\n    \"calendar-day\": [448, 512, [], \"f783\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h96c8.8 0 16 7.2 16 16v96c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-96zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"calendar-minus\": [448, 512, [], \"f272\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm304 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H132c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h184z\"],\n    \"calendar-plus\": [448, 512, [], \"f271\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm316 140c0-6.6-5.4-12-12-12h-60v-60c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v60h-60c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h60v60c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-60h60c6.6 0 12-5.4 12-12v-40z\"],\n    \"calendar-times\": [448, 512, [], \"f273\", \"M436 160H12c-6.6 0-12-5.4-12-12v-36c0-26.5 21.5-48 48-48h48V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h128V12c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h48c26.5 0 48 21.5 48 48v36c0 6.6-5.4 12-12 12zM12 192h424c6.6 0 12 5.4 12 12v260c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V204c0-6.6 5.4-12 12-12zm257.3 160l48.1-48.1c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0L224 306.7l-48.1-48.1c-4.7-4.7-12.3-4.7-17 0l-28.3 28.3c-4.7 4.7-4.7 12.3 0 17l48.1 48.1-48.1 48.1c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l48.1-48.1 48.1 48.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L269.3 352z\"],\n    \"calendar-week\": [448, 512, [], \"f784\", \"M0 464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V192H0v272zm64-192c0-8.8 7.2-16 16-16h288c8.8 0 16 7.2 16 16v64c0 8.8-7.2 16-16 16H80c-8.8 0-16-7.2-16-16v-64zM400 64h-48V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H160V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48H48C21.5 64 0 85.5 0 112v48h448v-48c0-26.5-21.5-48-48-48z\"],\n    \"camera\": [512, 512, [], \"f030\", \"M512 144v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V144c0-26.5 21.5-48 48-48h88l12.3-32.9c7-18.7 24.9-31.1 44.9-31.1h125.5c20 0 37.9 12.4 44.9 31.1L376 96h88c26.5 0 48 21.5 48 48zM376 288c0-66.2-53.8-120-120-120s-120 53.8-120 120 53.8 120 120 120 120-53.8 120-120zm-32 0c0 48.5-39.5 88-88 88s-88-39.5-88-88 39.5-88 88-88 88 39.5 88 88z\"],\n    \"camera-retro\": [512, 512, [], \"f083\", \"M48 32C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48H48zm0 32h106c3.3 0 6 2.7 6 6v20c0 3.3-2.7 6-6 6H38c-3.3 0-6-2.7-6-6V80c0-8.8 7.2-16 16-16zm426 96H38c-3.3 0-6-2.7-6-6v-36c0-3.3 2.7-6 6-6h138l30.2-45.3c1.1-1.7 3-2.7 5-2.7H464c8.8 0 16 7.2 16 16v74c0 3.3-2.7 6-6 6zM256 424c-66.2 0-120-53.8-120-120s53.8-120 120-120 120 53.8 120 120-53.8 120-120 120zm0-208c-48.5 0-88 39.5-88 88s39.5 88 88 88 88-39.5 88-88-39.5-88-88-88zm-48 104c-8.8 0-16-7.2-16-16 0-35.3 28.7-64 64-64 8.8 0 16 7.2 16 16s-7.2 16-16 16c-17.6 0-32 14.4-32 32 0 8.8-7.2 16-16 16z\"],\n    \"campground\": [640, 512, [], \"f6bb\", \"M624 448h-24.68L359.54 117.75l53.41-73.55c5.19-7.15 3.61-17.16-3.54-22.35l-25.9-18.79c-7.15-5.19-17.15-3.61-22.35 3.55L320 63.3 278.83 6.6c-5.19-7.15-15.2-8.74-22.35-3.55l-25.88 18.8c-7.15 5.19-8.74 15.2-3.54 22.35l53.41 73.55L40.68 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM320 288l116.36 160H203.64L320 288z\"],\n    \"candy-cane\": [512, 512, [], \"f786\", \"M497.5 92C469.6 33.1 411.8 0 352.4 0c-27.9 0-56.2 7.3-81.8 22.6L243.1 39c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5l27.5-16.4c5.1-3.1 10.8-4.5 16.4-4.5 10.9 0 21.5 5.6 27.5 15.6 9.1 15.1 4.1 34.8-11 43.9L15.6 397.6c-15.2 9.1-20.1 28.7-11 43.9l32.8 54.9c6 10 16.6 15.6 27.5 15.6 5.6 0 11.2-1.5 16.4-4.5L428.6 301c71.7-42.9 104.6-133.5 68.9-209zm-177.7 13l-2.5 1.5L296.8 45c9.7-4.7 19.8-8.1 30.3-10.2l20.6 61.8c-9.8.8-19.4 3.3-27.9 8.4zM145.9 431.8l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm107.5-63.9l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zM364.3 302l-60.5-38.5 30.8-18.3 60.5 38.5-30.8 18.3zm20.4-197.3l46-46c8.4 6.5 16 14.1 22.6 22.6L407.6 127c-5.7-9.3-13.7-16.9-22.9-22.3zm82.1 107.8l-59.5-19.8c3.2-5.3 5.8-10.9 7.4-17.1 1.1-4.5 1.7-9.1 1.8-13.6l60.4 20.1c-2.1 10.4-5.5 20.6-10.1 30.4z\"],\n    \"cannabis\": [512, 512, [], \"f55f\", \"M503.47 360.25c-1.56-.82-32.39-16.89-76.78-25.81 64.25-75.12 84.05-161.67 84.93-165.64 1.18-5.33-.44-10.9-4.3-14.77-3.03-3.04-7.12-4.7-11.32-4.7-1.14 0-2.29.12-3.44.38-3.88.85-86.54 19.59-160.58 79.76.01-1.46.01-2.93.01-4.4 0-118.79-59.98-213.72-62.53-217.7A15.973 15.973 0 0 0 256 0c-5.45 0-10.53 2.78-13.47 7.37-2.55 3.98-62.53 98.91-62.53 217.7 0 1.47.01 2.94.01 4.4-74.03-60.16-156.69-78.9-160.58-79.76-1.14-.25-2.29-.38-3.44-.38-4.2 0-8.29 1.66-11.32 4.7A15.986 15.986 0 0 0 .38 168.8c.88 3.97 20.68 90.52 84.93 165.64-44.39 8.92-75.21 24.99-76.78 25.81a16.003 16.003 0 0 0-.02 28.29c2.45 1.29 60.76 31.72 133.49 31.72 6.14 0 11.96-.1 17.5-.31-11.37 22.23-16.52 38.31-16.81 39.22-1.8 5.68-.29 11.89 3.91 16.11a16.019 16.019 0 0 0 16.1 3.99c1.83-.57 37.72-11.99 77.3-39.29V504c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-64.01c39.58 27.3 75.47 38.71 77.3 39.29a16.019 16.019 0 0 0 16.1-3.99c4.2-4.22 5.71-10.43 3.91-16.11-.29-.91-5.45-16.99-16.81-39.22 5.54.21 11.37.31 17.5.31 72.72 0 131.04-30.43 133.49-31.72 5.24-2.78 8.52-8.22 8.51-14.15-.01-5.94-3.29-11.39-8.53-14.15z\"],\n    \"capsules\": [576, 512, [], \"f46b\", \"M555.3 300.1L424.2 112.8C401.9 81 366.4 64 330.4 64c-22.6 0-45.5 6.7-65.5 20.7-19.7 13.8-33.7 32.8-41.5 53.8C220.5 79.2 172 32 112 32 50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V218.9c3.3 8.6 7.3 17.1 12.8 25L368 431.2c22.2 31.8 57.7 48.8 93.8 48.8 22.7 0 45.5-6.7 65.5-20.7 51.7-36.2 64.2-107.5 28-159.2zM160 256H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm194.8 44.9l-65.6-93.7c-7.7-11-10.7-24.4-8.3-37.6 2.3-13.2 9.7-24.8 20.7-32.5 8.5-6 18.5-9.1 28.8-9.1 16.5 0 31.9 8 41.3 21.5l65.6 93.7-82.5 57.7z\"],\n    \"car\": [512, 512, [], \"f1b9\", \"M499.99 176h-59.87l-16.64-41.6C406.38 91.63 365.57 64 319.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4L71.87 176H12.01C4.2 176-1.53 183.34.37 190.91l6 24C7.7 220.25 12.5 224 18.01 224h20.07C24.65 235.73 16 252.78 16 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-19.22-8.65-36.27-22.07-48H494c5.51 0 10.31-3.75 11.64-9.09l6-24c1.89-7.57-3.84-14.91-11.65-14.91zm-352.06-17.83c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L384 208H128l19.93-49.83zM96 319.8c-19.2 0-32-12.76-32-31.9S76.8 256 96 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S396.8 256 416 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-alt\": [480, 512, [], \"f5de\", \"M438.66 212.33l-11.24-28.1-19.93-49.83C390.38 91.63 349.57 64 303.5 64h-127c-46.06 0-86.88 27.63-103.99 70.4l-19.93 49.83-11.24 28.1C17.22 221.5 0 244.66 0 272v48c0 16.12 6.16 30.67 16 41.93V416c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-54.07c9.84-11.25 16-25.8 16-41.93v-48c0-27.34-17.22-50.5-41.34-59.67zm-306.73-54.16c7.29-18.22 24.94-30.17 44.57-30.17h127c19.63 0 37.28 11.95 44.57 30.17L368 208H112l19.93-49.83zM80 319.8c-19.2 0-32-12.76-32-31.9S60.8 256 80 256s48 28.71 48 47.85-28.8 15.95-48 15.95zm320 0c-19.2 0-48 3.19-48-15.95S380.8 256 400 256s32 12.76 32 31.9-12.8 31.9-32 31.9z\"],\n    \"car-battery\": [512, 512, [], \"f5df\", \"M480 128h-32V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v48H192V80c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v48H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zM192 264c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm256 0c0 4.42-3.58 8-8 8h-40v40c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-40h-40c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h40v-40c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v40h40c4.42 0 8 3.58 8 8v16z\"],\n    \"car-crash\": [640, 512, [], \"f5e1\", \"M143.25 220.81l-12.42 46.37c-3.01 11.25-3.63 22.89-2.41 34.39l-35.2 28.98c-6.57 5.41-16.31-.43-14.62-8.77l15.44-76.68c1.06-5.26-2.66-10.28-8-10.79l-77.86-7.55c-8.47-.82-11.23-11.83-4.14-16.54l65.15-43.3c4.46-2.97 5.38-9.15 1.98-13.29L21.46 93.22c-5.41-6.57.43-16.3 8.78-14.62l76.68 15.44c5.26 1.06 10.28-2.66 10.8-8l7.55-77.86c.82-8.48 11.83-11.23 16.55-4.14l43.3 65.14c2.97 4.46 9.15 5.38 13.29 1.98l60.4-49.71c6.57-5.41 16.3.43 14.62 8.77L262.1 86.38c-2.71 3.05-5.43 6.09-7.91 9.4l-32.15 42.97-10.71 14.32c-32.73 8.76-59.18 34.53-68.08 67.74zm494.57 132.51l-12.42 46.36c-3.13 11.68-9.38 21.61-17.55 29.36a66.876 66.876 0 0 1-8.76 7l-13.99 52.23c-1.14 4.27-3.1 8.1-5.65 11.38-7.67 9.84-20.74 14.68-33.54 11.25L515 502.62c-17.07-4.57-27.2-22.12-22.63-39.19l8.28-30.91-247.28-66.26-8.28 30.91c-4.57 17.07-22.12 27.2-39.19 22.63l-30.91-8.28c-12.8-3.43-21.7-14.16-23.42-26.51-.57-4.12-.35-8.42.79-12.68l13.99-52.23a66.62 66.62 0 0 1-4.09-10.45c-3.2-10.79-3.65-22.52-.52-34.2l12.42-46.37c5.31-19.8 19.36-34.83 36.89-42.21a64.336 64.336 0 0 1 18.49-4.72l18.13-24.23 32.15-42.97c3.45-4.61 7.19-8.9 11.2-12.84 8-7.89 17.03-14.44 26.74-19.51 4.86-2.54 9.89-4.71 15.05-6.49 10.33-3.58 21.19-5.63 32.24-6.04 11.05-.41 22.31.82 33.43 3.8l122.68 32.87c11.12 2.98 21.48 7.54 30.85 13.43a111.11 111.11 0 0 1 34.69 34.5c8.82 13.88 14.64 29.84 16.68 46.99l6.36 53.29 3.59 30.05a64.49 64.49 0 0 1 22.74 29.93c4.39 11.88 5.29 25.19 1.75 38.39zM255.58 234.34c-18.55-4.97-34.21 4.04-39.17 22.53-4.96 18.49 4.11 34.12 22.65 39.09 18.55 4.97 45.54 15.51 50.49-2.98 4.96-18.49-15.43-53.67-33.97-58.64zm290.61 28.17l-6.36-53.29c-.58-4.87-1.89-9.53-3.82-13.86-5.8-12.99-17.2-23.01-31.42-26.82l-122.68-32.87a48.008 48.008 0 0 0-50.86 17.61l-32.15 42.97 172 46.08 75.29 20.18zm18.49 54.65c-18.55-4.97-53.8 15.31-58.75 33.79-4.95 18.49 23.69 22.86 42.24 27.83 18.55 4.97 34.21-4.04 39.17-22.53 4.95-18.48-4.11-34.12-22.66-39.09z\"],\n    \"car-side\": [640, 512, [], \"f5e4\", \"M544 192h-16L419.22 56.02A64.025 64.025 0 0 0 369.24 32H155.33c-26.17 0-49.7 15.93-59.42 40.23L48 194.26C20.44 201.4 0 226.21 0 256v112c0 8.84 7.16 16 16 16h48c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h48c8.84 0 16-7.16 16-16v-80c0-53.02-42.98-96-96-96zM160 432c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm72-240H116.93l38.4-96H232v96zm48 0V96h89.24l76.8 96H280zm200 240c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"caret-down\": [320, 512, [], \"f0d7\", \"M31.3 192h257.3c17.8 0 26.7 21.5 14.1 34.1L174.1 354.8c-7.8 7.8-20.5 7.8-28.3 0L17.2 226.1C4.6 213.5 13.5 192 31.3 192z\"],\n    \"caret-left\": [192, 512, [], \"f0d9\", \"M192 127.338v257.324c0 17.818-21.543 26.741-34.142 14.142L29.196 270.142c-7.81-7.81-7.81-20.474 0-28.284l128.662-128.662c12.599-12.6 34.142-3.676 34.142 14.142z\"],\n    \"caret-right\": [192, 512, [], \"f0da\", \"M0 384.662V127.338c0-17.818 21.543-26.741 34.142-14.142l128.662 128.662c7.81 7.81 7.81 20.474 0 28.284L34.142 398.804C21.543 411.404 0 402.48 0 384.662z\"],\n    \"caret-square-down\": [448, 512, [], \"f150\", \"M448 80v352c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48zM92.5 220.5l123 123c4.7 4.7 12.3 4.7 17 0l123-123c7.6-7.6 2.2-20.5-8.5-20.5H101c-10.7 0-16.1 12.9-8.5 20.5z\"],\n    \"caret-square-left\": [448, 512, [], \"f191\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM259.515 124.485l-123.03 123.03c-4.686 4.686-4.686 12.284 0 16.971l123.029 123.029c7.56 7.56 20.485 2.206 20.485-8.485V132.971c.001-10.691-12.925-16.045-20.484-8.486z\"],\n    \"caret-square-right\": [448, 512, [], \"f152\", \"M48 32h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48zm140.485 355.515l123.029-123.029c4.686-4.686 4.686-12.284 0-16.971l-123.029-123.03c-7.56-7.56-20.485-2.206-20.485 8.485v246.059c0 10.691 12.926 16.045 20.485 8.486z\"],\n    \"caret-square-up\": [448, 512, [], \"f151\", \"M0 432V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48zm355.515-140.485l-123.03-123.03c-4.686-4.686-12.284-4.686-16.971 0L92.485 291.515c-7.56 7.56-2.206 20.485 8.485 20.485h246.059c10.691 0 16.045-12.926 8.486-20.485z\"],\n    \"caret-up\": [320, 512, [], \"f0d8\", \"M288.662 352H31.338c-17.818 0-26.741-21.543-14.142-34.142l128.662-128.662c7.81-7.81 20.474-7.81 28.284 0l128.662 128.662c12.6 12.599 3.676 34.142-14.142 34.142z\"],\n    \"carrot\": [512, 512, [], \"f787\", \"M298.2 156.6c-52.7-25.7-114.5-10.5-150.2 32.8l55.2 55.2c6.3 6.3 6.3 16.4 0 22.6-3.1 3.1-7.2 4.7-11.3 4.7s-8.2-1.6-11.3-4.7L130.4 217 2.3 479.7c-2.9 6-3.1 13.3 0 19.7 5.4 11.1 18.9 15.7 30 10.3l133.6-65.2-49.2-49.2c-6.3-6.2-6.3-16.4 0-22.6 6.3-6.2 16.4-6.2 22.6 0l57 57 102-49.8c24-11.7 44.5-31.3 57.1-57.1 30.1-61.7 4.5-136.1-57.2-166.2zm92.1-34.9C409.8 81 399.7 32.9 360 0c-50.3 41.7-52.5 107.5-7.9 151.9l8 8c44.4 44.6 110.3 42.4 151.9-7.9-32.9-39.7-81-49.8-121.7-30.3z\"],\n    \"cart-arrow-down\": [576, 512, [], \"f218\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM403.029 192H360v-60c0-6.627-5.373-12-12-12h-24c-6.627 0-12 5.373-12 12v60h-43.029c-10.691 0-16.045 12.926-8.485 20.485l67.029 67.029c4.686 4.686 12.284 4.686 16.971 0l67.029-67.029c7.559-7.559 2.205-20.485-8.486-20.485z\"],\n    \"cart-plus\": [576, 512, [], \"f217\", \"M504.717 320H211.572l6.545 32h268.418c15.401 0 26.816 14.301 23.403 29.319l-5.517 24.276C523.112 414.668 536 433.828 536 456c0 31.202-25.519 56.444-56.824 55.994-29.823-.429-54.35-24.631-55.155-54.447-.44-16.287 6.085-31.049 16.803-41.548H231.176C241.553 426.165 248 440.326 248 456c0 31.813-26.528 57.431-58.67 55.938-28.54-1.325-51.751-24.385-53.251-52.917-1.158-22.034 10.436-41.455 28.051-51.586L93.883 64H24C10.745 64 0 53.255 0 40V24C0 10.745 10.745 0 24 0h102.529c11.401 0 21.228 8.021 23.513 19.19L159.208 64H551.99c15.401 0 26.816 14.301 23.403 29.319l-47.273 208C525.637 312.246 515.923 320 504.717 320zM408 168h-48v-40c0-8.837-7.163-16-16-16h-16c-8.837 0-16 7.163-16 16v40h-48c-8.837 0-16 7.163-16 16v16c0 8.837 7.163 16 16 16h48v40c0 8.837 7.163 16 16 16h16c8.837 0 16-7.163 16-16v-40h48c8.837 0 16-7.163 16-16v-16c0-8.837-7.163-16-16-16z\"],\n    \"cash-register\": [512, 512, [], \"f788\", \"M511.1 378.8l-26.7-160c-2.6-15.4-15.9-26.7-31.6-26.7H208v-64h96c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h96v64H59.1c-15.6 0-29 11.3-31.6 26.7L.8 378.7c-.6 3.5-.9 7-.9 10.5V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-90.7c.1-3.5-.2-7-.8-10.5zM280 248c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16zm-32 64h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16zm-32-80c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16zM80 80V48h192v32H80zm40 200h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16zm16 64v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16zm216 112c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16zm24-112c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16zm48-80c0 8.8-7.2 16-16 16h-16c-8.8 0-16-7.2-16-16v-16c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v16z\"],\n    \"cat\": [512, 512, [], \"f6be\", \"M290.59 192c-20.18 0-106.82 1.98-162.59 85.95V192c0-52.94-43.06-96-96-96-17.67 0-32 14.33-32 32s14.33 32 32 32c17.64 0 32 14.36 32 32v256c0 35.3 28.7 64 64 64h176c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-32l128-96v144c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V289.86c-10.29 2.67-20.89 4.54-32 4.54-61.81 0-113.52-44.05-125.41-102.4zM448 96h-64l-64-64v134.4c0 53.02 42.98 96 96 96s96-42.98 96-96V32l-64 64zm-72 80c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm80 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"certificate\": [512, 512, [], \"f0a3\", \"M458.622 255.92l45.985-45.005c13.708-12.977 7.316-36.039-10.664-40.339l-62.65-15.99 17.661-62.015c4.991-17.838-11.829-34.663-29.661-29.671l-61.994 17.667-15.984-62.671C337.085.197 313.765-6.276 300.99 7.228L256 53.57 211.011 7.229c-12.63-13.351-36.047-7.234-40.325 10.668l-15.984 62.671-61.995-17.667C74.87 57.907 58.056 74.738 63.046 92.572l17.661 62.015-62.65 15.99C.069 174.878-6.31 197.944 7.392 210.915l45.985 45.005-45.985 45.004c-13.708 12.977-7.316 36.039 10.664 40.339l62.65 15.99-17.661 62.015c-4.991 17.838 11.829 34.663 29.661 29.671l61.994-17.667 15.984 62.671c4.439 18.575 27.696 24.018 40.325 10.668L256 458.61l44.989 46.001c12.5 13.488 35.987 7.486 40.325-10.668l15.984-62.671 61.994 17.667c17.836 4.994 34.651-11.837 29.661-29.671l-17.661-62.015 62.65-15.99c17.987-4.302 24.366-27.367 10.664-40.339l-45.984-45.004z\"],\n    \"chair\": [448, 512, [], \"f6c0\", \"M112 128c0-29.5 16.2-55 40-68.9V256h48V48h48v208h48V59.1c23.8 13.9 40 39.4 40 68.9v128h48V128C384 57.3 326.7 0 256 0h-64C121.3 0 64 57.3 64 128v128h48zm334.3 213.9l-10.7-32c-4.4-13.1-16.6-21.9-30.4-21.9H42.7c-13.8 0-26 8.8-30.4 21.9l-10.7 32C-5.2 362.6 10.2 384 32 384v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384h256v112c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V384c21.8 0 37.2-21.4 30.3-42.1z\"],\n    \"chalkboard\": [640, 512, [], \"f51b\", \"M96 64h448v352h64V40c0-22.06-17.94-40-40-40H72C49.94 0 32 17.94 32 40v376h64V64zm528 384H480v-64H288v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chalkboard-teacher\": [640, 512, [], \"f51c\", \"M208 352c-2.39 0-4.78.35-7.06 1.09C187.98 357.3 174.35 360 160 360c-14.35 0-27.98-2.7-40.95-6.91-2.28-.74-4.66-1.09-7.05-1.09C49.94 352-.33 402.48 0 464.62.14 490.88 21.73 512 48 512h224c26.27 0 47.86-21.12 48-47.38.33-62.14-49.94-112.62-112-112.62zm-48-32c53.02 0 96-42.98 96-96s-42.98-96-96-96-96 42.98-96 96 42.98 96 96 96zM592 0H208c-26.47 0-48 22.25-48 49.59V96c23.42 0 45.1 6.78 64 17.8V64h352v288h-64v-64H384v64h-76.24c19.1 16.69 33.12 38.73 39.69 64H592c26.47 0 48-22.25 48-49.59V49.59C640 22.25 618.47 0 592 0z\"],\n    \"charging-station\": [576, 512, [], \"f5e7\", \"M336 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h320c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm208-320V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-32V80c0-8.84-7.16-16-16-16s-16 7.16-16 16v48h-16c-8.84 0-16 7.16-16 16v32c0 35.76 23.62 65.69 56 75.93v118.49c0 13.95-9.5 26.92-23.26 29.19C431.22 402.5 416 388.99 416 372v-28c0-48.6-39.4-88-88-88h-8V64c0-35.35-28.65-64-64-64H96C60.65 0 32 28.65 32 64v352h288V304h8c22.09 0 40 17.91 40 40v24.61c0 39.67 28.92 75.16 68.41 79.01C481.71 452.05 520 416.41 520 372V251.93c32.38-10.24 56-40.17 56-75.93v-32c0-8.84-7.16-16-16-16h-16zm-283.91 47.76l-93.7 139c-2.2 3.33-6.21 5.24-10.39 5.24-7.67 0-13.47-6.28-11.67-12.92L167.35 224H108c-7.25 0-12.85-5.59-11.89-11.89l16-107C112.9 99.9 117.98 96 124 96h68c7.88 0 13.62 6.54 11.6 13.21L192 160h57.7c9.24 0 15.01 8.78 10.39 15.76z\"],\n    \"chart-area\": [512, 512, [], \"f1fe\", \"M500 384c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v308h436zM372.7 159.5L288 216l-85.3-113.7c-5.1-6.8-15.5-6.3-19.9 1L96 248v104h384l-89.9-187.8c-3.2-6.5-11.4-8.7-17.4-4.7z\"],\n    \"chart-bar\": [512, 512, [], \"f080\", \"M332.8 320h38.4c6.4 0 12.8-6.4 12.8-12.8V172.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v134.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V76.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v230.4c0 6.4 6.4 12.8 12.8 12.8zm-288 0h38.4c6.4 0 12.8-6.4 12.8-12.8v-70.4c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v70.4c0 6.4 6.4 12.8 12.8 12.8zm96 0h38.4c6.4 0 12.8-6.4 12.8-12.8V108.8c0-6.4-6.4-12.8-12.8-12.8h-38.4c-6.4 0-12.8 6.4-12.8 12.8v198.4c0 6.4 6.4 12.8 12.8 12.8zM496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"chart-line\": [512, 512, [], \"f201\", \"M496 384H64V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v336c0 17.67 14.33 32 32 32h464c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM464 96H345.94c-21.38 0-32.09 25.85-16.97 40.97l32.4 32.4L288 242.75l-73.37-73.37c-12.5-12.5-32.76-12.5-45.25 0l-68.69 68.69c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L192 237.25l73.37 73.37c12.5 12.5 32.76 12.5 45.25 0l96-96 32.4 32.4c15.12 15.12 40.97 4.41 40.97-16.97V112c.01-8.84-7.15-16-15.99-16z\"],\n    \"chart-pie\": [544, 512, [], \"f200\", \"M527.79 288H290.5l158.03 158.03c6.04 6.04 15.98 6.53 22.19.68 38.7-36.46 65.32-85.61 73.13-140.86 1.34-9.46-6.51-17.85-16.06-17.85zm-15.83-64.8C503.72 103.74 408.26 8.28 288.8.04 279.68-.59 272 7.1 272 16.24V240h223.77c9.14 0 16.82-7.68 16.19-16.8zM224 288V50.71c0-9.55-8.39-17.4-17.84-16.06C86.99 51.49-4.1 155.6.14 280.37 4.5 408.51 114.83 513.59 243.03 511.98c50.4-.63 96.97-16.87 135.26-44.03 7.9-5.6 8.42-17.23 1.57-24.08L224 288z\"],\n    \"check\": [512, 512, [], \"f00c\", \"M173.898 439.404l-166.4-166.4c-9.997-9.997-9.997-26.206 0-36.204l36.203-36.204c9.997-9.998 26.207-9.998 36.204 0L192 312.69 432.095 72.596c9.997-9.997 26.207-9.997 36.204 0l36.203 36.204c9.997 9.997 9.997 26.206 0 36.204l-294.4 294.401c-9.998 9.997-26.207 9.997-36.204-.001z\"],\n    \"check-circle\": [512, 512, [], \"f058\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM227.314 387.314l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.249-16.379-6.249-22.628 0L216 308.118l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.249 16.379 6.249 22.628.001z\"],\n    \"check-double\": [512, 512, [], \"f560\", \"M505 174.8l-39.6-39.6c-9.4-9.4-24.6-9.4-33.9 0L192 374.7 80.6 263.2c-9.4-9.4-24.6-9.4-33.9 0L7 302.9c-9.4 9.4-9.4 24.6 0 34L175 505c9.4 9.4 24.6 9.4 33.9 0l296-296.2c9.4-9.5 9.4-24.7.1-34zm-324.3 106c6.2 6.3 16.4 6.3 22.6 0l208-208.2c6.2-6.3 6.2-16.4 0-22.6L366.1 4.7c-6.2-6.3-16.4-6.3-22.6 0L192 156.2l-55.4-55.5c-6.2-6.3-16.4-6.3-22.6 0L68.7 146c-6.2 6.3-6.2 16.4 0 22.6l112 112.2z\"],\n    \"check-square\": [448, 512, [], \"f14a\", \"M400 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zm-204.686-98.059l184-184c6.248-6.248 6.248-16.379 0-22.627l-22.627-22.627c-6.248-6.248-16.379-6.249-22.628 0L184 302.745l-70.059-70.059c-6.248-6.248-16.379-6.248-22.628 0l-22.627 22.627c-6.248 6.248-6.248 16.379 0 22.627l104 104c6.249 6.25 16.379 6.25 22.628.001z\"],\n    \"cheese\": [512, 512, [], \"f7ef\", \"M0 288v160a32 32 0 0 0 32 32h448a32 32 0 0 0 32-32V288zM299.83 32a32 32 0 0 0-21.13 7L0 256h512c0-119.89-94-217.8-212.17-224z\"],\n    \"chess\": [512, 512, [], \"f439\", \"M74 208H64a16 16 0 0 0-16 16v16a16 16 0 0 0 16 16h15.94A535.78 535.78 0 0 1 64 384h128a535.78 535.78 0 0 1-15.94-128H192a16 16 0 0 0 16-16v-16a16 16 0 0 0-16-16h-10l33.89-90.38a16 16 0 0 0-15-21.62H144V64h24a8 8 0 0 0 8-8V40a8 8 0 0 0-8-8h-24V8a8 8 0 0 0-8-8h-16a8 8 0 0 0-8 8v24H88a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h24v32H55.09a16 16 0 0 0-15 21.62zm173.16 251.58L224 448v-16a16 16 0 0 0-16-16H48a16 16 0 0 0-16 16v16L8.85 459.58A16 16 0 0 0 0 473.89V496a16 16 0 0 0 16 16h224a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31zm92.77-157.78l-3.29 82.2h126.72l-3.29-82.21 24.6-20.79A32 32 0 0 0 496 256.54V198a6 6 0 0 0-6-6h-26.38a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H373.1a6 6 0 0 0-6 6v26h-24.71v-26a6 6 0 0 0-6-6H310a6 6 0 0 0-6 6v58.6a32 32 0 0 0 11.36 24.4zM384 304a16 16 0 0 1 32 0v32h-32zm119.16 155.58L480 448v-16a16 16 0 0 0-16-16H336a16 16 0 0 0-16 16v16l-23.15 11.58a16 16 0 0 0-8.85 14.31V496a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-22.11a16 16 0 0 0-8.84-14.31z\"],\n    \"chess-bishop\": [320, 512, [], \"f43a\", \"M8 287.88c0 51.64 22.14 73.83 56 84.6V416h192v-43.52c33.86-10.77 56-33 56-84.6 0-30.61-10.73-67.1-26.69-102.56L185 285.65a8 8 0 0 1-11.31 0l-11.31-11.31a8 8 0 0 1 0-11.31L270.27 155.1c-20.8-37.91-46.47-72.1-70.87-92.59C213.4 59.09 224 47.05 224 32a32 32 0 0 0-32-32h-64a32 32 0 0 0-32 32c0 15 10.6 27.09 24.6 30.51C67.81 106.8 8 214.5 8 287.88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-board\": [512, 512, [], \"f43c\", \"M255.9.2h-64v64h64zM0 64.17v64h64v-64zM128 .2H64v64h64zm64 255.9v64h64v-64zM0 192.12v64h64v-64zM383.85.2h-64v64h64zm128 0h-64v64h64zM128 256.1H64v64h64zM511.8 448v-64h-64v64zm0-128v-64h-64v64zM383.85 512h64v-64h-64zm128-319.88v-64h-64v64zM128 512h64v-64h-64zM0 512h64v-64H0zm255.9 0h64v-64h-64zM0 320.07v64h64v-64zm319.88-191.92v-64h-64v64zm-64 128h64v-64h-64zm-64 128v64h64v-64zm128-64h64v-64h-64zm0-127.95h64v-64h-64zm0 191.93v64h64v-64zM64 384.05v64h64v-64zm128-255.9v-64h-64v64zm191.92 255.9h64v-64h-64zm-128-191.93v-64h-64v64zm128-127.95v64h64v-64zm-128 255.9v64h64v-64zm-64-127.95H128v64h64zm191.92 64h64v-64h-64zM128 128.15H64v64h64zm0 191.92v64h64v-64z\"],\n    \"chess-king\": [448, 512, [], \"f43f\", \"M400 448H48a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm16-288H256v-48h40a8 8 0 0 0 8-8V56a8 8 0 0 0-8-8h-40V8a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v40h-40a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8h40v48H32a32 32 0 0 0-30.52 41.54L74.56 416h298.88l73.08-214.46A32 32 0 0 0 416 160z\"],\n    \"chess-knight\": [384, 512, [], \"f441\", \"M19 272.47l40.63 18.06a32 32 0 0 0 24.88.47l12.78-5.12a32 32 0 0 0 18.76-20.5l9.22-30.65a24 24 0 0 1 12.55-15.65L159.94 208v50.33a48 48 0 0 1-26.53 42.94l-57.22 28.65A80 80 0 0 0 32 401.48V416h319.86V224c0-106-85.92-192-191.92-192H12A12 12 0 0 0 0 44a16.9 16.9 0 0 0 1.79 7.58L16 80l-9 9a24 24 0 0 0-7 17v137.21a32 32 0 0 0 19 29.26zM52 128a20 20 0 1 1-20 20 20 20 0 0 1 20-20zm316 320H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-pawn\": [320, 512, [], \"f443\", \"M105.1 224H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h16v5.49c0 44-4.14 86.6-24 122.51h176c-19.89-35.91-24-78.51-24-122.51V288h16a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-25.1c29.39-18.38 49.1-50.78 49.1-88a104 104 0 0 0-208 0c0 37.22 19.71 69.62 49.1 88zM304 448H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chess-queen\": [512, 512, [], \"f445\", \"M256 112a56 56 0 1 0-56-56 56 56 0 0 0 56 56zm176 336H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm72.87-263.84l-28.51-15.92c-7.44-5-16.91-2.46-22.29 4.68a47.59 47.59 0 0 1-47.23 18.23C383.7 186.86 368 164.93 368 141.4a13.4 13.4 0 0 0-13.4-13.4h-38.77c-6 0-11.61 4-12.86 9.91a48 48 0 0 1-93.94 0c-1.25-5.92-6.82-9.91-12.86-9.91H157.4a13.4 13.4 0 0 0-13.4 13.4c0 25.69-19 48.75-44.67 50.49a47.5 47.5 0 0 1-41.54-19.15c-5.28-7.09-14.73-9.45-22.09-4.54l-28.57 16a16 16 0 0 0-5.44 20.47L104.24 416h303.52l102.55-211.37a16 16 0 0 0-5.44-20.47z\"],\n    \"chess-rook\": [384, 512, [], \"f447\", \"M368 32h-56a16 16 0 0 0-16 16v48h-48V48a16 16 0 0 0-16-16h-80a16 16 0 0 0-16 16v48H88.1V48a16 16 0 0 0-16-16H16A16 16 0 0 0 0 48v176l64 32c0 48.33-1.54 95-13.21 160h282.42C321.54 351 320 303.72 320 256l64-32V48a16 16 0 0 0-16-16zM224 320h-64v-64a32 32 0 0 1 64 0zm144 128H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h352a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"chevron-circle-down\": [512, 512, [], \"f13a\", \"M504 256c0 137-111 248-248 248S8 393 8 256 119 8 256 8s248 111 248 248zM273 369.9l135.5-135.5c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L256 285.1 154.4 183.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L239 369.9c9.4 9.4 24.6 9.4 34 0z\"],\n    \"chevron-circle-left\": [512, 512, [], \"f137\", \"M256 504C119 504 8 393 8 256S119 8 256 8s248 111 248 248-111 248-248 248zM142.1 273l135.5 135.5c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L226.9 256l101.6-101.6c9.4-9.4 9.4-24.6 0-33.9l-17-17c-9.4-9.4-24.6-9.4-33.9 0L142.1 239c-9.4 9.4-9.4 24.6 0 34z\"],\n    \"chevron-circle-right\": [512, 512, [], \"f138\", \"M256 8c137 0 248 111 248 248S393 504 256 504 8 393 8 256 119 8 256 8zm113.9 231L234.4 103.5c-9.4-9.4-24.6-9.4-33.9 0l-17 17c-9.4 9.4-9.4 24.6 0 33.9L285.1 256 183.5 357.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L369.9 273c9.4-9.4 9.4-24.6 0-34z\"],\n    \"chevron-circle-up\": [512, 512, [], \"f139\", \"M8 256C8 119 119 8 256 8s248 111 248 248-111 248-248 248S8 393 8 256zm231-113.9L103.5 277.6c-9.4 9.4-9.4 24.6 0 33.9l17 17c9.4 9.4 24.6 9.4 33.9 0L256 226.9l101.6 101.6c9.4 9.4 24.6 9.4 33.9 0l17-17c9.4-9.4 9.4-24.6 0-33.9L273 142.1c-9.4-9.4-24.6-9.4-34 0z\"],\n    \"chevron-down\": [448, 512, [], \"f078\", \"M207.029 381.476L12.686 187.132c-9.373-9.373-9.373-24.569 0-33.941l22.667-22.667c9.357-9.357 24.522-9.375 33.901-.04L224 284.505l154.745-154.021c9.379-9.335 24.544-9.317 33.901.04l22.667 22.667c9.373 9.373 9.373 24.569 0 33.941L240.971 381.476c-9.373 9.372-24.569 9.372-33.942 0z\"],\n    \"chevron-left\": [320, 512, [], \"f053\", \"M34.52 239.03L228.87 44.69c9.37-9.37 24.57-9.37 33.94 0l22.67 22.67c9.36 9.36 9.37 24.52.04 33.9L131.49 256l154.02 154.75c9.34 9.38 9.32 24.54-.04 33.9l-22.67 22.67c-9.37 9.37-24.57 9.37-33.94 0L34.52 272.97c-9.37-9.37-9.37-24.57 0-33.94z\"],\n    \"chevron-right\": [320, 512, [], \"f054\", \"M285.476 272.971L91.132 467.314c-9.373 9.373-24.569 9.373-33.941 0l-22.667-22.667c-9.357-9.357-9.375-24.522-.04-33.901L188.505 256 34.484 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L285.475 239.03c9.373 9.372 9.373 24.568.001 33.941z\"],\n    \"chevron-up\": [448, 512, [], \"f077\", \"M240.971 130.524l194.343 194.343c9.373 9.373 9.373 24.569 0 33.941l-22.667 22.667c-9.357 9.357-24.522 9.375-33.901.04L224 227.495 69.255 381.516c-9.379 9.335-24.544 9.317-33.901-.04l-22.667-22.667c-9.373-9.373-9.373-24.569 0-33.941L207.03 130.525c9.372-9.373 24.568-9.373 33.941-.001z\"],\n    \"child\": [384, 512, [], \"f1ae\", \"M120 72c0-39.765 32.235-72 72-72s72 32.235 72 72c0 39.764-32.235 72-72 72s-72-32.236-72-72zm254.627 1.373c-12.496-12.497-32.758-12.497-45.254 0L242.745 160H141.254L54.627 73.373c-12.496-12.497-32.758-12.497-45.254 0-12.497 12.497-12.497 32.758 0 45.255L104 213.254V480c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V368h16v112c0 17.673 14.327 32 32 32h16c17.673 0 32-14.327 32-32V213.254l94.627-94.627c12.497-12.497 12.497-32.757 0-45.254z\"],\n    \"church\": [640, 512, [], \"f51d\", \"M464.46 246.68L352 179.2V128h48c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-48V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v48h-48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v51.2l-112.46 67.48A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.65-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.54A32.024 32.024 0 0 0 0 395.96zm620.61-29.42L512 320v192h112c8.84 0 16-7.16 16-16V395.96c0-12.8-7.63-24.37-19.39-29.42z\"],\n    \"circle\": [512, 512, [], \"f111\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8z\"],\n    \"circle-notch\": [512, 512, [], \"f1ce\", \"M288 39.056v16.659c0 10.804 7.281 20.159 17.686 23.066C383.204 100.434 440 171.518 440 256c0 101.689-82.295 184-184 184-101.689 0-184-82.295-184-184 0-84.47 56.786-155.564 134.312-177.219C216.719 75.874 224 66.517 224 55.712V39.064c0-15.709-14.834-27.153-30.046-23.234C86.603 43.482 7.394 141.206 8.003 257.332c.72 137.052 111.477 246.956 248.531 246.667C393.255 503.711 504 392.788 504 256c0-115.633-79.14-212.779-186.211-240.236C302.678 11.889 288 23.456 288 39.056z\"],\n    \"city\": [640, 512, [], \"f64f\", \"M616 192H480V24c0-13.26-10.74-24-24-24H312c-13.26 0-24 10.74-24 24v72h-64V16c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v80h-64V16c0-8.84-7.16-16-16-16H80c-8.84 0-16 7.16-16 16v80H24c-13.26 0-24 10.74-24 24v360c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V216c0-13.26-10.75-24-24-24zM128 404c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12H76c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm128 192c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12V76c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm160 288c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40zm0-96c0 6.63-5.37 12-12 12h-40c-6.63 0-12-5.37-12-12v-40c0-6.63 5.37-12 12-12h40c6.63 0 12 5.37 12 12v40z\"],\n    \"clinic-medical\": [576, 512, [], \"f7f2\", \"M288 115L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2zm96 261a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8zm186.69-139.72l-255.94-226a39.85 39.85 0 0 0-53.45 0l-256 226a16 16 0 0 0-1.21 22.6L25.5 282.7a16 16 0 0 0 22.6 1.21L277.42 81.63a16 16 0 0 1 21.17 0L527.91 283.9a16 16 0 0 0 22.6-1.21l21.4-23.82a16 16 0 0 0-1.22-22.59z\"],\n    \"clipboard\": [384, 512, [], \"f328\", \"M384 112v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h80c0-35.29 28.71-64 64-64s64 28.71 64 64h80c26.51 0 48 21.49 48 48zM192 40c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24m96 114v-20a6 6 0 0 0-6-6H102a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6h180a6 6 0 0 0 6-6z\"],\n    \"clipboard-check\": [384, 512, [], \"f46c\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm121.2 231.8l-143 141.8c-4.7 4.7-12.3 4.6-17-.1l-82.6-83.3c-4.7-4.7-4.6-12.3.1-17L99.1 285c4.7-4.7 12.3-4.6 17 .1l46 46.4 106-105.2c4.7-4.7 12.3-4.6 17 .1l28.2 28.4c4.7 4.8 4.6 12.3-.1 17z\"],\n    \"clipboard-list\": [384, 512, [], \"f46d\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM96 424c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm0-96c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24zm96-192c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm128 368c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16z\"],\n    \"clock\": [512, 512, [], \"f017\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm57.1 350.1L224.9 294c-3.1-2.3-4.9-5.9-4.9-9.7V116c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v137.7l63.5 46.2c5.4 3.9 6.5 11.4 2.6 16.8l-28.2 38.8c-3.9 5.3-11.4 6.5-16.8 2.6z\"],\n    \"clone\": [512, 512, [], \"f24d\", \"M464 0c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48H176c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h288M176 416c-44.112 0-80-35.888-80-80V128H48c-26.51 0-48 21.49-48 48v288c0 26.51 21.49 48 48 48h288c26.51 0 48-21.49 48-48v-48H176z\"],\n    \"closed-captioning\": [512, 512, [], \"f20a\", \"M464 64H48C21.5 64 0 85.5 0 112v288c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM218.1 287.7c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.6 56.8-172.8 32.1-172.8-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7l-17.5 30.5c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2.1 48 51.1 70.5 92.3 32.6zm190.4 0c2.8-2.5 7.1-2.1 9.2.9l19.5 27.7c1.7 2.4 1.5 5.6-.5 7.7-53.5 56.9-172.7 32.1-172.7-67.9 0-97.3 121.7-119.5 172.5-70.1 2.1 2 2.5 3.2 1 5.7L420 222.2c-1.9 3.1-6.2 4-9.1 1.7-40.8-32-94.6-14.9-94.6 31.2 0 48 51 70.5 92.2 32.6z\"],\n    \"cloud\": [640, 512, [], \"f0c2\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4z\"],\n    \"cloud-download-alt\": [640, 512, [], \"f381\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zm-132.9 88.7L299.3 420.7c-6.2 6.2-16.4 6.2-22.6 0L171.3 315.3c-10.1-10.1-2.9-27.3 11.3-27.3H248V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v112h65.4c14.2 0 21.4 17.2 11.3 27.3z\"],\n    \"cloud-meatball\": [512, 512, [], \"f73b\", \"M48 352c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm416 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm-119 11.1c4.6-14.5 1.6-30.8-9.8-42.3-11.5-11.5-27.8-14.4-42.3-9.9-7-13.5-20.7-23-36.9-23s-29.9 9.5-36.9 23c-14.5-4.6-30.8-1.6-42.3 9.9-11.5 11.5-14.4 27.8-9.9 42.3-13.5 7-23 20.7-23 36.9s9.5 29.9 23 36.9c-4.6 14.5-1.6 30.8 9.9 42.3 8.2 8.2 18.9 12.3 29.7 12.3 4.3 0 8.5-1.1 12.6-2.5 7 13.5 20.7 23 36.9 23s29.9-9.5 36.9-23c4.1 1.3 8.3 2.5 12.6 2.5 10.8 0 21.5-4.1 29.7-12.3 11.5-11.5 14.4-27.8 9.8-42.3 13.5-7 23-20.7 23-36.9s-9.5-29.9-23-36.9zM512 224c0-53-43-96-96-96-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h43.4c3.6-8 8.4-15.4 14.8-21.8 13.5-13.5 31.5-21.1 50.8-21.3 13.5-13.2 31.7-20.9 51-20.9s37.5 7.7 51 20.9c19.3.2 37.3 7.8 50.8 21.3 6.4 6.4 11.3 13.8 14.8 21.8H416c53 0 96-43 96-96z\"],\n    \"cloud-moon\": [576, 512, [], \"f6c3\", \"M342.8 352.7c5.7-9.6 9.2-20.7 9.2-32.7 0-35.3-28.7-64-64-64-17.2 0-32.8 6.9-44.3 17.9-16.3-29.6-47.5-49.9-83.7-49.9-53 0-96 43-96 96 0 2 .5 3.8.6 5.7C27.1 338.8 0 374.1 0 416c0 53 43 96 96 96h240c44.2 0 80-35.8 80-80 0-41.9-32.3-75.8-73.2-79.3zm222.5-54.3c-93.1 17.7-178.5-53.7-178.5-147.7 0-54.2 29-104 76.1-130.8 7.3-4.1 5.4-15.1-2.8-16.7C448.4 1.1 436.7 0 425 0 319.1 0 233.1 85.9 233.1 192c0 8.5.7 16.8 1.8 25 5.9 4.3 11.6 8.9 16.7 14.2 11.4-4.7 23.7-7.2 36.4-7.2 52.9 0 96 43.1 96 96 0 3.6-.2 7.2-.6 10.7 23.6 10.8 42.4 29.5 53.5 52.6 54.4-3.4 103.7-29.3 137.1-70.4 5.3-6.5-.5-16.1-8.7-14.5z\"],\n    \"cloud-moon-rain\": [576, 512, [], \"f73c\", \"M350.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C27.6 232.9 0 265.2 0 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm217.4-1.7c-70.4 13.3-135-40.3-135-110.8 0-40.6 21.9-78 57.5-98.1 5.5-3.1 4.1-11.4-2.1-12.5C479.6.8 470.7 0 461.8 0c-77.9 0-141.1 61.2-144.4 137.9 26.7 11.9 48.2 33.8 58.9 61.7 37.1 14.3 64 47.4 70.2 86.8 5.1.5 10 1.5 15.2 1.5 44.7 0 85.6-20.2 112.6-53.3 4.2-4.8-.2-12-6.4-10.8zM364.5 418.1c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-rain\": [512, 512, [], \"f73d\", \"M416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.1 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96zM88 374.2c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0zm160 0c-12.8 44.4-40 56.4-40 87.7 0 27.7 21.5 50.1 48 50.1s48-22.4 48-50.1c0-31.4-27.2-43.1-40-87.7-2.2-8.1-13.5-8.5-16 0z\"],\n    \"cloud-showers-heavy\": [512, 512, [], \"f740\", \"M183.9 370.1c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-192 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm384 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zm-96 0c-7.6-4.4-17.4-1.8-21.8 6l-64 112c-4.4 7.7-1.7 17.5 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l64-112c4.4-7.6 1.7-17.4-6-21.8zM416 128c-.6 0-1.1.2-1.6.2 1.1-5.2 1.6-10.6 1.6-16.2 0-44.2-35.8-80-80-80-24.6 0-46.3 11.3-61 28.8C256.4 24.8 219.3 0 176 0 114.2 0 64 50.1 64 112c0 7.3.8 14.3 2.1 21.2C27.8 145.8 0 181.5 0 224c0 53 43 96 96 96h320c53 0 96-43 96-96s-43-96-96-96z\"],\n    \"cloud-sun\": [640, 512, [], \"f6c4\", \"M575.2 325.7c.2-1.9.8-3.7.8-5.6 0-35.3-28.7-64-64-64-12.6 0-24.2 3.8-34.1 10-17.6-38.8-56.5-66-101.9-66-61.8 0-112 50.1-112 112 0 3 .7 5.8.9 8.7-49.6 3.7-88.9 44.7-88.9 95.3 0 53 43 96 96 96h272c53 0 96-43 96-96 0-42.1-27.2-77.4-64.8-90.4zm-430.4-22.6c-43.7-43.7-43.7-114.7 0-158.3 43.7-43.7 114.7-43.7 158.4 0 9.7 9.7 16.9 20.9 22.3 32.7 9.8-3.7 20.1-6 30.7-7.5L386 81.1c4-11.9-7.3-23.1-19.2-19.2L279 91.2 237.5 8.4C232-2.8 216-2.8 210.4 8.4L169 91.2 81.1 61.9C69.3 58 58 69.3 61.9 81.1l29.3 87.8-82.8 41.5c-11.2 5.6-11.2 21.5 0 27.1l82.8 41.4-29.3 87.8c-4 11.9 7.3 23.1 19.2 19.2l76.1-25.3c6.1-12.4 14-23.7 23.6-33.5-13.1-5.4-25.4-13.4-36-24zm-4.8-79.2c0 40.8 29.3 74.8 67.9 82.3 8-4.7 16.3-8.8 25.2-11.7 5.4-44.3 31-82.5 67.4-105C287.3 160.4 258 140 224 140c-46.3 0-84 37.6-84 83.9z\"],\n    \"cloud-sun-rain\": [576, 512, [], \"f743\", \"M510.5 225.5c-6.9-37.2-39.3-65.5-78.5-65.5-12.3 0-23.9 3-34.3 8-17.4-24.1-45.6-40-77.7-40-53 0-96 43-96 96 0 .5.2 1.1.2 1.6C187.6 233 160 265.2 160 304c0 44.2 35.8 80 80 80h256c44.2 0 80-35.8 80-80 0-39.2-28.2-71.7-65.5-78.5zm-386.4 34.4c-37.4-37.4-37.4-98.3 0-135.8 34.6-34.6 89.1-36.8 126.7-7.4 20-12.9 43.6-20.7 69.2-20.7.7 0 1.3.2 2 .2l8.9-26.7c3.4-10.2-6.3-19.8-16.5-16.4l-75.3 25.1-35.5-71c-4.8-9.6-18.5-9.6-23.3 0l-35.5 71-75.3-25.1c-10.2-3.4-19.8 6.3-16.4 16.5l25.1 75.3-71 35.5c-9.6 4.8-9.6 18.5 0 23.3l71 35.5-25.1 75.3c-3.4 10.2 6.3 19.8 16.5 16.5l59.2-19.7c-.2-2.4-.7-4.7-.7-7.2 0-12.5 2.3-24.5 6.2-35.9-3.6-2.7-7.1-5.2-10.2-8.3zm69.8-58c4.3-24.5 15.8-46.4 31.9-64-9.8-6.2-21.4-9.9-33.8-9.9-35.3 0-64 28.7-64 64 0 18.7 8.2 35.4 21.1 47.1 11.3-15.9 26.6-28.9 44.8-37.2zm330.6 216.2c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8zm-96 0c-7.6-4.3-17.4-1.8-21.8 6l-36.6 64c-4.4 7.7-1.7 17.4 6 21.8 2.5 1.4 5.2 2.1 7.9 2.1 5.5 0 10.9-2.9 13.9-8.1l36.6-64c4.3-7.7 1.7-17.4-6-21.8z\"],\n    \"cloud-upload-alt\": [640, 512, [], \"f382\", \"M537.6 226.6c4.1-10.7 6.4-22.4 6.4-34.6 0-53-43-96-96-96-19.7 0-38.1 6-53.3 16.2C367 64.2 315.3 32 256 32c-88.4 0-160 71.6-160 160 0 2.7.1 5.4.2 8.1C40.2 219.8 0 273.2 0 336c0 79.5 64.5 144 144 144h368c70.7 0 128-57.3 128-128 0-61.9-44-113.6-102.4-125.4zM393.4 288H328v112c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V288h-65.4c-14.3 0-21.4-17.2-11.3-27.3l105.4-105.4c6.2-6.2 16.4-6.2 22.6 0l105.4 105.4c10.1 10.1 2.9 27.3-11.3 27.3z\"],\n    \"cocktail\": [576, 512, [], \"f561\", \"M296 464h-56V338.78l168.74-168.73c15.52-15.52 4.53-42.05-17.42-42.05H24.68c-21.95 0-32.94 26.53-17.42 42.05L176 338.78V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM432 0c-62.61 0-115.35 40.2-135.18 96h52.54c16.65-28.55 47.27-48 82.64-48 52.93 0 96 43.06 96 96s-43.07 96-96 96c-14.04 0-27.29-3.2-39.32-8.64l-35.26 35.26C379.23 279.92 404.59 288 432 288c79.53 0 144-64.47 144-144S511.53 0 432 0z\"],\n    \"code\": [640, 512, [], \"f121\", \"M278.9 511.5l-61-17.7c-6.4-1.8-10-8.5-8.2-14.9L346.2 8.7c1.8-6.4 8.5-10 14.9-8.2l61 17.7c6.4 1.8 10 8.5 8.2 14.9L293.8 503.3c-1.9 6.4-8.5 10.1-14.9 8.2zm-114-112.2l43.5-46.4c4.6-4.9 4.3-12.7-.8-17.2L117 256l90.6-79.7c5.1-4.5 5.5-12.3.8-17.2l-43.5-46.4c-4.5-4.8-12.1-5.1-17-.5L3.8 247.2c-5.1 4.7-5.1 12.8 0 17.5l144.1 135.1c4.9 4.6 12.5 4.4 17-.5zm327.2.6l144.1-135.1c5.1-4.7 5.1-12.8 0-17.5L492.1 112.1c-4.8-4.5-12.4-4.3-17 .5L431.6 159c-4.6 4.9-4.3 12.7.8 17.2L523 256l-90.6 79.7c-5.1 4.5-5.5 12.3-.8 17.2l43.5 46.4c4.5 4.9 12.1 5.1 17 .6z\"],\n    \"code-branch\": [384, 512, [], \"f126\", \"M384 144c0-44.2-35.8-80-80-80s-80 35.8-80 80c0 36.4 24.3 67.1 57.5 76.8-.6 16.1-4.2 28.5-11 36.9-15.4 19.2-49.3 22.4-85.2 25.7-28.2 2.6-57.4 5.4-81.3 16.9v-144c32.5-10.2 56-40.5 56-76.3 0-44.2-35.8-80-80-80S0 35.8 0 80c0 35.8 23.5 66.1 56 76.3v199.3C23.5 365.9 0 396.2 0 432c0 44.2 35.8 80 80 80s80-35.8 80-80c0-34-21.2-63.1-51.2-74.6 3.1-5.2 7.8-9.8 14.9-13.4 16.2-8.2 40.4-10.4 66.1-12.8 42.2-3.9 90-8.4 118.2-43.4 14-17.4 21.1-39.8 21.6-67.9 31.6-10.8 54.4-40.7 54.4-75.9zM80 64c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16zm0 384c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm224-320c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16 7.2-16 16-16z\"],\n    \"coffee\": [640, 512, [], \"f0f4\", \"M192 384h192c53 0 96-43 96-96h32c70.6 0 128-57.4 128-128S582.6 32 512 32H120c-13.3 0-24 10.7-24 24v232c0 53 43 96 96 96zM512 96c35.3 0 64 28.7 64 64s-28.7 64-64 64h-32V96h32zm47.7 384H48.3c-47.6 0-61-64-36-64h583.3c25 0 11.8 64-35.9 64z\"],\n    \"cog\": [512, 512, [], \"f013\", \"M487.4 315.7l-42.6-24.6c4.3-23.2 4.3-47 0-70.2l42.6-24.6c4.9-2.8 7.1-8.6 5.5-14-11.1-35.6-30-67.8-54.7-94.6-3.8-4.1-10-5.1-14.8-2.3L380.8 110c-17.9-15.4-38.5-27.3-60.8-35.1V25.8c0-5.6-3.9-10.5-9.4-11.7-36.7-8.2-74.3-7.8-109.2 0-5.5 1.2-9.4 6.1-9.4 11.7V75c-22.2 7.9-42.8 19.8-60.8 35.1L88.7 85.5c-4.9-2.8-11-1.9-14.8 2.3-24.7 26.7-43.6 58.9-54.7 94.6-1.7 5.4.6 11.2 5.5 14L67.3 221c-4.3 23.2-4.3 47 0 70.2l-42.6 24.6c-4.9 2.8-7.1 8.6-5.5 14 11.1 35.6 30 67.8 54.7 94.6 3.8 4.1 10 5.1 14.8 2.3l42.6-24.6c17.9 15.4 38.5 27.3 60.8 35.1v49.2c0 5.6 3.9 10.5 9.4 11.7 36.7 8.2 74.3 7.8 109.2 0 5.5-1.2 9.4-6.1 9.4-11.7v-49.2c22.2-7.9 42.8-19.8 60.8-35.1l42.6 24.6c4.9 2.8 11 1.9 14.8-2.3 24.7-26.7 43.6-58.9 54.7-94.6 1.5-5.5-.7-11.3-5.6-14.1zM256 336c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"cogs\": [640, 512, [], \"f085\", \"M512.1 191l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0L552 6.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zm-10.5-58.8c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.7-82.4 14.3-52.8 52.8zM386.3 286.1l33.7 16.8c10.1 5.8 14.5 18.1 10.5 29.1-8.9 24.2-26.4 46.4-42.6 65.8-7.4 8.9-20.2 11.1-30.3 5.3l-29.1-16.8c-16 13.7-34.6 24.6-54.9 31.7v33.6c0 11.6-8.3 21.6-19.7 23.6-24.6 4.2-50.4 4.4-75.9 0-11.5-2-20-11.9-20-23.6V418c-20.3-7.2-38.9-18-54.9-31.7L74 403c-10 5.8-22.9 3.6-30.3-5.3-16.2-19.4-33.3-41.6-42.2-65.7-4-10.9.4-23.2 10.5-29.1l33.3-16.8c-3.9-20.9-3.9-42.4 0-63.4L12 205.8c-10.1-5.8-14.6-18.1-10.5-29 8.9-24.2 26-46.4 42.2-65.8 7.4-8.9 20.2-11.1 30.3-5.3l29.1 16.8c16-13.7 34.6-24.6 54.9-31.7V57.1c0-11.5 8.2-21.5 19.6-23.5 24.6-4.2 50.5-4.4 76-.1 11.5 2 20 11.9 20 23.6v33.6c20.3 7.2 38.9 18 54.9 31.7l29.1-16.8c10-5.8 22.9-3.6 30.3 5.3 16.2 19.4 33.2 41.6 42.1 65.8 4 10.9.1 23.2-10 29.1l-33.7 16.8c3.9 21 3.9 42.5 0 63.5zm-117.6 21.1c59.2-77-28.7-164.9-105.7-105.7-59.2 77 28.7 164.9 105.7 105.7zm243.4 182.7l-8.2 14.3c-3 5.3-9.4 7.5-15.1 5.4-11.8-4.4-22.6-10.7-32.1-18.6-4.6-3.8-5.8-10.5-2.8-15.7l8.2-14.3c-6.9-8-12.3-17.3-15.9-27.4h-16.5c-6 0-11.2-4.3-12.2-10.3-2-12-2.1-24.6 0-37.1 1-6 6.2-10.4 12.2-10.4h16.5c3.6-10.1 9-19.4 15.9-27.4l-8.2-14.3c-3-5.2-1.9-11.9 2.8-15.7 9.5-7.9 20.4-14.2 32.1-18.6 5.7-2.1 12.1.1 15.1 5.4l8.2 14.3c10.5-1.9 21.2-1.9 31.7 0l8.2-14.3c3-5.3 9.4-7.5 15.1-5.4 11.8 4.4 22.6 10.7 32.1 18.6 4.6 3.8 5.8 10.5 2.8 15.7l-8.2 14.3c6.9 8 12.3 17.3 15.9 27.4h16.5c6 0 11.2 4.3 12.2 10.3 2 12 2.1 24.6 0 37.1-1 6-6.2 10.4-12.2 10.4h-16.5c-3.6 10.1-9 19.4-15.9 27.4l8.2 14.3c3 5.2 1.9 11.9-2.8 15.7-9.5 7.9-20.4 14.2-32.1 18.6-5.7 2.1-12.1-.1-15.1-5.4l-8.2-14.3c-10.4 1.9-21.2 1.9-31.7 0zM501.6 431c38.5 29.6 82.4-14.3 52.8-52.8-38.5-29.6-82.4 14.3-52.8 52.8z\"],\n    \"coins\": [512, 512, [], \"f51e\", \"M0 405.3V448c0 35.3 86 64 192 64s192-28.7 192-64v-42.7C342.7 434.4 267.2 448 192 448S41.3 434.4 0 405.3zM320 128c106 0 192-28.7 192-64S426 0 320 0 128 28.7 128 64s86 64 192 64zM0 300.4V352c0 35.3 86 64 192 64s192-28.7 192-64v-51.6c-41.3 34-116.9 51.6-192 51.6S41.3 334.4 0 300.4zm416 11c57.3-11.1 96-31.7 96-55.4v-42.7c-23.2 16.4-57.3 27.6-96 34.5v63.6zM192 160C86 160 0 195.8 0 240s86 80 192 80 192-35.8 192-80-86-80-192-80zm219.3 56.3c60-10.8 100.7-32 100.7-56.3v-42.7c-35.5 25.1-96.5 38.6-160.7 41.8 29.5 14.3 51.2 33.5 60 57.2z\"],\n    \"columns\": [512, 512, [], \"f0db\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64V160h160v256zm224 0H288V160h160v256z\"],\n    \"comment\": [512, 512, [], \"f075\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32z\"],\n    \"comment-alt\": [512, 512, [], \"f27a\", \"M448 0H64C28.7 0 0 28.7 0 64v288c0 35.3 28.7 64 64 64h96v84c0 9.8 11.2 15.5 19.1 9.7L304 416h144c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64z\"],\n    \"comment-dollar\": [512, 512, [], \"f651\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95.01 57.02 130.74C44.46 421.05 2.7 465.97 2.2 466.5A7.995 7.995 0 0 0 8 480c66.26 0 115.99-31.75 140.6-51.38C181.29 440.93 217.59 448 256 448c141.38 0 256-93.12 256-208S397.38 32 256 32zm24 302.44V352c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-17.73c-11.42-1.35-22.28-5.19-31.78-11.46-6.22-4.11-6.82-13.11-1.55-18.38l17.52-17.52c3.74-3.74 9.31-4.24 14.11-2.03 3.18 1.46 6.66 2.22 10.26 2.22h32.78c4.66 0 8.44-3.78 8.44-8.42 0-3.75-2.52-7.08-6.12-8.11l-50.07-14.3c-22.25-6.35-40.01-24.71-42.91-47.67-4.05-32.07 19.03-59.43 49.32-63.05V128c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v17.73c11.42 1.35 22.28 5.19 31.78 11.46 6.22 4.11 6.82 13.11 1.55 18.38l-17.52 17.52c-3.74 3.74-9.31 4.24-14.11 2.03a24.516 24.516 0 0 0-10.26-2.22h-32.78c-4.66 0-8.44 3.78-8.44 8.42 0 3.75 2.52 7.08 6.12 8.11l50.07 14.3c22.25 6.36 40.01 24.71 42.91 47.67 4.05 32.06-19.03 59.42-49.32 63.04z\"],\n    \"comment-dots\": [512, 512, [], \"f4ad\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7S4.8 480 8 480c66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128 272c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"comment-medical\": [512, 512, [], \"f7f5\", \"M256 32C114.62 32 0 125.12 0 240c0 49.56 21.41 95 57 130.74C44.46 421.05 2.7 466 2.2 466.5A8 8 0 0 0 8 480c66.26 0 116-31.75 140.6-51.38A304.66 304.66 0 0 0 256 448c141.39 0 256-93.12 256-208S397.39 32 256 32zm96 232a8 8 0 0 1-8 8h-56v56a8 8 0 0 1-8 8h-48a8 8 0 0 1-8-8v-56h-56a8 8 0 0 1-8-8v-48a8 8 0 0 1 8-8h56v-56a8 8 0 0 1 8-8h48a8 8 0 0 1 8 8v56h56a8 8 0 0 1 8 8z\"],\n    \"comment-slash\": [640, 512, [], \"f4b3\", \"M64 240c0 49.6 21.4 95 57 130.7-12.6 50.3-54.3 95.2-54.8 95.8-2.2 2.3-2.8 5.7-1.5 8.7 1.3 2.9 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 27.4 0 53.7-3.6 78.4-10L72.9 186.4c-5.6 17.1-8.9 35-8.9 53.6zm569.8 218.1l-114.4-88.4C554.6 334.1 576 289.2 576 240c0-114.9-114.6-208-256-208-65.1 0-124.2 20.1-169.4 52.7L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"comments\": [576, 512, [], \"f086\", \"M416 192c0-88.4-93.1-160-208-160S0 103.6 0 192c0 34.3 14.1 65.9 38 92-13.4 30.2-35.5 54.2-35.8 54.5-2.2 2.3-2.8 5.7-1.5 8.7S4.8 352 8 352c36.6 0 66.9-12.3 88.7-25 32.2 15.7 70.3 25 111.3 25 114.9 0 208-71.6 208-160zm122 220c23.9-26 38-57.7 38-92 0-66.9-53.5-124.2-129.3-148.1.9 6.6 1.3 13.3 1.3 20.1 0 105.9-107.7 192-240 192-10.8 0-21.3-.8-31.7-1.9C207.8 439.6 281.8 480 368 480c41 0 79.1-9.2 111.3-25 21.8 12.7 52.1 25 88.7 25 3.2 0 6.1-1.9 7.3-4.8 1.3-2.9.7-6.3-1.5-8.7-.3-.3-22.4-24.2-35.8-54.5z\"],\n    \"comments-dollar\": [576, 512, [], \"f653\", \"M416 192c0-88.37-93.12-160-208-160S0 103.63 0 192c0 34.27 14.13 65.95 37.97 91.98C24.61 314.22 2.52 338.16 2.2 338.5A7.995 7.995 0 0 0 8 352c36.58 0 66.93-12.25 88.73-24.98C128.93 342.76 167.02 352 208 352c114.88 0 208-71.63 208-160zm-224 96v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V96c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07V288c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm346.01 123.99C561.87 385.96 576 354.27 576 320c0-66.94-53.49-124.2-129.33-148.07.86 6.6 1.33 13.29 1.33 20.07 0 105.87-107.66 192-240 192-10.78 0-21.32-.77-31.73-1.88C207.8 439.63 281.77 480 368 480c40.98 0 79.07-9.24 111.27-24.98C501.07 467.75 531.42 480 568 480c3.2 0 6.09-1.91 7.34-4.84 1.27-2.94.66-6.34-1.55-8.67-.31-.33-22.42-24.24-35.78-54.5z\"],\n    \"compact-disc\": [496, 512, [], \"f51f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 256H56c0-105.9 86.1-192 192-192v32c-88.2 0-160 71.8-160 160zm160 96c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96zm0-128c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32z\"],\n    \"compass\": [496, 512, [], \"f14e\", \"M225.38 233.37c-12.5 12.5-12.5 32.76 0 45.25 12.49 12.5 32.76 12.5 45.25 0 12.5-12.5 12.5-32.76 0-45.25-12.5-12.49-32.76-12.49-45.25 0zM248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm126.14 148.05L308.17 300.4a31.938 31.938 0 0 1-15.77 15.77l-144.34 65.97c-16.65 7.61-33.81-9.55-26.2-26.2l65.98-144.35a31.938 31.938 0 0 1 15.77-15.77l144.34-65.97c16.65-7.6 33.8 9.55 26.19 26.2z\"],\n    \"compress\": [448, 512, [], \"f066\", \"M436 192H312c-13.3 0-24-10.7-24-24V44c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v84h84c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12zm-276-24V44c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v84H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24zm0 300V344c0-13.3-10.7-24-24-24H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12zm192 0v-84h84c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12H312c-13.3 0-24 10.7-24 24v124c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"compress-arrows-alt\": [512, 512, [], \"f78c\", \"M200 288H88c-21.4 0-32.1 25.8-17 41l32.9 31-99.2 99.3c-6.2 6.2-6.2 16.4 0 22.6l25.4 25.4c6.2 6.2 16.4 6.2 22.6 0L152 408l31.1 33c15.1 15.1 40.9 4.4 40.9-17V312c0-13.3-10.7-24-24-24zm112-64h112c21.4 0 32.1-25.9 17-41l-33-31 99.3-99.3c6.2-6.2 6.2-16.4 0-22.6L481.9 4.7c-6.2-6.2-16.4-6.2-22.6 0L360 104l-31.1-33C313.8 55.9 288 66.6 288 88v112c0 13.3 10.7 24 24 24zm96 136l33-31.1c15.1-15.1 4.4-40.9-17-40.9H312c-13.3 0-24 10.7-24 24v112c0 21.4 25.9 32.1 41 17l31-32.9 99.3 99.3c6.2 6.2 16.4 6.2 22.6 0l25.4-25.4c6.2-6.2 6.2-16.4 0-22.6L408 360zM183 71.1L152 104 52.7 4.7c-6.2-6.2-16.4-6.2-22.6 0L4.7 30.1c-6.2 6.2-6.2 16.4 0 22.6L104 152l-33 31.1C55.9 198.2 66.6 224 88 224h112c13.3 0 24-10.7 24-24V88c0-21.3-25.9-32-41-16.9z\"],\n    \"concierge-bell\": [512, 512, [], \"f562\", \"M288 130.54V112h16c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16h-96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h16v18.54C115.49 146.11 32 239.18 32 352h448c0-112.82-83.49-205.89-192-221.46zM496 384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"cookie\": [512, 512, [], \"f563\", \"M510.37 254.79l-12.08-76.26a132.493 132.493 0 0 0-37.16-72.95l-54.76-54.75c-19.73-19.72-45.18-32.7-72.71-37.05l-76.7-12.15c-27.51-4.36-55.69.11-80.52 12.76L107.32 49.6a132.25 132.25 0 0 0-57.79 57.8l-35.1 68.88a132.602 132.602 0 0 0-12.82 80.94l12.08 76.27a132.493 132.493 0 0 0 37.16 72.95l54.76 54.75a132.087 132.087 0 0 0 72.71 37.05l76.7 12.14c27.51 4.36 55.69-.11 80.52-12.75l69.12-35.21a132.302 132.302 0 0 0 57.79-57.8l35.1-68.87c12.71-24.96 17.2-53.3 12.82-80.96zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"cookie-bite\": [512, 512, [], \"f564\", \"M510.52 255.82c-69.97-.85-126.47-57.69-126.47-127.86-70.17 0-127-56.49-127.86-126.45-27.26-4.14-55.13.3-79.72 12.82l-69.13 35.22a132.221 132.221 0 0 0-57.79 57.81l-35.1 68.88a132.645 132.645 0 0 0-12.82 80.95l12.08 76.27a132.521 132.521 0 0 0 37.16 72.96l54.77 54.76a132.036 132.036 0 0 0 72.71 37.06l76.71 12.15c27.51 4.36 55.7-.11 80.53-12.76l69.13-35.21a132.273 132.273 0 0 0 57.79-57.81l35.1-68.88c12.56-24.64 17.01-52.58 12.91-79.91zM176 368c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm32-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm160 128c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"copy\": [448, 512, [], \"f0c5\", \"M320 448v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V120c0-13.255 10.745-24 24-24h72v296c0 30.879 25.121 56 56 56h168zm0-344V0H152c-13.255 0-24 10.745-24 24v368c0 13.255 10.745 24 24 24h272c13.255 0 24-10.745 24-24V128H344c-13.2 0-24-10.8-24-24zm120.971-31.029L375.029 7.029A24 24 0 0 0 358.059 0H352v96h96v-6.059a24 24 0 0 0-7.029-16.97z\"],\n    \"copyright\": [512, 512, [], \"f1f9\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm117.134 346.753c-1.592 1.867-39.776 45.731-109.851 45.731-84.692 0-144.484-63.26-144.484-145.567 0-81.303 62.004-143.401 143.762-143.401 66.957 0 101.965 37.315 103.422 38.904a12 12 0 0 1 1.238 14.623l-22.38 34.655c-4.049 6.267-12.774 7.351-18.234 2.295-.233-.214-26.529-23.88-61.88-23.88-46.116 0-73.916 33.575-73.916 76.082 0 39.602 25.514 79.692 74.277 79.692 38.697 0 65.28-28.338 65.544-28.625 5.132-5.565 14.059-5.033 18.508 1.053l24.547 33.572a12.001 12.001 0 0 1-.553 14.866z\"],\n    \"couch\": [640, 512, [], \"f4b8\", \"M160 224v64h320v-64c0-35.3 28.7-64 64-64h32c0-53-43-96-96-96H160c-53 0-96 43-96 96h32c35.3 0 64 28.7 64 64zm416-32h-32c-17.7 0-32 14.3-32 32v96H128v-96c0-17.7-14.3-32-32-32H64c-35.3 0-64 28.7-64 64 0 23.6 13 44 32 55.1V432c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-16h384v16c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V311.1c19-11.1 32-31.5 32-55.1 0-35.3-28.7-64-64-64z\"],\n    \"credit-card\": [576, 512, [], \"f09d\", \"M0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V256H0v176zm192-68c0-6.6 5.4-12 12-12h136c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H204c-6.6 0-12-5.4-12-12v-40zm-128 0c0-6.6 5.4-12 12-12h72c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12v-40zM576 80v48H0V80c0-26.5 21.5-48 48-48h480c26.5 0 48 21.5 48 48z\"],\n    \"crop\": [512, 512, [], \"f125\", \"M488 352h-40V109.25l59.31-59.31c6.25-6.25 6.25-16.38 0-22.63L484.69 4.69c-6.25-6.25-16.38-6.25-22.63 0L402.75 64H192v96h114.75L160 306.75V24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v264c0 13.25 10.75 24 24 24h232v-96H205.25L352 205.25V488c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"crop-alt\": [512, 512, [], \"f565\", \"M488 352h-40V96c0-17.67-14.33-32-32-32H192v96h160v328c0 13.25 10.75 24 24 24h48c13.25 0 24-10.75 24-24v-40h40c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24zM160 24c0-13.26-10.75-24-24-24H88C74.75 0 64 10.74 64 24v40H24C10.75 64 0 74.74 0 88v48c0 13.25 10.75 24 24 24h40v256c0 17.67 14.33 32 32 32h224v-96H160V24z\"],\n    \"cross\": [384, 512, [], \"f654\", \"M352 128h-96V32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h96v224c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V256h96c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"crosshairs\": [512, 512, [], \"f05b\", \"M500 224h-30.364C455.724 130.325 381.675 56.276 288 42.364V12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v30.364C130.325 56.276 56.276 130.325 42.364 224H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h30.364C56.276 381.675 130.325 455.724 224 469.636V500c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-30.364C381.675 455.724 455.724 381.675 469.636 288H500c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zM288 404.634V364c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40.634C165.826 392.232 119.783 346.243 107.366 288H148c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40.634C119.768 165.826 165.757 119.783 224 107.366V148c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40.634C346.174 119.768 392.217 165.757 404.634 224H364c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40.634C392.232 346.174 346.243 392.217 288 404.634zM288 256c0 17.673-14.327 32-32 32s-32-14.327-32-32c0-17.673 14.327-32 32-32s32 14.327 32 32z\"],\n    \"crow\": [640, 512, [], \"f520\", \"M544 32h-16.36C513.04 12.68 490.09 0 464 0c-44.18 0-80 35.82-80 80v20.98L12.09 393.57A30.216 30.216 0 0 0 0 417.74c0 22.46 23.64 37.07 43.73 27.03L165.27 384h96.49l44.41 120.1c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38L312.94 384H352c1.91 0 3.76-.23 5.66-.29l44.51 120.38c2.27 6.23 9.15 9.44 15.38 7.17l22.55-8.21c6.23-2.27 9.44-9.15 7.17-15.38l-41.24-111.53C485.74 352.8 544 279.26 544 192v-80l96-16c0-35.35-42.98-64-96-64zm-80 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"crown\": [640, 512, [], \"f521\", \"M528 448H112c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h416c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm64-320c-26.5 0-48 21.5-48 48 0 7.1 1.6 13.7 4.4 19.8L476 239.2c-15.4 9.2-35.3 4-44.2-11.6L350.3 85C361 76.2 368 63 368 48c0-26.5-21.5-48-48-48s-48 21.5-48 48c0 15 7 28.2 17.7 37l-81.5 142.6c-8.9 15.6-28.9 20.8-44.2 11.6l-72.3-43.4c2.7-6 4.4-12.7 4.4-19.8 0-26.5-21.5-48-48-48S0 149.5 0 176s21.5 48 48 48c2.6 0 5.2-.4 7.7-.8L128 416h384l72.3-192.8c2.5.4 5.1.8 7.7.8 26.5 0 48-21.5 48-48s-21.5-48-48-48z\"],\n    \"crutch\": [512, 512, [], \"f7f7\", \"M507.31 185.71l-181-181a16 16 0 0 0-22.62 0L281 27.31a16 16 0 0 0 0 22.63l181 181a16 16 0 0 0 22.63 0l22.62-22.63a16 16 0 0 0 .06-22.6zm-179.54 66.41l-67.89-67.89 55.1-55.1-45.25-45.25-109.67 109.67a96.08 96.08 0 0 0-25.67 46.29L106.65 360.1l-102 102a16 16 0 0 0 0 22.63l22.62 22.62a16 16 0 0 0 22.63 0l102-102 120.25-27.75a95.88 95.88 0 0 0 46.29-25.65l109.68-109.68L382.87 197zm-54.57 54.57a32 32 0 0 1-15.45 8.54l-79.3 18.32 18.3-79.3a32.22 32.22 0 0 1 8.56-15.45l9.31-9.31 67.89 67.89z\"],\n    \"cube\": [512, 512, [], \"f1b2\", \"M239.1 6.3l-208 78c-18.7 7-31.1 25-31.1 45v225.1c0 18.2 10.3 34.8 26.5 42.9l208 104c13.5 6.8 29.4 6.8 42.9 0l208-104c16.3-8.1 26.5-24.8 26.5-42.9V129.3c0-20-12.4-37.9-31.1-44.9l-208-78C262 2.2 250 2.2 239.1 6.3zM256 68.4l192 72v1.1l-192 78-192-78v-1.1l192-72zm32 356V275.5l160-65v133.9l-160 80z\"],\n    \"cubes\": [512, 512, [], \"f1b3\", \"M488.6 250.2L392 214V105.5c0-15-9.3-28.4-23.4-33.7l-100-37.5c-8.1-3.1-17.1-3.1-25.3 0l-100 37.5c-14.1 5.3-23.4 18.7-23.4 33.7V214l-96.6 36.2C9.3 255.5 0 268.9 0 283.9V394c0 13.6 7.7 26.1 19.9 32.2l100 50c10.1 5.1 22.1 5.1 32.2 0l103.9-52 103.9 52c10.1 5.1 22.1 5.1 32.2 0l100-50c12.2-6.1 19.9-18.6 19.9-32.2V283.9c0-15-9.3-28.4-23.4-33.7zM358 214.8l-85 31.9v-68.2l85-37v73.3zM154 104.1l102-38.2 102 38.2v.6l-102 41.4-102-41.4v-.6zm84 291.1l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6zm240 112l-85 42.5v-79.1l85-38.8v75.4zm0-112l-102 41.4-102-41.4v-.6l102-38.2 102 38.2v.6z\"],\n    \"cut\": [448, 512, [], \"f0c4\", \"M278.06 256L444.48 89.57c4.69-4.69 4.69-12.29 0-16.97-32.8-32.8-85.99-32.8-118.79 0L210.18 188.12l-24.86-24.86c4.31-10.92 6.68-22.81 6.68-35.26 0-53.02-42.98-96-96-96S0 74.98 0 128s42.98 96 96 96c4.54 0 8.99-.32 13.36-.93L142.29 256l-32.93 32.93c-4.37-.61-8.83-.93-13.36-.93-53.02 0-96 42.98-96 96s42.98 96 96 96 96-42.98 96-96c0-12.45-2.37-24.34-6.68-35.26l24.86-24.86L325.69 439.4c32.8 32.8 85.99 32.8 118.79 0 4.69-4.68 4.69-12.28 0-16.97L278.06 256zM96 160c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32zm0 256c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"database\": [448, 512, [], \"f1c0\", \"M448 73.143v45.714C448 159.143 347.667 192 224 192S0 159.143 0 118.857V73.143C0 32.857 100.333 0 224 0s224 32.857 224 73.143zM448 176v102.857C448 319.143 347.667 352 224 352S0 319.143 0 278.857V176c48.125 33.143 136.208 48.572 224 48.572S399.874 209.143 448 176zm0 160v102.857C448 479.143 347.667 512 224 512S0 479.143 0 438.857V336c48.125 33.143 136.208 48.572 224 48.572S399.874 369.143 448 336z\"],\n    \"deaf\": [512, 512, [], \"f2a4\", \"M216 260c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-44.112 35.888-80 80-80s80 35.888 80 80c0 15.464-12.536 28-28 28s-28-12.536-28-28c0-13.234-10.767-24-24-24s-24 10.766-24 24zm24-176c-97.047 0-176 78.953-176 176 0 15.464 12.536 28 28 28s28-12.536 28-28c0-66.168 53.832-120 120-120s120 53.832 120 120c0 75.164-71.009 70.311-71.997 143.622L288 404c0 28.673-23.327 52-52 52-15.464 0-28 12.536-28 28s12.536 28 28 28c59.475 0 107.876-48.328 108-107.774.595-34.428 72-48.24 72-144.226 0-97.047-78.953-176-176-176zm268.485-52.201L480.2 3.515c-4.687-4.686-12.284-4.686-16.971 0L376.2 90.544c-4.686 4.686-4.686 12.284 0 16.971l28.285 28.285c4.686 4.686 12.284 4.686 16.97 0l87.03-87.029c4.687-4.688 4.687-12.286 0-16.972zM168.97 314.745c-4.686-4.686-12.284-4.686-16.97 0L3.515 463.23c-4.686 4.686-4.686 12.284 0 16.971L31.8 508.485c4.687 4.686 12.284 4.686 16.971 0L197.256 360c4.686-4.686 4.686-12.284 0-16.971l-28.286-28.284z\"],\n    \"democrat\": [640, 512, [], \"f747\", \"M637.3 256.9l-19.6-29.4c-28.2-42.3-75.3-67.5-126.1-67.5H256l-81.2-81.2c20.1-20.1 22.6-51.1 7.5-73.9-3.4-5.2-10.8-5.9-15.2-1.5l-41.8 41.8L82.4 2.4c-3.6-3.6-9.6-3-12.4 1.2-12.3 18.6-10.3 44 6.1 60.4 3.3 3.3 7.3 5.3 11.3 7.5-2.2 1.7-4.7 3.1-6.4 5.4L6.4 176.2c-7.3 9.7-8.4 22.7-3 33.5l14.3 28.6c5.4 10.8 16.5 17.7 28.6 17.7h31c8.5 0 16.6-3.4 22.6-9.4L138 212l54 108h352v-77.8c16.2 12.2 18.3 17.6 40.1 50.3 4.9 7.4 14.8 9.3 22.2 4.4l26.6-17.7c7.3-5 9.3-14.9 4.4-22.3zm-341.1-13.6l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L256 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L368 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zm112 0l-16.5 16.1 3.9 22.7c.7 4.1-3.6 7.2-7.2 5.3L480 276.7l-20.4 10.7c-3.6 1.9-7.9-1.2-7.2-5.3l3.9-22.7-16.5-16.1c-3-2.9-1.3-7.9 2.8-8.5l22.8-3.3 10.2-20.7c1.8-3.7 7.1-3.7 9 0l10.2 20.7 22.8 3.3c4 .6 5.6 5.6 2.6 8.5zM192 496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80h160v80c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16V352H192v144z\"],\n    \"desktop\": [576, 512, [], \"f108\", \"M528 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h192l-16 48h-72c-13.3 0-24 10.7-24 24s10.7 24 24 24h272c13.3 0 24-10.7 24-24s-10.7-24-24-24h-72l-16-48h192c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h448v288z\"],\n    \"dharmachakra\": [512, 512, [], \"f655\", \"M495 225.06l-17.22 1.08c-5.27-39.49-20.79-75.64-43.86-105.84l12.95-11.43c6.92-6.11 7.25-16.79.73-23.31L426.44 64.4c-6.53-6.53-17.21-6.19-23.31.73L391.7 78.07c-30.2-23.06-66.35-38.58-105.83-43.86L286.94 17c.58-9.21-6.74-17-15.97-17h-29.94c-9.23 0-16.54 7.79-15.97 17l1.08 17.22c-39.49 5.27-75.64 20.79-105.83 43.86l-11.43-12.95c-6.11-6.92-16.79-7.25-23.31-.73L64.4 85.56c-6.53 6.53-6.19 17.21.73 23.31l12.95 11.43c-23.06 30.2-38.58 66.35-43.86 105.84L17 225.06c-9.21-.58-17 6.74-17 15.97v29.94c0 9.23 7.79 16.54 17 15.97l17.22-1.08c5.27 39.49 20.79 75.64 43.86 105.83l-12.95 11.43c-6.92 6.11-7.25 16.79-.73 23.31l21.17 21.17c6.53 6.53 17.21 6.19 23.31-.73l11.43-12.95c30.2 23.06 66.35 38.58 105.84 43.86L225.06 495c-.58 9.21 6.74 17 15.97 17h29.94c9.23 0 16.54-7.79 15.97-17l-1.08-17.22c39.49-5.27 75.64-20.79 105.84-43.86l11.43 12.95c6.11 6.92 16.79 7.25 23.31.73l21.17-21.17c6.53-6.53 6.19-17.21-.73-23.31l-12.95-11.43c23.06-30.2 38.58-66.35 43.86-105.83l17.22 1.08c9.21.58 17-6.74 17-15.97v-29.94c-.01-9.23-7.8-16.54-17.01-15.97zM281.84 98.61c24.81 4.07 47.63 13.66 67.23 27.78l-42.62 48.29c-8.73-5.44-18.32-9.54-28.62-11.95l4.01-64.12zm-51.68 0l4.01 64.12c-10.29 2.41-19.89 6.52-28.62 11.95l-42.62-48.29c19.6-14.12 42.42-23.71 67.23-27.78zm-103.77 64.33l48.3 42.61c-5.44 8.73-9.54 18.33-11.96 28.62l-64.12-4.01c4.07-24.81 13.66-47.62 27.78-67.22zm-27.78 118.9l64.12-4.01c2.41 10.29 6.52 19.89 11.95 28.62l-48.29 42.62c-14.12-19.6-23.71-42.42-27.78-67.23zm131.55 131.55c-24.81-4.07-47.63-13.66-67.23-27.78l42.61-48.3c8.73 5.44 18.33 9.54 28.62 11.96l-4 64.12zM256 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm25.84 125.39l-4.01-64.12c10.29-2.41 19.89-6.52 28.62-11.96l42.61 48.3c-19.6 14.12-42.41 23.71-67.22 27.78zm103.77-64.33l-48.29-42.62c5.44-8.73 9.54-18.32 11.95-28.62l64.12 4.01c-4.07 24.82-13.66 47.64-27.78 67.23zm-36.34-114.89c-2.41-10.29-6.52-19.89-11.96-28.62l48.3-42.61c14.12 19.6 23.71 42.42 27.78 67.23l-64.12 4z\"],\n    \"diagnoses\": [640, 512, [], \"f470\", \"M496 256c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm-176-80c48.5 0 88-39.5 88-88S368.5 0 320 0s-88 39.5-88 88 39.5 88 88 88zM59.8 364c10.2 15.3 29.3 17.8 42.9 9.8 16.2-9.6 56.2-31.7 105.3-48.6V416h224v-90.7c49.1 16.8 89.1 39 105.3 48.6 13.6 8 32.7 5.3 42.9-9.8l17.8-26.7c8.8-13.2 7.6-34.6-10-45.1-11.9-7.1-29.7-17-51.1-27.4-28.1 46.1-99.4 17.8-87.7-35.1C409.3 217.2 365.1 208 320 208c-57 0-112.9 14.5-160 32.2-.2 40.2-47.6 63.3-79.2 36-11.2 6-21.3 11.6-28.7 16-17.6 10.5-18.8 31.8-10 45.1L59.8 364zM368 344c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-96-96c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm-160 8c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zm512 192H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dice\": [640, 512, [], \"f522\", \"M592 192H473.26c12.69 29.59 7.12 65.2-17 89.32L320 417.58V464c0 26.51 21.49 48 48 48h224c26.51 0 48-21.49 48-48V240c0-26.51-21.49-48-48-48zM480 376c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm-46.37-186.7L258.7 14.37c-19.16-19.16-50.23-19.16-69.39 0L14.37 189.3c-19.16 19.16-19.16 50.23 0 69.39L189.3 433.63c19.16 19.16 50.23 19.16 69.39 0L433.63 258.7c19.16-19.17 19.16-50.24 0-69.4zM96 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm0-128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm128 128c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"dice-d20\": [480, 512, [], \"f6cf\", \"M106.75 215.06L1.2 370.95c-3.08 5 .1 11.5 5.93 12.14l208.26 22.07-108.64-190.1zM7.41 315.43L82.7 193.08 6.06 147.1c-2.67-1.6-6.06.32-6.06 3.43v162.81c0 4.03 5.29 5.53 7.41 2.09zM18.25 423.6l194.4 87.66c5.3 2.45 11.35-1.43 11.35-7.26v-65.67l-203.55-22.3c-4.45-.5-6.23 5.59-2.2 7.57zm81.22-257.78L179.4 22.88c4.34-7.06-3.59-15.25-10.78-11.14L17.81 110.35c-2.47 1.62-2.39 5.26.13 6.78l81.53 48.69zM240 176h109.21L253.63 7.62C250.5 2.54 245.25 0 240 0s-10.5 2.54-13.63 7.62L130.79 176H240zm233.94-28.9l-76.64 45.99 75.29 122.35c2.11 3.44 7.41 1.94 7.41-2.1V150.53c0-3.11-3.39-5.03-6.06-3.43zm-93.41 18.72l81.53-48.7c2.53-1.52 2.6-5.16.13-6.78l-150.81-98.6c-7.19-4.11-15.12 4.08-10.78 11.14l79.93 142.94zm79.02 250.21L256 438.32v65.67c0 5.84 6.05 9.71 11.35 7.26l194.4-87.66c4.03-1.97 2.25-8.06-2.2-7.56zm-86.3-200.97l-108.63 190.1 208.26-22.07c5.83-.65 9.01-7.14 5.93-12.14L373.25 215.06zM240 208H139.57L240 383.75 340.43 208H240z\"],\n    \"dice-d6\": [448, 512, [], \"f6d1\", \"M422.19 109.95L256.21 9.07c-19.91-12.1-44.52-12.1-64.43 0L25.81 109.95c-5.32 3.23-5.29 11.27.06 14.46L224 242.55l198.14-118.14c5.35-3.19 5.38-11.22.05-14.46zm13.84 44.63L240 271.46v223.82c0 12.88 13.39 20.91 24.05 14.43l152.16-92.48c19.68-11.96 31.79-33.94 31.79-57.7v-197.7c0-6.41-6.64-10.43-11.97-7.25zM0 161.83v197.7c0 23.77 12.11 45.74 31.79 57.7l152.16 92.47c10.67 6.48 24.05-1.54 24.05-14.43V271.46L11.97 154.58C6.64 151.4 0 155.42 0 161.83z\"],\n    \"dice-five\": [448, 512, [], \"f523\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-four\": [448, 512, [], \"f524\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-one\": [448, 512, [], \"f525\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM224 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-six\": [448, 512, [], \"f526\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-three\": [448, 512, [], \"f527\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm96 96c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"dice-two\": [448, 512, [], \"f528\", \"M384 32H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h320c35.35 0 64-28.65 64-64V96c0-35.35-28.65-64-64-64zM128 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm192 192c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"digital-tachograph\": [640, 512, [], \"f566\", \"M608 96H32c-17.67 0-32 14.33-32 32v256c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128c0-17.67-14.33-32-32-32zM304 352c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8zM72 288v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H80c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm64 0v-16c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8zm40-64c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-48c0-8.84 7.16-16 16-16h208c8.84 0 16 7.16 16 16v48zm272 128c0 4.42-3.58 8-8 8H344c-4.42 0-8-3.58-8-8v-8c0-4.42 3.58-8 8-8h224c4.42 0 8 3.58 8 8v8z\"],\n    \"directions\": [512, 512, [], \"f5eb\", \"M502.61 233.32L278.68 9.39c-12.52-12.52-32.83-12.52-45.36 0L9.39 233.32c-12.52 12.53-12.52 32.83 0 45.36l223.93 223.93c12.52 12.53 32.83 12.53 45.36 0l223.93-223.93c12.52-12.53 12.52-32.83 0-45.36zm-100.98 12.56l-84.21 77.73c-5.12 4.73-13.43 1.1-13.43-5.88V264h-96v64c0 4.42-3.58 8-8 8h-32c-4.42 0-8-3.58-8-8v-80c0-17.67 14.33-32 32-32h112v-53.73c0-6.97 8.3-10.61 13.43-5.88l84.21 77.73c3.43 3.17 3.43 8.59 0 11.76z\"],\n    \"divide\": [448, 512, [], \"f529\", \"M224 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm0-192c35.35 0 64-28.65 64-64s-28.65-64-64-64-64 28.65-64 64 28.65 64 64 64zm192 48H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"dizzy\": [496, 512, [], \"f567\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-96 206.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L174.6 192l28.7 28.7c15.2 15.2-7.9 37.4-22.6 22.6L152 214.6zM248 416c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm147.3-195.3c15.2 15.2-7.9 37.4-22.6 22.6L344 214.6l-28.7 28.7c-14.8 14.8-37.8-7.5-22.6-22.6l28.7-28.7-28.7-28.7c-15-15 7.7-37.6 22.6-22.6l28.7 28.7 28.7-28.7c15-15 37.6 7.7 22.6 22.6L366.6 192l28.7 28.7z\"],\n    \"dna\": [448, 512, [], \"f471\", \"M.1 494.1c-1.1 9.5 6.3 17.8 15.9 17.8l32.3.1c8.1 0 14.9-5.9 16-13.9.7-4.9 1.8-11.1 3.4-18.1H380c1.6 6.9 2.9 13.2 3.5 18.1 1.1 8 7.9 14 16 13.9l32.3-.1c9.6 0 17.1-8.3 15.9-17.8-4.6-37.9-25.6-129-118.9-207.7-17.6 12.4-37.1 24.2-58.5 35.4 6.2 4.6 11.4 9.4 17 14.2H159.7c21.3-18.1 47-35.6 78.7-51.4C410.5 199.1 442.1 65.8 447.9 17.9 449 8.4 441.6.1 432 .1L399.6 0c-8.1 0-14.9 5.9-16 13.9-.7 4.9-1.8 11.1-3.4 18.1H67.8c-1.6-7-2.7-13.1-3.4-18.1-1.1-8-7.9-14-16-13.9L16.1.1C6.5.1-1 8.4.1 17.9 5.3 60.8 31.4 171.8 160 256 31.5 340.2 5.3 451.2.1 494.1zM224 219.6c-25.1-13.7-46.4-28.4-64.3-43.6h128.5c-17.8 15.2-39.1 30-64.2 43.6zM355.1 96c-5.8 10.4-12.8 21.1-21 32H114c-8.3-10.9-15.3-21.6-21-32h262.1zM92.9 416c5.8-10.4 12.8-21.1 21-32h219.4c8.3 10.9 15.4 21.6 21.2 32H92.9z\"],\n    \"dog\": [512, 512, [], \"f6d3\", \"M496 96h-64l-7.16-14.31A32 32 0 0 0 396.22 64H342.6l-27.28-27.28C305.23 26.64 288 33.78 288 48.03v149.84l128 45.71V208h32c35.35 0 64-28.65 64-64v-32c0-8.84-7.16-16-16-16zm-112 48c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM96 224c-17.64 0-32-14.36-32-32 0-17.67-14.33-32-32-32S0 174.33 0 192c0 41.66 26.83 76.85 64 90.1V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V384h160v112c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V277.55L266.05 224H96z\"],\n    \"dollar-sign\": [288, 512, [], \"f155\", \"M209.2 233.4l-108-31.6C88.7 198.2 80 186.5 80 173.5c0-16.3 13.2-29.5 29.5-29.5h66.3c12.2 0 24.2 3.7 34.2 10.5 6.1 4.1 14.3 3.1 19.5-2l34.8-34c7.1-6.9 6.1-18.4-1.8-24.5C238 74.8 207.4 64.1 176 64V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v48h-2.5C45.8 64-5.4 118.7.5 183.6c4.2 46.1 39.4 83.6 83.8 96.6l102.5 30c12.5 3.7 21.2 15.3 21.2 28.3 0 16.3-13.2 29.5-29.5 29.5h-66.3C100 368 88 364.3 78 357.5c-6.1-4.1-14.3-3.1-19.5 2l-34.8 34c-7.1 6.9-6.1 18.4 1.8 24.5 24.5 19.2 55.1 29.9 86.5 30v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48.2c46.6-.9 90.3-28.6 105.7-72.7 21.5-61.6-14.6-124.8-72.5-141.7z\"],\n    \"dolly\": [576, 512, [], \"f472\", \"M294.2 277.7c18 5 34.7 13.4 49.5 24.7l161.5-53.8c8.4-2.8 12.9-11.9 10.1-20.2L454.9 47.2c-2.8-8.4-11.9-12.9-20.2-10.1l-61.1 20.4 33.1 99.4L346 177l-33.1-99.4-61.6 20.5c-8.4 2.8-12.9 11.9-10.1 20.2l53 159.4zm281 48.7L565 296c-2.8-8.4-11.9-12.9-20.2-10.1l-213.5 71.2c-17.2-22-43.6-36.4-73.5-37L158.4 21.9C154 8.8 141.8 0 128 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h88.9l92.2 276.7c-26.1 20.4-41.7 53.6-36 90.5 6.1 39.4 37.9 72.3 77.3 79.2 60.2 10.7 112.3-34.8 113.4-92.6l213.3-71.2c8.3-2.8 12.9-11.8 10.1-20.2zM256 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"dolly-flatbed\": [640, 512, [], \"f474\", \"M208 320h384c8.8 0 16-7.2 16-16V48c0-8.8-7.2-16-16-16H448v128l-48-32-48 32V32H208c-8.8 0-16 7.2-16 16v256c0 8.8 7.2 16 16 16zm416 64H128V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h82.9c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H451c-1.8 5-2.9 10.4-2.9 16 0 26.5 21.5 48 48 48s48-21.5 48-48c0-5.6-1.2-11-2.9-16H624c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"donate\": [512, 512, [], \"f4b9\", \"M256 416c114.9 0 208-93.1 208-208S370.9 0 256 0 48 93.1 48 208s93.1 208 208 208zM233.8 97.4V80.6c0-9.2 7.4-16.6 16.6-16.6h11.1c9.2 0 16.6 7.4 16.6 16.6v17c15.5.8 30.5 6.1 43 15.4 5.6 4.1 6.2 12.3 1.2 17.1L306 145.6c-3.8 3.7-9.5 3.8-14 1-5.4-3.4-11.4-5.1-17.8-5.1h-38.9c-9 0-16.3 8.2-16.3 18.3 0 8.2 5 15.5 12.1 17.6l62.3 18.7c25.7 7.7 43.7 32.4 43.7 60.1 0 34-26.4 61.5-59.1 62.4v16.8c0 9.2-7.4 16.6-16.6 16.6h-11.1c-9.2 0-16.6-7.4-16.6-16.6v-17c-15.5-.8-30.5-6.1-43-15.4-5.6-4.1-6.2-12.3-1.2-17.1l16.3-15.5c3.8-3.7 9.5-3.8 14-1 5.4 3.4 11.4 5.1 17.8 5.1h38.9c9 0 16.3-8.2 16.3-18.3 0-8.2-5-15.5-12.1-17.6l-62.3-18.7c-25.7-7.7-43.7-32.4-43.7-60.1.1-34 26.4-61.5 59.1-62.4zM480 352h-32.5c-19.6 26-44.6 47.7-73 64h63.8c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8h63.8c-28.4-16.3-53.3-38-73-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32z\"],\n    \"door-closed\": [640, 512, [], \"f52a\", \"M624 448H512V50.8C512 22.78 490.47 0 464 0H175.99c-26.47 0-48 22.78-48 50.8V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM415.99 288c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32c.01 17.67-14.32 32-32 32z\"],\n    \"door-open\": [640, 512, [], \"f52b\", \"M624 448h-80V113.45C544 86.19 522.47 64 496 64H384v64h96v384h144c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM312.24 1.01l-192 49.74C105.99 54.44 96 67.7 96 82.92V448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h336V33.18c0-21.58-19.56-37.41-39.76-32.17zM264 288c-13.25 0-24-14.33-24-32s10.75-32 24-32 24 14.33 24 32-10.75 32-24 32z\"],\n    \"dot-circle\": [512, 512, [], \"f192\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm80 248c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80z\"],\n    \"dove\": [512, 512, [], \"f4ba\", \"M288 167.2v-28.1c-28.2-36.3-47.1-79.3-54.1-125.2-2.1-13.5-19-18.8-27.8-8.3-21.1 24.9-37.7 54.1-48.9 86.5 34.2 38.3 80 64.6 130.8 75.1zM400 64c-44.2 0-80 35.9-80 80.1v59.4C215.6 197.3 127 133 87 41.8c-5.5-12.5-23.2-13.2-29-.9C41.4 76 32 115.2 32 156.6c0 70.8 34.1 136.9 85.1 185.9 13.2 12.7 26.1 23.2 38.9 32.8l-143.9 36C1.4 414-3.4 426.4 2.6 435.7 20 462.6 63 508.2 155.8 512c8 .3 16-2.6 22.1-7.9l65.2-56.1H320c88.4 0 160-71.5 160-159.9V128l32-64H400zm0 96.1c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"download\": [512, 512, [], \"f019\", \"M216 0h80c13.3 0 24 10.7 24 24v168h87.7c17.8 0 26.7 21.5 14.1 34.1L269.7 378.3c-7.5 7.5-19.8 7.5-27.3 0L90.1 226.1c-12.6-12.6-3.7-34.1 14.1-34.1H192V24c0-13.3 10.7-24 24-24zm296 376v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h146.7l49 49c20.1 20.1 52.5 20.1 72.6 0l49-49H488c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"drafting-compass\": [512, 512, [], \"f568\", \"M457.01 344.42c-25.05 20.33-52.63 37.18-82.54 49.05l54.38 94.19 53.95 23.04c9.81 4.19 20.89-2.21 22.17-12.8l7.02-58.25-54.98-95.23zm42.49-94.56c4.86-7.67 1.89-17.99-6.05-22.39l-28.07-15.57c-7.48-4.15-16.61-1.46-21.26 5.72C403.01 281.15 332.25 320 256 320c-23.93 0-47.23-4.25-69.41-11.53l67.36-116.68c.7.02 1.34.21 2.04.21s1.35-.19 2.04-.21l51.09 88.5c31.23-8.96 59.56-25.75 82.61-48.92l-51.79-89.71C347.39 128.03 352 112.63 352 96c0-53.02-42.98-96-96-96s-96 42.98-96 96c0 16.63 4.61 32.03 12.05 45.66l-68.3 118.31c-12.55-11.61-23.96-24.59-33.68-39-4.79-7.1-13.97-9.62-21.38-5.33l-27.75 16.07c-7.85 4.54-10.63 14.9-5.64 22.47 15.57 23.64 34.69 44.21 55.98 62.02L0 439.66l7.02 58.25c1.28 10.59 12.36 16.99 22.17 12.8l53.95-23.04 70.8-122.63C186.13 377.28 220.62 384 256 384c99.05 0 190.88-51.01 243.5-134.14zM256 64c17.67 0 32 14.33 32 32s-14.33 32-32 32-32-14.33-32-32 14.33-32 32-32z\"],\n    \"dragon\": [640, 512, [], \"f6d5\", \"M18.32 255.78L192 223.96l-91.28 68.69c-10.08 10.08-2.94 27.31 11.31 27.31h222.7c-9.44-26.4-14.73-54.47-14.73-83.38v-42.27l-119.73-87.6c-23.82-15.88-55.29-14.01-77.06 4.59L5.81 227.64c-12.38 10.33-3.45 30.42 12.51 28.14zm556.87 34.1l-100.66-50.31A47.992 47.992 0 0 1 448 196.65v-36.69h64l28.09 22.63c6 6 14.14 9.37 22.63 9.37h30.97a32 32 0 0 0 28.62-17.69l14.31-28.62a32.005 32.005 0 0 0-3.02-33.51l-74.53-99.38C553.02 4.7 543.54 0 533.47 0H296.02c-7.13 0-10.7 8.57-5.66 13.61L352 63.96 292.42 88.8c-5.9 2.95-5.9 11.36 0 14.31L352 127.96v108.62c0 72.08 36.03 139.39 96 179.38-195.59 6.81-344.56 41.01-434.1 60.91C5.78 478.67 0 485.88 0 494.2 0 504 7.95 512 17.76 512h499.08c63.29.01 119.61-47.56 122.99-110.76 2.52-47.28-22.73-90.4-64.64-111.36zM489.18 66.25l45.65 11.41c-2.75 10.91-12.47 18.89-24.13 18.26-12.96-.71-25.85-12.53-21.52-29.67z\"],\n    \"draw-polygon\": [448, 512, [], \"f5ee\", \"M384 352c-.35 0-.67.1-1.02.1l-39.2-65.32c5.07-9.17 8.22-19.56 8.22-30.78s-3.14-21.61-8.22-30.78l39.2-65.32c.35.01.67.1 1.02.1 35.35 0 64-28.65 64-64s-28.65-64-64-64c-23.63 0-44.04 12.95-55.12 32H119.12C108.04 44.95 87.63 32 64 32 28.65 32 0 60.65 0 96c0 23.63 12.95 44.04 32 55.12v209.75C12.95 371.96 0 392.37 0 416c0 35.35 28.65 64 64 64 23.63 0 44.04-12.95 55.12-32h209.75c11.09 19.05 31.49 32 55.12 32 35.35 0 64-28.65 64-64 .01-35.35-28.64-64-63.99-64zm-288 8.88V151.12A63.825 63.825 0 0 0 119.12 128h208.36l-38.46 64.1c-.35-.01-.67-.1-1.02-.1-35.35 0-64 28.65-64 64s28.65 64 64 64c.35 0 .67-.1 1.02-.1l38.46 64.1H119.12A63.748 63.748 0 0 0 96 360.88zM272 256c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zM400 96c0 8.82-7.18 16-16 16s-16-7.18-16-16 7.18-16 16-16 16 7.18 16 16zM64 80c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zM48 416c0-8.82 7.18-16 16-16s16 7.18 16 16-7.18 16-16 16-16-7.18-16-16zm336 16c-8.82 0-16-7.18-16-16s7.18-16 16-16 16 7.18 16 16-7.18 16-16 16z\"],\n    \"drum\": [576, 512, [], \"f569\", \"M458.08 120.88l102.39-61.43c15.16-9.09 20.06-28.75 10.97-43.91C562.34.39 542.7-4.53 527.53 4.57l-160.69 96.41A629.32 629.32 0 0 0 288 96C128.94 96 0 153.31 0 224v160.83c0 30.46 24.03 58.4 64 80.37v-96.37c0-17.6 14.4-32 32-32s32 14.4 32 32v122.41c37.4 11.13 81 18.44 128 20.75V400.84c0-17.6 14.4-32 32-32s32 14.4 32 32V512c47-2.31 90.6-9.62 128-20.75V368.84c0-17.6 14.4-32 32-32s32 14.4 32 32v96.37c39.97-21.97 64-49.91 64-80.37V224.01c-.01-42.38-46.54-79.84-117.92-103.13zM288 304c-132.55 0-240-35.82-240-80s107.45-80 240-80c2.34 0 4.62.1 6.94.12l-87.41 52.44c-15.16 9.09-20.06 28.75-10.97 43.91 9.56 15.93 29.51 19.61 43.91 10.97l162.71-97.62C477.55 167.41 528 193.74 528 224.01 528 268.19 420.54 304 288 304z\"],\n    \"drum-steelpan\": [576, 512, [], \"f56a\", \"M288 32C128.94 32 0 89.31 0 160v192c0 70.69 128.94 128 288 128s288-57.31 288-128V160c0-70.69-128.94-128-288-128zm-82.99 158.36c-4.45 16.61-14.54 30.57-28.31 40.48C100.23 217.46 48 190.78 48 160c0-30.16 50.11-56.39 124.04-70.03l25.6 44.34c9.86 17.09 12.48 36.99 7.37 56.05zM288 240c-21.08 0-41.41-1-60.89-2.7 8.06-26.13 32.15-45.3 60.89-45.3s52.83 19.17 60.89 45.3C329.41 239 309.08 240 288 240zm64-144c0 35.29-28.71 64-64 64s-64-28.71-64-64V82.96c20.4-1.88 41.8-2.96 64-2.96s43.6 1.08 64 2.96V96zm46.93 134.9c-13.81-9.91-23.94-23.9-28.4-40.54-5.11-19.06-2.49-38.96 7.38-56.04l25.65-44.42C477.72 103.5 528 129.79 528 160c0 30.83-52.4 57.54-129.07 70.9z\"],\n    \"drumstick-bite\": [512, 512, [], \"f6d7\", \"M462.8 49.57a169.44 169.44 0 0 0-239.5 0C187.82 85 160.13 128 160.13 192v85.83l-40.62 40.59c-9.7 9.69-24 11.07-36.78 6a60.33 60.33 0 0 0-65 98.72C33 438.39 54.24 442.7 73.85 438.21c-4.5 19.6-.18 40.83 15.1 56.1a60.35 60.35 0 0 0 98.8-65c-5.09-12.73-3.72-27 6-36.75L234.36 352h85.89a187.87 187.87 0 0 0 61.89-10c-39.64-43.89-39.83-110.23 1.05-151.07 34.38-34.36 86.76-39.46 128.74-16.8 1.3-44.96-14.81-90.28-49.13-124.56z\"],\n    \"dumbbell\": [640, 512, [], \"f44b\", \"M104 96H56c-13.3 0-24 10.7-24 24v104H8c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8h24v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm528 128h-24V120c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v272c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h24c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zM456 32h-48c-13.3 0-24 10.7-24 24v168H256V56c0-13.3-10.7-24-24-24h-48c-13.3 0-24 10.7-24 24v400c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V288h128v168c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24z\"],\n    \"dumpster\": [576, 512, [], \"f793\", \"M560 160c10.4 0 18-9.8 15.5-19.9l-24-96C549.7 37 543.3 32 536 32h-98.9l25.6 128H560zM272 32H171.5l-25.6 128H272V32zm132.5 0H304v128h126.1L404.5 32zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm544 64h-20l4-32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h320v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16l20-160h28c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"dumpster-fire\": [640, 512, [], \"f794\", \"M418.7 104.1l.2-.2-14.4-72H304v128h60.8c16.2-19.3 34.2-38.2 53.9-55.8zM272 32H171.5l-25.6 128H272V32zm189.3 72.1c18.2 16.3 35.5 33.7 51.1 51.5 5.7-5.6 11.4-11.1 17.3-16.3l21.3-19 21.3 19c1.1.9 2.1 2.1 3.1 3.1-.1-.8.2-1.5 0-2.3l-24-96C549.7 37 543.3 32 536 32h-98.9l12.3 61.5 11.9 10.6zM16 160h97.3l25.6-128H40c-7.3 0-13.7 5-15.5 12.1l-24 96C-2 150.2 5.6 160 16 160zm324.6 32H32l4 32H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h28l20 160v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208.8c-30.2-33.7-48.8-77.9-48.8-126.4 0-35.9 19.9-82.9 52.6-129.6zm210.5-28.8c-14.9 13.3-28.3 27.2-40.2 41.2-19.5-25.8-43.6-52-71-76.4-70.2 62.7-120 144.3-120 193.6 0 87.5 71.6 158.4 160 158.4s160-70.9 160-158.4c.1-36.6-37-112.2-88.8-158.4zm-18.6 229.4c-14.7 10.7-32.9 17-52.5 17-49 0-88.9-33.5-88.9-88 0-27.1 16.5-51 49.4-91.9 4.7 5.6 67.1 88.1 67.1 88.1l39.8-47c2.8 4.8 5.4 9.5 7.7 14 18.6 36.7 10.8 83.6-22.6 107.8z\"],\n    \"dungeon\": [512, 512, [], \"f6d9\", \"M128.73 195.32l-82.81-51.76c-8.04-5.02-18.99-2.17-22.93 6.45A254.19 254.19 0 0 0 .54 239.28C-.05 248.37 7.59 256 16.69 256h97.13c7.96 0 14.08-6.25 15.01-14.16 1.09-9.33 3.24-18.33 6.24-26.94 2.56-7.34.25-15.46-6.34-19.58zM319.03 8C298.86 2.82 277.77 0 256 0s-42.86 2.82-63.03 8c-9.17 2.35-13.91 12.6-10.39 21.39l37.47 104.03A16.003 16.003 0 0 0 235.1 144h41.8c6.75 0 12.77-4.23 15.05-10.58l37.47-104.03c3.52-8.79-1.22-19.03-10.39-21.39zM112 288H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm77.31-283.67l-36.32-90.8c-3.53-8.83-14.13-12.99-22.42-8.31a257.308 257.308 0 0 0-71.61 59.89c-6.06 7.32-3.85 18.48 4.22 23.52l82.93 51.83c6.51 4.07 14.66 2.62 20.11-2.79 5.18-5.15 10.79-9.85 16.79-14.05 6.28-4.41 9.15-12.17 6.3-19.29zM398.18 256h97.13c9.1 0 16.74-7.63 16.15-16.72a254.135 254.135 0 0 0-22.45-89.27c-3.94-8.62-14.89-11.47-22.93-6.45l-82.81 51.76c-6.59 4.12-8.9 12.24-6.34 19.58 3.01 8.61 5.15 17.62 6.24 26.94.93 7.91 7.05 14.16 15.01 14.16zm54.85-162.89a257.308 257.308 0 0 0-71.61-59.89c-8.28-4.68-18.88-.52-22.42 8.31l-36.32 90.8c-2.85 7.12.02 14.88 6.3 19.28 6 4.2 11.61 8.9 16.79 14.05 5.44 5.41 13.6 6.86 20.11 2.79l82.93-51.83c8.07-5.03 10.29-16.19 4.22-23.51zM496 288h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm0 128h-96c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h96c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zM240 177.62V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V177.62c-5.23-.89-10.52-1.62-16-1.62s-10.77.73-16 1.62zm-64 41.51V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V189.36c-12.78 7.45-23.84 17.47-32 29.77zm128-29.77V472c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8V219.13c-8.16-12.3-19.22-22.32-32-29.77z\"],\n    \"edit\": [576, 512, [], \"f044\", \"M402.6 83.2l90.2 90.2c3.8 3.8 3.8 10 0 13.8L274.4 405.6l-92.8 10.3c-12.4 1.4-22.9-9.1-21.5-21.5l10.3-92.8L388.8 83.2c3.8-3.8 10-3.8 13.8 0zm162-22.9l-48.8-48.8c-15.2-15.2-39.9-15.2-55.2 0l-35.4 35.4c-3.8 3.8-3.8 10 0 13.8l90.2 90.2c3.8 3.8 10 3.8 13.8 0l35.4-35.4c15.2-15.3 15.2-40 0-55.2zM384 346.2V448H64V128h229.8c3.2 0 6.2-1.3 8.5-3.5l40-40c7.6-7.6 2.2-20.5-8.5-20.5H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V306.2c0-10.7-12.9-16-20.5-8.5l-40 40c-2.2 2.3-3.5 5.3-3.5 8.5z\"],\n    \"egg\": [384, 512, [], \"f7fb\", \"M192 0C86 0 0 214 0 320s86 192 192 192 192-86 192-192S298 0 192 0z\"],\n    \"eject\": [448, 512, [], \"f052\", \"M448 384v64c0 17.673-14.327 32-32 32H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h384c17.673 0 32 14.327 32 32zM48.053 320h351.886c41.651 0 63.581-49.674 35.383-80.435L259.383 47.558c-19.014-20.743-51.751-20.744-70.767 0L12.67 239.565C-15.475 270.268 6.324 320 48.053 320z\"],\n    \"ellipsis-h\": [512, 512, [], \"f141\", \"M328 256c0 39.8-32.2 72-72 72s-72-32.2-72-72 32.2-72 72-72 72 32.2 72 72zm104-72c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72zm-352 0c-39.8 0-72 32.2-72 72s32.2 72 72 72 72-32.2 72-72-32.2-72-72-72z\"],\n    \"ellipsis-v\": [192, 512, [], \"f142\", \"M96 184c39.8 0 72 32.2 72 72s-32.2 72-72 72-72-32.2-72-72 32.2-72 72-72zM24 80c0 39.8 32.2 72 72 72s72-32.2 72-72S135.8 8 96 8 24 40.2 24 80zm0 352c0 39.8 32.2 72 72 72s72-32.2 72-72-32.2-72-72-72-72 32.2-72 72z\"],\n    \"envelope\": [512, 512, [], \"f0e0\", \"M502.3 190.8c3.9-3.1 9.7-.2 9.7 4.7V400c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V195.6c0-5 5.7-7.8 9.7-4.7 22.4 17.4 52.1 39.5 154.1 113.6 21.1 15.4 56.7 47.8 92.2 47.6 35.7.3 72-32.8 92.3-47.6 102-74.1 131.6-96.3 154-113.7zM256 320c23.2.4 56.6-29.2 73.4-41.4 132.7-96.3 142.8-104.7 173.4-128.7 5.8-4.5 9.2-11.5 9.2-18.9v-19c0-26.5-21.5-48-48-48H48C21.5 64 0 85.5 0 112v19c0 7.4 3.4 14.3 9.2 18.9 30.6 23.9 40.7 32.4 173.4 128.7 16.8 12.2 50.2 41.8 73.4 41.4z\"],\n    \"envelope-open\": [512, 512, [], \"f2b6\", \"M512 464c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V200.724a48 48 0 0 1 18.387-37.776c24.913-19.529 45.501-35.365 164.2-121.511C199.412 29.17 232.797-.347 256 .003c23.198-.354 56.596 29.172 73.413 41.433 118.687 86.137 139.303 101.995 164.2 121.512A48 48 0 0 1 512 200.724V464zm-65.666-196.605c-2.563-3.728-7.7-4.595-11.339-1.907-22.845 16.873-55.462 40.705-105.582 77.079-16.825 12.266-50.21 41.781-73.413 41.43-23.211.344-56.559-29.143-73.413-41.43-50.114-36.37-82.734-60.204-105.582-77.079-3.639-2.688-8.776-1.821-11.339 1.907l-9.072 13.196a7.998 7.998 0 0 0 1.839 10.967c22.887 16.899 55.454 40.69 105.303 76.868 20.274 14.781 56.524 47.813 92.264 47.573 35.724.242 71.961-32.771 92.263-47.573 49.85-36.179 82.418-59.97 105.303-76.868a7.998 7.998 0 0 0 1.839-10.967l-9.071-13.196z\"],\n    \"envelope-open-text\": [512, 512, [], \"f658\", \"M176 216h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16zm-16 80c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16zm96 121.13c-16.42 0-32.84-5.06-46.86-15.19L0 250.86V464c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V250.86L302.86 401.94c-14.02 10.12-30.44 15.19-46.86 15.19zm237.61-254.18c-8.85-6.94-17.24-13.47-29.61-22.81V96c0-26.51-21.49-48-48-48h-77.55c-3.04-2.2-5.87-4.26-9.04-6.56C312.6 29.17 279.2-.35 256 0c-23.2-.35-56.59 29.17-73.41 41.44-3.17 2.3-6 4.36-9.04 6.56H96c-26.51 0-48 21.49-48 48v44.14c-12.37 9.33-20.76 15.87-29.61 22.81A47.995 47.995 0 0 0 0 200.72v10.65l96 69.35V96h320v184.72l96-69.35v-10.65c0-14.74-6.78-28.67-18.39-37.77z\"],\n    \"envelope-square\": [448, 512, [], \"f199\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM178.117 262.104C87.429 196.287 88.353 196.121 64 177.167V152c0-13.255 10.745-24 24-24h272c13.255 0 24 10.745 24 24v25.167c-24.371 18.969-23.434 19.124-114.117 84.938-10.5 7.655-31.392 26.12-45.883 25.894-14.503.218-35.367-18.227-45.883-25.895zM384 217.775V360c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V217.775c13.958 10.794 33.329 25.236 95.303 70.214 14.162 10.341 37.975 32.145 64.694 32.01 26.887.134 51.037-22.041 64.72-32.025 61.958-44.965 81.325-59.406 95.283-70.199z\"],\n    \"equals\": [448, 512, [], \"f52c\", \"M416 304H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32zm0-192H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"eraser\": [512, 512, [], \"f12d\", \"M497.941 273.941c18.745-18.745 18.745-49.137 0-67.882l-160-160c-18.745-18.745-49.136-18.746-67.883 0l-256 256c-18.745 18.745-18.745 49.137 0 67.882l96 96A48.004 48.004 0 0 0 144 480h356c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H355.883l142.058-142.059zm-302.627-62.627l137.373 137.373L265.373 416H150.628l-80-80 124.686-124.686z\"],\n    \"ethernet\": [512, 512, [], \"f796\", \"M496 192h-48v-48c0-8.8-7.2-16-16-16h-48V80c0-8.8-7.2-16-16-16H144c-8.8 0-16 7.2-16 16v48H80c-8.8 0-16 7.2-16 16v48H16c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16h80V320h32v128h64V320h32v128h64V320h32v128h64V320h32v128h80c8.8 0 16-7.2 16-16V208c0-8.8-7.2-16-16-16z\"],\n    \"euro-sign\": [320, 512, [], \"f153\", \"M310.706 413.765c-1.314-6.63-7.835-10.872-14.424-9.369-10.692 2.439-27.422 5.413-45.426 5.413-56.763 0-101.929-34.79-121.461-85.449h113.689a12 12 0 0 0 11.708-9.369l6.373-28.36c1.686-7.502-4.019-14.631-11.708-14.631H115.22c-1.21-14.328-1.414-28.287.137-42.245H261.95a12 12 0 0 0 11.723-9.434l6.512-29.755c1.638-7.484-4.061-14.566-11.723-14.566H130.184c20.633-44.991 62.69-75.03 117.619-75.03 14.486 0 28.564 2.25 37.851 4.145 6.216 1.268 12.347-2.498 14.002-8.623l11.991-44.368c1.822-6.741-2.465-13.616-9.326-14.917C290.217 34.912 270.71 32 249.635 32 152.451 32 74.03 92.252 45.075 176H12c-6.627 0-12 5.373-12 12v29.755c0 6.627 5.373 12 12 12h21.569c-1.009 13.607-1.181 29.287-.181 42.245H12c-6.627 0-12 5.373-12 12v28.36c0 6.627 5.373 12 12 12h30.114C67.139 414.692 145.264 480 249.635 480c26.301 0 48.562-4.544 61.101-7.788 6.167-1.595 10.027-7.708 8.788-13.957l-8.818-44.49z\"],\n    \"exchange-alt\": [512, 512, [], \"f362\", \"M0 168v-16c0-13.255 10.745-24 24-24h360V80c0-21.367 25.899-32.042 40.971-16.971l80 80c9.372 9.373 9.372 24.569 0 33.941l-80 80C409.956 271.982 384 261.456 384 240v-48H24c-13.255 0-24-10.745-24-24zm488 152H128v-48c0-21.314-25.862-32.08-40.971-16.971l-80 80c-9.372 9.373-9.372 24.569 0 33.941l80 80C102.057 463.997 128 453.437 128 432v-48h360c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24z\"],\n    \"exclamation\": [192, 512, [], \"f12a\", \"M176 432c0 44.112-35.888 80-80 80s-80-35.888-80-80 35.888-80 80-80 80 35.888 80 80zM25.26 25.199l13.6 272C39.499 309.972 50.041 320 62.83 320h66.34c12.789 0 23.331-10.028 23.97-22.801l13.6-272C167.425 11.49 156.496 0 142.77 0H49.23C35.504 0 24.575 11.49 25.26 25.199z\"],\n    \"exclamation-circle\": [512, 512, [], \"f06a\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zm-248 50c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"exclamation-triangle\": [576, 512, [], \"f071\", \"M569.517 440.013C587.975 472.007 564.806 512 527.94 512H48.054c-36.937 0-59.999-40.055-41.577-71.987L246.423 23.985c18.467-32.009 64.72-31.951 83.154 0l239.94 416.028zM288 354c-25.405 0-46 20.595-46 46s20.595 46 46 46 46-20.595 46-46-20.595-46-46-46zm-43.673-165.346l7.418 136c.347 6.364 5.609 11.346 11.982 11.346h48.546c6.373 0 11.635-4.982 11.982-11.346l7.418-136c.375-6.874-5.098-12.654-11.982-12.654h-63.383c-6.884 0-12.356 5.78-11.981 12.654z\"],\n    \"expand\": [448, 512, [], \"f065\", \"M0 180V56c0-13.3 10.7-24 24-24h124c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12H64v84c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12zM288 44v40c0 6.6 5.4 12 12 12h84v84c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V56c0-13.3-10.7-24-24-24H300c-6.6 0-12 5.4-12 12zm148 276h-40c-6.6 0-12 5.4-12 12v84h-84c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h124c13.3 0 24-10.7 24-24V332c0-6.6-5.4-12-12-12zM160 468v-40c0-6.6-5.4-12-12-12H64v-84c0-6.6-5.4-12-12-12H12c-6.6 0-12 5.4-12 12v124c0 13.3 10.7 24 24 24h124c6.6 0 12-5.4 12-12z\"],\n    \"expand-arrows-alt\": [448, 512, [], \"f31e\", \"M448 344v112a23.94 23.94 0 0 1-24 24H312c-21.39 0-32.09-25.9-17-41l36.2-36.2L224 295.6 116.77 402.9 153 439c15.09 15.1 4.39 41-17 41H24a23.94 23.94 0 0 1-24-24V344c0-21.4 25.89-32.1 41-17l36.19 36.2L184.46 256 77.18 148.7 41 185c-15.1 15.1-41 4.4-41-17V56a23.94 23.94 0 0 1 24-24h112c21.39 0 32.09 25.9 17 41l-36.2 36.2L224 216.4l107.23-107.3L295 73c-15.09-15.1-4.39-41 17-41h112a23.94 23.94 0 0 1 24 24v112c0 21.4-25.89 32.1-41 17l-36.19-36.2L263.54 256l107.28 107.3L407 327.1c15.1-15.2 41-4.5 41 16.9z\"],\n    \"external-link-alt\": [576, 512, [], \"f35d\", \"M576 24v127.984c0 21.461-25.96 31.98-40.971 16.971l-35.707-35.709-243.523 243.523c-9.373 9.373-24.568 9.373-33.941 0l-22.627-22.627c-9.373-9.373-9.373-24.569 0-33.941L442.756 76.676l-35.703-35.705C391.982 25.9 402.656 0 424.024 0H552c13.255 0 24 10.745 24 24zM407.029 270.794l-16 16A23.999 23.999 0 0 0 384 303.765V448H64V128h264a24.003 24.003 0 0 0 16.97-7.029l16-16C376.089 89.851 365.381 64 344 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V287.764c0-21.382-25.852-32.09-40.971-16.97z\"],\n    \"external-link-square-alt\": [448, 512, [], \"f360\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-88 16H248.029c-21.313 0-32.08 25.861-16.971 40.971l31.984 31.987L67.515 364.485c-4.686 4.686-4.686 12.284 0 16.971l31.029 31.029c4.687 4.686 12.285 4.686 16.971 0l195.526-195.526 31.988 31.991C358.058 263.977 384 253.425 384 231.979V120c0-13.255-10.745-24-24-24z\"],\n    \"eye\": [576, 512, [], \"f06e\", \"M572.52 241.4C518.29 135.59 410.93 64 288 64S57.68 135.64 3.48 241.41a32.35 32.35 0 0 0 0 29.19C57.71 376.41 165.07 448 288 448s230.32-71.64 284.52-177.41a32.35 32.35 0 0 0 0-29.19zM288 400a144 144 0 1 1 144-144 143.93 143.93 0 0 1-144 144zm0-240a95.31 95.31 0 0 0-25.31 3.79 47.85 47.85 0 0 1-66.9 66.9A95.78 95.78 0 1 0 288 160z\"],\n    \"eye-dropper\": [512, 512, [], \"f1fb\", \"M50.75 333.25c-12 12-18.75 28.28-18.75 45.26V424L0 480l32 32 56-32h45.49c16.97 0 33.25-6.74 45.25-18.74l126.64-126.62-128-128L50.75 333.25zM483.88 28.12c-37.47-37.5-98.28-37.5-135.75 0l-77.09 77.09-13.1-13.1c-9.44-9.44-24.65-9.31-33.94 0l-40.97 40.97c-9.37 9.37-9.37 24.57 0 33.94l161.94 161.94c9.44 9.44 24.65 9.31 33.94 0L419.88 288c9.37-9.37 9.37-24.57 0-33.94l-13.1-13.1 77.09-77.09c37.51-37.48 37.51-98.26.01-135.75z\"],\n    \"eye-slash\": [640, 512, [], \"f070\", \"M320 400c-75.85 0-137.25-58.71-142.9-133.11L72.2 185.82c-13.79 17.3-26.48 35.59-36.72 55.59a32.35 32.35 0 0 0 0 29.19C89.71 376.41 197.07 448 320 448c26.91 0 52.87-4 77.89-10.46L346 397.39a144.13 144.13 0 0 1-26 2.61zm313.82 58.1l-110.55-85.44a331.25 331.25 0 0 0 81.25-102.07 32.35 32.35 0 0 0 0-29.19C550.29 135.59 442.93 64 320 64a308.15 308.15 0 0 0-147.32 37.7L45.46 3.37A16 16 0 0 0 23 6.18L3.37 31.45A16 16 0 0 0 6.18 53.9l588.36 454.73a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zm-183.72-142l-39.3-30.38A94.75 94.75 0 0 0 416 256a94.76 94.76 0 0 0-121.31-92.21A47.65 47.65 0 0 1 304 192a46.64 46.64 0 0 1-1.54 10l-73.61-56.89A142.31 142.31 0 0 1 320 112a143.92 143.92 0 0 1 144 144c0 21.63-5.29 41.79-13.9 60.11z\"],\n    \"fan\": [512, 512, [], \"f863\", \"M352.57 128c-28.09 0-54.09 4.52-77.06 12.86l12.41-123.11C289 7.31 279.81-1.18 269.33.13 189.63 10.13 128 77.64 128 159.43c0 28.09 4.52 54.09 12.86 77.06L17.75 224.08C7.31 223-1.18 232.19.13 242.67c10 79.7 77.51 141.33 159.3 141.33 28.09 0 54.09-4.52 77.06-12.86l-12.41 123.11c-1.05 10.43 8.11 18.93 18.59 17.62 79.7-10 141.33-77.51 141.33-159.3 0-28.09-4.52-54.09-12.86-77.06l123.11 12.41c10.44 1.05 18.93-8.11 17.62-18.59-10-79.7-77.51-141.33-159.3-141.33zM256 288a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"fast-backward\": [512, 512, [], \"f049\", \"M0 436V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v151.9L235.5 71.4C256.1 54.3 288 68.6 288 96v131.9L459.5 71.4C480.1 54.3 512 68.6 512 96v320c0 27.4-31.9 41.7-52.5 24.6L288 285.3V416c0 27.4-31.9 41.7-52.5 24.6L64 285.3V436c0 6.6-5.4 12-12 12H12c-6.6 0-12-5.4-12-12z\"],\n    \"fast-forward\": [512, 512, [], \"f050\", \"M512 76v360c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V284.1L276.5 440.6c-20.6 17.2-52.5 2.8-52.5-24.6V284.1L52.5 440.6C31.9 457.8 0 443.4 0 416V96c0-27.4 31.9-41.7 52.5-24.6L224 226.8V96c0-27.4 31.9-41.7 52.5-24.6L448 226.8V76c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12z\"],\n    \"fax\": [512, 512, [], \"f1ac\", \"M64 128H32c-17.67 0-32 14.33-32 32v320c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32zm416 32V77.25c0-8.49-3.37-16.62-9.37-22.63L425.37 9.37c-6-6-14.14-9.37-22.63-9.37H160c-17.67 0-32 14.33-32 32v448c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zM288 432c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm128 128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm0-128c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v32zm16-112H176V48h208v32c0 8.84 7.16 16 16 16h32v96z\"],\n    \"feather\": [512, 512, [], \"f52d\", \"M467.14 44.84c-62.55-62.48-161.67-64.78-252.28 25.73-78.61 78.52-60.98 60.92-85.75 85.66-60.46 60.39-70.39 150.83-63.64 211.17l178.44-178.25c6.26-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.6 9.37 33.98 0l66.1-66.03C159.42 454.65 279 457.11 353.95 384h-98.19l147.57-49.14c49.99-49.93 36.38-36.18 46.31-46.86h-97.78l131.54-43.8c45.44-74.46 34.31-148.84-16.26-199.36z\"],\n    \"feather-alt\": [512, 512, [], \"f56b\", \"M512 0C460.22 3.56 96.44 38.2 71.01 287.61c-3.09 26.66-4.84 53.44-5.99 80.24l178.87-178.69c6.25-6.25 16.4-6.25 22.65 0s6.25 16.38 0 22.63L7.04 471.03c-9.38 9.37-9.38 24.57 0 33.94 9.38 9.37 24.59 9.37 33.98 0l57.13-57.07c42.09-.14 84.15-2.53 125.96-7.36 53.48-5.44 97.02-26.47 132.58-56.54H255.74l146.79-48.88c11.25-14.89 21.37-30.71 30.45-47.12h-81.14l106.54-53.21C500.29 132.86 510.19 26.26 512 0z\"],\n    \"female\": [256, 512, [], \"f182\", \"M128 0c35.346 0 64 28.654 64 64s-28.654 64-64 64c-35.346 0-64-28.654-64-64S92.654 0 128 0m119.283 354.179l-48-192A24 24 0 0 0 176 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H80a24 24 0 0 0-23.283 18.179l-48 192C4.935 369.305 16.383 384 32 384h56v104c0 13.255 10.745 24 24 24h32c13.255 0 24-10.745 24-24V384h56c15.591 0 27.071-14.671 23.283-29.821z\"],\n    \"fighter-jet\": [640, 512, [], \"f0fb\", \"M544 224l-128-16-48-16h-24L227.158 44h39.509C278.333 44 288 41.375 288 38s-9.667-6-21.333-6H152v12h16v164h-48l-66.667-80H18.667L8 138.667V208h8v16h48v2.666l-64 8v42.667l64 8V288H16v16H8v69.333L18.667 384h34.667L120 304h48v164h-16v12h114.667c11.667 0 21.333-2.625 21.333-6s-9.667-6-21.333-6h-39.509L344 320h24l48-16 128-16c96-21.333 96-26.583 96-32 0-5.417 0-10.667-96-32z\"],\n    \"file\": [384, 512, [], \"f15b\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm160-14.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-alt\": [384, 512, [], \"f15c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 236c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-64c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12v8zm0-72v8c0 6.6-5.4 12-12 12H108c-6.6 0-12-5.4-12-12v-8c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm96-114.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-archive\": [384, 512, [], \"f1c6\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zM128.4 336c-17.9 0-32.4 12.1-32.4 27 0 15 14.6 27 32.5 27s32.4-12.1 32.4-27-14.6-27-32.5-27zM224 136V0h-63.6v32h-32V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM95.9 32h32v32h-32zm32.3 384c-33.2 0-58-30.4-51.4-62.9L96.4 256v-32h32v-32h-32v-32h32v-32h-32V96h32V64h32v32h-32v32h32v32h-32v32h32v32h-32v32h22.1c5.7 0 10.7 4.1 11.8 9.7l17.3 87.7c6.4 32.4-18.4 62.6-51.4 62.6z\"],\n    \"file-audio\": [384, 512, [], \"f1c7\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-64 268c0 10.7-12.9 16-20.5 8.5L104 376H76c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h28l35.5-36.5c7.6-7.6 20.5-2.2 20.5 8.5v136zm33.2-47.6c9.1-9.3 9.1-24.1 0-33.4-22.1-22.8 12.2-56.2 34.4-33.5 27.2 27.9 27.2 72.4 0 100.4-21.8 22.3-56.9-10.4-34.4-33.5zm86-117.1c54.4 55.9 54.4 144.8 0 200.8-21.8 22.4-57-10.3-34.4-33.5 36.2-37.2 36.3-96.5 0-133.8-22.1-22.8 12.3-56.3 34.4-33.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-code\": [384, 512, [], \"f1c9\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zM123.206 400.505a5.4 5.4 0 0 1-7.633.246l-64.866-60.812a5.4 5.4 0 0 1 0-7.879l64.866-60.812a5.4 5.4 0 0 1 7.633.246l19.579 20.885a5.4 5.4 0 0 1-.372 7.747L101.65 336l40.763 35.874a5.4 5.4 0 0 1 .372 7.747l-19.579 20.884zm51.295 50.479l-27.453-7.97a5.402 5.402 0 0 1-3.681-6.692l61.44-211.626a5.402 5.402 0 0 1 6.692-3.681l27.452 7.97a5.4 5.4 0 0 1 3.68 6.692l-61.44 211.626a5.397 5.397 0 0 1-6.69 3.681zm160.792-111.045l-64.866 60.812a5.4 5.4 0 0 1-7.633-.246l-19.58-20.885a5.4 5.4 0 0 1 .372-7.747L284.35 336l-40.763-35.874a5.4 5.4 0 0 1-.372-7.747l19.58-20.885a5.4 5.4 0 0 1 7.633-.246l64.866 60.812a5.4 5.4 0 0 1-.001 7.879z\"],\n    \"file-contract\": [384, 512, [], \"f56c\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm192.81 248H304c8.84 0 16 7.16 16 16s-7.16 16-16 16h-47.19c-16.45 0-31.27-9.14-38.64-23.86-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34a15.986 15.986 0 0 1-14.31 8.84c-.38 0-.75-.02-1.14-.05-6.45-.45-12-4.75-14.03-10.89L144 354.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.77-16.19 54.05-9.7 66 14.16 2.02 4.06 5.96 6.5 10.16 6.5zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-csv\": [384, 512, [], \"f6dd\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm-96 144c0 4.42-3.58 8-8 8h-8c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h8c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-8c-26.51 0-48-21.49-48-48v-32c0-26.51 21.49-48 48-48h8c4.42 0 8 3.58 8 8v16zm44.27 104H160c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h12.27c5.95 0 10.41-3.5 10.41-6.62 0-1.3-.75-2.66-2.12-3.84l-21.89-18.77c-8.47-7.22-13.33-17.48-13.33-28.14 0-21.3 19.02-38.62 42.41-38.62H200c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8h-12.27c-5.95 0-10.41 3.5-10.41 6.62 0 1.3.75 2.66 2.12 3.84l21.89 18.77c8.47 7.22 13.33 17.48 13.33 28.14.01 21.29-19 38.62-42.39 38.62zM256 264v20.8c0 20.27 5.7 40.17 16 56.88 10.3-16.7 16-36.61 16-56.88V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v20.8c0 35.48-12.88 68.89-36.28 94.09-3.02 3.25-7.27 5.11-11.72 5.11s-8.7-1.86-11.72-5.11c-23.4-25.2-36.28-58.61-36.28-94.09V264c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8zm121-159L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-download\": [384, 512, [], \"f56d\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm76.45 211.36l-96.42 95.7c-6.65 6.61-17.39 6.61-24.04 0l-96.42-95.7C73.42 337.29 80.54 320 94.82 320H160v-80c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v80h65.18c14.28 0 21.4 17.29 11.27 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-excel\": [384, 512, [], \"f1c3\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm60.1 106.5L224 336l60.1 93.5c5.1 8-.6 18.5-10.1 18.5h-34.9c-4.4 0-8.5-2.4-10.6-6.3C208.9 405.5 192 373 192 373c-6.4 14.8-10 20-36.6 68.8-2.1 3.9-6.1 6.3-10.5 6.3H110c-9.5 0-15.2-10.5-10.1-18.5l60.3-93.5-60.3-93.5c-5.2-8 .6-18.5 10.1-18.5h34.8c4.4 0 8.5 2.4 10.6 6.3 26.1 48.8 20 33.6 36.6 68.5 0 0 6.1-11.7 36.6-68.5 2.1-3.9 6.2-6.3 10.6-6.3H274c9.5-.1 15.2 10.4 10.1 18.4zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-export\": [576, 512, [], \"f56e\", \"M384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128zM571 308l-95.7-96.4c-10.1-10.1-27.4-3-27.4 11.3V288h-64v64h64v65.2c0 14.3 17.3 21.4 27.4 11.3L571 332c6.6-6.6 6.6-17.4 0-24zm-379 28v-32c0-8.8 7.2-16 16-16h176V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V352H208c-8.8 0-16-7.2-16-16z\"],\n    \"file-image\": [384, 512, [], \"f1c5\", \"M384 121.941V128H256V0h6.059a24 24 0 0 1 16.97 7.029l97.941 97.941a24.002 24.002 0 0 1 7.03 16.971zM248 160c-13.2 0-24-10.8-24-24V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248zm-135.455 16c26.51 0 48 21.49 48 48s-21.49 48-48 48-48-21.49-48-48 21.491-48 48-48zm208 240h-256l.485-48.485L104.545 328c4.686-4.686 11.799-4.201 16.485.485L160.545 368 264.06 264.485c4.686-4.686 12.284-4.686 16.971 0L320.545 304v112z\"],\n    \"file-import\": [512, 512, [], \"f56f\", \"M16 288c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h112v-64zm489-183L407.1 7c-4.5-4.5-10.6-7-17-7H384v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H152c-13.3 0-24 10.7-24 24v264h128v-65.2c0-14.3 17.3-21.4 27.4-11.3L379 308c6.6 6.7 6.6 17.4 0 24l-95.7 96.4c-10.1 10.1-27.4 3-27.4-11.3V352H128v136c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H376c-13.2 0-24-10.8-24-24z\"],\n    \"file-invoice\": [384, 512, [], \"f570\", \"M288 256H96v64h192v-64zm89-151L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 64c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm256 304c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-200v96c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-96c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16z\"],\n    \"file-invoice-dollar\": [384, 512, [], \"f571\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zM64 72c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8V72zm0 80v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8zm144 263.88V440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-24.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V232c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v24.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07z\"],\n    \"file-medical\": [384, 512, [], \"f477\", \"M377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm64 160v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8z\"],\n    \"file-medical-alt\": [448, 512, [], \"f478\", \"M288 136V0H88C74.7 0 64 10.7 64 24v232H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h140.9c3 0 5.8 1.7 7.2 4.4l19.9 39.8 56.8-113.7c2.9-5.9 11.4-5.9 14.3 0l34.7 69.5H352c8.8 0 16 7.2 16 16s-7.2 16-16 16h-89.9L240 275.8l-56.8 113.7c-2.9 5.9-11.4 5.9-14.3 0L134.1 320H64v168c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H312c-13.2 0-24-10.8-24-24zm153-31L343.1 7c-4.5-4.5-10.6-7-17-7H320v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-pdf\": [384, 512, [], \"f1c1\", \"M181.9 256.1c-5-16-4.9-46.9-2-46.9 8.4 0 7.6 36.9 2 46.9zm-1.7 47.2c-7.7 20.2-17.3 43.3-28.4 62.7 18.3-7 39-17.2 62.9-21.9-12.7-9.6-24.9-23.4-34.5-40.8zM86.1 428.1c0 .8 13.2-5.4 34.9-40.2-6.7 6.3-29.1 24.5-34.9 40.2zM248 160h136v328c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V24C0 10.7 10.7 0 24 0h200v136c0 13.2 10.8 24 24 24zm-8 171.8c-20-12.2-33.3-29-42.7-53.8 4.5-18.5 11.6-46.6 6.2-64.2-4.7-29.4-42.4-26.5-47.8-6.8-5 18.3-.4 44.1 8.1 77-11.6 27.6-28.7 64.6-40.8 85.8-.1 0-.1.1-.2.1-27.1 13.9-73.6 44.5-54.5 68 5.6 6.9 16 10 21.5 10 17.9 0 35.7-18 61.1-61.8 25.8-8.5 54.1-19.1 79-23.2 21.7 11.8 47.1 19.5 64 19.5 29.2 0 31.2-32 19.7-43.4-13.9-13.6-54.3-9.7-73.6-7.2zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-74.1 255.3c4.1-2.7-2.5-11.9-42.8-9 37.1 15.8 42.8 9 42.8 9z\"],\n    \"file-powerpoint\": [384, 512, [], \"f1c4\", \"M193.7 271.2c8.8 0 15.5 2.7 20.3 8.1 9.6 10.9 9.8 32.7-.2 44.1-4.9 5.6-11.9 8.5-21.1 8.5h-26.9v-60.7h27.9zM377 105L279 7c-4.5-4.5-10.6-7-17-7h-6v128h128v-6.1c0-6.3-2.5-12.4-7-16.9zm-153 31V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm53 165.2c0 90.3-88.8 77.6-111.1 77.6V436c0 6.6-5.4 12-12 12h-30.8c-6.6 0-12-5.4-12-12V236.2c0-6.6 5.4-12 12-12h81c44.5 0 72.9 32.8 72.9 77z\"],\n    \"file-prescription\": [384, 512, [], \"f572\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm68.53 179.48l11.31 11.31c6.25 6.25 6.25 16.38 0 22.63l-29.9 29.9L304 409.38c6.25 6.25 6.25 16.38 0 22.63l-11.31 11.31c-6.25 6.25-16.38 6.25-22.63 0L240 413.25l-30.06 30.06c-6.25 6.25-16.38 6.25-22.63 0L176 432c-6.25-6.25-6.25-16.38 0-22.63l30.06-30.06L146.74 320H128v48c0 8.84-7.16 16-16 16H96c-8.84 0-16-7.16-16-16V208c0-8.84 7.16-16 16-16h80c35.35 0 64 28.65 64 64 0 24.22-13.62 45.05-33.46 55.92L240 345.38l29.9-29.9c6.25-6.25 16.38-6.25 22.63 0zM176 272h-48v-32h48c8.82 0 16 7.18 16 16s-7.18 16-16 16zm208-150.1v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"file-signature\": [576, 512, [], \"f573\", \"M218.17 424.14c-2.95-5.92-8.09-6.52-10.17-6.52s-7.22.59-10.02 6.19l-7.67 15.34c-6.37 12.78-25.03 11.37-29.48-2.09L144 386.59l-10.61 31.88c-5.89 17.66-22.38 29.53-41 29.53H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h12.39c4.83 0 9.11-3.08 10.64-7.66l18.19-54.64c3.3-9.81 12.44-16.41 22.78-16.41s19.48 6.59 22.77 16.41l13.88 41.64c19.75-16.19 54.06-9.7 66 14.16 1.89 3.78 5.49 5.95 9.36 6.26v-82.12l128-127.09V160H248c-13.2 0-24-10.8-24-24V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24v-40l-128-.11c-16.12-.31-30.58-9.28-37.83-23.75zM384 121.9c0-6.3-2.5-12.4-7-16.9L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1zm-96 225.06V416h68.99l161.68-162.78-67.88-67.88L288 346.96zm280.54-179.63l-31.87-31.87c-9.94-9.94-26.07-9.94-36.01 0l-27.25 27.25 67.88 67.88 27.25-27.25c9.95-9.94 9.95-26.07 0-36.01z\"],\n    \"file-upload\": [384, 512, [], \"f574\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm65.18 216.01H224v80c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-80H94.82c-14.28 0-21.41-17.29-11.27-27.36l96.42-95.7c6.65-6.61 17.39-6.61 24.04 0l96.42 95.7c10.15 10.07 3.03 27.36-11.25 27.36zM377 105L279.1 7c-4.5-4.5-10.6-7-17-7H256v128h128v-6.1c0-6.3-2.5-12.4-7-16.9z\"],\n    \"file-video\": [384, 512, [], \"f1c8\", \"M384 121.941V128H256V0h6.059c6.365 0 12.47 2.529 16.971 7.029l97.941 97.941A24.005 24.005 0 0 1 384 121.941zM224 136V0H24C10.745 0 0 10.745 0 24v464c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V160H248c-13.2 0-24-10.8-24-24zm96 144.016v111.963c0 21.445-25.943 31.998-40.971 16.971L224 353.941V392c0 13.255-10.745 24-24 24H88c-13.255 0-24-10.745-24-24V280c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v38.059l55.029-55.013c15.011-15.01 40.971-4.491 40.971 16.97z\"],\n    \"file-word\": [384, 512, [], \"f1c2\", \"M224 136V0H24C10.7 0 0 10.7 0 24v464c0 13.3 10.7 24 24 24h336c13.3 0 24-10.7 24-24V160H248c-13.2 0-24-10.8-24-24zm57.1 120H305c7.7 0 13.4 7.1 11.7 14.7l-38 168c-1.2 5.5-6.1 9.3-11.7 9.3h-38c-5.5 0-10.3-3.8-11.6-9.1-25.8-103.5-20.8-81.2-25.6-110.5h-.5c-1.1 14.3-2.4 17.4-25.6 110.5-1.3 5.3-6.1 9.1-11.6 9.1H117c-5.6 0-10.5-3.9-11.7-9.4l-37.8-168c-1.7-7.5 4-14.6 11.7-14.6h24.5c5.7 0 10.7 4 11.8 9.7 15.6 78 20.1 109.5 21 122.2 1.6-10.2 7.3-32.7 29.4-122.7 1.3-5.4 6.1-9.1 11.7-9.1h29.1c5.6 0 10.4 3.8 11.7 9.2 24 100.4 28.8 124 29.6 129.4-.2-11.2-2.6-17.8 21.6-129.2 1-5.6 5.9-9.5 11.5-9.5zM384 121.9v6.1H256V0h6.1c6.4 0 12.5 2.5 17 7l97.9 98c4.5 4.5 7 10.6 7 16.9z\"],\n    \"fill\": [512, 512, [], \"f575\", \"M502.63 217.06L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.77c-6.24-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.63l86.19 86.18-94.76 94.76c-37.49 37.49-37.49 98.26 0 135.75l117.19 117.19c18.75 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.88-28.12l221.57-221.57c12.49-12.5 12.49-32.76 0-45.26zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.61 58.6c12.49 12.49 32.75 12.49 45.24 0 12.49-12.49 12.49-32.75 0-45.24l-58.61-58.6 58.95-58.95 162.45 162.44-48.35 48.34z\"],\n    \"fill-drip\": [576, 512, [], \"f576\", \"M512 320s-64 92.65-64 128c0 35.35 28.66 64 64 64s64-28.65 64-64-64-128-64-128zm-9.37-102.94L294.94 9.37C288.69 3.12 280.5 0 272.31 0s-16.38 3.12-22.62 9.37l-81.58 81.58L81.93 4.76c-6.25-6.25-16.38-6.25-22.62 0L36.69 27.38c-6.24 6.25-6.24 16.38 0 22.62l86.19 86.18-94.76 94.76c-37.49 37.48-37.49 98.26 0 135.75l117.19 117.19c18.74 18.74 43.31 28.12 67.87 28.12 24.57 0 49.13-9.37 67.87-28.12l221.57-221.57c12.5-12.5 12.5-32.75.01-45.25zm-116.22 70.97H65.93c1.36-3.84 3.57-7.98 7.43-11.83l13.15-13.15 81.61-81.61 58.6 58.6c12.49 12.49 32.75 12.49 45.24 0s12.49-32.75 0-45.24l-58.6-58.6 58.95-58.95 162.44 162.44-48.34 48.34z\"],\n    \"film\": [512, 512, [], \"f008\", \"M488 64h-8v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12V64H96v20c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12V64h-8C10.7 64 0 74.7 0 88v336c0 13.3 10.7 24 24 24h8v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h320v-20c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v20h8c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24zM96 372c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12H44c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm272 208c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm0-168c0 6.6-5.4 12-12 12H156c-6.6 0-12-5.4-12-12v-96c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v96zm112 152c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-96c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"filter\": [512, 512, [], \"f0b0\", \"M487.976 0H24.028C2.71 0-8.047 25.866 7.058 40.971L192 225.941V432c0 7.831 3.821 15.17 10.237 19.662l80 55.98C298.02 518.69 320 507.493 320 487.98V225.941l184.947-184.97C520.021 25.896 509.338 0 487.976 0z\"],\n    \"fingerprint\": [512, 512, [], \"f577\", \"M256.12 245.96c-13.25 0-24 10.74-24 24 1.14 72.25-8.14 141.9-27.7 211.55-2.73 9.72 2.15 30.49 23.12 30.49 10.48 0 20.11-6.92 23.09-17.52 13.53-47.91 31.04-125.41 29.48-224.52.01-13.25-10.73-24-23.99-24zm-.86-81.73C194 164.16 151.25 211.3 152.1 265.32c.75 47.94-3.75 95.91-13.37 142.55-2.69 12.98 5.67 25.69 18.64 28.36 13.05 2.67 25.67-5.66 28.36-18.64 10.34-50.09 15.17-101.58 14.37-153.02-.41-25.95 19.92-52.49 54.45-52.34 31.31.47 57.15 25.34 57.62 55.47.77 48.05-2.81 96.33-10.61 143.55-2.17 13.06 6.69 25.42 19.76 27.58 19.97 3.33 26.81-15.1 27.58-19.77 8.28-50.03 12.06-101.21 11.27-152.11-.88-55.8-47.94-101.88-104.91-102.72zm-110.69-19.78c-10.3-8.34-25.37-6.8-33.76 3.48-25.62 31.5-39.39 71.28-38.75 112 .59 37.58-2.47 75.27-9.11 112.05-2.34 13.05 6.31 25.53 19.36 27.89 20.11 3.5 27.07-14.81 27.89-19.36 7.19-39.84 10.5-80.66 9.86-121.33-.47-29.88 9.2-57.88 28-80.97 8.35-10.28 6.79-25.39-3.49-33.76zm109.47-62.33c-15.41-.41-30.87 1.44-45.78 4.97-12.89 3.06-20.87 15.98-17.83 28.89 3.06 12.89 16 20.83 28.89 17.83 11.05-2.61 22.47-3.77 34-3.69 75.43 1.13 137.73 61.5 138.88 134.58.59 37.88-1.28 76.11-5.58 113.63-1.5 13.17 7.95 25.08 21.11 26.58 16.72 1.95 25.51-11.88 26.58-21.11a929.06 929.06 0 0 0 5.89-119.85c-1.56-98.75-85.07-180.33-186.16-181.83zm252.07 121.45c-2.86-12.92-15.51-21.2-28.61-18.27-12.94 2.86-21.12 15.66-18.26 28.61 4.71 21.41 4.91 37.41 4.7 61.6-.11 13.27 10.55 24.09 23.8 24.2h.2c13.17 0 23.89-10.61 24-23.8.18-22.18.4-44.11-5.83-72.34zm-40.12-90.72C417.29 43.46 337.6 1.29 252.81.02 183.02-.82 118.47 24.91 70.46 72.94 24.09 119.37-.9 181.04.14 246.65l-.12 21.47c-.39 13.25 10.03 24.31 23.28 24.69.23.02.48.02.72.02 12.92 0 23.59-10.3 23.97-23.3l.16-23.64c-.83-52.5 19.16-101.86 56.28-139 38.76-38.8 91.34-59.67 147.68-58.86 69.45 1.03 134.73 35.56 174.62 92.39 7.61 10.86 22.56 13.45 33.42 5.86 10.84-7.62 13.46-22.59 5.84-33.43z\"],\n    \"fire\": [384, 512, [], \"f06d\", \"M216 23.86c0-23.8-30.65-32.77-44.15-13.04C48 191.85 224 200 224 288c0 35.63-29.11 64.46-64.85 63.99-35.17-.45-63.15-29.77-63.15-64.94v-85.51c0-21.7-26.47-32.23-41.43-16.5C27.8 213.16 0 261.33 0 320c0 105.87 86.13 192 192 192s192-86.13 192-192c0-170.29-168-193-168-296.14z\"],\n    \"fire-alt\": [448, 512, [], \"f7e4\", \"M323.56 51.2c-20.8 19.3-39.58 39.59-56.22 59.97C240.08 73.62 206.28 35.53 168 0 69.74 91.17 0 209.96 0 281.6 0 408.85 100.29 512 224 512s224-103.15 224-230.4c0-53.27-51.98-163.14-124.44-230.4zm-19.47 340.65C282.43 407.01 255.72 416 226.86 416 154.71 416 96 368.26 96 290.75c0-38.61 24.31-72.63 72.79-130.75 6.93 7.98 98.83 125.34 98.83 125.34l58.63-66.88c4.14 6.85 7.91 13.55 11.27 19.97 27.35 52.19 15.81 118.97-33.43 153.42z\"],\n    \"fire-extinguisher\": [448, 512, [], \"f134\", \"M434.027 26.329l-168 28C254.693 56.218 256 67.8 256 72h-58.332C208.353 36.108 181.446 0 144 0c-39.435 0-66.368 39.676-52.228 76.203-52.039 13.051-75.381 54.213-90.049 90.884-4.923 12.307 1.063 26.274 13.37 31.197 12.317 4.926 26.279-1.075 31.196-13.37C75.058 112.99 106.964 120 168 120v27.076c-41.543 10.862-72 49.235-72 94.129V488c0 13.255 10.745 24 24 24h144c13.255 0 24-10.745 24-24V240c0-44.731-30.596-82.312-72-92.97V120h40c0 2.974-1.703 15.716 10.027 17.671l168 28C441.342 166.89 448 161.25 448 153.834V38.166c0-7.416-6.658-13.056-13.973-11.837zM144 72c-8.822 0-16-7.178-16-16s7.178-16 16-16 16 7.178 16 16-7.178 16-16 16z\"],\n    \"first-aid\": [576, 512, [], \"f479\", \"M0 80v352c0 26.5 21.5 48 48 48h48V32H48C21.5 32 0 53.5 0 80zm128 400h320V32H128v448zm64-248c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48zM528 32h-48v448h48c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"fish\": [576, 512, [], \"f578\", \"M327.1 96c-89.97 0-168.54 54.77-212.27 101.63L27.5 131.58c-12.13-9.18-30.24.6-27.14 14.66L24.54 256 .35 365.77c-3.1 14.06 15.01 23.83 27.14 14.66l87.33-66.05C158.55 361.23 237.13 416 327.1 416 464.56 416 576 288 576 256S464.56 96 327.1 96zm87.43 184c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24 13.26 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"fist-raised\": [384, 512, [], \"f6de\", \"M255.98 160V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v146.93c5.02-1.78 10.34-2.93 15.97-2.93h48.03zm128 95.99c-.01-35.34-28.66-63.99-63.99-63.99H207.85c-8.78 0-15.9 7.07-15.9 15.85v.56c0 26.27 21.3 47.59 47.57 47.59h35.26c9.68 0 13.2 3.58 13.2 8v16.2c0 4.29-3.59 7.78-7.88 8-44.52 2.28-64.16 24.71-96.05 72.55l-6.31 9.47a7.994 7.994 0 0 1-11.09 2.22l-13.31-8.88a7.994 7.994 0 0 1-2.22-11.09l6.31-9.47c15.73-23.6 30.2-43.26 47.31-58.08-17.27-5.51-31.4-18.12-38.87-34.45-6.59 3.41-13.96 5.52-21.87 5.52h-32c-12.34 0-23.49-4.81-32-12.48C71.48 251.19 60.33 256 48 256H16c-5.64 0-10.97-1.15-16-2.95v77.93c0 33.95 13.48 66.5 37.49 90.51L63.99 448v64h255.98v-63.96l35.91-35.92A96.035 96.035 0 0 0 384 344.21l-.02-88.22zm-32.01-90.09V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v112h32c11.28 0 21.94 2.31 32 5.9zM16 224h32c8.84 0 16-7.16 16-16V80c0-8.84-7.16-16-16-16H16C7.16 64 0 71.16 0 80v128c0 8.84 7.16 16 16 16zm95.99 0h32c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v160c0 8.84 7.16 16 16 16z\"],\n    \"flag\": [512, 512, [], \"f024\", \"M349.565 98.783C295.978 98.783 251.721 64 184.348 64c-24.955 0-47.309 4.384-68.045 12.013a55.947 55.947 0 0 0 3.586-23.562C118.117 24.015 94.806 1.206 66.338.048 34.345-1.254 8 24.296 8 56c0 19.026 9.497 35.825 24 45.945V488c0 13.255 10.745 24 24 24h16c13.255 0 24-10.745 24-24v-94.4c28.311-12.064 63.582-22.122 114.435-22.122 53.588 0 97.844 34.783 165.217 34.783 48.169 0 86.667-16.294 122.505-40.858C506.84 359.452 512 349.571 512 339.045v-243.1c0-23.393-24.269-38.87-45.485-29.016-34.338 15.948-76.454 31.854-116.95 31.854z\"],\n    \"flag-checkered\": [512, 512, [], \"f11e\", \"M243.2 189.9V258c26.1 5.9 49.3 15.6 73.6 22.3v-68.2c-26-5.8-49.4-15.5-73.6-22.2zm223.3-123c-34.3 15.9-76.5 31.9-117 31.9C296 98.8 251.7 64 184.3 64c-25 0-47.3 4.4-68 12 2.8-7.3 4.1-15.2 3.6-23.6C118.1 24 94.8 1.2 66.3 0 34.3-1.3 8 24.3 8 56c0 19 9.5 35.8 24 45.9V488c0 13.3 10.7 24 24 24h16c13.3 0 24-10.7 24-24v-94.4c28.3-12.1 63.6-22.1 114.4-22.1 53.6 0 97.8 34.8 165.2 34.8 48.2 0 86.7-16.3 122.5-40.9 8.7-6 13.8-15.8 13.8-26.4V95.9c.1-23.3-24.2-38.8-45.4-29zM169.6 325.5c-25.8 2.7-50 8.2-73.6 16.6v-70.5c26.2-9.3 47.5-15 73.6-17.4zM464 191c-23.6 9.8-46.3 19.5-73.6 23.9V286c24.8-3.4 51.4-11.8 73.6-26v70.5c-25.1 16.1-48.5 24.7-73.6 27.1V286c-27 3.7-47.9 1.5-73.6-5.6v67.4c-23.9-7.4-47.3-16.7-73.6-21.3V258c-19.7-4.4-40.8-6.8-73.6-3.8v-70c-22.4 3.1-44.6 10.2-73.6 20.9v-70.5c33.2-12.2 50.1-19.8 73.6-22v71.6c27-3.7 48.4-1.3 73.6 5.7v-67.4c23.7 7.4 47.2 16.7 73.6 21.3v68.4c23.7 5.3 47.6 6.9 73.6 2.7V143c27-4.8 52.3-13.6 73.6-22.5z\"],\n    \"flag-usa\": [512, 512, [], \"f74d\", \"M32 0C14.3 0 0 14.3 0 32v464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32C64 14.3 49.7 0 32 0zm267.9 303.6c-57.2-15.1-111.7-28.8-203.9 11.1V384c185.7-92.2 221.7 53.3 397.5-23.1 11.4-5 18.5-16.5 18.5-28.8v-36c-43.6 17.3-80.2 24.1-112.1 24.1-37.4-.1-68.9-8.4-100-16.6zm0-96c-57.2-15.1-111.7-28.8-203.9 11.1v61.5c94.8-37.6 154.6-22.7 212.1-7.6 57.2 15.1 111.7 28.8 203.9-11.1V200c-43.6 17.3-80.2 24.1-112.1 24.1-37.4 0-68.9-8.3-100-16.5zm9.5-125.9c51.8 15.6 97.4 29 202.6-20.1V30.8c0-25.1-26.8-38.1-49.4-26.6C291.3 91.5 305.4-62.2 96 32.4v151.9c94.8-37.5 154.6-22.7 212.1-7.6 57.2 15 111.7 28.7 203.9-11.1V96.7c-53.6 23.5-93.3 31.4-126.1 31.4s-59-7.8-85.7-15.9c-4-1.2-8.1-2.4-12.1-3.5V75.5c7.2 2 14.3 4.1 21.3 6.2zM160 128.1c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16-7.2 16-16 16zm0-55.8c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm64 47.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16zm0-55.9c-8.8 0-16-7.1-16-16 0-8.8 7.2-16 16-16s16 7.1 16 16c0 8.8-7.2 16-16 16z\"],\n    \"flask\": [448, 512, [], \"f0c3\", \"M437.2 403.5L320 215V64h8c13.3 0 24-10.7 24-24V24c0-13.3-10.7-24-24-24H120c-13.3 0-24 10.7-24 24v16c0 13.3 10.7 24 24 24h8v151L10.8 403.5C-18.5 450.6 15.3 512 70.9 512h306.2c55.7 0 89.4-61.5 60.1-108.5zM137.9 320l48.2-77.6c3.7-5.2 5.8-11.6 5.8-18.4V64h64v160c0 6.9 2.2 13.2 5.8 18.4l48.2 77.6h-172z\"],\n    \"flushed\": [496, 512, [], \"f579\", \"M344 200c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm-192 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM80 224c0-39.8 32.2-72 72-72s72 32.2 72 72-32.2 72-72 72-72-32.2-72-72zm232 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-104c-39.8 0-72-32.2-72-72s32.2-72 72-72 72 32.2 72 72-32.2 72-72 72z\"],\n    \"folder\": [512, 512, [], \"f07b\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48z\"],\n    \"folder-minus\": [512, 512, [], \"f65d\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16H160c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h192c8.84 0 16 7.16 16 16v16z\"],\n    \"folder-open\": [576, 512, [], \"f07c\", \"M572.694 292.093L500.27 416.248A63.997 63.997 0 0 1 444.989 448H45.025c-18.523 0-30.064-20.093-20.731-36.093l72.424-124.155A64 64 0 0 1 152 256h399.964c18.523 0 30.064 20.093 20.73 36.093zM152 224h328v-48c0-26.51-21.49-48-48-48H272l-64-64H48C21.49 64 0 85.49 0 112v278.046l69.077-118.418C86.214 242.25 117.989 224 152 224z\"],\n    \"folder-plus\": [512, 512, [], \"f65e\", \"M464 128H272l-64-64H48C21.49 64 0 85.49 0 112v288c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V176c0-26.51-21.49-48-48-48zm-96 168c0 8.84-7.16 16-16 16h-72v72c0 8.84-7.16 16-16 16h-16c-8.84 0-16-7.16-16-16v-72h-72c-8.84 0-16-7.16-16-16v-16c0-8.84 7.16-16 16-16h72v-72c0-8.84 7.16-16 16-16h16c8.84 0 16 7.16 16 16v72h72c8.84 0 16 7.16 16 16v16z\"],\n    \"font\": [448, 512, [], \"f031\", \"M432 416h-23.41L277.88 53.69A32 32 0 0 0 247.58 32h-47.16a32 32 0 0 0-30.3 21.69L39.41 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-19.58l23.3-64h152.56l23.3 64H304a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM176.85 272L224 142.51 271.15 272z\"],\n    \"font-awesome-logo-full\": [3992, 512, [\"Font Awesome\"], \"f4e6\", \"M454.6 0H57.4C25.9 0 0 25.9 0 57.4v397.3C0 486.1 25.9 512 57.4 512h397.3c31.4 0 57.4-25.9 57.4-57.4V57.4C512 25.9 486.1 0 454.6 0zm-58.9 324.9c0 4.8-4.1 6.9-8.9 8.9-19.2 8.1-39.7 15.7-61.5 15.7-40.5 0-68.7-44.8-163.2 2.5v51.8c0 30.3-45.7 30.2-45.7 0v-250c-9-7-15-17.9-15-30.3 0-21 17.1-38.2 38.2-38.2 21 0 38.2 17.1 38.2 38.2 0 12.2-5.8 23.2-14.9 30.2v21c37.1-12 65.5-34.4 146.1-3.4 26.6 11.4 68.7-15.7 76.5-15.7 5.5 0 10.3 4.1 10.3 8.9v160.4zm432.9-174.2h-137v70.1H825c39.8 0 40.4 62.2 0 62.2H691.6v105.6c0 45.5-70.7 46.4-70.7 0V128.3c0-22 18-39.8 39.8-39.8h167.8c39.6 0 40.5 62.2.1 62.2zm191.1 23.4c-169.3 0-169.1 252.4 0 252.4 169.9 0 169.9-252.4 0-252.4zm0 196.1c-81.6 0-82.1-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm372.4 53.4c-17.5 0-31.4-13.9-31.4-31.4v-117c0-62.4-72.6-52.5-99.1-16.4v133.4c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c43.3-51.6 162.4-60.4 162.4 39.3v141.5c.3 30.4-31.5 31.4-31.7 31.4zm179.7 2.9c-44.3 0-68.3-22.9-68.3-65.8V235.2H1488c-35.6 0-36.7-55.3 0-55.3h15.5v-37.3c0-41.3 63.8-42.1 63.8 0v37.5h24.9c35.4 0 35.7 55.3 0 55.3h-24.9v108.5c0 29.6 26.1 26.3 27.4 26.3 31.4 0 52.6 56.3-22.9 56.3zM1992 123c-19.5-50.2-95.5-50-114.5 0-107.3 275.7-99.5 252.7-99.5 262.8 0 42.8 58.3 51.2 72.1 14.4l13.5-35.9H2006l13 35.9c14.2 37.7 72.1 27.2 72.1-14.4 0-10.1 5.3 6.8-99.1-262.8zm-108.9 179.1l51.7-142.9 51.8 142.9h-103.5zm591.3-85.6l-53.7 176.3c-12.4 41.2-72 41-84 0l-42.3-135.9-42.3 135.9c-12.4 40.9-72 41.2-84.5 0l-54.2-176.3c-12.5-39.4 49.8-56.1 60.2-16.9L2213 342l45.3-139.5c10.9-32.7 59.6-34.7 71.2 0l45.3 139.5 39.3-142.4c10.3-38.3 72.6-23.8 60.3 16.9zm275.4 75.1c0-42.4-33.9-117.5-119.5-117.5-73.2 0-124.4 56.3-124.4 126 0 77.2 55.3 126.4 128.5 126.4 31.7 0 93-11.5 93-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-109 8.4-115.9-43.8h148.3c16.3 0 29.3-13.4 29.3-28.9zM2571 277.7c9.5-73.4 113.9-68.6 118.6 0H2571zm316.7 148.8c-31.4 0-81.6-10.5-96.6-31.9-12.4-17 2.5-39.8 21.8-39.8 16.3 0 36.8 22.9 77.7 22.9 27.4 0 40.4-11 40.4-25.8 0-39.8-142.9-7.4-142.9-102 0-40.4 35.3-75.7 98.6-75.7 31.4 0 74.1 9.9 87.6 29.4 10.8 14.8-1.4 36.2-20.9 36.2-15.1 0-26.7-17.3-66.2-17.3-22.9 0-37.8 10.5-37.8 23.8 0 35.9 142.4 6 142.4 103.1-.1 43.7-37.4 77.1-104.1 77.1zm266.8-252.4c-169.3 0-169.1 252.4 0 252.4 170.1 0 169.6-252.4 0-252.4zm0 196.1c-81.8 0-82-139.8 0-139.8 82.5 0 82.4 139.8 0 139.8zm476.9 22V268.7c0-53.8-61.4-45.8-85.7-10.5v134c0 41.3-63.8 42.1-63.8 0V268.7c0-52.1-59.5-47.4-85.7-10.1v133.6c0 41.5-63.3 41.8-63.3 0V208c0-40 63.1-41.6 63.1 0v3.4c9.9-14.4 41.8-37.3 78.6-37.3 35.3 0 57.7 16.4 66.7 43.8 13.9-21.8 45.8-43.8 82.6-43.8 44.3 0 70.7 23.4 70.7 72.7v145.3c.5 17.3-13.5 31.4-31.9 31.4 3.5.1-31.3 1.1-31.3-31.3zM3992 291.6c0-42.4-32.4-117.5-117.9-117.5-73.2 0-127.5 56.3-127.5 126 0 77.2 58.3 126.4 131.6 126.4 31.7 0 91.5-11.5 91.5-39.8 0-18.3-21.1-31.5-39.3-22.4-49.4 26.2-110.5 8.4-117.5-43.8h149.8c16.3 0 29.1-13.4 29.3-28.9zm-180.5-13.9c9.7-74.4 115.9-68.3 120.1 0h-120.1z\"],\n    \"football-ball\": [496, 512, [], \"f44e\", \"M481.5 60.3c-4.8-18.2-19.1-32.5-37.3-37.4C420.3 16.5 383 8.9 339.4 8L496 164.8c-.8-43.5-8.2-80.6-14.5-104.5zm-467 391.4c4.8 18.2 19.1 32.5 37.3 37.4 23.9 6.4 61.2 14 104.8 14.9L0 347.2c.8 43.5 8.2 80.6 14.5 104.5zM4.2 283.4L220.4 500c132.5-19.4 248.8-118.7 271.5-271.4L275.6 12C143.1 31.4 26.8 130.7 4.2 283.4zm317.3-123.6c3.1-3.1 8.2-3.1 11.3 0l11.3 11.3c3.1 3.1 3.1 8.2 0 11.3l-28.3 28.3 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-22.6 22.7 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L248 278.6l-22.6 22.6 28.3 28.3c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-28.3-28.3-28.3 28.3c-3.1 3.1-8.2 3.1-11.3 0l-11.3-11.3c-3.1-3.1-3.1-8.2 0-11.3l28.3-28.3-28.3-28.2c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 22.6-22.6-28.3-28.3c-3.1-3.1-3.1-8.2 0-11.3l11.3-11.3c3.1-3.1 8.2-3.1 11.3 0l28.3 28.3 28.3-28.5z\"],\n    \"forward\": [512, 512, [], \"f04e\", \"M500.5 231.4l-192-160C287.9 54.3 256 68.6 256 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2zm-256 0l-192-160C31.9 54.3 0 68.6 0 96v320c0 27.4 31.9 41.8 52.5 24.6l192-160c15.3-12.8 15.3-36.4 0-49.2z\"],\n    \"frog\": [576, 512, [], \"f52e\", \"M446.53 97.43C439.67 60.23 407.19 32 368 32c-39.23 0-71.72 28.29-78.54 65.54C126.75 112.96-.5 250.12 0 416.98.11 451.9 29.08 480 64 480h304c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-79.49l35.8-48.33c24.14-36.23 10.35-88.28-33.71-106.6-23.89-9.93-51.55-4.65-72.24 10.88l-32.76 24.59c-7.06 5.31-17.09 3.91-22.41-3.19-5.3-7.08-3.88-17.11 3.19-22.41l34.78-26.09c36.84-27.66 88.28-27.62 125.13 0 10.87 8.15 45.87 39.06 40.8 93.21L469.62 480H560c8.84 0 16-7.16 16-16 0-17.67-14.33-32-32-32h-53.63l-98.52-104.68 154.44-86.65A58.16 58.16 0 0 0 576 189.94c0-21.4-11.72-40.95-30.48-51.23-40.56-22.22-98.99-41.28-98.99-41.28zM368 136c-13.26 0-24-10.75-24-24 0-13.26 10.74-24 24-24 13.25 0 24 10.74 24 24 0 13.25-10.75 24-24 24z\"],\n    \"frown\": [496, 512, [], \"f119\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm170.2 218.2C315.8 367.4 282.9 352 248 352s-67.8 15.4-90.2 42.2c-13.5 16.3-38.1-4.2-24.6-20.5C161.7 339.6 203.6 320 248 320s86.3 19.6 114.7 53.8c13.6 16.2-11 36.7-24.5 20.4z\"],\n    \"frown-open\": [496, 512, [], \"f57a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm187.3 183.3c-31.2-9.6-59.4-15.3-75.3-15.3s-44.1 5.7-75.3 15.3c-11.5 3.5-22.5-6.3-20.5-18.1 7-40 60.1-61.2 95.8-61.2s88.8 21.3 95.8 61.2c2 11.9-9.1 21.6-20.5 18.1zM328 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"funnel-dollar\": [640, 512, [], \"f662\", \"M433.46 165.94l101.2-111.87C554.61 34.12 540.48 0 512.26 0H31.74C3.52 0-10.61 34.12 9.34 54.07L192 256v155.92c0 12.59 5.93 24.44 16 32l79.99 60c20.86 15.64 48.47 6.97 59.22-13.57C310.8 455.38 288 406.35 288 352c0-89.79 62.05-165.17 145.46-186.06zM480 192c-88.37 0-160 71.63-160 160s71.63 160 160 160 160-71.63 160-160-71.63-160-160-160zm16 239.88V448c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V256c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.04 44.44-42.67 45.07z\"],\n    \"futbol\": [512, 512, [], \"f1e3\", \"M504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zm-48 0l-.003-.282-26.064 22.741-62.679-58.5 16.454-84.355 34.303 3.072c-24.889-34.216-60.004-60.089-100.709-73.141l13.651 31.939L256 139l-74.953-41.525 13.651-31.939c-40.631 13.028-75.78 38.87-100.709 73.141l34.565-3.073 16.192 84.355-62.678 58.5-26.064-22.741-.003.282c0 43.015 13.497 83.952 38.472 117.991l7.704-33.897 85.138 10.447 36.301 77.826-29.902 17.786c40.202 13.122 84.29 13.148 124.572 0l-29.902-17.786 36.301-77.826 85.138-10.447 7.704 33.897C442.503 339.952 456 299.015 456 256zm-248.102 69.571l-29.894-91.312L256 177.732l77.996 56.527-29.622 91.312h-96.476z\"],\n    \"gamepad\": [640, 512, [], \"f11b\", \"M480 96H160C71.6 96 0 167.6 0 256s71.6 160 160 160c44.8 0 85.2-18.4 114.2-48h91.5c29 29.6 69.5 48 114.2 48 88.4 0 160-71.6 160-160S568.4 96 480 96zM256 276c0 6.6-5.4 12-12 12h-52v52c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-52H76c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h52v-52c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v52h52c6.6 0 12 5.4 12 12v40zm184 68c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-80c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"gas-pump\": [512, 512, [], \"f52f\", \"M336 448H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm157.2-340.7l-81-81c-6.2-6.2-16.4-6.2-22.6 0l-11.3 11.3c-6.2 6.2-6.2 16.4 0 22.6L416 97.9V160c0 28.1 20.9 51.3 48 55.2V376c0 13.2-10.8 24-24 24s-24-10.8-24-24v-32c0-48.6-39.4-88-88-88h-8V64c0-35.3-28.7-64-64-64H96C60.7 0 32 28.7 32 64v352h288V304h8c22.1 0 40 17.9 40 40v27.8c0 37.7 27 72 64.5 75.9 43 4.3 79.5-29.5 79.5-71.7V152.6c0-17-6.8-33.3-18.8-45.3zM256 192H96V64h160v128z\"],\n    \"gavel\": [512, 512, [], \"f0e3\", \"M504.971 199.362l-22.627-22.627c-9.373-9.373-24.569-9.373-33.941 0l-5.657 5.657L329.608 69.255l5.657-5.657c9.373-9.373 9.373-24.569 0-33.941L312.638 7.029c-9.373-9.373-24.569-9.373-33.941 0L154.246 131.48c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l5.657-5.657 39.598 39.598-81.04 81.04-5.657-5.657c-12.497-12.497-32.758-12.497-45.255 0L9.373 412.118c-12.497 12.497-12.497 32.758 0 45.255l45.255 45.255c12.497 12.497 32.758 12.497 45.255 0l114.745-114.745c12.497-12.497 12.497-32.758 0-45.255l-5.657-5.657 81.04-81.04 39.598 39.598-5.657 5.657c-9.373 9.373-9.373 24.569 0 33.941l22.627 22.627c9.373 9.373 24.569 9.373 33.941 0l124.451-124.451c9.372-9.372 9.372-24.568 0-33.941z\"],\n    \"gem\": [576, 512, [], \"f3a5\", \"M485.5 0L576 160H474.9L405.7 0h79.8zm-128 0l69.2 160H149.3L218.5 0h139zm-267 0h79.8l-69.2 160H0L90.5 0zM0 192h100.7l123 251.7c1.5 3.1-2.7 5.9-5 3.3L0 192zm148.2 0h279.6l-137 318.2c-1 2.4-4.5 2.4-5.5 0L148.2 192zm204.1 251.7l123-251.7H576L357.3 446.9c-2.3 2.7-6.5-.1-5-3.2z\"],\n    \"genderless\": [288, 512, [], \"f22d\", \"M144 176c44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80 35.9-80 80-80m0-64C64.5 112 0 176.5 0 256s64.5 144 144 144 144-64.5 144-144-64.5-144-144-144z\"],\n    \"ghost\": [384, 512, [], \"f6e2\", \"M186.1.09C81.01 3.24 0 94.92 0 200.05v263.92c0 14.26 17.23 21.39 27.31 11.31l24.92-18.53c6.66-4.95 16-3.99 21.51 2.21l42.95 48.35c6.25 6.25 16.38 6.25 22.63 0l40.72-45.85c6.37-7.17 17.56-7.17 23.92 0l40.72 45.85c6.25 6.25 16.38 6.25 22.63 0l42.95-48.35c5.51-6.2 14.85-7.17 21.51-2.21l24.92 18.53c10.08 10.08 27.31 2.94 27.31-11.31V192C384 84 294.83-3.17 186.1.09zM128 224c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm128 0c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"gift\": [512, 512, [], \"f06b\", \"M32 448c0 17.7 14.3 32 32 32h160V320H32v128zm256 32h160c17.7 0 32-14.3 32-32V320H288v160zm192-320h-42.1c6.2-12.1 10.1-25.5 10.1-40 0-48.5-39.5-88-88-88-41.6 0-68.5 21.3-103 68.3-34.5-47-61.4-68.3-103-68.3-48.5 0-88 39.5-88 88 0 14.5 3.8 27.9 10.1 40H32c-17.7 0-32 14.3-32 32v80c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-80c0-17.7-14.3-32-32-32zm-326.1 0c-22.1 0-40-17.9-40-40s17.9-40 40-40c19.9 0 34.6 3.3 86.1 80h-86.1zm206.1 0h-86.1c51.4-76.5 65.7-80 86.1-80 22.1 0 40 17.9 40 40s-17.9 40-40 40z\"],\n    \"gifts\": [640, 512, [], \"f79c\", \"M240.6 194.1c1.9-30.8 17.3-61.2 44-79.8C279.4 103.5 268.7 96 256 96h-29.4l30.7-22c7.2-5.1 8.9-15.1 3.7-22.3l-9.3-13c-5.1-7.2-15.1-8.9-22.3-3.7l-32 22.9 11.5-30.6c3.1-8.3-1.1-17.5-9.4-20.6l-15-5.6c-8.3-3.1-17.5 1.1-20.6 9.4l-19.9 53-19.9-53.1C121 2.1 111.8-2.1 103.5 1l-15 5.6C80.2 9.7 76 19 79.2 27.2l11.5 30.6L58.6 35c-7.2-5.1-17.2-3.5-22.3 3.7l-9.3 13c-5.1 7.2-3.5 17.2 3.7 22.3l30.7 22H32c-17.7 0-32 14.3-32 32v352c0 17.7 14.3 32 32 32h168.9c-5.5-9.5-8.9-20.3-8.9-32V256c0-29.9 20.8-55 48.6-61.9zM224 480c0 17.7 14.3 32 32 32h160V384H224v96zm224 32h160c17.7 0 32-14.3 32-32v-96H448v128zm160-288h-20.4c2.6-7.6 4.4-15.5 4.4-23.8 0-35.5-27-72.2-72.1-72.2-48.1 0-75.9 47.7-87.9 75.3-12.1-27.6-39.9-75.3-87.9-75.3-45.1 0-72.1 36.7-72.1 72.2 0 8.3 1.7 16.2 4.4 23.8H256c-17.7 0-32 14.3-32 32v96h192V224h15.3l.7-.2.7.2H448v128h192v-96c0-17.7-14.3-32-32-32zm-272 0c-2.7-1.4-5.1-3-7.2-4.8-7.3-6.4-8.8-13.8-8.8-19 0-9.7 6.4-24.2 24.1-24.2 18.7 0 35.6 27.4 44.5 48H336zm199.2-4.8c-2.1 1.8-4.5 3.4-7.2 4.8h-52.6c8.8-20.3 25.8-48 44.5-48 17.7 0 24.1 14.5 24.1 24.2 0 5.2-1.5 12.6-8.8 19z\"],\n    \"glass-cheers\": [640, 512, [], \"f79f\", \"M639.4 433.6c-8.4-20.4-31.8-30.1-52.2-21.6l-22.1 9.2-38.7-101.9c47.9-35 64.8-100.3 34.5-152.8L474.3 16c-8-13.9-25.1-19.7-40-13.6L320 49.8 205.7 2.4c-14.9-6.2-32-.3-40 13.6L79.1 166.5C48.9 219 65.7 284.3 113.6 319.2L74.9 421.1l-22.1-9.2c-20.4-8.5-43.7 1.2-52.2 21.6-1.7 4.1.2 8.8 4.3 10.5l162.3 67.4c4.1 1.7 8.7-.2 10.4-4.3 8.4-20.4-1.2-43.8-21.6-52.3l-22.1-9.2L173.3 342c4.4.5 8.8 1.3 13.1 1.3 51.7 0 99.4-33.1 113.4-85.3l20.2-75.4 20.2 75.4c14 52.2 61.7 85.3 113.4 85.3 4.3 0 8.7-.8 13.1-1.3L506 445.6l-22.1 9.2c-20.4 8.5-30.1 31.9-21.6 52.3 1.7 4.1 6.4 6 10.4 4.3L635.1 444c4-1.7 6-6.3 4.3-10.4zM275.9 162.1l-112.1-46.5 36.5-63.4 94.5 39.2-18.9 70.7zm88.2 0l-18.9-70.7 94.5-39.2 36.5 63.4-112.1 46.5z\"],\n    \"glass-martini\": [512, 512, [], \"f000\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6z\"],\n    \"glass-martini-alt\": [512, 512, [], \"f57b\", \"M502.05 57.6C523.3 36.34 508.25 0 478.2 0H33.8C3.75 0-11.3 36.34 9.95 57.6L224 271.64V464h-56c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h240c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40h-56V271.64L502.05 57.6zM443.77 48l-48 48H116.24l-48-48h375.53z\"],\n    \"glass-whiskey\": [512, 512, [], \"f7a0\", \"M480 32H32C12.5 32-2.4 49.2.3 68.5l56 356.5c4.5 31.5 31.5 54.9 63.4 54.9h273c31.8 0 58.9-23.4 63.4-54.9l55.6-356.5C514.4 49.2 499.5 32 480 32zm-37.4 64l-30 192h-313L69.4 96h373.2z\"],\n    \"glasses\": [576, 512, [], \"f530\", \"M574.1 280.37L528.75 98.66c-5.91-23.7-21.59-44.05-43-55.81-21.44-11.73-46.97-14.11-70.19-6.33l-15.25 5.08c-8.39 2.79-12.92 11.86-10.12 20.24l5.06 15.18c2.79 8.38 11.85 12.91 20.23 10.12l13.18-4.39c10.87-3.62 23-3.57 33.16 1.73 10.29 5.37 17.57 14.56 20.37 25.82l38.46 153.82c-22.19-6.81-49.79-12.46-81.2-12.46-34.77 0-73.98 7.02-114.85 26.74h-73.18c-40.87-19.74-80.08-26.75-114.86-26.75-31.42 0-59.02 5.65-81.21 12.46l38.46-153.83c2.79-11.25 10.09-20.45 20.38-25.81 10.16-5.3 22.28-5.35 33.15-1.73l13.17 4.39c8.38 2.79 17.44-1.74 20.23-10.12l5.06-15.18c2.8-8.38-1.73-17.45-10.12-20.24l-15.25-5.08c-23.22-7.78-48.75-5.41-70.19 6.33-21.41 11.77-37.09 32.11-43 55.8L1.9 280.37A64.218 64.218 0 0 0 0 295.86v70.25C0 429.01 51.58 480 115.2 480h37.12c60.28 0 110.37-45.94 114.88-105.37l2.93-38.63h35.75l2.93 38.63C313.31 434.06 363.4 480 423.68 480h37.12c63.62 0 115.2-50.99 115.2-113.88v-70.25c0-5.23-.64-10.43-1.9-15.5zm-370.72 89.42c-1.97 25.91-24.4 46.21-51.06 46.21H115.2C86.97 416 64 393.62 64 366.11v-37.54c18.12-6.49 43.42-12.92 72.58-12.92 23.86 0 47.26 4.33 69.93 12.92l-3.13 41.22zM512 366.12c0 27.51-22.97 49.88-51.2 49.88h-37.12c-26.67 0-49.1-20.3-51.06-46.21l-3.13-41.22c22.67-8.59 46.08-12.92 69.95-12.92 29.12 0 54.43 6.44 72.55 12.93v37.54z\"],\n    \"globe\": [496, 512, [], \"f0ac\", \"M336.5 160C322 70.7 287.8 8 248 8s-74 62.7-88.5 152h177zM152 256c0 22.2 1.2 43.5 3.3 64h185.3c2.1-20.5 3.3-41.8 3.3-64s-1.2-43.5-3.3-64H155.3c-2.1 20.5-3.3 41.8-3.3 64zm324.7-96c-28.6-67.9-86.5-120.4-158-141.6 24.4 33.8 41.2 84.7 50 141.6h108zM177.2 18.4C105.8 39.6 47.8 92.1 19.3 160h108c8.7-56.9 25.5-107.8 49.9-141.6zM487.4 192H372.7c2.1 21 3.3 42.5 3.3 64s-1.2 43-3.3 64h114.6c5.5-20.5 8.6-41.8 8.6-64s-3.1-43.5-8.5-64zM120 256c0-21.5 1.2-43 3.3-64H8.6C3.2 212.5 0 233.8 0 256s3.2 43.5 8.6 64h114.6c-2-21-3.2-42.5-3.2-64zm39.5 96c14.5 89.3 48.7 152 88.5 152s74-62.7 88.5-152h-177zm159.3 141.6c71.4-21.2 129.4-73.7 158-141.6h-108c-8.8 56.9-25.6 107.8-50 141.6zM19.3 352c28.6 67.9 86.5 120.4 158 141.6-24.4-33.8-41.2-84.7-50-141.6h-108z\"],\n    \"globe-africa\": [496, 512, [], \"f57c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm160 215.5v6.93c0 5.87-3.32 11.24-8.57 13.86l-15.39 7.7a15.485 15.485 0 0 1-15.53-.97l-18.21-12.14a15.52 15.52 0 0 0-13.5-1.81l-2.65.88c-9.7 3.23-13.66 14.79-7.99 23.3l13.24 19.86c2.87 4.31 7.71 6.9 12.89 6.9h8.21c8.56 0 15.5 6.94 15.5 15.5v11.34c0 3.35-1.09 6.62-3.1 9.3l-18.74 24.98c-1.42 1.9-2.39 4.1-2.83 6.43l-4.3 22.83c-.62 3.29-2.29 6.29-4.76 8.56a159.608 159.608 0 0 0-25 29.16l-13.03 19.55a27.756 27.756 0 0 1-23.09 12.36c-10.51 0-20.12-5.94-24.82-15.34a78.902 78.902 0 0 1-8.33-35.29V367.5c0-8.56-6.94-15.5-15.5-15.5h-25.88c-14.49 0-28.38-5.76-38.63-16a54.659 54.659 0 0 1-16-38.63v-14.06c0-17.19 8.1-33.38 21.85-43.7l27.58-20.69a54.663 54.663 0 0 1 32.78-10.93h.89c8.48 0 16.85 1.97 24.43 5.77l14.72 7.36c3.68 1.84 7.93 2.14 11.83.84l47.31-15.77c6.33-2.11 10.6-8.03 10.6-14.7 0-8.56-6.94-15.5-15.5-15.5h-10.09c-4.11 0-8.05-1.63-10.96-4.54l-6.92-6.92a15.493 15.493 0 0 0-10.96-4.54H199.5c-8.56 0-15.5-6.94-15.5-15.5v-4.4c0-7.11 4.84-13.31 11.74-15.04l14.45-3.61c3.74-.94 7-3.23 9.14-6.44l8.08-12.11c2.87-4.31 7.71-6.9 12.89-6.9h24.21c8.56 0 15.5-6.94 15.5-15.5v-21.7C359.23 71.63 422.86 131.02 441.93 208H423.5c-8.56 0-15.5 6.94-15.5 15.5z\"],\n    \"globe-americas\": [496, 512, [], \"f57d\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm82.29 357.6c-3.9 3.88-7.99 7.95-11.31 11.28-2.99 3-5.1 6.7-6.17 10.71-1.51 5.66-2.73 11.38-4.77 16.87l-17.39 46.85c-13.76 3-28 4.69-42.65 4.69v-27.38c1.69-12.62-7.64-36.26-22.63-51.25-6-6-9.37-14.14-9.37-22.63v-32.01c0-11.64-6.27-22.34-16.46-27.97-14.37-7.95-34.81-19.06-48.81-26.11-11.48-5.78-22.1-13.14-31.65-21.75l-.8-.72a114.792 114.792 0 0 1-18.06-20.74c-9.38-13.77-24.66-36.42-34.59-51.14 20.47-45.5 57.36-82.04 103.2-101.89l24.01 12.01C203.48 89.74 216 82.01 216 70.11v-11.3c7.99-1.29 16.12-2.11 24.39-2.42l28.3 28.3c6.25 6.25 6.25 16.38 0 22.63L264 112l-10.34 10.34c-3.12 3.12-3.12 8.19 0 11.31l4.69 4.69c3.12 3.12 3.12 8.19 0 11.31l-8 8a8.008 8.008 0 0 1-5.66 2.34h-8.99c-2.08 0-4.08.81-5.58 2.27l-9.92 9.65a8.008 8.008 0 0 0-1.58 9.31l15.59 31.19c2.66 5.32-1.21 11.58-7.15 11.58h-5.64c-1.93 0-3.79-.7-5.24-1.96l-9.28-8.06a16.017 16.017 0 0 0-15.55-3.1l-31.17 10.39a11.95 11.95 0 0 0-8.17 11.34c0 4.53 2.56 8.66 6.61 10.69l11.08 5.54c9.41 4.71 19.79 7.16 30.31 7.16s22.59 27.29 32 32h66.75c8.49 0 16.62 3.37 22.63 9.37l13.69 13.69a30.503 30.503 0 0 1 8.93 21.57 46.536 46.536 0 0 1-13.72 32.98zM417 274.25c-5.79-1.45-10.84-5-14.15-9.97l-17.98-26.97a23.97 23.97 0 0 1 0-26.62l19.59-29.38c2.32-3.47 5.5-6.29 9.24-8.15l12.98-6.49C440.2 193.59 448 223.87 448 256c0 8.67-.74 17.16-1.82 25.54L417 274.25z\"],\n    \"globe-asia\": [496, 512, [], \"f57e\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm-11.34 240.23c-2.89 4.82-8.1 7.77-13.72 7.77h-.31c-4.24 0-8.31 1.69-11.31 4.69l-5.66 5.66c-3.12 3.12-3.12 8.19 0 11.31l5.66 5.66c3 3 4.69 7.07 4.69 11.31V304c0 8.84-7.16 16-16 16h-6.11c-6.06 0-11.6-3.42-14.31-8.85l-22.62-45.23c-2.44-4.88-8.95-5.94-12.81-2.08l-19.47 19.46c-3 3-7.07 4.69-11.31 4.69H50.81C49.12 277.55 48 266.92 48 256c0-110.28 89.72-200 200-200 21.51 0 42.2 3.51 61.63 9.82l-50.16 38.53c-5.11 3.41-4.63 11.06.86 13.81l10.83 5.41c5.42 2.71 8.84 8.25 8.84 14.31V216c0 4.42-3.58 8-8 8h-3.06c-3.03 0-5.8-1.71-7.15-4.42-1.56-3.12-5.96-3.29-7.76-.3l-17.37 28.95zM408 358.43c0 4.24-1.69 8.31-4.69 11.31l-9.57 9.57c-3 3-7.07 4.69-11.31 4.69h-15.16c-4.24 0-8.31-1.69-11.31-4.69l-13.01-13.01a26.767 26.767 0 0 0-25.42-7.04l-21.27 5.32c-1.27.32-2.57.48-3.88.48h-10.34c-4.24 0-8.31-1.69-11.31-4.69l-11.91-11.91a8.008 8.008 0 0 1-2.34-5.66v-10.2c0-3.27 1.99-6.21 5.03-7.43l39.34-15.74c1.98-.79 3.86-1.82 5.59-3.05l23.71-16.89a7.978 7.978 0 0 1 4.64-1.48h12.09c3.23 0 6.15 1.94 7.39 4.93l5.35 12.85a4 4 0 0 0 3.69 2.46h3.8c1.78 0 3.35-1.18 3.84-2.88l4.2-14.47c.5-1.71 2.06-2.88 3.84-2.88h6.06c2.21 0 4 1.79 4 4v12.93c0 2.12.84 4.16 2.34 5.66l11.91 11.91c3 3 4.69 7.07 4.69 11.31v24.6z\"],\n    \"globe-europe\": [496, 512, [], \"f7a2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm200 248c0 22.5-3.9 44.2-10.8 64.4h-20.3c-4.3 0-8.4-1.7-11.4-4.8l-32-32.6c-4.5-4.6-4.5-12.1.1-16.7l12.5-12.5v-8.7c0-3-1.2-5.9-3.3-8l-9.4-9.4c-2.1-2.1-5-3.3-8-3.3h-16c-6.2 0-11.3-5.1-11.3-11.3 0-3 1.2-5.9 3.3-8l9.4-9.4c2.1-2.1 5-3.3 8-3.3h32c6.2 0 11.3-5.1 11.3-11.3v-9.4c0-6.2-5.1-11.3-11.3-11.3h-36.7c-8.8 0-16 7.2-16 16v4.5c0 6.9-4.4 13-10.9 15.2l-31.6 10.5c-3.3 1.1-5.5 4.1-5.5 7.6v2.2c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8s-3.6-8-8-8H247c-3 0-5.8 1.7-7.2 4.4l-9.4 18.7c-2.7 5.4-8.2 8.8-14.3 8.8H194c-8.8 0-16-7.2-16-16V199c0-4.2 1.7-8.3 4.7-11.3l20.1-20.1c4.6-4.6 7.2-10.9 7.2-17.5 0-3.4 2.2-6.5 5.5-7.6l40-13.3c1.7-.6 3.2-1.5 4.4-2.7l26.8-26.8c2.1-2.1 3.3-5 3.3-8 0-6.2-5.1-11.3-11.3-11.3H258l-16 16v8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-20c0-2.5 1.2-4.9 3.2-6.4l28.9-21.7c1.9-.1 3.8-.3 5.7-.3C358.3 56 448 145.7 448 256zM130.1 149.1c0-3 1.2-5.9 3.3-8l25.4-25.4c2.1-2.1 5-3.3 8-3.3 6.2 0 11.3 5.1 11.3 11.3v16c0 3-1.2 5.9-3.3 8l-9.4 9.4c-2.1 2.1-5 3.3-8 3.3h-16c-6.2 0-11.3-5.1-11.3-11.3zm128 306.4v-7.1c0-8.8-7.2-16-16-16h-20.2c-10.8 0-26.7-5.3-35.4-11.8l-22.2-16.7c-11.5-8.6-18.2-22.1-18.2-36.4v-23.9c0-16 8.4-30.8 22.1-39l42.9-25.7c7.1-4.2 15.2-6.5 23.4-6.5h31.2c10.9 0 21.4 3.9 29.6 10.9l43.2 37.1h18.3c8.5 0 16.6 3.4 22.6 9.4l17.3 17.3c3.4 3.4 8.1 5.3 12.9 5.3H423c-32.4 58.9-93.8 99.5-164.9 103.1z\"],\n    \"golf-ball\": [416, 512, [], \"f450\", \"M96 416h224c0 17.7-14.3 32-32 32h-16c-17.7 0-32 14.3-32 32v20c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-20c0-17.7-14.3-32-32-32h-16c-17.7 0-32-14.3-32-32zm320-208c0 74.2-39 139.2-97.5 176h-221C39 347.2 0 282.2 0 208 0 93.1 93.1 0 208 0s208 93.1 208 208zm-180.1 43.9c18.3 0 33.1-14.8 33.1-33.1 0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1zm49.1 46.9c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1zm64-64c0-14.4-9.3-26.3-22.1-30.9 9.6 26.8-15.6 51.3-41.9 41.9 4.6 12.8 16.5 22.1 30.9 22.1 18.3 0 33.1-14.9 33.1-33.1z\"],\n    \"gopuram\": [512, 512, [], \"f664\", \"M496 352h-16V240c0-8.8-7.2-16-16-16h-16v-80c0-8.8-7.2-16-16-16h-16V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16s-16 7.2-16 16v16h-64V16c0-8.8-7.2-16-16-16S96 7.2 96 16v112H80c-8.8 0-16 7.2-16 16v80H48c-8.8 0-16 7.2-16 16v112H16c-8.8 0-16 7.2-16 16v128c0 8.8 7.2 16 16 16h80V352h32V224h32v-96h32v96h-32v128h-32v160h80v-80c0-8.8 7.2-16 16-16h64c8.8 0 16 7.2 16 16v80h80V352h-32V224h-32v-96h32v96h32v128h32v160h80c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zM232 176c0-8.8 7.2-16 16-16h16c8.8 0 16 7.2 16 16v48h-48zm56 176h-64v-64c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16z\"],\n    \"graduation-cap\": [640, 512, [], \"f19d\", \"M622.34 153.2L343.4 67.5c-15.2-4.67-31.6-4.67-46.79 0L17.66 153.2c-23.54 7.23-23.54 38.36 0 45.59l48.63 14.94c-10.67 13.19-17.23 29.28-17.88 46.9C38.78 266.15 32 276.11 32 288c0 10.78 5.68 19.85 13.86 25.65L20.33 428.53C18.11 438.52 25.71 448 35.94 448h56.11c10.24 0 17.84-9.48 15.62-19.47L82.14 313.65C90.32 307.85 96 298.78 96 288c0-11.57-6.47-21.25-15.66-26.87.76-15.02 8.44-28.3 20.69-36.72L296.6 284.5c9.06 2.78 26.44 6.25 46.79 0l278.95-85.7c23.55-7.24 23.55-38.36 0-45.6zM352.79 315.09c-28.53 8.76-52.84 3.92-65.59 0l-145.02-44.55L128 384c0 35.35 85.96 64 192 64s192-28.65 192-64l-14.18-113.47-145.03 44.56z\"],\n    \"greater-than\": [384, 512, [], \"f531\", \"M365.52 209.85L59.22 67.01c-16.06-7.49-35.15-.54-42.64 15.52L3.01 111.61c-7.49 16.06-.54 35.15 15.52 42.64L236.96 256.1 18.49 357.99C2.47 365.46-4.46 384.5 3.01 400.52l13.52 29C24 445.54 43.04 452.47 59.06 445l306.47-142.91a32.003 32.003 0 0 0 18.48-29v-34.23c-.01-12.45-7.21-23.76-18.49-29.01z\"],\n    \"greater-than-equal\": [448, 512, [], \"f532\", \"M55.22 107.69l175.56 68.09-175.44 68.05c-18.39 6.03-27.88 24.39-21.2 41l12.09 30.08c6.68 16.61 26.99 25.19 45.38 19.15L393.02 214.2c13.77-4.52 22.98-16.61 22.98-30.17v-15.96c0-13.56-9.21-25.65-22.98-30.17L91.3 17.92c-18.29-6-38.51 2.53-45.15 19.06L34.12 66.9c-6.64 16.53 2.81 34.79 21.1 40.79zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"grimace\": [496, 512, [], \"f57f\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM144 400h-8c-17.7 0-32-14.3-32-32v-8h40v40zm0-56h-40v-8c0-17.7 14.3-32 32-32h8v40zm-8-136c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm72 192h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm64 56h-48v-40h48v40zm0-56h-48v-40h48v40zm-8-104c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm64 128c0 17.7-14.3 32-32 32h-8v-40h40v8zm0-24h-40v-40h8c17.7 0 32 14.3 32 32v8z\"],\n    \"grin\": [496, 512, [], \"f580\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm80 256c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-alt\": [496, 512, [], \"f581\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm63.7 128.7c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zm-160 0c7.6-11.4 24.7-11.7 32.7 0 12.4 18.4 15.1 36.9 15.7 55.3-.5 18.4-3.3 36.9-15.7 55.3-7.6 11.4-24.7 11.7-32.7 0-12.4-18.4-15.1-36.9-15.7-55.3.5-18.4 3.3-36.9 15.7-55.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam\": [496, 512, [], \"f582\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 144c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-beam-sweat\": [504, 512, [], \"f583\", \"M456 128c26.5 0 48-21 48-47 0-20-28.5-60.4-41.6-77.8-3.2-4.3-9.6-4.3-12.8 0C436.5 20.6 408 61 408 81c0 26 21.5 47 48 47zm0 32c-44.1 0-80-35.4-80-79 0-4.4.3-14.2 8.1-32.2C345 23.1 298.3 8 248 8 111 8 0 119 0 256s111 248 248 248 248-111 248-248c0-35.1-7.4-68.4-20.5-98.6-6.3 1.5-12.7 2.6-19.5 2.6zm-128-8c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-hearts\": [496, 512, [], \"f584\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM90.4 183.6c6.7-17.6 26.7-26.7 44.9-21.9l7.1 1.9 2-7.1c5-18.1 22.8-30.9 41.5-27.9 21.4 3.4 34.4 24.2 28.8 44.5L195.3 243c-1.2 4.5-5.9 7.2-10.5 6l-70.2-18.2c-20.4-5.4-31.9-27-24.2-47.2zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm133.4-201.3l-70.2 18.2c-4.5 1.2-9.2-1.5-10.5-6L281.3 173c-5.6-20.3 7.4-41.1 28.8-44.5 18.6-3 36.4 9.8 41.5 27.9l2 7.1 7.1-1.9c18.2-4.7 38.2 4.3 44.9 21.9 7.7 20.3-3.8 41.9-24.2 47.2z\"],\n    \"grin-squint\": [496, 512, [], \"f585\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.9 9.4-21.6 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.2 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-squint-tears\": [512, 512, [], \"f586\", \"M409.6 111.9c22.6-3.2 73.5-12 88.3-26.8 19.2-19.2 18.9-50.6-.7-70.2S446-5 426.9 14.2c-14.8 14.8-23.5 65.7-26.8 88.3-.8 5.5 3.9 10.2 9.5 9.4zM102.4 400.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm311.7-256.5c-33 3.9-48.6-25.1-45.7-45.7 3.4-24 7.4-42.1 11.5-56.5C285.1-13.4 161.8-.5 80.6 80.6-.5 161.7-13.4 285 41.4 379.9c14.4-4.1 32.4-8 56.5-11.5 33.2-3.9 48.6 25.2 45.7 45.7-3.4 24-7.4 42.1-11.5 56.5 94.8 54.8 218.1 41.9 299.3-39.2s94-204.4 39.2-299.3c-14.4 4.1-32.5 8-56.5 11.5zM255.7 106c3.3-13.2 22.4-11.5 23.6 1.8l4.8 52.3 52.3 4.8c13.4 1.2 14.9 20.3 1.8 23.6l-90.5 22.6c-8.9 2.2-16.7-5.9-14.5-14.5l22.5-90.6zm-90.9 230.3L160 284l-52.3-4.8c-13.4-1.2-14.9-20.3-1.8-23.6l90.5-22.6c8.8-2.2 16.7 5.8 14.5 14.5L188.3 338c-3.1 13.2-22.2 11.7-23.5-1.7zm215.7 44.2c-29.3 29.3-75.7 50.4-116.7 50.4-18.9 0-36.6-4.5-51-14.7-9.8-6.9-8.7-21.8 2-27.2 28.3-14.6 63.9-42.4 97.8-76.3s61.7-69.6 76.3-97.8c5.4-10.5 20.2-11.9 27.3-2 32.3 45.3 7.1 124.7-35.7 167.6z\"],\n    \"grin-stars\": [496, 512, [], \"f587\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM94.6 168.9l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.2 1 8.9 8.6 4.3 13.2l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L152 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.6-4.7-1.9-12.3 4.3-13.3zM248 432c-60.6 0-134.5-38.3-143.8-93.3-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3zm157.7-249.9l-25.4 24.6 6 34.9c1 6.2-5.3 11-11 7.9L344 233.3l-31.3 16.3c-5.7 3.1-12-1.7-11-7.9l6-34.9-25.4-24.6c-4.5-4.6-1.9-12.2 4.3-13.2l34.9-5 15.5-31.6c2.9-5.8 11-5.8 13.9 0l15.5 31.6 34.9 5c6.3.9 9 8.5 4.4 13.1z\"],\n    \"grin-tears\": [640, 512, [], \"f588\", \"M102.4 256.1c-22.6 3.2-73.5 12-88.3 26.8-19.1 19.1-18.8 50.6.8 70.2s51 19.9 70.2.7c14.8-14.8 23.5-65.7 26.8-88.3.8-5.5-3.9-10.2-9.5-9.4zm523.4 26.8c-14.8-14.8-65.7-23.5-88.3-26.8-5.5-.8-10.3 3.9-9.5 9.5 3.2 22.6 12 73.5 26.8 88.3 19.2 19.2 50.6 18.9 70.2-.7s20-51.2.8-70.3zm-129.4-12.8c-3.8-26.6 19.1-49.5 45.7-45.7 8.9 1.3 16.8 2.7 24.3 4.1C552.7 104.5 447.7 8 320 8S87.3 104.5 73.6 228.5c7.5-1.4 15.4-2.8 24.3-4.1 33.2-3.9 48.6 25.3 45.7 45.7-11.8 82.3-29.9 100.4-35.8 106.4-.9.9-2 1.6-3 2.5 42.7 74.6 123 125 215.2 125s172.5-50.4 215.2-125.1c-1-.9-2.1-1.5-3-2.5-5.9-5.9-24-24-35.8-106.3zM400 152c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm-160 0c23.8 0 52.7 29.3 56 71.4.7 8.6-10.8 12-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.1-42.1 32-71.4 55.8-71.4zm80 280c-60.6 0-134.5-38.3-143.8-93.3-2-11.7 9.2-21.6 20.7-17.9C227.1 330.5 272 336 320 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-9.3 55-83.2 93.3-143.8 93.3z\"],\n    \"grin-tongue\": [496, 512, [], \"f589\", \"M248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.6 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-34.9 134.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-tongue-squint\": [496, 512, [], \"f58a\", \"M293.1 374.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.2-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.4-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-33.8 210.3l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.7 4.7 7.7 15.9 0 20.6zm163 30c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.8-4.7-7.8-15.9 0-20.6l80-48c11.7-6.9 23.9 7.7 15.4 18L343.6 208l33.6 40.3z\"],\n    \"grin-tongue-wink\": [496, 512, [], \"f58b\", \"M344 184c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zM248 8C111 8 0 119 0 256c0 106.3 67 196.7 161 232-5.6-12.2-9-25.7-9-40v-45.5c-24.7-16.2-43.5-38.1-47.8-63.8-2-11.8 9.3-21.5 20.7-17.9C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.5-3.7 22.6 6.1 20.7 17.9-4.3 25.7-23.1 47.6-47.8 63.8V448c0 14.3-3.4 27.8-9 40 94-35.3 161-125.7 161-232C496 119 385 8 248 8zm-56 225l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L112 233c-8.5 7.4-21.6.3-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c1.6 11.1-11.6 18.2-20 10.8zm152 39c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm-50.9 102.6c-14.4-6.5-31.1 2.2-34.6 17.6l-1.8 7.8c-2.1 9.2-15.2 9.2-17.3 0l-1.8-7.8c-3.5-15.4-20.2-24.1-34.6-17.6-.9.4.3-.2-18.9 9.4v63c0 35.2 28 64.5 63.1 64.9 35.7.5 64.9-28.4 64.9-64v-64c-19.5-9.6-18.2-8.9-19-9.3z\"],\n    \"grin-wink\": [496, 512, [], \"f58c\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm168 25l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.6 11-11.5 18.2-20 10.8zm-243.1 87.8C155.1 330.5 200 336 248 336s92.9-5.5 123.1-15.2c11.3-3.7 22.6 6 20.7 17.9-9.2 55-83.2 93.3-143.8 93.3s-134.5-38.3-143.8-93.3c-2-11.9 9.3-21.6 20.7-17.9z\"],\n    \"grip-horizontal\": [448, 512, [], \"f58d\", \"M96 288H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM96 96H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm160 0h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"grip-lines\": [512, 512, [], \"f7a4\", \"M496 288H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-128H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h480c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16z\"],\n    \"grip-lines-vertical\": [256, 512, [], \"f7a5\", \"M96 496V16c0-8.8-7.2-16-16-16H48c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16zm128 0V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16z\"],\n    \"grip-vertical\": [320, 512, [], \"f58e\", \"M96 32H32C14.33 32 0 46.33 0 64v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160H32c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zM288 32h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32zm0 160h-64c-17.67 0-32 14.33-32 32v64c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-64c0-17.67-14.33-32-32-32z\"],\n    \"guitar\": [512, 512, [], \"f7a6\", \"M502.6 54.6L457.4 9.4c-12.5-12.5-32.8-12.5-45.3 0l-67.9 67.9c-12.5 12.5-12.5 32.8 0 45.3L290 176.7c-45.4-29-100.4-28.9-133.5 4.2-9.7 9.7-16.4 21.2-20.5 33.9-6.1 18.8-23.5 33.1-42.7 34.9-24 2.3-46.3 11.6-63.4 28.8C-16.3 324.6-8 407.6 48.2 463.8c56.2 56.2 139.2 64.4 185.3 18.3 17.2-17.1 26.5-39.4 28.8-63.5 1.8-19.1 16.1-36.6 34.9-42.7 12.7-4.1 24.2-10.8 33.9-20.5 33.1-33.1 33.1-88.1 4.2-133.5l54.2-54.2c12.5 12.5 32.8 12.5 45.3 0l67.9-67.9c12.4-12.4 12.4-32.7-.1-45.2zM208 352c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"h-square\": [448, 512, [], \"f0fd\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zm-112 48h-32c-8.837 0-16 7.163-16 16v80H160v-80c0-8.837-7.163-16-16-16h-32c-8.837 0-16 7.163-16 16v224c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16v-80h128v80c0 8.837 7.163 16 16 16h32c8.837 0 16-7.163 16-16V144c0-8.837-7.163-16-16-16z\"],\n    \"hamburger\": [512, 512, [], \"f805\", \"M464 256H48a48 48 0 0 0 0 96h416a48 48 0 0 0 0-96zm16 128H32a16 16 0 0 0-16 16v16a64 64 0 0 0 64 64h352a64 64 0 0 0 64-64v-16a16 16 0 0 0-16-16zM58.64 224h394.72c34.57 0 54.62-43.9 34.82-75.88C448 83.2 359.55 32.1 256 32c-103.54.1-192 51.2-232.18 116.11C4 180.09 24.07 224 58.64 224zM384 112a16 16 0 1 1-16 16 16 16 0 0 1 16-16zM256 80a16 16 0 1 1-16 16 16 16 0 0 1 16-16zm-128 32a16 16 0 1 1-16 16 16 16 0 0 1 16-16z\"],\n    \"hammer\": [576, 512, [], \"f6e3\", \"M571.31 193.94l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31-28.9-28.9c5.63-21.31.36-44.9-16.35-61.61l-45.25-45.25c-62.48-62.48-163.79-62.48-226.28 0l90.51 45.25v18.75c0 16.97 6.74 33.25 18.75 45.25l49.14 49.14c16.71 16.71 40.3 21.98 61.61 16.35l28.9 28.9-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l90.51-90.51c6.23-6.24 6.23-16.37-.02-22.62zm-286.72-15.2c-3.7-3.7-6.84-7.79-9.85-11.95L19.64 404.96c-25.57 23.88-26.26 64.19-1.53 88.93s65.05 24.05 88.93-1.53l238.13-255.07c-3.96-2.91-7.9-5.87-11.44-9.41l-49.14-49.14z\"],\n    \"hamsa\": [512, 512, [], \"f665\", \"M509.34 307.25C504.28 295.56 492.75 288 480 288h-64V80c0-22-18-40-40-40s-40 18-40 40v134c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V40c0-22-18-40-40-40s-40 18-40 40v174c0 5.52-4.48 10-10 10h-20c-5.52 0-10-4.48-10-10V80c0-22-18-40-40-40S96 58 96 80v208H32c-12.75 0-24.28 7.56-29.34 19.25a31.966 31.966 0 0 0 5.94 34.58l102.69 110.03C146.97 490.08 199.69 512 256 512s109.03-21.92 144.72-60.14L503.4 341.83a31.966 31.966 0 0 0 5.94-34.58zM256 416c-53.02 0-96-64-96-64s42.98-64 96-64 96 64 96 64-42.98 64-96 64zm0-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"hand-holding\": [576, 512, [], \"f4bd\", \"M565.3 328.1c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-heart\": [576, 512, [], \"f4be\", \"M275.3 250.5c7 7.4 18.4 7.4 25.5 0l108.9-114.2c31.6-33.2 29.8-88.2-5.6-118.8-30.8-26.7-76.7-21.9-104.9 7.7L288 36.9l-11.1-11.6C248.7-4.4 202.8-9.2 172 17.5c-35.3 30.6-37.2 85.6-5.6 118.8l108.9 114.2zm290 77.6c-11.8-10.7-30.2-10-42.6 0L430.3 402c-11.3 9.1-25.4 14-40 14H272c-8.8 0-16-7.2-16-16s7.2-16 16-16h78.3c15.9 0 30.7-10.9 33.3-26.6 3.3-20-12.1-37.4-31.6-37.4H192c-27 0-53.1 9.3-74.1 26.3L71.4 384H16c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16h356.8c14.5 0 28.6-4.9 40-14L564 377c15.2-12.1 16.4-35.3 1.3-48.9z\"],\n    \"hand-holding-usd\": [544, 512, [], \"f4c0\", \"M257.6 144.3l50 14.3c3.6 1 6.1 4.4 6.1 8.1 0 4.6-3.8 8.4-8.4 8.4h-32.8c-3.6 0-7.1-.8-10.3-2.2-4.8-2.2-10.4-1.7-14.1 2l-17.5 17.5c-5.3 5.3-4.7 14.3 1.5 18.4 9.5 6.3 20.3 10.1 31.8 11.5V240c0 8.8 7.2 16 16 16h16c8.8 0 16-7.2 16-16v-17.6c30.3-3.6 53.3-31 49.3-63-2.9-23-20.7-41.3-42.9-47.7l-50-14.3c-3.6-1-6.1-4.4-6.1-8.1 0-4.6 3.8-8.4 8.4-8.4h32.8c3.6 0 7.1.8 10.3 2.2 4.8 2.2 10.4 1.7 14.1-2l17.5-17.5c5.3-5.3 4.7-14.3-1.5-18.4-9.5-6.3-20.3-10.1-31.8-11.5V16c0-8.8-7.2-16-16-16h-16c-8.8 0-16 7.2-16 16v17.6c-30.3 3.6-53.3 31-49.3 63 2.9 23 20.7 41.3 42.9 47.7zm276.3 183.8c-11.2-10.7-28.5-10-40.3 0L406.4 402c-10.7 9.1-24 14-37.8 14H256.9c-8.3 0-15.1-7.2-15.1-16s6.8-16 15.1-16h73.9c15.1 0 29-10.9 31.4-26.6 3.1-20-11.5-37.4-29.8-37.4H181.3c-25.5 0-50.2 9.3-69.9 26.3L67.5 384H15.1C6.8 384 0 391.2 0 400v96c0 8.8 6.8 16 15.1 16H352c13.7 0 27-4.9 37.8-14l142.8-121c14.4-12.1 15.5-35.3 1.3-48.9z\"],\n    \"hand-lizard\": [576, 512, [], \"f258\", \"M384 480h192V363.778a95.998 95.998 0 0 0-14.833-51.263L398.127 54.368A48 48 0 0 0 357.544 32H24C10.745 32 0 42.745 0 56v16c0 30.928 25.072 56 56 56h229.981c12.844 0 21.556 13.067 16.615 24.923l-21.41 51.385A32 32 0 0 1 251.648 224H128c-35.346 0-64 28.654-64 64v8c0 13.255 10.745 24 24 24h147.406a47.995 47.995 0 0 1 25.692 7.455l111.748 70.811A24.001 24.001 0 0 1 384 418.539V480z\"],\n    \"hand-middle-finger\": [512, 512, [], \"f806\", \"M479.93 317.12a37.33 37.33 0 0 0-28.28-36.19L416 272v-49.59c0-11.44-9.69-21.29-23.15-23.54l-38.4-6.4C336.63 189.5 320 200.86 320 216v32a8 8 0 0 1-16 0V50c0-26.28-20.25-49.2-46.52-50A48 48 0 0 0 208 48v200a8 8 0 0 1-16 0v-32c0-15.15-16.63-26.51-34.45-23.54l-30.68 5.12c-18 3-30.87 16.12-30.87 31.38V376a8 8 0 0 1-16 0v-76l-27.36 15A37.34 37.34 0 0 0 32 348.4v73.47a37.31 37.31 0 0 0 10.93 26.39l30.93 30.93A112 112 0 0 0 153.05 512h215A112 112 0 0 0 480 400z\"],\n    \"hand-paper\": [448, 512, [], \"f256\", \"M408.781 128.007C386.356 127.578 368 146.36 368 168.79V256h-8V79.79c0-22.43-18.356-41.212-40.781-40.783C297.488 39.423 280 57.169 280 79v177h-8V40.79C272 18.36 253.644-.422 231.219.007 209.488.423 192 18.169 192 40v216h-8V80.79c0-22.43-18.356-41.212-40.781-40.783C121.488 40.423 104 58.169 104 80v235.992l-31.648-43.519c-12.993-17.866-38.009-21.817-55.877-8.823-17.865 12.994-21.815 38.01-8.822 55.877l125.601 172.705A48 48 0 0 0 172.073 512h197.59c22.274 0 41.622-15.324 46.724-37.006l26.508-112.66a192.011 192.011 0 0 0 5.104-43.975V168c.001-21.831-17.487-39.577-39.218-39.993z\"],\n    \"hand-peace\": [448, 512, [], \"f25b\", \"M408 216c-22.092 0-40 17.909-40 40h-8v-32c0-22.091-17.908-40-40-40s-40 17.909-40 40v32h-8V48c0-26.51-21.49-48-48-48s-48 21.49-48 48v208h-13.572L92.688 78.449C82.994 53.774 55.134 41.63 30.461 51.324 5.787 61.017-6.356 88.877 3.337 113.551l74.765 190.342-31.09 24.872c-15.381 12.306-19.515 33.978-9.741 51.081l64 112A39.998 39.998 0 0 0 136 512h240c18.562 0 34.686-12.77 38.937-30.838l32-136A39.97 39.97 0 0 0 448 336v-80c0-22.091-17.908-40-40-40z\"],\n    \"hand-point-down\": [384, 512, [], \"f0a7\", \"M91.826 467.2V317.966c-8.248 5.841-16.558 10.57-24.918 14.153C35.098 345.752-.014 322.222 0 288c.008-18.616 10.897-32.203 29.092-40 28.286-12.122 64.329-78.648 77.323-107.534 7.956-17.857 25.479-28.453 43.845-28.464l.001-.002h171.526c11.812 0 21.897 8.596 23.703 20.269 7.25 46.837 38.483 61.76 38.315 123.731-.007 2.724.195 13.254.195 16 0 50.654-22.122 81.574-71.263 72.6-9.297 18.597-39.486 30.738-62.315 16.45-21.177 24.645-53.896 22.639-70.944 6.299V467.2c0 24.15-20.201 44.8-43.826 44.8-23.283 0-43.826-21.35-43.826-44.8zM112 72V24c0-13.255 10.745-24 24-24h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24zm212-24c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-left\": [512, 512, [], \"f0a5\", \"M44.8 155.826h149.234c-5.841-8.248-10.57-16.558-14.153-24.918C166.248 99.098 189.778 63.986 224 64c18.616.008 32.203 10.897 40 29.092 12.122 28.286 78.648 64.329 107.534 77.323 17.857 7.956 28.453 25.479 28.464 43.845l.002.001v171.526c0 11.812-8.596 21.897-20.269 23.703-46.837 7.25-61.76 38.483-123.731 38.315-2.724-.007-13.254.195-16 .195-50.654 0-81.574-22.122-72.6-71.263-18.597-9.297-30.738-39.486-16.45-62.315-24.645-21.177-22.639-53.896-6.299-70.944H44.8c-24.15 0-44.8-20.201-44.8-43.826 0-23.283 21.35-43.826 44.8-43.826zM440 176h48c13.255 0 24 10.745 24 24v192c0 13.255-10.745 24-24 24h-48c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24zm24 212c11.046 0 20-8.954 20-20s-8.954-20-20-20-20 8.954-20 20 8.954 20 20 20z\"],\n    \"hand-point-right\": [512, 512, [], \"f0a4\", \"M512 199.652c0 23.625-20.65 43.826-44.8 43.826h-99.851c16.34 17.048 18.346 49.766-6.299 70.944 14.288 22.829 2.147 53.017-16.45 62.315C353.574 425.878 322.654 448 272 448c-2.746 0-13.276-.203-16-.195-61.971.168-76.894-31.065-123.731-38.315C120.596 407.683 112 397.599 112 385.786V214.261l.002-.001c.011-18.366 10.607-35.889 28.464-43.845 28.886-12.994 95.413-49.038 107.534-77.323 7.797-18.194 21.384-29.084 40-29.092 34.222-.014 57.752 35.098 44.119 66.908-3.583 8.359-8.312 16.67-14.153 24.918H467.2c23.45 0 44.8 20.543 44.8 43.826zM96 200v192c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V200c0-13.255 10.745-24 24-24h48c13.255 0 24 10.745 24 24zM68 368c0-11.046-8.954-20-20-20s-20 8.954-20 20 8.954 20 20 20 20-8.954 20-20z\"],\n    \"hand-point-up\": [384, 512, [], \"f0a6\", \"M135.652 0c23.625 0 43.826 20.65 43.826 44.8v99.851c17.048-16.34 49.766-18.346 70.944 6.299 22.829-14.288 53.017-2.147 62.315 16.45C361.878 158.426 384 189.346 384 240c0 2.746-.203 13.276-.195 16 .168 61.971-31.065 76.894-38.315 123.731C343.683 391.404 333.599 400 321.786 400H150.261l-.001-.002c-18.366-.011-35.889-10.607-43.845-28.464C93.421 342.648 57.377 276.122 29.092 264 10.897 256.203.008 242.616 0 224c-.014-34.222 35.098-57.752 66.908-44.119 8.359 3.583 16.67 8.312 24.918 14.153V44.8c0-23.45 20.543-44.8 43.826-44.8zM136 416h192c13.255 0 24 10.745 24 24v48c0 13.255-10.745 24-24 24H136c-13.255 0-24-10.745-24-24v-48c0-13.255 10.745-24 24-24zm168 28c-11.046 0-20 8.954-20 20s8.954 20 20 20 20-8.954 20-20-8.954-20-20-20z\"],\n    \"hand-pointer\": [448, 512, [], \"f25a\", \"M448 240v96c0 3.084-.356 6.159-1.063 9.162l-32 136C410.686 499.23 394.562 512 376 512H168a40.004 40.004 0 0 1-32.35-16.473l-127.997-176c-12.993-17.866-9.043-42.883 8.822-55.876 17.867-12.994 42.884-9.043 55.877 8.823L104 315.992V40c0-22.091 17.908-40 40-40s40 17.909 40 40v200h8v-40c0-22.091 17.908-40 40-40s40 17.909 40 40v40h8v-24c0-22.091 17.908-40 40-40s40 17.909 40 40v24h8c0-22.091 17.908-40 40-40s40 17.909 40 40zm-256 80h-8v96h8v-96zm88 0h-8v96h8v-96zm88 0h-8v96h8v-96z\"],\n    \"hand-rock\": [512, 512, [], \"f255\", \"M464.8 80c-26.9-.4-48.8 21.2-48.8 48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v32h-8V80.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v48h-8V96.8c0-26.3-20.9-48.3-47.2-48.8-26.9-.4-48.8 21.2-48.8 48v136l-8-7.1v-48.1c0-26.3-20.9-48.3-47.2-48.8C21.9 127.6 0 149.2 0 176v66.4c0 27.4 11.7 53.5 32.2 71.8l111.7 99.3c10.2 9.1 16.1 22.2 16.1 35.9v6.7c0 13.3 10.7 24 24 24h240c13.3 0 24-10.7 24-24v-2.9c0-12.8 2.6-25.5 7.5-37.3l49-116.3c5-11.8 7.5-24.5 7.5-37.3V128.8c0-26.3-20.9-48.4-47.2-48.8z\"],\n    \"hand-scissors\": [512, 512, [], \"f257\", \"M216 440c0-22.092 17.909-40 40-40v-8h-32c-22.091 0-40-17.908-40-40s17.909-40 40-40h32v-8H48c-26.51 0-48-21.49-48-48s21.49-48 48-48h208v-13.572l-177.551-69.74c-24.674-9.694-36.818-37.555-27.125-62.228 9.693-24.674 37.554-36.817 62.228-27.124l190.342 74.765 24.872-31.09c12.306-15.381 33.978-19.515 51.081-9.741l112 64A40.002 40.002 0 0 1 512 168v240c0 18.562-12.77 34.686-30.838 38.937l-136 32A39.982 39.982 0 0 1 336 480h-80c-22.091 0-40-17.908-40-40z\"],\n    \"hand-spock\": [512, 512, [], \"f259\", \"M481.3 97.1c-21.5-5.1-43.1 8.2-48.2 29.6L402.3 256h-11.1l43.6-174.3c5.4-21.4-7.7-43.1-29.1-48.5s-43.1 7.7-48.5 29.1L308.8 256h-15.1L242 31.1c-5-21.6-26.4-35-48-30.1-21.5 4.9-35 26.4-30 47.9l47.6 207h-9.8L167 103.1c-4.9-21.5-26.3-35-47.9-30.1-21.5 4.9-35 26.3-30.1 47.9l39 171.6v79.4l-60.6-57c-16.1-15.1-41.4-14.4-56.5 1.7s-14.4 41.4 1.7 56.5L146.3 499c8.9 8.4 20.7 13 32.9 13h216.7c21.3 0 40-14 46-34.4l26.2-88.3c2.6-8.9 4-18 4-27.3v-42c0-7.5.9-15 2.6-22.2L511 145.3c5-21.5-8.3-43.1-29.7-48.2z\"],\n    \"hands\": [640, 512, [], \"f4c2\", \"M204.8 230.4c-10.6-14.1-30.7-17-44.8-6.4-14.1 10.6-17 30.7-6.4 44.8l38.1 50.8c4.8 6.4 4.1 15.3-1.5 20.9l-12.8 12.8c-6.7 6.7-17.6 6.2-23.6-1.1L64 244.4V96c0-17.7-14.3-32-32-32S0 78.3 0 96v218.4c0 10.9 3.7 21.5 10.5 30l104.1 134.3c5 6.5 8.4 13.9 10.4 21.7 1.8 6.9 8.1 11.6 15.3 11.6H272c8.8 0 16-7.2 16-16V384c0-27.7-9-54.6-25.6-76.8l-57.6-76.8zM608 64c-17.7 0-32 14.3-32 32v148.4l-89.8 107.8c-6 7.2-17 7.7-23.6 1.1l-12.8-12.8c-5.6-5.6-6.3-14.5-1.5-20.9l38.1-50.8c10.6-14.1 7.7-34.2-6.4-44.8-14.1-10.6-34.2-7.7-44.8 6.4l-57.6 76.8C361 329.4 352 356.3 352 384v112c0 8.8 7.2 16 16 16h131.7c7.1 0 13.5-4.7 15.3-11.6 2-7.8 5.4-15.2 10.4-21.7l104.1-134.3c6.8-8.5 10.5-19.1 10.5-30V96c0-17.7-14.3-32-32-32z\"],\n    \"hands-helping\": [640, 512, [], \"f4c4\", \"M488 192H336v56c0 39.7-32.3 72-72 72s-72-32.3-72-72V126.4l-64.9 39C107.8 176.9 96 197.8 96 220.2v47.3l-80 46.2C.7 322.5-4.6 342.1 4.3 357.4l80 138.6c8.8 15.3 28.4 20.5 43.7 11.7L231.4 448H368c35.3 0 64-28.7 64-64h16c17.7 0 32-14.3 32-32v-64h8c13.3 0 24-10.7 24-24v-48c0-13.3-10.7-24-24-24zm147.7-37.4L555.7 16C546.9.7 527.3-4.5 512 4.3L408.6 64H306.4c-12 0-23.7 3.4-33.9 9.7L239 94.6c-9.4 5.8-15 16.1-15 27.1V248c0 22.1 17.9 40 40 40s40-17.9 40-40v-88h184c30.9 0 56 25.1 56 56v28.5l80-46.2c15.3-8.9 20.5-28.4 11.7-43.7z\"],\n    \"handshake\": [640, 512, [], \"f2b5\", \"M434.7 64h-85.9c-8 0-15.7 3-21.6 8.4l-98.3 90c-.1.1-.2.3-.3.4-16.6 15.6-16.3 40.5-2.1 56 12.7 13.9 39.4 17.6 56.1 2.7.1-.1.3-.1.4-.2l79.9-73.2c6.5-5.9 16.7-5.5 22.6 1 6 6.5 5.5 16.6-1 22.6l-26.1 23.9L504 313.8c2.9 2.4 5.5 5 7.9 7.7V128l-54.6-54.6c-5.9-6-14.1-9.4-22.6-9.4zM544 128.2v223.9c0 17.7 14.3 32 32 32h64V128.2h-96zm48 223.9c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM0 384h64c17.7 0 32-14.3 32-32V128.2H0V384zm48-63.9c8.8 0 16 7.2 16 16s-7.2 16-16 16-16-7.2-16-16c0-8.9 7.2-16 16-16zm435.9 18.6L334.6 217.5l-30 27.5c-29.7 27.1-75.2 24.5-101.7-4.4-26.9-29.4-24.8-74.9 4.4-101.7L289.1 64h-83.8c-8.5 0-16.6 3.4-22.6 9.4L128 128v223.9h18.3l90.5 81.9c27.4 22.3 67.7 18.1 90-9.3l.2-.2 17.9 15.5c15.9 13 39.4 10.5 52.3-5.4l31.4-38.6 5.4 4.4c13.7 11.1 33.9 9.1 45-4.7l9.5-11.7c11.2-13.8 9.1-33.9-4.6-45.1z\"],\n    \"hanukiah\": [640, 512, [], \"f6e6\", \"M232 160c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm-64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm224 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm64 0c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm88 8c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v120h32V168zm-440-8c-4.42 0-8 3.58-8 8v120h32V168c0-4.42-3.58-8-8-8h-16zm520 0h-32c-8.84 0-16 7.16-16 16v112c0 17.67-14.33 32-32 32H352V128c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v192H96c-17.67 0-32-14.33-32-32V176c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v112c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V176c0-8.84-7.16-16-16-16zm-16-32c13.25 0 24-11.94 24-26.67S608 48 608 48s-24 38.61-24 53.33S594.75 128 608 128zm-576 0c13.25 0 24-11.94 24-26.67S32 48 32 48 8 86.61 8 101.33 18.75 128 32 128zm288-48c13.25 0 24-11.94 24-26.67S320 0 320 0s-24 38.61-24 53.33S306.75 80 320 80zm-208 48c13.25 0 24-11.94 24-26.67S112 48 112 48s-24 38.61-24 53.33S98.75 128 112 128zm64 0c13.25 0 24-11.94 24-26.67S176 48 176 48s-24 38.61-24 53.33S162.75 128 176 128zm64 0c13.25 0 24-11.94 24-26.67S240 48 240 48s-24 38.61-24 53.33S226.75 128 240 128zm160 0c13.25 0 24-11.94 24-26.67S400 48 400 48s-24 38.61-24 53.33S386.75 128 400 128zm64 0c13.25 0 24-11.94 24-26.67S464 48 464 48s-24 38.61-24 53.33S450.75 128 464 128zm64 0c13.25 0 24-11.94 24-26.67S528 48 528 48s-24 38.61-24 53.33S514.75 128 528 128z\"],\n    \"hard-hat\": [512, 512, [], \"f807\", \"M480 288c0-80.25-49.28-148.92-119.19-177.62L320 192V80a16 16 0 0 0-16-16h-96a16 16 0 0 0-16 16v112l-40.81-81.62C81.28 139.08 32 207.75 32 288v64h448zm16 96H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"hashtag\": [448, 512, [], \"f292\", \"M440.667 182.109l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l14.623-81.891C377.123 38.754 371.468 32 363.997 32h-40.632a12 12 0 0 0-11.813 9.891L296.175 128H197.54l14.623-81.891C213.477 38.754 207.822 32 200.35 32h-40.632a12 12 0 0 0-11.813 9.891L132.528 128H53.432a12 12 0 0 0-11.813 9.891l-7.143 40C33.163 185.246 38.818 192 46.289 192h74.81L98.242 320H19.146a12 12 0 0 0-11.813 9.891l-7.143 40C-1.123 377.246 4.532 384 12.003 384h74.81L72.19 465.891C70.877 473.246 76.532 480 84.003 480h40.632a12 12 0 0 0 11.813-9.891L151.826 384h98.634l-14.623 81.891C234.523 473.246 240.178 480 247.65 480h40.632a12 12 0 0 0 11.813-9.891L315.472 384h79.096a12 12 0 0 0 11.813-9.891l7.143-40c1.313-7.355-4.342-14.109-11.813-14.109h-74.81l22.857-128h79.096a12 12 0 0 0 11.813-9.891zM261.889 320h-98.634l22.857-128h98.634l-22.857 128z\"],\n    \"hat-wizard\": [512, 512, [], \"f6e8\", \"M496 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-304-64l-64-32 64-32 32-64 32 64 64 32-64 32-16 32h208l-86.41-201.63a63.955 63.955 0 0 1-1.89-45.45L416 0 228.42 107.19a127.989 127.989 0 0 0-53.46 59.15L64 416h144l-16-32zm64-224l16-32 16 32 32 16-32 16-16 32-16-32-32-16 32-16z\"],\n    \"haykal\": [512, 512, [], \"f666\", \"M496.25 202.52l-110-15.44 41.82-104.34c6.67-16.64-11.6-32.18-26.59-22.63L307.44 120 273.35 12.82C270.64 4.27 263.32 0 256 0c-7.32 0-14.64 4.27-17.35 12.82l-34.09 107.19-94.04-59.89c-14.99-9.55-33.25 5.99-26.59 22.63l41.82 104.34-110 15.43c-17.54 2.46-21.68 26.27-6.03 34.67l98.16 52.66-74.48 83.54c-10.92 12.25-1.72 30.93 13.29 30.93 1.31 0 2.67-.14 4.07-.45l108.57-23.65-4.11 112.55c-.43 11.65 8.87 19.22 18.41 19.22 5.15 0 10.39-2.21 14.2-7.18l68.18-88.9 68.18 88.9c3.81 4.97 9.04 7.18 14.2 7.18 9.54 0 18.84-7.57 18.41-19.22l-4.11-112.55 108.57 23.65c17.36 3.76 29.21-17.2 17.35-30.49l-74.48-83.54 98.16-52.66c15.64-8.39 11.5-32.2-6.04-34.66zM338.51 311.68l-51.89-11.3 1.97 53.79L256 311.68l-32.59 42.49 1.96-53.79-51.89 11.3 35.6-39.93-46.92-25.17 52.57-7.38-19.99-49.87 44.95 28.62L256 166.72l16.29 51.23 44.95-28.62-19.99 49.87 52.57 7.38-46.92 25.17 35.61 39.93z\"],\n    \"hdd\": [576, 512, [], \"f0a0\", \"M576 304v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48zm-48-80a79.557 79.557 0 0 1 30.777 6.165L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L17.223 230.165A79.557 79.557 0 0 1 48 224h480zm-48 96c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32zm-96 0c-17.673 0-32 14.327-32 32s14.327 32 32 32 32-14.327 32-32-14.327-32-32-32z\"],\n    \"heading\": [512, 512, [], \"f1dc\", \"M448 96v320h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H320a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V288H160v128h32a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H32a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h32V96H32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16h-32v128h192V96h-32a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h160a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16z\"],\n    \"headphones\": [512, 512, [], \"f025\", \"M256 32C114.52 32 0 146.496 0 288v48a32 32 0 0 0 17.689 28.622l14.383 7.191C34.083 431.903 83.421 480 144 480h24c13.255 0 24-10.745 24-24V280c0-13.255-10.745-24-24-24h-24c-31.342 0-59.671 12.879-80 33.627V288c0-105.869 86.131-192 192-192s192 86.131 192 192v1.627C427.671 268.879 399.342 256 368 256h-24c-13.255 0-24 10.745-24 24v176c0 13.255 10.745 24 24 24h24c60.579 0 109.917-48.098 111.928-108.187l14.382-7.191A32 32 0 0 0 512 336v-48c0-141.479-114.496-256-256-256z\"],\n    \"headphones-alt\": [512, 512, [], \"f58f\", \"M160 288h-16c-35.35 0-64 28.7-64 64.12v63.76c0 35.41 28.65 64.12 64 64.12h16c17.67 0 32-14.36 32-32.06V320.06c0-17.71-14.33-32.06-32-32.06zm208 0h-16c-17.67 0-32 14.35-32 32.06v127.88c0 17.7 14.33 32.06 32 32.06h16c35.35 0 64-28.71 64-64.12v-63.76c0-35.41-28.65-64.12-64-64.12zM256 32C112.91 32 4.57 151.13 0 288v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288c0-114.67 93.33-207.8 208-207.82 114.67.02 208 93.15 208 207.82v112c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V288C507.43 151.13 399.09 32 256 32z\"],\n    \"headset\": [512, 512, [], \"f590\", \"M192 208c0-17.67-14.33-32-32-32h-16c-35.35 0-64 28.65-64 64v48c0 35.35 28.65 64 64 64h16c17.67 0 32-14.33 32-32V208zm176 144c35.35 0 64-28.65 64-64v-48c0-35.35-28.65-64-64-64h-16c-17.67 0-32 14.33-32 32v112c0 17.67 14.33 32 32 32h16zM256 0C113.18 0 4.58 118.83 0 256v16c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-16c0-114.69 93.31-208 208-208s208 93.31 208 208h-.12c.08 2.43.12 165.72.12 165.72 0 23.35-18.93 42.28-42.28 42.28H320c0-26.51-21.49-48-48-48h-32c-26.51 0-48 21.49-48 48s21.49 48 48 48h181.72c49.86 0 90.28-40.42 90.28-90.28V256C507.42 118.83 398.82 0 256 0z\"],\n    \"heart\": [512, 512, [], \"f004\", \"M462.3 62.6C407.5 15.9 326 24.3 275.7 76.2L256 96.5l-19.7-20.3C186.1 24.3 104.5 15.9 49.7 62.6c-62.8 53.6-66.1 149.8-9.9 207.9l193.5 199.8c12.5 12.9 32.8 12.9 45.3 0l193.5-199.8c56.3-58.1 53-154.3-9.8-207.9z\"],\n    \"heart-broken\": [512, 512, [], \"f7a9\", \"M473.7 73.8l-2.4-2.5c-46-47-118-51.7-169.6-14.8L336 159.9l-96 64 48 128-144-144 96-64-28.6-86.5C159.7 19.6 87 24 40.7 71.4l-2.4 2.4C-10.4 123.6-12.5 202.9 31 256l212.1 218.6c7.1 7.3 18.6 7.3 25.7 0L481 255.9c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"heartbeat\": [512, 512, [], \"f21e\", \"M320.2 243.8l-49.7 99.4c-6 12.1-23.4 11.7-28.9-.6l-56.9-126.3-30 71.7H60.6l182.5 186.5c7.1 7.3 18.6 7.3 25.7 0L451.4 288H342.3l-22.1-44.2zM473.7 73.9l-2.4-2.5c-51.5-52.6-135.8-52.6-187.4 0L256 100l-27.9-28.5c-51.5-52.7-135.9-52.7-187.4 0l-2.4 2.4C-10.4 123.7-12.5 203 31 256h102.4l35.9-86.2c5.4-12.9 23.6-13.2 29.4-.4l58.2 129.3 49-97.9c5.9-11.8 22.7-11.8 28.6 0l27.6 55.2H481c43.5-53 41.4-132.3-7.3-182.1z\"],\n    \"helicopter\": [640, 512, [], \"f533\", \"M304 384h272c17.67 0 32-14.33 32-32 0-123.71-100.29-224-224-224V64h176c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H144c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h176v64H112L68.8 70.4C65.78 66.37 61.03 64 56 64H16.01C5.6 64-2.04 73.78.49 83.88L32 192l160 64 86.4 115.2A31.992 31.992 0 0 0 304 384zm112-188.49C478.55 208.3 528.03 257.44 540.79 320H416V195.51zm219.37 263.3l-22.15-22.2c-6.25-6.26-16.24-6.1-22.64.01-7.09 6.77-13.84 11.25-24.64 11.25H240c-8.84 0-16 7.18-16 16.03v32.06c0 8.85 7.16 16.03 16 16.03h325.94c14.88 0 35.3-.47 68.45-29.52 7.02-6.14 7.57-17.05.98-23.66z\"],\n    \"highlighter\": [544, 512, [], \"f591\", \"M0 479.98L99.92 512l35.45-35.45-67.04-67.04L0 479.98zm124.61-240.01a36.592 36.592 0 0 0-10.79 38.1l13.05 42.83-50.93 50.94 96.23 96.23 50.86-50.86 42.74 13.08c13.73 4.2 28.65-.01 38.15-10.78l35.55-41.64-173.34-173.34-41.52 35.44zm403.31-160.7l-63.2-63.2c-20.49-20.49-53.38-21.52-75.12-2.35L190.55 183.68l169.77 169.78L530.27 154.4c19.18-21.74 18.15-54.63-2.35-75.13z\"],\n    \"hiking\": [384, 512, [], \"f6ec\", \"M80.95 472.23c-4.28 17.16 6.14 34.53 23.28 38.81 2.61.66 5.22.95 7.8.95 14.33 0 27.37-9.7 31.02-24.23l25.24-100.97-52.78-52.78-34.56 138.22zm14.89-196.12L137 117c2.19-8.42-3.14-16.95-11.92-19.06-43.88-10.52-88.35 15.07-99.32 57.17L.49 253.24c-2.19 8.42 3.14 16.95 11.92 19.06l63.56 15.25c8.79 2.1 17.68-3.02 19.87-11.44zM368 160h-16c-8.84 0-16 7.16-16 16v16h-34.75l-46.78-46.78C243.38 134.11 228.61 128 212.91 128c-27.02 0-50.47 18.3-57.03 44.52l-26.92 107.72a32.012 32.012 0 0 0 8.42 30.39L224 397.25V480c0 17.67 14.33 32 32 32s32-14.33 32-32v-82.75c0-17.09-6.66-33.16-18.75-45.25l-46.82-46.82c.15-.5.49-.89.62-1.41l19.89-79.57 22.43 22.43c6 6 14.14 9.38 22.62 9.38h48v240c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16V176c.01-8.84-7.15-16-15.99-16zM240 96c26.51 0 48-21.49 48-48S266.51 0 240 0s-48 21.49-48 48 21.49 48 48 48z\"],\n    \"hippo\": [640, 512, [], \"f6ed\", \"M581.12 96.2c-27.67-.15-52.5 17.58-76.6 26.62C489.98 88.27 455.83 64 416 64c-11.28 0-21.95 2.3-32 5.88V56c0-13.26-10.75-24-24-24h-16c-13.25 0-24 10.74-24 24v48.98C286.01 79.58 241.24 64 192 64 85.96 64 0 135.64 0 224v240c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16v-70.79C128.35 407.57 166.72 416 208 416s79.65-8.43 112-22.79V464c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V288h128v32c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-32c17.67 0 32-14.33 32-32v-92.02c0-34.09-24.79-67.59-58.88-67.78zM448 176c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"history\": [512, 512, [], \"f1da\", \"M504 255.531c.253 136.64-111.18 248.372-247.82 248.468-59.015.042-113.223-20.53-155.822-54.911-11.077-8.94-11.905-25.541-1.839-35.607l11.267-11.267c8.609-8.609 22.353-9.551 31.891-1.984C173.062 425.135 212.781 440 256 440c101.705 0 184-82.311 184-184 0-101.705-82.311-184-184-184-48.814 0-93.149 18.969-126.068 49.932l50.754 50.754c10.08 10.08 2.941 27.314-11.313 27.314H24c-8.837 0-16-7.163-16-16V38.627c0-14.254 17.234-21.393 27.314-11.314l49.372 49.372C129.209 34.136 189.552 8 256 8c136.81 0 247.747 110.78 248 247.531zm-180.912 78.784l9.823-12.63c8.138-10.463 6.253-25.542-4.21-33.679L288 256.349V152c0-13.255-10.745-24-24-24h-16c-13.255 0-24 10.745-24 24v135.651l65.409 50.874c10.463 8.137 25.541 6.253 33.679-4.21z\"],\n    \"hockey-puck\": [512, 512, [], \"f453\", \"M0 160c0-53 114.6-96 256-96s256 43 256 96-114.6 96-256 96S0 213 0 160zm0 82.2V352c0 53 114.6 96 256 96s256-43 256-96V242.2c-113.4 82.3-398.5 82.4-512 0z\"],\n    \"holly-berry\": [448, 512, [], \"f7aa\", \"M144 192c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm112-48c0 26.5 21.5 48 48 48s48-21.5 48-48-21.5-48-48-48-48 21.5-48 48zm-32-48c26.5 0 48-21.5 48-48S250.5 0 224 0s-48 21.5-48 48 21.5 48 48 48zm-16.2 139.1c.1-12.4-13.1-20.1-23.8-13.7-34.3 20.3-71.4 32.7-108.7 36.2-9.7.9-15.6 11.3-11.6 20.2 6.2 13.9 11.1 28.6 14.7 43.8 3.6 15.2-5.3 30.6-20.2 35.1-14.9 4.5-30.1 7.6-45.3 9.1-9.7 1-15.7 11.3-11.7 20.2 15 32.8 22.9 69.5 23 107.7.1 14.4 15.2 23.1 27.6 16 33.2-19 68.9-30.5 104.8-33.9 9.7-.9 15.6-11.3 11.6-20.2-6.2-13.9-11.1-28.6-14.7-43.8-3.6-15.2 5.3-30.6 20.2-35.1 14.9-4.5 30.1-7.6 45.3-9.1 9.7-1 15.7-11.3 11.7-20.2-15.5-34.2-23.3-72.5-22.9-112.3zM435 365.6c-15.2-1.6-30.3-4.7-45.3-9.1-14.9-4.5-23.8-19.9-20.2-35.1 3.6-15.2 8.5-29.8 14.7-43.8 4-8.9-1.9-19.3-11.6-20.2-37.3-3.5-74.4-15.9-108.7-36.2-10.7-6.3-23.9 1.4-23.8 13.7 0 1.6-.2 3.2-.2 4.9.2 33.3 7 65.7 19.9 94 5.7 12.4 5.2 26.6-.6 38.9 4.9 1.2 9.9 2.2 14.8 3.7 14.9 4.5 23.8 19.9 20.2 35.1-3.6 15.2-8.5 29.8-14.7 43.8-4 8.9 1.9 19.3 11.6 20.2 35.9 3.4 71.6 14.9 104.8 33.9 12.5 7.1 27.6-1.6 27.6-16 .2-38.2 8-75 23-107.7 4.3-8.7-1.8-19.1-11.5-20.1z\"],\n    \"home\": [576, 512, [], \"f015\", \"M280.37 148.26L96 300.11V464a16 16 0 0 0 16 16l112.06-.29a16 16 0 0 0 15.92-16V368a16 16 0 0 1 16-16h64a16 16 0 0 1 16 16v95.64a16 16 0 0 0 16 16.05L464 480a16 16 0 0 0 16-16V300L295.67 148.26a12.19 12.19 0 0 0-15.3 0zM571.6 251.47L488 182.56V44.05a12 12 0 0 0-12-12h-56a12 12 0 0 0-12 12v72.61L318.47 43a48 48 0 0 0-61 0L4.34 251.47a12 12 0 0 0-1.6 16.9l25.5 31A12 12 0 0 0 45.15 301l235.22-193.74a12.19 12.19 0 0 1 15.3 0L530.9 301a12 12 0 0 0 16.9-1.6l25.5-31a12 12 0 0 0-1.7-16.93z\"],\n    \"horse\": [576, 512, [], \"f6f0\", \"M575.92 76.6c-.01-8.13-3.02-15.87-8.58-21.8-3.78-4.03-8.58-9.12-13.69-14.5 11.06-6.84 19.5-17.49 22.18-30.66C576.85 4.68 572.96 0 567.9 0H447.92c-70.69 0-128 57.31-128 128H160c-28.84 0-54.4 12.98-72 33.11V160c-48.53 0-88 39.47-88 88v56c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-56c0-13.22 6.87-24.39 16.78-31.68-.21 2.58-.78 5.05-.78 7.68 0 27.64 11.84 52.36 30.54 69.88l-25.72 68.6a63.945 63.945 0 0 0-2.16 37.99l24.85 99.41A15.982 15.982 0 0 0 107.02 512h65.96c10.41 0 18.05-9.78 15.52-19.88l-26.31-105.26 23.84-63.59L320 345.6V496c0 8.84 7.16 16 16 16h64c8.84 0 16-7.16 16-16V318.22c19.74-20.19 32-47.75 32-78.22 0-.22-.07-.42-.08-.64V136.89l16 7.11 18.9 37.7c7.45 14.87 25.05 21.55 40.49 15.37l32.55-13.02a31.997 31.997 0 0 0 20.12-29.74l-.06-77.71zm-64 19.4c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16z\"],\n    \"horse-head\": [512, 512, [], \"f7ab\", \"M509.8 332.5l-69.9-164.3c-14.9-41.2-50.4-71-93-79.2 18-10.6 46.3-35.9 34.2-82.3-1.3-5-7.1-7.9-12-6.1L166.9 76.3C35.9 123.4 0 238.9 0 398.8V480c0 17.7 14.3 32 32 32h236.2c23.8 0 39.3-25 28.6-46.3L256 384v-.7c-45.6-3.5-84.6-30.7-104.3-69.6-1.6-3.1-.9-6.9 1.6-9.3l12.1-12.1c3.9-3.9 10.6-2.7 12.9 2.4 14.8 33.7 48.2 57.4 87.4 57.4 17.2 0 33-5.1 46.8-13.2l46 63.9c6 8.4 15.7 13.3 26 13.3h50.3c8.5 0 16.6-3.4 22.6-9.4l45.3-39.8c8.9-9.1 11.7-22.6 7.1-34.4zM328 224c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24-10.7 24-24 24z\"],\n    \"hospital\": [448, 512, [], \"f0f8\", \"M448 492v20H0v-20c0-6.627 5.373-12 12-12h20V120c0-13.255 10.745-24 24-24h88V24c0-13.255 10.745-24 24-24h112c13.255 0 24 10.745 24 24v72h88c13.255 0 24 10.745 24 24v360h20c6.627 0 12 5.373 12 12zM308 192h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-168 64h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12zm104 128h-40c-6.627 0-12 5.373-12 12v84h64v-84c0-6.627-5.373-12-12-12zm64-96h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12zm-116 12c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40zM182 96h26v26a6 6 0 0 0 6 6h20a6 6 0 0 0 6-6V96h26a6 6 0 0 0 6-6V70a6 6 0 0 0-6-6h-26V38a6 6 0 0 0-6-6h-20a6 6 0 0 0-6 6v26h-26a6 6 0 0 0-6 6v20a6 6 0 0 0 6 6z\"],\n    \"hospital-alt\": [576, 512, [], \"f47d\", \"M544 96H416V32c0-17.7-14.3-32-32-32H192c-17.7 0-32 14.3-32 32v64H32c-17.7 0-32 14.3-32 32v368c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16V128c0-17.7-14.3-32-32-32zM160 436c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm160 128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm16-170c0 3.3-2.7 6-6 6h-26v26c0 3.3-2.7 6-6 6h-20c-3.3 0-6-2.7-6-6v-26h-26c-3.3 0-6-2.7-6-6v-20c0-3.3 2.7-6 6-6h26V86c0-3.3 2.7-6 6-6h20c3.3 0 6 2.7 6 6v26h26c3.3 0 6 2.7 6 6v20zm144 298c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40zm0-128c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h40c6.6 0 12 5.4 12 12v40z\"],\n    \"hospital-symbol\": [512, 512, [], \"f47e\", \"M256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm112 376c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-88h-96v88c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8V136c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v88h96v-88c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v240z\"],\n    \"hot-tub\": [512, 512, [], \"f593\", \"M414.21 177.65c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C378.96 6.14 372.22 0 364.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zm-108 0c1.02 8.21 7.75 14.35 15.75 14.35h16.12c9.51 0 17.08-8.57 16-18.35-4.34-39.11-22.4-74.53-50.13-97.16-17.37-14.17-28.82-36.75-31.98-62.15C270.96 6.14 264.22 0 256.23 0h-16.12c-9.51 0-17.09 8.57-16 18.35 4.34 39.11 22.4 74.53 50.13 97.16 17.36 14.17 28.82 36.75 31.97 62.14zM480 256H256l-110.93-83.2a63.99 63.99 0 0 0-38.4-12.8H64c-35.35 0-64 28.65-64 64v224c0 35.35 28.65 64 64 64h384c35.35 0 64-28.65 64-64V288c0-17.67-14.33-32-32-32zM128 440c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zm96 0c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8V328c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v112zM64 128c35.35 0 64-28.65 64-64S99.35 0 64 0 0 28.65 0 64s28.65 64 64 64z\"],\n    \"hotdog\": [512, 512, [], \"f80f\", \"M488.56 23.44a80 80 0 0 0-113.12 0l-352 352a80 80 0 1 0 113.12 113.12l352-352a80 80 0 0 0 0-113.12zm-49.93 95.19c-19.6 19.59-37.52 22.67-51.93 25.14C373.76 146 364.4 147.6 352 160s-14 21.76-16.23 34.71c-2.48 14.4-5.55 32.33-25.15 51.92s-37.52 22.67-51.92 25.15C245.75 274 236.4 275.6 224 288s-14 21.75-16.23 34.7c-2.47 14.4-5.54 32.33-25.14 51.92s-37.53 22.68-51.93 25.15C117.76 402 108.4 403.6 96 416a16 16 0 0 1-22.63-22.63c19.6-19.59 37.52-22.67 51.92-25.14 13-2.22 22.3-3.82 34.71-16.23s14-21.75 16.22-34.7c2.48-14.4 5.55-32.33 25.15-51.92s37.52-22.67 51.92-25.14c13-2.22 22.3-3.83 34.7-16.23s14-21.76 16.24-34.71c2.47-14.4 5.54-32.33 25.14-51.92s37.52-22.68 51.92-25.15C394.24 110 403.59 108.41 416 96a16 16 0 0 1 22.63 22.63zM31.44 322.18L322.18 31.44l-11.54-11.55c-25-25-63.85-26.66-86.79-3.72L16.17 223.85c-22.94 22.94-21.27 61.79 3.72 86.78zm449.12-132.36L189.82 480.56l11.54 11.55c25 25 63.85 26.66 86.79 3.72l207.68-207.68c22.94-22.94 21.27-61.79-3.72-86.79z\"],\n    \"hotel\": [576, 512, [], \"f594\", \"M560 64c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h15.98v384H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h240v-80c0-8.8 7.2-16 16-16h32c8.8 0 16 7.2 16 16v80h240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-16V64h16zm-304 44.8c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm0 96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zm-128-96c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4zM179.2 256h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4c0 6.4-6.4 12.8-12.8 12.8zM192 384c0-53.02 42.98-96 96-96s96 42.98 96 96H192zm256-140.8c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4zm0-96c0 6.4-6.4 12.8-12.8 12.8h-38.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h38.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"hourglass\": [384, 512, [], \"f254\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64z\"],\n    \"hourglass-end\": [384, 512, [], \"f253\", \"M360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64zM192 208c-57.787 0-104-66.518-104-144h208c0 77.945-46.51 144-104 144z\"],\n    \"hourglass-half\": [384, 512, [], \"f252\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-75.078 384H99.08c17.059-46.797 52.096-80 92.92-80 40.821 0 75.862 33.196 92.922 80zm.019-256H99.078C91.988 108.548 88 86.748 88 64h208c0 22.805-3.987 44.587-11.059 64z\"],\n    \"hourglass-start\": [384, 512, [], \"f251\", \"M360 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24 0 90.965 51.016 167.734 120.842 192C75.016 280.266 24 357.035 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24 0-90.965-51.016-167.734-120.842-192C308.984 231.734 360 154.965 360 64c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24zm-64 448H88c0-77.458 46.204-144 104-144 57.786 0 104 66.517 104 144z\"],\n    \"house-damage\": [576, 512, [], \"f6f1\", \"M288 114.96L69.47 307.71c-1.62 1.46-3.69 2.14-5.47 3.35V496c0 8.84 7.16 16 16 16h149.23L192 439.19l104.11-64-60.16-119.22L384 392.75l-104.11 64L319.81 512H496c8.84 0 16-7.16 16-16V311.1c-1.7-1.16-3.72-1.82-5.26-3.2L288 114.96zm282.69 121.32L512 184.45V48c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v51.69L314.75 10.31C307.12 3.45 297.56.01 288 0s-19.1 3.41-26.7 10.27L5.31 236.28c-6.57 5.91-7.12 16.02-1.21 22.6l21.4 23.82c5.9 6.57 16.02 7.12 22.6 1.21L277.42 81.63c6.05-5.33 15.12-5.33 21.17 0L527.91 283.9c6.57 5.9 16.69 5.36 22.6-1.21l21.4-23.82c5.9-6.57 5.36-16.69-1.22-22.59z\"],\n    \"hryvnia\": [384, 512, [], \"f6f2\", \"M368 240c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-41.86c13.41-28.63 13.74-63.33-4.13-94.05C303.34 49.84 267.1 32 229.96 32h-78.82c-24.32 0-47.86 8.53-66.54 24.09L72.83 65.9c-10.18 8.49-11.56 23.62-3.07 33.8l20.49 24.59c8.49 10.19 23.62 11.56 33.81 3.07l11.73-9.78c4.32-3.6 9.77-5.57 15.39-5.57h83.62c11.69 0 21.2 9.52 21.2 21.2 0 5.91-2.48 11.58-6.81 15.58L219.7 176H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h134.37l-34.67 32H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h41.86c-13.41 28.63-13.74 63.33 4.13 94.05C80.66 462.15 116.9 480 154.04 480h78.82c24.32 0 47.86-8.53 66.54-24.09l11.77-9.81c10.18-8.49 11.56-23.62 3.07-33.8l-20.49-24.59c-8.49-10.19-23.62-11.56-33.81-3.07l-11.75 9.8a23.992 23.992 0 0 1-15.36 5.56H149.2c-11.69 0-21.2-9.52-21.2-21.2 0-5.91 2.48-11.58 6.81-15.58L164.3 336H368c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H233.63l34.67-32H368z\"],\n    \"i-cursor\": [256, 512, [], \"f246\", \"M256 52.048V12.065C256 5.496 250.726.148 244.158.066 211.621-.344 166.469.011 128 37.959 90.266.736 46.979-.114 11.913.114 5.318.157 0 5.519 0 12.114v39.645c0 6.687 5.458 12.078 12.145 11.998C38.111 63.447 96 67.243 96 112.182V224H60c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h36v112c0 44.932-56.075 48.031-83.95 47.959C5.404 447.942 0 453.306 0 459.952v39.983c0 6.569 5.274 11.917 11.842 11.999 32.537.409 77.689.054 116.158-37.894 37.734 37.223 81.021 38.073 116.087 37.845 6.595-.043 11.913-5.405 11.913-12V460.24c0-6.687-5.458-12.078-12.145-11.998C217.889 448.553 160 444.939 160 400V288h36c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-36V112.182c0-44.932 56.075-48.213 83.95-48.142 6.646.018 12.05-5.346 12.05-11.992z\"],\n    \"ice-cream\": [448, 512, [], \"f810\", \"M368 160h-.94a144 144 0 1 0-286.12 0H80a48 48 0 0 0 0 96h288a48 48 0 0 0 0-96zM195.38 493.69a31.52 31.52 0 0 0 57.24 0L352 288H96z\"],\n    \"icicles\": [512, 512, [], \"f7ad\", \"M511.4 37.9C515.1 18.2 500 0 480 0H32C10.6 0-4.8 20.7 1.4 41.2l87.1 273.4c2.5 7.2 12.7 7.2 15.1 0L140 190.5l44.2 187.3c1.9 8.3 13.7 8.3 15.6 0l46.5-196.9 34.1 133.4c2.3 7.6 13 7.6 15.3 0l45.8-172.5 66.7 363.8c1.7 8.6 14 8.6 15.7 0l87.5-467.7z\"],\n    \"icons\": [512, 512, [], \"f86d\", \"M116.65 219.35a15.68 15.68 0 0 0 22.65 0l96.75-99.83c28.15-29 26.5-77.1-4.91-103.88C203.75-7.7 163-3.5 137.86 22.44L128 32.58l-9.85-10.14C93.05-3.5 52.25-7.7 24.86 15.64c-31.41 26.78-33 74.85-5 103.88zm143.92 100.49h-48l-7.08-14.24a27.39 27.39 0 0 0-25.66-17.78h-71.71a27.39 27.39 0 0 0-25.66 17.78l-7 14.24h-48A27.45 27.45 0 0 0 0 347.3v137.25A27.44 27.44 0 0 0 27.43 512h233.14A27.45 27.45 0 0 0 288 484.55V347.3a27.45 27.45 0 0 0-27.43-27.46zM144 468a52 52 0 1 1 52-52 52 52 0 0 1-52 52zm355.4-115.9h-60.58l22.36-50.75c2.1-6.65-3.93-13.21-12.18-13.21h-75.59c-6.3 0-11.66 3.9-12.5 9.1l-16.8 106.93c-1 6.3 4.88 11.89 12.5 11.89h62.31l-24.2 83c-1.89 6.65 4.2 12.9 12.23 12.9a13.26 13.26 0 0 0 10.92-5.25l92.4-138.91c4.88-6.91-1.16-15.7-10.87-15.7zM478.08.33L329.51 23.17C314.87 25.42 304 38.92 304 54.83V161.6a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V99.66l112-17.22v47.18a83.25 83.25 0 0 0-16-1.7c-35.35 0-64 21.48-64 48s28.65 48 64 48c35.2 0 63.73-21.32 64-47.66V32c0-19.48-16-34.42-33.92-31.67z\"],\n    \"id-badge\": [384, 512, [], \"f2c1\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM144 32h96c8.8 0 16 7.2 16 16s-7.2 16-16 16h-96c-8.8 0-16-7.2-16-16s7.2-16 16-16zm48 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 416 80 407.4 80 396.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"id-card\": [576, 512, [], \"f2c2\", \"M528 32H48C21.5 32 0 53.5 0 80v16h576V80c0-26.5-21.5-48-48-48zM0 432c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V128H0v304zm352-232c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zm0 64c0-4.4 3.6-8 8-8h144c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H360c-4.4 0-8-3.6-8-8v-16zM176 192c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zM67.1 396.2C75.5 370.5 99.6 352 128 352h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.9-5.2 19.8-15.6 19.8H82.7c-10.4 0-18.8-10-15.6-19.8z\"],\n    \"id-card-alt\": [576, 512, [], \"f47f\", \"M528 64H384v96H192V64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h480c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM288 224c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm93.3 224H194.7c-10.4 0-18.8-10-15.6-19.8 8.3-25.6 32.4-44.2 60.9-44.2h8.2c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h8.2c28.4 0 52.5 18.5 60.9 44.2 3.2 9.8-5.2 19.8-15.6 19.8zM352 32c0-17.7-14.3-32-32-32h-64c-17.7 0-32 14.3-32 32v96h128V32z\"],\n    \"igloo\": [576, 512, [], \"f7ae\", \"M320 33.9c-10.5-1.2-21.2-1.9-32-1.9-99.8 0-187.8 50.8-239.4 128H320V33.9zM96 192H30.3C11.1 230.6 0 274 0 320h96V192zM352 39.4V160h175.4C487.2 99.9 424.8 55.9 352 39.4zM480 320h96c0-46-11.1-89.4-30.3-128H480v128zm-64 64v96h128c17.7 0 32-14.3 32-32v-96H411.5c2.6 10.3 4.5 20.9 4.5 32zm32-192H128v128h49.8c22.2-38.1 63-64 110.2-64s88 25.9 110.2 64H448V192zM0 448c0 17.7 14.3 32 32 32h128v-96c0-11.1 1.9-21.7 4.5-32H0v96zm288-160c-53 0-96 43-96 96v96h192v-96c0-53-43-96-96-96z\"],\n    \"image\": [512, 512, [], \"f03e\", \"M464 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM112 120c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56zM64 384h384V272l-87.515-87.515c-4.686-4.686-12.284-4.686-16.971 0L208 320l-55.515-55.515c-4.686-4.686-12.284-4.686-16.971 0L64 336v48z\"],\n    \"images\": [576, 512, [], \"f302\", \"M480 416v16c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v208c0 44.112 35.888 80 80 80h336zm96-80V80c0-26.51-21.49-48-48-48H144c-26.51 0-48 21.49-48 48v256c0 26.51 21.49 48 48 48h384c26.51 0 48-21.49 48-48zM256 128c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-96 144l55.515-55.515c4.686-4.686 12.284-4.686 16.971 0L272 256l135.515-135.515c4.686-4.686 12.284-4.686 16.971 0L512 208v112H160v-48z\"],\n    \"inbox\": [576, 512, [], \"f01c\", \"M567.938 243.908L462.25 85.374A48.003 48.003 0 0 0 422.311 64H153.689a48 48 0 0 0-39.938 21.374L8.062 243.908A47.994 47.994 0 0 0 0 270.533V400c0 26.51 21.49 48 48 48h480c26.51 0 48-21.49 48-48V270.533a47.994 47.994 0 0 0-8.062-26.625zM162.252 128h251.497l85.333 128H376l-32 64H232l-32-64H76.918l85.334-128z\"],\n    \"indent\": [448, 512, [], \"f03c\", \"M27.31 363.3l96-96a16 16 0 0 0 0-22.62l-96-96C17.27 138.66 0 145.78 0 160v192c0 14.31 17.33 21.3 27.31 11.3zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"industry\": [512, 512, [], \"f275\", \"M475.115 163.781L336 252.309v-68.28c0-18.916-20.931-30.399-36.885-20.248L160 252.309V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56v400c0 13.255 10.745 24 24 24h464c13.255 0 24-10.745 24-24V184.029c0-18.917-20.931-30.399-36.885-20.248z\"],\n    \"infinity\": [640, 512, [], \"f534\", \"M471.1 96C405 96 353.3 137.3 320 174.6 286.7 137.3 235 96 168.9 96 75.8 96 0 167.8 0 256s75.8 160 168.9 160c66.1 0 117.8-41.3 151.1-78.6 33.3 37.3 85 78.6 151.1 78.6 93.1 0 168.9-71.8 168.9-160S564.2 96 471.1 96zM168.9 320c-40.2 0-72.9-28.7-72.9-64s32.7-64 72.9-64c38.2 0 73.4 36.1 94 64-20.4 27.6-55.9 64-94 64zm302.2 0c-38.2 0-73.4-36.1-94-64 20.4-27.6 55.9-64 94-64 40.2 0 72.9 28.7 72.9 64s-32.7 64-72.9 64z\"],\n    \"info\": [192, 512, [], \"f129\", \"M20 424.229h20V279.771H20c-11.046 0-20-8.954-20-20V212c0-11.046 8.954-20 20-20h112c11.046 0 20 8.954 20 20v212.229h20c11.046 0 20 8.954 20 20V492c0 11.046-8.954 20-20 20H20c-11.046 0-20-8.954-20-20v-47.771c0-11.046 8.954-20 20-20zM96 0C56.235 0 24 32.235 24 72s32.235 72 72 72 72-32.235 72-72S135.764 0 96 0z\"],\n    \"info-circle\": [512, 512, [], \"f05a\", \"M256 8C119.043 8 8 119.083 8 256c0 136.997 111.043 248 248 248s248-111.003 248-248C504 119.083 392.957 8 256 8zm0 110c23.196 0 42 18.804 42 42s-18.804 42-42 42-42-18.804-42-42 18.804-42 42-42zm56 254c0 6.627-5.373 12-12 12h-88c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h12v-64h-12c-6.627 0-12-5.373-12-12v-24c0-6.627 5.373-12 12-12h64c6.627 0 12 5.373 12 12v100h12c6.627 0 12 5.373 12 12v24z\"],\n    \"italic\": [320, 512, [], \"f033\", \"M320 48v32a16 16 0 0 1-16 16h-62.76l-80 320H208a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h62.76l80-320H112a16 16 0 0 1-16-16V48a16 16 0 0 1 16-16h192a16 16 0 0 1 16 16z\"],\n    \"jedi\": [544, 512, [], \"f669\", \"M479.99 352l58.88-58.87c3.29-16.8 5.13-34.12 5.13-51.86 0-5.81-.68-11.51-1.05-17.27H496l41.25-41.24c-14.5-64.79-52.43-123.05-107.91-162.27-2.77-1.96-5.97-2.99-9.25-2.99-5.37 0-10.41 2.71-13.49 7.24-3.05 4.49-3.64 9.99-1.61 15.09 6.55 16.46 9.86 33.73 9.86 51.31 0 45.12-21.03 86.57-57.69 113.73-4.02 2.98-6.46 7.5-6.7 12.4-.24 4.92 1.76 9.66 5.49 13.03 32.93 29.75 47.35 73.51 38.57 117.07-9.74 48.35-48.84 87.1-97.31 96.5l-2.5-65.34L321.88 397c2.98 2.06 7.39 1.69 10.02-.8a8.002 8.002 0 0 0 1.34-9.92l-20.11-33.73 42.07-8.72c3.7-.75 6.38-4.05 6.38-7.83 0-3.77-2.69-7.06-6.38-7.83l-42.07-8.73 20.13-33.77c1.92-3.23 1.34-7.31-1.38-9.91-2.7-2.55-6.97-2.89-10-.8l-30.39 20.67L279.96 7.7a7.964 7.964 0 0 0-8-7.7c-4.33 0-7.84 3.38-8 7.67l-11.52 287.97-30.39-20.66c-3.14-2.12-7.27-1.83-10 .78-2.72 2.59-3.3 6.67-1.36 9.94l20.11 33.73-42.07 8.73c-3.7.75-6.38 4.05-6.38 7.83s2.67 7.08 6.38 7.83l42.07 8.72-20.13 33.77c-1.92 3.23-1.34 7.33 1.39 9.94 2.59 2.45 7.03 2.75 10 .75l27.16-18.48-2.5 65.26c-56.94-11.64-99.89-61.89-99.89-121.92 0-35.08 14.62-67.6 41.17-91.58 3.72-3.36 5.72-8.11 5.48-13.01-.24-4.9-2.68-9.41-6.69-12.38-36.67-27.16-57.71-68.62-57.71-113.74 0-17.56 3.31-34.81 9.84-51.26 2.02-5.09 1.43-10.59-1.62-15.09-3.08-4.54-8.13-7.25-13.51-7.25-3.3 0-6.5 1.04-9.27 3-55.87 39.52-93.6 97.37-107.97 162.07L47.93 224H.72c-.63 9.92-.97 19.91-.5 29.99.62 13.43 2.54 26.53 5.11 39.41l58.6 58.6H24.02c41.25 90.23 131.13 154.94 235.1 159.71 4.3.2 8.59.29 12.85.29 110.34 0 205.35-65.83 247.98-160h-39.96z\"],\n    \"joint\": [640, 512, [], \"f595\", \"M444.34 181.1c22.38 15.68 35.66 41.16 35.66 68.59V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-43.24-21.01-83.41-56.34-108.06C463.85 125.02 448 99.34 448 70.31V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v66.4c0 43.69 24.56 81.63 60.34 106.7zM194.97 358.98C126.03 370.07 59.69 394.69 0 432c83.65 52.28 180.3 80 278.94 80h88.57L254.79 380.49c-14.74-17.2-37.45-25.11-59.82-21.51zM553.28 87.09c-5.67-3.8-9.28-9.96-9.28-16.78V8c0-4.42-3.58-8-8-8h-48c-4.42 0-8 3.58-8 8v62.31c0 22.02 10.17 43.41 28.64 55.39C550.79 153.04 576 199.54 576 249.69V280c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-30.31c0-65.44-32.41-126.19-86.72-162.6zM360.89 352.05c-34.4.06-86.81.15-88.21.17l117.8 137.43A63.987 63.987 0 0 0 439.07 512h88.45L409.57 374.4a63.955 63.955 0 0 0-48.68-22.35zM616 352H432l117.99 137.65A63.987 63.987 0 0 0 598.58 512H616c13.25 0 24-10.75 24-24V376c0-13.26-10.75-24-24-24z\"],\n    \"journal-whills\": [448, 512, [], \"f66a\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM133.08 144.39l21.26 21.26c1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34c3.12-3.12 3.12-8.19 0-11.31l-26.42-26.42c10-20.9 26.24-37.97 46.37-49.26C179.62 88.4 176 99.74 176 112c0 19.96 9.33 37.57 23.66 49.31C190.01 171.37 184 184.96 184 200c0 26.94 19.04 49.4 44.38 54.76l1.36-32.71-10.37 7.04c-.69.45-1.47.69-2.25.69-1 0-1.98-.38-2.75-1.09a4.006 4.006 0 0 1-.69-4.95l8.54-14.31-17.91-3.72c-1.86-.39-3.19-2.03-3.19-3.92s1.33-3.53 3.19-3.92l17.91-3.72-8.54-14.31c-.95-1.61-.67-3.67.69-4.95 1.36-1.3 3.44-1.44 5-.41l12.01 8.16L236 71.83c.09-2.14 1.86-3.83 4-3.83s3.91 1.69 4 3.83l4.68 112.29 14.2-9.65a4.067 4.067 0 0 1 5 .41 4.006 4.006 0 0 1 .69 4.95l-8.54 14.31 17.91 3.72c1.86.39 3.19 2.03 3.19 3.92s-1.33 3.53-3.19 3.92l-17.91 3.72 8.54 14.31c.95 1.61.67 3.67-.69 4.95-.77.72-1.77 1.09-2.75 1.09-.78 0-1.56-.23-2.25-.69l-12.68-8.62 1.43 34.28C276.96 249.4 296 226.94 296 200c0-15.04-6.01-28.63-15.66-38.69C294.67 149.57 304 131.96 304 112c0-12.26-3.62-23.6-9.6-33.33 20.13 11.28 36.37 28.36 46.37 49.26l-26.42 26.42c-3.12 3.12-3.12 8.19 0 11.31 1.56 1.56 3.61 2.34 5.66 2.34s4.09-.78 5.66-2.34l21.26-21.26c2.97 10.08 5.07 20.55 5.07 31.6 0 .52-.14.99-.15 1.51l-37.11 32.47a7.975 7.975 0 0 0-.75 11.28 7.97 7.97 0 0 0 6.02 2.73c1.88 0 3.75-.66 5.27-1.98l23.59-20.64C337.32 250.96 293.09 288 240 288s-97.32-37.04-108.86-86.62l23.59 20.64A7.957 7.957 0 0 0 160 224c2.22 0 4.44-.92 6.02-2.73 2.92-3.33 2.58-8.38-.75-11.28l-37.11-32.47c-.01-.52-.15-.99-.15-1.51-.01-11.06 2.09-21.53 5.07-31.62zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"kaaba\": [576, 512, [], \"f66b\", \"M554.12 83.51L318.36 4.93a95.962 95.962 0 0 0-60.71 0L21.88 83.51A32.006 32.006 0 0 0 0 113.87v49.01l265.02-79.51c15.03-4.5 30.92-4.5 45.98 0l265 79.51v-49.01c0-13.77-8.81-26-21.88-30.36zm-279.9 30.52L0 196.3v228.38c0 15 10.42 27.98 25.06 31.24l242.12 53.8a95.937 95.937 0 0 0 41.65 0l242.12-53.8c14.64-3.25 25.06-16.24 25.06-31.24V196.29l-274.2-82.26c-9.04-2.72-18.59-2.72-27.59 0zM128 230.11c0 3.61-2.41 6.77-5.89 7.72l-80 21.82C37.02 261.03 32 257.2 32 251.93v-16.58c0-3.61 2.41-6.77 5.89-7.72l80-21.82c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm144-39.28c0 3.61-2.41 6.77-5.89 7.72l-96 26.18c-5.09 1.39-10.11-2.44-10.11-7.72v-16.58c0-3.61 2.41-6.77 5.89-7.72l96-26.18c5.09-1.39 10.11 2.44 10.11 7.72v16.58zm176 22.7c0-5.28 5.02-9.11 10.11-7.72l80 21.82c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-80-21.82a7.997 7.997 0 0 1-5.89-7.72v-16.58zm-144-39.27c0-5.28 5.02-9.11 10.11-7.72l96 26.18c3.48.95 5.89 4.11 5.89 7.72v16.58c0 5.28-5.02 9.11-10.11 7.72l-96-26.18a7.997 7.997 0 0 1-5.89-7.72v-16.58z\"],\n    \"key\": [512, 512, [], \"f084\", \"M512 176.001C512 273.203 433.202 352 336 352c-11.22 0-22.19-1.062-32.827-3.069l-24.012 27.014A23.999 23.999 0 0 1 261.223 384H224v40c0 13.255-10.745 24-24 24h-40v40c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-78.059c0-6.365 2.529-12.47 7.029-16.971l161.802-161.802C163.108 213.814 160 195.271 160 176 160 78.798 238.797.001 335.999 0 433.488-.001 512 78.511 512 176.001zM336 128c0 26.51 21.49 48 48 48s48-21.49 48-48-21.49-48-48-48-48 21.49-48 48z\"],\n    \"keyboard\": [576, 512, [], \"f11c\", \"M528 448H48c-26.51 0-48-21.49-48-48V112c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v288c0 26.51-21.49 48-48 48zM128 180v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H172c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"khanda\": [512, 512, [], \"f66d\", \"M415.81 66c-6.37-3.5-14.37-2.33-19.36 3.02a15.974 15.974 0 0 0-1.91 19.52c16.49 26.16 25.2 56.39 25.2 87.41-.19 53.25-26.77 102.69-71.27 132.41l-76.63 53.35v-20.1l44.05-36.09c3.92-4.2 5-10.09 2.81-15.28L310.85 273c33.84-19.26 56.94-55.25 56.94-96.99 0-40.79-22.02-76.13-54.59-95.71l5.22-11.44c2.34-5.53.93-11.83-3.57-16.04L255.86 0l-58.99 52.81c-4.5 4.21-5.9 10.51-3.57 16.04l5.22 11.44c-32.57 19.58-54.59 54.93-54.59 95.72 0 41.75 23.09 77.73 56.94 96.99l-7.85 17.24c-2.19 5.18-1.1 11.07 2.81 15.28l44.05 36.09v19.9l-76.59-53.33C119.02 278.62 92.44 229.19 92.26 176c0-31.08 8.71-61.31 25.2-87.47 3.87-6.16 2.4-13.77-2.59-19.08-5-5.34-13.68-6.2-20.02-2.7C16.32 109.6-22.3 205.3 13.36 295.99c7.07 17.99 17.89 34.38 30.46 49.06l55.97 65.36c4.87 5.69 13.04 7.24 19.65 3.72l79.35-42.23L228 392.23l-47.08 32.78c-1.67-.37-3.23-1.01-5.01-1.01-13.25 0-23.99 10.74-23.99 24 0 13.25 10.74 24 23.99 24 12.1 0 21.69-9.11 23.33-20.76l40.63-28.28v29.95c-9.39 5.57-15.99 15.38-15.99 27.1 0 17.67 14.32 32 31.98 32s31.98-14.33 31.98-32c0-11.71-6.61-21.52-15.99-27.1v-30.15l40.91 28.48C314.41 462.89 324 472 336.09 472c13.25 0 23.99-10.75 23.99-24 0-13.26-10.74-24-23.99-24-1.78 0-3.34.64-5.01 1.01L284 392.23l29.21-20.34 79.35 42.23c6.61 3.52 14.78 1.97 19.65-3.71l52.51-61.31c18.87-22.02 34-47.5 41.25-75.59 21.62-83.66-16.45-167.27-90.16-207.51zm-95.99 110c0 22.3-11.49 41.92-28.83 53.38l-5.65-12.41c-8.75-24.52-8.75-51.04 0-75.56l7.83-17.18c16.07 11.65 26.65 30.45 26.65 51.77zm-127.93 0c0-21.32 10.58-40.12 26.66-51.76l7.83 17.18c8.75 24.52 8.75 51.03 0 75.56l-5.65 12.41c-17.34-11.46-28.84-31.09-28.84-53.39z\"],\n    \"kiss\": [496, 512, [], \"f596\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm136 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm24-156c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"kiss-beam\": [496, 512, [], \"f597\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-39 219.9l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5zM304 396c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-6.1-12.2 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.6-3.6-4.8-16.5 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C290.6 368.7 304 383 304 396zm65-168.1l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.5 8.5-10.9 12-15.1 4.5z\"],\n    \"kiss-wink-heart\": [504, 512, [], \"f598\", \"M501.1 402.5c-8-20.8-31.5-31.5-53.1-25.9l-8.4 2.2-2.3-8.4c-5.9-21.4-27-36.5-49-33-25.2 4-40.6 28.6-34 52.6l22.9 82.6c1.5 5.3 7 8.5 12.4 7.1l83-21.5c24.1-6.3 37.7-31.8 28.5-55.7zm-177.6-4c-5.6-20.3-2.3-42 9-59.7 29.7-46.3 98.7-45.5 127.8 4.3 6.4.1 12.6 1.4 18.6 2.9 10.9-27.9 17.1-58.2 17.1-90C496 119 385 8 248 8S0 119 0 256s111 248 248 248c35.4 0 68.9-7.5 99.4-20.9-.3-.7-23.9-84.6-23.9-84.6zM168 240c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm120 156c0 19.2-28.7 41.5-71.5 44-8.5.8-12.1-11.8-3.6-15.4l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-6-2.5-5.7-12.3 0-14.8l17-7.2c13-5.5 20.8-13.5 20.8-21.5s-7.8-16-20.8-21.5l-17-7.2c-8.8-3.7-4.6-16.6 3.6-15.4 42.8 2.5 71.5 24.8 71.5 44 0 13-13.4 27.3-35.2 36C274.6 368.7 288 383 288 396zm16-179c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S400 181 404 206.2c1.7 11.1-11.3 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 217z\"],\n    \"kiwi-bird\": [576, 512, [], \"f535\", \"M575.81 217.98C572.64 157.41 518.28 112 457.63 112h-9.37c-52.82 0-104.25-16.25-147.74-46.24-41.99-28.96-96.04-41.62-153.21-28.7C129.3 41.12-.08 78.24 0 224c.04 70.95 38.68 132.8 95.99 166.01V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-54.26c15.36 3.96 31.4 6.26 48 6.26 5.44 0 10.68-.73 16-1.18V464c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-59.43c14.24-5.06 27.88-11.39 40.34-19.51C342.07 355.25 393.86 336 448.46 336c25.48 0 16.01-.31 23.05-.78l74.41 136.44c2.86 5.23 8.3 8.34 14.05 8.34 1.31 0 2.64-.16 3.95-.5 7.09-1.8 12.05-8.19 12.05-15.5 0 0 .14-240.24-.16-246.02zM463.97 248c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24zm80 153.25l-39.86-73.08c15.12-5.83 28.73-14.6 39.86-25.98v99.06z\"],\n    \"landmark\": [512, 512, [], \"f66f\", \"M501.62 92.11L267.24 2.04a31.958 31.958 0 0 0-22.47 0L10.38 92.11A16.001 16.001 0 0 0 0 107.09V144c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-36.91c0-6.67-4.14-12.64-10.38-14.98zM64 192v160H48c-8.84 0-16 7.16-16 16v48h448v-48c0-8.84-7.16-16-16-16h-16V192h-64v160h-96V192h-64v160h-96V192H64zm432 256H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"language\": [640, 512, [], \"f1ab\", \"M152.1 236.2c-3.5-12.1-7.8-33.2-7.8-33.2h-.5s-4.3 21.1-7.8 33.2l-11.1 37.5H163zM616 96H336v320h280c13.3 0 24-10.7 24-24V120c0-13.3-10.7-24-24-24zm-24 120c0 6.6-5.4 12-12 12h-11.4c-6.9 23.6-21.7 47.4-42.7 69.9 8.4 6.4 17.1 12.5 26.1 18 5.5 3.4 7.3 10.5 4.1 16.2l-7.9 13.9c-3.4 5.9-10.9 7.8-16.7 4.3-12.6-7.8-24.5-16.1-35.4-24.9-10.9 8.7-22.7 17.1-35.4 24.9-5.8 3.5-13.3 1.6-16.7-4.3l-7.9-13.9c-3.2-5.6-1.4-12.8 4.2-16.2 9.3-5.7 18-11.7 26.1-18-7.9-8.4-14.9-17-21-25.7-4-5.7-2.2-13.6 3.7-17.1l6.5-3.9 7.3-4.3c5.4-3.2 12.4-1.7 16 3.4 5 7 10.8 14 17.4 20.9 13.5-14.2 23.8-28.9 30-43.2H412c-6.6 0-12-5.4-12-12v-16c0-6.6 5.4-12 12-12h64v-16c0-6.6 5.4-12 12-12h16c6.6 0 12 5.4 12 12v16h64c6.6 0 12 5.4 12 12zM0 120v272c0 13.3 10.7 24 24 24h280V96H24c-13.3 0-24 10.7-24 24zm58.9 216.1L116.4 167c1.7-4.9 6.2-8.1 11.4-8.1h32.5c5.1 0 9.7 3.3 11.4 8.1l57.5 169.1c2.6 7.8-3.1 15.9-11.4 15.9h-22.9a12 12 0 0 1-11.5-8.6l-9.4-31.9h-60.2l-9.1 31.8c-1.5 5.1-6.2 8.7-11.5 8.7H70.3c-8.2 0-14-8.1-11.4-15.9z\"],\n    \"laptop\": [640, 512, [], \"f109\", \"M624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-code\": [640, 512, [], \"f5fc\", \"M255.03 261.65c6.25 6.25 16.38 6.25 22.63 0l11.31-11.31c6.25-6.25 6.25-16.38 0-22.63L253.25 192l35.71-35.72c6.25-6.25 6.25-16.38 0-22.63l-11.31-11.31c-6.25-6.25-16.38-6.25-22.63 0l-58.34 58.34c-6.25 6.25-6.25 16.38 0 22.63l58.35 58.34zm96.01-11.3l11.31 11.31c6.25 6.25 16.38 6.25 22.63 0l58.34-58.34c6.25-6.25 6.25-16.38 0-22.63l-58.34-58.34c-6.25-6.25-16.38-6.25-22.63 0l-11.31 11.31c-6.25 6.25-6.25 16.38 0 22.63L386.75 192l-35.71 35.72c-6.25 6.25-6.25 16.38 0 22.63zM624 416H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33.02-17.47-32.77-32H16c-8.8 0-16 7.2-16 16v16c0 35.2 28.8 64 64 64h512c35.2 0 64-28.8 64-64v-16c0-8.8-7.2-16-16-16zM576 48c0-26.4-21.6-48-48-48H112C85.6 0 64 21.6 64 48v336h512V48zm-64 272H128V64h384v256z\"],\n    \"laptop-medical\": [640, 512, [], \"f812\", \"M232 224h56v56a8 8 0 0 0 8 8h48a8 8 0 0 0 8-8v-56h56a8 8 0 0 0 8-8v-48a8 8 0 0 0-8-8h-56v-56a8 8 0 0 0-8-8h-48a8 8 0 0 0-8 8v56h-56a8 8 0 0 0-8 8v48a8 8 0 0 0 8 8zM576 48a48.14 48.14 0 0 0-48-48H112a48.14 48.14 0 0 0-48 48v336h512zm-64 272H128V64h384zm112 96H381.54c-.74 19.81-14.71 32-32.74 32H288c-18.69 0-33-17.47-32.77-32H16a16 16 0 0 0-16 16v16a64.19 64.19 0 0 0 64 64h512a64.19 64.19 0 0 0 64-64v-16a16 16 0 0 0-16-16z\"],\n    \"laugh\": [496, 512, [], \"f599\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 152c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm88 272h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18-8.9 71-69.5 126-142.9 126z\"],\n    \"laugh-beam\": [496, 512, [], \"f59a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm24 199.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.2 7.4-15.8 4.1-15.1-4.5zm-160 0c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-squint\": [496, 512, [], \"f59b\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 161.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 180l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM398.9 306C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"laugh-wink\": [496, 512, [], \"f59c\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm20.1 198.1c4-25.2 34.2-42.1 59.9-42.1s55.9 16.9 59.9 42.1c1.7 11.1-11.4 18.3-19.8 10.8l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L288 217c-8.4 7.4-21.6.3-19.9-10.9zM168 160c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm230.9 146C390 377 329.4 432 256 432h-16c-73.4 0-134-55-142.9-126-1.2-9.5 6.3-18 15.9-18h270c9.6 0 17.1 8.4 15.9 18z\"],\n    \"layer-group\": [512, 512, [], \"f5fd\", \"M12.41 148.02l232.94 105.67c6.8 3.09 14.49 3.09 21.29 0l232.94-105.67c16.55-7.51 16.55-32.52 0-40.03L266.65 2.31a25.607 25.607 0 0 0-21.29 0L12.41 107.98c-16.55 7.51-16.55 32.53 0 40.04zm487.18 88.28l-58.09-26.33-161.64 73.27c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.51 209.97l-58.1 26.33c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 276.3c16.55-7.5 16.55-32.5 0-40zm0 127.8l-57.87-26.23-161.86 73.37c-7.56 3.43-15.59 5.17-23.86 5.17s-16.29-1.74-23.86-5.17L70.29 337.87 12.41 364.1c-16.55 7.5-16.55 32.5 0 40l232.94 105.59c6.8 3.08 14.49 3.08 21.29 0L499.59 404.1c16.55-7.5 16.55-32.5 0-40z\"],\n    \"leaf\": [576, 512, [], \"f06c\", \"M546.2 9.7c-5.6-12.5-21.6-13-28.3-1.2C486.9 62.4 431.4 96 368 96h-80C182 96 96 182 96 288c0 7 .8 13.7 1.5 20.5C161.3 262.8 253.4 224 384 224c8.8 0 16 7.2 16 16s-7.2 16-16 16C132.6 256 26 410.1 2.4 468c-6.6 16.3 1.2 34.9 17.5 41.6 16.4 6.8 35-1.1 41.8-17.3 1.5-3.6 20.9-47.9 71.9-90.6 32.4 43.9 94 85.8 174.9 77.2C465.5 467.5 576 326.7 576 154.3c0-50.2-10.8-102.2-29.8-144.6z\"],\n    \"lemon\": [512, 512, [], \"f094\", \"M489.038 22.963C465.944-.13 434.648-5.93 413.947 6.129c-58.906 34.312-181.25-53.077-321.073 86.746S40.441 355.041 6.129 413.945c-12.059 20.702-6.26 51.999 16.833 75.093 23.095 23.095 54.392 28.891 75.095 16.832 58.901-34.31 181.246 53.079 321.068-86.743S471.56 156.96 505.871 98.056c12.059-20.702 6.261-51.999-16.833-75.093zM243.881 95.522c-58.189 14.547-133.808 90.155-148.358 148.358-1.817 7.27-8.342 12.124-15.511 12.124-1.284 0-2.59-.156-3.893-.481-8.572-2.144-13.784-10.83-11.642-19.403C81.901 166.427 166.316 81.93 236.119 64.478c8.575-2.143 17.261 3.069 19.403 11.642s-3.069 17.259-11.641 19.402z\"],\n    \"less-than\": [384, 512, [], \"f536\", \"M365.46 357.74L147.04 255.89l218.47-101.88c16.02-7.47 22.95-26.51 15.48-42.53l-13.52-29C360 66.46 340.96 59.53 324.94 67L18.48 209.91a32.014 32.014 0 0 0-18.48 29v34.24c0 12.44 7.21 23.75 18.48 29l306.31 142.83c16.06 7.49 35.15.54 42.64-15.52l13.56-29.08c7.49-16.06.54-35.15-15.53-42.64z\"],\n    \"less-than-equal\": [448, 512, [], \"f537\", \"M54.98 214.2l301.41 119.87c18.39 6.03 38.71-2.54 45.38-19.15l12.09-30.08c6.68-16.61-2.82-34.97-21.21-41l-175.44-68.05 175.56-68.09c18.29-6 27.74-24.27 21.1-40.79l-12.03-29.92c-6.64-16.53-26.86-25.06-45.15-19.06L54.98 137.89C41.21 142.41 32 154.5 32 168.07v15.96c0 13.56 9.21 25.65 22.98 30.17zM424 400H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h400c13.25 0 24-10.75 24-24v-48c0-13.26-10.75-24-24-24z\"],\n    \"level-down-alt\": [320, 512, [], \"f3be\", \"M313.553 392.331L209.587 504.334c-9.485 10.214-25.676 10.229-35.174 0L70.438 392.331C56.232 377.031 67.062 352 88.025 352H152V80H68.024a11.996 11.996 0 0 1-8.485-3.515l-56-56C-4.021 12.926 1.333 0 12.024 0H208c13.255 0 24 10.745 24 24v328h63.966c20.878 0 31.851 24.969 17.587 40.331z\"],\n    \"level-up-alt\": [320, 512, [], \"f3bf\", \"M313.553 119.669L209.587 7.666c-9.485-10.214-25.676-10.229-35.174 0L70.438 119.669C56.232 134.969 67.062 160 88.025 160H152v272H68.024a11.996 11.996 0 0 0-8.485 3.515l-56 56C-4.021 499.074 1.333 512 12.024 512H208c13.255 0 24-10.745 24-24V160h63.966c20.878 0 31.851-24.969 17.587-40.331z\"],\n    \"life-ring\": [512, 512, [], \"f1cd\", \"M256 8C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm173.696 119.559l-63.399 63.399c-10.987-18.559-26.67-34.252-45.255-45.255l63.399-63.399a218.396 218.396 0 0 1 45.255 45.255zM256 352c-53.019 0-96-42.981-96-96s42.981-96 96-96 96 42.981 96 96-42.981 96-96 96zM127.559 82.304l63.399 63.399c-18.559 10.987-34.252 26.67-45.255 45.255l-63.399-63.399a218.372 218.372 0 0 1 45.255-45.255zM82.304 384.441l63.399-63.399c10.987 18.559 26.67 34.252 45.255 45.255l-63.399 63.399a218.396 218.396 0 0 1-45.255-45.255zm302.137 45.255l-63.399-63.399c18.559-10.987 34.252-26.67 45.255-45.255l63.399 63.399a218.403 218.403 0 0 1-45.255 45.255z\"],\n    \"lightbulb\": [352, 512, [], \"f0eb\", \"M96.06 454.35c.01 6.29 1.87 12.45 5.36 17.69l17.09 25.69a31.99 31.99 0 0 0 26.64 14.28h61.71a31.99 31.99 0 0 0 26.64-14.28l17.09-25.69a31.989 31.989 0 0 0 5.36-17.69l.04-38.35H96.01l.05 38.35zM0 176c0 44.37 16.45 84.85 43.56 115.78 16.52 18.85 42.36 58.23 52.21 91.45.04.26.07.52.11.78h160.24c.04-.26.07-.51.11-.78 9.85-33.22 35.69-72.6 52.21-91.45C335.55 260.85 352 220.37 352 176 352 78.61 272.91-.3 175.45 0 73.44.31 0 82.97 0 176zm176-80c-44.11 0-80 35.89-80 80 0 8.84-7.16 16-16 16s-16-7.16-16-16c0-61.76 50.24-112 112-112 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"link\": [512, 512, [], \"f0c1\", \"M326.612 185.391c59.747 59.809 58.927 155.698.36 214.59-.11.12-.24.25-.36.37l-67.2 67.2c-59.27 59.27-155.699 59.262-214.96 0-59.27-59.26-59.27-155.7 0-214.96l37.106-37.106c9.84-9.84 26.786-3.3 27.294 10.606.648 17.722 3.826 35.527 9.69 52.721 1.986 5.822.567 12.262-3.783 16.612l-13.087 13.087c-28.026 28.026-28.905 73.66-1.155 101.96 28.024 28.579 74.086 28.749 102.325.51l67.2-67.19c28.191-28.191 28.073-73.757 0-101.83-3.701-3.694-7.429-6.564-10.341-8.569a16.037 16.037 0 0 1-6.947-12.606c-.396-10.567 3.348-21.456 11.698-29.806l21.054-21.055c5.521-5.521 14.182-6.199 20.584-1.731a152.482 152.482 0 0 1 20.522 17.197zM467.547 44.449c-59.261-59.262-155.69-59.27-214.96 0l-67.2 67.2c-.12.12-.25.25-.36.37-58.566 58.892-59.387 154.781.36 214.59a152.454 152.454 0 0 0 20.521 17.196c6.402 4.468 15.064 3.789 20.584-1.731l21.054-21.055c8.35-8.35 12.094-19.239 11.698-29.806a16.037 16.037 0 0 0-6.947-12.606c-2.912-2.005-6.64-4.875-10.341-8.569-28.073-28.073-28.191-73.639 0-101.83l67.2-67.19c28.239-28.239 74.3-28.069 102.325.51 27.75 28.3 26.872 73.934-1.155 101.96l-13.087 13.087c-4.35 4.35-5.769 10.79-3.783 16.612 5.864 17.194 9.042 34.999 9.69 52.721.509 13.906 17.454 20.446 27.294 10.606l37.106-37.106c59.271-59.259 59.271-155.699.001-214.959z\"],\n    \"lira-sign\": [384, 512, [], \"f195\", \"M371.994 256h-48.019C317.64 256 312 260.912 312 267.246 312 368 230.179 416 144 416V256.781l134.603-29.912A12 12 0 0 0 288 215.155v-40.976c0-7.677-7.109-13.38-14.603-11.714L144 191.219V160.78l134.603-29.912A12 12 0 0 0 288 119.154V78.179c0-7.677-7.109-13.38-14.603-11.714L144 95.219V44c0-6.627-5.373-12-12-12H76c-6.627 0-12 5.373-12 12v68.997L9.397 125.131A12 12 0 0 0 0 136.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 178.558v30.439L9.397 221.131A12 12 0 0 0 0 232.845v40.976c0 7.677 7.109 13.38 14.603 11.714L64 274.558V468c0 6.627 5.373 12 12 12h79.583c134.091 0 223.255-77.834 228.408-211.592.261-6.782-5.211-12.408-11.997-12.408z\"],\n    \"list\": [512, 512, [], \"f03a\", \"M80 368H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm0-320H16A16 16 0 0 0 0 64v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16V64a16 16 0 0 0-16-16zm0 160H16a16 16 0 0 0-16 16v64a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-64a16 16 0 0 0-16-16zm416 176H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"list-alt\": [512, 512, [], \"f022\", \"M464 480H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h416c26.51 0 48 21.49 48 48v352c0 26.51-21.49 48-48 48zM128 120c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm0 96c-22.091 0-40 17.909-40 40s17.909 40 40 40 40-17.909 40-40-17.909-40-40-40zm288-136v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12zm0 96v-32c0-6.627-5.373-12-12-12H204c-6.627 0-12 5.373-12 12v32c0 6.627 5.373 12 12 12h200c6.627 0 12-5.373 12-12z\"],\n    \"list-ol\": [512, 512, [], \"f0cb\", \"M61.77 401l17.5-20.15a19.92 19.92 0 0 0 5.07-14.19v-3.31C84.34 356 80.5 352 73 352H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8h22.83a157.41 157.41 0 0 0-11 12.31l-5.61 7c-4 5.07-5.25 10.13-2.8 14.88l1.05 1.93c3 5.76 6.29 7.88 12.25 7.88h4.73c10.33 0 15.94 2.44 15.94 9.09 0 4.72-4.2 8.22-14.36 8.22a41.54 41.54 0 0 1-15.47-3.12c-6.49-3.88-11.74-3.5-15.6 3.12l-5.59 9.31c-3.72 6.13-3.19 11.72 2.63 15.94 7.71 4.69 20.38 9.44 37 9.44 34.16 0 48.5-22.75 48.5-44.12-.03-14.38-9.12-29.76-28.73-34.88zM496 224H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h64a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H64V40a8 8 0 0 0-8-8H32a8 8 0 0 0-7.14 4.42l-8 16A8 8 0 0 0 24 64h8v64H16a8 8 0 0 0-8 8v16a8 8 0 0 0 8 8zm-3.91 160H80a8 8 0 0 0 8-8v-16a8 8 0 0 0-8-8H41.32c3.29-10.29 48.34-18.68 48.34-56.44 0-29.06-25-39.56-44.47-39.56-21.36 0-33.8 10-40.46 18.75-4.37 5.59-3 10.84 2.8 15.37l8.58 6.88c5.61 4.56 11 2.47 16.12-2.44a13.44 13.44 0 0 1 9.46-3.84c3.33 0 9.28 1.56 9.28 8.75C51 248.19 0 257.31 0 304.59v4C0 316 5.08 320 12.09 320z\"],\n    \"list-ul\": [512, 512, [], \"f0ca\", \"M48 48a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm0 160a48 48 0 1 0 48 48 48 48 0 0 0-48-48zm448 16H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H176a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h320a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"location-arrow\": [512, 512, [], \"f124\", \"M444.52 3.52L28.74 195.42c-47.97 22.39-31.98 92.75 19.19 92.75h175.91v175.91c0 51.17 70.36 67.17 92.75 19.19l191.9-415.78c15.99-38.39-25.59-79.97-63.97-63.97z\"],\n    \"lock\": [448, 512, [], \"f023\", \"M400 224h-24v-72C376 68.2 307.8 0 224 0S72 68.2 72 152v72H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48zm-104 0H152v-72c0-39.7 32.3-72 72-72s72 32.3 72 72v72z\"],\n    \"lock-open\": [576, 512, [], \"f3c1\", \"M423.5 0C339.5.3 272 69.5 272 153.5V224H48c-26.5 0-48 21.5-48 48v192c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V272c0-26.5-21.5-48-48-48h-48v-71.1c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v80c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-80C576 68 507.5-.3 423.5 0z\"],\n    \"long-arrow-alt-down\": [256, 512, [], \"f309\", \"M168 345.941V44c0-6.627-5.373-12-12-12h-56c-6.627 0-12 5.373-12 12v301.941H41.941c-21.382 0-32.09 25.851-16.971 40.971l86.059 86.059c9.373 9.373 24.569 9.373 33.941 0l86.059-86.059c15.119-15.119 4.411-40.971-16.971-40.971H168z\"],\n    \"long-arrow-alt-left\": [448, 512, [], \"f30a\", \"M134.059 296H436c6.627 0 12-5.373 12-12v-56c0-6.627-5.373-12-12-12H134.059v-46.059c0-21.382-25.851-32.09-40.971-16.971L7.029 239.029c-9.373 9.373-9.373 24.569 0 33.941l86.059 86.059c15.119 15.119 40.971 4.411 40.971-16.971V296z\"],\n    \"long-arrow-alt-right\": [448, 512, [], \"f30b\", \"M313.941 216H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h301.941v46.059c0 21.382 25.851 32.09 40.971 16.971l86.059-86.059c9.373-9.373 9.373-24.569 0-33.941l-86.059-86.059c-15.119-15.119-40.971-4.411-40.971 16.971V216z\"],\n    \"long-arrow-alt-up\": [256, 512, [], \"f30c\", \"M88 166.059V468c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12V166.059h46.059c21.382 0 32.09-25.851 16.971-40.971l-86.059-86.059c-9.373-9.373-24.569-9.373-33.941 0l-86.059 86.059c-15.119 15.119-4.411 40.971 16.971 40.971H88z\"],\n    \"low-vision\": [576, 512, [], \"f2a8\", \"M569.344 231.631C512.96 135.949 407.81 72 288 72c-28.468 0-56.102 3.619-82.451 10.409L152.778 10.24c-7.601-10.858-22.564-13.5-33.423-5.9l-13.114 9.178c-10.86 7.601-13.502 22.566-5.9 33.426l43.131 58.395C89.449 131.73 40.228 174.683 6.682 231.581c-.01.017-.023.033-.034.05-8.765 14.875-8.964 33.528 0 48.739 38.5 65.332 99.742 115.862 172.859 141.349L55.316 244.302A272.194 272.194 0 0 1 83.61 208.39l119.4 170.58h.01l40.63 58.04a330.055 330.055 0 0 0 78.94 1.17l-189.98-271.4a277.628 277.628 0 0 1 38.777-21.563l251.836 356.544c7.601 10.858 22.564 13.499 33.423 5.9l13.114-9.178c10.86-7.601 13.502-22.567 5.9-33.426l-43.12-58.377-.007-.009c57.161-27.978 104.835-72.04 136.81-126.301a47.938 47.938 0 0 0 .001-48.739zM390.026 345.94l-19.066-27.23c24.682-32.567 27.711-76.353 8.8-111.68v.03c0 23.65-19.17 42.82-42.82 42.82-23.828 0-42.82-19.349-42.82-42.82 0-23.65 19.17-42.82 42.82-42.82h.03c-24.75-13.249-53.522-15.643-79.51-7.68l-19.068-27.237C253.758 123.306 270.488 120 288 120c75.162 0 136 60.826 136 136 0 34.504-12.833 65.975-33.974 89.94z\"],\n    \"luggage-cart\": [640, 512, [], \"f59d\", \"M224 320h32V96h-32c-17.67 0-32 14.33-32 32v160c0 17.67 14.33 32 32 32zm352-32V128c0-17.67-14.33-32-32-32h-32v224h32c17.67 0 32-14.33 32-32zm48 96H128V16c0-8.84-7.16-16-16-16H16C7.16 0 0 7.16 0 16v32c0 8.84 7.16 16 16 16h48v368c0 8.84 7.16 16 16 16h82.94c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16h197.88c-1.79 5.03-2.94 10.36-2.94 16 0 26.51 21.49 48 48 48s48-21.49 48-48c0-5.64-1.15-10.97-2.94-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM480 96V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v272h192V96zm-48 0h-96V48h96v48z\"],\n    \"magic\": [512, 512, [], \"f0d0\", \"M224 96l16-32 32-16-32-16-16-32-16 32-32 16 32 16 16 32zM80 160l26.66-53.33L160 80l-53.34-26.67L80 0 53.34 53.33 0 80l53.34 26.67L80 160zm352 128l-26.66 53.33L352 368l53.34 26.67L432 448l26.66-53.33L512 368l-53.34-26.67L432 288zm70.62-193.77L417.77 9.38C411.53 3.12 403.34 0 395.15 0c-8.19 0-16.38 3.12-22.63 9.38L9.38 372.52c-12.5 12.5-12.5 32.76 0 45.25l84.85 84.85c6.25 6.25 14.44 9.37 22.62 9.37 8.19 0 16.38-3.12 22.63-9.37l363.14-363.15c12.5-12.48 12.5-32.75 0-45.24zM359.45 203.46l-50.91-50.91 86.6-86.6 50.91 50.91-86.6 86.6z\"],\n    \"magnet\": [512, 512, [], \"f076\", \"M164.07 148.1H12a12 12 0 0 1-12-12v-80a36 36 0 0 1 36-36h104a36 36 0 0 1 36 36v80a11.89 11.89 0 0 1-11.93 12zm347.93-12V56a36 36 0 0 0-36-36H372a36 36 0 0 0-36 36v80a12 12 0 0 0 12 12h152a11.89 11.89 0 0 0 12-11.9zm-164 44a12 12 0 0 0-12 12v52c0 128.1-160 127.9-160 0v-52a12 12 0 0 0-12-12H12.1a12 12 0 0 0-12 12.1c.1 21.4.6 40.3 0 53.3 0 150.6 136.17 246.6 256.75 246.6s255-96 255-246.7c-.6-12.8-.2-33 0-53.2a12 12 0 0 0-12-12.1z\"],\n    \"mail-bulk\": [576, 512, [], \"f674\", \"M160 448c-25.6 0-51.2-22.4-64-32-64-44.8-83.2-60.8-96-70.4V480c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V345.6c-12.8 9.6-32 25.6-96 70.4-12.8 9.6-38.4 32-64 32zm128-192H32c-17.67 0-32 14.33-32 32v16c25.6 19.2 22.4 19.2 115.2 86.4 9.6 6.4 28.8 25.6 44.8 25.6s35.2-19.2 44.8-22.4c92.8-67.2 89.6-67.2 115.2-86.4V288c0-17.67-14.33-32-32-32zm256-96H224c-17.67 0-32 14.33-32 32v32h96c33.21 0 60.59 25.42 63.71 57.82l.29-.22V416h192c17.67 0 32-14.33 32-32V192c0-17.67-14.33-32-32-32zm-32 128h-64v-64h64v64zm-352-96c0-35.29 28.71-64 64-64h224V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v192h96v-32z\"],\n    \"male\": [192, 512, [], \"f183\", \"M96 0c35.346 0 64 28.654 64 64s-28.654 64-64 64-64-28.654-64-64S60.654 0 96 0m48 144h-11.36c-22.711 10.443-49.59 10.894-73.28 0H48c-26.51 0-48 21.49-48 48v136c0 13.255 10.745 24 24 24h16v136c0 13.255 10.745 24 24 24h64c13.255 0 24-10.745 24-24V352h16c13.255 0 24-10.745 24-24V192c0-26.51-21.49-48-48-48z\"],\n    \"map\": [576, 512, [], \"f279\", \"M0 117.66v346.32c0 11.32 11.43 19.06 21.94 14.86L160 416V32L20.12 87.95A32.006 32.006 0 0 0 0 117.66zM192 416l192 64V96L192 32v384zM554.06 33.16L416 96v384l139.88-55.95A31.996 31.996 0 0 0 576 394.34V48.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked\": [576, 512, [], \"f59f\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marked-alt\": [576, 512, [], \"f5a0\", \"M288 0c-69.59 0-126 56.41-126 126 0 56.26 82.35 158.8 113.9 196.02 6.39 7.54 17.82 7.54 24.2 0C331.65 284.8 414 182.26 414 126 414 56.41 357.59 0 288 0zm0 168c-23.2 0-42-18.8-42-42s18.8-42 42-42 42 18.8 42 42-18.8 42-42 42zM20.12 215.95A32.006 32.006 0 0 0 0 245.66v250.32c0 11.32 11.43 19.06 21.94 14.86L160 448V214.92c-8.84-15.98-16.07-31.54-21.25-46.42L20.12 215.95zM288 359.67c-14.07 0-27.38-6.18-36.51-16.96-19.66-23.2-40.57-49.62-59.49-76.72v182l192 64V266c-18.92 27.09-39.82 53.52-59.49 76.72-9.13 10.77-22.44 16.95-36.51 16.95zm266.06-198.51L416 224v288l139.88-55.95A31.996 31.996 0 0 0 576 426.34V176.02c0-11.32-11.43-19.06-21.94-14.86z\"],\n    \"map-marker\": [384, 512, [], \"f041\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0z\"],\n    \"map-marker-alt\": [384, 512, [], \"f3c5\", \"M172.268 501.67C26.97 291.031 0 269.413 0 192 0 85.961 85.961 0 192 0s192 85.961 192 192c0 77.413-26.97 99.031-172.268 309.67-9.535 13.774-29.93 13.773-39.464 0zM192 272c44.183 0 80-35.817 80-80s-35.817-80-80-80-80 35.817-80 80 35.817 80 80 80z\"],\n    \"map-pin\": [288, 512, [], \"f276\", \"M112 316.94v156.69l22.02 33.02c4.75 7.12 15.22 7.12 19.97 0L176 473.63V316.94c-10.39 1.92-21.06 3.06-32 3.06s-21.61-1.14-32-3.06zM144 0C64.47 0 0 64.47 0 144s64.47 144 144 144 144-64.47 144-144S223.53 0 144 0zm0 76c-37.5 0-68 30.5-68 68 0 6.62-5.38 12-12 12s-12-5.38-12-12c0-50.73 41.28-92 92-92 6.62 0 12 5.38 12 12s-5.38 12-12 12z\"],\n    \"map-signs\": [512, 512, [], \"f277\", \"M507.31 84.69L464 41.37c-6-6-14.14-9.37-22.63-9.37H288V16c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v16H56c-13.25 0-24 10.75-24 24v80c0 13.25 10.75 24 24 24h385.37c8.49 0 16.62-3.37 22.63-9.37l43.31-43.31c6.25-6.26 6.25-16.38 0-22.63zM224 496c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V384h-64v112zm232-272H288v-32h-64v32H70.63c-8.49 0-16.62 3.37-22.63 9.37L4.69 276.69c-6.25 6.25-6.25 16.38 0 22.63L48 342.63c6 6 14.14 9.37 22.63 9.37H456c13.25 0 24-10.75 24-24v-80c0-13.25-10.75-24-24-24z\"],\n    \"marker\": [512, 512, [], \"f5a1\", \"M93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l75.4-75.4-128.02-128.02-75.4 75.4zM485.49 26.51c-35.35-35.35-92.67-35.35-128.02 0l-21.76 21.76-36.56-36.55c-15.62-15.62-40.95-15.62-56.56 0L138.47 115.84c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0l87.15-87.15 19.59 19.59L191.98 192 320 320.02l165.49-165.49c35.35-35.35 35.35-92.66 0-128.02z\"],\n    \"mars\": [384, 512, [], \"f222\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c0-6.6-5.4-12-12-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-double\": [512, 512, [], \"f227\", \"M340 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C198.5 72.1 172.2 64 144 64 64.5 64 0 128.5 0 208s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.5 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 288c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80zm356-128.1h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7c-18.2-11.4-39-18.9-61.5-21.3-2.1 21.8-8.2 43.3-18.4 63.3 1.1 0 2.2-.1 3.2-.1 44.1 0 80 35.9 80 80s-35.9 80-80 80-80-35.9-80-80c0-1.1 0-2.2.1-3.2-20 10.2-41.5 16.4-63.3 18.4C168.4 455.6 229.6 512 304 512c79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12v-79c0-6.7-5.4-12.1-12-12.1z\"],\n    \"mars-stroke\": [384, 512, [], \"f229\", \"M372 64h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-17.5 17.5-14.1-14.1c-4.7-4.7-12.3-4.7-17 0L224.5 133c-4.7 4.7-4.7 12.3 0 17l14.1 14.1-18 18c-22.2-14-48.5-22.1-76.7-22.1C64.5 160 0 224.5 0 304s64.5 144 144 144 144-64.5 144-144c0-28.2-8.1-54.5-22.1-76.7l18-18 14.1 14.1c4.7 4.7 12.3 4.7 17 0l28.3-28.3c4.7-4.7 4.7-12.3 0-17L329.2 164l17.5-17.5 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V76c-.1-6.6-5.5-12-12.1-12zM144 384c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"mars-stroke-h\": [480, 512, [], \"f22b\", \"M476.2 247.5l-55.9-55.9c-7.6-7.6-20.5-2.2-20.5 8.5V224H376v-20c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12v20h-27.6c-5.8-25.6-18.7-49.9-38.6-69.8C189.6 98 98.4 98 42.2 154.2c-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 19.9-19.9 32.8-44.2 38.6-69.8H312v20c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-20h23.9v23.9c0 10.7 12.9 16 20.5 8.5l55.9-55.9c4.6-4.7 4.6-12.3-.1-17zm-275.6 65.1c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mars-stroke-v\": [288, 512, [], \"f22a\", \"M245.8 234.2c-19.9-19.9-44.2-32.8-69.8-38.6v-25.4h20c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-20V81.4h23.9c10.7 0 16-12.9 8.5-20.5L152.5 5.1c-4.7-4.7-12.3-4.7-17 0L79.6 61c-7.6 7.6-2.2 20.5 8.5 20.5H112v24.7H92c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h20v25.4c-25.6 5.8-49.9 18.7-69.8 38.6-56.2 56.2-56.2 147.4 0 203.6 56.2 56.2 147.4 56.2 203.6 0 56.3-56.2 56.3-147.4 0-203.6zm-45.2 158.4c-31.2 31.2-81.9 31.2-113.1 0-31.2-31.2-31.2-81.9 0-113.1 31.2-31.2 81.9-31.2 113.1 0 31.2 31.1 31.2 81.9 0 113.1z\"],\n    \"mask\": [640, 512, [], \"f6fa\", \"M320.67 64c-442.6 0-357.57 384-158.46 384 39.9 0 77.47-20.69 101.42-55.86l25.73-37.79c15.66-22.99 46.97-22.99 62.63 0l25.73 37.79C401.66 427.31 439.23 448 479.13 448c189.86 0 290.63-384-158.46-384zM184 308.36c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05zm272 0c-41.06 0-67.76-25.66-80.08-41.05-5.23-6.53-5.23-16.09 0-22.63 12.32-15.4 39.01-41.05 80.08-41.05s67.76 25.66 80.08 41.05c5.23 6.53 5.23 16.09 0 22.63-12.32 15.4-39.02 41.05-80.08 41.05z\"],\n    \"medal\": [512, 512, [], \"f5a2\", \"M223.75 130.75L154.62 15.54A31.997 31.997 0 0 0 127.18 0H16.03C3.08 0-4.5 14.57 2.92 25.18l111.27 158.96c29.72-27.77 67.52-46.83 109.56-53.39zM495.97 0H384.82c-11.24 0-21.66 5.9-27.44 15.54l-69.13 115.21c42.04 6.56 79.84 25.62 109.56 53.38L509.08 25.18C516.5 14.57 508.92 0 495.97 0zM256 160c-97.2 0-176 78.8-176 176s78.8 176 176 176 176-78.8 176-176-78.8-176-176-176zm92.52 157.26l-37.93 36.96 8.97 52.22c1.6 9.36-8.26 16.51-16.65 12.09L256 393.88l-46.9 24.65c-8.4 4.45-18.25-2.74-16.65-12.09l8.97-52.22-37.93-36.96c-6.82-6.64-3.05-18.23 6.35-19.59l52.43-7.64 23.43-47.52c2.11-4.28 6.19-6.39 10.28-6.39 4.11 0 8.22 2.14 10.33 6.39l23.43 47.52 52.43 7.64c9.4 1.36 13.17 12.95 6.35 19.59z\"],\n    \"medkit\": [512, 512, [], \"f0fa\", \"M96 480h320V128h-32V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v48H96v352zm96-384h128v32H192V96zm320 80v256c0 26.51-21.49 48-48 48h-16V128h16c26.51 0 48 21.49 48 48zM64 480H48c-26.51 0-48-21.49-48-48V176c0-26.51 21.49-48 48-48h16v352zm288-208v32c0 8.837-7.163 16-16 16h-48v48c0 8.837-7.163 16-16 16h-32c-8.837 0-16-7.163-16-16v-48h-48c-8.837 0-16-7.163-16-16v-32c0-8.837 7.163-16 16-16h48v-48c0-8.837 7.163-16 16-16h32c8.837 0 16 7.163 16 16v48h48c8.837 0 16 7.163 16 16z\"],\n    \"meh\": [496, 512, [], \"f11a\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm176 192H152c-21.2 0-21.2-32 0-32h192c21.2 0 21.2 32 0 32zm-16-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-blank\": [496, 512, [], \"f5a4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm-80 232c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm160 0c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"meh-rolling-eyes\": [496, 512, [], \"f5a5\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM88 224c0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64s-64-28.7-64-64zm224 176H184c-21.2 0-21.2-32 0-32h128c21.2 0 21.2 32 0 32zm32-112c-35.3 0-64-28.7-64-64 0-24.3 13.7-45.2 33.6-56-.7 2.6-1.6 5.2-1.6 8 0 17.7 14.3 32 32 32s32-14.3 32-32c0-2.8-.9-5.4-1.6-8 19.9 10.8 33.6 31.7 33.6 56 0 35.3-28.7 64-64 64z\"],\n    \"memory\": [640, 512, [], \"f538\", \"M640 130.94V96c0-17.67-14.33-32-32-32H32C14.33 64 0 78.33 0 96v34.94c18.6 6.61 32 24.19 32 45.06s-13.4 38.45-32 45.06V320h640v-98.94c-18.6-6.61-32-24.19-32-45.06s13.4-38.45 32-45.06zM224 256h-64V128h64v128zm128 0h-64V128h64v128zm128 0h-64V128h64v128zM0 448h64v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h128v-26.67c0-8.84 7.16-16 16-16s16 7.16 16 16V448h64v-96H0v96z\"],\n    \"menorah\": [640, 512, [], \"f676\", \"M144 128h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm192 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm96 0h-32c-8.84 0-16 7.16-16 16v144h64V144c0-8.84-7.16-16-16-16zm80-32c17.67 0 32-14.33 32-32S608 0 608 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S512 0 512 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S416 0 416 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S320 0 320 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S224 0 224 0s-32 46.33-32 64 14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S128 0 128 0 96 46.33 96 64s14.33 32 32 32zm-96 0c17.67 0 32-14.33 32-32S32 0 32 0 0 46.33 0 64s14.33 32 32 32zm544 192c0 17.67-14.33 32-32 32H352V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v176H96c-17.67 0-32-14.33-32-32V144c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v144c0 53.02 42.98 96 96 96h192v64H112c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16H352v-64h192c53.02 0 96-42.98 96-96V144c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v144z\"],\n    \"mercury\": [288, 512, [], \"f223\", \"M288 208c0-44.2-19.9-83.7-51.2-110.1 2.5-1.8 4.9-3.8 7.2-5.8 24.7-21.2 39.8-48.8 43.2-78.8.9-7.1-4.7-13.3-11.9-13.3h-40.5C229 0 224.1 4.1 223 9.8c-2.4 12.5-9.6 24.3-20.7 33.8C187 56.8 166.3 64 144 64s-43-7.2-58.4-20.4C74.5 34.1 67.4 22.3 64.9 9.8 63.8 4.1 58.9 0 53.2 0H12.7C5.5 0-.1 6.2.8 13.3 4.2 43.4 19.2 71 44 92.2c2.3 2 4.7 3.9 7.2 5.8C19.9 124.3 0 163.8 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"meteor\": [512, 512, [], \"f753\", \"M491.2.7C452.5 12.3 379.4 35 303.5 62c-2.1-7-4-13.5-5.6-18.6-3-9.7-13.9-14.2-22.9-9.5C232.6 56 122.2 116.5 60.6 176.4c-1.1 1-2.5 2-3.5 3C19 217.4 0 267.3 0 317.2 0 367 19 416.9 57 455c38 38 87.9 57.1 137.8 57 49.9 0 99.8-19 137.9-57.1 1-1 2-2.4 3-3.5 59.8-61.6 120.4-172.1 142.5-214.4 4.7-9 .2-19.9-9.5-22.9-5.2-1.6-11.6-3.5-18.6-5.6 27-76 49.7-149 61.3-187.7C515 8.4 503.6-3 491.2.7zM192 448c-70.7 0-128-57.3-128-128s57.3-128 128-128 128 57.3 128 128-57.3 128-128 128zm-32-192c-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32-14.3-32-32-32zm48 96c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16z\"],\n    \"microchip\": [512, 512, [], \"f2db\", \"M416 48v416c0 26.51-21.49 48-48 48H144c-26.51 0-48-21.49-48-48V48c0-26.51 21.49-48 48-48h224c26.51 0 48 21.49 48 48zm96 58v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42V88h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zm0 96v12a6 6 0 0 1-6 6h-18v6a6 6 0 0 1-6 6h-42v-48h42a6 6 0 0 1 6 6v6h18a6 6 0 0 1 6 6zM30 376h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6zm0-96h42v48H30a6 6 0 0 1-6-6v-6H6a6 6 0 0 1-6-6v-12a6 6 0 0 1 6-6h18v-6a6 6 0 0 1 6-6z\"],\n    \"microphone\": [352, 512, [], \"f130\", \"M176 352c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96zm160-160h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16z\"],\n    \"microphone-alt\": [352, 512, [], \"f3c9\", \"M336 192h-16c-8.84 0-16 7.16-16 16v48c0 74.8-64.49 134.82-140.79 127.38C96.71 376.89 48 317.11 48 250.3V208c0-8.84-7.16-16-16-16H16c-8.84 0-16 7.16-16 16v40.16c0 89.64 63.97 169.55 152 181.69V464H96c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16h-56v-33.77C285.71 418.47 352 344.9 352 256v-48c0-8.84-7.16-16-16-16zM176 352c53.02 0 96-42.98 96-96h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H272c0-53.02-42.98-96-96-96S80 42.98 80 96v160c0 53.02 42.98 96 96 96z\"],\n    \"microphone-alt-slash\": [640, 512, [], \"f539\", \"M633.82 458.1L476.26 336.33C488.74 312.21 496 284.98 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67h-43.67l-41.4-32H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416v-32h-85.33c-5.89 0-10.67-3.58-10.67-8v-16c0-4.42 4.78-8 10.67-8H416c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.78c11.71-1.62 23.1-4.28 33.96-8.08l-50.4-38.96c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microphone-slash\": [640, 512, [], \"f131\", \"M633.82 458.1l-157.8-121.96C488.61 312.13 496 285.01 496 256v-48c0-8.84-7.16-16-16-16h-16c-8.84 0-16 7.16-16 16v48c0 17.92-3.96 34.8-10.72 50.2l-26.55-20.52c3.1-9.4 5.28-19.22 5.28-29.67V96c0-53.02-42.98-96-96-96s-96 42.98-96 96v45.36L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM400 464h-56v-33.77c11.66-1.6 22.85-4.54 33.67-8.31l-50.11-38.73c-6.71.4-13.41.87-20.35.2-55.85-5.45-98.74-48.63-111.18-101.85L144 241.31v6.85c0 89.64 63.97 169.55 152 181.69V464h-56c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h160c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16z\"],\n    \"microscope\": [512, 512, [], \"f610\", \"M160 320h12v16c0 8.84 7.16 16 16 16h40c8.84 0 16-7.16 16-16v-16h12c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32V16c0-8.84-7.16-16-16-16h-64c-8.84 0-16 7.16-16 16v16c-17.67 0-32 14.33-32 32v224c0 17.67 14.33 32 32 32zm304 128h-1.29C493.24 413.99 512 369.2 512 320c0-105.88-86.12-192-192-192v64c70.58 0 128 57.42 128 128s-57.42 128-128 128H48c-26.51 0-48 21.49-48 48 0 8.84 7.16 16 16 16h480c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48zm-360-32h208c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8H104c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8z\"],\n    \"minus\": [448, 512, [], \"f068\", \"M416 208H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h384c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"minus-circle\": [512, 512, [], \"f056\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zM124 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H124z\"],\n    \"minus-square\": [448, 512, [], \"f146\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM92 296c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h264c6.6 0 12 5.4 12 12v56c0 6.6-5.4 12-12 12H92z\"],\n    \"mitten\": [448, 512, [], \"f7b5\", \"M368 416H48c-8.8 0-16 7.2-16 16v64c0 8.8 7.2 16 16 16h320c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16zm57-209.1c-27.2-22.6-67.5-19-90.1 8.2l-20.9 25-29.6-128.4c-18-77.5-95.4-125.9-172.8-108C34.2 21.6-14.2 98.9 3.7 176.4L51.6 384h309l72.5-87c22.7-27.2 19-67.5-8.1-90.1z\"],\n    \"mobile\": [320, 512, [], \"f10b\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"mobile-alt\": [320, 512, [], \"f3cd\", \"M272 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h224c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM160 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm112-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h200c6.6 0 12 5.4 12 12v312z\"],\n    \"money-bill\": [640, 512, [], \"f0d6\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 176c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 48h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-alt\": [640, 512, [], \"f3d1\", \"M352 288h-16v-88c0-4.42-3.58-8-8-8h-13.58c-4.74 0-9.37 1.4-13.31 4.03l-15.33 10.22a7.994 7.994 0 0 0-2.22 11.09l8.88 13.31a7.994 7.994 0 0 0 11.09 2.22l.47-.31V288h-16c-4.42 0-8 3.58-8 8v16c0 4.42 3.58 8 8 8h64c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zM608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM48 400v-64c35.35 0 64 28.65 64 64H48zm0-224v-64h64c0 35.35-28.65 64-64 64zm272 192c-53.02 0-96-50.15-96-112 0-61.86 42.98-112 96-112s96 50.14 96 112c0 61.87-43 112-96 112zm272 32h-64c0-35.35 28.65-64 64-64v64zm0-224c-35.35 0-64-28.65-64-64h64v64z\"],\n    \"money-bill-wave\": [640, 512, [], \"f53a\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM48 132.22c20.12 5.04 41.12 7.57 62.72 8.93C104.84 170.54 79 192.69 48 192.69v-60.47zm0 285v-47.78c34.37 0 62.18 27.27 63.71 61.4-22.53-1.81-43.59-6.31-63.71-13.62zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96zm272 27.78c-17.52-4.39-35.71-6.85-54.32-8.44 5.87-26.08 27.5-45.88 54.32-49.28v57.72zm0-236.11c-30.89-3.91-54.86-29.7-55.81-61.55 19.54 2.17 38.09 6.23 55.81 12.66v48.89z\"],\n    \"money-bill-wave-alt\": [640, 512, [], \"f53b\", \"M621.16 54.46C582.37 38.19 543.55 32 504.75 32c-123.17-.01-246.33 62.34-369.5 62.34-30.89 0-61.76-3.92-92.65-13.72-3.47-1.1-6.95-1.62-10.35-1.62C15.04 79 0 92.32 0 110.81v317.26c0 12.63 7.23 24.6 18.84 29.46C57.63 473.81 96.45 480 135.25 480c123.17 0 246.34-62.35 369.51-62.35 30.89 0 61.76 3.92 92.65 13.72 3.47 1.1 6.95 1.62 10.35 1.62 17.21 0 32.25-13.32 32.25-31.81V83.93c-.01-12.64-7.24-24.6-18.85-29.47zM320 352c-44.19 0-80-42.99-80-96 0-53.02 35.82-96 80-96s80 42.98 80 96c0 53.03-35.83 96-80 96z\"],\n    \"money-check\": [640, 512, [], \"f53c\", \"M0 448c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V128H0v320zm448-208c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-96c-8.84 0-16-7.16-16-16v-32zm0 120c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H456c-4.42 0-8-3.58-8-8v-16zM64 264c0-4.42 3.58-8 8-8h304c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zm0 96c0-4.42 3.58-8 8-8h176c4.42 0 8 3.58 8 8v16c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16zM624 32H16C7.16 32 0 39.16 0 48v48h640V48c0-8.84-7.16-16-16-16z\"],\n    \"money-check-alt\": [640, 512, [], \"f53d\", \"M608 32H32C14.33 32 0 46.33 0 64v384c0 17.67 14.33 32 32 32h576c17.67 0 32-14.33 32-32V64c0-17.67-14.33-32-32-32zM176 327.88V344c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-16.29c-11.29-.58-22.27-4.52-31.37-11.35-3.9-2.93-4.1-8.77-.57-12.14l11.75-11.21c2.77-2.64 6.89-2.76 10.13-.73 3.87 2.42 8.26 3.72 12.82 3.72h28.11c6.5 0 11.8-5.92 11.8-13.19 0-5.95-3.61-11.19-8.77-12.73l-45-13.5c-18.59-5.58-31.58-23.42-31.58-43.39 0-24.52 19.05-44.44 42.67-45.07V152c0-4.42 3.58-8 8-8h16c4.42 0 8 3.58 8 8v16.29c11.29.58 22.27 4.51 31.37 11.35 3.9 2.93 4.1 8.77.57 12.14l-11.75 11.21c-2.77 2.64-6.89 2.76-10.13.73-3.87-2.43-8.26-3.72-12.82-3.72h-28.11c-6.5 0-11.8 5.92-11.8 13.19 0 5.95 3.61 11.19 8.77 12.73l45 13.5c18.59 5.58 31.58 23.42 31.58 43.39 0 24.53-19.05 44.44-42.67 45.07zM416 312c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h112c4.42 0 8 3.58 8 8v16zm160 0c0 4.42-3.58 8-8 8h-80c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h80c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H296c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h272c4.42 0 8 3.58 8 8v16z\"],\n    \"monument\": [384, 512, [], \"f5a6\", \"M368 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h352c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-78.86-347.26a31.97 31.97 0 0 0-9.21-19.44L203.31 4.69c-6.25-6.25-16.38-6.25-22.63 0l-76.6 76.61a31.97 31.97 0 0 0-9.21 19.44L64 416h256l-30.86-315.26zM240 307.2c0 6.4-6.4 12.8-12.8 12.8h-70.4c-6.4 0-12.8-6.4-12.8-12.8v-38.4c0-6.4 6.4-12.8 12.8-12.8h70.4c6.4 0 12.8 6.4 12.8 12.8v38.4z\"],\n    \"moon\": [512, 512, [], \"f186\", \"M283.211 512c78.962 0 151.079-35.925 198.857-94.792 7.068-8.708-.639-21.43-11.562-19.35-124.203 23.654-238.262-71.576-238.262-196.954 0-72.222 38.662-138.635 101.498-174.394 9.686-5.512 7.25-20.197-3.756-22.23A258.156 258.156 0 0 0 283.211 0c-141.309 0-256 114.511-256 256 0 141.309 114.511 256 256 256z\"],\n    \"mortar-pestle\": [512, 512, [], \"f5a7\", \"M501.54 60.91c17.22-17.22 12.51-46.25-9.27-57.14a35.696 35.696 0 0 0-37.37 3.37L251.09 160h151.37l99.08-99.09zM496 192H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c0 80.98 50.2 150.11 121.13 178.32-12.76 16.87-21.72 36.8-24.95 58.69-1.46 9.92 6.04 18.98 16.07 18.98h223.5c10.03 0 17.53-9.06 16.07-18.98-3.22-21.89-12.18-41.82-24.95-58.69C429.8 406.11 480 336.98 480 256h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16z\"],\n    \"mosque\": [640, 512, [], \"f678\", \"M0 480c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V160H0v320zm579.16-192c17.86-17.39 28.84-37.34 28.84-58.91 0-52.86-41.79-93.79-87.92-122.9-41.94-26.47-80.63-57.77-111.96-96.22L400 0l-8.12 9.97c-31.33 38.45-70.01 69.76-111.96 96.22C233.79 135.3 192 176.23 192 229.09c0 21.57 10.98 41.52 28.84 58.91h358.32zM608 320H192c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h32v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h64v-72c0-48 48-72 48-72s48 24 48 72v72h64v-64c0-17.67 14.33-32 32-32s32 14.33 32 32v64h32c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM64 0S0 32 0 96v32h128V96c0-64-64-96-64-96z\"],\n    \"motorcycle\": [640, 512, [], \"f21c\", \"M512.9 192c-14.9-.1-29.1 2.3-42.4 6.9L437.6 144H520c13.3 0 24-10.7 24-24V88c0-13.3-10.7-24-24-24h-45.3c-6.8 0-13.3 2.9-17.8 7.9l-37.5 41.7-22.8-38C392.2 68.4 384.4 64 376 64h-80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h66.4l19.2 32H227.9c-17.7-23.1-44.9-40-99.9-40H72.5C59 104 47.7 115 48 128.5c.2 13 10.9 23.5 24 23.5h56c24.5 0 38.7 10.9 47.8 24.8l-11.3 20.5c-13-3.9-26.9-5.7-41.3-5.2C55.9 194.5 1.6 249.6 0 317c-1.6 72.1 56.3 131 128 131 59.6 0 109.7-40.8 124-96h84.2c13.7 0 24.6-11.4 24-25.1-2.1-47.1 17.5-93.7 56.2-125l12.5 20.8c-27.6 23.7-45.1 58.9-44.8 98.2.5 69.6 57.2 126.5 126.8 127.1 71.6.7 129.8-57.5 129.2-129.1-.7-69.6-57.6-126.4-127.2-126.9zM128 400c-44.1 0-80-35.9-80-80s35.9-80 80-80c4.2 0 8.4.3 12.5 1L99 316.4c-8.8 16 2.8 35.6 21 35.6h81.3c-12.4 28.2-40.6 48-73.3 48zm463.9-75.6c-2.2 40.6-35 73.4-75.5 75.5-46.1 2.5-84.4-34.3-84.4-79.9 0-21.4 8.4-40.8 22.1-55.1l49.4 82.4c4.5 7.6 14.4 10 22 5.5l13.7-8.2c7.6-4.5 10-14.4 5.5-22l-48.6-80.9c5.2-1.1 10.5-1.6 15.9-1.6 45.6-.1 82.3 38.2 79.9 84.3z\"],\n    \"mountain\": [640, 512, [], \"f6fc\", \"M634.92 462.7l-288-448C341.03 5.54 330.89 0 320 0s-21.03 5.54-26.92 14.7l-288 448a32.001 32.001 0 0 0-1.17 32.64A32.004 32.004 0 0 0 32 512h576c11.71 0 22.48-6.39 28.09-16.67a31.983 31.983 0 0 0-1.17-32.63zM320 91.18L405.39 224H320l-64 64-38.06-38.06L320 91.18z\"],\n    \"mouse-pointer\": [320, 512, [], \"f245\", \"M302.189 329.126H196.105l55.831 135.993c3.889 9.428-.555 19.999-9.444 23.999l-49.165 21.427c-9.165 4-19.443-.571-23.332-9.714l-53.053-129.136-86.664 89.138C18.729 472.71 0 463.554 0 447.977V18.299C0 1.899 19.921-6.096 30.277 5.443l284.412 292.542c11.472 11.179 3.007 31.141-12.5 31.141z\"],\n    \"mug-hot\": [512, 512, [], \"f7b6\", \"M127.1 146.5c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C111.8 5.9 105 0 96.8 0H80.4C70.6 0 63 8.5 64.1 18c3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zm112 0c1.3 7.7 8 13.5 16 13.5h16.5c9.8 0 17.6-8.5 16.3-18-3.8-28.2-16.4-54.2-36.6-74.7-14.4-14.7-23.6-33.3-26.4-53.5C223.8 5.9 217 0 208.8 0h-16.4c-9.8 0-17.5 8.5-16.3 18 3.9 31.9 18 61.3 40.6 84.4 12 12.2 19.7 27.5 22.4 44.1zM400 192H32c-17.7 0-32 14.3-32 32v192c0 53 43 96 96 96h192c53 0 96-43 96-96h16c61.8 0 112-50.2 112-112s-50.2-112-112-112zm0 160h-16v-96h16c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"music\": [512, 512, [], \"f001\", \"M511.99 32.01c0-21.71-21.1-37.01-41.6-30.51L150.4 96c-13.3 4.2-22.4 16.5-22.4 30.5v261.42c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64V214.31l256-75.02v184.63c-10.05-2.38-20.72-3.92-32-3.92-53.02 0-96 28.65-96 64s42.98 64 96 64 96-28.65 96-64l-.01-351.99z\"],\n    \"network-wired\": [640, 512, [], \"f6ff\", \"M640 264v-16c0-8.84-7.16-16-16-16H344v-40h72c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H224c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h72v40H16c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h104v40H64c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h304v40h-56c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h160c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32h-56v-40h104c8.84 0 16-7.16 16-16zM256 128V64h128v64H256zm-64 320H96v-64h96v64zm352 0h-96v-64h96v64z\"],\n    \"neuter\": [288, 512, [], \"f22c\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V468c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12V316.4c64.1-14.5 112-71.9 112-140.4zm-144 80c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"newspaper\": [576, 512, [], \"f1ea\", \"M552 64H88c-13.255 0-24 10.745-24 24v8H24c-13.255 0-24 10.745-24 24v272c0 30.928 25.072 56 56 56h472c26.51 0 48-21.49 48-48V88c0-13.255-10.745-24-24-24zM56 400a8 8 0 0 1-8-8V144h16v248a8 8 0 0 1-8 8zm236-16H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm-208-96H140c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm208 0H348c-6.627 0-12-5.373-12-12v-8c0-6.627 5.373-12 12-12h152c6.627 0 12 5.373 12 12v8c0 6.627-5.373 12-12 12zm0-96H140c-6.627 0-12-5.373-12-12v-40c0-6.627 5.373-12 12-12h360c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12z\"],\n    \"not-equal\": [448, 512, [], \"f53e\", \"M416 208c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32h-23.88l51.87-66.81c5.37-7.02 4.04-17.06-2.97-22.43L415.61 3.3c-7.02-5.38-17.06-4.04-22.44 2.97L311.09 112H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h204.56l-74.53 96H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h55.49l-51.87 66.81c-5.37 7.01-4.04 17.05 2.97 22.43L64 508.7c7.02 5.38 17.06 4.04 22.43-2.97L168.52 400H416c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32H243.05l74.53-96H416z\"],\n    \"notes-medical\": [384, 512, [], \"f481\", \"M336 64h-80c0-35.3-28.7-64-64-64s-64 28.7-64 64H48C21.5 64 0 85.5 0 112v352c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V112c0-26.5-21.5-48-48-48zM192 40c13.3 0 24 10.7 24 24s-10.7 24-24 24-24-10.7-24-24 10.7-24 24-24zm96 304c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48zm0-192c0 4.4-3.6 8-8 8H104c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h176c4.4 0 8 3.6 8 8v16z\"],\n    \"object-group\": [512, 512, [], \"f247\", \"M480 128V96h20c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v20H64V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v40c0 6.627 5.373 12 12 12h20v320H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-20h384v20c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-20V128zM96 276V140c0-6.627 5.373-12 12-12h168c6.627 0 12 5.373 12 12v136c0 6.627-5.373 12-12 12H108c-6.627 0-12-5.373-12-12zm320 96c0 6.627-5.373 12-12 12H236c-6.627 0-12-5.373-12-12v-52h72c13.255 0 24-10.745 24-24v-72h84c6.627 0 12 5.373 12 12v136z\"],\n    \"object-ungroup\": [576, 512, [], \"f248\", \"M64 320v26a6 6 0 0 1-6 6H6a6 6 0 0 1-6-6v-52a6 6 0 0 1 6-6h26V96H6a6 6 0 0 1-6-6V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v26h288V38a6 6 0 0 1 6-6h52a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-26v192h26a6 6 0 0 1 6 6v52a6 6 0 0 1-6 6h-52a6 6 0 0 1-6-6v-26H64zm480-64v-32h26a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-52a6 6 0 0 0-6 6v26H408v72h8c13.255 0 24 10.745 24 24v64c0 13.255-10.745 24-24 24h-64c-13.255 0-24-10.745-24-24v-8H192v72h-26a6 6 0 0 0-6 6v52a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-26h288v26a6 6 0 0 0 6 6h52a6 6 0 0 0 6-6v-52a6 6 0 0 0-6-6h-26V256z\"],\n    \"oil-can\": [640, 512, [], \"f613\", \"M629.8 160.31L416 224l-50.49-25.24a64.07 64.07 0 0 0-28.62-6.76H280v-48h56c8.84 0 16-7.16 16-16v-16c0-8.84-7.16-16-16-16H176c-8.84 0-16 7.16-16 16v16c0 8.84 7.16 16 16 16h56v48h-56L37.72 166.86a31.9 31.9 0 0 0-5.79-.53C14.67 166.33 0 180.36 0 198.34v94.95c0 15.46 11.06 28.72 26.28 31.48L96 337.46V384c0 17.67 14.33 32 32 32h274.63c8.55 0 16.75-3.42 22.76-9.51l212.26-214.75c1.5-1.5 2.34-3.54 2.34-5.66V168c.01-5.31-5.08-9.15-10.19-7.69zM96 288.67l-48-8.73v-62.43l48 8.73v62.43zm453.33 84.66c0 23.56 19.1 42.67 42.67 42.67s42.67-19.1 42.67-42.67S592 288 592 288s-42.67 61.77-42.67 85.33z\"],\n    \"om\": [512, 512, [], \"f679\", \"M360.6 60.94a10.43 10.43 0 0 0 14.76 0l21.57-21.56a10.43 10.43 0 0 0 0-14.76L375.35 3.06c-4.08-4.07-10.68-4.07-14.76 0l-21.57 21.56a10.43 10.43 0 0 0 0 14.76l21.58 21.56zM412.11 192c-26.69 0-51.77 10.39-70.64 29.25l-24.25 24.25c-6.78 6.77-15.78 10.5-25.38 10.5H245c10.54-22.1 14.17-48.11 7.73-75.23-10.1-42.55-46.36-76.11-89.52-83.19-36.15-5.93-70.9 5.04-96.01 28.78-7.36 6.96-6.97 18.85 1.12 24.93l26.15 19.63c5.72 4.3 13.66 4.32 19.2-.21 8.45-6.9 19.02-10.71 30.27-10.71 26.47 0 48.01 21.53 48.01 48s-21.54 48-48.01 48h-31.9c-11.96 0-19.74 12.58-14.39 23.28l16.09 32.17c2.53 5.06 7.6 8.1 13.17 8.55h33.03c35.3 0 64.01 28.7 64.01 64s-28.71 64-64.01 64c-96.02 0-122.35-54.02-145.15-92.03-4.53-7.55-14.77-3.58-14.79 5.22C-.09 416 41.13 512 159.94 512c70.59 0 128.02-57.42 128.02-128 0-23.42-6.78-45.1-17.81-64h21.69c26.69 0 51.77-10.39 70.64-29.25l24.25-24.25c6.78-6.77 15.78-10.5 25.38-10.5 19.78 0 35.88 16.09 35.88 35.88V392c0 13.23-18.77 24-32.01 24-39.4 0-66.67-24.24-81.82-42.89-4.77-5.87-14.2-2.54-14.2 5.02V416s0 64 96.02 64c48.54 0 96.02-39.47 96.02-88V291.88c0-55.08-44.8-99.88-99.89-99.88zm42.18-124.73c-85.55 65.12-169.05 2.75-172.58.05-6.02-4.62-14.44-4.38-20.14.55-5.74 4.92-7.27 13.17-3.66 19.8 1.61 2.95 40.37 72.34 118.8 72.34 79.92 0 98.78-31.36 101.75-37.66 1.02-2.12 1.53-4.47 1.53-6.83V80c0-13.22-15.14-20.69-25.7-12.73z\"],\n    \"otter\": [640, 512, [], \"f700\", \"M608 32h-32l-13.25-13.25A63.97 63.97 0 0 0 517.49 0H497c-11.14 0-22.08 2.91-31.75 8.43L312 96h-56C149.96 96 64 181.96 64 288v1.61c0 32.75-16 62.14-39.56 84.89-18.19 17.58-28.1 43.68-23.19 71.8 6.76 38.8 42.9 65.7 82.28 65.7H192c17.67 0 32-14.33 32-32s-14.33-32-32-32H80c-8.83 0-16-7.17-16-16s7.17-16 16-16h224c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-64l149.49-80.5L448 416h80c8.84 0 16-7.16 16-16v-16c0-17.67-14.33-32-32-32h-28.22l-55.11-110.21L521.14 192H544c53.02 0 96-42.98 96-96V64c0-17.67-14.33-32-32-32zm-96 16c8.84 0 16 7.16 16 16s-7.16 16-16 16-16-7.16-16-16 7.16-16 16-16zm32 96h-34.96L407.2 198.84l-13.77-27.55L512 112h77.05c-6.62 18.58-24.22 32-45.05 32z\"],\n    \"outdent\": [448, 512, [], \"f03b\", \"M100.69 363.29c10 10 27.31 2.93 27.31-11.31V160c0-14.32-17.33-21.31-27.31-11.31l-96 96a16 16 0 0 0 0 22.62zM432 416H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm3.17-128H204.83A12.82 12.82 0 0 0 192 300.83v38.34A12.82 12.82 0 0 0 204.83 352h230.34A12.82 12.82 0 0 0 448 339.17v-38.34A12.82 12.82 0 0 0 435.17 288zm0-128H204.83A12.82 12.82 0 0 0 192 172.83v38.34A12.82 12.82 0 0 0 204.83 224h230.34A12.82 12.82 0 0 0 448 211.17v-38.34A12.82 12.82 0 0 0 435.17 160zM432 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"pager\": [512, 512, [], \"f815\", \"M448 64H64a64 64 0 0 0-64 64v256a64 64 0 0 0 64 64h384a64 64 0 0 0 64-64V128a64 64 0 0 0-64-64zM160 368H80a16 16 0 0 1-16-16v-16a16 16 0 0 1 16-16h80zm128-16a16 16 0 0 1-16 16h-80v-48h80a16 16 0 0 1 16 16zm160-128a32 32 0 0 1-32 32H96a32 32 0 0 1-32-32v-64a32 32 0 0 1 32-32h320a32 32 0 0 1 32 32z\"],\n    \"paint-brush\": [512, 512, [], \"f1fc\", \"M167.02 309.34c-40.12 2.58-76.53 17.86-97.19 72.3-2.35 6.21-8 9.98-14.59 9.98-11.11 0-45.46-27.67-55.25-34.35C0 439.62 37.93 512 128 512c75.86 0 128-43.77 128-120.19 0-3.11-.65-6.08-.97-9.13l-88.01-73.34zM457.89 0c-15.16 0-29.37 6.71-40.21 16.45C213.27 199.05 192 203.34 192 257.09c0 13.7 3.25 26.76 8.73 38.7l63.82 53.18c7.21 1.8 14.64 3.03 22.39 3.03 62.11 0 98.11-45.47 211.16-256.46 7.38-14.35 13.9-29.85 13.9-45.99C512 20.64 486 0 457.89 0z\"],\n    \"paint-roller\": [512, 512, [], \"f5aa\", \"M416 128V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32h352c17.67 0 32-14.33 32-32zm32-64v128c0 17.67-14.33 32-32 32H256c-35.35 0-64 28.65-64 64v32c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32v-32h160c53.02 0 96-42.98 96-96v-64c0-35.35-28.65-64-64-64z\"],\n    \"palette\": [512, 512, [], \"f53f\", \"M204.3 5C104.9 24.4 24.8 104.3 5.2 203.4c-37 187 131.7 326.4 258.8 306.7 41.2-6.4 61.4-54.6 42.5-91.7-23.1-45.4 9.9-98.4 60.9-98.4h79.7c35.8 0 64.8-29.6 64.9-65.3C511.5 97.1 368.1-26.9 204.3 5zM96 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm32-128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128-64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm128 64c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"pallet\": [640, 512, [], \"f482\", \"M144 256h352c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H384v128l-64-32-64 32V0H144c-8.8 0-16 7.2-16 16v224c0 8.8 7.2 16 16 16zm480 128c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h48v64H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16h-48v-64h48zm-336 64H128v-64h160v64zm224 0H352v-64h160v64z\"],\n    \"paper-plane\": [512, 512, [], \"f1d8\", \"M476 3.2L12.5 270.6c-18.1 10.4-15.8 35.6 2.2 43.2L121 358.4l287.3-253.2c5.5-4.9 13.3 2.6 8.6 8.3L176 407v80.5c0 23.6 28.5 32.9 42.5 15.8L282 426l124.6 52.2c14.2 6 30.4-2.9 33-18.2l72-432C515 7.8 493.3-6.8 476 3.2z\"],\n    \"paperclip\": [448, 512, [], \"f0c6\", \"M43.246 466.142c-58.43-60.289-57.341-157.511 1.386-217.581L254.392 34c44.316-45.332 116.351-45.336 160.671 0 43.89 44.894 43.943 117.329 0 162.276L232.214 383.128c-29.855 30.537-78.633 30.111-107.982-.998-28.275-29.97-27.368-77.473 1.452-106.953l143.743-146.835c6.182-6.314 16.312-6.422 22.626-.241l22.861 22.379c6.315 6.182 6.422 16.312.241 22.626L171.427 319.927c-4.932 5.045-5.236 13.428-.648 18.292 4.372 4.634 11.245 4.711 15.688.165l182.849-186.851c19.613-20.062 19.613-52.725-.011-72.798-19.189-19.627-49.957-19.637-69.154 0L90.39 293.295c-34.763 35.56-35.299 93.12-1.191 128.313 34.01 35.093 88.985 35.137 123.058.286l172.06-175.999c6.177-6.319 16.307-6.433 22.626-.256l22.877 22.364c6.319 6.177 6.434 16.307.256 22.626l-172.06 175.998c-59.576 60.938-155.943 60.216-214.77-.485z\"],\n    \"parachute-box\": [512, 512, [], \"f4cd\", \"M511.9 175c-9.1-75.6-78.4-132.4-158.3-158.7C390 55.7 416 116.9 416 192h28.1L327.5 321.5c-2.5-.6-4.8-1.5-7.5-1.5h-48V192h112C384 76.8 315.1 0 256 0S128 76.8 128 192h112v128h-48c-2.7 0-5 .9-7.5 1.5L67.9 192H96c0-75.1 26-136.3 62.4-175.7C78.5 42.7 9.2 99.5.1 175c-1.1 9.1 6.8 17 16 17h8.7l136.7 151.9c-.7 2.6-1.6 5.2-1.6 8.1v128c0 17.7 14.3 32 32 32h128c17.7 0 32-14.3 32-32V352c0-2.9-.9-5.4-1.6-8.1L487.1 192h8.7c9.3 0 17.2-7.8 16.1-17z\"],\n    \"paragraph\": [448, 512, [], \"f1dd\", \"M448 48v32a16 16 0 0 1-16 16h-48v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V96h-32v368a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V352h-32a160 160 0 0 1 0-320h240a16 16 0 0 1 16 16z\"],\n    \"parking\": [448, 512, [], \"f540\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM240 320h-48v48c0 8.8-7.2 16-16 16h-32c-8.8 0-16-7.2-16-16V144c0-8.8 7.2-16 16-16h96c52.9 0 96 43.1 96 96s-43.1 96-96 96zm0-128h-48v64h48c17.6 0 32-14.4 32-32s-14.4-32-32-32z\"],\n    \"passport\": [448, 512, [], \"f5ab\", \"M129.62 176h39.09c1.49-27.03 6.54-51.35 14.21-70.41-27.71 13.24-48.02 39.19-53.3 70.41zm0 32c5.29 31.22 25.59 57.17 53.3 70.41-7.68-19.06-12.72-43.38-14.21-70.41h-39.09zM224 286.69c7.69-7.45 20.77-34.42 23.43-78.69h-46.87c2.67 44.26 15.75 71.24 23.44 78.69zM200.57 176h46.87c-2.66-44.26-15.74-71.24-23.43-78.69-7.7 7.45-20.78 34.43-23.44 78.69zm64.51 102.41c27.71-13.24 48.02-39.19 53.3-70.41h-39.09c-1.49 27.03-6.53 51.35-14.21 70.41zM416 0H64C28.65 0 0 28.65 0 64v384c0 35.35 28.65 64 64 64h352c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32zm-80 416H112c-8.8 0-16-7.2-16-16s7.2-16 16-16h224c8.8 0 16 7.2 16 16s-7.2 16-16 16zm-112-96c-70.69 0-128-57.31-128-128S153.31 64 224 64s128 57.31 128 128-57.31 128-128 128zm41.08-214.41c7.68 19.06 12.72 43.38 14.21 70.41h39.09c-5.28-31.22-25.59-57.17-53.3-70.41z\"],\n    \"pastafarianism\": [640, 512, [], \"f67b\", \"M624.54 347.67c-32.7-12.52-57.36 4.25-75.37 16.45-17.06 11.53-23.25 14.42-31.41 11.36-8.12-3.09-10.83-9.38-15.89-29.38-3.33-13.15-7.44-29.32-17.95-42.65 2.24-2.91 4.43-5.79 6.38-8.57C500.47 304.45 513.71 312 532 312c33.95 0 50.87-25.78 62.06-42.83 10.59-16.14 15-21.17 21.94-21.17 13.25 0 24-10.75 24-24s-10.75-24-24-24c-33.95 0-50.87 25.78-62.06 42.83-10.6 16.14-15 21.17-21.94 21.17-17.31 0-37.48-61.43-97.26-101.91l17.25-34.5C485.43 125.5 512 97.98 512 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 13.02 3.94 25.1 10.62 35.21l-18.15 36.3c-16.98-4.6-35.6-7.51-56.46-7.51s-39.49 2.91-56.46 7.51l-18.15-36.3C252.06 89.1 256 77.02 256 64c0-35.35-28.65-64-64-64s-64 28.65-64 64c0 33.98 26.56 61.5 60.02 63.6l17.25 34.5C145.68 202.44 125.15 264 108 264c-6.94 0-11.34-5.03-21.94-21.17C74.88 225.78 57.96 200 24 200c-13.25 0-24 10.75-24 24s10.75 24 24 24c6.94 0 11.34 5.03 21.94 21.17C57.13 286.22 74.05 312 108 312c18.29 0 31.53-7.55 41.7-17.11 1.95 2.79 4.14 5.66 6.38 8.57-10.51 13.33-14.62 29.5-17.95 42.65-5.06 20-7.77 26.28-15.89 29.38-8.11 3.06-14.33.17-31.41-11.36-18.03-12.2-42.72-28.92-75.37-16.45-12.39 4.72-18.59 18.58-13.87 30.97 4.72 12.41 18.61 18.61 30.97 13.88 8.16-3.09 14.34-.19 31.39 11.36 13.55 9.16 30.83 20.86 52.42 20.84 7.17 0 14.83-1.28 22.97-4.39 32.66-12.44 39.98-41.33 45.33-62.44 2.21-8.72 3.99-14.49 5.95-18.87 16.62 13.61 36.95 25.88 61.64 34.17-9.96 37-32.18 90.8-60.26 90.8-13.25 0-24 10.75-24 24s10.75 24 24 24c66.74 0 97.05-88.63 107.42-129.14 6.69.6 13.42 1.14 20.58 1.14s13.89-.54 20.58-1.14C350.95 423.37 381.26 512 448 512c13.25 0 24-10.75 24-24s-10.75-24-24-24c-27.94 0-50.21-53.81-60.22-90.81 24.69-8.29 45-20.56 61.62-34.16 1.96 4.38 3.74 10.15 5.95 18.87 5.34 21.11 12.67 50 45.33 62.44 8.14 3.11 15.8 4.39 22.97 4.39 21.59 0 38.87-11.69 52.42-20.84 17.05-11.55 23.28-14.45 31.39-11.36 12.39 4.75 26.27-1.47 30.97-13.88 4.71-12.4-1.49-26.26-13.89-30.98zM448 48c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16zm-256 0c8.82 0 16 7.18 16 16s-7.18 16-16 16-16-7.18-16-16 7.18-16 16-16z\"],\n    \"paste\": [448, 512, [], \"f0ea\", \"M128 184c0-30.879 25.122-56 56-56h136V56c0-13.255-10.745-24-24-24h-80.61C204.306 12.89 183.637 0 160 0s-44.306 12.89-55.39 32H24C10.745 32 0 42.745 0 56v336c0 13.255 10.745 24 24 24h104V184zm32-144c13.255 0 24 10.745 24 24s-10.745 24-24 24-24-10.745-24-24 10.745-24 24-24zm184 248h104v200c0 13.255-10.745 24-24 24H184c-13.255 0-24-10.745-24-24V184c0-13.255 10.745-24 24-24h136v104c0 13.2 10.8 24 24 24zm104-38.059V256h-96v-96h6.059a24 24 0 0 1 16.97 7.029l65.941 65.941a24.002 24.002 0 0 1 7.03 16.971z\"],\n    \"pause\": [448, 512, [], \"f04c\", \"M144 479H48c-26.5 0-48-21.5-48-48V79c0-26.5 21.5-48 48-48h96c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zm304-48V79c0-26.5-21.5-48-48-48h-96c-26.5 0-48 21.5-48 48v352c0 26.5 21.5 48 48 48h96c26.5 0 48-21.5 48-48z\"],\n    \"pause-circle\": [512, 512, [], \"f28b\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm-16 328c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160zm112 0c0 8.8-7.2 16-16 16h-48c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h48c8.8 0 16 7.2 16 16v160z\"],\n    \"paw\": [512, 512, [], \"f1b0\", \"M256 224c-79.41 0-192 122.76-192 200.25 0 34.9 26.81 55.75 71.74 55.75 48.84 0 81.09-25.08 120.26-25.08 39.51 0 71.85 25.08 120.26 25.08 44.93 0 71.74-20.85 71.74-55.75C448 346.76 335.41 224 256 224zm-147.28-12.61c-10.4-34.65-42.44-57.09-71.56-50.13-29.12 6.96-44.29 40.69-33.89 75.34 10.4 34.65 42.44 57.09 71.56 50.13 29.12-6.96 44.29-40.69 33.89-75.34zm84.72-20.78c30.94-8.14 46.42-49.94 34.58-93.36s-46.52-72.01-77.46-63.87-46.42 49.94-34.58 93.36c11.84 43.42 46.53 72.02 77.46 63.87zm281.39-29.34c-29.12-6.96-61.15 15.48-71.56 50.13-10.4 34.65 4.77 68.38 33.89 75.34 29.12 6.96 61.15-15.48 71.56-50.13 10.4-34.65-4.77-68.38-33.89-75.34zm-156.27 29.34c30.94 8.14 65.62-20.45 77.46-63.87 11.84-43.42-3.64-85.21-34.58-93.36s-65.62 20.45-77.46 63.87c-11.84 43.42 3.64 85.22 34.58 93.36z\"],\n    \"peace\": [496, 512, [], \"f67c\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm184 248c0 31.93-8.2 61.97-22.57 88.17L280 240.63V74.97c86.23 15.21 152 90.5 152 181.03zM216 437.03c-33.86-5.97-64.49-21.2-89.29-43.02L216 322.57v114.46zm64-114.46L369.29 394c-24.8 21.82-55.43 37.05-89.29 43.02V322.57zm-64-247.6v165.66L86.57 344.17C72.2 317.97 64 287.93 64 256c0-90.53 65.77-165.82 152-181.03z\"],\n    \"pen\": [512, 512, [], \"f304\", \"M290.74 93.24l128.02 128.02-277.99 277.99-114.14 12.6C11.35 513.54-1.56 500.62.14 485.34l12.7-114.22 277.9-277.88zm207.2-19.06l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.76 18.75-49.16 0-67.91z\"],\n    \"pen-alt\": [512, 512, [], \"f305\", \"M497.94 74.17l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91zm-246.8-20.53c-15.62-15.62-40.94-15.62-56.56 0L75.8 172.43c-6.25 6.25-6.25 16.38 0 22.62l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l101.82-101.82 22.63 22.62L93.95 290.03A327.038 327.038 0 0 0 .17 485.11l-.03.23c-1.7 15.28 11.21 28.2 26.49 26.51a327.02 327.02 0 0 0 195.34-93.8l196.79-196.79-82.77-82.77-84.85-84.85z\"],\n    \"pen-fancy\": [512, 512, [], \"f5ac\", \"M79.18 282.94a32.005 32.005 0 0 0-20.24 20.24L0 480l4.69 4.69 92.89-92.89c-.66-2.56-1.57-5.03-1.57-7.8 0-17.67 14.33-32 32-32s32 14.33 32 32-14.33 32-32 32c-2.77 0-5.24-.91-7.8-1.57l-92.89 92.89L32 512l176.82-58.94a31.983 31.983 0 0 0 20.24-20.24l33.07-84.07-98.88-98.88-84.07 33.07zM369.25 28.32L186.14 227.81l97.85 97.85 199.49-183.11C568.4 67.48 443.73-55.94 369.25 28.32z\"],\n    \"pen-nib\": [512, 512, [], \"f5ad\", \"M136.6 138.79a64.003 64.003 0 0 0-43.31 41.35L0 460l14.69 14.69L164.8 324.58c-2.99-6.26-4.8-13.18-4.8-20.58 0-26.51 21.49-48 48-48s48 21.49 48 48-21.49 48-48 48c-7.4 0-14.32-1.81-20.58-4.8L37.31 497.31 52 512l279.86-93.29a64.003 64.003 0 0 0 41.35-43.31L416 224 288 96l-151.4 42.79zm361.34-64.62l-60.11-60.11c-18.75-18.75-49.16-18.75-67.91 0l-56.55 56.55 128.02 128.02 56.55-56.55c18.75-18.75 18.75-49.15 0-67.91z\"],\n    \"pen-square\": [448, 512, [], \"f14b\", \"M400 480H48c-26.5 0-48-21.5-48-48V80c0-26.5 21.5-48 48-48h352c26.5 0 48 21.5 48 48v352c0 26.5-21.5 48-48 48zM238.1 177.9L102.4 313.6l-6.3 57.1c-.8 7.6 5.6 14.1 13.3 13.3l57.1-6.3L302.2 242c2.3-2.3 2.3-6.1 0-8.5L246.7 178c-2.5-2.4-6.3-2.4-8.6-.1zM345 165.1L314.9 135c-9.4-9.4-24.6-9.4-33.9 0l-23.1 23.1c-2.3 2.3-2.3 6.1 0 8.5l55.5 55.5c2.3 2.3 6.1 2.3 8.5 0L345 199c9.3-9.3 9.3-24.5 0-33.9z\"],\n    \"pencil-alt\": [512, 512, [], \"f303\", \"M497.9 142.1l-46.1 46.1c-4.7 4.7-12.3 4.7-17 0l-111-111c-4.7-4.7-4.7-12.3 0-17l46.1-46.1c18.7-18.7 49.1-18.7 67.9 0l60.1 60.1c18.8 18.7 18.8 49.1 0 67.9zM284.2 99.8L21.6 362.4.4 483.9c-2.9 16.4 11.4 30.6 27.8 27.8l121.5-21.3 262.6-262.6c4.7-4.7 4.7-12.3 0-17l-111-111c-4.8-4.7-12.4-4.7-17.1 0zM124.1 339.9c-5.5-5.5-5.5-14.3 0-19.8l154-154c5.5-5.5 14.3-5.5 19.8 0s5.5 14.3 0 19.8l-154 154c-5.5 5.5-14.3 5.5-19.8 0zM88 424h48v36.3l-64.5 11.3-31.1-31.1L51.7 376H88v48z\"],\n    \"pencil-ruler\": [512, 512, [], \"f5ae\", \"M109.46 244.04l134.58-134.56-44.12-44.12-61.68 61.68a7.919 7.919 0 0 1-11.21 0l-11.21-11.21c-3.1-3.1-3.1-8.12 0-11.21l61.68-61.68-33.64-33.65C131.47-3.1 111.39-3.1 99 9.29L9.29 99c-12.38 12.39-12.39 32.47 0 44.86l100.17 100.18zm388.47-116.8c18.76-18.76 18.75-49.17 0-67.93l-45.25-45.25c-18.76-18.76-49.18-18.76-67.95 0l-46.02 46.01 113.2 113.2 46.02-46.03zM316.08 82.71l-297 296.96L.32 487.11c-2.53 14.49 10.09 27.11 24.59 24.56l107.45-18.84L429.28 195.9 316.08 82.71zm186.63 285.43l-33.64-33.64-61.68 61.68c-3.1 3.1-8.12 3.1-11.21 0l-11.21-11.21c-3.09-3.1-3.09-8.12 0-11.21l61.68-61.68-44.14-44.14L267.93 402.5l100.21 100.2c12.39 12.39 32.47 12.39 44.86 0l89.71-89.7c12.39-12.39 12.39-32.47 0-44.86z\"],\n    \"people-carry\": [640, 512, [], \"f4ce\", \"M128 96c26.5 0 48-21.5 48-48S154.5 0 128 0 80 21.5 80 48s21.5 48 48 48zm384 0c26.5 0 48-21.5 48-48S538.5 0 512 0s-48 21.5-48 48 21.5 48 48 48zm125.7 372.1l-44-110-41.1 46.4-2 18.2 27.7 69.2c5 12.5 17 20.1 29.7 20.1 4 0 8-.7 11.9-2.3 16.4-6.6 24.4-25.2 17.8-41.6zm-34.2-209.8L585 178.1c-4.6-20-18.6-36.8-37.5-44.9-18.5-8-39-6.7-56.1 3.3-22.7 13.4-39.7 34.5-48.1 59.4L432 229.8 416 240v-96c0-8.8-7.2-16-16-16H240c-8.8 0-16 7.2-16 16v96l-16.1-10.2-11.3-33.9c-8.3-25-25.4-46-48.1-59.4-17.2-10-37.6-11.3-56.1-3.3-18.9 8.1-32.9 24.9-37.5 44.9l-18.4 80.2c-4.6 20 .7 41.2 14.4 56.7l67.2 75.9 10.1 92.6C130 499.8 143.8 512 160 512c1.2 0 2.3-.1 3.5-.2 17.6-1.9 30.2-17.7 28.3-35.3l-10.1-92.8c-1.5-13-6.9-25.1-15.6-35l-43.3-49 17.6-70.3 6.8 20.4c4.1 12.5 11.9 23.4 24.5 32.6l51.1 32.5c4.6 2.9 12.1 4.6 17.2 5h160c5.1-.4 12.6-2.1 17.2-5l51.1-32.5c12.6-9.2 20.4-20 24.5-32.6l6.8-20.4 17.6 70.3-43.3 49c-8.7 9.9-14.1 22-15.6 35l-10.1 92.8c-1.9 17.6 10.8 33.4 28.3 35.3 1.2.1 2.3.2 3.5.2 16.1 0 30-12.1 31.8-28.5l10.1-92.6 67.2-75.9c13.6-15.5 19-36.7 14.4-56.7zM46.3 358.1l-44 110c-6.6 16.4 1.4 35 17.8 41.6 16.8 6.6 35.1-1.7 41.6-17.8l27.7-69.2-2-18.2-41.1-46.4z\"],\n    \"pepper-hot\": [512, 512, [], \"f816\", \"M330.67 263.12V173.4l-52.75-24.22C219.44 218.76 197.58 400 56 400a56 56 0 0 0 0 112c212.64 0 370.65-122.87 419.18-210.34l-37.05-38.54zm131.09-128.37C493.92 74.91 477.18 26.48 458.62 3a8 8 0 0 0-11.93-.59l-22.9 23a8.06 8.06 0 0 0-.89 10.23c6.86 10.36 17.05 35.1-1.4 72.32A142.85 142.85 0 0 0 364.34 96c-28 0-54 8.54-76.34 22.59l74.67 34.29v78.24h89.09L506.44 288c3.26-12.62 5.56-25.63 5.56-39.31a154 154 0 0 0-50.24-113.94z\"],\n    \"percent\": [448, 512, [], \"f295\", \"M112 224c61.9 0 112-50.1 112-112S173.9 0 112 0 0 50.1 0 112s50.1 112 112 112zm0-160c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48 21.5-48 48-48zm224 224c-61.9 0-112 50.1-112 112s50.1 112 112 112 112-50.1 112-112-50.1-112-112-112zm0 160c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zM392.3.2l31.6-.1c19.4-.1 30.9 21.8 19.7 37.8L77.4 501.6a23.95 23.95 0 0 1-19.6 10.2l-33.4.1c-19.5 0-30.9-21.9-19.7-37.8l368-463.7C377.2 4 384.5.2 392.3.2z\"],\n    \"percentage\": [384, 512, [], \"f541\", \"M109.25 173.25c24.99-24.99 24.99-65.52 0-90.51-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 25 25 65.52 25 90.51 0zm256 165.49c-24.99-24.99-65.52-24.99-90.51 0-24.99 24.99-24.99 65.52 0 90.51 24.99 24.99 65.52 24.99 90.51 0 25-24.99 25-65.51 0-90.51zm-1.94-231.43l-22.62-22.62c-12.5-12.5-32.76-12.5-45.25 0L20.69 359.44c-12.5 12.5-12.5 32.76 0 45.25l22.62 22.62c12.5 12.5 32.76 12.5 45.25 0l274.75-274.75c12.5-12.49 12.5-32.75 0-45.25z\"],\n    \"person-booth\": [576, 512, [], \"f756\", \"M192 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320h-64v176zm32-272h-50.9l-45.2-45.3C115.8 166.6 99.7 160 82.7 160H64c-17.1 0-33.2 6.7-45.3 18.8C6.7 190.9 0 207 0 224.1L.2 320 0 480c0 17.7 14.3 32 31.9 32 17.6 0 32-14.3 32-32l.1-100.7c.9.5 1.6 1.3 2.5 1.7l29.1 43v56c0 17.7 14.3 32 32 32s32-14.3 32-32v-56.5c0-9.9-2.3-19.8-6.7-28.6l-41.2-61.3V253l20.9 20.9c9.1 9.1 21.1 14.1 33.9 14.1H224c17.7 0 32-14.3 32-32s-14.3-32-32-32zM64 128c26.5 0 48-21.5 48-48S90.5 32 64 32 16 53.5 16 80s21.5 48 48 48zm224-96l31.5 223.1-30.9 154.6c-4.3 21.6 13 38.3 31.4 38.3 15.2 0 28-9.1 32.3-30.4.9 16.9 14.6 30.4 31.7 30.4 17.7 0 32-14.3 32-32 0 17.7 14.3 32 32 32s32-14.3 32-32V0H288v32zm-96 0v160h64V0h-32c-17.7 0-32 14.3-32 32zM544 0h-32v496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V32c0-17.7-14.3-32-32-32z\"],\n    \"phone\": [512, 512, [], \"f095\", \"M493.4 24.6l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-36 76.7-98.9 140.5-177.2 177.2l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48C3.9 366.5-2 378.1.6 389.4l24 104C27.1 504.2 36.7 512 48 512c256.1 0 464-207.5 464-464 0-11.2-7.7-20.9-18.6-23.4z\"],\n    \"phone-alt\": [512, 512, [], \"f879\", \"M497.39 361.8l-112-48a24 24 0 0 0-28 6.9l-49.6 60.6A370.66 370.66 0 0 1 130.6 204.11l60.6-49.6a23.94 23.94 0 0 0 6.9-28l-48-112A24.16 24.16 0 0 0 122.6.61l-104 24A24 24 0 0 0 0 48c0 256.5 207.9 464 464 464a24 24 0 0 0 23.4-18.6l24-104a24.29 24.29 0 0 0-14.01-27.6z\"],\n    \"phone-slash\": [640, 512, [], \"f3dd\", \"M268.2 381.4l-49.6-60.6c-6.8-8.3-18.2-11.1-28-6.9l-112 48c-10.7 4.6-16.5 16.1-13.9 27.5l24 104c2.5 10.8 12.1 18.6 23.4 18.6 100.7 0 193.7-32.4 269.7-86.9l-80-61.8c-10.9 6.5-22.1 12.7-33.6 18.1zm365.6 76.7L475.1 335.5C537.9 256.4 576 156.9 576 48c0-11.2-7.7-20.9-18.6-23.4l-104-24c-11.3-2.6-22.9 3.3-27.5 13.9l-48 112c-4.2 9.8-1.4 21.3 6.9 28l60.6 49.6c-12.2 26.1-27.9 50.3-46 72.8L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3z\"],\n    \"phone-square\": [448, 512, [], \"f098\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM94 416c-7.033 0-13.057-4.873-14.616-11.627l-14.998-65a15 15 0 0 1 8.707-17.16l69.998-29.999a15 15 0 0 1 17.518 4.289l30.997 37.885c48.944-22.963 88.297-62.858 110.781-110.78l-37.886-30.997a15.001 15.001 0 0 1-4.289-17.518l30-69.998a15 15 0 0 1 17.16-8.707l65 14.998A14.997 14.997 0 0 1 384 126c0 160.292-129.945 290-290 290z\"],\n    \"phone-square-alt\": [448, 512, [], \"f87b\", \"M400 32H48A48 48 0 0 0 0 80v352a48 48 0 0 0 48 48h352a48 48 0 0 0 48-48V80a48 48 0 0 0-48-48zm-16.39 307.37l-15 65A15 15 0 0 1 354 416C194 416 64 286.29 64 126a15.7 15.7 0 0 1 11.63-14.61l65-15A18.23 18.23 0 0 1 144 96a16.27 16.27 0 0 1 13.79 9.09l30 70A17.9 17.9 0 0 1 189 181a17 17 0 0 1-5.5 11.61l-37.89 31a231.91 231.91 0 0 0 110.78 110.78l31-37.89A17 17 0 0 1 299 291a17.85 17.85 0 0 1 5.91 1.21l70 30A16.25 16.25 0 0 1 384 336a17.41 17.41 0 0 1-.39 3.37z\"],\n    \"phone-volume\": [384, 512, [], \"f2a0\", \"M97.333 506.966c-129.874-129.874-129.681-340.252 0-469.933 5.698-5.698 14.527-6.632 21.263-2.422l64.817 40.513a17.187 17.187 0 0 1 6.849 20.958l-32.408 81.021a17.188 17.188 0 0 1-17.669 10.719l-55.81-5.58c-21.051 58.261-20.612 122.471 0 179.515l55.811-5.581a17.188 17.188 0 0 1 17.669 10.719l32.408 81.022a17.188 17.188 0 0 1-6.849 20.958l-64.817 40.513a17.19 17.19 0 0 1-21.264-2.422zM247.126 95.473c11.832 20.047 11.832 45.008 0 65.055-3.95 6.693-13.108 7.959-18.718 2.581l-5.975-5.726c-3.911-3.748-4.793-9.622-2.261-14.41a32.063 32.063 0 0 0 0-29.945c-2.533-4.788-1.65-10.662 2.261-14.41l5.975-5.726c5.61-5.378 14.768-4.112 18.718 2.581zm91.787-91.187c60.14 71.604 60.092 175.882 0 247.428-4.474 5.327-12.53 5.746-17.552.933l-5.798-5.557c-4.56-4.371-4.977-11.529-.93-16.379 49.687-59.538 49.646-145.933 0-205.422-4.047-4.85-3.631-12.008.93-16.379l5.798-5.557c5.022-4.813 13.078-4.394 17.552.933zm-45.972 44.941c36.05 46.322 36.108 111.149 0 157.546-4.39 5.641-12.697 6.251-17.856 1.304l-5.818-5.579c-4.4-4.219-4.998-11.095-1.285-15.931 26.536-34.564 26.534-82.572 0-117.134-3.713-4.836-3.115-11.711 1.285-15.931l5.818-5.579c5.159-4.947 13.466-4.337 17.856 1.304z\"],\n    \"photo-video\": [640, 512, [], \"f87c\", \"M608 0H160a32 32 0 0 0-32 32v96h160V64h192v320h128a32 32 0 0 0 32-32V32a32 32 0 0 0-32-32zM232 103a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm352 208a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9v-30a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm0-104a9 9 0 0 1-9 9h-30a9 9 0 0 1-9-9V73a9 9 0 0 1 9-9h30a9 9 0 0 1 9 9zm-168 57H32a32 32 0 0 0-32 32v288a32 32 0 0 0 32 32h384a32 32 0 0 0 32-32V192a32 32 0 0 0-32-32zM96 224a32 32 0 1 1-32 32 32 32 0 0 1 32-32zm288 224H64v-32l64-64 32 32 128-128 96 96z\"],\n    \"piggy-bank\": [576, 512, [], \"f4d3\", \"M560 224h-29.5c-8.8-20-21.6-37.7-37.4-52.5L512 96h-32c-29.4 0-55.4 13.5-73 34.3-7.6-1.1-15.1-2.3-23-2.3H256c-77.4 0-141.9 55-156.8 128H56c-14.8 0-26.5-13.5-23.5-28.8C34.7 215.8 45.4 208 57 208h1c3.3 0 6-2.7 6-6v-20c0-3.3-2.7-6-6-6-28.5 0-53.9 20.4-57.5 48.6C-3.9 258.8 22.7 288 56 288h40c0 52.2 25.4 98.1 64 127.3V496c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-48h128v48c0 8.8 7.2 16 16 16h64c8.8 0 16-7.2 16-16v-80.7c11.8-8.9 22.3-19.4 31.3-31.3H560c8.8 0 16-7.2 16-16V240c0-8.8-7.2-16-16-16zm-128 64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zM256 96h128c5.4 0 10.7.4 15.9.8 0-.3.1-.5.1-.8 0-53-43-96-96-96s-96 43-96 96c0 2.1.5 4.1.6 6.2 15.2-3.9 31-6.2 47.4-6.2z\"],\n    \"pills\": [576, 512, [], \"f484\", \"M112 32C50.1 32 0 82.1 0 144v224c0 61.9 50.1 112 112 112s112-50.1 112-112V144c0-61.9-50.1-112-112-112zm48 224H64V144c0-26.5 21.5-48 48-48s48 21.5 48 48v112zm139.7-29.7c-3.5-3.5-9.4-3.1-12.3.8-45.3 62.5-40.4 150.1 15.9 206.4 56.3 56.3 143.9 61.2 206.4 15.9 4-2.9 4.3-8.8.8-12.3L299.7 226.3zm229.8-19c-56.3-56.3-143.9-61.2-206.4-15.9-4 2.9-4.3 8.8-.8 12.3l210.8 210.8c3.5 3.5 9.4 3.1 12.3-.8 45.3-62.6 40.5-150.1-15.9-206.4z\"],\n    \"pizza-slice\": [512, 512, [], \"f818\", \"M158.87.15c-16.16-1.52-31.2 8.42-35.33 24.12l-14.81 56.27c187.62 5.49 314.54 130.61 322.48 317l56.94-15.78c15.72-4.36 25.49-19.68 23.62-35.9C490.89 165.08 340.78 17.32 158.87.15zm-58.47 112L.55 491.64a16.21 16.21 0 0 0 20 19.75l379-105.1c-4.27-174.89-123.08-292.14-299.15-294.1zM128 416a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm48-152a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm104 104a32 32 0 1 1 32-32 32 32 0 0 1-32 32z\"],\n    \"place-of-worship\": [640, 512, [], \"f67f\", \"M620.61 366.55L512 320v192h112c8.84 0 16-7.16 16-16V395.96a32 32 0 0 0-19.39-29.41zM0 395.96V496c0 8.84 7.16 16 16 16h112V320L19.39 366.55A32 32 0 0 0 0 395.96zm464.46-149.28L416 217.6V102.63c0-8.49-3.37-16.62-9.38-22.63L331.31 4.69c-6.25-6.25-16.38-6.25-22.62 0L233.38 80c-6 6-9.38 14.14-9.38 22.63V217.6l-48.46 29.08A31.997 31.997 0 0 0 160 274.12V512h96v-96c0-35.35 28.66-64 64-64s64 28.65 64 64v96h96V274.12c0-11.24-5.9-21.66-15.54-27.44z\"],\n    \"plane\": [576, 512, [], \"f072\", \"M480 192H365.71L260.61 8.06A16.014 16.014 0 0 0 246.71 0h-65.5c-10.63 0-18.3 10.17-15.38 20.39L214.86 192H112l-43.2-57.6c-3.02-4.03-7.77-6.4-12.8-6.4H16.01C5.6 128-2.04 137.78.49 147.88L32 256 .49 364.12C-2.04 374.22 5.6 384 16.01 384H56c5.04 0 9.78-2.37 12.8-6.4L112 320h102.86l-49.03 171.6c-2.92 10.22 4.75 20.4 15.38 20.4h65.5c5.74 0 11.04-3.08 13.89-8.06L365.71 320H480c35.35 0 96-28.65 96-64s-60.65-64-96-64z\"],\n    \"plane-arrival\": [640, 512, [], \"f5af\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM44.81 205.66l88.74 80a62.607 62.607 0 0 0 25.47 13.93l287.6 78.35c26.48 7.21 54.56 8.72 81 1.36 29.67-8.27 43.44-21.21 47.25-35.71 3.83-14.5-1.73-32.71-23.37-54.96-19.28-19.82-44.35-32.79-70.83-40l-97.51-26.56L282.8 30.22c-1.51-5.81-5.95-10.35-11.66-11.91L206.05.58c-10.56-2.88-20.9 5.32-20.71 16.44l47.92 164.21-102.2-27.84-27.59-67.88c-1.93-4.89-6.01-8.57-11.02-9.93L52.72 64.75c-10.34-2.82-20.53 5-20.72 15.88l.23 101.78c.19 8.91 6.03 17.34 12.58 23.25z\"],\n    \"plane-departure\": [640, 512, [], \"f5b0\", \"M624 448H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h608c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM80.55 341.27c6.28 6.84 15.1 10.72 24.33 10.71l130.54-.18a65.62 65.62 0 0 0 29.64-7.12l290.96-147.65c26.74-13.57 50.71-32.94 67.02-58.31 18.31-28.48 20.3-49.09 13.07-63.65-7.21-14.57-24.74-25.27-58.25-27.45-29.85-1.94-59.54 5.92-86.28 19.48l-98.51 49.99-218.7-82.06a17.799 17.799 0 0 0-18-1.11L90.62 67.29c-10.67 5.41-13.25 19.65-5.17 28.53l156.22 98.1-103.21 52.38-72.35-36.47a17.804 17.804 0 0 0-16.07.02L9.91 230.22c-10.44 5.3-13.19 19.12-5.57 28.08l76.21 82.97z\"],\n    \"play\": [448, 512, [], \"f04b\", \"M424.4 214.7L72.4 6.6C43.8-10.3 0 6.1 0 47.9V464c0 37.5 40.7 60.1 72.4 41.3l352-208c31.4-18.5 31.5-64.1 0-82.6z\"],\n    \"play-circle\": [512, 512, [], \"f144\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm115.7 272l-176 101c-15.8 8.8-35.7-2.5-35.7-21V152c0-18.4 19.8-29.8 35.7-21l176 107c16.4 9.2 16.4 32.9 0 42z\"],\n    \"plug\": [384, 512, [], \"f1e6\", \"M256 144V32c0-17.673 14.327-32 32-32s32 14.327 32 32v112h-64zm112 16H16c-8.837 0-16 7.163-16 16v32c0 8.837 7.163 16 16 16h16v32c0 77.406 54.969 141.971 128 156.796V512h64v-99.204c73.031-14.825 128-79.39 128-156.796v-32h16c8.837 0 16-7.163 16-16v-32c0-8.837-7.163-16-16-16zm-240-16V32c0-17.673-14.327-32-32-32S64 14.327 64 32v112h64z\"],\n    \"plus\": [448, 512, [], \"f067\", \"M416 208H272V64c0-17.67-14.33-32-32-32h-32c-17.67 0-32 14.33-32 32v144H32c-17.67 0-32 14.33-32 32v32c0 17.67 14.33 32 32 32h144v144c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32V304h144c17.67 0 32-14.33 32-32v-32c0-17.67-14.33-32-32-32z\"],\n    \"plus-circle\": [512, 512, [], \"f055\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm144 276c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92h-92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"plus-square\": [448, 512, [], \"f0fe\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-32 252c0 6.6-5.4 12-12 12h-92v92c0 6.6-5.4 12-12 12h-56c-6.6 0-12-5.4-12-12v-92H92c-6.6 0-12-5.4-12-12v-56c0-6.6 5.4-12 12-12h92v-92c0-6.6 5.4-12 12-12h56c6.6 0 12 5.4 12 12v92h92c6.6 0 12 5.4 12 12v56z\"],\n    \"podcast\": [448, 512, [], \"f2ce\", \"M267.429 488.563C262.286 507.573 242.858 512 224 512c-18.857 0-38.286-4.427-43.428-23.437C172.927 460.134 160 388.898 160 355.75c0-35.156 31.142-43.75 64-43.75s64 8.594 64 43.75c0 32.949-12.871 104.179-20.571 132.813zM156.867 288.554c-18.693-18.308-29.958-44.173-28.784-72.599 2.054-49.724 42.395-89.956 92.124-91.881C274.862 121.958 320 165.807 320 220c0 26.827-11.064 51.116-28.866 68.552-2.675 2.62-2.401 6.986.628 9.187 9.312 6.765 16.46 15.343 21.234 25.363 1.741 3.654 6.497 4.66 9.449 1.891 28.826-27.043 46.553-65.783 45.511-108.565-1.855-76.206-63.595-138.208-139.793-140.369C146.869 73.753 80 139.215 80 220c0 41.361 17.532 78.7 45.55 104.989 2.953 2.771 7.711 1.77 9.453-1.887 4.774-10.021 11.923-18.598 21.235-25.363 3.029-2.2 3.304-6.566.629-9.185zM224 0C100.204 0 0 100.185 0 224c0 89.992 52.602 165.647 125.739 201.408 4.333 2.118 9.267-1.544 8.535-6.31-2.382-15.512-4.342-30.946-5.406-44.339-.146-1.836-1.149-3.486-2.678-4.512-47.4-31.806-78.564-86.016-78.187-147.347.592-96.237 79.29-174.648 175.529-174.899C320.793 47.747 400 126.797 400 224c0 61.932-32.158 116.49-80.65 147.867-.999 14.037-3.069 30.588-5.624 47.23-.732 4.767 4.203 8.429 8.535 6.31C395.227 389.727 448 314.187 448 224 448 100.205 347.815 0 224 0zm0 160c-35.346 0-64 28.654-64 64s28.654 64 64 64 64-28.654 64-64-28.654-64-64-64z\"],\n    \"poll\": [448, 512, [], \"f681\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zM160 368c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V240c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v128zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16V144c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v224zm96 0c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-64c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v64z\"],\n    \"poll-h\": [448, 512, [], \"f682\", \"M448 432V80c0-26.5-21.5-48-48-48H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48zM112 192c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h128c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h224c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16H112zm0 96c-8.84 0-16-7.16-16-16v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32c0 8.84-7.16 16-16 16h-64z\"],\n    \"poo\": [512, 512, [], \"f2fe\", \"M451.4 369.1C468.7 356 480 335.4 480 312c0-39.8-32.2-72-72-72h-14.1c13.4-11.7 22.1-28.8 22.1-48 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C250.3 14.6 256 30.6 256 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 19.2 8.7 36.3 22.1 48H104c-39.8 0-72 32.2-72 72 0 23.4 11.3 44 28.6 57.1C26.3 374.6 0 404.1 0 440c0 39.8 32.2 72 72 72h368c39.8 0 72-32.2 72-72 0-35.9-26.3-65.4-60.6-70.9zM192 256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm159.5 139C341 422.9 293 448 256 448s-85-25.1-95.5-53c-2-5.3 2-11 7.8-11h175.4c5.8 0 9.8 5.7 7.8 11zM320 320c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"poo-storm\": [448, 512, [], \"f75a\", \"M308 336h-57.7l17.3-64.9c2-7.6-3.7-15.1-11.6-15.1h-68c-6 0-11.1 4.5-11.9 10.4l-16 120c-1 7.2 4.6 13.6 11.9 13.6h59.3l-23 97.2c-1.8 7.6 4 14.8 11.7 14.8 4.2 0 8.2-2.2 10.4-6l88-152c4.6-8-1.2-18-10.4-18zm66.4-111.3c5.9-9.6 9.6-20.6 9.6-32.7 0-35.3-28.7-64-64-64h-5.9c3.6-10.1 5.9-20.7 5.9-32 0-53-43-96-96-96-5.2 0-10.2.7-15.1 1.5C218.3 14.6 224 30.6 224 48c0 44.2-35.8 80-80 80h-16c-35.3 0-64 28.7-64 64 0 12.1 3.7 23.1 9.6 32.7C32.6 228 0 262.2 0 304c0 44 36 80 80 80h48.3c.1-.6 0-1.2 0-1.8l16-120c3-21.8 21.7-38.2 43.7-38.2h68c13.8 0 26.5 6.3 34.9 17.2s11.2 24.8 7.6 38.1l-6.6 24.7h16c15.7 0 30.3 8.4 38.1 22 7.8 13.6 7.8 30.5 0 44l-8.1 14h30c44 0 80-36 80-80 .1-41.8-32.5-76-73.5-79.3z\"],\n    \"poop\": [512, 512, [], \"f619\", \"M451.36 369.14C468.66 355.99 480 335.41 480 312c0-39.77-32.24-72-72-72h-14.07c13.42-11.73 22.07-28.78 22.07-48 0-35.35-28.65-64-64-64h-5.88c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96-5.17 0-10.15.74-15.11 1.52C250.31 14.64 256 30.62 256 48c0 44.18-35.82 80-80 80h-16c-35.35 0-64 28.65-64 64 0 19.22 8.65 36.27 22.07 48H104c-39.76 0-72 32.23-72 72 0 23.41 11.34 43.99 28.64 57.14C26.31 374.62 0 404.12 0 440c0 39.76 32.24 72 72 72h368c39.76 0 72-32.24 72-72 0-35.88-26.31-65.38-60.64-70.86z\"],\n    \"portrait\": [384, 512, [], \"f3e0\", \"M336 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM192 128c35.3 0 64 28.7 64 64s-28.7 64-64 64-64-28.7-64-64 28.7-64 64-64zm112 236.8c0 10.6-10 19.2-22.4 19.2H102.4C90 384 80 375.4 80 364.8v-19.2c0-31.8 30.1-57.6 67.2-57.6h5c12.3 5.1 25.7 8 39.8 8s27.6-2.9 39.8-8h5c37.1 0 67.2 25.8 67.2 57.6v19.2z\"],\n    \"pound-sign\": [320, 512, [], \"f154\", \"M308 352h-45.495c-6.627 0-12 5.373-12 12v50.848H128V288h84c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-84v-63.556c0-32.266 24.562-57.086 61.792-57.086 23.658 0 45.878 11.505 57.652 18.849 5.151 3.213 11.888 2.051 15.688-2.685l28.493-35.513c4.233-5.276 3.279-13.005-2.119-17.081C273.124 54.56 236.576 32 187.931 32 106.026 32 48 84.742 48 157.961V224H20c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h28v128H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h296c6.627 0 12-5.373 12-12V364c0-6.627-5.373-12-12-12z\"],\n    \"power-off\": [512, 512, [], \"f011\", \"M400 54.1c63 45 104 118.6 104 201.9 0 136.8-110.8 247.7-247.5 248C120 504.3 8.2 393 8 256.4 7.9 173.1 48.9 99.3 111.8 54.2c11.7-8.3 28-4.8 35 7.7L162.6 90c5.9 10.5 3.1 23.8-6.6 31-41.5 30.8-68 79.6-68 134.9-.1 92.3 74.5 168.1 168 168.1 91.6 0 168.6-74.2 168-169.1-.3-51.8-24.7-101.8-68.1-134-9.7-7.2-12.4-20.5-6.5-30.9l15.8-28.1c7-12.4 23.2-16.1 34.8-7.8zM296 264V24c0-13.3-10.7-24-24-24h-32c-13.3 0-24 10.7-24 24v240c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24z\"],\n    \"pray\": [384, 512, [], \"f683\", \"M256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-30.63 169.75c14.06 16.72 39 19.09 55.97 5.22l88-72.02c17.09-13.98 19.59-39.19 5.62-56.28-13.97-17.11-39.19-19.59-56.31-5.62l-57.44 47-38.91-46.31c-15.44-18.39-39.22-27.92-64-25.33-24.19 2.48-45.25 16.27-56.37 36.92l-49.37 92.03c-23.4 43.64-8.69 96.37 34.19 123.75L131.56 432H40c-22.09 0-40 17.91-40 40s17.91 40 40 40h208c34.08 0 53.77-42.79 28.28-68.28L166.42 333.86l34.8-64.87 24.15 28.76z\"],\n    \"praying-hands\": [640, 512, [], \"f684\", \"M272 191.91c-17.6 0-32 14.4-32 32v80c0 8.84-7.16 16-16 16s-16-7.16-16-16v-76.55c0-17.39 4.72-34.47 13.69-49.39l77.75-129.59c9.09-15.16 4.19-34.81-10.97-43.91-14.45-8.67-32.72-4.3-42.3 9.21-.2.23-.62.21-.79.48l-117.26 175.9C117.56 205.9 112 224.31 112 243.29v80.23l-90.12 30.04A31.974 31.974 0 0 0 0 383.91v96c0 10.82 8.52 32 32 32 2.69 0 5.41-.34 8.06-1.03l179.19-46.62C269.16 449.99 304 403.8 304 351.91v-128c0-17.6-14.4-32-32-32zm346.12 161.73L528 323.6v-80.23c0-18.98-5.56-37.39-16.12-53.23L394.62 14.25c-.18-.27-.59-.24-.79-.48-9.58-13.51-27.85-17.88-42.3-9.21-15.16 9.09-20.06 28.75-10.97 43.91l77.75 129.59c8.97 14.92 13.69 32 13.69 49.39V304c0 8.84-7.16 16-16 16s-16-7.16-16-16v-80c0-17.6-14.4-32-32-32s-32 14.4-32 32v128c0 51.89 34.84 98.08 84.75 112.34l179.19 46.62c2.66.69 5.38 1.03 8.06 1.03 23.48 0 32-21.18 32-32v-96c0-13.77-8.81-25.99-21.88-30.35z\"],\n    \"prescription\": [384, 512, [], \"f5b1\", \"M301.26 352l78.06-78.06c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0L256 306.74l-83.96-83.96C219.31 216.8 256 176.89 256 128c0-53.02-42.98-96-96-96H16C7.16 32 0 39.16 0 48v256c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-80h18.75l128 128-78.06 78.06c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0L256 397.25l78.06 78.06c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63L301.26 352zM64 96h96c17.64 0 32 14.36 32 32s-14.36 32-32 32H64V96z\"],\n    \"prescription-bottle\": [384, 512, [], \"f485\", \"M32 192h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64h120c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H32v64c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v64zM360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24z\"],\n    \"prescription-bottle-alt\": [384, 512, [], \"f486\", \"M360 0H24C10.8 0 0 10.8 0 24v48c0 13.2 10.8 24 24 24h336c13.2 0 24-10.8 24-24V24c0-13.2-10.8-24-24-24zM32 480c0 17.6 14.4 32 32 32h256c17.6 0 32-14.4 32-32V128H32v352zm64-184c0-4.4 3.6-8 8-8h56v-56c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v56h56c4.4 0 8 3.6 8 8v48c0 4.4-3.6 8-8 8h-56v56c0 4.4-3.6 8-8 8h-48c-4.4 0-8-3.6-8-8v-56h-56c-4.4 0-8-3.6-8-8v-48z\"],\n    \"print\": [512, 512, [], \"f02f\", \"M448 192V77.25c0-8.49-3.37-16.62-9.37-22.63L393.37 9.37c-6-6-14.14-9.37-22.63-9.37H96C78.33 0 64 14.33 64 32v160c-35.35 0-64 28.65-64 64v112c0 8.84 7.16 16 16 16h48v96c0 17.67 14.33 32 32 32h320c17.67 0 32-14.33 32-32v-96h48c8.84 0 16-7.16 16-16V256c0-35.35-28.65-64-64-64zm-64 256H128v-96h256v96zm0-224H128V64h192v48c0 8.84 7.16 16 16 16h48v96zm48 72c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"procedures\": [640, 512, [], \"f487\", \"M528 224H272c-8.8 0-16 7.2-16 16v144H64V144c0-8.8-7.2-16-16-16H16c-8.8 0-16 7.2-16 16v352c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-48h512v48c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V336c0-61.9-50.1-112-112-112zM136 96h126.1l27.6 55.2c5.9 11.8 22.7 11.8 28.6 0L368 51.8 390.1 96H512c8.8 0 16-7.2 16-16s-7.2-16-16-16H409.9L382.3 8.8C376.4-3 359.6-3 353.7 8.8L304 108.2l-19.9-39.8c-1.4-2.7-4.1-4.4-7.2-4.4H136c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8zm24 256c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64z\"],\n    \"project-diagram\": [640, 512, [], \"f542\", \"M384 320H256c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V352c0-17.67-14.33-32-32-32zM192 32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v128c0 17.67 14.33 32 32 32h95.72l73.16 128.04C211.98 300.98 232.4 288 256 288h.28L192 175.51V128h224V64H192V32zM608 0H480c-17.67 0-32 14.33-32 32v128c0 17.67 14.33 32 32 32h128c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32z\"],\n    \"puzzle-piece\": [576, 512, [], \"f12e\", \"M519.442 288.651c-41.519 0-59.5 31.593-82.058 31.593C377.409 320.244 432 144 432 144s-196.288 80-196.288-3.297c0-35.827 36.288-46.25 36.288-85.985C272 19.216 243.885 0 210.539 0c-34.654 0-66.366 18.891-66.366 56.346 0 41.364 31.711 59.277 31.711 81.75C175.885 207.719 0 166.758 0 166.758v333.237s178.635 41.047 178.635-28.662c0-22.473-40-40.107-40-81.471 0-37.456 29.25-56.346 63.577-56.346 33.673 0 61.788 19.216 61.788 54.717 0 39.735-36.288 50.158-36.288 85.985 0 60.803 129.675 25.73 181.23 25.73 0 0-34.725-120.101 25.827-120.101 35.962 0 46.423 36.152 86.308 36.152C556.712 416 576 387.99 576 354.443c0-34.199-18.962-65.792-56.558-65.792z\"],\n    \"qrcode\": [448, 512, [], \"f029\", \"M0 224h192V32H0v192zM64 96h64v64H64V96zm192-64v192h192V32H256zm128 128h-64V96h64v64zM0 480h192V288H0v192zm64-128h64v64H64v-64zm352-64h32v128h-96v-32h-32v96h-64V288h96v32h64v-32zm0 160h32v32h-32v-32zm-64 0h32v32h-32v-32z\"],\n    \"question\": [384, 512, [], \"f128\", \"M202.021 0C122.202 0 70.503 32.703 29.914 91.026c-7.363 10.58-5.093 25.086 5.178 32.874l43.138 32.709c10.373 7.865 25.132 6.026 33.253-4.148 25.049-31.381 43.63-49.449 82.757-49.449 30.764 0 68.816 19.799 68.816 49.631 0 22.552-18.617 34.134-48.993 51.164-35.423 19.86-82.299 44.576-82.299 106.405V320c0 13.255 10.745 24 24 24h72.471c13.255 0 24-10.745 24-24v-5.773c0-42.86 125.268-44.645 125.268-160.627C377.504 66.256 286.902 0 202.021 0zM192 373.459c-38.196 0-69.271 31.075-69.271 69.271 0 38.195 31.075 69.27 69.271 69.27s69.271-31.075 69.271-69.271-31.075-69.27-69.271-69.27z\"],\n    \"question-circle\": [512, 512, [], \"f059\", \"M504 256c0 136.997-111.043 248-248 248S8 392.997 8 256C8 119.083 119.043 8 256 8s248 111.083 248 248zM262.655 90c-54.497 0-89.255 22.957-116.549 63.758-3.536 5.286-2.353 12.415 2.715 16.258l34.699 26.31c5.205 3.947 12.621 3.008 16.665-2.122 17.864-22.658 30.113-35.797 57.303-35.797 20.429 0 45.698 13.148 45.698 32.958 0 14.976-12.363 22.667-32.534 33.976C247.128 238.528 216 254.941 216 296v4c0 6.627 5.373 12 12 12h56c6.627 0 12-5.373 12-12v-1.333c0-28.462 83.186-29.647 83.186-106.667 0-58.002-60.165-102-116.531-102zM256 338c-25.365 0-46 20.635-46 46 0 25.364 20.635 46 46 46s46-20.636 46-46c0-25.365-20.635-46-46-46z\"],\n    \"quidditch\": [640, 512, [], \"f458\", \"M256.5 216.8L343.2 326s-16.6 102.4-76.6 150.1C206.7 523.8 0 510.2 0 510.2s3.8-23.1 11-55.4l94.6-112.2c4-4.7-.9-11.6-6.6-9.5l-60.4 22.1c14.4-41.7 32.7-80 54.6-97.5 59.9-47.8 163.3-40.9 163.3-40.9zm238 135c-44 0-79.8 35.8-79.8 79.9 0 44.1 35.7 79.9 79.8 79.9 44.1 0 79.8-35.8 79.8-79.9 0-44.2-35.8-79.9-79.8-79.9zM636.5 31L616.7 6c-5.5-6.9-15.5-8-22.4-2.6L361.8 181.3l-34.1-43c-5.1-6.4-15.1-5.2-18.6 2.2l-25.3 54.6 86.7 109.2 58.8-12.4c8-1.7 11.4-11.2 6.3-17.6l-34.1-42.9L634 53.5c6.9-5.5 8-15.6 2.5-22.5z\"],\n    \"quote-left\": [512, 512, [], \"f10d\", \"M464 256h-80v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8c-88.4 0-160 71.6-160 160v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zm-288 0H96v-64c0-35.3 28.7-64 64-64h8c13.3 0 24-10.7 24-24V56c0-13.3-10.7-24-24-24h-8C71.6 32 0 103.6 0 192v240c0 26.5 21.5 48 48 48h128c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"quote-right\": [512, 512, [], \"f10e\", \"M464 32H336c-26.5 0-48 21.5-48 48v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48zm-288 0H48C21.5 32 0 53.5 0 80v128c0 26.5 21.5 48 48 48h80v64c0 35.3-28.7 64-64 64h-8c-13.3 0-24 10.7-24 24v48c0 13.3 10.7 24 24 24h8c88.4 0 160-71.6 160-160V80c0-26.5-21.5-48-48-48z\"],\n    \"quran\": [448, 512, [], \"f687\", \"M448 358.4V25.6c0-16-9.6-25.6-25.6-25.6H96C41.6 0 0 41.6 0 96v320c0 54.4 41.6 96 96 96h326.4c12.8 0 25.6-9.6 25.6-25.6v-16c0-6.4-3.2-12.8-9.6-19.2-3.2-16-3.2-60.8 0-73.6 6.4-3.2 9.6-9.6 9.6-19.2zM301.08 145.82c.6-1.21 1.76-1.82 2.92-1.82s2.32.61 2.92 1.82l11.18 22.65 25 3.63c2.67.39 3.74 3.67 1.81 5.56l-18.09 17.63 4.27 24.89c.36 2.11-1.31 3.82-3.21 3.82-.5 0-1.02-.12-1.52-.38L304 211.87l-22.36 11.75c-.5.26-1.02.38-1.52.38-1.9 0-3.57-1.71-3.21-3.82l4.27-24.89-18.09-17.63c-1.94-1.89-.87-5.17 1.81-5.56l24.99-3.63 11.19-22.65zm-57.89-69.01c13.67 0 27.26 2.49 40.38 7.41a6.775 6.775 0 1 1-2.38 13.12c-.67 0-3.09-.21-4.13-.21-52.31 0-94.86 42.55-94.86 94.86 0 52.3 42.55 94.86 94.86 94.86 1.03 0 3.48-.21 4.13-.21 3.93 0 6.8 3.14 6.8 6.78 0 2.98-1.94 5.51-4.62 6.42-13.07 4.87-26.59 7.34-40.19 7.34C179.67 307.19 128 255.51 128 192c0-63.52 51.67-115.19 115.19-115.19zM380.8 448H96c-19.2 0-32-12.8-32-32s16-32 32-32h284.8v64z\"],\n    \"radiation\": [496, 512, [], \"f7b9\", \"M328.2 255.8h151.6c9.1 0 16.8-7.7 16.2-16.8-5.1-75.8-44.4-142.2-102.5-184.2-7.4-5.3-17.9-2.9-22.7 4.8L290.4 188c22.6 14.3 37.8 39.2 37.8 67.8zm-37.8 67.7c-12.3 7.7-26.8 12.4-42.4 12.4-15.6 0-30-4.7-42.4-12.4L125.2 452c-4.8 7.7-2.4 18.1 5.6 22.4C165.7 493.2 205.6 504 248 504s82.3-10.8 117.2-29.6c8-4.3 10.4-14.8 5.6-22.4l-80.4-128.5zM248 303.8c26.5 0 48-21.5 48-48s-21.5-48-48-48-48 21.5-48 48 21.5 48 48 48zm-231.8-48h151.6c0-28.6 15.2-53.5 37.8-67.7L125.2 59.7c-4.8-7.7-15.3-10.2-22.7-4.8C44.4 96.9 5.1 163.3 0 239.1c-.6 9 7.1 16.7 16.2 16.7z\"],\n    \"radiation-alt\": [496, 512, [], \"f7ba\", \"M312 256h79.1c9.2 0 16.9-7.7 16-16.8-4.6-43.6-27-81.8-59.5-107.8-7.6-6.1-18.8-4.5-24 3.8L281.9 202c18 11.2 30.1 31.2 30.1 54zm-97.8 54.1L172.4 377c-4.9 7.8-2.4 18.4 5.8 22.5 21.1 10.4 44.7 16.5 69.8 16.5s48.7-6.1 69.9-16.5c8.2-4.1 10.6-14.7 5.8-22.5l-41.8-66.9c-9.8 6.2-21.4 9.9-33.8 9.9s-24.1-3.7-33.9-9.9zM104.9 256H184c0-22.8 12.1-42.8 30.2-54.1l-41.7-66.8c-5.2-8.3-16.4-9.9-24-3.8-32.6 26-54.9 64.2-59.5 107.8-1.1 9.2 6.7 16.9 15.9 16.9zM248 504c137 0 248-111 248-248S385 8 248 8 0 119 0 256s111 248 248 248zm0-432c101.5 0 184 82.5 184 184s-82.5 184-184 184S64 357.5 64 256 146.5 72 248 72zm0 216c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"rainbow\": [576, 512, [], \"f75b\", \"M268.3 32.7C115.4 42.9 0 176.9 0 330.2V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C64 186.8 180.9 80.3 317.5 97.9 430.4 112.4 512 214 512 327.8V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-165.3-140-298.6-307.7-287.3zm-5.6 96.9C166 142 96 229.1 96 326.7V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-74.8 64.5-134.8 140.8-127.4 66.5 6.5 115.2 66.2 115.2 133.1V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-114.2-100.2-205.4-217.3-190.4zm6.2 96.3c-45.6 8.9-76.9 51.5-76.9 97.9V464c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-17.6 14.3-32 32-32s32 14.4 32 32v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320c0-59.2-53.8-106-115.1-94.1z\"],\n    \"random\": [512, 512, [], \"f074\", \"M504.971 359.029c9.373 9.373 9.373 24.569 0 33.941l-80 79.984c-15.01 15.01-40.971 4.49-40.971-16.971V416h-58.785a12.004 12.004 0 0 1-8.773-3.812l-70.556-75.596 53.333-57.143L352 336h32v-39.981c0-21.438 25.943-31.998 40.971-16.971l80 79.981zM12 176h84l52.781 56.551 53.333-57.143-70.556-75.596A11.999 11.999 0 0 0 122.785 96H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12zm372 0v39.984c0 21.46 25.961 31.98 40.971 16.971l80-79.984c9.373-9.373 9.373-24.569 0-33.941l-80-79.981C409.943 24.021 384 34.582 384 56.019V96h-58.785a12.004 12.004 0 0 0-8.773 3.812L96 336H12c-6.627 0-12 5.373-12 12v56c0 6.627 5.373 12 12 12h110.785c3.326 0 6.503-1.381 8.773-3.812L352 176h32z\"],\n    \"receipt\": [384, 512, [], \"f543\", \"M358.4 3.2L320 48 265.6 3.2a15.9 15.9 0 0 0-19.2 0L192 48 137.6 3.2a15.9 15.9 0 0 0-19.2 0L64 48 25.6 3.2C15-4.7 0 2.8 0 16v480c0 13.2 15 20.7 25.6 12.8L64 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L192 464l54.4 44.8a15.9 15.9 0 0 0 19.2 0L320 464l38.4 44.8c10.5 7.9 25.6.4 25.6-12.8V16c0-13.2-15-20.7-25.6-12.8zM320 360c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16zm0-96c0 4.4-3.6 8-8 8H72c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h240c4.4 0 8 3.6 8 8v16z\"],\n    \"recycle\": [512, 512, [], \"f1b8\", \"M184.561 261.903c3.232 13.997-12.123 24.635-24.068 17.168l-40.736-25.455-50.867 81.402C55.606 356.273 70.96 384 96.012 384H148c6.627 0 12 5.373 12 12v40c0 6.627-5.373 12-12 12H96.115c-75.334 0-121.302-83.048-81.408-146.88l50.822-81.388-40.725-25.448c-12.081-7.547-8.966-25.961 4.879-29.158l110.237-25.45c8.611-1.988 17.201 3.381 19.189 11.99l25.452 110.237zm98.561-182.915l41.289 66.076-40.74 25.457c-12.051 7.528-9 25.953 4.879 29.158l110.237 25.45c8.672 1.999 17.215-3.438 19.189-11.99l25.45-110.237c3.197-13.844-11.99-24.719-24.068-17.168l-40.687 25.424-41.263-66.082c-37.521-60.033-125.209-60.171-162.816 0l-17.963 28.766c-3.51 5.62-1.8 13.021 3.82 16.533l33.919 21.195c5.62 3.512 13.024 1.803 16.536-3.817l17.961-28.743c12.712-20.341 41.973-19.676 54.257-.022zM497.288 301.12l-27.515-44.065c-3.511-5.623-10.916-7.334-16.538-3.821l-33.861 21.159c-5.62 3.512-7.33 10.915-3.818 16.536l27.564 44.112c13.257 21.211-2.057 48.96-27.136 48.96H320V336.02c0-14.213-17.242-21.383-27.313-11.313l-80 79.981c-6.249 6.248-6.249 16.379 0 22.627l80 79.989C302.689 517.308 320 510.3 320 495.989V448h95.88c75.274 0 121.335-82.997 81.408-146.88z\"],\n    \"redo\": [512, 512, [], \"f01e\", \"M500.33 0h-47.41a12 12 0 0 0-12 12.57l4 82.76A247.42 247.42 0 0 0 256 8C119.34 8 7.9 119.53 8 256.19 8.1 393.07 119.1 504 256 504a247.1 247.1 0 0 0 166.18-63.91 12 12 0 0 0 .48-17.43l-34-34a12 12 0 0 0-16.38-.55A176 176 0 1 1 402.1 157.8l-101.53-4.87a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12h200.33a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12z\"],\n    \"redo-alt\": [512, 512, [], \"f2f9\", \"M256.455 8c66.269.119 126.437 26.233 170.859 68.685l35.715-35.715C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.75c-30.864-28.899-70.801-44.907-113.23-45.273-92.398-.798-170.283 73.977-169.484 169.442C88.764 348.009 162.184 424 256 424c41.127 0 79.997-14.678 110.629-41.556 4.743-4.161 11.906-3.908 16.368.553l39.662 39.662c4.872 4.872 4.631 12.815-.482 17.433C378.202 479.813 319.926 504 256 504 119.034 504 8.001 392.967 8 256.002 7.999 119.193 119.646 7.755 256.455 8z\"],\n    \"registered\": [512, 512, [], \"f25d\", \"M285.363 207.475c0 18.6-9.831 28.431-28.431 28.431h-29.876v-56.14h23.378c28.668 0 34.929 8.773 34.929 27.709zM504 256c0 136.967-111.033 248-248 248S8 392.967 8 256 119.033 8 256 8s248 111.033 248 248zM363.411 360.414c-46.729-84.825-43.299-78.636-44.702-80.98 23.432-15.172 37.945-42.979 37.945-74.486 0-54.244-31.5-89.252-105.498-89.252h-70.667c-13.255 0-24 10.745-24 24V372c0 13.255 10.745 24 24 24h22.567c13.255 0 24-10.745 24-24v-71.663h25.556l44.129 82.937a24.001 24.001 0 0 0 21.188 12.727h24.464c18.261-.001 29.829-19.591 21.018-35.587z\"],\n    \"remove-format\": [640, 512, [], \"f87d\", \"M336 416h-11.17l9.26-27.77L267 336.4 240.49 416H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm297.82 42.1L377 259.59 426.17 112H544v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16H176a16 16 0 0 0-16 16v43.9L45.46 3.38A16 16 0 0 0 23 6.19L3.37 31.46a16 16 0 0 0 2.81 22.45l588.36 454.72a16 16 0 0 0 22.46-2.81l19.64-25.27a16 16 0 0 0-2.82-22.45zM309.91 207.76L224 141.36V112h117.83z\"],\n    \"reply\": [512, 512, [], \"f3e5\", \"M8.309 189.836L184.313 37.851C199.719 24.546 224 35.347 224 56.015v80.053c160.629 1.839 288 34.032 288 186.258 0 61.441-39.581 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 45.344-145.012-21.507-183.51-176.59-185.742V360c0 20.7-24.3 31.453-39.687 18.164l-176.004-152c-11.071-9.562-11.086-26.753 0-36.328z\"],\n    \"reply-all\": [576, 512, [], \"f122\", \"M136.309 189.836L312.313 37.851C327.72 24.546 352 35.348 352 56.015v82.763c129.182 10.231 224 52.212 224 183.548 0 61.441-39.582 122.309-83.333 154.132-13.653 9.931-33.111-2.533-28.077-18.631 38.512-123.162-3.922-169.482-112.59-182.015v84.175c0 20.701-24.3 31.453-39.687 18.164L136.309 226.164c-11.071-9.561-11.086-26.753 0-36.328zm-128 36.328L184.313 378.15C199.7 391.439 224 380.687 224 359.986v-15.818l-108.606-93.785A55.96 55.96 0 0 1 96 207.998a55.953 55.953 0 0 1 19.393-42.38L224 71.832V56.015c0-20.667-24.28-31.469-39.687-18.164L8.309 189.836c-11.086 9.575-11.071 26.767 0 36.328z\"],\n    \"republican\": [640, 512, [], \"f75e\", \"M544 192c0-88.4-71.6-160-160-160H160C71.6 32 0 103.6 0 192v64h544v-64zm-367.7-21.6l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L128 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L272 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zm144 0l-19.8 19.3 4.7 27.3c.8 4.9-4.3 8.6-8.7 6.3L416 210.4l-24.5 12.9c-4.3 2.3-9.5-1.4-8.7-6.3l4.7-27.3-19.8-19.3c-3.6-3.5-1.6-9.5 3.3-10.2l27.4-4 12.2-24.8c2.2-4.5 8.6-4.4 10.7 0l12.2 24.8 27.4 4c5 .7 6.9 6.7 3.4 10.2zM624 320h-32c-8.8 0-16 7.2-16 16v64c0 8.8-7.2 16-16 16s-16-7.2-16-16V288H0v176c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16v-80h192v80c0 8.8 7.2 16 16 16h96c8.8 0 16-7.2 16-16V352h32v43.3c0 41.8 30 80.1 71.6 84.3 47.8 4.9 88.4-32.7 88.4-79.6v-64c0-8.8-7.2-16-16-16z\"],\n    \"restroom\": [640, 512, [], \"f7bd\", \"M128 128c35.3 0 64-28.7 64-64S163.3 0 128 0 64 28.7 64 64s28.7 64 64 64zm384 0c35.3 0 64-28.7 64-64S547.3 0 512 0s-64 28.7-64 64 28.7 64 64 64zm127.3 226.5l-45.6-185.8c-3.3-13.5-15.5-23-29.8-24.2-15 9.7-32.8 15.5-52 15.5-19.2 0-37-5.8-52-15.5-14.3 1.2-26.5 10.7-29.8 24.2l-45.6 185.8C381 369.6 393 384 409.2 384H464v104c0 13.3 10.7 24 24 24h48c13.3 0 24-10.7 24-24V384h54.8c16.2 0 28.2-14.4 24.5-29.5zM336 0h-32c-8.8 0-16 7.2-16 16v480c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zM180.1 144.4c-15 9.8-32.9 15.6-52.1 15.6-19.2 0-37.1-5.8-52.1-15.6C51.3 146.5 32 166.9 32 192v136c0 13.3 10.7 24 24 24h8v136c0 13.3 10.7 24 24 24h80c13.3 0 24-10.7 24-24V352h8c13.3 0 24-10.7 24-24V192c0-25.1-19.3-45.5-43.9-47.6z\"],\n    \"retweet\": [640, 512, [], \"f079\", \"M629.657 343.598L528.971 444.284c-9.373 9.372-24.568 9.372-33.941 0L394.343 343.598c-9.373-9.373-9.373-24.569 0-33.941l10.823-10.823c9.562-9.562 25.133-9.34 34.419.492L480 342.118V160H292.451a24.005 24.005 0 0 1-16.971-7.029l-16-16C244.361 121.851 255.069 96 276.451 96H520c13.255 0 24 10.745 24 24v222.118l40.416-42.792c9.285-9.831 24.856-10.054 34.419-.492l10.823 10.823c9.372 9.372 9.372 24.569-.001 33.941zm-265.138 15.431A23.999 23.999 0 0 0 347.548 352H160V169.881l40.416 42.792c9.286 9.831 24.856 10.054 34.419.491l10.822-10.822c9.373-9.373 9.373-24.569 0-33.941L144.971 67.716c-9.373-9.373-24.569-9.373-33.941 0L10.343 168.402c-9.373 9.373-9.373 24.569 0 33.941l10.822 10.822c9.562 9.562 25.133 9.34 34.419-.491L96 169.881V392c0 13.255 10.745 24 24 24h243.549c21.382 0 32.09-25.851 16.971-40.971l-16.001-16z\"],\n    \"ribbon\": [448, 512, [], \"f4d6\", \"M6.1 444.3c-9.6 10.8-7.5 27.6 4.5 35.7l68.8 27.9c9.9 6.7 23.3 5 31.3-3.8l91.8-101.9-79.2-87.9-117.2 130zm435.8 0s-292-324.6-295.4-330.1c15.4-8.4 40.2-17.9 77.5-17.9s62.1 9.5 77.5 17.9c-3.3 5.6-56 64.6-56 64.6l79.1 87.7 34.2-38c28.7-31.9 33.3-78.6 11.4-115.5l-43.7-73.5c-4.3-7.2-9.9-13.3-16.8-18-40.7-27.6-127.4-29.7-171.4 0-6.9 4.7-12.5 10.8-16.8 18l-43.6 73.2c-1.5 2.5-37.1 62.2 11.5 116L337.5 504c8 8.9 21.4 10.5 31.3 3.8l68.8-27.9c11.9-8 14-24.8 4.3-35.6z\"],\n    \"ring\": [512, 512, [], \"f70b\", \"M256 64C110.06 64 0 125.91 0 208v98.13C0 384.48 114.62 448 256 448s256-63.52 256-141.87V208c0-82.09-110.06-144-256-144zm0 64c106.04 0 192 35.82 192 80 0 9.26-3.97 18.12-10.91 26.39C392.15 208.21 328.23 192 256 192s-136.15 16.21-181.09 42.39C67.97 226.12 64 217.26 64 208c0-44.18 85.96-80 192-80zM120.43 264.64C155.04 249.93 201.64 240 256 240s100.96 9.93 135.57 24.64C356.84 279.07 308.93 288 256 288s-100.84-8.93-135.57-23.36z\"],\n    \"road\": [576, 512, [], \"f018\", \"M573.19 402.67l-139.79-320C428.43 71.29 417.6 64 405.68 64h-97.59l2.45 23.16c.5 4.72-3.21 8.84-7.96 8.84h-29.16c-4.75 0-8.46-4.12-7.96-8.84L267.91 64h-97.59c-11.93 0-22.76 7.29-27.73 18.67L2.8 402.67C-6.45 423.86 8.31 448 30.54 448h196.84l10.31-97.68c.86-8.14 7.72-14.32 15.91-14.32h68.8c8.19 0 15.05 6.18 15.91 14.32L348.62 448h196.84c22.23 0 36.99-24.14 27.73-45.33zM260.4 135.16a8 8 0 0 1 7.96-7.16h39.29c4.09 0 7.53 3.09 7.96 7.16l4.6 43.58c.75 7.09-4.81 13.26-11.93 13.26h-40.54c-7.13 0-12.68-6.17-11.93-13.26l4.59-43.58zM315.64 304h-55.29c-9.5 0-16.91-8.23-15.91-17.68l5.07-48c.86-8.14 7.72-14.32 15.91-14.32h45.15c8.19 0 15.05 6.18 15.91 14.32l5.07 48c1 9.45-6.41 17.68-15.91 17.68z\"],\n    \"robot\": [640, 512, [], \"f544\", \"M0 256v128c0 17.7 14.3 32 32 32h32V224H32c-17.7 0-32 14.3-32 32zM464 96H352V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v64H176c-44.2 0-80 35.8-80 80v272c0 35.3 28.7 64 64 64h320c35.3 0 64-28.7 64-64V176c0-44.2-35.8-80-80-80zM256 416h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm128 120h-64v-32h64v32zm96 0h-64v-32h64v32zm-32-120c-22.1 0-40-17.9-40-40s17.9-40 40-40 40 17.9 40 40-17.9 40-40 40zm192-72h-32v192h32c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32z\"],\n    \"rocket\": [512, 512, [], \"f135\", \"M505.05 19.1a15.89 15.89 0 0 0-12.2-12.2C460.65 0 435.46 0 410.36 0c-103.2 0-165.1 55.2-211.29 128H94.87A48 48 0 0 0 52 154.49l-49.42 98.8A24 24 0 0 0 24.07 288h103.77l-22.47 22.47a32 32 0 0 0 0 45.25l50.9 50.91a32 32 0 0 0 45.26 0L224 384.16V488a24 24 0 0 0 34.7 21.49l98.7-49.39a47.91 47.91 0 0 0 26.5-42.9V312.79c72.59-46.3 128-108.4 128-211.09.1-25.2.1-50.4-6.85-82.6zM384 168a40 40 0 1 1 40-40 40 40 0 0 1-40 40z\"],\n    \"route\": [512, 512, [], \"f4d7\", \"M416 320h-96c-17.6 0-32-14.4-32-32s14.4-32 32-32h96s96-107 96-160-43-96-96-96-96 43-96 96c0 25.5 22.2 63.4 45.3 96H320c-52.9 0-96 43.1-96 96s43.1 96 96 96h96c17.6 0 32 14.4 32 32s-14.4 32-32 32H185.5c-16 24.8-33.8 47.7-47.3 64H416c52.9 0 96-43.1 96-96s-43.1-96-96-96zm0-256c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM96 256c-53 0-96 43-96 96s96 160 96 160 96-107 96-160-43-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"rss\": [448, 512, [], \"f09e\", \"M128.081 415.959c0 35.369-28.672 64.041-64.041 64.041S0 451.328 0 415.959s28.672-64.041 64.041-64.041 64.04 28.673 64.04 64.041zm175.66 47.25c-8.354-154.6-132.185-278.587-286.95-286.95C7.656 175.765 0 183.105 0 192.253v48.069c0 8.415 6.49 15.472 14.887 16.018 111.832 7.284 201.473 96.702 208.772 208.772.547 8.397 7.604 14.887 16.018 14.887h48.069c9.149.001 16.489-7.655 15.995-16.79zm144.249.288C439.596 229.677 251.465 40.445 16.503 32.01 7.473 31.686 0 38.981 0 48.016v48.068c0 8.625 6.835 15.645 15.453 15.999 191.179 7.839 344.627 161.316 352.465 352.465.353 8.618 7.373 15.453 15.999 15.453h48.068c9.034-.001 16.329-7.474 16.005-16.504z\"],\n    \"rss-square\": [448, 512, [], \"f143\", \"M400 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM112 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm157.533 0h-34.335c-6.011 0-11.051-4.636-11.442-10.634-5.214-80.05-69.243-143.92-149.123-149.123-5.997-.39-10.633-5.431-10.633-11.441v-34.335c0-6.535 5.468-11.777 11.994-11.425 110.546 5.974 198.997 94.536 204.964 204.964.352 6.526-4.89 11.994-11.425 11.994zm103.027 0h-34.334c-6.161 0-11.175-4.882-11.427-11.038-5.598-136.535-115.204-246.161-251.76-251.76C68.882 152.949 64 147.935 64 141.774V107.44c0-6.454 5.338-11.664 11.787-11.432 167.83 6.025 302.21 141.191 308.205 308.205.232 6.449-4.978 11.787-11.432 11.787z\"],\n    \"ruble-sign\": [384, 512, [], \"f158\", \"M239.36 320C324.48 320 384 260.542 384 175.071S324.48 32 239.36 32H76c-6.627 0-12 5.373-12 12v206.632H12c-6.627 0-12 5.373-12 12V308c0 6.627 5.373 12 12 12h52v32H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h52v52c0 6.627 5.373 12 12 12h58.56c6.627 0 12-5.373 12-12v-52H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12H146.56v-32h92.8zm-92.8-219.252h78.72c46.72 0 74.88 29.11 74.88 74.323 0 45.832-28.16 75.561-76.16 75.561h-77.44V100.748z\"],\n    \"ruler\": [640, 512, [], \"f545\", \"M635.7 167.2L556.1 31.7c-8.8-15-28.3-20.1-43.5-11.5l-69 39.1L503.3 161c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L416 75l-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L333.2 122 278 153.3 337.8 255c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-59.7-101.7-55.2 31.3 27.9 47.4c2.2 3.8.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9l-27.9-47.5-55.2 31.3 59.7 101.7c2.2 3.7.9 8.5-2.9 10.7l-13.8 7.8c-3.8 2.2-8.7.9-10.9-2.9L84.9 262.9l-69 39.1C.7 310.7-4.6 329.8 4.2 344.8l79.6 135.6c8.8 15 28.3 20.1 43.5 11.5L624.1 210c15.2-8.6 20.4-27.8 11.6-42.8z\"],\n    \"ruler-combined\": [512, 512, [], \"f546\", \"M160 288h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56v-64h-56c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h56V96h-56c-4.42 0-8-3.58-8-8V72c0-4.42 3.58-8 8-8h56V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 2.77.91 5.24 1.57 7.8L160 329.38V288zm320 64h-32v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-64v56c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-56h-41.37L24.2 510.43c2.56.66 5.04 1.57 7.8 1.57h448c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"ruler-horizontal\": [576, 512, [], \"f547\", \"M544 128h-48v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8h-16c-4.42 0-8-3.58-8-8v-88h-64v88c0 4.42-3.58 8-8 8H88c-4.42 0-8-3.58-8-8v-88H32c-17.67 0-32 14.33-32 32v192c0 17.67 14.33 32 32 32h512c17.67 0 32-14.33 32-32V160c0-17.67-14.33-32-32-32z\"],\n    \"ruler-vertical\": [256, 512, [], \"f548\", \"M168 416c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88v-64h-88c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h88V32c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v448c0 17.67 14.33 32 32 32h192c17.67 0 32-14.33 32-32v-64h-88z\"],\n    \"running\": [416, 512, [], \"f70c\", \"M272 96c26.51 0 48-21.49 48-48S298.51 0 272 0s-48 21.49-48 48 21.49 48 48 48zM113.69 317.47l-14.8 34.52H32c-17.67 0-32 14.33-32 32s14.33 32 32 32h77.45c19.25 0 36.58-11.44 44.11-29.09l8.79-20.52-10.67-6.3c-17.32-10.23-30.06-25.37-37.99-42.61zM384 223.99h-44.03l-26.06-53.25c-12.5-25.55-35.45-44.23-61.78-50.94l-71.08-21.14c-28.3-6.8-57.77-.55-80.84 17.14l-39.67 30.41c-14.03 10.75-16.69 30.83-5.92 44.86s30.84 16.66 44.86 5.92l39.69-30.41c7.67-5.89 17.44-8 25.27-6.14l14.7 4.37-37.46 87.39c-12.62 29.48-1.31 64.01 26.3 80.31l84.98 50.17-27.47 87.73c-5.28 16.86 4.11 34.81 20.97 40.09 3.19 1 6.41 1.48 9.58 1.48 13.61 0 26.23-8.77 30.52-22.45l31.64-101.06c5.91-20.77-2.89-43.08-21.64-54.39l-61.24-36.14 31.31-78.28 20.27 41.43c8 16.34 24.92 26.89 43.11 26.89H384c17.67 0 32-14.33 32-32s-14.33-31.99-32-31.99z\"],\n    \"rupee-sign\": [320, 512, [], \"f156\", \"M308 96c6.627 0 12-5.373 12-12V44c0-6.627-5.373-12-12-12H12C5.373 32 0 37.373 0 44v44.748c0 6.627 5.373 12 12 12h85.28c27.308 0 48.261 9.958 60.97 27.252H12c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h158.757c-6.217 36.086-32.961 58.632-74.757 58.632H12c-6.627 0-12 5.373-12 12v53.012c0 3.349 1.4 6.546 3.861 8.818l165.052 152.356a12.001 12.001 0 0 0 8.139 3.182h82.562c10.924 0 16.166-13.408 8.139-20.818L116.871 319.906c76.499-2.34 131.144-53.395 138.318-127.906H308c6.627 0 12-5.373 12-12v-40c0-6.627-5.373-12-12-12h-58.69c-3.486-11.541-8.28-22.246-14.252-32H308z\"],\n    \"sad-cry\": [496, 512, [], \"f5b3\", \"M248 8C111 8 0 119 0 256c0 90.1 48.2 168.7 120 212.1V288c0-8.8 7.2-16 16-16s16 7.2 16 16v196.7c29.5 12.4 62 19.3 96 19.3s66.5-6.9 96-19.3V288c0-8.8 7.2-16 16-16s16 7.2 16 16v180.1C447.8 424.7 496 346 496 256 496 119 385 8 248 8zm-65.5 216.5c-14.8-13.2-46.2-13.2-61 0L112 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S208 197 212 222.2c.8 5-1.7 10-6.1 12.4-5.8 3.1-11.2.7-13.7-1.6l-9.7-8.5zM248 416c-26.5 0-48-28.7-48-64s21.5-64 48-64 48 28.7 48 64-21.5 64-48 64zm149.8-181.5c-5.8 3.1-11.2.7-13.7-1.6l-9.5-8.5c-14.8-13.2-46.2-13.2-61 0L304 233c-3.8 3.3-9.3 4-13.7 1.6-4.4-2.4-6.9-7.4-6.1-12.4 4-25.2 34.2-42.1 59.9-42.1S400 197 404 222.2c.6 4.9-1.8 9.9-6.2 12.3z\"],\n    \"sad-tear\": [496, 512, [], \"f5b4\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zM152 416c-26.5 0-48-21-48-47 0-20 28.5-60.4 41.6-77.8 3.2-4.3 9.6-4.3 12.8 0C171.5 308.6 200 349 200 369c0 26-21.5 47-48 47zm16-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm170.2 154.2C315.8 367.4 282.9 352 248 352c-21.2 0-21.2-32 0-32 44.4 0 86.3 19.6 114.7 53.8 13.8 16.4-11.2 36.5-24.5 20.4z\"],\n    \"satellite\": [512, 512, [], \"f7bf\", \"M502.7 265l-80.3-80.4 47.8-47.9c13.1-13.1 13.1-34.4 0-47.5l-47.5-47.5c-13.1-13.1-34.4-13.1-47.5 0l-47.8 47.9-80.3-80.3C240.8 3.1 232.7 0 224.5 0S208.2 3.1 202 9.3L105.3 106c-12.4 12.4-12.4 32.6 0 45.1l80.3 80.4-9.8 9.8C122.1 217 59.6 218.6 7.3 246.7c-8.5 4.6-9.6 16.4-2.8 23.2L112 377.4l-17.8 17.8c-2.6-.7-5-1.6-7.8-1.6-17.7 0-32 14.3-32 32s14.3 32 32 32 32-14.3 32-32c0-2.8-.9-5.2-1.6-7.8l17.8-17.8 107.5 107.5c6.8 6.8 18.7 5.7 23.2-2.8 28.1-52.3 29.7-114.8 5.4-168.5l9.9-9.9 80.3 80.4c6.2 6.2 14.4 9.3 22.5 9.3s16.3-3.1 22.5-9.3l96.7-96.7c12.5-12.4 12.5-32.6.1-45zm-352-136.5l73.8-73.8 68.9 68.9-73.8 73.8-68.9-68.9zm232.8 232.8l-68.9-68.9 73.8-73.8 68.9 68.9-73.8 73.8z\"],\n    \"satellite-dish\": [512, 512, [], \"f7c0\", \"M188.8 345.9l27.4-27.4c2.6.7 5 1.6 7.8 1.6 17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32c0 2.8.9 5.2 1.6 7.8l-27.4 27.4L49.4 206.5c-7.3-7.3-20.1-6.1-25 3-41.8 77.8-29.9 176.7 35.7 242.3 65.6 65.6 164.6 77.5 242.3 35.7 9.2-4.9 10.4-17.7 3-25L188.8 345.9zM209 0c-9.2-.5-17 6.8-17 16v31.6c0 8.5 6.6 15.5 15 15.9 129.4 7 233.4 112 240.9 241.5.5 8.4 7.5 15 15.9 15h32.1c9.2 0 16.5-7.8 16-17C503.4 139.8 372.2 8.6 209 0zm.3 96c-9.3-.7-17.3 6.7-17.3 16.1v32.1c0 8.4 6.5 15.3 14.8 15.9 76.8 6.3 138 68.2 144.9 145.2.8 8.3 7.6 14.7 15.9 14.7h32.2c9.3 0 16.8-8 16.1-17.3-8.4-110.1-96.5-198.2-206.6-206.7z\"],\n    \"save\": [448, 512, [], \"f0c7\", \"M433.941 129.941l-83.882-83.882A48 48 0 0 0 316.118 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48V163.882a48 48 0 0 0-14.059-33.941zM224 416c-35.346 0-64-28.654-64-64 0-35.346 28.654-64 64-64s64 28.654 64 64c0 35.346-28.654 64-64 64zm96-304.52V212c0 6.627-5.373 12-12 12H76c-6.627 0-12-5.373-12-12V108c0-6.627 5.373-12 12-12h228.52c3.183 0 6.235 1.264 8.485 3.515l3.48 3.48A11.996 11.996 0 0 1 320 111.48z\"],\n    \"school\": [640, 512, [], \"f549\", \"M0 224v272c0 8.84 7.16 16 16 16h80V192H32c-17.67 0-32 14.33-32 32zm360-48h-24v-40c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v64c0 4.42 3.58 8 8 8h48c4.42 0 8-3.58 8-8v-16c0-4.42-3.58-8-8-8zm137.75-63.96l-160-106.67a32.02 32.02 0 0 0-35.5 0l-160 106.67A32.002 32.002 0 0 0 128 138.66V512h128V368c0-8.84 7.16-16 16-16h96c8.84 0 16 7.16 16 16v144h128V138.67c0-10.7-5.35-20.7-14.25-26.63zM320 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm288-64h-64v320h80c8.84 0 16-7.16 16-16V224c0-17.67-14.33-32-32-32z\"],\n    \"screwdriver\": [512, 512, [], \"f54a\", \"M448 0L320 96v62.06l-83.03 83.03c6.79 4.25 13.27 9.06 19.07 14.87 5.8 5.8 10.62 12.28 14.87 19.07L353.94 192H416l96-128-64-64zM128 278.59L10.92 395.67c-14.55 14.55-14.55 38.15 0 52.71l52.7 52.7c14.56 14.56 38.15 14.56 52.71 0L233.41 384c29.11-29.11 29.11-76.3 0-105.41s-76.3-29.11-105.41 0z\"],\n    \"scroll\": [640, 512, [], \"f70e\", \"M48 0C21.53 0 0 21.53 0 48v64c0 8.84 7.16 16 16 16h80V48C96 21.53 74.47 0 48 0zm208 412.57V352h288V96c0-52.94-43.06-96-96-96H111.59C121.74 13.41 128 29.92 128 48v368c0 38.87 34.65 69.65 74.75 63.12C234.22 474 256 444.46 256 412.57zM288 384v32c0 52.93-43.06 96-96 96h336c61.86 0 112-50.14 112-112 0-8.84-7.16-16-16-16H288z\"],\n    \"sd-card\": [384, 512, [], \"f7c2\", \"M320 0H128L0 128v320c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V64c0-35.3-28.7-64-64-64zM160 160h-48V64h48v96zm80 0h-48V64h48v96zm80 0h-48V64h48v96z\"],\n    \"search\": [512, 512, [], \"f002\", \"M505 442.7L405.3 343c-4.5-4.5-10.6-7-17-7H372c27.6-35.3 44-79.7 44-128C416 93.1 322.9 0 208 0S0 93.1 0 208s93.1 208 208 208c48.3 0 92.7-16.4 128-44v16.3c0 6.4 2.5 12.5 7 17l99.7 99.7c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.6.1-34zM208 336c-70.7 0-128-57.2-128-128 0-70.7 57.2-128 128-128 70.7 0 128 57.2 128 128 0 70.7-57.2 128-128 128z\"],\n    \"search-dollar\": [512, 512, [], \"f688\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm27.11-152.54l-45.01-13.5c-5.16-1.55-8.77-6.78-8.77-12.73 0-7.27 5.3-13.19 11.8-13.19h28.11c4.56 0 8.96 1.29 12.82 3.72 3.24 2.03 7.36 1.91 10.13-.73l11.75-11.21c3.53-3.37 3.33-9.21-.57-12.14-9.1-6.83-20.08-10.77-31.37-11.35V112c0-4.42-3.58-8-8-8h-16c-4.42 0-8 3.58-8 8v16.12c-23.63.63-42.68 20.55-42.68 45.07 0 19.97 12.99 37.81 31.58 43.39l45.01 13.5c5.16 1.55 8.77 6.78 8.77 12.73 0 7.27-5.3 13.19-11.8 13.19h-28.1c-4.56 0-8.96-1.29-12.82-3.72-3.24-2.03-7.36-1.91-10.13.73l-11.75 11.21c-3.53 3.37-3.33 9.21.57 12.14 9.1 6.83 20.08 10.77 31.37 11.35V304c0 4.42 3.58 8 8 8h16c4.42 0 8-3.58 8-8v-16.12c23.63-.63 42.68-20.54 42.68-45.07 0-19.97-12.99-37.81-31.59-43.39z\"],\n    \"search-location\": [512, 512, [], \"f689\", \"M505.04 442.66l-99.71-99.69c-4.5-4.5-10.6-7-17-7h-16.3c27.6-35.3 44-79.69 44-127.99C416.03 93.09 322.92 0 208.02 0S0 93.09 0 207.98s93.11 207.98 208.02 207.98c48.3 0 92.71-16.4 128.01-44v16.3c0 6.4 2.5 12.5 7 17l99.71 99.69c9.4 9.4 24.6 9.4 33.9 0l28.3-28.3c9.4-9.4 9.4-24.59.1-33.99zm-297.02-90.7c-79.54 0-144-64.34-144-143.98 0-79.53 64.35-143.98 144-143.98 79.54 0 144 64.34 144 143.98 0 79.53-64.35 143.98-144 143.98zm.02-239.96c-40.78 0-73.84 33.05-73.84 73.83 0 32.96 48.26 93.05 66.75 114.86a9.24 9.24 0 0 0 14.18 0c18.49-21.81 66.75-81.89 66.75-114.86 0-40.78-33.06-73.83-73.84-73.83zm0 96c-13.26 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"search-minus\": [512, 512, [], \"f010\", \"M304 192v32c0 6.6-5.4 12-12 12H124c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h168c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"search-plus\": [512, 512, [], \"f00e\", \"M304 192v32c0 6.6-5.4 12-12 12h-56v56c0 6.6-5.4 12-12 12h-32c-6.6 0-12-5.4-12-12v-56h-56c-6.6 0-12-5.4-12-12v-32c0-6.6 5.4-12 12-12h56v-56c0-6.6 5.4-12 12-12h32c6.6 0 12 5.4 12 12v56h56c6.6 0 12 5.4 12 12zm201 284.7L476.7 505c-9.4 9.4-24.6 9.4-33.9 0L343 405.3c-4.5-4.5-7-10.6-7-17V372c-35.3 27.6-79.7 44-128 44C93.1 416 0 322.9 0 208S93.1 0 208 0s208 93.1 208 208c0 48.3-16.4 92.7-44 128h16.3c6.4 0 12.5 2.5 17 7l99.7 99.7c9.3 9.4 9.3 24.6 0 34zM344 208c0-75.2-60.8-136-136-136S72 132.8 72 208s60.8 136 136 136 136-60.8 136-136z\"],\n    \"seedling\": [512, 512, [], \"f4d8\", \"M64 96H0c0 123.7 100.3 224 224 224v144c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V320C288 196.3 187.7 96 64 96zm384-64c-84.2 0-157.4 46.5-195.7 115.2 27.7 30.2 48.2 66.9 59 107.6C424 243.1 512 147.9 512 32h-64z\"],\n    \"server\": [512, 512, [], \"f233\", \"M480 160H32c-17.673 0-32-14.327-32-32V64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm112 248H32c-17.673 0-32-14.327-32-32v-64c0-17.673 14.327-32 32-32h448c17.673 0 32 14.327 32 32v64c0 17.673-14.327 32-32 32zm-48-88c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24zm-64 0c-13.255 0-24 10.745-24 24s10.745 24 24 24 24-10.745 24-24-10.745-24-24-24z\"],\n    \"shapes\": [512, 512, [], \"f61f\", \"M512 320v160c0 17.67-14.33 32-32 32H320c-17.67 0-32-14.33-32-32V320c0-17.67 14.33-32 32-32h160c17.67 0 32 14.33 32 32zm-384-64C57.31 256 0 313.31 0 384s57.31 128 128 128 128-57.31 128-128-57.31-128-128-128zm351.03-32c25.34 0 41.18-26.67 28.51-48L412.51 16c-12.67-21.33-44.35-21.33-57.02 0l-95.03 160c-12.67 21.33 3.17 48 28.51 48h190.06z\"],\n    \"share\": [512, 512, [], \"f064\", \"M503.691 189.836L327.687 37.851C312.281 24.546 288 35.347 288 56.015v80.053C127.371 137.907 0 170.1 0 322.326c0 61.441 39.581 122.309 83.333 154.132 13.653 9.931 33.111-2.533 28.077-18.631C66.066 312.814 132.917 274.316 288 272.085V360c0 20.7 24.3 31.453 39.687 18.164l176.004-152c11.071-9.562 11.086-26.753 0-36.328z\"],\n    \"share-alt\": [448, 512, [], \"f1e0\", \"M352 320c-22.608 0-43.387 7.819-59.79 20.895l-102.486-64.054a96.551 96.551 0 0 0 0-41.683l102.486-64.054C308.613 184.181 329.392 192 352 192c53.019 0 96-42.981 96-96S405.019 0 352 0s-96 42.981-96 96c0 7.158.79 14.13 2.276 20.841L155.79 180.895C139.387 167.819 118.608 160 96 160c-53.019 0-96 42.981-96 96s42.981 96 96 96c22.608 0 43.387-7.819 59.79-20.895l102.486 64.054A96.301 96.301 0 0 0 256 416c0 53.019 42.981 96 96 96s96-42.981 96-96-42.981-96-96-96z\"],\n    \"share-alt-square\": [448, 512, [], \"f1e1\", \"M448 80v352c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48V80c0-26.51 21.49-48 48-48h352c26.51 0 48 21.49 48 48zM304 296c-14.562 0-27.823 5.561-37.783 14.671l-67.958-40.775a56.339 56.339 0 0 0 0-27.793l67.958-40.775C276.177 210.439 289.438 216 304 216c30.928 0 56-25.072 56-56s-25.072-56-56-56-56 25.072-56 56c0 4.797.605 9.453 1.74 13.897l-67.958 40.775C171.823 205.561 158.562 200 144 200c-30.928 0-56 25.072-56 56s25.072 56 56 56c14.562 0 27.823-5.561 37.783-14.671l67.958 40.775a56.088 56.088 0 0 0-1.74 13.897c0 30.928 25.072 56 56 56s56-25.072 56-56C360 321.072 334.928 296 304 296z\"],\n    \"share-square\": [576, 512, [], \"f14d\", \"M568.482 177.448L424.479 313.433C409.3 327.768 384 317.14 384 295.985v-71.963c-144.575.97-205.566 35.113-164.775 171.353 4.483 14.973-12.846 26.567-25.006 17.33C155.252 383.105 120 326.488 120 269.339c0-143.937 117.599-172.5 264-173.312V24.012c0-21.174 25.317-31.768 40.479-17.448l144.003 135.988c10.02 9.463 10.028 25.425 0 34.896zM384 379.128V448H64V128h50.916a11.99 11.99 0 0 0 8.648-3.693c14.953-15.568 32.237-27.89 51.014-37.676C185.708 80.83 181.584 64 169.033 64H48C21.49 64 0 85.49 0 112v352c0 26.51 21.49 48 48 48h352c26.51 0 48-21.49 48-48v-88.806c0-8.288-8.197-14.066-16.011-11.302a71.83 71.83 0 0 1-34.189 3.377c-7.27-1.046-13.8 4.514-13.8 11.859z\"],\n    \"shekel-sign\": [448, 512, [], \"f20b\", \"M248 168v168c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V168c0-75.11-60.89-136-136-136H24C10.75 32 0 42.74 0 56v408c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112h112c30.93 0 56 25.07 56 56zM432 32h-48c-8.84 0-16 7.16-16 16v296c0 30.93-25.07 56-56 56H200V176c0-8.84-7.16-16-16-16h-48c-8.84 0-16 7.16-16 16v280c0 13.25 10.75 24 24 24h168c75.11 0 136-60.89 136-136V48c0-8.84-7.16-16-16-16z\"],\n    \"shield-alt\": [512, 512, [], \"f3ed\", \"M466.5 83.7l-192-80a48.15 48.15 0 0 0-36.9 0l-192 80C27.7 91.1 16 108.6 16 128c0 198.5 114.5 335.7 221.5 380.3 11.8 4.9 25.1 4.9 36.9 0C360.1 472.6 496 349.3 496 128c0-19.4-11.7-36.9-29.5-44.3zM256.1 446.3l-.1-381 175.9 73.3c-3.3 151.4-82.1 261.1-175.8 307.7z\"],\n    \"ship\": [640, 512, [], \"f21a\", \"M496.616 372.639l70.012-70.012c16.899-16.9 9.942-45.771-12.836-53.092L512 236.102V96c0-17.673-14.327-32-32-32h-64V24c0-13.255-10.745-24-24-24H248c-13.255 0-24 10.745-24 24v40h-64c-17.673 0-32 14.327-32 32v140.102l-41.792 13.433c-22.753 7.313-29.754 36.173-12.836 53.092l70.012 70.012C125.828 416.287 85.587 448 24 448c-13.255 0-24 10.745-24 24v16c0 13.255 10.745 24 24 24 61.023 0 107.499-20.61 143.258-59.396C181.677 487.432 216.021 512 256 512h128c39.979 0 74.323-24.568 88.742-59.396C508.495 491.384 554.968 512 616 512c13.255 0 24-10.745 24-24v-16c0-13.255-10.745-24-24-24-60.817 0-101.542-31.001-119.384-75.361zM192 128h256v87.531l-118.208-37.995a31.995 31.995 0 0 0-19.584 0L192 215.531V128z\"],\n    \"shipping-fast\": [640, 512, [], \"f48b\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H112C85.5 0 64 21.5 64 48v48H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h272c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H40c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H8c-4.4 0-8 3.6-8 8v16c0 4.4 3.6 8 8 8h208c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H64v128c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"shoe-prints\": [640, 512, [], \"f54b\", \"M192 160h32V32h-32c-35.35 0-64 28.65-64 64s28.65 64 64 64zM0 416c0 35.35 28.65 64 64 64h32V352H64c-35.35 0-64 28.65-64 64zm337.46-128c-34.91 0-76.16 13.12-104.73 32-24.79 16.38-44.52 32-104.73 32v128l57.53 15.97c26.21 7.28 53.01 13.12 80.31 15.05 32.69 2.31 65.6.67 97.58-6.2C472.9 481.3 512 429.22 512 384c0-64-84.18-96-174.54-96zM491.42 7.19C459.44.32 426.53-1.33 393.84.99c-27.3 1.93-54.1 7.77-80.31 15.04L256 32v128c60.2 0 79.94 15.62 104.73 32 28.57 18.88 69.82 32 104.73 32C555.82 224 640 192 640 128c0-45.22-39.1-97.3-148.58-120.81z\"],\n    \"shopping-bag\": [448, 512, [], \"f290\", \"M352 160v-32C352 57.42 294.579 0 224 0 153.42 0 96 57.42 96 128v32H0v272c0 44.183 35.817 80 80 80h288c44.183 0 80-35.817 80-80V160h-96zm-192-32c0-35.29 28.71-64 64-64s64 28.71 64 64v32H160v-32zm160 120c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zm-192 0c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24z\"],\n    \"shopping-basket\": [576, 512, [], \"f291\", \"M576 216v16c0 13.255-10.745 24-24 24h-8l-26.113 182.788C514.509 462.435 494.257 480 470.37 480H105.63c-23.887 0-44.139-17.565-47.518-41.212L32 256h-8c-13.255 0-24-10.745-24-24v-16c0-13.255 10.745-24 24-24h67.341l106.78-146.821c10.395-14.292 30.407-17.453 44.701-7.058 14.293 10.395 17.453 30.408 7.058 44.701L170.477 192h235.046L326.12 82.821c-10.395-14.292-7.234-34.306 7.059-44.701 14.291-10.395 34.306-7.235 44.701 7.058L484.659 192H552c13.255 0 24 10.745 24 24zM312 392V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm112 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24zm-224 0V280c0-13.255-10.745-24-24-24s-24 10.745-24 24v112c0 13.255 10.745 24 24 24s24-10.745 24-24z\"],\n    \"shopping-cart\": [576, 512, [], \"f07a\", \"M528.12 301.319l47.273-208C578.806 78.301 567.391 64 551.99 64H159.208l-9.166-44.81C147.758 8.021 137.93 0 126.529 0H24C10.745 0 0 10.745 0 24v16c0 13.255 10.745 24 24 24h69.883l70.248 343.435C147.325 417.1 136 435.222 136 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-15.674-6.447-29.835-16.824-40h209.647C430.447 426.165 424 440.326 424 456c0 30.928 25.072 56 56 56s56-25.072 56-56c0-22.172-12.888-41.332-31.579-50.405l5.517-24.276c3.413-15.018-8.002-29.319-23.403-29.319H218.117l-6.545-32h293.145c11.206 0 20.92-7.754 23.403-18.681z\"],\n    \"shower\": [512, 512, [], \"f2cc\", \"M389.66 135.6L231.6 293.66c-9.37 9.37-24.57 9.37-33.94 0l-11.32-11.32c-9.37-9.37-9.37-24.57 0-33.94l.11-.11c-34.03-40.21-35.16-98.94-3.39-140.38-11.97-7.55-26.14-11.91-41.3-11.91C98.88 96 64 130.88 64 173.76V480H0V173.76C0 95.59 63.59 32 141.76 32c36.93 0 70.61 14.2 95.86 37.42 35.9-11.51 76.5-4.5 106.67 21.03l.11-.11c9.37-9.37 24.57-9.37 33.94 0l11.32 11.32c9.37 9.37 9.37 24.57 0 33.94zM384 208c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm48-16c8.837 0 16 7.163 16 16s-7.163 16-16 16-16-7.163-16-16 7.163-16 16-16zm80 16c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-160 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm32 0c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-128 32c0-8.837 7.163-16 16-16s16 7.163 16 16-7.163 16-16 16-16-7.163-16-16zm96 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-96 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm64 0c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16zm-32 32c0 8.837-7.163 16-16 16s-16-7.163-16-16 7.163-16 16-16 16 7.163 16 16z\"],\n    \"shuttle-van\": [640, 512, [], \"f5b6\", \"M628.88 210.65L494.39 49.27A48.01 48.01 0 0 0 457.52 32H32C14.33 32 0 46.33 0 64v288c0 17.67 14.33 32 32 32h32c0 53.02 42.98 96 96 96s96-42.98 96-96h128c0 53.02 42.98 96 96 96s96-42.98 96-96h32c17.67 0 32-14.33 32-32V241.38c0-11.23-3.94-22.1-11.12-30.73zM64 192V96h96v96H64zm96 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm160-240h-96V96h96v96zm160 240c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-96-240V96h66.02l80 96H384z\"],\n    \"sign\": [512, 512, [], \"f4d9\", \"M496 64H128V16c0-8.8-7.2-16-16-16H80c-8.8 0-16 7.2-16 16v48H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h48v368c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V128h368c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16zM160 384h320V160H160v224z\"],\n    \"sign-in-alt\": [512, 512, [], \"f2f6\", \"M416 448h-84c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h84c17.7 0 32-14.3 32-32V160c0-17.7-14.3-32-32-32h-84c-6.6 0-12-5.4-12-12V76c0-6.6 5.4-12 12-12h84c53 0 96 43 96 96v192c0 53-43 96-96 96zm-47-201L201 79c-15-15-41-4.5-41 17v96H24c-13.3 0-24 10.7-24 24v96c0 13.3 10.7 24 24 24h136v96c0 21.5 26 32 41 17l168-168c9.3-9.4 9.3-24.6 0-34z\"],\n    \"sign-language\": [448, 512, [], \"f2a7\", \"M91.434 483.987c-.307-16.018 13.109-29.129 29.13-29.129h62.293v-5.714H56.993c-16.021 0-29.437-13.111-29.13-29.129C28.16 404.491 40.835 392 56.428 392h126.429v-5.714H29.136c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h154.286v-5.714H57.707c-16.021 0-29.437-13.111-29.13-29.129.297-15.522 12.973-28.013 28.566-28.013h168.566l-31.085-22.606c-12.762-9.281-15.583-27.149-6.302-39.912 9.281-12.761 27.15-15.582 39.912-6.302l123.361 89.715a34.287 34.287 0 0 1 14.12 27.728v141.136c0 15.91-10.946 29.73-26.433 33.374l-80.471 18.934a137.16 137.16 0 0 1-31.411 3.646H120c-15.593-.001-28.269-12.492-28.566-28.014zm73.249-225.701h36.423l-11.187-8.136c-18.579-13.511-20.313-40.887-3.17-56.536l-13.004-16.7c-9.843-12.641-28.43-15.171-40.88-5.088-12.065 9.771-14.133 27.447-4.553 39.75l36.371 46.71zm283.298-2.103l-5.003-152.452c-.518-15.771-13.722-28.136-29.493-27.619-15.773.518-28.137 13.722-27.619 29.493l1.262 38.415L283.565 11.019c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l76.889 98.745-4.509 3.511-94.79-121.734c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l94.443 121.288-4.509 3.511-77.675-99.754c-9.58-12.303-27.223-14.63-39.653-5.328-12.827 9.599-14.929 28.24-5.086 40.881l52.053 66.849c12.497-8.257 29.055-8.285 41.69.904l123.36 89.714c10.904 7.93 17.415 20.715 17.415 34.198v16.999l61.064-47.549a34.285 34.285 0 0 0 13.202-28.177z\"],\n    \"sign-out-alt\": [512, 512, [], \"f2f5\", \"M497 273L329 441c-15 15-41 4.5-41-17v-96H152c-13.3 0-24-10.7-24-24v-96c0-13.3 10.7-24 24-24h136V88c0-21.4 25.9-32 41-17l168 168c9.3 9.4 9.3 24.6 0 34zM192 436v-40c0-6.6-5.4-12-12-12H96c-17.7 0-32-14.3-32-32V160c0-17.7 14.3-32 32-32h84c6.6 0 12-5.4 12-12V76c0-6.6-5.4-12-12-12H96c-53 0-96 43-96 96v192c0 53 43 96 96 96h84c6.6 0 12-5.4 12-12z\"],\n    \"signal\": [640, 512, [], \"f012\", \"M216 288h-48c-8.84 0-16 7.16-16 16v192c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V304c0-8.84-7.16-16-16-16zM88 384H40c-8.84 0-16 7.16-16 16v96c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16v-96c0-8.84-7.16-16-16-16zm256-192h-48c-8.84 0-16 7.16-16 16v288c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V208c0-8.84-7.16-16-16-16zm128-96h-48c-8.84 0-16 7.16-16 16v384c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V112c0-8.84-7.16-16-16-16zM600 0h-48c-8.84 0-16 7.16-16 16v480c0 8.84 7.16 16 16 16h48c8.84 0 16-7.16 16-16V16c0-8.84-7.16-16-16-16z\"],\n    \"signature\": [640, 512, [], \"f5b7\", \"M623.2 192c-51.8 3.5-125.7 54.7-163.1 71.5-29.1 13.1-54.2 24.4-76.1 24.4-22.6 0-26-16.2-21.3-51.9 1.1-8 11.7-79.2-42.7-76.1-25.1 1.5-64.3 24.8-169.5 126L192 182.2c30.4-75.9-53.2-151.5-129.7-102.8L7.4 116.3C0 121-2.2 130.9 2.5 138.4l17.2 27c4.7 7.5 14.6 9.7 22.1 4.9l58-38.9c18.4-11.7 40.7 7.2 32.7 27.1L34.3 404.1C27.5 421 37 448 64 448c8.3 0 16.5-3.2 22.6-9.4 42.2-42.2 154.7-150.7 211.2-195.8-2.2 28.5-2.1 58.9 20.6 83.8 15.3 16.8 37.3 25.3 65.5 25.3 35.6 0 68-14.6 102.3-30 33-14.8 99-62.6 138.4-65.8 8.5-.7 15.2-7.3 15.2-15.8v-32.1c.2-9.1-7.5-16.8-16.6-16.2z\"],\n    \"sim-card\": [384, 512, [], \"f7c4\", \"M0 64v384c0 35.3 28.7 64 64 64h256c35.3 0 64-28.7 64-64V128L256 0H64C28.7 0 0 28.7 0 64zm224 192h-64v-64h64v64zm96 0h-64v-64h32c17.7 0 32 14.3 32 32v32zm-64 128h64v32c0 17.7-14.3 32-32 32h-32v-64zm-96 0h64v64h-64v-64zm-96 0h64v64H96c-17.7 0-32-14.3-32-32v-32zm0-96h256v64H64v-64zm0-64c0-17.7 14.3-32 32-32h32v64H64v-32z\"],\n    \"sitemap\": [640, 512, [], \"f0e8\", \"M128 352H32c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm-24-80h192v48h48v-48h192v48h48v-57.59c0-21.17-17.23-38.41-38.41-38.41H344v-64h40c17.67 0 32-14.33 32-32V32c0-17.67-14.33-32-32-32H256c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h40v64H94.41C73.23 224 56 241.23 56 262.41V320h48v-48zm264 80h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32zm240 0h-96c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32z\"],\n    \"skating\": [448, 512, [], \"f7c5\", \"M400 0c-26.5 0-48 21.5-48 48s21.5 48 48 48 48-21.5 48-48-21.5-48-48-48zm0 448c-8.8 0-16 7.2-16 16s-7.2 16-16 16h-96c-8.8 0-16 7.2-16 16s7.2 16 16 16h96c26.5 0 48-21.5 48-48 0-8.8-7.2-16-16-16zm-282.2 8.6c-6.2 6.2-16.4 6.3-22.6 0l-67.9-67.9c-6.2-6.2-16.4-6.2-22.6 0s-6.2 16.4 0 22.6l67.9 67.9c9.4 9.4 21.7 14 34 14s24.6-4.7 33.9-14c6.2-6.2 6.2-16.4 0-22.6s-16.4-6.3-22.7 0zm56.1-179.8l-93.7 93.7c-12.5 12.5-12.5 32.8 0 45.2 6.2 6.2 14.4 9.4 22.6 9.4s16.4-3.1 22.6-9.4l91.9-91.9-30.2-30.2c-5-5-9.4-10.7-13.2-16.8zM128 160h105.5l-20.1 17.2c-13.5 11.5-21.6 28.4-22.3 46.1-.7 17.8 6.1 35.2 18.7 47.7l78.2 78.2V432c0 17.7 14.3 32 32 32s32-14.3 32-32v-89.4c0-12.6-5.1-25-14.1-33.9l-61-61c.5-.4 1.2-.6 1.7-1.1l82.3-82.3c11.5-11.5 14.9-28.6 8.7-43.6-6.2-15-20.7-24.7-37-24.7H128c-17.7 0-32 14.3-32 32s14.3 32 32 32z\"],\n    \"skiing\": [512, 512, [], \"f7c9\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm73 356.1c-9.4-9.4-24.6-9.4-33.9 0-12.1 12.1-30.5 15.4-45.1 8.7l-135.8-70.2 49.2-73.8c12.7-19 10.2-44.5-6-60.6L293 215.7l-107-53.1c-2.9 19.9 3.4 40 17.7 54.4l75.1 75.2-45.9 68.8L35 258.7c-11.7-6-26.2-1.5-32.3 10.3-6.1 11.8-1.5 26.3 10.3 32.3l391.9 202.5c11.9 5.5 24.5 8.1 37.1 8.1 23.2 0 46-9 63-26 9.3-9.3 9.3-24.5 0-33.8zM120 91.6l-11.5 22.5c14.4 7.3 31.2 4.9 42.8-4.8l47.2 23.4c-.1.1-.1.2-.2.3l114.5 56.8 32.4-13 6.4 19.1c4 12.1 12.6 22 24 27.7l58.1 29c15.9 7.9 35 1.5 42.9-14.3 7.9-15.8 1.5-35-14.3-42.9l-52.1-26.1-17.1-51.2c-8.1-24.2-40.9-56.6-84.5-39.2l-81.2 32.5-62.5-31c.3-14.5-7.2-28.6-20.9-35.6l-11.1 21.7h-.2l-34.4-7c-1.8-.4-3.7.2-5 1.7-1.9 2.2-1.7 5.5.5 7.4l26.2 23z\"],\n    \"skiing-nordic\": [576, 512, [], \"f7ca\", \"M336 96c26.5 0 48-21.5 48-48S362.5 0 336 0s-48 21.5-48 48 21.5 48 48 48zm216 320c-13.2 0-24 10.7-24 24 0 13.2-10.8 24-24 24h-69.5L460 285.6c11.7-4.7 20.1-16.2 20.1-29.6 0-17.7-14.3-32-32-32h-44L378 170.8c-12.5-25.5-35.5-44.2-61.8-50.9L245 98.7c-28.3-6.8-57.8-.5-80.8 17.1l-39.7 30.4c-14 10.7-16.7 30.8-5.9 44.9.7.9 1.7 1.3 2.4 2.1L66.9 464H24c-13.2 0-24 10.7-24 24s10.8 24 24 24h480c39.7 0 72-32.3 72-72 0-13.2-10.8-24-24-24zm-260.5 48h-96.9l43.1-91-22-13c-12.1-7.2-21.9-16.9-29.5-27.8L123.7 464H99.5l52.3-261.4c4.1-1 8.1-2.9 11.7-5.6l39.7-30.4c7.7-5.9 17.4-8 25.3-6.1l14.7 4.4-37.5 87.4c-12.6 29.5-1.3 64 26.3 80.3l85 50.2-25.5 81.2zm110.6 0h-43.6l23.6-75.5c5.9-20.8-2.9-43.1-21.6-54.4L299.3 298l31.3-78.3 20.3 41.4c8 16.3 24.9 26.9 43.1 26.9h33.3l-25.2 176z\"],\n    \"skull\": [512, 512, [], \"f54c\", \"M256 0C114.6 0 0 100.3 0 224c0 70.1 36.9 132.6 94.5 173.7 9.6 6.9 15.2 18.1 13.5 29.9l-9.4 66.2c-1.4 9.6 6 18.2 15.7 18.2H192v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h64v-56c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v56h77.7c9.7 0 17.1-8.6 15.7-18.2l-9.4-66.2c-1.7-11.7 3.8-23 13.5-29.9C475.1 356.6 512 294.1 512 224 512 100.3 397.4 0 256 0zm-96 320c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm192 0c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64z\"],\n    \"skull-crossbones\": [448, 512, [], \"f714\", \"M439.15 453.06L297.17 384l141.99-69.06c7.9-3.95 11.11-13.56 7.15-21.46L432 264.85c-3.95-7.9-13.56-11.11-21.47-7.16L224 348.41 37.47 257.69c-7.9-3.95-17.51-.75-21.47 7.16L1.69 293.48c-3.95 7.9-.75 17.51 7.15 21.46L150.83 384 8.85 453.06c-7.9 3.95-11.11 13.56-7.15 21.47l14.31 28.63c3.95 7.9 13.56 11.11 21.47 7.15L224 419.59l186.53 90.72c7.9 3.95 17.51.75 21.47-7.15l14.31-28.63c3.95-7.91.74-17.52-7.16-21.47zM150 237.28l-5.48 25.87c-2.67 12.62 5.42 24.85 16.45 24.85h126.08c11.03 0 19.12-12.23 16.45-24.85l-5.5-25.87c41.78-22.41 70-62.75 70-109.28C368 57.31 303.53 0 224 0S80 57.31 80 128c0 46.53 28.22 86.87 70 109.28zM280 112c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32zm-112 0c17.65 0 32 14.35 32 32s-14.35 32-32 32-32-14.35-32-32 14.35-32 32-32z\"],\n    \"slash\": [640, 512, [], \"f715\", \"M594.53 508.63L6.18 53.9c-6.97-5.42-8.23-15.47-2.81-22.45L23.01 6.18C28.43-.8 38.49-2.06 45.47 3.37L633.82 458.1c6.97 5.42 8.23 15.47 2.81 22.45l-19.64 25.27c-5.42 6.98-15.48 8.23-22.46 2.81z\"],\n    \"sleigh\": [640, 512, [], \"f7cc\", \"M612.7 350.7l-9.3-7.4c-6.9-5.5-17-4.4-22.5 2.5l-10 12.5c-5.5 6.9-4.4 17 2.5 22.5l9.3 7.4c5.9 4.7 9.2 11.7 9.2 19.2 0 13.6-11 24.6-24.6 24.6H48c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h516c39 0 73.7-29.3 75.9-68.3 1.4-23.8-8.7-46.3-27.2-61zM32 224c0 59.6 40.9 109.2 96 123.5V400h64v-48h192v48h64v-48c53 0 96-43 96-96v-96c17.7 0 32-14.3 32-32s-14.3-32-32-32h-96v64c0 35.3-28.7 64-64 64h-20.7c-65.8 0-125.9-37.2-155.3-96-29.4-58.8-89.6-96-155.3-96H32C14.3 32 0 46.3 0 64s14.3 32 32 32v128z\"],\n    \"sliders-h\": [512, 512, [], \"f1de\", \"M496 384H160v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h80v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h336c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160h-80v-16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h336v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h80c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm0-160H288V48c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v16H16C7.2 64 0 71.2 0 80v32c0 8.8 7.2 16 16 16h208v16c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-16h208c8.8 0 16-7.2 16-16V80c0-8.8-7.2-16-16-16z\"],\n    \"smile\": [496, 512, [], \"f118\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm80 168c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm-160 0c17.7 0 32 14.3 32 32s-14.3 32-32 32-32-14.3-32-32 14.3-32 32-32zm194.8 170.2C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.6-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.4-16.2 38.1 4.2 24.6 20.5z\"],\n    \"smile-beam\": [496, 512, [], \"f5b8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM112 223.4c3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.7 8.6-10.8 11.9-14.9 4.5l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.3 7.4-15.8 4-15.1-4.5zm250.8 122.8C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11-36.7 24.6-20.5 22.4 26.9 55.2 42.2 90.2 42.2s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.3 24.6 20.5zm6.2-118.3l-9.5-17c-7.7-13.7-19.2-21.6-31.5-21.6s-23.8 7.9-31.5 21.6l-9.5 17c-4.1 7.3-15.6 4-14.9-4.5 3.3-42.1 32.2-71.4 56-71.4s52.7 29.3 56 71.4c.6 8.6-11 11.9-15.1 4.5z\"],\n    \"smile-wink\": [496, 512, [], \"f4da\", \"M0 256c0 137 111 248 248 248s248-111 248-248S385 8 248 8 0 119 0 256zm200-48c0 17.7-14.3 32-32 32s-32-14.3-32-32 14.3-32 32-32 32 14.3 32 32zm158.5 16.5c-14.8-13.2-46.2-13.2-61 0L288 233c-8.3 7.4-21.6.4-19.8-10.8 4-25.2 34.2-42.1 59.9-42.1S384 197 388 222.2c1.7 11.1-11.4 18.3-19.8 10.8l-9.7-8.5zM157.8 325.8C180.2 352.7 213 368 248 368s67.8-15.4 90.2-42.2c13.6-16.2 38.1 4.2 24.6 20.5C334.3 380.4 292.5 400 248 400s-86.3-19.6-114.8-53.8c-13.5-16.3 11.2-36.7 24.6-20.4z\"],\n    \"smog\": [640, 512, [], \"f75f\", \"M624 368H80c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h544c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm-480 96H16c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h128c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zm416 0H224c-8.8 0-16 7.2-16 16v16c0 8.8 7.2 16 16 16h336c8.8 0 16-7.2 16-16v-16c0-8.8-7.2-16-16-16zM144 288h156.1c22.5 19.7 51.6 32 83.9 32s61.3-12.3 83.9-32H528c61.9 0 112-50.1 112-112S589.9 64 528 64c-18 0-34.7 4.6-49.7 12.1C454 31 406.8 0 352 0c-41 0-77.8 17.3-104 44.8C221.8 17.3 185 0 144 0 64.5 0 0 64.5 0 144s64.5 144 144 144z\"],\n    \"smoking\": [640, 512, [], \"f48d\", \"M632 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8zM553.3 87.1c-5.7-3.8-9.3-10-9.3-16.8V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v62.3c0 22 10.2 43.4 28.6 55.4 42.2 27.3 67.4 73.8 67.4 124V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-65.5-32.4-126.2-86.7-162.6zM432 352H48c-26.5 0-48 21.5-48 48v64c0 26.5 21.5 48 48 48h384c8.8 0 16-7.2 16-16V368c0-8.8-7.2-16-16-16zm-32 112H224v-64h176v64zm87.7-322.4C463.8 125 448 99.3 448 70.3V8c0-4.4-3.6-8-8-8h-48c-4.4 0-8 3.6-8 8v66.4c0 43.7 24.6 81.6 60.3 106.7 22.4 15.7 35.7 41.2 35.7 68.6V280c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8v-30.3c0-43.3-21-83.4-56.3-108.1zM536 352h-48c-4.4 0-8 3.6-8 8v144c0 4.4 3.6 8 8 8h48c4.4 0 8-3.6 8-8V360c0-4.4-3.6-8-8-8z\"],\n    \"smoking-ban\": [512, 512, [], \"f54d\", \"M96 304c0 8.8 7.2 16 16 16h117.5l-96-96H112c-8.8 0-16 7.2-16 16v64zM256 0C114.6 0 0 114.6 0 256s114.6 256 256 256 256-114.6 256-256S397.4 0 256 0zm0 448c-105.9 0-192-86.1-192-192 0-41.4 13.3-79.7 35.7-111.1l267.4 267.4C335.7 434.7 297.4 448 256 448zm45.2-192H384v32h-50.8l-32-32zm111.1 111.1L365.2 320H400c8.8 0 16-7.2 16-16v-64c0-8.8-7.2-16-16-16H269.2L144.9 99.7C176.3 77.3 214.6 64 256 64c105.9 0 192 86.1 192 192 0 41.4-13.3 79.7-35.7 111.1zM320.6 128c-15.6 0-28.6-11.2-31.4-25.9-.7-3.6-4-6.1-7.7-6.1h-16.2c-5 0-8.7 4.5-8 9.4 4.6 30.9 31.2 54.6 63.3 54.6 15.6 0 28.6 11.2 31.4 25.9.7 3.6 4 6.1 7.7 6.1h16.2c5 0 8.7-4.5 8-9.4-4.6-30.9-31.2-54.6-63.3-54.6z\"],\n    \"sms\": [512, 512, [], \"f7cd\", \"M256 32C114.6 32 0 125.1 0 240c0 49.6 21.4 95 57 130.7C44.5 421.1 2.7 466 2.2 466.5c-2.2 2.3-2.8 5.7-1.5 8.7 1.3 3 4.1 4.8 7.3 4.8 66.3 0 116-31.8 140.6-51.4 32.7 12.3 69 19.4 107.4 19.4 141.4 0 256-93.1 256-208S397.4 32 256 32zM128.2 304H116c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H156c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-19 38.6-42.4 38.6zm191.8-8c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8v-68.2l-24.8 55.8c-2.9 5.9-11.4 5.9-14.3 0L224 227.8V296c0 4.4-3.6 8-8 8h-16c-4.4 0-8-3.6-8-8V192c0-8.8 7.2-16 16-16h16c6.1 0 11.6 3.4 14.3 8.8l17.7 35.4 17.7-35.4c2.7-5.4 8.3-8.8 14.3-8.8h16c8.8 0 16 7.2 16 16v104zm48.3 8H356c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h12.3c6 0 10.4-3.5 10.4-6.6 0-1.3-.8-2.7-2.1-3.8l-21.9-18.8c-8.5-7.2-13.3-17.5-13.3-28.1 0-21.3 19-38.6 42.4-38.6H396c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8h-12.3c-6 0-10.4 3.5-10.4 6.6 0 1.3.8 2.7 2.1 3.8l21.9 18.8c8.5 7.2 13.3 17.5 13.3 28.1.1 21.3-18.9 38.6-42.3 38.6z\"],\n    \"snowboarding\": [512, 512, [], \"f7ce\", \"M432 96c26.5 0 48-21.5 48-48S458.5 0 432 0s-48 21.5-48 48 21.5 48 48 48zm28.8 153.6c5.8 4.3 12.5 6.4 19.2 6.4 9.7 0 19.3-4.4 25.6-12.8 10.6-14.1 7.8-34.2-6.4-44.8l-111.4-83.5c-13.8-10.3-29.1-18.4-45.4-23.8l-63.7-21.2-26.1-52.1C244.7 2 225.5-4.4 209.7 3.5c-15.8 7.9-22.2 27.1-14.3 42.9l29.1 58.1c5.7 11.4 15.6 19.9 27.7 24l16.4 5.5-41.2 20.6c-21.8 10.9-35.4 32.8-35.4 57.2v53.1l-74.1 24.7c-16.8 5.6-25.8 23.7-20.2 40.5 1.7 5.2 4.9 9.4 8.7 12.9l-38.7-14.1c-9.7-3.5-17.4-10.6-21.8-20-5.6-12-19.9-17.2-31.9-11.6s-17.2 19.9-11.6 31.9c9.8 21 27.1 36.9 48.9 44.8l364.8 132.7c9.7 3.5 19.7 5.3 29.7 5.3 12.5 0 24.9-2.7 36.5-8.2 12-5.6 17.2-19.9 11.6-31.9S474 454.7 462 460.3c-9.3 4.4-19.8 4.8-29.5 1.3l-90.8-33.1c8.7-4.1 15.6-11.8 17.8-21.9l21.9-102c3.9-18.2-3.2-37.2-18.1-48.4l-52-39 66-30.5 83.5 62.9zm-144.4 51.7l-19.7 92c-1.5 7.1-.1 13.9 2.8 20l-169.4-61.6c2.7-.2 5.4-.4 8-1.3l85-28.4c19.6-6.5 32.8-24.8 32.8-45.5V256l60.5 45.3z\"],\n    \"snowflake\": [448, 512, [], \"f2dc\", \"M440.3 345.2l-33.8-19.5 26-7c8.2-2.2 13.1-10.7 10.9-18.9l-4-14.9c-2.2-8.2-10.7-13.1-18.9-10.9l-70.8 19-63.9-37 63.8-36.9 70.8 19c8.2 2.2 16.7-2.7 18.9-10.9l4-14.9c2.2-8.2-2.7-16.7-10.9-18.9l-26-7 33.8-19.5c7.4-4.3 9.9-13.7 5.7-21.1L430.4 119c-4.3-7.4-13.7-9.9-21.1-5.7l-33.8 19.5 7-26c2.2-8.2-2.7-16.7-10.9-18.9l-14.9-4c-8.2-2.2-16.7 2.7-18.9 10.9l-19 70.8-62.8 36.2v-77.5l53.7-53.7c6.2-6.2 6.2-16.4 0-22.6l-11.3-11.3c-6.2-6.2-16.4-6.2-22.6 0L256 56.4V16c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v40.4l-19.7-19.7c-6.2-6.2-16.4-6.2-22.6 0L138.3 48c-6.3 6.2-6.3 16.4 0 22.6l53.7 53.7v77.5l-62.8-36.2-19-70.8c-2.2-8.2-10.7-13.1-18.9-10.9l-14.9 4c-8.2 2.2-13.1 10.7-10.9 18.9l7 26-33.8-19.5c-7.4-4.3-16.8-1.7-21.1 5.7L2.1 145.7c-4.3 7.4-1.7 16.8 5.7 21.1l33.8 19.5-26 7c-8.3 2.2-13.2 10.7-11 19l4 14.9c2.2 8.2 10.7 13.1 18.9 10.9l70.8-19 63.8 36.9-63.8 36.9-70.8-19c-8.2-2.2-16.7 2.7-18.9 10.9l-4 14.9c-2.2 8.2 2.7 16.7 10.9 18.9l26 7-33.8 19.6c-7.4 4.3-9.9 13.7-5.7 21.1l15.5 26.8c4.3 7.4 13.7 9.9 21.1 5.7l33.8-19.5-7 26c-2.2 8.2 2.7 16.7 10.9 18.9l14.9 4c8.2 2.2 16.7-2.7 18.9-10.9l19-70.8 62.8-36.2v77.5l-53.7 53.7c-6.3 6.2-6.3 16.4 0 22.6l11.3 11.3c6.2 6.2 16.4 6.2 22.6 0l19.7-19.7V496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-40.4l19.7 19.7c6.2 6.2 16.4 6.2 22.6 0l11.3-11.3c6.2-6.2 6.2-16.4 0-22.6L256 387.7v-77.5l62.8 36.2 19 70.8c2.2 8.2 10.7 13.1 18.9 10.9l14.9-4c8.2-2.2 13.1-10.7 10.9-18.9l-7-26 33.8 19.5c7.4 4.3 16.8 1.7 21.1-5.7l15.5-26.8c4.3-7.3 1.8-16.8-5.6-21z\"],\n    \"snowman\": [512, 512, [], \"f7d0\", \"M510.9 152.3l-5.9-14.5c-3.3-8-12.6-11.9-20.8-8.7L456 140.6v-29c0-8.6-7.2-15.6-16-15.6h-16c-8.8 0-16 7-16 15.6v46.9c0 .5.3 1 .3 1.5l-56.4 23c-5.9-10-13.3-18.9-22-26.6 13.6-16.6 22-37.4 22-60.5 0-53-43-96-96-96s-96 43-96 96c0 23.1 8.5 43.9 22 60.5-8.7 7.7-16 16.6-22 26.6l-56.4-23c.1-.5.3-1 .3-1.5v-46.9C104 103 96.8 96 88 96H72c-8.8 0-16 7-16 15.6v29l-28.1-11.5c-8.2-3.2-17.5.7-20.8 8.7l-5.9 14.5c-3.3 8 .7 17.1 8.9 20.3l135.2 55.2c-.4 4-1.2 8-1.2 12.2 0 10.1 1.7 19.6 4.2 28.9C120.9 296.4 104 334.2 104 376c0 54 28.4 100.9 70.8 127.8 9.3 5.9 20.3 8.2 31.3 8.2h99.2c13.3 0 26.3-4.1 37.2-11.7 46.5-32.3 74.4-89.4 62.9-152.6-5.5-30.2-20.5-57.6-41.6-79 2.5-9.2 4.2-18.7 4.2-28.7 0-4.2-.8-8.1-1.2-12.2L502 172.6c8.1-3.1 12.1-12.2 8.9-20.3zM224 96c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm32 272c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-64c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16zm0-88s-16-23.2-16-32 7.2-16 16-16 16 7.2 16 16-16 32-16 32zm32-56c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"snowplow\": [640, 512, [], \"f7d2\", \"M120 376c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm80 0c-13.3 0-24 10.7-24 24s10.7 24 24 24 24-10.7 24-24-10.7-24-24-24zm238.6 49.4c-14.5-14.5-22.6-34.1-22.6-54.6V269.2c0-20.5 8.1-40.1 22.6-54.6l36.7-36.7c6.2-6.2 6.2-16.4 0-22.6l-22.6-22.6c-6.2-6.2-16.4-6.2-22.6 0l-36.7 36.7c-26.5 26.5-41.4 62.4-41.4 99.9V288h-64v-50.9c0-8.7-1.8-17.2-5.2-25.2L364.5 29.1C356.9 11.4 339.6 0 320.3 0H176c-26.5 0-48 21.5-48 48v112h-16c-26.5 0-48 21.5-48 48v91.2C26.3 317.2 0 355.4 0 400c0 61.9 50.1 112 112 112h256c61.9 0 112-50.1 112-112 0-17.3-4.2-33.4-11.2-48H512v18.7c0 37.5 14.9 73.4 41.4 99.9l36.7 36.7c6.2 6.2 16.4 6.2 22.6 0l22.6-22.6c6.2-6.2 6.2-16.4 0-22.6l-36.7-36.7zM192 64h117.8l68.6 160H256l-64-64V64zm176 384H112c-26.5 0-48-21.5-48-48s21.5-48 48-48h256c26.5 0 48 21.5 48 48s-21.5 48-48 48z\"],\n    \"socks\": [512, 512, [], \"f696\", \"M214.66 311.01L288 256V96H128v176l-86.65 64.61c-39.4 29.56-53.86 84.42-29.21 127.06C30.39 495.25 63.27 512 96.08 512c20.03 0 40.25-6.25 57.52-19.2l21.86-16.39c-29.85-55.38-13.54-125.84 39.2-165.4zM288 32c0-11.05 3.07-21.3 8.02-30.38C293.4.92 290.85 0 288 0H160c-17.67 0-32 14.33-32 32v32h160V32zM480 0H352c-17.67 0-32 14.33-32 32v32h192V32c0-17.67-14.33-32-32-32zM320 272l-86.13 64.61c-39.4 29.56-53.86 84.42-29.21 127.06 18.25 31.58 50.61 48.33 83.42 48.33 20.03 0 40.25-6.25 57.52-19.2l115.2-86.4A127.997 127.997 0 0 0 512 304V96H320v176z\"],\n    \"solar-panel\": [640, 512, [], \"f5ba\", \"M431.98 448.01l-47.97.05V416h-128v32.21l-47.98.05c-8.82.01-15.97 7.16-15.98 15.99l-.05 31.73c-.01 8.85 7.17 16.03 16.02 16.02l223.96-.26c8.82-.01 15.97-7.16 15.98-15.98l.04-31.73c.01-8.85-7.17-16.03-16.02-16.02zM585.2 26.74C582.58 11.31 568.99 0 553.06 0H86.93C71 0 57.41 11.31 54.79 26.74-3.32 369.16.04 348.08.03 352c-.03 17.32 14.29 32 32.6 32h574.74c18.23 0 32.51-14.56 32.59-31.79.02-4.08 3.35 16.95-54.76-325.47zM259.83 64h120.33l9.77 96H250.06l9.77-96zm-75.17 256H71.09L90.1 208h105.97l-11.41 112zm16.29-160H98.24l16.29-96h96.19l-9.77 96zm32.82 160l11.4-112h149.65l11.4 112H233.77zm195.5-256h96.19l16.29 96H439.04l-9.77-96zm26.06 256l-11.4-112H549.9l19.01 112H455.33z\"],\n    \"sort\": [320, 512, [], \"f0dc\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41zm255-105L177 64c-9.4-9.4-24.6-9.4-33.9 0L24 183c-15.1 15.1-4.4 41 17 41h238c21.4 0 32.1-25.9 17-41z\"],\n    \"sort-alpha-down\": [448, 512, [], \"f15d\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm240-64H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-down-alt\": [448, 512, [], \"f881\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm112-128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-alpha-up\": [448, 512, [], \"f15e\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm400 128H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 446.37V464a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 321.63V304a16 16 0 0 0-16-16zm31.06-85.38l-59.27-160A16 16 0 0 0 372.72 32h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 224h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 224H432a16 16 0 0 0 15.06-21.38zM335.61 144L352 96l16.39 48z\"],\n    \"sort-alpha-up-alt\": [448, 512, [], \"f882\", \"M16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160zm272 64h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-56l61.26-70.45A32 32 0 0 0 432 65.63V48a16 16 0 0 0-16-16H288a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h56l-61.26 70.45A32 32 0 0 0 272 190.37V208a16 16 0 0 0 16 16zm159.06 234.62l-59.27-160A16 16 0 0 0 372.72 288h-41.44a16 16 0 0 0-15.07 10.62l-59.27 160A16 16 0 0 0 272 480h24.83a16 16 0 0 0 15.23-11.08l4.42-12.92h71l4.41 12.92A16 16 0 0 0 407.16 480H432a16 16 0 0 0 15.06-21.38zM335.61 400L352 352l16.39 48z\"],\n    \"sort-amount-down\": [512, 512, [], \"f160\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-128-64h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm256-192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-down-alt\": [512, 512, [], \"f884\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm-64 0h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.37 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-amount-up\": [512, 512, [], \"f161\", \"M304 416h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h64a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.77 160 16 160zm416 0H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-64 128H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM496 32H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"sort-amount-up-alt\": [512, 512, [], \"f885\", \"M240 96h64a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16h-64a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm0 128h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm256 192H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h256a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-256-64h192a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16H240a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zM16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.39-17.24 11.31-27.31l-80-96a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160z\"],\n    \"sort-down\": [320, 512, [], \"f0dd\", \"M41 288h238c21.4 0 32.1 25.9 17 41L177 448c-9.4 9.4-24.6 9.4-33.9 0L24 329c-15.1-15.1-4.4-41 17-41z\"],\n    \"sort-numeric-down\": [448, 512, [], \"f162\", \"M304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zm26.15 162.91a79 79 0 0 0-55 54.17c-14.25 51.05 21.21 97.77 68.85 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zm-176-4h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352z\"],\n    \"sort-numeric-down-alt\": [448, 512, [], \"f886\", \"M176 352h-48V48a16 16 0 0 0-16-16H80a16 16 0 0 0-16 16v304H16c-14.19 0-21.36 17.24-11.29 27.31l80 96a16 16 0 0 0 22.62 0l80-96C197.35 369.26 190.22 352 176 352zm224 64h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-numeric-up\": [448, 512, [], \"f163\", \"M330.17 258.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.76 86.25-61.61 86.25-132V336c-.02-51.21-48.4-91.34-101.85-77.09zM352 356a20 20 0 1 1 20-20 20 20 0 0 1-20 20zM304 96h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-16V48a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 96zM107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31z\"],\n    \"sort-numeric-up-alt\": [448, 512, [], \"f887\", \"M107.31 36.69a16 16 0 0 0-22.62 0l-80 96C-5.35 142.74 1.78 160 16 160h48v304a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V160h48c14.21 0 21.38-17.24 11.31-27.31zM400 416h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 304 352h16v64h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM330.17 34.91a79 79 0 0 0-55 54.17c-14.27 51.05 21.19 97.77 68.83 102.53a84.07 84.07 0 0 1-20.85 12.91c-7.57 3.4-10.8 12.47-8.18 20.34l9.9 20c2.87 8.63 12.53 13.49 20.9 9.91 58-24.77 86.25-61.61 86.25-132V112c-.02-51.21-48.4-91.34-101.85-77.09zM352 132a20 20 0 1 1 20-20 20 20 0 0 1-20 20z\"],\n    \"sort-up\": [320, 512, [], \"f0de\", \"M279 224H41c-21.4 0-32.1-25.9-17-41L143 64c9.4-9.4 24.6-9.4 33.9 0l119 119c15.2 15.1 4.5 41-16.9 41z\"],\n    \"spa\": [576, 512, [], \"f5bb\", \"M568.25 192c-29.04.13-135.01 6.16-213.84 83-33.12 29.63-53.36 63.3-66.41 94.86-13.05-31.56-33.29-65.23-66.41-94.86-78.83-76.84-184.8-82.87-213.84-83-4.41-.02-7.79 3.4-7.75 7.82.23 27.92 7.14 126.14 88.77 199.3C172.79 480.94 256 480 288 480s115.19.95 199.23-80.88c81.64-73.17 88.54-171.38 88.77-199.3.04-4.42-3.34-7.84-7.75-7.82zM287.98 302.6c12.82-18.85 27.6-35.78 44.09-50.52 19.09-18.61 39.58-33.3 60.26-45.18-16.44-70.5-51.72-133.05-96.73-172.22-4.11-3.58-11.02-3.58-15.14 0-44.99 39.14-80.27 101.63-96.74 172.07 20.37 11.7 40.5 26.14 59.22 44.39a282.768 282.768 0 0 1 45.04 51.46z\"],\n    \"space-shuttle\": [640, 512, [], \"f197\", \"M592.604 208.244C559.735 192.836 515.777 184 472 184H186.327c-4.952-6.555-10.585-11.978-16.72-16H376C229.157 137.747 219.403 32 96.003 32H96v128H80V32c-26.51 0-48 28.654-48 64v64c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v16c-23.197 0-32 10.032-32 24v40c0 13.983 8.819 24 32 24v64c0 35.346 21.49 64 48 64V352h16v128h.003c123.4 0 133.154-105.747 279.997-136H169.606c6.135-4.022 11.768-9.445 16.72-16H472c43.777 0 87.735-8.836 120.604-24.244C622.282 289.845 640 271.992 640 256s-17.718-33.845-47.396-47.756zM488 296a8 8 0 0 1-8-8v-64a8 8 0 0 1 8-8c31.909 0 31.942 80 0 80z\"],\n    \"spell-check\": [576, 512, [], \"f891\", \"M272 256h91.36c43.2 0 82-32.2 84.51-75.34a79.82 79.82 0 0 0-25.26-63.07 79.81 79.81 0 0 0 9.06-44.91C427.9 30.57 389.3 0 347 0h-75a16 16 0 0 0-16 16v224a16 16 0 0 0 16 16zm40-200h40a24 24 0 0 1 0 48h-40zm0 96h56a24 24 0 0 1 0 48h-56zM155.12 22.25A32 32 0 0 0 124.64 0H99.36a32 32 0 0 0-30.48 22.25L.59 235.73A16 16 0 0 0 16 256h24.93a16 16 0 0 0 15.42-11.73L68.29 208h87.42l11.94 36.27A16 16 0 0 0 183.07 256H208a16 16 0 0 0 15.42-20.27zM89.37 144L112 75.3l22.63 68.7zm482 132.48l-45.21-45.3a15.88 15.88 0 0 0-22.59 0l-151.5 151.5-55.41-55.5a15.88 15.88 0 0 0-22.59 0l-45.3 45.3a16 16 0 0 0 0 22.59l112 112.21a15.89 15.89 0 0 0 22.6 0l208-208.21a16 16 0 0 0-.02-22.59z\"],\n    \"spider\": [576, 512, [], \"f717\", \"M151.17 167.35L177.1 176h4.67l5.22-26.12c.72-3.58 1.8-7.58 3.21-11.79l-20.29-40.58 23.8-71.39c2.79-8.38-1.73-17.44-10.12-20.24L168.42.82c-8.38-2.8-17.45 1.73-20.24 10.12l-25.89 77.68a32.04 32.04 0 0 0 1.73 24.43l27.15 54.3zm422.14 182.03l-52.75-79.12a32.002 32.002 0 0 0-26.62-14.25H416l68.99-24.36a32.03 32.03 0 0 0 16.51-12.61l53.6-80.41c4.9-7.35 2.91-17.29-4.44-22.19l-13.31-8.88c-7.35-4.9-17.29-2.91-22.19 4.44l-50.56 75.83L404.1 208H368l-10.37-51.85C355.44 145.18 340.26 96 288 96c-52.26 0-67.44 49.18-69.63 60.15L208 208h-36.1l-60.49-20.17L60.84 112c-4.9-7.35-14.83-9.34-22.19-4.44l-13.31 8.88c-7.35 4.9-9.34 14.83-4.44 22.19l53.6 80.41a32.03 32.03 0 0 0 16.51 12.61L160 256H82.06a32.02 32.02 0 0 0-26.63 14.25L2.69 349.38c-4.9 7.35-2.92 17.29 4.44 22.19l13.31 8.88c7.35 4.9 17.29 2.91 22.19-4.44l48-72h47.06l-60.83 97.33A31.988 31.988 0 0 0 72 418.3V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-73.11l74.08-118.53c-1.01 14.05-2.08 28.11-2.08 42.21C192 399.64 232.76 448 288 448s96-48.36 96-101.43c0-14.1-1.08-28.16-2.08-42.21L456 422.89V496c0 8.84 7.16 16 16 16h16c8.84 0 16-7.16 16-16v-77.71c0-6-1.69-11.88-4.86-16.96L438.31 304h47.06l48 72c4.9 7.35 14.84 9.34 22.19 4.44l13.31-8.88c7.36-4.9 9.34-14.83 4.44-22.18zM406.09 97.51l-20.29 40.58c1.41 4.21 2.49 8.21 3.21 11.79l5.22 26.12h4.67l25.93-8.65 27.15-54.3a31.995 31.995 0 0 0 1.73-24.43l-25.89-77.68C425.03 2.56 415.96-1.98 407.58.82l-15.17 5.06c-8.38 2.8-12.91 11.86-10.12 20.24l23.8 71.39z\"],\n    \"spinner\": [512, 512, [], \"f110\", \"M304 48c0 26.51-21.49 48-48 48s-48-21.49-48-48 21.49-48 48-48 48 21.49 48 48zm-48 368c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm208-208c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zM96 256c0-26.51-21.49-48-48-48S0 229.49 0 256s21.49 48 48 48 48-21.49 48-48zm12.922 99.078c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.491-48-48-48zm294.156 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48c0-26.509-21.49-48-48-48zM108.922 60.922c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.491-48-48-48z\"],\n    \"splotch\": [512, 512, [], \"f5bc\", \"M472.29 195.89l-67.06-22.95c-19.28-6.6-33.54-20.92-38.14-38.3L351.1 74.19c-11.58-43.77-76.57-57.13-109.98-22.62l-46.14 47.67c-13.26 13.71-33.54 20.93-54.2 19.31l-71.88-5.62c-52.05-4.07-86.93 44.88-59.03 82.83l38.54 52.42c11.08 15.07 12.82 33.86 4.64 50.24L24.62 355.4c-20.59 41.25 22.84 84.87 73.49 73.81l69.96-15.28c20.11-4.39 41.45 0 57.07 11.73l54.32 40.83c39.32 29.56 101.04 7.57 104.45-37.22l4.7-61.86c1.35-17.79 12.8-33.86 30.63-42.99l62-31.74c44.88-22.96 39.59-80.17-8.95-96.79z\"],\n    \"spray-can\": [512, 512, [], \"f5bd\", \"M224 32c0-17.67-14.33-32-32-32h-64c-17.67 0-32 14.33-32 32v96h128V32zm256 96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-256 32H96c-53.02 0-96 42.98-96 96v224c0 17.67 14.33 32 32 32h256c17.67 0 32-14.33 32-32V256c0-53.02-42.98-96-96-96zm-64 256c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zM480 96c17.67 0 32-14.33 32-32s-14.33-32-32-32-32 14.33-32 32 14.33 32 32 32zm-96 32c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm-96-96c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 0c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32zm96 192c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"],\n    \"square\": [448, 512, [], \"f0c8\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"square-full\": [512, 512, [], \"f45c\", \"M512 512H0V0h512v512z\"],\n    \"square-root-alt\": [576, 512, [], \"f698\", \"M571.31 251.31l-22.62-22.62c-6.25-6.25-16.38-6.25-22.63 0L480 274.75l-46.06-46.06c-6.25-6.25-16.38-6.25-22.63 0l-22.62 22.62c-6.25 6.25-6.25 16.38 0 22.63L434.75 320l-46.06 46.06c-6.25 6.25-6.25 16.38 0 22.63l22.62 22.62c6.25 6.25 16.38 6.25 22.63 0L480 365.25l46.06 46.06c6.25 6.25 16.38 6.25 22.63 0l22.62-22.62c6.25-6.25 6.25-16.38 0-22.63L525.25 320l46.06-46.06c6.25-6.25 6.25-16.38 0-22.63zM552 0H307.65c-14.54 0-27.26 9.8-30.95 23.87l-84.79 322.8-58.41-106.1A32.008 32.008 0 0 0 105.47 224H24c-13.25 0-24 10.74-24 24v48c0 13.25 10.75 24 24 24h43.62l88.88 163.73C168.99 503.5 186.3 512 204.94 512c17.27 0 44.44-9 54.28-41.48L357.03 96H552c13.25 0 24-10.75 24-24V24c0-13.26-10.75-24-24-24z\"],\n    \"stamp\": [512, 512, [], \"f5bf\", \"M32 512h448v-64H32v64zm384-256h-66.56c-16.26 0-29.44-13.18-29.44-29.44v-9.46c0-27.37 8.88-53.41 21.46-77.72 9.11-17.61 12.9-38.39 9.05-60.42-6.77-38.78-38.47-70.7-77.26-77.45C212.62-9.04 160 37.33 160 96c0 14.16 3.12 27.54 8.69 39.58C182.02 164.43 192 194.7 192 226.49v.07c0 16.26-13.18 29.44-29.44 29.44H96c-53.02 0-96 42.98-96 96v32c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-32c0-53.02-42.98-96-96-96z\"],\n    \"star\": [576, 512, [], \"f005\", \"M259.3 17.8L194 150.2 47.9 171.5c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.3 23.2 46 46.4 33.7L288 439.6l130.7 68.7c23.2 12.2 50.9-7.4 46.4-33.7l-25-145.5 105.7-103c19-18.5 8.5-50.8-17.7-54.6L382 150.2 316.7 17.8c-11.7-23.6-45.6-23.9-57.4 0z\"],\n    \"star-and-crescent\": [512, 512, [], \"f699\", \"M340.47 466.36c-1.45 0-6.89.46-9.18.46-116.25 0-210.82-94.57-210.82-210.82S215.04 45.18 331.29 45.18c2.32 0 7.7.46 9.18.46 7.13 0 13.33-5.03 14.75-12.07 1.46-7.25-2.55-14.49-9.47-17.09C316.58 5.54 286.39 0 256 0 114.84 0 0 114.84 0 256s114.84 256 256 256c30.23 0 60.28-5.49 89.32-16.32 5.96-2.02 10.28-7.64 10.28-14.26 0-8.09-6.39-15.06-15.13-15.06zm162.99-252.5l-76.38-11.1-34.16-69.21c-1.83-3.7-5.38-5.55-8.93-5.55s-7.1 1.85-8.93 5.55l-34.16 69.21-76.38 11.1c-8.17 1.18-11.43 11.22-5.52 16.99l55.27 53.87-13.05 76.07c-1.11 6.44 4.01 11.66 9.81 11.66 1.53 0 3.11-.36 4.64-1.17L384 335.37l68.31 35.91c1.53.8 3.11 1.17 4.64 1.17 5.8 0 10.92-5.23 9.81-11.66l-13.05-76.07 55.27-53.87c5.91-5.77 2.65-15.81-5.52-16.99z\"],\n    \"star-half\": [576, 512, [], \"f089\", \"M288 0c-11.4 0-22.8 5.9-28.7 17.8L194 150.2 47.9 171.4c-26.2 3.8-36.7 36.1-17.7 54.6l105.7 103-25 145.5c-4.5 26.1 23 46 46.4 33.7L288 439.6V0z\"],\n    \"star-half-alt\": [536, 512, [], \"f5c0\", \"M508.55 171.51L362.18 150.2 296.77 17.81C290.89 5.98 279.42 0 267.95 0c-11.4 0-22.79 5.9-28.69 17.81l-65.43 132.38-146.38 21.29c-26.25 3.8-36.77 36.09-17.74 54.59l105.89 103-25.06 145.48C86.98 495.33 103.57 512 122.15 512c4.93 0 10-1.17 14.87-3.75l130.95-68.68 130.94 68.7c4.86 2.55 9.92 3.71 14.83 3.71 18.6 0 35.22-16.61 31.66-37.4l-25.03-145.49 105.91-102.98c19.04-18.5 8.52-50.8-17.73-54.6zm-121.74 123.2l-18.12 17.62 4.28 24.88 19.52 113.45-102.13-53.59-22.38-11.74.03-317.19 51.03 103.29 11.18 22.63 25.01 3.64 114.23 16.63-82.65 80.38z\"],\n    \"star-of-david\": [464, 512, [], \"f69a\", \"M405.68 256l53.21-89.39C473.3 142.4 455.48 112 426.88 112H319.96l-55.95-93.98C256.86 6.01 244.43 0 232 0s-24.86 6.01-32.01 18.02L144.04 112H37.11c-28.6 0-46.42 30.4-32.01 54.61L58.32 256 5.1 345.39C-9.31 369.6 8.51 400 37.11 400h106.93l55.95 93.98C207.14 505.99 219.57 512 232 512s24.86-6.01 32.01-18.02L319.96 400h106.93c28.6 0 46.42-30.4 32.01-54.61L405.68 256zm-12.78-88l-19.8 33.26L353.3 168h39.6zm-52.39 88l-52.39 88H175.88l-52.39-88 52.38-88h112.25l52.39 88zM232 73.72L254.79 112h-45.57L232 73.72zM71.1 168h39.6l-19.8 33.26L71.1 168zm0 176l19.8-33.26L110.7 344H71.1zM232 438.28L209.21 400h45.57L232 438.28zM353.29 344l19.8-33.26L392.9 344h-39.61z\"],\n    \"star-of-life\": [480, 512, [], \"f621\", \"M471.99 334.43L336.06 256l135.93-78.43c7.66-4.42 10.28-14.2 5.86-21.86l-32.02-55.43c-4.42-7.65-14.21-10.28-21.87-5.86l-135.93 78.43V16c0-8.84-7.17-16-16.01-16h-64.04c-8.84 0-16.01 7.16-16.01 16v156.86L56.04 94.43c-7.66-4.42-17.45-1.79-21.87 5.86L2.15 155.71c-4.42 7.65-1.8 17.44 5.86 21.86L143.94 256 8.01 334.43c-7.66 4.42-10.28 14.21-5.86 21.86l32.02 55.43c4.42 7.65 14.21 10.27 21.87 5.86l135.93-78.43V496c0 8.84 7.17 16 16.01 16h64.04c8.84 0 16.01-7.16 16.01-16V339.14l135.93 78.43c7.66 4.42 17.45 1.8 21.87-5.86l32.02-55.43c4.42-7.65 1.8-17.43-5.86-21.85z\"],\n    \"step-backward\": [448, 512, [], \"f048\", \"M64 468V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12v176.4l195.5-181C352.1 22.3 384 36.6 384 64v384c0 27.4-31.9 41.7-52.5 24.6L136 292.7V468c0 6.6-5.4 12-12 12H76c-6.6 0-12-5.4-12-12z\"],\n    \"step-forward\": [448, 512, [], \"f051\", \"M384 44v424c0 6.6-5.4 12-12 12h-48c-6.6 0-12-5.4-12-12V291.6l-195.5 181C95.9 489.7 64 475.4 64 448V64c0-27.4 31.9-41.7 52.5-24.6L312 219.3V44c0-6.6 5.4-12 12-12h48c6.6 0 12 5.4 12 12z\"],\n    \"stethoscope\": [512, 512, [], \"f0f1\", \"M447.1 112c-34.2.5-62.3 28.4-63 62.6-.5 24.3 12.5 45.6 32 56.8V344c0 57.3-50.2 104-112 104-60 0-109.2-44.1-111.9-99.2C265 333.8 320 269.2 320 192V36.6c0-11.4-8.1-21.3-19.3-23.5L237.8.5c-13-2.6-25.6 5.8-28.2 18.8L206.4 35c-2.6 13 5.8 25.6 18.8 28.2l30.7 6.1v121.4c0 52.9-42.2 96.7-95.1 97.2-53.4.5-96.9-42.7-96.9-96V69.4l30.7-6.1c13-2.6 21.4-15.2 18.8-28.2l-3.1-15.7C107.7 6.4 95.1-2 82.1.6L19.3 13C8.1 15.3 0 25.1 0 36.6V192c0 77.3 55.1 142 128.1 156.8C130.7 439.2 208.6 512 304 512c97 0 176-75.4 176-168V231.4c19.1-11.1 32-31.7 32-55.4 0-35.7-29.2-64.5-64.9-64zm.9 80c-8.8 0-16-7.2-16-16s7.2-16 16-16 16 7.2 16 16-7.2 16-16 16z\"],\n    \"sticky-note\": [448, 512, [], \"f249\", \"M312 320h136V56c0-13.3-10.7-24-24-24H24C10.7 32 0 42.7 0 56v400c0 13.3 10.7 24 24 24h264V344c0-13.2 10.8-24 24-24zm129 55l-98 98c-4.5 4.5-10.6 7-17 7h-6V352h128v6.1c0 6.3-2.5 12.4-7 16.9z\"],\n    \"stop\": [448, 512, [], \"f04d\", \"M400 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48z\"],\n    \"stop-circle\": [512, 512, [], \"f28d\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm96 328c0 8.8-7.2 16-16 16H176c-8.8 0-16-7.2-16-16V176c0-8.8 7.2-16 16-16h160c8.8 0 16 7.2 16 16v160z\"],\n    \"stopwatch\": [448, 512, [], \"f2f2\", \"M432 304c0 114.9-93.1 208-208 208S16 418.9 16 304c0-104 76.3-190.2 176-205.5V64h-28c-6.6 0-12-5.4-12-12V12c0-6.6 5.4-12 12-12h120c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-28v34.5c37.5 5.8 71.7 21.6 99.7 44.6l27.5-27.5c4.7-4.7 12.3-4.7 17 0l28.3 28.3c4.7 4.7 4.7 12.3 0 17l-29.4 29.4-.6.6C419.7 223.3 432 262.2 432 304zm-176 36V188.5c0-6.6-5.4-12-12-12h-40c-6.6 0-12 5.4-12 12V340c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12z\"],\n    \"store\": [616, 512, [], \"f54e\", \"M602 118.6L537.1 15C531.3 5.7 521 0 510 0H106C95 0 84.7 5.7 78.9 15L14 118.6c-33.5 53.5-3.8 127.9 58.8 136.4 4.5.6 9.1.9 13.7.9 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18 20.1 44.3 33.1 73.8 33.1 29.6 0 55.8-13 73.8-33.1 18.1 20.1 44.3 33.1 73.8 33.1 4.7 0 9.2-.3 13.7-.9 62.8-8.4 92.6-82.8 59-136.4zM529.5 288c-10 0-19.9-1.5-29.5-3.8V384H116v-99.8c-9.6 2.2-19.5 3.8-29.5 3.8-6 0-12.1-.4-18-1.2-5.6-.8-11.1-2.1-16.4-3.6V480c0 17.7 14.3 32 32 32h448c17.7 0 32-14.3 32-32V283.2c-5.4 1.6-10.8 2.9-16.4 3.6-6.1.8-12.1 1.2-18.2 1.2z\"],\n    \"store-alt\": [640, 512, [], \"f54f\", \"M320 384H128V224H64v256c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V224h-64v160zm314.6-241.8l-85.3-128c-6-8.9-16-14.2-26.7-14.2H117.4c-10.7 0-20.7 5.3-26.6 14.2l-85.3 128c-14.2 21.3 1 49.8 26.6 49.8H608c25.5 0 40.7-28.5 26.6-49.8zM512 496c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16V224h-64v272z\"],\n    \"stream\": [512, 512, [], \"f550\", \"M16 128h416c8.84 0 16-7.16 16-16V48c0-8.84-7.16-16-16-16H16C7.16 32 0 39.16 0 48v64c0 8.84 7.16 16 16 16zm480 80H80c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16zm-64 176H16c-8.84 0-16 7.16-16 16v64c0 8.84 7.16 16 16 16h416c8.84 0 16-7.16 16-16v-64c0-8.84-7.16-16-16-16z\"],\n    \"street-view\": [512, 512, [], \"f21d\", \"M367.9 329.76c-4.62 5.3-9.78 10.1-15.9 13.65v22.94c66.52 9.34 112 28.05 112 49.65 0 30.93-93.12 56-208 56S48 446.93 48 416c0-21.6 45.48-40.3 112-49.65v-22.94c-6.12-3.55-11.28-8.35-15.9-13.65C58.87 345.34 0 378.05 0 416c0 53.02 114.62 96 256 96s256-42.98 256-96c0-37.95-58.87-70.66-144.1-86.24zM256 128c35.35 0 64-28.65 64-64S291.35 0 256 0s-64 28.65-64 64 28.65 64 64 64zm-64 192v96c0 17.67 14.33 32 32 32h64c17.67 0 32-14.33 32-32v-96c17.67 0 32-14.33 32-32v-96c0-26.51-21.49-48-48-48h-11.8c-11.07 5.03-23.26 8-36.2 8s-25.13-2.97-36.2-8H208c-26.51 0-48 21.49-48 48v96c0 17.67 14.33 32 32 32z\"],\n    \"strikethrough\": [512, 512, [], \"f0cc\", \"M496 224H293.9l-87.17-26.83A43.55 43.55 0 0 1 219.55 112h66.79A49.89 49.89 0 0 1 331 139.58a16 16 0 0 0 21.46 7.15l42.94-21.47a16 16 0 0 0 7.16-21.46l-.53-1A128 128 0 0 0 287.51 32h-68a123.68 123.68 0 0 0-123 135.64c2 20.89 10.1 39.83 21.78 56.36H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h480a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm-180.24 96A43 43 0 0 1 336 356.45 43.59 43.59 0 0 1 292.45 400h-66.79A49.89 49.89 0 0 1 181 372.42a16 16 0 0 0-21.46-7.15l-42.94 21.47a16 16 0 0 0-7.16 21.46l.53 1A128 128 0 0 0 224.49 480h68a123.68 123.68 0 0 0 123-135.64 114.25 114.25 0 0 0-5.34-24.36z\"],\n    \"stroopwafel\": [512, 512, [], \"f551\", \"M188.12 210.74L142.86 256l45.25 45.25L233.37 256l-45.25-45.26zm113.13-22.62L256 142.86l-45.25 45.25L256 233.37l45.25-45.25zm-90.5 135.76L256 369.14l45.26-45.26L256 278.63l-45.25 45.25zM256 0C114.62 0 0 114.62 0 256s114.62 256 256 256 256-114.62 256-256S397.38 0 256 0zm186.68 295.6l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-28.29-28.29-45.25 45.25 33.94 33.94 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-33.94-33.94-45.26 45.26 28.29 28.29c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0L256 414.39l-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l28.29-28.29-45.25-45.26-33.94 33.94 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 33.94-33.94-45.25-45.25-28.29 28.29c-3.12 3.12-8.19 3.12-11.31 0L69.32 295.6c-3.12-3.12-3.12-8.19 0-11.31L97.61 256l-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l28.29 28.29 45.25-45.26-33.94-33.94-16.97 16.97c-3.12 3.12-8.19 3.12-11.31 0l-11.31-11.31c-3.12-3.12-3.12-8.19 0-11.31l16.97-16.97-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 33.94 33.94 45.26-45.25-28.29-28.29c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0L256 97.61l28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-28.29 28.29 45.26 45.25 33.94-33.94-16.97-16.97c-3.12-3.12-3.12-8.19 0-11.31l11.31-11.31c3.12-3.12 8.19-3.12 11.31 0l16.97 16.97 16.97-16.97c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31l-16.97 16.97 16.97 16.97c3.12 3.12 3.12 8.19 0 11.31l-11.31 11.31c-3.12 3.12-8.19 3.12-11.31 0l-16.97-16.97-33.94 33.94 45.25 45.26 28.29-28.29c3.12-3.12 8.19-3.12 11.31 0l11.31 11.31c3.12 3.12 3.12 8.19 0 11.31L414.39 256l28.29 28.28a8.015 8.015 0 0 1 0 11.32zM278.63 256l45.26 45.25L369.14 256l-45.25-45.26L278.63 256z\"],\n    \"subscript\": [512, 512, [], \"f12c\", \"M496 448h-16V304a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 352h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"subway\": [448, 512, [], \"f239\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zM200 232V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm200 0V120c0-13.255-10.745-24-24-24H272c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h104c13.255 0 24-10.745 24-24zm-48 56c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48zm-256 0c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"suitcase\": [512, 512, [], \"f0f2\", \"M128 480h256V80c0-26.5-21.5-48-48-48H176c-26.5 0-48 21.5-48 48v400zm64-384h128v32H192V96zm320 80v256c0 26.5-21.5 48-48 48h-48V128h48c26.5 0 48 21.5 48 48zM96 480H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h48v352z\"],\n    \"suitcase-rolling\": [384, 512, [], \"f5c1\", \"M336 160H48c-26.51 0-48 21.49-48 48v224c0 26.51 21.49 48 48 48h16v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h128v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16h16c26.51 0 48-21.49 48-48V208c0-26.51-21.49-48-48-48zm-16 216c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zm0-96c0 4.42-3.58 8-8 8H72c-4.42 0-8-3.58-8-8v-16c0-4.42 3.58-8 8-8h240c4.42 0 8 3.58 8 8v16zM144 48h96v80h48V48c0-26.51-21.49-48-48-48h-96c-26.51 0-48 21.49-48 48v80h48V48z\"],\n    \"sun\": [512, 512, [], \"f185\", \"M256 160c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm246.4 80.5l-94.7-47.3 33.5-100.4c4.5-13.6-8.4-26.5-21.9-21.9l-100.4 33.5-47.4-94.8c-6.4-12.8-24.6-12.8-31 0l-47.3 94.7L92.7 70.8c-13.6-4.5-26.5 8.4-21.9 21.9l33.5 100.4-94.7 47.4c-12.8 6.4-12.8 24.6 0 31l94.7 47.3-33.5 100.5c-4.5 13.6 8.4 26.5 21.9 21.9l100.4-33.5 47.3 94.7c6.4 12.8 24.6 12.8 31 0l47.3-94.7 100.4 33.5c13.6 4.5 26.5-8.4 21.9-21.9l-33.5-100.4 94.7-47.3c13-6.5 13-24.7.2-31.1zm-155.9 106c-49.9 49.9-131.1 49.9-181 0-49.9-49.9-49.9-131.1 0-181 49.9-49.9 131.1-49.9 181 0 49.9 49.9 49.9 131.1 0 181z\"],\n    \"superscript\": [512, 512, [], \"f12b\", \"M496 160h-16V16a16 16 0 0 0-16-16h-48a16 16 0 0 0-14.29 8.83l-16 32A16 16 0 0 0 400 64h16v96h-16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h96a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zM336 64h-67a16 16 0 0 0-13.14 6.87l-79.9 115-79.9-115A16 16 0 0 0 83 64H16A16 16 0 0 0 0 80v48a16 16 0 0 0 16 16h33.48l77.81 112-77.81 112H16a16 16 0 0 0-16 16v48a16 16 0 0 0 16 16h67a16 16 0 0 0 13.14-6.87l79.9-115 79.9 115A16 16 0 0 0 269 448h67a16 16 0 0 0 16-16v-48a16 16 0 0 0-16-16h-33.48l-77.81-112 77.81-112H336a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16z\"],\n    \"surprise\": [496, 512, [], \"f5c2\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zM136 208c0-17.7 14.3-32 32-32s32 14.3 32 32-14.3 32-32 32-32-14.3-32-32zm112 208c-35.3 0-64-28.7-64-64s28.7-64 64-64 64 28.7 64 64-28.7 64-64 64zm80-176c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"swatchbook\": [511, 512, [], \"f5c3\", \"M479.06 320H372.29L186.15 506.51c-2.06 2.07-4.49 3.58-6.67 5.49h299.58c17.64 0 31.94-14.33 31.94-32V352c0-17.67-14.3-32-31.94-32zm-44.5-152.9l-90.33-90.51c-12.47-12.5-32.69-12.5-45.17 0l-75.5 75.65V416c0 2.96-.67 5.73-.87 8.64l211.87-212.28c12.47-12.5 12.47-32.77 0-45.26zM191.62 32c0-17.67-14.3-32-31.94-32H31.94C14.3 0 0 14.33 0 32v384c0 53.02 42.9 96 95.81 96s95.81-42.98 95.81-96V32zM95.81 440c-13.23 0-23.95-10.75-23.95-24 0-13.26 10.73-24 23.95-24s23.95 10.74 23.95 24c.01 13.25-10.72 24-23.95 24zm31.94-184H63.88v-64h63.88v64zm0-128H63.88V64h63.88v64z\"],\n    \"swimmer\": [640, 512, [], \"f5c4\", \"M189.61 310.58c3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c16.02-14.77 34.5-22.58 53.46-22.58h16.3c18.96 0 37.45 7.81 53.46 22.58 3.54 3.26 15.27 9.42 34.39 9.42s30.86-6.16 34.39-9.42c14.86-13.71 31.88-21.12 49.39-22.16l-112.84-80.6 18-12.86c3.64-2.58 8.28-3.52 12.62-2.61l100.35 21.53c25.91 5.53 51.44-10.97 57-36.88 5.55-25.92-10.95-51.44-36.88-57L437.68 98.47c-30.73-6.58-63.02.12-88.56 18.38l-80.02 57.17c-10.38 7.39-19.36 16.44-26.72 26.94L173.75 299c5.47 3.23 10.82 6.93 15.86 11.58zM624 352h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 343.58 442.04 352 416 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 343.58 250.04 352 224 352s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 343.58 58.04 352 32 352H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-512-96c44.18 0 80-35.82 80-80s-35.82-80-80-80-80 35.82-80 80 35.82 80 80 80z\"],\n    \"swimming-pool\": [640, 512, [], \"f5c5\", \"M624 416h-16c-26.04 0-45.8-8.42-56.09-17.9-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C461.8 407.58 442.04 416 416 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C269.8 407.58 250.04 416 224 416s-45.8-8.42-56.09-17.9c-8.9-8.21-19.66-14.1-31.77-14.1h-16.3c-12.11 0-22.87 5.89-31.77 14.1C77.8 407.58 58.04 416 32 416H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16c38.62 0 72.72-12.19 96-31.84 23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84s72.72-12.19 96-31.84c23.28 19.66 57.38 31.84 96 31.84h16c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-400-32v-96h192v96c19.12 0 30.86-6.16 34.39-9.42 9.17-8.46 19.2-14.34 29.61-18.07V128c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v96H224v-96c0-17.64 14.36-32 32-32s32 14.36 32 32v16c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-16c0-52.94-43.06-96-96-96s-96 43.06-96 96v228.5c10.41 3.73 20.44 9.62 29.61 18.07 3.53 3.27 15.27 9.43 34.39 9.43z\"],\n    \"synagogue\": [640, 512, [], \"f69b\", \"M70 196.51L6.67 268.29A26.643 26.643 0 0 0 0 285.93V512h128V239.58l-38-43.07c-5.31-6.01-14.69-6.01-20 0zm563.33 71.78L570 196.51c-5.31-6.02-14.69-6.02-20 0l-38 43.07V512h128V285.93c0-6.5-2.37-12.77-6.67-17.64zM339.99 7.01c-11.69-9.35-28.29-9.35-39.98 0l-128 102.4A32.005 32.005 0 0 0 160 134.4V512h96v-92.57c0-31.88 21.78-61.43 53.25-66.55C349.34 346.35 384 377.13 384 416v96h96V134.4c0-9.72-4.42-18.92-12.01-24.99l-128-102.4zm52.07 215.55c1.98 3.15-.29 7.24-4 7.24h-38.94L324 269.79c-1.85 2.95-6.15 2.95-8 0l-25.12-39.98h-38.94c-3.72 0-5.98-4.09-4-7.24l19.2-30.56-19.2-30.56c-1.98-3.15.29-7.24 4-7.24h38.94l25.12-40c1.85-2.95 6.15-2.95 8 0l25.12 39.98h38.95c3.71 0 5.98 4.09 4 7.24L372.87 192l19.19 30.56z\"],\n    \"sync\": [512, 512, [], \"f021\", \"M440.65 12.57l4 82.77A247.16 247.16 0 0 0 255.83 8C134.73 8 33.91 94.92 12.29 209.82A12 12 0 0 0 24.09 224h49.05a12 12 0 0 0 11.67-9.26 175.91 175.91 0 0 1 317-56.94l-101.46-4.86a12 12 0 0 0-12.57 12v47.41a12 12 0 0 0 12 12H500a12 12 0 0 0 12-12V12a12 12 0 0 0-12-12h-47.37a12 12 0 0 0-11.98 12.57zM255.83 432a175.61 175.61 0 0 1-146-77.8l101.8 4.87a12 12 0 0 0 12.57-12v-47.4a12 12 0 0 0-12-12H12a12 12 0 0 0-12 12V500a12 12 0 0 0 12 12h47.35a12 12 0 0 0 12-12.6l-4.15-82.57A247.17 247.17 0 0 0 255.83 504c121.11 0 221.93-86.92 243.55-201.82a12 12 0 0 0-11.8-14.18h-49.05a12 12 0 0 0-11.67 9.26A175.86 175.86 0 0 1 255.83 432z\"],\n    \"sync-alt\": [512, 512, [], \"f2f1\", \"M370.72 133.28C339.458 104.008 298.888 87.962 255.848 88c-77.458.068-144.328 53.178-162.791 126.85-1.344 5.363-6.122 9.15-11.651 9.15H24.103c-7.498 0-13.194-6.807-11.807-14.176C33.933 94.924 134.813 8 256 8c66.448 0 126.791 26.136 171.315 68.685L463.03 40.97C478.149 25.851 504 36.559 504 57.941V192c0 13.255-10.745 24-24 24H345.941c-21.382 0-32.09-25.851-16.971-40.971l41.75-41.749zM32 296h134.059c21.382 0 32.09 25.851 16.971 40.971l-41.75 41.75c31.262 29.273 71.835 45.319 114.876 45.28 77.418-.07 144.315-53.144 162.787-126.849 1.344-5.363 6.122-9.15 11.651-9.15h57.304c7.498 0 13.194 6.807 11.807 14.176C478.067 417.076 377.187 504 256 504c-66.448 0-126.791-26.136-171.315-68.685L48.97 471.03C33.851 486.149 8 475.441 8 454.059V320c0-13.255 10.745-24 24-24z\"],\n    \"syringe\": [512, 512, [], \"f48e\", \"M201.5 174.8l55.7 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-55.7-55.8-45.3 45.3 55.8 55.8c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L111 265.2l-26.4 26.4c-17.3 17.3-25.6 41.1-23 65.4l7.1 63.6L2.3 487c-3.1 3.1-3.1 8.2 0 11.3l11.3 11.3c3.1 3.1 8.2 3.1 11.3 0l66.3-66.3 63.6 7.1c23.9 2.6 47.9-5.4 65.4-23l181.9-181.9-135.7-135.7-64.9 65zm308.2-93.3L430.5 2.3c-3.1-3.1-8.2-3.1-11.3 0l-11.3 11.3c-3.1 3.1-3.1 8.2 0 11.3l28.3 28.3-45.3 45.3-56.6-56.6-17-17c-3.1-3.1-8.2-3.1-11.3 0l-33.9 33.9c-3.1 3.1-3.1 8.2 0 11.3l17 17L424.8 223l17 17c3.1 3.1 8.2 3.1 11.3 0l33.9-34c3.1-3.1 3.1-8.2 0-11.3l-73.5-73.5 45.3-45.3 28.3 28.3c3.1 3.1 8.2 3.1 11.3 0l11.3-11.3c3.1-3.2 3.1-8.2 0-11.4z\"],\n    \"table\": [512, 512, [], \"f0ce\", \"M464 32H48C21.49 32 0 53.49 0 80v352c0 26.51 21.49 48 48 48h416c26.51 0 48-21.49 48-48V80c0-26.51-21.49-48-48-48zM224 416H64v-96h160v96zm0-160H64v-96h160v96zm224 160H288v-96h160v96zm0-160H288v-96h160v96z\"],\n    \"table-tennis\": [512, 512, [], \"f45d\", \"M496.2 296.5C527.7 218.7 512 126.2 449 63.1 365.1-21 229-21 145.1 63.1l-56 56.1 211.5 211.5c46.1-62.1 131.5-77.4 195.6-34.2zm-217.9 79.7L57.9 155.9c-27.3 45.3-21.7 105 17.3 144.1l34.5 34.6L6.7 424c-8.6 7.5-9.1 20.7-1 28.8l53.4 53.5c8 8.1 21.2 7.6 28.7-1L177.1 402l35.7 35.7c19.7 19.7 44.6 30.5 70.3 33.3-7.1-17-11-35.6-11-55.1-.1-13.8 2.5-27 6.2-39.7zM416 320c-53 0-96 43-96 96s43 96 96 96 96-43 96-96-43-96-96-96z\"],\n    \"tablet\": [448, 512, [], \"f10a\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32z\"],\n    \"tablet-alt\": [448, 512, [], \"f3fa\", \"M400 0H48C21.5 0 0 21.5 0 48v416c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zM224 480c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm176-108c0 6.6-5.4 12-12 12H60c-6.6 0-12-5.4-12-12V60c0-6.6 5.4-12 12-12h328c6.6 0 12 5.4 12 12v312z\"],\n    \"tablets\": [640, 512, [], \"f490\", \"M160 192C78.9 192 12.5 250.5.1 326.7c-.8 4.8 3.3 9.3 8.3 9.3h303.3c5 0 9.1-4.5 8.3-9.3C307.5 250.5 241.1 192 160 192zm151.6 176H8.4c-5 0-9.1 4.5-8.3 9.3C12.5 453.5 78.9 512 160 512s147.5-58.5 159.9-134.7c.8-4.8-3.3-9.3-8.3-9.3zM593.4 46.6c-56.5-56.5-144.2-61.4-206.9-16-4 2.9-4.3 8.9-.8 12.3L597 254.3c3.5 3.5 9.5 3.2 12.3-.8 45.5-62.7 40.6-150.4-15.9-206.9zM363 65.7c-3.5-3.5-9.5-3.2-12.3.8-45.4 62.7-40.5 150.4 15.9 206.9 56.5 56.5 144.2 61.4 206.9 15.9 4-2.9 4.3-8.9.8-12.3L363 65.7z\"],\n    \"tachometer-alt\": [576, 512, [], \"f3fd\", \"M288 32C128.94 32 0 160.94 0 320c0 52.8 14.25 102.26 39.06 144.8 5.61 9.62 16.3 15.2 27.44 15.2h443c11.14 0 21.83-5.58 27.44-15.2C561.75 422.26 576 372.8 576 320c0-159.06-128.94-288-288-288zm0 64c14.71 0 26.58 10.13 30.32 23.65-1.11 2.26-2.64 4.23-3.45 6.67l-9.22 27.67c-5.13 3.49-10.97 6.01-17.64 6.01-17.67 0-32-14.33-32-32S270.33 96 288 96zM96 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm48-160c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm246.77-72.41l-61.33 184C343.13 347.33 352 364.54 352 384c0 11.72-3.38 22.55-8.88 32H232.88c-5.5-9.45-8.88-20.28-8.88-32 0-33.94 26.5-61.43 59.9-63.59l61.34-184.01c4.17-12.56 17.73-19.45 30.36-15.17 12.57 4.19 19.35 17.79 15.17 30.36zm14.66 57.2l15.52-46.55c3.47-1.29 7.13-2.23 11.05-2.23 17.67 0 32 14.33 32 32s-14.33 32-32 32c-11.38-.01-20.89-6.28-26.57-15.22zM480 384c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"tag\": [512, 512, [], \"f02b\", \"M0 252.118V48C0 21.49 21.49 0 48 0h204.118a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882L293.823 497.941c-18.745 18.745-49.137 18.745-67.882 0L14.059 286.059A48 48 0 0 1 0 252.118zM112 64c-26.51 0-48 21.49-48 48s21.49 48 48 48 48-21.49 48-48-21.49-48-48-48z\"],\n    \"tags\": [640, 512, [], \"f02c\", \"M497.941 225.941L286.059 14.059A48 48 0 0 0 252.118 0H48C21.49 0 0 21.49 0 48v204.118a48 48 0 0 0 14.059 33.941l211.882 211.882c18.744 18.745 49.136 18.746 67.882 0l204.118-204.118c18.745-18.745 18.745-49.137 0-67.882zM112 160c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm513.941 133.823L421.823 497.941c-18.745 18.745-49.137 18.745-67.882 0l-.36-.36L527.64 323.522c16.999-16.999 26.36-39.6 26.36-63.64s-9.362-46.641-26.36-63.64L331.397 0h48.721a48 48 0 0 1 33.941 14.059l211.882 211.882c18.745 18.745 18.745 49.137 0 67.882z\"],\n    \"tape\": [640, 512, [], \"f4db\", \"M224 192c-35.3 0-64 28.7-64 64s28.7 64 64 64 64-28.7 64-64-28.7-64-64-64zm400 224H380.6c41.5-40.7 67.4-97.3 67.4-160 0-123.7-100.3-224-224-224S0 132.3 0 256s100.3 224 224 224h400c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400-64c-53 0-96-43-96-96s43-96 96-96 96 43 96 96-43 96-96 96z\"],\n    \"tasks\": [512, 512, [], \"f0ae\", \"M139.61 35.5a12 12 0 0 0-17 0L58.93 98.81l-22.7-22.12a12 12 0 0 0-17 0L3.53 92.41a12 12 0 0 0 0 17l47.59 47.4a12.78 12.78 0 0 0 17.61 0l15.59-15.62L156.52 69a12.09 12.09 0 0 0 .09-17zm0 159.19a12 12 0 0 0-17 0l-63.68 63.72-22.7-22.1a12 12 0 0 0-17 0L3.53 252a12 12 0 0 0 0 17L51 316.5a12.77 12.77 0 0 0 17.6 0l15.7-15.69 72.2-72.22a12 12 0 0 0 .09-16.9zM64 368c-26.49 0-48.59 21.5-48.59 48S37.53 464 64 464a48 48 0 0 0 0-96zm432 16H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16zm0-320H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16V80a16 16 0 0 0-16-16zm0 160H208a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h288a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"taxi\": [512, 512, [], \"f1ba\", \"M462 241.64l-22-84.84c-9.6-35.2-41.6-60.8-76.8-60.8H352V64c0-17.67-14.33-32-32-32H192c-17.67 0-32 14.33-32 32v32h-11.2c-35.2 0-67.2 25.6-76.8 60.8l-22 84.84C21.41 248.04 0 273.47 0 304v48c0 23.63 12.95 44.04 32 55.12V448c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-32h256v32c0 17.67 14.33 32 32 32h32c17.67 0 32-14.33 32-32v-40.88c19.05-11.09 32-31.5 32-55.12v-48c0-30.53-21.41-55.96-50-62.36zM96 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm20.55-112l17.2-66.36c2.23-8.16 9.59-13.64 15.06-13.64h214.4c5.47 0 12.83 5.48 14.85 12.86L395.45 240h-278.9zM416 352c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"teeth\": [640, 512, [], \"f62e\", \"M544 0H96C42.98 0 0 42.98 0 96v320c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96V96c0-53.02-42.98-96-96-96zM160 368c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm144 120c0 30.93-25.07 56-56 56s-56-25.07-56-56v-56c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v56zm0-120c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-88c0-30.93 25.07-56 56-56s56 25.07 56 56v88zm128 128c0 26.51-21.49 48-48 48s-48-21.49-48-48v-64c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v64zm0-128c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-64c0-26.51 21.49-48 48-48s48 21.49 48 48v64z\"],\n    \"teeth-open\": [640, 512, [], \"f62f\", \"M544 0H96C42.98 0 0 42.98 0 96v64c0 35.35 28.66 64 64 64h512c35.34 0 64-28.65 64-64V96c0-53.02-42.98-96-96-96zM160 176c0 8.84-7.16 16-16 16H80c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm144 0c0 8.84-7.16 16-16 16h-80c-8.84 0-16-7.16-16-16v-56c0-30.93 25.07-56 56-56s56 25.07 56 56v56zm128 0c0 8.84-7.16 16-16 16h-64c-8.84 0-16-7.16-16-16v-32c0-26.51 21.49-48 48-48s48 21.49 48 48v32zm0 144H64c-35.34 0-64 28.65-64 64v32c0 53.02 42.98 96 96 96h448c53.02 0 96-42.98 96-96v-32c0-35.35-28.66-64-64-64zm-416 80c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32zm144-8c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm144 0c0 30.93-25.07 56-56 56s-56-25.07-56-56v-24c0-8.84 7.16-16 16-16h80c8.84 0 16 7.16 16 16v24zm128 8c0 26.51-21.49 48-48 48s-48-21.49-48-48v-32c0-8.84 7.16-16 16-16h64c8.84 0 16 7.16 16 16v32z\"],\n    \"temperature-high\": [512, 512, [], \"f769\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V112c0-8.8-7.2-16-16-16s-16 7.2-16 16v210.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"temperature-low\": [512, 512, [], \"f76b\", \"M416 0c-52.9 0-96 43.1-96 96s43.1 96 96 96 96-43.1 96-96-43.1-96-96-96zm0 128c-17.7 0-32-14.3-32-32s14.3-32 32-32 32 14.3 32 32-14.3 32-32 32zm-160-16C256 50.1 205.9 0 144 0S32 50.1 32 112v166.5C12.3 303.2 0 334 0 368c0 79.5 64.5 144 144 144s144-64.5 144-144c0-34-12.3-64.9-32-89.5V112zM144 448c-44.1 0-80-35.9-80-80 0-25.5 12.2-48.9 32-63.8V112c0-26.5 21.5-48 48-48s48 21.5 48 48v192.2c19.8 14.8 32 38.3 32 63.8 0 44.1-35.9 80-80 80zm16-125.1V304c0-8.8-7.2-16-16-16s-16 7.2-16 16v18.9c-18.6 6.6-32 24.2-32 45.1 0 26.5 21.5 48 48 48s48-21.5 48-48c0-20.9-13.4-38.5-32-45.1z\"],\n    \"tenge\": [384, 512, [], \"f7d7\", \"M372 160H12c-6.6 0-12 5.4-12 12v56c0 6.6 5.4 12 12 12h140v228c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12V240h140c6.6 0 12-5.4 12-12v-56c0-6.6-5.4-12-12-12zm0-128H12C5.4 32 0 37.4 0 44v56c0 6.6 5.4 12 12 12h360c6.6 0 12-5.4 12-12V44c0-6.6-5.4-12-12-12z\"],\n    \"terminal\": [640, 512, [], \"f120\", \"M257.981 272.971L63.638 467.314c-9.373 9.373-24.569 9.373-33.941 0L7.029 444.647c-9.357-9.357-9.375-24.522-.04-33.901L161.011 256 6.99 101.255c-9.335-9.379-9.317-24.544.04-33.901l22.667-22.667c9.373-9.373 24.569-9.373 33.941 0L257.981 239.03c9.373 9.372 9.373 24.568 0 33.941zM640 456v-32c0-13.255-10.745-24-24-24H312c-13.255 0-24 10.745-24 24v32c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24z\"],\n    \"text-height\": [576, 512, [], \"f034\", \"M304 32H16A16 16 0 0 0 0 48v96a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-32h56v304H80a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h160a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-40V112h56v32a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm256 336h-48V144h48c14.31 0 21.33-17.31 11.31-27.31l-80-80a16 16 0 0 0-22.62 0l-80 80C379.36 126 384.36 144 400 144h48v224h-48c-14.31 0-21.32 17.31-11.31 27.31l80 80a16 16 0 0 0 22.62 0l80-80C580.64 386 575.64 368 560 368z\"],\n    \"text-width\": [448, 512, [], \"f035\", \"M432 32H16A16 16 0 0 0 0 48v80a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16v-16h120v112h-24a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h128a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16h-24V112h120v16a16 16 0 0 0 16 16h32a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zm-68.69 260.69C354 283.36 336 288.36 336 304v48H112v-48c0-14.31-17.31-21.32-27.31-11.31l-80 80a16 16 0 0 0 0 22.62l80 80C94 484.64 112 479.64 112 464v-48h224v48c0 14.31 17.31 21.33 27.31 11.31l80-80a16 16 0 0 0 0-22.62z\"],\n    \"th\": [512, 512, [], \"f00a\", \"M149.333 56v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zm181.334 240v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm32-240v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24zm-32 80V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.256 0 24.001-10.745 24.001-24zm-205.334 56H24c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm386.667-56H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm0 160H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H386.667c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zM181.333 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24z\"],\n    \"th-large\": [512, 512, [], \"f009\", \"M296 32h192c13.255 0 24 10.745 24 24v160c0 13.255-10.745 24-24 24H296c-13.255 0-24-10.745-24-24V56c0-13.255 10.745-24 24-24zm-80 0H24C10.745 32 0 42.745 0 56v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zM0 296v160c0 13.255 10.745 24 24 24h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zm296 184h192c13.255 0 24-10.745 24-24V296c0-13.255-10.745-24-24-24H296c-13.255 0-24 10.745-24 24v160c0 13.255 10.745 24 24 24z\"],\n    \"th-list\": [512, 512, [], \"f00b\", \"M149.333 216v80c0 13.255-10.745 24-24 24H24c-13.255 0-24-10.745-24-24v-80c0-13.255 10.745-24 24-24h101.333c13.255 0 24 10.745 24 24zM0 376v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H24c-13.255 0-24 10.745-24 24zM125.333 32H24C10.745 32 0 42.745 0 56v80c0 13.255 10.745 24 24 24h101.333c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24zm80 448H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24zm-24-424v80c0 13.255 10.745 24 24 24H488c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24zm24 264H488c13.255 0 24-10.745 24-24v-80c0-13.255-10.745-24-24-24H205.333c-13.255 0-24 10.745-24 24v80c0 13.255 10.745 24 24 24z\"],\n    \"theater-masks\": [640, 512, [], \"f630\", \"M206.86 245.15c-35.88 10.45-59.95 41.2-57.53 74.1 11.4-12.72 28.81-23.7 49.9-30.92l7.63-43.18zM95.81 295L64.08 115.49c-.29-1.62.28-2.62.24-2.65 57.76-32.06 123.12-49.01 189.01-49.01 1.61 0 3.23.17 4.85.19 13.95-13.47 31.73-22.83 51.59-26 18.89-3.02 38.05-4.55 57.18-5.32-9.99-13.95-24.48-24.23-41.77-27C301.27 1.89 277.24 0 253.32 0 176.66 0 101.02 19.42 33.2 57.06 9.03 70.48-3.92 98.48 1.05 126.58l31.73 179.51c14.23 80.52 136.33 142.08 204.45 142.08 3.59 0 6.75-.46 10.01-.8-13.52-17.08-28.94-40.48-39.5-67.58-47.61-12.98-106.06-51.62-111.93-84.79zm97.55-137.46c-.73-4.12-2.23-7.87-4.07-11.4-8.25 8.91-20.67 15.75-35.32 18.32-14.65 2.58-28.67.4-39.48-5.17-.52 3.94-.64 7.98.09 12.1 3.84 21.7 24.58 36.19 46.34 32.37 21.75-3.82 36.28-24.52 32.44-46.22zM606.8 120.9c-88.98-49.38-191.43-67.41-291.98-51.35-27.31 4.36-49.08 26.26-54.04 54.36l-31.73 179.51c-15.39 87.05 95.28 196.27 158.31 207.35 63.03 11.09 204.47-53.79 219.86-140.84l31.73-179.51c4.97-28.11-7.98-56.11-32.15-69.52zm-273.24 96.8c3.84-21.7 24.58-36.19 46.34-32.36 21.76 3.83 36.28 24.52 32.45 46.22-.73 4.12-2.23 7.87-4.07 11.4-8.25-8.91-20.67-15.75-35.32-18.32-14.65-2.58-28.67-.4-39.48 5.17-.53-3.95-.65-7.99.08-12.11zm70.47 198.76c-55.68-9.79-93.52-59.27-89.04-112.9 20.6 25.54 56.21 46.17 99.49 53.78 43.28 7.61 83.82.37 111.93-16.6-14.18 51.94-66.71 85.51-122.38 75.72zm130.3-151.34c-8.25-8.91-20.68-15.75-35.33-18.32-14.65-2.58-28.67-.4-39.48 5.17-.52-3.94-.64-7.98.09-12.1 3.84-21.7 24.58-36.19 46.34-32.37 21.75 3.83 36.28 24.52 32.45 46.22-.73 4.13-2.23 7.88-4.07 11.4z\"],\n    \"thermometer\": [512, 512, [], \"f491\", \"M476.8 20.4c-37.5-30.7-95.5-26.3-131.9 10.2l-45.7 46 50.5 50.5c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.4-50.5-45.1 45.4 50.3 50.4c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0L209 167.4l-45.1 45.4L214 263c3.1 3.1 3.1 8.2 0 11.3l-11.3 11.3c-3.1 3.1-8.2 3.1-11.3 0l-50.1-50.2L96 281.1V382L7 471c-9.4 9.4-9.4 24.6 0 33.9 9.4 9.4 24.6 9.4 33.9 0l89-89h99.9L484 162.6c34.9-34.9 42.2-101.5-7.2-142.2z\"],\n    \"thermometer-empty\": [256, 512, [], \"f2cb\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-35.346 28.654-64 64-64s64 28.654 64 64zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-full\": [256, 512, [], \"f2c7\", \"M224 96c0-53.019-42.981-96-96-96S32 42.981 32 96v203.347C12.225 321.756.166 351.136.002 383.333c-.359 70.303 56.787 128.176 127.089 128.664.299.002.61.003.909.003 70.698 0 128-57.304 128-128 0-32.459-12.088-62.09-32-84.653V96zm-96 368l-.576-.002c-43.86-.304-79.647-36.544-79.423-80.42.173-33.98 19.266-51.652 31.999-66.08V96c0-26.467 21.533-48 48-48s48 21.533 48 48v221.498c12.63 14.312 32 32.164 32 66.502 0 44.112-35.888 80-80 80zm64-80c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V96c0-17.673 14.327-32 32-32s32 14.327 32 32v232.583c19.124 11.068 32 31.732 32 55.417z\"],\n    \"thermometer-half\": [256, 512, [], \"f2c9\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V224c0-17.673 14.327-32 32-32s32 14.327 32 32v104.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-quarter\": [256, 512, [], \"f2ca\", \"M192 384c0 35.346-28.654 64-64 64s-64-28.654-64-64c0-23.685 12.876-44.349 32-55.417V288c0-17.673 14.327-32 32-32s32 14.327 32 32v40.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thermometer-three-quarters\": [256, 512, [], \"f2c8\", \"M192 384c0 35.346-28.654 64-64 64-35.346 0-64-28.654-64-64 0-23.685 12.876-44.349 32-55.417V160c0-17.673 14.327-32 32-32s32 14.327 32 32v168.583c19.124 11.068 32 31.732 32 55.417zm32-84.653c19.912 22.563 32 52.194 32 84.653 0 70.696-57.303 128-128 128-.299 0-.609-.001-.909-.003C56.789 511.509-.357 453.636.002 383.333.166 351.135 12.225 321.755 32 299.347V96c0-53.019 42.981-96 96-96s96 42.981 96 96v203.347zM208 384c0-34.339-19.37-52.19-32-66.502V96c0-26.467-21.533-48-48-48S80 69.533 80 96v221.498c-12.732 14.428-31.825 32.1-31.999 66.08-.224 43.876 35.563 80.116 79.423 80.42L128 464c44.112 0 80-35.888 80-80z\"],\n    \"thumbs-down\": [512, 512, [], \"f165\", \"M0 56v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V56c0-13.255-10.745-24-24-24H24C10.745 32 0 42.745 0 56zm40 200c0-13.255 10.745-24 24-24s24 10.745 24 24-10.745 24-24 24-24-10.745-24-24zm272 256c-20.183 0-29.485-39.293-33.931-57.795-5.206-21.666-10.589-44.07-25.393-58.902-32.469-32.524-49.503-73.967-89.117-113.111a11.98 11.98 0 0 1-3.558-8.521V59.901c0-6.541 5.243-11.878 11.783-11.998 15.831-.29 36.694-9.079 52.651-16.178C256.189 17.598 295.709.017 343.995 0h2.844c42.777 0 93.363.413 113.774 29.737 8.392 12.057 10.446 27.034 6.148 44.632 16.312 17.053 25.063 48.863 16.382 74.757 17.544 23.432 19.143 56.132 9.308 79.469l.11.11c11.893 11.949 19.523 31.259 19.439 49.197-.156 30.352-26.157 58.098-59.553 58.098H350.723C358.03 364.34 384 388.132 384 430.548 384 504 336 512 312 512z\"],\n    \"thumbs-up\": [512, 512, [], \"f164\", \"M104 224H24c-13.255 0-24 10.745-24 24v240c0 13.255 10.745 24 24 24h80c13.255 0 24-10.745 24-24V248c0-13.255-10.745-24-24-24zM64 472c-13.255 0-24-10.745-24-24s10.745-24 24-24 24 10.745 24 24-10.745 24-24 24zM384 81.452c0 42.416-25.97 66.208-33.277 94.548h101.723c33.397 0 59.397 27.746 59.553 58.098.084 17.938-7.546 37.249-19.439 49.197l-.11.11c9.836 23.337 8.237 56.037-9.308 79.469 8.681 25.895-.069 57.704-16.382 74.757 4.298 17.598 2.244 32.575-6.148 44.632C440.202 511.587 389.616 512 346.839 512l-2.845-.001c-48.287-.017-87.806-17.598-119.56-31.725-15.957-7.099-36.821-15.887-52.651-16.178-6.54-.12-11.783-5.457-11.783-11.998v-213.77c0-3.2 1.282-6.271 3.558-8.521 39.614-39.144 56.648-80.587 89.117-113.111 14.804-14.832 20.188-37.236 25.393-58.902C282.515 39.293 291.817 0 312 0c24 0 72 8 72 81.452z\"],\n    \"thumbtack\": [384, 512, [], \"f08d\", \"M298.028 214.267L285.793 96H328c13.255 0 24-10.745 24-24V24c0-13.255-10.745-24-24-24H56C42.745 0 32 10.745 32 24v48c0 13.255 10.745 24 24 24h42.207L85.972 214.267C37.465 236.82 0 277.261 0 328c0 13.255 10.745 24 24 24h136v104.007c0 1.242.289 2.467.845 3.578l24 48c2.941 5.882 11.364 5.893 14.311 0l24-48a8.008 8.008 0 0 0 .845-3.578V352h136c13.255 0 24-10.745 24-24-.001-51.183-37.983-91.42-85.973-113.733z\"],\n    \"ticket-alt\": [576, 512, [], \"f3ff\", \"M128 160h320v192H128V160zm400 96c0 26.51 21.49 48 48 48v96c0 26.51-21.49 48-48 48H48c-26.51 0-48-21.49-48-48v-96c26.51 0 48-21.49 48-48s-21.49-48-48-48v-96c0-26.51 21.49-48 48-48h480c26.51 0 48 21.49 48 48v96c-26.51 0-48 21.49-48 48zm-48-104c0-13.255-10.745-24-24-24H120c-13.255 0-24 10.745-24 24v208c0 13.255 10.745 24 24 24h336c13.255 0 24-10.745 24-24V152z\"],\n    \"times\": [352, 512, [], \"f00d\", \"M242.72 256l100.07-100.07c12.28-12.28 12.28-32.19 0-44.48l-22.24-22.24c-12.28-12.28-32.19-12.28-44.48 0L176 189.28 75.93 89.21c-12.28-12.28-32.19-12.28-44.48 0L9.21 111.45c-12.28 12.28-12.28 32.19 0 44.48L109.28 256 9.21 356.07c-12.28 12.28-12.28 32.19 0 44.48l22.24 22.24c12.28 12.28 32.2 12.28 44.48 0L176 322.72l100.07 100.07c12.28 12.28 32.2 12.28 44.48 0l22.24-22.24c12.28-12.28 12.28-32.19 0-44.48L242.72 256z\"],\n    \"times-circle\": [512, 512, [], \"f057\", \"M256 8C119 8 8 119 8 256s111 248 248 248 248-111 248-248S393 8 256 8zm121.6 313.1c4.7 4.7 4.7 12.3 0 17L338 377.6c-4.7 4.7-12.3 4.7-17 0L256 312l-65.1 65.6c-4.7 4.7-12.3 4.7-17 0L134.4 338c-4.7-4.7-4.7-12.3 0-17l65.6-65-65.6-65.1c-4.7-4.7-4.7-12.3 0-17l39.6-39.6c4.7-4.7 12.3-4.7 17 0l65 65.7 65.1-65.6c4.7-4.7 12.3-4.7 17 0l39.6 39.6c4.7 4.7 4.7 12.3 0 17L312 256l65.6 65.1z\"],\n    \"tint\": [352, 512, [], \"f043\", \"M205.22 22.09c-7.94-28.78-49.44-30.12-58.44 0C100.01 179.85 0 222.72 0 333.91 0 432.35 78.72 512 176 512s176-79.65 176-178.09c0-111.75-99.79-153.34-146.78-311.82zM176 448c-61.75 0-112-50.25-112-112 0-8.84 7.16-16 16-16s16 7.16 16 16c0 44.11 35.89 80 80 80 8.84 0 16 7.16 16 16s-7.16 16-16 16z\"],\n    \"tint-slash\": [640, 512, [], \"f5c7\", \"M633.82 458.1L494.97 350.78c.52-5.57 1.03-11.16 1.03-16.87 0-111.76-99.79-153.34-146.78-311.82-7.94-28.78-49.44-30.12-58.44 0-15.52 52.34-36.87 91.96-58.49 125.68L45.47 3.37C38.49-2.05 28.43-.8 23.01 6.18L3.37 31.45C-2.05 38.42-.8 48.47 6.18 53.9l588.36 454.73c6.98 5.43 17.03 4.17 22.46-2.81l19.64-25.27c5.41-6.97 4.16-17.02-2.82-22.45zM144 333.91C144 432.35 222.72 512 320 512c44.71 0 85.37-16.96 116.4-44.7L162.72 255.78c-11.41 23.5-18.72 48.35-18.72 78.13z\"],\n    \"tired\": [496, 512, [], \"f5c8\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm33.8 189.7l80-48c11.6-6.9 24 7.7 15.4 18L343.6 208l33.6 40.3c8.7 10.4-3.9 24.8-15.4 18l-80-48c-7.7-4.7-7.7-15.9 0-20.6zm-163-30c-8.6-10.3 3.8-24.9 15.4-18l80 48c7.8 4.7 7.8 15.9 0 20.6l-80 48c-11.5 6.8-24-7.6-15.4-18l33.6-40.3-33.6-40.3zM248 288c51.9 0 115.3 43.8 123.2 106.7 1.7 13.6-8 24.6-17.7 20.4-25.9-11.1-64.4-17.4-105.5-17.4s-79.6 6.3-105.5 17.4c-9.8 4.2-19.4-7-17.7-20.4C132.7 331.8 196.1 288 248 288z\"],\n    \"toggle-off\": [576, 512, [], \"f204\", \"M384 64H192C85.961 64 0 149.961 0 256s85.961 192 192 192h192c106.039 0 192-85.961 192-192S490.039 64 384 64zM64 256c0-70.741 57.249-128 128-128 70.741 0 128 57.249 128 128 0 70.741-57.249 128-128 128-70.741 0-128-57.249-128-128zm320 128h-48.905c65.217-72.858 65.236-183.12 0-256H384c70.741 0 128 57.249 128 128 0 70.74-57.249 128-128 128z\"],\n    \"toggle-on\": [576, 512, [], \"f205\", \"M384 64H192C86 64 0 150 0 256s86 192 192 192h192c106 0 192-86 192-192S490 64 384 64zm0 320c-70.8 0-128-57.3-128-128 0-70.8 57.3-128 128-128 70.8 0 128 57.3 128 128 0 70.8-57.3 128-128 128z\"],\n    \"toilet\": [384, 512, [], \"f7d8\", \"M368 48c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16H16C7.2 0 0 7.2 0 16v16c0 8.8 7.2 16 16 16h16v156.7C11.8 214.8 0 226.9 0 240c0 67.2 34.6 126.2 86.8 160.5l-21.4 70.2C59.1 491.2 74.5 512 96 512h192c21.5 0 36.9-20.8 30.6-41.3l-21.4-70.2C349.4 366.2 384 307.2 384 240c0-13.1-11.8-25.2-32-35.3V48h16zM80 72c0-4.4 3.6-8 8-8h48c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H88c-4.4 0-8-3.6-8-8V72zm112 200c-77.1 0-139.6-14.3-139.6-32s62.5-32 139.6-32 139.6 14.3 139.6 32-62.5 32-139.6 32z\"],\n    \"toilet-paper\": [576, 512, [], \"f71e\", \"M128 0C74.98 0 32 85.96 32 192v172.07c0 41.12-9.8 62.77-31.17 126.87C-2.62 501.3 5.09 512 16.01 512h280.92c13.77 0 26-8.81 30.36-21.88 12.83-38.48 24.71-72.4 24.71-126.05V192c0-83.6 23.67-153.52 60.44-192H128zM96 224c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zm64 0c-8.84 0-16-7.16-16-16s7.16-16 16-16 16 7.16 16 16-7.16 16-16 16zM480 0c-53.02 0-96 85.96-96 192s42.98 192 96 192 96-85.96 96-192S533.02 0 480 0zm0 256c-17.67 0-32-28.65-32-64s14.33-64 32-64 32 28.65 32 64-14.33 64-32 64z\"],\n    \"toolbox\": [512, 512, [], \"f552\", \"M502.63 214.63l-45.25-45.25c-6-6-14.14-9.37-22.63-9.37H384V80c0-26.51-21.49-48-48-48H176c-26.51 0-48 21.49-48 48v80H77.25c-8.49 0-16.62 3.37-22.63 9.37L9.37 214.63c-6 6-9.37 14.14-9.37 22.63V320h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-16c0-8.84 7.16-16 16-16h32c8.84 0 16 7.16 16 16v16h128v-82.75c0-8.48-3.37-16.62-9.37-22.62zM320 160H192V96h128v64zm64 208c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H192v16c0 8.84-7.16 16-16 16h-32c-8.84 0-16-7.16-16-16v-16H0v96c0 17.67 14.33 32 32 32h448c17.67 0 32-14.33 32-32v-96H384v16z\"],\n    \"tools\": [512, 512, [], \"f7d9\", \"M501.1 395.7L384 278.6c-23.1-23.1-57.6-27.6-85.4-13.9L192 158.1V96L64 0 0 64l96 128h62.1l106.6 106.6c-13.6 27.8-9.2 62.3 13.9 85.4l117.1 117.1c14.6 14.6 38.2 14.6 52.7 0l52.7-52.7c14.5-14.6 14.5-38.2 0-52.7zM331.7 225c28.3 0 54.9 11 74.9 31l19.4 19.4c15.8-6.9 30.8-16.5 43.8-29.5 37.1-37.1 49.7-89.3 37.9-136.7-2.2-9-13.5-12.1-20.1-5.5l-74.4 74.4-67.9-11.3L334 98.9l74.4-74.4c6.6-6.6 3.4-17.9-5.7-20.2-47.4-11.7-99.6.9-136.6 37.9-28.5 28.5-41.9 66.1-41.2 103.6l82.1 82.1c8.1-1.9 16.5-2.9 24.7-2.9zm-103.9 82l-56.7-56.7L18.7 402.8c-25 25-25 65.5 0 90.5s65.5 25 90.5 0l123.6-123.6c-7.6-19.9-9.9-41.6-5-62.7zM64 472c-13.2 0-24-10.8-24-24 0-13.3 10.7-24 24-24s24 10.7 24 24c0 13.2-10.7 24-24 24z\"],\n    \"tooth\": [448, 512, [], \"f5c9\", \"M443.98 96.25c-11.01-45.22-47.11-82.06-92.01-93.72-32.19-8.36-63 5.1-89.14 24.33-3.25 2.39-6.96 3.73-10.5 5.48l28.32 18.21c7.42 4.77 9.58 14.67 4.8 22.11-4.46 6.95-14.27 9.86-22.11 4.8L162.83 12.84c-20.7-10.85-43.38-16.4-66.81-10.31-44.9 11.67-81 48.5-92.01 93.72-10.13 41.62-.42 80.81 21.5 110.43 23.36 31.57 32.68 68.66 36.29 107.35 4.4 47.16 10.33 94.16 20.94 140.32l7.8 33.95c3.19 13.87 15.49 23.7 29.67 23.7 13.97 0 26.15-9.55 29.54-23.16l34.47-138.42c4.56-18.32 20.96-31.16 39.76-31.16s35.2 12.85 39.76 31.16l34.47 138.42c3.39 13.61 15.57 23.16 29.54 23.16 14.18 0 26.48-9.83 29.67-23.7l7.8-33.95c10.61-46.15 16.53-93.16 20.94-140.32 3.61-38.7 12.93-75.78 36.29-107.35 21.95-29.61 31.66-68.8 21.53-110.43z\"],\n    \"torah\": [640, 512, [], \"f6a0\", \"M320.05 366.48l17.72-29.64h-35.46zm99.21-166H382.4l18.46 30.82zM48 0C21.49 0 0 14.33 0 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32C96 14.33 74.51 0 48 0zm172.74 311.5h36.85l-18.46-30.82zm161.71 0h36.86l-18.45-30.8zM128 464h384V48H128zm66.77-278.13a21.22 21.22 0 0 1 18.48-10.71h59.45l29.13-48.71a21.13 21.13 0 0 1 18.22-10.37A20.76 20.76 0 0 1 338 126.29l29.25 48.86h59.52a21.12 21.12 0 0 1 18.1 32L415.63 256 445 305a20.69 20.69 0 0 1 .24 21.12 21.25 21.25 0 0 1-18.48 10.72h-59.47l-29.13 48.7a21.13 21.13 0 0 1-18.16 10.4 20.79 20.79 0 0 1-18-10.22l-29.25-48.88h-59.5a21.11 21.11 0 0 1-18.1-32L224.36 256 195 207a20.7 20.7 0 0 1-.23-21.13zM592 0c-26.51 0-48 14.33-48 32v448c0 17.67 21.49 32 48 32s48-14.33 48-32V32c0-17.67-21.49-32-48-32zM320 145.53l-17.78 29.62h35.46zm-62.45 55h-36.81l18.44 30.8zm29.58 111h65.79L386.09 256l-33.23-55.52h-65.79L253.9 256z\"],\n    \"torii-gate\": [512, 512, [], \"f6a1\", \"M376.45 32h-240.9A303.17 303.17 0 0 1 0 0v96c0 17.67 14.33 32 32 32h32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h48v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h256v240c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16V256h48c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16h-48v-64h32c17.67 0 32-14.33 32-32V0a303.17 303.17 0 0 1-135.55 32zM128 128h96v64h-96v-64zm256 64h-96v-64h96v64z\"],\n    \"tractor\": [640, 512, [], \"f722\", \"M528 336c-48.6 0-88 39.4-88 88s39.4 88 88 88 88-39.4 88-88-39.4-88-88-88zm0 112c-13.23 0-24-10.77-24-24s10.77-24 24-24 24 10.77 24 24-10.77 24-24 24zm80-288h-64v-40.2c0-14.12 4.7-27.76 13.15-38.84 4.42-5.8 3.55-14.06-1.32-19.49L534.2 37.3c-6.66-7.45-18.32-6.92-24.7.78C490.58 60.9 480 89.81 480 119.8V160H377.67L321.58 29.14A47.914 47.914 0 0 0 277.45 0H144c-26.47 0-48 21.53-48 48v146.52c-8.63-6.73-20.96-6.46-28.89 1.47L36 227.1c-8.59 8.59-8.59 22.52 0 31.11l5.06 5.06c-4.99 9.26-8.96 18.82-11.91 28.72H22c-12.15 0-22 9.85-22 22v44c0 12.15 9.85 22 22 22h7.14c2.96 9.91 6.92 19.46 11.91 28.73l-5.06 5.06c-8.59 8.59-8.59 22.52 0 31.11L67.1 476c8.59 8.59 22.52 8.59 31.11 0l5.06-5.06c9.26 4.99 18.82 8.96 28.72 11.91V490c0 12.15 9.85 22 22 22h44c12.15 0 22-9.85 22-22v-7.14c9.9-2.95 19.46-6.92 28.72-11.91l5.06 5.06c8.59 8.59 22.52 8.59 31.11 0l31.11-31.11c8.59-8.59 8.59-22.52 0-31.11l-5.06-5.06c4.99-9.26 8.96-18.82 11.91-28.72H330c12.15 0 22-9.85 22-22v-6h80.54c21.91-28.99 56.32-48 95.46-48 18.64 0 36.07 4.61 51.8 12.2l50.82-50.82c6-6 9.37-14.14 9.37-22.63V192c.01-17.67-14.32-32-31.99-32zM176 416c-44.18 0-80-35.82-80-80s35.82-80 80-80 80 35.82 80 80-35.82 80-80 80zm22-256h-38V64h106.89l41.15 96H198z\"],\n    \"trademark\": [640, 512, [], \"f25c\", \"M260.6 96H12c-6.6 0-12 5.4-12 12v43.1c0 6.6 5.4 12 12 12h85.1V404c0 6.6 5.4 12 12 12h54.3c6.6 0 12-5.4 12-12V163.1h85.1c6.6 0 12-5.4 12-12V108c.1-6.6-5.3-12-11.9-12zM640 403l-24-296c-.5-6.2-5.7-11-12-11h-65.4c-5.1 0-9.7 3.3-11.3 8.1l-43.8 127.1c-7.2 20.6-16.1 52.8-16.1 52.8h-.9s-8.9-32.2-16.1-52.8l-43.8-127.1c-1.7-4.8-6.2-8.1-11.3-8.1h-65.4c-6.2 0-11.4 4.8-12 11l-24.4 296c-.6 7 4.9 13 12 13H360c6.3 0 11.5-4.9 12-11.2l9.1-132.9c1.8-24.2 0-53.7 0-53.7h.9s10.7 33.6 17.9 53.7l30.7 84.7c1.7 4.7 6.2 7.9 11.3 7.9h50.3c5.1 0 9.6-3.2 11.3-7.9l30.7-84.7c7.2-20.1 17.9-53.7 17.9-53.7h.9s-1.8 29.5 0 53.7l9.1 132.9c.4 6.3 5.7 11.2 12 11.2H628c7 0 12.5-6 12-13z\"],\n    \"traffic-light\": [384, 512, [], \"f637\", \"M384 192h-64v-37.88c37.2-13.22 64-48.38 64-90.12h-64V32c0-17.67-14.33-32-32-32H96C78.33 0 64 14.33 64 32v32H0c0 41.74 26.8 76.9 64 90.12V192H0c0 41.74 26.8 76.9 64 90.12V320H0c0 42.84 28.25 78.69 66.99 91.05C79.42 468.72 130.6 512 192 512s112.58-43.28 125.01-100.95C355.75 398.69 384 362.84 384 320h-64v-37.88c37.2-13.22 64-48.38 64-90.12zM192 416c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm0-128c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"train\": [448, 512, [], \"f238\", \"M448 96v256c0 51.815-61.624 96-130.022 96l62.98 49.721C386.905 502.417 383.562 512 376 512H72c-7.578 0-10.892-9.594-4.957-14.279L130.022 448C61.82 448 0 403.954 0 352V96C0 42.981 64 0 128 0h192c65 0 128 42.981 128 96zm-48 136V120c0-13.255-10.745-24-24-24H72c-13.255 0-24 10.745-24 24v112c0 13.255 10.745 24 24 24h304c13.255 0 24-10.745 24-24zm-176 64c-30.928 0-56 25.072-56 56s25.072 56 56 56 56-25.072 56-56-25.072-56-56-56z\"],\n    \"tram\": [512, 512, [], \"f7da\", \"M288 64c17.7 0 32-14.3 32-32S305.7 0 288 0s-32 14.3-32 32 14.3 32 32 32zm223.5-12.1c-2.3-8.6-11-13.6-19.6-11.3l-480 128c-8.5 2.3-13.6 11-11.3 19.6C2.5 195.3 8.9 200 16 200c1.4 0 2.8-.2 4.1-.5L240 140.8V224H64c-17.7 0-32 14.3-32 32v224c0 17.7 14.3 32 32 32h384c17.7 0 32-14.3 32-32V256c0-17.7-14.3-32-32-32H272v-91.7l228.1-60.8c8.6-2.3 13.6-11.1 11.4-19.6zM176 384H80v-96h96v96zm160-96h96v96h-96v-96zm-32 0v96h-96v-96h96zM192 96c17.7 0 32-14.3 32-32s-14.3-32-32-32-32 14.3-32 32 14.3 32 32 32z\"],\n    \"transgender\": [384, 512, [], \"f224\", \"M372 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C198.5 104.1 172.2 96 144 96 64.5 96 0 160.5 0 240c0 68.5 47.9 125.9 112 140.4V408H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM144 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"transgender-alt\": [480, 512, [], \"f225\", \"M468 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-80.7 80.7C294.5 104.1 268.2 96 240 96c-28.2 0-54.5 8.1-76.7 22.1l-16.5-16.5 19.8-19.8c4.7-4.7 4.7-12.3 0-17l-28.3-28.3c-4.7-4.7-12.3-4.7-17 0l-19.8 19.8-19-19 16.9-16.9C107.1 12.9 101.7 0 91 0H12C5.4 0 0 5.4 0 12v79c0 10.7 12.9 16 20.5 8.5l16.9-16.9 19 19-19.8 19.8c-4.7 4.7-4.7 12.3 0 17l28.3 28.3c4.7 4.7 12.3 4.7 17 0l19.8-19.8 16.5 16.5C104.1 185.5 96 211.8 96 240c0 68.5 47.9 125.9 112 140.4V408h-36c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v28c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-28h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-27.6c64.1-14.6 112-71.9 112-140.4 0-28.2-8.1-54.5-22.1-76.7l80.7-80.7 16.9 16.9c7.6 7.6 20.5 2.2 20.5-8.5V12c0-6.6-5.4-12-12-12zM240 320c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"trash\": [448, 512, [], \"f1f8\", \"M432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16zM53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32z\"],\n    \"trash-alt\": [448, 512, [], \"f2ed\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm272-256a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zm-96 0a16 16 0 0 1 32 0v224a16 16 0 0 1-32 0zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore\": [448, 512, [], \"f829\", \"M53.2 467a48 48 0 0 0 47.9 45h245.8a48 48 0 0 0 47.9-45L416 128H32zm70.11-175.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"trash-restore-alt\": [448, 512, [], \"f82a\", \"M32 464a48 48 0 0 0 48 48h288a48 48 0 0 0 48-48V128H32zm91.31-172.8l89.38-94.26a15.41 15.41 0 0 1 22.62 0l89.38 94.26c10.08 10.62 2.94 28.8-11.32 28.8H256v112a16 16 0 0 1-16 16h-32a16 16 0 0 1-16-16V320h-57.37c-14.26 0-21.4-18.18-11.32-28.8zM432 32H312l-9.4-18.7A24 24 0 0 0 281.1 0H166.8a23.72 23.72 0 0 0-21.4 13.3L136 32H16A16 16 0 0 0 0 48v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16V48a16 16 0 0 0-16-16z\"],\n    \"tree\": [384, 512, [], \"f1bb\", \"M378.31 378.49L298.42 288h30.63c9.01 0 16.98-5 20.78-13.06 3.8-8.04 2.55-17.26-3.28-24.05L268.42 160h28.89c9.1 0 17.3-5.35 20.86-13.61 3.52-8.13 1.86-17.59-4.24-24.08L203.66 4.83c-6.03-6.45-17.28-6.45-23.32 0L70.06 122.31c-6.1 6.49-7.75 15.95-4.24 24.08C69.38 154.65 77.59 160 86.69 160h28.89l-78.14 90.91c-5.81 6.78-7.06 15.99-3.27 24.04C37.97 283 45.93 288 54.95 288h30.63L5.69 378.49c-6 6.79-7.36 16.09-3.56 24.26 3.75 8.05 12 13.25 21.01 13.25H160v24.45l-30.29 48.4c-5.32 10.64 2.42 23.16 14.31 23.16h95.96c11.89 0 19.63-12.52 14.31-23.16L224 440.45V416h136.86c9.01 0 17.26-5.2 21.01-13.25 3.8-8.17 2.44-17.47-3.56-24.26z\"],\n    \"trophy\": [576, 512, [], \"f091\", \"M552 64H448V24c0-13.3-10.7-24-24-24H152c-13.3 0-24 10.7-24 24v40H24C10.7 64 0 74.7 0 88v56c0 35.7 22.5 72.4 61.9 100.7 31.5 22.7 69.8 37.1 110 41.7C203.3 338.5 240 360 240 360v72h-48c-35.3 0-64 20.7-64 56v12c0 6.6 5.4 12 12 12h296c6.6 0 12-5.4 12-12v-12c0-35.3-28.7-56-64-56h-48v-72s36.7-21.5 68.1-73.6c40.3-4.6 78.6-19 110-41.7 39.3-28.3 61.9-65 61.9-100.7V88c0-13.3-10.7-24-24-24zM99.3 192.8C74.9 175.2 64 155.6 64 144v-16h64.2c1 32.6 5.8 61.2 12.8 86.2-15.1-5.2-29.2-12.4-41.7-21.4zM512 144c0 16.1-17.7 36.1-35.3 48.8-12.5 9-26.7 16.2-41.8 21.4 7-25 11.8-53.6 12.8-86.2H512v16z\"],\n    \"truck\": [640, 512, [], \"f0d1\", \"M624 352h-16V243.9c0-12.7-5.1-24.9-14.1-33.9L494 110.1c-9-9-21.2-14.1-33.9-14.1H416V48c0-26.5-21.5-48-48-48H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h16c0 53 43 96 96 96s96-43 96-96h128c0 53 43 96 96 96s96-43 96-96h48c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM160 464c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm320 0c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48zm80-208H416V144h44.1l99.9 99.9V256z\"],\n    \"truck-loading\": [640, 512, [], \"f4de\", \"M50.2 375.6c2.3 8.5 11.1 13.6 19.6 11.3l216.4-58c8.5-2.3 13.6-11.1 11.3-19.6l-49.7-185.5c-2.3-8.5-11.1-13.6-19.6-11.3L151 133.3l24.8 92.7-61.8 16.5-24.8-92.7-77.3 20.7C3.4 172.8-1.7 181.6.6 190.1l49.6 185.5zM384 0c-17.7 0-32 14.3-32 32v323.6L5.9 450c-4.3 1.2-6.8 5.6-5.6 9.8l12.6 46.3c1.2 4.3 5.6 6.8 9.8 5.6l393.7-107.4C418.8 464.1 467.6 512 528 512c61.9 0 112-50.1 112-112V0H384zm144 448c-26.5 0-48-21.5-48-48s21.5-48 48-48 48 21.5 48 48-21.5 48-48 48z\"],\n    \"truck-monster\": [640, 512, [], \"f63b\", \"M624 224h-16v-64c0-17.67-14.33-32-32-32h-73.6L419.22 24.02A64.025 64.025 0 0 0 369.24 0H256c-17.67 0-32 14.33-32 32v96H48c-8.84 0-16 7.16-16 16v80H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h16.72c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64h65.45c29.21-38.65 75.1-64 127.28-64s98.07 25.35 127.28 64H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zm-336-96V64h81.24l51.2 64H288zm304 224h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 512 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67A110.85 110.85 0 0 0 373.2 352H368c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32c-.02-8.84-7.18-16-16.02-16zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48zm-208-80h-5.2c-2.2-7.33-5.07-14.28-8.65-20.89l3.67-3.67c6.25-6.25 6.25-16.38 0-22.63l-22.63-22.63c-6.25-6.25-16.38-6.25-22.63 0l-3.67 3.67A110.85 110.85 0 0 0 192 277.2V272c0-8.84-7.16-16-16-16h-32c-8.84 0-16 7.16-16 16v5.2c-7.33 2.2-14.28 5.07-20.89 8.65l-3.67-3.67c-6.25-6.25-16.38-6.25-22.63 0L58.18 304.8c-6.25 6.25-6.25 16.38 0 22.63l3.67 3.67a110.85 110.85 0 0 0-8.65 20.89H48c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h5.2c2.2 7.33 5.07 14.28 8.65 20.89l-3.67 3.67c-6.25 6.25-6.25 16.38 0 22.63l22.63 22.63c6.25 6.25 16.38 6.25 22.63 0l3.67-3.67c6.61 3.57 13.57 6.45 20.9 8.65v5.2c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-5.2c7.33-2.2 14.28-5.07 20.9-8.65l3.67 3.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.25-6.25 6.25-16.38 0-22.63l-3.67-3.67a110.85 110.85 0 0 0 8.65-20.89h5.2c8.84 0 16-7.16 16-16v-32C288 359.16 280.84 352 272 352zm-112 80c-26.51 0-48-21.49-48-48s21.49-48 48-48 48 21.49 48 48-21.49 48-48 48z\"],\n    \"truck-moving\": [640, 512, [], \"f4df\", \"M621.3 237.3l-58.5-58.5c-12-12-28.3-18.7-45.3-18.7H480V64c0-17.7-14.3-32-32-32H32C14.3 32 0 46.3 0 64v336c0 44.2 35.8 80 80 80 26.3 0 49.4-12.9 64-32.4 14.6 19.6 37.7 32.4 64 32.4 44.2 0 80-35.8 80-80 0-5.5-.6-10.8-1.6-16h163.2c-1.1 5.2-1.6 10.5-1.6 16 0 44.2 35.8 80 80 80s80-35.8 80-80c0-5.5-.6-10.8-1.6-16H624c8.8 0 16-7.2 16-16v-85.5c0-17-6.7-33.2-18.7-45.2zM80 432c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm128 0c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32zm272-224h37.5c4.3 0 8.3 1.7 11.3 4.7l43.3 43.3H480v-48zm48 224c-17.6 0-32-14.4-32-32s14.4-32 32-32 32 14.4 32 32-14.4 32-32 32z\"],\n    \"truck-pickup\": [640, 512, [], \"f63c\", \"M624 288h-16v-64c0-17.67-14.33-32-32-32h-48L419.22 56.02A64.025 64.025 0 0 0 369.24 32H256c-17.67 0-32 14.33-32 32v128H64c-17.67 0-32 14.33-32 32v64H16c-8.84 0-16 7.16-16 16v32c0 8.84 7.16 16 16 16h49.61c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16h67.23c-.76 5.27-1.61 10.52-1.61 16 0 61.86 50.14 112 112 112s112-50.14 112-112c0-5.48-.85-10.73-1.61-16H624c8.84 0 16-7.16 16-16v-32c0-8.84-7.16-16-16-16zM288 96h81.24l76.8 96H288V96zM176 416c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48zm288 0c-26.47 0-48-21.53-48-48s21.53-48 48-48 48 21.53 48 48-21.53 48-48 48z\"],\n    \"tshirt\": [640, 512, [], \"f553\", \"M631.2 96.5L436.5 0C416.4 27.8 371.9 47.2 320 47.2S223.6 27.8 203.5 0L8.8 96.5c-7.9 4-11.1 13.6-7.2 21.5l57.2 114.5c4 7.9 13.6 11.1 21.5 7.2l56.6-27.7c10.6-5.2 23 2.5 23 14.4V480c0 17.7 14.3 32 32 32h256c17.7 0 32-14.3 32-32V226.3c0-11.8 12.4-19.6 23-14.4l56.6 27.7c7.9 4 17.5.8 21.5-7.2L638.3 118c4-7.9.8-17.6-7.1-21.5z\"],\n    \"tty\": [512, 512, [], \"f1e4\", \"M5.37 103.822c138.532-138.532 362.936-138.326 501.262 0 6.078 6.078 7.074 15.496 2.583 22.681l-43.214 69.138a18.332 18.332 0 0 1-22.356 7.305l-86.422-34.569a18.335 18.335 0 0 1-11.434-18.846L351.741 90c-62.145-22.454-130.636-21.986-191.483 0l5.953 59.532a18.331 18.331 0 0 1-11.434 18.846l-86.423 34.568a18.334 18.334 0 0 1-22.356-7.305L2.787 126.502a18.333 18.333 0 0 1 2.583-22.68zM96 308v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm-336 96v-40c0-6.627-5.373-12-12-12H92c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zM96 500v-40c0-6.627-5.373-12-12-12H44c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12zm288 0v-40c0-6.627-5.373-12-12-12H140c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h232c6.627 0 12-5.373 12-12zm96 0v-40c0-6.627-5.373-12-12-12h-40c-6.627 0-12 5.373-12 12v40c0 6.627 5.373 12 12 12h40c6.627 0 12-5.373 12-12z\"],\n    \"tv\": [640, 512, [], \"f26c\", \"M592 0H48C21.5 0 0 21.5 0 48v320c0 26.5 21.5 48 48 48h245.1v32h-160c-17.7 0-32 14.3-32 32s14.3 32 32 32h384c17.7 0 32-14.3 32-32s-14.3-32-32-32h-160v-32H592c26.5 0 48-21.5 48-48V48c0-26.5-21.5-48-48-48zm-16 352H64V64h512v288z\"],\n    \"umbrella\": [576, 512, [], \"f0e9\", \"M575.7 280.8C547.1 144.5 437.3 62.6 320 49.9V32c0-17.7-14.3-32-32-32s-32 14.3-32 32v17.9C138.3 62.6 29.5 144.5.3 280.8c-2.2 10.1 8.5 21.3 18.7 11.4 52-55 107.7-52.4 158.6 37 5.3 9.5 14.9 8.6 19.7 0 20.2-35.4 44.9-73.2 90.7-73.2 58.5 0 88.2 68.8 90.7 73.2 4.8 8.6 14.4 9.5 19.7 0 51-89.5 107.1-91.4 158.6-37 10.3 10 20.9-1.3 18.7-11.4zM256 301.7V432c0 8.8-7.2 16-16 16-7.8 0-13.2-5.3-15.1-10.7-5.9-16.7-24.1-25.4-40.8-19.5-16.7 5.9-25.4 24.2-19.5 40.8 11.2 31.9 41.6 53.3 75.4 53.3 44.1 0 80-35.9 80-80V301.6c-9.1-7.9-19.8-13.6-32-13.6-12.3.1-22.4 4.8-32 13.7z\"],\n    \"umbrella-beach\": [640, 512, [], \"f5ca\", \"M115.38 136.9l102.11 37.18c35.19-81.54 86.21-144.29 139-173.7-95.88-4.89-188.78 36.96-248.53 111.8-6.69 8.4-2.66 21.05 7.42 24.72zm132.25 48.16l238.48 86.83c35.76-121.38 18.7-231.66-42.63-253.98-7.4-2.7-15.13-4-23.09-4-58.02.01-128.27 69.17-172.76 171.15zM521.48 60.5c6.22 16.3 10.83 34.6 13.2 55.19 5.74 49.89-1.42 108.23-18.95 166.98l102.62 37.36c10.09 3.67 21.31-3.43 21.57-14.17 2.32-95.69-41.91-187.44-118.44-245.36zM560 447.98H321.06L386 269.5l-60.14-21.9-72.9 200.37H16c-8.84 0-16 7.16-16 16.01v32.01C0 504.83 7.16 512 16 512h544c8.84 0 16-7.17 16-16.01v-32.01c0-8.84-7.16-16-16-16z\"],\n    \"underline\": [448, 512, [], \"f0cd\", \"M32 64h32v160c0 88.22 71.78 160 160 160s160-71.78 160-160V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H272a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h32v160a80 80 0 0 1-160 0V64h32a16 16 0 0 0 16-16V16a16 16 0 0 0-16-16H32a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16zm400 384H16a16 16 0 0 0-16 16v32a16 16 0 0 0 16 16h416a16 16 0 0 0 16-16v-32a16 16 0 0 0-16-16z\"],\n    \"undo\": [512, 512, [], \"f0e2\", \"M212.333 224.333H12c-6.627 0-12-5.373-12-12V12C0 5.373 5.373 0 12 0h48c6.627 0 12 5.373 12 12v78.112C117.773 39.279 184.26 7.47 258.175 8.007c136.906.994 246.448 111.623 246.157 248.532C504.041 393.258 393.12 504 256.333 504c-64.089 0-122.496-24.313-166.51-64.215-5.099-4.622-5.334-12.554-.467-17.42l33.967-33.967c4.474-4.474 11.662-4.717 16.401-.525C170.76 415.336 211.58 432 256.333 432c97.268 0 176-78.716 176-176 0-97.267-78.716-176-176-176-58.496 0-110.28 28.476-142.274 72.333h98.274c6.627 0 12 5.373 12 12v48c0 6.627-5.373 12-12 12z\"],\n    \"undo-alt\": [512, 512, [], \"f2ea\", \"M255.545 8c-66.269.119-126.438 26.233-170.86 68.685L48.971 40.971C33.851 25.851 8 36.559 8 57.941V192c0 13.255 10.745 24 24 24h134.059c21.382 0 32.09-25.851 16.971-40.971l-41.75-41.75c30.864-28.899 70.801-44.907 113.23-45.273 92.398-.798 170.283 73.977 169.484 169.442C423.236 348.009 349.816 424 256 424c-41.127 0-79.997-14.678-110.63-41.556-4.743-4.161-11.906-3.908-16.368.553L89.34 422.659c-4.872 4.872-4.631 12.815.482 17.433C133.798 479.813 192.074 504 256 504c136.966 0 247.999-111.033 248-247.998C504.001 119.193 392.354 7.755 255.545 8z\"],\n    \"universal-access\": [512, 512, [], \"f29a\", \"M256 48c114.953 0 208 93.029 208 208 0 114.953-93.029 208-208 208-114.953 0-208-93.029-208-208 0-114.953 93.029-208 208-208m0-40C119.033 8 8 119.033 8 256s111.033 248 248 248 248-111.033 248-248S392.967 8 256 8zm0 56C149.961 64 64 149.961 64 256s85.961 192 192 192 192-85.961 192-192S362.039 64 256 64zm0 44c19.882 0 36 16.118 36 36s-16.118 36-36 36-36-16.118-36-36 16.118-36 36-36zm117.741 98.023c-28.712 6.779-55.511 12.748-82.14 15.807.851 101.023 12.306 123.052 25.037 155.621 3.617 9.26-.957 19.698-10.217 23.315-9.261 3.617-19.699-.957-23.316-10.217-8.705-22.308-17.086-40.636-22.261-78.549h-9.686c-5.167 37.851-13.534 56.208-22.262 78.549-3.615 9.255-14.05 13.836-23.315 10.217-9.26-3.617-13.834-14.056-10.217-23.315 12.713-32.541 24.185-54.541 25.037-155.621-26.629-3.058-53.428-9.027-82.141-15.807-8.6-2.031-13.926-10.648-11.895-19.249s10.647-13.926 19.249-11.895c96.686 22.829 124.283 22.783 220.775 0 8.599-2.03 17.218 3.294 19.249 11.895 2.029 8.601-3.297 17.219-11.897 19.249z\"],\n    \"university\": [512, 512, [], \"f19c\", \"M496 128v16a8 8 0 0 1-8 8h-24v12c0 6.627-5.373 12-12 12H60c-6.627 0-12-5.373-12-12v-12H24a8 8 0 0 1-8-8v-16a8 8 0 0 1 4.941-7.392l232-88a7.996 7.996 0 0 1 6.118 0l232 88A8 8 0 0 1 496 128zm-24 304H40c-13.255 0-24 10.745-24 24v16a8 8 0 0 0 8 8h464a8 8 0 0 0 8-8v-16c0-13.255-10.745-24-24-24zM96 192v192H60c-6.627 0-12 5.373-12 12v20h416v-20c0-6.627-5.373-12-12-12h-36V192h-64v192h-64V192h-64v192h-64V192H96z\"],\n    \"unlink\": [512, 512, [], \"f127\", \"M304.083 405.907c4.686 4.686 4.686 12.284 0 16.971l-44.674 44.674c-59.263 59.262-155.693 59.266-214.961 0-59.264-59.265-59.264-155.696 0-214.96l44.675-44.675c4.686-4.686 12.284-4.686 16.971 0l39.598 39.598c4.686 4.686 4.686 12.284 0 16.971l-44.675 44.674c-28.072 28.073-28.072 73.75 0 101.823 28.072 28.072 73.75 28.073 101.824 0l44.674-44.674c4.686-4.686 12.284-4.686 16.971 0l39.597 39.598zm-56.568-260.216c4.686 4.686 12.284 4.686 16.971 0l44.674-44.674c28.072-28.075 73.75-28.073 101.824 0 28.072 28.073 28.072 73.75 0 101.823l-44.675 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.598 39.598c4.686 4.686 12.284 4.686 16.971 0l44.675-44.675c59.265-59.265 59.265-155.695 0-214.96-59.266-59.264-155.695-59.264-214.961 0l-44.674 44.674c-4.686 4.686-4.686 12.284 0 16.971l39.597 39.598zm234.828 359.28l22.627-22.627c9.373-9.373 9.373-24.569 0-33.941L63.598 7.029c-9.373-9.373-24.569-9.373-33.941 0L7.029 29.657c-9.373 9.373-9.373 24.569 0 33.941l441.373 441.373c9.373 9.372 24.569 9.372 33.941 0z\"],\n    \"unlock\": [448, 512, [], \"f09c\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48z\"],\n    \"unlock-alt\": [448, 512, [], \"f13e\", \"M400 256H152V152.9c0-39.6 31.7-72.5 71.3-72.9 40-.4 72.7 32.1 72.7 72v16c0 13.3 10.7 24 24 24h32c13.3 0 24-10.7 24-24v-16C376 68 307.5-.3 223.5 0 139.5.3 72 69.5 72 153.5V256H48c-26.5 0-48 21.5-48 48v160c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48V304c0-26.5-21.5-48-48-48zM264 408c0 22.1-17.9 40-40 40s-40-17.9-40-40v-48c0-22.1 17.9-40 40-40s40 17.9 40 40v48z\"],\n    \"upload\": [512, 512, [], \"f093\", \"M296 384h-80c-13.3 0-24-10.7-24-24V192h-87.7c-17.8 0-26.7-21.5-14.1-34.1L242.3 5.7c7.5-7.5 19.8-7.5 27.3 0l152.2 152.2c12.6 12.6 3.7 34.1-14.1 34.1H320v168c0 13.3-10.7 24-24 24zm216-8v112c0 13.3-10.7 24-24 24H24c-13.3 0-24-10.7-24-24V376c0-13.3 10.7-24 24-24h136v8c0 30.9 25.1 56 56 56h80c30.9 0 56-25.1 56-56v-8h136c13.3 0 24 10.7 24 24zm-124 88c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20zm64 0c0-11-9-20-20-20s-20 9-20 20 9 20 20 20 20-9 20-20z\"],\n    \"user\": [448, 512, [], \"f007\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-alt\": [512, 512, [], \"f406\", \"M256 288c79.5 0 144-64.5 144-144S335.5 0 256 0 112 64.5 112 144s64.5 144 144 144zm128 32h-55.1c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16H128C57.3 320 0 377.3 0 448v16c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-16c0-70.7-57.3-128-128-128z\"],\n    \"user-alt-slash\": [640, 512, [], \"f4fa\", \"M633.8 458.1L389.6 269.3C433.8 244.7 464 198.1 464 144 464 64.5 399.5 0 320 0c-67.1 0-123 46.1-139 108.2L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM198.4 320C124.2 320 64 380.2 64 454.4v9.6c0 26.5 21.5 48 48 48h382.2L245.8 320h-47.4z\"],\n    \"user-astronaut\": [448, 512, [], \"f4fb\", \"M64 224h13.5c24.7 56.5 80.9 96 146.5 96s121.8-39.5 146.5-96H384c8.8 0 16-7.2 16-16v-96c0-8.8-7.2-16-16-16h-13.5C345.8 39.5 289.6 0 224 0S102.2 39.5 77.5 96H64c-8.8 0-16 7.2-16 16v96c0 8.8 7.2 16 16 16zm40-88c0-22.1 21.5-40 48-40h144c26.5 0 48 17.9 48 40v24c0 53-43 96-96 96h-48c-53 0-96-43-96-96v-24zm72 72l12-36 36-12-36-12-12-36-12 36-36 12 36 12 12 36zm151.6 113.4C297.7 340.7 262.2 352 224 352s-73.7-11.3-103.6-30.6C52.9 328.5 0 385 0 454.4v9.6c0 26.5 21.5 48 48 48h80v-64c0-17.7 14.3-32 32-32h128c17.7 0 32 14.3 32 32v64h80c26.5 0 48-21.5 48-48v-9.6c0-69.4-52.9-125.9-120.4-133zM272 448c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm-96 0c-8.8 0-16 7.2-16 16v48h32v-48c0-8.8-7.2-16-16-16z\"],\n    \"user-check\": [640, 512, [], \"f4fc\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4zm323-128.4l-27.8-28.1c-4.6-4.7-12.1-4.7-16.8-.1l-104.8 104-45.5-45.8c-4.6-4.7-12.1-4.7-16.8-.1l-28.1 27.9c-4.7 4.6-4.7 12.1-.1 16.8l81.7 82.3c4.6 4.7 12.1 4.7 16.8.1l141.3-140.2c4.6-4.7 4.7-12.2.1-16.8z\"],\n    \"user-circle\": [496, 512, [], \"f2bd\", \"M248 8C111 8 0 119 0 256s111 248 248 248 248-111 248-248S385 8 248 8zm0 96c48.6 0 88 39.4 88 88s-39.4 88-88 88-88-39.4-88-88 39.4-88 88-88zm0 344c-58.7 0-111.3-26.6-146.5-68.2 18.8-35.4 55.6-59.8 98.5-59.8 2.4 0 4.8.4 7.1 1.1 13 4.2 26.6 6.9 40.9 6.9 14.3 0 28-2.7 40.9-6.9 2.3-.7 4.7-1.1 7.1-1.1 42.9 0 79.7 24.4 98.5 59.8C359.3 421.4 306.7 448 248 448z\"],\n    \"user-clock\": [640, 512, [], \"f4fd\", \"M496 224c-79.6 0-144 64.4-144 144s64.4 144 144 144 144-64.4 144-144-64.4-144-144-144zm64 150.3c0 5.3-4.4 9.7-9.7 9.7h-60.6c-5.3 0-9.7-4.4-9.7-9.7v-76.6c0-5.3 4.4-9.7 9.7-9.7h12.6c5.3 0 9.7 4.4 9.7 9.7V352h38.3c5.3 0 9.7 4.4 9.7 9.7v12.6zM320 368c0-27.8 6.7-54.1 18.2-77.5-8-1.5-16.2-2.5-24.6-2.5h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h347.1c-45.3-31.9-75.1-84.5-75.1-144zm-96-112c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128z\"],\n    \"user-cog\": [640, 512, [], \"f4fe\", \"M610.5 373.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 400.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm201.2 226.5c-2.3-1.2-4.6-2.6-6.8-3.9l-7.9 4.6c-6 3.4-12.8 5.3-19.6 5.3-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-5.5-17.7 1.9-36.4 17.9-45.7l7.9-4.6c-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-16-9.2-23.4-28-17.9-45.7.9-2.9 2.2-5.8 3.2-8.7-3.8-.3-7.5-1.2-11.4-1.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c10.1 0 19.5-3.2 27.2-8.5-1.2-3.8-2-7.7-2-11.8v-9.2z\"],\n    \"user-edit\": [640, 512, [], \"f4ff\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h274.9c-2.4-6.8-3.4-14-2.6-21.3l6.8-60.9 1.2-11.1 7.9-7.9 77.3-77.3c-24.5-27.7-60-45.5-99.9-45.5zm45.3 145.3l-6.8 61c-1.1 10.2 7.5 18.8 17.6 17.6l60.9-6.8 137.9-137.9-71.7-71.7-137.9 137.8zM633 268.9L595.1 231c-9.3-9.3-24.5-9.3-33.8 0l-37.8 37.8-4.1 4.1 71.8 71.7 41.8-41.8c9.3-9.4 9.3-24.5 0-33.9z\"],\n    \"user-friends\": [640, 512, [], \"f500\", \"M192 256c61.9 0 112-50.1 112-112S253.9 32 192 32 80 82.1 80 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C51.6 288 0 339.6 0 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zM480 256c53 0 96-43 96-96s-43-96-96-96-96 43-96 96 43 96 96 96zm48 32h-3.8c-13.9 4.8-28.6 8-44.2 8s-30.3-3.2-44.2-8H432c-20.4 0-39.2 5.9-55.7 15.4 24.4 26.3 39.7 61.2 39.7 99.8v38.4c0 2.2-.5 4.3-.6 6.4H592c26.5 0 48-21.5 48-48 0-61.9-50.1-112-112-112z\"],\n    \"user-graduate\": [448, 512, [], \"f501\", \"M319.4 320.6L224 416l-95.4-95.4C57.1 323.7 0 382.2 0 454.4v9.6c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-9.6c0-72.2-57.1-130.7-128.6-133.8zM13.6 79.8l6.4 1.5v58.4c-7 4.2-12 11.5-12 20.3 0 8.4 4.6 15.4 11.1 19.7L3.5 242c-1.7 6.9 2.1 14 7.6 14h41.8c5.5 0 9.3-7.1 7.6-14l-15.6-62.3C51.4 175.4 56 168.4 56 160c0-8.8-5-16.1-12-20.3V87.1l66 15.9c-8.6 17.2-14 36.4-14 57 0 70.7 57.3 128 128 128s128-57.3 128-128c0-20.6-5.3-39.8-14-57l96.3-23.2c18.2-4.4 18.2-27.1 0-31.5l-190.4-46c-13-3.1-26.7-3.1-39.7 0L13.6 48.2c-18.1 4.4-18.1 27.2 0 31.6z\"],\n    \"user-injured\": [448, 512, [], \"f728\", \"M277.37 11.98C261.08 4.47 243.11 0 224 0c-53.69 0-99.5 33.13-118.51 80h81.19l90.69-68.02zM342.51 80c-7.9-19.47-20.67-36.2-36.49-49.52L239.99 80h102.52zM224 256c70.69 0 128-57.31 128-128 0-5.48-.95-10.7-1.61-16H97.61c-.67 5.3-1.61 10.52-1.61 16 0 70.69 57.31 128 128 128zM80 299.7V512h128.26l-98.45-221.52A132.835 132.835 0 0 0 80 299.7zM0 464c0 26.51 21.49 48 48 48V320.24C18.88 344.89 0 381.26 0 422.4V464zm256-48h-55.38l42.67 96H256c26.47 0 48-21.53 48-48s-21.53-48-48-48zm57.6-128h-16.71c-22.24 10.18-46.88 16-72.89 16s-50.65-5.82-72.89-16h-7.37l42.67 96H256c44.11 0 80 35.89 80 80 0 18.08-6.26 34.59-16.41 48H400c26.51 0 48-21.49 48-48v-41.6c0-74.23-60.17-134.4-134.4-134.4z\"],\n    \"user-lock\": [640, 512, [], \"f502\", \"M224 256A128 128 0 1 0 96 128a128 128 0 0 0 128 128zm96 64a63.08 63.08 0 0 1 8.1-30.5c-4.8-.5-9.5-1.5-14.5-1.5h-16.7a174.08 174.08 0 0 1-145.8 0h-16.7A134.43 134.43 0 0 0 0 422.4V464a48 48 0 0 0 48 48h280.9a63.54 63.54 0 0 1-8.9-32zm288-32h-32v-80a80 80 0 0 0-160 0v80h-32a32 32 0 0 0-32 32v160a32 32 0 0 0 32 32h224a32 32 0 0 0 32-32V320a32 32 0 0 0-32-32zM496 432a32 32 0 1 1 32-32 32 32 0 0 1-32 32zm32-144h-64v-80a32 32 0 0 1 64 0z\"],\n    \"user-md\": [448, 512, [], \"f0f0\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zM104 424c0 13.3 10.7 24 24 24s24-10.7 24-24-10.7-24-24-24-24 10.7-24 24zm216-135.4v49c36.5 7.4 64 39.8 64 78.4v41.7c0 7.6-5.4 14.2-12.9 15.7l-32.2 6.4c-4.3.9-8.5-1.9-9.4-6.3l-3.1-15.7c-.9-4.3 1.9-8.6 6.3-9.4l19.3-3.9V416c0-62.8-96-65.1-96 1.9v26.7l19.3 3.9c4.3.9 7.1 5.1 6.3 9.4l-3.1 15.7c-.9 4.3-5.1 7.1-9.4 6.3l-31.2-4.2c-7.9-1.1-13.8-7.8-13.8-15.9V416c0-38.6 27.5-70.9 64-78.4v-45.2c-2.2.7-4.4 1.1-6.6 1.9-18 6.3-37.3 9.8-57.4 9.8s-39.4-3.5-57.4-9.8c-7.4-2.6-14.9-4.2-22.6-5.2v81.6c23.1 6.9 40 28.1 40 53.4 0 30.9-25.1 56-56 56s-56-25.1-56-56c0-25.3 16.9-46.5 40-53.4v-80.4C48.5 301 0 355.8 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-72-56.8-130.3-128-133.8z\"],\n    \"user-minus\": [640, 512, [], \"f503\", \"M624 208H432c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h192c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-ninja\": [448, 512, [], \"f504\", \"M325.4 289.2L224 390.6 122.6 289.2C54 295.3 0 352.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-70.2-54-127.1-122.6-133.2zM32 192c27.3 0 51.8-11.5 69.2-29.7 15.1 53.9 64 93.7 122.8 93.7 70.7 0 128-57.3 128-128S294.7 0 224 0c-50.4 0-93.6 29.4-114.5 71.8C92.1 47.8 64 32 32 32c0 33.4 17.1 62.8 43.1 80-26 17.2-43.1 46.6-43.1 80zm144-96h96c17.7 0 32 14.3 32 32H144c0-17.7 14.3-32 32-32z\"],\n    \"user-nurse\": [448, 512, [], \"f82f\", \"M57.78 288h82.36c22.51 19.68 51.62 32 83.86 32s61.35-12.32 83.86-32h82.36a16 16 0 0 0 14.28-23.18c-15.23-29.85-31.28-62.23-42.15-95.54C354.78 146.09 352 121.59 352 97.2V48L224 0 96 48v49.2c0 24.39-2.75 48.89-10.33 72.08C74.78 202.59 58.73 235 43.5 264.82A16 16 0 0 0 57.78 288zM184 71.67a5 5 0 0 1 5-5h21.67V45a5 5 0 0 1 5-5h16.66a5 5 0 0 1 5 5v21.67H259a5 5 0 0 1 5 5v16.66a5 5 0 0 1-5 5h-21.67V115a5 5 0 0 1-5 5h-16.66a5 5 0 0 1-5-5V93.33H189a5 5 0 0 1-5-5zM144 160h160v32a80 80 0 0 1-160 0zm175.41 160L224 415.39 128.59 320C57.1 323.1 0 381.6 0 453.79A58.21 58.21 0 0 0 58.21 512h331.58A58.21 58.21 0 0 0 448 453.79C448 381.6 390.9 323.1 319.41 320z\"],\n    \"user-plus\": [640, 512, [], \"f234\", \"M624 208h-64v-64c0-8.8-7.2-16-16-16h-32c-8.8 0-16 7.2-16 16v64h-64c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h64v64c0 8.8 7.2 16 16 16h32c8.8 0 16-7.2 16-16v-64h64c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zm-400 48c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"user-secret\": [448, 512, [], \"f21b\", \"M383.9 308.3l23.9-62.6c4-10.5-3.7-21.7-15-21.7h-58.5c11-18.9 17.8-40.6 17.8-64v-.3c39.2-7.8 64-19.1 64-31.7 0-13.3-27.3-25.1-70.1-33-9.2-32.8-27-65.8-40.6-82.8-9.5-11.9-25.9-15.6-39.5-8.8l-27.6 13.8c-9 4.5-19.6 4.5-28.6 0L182.1 3.4c-13.6-6.8-30-3.1-39.5 8.8-13.5 17-31.4 50-40.6 82.8-42.7 7.9-70 19.7-70 33 0 12.6 24.8 23.9 64 31.7v.3c0 23.4 6.8 45.1 17.8 64H56.3c-11.5 0-19.2 11.7-14.7 22.3l25.8 60.2C27.3 329.8 0 372.7 0 422.4v44.8C0 491.9 20.1 512 44.8 512h358.4c24.7 0 44.8-20.1 44.8-44.8v-44.8c0-48.4-25.8-90.4-64.1-114.1zM176 480l-41.6-192 49.6 32 24 40-32 120zm96 0l-32-120 24-40 49.6-32L272 480zm41.7-298.5c-3.9 11.9-7 24.6-16.5 33.4-10.1 9.3-48 22.4-64-25-2.8-8.4-15.4-8.4-18.3 0-17 50.2-56 32.4-64 25-9.5-8.8-12.7-21.5-16.5-33.4-.8-2.5-6.3-5.7-6.3-5.8v-10.8c28.3 3.6 61 5.8 96 5.8s67.7-2.1 96-5.8v10.8c-.1.1-5.6 3.2-6.4 5.8z\"],\n    \"user-shield\": [640, 512, [], \"f505\", \"M622.3 271.1l-115.2-45c-4.1-1.6-12.6-3.7-22.2 0l-115.2 45c-10.7 4.2-17.7 14-17.7 24.9 0 111.6 68.7 188.8 132.9 213.9 9.6 3.7 18 1.6 22.2 0C558.4 489.9 640 420.5 640 296c0-10.9-7-20.7-17.7-24.9zM496 462.4V273.3l95.5 37.3c-5.6 87.1-60.9 135.4-95.5 151.8zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm96 40c0-2.5.8-4.8 1.1-7.2-2.5-.1-4.9-.8-7.5-.8h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c6.8 0 13.3-1.5 19.2-4-54-42.9-99.2-116.7-99.2-212z\"],\n    \"user-slash\": [640, 512, [], \"f506\", \"M633.8 458.1L362.3 248.3C412.1 230.7 448 183.8 448 128 448 57.3 390.7 0 320 0c-67.1 0-121.5 51.8-126.9 117.4L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4l588.4 454.7c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.4-6.8 4.1-16.9-2.9-22.3zM96 422.4V464c0 26.5 21.5 48 48 48h350.2L207.4 290.3C144.2 301.3 96 356 96 422.4z\"],\n    \"user-tag\": [640, 512, [], \"f507\", \"M630.6 364.9l-90.3-90.2c-12-12-28.3-18.7-45.3-18.7h-79.3c-17.7 0-32 14.3-32 32v79.2c0 17 6.7 33.2 18.7 45.2l90.3 90.2c12.5 12.5 32.8 12.5 45.3 0l92.5-92.5c12.6-12.5 12.6-32.7.1-45.2zm-182.8-21c-13.3 0-24-10.7-24-24s10.7-24 24-24 24 10.7 24 24c0 13.2-10.7 24-24 24zm-223.8-88c70.7 0 128-57.3 128-128C352 57.3 294.7 0 224 0S96 57.3 96 128c0 70.6 57.3 127.9 128 127.9zm127.8 111.2V294c-12.2-3.6-24.9-6.2-38.2-6.2h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 287.9 0 348.1 0 422.3v41.6c0 26.5 21.5 48 48 48h352c15.5 0 29.1-7.5 37.9-18.9l-58-58c-18.1-18.1-28.1-42.2-28.1-67.9z\"],\n    \"user-tie\": [448, 512, [], \"f508\", \"M224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm95.8 32.6L272 480l-32-136 32-56h-96l32 56-32 136-47.8-191.4C56.9 292 0 350.3 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-72.1-56.9-130.4-128.2-133.8z\"],\n    \"user-times\": [640, 512, [], \"f235\", \"M589.6 240l45.6-45.6c6.3-6.3 6.3-16.5 0-22.8l-22.8-22.8c-6.3-6.3-16.5-6.3-22.8 0L544 194.4l-45.6-45.6c-6.3-6.3-16.5-6.3-22.8 0l-22.8 22.8c-6.3 6.3-6.3 16.5 0 22.8l45.6 45.6-45.6 45.6c-6.3 6.3-6.3 16.5 0 22.8l22.8 22.8c6.3 6.3 16.5 6.3 22.8 0l45.6-45.6 45.6 45.6c6.3 6.3 16.5 6.3 22.8 0l22.8-22.8c6.3-6.3 6.3-16.5 0-22.8L589.6 240zM224 256c70.7 0 128-57.3 128-128S294.7 0 224 0 96 57.3 96 128s57.3 128 128 128zm89.6 32h-16.7c-22.2 10.2-46.9 16-72.9 16s-50.6-5.8-72.9-16h-16.7C60.2 288 0 348.2 0 422.4V464c0 26.5 21.5 48 48 48h352c26.5 0 48-21.5 48-48v-41.6c0-74.2-60.2-134.4-134.4-134.4z\"],\n    \"users\": [640, 512, [], \"f0c0\", \"M96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm448 0c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm32 32h-64c-17.6 0-33.5 7.1-45.1 18.6 40.3 22.1 68.9 62 75.1 109.4h66c17.7 0 32-14.3 32-32v-32c0-35.3-28.7-64-64-64zm-256 0c61.9 0 112-50.1 112-112S381.9 32 320 32 208 82.1 208 144s50.1 112 112 112zm76.8 32h-8.3c-20.8 10-43.9 16-68.5 16s-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h288c26.5 0 48-21.5 48-48v-28.8c0-63.6-51.6-115.2-115.2-115.2zm-223.7-13.4C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"users-cog\": [640, 512, [], \"f509\", \"M610.5 341.3c2.6-14.1 2.6-28.5 0-42.6l25.8-14.9c3-1.7 4.3-5.2 3.3-8.5-6.7-21.6-18.2-41.2-33.2-57.4-2.3-2.5-6-3.1-9-1.4l-25.8 14.9c-10.9-9.3-23.4-16.5-36.9-21.3v-29.8c0-3.4-2.4-6.4-5.7-7.1-22.3-5-45-4.8-66.2 0-3.3.7-5.7 3.7-5.7 7.1v29.8c-13.5 4.8-26 12-36.9 21.3l-25.8-14.9c-2.9-1.7-6.7-1.1-9 1.4-15 16.2-26.5 35.8-33.2 57.4-1 3.3.4 6.8 3.3 8.5l25.8 14.9c-2.6 14.1-2.6 28.5 0 42.6l-25.8 14.9c-3 1.7-4.3 5.2-3.3 8.5 6.7 21.6 18.2 41.1 33.2 57.4 2.3 2.5 6 3.1 9 1.4l25.8-14.9c10.9 9.3 23.4 16.5 36.9 21.3v29.8c0 3.4 2.4 6.4 5.7 7.1 22.3 5 45 4.8 66.2 0 3.3-.7 5.7-3.7 5.7-7.1v-29.8c13.5-4.8 26-12 36.9-21.3l25.8 14.9c2.9 1.7 6.7 1.1 9-1.4 15-16.2 26.5-35.8 33.2-57.4 1-3.3-.4-6.8-3.3-8.5l-25.8-14.9zM496 368.5c-26.8 0-48.5-21.8-48.5-48.5s21.8-48.5 48.5-48.5 48.5 21.8 48.5 48.5-21.7 48.5-48.5 48.5zM96 224c35.3 0 64-28.7 64-64s-28.7-64-64-64-64 28.7-64 64 28.7 64 64 64zm224 32c1.9 0 3.7-.5 5.6-.6 8.3-21.7 20.5-42.1 36.3-59.2 7.4-8 17.9-12.6 28.9-12.6 6.9 0 13.7 1.8 19.6 5.3l7.9 4.6c.8-.5 1.6-.9 2.4-1.4 7-14.6 11.2-30.8 11.2-48 0-61.9-50.1-112-112-112S208 82.1 208 144c0 61.9 50.1 112 112 112zm105.2 194.5c-2.3-1.2-4.6-2.6-6.8-3.9-8.2 4.8-15.3 9.8-27.5 9.8-10.9 0-21.4-4.6-28.9-12.6-18.3-19.8-32.3-43.9-40.2-69.6-10.7-34.5 24.9-49.7 25.8-50.3-.1-2.6-.1-5.2 0-7.8l-7.9-4.6c-3.8-2.2-7-5-9.8-8.1-3.3.2-6.5.6-9.8.6-24.6 0-47.6-6-68.5-16h-8.3C179.6 288 128 339.6 128 403.2V432c0 26.5 21.5 48 48 48h255.4c-3.7-6-6.2-12.8-6.2-20.3v-9.2zM173.1 274.6C161.5 263.1 145.6 256 128 256H64c-35.3 0-64 28.7-64 64v32c0 17.7 14.3 32 32 32h65.9c6.3-47.4 34.9-87.3 75.2-109.4z\"],\n    \"utensil-spoon\": [512, 512, [], \"f2e5\", \"M480.1 31.9c-55-55.1-164.9-34.5-227.8 28.5-49.3 49.3-55.1 110-28.8 160.4L9 413.2c-11.6 10.5-12.1 28.5-1 39.5L59.3 504c11 11 29.1 10.5 39.5-1.1l192.4-214.4c50.4 26.3 111.1 20.5 160.4-28.8 63-62.9 83.6-172.8 28.5-227.8z\"],\n    \"utensils\": [416, 512, [], \"f2e7\", \"M207.9 15.2c.8 4.7 16.1 94.5 16.1 128.8 0 52.3-27.8 89.6-68.9 104.6L168 486.7c.7 13.7-10.2 25.3-24 25.3H80c-13.7 0-24.7-11.5-24-25.3l12.9-238.1C27.7 233.6 0 196.2 0 144 0 109.6 15.3 19.9 16.1 15.2 19.3-5.1 61.4-5.4 64 16.3v141.2c1.3 3.4 15.1 3.2 16 0 1.4-25.3 7.9-139.2 8-141.8 3.3-20.8 44.7-20.8 47.9 0 .2 2.7 6.6 116.5 8 141.8.9 3.2 14.8 3.4 16 0V16.3c2.6-21.6 44.8-21.4 48-1.1zm119.2 285.7l-15 185.1c-1.2 14 9.9 26 23.9 26h56c13.3 0 24-10.7 24-24V24c0-13.2-10.7-24-24-24-82.5 0-221.4 178.5-64.9 300.9z\"],\n    \"vector-square\": [512, 512, [], \"f5cb\", \"M512 128V32c0-17.67-14.33-32-32-32h-96c-17.67 0-32 14.33-32 32H160c0-17.67-14.33-32-32-32H32C14.33 0 0 14.33 0 32v96c0 17.67 14.33 32 32 32v192c-17.67 0-32 14.33-32 32v96c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32h192c0 17.67 14.33 32 32 32h96c17.67 0 32-14.33 32-32v-96c0-17.67-14.33-32-32-32V160c17.67 0 32-14.33 32-32zm-96-64h32v32h-32V64zM64 64h32v32H64V64zm32 384H64v-32h32v32zm352 0h-32v-32h32v32zm-32-96h-32c-17.67 0-32 14.33-32 32v32H160v-32c0-17.67-14.33-32-32-32H96V160h32c17.67 0 32-14.33 32-32V96h192v32c0 17.67 14.33 32 32 32h32v192z\"],\n    \"venus\": [288, 512, [], \"f221\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80z\"],\n    \"venus-double\": [512, 512, [], \"f226\", \"M288 176c0-79.5-64.5-144-144-144S0 96.5 0 176c0 68.5 47.9 125.9 112 140.4V368H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.5 112-71.9 112-140.4zm-224 0c0-44.1 35.9-80 80-80s80 35.9 80 80-35.9 80-80 80-80-35.9-80-80zm336 140.4V368h36c6.6 0 12 5.4 12 12v40c0 6.6-5.4 12-12 12h-36v36c0 6.6-5.4 12-12 12h-40c-6.6 0-12-5.4-12-12v-36h-36c-6.6 0-12-5.4-12-12v-40c0-6.6 5.4-12 12-12h36v-51.6c-21.2-4.8-40.6-14.3-57.2-27.3 14-16.7 25-36 32.1-57.1 14.5 14.8 34.7 24 57.1 24 44.1 0 80-35.9 80-80s-35.9-80-80-80c-22.3 0-42.6 9.2-57.1 24-7.1-21.1-18-40.4-32.1-57.1C303.4 43.6 334.3 32 368 32c79.5 0 144 64.5 144 144 0 68.5-47.9 125.9-112 140.4z\"],\n    \"venus-mars\": [576, 512, [], \"f228\", \"M564 0h-79c-10.7 0-16 12.9-8.5 20.5l16.9 16.9-48.7 48.7C422.5 72.1 396.2 64 368 64c-33.7 0-64.6 11.6-89.2 30.9 14 16.7 25 36 32.1 57.1 14.5-14.8 34.7-24 57.1-24 44.1 0 80 35.9 80 80s-35.9 80-80 80c-22.3 0-42.6-9.2-57.1-24-7.1 21.1-18 40.4-32.1 57.1 24.5 19.4 55.5 30.9 89.2 30.9 79.5 0 144-64.5 144-144 0-28.2-8.1-54.5-22.1-76.7l48.7-48.7 16.9 16.9c2.4 2.4 5.4 3.5 8.4 3.5 6.2 0 12.1-4.8 12.1-12V12c0-6.6-5.4-12-12-12zM144 64C64.5 64 0 128.5 0 208c0 68.5 47.9 125.9 112 140.4V400H76c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h36v36c0 6.6 5.4 12 12 12h40c6.6 0 12-5.4 12-12v-36h36c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-36v-51.6c64.1-14.6 112-71.9 112-140.4 0-79.5-64.5-144-144-144zm0 224c-44.1 0-80-35.9-80-80s35.9-80 80-80 80 35.9 80 80-35.9 80-80 80z\"],\n    \"vial\": [480, 512, [], \"f492\", \"M477.7 186.1L309.5 18.3c-3.1-3.1-8.2-3.1-11.3 0l-34 33.9c-3.1 3.1-3.1 8.2 0 11.3l11.2 11.1L33 316.5c-38.8 38.7-45.1 102-9.4 143.5 20.6 24 49.5 36 78.4 35.9 26.4 0 52.8-10 72.9-30.1l246.3-245.7 11.2 11.1c3.1 3.1 8.2 3.1 11.3 0l34-33.9c3.1-3 3.1-8.1 0-11.2zM318 256H161l148-147.7 78.5 78.3L318 256z\"],\n    \"vials\": [640, 512, [], \"f493\", \"M72 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H72c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64zm480 384H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM360 64h24v240c0 44.1 35.9 80 80 80s80-35.9 80-80V64h24c4.4 0 8-3.6 8-8V8c0-4.4-3.6-8-8-8H360c-4.4 0-8 3.6-8 8v48c0 4.4 3.6 8 8 8zm72 0h64v96h-64V64z\"],\n    \"video\": [576, 512, [], \"f03d\", \"M336.2 64H47.8C21.4 64 0 85.4 0 111.8v288.4C0 426.6 21.4 448 47.8 448h288.4c26.4 0 47.8-21.4 47.8-47.8V111.8c0-26.4-21.4-47.8-47.8-47.8zm189.4 37.7L416 177.3v157.4l109.6 75.5c21.2 14.6 50.4-.3 50.4-25.8V127.5c0-25.4-29.1-40.4-50.4-25.8z\"],\n    \"video-slash\": [640, 512, [], \"f4e2\", \"M633.8 458.1l-55-42.5c15.4-1.4 29.2-13.7 29.2-31.1v-257c0-25.5-29.1-40.4-50.4-25.8L448 177.3v137.2l-32-24.7v-178c0-26.4-21.4-47.8-47.8-47.8H123.9L45.5 3.4C38.5-2 28.5-.8 23 6.2L3.4 31.4c-5.4 7-4.2 17 2.8 22.4L42.7 82 416 370.6l178.5 138c7 5.4 17 4.2 22.5-2.8l19.6-25.3c5.5-6.9 4.2-17-2.8-22.4zM32 400.2c0 26.4 21.4 47.8 47.8 47.8h288.4c11.2 0 21.4-4 29.6-10.5L32 154.7v245.5z\"],\n    \"vihara\": [640, 512, [], \"f6a7\", \"M632.88 400.71L544 352v-64l55.16-17.69c11.79-5.9 11.79-22.72 0-28.62L480 192v-64l27.31-16.3c7.72-7.72 5.61-20.74-4.16-25.62L320 0 136.85 86.07c-9.77 4.88-11.88 17.9-4.16 25.62L160 128v64L40.84 241.69c-11.79 5.9-11.79 22.72 0 28.62L96 288v64L7.12 400.71c-5.42 3.62-7.7 9.63-7 15.29.62 5.01 3.57 9.75 8.72 12.33L64 448v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48h160v48c0 8.84 7.16 16 16 16h32c8.84 0 16-7.16 16-16v-48l55.15-19.67c5.16-2.58 8.1-7.32 8.72-12.33.71-5.67-1.57-11.68-6.99-15.29zM224 128h192v64H224v-64zm-64 224v-64h320v64H160z\"],\n    \"voicemail\": [640, 512, [], \"f897\", \"M496 128a144 144 0 0 0-119.74 224H263.74A144 144 0 1 0 144 416h352a144 144 0 0 0 0-288zM64 272a80 80 0 1 1 80 80 80 80 0 0 1-80-80zm432 80a80 80 0 1 1 80-80 80 80 0 0 1-80 80z\"],\n    \"volleyball-ball\": [512, 512, [], \"f45f\", \"M231.39 243.48a285.56 285.56 0 0 0-22.7-105.7c-90.8 42.4-157.5 122.4-180.3 216.8a249 249 0 0 0 56.9 81.1 333.87 333.87 0 0 1 146.1-192.2zm-36.9-134.4a284.23 284.23 0 0 0-57.4-70.7c-91 49.8-144.8 152.9-125 262.2 33.4-83.1 98.4-152 182.4-191.5zm187.6 165.1c8.6-99.8-27.3-197.5-97.5-264.4-14.7-1.7-51.6-5.5-98.9 8.5A333.87 333.87 0 0 1 279.19 241a285 285 0 0 0 102.9 33.18zm-124.7 9.5a286.33 286.33 0 0 0-80.2 72.6c82 57.3 184.5 75.1 277.5 47.8a247.15 247.15 0 0 0 42.2-89.9 336.1 336.1 0 0 1-80.9 10.4c-54.6-.1-108.9-14.1-158.6-40.9zm-98.3 99.7c-15.2 26-25.7 54.4-32.1 84.2a247.07 247.07 0 0 0 289-22.1c-112.9 16.1-203.3-24.8-256.9-62.1zm180.3-360.6c55.3 70.4 82.5 161.2 74.6 253.6a286.59 286.59 0 0 0 89.7-14.2c0-2 .3-4 .3-6 0-107.8-68.7-199.1-164.6-233.4z\"],\n    \"volume-down\": [384, 512, [], \"f027\", \"M215.03 72.04L126.06 161H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V89.02c0-21.47-25.96-31.98-40.97-16.98zm123.2 108.08c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 229.28 336 242.62 336 257c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.87z\"],\n    \"volume-mute\": [512, 512, [], \"f6a9\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zM461.64 256l45.64-45.64c6.3-6.3 6.3-16.52 0-22.82l-22.82-22.82c-6.3-6.3-16.52-6.3-22.82 0L416 210.36l-45.64-45.64c-6.3-6.3-16.52-6.3-22.82 0l-22.82 22.82c-6.3 6.3-6.3 16.52 0 22.82L370.36 256l-45.63 45.63c-6.3 6.3-6.3 16.52 0 22.82l22.82 22.82c6.3 6.3 16.52 6.3 22.82 0L416 301.64l45.64 45.64c6.3 6.3 16.52 6.3 22.82 0l22.82-22.82c6.3-6.3 6.3-16.52 0-22.82L461.64 256z\"],\n    \"volume-off\": [256, 512, [], \"f026\", \"M215 71l-89 89H24a24 24 0 0 0-24 24v144a24 24 0 0 0 24 24h102.06L215 441c15 15 41 4.47 41-17V88c0-21.47-26-32-41-17z\"],\n    \"volume-up\": [576, 512, [], \"f028\", \"M215.03 71.05L126.06 160H24c-13.26 0-24 10.74-24 24v144c0 13.25 10.74 24 24 24h102.06l88.97 88.95c15.03 15.03 40.97 4.47 40.97-16.97V88.02c0-21.46-25.96-31.98-40.97-16.97zm233.32-51.08c-11.17-7.33-26.18-4.24-33.51 6.95-7.34 11.17-4.22 26.18 6.95 33.51 66.27 43.49 105.82 116.6 105.82 195.58 0 78.98-39.55 152.09-105.82 195.58-11.17 7.32-14.29 22.34-6.95 33.5 7.04 10.71 21.93 14.56 33.51 6.95C528.27 439.58 576 351.33 576 256S528.27 72.43 448.35 19.97zM480 256c0-63.53-32.06-121.94-85.77-156.24-11.19-7.14-26.03-3.82-33.12 7.46s-3.78 26.21 7.41 33.36C408.27 165.97 432 209.11 432 256s-23.73 90.03-63.48 115.42c-11.19 7.14-14.5 22.07-7.41 33.36 6.51 10.36 21.12 15.14 33.12 7.46C447.94 377.94 480 319.54 480 256zm-141.77-76.87c-11.58-6.33-26.19-2.16-32.61 9.45-6.39 11.61-2.16 26.2 9.45 32.61C327.98 228.28 336 241.63 336 256c0 14.38-8.02 27.72-20.92 34.81-11.61 6.41-15.84 21-9.45 32.61 6.43 11.66 21.05 15.8 32.61 9.45 28.23-15.55 45.77-45 45.77-76.88s-17.54-61.32-45.78-76.86z\"],\n    \"vote-yea\": [640, 512, [], \"f772\", \"M608 320h-64v64h22.4c5.3 0 9.6 3.6 9.6 8v16c0 4.4-4.3 8-9.6 8H73.6c-5.3 0-9.6-3.6-9.6-8v-16c0-4.4 4.3-8 9.6-8H96v-64H32c-17.7 0-32 14.3-32 32v96c0 17.7 14.3 32 32 32h576c17.7 0 32-14.3 32-32v-96c0-17.7-14.3-32-32-32zm-96 64V64.3c0-17.9-14.5-32.3-32.3-32.3H160.4C142.5 32 128 46.5 128 64.3V384h384zM211.2 202l25.5-25.3c4.2-4.2 11-4.2 15.2.1l41.3 41.6 95.2-94.4c4.2-4.2 11-4.2 15.2.1l25.3 25.5c4.2 4.2 4.2 11-.1 15.2L300.5 292c-4.2 4.2-11 4.2-15.2-.1l-74.1-74.7c-4.3-4.2-4.2-11 0-15.2z\"],\n    \"vr-cardboard\": [640, 512, [], \"f729\", \"M608 64H32C14.33 64 0 78.33 0 96v320c0 17.67 14.33 32 32 32h160.22c25.19 0 48.03-14.77 58.36-37.74l27.74-61.64C286.21 331.08 302.35 320 320 320s33.79 11.08 41.68 28.62l27.74 61.64C399.75 433.23 422.6 448 447.78 448H608c17.67 0 32-14.33 32-32V96c0-17.67-14.33-32-32-32zM160 304c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64zm320 0c-35.35 0-64-28.65-64-64s28.65-64 64-64 64 28.65 64 64-28.65 64-64 64z\"],\n    \"walking\": [320, 512, [], \"f554\", \"M208 96c26.5 0 48-21.5 48-48S234.5 0 208 0s-48 21.5-48 48 21.5 48 48 48zm94.5 149.1l-23.3-11.8-9.7-29.4c-14.7-44.6-55.7-75.8-102.2-75.9-36-.1-55.9 10.1-93.3 25.2-21.6 8.7-39.3 25.2-49.7 46.2L17.6 213c-7.8 15.8-1.5 35 14.2 42.9 15.6 7.9 34.6 1.5 42.5-14.3L81 228c3.5-7 9.3-12.5 16.5-15.4l26.8-10.8-15.2 60.7c-5.2 20.8.4 42.9 14.9 58.8l59.9 65.4c7.2 7.9 12.3 17.4 14.9 27.7l18.3 73.3c4.3 17.1 21.7 27.6 38.8 23.3 17.1-4.3 27.6-21.7 23.3-38.8l-22.2-89c-2.6-10.3-7.7-19.9-14.9-27.7l-45.5-49.7 17.2-68.7 5.5 16.5c5.3 16.1 16.7 29.4 31.7 37l23.3 11.8c15.6 7.9 34.6 1.5 42.5-14.3 7.7-15.7 1.4-35.1-14.3-43zM73.6 385.8c-3.2 8.1-8 15.4-14.2 21.5l-50 50.1c-12.5 12.5-12.5 32.8 0 45.3s32.7 12.5 45.2 0l59.4-59.4c6.1-6.1 10.9-13.4 14.2-21.5l13.5-33.8c-55.3-60.3-38.7-41.8-47.4-53.7l-20.7 51.5z\"],\n    \"wallet\": [512, 512, [], \"f555\", \"M461.2 128H80c-8.84 0-16-7.16-16-16s7.16-16 16-16h384c8.84 0 16-7.16 16-16 0-26.51-21.49-48-48-48H64C28.65 32 0 60.65 0 96v320c0 35.35 28.65 64 64 64h397.2c28.02 0 50.8-21.53 50.8-48V176c0-26.47-22.78-48-50.8-48zM416 336c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32z\"],\n    \"warehouse\": [640, 512, [], \"f494\", \"M504 352H136.4c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0 96H136.1c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8h368c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm0-192H136.6c-4.4 0-8 3.6-8 8l-.1 48c0 4.4 3.6 8 8 8H504c4.4 0 8-3.6 8-8v-48c0-4.4-3.6-8-8-8zm106.5-139L338.4 3.7a48.15 48.15 0 0 0-36.9 0L29.5 117C11.7 124.5 0 141.9 0 161.3V504c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V256c0-17.6 14.6-32 32.6-32h382.8c18 0 32.6 14.4 32.6 32v248c0 4.4 3.6 8 8 8h80c4.4 0 8-3.6 8-8V161.3c0-19.4-11.7-36.8-29.5-44.3z\"],\n    \"water\": [576, 512, [], \"f773\", \"M562.1 383.9c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144c-21.5-2.4-42.1-10.5-57.9-22.9-14.1-11.1-34.2-11.3-48.2 0-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3zm0-144C540.6 93.4 520 85.4 504.2 73 490.1 61.9 470 61.7 456 73c-37.9 30.4-107.2 30.4-145.7-1.5-13.5-11.2-33-9.1-46.7 1.8-38 30.1-106.9 30-145.2-1.7-13.5-11.2-33.3-8.9-47.1 2-15.5 12.2-36 20.1-57.7 22.4-7.9.8-13.6 7.8-13.6 15.7v32.2c0 9.1 7.6 16.8 16.7 16 28.8-2.5 56.1-11.4 79.4-25.9 56.5 34.6 137 34.1 192 0 56.5 34.6 137 34.1 192 0 23.3 14.2 50.9 23.3 79.1 25.8 9.1.8 16.7-6.9 16.7-16v-31.6c.1-8-5.7-15.4-13.8-16.3z\"],\n    \"wave-square\": [640, 512, [], \"f83e\", \"M476 480H324a36 36 0 0 1-36-36V96h-96v156a36 36 0 0 1-36 36H16a16 16 0 0 1-16-16v-32a16 16 0 0 1 16-16h112V68a36 36 0 0 1 36-36h152a36 36 0 0 1 36 36v348h96V260a36 36 0 0 1 36-36h140a16 16 0 0 1 16 16v32a16 16 0 0 1-16 16H512v156a36 36 0 0 1-36 36z\"],\n    \"weight\": [512, 512, [], \"f496\", \"M448 64h-25.98C438.44 92.28 448 125.01 448 160c0 105.87-86.13 192-192 192S64 265.87 64 160c0-34.99 9.56-67.72 25.98-96H64C28.71 64 0 92.71 0 128v320c0 35.29 28.71 64 64 64h384c35.29 0 64-28.71 64-64V128c0-35.29-28.71-64-64-64zM256 320c88.37 0 160-71.63 160-160S344.37 0 256 0 96 71.63 96 160s71.63 160 160 160zm-.3-151.94l33.58-78.36c3.5-8.17 12.94-11.92 21.03-8.41 8.12 3.48 11.88 12.89 8.41 21l-33.67 78.55C291.73 188 296 197.45 296 208c0 22.09-17.91 40-40 40s-40-17.91-40-40c0-21.98 17.76-39.77 39.7-39.94z\"],\n    \"weight-hanging\": [512, 512, [], \"f5cd\", \"M510.28 445.86l-73.03-292.13c-3.8-15.19-16.44-25.72-30.87-25.72h-60.25c3.57-10.05 5.88-20.72 5.88-32 0-53.02-42.98-96-96-96s-96 42.98-96 96c0 11.28 2.3 21.95 5.88 32h-60.25c-14.43 0-27.08 10.54-30.87 25.72L1.72 445.86C-6.61 479.17 16.38 512 48.03 512h415.95c31.64 0 54.63-32.83 46.3-66.14zM256 128c-17.64 0-32-14.36-32-32s14.36-32 32-32 32 14.36 32 32-14.36 32-32 32z\"],\n    \"wheelchair\": [512, 512, [], \"f193\", \"M496.101 385.669l14.227 28.663c3.929 7.915.697 17.516-7.218 21.445l-65.465 32.886c-16.049 7.967-35.556 1.194-43.189-15.055L331.679 320H192c-15.925 0-29.426-11.71-31.679-27.475C126.433 55.308 128.38 70.044 128 64c0-36.358 30.318-65.635 67.052-63.929 33.271 1.545 60.048 28.905 60.925 62.201.868 32.933-23.152 60.423-54.608 65.039l4.67 32.69H336c8.837 0 16 7.163 16 16v32c0 8.837-7.163 16-16 16H215.182l4.572 32H352a32 32 0 0 1 28.962 18.392L438.477 396.8l36.178-18.349c7.915-3.929 17.517-.697 21.446 7.218zM311.358 352h-24.506c-7.788 54.204-54.528 96-110.852 96-61.757 0-112-50.243-112-112 0-41.505 22.694-77.809 56.324-97.156-3.712-25.965-6.844-47.86-9.488-66.333C45.956 198.464 0 261.963 0 336c0 97.047 78.953 176 176 176 71.87 0 133.806-43.308 161.11-105.192L311.358 352z\"],\n    \"wifi\": [640, 512, [], \"f1eb\", \"M634.91 154.88C457.74-8.99 182.19-8.93 5.09 154.88c-6.66 6.16-6.79 16.59-.35 22.98l34.24 33.97c6.14 6.1 16.02 6.23 22.4.38 145.92-133.68 371.3-133.71 517.25 0 6.38 5.85 16.26 5.71 22.4-.38l34.24-33.97c6.43-6.39 6.3-16.82-.36-22.98zM320 352c-35.35 0-64 28.65-64 64s28.65 64 64 64 64-28.65 64-64-28.65-64-64-64zm202.67-83.59c-115.26-101.93-290.21-101.82-405.34 0-6.9 6.1-7.12 16.69-.57 23.15l34.44 33.99c6 5.92 15.66 6.32 22.05.8 83.95-72.57 209.74-72.41 293.49 0 6.39 5.52 16.05 5.13 22.05-.8l34.44-33.99c6.56-6.46 6.33-17.06-.56-23.15z\"],\n    \"wind\": [512, 512, [], \"f72e\", \"M156.7 256H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h142.2c15.9 0 30.8 10.9 33.4 26.6 3.3 20-12.1 37.4-31.6 37.4-14.1 0-26.1-9.2-30.4-21.9-2.1-6.3-8.6-10.1-15.2-10.1H81.6c-9.8 0-17.7 8.8-15.9 18.4 8.6 44.1 47.6 77.6 94.2 77.6 57.1 0 102.7-50.1 95.2-108.6C249 291 205.4 256 156.7 256zM16 224h336c59.7 0 106.8-54.8 93.8-116.7-7.6-36.2-36.9-65.5-73.1-73.1-55.4-11.6-105.1 24.9-114.9 75.5-1.9 9.6 6.1 18.3 15.8 18.3h32.8c6.7 0 13.1-3.8 15.2-10.1C325.9 105.2 337.9 96 352 96c19.4 0 34.9 17.4 31.6 37.4-2.6 15.7-17.4 26.6-33.4 26.6H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16zm384 32H243.7c19.3 16.6 33.2 38.8 39.8 64H400c26.5 0 48 21.5 48 48s-21.5 48-48 48c-17.9 0-33.3-9.9-41.6-24.4-2.9-5-8.7-7.6-14.5-7.6h-33.8c-10.9 0-19 10.8-15.3 21.1 17.8 50.6 70.5 84.8 129.4 72.3 41.2-8.7 75.1-41.6 84.7-82.7C526 321.5 470.5 256 400 256z\"],\n    \"window-close\": [512, 512, [], \"f410\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-83.6 290.5c4.8 4.8 4.8 12.6 0 17.4l-40.5 40.5c-4.8 4.8-12.6 4.8-17.4 0L256 313.3l-66.5 67.1c-4.8 4.8-12.6 4.8-17.4 0l-40.5-40.5c-4.8-4.8-4.8-12.6 0-17.4l67.1-66.5-67.1-66.5c-4.8-4.8-4.8-12.6 0-17.4l40.5-40.5c4.8-4.8 12.6-4.8 17.4 0l66.5 67.1 66.5-67.1c4.8-4.8 12.6-4.8 17.4 0l40.5 40.5c4.8 4.8 4.8 12.6 0 17.4L313.3 256l67.1 66.5z\"],\n    \"window-maximize\": [512, 512, [], \"f2d0\", \"M464 32H48C21.5 32 0 53.5 0 80v352c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48V80c0-26.5-21.5-48-48-48zm-16 160H64v-84c0-6.6 5.4-12 12-12h360c6.6 0 12 5.4 12 12v84z\"],\n    \"window-minimize\": [512, 512, [], \"f2d1\", \"M464 352H48c-26.5 0-48 21.5-48 48v32c0 26.5 21.5 48 48 48h416c26.5 0 48-21.5 48-48v-32c0-26.5-21.5-48-48-48z\"],\n    \"window-restore\": [512, 512, [], \"f2d2\", \"M512 48v288c0 26.5-21.5 48-48 48h-48V176c0-44.1-35.9-80-80-80H128V48c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zM384 176v288c0 26.5-21.5 48-48 48H48c-26.5 0-48-21.5-48-48V176c0-26.5 21.5-48 48-48h288c26.5 0 48 21.5 48 48zm-68 28c0-6.6-5.4-12-12-12H76c-6.6 0-12 5.4-12 12v52h252v-52z\"],\n    \"wine-bottle\": [512, 512, [], \"f72f\", \"M507.31 72.57L439.43 4.69c-6.25-6.25-16.38-6.25-22.63 0l-22.63 22.63c-6.25 6.25-6.25 16.38 0 22.63l-76.67 76.67c-46.58-19.7-102.4-10.73-140.37 27.23L18.75 312.23c-24.99 24.99-24.99 65.52 0 90.51l90.51 90.51c24.99 24.99 65.52 24.99 90.51 0l158.39-158.39c37.96-37.96 46.93-93.79 27.23-140.37l76.67-76.67c6.25 6.25 16.38 6.25 22.63 0l22.63-22.63c6.24-6.24 6.24-16.37-.01-22.62zM179.22 423.29l-90.51-90.51 122.04-122.04 90.51 90.51-122.04 122.04z\"],\n    \"wine-glass\": [288, 512, [], \"f4e3\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40z\"],\n    \"wine-glass-alt\": [288, 512, [], \"f5ce\", \"M216 464h-40V346.81c68.47-15.89 118.05-79.91 111.4-154.16l-15.95-178.1C270.71 6.31 263.9 0 255.74 0H32.26c-8.15 0-14.97 6.31-15.7 14.55L.6 192.66C-6.05 266.91 43.53 330.93 112 346.82V464H72c-22.09 0-40 17.91-40 40 0 4.42 3.58 8 8 8h208c4.42 0 8-3.58 8-8 0-22.09-17.91-40-40-40zM61.75 48h164.5l7.17 80H54.58l7.17-80z\"],\n    \"won-sign\": [576, 512, [], \"f159\", \"M564 192c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-48l18.6-80.6c1.7-7.5-4-14.7-11.7-14.7h-46.1c-5.7 0-10.6 4-11.7 9.5L450.7 128H340.8l-19.7-86c-1.3-5.5-6.1-9.3-11.7-9.3h-44c-5.6 0-10.4 3.8-11.7 9.3l-20 86H125l-17.5-85.7c-1.1-5.6-6.1-9.6-11.8-9.6H53.6c-7.7 0-13.4 7.1-11.7 14.6L60 128H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h62.3l7.2 32H12c-6.6 0-12 5.4-12 12v40c0 6.6 5.4 12 12 12h83.9l40.9 182.6c1.2 5.5 6.1 9.4 11.7 9.4h56.8c5.6 0 10.4-3.9 11.7-9.3L259.3 288h55.1l42.4 182.7c1.3 5.4 6.1 9.3 11.7 9.3h56.8c5.6 0 10.4-3.9 11.7-9.3L479.1 288H564c6.6 0 12-5.4 12-12v-40c0-6.6-5.4-12-12-12h-70.1l7.4-32zM183.8 342c-6.2 25.8-6.8 47.2-7.3 47.2h-1.1s-1.7-22-6.8-47.2l-11-54h38.8zm27.5-118h-66.8l-6.5-32h80.8zm62.9 0l2-8.6c1.9-8 3.5-16 4.8-23.4h11.8c1.3 7.4 2.9 15.4 4.8 23.4l2 8.6zm130.9 118c-5.1 25.2-6.8 47.2-6.8 47.2h-1.1c-.6 0-1.1-21.4-7.3-47.2l-12.4-54h39.1zm25.2-118h-67.4l-7.3-32h81.6z\"],\n    \"wrench\": [512, 512, [], \"f0ad\", \"M507.73 109.1c-2.24-9.03-13.54-12.09-20.12-5.51l-74.36 74.36-67.88-11.31-11.31-67.88 74.36-74.36c6.62-6.62 3.43-17.9-5.66-20.16-47.38-11.74-99.55.91-136.58 37.93-39.64 39.64-50.55 97.1-34.05 147.2L18.74 402.76c-24.99 24.99-24.99 65.51 0 90.5 24.99 24.99 65.51 24.99 90.5 0l213.21-213.21c50.12 16.71 107.47 5.68 147.37-34.22 37.07-37.07 49.7-89.32 37.91-136.73zM64 472c-13.25 0-24-10.75-24-24 0-13.26 10.75-24 24-24s24 10.74 24 24c0 13.25-10.75 24-24 24z\"],\n    \"x-ray\": [640, 512, [], \"f497\", \"M240 384c-8.8 0-16 7.2-16 16s7.2 16 16 16 16-7.2 16-16-7.2-16-16-16zm160 32c8.8 0 16-7.2 16-16s-7.2-16-16-16-16 7.2-16 16 7.2 16 16 16zM624 0H16C7.2 0 0 7.2 0 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16V16c0-8.8-7.2-16-16-16zm0 448h-48V96H64v352H16c-8.8 0-16 7.2-16 16v32c0 8.8 7.2 16 16 16h608c8.8 0 16-7.2 16-16v-32c0-8.8-7.2-16-16-16zM480 248c0 4.4-3.6 8-8 8H336v32h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h64c26.5 0 48 21.5 48 48s-21.5 48-48 48-48-21.5-48-48v-16h-64v16c0 26.5-21.5 48-48 48s-48-21.5-48-48 21.5-48 48-48h64v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-32H168c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h136v-32H200c-4.4 0-8-3.6-8-8v-16c0-4.4 3.6-8 8-8h104v-24c0-4.4 3.6-8 8-8h16c4.4 0 8 3.6 8 8v24h104c4.4 0 8 3.6 8 8v16c0 4.4-3.6 8-8 8H336v32h136c4.4 0 8 3.6 8 8v16z\"],\n    \"yen-sign\": [384, 512, [], \"f157\", \"M351.2 32h-65.3c-4.6 0-8.8 2.6-10.8 6.7l-55.4 113.2c-14.5 34.7-27.1 71.9-27.1 71.9h-1.3s-12.6-37.2-27.1-71.9L108.8 38.7c-2-4.1-6.2-6.7-10.8-6.7H32.8c-9.1 0-14.8 9.7-10.6 17.6L102.3 200H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h88.2l19.8 37.2V320H44c-6.6 0-12 5.4-12 12v32c0 6.6 5.4 12 12 12h108v92c0 6.6 5.4 12 12 12h56c6.6 0 12-5.4 12-12v-92h108c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12H232v-26.8l19.8-37.2H340c6.6 0 12-5.4 12-12v-32c0-6.6-5.4-12-12-12h-58.3l80.1-150.4c4.3-7.9-1.5-17.6-10.6-17.6z\"],\n    \"yin-yang\": [496, 512, [], \"f6ad\", \"M248 8C111.03 8 0 119.03 0 256s111.03 248 248 248 248-111.03 248-248S384.97 8 248 8zm0 376c-17.67 0-32-14.33-32-32s14.33-32 32-32 32 14.33 32 32-14.33 32-32 32zm0-128c-53.02 0-96 42.98-96 96s42.98 96 96 96c-106.04 0-192-85.96-192-192S141.96 64 248 64c53.02 0 96 42.98 96 96s-42.98 96-96 96zm0-128c-17.67 0-32 14.33-32 32s14.33 32 32 32 32-14.33 32-32-14.33-32-32-32z\"]\n  };\n\n  bunker(function () {\n    defineIcons('fas', icons);\n  });\n\n}());\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/js/v4-shims.js",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n(function (global, factory) {\n  typeof exports === 'object' && typeof module !== 'undefined' ? module.exports = factory() :\n  typeof define === 'function' && define.amd ? define(factory) :\n  (global['fontawesome-free-shims'] = factory());\n}(this, (function () { 'use strict';\n\n  var _WINDOW = {};\n  var _DOCUMENT = {};\n\n  try {\n    if (typeof window !== 'undefined') _WINDOW = window;\n    if (typeof document !== 'undefined') _DOCUMENT = document;\n  } catch (e) {}\n\n  var _ref = _WINDOW.navigator || {},\n      _ref$userAgent = _ref.userAgent,\n      userAgent = _ref$userAgent === void 0 ? '' : _ref$userAgent;\n\n  var WINDOW = _WINDOW;\n  var DOCUMENT = _DOCUMENT;\n  var IS_BROWSER = !!WINDOW.document;\n  var IS_DOM = !!DOCUMENT.documentElement && !!DOCUMENT.head && typeof DOCUMENT.addEventListener === 'function' && typeof DOCUMENT.createElement === 'function';\n  var IS_IE = ~userAgent.indexOf('MSIE') || ~userAgent.indexOf('Trident/');\n\n  var NAMESPACE_IDENTIFIER = '___FONT_AWESOME___';\n  var PRODUCTION = function () {\n    try {\n      return process.env.NODE_ENV === 'production';\n    } catch (e) {\n      return false;\n    }\n  }();\n\n  function bunker(fn) {\n    try {\n      fn();\n    } catch (e) {\n      if (!PRODUCTION) {\n        throw e;\n      }\n    }\n  }\n\n  var w = WINDOW || {};\n  if (!w[NAMESPACE_IDENTIFIER]) w[NAMESPACE_IDENTIFIER] = {};\n  if (!w[NAMESPACE_IDENTIFIER].styles) w[NAMESPACE_IDENTIFIER].styles = {};\n  if (!w[NAMESPACE_IDENTIFIER].hooks) w[NAMESPACE_IDENTIFIER].hooks = {};\n  if (!w[NAMESPACE_IDENTIFIER].shims) w[NAMESPACE_IDENTIFIER].shims = [];\n  var namespace = w[NAMESPACE_IDENTIFIER];\n\n  var shims = [[\"glass\", null, \"glass-martini\"], [\"meetup\", \"fab\", null], [\"star-o\", \"far\", \"star\"], [\"remove\", null, \"times\"], [\"close\", null, \"times\"], [\"gear\", null, \"cog\"], [\"trash-o\", \"far\", \"trash-alt\"], [\"file-o\", \"far\", \"file\"], [\"clock-o\", \"far\", \"clock\"], [\"arrow-circle-o-down\", \"far\", \"arrow-alt-circle-down\"], [\"arrow-circle-o-up\", \"far\", \"arrow-alt-circle-up\"], [\"play-circle-o\", \"far\", \"play-circle\"], [\"repeat\", null, \"redo\"], [\"rotate-right\", null, \"redo\"], [\"refresh\", null, \"sync\"], [\"list-alt\", \"far\", null], [\"dedent\", null, \"outdent\"], [\"video-camera\", null, \"video\"], [\"picture-o\", \"far\", \"image\"], [\"photo\", \"far\", \"image\"], [\"image\", \"far\", \"image\"], [\"pencil\", null, \"pencil-alt\"], [\"map-marker\", null, \"map-marker-alt\"], [\"pencil-square-o\", \"far\", \"edit\"], [\"share-square-o\", \"far\", \"share-square\"], [\"check-square-o\", \"far\", \"check-square\"], [\"arrows\", null, \"arrows-alt\"], [\"times-circle-o\", \"far\", \"times-circle\"], [\"check-circle-o\", \"far\", \"check-circle\"], [\"mail-forward\", null, \"share\"], [\"eye\", \"far\", null], [\"eye-slash\", \"far\", null], [\"warning\", null, \"exclamation-triangle\"], [\"calendar\", null, \"calendar-alt\"], [\"arrows-v\", null, \"arrows-alt-v\"], [\"arrows-h\", null, \"arrows-alt-h\"], [\"bar-chart\", \"far\", \"chart-bar\"], [\"bar-chart-o\", \"far\", \"chart-bar\"], [\"twitter-square\", \"fab\", null], [\"facebook-square\", \"fab\", null], [\"gears\", null, \"cogs\"], [\"thumbs-o-up\", \"far\", \"thumbs-up\"], [\"thumbs-o-down\", \"far\", \"thumbs-down\"], [\"heart-o\", \"far\", \"heart\"], [\"sign-out\", null, \"sign-out-alt\"], [\"linkedin-square\", \"fab\", \"linkedin\"], [\"thumb-tack\", null, \"thumbtack\"], [\"external-link\", null, \"external-link-alt\"], [\"sign-in\", null, \"sign-in-alt\"], [\"github-square\", \"fab\", null], [\"lemon-o\", \"far\", \"lemon\"], [\"square-o\", \"far\", \"square\"], [\"bookmark-o\", \"far\", \"bookmark\"], [\"twitter\", \"fab\", null], [\"facebook\", \"fab\", \"facebook-f\"], [\"facebook-f\", \"fab\", \"facebook-f\"], [\"github\", \"fab\", null], [\"credit-card\", \"far\", null], [\"feed\", null, \"rss\"], [\"hdd-o\", \"far\", \"hdd\"], [\"hand-o-right\", \"far\", \"hand-point-right\"], [\"hand-o-left\", \"far\", \"hand-point-left\"], [\"hand-o-up\", \"far\", \"hand-point-up\"], [\"hand-o-down\", \"far\", \"hand-point-down\"], [\"arrows-alt\", null, \"expand-arrows-alt\"], [\"group\", null, \"users\"], [\"chain\", null, \"link\"], [\"scissors\", null, \"cut\"], [\"files-o\", \"far\", \"copy\"], [\"floppy-o\", \"far\", \"save\"], [\"navicon\", null, \"bars\"], [\"reorder\", null, \"bars\"], [\"pinterest\", \"fab\", null], [\"pinterest-square\", \"fab\", null], [\"google-plus-square\", \"fab\", null], [\"google-plus\", \"fab\", \"google-plus-g\"], [\"money\", \"far\", \"money-bill-alt\"], [\"unsorted\", null, \"sort\"], [\"sort-desc\", null, \"sort-down\"], [\"sort-asc\", null, \"sort-up\"], [\"linkedin\", \"fab\", \"linkedin-in\"], [\"rotate-left\", null, \"undo\"], [\"legal\", null, \"gavel\"], [\"tachometer\", null, \"tachometer-alt\"], [\"dashboard\", null, \"tachometer-alt\"], [\"comment-o\", \"far\", \"comment\"], [\"comments-o\", \"far\", \"comments\"], [\"flash\", null, \"bolt\"], [\"clipboard\", \"far\", null], [\"paste\", \"far\", \"clipboard\"], [\"lightbulb-o\", \"far\", \"lightbulb\"], [\"exchange\", null, \"exchange-alt\"], [\"cloud-download\", null, \"cloud-download-alt\"], [\"cloud-upload\", null, \"cloud-upload-alt\"], [\"bell-o\", \"far\", \"bell\"], [\"cutlery\", null, \"utensils\"], [\"file-text-o\", \"far\", \"file-alt\"], [\"building-o\", \"far\", \"building\"], [\"hospital-o\", \"far\", \"hospital\"], [\"tablet\", null, \"tablet-alt\"], [\"mobile\", null, \"mobile-alt\"], [\"mobile-phone\", null, \"mobile-alt\"], [\"circle-o\", \"far\", \"circle\"], [\"mail-reply\", null, \"reply\"], [\"github-alt\", \"fab\", null], [\"folder-o\", \"far\", \"folder\"], [\"folder-open-o\", \"far\", \"folder-open\"], [\"smile-o\", \"far\", \"smile\"], [\"frown-o\", \"far\", \"frown\"], [\"meh-o\", \"far\", \"meh\"], [\"keyboard-o\", \"far\", \"keyboard\"], [\"flag-o\", \"far\", \"flag\"], [\"mail-reply-all\", null, \"reply-all\"], [\"star-half-o\", \"far\", \"star-half\"], [\"star-half-empty\", \"far\", \"star-half\"], [\"star-half-full\", \"far\", \"star-half\"], [\"code-fork\", null, \"code-branch\"], [\"chain-broken\", null, \"unlink\"], [\"shield\", null, \"shield-alt\"], [\"calendar-o\", \"far\", \"calendar\"], [\"maxcdn\", \"fab\", null], [\"html5\", \"fab\", null], [\"css3\", \"fab\", null], [\"ticket\", null, \"ticket-alt\"], [\"minus-square-o\", \"far\", \"minus-square\"], [\"level-up\", null, \"level-up-alt\"], [\"level-down\", null, \"level-down-alt\"], [\"pencil-square\", null, \"pen-square\"], [\"external-link-square\", null, \"external-link-square-alt\"], [\"compass\", \"far\", null], [\"caret-square-o-down\", \"far\", \"caret-square-down\"], [\"toggle-down\", \"far\", \"caret-square-down\"], [\"caret-square-o-up\", \"far\", \"caret-square-up\"], [\"toggle-up\", \"far\", \"caret-square-up\"], [\"caret-square-o-right\", \"far\", \"caret-square-right\"], [\"toggle-right\", \"far\", \"caret-square-right\"], [\"eur\", null, \"euro-sign\"], [\"euro\", null, \"euro-sign\"], [\"gbp\", null, \"pound-sign\"], [\"usd\", null, \"dollar-sign\"], [\"dollar\", null, \"dollar-sign\"], [\"inr\", null, \"rupee-sign\"], [\"rupee\", null, \"rupee-sign\"], [\"jpy\", null, \"yen-sign\"], [\"cny\", null, \"yen-sign\"], [\"rmb\", null, \"yen-sign\"], [\"yen\", null, \"yen-sign\"], [\"rub\", null, \"ruble-sign\"], [\"ruble\", null, \"ruble-sign\"], [\"rouble\", null, \"ruble-sign\"], [\"krw\", null, \"won-sign\"], [\"won\", null, \"won-sign\"], [\"btc\", \"fab\", null], [\"bitcoin\", \"fab\", \"btc\"], [\"file-text\", null, \"file-alt\"], [\"sort-alpha-asc\", null, \"sort-alpha-down\"], [\"sort-alpha-desc\", null, \"sort-alpha-down-alt\"], [\"sort-amount-asc\", null, \"sort-amount-down\"], [\"sort-amount-desc\", null, \"sort-amount-down-alt\"], [\"sort-numeric-asc\", null, \"sort-numeric-down\"], [\"sort-numeric-desc\", null, \"sort-numeric-down-alt\"], [\"youtube-square\", \"fab\", null], [\"youtube\", \"fab\", null], [\"xing\", \"fab\", null], [\"xing-square\", \"fab\", null], [\"youtube-play\", \"fab\", \"youtube\"], [\"dropbox\", \"fab\", null], [\"stack-overflow\", \"fab\", null], [\"instagram\", \"fab\", null], [\"flickr\", \"fab\", null], [\"adn\", \"fab\", null], [\"bitbucket\", \"fab\", null], [\"bitbucket-square\", \"fab\", \"bitbucket\"], [\"tumblr\", \"fab\", null], [\"tumblr-square\", \"fab\", null], [\"long-arrow-down\", null, \"long-arrow-alt-down\"], [\"long-arrow-up\", null, \"long-arrow-alt-up\"], [\"long-arrow-left\", null, \"long-arrow-alt-left\"], [\"long-arrow-right\", null, \"long-arrow-alt-right\"], [\"apple\", \"fab\", null], [\"windows\", \"fab\", null], [\"android\", \"fab\", null], [\"linux\", \"fab\", null], [\"dribbble\", \"fab\", null], [\"skype\", \"fab\", null], [\"foursquare\", \"fab\", null], [\"trello\", \"fab\", null], [\"gratipay\", \"fab\", null], [\"gittip\", \"fab\", \"gratipay\"], [\"sun-o\", \"far\", \"sun\"], [\"moon-o\", \"far\", \"moon\"], [\"vk\", \"fab\", null], [\"weibo\", \"fab\", null], [\"renren\", \"fab\", null], [\"pagelines\", \"fab\", null], [\"stack-exchange\", \"fab\", null], [\"arrow-circle-o-right\", \"far\", \"arrow-alt-circle-right\"], [\"arrow-circle-o-left\", \"far\", \"arrow-alt-circle-left\"], [\"caret-square-o-left\", \"far\", \"caret-square-left\"], [\"toggle-left\", \"far\", \"caret-square-left\"], [\"dot-circle-o\", \"far\", \"dot-circle\"], [\"vimeo-square\", \"fab\", null], [\"try\", null, \"lira-sign\"], [\"turkish-lira\", null, \"lira-sign\"], [\"plus-square-o\", \"far\", \"plus-square\"], [\"slack\", \"fab\", null], [\"wordpress\", \"fab\", null], [\"openid\", \"fab\", null], [\"institution\", null, \"university\"], [\"bank\", null, \"university\"], [\"mortar-board\", null, \"graduation-cap\"], [\"yahoo\", \"fab\", null], [\"google\", \"fab\", null], [\"reddit\", \"fab\", null], [\"reddit-square\", \"fab\", null], [\"stumbleupon-circle\", \"fab\", null], [\"stumbleupon\", \"fab\", null], [\"delicious\", \"fab\", null], [\"digg\", \"fab\", null], [\"pied-piper-pp\", \"fab\", null], [\"pied-piper-alt\", \"fab\", null], [\"drupal\", \"fab\", null], [\"joomla\", \"fab\", null], [\"spoon\", null, \"utensil-spoon\"], [\"behance\", \"fab\", null], [\"behance-square\", \"fab\", null], [\"steam\", \"fab\", null], [\"steam-square\", \"fab\", null], [\"automobile\", null, \"car\"], [\"cab\", null, \"taxi\"], [\"envelope-o\", \"far\", \"envelope\"], [\"deviantart\", \"fab\", null], [\"soundcloud\", \"fab\", null], [\"file-pdf-o\", \"far\", \"file-pdf\"], [\"file-word-o\", \"far\", \"file-word\"], [\"file-excel-o\", \"far\", \"file-excel\"], [\"file-powerpoint-o\", \"far\", \"file-powerpoint\"], [\"file-image-o\", \"far\", \"file-image\"], [\"file-photo-o\", \"far\", \"file-image\"], [\"file-picture-o\", \"far\", \"file-image\"], [\"file-archive-o\", \"far\", \"file-archive\"], [\"file-zip-o\", \"far\", \"file-archive\"], [\"file-audio-o\", \"far\", \"file-audio\"], [\"file-sound-o\", \"far\", \"file-audio\"], [\"file-video-o\", \"far\", \"file-video\"], [\"file-movie-o\", \"far\", \"file-video\"], [\"file-code-o\", \"far\", \"file-code\"], [\"vine\", \"fab\", null], [\"codepen\", \"fab\", null], [\"jsfiddle\", \"fab\", null], [\"life-ring\", \"far\", null], [\"life-bouy\", \"far\", \"life-ring\"], [\"life-buoy\", \"far\", \"life-ring\"], [\"life-saver\", \"far\", \"life-ring\"], [\"support\", \"far\", \"life-ring\"], [\"circle-o-notch\", null, \"circle-notch\"], [\"rebel\", \"fab\", null], [\"ra\", \"fab\", \"rebel\"], [\"resistance\", \"fab\", \"rebel\"], [\"empire\", \"fab\", null], [\"ge\", \"fab\", \"empire\"], [\"git-square\", \"fab\", null], [\"git\", \"fab\", null], [\"hacker-news\", \"fab\", null], [\"y-combinator-square\", \"fab\", \"hacker-news\"], [\"yc-square\", \"fab\", \"hacker-news\"], [\"tencent-weibo\", \"fab\", null], [\"qq\", \"fab\", null], [\"weixin\", \"fab\", null], [\"wechat\", \"fab\", \"weixin\"], [\"send\", null, \"paper-plane\"], [\"paper-plane-o\", \"far\", \"paper-plane\"], [\"send-o\", \"far\", \"paper-plane\"], [\"circle-thin\", \"far\", \"circle\"], [\"header\", null, \"heading\"], [\"sliders\", null, \"sliders-h\"], [\"futbol-o\", \"far\", \"futbol\"], [\"soccer-ball-o\", \"far\", \"futbol\"], [\"slideshare\", \"fab\", null], [\"twitch\", \"fab\", null], [\"yelp\", \"fab\", null], [\"newspaper-o\", \"far\", \"newspaper\"], [\"paypal\", \"fab\", null], [\"google-wallet\", \"fab\", null], [\"cc-visa\", \"fab\", null], [\"cc-mastercard\", \"fab\", null], [\"cc-discover\", \"fab\", null], [\"cc-amex\", \"fab\", null], [\"cc-paypal\", \"fab\", null], [\"cc-stripe\", \"fab\", null], [\"bell-slash-o\", \"far\", \"bell-slash\"], [\"trash\", null, \"trash-alt\"], [\"copyright\", \"far\", null], [\"eyedropper\", null, \"eye-dropper\"], [\"area-chart\", null, \"chart-area\"], [\"pie-chart\", null, \"chart-pie\"], [\"line-chart\", null, \"chart-line\"], [\"lastfm\", \"fab\", null], [\"lastfm-square\", \"fab\", null], [\"ioxhost\", \"fab\", null], [\"angellist\", \"fab\", null], [\"cc\", \"far\", \"closed-captioning\"], [\"ils\", null, \"shekel-sign\"], [\"shekel\", null, \"shekel-sign\"], [\"sheqel\", null, \"shekel-sign\"], [\"meanpath\", \"fab\", \"font-awesome\"], [\"buysellads\", \"fab\", null], [\"connectdevelop\", \"fab\", null], [\"dashcube\", \"fab\", null], [\"forumbee\", \"fab\", null], [\"leanpub\", \"fab\", null], [\"sellsy\", \"fab\", null], [\"shirtsinbulk\", \"fab\", null], [\"simplybuilt\", \"fab\", null], [\"skyatlas\", \"fab\", null], [\"diamond\", \"far\", \"gem\"], [\"intersex\", null, \"transgender\"], [\"facebook-official\", \"fab\", \"facebook\"], [\"pinterest-p\", \"fab\", null], [\"whatsapp\", \"fab\", null], [\"hotel\", null, \"bed\"], [\"viacoin\", \"fab\", null], [\"medium\", \"fab\", null], [\"y-combinator\", \"fab\", null], [\"yc\", \"fab\", \"y-combinator\"], [\"optin-monster\", \"fab\", null], [\"opencart\", \"fab\", null], [\"expeditedssl\", \"fab\", null], [\"battery-4\", null, \"battery-full\"], [\"battery\", null, \"battery-full\"], [\"battery-3\", null, \"battery-three-quarters\"], [\"battery-2\", null, \"battery-half\"], [\"battery-1\", null, \"battery-quarter\"], [\"battery-0\", null, \"battery-empty\"], [\"object-group\", \"far\", null], [\"object-ungroup\", \"far\", null], [\"sticky-note-o\", \"far\", \"sticky-note\"], [\"cc-jcb\", \"fab\", null], [\"cc-diners-club\", \"fab\", null], [\"clone\", \"far\", null], [\"hourglass-o\", \"far\", \"hourglass\"], [\"hourglass-1\", null, \"hourglass-start\"], [\"hourglass-2\", null, \"hourglass-half\"], [\"hourglass-3\", null, \"hourglass-end\"], [\"hand-rock-o\", \"far\", \"hand-rock\"], [\"hand-grab-o\", \"far\", \"hand-rock\"], [\"hand-paper-o\", \"far\", \"hand-paper\"], [\"hand-stop-o\", \"far\", \"hand-paper\"], [\"hand-scissors-o\", \"far\", \"hand-scissors\"], [\"hand-lizard-o\", \"far\", \"hand-lizard\"], [\"hand-spock-o\", \"far\", \"hand-spock\"], [\"hand-pointer-o\", \"far\", \"hand-pointer\"], [\"hand-peace-o\", \"far\", \"hand-peace\"], [\"registered\", \"far\", null], [\"creative-commons\", \"fab\", null], [\"gg\", \"fab\", null], [\"gg-circle\", \"fab\", null], [\"tripadvisor\", \"fab\", null], [\"odnoklassniki\", \"fab\", null], [\"odnoklassniki-square\", \"fab\", null], [\"get-pocket\", \"fab\", null], [\"wikipedia-w\", \"fab\", null], [\"safari\", \"fab\", null], [\"chrome\", \"fab\", null], [\"firefox\", \"fab\", null], [\"opera\", \"fab\", null], [\"internet-explorer\", \"fab\", null], [\"television\", null, \"tv\"], [\"contao\", \"fab\", null], [\"500px\", \"fab\", null], [\"amazon\", \"fab\", null], [\"calendar-plus-o\", \"far\", \"calendar-plus\"], [\"calendar-minus-o\", \"far\", \"calendar-minus\"], [\"calendar-times-o\", \"far\", \"calendar-times\"], [\"calendar-check-o\", \"far\", \"calendar-check\"], [\"map-o\", \"far\", \"map\"], [\"commenting\", null, \"comment-dots\"], [\"commenting-o\", \"far\", \"comment-dots\"], [\"houzz\", \"fab\", null], [\"vimeo\", \"fab\", \"vimeo-v\"], [\"black-tie\", \"fab\", null], [\"fonticons\", \"fab\", null], [\"reddit-alien\", \"fab\", null], [\"edge\", \"fab\", null], [\"credit-card-alt\", null, \"credit-card\"], [\"codiepie\", \"fab\", null], [\"modx\", \"fab\", null], [\"fort-awesome\", \"fab\", null], [\"usb\", \"fab\", null], [\"product-hunt\", \"fab\", null], [\"mixcloud\", \"fab\", null], [\"scribd\", \"fab\", null], [\"pause-circle-o\", \"far\", \"pause-circle\"], [\"stop-circle-o\", \"far\", \"stop-circle\"], [\"bluetooth\", \"fab\", null], [\"bluetooth-b\", \"fab\", null], [\"gitlab\", \"fab\", null], [\"wpbeginner\", \"fab\", null], [\"wpforms\", \"fab\", null], [\"envira\", \"fab\", null], [\"wheelchair-alt\", \"fab\", \"accessible-icon\"], [\"question-circle-o\", \"far\", \"question-circle\"], [\"volume-control-phone\", null, \"phone-volume\"], [\"asl-interpreting\", null, \"american-sign-language-interpreting\"], [\"deafness\", null, \"deaf\"], [\"hard-of-hearing\", null, \"deaf\"], [\"glide\", \"fab\", null], [\"glide-g\", \"fab\", null], [\"signing\", null, \"sign-language\"], [\"viadeo\", \"fab\", null], [\"viadeo-square\", \"fab\", null], [\"snapchat\", \"fab\", null], [\"snapchat-ghost\", \"fab\", null], [\"snapchat-square\", \"fab\", null], [\"pied-piper\", \"fab\", null], [\"first-order\", \"fab\", null], [\"yoast\", \"fab\", null], [\"themeisle\", \"fab\", null], [\"google-plus-official\", \"fab\", \"google-plus\"], [\"google-plus-circle\", \"fab\", \"google-plus\"], [\"font-awesome\", \"fab\", null], [\"fa\", \"fab\", \"font-awesome\"], [\"handshake-o\", \"far\", \"handshake\"], [\"envelope-open-o\", \"far\", \"envelope-open\"], [\"linode\", \"fab\", null], [\"address-book-o\", \"far\", \"address-book\"], [\"vcard\", null, \"address-card\"], [\"address-card-o\", \"far\", \"address-card\"], [\"vcard-o\", \"far\", \"address-card\"], [\"user-circle-o\", \"far\", \"user-circle\"], [\"user-o\", \"far\", \"user\"], [\"id-badge\", \"far\", null], [\"drivers-license\", null, \"id-card\"], [\"id-card-o\", \"far\", \"id-card\"], [\"drivers-license-o\", \"far\", \"id-card\"], [\"quora\", \"fab\", null], [\"free-code-camp\", \"fab\", null], [\"telegram\", \"fab\", null], [\"thermometer-4\", null, \"thermometer-full\"], [\"thermometer\", null, \"thermometer-full\"], [\"thermometer-3\", null, \"thermometer-three-quarters\"], [\"thermometer-2\", null, \"thermometer-half\"], [\"thermometer-1\", null, \"thermometer-quarter\"], [\"thermometer-0\", null, \"thermometer-empty\"], [\"bathtub\", null, \"bath\"], [\"s15\", null, \"bath\"], [\"window-maximize\", \"far\", null], [\"window-restore\", \"far\", null], [\"times-rectangle\", null, \"window-close\"], [\"window-close-o\", \"far\", \"window-close\"], [\"times-rectangle-o\", \"far\", \"window-close\"], [\"bandcamp\", \"fab\", null], [\"grav\", \"fab\", null], [\"etsy\", \"fab\", null], [\"imdb\", \"fab\", null], [\"ravelry\", \"fab\", null], [\"eercast\", \"fab\", \"sellcast\"], [\"snowflake-o\", \"far\", \"snowflake\"], [\"superpowers\", \"fab\", null], [\"wpexplorer\", \"fab\", null], [\"spotify\", \"fab\", null]];\n  bunker(function () {\n    if (typeof namespace.hooks.addShims === 'function') {\n      namespace.hooks.addShims(shims);\n    } else {\n      var _namespace$shims;\n\n      (_namespace$shims = namespace.shims).push.apply(_namespace$shims, shims);\n    }\n  });\n\n  return shims;\n\n})));\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_animated.less",
    "content": "// Animated Icons\n// --------------------------\n\n.@{fa-css-prefix}-spin {\n  animation: fa-spin 2s infinite linear;\n}\n\n.@{fa-css-prefix}-pulse {\n  animation: fa-spin 1s infinite steps(8);\n}\n\n@keyframes fa-spin {\n  0% {\n    transform: rotate(0deg);\n  }\n  100% {\n    transform: rotate(360deg);\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_bordered-pulled.less",
    "content": "// Bordered & Pulled\n// -------------------------\n\n.@{fa-css-prefix}-border {\n  border-radius: .1em;\n  border: solid .08em @fa-border-color;\n  padding: .2em .25em .15em;\n}\n\n.@{fa-css-prefix}-pull-left { float: left; }\n.@{fa-css-prefix}-pull-right { float: right; }\n\n.@{fa-css-prefix}, .fas, .far, .fal, .fab {\n  &.@{fa-css-prefix}-pull-left { margin-right: .3em; }\n  &.@{fa-css-prefix}-pull-right { margin-left: .3em; }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_core.less",
    "content": "// Base Class Definition\n// -------------------------\n\n.@{fa-css-prefix}, .fas, .far, .fal, .fad, .fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_fixed-width.less",
    "content": "// Fixed Width Icons\n// -------------------------\n.@{fa-css-prefix}-fw {\n  text-align: center;\n  width: (20em / 16);\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_icons.less",
    "content": "/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\n   readers do not read off random characters that represent icons */\n\n.@{fa-css-prefix}-500px:before { content: @fa-var-500px; }\n.@{fa-css-prefix}-accessible-icon:before { content: @fa-var-accessible-icon; }\n.@{fa-css-prefix}-accusoft:before { content: @fa-var-accusoft; }\n.@{fa-css-prefix}-acquisitions-incorporated:before { content: @fa-var-acquisitions-incorporated; }\n.@{fa-css-prefix}-ad:before { content: @fa-var-ad; }\n.@{fa-css-prefix}-address-book:before { content: @fa-var-address-book; }\n.@{fa-css-prefix}-address-card:before { content: @fa-var-address-card; }\n.@{fa-css-prefix}-adjust:before { content: @fa-var-adjust; }\n.@{fa-css-prefix}-adn:before { content: @fa-var-adn; }\n.@{fa-css-prefix}-adobe:before { content: @fa-var-adobe; }\n.@{fa-css-prefix}-adversal:before { content: @fa-var-adversal; }\n.@{fa-css-prefix}-affiliatetheme:before { content: @fa-var-affiliatetheme; }\n.@{fa-css-prefix}-air-freshener:before { content: @fa-var-air-freshener; }\n.@{fa-css-prefix}-airbnb:before { content: @fa-var-airbnb; }\n.@{fa-css-prefix}-algolia:before { content: @fa-var-algolia; }\n.@{fa-css-prefix}-align-center:before { content: @fa-var-align-center; }\n.@{fa-css-prefix}-align-justify:before { content: @fa-var-align-justify; }\n.@{fa-css-prefix}-align-left:before { content: @fa-var-align-left; }\n.@{fa-css-prefix}-align-right:before { content: @fa-var-align-right; }\n.@{fa-css-prefix}-alipay:before { content: @fa-var-alipay; }\n.@{fa-css-prefix}-allergies:before { content: @fa-var-allergies; }\n.@{fa-css-prefix}-amazon:before { content: @fa-var-amazon; }\n.@{fa-css-prefix}-amazon-pay:before { content: @fa-var-amazon-pay; }\n.@{fa-css-prefix}-ambulance:before { content: @fa-var-ambulance; }\n.@{fa-css-prefix}-american-sign-language-interpreting:before { content: @fa-var-american-sign-language-interpreting; }\n.@{fa-css-prefix}-amilia:before { content: @fa-var-amilia; }\n.@{fa-css-prefix}-anchor:before { content: @fa-var-anchor; }\n.@{fa-css-prefix}-android:before { content: @fa-var-android; }\n.@{fa-css-prefix}-angellist:before { content: @fa-var-angellist; }\n.@{fa-css-prefix}-angle-double-down:before { content: @fa-var-angle-double-down; }\n.@{fa-css-prefix}-angle-double-left:before { content: @fa-var-angle-double-left; }\n.@{fa-css-prefix}-angle-double-right:before { content: @fa-var-angle-double-right; }\n.@{fa-css-prefix}-angle-double-up:before { content: @fa-var-angle-double-up; }\n.@{fa-css-prefix}-angle-down:before { content: @fa-var-angle-down; }\n.@{fa-css-prefix}-angle-left:before { content: @fa-var-angle-left; }\n.@{fa-css-prefix}-angle-right:before { content: @fa-var-angle-right; }\n.@{fa-css-prefix}-angle-up:before { content: @fa-var-angle-up; }\n.@{fa-css-prefix}-angry:before { content: @fa-var-angry; }\n.@{fa-css-prefix}-angrycreative:before { content: @fa-var-angrycreative; }\n.@{fa-css-prefix}-angular:before { content: @fa-var-angular; }\n.@{fa-css-prefix}-ankh:before { content: @fa-var-ankh; }\n.@{fa-css-prefix}-app-store:before { content: @fa-var-app-store; }\n.@{fa-css-prefix}-app-store-ios:before { content: @fa-var-app-store-ios; }\n.@{fa-css-prefix}-apper:before { content: @fa-var-apper; }\n.@{fa-css-prefix}-apple:before { content: @fa-var-apple; }\n.@{fa-css-prefix}-apple-alt:before { content: @fa-var-apple-alt; }\n.@{fa-css-prefix}-apple-pay:before { content: @fa-var-apple-pay; }\n.@{fa-css-prefix}-archive:before { content: @fa-var-archive; }\n.@{fa-css-prefix}-archway:before { content: @fa-var-archway; }\n.@{fa-css-prefix}-arrow-alt-circle-down:before { content: @fa-var-arrow-alt-circle-down; }\n.@{fa-css-prefix}-arrow-alt-circle-left:before { content: @fa-var-arrow-alt-circle-left; }\n.@{fa-css-prefix}-arrow-alt-circle-right:before { content: @fa-var-arrow-alt-circle-right; }\n.@{fa-css-prefix}-arrow-alt-circle-up:before { content: @fa-var-arrow-alt-circle-up; }\n.@{fa-css-prefix}-arrow-circle-down:before { content: @fa-var-arrow-circle-down; }\n.@{fa-css-prefix}-arrow-circle-left:before { content: @fa-var-arrow-circle-left; }\n.@{fa-css-prefix}-arrow-circle-right:before { content: @fa-var-arrow-circle-right; }\n.@{fa-css-prefix}-arrow-circle-up:before { content: @fa-var-arrow-circle-up; }\n.@{fa-css-prefix}-arrow-down:before { content: @fa-var-arrow-down; }\n.@{fa-css-prefix}-arrow-left:before { content: @fa-var-arrow-left; }\n.@{fa-css-prefix}-arrow-right:before { content: @fa-var-arrow-right; }\n.@{fa-css-prefix}-arrow-up:before { content: @fa-var-arrow-up; }\n.@{fa-css-prefix}-arrows-alt:before { content: @fa-var-arrows-alt; }\n.@{fa-css-prefix}-arrows-alt-h:before { content: @fa-var-arrows-alt-h; }\n.@{fa-css-prefix}-arrows-alt-v:before { content: @fa-var-arrows-alt-v; }\n.@{fa-css-prefix}-artstation:before { content: @fa-var-artstation; }\n.@{fa-css-prefix}-assistive-listening-systems:before { content: @fa-var-assistive-listening-systems; }\n.@{fa-css-prefix}-asterisk:before { content: @fa-var-asterisk; }\n.@{fa-css-prefix}-asymmetrik:before { content: @fa-var-asymmetrik; }\n.@{fa-css-prefix}-at:before { content: @fa-var-at; }\n.@{fa-css-prefix}-atlas:before { content: @fa-var-atlas; }\n.@{fa-css-prefix}-atlassian:before { content: @fa-var-atlassian; }\n.@{fa-css-prefix}-atom:before { content: @fa-var-atom; }\n.@{fa-css-prefix}-audible:before { content: @fa-var-audible; }\n.@{fa-css-prefix}-audio-description:before { content: @fa-var-audio-description; }\n.@{fa-css-prefix}-autoprefixer:before { content: @fa-var-autoprefixer; }\n.@{fa-css-prefix}-avianex:before { content: @fa-var-avianex; }\n.@{fa-css-prefix}-aviato:before { content: @fa-var-aviato; }\n.@{fa-css-prefix}-award:before { content: @fa-var-award; }\n.@{fa-css-prefix}-aws:before { content: @fa-var-aws; }\n.@{fa-css-prefix}-baby:before { content: @fa-var-baby; }\n.@{fa-css-prefix}-baby-carriage:before { content: @fa-var-baby-carriage; }\n.@{fa-css-prefix}-backspace:before { content: @fa-var-backspace; }\n.@{fa-css-prefix}-backward:before { content: @fa-var-backward; }\n.@{fa-css-prefix}-bacon:before { content: @fa-var-bacon; }\n.@{fa-css-prefix}-balance-scale:before { content: @fa-var-balance-scale; }\n.@{fa-css-prefix}-balance-scale-left:before { content: @fa-var-balance-scale-left; }\n.@{fa-css-prefix}-balance-scale-right:before { content: @fa-var-balance-scale-right; }\n.@{fa-css-prefix}-ban:before { content: @fa-var-ban; }\n.@{fa-css-prefix}-band-aid:before { content: @fa-var-band-aid; }\n.@{fa-css-prefix}-bandcamp:before { content: @fa-var-bandcamp; }\n.@{fa-css-prefix}-barcode:before { content: @fa-var-barcode; }\n.@{fa-css-prefix}-bars:before { content: @fa-var-bars; }\n.@{fa-css-prefix}-baseball-ball:before { content: @fa-var-baseball-ball; }\n.@{fa-css-prefix}-basketball-ball:before { content: @fa-var-basketball-ball; }\n.@{fa-css-prefix}-bath:before { content: @fa-var-bath; }\n.@{fa-css-prefix}-battery-empty:before { content: @fa-var-battery-empty; }\n.@{fa-css-prefix}-battery-full:before { content: @fa-var-battery-full; }\n.@{fa-css-prefix}-battery-half:before { content: @fa-var-battery-half; }\n.@{fa-css-prefix}-battery-quarter:before { content: @fa-var-battery-quarter; }\n.@{fa-css-prefix}-battery-three-quarters:before { content: @fa-var-battery-three-quarters; }\n.@{fa-css-prefix}-battle-net:before { content: @fa-var-battle-net; }\n.@{fa-css-prefix}-bed:before { content: @fa-var-bed; }\n.@{fa-css-prefix}-beer:before { content: @fa-var-beer; }\n.@{fa-css-prefix}-behance:before { content: @fa-var-behance; }\n.@{fa-css-prefix}-behance-square:before { content: @fa-var-behance-square; }\n.@{fa-css-prefix}-bell:before { content: @fa-var-bell; }\n.@{fa-css-prefix}-bell-slash:before { content: @fa-var-bell-slash; }\n.@{fa-css-prefix}-bezier-curve:before { content: @fa-var-bezier-curve; }\n.@{fa-css-prefix}-bible:before { content: @fa-var-bible; }\n.@{fa-css-prefix}-bicycle:before { content: @fa-var-bicycle; }\n.@{fa-css-prefix}-biking:before { content: @fa-var-biking; }\n.@{fa-css-prefix}-bimobject:before { content: @fa-var-bimobject; }\n.@{fa-css-prefix}-binoculars:before { content: @fa-var-binoculars; }\n.@{fa-css-prefix}-biohazard:before { content: @fa-var-biohazard; }\n.@{fa-css-prefix}-birthday-cake:before { content: @fa-var-birthday-cake; }\n.@{fa-css-prefix}-bitbucket:before { content: @fa-var-bitbucket; }\n.@{fa-css-prefix}-bitcoin:before { content: @fa-var-bitcoin; }\n.@{fa-css-prefix}-bity:before { content: @fa-var-bity; }\n.@{fa-css-prefix}-black-tie:before { content: @fa-var-black-tie; }\n.@{fa-css-prefix}-blackberry:before { content: @fa-var-blackberry; }\n.@{fa-css-prefix}-blender:before { content: @fa-var-blender; }\n.@{fa-css-prefix}-blender-phone:before { content: @fa-var-blender-phone; }\n.@{fa-css-prefix}-blind:before { content: @fa-var-blind; }\n.@{fa-css-prefix}-blog:before { content: @fa-var-blog; }\n.@{fa-css-prefix}-blogger:before { content: @fa-var-blogger; }\n.@{fa-css-prefix}-blogger-b:before { content: @fa-var-blogger-b; }\n.@{fa-css-prefix}-bluetooth:before { content: @fa-var-bluetooth; }\n.@{fa-css-prefix}-bluetooth-b:before { content: @fa-var-bluetooth-b; }\n.@{fa-css-prefix}-bold:before { content: @fa-var-bold; }\n.@{fa-css-prefix}-bolt:before { content: @fa-var-bolt; }\n.@{fa-css-prefix}-bomb:before { content: @fa-var-bomb; }\n.@{fa-css-prefix}-bone:before { content: @fa-var-bone; }\n.@{fa-css-prefix}-bong:before { content: @fa-var-bong; }\n.@{fa-css-prefix}-book:before { content: @fa-var-book; }\n.@{fa-css-prefix}-book-dead:before { content: @fa-var-book-dead; }\n.@{fa-css-prefix}-book-medical:before { content: @fa-var-book-medical; }\n.@{fa-css-prefix}-book-open:before { content: @fa-var-book-open; }\n.@{fa-css-prefix}-book-reader:before { content: @fa-var-book-reader; }\n.@{fa-css-prefix}-bookmark:before { content: @fa-var-bookmark; }\n.@{fa-css-prefix}-bootstrap:before { content: @fa-var-bootstrap; }\n.@{fa-css-prefix}-border-all:before { content: @fa-var-border-all; }\n.@{fa-css-prefix}-border-none:before { content: @fa-var-border-none; }\n.@{fa-css-prefix}-border-style:before { content: @fa-var-border-style; }\n.@{fa-css-prefix}-bowling-ball:before { content: @fa-var-bowling-ball; }\n.@{fa-css-prefix}-box:before { content: @fa-var-box; }\n.@{fa-css-prefix}-box-open:before { content: @fa-var-box-open; }\n.@{fa-css-prefix}-boxes:before { content: @fa-var-boxes; }\n.@{fa-css-prefix}-braille:before { content: @fa-var-braille; }\n.@{fa-css-prefix}-brain:before { content: @fa-var-brain; }\n.@{fa-css-prefix}-bread-slice:before { content: @fa-var-bread-slice; }\n.@{fa-css-prefix}-briefcase:before { content: @fa-var-briefcase; }\n.@{fa-css-prefix}-briefcase-medical:before { content: @fa-var-briefcase-medical; }\n.@{fa-css-prefix}-broadcast-tower:before { content: @fa-var-broadcast-tower; }\n.@{fa-css-prefix}-broom:before { content: @fa-var-broom; }\n.@{fa-css-prefix}-brush:before { content: @fa-var-brush; }\n.@{fa-css-prefix}-btc:before { content: @fa-var-btc; }\n.@{fa-css-prefix}-buffer:before { content: @fa-var-buffer; }\n.@{fa-css-prefix}-bug:before { content: @fa-var-bug; }\n.@{fa-css-prefix}-building:before { content: @fa-var-building; }\n.@{fa-css-prefix}-bullhorn:before { content: @fa-var-bullhorn; }\n.@{fa-css-prefix}-bullseye:before { content: @fa-var-bullseye; }\n.@{fa-css-prefix}-burn:before { content: @fa-var-burn; }\n.@{fa-css-prefix}-buromobelexperte:before { content: @fa-var-buromobelexperte; }\n.@{fa-css-prefix}-bus:before { content: @fa-var-bus; }\n.@{fa-css-prefix}-bus-alt:before { content: @fa-var-bus-alt; }\n.@{fa-css-prefix}-business-time:before { content: @fa-var-business-time; }\n.@{fa-css-prefix}-buysellads:before { content: @fa-var-buysellads; }\n.@{fa-css-prefix}-calculator:before { content: @fa-var-calculator; }\n.@{fa-css-prefix}-calendar:before { content: @fa-var-calendar; }\n.@{fa-css-prefix}-calendar-alt:before { content: @fa-var-calendar-alt; }\n.@{fa-css-prefix}-calendar-check:before { content: @fa-var-calendar-check; }\n.@{fa-css-prefix}-calendar-day:before { content: @fa-var-calendar-day; }\n.@{fa-css-prefix}-calendar-minus:before { content: @fa-var-calendar-minus; }\n.@{fa-css-prefix}-calendar-plus:before { content: @fa-var-calendar-plus; }\n.@{fa-css-prefix}-calendar-times:before { content: @fa-var-calendar-times; }\n.@{fa-css-prefix}-calendar-week:before { content: @fa-var-calendar-week; }\n.@{fa-css-prefix}-camera:before { content: @fa-var-camera; }\n.@{fa-css-prefix}-camera-retro:before { content: @fa-var-camera-retro; }\n.@{fa-css-prefix}-campground:before { content: @fa-var-campground; }\n.@{fa-css-prefix}-canadian-maple-leaf:before { content: @fa-var-canadian-maple-leaf; }\n.@{fa-css-prefix}-candy-cane:before { content: @fa-var-candy-cane; }\n.@{fa-css-prefix}-cannabis:before { content: @fa-var-cannabis; }\n.@{fa-css-prefix}-capsules:before { content: @fa-var-capsules; }\n.@{fa-css-prefix}-car:before { content: @fa-var-car; }\n.@{fa-css-prefix}-car-alt:before { content: @fa-var-car-alt; }\n.@{fa-css-prefix}-car-battery:before { content: @fa-var-car-battery; }\n.@{fa-css-prefix}-car-crash:before { content: @fa-var-car-crash; }\n.@{fa-css-prefix}-car-side:before { content: @fa-var-car-side; }\n.@{fa-css-prefix}-caret-down:before { content: @fa-var-caret-down; }\n.@{fa-css-prefix}-caret-left:before { content: @fa-var-caret-left; }\n.@{fa-css-prefix}-caret-right:before { content: @fa-var-caret-right; }\n.@{fa-css-prefix}-caret-square-down:before { content: @fa-var-caret-square-down; }\n.@{fa-css-prefix}-caret-square-left:before { content: @fa-var-caret-square-left; }\n.@{fa-css-prefix}-caret-square-right:before { content: @fa-var-caret-square-right; }\n.@{fa-css-prefix}-caret-square-up:before { content: @fa-var-caret-square-up; }\n.@{fa-css-prefix}-caret-up:before { content: @fa-var-caret-up; }\n.@{fa-css-prefix}-carrot:before { content: @fa-var-carrot; }\n.@{fa-css-prefix}-cart-arrow-down:before { content: @fa-var-cart-arrow-down; }\n.@{fa-css-prefix}-cart-plus:before { content: @fa-var-cart-plus; }\n.@{fa-css-prefix}-cash-register:before { content: @fa-var-cash-register; }\n.@{fa-css-prefix}-cat:before { content: @fa-var-cat; }\n.@{fa-css-prefix}-cc-amazon-pay:before { content: @fa-var-cc-amazon-pay; }\n.@{fa-css-prefix}-cc-amex:before { content: @fa-var-cc-amex; }\n.@{fa-css-prefix}-cc-apple-pay:before { content: @fa-var-cc-apple-pay; }\n.@{fa-css-prefix}-cc-diners-club:before { content: @fa-var-cc-diners-club; }\n.@{fa-css-prefix}-cc-discover:before { content: @fa-var-cc-discover; }\n.@{fa-css-prefix}-cc-jcb:before { content: @fa-var-cc-jcb; }\n.@{fa-css-prefix}-cc-mastercard:before { content: @fa-var-cc-mastercard; }\n.@{fa-css-prefix}-cc-paypal:before { content: @fa-var-cc-paypal; }\n.@{fa-css-prefix}-cc-stripe:before { content: @fa-var-cc-stripe; }\n.@{fa-css-prefix}-cc-visa:before { content: @fa-var-cc-visa; }\n.@{fa-css-prefix}-centercode:before { content: @fa-var-centercode; }\n.@{fa-css-prefix}-centos:before { content: @fa-var-centos; }\n.@{fa-css-prefix}-certificate:before { content: @fa-var-certificate; }\n.@{fa-css-prefix}-chair:before { content: @fa-var-chair; }\n.@{fa-css-prefix}-chalkboard:before { content: @fa-var-chalkboard; }\n.@{fa-css-prefix}-chalkboard-teacher:before { content: @fa-var-chalkboard-teacher; }\n.@{fa-css-prefix}-charging-station:before { content: @fa-var-charging-station; }\n.@{fa-css-prefix}-chart-area:before { content: @fa-var-chart-area; }\n.@{fa-css-prefix}-chart-bar:before { content: @fa-var-chart-bar; }\n.@{fa-css-prefix}-chart-line:before { content: @fa-var-chart-line; }\n.@{fa-css-prefix}-chart-pie:before { content: @fa-var-chart-pie; }\n.@{fa-css-prefix}-check:before { content: @fa-var-check; }\n.@{fa-css-prefix}-check-circle:before { content: @fa-var-check-circle; }\n.@{fa-css-prefix}-check-double:before { content: @fa-var-check-double; }\n.@{fa-css-prefix}-check-square:before { content: @fa-var-check-square; }\n.@{fa-css-prefix}-cheese:before { content: @fa-var-cheese; }\n.@{fa-css-prefix}-chess:before { content: @fa-var-chess; }\n.@{fa-css-prefix}-chess-bishop:before { content: @fa-var-chess-bishop; }\n.@{fa-css-prefix}-chess-board:before { content: @fa-var-chess-board; }\n.@{fa-css-prefix}-chess-king:before { content: @fa-var-chess-king; }\n.@{fa-css-prefix}-chess-knight:before { content: @fa-var-chess-knight; }\n.@{fa-css-prefix}-chess-pawn:before { content: @fa-var-chess-pawn; }\n.@{fa-css-prefix}-chess-queen:before { content: @fa-var-chess-queen; }\n.@{fa-css-prefix}-chess-rook:before { content: @fa-var-chess-rook; }\n.@{fa-css-prefix}-chevron-circle-down:before { content: @fa-var-chevron-circle-down; }\n.@{fa-css-prefix}-chevron-circle-left:before { content: @fa-var-chevron-circle-left; }\n.@{fa-css-prefix}-chevron-circle-right:before { content: @fa-var-chevron-circle-right; }\n.@{fa-css-prefix}-chevron-circle-up:before { content: @fa-var-chevron-circle-up; }\n.@{fa-css-prefix}-chevron-down:before { content: @fa-var-chevron-down; }\n.@{fa-css-prefix}-chevron-left:before { content: @fa-var-chevron-left; }\n.@{fa-css-prefix}-chevron-right:before { content: @fa-var-chevron-right; }\n.@{fa-css-prefix}-chevron-up:before { content: @fa-var-chevron-up; }\n.@{fa-css-prefix}-child:before { content: @fa-var-child; }\n.@{fa-css-prefix}-chrome:before { content: @fa-var-chrome; }\n.@{fa-css-prefix}-chromecast:before { content: @fa-var-chromecast; }\n.@{fa-css-prefix}-church:before { content: @fa-var-church; }\n.@{fa-css-prefix}-circle:before { content: @fa-var-circle; }\n.@{fa-css-prefix}-circle-notch:before { content: @fa-var-circle-notch; }\n.@{fa-css-prefix}-city:before { content: @fa-var-city; }\n.@{fa-css-prefix}-clinic-medical:before { content: @fa-var-clinic-medical; }\n.@{fa-css-prefix}-clipboard:before { content: @fa-var-clipboard; }\n.@{fa-css-prefix}-clipboard-check:before { content: @fa-var-clipboard-check; }\n.@{fa-css-prefix}-clipboard-list:before { content: @fa-var-clipboard-list; }\n.@{fa-css-prefix}-clock:before { content: @fa-var-clock; }\n.@{fa-css-prefix}-clone:before { content: @fa-var-clone; }\n.@{fa-css-prefix}-closed-captioning:before { content: @fa-var-closed-captioning; }\n.@{fa-css-prefix}-cloud:before { content: @fa-var-cloud; }\n.@{fa-css-prefix}-cloud-download-alt:before { content: @fa-var-cloud-download-alt; }\n.@{fa-css-prefix}-cloud-meatball:before { content: @fa-var-cloud-meatball; }\n.@{fa-css-prefix}-cloud-moon:before { content: @fa-var-cloud-moon; }\n.@{fa-css-prefix}-cloud-moon-rain:before { content: @fa-var-cloud-moon-rain; }\n.@{fa-css-prefix}-cloud-rain:before { content: @fa-var-cloud-rain; }\n.@{fa-css-prefix}-cloud-showers-heavy:before { content: @fa-var-cloud-showers-heavy; }\n.@{fa-css-prefix}-cloud-sun:before { content: @fa-var-cloud-sun; }\n.@{fa-css-prefix}-cloud-sun-rain:before { content: @fa-var-cloud-sun-rain; }\n.@{fa-css-prefix}-cloud-upload-alt:before { content: @fa-var-cloud-upload-alt; }\n.@{fa-css-prefix}-cloudscale:before { content: @fa-var-cloudscale; }\n.@{fa-css-prefix}-cloudsmith:before { content: @fa-var-cloudsmith; }\n.@{fa-css-prefix}-cloudversify:before { content: @fa-var-cloudversify; }\n.@{fa-css-prefix}-cocktail:before { content: @fa-var-cocktail; }\n.@{fa-css-prefix}-code:before { content: @fa-var-code; }\n.@{fa-css-prefix}-code-branch:before { content: @fa-var-code-branch; }\n.@{fa-css-prefix}-codepen:before { content: @fa-var-codepen; }\n.@{fa-css-prefix}-codiepie:before { content: @fa-var-codiepie; }\n.@{fa-css-prefix}-coffee:before { content: @fa-var-coffee; }\n.@{fa-css-prefix}-cog:before { content: @fa-var-cog; }\n.@{fa-css-prefix}-cogs:before { content: @fa-var-cogs; }\n.@{fa-css-prefix}-coins:before { content: @fa-var-coins; }\n.@{fa-css-prefix}-columns:before { content: @fa-var-columns; }\n.@{fa-css-prefix}-comment:before { content: @fa-var-comment; }\n.@{fa-css-prefix}-comment-alt:before { content: @fa-var-comment-alt; }\n.@{fa-css-prefix}-comment-dollar:before { content: @fa-var-comment-dollar; }\n.@{fa-css-prefix}-comment-dots:before { content: @fa-var-comment-dots; }\n.@{fa-css-prefix}-comment-medical:before { content: @fa-var-comment-medical; }\n.@{fa-css-prefix}-comment-slash:before { content: @fa-var-comment-slash; }\n.@{fa-css-prefix}-comments:before { content: @fa-var-comments; }\n.@{fa-css-prefix}-comments-dollar:before { content: @fa-var-comments-dollar; }\n.@{fa-css-prefix}-compact-disc:before { content: @fa-var-compact-disc; }\n.@{fa-css-prefix}-compass:before { content: @fa-var-compass; }\n.@{fa-css-prefix}-compress:before { content: @fa-var-compress; }\n.@{fa-css-prefix}-compress-arrows-alt:before { content: @fa-var-compress-arrows-alt; }\n.@{fa-css-prefix}-concierge-bell:before { content: @fa-var-concierge-bell; }\n.@{fa-css-prefix}-confluence:before { content: @fa-var-confluence; }\n.@{fa-css-prefix}-connectdevelop:before { content: @fa-var-connectdevelop; }\n.@{fa-css-prefix}-contao:before { content: @fa-var-contao; }\n.@{fa-css-prefix}-cookie:before { content: @fa-var-cookie; }\n.@{fa-css-prefix}-cookie-bite:before { content: @fa-var-cookie-bite; }\n.@{fa-css-prefix}-copy:before { content: @fa-var-copy; }\n.@{fa-css-prefix}-copyright:before { content: @fa-var-copyright; }\n.@{fa-css-prefix}-cotton-bureau:before { content: @fa-var-cotton-bureau; }\n.@{fa-css-prefix}-couch:before { content: @fa-var-couch; }\n.@{fa-css-prefix}-cpanel:before { content: @fa-var-cpanel; }\n.@{fa-css-prefix}-creative-commons:before { content: @fa-var-creative-commons; }\n.@{fa-css-prefix}-creative-commons-by:before { content: @fa-var-creative-commons-by; }\n.@{fa-css-prefix}-creative-commons-nc:before { content: @fa-var-creative-commons-nc; }\n.@{fa-css-prefix}-creative-commons-nc-eu:before { content: @fa-var-creative-commons-nc-eu; }\n.@{fa-css-prefix}-creative-commons-nc-jp:before { content: @fa-var-creative-commons-nc-jp; }\n.@{fa-css-prefix}-creative-commons-nd:before { content: @fa-var-creative-commons-nd; }\n.@{fa-css-prefix}-creative-commons-pd:before { content: @fa-var-creative-commons-pd; }\n.@{fa-css-prefix}-creative-commons-pd-alt:before { content: @fa-var-creative-commons-pd-alt; }\n.@{fa-css-prefix}-creative-commons-remix:before { content: @fa-var-creative-commons-remix; }\n.@{fa-css-prefix}-creative-commons-sa:before { content: @fa-var-creative-commons-sa; }\n.@{fa-css-prefix}-creative-commons-sampling:before { content: @fa-var-creative-commons-sampling; }\n.@{fa-css-prefix}-creative-commons-sampling-plus:before { content: @fa-var-creative-commons-sampling-plus; }\n.@{fa-css-prefix}-creative-commons-share:before { content: @fa-var-creative-commons-share; }\n.@{fa-css-prefix}-creative-commons-zero:before { content: @fa-var-creative-commons-zero; }\n.@{fa-css-prefix}-credit-card:before { content: @fa-var-credit-card; }\n.@{fa-css-prefix}-critical-role:before { content: @fa-var-critical-role; }\n.@{fa-css-prefix}-crop:before { content: @fa-var-crop; }\n.@{fa-css-prefix}-crop-alt:before { content: @fa-var-crop-alt; }\n.@{fa-css-prefix}-cross:before { content: @fa-var-cross; }\n.@{fa-css-prefix}-crosshairs:before { content: @fa-var-crosshairs; }\n.@{fa-css-prefix}-crow:before { content: @fa-var-crow; }\n.@{fa-css-prefix}-crown:before { content: @fa-var-crown; }\n.@{fa-css-prefix}-crutch:before { content: @fa-var-crutch; }\n.@{fa-css-prefix}-css3:before { content: @fa-var-css3; }\n.@{fa-css-prefix}-css3-alt:before { content: @fa-var-css3-alt; }\n.@{fa-css-prefix}-cube:before { content: @fa-var-cube; }\n.@{fa-css-prefix}-cubes:before { content: @fa-var-cubes; }\n.@{fa-css-prefix}-cut:before { content: @fa-var-cut; }\n.@{fa-css-prefix}-cuttlefish:before { content: @fa-var-cuttlefish; }\n.@{fa-css-prefix}-d-and-d:before { content: @fa-var-d-and-d; }\n.@{fa-css-prefix}-d-and-d-beyond:before { content: @fa-var-d-and-d-beyond; }\n.@{fa-css-prefix}-dashcube:before { content: @fa-var-dashcube; }\n.@{fa-css-prefix}-database:before { content: @fa-var-database; }\n.@{fa-css-prefix}-deaf:before { content: @fa-var-deaf; }\n.@{fa-css-prefix}-delicious:before { content: @fa-var-delicious; }\n.@{fa-css-prefix}-democrat:before { content: @fa-var-democrat; }\n.@{fa-css-prefix}-deploydog:before { content: @fa-var-deploydog; }\n.@{fa-css-prefix}-deskpro:before { content: @fa-var-deskpro; }\n.@{fa-css-prefix}-desktop:before { content: @fa-var-desktop; }\n.@{fa-css-prefix}-dev:before { content: @fa-var-dev; }\n.@{fa-css-prefix}-deviantart:before { content: @fa-var-deviantart; }\n.@{fa-css-prefix}-dharmachakra:before { content: @fa-var-dharmachakra; }\n.@{fa-css-prefix}-dhl:before { content: @fa-var-dhl; }\n.@{fa-css-prefix}-diagnoses:before { content: @fa-var-diagnoses; }\n.@{fa-css-prefix}-diaspora:before { content: @fa-var-diaspora; }\n.@{fa-css-prefix}-dice:before { content: @fa-var-dice; }\n.@{fa-css-prefix}-dice-d20:before { content: @fa-var-dice-d20; }\n.@{fa-css-prefix}-dice-d6:before { content: @fa-var-dice-d6; }\n.@{fa-css-prefix}-dice-five:before { content: @fa-var-dice-five; }\n.@{fa-css-prefix}-dice-four:before { content: @fa-var-dice-four; }\n.@{fa-css-prefix}-dice-one:before { content: @fa-var-dice-one; }\n.@{fa-css-prefix}-dice-six:before { content: @fa-var-dice-six; }\n.@{fa-css-prefix}-dice-three:before { content: @fa-var-dice-three; }\n.@{fa-css-prefix}-dice-two:before { content: @fa-var-dice-two; }\n.@{fa-css-prefix}-digg:before { content: @fa-var-digg; }\n.@{fa-css-prefix}-digital-ocean:before { content: @fa-var-digital-ocean; }\n.@{fa-css-prefix}-digital-tachograph:before { content: @fa-var-digital-tachograph; }\n.@{fa-css-prefix}-directions:before { content: @fa-var-directions; }\n.@{fa-css-prefix}-discord:before { content: @fa-var-discord; }\n.@{fa-css-prefix}-discourse:before { content: @fa-var-discourse; }\n.@{fa-css-prefix}-divide:before { content: @fa-var-divide; }\n.@{fa-css-prefix}-dizzy:before { content: @fa-var-dizzy; }\n.@{fa-css-prefix}-dna:before { content: @fa-var-dna; }\n.@{fa-css-prefix}-dochub:before { content: @fa-var-dochub; }\n.@{fa-css-prefix}-docker:before { content: @fa-var-docker; }\n.@{fa-css-prefix}-dog:before { content: @fa-var-dog; }\n.@{fa-css-prefix}-dollar-sign:before { content: @fa-var-dollar-sign; }\n.@{fa-css-prefix}-dolly:before { content: @fa-var-dolly; }\n.@{fa-css-prefix}-dolly-flatbed:before { content: @fa-var-dolly-flatbed; }\n.@{fa-css-prefix}-donate:before { content: @fa-var-donate; }\n.@{fa-css-prefix}-door-closed:before { content: @fa-var-door-closed; }\n.@{fa-css-prefix}-door-open:before { content: @fa-var-door-open; }\n.@{fa-css-prefix}-dot-circle:before { content: @fa-var-dot-circle; }\n.@{fa-css-prefix}-dove:before { content: @fa-var-dove; }\n.@{fa-css-prefix}-download:before { content: @fa-var-download; }\n.@{fa-css-prefix}-draft2digital:before { content: @fa-var-draft2digital; }\n.@{fa-css-prefix}-drafting-compass:before { content: @fa-var-drafting-compass; }\n.@{fa-css-prefix}-dragon:before { content: @fa-var-dragon; }\n.@{fa-css-prefix}-draw-polygon:before { content: @fa-var-draw-polygon; }\n.@{fa-css-prefix}-dribbble:before { content: @fa-var-dribbble; }\n.@{fa-css-prefix}-dribbble-square:before { content: @fa-var-dribbble-square; }\n.@{fa-css-prefix}-dropbox:before { content: @fa-var-dropbox; }\n.@{fa-css-prefix}-drum:before { content: @fa-var-drum; }\n.@{fa-css-prefix}-drum-steelpan:before { content: @fa-var-drum-steelpan; }\n.@{fa-css-prefix}-drumstick-bite:before { content: @fa-var-drumstick-bite; }\n.@{fa-css-prefix}-drupal:before { content: @fa-var-drupal; }\n.@{fa-css-prefix}-dumbbell:before { content: @fa-var-dumbbell; }\n.@{fa-css-prefix}-dumpster:before { content: @fa-var-dumpster; }\n.@{fa-css-prefix}-dumpster-fire:before { content: @fa-var-dumpster-fire; }\n.@{fa-css-prefix}-dungeon:before { content: @fa-var-dungeon; }\n.@{fa-css-prefix}-dyalog:before { content: @fa-var-dyalog; }\n.@{fa-css-prefix}-earlybirds:before { content: @fa-var-earlybirds; }\n.@{fa-css-prefix}-ebay:before { content: @fa-var-ebay; }\n.@{fa-css-prefix}-edge:before { content: @fa-var-edge; }\n.@{fa-css-prefix}-edit:before { content: @fa-var-edit; }\n.@{fa-css-prefix}-egg:before { content: @fa-var-egg; }\n.@{fa-css-prefix}-eject:before { content: @fa-var-eject; }\n.@{fa-css-prefix}-elementor:before { content: @fa-var-elementor; }\n.@{fa-css-prefix}-ellipsis-h:before { content: @fa-var-ellipsis-h; }\n.@{fa-css-prefix}-ellipsis-v:before { content: @fa-var-ellipsis-v; }\n.@{fa-css-prefix}-ello:before { content: @fa-var-ello; }\n.@{fa-css-prefix}-ember:before { content: @fa-var-ember; }\n.@{fa-css-prefix}-empire:before { content: @fa-var-empire; }\n.@{fa-css-prefix}-envelope:before { content: @fa-var-envelope; }\n.@{fa-css-prefix}-envelope-open:before { content: @fa-var-envelope-open; }\n.@{fa-css-prefix}-envelope-open-text:before { content: @fa-var-envelope-open-text; }\n.@{fa-css-prefix}-envelope-square:before { content: @fa-var-envelope-square; }\n.@{fa-css-prefix}-envira:before { content: @fa-var-envira; }\n.@{fa-css-prefix}-equals:before { content: @fa-var-equals; }\n.@{fa-css-prefix}-eraser:before { content: @fa-var-eraser; }\n.@{fa-css-prefix}-erlang:before { content: @fa-var-erlang; }\n.@{fa-css-prefix}-ethereum:before { content: @fa-var-ethereum; }\n.@{fa-css-prefix}-ethernet:before { content: @fa-var-ethernet; }\n.@{fa-css-prefix}-etsy:before { content: @fa-var-etsy; }\n.@{fa-css-prefix}-euro-sign:before { content: @fa-var-euro-sign; }\n.@{fa-css-prefix}-evernote:before { content: @fa-var-evernote; }\n.@{fa-css-prefix}-exchange-alt:before { content: @fa-var-exchange-alt; }\n.@{fa-css-prefix}-exclamation:before { content: @fa-var-exclamation; }\n.@{fa-css-prefix}-exclamation-circle:before { content: @fa-var-exclamation-circle; }\n.@{fa-css-prefix}-exclamation-triangle:before { content: @fa-var-exclamation-triangle; }\n.@{fa-css-prefix}-expand:before { content: @fa-var-expand; }\n.@{fa-css-prefix}-expand-arrows-alt:before { content: @fa-var-expand-arrows-alt; }\n.@{fa-css-prefix}-expeditedssl:before { content: @fa-var-expeditedssl; }\n.@{fa-css-prefix}-external-link-alt:before { content: @fa-var-external-link-alt; }\n.@{fa-css-prefix}-external-link-square-alt:before { content: @fa-var-external-link-square-alt; }\n.@{fa-css-prefix}-eye:before { content: @fa-var-eye; }\n.@{fa-css-prefix}-eye-dropper:before { content: @fa-var-eye-dropper; }\n.@{fa-css-prefix}-eye-slash:before { content: @fa-var-eye-slash; }\n.@{fa-css-prefix}-facebook:before { content: @fa-var-facebook; }\n.@{fa-css-prefix}-facebook-f:before { content: @fa-var-facebook-f; }\n.@{fa-css-prefix}-facebook-messenger:before { content: @fa-var-facebook-messenger; }\n.@{fa-css-prefix}-facebook-square:before { content: @fa-var-facebook-square; }\n.@{fa-css-prefix}-fan:before { content: @fa-var-fan; }\n.@{fa-css-prefix}-fantasy-flight-games:before { content: @fa-var-fantasy-flight-games; }\n.@{fa-css-prefix}-fast-backward:before { content: @fa-var-fast-backward; }\n.@{fa-css-prefix}-fast-forward:before { content: @fa-var-fast-forward; }\n.@{fa-css-prefix}-fax:before { content: @fa-var-fax; }\n.@{fa-css-prefix}-feather:before { content: @fa-var-feather; }\n.@{fa-css-prefix}-feather-alt:before { content: @fa-var-feather-alt; }\n.@{fa-css-prefix}-fedex:before { content: @fa-var-fedex; }\n.@{fa-css-prefix}-fedora:before { content: @fa-var-fedora; }\n.@{fa-css-prefix}-female:before { content: @fa-var-female; }\n.@{fa-css-prefix}-fighter-jet:before { content: @fa-var-fighter-jet; }\n.@{fa-css-prefix}-figma:before { content: @fa-var-figma; }\n.@{fa-css-prefix}-file:before { content: @fa-var-file; }\n.@{fa-css-prefix}-file-alt:before { content: @fa-var-file-alt; }\n.@{fa-css-prefix}-file-archive:before { content: @fa-var-file-archive; }\n.@{fa-css-prefix}-file-audio:before { content: @fa-var-file-audio; }\n.@{fa-css-prefix}-file-code:before { content: @fa-var-file-code; }\n.@{fa-css-prefix}-file-contract:before { content: @fa-var-file-contract; }\n.@{fa-css-prefix}-file-csv:before { content: @fa-var-file-csv; }\n.@{fa-css-prefix}-file-download:before { content: @fa-var-file-download; }\n.@{fa-css-prefix}-file-excel:before { content: @fa-var-file-excel; }\n.@{fa-css-prefix}-file-export:before { content: @fa-var-file-export; }\n.@{fa-css-prefix}-file-image:before { content: @fa-var-file-image; }\n.@{fa-css-prefix}-file-import:before { content: @fa-var-file-import; }\n.@{fa-css-prefix}-file-invoice:before { content: @fa-var-file-invoice; }\n.@{fa-css-prefix}-file-invoice-dollar:before { content: @fa-var-file-invoice-dollar; }\n.@{fa-css-prefix}-file-medical:before { content: @fa-var-file-medical; }\n.@{fa-css-prefix}-file-medical-alt:before { content: @fa-var-file-medical-alt; }\n.@{fa-css-prefix}-file-pdf:before { content: @fa-var-file-pdf; }\n.@{fa-css-prefix}-file-powerpoint:before { content: @fa-var-file-powerpoint; }\n.@{fa-css-prefix}-file-prescription:before { content: @fa-var-file-prescription; }\n.@{fa-css-prefix}-file-signature:before { content: @fa-var-file-signature; }\n.@{fa-css-prefix}-file-upload:before { content: @fa-var-file-upload; }\n.@{fa-css-prefix}-file-video:before { content: @fa-var-file-video; }\n.@{fa-css-prefix}-file-word:before { content: @fa-var-file-word; }\n.@{fa-css-prefix}-fill:before { content: @fa-var-fill; }\n.@{fa-css-prefix}-fill-drip:before { content: @fa-var-fill-drip; }\n.@{fa-css-prefix}-film:before { content: @fa-var-film; }\n.@{fa-css-prefix}-filter:before { content: @fa-var-filter; }\n.@{fa-css-prefix}-fingerprint:before { content: @fa-var-fingerprint; }\n.@{fa-css-prefix}-fire:before { content: @fa-var-fire; }\n.@{fa-css-prefix}-fire-alt:before { content: @fa-var-fire-alt; }\n.@{fa-css-prefix}-fire-extinguisher:before { content: @fa-var-fire-extinguisher; }\n.@{fa-css-prefix}-firefox:before { content: @fa-var-firefox; }\n.@{fa-css-prefix}-first-aid:before { content: @fa-var-first-aid; }\n.@{fa-css-prefix}-first-order:before { content: @fa-var-first-order; }\n.@{fa-css-prefix}-first-order-alt:before { content: @fa-var-first-order-alt; }\n.@{fa-css-prefix}-firstdraft:before { content: @fa-var-firstdraft; }\n.@{fa-css-prefix}-fish:before { content: @fa-var-fish; }\n.@{fa-css-prefix}-fist-raised:before { content: @fa-var-fist-raised; }\n.@{fa-css-prefix}-flag:before { content: @fa-var-flag; }\n.@{fa-css-prefix}-flag-checkered:before { content: @fa-var-flag-checkered; }\n.@{fa-css-prefix}-flag-usa:before { content: @fa-var-flag-usa; }\n.@{fa-css-prefix}-flask:before { content: @fa-var-flask; }\n.@{fa-css-prefix}-flickr:before { content: @fa-var-flickr; }\n.@{fa-css-prefix}-flipboard:before { content: @fa-var-flipboard; }\n.@{fa-css-prefix}-flushed:before { content: @fa-var-flushed; }\n.@{fa-css-prefix}-fly:before { content: @fa-var-fly; }\n.@{fa-css-prefix}-folder:before { content: @fa-var-folder; }\n.@{fa-css-prefix}-folder-minus:before { content: @fa-var-folder-minus; }\n.@{fa-css-prefix}-folder-open:before { content: @fa-var-folder-open; }\n.@{fa-css-prefix}-folder-plus:before { content: @fa-var-folder-plus; }\n.@{fa-css-prefix}-font:before { content: @fa-var-font; }\n.@{fa-css-prefix}-font-awesome:before { content: @fa-var-font-awesome; }\n.@{fa-css-prefix}-font-awesome-alt:before { content: @fa-var-font-awesome-alt; }\n.@{fa-css-prefix}-font-awesome-flag:before { content: @fa-var-font-awesome-flag; }\n.@{fa-css-prefix}-font-awesome-logo-full:before { content: @fa-var-font-awesome-logo-full; }\n.@{fa-css-prefix}-fonticons:before { content: @fa-var-fonticons; }\n.@{fa-css-prefix}-fonticons-fi:before { content: @fa-var-fonticons-fi; }\n.@{fa-css-prefix}-football-ball:before { content: @fa-var-football-ball; }\n.@{fa-css-prefix}-fort-awesome:before { content: @fa-var-fort-awesome; }\n.@{fa-css-prefix}-fort-awesome-alt:before { content: @fa-var-fort-awesome-alt; }\n.@{fa-css-prefix}-forumbee:before { content: @fa-var-forumbee; }\n.@{fa-css-prefix}-forward:before { content: @fa-var-forward; }\n.@{fa-css-prefix}-foursquare:before { content: @fa-var-foursquare; }\n.@{fa-css-prefix}-free-code-camp:before { content: @fa-var-free-code-camp; }\n.@{fa-css-prefix}-freebsd:before { content: @fa-var-freebsd; }\n.@{fa-css-prefix}-frog:before { content: @fa-var-frog; }\n.@{fa-css-prefix}-frown:before { content: @fa-var-frown; }\n.@{fa-css-prefix}-frown-open:before { content: @fa-var-frown-open; }\n.@{fa-css-prefix}-fulcrum:before { content: @fa-var-fulcrum; }\n.@{fa-css-prefix}-funnel-dollar:before { content: @fa-var-funnel-dollar; }\n.@{fa-css-prefix}-futbol:before { content: @fa-var-futbol; }\n.@{fa-css-prefix}-galactic-republic:before { content: @fa-var-galactic-republic; }\n.@{fa-css-prefix}-galactic-senate:before { content: @fa-var-galactic-senate; }\n.@{fa-css-prefix}-gamepad:before { content: @fa-var-gamepad; }\n.@{fa-css-prefix}-gas-pump:before { content: @fa-var-gas-pump; }\n.@{fa-css-prefix}-gavel:before { content: @fa-var-gavel; }\n.@{fa-css-prefix}-gem:before { content: @fa-var-gem; }\n.@{fa-css-prefix}-genderless:before { content: @fa-var-genderless; }\n.@{fa-css-prefix}-get-pocket:before { content: @fa-var-get-pocket; }\n.@{fa-css-prefix}-gg:before { content: @fa-var-gg; }\n.@{fa-css-prefix}-gg-circle:before { content: @fa-var-gg-circle; }\n.@{fa-css-prefix}-ghost:before { content: @fa-var-ghost; }\n.@{fa-css-prefix}-gift:before { content: @fa-var-gift; }\n.@{fa-css-prefix}-gifts:before { content: @fa-var-gifts; }\n.@{fa-css-prefix}-git:before { content: @fa-var-git; }\n.@{fa-css-prefix}-git-alt:before { content: @fa-var-git-alt; }\n.@{fa-css-prefix}-git-square:before { content: @fa-var-git-square; }\n.@{fa-css-prefix}-github:before { content: @fa-var-github; }\n.@{fa-css-prefix}-github-alt:before { content: @fa-var-github-alt; }\n.@{fa-css-prefix}-github-square:before { content: @fa-var-github-square; }\n.@{fa-css-prefix}-gitkraken:before { content: @fa-var-gitkraken; }\n.@{fa-css-prefix}-gitlab:before { content: @fa-var-gitlab; }\n.@{fa-css-prefix}-gitter:before { content: @fa-var-gitter; }\n.@{fa-css-prefix}-glass-cheers:before { content: @fa-var-glass-cheers; }\n.@{fa-css-prefix}-glass-martini:before { content: @fa-var-glass-martini; }\n.@{fa-css-prefix}-glass-martini-alt:before { content: @fa-var-glass-martini-alt; }\n.@{fa-css-prefix}-glass-whiskey:before { content: @fa-var-glass-whiskey; }\n.@{fa-css-prefix}-glasses:before { content: @fa-var-glasses; }\n.@{fa-css-prefix}-glide:before { content: @fa-var-glide; }\n.@{fa-css-prefix}-glide-g:before { content: @fa-var-glide-g; }\n.@{fa-css-prefix}-globe:before { content: @fa-var-globe; }\n.@{fa-css-prefix}-globe-africa:before { content: @fa-var-globe-africa; }\n.@{fa-css-prefix}-globe-americas:before { content: @fa-var-globe-americas; }\n.@{fa-css-prefix}-globe-asia:before { content: @fa-var-globe-asia; }\n.@{fa-css-prefix}-globe-europe:before { content: @fa-var-globe-europe; }\n.@{fa-css-prefix}-gofore:before { content: @fa-var-gofore; }\n.@{fa-css-prefix}-golf-ball:before { content: @fa-var-golf-ball; }\n.@{fa-css-prefix}-goodreads:before { content: @fa-var-goodreads; }\n.@{fa-css-prefix}-goodreads-g:before { content: @fa-var-goodreads-g; }\n.@{fa-css-prefix}-google:before { content: @fa-var-google; }\n.@{fa-css-prefix}-google-drive:before { content: @fa-var-google-drive; }\n.@{fa-css-prefix}-google-play:before { content: @fa-var-google-play; }\n.@{fa-css-prefix}-google-plus:before { content: @fa-var-google-plus; }\n.@{fa-css-prefix}-google-plus-g:before { content: @fa-var-google-plus-g; }\n.@{fa-css-prefix}-google-plus-square:before { content: @fa-var-google-plus-square; }\n.@{fa-css-prefix}-google-wallet:before { content: @fa-var-google-wallet; }\n.@{fa-css-prefix}-gopuram:before { content: @fa-var-gopuram; }\n.@{fa-css-prefix}-graduation-cap:before { content: @fa-var-graduation-cap; }\n.@{fa-css-prefix}-gratipay:before { content: @fa-var-gratipay; }\n.@{fa-css-prefix}-grav:before { content: @fa-var-grav; }\n.@{fa-css-prefix}-greater-than:before { content: @fa-var-greater-than; }\n.@{fa-css-prefix}-greater-than-equal:before { content: @fa-var-greater-than-equal; }\n.@{fa-css-prefix}-grimace:before { content: @fa-var-grimace; }\n.@{fa-css-prefix}-grin:before { content: @fa-var-grin; }\n.@{fa-css-prefix}-grin-alt:before { content: @fa-var-grin-alt; }\n.@{fa-css-prefix}-grin-beam:before { content: @fa-var-grin-beam; }\n.@{fa-css-prefix}-grin-beam-sweat:before { content: @fa-var-grin-beam-sweat; }\n.@{fa-css-prefix}-grin-hearts:before { content: @fa-var-grin-hearts; }\n.@{fa-css-prefix}-grin-squint:before { content: @fa-var-grin-squint; }\n.@{fa-css-prefix}-grin-squint-tears:before { content: @fa-var-grin-squint-tears; }\n.@{fa-css-prefix}-grin-stars:before { content: @fa-var-grin-stars; }\n.@{fa-css-prefix}-grin-tears:before { content: @fa-var-grin-tears; }\n.@{fa-css-prefix}-grin-tongue:before { content: @fa-var-grin-tongue; }\n.@{fa-css-prefix}-grin-tongue-squint:before { content: @fa-var-grin-tongue-squint; }\n.@{fa-css-prefix}-grin-tongue-wink:before { content: @fa-var-grin-tongue-wink; }\n.@{fa-css-prefix}-grin-wink:before { content: @fa-var-grin-wink; }\n.@{fa-css-prefix}-grip-horizontal:before { content: @fa-var-grip-horizontal; }\n.@{fa-css-prefix}-grip-lines:before { content: @fa-var-grip-lines; }\n.@{fa-css-prefix}-grip-lines-vertical:before { content: @fa-var-grip-lines-vertical; }\n.@{fa-css-prefix}-grip-vertical:before { content: @fa-var-grip-vertical; }\n.@{fa-css-prefix}-gripfire:before { content: @fa-var-gripfire; }\n.@{fa-css-prefix}-grunt:before { content: @fa-var-grunt; }\n.@{fa-css-prefix}-guitar:before { content: @fa-var-guitar; }\n.@{fa-css-prefix}-gulp:before { content: @fa-var-gulp; }\n.@{fa-css-prefix}-h-square:before { content: @fa-var-h-square; }\n.@{fa-css-prefix}-hacker-news:before { content: @fa-var-hacker-news; }\n.@{fa-css-prefix}-hacker-news-square:before { content: @fa-var-hacker-news-square; }\n.@{fa-css-prefix}-hackerrank:before { content: @fa-var-hackerrank; }\n.@{fa-css-prefix}-hamburger:before { content: @fa-var-hamburger; }\n.@{fa-css-prefix}-hammer:before { content: @fa-var-hammer; }\n.@{fa-css-prefix}-hamsa:before { content: @fa-var-hamsa; }\n.@{fa-css-prefix}-hand-holding:before { content: @fa-var-hand-holding; }\n.@{fa-css-prefix}-hand-holding-heart:before { content: @fa-var-hand-holding-heart; }\n.@{fa-css-prefix}-hand-holding-usd:before { content: @fa-var-hand-holding-usd; }\n.@{fa-css-prefix}-hand-lizard:before { content: @fa-var-hand-lizard; }\n.@{fa-css-prefix}-hand-middle-finger:before { content: @fa-var-hand-middle-finger; }\n.@{fa-css-prefix}-hand-paper:before { content: @fa-var-hand-paper; }\n.@{fa-css-prefix}-hand-peace:before { content: @fa-var-hand-peace; }\n.@{fa-css-prefix}-hand-point-down:before { content: @fa-var-hand-point-down; }\n.@{fa-css-prefix}-hand-point-left:before { content: @fa-var-hand-point-left; }\n.@{fa-css-prefix}-hand-point-right:before { content: @fa-var-hand-point-right; }\n.@{fa-css-prefix}-hand-point-up:before { content: @fa-var-hand-point-up; }\n.@{fa-css-prefix}-hand-pointer:before { content: @fa-var-hand-pointer; }\n.@{fa-css-prefix}-hand-rock:before { content: @fa-var-hand-rock; }\n.@{fa-css-prefix}-hand-scissors:before { content: @fa-var-hand-scissors; }\n.@{fa-css-prefix}-hand-spock:before { content: @fa-var-hand-spock; }\n.@{fa-css-prefix}-hands:before { content: @fa-var-hands; }\n.@{fa-css-prefix}-hands-helping:before { content: @fa-var-hands-helping; }\n.@{fa-css-prefix}-handshake:before { content: @fa-var-handshake; }\n.@{fa-css-prefix}-hanukiah:before { content: @fa-var-hanukiah; }\n.@{fa-css-prefix}-hard-hat:before { content: @fa-var-hard-hat; }\n.@{fa-css-prefix}-hashtag:before { content: @fa-var-hashtag; }\n.@{fa-css-prefix}-hat-wizard:before { content: @fa-var-hat-wizard; }\n.@{fa-css-prefix}-haykal:before { content: @fa-var-haykal; }\n.@{fa-css-prefix}-hdd:before { content: @fa-var-hdd; }\n.@{fa-css-prefix}-heading:before { content: @fa-var-heading; }\n.@{fa-css-prefix}-headphones:before { content: @fa-var-headphones; }\n.@{fa-css-prefix}-headphones-alt:before { content: @fa-var-headphones-alt; }\n.@{fa-css-prefix}-headset:before { content: @fa-var-headset; }\n.@{fa-css-prefix}-heart:before { content: @fa-var-heart; }\n.@{fa-css-prefix}-heart-broken:before { content: @fa-var-heart-broken; }\n.@{fa-css-prefix}-heartbeat:before { content: @fa-var-heartbeat; }\n.@{fa-css-prefix}-helicopter:before { content: @fa-var-helicopter; }\n.@{fa-css-prefix}-highlighter:before { content: @fa-var-highlighter; }\n.@{fa-css-prefix}-hiking:before { content: @fa-var-hiking; }\n.@{fa-css-prefix}-hippo:before { content: @fa-var-hippo; }\n.@{fa-css-prefix}-hips:before { content: @fa-var-hips; }\n.@{fa-css-prefix}-hire-a-helper:before { content: @fa-var-hire-a-helper; }\n.@{fa-css-prefix}-history:before { content: @fa-var-history; }\n.@{fa-css-prefix}-hockey-puck:before { content: @fa-var-hockey-puck; }\n.@{fa-css-prefix}-holly-berry:before { content: @fa-var-holly-berry; }\n.@{fa-css-prefix}-home:before { content: @fa-var-home; }\n.@{fa-css-prefix}-hooli:before { content: @fa-var-hooli; }\n.@{fa-css-prefix}-hornbill:before { content: @fa-var-hornbill; }\n.@{fa-css-prefix}-horse:before { content: @fa-var-horse; }\n.@{fa-css-prefix}-horse-head:before { content: @fa-var-horse-head; }\n.@{fa-css-prefix}-hospital:before { content: @fa-var-hospital; }\n.@{fa-css-prefix}-hospital-alt:before { content: @fa-var-hospital-alt; }\n.@{fa-css-prefix}-hospital-symbol:before { content: @fa-var-hospital-symbol; }\n.@{fa-css-prefix}-hot-tub:before { content: @fa-var-hot-tub; }\n.@{fa-css-prefix}-hotdog:before { content: @fa-var-hotdog; }\n.@{fa-css-prefix}-hotel:before { content: @fa-var-hotel; }\n.@{fa-css-prefix}-hotjar:before { content: @fa-var-hotjar; }\n.@{fa-css-prefix}-hourglass:before { content: @fa-var-hourglass; }\n.@{fa-css-prefix}-hourglass-end:before { content: @fa-var-hourglass-end; }\n.@{fa-css-prefix}-hourglass-half:before { content: @fa-var-hourglass-half; }\n.@{fa-css-prefix}-hourglass-start:before { content: @fa-var-hourglass-start; }\n.@{fa-css-prefix}-house-damage:before { content: @fa-var-house-damage; }\n.@{fa-css-prefix}-houzz:before { content: @fa-var-houzz; }\n.@{fa-css-prefix}-hryvnia:before { content: @fa-var-hryvnia; }\n.@{fa-css-prefix}-html5:before { content: @fa-var-html5; }\n.@{fa-css-prefix}-hubspot:before { content: @fa-var-hubspot; }\n.@{fa-css-prefix}-i-cursor:before { content: @fa-var-i-cursor; }\n.@{fa-css-prefix}-ice-cream:before { content: @fa-var-ice-cream; }\n.@{fa-css-prefix}-icicles:before { content: @fa-var-icicles; }\n.@{fa-css-prefix}-icons:before { content: @fa-var-icons; }\n.@{fa-css-prefix}-id-badge:before { content: @fa-var-id-badge; }\n.@{fa-css-prefix}-id-card:before { content: @fa-var-id-card; }\n.@{fa-css-prefix}-id-card-alt:before { content: @fa-var-id-card-alt; }\n.@{fa-css-prefix}-igloo:before { content: @fa-var-igloo; }\n.@{fa-css-prefix}-image:before { content: @fa-var-image; }\n.@{fa-css-prefix}-images:before { content: @fa-var-images; }\n.@{fa-css-prefix}-imdb:before { content: @fa-var-imdb; }\n.@{fa-css-prefix}-inbox:before { content: @fa-var-inbox; }\n.@{fa-css-prefix}-indent:before { content: @fa-var-indent; }\n.@{fa-css-prefix}-industry:before { content: @fa-var-industry; }\n.@{fa-css-prefix}-infinity:before { content: @fa-var-infinity; }\n.@{fa-css-prefix}-info:before { content: @fa-var-info; }\n.@{fa-css-prefix}-info-circle:before { content: @fa-var-info-circle; }\n.@{fa-css-prefix}-instagram:before { content: @fa-var-instagram; }\n.@{fa-css-prefix}-intercom:before { content: @fa-var-intercom; }\n.@{fa-css-prefix}-internet-explorer:before { content: @fa-var-internet-explorer; }\n.@{fa-css-prefix}-invision:before { content: @fa-var-invision; }\n.@{fa-css-prefix}-ioxhost:before { content: @fa-var-ioxhost; }\n.@{fa-css-prefix}-italic:before { content: @fa-var-italic; }\n.@{fa-css-prefix}-itch-io:before { content: @fa-var-itch-io; }\n.@{fa-css-prefix}-itunes:before { content: @fa-var-itunes; }\n.@{fa-css-prefix}-itunes-note:before { content: @fa-var-itunes-note; }\n.@{fa-css-prefix}-java:before { content: @fa-var-java; }\n.@{fa-css-prefix}-jedi:before { content: @fa-var-jedi; }\n.@{fa-css-prefix}-jedi-order:before { content: @fa-var-jedi-order; }\n.@{fa-css-prefix}-jenkins:before { content: @fa-var-jenkins; }\n.@{fa-css-prefix}-jira:before { content: @fa-var-jira; }\n.@{fa-css-prefix}-joget:before { content: @fa-var-joget; }\n.@{fa-css-prefix}-joint:before { content: @fa-var-joint; }\n.@{fa-css-prefix}-joomla:before { content: @fa-var-joomla; }\n.@{fa-css-prefix}-journal-whills:before { content: @fa-var-journal-whills; }\n.@{fa-css-prefix}-js:before { content: @fa-var-js; }\n.@{fa-css-prefix}-js-square:before { content: @fa-var-js-square; }\n.@{fa-css-prefix}-jsfiddle:before { content: @fa-var-jsfiddle; }\n.@{fa-css-prefix}-kaaba:before { content: @fa-var-kaaba; }\n.@{fa-css-prefix}-kaggle:before { content: @fa-var-kaggle; }\n.@{fa-css-prefix}-key:before { content: @fa-var-key; }\n.@{fa-css-prefix}-keybase:before { content: @fa-var-keybase; }\n.@{fa-css-prefix}-keyboard:before { content: @fa-var-keyboard; }\n.@{fa-css-prefix}-keycdn:before { content: @fa-var-keycdn; }\n.@{fa-css-prefix}-khanda:before { content: @fa-var-khanda; }\n.@{fa-css-prefix}-kickstarter:before { content: @fa-var-kickstarter; }\n.@{fa-css-prefix}-kickstarter-k:before { content: @fa-var-kickstarter-k; }\n.@{fa-css-prefix}-kiss:before { content: @fa-var-kiss; }\n.@{fa-css-prefix}-kiss-beam:before { content: @fa-var-kiss-beam; }\n.@{fa-css-prefix}-kiss-wink-heart:before { content: @fa-var-kiss-wink-heart; }\n.@{fa-css-prefix}-kiwi-bird:before { content: @fa-var-kiwi-bird; }\n.@{fa-css-prefix}-korvue:before { content: @fa-var-korvue; }\n.@{fa-css-prefix}-landmark:before { content: @fa-var-landmark; }\n.@{fa-css-prefix}-language:before { content: @fa-var-language; }\n.@{fa-css-prefix}-laptop:before { content: @fa-var-laptop; }\n.@{fa-css-prefix}-laptop-code:before { content: @fa-var-laptop-code; }\n.@{fa-css-prefix}-laptop-medical:before { content: @fa-var-laptop-medical; }\n.@{fa-css-prefix}-laravel:before { content: @fa-var-laravel; }\n.@{fa-css-prefix}-lastfm:before { content: @fa-var-lastfm; }\n.@{fa-css-prefix}-lastfm-square:before { content: @fa-var-lastfm-square; }\n.@{fa-css-prefix}-laugh:before { content: @fa-var-laugh; }\n.@{fa-css-prefix}-laugh-beam:before { content: @fa-var-laugh-beam; }\n.@{fa-css-prefix}-laugh-squint:before { content: @fa-var-laugh-squint; }\n.@{fa-css-prefix}-laugh-wink:before { content: @fa-var-laugh-wink; }\n.@{fa-css-prefix}-layer-group:before { content: @fa-var-layer-group; }\n.@{fa-css-prefix}-leaf:before { content: @fa-var-leaf; }\n.@{fa-css-prefix}-leanpub:before { content: @fa-var-leanpub; }\n.@{fa-css-prefix}-lemon:before { content: @fa-var-lemon; }\n.@{fa-css-prefix}-less:before { content: @fa-var-less; }\n.@{fa-css-prefix}-less-than:before { content: @fa-var-less-than; }\n.@{fa-css-prefix}-less-than-equal:before { content: @fa-var-less-than-equal; }\n.@{fa-css-prefix}-level-down-alt:before { content: @fa-var-level-down-alt; }\n.@{fa-css-prefix}-level-up-alt:before { content: @fa-var-level-up-alt; }\n.@{fa-css-prefix}-life-ring:before { content: @fa-var-life-ring; }\n.@{fa-css-prefix}-lightbulb:before { content: @fa-var-lightbulb; }\n.@{fa-css-prefix}-line:before { content: @fa-var-line; }\n.@{fa-css-prefix}-link:before { content: @fa-var-link; }\n.@{fa-css-prefix}-linkedin:before { content: @fa-var-linkedin; }\n.@{fa-css-prefix}-linkedin-in:before { content: @fa-var-linkedin-in; }\n.@{fa-css-prefix}-linode:before { content: @fa-var-linode; }\n.@{fa-css-prefix}-linux:before { content: @fa-var-linux; }\n.@{fa-css-prefix}-lira-sign:before { content: @fa-var-lira-sign; }\n.@{fa-css-prefix}-list:before { content: @fa-var-list; }\n.@{fa-css-prefix}-list-alt:before { content: @fa-var-list-alt; }\n.@{fa-css-prefix}-list-ol:before { content: @fa-var-list-ol; }\n.@{fa-css-prefix}-list-ul:before { content: @fa-var-list-ul; }\n.@{fa-css-prefix}-location-arrow:before { content: @fa-var-location-arrow; }\n.@{fa-css-prefix}-lock:before { content: @fa-var-lock; }\n.@{fa-css-prefix}-lock-open:before { content: @fa-var-lock-open; }\n.@{fa-css-prefix}-long-arrow-alt-down:before { content: @fa-var-long-arrow-alt-down; }\n.@{fa-css-prefix}-long-arrow-alt-left:before { content: @fa-var-long-arrow-alt-left; }\n.@{fa-css-prefix}-long-arrow-alt-right:before { content: @fa-var-long-arrow-alt-right; }\n.@{fa-css-prefix}-long-arrow-alt-up:before { content: @fa-var-long-arrow-alt-up; }\n.@{fa-css-prefix}-low-vision:before { content: @fa-var-low-vision; }\n.@{fa-css-prefix}-luggage-cart:before { content: @fa-var-luggage-cart; }\n.@{fa-css-prefix}-lyft:before { content: @fa-var-lyft; }\n.@{fa-css-prefix}-magento:before { content: @fa-var-magento; }\n.@{fa-css-prefix}-magic:before { content: @fa-var-magic; }\n.@{fa-css-prefix}-magnet:before { content: @fa-var-magnet; }\n.@{fa-css-prefix}-mail-bulk:before { content: @fa-var-mail-bulk; }\n.@{fa-css-prefix}-mailchimp:before { content: @fa-var-mailchimp; }\n.@{fa-css-prefix}-male:before { content: @fa-var-male; }\n.@{fa-css-prefix}-mandalorian:before { content: @fa-var-mandalorian; }\n.@{fa-css-prefix}-map:before { content: @fa-var-map; }\n.@{fa-css-prefix}-map-marked:before { content: @fa-var-map-marked; }\n.@{fa-css-prefix}-map-marked-alt:before { content: @fa-var-map-marked-alt; }\n.@{fa-css-prefix}-map-marker:before { content: @fa-var-map-marker; }\n.@{fa-css-prefix}-map-marker-alt:before { content: @fa-var-map-marker-alt; }\n.@{fa-css-prefix}-map-pin:before { content: @fa-var-map-pin; }\n.@{fa-css-prefix}-map-signs:before { content: @fa-var-map-signs; }\n.@{fa-css-prefix}-markdown:before { content: @fa-var-markdown; }\n.@{fa-css-prefix}-marker:before { content: @fa-var-marker; }\n.@{fa-css-prefix}-mars:before { content: @fa-var-mars; }\n.@{fa-css-prefix}-mars-double:before { content: @fa-var-mars-double; }\n.@{fa-css-prefix}-mars-stroke:before { content: @fa-var-mars-stroke; }\n.@{fa-css-prefix}-mars-stroke-h:before { content: @fa-var-mars-stroke-h; }\n.@{fa-css-prefix}-mars-stroke-v:before { content: @fa-var-mars-stroke-v; }\n.@{fa-css-prefix}-mask:before { content: @fa-var-mask; }\n.@{fa-css-prefix}-mastodon:before { content: @fa-var-mastodon; }\n.@{fa-css-prefix}-maxcdn:before { content: @fa-var-maxcdn; }\n.@{fa-css-prefix}-medal:before { content: @fa-var-medal; }\n.@{fa-css-prefix}-medapps:before { content: @fa-var-medapps; }\n.@{fa-css-prefix}-medium:before { content: @fa-var-medium; }\n.@{fa-css-prefix}-medium-m:before { content: @fa-var-medium-m; }\n.@{fa-css-prefix}-medkit:before { content: @fa-var-medkit; }\n.@{fa-css-prefix}-medrt:before { content: @fa-var-medrt; }\n.@{fa-css-prefix}-meetup:before { content: @fa-var-meetup; }\n.@{fa-css-prefix}-megaport:before { content: @fa-var-megaport; }\n.@{fa-css-prefix}-meh:before { content: @fa-var-meh; }\n.@{fa-css-prefix}-meh-blank:before { content: @fa-var-meh-blank; }\n.@{fa-css-prefix}-meh-rolling-eyes:before { content: @fa-var-meh-rolling-eyes; }\n.@{fa-css-prefix}-memory:before { content: @fa-var-memory; }\n.@{fa-css-prefix}-mendeley:before { content: @fa-var-mendeley; }\n.@{fa-css-prefix}-menorah:before { content: @fa-var-menorah; }\n.@{fa-css-prefix}-mercury:before { content: @fa-var-mercury; }\n.@{fa-css-prefix}-meteor:before { content: @fa-var-meteor; }\n.@{fa-css-prefix}-microchip:before { content: @fa-var-microchip; }\n.@{fa-css-prefix}-microphone:before { content: @fa-var-microphone; }\n.@{fa-css-prefix}-microphone-alt:before { content: @fa-var-microphone-alt; }\n.@{fa-css-prefix}-microphone-alt-slash:before { content: @fa-var-microphone-alt-slash; }\n.@{fa-css-prefix}-microphone-slash:before { content: @fa-var-microphone-slash; }\n.@{fa-css-prefix}-microscope:before { content: @fa-var-microscope; }\n.@{fa-css-prefix}-microsoft:before { content: @fa-var-microsoft; }\n.@{fa-css-prefix}-minus:before { content: @fa-var-minus; }\n.@{fa-css-prefix}-minus-circle:before { content: @fa-var-minus-circle; }\n.@{fa-css-prefix}-minus-square:before { content: @fa-var-minus-square; }\n.@{fa-css-prefix}-mitten:before { content: @fa-var-mitten; }\n.@{fa-css-prefix}-mix:before { content: @fa-var-mix; }\n.@{fa-css-prefix}-mixcloud:before { content: @fa-var-mixcloud; }\n.@{fa-css-prefix}-mizuni:before { content: @fa-var-mizuni; }\n.@{fa-css-prefix}-mobile:before { content: @fa-var-mobile; }\n.@{fa-css-prefix}-mobile-alt:before { content: @fa-var-mobile-alt; }\n.@{fa-css-prefix}-modx:before { content: @fa-var-modx; }\n.@{fa-css-prefix}-monero:before { content: @fa-var-monero; }\n.@{fa-css-prefix}-money-bill:before { content: @fa-var-money-bill; }\n.@{fa-css-prefix}-money-bill-alt:before { content: @fa-var-money-bill-alt; }\n.@{fa-css-prefix}-money-bill-wave:before { content: @fa-var-money-bill-wave; }\n.@{fa-css-prefix}-money-bill-wave-alt:before { content: @fa-var-money-bill-wave-alt; }\n.@{fa-css-prefix}-money-check:before { content: @fa-var-money-check; }\n.@{fa-css-prefix}-money-check-alt:before { content: @fa-var-money-check-alt; }\n.@{fa-css-prefix}-monument:before { content: @fa-var-monument; }\n.@{fa-css-prefix}-moon:before { content: @fa-var-moon; }\n.@{fa-css-prefix}-mortar-pestle:before { content: @fa-var-mortar-pestle; }\n.@{fa-css-prefix}-mosque:before { content: @fa-var-mosque; }\n.@{fa-css-prefix}-motorcycle:before { content: @fa-var-motorcycle; }\n.@{fa-css-prefix}-mountain:before { content: @fa-var-mountain; }\n.@{fa-css-prefix}-mouse-pointer:before { content: @fa-var-mouse-pointer; }\n.@{fa-css-prefix}-mug-hot:before { content: @fa-var-mug-hot; }\n.@{fa-css-prefix}-music:before { content: @fa-var-music; }\n.@{fa-css-prefix}-napster:before { content: @fa-var-napster; }\n.@{fa-css-prefix}-neos:before { content: @fa-var-neos; }\n.@{fa-css-prefix}-network-wired:before { content: @fa-var-network-wired; }\n.@{fa-css-prefix}-neuter:before { content: @fa-var-neuter; }\n.@{fa-css-prefix}-newspaper:before { content: @fa-var-newspaper; }\n.@{fa-css-prefix}-nimblr:before { content: @fa-var-nimblr; }\n.@{fa-css-prefix}-node:before { content: @fa-var-node; }\n.@{fa-css-prefix}-node-js:before { content: @fa-var-node-js; }\n.@{fa-css-prefix}-not-equal:before { content: @fa-var-not-equal; }\n.@{fa-css-prefix}-notes-medical:before { content: @fa-var-notes-medical; }\n.@{fa-css-prefix}-npm:before { content: @fa-var-npm; }\n.@{fa-css-prefix}-ns8:before { content: @fa-var-ns8; }\n.@{fa-css-prefix}-nutritionix:before { content: @fa-var-nutritionix; }\n.@{fa-css-prefix}-object-group:before { content: @fa-var-object-group; }\n.@{fa-css-prefix}-object-ungroup:before { content: @fa-var-object-ungroup; }\n.@{fa-css-prefix}-odnoklassniki:before { content: @fa-var-odnoklassniki; }\n.@{fa-css-prefix}-odnoklassniki-square:before { content: @fa-var-odnoklassniki-square; }\n.@{fa-css-prefix}-oil-can:before { content: @fa-var-oil-can; }\n.@{fa-css-prefix}-old-republic:before { content: @fa-var-old-republic; }\n.@{fa-css-prefix}-om:before { content: @fa-var-om; }\n.@{fa-css-prefix}-opencart:before { content: @fa-var-opencart; }\n.@{fa-css-prefix}-openid:before { content: @fa-var-openid; }\n.@{fa-css-prefix}-opera:before { content: @fa-var-opera; }\n.@{fa-css-prefix}-optin-monster:before { content: @fa-var-optin-monster; }\n.@{fa-css-prefix}-osi:before { content: @fa-var-osi; }\n.@{fa-css-prefix}-otter:before { content: @fa-var-otter; }\n.@{fa-css-prefix}-outdent:before { content: @fa-var-outdent; }\n.@{fa-css-prefix}-page4:before { content: @fa-var-page4; }\n.@{fa-css-prefix}-pagelines:before { content: @fa-var-pagelines; }\n.@{fa-css-prefix}-pager:before { content: @fa-var-pager; }\n.@{fa-css-prefix}-paint-brush:before { content: @fa-var-paint-brush; }\n.@{fa-css-prefix}-paint-roller:before { content: @fa-var-paint-roller; }\n.@{fa-css-prefix}-palette:before { content: @fa-var-palette; }\n.@{fa-css-prefix}-palfed:before { content: @fa-var-palfed; }\n.@{fa-css-prefix}-pallet:before { content: @fa-var-pallet; }\n.@{fa-css-prefix}-paper-plane:before { content: @fa-var-paper-plane; }\n.@{fa-css-prefix}-paperclip:before { content: @fa-var-paperclip; }\n.@{fa-css-prefix}-parachute-box:before { content: @fa-var-parachute-box; }\n.@{fa-css-prefix}-paragraph:before { content: @fa-var-paragraph; }\n.@{fa-css-prefix}-parking:before { content: @fa-var-parking; }\n.@{fa-css-prefix}-passport:before { content: @fa-var-passport; }\n.@{fa-css-prefix}-pastafarianism:before { content: @fa-var-pastafarianism; }\n.@{fa-css-prefix}-paste:before { content: @fa-var-paste; }\n.@{fa-css-prefix}-patreon:before { content: @fa-var-patreon; }\n.@{fa-css-prefix}-pause:before { content: @fa-var-pause; }\n.@{fa-css-prefix}-pause-circle:before { content: @fa-var-pause-circle; }\n.@{fa-css-prefix}-paw:before { content: @fa-var-paw; }\n.@{fa-css-prefix}-paypal:before { content: @fa-var-paypal; }\n.@{fa-css-prefix}-peace:before { content: @fa-var-peace; }\n.@{fa-css-prefix}-pen:before { content: @fa-var-pen; }\n.@{fa-css-prefix}-pen-alt:before { content: @fa-var-pen-alt; }\n.@{fa-css-prefix}-pen-fancy:before { content: @fa-var-pen-fancy; }\n.@{fa-css-prefix}-pen-nib:before { content: @fa-var-pen-nib; }\n.@{fa-css-prefix}-pen-square:before { content: @fa-var-pen-square; }\n.@{fa-css-prefix}-pencil-alt:before { content: @fa-var-pencil-alt; }\n.@{fa-css-prefix}-pencil-ruler:before { content: @fa-var-pencil-ruler; }\n.@{fa-css-prefix}-penny-arcade:before { content: @fa-var-penny-arcade; }\n.@{fa-css-prefix}-people-carry:before { content: @fa-var-people-carry; }\n.@{fa-css-prefix}-pepper-hot:before { content: @fa-var-pepper-hot; }\n.@{fa-css-prefix}-percent:before { content: @fa-var-percent; }\n.@{fa-css-prefix}-percentage:before { content: @fa-var-percentage; }\n.@{fa-css-prefix}-periscope:before { content: @fa-var-periscope; }\n.@{fa-css-prefix}-person-booth:before { content: @fa-var-person-booth; }\n.@{fa-css-prefix}-phabricator:before { content: @fa-var-phabricator; }\n.@{fa-css-prefix}-phoenix-framework:before { content: @fa-var-phoenix-framework; }\n.@{fa-css-prefix}-phoenix-squadron:before { content: @fa-var-phoenix-squadron; }\n.@{fa-css-prefix}-phone:before { content: @fa-var-phone; }\n.@{fa-css-prefix}-phone-alt:before { content: @fa-var-phone-alt; }\n.@{fa-css-prefix}-phone-slash:before { content: @fa-var-phone-slash; }\n.@{fa-css-prefix}-phone-square:before { content: @fa-var-phone-square; }\n.@{fa-css-prefix}-phone-square-alt:before { content: @fa-var-phone-square-alt; }\n.@{fa-css-prefix}-phone-volume:before { content: @fa-var-phone-volume; }\n.@{fa-css-prefix}-photo-video:before { content: @fa-var-photo-video; }\n.@{fa-css-prefix}-php:before { content: @fa-var-php; }\n.@{fa-css-prefix}-pied-piper:before { content: @fa-var-pied-piper; }\n.@{fa-css-prefix}-pied-piper-alt:before { content: @fa-var-pied-piper-alt; }\n.@{fa-css-prefix}-pied-piper-hat:before { content: @fa-var-pied-piper-hat; }\n.@{fa-css-prefix}-pied-piper-pp:before { content: @fa-var-pied-piper-pp; }\n.@{fa-css-prefix}-piggy-bank:before { content: @fa-var-piggy-bank; }\n.@{fa-css-prefix}-pills:before { content: @fa-var-pills; }\n.@{fa-css-prefix}-pinterest:before { content: @fa-var-pinterest; }\n.@{fa-css-prefix}-pinterest-p:before { content: @fa-var-pinterest-p; }\n.@{fa-css-prefix}-pinterest-square:before { content: @fa-var-pinterest-square; }\n.@{fa-css-prefix}-pizza-slice:before { content: @fa-var-pizza-slice; }\n.@{fa-css-prefix}-place-of-worship:before { content: @fa-var-place-of-worship; }\n.@{fa-css-prefix}-plane:before { content: @fa-var-plane; }\n.@{fa-css-prefix}-plane-arrival:before { content: @fa-var-plane-arrival; }\n.@{fa-css-prefix}-plane-departure:before { content: @fa-var-plane-departure; }\n.@{fa-css-prefix}-play:before { content: @fa-var-play; }\n.@{fa-css-prefix}-play-circle:before { content: @fa-var-play-circle; }\n.@{fa-css-prefix}-playstation:before { content: @fa-var-playstation; }\n.@{fa-css-prefix}-plug:before { content: @fa-var-plug; }\n.@{fa-css-prefix}-plus:before { content: @fa-var-plus; }\n.@{fa-css-prefix}-plus-circle:before { content: @fa-var-plus-circle; }\n.@{fa-css-prefix}-plus-square:before { content: @fa-var-plus-square; }\n.@{fa-css-prefix}-podcast:before { content: @fa-var-podcast; }\n.@{fa-css-prefix}-poll:before { content: @fa-var-poll; }\n.@{fa-css-prefix}-poll-h:before { content: @fa-var-poll-h; }\n.@{fa-css-prefix}-poo:before { content: @fa-var-poo; }\n.@{fa-css-prefix}-poo-storm:before { content: @fa-var-poo-storm; }\n.@{fa-css-prefix}-poop:before { content: @fa-var-poop; }\n.@{fa-css-prefix}-portrait:before { content: @fa-var-portrait; }\n.@{fa-css-prefix}-pound-sign:before { content: @fa-var-pound-sign; }\n.@{fa-css-prefix}-power-off:before { content: @fa-var-power-off; }\n.@{fa-css-prefix}-pray:before { content: @fa-var-pray; }\n.@{fa-css-prefix}-praying-hands:before { content: @fa-var-praying-hands; }\n.@{fa-css-prefix}-prescription:before { content: @fa-var-prescription; }\n.@{fa-css-prefix}-prescription-bottle:before { content: @fa-var-prescription-bottle; }\n.@{fa-css-prefix}-prescription-bottle-alt:before { content: @fa-var-prescription-bottle-alt; }\n.@{fa-css-prefix}-print:before { content: @fa-var-print; }\n.@{fa-css-prefix}-procedures:before { content: @fa-var-procedures; }\n.@{fa-css-prefix}-product-hunt:before { content: @fa-var-product-hunt; }\n.@{fa-css-prefix}-project-diagram:before { content: @fa-var-project-diagram; }\n.@{fa-css-prefix}-pushed:before { content: @fa-var-pushed; }\n.@{fa-css-prefix}-puzzle-piece:before { content: @fa-var-puzzle-piece; }\n.@{fa-css-prefix}-python:before { content: @fa-var-python; }\n.@{fa-css-prefix}-qq:before { content: @fa-var-qq; }\n.@{fa-css-prefix}-qrcode:before { content: @fa-var-qrcode; }\n.@{fa-css-prefix}-question:before { content: @fa-var-question; }\n.@{fa-css-prefix}-question-circle:before { content: @fa-var-question-circle; }\n.@{fa-css-prefix}-quidditch:before { content: @fa-var-quidditch; }\n.@{fa-css-prefix}-quinscape:before { content: @fa-var-quinscape; }\n.@{fa-css-prefix}-quora:before { content: @fa-var-quora; }\n.@{fa-css-prefix}-quote-left:before { content: @fa-var-quote-left; }\n.@{fa-css-prefix}-quote-right:before { content: @fa-var-quote-right; }\n.@{fa-css-prefix}-quran:before { content: @fa-var-quran; }\n.@{fa-css-prefix}-r-project:before { content: @fa-var-r-project; }\n.@{fa-css-prefix}-radiation:before { content: @fa-var-radiation; }\n.@{fa-css-prefix}-radiation-alt:before { content: @fa-var-radiation-alt; }\n.@{fa-css-prefix}-rainbow:before { content: @fa-var-rainbow; }\n.@{fa-css-prefix}-random:before { content: @fa-var-random; }\n.@{fa-css-prefix}-raspberry-pi:before { content: @fa-var-raspberry-pi; }\n.@{fa-css-prefix}-ravelry:before { content: @fa-var-ravelry; }\n.@{fa-css-prefix}-react:before { content: @fa-var-react; }\n.@{fa-css-prefix}-reacteurope:before { content: @fa-var-reacteurope; }\n.@{fa-css-prefix}-readme:before { content: @fa-var-readme; }\n.@{fa-css-prefix}-rebel:before { content: @fa-var-rebel; }\n.@{fa-css-prefix}-receipt:before { content: @fa-var-receipt; }\n.@{fa-css-prefix}-recycle:before { content: @fa-var-recycle; }\n.@{fa-css-prefix}-red-river:before { content: @fa-var-red-river; }\n.@{fa-css-prefix}-reddit:before { content: @fa-var-reddit; }\n.@{fa-css-prefix}-reddit-alien:before { content: @fa-var-reddit-alien; }\n.@{fa-css-prefix}-reddit-square:before { content: @fa-var-reddit-square; }\n.@{fa-css-prefix}-redhat:before { content: @fa-var-redhat; }\n.@{fa-css-prefix}-redo:before { content: @fa-var-redo; }\n.@{fa-css-prefix}-redo-alt:before { content: @fa-var-redo-alt; }\n.@{fa-css-prefix}-registered:before { content: @fa-var-registered; }\n.@{fa-css-prefix}-remove-format:before { content: @fa-var-remove-format; }\n.@{fa-css-prefix}-renren:before { content: @fa-var-renren; }\n.@{fa-css-prefix}-reply:before { content: @fa-var-reply; }\n.@{fa-css-prefix}-reply-all:before { content: @fa-var-reply-all; }\n.@{fa-css-prefix}-replyd:before { content: @fa-var-replyd; }\n.@{fa-css-prefix}-republican:before { content: @fa-var-republican; }\n.@{fa-css-prefix}-researchgate:before { content: @fa-var-researchgate; }\n.@{fa-css-prefix}-resolving:before { content: @fa-var-resolving; }\n.@{fa-css-prefix}-restroom:before { content: @fa-var-restroom; }\n.@{fa-css-prefix}-retweet:before { content: @fa-var-retweet; }\n.@{fa-css-prefix}-rev:before { content: @fa-var-rev; }\n.@{fa-css-prefix}-ribbon:before { content: @fa-var-ribbon; }\n.@{fa-css-prefix}-ring:before { content: @fa-var-ring; }\n.@{fa-css-prefix}-road:before { content: @fa-var-road; }\n.@{fa-css-prefix}-robot:before { content: @fa-var-robot; }\n.@{fa-css-prefix}-rocket:before { content: @fa-var-rocket; }\n.@{fa-css-prefix}-rocketchat:before { content: @fa-var-rocketchat; }\n.@{fa-css-prefix}-rockrms:before { content: @fa-var-rockrms; }\n.@{fa-css-prefix}-route:before { content: @fa-var-route; }\n.@{fa-css-prefix}-rss:before { content: @fa-var-rss; }\n.@{fa-css-prefix}-rss-square:before { content: @fa-var-rss-square; }\n.@{fa-css-prefix}-ruble-sign:before { content: @fa-var-ruble-sign; }\n.@{fa-css-prefix}-ruler:before { content: @fa-var-ruler; }\n.@{fa-css-prefix}-ruler-combined:before { content: @fa-var-ruler-combined; }\n.@{fa-css-prefix}-ruler-horizontal:before { content: @fa-var-ruler-horizontal; }\n.@{fa-css-prefix}-ruler-vertical:before { content: @fa-var-ruler-vertical; }\n.@{fa-css-prefix}-running:before { content: @fa-var-running; }\n.@{fa-css-prefix}-rupee-sign:before { content: @fa-var-rupee-sign; }\n.@{fa-css-prefix}-sad-cry:before { content: @fa-var-sad-cry; }\n.@{fa-css-prefix}-sad-tear:before { content: @fa-var-sad-tear; }\n.@{fa-css-prefix}-safari:before { content: @fa-var-safari; }\n.@{fa-css-prefix}-salesforce:before { content: @fa-var-salesforce; }\n.@{fa-css-prefix}-sass:before { content: @fa-var-sass; }\n.@{fa-css-prefix}-satellite:before { content: @fa-var-satellite; }\n.@{fa-css-prefix}-satellite-dish:before { content: @fa-var-satellite-dish; }\n.@{fa-css-prefix}-save:before { content: @fa-var-save; }\n.@{fa-css-prefix}-schlix:before { content: @fa-var-schlix; }\n.@{fa-css-prefix}-school:before { content: @fa-var-school; }\n.@{fa-css-prefix}-screwdriver:before { content: @fa-var-screwdriver; }\n.@{fa-css-prefix}-scribd:before { content: @fa-var-scribd; }\n.@{fa-css-prefix}-scroll:before { content: @fa-var-scroll; }\n.@{fa-css-prefix}-sd-card:before { content: @fa-var-sd-card; }\n.@{fa-css-prefix}-search:before { content: @fa-var-search; }\n.@{fa-css-prefix}-search-dollar:before { content: @fa-var-search-dollar; }\n.@{fa-css-prefix}-search-location:before { content: @fa-var-search-location; }\n.@{fa-css-prefix}-search-minus:before { content: @fa-var-search-minus; }\n.@{fa-css-prefix}-search-plus:before { content: @fa-var-search-plus; }\n.@{fa-css-prefix}-searchengin:before { content: @fa-var-searchengin; }\n.@{fa-css-prefix}-seedling:before { content: @fa-var-seedling; }\n.@{fa-css-prefix}-sellcast:before { content: @fa-var-sellcast; }\n.@{fa-css-prefix}-sellsy:before { content: @fa-var-sellsy; }\n.@{fa-css-prefix}-server:before { content: @fa-var-server; }\n.@{fa-css-prefix}-servicestack:before { content: @fa-var-servicestack; }\n.@{fa-css-prefix}-shapes:before { content: @fa-var-shapes; }\n.@{fa-css-prefix}-share:before { content: @fa-var-share; }\n.@{fa-css-prefix}-share-alt:before { content: @fa-var-share-alt; }\n.@{fa-css-prefix}-share-alt-square:before { content: @fa-var-share-alt-square; }\n.@{fa-css-prefix}-share-square:before { content: @fa-var-share-square; }\n.@{fa-css-prefix}-shekel-sign:before { content: @fa-var-shekel-sign; }\n.@{fa-css-prefix}-shield-alt:before { content: @fa-var-shield-alt; }\n.@{fa-css-prefix}-ship:before { content: @fa-var-ship; }\n.@{fa-css-prefix}-shipping-fast:before { content: @fa-var-shipping-fast; }\n.@{fa-css-prefix}-shirtsinbulk:before { content: @fa-var-shirtsinbulk; }\n.@{fa-css-prefix}-shoe-prints:before { content: @fa-var-shoe-prints; }\n.@{fa-css-prefix}-shopping-bag:before { content: @fa-var-shopping-bag; }\n.@{fa-css-prefix}-shopping-basket:before { content: @fa-var-shopping-basket; }\n.@{fa-css-prefix}-shopping-cart:before { content: @fa-var-shopping-cart; }\n.@{fa-css-prefix}-shopware:before { content: @fa-var-shopware; }\n.@{fa-css-prefix}-shower:before { content: @fa-var-shower; }\n.@{fa-css-prefix}-shuttle-van:before { content: @fa-var-shuttle-van; }\n.@{fa-css-prefix}-sign:before { content: @fa-var-sign; }\n.@{fa-css-prefix}-sign-in-alt:before { content: @fa-var-sign-in-alt; }\n.@{fa-css-prefix}-sign-language:before { content: @fa-var-sign-language; }\n.@{fa-css-prefix}-sign-out-alt:before { content: @fa-var-sign-out-alt; }\n.@{fa-css-prefix}-signal:before { content: @fa-var-signal; }\n.@{fa-css-prefix}-signature:before { content: @fa-var-signature; }\n.@{fa-css-prefix}-sim-card:before { content: @fa-var-sim-card; }\n.@{fa-css-prefix}-simplybuilt:before { content: @fa-var-simplybuilt; }\n.@{fa-css-prefix}-sistrix:before { content: @fa-var-sistrix; }\n.@{fa-css-prefix}-sitemap:before { content: @fa-var-sitemap; }\n.@{fa-css-prefix}-sith:before { content: @fa-var-sith; }\n.@{fa-css-prefix}-skating:before { content: @fa-var-skating; }\n.@{fa-css-prefix}-sketch:before { content: @fa-var-sketch; }\n.@{fa-css-prefix}-skiing:before { content: @fa-var-skiing; }\n.@{fa-css-prefix}-skiing-nordic:before { content: @fa-var-skiing-nordic; }\n.@{fa-css-prefix}-skull:before { content: @fa-var-skull; }\n.@{fa-css-prefix}-skull-crossbones:before { content: @fa-var-skull-crossbones; }\n.@{fa-css-prefix}-skyatlas:before { content: @fa-var-skyatlas; }\n.@{fa-css-prefix}-skype:before { content: @fa-var-skype; }\n.@{fa-css-prefix}-slack:before { content: @fa-var-slack; }\n.@{fa-css-prefix}-slack-hash:before { content: @fa-var-slack-hash; }\n.@{fa-css-prefix}-slash:before { content: @fa-var-slash; }\n.@{fa-css-prefix}-sleigh:before { content: @fa-var-sleigh; }\n.@{fa-css-prefix}-sliders-h:before { content: @fa-var-sliders-h; }\n.@{fa-css-prefix}-slideshare:before { content: @fa-var-slideshare; }\n.@{fa-css-prefix}-smile:before { content: @fa-var-smile; }\n.@{fa-css-prefix}-smile-beam:before { content: @fa-var-smile-beam; }\n.@{fa-css-prefix}-smile-wink:before { content: @fa-var-smile-wink; }\n.@{fa-css-prefix}-smog:before { content: @fa-var-smog; }\n.@{fa-css-prefix}-smoking:before { content: @fa-var-smoking; }\n.@{fa-css-prefix}-smoking-ban:before { content: @fa-var-smoking-ban; }\n.@{fa-css-prefix}-sms:before { content: @fa-var-sms; }\n.@{fa-css-prefix}-snapchat:before { content: @fa-var-snapchat; }\n.@{fa-css-prefix}-snapchat-ghost:before { content: @fa-var-snapchat-ghost; }\n.@{fa-css-prefix}-snapchat-square:before { content: @fa-var-snapchat-square; }\n.@{fa-css-prefix}-snowboarding:before { content: @fa-var-snowboarding; }\n.@{fa-css-prefix}-snowflake:before { content: @fa-var-snowflake; }\n.@{fa-css-prefix}-snowman:before { content: @fa-var-snowman; }\n.@{fa-css-prefix}-snowplow:before { content: @fa-var-snowplow; }\n.@{fa-css-prefix}-socks:before { content: @fa-var-socks; }\n.@{fa-css-prefix}-solar-panel:before { content: @fa-var-solar-panel; }\n.@{fa-css-prefix}-sort:before { content: @fa-var-sort; }\n.@{fa-css-prefix}-sort-alpha-down:before { content: @fa-var-sort-alpha-down; }\n.@{fa-css-prefix}-sort-alpha-down-alt:before { content: @fa-var-sort-alpha-down-alt; }\n.@{fa-css-prefix}-sort-alpha-up:before { content: @fa-var-sort-alpha-up; }\n.@{fa-css-prefix}-sort-alpha-up-alt:before { content: @fa-var-sort-alpha-up-alt; }\n.@{fa-css-prefix}-sort-amount-down:before { content: @fa-var-sort-amount-down; }\n.@{fa-css-prefix}-sort-amount-down-alt:before { content: @fa-var-sort-amount-down-alt; }\n.@{fa-css-prefix}-sort-amount-up:before { content: @fa-var-sort-amount-up; }\n.@{fa-css-prefix}-sort-amount-up-alt:before { content: @fa-var-sort-amount-up-alt; }\n.@{fa-css-prefix}-sort-down:before { content: @fa-var-sort-down; }\n.@{fa-css-prefix}-sort-numeric-down:before { content: @fa-var-sort-numeric-down; }\n.@{fa-css-prefix}-sort-numeric-down-alt:before { content: @fa-var-sort-numeric-down-alt; }\n.@{fa-css-prefix}-sort-numeric-up:before { content: @fa-var-sort-numeric-up; }\n.@{fa-css-prefix}-sort-numeric-up-alt:before { content: @fa-var-sort-numeric-up-alt; }\n.@{fa-css-prefix}-sort-up:before { content: @fa-var-sort-up; }\n.@{fa-css-prefix}-soundcloud:before { content: @fa-var-soundcloud; }\n.@{fa-css-prefix}-sourcetree:before { content: @fa-var-sourcetree; }\n.@{fa-css-prefix}-spa:before { content: @fa-var-spa; }\n.@{fa-css-prefix}-space-shuttle:before { content: @fa-var-space-shuttle; }\n.@{fa-css-prefix}-speakap:before { content: @fa-var-speakap; }\n.@{fa-css-prefix}-speaker-deck:before { content: @fa-var-speaker-deck; }\n.@{fa-css-prefix}-spell-check:before { content: @fa-var-spell-check; }\n.@{fa-css-prefix}-spider:before { content: @fa-var-spider; }\n.@{fa-css-prefix}-spinner:before { content: @fa-var-spinner; }\n.@{fa-css-prefix}-splotch:before { content: @fa-var-splotch; }\n.@{fa-css-prefix}-spotify:before { content: @fa-var-spotify; }\n.@{fa-css-prefix}-spray-can:before { content: @fa-var-spray-can; }\n.@{fa-css-prefix}-square:before { content: @fa-var-square; }\n.@{fa-css-prefix}-square-full:before { content: @fa-var-square-full; }\n.@{fa-css-prefix}-square-root-alt:before { content: @fa-var-square-root-alt; }\n.@{fa-css-prefix}-squarespace:before { content: @fa-var-squarespace; }\n.@{fa-css-prefix}-stack-exchange:before { content: @fa-var-stack-exchange; }\n.@{fa-css-prefix}-stack-overflow:before { content: @fa-var-stack-overflow; }\n.@{fa-css-prefix}-stackpath:before { content: @fa-var-stackpath; }\n.@{fa-css-prefix}-stamp:before { content: @fa-var-stamp; }\n.@{fa-css-prefix}-star:before { content: @fa-var-star; }\n.@{fa-css-prefix}-star-and-crescent:before { content: @fa-var-star-and-crescent; }\n.@{fa-css-prefix}-star-half:before { content: @fa-var-star-half; }\n.@{fa-css-prefix}-star-half-alt:before { content: @fa-var-star-half-alt; }\n.@{fa-css-prefix}-star-of-david:before { content: @fa-var-star-of-david; }\n.@{fa-css-prefix}-star-of-life:before { content: @fa-var-star-of-life; }\n.@{fa-css-prefix}-staylinked:before { content: @fa-var-staylinked; }\n.@{fa-css-prefix}-steam:before { content: @fa-var-steam; }\n.@{fa-css-prefix}-steam-square:before { content: @fa-var-steam-square; }\n.@{fa-css-prefix}-steam-symbol:before { content: @fa-var-steam-symbol; }\n.@{fa-css-prefix}-step-backward:before { content: @fa-var-step-backward; }\n.@{fa-css-prefix}-step-forward:before { content: @fa-var-step-forward; }\n.@{fa-css-prefix}-stethoscope:before { content: @fa-var-stethoscope; }\n.@{fa-css-prefix}-sticker-mule:before { content: @fa-var-sticker-mule; }\n.@{fa-css-prefix}-sticky-note:before { content: @fa-var-sticky-note; }\n.@{fa-css-prefix}-stop:before { content: @fa-var-stop; }\n.@{fa-css-prefix}-stop-circle:before { content: @fa-var-stop-circle; }\n.@{fa-css-prefix}-stopwatch:before { content: @fa-var-stopwatch; }\n.@{fa-css-prefix}-store:before { content: @fa-var-store; }\n.@{fa-css-prefix}-store-alt:before { content: @fa-var-store-alt; }\n.@{fa-css-prefix}-strava:before { content: @fa-var-strava; }\n.@{fa-css-prefix}-stream:before { content: @fa-var-stream; }\n.@{fa-css-prefix}-street-view:before { content: @fa-var-street-view; }\n.@{fa-css-prefix}-strikethrough:before { content: @fa-var-strikethrough; }\n.@{fa-css-prefix}-stripe:before { content: @fa-var-stripe; }\n.@{fa-css-prefix}-stripe-s:before { content: @fa-var-stripe-s; }\n.@{fa-css-prefix}-stroopwafel:before { content: @fa-var-stroopwafel; }\n.@{fa-css-prefix}-studiovinari:before { content: @fa-var-studiovinari; }\n.@{fa-css-prefix}-stumbleupon:before { content: @fa-var-stumbleupon; }\n.@{fa-css-prefix}-stumbleupon-circle:before { content: @fa-var-stumbleupon-circle; }\n.@{fa-css-prefix}-subscript:before { content: @fa-var-subscript; }\n.@{fa-css-prefix}-subway:before { content: @fa-var-subway; }\n.@{fa-css-prefix}-suitcase:before { content: @fa-var-suitcase; }\n.@{fa-css-prefix}-suitcase-rolling:before { content: @fa-var-suitcase-rolling; }\n.@{fa-css-prefix}-sun:before { content: @fa-var-sun; }\n.@{fa-css-prefix}-superpowers:before { content: @fa-var-superpowers; }\n.@{fa-css-prefix}-superscript:before { content: @fa-var-superscript; }\n.@{fa-css-prefix}-supple:before { content: @fa-var-supple; }\n.@{fa-css-prefix}-surprise:before { content: @fa-var-surprise; }\n.@{fa-css-prefix}-suse:before { content: @fa-var-suse; }\n.@{fa-css-prefix}-swatchbook:before { content: @fa-var-swatchbook; }\n.@{fa-css-prefix}-swimmer:before { content: @fa-var-swimmer; }\n.@{fa-css-prefix}-swimming-pool:before { content: @fa-var-swimming-pool; }\n.@{fa-css-prefix}-symfony:before { content: @fa-var-symfony; }\n.@{fa-css-prefix}-synagogue:before { content: @fa-var-synagogue; }\n.@{fa-css-prefix}-sync:before { content: @fa-var-sync; }\n.@{fa-css-prefix}-sync-alt:before { content: @fa-var-sync-alt; }\n.@{fa-css-prefix}-syringe:before { content: @fa-var-syringe; }\n.@{fa-css-prefix}-table:before { content: @fa-var-table; }\n.@{fa-css-prefix}-table-tennis:before { content: @fa-var-table-tennis; }\n.@{fa-css-prefix}-tablet:before { content: @fa-var-tablet; }\n.@{fa-css-prefix}-tablet-alt:before { content: @fa-var-tablet-alt; }\n.@{fa-css-prefix}-tablets:before { content: @fa-var-tablets; }\n.@{fa-css-prefix}-tachometer-alt:before { content: @fa-var-tachometer-alt; }\n.@{fa-css-prefix}-tag:before { content: @fa-var-tag; }\n.@{fa-css-prefix}-tags:before { content: @fa-var-tags; }\n.@{fa-css-prefix}-tape:before { content: @fa-var-tape; }\n.@{fa-css-prefix}-tasks:before { content: @fa-var-tasks; }\n.@{fa-css-prefix}-taxi:before { content: @fa-var-taxi; }\n.@{fa-css-prefix}-teamspeak:before { content: @fa-var-teamspeak; }\n.@{fa-css-prefix}-teeth:before { content: @fa-var-teeth; }\n.@{fa-css-prefix}-teeth-open:before { content: @fa-var-teeth-open; }\n.@{fa-css-prefix}-telegram:before { content: @fa-var-telegram; }\n.@{fa-css-prefix}-telegram-plane:before { content: @fa-var-telegram-plane; }\n.@{fa-css-prefix}-temperature-high:before { content: @fa-var-temperature-high; }\n.@{fa-css-prefix}-temperature-low:before { content: @fa-var-temperature-low; }\n.@{fa-css-prefix}-tencent-weibo:before { content: @fa-var-tencent-weibo; }\n.@{fa-css-prefix}-tenge:before { content: @fa-var-tenge; }\n.@{fa-css-prefix}-terminal:before { content: @fa-var-terminal; }\n.@{fa-css-prefix}-text-height:before { content: @fa-var-text-height; }\n.@{fa-css-prefix}-text-width:before { content: @fa-var-text-width; }\n.@{fa-css-prefix}-th:before { content: @fa-var-th; }\n.@{fa-css-prefix}-th-large:before { content: @fa-var-th-large; }\n.@{fa-css-prefix}-th-list:before { content: @fa-var-th-list; }\n.@{fa-css-prefix}-the-red-yeti:before { content: @fa-var-the-red-yeti; }\n.@{fa-css-prefix}-theater-masks:before { content: @fa-var-theater-masks; }\n.@{fa-css-prefix}-themeco:before { content: @fa-var-themeco; }\n.@{fa-css-prefix}-themeisle:before { content: @fa-var-themeisle; }\n.@{fa-css-prefix}-thermometer:before { content: @fa-var-thermometer; }\n.@{fa-css-prefix}-thermometer-empty:before { content: @fa-var-thermometer-empty; }\n.@{fa-css-prefix}-thermometer-full:before { content: @fa-var-thermometer-full; }\n.@{fa-css-prefix}-thermometer-half:before { content: @fa-var-thermometer-half; }\n.@{fa-css-prefix}-thermometer-quarter:before { content: @fa-var-thermometer-quarter; }\n.@{fa-css-prefix}-thermometer-three-quarters:before { content: @fa-var-thermometer-three-quarters; }\n.@{fa-css-prefix}-think-peaks:before { content: @fa-var-think-peaks; }\n.@{fa-css-prefix}-thumbs-down:before { content: @fa-var-thumbs-down; }\n.@{fa-css-prefix}-thumbs-up:before { content: @fa-var-thumbs-up; }\n.@{fa-css-prefix}-thumbtack:before { content: @fa-var-thumbtack; }\n.@{fa-css-prefix}-ticket-alt:before { content: @fa-var-ticket-alt; }\n.@{fa-css-prefix}-times:before { content: @fa-var-times; }\n.@{fa-css-prefix}-times-circle:before { content: @fa-var-times-circle; }\n.@{fa-css-prefix}-tint:before { content: @fa-var-tint; }\n.@{fa-css-prefix}-tint-slash:before { content: @fa-var-tint-slash; }\n.@{fa-css-prefix}-tired:before { content: @fa-var-tired; }\n.@{fa-css-prefix}-toggle-off:before { content: @fa-var-toggle-off; }\n.@{fa-css-prefix}-toggle-on:before { content: @fa-var-toggle-on; }\n.@{fa-css-prefix}-toilet:before { content: @fa-var-toilet; }\n.@{fa-css-prefix}-toilet-paper:before { content: @fa-var-toilet-paper; }\n.@{fa-css-prefix}-toolbox:before { content: @fa-var-toolbox; }\n.@{fa-css-prefix}-tools:before { content: @fa-var-tools; }\n.@{fa-css-prefix}-tooth:before { content: @fa-var-tooth; }\n.@{fa-css-prefix}-torah:before { content: @fa-var-torah; }\n.@{fa-css-prefix}-torii-gate:before { content: @fa-var-torii-gate; }\n.@{fa-css-prefix}-tractor:before { content: @fa-var-tractor; }\n.@{fa-css-prefix}-trade-federation:before { content: @fa-var-trade-federation; }\n.@{fa-css-prefix}-trademark:before { content: @fa-var-trademark; }\n.@{fa-css-prefix}-traffic-light:before { content: @fa-var-traffic-light; }\n.@{fa-css-prefix}-train:before { content: @fa-var-train; }\n.@{fa-css-prefix}-tram:before { content: @fa-var-tram; }\n.@{fa-css-prefix}-transgender:before { content: @fa-var-transgender; }\n.@{fa-css-prefix}-transgender-alt:before { content: @fa-var-transgender-alt; }\n.@{fa-css-prefix}-trash:before { content: @fa-var-trash; }\n.@{fa-css-prefix}-trash-alt:before { content: @fa-var-trash-alt; }\n.@{fa-css-prefix}-trash-restore:before { content: @fa-var-trash-restore; }\n.@{fa-css-prefix}-trash-restore-alt:before { content: @fa-var-trash-restore-alt; }\n.@{fa-css-prefix}-tree:before { content: @fa-var-tree; }\n.@{fa-css-prefix}-trello:before { content: @fa-var-trello; }\n.@{fa-css-prefix}-tripadvisor:before { content: @fa-var-tripadvisor; }\n.@{fa-css-prefix}-trophy:before { content: @fa-var-trophy; }\n.@{fa-css-prefix}-truck:before { content: @fa-var-truck; }\n.@{fa-css-prefix}-truck-loading:before { content: @fa-var-truck-loading; }\n.@{fa-css-prefix}-truck-monster:before { content: @fa-var-truck-monster; }\n.@{fa-css-prefix}-truck-moving:before { content: @fa-var-truck-moving; }\n.@{fa-css-prefix}-truck-pickup:before { content: @fa-var-truck-pickup; }\n.@{fa-css-prefix}-tshirt:before { content: @fa-var-tshirt; }\n.@{fa-css-prefix}-tty:before { content: @fa-var-tty; }\n.@{fa-css-prefix}-tumblr:before { content: @fa-var-tumblr; }\n.@{fa-css-prefix}-tumblr-square:before { content: @fa-var-tumblr-square; }\n.@{fa-css-prefix}-tv:before { content: @fa-var-tv; }\n.@{fa-css-prefix}-twitch:before { content: @fa-var-twitch; }\n.@{fa-css-prefix}-twitter:before { content: @fa-var-twitter; }\n.@{fa-css-prefix}-twitter-square:before { content: @fa-var-twitter-square; }\n.@{fa-css-prefix}-typo3:before { content: @fa-var-typo3; }\n.@{fa-css-prefix}-uber:before { content: @fa-var-uber; }\n.@{fa-css-prefix}-ubuntu:before { content: @fa-var-ubuntu; }\n.@{fa-css-prefix}-uikit:before { content: @fa-var-uikit; }\n.@{fa-css-prefix}-umbrella:before { content: @fa-var-umbrella; }\n.@{fa-css-prefix}-umbrella-beach:before { content: @fa-var-umbrella-beach; }\n.@{fa-css-prefix}-underline:before { content: @fa-var-underline; }\n.@{fa-css-prefix}-undo:before { content: @fa-var-undo; }\n.@{fa-css-prefix}-undo-alt:before { content: @fa-var-undo-alt; }\n.@{fa-css-prefix}-uniregistry:before { content: @fa-var-uniregistry; }\n.@{fa-css-prefix}-universal-access:before { content: @fa-var-universal-access; }\n.@{fa-css-prefix}-university:before { content: @fa-var-university; }\n.@{fa-css-prefix}-unlink:before { content: @fa-var-unlink; }\n.@{fa-css-prefix}-unlock:before { content: @fa-var-unlock; }\n.@{fa-css-prefix}-unlock-alt:before { content: @fa-var-unlock-alt; }\n.@{fa-css-prefix}-untappd:before { content: @fa-var-untappd; }\n.@{fa-css-prefix}-upload:before { content: @fa-var-upload; }\n.@{fa-css-prefix}-ups:before { content: @fa-var-ups; }\n.@{fa-css-prefix}-usb:before { content: @fa-var-usb; }\n.@{fa-css-prefix}-user:before { content: @fa-var-user; }\n.@{fa-css-prefix}-user-alt:before { content: @fa-var-user-alt; }\n.@{fa-css-prefix}-user-alt-slash:before { content: @fa-var-user-alt-slash; }\n.@{fa-css-prefix}-user-astronaut:before { content: @fa-var-user-astronaut; }\n.@{fa-css-prefix}-user-check:before { content: @fa-var-user-check; }\n.@{fa-css-prefix}-user-circle:before { content: @fa-var-user-circle; }\n.@{fa-css-prefix}-user-clock:before { content: @fa-var-user-clock; }\n.@{fa-css-prefix}-user-cog:before { content: @fa-var-user-cog; }\n.@{fa-css-prefix}-user-edit:before { content: @fa-var-user-edit; }\n.@{fa-css-prefix}-user-friends:before { content: @fa-var-user-friends; }\n.@{fa-css-prefix}-user-graduate:before { content: @fa-var-user-graduate; }\n.@{fa-css-prefix}-user-injured:before { content: @fa-var-user-injured; }\n.@{fa-css-prefix}-user-lock:before { content: @fa-var-user-lock; }\n.@{fa-css-prefix}-user-md:before { content: @fa-var-user-md; }\n.@{fa-css-prefix}-user-minus:before { content: @fa-var-user-minus; }\n.@{fa-css-prefix}-user-ninja:before { content: @fa-var-user-ninja; }\n.@{fa-css-prefix}-user-nurse:before { content: @fa-var-user-nurse; }\n.@{fa-css-prefix}-user-plus:before { content: @fa-var-user-plus; }\n.@{fa-css-prefix}-user-secret:before { content: @fa-var-user-secret; }\n.@{fa-css-prefix}-user-shield:before { content: @fa-var-user-shield; }\n.@{fa-css-prefix}-user-slash:before { content: @fa-var-user-slash; }\n.@{fa-css-prefix}-user-tag:before { content: @fa-var-user-tag; }\n.@{fa-css-prefix}-user-tie:before { content: @fa-var-user-tie; }\n.@{fa-css-prefix}-user-times:before { content: @fa-var-user-times; }\n.@{fa-css-prefix}-users:before { content: @fa-var-users; }\n.@{fa-css-prefix}-users-cog:before { content: @fa-var-users-cog; }\n.@{fa-css-prefix}-usps:before { content: @fa-var-usps; }\n.@{fa-css-prefix}-ussunnah:before { content: @fa-var-ussunnah; }\n.@{fa-css-prefix}-utensil-spoon:before { content: @fa-var-utensil-spoon; }\n.@{fa-css-prefix}-utensils:before { content: @fa-var-utensils; }\n.@{fa-css-prefix}-vaadin:before { content: @fa-var-vaadin; }\n.@{fa-css-prefix}-vector-square:before { content: @fa-var-vector-square; }\n.@{fa-css-prefix}-venus:before { content: @fa-var-venus; }\n.@{fa-css-prefix}-venus-double:before { content: @fa-var-venus-double; }\n.@{fa-css-prefix}-venus-mars:before { content: @fa-var-venus-mars; }\n.@{fa-css-prefix}-viacoin:before { content: @fa-var-viacoin; }\n.@{fa-css-prefix}-viadeo:before { content: @fa-var-viadeo; }\n.@{fa-css-prefix}-viadeo-square:before { content: @fa-var-viadeo-square; }\n.@{fa-css-prefix}-vial:before { content: @fa-var-vial; }\n.@{fa-css-prefix}-vials:before { content: @fa-var-vials; }\n.@{fa-css-prefix}-viber:before { content: @fa-var-viber; }\n.@{fa-css-prefix}-video:before { content: @fa-var-video; }\n.@{fa-css-prefix}-video-slash:before { content: @fa-var-video-slash; }\n.@{fa-css-prefix}-vihara:before { content: @fa-var-vihara; }\n.@{fa-css-prefix}-vimeo:before { content: @fa-var-vimeo; }\n.@{fa-css-prefix}-vimeo-square:before { content: @fa-var-vimeo-square; }\n.@{fa-css-prefix}-vimeo-v:before { content: @fa-var-vimeo-v; }\n.@{fa-css-prefix}-vine:before { content: @fa-var-vine; }\n.@{fa-css-prefix}-vk:before { content: @fa-var-vk; }\n.@{fa-css-prefix}-vnv:before { content: @fa-var-vnv; }\n.@{fa-css-prefix}-voicemail:before { content: @fa-var-voicemail; }\n.@{fa-css-prefix}-volleyball-ball:before { content: @fa-var-volleyball-ball; }\n.@{fa-css-prefix}-volume-down:before { content: @fa-var-volume-down; }\n.@{fa-css-prefix}-volume-mute:before { content: @fa-var-volume-mute; }\n.@{fa-css-prefix}-volume-off:before { content: @fa-var-volume-off; }\n.@{fa-css-prefix}-volume-up:before { content: @fa-var-volume-up; }\n.@{fa-css-prefix}-vote-yea:before { content: @fa-var-vote-yea; }\n.@{fa-css-prefix}-vr-cardboard:before { content: @fa-var-vr-cardboard; }\n.@{fa-css-prefix}-vuejs:before { content: @fa-var-vuejs; }\n.@{fa-css-prefix}-walking:before { content: @fa-var-walking; }\n.@{fa-css-prefix}-wallet:before { content: @fa-var-wallet; }\n.@{fa-css-prefix}-warehouse:before { content: @fa-var-warehouse; }\n.@{fa-css-prefix}-water:before { content: @fa-var-water; }\n.@{fa-css-prefix}-wave-square:before { content: @fa-var-wave-square; }\n.@{fa-css-prefix}-waze:before { content: @fa-var-waze; }\n.@{fa-css-prefix}-weebly:before { content: @fa-var-weebly; }\n.@{fa-css-prefix}-weibo:before { content: @fa-var-weibo; }\n.@{fa-css-prefix}-weight:before { content: @fa-var-weight; }\n.@{fa-css-prefix}-weight-hanging:before { content: @fa-var-weight-hanging; }\n.@{fa-css-prefix}-weixin:before { content: @fa-var-weixin; }\n.@{fa-css-prefix}-whatsapp:before { content: @fa-var-whatsapp; }\n.@{fa-css-prefix}-whatsapp-square:before { content: @fa-var-whatsapp-square; }\n.@{fa-css-prefix}-wheelchair:before { content: @fa-var-wheelchair; }\n.@{fa-css-prefix}-whmcs:before { content: @fa-var-whmcs; }\n.@{fa-css-prefix}-wifi:before { content: @fa-var-wifi; }\n.@{fa-css-prefix}-wikipedia-w:before { content: @fa-var-wikipedia-w; }\n.@{fa-css-prefix}-wind:before { content: @fa-var-wind; }\n.@{fa-css-prefix}-window-close:before { content: @fa-var-window-close; }\n.@{fa-css-prefix}-window-maximize:before { content: @fa-var-window-maximize; }\n.@{fa-css-prefix}-window-minimize:before { content: @fa-var-window-minimize; }\n.@{fa-css-prefix}-window-restore:before { content: @fa-var-window-restore; }\n.@{fa-css-prefix}-windows:before { content: @fa-var-windows; }\n.@{fa-css-prefix}-wine-bottle:before { content: @fa-var-wine-bottle; }\n.@{fa-css-prefix}-wine-glass:before { content: @fa-var-wine-glass; }\n.@{fa-css-prefix}-wine-glass-alt:before { content: @fa-var-wine-glass-alt; }\n.@{fa-css-prefix}-wix:before { content: @fa-var-wix; }\n.@{fa-css-prefix}-wizards-of-the-coast:before { content: @fa-var-wizards-of-the-coast; }\n.@{fa-css-prefix}-wolf-pack-battalion:before { content: @fa-var-wolf-pack-battalion; }\n.@{fa-css-prefix}-won-sign:before { content: @fa-var-won-sign; }\n.@{fa-css-prefix}-wordpress:before { content: @fa-var-wordpress; }\n.@{fa-css-prefix}-wordpress-simple:before { content: @fa-var-wordpress-simple; }\n.@{fa-css-prefix}-wpbeginner:before { content: @fa-var-wpbeginner; }\n.@{fa-css-prefix}-wpexplorer:before { content: @fa-var-wpexplorer; }\n.@{fa-css-prefix}-wpforms:before { content: @fa-var-wpforms; }\n.@{fa-css-prefix}-wpressr:before { content: @fa-var-wpressr; }\n.@{fa-css-prefix}-wrench:before { content: @fa-var-wrench; }\n.@{fa-css-prefix}-x-ray:before { content: @fa-var-x-ray; }\n.@{fa-css-prefix}-xbox:before { content: @fa-var-xbox; }\n.@{fa-css-prefix}-xing:before { content: @fa-var-xing; }\n.@{fa-css-prefix}-xing-square:before { content: @fa-var-xing-square; }\n.@{fa-css-prefix}-y-combinator:before { content: @fa-var-y-combinator; }\n.@{fa-css-prefix}-yahoo:before { content: @fa-var-yahoo; }\n.@{fa-css-prefix}-yammer:before { content: @fa-var-yammer; }\n.@{fa-css-prefix}-yandex:before { content: @fa-var-yandex; }\n.@{fa-css-prefix}-yandex-international:before { content: @fa-var-yandex-international; }\n.@{fa-css-prefix}-yarn:before { content: @fa-var-yarn; }\n.@{fa-css-prefix}-yelp:before { content: @fa-var-yelp; }\n.@{fa-css-prefix}-yen-sign:before { content: @fa-var-yen-sign; }\n.@{fa-css-prefix}-yin-yang:before { content: @fa-var-yin-yang; }\n.@{fa-css-prefix}-yoast:before { content: @fa-var-yoast; }\n.@{fa-css-prefix}-youtube:before { content: @fa-var-youtube; }\n.@{fa-css-prefix}-youtube-square:before { content: @fa-var-youtube-square; }\n.@{fa-css-prefix}-zhihu:before { content: @fa-var-zhihu; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_larger.less",
    "content": "// Icon Sizes\n// -------------------------\n\n.larger(@factor) when (@factor > 0) {\n  .larger((@factor - 1));\n\n  .@{fa-css-prefix}-@{factor}x {\n    font-size: (@factor * 1em);\n  }\n}\n\n/* makes the font 33% larger relative to the icon container */\n.@{fa-css-prefix}-lg {\n  font-size: (4em / 3);\n  line-height: (3em / 4);\n  vertical-align: -.0667em;\n}\n\n.@{fa-css-prefix}-xs {\n  font-size: .75em;\n}\n\n.@{fa-css-prefix}-sm {\n  font-size: .875em;\n}\n\n.larger(10);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_list.less",
    "content": "// List Icons\n// -------------------------\n\n.@{fa-css-prefix}-ul {\n  list-style-type: none;\n  margin-left: (@fa-li-width * 5/4);\n  padding-left: 0;\n\n  > li { position: relative; }\n}\n\n.@{fa-css-prefix}-li {\n  left: -@fa-li-width;\n  position: absolute;\n  text-align: center;\n  width: @fa-li-width;\n  line-height: inherit;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_mixins.less",
    "content": "// Mixins\n// --------------------------\n\n.fa-icon() {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  font-weight: normal;\n  line-height: 1;\n}\n\n.fa-icon-rotate(@degrees, @rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=@{rotation})\";\n  transform: rotate(@degrees);\n}\n\n.fa-icon-flip(@horiz, @vert, @rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=@{rotation}, mirror=1)\";\n  transform: scale(@horiz, @vert);\n}\n\n\n// Only display content to screen readers. A la Bootstrap 4.\n//\n// See: http://a11yproject.com/posts/how-to-hide-content/\n\n.sr-only() {\n  border: 0;\n  clip: rect(0,0,0,0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px;\n}\n\n// Use in conjunction with .sr-only to only display content when it's focused.\n//\n// Useful for \"Skip to main content\" links; see http://www.w3.org/TR/2013/NOTE-WCAG20-TECHS-20130905/G1\n//\n// Credit: HTML5 Boilerplate\n\n.sr-only-focusable() {\n  &:active,\n  &:focus {\n    clip: auto;\n    height: auto;\n    margin: 0;\n    overflow: visible;\n    position: static;\n    width: auto;\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_rotated-flipped.less",
    "content": "// Rotated & Flipped Icons\n// -------------------------\n\n.@{fa-css-prefix}-rotate-90  { .fa-icon-rotate(90deg, 1);  }\n.@{fa-css-prefix}-rotate-180 { .fa-icon-rotate(180deg, 2); }\n.@{fa-css-prefix}-rotate-270 { .fa-icon-rotate(270deg, 3); }\n\n.@{fa-css-prefix}-flip-horizontal { .fa-icon-flip(-1, 1, 0); }\n.@{fa-css-prefix}-flip-vertical   { .fa-icon-flip(1, -1, 2); }\n.@{fa-css-prefix}-flip-both, .@{fa-css-prefix}-flip-horizontal.@{fa-css-prefix}-flip-vertical { .fa-icon-flip(-1, -1, 2); }\n\n// Hook for IE8-9\n// -------------------------\n\n:root {\n  .@{fa-css-prefix}-rotate-90,\n  .@{fa-css-prefix}-rotate-180,\n  .@{fa-css-prefix}-rotate-270,\n  .@{fa-css-prefix}-flip-horizontal,\n  .@{fa-css-prefix}-flip-vertical,\n  .@{fa-css-prefix}-flip-both {\n    filter: none;\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_screen-reader.less",
    "content": "// Screen Readers\n// -------------------------\n\n.sr-only { .sr-only(); }\n.sr-only-focusable { .sr-only-focusable(); }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_shims.less",
    "content": ".@{fa-css-prefix}.@{fa-css-prefix}-glass:before { content: @fa-var-glass-martini; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-meetup {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-o:before { content: @fa-var-star; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-remove:before { content: @fa-var-times; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-close:before { content: @fa-var-times; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gear:before { content: @fa-var-cog; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-trash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-trash-o:before { content: @fa-var-trash-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-o:before { content: @fa-var-file; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-clock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-clock-o:before { content: @fa-var-clock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-down:before { content: @fa-var-arrow-alt-circle-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-up:before { content: @fa-var-arrow-alt-circle-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-play-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-play-circle-o:before { content: @fa-var-play-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-repeat:before { content: @fa-var-redo; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rotate-right:before { content: @fa-var-redo; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-refresh:before { content: @fa-var-sync; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-list-alt {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dedent:before { content: @fa-var-outdent; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-video-camera:before { content: @fa-var-video; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-picture-o:before { content: @fa-var-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-photo {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-photo:before { content: @fa-var-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-image {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-image:before { content: @fa-var-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil:before { content: @fa-var-pencil-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-map-marker:before { content: @fa-var-map-marker-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil-square-o:before { content: @fa-var-edit; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-share-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-share-square-o:before { content: @fa-var-share-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-check-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-check-square-o:before { content: @fa-var-check-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows:before { content: @fa-var-arrows-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-times-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-times-circle-o:before { content: @fa-var-times-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-check-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-check-circle-o:before { content: @fa-var-check-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mail-forward:before { content: @fa-var-share; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eye {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eye-slash {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-warning:before { content: @fa-var-exclamation-triangle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar:before { content: @fa-var-calendar-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows-v:before { content: @fa-var-arrows-alt-v; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows-h:before { content: @fa-var-arrows-alt-h; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart:before { content: @fa-var-chart-bar; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bar-chart-o:before { content: @fa-var-chart-bar; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-twitter-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gears:before { content: @fa-var-cogs; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-up:before { content: @fa-var-thumbs-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-thumbs-o-down:before { content: @fa-var-thumbs-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-heart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-heart-o:before { content: @fa-var-heart; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sign-out:before { content: @fa-var-sign-out-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin-square:before { content: @fa-var-linkedin; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thumb-tack:before { content: @fa-var-thumbtack; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-external-link:before { content: @fa-var-external-link-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sign-in:before { content: @fa-var-sign-in-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-github-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lemon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-lemon-o:before { content: @fa-var-lemon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-square-o:before { content: @fa-var-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bookmark-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bookmark-o:before { content: @fa-var-bookmark; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-twitter {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook:before { content: @fa-var-facebook-f; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-f {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-f:before { content: @fa-var-facebook-f; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-github {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-credit-card {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-feed:before { content: @fa-var-rss; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hdd-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hdd-o:before { content: @fa-var-hdd; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-right:before { content: @fa-var-hand-point-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-left:before { content: @fa-var-hand-point-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-up:before { content: @fa-var-hand-point-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-o-down:before { content: @fa-var-hand-point-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrows-alt:before { content: @fa-var-expand-arrows-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-group:before { content: @fa-var-users; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-chain:before { content: @fa-var-link; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-scissors:before { content: @fa-var-cut; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-files-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-files-o:before { content: @fa-var-copy; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-floppy-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-floppy-o:before { content: @fa-var-save; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-navicon:before { content: @fa-var-bars; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reorder:before { content: @fa-var-bars; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pinterest {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pinterest-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus:before { content: @fa-var-google-plus-g; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-money {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-money:before { content: @fa-var-money-bill-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-unsorted:before { content: @fa-var-sort; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-desc:before { content: @fa-var-sort-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-asc:before { content: @fa-var-sort-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-linkedin:before { content: @fa-var-linkedin-in; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rotate-left:before { content: @fa-var-undo; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-legal:before { content: @fa-var-gavel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tachometer:before { content: @fa-var-tachometer-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dashboard:before { content: @fa-var-tachometer-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-comment-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-comment-o:before { content: @fa-var-comment; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-comments-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-comments-o:before { content: @fa-var-comments; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-flash:before { content: @fa-var-bolt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-clipboard {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-paste {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-paste:before { content: @fa-var-clipboard; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lightbulb-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-lightbulb-o:before { content: @fa-var-lightbulb; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-exchange:before { content: @fa-var-exchange-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cloud-download:before { content: @fa-var-cloud-download-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cloud-upload:before { content: @fa-var-cloud-upload-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-o:before { content: @fa-var-bell; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cutlery:before { content: @fa-var-utensils; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-text-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-text-o:before { content: @fa-var-file-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-building-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-building-o:before { content: @fa-var-building; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hospital-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hospital-o:before { content: @fa-var-hospital; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tablet:before { content: @fa-var-tablet-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mobile:before { content: @fa-var-mobile-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mobile-phone:before { content: @fa-var-mobile-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-o:before { content: @fa-var-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mail-reply:before { content: @fa-var-reply; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-github-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-o:before { content: @fa-var-folder; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-folder-open-o:before { content: @fa-var-folder-open; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-smile-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-smile-o:before { content: @fa-var-smile; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-frown-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-frown-o:before { content: @fa-var-frown; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-meh-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-meh-o:before { content: @fa-var-meh; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-keyboard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-keyboard-o:before { content: @fa-var-keyboard; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-flag-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-flag-o:before { content: @fa-var-flag; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mail-reply-all:before { content: @fa-var-reply-all; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-o:before { content: @fa-var-star-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-empty {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-empty:before { content: @fa-var-star-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-full {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-star-half-full:before { content: @fa-var-star-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-code-fork:before { content: @fa-var-code-branch; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-chain-broken:before { content: @fa-var-unlink; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-shield:before { content: @fa-var-shield-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-o:before { content: @fa-var-calendar; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-maxcdn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-html5 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-css3 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ticket:before { content: @fa-var-ticket-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-minus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-minus-square-o:before { content: @fa-var-minus-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-level-up:before { content: @fa-var-level-up-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-level-down:before { content: @fa-var-level-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pencil-square:before { content: @fa-var-pen-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-external-link-square:before { content: @fa-var-external-link-square-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-compass {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-down:before { content: @fa-var-caret-square-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-down:before { content: @fa-var-caret-square-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-up:before { content: @fa-var-caret-square-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-up:before { content: @fa-var-caret-square-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-right:before { content: @fa-var-caret-square-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-right:before { content: @fa-var-caret-square-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eur:before { content: @fa-var-euro-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-euro:before { content: @fa-var-euro-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gbp:before { content: @fa-var-pound-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-usd:before { content: @fa-var-dollar-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dollar:before { content: @fa-var-dollar-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-inr:before { content: @fa-var-rupee-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rupee:before { content: @fa-var-rupee-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-jpy:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cny:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rmb:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yen:before { content: @fa-var-yen-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rub:before { content: @fa-var-ruble-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ruble:before { content: @fa-var-ruble-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rouble:before { content: @fa-var-ruble-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-krw:before { content: @fa-var-won-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-won:before { content: @fa-var-won-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-btc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bitcoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bitcoin:before { content: @fa-var-btc; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-text:before { content: @fa-var-file-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-alpha-asc:before { content: @fa-var-sort-alpha-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-alpha-desc:before { content: @fa-var-sort-alpha-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-amount-asc:before { content: @fa-var-sort-amount-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-amount-desc:before { content: @fa-var-sort-amount-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-numeric-asc:before { content: @fa-var-sort-numeric-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sort-numeric-desc:before { content: @fa-var-sort-numeric-down-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-xing {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-xing-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube-play {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-youtube-play:before { content: @fa-var-youtube; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dropbox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stack-overflow {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-instagram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-flickr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-adn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bitbucket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bitbucket-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bitbucket-square:before { content: @fa-var-bitbucket; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tumblr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tumblr-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-down:before { content: @fa-var-long-arrow-alt-down; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-up:before { content: @fa-var-long-arrow-alt-up; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-left:before { content: @fa-var-long-arrow-alt-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-long-arrow-right:before { content: @fa-var-long-arrow-alt-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-apple {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-windows {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-android {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linux {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dribbble {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-skype {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-foursquare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-trello {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gratipay {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gittip {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-gittip:before { content: @fa-var-gratipay; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sun-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-sun-o:before { content: @fa-var-sun; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-moon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-moon-o:before { content: @fa-var-moon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-renren {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pagelines {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stack-exchange {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-right:before { content: @fa-var-arrow-alt-circle-right; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-arrow-circle-o-left:before { content: @fa-var-arrow-alt-circle-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-caret-square-o-left:before { content: @fa-var-caret-square-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-toggle-left:before { content: @fa-var-caret-square-left; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dot-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-dot-circle-o:before { content: @fa-var-dot-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vimeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-try:before { content: @fa-var-lira-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-turkish-lira:before { content: @fa-var-lira-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-plus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-plus-square-o:before { content: @fa-var-plus-square; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-slack {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wordpress {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-openid {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-institution:before { content: @fa-var-university; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bank:before { content: @fa-var-university; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mortar-board:before { content: @fa-var-graduation-cap; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yahoo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reddit {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reddit-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stumbleupon-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stumbleupon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-delicious {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-digg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pied-piper-pp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pied-piper-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-drupal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-joomla {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-spoon:before { content: @fa-var-utensil-spoon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-behance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-behance-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-steam {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-steam-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-automobile:before { content: @fa-var-car; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cab:before { content: @fa-var-taxi; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-o:before { content: @fa-var-envelope; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-deviantart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-soundcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-pdf-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-pdf-o:before { content: @fa-var-file-pdf; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-word-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-word-o:before { content: @fa-var-file-word; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-excel-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-excel-o:before { content: @fa-var-file-excel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-powerpoint-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-powerpoint-o:before { content: @fa-var-file-powerpoint; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-image-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-image-o:before { content: @fa-var-file-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-photo-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-photo-o:before { content: @fa-var-file-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-picture-o:before { content: @fa-var-file-image; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-archive-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-archive-o:before { content: @fa-var-file-archive; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-zip-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-zip-o:before { content: @fa-var-file-archive; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-audio-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-audio-o:before { content: @fa-var-file-audio; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-sound-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-sound-o:before { content: @fa-var-file-audio; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-video-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-video-o:before { content: @fa-var-file-video; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-movie-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-movie-o:before { content: @fa-var-file-video; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-file-code-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-file-code-o:before { content: @fa-var-file-code; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vine {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-codepen {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-jsfiddle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-ring {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-bouy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-life-bouy:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-buoy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-life-buoy:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-life-saver {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-life-saver:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-support {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-support:before { content: @fa-var-life-ring; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-o-notch:before { content: @fa-var-circle-notch; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-rebel {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ra {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-ra:before { content: @fa-var-rebel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-resistance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-resistance:before { content: @fa-var-rebel; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-empire {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-ge:before { content: @fa-var-empire; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-git-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-git {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hacker-news {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-y-combinator-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-y-combinator-square:before { content: @fa-var-hacker-news; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yc-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-yc-square:before { content: @fa-var-hacker-news; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tencent-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-qq {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-weixin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wechat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-wechat:before { content: @fa-var-weixin; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-send:before { content: @fa-var-paper-plane; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-paper-plane-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-paper-plane-o:before { content: @fa-var-paper-plane; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-send-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-send-o:before { content: @fa-var-paper-plane; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-thin {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-circle-thin:before { content: @fa-var-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-header:before { content: @fa-var-heading; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sliders:before { content: @fa-var-sliders-h; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-futbol-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-futbol-o:before { content: @fa-var-futbol; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-soccer-ball-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-soccer-ball-o:before { content: @fa-var-futbol; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-slideshare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-twitch {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yelp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-newspaper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-newspaper-o:before { content: @fa-var-newspaper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-wallet {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-visa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-mastercard {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-discover {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-amex {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-stripe {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-slash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-bell-slash-o:before { content: @fa-var-bell-slash; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-trash:before { content: @fa-var-trash-alt; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-copyright {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eyedropper:before { content: @fa-var-eye-dropper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-area-chart:before { content: @fa-var-chart-area; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pie-chart:before { content: @fa-var-chart-pie; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-line-chart:before { content: @fa-var-chart-line; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lastfm {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-lastfm-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ioxhost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-angellist {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-cc:before { content: @fa-var-closed-captioning; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ils:before { content: @fa-var-shekel-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-shekel:before { content: @fa-var-shekel-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sheqel:before { content: @fa-var-shekel-sign; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-meanpath {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-meanpath:before { content: @fa-var-font-awesome; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-buysellads {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-connectdevelop {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-dashcube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-forumbee {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-leanpub {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sellsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-shirtsinbulk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-simplybuilt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-skyatlas {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-diamond {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-diamond:before { content: @fa-var-gem; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-intersex:before { content: @fa-var-transgender; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-facebook-official:before { content: @fa-var-facebook; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pinterest-p {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-whatsapp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hotel:before { content: @fa-var-bed; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-viacoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-medium {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-y-combinator {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-yc:before { content: @fa-var-y-combinator; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-optin-monster {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-opencart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-expeditedssl {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-4:before { content: @fa-var-battery-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery:before { content: @fa-var-battery-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-3:before { content: @fa-var-battery-three-quarters; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-2:before { content: @fa-var-battery-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-1:before { content: @fa-var-battery-quarter; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-battery-0:before { content: @fa-var-battery-empty; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-object-group {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-object-ungroup {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-sticky-note-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-sticky-note-o:before { content: @fa-var-sticky-note; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-jcb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-cc-diners-club {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-clone {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-o:before { content: @fa-var-hourglass; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-1:before { content: @fa-var-hourglass-start; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-2:before { content: @fa-var-hourglass-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hourglass-3:before { content: @fa-var-hourglass-end; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-rock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-rock-o:before { content: @fa-var-hand-rock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-grab-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-grab-o:before { content: @fa-var-hand-rock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-paper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-paper-o:before { content: @fa-var-hand-paper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-stop-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-stop-o:before { content: @fa-var-hand-paper; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-scissors-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-scissors-o:before { content: @fa-var-hand-scissors; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-lizard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-lizard-o:before { content: @fa-var-hand-lizard; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-spock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-spock-o:before { content: @fa-var-hand-spock; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-pointer-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-pointer-o:before { content: @fa-var-hand-pointer; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-peace-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-hand-peace-o:before { content: @fa-var-hand-peace; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-registered {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-creative-commons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gg-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-tripadvisor {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-odnoklassniki {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-odnoklassniki-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-get-pocket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wikipedia-w {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-safari {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-chrome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-firefox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-opera {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-internet-explorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-television:before { content: @fa-var-tv; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-contao {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-500px {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-amazon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-plus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-plus-o:before { content: @fa-var-calendar-plus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-minus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-minus-o:before { content: @fa-var-calendar-minus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-times-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-times-o:before { content: @fa-var-calendar-times; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-check-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-calendar-check-o:before { content: @fa-var-calendar-check; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-map-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-map-o:before { content: @fa-var-map; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-commenting:before { content: @fa-var-comment-dots; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-commenting-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-commenting-o:before { content: @fa-var-comment-dots; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-houzz {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vimeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-vimeo:before { content: @fa-var-vimeo-v; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-black-tie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-fonticons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-reddit-alien {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-edge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-credit-card-alt:before { content: @fa-var-credit-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-codiepie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-modx {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-fort-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-usb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-product-hunt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-mixcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-scribd {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pause-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-pause-circle-o:before { content: @fa-var-pause-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-stop-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-stop-circle-o:before { content: @fa-var-stop-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bluetooth {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bluetooth-b {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-gitlab {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wpbeginner {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wpforms {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-envira {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wheelchair-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-wheelchair-alt:before { content: @fa-var-accessible-icon; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-question-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-question-circle-o:before { content: @fa-var-question-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-volume-control-phone:before { content: @fa-var-phone-volume; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-asl-interpreting:before { content: @fa-var-american-sign-language-interpreting; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-deafness:before { content: @fa-var-deaf; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-hard-of-hearing:before { content: @fa-var-deaf; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-glide {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-glide-g {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-signing:before { content: @fa-var-sign-language; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-viadeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-viadeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snapchat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snapchat-ghost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snapchat-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-pied-piper {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-first-order {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-yoast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-themeisle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-official:before { content: @fa-var-google-plus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-google-plus-circle:before { content: @fa-var-google-plus; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-font-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-fa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-fa:before { content: @fa-var-font-awesome; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-handshake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-handshake-o:before { content: @fa-var-handshake; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-envelope-open-o:before { content: @fa-var-envelope-open; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-linode {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-address-book-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-address-book-o:before { content: @fa-var-address-book; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vcard:before { content: @fa-var-address-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-address-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-address-card-o:before { content: @fa-var-address-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-vcard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-vcard-o:before { content: @fa-var-address-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-user-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-user-circle-o:before { content: @fa-var-user-circle; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-user-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-user-o:before { content: @fa-var-user; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-id-badge {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-drivers-license:before { content: @fa-var-id-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-id-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-id-card-o:before { content: @fa-var-id-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-drivers-license-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-drivers-license-o:before { content: @fa-var-id-card; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-quora {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-free-code-camp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-telegram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-4:before { content: @fa-var-thermometer-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer:before { content: @fa-var-thermometer-full; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-3:before { content: @fa-var-thermometer-three-quarters; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-2:before { content: @fa-var-thermometer-half; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-1:before { content: @fa-var-thermometer-quarter; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-thermometer-0:before { content: @fa-var-thermometer-empty; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bathtub:before { content: @fa-var-bath; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-s15:before { content: @fa-var-bath; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-window-maximize {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-window-restore {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-times-rectangle:before { content: @fa-var-window-close; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-window-close-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-window-close-o:before { content: @fa-var-window-close; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-times-rectangle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-times-rectangle-o:before { content: @fa-var-window-close; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-bandcamp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-grav {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-etsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-imdb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-ravelry {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-eercast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-eercast:before { content: @fa-var-sellcast; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-snowflake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.@{fa-css-prefix}.@{fa-css-prefix}-snowflake-o:before { content: @fa-var-snowflake; }\n\n.@{fa-css-prefix}.@{fa-css-prefix}-superpowers {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-wpexplorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.@{fa-css-prefix}.@{fa-css-prefix}-spotify {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_stacked.less",
    "content": "// Stacked Icons\n// -------------------------\n\n.@{fa-css-prefix}-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: 2em;\n}\n\n.@{fa-css-prefix}-stack-1x, .@{fa-css-prefix}-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%;\n}\n\n.@{fa-css-prefix}-stack-1x { line-height: inherit; }\n.@{fa-css-prefix}-stack-2x { font-size: 2em; }\n.@{fa-css-prefix}-inverse { color: @fa-inverse; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/_variables.less",
    "content": "// Variables\n// --------------------------\n\n@fa-font-path:         \"../webfonts\";\n@fa-font-size-base:    16px;\n@fa-font-display:      auto;\n@fa-line-height-base:  1;\n@fa-css-prefix:        fa;\n@fa-version:           \"5.10.2\";\n@fa-border-color:      #eee;\n@fa-inverse:           #fff;\n@fa-li-width:          2em;\n@fa-primary-opacity:   1;\n@fa-secondary-opacity: .4;\n\n@fa-var-500px: \"\\f26e\";\n@fa-var-accessible-icon: \"\\f368\";\n@fa-var-accusoft: \"\\f369\";\n@fa-var-acquisitions-incorporated: \"\\f6af\";\n@fa-var-ad: \"\\f641\";\n@fa-var-address-book: \"\\f2b9\";\n@fa-var-address-card: \"\\f2bb\";\n@fa-var-adjust: \"\\f042\";\n@fa-var-adn: \"\\f170\";\n@fa-var-adobe: \"\\f778\";\n@fa-var-adversal: \"\\f36a\";\n@fa-var-affiliatetheme: \"\\f36b\";\n@fa-var-air-freshener: \"\\f5d0\";\n@fa-var-airbnb: \"\\f834\";\n@fa-var-algolia: \"\\f36c\";\n@fa-var-align-center: \"\\f037\";\n@fa-var-align-justify: \"\\f039\";\n@fa-var-align-left: \"\\f036\";\n@fa-var-align-right: \"\\f038\";\n@fa-var-alipay: \"\\f642\";\n@fa-var-allergies: \"\\f461\";\n@fa-var-amazon: \"\\f270\";\n@fa-var-amazon-pay: \"\\f42c\";\n@fa-var-ambulance: \"\\f0f9\";\n@fa-var-american-sign-language-interpreting: \"\\f2a3\";\n@fa-var-amilia: \"\\f36d\";\n@fa-var-anchor: \"\\f13d\";\n@fa-var-android: \"\\f17b\";\n@fa-var-angellist: \"\\f209\";\n@fa-var-angle-double-down: \"\\f103\";\n@fa-var-angle-double-left: \"\\f100\";\n@fa-var-angle-double-right: \"\\f101\";\n@fa-var-angle-double-up: \"\\f102\";\n@fa-var-angle-down: \"\\f107\";\n@fa-var-angle-left: \"\\f104\";\n@fa-var-angle-right: \"\\f105\";\n@fa-var-angle-up: \"\\f106\";\n@fa-var-angry: \"\\f556\";\n@fa-var-angrycreative: \"\\f36e\";\n@fa-var-angular: \"\\f420\";\n@fa-var-ankh: \"\\f644\";\n@fa-var-app-store: \"\\f36f\";\n@fa-var-app-store-ios: \"\\f370\";\n@fa-var-apper: \"\\f371\";\n@fa-var-apple: \"\\f179\";\n@fa-var-apple-alt: \"\\f5d1\";\n@fa-var-apple-pay: \"\\f415\";\n@fa-var-archive: \"\\f187\";\n@fa-var-archway: \"\\f557\";\n@fa-var-arrow-alt-circle-down: \"\\f358\";\n@fa-var-arrow-alt-circle-left: \"\\f359\";\n@fa-var-arrow-alt-circle-right: \"\\f35a\";\n@fa-var-arrow-alt-circle-up: \"\\f35b\";\n@fa-var-arrow-circle-down: \"\\f0ab\";\n@fa-var-arrow-circle-left: \"\\f0a8\";\n@fa-var-arrow-circle-right: \"\\f0a9\";\n@fa-var-arrow-circle-up: \"\\f0aa\";\n@fa-var-arrow-down: \"\\f063\";\n@fa-var-arrow-left: \"\\f060\";\n@fa-var-arrow-right: \"\\f061\";\n@fa-var-arrow-up: \"\\f062\";\n@fa-var-arrows-alt: \"\\f0b2\";\n@fa-var-arrows-alt-h: \"\\f337\";\n@fa-var-arrows-alt-v: \"\\f338\";\n@fa-var-artstation: \"\\f77a\";\n@fa-var-assistive-listening-systems: \"\\f2a2\";\n@fa-var-asterisk: \"\\f069\";\n@fa-var-asymmetrik: \"\\f372\";\n@fa-var-at: \"\\f1fa\";\n@fa-var-atlas: \"\\f558\";\n@fa-var-atlassian: \"\\f77b\";\n@fa-var-atom: \"\\f5d2\";\n@fa-var-audible: \"\\f373\";\n@fa-var-audio-description: \"\\f29e\";\n@fa-var-autoprefixer: \"\\f41c\";\n@fa-var-avianex: \"\\f374\";\n@fa-var-aviato: \"\\f421\";\n@fa-var-award: \"\\f559\";\n@fa-var-aws: \"\\f375\";\n@fa-var-baby: \"\\f77c\";\n@fa-var-baby-carriage: \"\\f77d\";\n@fa-var-backspace: \"\\f55a\";\n@fa-var-backward: \"\\f04a\";\n@fa-var-bacon: \"\\f7e5\";\n@fa-var-balance-scale: \"\\f24e\";\n@fa-var-balance-scale-left: \"\\f515\";\n@fa-var-balance-scale-right: \"\\f516\";\n@fa-var-ban: \"\\f05e\";\n@fa-var-band-aid: \"\\f462\";\n@fa-var-bandcamp: \"\\f2d5\";\n@fa-var-barcode: \"\\f02a\";\n@fa-var-bars: \"\\f0c9\";\n@fa-var-baseball-ball: \"\\f433\";\n@fa-var-basketball-ball: \"\\f434\";\n@fa-var-bath: \"\\f2cd\";\n@fa-var-battery-empty: \"\\f244\";\n@fa-var-battery-full: \"\\f240\";\n@fa-var-battery-half: \"\\f242\";\n@fa-var-battery-quarter: \"\\f243\";\n@fa-var-battery-three-quarters: \"\\f241\";\n@fa-var-battle-net: \"\\f835\";\n@fa-var-bed: \"\\f236\";\n@fa-var-beer: \"\\f0fc\";\n@fa-var-behance: \"\\f1b4\";\n@fa-var-behance-square: \"\\f1b5\";\n@fa-var-bell: \"\\f0f3\";\n@fa-var-bell-slash: \"\\f1f6\";\n@fa-var-bezier-curve: \"\\f55b\";\n@fa-var-bible: \"\\f647\";\n@fa-var-bicycle: \"\\f206\";\n@fa-var-biking: \"\\f84a\";\n@fa-var-bimobject: \"\\f378\";\n@fa-var-binoculars: \"\\f1e5\";\n@fa-var-biohazard: \"\\f780\";\n@fa-var-birthday-cake: \"\\f1fd\";\n@fa-var-bitbucket: \"\\f171\";\n@fa-var-bitcoin: \"\\f379\";\n@fa-var-bity: \"\\f37a\";\n@fa-var-black-tie: \"\\f27e\";\n@fa-var-blackberry: \"\\f37b\";\n@fa-var-blender: \"\\f517\";\n@fa-var-blender-phone: \"\\f6b6\";\n@fa-var-blind: \"\\f29d\";\n@fa-var-blog: \"\\f781\";\n@fa-var-blogger: \"\\f37c\";\n@fa-var-blogger-b: \"\\f37d\";\n@fa-var-bluetooth: \"\\f293\";\n@fa-var-bluetooth-b: \"\\f294\";\n@fa-var-bold: \"\\f032\";\n@fa-var-bolt: \"\\f0e7\";\n@fa-var-bomb: \"\\f1e2\";\n@fa-var-bone: \"\\f5d7\";\n@fa-var-bong: \"\\f55c\";\n@fa-var-book: \"\\f02d\";\n@fa-var-book-dead: \"\\f6b7\";\n@fa-var-book-medical: \"\\f7e6\";\n@fa-var-book-open: \"\\f518\";\n@fa-var-book-reader: \"\\f5da\";\n@fa-var-bookmark: \"\\f02e\";\n@fa-var-bootstrap: \"\\f836\";\n@fa-var-border-all: \"\\f84c\";\n@fa-var-border-none: \"\\f850\";\n@fa-var-border-style: \"\\f853\";\n@fa-var-bowling-ball: \"\\f436\";\n@fa-var-box: \"\\f466\";\n@fa-var-box-open: \"\\f49e\";\n@fa-var-boxes: \"\\f468\";\n@fa-var-braille: \"\\f2a1\";\n@fa-var-brain: \"\\f5dc\";\n@fa-var-bread-slice: \"\\f7ec\";\n@fa-var-briefcase: \"\\f0b1\";\n@fa-var-briefcase-medical: \"\\f469\";\n@fa-var-broadcast-tower: \"\\f519\";\n@fa-var-broom: \"\\f51a\";\n@fa-var-brush: \"\\f55d\";\n@fa-var-btc: \"\\f15a\";\n@fa-var-buffer: \"\\f837\";\n@fa-var-bug: \"\\f188\";\n@fa-var-building: \"\\f1ad\";\n@fa-var-bullhorn: \"\\f0a1\";\n@fa-var-bullseye: \"\\f140\";\n@fa-var-burn: \"\\f46a\";\n@fa-var-buromobelexperte: \"\\f37f\";\n@fa-var-bus: \"\\f207\";\n@fa-var-bus-alt: \"\\f55e\";\n@fa-var-business-time: \"\\f64a\";\n@fa-var-buysellads: \"\\f20d\";\n@fa-var-calculator: \"\\f1ec\";\n@fa-var-calendar: \"\\f133\";\n@fa-var-calendar-alt: \"\\f073\";\n@fa-var-calendar-check: \"\\f274\";\n@fa-var-calendar-day: \"\\f783\";\n@fa-var-calendar-minus: \"\\f272\";\n@fa-var-calendar-plus: \"\\f271\";\n@fa-var-calendar-times: \"\\f273\";\n@fa-var-calendar-week: \"\\f784\";\n@fa-var-camera: \"\\f030\";\n@fa-var-camera-retro: \"\\f083\";\n@fa-var-campground: \"\\f6bb\";\n@fa-var-canadian-maple-leaf: \"\\f785\";\n@fa-var-candy-cane: \"\\f786\";\n@fa-var-cannabis: \"\\f55f\";\n@fa-var-capsules: \"\\f46b\";\n@fa-var-car: \"\\f1b9\";\n@fa-var-car-alt: \"\\f5de\";\n@fa-var-car-battery: \"\\f5df\";\n@fa-var-car-crash: \"\\f5e1\";\n@fa-var-car-side: \"\\f5e4\";\n@fa-var-caret-down: \"\\f0d7\";\n@fa-var-caret-left: \"\\f0d9\";\n@fa-var-caret-right: \"\\f0da\";\n@fa-var-caret-square-down: \"\\f150\";\n@fa-var-caret-square-left: \"\\f191\";\n@fa-var-caret-square-right: \"\\f152\";\n@fa-var-caret-square-up: \"\\f151\";\n@fa-var-caret-up: \"\\f0d8\";\n@fa-var-carrot: \"\\f787\";\n@fa-var-cart-arrow-down: \"\\f218\";\n@fa-var-cart-plus: \"\\f217\";\n@fa-var-cash-register: \"\\f788\";\n@fa-var-cat: \"\\f6be\";\n@fa-var-cc-amazon-pay: \"\\f42d\";\n@fa-var-cc-amex: \"\\f1f3\";\n@fa-var-cc-apple-pay: \"\\f416\";\n@fa-var-cc-diners-club: \"\\f24c\";\n@fa-var-cc-discover: \"\\f1f2\";\n@fa-var-cc-jcb: \"\\f24b\";\n@fa-var-cc-mastercard: \"\\f1f1\";\n@fa-var-cc-paypal: \"\\f1f4\";\n@fa-var-cc-stripe: \"\\f1f5\";\n@fa-var-cc-visa: \"\\f1f0\";\n@fa-var-centercode: \"\\f380\";\n@fa-var-centos: \"\\f789\";\n@fa-var-certificate: \"\\f0a3\";\n@fa-var-chair: \"\\f6c0\";\n@fa-var-chalkboard: \"\\f51b\";\n@fa-var-chalkboard-teacher: \"\\f51c\";\n@fa-var-charging-station: \"\\f5e7\";\n@fa-var-chart-area: \"\\f1fe\";\n@fa-var-chart-bar: \"\\f080\";\n@fa-var-chart-line: \"\\f201\";\n@fa-var-chart-pie: \"\\f200\";\n@fa-var-check: \"\\f00c\";\n@fa-var-check-circle: \"\\f058\";\n@fa-var-check-double: \"\\f560\";\n@fa-var-check-square: \"\\f14a\";\n@fa-var-cheese: \"\\f7ef\";\n@fa-var-chess: \"\\f439\";\n@fa-var-chess-bishop: \"\\f43a\";\n@fa-var-chess-board: \"\\f43c\";\n@fa-var-chess-king: \"\\f43f\";\n@fa-var-chess-knight: \"\\f441\";\n@fa-var-chess-pawn: \"\\f443\";\n@fa-var-chess-queen: \"\\f445\";\n@fa-var-chess-rook: \"\\f447\";\n@fa-var-chevron-circle-down: \"\\f13a\";\n@fa-var-chevron-circle-left: \"\\f137\";\n@fa-var-chevron-circle-right: \"\\f138\";\n@fa-var-chevron-circle-up: \"\\f139\";\n@fa-var-chevron-down: \"\\f078\";\n@fa-var-chevron-left: \"\\f053\";\n@fa-var-chevron-right: \"\\f054\";\n@fa-var-chevron-up: \"\\f077\";\n@fa-var-child: \"\\f1ae\";\n@fa-var-chrome: \"\\f268\";\n@fa-var-chromecast: \"\\f838\";\n@fa-var-church: \"\\f51d\";\n@fa-var-circle: \"\\f111\";\n@fa-var-circle-notch: \"\\f1ce\";\n@fa-var-city: \"\\f64f\";\n@fa-var-clinic-medical: \"\\f7f2\";\n@fa-var-clipboard: \"\\f328\";\n@fa-var-clipboard-check: \"\\f46c\";\n@fa-var-clipboard-list: \"\\f46d\";\n@fa-var-clock: \"\\f017\";\n@fa-var-clone: \"\\f24d\";\n@fa-var-closed-captioning: \"\\f20a\";\n@fa-var-cloud: \"\\f0c2\";\n@fa-var-cloud-download-alt: \"\\f381\";\n@fa-var-cloud-meatball: \"\\f73b\";\n@fa-var-cloud-moon: \"\\f6c3\";\n@fa-var-cloud-moon-rain: \"\\f73c\";\n@fa-var-cloud-rain: \"\\f73d\";\n@fa-var-cloud-showers-heavy: \"\\f740\";\n@fa-var-cloud-sun: \"\\f6c4\";\n@fa-var-cloud-sun-rain: \"\\f743\";\n@fa-var-cloud-upload-alt: \"\\f382\";\n@fa-var-cloudscale: \"\\f383\";\n@fa-var-cloudsmith: \"\\f384\";\n@fa-var-cloudversify: \"\\f385\";\n@fa-var-cocktail: \"\\f561\";\n@fa-var-code: \"\\f121\";\n@fa-var-code-branch: \"\\f126\";\n@fa-var-codepen: \"\\f1cb\";\n@fa-var-codiepie: \"\\f284\";\n@fa-var-coffee: \"\\f0f4\";\n@fa-var-cog: \"\\f013\";\n@fa-var-cogs: \"\\f085\";\n@fa-var-coins: \"\\f51e\";\n@fa-var-columns: \"\\f0db\";\n@fa-var-comment: \"\\f075\";\n@fa-var-comment-alt: \"\\f27a\";\n@fa-var-comment-dollar: \"\\f651\";\n@fa-var-comment-dots: \"\\f4ad\";\n@fa-var-comment-medical: \"\\f7f5\";\n@fa-var-comment-slash: \"\\f4b3\";\n@fa-var-comments: \"\\f086\";\n@fa-var-comments-dollar: \"\\f653\";\n@fa-var-compact-disc: \"\\f51f\";\n@fa-var-compass: \"\\f14e\";\n@fa-var-compress: \"\\f066\";\n@fa-var-compress-arrows-alt: \"\\f78c\";\n@fa-var-concierge-bell: \"\\f562\";\n@fa-var-confluence: \"\\f78d\";\n@fa-var-connectdevelop: \"\\f20e\";\n@fa-var-contao: \"\\f26d\";\n@fa-var-cookie: \"\\f563\";\n@fa-var-cookie-bite: \"\\f564\";\n@fa-var-copy: \"\\f0c5\";\n@fa-var-copyright: \"\\f1f9\";\n@fa-var-cotton-bureau: \"\\f89e\";\n@fa-var-couch: \"\\f4b8\";\n@fa-var-cpanel: \"\\f388\";\n@fa-var-creative-commons: \"\\f25e\";\n@fa-var-creative-commons-by: \"\\f4e7\";\n@fa-var-creative-commons-nc: \"\\f4e8\";\n@fa-var-creative-commons-nc-eu: \"\\f4e9\";\n@fa-var-creative-commons-nc-jp: \"\\f4ea\";\n@fa-var-creative-commons-nd: \"\\f4eb\";\n@fa-var-creative-commons-pd: \"\\f4ec\";\n@fa-var-creative-commons-pd-alt: \"\\f4ed\";\n@fa-var-creative-commons-remix: \"\\f4ee\";\n@fa-var-creative-commons-sa: \"\\f4ef\";\n@fa-var-creative-commons-sampling: \"\\f4f0\";\n@fa-var-creative-commons-sampling-plus: \"\\f4f1\";\n@fa-var-creative-commons-share: \"\\f4f2\";\n@fa-var-creative-commons-zero: \"\\f4f3\";\n@fa-var-credit-card: \"\\f09d\";\n@fa-var-critical-role: \"\\f6c9\";\n@fa-var-crop: \"\\f125\";\n@fa-var-crop-alt: \"\\f565\";\n@fa-var-cross: \"\\f654\";\n@fa-var-crosshairs: \"\\f05b\";\n@fa-var-crow: \"\\f520\";\n@fa-var-crown: \"\\f521\";\n@fa-var-crutch: \"\\f7f7\";\n@fa-var-css3: \"\\f13c\";\n@fa-var-css3-alt: \"\\f38b\";\n@fa-var-cube: \"\\f1b2\";\n@fa-var-cubes: \"\\f1b3\";\n@fa-var-cut: \"\\f0c4\";\n@fa-var-cuttlefish: \"\\f38c\";\n@fa-var-d-and-d: \"\\f38d\";\n@fa-var-d-and-d-beyond: \"\\f6ca\";\n@fa-var-dashcube: \"\\f210\";\n@fa-var-database: \"\\f1c0\";\n@fa-var-deaf: \"\\f2a4\";\n@fa-var-delicious: \"\\f1a5\";\n@fa-var-democrat: \"\\f747\";\n@fa-var-deploydog: \"\\f38e\";\n@fa-var-deskpro: \"\\f38f\";\n@fa-var-desktop: \"\\f108\";\n@fa-var-dev: \"\\f6cc\";\n@fa-var-deviantart: \"\\f1bd\";\n@fa-var-dharmachakra: \"\\f655\";\n@fa-var-dhl: \"\\f790\";\n@fa-var-diagnoses: \"\\f470\";\n@fa-var-diaspora: \"\\f791\";\n@fa-var-dice: \"\\f522\";\n@fa-var-dice-d20: \"\\f6cf\";\n@fa-var-dice-d6: \"\\f6d1\";\n@fa-var-dice-five: \"\\f523\";\n@fa-var-dice-four: \"\\f524\";\n@fa-var-dice-one: \"\\f525\";\n@fa-var-dice-six: \"\\f526\";\n@fa-var-dice-three: \"\\f527\";\n@fa-var-dice-two: \"\\f528\";\n@fa-var-digg: \"\\f1a6\";\n@fa-var-digital-ocean: \"\\f391\";\n@fa-var-digital-tachograph: \"\\f566\";\n@fa-var-directions: \"\\f5eb\";\n@fa-var-discord: \"\\f392\";\n@fa-var-discourse: \"\\f393\";\n@fa-var-divide: \"\\f529\";\n@fa-var-dizzy: \"\\f567\";\n@fa-var-dna: \"\\f471\";\n@fa-var-dochub: \"\\f394\";\n@fa-var-docker: \"\\f395\";\n@fa-var-dog: \"\\f6d3\";\n@fa-var-dollar-sign: \"\\f155\";\n@fa-var-dolly: \"\\f472\";\n@fa-var-dolly-flatbed: \"\\f474\";\n@fa-var-donate: \"\\f4b9\";\n@fa-var-door-closed: \"\\f52a\";\n@fa-var-door-open: \"\\f52b\";\n@fa-var-dot-circle: \"\\f192\";\n@fa-var-dove: \"\\f4ba\";\n@fa-var-download: \"\\f019\";\n@fa-var-draft2digital: \"\\f396\";\n@fa-var-drafting-compass: \"\\f568\";\n@fa-var-dragon: \"\\f6d5\";\n@fa-var-draw-polygon: \"\\f5ee\";\n@fa-var-dribbble: \"\\f17d\";\n@fa-var-dribbble-square: \"\\f397\";\n@fa-var-dropbox: \"\\f16b\";\n@fa-var-drum: \"\\f569\";\n@fa-var-drum-steelpan: \"\\f56a\";\n@fa-var-drumstick-bite: \"\\f6d7\";\n@fa-var-drupal: \"\\f1a9\";\n@fa-var-dumbbell: \"\\f44b\";\n@fa-var-dumpster: \"\\f793\";\n@fa-var-dumpster-fire: \"\\f794\";\n@fa-var-dungeon: \"\\f6d9\";\n@fa-var-dyalog: \"\\f399\";\n@fa-var-earlybirds: \"\\f39a\";\n@fa-var-ebay: \"\\f4f4\";\n@fa-var-edge: \"\\f282\";\n@fa-var-edit: \"\\f044\";\n@fa-var-egg: \"\\f7fb\";\n@fa-var-eject: \"\\f052\";\n@fa-var-elementor: \"\\f430\";\n@fa-var-ellipsis-h: \"\\f141\";\n@fa-var-ellipsis-v: \"\\f142\";\n@fa-var-ello: \"\\f5f1\";\n@fa-var-ember: \"\\f423\";\n@fa-var-empire: \"\\f1d1\";\n@fa-var-envelope: \"\\f0e0\";\n@fa-var-envelope-open: \"\\f2b6\";\n@fa-var-envelope-open-text: \"\\f658\";\n@fa-var-envelope-square: \"\\f199\";\n@fa-var-envira: \"\\f299\";\n@fa-var-equals: \"\\f52c\";\n@fa-var-eraser: \"\\f12d\";\n@fa-var-erlang: \"\\f39d\";\n@fa-var-ethereum: \"\\f42e\";\n@fa-var-ethernet: \"\\f796\";\n@fa-var-etsy: \"\\f2d7\";\n@fa-var-euro-sign: \"\\f153\";\n@fa-var-evernote: \"\\f839\";\n@fa-var-exchange-alt: \"\\f362\";\n@fa-var-exclamation: \"\\f12a\";\n@fa-var-exclamation-circle: \"\\f06a\";\n@fa-var-exclamation-triangle: \"\\f071\";\n@fa-var-expand: \"\\f065\";\n@fa-var-expand-arrows-alt: \"\\f31e\";\n@fa-var-expeditedssl: \"\\f23e\";\n@fa-var-external-link-alt: \"\\f35d\";\n@fa-var-external-link-square-alt: \"\\f360\";\n@fa-var-eye: \"\\f06e\";\n@fa-var-eye-dropper: \"\\f1fb\";\n@fa-var-eye-slash: \"\\f070\";\n@fa-var-facebook: \"\\f09a\";\n@fa-var-facebook-f: \"\\f39e\";\n@fa-var-facebook-messenger: \"\\f39f\";\n@fa-var-facebook-square: \"\\f082\";\n@fa-var-fan: \"\\f863\";\n@fa-var-fantasy-flight-games: \"\\f6dc\";\n@fa-var-fast-backward: \"\\f049\";\n@fa-var-fast-forward: \"\\f050\";\n@fa-var-fax: \"\\f1ac\";\n@fa-var-feather: \"\\f52d\";\n@fa-var-feather-alt: \"\\f56b\";\n@fa-var-fedex: \"\\f797\";\n@fa-var-fedora: \"\\f798\";\n@fa-var-female: \"\\f182\";\n@fa-var-fighter-jet: \"\\f0fb\";\n@fa-var-figma: \"\\f799\";\n@fa-var-file: \"\\f15b\";\n@fa-var-file-alt: \"\\f15c\";\n@fa-var-file-archive: \"\\f1c6\";\n@fa-var-file-audio: \"\\f1c7\";\n@fa-var-file-code: \"\\f1c9\";\n@fa-var-file-contract: \"\\f56c\";\n@fa-var-file-csv: \"\\f6dd\";\n@fa-var-file-download: \"\\f56d\";\n@fa-var-file-excel: \"\\f1c3\";\n@fa-var-file-export: \"\\f56e\";\n@fa-var-file-image: \"\\f1c5\";\n@fa-var-file-import: \"\\f56f\";\n@fa-var-file-invoice: \"\\f570\";\n@fa-var-file-invoice-dollar: \"\\f571\";\n@fa-var-file-medical: \"\\f477\";\n@fa-var-file-medical-alt: \"\\f478\";\n@fa-var-file-pdf: \"\\f1c1\";\n@fa-var-file-powerpoint: \"\\f1c4\";\n@fa-var-file-prescription: \"\\f572\";\n@fa-var-file-signature: \"\\f573\";\n@fa-var-file-upload: \"\\f574\";\n@fa-var-file-video: \"\\f1c8\";\n@fa-var-file-word: \"\\f1c2\";\n@fa-var-fill: \"\\f575\";\n@fa-var-fill-drip: \"\\f576\";\n@fa-var-film: \"\\f008\";\n@fa-var-filter: \"\\f0b0\";\n@fa-var-fingerprint: \"\\f577\";\n@fa-var-fire: \"\\f06d\";\n@fa-var-fire-alt: \"\\f7e4\";\n@fa-var-fire-extinguisher: \"\\f134\";\n@fa-var-firefox: \"\\f269\";\n@fa-var-first-aid: \"\\f479\";\n@fa-var-first-order: \"\\f2b0\";\n@fa-var-first-order-alt: \"\\f50a\";\n@fa-var-firstdraft: \"\\f3a1\";\n@fa-var-fish: \"\\f578\";\n@fa-var-fist-raised: \"\\f6de\";\n@fa-var-flag: \"\\f024\";\n@fa-var-flag-checkered: \"\\f11e\";\n@fa-var-flag-usa: \"\\f74d\";\n@fa-var-flask: \"\\f0c3\";\n@fa-var-flickr: \"\\f16e\";\n@fa-var-flipboard: \"\\f44d\";\n@fa-var-flushed: \"\\f579\";\n@fa-var-fly: \"\\f417\";\n@fa-var-folder: \"\\f07b\";\n@fa-var-folder-minus: \"\\f65d\";\n@fa-var-folder-open: \"\\f07c\";\n@fa-var-folder-plus: \"\\f65e\";\n@fa-var-font: \"\\f031\";\n@fa-var-font-awesome: \"\\f2b4\";\n@fa-var-font-awesome-alt: \"\\f35c\";\n@fa-var-font-awesome-flag: \"\\f425\";\n@fa-var-font-awesome-logo-full: \"\\f4e6\";\n@fa-var-fonticons: \"\\f280\";\n@fa-var-fonticons-fi: \"\\f3a2\";\n@fa-var-football-ball: \"\\f44e\";\n@fa-var-fort-awesome: \"\\f286\";\n@fa-var-fort-awesome-alt: \"\\f3a3\";\n@fa-var-forumbee: \"\\f211\";\n@fa-var-forward: \"\\f04e\";\n@fa-var-foursquare: \"\\f180\";\n@fa-var-free-code-camp: \"\\f2c5\";\n@fa-var-freebsd: \"\\f3a4\";\n@fa-var-frog: \"\\f52e\";\n@fa-var-frown: \"\\f119\";\n@fa-var-frown-open: \"\\f57a\";\n@fa-var-fulcrum: \"\\f50b\";\n@fa-var-funnel-dollar: \"\\f662\";\n@fa-var-futbol: \"\\f1e3\";\n@fa-var-galactic-republic: \"\\f50c\";\n@fa-var-galactic-senate: \"\\f50d\";\n@fa-var-gamepad: \"\\f11b\";\n@fa-var-gas-pump: \"\\f52f\";\n@fa-var-gavel: \"\\f0e3\";\n@fa-var-gem: \"\\f3a5\";\n@fa-var-genderless: \"\\f22d\";\n@fa-var-get-pocket: \"\\f265\";\n@fa-var-gg: \"\\f260\";\n@fa-var-gg-circle: \"\\f261\";\n@fa-var-ghost: \"\\f6e2\";\n@fa-var-gift: \"\\f06b\";\n@fa-var-gifts: \"\\f79c\";\n@fa-var-git: \"\\f1d3\";\n@fa-var-git-alt: \"\\f841\";\n@fa-var-git-square: \"\\f1d2\";\n@fa-var-github: \"\\f09b\";\n@fa-var-github-alt: \"\\f113\";\n@fa-var-github-square: \"\\f092\";\n@fa-var-gitkraken: \"\\f3a6\";\n@fa-var-gitlab: \"\\f296\";\n@fa-var-gitter: \"\\f426\";\n@fa-var-glass-cheers: \"\\f79f\";\n@fa-var-glass-martini: \"\\f000\";\n@fa-var-glass-martini-alt: \"\\f57b\";\n@fa-var-glass-whiskey: \"\\f7a0\";\n@fa-var-glasses: \"\\f530\";\n@fa-var-glide: \"\\f2a5\";\n@fa-var-glide-g: \"\\f2a6\";\n@fa-var-globe: \"\\f0ac\";\n@fa-var-globe-africa: \"\\f57c\";\n@fa-var-globe-americas: \"\\f57d\";\n@fa-var-globe-asia: \"\\f57e\";\n@fa-var-globe-europe: \"\\f7a2\";\n@fa-var-gofore: \"\\f3a7\";\n@fa-var-golf-ball: \"\\f450\";\n@fa-var-goodreads: \"\\f3a8\";\n@fa-var-goodreads-g: \"\\f3a9\";\n@fa-var-google: \"\\f1a0\";\n@fa-var-google-drive: \"\\f3aa\";\n@fa-var-google-play: \"\\f3ab\";\n@fa-var-google-plus: \"\\f2b3\";\n@fa-var-google-plus-g: \"\\f0d5\";\n@fa-var-google-plus-square: \"\\f0d4\";\n@fa-var-google-wallet: \"\\f1ee\";\n@fa-var-gopuram: \"\\f664\";\n@fa-var-graduation-cap: \"\\f19d\";\n@fa-var-gratipay: \"\\f184\";\n@fa-var-grav: \"\\f2d6\";\n@fa-var-greater-than: \"\\f531\";\n@fa-var-greater-than-equal: \"\\f532\";\n@fa-var-grimace: \"\\f57f\";\n@fa-var-grin: \"\\f580\";\n@fa-var-grin-alt: \"\\f581\";\n@fa-var-grin-beam: \"\\f582\";\n@fa-var-grin-beam-sweat: \"\\f583\";\n@fa-var-grin-hearts: \"\\f584\";\n@fa-var-grin-squint: \"\\f585\";\n@fa-var-grin-squint-tears: \"\\f586\";\n@fa-var-grin-stars: \"\\f587\";\n@fa-var-grin-tears: \"\\f588\";\n@fa-var-grin-tongue: \"\\f589\";\n@fa-var-grin-tongue-squint: \"\\f58a\";\n@fa-var-grin-tongue-wink: \"\\f58b\";\n@fa-var-grin-wink: \"\\f58c\";\n@fa-var-grip-horizontal: \"\\f58d\";\n@fa-var-grip-lines: \"\\f7a4\";\n@fa-var-grip-lines-vertical: \"\\f7a5\";\n@fa-var-grip-vertical: \"\\f58e\";\n@fa-var-gripfire: \"\\f3ac\";\n@fa-var-grunt: \"\\f3ad\";\n@fa-var-guitar: \"\\f7a6\";\n@fa-var-gulp: \"\\f3ae\";\n@fa-var-h-square: \"\\f0fd\";\n@fa-var-hacker-news: \"\\f1d4\";\n@fa-var-hacker-news-square: \"\\f3af\";\n@fa-var-hackerrank: \"\\f5f7\";\n@fa-var-hamburger: \"\\f805\";\n@fa-var-hammer: \"\\f6e3\";\n@fa-var-hamsa: \"\\f665\";\n@fa-var-hand-holding: \"\\f4bd\";\n@fa-var-hand-holding-heart: \"\\f4be\";\n@fa-var-hand-holding-usd: \"\\f4c0\";\n@fa-var-hand-lizard: \"\\f258\";\n@fa-var-hand-middle-finger: \"\\f806\";\n@fa-var-hand-paper: \"\\f256\";\n@fa-var-hand-peace: \"\\f25b\";\n@fa-var-hand-point-down: \"\\f0a7\";\n@fa-var-hand-point-left: \"\\f0a5\";\n@fa-var-hand-point-right: \"\\f0a4\";\n@fa-var-hand-point-up: \"\\f0a6\";\n@fa-var-hand-pointer: \"\\f25a\";\n@fa-var-hand-rock: \"\\f255\";\n@fa-var-hand-scissors: \"\\f257\";\n@fa-var-hand-spock: \"\\f259\";\n@fa-var-hands: \"\\f4c2\";\n@fa-var-hands-helping: \"\\f4c4\";\n@fa-var-handshake: \"\\f2b5\";\n@fa-var-hanukiah: \"\\f6e6\";\n@fa-var-hard-hat: \"\\f807\";\n@fa-var-hashtag: \"\\f292\";\n@fa-var-hat-wizard: \"\\f6e8\";\n@fa-var-haykal: \"\\f666\";\n@fa-var-hdd: \"\\f0a0\";\n@fa-var-heading: \"\\f1dc\";\n@fa-var-headphones: \"\\f025\";\n@fa-var-headphones-alt: \"\\f58f\";\n@fa-var-headset: \"\\f590\";\n@fa-var-heart: \"\\f004\";\n@fa-var-heart-broken: \"\\f7a9\";\n@fa-var-heartbeat: \"\\f21e\";\n@fa-var-helicopter: \"\\f533\";\n@fa-var-highlighter: \"\\f591\";\n@fa-var-hiking: \"\\f6ec\";\n@fa-var-hippo: \"\\f6ed\";\n@fa-var-hips: \"\\f452\";\n@fa-var-hire-a-helper: \"\\f3b0\";\n@fa-var-history: \"\\f1da\";\n@fa-var-hockey-puck: \"\\f453\";\n@fa-var-holly-berry: \"\\f7aa\";\n@fa-var-home: \"\\f015\";\n@fa-var-hooli: \"\\f427\";\n@fa-var-hornbill: \"\\f592\";\n@fa-var-horse: \"\\f6f0\";\n@fa-var-horse-head: \"\\f7ab\";\n@fa-var-hospital: \"\\f0f8\";\n@fa-var-hospital-alt: \"\\f47d\";\n@fa-var-hospital-symbol: \"\\f47e\";\n@fa-var-hot-tub: \"\\f593\";\n@fa-var-hotdog: \"\\f80f\";\n@fa-var-hotel: \"\\f594\";\n@fa-var-hotjar: \"\\f3b1\";\n@fa-var-hourglass: \"\\f254\";\n@fa-var-hourglass-end: \"\\f253\";\n@fa-var-hourglass-half: \"\\f252\";\n@fa-var-hourglass-start: \"\\f251\";\n@fa-var-house-damage: \"\\f6f1\";\n@fa-var-houzz: \"\\f27c\";\n@fa-var-hryvnia: \"\\f6f2\";\n@fa-var-html5: \"\\f13b\";\n@fa-var-hubspot: \"\\f3b2\";\n@fa-var-i-cursor: \"\\f246\";\n@fa-var-ice-cream: \"\\f810\";\n@fa-var-icicles: \"\\f7ad\";\n@fa-var-icons: \"\\f86d\";\n@fa-var-id-badge: \"\\f2c1\";\n@fa-var-id-card: \"\\f2c2\";\n@fa-var-id-card-alt: \"\\f47f\";\n@fa-var-igloo: \"\\f7ae\";\n@fa-var-image: \"\\f03e\";\n@fa-var-images: \"\\f302\";\n@fa-var-imdb: \"\\f2d8\";\n@fa-var-inbox: \"\\f01c\";\n@fa-var-indent: \"\\f03c\";\n@fa-var-industry: \"\\f275\";\n@fa-var-infinity: \"\\f534\";\n@fa-var-info: \"\\f129\";\n@fa-var-info-circle: \"\\f05a\";\n@fa-var-instagram: \"\\f16d\";\n@fa-var-intercom: \"\\f7af\";\n@fa-var-internet-explorer: \"\\f26b\";\n@fa-var-invision: \"\\f7b0\";\n@fa-var-ioxhost: \"\\f208\";\n@fa-var-italic: \"\\f033\";\n@fa-var-itch-io: \"\\f83a\";\n@fa-var-itunes: \"\\f3b4\";\n@fa-var-itunes-note: \"\\f3b5\";\n@fa-var-java: \"\\f4e4\";\n@fa-var-jedi: \"\\f669\";\n@fa-var-jedi-order: \"\\f50e\";\n@fa-var-jenkins: \"\\f3b6\";\n@fa-var-jira: \"\\f7b1\";\n@fa-var-joget: \"\\f3b7\";\n@fa-var-joint: \"\\f595\";\n@fa-var-joomla: \"\\f1aa\";\n@fa-var-journal-whills: \"\\f66a\";\n@fa-var-js: \"\\f3b8\";\n@fa-var-js-square: \"\\f3b9\";\n@fa-var-jsfiddle: \"\\f1cc\";\n@fa-var-kaaba: \"\\f66b\";\n@fa-var-kaggle: \"\\f5fa\";\n@fa-var-key: \"\\f084\";\n@fa-var-keybase: \"\\f4f5\";\n@fa-var-keyboard: \"\\f11c\";\n@fa-var-keycdn: \"\\f3ba\";\n@fa-var-khanda: \"\\f66d\";\n@fa-var-kickstarter: \"\\f3bb\";\n@fa-var-kickstarter-k: \"\\f3bc\";\n@fa-var-kiss: \"\\f596\";\n@fa-var-kiss-beam: \"\\f597\";\n@fa-var-kiss-wink-heart: \"\\f598\";\n@fa-var-kiwi-bird: \"\\f535\";\n@fa-var-korvue: \"\\f42f\";\n@fa-var-landmark: \"\\f66f\";\n@fa-var-language: \"\\f1ab\";\n@fa-var-laptop: \"\\f109\";\n@fa-var-laptop-code: \"\\f5fc\";\n@fa-var-laptop-medical: \"\\f812\";\n@fa-var-laravel: \"\\f3bd\";\n@fa-var-lastfm: \"\\f202\";\n@fa-var-lastfm-square: \"\\f203\";\n@fa-var-laugh: \"\\f599\";\n@fa-var-laugh-beam: \"\\f59a\";\n@fa-var-laugh-squint: \"\\f59b\";\n@fa-var-laugh-wink: \"\\f59c\";\n@fa-var-layer-group: \"\\f5fd\";\n@fa-var-leaf: \"\\f06c\";\n@fa-var-leanpub: \"\\f212\";\n@fa-var-lemon: \"\\f094\";\n@fa-var-less: \"\\f41d\";\n@fa-var-less-than: \"\\f536\";\n@fa-var-less-than-equal: \"\\f537\";\n@fa-var-level-down-alt: \"\\f3be\";\n@fa-var-level-up-alt: \"\\f3bf\";\n@fa-var-life-ring: \"\\f1cd\";\n@fa-var-lightbulb: \"\\f0eb\";\n@fa-var-line: \"\\f3c0\";\n@fa-var-link: \"\\f0c1\";\n@fa-var-linkedin: \"\\f08c\";\n@fa-var-linkedin-in: \"\\f0e1\";\n@fa-var-linode: \"\\f2b8\";\n@fa-var-linux: \"\\f17c\";\n@fa-var-lira-sign: \"\\f195\";\n@fa-var-list: \"\\f03a\";\n@fa-var-list-alt: \"\\f022\";\n@fa-var-list-ol: \"\\f0cb\";\n@fa-var-list-ul: \"\\f0ca\";\n@fa-var-location-arrow: \"\\f124\";\n@fa-var-lock: \"\\f023\";\n@fa-var-lock-open: \"\\f3c1\";\n@fa-var-long-arrow-alt-down: \"\\f309\";\n@fa-var-long-arrow-alt-left: \"\\f30a\";\n@fa-var-long-arrow-alt-right: \"\\f30b\";\n@fa-var-long-arrow-alt-up: \"\\f30c\";\n@fa-var-low-vision: \"\\f2a8\";\n@fa-var-luggage-cart: \"\\f59d\";\n@fa-var-lyft: \"\\f3c3\";\n@fa-var-magento: \"\\f3c4\";\n@fa-var-magic: \"\\f0d0\";\n@fa-var-magnet: \"\\f076\";\n@fa-var-mail-bulk: \"\\f674\";\n@fa-var-mailchimp: \"\\f59e\";\n@fa-var-male: \"\\f183\";\n@fa-var-mandalorian: \"\\f50f\";\n@fa-var-map: \"\\f279\";\n@fa-var-map-marked: \"\\f59f\";\n@fa-var-map-marked-alt: \"\\f5a0\";\n@fa-var-map-marker: \"\\f041\";\n@fa-var-map-marker-alt: \"\\f3c5\";\n@fa-var-map-pin: \"\\f276\";\n@fa-var-map-signs: \"\\f277\";\n@fa-var-markdown: \"\\f60f\";\n@fa-var-marker: \"\\f5a1\";\n@fa-var-mars: \"\\f222\";\n@fa-var-mars-double: \"\\f227\";\n@fa-var-mars-stroke: \"\\f229\";\n@fa-var-mars-stroke-h: \"\\f22b\";\n@fa-var-mars-stroke-v: \"\\f22a\";\n@fa-var-mask: \"\\f6fa\";\n@fa-var-mastodon: \"\\f4f6\";\n@fa-var-maxcdn: \"\\f136\";\n@fa-var-medal: \"\\f5a2\";\n@fa-var-medapps: \"\\f3c6\";\n@fa-var-medium: \"\\f23a\";\n@fa-var-medium-m: \"\\f3c7\";\n@fa-var-medkit: \"\\f0fa\";\n@fa-var-medrt: \"\\f3c8\";\n@fa-var-meetup: \"\\f2e0\";\n@fa-var-megaport: \"\\f5a3\";\n@fa-var-meh: \"\\f11a\";\n@fa-var-meh-blank: \"\\f5a4\";\n@fa-var-meh-rolling-eyes: \"\\f5a5\";\n@fa-var-memory: \"\\f538\";\n@fa-var-mendeley: \"\\f7b3\";\n@fa-var-menorah: \"\\f676\";\n@fa-var-mercury: \"\\f223\";\n@fa-var-meteor: \"\\f753\";\n@fa-var-microchip: \"\\f2db\";\n@fa-var-microphone: \"\\f130\";\n@fa-var-microphone-alt: \"\\f3c9\";\n@fa-var-microphone-alt-slash: \"\\f539\";\n@fa-var-microphone-slash: \"\\f131\";\n@fa-var-microscope: \"\\f610\";\n@fa-var-microsoft: \"\\f3ca\";\n@fa-var-minus: \"\\f068\";\n@fa-var-minus-circle: \"\\f056\";\n@fa-var-minus-square: \"\\f146\";\n@fa-var-mitten: \"\\f7b5\";\n@fa-var-mix: \"\\f3cb\";\n@fa-var-mixcloud: \"\\f289\";\n@fa-var-mizuni: \"\\f3cc\";\n@fa-var-mobile: \"\\f10b\";\n@fa-var-mobile-alt: \"\\f3cd\";\n@fa-var-modx: \"\\f285\";\n@fa-var-monero: \"\\f3d0\";\n@fa-var-money-bill: \"\\f0d6\";\n@fa-var-money-bill-alt: \"\\f3d1\";\n@fa-var-money-bill-wave: \"\\f53a\";\n@fa-var-money-bill-wave-alt: \"\\f53b\";\n@fa-var-money-check: \"\\f53c\";\n@fa-var-money-check-alt: \"\\f53d\";\n@fa-var-monument: \"\\f5a6\";\n@fa-var-moon: \"\\f186\";\n@fa-var-mortar-pestle: \"\\f5a7\";\n@fa-var-mosque: \"\\f678\";\n@fa-var-motorcycle: \"\\f21c\";\n@fa-var-mountain: \"\\f6fc\";\n@fa-var-mouse-pointer: \"\\f245\";\n@fa-var-mug-hot: \"\\f7b6\";\n@fa-var-music: \"\\f001\";\n@fa-var-napster: \"\\f3d2\";\n@fa-var-neos: \"\\f612\";\n@fa-var-network-wired: \"\\f6ff\";\n@fa-var-neuter: \"\\f22c\";\n@fa-var-newspaper: \"\\f1ea\";\n@fa-var-nimblr: \"\\f5a8\";\n@fa-var-node: \"\\f419\";\n@fa-var-node-js: \"\\f3d3\";\n@fa-var-not-equal: \"\\f53e\";\n@fa-var-notes-medical: \"\\f481\";\n@fa-var-npm: \"\\f3d4\";\n@fa-var-ns8: \"\\f3d5\";\n@fa-var-nutritionix: \"\\f3d6\";\n@fa-var-object-group: \"\\f247\";\n@fa-var-object-ungroup: \"\\f248\";\n@fa-var-odnoklassniki: \"\\f263\";\n@fa-var-odnoklassniki-square: \"\\f264\";\n@fa-var-oil-can: \"\\f613\";\n@fa-var-old-republic: \"\\f510\";\n@fa-var-om: \"\\f679\";\n@fa-var-opencart: \"\\f23d\";\n@fa-var-openid: \"\\f19b\";\n@fa-var-opera: \"\\f26a\";\n@fa-var-optin-monster: \"\\f23c\";\n@fa-var-osi: \"\\f41a\";\n@fa-var-otter: \"\\f700\";\n@fa-var-outdent: \"\\f03b\";\n@fa-var-page4: \"\\f3d7\";\n@fa-var-pagelines: \"\\f18c\";\n@fa-var-pager: \"\\f815\";\n@fa-var-paint-brush: \"\\f1fc\";\n@fa-var-paint-roller: \"\\f5aa\";\n@fa-var-palette: \"\\f53f\";\n@fa-var-palfed: \"\\f3d8\";\n@fa-var-pallet: \"\\f482\";\n@fa-var-paper-plane: \"\\f1d8\";\n@fa-var-paperclip: \"\\f0c6\";\n@fa-var-parachute-box: \"\\f4cd\";\n@fa-var-paragraph: \"\\f1dd\";\n@fa-var-parking: \"\\f540\";\n@fa-var-passport: \"\\f5ab\";\n@fa-var-pastafarianism: \"\\f67b\";\n@fa-var-paste: \"\\f0ea\";\n@fa-var-patreon: \"\\f3d9\";\n@fa-var-pause: \"\\f04c\";\n@fa-var-pause-circle: \"\\f28b\";\n@fa-var-paw: \"\\f1b0\";\n@fa-var-paypal: \"\\f1ed\";\n@fa-var-peace: \"\\f67c\";\n@fa-var-pen: \"\\f304\";\n@fa-var-pen-alt: \"\\f305\";\n@fa-var-pen-fancy: \"\\f5ac\";\n@fa-var-pen-nib: \"\\f5ad\";\n@fa-var-pen-square: \"\\f14b\";\n@fa-var-pencil-alt: \"\\f303\";\n@fa-var-pencil-ruler: \"\\f5ae\";\n@fa-var-penny-arcade: \"\\f704\";\n@fa-var-people-carry: \"\\f4ce\";\n@fa-var-pepper-hot: \"\\f816\";\n@fa-var-percent: \"\\f295\";\n@fa-var-percentage: \"\\f541\";\n@fa-var-periscope: \"\\f3da\";\n@fa-var-person-booth: \"\\f756\";\n@fa-var-phabricator: \"\\f3db\";\n@fa-var-phoenix-framework: \"\\f3dc\";\n@fa-var-phoenix-squadron: \"\\f511\";\n@fa-var-phone: \"\\f095\";\n@fa-var-phone-alt: \"\\f879\";\n@fa-var-phone-slash: \"\\f3dd\";\n@fa-var-phone-square: \"\\f098\";\n@fa-var-phone-square-alt: \"\\f87b\";\n@fa-var-phone-volume: \"\\f2a0\";\n@fa-var-photo-video: \"\\f87c\";\n@fa-var-php: \"\\f457\";\n@fa-var-pied-piper: \"\\f2ae\";\n@fa-var-pied-piper-alt: \"\\f1a8\";\n@fa-var-pied-piper-hat: \"\\f4e5\";\n@fa-var-pied-piper-pp: \"\\f1a7\";\n@fa-var-piggy-bank: \"\\f4d3\";\n@fa-var-pills: \"\\f484\";\n@fa-var-pinterest: \"\\f0d2\";\n@fa-var-pinterest-p: \"\\f231\";\n@fa-var-pinterest-square: \"\\f0d3\";\n@fa-var-pizza-slice: \"\\f818\";\n@fa-var-place-of-worship: \"\\f67f\";\n@fa-var-plane: \"\\f072\";\n@fa-var-plane-arrival: \"\\f5af\";\n@fa-var-plane-departure: \"\\f5b0\";\n@fa-var-play: \"\\f04b\";\n@fa-var-play-circle: \"\\f144\";\n@fa-var-playstation: \"\\f3df\";\n@fa-var-plug: \"\\f1e6\";\n@fa-var-plus: \"\\f067\";\n@fa-var-plus-circle: \"\\f055\";\n@fa-var-plus-square: \"\\f0fe\";\n@fa-var-podcast: \"\\f2ce\";\n@fa-var-poll: \"\\f681\";\n@fa-var-poll-h: \"\\f682\";\n@fa-var-poo: \"\\f2fe\";\n@fa-var-poo-storm: \"\\f75a\";\n@fa-var-poop: \"\\f619\";\n@fa-var-portrait: \"\\f3e0\";\n@fa-var-pound-sign: \"\\f154\";\n@fa-var-power-off: \"\\f011\";\n@fa-var-pray: \"\\f683\";\n@fa-var-praying-hands: \"\\f684\";\n@fa-var-prescription: \"\\f5b1\";\n@fa-var-prescription-bottle: \"\\f485\";\n@fa-var-prescription-bottle-alt: \"\\f486\";\n@fa-var-print: \"\\f02f\";\n@fa-var-procedures: \"\\f487\";\n@fa-var-product-hunt: \"\\f288\";\n@fa-var-project-diagram: \"\\f542\";\n@fa-var-pushed: \"\\f3e1\";\n@fa-var-puzzle-piece: \"\\f12e\";\n@fa-var-python: \"\\f3e2\";\n@fa-var-qq: \"\\f1d6\";\n@fa-var-qrcode: \"\\f029\";\n@fa-var-question: \"\\f128\";\n@fa-var-question-circle: \"\\f059\";\n@fa-var-quidditch: \"\\f458\";\n@fa-var-quinscape: \"\\f459\";\n@fa-var-quora: \"\\f2c4\";\n@fa-var-quote-left: \"\\f10d\";\n@fa-var-quote-right: \"\\f10e\";\n@fa-var-quran: \"\\f687\";\n@fa-var-r-project: \"\\f4f7\";\n@fa-var-radiation: \"\\f7b9\";\n@fa-var-radiation-alt: \"\\f7ba\";\n@fa-var-rainbow: \"\\f75b\";\n@fa-var-random: \"\\f074\";\n@fa-var-raspberry-pi: \"\\f7bb\";\n@fa-var-ravelry: \"\\f2d9\";\n@fa-var-react: \"\\f41b\";\n@fa-var-reacteurope: \"\\f75d\";\n@fa-var-readme: \"\\f4d5\";\n@fa-var-rebel: \"\\f1d0\";\n@fa-var-receipt: \"\\f543\";\n@fa-var-recycle: \"\\f1b8\";\n@fa-var-red-river: \"\\f3e3\";\n@fa-var-reddit: \"\\f1a1\";\n@fa-var-reddit-alien: \"\\f281\";\n@fa-var-reddit-square: \"\\f1a2\";\n@fa-var-redhat: \"\\f7bc\";\n@fa-var-redo: \"\\f01e\";\n@fa-var-redo-alt: \"\\f2f9\";\n@fa-var-registered: \"\\f25d\";\n@fa-var-remove-format: \"\\f87d\";\n@fa-var-renren: \"\\f18b\";\n@fa-var-reply: \"\\f3e5\";\n@fa-var-reply-all: \"\\f122\";\n@fa-var-replyd: \"\\f3e6\";\n@fa-var-republican: \"\\f75e\";\n@fa-var-researchgate: \"\\f4f8\";\n@fa-var-resolving: \"\\f3e7\";\n@fa-var-restroom: \"\\f7bd\";\n@fa-var-retweet: \"\\f079\";\n@fa-var-rev: \"\\f5b2\";\n@fa-var-ribbon: \"\\f4d6\";\n@fa-var-ring: \"\\f70b\";\n@fa-var-road: \"\\f018\";\n@fa-var-robot: \"\\f544\";\n@fa-var-rocket: \"\\f135\";\n@fa-var-rocketchat: \"\\f3e8\";\n@fa-var-rockrms: \"\\f3e9\";\n@fa-var-route: \"\\f4d7\";\n@fa-var-rss: \"\\f09e\";\n@fa-var-rss-square: \"\\f143\";\n@fa-var-ruble-sign: \"\\f158\";\n@fa-var-ruler: \"\\f545\";\n@fa-var-ruler-combined: \"\\f546\";\n@fa-var-ruler-horizontal: \"\\f547\";\n@fa-var-ruler-vertical: \"\\f548\";\n@fa-var-running: \"\\f70c\";\n@fa-var-rupee-sign: \"\\f156\";\n@fa-var-sad-cry: \"\\f5b3\";\n@fa-var-sad-tear: \"\\f5b4\";\n@fa-var-safari: \"\\f267\";\n@fa-var-salesforce: \"\\f83b\";\n@fa-var-sass: \"\\f41e\";\n@fa-var-satellite: \"\\f7bf\";\n@fa-var-satellite-dish: \"\\f7c0\";\n@fa-var-save: \"\\f0c7\";\n@fa-var-schlix: \"\\f3ea\";\n@fa-var-school: \"\\f549\";\n@fa-var-screwdriver: \"\\f54a\";\n@fa-var-scribd: \"\\f28a\";\n@fa-var-scroll: \"\\f70e\";\n@fa-var-sd-card: \"\\f7c2\";\n@fa-var-search: \"\\f002\";\n@fa-var-search-dollar: \"\\f688\";\n@fa-var-search-location: \"\\f689\";\n@fa-var-search-minus: \"\\f010\";\n@fa-var-search-plus: \"\\f00e\";\n@fa-var-searchengin: \"\\f3eb\";\n@fa-var-seedling: \"\\f4d8\";\n@fa-var-sellcast: \"\\f2da\";\n@fa-var-sellsy: \"\\f213\";\n@fa-var-server: \"\\f233\";\n@fa-var-servicestack: \"\\f3ec\";\n@fa-var-shapes: \"\\f61f\";\n@fa-var-share: \"\\f064\";\n@fa-var-share-alt: \"\\f1e0\";\n@fa-var-share-alt-square: \"\\f1e1\";\n@fa-var-share-square: \"\\f14d\";\n@fa-var-shekel-sign: \"\\f20b\";\n@fa-var-shield-alt: \"\\f3ed\";\n@fa-var-ship: \"\\f21a\";\n@fa-var-shipping-fast: \"\\f48b\";\n@fa-var-shirtsinbulk: \"\\f214\";\n@fa-var-shoe-prints: \"\\f54b\";\n@fa-var-shopping-bag: \"\\f290\";\n@fa-var-shopping-basket: \"\\f291\";\n@fa-var-shopping-cart: \"\\f07a\";\n@fa-var-shopware: \"\\f5b5\";\n@fa-var-shower: \"\\f2cc\";\n@fa-var-shuttle-van: \"\\f5b6\";\n@fa-var-sign: \"\\f4d9\";\n@fa-var-sign-in-alt: \"\\f2f6\";\n@fa-var-sign-language: \"\\f2a7\";\n@fa-var-sign-out-alt: \"\\f2f5\";\n@fa-var-signal: \"\\f012\";\n@fa-var-signature: \"\\f5b7\";\n@fa-var-sim-card: \"\\f7c4\";\n@fa-var-simplybuilt: \"\\f215\";\n@fa-var-sistrix: \"\\f3ee\";\n@fa-var-sitemap: \"\\f0e8\";\n@fa-var-sith: \"\\f512\";\n@fa-var-skating: \"\\f7c5\";\n@fa-var-sketch: \"\\f7c6\";\n@fa-var-skiing: \"\\f7c9\";\n@fa-var-skiing-nordic: \"\\f7ca\";\n@fa-var-skull: \"\\f54c\";\n@fa-var-skull-crossbones: \"\\f714\";\n@fa-var-skyatlas: \"\\f216\";\n@fa-var-skype: \"\\f17e\";\n@fa-var-slack: \"\\f198\";\n@fa-var-slack-hash: \"\\f3ef\";\n@fa-var-slash: \"\\f715\";\n@fa-var-sleigh: \"\\f7cc\";\n@fa-var-sliders-h: \"\\f1de\";\n@fa-var-slideshare: \"\\f1e7\";\n@fa-var-smile: \"\\f118\";\n@fa-var-smile-beam: \"\\f5b8\";\n@fa-var-smile-wink: \"\\f4da\";\n@fa-var-smog: \"\\f75f\";\n@fa-var-smoking: \"\\f48d\";\n@fa-var-smoking-ban: \"\\f54d\";\n@fa-var-sms: \"\\f7cd\";\n@fa-var-snapchat: \"\\f2ab\";\n@fa-var-snapchat-ghost: \"\\f2ac\";\n@fa-var-snapchat-square: \"\\f2ad\";\n@fa-var-snowboarding: \"\\f7ce\";\n@fa-var-snowflake: \"\\f2dc\";\n@fa-var-snowman: \"\\f7d0\";\n@fa-var-snowplow: \"\\f7d2\";\n@fa-var-socks: \"\\f696\";\n@fa-var-solar-panel: \"\\f5ba\";\n@fa-var-sort: \"\\f0dc\";\n@fa-var-sort-alpha-down: \"\\f15d\";\n@fa-var-sort-alpha-down-alt: \"\\f881\";\n@fa-var-sort-alpha-up: \"\\f15e\";\n@fa-var-sort-alpha-up-alt: \"\\f882\";\n@fa-var-sort-amount-down: \"\\f160\";\n@fa-var-sort-amount-down-alt: \"\\f884\";\n@fa-var-sort-amount-up: \"\\f161\";\n@fa-var-sort-amount-up-alt: \"\\f885\";\n@fa-var-sort-down: \"\\f0dd\";\n@fa-var-sort-numeric-down: \"\\f162\";\n@fa-var-sort-numeric-down-alt: \"\\f886\";\n@fa-var-sort-numeric-up: \"\\f163\";\n@fa-var-sort-numeric-up-alt: \"\\f887\";\n@fa-var-sort-up: \"\\f0de\";\n@fa-var-soundcloud: \"\\f1be\";\n@fa-var-sourcetree: \"\\f7d3\";\n@fa-var-spa: \"\\f5bb\";\n@fa-var-space-shuttle: \"\\f197\";\n@fa-var-speakap: \"\\f3f3\";\n@fa-var-speaker-deck: \"\\f83c\";\n@fa-var-spell-check: \"\\f891\";\n@fa-var-spider: \"\\f717\";\n@fa-var-spinner: \"\\f110\";\n@fa-var-splotch: \"\\f5bc\";\n@fa-var-spotify: \"\\f1bc\";\n@fa-var-spray-can: \"\\f5bd\";\n@fa-var-square: \"\\f0c8\";\n@fa-var-square-full: \"\\f45c\";\n@fa-var-square-root-alt: \"\\f698\";\n@fa-var-squarespace: \"\\f5be\";\n@fa-var-stack-exchange: \"\\f18d\";\n@fa-var-stack-overflow: \"\\f16c\";\n@fa-var-stackpath: \"\\f842\";\n@fa-var-stamp: \"\\f5bf\";\n@fa-var-star: \"\\f005\";\n@fa-var-star-and-crescent: \"\\f699\";\n@fa-var-star-half: \"\\f089\";\n@fa-var-star-half-alt: \"\\f5c0\";\n@fa-var-star-of-david: \"\\f69a\";\n@fa-var-star-of-life: \"\\f621\";\n@fa-var-staylinked: \"\\f3f5\";\n@fa-var-steam: \"\\f1b6\";\n@fa-var-steam-square: \"\\f1b7\";\n@fa-var-steam-symbol: \"\\f3f6\";\n@fa-var-step-backward: \"\\f048\";\n@fa-var-step-forward: \"\\f051\";\n@fa-var-stethoscope: \"\\f0f1\";\n@fa-var-sticker-mule: \"\\f3f7\";\n@fa-var-sticky-note: \"\\f249\";\n@fa-var-stop: \"\\f04d\";\n@fa-var-stop-circle: \"\\f28d\";\n@fa-var-stopwatch: \"\\f2f2\";\n@fa-var-store: \"\\f54e\";\n@fa-var-store-alt: \"\\f54f\";\n@fa-var-strava: \"\\f428\";\n@fa-var-stream: \"\\f550\";\n@fa-var-street-view: \"\\f21d\";\n@fa-var-strikethrough: \"\\f0cc\";\n@fa-var-stripe: \"\\f429\";\n@fa-var-stripe-s: \"\\f42a\";\n@fa-var-stroopwafel: \"\\f551\";\n@fa-var-studiovinari: \"\\f3f8\";\n@fa-var-stumbleupon: \"\\f1a4\";\n@fa-var-stumbleupon-circle: \"\\f1a3\";\n@fa-var-subscript: \"\\f12c\";\n@fa-var-subway: \"\\f239\";\n@fa-var-suitcase: \"\\f0f2\";\n@fa-var-suitcase-rolling: \"\\f5c1\";\n@fa-var-sun: \"\\f185\";\n@fa-var-superpowers: \"\\f2dd\";\n@fa-var-superscript: \"\\f12b\";\n@fa-var-supple: \"\\f3f9\";\n@fa-var-surprise: \"\\f5c2\";\n@fa-var-suse: \"\\f7d6\";\n@fa-var-swatchbook: \"\\f5c3\";\n@fa-var-swimmer: \"\\f5c4\";\n@fa-var-swimming-pool: \"\\f5c5\";\n@fa-var-symfony: \"\\f83d\";\n@fa-var-synagogue: \"\\f69b\";\n@fa-var-sync: \"\\f021\";\n@fa-var-sync-alt: \"\\f2f1\";\n@fa-var-syringe: \"\\f48e\";\n@fa-var-table: \"\\f0ce\";\n@fa-var-table-tennis: \"\\f45d\";\n@fa-var-tablet: \"\\f10a\";\n@fa-var-tablet-alt: \"\\f3fa\";\n@fa-var-tablets: \"\\f490\";\n@fa-var-tachometer-alt: \"\\f3fd\";\n@fa-var-tag: \"\\f02b\";\n@fa-var-tags: \"\\f02c\";\n@fa-var-tape: \"\\f4db\";\n@fa-var-tasks: \"\\f0ae\";\n@fa-var-taxi: \"\\f1ba\";\n@fa-var-teamspeak: \"\\f4f9\";\n@fa-var-teeth: \"\\f62e\";\n@fa-var-teeth-open: \"\\f62f\";\n@fa-var-telegram: \"\\f2c6\";\n@fa-var-telegram-plane: \"\\f3fe\";\n@fa-var-temperature-high: \"\\f769\";\n@fa-var-temperature-low: \"\\f76b\";\n@fa-var-tencent-weibo: \"\\f1d5\";\n@fa-var-tenge: \"\\f7d7\";\n@fa-var-terminal: \"\\f120\";\n@fa-var-text-height: \"\\f034\";\n@fa-var-text-width: \"\\f035\";\n@fa-var-th: \"\\f00a\";\n@fa-var-th-large: \"\\f009\";\n@fa-var-th-list: \"\\f00b\";\n@fa-var-the-red-yeti: \"\\f69d\";\n@fa-var-theater-masks: \"\\f630\";\n@fa-var-themeco: \"\\f5c6\";\n@fa-var-themeisle: \"\\f2b2\";\n@fa-var-thermometer: \"\\f491\";\n@fa-var-thermometer-empty: \"\\f2cb\";\n@fa-var-thermometer-full: \"\\f2c7\";\n@fa-var-thermometer-half: \"\\f2c9\";\n@fa-var-thermometer-quarter: \"\\f2ca\";\n@fa-var-thermometer-three-quarters: \"\\f2c8\";\n@fa-var-think-peaks: \"\\f731\";\n@fa-var-thumbs-down: \"\\f165\";\n@fa-var-thumbs-up: \"\\f164\";\n@fa-var-thumbtack: \"\\f08d\";\n@fa-var-ticket-alt: \"\\f3ff\";\n@fa-var-times: \"\\f00d\";\n@fa-var-times-circle: \"\\f057\";\n@fa-var-tint: \"\\f043\";\n@fa-var-tint-slash: \"\\f5c7\";\n@fa-var-tired: \"\\f5c8\";\n@fa-var-toggle-off: \"\\f204\";\n@fa-var-toggle-on: \"\\f205\";\n@fa-var-toilet: \"\\f7d8\";\n@fa-var-toilet-paper: \"\\f71e\";\n@fa-var-toolbox: \"\\f552\";\n@fa-var-tools: \"\\f7d9\";\n@fa-var-tooth: \"\\f5c9\";\n@fa-var-torah: \"\\f6a0\";\n@fa-var-torii-gate: \"\\f6a1\";\n@fa-var-tractor: \"\\f722\";\n@fa-var-trade-federation: \"\\f513\";\n@fa-var-trademark: \"\\f25c\";\n@fa-var-traffic-light: \"\\f637\";\n@fa-var-train: \"\\f238\";\n@fa-var-tram: \"\\f7da\";\n@fa-var-transgender: \"\\f224\";\n@fa-var-transgender-alt: \"\\f225\";\n@fa-var-trash: \"\\f1f8\";\n@fa-var-trash-alt: \"\\f2ed\";\n@fa-var-trash-restore: \"\\f829\";\n@fa-var-trash-restore-alt: \"\\f82a\";\n@fa-var-tree: \"\\f1bb\";\n@fa-var-trello: \"\\f181\";\n@fa-var-tripadvisor: \"\\f262\";\n@fa-var-trophy: \"\\f091\";\n@fa-var-truck: \"\\f0d1\";\n@fa-var-truck-loading: \"\\f4de\";\n@fa-var-truck-monster: \"\\f63b\";\n@fa-var-truck-moving: \"\\f4df\";\n@fa-var-truck-pickup: \"\\f63c\";\n@fa-var-tshirt: \"\\f553\";\n@fa-var-tty: \"\\f1e4\";\n@fa-var-tumblr: \"\\f173\";\n@fa-var-tumblr-square: \"\\f174\";\n@fa-var-tv: \"\\f26c\";\n@fa-var-twitch: \"\\f1e8\";\n@fa-var-twitter: \"\\f099\";\n@fa-var-twitter-square: \"\\f081\";\n@fa-var-typo3: \"\\f42b\";\n@fa-var-uber: \"\\f402\";\n@fa-var-ubuntu: \"\\f7df\";\n@fa-var-uikit: \"\\f403\";\n@fa-var-umbrella: \"\\f0e9\";\n@fa-var-umbrella-beach: \"\\f5ca\";\n@fa-var-underline: \"\\f0cd\";\n@fa-var-undo: \"\\f0e2\";\n@fa-var-undo-alt: \"\\f2ea\";\n@fa-var-uniregistry: \"\\f404\";\n@fa-var-universal-access: \"\\f29a\";\n@fa-var-university: \"\\f19c\";\n@fa-var-unlink: \"\\f127\";\n@fa-var-unlock: \"\\f09c\";\n@fa-var-unlock-alt: \"\\f13e\";\n@fa-var-untappd: \"\\f405\";\n@fa-var-upload: \"\\f093\";\n@fa-var-ups: \"\\f7e0\";\n@fa-var-usb: \"\\f287\";\n@fa-var-user: \"\\f007\";\n@fa-var-user-alt: \"\\f406\";\n@fa-var-user-alt-slash: \"\\f4fa\";\n@fa-var-user-astronaut: \"\\f4fb\";\n@fa-var-user-check: \"\\f4fc\";\n@fa-var-user-circle: \"\\f2bd\";\n@fa-var-user-clock: \"\\f4fd\";\n@fa-var-user-cog: \"\\f4fe\";\n@fa-var-user-edit: \"\\f4ff\";\n@fa-var-user-friends: \"\\f500\";\n@fa-var-user-graduate: \"\\f501\";\n@fa-var-user-injured: \"\\f728\";\n@fa-var-user-lock: \"\\f502\";\n@fa-var-user-md: \"\\f0f0\";\n@fa-var-user-minus: \"\\f503\";\n@fa-var-user-ninja: \"\\f504\";\n@fa-var-user-nurse: \"\\f82f\";\n@fa-var-user-plus: \"\\f234\";\n@fa-var-user-secret: \"\\f21b\";\n@fa-var-user-shield: \"\\f505\";\n@fa-var-user-slash: \"\\f506\";\n@fa-var-user-tag: \"\\f507\";\n@fa-var-user-tie: \"\\f508\";\n@fa-var-user-times: \"\\f235\";\n@fa-var-users: \"\\f0c0\";\n@fa-var-users-cog: \"\\f509\";\n@fa-var-usps: \"\\f7e1\";\n@fa-var-ussunnah: \"\\f407\";\n@fa-var-utensil-spoon: \"\\f2e5\";\n@fa-var-utensils: \"\\f2e7\";\n@fa-var-vaadin: \"\\f408\";\n@fa-var-vector-square: \"\\f5cb\";\n@fa-var-venus: \"\\f221\";\n@fa-var-venus-double: \"\\f226\";\n@fa-var-venus-mars: \"\\f228\";\n@fa-var-viacoin: \"\\f237\";\n@fa-var-viadeo: \"\\f2a9\";\n@fa-var-viadeo-square: \"\\f2aa\";\n@fa-var-vial: \"\\f492\";\n@fa-var-vials: \"\\f493\";\n@fa-var-viber: \"\\f409\";\n@fa-var-video: \"\\f03d\";\n@fa-var-video-slash: \"\\f4e2\";\n@fa-var-vihara: \"\\f6a7\";\n@fa-var-vimeo: \"\\f40a\";\n@fa-var-vimeo-square: \"\\f194\";\n@fa-var-vimeo-v: \"\\f27d\";\n@fa-var-vine: \"\\f1ca\";\n@fa-var-vk: \"\\f189\";\n@fa-var-vnv: \"\\f40b\";\n@fa-var-voicemail: \"\\f897\";\n@fa-var-volleyball-ball: \"\\f45f\";\n@fa-var-volume-down: \"\\f027\";\n@fa-var-volume-mute: \"\\f6a9\";\n@fa-var-volume-off: \"\\f026\";\n@fa-var-volume-up: \"\\f028\";\n@fa-var-vote-yea: \"\\f772\";\n@fa-var-vr-cardboard: \"\\f729\";\n@fa-var-vuejs: \"\\f41f\";\n@fa-var-walking: \"\\f554\";\n@fa-var-wallet: \"\\f555\";\n@fa-var-warehouse: \"\\f494\";\n@fa-var-water: \"\\f773\";\n@fa-var-wave-square: \"\\f83e\";\n@fa-var-waze: \"\\f83f\";\n@fa-var-weebly: \"\\f5cc\";\n@fa-var-weibo: \"\\f18a\";\n@fa-var-weight: \"\\f496\";\n@fa-var-weight-hanging: \"\\f5cd\";\n@fa-var-weixin: \"\\f1d7\";\n@fa-var-whatsapp: \"\\f232\";\n@fa-var-whatsapp-square: \"\\f40c\";\n@fa-var-wheelchair: \"\\f193\";\n@fa-var-whmcs: \"\\f40d\";\n@fa-var-wifi: \"\\f1eb\";\n@fa-var-wikipedia-w: \"\\f266\";\n@fa-var-wind: \"\\f72e\";\n@fa-var-window-close: \"\\f410\";\n@fa-var-window-maximize: \"\\f2d0\";\n@fa-var-window-minimize: \"\\f2d1\";\n@fa-var-window-restore: \"\\f2d2\";\n@fa-var-windows: \"\\f17a\";\n@fa-var-wine-bottle: \"\\f72f\";\n@fa-var-wine-glass: \"\\f4e3\";\n@fa-var-wine-glass-alt: \"\\f5ce\";\n@fa-var-wix: \"\\f5cf\";\n@fa-var-wizards-of-the-coast: \"\\f730\";\n@fa-var-wolf-pack-battalion: \"\\f514\";\n@fa-var-won-sign: \"\\f159\";\n@fa-var-wordpress: \"\\f19a\";\n@fa-var-wordpress-simple: \"\\f411\";\n@fa-var-wpbeginner: \"\\f297\";\n@fa-var-wpexplorer: \"\\f2de\";\n@fa-var-wpforms: \"\\f298\";\n@fa-var-wpressr: \"\\f3e4\";\n@fa-var-wrench: \"\\f0ad\";\n@fa-var-x-ray: \"\\f497\";\n@fa-var-xbox: \"\\f412\";\n@fa-var-xing: \"\\f168\";\n@fa-var-xing-square: \"\\f169\";\n@fa-var-y-combinator: \"\\f23b\";\n@fa-var-yahoo: \"\\f19e\";\n@fa-var-yammer: \"\\f840\";\n@fa-var-yandex: \"\\f413\";\n@fa-var-yandex-international: \"\\f414\";\n@fa-var-yarn: \"\\f7e3\";\n@fa-var-yelp: \"\\f1e9\";\n@fa-var-yen-sign: \"\\f157\";\n@fa-var-yin-yang: \"\\f6ad\";\n@fa-var-yoast: \"\\f2b1\";\n@fa-var-youtube: \"\\f167\";\n@fa-var-youtube-square: \"\\f431\";\n@fa-var-zhihu: \"\\f63f\";\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/brands.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: @fa-font-display;\n  src: url('@{fa-font-path}/fa-brands-400.eot');\n  src: url('@{fa-font-path}/fa-brands-400.eot?#iefix') format('embedded-opentype'),\n    url('@{fa-font-path}/fa-brands-400.woff2') format('woff2'),\n    url('@{fa-font-path}/fa-brands-400.woff') format('woff'),\n    url('@{fa-font-path}/fa-brands-400.ttf') format('truetype'),\n    url('@{fa-font-path}/fa-brands-400.svg#fontawesome') format('svg');\n}\n\n.fab {\n  font-family: 'Font Awesome 5 Brands';\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/fontawesome.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n@import \"_mixins.less\";\n@import \"_core.less\";\n@import \"_larger.less\";\n@import \"_fixed-width.less\";\n@import \"_list.less\";\n@import \"_bordered-pulled.less\";\n@import \"_animated.less\";\n@import \"_rotated-flipped.less\";\n@import \"_stacked.less\";\n@import \"_icons.less\";\n@import \"_screen-reader.less\";\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/regular.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: @fa-font-display;\n  src: url('@{fa-font-path}/fa-regular-400.eot');\n  src: url('@{fa-font-path}/fa-regular-400.eot?#iefix') format('embedded-opentype'),\n    url('@{fa-font-path}/fa-regular-400.woff2') format('woff2'),\n    url('@{fa-font-path}/fa-regular-400.woff') format('woff'),\n    url('@{fa-font-path}/fa-regular-400.ttf') format('truetype'),\n    url('@{fa-font-path}/fa-regular-400.svg#fontawesome') format('svg');\n}\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/solid.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import \"_variables.less\";\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: @fa-font-display;\n  src: url('@{fa-font-path}/fa-solid-900.eot');\n  src: url('@{fa-font-path}/fa-solid-900.eot?#iefix') format('embedded-opentype'),\n    url('@{fa-font-path}/fa-solid-900.woff2') format('woff2'),\n    url('@{fa-font-path}/fa-solid-900.woff') format('woff'),\n    url('@{fa-font-path}/fa-solid-900.ttf') format('truetype'),\n    url('@{fa-font-path}/fa-solid-900.svg#fontawesome') format('svg');\n}\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/less/v4-shims.less",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import '_variables.less';\n@import '_shims.less';\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_animated.scss",
    "content": "// Animated Icons\n// --------------------------\n\n.#{$fa-css-prefix}-spin {\n  animation: fa-spin 2s infinite linear;\n}\n\n.#{$fa-css-prefix}-pulse {\n  animation: fa-spin 1s infinite steps(8);\n}\n\n@keyframes fa-spin {\n  0% {\n    transform: rotate(0deg);\n  }\n\n  100% {\n    transform: rotate(360deg);\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_bordered-pulled.scss",
    "content": "// Bordered & Pulled\n// -------------------------\n\n.#{$fa-css-prefix}-border {\n  border: solid .08em $fa-border-color;\n  border-radius: .1em;\n  padding: .2em .25em .15em;\n}\n\n.#{$fa-css-prefix}-pull-left { float: left; }\n.#{$fa-css-prefix}-pull-right { float: right; }\n\n.#{$fa-css-prefix},\n.fas,\n.far,\n.fal,\n.fab {\n  &.#{$fa-css-prefix}-pull-left { margin-right: .3em; }\n  &.#{$fa-css-prefix}-pull-right { margin-left: .3em; }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_core.scss",
    "content": "// Base Class Definition\n// -------------------------\n\n.#{$fa-css-prefix},\n.fas,\n.far,\n.fal,\n.fad,\n.fab {\n  -moz-osx-font-smoothing: grayscale;\n  -webkit-font-smoothing: antialiased;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  text-rendering: auto;\n  line-height: 1;\n}\n\n%fa-icon {\n  @include fa-icon;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_fixed-width.scss",
    "content": "// Fixed Width Icons\n// -------------------------\n.#{$fa-css-prefix}-fw {\n  text-align: center;\n  width: $fa-fw-width;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_icons.scss",
    "content": "/* Font Awesome uses the Unicode Private Use Area (PUA) to ensure screen\nreaders do not read off random characters that represent icons */\n\n.#{$fa-css-prefix}-500px:before { content: fa-content($fa-var-500px); }\n.#{$fa-css-prefix}-accessible-icon:before { content: fa-content($fa-var-accessible-icon); }\n.#{$fa-css-prefix}-accusoft:before { content: fa-content($fa-var-accusoft); }\n.#{$fa-css-prefix}-acquisitions-incorporated:before { content: fa-content($fa-var-acquisitions-incorporated); }\n.#{$fa-css-prefix}-ad:before { content: fa-content($fa-var-ad); }\n.#{$fa-css-prefix}-address-book:before { content: fa-content($fa-var-address-book); }\n.#{$fa-css-prefix}-address-card:before { content: fa-content($fa-var-address-card); }\n.#{$fa-css-prefix}-adjust:before { content: fa-content($fa-var-adjust); }\n.#{$fa-css-prefix}-adn:before { content: fa-content($fa-var-adn); }\n.#{$fa-css-prefix}-adobe:before { content: fa-content($fa-var-adobe); }\n.#{$fa-css-prefix}-adversal:before { content: fa-content($fa-var-adversal); }\n.#{$fa-css-prefix}-affiliatetheme:before { content: fa-content($fa-var-affiliatetheme); }\n.#{$fa-css-prefix}-air-freshener:before { content: fa-content($fa-var-air-freshener); }\n.#{$fa-css-prefix}-airbnb:before { content: fa-content($fa-var-airbnb); }\n.#{$fa-css-prefix}-algolia:before { content: fa-content($fa-var-algolia); }\n.#{$fa-css-prefix}-align-center:before { content: fa-content($fa-var-align-center); }\n.#{$fa-css-prefix}-align-justify:before { content: fa-content($fa-var-align-justify); }\n.#{$fa-css-prefix}-align-left:before { content: fa-content($fa-var-align-left); }\n.#{$fa-css-prefix}-align-right:before { content: fa-content($fa-var-align-right); }\n.#{$fa-css-prefix}-alipay:before { content: fa-content($fa-var-alipay); }\n.#{$fa-css-prefix}-allergies:before { content: fa-content($fa-var-allergies); }\n.#{$fa-css-prefix}-amazon:before { content: fa-content($fa-var-amazon); }\n.#{$fa-css-prefix}-amazon-pay:before { content: fa-content($fa-var-amazon-pay); }\n.#{$fa-css-prefix}-ambulance:before { content: fa-content($fa-var-ambulance); }\n.#{$fa-css-prefix}-american-sign-language-interpreting:before { content: fa-content($fa-var-american-sign-language-interpreting); }\n.#{$fa-css-prefix}-amilia:before { content: fa-content($fa-var-amilia); }\n.#{$fa-css-prefix}-anchor:before { content: fa-content($fa-var-anchor); }\n.#{$fa-css-prefix}-android:before { content: fa-content($fa-var-android); }\n.#{$fa-css-prefix}-angellist:before { content: fa-content($fa-var-angellist); }\n.#{$fa-css-prefix}-angle-double-down:before { content: fa-content($fa-var-angle-double-down); }\n.#{$fa-css-prefix}-angle-double-left:before { content: fa-content($fa-var-angle-double-left); }\n.#{$fa-css-prefix}-angle-double-right:before { content: fa-content($fa-var-angle-double-right); }\n.#{$fa-css-prefix}-angle-double-up:before { content: fa-content($fa-var-angle-double-up); }\n.#{$fa-css-prefix}-angle-down:before { content: fa-content($fa-var-angle-down); }\n.#{$fa-css-prefix}-angle-left:before { content: fa-content($fa-var-angle-left); }\n.#{$fa-css-prefix}-angle-right:before { content: fa-content($fa-var-angle-right); }\n.#{$fa-css-prefix}-angle-up:before { content: fa-content($fa-var-angle-up); }\n.#{$fa-css-prefix}-angry:before { content: fa-content($fa-var-angry); }\n.#{$fa-css-prefix}-angrycreative:before { content: fa-content($fa-var-angrycreative); }\n.#{$fa-css-prefix}-angular:before { content: fa-content($fa-var-angular); }\n.#{$fa-css-prefix}-ankh:before { content: fa-content($fa-var-ankh); }\n.#{$fa-css-prefix}-app-store:before { content: fa-content($fa-var-app-store); }\n.#{$fa-css-prefix}-app-store-ios:before { content: fa-content($fa-var-app-store-ios); }\n.#{$fa-css-prefix}-apper:before { content: fa-content($fa-var-apper); }\n.#{$fa-css-prefix}-apple:before { content: fa-content($fa-var-apple); }\n.#{$fa-css-prefix}-apple-alt:before { content: fa-content($fa-var-apple-alt); }\n.#{$fa-css-prefix}-apple-pay:before { content: fa-content($fa-var-apple-pay); }\n.#{$fa-css-prefix}-archive:before { content: fa-content($fa-var-archive); }\n.#{$fa-css-prefix}-archway:before { content: fa-content($fa-var-archway); }\n.#{$fa-css-prefix}-arrow-alt-circle-down:before { content: fa-content($fa-var-arrow-alt-circle-down); }\n.#{$fa-css-prefix}-arrow-alt-circle-left:before { content: fa-content($fa-var-arrow-alt-circle-left); }\n.#{$fa-css-prefix}-arrow-alt-circle-right:before { content: fa-content($fa-var-arrow-alt-circle-right); }\n.#{$fa-css-prefix}-arrow-alt-circle-up:before { content: fa-content($fa-var-arrow-alt-circle-up); }\n.#{$fa-css-prefix}-arrow-circle-down:before { content: fa-content($fa-var-arrow-circle-down); }\n.#{$fa-css-prefix}-arrow-circle-left:before { content: fa-content($fa-var-arrow-circle-left); }\n.#{$fa-css-prefix}-arrow-circle-right:before { content: fa-content($fa-var-arrow-circle-right); }\n.#{$fa-css-prefix}-arrow-circle-up:before { content: fa-content($fa-var-arrow-circle-up); }\n.#{$fa-css-prefix}-arrow-down:before { content: fa-content($fa-var-arrow-down); }\n.#{$fa-css-prefix}-arrow-left:before { content: fa-content($fa-var-arrow-left); }\n.#{$fa-css-prefix}-arrow-right:before { content: fa-content($fa-var-arrow-right); }\n.#{$fa-css-prefix}-arrow-up:before { content: fa-content($fa-var-arrow-up); }\n.#{$fa-css-prefix}-arrows-alt:before { content: fa-content($fa-var-arrows-alt); }\n.#{$fa-css-prefix}-arrows-alt-h:before { content: fa-content($fa-var-arrows-alt-h); }\n.#{$fa-css-prefix}-arrows-alt-v:before { content: fa-content($fa-var-arrows-alt-v); }\n.#{$fa-css-prefix}-artstation:before { content: fa-content($fa-var-artstation); }\n.#{$fa-css-prefix}-assistive-listening-systems:before { content: fa-content($fa-var-assistive-listening-systems); }\n.#{$fa-css-prefix}-asterisk:before { content: fa-content($fa-var-asterisk); }\n.#{$fa-css-prefix}-asymmetrik:before { content: fa-content($fa-var-asymmetrik); }\n.#{$fa-css-prefix}-at:before { content: fa-content($fa-var-at); }\n.#{$fa-css-prefix}-atlas:before { content: fa-content($fa-var-atlas); }\n.#{$fa-css-prefix}-atlassian:before { content: fa-content($fa-var-atlassian); }\n.#{$fa-css-prefix}-atom:before { content: fa-content($fa-var-atom); }\n.#{$fa-css-prefix}-audible:before { content: fa-content($fa-var-audible); }\n.#{$fa-css-prefix}-audio-description:before { content: fa-content($fa-var-audio-description); }\n.#{$fa-css-prefix}-autoprefixer:before { content: fa-content($fa-var-autoprefixer); }\n.#{$fa-css-prefix}-avianex:before { content: fa-content($fa-var-avianex); }\n.#{$fa-css-prefix}-aviato:before { content: fa-content($fa-var-aviato); }\n.#{$fa-css-prefix}-award:before { content: fa-content($fa-var-award); }\n.#{$fa-css-prefix}-aws:before { content: fa-content($fa-var-aws); }\n.#{$fa-css-prefix}-baby:before { content: fa-content($fa-var-baby); }\n.#{$fa-css-prefix}-baby-carriage:before { content: fa-content($fa-var-baby-carriage); }\n.#{$fa-css-prefix}-backspace:before { content: fa-content($fa-var-backspace); }\n.#{$fa-css-prefix}-backward:before { content: fa-content($fa-var-backward); }\n.#{$fa-css-prefix}-bacon:before { content: fa-content($fa-var-bacon); }\n.#{$fa-css-prefix}-balance-scale:before { content: fa-content($fa-var-balance-scale); }\n.#{$fa-css-prefix}-balance-scale-left:before { content: fa-content($fa-var-balance-scale-left); }\n.#{$fa-css-prefix}-balance-scale-right:before { content: fa-content($fa-var-balance-scale-right); }\n.#{$fa-css-prefix}-ban:before { content: fa-content($fa-var-ban); }\n.#{$fa-css-prefix}-band-aid:before { content: fa-content($fa-var-band-aid); }\n.#{$fa-css-prefix}-bandcamp:before { content: fa-content($fa-var-bandcamp); }\n.#{$fa-css-prefix}-barcode:before { content: fa-content($fa-var-barcode); }\n.#{$fa-css-prefix}-bars:before { content: fa-content($fa-var-bars); }\n.#{$fa-css-prefix}-baseball-ball:before { content: fa-content($fa-var-baseball-ball); }\n.#{$fa-css-prefix}-basketball-ball:before { content: fa-content($fa-var-basketball-ball); }\n.#{$fa-css-prefix}-bath:before { content: fa-content($fa-var-bath); }\n.#{$fa-css-prefix}-battery-empty:before { content: fa-content($fa-var-battery-empty); }\n.#{$fa-css-prefix}-battery-full:before { content: fa-content($fa-var-battery-full); }\n.#{$fa-css-prefix}-battery-half:before { content: fa-content($fa-var-battery-half); }\n.#{$fa-css-prefix}-battery-quarter:before { content: fa-content($fa-var-battery-quarter); }\n.#{$fa-css-prefix}-battery-three-quarters:before { content: fa-content($fa-var-battery-three-quarters); }\n.#{$fa-css-prefix}-battle-net:before { content: fa-content($fa-var-battle-net); }\n.#{$fa-css-prefix}-bed:before { content: fa-content($fa-var-bed); }\n.#{$fa-css-prefix}-beer:before { content: fa-content($fa-var-beer); }\n.#{$fa-css-prefix}-behance:before { content: fa-content($fa-var-behance); }\n.#{$fa-css-prefix}-behance-square:before { content: fa-content($fa-var-behance-square); }\n.#{$fa-css-prefix}-bell:before { content: fa-content($fa-var-bell); }\n.#{$fa-css-prefix}-bell-slash:before { content: fa-content($fa-var-bell-slash); }\n.#{$fa-css-prefix}-bezier-curve:before { content: fa-content($fa-var-bezier-curve); }\n.#{$fa-css-prefix}-bible:before { content: fa-content($fa-var-bible); }\n.#{$fa-css-prefix}-bicycle:before { content: fa-content($fa-var-bicycle); }\n.#{$fa-css-prefix}-biking:before { content: fa-content($fa-var-biking); }\n.#{$fa-css-prefix}-bimobject:before { content: fa-content($fa-var-bimobject); }\n.#{$fa-css-prefix}-binoculars:before { content: fa-content($fa-var-binoculars); }\n.#{$fa-css-prefix}-biohazard:before { content: fa-content($fa-var-biohazard); }\n.#{$fa-css-prefix}-birthday-cake:before { content: fa-content($fa-var-birthday-cake); }\n.#{$fa-css-prefix}-bitbucket:before { content: fa-content($fa-var-bitbucket); }\n.#{$fa-css-prefix}-bitcoin:before { content: fa-content($fa-var-bitcoin); }\n.#{$fa-css-prefix}-bity:before { content: fa-content($fa-var-bity); }\n.#{$fa-css-prefix}-black-tie:before { content: fa-content($fa-var-black-tie); }\n.#{$fa-css-prefix}-blackberry:before { content: fa-content($fa-var-blackberry); }\n.#{$fa-css-prefix}-blender:before { content: fa-content($fa-var-blender); }\n.#{$fa-css-prefix}-blender-phone:before { content: fa-content($fa-var-blender-phone); }\n.#{$fa-css-prefix}-blind:before { content: fa-content($fa-var-blind); }\n.#{$fa-css-prefix}-blog:before { content: fa-content($fa-var-blog); }\n.#{$fa-css-prefix}-blogger:before { content: fa-content($fa-var-blogger); }\n.#{$fa-css-prefix}-blogger-b:before { content: fa-content($fa-var-blogger-b); }\n.#{$fa-css-prefix}-bluetooth:before { content: fa-content($fa-var-bluetooth); }\n.#{$fa-css-prefix}-bluetooth-b:before { content: fa-content($fa-var-bluetooth-b); }\n.#{$fa-css-prefix}-bold:before { content: fa-content($fa-var-bold); }\n.#{$fa-css-prefix}-bolt:before { content: fa-content($fa-var-bolt); }\n.#{$fa-css-prefix}-bomb:before { content: fa-content($fa-var-bomb); }\n.#{$fa-css-prefix}-bone:before { content: fa-content($fa-var-bone); }\n.#{$fa-css-prefix}-bong:before { content: fa-content($fa-var-bong); }\n.#{$fa-css-prefix}-book:before { content: fa-content($fa-var-book); }\n.#{$fa-css-prefix}-book-dead:before { content: fa-content($fa-var-book-dead); }\n.#{$fa-css-prefix}-book-medical:before { content: fa-content($fa-var-book-medical); }\n.#{$fa-css-prefix}-book-open:before { content: fa-content($fa-var-book-open); }\n.#{$fa-css-prefix}-book-reader:before { content: fa-content($fa-var-book-reader); }\n.#{$fa-css-prefix}-bookmark:before { content: fa-content($fa-var-bookmark); }\n.#{$fa-css-prefix}-bootstrap:before { content: fa-content($fa-var-bootstrap); }\n.#{$fa-css-prefix}-border-all:before { content: fa-content($fa-var-border-all); }\n.#{$fa-css-prefix}-border-none:before { content: fa-content($fa-var-border-none); }\n.#{$fa-css-prefix}-border-style:before { content: fa-content($fa-var-border-style); }\n.#{$fa-css-prefix}-bowling-ball:before { content: fa-content($fa-var-bowling-ball); }\n.#{$fa-css-prefix}-box:before { content: fa-content($fa-var-box); }\n.#{$fa-css-prefix}-box-open:before { content: fa-content($fa-var-box-open); }\n.#{$fa-css-prefix}-boxes:before { content: fa-content($fa-var-boxes); }\n.#{$fa-css-prefix}-braille:before { content: fa-content($fa-var-braille); }\n.#{$fa-css-prefix}-brain:before { content: fa-content($fa-var-brain); }\n.#{$fa-css-prefix}-bread-slice:before { content: fa-content($fa-var-bread-slice); }\n.#{$fa-css-prefix}-briefcase:before { content: fa-content($fa-var-briefcase); }\n.#{$fa-css-prefix}-briefcase-medical:before { content: fa-content($fa-var-briefcase-medical); }\n.#{$fa-css-prefix}-broadcast-tower:before { content: fa-content($fa-var-broadcast-tower); }\n.#{$fa-css-prefix}-broom:before { content: fa-content($fa-var-broom); }\n.#{$fa-css-prefix}-brush:before { content: fa-content($fa-var-brush); }\n.#{$fa-css-prefix}-btc:before { content: fa-content($fa-var-btc); }\n.#{$fa-css-prefix}-buffer:before { content: fa-content($fa-var-buffer); }\n.#{$fa-css-prefix}-bug:before { content: fa-content($fa-var-bug); }\n.#{$fa-css-prefix}-building:before { content: fa-content($fa-var-building); }\n.#{$fa-css-prefix}-bullhorn:before { content: fa-content($fa-var-bullhorn); }\n.#{$fa-css-prefix}-bullseye:before { content: fa-content($fa-var-bullseye); }\n.#{$fa-css-prefix}-burn:before { content: fa-content($fa-var-burn); }\n.#{$fa-css-prefix}-buromobelexperte:before { content: fa-content($fa-var-buromobelexperte); }\n.#{$fa-css-prefix}-bus:before { content: fa-content($fa-var-bus); }\n.#{$fa-css-prefix}-bus-alt:before { content: fa-content($fa-var-bus-alt); }\n.#{$fa-css-prefix}-business-time:before { content: fa-content($fa-var-business-time); }\n.#{$fa-css-prefix}-buysellads:before { content: fa-content($fa-var-buysellads); }\n.#{$fa-css-prefix}-calculator:before { content: fa-content($fa-var-calculator); }\n.#{$fa-css-prefix}-calendar:before { content: fa-content($fa-var-calendar); }\n.#{$fa-css-prefix}-calendar-alt:before { content: fa-content($fa-var-calendar-alt); }\n.#{$fa-css-prefix}-calendar-check:before { content: fa-content($fa-var-calendar-check); }\n.#{$fa-css-prefix}-calendar-day:before { content: fa-content($fa-var-calendar-day); }\n.#{$fa-css-prefix}-calendar-minus:before { content: fa-content($fa-var-calendar-minus); }\n.#{$fa-css-prefix}-calendar-plus:before { content: fa-content($fa-var-calendar-plus); }\n.#{$fa-css-prefix}-calendar-times:before { content: fa-content($fa-var-calendar-times); }\n.#{$fa-css-prefix}-calendar-week:before { content: fa-content($fa-var-calendar-week); }\n.#{$fa-css-prefix}-camera:before { content: fa-content($fa-var-camera); }\n.#{$fa-css-prefix}-camera-retro:before { content: fa-content($fa-var-camera-retro); }\n.#{$fa-css-prefix}-campground:before { content: fa-content($fa-var-campground); }\n.#{$fa-css-prefix}-canadian-maple-leaf:before { content: fa-content($fa-var-canadian-maple-leaf); }\n.#{$fa-css-prefix}-candy-cane:before { content: fa-content($fa-var-candy-cane); }\n.#{$fa-css-prefix}-cannabis:before { content: fa-content($fa-var-cannabis); }\n.#{$fa-css-prefix}-capsules:before { content: fa-content($fa-var-capsules); }\n.#{$fa-css-prefix}-car:before { content: fa-content($fa-var-car); }\n.#{$fa-css-prefix}-car-alt:before { content: fa-content($fa-var-car-alt); }\n.#{$fa-css-prefix}-car-battery:before { content: fa-content($fa-var-car-battery); }\n.#{$fa-css-prefix}-car-crash:before { content: fa-content($fa-var-car-crash); }\n.#{$fa-css-prefix}-car-side:before { content: fa-content($fa-var-car-side); }\n.#{$fa-css-prefix}-caret-down:before { content: fa-content($fa-var-caret-down); }\n.#{$fa-css-prefix}-caret-left:before { content: fa-content($fa-var-caret-left); }\n.#{$fa-css-prefix}-caret-right:before { content: fa-content($fa-var-caret-right); }\n.#{$fa-css-prefix}-caret-square-down:before { content: fa-content($fa-var-caret-square-down); }\n.#{$fa-css-prefix}-caret-square-left:before { content: fa-content($fa-var-caret-square-left); }\n.#{$fa-css-prefix}-caret-square-right:before { content: fa-content($fa-var-caret-square-right); }\n.#{$fa-css-prefix}-caret-square-up:before { content: fa-content($fa-var-caret-square-up); }\n.#{$fa-css-prefix}-caret-up:before { content: fa-content($fa-var-caret-up); }\n.#{$fa-css-prefix}-carrot:before { content: fa-content($fa-var-carrot); }\n.#{$fa-css-prefix}-cart-arrow-down:before { content: fa-content($fa-var-cart-arrow-down); }\n.#{$fa-css-prefix}-cart-plus:before { content: fa-content($fa-var-cart-plus); }\n.#{$fa-css-prefix}-cash-register:before { content: fa-content($fa-var-cash-register); }\n.#{$fa-css-prefix}-cat:before { content: fa-content($fa-var-cat); }\n.#{$fa-css-prefix}-cc-amazon-pay:before { content: fa-content($fa-var-cc-amazon-pay); }\n.#{$fa-css-prefix}-cc-amex:before { content: fa-content($fa-var-cc-amex); }\n.#{$fa-css-prefix}-cc-apple-pay:before { content: fa-content($fa-var-cc-apple-pay); }\n.#{$fa-css-prefix}-cc-diners-club:before { content: fa-content($fa-var-cc-diners-club); }\n.#{$fa-css-prefix}-cc-discover:before { content: fa-content($fa-var-cc-discover); }\n.#{$fa-css-prefix}-cc-jcb:before { content: fa-content($fa-var-cc-jcb); }\n.#{$fa-css-prefix}-cc-mastercard:before { content: fa-content($fa-var-cc-mastercard); }\n.#{$fa-css-prefix}-cc-paypal:before { content: fa-content($fa-var-cc-paypal); }\n.#{$fa-css-prefix}-cc-stripe:before { content: fa-content($fa-var-cc-stripe); }\n.#{$fa-css-prefix}-cc-visa:before { content: fa-content($fa-var-cc-visa); }\n.#{$fa-css-prefix}-centercode:before { content: fa-content($fa-var-centercode); }\n.#{$fa-css-prefix}-centos:before { content: fa-content($fa-var-centos); }\n.#{$fa-css-prefix}-certificate:before { content: fa-content($fa-var-certificate); }\n.#{$fa-css-prefix}-chair:before { content: fa-content($fa-var-chair); }\n.#{$fa-css-prefix}-chalkboard:before { content: fa-content($fa-var-chalkboard); }\n.#{$fa-css-prefix}-chalkboard-teacher:before { content: fa-content($fa-var-chalkboard-teacher); }\n.#{$fa-css-prefix}-charging-station:before { content: fa-content($fa-var-charging-station); }\n.#{$fa-css-prefix}-chart-area:before { content: fa-content($fa-var-chart-area); }\n.#{$fa-css-prefix}-chart-bar:before { content: fa-content($fa-var-chart-bar); }\n.#{$fa-css-prefix}-chart-line:before { content: fa-content($fa-var-chart-line); }\n.#{$fa-css-prefix}-chart-pie:before { content: fa-content($fa-var-chart-pie); }\n.#{$fa-css-prefix}-check:before { content: fa-content($fa-var-check); }\n.#{$fa-css-prefix}-check-circle:before { content: fa-content($fa-var-check-circle); }\n.#{$fa-css-prefix}-check-double:before { content: fa-content($fa-var-check-double); }\n.#{$fa-css-prefix}-check-square:before { content: fa-content($fa-var-check-square); }\n.#{$fa-css-prefix}-cheese:before { content: fa-content($fa-var-cheese); }\n.#{$fa-css-prefix}-chess:before { content: fa-content($fa-var-chess); }\n.#{$fa-css-prefix}-chess-bishop:before { content: fa-content($fa-var-chess-bishop); }\n.#{$fa-css-prefix}-chess-board:before { content: fa-content($fa-var-chess-board); }\n.#{$fa-css-prefix}-chess-king:before { content: fa-content($fa-var-chess-king); }\n.#{$fa-css-prefix}-chess-knight:before { content: fa-content($fa-var-chess-knight); }\n.#{$fa-css-prefix}-chess-pawn:before { content: fa-content($fa-var-chess-pawn); }\n.#{$fa-css-prefix}-chess-queen:before { content: fa-content($fa-var-chess-queen); }\n.#{$fa-css-prefix}-chess-rook:before { content: fa-content($fa-var-chess-rook); }\n.#{$fa-css-prefix}-chevron-circle-down:before { content: fa-content($fa-var-chevron-circle-down); }\n.#{$fa-css-prefix}-chevron-circle-left:before { content: fa-content($fa-var-chevron-circle-left); }\n.#{$fa-css-prefix}-chevron-circle-right:before { content: fa-content($fa-var-chevron-circle-right); }\n.#{$fa-css-prefix}-chevron-circle-up:before { content: fa-content($fa-var-chevron-circle-up); }\n.#{$fa-css-prefix}-chevron-down:before { content: fa-content($fa-var-chevron-down); }\n.#{$fa-css-prefix}-chevron-left:before { content: fa-content($fa-var-chevron-left); }\n.#{$fa-css-prefix}-chevron-right:before { content: fa-content($fa-var-chevron-right); }\n.#{$fa-css-prefix}-chevron-up:before { content: fa-content($fa-var-chevron-up); }\n.#{$fa-css-prefix}-child:before { content: fa-content($fa-var-child); }\n.#{$fa-css-prefix}-chrome:before { content: fa-content($fa-var-chrome); }\n.#{$fa-css-prefix}-chromecast:before { content: fa-content($fa-var-chromecast); }\n.#{$fa-css-prefix}-church:before { content: fa-content($fa-var-church); }\n.#{$fa-css-prefix}-circle:before { content: fa-content($fa-var-circle); }\n.#{$fa-css-prefix}-circle-notch:before { content: fa-content($fa-var-circle-notch); }\n.#{$fa-css-prefix}-city:before { content: fa-content($fa-var-city); }\n.#{$fa-css-prefix}-clinic-medical:before { content: fa-content($fa-var-clinic-medical); }\n.#{$fa-css-prefix}-clipboard:before { content: fa-content($fa-var-clipboard); }\n.#{$fa-css-prefix}-clipboard-check:before { content: fa-content($fa-var-clipboard-check); }\n.#{$fa-css-prefix}-clipboard-list:before { content: fa-content($fa-var-clipboard-list); }\n.#{$fa-css-prefix}-clock:before { content: fa-content($fa-var-clock); }\n.#{$fa-css-prefix}-clone:before { content: fa-content($fa-var-clone); }\n.#{$fa-css-prefix}-closed-captioning:before { content: fa-content($fa-var-closed-captioning); }\n.#{$fa-css-prefix}-cloud:before { content: fa-content($fa-var-cloud); }\n.#{$fa-css-prefix}-cloud-download-alt:before { content: fa-content($fa-var-cloud-download-alt); }\n.#{$fa-css-prefix}-cloud-meatball:before { content: fa-content($fa-var-cloud-meatball); }\n.#{$fa-css-prefix}-cloud-moon:before { content: fa-content($fa-var-cloud-moon); }\n.#{$fa-css-prefix}-cloud-moon-rain:before { content: fa-content($fa-var-cloud-moon-rain); }\n.#{$fa-css-prefix}-cloud-rain:before { content: fa-content($fa-var-cloud-rain); }\n.#{$fa-css-prefix}-cloud-showers-heavy:before { content: fa-content($fa-var-cloud-showers-heavy); }\n.#{$fa-css-prefix}-cloud-sun:before { content: fa-content($fa-var-cloud-sun); }\n.#{$fa-css-prefix}-cloud-sun-rain:before { content: fa-content($fa-var-cloud-sun-rain); }\n.#{$fa-css-prefix}-cloud-upload-alt:before { content: fa-content($fa-var-cloud-upload-alt); }\n.#{$fa-css-prefix}-cloudscale:before { content: fa-content($fa-var-cloudscale); }\n.#{$fa-css-prefix}-cloudsmith:before { content: fa-content($fa-var-cloudsmith); }\n.#{$fa-css-prefix}-cloudversify:before { content: fa-content($fa-var-cloudversify); }\n.#{$fa-css-prefix}-cocktail:before { content: fa-content($fa-var-cocktail); }\n.#{$fa-css-prefix}-code:before { content: fa-content($fa-var-code); }\n.#{$fa-css-prefix}-code-branch:before { content: fa-content($fa-var-code-branch); }\n.#{$fa-css-prefix}-codepen:before { content: fa-content($fa-var-codepen); }\n.#{$fa-css-prefix}-codiepie:before { content: fa-content($fa-var-codiepie); }\n.#{$fa-css-prefix}-coffee:before { content: fa-content($fa-var-coffee); }\n.#{$fa-css-prefix}-cog:before { content: fa-content($fa-var-cog); }\n.#{$fa-css-prefix}-cogs:before { content: fa-content($fa-var-cogs); }\n.#{$fa-css-prefix}-coins:before { content: fa-content($fa-var-coins); }\n.#{$fa-css-prefix}-columns:before { content: fa-content($fa-var-columns); }\n.#{$fa-css-prefix}-comment:before { content: fa-content($fa-var-comment); }\n.#{$fa-css-prefix}-comment-alt:before { content: fa-content($fa-var-comment-alt); }\n.#{$fa-css-prefix}-comment-dollar:before { content: fa-content($fa-var-comment-dollar); }\n.#{$fa-css-prefix}-comment-dots:before { content: fa-content($fa-var-comment-dots); }\n.#{$fa-css-prefix}-comment-medical:before { content: fa-content($fa-var-comment-medical); }\n.#{$fa-css-prefix}-comment-slash:before { content: fa-content($fa-var-comment-slash); }\n.#{$fa-css-prefix}-comments:before { content: fa-content($fa-var-comments); }\n.#{$fa-css-prefix}-comments-dollar:before { content: fa-content($fa-var-comments-dollar); }\n.#{$fa-css-prefix}-compact-disc:before { content: fa-content($fa-var-compact-disc); }\n.#{$fa-css-prefix}-compass:before { content: fa-content($fa-var-compass); }\n.#{$fa-css-prefix}-compress:before { content: fa-content($fa-var-compress); }\n.#{$fa-css-prefix}-compress-arrows-alt:before { content: fa-content($fa-var-compress-arrows-alt); }\n.#{$fa-css-prefix}-concierge-bell:before { content: fa-content($fa-var-concierge-bell); }\n.#{$fa-css-prefix}-confluence:before { content: fa-content($fa-var-confluence); }\n.#{$fa-css-prefix}-connectdevelop:before { content: fa-content($fa-var-connectdevelop); }\n.#{$fa-css-prefix}-contao:before { content: fa-content($fa-var-contao); }\n.#{$fa-css-prefix}-cookie:before { content: fa-content($fa-var-cookie); }\n.#{$fa-css-prefix}-cookie-bite:before { content: fa-content($fa-var-cookie-bite); }\n.#{$fa-css-prefix}-copy:before { content: fa-content($fa-var-copy); }\n.#{$fa-css-prefix}-copyright:before { content: fa-content($fa-var-copyright); }\n.#{$fa-css-prefix}-cotton-bureau:before { content: fa-content($fa-var-cotton-bureau); }\n.#{$fa-css-prefix}-couch:before { content: fa-content($fa-var-couch); }\n.#{$fa-css-prefix}-cpanel:before { content: fa-content($fa-var-cpanel); }\n.#{$fa-css-prefix}-creative-commons:before { content: fa-content($fa-var-creative-commons); }\n.#{$fa-css-prefix}-creative-commons-by:before { content: fa-content($fa-var-creative-commons-by); }\n.#{$fa-css-prefix}-creative-commons-nc:before { content: fa-content($fa-var-creative-commons-nc); }\n.#{$fa-css-prefix}-creative-commons-nc-eu:before { content: fa-content($fa-var-creative-commons-nc-eu); }\n.#{$fa-css-prefix}-creative-commons-nc-jp:before { content: fa-content($fa-var-creative-commons-nc-jp); }\n.#{$fa-css-prefix}-creative-commons-nd:before { content: fa-content($fa-var-creative-commons-nd); }\n.#{$fa-css-prefix}-creative-commons-pd:before { content: fa-content($fa-var-creative-commons-pd); }\n.#{$fa-css-prefix}-creative-commons-pd-alt:before { content: fa-content($fa-var-creative-commons-pd-alt); }\n.#{$fa-css-prefix}-creative-commons-remix:before { content: fa-content($fa-var-creative-commons-remix); }\n.#{$fa-css-prefix}-creative-commons-sa:before { content: fa-content($fa-var-creative-commons-sa); }\n.#{$fa-css-prefix}-creative-commons-sampling:before { content: fa-content($fa-var-creative-commons-sampling); }\n.#{$fa-css-prefix}-creative-commons-sampling-plus:before { content: fa-content($fa-var-creative-commons-sampling-plus); }\n.#{$fa-css-prefix}-creative-commons-share:before { content: fa-content($fa-var-creative-commons-share); }\n.#{$fa-css-prefix}-creative-commons-zero:before { content: fa-content($fa-var-creative-commons-zero); }\n.#{$fa-css-prefix}-credit-card:before { content: fa-content($fa-var-credit-card); }\n.#{$fa-css-prefix}-critical-role:before { content: fa-content($fa-var-critical-role); }\n.#{$fa-css-prefix}-crop:before { content: fa-content($fa-var-crop); }\n.#{$fa-css-prefix}-crop-alt:before { content: fa-content($fa-var-crop-alt); }\n.#{$fa-css-prefix}-cross:before { content: fa-content($fa-var-cross); }\n.#{$fa-css-prefix}-crosshairs:before { content: fa-content($fa-var-crosshairs); }\n.#{$fa-css-prefix}-crow:before { content: fa-content($fa-var-crow); }\n.#{$fa-css-prefix}-crown:before { content: fa-content($fa-var-crown); }\n.#{$fa-css-prefix}-crutch:before { content: fa-content($fa-var-crutch); }\n.#{$fa-css-prefix}-css3:before { content: fa-content($fa-var-css3); }\n.#{$fa-css-prefix}-css3-alt:before { content: fa-content($fa-var-css3-alt); }\n.#{$fa-css-prefix}-cube:before { content: fa-content($fa-var-cube); }\n.#{$fa-css-prefix}-cubes:before { content: fa-content($fa-var-cubes); }\n.#{$fa-css-prefix}-cut:before { content: fa-content($fa-var-cut); }\n.#{$fa-css-prefix}-cuttlefish:before { content: fa-content($fa-var-cuttlefish); }\n.#{$fa-css-prefix}-d-and-d:before { content: fa-content($fa-var-d-and-d); }\n.#{$fa-css-prefix}-d-and-d-beyond:before { content: fa-content($fa-var-d-and-d-beyond); }\n.#{$fa-css-prefix}-dashcube:before { content: fa-content($fa-var-dashcube); }\n.#{$fa-css-prefix}-database:before { content: fa-content($fa-var-database); }\n.#{$fa-css-prefix}-deaf:before { content: fa-content($fa-var-deaf); }\n.#{$fa-css-prefix}-delicious:before { content: fa-content($fa-var-delicious); }\n.#{$fa-css-prefix}-democrat:before { content: fa-content($fa-var-democrat); }\n.#{$fa-css-prefix}-deploydog:before { content: fa-content($fa-var-deploydog); }\n.#{$fa-css-prefix}-deskpro:before { content: fa-content($fa-var-deskpro); }\n.#{$fa-css-prefix}-desktop:before { content: fa-content($fa-var-desktop); }\n.#{$fa-css-prefix}-dev:before { content: fa-content($fa-var-dev); }\n.#{$fa-css-prefix}-deviantart:before { content: fa-content($fa-var-deviantart); }\n.#{$fa-css-prefix}-dharmachakra:before { content: fa-content($fa-var-dharmachakra); }\n.#{$fa-css-prefix}-dhl:before { content: fa-content($fa-var-dhl); }\n.#{$fa-css-prefix}-diagnoses:before { content: fa-content($fa-var-diagnoses); }\n.#{$fa-css-prefix}-diaspora:before { content: fa-content($fa-var-diaspora); }\n.#{$fa-css-prefix}-dice:before { content: fa-content($fa-var-dice); }\n.#{$fa-css-prefix}-dice-d20:before { content: fa-content($fa-var-dice-d20); }\n.#{$fa-css-prefix}-dice-d6:before { content: fa-content($fa-var-dice-d6); }\n.#{$fa-css-prefix}-dice-five:before { content: fa-content($fa-var-dice-five); }\n.#{$fa-css-prefix}-dice-four:before { content: fa-content($fa-var-dice-four); }\n.#{$fa-css-prefix}-dice-one:before { content: fa-content($fa-var-dice-one); }\n.#{$fa-css-prefix}-dice-six:before { content: fa-content($fa-var-dice-six); }\n.#{$fa-css-prefix}-dice-three:before { content: fa-content($fa-var-dice-three); }\n.#{$fa-css-prefix}-dice-two:before { content: fa-content($fa-var-dice-two); }\n.#{$fa-css-prefix}-digg:before { content: fa-content($fa-var-digg); }\n.#{$fa-css-prefix}-digital-ocean:before { content: fa-content($fa-var-digital-ocean); }\n.#{$fa-css-prefix}-digital-tachograph:before { content: fa-content($fa-var-digital-tachograph); }\n.#{$fa-css-prefix}-directions:before { content: fa-content($fa-var-directions); }\n.#{$fa-css-prefix}-discord:before { content: fa-content($fa-var-discord); }\n.#{$fa-css-prefix}-discourse:before { content: fa-content($fa-var-discourse); }\n.#{$fa-css-prefix}-divide:before { content: fa-content($fa-var-divide); }\n.#{$fa-css-prefix}-dizzy:before { content: fa-content($fa-var-dizzy); }\n.#{$fa-css-prefix}-dna:before { content: fa-content($fa-var-dna); }\n.#{$fa-css-prefix}-dochub:before { content: fa-content($fa-var-dochub); }\n.#{$fa-css-prefix}-docker:before { content: fa-content($fa-var-docker); }\n.#{$fa-css-prefix}-dog:before { content: fa-content($fa-var-dog); }\n.#{$fa-css-prefix}-dollar-sign:before { content: fa-content($fa-var-dollar-sign); }\n.#{$fa-css-prefix}-dolly:before { content: fa-content($fa-var-dolly); }\n.#{$fa-css-prefix}-dolly-flatbed:before { content: fa-content($fa-var-dolly-flatbed); }\n.#{$fa-css-prefix}-donate:before { content: fa-content($fa-var-donate); }\n.#{$fa-css-prefix}-door-closed:before { content: fa-content($fa-var-door-closed); }\n.#{$fa-css-prefix}-door-open:before { content: fa-content($fa-var-door-open); }\n.#{$fa-css-prefix}-dot-circle:before { content: fa-content($fa-var-dot-circle); }\n.#{$fa-css-prefix}-dove:before { content: fa-content($fa-var-dove); }\n.#{$fa-css-prefix}-download:before { content: fa-content($fa-var-download); }\n.#{$fa-css-prefix}-draft2digital:before { content: fa-content($fa-var-draft2digital); }\n.#{$fa-css-prefix}-drafting-compass:before { content: fa-content($fa-var-drafting-compass); }\n.#{$fa-css-prefix}-dragon:before { content: fa-content($fa-var-dragon); }\n.#{$fa-css-prefix}-draw-polygon:before { content: fa-content($fa-var-draw-polygon); }\n.#{$fa-css-prefix}-dribbble:before { content: fa-content($fa-var-dribbble); }\n.#{$fa-css-prefix}-dribbble-square:before { content: fa-content($fa-var-dribbble-square); }\n.#{$fa-css-prefix}-dropbox:before { content: fa-content($fa-var-dropbox); }\n.#{$fa-css-prefix}-drum:before { content: fa-content($fa-var-drum); }\n.#{$fa-css-prefix}-drum-steelpan:before { content: fa-content($fa-var-drum-steelpan); }\n.#{$fa-css-prefix}-drumstick-bite:before { content: fa-content($fa-var-drumstick-bite); }\n.#{$fa-css-prefix}-drupal:before { content: fa-content($fa-var-drupal); }\n.#{$fa-css-prefix}-dumbbell:before { content: fa-content($fa-var-dumbbell); }\n.#{$fa-css-prefix}-dumpster:before { content: fa-content($fa-var-dumpster); }\n.#{$fa-css-prefix}-dumpster-fire:before { content: fa-content($fa-var-dumpster-fire); }\n.#{$fa-css-prefix}-dungeon:before { content: fa-content($fa-var-dungeon); }\n.#{$fa-css-prefix}-dyalog:before { content: fa-content($fa-var-dyalog); }\n.#{$fa-css-prefix}-earlybirds:before { content: fa-content($fa-var-earlybirds); }\n.#{$fa-css-prefix}-ebay:before { content: fa-content($fa-var-ebay); }\n.#{$fa-css-prefix}-edge:before { content: fa-content($fa-var-edge); }\n.#{$fa-css-prefix}-edit:before { content: fa-content($fa-var-edit); }\n.#{$fa-css-prefix}-egg:before { content: fa-content($fa-var-egg); }\n.#{$fa-css-prefix}-eject:before { content: fa-content($fa-var-eject); }\n.#{$fa-css-prefix}-elementor:before { content: fa-content($fa-var-elementor); }\n.#{$fa-css-prefix}-ellipsis-h:before { content: fa-content($fa-var-ellipsis-h); }\n.#{$fa-css-prefix}-ellipsis-v:before { content: fa-content($fa-var-ellipsis-v); }\n.#{$fa-css-prefix}-ello:before { content: fa-content($fa-var-ello); }\n.#{$fa-css-prefix}-ember:before { content: fa-content($fa-var-ember); }\n.#{$fa-css-prefix}-empire:before { content: fa-content($fa-var-empire); }\n.#{$fa-css-prefix}-envelope:before { content: fa-content($fa-var-envelope); }\n.#{$fa-css-prefix}-envelope-open:before { content: fa-content($fa-var-envelope-open); }\n.#{$fa-css-prefix}-envelope-open-text:before { content: fa-content($fa-var-envelope-open-text); }\n.#{$fa-css-prefix}-envelope-square:before { content: fa-content($fa-var-envelope-square); }\n.#{$fa-css-prefix}-envira:before { content: fa-content($fa-var-envira); }\n.#{$fa-css-prefix}-equals:before { content: fa-content($fa-var-equals); }\n.#{$fa-css-prefix}-eraser:before { content: fa-content($fa-var-eraser); }\n.#{$fa-css-prefix}-erlang:before { content: fa-content($fa-var-erlang); }\n.#{$fa-css-prefix}-ethereum:before { content: fa-content($fa-var-ethereum); }\n.#{$fa-css-prefix}-ethernet:before { content: fa-content($fa-var-ethernet); }\n.#{$fa-css-prefix}-etsy:before { content: fa-content($fa-var-etsy); }\n.#{$fa-css-prefix}-euro-sign:before { content: fa-content($fa-var-euro-sign); }\n.#{$fa-css-prefix}-evernote:before { content: fa-content($fa-var-evernote); }\n.#{$fa-css-prefix}-exchange-alt:before { content: fa-content($fa-var-exchange-alt); }\n.#{$fa-css-prefix}-exclamation:before { content: fa-content($fa-var-exclamation); }\n.#{$fa-css-prefix}-exclamation-circle:before { content: fa-content($fa-var-exclamation-circle); }\n.#{$fa-css-prefix}-exclamation-triangle:before { content: fa-content($fa-var-exclamation-triangle); }\n.#{$fa-css-prefix}-expand:before { content: fa-content($fa-var-expand); }\n.#{$fa-css-prefix}-expand-arrows-alt:before { content: fa-content($fa-var-expand-arrows-alt); }\n.#{$fa-css-prefix}-expeditedssl:before { content: fa-content($fa-var-expeditedssl); }\n.#{$fa-css-prefix}-external-link-alt:before { content: fa-content($fa-var-external-link-alt); }\n.#{$fa-css-prefix}-external-link-square-alt:before { content: fa-content($fa-var-external-link-square-alt); }\n.#{$fa-css-prefix}-eye:before { content: fa-content($fa-var-eye); }\n.#{$fa-css-prefix}-eye-dropper:before { content: fa-content($fa-var-eye-dropper); }\n.#{$fa-css-prefix}-eye-slash:before { content: fa-content($fa-var-eye-slash); }\n.#{$fa-css-prefix}-facebook:before { content: fa-content($fa-var-facebook); }\n.#{$fa-css-prefix}-facebook-f:before { content: fa-content($fa-var-facebook-f); }\n.#{$fa-css-prefix}-facebook-messenger:before { content: fa-content($fa-var-facebook-messenger); }\n.#{$fa-css-prefix}-facebook-square:before { content: fa-content($fa-var-facebook-square); }\n.#{$fa-css-prefix}-fan:before { content: fa-content($fa-var-fan); }\n.#{$fa-css-prefix}-fantasy-flight-games:before { content: fa-content($fa-var-fantasy-flight-games); }\n.#{$fa-css-prefix}-fast-backward:before { content: fa-content($fa-var-fast-backward); }\n.#{$fa-css-prefix}-fast-forward:before { content: fa-content($fa-var-fast-forward); }\n.#{$fa-css-prefix}-fax:before { content: fa-content($fa-var-fax); }\n.#{$fa-css-prefix}-feather:before { content: fa-content($fa-var-feather); }\n.#{$fa-css-prefix}-feather-alt:before { content: fa-content($fa-var-feather-alt); }\n.#{$fa-css-prefix}-fedex:before { content: fa-content($fa-var-fedex); }\n.#{$fa-css-prefix}-fedora:before { content: fa-content($fa-var-fedora); }\n.#{$fa-css-prefix}-female:before { content: fa-content($fa-var-female); }\n.#{$fa-css-prefix}-fighter-jet:before { content: fa-content($fa-var-fighter-jet); }\n.#{$fa-css-prefix}-figma:before { content: fa-content($fa-var-figma); }\n.#{$fa-css-prefix}-file:before { content: fa-content($fa-var-file); }\n.#{$fa-css-prefix}-file-alt:before { content: fa-content($fa-var-file-alt); }\n.#{$fa-css-prefix}-file-archive:before { content: fa-content($fa-var-file-archive); }\n.#{$fa-css-prefix}-file-audio:before { content: fa-content($fa-var-file-audio); }\n.#{$fa-css-prefix}-file-code:before { content: fa-content($fa-var-file-code); }\n.#{$fa-css-prefix}-file-contract:before { content: fa-content($fa-var-file-contract); }\n.#{$fa-css-prefix}-file-csv:before { content: fa-content($fa-var-file-csv); }\n.#{$fa-css-prefix}-file-download:before { content: fa-content($fa-var-file-download); }\n.#{$fa-css-prefix}-file-excel:before { content: fa-content($fa-var-file-excel); }\n.#{$fa-css-prefix}-file-export:before { content: fa-content($fa-var-file-export); }\n.#{$fa-css-prefix}-file-image:before { content: fa-content($fa-var-file-image); }\n.#{$fa-css-prefix}-file-import:before { content: fa-content($fa-var-file-import); }\n.#{$fa-css-prefix}-file-invoice:before { content: fa-content($fa-var-file-invoice); }\n.#{$fa-css-prefix}-file-invoice-dollar:before { content: fa-content($fa-var-file-invoice-dollar); }\n.#{$fa-css-prefix}-file-medical:before { content: fa-content($fa-var-file-medical); }\n.#{$fa-css-prefix}-file-medical-alt:before { content: fa-content($fa-var-file-medical-alt); }\n.#{$fa-css-prefix}-file-pdf:before { content: fa-content($fa-var-file-pdf); }\n.#{$fa-css-prefix}-file-powerpoint:before { content: fa-content($fa-var-file-powerpoint); }\n.#{$fa-css-prefix}-file-prescription:before { content: fa-content($fa-var-file-prescription); }\n.#{$fa-css-prefix}-file-signature:before { content: fa-content($fa-var-file-signature); }\n.#{$fa-css-prefix}-file-upload:before { content: fa-content($fa-var-file-upload); }\n.#{$fa-css-prefix}-file-video:before { content: fa-content($fa-var-file-video); }\n.#{$fa-css-prefix}-file-word:before { content: fa-content($fa-var-file-word); }\n.#{$fa-css-prefix}-fill:before { content: fa-content($fa-var-fill); }\n.#{$fa-css-prefix}-fill-drip:before { content: fa-content($fa-var-fill-drip); }\n.#{$fa-css-prefix}-film:before { content: fa-content($fa-var-film); }\n.#{$fa-css-prefix}-filter:before { content: fa-content($fa-var-filter); }\n.#{$fa-css-prefix}-fingerprint:before { content: fa-content($fa-var-fingerprint); }\n.#{$fa-css-prefix}-fire:before { content: fa-content($fa-var-fire); }\n.#{$fa-css-prefix}-fire-alt:before { content: fa-content($fa-var-fire-alt); }\n.#{$fa-css-prefix}-fire-extinguisher:before { content: fa-content($fa-var-fire-extinguisher); }\n.#{$fa-css-prefix}-firefox:before { content: fa-content($fa-var-firefox); }\n.#{$fa-css-prefix}-first-aid:before { content: fa-content($fa-var-first-aid); }\n.#{$fa-css-prefix}-first-order:before { content: fa-content($fa-var-first-order); }\n.#{$fa-css-prefix}-first-order-alt:before { content: fa-content($fa-var-first-order-alt); }\n.#{$fa-css-prefix}-firstdraft:before { content: fa-content($fa-var-firstdraft); }\n.#{$fa-css-prefix}-fish:before { content: fa-content($fa-var-fish); }\n.#{$fa-css-prefix}-fist-raised:before { content: fa-content($fa-var-fist-raised); }\n.#{$fa-css-prefix}-flag:before { content: fa-content($fa-var-flag); }\n.#{$fa-css-prefix}-flag-checkered:before { content: fa-content($fa-var-flag-checkered); }\n.#{$fa-css-prefix}-flag-usa:before { content: fa-content($fa-var-flag-usa); }\n.#{$fa-css-prefix}-flask:before { content: fa-content($fa-var-flask); }\n.#{$fa-css-prefix}-flickr:before { content: fa-content($fa-var-flickr); }\n.#{$fa-css-prefix}-flipboard:before { content: fa-content($fa-var-flipboard); }\n.#{$fa-css-prefix}-flushed:before { content: fa-content($fa-var-flushed); }\n.#{$fa-css-prefix}-fly:before { content: fa-content($fa-var-fly); }\n.#{$fa-css-prefix}-folder:before { content: fa-content($fa-var-folder); }\n.#{$fa-css-prefix}-folder-minus:before { content: fa-content($fa-var-folder-minus); }\n.#{$fa-css-prefix}-folder-open:before { content: fa-content($fa-var-folder-open); }\n.#{$fa-css-prefix}-folder-plus:before { content: fa-content($fa-var-folder-plus); }\n.#{$fa-css-prefix}-font:before { content: fa-content($fa-var-font); }\n.#{$fa-css-prefix}-font-awesome:before { content: fa-content($fa-var-font-awesome); }\n.#{$fa-css-prefix}-font-awesome-alt:before { content: fa-content($fa-var-font-awesome-alt); }\n.#{$fa-css-prefix}-font-awesome-flag:before { content: fa-content($fa-var-font-awesome-flag); }\n.#{$fa-css-prefix}-font-awesome-logo-full:before { content: fa-content($fa-var-font-awesome-logo-full); }\n.#{$fa-css-prefix}-fonticons:before { content: fa-content($fa-var-fonticons); }\n.#{$fa-css-prefix}-fonticons-fi:before { content: fa-content($fa-var-fonticons-fi); }\n.#{$fa-css-prefix}-football-ball:before { content: fa-content($fa-var-football-ball); }\n.#{$fa-css-prefix}-fort-awesome:before { content: fa-content($fa-var-fort-awesome); }\n.#{$fa-css-prefix}-fort-awesome-alt:before { content: fa-content($fa-var-fort-awesome-alt); }\n.#{$fa-css-prefix}-forumbee:before { content: fa-content($fa-var-forumbee); }\n.#{$fa-css-prefix}-forward:before { content: fa-content($fa-var-forward); }\n.#{$fa-css-prefix}-foursquare:before { content: fa-content($fa-var-foursquare); }\n.#{$fa-css-prefix}-free-code-camp:before { content: fa-content($fa-var-free-code-camp); }\n.#{$fa-css-prefix}-freebsd:before { content: fa-content($fa-var-freebsd); }\n.#{$fa-css-prefix}-frog:before { content: fa-content($fa-var-frog); }\n.#{$fa-css-prefix}-frown:before { content: fa-content($fa-var-frown); }\n.#{$fa-css-prefix}-frown-open:before { content: fa-content($fa-var-frown-open); }\n.#{$fa-css-prefix}-fulcrum:before { content: fa-content($fa-var-fulcrum); }\n.#{$fa-css-prefix}-funnel-dollar:before { content: fa-content($fa-var-funnel-dollar); }\n.#{$fa-css-prefix}-futbol:before { content: fa-content($fa-var-futbol); }\n.#{$fa-css-prefix}-galactic-republic:before { content: fa-content($fa-var-galactic-republic); }\n.#{$fa-css-prefix}-galactic-senate:before { content: fa-content($fa-var-galactic-senate); }\n.#{$fa-css-prefix}-gamepad:before { content: fa-content($fa-var-gamepad); }\n.#{$fa-css-prefix}-gas-pump:before { content: fa-content($fa-var-gas-pump); }\n.#{$fa-css-prefix}-gavel:before { content: fa-content($fa-var-gavel); }\n.#{$fa-css-prefix}-gem:before { content: fa-content($fa-var-gem); }\n.#{$fa-css-prefix}-genderless:before { content: fa-content($fa-var-genderless); }\n.#{$fa-css-prefix}-get-pocket:before { content: fa-content($fa-var-get-pocket); }\n.#{$fa-css-prefix}-gg:before { content: fa-content($fa-var-gg); }\n.#{$fa-css-prefix}-gg-circle:before { content: fa-content($fa-var-gg-circle); }\n.#{$fa-css-prefix}-ghost:before { content: fa-content($fa-var-ghost); }\n.#{$fa-css-prefix}-gift:before { content: fa-content($fa-var-gift); }\n.#{$fa-css-prefix}-gifts:before { content: fa-content($fa-var-gifts); }\n.#{$fa-css-prefix}-git:before { content: fa-content($fa-var-git); }\n.#{$fa-css-prefix}-git-alt:before { content: fa-content($fa-var-git-alt); }\n.#{$fa-css-prefix}-git-square:before { content: fa-content($fa-var-git-square); }\n.#{$fa-css-prefix}-github:before { content: fa-content($fa-var-github); }\n.#{$fa-css-prefix}-github-alt:before { content: fa-content($fa-var-github-alt); }\n.#{$fa-css-prefix}-github-square:before { content: fa-content($fa-var-github-square); }\n.#{$fa-css-prefix}-gitkraken:before { content: fa-content($fa-var-gitkraken); }\n.#{$fa-css-prefix}-gitlab:before { content: fa-content($fa-var-gitlab); }\n.#{$fa-css-prefix}-gitter:before { content: fa-content($fa-var-gitter); }\n.#{$fa-css-prefix}-glass-cheers:before { content: fa-content($fa-var-glass-cheers); }\n.#{$fa-css-prefix}-glass-martini:before { content: fa-content($fa-var-glass-martini); }\n.#{$fa-css-prefix}-glass-martini-alt:before { content: fa-content($fa-var-glass-martini-alt); }\n.#{$fa-css-prefix}-glass-whiskey:before { content: fa-content($fa-var-glass-whiskey); }\n.#{$fa-css-prefix}-glasses:before { content: fa-content($fa-var-glasses); }\n.#{$fa-css-prefix}-glide:before { content: fa-content($fa-var-glide); }\n.#{$fa-css-prefix}-glide-g:before { content: fa-content($fa-var-glide-g); }\n.#{$fa-css-prefix}-globe:before { content: fa-content($fa-var-globe); }\n.#{$fa-css-prefix}-globe-africa:before { content: fa-content($fa-var-globe-africa); }\n.#{$fa-css-prefix}-globe-americas:before { content: fa-content($fa-var-globe-americas); }\n.#{$fa-css-prefix}-globe-asia:before { content: fa-content($fa-var-globe-asia); }\n.#{$fa-css-prefix}-globe-europe:before { content: fa-content($fa-var-globe-europe); }\n.#{$fa-css-prefix}-gofore:before { content: fa-content($fa-var-gofore); }\n.#{$fa-css-prefix}-golf-ball:before { content: fa-content($fa-var-golf-ball); }\n.#{$fa-css-prefix}-goodreads:before { content: fa-content($fa-var-goodreads); }\n.#{$fa-css-prefix}-goodreads-g:before { content: fa-content($fa-var-goodreads-g); }\n.#{$fa-css-prefix}-google:before { content: fa-content($fa-var-google); }\n.#{$fa-css-prefix}-google-drive:before { content: fa-content($fa-var-google-drive); }\n.#{$fa-css-prefix}-google-play:before { content: fa-content($fa-var-google-play); }\n.#{$fa-css-prefix}-google-plus:before { content: fa-content($fa-var-google-plus); }\n.#{$fa-css-prefix}-google-plus-g:before { content: fa-content($fa-var-google-plus-g); }\n.#{$fa-css-prefix}-google-plus-square:before { content: fa-content($fa-var-google-plus-square); }\n.#{$fa-css-prefix}-google-wallet:before { content: fa-content($fa-var-google-wallet); }\n.#{$fa-css-prefix}-gopuram:before { content: fa-content($fa-var-gopuram); }\n.#{$fa-css-prefix}-graduation-cap:before { content: fa-content($fa-var-graduation-cap); }\n.#{$fa-css-prefix}-gratipay:before { content: fa-content($fa-var-gratipay); }\n.#{$fa-css-prefix}-grav:before { content: fa-content($fa-var-grav); }\n.#{$fa-css-prefix}-greater-than:before { content: fa-content($fa-var-greater-than); }\n.#{$fa-css-prefix}-greater-than-equal:before { content: fa-content($fa-var-greater-than-equal); }\n.#{$fa-css-prefix}-grimace:before { content: fa-content($fa-var-grimace); }\n.#{$fa-css-prefix}-grin:before { content: fa-content($fa-var-grin); }\n.#{$fa-css-prefix}-grin-alt:before { content: fa-content($fa-var-grin-alt); }\n.#{$fa-css-prefix}-grin-beam:before { content: fa-content($fa-var-grin-beam); }\n.#{$fa-css-prefix}-grin-beam-sweat:before { content: fa-content($fa-var-grin-beam-sweat); }\n.#{$fa-css-prefix}-grin-hearts:before { content: fa-content($fa-var-grin-hearts); }\n.#{$fa-css-prefix}-grin-squint:before { content: fa-content($fa-var-grin-squint); }\n.#{$fa-css-prefix}-grin-squint-tears:before { content: fa-content($fa-var-grin-squint-tears); }\n.#{$fa-css-prefix}-grin-stars:before { content: fa-content($fa-var-grin-stars); }\n.#{$fa-css-prefix}-grin-tears:before { content: fa-content($fa-var-grin-tears); }\n.#{$fa-css-prefix}-grin-tongue:before { content: fa-content($fa-var-grin-tongue); }\n.#{$fa-css-prefix}-grin-tongue-squint:before { content: fa-content($fa-var-grin-tongue-squint); }\n.#{$fa-css-prefix}-grin-tongue-wink:before { content: fa-content($fa-var-grin-tongue-wink); }\n.#{$fa-css-prefix}-grin-wink:before { content: fa-content($fa-var-grin-wink); }\n.#{$fa-css-prefix}-grip-horizontal:before { content: fa-content($fa-var-grip-horizontal); }\n.#{$fa-css-prefix}-grip-lines:before { content: fa-content($fa-var-grip-lines); }\n.#{$fa-css-prefix}-grip-lines-vertical:before { content: fa-content($fa-var-grip-lines-vertical); }\n.#{$fa-css-prefix}-grip-vertical:before { content: fa-content($fa-var-grip-vertical); }\n.#{$fa-css-prefix}-gripfire:before { content: fa-content($fa-var-gripfire); }\n.#{$fa-css-prefix}-grunt:before { content: fa-content($fa-var-grunt); }\n.#{$fa-css-prefix}-guitar:before { content: fa-content($fa-var-guitar); }\n.#{$fa-css-prefix}-gulp:before { content: fa-content($fa-var-gulp); }\n.#{$fa-css-prefix}-h-square:before { content: fa-content($fa-var-h-square); }\n.#{$fa-css-prefix}-hacker-news:before { content: fa-content($fa-var-hacker-news); }\n.#{$fa-css-prefix}-hacker-news-square:before { content: fa-content($fa-var-hacker-news-square); }\n.#{$fa-css-prefix}-hackerrank:before { content: fa-content($fa-var-hackerrank); }\n.#{$fa-css-prefix}-hamburger:before { content: fa-content($fa-var-hamburger); }\n.#{$fa-css-prefix}-hammer:before { content: fa-content($fa-var-hammer); }\n.#{$fa-css-prefix}-hamsa:before { content: fa-content($fa-var-hamsa); }\n.#{$fa-css-prefix}-hand-holding:before { content: fa-content($fa-var-hand-holding); }\n.#{$fa-css-prefix}-hand-holding-heart:before { content: fa-content($fa-var-hand-holding-heart); }\n.#{$fa-css-prefix}-hand-holding-usd:before { content: fa-content($fa-var-hand-holding-usd); }\n.#{$fa-css-prefix}-hand-lizard:before { content: fa-content($fa-var-hand-lizard); }\n.#{$fa-css-prefix}-hand-middle-finger:before { content: fa-content($fa-var-hand-middle-finger); }\n.#{$fa-css-prefix}-hand-paper:before { content: fa-content($fa-var-hand-paper); }\n.#{$fa-css-prefix}-hand-peace:before { content: fa-content($fa-var-hand-peace); }\n.#{$fa-css-prefix}-hand-point-down:before { content: fa-content($fa-var-hand-point-down); }\n.#{$fa-css-prefix}-hand-point-left:before { content: fa-content($fa-var-hand-point-left); }\n.#{$fa-css-prefix}-hand-point-right:before { content: fa-content($fa-var-hand-point-right); }\n.#{$fa-css-prefix}-hand-point-up:before { content: fa-content($fa-var-hand-point-up); }\n.#{$fa-css-prefix}-hand-pointer:before { content: fa-content($fa-var-hand-pointer); }\n.#{$fa-css-prefix}-hand-rock:before { content: fa-content($fa-var-hand-rock); }\n.#{$fa-css-prefix}-hand-scissors:before { content: fa-content($fa-var-hand-scissors); }\n.#{$fa-css-prefix}-hand-spock:before { content: fa-content($fa-var-hand-spock); }\n.#{$fa-css-prefix}-hands:before { content: fa-content($fa-var-hands); }\n.#{$fa-css-prefix}-hands-helping:before { content: fa-content($fa-var-hands-helping); }\n.#{$fa-css-prefix}-handshake:before { content: fa-content($fa-var-handshake); }\n.#{$fa-css-prefix}-hanukiah:before { content: fa-content($fa-var-hanukiah); }\n.#{$fa-css-prefix}-hard-hat:before { content: fa-content($fa-var-hard-hat); }\n.#{$fa-css-prefix}-hashtag:before { content: fa-content($fa-var-hashtag); }\n.#{$fa-css-prefix}-hat-wizard:before { content: fa-content($fa-var-hat-wizard); }\n.#{$fa-css-prefix}-haykal:before { content: fa-content($fa-var-haykal); }\n.#{$fa-css-prefix}-hdd:before { content: fa-content($fa-var-hdd); }\n.#{$fa-css-prefix}-heading:before { content: fa-content($fa-var-heading); }\n.#{$fa-css-prefix}-headphones:before { content: fa-content($fa-var-headphones); }\n.#{$fa-css-prefix}-headphones-alt:before { content: fa-content($fa-var-headphones-alt); }\n.#{$fa-css-prefix}-headset:before { content: fa-content($fa-var-headset); }\n.#{$fa-css-prefix}-heart:before { content: fa-content($fa-var-heart); }\n.#{$fa-css-prefix}-heart-broken:before { content: fa-content($fa-var-heart-broken); }\n.#{$fa-css-prefix}-heartbeat:before { content: fa-content($fa-var-heartbeat); }\n.#{$fa-css-prefix}-helicopter:before { content: fa-content($fa-var-helicopter); }\n.#{$fa-css-prefix}-highlighter:before { content: fa-content($fa-var-highlighter); }\n.#{$fa-css-prefix}-hiking:before { content: fa-content($fa-var-hiking); }\n.#{$fa-css-prefix}-hippo:before { content: fa-content($fa-var-hippo); }\n.#{$fa-css-prefix}-hips:before { content: fa-content($fa-var-hips); }\n.#{$fa-css-prefix}-hire-a-helper:before { content: fa-content($fa-var-hire-a-helper); }\n.#{$fa-css-prefix}-history:before { content: fa-content($fa-var-history); }\n.#{$fa-css-prefix}-hockey-puck:before { content: fa-content($fa-var-hockey-puck); }\n.#{$fa-css-prefix}-holly-berry:before { content: fa-content($fa-var-holly-berry); }\n.#{$fa-css-prefix}-home:before { content: fa-content($fa-var-home); }\n.#{$fa-css-prefix}-hooli:before { content: fa-content($fa-var-hooli); }\n.#{$fa-css-prefix}-hornbill:before { content: fa-content($fa-var-hornbill); }\n.#{$fa-css-prefix}-horse:before { content: fa-content($fa-var-horse); }\n.#{$fa-css-prefix}-horse-head:before { content: fa-content($fa-var-horse-head); }\n.#{$fa-css-prefix}-hospital:before { content: fa-content($fa-var-hospital); }\n.#{$fa-css-prefix}-hospital-alt:before { content: fa-content($fa-var-hospital-alt); }\n.#{$fa-css-prefix}-hospital-symbol:before { content: fa-content($fa-var-hospital-symbol); }\n.#{$fa-css-prefix}-hot-tub:before { content: fa-content($fa-var-hot-tub); }\n.#{$fa-css-prefix}-hotdog:before { content: fa-content($fa-var-hotdog); }\n.#{$fa-css-prefix}-hotel:before { content: fa-content($fa-var-hotel); }\n.#{$fa-css-prefix}-hotjar:before { content: fa-content($fa-var-hotjar); }\n.#{$fa-css-prefix}-hourglass:before { content: fa-content($fa-var-hourglass); }\n.#{$fa-css-prefix}-hourglass-end:before { content: fa-content($fa-var-hourglass-end); }\n.#{$fa-css-prefix}-hourglass-half:before { content: fa-content($fa-var-hourglass-half); }\n.#{$fa-css-prefix}-hourglass-start:before { content: fa-content($fa-var-hourglass-start); }\n.#{$fa-css-prefix}-house-damage:before { content: fa-content($fa-var-house-damage); }\n.#{$fa-css-prefix}-houzz:before { content: fa-content($fa-var-houzz); }\n.#{$fa-css-prefix}-hryvnia:before { content: fa-content($fa-var-hryvnia); }\n.#{$fa-css-prefix}-html5:before { content: fa-content($fa-var-html5); }\n.#{$fa-css-prefix}-hubspot:before { content: fa-content($fa-var-hubspot); }\n.#{$fa-css-prefix}-i-cursor:before { content: fa-content($fa-var-i-cursor); }\n.#{$fa-css-prefix}-ice-cream:before { content: fa-content($fa-var-ice-cream); }\n.#{$fa-css-prefix}-icicles:before { content: fa-content($fa-var-icicles); }\n.#{$fa-css-prefix}-icons:before { content: fa-content($fa-var-icons); }\n.#{$fa-css-prefix}-id-badge:before { content: fa-content($fa-var-id-badge); }\n.#{$fa-css-prefix}-id-card:before { content: fa-content($fa-var-id-card); }\n.#{$fa-css-prefix}-id-card-alt:before { content: fa-content($fa-var-id-card-alt); }\n.#{$fa-css-prefix}-igloo:before { content: fa-content($fa-var-igloo); }\n.#{$fa-css-prefix}-image:before { content: fa-content($fa-var-image); }\n.#{$fa-css-prefix}-images:before { content: fa-content($fa-var-images); }\n.#{$fa-css-prefix}-imdb:before { content: fa-content($fa-var-imdb); }\n.#{$fa-css-prefix}-inbox:before { content: fa-content($fa-var-inbox); }\n.#{$fa-css-prefix}-indent:before { content: fa-content($fa-var-indent); }\n.#{$fa-css-prefix}-industry:before { content: fa-content($fa-var-industry); }\n.#{$fa-css-prefix}-infinity:before { content: fa-content($fa-var-infinity); }\n.#{$fa-css-prefix}-info:before { content: fa-content($fa-var-info); }\n.#{$fa-css-prefix}-info-circle:before { content: fa-content($fa-var-info-circle); }\n.#{$fa-css-prefix}-instagram:before { content: fa-content($fa-var-instagram); }\n.#{$fa-css-prefix}-intercom:before { content: fa-content($fa-var-intercom); }\n.#{$fa-css-prefix}-internet-explorer:before { content: fa-content($fa-var-internet-explorer); }\n.#{$fa-css-prefix}-invision:before { content: fa-content($fa-var-invision); }\n.#{$fa-css-prefix}-ioxhost:before { content: fa-content($fa-var-ioxhost); }\n.#{$fa-css-prefix}-italic:before { content: fa-content($fa-var-italic); }\n.#{$fa-css-prefix}-itch-io:before { content: fa-content($fa-var-itch-io); }\n.#{$fa-css-prefix}-itunes:before { content: fa-content($fa-var-itunes); }\n.#{$fa-css-prefix}-itunes-note:before { content: fa-content($fa-var-itunes-note); }\n.#{$fa-css-prefix}-java:before { content: fa-content($fa-var-java); }\n.#{$fa-css-prefix}-jedi:before { content: fa-content($fa-var-jedi); }\n.#{$fa-css-prefix}-jedi-order:before { content: fa-content($fa-var-jedi-order); }\n.#{$fa-css-prefix}-jenkins:before { content: fa-content($fa-var-jenkins); }\n.#{$fa-css-prefix}-jira:before { content: fa-content($fa-var-jira); }\n.#{$fa-css-prefix}-joget:before { content: fa-content($fa-var-joget); }\n.#{$fa-css-prefix}-joint:before { content: fa-content($fa-var-joint); }\n.#{$fa-css-prefix}-joomla:before { content: fa-content($fa-var-joomla); }\n.#{$fa-css-prefix}-journal-whills:before { content: fa-content($fa-var-journal-whills); }\n.#{$fa-css-prefix}-js:before { content: fa-content($fa-var-js); }\n.#{$fa-css-prefix}-js-square:before { content: fa-content($fa-var-js-square); }\n.#{$fa-css-prefix}-jsfiddle:before { content: fa-content($fa-var-jsfiddle); }\n.#{$fa-css-prefix}-kaaba:before { content: fa-content($fa-var-kaaba); }\n.#{$fa-css-prefix}-kaggle:before { content: fa-content($fa-var-kaggle); }\n.#{$fa-css-prefix}-key:before { content: fa-content($fa-var-key); }\n.#{$fa-css-prefix}-keybase:before { content: fa-content($fa-var-keybase); }\n.#{$fa-css-prefix}-keyboard:before { content: fa-content($fa-var-keyboard); }\n.#{$fa-css-prefix}-keycdn:before { content: fa-content($fa-var-keycdn); }\n.#{$fa-css-prefix}-khanda:before { content: fa-content($fa-var-khanda); }\n.#{$fa-css-prefix}-kickstarter:before { content: fa-content($fa-var-kickstarter); }\n.#{$fa-css-prefix}-kickstarter-k:before { content: fa-content($fa-var-kickstarter-k); }\n.#{$fa-css-prefix}-kiss:before { content: fa-content($fa-var-kiss); }\n.#{$fa-css-prefix}-kiss-beam:before { content: fa-content($fa-var-kiss-beam); }\n.#{$fa-css-prefix}-kiss-wink-heart:before { content: fa-content($fa-var-kiss-wink-heart); }\n.#{$fa-css-prefix}-kiwi-bird:before { content: fa-content($fa-var-kiwi-bird); }\n.#{$fa-css-prefix}-korvue:before { content: fa-content($fa-var-korvue); }\n.#{$fa-css-prefix}-landmark:before { content: fa-content($fa-var-landmark); }\n.#{$fa-css-prefix}-language:before { content: fa-content($fa-var-language); }\n.#{$fa-css-prefix}-laptop:before { content: fa-content($fa-var-laptop); }\n.#{$fa-css-prefix}-laptop-code:before { content: fa-content($fa-var-laptop-code); }\n.#{$fa-css-prefix}-laptop-medical:before { content: fa-content($fa-var-laptop-medical); }\n.#{$fa-css-prefix}-laravel:before { content: fa-content($fa-var-laravel); }\n.#{$fa-css-prefix}-lastfm:before { content: fa-content($fa-var-lastfm); }\n.#{$fa-css-prefix}-lastfm-square:before { content: fa-content($fa-var-lastfm-square); }\n.#{$fa-css-prefix}-laugh:before { content: fa-content($fa-var-laugh); }\n.#{$fa-css-prefix}-laugh-beam:before { content: fa-content($fa-var-laugh-beam); }\n.#{$fa-css-prefix}-laugh-squint:before { content: fa-content($fa-var-laugh-squint); }\n.#{$fa-css-prefix}-laugh-wink:before { content: fa-content($fa-var-laugh-wink); }\n.#{$fa-css-prefix}-layer-group:before { content: fa-content($fa-var-layer-group); }\n.#{$fa-css-prefix}-leaf:before { content: fa-content($fa-var-leaf); }\n.#{$fa-css-prefix}-leanpub:before { content: fa-content($fa-var-leanpub); }\n.#{$fa-css-prefix}-lemon:before { content: fa-content($fa-var-lemon); }\n.#{$fa-css-prefix}-less:before { content: fa-content($fa-var-less); }\n.#{$fa-css-prefix}-less-than:before { content: fa-content($fa-var-less-than); }\n.#{$fa-css-prefix}-less-than-equal:before { content: fa-content($fa-var-less-than-equal); }\n.#{$fa-css-prefix}-level-down-alt:before { content: fa-content($fa-var-level-down-alt); }\n.#{$fa-css-prefix}-level-up-alt:before { content: fa-content($fa-var-level-up-alt); }\n.#{$fa-css-prefix}-life-ring:before { content: fa-content($fa-var-life-ring); }\n.#{$fa-css-prefix}-lightbulb:before { content: fa-content($fa-var-lightbulb); }\n.#{$fa-css-prefix}-line:before { content: fa-content($fa-var-line); }\n.#{$fa-css-prefix}-link:before { content: fa-content($fa-var-link); }\n.#{$fa-css-prefix}-linkedin:before { content: fa-content($fa-var-linkedin); }\n.#{$fa-css-prefix}-linkedin-in:before { content: fa-content($fa-var-linkedin-in); }\n.#{$fa-css-prefix}-linode:before { content: fa-content($fa-var-linode); }\n.#{$fa-css-prefix}-linux:before { content: fa-content($fa-var-linux); }\n.#{$fa-css-prefix}-lira-sign:before { content: fa-content($fa-var-lira-sign); }\n.#{$fa-css-prefix}-list:before { content: fa-content($fa-var-list); }\n.#{$fa-css-prefix}-list-alt:before { content: fa-content($fa-var-list-alt); }\n.#{$fa-css-prefix}-list-ol:before { content: fa-content($fa-var-list-ol); }\n.#{$fa-css-prefix}-list-ul:before { content: fa-content($fa-var-list-ul); }\n.#{$fa-css-prefix}-location-arrow:before { content: fa-content($fa-var-location-arrow); }\n.#{$fa-css-prefix}-lock:before { content: fa-content($fa-var-lock); }\n.#{$fa-css-prefix}-lock-open:before { content: fa-content($fa-var-lock-open); }\n.#{$fa-css-prefix}-long-arrow-alt-down:before { content: fa-content($fa-var-long-arrow-alt-down); }\n.#{$fa-css-prefix}-long-arrow-alt-left:before { content: fa-content($fa-var-long-arrow-alt-left); }\n.#{$fa-css-prefix}-long-arrow-alt-right:before { content: fa-content($fa-var-long-arrow-alt-right); }\n.#{$fa-css-prefix}-long-arrow-alt-up:before { content: fa-content($fa-var-long-arrow-alt-up); }\n.#{$fa-css-prefix}-low-vision:before { content: fa-content($fa-var-low-vision); }\n.#{$fa-css-prefix}-luggage-cart:before { content: fa-content($fa-var-luggage-cart); }\n.#{$fa-css-prefix}-lyft:before { content: fa-content($fa-var-lyft); }\n.#{$fa-css-prefix}-magento:before { content: fa-content($fa-var-magento); }\n.#{$fa-css-prefix}-magic:before { content: fa-content($fa-var-magic); }\n.#{$fa-css-prefix}-magnet:before { content: fa-content($fa-var-magnet); }\n.#{$fa-css-prefix}-mail-bulk:before { content: fa-content($fa-var-mail-bulk); }\n.#{$fa-css-prefix}-mailchimp:before { content: fa-content($fa-var-mailchimp); }\n.#{$fa-css-prefix}-male:before { content: fa-content($fa-var-male); }\n.#{$fa-css-prefix}-mandalorian:before { content: fa-content($fa-var-mandalorian); }\n.#{$fa-css-prefix}-map:before { content: fa-content($fa-var-map); }\n.#{$fa-css-prefix}-map-marked:before { content: fa-content($fa-var-map-marked); }\n.#{$fa-css-prefix}-map-marked-alt:before { content: fa-content($fa-var-map-marked-alt); }\n.#{$fa-css-prefix}-map-marker:before { content: fa-content($fa-var-map-marker); }\n.#{$fa-css-prefix}-map-marker-alt:before { content: fa-content($fa-var-map-marker-alt); }\n.#{$fa-css-prefix}-map-pin:before { content: fa-content($fa-var-map-pin); }\n.#{$fa-css-prefix}-map-signs:before { content: fa-content($fa-var-map-signs); }\n.#{$fa-css-prefix}-markdown:before { content: fa-content($fa-var-markdown); }\n.#{$fa-css-prefix}-marker:before { content: fa-content($fa-var-marker); }\n.#{$fa-css-prefix}-mars:before { content: fa-content($fa-var-mars); }\n.#{$fa-css-prefix}-mars-double:before { content: fa-content($fa-var-mars-double); }\n.#{$fa-css-prefix}-mars-stroke:before { content: fa-content($fa-var-mars-stroke); }\n.#{$fa-css-prefix}-mars-stroke-h:before { content: fa-content($fa-var-mars-stroke-h); }\n.#{$fa-css-prefix}-mars-stroke-v:before { content: fa-content($fa-var-mars-stroke-v); }\n.#{$fa-css-prefix}-mask:before { content: fa-content($fa-var-mask); }\n.#{$fa-css-prefix}-mastodon:before { content: fa-content($fa-var-mastodon); }\n.#{$fa-css-prefix}-maxcdn:before { content: fa-content($fa-var-maxcdn); }\n.#{$fa-css-prefix}-medal:before { content: fa-content($fa-var-medal); }\n.#{$fa-css-prefix}-medapps:before { content: fa-content($fa-var-medapps); }\n.#{$fa-css-prefix}-medium:before { content: fa-content($fa-var-medium); }\n.#{$fa-css-prefix}-medium-m:before { content: fa-content($fa-var-medium-m); }\n.#{$fa-css-prefix}-medkit:before { content: fa-content($fa-var-medkit); }\n.#{$fa-css-prefix}-medrt:before { content: fa-content($fa-var-medrt); }\n.#{$fa-css-prefix}-meetup:before { content: fa-content($fa-var-meetup); }\n.#{$fa-css-prefix}-megaport:before { content: fa-content($fa-var-megaport); }\n.#{$fa-css-prefix}-meh:before { content: fa-content($fa-var-meh); }\n.#{$fa-css-prefix}-meh-blank:before { content: fa-content($fa-var-meh-blank); }\n.#{$fa-css-prefix}-meh-rolling-eyes:before { content: fa-content($fa-var-meh-rolling-eyes); }\n.#{$fa-css-prefix}-memory:before { content: fa-content($fa-var-memory); }\n.#{$fa-css-prefix}-mendeley:before { content: fa-content($fa-var-mendeley); }\n.#{$fa-css-prefix}-menorah:before { content: fa-content($fa-var-menorah); }\n.#{$fa-css-prefix}-mercury:before { content: fa-content($fa-var-mercury); }\n.#{$fa-css-prefix}-meteor:before { content: fa-content($fa-var-meteor); }\n.#{$fa-css-prefix}-microchip:before { content: fa-content($fa-var-microchip); }\n.#{$fa-css-prefix}-microphone:before { content: fa-content($fa-var-microphone); }\n.#{$fa-css-prefix}-microphone-alt:before { content: fa-content($fa-var-microphone-alt); }\n.#{$fa-css-prefix}-microphone-alt-slash:before { content: fa-content($fa-var-microphone-alt-slash); }\n.#{$fa-css-prefix}-microphone-slash:before { content: fa-content($fa-var-microphone-slash); }\n.#{$fa-css-prefix}-microscope:before { content: fa-content($fa-var-microscope); }\n.#{$fa-css-prefix}-microsoft:before { content: fa-content($fa-var-microsoft); }\n.#{$fa-css-prefix}-minus:before { content: fa-content($fa-var-minus); }\n.#{$fa-css-prefix}-minus-circle:before { content: fa-content($fa-var-minus-circle); }\n.#{$fa-css-prefix}-minus-square:before { content: fa-content($fa-var-minus-square); }\n.#{$fa-css-prefix}-mitten:before { content: fa-content($fa-var-mitten); }\n.#{$fa-css-prefix}-mix:before { content: fa-content($fa-var-mix); }\n.#{$fa-css-prefix}-mixcloud:before { content: fa-content($fa-var-mixcloud); }\n.#{$fa-css-prefix}-mizuni:before { content: fa-content($fa-var-mizuni); }\n.#{$fa-css-prefix}-mobile:before { content: fa-content($fa-var-mobile); }\n.#{$fa-css-prefix}-mobile-alt:before { content: fa-content($fa-var-mobile-alt); }\n.#{$fa-css-prefix}-modx:before { content: fa-content($fa-var-modx); }\n.#{$fa-css-prefix}-monero:before { content: fa-content($fa-var-monero); }\n.#{$fa-css-prefix}-money-bill:before { content: fa-content($fa-var-money-bill); }\n.#{$fa-css-prefix}-money-bill-alt:before { content: fa-content($fa-var-money-bill-alt); }\n.#{$fa-css-prefix}-money-bill-wave:before { content: fa-content($fa-var-money-bill-wave); }\n.#{$fa-css-prefix}-money-bill-wave-alt:before { content: fa-content($fa-var-money-bill-wave-alt); }\n.#{$fa-css-prefix}-money-check:before { content: fa-content($fa-var-money-check); }\n.#{$fa-css-prefix}-money-check-alt:before { content: fa-content($fa-var-money-check-alt); }\n.#{$fa-css-prefix}-monument:before { content: fa-content($fa-var-monument); }\n.#{$fa-css-prefix}-moon:before { content: fa-content($fa-var-moon); }\n.#{$fa-css-prefix}-mortar-pestle:before { content: fa-content($fa-var-mortar-pestle); }\n.#{$fa-css-prefix}-mosque:before { content: fa-content($fa-var-mosque); }\n.#{$fa-css-prefix}-motorcycle:before { content: fa-content($fa-var-motorcycle); }\n.#{$fa-css-prefix}-mountain:before { content: fa-content($fa-var-mountain); }\n.#{$fa-css-prefix}-mouse-pointer:before { content: fa-content($fa-var-mouse-pointer); }\n.#{$fa-css-prefix}-mug-hot:before { content: fa-content($fa-var-mug-hot); }\n.#{$fa-css-prefix}-music:before { content: fa-content($fa-var-music); }\n.#{$fa-css-prefix}-napster:before { content: fa-content($fa-var-napster); }\n.#{$fa-css-prefix}-neos:before { content: fa-content($fa-var-neos); }\n.#{$fa-css-prefix}-network-wired:before { content: fa-content($fa-var-network-wired); }\n.#{$fa-css-prefix}-neuter:before { content: fa-content($fa-var-neuter); }\n.#{$fa-css-prefix}-newspaper:before { content: fa-content($fa-var-newspaper); }\n.#{$fa-css-prefix}-nimblr:before { content: fa-content($fa-var-nimblr); }\n.#{$fa-css-prefix}-node:before { content: fa-content($fa-var-node); }\n.#{$fa-css-prefix}-node-js:before { content: fa-content($fa-var-node-js); }\n.#{$fa-css-prefix}-not-equal:before { content: fa-content($fa-var-not-equal); }\n.#{$fa-css-prefix}-notes-medical:before { content: fa-content($fa-var-notes-medical); }\n.#{$fa-css-prefix}-npm:before { content: fa-content($fa-var-npm); }\n.#{$fa-css-prefix}-ns8:before { content: fa-content($fa-var-ns8); }\n.#{$fa-css-prefix}-nutritionix:before { content: fa-content($fa-var-nutritionix); }\n.#{$fa-css-prefix}-object-group:before { content: fa-content($fa-var-object-group); }\n.#{$fa-css-prefix}-object-ungroup:before { content: fa-content($fa-var-object-ungroup); }\n.#{$fa-css-prefix}-odnoklassniki:before { content: fa-content($fa-var-odnoklassniki); }\n.#{$fa-css-prefix}-odnoklassniki-square:before { content: fa-content($fa-var-odnoklassniki-square); }\n.#{$fa-css-prefix}-oil-can:before { content: fa-content($fa-var-oil-can); }\n.#{$fa-css-prefix}-old-republic:before { content: fa-content($fa-var-old-republic); }\n.#{$fa-css-prefix}-om:before { content: fa-content($fa-var-om); }\n.#{$fa-css-prefix}-opencart:before { content: fa-content($fa-var-opencart); }\n.#{$fa-css-prefix}-openid:before { content: fa-content($fa-var-openid); }\n.#{$fa-css-prefix}-opera:before { content: fa-content($fa-var-opera); }\n.#{$fa-css-prefix}-optin-monster:before { content: fa-content($fa-var-optin-monster); }\n.#{$fa-css-prefix}-osi:before { content: fa-content($fa-var-osi); }\n.#{$fa-css-prefix}-otter:before { content: fa-content($fa-var-otter); }\n.#{$fa-css-prefix}-outdent:before { content: fa-content($fa-var-outdent); }\n.#{$fa-css-prefix}-page4:before { content: fa-content($fa-var-page4); }\n.#{$fa-css-prefix}-pagelines:before { content: fa-content($fa-var-pagelines); }\n.#{$fa-css-prefix}-pager:before { content: fa-content($fa-var-pager); }\n.#{$fa-css-prefix}-paint-brush:before { content: fa-content($fa-var-paint-brush); }\n.#{$fa-css-prefix}-paint-roller:before { content: fa-content($fa-var-paint-roller); }\n.#{$fa-css-prefix}-palette:before { content: fa-content($fa-var-palette); }\n.#{$fa-css-prefix}-palfed:before { content: fa-content($fa-var-palfed); }\n.#{$fa-css-prefix}-pallet:before { content: fa-content($fa-var-pallet); }\n.#{$fa-css-prefix}-paper-plane:before { content: fa-content($fa-var-paper-plane); }\n.#{$fa-css-prefix}-paperclip:before { content: fa-content($fa-var-paperclip); }\n.#{$fa-css-prefix}-parachute-box:before { content: fa-content($fa-var-parachute-box); }\n.#{$fa-css-prefix}-paragraph:before { content: fa-content($fa-var-paragraph); }\n.#{$fa-css-prefix}-parking:before { content: fa-content($fa-var-parking); }\n.#{$fa-css-prefix}-passport:before { content: fa-content($fa-var-passport); }\n.#{$fa-css-prefix}-pastafarianism:before { content: fa-content($fa-var-pastafarianism); }\n.#{$fa-css-prefix}-paste:before { content: fa-content($fa-var-paste); }\n.#{$fa-css-prefix}-patreon:before { content: fa-content($fa-var-patreon); }\n.#{$fa-css-prefix}-pause:before { content: fa-content($fa-var-pause); }\n.#{$fa-css-prefix}-pause-circle:before { content: fa-content($fa-var-pause-circle); }\n.#{$fa-css-prefix}-paw:before { content: fa-content($fa-var-paw); }\n.#{$fa-css-prefix}-paypal:before { content: fa-content($fa-var-paypal); }\n.#{$fa-css-prefix}-peace:before { content: fa-content($fa-var-peace); }\n.#{$fa-css-prefix}-pen:before { content: fa-content($fa-var-pen); }\n.#{$fa-css-prefix}-pen-alt:before { content: fa-content($fa-var-pen-alt); }\n.#{$fa-css-prefix}-pen-fancy:before { content: fa-content($fa-var-pen-fancy); }\n.#{$fa-css-prefix}-pen-nib:before { content: fa-content($fa-var-pen-nib); }\n.#{$fa-css-prefix}-pen-square:before { content: fa-content($fa-var-pen-square); }\n.#{$fa-css-prefix}-pencil-alt:before { content: fa-content($fa-var-pencil-alt); }\n.#{$fa-css-prefix}-pencil-ruler:before { content: fa-content($fa-var-pencil-ruler); }\n.#{$fa-css-prefix}-penny-arcade:before { content: fa-content($fa-var-penny-arcade); }\n.#{$fa-css-prefix}-people-carry:before { content: fa-content($fa-var-people-carry); }\n.#{$fa-css-prefix}-pepper-hot:before { content: fa-content($fa-var-pepper-hot); }\n.#{$fa-css-prefix}-percent:before { content: fa-content($fa-var-percent); }\n.#{$fa-css-prefix}-percentage:before { content: fa-content($fa-var-percentage); }\n.#{$fa-css-prefix}-periscope:before { content: fa-content($fa-var-periscope); }\n.#{$fa-css-prefix}-person-booth:before { content: fa-content($fa-var-person-booth); }\n.#{$fa-css-prefix}-phabricator:before { content: fa-content($fa-var-phabricator); }\n.#{$fa-css-prefix}-phoenix-framework:before { content: fa-content($fa-var-phoenix-framework); }\n.#{$fa-css-prefix}-phoenix-squadron:before { content: fa-content($fa-var-phoenix-squadron); }\n.#{$fa-css-prefix}-phone:before { content: fa-content($fa-var-phone); }\n.#{$fa-css-prefix}-phone-alt:before { content: fa-content($fa-var-phone-alt); }\n.#{$fa-css-prefix}-phone-slash:before { content: fa-content($fa-var-phone-slash); }\n.#{$fa-css-prefix}-phone-square:before { content: fa-content($fa-var-phone-square); }\n.#{$fa-css-prefix}-phone-square-alt:before { content: fa-content($fa-var-phone-square-alt); }\n.#{$fa-css-prefix}-phone-volume:before { content: fa-content($fa-var-phone-volume); }\n.#{$fa-css-prefix}-photo-video:before { content: fa-content($fa-var-photo-video); }\n.#{$fa-css-prefix}-php:before { content: fa-content($fa-var-php); }\n.#{$fa-css-prefix}-pied-piper:before { content: fa-content($fa-var-pied-piper); }\n.#{$fa-css-prefix}-pied-piper-alt:before { content: fa-content($fa-var-pied-piper-alt); }\n.#{$fa-css-prefix}-pied-piper-hat:before { content: fa-content($fa-var-pied-piper-hat); }\n.#{$fa-css-prefix}-pied-piper-pp:before { content: fa-content($fa-var-pied-piper-pp); }\n.#{$fa-css-prefix}-piggy-bank:before { content: fa-content($fa-var-piggy-bank); }\n.#{$fa-css-prefix}-pills:before { content: fa-content($fa-var-pills); }\n.#{$fa-css-prefix}-pinterest:before { content: fa-content($fa-var-pinterest); }\n.#{$fa-css-prefix}-pinterest-p:before { content: fa-content($fa-var-pinterest-p); }\n.#{$fa-css-prefix}-pinterest-square:before { content: fa-content($fa-var-pinterest-square); }\n.#{$fa-css-prefix}-pizza-slice:before { content: fa-content($fa-var-pizza-slice); }\n.#{$fa-css-prefix}-place-of-worship:before { content: fa-content($fa-var-place-of-worship); }\n.#{$fa-css-prefix}-plane:before { content: fa-content($fa-var-plane); }\n.#{$fa-css-prefix}-plane-arrival:before { content: fa-content($fa-var-plane-arrival); }\n.#{$fa-css-prefix}-plane-departure:before { content: fa-content($fa-var-plane-departure); }\n.#{$fa-css-prefix}-play:before { content: fa-content($fa-var-play); }\n.#{$fa-css-prefix}-play-circle:before { content: fa-content($fa-var-play-circle); }\n.#{$fa-css-prefix}-playstation:before { content: fa-content($fa-var-playstation); }\n.#{$fa-css-prefix}-plug:before { content: fa-content($fa-var-plug); }\n.#{$fa-css-prefix}-plus:before { content: fa-content($fa-var-plus); }\n.#{$fa-css-prefix}-plus-circle:before { content: fa-content($fa-var-plus-circle); }\n.#{$fa-css-prefix}-plus-square:before { content: fa-content($fa-var-plus-square); }\n.#{$fa-css-prefix}-podcast:before { content: fa-content($fa-var-podcast); }\n.#{$fa-css-prefix}-poll:before { content: fa-content($fa-var-poll); }\n.#{$fa-css-prefix}-poll-h:before { content: fa-content($fa-var-poll-h); }\n.#{$fa-css-prefix}-poo:before { content: fa-content($fa-var-poo); }\n.#{$fa-css-prefix}-poo-storm:before { content: fa-content($fa-var-poo-storm); }\n.#{$fa-css-prefix}-poop:before { content: fa-content($fa-var-poop); }\n.#{$fa-css-prefix}-portrait:before { content: fa-content($fa-var-portrait); }\n.#{$fa-css-prefix}-pound-sign:before { content: fa-content($fa-var-pound-sign); }\n.#{$fa-css-prefix}-power-off:before { content: fa-content($fa-var-power-off); }\n.#{$fa-css-prefix}-pray:before { content: fa-content($fa-var-pray); }\n.#{$fa-css-prefix}-praying-hands:before { content: fa-content($fa-var-praying-hands); }\n.#{$fa-css-prefix}-prescription:before { content: fa-content($fa-var-prescription); }\n.#{$fa-css-prefix}-prescription-bottle:before { content: fa-content($fa-var-prescription-bottle); }\n.#{$fa-css-prefix}-prescription-bottle-alt:before { content: fa-content($fa-var-prescription-bottle-alt); }\n.#{$fa-css-prefix}-print:before { content: fa-content($fa-var-print); }\n.#{$fa-css-prefix}-procedures:before { content: fa-content($fa-var-procedures); }\n.#{$fa-css-prefix}-product-hunt:before { content: fa-content($fa-var-product-hunt); }\n.#{$fa-css-prefix}-project-diagram:before { content: fa-content($fa-var-project-diagram); }\n.#{$fa-css-prefix}-pushed:before { content: fa-content($fa-var-pushed); }\n.#{$fa-css-prefix}-puzzle-piece:before { content: fa-content($fa-var-puzzle-piece); }\n.#{$fa-css-prefix}-python:before { content: fa-content($fa-var-python); }\n.#{$fa-css-prefix}-qq:before { content: fa-content($fa-var-qq); }\n.#{$fa-css-prefix}-qrcode:before { content: fa-content($fa-var-qrcode); }\n.#{$fa-css-prefix}-question:before { content: fa-content($fa-var-question); }\n.#{$fa-css-prefix}-question-circle:before { content: fa-content($fa-var-question-circle); }\n.#{$fa-css-prefix}-quidditch:before { content: fa-content($fa-var-quidditch); }\n.#{$fa-css-prefix}-quinscape:before { content: fa-content($fa-var-quinscape); }\n.#{$fa-css-prefix}-quora:before { content: fa-content($fa-var-quora); }\n.#{$fa-css-prefix}-quote-left:before { content: fa-content($fa-var-quote-left); }\n.#{$fa-css-prefix}-quote-right:before { content: fa-content($fa-var-quote-right); }\n.#{$fa-css-prefix}-quran:before { content: fa-content($fa-var-quran); }\n.#{$fa-css-prefix}-r-project:before { content: fa-content($fa-var-r-project); }\n.#{$fa-css-prefix}-radiation:before { content: fa-content($fa-var-radiation); }\n.#{$fa-css-prefix}-radiation-alt:before { content: fa-content($fa-var-radiation-alt); }\n.#{$fa-css-prefix}-rainbow:before { content: fa-content($fa-var-rainbow); }\n.#{$fa-css-prefix}-random:before { content: fa-content($fa-var-random); }\n.#{$fa-css-prefix}-raspberry-pi:before { content: fa-content($fa-var-raspberry-pi); }\n.#{$fa-css-prefix}-ravelry:before { content: fa-content($fa-var-ravelry); }\n.#{$fa-css-prefix}-react:before { content: fa-content($fa-var-react); }\n.#{$fa-css-prefix}-reacteurope:before { content: fa-content($fa-var-reacteurope); }\n.#{$fa-css-prefix}-readme:before { content: fa-content($fa-var-readme); }\n.#{$fa-css-prefix}-rebel:before { content: fa-content($fa-var-rebel); }\n.#{$fa-css-prefix}-receipt:before { content: fa-content($fa-var-receipt); }\n.#{$fa-css-prefix}-recycle:before { content: fa-content($fa-var-recycle); }\n.#{$fa-css-prefix}-red-river:before { content: fa-content($fa-var-red-river); }\n.#{$fa-css-prefix}-reddit:before { content: fa-content($fa-var-reddit); }\n.#{$fa-css-prefix}-reddit-alien:before { content: fa-content($fa-var-reddit-alien); }\n.#{$fa-css-prefix}-reddit-square:before { content: fa-content($fa-var-reddit-square); }\n.#{$fa-css-prefix}-redhat:before { content: fa-content($fa-var-redhat); }\n.#{$fa-css-prefix}-redo:before { content: fa-content($fa-var-redo); }\n.#{$fa-css-prefix}-redo-alt:before { content: fa-content($fa-var-redo-alt); }\n.#{$fa-css-prefix}-registered:before { content: fa-content($fa-var-registered); }\n.#{$fa-css-prefix}-remove-format:before { content: fa-content($fa-var-remove-format); }\n.#{$fa-css-prefix}-renren:before { content: fa-content($fa-var-renren); }\n.#{$fa-css-prefix}-reply:before { content: fa-content($fa-var-reply); }\n.#{$fa-css-prefix}-reply-all:before { content: fa-content($fa-var-reply-all); }\n.#{$fa-css-prefix}-replyd:before { content: fa-content($fa-var-replyd); }\n.#{$fa-css-prefix}-republican:before { content: fa-content($fa-var-republican); }\n.#{$fa-css-prefix}-researchgate:before { content: fa-content($fa-var-researchgate); }\n.#{$fa-css-prefix}-resolving:before { content: fa-content($fa-var-resolving); }\n.#{$fa-css-prefix}-restroom:before { content: fa-content($fa-var-restroom); }\n.#{$fa-css-prefix}-retweet:before { content: fa-content($fa-var-retweet); }\n.#{$fa-css-prefix}-rev:before { content: fa-content($fa-var-rev); }\n.#{$fa-css-prefix}-ribbon:before { content: fa-content($fa-var-ribbon); }\n.#{$fa-css-prefix}-ring:before { content: fa-content($fa-var-ring); }\n.#{$fa-css-prefix}-road:before { content: fa-content($fa-var-road); }\n.#{$fa-css-prefix}-robot:before { content: fa-content($fa-var-robot); }\n.#{$fa-css-prefix}-rocket:before { content: fa-content($fa-var-rocket); }\n.#{$fa-css-prefix}-rocketchat:before { content: fa-content($fa-var-rocketchat); }\n.#{$fa-css-prefix}-rockrms:before { content: fa-content($fa-var-rockrms); }\n.#{$fa-css-prefix}-route:before { content: fa-content($fa-var-route); }\n.#{$fa-css-prefix}-rss:before { content: fa-content($fa-var-rss); }\n.#{$fa-css-prefix}-rss-square:before { content: fa-content($fa-var-rss-square); }\n.#{$fa-css-prefix}-ruble-sign:before { content: fa-content($fa-var-ruble-sign); }\n.#{$fa-css-prefix}-ruler:before { content: fa-content($fa-var-ruler); }\n.#{$fa-css-prefix}-ruler-combined:before { content: fa-content($fa-var-ruler-combined); }\n.#{$fa-css-prefix}-ruler-horizontal:before { content: fa-content($fa-var-ruler-horizontal); }\n.#{$fa-css-prefix}-ruler-vertical:before { content: fa-content($fa-var-ruler-vertical); }\n.#{$fa-css-prefix}-running:before { content: fa-content($fa-var-running); }\n.#{$fa-css-prefix}-rupee-sign:before { content: fa-content($fa-var-rupee-sign); }\n.#{$fa-css-prefix}-sad-cry:before { content: fa-content($fa-var-sad-cry); }\n.#{$fa-css-prefix}-sad-tear:before { content: fa-content($fa-var-sad-tear); }\n.#{$fa-css-prefix}-safari:before { content: fa-content($fa-var-safari); }\n.#{$fa-css-prefix}-salesforce:before { content: fa-content($fa-var-salesforce); }\n.#{$fa-css-prefix}-sass:before { content: fa-content($fa-var-sass); }\n.#{$fa-css-prefix}-satellite:before { content: fa-content($fa-var-satellite); }\n.#{$fa-css-prefix}-satellite-dish:before { content: fa-content($fa-var-satellite-dish); }\n.#{$fa-css-prefix}-save:before { content: fa-content($fa-var-save); }\n.#{$fa-css-prefix}-schlix:before { content: fa-content($fa-var-schlix); }\n.#{$fa-css-prefix}-school:before { content: fa-content($fa-var-school); }\n.#{$fa-css-prefix}-screwdriver:before { content: fa-content($fa-var-screwdriver); }\n.#{$fa-css-prefix}-scribd:before { content: fa-content($fa-var-scribd); }\n.#{$fa-css-prefix}-scroll:before { content: fa-content($fa-var-scroll); }\n.#{$fa-css-prefix}-sd-card:before { content: fa-content($fa-var-sd-card); }\n.#{$fa-css-prefix}-search:before { content: fa-content($fa-var-search); }\n.#{$fa-css-prefix}-search-dollar:before { content: fa-content($fa-var-search-dollar); }\n.#{$fa-css-prefix}-search-location:before { content: fa-content($fa-var-search-location); }\n.#{$fa-css-prefix}-search-minus:before { content: fa-content($fa-var-search-minus); }\n.#{$fa-css-prefix}-search-plus:before { content: fa-content($fa-var-search-plus); }\n.#{$fa-css-prefix}-searchengin:before { content: fa-content($fa-var-searchengin); }\n.#{$fa-css-prefix}-seedling:before { content: fa-content($fa-var-seedling); }\n.#{$fa-css-prefix}-sellcast:before { content: fa-content($fa-var-sellcast); }\n.#{$fa-css-prefix}-sellsy:before { content: fa-content($fa-var-sellsy); }\n.#{$fa-css-prefix}-server:before { content: fa-content($fa-var-server); }\n.#{$fa-css-prefix}-servicestack:before { content: fa-content($fa-var-servicestack); }\n.#{$fa-css-prefix}-shapes:before { content: fa-content($fa-var-shapes); }\n.#{$fa-css-prefix}-share:before { content: fa-content($fa-var-share); }\n.#{$fa-css-prefix}-share-alt:before { content: fa-content($fa-var-share-alt); }\n.#{$fa-css-prefix}-share-alt-square:before { content: fa-content($fa-var-share-alt-square); }\n.#{$fa-css-prefix}-share-square:before { content: fa-content($fa-var-share-square); }\n.#{$fa-css-prefix}-shekel-sign:before { content: fa-content($fa-var-shekel-sign); }\n.#{$fa-css-prefix}-shield-alt:before { content: fa-content($fa-var-shield-alt); }\n.#{$fa-css-prefix}-ship:before { content: fa-content($fa-var-ship); }\n.#{$fa-css-prefix}-shipping-fast:before { content: fa-content($fa-var-shipping-fast); }\n.#{$fa-css-prefix}-shirtsinbulk:before { content: fa-content($fa-var-shirtsinbulk); }\n.#{$fa-css-prefix}-shoe-prints:before { content: fa-content($fa-var-shoe-prints); }\n.#{$fa-css-prefix}-shopping-bag:before { content: fa-content($fa-var-shopping-bag); }\n.#{$fa-css-prefix}-shopping-basket:before { content: fa-content($fa-var-shopping-basket); }\n.#{$fa-css-prefix}-shopping-cart:before { content: fa-content($fa-var-shopping-cart); }\n.#{$fa-css-prefix}-shopware:before { content: fa-content($fa-var-shopware); }\n.#{$fa-css-prefix}-shower:before { content: fa-content($fa-var-shower); }\n.#{$fa-css-prefix}-shuttle-van:before { content: fa-content($fa-var-shuttle-van); }\n.#{$fa-css-prefix}-sign:before { content: fa-content($fa-var-sign); }\n.#{$fa-css-prefix}-sign-in-alt:before { content: fa-content($fa-var-sign-in-alt); }\n.#{$fa-css-prefix}-sign-language:before { content: fa-content($fa-var-sign-language); }\n.#{$fa-css-prefix}-sign-out-alt:before { content: fa-content($fa-var-sign-out-alt); }\n.#{$fa-css-prefix}-signal:before { content: fa-content($fa-var-signal); }\n.#{$fa-css-prefix}-signature:before { content: fa-content($fa-var-signature); }\n.#{$fa-css-prefix}-sim-card:before { content: fa-content($fa-var-sim-card); }\n.#{$fa-css-prefix}-simplybuilt:before { content: fa-content($fa-var-simplybuilt); }\n.#{$fa-css-prefix}-sistrix:before { content: fa-content($fa-var-sistrix); }\n.#{$fa-css-prefix}-sitemap:before { content: fa-content($fa-var-sitemap); }\n.#{$fa-css-prefix}-sith:before { content: fa-content($fa-var-sith); }\n.#{$fa-css-prefix}-skating:before { content: fa-content($fa-var-skating); }\n.#{$fa-css-prefix}-sketch:before { content: fa-content($fa-var-sketch); }\n.#{$fa-css-prefix}-skiing:before { content: fa-content($fa-var-skiing); }\n.#{$fa-css-prefix}-skiing-nordic:before { content: fa-content($fa-var-skiing-nordic); }\n.#{$fa-css-prefix}-skull:before { content: fa-content($fa-var-skull); }\n.#{$fa-css-prefix}-skull-crossbones:before { content: fa-content($fa-var-skull-crossbones); }\n.#{$fa-css-prefix}-skyatlas:before { content: fa-content($fa-var-skyatlas); }\n.#{$fa-css-prefix}-skype:before { content: fa-content($fa-var-skype); }\n.#{$fa-css-prefix}-slack:before { content: fa-content($fa-var-slack); }\n.#{$fa-css-prefix}-slack-hash:before { content: fa-content($fa-var-slack-hash); }\n.#{$fa-css-prefix}-slash:before { content: fa-content($fa-var-slash); }\n.#{$fa-css-prefix}-sleigh:before { content: fa-content($fa-var-sleigh); }\n.#{$fa-css-prefix}-sliders-h:before { content: fa-content($fa-var-sliders-h); }\n.#{$fa-css-prefix}-slideshare:before { content: fa-content($fa-var-slideshare); }\n.#{$fa-css-prefix}-smile:before { content: fa-content($fa-var-smile); }\n.#{$fa-css-prefix}-smile-beam:before { content: fa-content($fa-var-smile-beam); }\n.#{$fa-css-prefix}-smile-wink:before { content: fa-content($fa-var-smile-wink); }\n.#{$fa-css-prefix}-smog:before { content: fa-content($fa-var-smog); }\n.#{$fa-css-prefix}-smoking:before { content: fa-content($fa-var-smoking); }\n.#{$fa-css-prefix}-smoking-ban:before { content: fa-content($fa-var-smoking-ban); }\n.#{$fa-css-prefix}-sms:before { content: fa-content($fa-var-sms); }\n.#{$fa-css-prefix}-snapchat:before { content: fa-content($fa-var-snapchat); }\n.#{$fa-css-prefix}-snapchat-ghost:before { content: fa-content($fa-var-snapchat-ghost); }\n.#{$fa-css-prefix}-snapchat-square:before { content: fa-content($fa-var-snapchat-square); }\n.#{$fa-css-prefix}-snowboarding:before { content: fa-content($fa-var-snowboarding); }\n.#{$fa-css-prefix}-snowflake:before { content: fa-content($fa-var-snowflake); }\n.#{$fa-css-prefix}-snowman:before { content: fa-content($fa-var-snowman); }\n.#{$fa-css-prefix}-snowplow:before { content: fa-content($fa-var-snowplow); }\n.#{$fa-css-prefix}-socks:before { content: fa-content($fa-var-socks); }\n.#{$fa-css-prefix}-solar-panel:before { content: fa-content($fa-var-solar-panel); }\n.#{$fa-css-prefix}-sort:before { content: fa-content($fa-var-sort); }\n.#{$fa-css-prefix}-sort-alpha-down:before { content: fa-content($fa-var-sort-alpha-down); }\n.#{$fa-css-prefix}-sort-alpha-down-alt:before { content: fa-content($fa-var-sort-alpha-down-alt); }\n.#{$fa-css-prefix}-sort-alpha-up:before { content: fa-content($fa-var-sort-alpha-up); }\n.#{$fa-css-prefix}-sort-alpha-up-alt:before { content: fa-content($fa-var-sort-alpha-up-alt); }\n.#{$fa-css-prefix}-sort-amount-down:before { content: fa-content($fa-var-sort-amount-down); }\n.#{$fa-css-prefix}-sort-amount-down-alt:before { content: fa-content($fa-var-sort-amount-down-alt); }\n.#{$fa-css-prefix}-sort-amount-up:before { content: fa-content($fa-var-sort-amount-up); }\n.#{$fa-css-prefix}-sort-amount-up-alt:before { content: fa-content($fa-var-sort-amount-up-alt); }\n.#{$fa-css-prefix}-sort-down:before { content: fa-content($fa-var-sort-down); }\n.#{$fa-css-prefix}-sort-numeric-down:before { content: fa-content($fa-var-sort-numeric-down); }\n.#{$fa-css-prefix}-sort-numeric-down-alt:before { content: fa-content($fa-var-sort-numeric-down-alt); }\n.#{$fa-css-prefix}-sort-numeric-up:before { content: fa-content($fa-var-sort-numeric-up); }\n.#{$fa-css-prefix}-sort-numeric-up-alt:before { content: fa-content($fa-var-sort-numeric-up-alt); }\n.#{$fa-css-prefix}-sort-up:before { content: fa-content($fa-var-sort-up); }\n.#{$fa-css-prefix}-soundcloud:before { content: fa-content($fa-var-soundcloud); }\n.#{$fa-css-prefix}-sourcetree:before { content: fa-content($fa-var-sourcetree); }\n.#{$fa-css-prefix}-spa:before { content: fa-content($fa-var-spa); }\n.#{$fa-css-prefix}-space-shuttle:before { content: fa-content($fa-var-space-shuttle); }\n.#{$fa-css-prefix}-speakap:before { content: fa-content($fa-var-speakap); }\n.#{$fa-css-prefix}-speaker-deck:before { content: fa-content($fa-var-speaker-deck); }\n.#{$fa-css-prefix}-spell-check:before { content: fa-content($fa-var-spell-check); }\n.#{$fa-css-prefix}-spider:before { content: fa-content($fa-var-spider); }\n.#{$fa-css-prefix}-spinner:before { content: fa-content($fa-var-spinner); }\n.#{$fa-css-prefix}-splotch:before { content: fa-content($fa-var-splotch); }\n.#{$fa-css-prefix}-spotify:before { content: fa-content($fa-var-spotify); }\n.#{$fa-css-prefix}-spray-can:before { content: fa-content($fa-var-spray-can); }\n.#{$fa-css-prefix}-square:before { content: fa-content($fa-var-square); }\n.#{$fa-css-prefix}-square-full:before { content: fa-content($fa-var-square-full); }\n.#{$fa-css-prefix}-square-root-alt:before { content: fa-content($fa-var-square-root-alt); }\n.#{$fa-css-prefix}-squarespace:before { content: fa-content($fa-var-squarespace); }\n.#{$fa-css-prefix}-stack-exchange:before { content: fa-content($fa-var-stack-exchange); }\n.#{$fa-css-prefix}-stack-overflow:before { content: fa-content($fa-var-stack-overflow); }\n.#{$fa-css-prefix}-stackpath:before { content: fa-content($fa-var-stackpath); }\n.#{$fa-css-prefix}-stamp:before { content: fa-content($fa-var-stamp); }\n.#{$fa-css-prefix}-star:before { content: fa-content($fa-var-star); }\n.#{$fa-css-prefix}-star-and-crescent:before { content: fa-content($fa-var-star-and-crescent); }\n.#{$fa-css-prefix}-star-half:before { content: fa-content($fa-var-star-half); }\n.#{$fa-css-prefix}-star-half-alt:before { content: fa-content($fa-var-star-half-alt); }\n.#{$fa-css-prefix}-star-of-david:before { content: fa-content($fa-var-star-of-david); }\n.#{$fa-css-prefix}-star-of-life:before { content: fa-content($fa-var-star-of-life); }\n.#{$fa-css-prefix}-staylinked:before { content: fa-content($fa-var-staylinked); }\n.#{$fa-css-prefix}-steam:before { content: fa-content($fa-var-steam); }\n.#{$fa-css-prefix}-steam-square:before { content: fa-content($fa-var-steam-square); }\n.#{$fa-css-prefix}-steam-symbol:before { content: fa-content($fa-var-steam-symbol); }\n.#{$fa-css-prefix}-step-backward:before { content: fa-content($fa-var-step-backward); }\n.#{$fa-css-prefix}-step-forward:before { content: fa-content($fa-var-step-forward); }\n.#{$fa-css-prefix}-stethoscope:before { content: fa-content($fa-var-stethoscope); }\n.#{$fa-css-prefix}-sticker-mule:before { content: fa-content($fa-var-sticker-mule); }\n.#{$fa-css-prefix}-sticky-note:before { content: fa-content($fa-var-sticky-note); }\n.#{$fa-css-prefix}-stop:before { content: fa-content($fa-var-stop); }\n.#{$fa-css-prefix}-stop-circle:before { content: fa-content($fa-var-stop-circle); }\n.#{$fa-css-prefix}-stopwatch:before { content: fa-content($fa-var-stopwatch); }\n.#{$fa-css-prefix}-store:before { content: fa-content($fa-var-store); }\n.#{$fa-css-prefix}-store-alt:before { content: fa-content($fa-var-store-alt); }\n.#{$fa-css-prefix}-strava:before { content: fa-content($fa-var-strava); }\n.#{$fa-css-prefix}-stream:before { content: fa-content($fa-var-stream); }\n.#{$fa-css-prefix}-street-view:before { content: fa-content($fa-var-street-view); }\n.#{$fa-css-prefix}-strikethrough:before { content: fa-content($fa-var-strikethrough); }\n.#{$fa-css-prefix}-stripe:before { content: fa-content($fa-var-stripe); }\n.#{$fa-css-prefix}-stripe-s:before { content: fa-content($fa-var-stripe-s); }\n.#{$fa-css-prefix}-stroopwafel:before { content: fa-content($fa-var-stroopwafel); }\n.#{$fa-css-prefix}-studiovinari:before { content: fa-content($fa-var-studiovinari); }\n.#{$fa-css-prefix}-stumbleupon:before { content: fa-content($fa-var-stumbleupon); }\n.#{$fa-css-prefix}-stumbleupon-circle:before { content: fa-content($fa-var-stumbleupon-circle); }\n.#{$fa-css-prefix}-subscript:before { content: fa-content($fa-var-subscript); }\n.#{$fa-css-prefix}-subway:before { content: fa-content($fa-var-subway); }\n.#{$fa-css-prefix}-suitcase:before { content: fa-content($fa-var-suitcase); }\n.#{$fa-css-prefix}-suitcase-rolling:before { content: fa-content($fa-var-suitcase-rolling); }\n.#{$fa-css-prefix}-sun:before { content: fa-content($fa-var-sun); }\n.#{$fa-css-prefix}-superpowers:before { content: fa-content($fa-var-superpowers); }\n.#{$fa-css-prefix}-superscript:before { content: fa-content($fa-var-superscript); }\n.#{$fa-css-prefix}-supple:before { content: fa-content($fa-var-supple); }\n.#{$fa-css-prefix}-surprise:before { content: fa-content($fa-var-surprise); }\n.#{$fa-css-prefix}-suse:before { content: fa-content($fa-var-suse); }\n.#{$fa-css-prefix}-swatchbook:before { content: fa-content($fa-var-swatchbook); }\n.#{$fa-css-prefix}-swimmer:before { content: fa-content($fa-var-swimmer); }\n.#{$fa-css-prefix}-swimming-pool:before { content: fa-content($fa-var-swimming-pool); }\n.#{$fa-css-prefix}-symfony:before { content: fa-content($fa-var-symfony); }\n.#{$fa-css-prefix}-synagogue:before { content: fa-content($fa-var-synagogue); }\n.#{$fa-css-prefix}-sync:before { content: fa-content($fa-var-sync); }\n.#{$fa-css-prefix}-sync-alt:before { content: fa-content($fa-var-sync-alt); }\n.#{$fa-css-prefix}-syringe:before { content: fa-content($fa-var-syringe); }\n.#{$fa-css-prefix}-table:before { content: fa-content($fa-var-table); }\n.#{$fa-css-prefix}-table-tennis:before { content: fa-content($fa-var-table-tennis); }\n.#{$fa-css-prefix}-tablet:before { content: fa-content($fa-var-tablet); }\n.#{$fa-css-prefix}-tablet-alt:before { content: fa-content($fa-var-tablet-alt); }\n.#{$fa-css-prefix}-tablets:before { content: fa-content($fa-var-tablets); }\n.#{$fa-css-prefix}-tachometer-alt:before { content: fa-content($fa-var-tachometer-alt); }\n.#{$fa-css-prefix}-tag:before { content: fa-content($fa-var-tag); }\n.#{$fa-css-prefix}-tags:before { content: fa-content($fa-var-tags); }\n.#{$fa-css-prefix}-tape:before { content: fa-content($fa-var-tape); }\n.#{$fa-css-prefix}-tasks:before { content: fa-content($fa-var-tasks); }\n.#{$fa-css-prefix}-taxi:before { content: fa-content($fa-var-taxi); }\n.#{$fa-css-prefix}-teamspeak:before { content: fa-content($fa-var-teamspeak); }\n.#{$fa-css-prefix}-teeth:before { content: fa-content($fa-var-teeth); }\n.#{$fa-css-prefix}-teeth-open:before { content: fa-content($fa-var-teeth-open); }\n.#{$fa-css-prefix}-telegram:before { content: fa-content($fa-var-telegram); }\n.#{$fa-css-prefix}-telegram-plane:before { content: fa-content($fa-var-telegram-plane); }\n.#{$fa-css-prefix}-temperature-high:before { content: fa-content($fa-var-temperature-high); }\n.#{$fa-css-prefix}-temperature-low:before { content: fa-content($fa-var-temperature-low); }\n.#{$fa-css-prefix}-tencent-weibo:before { content: fa-content($fa-var-tencent-weibo); }\n.#{$fa-css-prefix}-tenge:before { content: fa-content($fa-var-tenge); }\n.#{$fa-css-prefix}-terminal:before { content: fa-content($fa-var-terminal); }\n.#{$fa-css-prefix}-text-height:before { content: fa-content($fa-var-text-height); }\n.#{$fa-css-prefix}-text-width:before { content: fa-content($fa-var-text-width); }\n.#{$fa-css-prefix}-th:before { content: fa-content($fa-var-th); }\n.#{$fa-css-prefix}-th-large:before { content: fa-content($fa-var-th-large); }\n.#{$fa-css-prefix}-th-list:before { content: fa-content($fa-var-th-list); }\n.#{$fa-css-prefix}-the-red-yeti:before { content: fa-content($fa-var-the-red-yeti); }\n.#{$fa-css-prefix}-theater-masks:before { content: fa-content($fa-var-theater-masks); }\n.#{$fa-css-prefix}-themeco:before { content: fa-content($fa-var-themeco); }\n.#{$fa-css-prefix}-themeisle:before { content: fa-content($fa-var-themeisle); }\n.#{$fa-css-prefix}-thermometer:before { content: fa-content($fa-var-thermometer); }\n.#{$fa-css-prefix}-thermometer-empty:before { content: fa-content($fa-var-thermometer-empty); }\n.#{$fa-css-prefix}-thermometer-full:before { content: fa-content($fa-var-thermometer-full); }\n.#{$fa-css-prefix}-thermometer-half:before { content: fa-content($fa-var-thermometer-half); }\n.#{$fa-css-prefix}-thermometer-quarter:before { content: fa-content($fa-var-thermometer-quarter); }\n.#{$fa-css-prefix}-thermometer-three-quarters:before { content: fa-content($fa-var-thermometer-three-quarters); }\n.#{$fa-css-prefix}-think-peaks:before { content: fa-content($fa-var-think-peaks); }\n.#{$fa-css-prefix}-thumbs-down:before { content: fa-content($fa-var-thumbs-down); }\n.#{$fa-css-prefix}-thumbs-up:before { content: fa-content($fa-var-thumbs-up); }\n.#{$fa-css-prefix}-thumbtack:before { content: fa-content($fa-var-thumbtack); }\n.#{$fa-css-prefix}-ticket-alt:before { content: fa-content($fa-var-ticket-alt); }\n.#{$fa-css-prefix}-times:before { content: fa-content($fa-var-times); }\n.#{$fa-css-prefix}-times-circle:before { content: fa-content($fa-var-times-circle); }\n.#{$fa-css-prefix}-tint:before { content: fa-content($fa-var-tint); }\n.#{$fa-css-prefix}-tint-slash:before { content: fa-content($fa-var-tint-slash); }\n.#{$fa-css-prefix}-tired:before { content: fa-content($fa-var-tired); }\n.#{$fa-css-prefix}-toggle-off:before { content: fa-content($fa-var-toggle-off); }\n.#{$fa-css-prefix}-toggle-on:before { content: fa-content($fa-var-toggle-on); }\n.#{$fa-css-prefix}-toilet:before { content: fa-content($fa-var-toilet); }\n.#{$fa-css-prefix}-toilet-paper:before { content: fa-content($fa-var-toilet-paper); }\n.#{$fa-css-prefix}-toolbox:before { content: fa-content($fa-var-toolbox); }\n.#{$fa-css-prefix}-tools:before { content: fa-content($fa-var-tools); }\n.#{$fa-css-prefix}-tooth:before { content: fa-content($fa-var-tooth); }\n.#{$fa-css-prefix}-torah:before { content: fa-content($fa-var-torah); }\n.#{$fa-css-prefix}-torii-gate:before { content: fa-content($fa-var-torii-gate); }\n.#{$fa-css-prefix}-tractor:before { content: fa-content($fa-var-tractor); }\n.#{$fa-css-prefix}-trade-federation:before { content: fa-content($fa-var-trade-federation); }\n.#{$fa-css-prefix}-trademark:before { content: fa-content($fa-var-trademark); }\n.#{$fa-css-prefix}-traffic-light:before { content: fa-content($fa-var-traffic-light); }\n.#{$fa-css-prefix}-train:before { content: fa-content($fa-var-train); }\n.#{$fa-css-prefix}-tram:before { content: fa-content($fa-var-tram); }\n.#{$fa-css-prefix}-transgender:before { content: fa-content($fa-var-transgender); }\n.#{$fa-css-prefix}-transgender-alt:before { content: fa-content($fa-var-transgender-alt); }\n.#{$fa-css-prefix}-trash:before { content: fa-content($fa-var-trash); }\n.#{$fa-css-prefix}-trash-alt:before { content: fa-content($fa-var-trash-alt); }\n.#{$fa-css-prefix}-trash-restore:before { content: fa-content($fa-var-trash-restore); }\n.#{$fa-css-prefix}-trash-restore-alt:before { content: fa-content($fa-var-trash-restore-alt); }\n.#{$fa-css-prefix}-tree:before { content: fa-content($fa-var-tree); }\n.#{$fa-css-prefix}-trello:before { content: fa-content($fa-var-trello); }\n.#{$fa-css-prefix}-tripadvisor:before { content: fa-content($fa-var-tripadvisor); }\n.#{$fa-css-prefix}-trophy:before { content: fa-content($fa-var-trophy); }\n.#{$fa-css-prefix}-truck:before { content: fa-content($fa-var-truck); }\n.#{$fa-css-prefix}-truck-loading:before { content: fa-content($fa-var-truck-loading); }\n.#{$fa-css-prefix}-truck-monster:before { content: fa-content($fa-var-truck-monster); }\n.#{$fa-css-prefix}-truck-moving:before { content: fa-content($fa-var-truck-moving); }\n.#{$fa-css-prefix}-truck-pickup:before { content: fa-content($fa-var-truck-pickup); }\n.#{$fa-css-prefix}-tshirt:before { content: fa-content($fa-var-tshirt); }\n.#{$fa-css-prefix}-tty:before { content: fa-content($fa-var-tty); }\n.#{$fa-css-prefix}-tumblr:before { content: fa-content($fa-var-tumblr); }\n.#{$fa-css-prefix}-tumblr-square:before { content: fa-content($fa-var-tumblr-square); }\n.#{$fa-css-prefix}-tv:before { content: fa-content($fa-var-tv); }\n.#{$fa-css-prefix}-twitch:before { content: fa-content($fa-var-twitch); }\n.#{$fa-css-prefix}-twitter:before { content: fa-content($fa-var-twitter); }\n.#{$fa-css-prefix}-twitter-square:before { content: fa-content($fa-var-twitter-square); }\n.#{$fa-css-prefix}-typo3:before { content: fa-content($fa-var-typo3); }\n.#{$fa-css-prefix}-uber:before { content: fa-content($fa-var-uber); }\n.#{$fa-css-prefix}-ubuntu:before { content: fa-content($fa-var-ubuntu); }\n.#{$fa-css-prefix}-uikit:before { content: fa-content($fa-var-uikit); }\n.#{$fa-css-prefix}-umbrella:before { content: fa-content($fa-var-umbrella); }\n.#{$fa-css-prefix}-umbrella-beach:before { content: fa-content($fa-var-umbrella-beach); }\n.#{$fa-css-prefix}-underline:before { content: fa-content($fa-var-underline); }\n.#{$fa-css-prefix}-undo:before { content: fa-content($fa-var-undo); }\n.#{$fa-css-prefix}-undo-alt:before { content: fa-content($fa-var-undo-alt); }\n.#{$fa-css-prefix}-uniregistry:before { content: fa-content($fa-var-uniregistry); }\n.#{$fa-css-prefix}-universal-access:before { content: fa-content($fa-var-universal-access); }\n.#{$fa-css-prefix}-university:before { content: fa-content($fa-var-university); }\n.#{$fa-css-prefix}-unlink:before { content: fa-content($fa-var-unlink); }\n.#{$fa-css-prefix}-unlock:before { content: fa-content($fa-var-unlock); }\n.#{$fa-css-prefix}-unlock-alt:before { content: fa-content($fa-var-unlock-alt); }\n.#{$fa-css-prefix}-untappd:before { content: fa-content($fa-var-untappd); }\n.#{$fa-css-prefix}-upload:before { content: fa-content($fa-var-upload); }\n.#{$fa-css-prefix}-ups:before { content: fa-content($fa-var-ups); }\n.#{$fa-css-prefix}-usb:before { content: fa-content($fa-var-usb); }\n.#{$fa-css-prefix}-user:before { content: fa-content($fa-var-user); }\n.#{$fa-css-prefix}-user-alt:before { content: fa-content($fa-var-user-alt); }\n.#{$fa-css-prefix}-user-alt-slash:before { content: fa-content($fa-var-user-alt-slash); }\n.#{$fa-css-prefix}-user-astronaut:before { content: fa-content($fa-var-user-astronaut); }\n.#{$fa-css-prefix}-user-check:before { content: fa-content($fa-var-user-check); }\n.#{$fa-css-prefix}-user-circle:before { content: fa-content($fa-var-user-circle); }\n.#{$fa-css-prefix}-user-clock:before { content: fa-content($fa-var-user-clock); }\n.#{$fa-css-prefix}-user-cog:before { content: fa-content($fa-var-user-cog); }\n.#{$fa-css-prefix}-user-edit:before { content: fa-content($fa-var-user-edit); }\n.#{$fa-css-prefix}-user-friends:before { content: fa-content($fa-var-user-friends); }\n.#{$fa-css-prefix}-user-graduate:before { content: fa-content($fa-var-user-graduate); }\n.#{$fa-css-prefix}-user-injured:before { content: fa-content($fa-var-user-injured); }\n.#{$fa-css-prefix}-user-lock:before { content: fa-content($fa-var-user-lock); }\n.#{$fa-css-prefix}-user-md:before { content: fa-content($fa-var-user-md); }\n.#{$fa-css-prefix}-user-minus:before { content: fa-content($fa-var-user-minus); }\n.#{$fa-css-prefix}-user-ninja:before { content: fa-content($fa-var-user-ninja); }\n.#{$fa-css-prefix}-user-nurse:before { content: fa-content($fa-var-user-nurse); }\n.#{$fa-css-prefix}-user-plus:before { content: fa-content($fa-var-user-plus); }\n.#{$fa-css-prefix}-user-secret:before { content: fa-content($fa-var-user-secret); }\n.#{$fa-css-prefix}-user-shield:before { content: fa-content($fa-var-user-shield); }\n.#{$fa-css-prefix}-user-slash:before { content: fa-content($fa-var-user-slash); }\n.#{$fa-css-prefix}-user-tag:before { content: fa-content($fa-var-user-tag); }\n.#{$fa-css-prefix}-user-tie:before { content: fa-content($fa-var-user-tie); }\n.#{$fa-css-prefix}-user-times:before { content: fa-content($fa-var-user-times); }\n.#{$fa-css-prefix}-users:before { content: fa-content($fa-var-users); }\n.#{$fa-css-prefix}-users-cog:before { content: fa-content($fa-var-users-cog); }\n.#{$fa-css-prefix}-usps:before { content: fa-content($fa-var-usps); }\n.#{$fa-css-prefix}-ussunnah:before { content: fa-content($fa-var-ussunnah); }\n.#{$fa-css-prefix}-utensil-spoon:before { content: fa-content($fa-var-utensil-spoon); }\n.#{$fa-css-prefix}-utensils:before { content: fa-content($fa-var-utensils); }\n.#{$fa-css-prefix}-vaadin:before { content: fa-content($fa-var-vaadin); }\n.#{$fa-css-prefix}-vector-square:before { content: fa-content($fa-var-vector-square); }\n.#{$fa-css-prefix}-venus:before { content: fa-content($fa-var-venus); }\n.#{$fa-css-prefix}-venus-double:before { content: fa-content($fa-var-venus-double); }\n.#{$fa-css-prefix}-venus-mars:before { content: fa-content($fa-var-venus-mars); }\n.#{$fa-css-prefix}-viacoin:before { content: fa-content($fa-var-viacoin); }\n.#{$fa-css-prefix}-viadeo:before { content: fa-content($fa-var-viadeo); }\n.#{$fa-css-prefix}-viadeo-square:before { content: fa-content($fa-var-viadeo-square); }\n.#{$fa-css-prefix}-vial:before { content: fa-content($fa-var-vial); }\n.#{$fa-css-prefix}-vials:before { content: fa-content($fa-var-vials); }\n.#{$fa-css-prefix}-viber:before { content: fa-content($fa-var-viber); }\n.#{$fa-css-prefix}-video:before { content: fa-content($fa-var-video); }\n.#{$fa-css-prefix}-video-slash:before { content: fa-content($fa-var-video-slash); }\n.#{$fa-css-prefix}-vihara:before { content: fa-content($fa-var-vihara); }\n.#{$fa-css-prefix}-vimeo:before { content: fa-content($fa-var-vimeo); }\n.#{$fa-css-prefix}-vimeo-square:before { content: fa-content($fa-var-vimeo-square); }\n.#{$fa-css-prefix}-vimeo-v:before { content: fa-content($fa-var-vimeo-v); }\n.#{$fa-css-prefix}-vine:before { content: fa-content($fa-var-vine); }\n.#{$fa-css-prefix}-vk:before { content: fa-content($fa-var-vk); }\n.#{$fa-css-prefix}-vnv:before { content: fa-content($fa-var-vnv); }\n.#{$fa-css-prefix}-voicemail:before { content: fa-content($fa-var-voicemail); }\n.#{$fa-css-prefix}-volleyball-ball:before { content: fa-content($fa-var-volleyball-ball); }\n.#{$fa-css-prefix}-volume-down:before { content: fa-content($fa-var-volume-down); }\n.#{$fa-css-prefix}-volume-mute:before { content: fa-content($fa-var-volume-mute); }\n.#{$fa-css-prefix}-volume-off:before { content: fa-content($fa-var-volume-off); }\n.#{$fa-css-prefix}-volume-up:before { content: fa-content($fa-var-volume-up); }\n.#{$fa-css-prefix}-vote-yea:before { content: fa-content($fa-var-vote-yea); }\n.#{$fa-css-prefix}-vr-cardboard:before { content: fa-content($fa-var-vr-cardboard); }\n.#{$fa-css-prefix}-vuejs:before { content: fa-content($fa-var-vuejs); }\n.#{$fa-css-prefix}-walking:before { content: fa-content($fa-var-walking); }\n.#{$fa-css-prefix}-wallet:before { content: fa-content($fa-var-wallet); }\n.#{$fa-css-prefix}-warehouse:before { content: fa-content($fa-var-warehouse); }\n.#{$fa-css-prefix}-water:before { content: fa-content($fa-var-water); }\n.#{$fa-css-prefix}-wave-square:before { content: fa-content($fa-var-wave-square); }\n.#{$fa-css-prefix}-waze:before { content: fa-content($fa-var-waze); }\n.#{$fa-css-prefix}-weebly:before { content: fa-content($fa-var-weebly); }\n.#{$fa-css-prefix}-weibo:before { content: fa-content($fa-var-weibo); }\n.#{$fa-css-prefix}-weight:before { content: fa-content($fa-var-weight); }\n.#{$fa-css-prefix}-weight-hanging:before { content: fa-content($fa-var-weight-hanging); }\n.#{$fa-css-prefix}-weixin:before { content: fa-content($fa-var-weixin); }\n.#{$fa-css-prefix}-whatsapp:before { content: fa-content($fa-var-whatsapp); }\n.#{$fa-css-prefix}-whatsapp-square:before { content: fa-content($fa-var-whatsapp-square); }\n.#{$fa-css-prefix}-wheelchair:before { content: fa-content($fa-var-wheelchair); }\n.#{$fa-css-prefix}-whmcs:before { content: fa-content($fa-var-whmcs); }\n.#{$fa-css-prefix}-wifi:before { content: fa-content($fa-var-wifi); }\n.#{$fa-css-prefix}-wikipedia-w:before { content: fa-content($fa-var-wikipedia-w); }\n.#{$fa-css-prefix}-wind:before { content: fa-content($fa-var-wind); }\n.#{$fa-css-prefix}-window-close:before { content: fa-content($fa-var-window-close); }\n.#{$fa-css-prefix}-window-maximize:before { content: fa-content($fa-var-window-maximize); }\n.#{$fa-css-prefix}-window-minimize:before { content: fa-content($fa-var-window-minimize); }\n.#{$fa-css-prefix}-window-restore:before { content: fa-content($fa-var-window-restore); }\n.#{$fa-css-prefix}-windows:before { content: fa-content($fa-var-windows); }\n.#{$fa-css-prefix}-wine-bottle:before { content: fa-content($fa-var-wine-bottle); }\n.#{$fa-css-prefix}-wine-glass:before { content: fa-content($fa-var-wine-glass); }\n.#{$fa-css-prefix}-wine-glass-alt:before { content: fa-content($fa-var-wine-glass-alt); }\n.#{$fa-css-prefix}-wix:before { content: fa-content($fa-var-wix); }\n.#{$fa-css-prefix}-wizards-of-the-coast:before { content: fa-content($fa-var-wizards-of-the-coast); }\n.#{$fa-css-prefix}-wolf-pack-battalion:before { content: fa-content($fa-var-wolf-pack-battalion); }\n.#{$fa-css-prefix}-won-sign:before { content: fa-content($fa-var-won-sign); }\n.#{$fa-css-prefix}-wordpress:before { content: fa-content($fa-var-wordpress); }\n.#{$fa-css-prefix}-wordpress-simple:before { content: fa-content($fa-var-wordpress-simple); }\n.#{$fa-css-prefix}-wpbeginner:before { content: fa-content($fa-var-wpbeginner); }\n.#{$fa-css-prefix}-wpexplorer:before { content: fa-content($fa-var-wpexplorer); }\n.#{$fa-css-prefix}-wpforms:before { content: fa-content($fa-var-wpforms); }\n.#{$fa-css-prefix}-wpressr:before { content: fa-content($fa-var-wpressr); }\n.#{$fa-css-prefix}-wrench:before { content: fa-content($fa-var-wrench); }\n.#{$fa-css-prefix}-x-ray:before { content: fa-content($fa-var-x-ray); }\n.#{$fa-css-prefix}-xbox:before { content: fa-content($fa-var-xbox); }\n.#{$fa-css-prefix}-xing:before { content: fa-content($fa-var-xing); }\n.#{$fa-css-prefix}-xing-square:before { content: fa-content($fa-var-xing-square); }\n.#{$fa-css-prefix}-y-combinator:before { content: fa-content($fa-var-y-combinator); }\n.#{$fa-css-prefix}-yahoo:before { content: fa-content($fa-var-yahoo); }\n.#{$fa-css-prefix}-yammer:before { content: fa-content($fa-var-yammer); }\n.#{$fa-css-prefix}-yandex:before { content: fa-content($fa-var-yandex); }\n.#{$fa-css-prefix}-yandex-international:before { content: fa-content($fa-var-yandex-international); }\n.#{$fa-css-prefix}-yarn:before { content: fa-content($fa-var-yarn); }\n.#{$fa-css-prefix}-yelp:before { content: fa-content($fa-var-yelp); }\n.#{$fa-css-prefix}-yen-sign:before { content: fa-content($fa-var-yen-sign); }\n.#{$fa-css-prefix}-yin-yang:before { content: fa-content($fa-var-yin-yang); }\n.#{$fa-css-prefix}-yoast:before { content: fa-content($fa-var-yoast); }\n.#{$fa-css-prefix}-youtube:before { content: fa-content($fa-var-youtube); }\n.#{$fa-css-prefix}-youtube-square:before { content: fa-content($fa-var-youtube-square); }\n.#{$fa-css-prefix}-zhihu:before { content: fa-content($fa-var-zhihu); }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_larger.scss",
    "content": "// Icon Sizes\n// -------------------------\n\n// makes the font 33% larger relative to the icon container\n.#{$fa-css-prefix}-lg {\n  font-size: (4em / 3);\n  line-height: (3em / 4);\n  vertical-align: -.0667em;\n}\n\n.#{$fa-css-prefix}-xs {\n  font-size: .75em;\n}\n\n.#{$fa-css-prefix}-sm {\n  font-size: .875em;\n}\n\n@for $i from 1 through 10 {\n  .#{$fa-css-prefix}-#{$i}x {\n    font-size: $i * 1em;\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_list.scss",
    "content": "// List Icons\n// -------------------------\n\n.#{$fa-css-prefix}-ul {\n  list-style-type: none;\n  margin-left: $fa-li-width * 5/4;\n  padding-left: 0;\n\n  > li { position: relative; }\n}\n\n.#{$fa-css-prefix}-li {\n  left: -$fa-li-width;\n  position: absolute;\n  text-align: center;\n  width: $fa-li-width;\n  line-height: inherit;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_mixins.scss",
    "content": "// Mixins\n// --------------------------\n\n@mixin fa-icon {\n  -webkit-font-smoothing: antialiased;\n  -moz-osx-font-smoothing: grayscale;\n  display: inline-block;\n  font-style: normal;\n  font-variant: normal;\n  font-weight: normal;\n  line-height: 1;\n}\n\n@mixin fa-icon-rotate($degrees, $rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=#{$rotation})\";\n  transform: rotate($degrees);\n}\n\n@mixin fa-icon-flip($horiz, $vert, $rotation) {\n  -ms-filter: \"progid:DXImageTransform.Microsoft.BasicImage(rotation=#{$rotation}, mirror=1)\";\n  transform: scale($horiz, $vert);\n}\n\n\n// Only display content to screen readers. A la Bootstrap 4.\n//\n// See: http://a11yproject.com/posts/how-to-hide-content/\n\n@mixin sr-only {\n  border: 0;\n  clip: rect(0, 0, 0, 0);\n  height: 1px;\n  margin: -1px;\n  overflow: hidden;\n  padding: 0;\n  position: absolute;\n  width: 1px;\n}\n\n// Use in conjunction with .sr-only to only display content when it's focused.\n//\n// Useful for \"Skip to main content\" links; see http://www.w3.org/TR/2013/NOTE-WCAG20-TECHS-20130905/G1\n//\n// Credit: HTML5 Boilerplate\n\n@mixin sr-only-focusable {\n  &:active,\n  &:focus {\n    clip: auto;\n    height: auto;\n    margin: 0;\n    overflow: visible;\n    position: static;\n    width: auto;\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_rotated-flipped.scss",
    "content": "// Rotated & Flipped Icons\n// -------------------------\n\n.#{$fa-css-prefix}-rotate-90  { @include fa-icon-rotate(90deg, 1);  }\n.#{$fa-css-prefix}-rotate-180 { @include fa-icon-rotate(180deg, 2); }\n.#{$fa-css-prefix}-rotate-270 { @include fa-icon-rotate(270deg, 3); }\n\n.#{$fa-css-prefix}-flip-horizontal { @include fa-icon-flip(-1, 1, 0); }\n.#{$fa-css-prefix}-flip-vertical   { @include fa-icon-flip(1, -1, 2); }\n.#{$fa-css-prefix}-flip-both, .#{$fa-css-prefix}-flip-horizontal.#{$fa-css-prefix}-flip-vertical { @include fa-icon-flip(-1, -1, 2); }\n\n// Hook for IE8-9\n// -------------------------\n\n:root {\n  .#{$fa-css-prefix}-rotate-90,\n  .#{$fa-css-prefix}-rotate-180,\n  .#{$fa-css-prefix}-rotate-270,\n  .#{$fa-css-prefix}-flip-horizontal,\n  .#{$fa-css-prefix}-flip-vertical,\n  .#{$fa-css-prefix}-flip-both {\n    filter: none;\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_screen-reader.scss",
    "content": "// Screen Readers\n// -------------------------\n\n.sr-only { @include sr-only; }\n.sr-only-focusable { @include sr-only-focusable; }\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_shims.scss",
    "content": ".#{$fa-css-prefix}.#{$fa-css-prefix}-glass:before { content: fa-content($fa-var-glass-martini); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meetup {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-o:before { content: fa-content($fa-var-star); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-remove:before { content: fa-content($fa-var-times); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-close:before { content: fa-content($fa-var-times); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gear:before { content: fa-content($fa-var-cog); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trash-o:before { content: fa-content($fa-var-trash-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-o:before { content: fa-content($fa-var-file); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clock-o:before { content: fa-content($fa-var-clock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-down:before { content: fa-content($fa-var-arrow-alt-circle-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-up:before { content: fa-content($fa-var-arrow-alt-circle-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-play-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-play-circle-o:before { content: fa-content($fa-var-play-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-repeat:before { content: fa-content($fa-var-redo); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rotate-right:before { content: fa-content($fa-var-redo); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-refresh:before { content: fa-content($fa-var-sync); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-list-alt {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dedent:before { content: fa-content($fa-var-outdent); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-video-camera:before { content: fa-content($fa-var-video); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-picture-o:before { content: fa-content($fa-var-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-photo {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-photo:before { content: fa-content($fa-var-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-image {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-image:before { content: fa-content($fa-var-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil:before { content: fa-content($fa-var-pencil-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-map-marker:before { content: fa-content($fa-var-map-marker-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil-square-o:before { content: fa-content($fa-var-edit); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-share-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-share-square-o:before { content: fa-content($fa-var-share-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-square-o:before { content: fa-content($fa-var-check-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows:before { content: fa-content($fa-var-arrows-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-circle-o:before { content: fa-content($fa-var-times-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-check-circle-o:before { content: fa-content($fa-var-check-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mail-forward:before { content: fa-content($fa-var-share); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eye {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eye-slash {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-warning:before { content: fa-content($fa-var-exclamation-triangle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar:before { content: fa-content($fa-var-calendar-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows-v:before { content: fa-content($fa-var-arrows-alt-v); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows-h:before { content: fa-content($fa-var-arrows-alt-h); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart:before { content: fa-content($fa-var-chart-bar); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bar-chart-o:before { content: fa-content($fa-var-chart-bar); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-twitter-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gears:before { content: fa-content($fa-var-cogs); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-up:before { content: fa-content($fa-var-thumbs-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumbs-o-down:before { content: fa-content($fa-var-thumbs-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-heart-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-heart-o:before { content: fa-content($fa-var-heart); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sign-out:before { content: fa-content($fa-var-sign-out-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin-square:before { content: fa-content($fa-var-linkedin); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thumb-tack:before { content: fa-content($fa-var-thumbtack); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-external-link:before { content: fa-content($fa-var-external-link-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sign-in:before { content: fa-content($fa-var-sign-in-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-github-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lemon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lemon-o:before { content: fa-content($fa-var-lemon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-square-o:before { content: fa-content($fa-var-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bookmark-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bookmark-o:before { content: fa-content($fa-var-bookmark); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-twitter {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook:before { content: fa-content($fa-var-facebook-f); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-f {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-f:before { content: fa-content($fa-var-facebook-f); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-github {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-credit-card {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-feed:before { content: fa-content($fa-var-rss); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hdd-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hdd-o:before { content: fa-content($fa-var-hdd); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-right:before { content: fa-content($fa-var-hand-point-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-left:before { content: fa-content($fa-var-hand-point-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-up:before { content: fa-content($fa-var-hand-point-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-o-down:before { content: fa-content($fa-var-hand-point-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrows-alt:before { content: fa-content($fa-var-expand-arrows-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-group:before { content: fa-content($fa-var-users); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-chain:before { content: fa-content($fa-var-link); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-scissors:before { content: fa-content($fa-var-cut); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-files-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-files-o:before { content: fa-content($fa-var-copy); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-floppy-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-floppy-o:before { content: fa-content($fa-var-save); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-navicon:before { content: fa-content($fa-var-bars); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reorder:before { content: fa-content($fa-var-bars); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pinterest {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pinterest-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus:before { content: fa-content($fa-var-google-plus-g); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-money {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-money:before { content: fa-content($fa-var-money-bill-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-unsorted:before { content: fa-content($fa-var-sort); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-desc:before { content: fa-content($fa-var-sort-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-asc:before { content: fa-content($fa-var-sort-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linkedin:before { content: fa-content($fa-var-linkedin-in); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rotate-left:before { content: fa-content($fa-var-undo); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-legal:before { content: fa-content($fa-var-gavel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tachometer:before { content: fa-content($fa-var-tachometer-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dashboard:before { content: fa-content($fa-var-tachometer-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comment-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comment-o:before { content: fa-content($fa-var-comment); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comments-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-comments-o:before { content: fa-content($fa-var-comments); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flash:before { content: fa-content($fa-var-bolt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clipboard {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paste {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paste:before { content: fa-content($fa-var-clipboard); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lightbulb-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lightbulb-o:before { content: fa-content($fa-var-lightbulb); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-exchange:before { content: fa-content($fa-var-exchange-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cloud-download:before { content: fa-content($fa-var-cloud-download-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cloud-upload:before { content: fa-content($fa-var-cloud-upload-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-o:before { content: fa-content($fa-var-bell); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cutlery:before { content: fa-content($fa-var-utensils); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-text-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-text-o:before { content: fa-content($fa-var-file-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-building-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-building-o:before { content: fa-content($fa-var-building); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hospital-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hospital-o:before { content: fa-content($fa-var-hospital); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tablet:before { content: fa-content($fa-var-tablet-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mobile:before { content: fa-content($fa-var-mobile-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mobile-phone:before { content: fa-content($fa-var-mobile-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-o:before { content: fa-content($fa-var-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mail-reply:before { content: fa-content($fa-var-reply); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-github-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-o:before { content: fa-content($fa-var-folder); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-folder-open-o:before { content: fa-content($fa-var-folder-open); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-smile-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-smile-o:before { content: fa-content($fa-var-smile); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-frown-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-frown-o:before { content: fa-content($fa-var-frown); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meh-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meh-o:before { content: fa-content($fa-var-meh); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-keyboard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-keyboard-o:before { content: fa-content($fa-var-keyboard); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flag-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flag-o:before { content: fa-content($fa-var-flag); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mail-reply-all:before { content: fa-content($fa-var-reply-all); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-o:before { content: fa-content($fa-var-star-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-empty {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-empty:before { content: fa-content($fa-var-star-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-full {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-star-half-full:before { content: fa-content($fa-var-star-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-code-fork:before { content: fa-content($fa-var-code-branch); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-chain-broken:before { content: fa-content($fa-var-unlink); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-shield:before { content: fa-content($fa-var-shield-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-o:before { content: fa-content($fa-var-calendar); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-maxcdn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-html5 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-css3 {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ticket:before { content: fa-content($fa-var-ticket-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-minus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-minus-square-o:before { content: fa-content($fa-var-minus-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-level-up:before { content: fa-content($fa-var-level-up-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-level-down:before { content: fa-content($fa-var-level-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pencil-square:before { content: fa-content($fa-var-pen-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-external-link-square:before { content: fa-content($fa-var-external-link-square-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-compass {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-down:before { content: fa-content($fa-var-caret-square-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-down {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-down:before { content: fa-content($fa-var-caret-square-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-up:before { content: fa-content($fa-var-caret-square-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-up {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-up:before { content: fa-content($fa-var-caret-square-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-right:before { content: fa-content($fa-var-caret-square-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-right:before { content: fa-content($fa-var-caret-square-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eur:before { content: fa-content($fa-var-euro-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-euro:before { content: fa-content($fa-var-euro-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gbp:before { content: fa-content($fa-var-pound-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-usd:before { content: fa-content($fa-var-dollar-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dollar:before { content: fa-content($fa-var-dollar-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-inr:before { content: fa-content($fa-var-rupee-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rupee:before { content: fa-content($fa-var-rupee-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-jpy:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cny:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rmb:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yen:before { content: fa-content($fa-var-yen-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rub:before { content: fa-content($fa-var-ruble-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ruble:before { content: fa-content($fa-var-ruble-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rouble:before { content: fa-content($fa-var-ruble-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-krw:before { content: fa-content($fa-var-won-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-won:before { content: fa-content($fa-var-won-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-btc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitcoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitcoin:before { content: fa-content($fa-var-btc); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-text:before { content: fa-content($fa-var-file-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-alpha-asc:before { content: fa-content($fa-var-sort-alpha-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-alpha-desc:before { content: fa-content($fa-var-sort-alpha-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-amount-asc:before { content: fa-content($fa-var-sort-amount-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-amount-desc:before { content: fa-content($fa-var-sort-amount-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-numeric-asc:before { content: fa-content($fa-var-sort-numeric-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sort-numeric-desc:before { content: fa-content($fa-var-sort-numeric-down-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-xing {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-xing-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube-play {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-youtube-play:before { content: fa-content($fa-var-youtube); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dropbox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stack-overflow {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-instagram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-flickr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-adn {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitbucket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitbucket-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bitbucket-square:before { content: fa-content($fa-var-bitbucket); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tumblr {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tumblr-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-down:before { content: fa-content($fa-var-long-arrow-alt-down); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-up:before { content: fa-content($fa-var-long-arrow-alt-up); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-left:before { content: fa-content($fa-var-long-arrow-alt-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-long-arrow-right:before { content: fa-content($fa-var-long-arrow-alt-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-apple {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-windows {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-android {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linux {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dribbble {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-skype {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-foursquare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trello {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gratipay {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gittip {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gittip:before { content: fa-content($fa-var-gratipay); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sun-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sun-o:before { content: fa-content($fa-var-sun); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-moon-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-moon-o:before { content: fa-content($fa-var-moon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-renren {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pagelines {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stack-exchange {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-right {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-right:before { content: fa-content($fa-var-arrow-alt-circle-right); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-arrow-circle-o-left:before { content: fa-content($fa-var-arrow-alt-circle-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-caret-square-o-left:before { content: fa-content($fa-var-caret-square-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-left {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-toggle-left:before { content: fa-content($fa-var-caret-square-left); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dot-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dot-circle-o:before { content: fa-content($fa-var-dot-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vimeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-try:before { content: fa-content($fa-var-lira-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-turkish-lira:before { content: fa-content($fa-var-lira-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-plus-square-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-plus-square-o:before { content: fa-content($fa-var-plus-square); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-slack {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wordpress {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-openid {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-institution:before { content: fa-content($fa-var-university); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bank:before { content: fa-content($fa-var-university); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mortar-board:before { content: fa-content($fa-var-graduation-cap); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yahoo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reddit {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reddit-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stumbleupon-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stumbleupon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-delicious {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-digg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pied-piper-pp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pied-piper-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drupal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-joomla {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-spoon:before { content: fa-content($fa-var-utensil-spoon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-behance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-behance-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-steam {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-steam-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-automobile:before { content: fa-content($fa-var-car); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cab:before { content: fa-content($fa-var-taxi); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-o:before { content: fa-content($fa-var-envelope); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-deviantart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-soundcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-pdf-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-pdf-o:before { content: fa-content($fa-var-file-pdf); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-word-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-word-o:before { content: fa-content($fa-var-file-word); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-excel-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-excel-o:before { content: fa-content($fa-var-file-excel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-powerpoint-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-powerpoint-o:before { content: fa-content($fa-var-file-powerpoint); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-image-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-image-o:before { content: fa-content($fa-var-file-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-photo-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-photo-o:before { content: fa-content($fa-var-file-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-picture-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-picture-o:before { content: fa-content($fa-var-file-image); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-archive-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-archive-o:before { content: fa-content($fa-var-file-archive); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-zip-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-zip-o:before { content: fa-content($fa-var-file-archive); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-audio-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-audio-o:before { content: fa-content($fa-var-file-audio); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-sound-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-sound-o:before { content: fa-content($fa-var-file-audio); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-video-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-video-o:before { content: fa-content($fa-var-file-video); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-movie-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-movie-o:before { content: fa-content($fa-var-file-video); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-code-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-file-code-o:before { content: fa-content($fa-var-file-code); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vine {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-codepen {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-jsfiddle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-ring {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-bouy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-bouy:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-buoy {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-buoy:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-saver {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-life-saver:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-support {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-support:before { content: fa-content($fa-var-life-ring); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-o-notch:before { content: fa-content($fa-var-circle-notch); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-rebel {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ra {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ra:before { content: fa-content($fa-var-rebel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-resistance {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-resistance:before { content: fa-content($fa-var-rebel); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-empire {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ge:before { content: fa-content($fa-var-empire); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-git-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-git {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hacker-news {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-y-combinator-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-y-combinator-square:before { content: fa-content($fa-var-hacker-news); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc-square:before { content: fa-content($fa-var-hacker-news); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tencent-weibo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-qq {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-weixin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wechat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wechat:before { content: fa-content($fa-var-weixin); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-send:before { content: fa-content($fa-var-paper-plane); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paper-plane-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paper-plane-o:before { content: fa-content($fa-var-paper-plane); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-send-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-send-o:before { content: fa-content($fa-var-paper-plane); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-thin {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-circle-thin:before { content: fa-content($fa-var-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-header:before { content: fa-content($fa-var-heading); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sliders:before { content: fa-content($fa-var-sliders-h); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-futbol-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-futbol-o:before { content: fa-content($fa-var-futbol); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-soccer-ball-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-soccer-ball-o:before { content: fa-content($fa-var-futbol); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-slideshare {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-twitch {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yelp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-newspaper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-newspaper-o:before { content: fa-content($fa-var-newspaper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-wallet {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-visa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-mastercard {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-discover {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-amex {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-paypal {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-stripe {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-slash-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bell-slash-o:before { content: fa-content($fa-var-bell-slash); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-trash:before { content: fa-content($fa-var-trash-alt); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-copyright {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eyedropper:before { content: fa-content($fa-var-eye-dropper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-area-chart:before { content: fa-content($fa-var-chart-area); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pie-chart:before { content: fa-content($fa-var-chart-pie); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-line-chart:before { content: fa-content($fa-var-chart-line); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lastfm {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-lastfm-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ioxhost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-angellist {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc:before { content: fa-content($fa-var-closed-captioning); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ils:before { content: fa-content($fa-var-shekel-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-shekel:before { content: fa-content($fa-var-shekel-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sheqel:before { content: fa-content($fa-var-shekel-sign); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meanpath {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-meanpath:before { content: fa-content($fa-var-font-awesome); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-buysellads {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-connectdevelop {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-dashcube {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-forumbee {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-leanpub {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sellsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-shirtsinbulk {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-simplybuilt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-skyatlas {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-diamond {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-diamond:before { content: fa-content($fa-var-gem); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-intersex:before { content: fa-content($fa-var-transgender); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-facebook-official:before { content: fa-content($fa-var-facebook); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pinterest-p {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-whatsapp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hotel:before { content: fa-content($fa-var-bed); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-viacoin {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-medium {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-y-combinator {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yc:before { content: fa-content($fa-var-y-combinator); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-optin-monster {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-opencart {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-expeditedssl {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-4:before { content: fa-content($fa-var-battery-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery:before { content: fa-content($fa-var-battery-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-3:before { content: fa-content($fa-var-battery-three-quarters); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-2:before { content: fa-content($fa-var-battery-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-1:before { content: fa-content($fa-var-battery-quarter); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-battery-0:before { content: fa-content($fa-var-battery-empty); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-object-group {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-object-ungroup {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sticky-note-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-sticky-note-o:before { content: fa-content($fa-var-sticky-note); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-jcb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-cc-diners-club {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-clone {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-o:before { content: fa-content($fa-var-hourglass); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-1:before { content: fa-content($fa-var-hourglass-start); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-2:before { content: fa-content($fa-var-hourglass-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hourglass-3:before { content: fa-content($fa-var-hourglass-end); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-rock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-rock-o:before { content: fa-content($fa-var-hand-rock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-grab-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-grab-o:before { content: fa-content($fa-var-hand-rock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-paper-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-paper-o:before { content: fa-content($fa-var-hand-paper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-stop-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-stop-o:before { content: fa-content($fa-var-hand-paper); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-scissors-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-scissors-o:before { content: fa-content($fa-var-hand-scissors); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-lizard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-lizard-o:before { content: fa-content($fa-var-hand-lizard); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-spock-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-spock-o:before { content: fa-content($fa-var-hand-spock); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-pointer-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-pointer-o:before { content: fa-content($fa-var-hand-pointer); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-peace-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hand-peace-o:before { content: fa-content($fa-var-hand-peace); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-registered {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-creative-commons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gg {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gg-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-tripadvisor {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-odnoklassniki {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-odnoklassniki-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-get-pocket {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wikipedia-w {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-safari {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-chrome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-firefox {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-opera {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-internet-explorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-television:before { content: fa-content($fa-var-tv); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-contao {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-500px {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-amazon {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-plus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-plus-o:before { content: fa-content($fa-var-calendar-plus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-minus-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-minus-o:before { content: fa-content($fa-var-calendar-minus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-times-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-times-o:before { content: fa-content($fa-var-calendar-times); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-check-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-calendar-check-o:before { content: fa-content($fa-var-calendar-check); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-map-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-map-o:before { content: fa-content($fa-var-map); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-commenting:before { content: fa-content($fa-var-comment-dots); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-commenting-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-commenting-o:before { content: fa-content($fa-var-comment-dots); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-houzz {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vimeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vimeo:before { content: fa-content($fa-var-vimeo-v); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-black-tie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fonticons {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-reddit-alien {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-edge {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-credit-card-alt:before { content: fa-content($fa-var-credit-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-codiepie {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-modx {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fort-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-usb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-product-hunt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-mixcloud {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-scribd {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pause-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pause-circle-o:before { content: fa-content($fa-var-pause-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stop-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-stop-circle-o:before { content: fa-content($fa-var-stop-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bluetooth {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bluetooth-b {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-gitlab {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wpbeginner {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wpforms {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envira {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wheelchair-alt {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wheelchair-alt:before { content: fa-content($fa-var-accessible-icon); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-question-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-question-circle-o:before { content: fa-content($fa-var-question-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-volume-control-phone:before { content: fa-content($fa-var-phone-volume); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-asl-interpreting:before { content: fa-content($fa-var-american-sign-language-interpreting); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-deafness:before { content: fa-content($fa-var-deaf); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-hard-of-hearing:before { content: fa-content($fa-var-deaf); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-glide {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-glide-g {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-signing:before { content: fa-content($fa-var-sign-language); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-viadeo {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-viadeo-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snapchat {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snapchat-ghost {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snapchat-square {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-pied-piper {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-first-order {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-yoast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-themeisle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-official {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-official:before { content: fa-content($fa-var-google-plus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-circle {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-google-plus-circle:before { content: fa-content($fa-var-google-plus); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-font-awesome {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fa {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-fa:before { content: fa-content($fa-var-font-awesome); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-handshake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-handshake-o:before { content: fa-content($fa-var-handshake); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-open-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-envelope-open-o:before { content: fa-content($fa-var-envelope-open); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-linode {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-book-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-book-o:before { content: fa-content($fa-var-address-book); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vcard:before { content: fa-content($fa-var-address-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-address-card-o:before { content: fa-content($fa-var-address-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vcard-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-vcard-o:before { content: fa-content($fa-var-address-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-circle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-circle-o:before { content: fa-content($fa-var-user-circle); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-user-o:before { content: fa-content($fa-var-user); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-id-badge {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drivers-license:before { content: fa-content($fa-var-id-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-id-card-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-id-card-o:before { content: fa-content($fa-var-id-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drivers-license-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-drivers-license-o:before { content: fa-content($fa-var-id-card); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-quora {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-free-code-camp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-telegram {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-4:before { content: fa-content($fa-var-thermometer-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer:before { content: fa-content($fa-var-thermometer-full); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-3:before { content: fa-content($fa-var-thermometer-three-quarters); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-2:before { content: fa-content($fa-var-thermometer-half); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-1:before { content: fa-content($fa-var-thermometer-quarter); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-thermometer-0:before { content: fa-content($fa-var-thermometer-empty); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bathtub:before { content: fa-content($fa-var-bath); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-s15:before { content: fa-content($fa-var-bath); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-maximize {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-restore {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-rectangle:before { content: fa-content($fa-var-window-close); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-close-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-window-close-o:before { content: fa-content($fa-var-window-close); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-rectangle-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-times-rectangle-o:before { content: fa-content($fa-var-window-close); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-bandcamp {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-grav {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-etsy {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-imdb {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-ravelry {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eercast {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-eercast:before { content: fa-content($fa-var-sellcast); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snowflake-o {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n.#{$fa-css-prefix}.#{$fa-css-prefix}-snowflake-o:before { content: fa-content($fa-var-snowflake); }\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-superpowers {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-wpexplorer {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n.#{$fa-css-prefix}.#{$fa-css-prefix}-spotify {\n  font-family: 'Font Awesome 5 Brands';\n  font-weight: 400;\n}\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_stacked.scss",
    "content": "// Stacked Icons\n// -------------------------\n\n.#{$fa-css-prefix}-stack {\n  display: inline-block;\n  height: 2em;\n  line-height: 2em;\n  position: relative;\n  vertical-align: middle;\n  width: ($fa-fw-width*2);\n}\n\n.#{$fa-css-prefix}-stack-1x,\n.#{$fa-css-prefix}-stack-2x {\n  left: 0;\n  position: absolute;\n  text-align: center;\n  width: 100%;\n}\n\n.#{$fa-css-prefix}-stack-1x {\n  line-height: inherit;\n}\n\n.#{$fa-css-prefix}-stack-2x {\n  font-size: 2em;\n}\n\n.#{$fa-css-prefix}-inverse {\n  color: $fa-inverse;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/_variables.scss",
    "content": "// Variables\n// --------------------------\n\n$fa-font-path:         \"../webfonts\" !default;\n$fa-font-size-base:    16px !default;\n$fa-font-display:      auto !default;\n$fa-css-prefix:        fa !default;\n$fa-version:           \"5.10.2\" !default;\n$fa-border-color:      #eee !default;\n$fa-inverse:           #fff !default;\n$fa-li-width:          2em !default;\n$fa-fw-width:          (20em / 16);\n$fa-primary-opacity:   1 !default;\n$fa-secondary-opacity: .4 !default;\n\n// Convenience function used to set content property\n@function fa-content($fa-var) {\n  @return unquote(\"\\\"#{ $fa-var }\\\"\");\n}\n\n$fa-var-500px: \\f26e;\n$fa-var-accessible-icon: \\f368;\n$fa-var-accusoft: \\f369;\n$fa-var-acquisitions-incorporated: \\f6af;\n$fa-var-ad: \\f641;\n$fa-var-address-book: \\f2b9;\n$fa-var-address-card: \\f2bb;\n$fa-var-adjust: \\f042;\n$fa-var-adn: \\f170;\n$fa-var-adobe: \\f778;\n$fa-var-adversal: \\f36a;\n$fa-var-affiliatetheme: \\f36b;\n$fa-var-air-freshener: \\f5d0;\n$fa-var-airbnb: \\f834;\n$fa-var-algolia: \\f36c;\n$fa-var-align-center: \\f037;\n$fa-var-align-justify: \\f039;\n$fa-var-align-left: \\f036;\n$fa-var-align-right: \\f038;\n$fa-var-alipay: \\f642;\n$fa-var-allergies: \\f461;\n$fa-var-amazon: \\f270;\n$fa-var-amazon-pay: \\f42c;\n$fa-var-ambulance: \\f0f9;\n$fa-var-american-sign-language-interpreting: \\f2a3;\n$fa-var-amilia: \\f36d;\n$fa-var-anchor: \\f13d;\n$fa-var-android: \\f17b;\n$fa-var-angellist: \\f209;\n$fa-var-angle-double-down: \\f103;\n$fa-var-angle-double-left: \\f100;\n$fa-var-angle-double-right: \\f101;\n$fa-var-angle-double-up: \\f102;\n$fa-var-angle-down: \\f107;\n$fa-var-angle-left: \\f104;\n$fa-var-angle-right: \\f105;\n$fa-var-angle-up: \\f106;\n$fa-var-angry: \\f556;\n$fa-var-angrycreative: \\f36e;\n$fa-var-angular: \\f420;\n$fa-var-ankh: \\f644;\n$fa-var-app-store: \\f36f;\n$fa-var-app-store-ios: \\f370;\n$fa-var-apper: \\f371;\n$fa-var-apple: \\f179;\n$fa-var-apple-alt: \\f5d1;\n$fa-var-apple-pay: \\f415;\n$fa-var-archive: \\f187;\n$fa-var-archway: \\f557;\n$fa-var-arrow-alt-circle-down: \\f358;\n$fa-var-arrow-alt-circle-left: \\f359;\n$fa-var-arrow-alt-circle-right: \\f35a;\n$fa-var-arrow-alt-circle-up: \\f35b;\n$fa-var-arrow-circle-down: \\f0ab;\n$fa-var-arrow-circle-left: \\f0a8;\n$fa-var-arrow-circle-right: \\f0a9;\n$fa-var-arrow-circle-up: \\f0aa;\n$fa-var-arrow-down: \\f063;\n$fa-var-arrow-left: \\f060;\n$fa-var-arrow-right: \\f061;\n$fa-var-arrow-up: \\f062;\n$fa-var-arrows-alt: \\f0b2;\n$fa-var-arrows-alt-h: \\f337;\n$fa-var-arrows-alt-v: \\f338;\n$fa-var-artstation: \\f77a;\n$fa-var-assistive-listening-systems: \\f2a2;\n$fa-var-asterisk: \\f069;\n$fa-var-asymmetrik: \\f372;\n$fa-var-at: \\f1fa;\n$fa-var-atlas: \\f558;\n$fa-var-atlassian: \\f77b;\n$fa-var-atom: \\f5d2;\n$fa-var-audible: \\f373;\n$fa-var-audio-description: \\f29e;\n$fa-var-autoprefixer: \\f41c;\n$fa-var-avianex: \\f374;\n$fa-var-aviato: \\f421;\n$fa-var-award: \\f559;\n$fa-var-aws: \\f375;\n$fa-var-baby: \\f77c;\n$fa-var-baby-carriage: \\f77d;\n$fa-var-backspace: \\f55a;\n$fa-var-backward: \\f04a;\n$fa-var-bacon: \\f7e5;\n$fa-var-balance-scale: \\f24e;\n$fa-var-balance-scale-left: \\f515;\n$fa-var-balance-scale-right: \\f516;\n$fa-var-ban: \\f05e;\n$fa-var-band-aid: \\f462;\n$fa-var-bandcamp: \\f2d5;\n$fa-var-barcode: \\f02a;\n$fa-var-bars: \\f0c9;\n$fa-var-baseball-ball: \\f433;\n$fa-var-basketball-ball: \\f434;\n$fa-var-bath: \\f2cd;\n$fa-var-battery-empty: \\f244;\n$fa-var-battery-full: \\f240;\n$fa-var-battery-half: \\f242;\n$fa-var-battery-quarter: \\f243;\n$fa-var-battery-three-quarters: \\f241;\n$fa-var-battle-net: \\f835;\n$fa-var-bed: \\f236;\n$fa-var-beer: \\f0fc;\n$fa-var-behance: \\f1b4;\n$fa-var-behance-square: \\f1b5;\n$fa-var-bell: \\f0f3;\n$fa-var-bell-slash: \\f1f6;\n$fa-var-bezier-curve: \\f55b;\n$fa-var-bible: \\f647;\n$fa-var-bicycle: \\f206;\n$fa-var-biking: \\f84a;\n$fa-var-bimobject: \\f378;\n$fa-var-binoculars: \\f1e5;\n$fa-var-biohazard: \\f780;\n$fa-var-birthday-cake: \\f1fd;\n$fa-var-bitbucket: \\f171;\n$fa-var-bitcoin: \\f379;\n$fa-var-bity: \\f37a;\n$fa-var-black-tie: \\f27e;\n$fa-var-blackberry: \\f37b;\n$fa-var-blender: \\f517;\n$fa-var-blender-phone: \\f6b6;\n$fa-var-blind: \\f29d;\n$fa-var-blog: \\f781;\n$fa-var-blogger: \\f37c;\n$fa-var-blogger-b: \\f37d;\n$fa-var-bluetooth: \\f293;\n$fa-var-bluetooth-b: \\f294;\n$fa-var-bold: \\f032;\n$fa-var-bolt: \\f0e7;\n$fa-var-bomb: \\f1e2;\n$fa-var-bone: \\f5d7;\n$fa-var-bong: \\f55c;\n$fa-var-book: \\f02d;\n$fa-var-book-dead: \\f6b7;\n$fa-var-book-medical: \\f7e6;\n$fa-var-book-open: \\f518;\n$fa-var-book-reader: \\f5da;\n$fa-var-bookmark: \\f02e;\n$fa-var-bootstrap: \\f836;\n$fa-var-border-all: \\f84c;\n$fa-var-border-none: \\f850;\n$fa-var-border-style: \\f853;\n$fa-var-bowling-ball: \\f436;\n$fa-var-box: \\f466;\n$fa-var-box-open: \\f49e;\n$fa-var-boxes: \\f468;\n$fa-var-braille: \\f2a1;\n$fa-var-brain: \\f5dc;\n$fa-var-bread-slice: \\f7ec;\n$fa-var-briefcase: \\f0b1;\n$fa-var-briefcase-medical: \\f469;\n$fa-var-broadcast-tower: \\f519;\n$fa-var-broom: \\f51a;\n$fa-var-brush: \\f55d;\n$fa-var-btc: \\f15a;\n$fa-var-buffer: \\f837;\n$fa-var-bug: \\f188;\n$fa-var-building: \\f1ad;\n$fa-var-bullhorn: \\f0a1;\n$fa-var-bullseye: \\f140;\n$fa-var-burn: \\f46a;\n$fa-var-buromobelexperte: \\f37f;\n$fa-var-bus: \\f207;\n$fa-var-bus-alt: \\f55e;\n$fa-var-business-time: \\f64a;\n$fa-var-buysellads: \\f20d;\n$fa-var-calculator: \\f1ec;\n$fa-var-calendar: \\f133;\n$fa-var-calendar-alt: \\f073;\n$fa-var-calendar-check: \\f274;\n$fa-var-calendar-day: \\f783;\n$fa-var-calendar-minus: \\f272;\n$fa-var-calendar-plus: \\f271;\n$fa-var-calendar-times: \\f273;\n$fa-var-calendar-week: \\f784;\n$fa-var-camera: \\f030;\n$fa-var-camera-retro: \\f083;\n$fa-var-campground: \\f6bb;\n$fa-var-canadian-maple-leaf: \\f785;\n$fa-var-candy-cane: \\f786;\n$fa-var-cannabis: \\f55f;\n$fa-var-capsules: \\f46b;\n$fa-var-car: \\f1b9;\n$fa-var-car-alt: \\f5de;\n$fa-var-car-battery: \\f5df;\n$fa-var-car-crash: \\f5e1;\n$fa-var-car-side: \\f5e4;\n$fa-var-caret-down: \\f0d7;\n$fa-var-caret-left: \\f0d9;\n$fa-var-caret-right: \\f0da;\n$fa-var-caret-square-down: \\f150;\n$fa-var-caret-square-left: \\f191;\n$fa-var-caret-square-right: \\f152;\n$fa-var-caret-square-up: \\f151;\n$fa-var-caret-up: \\f0d8;\n$fa-var-carrot: \\f787;\n$fa-var-cart-arrow-down: \\f218;\n$fa-var-cart-plus: \\f217;\n$fa-var-cash-register: \\f788;\n$fa-var-cat: \\f6be;\n$fa-var-cc-amazon-pay: \\f42d;\n$fa-var-cc-amex: \\f1f3;\n$fa-var-cc-apple-pay: \\f416;\n$fa-var-cc-diners-club: \\f24c;\n$fa-var-cc-discover: \\f1f2;\n$fa-var-cc-jcb: \\f24b;\n$fa-var-cc-mastercard: \\f1f1;\n$fa-var-cc-paypal: \\f1f4;\n$fa-var-cc-stripe: \\f1f5;\n$fa-var-cc-visa: \\f1f0;\n$fa-var-centercode: \\f380;\n$fa-var-centos: \\f789;\n$fa-var-certificate: \\f0a3;\n$fa-var-chair: \\f6c0;\n$fa-var-chalkboard: \\f51b;\n$fa-var-chalkboard-teacher: \\f51c;\n$fa-var-charging-station: \\f5e7;\n$fa-var-chart-area: \\f1fe;\n$fa-var-chart-bar: \\f080;\n$fa-var-chart-line: \\f201;\n$fa-var-chart-pie: \\f200;\n$fa-var-check: \\f00c;\n$fa-var-check-circle: \\f058;\n$fa-var-check-double: \\f560;\n$fa-var-check-square: \\f14a;\n$fa-var-cheese: \\f7ef;\n$fa-var-chess: \\f439;\n$fa-var-chess-bishop: \\f43a;\n$fa-var-chess-board: \\f43c;\n$fa-var-chess-king: \\f43f;\n$fa-var-chess-knight: \\f441;\n$fa-var-chess-pawn: \\f443;\n$fa-var-chess-queen: \\f445;\n$fa-var-chess-rook: \\f447;\n$fa-var-chevron-circle-down: \\f13a;\n$fa-var-chevron-circle-left: \\f137;\n$fa-var-chevron-circle-right: \\f138;\n$fa-var-chevron-circle-up: \\f139;\n$fa-var-chevron-down: \\f078;\n$fa-var-chevron-left: \\f053;\n$fa-var-chevron-right: \\f054;\n$fa-var-chevron-up: \\f077;\n$fa-var-child: \\f1ae;\n$fa-var-chrome: \\f268;\n$fa-var-chromecast: \\f838;\n$fa-var-church: \\f51d;\n$fa-var-circle: \\f111;\n$fa-var-circle-notch: \\f1ce;\n$fa-var-city: \\f64f;\n$fa-var-clinic-medical: \\f7f2;\n$fa-var-clipboard: \\f328;\n$fa-var-clipboard-check: \\f46c;\n$fa-var-clipboard-list: \\f46d;\n$fa-var-clock: \\f017;\n$fa-var-clone: \\f24d;\n$fa-var-closed-captioning: \\f20a;\n$fa-var-cloud: \\f0c2;\n$fa-var-cloud-download-alt: \\f381;\n$fa-var-cloud-meatball: \\f73b;\n$fa-var-cloud-moon: \\f6c3;\n$fa-var-cloud-moon-rain: \\f73c;\n$fa-var-cloud-rain: \\f73d;\n$fa-var-cloud-showers-heavy: \\f740;\n$fa-var-cloud-sun: \\f6c4;\n$fa-var-cloud-sun-rain: \\f743;\n$fa-var-cloud-upload-alt: \\f382;\n$fa-var-cloudscale: \\f383;\n$fa-var-cloudsmith: \\f384;\n$fa-var-cloudversify: \\f385;\n$fa-var-cocktail: \\f561;\n$fa-var-code: \\f121;\n$fa-var-code-branch: \\f126;\n$fa-var-codepen: \\f1cb;\n$fa-var-codiepie: \\f284;\n$fa-var-coffee: \\f0f4;\n$fa-var-cog: \\f013;\n$fa-var-cogs: \\f085;\n$fa-var-coins: \\f51e;\n$fa-var-columns: \\f0db;\n$fa-var-comment: \\f075;\n$fa-var-comment-alt: \\f27a;\n$fa-var-comment-dollar: \\f651;\n$fa-var-comment-dots: \\f4ad;\n$fa-var-comment-medical: \\f7f5;\n$fa-var-comment-slash: \\f4b3;\n$fa-var-comments: \\f086;\n$fa-var-comments-dollar: \\f653;\n$fa-var-compact-disc: \\f51f;\n$fa-var-compass: \\f14e;\n$fa-var-compress: \\f066;\n$fa-var-compress-arrows-alt: \\f78c;\n$fa-var-concierge-bell: \\f562;\n$fa-var-confluence: \\f78d;\n$fa-var-connectdevelop: \\f20e;\n$fa-var-contao: \\f26d;\n$fa-var-cookie: \\f563;\n$fa-var-cookie-bite: \\f564;\n$fa-var-copy: \\f0c5;\n$fa-var-copyright: \\f1f9;\n$fa-var-cotton-bureau: \\f89e;\n$fa-var-couch: \\f4b8;\n$fa-var-cpanel: \\f388;\n$fa-var-creative-commons: \\f25e;\n$fa-var-creative-commons-by: \\f4e7;\n$fa-var-creative-commons-nc: \\f4e8;\n$fa-var-creative-commons-nc-eu: \\f4e9;\n$fa-var-creative-commons-nc-jp: \\f4ea;\n$fa-var-creative-commons-nd: \\f4eb;\n$fa-var-creative-commons-pd: \\f4ec;\n$fa-var-creative-commons-pd-alt: \\f4ed;\n$fa-var-creative-commons-remix: \\f4ee;\n$fa-var-creative-commons-sa: \\f4ef;\n$fa-var-creative-commons-sampling: \\f4f0;\n$fa-var-creative-commons-sampling-plus: \\f4f1;\n$fa-var-creative-commons-share: \\f4f2;\n$fa-var-creative-commons-zero: \\f4f3;\n$fa-var-credit-card: \\f09d;\n$fa-var-critical-role: \\f6c9;\n$fa-var-crop: \\f125;\n$fa-var-crop-alt: \\f565;\n$fa-var-cross: \\f654;\n$fa-var-crosshairs: \\f05b;\n$fa-var-crow: \\f520;\n$fa-var-crown: \\f521;\n$fa-var-crutch: \\f7f7;\n$fa-var-css3: \\f13c;\n$fa-var-css3-alt: \\f38b;\n$fa-var-cube: \\f1b2;\n$fa-var-cubes: \\f1b3;\n$fa-var-cut: \\f0c4;\n$fa-var-cuttlefish: \\f38c;\n$fa-var-d-and-d: \\f38d;\n$fa-var-d-and-d-beyond: \\f6ca;\n$fa-var-dashcube: \\f210;\n$fa-var-database: \\f1c0;\n$fa-var-deaf: \\f2a4;\n$fa-var-delicious: \\f1a5;\n$fa-var-democrat: \\f747;\n$fa-var-deploydog: \\f38e;\n$fa-var-deskpro: \\f38f;\n$fa-var-desktop: \\f108;\n$fa-var-dev: \\f6cc;\n$fa-var-deviantart: \\f1bd;\n$fa-var-dharmachakra: \\f655;\n$fa-var-dhl: \\f790;\n$fa-var-diagnoses: \\f470;\n$fa-var-diaspora: \\f791;\n$fa-var-dice: \\f522;\n$fa-var-dice-d20: \\f6cf;\n$fa-var-dice-d6: \\f6d1;\n$fa-var-dice-five: \\f523;\n$fa-var-dice-four: \\f524;\n$fa-var-dice-one: \\f525;\n$fa-var-dice-six: \\f526;\n$fa-var-dice-three: \\f527;\n$fa-var-dice-two: \\f528;\n$fa-var-digg: \\f1a6;\n$fa-var-digital-ocean: \\f391;\n$fa-var-digital-tachograph: \\f566;\n$fa-var-directions: \\f5eb;\n$fa-var-discord: \\f392;\n$fa-var-discourse: \\f393;\n$fa-var-divide: \\f529;\n$fa-var-dizzy: \\f567;\n$fa-var-dna: \\f471;\n$fa-var-dochub: \\f394;\n$fa-var-docker: \\f395;\n$fa-var-dog: \\f6d3;\n$fa-var-dollar-sign: \\f155;\n$fa-var-dolly: \\f472;\n$fa-var-dolly-flatbed: \\f474;\n$fa-var-donate: \\f4b9;\n$fa-var-door-closed: \\f52a;\n$fa-var-door-open: \\f52b;\n$fa-var-dot-circle: \\f192;\n$fa-var-dove: \\f4ba;\n$fa-var-download: \\f019;\n$fa-var-draft2digital: \\f396;\n$fa-var-drafting-compass: \\f568;\n$fa-var-dragon: \\f6d5;\n$fa-var-draw-polygon: \\f5ee;\n$fa-var-dribbble: \\f17d;\n$fa-var-dribbble-square: \\f397;\n$fa-var-dropbox: \\f16b;\n$fa-var-drum: \\f569;\n$fa-var-drum-steelpan: \\f56a;\n$fa-var-drumstick-bite: \\f6d7;\n$fa-var-drupal: \\f1a9;\n$fa-var-dumbbell: \\f44b;\n$fa-var-dumpster: \\f793;\n$fa-var-dumpster-fire: \\f794;\n$fa-var-dungeon: \\f6d9;\n$fa-var-dyalog: \\f399;\n$fa-var-earlybirds: \\f39a;\n$fa-var-ebay: \\f4f4;\n$fa-var-edge: \\f282;\n$fa-var-edit: \\f044;\n$fa-var-egg: \\f7fb;\n$fa-var-eject: \\f052;\n$fa-var-elementor: \\f430;\n$fa-var-ellipsis-h: \\f141;\n$fa-var-ellipsis-v: \\f142;\n$fa-var-ello: \\f5f1;\n$fa-var-ember: \\f423;\n$fa-var-empire: \\f1d1;\n$fa-var-envelope: \\f0e0;\n$fa-var-envelope-open: \\f2b6;\n$fa-var-envelope-open-text: \\f658;\n$fa-var-envelope-square: \\f199;\n$fa-var-envira: \\f299;\n$fa-var-equals: \\f52c;\n$fa-var-eraser: \\f12d;\n$fa-var-erlang: \\f39d;\n$fa-var-ethereum: \\f42e;\n$fa-var-ethernet: \\f796;\n$fa-var-etsy: \\f2d7;\n$fa-var-euro-sign: \\f153;\n$fa-var-evernote: \\f839;\n$fa-var-exchange-alt: \\f362;\n$fa-var-exclamation: \\f12a;\n$fa-var-exclamation-circle: \\f06a;\n$fa-var-exclamation-triangle: \\f071;\n$fa-var-expand: \\f065;\n$fa-var-expand-arrows-alt: \\f31e;\n$fa-var-expeditedssl: \\f23e;\n$fa-var-external-link-alt: \\f35d;\n$fa-var-external-link-square-alt: \\f360;\n$fa-var-eye: \\f06e;\n$fa-var-eye-dropper: \\f1fb;\n$fa-var-eye-slash: \\f070;\n$fa-var-facebook: \\f09a;\n$fa-var-facebook-f: \\f39e;\n$fa-var-facebook-messenger: \\f39f;\n$fa-var-facebook-square: \\f082;\n$fa-var-fan: \\f863;\n$fa-var-fantasy-flight-games: \\f6dc;\n$fa-var-fast-backward: \\f049;\n$fa-var-fast-forward: \\f050;\n$fa-var-fax: \\f1ac;\n$fa-var-feather: \\f52d;\n$fa-var-feather-alt: \\f56b;\n$fa-var-fedex: \\f797;\n$fa-var-fedora: \\f798;\n$fa-var-female: \\f182;\n$fa-var-fighter-jet: \\f0fb;\n$fa-var-figma: \\f799;\n$fa-var-file: \\f15b;\n$fa-var-file-alt: \\f15c;\n$fa-var-file-archive: \\f1c6;\n$fa-var-file-audio: \\f1c7;\n$fa-var-file-code: \\f1c9;\n$fa-var-file-contract: \\f56c;\n$fa-var-file-csv: \\f6dd;\n$fa-var-file-download: \\f56d;\n$fa-var-file-excel: \\f1c3;\n$fa-var-file-export: \\f56e;\n$fa-var-file-image: \\f1c5;\n$fa-var-file-import: \\f56f;\n$fa-var-file-invoice: \\f570;\n$fa-var-file-invoice-dollar: \\f571;\n$fa-var-file-medical: \\f477;\n$fa-var-file-medical-alt: \\f478;\n$fa-var-file-pdf: \\f1c1;\n$fa-var-file-powerpoint: \\f1c4;\n$fa-var-file-prescription: \\f572;\n$fa-var-file-signature: \\f573;\n$fa-var-file-upload: \\f574;\n$fa-var-file-video: \\f1c8;\n$fa-var-file-word: \\f1c2;\n$fa-var-fill: \\f575;\n$fa-var-fill-drip: \\f576;\n$fa-var-film: \\f008;\n$fa-var-filter: \\f0b0;\n$fa-var-fingerprint: \\f577;\n$fa-var-fire: \\f06d;\n$fa-var-fire-alt: \\f7e4;\n$fa-var-fire-extinguisher: \\f134;\n$fa-var-firefox: \\f269;\n$fa-var-first-aid: \\f479;\n$fa-var-first-order: \\f2b0;\n$fa-var-first-order-alt: \\f50a;\n$fa-var-firstdraft: \\f3a1;\n$fa-var-fish: \\f578;\n$fa-var-fist-raised: \\f6de;\n$fa-var-flag: \\f024;\n$fa-var-flag-checkered: \\f11e;\n$fa-var-flag-usa: \\f74d;\n$fa-var-flask: \\f0c3;\n$fa-var-flickr: \\f16e;\n$fa-var-flipboard: \\f44d;\n$fa-var-flushed: \\f579;\n$fa-var-fly: \\f417;\n$fa-var-folder: \\f07b;\n$fa-var-folder-minus: \\f65d;\n$fa-var-folder-open: \\f07c;\n$fa-var-folder-plus: \\f65e;\n$fa-var-font: \\f031;\n$fa-var-font-awesome: \\f2b4;\n$fa-var-font-awesome-alt: \\f35c;\n$fa-var-font-awesome-flag: \\f425;\n$fa-var-font-awesome-logo-full: \\f4e6;\n$fa-var-fonticons: \\f280;\n$fa-var-fonticons-fi: \\f3a2;\n$fa-var-football-ball: \\f44e;\n$fa-var-fort-awesome: \\f286;\n$fa-var-fort-awesome-alt: \\f3a3;\n$fa-var-forumbee: \\f211;\n$fa-var-forward: \\f04e;\n$fa-var-foursquare: \\f180;\n$fa-var-free-code-camp: \\f2c5;\n$fa-var-freebsd: \\f3a4;\n$fa-var-frog: \\f52e;\n$fa-var-frown: \\f119;\n$fa-var-frown-open: \\f57a;\n$fa-var-fulcrum: \\f50b;\n$fa-var-funnel-dollar: \\f662;\n$fa-var-futbol: \\f1e3;\n$fa-var-galactic-republic: \\f50c;\n$fa-var-galactic-senate: \\f50d;\n$fa-var-gamepad: \\f11b;\n$fa-var-gas-pump: \\f52f;\n$fa-var-gavel: \\f0e3;\n$fa-var-gem: \\f3a5;\n$fa-var-genderless: \\f22d;\n$fa-var-get-pocket: \\f265;\n$fa-var-gg: \\f260;\n$fa-var-gg-circle: \\f261;\n$fa-var-ghost: \\f6e2;\n$fa-var-gift: \\f06b;\n$fa-var-gifts: \\f79c;\n$fa-var-git: \\f1d3;\n$fa-var-git-alt: \\f841;\n$fa-var-git-square: \\f1d2;\n$fa-var-github: \\f09b;\n$fa-var-github-alt: \\f113;\n$fa-var-github-square: \\f092;\n$fa-var-gitkraken: \\f3a6;\n$fa-var-gitlab: \\f296;\n$fa-var-gitter: \\f426;\n$fa-var-glass-cheers: \\f79f;\n$fa-var-glass-martini: \\f000;\n$fa-var-glass-martini-alt: \\f57b;\n$fa-var-glass-whiskey: \\f7a0;\n$fa-var-glasses: \\f530;\n$fa-var-glide: \\f2a5;\n$fa-var-glide-g: \\f2a6;\n$fa-var-globe: \\f0ac;\n$fa-var-globe-africa: \\f57c;\n$fa-var-globe-americas: \\f57d;\n$fa-var-globe-asia: \\f57e;\n$fa-var-globe-europe: \\f7a2;\n$fa-var-gofore: \\f3a7;\n$fa-var-golf-ball: \\f450;\n$fa-var-goodreads: \\f3a8;\n$fa-var-goodreads-g: \\f3a9;\n$fa-var-google: \\f1a0;\n$fa-var-google-drive: \\f3aa;\n$fa-var-google-play: \\f3ab;\n$fa-var-google-plus: \\f2b3;\n$fa-var-google-plus-g: \\f0d5;\n$fa-var-google-plus-square: \\f0d4;\n$fa-var-google-wallet: \\f1ee;\n$fa-var-gopuram: \\f664;\n$fa-var-graduation-cap: \\f19d;\n$fa-var-gratipay: \\f184;\n$fa-var-grav: \\f2d6;\n$fa-var-greater-than: \\f531;\n$fa-var-greater-than-equal: \\f532;\n$fa-var-grimace: \\f57f;\n$fa-var-grin: \\f580;\n$fa-var-grin-alt: \\f581;\n$fa-var-grin-beam: \\f582;\n$fa-var-grin-beam-sweat: \\f583;\n$fa-var-grin-hearts: \\f584;\n$fa-var-grin-squint: \\f585;\n$fa-var-grin-squint-tears: \\f586;\n$fa-var-grin-stars: \\f587;\n$fa-var-grin-tears: \\f588;\n$fa-var-grin-tongue: \\f589;\n$fa-var-grin-tongue-squint: \\f58a;\n$fa-var-grin-tongue-wink: \\f58b;\n$fa-var-grin-wink: \\f58c;\n$fa-var-grip-horizontal: \\f58d;\n$fa-var-grip-lines: \\f7a4;\n$fa-var-grip-lines-vertical: \\f7a5;\n$fa-var-grip-vertical: \\f58e;\n$fa-var-gripfire: \\f3ac;\n$fa-var-grunt: \\f3ad;\n$fa-var-guitar: \\f7a6;\n$fa-var-gulp: \\f3ae;\n$fa-var-h-square: \\f0fd;\n$fa-var-hacker-news: \\f1d4;\n$fa-var-hacker-news-square: \\f3af;\n$fa-var-hackerrank: \\f5f7;\n$fa-var-hamburger: \\f805;\n$fa-var-hammer: \\f6e3;\n$fa-var-hamsa: \\f665;\n$fa-var-hand-holding: \\f4bd;\n$fa-var-hand-holding-heart: \\f4be;\n$fa-var-hand-holding-usd: \\f4c0;\n$fa-var-hand-lizard: \\f258;\n$fa-var-hand-middle-finger: \\f806;\n$fa-var-hand-paper: \\f256;\n$fa-var-hand-peace: \\f25b;\n$fa-var-hand-point-down: \\f0a7;\n$fa-var-hand-point-left: \\f0a5;\n$fa-var-hand-point-right: \\f0a4;\n$fa-var-hand-point-up: \\f0a6;\n$fa-var-hand-pointer: \\f25a;\n$fa-var-hand-rock: \\f255;\n$fa-var-hand-scissors: \\f257;\n$fa-var-hand-spock: \\f259;\n$fa-var-hands: \\f4c2;\n$fa-var-hands-helping: \\f4c4;\n$fa-var-handshake: \\f2b5;\n$fa-var-hanukiah: \\f6e6;\n$fa-var-hard-hat: \\f807;\n$fa-var-hashtag: \\f292;\n$fa-var-hat-wizard: \\f6e8;\n$fa-var-haykal: \\f666;\n$fa-var-hdd: \\f0a0;\n$fa-var-heading: \\f1dc;\n$fa-var-headphones: \\f025;\n$fa-var-headphones-alt: \\f58f;\n$fa-var-headset: \\f590;\n$fa-var-heart: \\f004;\n$fa-var-heart-broken: \\f7a9;\n$fa-var-heartbeat: \\f21e;\n$fa-var-helicopter: \\f533;\n$fa-var-highlighter: \\f591;\n$fa-var-hiking: \\f6ec;\n$fa-var-hippo: \\f6ed;\n$fa-var-hips: \\f452;\n$fa-var-hire-a-helper: \\f3b0;\n$fa-var-history: \\f1da;\n$fa-var-hockey-puck: \\f453;\n$fa-var-holly-berry: \\f7aa;\n$fa-var-home: \\f015;\n$fa-var-hooli: \\f427;\n$fa-var-hornbill: \\f592;\n$fa-var-horse: \\f6f0;\n$fa-var-horse-head: \\f7ab;\n$fa-var-hospital: \\f0f8;\n$fa-var-hospital-alt: \\f47d;\n$fa-var-hospital-symbol: \\f47e;\n$fa-var-hot-tub: \\f593;\n$fa-var-hotdog: \\f80f;\n$fa-var-hotel: \\f594;\n$fa-var-hotjar: \\f3b1;\n$fa-var-hourglass: \\f254;\n$fa-var-hourglass-end: \\f253;\n$fa-var-hourglass-half: \\f252;\n$fa-var-hourglass-start: \\f251;\n$fa-var-house-damage: \\f6f1;\n$fa-var-houzz: \\f27c;\n$fa-var-hryvnia: \\f6f2;\n$fa-var-html5: \\f13b;\n$fa-var-hubspot: \\f3b2;\n$fa-var-i-cursor: \\f246;\n$fa-var-ice-cream: \\f810;\n$fa-var-icicles: \\f7ad;\n$fa-var-icons: \\f86d;\n$fa-var-id-badge: \\f2c1;\n$fa-var-id-card: \\f2c2;\n$fa-var-id-card-alt: \\f47f;\n$fa-var-igloo: \\f7ae;\n$fa-var-image: \\f03e;\n$fa-var-images: \\f302;\n$fa-var-imdb: \\f2d8;\n$fa-var-inbox: \\f01c;\n$fa-var-indent: \\f03c;\n$fa-var-industry: \\f275;\n$fa-var-infinity: \\f534;\n$fa-var-info: \\f129;\n$fa-var-info-circle: \\f05a;\n$fa-var-instagram: \\f16d;\n$fa-var-intercom: \\f7af;\n$fa-var-internet-explorer: \\f26b;\n$fa-var-invision: \\f7b0;\n$fa-var-ioxhost: \\f208;\n$fa-var-italic: \\f033;\n$fa-var-itch-io: \\f83a;\n$fa-var-itunes: \\f3b4;\n$fa-var-itunes-note: \\f3b5;\n$fa-var-java: \\f4e4;\n$fa-var-jedi: \\f669;\n$fa-var-jedi-order: \\f50e;\n$fa-var-jenkins: \\f3b6;\n$fa-var-jira: \\f7b1;\n$fa-var-joget: \\f3b7;\n$fa-var-joint: \\f595;\n$fa-var-joomla: \\f1aa;\n$fa-var-journal-whills: \\f66a;\n$fa-var-js: \\f3b8;\n$fa-var-js-square: \\f3b9;\n$fa-var-jsfiddle: \\f1cc;\n$fa-var-kaaba: \\f66b;\n$fa-var-kaggle: \\f5fa;\n$fa-var-key: \\f084;\n$fa-var-keybase: \\f4f5;\n$fa-var-keyboard: \\f11c;\n$fa-var-keycdn: \\f3ba;\n$fa-var-khanda: \\f66d;\n$fa-var-kickstarter: \\f3bb;\n$fa-var-kickstarter-k: \\f3bc;\n$fa-var-kiss: \\f596;\n$fa-var-kiss-beam: \\f597;\n$fa-var-kiss-wink-heart: \\f598;\n$fa-var-kiwi-bird: \\f535;\n$fa-var-korvue: \\f42f;\n$fa-var-landmark: \\f66f;\n$fa-var-language: \\f1ab;\n$fa-var-laptop: \\f109;\n$fa-var-laptop-code: \\f5fc;\n$fa-var-laptop-medical: \\f812;\n$fa-var-laravel: \\f3bd;\n$fa-var-lastfm: \\f202;\n$fa-var-lastfm-square: \\f203;\n$fa-var-laugh: \\f599;\n$fa-var-laugh-beam: \\f59a;\n$fa-var-laugh-squint: \\f59b;\n$fa-var-laugh-wink: \\f59c;\n$fa-var-layer-group: \\f5fd;\n$fa-var-leaf: \\f06c;\n$fa-var-leanpub: \\f212;\n$fa-var-lemon: \\f094;\n$fa-var-less: \\f41d;\n$fa-var-less-than: \\f536;\n$fa-var-less-than-equal: \\f537;\n$fa-var-level-down-alt: \\f3be;\n$fa-var-level-up-alt: \\f3bf;\n$fa-var-life-ring: \\f1cd;\n$fa-var-lightbulb: \\f0eb;\n$fa-var-line: \\f3c0;\n$fa-var-link: \\f0c1;\n$fa-var-linkedin: \\f08c;\n$fa-var-linkedin-in: \\f0e1;\n$fa-var-linode: \\f2b8;\n$fa-var-linux: \\f17c;\n$fa-var-lira-sign: \\f195;\n$fa-var-list: \\f03a;\n$fa-var-list-alt: \\f022;\n$fa-var-list-ol: \\f0cb;\n$fa-var-list-ul: \\f0ca;\n$fa-var-location-arrow: \\f124;\n$fa-var-lock: \\f023;\n$fa-var-lock-open: \\f3c1;\n$fa-var-long-arrow-alt-down: \\f309;\n$fa-var-long-arrow-alt-left: \\f30a;\n$fa-var-long-arrow-alt-right: \\f30b;\n$fa-var-long-arrow-alt-up: \\f30c;\n$fa-var-low-vision: \\f2a8;\n$fa-var-luggage-cart: \\f59d;\n$fa-var-lyft: \\f3c3;\n$fa-var-magento: \\f3c4;\n$fa-var-magic: \\f0d0;\n$fa-var-magnet: \\f076;\n$fa-var-mail-bulk: \\f674;\n$fa-var-mailchimp: \\f59e;\n$fa-var-male: \\f183;\n$fa-var-mandalorian: \\f50f;\n$fa-var-map: \\f279;\n$fa-var-map-marked: \\f59f;\n$fa-var-map-marked-alt: \\f5a0;\n$fa-var-map-marker: \\f041;\n$fa-var-map-marker-alt: \\f3c5;\n$fa-var-map-pin: \\f276;\n$fa-var-map-signs: \\f277;\n$fa-var-markdown: \\f60f;\n$fa-var-marker: \\f5a1;\n$fa-var-mars: \\f222;\n$fa-var-mars-double: \\f227;\n$fa-var-mars-stroke: \\f229;\n$fa-var-mars-stroke-h: \\f22b;\n$fa-var-mars-stroke-v: \\f22a;\n$fa-var-mask: \\f6fa;\n$fa-var-mastodon: \\f4f6;\n$fa-var-maxcdn: \\f136;\n$fa-var-medal: \\f5a2;\n$fa-var-medapps: \\f3c6;\n$fa-var-medium: \\f23a;\n$fa-var-medium-m: \\f3c7;\n$fa-var-medkit: \\f0fa;\n$fa-var-medrt: \\f3c8;\n$fa-var-meetup: \\f2e0;\n$fa-var-megaport: \\f5a3;\n$fa-var-meh: \\f11a;\n$fa-var-meh-blank: \\f5a4;\n$fa-var-meh-rolling-eyes: \\f5a5;\n$fa-var-memory: \\f538;\n$fa-var-mendeley: \\f7b3;\n$fa-var-menorah: \\f676;\n$fa-var-mercury: \\f223;\n$fa-var-meteor: \\f753;\n$fa-var-microchip: \\f2db;\n$fa-var-microphone: \\f130;\n$fa-var-microphone-alt: \\f3c9;\n$fa-var-microphone-alt-slash: \\f539;\n$fa-var-microphone-slash: \\f131;\n$fa-var-microscope: \\f610;\n$fa-var-microsoft: \\f3ca;\n$fa-var-minus: \\f068;\n$fa-var-minus-circle: \\f056;\n$fa-var-minus-square: \\f146;\n$fa-var-mitten: \\f7b5;\n$fa-var-mix: \\f3cb;\n$fa-var-mixcloud: \\f289;\n$fa-var-mizuni: \\f3cc;\n$fa-var-mobile: \\f10b;\n$fa-var-mobile-alt: \\f3cd;\n$fa-var-modx: \\f285;\n$fa-var-monero: \\f3d0;\n$fa-var-money-bill: \\f0d6;\n$fa-var-money-bill-alt: \\f3d1;\n$fa-var-money-bill-wave: \\f53a;\n$fa-var-money-bill-wave-alt: \\f53b;\n$fa-var-money-check: \\f53c;\n$fa-var-money-check-alt: \\f53d;\n$fa-var-monument: \\f5a6;\n$fa-var-moon: \\f186;\n$fa-var-mortar-pestle: \\f5a7;\n$fa-var-mosque: \\f678;\n$fa-var-motorcycle: \\f21c;\n$fa-var-mountain: \\f6fc;\n$fa-var-mouse-pointer: \\f245;\n$fa-var-mug-hot: \\f7b6;\n$fa-var-music: \\f001;\n$fa-var-napster: \\f3d2;\n$fa-var-neos: \\f612;\n$fa-var-network-wired: \\f6ff;\n$fa-var-neuter: \\f22c;\n$fa-var-newspaper: \\f1ea;\n$fa-var-nimblr: \\f5a8;\n$fa-var-node: \\f419;\n$fa-var-node-js: \\f3d3;\n$fa-var-not-equal: \\f53e;\n$fa-var-notes-medical: \\f481;\n$fa-var-npm: \\f3d4;\n$fa-var-ns8: \\f3d5;\n$fa-var-nutritionix: \\f3d6;\n$fa-var-object-group: \\f247;\n$fa-var-object-ungroup: \\f248;\n$fa-var-odnoklassniki: \\f263;\n$fa-var-odnoklassniki-square: \\f264;\n$fa-var-oil-can: \\f613;\n$fa-var-old-republic: \\f510;\n$fa-var-om: \\f679;\n$fa-var-opencart: \\f23d;\n$fa-var-openid: \\f19b;\n$fa-var-opera: \\f26a;\n$fa-var-optin-monster: \\f23c;\n$fa-var-osi: \\f41a;\n$fa-var-otter: \\f700;\n$fa-var-outdent: \\f03b;\n$fa-var-page4: \\f3d7;\n$fa-var-pagelines: \\f18c;\n$fa-var-pager: \\f815;\n$fa-var-paint-brush: \\f1fc;\n$fa-var-paint-roller: \\f5aa;\n$fa-var-palette: \\f53f;\n$fa-var-palfed: \\f3d8;\n$fa-var-pallet: \\f482;\n$fa-var-paper-plane: \\f1d8;\n$fa-var-paperclip: \\f0c6;\n$fa-var-parachute-box: \\f4cd;\n$fa-var-paragraph: \\f1dd;\n$fa-var-parking: \\f540;\n$fa-var-passport: \\f5ab;\n$fa-var-pastafarianism: \\f67b;\n$fa-var-paste: \\f0ea;\n$fa-var-patreon: \\f3d9;\n$fa-var-pause: \\f04c;\n$fa-var-pause-circle: \\f28b;\n$fa-var-paw: \\f1b0;\n$fa-var-paypal: \\f1ed;\n$fa-var-peace: \\f67c;\n$fa-var-pen: \\f304;\n$fa-var-pen-alt: \\f305;\n$fa-var-pen-fancy: \\f5ac;\n$fa-var-pen-nib: \\f5ad;\n$fa-var-pen-square: \\f14b;\n$fa-var-pencil-alt: \\f303;\n$fa-var-pencil-ruler: \\f5ae;\n$fa-var-penny-arcade: \\f704;\n$fa-var-people-carry: \\f4ce;\n$fa-var-pepper-hot: \\f816;\n$fa-var-percent: \\f295;\n$fa-var-percentage: \\f541;\n$fa-var-periscope: \\f3da;\n$fa-var-person-booth: \\f756;\n$fa-var-phabricator: \\f3db;\n$fa-var-phoenix-framework: \\f3dc;\n$fa-var-phoenix-squadron: \\f511;\n$fa-var-phone: \\f095;\n$fa-var-phone-alt: \\f879;\n$fa-var-phone-slash: \\f3dd;\n$fa-var-phone-square: \\f098;\n$fa-var-phone-square-alt: \\f87b;\n$fa-var-phone-volume: \\f2a0;\n$fa-var-photo-video: \\f87c;\n$fa-var-php: \\f457;\n$fa-var-pied-piper: \\f2ae;\n$fa-var-pied-piper-alt: \\f1a8;\n$fa-var-pied-piper-hat: \\f4e5;\n$fa-var-pied-piper-pp: \\f1a7;\n$fa-var-piggy-bank: \\f4d3;\n$fa-var-pills: \\f484;\n$fa-var-pinterest: \\f0d2;\n$fa-var-pinterest-p: \\f231;\n$fa-var-pinterest-square: \\f0d3;\n$fa-var-pizza-slice: \\f818;\n$fa-var-place-of-worship: \\f67f;\n$fa-var-plane: \\f072;\n$fa-var-plane-arrival: \\f5af;\n$fa-var-plane-departure: \\f5b0;\n$fa-var-play: \\f04b;\n$fa-var-play-circle: \\f144;\n$fa-var-playstation: \\f3df;\n$fa-var-plug: \\f1e6;\n$fa-var-plus: \\f067;\n$fa-var-plus-circle: \\f055;\n$fa-var-plus-square: \\f0fe;\n$fa-var-podcast: \\f2ce;\n$fa-var-poll: \\f681;\n$fa-var-poll-h: \\f682;\n$fa-var-poo: \\f2fe;\n$fa-var-poo-storm: \\f75a;\n$fa-var-poop: \\f619;\n$fa-var-portrait: \\f3e0;\n$fa-var-pound-sign: \\f154;\n$fa-var-power-off: \\f011;\n$fa-var-pray: \\f683;\n$fa-var-praying-hands: \\f684;\n$fa-var-prescription: \\f5b1;\n$fa-var-prescription-bottle: \\f485;\n$fa-var-prescription-bottle-alt: \\f486;\n$fa-var-print: \\f02f;\n$fa-var-procedures: \\f487;\n$fa-var-product-hunt: \\f288;\n$fa-var-project-diagram: \\f542;\n$fa-var-pushed: \\f3e1;\n$fa-var-puzzle-piece: \\f12e;\n$fa-var-python: \\f3e2;\n$fa-var-qq: \\f1d6;\n$fa-var-qrcode: \\f029;\n$fa-var-question: \\f128;\n$fa-var-question-circle: \\f059;\n$fa-var-quidditch: \\f458;\n$fa-var-quinscape: \\f459;\n$fa-var-quora: \\f2c4;\n$fa-var-quote-left: \\f10d;\n$fa-var-quote-right: \\f10e;\n$fa-var-quran: \\f687;\n$fa-var-r-project: \\f4f7;\n$fa-var-radiation: \\f7b9;\n$fa-var-radiation-alt: \\f7ba;\n$fa-var-rainbow: \\f75b;\n$fa-var-random: \\f074;\n$fa-var-raspberry-pi: \\f7bb;\n$fa-var-ravelry: \\f2d9;\n$fa-var-react: \\f41b;\n$fa-var-reacteurope: \\f75d;\n$fa-var-readme: \\f4d5;\n$fa-var-rebel: \\f1d0;\n$fa-var-receipt: \\f543;\n$fa-var-recycle: \\f1b8;\n$fa-var-red-river: \\f3e3;\n$fa-var-reddit: \\f1a1;\n$fa-var-reddit-alien: \\f281;\n$fa-var-reddit-square: \\f1a2;\n$fa-var-redhat: \\f7bc;\n$fa-var-redo: \\f01e;\n$fa-var-redo-alt: \\f2f9;\n$fa-var-registered: \\f25d;\n$fa-var-remove-format: \\f87d;\n$fa-var-renren: \\f18b;\n$fa-var-reply: \\f3e5;\n$fa-var-reply-all: \\f122;\n$fa-var-replyd: \\f3e6;\n$fa-var-republican: \\f75e;\n$fa-var-researchgate: \\f4f8;\n$fa-var-resolving: \\f3e7;\n$fa-var-restroom: \\f7bd;\n$fa-var-retweet: \\f079;\n$fa-var-rev: \\f5b2;\n$fa-var-ribbon: \\f4d6;\n$fa-var-ring: \\f70b;\n$fa-var-road: \\f018;\n$fa-var-robot: \\f544;\n$fa-var-rocket: \\f135;\n$fa-var-rocketchat: \\f3e8;\n$fa-var-rockrms: \\f3e9;\n$fa-var-route: \\f4d7;\n$fa-var-rss: \\f09e;\n$fa-var-rss-square: \\f143;\n$fa-var-ruble-sign: \\f158;\n$fa-var-ruler: \\f545;\n$fa-var-ruler-combined: \\f546;\n$fa-var-ruler-horizontal: \\f547;\n$fa-var-ruler-vertical: \\f548;\n$fa-var-running: \\f70c;\n$fa-var-rupee-sign: \\f156;\n$fa-var-sad-cry: \\f5b3;\n$fa-var-sad-tear: \\f5b4;\n$fa-var-safari: \\f267;\n$fa-var-salesforce: \\f83b;\n$fa-var-sass: \\f41e;\n$fa-var-satellite: \\f7bf;\n$fa-var-satellite-dish: \\f7c0;\n$fa-var-save: \\f0c7;\n$fa-var-schlix: \\f3ea;\n$fa-var-school: \\f549;\n$fa-var-screwdriver: \\f54a;\n$fa-var-scribd: \\f28a;\n$fa-var-scroll: \\f70e;\n$fa-var-sd-card: \\f7c2;\n$fa-var-search: \\f002;\n$fa-var-search-dollar: \\f688;\n$fa-var-search-location: \\f689;\n$fa-var-search-minus: \\f010;\n$fa-var-search-plus: \\f00e;\n$fa-var-searchengin: \\f3eb;\n$fa-var-seedling: \\f4d8;\n$fa-var-sellcast: \\f2da;\n$fa-var-sellsy: \\f213;\n$fa-var-server: \\f233;\n$fa-var-servicestack: \\f3ec;\n$fa-var-shapes: \\f61f;\n$fa-var-share: \\f064;\n$fa-var-share-alt: \\f1e0;\n$fa-var-share-alt-square: \\f1e1;\n$fa-var-share-square: \\f14d;\n$fa-var-shekel-sign: \\f20b;\n$fa-var-shield-alt: \\f3ed;\n$fa-var-ship: \\f21a;\n$fa-var-shipping-fast: \\f48b;\n$fa-var-shirtsinbulk: \\f214;\n$fa-var-shoe-prints: \\f54b;\n$fa-var-shopping-bag: \\f290;\n$fa-var-shopping-basket: \\f291;\n$fa-var-shopping-cart: \\f07a;\n$fa-var-shopware: \\f5b5;\n$fa-var-shower: \\f2cc;\n$fa-var-shuttle-van: \\f5b6;\n$fa-var-sign: \\f4d9;\n$fa-var-sign-in-alt: \\f2f6;\n$fa-var-sign-language: \\f2a7;\n$fa-var-sign-out-alt: \\f2f5;\n$fa-var-signal: \\f012;\n$fa-var-signature: \\f5b7;\n$fa-var-sim-card: \\f7c4;\n$fa-var-simplybuilt: \\f215;\n$fa-var-sistrix: \\f3ee;\n$fa-var-sitemap: \\f0e8;\n$fa-var-sith: \\f512;\n$fa-var-skating: \\f7c5;\n$fa-var-sketch: \\f7c6;\n$fa-var-skiing: \\f7c9;\n$fa-var-skiing-nordic: \\f7ca;\n$fa-var-skull: \\f54c;\n$fa-var-skull-crossbones: \\f714;\n$fa-var-skyatlas: \\f216;\n$fa-var-skype: \\f17e;\n$fa-var-slack: \\f198;\n$fa-var-slack-hash: \\f3ef;\n$fa-var-slash: \\f715;\n$fa-var-sleigh: \\f7cc;\n$fa-var-sliders-h: \\f1de;\n$fa-var-slideshare: \\f1e7;\n$fa-var-smile: \\f118;\n$fa-var-smile-beam: \\f5b8;\n$fa-var-smile-wink: \\f4da;\n$fa-var-smog: \\f75f;\n$fa-var-smoking: \\f48d;\n$fa-var-smoking-ban: \\f54d;\n$fa-var-sms: \\f7cd;\n$fa-var-snapchat: \\f2ab;\n$fa-var-snapchat-ghost: \\f2ac;\n$fa-var-snapchat-square: \\f2ad;\n$fa-var-snowboarding: \\f7ce;\n$fa-var-snowflake: \\f2dc;\n$fa-var-snowman: \\f7d0;\n$fa-var-snowplow: \\f7d2;\n$fa-var-socks: \\f696;\n$fa-var-solar-panel: \\f5ba;\n$fa-var-sort: \\f0dc;\n$fa-var-sort-alpha-down: \\f15d;\n$fa-var-sort-alpha-down-alt: \\f881;\n$fa-var-sort-alpha-up: \\f15e;\n$fa-var-sort-alpha-up-alt: \\f882;\n$fa-var-sort-amount-down: \\f160;\n$fa-var-sort-amount-down-alt: \\f884;\n$fa-var-sort-amount-up: \\f161;\n$fa-var-sort-amount-up-alt: \\f885;\n$fa-var-sort-down: \\f0dd;\n$fa-var-sort-numeric-down: \\f162;\n$fa-var-sort-numeric-down-alt: \\f886;\n$fa-var-sort-numeric-up: \\f163;\n$fa-var-sort-numeric-up-alt: \\f887;\n$fa-var-sort-up: \\f0de;\n$fa-var-soundcloud: \\f1be;\n$fa-var-sourcetree: \\f7d3;\n$fa-var-spa: \\f5bb;\n$fa-var-space-shuttle: \\f197;\n$fa-var-speakap: \\f3f3;\n$fa-var-speaker-deck: \\f83c;\n$fa-var-spell-check: \\f891;\n$fa-var-spider: \\f717;\n$fa-var-spinner: \\f110;\n$fa-var-splotch: \\f5bc;\n$fa-var-spotify: \\f1bc;\n$fa-var-spray-can: \\f5bd;\n$fa-var-square: \\f0c8;\n$fa-var-square-full: \\f45c;\n$fa-var-square-root-alt: \\f698;\n$fa-var-squarespace: \\f5be;\n$fa-var-stack-exchange: \\f18d;\n$fa-var-stack-overflow: \\f16c;\n$fa-var-stackpath: \\f842;\n$fa-var-stamp: \\f5bf;\n$fa-var-star: \\f005;\n$fa-var-star-and-crescent: \\f699;\n$fa-var-star-half: \\f089;\n$fa-var-star-half-alt: \\f5c0;\n$fa-var-star-of-david: \\f69a;\n$fa-var-star-of-life: \\f621;\n$fa-var-staylinked: \\f3f5;\n$fa-var-steam: \\f1b6;\n$fa-var-steam-square: \\f1b7;\n$fa-var-steam-symbol: \\f3f6;\n$fa-var-step-backward: \\f048;\n$fa-var-step-forward: \\f051;\n$fa-var-stethoscope: \\f0f1;\n$fa-var-sticker-mule: \\f3f7;\n$fa-var-sticky-note: \\f249;\n$fa-var-stop: \\f04d;\n$fa-var-stop-circle: \\f28d;\n$fa-var-stopwatch: \\f2f2;\n$fa-var-store: \\f54e;\n$fa-var-store-alt: \\f54f;\n$fa-var-strava: \\f428;\n$fa-var-stream: \\f550;\n$fa-var-street-view: \\f21d;\n$fa-var-strikethrough: \\f0cc;\n$fa-var-stripe: \\f429;\n$fa-var-stripe-s: \\f42a;\n$fa-var-stroopwafel: \\f551;\n$fa-var-studiovinari: \\f3f8;\n$fa-var-stumbleupon: \\f1a4;\n$fa-var-stumbleupon-circle: \\f1a3;\n$fa-var-subscript: \\f12c;\n$fa-var-subway: \\f239;\n$fa-var-suitcase: \\f0f2;\n$fa-var-suitcase-rolling: \\f5c1;\n$fa-var-sun: \\f185;\n$fa-var-superpowers: \\f2dd;\n$fa-var-superscript: \\f12b;\n$fa-var-supple: \\f3f9;\n$fa-var-surprise: \\f5c2;\n$fa-var-suse: \\f7d6;\n$fa-var-swatchbook: \\f5c3;\n$fa-var-swimmer: \\f5c4;\n$fa-var-swimming-pool: \\f5c5;\n$fa-var-symfony: \\f83d;\n$fa-var-synagogue: \\f69b;\n$fa-var-sync: \\f021;\n$fa-var-sync-alt: \\f2f1;\n$fa-var-syringe: \\f48e;\n$fa-var-table: \\f0ce;\n$fa-var-table-tennis: \\f45d;\n$fa-var-tablet: \\f10a;\n$fa-var-tablet-alt: \\f3fa;\n$fa-var-tablets: \\f490;\n$fa-var-tachometer-alt: \\f3fd;\n$fa-var-tag: \\f02b;\n$fa-var-tags: \\f02c;\n$fa-var-tape: \\f4db;\n$fa-var-tasks: \\f0ae;\n$fa-var-taxi: \\f1ba;\n$fa-var-teamspeak: \\f4f9;\n$fa-var-teeth: \\f62e;\n$fa-var-teeth-open: \\f62f;\n$fa-var-telegram: \\f2c6;\n$fa-var-telegram-plane: \\f3fe;\n$fa-var-temperature-high: \\f769;\n$fa-var-temperature-low: \\f76b;\n$fa-var-tencent-weibo: \\f1d5;\n$fa-var-tenge: \\f7d7;\n$fa-var-terminal: \\f120;\n$fa-var-text-height: \\f034;\n$fa-var-text-width: \\f035;\n$fa-var-th: \\f00a;\n$fa-var-th-large: \\f009;\n$fa-var-th-list: \\f00b;\n$fa-var-the-red-yeti: \\f69d;\n$fa-var-theater-masks: \\f630;\n$fa-var-themeco: \\f5c6;\n$fa-var-themeisle: \\f2b2;\n$fa-var-thermometer: \\f491;\n$fa-var-thermometer-empty: \\f2cb;\n$fa-var-thermometer-full: \\f2c7;\n$fa-var-thermometer-half: \\f2c9;\n$fa-var-thermometer-quarter: \\f2ca;\n$fa-var-thermometer-three-quarters: \\f2c8;\n$fa-var-think-peaks: \\f731;\n$fa-var-thumbs-down: \\f165;\n$fa-var-thumbs-up: \\f164;\n$fa-var-thumbtack: \\f08d;\n$fa-var-ticket-alt: \\f3ff;\n$fa-var-times: \\f00d;\n$fa-var-times-circle: \\f057;\n$fa-var-tint: \\f043;\n$fa-var-tint-slash: \\f5c7;\n$fa-var-tired: \\f5c8;\n$fa-var-toggle-off: \\f204;\n$fa-var-toggle-on: \\f205;\n$fa-var-toilet: \\f7d8;\n$fa-var-toilet-paper: \\f71e;\n$fa-var-toolbox: \\f552;\n$fa-var-tools: \\f7d9;\n$fa-var-tooth: \\f5c9;\n$fa-var-torah: \\f6a0;\n$fa-var-torii-gate: \\f6a1;\n$fa-var-tractor: \\f722;\n$fa-var-trade-federation: \\f513;\n$fa-var-trademark: \\f25c;\n$fa-var-traffic-light: \\f637;\n$fa-var-train: \\f238;\n$fa-var-tram: \\f7da;\n$fa-var-transgender: \\f224;\n$fa-var-transgender-alt: \\f225;\n$fa-var-trash: \\f1f8;\n$fa-var-trash-alt: \\f2ed;\n$fa-var-trash-restore: \\f829;\n$fa-var-trash-restore-alt: \\f82a;\n$fa-var-tree: \\f1bb;\n$fa-var-trello: \\f181;\n$fa-var-tripadvisor: \\f262;\n$fa-var-trophy: \\f091;\n$fa-var-truck: \\f0d1;\n$fa-var-truck-loading: \\f4de;\n$fa-var-truck-monster: \\f63b;\n$fa-var-truck-moving: \\f4df;\n$fa-var-truck-pickup: \\f63c;\n$fa-var-tshirt: \\f553;\n$fa-var-tty: \\f1e4;\n$fa-var-tumblr: \\f173;\n$fa-var-tumblr-square: \\f174;\n$fa-var-tv: \\f26c;\n$fa-var-twitch: \\f1e8;\n$fa-var-twitter: \\f099;\n$fa-var-twitter-square: \\f081;\n$fa-var-typo3: \\f42b;\n$fa-var-uber: \\f402;\n$fa-var-ubuntu: \\f7df;\n$fa-var-uikit: \\f403;\n$fa-var-umbrella: \\f0e9;\n$fa-var-umbrella-beach: \\f5ca;\n$fa-var-underline: \\f0cd;\n$fa-var-undo: \\f0e2;\n$fa-var-undo-alt: \\f2ea;\n$fa-var-uniregistry: \\f404;\n$fa-var-universal-access: \\f29a;\n$fa-var-university: \\f19c;\n$fa-var-unlink: \\f127;\n$fa-var-unlock: \\f09c;\n$fa-var-unlock-alt: \\f13e;\n$fa-var-untappd: \\f405;\n$fa-var-upload: \\f093;\n$fa-var-ups: \\f7e0;\n$fa-var-usb: \\f287;\n$fa-var-user: \\f007;\n$fa-var-user-alt: \\f406;\n$fa-var-user-alt-slash: \\f4fa;\n$fa-var-user-astronaut: \\f4fb;\n$fa-var-user-check: \\f4fc;\n$fa-var-user-circle: \\f2bd;\n$fa-var-user-clock: \\f4fd;\n$fa-var-user-cog: \\f4fe;\n$fa-var-user-edit: \\f4ff;\n$fa-var-user-friends: \\f500;\n$fa-var-user-graduate: \\f501;\n$fa-var-user-injured: \\f728;\n$fa-var-user-lock: \\f502;\n$fa-var-user-md: \\f0f0;\n$fa-var-user-minus: \\f503;\n$fa-var-user-ninja: \\f504;\n$fa-var-user-nurse: \\f82f;\n$fa-var-user-plus: \\f234;\n$fa-var-user-secret: \\f21b;\n$fa-var-user-shield: \\f505;\n$fa-var-user-slash: \\f506;\n$fa-var-user-tag: \\f507;\n$fa-var-user-tie: \\f508;\n$fa-var-user-times: \\f235;\n$fa-var-users: \\f0c0;\n$fa-var-users-cog: \\f509;\n$fa-var-usps: \\f7e1;\n$fa-var-ussunnah: \\f407;\n$fa-var-utensil-spoon: \\f2e5;\n$fa-var-utensils: \\f2e7;\n$fa-var-vaadin: \\f408;\n$fa-var-vector-square: \\f5cb;\n$fa-var-venus: \\f221;\n$fa-var-venus-double: \\f226;\n$fa-var-venus-mars: \\f228;\n$fa-var-viacoin: \\f237;\n$fa-var-viadeo: \\f2a9;\n$fa-var-viadeo-square: \\f2aa;\n$fa-var-vial: \\f492;\n$fa-var-vials: \\f493;\n$fa-var-viber: \\f409;\n$fa-var-video: \\f03d;\n$fa-var-video-slash: \\f4e2;\n$fa-var-vihara: \\f6a7;\n$fa-var-vimeo: \\f40a;\n$fa-var-vimeo-square: \\f194;\n$fa-var-vimeo-v: \\f27d;\n$fa-var-vine: \\f1ca;\n$fa-var-vk: \\f189;\n$fa-var-vnv: \\f40b;\n$fa-var-voicemail: \\f897;\n$fa-var-volleyball-ball: \\f45f;\n$fa-var-volume-down: \\f027;\n$fa-var-volume-mute: \\f6a9;\n$fa-var-volume-off: \\f026;\n$fa-var-volume-up: \\f028;\n$fa-var-vote-yea: \\f772;\n$fa-var-vr-cardboard: \\f729;\n$fa-var-vuejs: \\f41f;\n$fa-var-walking: \\f554;\n$fa-var-wallet: \\f555;\n$fa-var-warehouse: \\f494;\n$fa-var-water: \\f773;\n$fa-var-wave-square: \\f83e;\n$fa-var-waze: \\f83f;\n$fa-var-weebly: \\f5cc;\n$fa-var-weibo: \\f18a;\n$fa-var-weight: \\f496;\n$fa-var-weight-hanging: \\f5cd;\n$fa-var-weixin: \\f1d7;\n$fa-var-whatsapp: \\f232;\n$fa-var-whatsapp-square: \\f40c;\n$fa-var-wheelchair: \\f193;\n$fa-var-whmcs: \\f40d;\n$fa-var-wifi: \\f1eb;\n$fa-var-wikipedia-w: \\f266;\n$fa-var-wind: \\f72e;\n$fa-var-window-close: \\f410;\n$fa-var-window-maximize: \\f2d0;\n$fa-var-window-minimize: \\f2d1;\n$fa-var-window-restore: \\f2d2;\n$fa-var-windows: \\f17a;\n$fa-var-wine-bottle: \\f72f;\n$fa-var-wine-glass: \\f4e3;\n$fa-var-wine-glass-alt: \\f5ce;\n$fa-var-wix: \\f5cf;\n$fa-var-wizards-of-the-coast: \\f730;\n$fa-var-wolf-pack-battalion: \\f514;\n$fa-var-won-sign: \\f159;\n$fa-var-wordpress: \\f19a;\n$fa-var-wordpress-simple: \\f411;\n$fa-var-wpbeginner: \\f297;\n$fa-var-wpexplorer: \\f2de;\n$fa-var-wpforms: \\f298;\n$fa-var-wpressr: \\f3e4;\n$fa-var-wrench: \\f0ad;\n$fa-var-x-ray: \\f497;\n$fa-var-xbox: \\f412;\n$fa-var-xing: \\f168;\n$fa-var-xing-square: \\f169;\n$fa-var-y-combinator: \\f23b;\n$fa-var-yahoo: \\f19e;\n$fa-var-yammer: \\f840;\n$fa-var-yandex: \\f413;\n$fa-var-yandex-international: \\f414;\n$fa-var-yarn: \\f7e3;\n$fa-var-yelp: \\f1e9;\n$fa-var-yen-sign: \\f157;\n$fa-var-yin-yang: \\f6ad;\n$fa-var-yoast: \\f2b1;\n$fa-var-youtube: \\f167;\n$fa-var-youtube-square: \\f431;\n$fa-var-zhihu: \\f63f;\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/brands.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n\n@font-face {\n  font-family: 'Font Awesome 5 Brands';\n  font-style: normal;\n  font-weight: normal;\n  font-display: $fa-font-display;\n  src: url('#{$fa-font-path}/fa-brands-400.eot');\n  src: url('#{$fa-font-path}/fa-brands-400.eot?#iefix') format('embedded-opentype'),\n  url('#{$fa-font-path}/fa-brands-400.woff2') format('woff2'),\n  url('#{$fa-font-path}/fa-brands-400.woff') format('woff'),\n  url('#{$fa-font-path}/fa-brands-400.ttf') format('truetype'),\n  url('#{$fa-font-path}/fa-brands-400.svg#fontawesome') format('svg');\n}\n\n.fab {\n  font-family: 'Font Awesome 5 Brands';\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/fontawesome.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n@import 'mixins';\n@import 'core';\n@import 'larger';\n@import 'fixed-width';\n@import 'list';\n@import 'bordered-pulled';\n@import 'animated';\n@import 'rotated-flipped';\n@import 'stacked';\n@import 'icons';\n@import 'screen-reader';\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/regular.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 400;\n  font-display: $fa-font-display;\n  src: url('#{$fa-font-path}/fa-regular-400.eot');\n  src: url('#{$fa-font-path}/fa-regular-400.eot?#iefix') format('embedded-opentype'),\n  url('#{$fa-font-path}/fa-regular-400.woff2') format('woff2'),\n  url('#{$fa-font-path}/fa-regular-400.woff') format('woff'),\n  url('#{$fa-font-path}/fa-regular-400.ttf') format('truetype'),\n  url('#{$fa-font-path}/fa-regular-400.svg#fontawesome') format('svg');\n}\n\n.far {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 400;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/solid.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n\n@font-face {\n  font-family: 'Font Awesome 5 Free';\n  font-style: normal;\n  font-weight: 900;\n  font-display: $fa-font-display;\n  src: url('#{$fa-font-path}/fa-solid-900.eot');\n  src: url('#{$fa-font-path}/fa-solid-900.eot?#iefix') format('embedded-opentype'),\n  url('#{$fa-font-path}/fa-solid-900.woff2') format('woff2'),\n  url('#{$fa-font-path}/fa-solid-900.woff') format('woff'),\n  url('#{$fa-font-path}/fa-solid-900.ttf') format('truetype'),\n  url('#{$fa-font-path}/fa-solid-900.svg#fontawesome') format('svg');\n}\n\n.fa,\n.fas {\n  font-family: 'Font Awesome 5 Free';\n  font-weight: 900;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/fontawesome-free/scss/v4-shims.scss",
    "content": "/*!\n * Font Awesome Free 5.10.2 by @fontawesome - https://fontawesome.com\n * License - https://fontawesome.com/license/free (Icons: CC BY 4.0, Fonts: SIL OFL 1.1, Code: MIT License)\n */\n@import 'variables';\n@import 'shims';\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/jquery/jquery.js",
    "content": "/*!\n * jQuery JavaScript Library v3.4.1\n * https://jquery.com/\n *\n * Includes Sizzle.js\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://jquery.org/license\n *\n * Date: 2019-05-01T21:04Z\n */\n( function( global, factory ) {\n\n\t\"use strict\";\n\n\tif ( typeof module === \"object\" && typeof module.exports === \"object\" ) {\n\n\t\t// For CommonJS and CommonJS-like environments where a proper `window`\n\t\t// is present, execute the factory and get jQuery.\n\t\t// For environments that do not have a `window` with a `document`\n\t\t// (such as Node.js), expose a factory as module.exports.\n\t\t// This accentuates the need for the creation of a real `window`.\n\t\t// e.g. var jQuery = require(\"jquery\")(window);\n\t\t// See ticket #14549 for more info.\n\t\tmodule.exports = global.document ?\n\t\t\tfactory( global, true ) :\n\t\t\tfunction( w ) {\n\t\t\t\tif ( !w.document ) {\n\t\t\t\t\tthrow new Error( \"jQuery requires a window with a document\" );\n\t\t\t\t}\n\t\t\t\treturn factory( w );\n\t\t\t};\n\t} else {\n\t\tfactory( global );\n\t}\n\n// Pass this if window is not defined yet\n} )( typeof window !== \"undefined\" ? window : this, function( window, noGlobal ) {\n\n// Edge <= 12 - 13+, Firefox <=18 - 45+, IE 10 - 11, Safari 5.1 - 9+, iOS 6 - 9.1\n// throw exceptions when non-strict code (e.g., ASP.NET 4.5) accesses strict mode\n// arguments.callee.caller (trac-13335). But as of jQuery 3.0 (2016), strict mode should be common\n// enough that all such attempts are guarded in a try block.\n\"use strict\";\n\nvar arr = [];\n\nvar document = window.document;\n\nvar getProto = Object.getPrototypeOf;\n\nvar slice = arr.slice;\n\nvar concat = arr.concat;\n\nvar push = arr.push;\n\nvar indexOf = arr.indexOf;\n\nvar class2type = {};\n\nvar toString = class2type.toString;\n\nvar hasOwn = class2type.hasOwnProperty;\n\nvar fnToString = hasOwn.toString;\n\nvar ObjectFunctionString = fnToString.call( Object );\n\nvar support = {};\n\nvar isFunction = function isFunction( obj ) {\n\n      // Support: Chrome <=57, Firefox <=52\n      // In some browsers, typeof returns \"function\" for HTML <object> elements\n      // (i.e., `typeof document.createElement( \"object\" ) === \"function\"`).\n      // We don't want to classify *any* DOM node as a function.\n      return typeof obj === \"function\" && typeof obj.nodeType !== \"number\";\n  };\n\n\nvar isWindow = function isWindow( obj ) {\n\t\treturn obj != null && obj === obj.window;\n\t};\n\n\n\n\n\tvar preservedScriptAttributes = {\n\t\ttype: true,\n\t\tsrc: true,\n\t\tnonce: true,\n\t\tnoModule: true\n\t};\n\n\tfunction DOMEval( code, node, doc ) {\n\t\tdoc = doc || document;\n\n\t\tvar i, val,\n\t\t\tscript = doc.createElement( \"script\" );\n\n\t\tscript.text = code;\n\t\tif ( node ) {\n\t\t\tfor ( i in preservedScriptAttributes ) {\n\n\t\t\t\t// Support: Firefox 64+, Edge 18+\n\t\t\t\t// Some browsers don't support the \"nonce\" property on scripts.\n\t\t\t\t// On the other hand, just using `getAttribute` is not enough as\n\t\t\t\t// the `nonce` attribute is reset to an empty string whenever it\n\t\t\t\t// becomes browsing-context connected.\n\t\t\t\t// See https://github.com/whatwg/html/issues/2369\n\t\t\t\t// See https://html.spec.whatwg.org/#nonce-attributes\n\t\t\t\t// The `node.getAttribute` check was added for the sake of\n\t\t\t\t// `jQuery.globalEval` so that it can fake a nonce-containing node\n\t\t\t\t// via an object.\n\t\t\t\tval = node[ i ] || node.getAttribute && node.getAttribute( i );\n\t\t\t\tif ( val ) {\n\t\t\t\t\tscript.setAttribute( i, val );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tdoc.head.appendChild( script ).parentNode.removeChild( script );\n\t}\n\n\nfunction toType( obj ) {\n\tif ( obj == null ) {\n\t\treturn obj + \"\";\n\t}\n\n\t// Support: Android <=2.3 only (functionish RegExp)\n\treturn typeof obj === \"object\" || typeof obj === \"function\" ?\n\t\tclass2type[ toString.call( obj ) ] || \"object\" :\n\t\ttypeof obj;\n}\n/* global Symbol */\n// Defining this global in .eslintrc.json would create a danger of using the global\n// unguarded in another place, it seems safer to define global only for this module\n\n\n\nvar\n\tversion = \"3.4.1\",\n\n\t// Define a local copy of jQuery\n\tjQuery = function( selector, context ) {\n\n\t\t// The jQuery object is actually just the init constructor 'enhanced'\n\t\t// Need init if jQuery is called (just allow error to be thrown if not included)\n\t\treturn new jQuery.fn.init( selector, context );\n\t},\n\n\t// Support: Android <=4.0 only\n\t// Make sure we trim BOM and NBSP\n\trtrim = /^[\\s\\uFEFF\\xA0]+|[\\s\\uFEFF\\xA0]+$/g;\n\njQuery.fn = jQuery.prototype = {\n\n\t// The current version of jQuery being used\n\tjquery: version,\n\n\tconstructor: jQuery,\n\n\t// The default length of a jQuery object is 0\n\tlength: 0,\n\n\ttoArray: function() {\n\t\treturn slice.call( this );\n\t},\n\n\t// Get the Nth element in the matched element set OR\n\t// Get the whole matched element set as a clean array\n\tget: function( num ) {\n\n\t\t// Return all the elements in a clean array\n\t\tif ( num == null ) {\n\t\t\treturn slice.call( this );\n\t\t}\n\n\t\t// Return just the one element from the set\n\t\treturn num < 0 ? this[ num + this.length ] : this[ num ];\n\t},\n\n\t// Take an array of elements and push it onto the stack\n\t// (returning the new matched element set)\n\tpushStack: function( elems ) {\n\n\t\t// Build a new jQuery matched element set\n\t\tvar ret = jQuery.merge( this.constructor(), elems );\n\n\t\t// Add the old object onto the stack (as a reference)\n\t\tret.prevObject = this;\n\n\t\t// Return the newly-formed element set\n\t\treturn ret;\n\t},\n\n\t// Execute a callback for every element in the matched set.\n\teach: function( callback ) {\n\t\treturn jQuery.each( this, callback );\n\t},\n\n\tmap: function( callback ) {\n\t\treturn this.pushStack( jQuery.map( this, function( elem, i ) {\n\t\t\treturn callback.call( elem, i, elem );\n\t\t} ) );\n\t},\n\n\tslice: function() {\n\t\treturn this.pushStack( slice.apply( this, arguments ) );\n\t},\n\n\tfirst: function() {\n\t\treturn this.eq( 0 );\n\t},\n\n\tlast: function() {\n\t\treturn this.eq( -1 );\n\t},\n\n\teq: function( i ) {\n\t\tvar len = this.length,\n\t\t\tj = +i + ( i < 0 ? len : 0 );\n\t\treturn this.pushStack( j >= 0 && j < len ? [ this[ j ] ] : [] );\n\t},\n\n\tend: function() {\n\t\treturn this.prevObject || this.constructor();\n\t},\n\n\t// For internal use only.\n\t// Behaves like an Array's method, not like a jQuery method.\n\tpush: push,\n\tsort: arr.sort,\n\tsplice: arr.splice\n};\n\njQuery.extend = jQuery.fn.extend = function() {\n\tvar options, name, src, copy, copyIsArray, clone,\n\t\ttarget = arguments[ 0 ] || {},\n\t\ti = 1,\n\t\tlength = arguments.length,\n\t\tdeep = false;\n\n\t// Handle a deep copy situation\n\tif ( typeof target === \"boolean\" ) {\n\t\tdeep = target;\n\n\t\t// Skip the boolean and the target\n\t\ttarget = arguments[ i ] || {};\n\t\ti++;\n\t}\n\n\t// Handle case when target is a string or something (possible in deep copy)\n\tif ( typeof target !== \"object\" && !isFunction( target ) ) {\n\t\ttarget = {};\n\t}\n\n\t// Extend jQuery itself if only one argument is passed\n\tif ( i === length ) {\n\t\ttarget = this;\n\t\ti--;\n\t}\n\n\tfor ( ; i < length; i++ ) {\n\n\t\t// Only deal with non-null/undefined values\n\t\tif ( ( options = arguments[ i ] ) != null ) {\n\n\t\t\t// Extend the base object\n\t\t\tfor ( name in options ) {\n\t\t\t\tcopy = options[ name ];\n\n\t\t\t\t// Prevent Object.prototype pollution\n\t\t\t\t// Prevent never-ending loop\n\t\t\t\tif ( name === \"__proto__\" || target === copy ) {\n\t\t\t\t\tcontinue;\n\t\t\t\t}\n\n\t\t\t\t// Recurse if we're merging plain objects or arrays\n\t\t\t\tif ( deep && copy && ( jQuery.isPlainObject( copy ) ||\n\t\t\t\t\t( copyIsArray = Array.isArray( copy ) ) ) ) {\n\t\t\t\t\tsrc = target[ name ];\n\n\t\t\t\t\t// Ensure proper type for the source value\n\t\t\t\t\tif ( copyIsArray && !Array.isArray( src ) ) {\n\t\t\t\t\t\tclone = [];\n\t\t\t\t\t} else if ( !copyIsArray && !jQuery.isPlainObject( src ) ) {\n\t\t\t\t\t\tclone = {};\n\t\t\t\t\t} else {\n\t\t\t\t\t\tclone = src;\n\t\t\t\t\t}\n\t\t\t\t\tcopyIsArray = false;\n\n\t\t\t\t\t// Never move original objects, clone them\n\t\t\t\t\ttarget[ name ] = jQuery.extend( deep, clone, copy );\n\n\t\t\t\t// Don't bring in undefined values\n\t\t\t\t} else if ( copy !== undefined ) {\n\t\t\t\t\ttarget[ name ] = copy;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Return the modified object\n\treturn target;\n};\n\njQuery.extend( {\n\n\t// Unique for each copy of jQuery on the page\n\texpando: \"jQuery\" + ( version + Math.random() ).replace( /\\D/g, \"\" ),\n\n\t// Assume jQuery is ready without the ready module\n\tisReady: true,\n\n\terror: function( msg ) {\n\t\tthrow new Error( msg );\n\t},\n\n\tnoop: function() {},\n\n\tisPlainObject: function( obj ) {\n\t\tvar proto, Ctor;\n\n\t\t// Detect obvious negatives\n\t\t// Use toString instead of jQuery.type to catch host objects\n\t\tif ( !obj || toString.call( obj ) !== \"[object Object]\" ) {\n\t\t\treturn false;\n\t\t}\n\n\t\tproto = getProto( obj );\n\n\t\t// Objects with no prototype (e.g., `Object.create( null )`) are plain\n\t\tif ( !proto ) {\n\t\t\treturn true;\n\t\t}\n\n\t\t// Objects with prototype are plain iff they were constructed by a global Object function\n\t\tCtor = hasOwn.call( proto, \"constructor\" ) && proto.constructor;\n\t\treturn typeof Ctor === \"function\" && fnToString.call( Ctor ) === ObjectFunctionString;\n\t},\n\n\tisEmptyObject: function( obj ) {\n\t\tvar name;\n\n\t\tfor ( name in obj ) {\n\t\t\treturn false;\n\t\t}\n\t\treturn true;\n\t},\n\n\t// Evaluates a script in a global context\n\tglobalEval: function( code, options ) {\n\t\tDOMEval( code, { nonce: options && options.nonce } );\n\t},\n\n\teach: function( obj, callback ) {\n\t\tvar length, i = 0;\n\n\t\tif ( isArrayLike( obj ) ) {\n\t\t\tlength = obj.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t} else {\n\t\t\tfor ( i in obj ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn obj;\n\t},\n\n\t// Support: Android <=4.0 only\n\ttrim: function( text ) {\n\t\treturn text == null ?\n\t\t\t\"\" :\n\t\t\t( text + \"\" ).replace( rtrim, \"\" );\n\t},\n\n\t// results is for internal usage only\n\tmakeArray: function( arr, results ) {\n\t\tvar ret = results || [];\n\n\t\tif ( arr != null ) {\n\t\t\tif ( isArrayLike( Object( arr ) ) ) {\n\t\t\t\tjQuery.merge( ret,\n\t\t\t\t\ttypeof arr === \"string\" ?\n\t\t\t\t\t[ arr ] : arr\n\t\t\t\t);\n\t\t\t} else {\n\t\t\t\tpush.call( ret, arr );\n\t\t\t}\n\t\t}\n\n\t\treturn ret;\n\t},\n\n\tinArray: function( elem, arr, i ) {\n\t\treturn arr == null ? -1 : indexOf.call( arr, elem, i );\n\t},\n\n\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t// push.apply(_, arraylike) throws on ancient WebKit\n\tmerge: function( first, second ) {\n\t\tvar len = +second.length,\n\t\t\tj = 0,\n\t\t\ti = first.length;\n\n\t\tfor ( ; j < len; j++ ) {\n\t\t\tfirst[ i++ ] = second[ j ];\n\t\t}\n\n\t\tfirst.length = i;\n\n\t\treturn first;\n\t},\n\n\tgrep: function( elems, callback, invert ) {\n\t\tvar callbackInverse,\n\t\t\tmatches = [],\n\t\t\ti = 0,\n\t\t\tlength = elems.length,\n\t\t\tcallbackExpect = !invert;\n\n\t\t// Go through the array, only saving the items\n\t\t// that pass the validator function\n\t\tfor ( ; i < length; i++ ) {\n\t\t\tcallbackInverse = !callback( elems[ i ], i );\n\t\t\tif ( callbackInverse !== callbackExpect ) {\n\t\t\t\tmatches.push( elems[ i ] );\n\t\t\t}\n\t\t}\n\n\t\treturn matches;\n\t},\n\n\t// arg is for internal usage only\n\tmap: function( elems, callback, arg ) {\n\t\tvar length, value,\n\t\t\ti = 0,\n\t\t\tret = [];\n\n\t\t// Go through the array, translating each of the items to their new values\n\t\tif ( isArrayLike( elems ) ) {\n\t\t\tlength = elems.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Go through every key on the object,\n\t\t} else {\n\t\t\tfor ( i in elems ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Flatten any nested arrays\n\t\treturn concat.apply( [], ret );\n\t},\n\n\t// A global GUID counter for objects\n\tguid: 1,\n\n\t// jQuery.support is not used in Core but other projects attach their\n\t// properties to it so it needs to exist.\n\tsupport: support\n} );\n\nif ( typeof Symbol === \"function\" ) {\n\tjQuery.fn[ Symbol.iterator ] = arr[ Symbol.iterator ];\n}\n\n// Populate the class2type map\njQuery.each( \"Boolean Number String Function Array Date RegExp Object Error Symbol\".split( \" \" ),\nfunction( i, name ) {\n\tclass2type[ \"[object \" + name + \"]\" ] = name.toLowerCase();\n} );\n\nfunction isArrayLike( obj ) {\n\n\t// Support: real iOS 8.2 only (not reproducible in simulator)\n\t// `in` check used to prevent JIT error (gh-2145)\n\t// hasOwn isn't used here due to false negatives\n\t// regarding Nodelist length in IE\n\tvar length = !!obj && \"length\" in obj && obj.length,\n\t\ttype = toType( obj );\n\n\tif ( isFunction( obj ) || isWindow( obj ) ) {\n\t\treturn false;\n\t}\n\n\treturn type === \"array\" || length === 0 ||\n\t\ttypeof length === \"number\" && length > 0 && ( length - 1 ) in obj;\n}\nvar Sizzle =\n/*!\n * Sizzle CSS Selector Engine v2.3.4\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://js.foundation/\n *\n * Date: 2019-04-08\n */\n(function( window ) {\n\nvar i,\n\tsupport,\n\tExpr,\n\tgetText,\n\tisXML,\n\ttokenize,\n\tcompile,\n\tselect,\n\toutermostContext,\n\tsortInput,\n\thasDuplicate,\n\n\t// Local document vars\n\tsetDocument,\n\tdocument,\n\tdocElem,\n\tdocumentIsHTML,\n\trbuggyQSA,\n\trbuggyMatches,\n\tmatches,\n\tcontains,\n\n\t// Instance-specific data\n\texpando = \"sizzle\" + 1 * new Date(),\n\tpreferredDoc = window.document,\n\tdirruns = 0,\n\tdone = 0,\n\tclassCache = createCache(),\n\ttokenCache = createCache(),\n\tcompilerCache = createCache(),\n\tnonnativeSelectorCache = createCache(),\n\tsortOrder = function( a, b ) {\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t}\n\t\treturn 0;\n\t},\n\n\t// Instance methods\n\thasOwn = ({}).hasOwnProperty,\n\tarr = [],\n\tpop = arr.pop,\n\tpush_native = arr.push,\n\tpush = arr.push,\n\tslice = arr.slice,\n\t// Use a stripped-down indexOf as it's faster than native\n\t// https://jsperf.com/thor-indexof-vs-for/5\n\tindexOf = function( list, elem ) {\n\t\tvar i = 0,\n\t\t\tlen = list.length;\n\t\tfor ( ; i < len; i++ ) {\n\t\t\tif ( list[i] === elem ) {\n\t\t\t\treturn i;\n\t\t\t}\n\t\t}\n\t\treturn -1;\n\t},\n\n\tbooleans = \"checked|selected|async|autofocus|autoplay|controls|defer|disabled|hidden|ismap|loop|multiple|open|readonly|required|scoped\",\n\n\t// Regular expressions\n\n\t// http://www.w3.org/TR/css3-selectors/#whitespace\n\twhitespace = \"[\\\\x20\\\\t\\\\r\\\\n\\\\f]\",\n\n\t// http://www.w3.org/TR/CSS21/syndata.html#value-def-identifier\n\tidentifier = \"(?:\\\\\\\\.|[\\\\w-]|[^\\0-\\\\xa0])+\",\n\n\t// Attribute selectors: http://www.w3.org/TR/selectors/#attribute-selectors\n\tattributes = \"\\\\[\" + whitespace + \"*(\" + identifier + \")(?:\" + whitespace +\n\t\t// Operator (capture 2)\n\t\t\"*([*^$|!~]?=)\" + whitespace +\n\t\t// \"Attribute values must be CSS identifiers [capture 5] or strings [capture 3 or capture 4]\"\n\t\t\"*(?:'((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\"|(\" + identifier + \"))|)\" + whitespace +\n\t\t\"*\\\\]\",\n\n\tpseudos = \":(\" + identifier + \")(?:\\\\((\" +\n\t\t// To reduce the number of selectors needing tokenize in the preFilter, prefer arguments:\n\t\t// 1. quoted (capture 3; capture 4 or capture 5)\n\t\t\"('((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\")|\" +\n\t\t// 2. simple (capture 6)\n\t\t\"((?:\\\\\\\\.|[^\\\\\\\\()[\\\\]]|\" + attributes + \")*)|\" +\n\t\t// 3. anything else (capture 2)\n\t\t\".*\" +\n\t\t\")\\\\)|)\",\n\n\t// Leading and non-escaped trailing whitespace, capturing some non-whitespace characters preceding the latter\n\trwhitespace = new RegExp( whitespace + \"+\", \"g\" ),\n\trtrim = new RegExp( \"^\" + whitespace + \"+|((?:^|[^\\\\\\\\])(?:\\\\\\\\.)*)\" + whitespace + \"+$\", \"g\" ),\n\n\trcomma = new RegExp( \"^\" + whitespace + \"*,\" + whitespace + \"*\" ),\n\trcombinators = new RegExp( \"^\" + whitespace + \"*([>+~]|\" + whitespace + \")\" + whitespace + \"*\" ),\n\trdescend = new RegExp( whitespace + \"|>\" ),\n\n\trpseudo = new RegExp( pseudos ),\n\tridentifier = new RegExp( \"^\" + identifier + \"$\" ),\n\n\tmatchExpr = {\n\t\t\"ID\": new RegExp( \"^#(\" + identifier + \")\" ),\n\t\t\"CLASS\": new RegExp( \"^\\\\.(\" + identifier + \")\" ),\n\t\t\"TAG\": new RegExp( \"^(\" + identifier + \"|[*])\" ),\n\t\t\"ATTR\": new RegExp( \"^\" + attributes ),\n\t\t\"PSEUDO\": new RegExp( \"^\" + pseudos ),\n\t\t\"CHILD\": new RegExp( \"^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\\\(\" + whitespace +\n\t\t\t\"*(even|odd|(([+-]|)(\\\\d*)n|)\" + whitespace + \"*(?:([+-]|)\" + whitespace +\n\t\t\t\"*(\\\\d+)|))\" + whitespace + \"*\\\\)|)\", \"i\" ),\n\t\t\"bool\": new RegExp( \"^(?:\" + booleans + \")$\", \"i\" ),\n\t\t// For use in libraries implementing .is()\n\t\t// We use this for POS matching in `select`\n\t\t\"needsContext\": new RegExp( \"^\" + whitespace + \"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\\\(\" +\n\t\t\twhitespace + \"*((?:-\\\\d)?\\\\d*)\" + whitespace + \"*\\\\)|)(?=[^-]|$)\", \"i\" )\n\t},\n\n\trhtml = /HTML$/i,\n\trinputs = /^(?:input|select|textarea|button)$/i,\n\trheader = /^h\\d$/i,\n\n\trnative = /^[^{]+\\{\\s*\\[native \\w/,\n\n\t// Easily-parseable/retrievable ID or TAG or CLASS selectors\n\trquickExpr = /^(?:#([\\w-]+)|(\\w+)|\\.([\\w-]+))$/,\n\n\trsibling = /[+~]/,\n\n\t// CSS escapes\n\t// http://www.w3.org/TR/CSS21/syndata.html#escaped-characters\n\trunescape = new RegExp( \"\\\\\\\\([\\\\da-f]{1,6}\" + whitespace + \"?|(\" + whitespace + \")|.)\", \"ig\" ),\n\tfunescape = function( _, escaped, escapedWhitespace ) {\n\t\tvar high = \"0x\" + escaped - 0x10000;\n\t\t// NaN means non-codepoint\n\t\t// Support: Firefox<24\n\t\t// Workaround erroneous numeric interpretation of +\"0x\"\n\t\treturn high !== high || escapedWhitespace ?\n\t\t\tescaped :\n\t\t\thigh < 0 ?\n\t\t\t\t// BMP codepoint\n\t\t\t\tString.fromCharCode( high + 0x10000 ) :\n\t\t\t\t// Supplemental Plane codepoint (surrogate pair)\n\t\t\t\tString.fromCharCode( high >> 10 | 0xD800, high & 0x3FF | 0xDC00 );\n\t},\n\n\t// CSS string/identifier serialization\n\t// https://drafts.csswg.org/cssom/#common-serializing-idioms\n\trcssescape = /([\\0-\\x1f\\x7f]|^-?\\d)|^-$|[^\\0-\\x1f\\x7f-\\uFFFF\\w-]/g,\n\tfcssescape = function( ch, asCodePoint ) {\n\t\tif ( asCodePoint ) {\n\n\t\t\t// U+0000 NULL becomes U+FFFD REPLACEMENT CHARACTER\n\t\t\tif ( ch === \"\\0\" ) {\n\t\t\t\treturn \"\\uFFFD\";\n\t\t\t}\n\n\t\t\t// Control characters and (dependent upon position) numbers get escaped as code points\n\t\t\treturn ch.slice( 0, -1 ) + \"\\\\\" + ch.charCodeAt( ch.length - 1 ).toString( 16 ) + \" \";\n\t\t}\n\n\t\t// Other potentially-special ASCII characters get backslash-escaped\n\t\treturn \"\\\\\" + ch;\n\t},\n\n\t// Used for iframes\n\t// See setDocument()\n\t// Removing the function wrapper causes a \"Permission Denied\"\n\t// error in IE\n\tunloadHandler = function() {\n\t\tsetDocument();\n\t},\n\n\tinDisabledFieldset = addCombinator(\n\t\tfunction( elem ) {\n\t\t\treturn elem.disabled === true && elem.nodeName.toLowerCase() === \"fieldset\";\n\t\t},\n\t\t{ dir: \"parentNode\", next: \"legend\" }\n\t);\n\n// Optimize for push.apply( _, NodeList )\ntry {\n\tpush.apply(\n\t\t(arr = slice.call( preferredDoc.childNodes )),\n\t\tpreferredDoc.childNodes\n\t);\n\t// Support: Android<4.0\n\t// Detect silently failing push.apply\n\tarr[ preferredDoc.childNodes.length ].nodeType;\n} catch ( e ) {\n\tpush = { apply: arr.length ?\n\n\t\t// Leverage slice if possible\n\t\tfunction( target, els ) {\n\t\t\tpush_native.apply( target, slice.call(els) );\n\t\t} :\n\n\t\t// Support: IE<9\n\t\t// Otherwise append directly\n\t\tfunction( target, els ) {\n\t\t\tvar j = target.length,\n\t\t\t\ti = 0;\n\t\t\t// Can't trust NodeList.length\n\t\t\twhile ( (target[j++] = els[i++]) ) {}\n\t\t\ttarget.length = j - 1;\n\t\t}\n\t};\n}\n\nfunction Sizzle( selector, context, results, seed ) {\n\tvar m, i, elem, nid, match, groups, newSelector,\n\t\tnewContext = context && context.ownerDocument,\n\n\t\t// nodeType defaults to 9, since context defaults to document\n\t\tnodeType = context ? context.nodeType : 9;\n\n\tresults = results || [];\n\n\t// Return early from calls with invalid selector or context\n\tif ( typeof selector !== \"string\" || !selector ||\n\t\tnodeType !== 1 && nodeType !== 9 && nodeType !== 11 ) {\n\n\t\treturn results;\n\t}\n\n\t// Try to shortcut find operations (as opposed to filters) in HTML documents\n\tif ( !seed ) {\n\n\t\tif ( ( context ? context.ownerDocument || context : preferredDoc ) !== document ) {\n\t\t\tsetDocument( context );\n\t\t}\n\t\tcontext = context || document;\n\n\t\tif ( documentIsHTML ) {\n\n\t\t\t// If the selector is sufficiently simple, try using a \"get*By*\" DOM method\n\t\t\t// (excepting DocumentFragment context, where the methods don't exist)\n\t\t\tif ( nodeType !== 11 && (match = rquickExpr.exec( selector )) ) {\n\n\t\t\t\t// ID selector\n\t\t\t\tif ( (m = match[1]) ) {\n\n\t\t\t\t\t// Document context\n\t\t\t\t\tif ( nodeType === 9 ) {\n\t\t\t\t\t\tif ( (elem = context.getElementById( m )) ) {\n\n\t\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\t\tif ( elem.id === m ) {\n\t\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t// Element context\n\t\t\t\t\t} else {\n\n\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\tif ( newContext && (elem = newContext.getElementById( m )) &&\n\t\t\t\t\t\t\tcontains( context, elem ) &&\n\t\t\t\t\t\t\telem.id === m ) {\n\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t// Type selector\n\t\t\t\t} else if ( match[2] ) {\n\t\t\t\t\tpush.apply( results, context.getElementsByTagName( selector ) );\n\t\t\t\t\treturn results;\n\n\t\t\t\t// Class selector\n\t\t\t\t} else if ( (m = match[3]) && support.getElementsByClassName &&\n\t\t\t\t\tcontext.getElementsByClassName ) {\n\n\t\t\t\t\tpush.apply( results, context.getElementsByClassName( m ) );\n\t\t\t\t\treturn results;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Take advantage of querySelectorAll\n\t\t\tif ( support.qsa &&\n\t\t\t\t!nonnativeSelectorCache[ selector + \" \" ] &&\n\t\t\t\t(!rbuggyQSA || !rbuggyQSA.test( selector )) &&\n\n\t\t\t\t// Support: IE 8 only\n\t\t\t\t// Exclude object elements\n\t\t\t\t(nodeType !== 1 || context.nodeName.toLowerCase() !== \"object\") ) {\n\n\t\t\t\tnewSelector = selector;\n\t\t\t\tnewContext = context;\n\n\t\t\t\t// qSA considers elements outside a scoping root when evaluating child or\n\t\t\t\t// descendant combinators, which is not what we want.\n\t\t\t\t// In such cases, we work around the behavior by prefixing every selector in the\n\t\t\t\t// list with an ID selector referencing the scope context.\n\t\t\t\t// Thanks to Andrew Dupont for this technique.\n\t\t\t\tif ( nodeType === 1 && rdescend.test( selector ) ) {\n\n\t\t\t\t\t// Capture the context ID, setting it first if necessary\n\t\t\t\t\tif ( (nid = context.getAttribute( \"id\" )) ) {\n\t\t\t\t\t\tnid = nid.replace( rcssescape, fcssescape );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tcontext.setAttribute( \"id\", (nid = expando) );\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prefix every selector in the list\n\t\t\t\t\tgroups = tokenize( selector );\n\t\t\t\t\ti = groups.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tgroups[i] = \"#\" + nid + \" \" + toSelector( groups[i] );\n\t\t\t\t\t}\n\t\t\t\t\tnewSelector = groups.join( \",\" );\n\n\t\t\t\t\t// Expand context for sibling selectors\n\t\t\t\t\tnewContext = rsibling.test( selector ) && testContext( context.parentNode ) ||\n\t\t\t\t\t\tcontext;\n\t\t\t\t}\n\n\t\t\t\ttry {\n\t\t\t\t\tpush.apply( results,\n\t\t\t\t\t\tnewContext.querySelectorAll( newSelector )\n\t\t\t\t\t);\n\t\t\t\t\treturn results;\n\t\t\t\t} catch ( qsaError ) {\n\t\t\t\t\tnonnativeSelectorCache( selector, true );\n\t\t\t\t} finally {\n\t\t\t\t\tif ( nid === expando ) {\n\t\t\t\t\t\tcontext.removeAttribute( \"id\" );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// All others\n\treturn select( selector.replace( rtrim, \"$1\" ), context, results, seed );\n}\n\n/**\n * Create key-value caches of limited size\n * @returns {function(string, object)} Returns the Object data after storing it on itself with\n *\tproperty name the (space-suffixed) string and (if the cache is larger than Expr.cacheLength)\n *\tdeleting the oldest entry\n */\nfunction createCache() {\n\tvar keys = [];\n\n\tfunction cache( key, value ) {\n\t\t// Use (key + \" \") to avoid collision with native prototype properties (see Issue #157)\n\t\tif ( keys.push( key + \" \" ) > Expr.cacheLength ) {\n\t\t\t// Only keep the most recent entries\n\t\t\tdelete cache[ keys.shift() ];\n\t\t}\n\t\treturn (cache[ key + \" \" ] = value);\n\t}\n\treturn cache;\n}\n\n/**\n * Mark a function for special use by Sizzle\n * @param {Function} fn The function to mark\n */\nfunction markFunction( fn ) {\n\tfn[ expando ] = true;\n\treturn fn;\n}\n\n/**\n * Support testing using an element\n * @param {Function} fn Passed the created element and returns a boolean result\n */\nfunction assert( fn ) {\n\tvar el = document.createElement(\"fieldset\");\n\n\ttry {\n\t\treturn !!fn( el );\n\t} catch (e) {\n\t\treturn false;\n\t} finally {\n\t\t// Remove from its parent by default\n\t\tif ( el.parentNode ) {\n\t\t\tel.parentNode.removeChild( el );\n\t\t}\n\t\t// release memory in IE\n\t\tel = null;\n\t}\n}\n\n/**\n * Adds the same handler for all of the specified attrs\n * @param {String} attrs Pipe-separated list of attributes\n * @param {Function} handler The method that will be applied\n */\nfunction addHandle( attrs, handler ) {\n\tvar arr = attrs.split(\"|\"),\n\t\ti = arr.length;\n\n\twhile ( i-- ) {\n\t\tExpr.attrHandle[ arr[i] ] = handler;\n\t}\n}\n\n/**\n * Checks document order of two siblings\n * @param {Element} a\n * @param {Element} b\n * @returns {Number} Returns less than 0 if a precedes b, greater than 0 if a follows b\n */\nfunction siblingCheck( a, b ) {\n\tvar cur = b && a,\n\t\tdiff = cur && a.nodeType === 1 && b.nodeType === 1 &&\n\t\t\ta.sourceIndex - b.sourceIndex;\n\n\t// Use IE sourceIndex if available on both nodes\n\tif ( diff ) {\n\t\treturn diff;\n\t}\n\n\t// Check if b follows a\n\tif ( cur ) {\n\t\twhile ( (cur = cur.nextSibling) ) {\n\t\t\tif ( cur === b ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t}\n\n\treturn a ? 1 : -1;\n}\n\n/**\n * Returns a function to use in pseudos for input types\n * @param {String} type\n */\nfunction createInputPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn name === \"input\" && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for buttons\n * @param {String} type\n */\nfunction createButtonPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn (name === \"input\" || name === \"button\") && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for :enabled/:disabled\n * @param {Boolean} disabled true for :disabled; false for :enabled\n */\nfunction createDisabledPseudo( disabled ) {\n\n\t// Known :disabled false positives: fieldset[disabled] > legend:nth-of-type(n+2) :can-disable\n\treturn function( elem ) {\n\n\t\t// Only certain elements can match :enabled or :disabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-enabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-disabled\n\t\tif ( \"form\" in elem ) {\n\n\t\t\t// Check for inherited disabledness on relevant non-disabled elements:\n\t\t\t// * listed form-associated elements in a disabled fieldset\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#category-listed\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-fe-disabled\n\t\t\t// * option elements in a disabled optgroup\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-option-disabled\n\t\t\t// All such elements have a \"form\" property.\n\t\t\tif ( elem.parentNode && elem.disabled === false ) {\n\n\t\t\t\t// Option elements defer to a parent optgroup if present\n\t\t\t\tif ( \"label\" in elem ) {\n\t\t\t\t\tif ( \"label\" in elem.parentNode ) {\n\t\t\t\t\t\treturn elem.parentNode.disabled === disabled;\n\t\t\t\t\t} else {\n\t\t\t\t\t\treturn elem.disabled === disabled;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Support: IE 6 - 11\n\t\t\t\t// Use the isDisabled shortcut property to check for disabled fieldset ancestors\n\t\t\t\treturn elem.isDisabled === disabled ||\n\n\t\t\t\t\t// Where there is no isDisabled, check manually\n\t\t\t\t\t/* jshint -W018 */\n\t\t\t\t\telem.isDisabled !== !disabled &&\n\t\t\t\t\t\tinDisabledFieldset( elem ) === disabled;\n\t\t\t}\n\n\t\t\treturn elem.disabled === disabled;\n\n\t\t// Try to winnow out elements that can't be disabled before trusting the disabled property.\n\t\t// Some victims get caught in our net (label, legend, menu, track), but it shouldn't\n\t\t// even exist on them, let alone have a boolean value.\n\t\t} else if ( \"label\" in elem ) {\n\t\t\treturn elem.disabled === disabled;\n\t\t}\n\n\t\t// Remaining elements are neither :enabled nor :disabled\n\t\treturn false;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for positionals\n * @param {Function} fn\n */\nfunction createPositionalPseudo( fn ) {\n\treturn markFunction(function( argument ) {\n\t\targument = +argument;\n\t\treturn markFunction(function( seed, matches ) {\n\t\t\tvar j,\n\t\t\t\tmatchIndexes = fn( [], seed.length, argument ),\n\t\t\t\ti = matchIndexes.length;\n\n\t\t\t// Match elements found at the specified indexes\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( seed[ (j = matchIndexes[i]) ] ) {\n\t\t\t\t\tseed[j] = !(matches[j] = seed[j]);\n\t\t\t\t}\n\t\t\t}\n\t\t});\n\t});\n}\n\n/**\n * Checks a node for validity as a Sizzle context\n * @param {Element|Object=} context\n * @returns {Element|Object|Boolean} The input node if acceptable, otherwise a falsy value\n */\nfunction testContext( context ) {\n\treturn context && typeof context.getElementsByTagName !== \"undefined\" && context;\n}\n\n// Expose support vars for convenience\nsupport = Sizzle.support = {};\n\n/**\n * Detects XML nodes\n * @param {Element|Object} elem An element or a document\n * @returns {Boolean} True iff elem is a non-HTML XML node\n */\nisXML = Sizzle.isXML = function( elem ) {\n\tvar namespace = elem.namespaceURI,\n\t\tdocElem = (elem.ownerDocument || elem).documentElement;\n\n\t// Support: IE <=8\n\t// Assume HTML when documentElement doesn't yet exist, such as inside loading iframes\n\t// https://bugs.jquery.com/ticket/4833\n\treturn !rhtml.test( namespace || docElem && docElem.nodeName || \"HTML\" );\n};\n\n/**\n * Sets document-related variables once based on the current document\n * @param {Element|Object} [doc] An element or document object to use to set the document\n * @returns {Object} Returns the current document\n */\nsetDocument = Sizzle.setDocument = function( node ) {\n\tvar hasCompare, subWindow,\n\t\tdoc = node ? node.ownerDocument || node : preferredDoc;\n\n\t// Return early if doc is invalid or already selected\n\tif ( doc === document || doc.nodeType !== 9 || !doc.documentElement ) {\n\t\treturn document;\n\t}\n\n\t// Update global variables\n\tdocument = doc;\n\tdocElem = document.documentElement;\n\tdocumentIsHTML = !isXML( document );\n\n\t// Support: IE 9-11, Edge\n\t// Accessing iframe documents after unload throws \"permission denied\" errors (jQuery #13936)\n\tif ( preferredDoc !== document &&\n\t\t(subWindow = document.defaultView) && subWindow.top !== subWindow ) {\n\n\t\t// Support: IE 11, Edge\n\t\tif ( subWindow.addEventListener ) {\n\t\t\tsubWindow.addEventListener( \"unload\", unloadHandler, false );\n\n\t\t// Support: IE 9 - 10 only\n\t\t} else if ( subWindow.attachEvent ) {\n\t\t\tsubWindow.attachEvent( \"onunload\", unloadHandler );\n\t\t}\n\t}\n\n\t/* Attributes\n\t---------------------------------------------------------------------- */\n\n\t// Support: IE<8\n\t// Verify that getAttribute really returns attributes and not properties\n\t// (excepting IE8 booleans)\n\tsupport.attributes = assert(function( el ) {\n\t\tel.className = \"i\";\n\t\treturn !el.getAttribute(\"className\");\n\t});\n\n\t/* getElement(s)By*\n\t---------------------------------------------------------------------- */\n\n\t// Check if getElementsByTagName(\"*\") returns only elements\n\tsupport.getElementsByTagName = assert(function( el ) {\n\t\tel.appendChild( document.createComment(\"\") );\n\t\treturn !el.getElementsByTagName(\"*\").length;\n\t});\n\n\t// Support: IE<9\n\tsupport.getElementsByClassName = rnative.test( document.getElementsByClassName );\n\n\t// Support: IE<10\n\t// Check if getElementById returns elements by name\n\t// The broken getElementById methods don't pick up programmatically-set names,\n\t// so use a roundabout getElementsByName test\n\tsupport.getById = assert(function( el ) {\n\t\tdocElem.appendChild( el ).id = expando;\n\t\treturn !document.getElementsByName || !document.getElementsByName( expando ).length;\n\t});\n\n\t// ID filter and find\n\tif ( support.getById ) {\n\t\tExpr.filter[\"ID\"] = function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn elem.getAttribute(\"id\") === attrId;\n\t\t\t};\n\t\t};\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar elem = context.getElementById( id );\n\t\t\t\treturn elem ? [ elem ] : [];\n\t\t\t}\n\t\t};\n\t} else {\n\t\tExpr.filter[\"ID\"] =  function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\tvar node = typeof elem.getAttributeNode !== \"undefined\" &&\n\t\t\t\t\telem.getAttributeNode(\"id\");\n\t\t\t\treturn node && node.value === attrId;\n\t\t\t};\n\t\t};\n\n\t\t// Support: IE 6 - 7 only\n\t\t// getElementById is not reliable as a find shortcut\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar node, i, elems,\n\t\t\t\t\telem = context.getElementById( id );\n\n\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t// Verify the id attribute\n\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t}\n\n\t\t\t\t\t// Fall back on getElementsByName\n\t\t\t\t\telems = context.getElementsByName( id );\n\t\t\t\t\ti = 0;\n\t\t\t\t\twhile ( (elem = elems[i++]) ) {\n\t\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn [];\n\t\t\t}\n\t\t};\n\t}\n\n\t// Tag\n\tExpr.find[\"TAG\"] = support.getElementsByTagName ?\n\t\tfunction( tag, context ) {\n\t\t\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\t\t\treturn context.getElementsByTagName( tag );\n\n\t\t\t// DocumentFragment nodes don't have gEBTN\n\t\t\t} else if ( support.qsa ) {\n\t\t\t\treturn context.querySelectorAll( tag );\n\t\t\t}\n\t\t} :\n\n\t\tfunction( tag, context ) {\n\t\t\tvar elem,\n\t\t\t\ttmp = [],\n\t\t\t\ti = 0,\n\t\t\t\t// By happy coincidence, a (broken) gEBTN appears on DocumentFragment nodes too\n\t\t\t\tresults = context.getElementsByTagName( tag );\n\n\t\t\t// Filter out possible comments\n\t\t\tif ( tag === \"*\" ) {\n\t\t\t\twhile ( (elem = results[i++]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\ttmp.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn tmp;\n\t\t\t}\n\t\t\treturn results;\n\t\t};\n\n\t// Class\n\tExpr.find[\"CLASS\"] = support.getElementsByClassName && function( className, context ) {\n\t\tif ( typeof context.getElementsByClassName !== \"undefined\" && documentIsHTML ) {\n\t\t\treturn context.getElementsByClassName( className );\n\t\t}\n\t};\n\n\t/* QSA/matchesSelector\n\t---------------------------------------------------------------------- */\n\n\t// QSA and matchesSelector support\n\n\t// matchesSelector(:active) reports false when true (IE9/Opera 11.5)\n\trbuggyMatches = [];\n\n\t// qSa(:focus) reports false when true (Chrome 21)\n\t// We allow this because of a bug in IE8/9 that throws an error\n\t// whenever `document.activeElement` is accessed on an iframe\n\t// So, we allow :focus to pass through QSA all the time to avoid the IE error\n\t// See https://bugs.jquery.com/ticket/13378\n\trbuggyQSA = [];\n\n\tif ( (support.qsa = rnative.test( document.querySelectorAll )) ) {\n\t\t// Build QSA regex\n\t\t// Regex strategy adopted from Diego Perini\n\t\tassert(function( el ) {\n\t\t\t// Select is set to empty string on purpose\n\t\t\t// This is to test IE's treatment of not explicitly\n\t\t\t// setting a boolean content attribute,\n\t\t\t// since its presence should be enough\n\t\t\t// https://bugs.jquery.com/ticket/12359\n\t\t\tdocElem.appendChild( el ).innerHTML = \"<a id='\" + expando + \"'></a>\" +\n\t\t\t\t\"<select id='\" + expando + \"-\\r\\\\' msallowcapture=''>\" +\n\t\t\t\t\"<option selected=''></option></select>\";\n\n\t\t\t// Support: IE8, Opera 11-12.16\n\t\t\t// Nothing should be selected when empty strings follow ^= or $= or *=\n\t\t\t// The test attribute must be unknown in Opera but \"safe\" for WinRT\n\t\t\t// https://msdn.microsoft.com/en-us/library/ie/hh465388.aspx#attribute_section\n\t\t\tif ( el.querySelectorAll(\"[msallowcapture^='']\").length ) {\n\t\t\t\trbuggyQSA.push( \"[*^$]=\" + whitespace + \"*(?:''|\\\"\\\")\" );\n\t\t\t}\n\n\t\t\t// Support: IE8\n\t\t\t// Boolean attributes and \"value\" are not treated correctly\n\t\t\tif ( !el.querySelectorAll(\"[selected]\").length ) {\n\t\t\t\trbuggyQSA.push( \"\\\\[\" + whitespace + \"*(?:value|\" + booleans + \")\" );\n\t\t\t}\n\n\t\t\t// Support: Chrome<29, Android<4.4, Safari<7.0+, iOS<7.0+, PhantomJS<1.9.8+\n\t\t\tif ( !el.querySelectorAll( \"[id~=\" + expando + \"-]\" ).length ) {\n\t\t\t\trbuggyQSA.push(\"~=\");\n\t\t\t}\n\n\t\t\t// Webkit/Opera - :checked should return selected option elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( !el.querySelectorAll(\":checked\").length ) {\n\t\t\t\trbuggyQSA.push(\":checked\");\n\t\t\t}\n\n\t\t\t// Support: Safari 8+, iOS 8+\n\t\t\t// https://bugs.webkit.org/show_bug.cgi?id=136851\n\t\t\t// In-page `selector#id sibling-combinator selector` fails\n\t\t\tif ( !el.querySelectorAll( \"a#\" + expando + \"+*\" ).length ) {\n\t\t\t\trbuggyQSA.push(\".#.+[+~]\");\n\t\t\t}\n\t\t});\n\n\t\tassert(function( el ) {\n\t\t\tel.innerHTML = \"<a href='' disabled='disabled'></a>\" +\n\t\t\t\t\"<select disabled='disabled'><option/></select>\";\n\n\t\t\t// Support: Windows 8 Native Apps\n\t\t\t// The type and name attributes are restricted during .innerHTML assignment\n\t\t\tvar input = document.createElement(\"input\");\n\t\t\tinput.setAttribute( \"type\", \"hidden\" );\n\t\t\tel.appendChild( input ).setAttribute( \"name\", \"D\" );\n\n\t\t\t// Support: IE8\n\t\t\t// Enforce case-sensitivity of name attribute\n\t\t\tif ( el.querySelectorAll(\"[name=d]\").length ) {\n\t\t\t\trbuggyQSA.push( \"name\" + whitespace + \"*[*^$|!~]?=\" );\n\t\t\t}\n\n\t\t\t// FF 3.5 - :enabled/:disabled and hidden elements (hidden elements are still enabled)\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( el.querySelectorAll(\":enabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Support: IE9-11+\n\t\t\t// IE's :disabled selector does not pick up the children of disabled fieldsets\n\t\t\tdocElem.appendChild( el ).disabled = true;\n\t\t\tif ( el.querySelectorAll(\":disabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Opera 10-11 does not throw on post-comma invalid pseudos\n\t\t\tel.querySelectorAll(\"*,:x\");\n\t\t\trbuggyQSA.push(\",.*:\");\n\t\t});\n\t}\n\n\tif ( (support.matchesSelector = rnative.test( (matches = docElem.matches ||\n\t\tdocElem.webkitMatchesSelector ||\n\t\tdocElem.mozMatchesSelector ||\n\t\tdocElem.oMatchesSelector ||\n\t\tdocElem.msMatchesSelector) )) ) {\n\n\t\tassert(function( el ) {\n\t\t\t// Check to see if it's possible to do matchesSelector\n\t\t\t// on a disconnected node (IE 9)\n\t\t\tsupport.disconnectedMatch = matches.call( el, \"*\" );\n\n\t\t\t// This should fail with an exception\n\t\t\t// Gecko does not error, returns false instead\n\t\t\tmatches.call( el, \"[s!='']:x\" );\n\t\t\trbuggyMatches.push( \"!=\", pseudos );\n\t\t});\n\t}\n\n\trbuggyQSA = rbuggyQSA.length && new RegExp( rbuggyQSA.join(\"|\") );\n\trbuggyMatches = rbuggyMatches.length && new RegExp( rbuggyMatches.join(\"|\") );\n\n\t/* Contains\n\t---------------------------------------------------------------------- */\n\thasCompare = rnative.test( docElem.compareDocumentPosition );\n\n\t// Element contains another\n\t// Purposefully self-exclusive\n\t// As in, an element does not contain itself\n\tcontains = hasCompare || rnative.test( docElem.contains ) ?\n\t\tfunction( a, b ) {\n\t\t\tvar adown = a.nodeType === 9 ? a.documentElement : a,\n\t\t\t\tbup = b && b.parentNode;\n\t\t\treturn a === bup || !!( bup && bup.nodeType === 1 && (\n\t\t\t\tadown.contains ?\n\t\t\t\t\tadown.contains( bup ) :\n\t\t\t\t\ta.compareDocumentPosition && a.compareDocumentPosition( bup ) & 16\n\t\t\t));\n\t\t} :\n\t\tfunction( a, b ) {\n\t\t\tif ( b ) {\n\t\t\t\twhile ( (b = b.parentNode) ) {\n\t\t\t\t\tif ( b === a ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n\n\t/* Sorting\n\t---------------------------------------------------------------------- */\n\n\t// Document order sorting\n\tsortOrder = hasCompare ?\n\tfunction( a, b ) {\n\n\t\t// Flag for duplicate removal\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\t// Sort on method existence if only one input has compareDocumentPosition\n\t\tvar compare = !a.compareDocumentPosition - !b.compareDocumentPosition;\n\t\tif ( compare ) {\n\t\t\treturn compare;\n\t\t}\n\n\t\t// Calculate position if both inputs belong to the same document\n\t\tcompare = ( a.ownerDocument || a ) === ( b.ownerDocument || b ) ?\n\t\t\ta.compareDocumentPosition( b ) :\n\n\t\t\t// Otherwise we know they are disconnected\n\t\t\t1;\n\n\t\t// Disconnected nodes\n\t\tif ( compare & 1 ||\n\t\t\t(!support.sortDetached && b.compareDocumentPosition( a ) === compare) ) {\n\n\t\t\t// Choose the first element that is related to our preferred document\n\t\t\tif ( a === document || a.ownerDocument === preferredDoc && contains(preferredDoc, a) ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t\tif ( b === document || b.ownerDocument === preferredDoc && contains(preferredDoc, b) ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\t// Maintain original order\n\t\t\treturn sortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\t\t}\n\n\t\treturn compare & 4 ? -1 : 1;\n\t} :\n\tfunction( a, b ) {\n\t\t// Exit early if the nodes are identical\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\taup = a.parentNode,\n\t\t\tbup = b.parentNode,\n\t\t\tap = [ a ],\n\t\t\tbp = [ b ];\n\n\t\t// Parentless nodes are either documents or disconnected\n\t\tif ( !aup || !bup ) {\n\t\t\treturn a === document ? -1 :\n\t\t\t\tb === document ? 1 :\n\t\t\t\taup ? -1 :\n\t\t\t\tbup ? 1 :\n\t\t\t\tsortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\n\t\t// If the nodes are siblings, we can do a quick check\n\t\t} else if ( aup === bup ) {\n\t\t\treturn siblingCheck( a, b );\n\t\t}\n\n\t\t// Otherwise we need full lists of their ancestors for comparison\n\t\tcur = a;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tap.unshift( cur );\n\t\t}\n\t\tcur = b;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tbp.unshift( cur );\n\t\t}\n\n\t\t// Walk down the tree looking for a discrepancy\n\t\twhile ( ap[i] === bp[i] ) {\n\t\t\ti++;\n\t\t}\n\n\t\treturn i ?\n\t\t\t// Do a sibling check if the nodes have a common ancestor\n\t\t\tsiblingCheck( ap[i], bp[i] ) :\n\n\t\t\t// Otherwise nodes in our document sort first\n\t\t\tap[i] === preferredDoc ? -1 :\n\t\t\tbp[i] === preferredDoc ? 1 :\n\t\t\t0;\n\t};\n\n\treturn document;\n};\n\nSizzle.matches = function( expr, elements ) {\n\treturn Sizzle( expr, null, null, elements );\n};\n\nSizzle.matchesSelector = function( elem, expr ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tif ( support.matchesSelector && documentIsHTML &&\n\t\t!nonnativeSelectorCache[ expr + \" \" ] &&\n\t\t( !rbuggyMatches || !rbuggyMatches.test( expr ) ) &&\n\t\t( !rbuggyQSA     || !rbuggyQSA.test( expr ) ) ) {\n\n\t\ttry {\n\t\t\tvar ret = matches.call( elem, expr );\n\n\t\t\t// IE 9's matchesSelector returns false on disconnected nodes\n\t\t\tif ( ret || support.disconnectedMatch ||\n\t\t\t\t\t// As well, disconnected nodes are said to be in a document\n\t\t\t\t\t// fragment in IE 9\n\t\t\t\t\telem.document && elem.document.nodeType !== 11 ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\t\t} catch (e) {\n\t\t\tnonnativeSelectorCache( expr, true );\n\t\t}\n\t}\n\n\treturn Sizzle( expr, document, null, [ elem ] ).length > 0;\n};\n\nSizzle.contains = function( context, elem ) {\n\t// Set document vars if needed\n\tif ( ( context.ownerDocument || context ) !== document ) {\n\t\tsetDocument( context );\n\t}\n\treturn contains( context, elem );\n};\n\nSizzle.attr = function( elem, name ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tvar fn = Expr.attrHandle[ name.toLowerCase() ],\n\t\t// Don't get fooled by Object.prototype properties (jQuery #13807)\n\t\tval = fn && hasOwn.call( Expr.attrHandle, name.toLowerCase() ) ?\n\t\t\tfn( elem, name, !documentIsHTML ) :\n\t\t\tundefined;\n\n\treturn val !== undefined ?\n\t\tval :\n\t\tsupport.attributes || !documentIsHTML ?\n\t\t\telem.getAttribute( name ) :\n\t\t\t(val = elem.getAttributeNode(name)) && val.specified ?\n\t\t\t\tval.value :\n\t\t\t\tnull;\n};\n\nSizzle.escape = function( sel ) {\n\treturn (sel + \"\").replace( rcssescape, fcssescape );\n};\n\nSizzle.error = function( msg ) {\n\tthrow new Error( \"Syntax error, unrecognized expression: \" + msg );\n};\n\n/**\n * Document sorting and removing duplicates\n * @param {ArrayLike} results\n */\nSizzle.uniqueSort = function( results ) {\n\tvar elem,\n\t\tduplicates = [],\n\t\tj = 0,\n\t\ti = 0;\n\n\t// Unless we *know* we can detect duplicates, assume their presence\n\thasDuplicate = !support.detectDuplicates;\n\tsortInput = !support.sortStable && results.slice( 0 );\n\tresults.sort( sortOrder );\n\n\tif ( hasDuplicate ) {\n\t\twhile ( (elem = results[i++]) ) {\n\t\t\tif ( elem === results[ i ] ) {\n\t\t\t\tj = duplicates.push( i );\n\t\t\t}\n\t\t}\n\t\twhile ( j-- ) {\n\t\t\tresults.splice( duplicates[ j ], 1 );\n\t\t}\n\t}\n\n\t// Clear input after sorting to release objects\n\t// See https://github.com/jquery/sizzle/pull/225\n\tsortInput = null;\n\n\treturn results;\n};\n\n/**\n * Utility function for retrieving the text value of an array of DOM nodes\n * @param {Array|Element} elem\n */\ngetText = Sizzle.getText = function( elem ) {\n\tvar node,\n\t\tret = \"\",\n\t\ti = 0,\n\t\tnodeType = elem.nodeType;\n\n\tif ( !nodeType ) {\n\t\t// If no nodeType, this is expected to be an array\n\t\twhile ( (node = elem[i++]) ) {\n\t\t\t// Do not traverse comment nodes\n\t\t\tret += getText( node );\n\t\t}\n\t} else if ( nodeType === 1 || nodeType === 9 || nodeType === 11 ) {\n\t\t// Use textContent for elements\n\t\t// innerText usage removed for consistency of new lines (jQuery #11153)\n\t\tif ( typeof elem.textContent === \"string\" ) {\n\t\t\treturn elem.textContent;\n\t\t} else {\n\t\t\t// Traverse its children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tret += getText( elem );\n\t\t\t}\n\t\t}\n\t} else if ( nodeType === 3 || nodeType === 4 ) {\n\t\treturn elem.nodeValue;\n\t}\n\t// Do not include comment or processing instruction nodes\n\n\treturn ret;\n};\n\nExpr = Sizzle.selectors = {\n\n\t// Can be adjusted by the user\n\tcacheLength: 50,\n\n\tcreatePseudo: markFunction,\n\n\tmatch: matchExpr,\n\n\tattrHandle: {},\n\n\tfind: {},\n\n\trelative: {\n\t\t\">\": { dir: \"parentNode\", first: true },\n\t\t\" \": { dir: \"parentNode\" },\n\t\t\"+\": { dir: \"previousSibling\", first: true },\n\t\t\"~\": { dir: \"previousSibling\" }\n\t},\n\n\tpreFilter: {\n\t\t\"ATTR\": function( match ) {\n\t\t\tmatch[1] = match[1].replace( runescape, funescape );\n\n\t\t\t// Move the given value to match[3] whether quoted or unquoted\n\t\t\tmatch[3] = ( match[3] || match[4] || match[5] || \"\" ).replace( runescape, funescape );\n\n\t\t\tif ( match[2] === \"~=\" ) {\n\t\t\t\tmatch[3] = \" \" + match[3] + \" \";\n\t\t\t}\n\n\t\t\treturn match.slice( 0, 4 );\n\t\t},\n\n\t\t\"CHILD\": function( match ) {\n\t\t\t/* matches from matchExpr[\"CHILD\"]\n\t\t\t\t1 type (only|nth|...)\n\t\t\t\t2 what (child|of-type)\n\t\t\t\t3 argument (even|odd|\\d*|\\d*n([+-]\\d+)?|...)\n\t\t\t\t4 xn-component of xn+y argument ([+-]?\\d*n|)\n\t\t\t\t5 sign of xn-component\n\t\t\t\t6 x of xn-component\n\t\t\t\t7 sign of y-component\n\t\t\t\t8 y of y-component\n\t\t\t*/\n\t\t\tmatch[1] = match[1].toLowerCase();\n\n\t\t\tif ( match[1].slice( 0, 3 ) === \"nth\" ) {\n\t\t\t\t// nth-* requires argument\n\t\t\t\tif ( !match[3] ) {\n\t\t\t\t\tSizzle.error( match[0] );\n\t\t\t\t}\n\n\t\t\t\t// numeric x and y parameters for Expr.filter.CHILD\n\t\t\t\t// remember that false/true cast respectively to 0/1\n\t\t\t\tmatch[4] = +( match[4] ? match[5] + (match[6] || 1) : 2 * ( match[3] === \"even\" || match[3] === \"odd\" ) );\n\t\t\t\tmatch[5] = +( ( match[7] + match[8] ) || match[3] === \"odd\" );\n\n\t\t\t// other types prohibit arguments\n\t\t\t} else if ( match[3] ) {\n\t\t\t\tSizzle.error( match[0] );\n\t\t\t}\n\n\t\t\treturn match;\n\t\t},\n\n\t\t\"PSEUDO\": function( match ) {\n\t\t\tvar excess,\n\t\t\t\tunquoted = !match[6] && match[2];\n\n\t\t\tif ( matchExpr[\"CHILD\"].test( match[0] ) ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\t// Accept quoted arguments as-is\n\t\t\tif ( match[3] ) {\n\t\t\t\tmatch[2] = match[4] || match[5] || \"\";\n\n\t\t\t// Strip excess characters from unquoted arguments\n\t\t\t} else if ( unquoted && rpseudo.test( unquoted ) &&\n\t\t\t\t// Get excess from tokenize (recursively)\n\t\t\t\t(excess = tokenize( unquoted, true )) &&\n\t\t\t\t// advance to the next closing parenthesis\n\t\t\t\t(excess = unquoted.indexOf( \")\", unquoted.length - excess ) - unquoted.length) ) {\n\n\t\t\t\t// excess is a negative index\n\t\t\t\tmatch[0] = match[0].slice( 0, excess );\n\t\t\t\tmatch[2] = unquoted.slice( 0, excess );\n\t\t\t}\n\n\t\t\t// Return only captures needed by the pseudo filter method (type and argument)\n\t\t\treturn match.slice( 0, 3 );\n\t\t}\n\t},\n\n\tfilter: {\n\n\t\t\"TAG\": function( nodeNameSelector ) {\n\t\t\tvar nodeName = nodeNameSelector.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn nodeNameSelector === \"*\" ?\n\t\t\t\tfunction() { return true; } :\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn elem.nodeName && elem.nodeName.toLowerCase() === nodeName;\n\t\t\t\t};\n\t\t},\n\n\t\t\"CLASS\": function( className ) {\n\t\t\tvar pattern = classCache[ className + \" \" ];\n\n\t\t\treturn pattern ||\n\t\t\t\t(pattern = new RegExp( \"(^|\" + whitespace + \")\" + className + \"(\" + whitespace + \"|$)\" )) &&\n\t\t\t\tclassCache( className, function( elem ) {\n\t\t\t\t\treturn pattern.test( typeof elem.className === \"string\" && elem.className || typeof elem.getAttribute !== \"undefined\" && elem.getAttribute(\"class\") || \"\" );\n\t\t\t\t});\n\t\t},\n\n\t\t\"ATTR\": function( name, operator, check ) {\n\t\t\treturn function( elem ) {\n\t\t\t\tvar result = Sizzle.attr( elem, name );\n\n\t\t\t\tif ( result == null ) {\n\t\t\t\t\treturn operator === \"!=\";\n\t\t\t\t}\n\t\t\t\tif ( !operator ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\n\t\t\t\tresult += \"\";\n\n\t\t\t\treturn operator === \"=\" ? result === check :\n\t\t\t\t\toperator === \"!=\" ? result !== check :\n\t\t\t\t\toperator === \"^=\" ? check && result.indexOf( check ) === 0 :\n\t\t\t\t\toperator === \"*=\" ? check && result.indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"$=\" ? check && result.slice( -check.length ) === check :\n\t\t\t\t\toperator === \"~=\" ? ( \" \" + result.replace( rwhitespace, \" \" ) + \" \" ).indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"|=\" ? result === check || result.slice( 0, check.length + 1 ) === check + \"-\" :\n\t\t\t\t\tfalse;\n\t\t\t};\n\t\t},\n\n\t\t\"CHILD\": function( type, what, argument, first, last ) {\n\t\t\tvar simple = type.slice( 0, 3 ) !== \"nth\",\n\t\t\t\tforward = type.slice( -4 ) !== \"last\",\n\t\t\t\tofType = what === \"of-type\";\n\n\t\t\treturn first === 1 && last === 0 ?\n\n\t\t\t\t// Shortcut for :nth-*(n)\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn !!elem.parentNode;\n\t\t\t\t} :\n\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tvar cache, uniqueCache, outerCache, node, nodeIndex, start,\n\t\t\t\t\t\tdir = simple !== forward ? \"nextSibling\" : \"previousSibling\",\n\t\t\t\t\t\tparent = elem.parentNode,\n\t\t\t\t\t\tname = ofType && elem.nodeName.toLowerCase(),\n\t\t\t\t\t\tuseCache = !xml && !ofType,\n\t\t\t\t\t\tdiff = false;\n\n\t\t\t\t\tif ( parent ) {\n\n\t\t\t\t\t\t// :(first|last|only)-(child|of-type)\n\t\t\t\t\t\tif ( simple ) {\n\t\t\t\t\t\t\twhile ( dir ) {\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\twhile ( (node = node[ dir ]) ) {\n\t\t\t\t\t\t\t\t\tif ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) {\n\n\t\t\t\t\t\t\t\t\t\treturn false;\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t// Reverse direction for :only-* (if we haven't yet done so)\n\t\t\t\t\t\t\t\tstart = dir = type === \"only\" && !start && \"nextSibling\";\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\tstart = [ forward ? parent.firstChild : parent.lastChild ];\n\n\t\t\t\t\t\t// non-xml :nth-child(...) stores cache data on `parent`\n\t\t\t\t\t\tif ( forward && useCache ) {\n\n\t\t\t\t\t\t\t// Seek `elem` from a previously-cached index\n\n\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\tnode = parent;\n\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\tdiff = nodeIndex && cache[ 2 ];\n\t\t\t\t\t\t\tnode = nodeIndex && parent.childNodes[ nodeIndex ];\n\n\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\n\t\t\t\t\t\t\t\t// Fallback to seeking `elem` from the start\n\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t// When found, cache indexes on `parent` and break\n\t\t\t\t\t\t\t\tif ( node.nodeType === 1 && ++diff && node === elem ) {\n\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, nodeIndex, diff ];\n\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Use previously-cached element index if available\n\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\t\tdiff = nodeIndex;\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t// xml :nth-child(...)\n\t\t\t\t\t\t\t// or :nth-last-child(...) or :nth(-last)?-of-type(...)\n\t\t\t\t\t\t\tif ( diff === false ) {\n\t\t\t\t\t\t\t\t// Use the same loop as above to seek `elem` from the start\n\t\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\t\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t\tif ( ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) &&\n\t\t\t\t\t\t\t\t\t\t++diff ) {\n\n\t\t\t\t\t\t\t\t\t\t// Cache the index of each encountered element\n\t\t\t\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, diff ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\tif ( node === elem ) {\n\t\t\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Incorporate the offset, then check against cycle size\n\t\t\t\t\t\tdiff -= last;\n\t\t\t\t\t\treturn diff === first || ( diff % first === 0 && diff / first >= 0 );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t},\n\n\t\t\"PSEUDO\": function( pseudo, argument ) {\n\t\t\t// pseudo-class names are case-insensitive\n\t\t\t// http://www.w3.org/TR/selectors/#pseudo-classes\n\t\t\t// Prioritize by case sensitivity in case custom pseudos are added with uppercase letters\n\t\t\t// Remember that setFilters inherits from pseudos\n\t\t\tvar args,\n\t\t\t\tfn = Expr.pseudos[ pseudo ] || Expr.setFilters[ pseudo.toLowerCase() ] ||\n\t\t\t\t\tSizzle.error( \"unsupported pseudo: \" + pseudo );\n\n\t\t\t// The user may use createPseudo to indicate that\n\t\t\t// arguments are needed to create the filter function\n\t\t\t// just as Sizzle does\n\t\t\tif ( fn[ expando ] ) {\n\t\t\t\treturn fn( argument );\n\t\t\t}\n\n\t\t\t// But maintain support for old signatures\n\t\t\tif ( fn.length > 1 ) {\n\t\t\t\targs = [ pseudo, pseudo, \"\", argument ];\n\t\t\t\treturn Expr.setFilters.hasOwnProperty( pseudo.toLowerCase() ) ?\n\t\t\t\t\tmarkFunction(function( seed, matches ) {\n\t\t\t\t\t\tvar idx,\n\t\t\t\t\t\t\tmatched = fn( seed, argument ),\n\t\t\t\t\t\t\ti = matched.length;\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tidx = indexOf( seed, matched[i] );\n\t\t\t\t\t\t\tseed[ idx ] = !( matches[ idx ] = matched[i] );\n\t\t\t\t\t\t}\n\t\t\t\t\t}) :\n\t\t\t\t\tfunction( elem ) {\n\t\t\t\t\t\treturn fn( elem, 0, args );\n\t\t\t\t\t};\n\t\t\t}\n\n\t\t\treturn fn;\n\t\t}\n\t},\n\n\tpseudos: {\n\t\t// Potentially complex pseudos\n\t\t\"not\": markFunction(function( selector ) {\n\t\t\t// Trim the selector passed to compile\n\t\t\t// to avoid treating leading and trailing\n\t\t\t// spaces as combinators\n\t\t\tvar input = [],\n\t\t\t\tresults = [],\n\t\t\t\tmatcher = compile( selector.replace( rtrim, \"$1\" ) );\n\n\t\t\treturn matcher[ expando ] ?\n\t\t\t\tmarkFunction(function( seed, matches, context, xml ) {\n\t\t\t\t\tvar elem,\n\t\t\t\t\t\tunmatched = matcher( seed, null, xml, [] ),\n\t\t\t\t\t\ti = seed.length;\n\n\t\t\t\t\t// Match elements unmatched by `matcher`\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = unmatched[i]) ) {\n\t\t\t\t\t\t\tseed[i] = !(matches[i] = elem);\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}) :\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tinput[0] = elem;\n\t\t\t\t\tmatcher( input, null, xml, results );\n\t\t\t\t\t// Don't keep the element (issue #299)\n\t\t\t\t\tinput[0] = null;\n\t\t\t\t\treturn !results.pop();\n\t\t\t\t};\n\t\t}),\n\n\t\t\"has\": markFunction(function( selector ) {\n\t\t\treturn function( elem ) {\n\t\t\t\treturn Sizzle( selector, elem ).length > 0;\n\t\t\t};\n\t\t}),\n\n\t\t\"contains\": markFunction(function( text ) {\n\t\t\ttext = text.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn ( elem.textContent || getText( elem ) ).indexOf( text ) > -1;\n\t\t\t};\n\t\t}),\n\n\t\t// \"Whether an element is represented by a :lang() selector\n\t\t// is based solely on the element's language value\n\t\t// being equal to the identifier C,\n\t\t// or beginning with the identifier C immediately followed by \"-\".\n\t\t// The matching of C against the element's language value is performed case-insensitively.\n\t\t// The identifier C does not have to be a valid language name.\"\n\t\t// http://www.w3.org/TR/selectors/#lang-pseudo\n\t\t\"lang\": markFunction( function( lang ) {\n\t\t\t// lang value must be a valid identifier\n\t\t\tif ( !ridentifier.test(lang || \"\") ) {\n\t\t\t\tSizzle.error( \"unsupported lang: \" + lang );\n\t\t\t}\n\t\t\tlang = lang.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn function( elem ) {\n\t\t\t\tvar elemLang;\n\t\t\t\tdo {\n\t\t\t\t\tif ( (elemLang = documentIsHTML ?\n\t\t\t\t\t\telem.lang :\n\t\t\t\t\t\telem.getAttribute(\"xml:lang\") || elem.getAttribute(\"lang\")) ) {\n\n\t\t\t\t\t\telemLang = elemLang.toLowerCase();\n\t\t\t\t\t\treturn elemLang === lang || elemLang.indexOf( lang + \"-\" ) === 0;\n\t\t\t\t\t}\n\t\t\t\t} while ( (elem = elem.parentNode) && elem.nodeType === 1 );\n\t\t\t\treturn false;\n\t\t\t};\n\t\t}),\n\n\t\t// Miscellaneous\n\t\t\"target\": function( elem ) {\n\t\t\tvar hash = window.location && window.location.hash;\n\t\t\treturn hash && hash.slice( 1 ) === elem.id;\n\t\t},\n\n\t\t\"root\": function( elem ) {\n\t\t\treturn elem === docElem;\n\t\t},\n\n\t\t\"focus\": function( elem ) {\n\t\t\treturn elem === document.activeElement && (!document.hasFocus || document.hasFocus()) && !!(elem.type || elem.href || ~elem.tabIndex);\n\t\t},\n\n\t\t// Boolean properties\n\t\t\"enabled\": createDisabledPseudo( false ),\n\t\t\"disabled\": createDisabledPseudo( true ),\n\n\t\t\"checked\": function( elem ) {\n\t\t\t// In CSS3, :checked should return both checked and selected elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\tvar nodeName = elem.nodeName.toLowerCase();\n\t\t\treturn (nodeName === \"input\" && !!elem.checked) || (nodeName === \"option\" && !!elem.selected);\n\t\t},\n\n\t\t\"selected\": function( elem ) {\n\t\t\t// Accessing this property makes selected-by-default\n\t\t\t// options in Safari work properly\n\t\t\tif ( elem.parentNode ) {\n\t\t\t\telem.parentNode.selectedIndex;\n\t\t\t}\n\n\t\t\treturn elem.selected === true;\n\t\t},\n\n\t\t// Contents\n\t\t\"empty\": function( elem ) {\n\t\t\t// http://www.w3.org/TR/selectors/#empty-pseudo\n\t\t\t// :empty is negated by element (1) or content nodes (text: 3; cdata: 4; entity ref: 5),\n\t\t\t//   but not by others (comment: 8; processing instruction: 7; etc.)\n\t\t\t// nodeType < 6 works because attributes (2) do not appear as children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tif ( elem.nodeType < 6 ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t},\n\n\t\t\"parent\": function( elem ) {\n\t\t\treturn !Expr.pseudos[\"empty\"]( elem );\n\t\t},\n\n\t\t// Element/input types\n\t\t\"header\": function( elem ) {\n\t\t\treturn rheader.test( elem.nodeName );\n\t\t},\n\n\t\t\"input\": function( elem ) {\n\t\t\treturn rinputs.test( elem.nodeName );\n\t\t},\n\n\t\t\"button\": function( elem ) {\n\t\t\tvar name = elem.nodeName.toLowerCase();\n\t\t\treturn name === \"input\" && elem.type === \"button\" || name === \"button\";\n\t\t},\n\n\t\t\"text\": function( elem ) {\n\t\t\tvar attr;\n\t\t\treturn elem.nodeName.toLowerCase() === \"input\" &&\n\t\t\t\telem.type === \"text\" &&\n\n\t\t\t\t// Support: IE<8\n\t\t\t\t// New HTML5 attribute values (e.g., \"search\") appear with elem.type === \"text\"\n\t\t\t\t( (attr = elem.getAttribute(\"type\")) == null || attr.toLowerCase() === \"text\" );\n\t\t},\n\n\t\t// Position-in-collection\n\t\t\"first\": createPositionalPseudo(function() {\n\t\t\treturn [ 0 ];\n\t\t}),\n\n\t\t\"last\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\treturn [ length - 1 ];\n\t\t}),\n\n\t\t\"eq\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\treturn [ argument < 0 ? argument + length : argument ];\n\t\t}),\n\n\t\t\"even\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"odd\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 1;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"lt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ?\n\t\t\t\targument + length :\n\t\t\t\targument > length ?\n\t\t\t\t\tlength :\n\t\t\t\t\targument;\n\t\t\tfor ( ; --i >= 0; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"gt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ? argument + length : argument;\n\t\t\tfor ( ; ++i < length; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t})\n\t}\n};\n\nExpr.pseudos[\"nth\"] = Expr.pseudos[\"eq\"];\n\n// Add button/input type pseudos\nfor ( i in { radio: true, checkbox: true, file: true, password: true, image: true } ) {\n\tExpr.pseudos[ i ] = createInputPseudo( i );\n}\nfor ( i in { submit: true, reset: true } ) {\n\tExpr.pseudos[ i ] = createButtonPseudo( i );\n}\n\n// Easy API for creating new setFilters\nfunction setFilters() {}\nsetFilters.prototype = Expr.filters = Expr.pseudos;\nExpr.setFilters = new setFilters();\n\ntokenize = Sizzle.tokenize = function( selector, parseOnly ) {\n\tvar matched, match, tokens, type,\n\t\tsoFar, groups, preFilters,\n\t\tcached = tokenCache[ selector + \" \" ];\n\n\tif ( cached ) {\n\t\treturn parseOnly ? 0 : cached.slice( 0 );\n\t}\n\n\tsoFar = selector;\n\tgroups = [];\n\tpreFilters = Expr.preFilter;\n\n\twhile ( soFar ) {\n\n\t\t// Comma and first run\n\t\tif ( !matched || (match = rcomma.exec( soFar )) ) {\n\t\t\tif ( match ) {\n\t\t\t\t// Don't consume trailing commas as valid\n\t\t\t\tsoFar = soFar.slice( match[0].length ) || soFar;\n\t\t\t}\n\t\t\tgroups.push( (tokens = []) );\n\t\t}\n\n\t\tmatched = false;\n\n\t\t// Combinators\n\t\tif ( (match = rcombinators.exec( soFar )) ) {\n\t\t\tmatched = match.shift();\n\t\t\ttokens.push({\n\t\t\t\tvalue: matched,\n\t\t\t\t// Cast descendant combinators to space\n\t\t\t\ttype: match[0].replace( rtrim, \" \" )\n\t\t\t});\n\t\t\tsoFar = soFar.slice( matched.length );\n\t\t}\n\n\t\t// Filters\n\t\tfor ( type in Expr.filter ) {\n\t\t\tif ( (match = matchExpr[ type ].exec( soFar )) && (!preFilters[ type ] ||\n\t\t\t\t(match = preFilters[ type ]( match ))) ) {\n\t\t\t\tmatched = match.shift();\n\t\t\t\ttokens.push({\n\t\t\t\t\tvalue: matched,\n\t\t\t\t\ttype: type,\n\t\t\t\t\tmatches: match\n\t\t\t\t});\n\t\t\t\tsoFar = soFar.slice( matched.length );\n\t\t\t}\n\t\t}\n\n\t\tif ( !matched ) {\n\t\t\tbreak;\n\t\t}\n\t}\n\n\t// Return the length of the invalid excess\n\t// if we're just parsing\n\t// Otherwise, throw an error or return tokens\n\treturn parseOnly ?\n\t\tsoFar.length :\n\t\tsoFar ?\n\t\t\tSizzle.error( selector ) :\n\t\t\t// Cache the tokens\n\t\t\ttokenCache( selector, groups ).slice( 0 );\n};\n\nfunction toSelector( tokens ) {\n\tvar i = 0,\n\t\tlen = tokens.length,\n\t\tselector = \"\";\n\tfor ( ; i < len; i++ ) {\n\t\tselector += tokens[i].value;\n\t}\n\treturn selector;\n}\n\nfunction addCombinator( matcher, combinator, base ) {\n\tvar dir = combinator.dir,\n\t\tskip = combinator.next,\n\t\tkey = skip || dir,\n\t\tcheckNonElements = base && key === \"parentNode\",\n\t\tdoneName = done++;\n\n\treturn combinator.first ?\n\t\t// Check against closest ancestor/preceding element\n\t\tfunction( elem, context, xml ) {\n\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\treturn matcher( elem, context, xml );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t} :\n\n\t\t// Check against all ancestor/preceding elements\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar oldCache, uniqueCache, outerCache,\n\t\t\t\tnewCache = [ dirruns, doneName ];\n\n\t\t\t// We can't set arbitrary data on XML nodes, so they don't benefit from combinator caching\n\t\t\tif ( xml ) {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\tif ( matcher( elem, context, xml ) ) {\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\touterCache = elem[ expando ] || (elem[ expando ] = {});\n\n\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\tuniqueCache = outerCache[ elem.uniqueID ] || (outerCache[ elem.uniqueID ] = {});\n\n\t\t\t\t\t\tif ( skip && skip === elem.nodeName.toLowerCase() ) {\n\t\t\t\t\t\t\telem = elem[ dir ] || elem;\n\t\t\t\t\t\t} else if ( (oldCache = uniqueCache[ key ]) &&\n\t\t\t\t\t\t\toldCache[ 0 ] === dirruns && oldCache[ 1 ] === doneName ) {\n\n\t\t\t\t\t\t\t// Assign to newCache so results back-propagate to previous elements\n\t\t\t\t\t\t\treturn (newCache[ 2 ] = oldCache[ 2 ]);\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Reuse newcache so results back-propagate to previous elements\n\t\t\t\t\t\t\tuniqueCache[ key ] = newCache;\n\n\t\t\t\t\t\t\t// A match means we're done; a fail means we have to keep checking\n\t\t\t\t\t\t\tif ( (newCache[ 2 ] = matcher( elem, context, xml )) ) {\n\t\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n}\n\nfunction elementMatcher( matchers ) {\n\treturn matchers.length > 1 ?\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar i = matchers.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( !matchers[i]( elem, context, xml ) ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t} :\n\t\tmatchers[0];\n}\n\nfunction multipleContexts( selector, contexts, results ) {\n\tvar i = 0,\n\t\tlen = contexts.length;\n\tfor ( ; i < len; i++ ) {\n\t\tSizzle( selector, contexts[i], results );\n\t}\n\treturn results;\n}\n\nfunction condense( unmatched, map, filter, context, xml ) {\n\tvar elem,\n\t\tnewUnmatched = [],\n\t\ti = 0,\n\t\tlen = unmatched.length,\n\t\tmapped = map != null;\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (elem = unmatched[i]) ) {\n\t\t\tif ( !filter || filter( elem, context, xml ) ) {\n\t\t\t\tnewUnmatched.push( elem );\n\t\t\t\tif ( mapped ) {\n\t\t\t\t\tmap.push( i );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn newUnmatched;\n}\n\nfunction setMatcher( preFilter, selector, matcher, postFilter, postFinder, postSelector ) {\n\tif ( postFilter && !postFilter[ expando ] ) {\n\t\tpostFilter = setMatcher( postFilter );\n\t}\n\tif ( postFinder && !postFinder[ expando ] ) {\n\t\tpostFinder = setMatcher( postFinder, postSelector );\n\t}\n\treturn markFunction(function( seed, results, context, xml ) {\n\t\tvar temp, i, elem,\n\t\t\tpreMap = [],\n\t\t\tpostMap = [],\n\t\t\tpreexisting = results.length,\n\n\t\t\t// Get initial elements from seed or context\n\t\t\telems = seed || multipleContexts( selector || \"*\", context.nodeType ? [ context ] : context, [] ),\n\n\t\t\t// Prefilter to get matcher input, preserving a map for seed-results synchronization\n\t\t\tmatcherIn = preFilter && ( seed || !selector ) ?\n\t\t\t\tcondense( elems, preMap, preFilter, context, xml ) :\n\t\t\t\telems,\n\n\t\t\tmatcherOut = matcher ?\n\t\t\t\t// If we have a postFinder, or filtered seed, or non-seed postFilter or preexisting results,\n\t\t\t\tpostFinder || ( seed ? preFilter : preexisting || postFilter ) ?\n\n\t\t\t\t\t// ...intermediate processing is necessary\n\t\t\t\t\t[] :\n\n\t\t\t\t\t// ...otherwise use results directly\n\t\t\t\t\tresults :\n\t\t\t\tmatcherIn;\n\n\t\t// Find primary matches\n\t\tif ( matcher ) {\n\t\t\tmatcher( matcherIn, matcherOut, context, xml );\n\t\t}\n\n\t\t// Apply postFilter\n\t\tif ( postFilter ) {\n\t\t\ttemp = condense( matcherOut, postMap );\n\t\t\tpostFilter( temp, [], context, xml );\n\n\t\t\t// Un-match failing elements by moving them back to matcherIn\n\t\t\ti = temp.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( (elem = temp[i]) ) {\n\t\t\t\t\tmatcherOut[ postMap[i] ] = !(matcherIn[ postMap[i] ] = elem);\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\tif ( seed ) {\n\t\t\tif ( postFinder || preFilter ) {\n\t\t\t\tif ( postFinder ) {\n\t\t\t\t\t// Get the final matcherOut by condensing this intermediate into postFinder contexts\n\t\t\t\t\ttemp = [];\n\t\t\t\t\ti = matcherOut.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = matcherOut[i]) ) {\n\t\t\t\t\t\t\t// Restore matcherIn since elem is not yet a final match\n\t\t\t\t\t\t\ttemp.push( (matcherIn[i] = elem) );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tpostFinder( null, (matcherOut = []), temp, xml );\n\t\t\t\t}\n\n\t\t\t\t// Move matched elements from seed to results to keep them synchronized\n\t\t\t\ti = matcherOut.length;\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\tif ( (elem = matcherOut[i]) &&\n\t\t\t\t\t\t(temp = postFinder ? indexOf( seed, elem ) : preMap[i]) > -1 ) {\n\n\t\t\t\t\t\tseed[temp] = !(results[temp] = elem);\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Add elements to results, through postFinder if defined\n\t\t} else {\n\t\t\tmatcherOut = condense(\n\t\t\t\tmatcherOut === results ?\n\t\t\t\t\tmatcherOut.splice( preexisting, matcherOut.length ) :\n\t\t\t\t\tmatcherOut\n\t\t\t);\n\t\t\tif ( postFinder ) {\n\t\t\t\tpostFinder( null, results, matcherOut, xml );\n\t\t\t} else {\n\t\t\t\tpush.apply( results, matcherOut );\n\t\t\t}\n\t\t}\n\t});\n}\n\nfunction matcherFromTokens( tokens ) {\n\tvar checkContext, matcher, j,\n\t\tlen = tokens.length,\n\t\tleadingRelative = Expr.relative[ tokens[0].type ],\n\t\timplicitRelative = leadingRelative || Expr.relative[\" \"],\n\t\ti = leadingRelative ? 1 : 0,\n\n\t\t// The foundational matcher ensures that elements are reachable from top-level context(s)\n\t\tmatchContext = addCombinator( function( elem ) {\n\t\t\treturn elem === checkContext;\n\t\t}, implicitRelative, true ),\n\t\tmatchAnyContext = addCombinator( function( elem ) {\n\t\t\treturn indexOf( checkContext, elem ) > -1;\n\t\t}, implicitRelative, true ),\n\t\tmatchers = [ function( elem, context, xml ) {\n\t\t\tvar ret = ( !leadingRelative && ( xml || context !== outermostContext ) ) || (\n\t\t\t\t(checkContext = context).nodeType ?\n\t\t\t\t\tmatchContext( elem, context, xml ) :\n\t\t\t\t\tmatchAnyContext( elem, context, xml ) );\n\t\t\t// Avoid hanging onto element (issue #299)\n\t\t\tcheckContext = null;\n\t\t\treturn ret;\n\t\t} ];\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (matcher = Expr.relative[ tokens[i].type ]) ) {\n\t\t\tmatchers = [ addCombinator(elementMatcher( matchers ), matcher) ];\n\t\t} else {\n\t\t\tmatcher = Expr.filter[ tokens[i].type ].apply( null, tokens[i].matches );\n\n\t\t\t// Return special upon seeing a positional matcher\n\t\t\tif ( matcher[ expando ] ) {\n\t\t\t\t// Find the next relative operator (if any) for proper handling\n\t\t\t\tj = ++i;\n\t\t\t\tfor ( ; j < len; j++ ) {\n\t\t\t\t\tif ( Expr.relative[ tokens[j].type ] ) {\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn setMatcher(\n\t\t\t\t\ti > 1 && elementMatcher( matchers ),\n\t\t\t\t\ti > 1 && toSelector(\n\t\t\t\t\t\t// If the preceding token was a descendant combinator, insert an implicit any-element `*`\n\t\t\t\t\t\ttokens.slice( 0, i - 1 ).concat({ value: tokens[ i - 2 ].type === \" \" ? \"*\" : \"\" })\n\t\t\t\t\t).replace( rtrim, \"$1\" ),\n\t\t\t\t\tmatcher,\n\t\t\t\t\ti < j && matcherFromTokens( tokens.slice( i, j ) ),\n\t\t\t\t\tj < len && matcherFromTokens( (tokens = tokens.slice( j )) ),\n\t\t\t\t\tj < len && toSelector( tokens )\n\t\t\t\t);\n\t\t\t}\n\t\t\tmatchers.push( matcher );\n\t\t}\n\t}\n\n\treturn elementMatcher( matchers );\n}\n\nfunction matcherFromGroupMatchers( elementMatchers, setMatchers ) {\n\tvar bySet = setMatchers.length > 0,\n\t\tbyElement = elementMatchers.length > 0,\n\t\tsuperMatcher = function( seed, context, xml, results, outermost ) {\n\t\t\tvar elem, j, matcher,\n\t\t\t\tmatchedCount = 0,\n\t\t\t\ti = \"0\",\n\t\t\t\tunmatched = seed && [],\n\t\t\t\tsetMatched = [],\n\t\t\t\tcontextBackup = outermostContext,\n\t\t\t\t// We must always have either seed elements or outermost context\n\t\t\t\telems = seed || byElement && Expr.find[\"TAG\"]( \"*\", outermost ),\n\t\t\t\t// Use integer dirruns iff this is the outermost matcher\n\t\t\t\tdirrunsUnique = (dirruns += contextBackup == null ? 1 : Math.random() || 0.1),\n\t\t\t\tlen = elems.length;\n\n\t\t\tif ( outermost ) {\n\t\t\t\toutermostContext = context === document || context || outermost;\n\t\t\t}\n\n\t\t\t// Add elements passing elementMatchers directly to results\n\t\t\t// Support: IE<9, Safari\n\t\t\t// Tolerate NodeList properties (IE: \"length\"; Safari: <number>) matching elements by id\n\t\t\tfor ( ; i !== len && (elem = elems[i]) != null; i++ ) {\n\t\t\t\tif ( byElement && elem ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\tif ( !context && elem.ownerDocument !== document ) {\n\t\t\t\t\t\tsetDocument( elem );\n\t\t\t\t\t\txml = !documentIsHTML;\n\t\t\t\t\t}\n\t\t\t\t\twhile ( (matcher = elementMatchers[j++]) ) {\n\t\t\t\t\t\tif ( matcher( elem, context || document, xml) ) {\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( outermost ) {\n\t\t\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Track unmatched elements for set filters\n\t\t\t\tif ( bySet ) {\n\t\t\t\t\t// They will have gone through all possible matchers\n\t\t\t\t\tif ( (elem = !matcher && elem) ) {\n\t\t\t\t\t\tmatchedCount--;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Lengthen the array for every element, matched or not\n\t\t\t\t\tif ( seed ) {\n\t\t\t\t\t\tunmatched.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// `i` is now the count of elements visited above, and adding it to `matchedCount`\n\t\t\t// makes the latter nonnegative.\n\t\t\tmatchedCount += i;\n\n\t\t\t// Apply set filters to unmatched elements\n\t\t\t// NOTE: This can be skipped if there are no unmatched elements (i.e., `matchedCount`\n\t\t\t// equals `i`), unless we didn't visit _any_ elements in the above loop because we have\n\t\t\t// no element matchers and no seed.\n\t\t\t// Incrementing an initially-string \"0\" `i` allows `i` to remain a string only in that\n\t\t\t// case, which will result in a \"00\" `matchedCount` that differs from `i` but is also\n\t\t\t// numerically zero.\n\t\t\tif ( bySet && i !== matchedCount ) {\n\t\t\t\tj = 0;\n\t\t\t\twhile ( (matcher = setMatchers[j++]) ) {\n\t\t\t\t\tmatcher( unmatched, setMatched, context, xml );\n\t\t\t\t}\n\n\t\t\t\tif ( seed ) {\n\t\t\t\t\t// Reintegrate element matches to eliminate the need for sorting\n\t\t\t\t\tif ( matchedCount > 0 ) {\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tif ( !(unmatched[i] || setMatched[i]) ) {\n\t\t\t\t\t\t\t\tsetMatched[i] = pop.call( results );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Discard index placeholder values to get only actual matches\n\t\t\t\t\tsetMatched = condense( setMatched );\n\t\t\t\t}\n\n\t\t\t\t// Add matches to results\n\t\t\t\tpush.apply( results, setMatched );\n\n\t\t\t\t// Seedless set matches succeeding multiple successful matchers stipulate sorting\n\t\t\t\tif ( outermost && !seed && setMatched.length > 0 &&\n\t\t\t\t\t( matchedCount + setMatchers.length ) > 1 ) {\n\n\t\t\t\t\tSizzle.uniqueSort( results );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Override manipulation of globals by nested matchers\n\t\t\tif ( outermost ) {\n\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\toutermostContext = contextBackup;\n\t\t\t}\n\n\t\t\treturn unmatched;\n\t\t};\n\n\treturn bySet ?\n\t\tmarkFunction( superMatcher ) :\n\t\tsuperMatcher;\n}\n\ncompile = Sizzle.compile = function( selector, match /* Internal Use Only */ ) {\n\tvar i,\n\t\tsetMatchers = [],\n\t\telementMatchers = [],\n\t\tcached = compilerCache[ selector + \" \" ];\n\n\tif ( !cached ) {\n\t\t// Generate a function of recursive functions that can be used to check each element\n\t\tif ( !match ) {\n\t\t\tmatch = tokenize( selector );\n\t\t}\n\t\ti = match.length;\n\t\twhile ( i-- ) {\n\t\t\tcached = matcherFromTokens( match[i] );\n\t\t\tif ( cached[ expando ] ) {\n\t\t\t\tsetMatchers.push( cached );\n\t\t\t} else {\n\t\t\t\telementMatchers.push( cached );\n\t\t\t}\n\t\t}\n\n\t\t// Cache the compiled function\n\t\tcached = compilerCache( selector, matcherFromGroupMatchers( elementMatchers, setMatchers ) );\n\n\t\t// Save selector and tokenization\n\t\tcached.selector = selector;\n\t}\n\treturn cached;\n};\n\n/**\n * A low-level selection function that works with Sizzle's compiled\n *  selector functions\n * @param {String|Function} selector A selector or a pre-compiled\n *  selector function built with Sizzle.compile\n * @param {Element} context\n * @param {Array} [results]\n * @param {Array} [seed] A set of elements to match against\n */\nselect = Sizzle.select = function( selector, context, results, seed ) {\n\tvar i, tokens, token, type, find,\n\t\tcompiled = typeof selector === \"function\" && selector,\n\t\tmatch = !seed && tokenize( (selector = compiled.selector || selector) );\n\n\tresults = results || [];\n\n\t// Try to minimize operations if there is only one selector in the list and no seed\n\t// (the latter of which guarantees us context)\n\tif ( match.length === 1 ) {\n\n\t\t// Reduce context if the leading compound selector is an ID\n\t\ttokens = match[0] = match[0].slice( 0 );\n\t\tif ( tokens.length > 2 && (token = tokens[0]).type === \"ID\" &&\n\t\t\t\tcontext.nodeType === 9 && documentIsHTML && Expr.relative[ tokens[1].type ] ) {\n\n\t\t\tcontext = ( Expr.find[\"ID\"]( token.matches[0].replace(runescape, funescape), context ) || [] )[0];\n\t\t\tif ( !context ) {\n\t\t\t\treturn results;\n\n\t\t\t// Precompiled matchers will still verify ancestry, so step up a level\n\t\t\t} else if ( compiled ) {\n\t\t\t\tcontext = context.parentNode;\n\t\t\t}\n\n\t\t\tselector = selector.slice( tokens.shift().value.length );\n\t\t}\n\n\t\t// Fetch a seed set for right-to-left matching\n\t\ti = matchExpr[\"needsContext\"].test( selector ) ? 0 : tokens.length;\n\t\twhile ( i-- ) {\n\t\t\ttoken = tokens[i];\n\n\t\t\t// Abort if we hit a combinator\n\t\t\tif ( Expr.relative[ (type = token.type) ] ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tif ( (find = Expr.find[ type ]) ) {\n\t\t\t\t// Search, expanding context for leading sibling combinators\n\t\t\t\tif ( (seed = find(\n\t\t\t\t\ttoken.matches[0].replace( runescape, funescape ),\n\t\t\t\t\trsibling.test( tokens[0].type ) && testContext( context.parentNode ) || context\n\t\t\t\t)) ) {\n\n\t\t\t\t\t// If seed is empty or no tokens remain, we can return early\n\t\t\t\t\ttokens.splice( i, 1 );\n\t\t\t\t\tselector = seed.length && toSelector( tokens );\n\t\t\t\t\tif ( !selector ) {\n\t\t\t\t\t\tpush.apply( results, seed );\n\t\t\t\t\t\treturn results;\n\t\t\t\t\t}\n\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Compile and execute a filtering function if one is not provided\n\t// Provide `match` to avoid retokenization if we modified the selector above\n\t( compiled || compile( selector, match ) )(\n\t\tseed,\n\t\tcontext,\n\t\t!documentIsHTML,\n\t\tresults,\n\t\t!context || rsibling.test( selector ) && testContext( context.parentNode ) || context\n\t);\n\treturn results;\n};\n\n// One-time assignments\n\n// Sort stability\nsupport.sortStable = expando.split(\"\").sort( sortOrder ).join(\"\") === expando;\n\n// Support: Chrome 14-35+\n// Always assume duplicates if they aren't passed to the comparison function\nsupport.detectDuplicates = !!hasDuplicate;\n\n// Initialize against the default document\nsetDocument();\n\n// Support: Webkit<537.32 - Safari 6.0.3/Chrome 25 (fixed in Chrome 27)\n// Detached nodes confoundingly follow *each other*\nsupport.sortDetached = assert(function( el ) {\n\t// Should return 1, but returns 4 (following)\n\treturn el.compareDocumentPosition( document.createElement(\"fieldset\") ) & 1;\n});\n\n// Support: IE<8\n// Prevent attribute/property \"interpolation\"\n// https://msdn.microsoft.com/en-us/library/ms536429%28VS.85%29.aspx\nif ( !assert(function( el ) {\n\tel.innerHTML = \"<a href='#'></a>\";\n\treturn el.firstChild.getAttribute(\"href\") === \"#\" ;\n}) ) {\n\taddHandle( \"type|href|height|width\", function( elem, name, isXML ) {\n\t\tif ( !isXML ) {\n\t\t\treturn elem.getAttribute( name, name.toLowerCase() === \"type\" ? 1 : 2 );\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use defaultValue in place of getAttribute(\"value\")\nif ( !support.attributes || !assert(function( el ) {\n\tel.innerHTML = \"<input/>\";\n\tel.firstChild.setAttribute( \"value\", \"\" );\n\treturn el.firstChild.getAttribute( \"value\" ) === \"\";\n}) ) {\n\taddHandle( \"value\", function( elem, name, isXML ) {\n\t\tif ( !isXML && elem.nodeName.toLowerCase() === \"input\" ) {\n\t\t\treturn elem.defaultValue;\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use getAttributeNode to fetch booleans when getAttribute lies\nif ( !assert(function( el ) {\n\treturn el.getAttribute(\"disabled\") == null;\n}) ) {\n\taddHandle( booleans, function( elem, name, isXML ) {\n\t\tvar val;\n\t\tif ( !isXML ) {\n\t\t\treturn elem[ name ] === true ? name.toLowerCase() :\n\t\t\t\t\t(val = elem.getAttributeNode( name )) && val.specified ?\n\t\t\t\t\tval.value :\n\t\t\t\tnull;\n\t\t}\n\t});\n}\n\nreturn Sizzle;\n\n})( window );\n\n\n\njQuery.find = Sizzle;\njQuery.expr = Sizzle.selectors;\n\n// Deprecated\njQuery.expr[ \":\" ] = jQuery.expr.pseudos;\njQuery.uniqueSort = jQuery.unique = Sizzle.uniqueSort;\njQuery.text = Sizzle.getText;\njQuery.isXMLDoc = Sizzle.isXML;\njQuery.contains = Sizzle.contains;\njQuery.escapeSelector = Sizzle.escape;\n\n\n\n\nvar dir = function( elem, dir, until ) {\n\tvar matched = [],\n\t\ttruncate = until !== undefined;\n\n\twhile ( ( elem = elem[ dir ] ) && elem.nodeType !== 9 ) {\n\t\tif ( elem.nodeType === 1 ) {\n\t\t\tif ( truncate && jQuery( elem ).is( until ) ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tmatched.push( elem );\n\t\t}\n\t}\n\treturn matched;\n};\n\n\nvar siblings = function( n, elem ) {\n\tvar matched = [];\n\n\tfor ( ; n; n = n.nextSibling ) {\n\t\tif ( n.nodeType === 1 && n !== elem ) {\n\t\t\tmatched.push( n );\n\t\t}\n\t}\n\n\treturn matched;\n};\n\n\nvar rneedsContext = jQuery.expr.match.needsContext;\n\n\n\nfunction nodeName( elem, name ) {\n\n  return elem.nodeName && elem.nodeName.toLowerCase() === name.toLowerCase();\n\n};\nvar rsingleTag = ( /^<([a-z][^\\/\\0>:\\x20\\t\\r\\n\\f]*)[\\x20\\t\\r\\n\\f]*\\/?>(?:<\\/\\1>|)$/i );\n\n\n\n// Implement the identical functionality for filter and not\nfunction winnow( elements, qualifier, not ) {\n\tif ( isFunction( qualifier ) ) {\n\t\treturn jQuery.grep( elements, function( elem, i ) {\n\t\t\treturn !!qualifier.call( elem, i, elem ) !== not;\n\t\t} );\n\t}\n\n\t// Single element\n\tif ( qualifier.nodeType ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( elem === qualifier ) !== not;\n\t\t} );\n\t}\n\n\t// Arraylike of elements (jQuery, arguments, Array)\n\tif ( typeof qualifier !== \"string\" ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( indexOf.call( qualifier, elem ) > -1 ) !== not;\n\t\t} );\n\t}\n\n\t// Filtered directly for both simple and complex selectors\n\treturn jQuery.filter( qualifier, elements, not );\n}\n\njQuery.filter = function( expr, elems, not ) {\n\tvar elem = elems[ 0 ];\n\n\tif ( not ) {\n\t\texpr = \":not(\" + expr + \")\";\n\t}\n\n\tif ( elems.length === 1 && elem.nodeType === 1 ) {\n\t\treturn jQuery.find.matchesSelector( elem, expr ) ? [ elem ] : [];\n\t}\n\n\treturn jQuery.find.matches( expr, jQuery.grep( elems, function( elem ) {\n\t\treturn elem.nodeType === 1;\n\t} ) );\n};\n\njQuery.fn.extend( {\n\tfind: function( selector ) {\n\t\tvar i, ret,\n\t\t\tlen = this.length,\n\t\t\tself = this;\n\n\t\tif ( typeof selector !== \"string\" ) {\n\t\t\treturn this.pushStack( jQuery( selector ).filter( function() {\n\t\t\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\t\t\tif ( jQuery.contains( self[ i ], this ) ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} ) );\n\t\t}\n\n\t\tret = this.pushStack( [] );\n\n\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\tjQuery.find( selector, self[ i ], ret );\n\t\t}\n\n\t\treturn len > 1 ? jQuery.uniqueSort( ret ) : ret;\n\t},\n\tfilter: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], false ) );\n\t},\n\tnot: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], true ) );\n\t},\n\tis: function( selector ) {\n\t\treturn !!winnow(\n\t\t\tthis,\n\n\t\t\t// If this is a positional/relative selector, check membership in the returned set\n\t\t\t// so $(\"p:first\").is(\"p:last\") won't return true for a doc with two \"p\".\n\t\t\ttypeof selector === \"string\" && rneedsContext.test( selector ) ?\n\t\t\t\tjQuery( selector ) :\n\t\t\t\tselector || [],\n\t\t\tfalse\n\t\t).length;\n\t}\n} );\n\n\n// Initialize a jQuery object\n\n\n// A central reference to the root jQuery(document)\nvar rootjQuery,\n\n\t// A simple way to check for HTML strings\n\t// Prioritize #id over <tag> to avoid XSS via location.hash (#9521)\n\t// Strict HTML recognition (#11290: must start with <)\n\t// Shortcut simple #id case for speed\n\trquickExpr = /^(?:\\s*(<[\\w\\W]+>)[^>]*|#([\\w-]+))$/,\n\n\tinit = jQuery.fn.init = function( selector, context, root ) {\n\t\tvar match, elem;\n\n\t\t// HANDLE: $(\"\"), $(null), $(undefined), $(false)\n\t\tif ( !selector ) {\n\t\t\treturn this;\n\t\t}\n\n\t\t// Method init() accepts an alternate rootjQuery\n\t\t// so migrate can support jQuery.sub (gh-2101)\n\t\troot = root || rootjQuery;\n\n\t\t// Handle HTML strings\n\t\tif ( typeof selector === \"string\" ) {\n\t\t\tif ( selector[ 0 ] === \"<\" &&\n\t\t\t\tselector[ selector.length - 1 ] === \">\" &&\n\t\t\t\tselector.length >= 3 ) {\n\n\t\t\t\t// Assume that strings that start and end with <> are HTML and skip the regex check\n\t\t\t\tmatch = [ null, selector, null ];\n\n\t\t\t} else {\n\t\t\t\tmatch = rquickExpr.exec( selector );\n\t\t\t}\n\n\t\t\t// Match html or make sure no context is specified for #id\n\t\t\tif ( match && ( match[ 1 ] || !context ) ) {\n\n\t\t\t\t// HANDLE: $(html) -> $(array)\n\t\t\t\tif ( match[ 1 ] ) {\n\t\t\t\t\tcontext = context instanceof jQuery ? context[ 0 ] : context;\n\n\t\t\t\t\t// Option to run scripts is true for back-compat\n\t\t\t\t\t// Intentionally let the error be thrown if parseHTML is not present\n\t\t\t\t\tjQuery.merge( this, jQuery.parseHTML(\n\t\t\t\t\t\tmatch[ 1 ],\n\t\t\t\t\t\tcontext && context.nodeType ? context.ownerDocument || context : document,\n\t\t\t\t\t\ttrue\n\t\t\t\t\t) );\n\n\t\t\t\t\t// HANDLE: $(html, props)\n\t\t\t\t\tif ( rsingleTag.test( match[ 1 ] ) && jQuery.isPlainObject( context ) ) {\n\t\t\t\t\t\tfor ( match in context ) {\n\n\t\t\t\t\t\t\t// Properties of context are called as methods if possible\n\t\t\t\t\t\t\tif ( isFunction( this[ match ] ) ) {\n\t\t\t\t\t\t\t\tthis[ match ]( context[ match ] );\n\n\t\t\t\t\t\t\t// ...and otherwise set as attributes\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tthis.attr( match, context[ match ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\treturn this;\n\n\t\t\t\t// HANDLE: $(#id)\n\t\t\t\t} else {\n\t\t\t\t\telem = document.getElementById( match[ 2 ] );\n\n\t\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t\t// Inject the element directly into the jQuery object\n\t\t\t\t\t\tthis[ 0 ] = elem;\n\t\t\t\t\t\tthis.length = 1;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\n\t\t\t// HANDLE: $(expr, $(...))\n\t\t\t} else if ( !context || context.jquery ) {\n\t\t\t\treturn ( context || root ).find( selector );\n\n\t\t\t// HANDLE: $(expr, context)\n\t\t\t// (which is just equivalent to: $(context).find(expr)\n\t\t\t} else {\n\t\t\t\treturn this.constructor( context ).find( selector );\n\t\t\t}\n\n\t\t// HANDLE: $(DOMElement)\n\t\t} else if ( selector.nodeType ) {\n\t\t\tthis[ 0 ] = selector;\n\t\t\tthis.length = 1;\n\t\t\treturn this;\n\n\t\t// HANDLE: $(function)\n\t\t// Shortcut for document ready\n\t\t} else if ( isFunction( selector ) ) {\n\t\t\treturn root.ready !== undefined ?\n\t\t\t\troot.ready( selector ) :\n\n\t\t\t\t// Execute immediately if ready is not present\n\t\t\t\tselector( jQuery );\n\t\t}\n\n\t\treturn jQuery.makeArray( selector, this );\n\t};\n\n// Give the init function the jQuery prototype for later instantiation\ninit.prototype = jQuery.fn;\n\n// Initialize central reference\nrootjQuery = jQuery( document );\n\n\nvar rparentsprev = /^(?:parents|prev(?:Until|All))/,\n\n\t// Methods guaranteed to produce a unique set when starting from a unique set\n\tguaranteedUnique = {\n\t\tchildren: true,\n\t\tcontents: true,\n\t\tnext: true,\n\t\tprev: true\n\t};\n\njQuery.fn.extend( {\n\thas: function( target ) {\n\t\tvar targets = jQuery( target, this ),\n\t\t\tl = targets.length;\n\n\t\treturn this.filter( function() {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tif ( jQuery.contains( this, targets[ i ] ) ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\tclosest: function( selectors, context ) {\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\tl = this.length,\n\t\t\tmatched = [],\n\t\t\ttargets = typeof selectors !== \"string\" && jQuery( selectors );\n\n\t\t// Positional selectors never match, since there's no _selection_ context\n\t\tif ( !rneedsContext.test( selectors ) ) {\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tfor ( cur = this[ i ]; cur && cur !== context; cur = cur.parentNode ) {\n\n\t\t\t\t\t// Always skip document fragments\n\t\t\t\t\tif ( cur.nodeType < 11 && ( targets ?\n\t\t\t\t\t\ttargets.index( cur ) > -1 :\n\n\t\t\t\t\t\t// Don't pass non-elements to Sizzle\n\t\t\t\t\t\tcur.nodeType === 1 &&\n\t\t\t\t\t\t\tjQuery.find.matchesSelector( cur, selectors ) ) ) {\n\n\t\t\t\t\t\tmatched.push( cur );\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched.length > 1 ? jQuery.uniqueSort( matched ) : matched );\n\t},\n\n\t// Determine the position of an element within the set\n\tindex: function( elem ) {\n\n\t\t// No argument, return index in parent\n\t\tif ( !elem ) {\n\t\t\treturn ( this[ 0 ] && this[ 0 ].parentNode ) ? this.first().prevAll().length : -1;\n\t\t}\n\n\t\t// Index in selector\n\t\tif ( typeof elem === \"string\" ) {\n\t\t\treturn indexOf.call( jQuery( elem ), this[ 0 ] );\n\t\t}\n\n\t\t// Locate the position of the desired element\n\t\treturn indexOf.call( this,\n\n\t\t\t// If it receives a jQuery object, the first element is used\n\t\t\telem.jquery ? elem[ 0 ] : elem\n\t\t);\n\t},\n\n\tadd: function( selector, context ) {\n\t\treturn this.pushStack(\n\t\t\tjQuery.uniqueSort(\n\t\t\t\tjQuery.merge( this.get(), jQuery( selector, context ) )\n\t\t\t)\n\t\t);\n\t},\n\n\taddBack: function( selector ) {\n\t\treturn this.add( selector == null ?\n\t\t\tthis.prevObject : this.prevObject.filter( selector )\n\t\t);\n\t}\n} );\n\nfunction sibling( cur, dir ) {\n\twhile ( ( cur = cur[ dir ] ) && cur.nodeType !== 1 ) {}\n\treturn cur;\n}\n\njQuery.each( {\n\tparent: function( elem ) {\n\t\tvar parent = elem.parentNode;\n\t\treturn parent && parent.nodeType !== 11 ? parent : null;\n\t},\n\tparents: function( elem ) {\n\t\treturn dir( elem, \"parentNode\" );\n\t},\n\tparentsUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"parentNode\", until );\n\t},\n\tnext: function( elem ) {\n\t\treturn sibling( elem, \"nextSibling\" );\n\t},\n\tprev: function( elem ) {\n\t\treturn sibling( elem, \"previousSibling\" );\n\t},\n\tnextAll: function( elem ) {\n\t\treturn dir( elem, \"nextSibling\" );\n\t},\n\tprevAll: function( elem ) {\n\t\treturn dir( elem, \"previousSibling\" );\n\t},\n\tnextUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"nextSibling\", until );\n\t},\n\tprevUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"previousSibling\", until );\n\t},\n\tsiblings: function( elem ) {\n\t\treturn siblings( ( elem.parentNode || {} ).firstChild, elem );\n\t},\n\tchildren: function( elem ) {\n\t\treturn siblings( elem.firstChild );\n\t},\n\tcontents: function( elem ) {\n\t\tif ( typeof elem.contentDocument !== \"undefined\" ) {\n\t\t\treturn elem.contentDocument;\n\t\t}\n\n\t\t// Support: IE 9 - 11 only, iOS 7 only, Android Browser <=4.3 only\n\t\t// Treat the template element as a regular one in browsers that\n\t\t// don't support it.\n\t\tif ( nodeName( elem, \"template\" ) ) {\n\t\t\telem = elem.content || elem;\n\t\t}\n\n\t\treturn jQuery.merge( [], elem.childNodes );\n\t}\n}, function( name, fn ) {\n\tjQuery.fn[ name ] = function( until, selector ) {\n\t\tvar matched = jQuery.map( this, fn, until );\n\n\t\tif ( name.slice( -5 ) !== \"Until\" ) {\n\t\t\tselector = until;\n\t\t}\n\n\t\tif ( selector && typeof selector === \"string\" ) {\n\t\t\tmatched = jQuery.filter( selector, matched );\n\t\t}\n\n\t\tif ( this.length > 1 ) {\n\n\t\t\t// Remove duplicates\n\t\t\tif ( !guaranteedUnique[ name ] ) {\n\t\t\t\tjQuery.uniqueSort( matched );\n\t\t\t}\n\n\t\t\t// Reverse order for parents* and prev-derivatives\n\t\t\tif ( rparentsprev.test( name ) ) {\n\t\t\t\tmatched.reverse();\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched );\n\t};\n} );\nvar rnothtmlwhite = ( /[^\\x20\\t\\r\\n\\f]+/g );\n\n\n\n// Convert String-formatted options into Object-formatted ones\nfunction createOptions( options ) {\n\tvar object = {};\n\tjQuery.each( options.match( rnothtmlwhite ) || [], function( _, flag ) {\n\t\tobject[ flag ] = true;\n\t} );\n\treturn object;\n}\n\n/*\n * Create a callback list using the following parameters:\n *\n *\toptions: an optional list of space-separated options that will change how\n *\t\t\tthe callback list behaves or a more traditional option object\n *\n * By default a callback list will act like an event callback list and can be\n * \"fired\" multiple times.\n *\n * Possible options:\n *\n *\tonce:\t\t\twill ensure the callback list can only be fired once (like a Deferred)\n *\n *\tmemory:\t\t\twill keep track of previous values and will call any callback added\n *\t\t\t\t\tafter the list has been fired right away with the latest \"memorized\"\n *\t\t\t\t\tvalues (like a Deferred)\n *\n *\tunique:\t\t\twill ensure a callback can only be added once (no duplicate in the list)\n *\n *\tstopOnFalse:\tinterrupt callings when a callback returns false\n *\n */\njQuery.Callbacks = function( options ) {\n\n\t// Convert options from String-formatted to Object-formatted if needed\n\t// (we check in cache first)\n\toptions = typeof options === \"string\" ?\n\t\tcreateOptions( options ) :\n\t\tjQuery.extend( {}, options );\n\n\tvar // Flag to know if list is currently firing\n\t\tfiring,\n\n\t\t// Last fire value for non-forgettable lists\n\t\tmemory,\n\n\t\t// Flag to know if list was already fired\n\t\tfired,\n\n\t\t// Flag to prevent firing\n\t\tlocked,\n\n\t\t// Actual callback list\n\t\tlist = [],\n\n\t\t// Queue of execution data for repeatable lists\n\t\tqueue = [],\n\n\t\t// Index of currently firing callback (modified by add/remove as needed)\n\t\tfiringIndex = -1,\n\n\t\t// Fire callbacks\n\t\tfire = function() {\n\n\t\t\t// Enforce single-firing\n\t\t\tlocked = locked || options.once;\n\n\t\t\t// Execute callbacks for all pending executions,\n\t\t\t// respecting firingIndex overrides and runtime changes\n\t\t\tfired = firing = true;\n\t\t\tfor ( ; queue.length; firingIndex = -1 ) {\n\t\t\t\tmemory = queue.shift();\n\t\t\t\twhile ( ++firingIndex < list.length ) {\n\n\t\t\t\t\t// Run callback and check for early termination\n\t\t\t\t\tif ( list[ firingIndex ].apply( memory[ 0 ], memory[ 1 ] ) === false &&\n\t\t\t\t\t\toptions.stopOnFalse ) {\n\n\t\t\t\t\t\t// Jump to end and forget the data so .add doesn't re-fire\n\t\t\t\t\t\tfiringIndex = list.length;\n\t\t\t\t\t\tmemory = false;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Forget the data if we're done with it\n\t\t\tif ( !options.memory ) {\n\t\t\t\tmemory = false;\n\t\t\t}\n\n\t\t\tfiring = false;\n\n\t\t\t// Clean up if we're done firing for good\n\t\t\tif ( locked ) {\n\n\t\t\t\t// Keep an empty list if we have data for future add calls\n\t\t\t\tif ( memory ) {\n\t\t\t\t\tlist = [];\n\n\t\t\t\t// Otherwise, this object is spent\n\t\t\t\t} else {\n\t\t\t\t\tlist = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t},\n\n\t\t// Actual Callbacks object\n\t\tself = {\n\n\t\t\t// Add a callback or a collection of callbacks to the list\n\t\t\tadd: function() {\n\t\t\t\tif ( list ) {\n\n\t\t\t\t\t// If we have memory from a past run, we should fire after adding\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfiringIndex = list.length - 1;\n\t\t\t\t\t\tqueue.push( memory );\n\t\t\t\t\t}\n\n\t\t\t\t\t( function add( args ) {\n\t\t\t\t\t\tjQuery.each( args, function( _, arg ) {\n\t\t\t\t\t\t\tif ( isFunction( arg ) ) {\n\t\t\t\t\t\t\t\tif ( !options.unique || !self.has( arg ) ) {\n\t\t\t\t\t\t\t\t\tlist.push( arg );\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} else if ( arg && arg.length && toType( arg ) !== \"string\" ) {\n\n\t\t\t\t\t\t\t\t// Inspect recursively\n\t\t\t\t\t\t\t\tadd( arg );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} );\n\t\t\t\t\t} )( arguments );\n\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Remove a callback from the list\n\t\t\tremove: function() {\n\t\t\t\tjQuery.each( arguments, function( _, arg ) {\n\t\t\t\t\tvar index;\n\t\t\t\t\twhile ( ( index = jQuery.inArray( arg, list, index ) ) > -1 ) {\n\t\t\t\t\t\tlist.splice( index, 1 );\n\n\t\t\t\t\t\t// Handle firing indexes\n\t\t\t\t\t\tif ( index <= firingIndex ) {\n\t\t\t\t\t\t\tfiringIndex--;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Check if a given callback is in the list.\n\t\t\t// If no argument is given, return whether or not list has callbacks attached.\n\t\t\thas: function( fn ) {\n\t\t\t\treturn fn ?\n\t\t\t\t\tjQuery.inArray( fn, list ) > -1 :\n\t\t\t\t\tlist.length > 0;\n\t\t\t},\n\n\t\t\t// Remove all callbacks from the list\n\t\t\tempty: function() {\n\t\t\t\tif ( list ) {\n\t\t\t\t\tlist = [];\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Disable .fire and .add\n\t\t\t// Abort any current/pending executions\n\t\t\t// Clear all callbacks and values\n\t\t\tdisable: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tlist = memory = \"\";\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tdisabled: function() {\n\t\t\t\treturn !list;\n\t\t\t},\n\n\t\t\t// Disable .fire\n\t\t\t// Also disable .add unless we have memory (since it would have no effect)\n\t\t\t// Abort any pending executions\n\t\t\tlock: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tif ( !memory && !firing ) {\n\t\t\t\t\tlist = memory = \"\";\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tlocked: function() {\n\t\t\t\treturn !!locked;\n\t\t\t},\n\n\t\t\t// Call all callbacks with the given context and arguments\n\t\t\tfireWith: function( context, args ) {\n\t\t\t\tif ( !locked ) {\n\t\t\t\t\targs = args || [];\n\t\t\t\t\targs = [ context, args.slice ? args.slice() : args ];\n\t\t\t\t\tqueue.push( args );\n\t\t\t\t\tif ( !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Call all the callbacks with the given arguments\n\t\t\tfire: function() {\n\t\t\t\tself.fireWith( this, arguments );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// To know if the callbacks have already been called at least once\n\t\t\tfired: function() {\n\t\t\t\treturn !!fired;\n\t\t\t}\n\t\t};\n\n\treturn self;\n};\n\n\nfunction Identity( v ) {\n\treturn v;\n}\nfunction Thrower( ex ) {\n\tthrow ex;\n}\n\nfunction adoptValue( value, resolve, reject, noValue ) {\n\tvar method;\n\n\ttry {\n\n\t\t// Check for promise aspect first to privilege synchronous behavior\n\t\tif ( value && isFunction( ( method = value.promise ) ) ) {\n\t\t\tmethod.call( value ).done( resolve ).fail( reject );\n\n\t\t// Other thenables\n\t\t} else if ( value && isFunction( ( method = value.then ) ) ) {\n\t\t\tmethod.call( value, resolve, reject );\n\n\t\t// Other non-thenables\n\t\t} else {\n\n\t\t\t// Control `resolve` arguments by letting Array#slice cast boolean `noValue` to integer:\n\t\t\t// * false: [ value ].slice( 0 ) => resolve( value )\n\t\t\t// * true: [ value ].slice( 1 ) => resolve()\n\t\t\tresolve.apply( undefined, [ value ].slice( noValue ) );\n\t\t}\n\n\t// For Promises/A+, convert exceptions into rejections\n\t// Since jQuery.when doesn't unwrap thenables, we can skip the extra checks appearing in\n\t// Deferred#then to conditionally suppress rejection.\n\t} catch ( value ) {\n\n\t\t// Support: Android 4.0 only\n\t\t// Strict mode functions invoked without .call/.apply get global-object context\n\t\treject.apply( undefined, [ value ] );\n\t}\n}\n\njQuery.extend( {\n\n\tDeferred: function( func ) {\n\t\tvar tuples = [\n\n\t\t\t\t// action, add listener, callbacks,\n\t\t\t\t// ... .then handlers, argument index, [final state]\n\t\t\t\t[ \"notify\", \"progress\", jQuery.Callbacks( \"memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"memory\" ), 2 ],\n\t\t\t\t[ \"resolve\", \"done\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 0, \"resolved\" ],\n\t\t\t\t[ \"reject\", \"fail\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 1, \"rejected\" ]\n\t\t\t],\n\t\t\tstate = \"pending\",\n\t\t\tpromise = {\n\t\t\t\tstate: function() {\n\t\t\t\t\treturn state;\n\t\t\t\t},\n\t\t\t\talways: function() {\n\t\t\t\t\tdeferred.done( arguments ).fail( arguments );\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\t\t\t\t\"catch\": function( fn ) {\n\t\t\t\t\treturn promise.then( null, fn );\n\t\t\t\t},\n\n\t\t\t\t// Keep pipe for back-compat\n\t\t\t\tpipe: function( /* fnDone, fnFail, fnProgress */ ) {\n\t\t\t\t\tvar fns = arguments;\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\t\t\t\t\t\tjQuery.each( tuples, function( i, tuple ) {\n\n\t\t\t\t\t\t\t// Map tuples (progress, done, fail) to arguments (done, fail, progress)\n\t\t\t\t\t\t\tvar fn = isFunction( fns[ tuple[ 4 ] ] ) && fns[ tuple[ 4 ] ];\n\n\t\t\t\t\t\t\t// deferred.progress(function() { bind to newDefer or newDefer.notify })\n\t\t\t\t\t\t\t// deferred.done(function() { bind to newDefer or newDefer.resolve })\n\t\t\t\t\t\t\t// deferred.fail(function() { bind to newDefer or newDefer.reject })\n\t\t\t\t\t\t\tdeferred[ tuple[ 1 ] ]( function() {\n\t\t\t\t\t\t\t\tvar returned = fn && fn.apply( this, arguments );\n\t\t\t\t\t\t\t\tif ( returned && isFunction( returned.promise ) ) {\n\t\t\t\t\t\t\t\t\treturned.promise()\n\t\t\t\t\t\t\t\t\t\t.progress( newDefer.notify )\n\t\t\t\t\t\t\t\t\t\t.done( newDefer.resolve )\n\t\t\t\t\t\t\t\t\t\t.fail( newDefer.reject );\n\t\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\t\tnewDefer[ tuple[ 0 ] + \"With\" ](\n\t\t\t\t\t\t\t\t\t\tthis,\n\t\t\t\t\t\t\t\t\t\tfn ? [ returned ] : arguments\n\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t} );\n\t\t\t\t\t\tfns = null;\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\t\t\t\tthen: function( onFulfilled, onRejected, onProgress ) {\n\t\t\t\t\tvar maxDepth = 0;\n\t\t\t\t\tfunction resolve( depth, deferred, handler, special ) {\n\t\t\t\t\t\treturn function() {\n\t\t\t\t\t\t\tvar that = this,\n\t\t\t\t\t\t\t\targs = arguments,\n\t\t\t\t\t\t\t\tmightThrow = function() {\n\t\t\t\t\t\t\t\t\tvar returned, then;\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.3\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-59\n\t\t\t\t\t\t\t\t\t// Ignore double-resolution attempts\n\t\t\t\t\t\t\t\t\tif ( depth < maxDepth ) {\n\t\t\t\t\t\t\t\t\t\treturn;\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\treturned = handler.apply( that, args );\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.1\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-48\n\t\t\t\t\t\t\t\t\tif ( returned === deferred.promise() ) {\n\t\t\t\t\t\t\t\t\t\tthrow new TypeError( \"Thenable self-resolution\" );\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ sections 2.3.3.1, 3.5\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-54\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-75\n\t\t\t\t\t\t\t\t\t// Retrieve `then` only once\n\t\t\t\t\t\t\t\t\tthen = returned &&\n\n\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.4\n\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-64\n\t\t\t\t\t\t\t\t\t\t// Only check objects and functions for thenability\n\t\t\t\t\t\t\t\t\t\t( typeof returned === \"object\" ||\n\t\t\t\t\t\t\t\t\t\t\ttypeof returned === \"function\" ) &&\n\t\t\t\t\t\t\t\t\t\treturned.then;\n\n\t\t\t\t\t\t\t\t\t// Handle a returned thenable\n\t\t\t\t\t\t\t\t\tif ( isFunction( then ) ) {\n\n\t\t\t\t\t\t\t\t\t\t// Special processors (notify) just wait for resolution\n\t\t\t\t\t\t\t\t\t\tif ( special ) {\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special )\n\t\t\t\t\t\t\t\t\t\t\t);\n\n\t\t\t\t\t\t\t\t\t\t// Normal processors (resolve) also hook into progress\n\t\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t\t// ...and disregard older resolution values\n\t\t\t\t\t\t\t\t\t\t\tmaxDepth++;\n\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity,\n\t\t\t\t\t\t\t\t\t\t\t\t\tdeferred.notifyWith )\n\t\t\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Handle all other returned values\n\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\tif ( handler !== Identity ) {\n\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\targs = [ returned ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t// Process the value(s)\n\t\t\t\t\t\t\t\t\t\t// Default process is resolve\n\t\t\t\t\t\t\t\t\t\t( special || deferred.resolveWith )( that, args );\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t},\n\n\t\t\t\t\t\t\t\t// Only normal processors (resolve) catch and reject exceptions\n\t\t\t\t\t\t\t\tprocess = special ?\n\t\t\t\t\t\t\t\t\tmightThrow :\n\t\t\t\t\t\t\t\t\tfunction() {\n\t\t\t\t\t\t\t\t\t\ttry {\n\t\t\t\t\t\t\t\t\t\t\tmightThrow();\n\t\t\t\t\t\t\t\t\t\t} catch ( e ) {\n\n\t\t\t\t\t\t\t\t\t\t\tif ( jQuery.Deferred.exceptionHook ) {\n\t\t\t\t\t\t\t\t\t\t\t\tjQuery.Deferred.exceptionHook( e,\n\t\t\t\t\t\t\t\t\t\t\t\t\tprocess.stackTrace );\n\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.4.1\n\t\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-61\n\t\t\t\t\t\t\t\t\t\t\t// Ignore post-resolution exceptions\n\t\t\t\t\t\t\t\t\t\t\tif ( depth + 1 >= maxDepth ) {\n\n\t\t\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\t\t\tif ( handler !== Thrower ) {\n\t\t\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\t\t\targs = [ e ];\n\t\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t\tdeferred.rejectWith( that, args );\n\t\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t};\n\n\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.1\n\t\t\t\t\t\t\t// https://promisesaplus.com/#point-57\n\t\t\t\t\t\t\t// Re-resolve promises immediately to dodge false rejection from\n\t\t\t\t\t\t\t// subsequent errors\n\t\t\t\t\t\t\tif ( depth ) {\n\t\t\t\t\t\t\t\tprocess();\n\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t// Call an optional hook to record the stack, in case of exception\n\t\t\t\t\t\t\t\t// since it's otherwise lost when execution goes async\n\t\t\t\t\t\t\t\tif ( jQuery.Deferred.getStackHook ) {\n\t\t\t\t\t\t\t\t\tprocess.stackTrace = jQuery.Deferred.getStackHook();\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\twindow.setTimeout( process );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t};\n\t\t\t\t\t}\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\n\t\t\t\t\t\t// progress_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 0 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onProgress ) ?\n\t\t\t\t\t\t\t\t\tonProgress :\n\t\t\t\t\t\t\t\t\tIdentity,\n\t\t\t\t\t\t\t\tnewDefer.notifyWith\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// fulfilled_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 1 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onFulfilled ) ?\n\t\t\t\t\t\t\t\t\tonFulfilled :\n\t\t\t\t\t\t\t\t\tIdentity\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// rejected_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 2 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onRejected ) ?\n\t\t\t\t\t\t\t\t\tonRejected :\n\t\t\t\t\t\t\t\t\tThrower\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\n\t\t\t\t// Get a promise for this deferred\n\t\t\t\t// If obj is provided, the promise aspect is added to the object\n\t\t\t\tpromise: function( obj ) {\n\t\t\t\t\treturn obj != null ? jQuery.extend( obj, promise ) : promise;\n\t\t\t\t}\n\t\t\t},\n\t\t\tdeferred = {};\n\n\t\t// Add list-specific methods\n\t\tjQuery.each( tuples, function( i, tuple ) {\n\t\t\tvar list = tuple[ 2 ],\n\t\t\t\tstateString = tuple[ 5 ];\n\n\t\t\t// promise.progress = list.add\n\t\t\t// promise.done = list.add\n\t\t\t// promise.fail = list.add\n\t\t\tpromise[ tuple[ 1 ] ] = list.add;\n\n\t\t\t// Handle state\n\t\t\tif ( stateString ) {\n\t\t\t\tlist.add(\n\t\t\t\t\tfunction() {\n\n\t\t\t\t\t\t// state = \"resolved\" (i.e., fulfilled)\n\t\t\t\t\t\t// state = \"rejected\"\n\t\t\t\t\t\tstate = stateString;\n\t\t\t\t\t},\n\n\t\t\t\t\t// rejected_callbacks.disable\n\t\t\t\t\t// fulfilled_callbacks.disable\n\t\t\t\t\ttuples[ 3 - i ][ 2 ].disable,\n\n\t\t\t\t\t// rejected_handlers.disable\n\t\t\t\t\t// fulfilled_handlers.disable\n\t\t\t\t\ttuples[ 3 - i ][ 3 ].disable,\n\n\t\t\t\t\t// progress_callbacks.lock\n\t\t\t\t\ttuples[ 0 ][ 2 ].lock,\n\n\t\t\t\t\t// progress_handlers.lock\n\t\t\t\t\ttuples[ 0 ][ 3 ].lock\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// progress_handlers.fire\n\t\t\t// fulfilled_handlers.fire\n\t\t\t// rejected_handlers.fire\n\t\t\tlist.add( tuple[ 3 ].fire );\n\n\t\t\t// deferred.notify = function() { deferred.notifyWith(...) }\n\t\t\t// deferred.resolve = function() { deferred.resolveWith(...) }\n\t\t\t// deferred.reject = function() { deferred.rejectWith(...) }\n\t\t\tdeferred[ tuple[ 0 ] ] = function() {\n\t\t\t\tdeferred[ tuple[ 0 ] + \"With\" ]( this === deferred ? undefined : this, arguments );\n\t\t\t\treturn this;\n\t\t\t};\n\n\t\t\t// deferred.notifyWith = list.fireWith\n\t\t\t// deferred.resolveWith = list.fireWith\n\t\t\t// deferred.rejectWith = list.fireWith\n\t\t\tdeferred[ tuple[ 0 ] + \"With\" ] = list.fireWith;\n\t\t} );\n\n\t\t// Make the deferred a promise\n\t\tpromise.promise( deferred );\n\n\t\t// Call given func if any\n\t\tif ( func ) {\n\t\t\tfunc.call( deferred, deferred );\n\t\t}\n\n\t\t// All done!\n\t\treturn deferred;\n\t},\n\n\t// Deferred helper\n\twhen: function( singleValue ) {\n\t\tvar\n\n\t\t\t// count of uncompleted subordinates\n\t\t\tremaining = arguments.length,\n\n\t\t\t// count of unprocessed arguments\n\t\t\ti = remaining,\n\n\t\t\t// subordinate fulfillment data\n\t\t\tresolveContexts = Array( i ),\n\t\t\tresolveValues = slice.call( arguments ),\n\n\t\t\t// the master Deferred\n\t\t\tmaster = jQuery.Deferred(),\n\n\t\t\t// subordinate callback factory\n\t\t\tupdateFunc = function( i ) {\n\t\t\t\treturn function( value ) {\n\t\t\t\t\tresolveContexts[ i ] = this;\n\t\t\t\t\tresolveValues[ i ] = arguments.length > 1 ? slice.call( arguments ) : value;\n\t\t\t\t\tif ( !( --remaining ) ) {\n\t\t\t\t\t\tmaster.resolveWith( resolveContexts, resolveValues );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t\t};\n\n\t\t// Single- and empty arguments are adopted like Promise.resolve\n\t\tif ( remaining <= 1 ) {\n\t\t\tadoptValue( singleValue, master.done( updateFunc( i ) ).resolve, master.reject,\n\t\t\t\t!remaining );\n\n\t\t\t// Use .then() to unwrap secondary thenables (cf. gh-3000)\n\t\t\tif ( master.state() === \"pending\" ||\n\t\t\t\tisFunction( resolveValues[ i ] && resolveValues[ i ].then ) ) {\n\n\t\t\t\treturn master.then();\n\t\t\t}\n\t\t}\n\n\t\t// Multiple arguments are aggregated like Promise.all array elements\n\t\twhile ( i-- ) {\n\t\t\tadoptValue( resolveValues[ i ], updateFunc( i ), master.reject );\n\t\t}\n\n\t\treturn master.promise();\n\t}\n} );\n\n\n// These usually indicate a programmer mistake during development,\n// warn about them ASAP rather than swallowing them by default.\nvar rerrorNames = /^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/;\n\njQuery.Deferred.exceptionHook = function( error, stack ) {\n\n\t// Support: IE 8 - 9 only\n\t// Console exists when dev tools are open, which can happen at any time\n\tif ( window.console && window.console.warn && error && rerrorNames.test( error.name ) ) {\n\t\twindow.console.warn( \"jQuery.Deferred exception: \" + error.message, error.stack, stack );\n\t}\n};\n\n\n\n\njQuery.readyException = function( error ) {\n\twindow.setTimeout( function() {\n\t\tthrow error;\n\t} );\n};\n\n\n\n\n// The deferred used on DOM ready\nvar readyList = jQuery.Deferred();\n\njQuery.fn.ready = function( fn ) {\n\n\treadyList\n\t\t.then( fn )\n\n\t\t// Wrap jQuery.readyException in a function so that the lookup\n\t\t// happens at the time of error handling instead of callback\n\t\t// registration.\n\t\t.catch( function( error ) {\n\t\t\tjQuery.readyException( error );\n\t\t} );\n\n\treturn this;\n};\n\njQuery.extend( {\n\n\t// Is the DOM ready to be used? Set to true once it occurs.\n\tisReady: false,\n\n\t// A counter to track how many items to wait for before\n\t// the ready event fires. See #6781\n\treadyWait: 1,\n\n\t// Handle when the DOM is ready\n\tready: function( wait ) {\n\n\t\t// Abort if there are pending holds or we're already ready\n\t\tif ( wait === true ? --jQuery.readyWait : jQuery.isReady ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Remember that the DOM is ready\n\t\tjQuery.isReady = true;\n\n\t\t// If a normal DOM Ready event fired, decrement, and wait if need be\n\t\tif ( wait !== true && --jQuery.readyWait > 0 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// If there are functions bound, to execute\n\t\treadyList.resolveWith( document, [ jQuery ] );\n\t}\n} );\n\njQuery.ready.then = readyList.then;\n\n// The ready event handler and self cleanup method\nfunction completed() {\n\tdocument.removeEventListener( \"DOMContentLoaded\", completed );\n\twindow.removeEventListener( \"load\", completed );\n\tjQuery.ready();\n}\n\n// Catch cases where $(document).ready() is called\n// after the browser event has already occurred.\n// Support: IE <=9 - 10 only\n// Older IE sometimes signals \"interactive\" too soon\nif ( document.readyState === \"complete\" ||\n\t( document.readyState !== \"loading\" && !document.documentElement.doScroll ) ) {\n\n\t// Handle it asynchronously to allow scripts the opportunity to delay ready\n\twindow.setTimeout( jQuery.ready );\n\n} else {\n\n\t// Use the handy event callback\n\tdocument.addEventListener( \"DOMContentLoaded\", completed );\n\n\t// A fallback to window.onload, that will always work\n\twindow.addEventListener( \"load\", completed );\n}\n\n\n\n\n// Multifunctional method to get and set values of a collection\n// The value/s can optionally be executed if it's a function\nvar access = function( elems, fn, key, value, chainable, emptyGet, raw ) {\n\tvar i = 0,\n\t\tlen = elems.length,\n\t\tbulk = key == null;\n\n\t// Sets many values\n\tif ( toType( key ) === \"object\" ) {\n\t\tchainable = true;\n\t\tfor ( i in key ) {\n\t\t\taccess( elems, fn, i, key[ i ], true, emptyGet, raw );\n\t\t}\n\n\t// Sets one value\n\t} else if ( value !== undefined ) {\n\t\tchainable = true;\n\n\t\tif ( !isFunction( value ) ) {\n\t\t\traw = true;\n\t\t}\n\n\t\tif ( bulk ) {\n\n\t\t\t// Bulk operations run against the entire set\n\t\t\tif ( raw ) {\n\t\t\t\tfn.call( elems, value );\n\t\t\t\tfn = null;\n\n\t\t\t// ...except when executing function values\n\t\t\t} else {\n\t\t\t\tbulk = fn;\n\t\t\t\tfn = function( elem, key, value ) {\n\t\t\t\t\treturn bulk.call( jQuery( elem ), value );\n\t\t\t\t};\n\t\t\t}\n\t\t}\n\n\t\tif ( fn ) {\n\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\tfn(\n\t\t\t\t\telems[ i ], key, raw ?\n\t\t\t\t\tvalue :\n\t\t\t\t\tvalue.call( elems[ i ], i, fn( elems[ i ], key ) )\n\t\t\t\t);\n\t\t\t}\n\t\t}\n\t}\n\n\tif ( chainable ) {\n\t\treturn elems;\n\t}\n\n\t// Gets\n\tif ( bulk ) {\n\t\treturn fn.call( elems );\n\t}\n\n\treturn len ? fn( elems[ 0 ], key ) : emptyGet;\n};\n\n\n// Matches dashed string for camelizing\nvar rmsPrefix = /^-ms-/,\n\trdashAlpha = /-([a-z])/g;\n\n// Used by camelCase as callback to replace()\nfunction fcamelCase( all, letter ) {\n\treturn letter.toUpperCase();\n}\n\n// Convert dashed to camelCase; used by the css and data modules\n// Support: IE <=9 - 11, Edge 12 - 15\n// Microsoft forgot to hump their vendor prefix (#9572)\nfunction camelCase( string ) {\n\treturn string.replace( rmsPrefix, \"ms-\" ).replace( rdashAlpha, fcamelCase );\n}\nvar acceptData = function( owner ) {\n\n\t// Accepts only:\n\t//  - Node\n\t//    - Node.ELEMENT_NODE\n\t//    - Node.DOCUMENT_NODE\n\t//  - Object\n\t//    - Any\n\treturn owner.nodeType === 1 || owner.nodeType === 9 || !( +owner.nodeType );\n};\n\n\n\n\nfunction Data() {\n\tthis.expando = jQuery.expando + Data.uid++;\n}\n\nData.uid = 1;\n\nData.prototype = {\n\n\tcache: function( owner ) {\n\n\t\t// Check if the owner object already has a cache\n\t\tvar value = owner[ this.expando ];\n\n\t\t// If not, create one\n\t\tif ( !value ) {\n\t\t\tvalue = {};\n\n\t\t\t// We can accept data for non-element nodes in modern browsers,\n\t\t\t// but we should not, see #8335.\n\t\t\t// Always return an empty object.\n\t\t\tif ( acceptData( owner ) ) {\n\n\t\t\t\t// If it is a node unlikely to be stringify-ed or looped over\n\t\t\t\t// use plain assignment\n\t\t\t\tif ( owner.nodeType ) {\n\t\t\t\t\towner[ this.expando ] = value;\n\n\t\t\t\t// Otherwise secure it in a non-enumerable property\n\t\t\t\t// configurable must be true to allow the property to be\n\t\t\t\t// deleted when data is removed\n\t\t\t\t} else {\n\t\t\t\t\tObject.defineProperty( owner, this.expando, {\n\t\t\t\t\t\tvalue: value,\n\t\t\t\t\t\tconfigurable: true\n\t\t\t\t\t} );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn value;\n\t},\n\tset: function( owner, data, value ) {\n\t\tvar prop,\n\t\t\tcache = this.cache( owner );\n\n\t\t// Handle: [ owner, key, value ] args\n\t\t// Always use camelCase key (gh-2257)\n\t\tif ( typeof data === \"string\" ) {\n\t\t\tcache[ camelCase( data ) ] = value;\n\n\t\t// Handle: [ owner, { properties } ] args\n\t\t} else {\n\n\t\t\t// Copy the properties one-by-one to the cache object\n\t\t\tfor ( prop in data ) {\n\t\t\t\tcache[ camelCase( prop ) ] = data[ prop ];\n\t\t\t}\n\t\t}\n\t\treturn cache;\n\t},\n\tget: function( owner, key ) {\n\t\treturn key === undefined ?\n\t\t\tthis.cache( owner ) :\n\n\t\t\t// Always use camelCase key (gh-2257)\n\t\t\towner[ this.expando ] && owner[ this.expando ][ camelCase( key ) ];\n\t},\n\taccess: function( owner, key, value ) {\n\n\t\t// In cases where either:\n\t\t//\n\t\t//   1. No key was specified\n\t\t//   2. A string key was specified, but no value provided\n\t\t//\n\t\t// Take the \"read\" path and allow the get method to determine\n\t\t// which value to return, respectively either:\n\t\t//\n\t\t//   1. The entire cache object\n\t\t//   2. The data stored at the key\n\t\t//\n\t\tif ( key === undefined ||\n\t\t\t\t( ( key && typeof key === \"string\" ) && value === undefined ) ) {\n\n\t\t\treturn this.get( owner, key );\n\t\t}\n\n\t\t// When the key is not a string, or both a key and value\n\t\t// are specified, set or extend (existing objects) with either:\n\t\t//\n\t\t//   1. An object of properties\n\t\t//   2. A key and value\n\t\t//\n\t\tthis.set( owner, key, value );\n\n\t\t// Since the \"set\" path can have two possible entry points\n\t\t// return the expected data based on which path was taken[*]\n\t\treturn value !== undefined ? value : key;\n\t},\n\tremove: function( owner, key ) {\n\t\tvar i,\n\t\t\tcache = owner[ this.expando ];\n\n\t\tif ( cache === undefined ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( key !== undefined ) {\n\n\t\t\t// Support array or space separated string of keys\n\t\t\tif ( Array.isArray( key ) ) {\n\n\t\t\t\t// If key is an array of keys...\n\t\t\t\t// We always set camelCase keys, so remove that.\n\t\t\t\tkey = key.map( camelCase );\n\t\t\t} else {\n\t\t\t\tkey = camelCase( key );\n\n\t\t\t\t// If a key with the spaces exists, use it.\n\t\t\t\t// Otherwise, create an array by matching non-whitespace\n\t\t\t\tkey = key in cache ?\n\t\t\t\t\t[ key ] :\n\t\t\t\t\t( key.match( rnothtmlwhite ) || [] );\n\t\t\t}\n\n\t\t\ti = key.length;\n\n\t\t\twhile ( i-- ) {\n\t\t\t\tdelete cache[ key[ i ] ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove the expando if there's no more data\n\t\tif ( key === undefined || jQuery.isEmptyObject( cache ) ) {\n\n\t\t\t// Support: Chrome <=35 - 45\n\t\t\t// Webkit & Blink performance suffers when deleting properties\n\t\t\t// from DOM nodes, so set to undefined instead\n\t\t\t// https://bugs.chromium.org/p/chromium/issues/detail?id=378607 (bug restricted)\n\t\t\tif ( owner.nodeType ) {\n\t\t\t\towner[ this.expando ] = undefined;\n\t\t\t} else {\n\t\t\t\tdelete owner[ this.expando ];\n\t\t\t}\n\t\t}\n\t},\n\thasData: function( owner ) {\n\t\tvar cache = owner[ this.expando ];\n\t\treturn cache !== undefined && !jQuery.isEmptyObject( cache );\n\t}\n};\nvar dataPriv = new Data();\n\nvar dataUser = new Data();\n\n\n\n//\tImplementation Summary\n//\n//\t1. Enforce API surface and semantic compatibility with 1.9.x branch\n//\t2. Improve the module's maintainability by reducing the storage\n//\t\tpaths to a single mechanism.\n//\t3. Use the same single mechanism to support \"private\" and \"user\" data.\n//\t4. _Never_ expose \"private\" data to user code (TODO: Drop _data, _removeData)\n//\t5. Avoid exposing implementation details on user objects (eg. expando properties)\n//\t6. Provide a clear path for implementation upgrade to WeakMap in 2014\n\nvar rbrace = /^(?:\\{[\\w\\W]*\\}|\\[[\\w\\W]*\\])$/,\n\trmultiDash = /[A-Z]/g;\n\nfunction getData( data ) {\n\tif ( data === \"true\" ) {\n\t\treturn true;\n\t}\n\n\tif ( data === \"false\" ) {\n\t\treturn false;\n\t}\n\n\tif ( data === \"null\" ) {\n\t\treturn null;\n\t}\n\n\t// Only convert to a number if it doesn't change the string\n\tif ( data === +data + \"\" ) {\n\t\treturn +data;\n\t}\n\n\tif ( rbrace.test( data ) ) {\n\t\treturn JSON.parse( data );\n\t}\n\n\treturn data;\n}\n\nfunction dataAttr( elem, key, data ) {\n\tvar name;\n\n\t// If nothing was found internally, try to fetch any\n\t// data from the HTML5 data-* attribute\n\tif ( data === undefined && elem.nodeType === 1 ) {\n\t\tname = \"data-\" + key.replace( rmultiDash, \"-$&\" ).toLowerCase();\n\t\tdata = elem.getAttribute( name );\n\n\t\tif ( typeof data === \"string\" ) {\n\t\t\ttry {\n\t\t\t\tdata = getData( data );\n\t\t\t} catch ( e ) {}\n\n\t\t\t// Make sure we set the data so it isn't changed later\n\t\t\tdataUser.set( elem, key, data );\n\t\t} else {\n\t\t\tdata = undefined;\n\t\t}\n\t}\n\treturn data;\n}\n\njQuery.extend( {\n\thasData: function( elem ) {\n\t\treturn dataUser.hasData( elem ) || dataPriv.hasData( elem );\n\t},\n\n\tdata: function( elem, name, data ) {\n\t\treturn dataUser.access( elem, name, data );\n\t},\n\n\tremoveData: function( elem, name ) {\n\t\tdataUser.remove( elem, name );\n\t},\n\n\t// TODO: Now that all calls to _data and _removeData have been replaced\n\t// with direct calls to dataPriv methods, these can be deprecated.\n\t_data: function( elem, name, data ) {\n\t\treturn dataPriv.access( elem, name, data );\n\t},\n\n\t_removeData: function( elem, name ) {\n\t\tdataPriv.remove( elem, name );\n\t}\n} );\n\njQuery.fn.extend( {\n\tdata: function( key, value ) {\n\t\tvar i, name, data,\n\t\t\telem = this[ 0 ],\n\t\t\tattrs = elem && elem.attributes;\n\n\t\t// Gets all values\n\t\tif ( key === undefined ) {\n\t\t\tif ( this.length ) {\n\t\t\t\tdata = dataUser.get( elem );\n\n\t\t\t\tif ( elem.nodeType === 1 && !dataPriv.get( elem, \"hasDataAttrs\" ) ) {\n\t\t\t\t\ti = attrs.length;\n\t\t\t\t\twhile ( i-- ) {\n\n\t\t\t\t\t\t// Support: IE 11 only\n\t\t\t\t\t\t// The attrs elements can be null (#14894)\n\t\t\t\t\t\tif ( attrs[ i ] ) {\n\t\t\t\t\t\t\tname = attrs[ i ].name;\n\t\t\t\t\t\t\tif ( name.indexOf( \"data-\" ) === 0 ) {\n\t\t\t\t\t\t\t\tname = camelCase( name.slice( 5 ) );\n\t\t\t\t\t\t\t\tdataAttr( elem, name, data[ name ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tdataPriv.set( elem, \"hasDataAttrs\", true );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\treturn data;\n\t\t}\n\n\t\t// Sets multiple values\n\t\tif ( typeof key === \"object\" ) {\n\t\t\treturn this.each( function() {\n\t\t\t\tdataUser.set( this, key );\n\t\t\t} );\n\t\t}\n\n\t\treturn access( this, function( value ) {\n\t\t\tvar data;\n\n\t\t\t// The calling jQuery object (element matches) is not empty\n\t\t\t// (and therefore has an element appears at this[ 0 ]) and the\n\t\t\t// `value` parameter was not undefined. An empty jQuery object\n\t\t\t// will result in `undefined` for elem = this[ 0 ] which will\n\t\t\t// throw an exception if an attempt to read a data cache is made.\n\t\t\tif ( elem && value === undefined ) {\n\n\t\t\t\t// Attempt to get data from the cache\n\t\t\t\t// The key will always be camelCased in Data\n\t\t\t\tdata = dataUser.get( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// Attempt to \"discover\" the data in\n\t\t\t\t// HTML5 custom data-* attrs\n\t\t\t\tdata = dataAttr( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// We tried really hard, but the data doesn't exist.\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Set the data...\n\t\t\tthis.each( function() {\n\n\t\t\t\t// We always store the camelCased key\n\t\t\t\tdataUser.set( this, key, value );\n\t\t\t} );\n\t\t}, null, value, arguments.length > 1, null, true );\n\t},\n\n\tremoveData: function( key ) {\n\t\treturn this.each( function() {\n\t\t\tdataUser.remove( this, key );\n\t\t} );\n\t}\n} );\n\n\njQuery.extend( {\n\tqueue: function( elem, type, data ) {\n\t\tvar queue;\n\n\t\tif ( elem ) {\n\t\t\ttype = ( type || \"fx\" ) + \"queue\";\n\t\t\tqueue = dataPriv.get( elem, type );\n\n\t\t\t// Speed up dequeue by getting out quickly if this is just a lookup\n\t\t\tif ( data ) {\n\t\t\t\tif ( !queue || Array.isArray( data ) ) {\n\t\t\t\t\tqueue = dataPriv.access( elem, type, jQuery.makeArray( data ) );\n\t\t\t\t} else {\n\t\t\t\t\tqueue.push( data );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn queue || [];\n\t\t}\n\t},\n\n\tdequeue: function( elem, type ) {\n\t\ttype = type || \"fx\";\n\n\t\tvar queue = jQuery.queue( elem, type ),\n\t\t\tstartLength = queue.length,\n\t\t\tfn = queue.shift(),\n\t\t\thooks = jQuery._queueHooks( elem, type ),\n\t\t\tnext = function() {\n\t\t\t\tjQuery.dequeue( elem, type );\n\t\t\t};\n\n\t\t// If the fx queue is dequeued, always remove the progress sentinel\n\t\tif ( fn === \"inprogress\" ) {\n\t\t\tfn = queue.shift();\n\t\t\tstartLength--;\n\t\t}\n\n\t\tif ( fn ) {\n\n\t\t\t// Add a progress sentinel to prevent the fx queue from being\n\t\t\t// automatically dequeued\n\t\t\tif ( type === \"fx\" ) {\n\t\t\t\tqueue.unshift( \"inprogress\" );\n\t\t\t}\n\n\t\t\t// Clear up the last queue stop function\n\t\t\tdelete hooks.stop;\n\t\t\tfn.call( elem, next, hooks );\n\t\t}\n\n\t\tif ( !startLength && hooks ) {\n\t\t\thooks.empty.fire();\n\t\t}\n\t},\n\n\t// Not public - generate a queueHooks object, or return the current one\n\t_queueHooks: function( elem, type ) {\n\t\tvar key = type + \"queueHooks\";\n\t\treturn dataPriv.get( elem, key ) || dataPriv.access( elem, key, {\n\t\t\tempty: jQuery.Callbacks( \"once memory\" ).add( function() {\n\t\t\t\tdataPriv.remove( elem, [ type + \"queue\", key ] );\n\t\t\t} )\n\t\t} );\n\t}\n} );\n\njQuery.fn.extend( {\n\tqueue: function( type, data ) {\n\t\tvar setter = 2;\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tdata = type;\n\t\t\ttype = \"fx\";\n\t\t\tsetter--;\n\t\t}\n\n\t\tif ( arguments.length < setter ) {\n\t\t\treturn jQuery.queue( this[ 0 ], type );\n\t\t}\n\n\t\treturn data === undefined ?\n\t\t\tthis :\n\t\t\tthis.each( function() {\n\t\t\t\tvar queue = jQuery.queue( this, type, data );\n\n\t\t\t\t// Ensure a hooks for this queue\n\t\t\t\tjQuery._queueHooks( this, type );\n\n\t\t\t\tif ( type === \"fx\" && queue[ 0 ] !== \"inprogress\" ) {\n\t\t\t\t\tjQuery.dequeue( this, type );\n\t\t\t\t}\n\t\t\t} );\n\t},\n\tdequeue: function( type ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.dequeue( this, type );\n\t\t} );\n\t},\n\tclearQueue: function( type ) {\n\t\treturn this.queue( type || \"fx\", [] );\n\t},\n\n\t// Get a promise resolved when queues of a certain type\n\t// are emptied (fx is the type by default)\n\tpromise: function( type, obj ) {\n\t\tvar tmp,\n\t\t\tcount = 1,\n\t\t\tdefer = jQuery.Deferred(),\n\t\t\telements = this,\n\t\t\ti = this.length,\n\t\t\tresolve = function() {\n\t\t\t\tif ( !( --count ) ) {\n\t\t\t\t\tdefer.resolveWith( elements, [ elements ] );\n\t\t\t\t}\n\t\t\t};\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tobj = type;\n\t\t\ttype = undefined;\n\t\t}\n\t\ttype = type || \"fx\";\n\n\t\twhile ( i-- ) {\n\t\t\ttmp = dataPriv.get( elements[ i ], type + \"queueHooks\" );\n\t\t\tif ( tmp && tmp.empty ) {\n\t\t\t\tcount++;\n\t\t\t\ttmp.empty.add( resolve );\n\t\t\t}\n\t\t}\n\t\tresolve();\n\t\treturn defer.promise( obj );\n\t}\n} );\nvar pnum = ( /[+-]?(?:\\d*\\.|)\\d+(?:[eE][+-]?\\d+|)/ ).source;\n\nvar rcssNum = new RegExp( \"^(?:([+-])=|)(\" + pnum + \")([a-z%]*)$\", \"i\" );\n\n\nvar cssExpand = [ \"Top\", \"Right\", \"Bottom\", \"Left\" ];\n\nvar documentElement = document.documentElement;\n\n\n\n\tvar isAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem );\n\t\t},\n\t\tcomposed = { composed: true };\n\n\t// Support: IE 9 - 11+, Edge 12 - 18+, iOS 10.0 - 10.2 only\n\t// Check attachment across shadow DOM boundaries when possible (gh-3504)\n\t// Support: iOS 10.0-10.2 only\n\t// Early iOS 10 versions support `attachShadow` but not `getRootNode`,\n\t// leading to errors. We need to check for `getRootNode`.\n\tif ( documentElement.getRootNode ) {\n\t\tisAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem ) ||\n\t\t\t\telem.getRootNode( composed ) === elem.ownerDocument;\n\t\t};\n\t}\nvar isHiddenWithinTree = function( elem, el ) {\n\n\t\t// isHiddenWithinTree might be called from jQuery#filter function;\n\t\t// in that case, element will be second argument\n\t\telem = el || elem;\n\n\t\t// Inline style trumps all\n\t\treturn elem.style.display === \"none\" ||\n\t\t\telem.style.display === \"\" &&\n\n\t\t\t// Otherwise, check computed style\n\t\t\t// Support: Firefox <=43 - 45\n\t\t\t// Disconnected elements can have computed display: none, so first confirm that elem is\n\t\t\t// in the document.\n\t\t\tisAttached( elem ) &&\n\n\t\t\tjQuery.css( elem, \"display\" ) === \"none\";\n\t};\n\nvar swap = function( elem, options, callback, args ) {\n\tvar ret, name,\n\t\told = {};\n\n\t// Remember the old values, and insert the new ones\n\tfor ( name in options ) {\n\t\told[ name ] = elem.style[ name ];\n\t\telem.style[ name ] = options[ name ];\n\t}\n\n\tret = callback.apply( elem, args || [] );\n\n\t// Revert the old values\n\tfor ( name in options ) {\n\t\telem.style[ name ] = old[ name ];\n\t}\n\n\treturn ret;\n};\n\n\n\n\nfunction adjustCSS( elem, prop, valueParts, tween ) {\n\tvar adjusted, scale,\n\t\tmaxIterations = 20,\n\t\tcurrentValue = tween ?\n\t\t\tfunction() {\n\t\t\t\treturn tween.cur();\n\t\t\t} :\n\t\t\tfunction() {\n\t\t\t\treturn jQuery.css( elem, prop, \"\" );\n\t\t\t},\n\t\tinitial = currentValue(),\n\t\tunit = valueParts && valueParts[ 3 ] || ( jQuery.cssNumber[ prop ] ? \"\" : \"px\" ),\n\n\t\t// Starting value computation is required for potential unit mismatches\n\t\tinitialInUnit = elem.nodeType &&\n\t\t\t( jQuery.cssNumber[ prop ] || unit !== \"px\" && +initial ) &&\n\t\t\trcssNum.exec( jQuery.css( elem, prop ) );\n\n\tif ( initialInUnit && initialInUnit[ 3 ] !== unit ) {\n\n\t\t// Support: Firefox <=54\n\t\t// Halve the iteration target value to prevent interference from CSS upper bounds (gh-2144)\n\t\tinitial = initial / 2;\n\n\t\t// Trust units reported by jQuery.css\n\t\tunit = unit || initialInUnit[ 3 ];\n\n\t\t// Iteratively approximate from a nonzero starting point\n\t\tinitialInUnit = +initial || 1;\n\n\t\twhile ( maxIterations-- ) {\n\n\t\t\t// Evaluate and update our best guess (doubling guesses that zero out).\n\t\t\t// Finish if the scale equals or crosses 1 (making the old*new product non-positive).\n\t\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\t\t\tif ( ( 1 - scale ) * ( 1 - ( scale = currentValue() / initial || 0.5 ) ) <= 0 ) {\n\t\t\t\tmaxIterations = 0;\n\t\t\t}\n\t\t\tinitialInUnit = initialInUnit / scale;\n\n\t\t}\n\n\t\tinitialInUnit = initialInUnit * 2;\n\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\n\t\t// Make sure we update the tween properties later on\n\t\tvalueParts = valueParts || [];\n\t}\n\n\tif ( valueParts ) {\n\t\tinitialInUnit = +initialInUnit || +initial || 0;\n\n\t\t// Apply relative offset (+=/-=) if specified\n\t\tadjusted = valueParts[ 1 ] ?\n\t\t\tinitialInUnit + ( valueParts[ 1 ] + 1 ) * valueParts[ 2 ] :\n\t\t\t+valueParts[ 2 ];\n\t\tif ( tween ) {\n\t\t\ttween.unit = unit;\n\t\t\ttween.start = initialInUnit;\n\t\t\ttween.end = adjusted;\n\t\t}\n\t}\n\treturn adjusted;\n}\n\n\nvar defaultDisplayMap = {};\n\nfunction getDefaultDisplay( elem ) {\n\tvar temp,\n\t\tdoc = elem.ownerDocument,\n\t\tnodeName = elem.nodeName,\n\t\tdisplay = defaultDisplayMap[ nodeName ];\n\n\tif ( display ) {\n\t\treturn display;\n\t}\n\n\ttemp = doc.body.appendChild( doc.createElement( nodeName ) );\n\tdisplay = jQuery.css( temp, \"display\" );\n\n\ttemp.parentNode.removeChild( temp );\n\n\tif ( display === \"none\" ) {\n\t\tdisplay = \"block\";\n\t}\n\tdefaultDisplayMap[ nodeName ] = display;\n\n\treturn display;\n}\n\nfunction showHide( elements, show ) {\n\tvar display, elem,\n\t\tvalues = [],\n\t\tindex = 0,\n\t\tlength = elements.length;\n\n\t// Determine new display value for elements that need to change\n\tfor ( ; index < length; index++ ) {\n\t\telem = elements[ index ];\n\t\tif ( !elem.style ) {\n\t\t\tcontinue;\n\t\t}\n\n\t\tdisplay = elem.style.display;\n\t\tif ( show ) {\n\n\t\t\t// Since we force visibility upon cascade-hidden elements, an immediate (and slow)\n\t\t\t// check is required in this first loop unless we have a nonempty display value (either\n\t\t\t// inline or about-to-be-restored)\n\t\t\tif ( display === \"none\" ) {\n\t\t\t\tvalues[ index ] = dataPriv.get( elem, \"display\" ) || null;\n\t\t\t\tif ( !values[ index ] ) {\n\t\t\t\t\telem.style.display = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t\tif ( elem.style.display === \"\" && isHiddenWithinTree( elem ) ) {\n\t\t\t\tvalues[ index ] = getDefaultDisplay( elem );\n\t\t\t}\n\t\t} else {\n\t\t\tif ( display !== \"none\" ) {\n\t\t\t\tvalues[ index ] = \"none\";\n\n\t\t\t\t// Remember what we're overwriting\n\t\t\t\tdataPriv.set( elem, \"display\", display );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Set the display of the elements in a second loop to avoid constant reflow\n\tfor ( index = 0; index < length; index++ ) {\n\t\tif ( values[ index ] != null ) {\n\t\t\telements[ index ].style.display = values[ index ];\n\t\t}\n\t}\n\n\treturn elements;\n}\n\njQuery.fn.extend( {\n\tshow: function() {\n\t\treturn showHide( this, true );\n\t},\n\thide: function() {\n\t\treturn showHide( this );\n\t},\n\ttoggle: function( state ) {\n\t\tif ( typeof state === \"boolean\" ) {\n\t\t\treturn state ? this.show() : this.hide();\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tif ( isHiddenWithinTree( this ) ) {\n\t\t\t\tjQuery( this ).show();\n\t\t\t} else {\n\t\t\t\tjQuery( this ).hide();\n\t\t\t}\n\t\t} );\n\t}\n} );\nvar rcheckableType = ( /^(?:checkbox|radio)$/i );\n\nvar rtagName = ( /<([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)/i );\n\nvar rscriptType = ( /^$|^module$|\\/(?:java|ecma)script/i );\n\n\n\n// We have to close these tags to support XHTML (#13200)\nvar wrapMap = {\n\n\t// Support: IE <=9 only\n\toption: [ 1, \"<select multiple='multiple'>\", \"</select>\" ],\n\n\t// XHTML parsers do not magically insert elements in the\n\t// same way that tag soup parsers do. So we cannot shorten\n\t// this by omitting <tbody> or other required elements.\n\tthead: [ 1, \"<table>\", \"</table>\" ],\n\tcol: [ 2, \"<table><colgroup>\", \"</colgroup></table>\" ],\n\ttr: [ 2, \"<table><tbody>\", \"</tbody></table>\" ],\n\ttd: [ 3, \"<table><tbody><tr>\", \"</tr></tbody></table>\" ],\n\n\t_default: [ 0, \"\", \"\" ]\n};\n\n// Support: IE <=9 only\nwrapMap.optgroup = wrapMap.option;\n\nwrapMap.tbody = wrapMap.tfoot = wrapMap.colgroup = wrapMap.caption = wrapMap.thead;\nwrapMap.th = wrapMap.td;\n\n\nfunction getAll( context, tag ) {\n\n\t// Support: IE <=9 - 11 only\n\t// Use typeof to avoid zero-argument method invocation on host objects (#15151)\n\tvar ret;\n\n\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\tret = context.getElementsByTagName( tag || \"*\" );\n\n\t} else if ( typeof context.querySelectorAll !== \"undefined\" ) {\n\t\tret = context.querySelectorAll( tag || \"*\" );\n\n\t} else {\n\t\tret = [];\n\t}\n\n\tif ( tag === undefined || tag && nodeName( context, tag ) ) {\n\t\treturn jQuery.merge( [ context ], ret );\n\t}\n\n\treturn ret;\n}\n\n\n// Mark scripts as having already been evaluated\nfunction setGlobalEval( elems, refElements ) {\n\tvar i = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\tdataPriv.set(\n\t\t\telems[ i ],\n\t\t\t\"globalEval\",\n\t\t\t!refElements || dataPriv.get( refElements[ i ], \"globalEval\" )\n\t\t);\n\t}\n}\n\n\nvar rhtml = /<|&#?\\w+;/;\n\nfunction buildFragment( elems, context, scripts, selection, ignored ) {\n\tvar elem, tmp, tag, wrap, attached, j,\n\t\tfragment = context.createDocumentFragment(),\n\t\tnodes = [],\n\t\ti = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\telem = elems[ i ];\n\n\t\tif ( elem || elem === 0 ) {\n\n\t\t\t// Add nodes directly\n\t\t\tif ( toType( elem ) === \"object\" ) {\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, elem.nodeType ? [ elem ] : elem );\n\n\t\t\t// Convert non-html into a text node\n\t\t\t} else if ( !rhtml.test( elem ) ) {\n\t\t\t\tnodes.push( context.createTextNode( elem ) );\n\n\t\t\t// Convert html into DOM nodes\n\t\t\t} else {\n\t\t\t\ttmp = tmp || fragment.appendChild( context.createElement( \"div\" ) );\n\n\t\t\t\t// Deserialize a standard representation\n\t\t\t\ttag = ( rtagName.exec( elem ) || [ \"\", \"\" ] )[ 1 ].toLowerCase();\n\t\t\t\twrap = wrapMap[ tag ] || wrapMap._default;\n\t\t\t\ttmp.innerHTML = wrap[ 1 ] + jQuery.htmlPrefilter( elem ) + wrap[ 2 ];\n\n\t\t\t\t// Descend through wrappers to the right content\n\t\t\t\tj = wrap[ 0 ];\n\t\t\t\twhile ( j-- ) {\n\t\t\t\t\ttmp = tmp.lastChild;\n\t\t\t\t}\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, tmp.childNodes );\n\n\t\t\t\t// Remember the top-level container\n\t\t\t\ttmp = fragment.firstChild;\n\n\t\t\t\t// Ensure the created nodes are orphaned (#12392)\n\t\t\t\ttmp.textContent = \"\";\n\t\t\t}\n\t\t}\n\t}\n\n\t// Remove wrapper from fragment\n\tfragment.textContent = \"\";\n\n\ti = 0;\n\twhile ( ( elem = nodes[ i++ ] ) ) {\n\n\t\t// Skip elements already in the context collection (trac-4087)\n\t\tif ( selection && jQuery.inArray( elem, selection ) > -1 ) {\n\t\t\tif ( ignored ) {\n\t\t\t\tignored.push( elem );\n\t\t\t}\n\t\t\tcontinue;\n\t\t}\n\n\t\tattached = isAttached( elem );\n\n\t\t// Append to fragment\n\t\ttmp = getAll( fragment.appendChild( elem ), \"script\" );\n\n\t\t// Preserve script evaluation history\n\t\tif ( attached ) {\n\t\t\tsetGlobalEval( tmp );\n\t\t}\n\n\t\t// Capture executables\n\t\tif ( scripts ) {\n\t\t\tj = 0;\n\t\t\twhile ( ( elem = tmp[ j++ ] ) ) {\n\t\t\t\tif ( rscriptType.test( elem.type || \"\" ) ) {\n\t\t\t\t\tscripts.push( elem );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn fragment;\n}\n\n\n( function() {\n\tvar fragment = document.createDocumentFragment(),\n\t\tdiv = fragment.appendChild( document.createElement( \"div\" ) ),\n\t\tinput = document.createElement( \"input\" );\n\n\t// Support: Android 4.0 - 4.3 only\n\t// Check state lost if the name is set (#11217)\n\t// Support: Windows Web Apps (WWA)\n\t// `name` and `type` must use .setAttribute for WWA (#14901)\n\tinput.setAttribute( \"type\", \"radio\" );\n\tinput.setAttribute( \"checked\", \"checked\" );\n\tinput.setAttribute( \"name\", \"t\" );\n\n\tdiv.appendChild( input );\n\n\t// Support: Android <=4.1 only\n\t// Older WebKit doesn't clone checked state correctly in fragments\n\tsupport.checkClone = div.cloneNode( true ).cloneNode( true ).lastChild.checked;\n\n\t// Support: IE <=11 only\n\t// Make sure textarea (and checkbox) defaultValue is properly cloned\n\tdiv.innerHTML = \"<textarea>x</textarea>\";\n\tsupport.noCloneChecked = !!div.cloneNode( true ).lastChild.defaultValue;\n} )();\n\n\nvar\n\trkeyEvent = /^key/,\n\trmouseEvent = /^(?:mouse|pointer|contextmenu|drag|drop)|click/,\n\trtypenamespace = /^([^.]*)(?:\\.(.+)|)/;\n\nfunction returnTrue() {\n\treturn true;\n}\n\nfunction returnFalse() {\n\treturn false;\n}\n\n// Support: IE <=9 - 11+\n// focus() and blur() are asynchronous, except when they are no-op.\n// So expect focus to be synchronous when the element is already active,\n// and blur to be synchronous when the element is not already active.\n// (focus and blur are always synchronous in other supported browsers,\n// this just defines when we can count on it).\nfunction expectSync( elem, type ) {\n\treturn ( elem === safeActiveElement() ) === ( type === \"focus\" );\n}\n\n// Support: IE <=9 only\n// Accessing document.activeElement can throw unexpectedly\n// https://bugs.jquery.com/ticket/13393\nfunction safeActiveElement() {\n\ttry {\n\t\treturn document.activeElement;\n\t} catch ( err ) { }\n}\n\nfunction on( elem, types, selector, data, fn, one ) {\n\tvar origFn, type;\n\n\t// Types can be a map of types/handlers\n\tif ( typeof types === \"object\" ) {\n\n\t\t// ( types-Object, selector, data )\n\t\tif ( typeof selector !== \"string\" ) {\n\n\t\t\t// ( types-Object, data )\n\t\t\tdata = data || selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tfor ( type in types ) {\n\t\t\ton( elem, type, selector, data, types[ type ], one );\n\t\t}\n\t\treturn elem;\n\t}\n\n\tif ( data == null && fn == null ) {\n\n\t\t// ( types, fn )\n\t\tfn = selector;\n\t\tdata = selector = undefined;\n\t} else if ( fn == null ) {\n\t\tif ( typeof selector === \"string\" ) {\n\n\t\t\t// ( types, selector, fn )\n\t\t\tfn = data;\n\t\t\tdata = undefined;\n\t\t} else {\n\n\t\t\t// ( types, data, fn )\n\t\t\tfn = data;\n\t\t\tdata = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t}\n\tif ( fn === false ) {\n\t\tfn = returnFalse;\n\t} else if ( !fn ) {\n\t\treturn elem;\n\t}\n\n\tif ( one === 1 ) {\n\t\torigFn = fn;\n\t\tfn = function( event ) {\n\n\t\t\t// Can use an empty set, since event contains the info\n\t\t\tjQuery().off( event );\n\t\t\treturn origFn.apply( this, arguments );\n\t\t};\n\n\t\t// Use same guid so caller can remove using origFn\n\t\tfn.guid = origFn.guid || ( origFn.guid = jQuery.guid++ );\n\t}\n\treturn elem.each( function() {\n\t\tjQuery.event.add( this, types, fn, data, selector );\n\t} );\n}\n\n/*\n * Helper functions for managing events -- not part of the public interface.\n * Props to Dean Edwards' addEvent library for many of the ideas.\n */\njQuery.event = {\n\n\tglobal: {},\n\n\tadd: function( elem, types, handler, data, selector ) {\n\n\t\tvar handleObjIn, eventHandle, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.get( elem );\n\n\t\t// Don't attach events to noData or text/comment nodes (but allow plain objects)\n\t\tif ( !elemData ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Caller can pass in an object of custom data in lieu of the handler\n\t\tif ( handler.handler ) {\n\t\t\thandleObjIn = handler;\n\t\t\thandler = handleObjIn.handler;\n\t\t\tselector = handleObjIn.selector;\n\t\t}\n\n\t\t// Ensure that invalid selectors throw exceptions at attach time\n\t\t// Evaluate against documentElement in case elem is a non-element node (e.g., document)\n\t\tif ( selector ) {\n\t\t\tjQuery.find.matchesSelector( documentElement, selector );\n\t\t}\n\n\t\t// Make sure that the handler has a unique ID, used to find/remove it later\n\t\tif ( !handler.guid ) {\n\t\t\thandler.guid = jQuery.guid++;\n\t\t}\n\n\t\t// Init the element's event structure and main handler, if this is the first\n\t\tif ( !( events = elemData.events ) ) {\n\t\t\tevents = elemData.events = {};\n\t\t}\n\t\tif ( !( eventHandle = elemData.handle ) ) {\n\t\t\teventHandle = elemData.handle = function( e ) {\n\n\t\t\t\t// Discard the second event of a jQuery.event.trigger() and\n\t\t\t\t// when an event is called after a page has unloaded\n\t\t\t\treturn typeof jQuery !== \"undefined\" && jQuery.event.triggered !== e.type ?\n\t\t\t\t\tjQuery.event.dispatch.apply( elem, arguments ) : undefined;\n\t\t\t};\n\t\t}\n\n\t\t// Handle multiple events separated by a space\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// There *must* be a type, no attaching namespace-only handlers\n\t\t\tif ( !type ) {\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\t// If event changes its type, use the special event handlers for the changed type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// If selector defined, determine special event api type, otherwise given type\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\n\t\t\t// Update special based on newly reset type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// handleObj is passed to all event handlers\n\t\t\thandleObj = jQuery.extend( {\n\t\t\t\ttype: type,\n\t\t\t\torigType: origType,\n\t\t\t\tdata: data,\n\t\t\t\thandler: handler,\n\t\t\t\tguid: handler.guid,\n\t\t\t\tselector: selector,\n\t\t\t\tneedsContext: selector && jQuery.expr.match.needsContext.test( selector ),\n\t\t\t\tnamespace: namespaces.join( \".\" )\n\t\t\t}, handleObjIn );\n\n\t\t\t// Init the event handler queue if we're the first\n\t\t\tif ( !( handlers = events[ type ] ) ) {\n\t\t\t\thandlers = events[ type ] = [];\n\t\t\t\thandlers.delegateCount = 0;\n\n\t\t\t\t// Only use addEventListener if the special events handler returns false\n\t\t\t\tif ( !special.setup ||\n\t\t\t\t\tspecial.setup.call( elem, data, namespaces, eventHandle ) === false ) {\n\n\t\t\t\t\tif ( elem.addEventListener ) {\n\t\t\t\t\t\telem.addEventListener( type, eventHandle );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tif ( special.add ) {\n\t\t\t\tspecial.add.call( elem, handleObj );\n\n\t\t\t\tif ( !handleObj.handler.guid ) {\n\t\t\t\t\thandleObj.handler.guid = handler.guid;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Add to the element's handler list, delegates in front\n\t\t\tif ( selector ) {\n\t\t\t\thandlers.splice( handlers.delegateCount++, 0, handleObj );\n\t\t\t} else {\n\t\t\t\thandlers.push( handleObj );\n\t\t\t}\n\n\t\t\t// Keep track of which events have ever been used, for event optimization\n\t\t\tjQuery.event.global[ type ] = true;\n\t\t}\n\n\t},\n\n\t// Detach an event or set of events from an element\n\tremove: function( elem, types, handler, selector, mappedTypes ) {\n\n\t\tvar j, origCount, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.hasData( elem ) && dataPriv.get( elem );\n\n\t\tif ( !elemData || !( events = elemData.events ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Once for each type.namespace in types; type may be omitted\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// Unbind all events (on this namespace, if provided) for the element\n\t\t\tif ( !type ) {\n\t\t\t\tfor ( type in events ) {\n\t\t\t\t\tjQuery.event.remove( elem, type + types[ t ], handler, selector, true );\n\t\t\t\t}\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\t\t\thandlers = events[ type ] || [];\n\t\t\ttmp = tmp[ 2 ] &&\n\t\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" );\n\n\t\t\t// Remove matching events\n\t\t\torigCount = j = handlers.length;\n\t\t\twhile ( j-- ) {\n\t\t\t\thandleObj = handlers[ j ];\n\n\t\t\t\tif ( ( mappedTypes || origType === handleObj.origType ) &&\n\t\t\t\t\t( !handler || handler.guid === handleObj.guid ) &&\n\t\t\t\t\t( !tmp || tmp.test( handleObj.namespace ) ) &&\n\t\t\t\t\t( !selector || selector === handleObj.selector ||\n\t\t\t\t\t\tselector === \"**\" && handleObj.selector ) ) {\n\t\t\t\t\thandlers.splice( j, 1 );\n\n\t\t\t\t\tif ( handleObj.selector ) {\n\t\t\t\t\t\thandlers.delegateCount--;\n\t\t\t\t\t}\n\t\t\t\t\tif ( special.remove ) {\n\t\t\t\t\t\tspecial.remove.call( elem, handleObj );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Remove generic event handler if we removed something and no more handlers exist\n\t\t\t// (avoids potential for endless recursion during removal of special event handlers)\n\t\t\tif ( origCount && !handlers.length ) {\n\t\t\t\tif ( !special.teardown ||\n\t\t\t\t\tspecial.teardown.call( elem, namespaces, elemData.handle ) === false ) {\n\n\t\t\t\t\tjQuery.removeEvent( elem, type, elemData.handle );\n\t\t\t\t}\n\n\t\t\t\tdelete events[ type ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove data and the expando if it's no longer used\n\t\tif ( jQuery.isEmptyObject( events ) ) {\n\t\t\tdataPriv.remove( elem, \"handle events\" );\n\t\t}\n\t},\n\n\tdispatch: function( nativeEvent ) {\n\n\t\t// Make a writable jQuery.Event from the native event object\n\t\tvar event = jQuery.event.fix( nativeEvent );\n\n\t\tvar i, j, ret, matched, handleObj, handlerQueue,\n\t\t\targs = new Array( arguments.length ),\n\t\t\thandlers = ( dataPriv.get( this, \"events\" ) || {} )[ event.type ] || [],\n\t\t\tspecial = jQuery.event.special[ event.type ] || {};\n\n\t\t// Use the fix-ed jQuery.Event rather than the (read-only) native event\n\t\targs[ 0 ] = event;\n\n\t\tfor ( i = 1; i < arguments.length; i++ ) {\n\t\t\targs[ i ] = arguments[ i ];\n\t\t}\n\n\t\tevent.delegateTarget = this;\n\n\t\t// Call the preDispatch hook for the mapped type, and let it bail if desired\n\t\tif ( special.preDispatch && special.preDispatch.call( this, event ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine handlers\n\t\thandlerQueue = jQuery.event.handlers.call( this, event, handlers );\n\n\t\t// Run delegates first; they may want to stop propagation beneath us\n\t\ti = 0;\n\t\twhile ( ( matched = handlerQueue[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tevent.currentTarget = matched.elem;\n\n\t\t\tj = 0;\n\t\t\twhile ( ( handleObj = matched.handlers[ j++ ] ) &&\n\t\t\t\t!event.isImmediatePropagationStopped() ) {\n\n\t\t\t\t// If the event is namespaced, then each handler is only invoked if it is\n\t\t\t\t// specially universal or its namespaces are a superset of the event's.\n\t\t\t\tif ( !event.rnamespace || handleObj.namespace === false ||\n\t\t\t\t\tevent.rnamespace.test( handleObj.namespace ) ) {\n\n\t\t\t\t\tevent.handleObj = handleObj;\n\t\t\t\t\tevent.data = handleObj.data;\n\n\t\t\t\t\tret = ( ( jQuery.event.special[ handleObj.origType ] || {} ).handle ||\n\t\t\t\t\t\thandleObj.handler ).apply( matched.elem, args );\n\n\t\t\t\t\tif ( ret !== undefined ) {\n\t\t\t\t\t\tif ( ( event.result = ret ) === false ) {\n\t\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Call the postDispatch hook for the mapped type\n\t\tif ( special.postDispatch ) {\n\t\t\tspecial.postDispatch.call( this, event );\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\thandlers: function( event, handlers ) {\n\t\tvar i, handleObj, sel, matchedHandlers, matchedSelectors,\n\t\t\thandlerQueue = [],\n\t\t\tdelegateCount = handlers.delegateCount,\n\t\t\tcur = event.target;\n\n\t\t// Find delegate handlers\n\t\tif ( delegateCount &&\n\n\t\t\t// Support: IE <=9\n\t\t\t// Black-hole SVG <use> instance trees (trac-13180)\n\t\t\tcur.nodeType &&\n\n\t\t\t// Support: Firefox <=42\n\t\t\t// Suppress spec-violating clicks indicating a non-primary pointer button (trac-3861)\n\t\t\t// https://www.w3.org/TR/DOM-Level-3-Events/#event-type-click\n\t\t\t// Support: IE 11 only\n\t\t\t// ...but not arrow key \"clicks\" of radio inputs, which can have `button` -1 (gh-2343)\n\t\t\t!( event.type === \"click\" && event.button >= 1 ) ) {\n\n\t\t\tfor ( ; cur !== this; cur = cur.parentNode || this ) {\n\n\t\t\t\t// Don't check non-elements (#13208)\n\t\t\t\t// Don't process clicks on disabled elements (#6911, #8165, #11382, #11764)\n\t\t\t\tif ( cur.nodeType === 1 && !( event.type === \"click\" && cur.disabled === true ) ) {\n\t\t\t\t\tmatchedHandlers = [];\n\t\t\t\t\tmatchedSelectors = {};\n\t\t\t\t\tfor ( i = 0; i < delegateCount; i++ ) {\n\t\t\t\t\t\thandleObj = handlers[ i ];\n\n\t\t\t\t\t\t// Don't conflict with Object.prototype properties (#13203)\n\t\t\t\t\t\tsel = handleObj.selector + \" \";\n\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] === undefined ) {\n\t\t\t\t\t\t\tmatchedSelectors[ sel ] = handleObj.needsContext ?\n\t\t\t\t\t\t\t\tjQuery( sel, this ).index( cur ) > -1 :\n\t\t\t\t\t\t\t\tjQuery.find( sel, this, null, [ cur ] ).length;\n\t\t\t\t\t\t}\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] ) {\n\t\t\t\t\t\t\tmatchedHandlers.push( handleObj );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( matchedHandlers.length ) {\n\t\t\t\t\t\thandlerQueue.push( { elem: cur, handlers: matchedHandlers } );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Add the remaining (directly-bound) handlers\n\t\tcur = this;\n\t\tif ( delegateCount < handlers.length ) {\n\t\t\thandlerQueue.push( { elem: cur, handlers: handlers.slice( delegateCount ) } );\n\t\t}\n\n\t\treturn handlerQueue;\n\t},\n\n\taddProp: function( name, hook ) {\n\t\tObject.defineProperty( jQuery.Event.prototype, name, {\n\t\t\tenumerable: true,\n\t\t\tconfigurable: true,\n\n\t\t\tget: isFunction( hook ) ?\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn hook( this.originalEvent );\n\t\t\t\t\t}\n\t\t\t\t} :\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn this.originalEvent[ name ];\n\t\t\t\t\t}\n\t\t\t\t},\n\n\t\t\tset: function( value ) {\n\t\t\t\tObject.defineProperty( this, name, {\n\t\t\t\t\tenumerable: true,\n\t\t\t\t\tconfigurable: true,\n\t\t\t\t\twritable: true,\n\t\t\t\t\tvalue: value\n\t\t\t\t} );\n\t\t\t}\n\t\t} );\n\t},\n\n\tfix: function( originalEvent ) {\n\t\treturn originalEvent[ jQuery.expando ] ?\n\t\t\toriginalEvent :\n\t\t\tnew jQuery.Event( originalEvent );\n\t},\n\n\tspecial: {\n\t\tload: {\n\n\t\t\t// Prevent triggered image.load events from bubbling to window.load\n\t\t\tnoBubble: true\n\t\t},\n\t\tclick: {\n\n\t\t\t// Utilize native event to ensure correct state for checkable inputs\n\t\t\tsetup: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Claim the first handler\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\t// dataPriv.set( el, \"click\", ... )\n\t\t\t\t\tleverageNative( el, \"click\", returnTrue );\n\t\t\t\t}\n\n\t\t\t\t// Return false to allow normal processing in the caller\n\t\t\t\treturn false;\n\t\t\t},\n\t\t\ttrigger: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Force setup before triggering a click\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\tleverageNative( el, \"click\" );\n\t\t\t\t}\n\n\t\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\t\treturn true;\n\t\t\t},\n\n\t\t\t// For cross-browser consistency, suppress native .click() on links\n\t\t\t// Also prevent it if we're currently inside a leveraged native-event stack\n\t\t\t_default: function( event ) {\n\t\t\t\tvar target = event.target;\n\t\t\t\treturn rcheckableType.test( target.type ) &&\n\t\t\t\t\ttarget.click && nodeName( target, \"input\" ) &&\n\t\t\t\t\tdataPriv.get( target, \"click\" ) ||\n\t\t\t\t\tnodeName( target, \"a\" );\n\t\t\t}\n\t\t},\n\n\t\tbeforeunload: {\n\t\t\tpostDispatch: function( event ) {\n\n\t\t\t\t// Support: Firefox 20+\n\t\t\t\t// Firefox doesn't alert if the returnValue field is not set.\n\t\t\t\tif ( event.result !== undefined && event.originalEvent ) {\n\t\t\t\t\tevent.originalEvent.returnValue = event.result;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n};\n\n// Ensure the presence of an event listener that handles manually-triggered\n// synthetic events by interrupting progress until reinvoked in response to\n// *native* events that it fires directly, ensuring that state changes have\n// already occurred before other listeners are invoked.\nfunction leverageNative( el, type, expectSync ) {\n\n\t// Missing expectSync indicates a trigger call, which must force setup through jQuery.event.add\n\tif ( !expectSync ) {\n\t\tif ( dataPriv.get( el, type ) === undefined ) {\n\t\t\tjQuery.event.add( el, type, returnTrue );\n\t\t}\n\t\treturn;\n\t}\n\n\t// Register the controller as a special universal handler for all event namespaces\n\tdataPriv.set( el, type, false );\n\tjQuery.event.add( el, type, {\n\t\tnamespace: false,\n\t\thandler: function( event ) {\n\t\t\tvar notAsync, result,\n\t\t\t\tsaved = dataPriv.get( this, type );\n\n\t\t\tif ( ( event.isTrigger & 1 ) && this[ type ] ) {\n\n\t\t\t\t// Interrupt processing of the outer synthetic .trigger()ed event\n\t\t\t\t// Saved data should be false in such cases, but might be a leftover capture object\n\t\t\t\t// from an async native handler (gh-4350)\n\t\t\t\tif ( !saved.length ) {\n\n\t\t\t\t\t// Store arguments for use when handling the inner native event\n\t\t\t\t\t// There will always be at least one argument (an event object), so this array\n\t\t\t\t\t// will not be confused with a leftover capture object.\n\t\t\t\t\tsaved = slice.call( arguments );\n\t\t\t\t\tdataPriv.set( this, type, saved );\n\n\t\t\t\t\t// Trigger the native event and capture its result\n\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t// focus() and blur() are asynchronous\n\t\t\t\t\tnotAsync = expectSync( this, type );\n\t\t\t\t\tthis[ type ]();\n\t\t\t\t\tresult = dataPriv.get( this, type );\n\t\t\t\t\tif ( saved !== result || notAsync ) {\n\t\t\t\t\t\tdataPriv.set( this, type, false );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tresult = {};\n\t\t\t\t\t}\n\t\t\t\t\tif ( saved !== result ) {\n\n\t\t\t\t\t\t// Cancel the outer synthetic event\n\t\t\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\treturn result.value;\n\t\t\t\t\t}\n\n\t\t\t\t// If this is an inner synthetic event for an event with a bubbling surrogate\n\t\t\t\t// (focus or blur), assume that the surrogate already propagated from triggering the\n\t\t\t\t// native event and prevent that from happening again here.\n\t\t\t\t// This technically gets the ordering wrong w.r.t. to `.trigger()` (in which the\n\t\t\t\t// bubbling surrogate propagates *after* the non-bubbling base), but that seems\n\t\t\t\t// less bad than duplication.\n\t\t\t\t} else if ( ( jQuery.event.special[ type ] || {} ).delegateType ) {\n\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t}\n\n\t\t\t// If this is a native event triggered above, everything is now in order\n\t\t\t// Fire an inner synthetic event with the original arguments\n\t\t\t} else if ( saved.length ) {\n\n\t\t\t\t// ...and capture the result\n\t\t\t\tdataPriv.set( this, type, {\n\t\t\t\t\tvalue: jQuery.event.trigger(\n\n\t\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t\t// Extend with the prototype to reset the above stopImmediatePropagation()\n\t\t\t\t\t\tjQuery.extend( saved[ 0 ], jQuery.Event.prototype ),\n\t\t\t\t\t\tsaved.slice( 1 ),\n\t\t\t\t\t\tthis\n\t\t\t\t\t)\n\t\t\t\t} );\n\n\t\t\t\t// Abort handling of the native event\n\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t}\n\t\t}\n\t} );\n}\n\njQuery.removeEvent = function( elem, type, handle ) {\n\n\t// This \"if\" is needed for plain objects\n\tif ( elem.removeEventListener ) {\n\t\telem.removeEventListener( type, handle );\n\t}\n};\n\njQuery.Event = function( src, props ) {\n\n\t// Allow instantiation without the 'new' keyword\n\tif ( !( this instanceof jQuery.Event ) ) {\n\t\treturn new jQuery.Event( src, props );\n\t}\n\n\t// Event object\n\tif ( src && src.type ) {\n\t\tthis.originalEvent = src;\n\t\tthis.type = src.type;\n\n\t\t// Events bubbling up the document may have been marked as prevented\n\t\t// by a handler lower down the tree; reflect the correct value.\n\t\tthis.isDefaultPrevented = src.defaultPrevented ||\n\t\t\t\tsrc.defaultPrevented === undefined &&\n\n\t\t\t\t// Support: Android <=2.3 only\n\t\t\t\tsrc.returnValue === false ?\n\t\t\treturnTrue :\n\t\t\treturnFalse;\n\n\t\t// Create target properties\n\t\t// Support: Safari <=6 - 7 only\n\t\t// Target should not be a text node (#504, #13143)\n\t\tthis.target = ( src.target && src.target.nodeType === 3 ) ?\n\t\t\tsrc.target.parentNode :\n\t\t\tsrc.target;\n\n\t\tthis.currentTarget = src.currentTarget;\n\t\tthis.relatedTarget = src.relatedTarget;\n\n\t// Event type\n\t} else {\n\t\tthis.type = src;\n\t}\n\n\t// Put explicitly provided properties onto the event object\n\tif ( props ) {\n\t\tjQuery.extend( this, props );\n\t}\n\n\t// Create a timestamp if incoming event doesn't have one\n\tthis.timeStamp = src && src.timeStamp || Date.now();\n\n\t// Mark it as fixed\n\tthis[ jQuery.expando ] = true;\n};\n\n// jQuery.Event is based on DOM3 Events as specified by the ECMAScript Language Binding\n// https://www.w3.org/TR/2003/WD-DOM-Level-3-Events-20030331/ecma-script-binding.html\njQuery.Event.prototype = {\n\tconstructor: jQuery.Event,\n\tisDefaultPrevented: returnFalse,\n\tisPropagationStopped: returnFalse,\n\tisImmediatePropagationStopped: returnFalse,\n\tisSimulated: false,\n\n\tpreventDefault: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isDefaultPrevented = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.preventDefault();\n\t\t}\n\t},\n\tstopPropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isPropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopPropagation();\n\t\t}\n\t},\n\tstopImmediatePropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isImmediatePropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopImmediatePropagation();\n\t\t}\n\n\t\tthis.stopPropagation();\n\t}\n};\n\n// Includes all common event props including KeyEvent and MouseEvent specific props\njQuery.each( {\n\taltKey: true,\n\tbubbles: true,\n\tcancelable: true,\n\tchangedTouches: true,\n\tctrlKey: true,\n\tdetail: true,\n\teventPhase: true,\n\tmetaKey: true,\n\tpageX: true,\n\tpageY: true,\n\tshiftKey: true,\n\tview: true,\n\t\"char\": true,\n\tcode: true,\n\tcharCode: true,\n\tkey: true,\n\tkeyCode: true,\n\tbutton: true,\n\tbuttons: true,\n\tclientX: true,\n\tclientY: true,\n\toffsetX: true,\n\toffsetY: true,\n\tpointerId: true,\n\tpointerType: true,\n\tscreenX: true,\n\tscreenY: true,\n\ttargetTouches: true,\n\ttoElement: true,\n\ttouches: true,\n\n\twhich: function( event ) {\n\t\tvar button = event.button;\n\n\t\t// Add which for key events\n\t\tif ( event.which == null && rkeyEvent.test( event.type ) ) {\n\t\t\treturn event.charCode != null ? event.charCode : event.keyCode;\n\t\t}\n\n\t\t// Add which for click: 1 === left; 2 === middle; 3 === right\n\t\tif ( !event.which && button !== undefined && rmouseEvent.test( event.type ) ) {\n\t\t\tif ( button & 1 ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\tif ( button & 2 ) {\n\t\t\t\treturn 3;\n\t\t\t}\n\n\t\t\tif ( button & 4 ) {\n\t\t\t\treturn 2;\n\t\t\t}\n\n\t\t\treturn 0;\n\t\t}\n\n\t\treturn event.which;\n\t}\n}, jQuery.event.addProp );\n\njQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( type, delegateType ) {\n\tjQuery.event.special[ type ] = {\n\n\t\t// Utilize native event if possible so blur/focus sequence is correct\n\t\tsetup: function() {\n\n\t\t\t// Claim the first handler\n\t\t\t// dataPriv.set( this, \"focus\", ... )\n\t\t\t// dataPriv.set( this, \"blur\", ... )\n\t\t\tleverageNative( this, type, expectSync );\n\n\t\t\t// Return false to allow normal processing in the caller\n\t\t\treturn false;\n\t\t},\n\t\ttrigger: function() {\n\n\t\t\t// Force setup before trigger\n\t\t\tleverageNative( this, type );\n\n\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\treturn true;\n\t\t},\n\n\t\tdelegateType: delegateType\n\t};\n} );\n\n// Create mouseenter/leave events using mouseover/out and event-time checks\n// so that event delegation works in jQuery.\n// Do the same for pointerenter/pointerleave and pointerover/pointerout\n//\n// Support: Safari 7 only\n// Safari sends mouseenter too often; see:\n// https://bugs.chromium.org/p/chromium/issues/detail?id=470258\n// for the description of the bug (it existed in older Chrome versions as well).\njQuery.each( {\n\tmouseenter: \"mouseover\",\n\tmouseleave: \"mouseout\",\n\tpointerenter: \"pointerover\",\n\tpointerleave: \"pointerout\"\n}, function( orig, fix ) {\n\tjQuery.event.special[ orig ] = {\n\t\tdelegateType: fix,\n\t\tbindType: fix,\n\n\t\thandle: function( event ) {\n\t\t\tvar ret,\n\t\t\t\ttarget = this,\n\t\t\t\trelated = event.relatedTarget,\n\t\t\t\thandleObj = event.handleObj;\n\n\t\t\t// For mouseenter/leave call the handler if related is outside the target.\n\t\t\t// NB: No relatedTarget if the mouse left/entered the browser window\n\t\t\tif ( !related || ( related !== target && !jQuery.contains( target, related ) ) ) {\n\t\t\t\tevent.type = handleObj.origType;\n\t\t\t\tret = handleObj.handler.apply( this, arguments );\n\t\t\t\tevent.type = fix;\n\t\t\t}\n\t\t\treturn ret;\n\t\t}\n\t};\n} );\n\njQuery.fn.extend( {\n\n\ton: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn );\n\t},\n\tone: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn, 1 );\n\t},\n\toff: function( types, selector, fn ) {\n\t\tvar handleObj, type;\n\t\tif ( types && types.preventDefault && types.handleObj ) {\n\n\t\t\t// ( event )  dispatched jQuery.Event\n\t\t\thandleObj = types.handleObj;\n\t\t\tjQuery( types.delegateTarget ).off(\n\t\t\t\thandleObj.namespace ?\n\t\t\t\t\thandleObj.origType + \".\" + handleObj.namespace :\n\t\t\t\t\thandleObj.origType,\n\t\t\t\thandleObj.selector,\n\t\t\t\thandleObj.handler\n\t\t\t);\n\t\t\treturn this;\n\t\t}\n\t\tif ( typeof types === \"object\" ) {\n\n\t\t\t// ( types-object [, selector] )\n\t\t\tfor ( type in types ) {\n\t\t\t\tthis.off( type, selector, types[ type ] );\n\t\t\t}\n\t\t\treturn this;\n\t\t}\n\t\tif ( selector === false || typeof selector === \"function\" ) {\n\n\t\t\t// ( types [, fn] )\n\t\t\tfn = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tif ( fn === false ) {\n\t\t\tfn = returnFalse;\n\t\t}\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.remove( this, types, fn, selector );\n\t\t} );\n\t}\n} );\n\n\nvar\n\n\t/* eslint-disable max-len */\n\n\t// See https://github.com/eslint/eslint/issues/3229\n\trxhtmlTag = /<(?!area|br|col|embed|hr|img|input|link|meta|param)(([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)[^>]*)\\/>/gi,\n\n\t/* eslint-enable */\n\n\t// Support: IE <=10 - 11, Edge 12 - 13 only\n\t// In IE/Edge using regex groups here causes severe slowdowns.\n\t// See https://connect.microsoft.com/IE/feedback/details/1736512/\n\trnoInnerhtml = /<script|<style|<link/i,\n\n\t// checked=\"checked\" or checked\n\trchecked = /checked\\s*(?:[^=]|=\\s*.checked.)/i,\n\trcleanScript = /^\\s*<!(?:\\[CDATA\\[|--)|(?:\\]\\]|--)>\\s*$/g;\n\n// Prefer a tbody over its parent table for containing new rows\nfunction manipulationTarget( elem, content ) {\n\tif ( nodeName( elem, \"table\" ) &&\n\t\tnodeName( content.nodeType !== 11 ? content : content.firstChild, \"tr\" ) ) {\n\n\t\treturn jQuery( elem ).children( \"tbody\" )[ 0 ] || elem;\n\t}\n\n\treturn elem;\n}\n\n// Replace/restore the type attribute of script elements for safe DOM manipulation\nfunction disableScript( elem ) {\n\telem.type = ( elem.getAttribute( \"type\" ) !== null ) + \"/\" + elem.type;\n\treturn elem;\n}\nfunction restoreScript( elem ) {\n\tif ( ( elem.type || \"\" ).slice( 0, 5 ) === \"true/\" ) {\n\t\telem.type = elem.type.slice( 5 );\n\t} else {\n\t\telem.removeAttribute( \"type\" );\n\t}\n\n\treturn elem;\n}\n\nfunction cloneCopyEvent( src, dest ) {\n\tvar i, l, type, pdataOld, pdataCur, udataOld, udataCur, events;\n\n\tif ( dest.nodeType !== 1 ) {\n\t\treturn;\n\t}\n\n\t// 1. Copy private data: events, handlers, etc.\n\tif ( dataPriv.hasData( src ) ) {\n\t\tpdataOld = dataPriv.access( src );\n\t\tpdataCur = dataPriv.set( dest, pdataOld );\n\t\tevents = pdataOld.events;\n\n\t\tif ( events ) {\n\t\t\tdelete pdataCur.handle;\n\t\t\tpdataCur.events = {};\n\n\t\t\tfor ( type in events ) {\n\t\t\t\tfor ( i = 0, l = events[ type ].length; i < l; i++ ) {\n\t\t\t\t\tjQuery.event.add( dest, type, events[ type ][ i ] );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// 2. Copy user data\n\tif ( dataUser.hasData( src ) ) {\n\t\tudataOld = dataUser.access( src );\n\t\tudataCur = jQuery.extend( {}, udataOld );\n\n\t\tdataUser.set( dest, udataCur );\n\t}\n}\n\n// Fix IE bugs, see support tests\nfunction fixInput( src, dest ) {\n\tvar nodeName = dest.nodeName.toLowerCase();\n\n\t// Fails to persist the checked state of a cloned checkbox or radio button.\n\tif ( nodeName === \"input\" && rcheckableType.test( src.type ) ) {\n\t\tdest.checked = src.checked;\n\n\t// Fails to return the selected option to the default selected state when cloning options\n\t} else if ( nodeName === \"input\" || nodeName === \"textarea\" ) {\n\t\tdest.defaultValue = src.defaultValue;\n\t}\n}\n\nfunction domManip( collection, args, callback, ignored ) {\n\n\t// Flatten any nested arrays\n\targs = concat.apply( [], args );\n\n\tvar fragment, first, scripts, hasScripts, node, doc,\n\t\ti = 0,\n\t\tl = collection.length,\n\t\tiNoClone = l - 1,\n\t\tvalue = args[ 0 ],\n\t\tvalueIsFunction = isFunction( value );\n\n\t// We can't cloneNode fragments that contain checked, in WebKit\n\tif ( valueIsFunction ||\n\t\t\t( l > 1 && typeof value === \"string\" &&\n\t\t\t\t!support.checkClone && rchecked.test( value ) ) ) {\n\t\treturn collection.each( function( index ) {\n\t\t\tvar self = collection.eq( index );\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\targs[ 0 ] = value.call( this, index, self.html() );\n\t\t\t}\n\t\t\tdomManip( self, args, callback, ignored );\n\t\t} );\n\t}\n\n\tif ( l ) {\n\t\tfragment = buildFragment( args, collection[ 0 ].ownerDocument, false, collection, ignored );\n\t\tfirst = fragment.firstChild;\n\n\t\tif ( fragment.childNodes.length === 1 ) {\n\t\t\tfragment = first;\n\t\t}\n\n\t\t// Require either new content or an interest in ignored elements to invoke the callback\n\t\tif ( first || ignored ) {\n\t\t\tscripts = jQuery.map( getAll( fragment, \"script\" ), disableScript );\n\t\t\thasScripts = scripts.length;\n\n\t\t\t// Use the original fragment for the last item\n\t\t\t// instead of the first because it can end up\n\t\t\t// being emptied incorrectly in certain situations (#8070).\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tnode = fragment;\n\n\t\t\t\tif ( i !== iNoClone ) {\n\t\t\t\t\tnode = jQuery.clone( node, true, true );\n\n\t\t\t\t\t// Keep references to cloned scripts for later restoration\n\t\t\t\t\tif ( hasScripts ) {\n\n\t\t\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\t\t\tjQuery.merge( scripts, getAll( node, \"script\" ) );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\tcallback.call( collection[ i ], node, i );\n\t\t\t}\n\n\t\t\tif ( hasScripts ) {\n\t\t\t\tdoc = scripts[ scripts.length - 1 ].ownerDocument;\n\n\t\t\t\t// Reenable scripts\n\t\t\t\tjQuery.map( scripts, restoreScript );\n\n\t\t\t\t// Evaluate executable scripts on first document insertion\n\t\t\t\tfor ( i = 0; i < hasScripts; i++ ) {\n\t\t\t\t\tnode = scripts[ i ];\n\t\t\t\t\tif ( rscriptType.test( node.type || \"\" ) &&\n\t\t\t\t\t\t!dataPriv.access( node, \"globalEval\" ) &&\n\t\t\t\t\t\tjQuery.contains( doc, node ) ) {\n\n\t\t\t\t\t\tif ( node.src && ( node.type || \"\" ).toLowerCase()  !== \"module\" ) {\n\n\t\t\t\t\t\t\t// Optional AJAX dependency, but won't run scripts if not present\n\t\t\t\t\t\t\tif ( jQuery._evalUrl && !node.noModule ) {\n\t\t\t\t\t\t\t\tjQuery._evalUrl( node.src, {\n\t\t\t\t\t\t\t\t\tnonce: node.nonce || node.getAttribute( \"nonce\" )\n\t\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\tDOMEval( node.textContent.replace( rcleanScript, \"\" ), node, doc );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn collection;\n}\n\nfunction remove( elem, selector, keepData ) {\n\tvar node,\n\t\tnodes = selector ? jQuery.filter( selector, elem ) : elem,\n\t\ti = 0;\n\n\tfor ( ; ( node = nodes[ i ] ) != null; i++ ) {\n\t\tif ( !keepData && node.nodeType === 1 ) {\n\t\t\tjQuery.cleanData( getAll( node ) );\n\t\t}\n\n\t\tif ( node.parentNode ) {\n\t\t\tif ( keepData && isAttached( node ) ) {\n\t\t\t\tsetGlobalEval( getAll( node, \"script\" ) );\n\t\t\t}\n\t\t\tnode.parentNode.removeChild( node );\n\t\t}\n\t}\n\n\treturn elem;\n}\n\njQuery.extend( {\n\thtmlPrefilter: function( html ) {\n\t\treturn html.replace( rxhtmlTag, \"<$1></$2>\" );\n\t},\n\n\tclone: function( elem, dataAndEvents, deepDataAndEvents ) {\n\t\tvar i, l, srcElements, destElements,\n\t\t\tclone = elem.cloneNode( true ),\n\t\t\tinPage = isAttached( elem );\n\n\t\t// Fix IE cloning issues\n\t\tif ( !support.noCloneChecked && ( elem.nodeType === 1 || elem.nodeType === 11 ) &&\n\t\t\t\t!jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// We eschew Sizzle here for performance reasons: https://jsperf.com/getall-vs-sizzle/2\n\t\t\tdestElements = getAll( clone );\n\t\t\tsrcElements = getAll( elem );\n\n\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\tfixInput( srcElements[ i ], destElements[ i ] );\n\t\t\t}\n\t\t}\n\n\t\t// Copy the events from the original to the clone\n\t\tif ( dataAndEvents ) {\n\t\t\tif ( deepDataAndEvents ) {\n\t\t\t\tsrcElements = srcElements || getAll( elem );\n\t\t\t\tdestElements = destElements || getAll( clone );\n\n\t\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\t\tcloneCopyEvent( srcElements[ i ], destElements[ i ] );\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tcloneCopyEvent( elem, clone );\n\t\t\t}\n\t\t}\n\n\t\t// Preserve script evaluation history\n\t\tdestElements = getAll( clone, \"script\" );\n\t\tif ( destElements.length > 0 ) {\n\t\t\tsetGlobalEval( destElements, !inPage && getAll( elem, \"script\" ) );\n\t\t}\n\n\t\t// Return the cloned set\n\t\treturn clone;\n\t},\n\n\tcleanData: function( elems ) {\n\t\tvar data, elem, type,\n\t\t\tspecial = jQuery.event.special,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = elems[ i ] ) !== undefined; i++ ) {\n\t\t\tif ( acceptData( elem ) ) {\n\t\t\t\tif ( ( data = elem[ dataPriv.expando ] ) ) {\n\t\t\t\t\tif ( data.events ) {\n\t\t\t\t\t\tfor ( type in data.events ) {\n\t\t\t\t\t\t\tif ( special[ type ] ) {\n\t\t\t\t\t\t\t\tjQuery.event.remove( elem, type );\n\n\t\t\t\t\t\t\t// This is a shortcut to avoid jQuery.event.remove's overhead\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tjQuery.removeEvent( elem, type, data.handle );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataPriv.expando ] = undefined;\n\t\t\t\t}\n\t\t\t\tif ( elem[ dataUser.expando ] ) {\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataUser.expando ] = undefined;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n} );\n\njQuery.fn.extend( {\n\tdetach: function( selector ) {\n\t\treturn remove( this, selector, true );\n\t},\n\n\tremove: function( selector ) {\n\t\treturn remove( this, selector );\n\t},\n\n\ttext: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\treturn value === undefined ?\n\t\t\t\tjQuery.text( this ) :\n\t\t\t\tthis.empty().each( function() {\n\t\t\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\t\t\tthis.textContent = value;\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t}, null, value, arguments.length );\n\t},\n\n\tappend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.appendChild( elem );\n\t\t\t}\n\t\t} );\n\t},\n\n\tprepend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.insertBefore( elem, target.firstChild );\n\t\t\t}\n\t\t} );\n\t},\n\n\tbefore: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this );\n\t\t\t}\n\t\t} );\n\t},\n\n\tafter: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this.nextSibling );\n\t\t\t}\n\t\t} );\n\t},\n\n\tempty: function() {\n\t\tvar elem,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = this[ i ] ) != null; i++ ) {\n\t\t\tif ( elem.nodeType === 1 ) {\n\n\t\t\t\t// Prevent memory leaks\n\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\n\t\t\t\t// Remove any remaining nodes\n\t\t\t\telem.textContent = \"\";\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tclone: function( dataAndEvents, deepDataAndEvents ) {\n\t\tdataAndEvents = dataAndEvents == null ? false : dataAndEvents;\n\t\tdeepDataAndEvents = deepDataAndEvents == null ? dataAndEvents : deepDataAndEvents;\n\n\t\treturn this.map( function() {\n\t\t\treturn jQuery.clone( this, dataAndEvents, deepDataAndEvents );\n\t\t} );\n\t},\n\n\thtml: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\tvar elem = this[ 0 ] || {},\n\t\t\t\ti = 0,\n\t\t\t\tl = this.length;\n\n\t\t\tif ( value === undefined && elem.nodeType === 1 ) {\n\t\t\t\treturn elem.innerHTML;\n\t\t\t}\n\n\t\t\t// See if we can take a shortcut and just use innerHTML\n\t\t\tif ( typeof value === \"string\" && !rnoInnerhtml.test( value ) &&\n\t\t\t\t!wrapMap[ ( rtagName.exec( value ) || [ \"\", \"\" ] )[ 1 ].toLowerCase() ] ) {\n\n\t\t\t\tvalue = jQuery.htmlPrefilter( value );\n\n\t\t\t\ttry {\n\t\t\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\t\t\telem = this[ i ] || {};\n\n\t\t\t\t\t\t// Remove element nodes and prevent memory leaks\n\t\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\t\t\t\t\t\t\telem.innerHTML = value;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\telem = 0;\n\n\t\t\t\t// If using innerHTML throws an exception, use the fallback method\n\t\t\t\t} catch ( e ) {}\n\t\t\t}\n\n\t\t\tif ( elem ) {\n\t\t\t\tthis.empty().append( value );\n\t\t\t}\n\t\t}, null, value, arguments.length );\n\t},\n\n\treplaceWith: function() {\n\t\tvar ignored = [];\n\n\t\t// Make the changes, replacing each non-ignored context element with the new content\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tvar parent = this.parentNode;\n\n\t\t\tif ( jQuery.inArray( this, ignored ) < 0 ) {\n\t\t\t\tjQuery.cleanData( getAll( this ) );\n\t\t\t\tif ( parent ) {\n\t\t\t\t\tparent.replaceChild( elem, this );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Force callback invocation\n\t\t}, ignored );\n\t}\n} );\n\njQuery.each( {\n\tappendTo: \"append\",\n\tprependTo: \"prepend\",\n\tinsertBefore: \"before\",\n\tinsertAfter: \"after\",\n\treplaceAll: \"replaceWith\"\n}, function( name, original ) {\n\tjQuery.fn[ name ] = function( selector ) {\n\t\tvar elems,\n\t\t\tret = [],\n\t\t\tinsert = jQuery( selector ),\n\t\t\tlast = insert.length - 1,\n\t\t\ti = 0;\n\n\t\tfor ( ; i <= last; i++ ) {\n\t\t\telems = i === last ? this : this.clone( true );\n\t\t\tjQuery( insert[ i ] )[ original ]( elems );\n\n\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t// .get() because push.apply(_, arraylike) throws on ancient WebKit\n\t\t\tpush.apply( ret, elems.get() );\n\t\t}\n\n\t\treturn this.pushStack( ret );\n\t};\n} );\nvar rnumnonpx = new RegExp( \"^(\" + pnum + \")(?!px)[a-z%]+$\", \"i\" );\n\nvar getStyles = function( elem ) {\n\n\t\t// Support: IE <=11 only, Firefox <=30 (#15098, #14150)\n\t\t// IE throws on elements created in popups\n\t\t// FF meanwhile throws on frame elements through \"defaultView.getComputedStyle\"\n\t\tvar view = elem.ownerDocument.defaultView;\n\n\t\tif ( !view || !view.opener ) {\n\t\t\tview = window;\n\t\t}\n\n\t\treturn view.getComputedStyle( elem );\n\t};\n\nvar rboxStyle = new RegExp( cssExpand.join( \"|\" ), \"i\" );\n\n\n\n( function() {\n\n\t// Executing both pixelPosition & boxSizingReliable tests require only one layout\n\t// so they're executed at the same time to save the second computation.\n\tfunction computeStyleTests() {\n\n\t\t// This is a singleton, we need to execute it only once\n\t\tif ( !div ) {\n\t\t\treturn;\n\t\t}\n\n\t\tcontainer.style.cssText = \"position:absolute;left:-11111px;width:60px;\" +\n\t\t\t\"margin-top:1px;padding:0;border:0\";\n\t\tdiv.style.cssText =\n\t\t\t\"position:relative;display:block;box-sizing:border-box;overflow:scroll;\" +\n\t\t\t\"margin:auto;border:1px;padding:1px;\" +\n\t\t\t\"width:60%;top:1%\";\n\t\tdocumentElement.appendChild( container ).appendChild( div );\n\n\t\tvar divStyle = window.getComputedStyle( div );\n\t\tpixelPositionVal = divStyle.top !== \"1%\";\n\n\t\t// Support: Android 4.0 - 4.3 only, Firefox <=3 - 44\n\t\treliableMarginLeftVal = roundPixelMeasures( divStyle.marginLeft ) === 12;\n\n\t\t// Support: Android 4.0 - 4.3 only, Safari <=9.1 - 10.1, iOS <=7.0 - 9.3\n\t\t// Some styles come back with percentage values, even though they shouldn't\n\t\tdiv.style.right = \"60%\";\n\t\tpixelBoxStylesVal = roundPixelMeasures( divStyle.right ) === 36;\n\n\t\t// Support: IE 9 - 11 only\n\t\t// Detect misreporting of content dimensions for box-sizing:border-box elements\n\t\tboxSizingReliableVal = roundPixelMeasures( divStyle.width ) === 36;\n\n\t\t// Support: IE 9 only\n\t\t// Detect overflow:scroll screwiness (gh-3699)\n\t\t// Support: Chrome <=64\n\t\t// Don't get tricked when zoom affects offsetWidth (gh-4029)\n\t\tdiv.style.position = \"absolute\";\n\t\tscrollboxSizeVal = roundPixelMeasures( div.offsetWidth / 3 ) === 12;\n\n\t\tdocumentElement.removeChild( container );\n\n\t\t// Nullify the div so it wouldn't be stored in the memory and\n\t\t// it will also be a sign that checks already performed\n\t\tdiv = null;\n\t}\n\n\tfunction roundPixelMeasures( measure ) {\n\t\treturn Math.round( parseFloat( measure ) );\n\t}\n\n\tvar pixelPositionVal, boxSizingReliableVal, scrollboxSizeVal, pixelBoxStylesVal,\n\t\treliableMarginLeftVal,\n\t\tcontainer = document.createElement( \"div\" ),\n\t\tdiv = document.createElement( \"div\" );\n\n\t// Finish early in limited (non-browser) environments\n\tif ( !div.style ) {\n\t\treturn;\n\t}\n\n\t// Support: IE <=9 - 11 only\n\t// Style of cloned element affects source element cloned (#8908)\n\tdiv.style.backgroundClip = \"content-box\";\n\tdiv.cloneNode( true ).style.backgroundClip = \"\";\n\tsupport.clearCloneStyle = div.style.backgroundClip === \"content-box\";\n\n\tjQuery.extend( support, {\n\t\tboxSizingReliable: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn boxSizingReliableVal;\n\t\t},\n\t\tpixelBoxStyles: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelBoxStylesVal;\n\t\t},\n\t\tpixelPosition: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelPositionVal;\n\t\t},\n\t\treliableMarginLeft: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn reliableMarginLeftVal;\n\t\t},\n\t\tscrollboxSize: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn scrollboxSizeVal;\n\t\t}\n\t} );\n} )();\n\n\nfunction curCSS( elem, name, computed ) {\n\tvar width, minWidth, maxWidth, ret,\n\n\t\t// Support: Firefox 51+\n\t\t// Retrieving style before computed somehow\n\t\t// fixes an issue with getting wrong values\n\t\t// on detached elements\n\t\tstyle = elem.style;\n\n\tcomputed = computed || getStyles( elem );\n\n\t// getPropertyValue is needed for:\n\t//   .css('filter') (IE 9 only, #12537)\n\t//   .css('--customProperty) (#3144)\n\tif ( computed ) {\n\t\tret = computed.getPropertyValue( name ) || computed[ name ];\n\n\t\tif ( ret === \"\" && !isAttached( elem ) ) {\n\t\t\tret = jQuery.style( elem, name );\n\t\t}\n\n\t\t// A tribute to the \"awesome hack by Dean Edwards\"\n\t\t// Android Browser returns percentage for some values,\n\t\t// but width seems to be reliably pixels.\n\t\t// This is against the CSSOM draft spec:\n\t\t// https://drafts.csswg.org/cssom/#resolved-values\n\t\tif ( !support.pixelBoxStyles() && rnumnonpx.test( ret ) && rboxStyle.test( name ) ) {\n\n\t\t\t// Remember the original values\n\t\t\twidth = style.width;\n\t\t\tminWidth = style.minWidth;\n\t\t\tmaxWidth = style.maxWidth;\n\n\t\t\t// Put in the new values to get a computed value out\n\t\t\tstyle.minWidth = style.maxWidth = style.width = ret;\n\t\t\tret = computed.width;\n\n\t\t\t// Revert the changed values\n\t\t\tstyle.width = width;\n\t\t\tstyle.minWidth = minWidth;\n\t\t\tstyle.maxWidth = maxWidth;\n\t\t}\n\t}\n\n\treturn ret !== undefined ?\n\n\t\t// Support: IE <=9 - 11 only\n\t\t// IE returns zIndex value as an integer.\n\t\tret + \"\" :\n\t\tret;\n}\n\n\nfunction addGetHookIf( conditionFn, hookFn ) {\n\n\t// Define the hook, we'll check on the first run if it's really needed.\n\treturn {\n\t\tget: function() {\n\t\t\tif ( conditionFn() ) {\n\n\t\t\t\t// Hook not needed (or it's not possible to use it due\n\t\t\t\t// to missing dependency), remove it.\n\t\t\t\tdelete this.get;\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Hook needed; redefine it so that the support test is not executed again.\n\t\t\treturn ( this.get = hookFn ).apply( this, arguments );\n\t\t}\n\t};\n}\n\n\nvar cssPrefixes = [ \"Webkit\", \"Moz\", \"ms\" ],\n\temptyStyle = document.createElement( \"div\" ).style,\n\tvendorProps = {};\n\n// Return a vendor-prefixed property or undefined\nfunction vendorPropName( name ) {\n\n\t// Check for vendor prefixed names\n\tvar capName = name[ 0 ].toUpperCase() + name.slice( 1 ),\n\t\ti = cssPrefixes.length;\n\n\twhile ( i-- ) {\n\t\tname = cssPrefixes[ i ] + capName;\n\t\tif ( name in emptyStyle ) {\n\t\t\treturn name;\n\t\t}\n\t}\n}\n\n// Return a potentially-mapped jQuery.cssProps or vendor prefixed property\nfunction finalPropName( name ) {\n\tvar final = jQuery.cssProps[ name ] || vendorProps[ name ];\n\n\tif ( final ) {\n\t\treturn final;\n\t}\n\tif ( name in emptyStyle ) {\n\t\treturn name;\n\t}\n\treturn vendorProps[ name ] = vendorPropName( name ) || name;\n}\n\n\nvar\n\n\t// Swappable if display is none or starts with table\n\t// except \"table\", \"table-cell\", or \"table-caption\"\n\t// See here for display values: https://developer.mozilla.org/en-US/docs/CSS/display\n\trdisplayswap = /^(none|table(?!-c[ea]).+)/,\n\trcustomProp = /^--/,\n\tcssShow = { position: \"absolute\", visibility: \"hidden\", display: \"block\" },\n\tcssNormalTransform = {\n\t\tletterSpacing: \"0\",\n\t\tfontWeight: \"400\"\n\t};\n\nfunction setPositiveNumber( elem, value, subtract ) {\n\n\t// Any relative (+/-) values have already been\n\t// normalized at this point\n\tvar matches = rcssNum.exec( value );\n\treturn matches ?\n\n\t\t// Guard against undefined \"subtract\", e.g., when used as in cssHooks\n\t\tMath.max( 0, matches[ 2 ] - ( subtract || 0 ) ) + ( matches[ 3 ] || \"px\" ) :\n\t\tvalue;\n}\n\nfunction boxModelAdjustment( elem, dimension, box, isBorderBox, styles, computedVal ) {\n\tvar i = dimension === \"width\" ? 1 : 0,\n\t\textra = 0,\n\t\tdelta = 0;\n\n\t// Adjustment may not be necessary\n\tif ( box === ( isBorderBox ? \"border\" : \"content\" ) ) {\n\t\treturn 0;\n\t}\n\n\tfor ( ; i < 4; i += 2 ) {\n\n\t\t// Both box models exclude margin\n\t\tif ( box === \"margin\" ) {\n\t\t\tdelta += jQuery.css( elem, box + cssExpand[ i ], true, styles );\n\t\t}\n\n\t\t// If we get here with a content-box, we're seeking \"padding\" or \"border\" or \"margin\"\n\t\tif ( !isBorderBox ) {\n\n\t\t\t// Add padding\n\t\t\tdelta += jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\n\t\t\t// For \"border\" or \"margin\", add border\n\t\t\tif ( box !== \"padding\" ) {\n\t\t\t\tdelta += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\n\t\t\t// But still keep track of it otherwise\n\t\t\t} else {\n\t\t\t\textra += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\n\t\t// If we get here with a border-box (content + padding + border), we're seeking \"content\" or\n\t\t// \"padding\" or \"margin\"\n\t\t} else {\n\n\t\t\t// For \"content\", subtract padding\n\t\t\tif ( box === \"content\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\t\t\t}\n\n\t\t\t// For \"content\" or \"padding\", subtract border\n\t\t\tif ( box !== \"margin\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Account for positive content-box scroll gutter when requested by providing computedVal\n\tif ( !isBorderBox && computedVal >= 0 ) {\n\n\t\t// offsetWidth/offsetHeight is a rounded sum of content, padding, scroll gutter, and border\n\t\t// Assuming integer scroll gutter, subtract the rest and round down\n\t\tdelta += Math.max( 0, Math.ceil(\n\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\tcomputedVal -\n\t\t\tdelta -\n\t\t\textra -\n\t\t\t0.5\n\n\t\t// If offsetWidth/offsetHeight is unknown, then we can't determine content-box scroll gutter\n\t\t// Use an explicit zero to avoid NaN (gh-3964)\n\t\t) ) || 0;\n\t}\n\n\treturn delta;\n}\n\nfunction getWidthOrHeight( elem, dimension, extra ) {\n\n\t// Start with computed style\n\tvar styles = getStyles( elem ),\n\n\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-4322).\n\t\t// Fake content-box until we know it's needed to know the true value.\n\t\tboxSizingNeeded = !support.boxSizingReliable() || extra,\n\t\tisBorderBox = boxSizingNeeded &&\n\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\tvalueIsBorderBox = isBorderBox,\n\n\t\tval = curCSS( elem, dimension, styles ),\n\t\toffsetProp = \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 );\n\n\t// Support: Firefox <=54\n\t// Return a confounding non-pixel value or feign ignorance, as appropriate.\n\tif ( rnumnonpx.test( val ) ) {\n\t\tif ( !extra ) {\n\t\t\treturn val;\n\t\t}\n\t\tval = \"auto\";\n\t}\n\n\n\t// Fall back to offsetWidth/offsetHeight when value is \"auto\"\n\t// This happens for inline elements with no explicit setting (gh-3571)\n\t// Support: Android <=4.1 - 4.3 only\n\t// Also use offsetWidth/offsetHeight for misreported inline dimensions (gh-3602)\n\t// Support: IE 9-11 only\n\t// Also use offsetWidth/offsetHeight for when box sizing is unreliable\n\t// We use getClientRects() to check for hidden/disconnected.\n\t// In those cases, the computed value can be trusted to be border-box\n\tif ( ( !support.boxSizingReliable() && isBorderBox ||\n\t\tval === \"auto\" ||\n\t\t!parseFloat( val ) && jQuery.css( elem, \"display\", false, styles ) === \"inline\" ) &&\n\t\telem.getClientRects().length ) {\n\n\t\tisBorderBox = jQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\";\n\n\t\t// Where available, offsetWidth/offsetHeight approximate border box dimensions.\n\t\t// Where not available (e.g., SVG), assume unreliable box-sizing and interpret the\n\t\t// retrieved value as a content box dimension.\n\t\tvalueIsBorderBox = offsetProp in elem;\n\t\tif ( valueIsBorderBox ) {\n\t\t\tval = elem[ offsetProp ];\n\t\t}\n\t}\n\n\t// Normalize \"\" and auto\n\tval = parseFloat( val ) || 0;\n\n\t// Adjust for the element's box model\n\treturn ( val +\n\t\tboxModelAdjustment(\n\t\t\telem,\n\t\t\tdimension,\n\t\t\textra || ( isBorderBox ? \"border\" : \"content\" ),\n\t\t\tvalueIsBorderBox,\n\t\t\tstyles,\n\n\t\t\t// Provide the current computed size to request scroll gutter calculation (gh-3589)\n\t\t\tval\n\t\t)\n\t) + \"px\";\n}\n\njQuery.extend( {\n\n\t// Add in style property hooks for overriding the default\n\t// behavior of getting and setting a style property\n\tcssHooks: {\n\t\topacity: {\n\t\t\tget: function( elem, computed ) {\n\t\t\t\tif ( computed ) {\n\n\t\t\t\t\t// We should always get a number back from opacity\n\t\t\t\t\tvar ret = curCSS( elem, \"opacity\" );\n\t\t\t\t\treturn ret === \"\" ? \"1\" : ret;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\t// Don't automatically add \"px\" to these possibly-unitless properties\n\tcssNumber: {\n\t\t\"animationIterationCount\": true,\n\t\t\"columnCount\": true,\n\t\t\"fillOpacity\": true,\n\t\t\"flexGrow\": true,\n\t\t\"flexShrink\": true,\n\t\t\"fontWeight\": true,\n\t\t\"gridArea\": true,\n\t\t\"gridColumn\": true,\n\t\t\"gridColumnEnd\": true,\n\t\t\"gridColumnStart\": true,\n\t\t\"gridRow\": true,\n\t\t\"gridRowEnd\": true,\n\t\t\"gridRowStart\": true,\n\t\t\"lineHeight\": true,\n\t\t\"opacity\": true,\n\t\t\"order\": true,\n\t\t\"orphans\": true,\n\t\t\"widows\": true,\n\t\t\"zIndex\": true,\n\t\t\"zoom\": true\n\t},\n\n\t// Add in properties whose names you wish to fix before\n\t// setting or getting the value\n\tcssProps: {},\n\n\t// Get and set the style property on a DOM Node\n\tstyle: function( elem, name, value, extra ) {\n\n\t\t// Don't set styles on text and comment nodes\n\t\tif ( !elem || elem.nodeType === 3 || elem.nodeType === 8 || !elem.style ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Make sure that we're working with the right name\n\t\tvar ret, type, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name ),\n\t\t\tstyle = elem.style;\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to query the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Gets hook for the prefixed version, then unprefixed version\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// Check if we're setting a value\n\t\tif ( value !== undefined ) {\n\t\t\ttype = typeof value;\n\n\t\t\t// Convert \"+=\" or \"-=\" to relative numbers (#7345)\n\t\t\tif ( type === \"string\" && ( ret = rcssNum.exec( value ) ) && ret[ 1 ] ) {\n\t\t\t\tvalue = adjustCSS( elem, name, ret );\n\n\t\t\t\t// Fixes bug #9237\n\t\t\t\ttype = \"number\";\n\t\t\t}\n\n\t\t\t// Make sure that null and NaN values aren't set (#7116)\n\t\t\tif ( value == null || value !== value ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// If a number was passed in, add the unit (except for certain CSS properties)\n\t\t\t// The isCustomProp check can be removed in jQuery 4.0 when we only auto-append\n\t\t\t// \"px\" to a few hardcoded values.\n\t\t\tif ( type === \"number\" && !isCustomProp ) {\n\t\t\t\tvalue += ret && ret[ 3 ] || ( jQuery.cssNumber[ origName ] ? \"\" : \"px\" );\n\t\t\t}\n\n\t\t\t// background-* props affect original clone's values\n\t\t\tif ( !support.clearCloneStyle && value === \"\" && name.indexOf( \"background\" ) === 0 ) {\n\t\t\t\tstyle[ name ] = \"inherit\";\n\t\t\t}\n\n\t\t\t// If a hook was provided, use that value, otherwise just set the specified value\n\t\t\tif ( !hooks || !( \"set\" in hooks ) ||\n\t\t\t\t( value = hooks.set( elem, value, extra ) ) !== undefined ) {\n\n\t\t\t\tif ( isCustomProp ) {\n\t\t\t\t\tstyle.setProperty( name, value );\n\t\t\t\t} else {\n\t\t\t\t\tstyle[ name ] = value;\n\t\t\t\t}\n\t\t\t}\n\n\t\t} else {\n\n\t\t\t// If a hook was provided get the non-computed value from there\n\t\t\tif ( hooks && \"get\" in hooks &&\n\t\t\t\t( ret = hooks.get( elem, false, extra ) ) !== undefined ) {\n\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\t// Otherwise just get the value from the style object\n\t\t\treturn style[ name ];\n\t\t}\n\t},\n\n\tcss: function( elem, name, extra, styles ) {\n\t\tvar val, num, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name );\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to modify the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Try prefixed name followed by the unprefixed name\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// If a hook was provided get the computed value from there\n\t\tif ( hooks && \"get\" in hooks ) {\n\t\t\tval = hooks.get( elem, true, extra );\n\t\t}\n\n\t\t// Otherwise, if a way to get the computed value exists, use that\n\t\tif ( val === undefined ) {\n\t\t\tval = curCSS( elem, name, styles );\n\t\t}\n\n\t\t// Convert \"normal\" to computed value\n\t\tif ( val === \"normal\" && name in cssNormalTransform ) {\n\t\t\tval = cssNormalTransform[ name ];\n\t\t}\n\n\t\t// Make numeric if forced or a qualifier was provided and val looks numeric\n\t\tif ( extra === \"\" || extra ) {\n\t\t\tnum = parseFloat( val );\n\t\t\treturn extra === true || isFinite( num ) ? num || 0 : val;\n\t\t}\n\n\t\treturn val;\n\t}\n} );\n\njQuery.each( [ \"height\", \"width\" ], function( i, dimension ) {\n\tjQuery.cssHooks[ dimension ] = {\n\t\tget: function( elem, computed, extra ) {\n\t\t\tif ( computed ) {\n\n\t\t\t\t// Certain elements can have dimension info if we invisibly show them\n\t\t\t\t// but it must have a current display style that would benefit\n\t\t\t\treturn rdisplayswap.test( jQuery.css( elem, \"display\" ) ) &&\n\n\t\t\t\t\t// Support: Safari 8+\n\t\t\t\t\t// Table columns in Safari have non-zero offsetWidth & zero\n\t\t\t\t\t// getBoundingClientRect().width unless display is changed.\n\t\t\t\t\t// Support: IE <=11 only\n\t\t\t\t\t// Running getBoundingClientRect on a disconnected node\n\t\t\t\t\t// in IE throws an error.\n\t\t\t\t\t( !elem.getClientRects().length || !elem.getBoundingClientRect().width ) ?\n\t\t\t\t\t\tswap( elem, cssShow, function() {\n\t\t\t\t\t\t\treturn getWidthOrHeight( elem, dimension, extra );\n\t\t\t\t\t\t} ) :\n\t\t\t\t\t\tgetWidthOrHeight( elem, dimension, extra );\n\t\t\t}\n\t\t},\n\n\t\tset: function( elem, value, extra ) {\n\t\t\tvar matches,\n\t\t\t\tstyles = getStyles( elem ),\n\n\t\t\t\t// Only read styles.position if the test has a chance to fail\n\t\t\t\t// to avoid forcing a reflow.\n\t\t\t\tscrollboxSizeBuggy = !support.scrollboxSize() &&\n\t\t\t\t\tstyles.position === \"absolute\",\n\n\t\t\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-3991)\n\t\t\t\tboxSizingNeeded = scrollboxSizeBuggy || extra,\n\t\t\t\tisBorderBox = boxSizingNeeded &&\n\t\t\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\t\t\tsubtract = extra ?\n\t\t\t\t\tboxModelAdjustment(\n\t\t\t\t\t\telem,\n\t\t\t\t\t\tdimension,\n\t\t\t\t\t\textra,\n\t\t\t\t\t\tisBorderBox,\n\t\t\t\t\t\tstyles\n\t\t\t\t\t) :\n\t\t\t\t\t0;\n\n\t\t\t// Account for unreliable border-box dimensions by comparing offset* to computed and\n\t\t\t// faking a content-box to get border and padding (gh-3699)\n\t\t\tif ( isBorderBox && scrollboxSizeBuggy ) {\n\t\t\t\tsubtract -= Math.ceil(\n\t\t\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\t\t\tparseFloat( styles[ dimension ] ) -\n\t\t\t\t\tboxModelAdjustment( elem, dimension, \"border\", false, styles ) -\n\t\t\t\t\t0.5\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// Convert to pixels if value adjustment is needed\n\t\t\tif ( subtract && ( matches = rcssNum.exec( value ) ) &&\n\t\t\t\t( matches[ 3 ] || \"px\" ) !== \"px\" ) {\n\n\t\t\t\telem.style[ dimension ] = value;\n\t\t\t\tvalue = jQuery.css( elem, dimension );\n\t\t\t}\n\n\t\t\treturn setPositiveNumber( elem, value, subtract );\n\t\t}\n\t};\n} );\n\njQuery.cssHooks.marginLeft = addGetHookIf( support.reliableMarginLeft,\n\tfunction( elem, computed ) {\n\t\tif ( computed ) {\n\t\t\treturn ( parseFloat( curCSS( elem, \"marginLeft\" ) ) ||\n\t\t\t\telem.getBoundingClientRect().left -\n\t\t\t\t\tswap( elem, { marginLeft: 0 }, function() {\n\t\t\t\t\t\treturn elem.getBoundingClientRect().left;\n\t\t\t\t\t} )\n\t\t\t\t) + \"px\";\n\t\t}\n\t}\n);\n\n// These hooks are used by animate to expand properties\njQuery.each( {\n\tmargin: \"\",\n\tpadding: \"\",\n\tborder: \"Width\"\n}, function( prefix, suffix ) {\n\tjQuery.cssHooks[ prefix + suffix ] = {\n\t\texpand: function( value ) {\n\t\t\tvar i = 0,\n\t\t\t\texpanded = {},\n\n\t\t\t\t// Assumes a single number if not a string\n\t\t\t\tparts = typeof value === \"string\" ? value.split( \" \" ) : [ value ];\n\n\t\t\tfor ( ; i < 4; i++ ) {\n\t\t\t\texpanded[ prefix + cssExpand[ i ] + suffix ] =\n\t\t\t\t\tparts[ i ] || parts[ i - 2 ] || parts[ 0 ];\n\t\t\t}\n\n\t\t\treturn expanded;\n\t\t}\n\t};\n\n\tif ( prefix !== \"margin\" ) {\n\t\tjQuery.cssHooks[ prefix + suffix ].set = setPositiveNumber;\n\t}\n} );\n\njQuery.fn.extend( {\n\tcss: function( name, value ) {\n\t\treturn access( this, function( elem, name, value ) {\n\t\t\tvar styles, len,\n\t\t\t\tmap = {},\n\t\t\t\ti = 0;\n\n\t\t\tif ( Array.isArray( name ) ) {\n\t\t\t\tstyles = getStyles( elem );\n\t\t\t\tlen = name.length;\n\n\t\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\t\tmap[ name[ i ] ] = jQuery.css( elem, name[ i ], false, styles );\n\t\t\t\t}\n\n\t\t\t\treturn map;\n\t\t\t}\n\n\t\t\treturn value !== undefined ?\n\t\t\t\tjQuery.style( elem, name, value ) :\n\t\t\t\tjQuery.css( elem, name );\n\t\t}, name, value, arguments.length > 1 );\n\t}\n} );\n\n\nfunction Tween( elem, options, prop, end, easing ) {\n\treturn new Tween.prototype.init( elem, options, prop, end, easing );\n}\njQuery.Tween = Tween;\n\nTween.prototype = {\n\tconstructor: Tween,\n\tinit: function( elem, options, prop, end, easing, unit ) {\n\t\tthis.elem = elem;\n\t\tthis.prop = prop;\n\t\tthis.easing = easing || jQuery.easing._default;\n\t\tthis.options = options;\n\t\tthis.start = this.now = this.cur();\n\t\tthis.end = end;\n\t\tthis.unit = unit || ( jQuery.cssNumber[ prop ] ? \"\" : \"px\" );\n\t},\n\tcur: function() {\n\t\tvar hooks = Tween.propHooks[ this.prop ];\n\n\t\treturn hooks && hooks.get ?\n\t\t\thooks.get( this ) :\n\t\t\tTween.propHooks._default.get( this );\n\t},\n\trun: function( percent ) {\n\t\tvar eased,\n\t\t\thooks = Tween.propHooks[ this.prop ];\n\n\t\tif ( this.options.duration ) {\n\t\t\tthis.pos = eased = jQuery.easing[ this.easing ](\n\t\t\t\tpercent, this.options.duration * percent, 0, 1, this.options.duration\n\t\t\t);\n\t\t} else {\n\t\t\tthis.pos = eased = percent;\n\t\t}\n\t\tthis.now = ( this.end - this.start ) * eased + this.start;\n\n\t\tif ( this.options.step ) {\n\t\t\tthis.options.step.call( this.elem, this.now, this );\n\t\t}\n\n\t\tif ( hooks && hooks.set ) {\n\t\t\thooks.set( this );\n\t\t} else {\n\t\t\tTween.propHooks._default.set( this );\n\t\t}\n\t\treturn this;\n\t}\n};\n\nTween.prototype.init.prototype = Tween.prototype;\n\nTween.propHooks = {\n\t_default: {\n\t\tget: function( tween ) {\n\t\t\tvar result;\n\n\t\t\t// Use a property on the element directly when it is not a DOM element,\n\t\t\t// or when there is no matching style property that exists.\n\t\t\tif ( tween.elem.nodeType !== 1 ||\n\t\t\t\ttween.elem[ tween.prop ] != null && tween.elem.style[ tween.prop ] == null ) {\n\t\t\t\treturn tween.elem[ tween.prop ];\n\t\t\t}\n\n\t\t\t// Passing an empty string as a 3rd parameter to .css will automatically\n\t\t\t// attempt a parseFloat and fallback to a string if the parse fails.\n\t\t\t// Simple values such as \"10px\" are parsed to Float;\n\t\t\t// complex values such as \"rotate(1rad)\" are returned as-is.\n\t\t\tresult = jQuery.css( tween.elem, tween.prop, \"\" );\n\n\t\t\t// Empty strings, null, undefined and \"auto\" are converted to 0.\n\t\t\treturn !result || result === \"auto\" ? 0 : result;\n\t\t},\n\t\tset: function( tween ) {\n\n\t\t\t// Use step hook for back compat.\n\t\t\t// Use cssHook if its there.\n\t\t\t// Use .style if available and use plain properties where available.\n\t\t\tif ( jQuery.fx.step[ tween.prop ] ) {\n\t\t\t\tjQuery.fx.step[ tween.prop ]( tween );\n\t\t\t} else if ( tween.elem.nodeType === 1 && (\n\t\t\t\t\tjQuery.cssHooks[ tween.prop ] ||\n\t\t\t\t\ttween.elem.style[ finalPropName( tween.prop ) ] != null ) ) {\n\t\t\t\tjQuery.style( tween.elem, tween.prop, tween.now + tween.unit );\n\t\t\t} else {\n\t\t\t\ttween.elem[ tween.prop ] = tween.now;\n\t\t\t}\n\t\t}\n\t}\n};\n\n// Support: IE <=9 only\n// Panic based approach to setting things on disconnected nodes\nTween.propHooks.scrollTop = Tween.propHooks.scrollLeft = {\n\tset: function( tween ) {\n\t\tif ( tween.elem.nodeType && tween.elem.parentNode ) {\n\t\t\ttween.elem[ tween.prop ] = tween.now;\n\t\t}\n\t}\n};\n\njQuery.easing = {\n\tlinear: function( p ) {\n\t\treturn p;\n\t},\n\tswing: function( p ) {\n\t\treturn 0.5 - Math.cos( p * Math.PI ) / 2;\n\t},\n\t_default: \"swing\"\n};\n\njQuery.fx = Tween.prototype.init;\n\n// Back compat <1.8 extension point\njQuery.fx.step = {};\n\n\n\n\nvar\n\tfxNow, inProgress,\n\trfxtypes = /^(?:toggle|show|hide)$/,\n\trrun = /queueHooks$/;\n\nfunction schedule() {\n\tif ( inProgress ) {\n\t\tif ( document.hidden === false && window.requestAnimationFrame ) {\n\t\t\twindow.requestAnimationFrame( schedule );\n\t\t} else {\n\t\t\twindow.setTimeout( schedule, jQuery.fx.interval );\n\t\t}\n\n\t\tjQuery.fx.tick();\n\t}\n}\n\n// Animations created synchronously will run synchronously\nfunction createFxNow() {\n\twindow.setTimeout( function() {\n\t\tfxNow = undefined;\n\t} );\n\treturn ( fxNow = Date.now() );\n}\n\n// Generate parameters to create a standard animation\nfunction genFx( type, includeWidth ) {\n\tvar which,\n\t\ti = 0,\n\t\tattrs = { height: type };\n\n\t// If we include width, step value is 1 to do all cssExpand values,\n\t// otherwise step value is 2 to skip over Left and Right\n\tincludeWidth = includeWidth ? 1 : 0;\n\tfor ( ; i < 4; i += 2 - includeWidth ) {\n\t\twhich = cssExpand[ i ];\n\t\tattrs[ \"margin\" + which ] = attrs[ \"padding\" + which ] = type;\n\t}\n\n\tif ( includeWidth ) {\n\t\tattrs.opacity = attrs.width = type;\n\t}\n\n\treturn attrs;\n}\n\nfunction createTween( value, prop, animation ) {\n\tvar tween,\n\t\tcollection = ( Animation.tweeners[ prop ] || [] ).concat( Animation.tweeners[ \"*\" ] ),\n\t\tindex = 0,\n\t\tlength = collection.length;\n\tfor ( ; index < length; index++ ) {\n\t\tif ( ( tween = collection[ index ].call( animation, prop, value ) ) ) {\n\n\t\t\t// We're done with this property\n\t\t\treturn tween;\n\t\t}\n\t}\n}\n\nfunction defaultPrefilter( elem, props, opts ) {\n\tvar prop, value, toggle, hooks, oldfire, propTween, restoreDisplay, display,\n\t\tisBox = \"width\" in props || \"height\" in props,\n\t\tanim = this,\n\t\torig = {},\n\t\tstyle = elem.style,\n\t\thidden = elem.nodeType && isHiddenWithinTree( elem ),\n\t\tdataShow = dataPriv.get( elem, \"fxshow\" );\n\n\t// Queue-skipping animations hijack the fx hooks\n\tif ( !opts.queue ) {\n\t\thooks = jQuery._queueHooks( elem, \"fx\" );\n\t\tif ( hooks.unqueued == null ) {\n\t\t\thooks.unqueued = 0;\n\t\t\toldfire = hooks.empty.fire;\n\t\t\thooks.empty.fire = function() {\n\t\t\t\tif ( !hooks.unqueued ) {\n\t\t\t\t\toldfire();\n\t\t\t\t}\n\t\t\t};\n\t\t}\n\t\thooks.unqueued++;\n\n\t\tanim.always( function() {\n\n\t\t\t// Ensure the complete handler is called before this completes\n\t\t\tanim.always( function() {\n\t\t\t\thooks.unqueued--;\n\t\t\t\tif ( !jQuery.queue( elem, \"fx\" ).length ) {\n\t\t\t\t\thooks.empty.fire();\n\t\t\t\t}\n\t\t\t} );\n\t\t} );\n\t}\n\n\t// Detect show/hide animations\n\tfor ( prop in props ) {\n\t\tvalue = props[ prop ];\n\t\tif ( rfxtypes.test( value ) ) {\n\t\t\tdelete props[ prop ];\n\t\t\ttoggle = toggle || value === \"toggle\";\n\t\t\tif ( value === ( hidden ? \"hide\" : \"show\" ) ) {\n\n\t\t\t\t// Pretend to be hidden if this is a \"show\" and\n\t\t\t\t// there is still data from a stopped show/hide\n\t\t\t\tif ( value === \"show\" && dataShow && dataShow[ prop ] !== undefined ) {\n\t\t\t\t\thidden = true;\n\n\t\t\t\t// Ignore all other no-op show/hide data\n\t\t\t\t} else {\n\t\t\t\t\tcontinue;\n\t\t\t\t}\n\t\t\t}\n\t\t\torig[ prop ] = dataShow && dataShow[ prop ] || jQuery.style( elem, prop );\n\t\t}\n\t}\n\n\t// Bail out if this is a no-op like .hide().hide()\n\tpropTween = !jQuery.isEmptyObject( props );\n\tif ( !propTween && jQuery.isEmptyObject( orig ) ) {\n\t\treturn;\n\t}\n\n\t// Restrict \"overflow\" and \"display\" styles during box animations\n\tif ( isBox && elem.nodeType === 1 ) {\n\n\t\t// Support: IE <=9 - 11, Edge 12 - 15\n\t\t// Record all 3 overflow attributes because IE does not infer the shorthand\n\t\t// from identically-valued overflowX and overflowY and Edge just mirrors\n\t\t// the overflowX value there.\n\t\topts.overflow = [ style.overflow, style.overflowX, style.overflowY ];\n\n\t\t// Identify a display type, preferring old show/hide data over the CSS cascade\n\t\trestoreDisplay = dataShow && dataShow.display;\n\t\tif ( restoreDisplay == null ) {\n\t\t\trestoreDisplay = dataPriv.get( elem, \"display\" );\n\t\t}\n\t\tdisplay = jQuery.css( elem, \"display\" );\n\t\tif ( display === \"none\" ) {\n\t\t\tif ( restoreDisplay ) {\n\t\t\t\tdisplay = restoreDisplay;\n\t\t\t} else {\n\n\t\t\t\t// Get nonempty value(s) by temporarily forcing visibility\n\t\t\t\tshowHide( [ elem ], true );\n\t\t\t\trestoreDisplay = elem.style.display || restoreDisplay;\n\t\t\t\tdisplay = jQuery.css( elem, \"display\" );\n\t\t\t\tshowHide( [ elem ] );\n\t\t\t}\n\t\t}\n\n\t\t// Animate inline elements as inline-block\n\t\tif ( display === \"inline\" || display === \"inline-block\" && restoreDisplay != null ) {\n\t\t\tif ( jQuery.css( elem, \"float\" ) === \"none\" ) {\n\n\t\t\t\t// Restore the original display value at the end of pure show/hide animations\n\t\t\t\tif ( !propTween ) {\n\t\t\t\t\tanim.done( function() {\n\t\t\t\t\t\tstyle.display = restoreDisplay;\n\t\t\t\t\t} );\n\t\t\t\t\tif ( restoreDisplay == null ) {\n\t\t\t\t\t\tdisplay = style.display;\n\t\t\t\t\t\trestoreDisplay = display === \"none\" ? \"\" : display;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\tstyle.display = \"inline-block\";\n\t\t\t}\n\t\t}\n\t}\n\n\tif ( opts.overflow ) {\n\t\tstyle.overflow = \"hidden\";\n\t\tanim.always( function() {\n\t\t\tstyle.overflow = opts.overflow[ 0 ];\n\t\t\tstyle.overflowX = opts.overflow[ 1 ];\n\t\t\tstyle.overflowY = opts.overflow[ 2 ];\n\t\t} );\n\t}\n\n\t// Implement show/hide animations\n\tpropTween = false;\n\tfor ( prop in orig ) {\n\n\t\t// General show/hide setup for this element animation\n\t\tif ( !propTween ) {\n\t\t\tif ( dataShow ) {\n\t\t\t\tif ( \"hidden\" in dataShow ) {\n\t\t\t\t\thidden = dataShow.hidden;\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tdataShow = dataPriv.access( elem, \"fxshow\", { display: restoreDisplay } );\n\t\t\t}\n\n\t\t\t// Store hidden/visible for toggle so `.stop().toggle()` \"reverses\"\n\t\t\tif ( toggle ) {\n\t\t\t\tdataShow.hidden = !hidden;\n\t\t\t}\n\n\t\t\t// Show elements before animating them\n\t\t\tif ( hidden ) {\n\t\t\t\tshowHide( [ elem ], true );\n\t\t\t}\n\n\t\t\t/* eslint-disable no-loop-func */\n\n\t\t\tanim.done( function() {\n\n\t\t\t/* eslint-enable no-loop-func */\n\n\t\t\t\t// The final step of a \"hide\" animation is actually hiding the element\n\t\t\t\tif ( !hidden ) {\n\t\t\t\t\tshowHide( [ elem ] );\n\t\t\t\t}\n\t\t\t\tdataPriv.remove( elem, \"fxshow\" );\n\t\t\t\tfor ( prop in orig ) {\n\t\t\t\t\tjQuery.style( elem, prop, orig[ prop ] );\n\t\t\t\t}\n\t\t\t} );\n\t\t}\n\n\t\t// Per-property setup\n\t\tpropTween = createTween( hidden ? dataShow[ prop ] : 0, prop, anim );\n\t\tif ( !( prop in dataShow ) ) {\n\t\t\tdataShow[ prop ] = propTween.start;\n\t\t\tif ( hidden ) {\n\t\t\t\tpropTween.end = propTween.start;\n\t\t\t\tpropTween.start = 0;\n\t\t\t}\n\t\t}\n\t}\n}\n\nfunction propFilter( props, specialEasing ) {\n\tvar index, name, easing, value, hooks;\n\n\t// camelCase, specialEasing and expand cssHook pass\n\tfor ( index in props ) {\n\t\tname = camelCase( index );\n\t\teasing = specialEasing[ name ];\n\t\tvalue = props[ index ];\n\t\tif ( Array.isArray( value ) ) {\n\t\t\teasing = value[ 1 ];\n\t\t\tvalue = props[ index ] = value[ 0 ];\n\t\t}\n\n\t\tif ( index !== name ) {\n\t\t\tprops[ name ] = value;\n\t\t\tdelete props[ index ];\n\t\t}\n\n\t\thooks = jQuery.cssHooks[ name ];\n\t\tif ( hooks && \"expand\" in hooks ) {\n\t\t\tvalue = hooks.expand( value );\n\t\t\tdelete props[ name ];\n\n\t\t\t// Not quite $.extend, this won't overwrite existing keys.\n\t\t\t// Reusing 'index' because we have the correct \"name\"\n\t\t\tfor ( index in value ) {\n\t\t\t\tif ( !( index in props ) ) {\n\t\t\t\t\tprops[ index ] = value[ index ];\n\t\t\t\t\tspecialEasing[ index ] = easing;\n\t\t\t\t}\n\t\t\t}\n\t\t} else {\n\t\t\tspecialEasing[ name ] = easing;\n\t\t}\n\t}\n}\n\nfunction Animation( elem, properties, options ) {\n\tvar result,\n\t\tstopped,\n\t\tindex = 0,\n\t\tlength = Animation.prefilters.length,\n\t\tdeferred = jQuery.Deferred().always( function() {\n\n\t\t\t// Don't match elem in the :animated selector\n\t\t\tdelete tick.elem;\n\t\t} ),\n\t\ttick = function() {\n\t\t\tif ( stopped ) {\n\t\t\t\treturn false;\n\t\t\t}\n\t\t\tvar currentTime = fxNow || createFxNow(),\n\t\t\t\tremaining = Math.max( 0, animation.startTime + animation.duration - currentTime ),\n\n\t\t\t\t// Support: Android 2.3 only\n\t\t\t\t// Archaic crash bug won't allow us to use `1 - ( 0.5 || 0 )` (#12497)\n\t\t\t\ttemp = remaining / animation.duration || 0,\n\t\t\t\tpercent = 1 - temp,\n\t\t\t\tindex = 0,\n\t\t\t\tlength = animation.tweens.length;\n\n\t\t\tfor ( ; index < length; index++ ) {\n\t\t\t\tanimation.tweens[ index ].run( percent );\n\t\t\t}\n\n\t\t\tdeferred.notifyWith( elem, [ animation, percent, remaining ] );\n\n\t\t\t// If there's more to do, yield\n\t\t\tif ( percent < 1 && length ) {\n\t\t\t\treturn remaining;\n\t\t\t}\n\n\t\t\t// If this was an empty animation, synthesize a final progress notification\n\t\t\tif ( !length ) {\n\t\t\t\tdeferred.notifyWith( elem, [ animation, 1, 0 ] );\n\t\t\t}\n\n\t\t\t// Resolve the animation and report its conclusion\n\t\t\tdeferred.resolveWith( elem, [ animation ] );\n\t\t\treturn false;\n\t\t},\n\t\tanimation = deferred.promise( {\n\t\t\telem: elem,\n\t\t\tprops: jQuery.extend( {}, properties ),\n\t\t\topts: jQuery.extend( true, {\n\t\t\t\tspecialEasing: {},\n\t\t\t\teasing: jQuery.easing._default\n\t\t\t}, options ),\n\t\t\toriginalProperties: properties,\n\t\t\toriginalOptions: options,\n\t\t\tstartTime: fxNow || createFxNow(),\n\t\t\tduration: options.duration,\n\t\t\ttweens: [],\n\t\t\tcreateTween: function( prop, end ) {\n\t\t\t\tvar tween = jQuery.Tween( elem, animation.opts, prop, end,\n\t\t\t\t\t\tanimation.opts.specialEasing[ prop ] || animation.opts.easing );\n\t\t\t\tanimation.tweens.push( tween );\n\t\t\t\treturn tween;\n\t\t\t},\n\t\t\tstop: function( gotoEnd ) {\n\t\t\t\tvar index = 0,\n\n\t\t\t\t\t// If we are going to the end, we want to run all the tweens\n\t\t\t\t\t// otherwise we skip this part\n\t\t\t\t\tlength = gotoEnd ? animation.tweens.length : 0;\n\t\t\t\tif ( stopped ) {\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\t\t\t\tstopped = true;\n\t\t\t\tfor ( ; index < length; index++ ) {\n\t\t\t\t\tanimation.tweens[ index ].run( 1 );\n\t\t\t\t}\n\n\t\t\t\t// Resolve when we played the last frame; otherwise, reject\n\t\t\t\tif ( gotoEnd ) {\n\t\t\t\t\tdeferred.notifyWith( elem, [ animation, 1, 0 ] );\n\t\t\t\t\tdeferred.resolveWith( elem, [ animation, gotoEnd ] );\n\t\t\t\t} else {\n\t\t\t\t\tdeferred.rejectWith( elem, [ animation, gotoEnd ] );\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t}\n\t\t} ),\n\t\tprops = animation.props;\n\n\tpropFilter( props, animation.opts.specialEasing );\n\n\tfor ( ; index < length; index++ ) {\n\t\tresult = Animation.prefilters[ index ].call( animation, elem, props, animation.opts );\n\t\tif ( result ) {\n\t\t\tif ( isFunction( result.stop ) ) {\n\t\t\t\tjQuery._queueHooks( animation.elem, animation.opts.queue ).stop =\n\t\t\t\t\tresult.stop.bind( result );\n\t\t\t}\n\t\t\treturn result;\n\t\t}\n\t}\n\n\tjQuery.map( props, createTween, animation );\n\n\tif ( isFunction( animation.opts.start ) ) {\n\t\tanimation.opts.start.call( elem, animation );\n\t}\n\n\t// Attach callbacks from options\n\tanimation\n\t\t.progress( animation.opts.progress )\n\t\t.done( animation.opts.done, animation.opts.complete )\n\t\t.fail( animation.opts.fail )\n\t\t.always( animation.opts.always );\n\n\tjQuery.fx.timer(\n\t\tjQuery.extend( tick, {\n\t\t\telem: elem,\n\t\t\tanim: animation,\n\t\t\tqueue: animation.opts.queue\n\t\t} )\n\t);\n\n\treturn animation;\n}\n\njQuery.Animation = jQuery.extend( Animation, {\n\n\ttweeners: {\n\t\t\"*\": [ function( prop, value ) {\n\t\t\tvar tween = this.createTween( prop, value );\n\t\t\tadjustCSS( tween.elem, prop, rcssNum.exec( value ), tween );\n\t\t\treturn tween;\n\t\t} ]\n\t},\n\n\ttweener: function( props, callback ) {\n\t\tif ( isFunction( props ) ) {\n\t\t\tcallback = props;\n\t\t\tprops = [ \"*\" ];\n\t\t} else {\n\t\t\tprops = props.match( rnothtmlwhite );\n\t\t}\n\n\t\tvar prop,\n\t\t\tindex = 0,\n\t\t\tlength = props.length;\n\n\t\tfor ( ; index < length; index++ ) {\n\t\t\tprop = props[ index ];\n\t\t\tAnimation.tweeners[ prop ] = Animation.tweeners[ prop ] || [];\n\t\t\tAnimation.tweeners[ prop ].unshift( callback );\n\t\t}\n\t},\n\n\tprefilters: [ defaultPrefilter ],\n\n\tprefilter: function( callback, prepend ) {\n\t\tif ( prepend ) {\n\t\t\tAnimation.prefilters.unshift( callback );\n\t\t} else {\n\t\t\tAnimation.prefilters.push( callback );\n\t\t}\n\t}\n} );\n\njQuery.speed = function( speed, easing, fn ) {\n\tvar opt = speed && typeof speed === \"object\" ? jQuery.extend( {}, speed ) : {\n\t\tcomplete: fn || !fn && easing ||\n\t\t\tisFunction( speed ) && speed,\n\t\tduration: speed,\n\t\teasing: fn && easing || easing && !isFunction( easing ) && easing\n\t};\n\n\t// Go to the end state if fx are off\n\tif ( jQuery.fx.off ) {\n\t\topt.duration = 0;\n\n\t} else {\n\t\tif ( typeof opt.duration !== \"number\" ) {\n\t\t\tif ( opt.duration in jQuery.fx.speeds ) {\n\t\t\t\topt.duration = jQuery.fx.speeds[ opt.duration ];\n\n\t\t\t} else {\n\t\t\t\topt.duration = jQuery.fx.speeds._default;\n\t\t\t}\n\t\t}\n\t}\n\n\t// Normalize opt.queue - true/undefined/null -> \"fx\"\n\tif ( opt.queue == null || opt.queue === true ) {\n\t\topt.queue = \"fx\";\n\t}\n\n\t// Queueing\n\topt.old = opt.complete;\n\n\topt.complete = function() {\n\t\tif ( isFunction( opt.old ) ) {\n\t\t\topt.old.call( this );\n\t\t}\n\n\t\tif ( opt.queue ) {\n\t\t\tjQuery.dequeue( this, opt.queue );\n\t\t}\n\t};\n\n\treturn opt;\n};\n\njQuery.fn.extend( {\n\tfadeTo: function( speed, to, easing, callback ) {\n\n\t\t// Show any hidden elements after setting opacity to 0\n\t\treturn this.filter( isHiddenWithinTree ).css( \"opacity\", 0 ).show()\n\n\t\t\t// Animate to the value specified\n\t\t\t.end().animate( { opacity: to }, speed, easing, callback );\n\t},\n\tanimate: function( prop, speed, easing, callback ) {\n\t\tvar empty = jQuery.isEmptyObject( prop ),\n\t\t\toptall = jQuery.speed( speed, easing, callback ),\n\t\t\tdoAnimation = function() {\n\n\t\t\t\t// Operate on a copy of prop so per-property easing won't be lost\n\t\t\t\tvar anim = Animation( this, jQuery.extend( {}, prop ), optall );\n\n\t\t\t\t// Empty animations, or finishing resolves immediately\n\t\t\t\tif ( empty || dataPriv.get( this, \"finish\" ) ) {\n\t\t\t\t\tanim.stop( true );\n\t\t\t\t}\n\t\t\t};\n\t\t\tdoAnimation.finish = doAnimation;\n\n\t\treturn empty || optall.queue === false ?\n\t\t\tthis.each( doAnimation ) :\n\t\t\tthis.queue( optall.queue, doAnimation );\n\t},\n\tstop: function( type, clearQueue, gotoEnd ) {\n\t\tvar stopQueue = function( hooks ) {\n\t\t\tvar stop = hooks.stop;\n\t\t\tdelete hooks.stop;\n\t\t\tstop( gotoEnd );\n\t\t};\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tgotoEnd = clearQueue;\n\t\t\tclearQueue = type;\n\t\t\ttype = undefined;\n\t\t}\n\t\tif ( clearQueue && type !== false ) {\n\t\t\tthis.queue( type || \"fx\", [] );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar dequeue = true,\n\t\t\t\tindex = type != null && type + \"queueHooks\",\n\t\t\t\ttimers = jQuery.timers,\n\t\t\t\tdata = dataPriv.get( this );\n\n\t\t\tif ( index ) {\n\t\t\t\tif ( data[ index ] && data[ index ].stop ) {\n\t\t\t\t\tstopQueue( data[ index ] );\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tfor ( index in data ) {\n\t\t\t\t\tif ( data[ index ] && data[ index ].stop && rrun.test( index ) ) {\n\t\t\t\t\t\tstopQueue( data[ index ] );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tfor ( index = timers.length; index--; ) {\n\t\t\t\tif ( timers[ index ].elem === this &&\n\t\t\t\t\t( type == null || timers[ index ].queue === type ) ) {\n\n\t\t\t\t\ttimers[ index ].anim.stop( gotoEnd );\n\t\t\t\t\tdequeue = false;\n\t\t\t\t\ttimers.splice( index, 1 );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Start the next in the queue if the last step wasn't forced.\n\t\t\t// Timers currently will call their complete callbacks, which\n\t\t\t// will dequeue but only if they were gotoEnd.\n\t\t\tif ( dequeue || !gotoEnd ) {\n\t\t\t\tjQuery.dequeue( this, type );\n\t\t\t}\n\t\t} );\n\t},\n\tfinish: function( type ) {\n\t\tif ( type !== false ) {\n\t\t\ttype = type || \"fx\";\n\t\t}\n\t\treturn this.each( function() {\n\t\t\tvar index,\n\t\t\t\tdata = dataPriv.get( this ),\n\t\t\t\tqueue = data[ type + \"queue\" ],\n\t\t\t\thooks = data[ type + \"queueHooks\" ],\n\t\t\t\ttimers = jQuery.timers,\n\t\t\t\tlength = queue ? queue.length : 0;\n\n\t\t\t// Enable finishing flag on private data\n\t\t\tdata.finish = true;\n\n\t\t\t// Empty the queue first\n\t\t\tjQuery.queue( this, type, [] );\n\n\t\t\tif ( hooks && hooks.stop ) {\n\t\t\t\thooks.stop.call( this, true );\n\t\t\t}\n\n\t\t\t// Look for any active animations, and finish them\n\t\t\tfor ( index = timers.length; index--; ) {\n\t\t\t\tif ( timers[ index ].elem === this && timers[ index ].queue === type ) {\n\t\t\t\t\ttimers[ index ].anim.stop( true );\n\t\t\t\t\ttimers.splice( index, 1 );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Look for any animations in the old queue and finish them\n\t\t\tfor ( index = 0; index < length; index++ ) {\n\t\t\t\tif ( queue[ index ] && queue[ index ].finish ) {\n\t\t\t\t\tqueue[ index ].finish.call( this );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Turn off finishing flag\n\t\t\tdelete data.finish;\n\t\t} );\n\t}\n} );\n\njQuery.each( [ \"toggle\", \"show\", \"hide\" ], function( i, name ) {\n\tvar cssFn = jQuery.fn[ name ];\n\tjQuery.fn[ name ] = function( speed, easing, callback ) {\n\t\treturn speed == null || typeof speed === \"boolean\" ?\n\t\t\tcssFn.apply( this, arguments ) :\n\t\t\tthis.animate( genFx( name, true ), speed, easing, callback );\n\t};\n} );\n\n// Generate shortcuts for custom animations\njQuery.each( {\n\tslideDown: genFx( \"show\" ),\n\tslideUp: genFx( \"hide\" ),\n\tslideToggle: genFx( \"toggle\" ),\n\tfadeIn: { opacity: \"show\" },\n\tfadeOut: { opacity: \"hide\" },\n\tfadeToggle: { opacity: \"toggle\" }\n}, function( name, props ) {\n\tjQuery.fn[ name ] = function( speed, easing, callback ) {\n\t\treturn this.animate( props, speed, easing, callback );\n\t};\n} );\n\njQuery.timers = [];\njQuery.fx.tick = function() {\n\tvar timer,\n\t\ti = 0,\n\t\ttimers = jQuery.timers;\n\n\tfxNow = Date.now();\n\n\tfor ( ; i < timers.length; i++ ) {\n\t\ttimer = timers[ i ];\n\n\t\t// Run the timer and safely remove it when done (allowing for external removal)\n\t\tif ( !timer() && timers[ i ] === timer ) {\n\t\t\ttimers.splice( i--, 1 );\n\t\t}\n\t}\n\n\tif ( !timers.length ) {\n\t\tjQuery.fx.stop();\n\t}\n\tfxNow = undefined;\n};\n\njQuery.fx.timer = function( timer ) {\n\tjQuery.timers.push( timer );\n\tjQuery.fx.start();\n};\n\njQuery.fx.interval = 13;\njQuery.fx.start = function() {\n\tif ( inProgress ) {\n\t\treturn;\n\t}\n\n\tinProgress = true;\n\tschedule();\n};\n\njQuery.fx.stop = function() {\n\tinProgress = null;\n};\n\njQuery.fx.speeds = {\n\tslow: 600,\n\tfast: 200,\n\n\t// Default speed\n\t_default: 400\n};\n\n\n// Based off of the plugin by Clint Helfers, with permission.\n// https://web.archive.org/web/20100324014747/http://blindsignals.com/index.php/2009/07/jquery-delay/\njQuery.fn.delay = function( time, type ) {\n\ttime = jQuery.fx ? jQuery.fx.speeds[ time ] || time : time;\n\ttype = type || \"fx\";\n\n\treturn this.queue( type, function( next, hooks ) {\n\t\tvar timeout = window.setTimeout( next, time );\n\t\thooks.stop = function() {\n\t\t\twindow.clearTimeout( timeout );\n\t\t};\n\t} );\n};\n\n\n( function() {\n\tvar input = document.createElement( \"input\" ),\n\t\tselect = document.createElement( \"select\" ),\n\t\topt = select.appendChild( document.createElement( \"option\" ) );\n\n\tinput.type = \"checkbox\";\n\n\t// Support: Android <=4.3 only\n\t// Default value for a checkbox should be \"on\"\n\tsupport.checkOn = input.value !== \"\";\n\n\t// Support: IE <=11 only\n\t// Must access selectedIndex to make default options select\n\tsupport.optSelected = opt.selected;\n\n\t// Support: IE <=11 only\n\t// An input loses its value after becoming a radio\n\tinput = document.createElement( \"input\" );\n\tinput.value = \"t\";\n\tinput.type = \"radio\";\n\tsupport.radioValue = input.value === \"t\";\n} )();\n\n\nvar boolHook,\n\tattrHandle = jQuery.expr.attrHandle;\n\njQuery.fn.extend( {\n\tattr: function( name, value ) {\n\t\treturn access( this, jQuery.attr, name, value, arguments.length > 1 );\n\t},\n\n\tremoveAttr: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.removeAttr( this, name );\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tattr: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set attributes on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Fallback to prop when attributes are not supported\n\t\tif ( typeof elem.getAttribute === \"undefined\" ) {\n\t\t\treturn jQuery.prop( elem, name, value );\n\t\t}\n\n\t\t// Attribute hooks are determined by the lowercase version\n\t\t// Grab necessary hook if one is defined\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\t\t\thooks = jQuery.attrHooks[ name.toLowerCase() ] ||\n\t\t\t\t( jQuery.expr.match.bool.test( name ) ? boolHook : undefined );\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( value === null ) {\n\t\t\t\tjQuery.removeAttr( elem, name );\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\telem.setAttribute( name, value + \"\" );\n\t\t\treturn value;\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\tret = jQuery.find.attr( elem, name );\n\n\t\t// Non-existent attributes return null, we normalize to undefined\n\t\treturn ret == null ? undefined : ret;\n\t},\n\n\tattrHooks: {\n\t\ttype: {\n\t\t\tset: function( elem, value ) {\n\t\t\t\tif ( !support.radioValue && value === \"radio\" &&\n\t\t\t\t\tnodeName( elem, \"input\" ) ) {\n\t\t\t\t\tvar val = elem.value;\n\t\t\t\t\telem.setAttribute( \"type\", value );\n\t\t\t\t\tif ( val ) {\n\t\t\t\t\t\telem.value = val;\n\t\t\t\t\t}\n\t\t\t\t\treturn value;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\tremoveAttr: function( elem, value ) {\n\t\tvar name,\n\t\t\ti = 0,\n\n\t\t\t// Attribute names can contain non-HTML whitespace characters\n\t\t\t// https://html.spec.whatwg.org/multipage/syntax.html#attributes-2\n\t\t\tattrNames = value && value.match( rnothtmlwhite );\n\n\t\tif ( attrNames && elem.nodeType === 1 ) {\n\t\t\twhile ( ( name = attrNames[ i++ ] ) ) {\n\t\t\t\telem.removeAttribute( name );\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Hooks for boolean attributes\nboolHook = {\n\tset: function( elem, value, name ) {\n\t\tif ( value === false ) {\n\n\t\t\t// Remove boolean attributes when set to false\n\t\t\tjQuery.removeAttr( elem, name );\n\t\t} else {\n\t\t\telem.setAttribute( name, name );\n\t\t}\n\t\treturn name;\n\t}\n};\n\njQuery.each( jQuery.expr.match.bool.source.match( /\\w+/g ), function( i, name ) {\n\tvar getter = attrHandle[ name ] || jQuery.find.attr;\n\n\tattrHandle[ name ] = function( elem, name, isXML ) {\n\t\tvar ret, handle,\n\t\t\tlowercaseName = name.toLowerCase();\n\n\t\tif ( !isXML ) {\n\n\t\t\t// Avoid an infinite loop by temporarily removing this function from the getter\n\t\t\thandle = attrHandle[ lowercaseName ];\n\t\t\tattrHandle[ lowercaseName ] = ret;\n\t\t\tret = getter( elem, name, isXML ) != null ?\n\t\t\t\tlowercaseName :\n\t\t\t\tnull;\n\t\t\tattrHandle[ lowercaseName ] = handle;\n\t\t}\n\t\treturn ret;\n\t};\n} );\n\n\n\n\nvar rfocusable = /^(?:input|select|textarea|button)$/i,\n\trclickable = /^(?:a|area)$/i;\n\njQuery.fn.extend( {\n\tprop: function( name, value ) {\n\t\treturn access( this, jQuery.prop, name, value, arguments.length > 1 );\n\t},\n\n\tremoveProp: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tdelete this[ jQuery.propFix[ name ] || name ];\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tprop: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set properties on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// Fix name and attach hooks\n\t\t\tname = jQuery.propFix[ name ] || name;\n\t\t\thooks = jQuery.propHooks[ name ];\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\treturn ( elem[ name ] = value );\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\treturn elem[ name ];\n\t},\n\n\tpropHooks: {\n\t\ttabIndex: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\t// Support: IE <=9 - 11 only\n\t\t\t\t// elem.tabIndex doesn't always return the\n\t\t\t\t// correct value when it hasn't been explicitly set\n\t\t\t\t// https://web.archive.org/web/20141116233347/http://fluidproject.org/blog/2008/01/09/getting-setting-and-removing-tabindex-values-with-javascript/\n\t\t\t\t// Use proper attribute retrieval(#12072)\n\t\t\t\tvar tabindex = jQuery.find.attr( elem, \"tabindex\" );\n\n\t\t\t\tif ( tabindex ) {\n\t\t\t\t\treturn parseInt( tabindex, 10 );\n\t\t\t\t}\n\n\t\t\t\tif (\n\t\t\t\t\trfocusable.test( elem.nodeName ) ||\n\t\t\t\t\trclickable.test( elem.nodeName ) &&\n\t\t\t\t\telem.href\n\t\t\t\t) {\n\t\t\t\t\treturn 0;\n\t\t\t\t}\n\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t},\n\n\tpropFix: {\n\t\t\"for\": \"htmlFor\",\n\t\t\"class\": \"className\"\n\t}\n} );\n\n// Support: IE <=11 only\n// Accessing the selectedIndex property\n// forces the browser to respect setting selected\n// on the option\n// The getter ensures a default option is selected\n// when in an optgroup\n// eslint rule \"no-unused-expressions\" is disabled for this code\n// since it considers such accessions noop\nif ( !support.optSelected ) {\n\tjQuery.propHooks.selected = {\n\t\tget: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent && parent.parentNode ) {\n\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t}\n\t\t\treturn null;\n\t\t},\n\t\tset: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent ) {\n\t\t\t\tparent.selectedIndex;\n\n\t\t\t\tif ( parent.parentNode ) {\n\t\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t};\n}\n\njQuery.each( [\n\t\"tabIndex\",\n\t\"readOnly\",\n\t\"maxLength\",\n\t\"cellSpacing\",\n\t\"cellPadding\",\n\t\"rowSpan\",\n\t\"colSpan\",\n\t\"useMap\",\n\t\"frameBorder\",\n\t\"contentEditable\"\n], function() {\n\tjQuery.propFix[ this.toLowerCase() ] = this;\n} );\n\n\n\n\n\t// Strip and collapse whitespace according to HTML spec\n\t// https://infra.spec.whatwg.org/#strip-and-collapse-ascii-whitespace\n\tfunction stripAndCollapse( value ) {\n\t\tvar tokens = value.match( rnothtmlwhite ) || [];\n\t\treturn tokens.join( \" \" );\n\t}\n\n\nfunction getClass( elem ) {\n\treturn elem.getAttribute && elem.getAttribute( \"class\" ) || \"\";\n}\n\nfunction classesToArray( value ) {\n\tif ( Array.isArray( value ) ) {\n\t\treturn value;\n\t}\n\tif ( typeof value === \"string\" ) {\n\t\treturn value.match( rnothtmlwhite ) || [];\n\t}\n\treturn [];\n}\n\njQuery.fn.extend( {\n\taddClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).addClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\t\t\t\t\t\tif ( cur.indexOf( \" \" + clazz + \" \" ) < 0 ) {\n\t\t\t\t\t\t\tcur += clazz + \" \";\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tremoveClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).removeClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tif ( !arguments.length ) {\n\t\t\treturn this.attr( \"class\", \"\" );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\n\t\t\t\t// This expression is here for better compressibility (see addClass)\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\n\t\t\t\t\t\t// Remove *all* instances\n\t\t\t\t\t\twhile ( cur.indexOf( \" \" + clazz + \" \" ) > -1 ) {\n\t\t\t\t\t\t\tcur = cur.replace( \" \" + clazz + \" \", \" \" );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\ttoggleClass: function( value, stateVal ) {\n\t\tvar type = typeof value,\n\t\t\tisValidValue = type === \"string\" || Array.isArray( value );\n\n\t\tif ( typeof stateVal === \"boolean\" && isValidValue ) {\n\t\t\treturn stateVal ? this.addClass( value ) : this.removeClass( value );\n\t\t}\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).toggleClass(\n\t\t\t\t\tvalue.call( this, i, getClass( this ), stateVal ),\n\t\t\t\t\tstateVal\n\t\t\t\t);\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar className, i, self, classNames;\n\n\t\t\tif ( isValidValue ) {\n\n\t\t\t\t// Toggle individual class names\n\t\t\t\ti = 0;\n\t\t\t\tself = jQuery( this );\n\t\t\t\tclassNames = classesToArray( value );\n\n\t\t\t\twhile ( ( className = classNames[ i++ ] ) ) {\n\n\t\t\t\t\t// Check each className given, space separated list\n\t\t\t\t\tif ( self.hasClass( className ) ) {\n\t\t\t\t\t\tself.removeClass( className );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tself.addClass( className );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t// Toggle whole class name\n\t\t\t} else if ( value === undefined || type === \"boolean\" ) {\n\t\t\t\tclassName = getClass( this );\n\t\t\t\tif ( className ) {\n\n\t\t\t\t\t// Store className if set\n\t\t\t\t\tdataPriv.set( this, \"__className__\", className );\n\t\t\t\t}\n\n\t\t\t\t// If the element has a class name or if we're passed `false`,\n\t\t\t\t// then remove the whole classname (if there was one, the above saved it).\n\t\t\t\t// Otherwise bring back whatever was previously saved (if anything),\n\t\t\t\t// falling back to the empty string if nothing was stored.\n\t\t\t\tif ( this.setAttribute ) {\n\t\t\t\t\tthis.setAttribute( \"class\",\n\t\t\t\t\t\tclassName || value === false ?\n\t\t\t\t\t\t\"\" :\n\t\t\t\t\t\tdataPriv.get( this, \"__className__\" ) || \"\"\n\t\t\t\t\t);\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\thasClass: function( selector ) {\n\t\tvar className, elem,\n\t\t\ti = 0;\n\n\t\tclassName = \" \" + selector + \" \";\n\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\tif ( elem.nodeType === 1 &&\n\t\t\t\t( \" \" + stripAndCollapse( getClass( elem ) ) + \" \" ).indexOf( className ) > -1 ) {\n\t\t\t\t\treturn true;\n\t\t\t}\n\t\t}\n\n\t\treturn false;\n\t}\n} );\n\n\n\n\nvar rreturn = /\\r/g;\n\njQuery.fn.extend( {\n\tval: function( value ) {\n\t\tvar hooks, ret, valueIsFunction,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !arguments.length ) {\n\t\t\tif ( elem ) {\n\t\t\t\thooks = jQuery.valHooks[ elem.type ] ||\n\t\t\t\t\tjQuery.valHooks[ elem.nodeName.toLowerCase() ];\n\n\t\t\t\tif ( hooks &&\n\t\t\t\t\t\"get\" in hooks &&\n\t\t\t\t\t( ret = hooks.get( elem, \"value\" ) ) !== undefined\n\t\t\t\t) {\n\t\t\t\t\treturn ret;\n\t\t\t\t}\n\n\t\t\t\tret = elem.value;\n\n\t\t\t\t// Handle most common string cases\n\t\t\t\tif ( typeof ret === \"string\" ) {\n\t\t\t\t\treturn ret.replace( rreturn, \"\" );\n\t\t\t\t}\n\n\t\t\t\t// Handle cases where value is null/undef or number\n\t\t\t\treturn ret == null ? \"\" : ret;\n\t\t\t}\n\n\t\t\treturn;\n\t\t}\n\n\t\tvalueIsFunction = isFunction( value );\n\n\t\treturn this.each( function( i ) {\n\t\t\tvar val;\n\n\t\t\tif ( this.nodeType !== 1 ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\tval = value.call( this, i, jQuery( this ).val() );\n\t\t\t} else {\n\t\t\t\tval = value;\n\t\t\t}\n\n\t\t\t// Treat null/undefined as \"\"; convert numbers to string\n\t\t\tif ( val == null ) {\n\t\t\t\tval = \"\";\n\n\t\t\t} else if ( typeof val === \"number\" ) {\n\t\t\t\tval += \"\";\n\n\t\t\t} else if ( Array.isArray( val ) ) {\n\t\t\t\tval = jQuery.map( val, function( value ) {\n\t\t\t\t\treturn value == null ? \"\" : value + \"\";\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\thooks = jQuery.valHooks[ this.type ] || jQuery.valHooks[ this.nodeName.toLowerCase() ];\n\n\t\t\t// If set returns undefined, fall back to normal setting\n\t\t\tif ( !hooks || !( \"set\" in hooks ) || hooks.set( this, val, \"value\" ) === undefined ) {\n\t\t\t\tthis.value = val;\n\t\t\t}\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tvalHooks: {\n\t\toption: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\tvar val = jQuery.find.attr( elem, \"value\" );\n\t\t\t\treturn val != null ?\n\t\t\t\t\tval :\n\n\t\t\t\t\t// Support: IE <=10 - 11 only\n\t\t\t\t\t// option.text throws exceptions (#14686, #14858)\n\t\t\t\t\t// Strip and collapse whitespace\n\t\t\t\t\t// https://html.spec.whatwg.org/#strip-and-collapse-whitespace\n\t\t\t\t\tstripAndCollapse( jQuery.text( elem ) );\n\t\t\t}\n\t\t},\n\t\tselect: {\n\t\t\tget: function( elem ) {\n\t\t\t\tvar value, option, i,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tindex = elem.selectedIndex,\n\t\t\t\t\tone = elem.type === \"select-one\",\n\t\t\t\t\tvalues = one ? null : [],\n\t\t\t\t\tmax = one ? index + 1 : options.length;\n\n\t\t\t\tif ( index < 0 ) {\n\t\t\t\t\ti = max;\n\n\t\t\t\t} else {\n\t\t\t\t\ti = one ? index : 0;\n\t\t\t\t}\n\n\t\t\t\t// Loop through all the selected options\n\t\t\t\tfor ( ; i < max; i++ ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t// IE8-9 doesn't update selected after form reset (#2551)\n\t\t\t\t\tif ( ( option.selected || i === index ) &&\n\n\t\t\t\t\t\t\t// Don't return options that are disabled or in a disabled optgroup\n\t\t\t\t\t\t\t!option.disabled &&\n\t\t\t\t\t\t\t( !option.parentNode.disabled ||\n\t\t\t\t\t\t\t\t!nodeName( option.parentNode, \"optgroup\" ) ) ) {\n\n\t\t\t\t\t\t// Get the specific value for the option\n\t\t\t\t\t\tvalue = jQuery( option ).val();\n\n\t\t\t\t\t\t// We don't need an array for one selects\n\t\t\t\t\t\tif ( one ) {\n\t\t\t\t\t\t\treturn value;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Multi-Selects return an array\n\t\t\t\t\t\tvalues.push( value );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn values;\n\t\t\t},\n\n\t\t\tset: function( elem, value ) {\n\t\t\t\tvar optionSet, option,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tvalues = jQuery.makeArray( value ),\n\t\t\t\t\ti = options.length;\n\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t/* eslint-disable no-cond-assign */\n\n\t\t\t\t\tif ( option.selected =\n\t\t\t\t\t\tjQuery.inArray( jQuery.valHooks.option.get( option ), values ) > -1\n\t\t\t\t\t) {\n\t\t\t\t\t\toptionSet = true;\n\t\t\t\t\t}\n\n\t\t\t\t\t/* eslint-enable no-cond-assign */\n\t\t\t\t}\n\n\t\t\t\t// Force browsers to behave consistently when non-matching value is set\n\t\t\t\tif ( !optionSet ) {\n\t\t\t\t\telem.selectedIndex = -1;\n\t\t\t\t}\n\t\t\t\treturn values;\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Radios and checkboxes getter/setter\njQuery.each( [ \"radio\", \"checkbox\" ], function() {\n\tjQuery.valHooks[ this ] = {\n\t\tset: function( elem, value ) {\n\t\t\tif ( Array.isArray( value ) ) {\n\t\t\t\treturn ( elem.checked = jQuery.inArray( jQuery( elem ).val(), value ) > -1 );\n\t\t\t}\n\t\t}\n\t};\n\tif ( !support.checkOn ) {\n\t\tjQuery.valHooks[ this ].get = function( elem ) {\n\t\t\treturn elem.getAttribute( \"value\" ) === null ? \"on\" : elem.value;\n\t\t};\n\t}\n} );\n\n\n\n\n// Return jQuery for attributes-only inclusion\n\n\nsupport.focusin = \"onfocusin\" in window;\n\n\nvar rfocusMorph = /^(?:focusinfocus|focusoutblur)$/,\n\tstopPropagationCallback = function( e ) {\n\t\te.stopPropagation();\n\t};\n\njQuery.extend( jQuery.event, {\n\n\ttrigger: function( event, data, elem, onlyHandlers ) {\n\n\t\tvar i, cur, tmp, bubbleType, ontype, handle, special, lastElement,\n\t\t\teventPath = [ elem || document ],\n\t\t\ttype = hasOwn.call( event, \"type\" ) ? event.type : event,\n\t\t\tnamespaces = hasOwn.call( event, \"namespace\" ) ? event.namespace.split( \".\" ) : [];\n\n\t\tcur = lastElement = tmp = elem = elem || document;\n\n\t\t// Don't do events on text and comment nodes\n\t\tif ( elem.nodeType === 3 || elem.nodeType === 8 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// focus/blur morphs to focusin/out; ensure we're not firing them right now\n\t\tif ( rfocusMorph.test( type + jQuery.event.triggered ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( type.indexOf( \".\" ) > -1 ) {\n\n\t\t\t// Namespaced trigger; create a regexp to match event type in handle()\n\t\t\tnamespaces = type.split( \".\" );\n\t\t\ttype = namespaces.shift();\n\t\t\tnamespaces.sort();\n\t\t}\n\t\tontype = type.indexOf( \":\" ) < 0 && \"on\" + type;\n\n\t\t// Caller can pass in a jQuery.Event object, Object, or just an event type string\n\t\tevent = event[ jQuery.expando ] ?\n\t\t\tevent :\n\t\t\tnew jQuery.Event( type, typeof event === \"object\" && event );\n\n\t\t// Trigger bitmask: & 1 for native handlers; & 2 for jQuery (always true)\n\t\tevent.isTrigger = onlyHandlers ? 2 : 3;\n\t\tevent.namespace = namespaces.join( \".\" );\n\t\tevent.rnamespace = event.namespace ?\n\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" ) :\n\t\t\tnull;\n\n\t\t// Clean up the event in case it is being reused\n\t\tevent.result = undefined;\n\t\tif ( !event.target ) {\n\t\t\tevent.target = elem;\n\t\t}\n\n\t\t// Clone any incoming data and prepend the event, creating the handler arg list\n\t\tdata = data == null ?\n\t\t\t[ event ] :\n\t\t\tjQuery.makeArray( data, [ event ] );\n\n\t\t// Allow special events to draw outside the lines\n\t\tspecial = jQuery.event.special[ type ] || {};\n\t\tif ( !onlyHandlers && special.trigger && special.trigger.apply( elem, data ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine event propagation path in advance, per W3C events spec (#9951)\n\t\t// Bubble up to document, then to window; watch for a global ownerDocument var (#9724)\n\t\tif ( !onlyHandlers && !special.noBubble && !isWindow( elem ) ) {\n\n\t\t\tbubbleType = special.delegateType || type;\n\t\t\tif ( !rfocusMorph.test( bubbleType + type ) ) {\n\t\t\t\tcur = cur.parentNode;\n\t\t\t}\n\t\t\tfor ( ; cur; cur = cur.parentNode ) {\n\t\t\t\teventPath.push( cur );\n\t\t\t\ttmp = cur;\n\t\t\t}\n\n\t\t\t// Only add window if we got to document (e.g., not plain obj or detached DOM)\n\t\t\tif ( tmp === ( elem.ownerDocument || document ) ) {\n\t\t\t\teventPath.push( tmp.defaultView || tmp.parentWindow || window );\n\t\t\t}\n\t\t}\n\n\t\t// Fire handlers on the event path\n\t\ti = 0;\n\t\twhile ( ( cur = eventPath[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tlastElement = cur;\n\t\t\tevent.type = i > 1 ?\n\t\t\t\tbubbleType :\n\t\t\t\tspecial.bindType || type;\n\n\t\t\t// jQuery handler\n\t\t\thandle = ( dataPriv.get( cur, \"events\" ) || {} )[ event.type ] &&\n\t\t\t\tdataPriv.get( cur, \"handle\" );\n\t\t\tif ( handle ) {\n\t\t\t\thandle.apply( cur, data );\n\t\t\t}\n\n\t\t\t// Native handler\n\t\t\thandle = ontype && cur[ ontype ];\n\t\t\tif ( handle && handle.apply && acceptData( cur ) ) {\n\t\t\t\tevent.result = handle.apply( cur, data );\n\t\t\t\tif ( event.result === false ) {\n\t\t\t\t\tevent.preventDefault();\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tevent.type = type;\n\n\t\t// If nobody prevented the default action, do it now\n\t\tif ( !onlyHandlers && !event.isDefaultPrevented() ) {\n\n\t\t\tif ( ( !special._default ||\n\t\t\t\tspecial._default.apply( eventPath.pop(), data ) === false ) &&\n\t\t\t\tacceptData( elem ) ) {\n\n\t\t\t\t// Call a native DOM method on the target with the same name as the event.\n\t\t\t\t// Don't do default actions on window, that's where global variables be (#6170)\n\t\t\t\tif ( ontype && isFunction( elem[ type ] ) && !isWindow( elem ) ) {\n\n\t\t\t\t\t// Don't re-trigger an onFOO event when we call its FOO() method\n\t\t\t\t\ttmp = elem[ ontype ];\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = null;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prevent re-triggering of the same event, since we already bubbled it above\n\t\t\t\t\tjQuery.event.triggered = type;\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.addEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\telem[ type ]();\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.removeEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\tjQuery.event.triggered = undefined;\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = tmp;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\t// Piggyback on a donor event to simulate a different one\n\t// Used only for `focus(in | out)` events\n\tsimulate: function( type, elem, event ) {\n\t\tvar e = jQuery.extend(\n\t\t\tnew jQuery.Event(),\n\t\t\tevent,\n\t\t\t{\n\t\t\t\ttype: type,\n\t\t\t\tisSimulated: true\n\t\t\t}\n\t\t);\n\n\t\tjQuery.event.trigger( e, null, elem );\n\t}\n\n} );\n\njQuery.fn.extend( {\n\n\ttrigger: function( type, data ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.trigger( type, data, this );\n\t\t} );\n\t},\n\ttriggerHandler: function( type, data ) {\n\t\tvar elem = this[ 0 ];\n\t\tif ( elem ) {\n\t\t\treturn jQuery.event.trigger( type, data, elem, true );\n\t\t}\n\t}\n} );\n\n\n// Support: Firefox <=44\n// Firefox doesn't have focus(in | out) events\n// Related ticket - https://bugzilla.mozilla.org/show_bug.cgi?id=687787\n//\n// Support: Chrome <=48 - 49, Safari <=9.0 - 9.1\n// focus(in | out) events fire after focus & blur events,\n// which is spec violation - http://www.w3.org/TR/DOM-Level-3-Events/#events-focusevent-event-order\n// Related ticket - https://bugs.chromium.org/p/chromium/issues/detail?id=449857\nif ( !support.focusin ) {\n\tjQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( orig, fix ) {\n\n\t\t// Attach a single capturing handler on the document while someone wants focusin/focusout\n\t\tvar handler = function( event ) {\n\t\t\tjQuery.event.simulate( fix, event.target, jQuery.event.fix( event ) );\n\t\t};\n\n\t\tjQuery.event.special[ fix ] = {\n\t\t\tsetup: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix );\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.addEventListener( orig, handler, true );\n\t\t\t\t}\n\t\t\t\tdataPriv.access( doc, fix, ( attaches || 0 ) + 1 );\n\t\t\t},\n\t\t\tteardown: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix ) - 1;\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.removeEventListener( orig, handler, true );\n\t\t\t\t\tdataPriv.remove( doc, fix );\n\n\t\t\t\t} else {\n\t\t\t\t\tdataPriv.access( doc, fix, attaches );\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t} );\n}\nvar location = window.location;\n\nvar nonce = Date.now();\n\nvar rquery = ( /\\?/ );\n\n\n\n// Cross-browser xml parsing\njQuery.parseXML = function( data ) {\n\tvar xml;\n\tif ( !data || typeof data !== \"string\" ) {\n\t\treturn null;\n\t}\n\n\t// Support: IE 9 - 11 only\n\t// IE throws on parseFromString with invalid input.\n\ttry {\n\t\txml = ( new window.DOMParser() ).parseFromString( data, \"text/xml\" );\n\t} catch ( e ) {\n\t\txml = undefined;\n\t}\n\n\tif ( !xml || xml.getElementsByTagName( \"parsererror\" ).length ) {\n\t\tjQuery.error( \"Invalid XML: \" + data );\n\t}\n\treturn xml;\n};\n\n\nvar\n\trbracket = /\\[\\]$/,\n\trCRLF = /\\r?\\n/g,\n\trsubmitterTypes = /^(?:submit|button|image|reset|file)$/i,\n\trsubmittable = /^(?:input|select|textarea|keygen)/i;\n\nfunction buildParams( prefix, obj, traditional, add ) {\n\tvar name;\n\n\tif ( Array.isArray( obj ) ) {\n\n\t\t// Serialize array item.\n\t\tjQuery.each( obj, function( i, v ) {\n\t\t\tif ( traditional || rbracket.test( prefix ) ) {\n\n\t\t\t\t// Treat each array item as a scalar.\n\t\t\t\tadd( prefix, v );\n\n\t\t\t} else {\n\n\t\t\t\t// Item is non-scalar (array or object), encode its numeric index.\n\t\t\t\tbuildParams(\n\t\t\t\t\tprefix + \"[\" + ( typeof v === \"object\" && v != null ? i : \"\" ) + \"]\",\n\t\t\t\t\tv,\n\t\t\t\t\ttraditional,\n\t\t\t\t\tadd\n\t\t\t\t);\n\t\t\t}\n\t\t} );\n\n\t} else if ( !traditional && toType( obj ) === \"object\" ) {\n\n\t\t// Serialize object item.\n\t\tfor ( name in obj ) {\n\t\t\tbuildParams( prefix + \"[\" + name + \"]\", obj[ name ], traditional, add );\n\t\t}\n\n\t} else {\n\n\t\t// Serialize scalar item.\n\t\tadd( prefix, obj );\n\t}\n}\n\n// Serialize an array of form elements or a set of\n// key/values into a query string\njQuery.param = function( a, traditional ) {\n\tvar prefix,\n\t\ts = [],\n\t\tadd = function( key, valueOrFunction ) {\n\n\t\t\t// If value is a function, invoke it and use its return value\n\t\t\tvar value = isFunction( valueOrFunction ) ?\n\t\t\t\tvalueOrFunction() :\n\t\t\t\tvalueOrFunction;\n\n\t\t\ts[ s.length ] = encodeURIComponent( key ) + \"=\" +\n\t\t\t\tencodeURIComponent( value == null ? \"\" : value );\n\t\t};\n\n\tif ( a == null ) {\n\t\treturn \"\";\n\t}\n\n\t// If an array was passed in, assume that it is an array of form elements.\n\tif ( Array.isArray( a ) || ( a.jquery && !jQuery.isPlainObject( a ) ) ) {\n\n\t\t// Serialize the form elements\n\t\tjQuery.each( a, function() {\n\t\t\tadd( this.name, this.value );\n\t\t} );\n\n\t} else {\n\n\t\t// If traditional, encode the \"old\" way (the way 1.3.2 or older\n\t\t// did it), otherwise encode params recursively.\n\t\tfor ( prefix in a ) {\n\t\t\tbuildParams( prefix, a[ prefix ], traditional, add );\n\t\t}\n\t}\n\n\t// Return the resulting serialization\n\treturn s.join( \"&\" );\n};\n\njQuery.fn.extend( {\n\tserialize: function() {\n\t\treturn jQuery.param( this.serializeArray() );\n\t},\n\tserializeArray: function() {\n\t\treturn this.map( function() {\n\n\t\t\t// Can add propHook for \"elements\" to filter or add form elements\n\t\t\tvar elements = jQuery.prop( this, \"elements\" );\n\t\t\treturn elements ? jQuery.makeArray( elements ) : this;\n\t\t} )\n\t\t.filter( function() {\n\t\t\tvar type = this.type;\n\n\t\t\t// Use .is( \":disabled\" ) so that fieldset[disabled] works\n\t\t\treturn this.name && !jQuery( this ).is( \":disabled\" ) &&\n\t\t\t\trsubmittable.test( this.nodeName ) && !rsubmitterTypes.test( type ) &&\n\t\t\t\t( this.checked || !rcheckableType.test( type ) );\n\t\t} )\n\t\t.map( function( i, elem ) {\n\t\t\tvar val = jQuery( this ).val();\n\n\t\t\tif ( val == null ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\tif ( Array.isArray( val ) ) {\n\t\t\t\treturn jQuery.map( val, function( val ) {\n\t\t\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t} ).get();\n\t}\n} );\n\n\nvar\n\tr20 = /%20/g,\n\trhash = /#.*$/,\n\trantiCache = /([?&])_=[^&]*/,\n\trheaders = /^(.*?):[ \\t]*([^\\r\\n]*)$/mg,\n\n\t// #7653, #8125, #8152: local protocol detection\n\trlocalProtocol = /^(?:about|app|app-storage|.+-extension|file|res|widget):$/,\n\trnoContent = /^(?:GET|HEAD)$/,\n\trprotocol = /^\\/\\//,\n\n\t/* Prefilters\n\t * 1) They are useful to introduce custom dataTypes (see ajax/jsonp.js for an example)\n\t * 2) These are called:\n\t *    - BEFORE asking for a transport\n\t *    - AFTER param serialization (s.data is a string if s.processData is true)\n\t * 3) key is the dataType\n\t * 4) the catchall symbol \"*\" can be used\n\t * 5) execution will start with transport dataType and THEN continue down to \"*\" if needed\n\t */\n\tprefilters = {},\n\n\t/* Transports bindings\n\t * 1) key is the dataType\n\t * 2) the catchall symbol \"*\" can be used\n\t * 3) selection will start with transport dataType and THEN go to \"*\" if needed\n\t */\n\ttransports = {},\n\n\t// Avoid comment-prolog char sequence (#10098); must appease lint and evade compression\n\tallTypes = \"*/\".concat( \"*\" ),\n\n\t// Anchor tag for parsing the document origin\n\toriginAnchor = document.createElement( \"a\" );\n\toriginAnchor.href = location.href;\n\n// Base \"constructor\" for jQuery.ajaxPrefilter and jQuery.ajaxTransport\nfunction addToPrefiltersOrTransports( structure ) {\n\n\t// dataTypeExpression is optional and defaults to \"*\"\n\treturn function( dataTypeExpression, func ) {\n\n\t\tif ( typeof dataTypeExpression !== \"string\" ) {\n\t\t\tfunc = dataTypeExpression;\n\t\t\tdataTypeExpression = \"*\";\n\t\t}\n\n\t\tvar dataType,\n\t\t\ti = 0,\n\t\t\tdataTypes = dataTypeExpression.toLowerCase().match( rnothtmlwhite ) || [];\n\n\t\tif ( isFunction( func ) ) {\n\n\t\t\t// For each dataType in the dataTypeExpression\n\t\t\twhile ( ( dataType = dataTypes[ i++ ] ) ) {\n\n\t\t\t\t// Prepend if requested\n\t\t\t\tif ( dataType[ 0 ] === \"+\" ) {\n\t\t\t\t\tdataType = dataType.slice( 1 ) || \"*\";\n\t\t\t\t\t( structure[ dataType ] = structure[ dataType ] || [] ).unshift( func );\n\n\t\t\t\t// Otherwise append\n\t\t\t\t} else {\n\t\t\t\t\t( structure[ dataType ] = structure[ dataType ] || [] ).push( func );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t};\n}\n\n// Base inspection function for prefilters and transports\nfunction inspectPrefiltersOrTransports( structure, options, originalOptions, jqXHR ) {\n\n\tvar inspected = {},\n\t\tseekingTransport = ( structure === transports );\n\n\tfunction inspect( dataType ) {\n\t\tvar selected;\n\t\tinspected[ dataType ] = true;\n\t\tjQuery.each( structure[ dataType ] || [], function( _, prefilterOrFactory ) {\n\t\t\tvar dataTypeOrTransport = prefilterOrFactory( options, originalOptions, jqXHR );\n\t\t\tif ( typeof dataTypeOrTransport === \"string\" &&\n\t\t\t\t!seekingTransport && !inspected[ dataTypeOrTransport ] ) {\n\n\t\t\t\toptions.dataTypes.unshift( dataTypeOrTransport );\n\t\t\t\tinspect( dataTypeOrTransport );\n\t\t\t\treturn false;\n\t\t\t} else if ( seekingTransport ) {\n\t\t\t\treturn !( selected = dataTypeOrTransport );\n\t\t\t}\n\t\t} );\n\t\treturn selected;\n\t}\n\n\treturn inspect( options.dataTypes[ 0 ] ) || !inspected[ \"*\" ] && inspect( \"*\" );\n}\n\n// A special extend for ajax options\n// that takes \"flat\" options (not to be deep extended)\n// Fixes #9887\nfunction ajaxExtend( target, src ) {\n\tvar key, deep,\n\t\tflatOptions = jQuery.ajaxSettings.flatOptions || {};\n\n\tfor ( key in src ) {\n\t\tif ( src[ key ] !== undefined ) {\n\t\t\t( flatOptions[ key ] ? target : ( deep || ( deep = {} ) ) )[ key ] = src[ key ];\n\t\t}\n\t}\n\tif ( deep ) {\n\t\tjQuery.extend( true, target, deep );\n\t}\n\n\treturn target;\n}\n\n/* Handles responses to an ajax request:\n * - finds the right dataType (mediates between content-type and expected dataType)\n * - returns the corresponding response\n */\nfunction ajaxHandleResponses( s, jqXHR, responses ) {\n\n\tvar ct, type, finalDataType, firstDataType,\n\t\tcontents = s.contents,\n\t\tdataTypes = s.dataTypes;\n\n\t// Remove auto dataType and get content-type in the process\n\twhile ( dataTypes[ 0 ] === \"*\" ) {\n\t\tdataTypes.shift();\n\t\tif ( ct === undefined ) {\n\t\t\tct = s.mimeType || jqXHR.getResponseHeader( \"Content-Type\" );\n\t\t}\n\t}\n\n\t// Check if we're dealing with a known content-type\n\tif ( ct ) {\n\t\tfor ( type in contents ) {\n\t\t\tif ( contents[ type ] && contents[ type ].test( ct ) ) {\n\t\t\t\tdataTypes.unshift( type );\n\t\t\t\tbreak;\n\t\t\t}\n\t\t}\n\t}\n\n\t// Check to see if we have a response for the expected dataType\n\tif ( dataTypes[ 0 ] in responses ) {\n\t\tfinalDataType = dataTypes[ 0 ];\n\t} else {\n\n\t\t// Try convertible dataTypes\n\t\tfor ( type in responses ) {\n\t\t\tif ( !dataTypes[ 0 ] || s.converters[ type + \" \" + dataTypes[ 0 ] ] ) {\n\t\t\t\tfinalDataType = type;\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tif ( !firstDataType ) {\n\t\t\t\tfirstDataType = type;\n\t\t\t}\n\t\t}\n\n\t\t// Or just use first one\n\t\tfinalDataType = finalDataType || firstDataType;\n\t}\n\n\t// If we found a dataType\n\t// We add the dataType to the list if needed\n\t// and return the corresponding response\n\tif ( finalDataType ) {\n\t\tif ( finalDataType !== dataTypes[ 0 ] ) {\n\t\t\tdataTypes.unshift( finalDataType );\n\t\t}\n\t\treturn responses[ finalDataType ];\n\t}\n}\n\n/* Chain conversions given the request and the original response\n * Also sets the responseXXX fields on the jqXHR instance\n */\nfunction ajaxConvert( s, response, jqXHR, isSuccess ) {\n\tvar conv2, current, conv, tmp, prev,\n\t\tconverters = {},\n\n\t\t// Work with a copy of dataTypes in case we need to modify it for conversion\n\t\tdataTypes = s.dataTypes.slice();\n\n\t// Create converters map with lowercased keys\n\tif ( dataTypes[ 1 ] ) {\n\t\tfor ( conv in s.converters ) {\n\t\t\tconverters[ conv.toLowerCase() ] = s.converters[ conv ];\n\t\t}\n\t}\n\n\tcurrent = dataTypes.shift();\n\n\t// Convert to each sequential dataType\n\twhile ( current ) {\n\n\t\tif ( s.responseFields[ current ] ) {\n\t\t\tjqXHR[ s.responseFields[ current ] ] = response;\n\t\t}\n\n\t\t// Apply the dataFilter if provided\n\t\tif ( !prev && isSuccess && s.dataFilter ) {\n\t\t\tresponse = s.dataFilter( response, s.dataType );\n\t\t}\n\n\t\tprev = current;\n\t\tcurrent = dataTypes.shift();\n\n\t\tif ( current ) {\n\n\t\t\t// There's only work to do if current dataType is non-auto\n\t\t\tif ( current === \"*\" ) {\n\n\t\t\t\tcurrent = prev;\n\n\t\t\t// Convert response if prev dataType is non-auto and differs from current\n\t\t\t} else if ( prev !== \"*\" && prev !== current ) {\n\n\t\t\t\t// Seek a direct converter\n\t\t\t\tconv = converters[ prev + \" \" + current ] || converters[ \"* \" + current ];\n\n\t\t\t\t// If none found, seek a pair\n\t\t\t\tif ( !conv ) {\n\t\t\t\t\tfor ( conv2 in converters ) {\n\n\t\t\t\t\t\t// If conv2 outputs current\n\t\t\t\t\t\ttmp = conv2.split( \" \" );\n\t\t\t\t\t\tif ( tmp[ 1 ] === current ) {\n\n\t\t\t\t\t\t\t// If prev can be converted to accepted input\n\t\t\t\t\t\t\tconv = converters[ prev + \" \" + tmp[ 0 ] ] ||\n\t\t\t\t\t\t\t\tconverters[ \"* \" + tmp[ 0 ] ];\n\t\t\t\t\t\t\tif ( conv ) {\n\n\t\t\t\t\t\t\t\t// Condense equivalence converters\n\t\t\t\t\t\t\t\tif ( conv === true ) {\n\t\t\t\t\t\t\t\t\tconv = converters[ conv2 ];\n\n\t\t\t\t\t\t\t\t// Otherwise, insert the intermediate dataType\n\t\t\t\t\t\t\t\t} else if ( converters[ conv2 ] !== true ) {\n\t\t\t\t\t\t\t\t\tcurrent = tmp[ 0 ];\n\t\t\t\t\t\t\t\t\tdataTypes.unshift( tmp[ 1 ] );\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Apply converter (if not an equivalence)\n\t\t\t\tif ( conv !== true ) {\n\n\t\t\t\t\t// Unless errors are allowed to bubble, catch and return them\n\t\t\t\t\tif ( conv && s.throws ) {\n\t\t\t\t\t\tresponse = conv( response );\n\t\t\t\t\t} else {\n\t\t\t\t\t\ttry {\n\t\t\t\t\t\t\tresponse = conv( response );\n\t\t\t\t\t\t} catch ( e ) {\n\t\t\t\t\t\t\treturn {\n\t\t\t\t\t\t\t\tstate: \"parsererror\",\n\t\t\t\t\t\t\t\terror: conv ? e : \"No conversion from \" + prev + \" to \" + current\n\t\t\t\t\t\t\t};\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn { state: \"success\", data: response };\n}\n\njQuery.extend( {\n\n\t// Counter for holding the number of active queries\n\tactive: 0,\n\n\t// Last-Modified header cache for next request\n\tlastModified: {},\n\tetag: {},\n\n\tajaxSettings: {\n\t\turl: location.href,\n\t\ttype: \"GET\",\n\t\tisLocal: rlocalProtocol.test( location.protocol ),\n\t\tglobal: true,\n\t\tprocessData: true,\n\t\tasync: true,\n\t\tcontentType: \"application/x-www-form-urlencoded; charset=UTF-8\",\n\n\t\t/*\n\t\ttimeout: 0,\n\t\tdata: null,\n\t\tdataType: null,\n\t\tusername: null,\n\t\tpassword: null,\n\t\tcache: null,\n\t\tthrows: false,\n\t\ttraditional: false,\n\t\theaders: {},\n\t\t*/\n\n\t\taccepts: {\n\t\t\t\"*\": allTypes,\n\t\t\ttext: \"text/plain\",\n\t\t\thtml: \"text/html\",\n\t\t\txml: \"application/xml, text/xml\",\n\t\t\tjson: \"application/json, text/javascript\"\n\t\t},\n\n\t\tcontents: {\n\t\t\txml: /\\bxml\\b/,\n\t\t\thtml: /\\bhtml/,\n\t\t\tjson: /\\bjson\\b/\n\t\t},\n\n\t\tresponseFields: {\n\t\t\txml: \"responseXML\",\n\t\t\ttext: \"responseText\",\n\t\t\tjson: \"responseJSON\"\n\t\t},\n\n\t\t// Data converters\n\t\t// Keys separate source (or catchall \"*\") and destination types with a single space\n\t\tconverters: {\n\n\t\t\t// Convert anything to text\n\t\t\t\"* text\": String,\n\n\t\t\t// Text to html (true = no transformation)\n\t\t\t\"text html\": true,\n\n\t\t\t// Evaluate text as a json expression\n\t\t\t\"text json\": JSON.parse,\n\n\t\t\t// Parse text as xml\n\t\t\t\"text xml\": jQuery.parseXML\n\t\t},\n\n\t\t// For options that shouldn't be deep extended:\n\t\t// you can add your own custom options here if\n\t\t// and when you create one that shouldn't be\n\t\t// deep extended (see ajaxExtend)\n\t\tflatOptions: {\n\t\t\turl: true,\n\t\t\tcontext: true\n\t\t}\n\t},\n\n\t// Creates a full fledged settings object into target\n\t// with both ajaxSettings and settings fields.\n\t// If target is omitted, writes into ajaxSettings.\n\tajaxSetup: function( target, settings ) {\n\t\treturn settings ?\n\n\t\t\t// Building a settings object\n\t\t\tajaxExtend( ajaxExtend( target, jQuery.ajaxSettings ), settings ) :\n\n\t\t\t// Extending ajaxSettings\n\t\t\tajaxExtend( jQuery.ajaxSettings, target );\n\t},\n\n\tajaxPrefilter: addToPrefiltersOrTransports( prefilters ),\n\tajaxTransport: addToPrefiltersOrTransports( transports ),\n\n\t// Main method\n\tajax: function( url, options ) {\n\n\t\t// If url is an object, simulate pre-1.5 signature\n\t\tif ( typeof url === \"object\" ) {\n\t\t\toptions = url;\n\t\t\turl = undefined;\n\t\t}\n\n\t\t// Force options to be an object\n\t\toptions = options || {};\n\n\t\tvar transport,\n\n\t\t\t// URL without anti-cache param\n\t\t\tcacheURL,\n\n\t\t\t// Response headers\n\t\t\tresponseHeadersString,\n\t\t\tresponseHeaders,\n\n\t\t\t// timeout handle\n\t\t\ttimeoutTimer,\n\n\t\t\t// Url cleanup var\n\t\t\turlAnchor,\n\n\t\t\t// Request state (becomes false upon send and true upon completion)\n\t\t\tcompleted,\n\n\t\t\t// To know if global events are to be dispatched\n\t\t\tfireGlobals,\n\n\t\t\t// Loop variable\n\t\t\ti,\n\n\t\t\t// uncached part of the url\n\t\t\tuncached,\n\n\t\t\t// Create the final options object\n\t\t\ts = jQuery.ajaxSetup( {}, options ),\n\n\t\t\t// Callbacks context\n\t\t\tcallbackContext = s.context || s,\n\n\t\t\t// Context for global events is callbackContext if it is a DOM node or jQuery collection\n\t\t\tglobalEventContext = s.context &&\n\t\t\t\t( callbackContext.nodeType || callbackContext.jquery ) ?\n\t\t\t\t\tjQuery( callbackContext ) :\n\t\t\t\t\tjQuery.event,\n\n\t\t\t// Deferreds\n\t\t\tdeferred = jQuery.Deferred(),\n\t\t\tcompleteDeferred = jQuery.Callbacks( \"once memory\" ),\n\n\t\t\t// Status-dependent callbacks\n\t\t\tstatusCode = s.statusCode || {},\n\n\t\t\t// Headers (they are sent all at once)\n\t\t\trequestHeaders = {},\n\t\t\trequestHeadersNames = {},\n\n\t\t\t// Default abort message\n\t\t\tstrAbort = \"canceled\",\n\n\t\t\t// Fake xhr\n\t\t\tjqXHR = {\n\t\t\t\treadyState: 0,\n\n\t\t\t\t// Builds headers hashtable if needed\n\t\t\t\tgetResponseHeader: function( key ) {\n\t\t\t\t\tvar match;\n\t\t\t\t\tif ( completed ) {\n\t\t\t\t\t\tif ( !responseHeaders ) {\n\t\t\t\t\t\t\tresponseHeaders = {};\n\t\t\t\t\t\t\twhile ( ( match = rheaders.exec( responseHeadersString ) ) ) {\n\t\t\t\t\t\t\t\tresponseHeaders[ match[ 1 ].toLowerCase() + \" \" ] =\n\t\t\t\t\t\t\t\t\t( responseHeaders[ match[ 1 ].toLowerCase() + \" \" ] || [] )\n\t\t\t\t\t\t\t\t\t\t.concat( match[ 2 ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t\tmatch = responseHeaders[ key.toLowerCase() + \" \" ];\n\t\t\t\t\t}\n\t\t\t\t\treturn match == null ? null : match.join( \", \" );\n\t\t\t\t},\n\n\t\t\t\t// Raw string\n\t\t\t\tgetAllResponseHeaders: function() {\n\t\t\t\t\treturn completed ? responseHeadersString : null;\n\t\t\t\t},\n\n\t\t\t\t// Caches the header\n\t\t\t\tsetRequestHeader: function( name, value ) {\n\t\t\t\t\tif ( completed == null ) {\n\t\t\t\t\t\tname = requestHeadersNames[ name.toLowerCase() ] =\n\t\t\t\t\t\t\trequestHeadersNames[ name.toLowerCase() ] || name;\n\t\t\t\t\t\trequestHeaders[ name ] = value;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\n\t\t\t\t// Overrides response content-type header\n\t\t\t\toverrideMimeType: function( type ) {\n\t\t\t\t\tif ( completed == null ) {\n\t\t\t\t\t\ts.mimeType = type;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\n\t\t\t\t// Status-dependent callbacks\n\t\t\t\tstatusCode: function( map ) {\n\t\t\t\t\tvar code;\n\t\t\t\t\tif ( map ) {\n\t\t\t\t\t\tif ( completed ) {\n\n\t\t\t\t\t\t\t// Execute the appropriate callbacks\n\t\t\t\t\t\t\tjqXHR.always( map[ jqXHR.status ] );\n\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t// Lazy-add the new callbacks in a way that preserves old ones\n\t\t\t\t\t\t\tfor ( code in map ) {\n\t\t\t\t\t\t\t\tstatusCode[ code ] = [ statusCode[ code ], map[ code ] ];\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\n\t\t\t\t// Cancel the request\n\t\t\t\tabort: function( statusText ) {\n\t\t\t\t\tvar finalText = statusText || strAbort;\n\t\t\t\t\tif ( transport ) {\n\t\t\t\t\t\ttransport.abort( finalText );\n\t\t\t\t\t}\n\t\t\t\t\tdone( 0, finalText );\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\t\t\t};\n\n\t\t// Attach deferreds\n\t\tdeferred.promise( jqXHR );\n\n\t\t// Add protocol if not provided (prefilters might expect it)\n\t\t// Handle falsy url in the settings object (#10093: consistency with old signature)\n\t\t// We also use the url parameter if available\n\t\ts.url = ( ( url || s.url || location.href ) + \"\" )\n\t\t\t.replace( rprotocol, location.protocol + \"//\" );\n\n\t\t// Alias method option to type as per ticket #12004\n\t\ts.type = options.method || options.type || s.method || s.type;\n\n\t\t// Extract dataTypes list\n\t\ts.dataTypes = ( s.dataType || \"*\" ).toLowerCase().match( rnothtmlwhite ) || [ \"\" ];\n\n\t\t// A cross-domain request is in order when the origin doesn't match the current origin.\n\t\tif ( s.crossDomain == null ) {\n\t\t\turlAnchor = document.createElement( \"a\" );\n\n\t\t\t// Support: IE <=8 - 11, Edge 12 - 15\n\t\t\t// IE throws exception on accessing the href property if url is malformed,\n\t\t\t// e.g. http://example.com:80x/\n\t\t\ttry {\n\t\t\t\turlAnchor.href = s.url;\n\n\t\t\t\t// Support: IE <=8 - 11 only\n\t\t\t\t// Anchor's host property isn't correctly set when s.url is relative\n\t\t\t\turlAnchor.href = urlAnchor.href;\n\t\t\t\ts.crossDomain = originAnchor.protocol + \"//\" + originAnchor.host !==\n\t\t\t\t\turlAnchor.protocol + \"//\" + urlAnchor.host;\n\t\t\t} catch ( e ) {\n\n\t\t\t\t// If there is an error parsing the URL, assume it is crossDomain,\n\t\t\t\t// it can be rejected by the transport if it is invalid\n\t\t\t\ts.crossDomain = true;\n\t\t\t}\n\t\t}\n\n\t\t// Convert data if not already a string\n\t\tif ( s.data && s.processData && typeof s.data !== \"string\" ) {\n\t\t\ts.data = jQuery.param( s.data, s.traditional );\n\t\t}\n\n\t\t// Apply prefilters\n\t\tinspectPrefiltersOrTransports( prefilters, s, options, jqXHR );\n\n\t\t// If request was aborted inside a prefilter, stop there\n\t\tif ( completed ) {\n\t\t\treturn jqXHR;\n\t\t}\n\n\t\t// We can fire global events as of now if asked to\n\t\t// Don't fire events if jQuery.event is undefined in an AMD-usage scenario (#15118)\n\t\tfireGlobals = jQuery.event && s.global;\n\n\t\t// Watch for a new set of requests\n\t\tif ( fireGlobals && jQuery.active++ === 0 ) {\n\t\t\tjQuery.event.trigger( \"ajaxStart\" );\n\t\t}\n\n\t\t// Uppercase the type\n\t\ts.type = s.type.toUpperCase();\n\n\t\t// Determine if request has content\n\t\ts.hasContent = !rnoContent.test( s.type );\n\n\t\t// Save the URL in case we're toying with the If-Modified-Since\n\t\t// and/or If-None-Match header later on\n\t\t// Remove hash to simplify url manipulation\n\t\tcacheURL = s.url.replace( rhash, \"\" );\n\n\t\t// More options handling for requests with no content\n\t\tif ( !s.hasContent ) {\n\n\t\t\t// Remember the hash so we can put it back\n\t\t\tuncached = s.url.slice( cacheURL.length );\n\n\t\t\t// If data is available and should be processed, append data to url\n\t\t\tif ( s.data && ( s.processData || typeof s.data === \"string\" ) ) {\n\t\t\t\tcacheURL += ( rquery.test( cacheURL ) ? \"&\" : \"?\" ) + s.data;\n\n\t\t\t\t// #9682: remove data so that it's not used in an eventual retry\n\t\t\t\tdelete s.data;\n\t\t\t}\n\n\t\t\t// Add or update anti-cache param if needed\n\t\t\tif ( s.cache === false ) {\n\t\t\t\tcacheURL = cacheURL.replace( rantiCache, \"$1\" );\n\t\t\t\tuncached = ( rquery.test( cacheURL ) ? \"&\" : \"?\" ) + \"_=\" + ( nonce++ ) + uncached;\n\t\t\t}\n\n\t\t\t// Put hash and anti-cache on the URL that will be requested (gh-1732)\n\t\t\ts.url = cacheURL + uncached;\n\n\t\t// Change '%20' to '+' if this is encoded form body content (gh-2658)\n\t\t} else if ( s.data && s.processData &&\n\t\t\t( s.contentType || \"\" ).indexOf( \"application/x-www-form-urlencoded\" ) === 0 ) {\n\t\t\ts.data = s.data.replace( r20, \"+\" );\n\t\t}\n\n\t\t// Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode.\n\t\tif ( s.ifModified ) {\n\t\t\tif ( jQuery.lastModified[ cacheURL ] ) {\n\t\t\t\tjqXHR.setRequestHeader( \"If-Modified-Since\", jQuery.lastModified[ cacheURL ] );\n\t\t\t}\n\t\t\tif ( jQuery.etag[ cacheURL ] ) {\n\t\t\t\tjqXHR.setRequestHeader( \"If-None-Match\", jQuery.etag[ cacheURL ] );\n\t\t\t}\n\t\t}\n\n\t\t// Set the correct header, if data is being sent\n\t\tif ( s.data && s.hasContent && s.contentType !== false || options.contentType ) {\n\t\t\tjqXHR.setRequestHeader( \"Content-Type\", s.contentType );\n\t\t}\n\n\t\t// Set the Accepts header for the server, depending on the dataType\n\t\tjqXHR.setRequestHeader(\n\t\t\t\"Accept\",\n\t\t\ts.dataTypes[ 0 ] && s.accepts[ s.dataTypes[ 0 ] ] ?\n\t\t\t\ts.accepts[ s.dataTypes[ 0 ] ] +\n\t\t\t\t\t( s.dataTypes[ 0 ] !== \"*\" ? \", \" + allTypes + \"; q=0.01\" : \"\" ) :\n\t\t\t\ts.accepts[ \"*\" ]\n\t\t);\n\n\t\t// Check for headers option\n\t\tfor ( i in s.headers ) {\n\t\t\tjqXHR.setRequestHeader( i, s.headers[ i ] );\n\t\t}\n\n\t\t// Allow custom headers/mimetypes and early abort\n\t\tif ( s.beforeSend &&\n\t\t\t( s.beforeSend.call( callbackContext, jqXHR, s ) === false || completed ) ) {\n\n\t\t\t// Abort if not done already and return\n\t\t\treturn jqXHR.abort();\n\t\t}\n\n\t\t// Aborting is no longer a cancellation\n\t\tstrAbort = \"abort\";\n\n\t\t// Install callbacks on deferreds\n\t\tcompleteDeferred.add( s.complete );\n\t\tjqXHR.done( s.success );\n\t\tjqXHR.fail( s.error );\n\n\t\t// Get transport\n\t\ttransport = inspectPrefiltersOrTransports( transports, s, options, jqXHR );\n\n\t\t// If no transport, we auto-abort\n\t\tif ( !transport ) {\n\t\t\tdone( -1, \"No Transport\" );\n\t\t} else {\n\t\t\tjqXHR.readyState = 1;\n\n\t\t\t// Send global event\n\t\t\tif ( fireGlobals ) {\n\t\t\t\tglobalEventContext.trigger( \"ajaxSend\", [ jqXHR, s ] );\n\t\t\t}\n\n\t\t\t// If request was aborted inside ajaxSend, stop there\n\t\t\tif ( completed ) {\n\t\t\t\treturn jqXHR;\n\t\t\t}\n\n\t\t\t// Timeout\n\t\t\tif ( s.async && s.timeout > 0 ) {\n\t\t\t\ttimeoutTimer = window.setTimeout( function() {\n\t\t\t\t\tjqXHR.abort( \"timeout\" );\n\t\t\t\t}, s.timeout );\n\t\t\t}\n\n\t\t\ttry {\n\t\t\t\tcompleted = false;\n\t\t\t\ttransport.send( requestHeaders, done );\n\t\t\t} catch ( e ) {\n\n\t\t\t\t// Rethrow post-completion exceptions\n\t\t\t\tif ( completed ) {\n\t\t\t\t\tthrow e;\n\t\t\t\t}\n\n\t\t\t\t// Propagate others as results\n\t\t\t\tdone( -1, e );\n\t\t\t}\n\t\t}\n\n\t\t// Callback for when everything is done\n\t\tfunction done( status, nativeStatusText, responses, headers ) {\n\t\t\tvar isSuccess, success, error, response, modified,\n\t\t\t\tstatusText = nativeStatusText;\n\n\t\t\t// Ignore repeat invocations\n\t\t\tif ( completed ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tcompleted = true;\n\n\t\t\t// Clear timeout if it exists\n\t\t\tif ( timeoutTimer ) {\n\t\t\t\twindow.clearTimeout( timeoutTimer );\n\t\t\t}\n\n\t\t\t// Dereference transport for early garbage collection\n\t\t\t// (no matter how long the jqXHR object will be used)\n\t\t\ttransport = undefined;\n\n\t\t\t// Cache response headers\n\t\t\tresponseHeadersString = headers || \"\";\n\n\t\t\t// Set readyState\n\t\t\tjqXHR.readyState = status > 0 ? 4 : 0;\n\n\t\t\t// Determine if successful\n\t\t\tisSuccess = status >= 200 && status < 300 || status === 304;\n\n\t\t\t// Get response data\n\t\t\tif ( responses ) {\n\t\t\t\tresponse = ajaxHandleResponses( s, jqXHR, responses );\n\t\t\t}\n\n\t\t\t// Convert no matter what (that way responseXXX fields are always set)\n\t\t\tresponse = ajaxConvert( s, response, jqXHR, isSuccess );\n\n\t\t\t// If successful, handle type chaining\n\t\t\tif ( isSuccess ) {\n\n\t\t\t\t// Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode.\n\t\t\t\tif ( s.ifModified ) {\n\t\t\t\t\tmodified = jqXHR.getResponseHeader( \"Last-Modified\" );\n\t\t\t\t\tif ( modified ) {\n\t\t\t\t\t\tjQuery.lastModified[ cacheURL ] = modified;\n\t\t\t\t\t}\n\t\t\t\t\tmodified = jqXHR.getResponseHeader( \"etag\" );\n\t\t\t\t\tif ( modified ) {\n\t\t\t\t\t\tjQuery.etag[ cacheURL ] = modified;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// if no content\n\t\t\t\tif ( status === 204 || s.type === \"HEAD\" ) {\n\t\t\t\t\tstatusText = \"nocontent\";\n\n\t\t\t\t// if not modified\n\t\t\t\t} else if ( status === 304 ) {\n\t\t\t\t\tstatusText = \"notmodified\";\n\n\t\t\t\t// If we have data, let's convert it\n\t\t\t\t} else {\n\t\t\t\t\tstatusText = response.state;\n\t\t\t\t\tsuccess = response.data;\n\t\t\t\t\terror = response.error;\n\t\t\t\t\tisSuccess = !error;\n\t\t\t\t}\n\t\t\t} else {\n\n\t\t\t\t// Extract error from statusText and normalize for non-aborts\n\t\t\t\terror = statusText;\n\t\t\t\tif ( status || !statusText ) {\n\t\t\t\t\tstatusText = \"error\";\n\t\t\t\t\tif ( status < 0 ) {\n\t\t\t\t\t\tstatus = 0;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Set data for the fake xhr object\n\t\t\tjqXHR.status = status;\n\t\t\tjqXHR.statusText = ( nativeStatusText || statusText ) + \"\";\n\n\t\t\t// Success/Error\n\t\t\tif ( isSuccess ) {\n\t\t\t\tdeferred.resolveWith( callbackContext, [ success, statusText, jqXHR ] );\n\t\t\t} else {\n\t\t\t\tdeferred.rejectWith( callbackContext, [ jqXHR, statusText, error ] );\n\t\t\t}\n\n\t\t\t// Status-dependent callbacks\n\t\t\tjqXHR.statusCode( statusCode );\n\t\t\tstatusCode = undefined;\n\n\t\t\tif ( fireGlobals ) {\n\t\t\t\tglobalEventContext.trigger( isSuccess ? \"ajaxSuccess\" : \"ajaxError\",\n\t\t\t\t\t[ jqXHR, s, isSuccess ? success : error ] );\n\t\t\t}\n\n\t\t\t// Complete\n\t\t\tcompleteDeferred.fireWith( callbackContext, [ jqXHR, statusText ] );\n\n\t\t\tif ( fireGlobals ) {\n\t\t\t\tglobalEventContext.trigger( \"ajaxComplete\", [ jqXHR, s ] );\n\n\t\t\t\t// Handle the global AJAX counter\n\t\t\t\tif ( !( --jQuery.active ) ) {\n\t\t\t\t\tjQuery.event.trigger( \"ajaxStop\" );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn jqXHR;\n\t},\n\n\tgetJSON: function( url, data, callback ) {\n\t\treturn jQuery.get( url, data, callback, \"json\" );\n\t},\n\n\tgetScript: function( url, callback ) {\n\t\treturn jQuery.get( url, undefined, callback, \"script\" );\n\t}\n} );\n\njQuery.each( [ \"get\", \"post\" ], function( i, method ) {\n\tjQuery[ method ] = function( url, data, callback, type ) {\n\n\t\t// Shift arguments if data argument was omitted\n\t\tif ( isFunction( data ) ) {\n\t\t\ttype = type || callback;\n\t\t\tcallback = data;\n\t\t\tdata = undefined;\n\t\t}\n\n\t\t// The url can be an options object (which then must have .url)\n\t\treturn jQuery.ajax( jQuery.extend( {\n\t\t\turl: url,\n\t\t\ttype: method,\n\t\t\tdataType: type,\n\t\t\tdata: data,\n\t\t\tsuccess: callback\n\t\t}, jQuery.isPlainObject( url ) && url ) );\n\t};\n} );\n\n\njQuery._evalUrl = function( url, options ) {\n\treturn jQuery.ajax( {\n\t\turl: url,\n\n\t\t// Make this explicit, since user can override this through ajaxSetup (#11264)\n\t\ttype: \"GET\",\n\t\tdataType: \"script\",\n\t\tcache: true,\n\t\tasync: false,\n\t\tglobal: false,\n\n\t\t// Only evaluate the response if it is successful (gh-4126)\n\t\t// dataFilter is not invoked for failure responses, so using it instead\n\t\t// of the default converter is kludgy but it works.\n\t\tconverters: {\n\t\t\t\"text script\": function() {}\n\t\t},\n\t\tdataFilter: function( response ) {\n\t\t\tjQuery.globalEval( response, options );\n\t\t}\n\t} );\n};\n\n\njQuery.fn.extend( {\n\twrapAll: function( html ) {\n\t\tvar wrap;\n\n\t\tif ( this[ 0 ] ) {\n\t\t\tif ( isFunction( html ) ) {\n\t\t\t\thtml = html.call( this[ 0 ] );\n\t\t\t}\n\n\t\t\t// The elements to wrap the target around\n\t\t\twrap = jQuery( html, this[ 0 ].ownerDocument ).eq( 0 ).clone( true );\n\n\t\t\tif ( this[ 0 ].parentNode ) {\n\t\t\t\twrap.insertBefore( this[ 0 ] );\n\t\t\t}\n\n\t\t\twrap.map( function() {\n\t\t\t\tvar elem = this;\n\n\t\t\t\twhile ( elem.firstElementChild ) {\n\t\t\t\t\telem = elem.firstElementChild;\n\t\t\t\t}\n\n\t\t\t\treturn elem;\n\t\t\t} ).append( this );\n\t\t}\n\n\t\treturn this;\n\t},\n\n\twrapInner: function( html ) {\n\t\tif ( isFunction( html ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).wrapInner( html.call( this, i ) );\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar self = jQuery( this ),\n\t\t\t\tcontents = self.contents();\n\n\t\t\tif ( contents.length ) {\n\t\t\t\tcontents.wrapAll( html );\n\n\t\t\t} else {\n\t\t\t\tself.append( html );\n\t\t\t}\n\t\t} );\n\t},\n\n\twrap: function( html ) {\n\t\tvar htmlIsFunction = isFunction( html );\n\n\t\treturn this.each( function( i ) {\n\t\t\tjQuery( this ).wrapAll( htmlIsFunction ? html.call( this, i ) : html );\n\t\t} );\n\t},\n\n\tunwrap: function( selector ) {\n\t\tthis.parent( selector ).not( \"body\" ).each( function() {\n\t\t\tjQuery( this ).replaceWith( this.childNodes );\n\t\t} );\n\t\treturn this;\n\t}\n} );\n\n\njQuery.expr.pseudos.hidden = function( elem ) {\n\treturn !jQuery.expr.pseudos.visible( elem );\n};\njQuery.expr.pseudos.visible = function( elem ) {\n\treturn !!( elem.offsetWidth || elem.offsetHeight || elem.getClientRects().length );\n};\n\n\n\n\njQuery.ajaxSettings.xhr = function() {\n\ttry {\n\t\treturn new window.XMLHttpRequest();\n\t} catch ( e ) {}\n};\n\nvar xhrSuccessStatus = {\n\n\t\t// File protocol always yields status code 0, assume 200\n\t\t0: 200,\n\n\t\t// Support: IE <=9 only\n\t\t// #1450: sometimes IE returns 1223 when it should be 204\n\t\t1223: 204\n\t},\n\txhrSupported = jQuery.ajaxSettings.xhr();\n\nsupport.cors = !!xhrSupported && ( \"withCredentials\" in xhrSupported );\nsupport.ajax = xhrSupported = !!xhrSupported;\n\njQuery.ajaxTransport( function( options ) {\n\tvar callback, errorCallback;\n\n\t// Cross domain only allowed if supported through XMLHttpRequest\n\tif ( support.cors || xhrSupported && !options.crossDomain ) {\n\t\treturn {\n\t\t\tsend: function( headers, complete ) {\n\t\t\t\tvar i,\n\t\t\t\t\txhr = options.xhr();\n\n\t\t\t\txhr.open(\n\t\t\t\t\toptions.type,\n\t\t\t\t\toptions.url,\n\t\t\t\t\toptions.async,\n\t\t\t\t\toptions.username,\n\t\t\t\t\toptions.password\n\t\t\t\t);\n\n\t\t\t\t// Apply custom fields if provided\n\t\t\t\tif ( options.xhrFields ) {\n\t\t\t\t\tfor ( i in options.xhrFields ) {\n\t\t\t\t\t\txhr[ i ] = options.xhrFields[ i ];\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Override mime type if needed\n\t\t\t\tif ( options.mimeType && xhr.overrideMimeType ) {\n\t\t\t\t\txhr.overrideMimeType( options.mimeType );\n\t\t\t\t}\n\n\t\t\t\t// X-Requested-With header\n\t\t\t\t// For cross-domain requests, seeing as conditions for a preflight are\n\t\t\t\t// akin to a jigsaw puzzle, we simply never set it to be sure.\n\t\t\t\t// (it can always be set on a per-request basis or even using ajaxSetup)\n\t\t\t\t// For same-domain requests, won't change header if already provided.\n\t\t\t\tif ( !options.crossDomain && !headers[ \"X-Requested-With\" ] ) {\n\t\t\t\t\theaders[ \"X-Requested-With\" ] = \"XMLHttpRequest\";\n\t\t\t\t}\n\n\t\t\t\t// Set headers\n\t\t\t\tfor ( i in headers ) {\n\t\t\t\t\txhr.setRequestHeader( i, headers[ i ] );\n\t\t\t\t}\n\n\t\t\t\t// Callback\n\t\t\t\tcallback = function( type ) {\n\t\t\t\t\treturn function() {\n\t\t\t\t\t\tif ( callback ) {\n\t\t\t\t\t\t\tcallback = errorCallback = xhr.onload =\n\t\t\t\t\t\t\t\txhr.onerror = xhr.onabort = xhr.ontimeout =\n\t\t\t\t\t\t\t\t\txhr.onreadystatechange = null;\n\n\t\t\t\t\t\t\tif ( type === \"abort\" ) {\n\t\t\t\t\t\t\t\txhr.abort();\n\t\t\t\t\t\t\t} else if ( type === \"error\" ) {\n\n\t\t\t\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t\t\t\t// On a manual native abort, IE9 throws\n\t\t\t\t\t\t\t\t// errors on any property access that is not readyState\n\t\t\t\t\t\t\t\tif ( typeof xhr.status !== \"number\" ) {\n\t\t\t\t\t\t\t\t\tcomplete( 0, \"error\" );\n\t\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\t\tcomplete(\n\n\t\t\t\t\t\t\t\t\t\t// File: protocol always yields status 0; see #8605, #14207\n\t\t\t\t\t\t\t\t\t\txhr.status,\n\t\t\t\t\t\t\t\t\t\txhr.statusText\n\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tcomplete(\n\t\t\t\t\t\t\t\t\txhrSuccessStatus[ xhr.status ] || xhr.status,\n\t\t\t\t\t\t\t\t\txhr.statusText,\n\n\t\t\t\t\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t\t\t\t\t// IE9 has no XHR2 but throws on binary (trac-11426)\n\t\t\t\t\t\t\t\t\t// For XHR2 non-text, let the caller handle it (gh-2498)\n\t\t\t\t\t\t\t\t\t( xhr.responseType || \"text\" ) !== \"text\"  ||\n\t\t\t\t\t\t\t\t\ttypeof xhr.responseText !== \"string\" ?\n\t\t\t\t\t\t\t\t\t\t{ binary: xhr.response } :\n\t\t\t\t\t\t\t\t\t\t{ text: xhr.responseText },\n\t\t\t\t\t\t\t\t\txhr.getAllResponseHeaders()\n\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t};\n\t\t\t\t};\n\n\t\t\t\t// Listen to events\n\t\t\t\txhr.onload = callback();\n\t\t\t\terrorCallback = xhr.onerror = xhr.ontimeout = callback( \"error\" );\n\n\t\t\t\t// Support: IE 9 only\n\t\t\t\t// Use onreadystatechange to replace onabort\n\t\t\t\t// to handle uncaught aborts\n\t\t\t\tif ( xhr.onabort !== undefined ) {\n\t\t\t\t\txhr.onabort = errorCallback;\n\t\t\t\t} else {\n\t\t\t\t\txhr.onreadystatechange = function() {\n\n\t\t\t\t\t\t// Check readyState before timeout as it changes\n\t\t\t\t\t\tif ( xhr.readyState === 4 ) {\n\n\t\t\t\t\t\t\t// Allow onerror to be called first,\n\t\t\t\t\t\t\t// but that will not handle a native abort\n\t\t\t\t\t\t\t// Also, save errorCallback to a variable\n\t\t\t\t\t\t\t// as xhr.onerror cannot be accessed\n\t\t\t\t\t\t\twindow.setTimeout( function() {\n\t\t\t\t\t\t\t\tif ( callback ) {\n\t\t\t\t\t\t\t\t\terrorCallback();\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t}\n\t\t\t\t\t};\n\t\t\t\t}\n\n\t\t\t\t// Create the abort callback\n\t\t\t\tcallback = callback( \"abort\" );\n\n\t\t\t\ttry {\n\n\t\t\t\t\t// Do send the request (this may raise an exception)\n\t\t\t\t\txhr.send( options.hasContent && options.data || null );\n\t\t\t\t} catch ( e ) {\n\n\t\t\t\t\t// #14683: Only rethrow if this hasn't been notified as an error yet\n\t\t\t\t\tif ( callback ) {\n\t\t\t\t\t\tthrow e;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t},\n\n\t\t\tabort: function() {\n\t\t\t\tif ( callback ) {\n\t\t\t\t\tcallback();\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t}\n} );\n\n\n\n\n// Prevent auto-execution of scripts when no explicit dataType was provided (See gh-2432)\njQuery.ajaxPrefilter( function( s ) {\n\tif ( s.crossDomain ) {\n\t\ts.contents.script = false;\n\t}\n} );\n\n// Install script dataType\njQuery.ajaxSetup( {\n\taccepts: {\n\t\tscript: \"text/javascript, application/javascript, \" +\n\t\t\t\"application/ecmascript, application/x-ecmascript\"\n\t},\n\tcontents: {\n\t\tscript: /\\b(?:java|ecma)script\\b/\n\t},\n\tconverters: {\n\t\t\"text script\": function( text ) {\n\t\t\tjQuery.globalEval( text );\n\t\t\treturn text;\n\t\t}\n\t}\n} );\n\n// Handle cache's special case and crossDomain\njQuery.ajaxPrefilter( \"script\", function( s ) {\n\tif ( s.cache === undefined ) {\n\t\ts.cache = false;\n\t}\n\tif ( s.crossDomain ) {\n\t\ts.type = \"GET\";\n\t}\n} );\n\n// Bind script tag hack transport\njQuery.ajaxTransport( \"script\", function( s ) {\n\n\t// This transport only deals with cross domain or forced-by-attrs requests\n\tif ( s.crossDomain || s.scriptAttrs ) {\n\t\tvar script, callback;\n\t\treturn {\n\t\t\tsend: function( _, complete ) {\n\t\t\t\tscript = jQuery( \"<script>\" )\n\t\t\t\t\t.attr( s.scriptAttrs || {} )\n\t\t\t\t\t.prop( { charset: s.scriptCharset, src: s.url } )\n\t\t\t\t\t.on( \"load error\", callback = function( evt ) {\n\t\t\t\t\t\tscript.remove();\n\t\t\t\t\t\tcallback = null;\n\t\t\t\t\t\tif ( evt ) {\n\t\t\t\t\t\t\tcomplete( evt.type === \"error\" ? 404 : 200, evt.type );\n\t\t\t\t\t\t}\n\t\t\t\t\t} );\n\n\t\t\t\t// Use native DOM manipulation to avoid our domManip AJAX trickery\n\t\t\t\tdocument.head.appendChild( script[ 0 ] );\n\t\t\t},\n\t\t\tabort: function() {\n\t\t\t\tif ( callback ) {\n\t\t\t\t\tcallback();\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t}\n} );\n\n\n\n\nvar oldCallbacks = [],\n\trjsonp = /(=)\\?(?=&|$)|\\?\\?/;\n\n// Default jsonp settings\njQuery.ajaxSetup( {\n\tjsonp: \"callback\",\n\tjsonpCallback: function() {\n\t\tvar callback = oldCallbacks.pop() || ( jQuery.expando + \"_\" + ( nonce++ ) );\n\t\tthis[ callback ] = true;\n\t\treturn callback;\n\t}\n} );\n\n// Detect, normalize options and install callbacks for jsonp requests\njQuery.ajaxPrefilter( \"json jsonp\", function( s, originalSettings, jqXHR ) {\n\n\tvar callbackName, overwritten, responseContainer,\n\t\tjsonProp = s.jsonp !== false && ( rjsonp.test( s.url ) ?\n\t\t\t\"url\" :\n\t\t\ttypeof s.data === \"string\" &&\n\t\t\t\t( s.contentType || \"\" )\n\t\t\t\t\t.indexOf( \"application/x-www-form-urlencoded\" ) === 0 &&\n\t\t\t\trjsonp.test( s.data ) && \"data\"\n\t\t);\n\n\t// Handle iff the expected data type is \"jsonp\" or we have a parameter to set\n\tif ( jsonProp || s.dataTypes[ 0 ] === \"jsonp\" ) {\n\n\t\t// Get callback name, remembering preexisting value associated with it\n\t\tcallbackName = s.jsonpCallback = isFunction( s.jsonpCallback ) ?\n\t\t\ts.jsonpCallback() :\n\t\t\ts.jsonpCallback;\n\n\t\t// Insert callback into url or form data\n\t\tif ( jsonProp ) {\n\t\t\ts[ jsonProp ] = s[ jsonProp ].replace( rjsonp, \"$1\" + callbackName );\n\t\t} else if ( s.jsonp !== false ) {\n\t\t\ts.url += ( rquery.test( s.url ) ? \"&\" : \"?\" ) + s.jsonp + \"=\" + callbackName;\n\t\t}\n\n\t\t// Use data converter to retrieve json after script execution\n\t\ts.converters[ \"script json\" ] = function() {\n\t\t\tif ( !responseContainer ) {\n\t\t\t\tjQuery.error( callbackName + \" was not called\" );\n\t\t\t}\n\t\t\treturn responseContainer[ 0 ];\n\t\t};\n\n\t\t// Force json dataType\n\t\ts.dataTypes[ 0 ] = \"json\";\n\n\t\t// Install callback\n\t\toverwritten = window[ callbackName ];\n\t\twindow[ callbackName ] = function() {\n\t\t\tresponseContainer = arguments;\n\t\t};\n\n\t\t// Clean-up function (fires after converters)\n\t\tjqXHR.always( function() {\n\n\t\t\t// If previous value didn't exist - remove it\n\t\t\tif ( overwritten === undefined ) {\n\t\t\t\tjQuery( window ).removeProp( callbackName );\n\n\t\t\t// Otherwise restore preexisting value\n\t\t\t} else {\n\t\t\t\twindow[ callbackName ] = overwritten;\n\t\t\t}\n\n\t\t\t// Save back as free\n\t\t\tif ( s[ callbackName ] ) {\n\n\t\t\t\t// Make sure that re-using the options doesn't screw things around\n\t\t\t\ts.jsonpCallback = originalSettings.jsonpCallback;\n\n\t\t\t\t// Save the callback name for future use\n\t\t\t\toldCallbacks.push( callbackName );\n\t\t\t}\n\n\t\t\t// Call if it was a function and we have a response\n\t\t\tif ( responseContainer && isFunction( overwritten ) ) {\n\t\t\t\toverwritten( responseContainer[ 0 ] );\n\t\t\t}\n\n\t\t\tresponseContainer = overwritten = undefined;\n\t\t} );\n\n\t\t// Delegate to script\n\t\treturn \"script\";\n\t}\n} );\n\n\n\n\n// Support: Safari 8 only\n// In Safari 8 documents created via document.implementation.createHTMLDocument\n// collapse sibling forms: the second one becomes a child of the first one.\n// Because of that, this security measure has to be disabled in Safari 8.\n// https://bugs.webkit.org/show_bug.cgi?id=137337\nsupport.createHTMLDocument = ( function() {\n\tvar body = document.implementation.createHTMLDocument( \"\" ).body;\n\tbody.innerHTML = \"<form></form><form></form>\";\n\treturn body.childNodes.length === 2;\n} )();\n\n\n// Argument \"data\" should be string of html\n// context (optional): If specified, the fragment will be created in this context,\n// defaults to document\n// keepScripts (optional): If true, will include scripts passed in the html string\njQuery.parseHTML = function( data, context, keepScripts ) {\n\tif ( typeof data !== \"string\" ) {\n\t\treturn [];\n\t}\n\tif ( typeof context === \"boolean\" ) {\n\t\tkeepScripts = context;\n\t\tcontext = false;\n\t}\n\n\tvar base, parsed, scripts;\n\n\tif ( !context ) {\n\n\t\t// Stop scripts or inline event handlers from being executed immediately\n\t\t// by using document.implementation\n\t\tif ( support.createHTMLDocument ) {\n\t\t\tcontext = document.implementation.createHTMLDocument( \"\" );\n\n\t\t\t// Set the base href for the created document\n\t\t\t// so any parsed elements with URLs\n\t\t\t// are based on the document's URL (gh-2965)\n\t\t\tbase = context.createElement( \"base\" );\n\t\t\tbase.href = document.location.href;\n\t\t\tcontext.head.appendChild( base );\n\t\t} else {\n\t\t\tcontext = document;\n\t\t}\n\t}\n\n\tparsed = rsingleTag.exec( data );\n\tscripts = !keepScripts && [];\n\n\t// Single tag\n\tif ( parsed ) {\n\t\treturn [ context.createElement( parsed[ 1 ] ) ];\n\t}\n\n\tparsed = buildFragment( [ data ], context, scripts );\n\n\tif ( scripts && scripts.length ) {\n\t\tjQuery( scripts ).remove();\n\t}\n\n\treturn jQuery.merge( [], parsed.childNodes );\n};\n\n\n/**\n * Load a url into a page\n */\njQuery.fn.load = function( url, params, callback ) {\n\tvar selector, type, response,\n\t\tself = this,\n\t\toff = url.indexOf( \" \" );\n\n\tif ( off > -1 ) {\n\t\tselector = stripAndCollapse( url.slice( off ) );\n\t\turl = url.slice( 0, off );\n\t}\n\n\t// If it's a function\n\tif ( isFunction( params ) ) {\n\n\t\t// We assume that it's the callback\n\t\tcallback = params;\n\t\tparams = undefined;\n\n\t// Otherwise, build a param string\n\t} else if ( params && typeof params === \"object\" ) {\n\t\ttype = \"POST\";\n\t}\n\n\t// If we have elements to modify, make the request\n\tif ( self.length > 0 ) {\n\t\tjQuery.ajax( {\n\t\t\turl: url,\n\n\t\t\t// If \"type\" variable is undefined, then \"GET\" method will be used.\n\t\t\t// Make value of this field explicit since\n\t\t\t// user can override it through ajaxSetup method\n\t\t\ttype: type || \"GET\",\n\t\t\tdataType: \"html\",\n\t\t\tdata: params\n\t\t} ).done( function( responseText ) {\n\n\t\t\t// Save response for use in complete callback\n\t\t\tresponse = arguments;\n\n\t\t\tself.html( selector ?\n\n\t\t\t\t// If a selector was specified, locate the right elements in a dummy div\n\t\t\t\t// Exclude scripts to avoid IE 'Permission Denied' errors\n\t\t\t\tjQuery( \"<div>\" ).append( jQuery.parseHTML( responseText ) ).find( selector ) :\n\n\t\t\t\t// Otherwise use the full result\n\t\t\t\tresponseText );\n\n\t\t// If the request succeeds, this function gets \"data\", \"status\", \"jqXHR\"\n\t\t// but they are ignored because response was set above.\n\t\t// If it fails, this function gets \"jqXHR\", \"status\", \"error\"\n\t\t} ).always( callback && function( jqXHR, status ) {\n\t\t\tself.each( function() {\n\t\t\t\tcallback.apply( this, response || [ jqXHR.responseText, status, jqXHR ] );\n\t\t\t} );\n\t\t} );\n\t}\n\n\treturn this;\n};\n\n\n\n\n// Attach a bunch of functions for handling common AJAX events\njQuery.each( [\n\t\"ajaxStart\",\n\t\"ajaxStop\",\n\t\"ajaxComplete\",\n\t\"ajaxError\",\n\t\"ajaxSuccess\",\n\t\"ajaxSend\"\n], function( i, type ) {\n\tjQuery.fn[ type ] = function( fn ) {\n\t\treturn this.on( type, fn );\n\t};\n} );\n\n\n\n\njQuery.expr.pseudos.animated = function( elem ) {\n\treturn jQuery.grep( jQuery.timers, function( fn ) {\n\t\treturn elem === fn.elem;\n\t} ).length;\n};\n\n\n\n\njQuery.offset = {\n\tsetOffset: function( elem, options, i ) {\n\t\tvar curPosition, curLeft, curCSSTop, curTop, curOffset, curCSSLeft, calculatePosition,\n\t\t\tposition = jQuery.css( elem, \"position\" ),\n\t\t\tcurElem = jQuery( elem ),\n\t\t\tprops = {};\n\n\t\t// Set position first, in-case top/left are set even on static elem\n\t\tif ( position === \"static\" ) {\n\t\t\telem.style.position = \"relative\";\n\t\t}\n\n\t\tcurOffset = curElem.offset();\n\t\tcurCSSTop = jQuery.css( elem, \"top\" );\n\t\tcurCSSLeft = jQuery.css( elem, \"left\" );\n\t\tcalculatePosition = ( position === \"absolute\" || position === \"fixed\" ) &&\n\t\t\t( curCSSTop + curCSSLeft ).indexOf( \"auto\" ) > -1;\n\n\t\t// Need to be able to calculate position if either\n\t\t// top or left is auto and position is either absolute or fixed\n\t\tif ( calculatePosition ) {\n\t\t\tcurPosition = curElem.position();\n\t\t\tcurTop = curPosition.top;\n\t\t\tcurLeft = curPosition.left;\n\n\t\t} else {\n\t\t\tcurTop = parseFloat( curCSSTop ) || 0;\n\t\t\tcurLeft = parseFloat( curCSSLeft ) || 0;\n\t\t}\n\n\t\tif ( isFunction( options ) ) {\n\n\t\t\t// Use jQuery.extend here to allow modification of coordinates argument (gh-1848)\n\t\t\toptions = options.call( elem, i, jQuery.extend( {}, curOffset ) );\n\t\t}\n\n\t\tif ( options.top != null ) {\n\t\t\tprops.top = ( options.top - curOffset.top ) + curTop;\n\t\t}\n\t\tif ( options.left != null ) {\n\t\t\tprops.left = ( options.left - curOffset.left ) + curLeft;\n\t\t}\n\n\t\tif ( \"using\" in options ) {\n\t\t\toptions.using.call( elem, props );\n\n\t\t} else {\n\t\t\tcurElem.css( props );\n\t\t}\n\t}\n};\n\njQuery.fn.extend( {\n\n\t// offset() relates an element's border box to the document origin\n\toffset: function( options ) {\n\n\t\t// Preserve chaining for setter\n\t\tif ( arguments.length ) {\n\t\t\treturn options === undefined ?\n\t\t\t\tthis :\n\t\t\t\tthis.each( function( i ) {\n\t\t\t\t\tjQuery.offset.setOffset( this, options, i );\n\t\t\t\t} );\n\t\t}\n\n\t\tvar rect, win,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !elem ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Return zeros for disconnected and hidden (display: none) elements (gh-2310)\n\t\t// Support: IE <=11 only\n\t\t// Running getBoundingClientRect on a\n\t\t// disconnected node in IE throws an error\n\t\tif ( !elem.getClientRects().length ) {\n\t\t\treturn { top: 0, left: 0 };\n\t\t}\n\n\t\t// Get document-relative position by adding viewport scroll to viewport-relative gBCR\n\t\trect = elem.getBoundingClientRect();\n\t\twin = elem.ownerDocument.defaultView;\n\t\treturn {\n\t\t\ttop: rect.top + win.pageYOffset,\n\t\t\tleft: rect.left + win.pageXOffset\n\t\t};\n\t},\n\n\t// position() relates an element's margin box to its offset parent's padding box\n\t// This corresponds to the behavior of CSS absolute positioning\n\tposition: function() {\n\t\tif ( !this[ 0 ] ) {\n\t\t\treturn;\n\t\t}\n\n\t\tvar offsetParent, offset, doc,\n\t\t\telem = this[ 0 ],\n\t\t\tparentOffset = { top: 0, left: 0 };\n\n\t\t// position:fixed elements are offset from the viewport, which itself always has zero offset\n\t\tif ( jQuery.css( elem, \"position\" ) === \"fixed\" ) {\n\n\t\t\t// Assume position:fixed implies availability of getBoundingClientRect\n\t\t\toffset = elem.getBoundingClientRect();\n\n\t\t} else {\n\t\t\toffset = this.offset();\n\n\t\t\t// Account for the *real* offset parent, which can be the document or its root element\n\t\t\t// when a statically positioned element is identified\n\t\t\tdoc = elem.ownerDocument;\n\t\t\toffsetParent = elem.offsetParent || doc.documentElement;\n\t\t\twhile ( offsetParent &&\n\t\t\t\t( offsetParent === doc.body || offsetParent === doc.documentElement ) &&\n\t\t\t\tjQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\n\t\t\t\toffsetParent = offsetParent.parentNode;\n\t\t\t}\n\t\t\tif ( offsetParent && offsetParent !== elem && offsetParent.nodeType === 1 ) {\n\n\t\t\t\t// Incorporate borders into its offset, since they are outside its content origin\n\t\t\t\tparentOffset = jQuery( offsetParent ).offset();\n\t\t\t\tparentOffset.top += jQuery.css( offsetParent, \"borderTopWidth\", true );\n\t\t\t\tparentOffset.left += jQuery.css( offsetParent, \"borderLeftWidth\", true );\n\t\t\t}\n\t\t}\n\n\t\t// Subtract parent offsets and element margins\n\t\treturn {\n\t\t\ttop: offset.top - parentOffset.top - jQuery.css( elem, \"marginTop\", true ),\n\t\t\tleft: offset.left - parentOffset.left - jQuery.css( elem, \"marginLeft\", true )\n\t\t};\n\t},\n\n\t// This method will return documentElement in the following cases:\n\t// 1) For the element inside the iframe without offsetParent, this method will return\n\t//    documentElement of the parent window\n\t// 2) For the hidden or detached element\n\t// 3) For body or html element, i.e. in case of the html node - it will return itself\n\t//\n\t// but those exceptions were never presented as a real life use-cases\n\t// and might be considered as more preferable results.\n\t//\n\t// This logic, however, is not guaranteed and can change at any point in the future\n\toffsetParent: function() {\n\t\treturn this.map( function() {\n\t\t\tvar offsetParent = this.offsetParent;\n\n\t\t\twhile ( offsetParent && jQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\t\t\t\toffsetParent = offsetParent.offsetParent;\n\t\t\t}\n\n\t\t\treturn offsetParent || documentElement;\n\t\t} );\n\t}\n} );\n\n// Create scrollLeft and scrollTop methods\njQuery.each( { scrollLeft: \"pageXOffset\", scrollTop: \"pageYOffset\" }, function( method, prop ) {\n\tvar top = \"pageYOffset\" === prop;\n\n\tjQuery.fn[ method ] = function( val ) {\n\t\treturn access( this, function( elem, method, val ) {\n\n\t\t\t// Coalesce documents and windows\n\t\t\tvar win;\n\t\t\tif ( isWindow( elem ) ) {\n\t\t\t\twin = elem;\n\t\t\t} else if ( elem.nodeType === 9 ) {\n\t\t\t\twin = elem.defaultView;\n\t\t\t}\n\n\t\t\tif ( val === undefined ) {\n\t\t\t\treturn win ? win[ prop ] : elem[ method ];\n\t\t\t}\n\n\t\t\tif ( win ) {\n\t\t\t\twin.scrollTo(\n\t\t\t\t\t!top ? val : win.pageXOffset,\n\t\t\t\t\ttop ? val : win.pageYOffset\n\t\t\t\t);\n\n\t\t\t} else {\n\t\t\t\telem[ method ] = val;\n\t\t\t}\n\t\t}, method, val, arguments.length );\n\t};\n} );\n\n// Support: Safari <=7 - 9.1, Chrome <=37 - 49\n// Add the top/left cssHooks using jQuery.fn.position\n// Webkit bug: https://bugs.webkit.org/show_bug.cgi?id=29084\n// Blink bug: https://bugs.chromium.org/p/chromium/issues/detail?id=589347\n// getComputedStyle returns percent when specified for top/left/bottom/right;\n// rather than make the css module depend on the offset module, just check for it here\njQuery.each( [ \"top\", \"left\" ], function( i, prop ) {\n\tjQuery.cssHooks[ prop ] = addGetHookIf( support.pixelPosition,\n\t\tfunction( elem, computed ) {\n\t\t\tif ( computed ) {\n\t\t\t\tcomputed = curCSS( elem, prop );\n\n\t\t\t\t// If curCSS returns percentage, fallback to offset\n\t\t\t\treturn rnumnonpx.test( computed ) ?\n\t\t\t\t\tjQuery( elem ).position()[ prop ] + \"px\" :\n\t\t\t\t\tcomputed;\n\t\t\t}\n\t\t}\n\t);\n} );\n\n\n// Create innerHeight, innerWidth, height, width, outerHeight and outerWidth methods\njQuery.each( { Height: \"height\", Width: \"width\" }, function( name, type ) {\n\tjQuery.each( { padding: \"inner\" + name, content: type, \"\": \"outer\" + name },\n\t\tfunction( defaultExtra, funcName ) {\n\n\t\t// Margin is only for outerHeight, outerWidth\n\t\tjQuery.fn[ funcName ] = function( margin, value ) {\n\t\t\tvar chainable = arguments.length && ( defaultExtra || typeof margin !== \"boolean\" ),\n\t\t\t\textra = defaultExtra || ( margin === true || value === true ? \"margin\" : \"border\" );\n\n\t\t\treturn access( this, function( elem, type, value ) {\n\t\t\t\tvar doc;\n\n\t\t\t\tif ( isWindow( elem ) ) {\n\n\t\t\t\t\t// $( window ).outerWidth/Height return w/h including scrollbars (gh-1729)\n\t\t\t\t\treturn funcName.indexOf( \"outer\" ) === 0 ?\n\t\t\t\t\t\telem[ \"inner\" + name ] :\n\t\t\t\t\t\telem.document.documentElement[ \"client\" + name ];\n\t\t\t\t}\n\n\t\t\t\t// Get document width or height\n\t\t\t\tif ( elem.nodeType === 9 ) {\n\t\t\t\t\tdoc = elem.documentElement;\n\n\t\t\t\t\t// Either scroll[Width/Height] or offset[Width/Height] or client[Width/Height],\n\t\t\t\t\t// whichever is greatest\n\t\t\t\t\treturn Math.max(\n\t\t\t\t\t\telem.body[ \"scroll\" + name ], doc[ \"scroll\" + name ],\n\t\t\t\t\t\telem.body[ \"offset\" + name ], doc[ \"offset\" + name ],\n\t\t\t\t\t\tdoc[ \"client\" + name ]\n\t\t\t\t\t);\n\t\t\t\t}\n\n\t\t\t\treturn value === undefined ?\n\n\t\t\t\t\t// Get width or height on the element, requesting but not forcing parseFloat\n\t\t\t\t\tjQuery.css( elem, type, extra ) :\n\n\t\t\t\t\t// Set width or height on the element\n\t\t\t\t\tjQuery.style( elem, type, value, extra );\n\t\t\t}, type, chainable ? margin : undefined, chainable );\n\t\t};\n\t} );\n} );\n\n\njQuery.each( ( \"blur focus focusin focusout resize scroll click dblclick \" +\n\t\"mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave \" +\n\t\"change select submit keydown keypress keyup contextmenu\" ).split( \" \" ),\n\tfunction( i, name ) {\n\n\t// Handle event binding\n\tjQuery.fn[ name ] = function( data, fn ) {\n\t\treturn arguments.length > 0 ?\n\t\t\tthis.on( name, null, data, fn ) :\n\t\t\tthis.trigger( name );\n\t};\n} );\n\njQuery.fn.extend( {\n\thover: function( fnOver, fnOut ) {\n\t\treturn this.mouseenter( fnOver ).mouseleave( fnOut || fnOver );\n\t}\n} );\n\n\n\n\njQuery.fn.extend( {\n\n\tbind: function( types, data, fn ) {\n\t\treturn this.on( types, null, data, fn );\n\t},\n\tunbind: function( types, fn ) {\n\t\treturn this.off( types, null, fn );\n\t},\n\n\tdelegate: function( selector, types, data, fn ) {\n\t\treturn this.on( types, selector, data, fn );\n\t},\n\tundelegate: function( selector, types, fn ) {\n\n\t\t// ( namespace ) or ( selector, types [, fn] )\n\t\treturn arguments.length === 1 ?\n\t\t\tthis.off( selector, \"**\" ) :\n\t\t\tthis.off( types, selector || \"**\", fn );\n\t}\n} );\n\n// Bind a function to a context, optionally partially applying any\n// arguments.\n// jQuery.proxy is deprecated to promote standards (specifically Function#bind)\n// However, it is not slated for removal any time soon\njQuery.proxy = function( fn, context ) {\n\tvar tmp, args, proxy;\n\n\tif ( typeof context === \"string\" ) {\n\t\ttmp = fn[ context ];\n\t\tcontext = fn;\n\t\tfn = tmp;\n\t}\n\n\t// Quick check to determine if target is callable, in the spec\n\t// this throws a TypeError, but we will just return undefined.\n\tif ( !isFunction( fn ) ) {\n\t\treturn undefined;\n\t}\n\n\t// Simulated bind\n\targs = slice.call( arguments, 2 );\n\tproxy = function() {\n\t\treturn fn.apply( context || this, args.concat( slice.call( arguments ) ) );\n\t};\n\n\t// Set the guid of unique handler to the same of original handler, so it can be removed\n\tproxy.guid = fn.guid = fn.guid || jQuery.guid++;\n\n\treturn proxy;\n};\n\njQuery.holdReady = function( hold ) {\n\tif ( hold ) {\n\t\tjQuery.readyWait++;\n\t} else {\n\t\tjQuery.ready( true );\n\t}\n};\njQuery.isArray = Array.isArray;\njQuery.parseJSON = JSON.parse;\njQuery.nodeName = nodeName;\njQuery.isFunction = isFunction;\njQuery.isWindow = isWindow;\njQuery.camelCase = camelCase;\njQuery.type = toType;\n\njQuery.now = Date.now;\n\njQuery.isNumeric = function( obj ) {\n\n\t// As of jQuery 3.0, isNumeric is limited to\n\t// strings and numbers (primitives or objects)\n\t// that can be coerced to finite numbers (gh-2662)\n\tvar type = jQuery.type( obj );\n\treturn ( type === \"number\" || type === \"string\" ) &&\n\n\t\t// parseFloat NaNs numeric-cast false positives (\"\")\n\t\t// ...but misinterprets leading-number strings, particularly hex literals (\"0x...\")\n\t\t// subtraction forces infinities to NaN\n\t\t!isNaN( obj - parseFloat( obj ) );\n};\n\n\n\n\n// Register as a named AMD module, since jQuery can be concatenated with other\n// files that may use define, but not via a proper concatenation script that\n// understands anonymous AMD modules. A named AMD is safest and most robust\n// way to register. Lowercase jquery is used because AMD module names are\n// derived from file names, and jQuery is normally delivered in a lowercase\n// file name. Do this after creating the global so that if an AMD module wants\n// to call noConflict to hide this version of jQuery, it will work.\n\n// Note that for maximum portability, libraries that are not jQuery should\n// declare themselves as anonymous modules, and avoid setting a global if an\n// AMD loader is present. jQuery is a special case. For more information, see\n// https://github.com/jrburke/requirejs/wiki/Updating-existing-libraries#wiki-anon\n\nif ( typeof define === \"function\" && define.amd ) {\n\tdefine( \"jquery\", [], function() {\n\t\treturn jQuery;\n\t} );\n}\n\n\n\n\nvar\n\n\t// Map over jQuery in case of overwrite\n\t_jQuery = window.jQuery,\n\n\t// Map over the $ in case of overwrite\n\t_$ = window.$;\n\njQuery.noConflict = function( deep ) {\n\tif ( window.$ === jQuery ) {\n\t\twindow.$ = _$;\n\t}\n\n\tif ( deep && window.jQuery === jQuery ) {\n\t\twindow.jQuery = _jQuery;\n\t}\n\n\treturn jQuery;\n};\n\n// Expose jQuery and $ identifiers, even in AMD\n// (#7102#comment:10, https://github.com/jquery/jquery/pull/557)\n// and CommonJS for browser emulators (#13566)\nif ( !noGlobal ) {\n\twindow.jQuery = window.$ = jQuery;\n}\n\n\n\n\nreturn jQuery;\n} );\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/jquery/jquery.slim.js",
    "content": "/*!\n * jQuery JavaScript Library v3.4.1 -ajax,-ajax/jsonp,-ajax/load,-ajax/parseXML,-ajax/script,-ajax/var/location,-ajax/var/nonce,-ajax/var/rquery,-ajax/xhr,-manipulation/_evalUrl,-event/ajax,-effects,-effects/Tween,-effects/animatedSelector\n * https://jquery.com/\n *\n * Includes Sizzle.js\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://jquery.org/license\n *\n * Date: 2019-05-01T21:04Z\n */\n( function( global, factory ) {\n\n\t\"use strict\";\n\n\tif ( typeof module === \"object\" && typeof module.exports === \"object\" ) {\n\n\t\t// For CommonJS and CommonJS-like environments where a proper `window`\n\t\t// is present, execute the factory and get jQuery.\n\t\t// For environments that do not have a `window` with a `document`\n\t\t// (such as Node.js), expose a factory as module.exports.\n\t\t// This accentuates the need for the creation of a real `window`.\n\t\t// e.g. var jQuery = require(\"jquery\")(window);\n\t\t// See ticket #14549 for more info.\n\t\tmodule.exports = global.document ?\n\t\t\tfactory( global, true ) :\n\t\t\tfunction( w ) {\n\t\t\t\tif ( !w.document ) {\n\t\t\t\t\tthrow new Error( \"jQuery requires a window with a document\" );\n\t\t\t\t}\n\t\t\t\treturn factory( w );\n\t\t\t};\n\t} else {\n\t\tfactory( global );\n\t}\n\n// Pass this if window is not defined yet\n} )( typeof window !== \"undefined\" ? window : this, function( window, noGlobal ) {\n\n// Edge <= 12 - 13+, Firefox <=18 - 45+, IE 10 - 11, Safari 5.1 - 9+, iOS 6 - 9.1\n// throw exceptions when non-strict code (e.g., ASP.NET 4.5) accesses strict mode\n// arguments.callee.caller (trac-13335). But as of jQuery 3.0 (2016), strict mode should be common\n// enough that all such attempts are guarded in a try block.\n\"use strict\";\n\nvar arr = [];\n\nvar document = window.document;\n\nvar getProto = Object.getPrototypeOf;\n\nvar slice = arr.slice;\n\nvar concat = arr.concat;\n\nvar push = arr.push;\n\nvar indexOf = arr.indexOf;\n\nvar class2type = {};\n\nvar toString = class2type.toString;\n\nvar hasOwn = class2type.hasOwnProperty;\n\nvar fnToString = hasOwn.toString;\n\nvar ObjectFunctionString = fnToString.call( Object );\n\nvar support = {};\n\nvar isFunction = function isFunction( obj ) {\n\n      // Support: Chrome <=57, Firefox <=52\n      // In some browsers, typeof returns \"function\" for HTML <object> elements\n      // (i.e., `typeof document.createElement( \"object\" ) === \"function\"`).\n      // We don't want to classify *any* DOM node as a function.\n      return typeof obj === \"function\" && typeof obj.nodeType !== \"number\";\n  };\n\n\nvar isWindow = function isWindow( obj ) {\n\t\treturn obj != null && obj === obj.window;\n\t};\n\n\n\n\n\tvar preservedScriptAttributes = {\n\t\ttype: true,\n\t\tsrc: true,\n\t\tnonce: true,\n\t\tnoModule: true\n\t};\n\n\tfunction DOMEval( code, node, doc ) {\n\t\tdoc = doc || document;\n\n\t\tvar i, val,\n\t\t\tscript = doc.createElement( \"script\" );\n\n\t\tscript.text = code;\n\t\tif ( node ) {\n\t\t\tfor ( i in preservedScriptAttributes ) {\n\n\t\t\t\t// Support: Firefox 64+, Edge 18+\n\t\t\t\t// Some browsers don't support the \"nonce\" property on scripts.\n\t\t\t\t// On the other hand, just using `getAttribute` is not enough as\n\t\t\t\t// the `nonce` attribute is reset to an empty string whenever it\n\t\t\t\t// becomes browsing-context connected.\n\t\t\t\t// See https://github.com/whatwg/html/issues/2369\n\t\t\t\t// See https://html.spec.whatwg.org/#nonce-attributes\n\t\t\t\t// The `node.getAttribute` check was added for the sake of\n\t\t\t\t// `jQuery.globalEval` so that it can fake a nonce-containing node\n\t\t\t\t// via an object.\n\t\t\t\tval = node[ i ] || node.getAttribute && node.getAttribute( i );\n\t\t\t\tif ( val ) {\n\t\t\t\t\tscript.setAttribute( i, val );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tdoc.head.appendChild( script ).parentNode.removeChild( script );\n\t}\n\n\nfunction toType( obj ) {\n\tif ( obj == null ) {\n\t\treturn obj + \"\";\n\t}\n\n\t// Support: Android <=2.3 only (functionish RegExp)\n\treturn typeof obj === \"object\" || typeof obj === \"function\" ?\n\t\tclass2type[ toString.call( obj ) ] || \"object\" :\n\t\ttypeof obj;\n}\n/* global Symbol */\n// Defining this global in .eslintrc.json would create a danger of using the global\n// unguarded in another place, it seems safer to define global only for this module\n\n\n\nvar\n\tversion = \"3.4.1 -ajax,-ajax/jsonp,-ajax/load,-ajax/parseXML,-ajax/script,-ajax/var/location,-ajax/var/nonce,-ajax/var/rquery,-ajax/xhr,-manipulation/_evalUrl,-event/ajax,-effects,-effects/Tween,-effects/animatedSelector\",\n\n\t// Define a local copy of jQuery\n\tjQuery = function( selector, context ) {\n\n\t\t// The jQuery object is actually just the init constructor 'enhanced'\n\t\t// Need init if jQuery is called (just allow error to be thrown if not included)\n\t\treturn new jQuery.fn.init( selector, context );\n\t},\n\n\t// Support: Android <=4.0 only\n\t// Make sure we trim BOM and NBSP\n\trtrim = /^[\\s\\uFEFF\\xA0]+|[\\s\\uFEFF\\xA0]+$/g;\n\njQuery.fn = jQuery.prototype = {\n\n\t// The current version of jQuery being used\n\tjquery: version,\n\n\tconstructor: jQuery,\n\n\t// The default length of a jQuery object is 0\n\tlength: 0,\n\n\ttoArray: function() {\n\t\treturn slice.call( this );\n\t},\n\n\t// Get the Nth element in the matched element set OR\n\t// Get the whole matched element set as a clean array\n\tget: function( num ) {\n\n\t\t// Return all the elements in a clean array\n\t\tif ( num == null ) {\n\t\t\treturn slice.call( this );\n\t\t}\n\n\t\t// Return just the one element from the set\n\t\treturn num < 0 ? this[ num + this.length ] : this[ num ];\n\t},\n\n\t// Take an array of elements and push it onto the stack\n\t// (returning the new matched element set)\n\tpushStack: function( elems ) {\n\n\t\t// Build a new jQuery matched element set\n\t\tvar ret = jQuery.merge( this.constructor(), elems );\n\n\t\t// Add the old object onto the stack (as a reference)\n\t\tret.prevObject = this;\n\n\t\t// Return the newly-formed element set\n\t\treturn ret;\n\t},\n\n\t// Execute a callback for every element in the matched set.\n\teach: function( callback ) {\n\t\treturn jQuery.each( this, callback );\n\t},\n\n\tmap: function( callback ) {\n\t\treturn this.pushStack( jQuery.map( this, function( elem, i ) {\n\t\t\treturn callback.call( elem, i, elem );\n\t\t} ) );\n\t},\n\n\tslice: function() {\n\t\treturn this.pushStack( slice.apply( this, arguments ) );\n\t},\n\n\tfirst: function() {\n\t\treturn this.eq( 0 );\n\t},\n\n\tlast: function() {\n\t\treturn this.eq( -1 );\n\t},\n\n\teq: function( i ) {\n\t\tvar len = this.length,\n\t\t\tj = +i + ( i < 0 ? len : 0 );\n\t\treturn this.pushStack( j >= 0 && j < len ? [ this[ j ] ] : [] );\n\t},\n\n\tend: function() {\n\t\treturn this.prevObject || this.constructor();\n\t},\n\n\t// For internal use only.\n\t// Behaves like an Array's method, not like a jQuery method.\n\tpush: push,\n\tsort: arr.sort,\n\tsplice: arr.splice\n};\n\njQuery.extend = jQuery.fn.extend = function() {\n\tvar options, name, src, copy, copyIsArray, clone,\n\t\ttarget = arguments[ 0 ] || {},\n\t\ti = 1,\n\t\tlength = arguments.length,\n\t\tdeep = false;\n\n\t// Handle a deep copy situation\n\tif ( typeof target === \"boolean\" ) {\n\t\tdeep = target;\n\n\t\t// Skip the boolean and the target\n\t\ttarget = arguments[ i ] || {};\n\t\ti++;\n\t}\n\n\t// Handle case when target is a string or something (possible in deep copy)\n\tif ( typeof target !== \"object\" && !isFunction( target ) ) {\n\t\ttarget = {};\n\t}\n\n\t// Extend jQuery itself if only one argument is passed\n\tif ( i === length ) {\n\t\ttarget = this;\n\t\ti--;\n\t}\n\n\tfor ( ; i < length; i++ ) {\n\n\t\t// Only deal with non-null/undefined values\n\t\tif ( ( options = arguments[ i ] ) != null ) {\n\n\t\t\t// Extend the base object\n\t\t\tfor ( name in options ) {\n\t\t\t\tcopy = options[ name ];\n\n\t\t\t\t// Prevent Object.prototype pollution\n\t\t\t\t// Prevent never-ending loop\n\t\t\t\tif ( name === \"__proto__\" || target === copy ) {\n\t\t\t\t\tcontinue;\n\t\t\t\t}\n\n\t\t\t\t// Recurse if we're merging plain objects or arrays\n\t\t\t\tif ( deep && copy && ( jQuery.isPlainObject( copy ) ||\n\t\t\t\t\t( copyIsArray = Array.isArray( copy ) ) ) ) {\n\t\t\t\t\tsrc = target[ name ];\n\n\t\t\t\t\t// Ensure proper type for the source value\n\t\t\t\t\tif ( copyIsArray && !Array.isArray( src ) ) {\n\t\t\t\t\t\tclone = [];\n\t\t\t\t\t} else if ( !copyIsArray && !jQuery.isPlainObject( src ) ) {\n\t\t\t\t\t\tclone = {};\n\t\t\t\t\t} else {\n\t\t\t\t\t\tclone = src;\n\t\t\t\t\t}\n\t\t\t\t\tcopyIsArray = false;\n\n\t\t\t\t\t// Never move original objects, clone them\n\t\t\t\t\ttarget[ name ] = jQuery.extend( deep, clone, copy );\n\n\t\t\t\t// Don't bring in undefined values\n\t\t\t\t} else if ( copy !== undefined ) {\n\t\t\t\t\ttarget[ name ] = copy;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Return the modified object\n\treturn target;\n};\n\njQuery.extend( {\n\n\t// Unique for each copy of jQuery on the page\n\texpando: \"jQuery\" + ( version + Math.random() ).replace( /\\D/g, \"\" ),\n\n\t// Assume jQuery is ready without the ready module\n\tisReady: true,\n\n\terror: function( msg ) {\n\t\tthrow new Error( msg );\n\t},\n\n\tnoop: function() {},\n\n\tisPlainObject: function( obj ) {\n\t\tvar proto, Ctor;\n\n\t\t// Detect obvious negatives\n\t\t// Use toString instead of jQuery.type to catch host objects\n\t\tif ( !obj || toString.call( obj ) !== \"[object Object]\" ) {\n\t\t\treturn false;\n\t\t}\n\n\t\tproto = getProto( obj );\n\n\t\t// Objects with no prototype (e.g., `Object.create( null )`) are plain\n\t\tif ( !proto ) {\n\t\t\treturn true;\n\t\t}\n\n\t\t// Objects with prototype are plain iff they were constructed by a global Object function\n\t\tCtor = hasOwn.call( proto, \"constructor\" ) && proto.constructor;\n\t\treturn typeof Ctor === \"function\" && fnToString.call( Ctor ) === ObjectFunctionString;\n\t},\n\n\tisEmptyObject: function( obj ) {\n\t\tvar name;\n\n\t\tfor ( name in obj ) {\n\t\t\treturn false;\n\t\t}\n\t\treturn true;\n\t},\n\n\t// Evaluates a script in a global context\n\tglobalEval: function( code, options ) {\n\t\tDOMEval( code, { nonce: options && options.nonce } );\n\t},\n\n\teach: function( obj, callback ) {\n\t\tvar length, i = 0;\n\n\t\tif ( isArrayLike( obj ) ) {\n\t\t\tlength = obj.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t} else {\n\t\t\tfor ( i in obj ) {\n\t\t\t\tif ( callback.call( obj[ i ], i, obj[ i ] ) === false ) {\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn obj;\n\t},\n\n\t// Support: Android <=4.0 only\n\ttrim: function( text ) {\n\t\treturn text == null ?\n\t\t\t\"\" :\n\t\t\t( text + \"\" ).replace( rtrim, \"\" );\n\t},\n\n\t// results is for internal usage only\n\tmakeArray: function( arr, results ) {\n\t\tvar ret = results || [];\n\n\t\tif ( arr != null ) {\n\t\t\tif ( isArrayLike( Object( arr ) ) ) {\n\t\t\t\tjQuery.merge( ret,\n\t\t\t\t\ttypeof arr === \"string\" ?\n\t\t\t\t\t[ arr ] : arr\n\t\t\t\t);\n\t\t\t} else {\n\t\t\t\tpush.call( ret, arr );\n\t\t\t}\n\t\t}\n\n\t\treturn ret;\n\t},\n\n\tinArray: function( elem, arr, i ) {\n\t\treturn arr == null ? -1 : indexOf.call( arr, elem, i );\n\t},\n\n\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t// push.apply(_, arraylike) throws on ancient WebKit\n\tmerge: function( first, second ) {\n\t\tvar len = +second.length,\n\t\t\tj = 0,\n\t\t\ti = first.length;\n\n\t\tfor ( ; j < len; j++ ) {\n\t\t\tfirst[ i++ ] = second[ j ];\n\t\t}\n\n\t\tfirst.length = i;\n\n\t\treturn first;\n\t},\n\n\tgrep: function( elems, callback, invert ) {\n\t\tvar callbackInverse,\n\t\t\tmatches = [],\n\t\t\ti = 0,\n\t\t\tlength = elems.length,\n\t\t\tcallbackExpect = !invert;\n\n\t\t// Go through the array, only saving the items\n\t\t// that pass the validator function\n\t\tfor ( ; i < length; i++ ) {\n\t\t\tcallbackInverse = !callback( elems[ i ], i );\n\t\t\tif ( callbackInverse !== callbackExpect ) {\n\t\t\t\tmatches.push( elems[ i ] );\n\t\t\t}\n\t\t}\n\n\t\treturn matches;\n\t},\n\n\t// arg is for internal usage only\n\tmap: function( elems, callback, arg ) {\n\t\tvar length, value,\n\t\t\ti = 0,\n\t\t\tret = [];\n\n\t\t// Go through the array, translating each of the items to their new values\n\t\tif ( isArrayLike( elems ) ) {\n\t\t\tlength = elems.length;\n\t\t\tfor ( ; i < length; i++ ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Go through every key on the object,\n\t\t} else {\n\t\t\tfor ( i in elems ) {\n\t\t\t\tvalue = callback( elems[ i ], i, arg );\n\n\t\t\t\tif ( value != null ) {\n\t\t\t\t\tret.push( value );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Flatten any nested arrays\n\t\treturn concat.apply( [], ret );\n\t},\n\n\t// A global GUID counter for objects\n\tguid: 1,\n\n\t// jQuery.support is not used in Core but other projects attach their\n\t// properties to it so it needs to exist.\n\tsupport: support\n} );\n\nif ( typeof Symbol === \"function\" ) {\n\tjQuery.fn[ Symbol.iterator ] = arr[ Symbol.iterator ];\n}\n\n// Populate the class2type map\njQuery.each( \"Boolean Number String Function Array Date RegExp Object Error Symbol\".split( \" \" ),\nfunction( i, name ) {\n\tclass2type[ \"[object \" + name + \"]\" ] = name.toLowerCase();\n} );\n\nfunction isArrayLike( obj ) {\n\n\t// Support: real iOS 8.2 only (not reproducible in simulator)\n\t// `in` check used to prevent JIT error (gh-2145)\n\t// hasOwn isn't used here due to false negatives\n\t// regarding Nodelist length in IE\n\tvar length = !!obj && \"length\" in obj && obj.length,\n\t\ttype = toType( obj );\n\n\tif ( isFunction( obj ) || isWindow( obj ) ) {\n\t\treturn false;\n\t}\n\n\treturn type === \"array\" || length === 0 ||\n\t\ttypeof length === \"number\" && length > 0 && ( length - 1 ) in obj;\n}\nvar Sizzle =\n/*!\n * Sizzle CSS Selector Engine v2.3.4\n * https://sizzlejs.com/\n *\n * Copyright JS Foundation and other contributors\n * Released under the MIT license\n * https://js.foundation/\n *\n * Date: 2019-04-08\n */\n(function( window ) {\n\nvar i,\n\tsupport,\n\tExpr,\n\tgetText,\n\tisXML,\n\ttokenize,\n\tcompile,\n\tselect,\n\toutermostContext,\n\tsortInput,\n\thasDuplicate,\n\n\t// Local document vars\n\tsetDocument,\n\tdocument,\n\tdocElem,\n\tdocumentIsHTML,\n\trbuggyQSA,\n\trbuggyMatches,\n\tmatches,\n\tcontains,\n\n\t// Instance-specific data\n\texpando = \"sizzle\" + 1 * new Date(),\n\tpreferredDoc = window.document,\n\tdirruns = 0,\n\tdone = 0,\n\tclassCache = createCache(),\n\ttokenCache = createCache(),\n\tcompilerCache = createCache(),\n\tnonnativeSelectorCache = createCache(),\n\tsortOrder = function( a, b ) {\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t}\n\t\treturn 0;\n\t},\n\n\t// Instance methods\n\thasOwn = ({}).hasOwnProperty,\n\tarr = [],\n\tpop = arr.pop,\n\tpush_native = arr.push,\n\tpush = arr.push,\n\tslice = arr.slice,\n\t// Use a stripped-down indexOf as it's faster than native\n\t// https://jsperf.com/thor-indexof-vs-for/5\n\tindexOf = function( list, elem ) {\n\t\tvar i = 0,\n\t\t\tlen = list.length;\n\t\tfor ( ; i < len; i++ ) {\n\t\t\tif ( list[i] === elem ) {\n\t\t\t\treturn i;\n\t\t\t}\n\t\t}\n\t\treturn -1;\n\t},\n\n\tbooleans = \"checked|selected|async|autofocus|autoplay|controls|defer|disabled|hidden|ismap|loop|multiple|open|readonly|required|scoped\",\n\n\t// Regular expressions\n\n\t// http://www.w3.org/TR/css3-selectors/#whitespace\n\twhitespace = \"[\\\\x20\\\\t\\\\r\\\\n\\\\f]\",\n\n\t// http://www.w3.org/TR/CSS21/syndata.html#value-def-identifier\n\tidentifier = \"(?:\\\\\\\\.|[\\\\w-]|[^\\0-\\\\xa0])+\",\n\n\t// Attribute selectors: http://www.w3.org/TR/selectors/#attribute-selectors\n\tattributes = \"\\\\[\" + whitespace + \"*(\" + identifier + \")(?:\" + whitespace +\n\t\t// Operator (capture 2)\n\t\t\"*([*^$|!~]?=)\" + whitespace +\n\t\t// \"Attribute values must be CSS identifiers [capture 5] or strings [capture 3 or capture 4]\"\n\t\t\"*(?:'((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\"|(\" + identifier + \"))|)\" + whitespace +\n\t\t\"*\\\\]\",\n\n\tpseudos = \":(\" + identifier + \")(?:\\\\((\" +\n\t\t// To reduce the number of selectors needing tokenize in the preFilter, prefer arguments:\n\t\t// 1. quoted (capture 3; capture 4 or capture 5)\n\t\t\"('((?:\\\\\\\\.|[^\\\\\\\\'])*)'|\\\"((?:\\\\\\\\.|[^\\\\\\\\\\\"])*)\\\")|\" +\n\t\t// 2. simple (capture 6)\n\t\t\"((?:\\\\\\\\.|[^\\\\\\\\()[\\\\]]|\" + attributes + \")*)|\" +\n\t\t// 3. anything else (capture 2)\n\t\t\".*\" +\n\t\t\")\\\\)|)\",\n\n\t// Leading and non-escaped trailing whitespace, capturing some non-whitespace characters preceding the latter\n\trwhitespace = new RegExp( whitespace + \"+\", \"g\" ),\n\trtrim = new RegExp( \"^\" + whitespace + \"+|((?:^|[^\\\\\\\\])(?:\\\\\\\\.)*)\" + whitespace + \"+$\", \"g\" ),\n\n\trcomma = new RegExp( \"^\" + whitespace + \"*,\" + whitespace + \"*\" ),\n\trcombinators = new RegExp( \"^\" + whitespace + \"*([>+~]|\" + whitespace + \")\" + whitespace + \"*\" ),\n\trdescend = new RegExp( whitespace + \"|>\" ),\n\n\trpseudo = new RegExp( pseudos ),\n\tridentifier = new RegExp( \"^\" + identifier + \"$\" ),\n\n\tmatchExpr = {\n\t\t\"ID\": new RegExp( \"^#(\" + identifier + \")\" ),\n\t\t\"CLASS\": new RegExp( \"^\\\\.(\" + identifier + \")\" ),\n\t\t\"TAG\": new RegExp( \"^(\" + identifier + \"|[*])\" ),\n\t\t\"ATTR\": new RegExp( \"^\" + attributes ),\n\t\t\"PSEUDO\": new RegExp( \"^\" + pseudos ),\n\t\t\"CHILD\": new RegExp( \"^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\\\(\" + whitespace +\n\t\t\t\"*(even|odd|(([+-]|)(\\\\d*)n|)\" + whitespace + \"*(?:([+-]|)\" + whitespace +\n\t\t\t\"*(\\\\d+)|))\" + whitespace + \"*\\\\)|)\", \"i\" ),\n\t\t\"bool\": new RegExp( \"^(?:\" + booleans + \")$\", \"i\" ),\n\t\t// For use in libraries implementing .is()\n\t\t// We use this for POS matching in `select`\n\t\t\"needsContext\": new RegExp( \"^\" + whitespace + \"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\\\(\" +\n\t\t\twhitespace + \"*((?:-\\\\d)?\\\\d*)\" + whitespace + \"*\\\\)|)(?=[^-]|$)\", \"i\" )\n\t},\n\n\trhtml = /HTML$/i,\n\trinputs = /^(?:input|select|textarea|button)$/i,\n\trheader = /^h\\d$/i,\n\n\trnative = /^[^{]+\\{\\s*\\[native \\w/,\n\n\t// Easily-parseable/retrievable ID or TAG or CLASS selectors\n\trquickExpr = /^(?:#([\\w-]+)|(\\w+)|\\.([\\w-]+))$/,\n\n\trsibling = /[+~]/,\n\n\t// CSS escapes\n\t// http://www.w3.org/TR/CSS21/syndata.html#escaped-characters\n\trunescape = new RegExp( \"\\\\\\\\([\\\\da-f]{1,6}\" + whitespace + \"?|(\" + whitespace + \")|.)\", \"ig\" ),\n\tfunescape = function( _, escaped, escapedWhitespace ) {\n\t\tvar high = \"0x\" + escaped - 0x10000;\n\t\t// NaN means non-codepoint\n\t\t// Support: Firefox<24\n\t\t// Workaround erroneous numeric interpretation of +\"0x\"\n\t\treturn high !== high || escapedWhitespace ?\n\t\t\tescaped :\n\t\t\thigh < 0 ?\n\t\t\t\t// BMP codepoint\n\t\t\t\tString.fromCharCode( high + 0x10000 ) :\n\t\t\t\t// Supplemental Plane codepoint (surrogate pair)\n\t\t\t\tString.fromCharCode( high >> 10 | 0xD800, high & 0x3FF | 0xDC00 );\n\t},\n\n\t// CSS string/identifier serialization\n\t// https://drafts.csswg.org/cssom/#common-serializing-idioms\n\trcssescape = /([\\0-\\x1f\\x7f]|^-?\\d)|^-$|[^\\0-\\x1f\\x7f-\\uFFFF\\w-]/g,\n\tfcssescape = function( ch, asCodePoint ) {\n\t\tif ( asCodePoint ) {\n\n\t\t\t// U+0000 NULL becomes U+FFFD REPLACEMENT CHARACTER\n\t\t\tif ( ch === \"\\0\" ) {\n\t\t\t\treturn \"\\uFFFD\";\n\t\t\t}\n\n\t\t\t// Control characters and (dependent upon position) numbers get escaped as code points\n\t\t\treturn ch.slice( 0, -1 ) + \"\\\\\" + ch.charCodeAt( ch.length - 1 ).toString( 16 ) + \" \";\n\t\t}\n\n\t\t// Other potentially-special ASCII characters get backslash-escaped\n\t\treturn \"\\\\\" + ch;\n\t},\n\n\t// Used for iframes\n\t// See setDocument()\n\t// Removing the function wrapper causes a \"Permission Denied\"\n\t// error in IE\n\tunloadHandler = function() {\n\t\tsetDocument();\n\t},\n\n\tinDisabledFieldset = addCombinator(\n\t\tfunction( elem ) {\n\t\t\treturn elem.disabled === true && elem.nodeName.toLowerCase() === \"fieldset\";\n\t\t},\n\t\t{ dir: \"parentNode\", next: \"legend\" }\n\t);\n\n// Optimize for push.apply( _, NodeList )\ntry {\n\tpush.apply(\n\t\t(arr = slice.call( preferredDoc.childNodes )),\n\t\tpreferredDoc.childNodes\n\t);\n\t// Support: Android<4.0\n\t// Detect silently failing push.apply\n\tarr[ preferredDoc.childNodes.length ].nodeType;\n} catch ( e ) {\n\tpush = { apply: arr.length ?\n\n\t\t// Leverage slice if possible\n\t\tfunction( target, els ) {\n\t\t\tpush_native.apply( target, slice.call(els) );\n\t\t} :\n\n\t\t// Support: IE<9\n\t\t// Otherwise append directly\n\t\tfunction( target, els ) {\n\t\t\tvar j = target.length,\n\t\t\t\ti = 0;\n\t\t\t// Can't trust NodeList.length\n\t\t\twhile ( (target[j++] = els[i++]) ) {}\n\t\t\ttarget.length = j - 1;\n\t\t}\n\t};\n}\n\nfunction Sizzle( selector, context, results, seed ) {\n\tvar m, i, elem, nid, match, groups, newSelector,\n\t\tnewContext = context && context.ownerDocument,\n\n\t\t// nodeType defaults to 9, since context defaults to document\n\t\tnodeType = context ? context.nodeType : 9;\n\n\tresults = results || [];\n\n\t// Return early from calls with invalid selector or context\n\tif ( typeof selector !== \"string\" || !selector ||\n\t\tnodeType !== 1 && nodeType !== 9 && nodeType !== 11 ) {\n\n\t\treturn results;\n\t}\n\n\t// Try to shortcut find operations (as opposed to filters) in HTML documents\n\tif ( !seed ) {\n\n\t\tif ( ( context ? context.ownerDocument || context : preferredDoc ) !== document ) {\n\t\t\tsetDocument( context );\n\t\t}\n\t\tcontext = context || document;\n\n\t\tif ( documentIsHTML ) {\n\n\t\t\t// If the selector is sufficiently simple, try using a \"get*By*\" DOM method\n\t\t\t// (excepting DocumentFragment context, where the methods don't exist)\n\t\t\tif ( nodeType !== 11 && (match = rquickExpr.exec( selector )) ) {\n\n\t\t\t\t// ID selector\n\t\t\t\tif ( (m = match[1]) ) {\n\n\t\t\t\t\t// Document context\n\t\t\t\t\tif ( nodeType === 9 ) {\n\t\t\t\t\t\tif ( (elem = context.getElementById( m )) ) {\n\n\t\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\t\tif ( elem.id === m ) {\n\t\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t// Element context\n\t\t\t\t\t} else {\n\n\t\t\t\t\t\t// Support: IE, Opera, Webkit\n\t\t\t\t\t\t// TODO: identify versions\n\t\t\t\t\t\t// getElementById can match elements by name instead of ID\n\t\t\t\t\t\tif ( newContext && (elem = newContext.getElementById( m )) &&\n\t\t\t\t\t\t\tcontains( context, elem ) &&\n\t\t\t\t\t\t\telem.id === m ) {\n\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\treturn results;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t// Type selector\n\t\t\t\t} else if ( match[2] ) {\n\t\t\t\t\tpush.apply( results, context.getElementsByTagName( selector ) );\n\t\t\t\t\treturn results;\n\n\t\t\t\t// Class selector\n\t\t\t\t} else if ( (m = match[3]) && support.getElementsByClassName &&\n\t\t\t\t\tcontext.getElementsByClassName ) {\n\n\t\t\t\t\tpush.apply( results, context.getElementsByClassName( m ) );\n\t\t\t\t\treturn results;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Take advantage of querySelectorAll\n\t\t\tif ( support.qsa &&\n\t\t\t\t!nonnativeSelectorCache[ selector + \" \" ] &&\n\t\t\t\t(!rbuggyQSA || !rbuggyQSA.test( selector )) &&\n\n\t\t\t\t// Support: IE 8 only\n\t\t\t\t// Exclude object elements\n\t\t\t\t(nodeType !== 1 || context.nodeName.toLowerCase() !== \"object\") ) {\n\n\t\t\t\tnewSelector = selector;\n\t\t\t\tnewContext = context;\n\n\t\t\t\t// qSA considers elements outside a scoping root when evaluating child or\n\t\t\t\t// descendant combinators, which is not what we want.\n\t\t\t\t// In such cases, we work around the behavior by prefixing every selector in the\n\t\t\t\t// list with an ID selector referencing the scope context.\n\t\t\t\t// Thanks to Andrew Dupont for this technique.\n\t\t\t\tif ( nodeType === 1 && rdescend.test( selector ) ) {\n\n\t\t\t\t\t// Capture the context ID, setting it first if necessary\n\t\t\t\t\tif ( (nid = context.getAttribute( \"id\" )) ) {\n\t\t\t\t\t\tnid = nid.replace( rcssescape, fcssescape );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tcontext.setAttribute( \"id\", (nid = expando) );\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prefix every selector in the list\n\t\t\t\t\tgroups = tokenize( selector );\n\t\t\t\t\ti = groups.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tgroups[i] = \"#\" + nid + \" \" + toSelector( groups[i] );\n\t\t\t\t\t}\n\t\t\t\t\tnewSelector = groups.join( \",\" );\n\n\t\t\t\t\t// Expand context for sibling selectors\n\t\t\t\t\tnewContext = rsibling.test( selector ) && testContext( context.parentNode ) ||\n\t\t\t\t\t\tcontext;\n\t\t\t\t}\n\n\t\t\t\ttry {\n\t\t\t\t\tpush.apply( results,\n\t\t\t\t\t\tnewContext.querySelectorAll( newSelector )\n\t\t\t\t\t);\n\t\t\t\t\treturn results;\n\t\t\t\t} catch ( qsaError ) {\n\t\t\t\t\tnonnativeSelectorCache( selector, true );\n\t\t\t\t} finally {\n\t\t\t\t\tif ( nid === expando ) {\n\t\t\t\t\t\tcontext.removeAttribute( \"id\" );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// All others\n\treturn select( selector.replace( rtrim, \"$1\" ), context, results, seed );\n}\n\n/**\n * Create key-value caches of limited size\n * @returns {function(string, object)} Returns the Object data after storing it on itself with\n *\tproperty name the (space-suffixed) string and (if the cache is larger than Expr.cacheLength)\n *\tdeleting the oldest entry\n */\nfunction createCache() {\n\tvar keys = [];\n\n\tfunction cache( key, value ) {\n\t\t// Use (key + \" \") to avoid collision with native prototype properties (see Issue #157)\n\t\tif ( keys.push( key + \" \" ) > Expr.cacheLength ) {\n\t\t\t// Only keep the most recent entries\n\t\t\tdelete cache[ keys.shift() ];\n\t\t}\n\t\treturn (cache[ key + \" \" ] = value);\n\t}\n\treturn cache;\n}\n\n/**\n * Mark a function for special use by Sizzle\n * @param {Function} fn The function to mark\n */\nfunction markFunction( fn ) {\n\tfn[ expando ] = true;\n\treturn fn;\n}\n\n/**\n * Support testing using an element\n * @param {Function} fn Passed the created element and returns a boolean result\n */\nfunction assert( fn ) {\n\tvar el = document.createElement(\"fieldset\");\n\n\ttry {\n\t\treturn !!fn( el );\n\t} catch (e) {\n\t\treturn false;\n\t} finally {\n\t\t// Remove from its parent by default\n\t\tif ( el.parentNode ) {\n\t\t\tel.parentNode.removeChild( el );\n\t\t}\n\t\t// release memory in IE\n\t\tel = null;\n\t}\n}\n\n/**\n * Adds the same handler for all of the specified attrs\n * @param {String} attrs Pipe-separated list of attributes\n * @param {Function} handler The method that will be applied\n */\nfunction addHandle( attrs, handler ) {\n\tvar arr = attrs.split(\"|\"),\n\t\ti = arr.length;\n\n\twhile ( i-- ) {\n\t\tExpr.attrHandle[ arr[i] ] = handler;\n\t}\n}\n\n/**\n * Checks document order of two siblings\n * @param {Element} a\n * @param {Element} b\n * @returns {Number} Returns less than 0 if a precedes b, greater than 0 if a follows b\n */\nfunction siblingCheck( a, b ) {\n\tvar cur = b && a,\n\t\tdiff = cur && a.nodeType === 1 && b.nodeType === 1 &&\n\t\t\ta.sourceIndex - b.sourceIndex;\n\n\t// Use IE sourceIndex if available on both nodes\n\tif ( diff ) {\n\t\treturn diff;\n\t}\n\n\t// Check if b follows a\n\tif ( cur ) {\n\t\twhile ( (cur = cur.nextSibling) ) {\n\t\t\tif ( cur === b ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t}\n\n\treturn a ? 1 : -1;\n}\n\n/**\n * Returns a function to use in pseudos for input types\n * @param {String} type\n */\nfunction createInputPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn name === \"input\" && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for buttons\n * @param {String} type\n */\nfunction createButtonPseudo( type ) {\n\treturn function( elem ) {\n\t\tvar name = elem.nodeName.toLowerCase();\n\t\treturn (name === \"input\" || name === \"button\") && elem.type === type;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for :enabled/:disabled\n * @param {Boolean} disabled true for :disabled; false for :enabled\n */\nfunction createDisabledPseudo( disabled ) {\n\n\t// Known :disabled false positives: fieldset[disabled] > legend:nth-of-type(n+2) :can-disable\n\treturn function( elem ) {\n\n\t\t// Only certain elements can match :enabled or :disabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-enabled\n\t\t// https://html.spec.whatwg.org/multipage/scripting.html#selector-disabled\n\t\tif ( \"form\" in elem ) {\n\n\t\t\t// Check for inherited disabledness on relevant non-disabled elements:\n\t\t\t// * listed form-associated elements in a disabled fieldset\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#category-listed\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-fe-disabled\n\t\t\t// * option elements in a disabled optgroup\n\t\t\t//   https://html.spec.whatwg.org/multipage/forms.html#concept-option-disabled\n\t\t\t// All such elements have a \"form\" property.\n\t\t\tif ( elem.parentNode && elem.disabled === false ) {\n\n\t\t\t\t// Option elements defer to a parent optgroup if present\n\t\t\t\tif ( \"label\" in elem ) {\n\t\t\t\t\tif ( \"label\" in elem.parentNode ) {\n\t\t\t\t\t\treturn elem.parentNode.disabled === disabled;\n\t\t\t\t\t} else {\n\t\t\t\t\t\treturn elem.disabled === disabled;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Support: IE 6 - 11\n\t\t\t\t// Use the isDisabled shortcut property to check for disabled fieldset ancestors\n\t\t\t\treturn elem.isDisabled === disabled ||\n\n\t\t\t\t\t// Where there is no isDisabled, check manually\n\t\t\t\t\t/* jshint -W018 */\n\t\t\t\t\telem.isDisabled !== !disabled &&\n\t\t\t\t\t\tinDisabledFieldset( elem ) === disabled;\n\t\t\t}\n\n\t\t\treturn elem.disabled === disabled;\n\n\t\t// Try to winnow out elements that can't be disabled before trusting the disabled property.\n\t\t// Some victims get caught in our net (label, legend, menu, track), but it shouldn't\n\t\t// even exist on them, let alone have a boolean value.\n\t\t} else if ( \"label\" in elem ) {\n\t\t\treturn elem.disabled === disabled;\n\t\t}\n\n\t\t// Remaining elements are neither :enabled nor :disabled\n\t\treturn false;\n\t};\n}\n\n/**\n * Returns a function to use in pseudos for positionals\n * @param {Function} fn\n */\nfunction createPositionalPseudo( fn ) {\n\treturn markFunction(function( argument ) {\n\t\targument = +argument;\n\t\treturn markFunction(function( seed, matches ) {\n\t\t\tvar j,\n\t\t\t\tmatchIndexes = fn( [], seed.length, argument ),\n\t\t\t\ti = matchIndexes.length;\n\n\t\t\t// Match elements found at the specified indexes\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( seed[ (j = matchIndexes[i]) ] ) {\n\t\t\t\t\tseed[j] = !(matches[j] = seed[j]);\n\t\t\t\t}\n\t\t\t}\n\t\t});\n\t});\n}\n\n/**\n * Checks a node for validity as a Sizzle context\n * @param {Element|Object=} context\n * @returns {Element|Object|Boolean} The input node if acceptable, otherwise a falsy value\n */\nfunction testContext( context ) {\n\treturn context && typeof context.getElementsByTagName !== \"undefined\" && context;\n}\n\n// Expose support vars for convenience\nsupport = Sizzle.support = {};\n\n/**\n * Detects XML nodes\n * @param {Element|Object} elem An element or a document\n * @returns {Boolean} True iff elem is a non-HTML XML node\n */\nisXML = Sizzle.isXML = function( elem ) {\n\tvar namespace = elem.namespaceURI,\n\t\tdocElem = (elem.ownerDocument || elem).documentElement;\n\n\t// Support: IE <=8\n\t// Assume HTML when documentElement doesn't yet exist, such as inside loading iframes\n\t// https://bugs.jquery.com/ticket/4833\n\treturn !rhtml.test( namespace || docElem && docElem.nodeName || \"HTML\" );\n};\n\n/**\n * Sets document-related variables once based on the current document\n * @param {Element|Object} [doc] An element or document object to use to set the document\n * @returns {Object} Returns the current document\n */\nsetDocument = Sizzle.setDocument = function( node ) {\n\tvar hasCompare, subWindow,\n\t\tdoc = node ? node.ownerDocument || node : preferredDoc;\n\n\t// Return early if doc is invalid or already selected\n\tif ( doc === document || doc.nodeType !== 9 || !doc.documentElement ) {\n\t\treturn document;\n\t}\n\n\t// Update global variables\n\tdocument = doc;\n\tdocElem = document.documentElement;\n\tdocumentIsHTML = !isXML( document );\n\n\t// Support: IE 9-11, Edge\n\t// Accessing iframe documents after unload throws \"permission denied\" errors (jQuery #13936)\n\tif ( preferredDoc !== document &&\n\t\t(subWindow = document.defaultView) && subWindow.top !== subWindow ) {\n\n\t\t// Support: IE 11, Edge\n\t\tif ( subWindow.addEventListener ) {\n\t\t\tsubWindow.addEventListener( \"unload\", unloadHandler, false );\n\n\t\t// Support: IE 9 - 10 only\n\t\t} else if ( subWindow.attachEvent ) {\n\t\t\tsubWindow.attachEvent( \"onunload\", unloadHandler );\n\t\t}\n\t}\n\n\t/* Attributes\n\t---------------------------------------------------------------------- */\n\n\t// Support: IE<8\n\t// Verify that getAttribute really returns attributes and not properties\n\t// (excepting IE8 booleans)\n\tsupport.attributes = assert(function( el ) {\n\t\tel.className = \"i\";\n\t\treturn !el.getAttribute(\"className\");\n\t});\n\n\t/* getElement(s)By*\n\t---------------------------------------------------------------------- */\n\n\t// Check if getElementsByTagName(\"*\") returns only elements\n\tsupport.getElementsByTagName = assert(function( el ) {\n\t\tel.appendChild( document.createComment(\"\") );\n\t\treturn !el.getElementsByTagName(\"*\").length;\n\t});\n\n\t// Support: IE<9\n\tsupport.getElementsByClassName = rnative.test( document.getElementsByClassName );\n\n\t// Support: IE<10\n\t// Check if getElementById returns elements by name\n\t// The broken getElementById methods don't pick up programmatically-set names,\n\t// so use a roundabout getElementsByName test\n\tsupport.getById = assert(function( el ) {\n\t\tdocElem.appendChild( el ).id = expando;\n\t\treturn !document.getElementsByName || !document.getElementsByName( expando ).length;\n\t});\n\n\t// ID filter and find\n\tif ( support.getById ) {\n\t\tExpr.filter[\"ID\"] = function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn elem.getAttribute(\"id\") === attrId;\n\t\t\t};\n\t\t};\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar elem = context.getElementById( id );\n\t\t\t\treturn elem ? [ elem ] : [];\n\t\t\t}\n\t\t};\n\t} else {\n\t\tExpr.filter[\"ID\"] =  function( id ) {\n\t\t\tvar attrId = id.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\tvar node = typeof elem.getAttributeNode !== \"undefined\" &&\n\t\t\t\t\telem.getAttributeNode(\"id\");\n\t\t\t\treturn node && node.value === attrId;\n\t\t\t};\n\t\t};\n\n\t\t// Support: IE 6 - 7 only\n\t\t// getElementById is not reliable as a find shortcut\n\t\tExpr.find[\"ID\"] = function( id, context ) {\n\t\t\tif ( typeof context.getElementById !== \"undefined\" && documentIsHTML ) {\n\t\t\t\tvar node, i, elems,\n\t\t\t\t\telem = context.getElementById( id );\n\n\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t// Verify the id attribute\n\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t}\n\n\t\t\t\t\t// Fall back on getElementsByName\n\t\t\t\t\telems = context.getElementsByName( id );\n\t\t\t\t\ti = 0;\n\t\t\t\t\twhile ( (elem = elems[i++]) ) {\n\t\t\t\t\t\tnode = elem.getAttributeNode(\"id\");\n\t\t\t\t\t\tif ( node && node.value === id ) {\n\t\t\t\t\t\t\treturn [ elem ];\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn [];\n\t\t\t}\n\t\t};\n\t}\n\n\t// Tag\n\tExpr.find[\"TAG\"] = support.getElementsByTagName ?\n\t\tfunction( tag, context ) {\n\t\t\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\t\t\treturn context.getElementsByTagName( tag );\n\n\t\t\t// DocumentFragment nodes don't have gEBTN\n\t\t\t} else if ( support.qsa ) {\n\t\t\t\treturn context.querySelectorAll( tag );\n\t\t\t}\n\t\t} :\n\n\t\tfunction( tag, context ) {\n\t\t\tvar elem,\n\t\t\t\ttmp = [],\n\t\t\t\ti = 0,\n\t\t\t\t// By happy coincidence, a (broken) gEBTN appears on DocumentFragment nodes too\n\t\t\t\tresults = context.getElementsByTagName( tag );\n\n\t\t\t// Filter out possible comments\n\t\t\tif ( tag === \"*\" ) {\n\t\t\t\twhile ( (elem = results[i++]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\ttmp.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn tmp;\n\t\t\t}\n\t\t\treturn results;\n\t\t};\n\n\t// Class\n\tExpr.find[\"CLASS\"] = support.getElementsByClassName && function( className, context ) {\n\t\tif ( typeof context.getElementsByClassName !== \"undefined\" && documentIsHTML ) {\n\t\t\treturn context.getElementsByClassName( className );\n\t\t}\n\t};\n\n\t/* QSA/matchesSelector\n\t---------------------------------------------------------------------- */\n\n\t// QSA and matchesSelector support\n\n\t// matchesSelector(:active) reports false when true (IE9/Opera 11.5)\n\trbuggyMatches = [];\n\n\t// qSa(:focus) reports false when true (Chrome 21)\n\t// We allow this because of a bug in IE8/9 that throws an error\n\t// whenever `document.activeElement` is accessed on an iframe\n\t// So, we allow :focus to pass through QSA all the time to avoid the IE error\n\t// See https://bugs.jquery.com/ticket/13378\n\trbuggyQSA = [];\n\n\tif ( (support.qsa = rnative.test( document.querySelectorAll )) ) {\n\t\t// Build QSA regex\n\t\t// Regex strategy adopted from Diego Perini\n\t\tassert(function( el ) {\n\t\t\t// Select is set to empty string on purpose\n\t\t\t// This is to test IE's treatment of not explicitly\n\t\t\t// setting a boolean content attribute,\n\t\t\t// since its presence should be enough\n\t\t\t// https://bugs.jquery.com/ticket/12359\n\t\t\tdocElem.appendChild( el ).innerHTML = \"<a id='\" + expando + \"'></a>\" +\n\t\t\t\t\"<select id='\" + expando + \"-\\r\\\\' msallowcapture=''>\" +\n\t\t\t\t\"<option selected=''></option></select>\";\n\n\t\t\t// Support: IE8, Opera 11-12.16\n\t\t\t// Nothing should be selected when empty strings follow ^= or $= or *=\n\t\t\t// The test attribute must be unknown in Opera but \"safe\" for WinRT\n\t\t\t// https://msdn.microsoft.com/en-us/library/ie/hh465388.aspx#attribute_section\n\t\t\tif ( el.querySelectorAll(\"[msallowcapture^='']\").length ) {\n\t\t\t\trbuggyQSA.push( \"[*^$]=\" + whitespace + \"*(?:''|\\\"\\\")\" );\n\t\t\t}\n\n\t\t\t// Support: IE8\n\t\t\t// Boolean attributes and \"value\" are not treated correctly\n\t\t\tif ( !el.querySelectorAll(\"[selected]\").length ) {\n\t\t\t\trbuggyQSA.push( \"\\\\[\" + whitespace + \"*(?:value|\" + booleans + \")\" );\n\t\t\t}\n\n\t\t\t// Support: Chrome<29, Android<4.4, Safari<7.0+, iOS<7.0+, PhantomJS<1.9.8+\n\t\t\tif ( !el.querySelectorAll( \"[id~=\" + expando + \"-]\" ).length ) {\n\t\t\t\trbuggyQSA.push(\"~=\");\n\t\t\t}\n\n\t\t\t// Webkit/Opera - :checked should return selected option elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( !el.querySelectorAll(\":checked\").length ) {\n\t\t\t\trbuggyQSA.push(\":checked\");\n\t\t\t}\n\n\t\t\t// Support: Safari 8+, iOS 8+\n\t\t\t// https://bugs.webkit.org/show_bug.cgi?id=136851\n\t\t\t// In-page `selector#id sibling-combinator selector` fails\n\t\t\tif ( !el.querySelectorAll( \"a#\" + expando + \"+*\" ).length ) {\n\t\t\t\trbuggyQSA.push(\".#.+[+~]\");\n\t\t\t}\n\t\t});\n\n\t\tassert(function( el ) {\n\t\t\tel.innerHTML = \"<a href='' disabled='disabled'></a>\" +\n\t\t\t\t\"<select disabled='disabled'><option/></select>\";\n\n\t\t\t// Support: Windows 8 Native Apps\n\t\t\t// The type and name attributes are restricted during .innerHTML assignment\n\t\t\tvar input = document.createElement(\"input\");\n\t\t\tinput.setAttribute( \"type\", \"hidden\" );\n\t\t\tel.appendChild( input ).setAttribute( \"name\", \"D\" );\n\n\t\t\t// Support: IE8\n\t\t\t// Enforce case-sensitivity of name attribute\n\t\t\tif ( el.querySelectorAll(\"[name=d]\").length ) {\n\t\t\t\trbuggyQSA.push( \"name\" + whitespace + \"*[*^$|!~]?=\" );\n\t\t\t}\n\n\t\t\t// FF 3.5 - :enabled/:disabled and hidden elements (hidden elements are still enabled)\n\t\t\t// IE8 throws error here and will not see later tests\n\t\t\tif ( el.querySelectorAll(\":enabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Support: IE9-11+\n\t\t\t// IE's :disabled selector does not pick up the children of disabled fieldsets\n\t\t\tdocElem.appendChild( el ).disabled = true;\n\t\t\tif ( el.querySelectorAll(\":disabled\").length !== 2 ) {\n\t\t\t\trbuggyQSA.push( \":enabled\", \":disabled\" );\n\t\t\t}\n\n\t\t\t// Opera 10-11 does not throw on post-comma invalid pseudos\n\t\t\tel.querySelectorAll(\"*,:x\");\n\t\t\trbuggyQSA.push(\",.*:\");\n\t\t});\n\t}\n\n\tif ( (support.matchesSelector = rnative.test( (matches = docElem.matches ||\n\t\tdocElem.webkitMatchesSelector ||\n\t\tdocElem.mozMatchesSelector ||\n\t\tdocElem.oMatchesSelector ||\n\t\tdocElem.msMatchesSelector) )) ) {\n\n\t\tassert(function( el ) {\n\t\t\t// Check to see if it's possible to do matchesSelector\n\t\t\t// on a disconnected node (IE 9)\n\t\t\tsupport.disconnectedMatch = matches.call( el, \"*\" );\n\n\t\t\t// This should fail with an exception\n\t\t\t// Gecko does not error, returns false instead\n\t\t\tmatches.call( el, \"[s!='']:x\" );\n\t\t\trbuggyMatches.push( \"!=\", pseudos );\n\t\t});\n\t}\n\n\trbuggyQSA = rbuggyQSA.length && new RegExp( rbuggyQSA.join(\"|\") );\n\trbuggyMatches = rbuggyMatches.length && new RegExp( rbuggyMatches.join(\"|\") );\n\n\t/* Contains\n\t---------------------------------------------------------------------- */\n\thasCompare = rnative.test( docElem.compareDocumentPosition );\n\n\t// Element contains another\n\t// Purposefully self-exclusive\n\t// As in, an element does not contain itself\n\tcontains = hasCompare || rnative.test( docElem.contains ) ?\n\t\tfunction( a, b ) {\n\t\t\tvar adown = a.nodeType === 9 ? a.documentElement : a,\n\t\t\t\tbup = b && b.parentNode;\n\t\t\treturn a === bup || !!( bup && bup.nodeType === 1 && (\n\t\t\t\tadown.contains ?\n\t\t\t\t\tadown.contains( bup ) :\n\t\t\t\t\ta.compareDocumentPosition && a.compareDocumentPosition( bup ) & 16\n\t\t\t));\n\t\t} :\n\t\tfunction( a, b ) {\n\t\t\tif ( b ) {\n\t\t\t\twhile ( (b = b.parentNode) ) {\n\t\t\t\t\tif ( b === a ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n\n\t/* Sorting\n\t---------------------------------------------------------------------- */\n\n\t// Document order sorting\n\tsortOrder = hasCompare ?\n\tfunction( a, b ) {\n\n\t\t// Flag for duplicate removal\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\t// Sort on method existence if only one input has compareDocumentPosition\n\t\tvar compare = !a.compareDocumentPosition - !b.compareDocumentPosition;\n\t\tif ( compare ) {\n\t\t\treturn compare;\n\t\t}\n\n\t\t// Calculate position if both inputs belong to the same document\n\t\tcompare = ( a.ownerDocument || a ) === ( b.ownerDocument || b ) ?\n\t\t\ta.compareDocumentPosition( b ) :\n\n\t\t\t// Otherwise we know they are disconnected\n\t\t\t1;\n\n\t\t// Disconnected nodes\n\t\tif ( compare & 1 ||\n\t\t\t(!support.sortDetached && b.compareDocumentPosition( a ) === compare) ) {\n\n\t\t\t// Choose the first element that is related to our preferred document\n\t\t\tif ( a === document || a.ownerDocument === preferredDoc && contains(preferredDoc, a) ) {\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t\tif ( b === document || b.ownerDocument === preferredDoc && contains(preferredDoc, b) ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\t// Maintain original order\n\t\t\treturn sortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\t\t}\n\n\t\treturn compare & 4 ? -1 : 1;\n\t} :\n\tfunction( a, b ) {\n\t\t// Exit early if the nodes are identical\n\t\tif ( a === b ) {\n\t\t\thasDuplicate = true;\n\t\t\treturn 0;\n\t\t}\n\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\taup = a.parentNode,\n\t\t\tbup = b.parentNode,\n\t\t\tap = [ a ],\n\t\t\tbp = [ b ];\n\n\t\t// Parentless nodes are either documents or disconnected\n\t\tif ( !aup || !bup ) {\n\t\t\treturn a === document ? -1 :\n\t\t\t\tb === document ? 1 :\n\t\t\t\taup ? -1 :\n\t\t\t\tbup ? 1 :\n\t\t\t\tsortInput ?\n\t\t\t\t( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) :\n\t\t\t\t0;\n\n\t\t// If the nodes are siblings, we can do a quick check\n\t\t} else if ( aup === bup ) {\n\t\t\treturn siblingCheck( a, b );\n\t\t}\n\n\t\t// Otherwise we need full lists of their ancestors for comparison\n\t\tcur = a;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tap.unshift( cur );\n\t\t}\n\t\tcur = b;\n\t\twhile ( (cur = cur.parentNode) ) {\n\t\t\tbp.unshift( cur );\n\t\t}\n\n\t\t// Walk down the tree looking for a discrepancy\n\t\twhile ( ap[i] === bp[i] ) {\n\t\t\ti++;\n\t\t}\n\n\t\treturn i ?\n\t\t\t// Do a sibling check if the nodes have a common ancestor\n\t\t\tsiblingCheck( ap[i], bp[i] ) :\n\n\t\t\t// Otherwise nodes in our document sort first\n\t\t\tap[i] === preferredDoc ? -1 :\n\t\t\tbp[i] === preferredDoc ? 1 :\n\t\t\t0;\n\t};\n\n\treturn document;\n};\n\nSizzle.matches = function( expr, elements ) {\n\treturn Sizzle( expr, null, null, elements );\n};\n\nSizzle.matchesSelector = function( elem, expr ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tif ( support.matchesSelector && documentIsHTML &&\n\t\t!nonnativeSelectorCache[ expr + \" \" ] &&\n\t\t( !rbuggyMatches || !rbuggyMatches.test( expr ) ) &&\n\t\t( !rbuggyQSA     || !rbuggyQSA.test( expr ) ) ) {\n\n\t\ttry {\n\t\t\tvar ret = matches.call( elem, expr );\n\n\t\t\t// IE 9's matchesSelector returns false on disconnected nodes\n\t\t\tif ( ret || support.disconnectedMatch ||\n\t\t\t\t\t// As well, disconnected nodes are said to be in a document\n\t\t\t\t\t// fragment in IE 9\n\t\t\t\t\telem.document && elem.document.nodeType !== 11 ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\t\t} catch (e) {\n\t\t\tnonnativeSelectorCache( expr, true );\n\t\t}\n\t}\n\n\treturn Sizzle( expr, document, null, [ elem ] ).length > 0;\n};\n\nSizzle.contains = function( context, elem ) {\n\t// Set document vars if needed\n\tif ( ( context.ownerDocument || context ) !== document ) {\n\t\tsetDocument( context );\n\t}\n\treturn contains( context, elem );\n};\n\nSizzle.attr = function( elem, name ) {\n\t// Set document vars if needed\n\tif ( ( elem.ownerDocument || elem ) !== document ) {\n\t\tsetDocument( elem );\n\t}\n\n\tvar fn = Expr.attrHandle[ name.toLowerCase() ],\n\t\t// Don't get fooled by Object.prototype properties (jQuery #13807)\n\t\tval = fn && hasOwn.call( Expr.attrHandle, name.toLowerCase() ) ?\n\t\t\tfn( elem, name, !documentIsHTML ) :\n\t\t\tundefined;\n\n\treturn val !== undefined ?\n\t\tval :\n\t\tsupport.attributes || !documentIsHTML ?\n\t\t\telem.getAttribute( name ) :\n\t\t\t(val = elem.getAttributeNode(name)) && val.specified ?\n\t\t\t\tval.value :\n\t\t\t\tnull;\n};\n\nSizzle.escape = function( sel ) {\n\treturn (sel + \"\").replace( rcssescape, fcssescape );\n};\n\nSizzle.error = function( msg ) {\n\tthrow new Error( \"Syntax error, unrecognized expression: \" + msg );\n};\n\n/**\n * Document sorting and removing duplicates\n * @param {ArrayLike} results\n */\nSizzle.uniqueSort = function( results ) {\n\tvar elem,\n\t\tduplicates = [],\n\t\tj = 0,\n\t\ti = 0;\n\n\t// Unless we *know* we can detect duplicates, assume their presence\n\thasDuplicate = !support.detectDuplicates;\n\tsortInput = !support.sortStable && results.slice( 0 );\n\tresults.sort( sortOrder );\n\n\tif ( hasDuplicate ) {\n\t\twhile ( (elem = results[i++]) ) {\n\t\t\tif ( elem === results[ i ] ) {\n\t\t\t\tj = duplicates.push( i );\n\t\t\t}\n\t\t}\n\t\twhile ( j-- ) {\n\t\t\tresults.splice( duplicates[ j ], 1 );\n\t\t}\n\t}\n\n\t// Clear input after sorting to release objects\n\t// See https://github.com/jquery/sizzle/pull/225\n\tsortInput = null;\n\n\treturn results;\n};\n\n/**\n * Utility function for retrieving the text value of an array of DOM nodes\n * @param {Array|Element} elem\n */\ngetText = Sizzle.getText = function( elem ) {\n\tvar node,\n\t\tret = \"\",\n\t\ti = 0,\n\t\tnodeType = elem.nodeType;\n\n\tif ( !nodeType ) {\n\t\t// If no nodeType, this is expected to be an array\n\t\twhile ( (node = elem[i++]) ) {\n\t\t\t// Do not traverse comment nodes\n\t\t\tret += getText( node );\n\t\t}\n\t} else if ( nodeType === 1 || nodeType === 9 || nodeType === 11 ) {\n\t\t// Use textContent for elements\n\t\t// innerText usage removed for consistency of new lines (jQuery #11153)\n\t\tif ( typeof elem.textContent === \"string\" ) {\n\t\t\treturn elem.textContent;\n\t\t} else {\n\t\t\t// Traverse its children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tret += getText( elem );\n\t\t\t}\n\t\t}\n\t} else if ( nodeType === 3 || nodeType === 4 ) {\n\t\treturn elem.nodeValue;\n\t}\n\t// Do not include comment or processing instruction nodes\n\n\treturn ret;\n};\n\nExpr = Sizzle.selectors = {\n\n\t// Can be adjusted by the user\n\tcacheLength: 50,\n\n\tcreatePseudo: markFunction,\n\n\tmatch: matchExpr,\n\n\tattrHandle: {},\n\n\tfind: {},\n\n\trelative: {\n\t\t\">\": { dir: \"parentNode\", first: true },\n\t\t\" \": { dir: \"parentNode\" },\n\t\t\"+\": { dir: \"previousSibling\", first: true },\n\t\t\"~\": { dir: \"previousSibling\" }\n\t},\n\n\tpreFilter: {\n\t\t\"ATTR\": function( match ) {\n\t\t\tmatch[1] = match[1].replace( runescape, funescape );\n\n\t\t\t// Move the given value to match[3] whether quoted or unquoted\n\t\t\tmatch[3] = ( match[3] || match[4] || match[5] || \"\" ).replace( runescape, funescape );\n\n\t\t\tif ( match[2] === \"~=\" ) {\n\t\t\t\tmatch[3] = \" \" + match[3] + \" \";\n\t\t\t}\n\n\t\t\treturn match.slice( 0, 4 );\n\t\t},\n\n\t\t\"CHILD\": function( match ) {\n\t\t\t/* matches from matchExpr[\"CHILD\"]\n\t\t\t\t1 type (only|nth|...)\n\t\t\t\t2 what (child|of-type)\n\t\t\t\t3 argument (even|odd|\\d*|\\d*n([+-]\\d+)?|...)\n\t\t\t\t4 xn-component of xn+y argument ([+-]?\\d*n|)\n\t\t\t\t5 sign of xn-component\n\t\t\t\t6 x of xn-component\n\t\t\t\t7 sign of y-component\n\t\t\t\t8 y of y-component\n\t\t\t*/\n\t\t\tmatch[1] = match[1].toLowerCase();\n\n\t\t\tif ( match[1].slice( 0, 3 ) === \"nth\" ) {\n\t\t\t\t// nth-* requires argument\n\t\t\t\tif ( !match[3] ) {\n\t\t\t\t\tSizzle.error( match[0] );\n\t\t\t\t}\n\n\t\t\t\t// numeric x and y parameters for Expr.filter.CHILD\n\t\t\t\t// remember that false/true cast respectively to 0/1\n\t\t\t\tmatch[4] = +( match[4] ? match[5] + (match[6] || 1) : 2 * ( match[3] === \"even\" || match[3] === \"odd\" ) );\n\t\t\t\tmatch[5] = +( ( match[7] + match[8] ) || match[3] === \"odd\" );\n\n\t\t\t// other types prohibit arguments\n\t\t\t} else if ( match[3] ) {\n\t\t\t\tSizzle.error( match[0] );\n\t\t\t}\n\n\t\t\treturn match;\n\t\t},\n\n\t\t\"PSEUDO\": function( match ) {\n\t\t\tvar excess,\n\t\t\t\tunquoted = !match[6] && match[2];\n\n\t\t\tif ( matchExpr[\"CHILD\"].test( match[0] ) ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\t// Accept quoted arguments as-is\n\t\t\tif ( match[3] ) {\n\t\t\t\tmatch[2] = match[4] || match[5] || \"\";\n\n\t\t\t// Strip excess characters from unquoted arguments\n\t\t\t} else if ( unquoted && rpseudo.test( unquoted ) &&\n\t\t\t\t// Get excess from tokenize (recursively)\n\t\t\t\t(excess = tokenize( unquoted, true )) &&\n\t\t\t\t// advance to the next closing parenthesis\n\t\t\t\t(excess = unquoted.indexOf( \")\", unquoted.length - excess ) - unquoted.length) ) {\n\n\t\t\t\t// excess is a negative index\n\t\t\t\tmatch[0] = match[0].slice( 0, excess );\n\t\t\t\tmatch[2] = unquoted.slice( 0, excess );\n\t\t\t}\n\n\t\t\t// Return only captures needed by the pseudo filter method (type and argument)\n\t\t\treturn match.slice( 0, 3 );\n\t\t}\n\t},\n\n\tfilter: {\n\n\t\t\"TAG\": function( nodeNameSelector ) {\n\t\t\tvar nodeName = nodeNameSelector.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn nodeNameSelector === \"*\" ?\n\t\t\t\tfunction() { return true; } :\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn elem.nodeName && elem.nodeName.toLowerCase() === nodeName;\n\t\t\t\t};\n\t\t},\n\n\t\t\"CLASS\": function( className ) {\n\t\t\tvar pattern = classCache[ className + \" \" ];\n\n\t\t\treturn pattern ||\n\t\t\t\t(pattern = new RegExp( \"(^|\" + whitespace + \")\" + className + \"(\" + whitespace + \"|$)\" )) &&\n\t\t\t\tclassCache( className, function( elem ) {\n\t\t\t\t\treturn pattern.test( typeof elem.className === \"string\" && elem.className || typeof elem.getAttribute !== \"undefined\" && elem.getAttribute(\"class\") || \"\" );\n\t\t\t\t});\n\t\t},\n\n\t\t\"ATTR\": function( name, operator, check ) {\n\t\t\treturn function( elem ) {\n\t\t\t\tvar result = Sizzle.attr( elem, name );\n\n\t\t\t\tif ( result == null ) {\n\t\t\t\t\treturn operator === \"!=\";\n\t\t\t\t}\n\t\t\t\tif ( !operator ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\n\t\t\t\tresult += \"\";\n\n\t\t\t\treturn operator === \"=\" ? result === check :\n\t\t\t\t\toperator === \"!=\" ? result !== check :\n\t\t\t\t\toperator === \"^=\" ? check && result.indexOf( check ) === 0 :\n\t\t\t\t\toperator === \"*=\" ? check && result.indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"$=\" ? check && result.slice( -check.length ) === check :\n\t\t\t\t\toperator === \"~=\" ? ( \" \" + result.replace( rwhitespace, \" \" ) + \" \" ).indexOf( check ) > -1 :\n\t\t\t\t\toperator === \"|=\" ? result === check || result.slice( 0, check.length + 1 ) === check + \"-\" :\n\t\t\t\t\tfalse;\n\t\t\t};\n\t\t},\n\n\t\t\"CHILD\": function( type, what, argument, first, last ) {\n\t\t\tvar simple = type.slice( 0, 3 ) !== \"nth\",\n\t\t\t\tforward = type.slice( -4 ) !== \"last\",\n\t\t\t\tofType = what === \"of-type\";\n\n\t\t\treturn first === 1 && last === 0 ?\n\n\t\t\t\t// Shortcut for :nth-*(n)\n\t\t\t\tfunction( elem ) {\n\t\t\t\t\treturn !!elem.parentNode;\n\t\t\t\t} :\n\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tvar cache, uniqueCache, outerCache, node, nodeIndex, start,\n\t\t\t\t\t\tdir = simple !== forward ? \"nextSibling\" : \"previousSibling\",\n\t\t\t\t\t\tparent = elem.parentNode,\n\t\t\t\t\t\tname = ofType && elem.nodeName.toLowerCase(),\n\t\t\t\t\t\tuseCache = !xml && !ofType,\n\t\t\t\t\t\tdiff = false;\n\n\t\t\t\t\tif ( parent ) {\n\n\t\t\t\t\t\t// :(first|last|only)-(child|of-type)\n\t\t\t\t\t\tif ( simple ) {\n\t\t\t\t\t\t\twhile ( dir ) {\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\twhile ( (node = node[ dir ]) ) {\n\t\t\t\t\t\t\t\t\tif ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) {\n\n\t\t\t\t\t\t\t\t\t\treturn false;\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t// Reverse direction for :only-* (if we haven't yet done so)\n\t\t\t\t\t\t\t\tstart = dir = type === \"only\" && !start && \"nextSibling\";\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\tstart = [ forward ? parent.firstChild : parent.lastChild ];\n\n\t\t\t\t\t\t// non-xml :nth-child(...) stores cache data on `parent`\n\t\t\t\t\t\tif ( forward && useCache ) {\n\n\t\t\t\t\t\t\t// Seek `elem` from a previously-cached index\n\n\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\tnode = parent;\n\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\tdiff = nodeIndex && cache[ 2 ];\n\t\t\t\t\t\t\tnode = nodeIndex && parent.childNodes[ nodeIndex ];\n\n\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\n\t\t\t\t\t\t\t\t// Fallback to seeking `elem` from the start\n\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t// When found, cache indexes on `parent` and break\n\t\t\t\t\t\t\t\tif ( node.nodeType === 1 && ++diff && node === elem ) {\n\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, nodeIndex, diff ];\n\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Use previously-cached element index if available\n\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t// ...in a gzip-friendly way\n\t\t\t\t\t\t\t\tnode = elem;\n\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\tcache = uniqueCache[ type ] || [];\n\t\t\t\t\t\t\t\tnodeIndex = cache[ 0 ] === dirruns && cache[ 1 ];\n\t\t\t\t\t\t\t\tdiff = nodeIndex;\n\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t// xml :nth-child(...)\n\t\t\t\t\t\t\t// or :nth-last-child(...) or :nth(-last)?-of-type(...)\n\t\t\t\t\t\t\tif ( diff === false ) {\n\t\t\t\t\t\t\t\t// Use the same loop as above to seek `elem` from the start\n\t\t\t\t\t\t\t\twhile ( (node = ++nodeIndex && node && node[ dir ] ||\n\t\t\t\t\t\t\t\t\t(diff = nodeIndex = 0) || start.pop()) ) {\n\n\t\t\t\t\t\t\t\t\tif ( ( ofType ?\n\t\t\t\t\t\t\t\t\t\tnode.nodeName.toLowerCase() === name :\n\t\t\t\t\t\t\t\t\t\tnode.nodeType === 1 ) &&\n\t\t\t\t\t\t\t\t\t\t++diff ) {\n\n\t\t\t\t\t\t\t\t\t\t// Cache the index of each encountered element\n\t\t\t\t\t\t\t\t\t\tif ( useCache ) {\n\t\t\t\t\t\t\t\t\t\t\touterCache = node[ expando ] || (node[ expando ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache = outerCache[ node.uniqueID ] ||\n\t\t\t\t\t\t\t\t\t\t\t\t(outerCache[ node.uniqueID ] = {});\n\n\t\t\t\t\t\t\t\t\t\t\tuniqueCache[ type ] = [ dirruns, diff ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\tif ( node === elem ) {\n\t\t\t\t\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Incorporate the offset, then check against cycle size\n\t\t\t\t\t\tdiff -= last;\n\t\t\t\t\t\treturn diff === first || ( diff % first === 0 && diff / first >= 0 );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t},\n\n\t\t\"PSEUDO\": function( pseudo, argument ) {\n\t\t\t// pseudo-class names are case-insensitive\n\t\t\t// http://www.w3.org/TR/selectors/#pseudo-classes\n\t\t\t// Prioritize by case sensitivity in case custom pseudos are added with uppercase letters\n\t\t\t// Remember that setFilters inherits from pseudos\n\t\t\tvar args,\n\t\t\t\tfn = Expr.pseudos[ pseudo ] || Expr.setFilters[ pseudo.toLowerCase() ] ||\n\t\t\t\t\tSizzle.error( \"unsupported pseudo: \" + pseudo );\n\n\t\t\t// The user may use createPseudo to indicate that\n\t\t\t// arguments are needed to create the filter function\n\t\t\t// just as Sizzle does\n\t\t\tif ( fn[ expando ] ) {\n\t\t\t\treturn fn( argument );\n\t\t\t}\n\n\t\t\t// But maintain support for old signatures\n\t\t\tif ( fn.length > 1 ) {\n\t\t\t\targs = [ pseudo, pseudo, \"\", argument ];\n\t\t\t\treturn Expr.setFilters.hasOwnProperty( pseudo.toLowerCase() ) ?\n\t\t\t\t\tmarkFunction(function( seed, matches ) {\n\t\t\t\t\t\tvar idx,\n\t\t\t\t\t\t\tmatched = fn( seed, argument ),\n\t\t\t\t\t\t\ti = matched.length;\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tidx = indexOf( seed, matched[i] );\n\t\t\t\t\t\t\tseed[ idx ] = !( matches[ idx ] = matched[i] );\n\t\t\t\t\t\t}\n\t\t\t\t\t}) :\n\t\t\t\t\tfunction( elem ) {\n\t\t\t\t\t\treturn fn( elem, 0, args );\n\t\t\t\t\t};\n\t\t\t}\n\n\t\t\treturn fn;\n\t\t}\n\t},\n\n\tpseudos: {\n\t\t// Potentially complex pseudos\n\t\t\"not\": markFunction(function( selector ) {\n\t\t\t// Trim the selector passed to compile\n\t\t\t// to avoid treating leading and trailing\n\t\t\t// spaces as combinators\n\t\t\tvar input = [],\n\t\t\t\tresults = [],\n\t\t\t\tmatcher = compile( selector.replace( rtrim, \"$1\" ) );\n\n\t\t\treturn matcher[ expando ] ?\n\t\t\t\tmarkFunction(function( seed, matches, context, xml ) {\n\t\t\t\t\tvar elem,\n\t\t\t\t\t\tunmatched = matcher( seed, null, xml, [] ),\n\t\t\t\t\t\ti = seed.length;\n\n\t\t\t\t\t// Match elements unmatched by `matcher`\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = unmatched[i]) ) {\n\t\t\t\t\t\t\tseed[i] = !(matches[i] = elem);\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}) :\n\t\t\t\tfunction( elem, context, xml ) {\n\t\t\t\t\tinput[0] = elem;\n\t\t\t\t\tmatcher( input, null, xml, results );\n\t\t\t\t\t// Don't keep the element (issue #299)\n\t\t\t\t\tinput[0] = null;\n\t\t\t\t\treturn !results.pop();\n\t\t\t\t};\n\t\t}),\n\n\t\t\"has\": markFunction(function( selector ) {\n\t\t\treturn function( elem ) {\n\t\t\t\treturn Sizzle( selector, elem ).length > 0;\n\t\t\t};\n\t\t}),\n\n\t\t\"contains\": markFunction(function( text ) {\n\t\t\ttext = text.replace( runescape, funescape );\n\t\t\treturn function( elem ) {\n\t\t\t\treturn ( elem.textContent || getText( elem ) ).indexOf( text ) > -1;\n\t\t\t};\n\t\t}),\n\n\t\t// \"Whether an element is represented by a :lang() selector\n\t\t// is based solely on the element's language value\n\t\t// being equal to the identifier C,\n\t\t// or beginning with the identifier C immediately followed by \"-\".\n\t\t// The matching of C against the element's language value is performed case-insensitively.\n\t\t// The identifier C does not have to be a valid language name.\"\n\t\t// http://www.w3.org/TR/selectors/#lang-pseudo\n\t\t\"lang\": markFunction( function( lang ) {\n\t\t\t// lang value must be a valid identifier\n\t\t\tif ( !ridentifier.test(lang || \"\") ) {\n\t\t\t\tSizzle.error( \"unsupported lang: \" + lang );\n\t\t\t}\n\t\t\tlang = lang.replace( runescape, funescape ).toLowerCase();\n\t\t\treturn function( elem ) {\n\t\t\t\tvar elemLang;\n\t\t\t\tdo {\n\t\t\t\t\tif ( (elemLang = documentIsHTML ?\n\t\t\t\t\t\telem.lang :\n\t\t\t\t\t\telem.getAttribute(\"xml:lang\") || elem.getAttribute(\"lang\")) ) {\n\n\t\t\t\t\t\telemLang = elemLang.toLowerCase();\n\t\t\t\t\t\treturn elemLang === lang || elemLang.indexOf( lang + \"-\" ) === 0;\n\t\t\t\t\t}\n\t\t\t\t} while ( (elem = elem.parentNode) && elem.nodeType === 1 );\n\t\t\t\treturn false;\n\t\t\t};\n\t\t}),\n\n\t\t// Miscellaneous\n\t\t\"target\": function( elem ) {\n\t\t\tvar hash = window.location && window.location.hash;\n\t\t\treturn hash && hash.slice( 1 ) === elem.id;\n\t\t},\n\n\t\t\"root\": function( elem ) {\n\t\t\treturn elem === docElem;\n\t\t},\n\n\t\t\"focus\": function( elem ) {\n\t\t\treturn elem === document.activeElement && (!document.hasFocus || document.hasFocus()) && !!(elem.type || elem.href || ~elem.tabIndex);\n\t\t},\n\n\t\t// Boolean properties\n\t\t\"enabled\": createDisabledPseudo( false ),\n\t\t\"disabled\": createDisabledPseudo( true ),\n\n\t\t\"checked\": function( elem ) {\n\t\t\t// In CSS3, :checked should return both checked and selected elements\n\t\t\t// http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked\n\t\t\tvar nodeName = elem.nodeName.toLowerCase();\n\t\t\treturn (nodeName === \"input\" && !!elem.checked) || (nodeName === \"option\" && !!elem.selected);\n\t\t},\n\n\t\t\"selected\": function( elem ) {\n\t\t\t// Accessing this property makes selected-by-default\n\t\t\t// options in Safari work properly\n\t\t\tif ( elem.parentNode ) {\n\t\t\t\telem.parentNode.selectedIndex;\n\t\t\t}\n\n\t\t\treturn elem.selected === true;\n\t\t},\n\n\t\t// Contents\n\t\t\"empty\": function( elem ) {\n\t\t\t// http://www.w3.org/TR/selectors/#empty-pseudo\n\t\t\t// :empty is negated by element (1) or content nodes (text: 3; cdata: 4; entity ref: 5),\n\t\t\t//   but not by others (comment: 8; processing instruction: 7; etc.)\n\t\t\t// nodeType < 6 works because attributes (2) do not appear as children\n\t\t\tfor ( elem = elem.firstChild; elem; elem = elem.nextSibling ) {\n\t\t\t\tif ( elem.nodeType < 6 ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t},\n\n\t\t\"parent\": function( elem ) {\n\t\t\treturn !Expr.pseudos[\"empty\"]( elem );\n\t\t},\n\n\t\t// Element/input types\n\t\t\"header\": function( elem ) {\n\t\t\treturn rheader.test( elem.nodeName );\n\t\t},\n\n\t\t\"input\": function( elem ) {\n\t\t\treturn rinputs.test( elem.nodeName );\n\t\t},\n\n\t\t\"button\": function( elem ) {\n\t\t\tvar name = elem.nodeName.toLowerCase();\n\t\t\treturn name === \"input\" && elem.type === \"button\" || name === \"button\";\n\t\t},\n\n\t\t\"text\": function( elem ) {\n\t\t\tvar attr;\n\t\t\treturn elem.nodeName.toLowerCase() === \"input\" &&\n\t\t\t\telem.type === \"text\" &&\n\n\t\t\t\t// Support: IE<8\n\t\t\t\t// New HTML5 attribute values (e.g., \"search\") appear with elem.type === \"text\"\n\t\t\t\t( (attr = elem.getAttribute(\"type\")) == null || attr.toLowerCase() === \"text\" );\n\t\t},\n\n\t\t// Position-in-collection\n\t\t\"first\": createPositionalPseudo(function() {\n\t\t\treturn [ 0 ];\n\t\t}),\n\n\t\t\"last\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\treturn [ length - 1 ];\n\t\t}),\n\n\t\t\"eq\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\treturn [ argument < 0 ? argument + length : argument ];\n\t\t}),\n\n\t\t\"even\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"odd\": createPositionalPseudo(function( matchIndexes, length ) {\n\t\t\tvar i = 1;\n\t\t\tfor ( ; i < length; i += 2 ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"lt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ?\n\t\t\t\targument + length :\n\t\t\t\targument > length ?\n\t\t\t\t\tlength :\n\t\t\t\t\targument;\n\t\t\tfor ( ; --i >= 0; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t}),\n\n\t\t\"gt\": createPositionalPseudo(function( matchIndexes, length, argument ) {\n\t\t\tvar i = argument < 0 ? argument + length : argument;\n\t\t\tfor ( ; ++i < length; ) {\n\t\t\t\tmatchIndexes.push( i );\n\t\t\t}\n\t\t\treturn matchIndexes;\n\t\t})\n\t}\n};\n\nExpr.pseudos[\"nth\"] = Expr.pseudos[\"eq\"];\n\n// Add button/input type pseudos\nfor ( i in { radio: true, checkbox: true, file: true, password: true, image: true } ) {\n\tExpr.pseudos[ i ] = createInputPseudo( i );\n}\nfor ( i in { submit: true, reset: true } ) {\n\tExpr.pseudos[ i ] = createButtonPseudo( i );\n}\n\n// Easy API for creating new setFilters\nfunction setFilters() {}\nsetFilters.prototype = Expr.filters = Expr.pseudos;\nExpr.setFilters = new setFilters();\n\ntokenize = Sizzle.tokenize = function( selector, parseOnly ) {\n\tvar matched, match, tokens, type,\n\t\tsoFar, groups, preFilters,\n\t\tcached = tokenCache[ selector + \" \" ];\n\n\tif ( cached ) {\n\t\treturn parseOnly ? 0 : cached.slice( 0 );\n\t}\n\n\tsoFar = selector;\n\tgroups = [];\n\tpreFilters = Expr.preFilter;\n\n\twhile ( soFar ) {\n\n\t\t// Comma and first run\n\t\tif ( !matched || (match = rcomma.exec( soFar )) ) {\n\t\t\tif ( match ) {\n\t\t\t\t// Don't consume trailing commas as valid\n\t\t\t\tsoFar = soFar.slice( match[0].length ) || soFar;\n\t\t\t}\n\t\t\tgroups.push( (tokens = []) );\n\t\t}\n\n\t\tmatched = false;\n\n\t\t// Combinators\n\t\tif ( (match = rcombinators.exec( soFar )) ) {\n\t\t\tmatched = match.shift();\n\t\t\ttokens.push({\n\t\t\t\tvalue: matched,\n\t\t\t\t// Cast descendant combinators to space\n\t\t\t\ttype: match[0].replace( rtrim, \" \" )\n\t\t\t});\n\t\t\tsoFar = soFar.slice( matched.length );\n\t\t}\n\n\t\t// Filters\n\t\tfor ( type in Expr.filter ) {\n\t\t\tif ( (match = matchExpr[ type ].exec( soFar )) && (!preFilters[ type ] ||\n\t\t\t\t(match = preFilters[ type ]( match ))) ) {\n\t\t\t\tmatched = match.shift();\n\t\t\t\ttokens.push({\n\t\t\t\t\tvalue: matched,\n\t\t\t\t\ttype: type,\n\t\t\t\t\tmatches: match\n\t\t\t\t});\n\t\t\t\tsoFar = soFar.slice( matched.length );\n\t\t\t}\n\t\t}\n\n\t\tif ( !matched ) {\n\t\t\tbreak;\n\t\t}\n\t}\n\n\t// Return the length of the invalid excess\n\t// if we're just parsing\n\t// Otherwise, throw an error or return tokens\n\treturn parseOnly ?\n\t\tsoFar.length :\n\t\tsoFar ?\n\t\t\tSizzle.error( selector ) :\n\t\t\t// Cache the tokens\n\t\t\ttokenCache( selector, groups ).slice( 0 );\n};\n\nfunction toSelector( tokens ) {\n\tvar i = 0,\n\t\tlen = tokens.length,\n\t\tselector = \"\";\n\tfor ( ; i < len; i++ ) {\n\t\tselector += tokens[i].value;\n\t}\n\treturn selector;\n}\n\nfunction addCombinator( matcher, combinator, base ) {\n\tvar dir = combinator.dir,\n\t\tskip = combinator.next,\n\t\tkey = skip || dir,\n\t\tcheckNonElements = base && key === \"parentNode\",\n\t\tdoneName = done++;\n\n\treturn combinator.first ?\n\t\t// Check against closest ancestor/preceding element\n\t\tfunction( elem, context, xml ) {\n\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\treturn matcher( elem, context, xml );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t} :\n\n\t\t// Check against all ancestor/preceding elements\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar oldCache, uniqueCache, outerCache,\n\t\t\t\tnewCache = [ dirruns, doneName ];\n\n\t\t\t// We can't set arbitrary data on XML nodes, so they don't benefit from combinator caching\n\t\t\tif ( xml ) {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\tif ( matcher( elem, context, xml ) ) {\n\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\twhile ( (elem = elem[ dir ]) ) {\n\t\t\t\t\tif ( elem.nodeType === 1 || checkNonElements ) {\n\t\t\t\t\t\touterCache = elem[ expando ] || (elem[ expando ] = {});\n\n\t\t\t\t\t\t// Support: IE <9 only\n\t\t\t\t\t\t// Defend against cloned attroperties (jQuery gh-1709)\n\t\t\t\t\t\tuniqueCache = outerCache[ elem.uniqueID ] || (outerCache[ elem.uniqueID ] = {});\n\n\t\t\t\t\t\tif ( skip && skip === elem.nodeName.toLowerCase() ) {\n\t\t\t\t\t\t\telem = elem[ dir ] || elem;\n\t\t\t\t\t\t} else if ( (oldCache = uniqueCache[ key ]) &&\n\t\t\t\t\t\t\toldCache[ 0 ] === dirruns && oldCache[ 1 ] === doneName ) {\n\n\t\t\t\t\t\t\t// Assign to newCache so results back-propagate to previous elements\n\t\t\t\t\t\t\treturn (newCache[ 2 ] = oldCache[ 2 ]);\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t// Reuse newcache so results back-propagate to previous elements\n\t\t\t\t\t\t\tuniqueCache[ key ] = newCache;\n\n\t\t\t\t\t\t\t// A match means we're done; a fail means we have to keep checking\n\t\t\t\t\t\t\tif ( (newCache[ 2 ] = matcher( elem, context, xml )) ) {\n\t\t\t\t\t\t\t\treturn true;\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn false;\n\t\t};\n}\n\nfunction elementMatcher( matchers ) {\n\treturn matchers.length > 1 ?\n\t\tfunction( elem, context, xml ) {\n\t\t\tvar i = matchers.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( !matchers[i]( elem, context, xml ) ) {\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn true;\n\t\t} :\n\t\tmatchers[0];\n}\n\nfunction multipleContexts( selector, contexts, results ) {\n\tvar i = 0,\n\t\tlen = contexts.length;\n\tfor ( ; i < len; i++ ) {\n\t\tSizzle( selector, contexts[i], results );\n\t}\n\treturn results;\n}\n\nfunction condense( unmatched, map, filter, context, xml ) {\n\tvar elem,\n\t\tnewUnmatched = [],\n\t\ti = 0,\n\t\tlen = unmatched.length,\n\t\tmapped = map != null;\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (elem = unmatched[i]) ) {\n\t\t\tif ( !filter || filter( elem, context, xml ) ) {\n\t\t\t\tnewUnmatched.push( elem );\n\t\t\t\tif ( mapped ) {\n\t\t\t\t\tmap.push( i );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn newUnmatched;\n}\n\nfunction setMatcher( preFilter, selector, matcher, postFilter, postFinder, postSelector ) {\n\tif ( postFilter && !postFilter[ expando ] ) {\n\t\tpostFilter = setMatcher( postFilter );\n\t}\n\tif ( postFinder && !postFinder[ expando ] ) {\n\t\tpostFinder = setMatcher( postFinder, postSelector );\n\t}\n\treturn markFunction(function( seed, results, context, xml ) {\n\t\tvar temp, i, elem,\n\t\t\tpreMap = [],\n\t\t\tpostMap = [],\n\t\t\tpreexisting = results.length,\n\n\t\t\t// Get initial elements from seed or context\n\t\t\telems = seed || multipleContexts( selector || \"*\", context.nodeType ? [ context ] : context, [] ),\n\n\t\t\t// Prefilter to get matcher input, preserving a map for seed-results synchronization\n\t\t\tmatcherIn = preFilter && ( seed || !selector ) ?\n\t\t\t\tcondense( elems, preMap, preFilter, context, xml ) :\n\t\t\t\telems,\n\n\t\t\tmatcherOut = matcher ?\n\t\t\t\t// If we have a postFinder, or filtered seed, or non-seed postFilter or preexisting results,\n\t\t\t\tpostFinder || ( seed ? preFilter : preexisting || postFilter ) ?\n\n\t\t\t\t\t// ...intermediate processing is necessary\n\t\t\t\t\t[] :\n\n\t\t\t\t\t// ...otherwise use results directly\n\t\t\t\t\tresults :\n\t\t\t\tmatcherIn;\n\n\t\t// Find primary matches\n\t\tif ( matcher ) {\n\t\t\tmatcher( matcherIn, matcherOut, context, xml );\n\t\t}\n\n\t\t// Apply postFilter\n\t\tif ( postFilter ) {\n\t\t\ttemp = condense( matcherOut, postMap );\n\t\t\tpostFilter( temp, [], context, xml );\n\n\t\t\t// Un-match failing elements by moving them back to matcherIn\n\t\t\ti = temp.length;\n\t\t\twhile ( i-- ) {\n\t\t\t\tif ( (elem = temp[i]) ) {\n\t\t\t\t\tmatcherOut[ postMap[i] ] = !(matcherIn[ postMap[i] ] = elem);\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\tif ( seed ) {\n\t\t\tif ( postFinder || preFilter ) {\n\t\t\t\tif ( postFinder ) {\n\t\t\t\t\t// Get the final matcherOut by condensing this intermediate into postFinder contexts\n\t\t\t\t\ttemp = [];\n\t\t\t\t\ti = matcherOut.length;\n\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\tif ( (elem = matcherOut[i]) ) {\n\t\t\t\t\t\t\t// Restore matcherIn since elem is not yet a final match\n\t\t\t\t\t\t\ttemp.push( (matcherIn[i] = elem) );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tpostFinder( null, (matcherOut = []), temp, xml );\n\t\t\t\t}\n\n\t\t\t\t// Move matched elements from seed to results to keep them synchronized\n\t\t\t\ti = matcherOut.length;\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\tif ( (elem = matcherOut[i]) &&\n\t\t\t\t\t\t(temp = postFinder ? indexOf( seed, elem ) : preMap[i]) > -1 ) {\n\n\t\t\t\t\t\tseed[temp] = !(results[temp] = elem);\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Add elements to results, through postFinder if defined\n\t\t} else {\n\t\t\tmatcherOut = condense(\n\t\t\t\tmatcherOut === results ?\n\t\t\t\t\tmatcherOut.splice( preexisting, matcherOut.length ) :\n\t\t\t\t\tmatcherOut\n\t\t\t);\n\t\t\tif ( postFinder ) {\n\t\t\t\tpostFinder( null, results, matcherOut, xml );\n\t\t\t} else {\n\t\t\t\tpush.apply( results, matcherOut );\n\t\t\t}\n\t\t}\n\t});\n}\n\nfunction matcherFromTokens( tokens ) {\n\tvar checkContext, matcher, j,\n\t\tlen = tokens.length,\n\t\tleadingRelative = Expr.relative[ tokens[0].type ],\n\t\timplicitRelative = leadingRelative || Expr.relative[\" \"],\n\t\ti = leadingRelative ? 1 : 0,\n\n\t\t// The foundational matcher ensures that elements are reachable from top-level context(s)\n\t\tmatchContext = addCombinator( function( elem ) {\n\t\t\treturn elem === checkContext;\n\t\t}, implicitRelative, true ),\n\t\tmatchAnyContext = addCombinator( function( elem ) {\n\t\t\treturn indexOf( checkContext, elem ) > -1;\n\t\t}, implicitRelative, true ),\n\t\tmatchers = [ function( elem, context, xml ) {\n\t\t\tvar ret = ( !leadingRelative && ( xml || context !== outermostContext ) ) || (\n\t\t\t\t(checkContext = context).nodeType ?\n\t\t\t\t\tmatchContext( elem, context, xml ) :\n\t\t\t\t\tmatchAnyContext( elem, context, xml ) );\n\t\t\t// Avoid hanging onto element (issue #299)\n\t\t\tcheckContext = null;\n\t\t\treturn ret;\n\t\t} ];\n\n\tfor ( ; i < len; i++ ) {\n\t\tif ( (matcher = Expr.relative[ tokens[i].type ]) ) {\n\t\t\tmatchers = [ addCombinator(elementMatcher( matchers ), matcher) ];\n\t\t} else {\n\t\t\tmatcher = Expr.filter[ tokens[i].type ].apply( null, tokens[i].matches );\n\n\t\t\t// Return special upon seeing a positional matcher\n\t\t\tif ( matcher[ expando ] ) {\n\t\t\t\t// Find the next relative operator (if any) for proper handling\n\t\t\t\tj = ++i;\n\t\t\t\tfor ( ; j < len; j++ ) {\n\t\t\t\t\tif ( Expr.relative[ tokens[j].type ] ) {\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn setMatcher(\n\t\t\t\t\ti > 1 && elementMatcher( matchers ),\n\t\t\t\t\ti > 1 && toSelector(\n\t\t\t\t\t\t// If the preceding token was a descendant combinator, insert an implicit any-element `*`\n\t\t\t\t\t\ttokens.slice( 0, i - 1 ).concat({ value: tokens[ i - 2 ].type === \" \" ? \"*\" : \"\" })\n\t\t\t\t\t).replace( rtrim, \"$1\" ),\n\t\t\t\t\tmatcher,\n\t\t\t\t\ti < j && matcherFromTokens( tokens.slice( i, j ) ),\n\t\t\t\t\tj < len && matcherFromTokens( (tokens = tokens.slice( j )) ),\n\t\t\t\t\tj < len && toSelector( tokens )\n\t\t\t\t);\n\t\t\t}\n\t\t\tmatchers.push( matcher );\n\t\t}\n\t}\n\n\treturn elementMatcher( matchers );\n}\n\nfunction matcherFromGroupMatchers( elementMatchers, setMatchers ) {\n\tvar bySet = setMatchers.length > 0,\n\t\tbyElement = elementMatchers.length > 0,\n\t\tsuperMatcher = function( seed, context, xml, results, outermost ) {\n\t\t\tvar elem, j, matcher,\n\t\t\t\tmatchedCount = 0,\n\t\t\t\ti = \"0\",\n\t\t\t\tunmatched = seed && [],\n\t\t\t\tsetMatched = [],\n\t\t\t\tcontextBackup = outermostContext,\n\t\t\t\t// We must always have either seed elements or outermost context\n\t\t\t\telems = seed || byElement && Expr.find[\"TAG\"]( \"*\", outermost ),\n\t\t\t\t// Use integer dirruns iff this is the outermost matcher\n\t\t\t\tdirrunsUnique = (dirruns += contextBackup == null ? 1 : Math.random() || 0.1),\n\t\t\t\tlen = elems.length;\n\n\t\t\tif ( outermost ) {\n\t\t\t\toutermostContext = context === document || context || outermost;\n\t\t\t}\n\n\t\t\t// Add elements passing elementMatchers directly to results\n\t\t\t// Support: IE<9, Safari\n\t\t\t// Tolerate NodeList properties (IE: \"length\"; Safari: <number>) matching elements by id\n\t\t\tfor ( ; i !== len && (elem = elems[i]) != null; i++ ) {\n\t\t\t\tif ( byElement && elem ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\tif ( !context && elem.ownerDocument !== document ) {\n\t\t\t\t\t\tsetDocument( elem );\n\t\t\t\t\t\txml = !documentIsHTML;\n\t\t\t\t\t}\n\t\t\t\t\twhile ( (matcher = elementMatchers[j++]) ) {\n\t\t\t\t\t\tif ( matcher( elem, context || document, xml) ) {\n\t\t\t\t\t\t\tresults.push( elem );\n\t\t\t\t\t\t\tbreak;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( outermost ) {\n\t\t\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\t// Track unmatched elements for set filters\n\t\t\t\tif ( bySet ) {\n\t\t\t\t\t// They will have gone through all possible matchers\n\t\t\t\t\tif ( (elem = !matcher && elem) ) {\n\t\t\t\t\t\tmatchedCount--;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Lengthen the array for every element, matched or not\n\t\t\t\t\tif ( seed ) {\n\t\t\t\t\t\tunmatched.push( elem );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// `i` is now the count of elements visited above, and adding it to `matchedCount`\n\t\t\t// makes the latter nonnegative.\n\t\t\tmatchedCount += i;\n\n\t\t\t// Apply set filters to unmatched elements\n\t\t\t// NOTE: This can be skipped if there are no unmatched elements (i.e., `matchedCount`\n\t\t\t// equals `i`), unless we didn't visit _any_ elements in the above loop because we have\n\t\t\t// no element matchers and no seed.\n\t\t\t// Incrementing an initially-string \"0\" `i` allows `i` to remain a string only in that\n\t\t\t// case, which will result in a \"00\" `matchedCount` that differs from `i` but is also\n\t\t\t// numerically zero.\n\t\t\tif ( bySet && i !== matchedCount ) {\n\t\t\t\tj = 0;\n\t\t\t\twhile ( (matcher = setMatchers[j++]) ) {\n\t\t\t\t\tmatcher( unmatched, setMatched, context, xml );\n\t\t\t\t}\n\n\t\t\t\tif ( seed ) {\n\t\t\t\t\t// Reintegrate element matches to eliminate the need for sorting\n\t\t\t\t\tif ( matchedCount > 0 ) {\n\t\t\t\t\t\twhile ( i-- ) {\n\t\t\t\t\t\t\tif ( !(unmatched[i] || setMatched[i]) ) {\n\t\t\t\t\t\t\t\tsetMatched[i] = pop.call( results );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Discard index placeholder values to get only actual matches\n\t\t\t\t\tsetMatched = condense( setMatched );\n\t\t\t\t}\n\n\t\t\t\t// Add matches to results\n\t\t\t\tpush.apply( results, setMatched );\n\n\t\t\t\t// Seedless set matches succeeding multiple successful matchers stipulate sorting\n\t\t\t\tif ( outermost && !seed && setMatched.length > 0 &&\n\t\t\t\t\t( matchedCount + setMatchers.length ) > 1 ) {\n\n\t\t\t\t\tSizzle.uniqueSort( results );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Override manipulation of globals by nested matchers\n\t\t\tif ( outermost ) {\n\t\t\t\tdirruns = dirrunsUnique;\n\t\t\t\toutermostContext = contextBackup;\n\t\t\t}\n\n\t\t\treturn unmatched;\n\t\t};\n\n\treturn bySet ?\n\t\tmarkFunction( superMatcher ) :\n\t\tsuperMatcher;\n}\n\ncompile = Sizzle.compile = function( selector, match /* Internal Use Only */ ) {\n\tvar i,\n\t\tsetMatchers = [],\n\t\telementMatchers = [],\n\t\tcached = compilerCache[ selector + \" \" ];\n\n\tif ( !cached ) {\n\t\t// Generate a function of recursive functions that can be used to check each element\n\t\tif ( !match ) {\n\t\t\tmatch = tokenize( selector );\n\t\t}\n\t\ti = match.length;\n\t\twhile ( i-- ) {\n\t\t\tcached = matcherFromTokens( match[i] );\n\t\t\tif ( cached[ expando ] ) {\n\t\t\t\tsetMatchers.push( cached );\n\t\t\t} else {\n\t\t\t\telementMatchers.push( cached );\n\t\t\t}\n\t\t}\n\n\t\t// Cache the compiled function\n\t\tcached = compilerCache( selector, matcherFromGroupMatchers( elementMatchers, setMatchers ) );\n\n\t\t// Save selector and tokenization\n\t\tcached.selector = selector;\n\t}\n\treturn cached;\n};\n\n/**\n * A low-level selection function that works with Sizzle's compiled\n *  selector functions\n * @param {String|Function} selector A selector or a pre-compiled\n *  selector function built with Sizzle.compile\n * @param {Element} context\n * @param {Array} [results]\n * @param {Array} [seed] A set of elements to match against\n */\nselect = Sizzle.select = function( selector, context, results, seed ) {\n\tvar i, tokens, token, type, find,\n\t\tcompiled = typeof selector === \"function\" && selector,\n\t\tmatch = !seed && tokenize( (selector = compiled.selector || selector) );\n\n\tresults = results || [];\n\n\t// Try to minimize operations if there is only one selector in the list and no seed\n\t// (the latter of which guarantees us context)\n\tif ( match.length === 1 ) {\n\n\t\t// Reduce context if the leading compound selector is an ID\n\t\ttokens = match[0] = match[0].slice( 0 );\n\t\tif ( tokens.length > 2 && (token = tokens[0]).type === \"ID\" &&\n\t\t\t\tcontext.nodeType === 9 && documentIsHTML && Expr.relative[ tokens[1].type ] ) {\n\n\t\t\tcontext = ( Expr.find[\"ID\"]( token.matches[0].replace(runescape, funescape), context ) || [] )[0];\n\t\t\tif ( !context ) {\n\t\t\t\treturn results;\n\n\t\t\t// Precompiled matchers will still verify ancestry, so step up a level\n\t\t\t} else if ( compiled ) {\n\t\t\t\tcontext = context.parentNode;\n\t\t\t}\n\n\t\t\tselector = selector.slice( tokens.shift().value.length );\n\t\t}\n\n\t\t// Fetch a seed set for right-to-left matching\n\t\ti = matchExpr[\"needsContext\"].test( selector ) ? 0 : tokens.length;\n\t\twhile ( i-- ) {\n\t\t\ttoken = tokens[i];\n\n\t\t\t// Abort if we hit a combinator\n\t\t\tif ( Expr.relative[ (type = token.type) ] ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tif ( (find = Expr.find[ type ]) ) {\n\t\t\t\t// Search, expanding context for leading sibling combinators\n\t\t\t\tif ( (seed = find(\n\t\t\t\t\ttoken.matches[0].replace( runescape, funescape ),\n\t\t\t\t\trsibling.test( tokens[0].type ) && testContext( context.parentNode ) || context\n\t\t\t\t)) ) {\n\n\t\t\t\t\t// If seed is empty or no tokens remain, we can return early\n\t\t\t\t\ttokens.splice( i, 1 );\n\t\t\t\t\tselector = seed.length && toSelector( tokens );\n\t\t\t\t\tif ( !selector ) {\n\t\t\t\t\t\tpush.apply( results, seed );\n\t\t\t\t\t\treturn results;\n\t\t\t\t\t}\n\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// Compile and execute a filtering function if one is not provided\n\t// Provide `match` to avoid retokenization if we modified the selector above\n\t( compiled || compile( selector, match ) )(\n\t\tseed,\n\t\tcontext,\n\t\t!documentIsHTML,\n\t\tresults,\n\t\t!context || rsibling.test( selector ) && testContext( context.parentNode ) || context\n\t);\n\treturn results;\n};\n\n// One-time assignments\n\n// Sort stability\nsupport.sortStable = expando.split(\"\").sort( sortOrder ).join(\"\") === expando;\n\n// Support: Chrome 14-35+\n// Always assume duplicates if they aren't passed to the comparison function\nsupport.detectDuplicates = !!hasDuplicate;\n\n// Initialize against the default document\nsetDocument();\n\n// Support: Webkit<537.32 - Safari 6.0.3/Chrome 25 (fixed in Chrome 27)\n// Detached nodes confoundingly follow *each other*\nsupport.sortDetached = assert(function( el ) {\n\t// Should return 1, but returns 4 (following)\n\treturn el.compareDocumentPosition( document.createElement(\"fieldset\") ) & 1;\n});\n\n// Support: IE<8\n// Prevent attribute/property \"interpolation\"\n// https://msdn.microsoft.com/en-us/library/ms536429%28VS.85%29.aspx\nif ( !assert(function( el ) {\n\tel.innerHTML = \"<a href='#'></a>\";\n\treturn el.firstChild.getAttribute(\"href\") === \"#\" ;\n}) ) {\n\taddHandle( \"type|href|height|width\", function( elem, name, isXML ) {\n\t\tif ( !isXML ) {\n\t\t\treturn elem.getAttribute( name, name.toLowerCase() === \"type\" ? 1 : 2 );\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use defaultValue in place of getAttribute(\"value\")\nif ( !support.attributes || !assert(function( el ) {\n\tel.innerHTML = \"<input/>\";\n\tel.firstChild.setAttribute( \"value\", \"\" );\n\treturn el.firstChild.getAttribute( \"value\" ) === \"\";\n}) ) {\n\taddHandle( \"value\", function( elem, name, isXML ) {\n\t\tif ( !isXML && elem.nodeName.toLowerCase() === \"input\" ) {\n\t\t\treturn elem.defaultValue;\n\t\t}\n\t});\n}\n\n// Support: IE<9\n// Use getAttributeNode to fetch booleans when getAttribute lies\nif ( !assert(function( el ) {\n\treturn el.getAttribute(\"disabled\") == null;\n}) ) {\n\taddHandle( booleans, function( elem, name, isXML ) {\n\t\tvar val;\n\t\tif ( !isXML ) {\n\t\t\treturn elem[ name ] === true ? name.toLowerCase() :\n\t\t\t\t\t(val = elem.getAttributeNode( name )) && val.specified ?\n\t\t\t\t\tval.value :\n\t\t\t\tnull;\n\t\t}\n\t});\n}\n\nreturn Sizzle;\n\n})( window );\n\n\n\njQuery.find = Sizzle;\njQuery.expr = Sizzle.selectors;\n\n// Deprecated\njQuery.expr[ \":\" ] = jQuery.expr.pseudos;\njQuery.uniqueSort = jQuery.unique = Sizzle.uniqueSort;\njQuery.text = Sizzle.getText;\njQuery.isXMLDoc = Sizzle.isXML;\njQuery.contains = Sizzle.contains;\njQuery.escapeSelector = Sizzle.escape;\n\n\n\n\nvar dir = function( elem, dir, until ) {\n\tvar matched = [],\n\t\ttruncate = until !== undefined;\n\n\twhile ( ( elem = elem[ dir ] ) && elem.nodeType !== 9 ) {\n\t\tif ( elem.nodeType === 1 ) {\n\t\t\tif ( truncate && jQuery( elem ).is( until ) ) {\n\t\t\t\tbreak;\n\t\t\t}\n\t\t\tmatched.push( elem );\n\t\t}\n\t}\n\treturn matched;\n};\n\n\nvar siblings = function( n, elem ) {\n\tvar matched = [];\n\n\tfor ( ; n; n = n.nextSibling ) {\n\t\tif ( n.nodeType === 1 && n !== elem ) {\n\t\t\tmatched.push( n );\n\t\t}\n\t}\n\n\treturn matched;\n};\n\n\nvar rneedsContext = jQuery.expr.match.needsContext;\n\n\n\nfunction nodeName( elem, name ) {\n\n  return elem.nodeName && elem.nodeName.toLowerCase() === name.toLowerCase();\n\n};\nvar rsingleTag = ( /^<([a-z][^\\/\\0>:\\x20\\t\\r\\n\\f]*)[\\x20\\t\\r\\n\\f]*\\/?>(?:<\\/\\1>|)$/i );\n\n\n\n// Implement the identical functionality for filter and not\nfunction winnow( elements, qualifier, not ) {\n\tif ( isFunction( qualifier ) ) {\n\t\treturn jQuery.grep( elements, function( elem, i ) {\n\t\t\treturn !!qualifier.call( elem, i, elem ) !== not;\n\t\t} );\n\t}\n\n\t// Single element\n\tif ( qualifier.nodeType ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( elem === qualifier ) !== not;\n\t\t} );\n\t}\n\n\t// Arraylike of elements (jQuery, arguments, Array)\n\tif ( typeof qualifier !== \"string\" ) {\n\t\treturn jQuery.grep( elements, function( elem ) {\n\t\t\treturn ( indexOf.call( qualifier, elem ) > -1 ) !== not;\n\t\t} );\n\t}\n\n\t// Filtered directly for both simple and complex selectors\n\treturn jQuery.filter( qualifier, elements, not );\n}\n\njQuery.filter = function( expr, elems, not ) {\n\tvar elem = elems[ 0 ];\n\n\tif ( not ) {\n\t\texpr = \":not(\" + expr + \")\";\n\t}\n\n\tif ( elems.length === 1 && elem.nodeType === 1 ) {\n\t\treturn jQuery.find.matchesSelector( elem, expr ) ? [ elem ] : [];\n\t}\n\n\treturn jQuery.find.matches( expr, jQuery.grep( elems, function( elem ) {\n\t\treturn elem.nodeType === 1;\n\t} ) );\n};\n\njQuery.fn.extend( {\n\tfind: function( selector ) {\n\t\tvar i, ret,\n\t\t\tlen = this.length,\n\t\t\tself = this;\n\n\t\tif ( typeof selector !== \"string\" ) {\n\t\t\treturn this.pushStack( jQuery( selector ).filter( function() {\n\t\t\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\t\t\tif ( jQuery.contains( self[ i ], this ) ) {\n\t\t\t\t\t\treturn true;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t} ) );\n\t\t}\n\n\t\tret = this.pushStack( [] );\n\n\t\tfor ( i = 0; i < len; i++ ) {\n\t\t\tjQuery.find( selector, self[ i ], ret );\n\t\t}\n\n\t\treturn len > 1 ? jQuery.uniqueSort( ret ) : ret;\n\t},\n\tfilter: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], false ) );\n\t},\n\tnot: function( selector ) {\n\t\treturn this.pushStack( winnow( this, selector || [], true ) );\n\t},\n\tis: function( selector ) {\n\t\treturn !!winnow(\n\t\t\tthis,\n\n\t\t\t// If this is a positional/relative selector, check membership in the returned set\n\t\t\t// so $(\"p:first\").is(\"p:last\") won't return true for a doc with two \"p\".\n\t\t\ttypeof selector === \"string\" && rneedsContext.test( selector ) ?\n\t\t\t\tjQuery( selector ) :\n\t\t\t\tselector || [],\n\t\t\tfalse\n\t\t).length;\n\t}\n} );\n\n\n// Initialize a jQuery object\n\n\n// A central reference to the root jQuery(document)\nvar rootjQuery,\n\n\t// A simple way to check for HTML strings\n\t// Prioritize #id over <tag> to avoid XSS via location.hash (#9521)\n\t// Strict HTML recognition (#11290: must start with <)\n\t// Shortcut simple #id case for speed\n\trquickExpr = /^(?:\\s*(<[\\w\\W]+>)[^>]*|#([\\w-]+))$/,\n\n\tinit = jQuery.fn.init = function( selector, context, root ) {\n\t\tvar match, elem;\n\n\t\t// HANDLE: $(\"\"), $(null), $(undefined), $(false)\n\t\tif ( !selector ) {\n\t\t\treturn this;\n\t\t}\n\n\t\t// Method init() accepts an alternate rootjQuery\n\t\t// so migrate can support jQuery.sub (gh-2101)\n\t\troot = root || rootjQuery;\n\n\t\t// Handle HTML strings\n\t\tif ( typeof selector === \"string\" ) {\n\t\t\tif ( selector[ 0 ] === \"<\" &&\n\t\t\t\tselector[ selector.length - 1 ] === \">\" &&\n\t\t\t\tselector.length >= 3 ) {\n\n\t\t\t\t// Assume that strings that start and end with <> are HTML and skip the regex check\n\t\t\t\tmatch = [ null, selector, null ];\n\n\t\t\t} else {\n\t\t\t\tmatch = rquickExpr.exec( selector );\n\t\t\t}\n\n\t\t\t// Match html or make sure no context is specified for #id\n\t\t\tif ( match && ( match[ 1 ] || !context ) ) {\n\n\t\t\t\t// HANDLE: $(html) -> $(array)\n\t\t\t\tif ( match[ 1 ] ) {\n\t\t\t\t\tcontext = context instanceof jQuery ? context[ 0 ] : context;\n\n\t\t\t\t\t// Option to run scripts is true for back-compat\n\t\t\t\t\t// Intentionally let the error be thrown if parseHTML is not present\n\t\t\t\t\tjQuery.merge( this, jQuery.parseHTML(\n\t\t\t\t\t\tmatch[ 1 ],\n\t\t\t\t\t\tcontext && context.nodeType ? context.ownerDocument || context : document,\n\t\t\t\t\t\ttrue\n\t\t\t\t\t) );\n\n\t\t\t\t\t// HANDLE: $(html, props)\n\t\t\t\t\tif ( rsingleTag.test( match[ 1 ] ) && jQuery.isPlainObject( context ) ) {\n\t\t\t\t\t\tfor ( match in context ) {\n\n\t\t\t\t\t\t\t// Properties of context are called as methods if possible\n\t\t\t\t\t\t\tif ( isFunction( this[ match ] ) ) {\n\t\t\t\t\t\t\t\tthis[ match ]( context[ match ] );\n\n\t\t\t\t\t\t\t// ...and otherwise set as attributes\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tthis.attr( match, context[ match ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\treturn this;\n\n\t\t\t\t// HANDLE: $(#id)\n\t\t\t\t} else {\n\t\t\t\t\telem = document.getElementById( match[ 2 ] );\n\n\t\t\t\t\tif ( elem ) {\n\n\t\t\t\t\t\t// Inject the element directly into the jQuery object\n\t\t\t\t\t\tthis[ 0 ] = elem;\n\t\t\t\t\t\tthis.length = 1;\n\t\t\t\t\t}\n\t\t\t\t\treturn this;\n\t\t\t\t}\n\n\t\t\t// HANDLE: $(expr, $(...))\n\t\t\t} else if ( !context || context.jquery ) {\n\t\t\t\treturn ( context || root ).find( selector );\n\n\t\t\t// HANDLE: $(expr, context)\n\t\t\t// (which is just equivalent to: $(context).find(expr)\n\t\t\t} else {\n\t\t\t\treturn this.constructor( context ).find( selector );\n\t\t\t}\n\n\t\t// HANDLE: $(DOMElement)\n\t\t} else if ( selector.nodeType ) {\n\t\t\tthis[ 0 ] = selector;\n\t\t\tthis.length = 1;\n\t\t\treturn this;\n\n\t\t// HANDLE: $(function)\n\t\t// Shortcut for document ready\n\t\t} else if ( isFunction( selector ) ) {\n\t\t\treturn root.ready !== undefined ?\n\t\t\t\troot.ready( selector ) :\n\n\t\t\t\t// Execute immediately if ready is not present\n\t\t\t\tselector( jQuery );\n\t\t}\n\n\t\treturn jQuery.makeArray( selector, this );\n\t};\n\n// Give the init function the jQuery prototype for later instantiation\ninit.prototype = jQuery.fn;\n\n// Initialize central reference\nrootjQuery = jQuery( document );\n\n\nvar rparentsprev = /^(?:parents|prev(?:Until|All))/,\n\n\t// Methods guaranteed to produce a unique set when starting from a unique set\n\tguaranteedUnique = {\n\t\tchildren: true,\n\t\tcontents: true,\n\t\tnext: true,\n\t\tprev: true\n\t};\n\njQuery.fn.extend( {\n\thas: function( target ) {\n\t\tvar targets = jQuery( target, this ),\n\t\t\tl = targets.length;\n\n\t\treturn this.filter( function() {\n\t\t\tvar i = 0;\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tif ( jQuery.contains( this, targets[ i ] ) ) {\n\t\t\t\t\treturn true;\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\tclosest: function( selectors, context ) {\n\t\tvar cur,\n\t\t\ti = 0,\n\t\t\tl = this.length,\n\t\t\tmatched = [],\n\t\t\ttargets = typeof selectors !== \"string\" && jQuery( selectors );\n\n\t\t// Positional selectors never match, since there's no _selection_ context\n\t\tif ( !rneedsContext.test( selectors ) ) {\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tfor ( cur = this[ i ]; cur && cur !== context; cur = cur.parentNode ) {\n\n\t\t\t\t\t// Always skip document fragments\n\t\t\t\t\tif ( cur.nodeType < 11 && ( targets ?\n\t\t\t\t\t\ttargets.index( cur ) > -1 :\n\n\t\t\t\t\t\t// Don't pass non-elements to Sizzle\n\t\t\t\t\t\tcur.nodeType === 1 &&\n\t\t\t\t\t\t\tjQuery.find.matchesSelector( cur, selectors ) ) ) {\n\n\t\t\t\t\t\tmatched.push( cur );\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched.length > 1 ? jQuery.uniqueSort( matched ) : matched );\n\t},\n\n\t// Determine the position of an element within the set\n\tindex: function( elem ) {\n\n\t\t// No argument, return index in parent\n\t\tif ( !elem ) {\n\t\t\treturn ( this[ 0 ] && this[ 0 ].parentNode ) ? this.first().prevAll().length : -1;\n\t\t}\n\n\t\t// Index in selector\n\t\tif ( typeof elem === \"string\" ) {\n\t\t\treturn indexOf.call( jQuery( elem ), this[ 0 ] );\n\t\t}\n\n\t\t// Locate the position of the desired element\n\t\treturn indexOf.call( this,\n\n\t\t\t// If it receives a jQuery object, the first element is used\n\t\t\telem.jquery ? elem[ 0 ] : elem\n\t\t);\n\t},\n\n\tadd: function( selector, context ) {\n\t\treturn this.pushStack(\n\t\t\tjQuery.uniqueSort(\n\t\t\t\tjQuery.merge( this.get(), jQuery( selector, context ) )\n\t\t\t)\n\t\t);\n\t},\n\n\taddBack: function( selector ) {\n\t\treturn this.add( selector == null ?\n\t\t\tthis.prevObject : this.prevObject.filter( selector )\n\t\t);\n\t}\n} );\n\nfunction sibling( cur, dir ) {\n\twhile ( ( cur = cur[ dir ] ) && cur.nodeType !== 1 ) {}\n\treturn cur;\n}\n\njQuery.each( {\n\tparent: function( elem ) {\n\t\tvar parent = elem.parentNode;\n\t\treturn parent && parent.nodeType !== 11 ? parent : null;\n\t},\n\tparents: function( elem ) {\n\t\treturn dir( elem, \"parentNode\" );\n\t},\n\tparentsUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"parentNode\", until );\n\t},\n\tnext: function( elem ) {\n\t\treturn sibling( elem, \"nextSibling\" );\n\t},\n\tprev: function( elem ) {\n\t\treturn sibling( elem, \"previousSibling\" );\n\t},\n\tnextAll: function( elem ) {\n\t\treturn dir( elem, \"nextSibling\" );\n\t},\n\tprevAll: function( elem ) {\n\t\treturn dir( elem, \"previousSibling\" );\n\t},\n\tnextUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"nextSibling\", until );\n\t},\n\tprevUntil: function( elem, i, until ) {\n\t\treturn dir( elem, \"previousSibling\", until );\n\t},\n\tsiblings: function( elem ) {\n\t\treturn siblings( ( elem.parentNode || {} ).firstChild, elem );\n\t},\n\tchildren: function( elem ) {\n\t\treturn siblings( elem.firstChild );\n\t},\n\tcontents: function( elem ) {\n\t\tif ( typeof elem.contentDocument !== \"undefined\" ) {\n\t\t\treturn elem.contentDocument;\n\t\t}\n\n\t\t// Support: IE 9 - 11 only, iOS 7 only, Android Browser <=4.3 only\n\t\t// Treat the template element as a regular one in browsers that\n\t\t// don't support it.\n\t\tif ( nodeName( elem, \"template\" ) ) {\n\t\t\telem = elem.content || elem;\n\t\t}\n\n\t\treturn jQuery.merge( [], elem.childNodes );\n\t}\n}, function( name, fn ) {\n\tjQuery.fn[ name ] = function( until, selector ) {\n\t\tvar matched = jQuery.map( this, fn, until );\n\n\t\tif ( name.slice( -5 ) !== \"Until\" ) {\n\t\t\tselector = until;\n\t\t}\n\n\t\tif ( selector && typeof selector === \"string\" ) {\n\t\t\tmatched = jQuery.filter( selector, matched );\n\t\t}\n\n\t\tif ( this.length > 1 ) {\n\n\t\t\t// Remove duplicates\n\t\t\tif ( !guaranteedUnique[ name ] ) {\n\t\t\t\tjQuery.uniqueSort( matched );\n\t\t\t}\n\n\t\t\t// Reverse order for parents* and prev-derivatives\n\t\t\tif ( rparentsprev.test( name ) ) {\n\t\t\t\tmatched.reverse();\n\t\t\t}\n\t\t}\n\n\t\treturn this.pushStack( matched );\n\t};\n} );\nvar rnothtmlwhite = ( /[^\\x20\\t\\r\\n\\f]+/g );\n\n\n\n// Convert String-formatted options into Object-formatted ones\nfunction createOptions( options ) {\n\tvar object = {};\n\tjQuery.each( options.match( rnothtmlwhite ) || [], function( _, flag ) {\n\t\tobject[ flag ] = true;\n\t} );\n\treturn object;\n}\n\n/*\n * Create a callback list using the following parameters:\n *\n *\toptions: an optional list of space-separated options that will change how\n *\t\t\tthe callback list behaves or a more traditional option object\n *\n * By default a callback list will act like an event callback list and can be\n * \"fired\" multiple times.\n *\n * Possible options:\n *\n *\tonce:\t\t\twill ensure the callback list can only be fired once (like a Deferred)\n *\n *\tmemory:\t\t\twill keep track of previous values and will call any callback added\n *\t\t\t\t\tafter the list has been fired right away with the latest \"memorized\"\n *\t\t\t\t\tvalues (like a Deferred)\n *\n *\tunique:\t\t\twill ensure a callback can only be added once (no duplicate in the list)\n *\n *\tstopOnFalse:\tinterrupt callings when a callback returns false\n *\n */\njQuery.Callbacks = function( options ) {\n\n\t// Convert options from String-formatted to Object-formatted if needed\n\t// (we check in cache first)\n\toptions = typeof options === \"string\" ?\n\t\tcreateOptions( options ) :\n\t\tjQuery.extend( {}, options );\n\n\tvar // Flag to know if list is currently firing\n\t\tfiring,\n\n\t\t// Last fire value for non-forgettable lists\n\t\tmemory,\n\n\t\t// Flag to know if list was already fired\n\t\tfired,\n\n\t\t// Flag to prevent firing\n\t\tlocked,\n\n\t\t// Actual callback list\n\t\tlist = [],\n\n\t\t// Queue of execution data for repeatable lists\n\t\tqueue = [],\n\n\t\t// Index of currently firing callback (modified by add/remove as needed)\n\t\tfiringIndex = -1,\n\n\t\t// Fire callbacks\n\t\tfire = function() {\n\n\t\t\t// Enforce single-firing\n\t\t\tlocked = locked || options.once;\n\n\t\t\t// Execute callbacks for all pending executions,\n\t\t\t// respecting firingIndex overrides and runtime changes\n\t\t\tfired = firing = true;\n\t\t\tfor ( ; queue.length; firingIndex = -1 ) {\n\t\t\t\tmemory = queue.shift();\n\t\t\t\twhile ( ++firingIndex < list.length ) {\n\n\t\t\t\t\t// Run callback and check for early termination\n\t\t\t\t\tif ( list[ firingIndex ].apply( memory[ 0 ], memory[ 1 ] ) === false &&\n\t\t\t\t\t\toptions.stopOnFalse ) {\n\n\t\t\t\t\t\t// Jump to end and forget the data so .add doesn't re-fire\n\t\t\t\t\t\tfiringIndex = list.length;\n\t\t\t\t\t\tmemory = false;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Forget the data if we're done with it\n\t\t\tif ( !options.memory ) {\n\t\t\t\tmemory = false;\n\t\t\t}\n\n\t\t\tfiring = false;\n\n\t\t\t// Clean up if we're done firing for good\n\t\t\tif ( locked ) {\n\n\t\t\t\t// Keep an empty list if we have data for future add calls\n\t\t\t\tif ( memory ) {\n\t\t\t\t\tlist = [];\n\n\t\t\t\t// Otherwise, this object is spent\n\t\t\t\t} else {\n\t\t\t\t\tlist = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t},\n\n\t\t// Actual Callbacks object\n\t\tself = {\n\n\t\t\t// Add a callback or a collection of callbacks to the list\n\t\t\tadd: function() {\n\t\t\t\tif ( list ) {\n\n\t\t\t\t\t// If we have memory from a past run, we should fire after adding\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfiringIndex = list.length - 1;\n\t\t\t\t\t\tqueue.push( memory );\n\t\t\t\t\t}\n\n\t\t\t\t\t( function add( args ) {\n\t\t\t\t\t\tjQuery.each( args, function( _, arg ) {\n\t\t\t\t\t\t\tif ( isFunction( arg ) ) {\n\t\t\t\t\t\t\t\tif ( !options.unique || !self.has( arg ) ) {\n\t\t\t\t\t\t\t\t\tlist.push( arg );\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} else if ( arg && arg.length && toType( arg ) !== \"string\" ) {\n\n\t\t\t\t\t\t\t\t// Inspect recursively\n\t\t\t\t\t\t\t\tadd( arg );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} );\n\t\t\t\t\t} )( arguments );\n\n\t\t\t\t\tif ( memory && !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Remove a callback from the list\n\t\t\tremove: function() {\n\t\t\t\tjQuery.each( arguments, function( _, arg ) {\n\t\t\t\t\tvar index;\n\t\t\t\t\twhile ( ( index = jQuery.inArray( arg, list, index ) ) > -1 ) {\n\t\t\t\t\t\tlist.splice( index, 1 );\n\n\t\t\t\t\t\t// Handle firing indexes\n\t\t\t\t\t\tif ( index <= firingIndex ) {\n\t\t\t\t\t\t\tfiringIndex--;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Check if a given callback is in the list.\n\t\t\t// If no argument is given, return whether or not list has callbacks attached.\n\t\t\thas: function( fn ) {\n\t\t\t\treturn fn ?\n\t\t\t\t\tjQuery.inArray( fn, list ) > -1 :\n\t\t\t\t\tlist.length > 0;\n\t\t\t},\n\n\t\t\t// Remove all callbacks from the list\n\t\t\tempty: function() {\n\t\t\t\tif ( list ) {\n\t\t\t\t\tlist = [];\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Disable .fire and .add\n\t\t\t// Abort any current/pending executions\n\t\t\t// Clear all callbacks and values\n\t\t\tdisable: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tlist = memory = \"\";\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tdisabled: function() {\n\t\t\t\treturn !list;\n\t\t\t},\n\n\t\t\t// Disable .fire\n\t\t\t// Also disable .add unless we have memory (since it would have no effect)\n\t\t\t// Abort any pending executions\n\t\t\tlock: function() {\n\t\t\t\tlocked = queue = [];\n\t\t\t\tif ( !memory && !firing ) {\n\t\t\t\t\tlist = memory = \"\";\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\t\t\tlocked: function() {\n\t\t\t\treturn !!locked;\n\t\t\t},\n\n\t\t\t// Call all callbacks with the given context and arguments\n\t\t\tfireWith: function( context, args ) {\n\t\t\t\tif ( !locked ) {\n\t\t\t\t\targs = args || [];\n\t\t\t\t\targs = [ context, args.slice ? args.slice() : args ];\n\t\t\t\t\tqueue.push( args );\n\t\t\t\t\tif ( !firing ) {\n\t\t\t\t\t\tfire();\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// Call all the callbacks with the given arguments\n\t\t\tfire: function() {\n\t\t\t\tself.fireWith( this, arguments );\n\t\t\t\treturn this;\n\t\t\t},\n\n\t\t\t// To know if the callbacks have already been called at least once\n\t\t\tfired: function() {\n\t\t\t\treturn !!fired;\n\t\t\t}\n\t\t};\n\n\treturn self;\n};\n\n\nfunction Identity( v ) {\n\treturn v;\n}\nfunction Thrower( ex ) {\n\tthrow ex;\n}\n\nfunction adoptValue( value, resolve, reject, noValue ) {\n\tvar method;\n\n\ttry {\n\n\t\t// Check for promise aspect first to privilege synchronous behavior\n\t\tif ( value && isFunction( ( method = value.promise ) ) ) {\n\t\t\tmethod.call( value ).done( resolve ).fail( reject );\n\n\t\t// Other thenables\n\t\t} else if ( value && isFunction( ( method = value.then ) ) ) {\n\t\t\tmethod.call( value, resolve, reject );\n\n\t\t// Other non-thenables\n\t\t} else {\n\n\t\t\t// Control `resolve` arguments by letting Array#slice cast boolean `noValue` to integer:\n\t\t\t// * false: [ value ].slice( 0 ) => resolve( value )\n\t\t\t// * true: [ value ].slice( 1 ) => resolve()\n\t\t\tresolve.apply( undefined, [ value ].slice( noValue ) );\n\t\t}\n\n\t// For Promises/A+, convert exceptions into rejections\n\t// Since jQuery.when doesn't unwrap thenables, we can skip the extra checks appearing in\n\t// Deferred#then to conditionally suppress rejection.\n\t} catch ( value ) {\n\n\t\t// Support: Android 4.0 only\n\t\t// Strict mode functions invoked without .call/.apply get global-object context\n\t\treject.apply( undefined, [ value ] );\n\t}\n}\n\njQuery.extend( {\n\n\tDeferred: function( func ) {\n\t\tvar tuples = [\n\n\t\t\t\t// action, add listener, callbacks,\n\t\t\t\t// ... .then handlers, argument index, [final state]\n\t\t\t\t[ \"notify\", \"progress\", jQuery.Callbacks( \"memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"memory\" ), 2 ],\n\t\t\t\t[ \"resolve\", \"done\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 0, \"resolved\" ],\n\t\t\t\t[ \"reject\", \"fail\", jQuery.Callbacks( \"once memory\" ),\n\t\t\t\t\tjQuery.Callbacks( \"once memory\" ), 1, \"rejected\" ]\n\t\t\t],\n\t\t\tstate = \"pending\",\n\t\t\tpromise = {\n\t\t\t\tstate: function() {\n\t\t\t\t\treturn state;\n\t\t\t\t},\n\t\t\t\talways: function() {\n\t\t\t\t\tdeferred.done( arguments ).fail( arguments );\n\t\t\t\t\treturn this;\n\t\t\t\t},\n\t\t\t\t\"catch\": function( fn ) {\n\t\t\t\t\treturn promise.then( null, fn );\n\t\t\t\t},\n\n\t\t\t\t// Keep pipe for back-compat\n\t\t\t\tpipe: function( /* fnDone, fnFail, fnProgress */ ) {\n\t\t\t\t\tvar fns = arguments;\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\t\t\t\t\t\tjQuery.each( tuples, function( i, tuple ) {\n\n\t\t\t\t\t\t\t// Map tuples (progress, done, fail) to arguments (done, fail, progress)\n\t\t\t\t\t\t\tvar fn = isFunction( fns[ tuple[ 4 ] ] ) && fns[ tuple[ 4 ] ];\n\n\t\t\t\t\t\t\t// deferred.progress(function() { bind to newDefer or newDefer.notify })\n\t\t\t\t\t\t\t// deferred.done(function() { bind to newDefer or newDefer.resolve })\n\t\t\t\t\t\t\t// deferred.fail(function() { bind to newDefer or newDefer.reject })\n\t\t\t\t\t\t\tdeferred[ tuple[ 1 ] ]( function() {\n\t\t\t\t\t\t\t\tvar returned = fn && fn.apply( this, arguments );\n\t\t\t\t\t\t\t\tif ( returned && isFunction( returned.promise ) ) {\n\t\t\t\t\t\t\t\t\treturned.promise()\n\t\t\t\t\t\t\t\t\t\t.progress( newDefer.notify )\n\t\t\t\t\t\t\t\t\t\t.done( newDefer.resolve )\n\t\t\t\t\t\t\t\t\t\t.fail( newDefer.reject );\n\t\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\t\tnewDefer[ tuple[ 0 ] + \"With\" ](\n\t\t\t\t\t\t\t\t\t\tthis,\n\t\t\t\t\t\t\t\t\t\tfn ? [ returned ] : arguments\n\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t} );\n\t\t\t\t\t\tfns = null;\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\t\t\t\tthen: function( onFulfilled, onRejected, onProgress ) {\n\t\t\t\t\tvar maxDepth = 0;\n\t\t\t\t\tfunction resolve( depth, deferred, handler, special ) {\n\t\t\t\t\t\treturn function() {\n\t\t\t\t\t\t\tvar that = this,\n\t\t\t\t\t\t\t\targs = arguments,\n\t\t\t\t\t\t\t\tmightThrow = function() {\n\t\t\t\t\t\t\t\t\tvar returned, then;\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.3\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-59\n\t\t\t\t\t\t\t\t\t// Ignore double-resolution attempts\n\t\t\t\t\t\t\t\t\tif ( depth < maxDepth ) {\n\t\t\t\t\t\t\t\t\t\treturn;\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\treturned = handler.apply( that, args );\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.1\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-48\n\t\t\t\t\t\t\t\t\tif ( returned === deferred.promise() ) {\n\t\t\t\t\t\t\t\t\t\tthrow new TypeError( \"Thenable self-resolution\" );\n\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Support: Promises/A+ sections 2.3.3.1, 3.5\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-54\n\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-75\n\t\t\t\t\t\t\t\t\t// Retrieve `then` only once\n\t\t\t\t\t\t\t\t\tthen = returned &&\n\n\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.4\n\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-64\n\t\t\t\t\t\t\t\t\t\t// Only check objects and functions for thenability\n\t\t\t\t\t\t\t\t\t\t( typeof returned === \"object\" ||\n\t\t\t\t\t\t\t\t\t\t\ttypeof returned === \"function\" ) &&\n\t\t\t\t\t\t\t\t\t\treturned.then;\n\n\t\t\t\t\t\t\t\t\t// Handle a returned thenable\n\t\t\t\t\t\t\t\t\tif ( isFunction( then ) ) {\n\n\t\t\t\t\t\t\t\t\t\t// Special processors (notify) just wait for resolution\n\t\t\t\t\t\t\t\t\t\tif ( special ) {\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special )\n\t\t\t\t\t\t\t\t\t\t\t);\n\n\t\t\t\t\t\t\t\t\t\t// Normal processors (resolve) also hook into progress\n\t\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t\t// ...and disregard older resolution values\n\t\t\t\t\t\t\t\t\t\t\tmaxDepth++;\n\n\t\t\t\t\t\t\t\t\t\t\tthen.call(\n\t\t\t\t\t\t\t\t\t\t\t\treturned,\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Thrower, special ),\n\t\t\t\t\t\t\t\t\t\t\t\tresolve( maxDepth, deferred, Identity,\n\t\t\t\t\t\t\t\t\t\t\t\t\tdeferred.notifyWith )\n\t\t\t\t\t\t\t\t\t\t\t);\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t// Handle all other returned values\n\t\t\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\tif ( handler !== Identity ) {\n\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\targs = [ returned ];\n\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t// Process the value(s)\n\t\t\t\t\t\t\t\t\t\t// Default process is resolve\n\t\t\t\t\t\t\t\t\t\t( special || deferred.resolveWith )( that, args );\n\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t},\n\n\t\t\t\t\t\t\t\t// Only normal processors (resolve) catch and reject exceptions\n\t\t\t\t\t\t\t\tprocess = special ?\n\t\t\t\t\t\t\t\t\tmightThrow :\n\t\t\t\t\t\t\t\t\tfunction() {\n\t\t\t\t\t\t\t\t\t\ttry {\n\t\t\t\t\t\t\t\t\t\t\tmightThrow();\n\t\t\t\t\t\t\t\t\t\t} catch ( e ) {\n\n\t\t\t\t\t\t\t\t\t\t\tif ( jQuery.Deferred.exceptionHook ) {\n\t\t\t\t\t\t\t\t\t\t\t\tjQuery.Deferred.exceptionHook( e,\n\t\t\t\t\t\t\t\t\t\t\t\t\tprocess.stackTrace );\n\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.4.1\n\t\t\t\t\t\t\t\t\t\t\t// https://promisesaplus.com/#point-61\n\t\t\t\t\t\t\t\t\t\t\t// Ignore post-resolution exceptions\n\t\t\t\t\t\t\t\t\t\t\tif ( depth + 1 >= maxDepth ) {\n\n\t\t\t\t\t\t\t\t\t\t\t\t// Only substitute handlers pass on context\n\t\t\t\t\t\t\t\t\t\t\t\t// and multiple values (non-spec behavior)\n\t\t\t\t\t\t\t\t\t\t\t\tif ( handler !== Thrower ) {\n\t\t\t\t\t\t\t\t\t\t\t\t\tthat = undefined;\n\t\t\t\t\t\t\t\t\t\t\t\t\targs = [ e ];\n\t\t\t\t\t\t\t\t\t\t\t\t}\n\n\t\t\t\t\t\t\t\t\t\t\t\tdeferred.rejectWith( that, args );\n\t\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\t\t};\n\n\t\t\t\t\t\t\t// Support: Promises/A+ section 2.3.3.3.1\n\t\t\t\t\t\t\t// https://promisesaplus.com/#point-57\n\t\t\t\t\t\t\t// Re-resolve promises immediately to dodge false rejection from\n\t\t\t\t\t\t\t// subsequent errors\n\t\t\t\t\t\t\tif ( depth ) {\n\t\t\t\t\t\t\t\tprocess();\n\t\t\t\t\t\t\t} else {\n\n\t\t\t\t\t\t\t\t// Call an optional hook to record the stack, in case of exception\n\t\t\t\t\t\t\t\t// since it's otherwise lost when execution goes async\n\t\t\t\t\t\t\t\tif ( jQuery.Deferred.getStackHook ) {\n\t\t\t\t\t\t\t\t\tprocess.stackTrace = jQuery.Deferred.getStackHook();\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t\twindow.setTimeout( process );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t};\n\t\t\t\t\t}\n\n\t\t\t\t\treturn jQuery.Deferred( function( newDefer ) {\n\n\t\t\t\t\t\t// progress_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 0 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onProgress ) ?\n\t\t\t\t\t\t\t\t\tonProgress :\n\t\t\t\t\t\t\t\t\tIdentity,\n\t\t\t\t\t\t\t\tnewDefer.notifyWith\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// fulfilled_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 1 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onFulfilled ) ?\n\t\t\t\t\t\t\t\t\tonFulfilled :\n\t\t\t\t\t\t\t\t\tIdentity\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\n\t\t\t\t\t\t// rejected_handlers.add( ... )\n\t\t\t\t\t\ttuples[ 2 ][ 3 ].add(\n\t\t\t\t\t\t\tresolve(\n\t\t\t\t\t\t\t\t0,\n\t\t\t\t\t\t\t\tnewDefer,\n\t\t\t\t\t\t\t\tisFunction( onRejected ) ?\n\t\t\t\t\t\t\t\t\tonRejected :\n\t\t\t\t\t\t\t\t\tThrower\n\t\t\t\t\t\t\t)\n\t\t\t\t\t\t);\n\t\t\t\t\t} ).promise();\n\t\t\t\t},\n\n\t\t\t\t// Get a promise for this deferred\n\t\t\t\t// If obj is provided, the promise aspect is added to the object\n\t\t\t\tpromise: function( obj ) {\n\t\t\t\t\treturn obj != null ? jQuery.extend( obj, promise ) : promise;\n\t\t\t\t}\n\t\t\t},\n\t\t\tdeferred = {};\n\n\t\t// Add list-specific methods\n\t\tjQuery.each( tuples, function( i, tuple ) {\n\t\t\tvar list = tuple[ 2 ],\n\t\t\t\tstateString = tuple[ 5 ];\n\n\t\t\t// promise.progress = list.add\n\t\t\t// promise.done = list.add\n\t\t\t// promise.fail = list.add\n\t\t\tpromise[ tuple[ 1 ] ] = list.add;\n\n\t\t\t// Handle state\n\t\t\tif ( stateString ) {\n\t\t\t\tlist.add(\n\t\t\t\t\tfunction() {\n\n\t\t\t\t\t\t// state = \"resolved\" (i.e., fulfilled)\n\t\t\t\t\t\t// state = \"rejected\"\n\t\t\t\t\t\tstate = stateString;\n\t\t\t\t\t},\n\n\t\t\t\t\t// rejected_callbacks.disable\n\t\t\t\t\t// fulfilled_callbacks.disable\n\t\t\t\t\ttuples[ 3 - i ][ 2 ].disable,\n\n\t\t\t\t\t// rejected_handlers.disable\n\t\t\t\t\t// fulfilled_handlers.disable\n\t\t\t\t\ttuples[ 3 - i ][ 3 ].disable,\n\n\t\t\t\t\t// progress_callbacks.lock\n\t\t\t\t\ttuples[ 0 ][ 2 ].lock,\n\n\t\t\t\t\t// progress_handlers.lock\n\t\t\t\t\ttuples[ 0 ][ 3 ].lock\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// progress_handlers.fire\n\t\t\t// fulfilled_handlers.fire\n\t\t\t// rejected_handlers.fire\n\t\t\tlist.add( tuple[ 3 ].fire );\n\n\t\t\t// deferred.notify = function() { deferred.notifyWith(...) }\n\t\t\t// deferred.resolve = function() { deferred.resolveWith(...) }\n\t\t\t// deferred.reject = function() { deferred.rejectWith(...) }\n\t\t\tdeferred[ tuple[ 0 ] ] = function() {\n\t\t\t\tdeferred[ tuple[ 0 ] + \"With\" ]( this === deferred ? undefined : this, arguments );\n\t\t\t\treturn this;\n\t\t\t};\n\n\t\t\t// deferred.notifyWith = list.fireWith\n\t\t\t// deferred.resolveWith = list.fireWith\n\t\t\t// deferred.rejectWith = list.fireWith\n\t\t\tdeferred[ tuple[ 0 ] + \"With\" ] = list.fireWith;\n\t\t} );\n\n\t\t// Make the deferred a promise\n\t\tpromise.promise( deferred );\n\n\t\t// Call given func if any\n\t\tif ( func ) {\n\t\t\tfunc.call( deferred, deferred );\n\t\t}\n\n\t\t// All done!\n\t\treturn deferred;\n\t},\n\n\t// Deferred helper\n\twhen: function( singleValue ) {\n\t\tvar\n\n\t\t\t// count of uncompleted subordinates\n\t\t\tremaining = arguments.length,\n\n\t\t\t// count of unprocessed arguments\n\t\t\ti = remaining,\n\n\t\t\t// subordinate fulfillment data\n\t\t\tresolveContexts = Array( i ),\n\t\t\tresolveValues = slice.call( arguments ),\n\n\t\t\t// the master Deferred\n\t\t\tmaster = jQuery.Deferred(),\n\n\t\t\t// subordinate callback factory\n\t\t\tupdateFunc = function( i ) {\n\t\t\t\treturn function( value ) {\n\t\t\t\t\tresolveContexts[ i ] = this;\n\t\t\t\t\tresolveValues[ i ] = arguments.length > 1 ? slice.call( arguments ) : value;\n\t\t\t\t\tif ( !( --remaining ) ) {\n\t\t\t\t\t\tmaster.resolveWith( resolveContexts, resolveValues );\n\t\t\t\t\t}\n\t\t\t\t};\n\t\t\t};\n\n\t\t// Single- and empty arguments are adopted like Promise.resolve\n\t\tif ( remaining <= 1 ) {\n\t\t\tadoptValue( singleValue, master.done( updateFunc( i ) ).resolve, master.reject,\n\t\t\t\t!remaining );\n\n\t\t\t// Use .then() to unwrap secondary thenables (cf. gh-3000)\n\t\t\tif ( master.state() === \"pending\" ||\n\t\t\t\tisFunction( resolveValues[ i ] && resolveValues[ i ].then ) ) {\n\n\t\t\t\treturn master.then();\n\t\t\t}\n\t\t}\n\n\t\t// Multiple arguments are aggregated like Promise.all array elements\n\t\twhile ( i-- ) {\n\t\t\tadoptValue( resolveValues[ i ], updateFunc( i ), master.reject );\n\t\t}\n\n\t\treturn master.promise();\n\t}\n} );\n\n\n// These usually indicate a programmer mistake during development,\n// warn about them ASAP rather than swallowing them by default.\nvar rerrorNames = /^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/;\n\njQuery.Deferred.exceptionHook = function( error, stack ) {\n\n\t// Support: IE 8 - 9 only\n\t// Console exists when dev tools are open, which can happen at any time\n\tif ( window.console && window.console.warn && error && rerrorNames.test( error.name ) ) {\n\t\twindow.console.warn( \"jQuery.Deferred exception: \" + error.message, error.stack, stack );\n\t}\n};\n\n\n\n\njQuery.readyException = function( error ) {\n\twindow.setTimeout( function() {\n\t\tthrow error;\n\t} );\n};\n\n\n\n\n// The deferred used on DOM ready\nvar readyList = jQuery.Deferred();\n\njQuery.fn.ready = function( fn ) {\n\n\treadyList\n\t\t.then( fn )\n\n\t\t// Wrap jQuery.readyException in a function so that the lookup\n\t\t// happens at the time of error handling instead of callback\n\t\t// registration.\n\t\t.catch( function( error ) {\n\t\t\tjQuery.readyException( error );\n\t\t} );\n\n\treturn this;\n};\n\njQuery.extend( {\n\n\t// Is the DOM ready to be used? Set to true once it occurs.\n\tisReady: false,\n\n\t// A counter to track how many items to wait for before\n\t// the ready event fires. See #6781\n\treadyWait: 1,\n\n\t// Handle when the DOM is ready\n\tready: function( wait ) {\n\n\t\t// Abort if there are pending holds or we're already ready\n\t\tif ( wait === true ? --jQuery.readyWait : jQuery.isReady ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Remember that the DOM is ready\n\t\tjQuery.isReady = true;\n\n\t\t// If a normal DOM Ready event fired, decrement, and wait if need be\n\t\tif ( wait !== true && --jQuery.readyWait > 0 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// If there are functions bound, to execute\n\t\treadyList.resolveWith( document, [ jQuery ] );\n\t}\n} );\n\njQuery.ready.then = readyList.then;\n\n// The ready event handler and self cleanup method\nfunction completed() {\n\tdocument.removeEventListener( \"DOMContentLoaded\", completed );\n\twindow.removeEventListener( \"load\", completed );\n\tjQuery.ready();\n}\n\n// Catch cases where $(document).ready() is called\n// after the browser event has already occurred.\n// Support: IE <=9 - 10 only\n// Older IE sometimes signals \"interactive\" too soon\nif ( document.readyState === \"complete\" ||\n\t( document.readyState !== \"loading\" && !document.documentElement.doScroll ) ) {\n\n\t// Handle it asynchronously to allow scripts the opportunity to delay ready\n\twindow.setTimeout( jQuery.ready );\n\n} else {\n\n\t// Use the handy event callback\n\tdocument.addEventListener( \"DOMContentLoaded\", completed );\n\n\t// A fallback to window.onload, that will always work\n\twindow.addEventListener( \"load\", completed );\n}\n\n\n\n\n// Multifunctional method to get and set values of a collection\n// The value/s can optionally be executed if it's a function\nvar access = function( elems, fn, key, value, chainable, emptyGet, raw ) {\n\tvar i = 0,\n\t\tlen = elems.length,\n\t\tbulk = key == null;\n\n\t// Sets many values\n\tif ( toType( key ) === \"object\" ) {\n\t\tchainable = true;\n\t\tfor ( i in key ) {\n\t\t\taccess( elems, fn, i, key[ i ], true, emptyGet, raw );\n\t\t}\n\n\t// Sets one value\n\t} else if ( value !== undefined ) {\n\t\tchainable = true;\n\n\t\tif ( !isFunction( value ) ) {\n\t\t\traw = true;\n\t\t}\n\n\t\tif ( bulk ) {\n\n\t\t\t// Bulk operations run against the entire set\n\t\t\tif ( raw ) {\n\t\t\t\tfn.call( elems, value );\n\t\t\t\tfn = null;\n\n\t\t\t// ...except when executing function values\n\t\t\t} else {\n\t\t\t\tbulk = fn;\n\t\t\t\tfn = function( elem, key, value ) {\n\t\t\t\t\treturn bulk.call( jQuery( elem ), value );\n\t\t\t\t};\n\t\t\t}\n\t\t}\n\n\t\tif ( fn ) {\n\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\tfn(\n\t\t\t\t\telems[ i ], key, raw ?\n\t\t\t\t\tvalue :\n\t\t\t\t\tvalue.call( elems[ i ], i, fn( elems[ i ], key ) )\n\t\t\t\t);\n\t\t\t}\n\t\t}\n\t}\n\n\tif ( chainable ) {\n\t\treturn elems;\n\t}\n\n\t// Gets\n\tif ( bulk ) {\n\t\treturn fn.call( elems );\n\t}\n\n\treturn len ? fn( elems[ 0 ], key ) : emptyGet;\n};\n\n\n// Matches dashed string for camelizing\nvar rmsPrefix = /^-ms-/,\n\trdashAlpha = /-([a-z])/g;\n\n// Used by camelCase as callback to replace()\nfunction fcamelCase( all, letter ) {\n\treturn letter.toUpperCase();\n}\n\n// Convert dashed to camelCase; used by the css and data modules\n// Support: IE <=9 - 11, Edge 12 - 15\n// Microsoft forgot to hump their vendor prefix (#9572)\nfunction camelCase( string ) {\n\treturn string.replace( rmsPrefix, \"ms-\" ).replace( rdashAlpha, fcamelCase );\n}\nvar acceptData = function( owner ) {\n\n\t// Accepts only:\n\t//  - Node\n\t//    - Node.ELEMENT_NODE\n\t//    - Node.DOCUMENT_NODE\n\t//  - Object\n\t//    - Any\n\treturn owner.nodeType === 1 || owner.nodeType === 9 || !( +owner.nodeType );\n};\n\n\n\n\nfunction Data() {\n\tthis.expando = jQuery.expando + Data.uid++;\n}\n\nData.uid = 1;\n\nData.prototype = {\n\n\tcache: function( owner ) {\n\n\t\t// Check if the owner object already has a cache\n\t\tvar value = owner[ this.expando ];\n\n\t\t// If not, create one\n\t\tif ( !value ) {\n\t\t\tvalue = {};\n\n\t\t\t// We can accept data for non-element nodes in modern browsers,\n\t\t\t// but we should not, see #8335.\n\t\t\t// Always return an empty object.\n\t\t\tif ( acceptData( owner ) ) {\n\n\t\t\t\t// If it is a node unlikely to be stringify-ed or looped over\n\t\t\t\t// use plain assignment\n\t\t\t\tif ( owner.nodeType ) {\n\t\t\t\t\towner[ this.expando ] = value;\n\n\t\t\t\t// Otherwise secure it in a non-enumerable property\n\t\t\t\t// configurable must be true to allow the property to be\n\t\t\t\t// deleted when data is removed\n\t\t\t\t} else {\n\t\t\t\t\tObject.defineProperty( owner, this.expando, {\n\t\t\t\t\t\tvalue: value,\n\t\t\t\t\t\tconfigurable: true\n\t\t\t\t\t} );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn value;\n\t},\n\tset: function( owner, data, value ) {\n\t\tvar prop,\n\t\t\tcache = this.cache( owner );\n\n\t\t// Handle: [ owner, key, value ] args\n\t\t// Always use camelCase key (gh-2257)\n\t\tif ( typeof data === \"string\" ) {\n\t\t\tcache[ camelCase( data ) ] = value;\n\n\t\t// Handle: [ owner, { properties } ] args\n\t\t} else {\n\n\t\t\t// Copy the properties one-by-one to the cache object\n\t\t\tfor ( prop in data ) {\n\t\t\t\tcache[ camelCase( prop ) ] = data[ prop ];\n\t\t\t}\n\t\t}\n\t\treturn cache;\n\t},\n\tget: function( owner, key ) {\n\t\treturn key === undefined ?\n\t\t\tthis.cache( owner ) :\n\n\t\t\t// Always use camelCase key (gh-2257)\n\t\t\towner[ this.expando ] && owner[ this.expando ][ camelCase( key ) ];\n\t},\n\taccess: function( owner, key, value ) {\n\n\t\t// In cases where either:\n\t\t//\n\t\t//   1. No key was specified\n\t\t//   2. A string key was specified, but no value provided\n\t\t//\n\t\t// Take the \"read\" path and allow the get method to determine\n\t\t// which value to return, respectively either:\n\t\t//\n\t\t//   1. The entire cache object\n\t\t//   2. The data stored at the key\n\t\t//\n\t\tif ( key === undefined ||\n\t\t\t\t( ( key && typeof key === \"string\" ) && value === undefined ) ) {\n\n\t\t\treturn this.get( owner, key );\n\t\t}\n\n\t\t// When the key is not a string, or both a key and value\n\t\t// are specified, set or extend (existing objects) with either:\n\t\t//\n\t\t//   1. An object of properties\n\t\t//   2. A key and value\n\t\t//\n\t\tthis.set( owner, key, value );\n\n\t\t// Since the \"set\" path can have two possible entry points\n\t\t// return the expected data based on which path was taken[*]\n\t\treturn value !== undefined ? value : key;\n\t},\n\tremove: function( owner, key ) {\n\t\tvar i,\n\t\t\tcache = owner[ this.expando ];\n\n\t\tif ( cache === undefined ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( key !== undefined ) {\n\n\t\t\t// Support array or space separated string of keys\n\t\t\tif ( Array.isArray( key ) ) {\n\n\t\t\t\t// If key is an array of keys...\n\t\t\t\t// We always set camelCase keys, so remove that.\n\t\t\t\tkey = key.map( camelCase );\n\t\t\t} else {\n\t\t\t\tkey = camelCase( key );\n\n\t\t\t\t// If a key with the spaces exists, use it.\n\t\t\t\t// Otherwise, create an array by matching non-whitespace\n\t\t\t\tkey = key in cache ?\n\t\t\t\t\t[ key ] :\n\t\t\t\t\t( key.match( rnothtmlwhite ) || [] );\n\t\t\t}\n\n\t\t\ti = key.length;\n\n\t\t\twhile ( i-- ) {\n\t\t\t\tdelete cache[ key[ i ] ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove the expando if there's no more data\n\t\tif ( key === undefined || jQuery.isEmptyObject( cache ) ) {\n\n\t\t\t// Support: Chrome <=35 - 45\n\t\t\t// Webkit & Blink performance suffers when deleting properties\n\t\t\t// from DOM nodes, so set to undefined instead\n\t\t\t// https://bugs.chromium.org/p/chromium/issues/detail?id=378607 (bug restricted)\n\t\t\tif ( owner.nodeType ) {\n\t\t\t\towner[ this.expando ] = undefined;\n\t\t\t} else {\n\t\t\t\tdelete owner[ this.expando ];\n\t\t\t}\n\t\t}\n\t},\n\thasData: function( owner ) {\n\t\tvar cache = owner[ this.expando ];\n\t\treturn cache !== undefined && !jQuery.isEmptyObject( cache );\n\t}\n};\nvar dataPriv = new Data();\n\nvar dataUser = new Data();\n\n\n\n//\tImplementation Summary\n//\n//\t1. Enforce API surface and semantic compatibility with 1.9.x branch\n//\t2. Improve the module's maintainability by reducing the storage\n//\t\tpaths to a single mechanism.\n//\t3. Use the same single mechanism to support \"private\" and \"user\" data.\n//\t4. _Never_ expose \"private\" data to user code (TODO: Drop _data, _removeData)\n//\t5. Avoid exposing implementation details on user objects (eg. expando properties)\n//\t6. Provide a clear path for implementation upgrade to WeakMap in 2014\n\nvar rbrace = /^(?:\\{[\\w\\W]*\\}|\\[[\\w\\W]*\\])$/,\n\trmultiDash = /[A-Z]/g;\n\nfunction getData( data ) {\n\tif ( data === \"true\" ) {\n\t\treturn true;\n\t}\n\n\tif ( data === \"false\" ) {\n\t\treturn false;\n\t}\n\n\tif ( data === \"null\" ) {\n\t\treturn null;\n\t}\n\n\t// Only convert to a number if it doesn't change the string\n\tif ( data === +data + \"\" ) {\n\t\treturn +data;\n\t}\n\n\tif ( rbrace.test( data ) ) {\n\t\treturn JSON.parse( data );\n\t}\n\n\treturn data;\n}\n\nfunction dataAttr( elem, key, data ) {\n\tvar name;\n\n\t// If nothing was found internally, try to fetch any\n\t// data from the HTML5 data-* attribute\n\tif ( data === undefined && elem.nodeType === 1 ) {\n\t\tname = \"data-\" + key.replace( rmultiDash, \"-$&\" ).toLowerCase();\n\t\tdata = elem.getAttribute( name );\n\n\t\tif ( typeof data === \"string\" ) {\n\t\t\ttry {\n\t\t\t\tdata = getData( data );\n\t\t\t} catch ( e ) {}\n\n\t\t\t// Make sure we set the data so it isn't changed later\n\t\t\tdataUser.set( elem, key, data );\n\t\t} else {\n\t\t\tdata = undefined;\n\t\t}\n\t}\n\treturn data;\n}\n\njQuery.extend( {\n\thasData: function( elem ) {\n\t\treturn dataUser.hasData( elem ) || dataPriv.hasData( elem );\n\t},\n\n\tdata: function( elem, name, data ) {\n\t\treturn dataUser.access( elem, name, data );\n\t},\n\n\tremoveData: function( elem, name ) {\n\t\tdataUser.remove( elem, name );\n\t},\n\n\t// TODO: Now that all calls to _data and _removeData have been replaced\n\t// with direct calls to dataPriv methods, these can be deprecated.\n\t_data: function( elem, name, data ) {\n\t\treturn dataPriv.access( elem, name, data );\n\t},\n\n\t_removeData: function( elem, name ) {\n\t\tdataPriv.remove( elem, name );\n\t}\n} );\n\njQuery.fn.extend( {\n\tdata: function( key, value ) {\n\t\tvar i, name, data,\n\t\t\telem = this[ 0 ],\n\t\t\tattrs = elem && elem.attributes;\n\n\t\t// Gets all values\n\t\tif ( key === undefined ) {\n\t\t\tif ( this.length ) {\n\t\t\t\tdata = dataUser.get( elem );\n\n\t\t\t\tif ( elem.nodeType === 1 && !dataPriv.get( elem, \"hasDataAttrs\" ) ) {\n\t\t\t\t\ti = attrs.length;\n\t\t\t\t\twhile ( i-- ) {\n\n\t\t\t\t\t\t// Support: IE 11 only\n\t\t\t\t\t\t// The attrs elements can be null (#14894)\n\t\t\t\t\t\tif ( attrs[ i ] ) {\n\t\t\t\t\t\t\tname = attrs[ i ].name;\n\t\t\t\t\t\t\tif ( name.indexOf( \"data-\" ) === 0 ) {\n\t\t\t\t\t\t\t\tname = camelCase( name.slice( 5 ) );\n\t\t\t\t\t\t\t\tdataAttr( elem, name, data[ name ] );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tdataPriv.set( elem, \"hasDataAttrs\", true );\n\t\t\t\t}\n\t\t\t}\n\n\t\t\treturn data;\n\t\t}\n\n\t\t// Sets multiple values\n\t\tif ( typeof key === \"object\" ) {\n\t\t\treturn this.each( function() {\n\t\t\t\tdataUser.set( this, key );\n\t\t\t} );\n\t\t}\n\n\t\treturn access( this, function( value ) {\n\t\t\tvar data;\n\n\t\t\t// The calling jQuery object (element matches) is not empty\n\t\t\t// (and therefore has an element appears at this[ 0 ]) and the\n\t\t\t// `value` parameter was not undefined. An empty jQuery object\n\t\t\t// will result in `undefined` for elem = this[ 0 ] which will\n\t\t\t// throw an exception if an attempt to read a data cache is made.\n\t\t\tif ( elem && value === undefined ) {\n\n\t\t\t\t// Attempt to get data from the cache\n\t\t\t\t// The key will always be camelCased in Data\n\t\t\t\tdata = dataUser.get( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// Attempt to \"discover\" the data in\n\t\t\t\t// HTML5 custom data-* attrs\n\t\t\t\tdata = dataAttr( elem, key );\n\t\t\t\tif ( data !== undefined ) {\n\t\t\t\t\treturn data;\n\t\t\t\t}\n\n\t\t\t\t// We tried really hard, but the data doesn't exist.\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Set the data...\n\t\t\tthis.each( function() {\n\n\t\t\t\t// We always store the camelCased key\n\t\t\t\tdataUser.set( this, key, value );\n\t\t\t} );\n\t\t}, null, value, arguments.length > 1, null, true );\n\t},\n\n\tremoveData: function( key ) {\n\t\treturn this.each( function() {\n\t\t\tdataUser.remove( this, key );\n\t\t} );\n\t}\n} );\n\n\njQuery.extend( {\n\tqueue: function( elem, type, data ) {\n\t\tvar queue;\n\n\t\tif ( elem ) {\n\t\t\ttype = ( type || \"fx\" ) + \"queue\";\n\t\t\tqueue = dataPriv.get( elem, type );\n\n\t\t\t// Speed up dequeue by getting out quickly if this is just a lookup\n\t\t\tif ( data ) {\n\t\t\t\tif ( !queue || Array.isArray( data ) ) {\n\t\t\t\t\tqueue = dataPriv.access( elem, type, jQuery.makeArray( data ) );\n\t\t\t\t} else {\n\t\t\t\t\tqueue.push( data );\n\t\t\t\t}\n\t\t\t}\n\t\t\treturn queue || [];\n\t\t}\n\t},\n\n\tdequeue: function( elem, type ) {\n\t\ttype = type || \"fx\";\n\n\t\tvar queue = jQuery.queue( elem, type ),\n\t\t\tstartLength = queue.length,\n\t\t\tfn = queue.shift(),\n\t\t\thooks = jQuery._queueHooks( elem, type ),\n\t\t\tnext = function() {\n\t\t\t\tjQuery.dequeue( elem, type );\n\t\t\t};\n\n\t\t// If the fx queue is dequeued, always remove the progress sentinel\n\t\tif ( fn === \"inprogress\" ) {\n\t\t\tfn = queue.shift();\n\t\t\tstartLength--;\n\t\t}\n\n\t\tif ( fn ) {\n\n\t\t\t// Add a progress sentinel to prevent the fx queue from being\n\t\t\t// automatically dequeued\n\t\t\tif ( type === \"fx\" ) {\n\t\t\t\tqueue.unshift( \"inprogress\" );\n\t\t\t}\n\n\t\t\t// Clear up the last queue stop function\n\t\t\tdelete hooks.stop;\n\t\t\tfn.call( elem, next, hooks );\n\t\t}\n\n\t\tif ( !startLength && hooks ) {\n\t\t\thooks.empty.fire();\n\t\t}\n\t},\n\n\t// Not public - generate a queueHooks object, or return the current one\n\t_queueHooks: function( elem, type ) {\n\t\tvar key = type + \"queueHooks\";\n\t\treturn dataPriv.get( elem, key ) || dataPriv.access( elem, key, {\n\t\t\tempty: jQuery.Callbacks( \"once memory\" ).add( function() {\n\t\t\t\tdataPriv.remove( elem, [ type + \"queue\", key ] );\n\t\t\t} )\n\t\t} );\n\t}\n} );\n\njQuery.fn.extend( {\n\tqueue: function( type, data ) {\n\t\tvar setter = 2;\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tdata = type;\n\t\t\ttype = \"fx\";\n\t\t\tsetter--;\n\t\t}\n\n\t\tif ( arguments.length < setter ) {\n\t\t\treturn jQuery.queue( this[ 0 ], type );\n\t\t}\n\n\t\treturn data === undefined ?\n\t\t\tthis :\n\t\t\tthis.each( function() {\n\t\t\t\tvar queue = jQuery.queue( this, type, data );\n\n\t\t\t\t// Ensure a hooks for this queue\n\t\t\t\tjQuery._queueHooks( this, type );\n\n\t\t\t\tif ( type === \"fx\" && queue[ 0 ] !== \"inprogress\" ) {\n\t\t\t\t\tjQuery.dequeue( this, type );\n\t\t\t\t}\n\t\t\t} );\n\t},\n\tdequeue: function( type ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.dequeue( this, type );\n\t\t} );\n\t},\n\tclearQueue: function( type ) {\n\t\treturn this.queue( type || \"fx\", [] );\n\t},\n\n\t// Get a promise resolved when queues of a certain type\n\t// are emptied (fx is the type by default)\n\tpromise: function( type, obj ) {\n\t\tvar tmp,\n\t\t\tcount = 1,\n\t\t\tdefer = jQuery.Deferred(),\n\t\t\telements = this,\n\t\t\ti = this.length,\n\t\t\tresolve = function() {\n\t\t\t\tif ( !( --count ) ) {\n\t\t\t\t\tdefer.resolveWith( elements, [ elements ] );\n\t\t\t\t}\n\t\t\t};\n\n\t\tif ( typeof type !== \"string\" ) {\n\t\t\tobj = type;\n\t\t\ttype = undefined;\n\t\t}\n\t\ttype = type || \"fx\";\n\n\t\twhile ( i-- ) {\n\t\t\ttmp = dataPriv.get( elements[ i ], type + \"queueHooks\" );\n\t\t\tif ( tmp && tmp.empty ) {\n\t\t\t\tcount++;\n\t\t\t\ttmp.empty.add( resolve );\n\t\t\t}\n\t\t}\n\t\tresolve();\n\t\treturn defer.promise( obj );\n\t}\n} );\nvar pnum = ( /[+-]?(?:\\d*\\.|)\\d+(?:[eE][+-]?\\d+|)/ ).source;\n\nvar rcssNum = new RegExp( \"^(?:([+-])=|)(\" + pnum + \")([a-z%]*)$\", \"i\" );\n\n\nvar cssExpand = [ \"Top\", \"Right\", \"Bottom\", \"Left\" ];\n\nvar documentElement = document.documentElement;\n\n\n\n\tvar isAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem );\n\t\t},\n\t\tcomposed = { composed: true };\n\n\t// Support: IE 9 - 11+, Edge 12 - 18+, iOS 10.0 - 10.2 only\n\t// Check attachment across shadow DOM boundaries when possible (gh-3504)\n\t// Support: iOS 10.0-10.2 only\n\t// Early iOS 10 versions support `attachShadow` but not `getRootNode`,\n\t// leading to errors. We need to check for `getRootNode`.\n\tif ( documentElement.getRootNode ) {\n\t\tisAttached = function( elem ) {\n\t\t\treturn jQuery.contains( elem.ownerDocument, elem ) ||\n\t\t\t\telem.getRootNode( composed ) === elem.ownerDocument;\n\t\t};\n\t}\nvar isHiddenWithinTree = function( elem, el ) {\n\n\t\t// isHiddenWithinTree might be called from jQuery#filter function;\n\t\t// in that case, element will be second argument\n\t\telem = el || elem;\n\n\t\t// Inline style trumps all\n\t\treturn elem.style.display === \"none\" ||\n\t\t\telem.style.display === \"\" &&\n\n\t\t\t// Otherwise, check computed style\n\t\t\t// Support: Firefox <=43 - 45\n\t\t\t// Disconnected elements can have computed display: none, so first confirm that elem is\n\t\t\t// in the document.\n\t\t\tisAttached( elem ) &&\n\n\t\t\tjQuery.css( elem, \"display\" ) === \"none\";\n\t};\n\nvar swap = function( elem, options, callback, args ) {\n\tvar ret, name,\n\t\told = {};\n\n\t// Remember the old values, and insert the new ones\n\tfor ( name in options ) {\n\t\told[ name ] = elem.style[ name ];\n\t\telem.style[ name ] = options[ name ];\n\t}\n\n\tret = callback.apply( elem, args || [] );\n\n\t// Revert the old values\n\tfor ( name in options ) {\n\t\telem.style[ name ] = old[ name ];\n\t}\n\n\treturn ret;\n};\n\n\n\n\nfunction adjustCSS( elem, prop, valueParts, tween ) {\n\tvar adjusted, scale,\n\t\tmaxIterations = 20,\n\t\tcurrentValue = tween ?\n\t\t\tfunction() {\n\t\t\t\treturn tween.cur();\n\t\t\t} :\n\t\t\tfunction() {\n\t\t\t\treturn jQuery.css( elem, prop, \"\" );\n\t\t\t},\n\t\tinitial = currentValue(),\n\t\tunit = valueParts && valueParts[ 3 ] || ( jQuery.cssNumber[ prop ] ? \"\" : \"px\" ),\n\n\t\t// Starting value computation is required for potential unit mismatches\n\t\tinitialInUnit = elem.nodeType &&\n\t\t\t( jQuery.cssNumber[ prop ] || unit !== \"px\" && +initial ) &&\n\t\t\trcssNum.exec( jQuery.css( elem, prop ) );\n\n\tif ( initialInUnit && initialInUnit[ 3 ] !== unit ) {\n\n\t\t// Support: Firefox <=54\n\t\t// Halve the iteration target value to prevent interference from CSS upper bounds (gh-2144)\n\t\tinitial = initial / 2;\n\n\t\t// Trust units reported by jQuery.css\n\t\tunit = unit || initialInUnit[ 3 ];\n\n\t\t// Iteratively approximate from a nonzero starting point\n\t\tinitialInUnit = +initial || 1;\n\n\t\twhile ( maxIterations-- ) {\n\n\t\t\t// Evaluate and update our best guess (doubling guesses that zero out).\n\t\t\t// Finish if the scale equals or crosses 1 (making the old*new product non-positive).\n\t\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\t\t\tif ( ( 1 - scale ) * ( 1 - ( scale = currentValue() / initial || 0.5 ) ) <= 0 ) {\n\t\t\t\tmaxIterations = 0;\n\t\t\t}\n\t\t\tinitialInUnit = initialInUnit / scale;\n\n\t\t}\n\n\t\tinitialInUnit = initialInUnit * 2;\n\t\tjQuery.style( elem, prop, initialInUnit + unit );\n\n\t\t// Make sure we update the tween properties later on\n\t\tvalueParts = valueParts || [];\n\t}\n\n\tif ( valueParts ) {\n\t\tinitialInUnit = +initialInUnit || +initial || 0;\n\n\t\t// Apply relative offset (+=/-=) if specified\n\t\tadjusted = valueParts[ 1 ] ?\n\t\t\tinitialInUnit + ( valueParts[ 1 ] + 1 ) * valueParts[ 2 ] :\n\t\t\t+valueParts[ 2 ];\n\t\tif ( tween ) {\n\t\t\ttween.unit = unit;\n\t\t\ttween.start = initialInUnit;\n\t\t\ttween.end = adjusted;\n\t\t}\n\t}\n\treturn adjusted;\n}\n\n\nvar defaultDisplayMap = {};\n\nfunction getDefaultDisplay( elem ) {\n\tvar temp,\n\t\tdoc = elem.ownerDocument,\n\t\tnodeName = elem.nodeName,\n\t\tdisplay = defaultDisplayMap[ nodeName ];\n\n\tif ( display ) {\n\t\treturn display;\n\t}\n\n\ttemp = doc.body.appendChild( doc.createElement( nodeName ) );\n\tdisplay = jQuery.css( temp, \"display\" );\n\n\ttemp.parentNode.removeChild( temp );\n\n\tif ( display === \"none\" ) {\n\t\tdisplay = \"block\";\n\t}\n\tdefaultDisplayMap[ nodeName ] = display;\n\n\treturn display;\n}\n\nfunction showHide( elements, show ) {\n\tvar display, elem,\n\t\tvalues = [],\n\t\tindex = 0,\n\t\tlength = elements.length;\n\n\t// Determine new display value for elements that need to change\n\tfor ( ; index < length; index++ ) {\n\t\telem = elements[ index ];\n\t\tif ( !elem.style ) {\n\t\t\tcontinue;\n\t\t}\n\n\t\tdisplay = elem.style.display;\n\t\tif ( show ) {\n\n\t\t\t// Since we force visibility upon cascade-hidden elements, an immediate (and slow)\n\t\t\t// check is required in this first loop unless we have a nonempty display value (either\n\t\t\t// inline or about-to-be-restored)\n\t\t\tif ( display === \"none\" ) {\n\t\t\t\tvalues[ index ] = dataPriv.get( elem, \"display\" ) || null;\n\t\t\t\tif ( !values[ index ] ) {\n\t\t\t\t\telem.style.display = \"\";\n\t\t\t\t}\n\t\t\t}\n\t\t\tif ( elem.style.display === \"\" && isHiddenWithinTree( elem ) ) {\n\t\t\t\tvalues[ index ] = getDefaultDisplay( elem );\n\t\t\t}\n\t\t} else {\n\t\t\tif ( display !== \"none\" ) {\n\t\t\t\tvalues[ index ] = \"none\";\n\n\t\t\t\t// Remember what we're overwriting\n\t\t\t\tdataPriv.set( elem, \"display\", display );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Set the display of the elements in a second loop to avoid constant reflow\n\tfor ( index = 0; index < length; index++ ) {\n\t\tif ( values[ index ] != null ) {\n\t\t\telements[ index ].style.display = values[ index ];\n\t\t}\n\t}\n\n\treturn elements;\n}\n\njQuery.fn.extend( {\n\tshow: function() {\n\t\treturn showHide( this, true );\n\t},\n\thide: function() {\n\t\treturn showHide( this );\n\t},\n\ttoggle: function( state ) {\n\t\tif ( typeof state === \"boolean\" ) {\n\t\t\treturn state ? this.show() : this.hide();\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tif ( isHiddenWithinTree( this ) ) {\n\t\t\t\tjQuery( this ).show();\n\t\t\t} else {\n\t\t\t\tjQuery( this ).hide();\n\t\t\t}\n\t\t} );\n\t}\n} );\nvar rcheckableType = ( /^(?:checkbox|radio)$/i );\n\nvar rtagName = ( /<([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)/i );\n\nvar rscriptType = ( /^$|^module$|\\/(?:java|ecma)script/i );\n\n\n\n// We have to close these tags to support XHTML (#13200)\nvar wrapMap = {\n\n\t// Support: IE <=9 only\n\toption: [ 1, \"<select multiple='multiple'>\", \"</select>\" ],\n\n\t// XHTML parsers do not magically insert elements in the\n\t// same way that tag soup parsers do. So we cannot shorten\n\t// this by omitting <tbody> or other required elements.\n\tthead: [ 1, \"<table>\", \"</table>\" ],\n\tcol: [ 2, \"<table><colgroup>\", \"</colgroup></table>\" ],\n\ttr: [ 2, \"<table><tbody>\", \"</tbody></table>\" ],\n\ttd: [ 3, \"<table><tbody><tr>\", \"</tr></tbody></table>\" ],\n\n\t_default: [ 0, \"\", \"\" ]\n};\n\n// Support: IE <=9 only\nwrapMap.optgroup = wrapMap.option;\n\nwrapMap.tbody = wrapMap.tfoot = wrapMap.colgroup = wrapMap.caption = wrapMap.thead;\nwrapMap.th = wrapMap.td;\n\n\nfunction getAll( context, tag ) {\n\n\t// Support: IE <=9 - 11 only\n\t// Use typeof to avoid zero-argument method invocation on host objects (#15151)\n\tvar ret;\n\n\tif ( typeof context.getElementsByTagName !== \"undefined\" ) {\n\t\tret = context.getElementsByTagName( tag || \"*\" );\n\n\t} else if ( typeof context.querySelectorAll !== \"undefined\" ) {\n\t\tret = context.querySelectorAll( tag || \"*\" );\n\n\t} else {\n\t\tret = [];\n\t}\n\n\tif ( tag === undefined || tag && nodeName( context, tag ) ) {\n\t\treturn jQuery.merge( [ context ], ret );\n\t}\n\n\treturn ret;\n}\n\n\n// Mark scripts as having already been evaluated\nfunction setGlobalEval( elems, refElements ) {\n\tvar i = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\tdataPriv.set(\n\t\t\telems[ i ],\n\t\t\t\"globalEval\",\n\t\t\t!refElements || dataPriv.get( refElements[ i ], \"globalEval\" )\n\t\t);\n\t}\n}\n\n\nvar rhtml = /<|&#?\\w+;/;\n\nfunction buildFragment( elems, context, scripts, selection, ignored ) {\n\tvar elem, tmp, tag, wrap, attached, j,\n\t\tfragment = context.createDocumentFragment(),\n\t\tnodes = [],\n\t\ti = 0,\n\t\tl = elems.length;\n\n\tfor ( ; i < l; i++ ) {\n\t\telem = elems[ i ];\n\n\t\tif ( elem || elem === 0 ) {\n\n\t\t\t// Add nodes directly\n\t\t\tif ( toType( elem ) === \"object\" ) {\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, elem.nodeType ? [ elem ] : elem );\n\n\t\t\t// Convert non-html into a text node\n\t\t\t} else if ( !rhtml.test( elem ) ) {\n\t\t\t\tnodes.push( context.createTextNode( elem ) );\n\n\t\t\t// Convert html into DOM nodes\n\t\t\t} else {\n\t\t\t\ttmp = tmp || fragment.appendChild( context.createElement( \"div\" ) );\n\n\t\t\t\t// Deserialize a standard representation\n\t\t\t\ttag = ( rtagName.exec( elem ) || [ \"\", \"\" ] )[ 1 ].toLowerCase();\n\t\t\t\twrap = wrapMap[ tag ] || wrapMap._default;\n\t\t\t\ttmp.innerHTML = wrap[ 1 ] + jQuery.htmlPrefilter( elem ) + wrap[ 2 ];\n\n\t\t\t\t// Descend through wrappers to the right content\n\t\t\t\tj = wrap[ 0 ];\n\t\t\t\twhile ( j-- ) {\n\t\t\t\t\ttmp = tmp.lastChild;\n\t\t\t\t}\n\n\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\tjQuery.merge( nodes, tmp.childNodes );\n\n\t\t\t\t// Remember the top-level container\n\t\t\t\ttmp = fragment.firstChild;\n\n\t\t\t\t// Ensure the created nodes are orphaned (#12392)\n\t\t\t\ttmp.textContent = \"\";\n\t\t\t}\n\t\t}\n\t}\n\n\t// Remove wrapper from fragment\n\tfragment.textContent = \"\";\n\n\ti = 0;\n\twhile ( ( elem = nodes[ i++ ] ) ) {\n\n\t\t// Skip elements already in the context collection (trac-4087)\n\t\tif ( selection && jQuery.inArray( elem, selection ) > -1 ) {\n\t\t\tif ( ignored ) {\n\t\t\t\tignored.push( elem );\n\t\t\t}\n\t\t\tcontinue;\n\t\t}\n\n\t\tattached = isAttached( elem );\n\n\t\t// Append to fragment\n\t\ttmp = getAll( fragment.appendChild( elem ), \"script\" );\n\n\t\t// Preserve script evaluation history\n\t\tif ( attached ) {\n\t\t\tsetGlobalEval( tmp );\n\t\t}\n\n\t\t// Capture executables\n\t\tif ( scripts ) {\n\t\t\tj = 0;\n\t\t\twhile ( ( elem = tmp[ j++ ] ) ) {\n\t\t\t\tif ( rscriptType.test( elem.type || \"\" ) ) {\n\t\t\t\t\tscripts.push( elem );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn fragment;\n}\n\n\n( function() {\n\tvar fragment = document.createDocumentFragment(),\n\t\tdiv = fragment.appendChild( document.createElement( \"div\" ) ),\n\t\tinput = document.createElement( \"input\" );\n\n\t// Support: Android 4.0 - 4.3 only\n\t// Check state lost if the name is set (#11217)\n\t// Support: Windows Web Apps (WWA)\n\t// `name` and `type` must use .setAttribute for WWA (#14901)\n\tinput.setAttribute( \"type\", \"radio\" );\n\tinput.setAttribute( \"checked\", \"checked\" );\n\tinput.setAttribute( \"name\", \"t\" );\n\n\tdiv.appendChild( input );\n\n\t// Support: Android <=4.1 only\n\t// Older WebKit doesn't clone checked state correctly in fragments\n\tsupport.checkClone = div.cloneNode( true ).cloneNode( true ).lastChild.checked;\n\n\t// Support: IE <=11 only\n\t// Make sure textarea (and checkbox) defaultValue is properly cloned\n\tdiv.innerHTML = \"<textarea>x</textarea>\";\n\tsupport.noCloneChecked = !!div.cloneNode( true ).lastChild.defaultValue;\n} )();\n\n\nvar\n\trkeyEvent = /^key/,\n\trmouseEvent = /^(?:mouse|pointer|contextmenu|drag|drop)|click/,\n\trtypenamespace = /^([^.]*)(?:\\.(.+)|)/;\n\nfunction returnTrue() {\n\treturn true;\n}\n\nfunction returnFalse() {\n\treturn false;\n}\n\n// Support: IE <=9 - 11+\n// focus() and blur() are asynchronous, except when they are no-op.\n// So expect focus to be synchronous when the element is already active,\n// and blur to be synchronous when the element is not already active.\n// (focus and blur are always synchronous in other supported browsers,\n// this just defines when we can count on it).\nfunction expectSync( elem, type ) {\n\treturn ( elem === safeActiveElement() ) === ( type === \"focus\" );\n}\n\n// Support: IE <=9 only\n// Accessing document.activeElement can throw unexpectedly\n// https://bugs.jquery.com/ticket/13393\nfunction safeActiveElement() {\n\ttry {\n\t\treturn document.activeElement;\n\t} catch ( err ) { }\n}\n\nfunction on( elem, types, selector, data, fn, one ) {\n\tvar origFn, type;\n\n\t// Types can be a map of types/handlers\n\tif ( typeof types === \"object\" ) {\n\n\t\t// ( types-Object, selector, data )\n\t\tif ( typeof selector !== \"string\" ) {\n\n\t\t\t// ( types-Object, data )\n\t\t\tdata = data || selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tfor ( type in types ) {\n\t\t\ton( elem, type, selector, data, types[ type ], one );\n\t\t}\n\t\treturn elem;\n\t}\n\n\tif ( data == null && fn == null ) {\n\n\t\t// ( types, fn )\n\t\tfn = selector;\n\t\tdata = selector = undefined;\n\t} else if ( fn == null ) {\n\t\tif ( typeof selector === \"string\" ) {\n\n\t\t\t// ( types, selector, fn )\n\t\t\tfn = data;\n\t\t\tdata = undefined;\n\t\t} else {\n\n\t\t\t// ( types, data, fn )\n\t\t\tfn = data;\n\t\t\tdata = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t}\n\tif ( fn === false ) {\n\t\tfn = returnFalse;\n\t} else if ( !fn ) {\n\t\treturn elem;\n\t}\n\n\tif ( one === 1 ) {\n\t\torigFn = fn;\n\t\tfn = function( event ) {\n\n\t\t\t// Can use an empty set, since event contains the info\n\t\t\tjQuery().off( event );\n\t\t\treturn origFn.apply( this, arguments );\n\t\t};\n\n\t\t// Use same guid so caller can remove using origFn\n\t\tfn.guid = origFn.guid || ( origFn.guid = jQuery.guid++ );\n\t}\n\treturn elem.each( function() {\n\t\tjQuery.event.add( this, types, fn, data, selector );\n\t} );\n}\n\n/*\n * Helper functions for managing events -- not part of the public interface.\n * Props to Dean Edwards' addEvent library for many of the ideas.\n */\njQuery.event = {\n\n\tglobal: {},\n\n\tadd: function( elem, types, handler, data, selector ) {\n\n\t\tvar handleObjIn, eventHandle, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.get( elem );\n\n\t\t// Don't attach events to noData or text/comment nodes (but allow plain objects)\n\t\tif ( !elemData ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Caller can pass in an object of custom data in lieu of the handler\n\t\tif ( handler.handler ) {\n\t\t\thandleObjIn = handler;\n\t\t\thandler = handleObjIn.handler;\n\t\t\tselector = handleObjIn.selector;\n\t\t}\n\n\t\t// Ensure that invalid selectors throw exceptions at attach time\n\t\t// Evaluate against documentElement in case elem is a non-element node (e.g., document)\n\t\tif ( selector ) {\n\t\t\tjQuery.find.matchesSelector( documentElement, selector );\n\t\t}\n\n\t\t// Make sure that the handler has a unique ID, used to find/remove it later\n\t\tif ( !handler.guid ) {\n\t\t\thandler.guid = jQuery.guid++;\n\t\t}\n\n\t\t// Init the element's event structure and main handler, if this is the first\n\t\tif ( !( events = elemData.events ) ) {\n\t\t\tevents = elemData.events = {};\n\t\t}\n\t\tif ( !( eventHandle = elemData.handle ) ) {\n\t\t\teventHandle = elemData.handle = function( e ) {\n\n\t\t\t\t// Discard the second event of a jQuery.event.trigger() and\n\t\t\t\t// when an event is called after a page has unloaded\n\t\t\t\treturn typeof jQuery !== \"undefined\" && jQuery.event.triggered !== e.type ?\n\t\t\t\t\tjQuery.event.dispatch.apply( elem, arguments ) : undefined;\n\t\t\t};\n\t\t}\n\n\t\t// Handle multiple events separated by a space\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// There *must* be a type, no attaching namespace-only handlers\n\t\t\tif ( !type ) {\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\t// If event changes its type, use the special event handlers for the changed type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// If selector defined, determine special event api type, otherwise given type\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\n\t\t\t// Update special based on newly reset type\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\n\t\t\t// handleObj is passed to all event handlers\n\t\t\thandleObj = jQuery.extend( {\n\t\t\t\ttype: type,\n\t\t\t\torigType: origType,\n\t\t\t\tdata: data,\n\t\t\t\thandler: handler,\n\t\t\t\tguid: handler.guid,\n\t\t\t\tselector: selector,\n\t\t\t\tneedsContext: selector && jQuery.expr.match.needsContext.test( selector ),\n\t\t\t\tnamespace: namespaces.join( \".\" )\n\t\t\t}, handleObjIn );\n\n\t\t\t// Init the event handler queue if we're the first\n\t\t\tif ( !( handlers = events[ type ] ) ) {\n\t\t\t\thandlers = events[ type ] = [];\n\t\t\t\thandlers.delegateCount = 0;\n\n\t\t\t\t// Only use addEventListener if the special events handler returns false\n\t\t\t\tif ( !special.setup ||\n\t\t\t\t\tspecial.setup.call( elem, data, namespaces, eventHandle ) === false ) {\n\n\t\t\t\t\tif ( elem.addEventListener ) {\n\t\t\t\t\t\telem.addEventListener( type, eventHandle );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tif ( special.add ) {\n\t\t\t\tspecial.add.call( elem, handleObj );\n\n\t\t\t\tif ( !handleObj.handler.guid ) {\n\t\t\t\t\thandleObj.handler.guid = handler.guid;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Add to the element's handler list, delegates in front\n\t\t\tif ( selector ) {\n\t\t\t\thandlers.splice( handlers.delegateCount++, 0, handleObj );\n\t\t\t} else {\n\t\t\t\thandlers.push( handleObj );\n\t\t\t}\n\n\t\t\t// Keep track of which events have ever been used, for event optimization\n\t\t\tjQuery.event.global[ type ] = true;\n\t\t}\n\n\t},\n\n\t// Detach an event or set of events from an element\n\tremove: function( elem, types, handler, selector, mappedTypes ) {\n\n\t\tvar j, origCount, tmp,\n\t\t\tevents, t, handleObj,\n\t\t\tspecial, handlers, type, namespaces, origType,\n\t\t\telemData = dataPriv.hasData( elem ) && dataPriv.get( elem );\n\n\t\tif ( !elemData || !( events = elemData.events ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Once for each type.namespace in types; type may be omitted\n\t\ttypes = ( types || \"\" ).match( rnothtmlwhite ) || [ \"\" ];\n\t\tt = types.length;\n\t\twhile ( t-- ) {\n\t\t\ttmp = rtypenamespace.exec( types[ t ] ) || [];\n\t\t\ttype = origType = tmp[ 1 ];\n\t\t\tnamespaces = ( tmp[ 2 ] || \"\" ).split( \".\" ).sort();\n\n\t\t\t// Unbind all events (on this namespace, if provided) for the element\n\t\t\tif ( !type ) {\n\t\t\t\tfor ( type in events ) {\n\t\t\t\t\tjQuery.event.remove( elem, type + types[ t ], handler, selector, true );\n\t\t\t\t}\n\t\t\t\tcontinue;\n\t\t\t}\n\n\t\t\tspecial = jQuery.event.special[ type ] || {};\n\t\t\ttype = ( selector ? special.delegateType : special.bindType ) || type;\n\t\t\thandlers = events[ type ] || [];\n\t\t\ttmp = tmp[ 2 ] &&\n\t\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" );\n\n\t\t\t// Remove matching events\n\t\t\torigCount = j = handlers.length;\n\t\t\twhile ( j-- ) {\n\t\t\t\thandleObj = handlers[ j ];\n\n\t\t\t\tif ( ( mappedTypes || origType === handleObj.origType ) &&\n\t\t\t\t\t( !handler || handler.guid === handleObj.guid ) &&\n\t\t\t\t\t( !tmp || tmp.test( handleObj.namespace ) ) &&\n\t\t\t\t\t( !selector || selector === handleObj.selector ||\n\t\t\t\t\t\tselector === \"**\" && handleObj.selector ) ) {\n\t\t\t\t\thandlers.splice( j, 1 );\n\n\t\t\t\t\tif ( handleObj.selector ) {\n\t\t\t\t\t\thandlers.delegateCount--;\n\t\t\t\t\t}\n\t\t\t\t\tif ( special.remove ) {\n\t\t\t\t\t\tspecial.remove.call( elem, handleObj );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\n\t\t\t// Remove generic event handler if we removed something and no more handlers exist\n\t\t\t// (avoids potential for endless recursion during removal of special event handlers)\n\t\t\tif ( origCount && !handlers.length ) {\n\t\t\t\tif ( !special.teardown ||\n\t\t\t\t\tspecial.teardown.call( elem, namespaces, elemData.handle ) === false ) {\n\n\t\t\t\t\tjQuery.removeEvent( elem, type, elemData.handle );\n\t\t\t\t}\n\n\t\t\t\tdelete events[ type ];\n\t\t\t}\n\t\t}\n\n\t\t// Remove data and the expando if it's no longer used\n\t\tif ( jQuery.isEmptyObject( events ) ) {\n\t\t\tdataPriv.remove( elem, \"handle events\" );\n\t\t}\n\t},\n\n\tdispatch: function( nativeEvent ) {\n\n\t\t// Make a writable jQuery.Event from the native event object\n\t\tvar event = jQuery.event.fix( nativeEvent );\n\n\t\tvar i, j, ret, matched, handleObj, handlerQueue,\n\t\t\targs = new Array( arguments.length ),\n\t\t\thandlers = ( dataPriv.get( this, \"events\" ) || {} )[ event.type ] || [],\n\t\t\tspecial = jQuery.event.special[ event.type ] || {};\n\n\t\t// Use the fix-ed jQuery.Event rather than the (read-only) native event\n\t\targs[ 0 ] = event;\n\n\t\tfor ( i = 1; i < arguments.length; i++ ) {\n\t\t\targs[ i ] = arguments[ i ];\n\t\t}\n\n\t\tevent.delegateTarget = this;\n\n\t\t// Call the preDispatch hook for the mapped type, and let it bail if desired\n\t\tif ( special.preDispatch && special.preDispatch.call( this, event ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine handlers\n\t\thandlerQueue = jQuery.event.handlers.call( this, event, handlers );\n\n\t\t// Run delegates first; they may want to stop propagation beneath us\n\t\ti = 0;\n\t\twhile ( ( matched = handlerQueue[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tevent.currentTarget = matched.elem;\n\n\t\t\tj = 0;\n\t\t\twhile ( ( handleObj = matched.handlers[ j++ ] ) &&\n\t\t\t\t!event.isImmediatePropagationStopped() ) {\n\n\t\t\t\t// If the event is namespaced, then each handler is only invoked if it is\n\t\t\t\t// specially universal or its namespaces are a superset of the event's.\n\t\t\t\tif ( !event.rnamespace || handleObj.namespace === false ||\n\t\t\t\t\tevent.rnamespace.test( handleObj.namespace ) ) {\n\n\t\t\t\t\tevent.handleObj = handleObj;\n\t\t\t\t\tevent.data = handleObj.data;\n\n\t\t\t\t\tret = ( ( jQuery.event.special[ handleObj.origType ] || {} ).handle ||\n\t\t\t\t\t\thandleObj.handler ).apply( matched.elem, args );\n\n\t\t\t\t\tif ( ret !== undefined ) {\n\t\t\t\t\t\tif ( ( event.result = ret ) === false ) {\n\t\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Call the postDispatch hook for the mapped type\n\t\tif ( special.postDispatch ) {\n\t\t\tspecial.postDispatch.call( this, event );\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\thandlers: function( event, handlers ) {\n\t\tvar i, handleObj, sel, matchedHandlers, matchedSelectors,\n\t\t\thandlerQueue = [],\n\t\t\tdelegateCount = handlers.delegateCount,\n\t\t\tcur = event.target;\n\n\t\t// Find delegate handlers\n\t\tif ( delegateCount &&\n\n\t\t\t// Support: IE <=9\n\t\t\t// Black-hole SVG <use> instance trees (trac-13180)\n\t\t\tcur.nodeType &&\n\n\t\t\t// Support: Firefox <=42\n\t\t\t// Suppress spec-violating clicks indicating a non-primary pointer button (trac-3861)\n\t\t\t// https://www.w3.org/TR/DOM-Level-3-Events/#event-type-click\n\t\t\t// Support: IE 11 only\n\t\t\t// ...but not arrow key \"clicks\" of radio inputs, which can have `button` -1 (gh-2343)\n\t\t\t!( event.type === \"click\" && event.button >= 1 ) ) {\n\n\t\t\tfor ( ; cur !== this; cur = cur.parentNode || this ) {\n\n\t\t\t\t// Don't check non-elements (#13208)\n\t\t\t\t// Don't process clicks on disabled elements (#6911, #8165, #11382, #11764)\n\t\t\t\tif ( cur.nodeType === 1 && !( event.type === \"click\" && cur.disabled === true ) ) {\n\t\t\t\t\tmatchedHandlers = [];\n\t\t\t\t\tmatchedSelectors = {};\n\t\t\t\t\tfor ( i = 0; i < delegateCount; i++ ) {\n\t\t\t\t\t\thandleObj = handlers[ i ];\n\n\t\t\t\t\t\t// Don't conflict with Object.prototype properties (#13203)\n\t\t\t\t\t\tsel = handleObj.selector + \" \";\n\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] === undefined ) {\n\t\t\t\t\t\t\tmatchedSelectors[ sel ] = handleObj.needsContext ?\n\t\t\t\t\t\t\t\tjQuery( sel, this ).index( cur ) > -1 :\n\t\t\t\t\t\t\t\tjQuery.find( sel, this, null, [ cur ] ).length;\n\t\t\t\t\t\t}\n\t\t\t\t\t\tif ( matchedSelectors[ sel ] ) {\n\t\t\t\t\t\t\tmatchedHandlers.push( handleObj );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t\tif ( matchedHandlers.length ) {\n\t\t\t\t\t\thandlerQueue.push( { elem: cur, handlers: matchedHandlers } );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\t// Add the remaining (directly-bound) handlers\n\t\tcur = this;\n\t\tif ( delegateCount < handlers.length ) {\n\t\t\thandlerQueue.push( { elem: cur, handlers: handlers.slice( delegateCount ) } );\n\t\t}\n\n\t\treturn handlerQueue;\n\t},\n\n\taddProp: function( name, hook ) {\n\t\tObject.defineProperty( jQuery.Event.prototype, name, {\n\t\t\tenumerable: true,\n\t\t\tconfigurable: true,\n\n\t\t\tget: isFunction( hook ) ?\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn hook( this.originalEvent );\n\t\t\t\t\t}\n\t\t\t\t} :\n\t\t\t\tfunction() {\n\t\t\t\t\tif ( this.originalEvent ) {\n\t\t\t\t\t\t\treturn this.originalEvent[ name ];\n\t\t\t\t\t}\n\t\t\t\t},\n\n\t\t\tset: function( value ) {\n\t\t\t\tObject.defineProperty( this, name, {\n\t\t\t\t\tenumerable: true,\n\t\t\t\t\tconfigurable: true,\n\t\t\t\t\twritable: true,\n\t\t\t\t\tvalue: value\n\t\t\t\t} );\n\t\t\t}\n\t\t} );\n\t},\n\n\tfix: function( originalEvent ) {\n\t\treturn originalEvent[ jQuery.expando ] ?\n\t\t\toriginalEvent :\n\t\t\tnew jQuery.Event( originalEvent );\n\t},\n\n\tspecial: {\n\t\tload: {\n\n\t\t\t// Prevent triggered image.load events from bubbling to window.load\n\t\t\tnoBubble: true\n\t\t},\n\t\tclick: {\n\n\t\t\t// Utilize native event to ensure correct state for checkable inputs\n\t\t\tsetup: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Claim the first handler\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\t// dataPriv.set( el, \"click\", ... )\n\t\t\t\t\tleverageNative( el, \"click\", returnTrue );\n\t\t\t\t}\n\n\t\t\t\t// Return false to allow normal processing in the caller\n\t\t\t\treturn false;\n\t\t\t},\n\t\t\ttrigger: function( data ) {\n\n\t\t\t\t// For mutual compressibility with _default, replace `this` access with a local var.\n\t\t\t\t// `|| data` is dead code meant only to preserve the variable through minification.\n\t\t\t\tvar el = this || data;\n\n\t\t\t\t// Force setup before triggering a click\n\t\t\t\tif ( rcheckableType.test( el.type ) &&\n\t\t\t\t\tel.click && nodeName( el, \"input\" ) ) {\n\n\t\t\t\t\tleverageNative( el, \"click\" );\n\t\t\t\t}\n\n\t\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\t\treturn true;\n\t\t\t},\n\n\t\t\t// For cross-browser consistency, suppress native .click() on links\n\t\t\t// Also prevent it if we're currently inside a leveraged native-event stack\n\t\t\t_default: function( event ) {\n\t\t\t\tvar target = event.target;\n\t\t\t\treturn rcheckableType.test( target.type ) &&\n\t\t\t\t\ttarget.click && nodeName( target, \"input\" ) &&\n\t\t\t\t\tdataPriv.get( target, \"click\" ) ||\n\t\t\t\t\tnodeName( target, \"a\" );\n\t\t\t}\n\t\t},\n\n\t\tbeforeunload: {\n\t\t\tpostDispatch: function( event ) {\n\n\t\t\t\t// Support: Firefox 20+\n\t\t\t\t// Firefox doesn't alert if the returnValue field is not set.\n\t\t\t\tif ( event.result !== undefined && event.originalEvent ) {\n\t\t\t\t\tevent.originalEvent.returnValue = event.result;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n};\n\n// Ensure the presence of an event listener that handles manually-triggered\n// synthetic events by interrupting progress until reinvoked in response to\n// *native* events that it fires directly, ensuring that state changes have\n// already occurred before other listeners are invoked.\nfunction leverageNative( el, type, expectSync ) {\n\n\t// Missing expectSync indicates a trigger call, which must force setup through jQuery.event.add\n\tif ( !expectSync ) {\n\t\tif ( dataPriv.get( el, type ) === undefined ) {\n\t\t\tjQuery.event.add( el, type, returnTrue );\n\t\t}\n\t\treturn;\n\t}\n\n\t// Register the controller as a special universal handler for all event namespaces\n\tdataPriv.set( el, type, false );\n\tjQuery.event.add( el, type, {\n\t\tnamespace: false,\n\t\thandler: function( event ) {\n\t\t\tvar notAsync, result,\n\t\t\t\tsaved = dataPriv.get( this, type );\n\n\t\t\tif ( ( event.isTrigger & 1 ) && this[ type ] ) {\n\n\t\t\t\t// Interrupt processing of the outer synthetic .trigger()ed event\n\t\t\t\t// Saved data should be false in such cases, but might be a leftover capture object\n\t\t\t\t// from an async native handler (gh-4350)\n\t\t\t\tif ( !saved.length ) {\n\n\t\t\t\t\t// Store arguments for use when handling the inner native event\n\t\t\t\t\t// There will always be at least one argument (an event object), so this array\n\t\t\t\t\t// will not be confused with a leftover capture object.\n\t\t\t\t\tsaved = slice.call( arguments );\n\t\t\t\t\tdataPriv.set( this, type, saved );\n\n\t\t\t\t\t// Trigger the native event and capture its result\n\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t// focus() and blur() are asynchronous\n\t\t\t\t\tnotAsync = expectSync( this, type );\n\t\t\t\t\tthis[ type ]();\n\t\t\t\t\tresult = dataPriv.get( this, type );\n\t\t\t\t\tif ( saved !== result || notAsync ) {\n\t\t\t\t\t\tdataPriv.set( this, type, false );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tresult = {};\n\t\t\t\t\t}\n\t\t\t\t\tif ( saved !== result ) {\n\n\t\t\t\t\t\t// Cancel the outer synthetic event\n\t\t\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t\t\t\tevent.preventDefault();\n\t\t\t\t\t\treturn result.value;\n\t\t\t\t\t}\n\n\t\t\t\t// If this is an inner synthetic event for an event with a bubbling surrogate\n\t\t\t\t// (focus or blur), assume that the surrogate already propagated from triggering the\n\t\t\t\t// native event and prevent that from happening again here.\n\t\t\t\t// This technically gets the ordering wrong w.r.t. to `.trigger()` (in which the\n\t\t\t\t// bubbling surrogate propagates *after* the non-bubbling base), but that seems\n\t\t\t\t// less bad than duplication.\n\t\t\t\t} else if ( ( jQuery.event.special[ type ] || {} ).delegateType ) {\n\t\t\t\t\tevent.stopPropagation();\n\t\t\t\t}\n\n\t\t\t// If this is a native event triggered above, everything is now in order\n\t\t\t// Fire an inner synthetic event with the original arguments\n\t\t\t} else if ( saved.length ) {\n\n\t\t\t\t// ...and capture the result\n\t\t\t\tdataPriv.set( this, type, {\n\t\t\t\t\tvalue: jQuery.event.trigger(\n\n\t\t\t\t\t\t// Support: IE <=9 - 11+\n\t\t\t\t\t\t// Extend with the prototype to reset the above stopImmediatePropagation()\n\t\t\t\t\t\tjQuery.extend( saved[ 0 ], jQuery.Event.prototype ),\n\t\t\t\t\t\tsaved.slice( 1 ),\n\t\t\t\t\t\tthis\n\t\t\t\t\t)\n\t\t\t\t} );\n\n\t\t\t\t// Abort handling of the native event\n\t\t\t\tevent.stopImmediatePropagation();\n\t\t\t}\n\t\t}\n\t} );\n}\n\njQuery.removeEvent = function( elem, type, handle ) {\n\n\t// This \"if\" is needed for plain objects\n\tif ( elem.removeEventListener ) {\n\t\telem.removeEventListener( type, handle );\n\t}\n};\n\njQuery.Event = function( src, props ) {\n\n\t// Allow instantiation without the 'new' keyword\n\tif ( !( this instanceof jQuery.Event ) ) {\n\t\treturn new jQuery.Event( src, props );\n\t}\n\n\t// Event object\n\tif ( src && src.type ) {\n\t\tthis.originalEvent = src;\n\t\tthis.type = src.type;\n\n\t\t// Events bubbling up the document may have been marked as prevented\n\t\t// by a handler lower down the tree; reflect the correct value.\n\t\tthis.isDefaultPrevented = src.defaultPrevented ||\n\t\t\t\tsrc.defaultPrevented === undefined &&\n\n\t\t\t\t// Support: Android <=2.3 only\n\t\t\t\tsrc.returnValue === false ?\n\t\t\treturnTrue :\n\t\t\treturnFalse;\n\n\t\t// Create target properties\n\t\t// Support: Safari <=6 - 7 only\n\t\t// Target should not be a text node (#504, #13143)\n\t\tthis.target = ( src.target && src.target.nodeType === 3 ) ?\n\t\t\tsrc.target.parentNode :\n\t\t\tsrc.target;\n\n\t\tthis.currentTarget = src.currentTarget;\n\t\tthis.relatedTarget = src.relatedTarget;\n\n\t// Event type\n\t} else {\n\t\tthis.type = src;\n\t}\n\n\t// Put explicitly provided properties onto the event object\n\tif ( props ) {\n\t\tjQuery.extend( this, props );\n\t}\n\n\t// Create a timestamp if incoming event doesn't have one\n\tthis.timeStamp = src && src.timeStamp || Date.now();\n\n\t// Mark it as fixed\n\tthis[ jQuery.expando ] = true;\n};\n\n// jQuery.Event is based on DOM3 Events as specified by the ECMAScript Language Binding\n// https://www.w3.org/TR/2003/WD-DOM-Level-3-Events-20030331/ecma-script-binding.html\njQuery.Event.prototype = {\n\tconstructor: jQuery.Event,\n\tisDefaultPrevented: returnFalse,\n\tisPropagationStopped: returnFalse,\n\tisImmediatePropagationStopped: returnFalse,\n\tisSimulated: false,\n\n\tpreventDefault: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isDefaultPrevented = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.preventDefault();\n\t\t}\n\t},\n\tstopPropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isPropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopPropagation();\n\t\t}\n\t},\n\tstopImmediatePropagation: function() {\n\t\tvar e = this.originalEvent;\n\n\t\tthis.isImmediatePropagationStopped = returnTrue;\n\n\t\tif ( e && !this.isSimulated ) {\n\t\t\te.stopImmediatePropagation();\n\t\t}\n\n\t\tthis.stopPropagation();\n\t}\n};\n\n// Includes all common event props including KeyEvent and MouseEvent specific props\njQuery.each( {\n\taltKey: true,\n\tbubbles: true,\n\tcancelable: true,\n\tchangedTouches: true,\n\tctrlKey: true,\n\tdetail: true,\n\teventPhase: true,\n\tmetaKey: true,\n\tpageX: true,\n\tpageY: true,\n\tshiftKey: true,\n\tview: true,\n\t\"char\": true,\n\tcode: true,\n\tcharCode: true,\n\tkey: true,\n\tkeyCode: true,\n\tbutton: true,\n\tbuttons: true,\n\tclientX: true,\n\tclientY: true,\n\toffsetX: true,\n\toffsetY: true,\n\tpointerId: true,\n\tpointerType: true,\n\tscreenX: true,\n\tscreenY: true,\n\ttargetTouches: true,\n\ttoElement: true,\n\ttouches: true,\n\n\twhich: function( event ) {\n\t\tvar button = event.button;\n\n\t\t// Add which for key events\n\t\tif ( event.which == null && rkeyEvent.test( event.type ) ) {\n\t\t\treturn event.charCode != null ? event.charCode : event.keyCode;\n\t\t}\n\n\t\t// Add which for click: 1 === left; 2 === middle; 3 === right\n\t\tif ( !event.which && button !== undefined && rmouseEvent.test( event.type ) ) {\n\t\t\tif ( button & 1 ) {\n\t\t\t\treturn 1;\n\t\t\t}\n\n\t\t\tif ( button & 2 ) {\n\t\t\t\treturn 3;\n\t\t\t}\n\n\t\t\tif ( button & 4 ) {\n\t\t\t\treturn 2;\n\t\t\t}\n\n\t\t\treturn 0;\n\t\t}\n\n\t\treturn event.which;\n\t}\n}, jQuery.event.addProp );\n\njQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( type, delegateType ) {\n\tjQuery.event.special[ type ] = {\n\n\t\t// Utilize native event if possible so blur/focus sequence is correct\n\t\tsetup: function() {\n\n\t\t\t// Claim the first handler\n\t\t\t// dataPriv.set( this, \"focus\", ... )\n\t\t\t// dataPriv.set( this, \"blur\", ... )\n\t\t\tleverageNative( this, type, expectSync );\n\n\t\t\t// Return false to allow normal processing in the caller\n\t\t\treturn false;\n\t\t},\n\t\ttrigger: function() {\n\n\t\t\t// Force setup before trigger\n\t\t\tleverageNative( this, type );\n\n\t\t\t// Return non-false to allow normal event-path propagation\n\t\t\treturn true;\n\t\t},\n\n\t\tdelegateType: delegateType\n\t};\n} );\n\n// Create mouseenter/leave events using mouseover/out and event-time checks\n// so that event delegation works in jQuery.\n// Do the same for pointerenter/pointerleave and pointerover/pointerout\n//\n// Support: Safari 7 only\n// Safari sends mouseenter too often; see:\n// https://bugs.chromium.org/p/chromium/issues/detail?id=470258\n// for the description of the bug (it existed in older Chrome versions as well).\njQuery.each( {\n\tmouseenter: \"mouseover\",\n\tmouseleave: \"mouseout\",\n\tpointerenter: \"pointerover\",\n\tpointerleave: \"pointerout\"\n}, function( orig, fix ) {\n\tjQuery.event.special[ orig ] = {\n\t\tdelegateType: fix,\n\t\tbindType: fix,\n\n\t\thandle: function( event ) {\n\t\t\tvar ret,\n\t\t\t\ttarget = this,\n\t\t\t\trelated = event.relatedTarget,\n\t\t\t\thandleObj = event.handleObj;\n\n\t\t\t// For mouseenter/leave call the handler if related is outside the target.\n\t\t\t// NB: No relatedTarget if the mouse left/entered the browser window\n\t\t\tif ( !related || ( related !== target && !jQuery.contains( target, related ) ) ) {\n\t\t\t\tevent.type = handleObj.origType;\n\t\t\t\tret = handleObj.handler.apply( this, arguments );\n\t\t\t\tevent.type = fix;\n\t\t\t}\n\t\t\treturn ret;\n\t\t}\n\t};\n} );\n\njQuery.fn.extend( {\n\n\ton: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn );\n\t},\n\tone: function( types, selector, data, fn ) {\n\t\treturn on( this, types, selector, data, fn, 1 );\n\t},\n\toff: function( types, selector, fn ) {\n\t\tvar handleObj, type;\n\t\tif ( types && types.preventDefault && types.handleObj ) {\n\n\t\t\t// ( event )  dispatched jQuery.Event\n\t\t\thandleObj = types.handleObj;\n\t\t\tjQuery( types.delegateTarget ).off(\n\t\t\t\thandleObj.namespace ?\n\t\t\t\t\thandleObj.origType + \".\" + handleObj.namespace :\n\t\t\t\t\thandleObj.origType,\n\t\t\t\thandleObj.selector,\n\t\t\t\thandleObj.handler\n\t\t\t);\n\t\t\treturn this;\n\t\t}\n\t\tif ( typeof types === \"object\" ) {\n\n\t\t\t// ( types-object [, selector] )\n\t\t\tfor ( type in types ) {\n\t\t\t\tthis.off( type, selector, types[ type ] );\n\t\t\t}\n\t\t\treturn this;\n\t\t}\n\t\tif ( selector === false || typeof selector === \"function\" ) {\n\n\t\t\t// ( types [, fn] )\n\t\t\tfn = selector;\n\t\t\tselector = undefined;\n\t\t}\n\t\tif ( fn === false ) {\n\t\t\tfn = returnFalse;\n\t\t}\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.remove( this, types, fn, selector );\n\t\t} );\n\t}\n} );\n\n\nvar\n\n\t/* eslint-disable max-len */\n\n\t// See https://github.com/eslint/eslint/issues/3229\n\trxhtmlTag = /<(?!area|br|col|embed|hr|img|input|link|meta|param)(([a-z][^\\/\\0>\\x20\\t\\r\\n\\f]*)[^>]*)\\/>/gi,\n\n\t/* eslint-enable */\n\n\t// Support: IE <=10 - 11, Edge 12 - 13 only\n\t// In IE/Edge using regex groups here causes severe slowdowns.\n\t// See https://connect.microsoft.com/IE/feedback/details/1736512/\n\trnoInnerhtml = /<script|<style|<link/i,\n\n\t// checked=\"checked\" or checked\n\trchecked = /checked\\s*(?:[^=]|=\\s*.checked.)/i,\n\trcleanScript = /^\\s*<!(?:\\[CDATA\\[|--)|(?:\\]\\]|--)>\\s*$/g;\n\n// Prefer a tbody over its parent table for containing new rows\nfunction manipulationTarget( elem, content ) {\n\tif ( nodeName( elem, \"table\" ) &&\n\t\tnodeName( content.nodeType !== 11 ? content : content.firstChild, \"tr\" ) ) {\n\n\t\treturn jQuery( elem ).children( \"tbody\" )[ 0 ] || elem;\n\t}\n\n\treturn elem;\n}\n\n// Replace/restore the type attribute of script elements for safe DOM manipulation\nfunction disableScript( elem ) {\n\telem.type = ( elem.getAttribute( \"type\" ) !== null ) + \"/\" + elem.type;\n\treturn elem;\n}\nfunction restoreScript( elem ) {\n\tif ( ( elem.type || \"\" ).slice( 0, 5 ) === \"true/\" ) {\n\t\telem.type = elem.type.slice( 5 );\n\t} else {\n\t\telem.removeAttribute( \"type\" );\n\t}\n\n\treturn elem;\n}\n\nfunction cloneCopyEvent( src, dest ) {\n\tvar i, l, type, pdataOld, pdataCur, udataOld, udataCur, events;\n\n\tif ( dest.nodeType !== 1 ) {\n\t\treturn;\n\t}\n\n\t// 1. Copy private data: events, handlers, etc.\n\tif ( dataPriv.hasData( src ) ) {\n\t\tpdataOld = dataPriv.access( src );\n\t\tpdataCur = dataPriv.set( dest, pdataOld );\n\t\tevents = pdataOld.events;\n\n\t\tif ( events ) {\n\t\t\tdelete pdataCur.handle;\n\t\t\tpdataCur.events = {};\n\n\t\t\tfor ( type in events ) {\n\t\t\t\tfor ( i = 0, l = events[ type ].length; i < l; i++ ) {\n\t\t\t\t\tjQuery.event.add( dest, type, events[ type ][ i ] );\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t// 2. Copy user data\n\tif ( dataUser.hasData( src ) ) {\n\t\tudataOld = dataUser.access( src );\n\t\tudataCur = jQuery.extend( {}, udataOld );\n\n\t\tdataUser.set( dest, udataCur );\n\t}\n}\n\n// Fix IE bugs, see support tests\nfunction fixInput( src, dest ) {\n\tvar nodeName = dest.nodeName.toLowerCase();\n\n\t// Fails to persist the checked state of a cloned checkbox or radio button.\n\tif ( nodeName === \"input\" && rcheckableType.test( src.type ) ) {\n\t\tdest.checked = src.checked;\n\n\t// Fails to return the selected option to the default selected state when cloning options\n\t} else if ( nodeName === \"input\" || nodeName === \"textarea\" ) {\n\t\tdest.defaultValue = src.defaultValue;\n\t}\n}\n\nfunction domManip( collection, args, callback, ignored ) {\n\n\t// Flatten any nested arrays\n\targs = concat.apply( [], args );\n\n\tvar fragment, first, scripts, hasScripts, node, doc,\n\t\ti = 0,\n\t\tl = collection.length,\n\t\tiNoClone = l - 1,\n\t\tvalue = args[ 0 ],\n\t\tvalueIsFunction = isFunction( value );\n\n\t// We can't cloneNode fragments that contain checked, in WebKit\n\tif ( valueIsFunction ||\n\t\t\t( l > 1 && typeof value === \"string\" &&\n\t\t\t\t!support.checkClone && rchecked.test( value ) ) ) {\n\t\treturn collection.each( function( index ) {\n\t\t\tvar self = collection.eq( index );\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\targs[ 0 ] = value.call( this, index, self.html() );\n\t\t\t}\n\t\t\tdomManip( self, args, callback, ignored );\n\t\t} );\n\t}\n\n\tif ( l ) {\n\t\tfragment = buildFragment( args, collection[ 0 ].ownerDocument, false, collection, ignored );\n\t\tfirst = fragment.firstChild;\n\n\t\tif ( fragment.childNodes.length === 1 ) {\n\t\t\tfragment = first;\n\t\t}\n\n\t\t// Require either new content or an interest in ignored elements to invoke the callback\n\t\tif ( first || ignored ) {\n\t\t\tscripts = jQuery.map( getAll( fragment, \"script\" ), disableScript );\n\t\t\thasScripts = scripts.length;\n\n\t\t\t// Use the original fragment for the last item\n\t\t\t// instead of the first because it can end up\n\t\t\t// being emptied incorrectly in certain situations (#8070).\n\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\tnode = fragment;\n\n\t\t\t\tif ( i !== iNoClone ) {\n\t\t\t\t\tnode = jQuery.clone( node, true, true );\n\n\t\t\t\t\t// Keep references to cloned scripts for later restoration\n\t\t\t\t\tif ( hasScripts ) {\n\n\t\t\t\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t\t\t\t// push.apply(_, arraylike) throws on ancient WebKit\n\t\t\t\t\t\tjQuery.merge( scripts, getAll( node, \"script\" ) );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\tcallback.call( collection[ i ], node, i );\n\t\t\t}\n\n\t\t\tif ( hasScripts ) {\n\t\t\t\tdoc = scripts[ scripts.length - 1 ].ownerDocument;\n\n\t\t\t\t// Reenable scripts\n\t\t\t\tjQuery.map( scripts, restoreScript );\n\n\t\t\t\t// Evaluate executable scripts on first document insertion\n\t\t\t\tfor ( i = 0; i < hasScripts; i++ ) {\n\t\t\t\t\tnode = scripts[ i ];\n\t\t\t\t\tif ( rscriptType.test( node.type || \"\" ) &&\n\t\t\t\t\t\t!dataPriv.access( node, \"globalEval\" ) &&\n\t\t\t\t\t\tjQuery.contains( doc, node ) ) {\n\n\t\t\t\t\t\tif ( node.src && ( node.type || \"\" ).toLowerCase()  !== \"module\" ) {\n\n\t\t\t\t\t\t\t// Optional AJAX dependency, but won't run scripts if not present\n\t\t\t\t\t\t\tif ( jQuery._evalUrl && !node.noModule ) {\n\t\t\t\t\t\t\t\tjQuery._evalUrl( node.src, {\n\t\t\t\t\t\t\t\t\tnonce: node.nonce || node.getAttribute( \"nonce\" )\n\t\t\t\t\t\t\t\t} );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\tDOMEval( node.textContent.replace( rcleanScript, \"\" ), node, doc );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\treturn collection;\n}\n\nfunction remove( elem, selector, keepData ) {\n\tvar node,\n\t\tnodes = selector ? jQuery.filter( selector, elem ) : elem,\n\t\ti = 0;\n\n\tfor ( ; ( node = nodes[ i ] ) != null; i++ ) {\n\t\tif ( !keepData && node.nodeType === 1 ) {\n\t\t\tjQuery.cleanData( getAll( node ) );\n\t\t}\n\n\t\tif ( node.parentNode ) {\n\t\t\tif ( keepData && isAttached( node ) ) {\n\t\t\t\tsetGlobalEval( getAll( node, \"script\" ) );\n\t\t\t}\n\t\t\tnode.parentNode.removeChild( node );\n\t\t}\n\t}\n\n\treturn elem;\n}\n\njQuery.extend( {\n\thtmlPrefilter: function( html ) {\n\t\treturn html.replace( rxhtmlTag, \"<$1></$2>\" );\n\t},\n\n\tclone: function( elem, dataAndEvents, deepDataAndEvents ) {\n\t\tvar i, l, srcElements, destElements,\n\t\t\tclone = elem.cloneNode( true ),\n\t\t\tinPage = isAttached( elem );\n\n\t\t// Fix IE cloning issues\n\t\tif ( !support.noCloneChecked && ( elem.nodeType === 1 || elem.nodeType === 11 ) &&\n\t\t\t\t!jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// We eschew Sizzle here for performance reasons: https://jsperf.com/getall-vs-sizzle/2\n\t\t\tdestElements = getAll( clone );\n\t\t\tsrcElements = getAll( elem );\n\n\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\tfixInput( srcElements[ i ], destElements[ i ] );\n\t\t\t}\n\t\t}\n\n\t\t// Copy the events from the original to the clone\n\t\tif ( dataAndEvents ) {\n\t\t\tif ( deepDataAndEvents ) {\n\t\t\t\tsrcElements = srcElements || getAll( elem );\n\t\t\t\tdestElements = destElements || getAll( clone );\n\n\t\t\t\tfor ( i = 0, l = srcElements.length; i < l; i++ ) {\n\t\t\t\t\tcloneCopyEvent( srcElements[ i ], destElements[ i ] );\n\t\t\t\t}\n\t\t\t} else {\n\t\t\t\tcloneCopyEvent( elem, clone );\n\t\t\t}\n\t\t}\n\n\t\t// Preserve script evaluation history\n\t\tdestElements = getAll( clone, \"script\" );\n\t\tif ( destElements.length > 0 ) {\n\t\t\tsetGlobalEval( destElements, !inPage && getAll( elem, \"script\" ) );\n\t\t}\n\n\t\t// Return the cloned set\n\t\treturn clone;\n\t},\n\n\tcleanData: function( elems ) {\n\t\tvar data, elem, type,\n\t\t\tspecial = jQuery.event.special,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = elems[ i ] ) !== undefined; i++ ) {\n\t\t\tif ( acceptData( elem ) ) {\n\t\t\t\tif ( ( data = elem[ dataPriv.expando ] ) ) {\n\t\t\t\t\tif ( data.events ) {\n\t\t\t\t\t\tfor ( type in data.events ) {\n\t\t\t\t\t\t\tif ( special[ type ] ) {\n\t\t\t\t\t\t\t\tjQuery.event.remove( elem, type );\n\n\t\t\t\t\t\t\t// This is a shortcut to avoid jQuery.event.remove's overhead\n\t\t\t\t\t\t\t} else {\n\t\t\t\t\t\t\t\tjQuery.removeEvent( elem, type, data.handle );\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataPriv.expando ] = undefined;\n\t\t\t\t}\n\t\t\t\tif ( elem[ dataUser.expando ] ) {\n\n\t\t\t\t\t// Support: Chrome <=35 - 45+\n\t\t\t\t\t// Assign undefined instead of using delete, see Data#remove\n\t\t\t\t\telem[ dataUser.expando ] = undefined;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n} );\n\njQuery.fn.extend( {\n\tdetach: function( selector ) {\n\t\treturn remove( this, selector, true );\n\t},\n\n\tremove: function( selector ) {\n\t\treturn remove( this, selector );\n\t},\n\n\ttext: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\treturn value === undefined ?\n\t\t\t\tjQuery.text( this ) :\n\t\t\t\tthis.empty().each( function() {\n\t\t\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\t\t\tthis.textContent = value;\n\t\t\t\t\t}\n\t\t\t\t} );\n\t\t}, null, value, arguments.length );\n\t},\n\n\tappend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.appendChild( elem );\n\t\t\t}\n\t\t} );\n\t},\n\n\tprepend: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) {\n\t\t\t\tvar target = manipulationTarget( this, elem );\n\t\t\t\ttarget.insertBefore( elem, target.firstChild );\n\t\t\t}\n\t\t} );\n\t},\n\n\tbefore: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this );\n\t\t\t}\n\t\t} );\n\t},\n\n\tafter: function() {\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tif ( this.parentNode ) {\n\t\t\t\tthis.parentNode.insertBefore( elem, this.nextSibling );\n\t\t\t}\n\t\t} );\n\t},\n\n\tempty: function() {\n\t\tvar elem,\n\t\t\ti = 0;\n\n\t\tfor ( ; ( elem = this[ i ] ) != null; i++ ) {\n\t\t\tif ( elem.nodeType === 1 ) {\n\n\t\t\t\t// Prevent memory leaks\n\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\n\t\t\t\t// Remove any remaining nodes\n\t\t\t\telem.textContent = \"\";\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tclone: function( dataAndEvents, deepDataAndEvents ) {\n\t\tdataAndEvents = dataAndEvents == null ? false : dataAndEvents;\n\t\tdeepDataAndEvents = deepDataAndEvents == null ? dataAndEvents : deepDataAndEvents;\n\n\t\treturn this.map( function() {\n\t\t\treturn jQuery.clone( this, dataAndEvents, deepDataAndEvents );\n\t\t} );\n\t},\n\n\thtml: function( value ) {\n\t\treturn access( this, function( value ) {\n\t\t\tvar elem = this[ 0 ] || {},\n\t\t\t\ti = 0,\n\t\t\t\tl = this.length;\n\n\t\t\tif ( value === undefined && elem.nodeType === 1 ) {\n\t\t\t\treturn elem.innerHTML;\n\t\t\t}\n\n\t\t\t// See if we can take a shortcut and just use innerHTML\n\t\t\tif ( typeof value === \"string\" && !rnoInnerhtml.test( value ) &&\n\t\t\t\t!wrapMap[ ( rtagName.exec( value ) || [ \"\", \"\" ] )[ 1 ].toLowerCase() ] ) {\n\n\t\t\t\tvalue = jQuery.htmlPrefilter( value );\n\n\t\t\t\ttry {\n\t\t\t\t\tfor ( ; i < l; i++ ) {\n\t\t\t\t\t\telem = this[ i ] || {};\n\n\t\t\t\t\t\t// Remove element nodes and prevent memory leaks\n\t\t\t\t\t\tif ( elem.nodeType === 1 ) {\n\t\t\t\t\t\t\tjQuery.cleanData( getAll( elem, false ) );\n\t\t\t\t\t\t\telem.innerHTML = value;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\telem = 0;\n\n\t\t\t\t// If using innerHTML throws an exception, use the fallback method\n\t\t\t\t} catch ( e ) {}\n\t\t\t}\n\n\t\t\tif ( elem ) {\n\t\t\t\tthis.empty().append( value );\n\t\t\t}\n\t\t}, null, value, arguments.length );\n\t},\n\n\treplaceWith: function() {\n\t\tvar ignored = [];\n\n\t\t// Make the changes, replacing each non-ignored context element with the new content\n\t\treturn domManip( this, arguments, function( elem ) {\n\t\t\tvar parent = this.parentNode;\n\n\t\t\tif ( jQuery.inArray( this, ignored ) < 0 ) {\n\t\t\t\tjQuery.cleanData( getAll( this ) );\n\t\t\t\tif ( parent ) {\n\t\t\t\t\tparent.replaceChild( elem, this );\n\t\t\t\t}\n\t\t\t}\n\n\t\t// Force callback invocation\n\t\t}, ignored );\n\t}\n} );\n\njQuery.each( {\n\tappendTo: \"append\",\n\tprependTo: \"prepend\",\n\tinsertBefore: \"before\",\n\tinsertAfter: \"after\",\n\treplaceAll: \"replaceWith\"\n}, function( name, original ) {\n\tjQuery.fn[ name ] = function( selector ) {\n\t\tvar elems,\n\t\t\tret = [],\n\t\t\tinsert = jQuery( selector ),\n\t\t\tlast = insert.length - 1,\n\t\t\ti = 0;\n\n\t\tfor ( ; i <= last; i++ ) {\n\t\t\telems = i === last ? this : this.clone( true );\n\t\t\tjQuery( insert[ i ] )[ original ]( elems );\n\n\t\t\t// Support: Android <=4.0 only, PhantomJS 1 only\n\t\t\t// .get() because push.apply(_, arraylike) throws on ancient WebKit\n\t\t\tpush.apply( ret, elems.get() );\n\t\t}\n\n\t\treturn this.pushStack( ret );\n\t};\n} );\nvar rnumnonpx = new RegExp( \"^(\" + pnum + \")(?!px)[a-z%]+$\", \"i\" );\n\nvar getStyles = function( elem ) {\n\n\t\t// Support: IE <=11 only, Firefox <=30 (#15098, #14150)\n\t\t// IE throws on elements created in popups\n\t\t// FF meanwhile throws on frame elements through \"defaultView.getComputedStyle\"\n\t\tvar view = elem.ownerDocument.defaultView;\n\n\t\tif ( !view || !view.opener ) {\n\t\t\tview = window;\n\t\t}\n\n\t\treturn view.getComputedStyle( elem );\n\t};\n\nvar rboxStyle = new RegExp( cssExpand.join( \"|\" ), \"i\" );\n\n\n\n( function() {\n\n\t// Executing both pixelPosition & boxSizingReliable tests require only one layout\n\t// so they're executed at the same time to save the second computation.\n\tfunction computeStyleTests() {\n\n\t\t// This is a singleton, we need to execute it only once\n\t\tif ( !div ) {\n\t\t\treturn;\n\t\t}\n\n\t\tcontainer.style.cssText = \"position:absolute;left:-11111px;width:60px;\" +\n\t\t\t\"margin-top:1px;padding:0;border:0\";\n\t\tdiv.style.cssText =\n\t\t\t\"position:relative;display:block;box-sizing:border-box;overflow:scroll;\" +\n\t\t\t\"margin:auto;border:1px;padding:1px;\" +\n\t\t\t\"width:60%;top:1%\";\n\t\tdocumentElement.appendChild( container ).appendChild( div );\n\n\t\tvar divStyle = window.getComputedStyle( div );\n\t\tpixelPositionVal = divStyle.top !== \"1%\";\n\n\t\t// Support: Android 4.0 - 4.3 only, Firefox <=3 - 44\n\t\treliableMarginLeftVal = roundPixelMeasures( divStyle.marginLeft ) === 12;\n\n\t\t// Support: Android 4.0 - 4.3 only, Safari <=9.1 - 10.1, iOS <=7.0 - 9.3\n\t\t// Some styles come back with percentage values, even though they shouldn't\n\t\tdiv.style.right = \"60%\";\n\t\tpixelBoxStylesVal = roundPixelMeasures( divStyle.right ) === 36;\n\n\t\t// Support: IE 9 - 11 only\n\t\t// Detect misreporting of content dimensions for box-sizing:border-box elements\n\t\tboxSizingReliableVal = roundPixelMeasures( divStyle.width ) === 36;\n\n\t\t// Support: IE 9 only\n\t\t// Detect overflow:scroll screwiness (gh-3699)\n\t\t// Support: Chrome <=64\n\t\t// Don't get tricked when zoom affects offsetWidth (gh-4029)\n\t\tdiv.style.position = \"absolute\";\n\t\tscrollboxSizeVal = roundPixelMeasures( div.offsetWidth / 3 ) === 12;\n\n\t\tdocumentElement.removeChild( container );\n\n\t\t// Nullify the div so it wouldn't be stored in the memory and\n\t\t// it will also be a sign that checks already performed\n\t\tdiv = null;\n\t}\n\n\tfunction roundPixelMeasures( measure ) {\n\t\treturn Math.round( parseFloat( measure ) );\n\t}\n\n\tvar pixelPositionVal, boxSizingReliableVal, scrollboxSizeVal, pixelBoxStylesVal,\n\t\treliableMarginLeftVal,\n\t\tcontainer = document.createElement( \"div\" ),\n\t\tdiv = document.createElement( \"div\" );\n\n\t// Finish early in limited (non-browser) environments\n\tif ( !div.style ) {\n\t\treturn;\n\t}\n\n\t// Support: IE <=9 - 11 only\n\t// Style of cloned element affects source element cloned (#8908)\n\tdiv.style.backgroundClip = \"content-box\";\n\tdiv.cloneNode( true ).style.backgroundClip = \"\";\n\tsupport.clearCloneStyle = div.style.backgroundClip === \"content-box\";\n\n\tjQuery.extend( support, {\n\t\tboxSizingReliable: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn boxSizingReliableVal;\n\t\t},\n\t\tpixelBoxStyles: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelBoxStylesVal;\n\t\t},\n\t\tpixelPosition: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn pixelPositionVal;\n\t\t},\n\t\treliableMarginLeft: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn reliableMarginLeftVal;\n\t\t},\n\t\tscrollboxSize: function() {\n\t\t\tcomputeStyleTests();\n\t\t\treturn scrollboxSizeVal;\n\t\t}\n\t} );\n} )();\n\n\nfunction curCSS( elem, name, computed ) {\n\tvar width, minWidth, maxWidth, ret,\n\n\t\t// Support: Firefox 51+\n\t\t// Retrieving style before computed somehow\n\t\t// fixes an issue with getting wrong values\n\t\t// on detached elements\n\t\tstyle = elem.style;\n\n\tcomputed = computed || getStyles( elem );\n\n\t// getPropertyValue is needed for:\n\t//   .css('filter') (IE 9 only, #12537)\n\t//   .css('--customProperty) (#3144)\n\tif ( computed ) {\n\t\tret = computed.getPropertyValue( name ) || computed[ name ];\n\n\t\tif ( ret === \"\" && !isAttached( elem ) ) {\n\t\t\tret = jQuery.style( elem, name );\n\t\t}\n\n\t\t// A tribute to the \"awesome hack by Dean Edwards\"\n\t\t// Android Browser returns percentage for some values,\n\t\t// but width seems to be reliably pixels.\n\t\t// This is against the CSSOM draft spec:\n\t\t// https://drafts.csswg.org/cssom/#resolved-values\n\t\tif ( !support.pixelBoxStyles() && rnumnonpx.test( ret ) && rboxStyle.test( name ) ) {\n\n\t\t\t// Remember the original values\n\t\t\twidth = style.width;\n\t\t\tminWidth = style.minWidth;\n\t\t\tmaxWidth = style.maxWidth;\n\n\t\t\t// Put in the new values to get a computed value out\n\t\t\tstyle.minWidth = style.maxWidth = style.width = ret;\n\t\t\tret = computed.width;\n\n\t\t\t// Revert the changed values\n\t\t\tstyle.width = width;\n\t\t\tstyle.minWidth = minWidth;\n\t\t\tstyle.maxWidth = maxWidth;\n\t\t}\n\t}\n\n\treturn ret !== undefined ?\n\n\t\t// Support: IE <=9 - 11 only\n\t\t// IE returns zIndex value as an integer.\n\t\tret + \"\" :\n\t\tret;\n}\n\n\nfunction addGetHookIf( conditionFn, hookFn ) {\n\n\t// Define the hook, we'll check on the first run if it's really needed.\n\treturn {\n\t\tget: function() {\n\t\t\tif ( conditionFn() ) {\n\n\t\t\t\t// Hook not needed (or it's not possible to use it due\n\t\t\t\t// to missing dependency), remove it.\n\t\t\t\tdelete this.get;\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// Hook needed; redefine it so that the support test is not executed again.\n\t\t\treturn ( this.get = hookFn ).apply( this, arguments );\n\t\t}\n\t};\n}\n\n\nvar cssPrefixes = [ \"Webkit\", \"Moz\", \"ms\" ],\n\temptyStyle = document.createElement( \"div\" ).style,\n\tvendorProps = {};\n\n// Return a vendor-prefixed property or undefined\nfunction vendorPropName( name ) {\n\n\t// Check for vendor prefixed names\n\tvar capName = name[ 0 ].toUpperCase() + name.slice( 1 ),\n\t\ti = cssPrefixes.length;\n\n\twhile ( i-- ) {\n\t\tname = cssPrefixes[ i ] + capName;\n\t\tif ( name in emptyStyle ) {\n\t\t\treturn name;\n\t\t}\n\t}\n}\n\n// Return a potentially-mapped jQuery.cssProps or vendor prefixed property\nfunction finalPropName( name ) {\n\tvar final = jQuery.cssProps[ name ] || vendorProps[ name ];\n\n\tif ( final ) {\n\t\treturn final;\n\t}\n\tif ( name in emptyStyle ) {\n\t\treturn name;\n\t}\n\treturn vendorProps[ name ] = vendorPropName( name ) || name;\n}\n\n\nvar\n\n\t// Swappable if display is none or starts with table\n\t// except \"table\", \"table-cell\", or \"table-caption\"\n\t// See here for display values: https://developer.mozilla.org/en-US/docs/CSS/display\n\trdisplayswap = /^(none|table(?!-c[ea]).+)/,\n\trcustomProp = /^--/,\n\tcssShow = { position: \"absolute\", visibility: \"hidden\", display: \"block\" },\n\tcssNormalTransform = {\n\t\tletterSpacing: \"0\",\n\t\tfontWeight: \"400\"\n\t};\n\nfunction setPositiveNumber( elem, value, subtract ) {\n\n\t// Any relative (+/-) values have already been\n\t// normalized at this point\n\tvar matches = rcssNum.exec( value );\n\treturn matches ?\n\n\t\t// Guard against undefined \"subtract\", e.g., when used as in cssHooks\n\t\tMath.max( 0, matches[ 2 ] - ( subtract || 0 ) ) + ( matches[ 3 ] || \"px\" ) :\n\t\tvalue;\n}\n\nfunction boxModelAdjustment( elem, dimension, box, isBorderBox, styles, computedVal ) {\n\tvar i = dimension === \"width\" ? 1 : 0,\n\t\textra = 0,\n\t\tdelta = 0;\n\n\t// Adjustment may not be necessary\n\tif ( box === ( isBorderBox ? \"border\" : \"content\" ) ) {\n\t\treturn 0;\n\t}\n\n\tfor ( ; i < 4; i += 2 ) {\n\n\t\t// Both box models exclude margin\n\t\tif ( box === \"margin\" ) {\n\t\t\tdelta += jQuery.css( elem, box + cssExpand[ i ], true, styles );\n\t\t}\n\n\t\t// If we get here with a content-box, we're seeking \"padding\" or \"border\" or \"margin\"\n\t\tif ( !isBorderBox ) {\n\n\t\t\t// Add padding\n\t\t\tdelta += jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\n\t\t\t// For \"border\" or \"margin\", add border\n\t\t\tif ( box !== \"padding\" ) {\n\t\t\t\tdelta += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\n\t\t\t// But still keep track of it otherwise\n\t\t\t} else {\n\t\t\t\textra += jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\n\t\t// If we get here with a border-box (content + padding + border), we're seeking \"content\" or\n\t\t// \"padding\" or \"margin\"\n\t\t} else {\n\n\t\t\t// For \"content\", subtract padding\n\t\t\tif ( box === \"content\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"padding\" + cssExpand[ i ], true, styles );\n\t\t\t}\n\n\t\t\t// For \"content\" or \"padding\", subtract border\n\t\t\tif ( box !== \"margin\" ) {\n\t\t\t\tdelta -= jQuery.css( elem, \"border\" + cssExpand[ i ] + \"Width\", true, styles );\n\t\t\t}\n\t\t}\n\t}\n\n\t// Account for positive content-box scroll gutter when requested by providing computedVal\n\tif ( !isBorderBox && computedVal >= 0 ) {\n\n\t\t// offsetWidth/offsetHeight is a rounded sum of content, padding, scroll gutter, and border\n\t\t// Assuming integer scroll gutter, subtract the rest and round down\n\t\tdelta += Math.max( 0, Math.ceil(\n\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\tcomputedVal -\n\t\t\tdelta -\n\t\t\textra -\n\t\t\t0.5\n\n\t\t// If offsetWidth/offsetHeight is unknown, then we can't determine content-box scroll gutter\n\t\t// Use an explicit zero to avoid NaN (gh-3964)\n\t\t) ) || 0;\n\t}\n\n\treturn delta;\n}\n\nfunction getWidthOrHeight( elem, dimension, extra ) {\n\n\t// Start with computed style\n\tvar styles = getStyles( elem ),\n\n\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-4322).\n\t\t// Fake content-box until we know it's needed to know the true value.\n\t\tboxSizingNeeded = !support.boxSizingReliable() || extra,\n\t\tisBorderBox = boxSizingNeeded &&\n\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\tvalueIsBorderBox = isBorderBox,\n\n\t\tval = curCSS( elem, dimension, styles ),\n\t\toffsetProp = \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 );\n\n\t// Support: Firefox <=54\n\t// Return a confounding non-pixel value or feign ignorance, as appropriate.\n\tif ( rnumnonpx.test( val ) ) {\n\t\tif ( !extra ) {\n\t\t\treturn val;\n\t\t}\n\t\tval = \"auto\";\n\t}\n\n\n\t// Fall back to offsetWidth/offsetHeight when value is \"auto\"\n\t// This happens for inline elements with no explicit setting (gh-3571)\n\t// Support: Android <=4.1 - 4.3 only\n\t// Also use offsetWidth/offsetHeight for misreported inline dimensions (gh-3602)\n\t// Support: IE 9-11 only\n\t// Also use offsetWidth/offsetHeight for when box sizing is unreliable\n\t// We use getClientRects() to check for hidden/disconnected.\n\t// In those cases, the computed value can be trusted to be border-box\n\tif ( ( !support.boxSizingReliable() && isBorderBox ||\n\t\tval === \"auto\" ||\n\t\t!parseFloat( val ) && jQuery.css( elem, \"display\", false, styles ) === \"inline\" ) &&\n\t\telem.getClientRects().length ) {\n\n\t\tisBorderBox = jQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\";\n\n\t\t// Where available, offsetWidth/offsetHeight approximate border box dimensions.\n\t\t// Where not available (e.g., SVG), assume unreliable box-sizing and interpret the\n\t\t// retrieved value as a content box dimension.\n\t\tvalueIsBorderBox = offsetProp in elem;\n\t\tif ( valueIsBorderBox ) {\n\t\t\tval = elem[ offsetProp ];\n\t\t}\n\t}\n\n\t// Normalize \"\" and auto\n\tval = parseFloat( val ) || 0;\n\n\t// Adjust for the element's box model\n\treturn ( val +\n\t\tboxModelAdjustment(\n\t\t\telem,\n\t\t\tdimension,\n\t\t\textra || ( isBorderBox ? \"border\" : \"content\" ),\n\t\t\tvalueIsBorderBox,\n\t\t\tstyles,\n\n\t\t\t// Provide the current computed size to request scroll gutter calculation (gh-3589)\n\t\t\tval\n\t\t)\n\t) + \"px\";\n}\n\njQuery.extend( {\n\n\t// Add in style property hooks for overriding the default\n\t// behavior of getting and setting a style property\n\tcssHooks: {\n\t\topacity: {\n\t\t\tget: function( elem, computed ) {\n\t\t\t\tif ( computed ) {\n\n\t\t\t\t\t// We should always get a number back from opacity\n\t\t\t\t\tvar ret = curCSS( elem, \"opacity\" );\n\t\t\t\t\treturn ret === \"\" ? \"1\" : ret;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\t// Don't automatically add \"px\" to these possibly-unitless properties\n\tcssNumber: {\n\t\t\"animationIterationCount\": true,\n\t\t\"columnCount\": true,\n\t\t\"fillOpacity\": true,\n\t\t\"flexGrow\": true,\n\t\t\"flexShrink\": true,\n\t\t\"fontWeight\": true,\n\t\t\"gridArea\": true,\n\t\t\"gridColumn\": true,\n\t\t\"gridColumnEnd\": true,\n\t\t\"gridColumnStart\": true,\n\t\t\"gridRow\": true,\n\t\t\"gridRowEnd\": true,\n\t\t\"gridRowStart\": true,\n\t\t\"lineHeight\": true,\n\t\t\"opacity\": true,\n\t\t\"order\": true,\n\t\t\"orphans\": true,\n\t\t\"widows\": true,\n\t\t\"zIndex\": true,\n\t\t\"zoom\": true\n\t},\n\n\t// Add in properties whose names you wish to fix before\n\t// setting or getting the value\n\tcssProps: {},\n\n\t// Get and set the style property on a DOM Node\n\tstyle: function( elem, name, value, extra ) {\n\n\t\t// Don't set styles on text and comment nodes\n\t\tif ( !elem || elem.nodeType === 3 || elem.nodeType === 8 || !elem.style ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Make sure that we're working with the right name\n\t\tvar ret, type, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name ),\n\t\t\tstyle = elem.style;\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to query the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Gets hook for the prefixed version, then unprefixed version\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// Check if we're setting a value\n\t\tif ( value !== undefined ) {\n\t\t\ttype = typeof value;\n\n\t\t\t// Convert \"+=\" or \"-=\" to relative numbers (#7345)\n\t\t\tif ( type === \"string\" && ( ret = rcssNum.exec( value ) ) && ret[ 1 ] ) {\n\t\t\t\tvalue = adjustCSS( elem, name, ret );\n\n\t\t\t\t// Fixes bug #9237\n\t\t\t\ttype = \"number\";\n\t\t\t}\n\n\t\t\t// Make sure that null and NaN values aren't set (#7116)\n\t\t\tif ( value == null || value !== value ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\t// If a number was passed in, add the unit (except for certain CSS properties)\n\t\t\t// The isCustomProp check can be removed in jQuery 4.0 when we only auto-append\n\t\t\t// \"px\" to a few hardcoded values.\n\t\t\tif ( type === \"number\" && !isCustomProp ) {\n\t\t\t\tvalue += ret && ret[ 3 ] || ( jQuery.cssNumber[ origName ] ? \"\" : \"px\" );\n\t\t\t}\n\n\t\t\t// background-* props affect original clone's values\n\t\t\tif ( !support.clearCloneStyle && value === \"\" && name.indexOf( \"background\" ) === 0 ) {\n\t\t\t\tstyle[ name ] = \"inherit\";\n\t\t\t}\n\n\t\t\t// If a hook was provided, use that value, otherwise just set the specified value\n\t\t\tif ( !hooks || !( \"set\" in hooks ) ||\n\t\t\t\t( value = hooks.set( elem, value, extra ) ) !== undefined ) {\n\n\t\t\t\tif ( isCustomProp ) {\n\t\t\t\t\tstyle.setProperty( name, value );\n\t\t\t\t} else {\n\t\t\t\t\tstyle[ name ] = value;\n\t\t\t\t}\n\t\t\t}\n\n\t\t} else {\n\n\t\t\t// If a hook was provided get the non-computed value from there\n\t\t\tif ( hooks && \"get\" in hooks &&\n\t\t\t\t( ret = hooks.get( elem, false, extra ) ) !== undefined ) {\n\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\t// Otherwise just get the value from the style object\n\t\t\treturn style[ name ];\n\t\t}\n\t},\n\n\tcss: function( elem, name, extra, styles ) {\n\t\tvar val, num, hooks,\n\t\t\torigName = camelCase( name ),\n\t\t\tisCustomProp = rcustomProp.test( name );\n\n\t\t// Make sure that we're working with the right name. We don't\n\t\t// want to modify the value if it is a CSS custom property\n\t\t// since they are user-defined.\n\t\tif ( !isCustomProp ) {\n\t\t\tname = finalPropName( origName );\n\t\t}\n\n\t\t// Try prefixed name followed by the unprefixed name\n\t\thooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ];\n\n\t\t// If a hook was provided get the computed value from there\n\t\tif ( hooks && \"get\" in hooks ) {\n\t\t\tval = hooks.get( elem, true, extra );\n\t\t}\n\n\t\t// Otherwise, if a way to get the computed value exists, use that\n\t\tif ( val === undefined ) {\n\t\t\tval = curCSS( elem, name, styles );\n\t\t}\n\n\t\t// Convert \"normal\" to computed value\n\t\tif ( val === \"normal\" && name in cssNormalTransform ) {\n\t\t\tval = cssNormalTransform[ name ];\n\t\t}\n\n\t\t// Make numeric if forced or a qualifier was provided and val looks numeric\n\t\tif ( extra === \"\" || extra ) {\n\t\t\tnum = parseFloat( val );\n\t\t\treturn extra === true || isFinite( num ) ? num || 0 : val;\n\t\t}\n\n\t\treturn val;\n\t}\n} );\n\njQuery.each( [ \"height\", \"width\" ], function( i, dimension ) {\n\tjQuery.cssHooks[ dimension ] = {\n\t\tget: function( elem, computed, extra ) {\n\t\t\tif ( computed ) {\n\n\t\t\t\t// Certain elements can have dimension info if we invisibly show them\n\t\t\t\t// but it must have a current display style that would benefit\n\t\t\t\treturn rdisplayswap.test( jQuery.css( elem, \"display\" ) ) &&\n\n\t\t\t\t\t// Support: Safari 8+\n\t\t\t\t\t// Table columns in Safari have non-zero offsetWidth & zero\n\t\t\t\t\t// getBoundingClientRect().width unless display is changed.\n\t\t\t\t\t// Support: IE <=11 only\n\t\t\t\t\t// Running getBoundingClientRect on a disconnected node\n\t\t\t\t\t// in IE throws an error.\n\t\t\t\t\t( !elem.getClientRects().length || !elem.getBoundingClientRect().width ) ?\n\t\t\t\t\t\tswap( elem, cssShow, function() {\n\t\t\t\t\t\t\treturn getWidthOrHeight( elem, dimension, extra );\n\t\t\t\t\t\t} ) :\n\t\t\t\t\t\tgetWidthOrHeight( elem, dimension, extra );\n\t\t\t}\n\t\t},\n\n\t\tset: function( elem, value, extra ) {\n\t\t\tvar matches,\n\t\t\t\tstyles = getStyles( elem ),\n\n\t\t\t\t// Only read styles.position if the test has a chance to fail\n\t\t\t\t// to avoid forcing a reflow.\n\t\t\t\tscrollboxSizeBuggy = !support.scrollboxSize() &&\n\t\t\t\t\tstyles.position === \"absolute\",\n\n\t\t\t\t// To avoid forcing a reflow, only fetch boxSizing if we need it (gh-3991)\n\t\t\t\tboxSizingNeeded = scrollboxSizeBuggy || extra,\n\t\t\t\tisBorderBox = boxSizingNeeded &&\n\t\t\t\t\tjQuery.css( elem, \"boxSizing\", false, styles ) === \"border-box\",\n\t\t\t\tsubtract = extra ?\n\t\t\t\t\tboxModelAdjustment(\n\t\t\t\t\t\telem,\n\t\t\t\t\t\tdimension,\n\t\t\t\t\t\textra,\n\t\t\t\t\t\tisBorderBox,\n\t\t\t\t\t\tstyles\n\t\t\t\t\t) :\n\t\t\t\t\t0;\n\n\t\t\t// Account for unreliable border-box dimensions by comparing offset* to computed and\n\t\t\t// faking a content-box to get border and padding (gh-3699)\n\t\t\tif ( isBorderBox && scrollboxSizeBuggy ) {\n\t\t\t\tsubtract -= Math.ceil(\n\t\t\t\t\telem[ \"offset\" + dimension[ 0 ].toUpperCase() + dimension.slice( 1 ) ] -\n\t\t\t\t\tparseFloat( styles[ dimension ] ) -\n\t\t\t\t\tboxModelAdjustment( elem, dimension, \"border\", false, styles ) -\n\t\t\t\t\t0.5\n\t\t\t\t);\n\t\t\t}\n\n\t\t\t// Convert to pixels if value adjustment is needed\n\t\t\tif ( subtract && ( matches = rcssNum.exec( value ) ) &&\n\t\t\t\t( matches[ 3 ] || \"px\" ) !== \"px\" ) {\n\n\t\t\t\telem.style[ dimension ] = value;\n\t\t\t\tvalue = jQuery.css( elem, dimension );\n\t\t\t}\n\n\t\t\treturn setPositiveNumber( elem, value, subtract );\n\t\t}\n\t};\n} );\n\njQuery.cssHooks.marginLeft = addGetHookIf( support.reliableMarginLeft,\n\tfunction( elem, computed ) {\n\t\tif ( computed ) {\n\t\t\treturn ( parseFloat( curCSS( elem, \"marginLeft\" ) ) ||\n\t\t\t\telem.getBoundingClientRect().left -\n\t\t\t\t\tswap( elem, { marginLeft: 0 }, function() {\n\t\t\t\t\t\treturn elem.getBoundingClientRect().left;\n\t\t\t\t\t} )\n\t\t\t\t) + \"px\";\n\t\t}\n\t}\n);\n\n// These hooks are used by animate to expand properties\njQuery.each( {\n\tmargin: \"\",\n\tpadding: \"\",\n\tborder: \"Width\"\n}, function( prefix, suffix ) {\n\tjQuery.cssHooks[ prefix + suffix ] = {\n\t\texpand: function( value ) {\n\t\t\tvar i = 0,\n\t\t\t\texpanded = {},\n\n\t\t\t\t// Assumes a single number if not a string\n\t\t\t\tparts = typeof value === \"string\" ? value.split( \" \" ) : [ value ];\n\n\t\t\tfor ( ; i < 4; i++ ) {\n\t\t\t\texpanded[ prefix + cssExpand[ i ] + suffix ] =\n\t\t\t\t\tparts[ i ] || parts[ i - 2 ] || parts[ 0 ];\n\t\t\t}\n\n\t\t\treturn expanded;\n\t\t}\n\t};\n\n\tif ( prefix !== \"margin\" ) {\n\t\tjQuery.cssHooks[ prefix + suffix ].set = setPositiveNumber;\n\t}\n} );\n\njQuery.fn.extend( {\n\tcss: function( name, value ) {\n\t\treturn access( this, function( elem, name, value ) {\n\t\t\tvar styles, len,\n\t\t\t\tmap = {},\n\t\t\t\ti = 0;\n\n\t\t\tif ( Array.isArray( name ) ) {\n\t\t\t\tstyles = getStyles( elem );\n\t\t\t\tlen = name.length;\n\n\t\t\t\tfor ( ; i < len; i++ ) {\n\t\t\t\t\tmap[ name[ i ] ] = jQuery.css( elem, name[ i ], false, styles );\n\t\t\t\t}\n\n\t\t\t\treturn map;\n\t\t\t}\n\n\t\t\treturn value !== undefined ?\n\t\t\t\tjQuery.style( elem, name, value ) :\n\t\t\t\tjQuery.css( elem, name );\n\t\t}, name, value, arguments.length > 1 );\n\t}\n} );\n\n\n// Based off of the plugin by Clint Helfers, with permission.\n// https://web.archive.org/web/20100324014747/http://blindsignals.com/index.php/2009/07/jquery-delay/\njQuery.fn.delay = function( time, type ) {\n\ttime = jQuery.fx ? jQuery.fx.speeds[ time ] || time : time;\n\ttype = type || \"fx\";\n\n\treturn this.queue( type, function( next, hooks ) {\n\t\tvar timeout = window.setTimeout( next, time );\n\t\thooks.stop = function() {\n\t\t\twindow.clearTimeout( timeout );\n\t\t};\n\t} );\n};\n\n\n( function() {\n\tvar input = document.createElement( \"input\" ),\n\t\tselect = document.createElement( \"select\" ),\n\t\topt = select.appendChild( document.createElement( \"option\" ) );\n\n\tinput.type = \"checkbox\";\n\n\t// Support: Android <=4.3 only\n\t// Default value for a checkbox should be \"on\"\n\tsupport.checkOn = input.value !== \"\";\n\n\t// Support: IE <=11 only\n\t// Must access selectedIndex to make default options select\n\tsupport.optSelected = opt.selected;\n\n\t// Support: IE <=11 only\n\t// An input loses its value after becoming a radio\n\tinput = document.createElement( \"input\" );\n\tinput.value = \"t\";\n\tinput.type = \"radio\";\n\tsupport.radioValue = input.value === \"t\";\n} )();\n\n\nvar boolHook,\n\tattrHandle = jQuery.expr.attrHandle;\n\njQuery.fn.extend( {\n\tattr: function( name, value ) {\n\t\treturn access( this, jQuery.attr, name, value, arguments.length > 1 );\n\t},\n\n\tremoveAttr: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.removeAttr( this, name );\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tattr: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set attributes on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Fallback to prop when attributes are not supported\n\t\tif ( typeof elem.getAttribute === \"undefined\" ) {\n\t\t\treturn jQuery.prop( elem, name, value );\n\t\t}\n\n\t\t// Attribute hooks are determined by the lowercase version\n\t\t// Grab necessary hook if one is defined\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\t\t\thooks = jQuery.attrHooks[ name.toLowerCase() ] ||\n\t\t\t\t( jQuery.expr.match.bool.test( name ) ? boolHook : undefined );\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( value === null ) {\n\t\t\t\tjQuery.removeAttr( elem, name );\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\telem.setAttribute( name, value + \"\" );\n\t\t\treturn value;\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\tret = jQuery.find.attr( elem, name );\n\n\t\t// Non-existent attributes return null, we normalize to undefined\n\t\treturn ret == null ? undefined : ret;\n\t},\n\n\tattrHooks: {\n\t\ttype: {\n\t\t\tset: function( elem, value ) {\n\t\t\t\tif ( !support.radioValue && value === \"radio\" &&\n\t\t\t\t\tnodeName( elem, \"input\" ) ) {\n\t\t\t\t\tvar val = elem.value;\n\t\t\t\t\telem.setAttribute( \"type\", value );\n\t\t\t\t\tif ( val ) {\n\t\t\t\t\t\telem.value = val;\n\t\t\t\t\t}\n\t\t\t\t\treturn value;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t},\n\n\tremoveAttr: function( elem, value ) {\n\t\tvar name,\n\t\t\ti = 0,\n\n\t\t\t// Attribute names can contain non-HTML whitespace characters\n\t\t\t// https://html.spec.whatwg.org/multipage/syntax.html#attributes-2\n\t\t\tattrNames = value && value.match( rnothtmlwhite );\n\n\t\tif ( attrNames && elem.nodeType === 1 ) {\n\t\t\twhile ( ( name = attrNames[ i++ ] ) ) {\n\t\t\t\telem.removeAttribute( name );\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Hooks for boolean attributes\nboolHook = {\n\tset: function( elem, value, name ) {\n\t\tif ( value === false ) {\n\n\t\t\t// Remove boolean attributes when set to false\n\t\t\tjQuery.removeAttr( elem, name );\n\t\t} else {\n\t\t\telem.setAttribute( name, name );\n\t\t}\n\t\treturn name;\n\t}\n};\n\njQuery.each( jQuery.expr.match.bool.source.match( /\\w+/g ), function( i, name ) {\n\tvar getter = attrHandle[ name ] || jQuery.find.attr;\n\n\tattrHandle[ name ] = function( elem, name, isXML ) {\n\t\tvar ret, handle,\n\t\t\tlowercaseName = name.toLowerCase();\n\n\t\tif ( !isXML ) {\n\n\t\t\t// Avoid an infinite loop by temporarily removing this function from the getter\n\t\t\thandle = attrHandle[ lowercaseName ];\n\t\t\tattrHandle[ lowercaseName ] = ret;\n\t\t\tret = getter( elem, name, isXML ) != null ?\n\t\t\t\tlowercaseName :\n\t\t\t\tnull;\n\t\t\tattrHandle[ lowercaseName ] = handle;\n\t\t}\n\t\treturn ret;\n\t};\n} );\n\n\n\n\nvar rfocusable = /^(?:input|select|textarea|button)$/i,\n\trclickable = /^(?:a|area)$/i;\n\njQuery.fn.extend( {\n\tprop: function( name, value ) {\n\t\treturn access( this, jQuery.prop, name, value, arguments.length > 1 );\n\t},\n\n\tremoveProp: function( name ) {\n\t\treturn this.each( function() {\n\t\t\tdelete this[ jQuery.propFix[ name ] || name ];\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tprop: function( elem, name, value ) {\n\t\tvar ret, hooks,\n\t\t\tnType = elem.nodeType;\n\n\t\t// Don't get/set properties on text, comment and attribute nodes\n\t\tif ( nType === 3 || nType === 8 || nType === 2 ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) {\n\n\t\t\t// Fix name and attach hooks\n\t\t\tname = jQuery.propFix[ name ] || name;\n\t\t\thooks = jQuery.propHooks[ name ];\n\t\t}\n\n\t\tif ( value !== undefined ) {\n\t\t\tif ( hooks && \"set\" in hooks &&\n\t\t\t\t( ret = hooks.set( elem, value, name ) ) !== undefined ) {\n\t\t\t\treturn ret;\n\t\t\t}\n\n\t\t\treturn ( elem[ name ] = value );\n\t\t}\n\n\t\tif ( hooks && \"get\" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) {\n\t\t\treturn ret;\n\t\t}\n\n\t\treturn elem[ name ];\n\t},\n\n\tpropHooks: {\n\t\ttabIndex: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\t// Support: IE <=9 - 11 only\n\t\t\t\t// elem.tabIndex doesn't always return the\n\t\t\t\t// correct value when it hasn't been explicitly set\n\t\t\t\t// https://web.archive.org/web/20141116233347/http://fluidproject.org/blog/2008/01/09/getting-setting-and-removing-tabindex-values-with-javascript/\n\t\t\t\t// Use proper attribute retrieval(#12072)\n\t\t\t\tvar tabindex = jQuery.find.attr( elem, \"tabindex\" );\n\n\t\t\t\tif ( tabindex ) {\n\t\t\t\t\treturn parseInt( tabindex, 10 );\n\t\t\t\t}\n\n\t\t\t\tif (\n\t\t\t\t\trfocusable.test( elem.nodeName ) ||\n\t\t\t\t\trclickable.test( elem.nodeName ) &&\n\t\t\t\t\telem.href\n\t\t\t\t) {\n\t\t\t\t\treturn 0;\n\t\t\t\t}\n\n\t\t\t\treturn -1;\n\t\t\t}\n\t\t}\n\t},\n\n\tpropFix: {\n\t\t\"for\": \"htmlFor\",\n\t\t\"class\": \"className\"\n\t}\n} );\n\n// Support: IE <=11 only\n// Accessing the selectedIndex property\n// forces the browser to respect setting selected\n// on the option\n// The getter ensures a default option is selected\n// when in an optgroup\n// eslint rule \"no-unused-expressions\" is disabled for this code\n// since it considers such accessions noop\nif ( !support.optSelected ) {\n\tjQuery.propHooks.selected = {\n\t\tget: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent && parent.parentNode ) {\n\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t}\n\t\t\treturn null;\n\t\t},\n\t\tset: function( elem ) {\n\n\t\t\t/* eslint no-unused-expressions: \"off\" */\n\n\t\t\tvar parent = elem.parentNode;\n\t\t\tif ( parent ) {\n\t\t\t\tparent.selectedIndex;\n\n\t\t\t\tif ( parent.parentNode ) {\n\t\t\t\t\tparent.parentNode.selectedIndex;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t};\n}\n\njQuery.each( [\n\t\"tabIndex\",\n\t\"readOnly\",\n\t\"maxLength\",\n\t\"cellSpacing\",\n\t\"cellPadding\",\n\t\"rowSpan\",\n\t\"colSpan\",\n\t\"useMap\",\n\t\"frameBorder\",\n\t\"contentEditable\"\n], function() {\n\tjQuery.propFix[ this.toLowerCase() ] = this;\n} );\n\n\n\n\n\t// Strip and collapse whitespace according to HTML spec\n\t// https://infra.spec.whatwg.org/#strip-and-collapse-ascii-whitespace\n\tfunction stripAndCollapse( value ) {\n\t\tvar tokens = value.match( rnothtmlwhite ) || [];\n\t\treturn tokens.join( \" \" );\n\t}\n\n\nfunction getClass( elem ) {\n\treturn elem.getAttribute && elem.getAttribute( \"class\" ) || \"\";\n}\n\nfunction classesToArray( value ) {\n\tif ( Array.isArray( value ) ) {\n\t\treturn value;\n\t}\n\tif ( typeof value === \"string\" ) {\n\t\treturn value.match( rnothtmlwhite ) || [];\n\t}\n\treturn [];\n}\n\njQuery.fn.extend( {\n\taddClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).addClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\t\t\t\t\t\tif ( cur.indexOf( \" \" + clazz + \" \" ) < 0 ) {\n\t\t\t\t\t\t\tcur += clazz + \" \";\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\tremoveClass: function( value ) {\n\t\tvar classes, elem, cur, curValue, clazz, j, finalValue,\n\t\t\ti = 0;\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( j ) {\n\t\t\t\tjQuery( this ).removeClass( value.call( this, j, getClass( this ) ) );\n\t\t\t} );\n\t\t}\n\n\t\tif ( !arguments.length ) {\n\t\t\treturn this.attr( \"class\", \"\" );\n\t\t}\n\n\t\tclasses = classesToArray( value );\n\n\t\tif ( classes.length ) {\n\t\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\t\tcurValue = getClass( elem );\n\n\t\t\t\t// This expression is here for better compressibility (see addClass)\n\t\t\t\tcur = elem.nodeType === 1 && ( \" \" + stripAndCollapse( curValue ) + \" \" );\n\n\t\t\t\tif ( cur ) {\n\t\t\t\t\tj = 0;\n\t\t\t\t\twhile ( ( clazz = classes[ j++ ] ) ) {\n\n\t\t\t\t\t\t// Remove *all* instances\n\t\t\t\t\t\twhile ( cur.indexOf( \" \" + clazz + \" \" ) > -1 ) {\n\t\t\t\t\t\t\tcur = cur.replace( \" \" + clazz + \" \", \" \" );\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\n\t\t\t\t\t// Only assign if different to avoid unneeded rendering.\n\t\t\t\t\tfinalValue = stripAndCollapse( cur );\n\t\t\t\t\tif ( curValue !== finalValue ) {\n\t\t\t\t\t\telem.setAttribute( \"class\", finalValue );\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn this;\n\t},\n\n\ttoggleClass: function( value, stateVal ) {\n\t\tvar type = typeof value,\n\t\t\tisValidValue = type === \"string\" || Array.isArray( value );\n\n\t\tif ( typeof stateVal === \"boolean\" && isValidValue ) {\n\t\t\treturn stateVal ? this.addClass( value ) : this.removeClass( value );\n\t\t}\n\n\t\tif ( isFunction( value ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).toggleClass(\n\t\t\t\t\tvalue.call( this, i, getClass( this ), stateVal ),\n\t\t\t\t\tstateVal\n\t\t\t\t);\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar className, i, self, classNames;\n\n\t\t\tif ( isValidValue ) {\n\n\t\t\t\t// Toggle individual class names\n\t\t\t\ti = 0;\n\t\t\t\tself = jQuery( this );\n\t\t\t\tclassNames = classesToArray( value );\n\n\t\t\t\twhile ( ( className = classNames[ i++ ] ) ) {\n\n\t\t\t\t\t// Check each className given, space separated list\n\t\t\t\t\tif ( self.hasClass( className ) ) {\n\t\t\t\t\t\tself.removeClass( className );\n\t\t\t\t\t} else {\n\t\t\t\t\t\tself.addClass( className );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t// Toggle whole class name\n\t\t\t} else if ( value === undefined || type === \"boolean\" ) {\n\t\t\t\tclassName = getClass( this );\n\t\t\t\tif ( className ) {\n\n\t\t\t\t\t// Store className if set\n\t\t\t\t\tdataPriv.set( this, \"__className__\", className );\n\t\t\t\t}\n\n\t\t\t\t// If the element has a class name or if we're passed `false`,\n\t\t\t\t// then remove the whole classname (if there was one, the above saved it).\n\t\t\t\t// Otherwise bring back whatever was previously saved (if anything),\n\t\t\t\t// falling back to the empty string if nothing was stored.\n\t\t\t\tif ( this.setAttribute ) {\n\t\t\t\t\tthis.setAttribute( \"class\",\n\t\t\t\t\t\tclassName || value === false ?\n\t\t\t\t\t\t\"\" :\n\t\t\t\t\t\tdataPriv.get( this, \"__className__\" ) || \"\"\n\t\t\t\t\t);\n\t\t\t\t}\n\t\t\t}\n\t\t} );\n\t},\n\n\thasClass: function( selector ) {\n\t\tvar className, elem,\n\t\t\ti = 0;\n\n\t\tclassName = \" \" + selector + \" \";\n\t\twhile ( ( elem = this[ i++ ] ) ) {\n\t\t\tif ( elem.nodeType === 1 &&\n\t\t\t\t( \" \" + stripAndCollapse( getClass( elem ) ) + \" \" ).indexOf( className ) > -1 ) {\n\t\t\t\t\treturn true;\n\t\t\t}\n\t\t}\n\n\t\treturn false;\n\t}\n} );\n\n\n\n\nvar rreturn = /\\r/g;\n\njQuery.fn.extend( {\n\tval: function( value ) {\n\t\tvar hooks, ret, valueIsFunction,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !arguments.length ) {\n\t\t\tif ( elem ) {\n\t\t\t\thooks = jQuery.valHooks[ elem.type ] ||\n\t\t\t\t\tjQuery.valHooks[ elem.nodeName.toLowerCase() ];\n\n\t\t\t\tif ( hooks &&\n\t\t\t\t\t\"get\" in hooks &&\n\t\t\t\t\t( ret = hooks.get( elem, \"value\" ) ) !== undefined\n\t\t\t\t) {\n\t\t\t\t\treturn ret;\n\t\t\t\t}\n\n\t\t\t\tret = elem.value;\n\n\t\t\t\t// Handle most common string cases\n\t\t\t\tif ( typeof ret === \"string\" ) {\n\t\t\t\t\treturn ret.replace( rreturn, \"\" );\n\t\t\t\t}\n\n\t\t\t\t// Handle cases where value is null/undef or number\n\t\t\t\treturn ret == null ? \"\" : ret;\n\t\t\t}\n\n\t\t\treturn;\n\t\t}\n\n\t\tvalueIsFunction = isFunction( value );\n\n\t\treturn this.each( function( i ) {\n\t\t\tvar val;\n\n\t\t\tif ( this.nodeType !== 1 ) {\n\t\t\t\treturn;\n\t\t\t}\n\n\t\t\tif ( valueIsFunction ) {\n\t\t\t\tval = value.call( this, i, jQuery( this ).val() );\n\t\t\t} else {\n\t\t\t\tval = value;\n\t\t\t}\n\n\t\t\t// Treat null/undefined as \"\"; convert numbers to string\n\t\t\tif ( val == null ) {\n\t\t\t\tval = \"\";\n\n\t\t\t} else if ( typeof val === \"number\" ) {\n\t\t\t\tval += \"\";\n\n\t\t\t} else if ( Array.isArray( val ) ) {\n\t\t\t\tval = jQuery.map( val, function( value ) {\n\t\t\t\t\treturn value == null ? \"\" : value + \"\";\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\thooks = jQuery.valHooks[ this.type ] || jQuery.valHooks[ this.nodeName.toLowerCase() ];\n\n\t\t\t// If set returns undefined, fall back to normal setting\n\t\t\tif ( !hooks || !( \"set\" in hooks ) || hooks.set( this, val, \"value\" ) === undefined ) {\n\t\t\t\tthis.value = val;\n\t\t\t}\n\t\t} );\n\t}\n} );\n\njQuery.extend( {\n\tvalHooks: {\n\t\toption: {\n\t\t\tget: function( elem ) {\n\n\t\t\t\tvar val = jQuery.find.attr( elem, \"value\" );\n\t\t\t\treturn val != null ?\n\t\t\t\t\tval :\n\n\t\t\t\t\t// Support: IE <=10 - 11 only\n\t\t\t\t\t// option.text throws exceptions (#14686, #14858)\n\t\t\t\t\t// Strip and collapse whitespace\n\t\t\t\t\t// https://html.spec.whatwg.org/#strip-and-collapse-whitespace\n\t\t\t\t\tstripAndCollapse( jQuery.text( elem ) );\n\t\t\t}\n\t\t},\n\t\tselect: {\n\t\t\tget: function( elem ) {\n\t\t\t\tvar value, option, i,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tindex = elem.selectedIndex,\n\t\t\t\t\tone = elem.type === \"select-one\",\n\t\t\t\t\tvalues = one ? null : [],\n\t\t\t\t\tmax = one ? index + 1 : options.length;\n\n\t\t\t\tif ( index < 0 ) {\n\t\t\t\t\ti = max;\n\n\t\t\t\t} else {\n\t\t\t\t\ti = one ? index : 0;\n\t\t\t\t}\n\n\t\t\t\t// Loop through all the selected options\n\t\t\t\tfor ( ; i < max; i++ ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t// Support: IE <=9 only\n\t\t\t\t\t// IE8-9 doesn't update selected after form reset (#2551)\n\t\t\t\t\tif ( ( option.selected || i === index ) &&\n\n\t\t\t\t\t\t\t// Don't return options that are disabled or in a disabled optgroup\n\t\t\t\t\t\t\t!option.disabled &&\n\t\t\t\t\t\t\t( !option.parentNode.disabled ||\n\t\t\t\t\t\t\t\t!nodeName( option.parentNode, \"optgroup\" ) ) ) {\n\n\t\t\t\t\t\t// Get the specific value for the option\n\t\t\t\t\t\tvalue = jQuery( option ).val();\n\n\t\t\t\t\t\t// We don't need an array for one selects\n\t\t\t\t\t\tif ( one ) {\n\t\t\t\t\t\t\treturn value;\n\t\t\t\t\t\t}\n\n\t\t\t\t\t\t// Multi-Selects return an array\n\t\t\t\t\t\tvalues.push( value );\n\t\t\t\t\t}\n\t\t\t\t}\n\n\t\t\t\treturn values;\n\t\t\t},\n\n\t\t\tset: function( elem, value ) {\n\t\t\t\tvar optionSet, option,\n\t\t\t\t\toptions = elem.options,\n\t\t\t\t\tvalues = jQuery.makeArray( value ),\n\t\t\t\t\ti = options.length;\n\n\t\t\t\twhile ( i-- ) {\n\t\t\t\t\toption = options[ i ];\n\n\t\t\t\t\t/* eslint-disable no-cond-assign */\n\n\t\t\t\t\tif ( option.selected =\n\t\t\t\t\t\tjQuery.inArray( jQuery.valHooks.option.get( option ), values ) > -1\n\t\t\t\t\t) {\n\t\t\t\t\t\toptionSet = true;\n\t\t\t\t\t}\n\n\t\t\t\t\t/* eslint-enable no-cond-assign */\n\t\t\t\t}\n\n\t\t\t\t// Force browsers to behave consistently when non-matching value is set\n\t\t\t\tif ( !optionSet ) {\n\t\t\t\t\telem.selectedIndex = -1;\n\t\t\t\t}\n\t\t\t\treturn values;\n\t\t\t}\n\t\t}\n\t}\n} );\n\n// Radios and checkboxes getter/setter\njQuery.each( [ \"radio\", \"checkbox\" ], function() {\n\tjQuery.valHooks[ this ] = {\n\t\tset: function( elem, value ) {\n\t\t\tif ( Array.isArray( value ) ) {\n\t\t\t\treturn ( elem.checked = jQuery.inArray( jQuery( elem ).val(), value ) > -1 );\n\t\t\t}\n\t\t}\n\t};\n\tif ( !support.checkOn ) {\n\t\tjQuery.valHooks[ this ].get = function( elem ) {\n\t\t\treturn elem.getAttribute( \"value\" ) === null ? \"on\" : elem.value;\n\t\t};\n\t}\n} );\n\n\n\n\n// Return jQuery for attributes-only inclusion\n\n\nsupport.focusin = \"onfocusin\" in window;\n\n\nvar rfocusMorph = /^(?:focusinfocus|focusoutblur)$/,\n\tstopPropagationCallback = function( e ) {\n\t\te.stopPropagation();\n\t};\n\njQuery.extend( jQuery.event, {\n\n\ttrigger: function( event, data, elem, onlyHandlers ) {\n\n\t\tvar i, cur, tmp, bubbleType, ontype, handle, special, lastElement,\n\t\t\teventPath = [ elem || document ],\n\t\t\ttype = hasOwn.call( event, \"type\" ) ? event.type : event,\n\t\t\tnamespaces = hasOwn.call( event, \"namespace\" ) ? event.namespace.split( \".\" ) : [];\n\n\t\tcur = lastElement = tmp = elem = elem || document;\n\n\t\t// Don't do events on text and comment nodes\n\t\tif ( elem.nodeType === 3 || elem.nodeType === 8 ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// focus/blur morphs to focusin/out; ensure we're not firing them right now\n\t\tif ( rfocusMorph.test( type + jQuery.event.triggered ) ) {\n\t\t\treturn;\n\t\t}\n\n\t\tif ( type.indexOf( \".\" ) > -1 ) {\n\n\t\t\t// Namespaced trigger; create a regexp to match event type in handle()\n\t\t\tnamespaces = type.split( \".\" );\n\t\t\ttype = namespaces.shift();\n\t\t\tnamespaces.sort();\n\t\t}\n\t\tontype = type.indexOf( \":\" ) < 0 && \"on\" + type;\n\n\t\t// Caller can pass in a jQuery.Event object, Object, or just an event type string\n\t\tevent = event[ jQuery.expando ] ?\n\t\t\tevent :\n\t\t\tnew jQuery.Event( type, typeof event === \"object\" && event );\n\n\t\t// Trigger bitmask: & 1 for native handlers; & 2 for jQuery (always true)\n\t\tevent.isTrigger = onlyHandlers ? 2 : 3;\n\t\tevent.namespace = namespaces.join( \".\" );\n\t\tevent.rnamespace = event.namespace ?\n\t\t\tnew RegExp( \"(^|\\\\.)\" + namespaces.join( \"\\\\.(?:.*\\\\.|)\" ) + \"(\\\\.|$)\" ) :\n\t\t\tnull;\n\n\t\t// Clean up the event in case it is being reused\n\t\tevent.result = undefined;\n\t\tif ( !event.target ) {\n\t\t\tevent.target = elem;\n\t\t}\n\n\t\t// Clone any incoming data and prepend the event, creating the handler arg list\n\t\tdata = data == null ?\n\t\t\t[ event ] :\n\t\t\tjQuery.makeArray( data, [ event ] );\n\n\t\t// Allow special events to draw outside the lines\n\t\tspecial = jQuery.event.special[ type ] || {};\n\t\tif ( !onlyHandlers && special.trigger && special.trigger.apply( elem, data ) === false ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Determine event propagation path in advance, per W3C events spec (#9951)\n\t\t// Bubble up to document, then to window; watch for a global ownerDocument var (#9724)\n\t\tif ( !onlyHandlers && !special.noBubble && !isWindow( elem ) ) {\n\n\t\t\tbubbleType = special.delegateType || type;\n\t\t\tif ( !rfocusMorph.test( bubbleType + type ) ) {\n\t\t\t\tcur = cur.parentNode;\n\t\t\t}\n\t\t\tfor ( ; cur; cur = cur.parentNode ) {\n\t\t\t\teventPath.push( cur );\n\t\t\t\ttmp = cur;\n\t\t\t}\n\n\t\t\t// Only add window if we got to document (e.g., not plain obj or detached DOM)\n\t\t\tif ( tmp === ( elem.ownerDocument || document ) ) {\n\t\t\t\teventPath.push( tmp.defaultView || tmp.parentWindow || window );\n\t\t\t}\n\t\t}\n\n\t\t// Fire handlers on the event path\n\t\ti = 0;\n\t\twhile ( ( cur = eventPath[ i++ ] ) && !event.isPropagationStopped() ) {\n\t\t\tlastElement = cur;\n\t\t\tevent.type = i > 1 ?\n\t\t\t\tbubbleType :\n\t\t\t\tspecial.bindType || type;\n\n\t\t\t// jQuery handler\n\t\t\thandle = ( dataPriv.get( cur, \"events\" ) || {} )[ event.type ] &&\n\t\t\t\tdataPriv.get( cur, \"handle\" );\n\t\t\tif ( handle ) {\n\t\t\t\thandle.apply( cur, data );\n\t\t\t}\n\n\t\t\t// Native handler\n\t\t\thandle = ontype && cur[ ontype ];\n\t\t\tif ( handle && handle.apply && acceptData( cur ) ) {\n\t\t\t\tevent.result = handle.apply( cur, data );\n\t\t\t\tif ( event.result === false ) {\n\t\t\t\t\tevent.preventDefault();\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tevent.type = type;\n\n\t\t// If nobody prevented the default action, do it now\n\t\tif ( !onlyHandlers && !event.isDefaultPrevented() ) {\n\n\t\t\tif ( ( !special._default ||\n\t\t\t\tspecial._default.apply( eventPath.pop(), data ) === false ) &&\n\t\t\t\tacceptData( elem ) ) {\n\n\t\t\t\t// Call a native DOM method on the target with the same name as the event.\n\t\t\t\t// Don't do default actions on window, that's where global variables be (#6170)\n\t\t\t\tif ( ontype && isFunction( elem[ type ] ) && !isWindow( elem ) ) {\n\n\t\t\t\t\t// Don't re-trigger an onFOO event when we call its FOO() method\n\t\t\t\t\ttmp = elem[ ontype ];\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = null;\n\t\t\t\t\t}\n\n\t\t\t\t\t// Prevent re-triggering of the same event, since we already bubbled it above\n\t\t\t\t\tjQuery.event.triggered = type;\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.addEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\telem[ type ]();\n\n\t\t\t\t\tif ( event.isPropagationStopped() ) {\n\t\t\t\t\t\tlastElement.removeEventListener( type, stopPropagationCallback );\n\t\t\t\t\t}\n\n\t\t\t\t\tjQuery.event.triggered = undefined;\n\n\t\t\t\t\tif ( tmp ) {\n\t\t\t\t\t\telem[ ontype ] = tmp;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\n\t\treturn event.result;\n\t},\n\n\t// Piggyback on a donor event to simulate a different one\n\t// Used only for `focus(in | out)` events\n\tsimulate: function( type, elem, event ) {\n\t\tvar e = jQuery.extend(\n\t\t\tnew jQuery.Event(),\n\t\t\tevent,\n\t\t\t{\n\t\t\t\ttype: type,\n\t\t\t\tisSimulated: true\n\t\t\t}\n\t\t);\n\n\t\tjQuery.event.trigger( e, null, elem );\n\t}\n\n} );\n\njQuery.fn.extend( {\n\n\ttrigger: function( type, data ) {\n\t\treturn this.each( function() {\n\t\t\tjQuery.event.trigger( type, data, this );\n\t\t} );\n\t},\n\ttriggerHandler: function( type, data ) {\n\t\tvar elem = this[ 0 ];\n\t\tif ( elem ) {\n\t\t\treturn jQuery.event.trigger( type, data, elem, true );\n\t\t}\n\t}\n} );\n\n\n// Support: Firefox <=44\n// Firefox doesn't have focus(in | out) events\n// Related ticket - https://bugzilla.mozilla.org/show_bug.cgi?id=687787\n//\n// Support: Chrome <=48 - 49, Safari <=9.0 - 9.1\n// focus(in | out) events fire after focus & blur events,\n// which is spec violation - http://www.w3.org/TR/DOM-Level-3-Events/#events-focusevent-event-order\n// Related ticket - https://bugs.chromium.org/p/chromium/issues/detail?id=449857\nif ( !support.focusin ) {\n\tjQuery.each( { focus: \"focusin\", blur: \"focusout\" }, function( orig, fix ) {\n\n\t\t// Attach a single capturing handler on the document while someone wants focusin/focusout\n\t\tvar handler = function( event ) {\n\t\t\tjQuery.event.simulate( fix, event.target, jQuery.event.fix( event ) );\n\t\t};\n\n\t\tjQuery.event.special[ fix ] = {\n\t\t\tsetup: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix );\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.addEventListener( orig, handler, true );\n\t\t\t\t}\n\t\t\t\tdataPriv.access( doc, fix, ( attaches || 0 ) + 1 );\n\t\t\t},\n\t\t\tteardown: function() {\n\t\t\t\tvar doc = this.ownerDocument || this,\n\t\t\t\t\tattaches = dataPriv.access( doc, fix ) - 1;\n\n\t\t\t\tif ( !attaches ) {\n\t\t\t\t\tdoc.removeEventListener( orig, handler, true );\n\t\t\t\t\tdataPriv.remove( doc, fix );\n\n\t\t\t\t} else {\n\t\t\t\t\tdataPriv.access( doc, fix, attaches );\n\t\t\t\t}\n\t\t\t}\n\t\t};\n\t} );\n}\n\n\nvar\n\trbracket = /\\[\\]$/,\n\trCRLF = /\\r?\\n/g,\n\trsubmitterTypes = /^(?:submit|button|image|reset|file)$/i,\n\trsubmittable = /^(?:input|select|textarea|keygen)/i;\n\nfunction buildParams( prefix, obj, traditional, add ) {\n\tvar name;\n\n\tif ( Array.isArray( obj ) ) {\n\n\t\t// Serialize array item.\n\t\tjQuery.each( obj, function( i, v ) {\n\t\t\tif ( traditional || rbracket.test( prefix ) ) {\n\n\t\t\t\t// Treat each array item as a scalar.\n\t\t\t\tadd( prefix, v );\n\n\t\t\t} else {\n\n\t\t\t\t// Item is non-scalar (array or object), encode its numeric index.\n\t\t\t\tbuildParams(\n\t\t\t\t\tprefix + \"[\" + ( typeof v === \"object\" && v != null ? i : \"\" ) + \"]\",\n\t\t\t\t\tv,\n\t\t\t\t\ttraditional,\n\t\t\t\t\tadd\n\t\t\t\t);\n\t\t\t}\n\t\t} );\n\n\t} else if ( !traditional && toType( obj ) === \"object\" ) {\n\n\t\t// Serialize object item.\n\t\tfor ( name in obj ) {\n\t\t\tbuildParams( prefix + \"[\" + name + \"]\", obj[ name ], traditional, add );\n\t\t}\n\n\t} else {\n\n\t\t// Serialize scalar item.\n\t\tadd( prefix, obj );\n\t}\n}\n\n// Serialize an array of form elements or a set of\n// key/values into a query string\njQuery.param = function( a, traditional ) {\n\tvar prefix,\n\t\ts = [],\n\t\tadd = function( key, valueOrFunction ) {\n\n\t\t\t// If value is a function, invoke it and use its return value\n\t\t\tvar value = isFunction( valueOrFunction ) ?\n\t\t\t\tvalueOrFunction() :\n\t\t\t\tvalueOrFunction;\n\n\t\t\ts[ s.length ] = encodeURIComponent( key ) + \"=\" +\n\t\t\t\tencodeURIComponent( value == null ? \"\" : value );\n\t\t};\n\n\tif ( a == null ) {\n\t\treturn \"\";\n\t}\n\n\t// If an array was passed in, assume that it is an array of form elements.\n\tif ( Array.isArray( a ) || ( a.jquery && !jQuery.isPlainObject( a ) ) ) {\n\n\t\t// Serialize the form elements\n\t\tjQuery.each( a, function() {\n\t\t\tadd( this.name, this.value );\n\t\t} );\n\n\t} else {\n\n\t\t// If traditional, encode the \"old\" way (the way 1.3.2 or older\n\t\t// did it), otherwise encode params recursively.\n\t\tfor ( prefix in a ) {\n\t\t\tbuildParams( prefix, a[ prefix ], traditional, add );\n\t\t}\n\t}\n\n\t// Return the resulting serialization\n\treturn s.join( \"&\" );\n};\n\njQuery.fn.extend( {\n\tserialize: function() {\n\t\treturn jQuery.param( this.serializeArray() );\n\t},\n\tserializeArray: function() {\n\t\treturn this.map( function() {\n\n\t\t\t// Can add propHook for \"elements\" to filter or add form elements\n\t\t\tvar elements = jQuery.prop( this, \"elements\" );\n\t\t\treturn elements ? jQuery.makeArray( elements ) : this;\n\t\t} )\n\t\t.filter( function() {\n\t\t\tvar type = this.type;\n\n\t\t\t// Use .is( \":disabled\" ) so that fieldset[disabled] works\n\t\t\treturn this.name && !jQuery( this ).is( \":disabled\" ) &&\n\t\t\t\trsubmittable.test( this.nodeName ) && !rsubmitterTypes.test( type ) &&\n\t\t\t\t( this.checked || !rcheckableType.test( type ) );\n\t\t} )\n\t\t.map( function( i, elem ) {\n\t\t\tvar val = jQuery( this ).val();\n\n\t\t\tif ( val == null ) {\n\t\t\t\treturn null;\n\t\t\t}\n\n\t\t\tif ( Array.isArray( val ) ) {\n\t\t\t\treturn jQuery.map( val, function( val ) {\n\t\t\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t\t\t} );\n\t\t\t}\n\n\t\t\treturn { name: elem.name, value: val.replace( rCRLF, \"\\r\\n\" ) };\n\t\t} ).get();\n\t}\n} );\n\n\njQuery.fn.extend( {\n\twrapAll: function( html ) {\n\t\tvar wrap;\n\n\t\tif ( this[ 0 ] ) {\n\t\t\tif ( isFunction( html ) ) {\n\t\t\t\thtml = html.call( this[ 0 ] );\n\t\t\t}\n\n\t\t\t// The elements to wrap the target around\n\t\t\twrap = jQuery( html, this[ 0 ].ownerDocument ).eq( 0 ).clone( true );\n\n\t\t\tif ( this[ 0 ].parentNode ) {\n\t\t\t\twrap.insertBefore( this[ 0 ] );\n\t\t\t}\n\n\t\t\twrap.map( function() {\n\t\t\t\tvar elem = this;\n\n\t\t\t\twhile ( elem.firstElementChild ) {\n\t\t\t\t\telem = elem.firstElementChild;\n\t\t\t\t}\n\n\t\t\t\treturn elem;\n\t\t\t} ).append( this );\n\t\t}\n\n\t\treturn this;\n\t},\n\n\twrapInner: function( html ) {\n\t\tif ( isFunction( html ) ) {\n\t\t\treturn this.each( function( i ) {\n\t\t\t\tjQuery( this ).wrapInner( html.call( this, i ) );\n\t\t\t} );\n\t\t}\n\n\t\treturn this.each( function() {\n\t\t\tvar self = jQuery( this ),\n\t\t\t\tcontents = self.contents();\n\n\t\t\tif ( contents.length ) {\n\t\t\t\tcontents.wrapAll( html );\n\n\t\t\t} else {\n\t\t\t\tself.append( html );\n\t\t\t}\n\t\t} );\n\t},\n\n\twrap: function( html ) {\n\t\tvar htmlIsFunction = isFunction( html );\n\n\t\treturn this.each( function( i ) {\n\t\t\tjQuery( this ).wrapAll( htmlIsFunction ? html.call( this, i ) : html );\n\t\t} );\n\t},\n\n\tunwrap: function( selector ) {\n\t\tthis.parent( selector ).not( \"body\" ).each( function() {\n\t\t\tjQuery( this ).replaceWith( this.childNodes );\n\t\t} );\n\t\treturn this;\n\t}\n} );\n\n\njQuery.expr.pseudos.hidden = function( elem ) {\n\treturn !jQuery.expr.pseudos.visible( elem );\n};\njQuery.expr.pseudos.visible = function( elem ) {\n\treturn !!( elem.offsetWidth || elem.offsetHeight || elem.getClientRects().length );\n};\n\n\n\n\n// Support: Safari 8 only\n// In Safari 8 documents created via document.implementation.createHTMLDocument\n// collapse sibling forms: the second one becomes a child of the first one.\n// Because of that, this security measure has to be disabled in Safari 8.\n// https://bugs.webkit.org/show_bug.cgi?id=137337\nsupport.createHTMLDocument = ( function() {\n\tvar body = document.implementation.createHTMLDocument( \"\" ).body;\n\tbody.innerHTML = \"<form></form><form></form>\";\n\treturn body.childNodes.length === 2;\n} )();\n\n\n// Argument \"data\" should be string of html\n// context (optional): If specified, the fragment will be created in this context,\n// defaults to document\n// keepScripts (optional): If true, will include scripts passed in the html string\njQuery.parseHTML = function( data, context, keepScripts ) {\n\tif ( typeof data !== \"string\" ) {\n\t\treturn [];\n\t}\n\tif ( typeof context === \"boolean\" ) {\n\t\tkeepScripts = context;\n\t\tcontext = false;\n\t}\n\n\tvar base, parsed, scripts;\n\n\tif ( !context ) {\n\n\t\t// Stop scripts or inline event handlers from being executed immediately\n\t\t// by using document.implementation\n\t\tif ( support.createHTMLDocument ) {\n\t\t\tcontext = document.implementation.createHTMLDocument( \"\" );\n\n\t\t\t// Set the base href for the created document\n\t\t\t// so any parsed elements with URLs\n\t\t\t// are based on the document's URL (gh-2965)\n\t\t\tbase = context.createElement( \"base\" );\n\t\t\tbase.href = document.location.href;\n\t\t\tcontext.head.appendChild( base );\n\t\t} else {\n\t\t\tcontext = document;\n\t\t}\n\t}\n\n\tparsed = rsingleTag.exec( data );\n\tscripts = !keepScripts && [];\n\n\t// Single tag\n\tif ( parsed ) {\n\t\treturn [ context.createElement( parsed[ 1 ] ) ];\n\t}\n\n\tparsed = buildFragment( [ data ], context, scripts );\n\n\tif ( scripts && scripts.length ) {\n\t\tjQuery( scripts ).remove();\n\t}\n\n\treturn jQuery.merge( [], parsed.childNodes );\n};\n\n\njQuery.offset = {\n\tsetOffset: function( elem, options, i ) {\n\t\tvar curPosition, curLeft, curCSSTop, curTop, curOffset, curCSSLeft, calculatePosition,\n\t\t\tposition = jQuery.css( elem, \"position\" ),\n\t\t\tcurElem = jQuery( elem ),\n\t\t\tprops = {};\n\n\t\t// Set position first, in-case top/left are set even on static elem\n\t\tif ( position === \"static\" ) {\n\t\t\telem.style.position = \"relative\";\n\t\t}\n\n\t\tcurOffset = curElem.offset();\n\t\tcurCSSTop = jQuery.css( elem, \"top\" );\n\t\tcurCSSLeft = jQuery.css( elem, \"left\" );\n\t\tcalculatePosition = ( position === \"absolute\" || position === \"fixed\" ) &&\n\t\t\t( curCSSTop + curCSSLeft ).indexOf( \"auto\" ) > -1;\n\n\t\t// Need to be able to calculate position if either\n\t\t// top or left is auto and position is either absolute or fixed\n\t\tif ( calculatePosition ) {\n\t\t\tcurPosition = curElem.position();\n\t\t\tcurTop = curPosition.top;\n\t\t\tcurLeft = curPosition.left;\n\n\t\t} else {\n\t\t\tcurTop = parseFloat( curCSSTop ) || 0;\n\t\t\tcurLeft = parseFloat( curCSSLeft ) || 0;\n\t\t}\n\n\t\tif ( isFunction( options ) ) {\n\n\t\t\t// Use jQuery.extend here to allow modification of coordinates argument (gh-1848)\n\t\t\toptions = options.call( elem, i, jQuery.extend( {}, curOffset ) );\n\t\t}\n\n\t\tif ( options.top != null ) {\n\t\t\tprops.top = ( options.top - curOffset.top ) + curTop;\n\t\t}\n\t\tif ( options.left != null ) {\n\t\t\tprops.left = ( options.left - curOffset.left ) + curLeft;\n\t\t}\n\n\t\tif ( \"using\" in options ) {\n\t\t\toptions.using.call( elem, props );\n\n\t\t} else {\n\t\t\tcurElem.css( props );\n\t\t}\n\t}\n};\n\njQuery.fn.extend( {\n\n\t// offset() relates an element's border box to the document origin\n\toffset: function( options ) {\n\n\t\t// Preserve chaining for setter\n\t\tif ( arguments.length ) {\n\t\t\treturn options === undefined ?\n\t\t\t\tthis :\n\t\t\t\tthis.each( function( i ) {\n\t\t\t\t\tjQuery.offset.setOffset( this, options, i );\n\t\t\t\t} );\n\t\t}\n\n\t\tvar rect, win,\n\t\t\telem = this[ 0 ];\n\n\t\tif ( !elem ) {\n\t\t\treturn;\n\t\t}\n\n\t\t// Return zeros for disconnected and hidden (display: none) elements (gh-2310)\n\t\t// Support: IE <=11 only\n\t\t// Running getBoundingClientRect on a\n\t\t// disconnected node in IE throws an error\n\t\tif ( !elem.getClientRects().length ) {\n\t\t\treturn { top: 0, left: 0 };\n\t\t}\n\n\t\t// Get document-relative position by adding viewport scroll to viewport-relative gBCR\n\t\trect = elem.getBoundingClientRect();\n\t\twin = elem.ownerDocument.defaultView;\n\t\treturn {\n\t\t\ttop: rect.top + win.pageYOffset,\n\t\t\tleft: rect.left + win.pageXOffset\n\t\t};\n\t},\n\n\t// position() relates an element's margin box to its offset parent's padding box\n\t// This corresponds to the behavior of CSS absolute positioning\n\tposition: function() {\n\t\tif ( !this[ 0 ] ) {\n\t\t\treturn;\n\t\t}\n\n\t\tvar offsetParent, offset, doc,\n\t\t\telem = this[ 0 ],\n\t\t\tparentOffset = { top: 0, left: 0 };\n\n\t\t// position:fixed elements are offset from the viewport, which itself always has zero offset\n\t\tif ( jQuery.css( elem, \"position\" ) === \"fixed\" ) {\n\n\t\t\t// Assume position:fixed implies availability of getBoundingClientRect\n\t\t\toffset = elem.getBoundingClientRect();\n\n\t\t} else {\n\t\t\toffset = this.offset();\n\n\t\t\t// Account for the *real* offset parent, which can be the document or its root element\n\t\t\t// when a statically positioned element is identified\n\t\t\tdoc = elem.ownerDocument;\n\t\t\toffsetParent = elem.offsetParent || doc.documentElement;\n\t\t\twhile ( offsetParent &&\n\t\t\t\t( offsetParent === doc.body || offsetParent === doc.documentElement ) &&\n\t\t\t\tjQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\n\t\t\t\toffsetParent = offsetParent.parentNode;\n\t\t\t}\n\t\t\tif ( offsetParent && offsetParent !== elem && offsetParent.nodeType === 1 ) {\n\n\t\t\t\t// Incorporate borders into its offset, since they are outside its content origin\n\t\t\t\tparentOffset = jQuery( offsetParent ).offset();\n\t\t\t\tparentOffset.top += jQuery.css( offsetParent, \"borderTopWidth\", true );\n\t\t\t\tparentOffset.left += jQuery.css( offsetParent, \"borderLeftWidth\", true );\n\t\t\t}\n\t\t}\n\n\t\t// Subtract parent offsets and element margins\n\t\treturn {\n\t\t\ttop: offset.top - parentOffset.top - jQuery.css( elem, \"marginTop\", true ),\n\t\t\tleft: offset.left - parentOffset.left - jQuery.css( elem, \"marginLeft\", true )\n\t\t};\n\t},\n\n\t// This method will return documentElement in the following cases:\n\t// 1) For the element inside the iframe without offsetParent, this method will return\n\t//    documentElement of the parent window\n\t// 2) For the hidden or detached element\n\t// 3) For body or html element, i.e. in case of the html node - it will return itself\n\t//\n\t// but those exceptions were never presented as a real life use-cases\n\t// and might be considered as more preferable results.\n\t//\n\t// This logic, however, is not guaranteed and can change at any point in the future\n\toffsetParent: function() {\n\t\treturn this.map( function() {\n\t\t\tvar offsetParent = this.offsetParent;\n\n\t\t\twhile ( offsetParent && jQuery.css( offsetParent, \"position\" ) === \"static\" ) {\n\t\t\t\toffsetParent = offsetParent.offsetParent;\n\t\t\t}\n\n\t\t\treturn offsetParent || documentElement;\n\t\t} );\n\t}\n} );\n\n// Create scrollLeft and scrollTop methods\njQuery.each( { scrollLeft: \"pageXOffset\", scrollTop: \"pageYOffset\" }, function( method, prop ) {\n\tvar top = \"pageYOffset\" === prop;\n\n\tjQuery.fn[ method ] = function( val ) {\n\t\treturn access( this, function( elem, method, val ) {\n\n\t\t\t// Coalesce documents and windows\n\t\t\tvar win;\n\t\t\tif ( isWindow( elem ) ) {\n\t\t\t\twin = elem;\n\t\t\t} else if ( elem.nodeType === 9 ) {\n\t\t\t\twin = elem.defaultView;\n\t\t\t}\n\n\t\t\tif ( val === undefined ) {\n\t\t\t\treturn win ? win[ prop ] : elem[ method ];\n\t\t\t}\n\n\t\t\tif ( win ) {\n\t\t\t\twin.scrollTo(\n\t\t\t\t\t!top ? val : win.pageXOffset,\n\t\t\t\t\ttop ? val : win.pageYOffset\n\t\t\t\t);\n\n\t\t\t} else {\n\t\t\t\telem[ method ] = val;\n\t\t\t}\n\t\t}, method, val, arguments.length );\n\t};\n} );\n\n// Support: Safari <=7 - 9.1, Chrome <=37 - 49\n// Add the top/left cssHooks using jQuery.fn.position\n// Webkit bug: https://bugs.webkit.org/show_bug.cgi?id=29084\n// Blink bug: https://bugs.chromium.org/p/chromium/issues/detail?id=589347\n// getComputedStyle returns percent when specified for top/left/bottom/right;\n// rather than make the css module depend on the offset module, just check for it here\njQuery.each( [ \"top\", \"left\" ], function( i, prop ) {\n\tjQuery.cssHooks[ prop ] = addGetHookIf( support.pixelPosition,\n\t\tfunction( elem, computed ) {\n\t\t\tif ( computed ) {\n\t\t\t\tcomputed = curCSS( elem, prop );\n\n\t\t\t\t// If curCSS returns percentage, fallback to offset\n\t\t\t\treturn rnumnonpx.test( computed ) ?\n\t\t\t\t\tjQuery( elem ).position()[ prop ] + \"px\" :\n\t\t\t\t\tcomputed;\n\t\t\t}\n\t\t}\n\t);\n} );\n\n\n// Create innerHeight, innerWidth, height, width, outerHeight and outerWidth methods\njQuery.each( { Height: \"height\", Width: \"width\" }, function( name, type ) {\n\tjQuery.each( { padding: \"inner\" + name, content: type, \"\": \"outer\" + name },\n\t\tfunction( defaultExtra, funcName ) {\n\n\t\t// Margin is only for outerHeight, outerWidth\n\t\tjQuery.fn[ funcName ] = function( margin, value ) {\n\t\t\tvar chainable = arguments.length && ( defaultExtra || typeof margin !== \"boolean\" ),\n\t\t\t\textra = defaultExtra || ( margin === true || value === true ? \"margin\" : \"border\" );\n\n\t\t\treturn access( this, function( elem, type, value ) {\n\t\t\t\tvar doc;\n\n\t\t\t\tif ( isWindow( elem ) ) {\n\n\t\t\t\t\t// $( window ).outerWidth/Height return w/h including scrollbars (gh-1729)\n\t\t\t\t\treturn funcName.indexOf( \"outer\" ) === 0 ?\n\t\t\t\t\t\telem[ \"inner\" + name ] :\n\t\t\t\t\t\telem.document.documentElement[ \"client\" + name ];\n\t\t\t\t}\n\n\t\t\t\t// Get document width or height\n\t\t\t\tif ( elem.nodeType === 9 ) {\n\t\t\t\t\tdoc = elem.documentElement;\n\n\t\t\t\t\t// Either scroll[Width/Height] or offset[Width/Height] or client[Width/Height],\n\t\t\t\t\t// whichever is greatest\n\t\t\t\t\treturn Math.max(\n\t\t\t\t\t\telem.body[ \"scroll\" + name ], doc[ \"scroll\" + name ],\n\t\t\t\t\t\telem.body[ \"offset\" + name ], doc[ \"offset\" + name ],\n\t\t\t\t\t\tdoc[ \"client\" + name ]\n\t\t\t\t\t);\n\t\t\t\t}\n\n\t\t\t\treturn value === undefined ?\n\n\t\t\t\t\t// Get width or height on the element, requesting but not forcing parseFloat\n\t\t\t\t\tjQuery.css( elem, type, extra ) :\n\n\t\t\t\t\t// Set width or height on the element\n\t\t\t\t\tjQuery.style( elem, type, value, extra );\n\t\t\t}, type, chainable ? margin : undefined, chainable );\n\t\t};\n\t} );\n} );\n\n\njQuery.each( ( \"blur focus focusin focusout resize scroll click dblclick \" +\n\t\"mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave \" +\n\t\"change select submit keydown keypress keyup contextmenu\" ).split( \" \" ),\n\tfunction( i, name ) {\n\n\t// Handle event binding\n\tjQuery.fn[ name ] = function( data, fn ) {\n\t\treturn arguments.length > 0 ?\n\t\t\tthis.on( name, null, data, fn ) :\n\t\t\tthis.trigger( name );\n\t};\n} );\n\njQuery.fn.extend( {\n\thover: function( fnOver, fnOut ) {\n\t\treturn this.mouseenter( fnOver ).mouseleave( fnOut || fnOver );\n\t}\n} );\n\n\n\n\njQuery.fn.extend( {\n\n\tbind: function( types, data, fn ) {\n\t\treturn this.on( types, null, data, fn );\n\t},\n\tunbind: function( types, fn ) {\n\t\treturn this.off( types, null, fn );\n\t},\n\n\tdelegate: function( selector, types, data, fn ) {\n\t\treturn this.on( types, selector, data, fn );\n\t},\n\tundelegate: function( selector, types, fn ) {\n\n\t\t// ( namespace ) or ( selector, types [, fn] )\n\t\treturn arguments.length === 1 ?\n\t\t\tthis.off( selector, \"**\" ) :\n\t\t\tthis.off( types, selector || \"**\", fn );\n\t}\n} );\n\n// Bind a function to a context, optionally partially applying any\n// arguments.\n// jQuery.proxy is deprecated to promote standards (specifically Function#bind)\n// However, it is not slated for removal any time soon\njQuery.proxy = function( fn, context ) {\n\tvar tmp, args, proxy;\n\n\tif ( typeof context === \"string\" ) {\n\t\ttmp = fn[ context ];\n\t\tcontext = fn;\n\t\tfn = tmp;\n\t}\n\n\t// Quick check to determine if target is callable, in the spec\n\t// this throws a TypeError, but we will just return undefined.\n\tif ( !isFunction( fn ) ) {\n\t\treturn undefined;\n\t}\n\n\t// Simulated bind\n\targs = slice.call( arguments, 2 );\n\tproxy = function() {\n\t\treturn fn.apply( context || this, args.concat( slice.call( arguments ) ) );\n\t};\n\n\t// Set the guid of unique handler to the same of original handler, so it can be removed\n\tproxy.guid = fn.guid = fn.guid || jQuery.guid++;\n\n\treturn proxy;\n};\n\njQuery.holdReady = function( hold ) {\n\tif ( hold ) {\n\t\tjQuery.readyWait++;\n\t} else {\n\t\tjQuery.ready( true );\n\t}\n};\njQuery.isArray = Array.isArray;\njQuery.parseJSON = JSON.parse;\njQuery.nodeName = nodeName;\njQuery.isFunction = isFunction;\njQuery.isWindow = isWindow;\njQuery.camelCase = camelCase;\njQuery.type = toType;\n\njQuery.now = Date.now;\n\njQuery.isNumeric = function( obj ) {\n\n\t// As of jQuery 3.0, isNumeric is limited to\n\t// strings and numbers (primitives or objects)\n\t// that can be coerced to finite numbers (gh-2662)\n\tvar type = jQuery.type( obj );\n\treturn ( type === \"number\" || type === \"string\" ) &&\n\n\t\t// parseFloat NaNs numeric-cast false positives (\"\")\n\t\t// ...but misinterprets leading-number strings, particularly hex literals (\"0x...\")\n\t\t// subtraction forces infinities to NaN\n\t\t!isNaN( obj - parseFloat( obj ) );\n};\n\n\n\n\n// Register as a named AMD module, since jQuery can be concatenated with other\n// files that may use define, but not via a proper concatenation script that\n// understands anonymous AMD modules. A named AMD is safest and most robust\n// way to register. Lowercase jquery is used because AMD module names are\n// derived from file names, and jQuery is normally delivered in a lowercase\n// file name. Do this after creating the global so that if an AMD module wants\n// to call noConflict to hide this version of jQuery, it will work.\n\n// Note that for maximum portability, libraries that are not jQuery should\n// declare themselves as anonymous modules, and avoid setting a global if an\n// AMD loader is present. jQuery is a special case. For more information, see\n// https://github.com/jrburke/requirejs/wiki/Updating-existing-libraries#wiki-anon\n\nif ( typeof define === \"function\" && define.amd ) {\n\tdefine( \"jquery\", [], function() {\n\t\treturn jQuery;\n\t} );\n}\n\n\n\n\nvar\n\n\t// Map over jQuery in case of overwrite\n\t_jQuery = window.jQuery,\n\n\t// Map over the $ in case of overwrite\n\t_$ = window.$;\n\njQuery.noConflict = function( deep ) {\n\tif ( window.$ === jQuery ) {\n\t\twindow.$ = _$;\n\t}\n\n\tif ( deep && window.jQuery === jQuery ) {\n\t\twindow.jQuery = _jQuery;\n\t}\n\n\treturn jQuery;\n};\n\n// Expose jQuery and $ identifiers, even in AMD\n// (#7102#comment:10, https://github.com/jquery/jquery/pull/557)\n// and CommonJS for browser emulators (#13566)\nif ( !noGlobal ) {\n\twindow.jQuery = window.$ = jQuery;\n}\n\n\n\n\nreturn jQuery;\n} );\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/js/jqBootstrapValidation.js",
    "content": "/* jqBootstrapValidation\n * A plugin for automating validation on Twitter Bootstrap formatted forms.\n *\n * v1.3.6\n *\n * License: MIT <http://opensource.org/licenses/mit-license.php> - see LICENSE file\n *\n * http://ReactiveRaven.github.com/jqBootstrapValidation/\n */\n\n(function($) {\n\n  var createdElements = [];\n\n  var defaults = {\n    options: {\n      prependExistingHelpBlock: false,\n      sniffHtml: true, // sniff for 'required', 'maxlength', etc\n      preventSubmit: true, // stop the form submit event from firing if validation fails\n      submitError: false, // function called if there is an error when trying to submit\n      submitSuccess: false, // function called just before a successful submit event is sent to the server\n      semanticallyStrict: false, // set to true to tidy up generated HTML output\n      autoAdd: {\n        helpBlocks: true\n      },\n      filter: function() {\n        // return $(this).is(\":visible\"); // only validate elements you can see\n        return true; // validate everything\n      }\n    },\n    methods: {\n      init: function(options) {\n\n        var settings = $.extend(true, {}, defaults);\n\n        settings.options = $.extend(true, settings.options, options);\n\n        var $siblingElements = this;\n\n        var uniqueForms = $.unique(\n          $siblingElements.map(function() {\n            return $(this).parents(\"form\")[0];\n          }).toArray()\n        );\n\n        $(uniqueForms).bind(\"submit\", function(e) {\n          var $form = $(this);\n          var warningsFound = 0;\n          var $inputs = $form.find(\"input,textarea,select\").not(\"[type=submit],[type=image]\").filter(settings.options.filter);\n          $inputs.trigger(\"submit.validation\").trigger(\"validationLostFocus.validation\");\n\n          $inputs.each(function(i, el) {\n            var $this = $(el),\n              $controlGroup = $this.parents(\".form-group\").first();\n            if (\n              $controlGroup.hasClass(\"warning\")\n            ) {\n              $controlGroup.removeClass(\"warning\").addClass(\"error\");\n              warningsFound++;\n            }\n          });\n\n          $inputs.trigger(\"validationLostFocus.validation\");\n\n          if (warningsFound) {\n            if (settings.options.preventSubmit) {\n              e.preventDefault();\n            }\n            $form.addClass(\"error\");\n            if ($.isFunction(settings.options.submitError)) {\n              settings.options.submitError($form, e, $inputs.jqBootstrapValidation(\"collectErrors\", true));\n            }\n          } else {\n            $form.removeClass(\"error\");\n            if ($.isFunction(settings.options.submitSuccess)) {\n              settings.options.submitSuccess($form, e);\n            }\n          }\n        });\n\n        return this.each(function() {\n\n          // Get references to everything we're interested in\n          var $this = $(this),\n            $controlGroup = $this.parents(\".form-group\").first(),\n            $helpBlock = $controlGroup.find(\".help-block\").first(),\n            $form = $this.parents(\"form\").first(),\n            validatorNames = [];\n\n          // create message container if not exists\n          if (!$helpBlock.length && settings.options.autoAdd && settings.options.autoAdd.helpBlocks) {\n            $helpBlock = $('<div class=\"help-block\" />');\n            $controlGroup.find('.controls').append($helpBlock);\n            createdElements.push($helpBlock[0]);\n          }\n\n          // =============================================================\n          //                                     SNIFF HTML FOR VALIDATORS\n          // =============================================================\n\n          // *snort sniff snuffle*\n\n          if (settings.options.sniffHtml) {\n            var message = \"\";\n            // ---------------------------------------------------------\n            //                                                   PATTERN\n            // ---------------------------------------------------------\n            if ($this.attr(\"pattern\") !== undefined) {\n              message = \"Not in the expected format<!-- data-validation-pattern-message to override -->\";\n              if ($this.data(\"validationPatternMessage\")) {\n                message = $this.data(\"validationPatternMessage\");\n              }\n              $this.data(\"validationPatternMessage\", message);\n              $this.data(\"validationPatternRegex\", $this.attr(\"pattern\"));\n            }\n            // ---------------------------------------------------------\n            //                                                       MAX\n            // ---------------------------------------------------------\n            if ($this.attr(\"max\") !== undefined || $this.attr(\"aria-valuemax\") !== undefined) {\n              var max = ($this.attr(\"max\") !== undefined ? $this.attr(\"max\") : $this.attr(\"aria-valuemax\"));\n              message = \"Too high: Maximum of '\" + max + \"'<!-- data-validation-max-message to override -->\";\n              if ($this.data(\"validationMaxMessage\")) {\n                message = $this.data(\"validationMaxMessage\");\n              }\n              $this.data(\"validationMaxMessage\", message);\n              $this.data(\"validationMaxMax\", max);\n            }\n            // ---------------------------------------------------------\n            //                                                       MIN\n            // ---------------------------------------------------------\n            if ($this.attr(\"min\") !== undefined || $this.attr(\"aria-valuemin\") !== undefined) {\n              var min = ($this.attr(\"min\") !== undefined ? $this.attr(\"min\") : $this.attr(\"aria-valuemin\"));\n              message = \"Too low: Minimum of '\" + min + \"'<!-- data-validation-min-message to override -->\";\n              if ($this.data(\"validationMinMessage\")) {\n                message = $this.data(\"validationMinMessage\");\n              }\n              $this.data(\"validationMinMessage\", message);\n              $this.data(\"validationMinMin\", min);\n            }\n            // ---------------------------------------------------------\n            //                                                 MAXLENGTH\n            // ---------------------------------------------------------\n            if ($this.attr(\"maxlength\") !== undefined) {\n              message = \"Too long: Maximum of '\" + $this.attr(\"maxlength\") + \"' characters<!-- data-validation-maxlength-message to override -->\";\n              if ($this.data(\"validationMaxlengthMessage\")) {\n                message = $this.data(\"validationMaxlengthMessage\");\n              }\n              $this.data(\"validationMaxlengthMessage\", message);\n              $this.data(\"validationMaxlengthMaxlength\", $this.attr(\"maxlength\"));\n            }\n            // ---------------------------------------------------------\n            //                                                 MINLENGTH\n            // ---------------------------------------------------------\n            if ($this.attr(\"minlength\") !== undefined) {\n              message = \"Too short: Minimum of '\" + $this.attr(\"minlength\") + \"' characters<!-- data-validation-minlength-message to override -->\";\n              if ($this.data(\"validationMinlengthMessage\")) {\n                message = $this.data(\"validationMinlengthMessage\");\n              }\n              $this.data(\"validationMinlengthMessage\", message);\n              $this.data(\"validationMinlengthMinlength\", $this.attr(\"minlength\"));\n            }\n            // ---------------------------------------------------------\n            //                                                  REQUIRED\n            // ---------------------------------------------------------\n            if ($this.attr(\"required\") !== undefined || $this.attr(\"aria-required\") !== undefined) {\n              message = settings.builtInValidators.required.message;\n              if ($this.data(\"validationRequiredMessage\")) {\n                message = $this.data(\"validationRequiredMessage\");\n              }\n              $this.data(\"validationRequiredMessage\", message);\n            }\n            // ---------------------------------------------------------\n            //                                                    NUMBER\n            // ---------------------------------------------------------\n            if ($this.attr(\"type\") !== undefined && $this.attr(\"type\").toLowerCase() === \"number\") {\n              message = settings.builtInValidators.number.message;\n              if ($this.data(\"validationNumberMessage\")) {\n                message = $this.data(\"validationNumberMessage\");\n              }\n              $this.data(\"validationNumberMessage\", message);\n            }\n            // ---------------------------------------------------------\n            //                                                     EMAIL\n            // ---------------------------------------------------------\n            if ($this.attr(\"type\") !== undefined && $this.attr(\"type\").toLowerCase() === \"email\") {\n              message = \"Not a valid email address<!-- data-validator-validemail-message to override -->\";\n              if ($this.data(\"validationValidemailMessage\")) {\n                message = $this.data(\"validationValidemailMessage\");\n              } else if ($this.data(\"validationEmailMessage\")) {\n                message = $this.data(\"validationEmailMessage\");\n              }\n              $this.data(\"validationValidemailMessage\", message);\n            }\n            // ---------------------------------------------------------\n            //                                                MINCHECKED\n            // ---------------------------------------------------------\n            if ($this.attr(\"minchecked\") !== undefined) {\n              message = \"Not enough options checked; Minimum of '\" + $this.attr(\"minchecked\") + \"' required<!-- data-validation-minchecked-message to override -->\";\n              if ($this.data(\"validationMincheckedMessage\")) {\n                message = $this.data(\"validationMincheckedMessage\");\n              }\n              $this.data(\"validationMincheckedMessage\", message);\n              $this.data(\"validationMincheckedMinchecked\", $this.attr(\"minchecked\"));\n            }\n            // ---------------------------------------------------------\n            //                                                MAXCHECKED\n            // ---------------------------------------------------------\n            if ($this.attr(\"maxchecked\") !== undefined) {\n              message = \"Too many options checked; Maximum of '\" + $this.attr(\"maxchecked\") + \"' required<!-- data-validation-maxchecked-message to override -->\";\n              if ($this.data(\"validationMaxcheckedMessage\")) {\n                message = $this.data(\"validationMaxcheckedMessage\");\n              }\n              $this.data(\"validationMaxcheckedMessage\", message);\n              $this.data(\"validationMaxcheckedMaxchecked\", $this.attr(\"maxchecked\"));\n            }\n          }\n\n          // =============================================================\n          //                                       COLLECT VALIDATOR NAMES\n          // =============================================================\n\n          // Get named validators\n          if ($this.data(\"validation\") !== undefined) {\n            validatorNames = $this.data(\"validation\").split(\",\");\n          }\n\n          // Get extra ones defined on the element's data attributes\n          $.each($this.data(), function(i, el) {\n            var parts = i.replace(/([A-Z])/g, \",$1\").split(\",\");\n            if (parts[0] === \"validation\" && parts[1]) {\n              validatorNames.push(parts[1]);\n            }\n          });\n\n          // =============================================================\n          //                                     NORMALISE VALIDATOR NAMES\n          // =============================================================\n\n          var validatorNamesToInspect = validatorNames;\n          var newValidatorNamesToInspect = [];\n\n          do // repeatedly expand 'shortcut' validators into their real validators\n          {\n            // Uppercase only the first letter of each name\n            $.each(validatorNames, function(i, el) {\n              validatorNames[i] = formatValidatorName(el);\n            });\n\n            // Remove duplicate validator names\n            validatorNames = $.unique(validatorNames);\n\n            // Pull out the new validator names from each shortcut\n            newValidatorNamesToInspect = [];\n            $.each(validatorNamesToInspect, function(i, el) {\n              if ($this.data(\"validation\" + el + \"Shortcut\") !== undefined) {\n                // Are these custom validators?\n                // Pull them out!\n                $.each($this.data(\"validation\" + el + \"Shortcut\").split(\",\"), function(i2, el2) {\n                  newValidatorNamesToInspect.push(el2);\n                });\n              } else if (settings.builtInValidators[el.toLowerCase()]) {\n                // Is this a recognised built-in?\n                // Pull it out!\n                var validator = settings.builtInValidators[el.toLowerCase()];\n                if (validator.type.toLowerCase() === \"shortcut\") {\n                  $.each(validator.shortcut.split(\",\"), function(i, el) {\n                    el = formatValidatorName(el);\n                    newValidatorNamesToInspect.push(el);\n                    validatorNames.push(el);\n                  });\n                }\n              }\n            });\n\n            validatorNamesToInspect = newValidatorNamesToInspect;\n\n          } while (validatorNamesToInspect.length > 0)\n\n          // =============================================================\n          //                                       SET UP VALIDATOR ARRAYS\n          // =============================================================\n\n          var validators = {};\n\n          $.each(validatorNames, function(i, el) {\n            // Set up the 'override' message\n            var message = $this.data(\"validation\" + el + \"Message\");\n            var hasOverrideMessage = (message !== undefined);\n            var foundValidator = false;\n            message =\n              (\n                message ?\n                message :\n                \"'\" + el + \"' validation failed <!-- Add attribute 'data-validation-\" + el.toLowerCase() + \"-message' to input to change this message -->\"\n              );\n\n            $.each(\n              settings.validatorTypes,\n              function(validatorType, validatorTemplate) {\n                if (validators[validatorType] === undefined) {\n                  validators[validatorType] = [];\n                }\n                if (!foundValidator && $this.data(\"validation\" + el + formatValidatorName(validatorTemplate.name)) !== undefined) {\n                  validators[validatorType].push(\n                    $.extend(\n                      true, {\n                        name: formatValidatorName(validatorTemplate.name),\n                        message: message\n                      },\n                      validatorTemplate.init($this, el)\n                    )\n                  );\n                  foundValidator = true;\n                }\n              }\n            );\n\n            if (!foundValidator && settings.builtInValidators[el.toLowerCase()]) {\n\n              var validator = $.extend(true, {}, settings.builtInValidators[el.toLowerCase()]);\n              if (hasOverrideMessage) {\n                validator.message = message;\n              }\n              var validatorType = validator.type.toLowerCase();\n\n              if (validatorType === \"shortcut\") {\n                foundValidator = true;\n              } else {\n                $.each(\n                  settings.validatorTypes,\n                  function(validatorTemplateType, validatorTemplate) {\n                    if (validators[validatorTemplateType] === undefined) {\n                      validators[validatorTemplateType] = [];\n                    }\n                    if (!foundValidator && validatorType === validatorTemplateType.toLowerCase()) {\n                      $this.data(\"validation\" + el + formatValidatorName(validatorTemplate.name), validator[validatorTemplate.name.toLowerCase()]);\n                      validators[validatorType].push(\n                        $.extend(\n                          validator,\n                          validatorTemplate.init($this, el)\n                        )\n                      );\n                      foundValidator = true;\n                    }\n                  }\n                );\n              }\n            }\n\n            if (!foundValidator) {\n              $.error(\"Cannot find validation info for '\" + el + \"'\");\n            }\n          });\n\n          // =============================================================\n          //                                         STORE FALLBACK VALUES\n          // =============================================================\n\n          $helpBlock.data(\n            \"original-contents\",\n            (\n              $helpBlock.data(\"original-contents\") ?\n              $helpBlock.data(\"original-contents\") :\n              $helpBlock.html()\n            )\n          );\n\n          $helpBlock.data(\n            \"original-role\",\n            (\n              $helpBlock.data(\"original-role\") ?\n              $helpBlock.data(\"original-role\") :\n              $helpBlock.attr(\"role\")\n            )\n          );\n\n          $controlGroup.data(\n            \"original-classes\",\n            (\n              $controlGroup.data(\"original-clases\") ?\n              $controlGroup.data(\"original-classes\") :\n              $controlGroup.attr(\"class\")\n            )\n          );\n\n          $this.data(\n            \"original-aria-invalid\",\n            (\n              $this.data(\"original-aria-invalid\") ?\n              $this.data(\"original-aria-invalid\") :\n              $this.attr(\"aria-invalid\")\n            )\n          );\n\n          // =============================================================\n          //                                                    VALIDATION\n          // =============================================================\n\n          $this.bind(\n            \"validation.validation\",\n            function(event, params) {\n\n              var value = getValue($this);\n\n              // Get a list of the errors to apply\n              var errorsFound = [];\n\n              $.each(validators, function(validatorType, validatorTypeArray) {\n                if (value || value.length || (params && params.includeEmpty) || (!!settings.validatorTypes[validatorType].blockSubmit && params && !!params.submitting)) {\n                  $.each(validatorTypeArray, function(i, validator) {\n                    if (settings.validatorTypes[validatorType].validate($this, value, validator)) {\n                      errorsFound.push(validator.message);\n                    }\n                  });\n                }\n              });\n\n              return errorsFound;\n            }\n          );\n\n          $this.bind(\n            \"getValidators.validation\",\n            function() {\n              return validators;\n            }\n          );\n\n          // =============================================================\n          //                                             WATCH FOR CHANGES\n          // =============================================================\n          $this.bind(\n            \"submit.validation\",\n            function() {\n              return $this.triggerHandler(\"change.validation\", {\n                submitting: true\n              });\n            }\n          );\n          $this.bind(\n            [\n              \"keyup\",\n              \"focus\",\n              \"blur\",\n              \"click\",\n              \"keydown\",\n              \"keypress\",\n              \"change\"\n            ].join(\".validation \") + \".validation\",\n            function(e, params) {\n\n              var value = getValue($this);\n\n              var errorsFound = [];\n\n              $controlGroup.find(\"input,textarea,select\").each(function(i, el) {\n                var oldCount = errorsFound.length;\n                $.each($(el).triggerHandler(\"validation.validation\", params), function(j, message) {\n                  errorsFound.push(message);\n                });\n                if (errorsFound.length > oldCount) {\n                  $(el).attr(\"aria-invalid\", \"true\");\n                } else {\n                  var original = $this.data(\"original-aria-invalid\");\n                  $(el).attr(\"aria-invalid\", (original !== undefined ? original : false));\n                }\n              });\n\n              $form.find(\"input,select,textarea\").not($this).not(\"[name=\\\"\" + $this.attr(\"name\") + \"\\\"]\").trigger(\"validationLostFocus.validation\");\n\n              errorsFound = $.unique(errorsFound.sort());\n\n              // Were there any errors?\n              if (errorsFound.length) {\n                // Better flag it up as a warning.\n                $controlGroup.removeClass(\"success error\").addClass(\"warning\");\n\n                // How many errors did we find?\n                if (settings.options.semanticallyStrict && errorsFound.length === 1) {\n                  // Only one? Being strict? Just output it.\n                  $helpBlock.html(errorsFound[0] +\n                    (settings.options.prependExistingHelpBlock ? $helpBlock.data(\"original-contents\") : \"\"));\n                } else {\n                  // Multiple? Being sloppy? Glue them together into an UL.\n                  $helpBlock.html(\"<ul role=\\\"alert\\\"><li>\" + errorsFound.join(\"</li><li>\") + \"</li></ul>\" +\n                    (settings.options.prependExistingHelpBlock ? $helpBlock.data(\"original-contents\") : \"\"));\n                }\n              } else {\n                $controlGroup.removeClass(\"warning error success\");\n                if (value.length > 0) {\n                  $controlGroup.addClass(\"success\");\n                }\n                $helpBlock.html($helpBlock.data(\"original-contents\"));\n              }\n\n              if (e.type === \"blur\") {\n                $controlGroup.removeClass(\"success\");\n              }\n            }\n          );\n          $this.bind(\"validationLostFocus.validation\", function() {\n            $controlGroup.removeClass(\"success\");\n          });\n        });\n      },\n      destroy: function() {\n\n        return this.each(\n          function() {\n\n            var\n              $this = $(this),\n              $controlGroup = $this.parents(\".form-group\").first(),\n              $helpBlock = $controlGroup.find(\".help-block\").first();\n\n            // remove our events\n            $this.unbind('.validation'); // events are namespaced.\n            // reset help text\n            $helpBlock.html($helpBlock.data(\"original-contents\"));\n            // reset classes\n            $controlGroup.attr(\"class\", $controlGroup.data(\"original-classes\"));\n            // reset aria\n            $this.attr(\"aria-invalid\", $this.data(\"original-aria-invalid\"));\n            // reset role\n            $helpBlock.attr(\"role\", $this.data(\"original-role\"));\n            // remove all elements we created\n            if (createdElements.indexOf($helpBlock[0]) > -1) {\n              $helpBlock.remove();\n            }\n\n          }\n        );\n\n      },\n      collectErrors: function(includeEmpty) {\n\n        var errorMessages = {};\n        this.each(function(i, el) {\n          var $el = $(el);\n          var name = $el.attr(\"name\");\n          var errors = $el.triggerHandler(\"validation.validation\", {\n            includeEmpty: true\n          });\n          errorMessages[name] = $.extend(true, errors, errorMessages[name]);\n        });\n\n        $.each(errorMessages, function(i, el) {\n          if (el.length === 0) {\n            delete errorMessages[i];\n          }\n        });\n\n        return errorMessages;\n\n      },\n      hasErrors: function() {\n\n        var errorMessages = [];\n\n        this.each(function(i, el) {\n          errorMessages = errorMessages.concat(\n            $(el).triggerHandler(\"getValidators.validation\") ? $(el).triggerHandler(\"validation.validation\", {\n              submitting: true\n            }) : []\n          );\n        });\n\n        return (errorMessages.length > 0);\n      },\n      override: function(newDefaults) {\n        defaults = $.extend(true, defaults, newDefaults);\n      }\n    },\n    validatorTypes: {\n      callback: {\n        name: \"callback\",\n        init: function($this, name) {\n          return {\n            validatorName: name,\n            callback: $this.data(\"validation\" + name + \"Callback\"),\n            lastValue: $this.val(),\n            lastValid: true,\n            lastFinished: true\n          };\n        },\n        validate: function($this, value, validator) {\n          if (validator.lastValue === value && validator.lastFinished) {\n            return !validator.lastValid;\n          }\n\n          if (validator.lastFinished === true) {\n            validator.lastValue = value;\n            validator.lastValid = true;\n            validator.lastFinished = false;\n\n            var rrjqbvValidator = validator;\n            var rrjqbvThis = $this;\n            executeFunctionByName(\n              validator.callback,\n              window,\n              $this,\n              value,\n              function(data) {\n                if (rrjqbvValidator.lastValue === data.value) {\n                  rrjqbvValidator.lastValid = data.valid;\n                  if (data.message) {\n                    rrjqbvValidator.message = data.message;\n                  }\n                  rrjqbvValidator.lastFinished = true;\n                  rrjqbvThis.data(\"validation\" + rrjqbvValidator.validatorName + \"Message\", rrjqbvValidator.message);\n                  // Timeout is set to avoid problems with the events being considered 'already fired'\n                  setTimeout(function() {\n                    rrjqbvThis.trigger(\"change.validation\");\n                  }, 1); // doesn't need a long timeout, just long enough for the event bubble to burst\n                }\n              }\n            );\n          }\n\n          return false;\n\n        }\n      },\n      ajax: {\n        name: \"ajax\",\n        init: function($this, name) {\n          return {\n            validatorName: name,\n            url: $this.data(\"validation\" + name + \"Ajax\"),\n            lastValue: $this.val(),\n            lastValid: true,\n            lastFinished: true\n          };\n        },\n        validate: function($this, value, validator) {\n          if (\"\" + validator.lastValue === \"\" + value && validator.lastFinished === true) {\n            return validator.lastValid === false;\n          }\n\n          if (validator.lastFinished === true) {\n            validator.lastValue = value;\n            validator.lastValid = true;\n            validator.lastFinished = false;\n            $.ajax({\n              url: validator.url,\n              data: \"value=\" + value + \"&field=\" + $this.attr(\"name\"),\n              dataType: \"json\",\n              success: function(data) {\n                if (\"\" + validator.lastValue === \"\" + data.value) {\n                  validator.lastValid = !!(data.valid);\n                  if (data.message) {\n                    validator.message = data.message;\n                  }\n                  validator.lastFinished = true;\n                  $this.data(\"validation\" + validator.validatorName + \"Message\", validator.message);\n                  // Timeout is set to avoid problems with the events being considered 'already fired'\n                  setTimeout(function() {\n                    $this.trigger(\"change.validation\");\n                  }, 1); // doesn't need a long timeout, just long enough for the event bubble to burst\n                }\n              },\n              failure: function() {\n                validator.lastValid = true;\n                validator.message = \"ajax call failed\";\n                validator.lastFinished = true;\n                $this.data(\"validation\" + validator.validatorName + \"Message\", validator.message);\n                // Timeout is set to avoid problems with the events being considered 'already fired'\n                setTimeout(function() {\n                  $this.trigger(\"change.validation\");\n                }, 1); // doesn't need a long timeout, just long enough for the event bubble to burst\n              }\n            });\n          }\n\n          return false;\n\n        }\n      },\n      regex: {\n        name: \"regex\",\n        init: function($this, name) {\n          return {\n            regex: regexFromString($this.data(\"validation\" + name + \"Regex\"))\n          };\n        },\n        validate: function($this, value, validator) {\n          return (!validator.regex.test(value) && !validator.negative) ||\n            (validator.regex.test(value) && validator.negative);\n        }\n      },\n      required: {\n        name: \"required\",\n        init: function($this, name) {\n          return {};\n        },\n        validate: function($this, value, validator) {\n          return !!(value.length === 0 && !validator.negative) ||\n            !!(value.length > 0 && validator.negative);\n        },\n        blockSubmit: true\n      },\n      match: {\n        name: \"match\",\n        init: function($this, name) {\n          var element = $this.parents(\"form\").first().find(\"[name=\\\"\" + $this.data(\"validation\" + name + \"Match\") + \"\\\"]\").first();\n          element.bind(\"validation.validation\", function() {\n            $this.trigger(\"change.validation\", {\n              submitting: true\n            });\n          });\n          return {\n            \"element\": element\n          };\n        },\n        validate: function($this, value, validator) {\n          return (value !== validator.element.val() && !validator.negative) ||\n            (value === validator.element.val() && validator.negative);\n        },\n        blockSubmit: true\n      },\n      max: {\n        name: \"max\",\n        init: function($this, name) {\n          return {\n            max: $this.data(\"validation\" + name + \"Max\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return (parseFloat(value, 10) > parseFloat(validator.max, 10) && !validator.negative) ||\n            (parseFloat(value, 10) <= parseFloat(validator.max, 10) && validator.negative);\n        }\n      },\n      min: {\n        name: \"min\",\n        init: function($this, name) {\n          return {\n            min: $this.data(\"validation\" + name + \"Min\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return (parseFloat(value) < parseFloat(validator.min) && !validator.negative) ||\n            (parseFloat(value) >= parseFloat(validator.min) && validator.negative);\n        }\n      },\n      maxlength: {\n        name: \"maxlength\",\n        init: function($this, name) {\n          return {\n            maxlength: $this.data(\"validation\" + name + \"Maxlength\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return ((value.length > validator.maxlength) && !validator.negative) ||\n            ((value.length <= validator.maxlength) && validator.negative);\n        }\n      },\n      minlength: {\n        name: \"minlength\",\n        init: function($this, name) {\n          return {\n            minlength: $this.data(\"validation\" + name + \"Minlength\")\n          };\n        },\n        validate: function($this, value, validator) {\n          return ((value.length < validator.minlength) && !validator.negative) ||\n            ((value.length >= validator.minlength) && validator.negative);\n        }\n      },\n      maxchecked: {\n        name: \"maxchecked\",\n        init: function($this, name) {\n          var elements = $this.parents(\"form\").first().find(\"[name=\\\"\" + $this.attr(\"name\") + \"\\\"]\");\n          elements.bind(\"click.validation\", function() {\n            $this.trigger(\"change.validation\", {\n              includeEmpty: true\n            });\n          });\n          return {\n            maxchecked: $this.data(\"validation\" + name + \"Maxchecked\"),\n            elements: elements\n          };\n        },\n        validate: function($this, value, validator) {\n          return (validator.elements.filter(\":checked\").length > validator.maxchecked && !validator.negative) ||\n            (validator.elements.filter(\":checked\").length <= validator.maxchecked && validator.negative);\n        },\n        blockSubmit: true\n      },\n      minchecked: {\n        name: \"minchecked\",\n        init: function($this, name) {\n          var elements = $this.parents(\"form\").first().find(\"[name=\\\"\" + $this.attr(\"name\") + \"\\\"]\");\n          elements.bind(\"click.validation\", function() {\n            $this.trigger(\"change.validation\", {\n              includeEmpty: true\n            });\n          });\n          return {\n            minchecked: $this.data(\"validation\" + name + \"Minchecked\"),\n            elements: elements\n          };\n        },\n        validate: function($this, value, validator) {\n          return (validator.elements.filter(\":checked\").length < validator.minchecked && !validator.negative) ||\n            (validator.elements.filter(\":checked\").length >= validator.minchecked && validator.negative);\n        },\n        blockSubmit: true\n      }\n    },\n    builtInValidators: {\n      email: {\n        name: \"Email\",\n        type: \"shortcut\",\n        shortcut: \"validemail\"\n      },\n      validemail: {\n        name: \"Validemail\",\n        type: \"regex\",\n        regex: \"[A-Za-z0-9._%+-]+@[A-Za-z0-9.-]+\\\\\\.[A-Za-z]{2,4}\",\n        message: \"Not a valid email address<!-- data-validator-validemail-message to override -->\"\n      },\n      passwordagain: {\n        name: \"Passwordagain\",\n        type: \"match\",\n        match: \"password\",\n        message: \"Does not match the given password<!-- data-validator-paswordagain-message to override -->\"\n      },\n      positive: {\n        name: \"Positive\",\n        type: \"shortcut\",\n        shortcut: \"number,positivenumber\"\n      },\n      negative: {\n        name: \"Negative\",\n        type: \"shortcut\",\n        shortcut: \"number,negativenumber\"\n      },\n      number: {\n        name: \"Number\",\n        type: \"regex\",\n        regex: \"([+-]?\\\\\\d+(\\\\\\.\\\\\\d*)?([eE][+-]?[0-9]+)?)?\",\n        message: \"Must be a number<!-- data-validator-number-message to override -->\"\n      },\n      integer: {\n        name: \"Integer\",\n        type: \"regex\",\n        regex: \"[+-]?\\\\\\d+\",\n        message: \"No decimal places allowed<!-- data-validator-integer-message to override -->\"\n      },\n      positivenumber: {\n        name: \"Positivenumber\",\n        type: \"min\",\n        min: 0,\n        message: \"Must be a positive number<!-- data-validator-positivenumber-message to override -->\"\n      },\n      negativenumber: {\n        name: \"Negativenumber\",\n        type: \"max\",\n        max: 0,\n        message: \"Must be a negative number<!-- data-validator-negativenumber-message to override -->\"\n      },\n      required: {\n        name: \"Required\",\n        type: \"required\",\n        message: \"This is required<!-- data-validator-required-message to override -->\"\n      },\n      checkone: {\n        name: \"Checkone\",\n        type: \"minchecked\",\n        minchecked: 1,\n        message: \"Check at least one option<!-- data-validation-checkone-message to override -->\"\n      }\n    }\n  };\n\n  var formatValidatorName = function(name) {\n    return name\n      .toLowerCase()\n      .replace(\n        /(^|\\s)([a-z])/g,\n        function(m, p1, p2) {\n          return p1 + p2.toUpperCase();\n        }\n      );\n  };\n\n  var getValue = function($this) {\n    // Extract the value we're talking about\n    var value = $this.val();\n    var type = $this.attr(\"type\");\n    if (type === \"checkbox\") {\n      value = ($this.is(\":checked\") ? value : \"\");\n    }\n    if (type === \"radio\") {\n      value = ($('input[name=\"' + $this.attr(\"name\") + '\"]:checked').length > 0 ? value : \"\");\n    }\n    return value;\n  };\n\n  function regexFromString(inputstring) {\n    return new RegExp(\"^\" + inputstring + \"$\");\n  }\n\n  /**\n   * Thanks to Jason Bunting via StackOverflow.com\n   *\n   * http://stackoverflow.com/questions/359788/how-to-execute-a-javascript-function-when-i-have-its-name-as-a-string#answer-359910\n   * Short link: http://tinyurl.com/executeFunctionByName\n   **/\n  function executeFunctionByName(functionName, context /*, args*/ ) {\n    var args = Array.prototype.slice.call(arguments).splice(2);\n    var namespaces = functionName.split(\".\");\n    var func = namespaces.pop();\n    for (var i = 0; i < namespaces.length; i++) {\n      context = context[namespaces[i]];\n    }\n    return context[func].apply(this, args);\n  }\n\n  $.fn.jqBootstrapValidation = function(method) {\n\n    if (defaults.methods[method]) {\n      return defaults.methods[method].apply(this, Array.prototype.slice.call(arguments, 1));\n    } else if (typeof method === 'object' || !method) {\n      return defaults.methods.init.apply(this, arguments);\n    } else {\n      $.error('Method ' + method + ' does not exist on jQuery.jqBootstrapValidation');\n      return null;\n    }\n\n  };\n\n  $.jqBootstrapValidation = function(options) {\n    $(\":input\").not(\"[type=image],[type=submit]\").jqBootstrapValidation.apply(this, arguments);\n  };\n\n})(jQuery);\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_bootstrap-overrides.scss",
    "content": "// Bootstrap overrides for this template\n.btn {\n  font-size: 14px;\n  font-weight: 800;\n  padding: 15px 25px;\n  letter-spacing: 1px;\n  text-transform: uppercase;\n  border-radius: 0;\n  @include sans-serif-font;\n}\n\n.btn-primary {\n  background-color: $primary;\n  border-color: $primary;\n  &:hover,\n  &:focus,\n  &:active {\n    color: $white;\n    background-color: darken($primary, 7.5) !important;\n    border-color: darken($primary, 7.5) !important;\n  }\n}\n\n.btn-lg {\n  font-size: 16px;\n  padding: 25px 35px;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_contact.scss",
    "content": "// Styling for the contact page\n.floating-label-form-group {\n  font-size: 14px;\n  position: relative;\n  margin-bottom: 0;\n  padding-bottom: 0.5em;\n  border-bottom: 1px solid $gray-300;\n  input,\n  textarea {\n    font-size: 1.5em;\n    position: relative;\n    z-index: 1;\n    padding: 0;\n    resize: none;\n    border: none;\n    border-radius: 0;\n    background: none;\n    box-shadow: none !important;\n    @include serif-font;\n    &::-webkit-input-placeholder {\n      color: $gray-600;\n      @include serif-font;\n    }\n  }\n  label {\n    font-size: 0.85em;\n    line-height: 1.764705882em;\n    position: relative;\n    z-index: 0;\n    top: 2em;\n    display: block;\n    margin: 0;\n    -webkit-transition: top 0.3s ease, opacity 0.3s ease;\n    -moz-transition: top 0.3s ease, opacity 0.3s ease;\n    -ms-transition: top 0.3s ease, opacity 0.3s ease;\n    transition: top 0.3s ease, opacity 0.3s ease;\n    vertical-align: middle;\n    vertical-align: baseline;\n    opacity: 0;\n  }\n  .help-block {\n    margin: 15px 0;\n  }\n}\n\n.floating-label-form-group-with-value {\n  label {\n    top: 0;\n    opacity: 1;\n  }\n}\n\n.floating-label-form-group-with-focus {\n  label {\n    color: $primary;\n  }\n}\nform .form-group:first-child .floating-label-form-group {\n  border-top: 1px solid $gray-300;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_footer.scss",
    "content": "// Styling for the footer\nfooter {\n  padding: 50px 0 65px;\n  .list-inline {\n    margin: 0;\n    padding: 0;\n  }\n  .copyright {\n    font-size: 14px;\n    margin-bottom: 0;\n    text-align: center;\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_global.scss",
    "content": "// Global styling for this template\nbody {\n  font-size: 20px;\n  color: $gray-900;\n  @include serif-font;\n}\n\np {\n  line-height: 1.5;\n  margin: 30px 0;\n  a {\n    text-decoration: underline;\n  }\n}\n\nh1,\nh2,\nh3,\nh4,\nh5,\nh6 {\n  font-weight: 800;\n  @include sans-serif-font;\n}\n\na {\n  color: $gray-900;\n  @include transition-all;\n  &:focus,\n  &:hover {\n    color: $primary;\n  }\n}\n\nblockquote {\n  font-style: italic;\n  color: $gray-600;\n}\n\n.section-heading {\n  font-size: 36px;\n  font-weight: 700;\n  margin-top: 60px;\n}\n\n.caption {\n  font-size: 14px;\n  font-style: italic;\n  display: block;\n  margin: 0;\n  padding: 10px;\n  text-align: center;\n  border-bottom-right-radius: 5px;\n  border-bottom-left-radius: 5px;\n}\n\n::-moz-selection {\n  color: $white;\n  background: $primary;\n  text-shadow: none;\n}\n\n::selection {\n  color: $white;\n  background: $primary;\n  text-shadow: none;\n}\n\nimg::selection {\n  color: $white;\n  background: transparent;\n}\n\nimg::-moz-selection {\n  color: $white;\n  background: transparent;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_masthead.scss",
    "content": "// Styling for the masthead\nheader.masthead {\n  // TIP: Background images are set within the HTML using inline CSS!\n  margin-bottom: 50px;\n  background: no-repeat center center;\n  background-color: $gray-600;\n  background-attachment: scroll;\n  position: relative;\n  @include background-cover;\n  .overlay {\n    position: absolute;\n    top: 0;\n    left: 0;\n    height: 100%;\n    width: 100%;\n    background-color: $gray-900;\n    opacity: 0.5;\n  }\n  .page-heading,\n  .post-heading,\n  .site-heading {\n    padding: 200px 0 150px;\n    color: white;\n    @media only screen and (min-width: 768px) {\n      padding: 200px 0;\n    }\n  }\n  .page-heading,\n  .site-heading {\n    text-align: center;\n    h1 {\n      font-size: 50px;\n      margin-top: 0;\n    }\n    .subheading {\n      font-size: 24px;\n      font-weight: 300;\n      line-height: 1.1;\n      display: block;\n      margin: 10px 0 0;\n      @include sans-serif-font;\n    }\n    @media only screen and (min-width: 768px) {\n      h1 {\n        font-size: 80px;\n      }\n    }\n  }\n  .post-heading {\n    h1 {\n      font-size: 35px;\n    }\n    .meta,\n    .subheading {\n      line-height: 1.1;\n      display: block;\n    }\n    .subheading {\n      font-size: 24px;\n      font-weight: 600;\n      margin: 10px 0 30px;\n      @include sans-serif-font;\n    }\n    .meta {\n      font-size: 20px;\n      font-weight: 300;\n      font-style: italic;\n      @include serif-font;\n      a {\n        color: $white;\n      }\n    }\n    @media only screen and (min-width: 768px) {\n      h1 {\n        font-size: 55px;\n      }\n      .subheading {\n        font-size: 30px;\n      }\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_mixins.scss",
    "content": "// Mixins\n// Bootstrap Button Variant\n@mixin button-variant($color, $background, $border) {\n  color: $color;\n  border-color: $border;\n  background-color: $background;\n  &.focus,\n  &:focus {\n    color: $color;\n    border-color: darken($border, 25%);\n    background-color: darken($background, 10%);\n  }\n  &:hover {\n    color: $color;\n    border-color: darken($border, 12%);\n    background-color: darken($background, 10%);\n  }\n  &.active,\n  &:active,\n  .open > &.dropdown-toggle {\n    color: $color;\n    border-color: darken($border, 12%);\n    background-color: darken($background, 10%);\n    &.focus,\n    &:focus,\n    &:hover {\n      color: $color;\n      border-color: darken($border, 25%);\n      background-color: darken($background, 17%);\n    }\n  }\n  &.active,\n  &:active,\n  .open > &.dropdown-toggle {\n    background-image: none;\n  }\n  &.disabled,\n  &[disabled],\n  fieldset[disabled] & {\n    &.focus,\n    &:focus,\n    &:hover {\n      border-color: $border;\n      background-color: $background;\n    }\n  }\n  .badge {\n    color: $background;\n    background-color: $color;\n  }\n}\n@mixin transition-all() {\n  -webkit-transition: all 0.2s;\n  -moz-transition: all 0.2s;\n  transition: all 0.2s;\n}\n@mixin background-cover() {\n  -webkit-background-size: cover;\n  -moz-background-size: cover;\n  -o-background-size: cover;\n  background-size: cover;\n}\n@mixin serif-font() {\n  font-family: 'Lora', 'Times New Roman', serif;\n}\n@mixin sans-serif-font() {\n  font-family: 'Open Sans', 'Helvetica Neue', Helvetica, Arial, sans-serif;\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_navbar.scss",
    "content": "// Styling for the navbar\n#mainNav {\n  position: absolute;\n  border-bottom: 1px solid $gray-200;\n  background-color: white;\n  @include sans-serif-font;\n  .navbar-brand {\n    font-weight: 800;\n    color: $gray-800;\n  }\n  .navbar-toggler {\n    font-size: 12px;\n    font-weight: 800;\n    padding: 13px;\n    text-transform: uppercase;\n    color: $gray-800;\n  }\n  .navbar-nav {\n    > li.nav-item {\n      > a {\n        font-size: 12px;\n        font-weight: 800;\n        letter-spacing: 1px;\n        text-transform: uppercase;\n      }\n    }\n  }\n  @media only screen and (min-width: 992px) {\n    border-bottom: 1px solid transparent;\n    background: transparent;\n    .navbar-brand {\n      padding: 10px 20px;\n      color: $white;\n      &:focus,\n      &:hover {\n        color: fade-out($white, .2);\n      }\n    }\n    .navbar-nav {\n      > li.nav-item {\n        > a {\n          padding: 10px 20px;\n          color: $white;\n          &:focus,\n          &:hover {\n            color: fade-out($white, .2);\n          }\n        }\n      }\n    }\n  }\n  @media only screen and (min-width: 992px) {\n    -webkit-transition: background-color 0.2s;\n    -moz-transition: background-color 0.2s;\n    transition: background-color 0.2s;\n    /* Force Hardware Acceleration in WebKit */\n    -webkit-transform: translate3d(0, 0, 0);\n    -moz-transform: translate3d(0, 0, 0);\n    -ms-transform: translate3d(0, 0, 0);\n    -o-transform: translate3d(0, 0, 0);\n    transform: translate3d(0, 0, 0);\n    -webkit-backface-visibility: hidden;\n    &.is-fixed {\n      /* when the user scrolls down, we hide the header right above the viewport */\n      position: fixed;\n      top: -67px;\n      -webkit-transition: -webkit-transform 0.2s;\n      -moz-transition: -moz-transform 0.2s;\n      transition: transform 0.2s;\n      border-bottom: 1px solid darken($white, .05);\n      background-color: fade-out($white, .1);\n      .navbar-brand {\n        color: $gray-900;\n        &:focus,\n        &:hover {\n          color: $primary;\n        }\n      }\n      .navbar-nav {\n        > li.nav-item {\n          > a {\n            color: $gray-900;\n            &:focus,\n            &:hover {\n              color: $primary;\n            }\n          }\n        }\n      }\n    }\n    &.is-visible {\n      /* if the user changes the scrolling direction, we show the header */\n      -webkit-transform: translate3d(0, 100%, 0);\n      -moz-transform: translate3d(0, 100%, 0);\n      -ms-transform: translate3d(0, 100%, 0);\n      -o-transform: translate3d(0, 100%, 0);\n      transform: translate3d(0, 100%, 0);\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_post.scss",
    "content": "// Styling for the post page\n.post-preview {\n  > a {\n    color: $gray-900;\n    &:focus,\n    &:hover {\n      text-decoration: none;\n      color: $primary;\n    }\n    > .post-title {\n      font-size: 30px;\n      margin-top: 30px;\n      margin-bottom: 10px;\n    }\n    > .post-subtitle {\n      font-weight: 300;\n      margin: 0 0 10px;\n    }\n  }\n  > .post-meta {\n    font-size: 18px;\n    font-style: italic;\n    margin-top: 0;\n    color: $gray-600;\n    > a {\n      text-decoration: none;\n      color: $gray-900;\n      &:focus,\n      &:hover {\n        text-decoration: underline;\n        color: $primary;\n      }\n    }\n  }\n  @media only screen and (min-width: 768px) {\n    > a {\n      > .post-title {\n        font-size: 36px;\n      }\n    }\n  }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/_variables.scss",
    "content": "// Variables\n\n$white:    #fff !default;\n$gray-100: #f8f9fa !default;\n$gray-200: #e9ecef !default;\n$gray-300: #dee2e6 !default;\n$gray-400: #ced4da !default;\n$gray-500: #adb5bd !default;\n$gray-600: #868e96 !default;\n$gray-700: #495057 !default;\n$gray-800: #343a40 !default;\n$gray-900: #212529 !default;\n$black:    #000 !default;\n\n$blue:    #007bff !default;\n$indigo:  #6610f2 !default;\n$purple:  #6f42c1 !default;\n$pink:    #e83e8c !default;\n$red:     #dc3545 !default;\n$orange:  #fd7e14 !default;\n$yellow:  #ffc107 !default;\n$green:   #28a745 !default;\n$teal:    #0085A1 !default;\n$cyan:    #17a2b8 !default;\n\n$primary:       $teal !default;\n$secondary:     $gray-600 !default;\n$success:       $green !default;\n$info:          $cyan !default;\n$warning:       $yellow !default;\n$danger:        $red !default;\n$light:         $gray-100 !default;\n$dark:          $gray-800 !default;\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/assets/vendor/startbootstrap-clean-blog/scss/clean-blog.scss",
    "content": "@import \"variables.scss\";\n@import \"mixins.scss\";\n@import \"global.scss\";\n@import \"navbar.scss\";\n@import \"masthead.scss\";\n@import \"post.scss\";\n@import \"contact.scss\";\n@import \"footer.scss\";\n@import \"bootstrap-overrides.scss\";\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/contact.html",
    "content": "---\nlayout: page\ntitle: Contact Me\ndescription: Have questions? I have answers.\nbackground: '/img/bg-contact.jpg'\nform: true\n---\n\n<p>Want to get in touch? Fill out the form below to send me a message and I will get back to you as soon as possible!</p>\n<form name=\"sentMessage\" id=\"contactForm\" novalidate>\n  <div class=\"control-group\">\n    <div class=\"form-group floating-label-form-group controls\">\n      <label>Name</label>\n      <input type=\"text\" class=\"form-control\" placeholder=\"Name\" id=\"name\" required data-validation-required-message=\"Please enter your name.\">\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <div class=\"control-group\">\n    <div class=\"form-group floating-label-form-group controls\">\n      <label>Email Address</label>\n      <input type=\"email\" class=\"form-control\" placeholder=\"Email Address\" id=\"email\" required data-validation-required-message=\"Please enter your email address.\">\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <div class=\"control-group\">\n    <div class=\"form-group col-xs-12 floating-label-form-group controls\">\n      <label>Phone Number</label>\n      <input type=\"tel\" class=\"form-control\" placeholder=\"Phone Number\" id=\"phone\" required data-validation-required-message=\"Please enter your phone number.\">\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <div class=\"control-group\">\n    <div class=\"form-group floating-label-form-group controls\">\n      <label>Message</label>\n      <textarea rows=\"5\" class=\"form-control\" placeholder=\"Message\" id=\"message\" required data-validation-required-message=\"Please enter a message.\"></textarea>\n      <p class=\"help-block text-danger\"></p>\n    </div>\n  </div>\n  <br>\n  <div id=\"success\"></div>\n  <div class=\"form-group\">\n    <button type=\"submit\" class=\"btn btn-primary\" id=\"sendMessageButton\">Send</button>\n  </div>\n</form>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/get_started.html",
    "content": "---\nlayout: page\ntitle: Getting Started\ndescription: Introduction to the leaderboard.\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/gulpfile.js",
    "content": "// Load plugins\nconst gulp = require(\"gulp\");\n\n// Copy third party libraries from /node_modules into /vendor\ngulp.task('vendor', function(cb) {\n\n  // Start Bootstrap Clean Blog SCSS\n  gulp.src([\n      './node_modules/startbootstrap-clean-blog/scss/**/*'\n    ])\n    .pipe(gulp.dest('./assets/vendor/startbootstrap-clean-blog/scss'))\n\n  // Start Bootstrap Clean Blog JS\n  gulp.src([\n      './node_modules/startbootstrap-clean-blog/js/clean-blog.min.js',\n      './node_modules/startbootstrap-clean-blog/js/jqBootstrapValidation.js'\n    ])\n    .pipe(gulp.dest('./assets/vendor/startbootstrap-clean-blog/js'))\n\n  // Bootstrap\n  gulp.src([\n      './node_modules/bootstrap/dist/**/*',\n      '!./node_modules/bootstrap/dist/css/bootstrap-grid*',\n      '!./node_modules/bootstrap/dist/css/bootstrap-reboot*'\n    ])\n    .pipe(gulp.dest('./assets/vendor/bootstrap'))\n\n  // jQuery\n  gulp.src([\n      './node_modules/jquery/dist/*',\n      '!./node_modules/jquery/dist/core.js'\n    ])\n    .pipe(gulp.dest('./assets/vendor/jquery'))\n\n  // Font Awesome\n  gulp.src([\n      './node_modules/@fortawesome/**/*',\n    ])\n    .pipe(gulp.dest('./assets/vendor'))\n\n  cb();\n\n});\n\ngulp.task(\"default\", gulp.parallel('vendor'));\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/index.html",
    "content": "---\nlayout: home\ntitle: CARLA Leaderboard\ndescription: CARLA Autonomous Driving competition.\nbackground: '/img/carla_header.png'\nimage: 'img/carla_header.png'\n---\n\n\n<h3>Introduction</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\n  The CARLA leaderboard is a way to...\n</p>\n\n<h3>Participation tracks</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\n  The challenge will have four parallel tracks, which differ in the type of input data provided to the agents.\n  In all tracks, the agents will have access to additional measurements, such as a high-level plan of how to reach destinations, and the current speed.\n</p>\n\n<h3>Competition metrics</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\nThe performance of an agent will depend on the number of routes successfully completed. A route is considered successfully completed if no critical infractions were triggered. If the agent triggers a critical infraction, the episode will be automatically terminated and the agent will only get a score proportional to the percentage of the route it completed until the critical infraction. The list of critical infractions is as follows:\n\nHitting the static scenery (poles, traffic signs, etc.).\n\nIf an agent runs out of time to complete a given route the final score will be the percentage of route completed before the timeout.\n\nThe final score will consist of two components:\n\nPoints obtained for route completion.\nPoints lost due to other infractions (e.g., running a red light).\nMinor infractions will have a negative effect on the final score. Each infraction discounts points from the final score, which could get down to 0 in the worst case. These are the points discounted for each infraction:\n</p>\n\n<h3>Participation mechanics</h3>\n<p style=\"margin-top:0px;font-size:18px;\">\n  Participants must create a new team in the EvalAI CARLA AD Challenge contest.\n  Teams will create a docker image using the provided Dockerfile templates.\n  Docker containers will be then pushed to CARLA AD Challenge internal repositories using EvalAI cli scripts. Teams must select the right challenge phase to submit their containers.\n  Docker images will be automatically evaluated in AWS by our evaluation infrastructure and results will be reported to users through the EvalAI CARLA AD Challenge site.\n  For detailed instructions, please visit the Submit section.\n\n  Important considerations\n  Agents will run on a private AWS instance endowed with a multi-processor and a GPU (NVIDIA Tesla K80).\n  Teams will receive a budget of 300 hours for the entire challenge. If a team exceeds its hours, new docker containers won’t be evaluated.\n  The CARLA AD Challenge organization reserves the right to assign further hours to teams due to extraordinary circumstances.\n  Some Autonomous Driving baselines are provided as a reference. Please, read the Get started section for more information.\n  We recommend participants to join our Discord chat to keep up-to-date with challenge news.\n</p>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/jekyll-theme-clean-blog.gemspec",
    "content": "# frozen_string_literal: true\n\nGem::Specification.new do |spec|\n  spec.name          = \"jekyll-theme-clean-blog\"\n  spec.version       = \"4.0.9\"\n  spec.authors       = [\"CARLA Team\"]\n  spec.email         = [\"carla.simulator@gmail.com\"]\n\n  spec.summary       = \"A simple blog theme based on Bootstrap 4 by Start Bootstrap.\"\n  spec.homepage      = \"https://github.com/blackrockdigital/startbootstrap-clean-blog-jekyll\"\n  spec.license       = \"MIT\"\n\n  spec.files         = `git ls-files -z`.split(\"\\x0\").select { |f| f.match(%r{^(assets|_layouts|_includes|_sass|LICENSE|README)}i) }\n\n  spec.add_runtime_dependency \"jekyll\", \"~> 3.8.5\"\n\n  spec.add_development_dependency \"bundler\", \"~> 2.0.1\"\n  spec.add_development_dependency \"rake\", \"~> 12.0\"\nend\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/leaderboard.html",
    "content": "---\nlayout: page\ntitle: Leaderboard\ndescription: \"\"\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/posts/index.html",
    "content": "---\nlayout: page\ntitle: Posts\nbackground: '/img/bg-post.jpg'\n---\n\n{% for post in paginator.posts %}\n\n<article class=\"post-preview\">\n  <a href=\"{{ post.url | prepend: site.baseurl | replace: '//', '/' }}\">\n    <h2 class=\"post-title\">{{ post.title }}</h2>\n    {% if post.subtitle %}\n    <h3 class=\"post-subtitle\">{{ post.subtitle }}</h3>\n    {% else %}\n    <h3 class=\"post-subtitle\">{{ post.excerpt | strip_html | truncatewords: 15 }}</h3>\n    {% endif %}\n  </a>\n  <p class=\"post-meta\">Posted by\n    {% if post.author %}\n    {{ post.author }}\n    {% else %}\n    {{ site.author }}\n    {% endif %}\n    on {{ post.date | date: '%B %d, %Y' }} &middot; {% include read_time.html content=post.content %}\n  </p>\n</article>\n\n<hr>\n\n{% endfor %}\n\n<!-- Pager -->\n{% if paginator.total_pages > 1 %}\n\n<div class=\"clearfix\">\n\n  {% if paginator.previous_page %}\n  <a class=\"btn btn-primary float-left\" href=\"{{ paginator.previous_page_path | prepend: site.baseurl | replace: '//', '/' }}\">&larr;\n    Newer<span class=\"d-none d-md-inline\"> Posts</span></a>\n  {% endif %}\n\n  {% if paginator.next_page %}\n  <a class=\"btn btn-primary float-right\" href=\"{{ paginator.next_page_path | prepend: site.baseurl | replace: '//', '/' }}\">Older<span class=\"d-none d-md-inline\"> Posts</span> &rarr;</a>\n  {% endif %}\n\n</div>\n\n{% endif %}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/docs/submit.html",
    "content": "---\nlayout: page\ntitle: Submit\ndescription: How to submit to the leaderboard.\n---\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Sed quisquam ut perspiciatis, repudiandae nulla animi iste vel, praesentium repellendus molestias aliquid consequatur, earum rem qui error voluptates eius enim consequuntur!</p>\n\n<p>Lorem ipsum dolor sit amet, consectetur adipisicing elit. Ex alias, earum consectetur quia natus ducimus voluptate explicabo, hic porro reprehenderit, quasi? Tenetur ipsum distinctio laboriosam perspiciatis officiis dolore, architecto id.</p>\n\n<p class=\"mb-5\">Lorem ipsum dolor sit amet, consectetur adipisicing elit. Totam inventore aspernatur repellendus incidunt adipisci modi voluptates recusandae iste eligendi, repudiandae corporis quod aut, optio! Explicabo quaerat unde voluptatem! Itaque, eum!</p>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/agent_wrapper.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nWrapper for autonomous agents required for tracking and checking of used sensors\n\"\"\"\n\nfrom __future__ import print_function\nimport math\nimport os\nimport time\n\nimport carla\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\nfrom leaderboard.envs.sensor_interface import CallBack, OpenDriveMapReader, SpeedometerReader, SensorConfigurationInvalid\nfrom leaderboard.autoagents.autonomous_agent import Track\nfrom leaderboard.autoagents.ros_base_agent import ROSBaseAgent\n\nIS_BENCH2DRIVE = os.environ.get('SAVE_PATH', None)\nif IS_BENCH2DRIVE:\n    MAX_ALLOWED_RADIUS_SENSOR = 100.0  # for visualize\nelse:\n    MAX_ALLOWED_RADIUS_SENSOR = 3.0\n\nQUALIFIER_SENSORS_LIMITS = {\n    'sensor.camera.rgb': 4,\n    'sensor.lidar.ray_cast': 1,\n    'sensor.other.radar': 2,\n    'sensor.other.gnss': 1,\n    'sensor.other.imu': 1,\n    'sensor.opendrive_map': 1,\n    'sensor.speedometer': 1\n}\nSENSORS_LIMITS = {\n    'sensor.camera.rgb': 8,\n    'sensor.lidar.ray_cast': 2,\n    'sensor.other.radar': 4,\n    'sensor.other.gnss': 1,\n    'sensor.other.imu': 1,\n    'sensor.opendrive_map': 1,\n    'sensor.speedometer': 1\n}\nALLOWED_SENSORS = SENSORS_LIMITS.keys()\n\n\nclass AgentError(Exception):\n    \"\"\"\n    Exceptions thrown when the agent returns an error during the simulation\n    \"\"\"\n\n    def __init__(self, message):\n        super(AgentError, self).__init__(message)\n\n        \nclass TickRuntimeError(Exception):\n    pass\n\nclass AgentWrapperFactory(object):\n\n    @staticmethod\n    def get_wrapper(agent):\n        if isinstance(agent, ROSBaseAgent):\n            return ROSAgentWrapper(agent)\n        else:\n            return AgentWrapper(agent)\n\n\ndef validate_sensor_configuration(sensors, agent_track, selected_track):\n    \"\"\"\n    Ensure that the sensor configuration is valid, in case the challenge mode is used\n    Returns true on valid configuration, false otherwise\n    \"\"\"\n    if Track(selected_track) != agent_track:\n        raise SensorConfigurationInvalid(\"You are submitting to the wrong track [{}]!\".format(Track(selected_track)))\n\n    sensor_count = {}\n    sensor_ids = []\n\n    for sensor in sensors:\n\n        # Check if the is has been already used\n        sensor_id = sensor['id']\n        if sensor_id in sensor_ids:\n            raise SensorConfigurationInvalid(\"Duplicated sensor tag [{}]\".format(sensor_id))\n        else:\n            sensor_ids.append(sensor_id)\n\n        # Check if the sensor is valid\n        if agent_track == Track.SENSORS:\n            if sensor['type'].startswith('sensor.opendrive_map'):\n                raise SensorConfigurationInvalid(\"Illegal sensor 'sensor.opendrive_map' used for Track [{}]!\".format(agent_track))\n\n        # Check the sensors validity\n        if sensor['type'] not in ALLOWED_SENSORS:\n            raise SensorConfigurationInvalid(\"Illegal sensor '{}' used for Track [{}]!\".format(sensor['type'], agent_track))\n\n        # Check the extrinsics of the sensor\n        if 'x' in sensor and 'y' in sensor and 'z' in sensor:\n            if math.sqrt(sensor['x']**2 + sensor['y']**2 + sensor['z']**2) > MAX_ALLOWED_RADIUS_SENSOR:\n                raise SensorConfigurationInvalid(\n                    \"Illegal sensor extrinsics used for sensor '{}'. Max allowed radius is {}m\".format(sensor['id'], MAX_ALLOWED_RADIUS_SENSOR))\n\n        # Check the amount of sensors\n        if sensor['type'] in sensor_count:\n            sensor_count[sensor['type']] += 1\n        else:\n            sensor_count[sensor['type']] = 1\n\n    if agent_track in (Track.SENSORS_QUALIFIER, Track.MAP_QUALIFIER):\n        sensor_limits = QUALIFIER_SENSORS_LIMITS\n    else:\n        sensor_limits = SENSORS_LIMITS\n\n    for sensor_type, max_instances_allowed in sensor_limits.items():\n        if sensor_type in sensor_count and sensor_count[sensor_type] > max_instances_allowed:\n            raise SensorConfigurationInvalid(\n                \"Too many {} used! \"\n                \"Maximum number allowed is {}, but {} were requested.\".format(sensor_type,\n                                                                              max_instances_allowed,\n                                                                              sensor_count[sensor_type]))\n\n\nclass AgentWrapper(object):\n\n    \"\"\"\n    Wrapper for autonomous agents required for tracking and checking of used sensors\n    \"\"\"\n    _agent = None\n    _sensors_list = []\n\n    def __init__(self, agent):\n        \"\"\"\n        Set the autonomous agent\n        \"\"\"\n        self._agent = agent\n\n    def __call__(self):\n        \"\"\"\n        Pass the call directly to the agent\n        \"\"\"\n        return self._agent()\n\n    def _preprocess_sensor_spec(self, sensor_spec):\n        type_ = sensor_spec[\"type\"]\n        id_ = sensor_spec[\"id\"]\n        attributes = {}\n\n        if type_ == 'sensor.opendrive_map':\n            attributes['reading_frequency'] = sensor_spec['reading_frequency']\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        elif type_ == 'sensor.speedometer':\n            delta_time = CarlaDataProvider.get_world().get_settings().fixed_delta_seconds\n            attributes['reading_frequency'] = 1 / delta_time\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        if type_ == 'sensor.camera.rgb':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.lidar.ray_cast':\n            attributes['range'] = str(85)\n            attributes['rotation_frequency'] = str(10)\n            attributes['channels'] = str(64)\n            attributes['upper_fov'] = str(10)\n            attributes['lower_fov'] = str(-30)\n            attributes['points_per_second'] = str(600000)\n            attributes['atmosphere_attenuation_rate'] = str(0.004)\n            attributes['dropoff_general_rate'] = str(0.45)\n            attributes['dropoff_intensity_limit'] = str(0.8)\n            attributes['dropoff_zero_intensity'] = str(0.4)\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.radar':\n            attributes['horizontal_fov'] = str(sensor_spec['horizontal_fov'])  # degrees\n            attributes['vertical_fov'] = str(sensor_spec['vertical_fov'])  # degrees\n            attributes['points_per_second'] = '1500'\n            attributes['range'] = '100'  # meters\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.gnss':\n            attributes['noise_alt_stddev'] = str(0.000005)\n            attributes['noise_lat_stddev'] = str(0.000005)\n            attributes['noise_lon_stddev'] = str(0.000005)\n            attributes['noise_alt_bias'] = str(0.0)\n            attributes['noise_lat_bias'] = str(0.0)\n            attributes['noise_lon_bias'] = str(0.0)\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation()\n\n        elif type_ == 'sensor.other.imu':\n            attributes['noise_accel_stddev_x'] = str(0.001)\n            attributes['noise_accel_stddev_y'] = str(0.001)\n            attributes['noise_accel_stddev_z'] = str(0.015)\n            attributes['noise_gyro_stddev_x'] = str(0.001)\n            attributes['noise_gyro_stddev_y'] = str(0.001)\n            attributes['noise_gyro_stddev_z'] = str(0.001)\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n        sensor_transform = carla.Transform(sensor_location, sensor_rotation)\n\n        return type_, id_, sensor_transform, attributes\n\n    def setup_sensors(self, vehicle):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        world = CarlaDataProvider.get_world()\n        bp_library = world.get_blueprint_library()\n        for sensor_spec in self._agent.sensors():\n            type_, id_, sensor_transform, attributes = self._preprocess_sensor_spec(sensor_spec)\n\n            # These are the pseudosensors (not spawned)\n            if type_ == 'sensor.opendrive_map':\n                sensor = OpenDriveMapReader(vehicle, attributes['reading_frequency'])\n            elif type_ == 'sensor.speedometer':\n                sensor = SpeedometerReader(vehicle, attributes['reading_frequency'])\n\n            # These are the sensors spawned on the carla world\n            else:\n                bp = bp_library.find(type_)\n                for key, value in attributes.items():\n                    bp.set_attribute(str(key), str(value))\n                sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)\n\n            # setup callback\n            sensor.listen(CallBack(id_, type_, sensor, self._agent.sensor_interface))\n            self._sensors_list.append(sensor)\n\n        # Some sensors miss sending data during the first ticks, so tick several times and remove the data\n        for _ in range(10):\n            world.tick()\n\n    def cleanup(self):\n        \"\"\"\n        Remove and destroy all sensors\n        \"\"\"\n        for i, _ in enumerate(self._sensors_list):\n            if self._sensors_list[i] is not None:\n                self._sensors_list[i].stop()\n                self._sensors_list[i].destroy()\n                self._sensors_list[i] = None\n        self._sensors_list = []\n\n        # Tick once to destroy the sensors\n        CarlaDataProvider.get_world().tick()\n\n\nclass ROSAgentWrapper(AgentWrapper):\n\n    SENSOR_TYPE_REMAPS = {\n        \"sensor.opendrive_map\": \"sensor.pseudo.opendrive_map\",\n        \"sensor.speedometer\": \"sensor.pseudo.speedometer\"\n    }\n\n    def __init__(self, agent):\n        super(ROSAgentWrapper, self).__init__(agent)\n\n    def _preprocess_sensor_spec(self, sensor_spec):\n        type_, id_, sensor_transform, attributes = super(ROSAgentWrapper, self)._preprocess_sensor_spec(sensor_spec)\n        new_type = self.SENSOR_TYPE_REMAPS.get(type_, type_)\n        return new_type, id_, sensor_transform, attributes\n\n    def setup_sensors(self, vehicle):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        for sensor_spec in self._agent.sensors():\n            type_, id_, transform, attributes = self._preprocess_sensor_spec(sensor_spec)\n            uid = self._agent.spawn_object(type_, id_, transform, attributes, attach_to=vehicle.id)\n            self._sensors_list.append(uid)\n\n        # Tick once to spawn the sensors\n        CarlaDataProvider.get_world().tick()\n\n    def cleanup(self):\n        for uid in self._sensors_list:\n            self._agent.destroy_object(uid)\n        self._sensors_list.clear()\n\n        # Tick once to destroy the sensors\n        CarlaDataProvider.get_world().tick()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/autonomous_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the base class for all autonomous agents\n\"\"\"\n\nfrom __future__ import print_function\n\nfrom enum import Enum\n\nimport carla\nfrom srunner.scenariomanager.timer import GameTime\n\nfrom leaderboard.utils.route_manipulation import downsample_route\nfrom leaderboard.envs.sensor_interface import SensorInterface\n\n\nclass Track(Enum):\n\n    \"\"\"\n    This enum represents the different tracks of the CARLA AD leaderboard.\n    \"\"\"\n    SENSORS = 'SENSORS'\n    MAP = 'MAP'\n    SENSORS_QUALIFIER = 'SENSORS_QUALIFIER'\n    MAP_QUALIFIER = 'MAP_QUALIFIER'\n\n\nclass AutonomousAgent(object):\n\n    \"\"\"\n    Autonomous agent base class. All user agents have to be derived from this class\n    \"\"\"\n\n    def __init__(self, carla_host, carla_port, debug=False):\n        self.track = Track.SENSORS\n        #  current global plans to reach a destination\n        self._global_plan = None\n        self._global_plan_world_coord = None\n\n        # this data structure will contain all sensor data\n        self.sensor_interface = SensorInterface()\n\n        self.wallclock_t0 = None\n\n        self.get_hero()\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Initialize everything needed by your agent and set the track attribute to the right type:\n            Track.SENSORS : CAMERAS, LIDAR, RADAR, GPS and IMU sensors are allowed\n            Track.MAP : OpenDRIVE map is also allowed\n        \"\"\"\n        pass\n\n    def sensors(self):  # pylint: disable=no-self-use\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n\n        \"\"\"\n        sensors = []\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        :return: control\n        \"\"\"\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        pass\n\n    def __call__(self):\n        \"\"\"\n        Execute the agent call, e.g. agent()\n        Returns the next vehicle controls\n        \"\"\"\n        input_data = self.sensor_interface.get_data(GameTime.get_frame())\n\n        timestamp = GameTime.get_time()\n\n        if not self.wallclock_t0:\n            self.wallclock_t0 = GameTime.get_wallclocktime()\n        wallclock = GameTime.get_wallclocktime()\n        wallclock_diff = (wallclock - self.wallclock_t0).total_seconds()\n        sim_ratio = 0 if wallclock_diff == 0 else timestamp/wallclock_diff\n\n        print('=== [Agent] -- Wallclock = {} -- System time = {} -- Game time = {} -- Ratio = {}x'.format(\n            str(wallclock)[:-3], format(wallclock_diff, '.3f'), format(timestamp, '.3f'), format(sim_ratio, '.3f')), flush=True)\n\n        control = self.run_step(input_data, timestamp)\n        control.manual_gear_shift = False\n\n        return control\n\n    @staticmethod\n    def get_ros_version():\n        return -1\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        \"\"\"\n        Set the plan (route) for the agent\n        \"\"\"\n        ds_ids = downsample_route(global_plan_world_coord, 50)\n        self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1]) for x in ds_ids]\n        self._global_plan = [global_plan_gps[x] for x in ds_ids]\n        self._plan_gps_HACK = global_plan_gps\n    \n    def get_hero(self):\n        hero_actor = None\n        from srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n        for actor in CarlaDataProvider.get_world().get_actors():\n            if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero':\n                hero_actor = actor\n                break\n        self.hero_actor = hero_actor\n    \n    def get_metric_info(self):\n        \n        def vector2list(vector, rotation=False):\n            if rotation:\n                return [vector.roll, vector.pitch, vector.yaw]\n            else:\n                return [vector.x, vector.y, vector.z]\n\n        output = {}\n        output['acceleration'] = vector2list(self.hero_actor.get_acceleration())\n        output['angular_velocity'] = vector2list(self.hero_actor.get_angular_velocity())\n        output['forward_vector'] = vector2list(self.hero_actor.get_transform().get_forward_vector())\n        output['right_vector'] = vector2list(self.hero_actor.get_transform().get_right_vector())\n        output['location'] = vector2list(self.hero_actor.get_transform().location)\n        output['rotation'] = vector2list(self.hero_actor.get_transform().rotation, rotation=True)\n        return output"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/dummy_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a dummy agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\ndef get_entry_point():\n    return 'DummyAgent'\n\nclass DummyAgent(AutonomousAgent):\n\n    \"\"\"\n    Dummy autonomous agent to control the ego vehicle\n    \"\"\"\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self.track = Track.MAP\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'},\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0,\n             'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'},\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0,\n             'width': 800, 'height': 600, 'fov': 100, 'id': 'Right'},\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n             'yaw': -45.0, 'id': 'LIDAR'},\n            {'type': 'sensor.other.radar', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n             'yaw': -45.0, 'fov': 30, 'id': 'RADAR', 'horizontal_fov' : 30.0, 'vertical_fov' : 30.0},\n            {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'},\n            {'type': 'sensor.other.imu', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n             'yaw': -45.0, 'id': 'IMU'},\n            {'type': 'sensor.opendrive_map', 'reading_frequency': 1, 'id': 'OpenDRIVE'},\n        ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        print(\"=====================>\")\n        for key, val in input_data.items():\n            if hasattr(val[1], 'shape'):\n                shape = val[1].shape\n                print(\"[{} -- {:06d}] with shape {}\".format(key, val[0], shape))\n            else:\n                print(\"[{} -- {:06d}] \".format(key, val[0]))\n        print(\"<=====================\")\n\n        # DO SOMETHING SMART\n\n        # RETURN CONTROL\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/human_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a human agent to control the ego vehicle via keyboard\n\"\"\"\n\nimport numpy as np\nimport json\n\ntry:\n    import pygame\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_UP\n    from pygame.locals import K_a\n    from pygame.locals import K_d\n    from pygame.locals import K_s\n    from pygame.locals import K_w\n    from pygame.locals import K_q\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\nimport carla\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\n\ndef get_entry_point():\n    return 'HumanAgent'\n\nclass HumanInterface(object):\n\n    \"\"\"\n    Class to control a vehicle manually for debugging purposes\n    \"\"\"\n\n    def __init__(self, width, height, side_scale, left_mirror=False, right_mirror=False):\n        self._width = width\n        self._height = height\n        self._scale = side_scale\n        self._surface = None\n\n        self._left_mirror = left_mirror\n        self._right_mirror = right_mirror\n\n        pygame.init()\n        pygame.font.init()\n        self._clock = pygame.time.Clock()\n        self._display = pygame.display.set_mode((self._width, self._height), pygame.HWSURFACE | pygame.DOUBLEBUF)\n        pygame.display.set_caption(\"Human Agent\")\n\n    def run_interface(self, input_data):\n        \"\"\"\n        Run the GUI\n        \"\"\"\n\n        # Process sensor data\n        image_center = input_data['Center'][1][:, :, -2::-1]\n        self._surface = pygame.surfarray.make_surface(image_center.swapaxes(0, 1))\n\n        # Add the left mirror\n        if self._left_mirror:\n            image_left = input_data['Left'][1][:, :, -2::-1]\n            left_surface = pygame.surfarray.make_surface(image_left.swapaxes(0, 1))\n            self._surface.blit(left_surface, (0, (1 - self._scale) * self._height))\n\n        # Add the right mirror\n        if self._right_mirror:\n            image_right = input_data['Right'][1][:, :, -2::-1]\n            right_surface = pygame.surfarray.make_surface(image_right.swapaxes(0, 1))\n            self._surface.blit(right_surface, ((1 - self._scale) * self._width, (1 - self._scale) * self._height))\n\n        # Display image\n        if self._surface is not None:\n            self._display.blit(self._surface, (0, 0))\n        pygame.display.flip()\n\n    def set_black_screen(self):\n        \"\"\"Set the surface to black\"\"\"\n        black_array = np.zeros([self._width, self._height])\n        self._surface = pygame.surfarray.make_surface(black_array)\n        if self._surface is not None:\n            self._display.blit(self._surface, (0, 0))\n        pygame.display.flip()\n\n    def _quit(self):\n        pygame.quit()\n\n\nclass HumanAgent(AutonomousAgent):\n\n    \"\"\"\n    Human agent to control the ego vehicle via keyboard\n    \"\"\"\n\n    current_control = None\n    agent_engaged = False\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self.track = Track.SENSORS\n\n        self.agent_engaged = False\n        self.camera_width = 1280\n        self.camera_height = 720\n        self._side_scale = 0.3\n        self._left_mirror = False\n        self._right_mirror = False\n\n        self._hic = HumanInterface(\n            self.camera_width,\n            self.camera_height,\n            self._side_scale,\n            self._left_mirror,\n            self._right_mirror\n        )\n        self._controller = KeyboardControl(path_to_conf_file)\n        self._prev_timestamp = 0\n\n        self._clock = pygame.time.Clock()\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': self.camera_width, 'height': self.camera_height, 'fov': 100, 'id': 'Center'},\n        ]\n\n        if self._left_mirror:\n            sensors.append(\n                {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -1.0, 'z': 1, 'roll': 0.0, 'pitch': 0.0, 'yaw': 210.0,\n                 'width': self.camera_width * self._side_scale, 'height': self.camera_height * self._side_scale,\n                 'fov': 100, 'id': 'Left'})\n\n        if self._right_mirror:\n            sensors.append(\n                {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 1.0, 'z': 1, 'roll': 0.0, 'pitch': 0.0, 'yaw': 150.0,\n                 'width': self.camera_width * self._side_scale, 'height': self.camera_height * self._side_scale,\n                 'fov': 100, 'id': 'Right'})\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        self._clock.tick_busy_loop(20)\n        self.agent_engaged = True\n        self._hic.run_interface(input_data)\n\n        control = self._controller.parse_events(timestamp - self._prev_timestamp)\n        self._prev_timestamp = timestamp\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Cleanup\n        \"\"\"\n        self._hic.set_black_screen()\n        self._hic._quit = True\n\n\nclass KeyboardControl(object):\n\n    \"\"\"\n    Keyboard control for the human agent\n    \"\"\"\n\n    def __init__(self, path_to_conf_file):\n        \"\"\"\n        Init\n        \"\"\"\n        self._control = carla.VehicleControl()\n        self._steer_cache = 0.0\n        self._clock = pygame.time.Clock()\n\n        # Get the mode\n        if path_to_conf_file:\n\n            with (open(path_to_conf_file, \"r\")) as f:\n                lines = f.read().split(\"\\n\")\n                self._mode = lines[0].split(\" \")[1]\n                self._endpoint = lines[1].split(\" \")[1]\n\n            # Get the needed vars\n            if self._mode == \"log\":\n                self._log_data = {'records': []}\n\n            elif self._mode == \"playback\":\n                self._index = 0\n                self._control_list = []\n\n                with open(self._endpoint) as fd:\n                    try:\n                        self._records = json.load(fd)\n                        self._json_to_control()\n                    except json.JSONDecodeError:\n                        pass\n        else:\n            self._mode = \"normal\"\n            self._endpoint = None\n\n    def _json_to_control(self):\n\n        # transform strs into VehicleControl commands\n        for entry in self._records['records']:\n            control = carla.VehicleControl(throttle=entry['control']['throttle'],\n                                           steer=entry['control']['steer'],\n                                           brake=entry['control']['brake'],\n                                           hand_brake=entry['control']['hand_brake'],\n                                           reverse=entry['control']['reverse'],\n                                           manual_gear_shift=entry['control']['manual_gear_shift'],\n                                           gear=entry['control']['gear'])\n            self._control_list.append(control)\n\n    def parse_events(self, timestamp):\n        \"\"\"\n        Parse the keyboard events and set the vehicle controls accordingly\n        \"\"\"\n        # Move the vehicle\n        if self._mode == \"playback\":\n            self._parse_json_control()\n        else:\n            self._parse_vehicle_keys(pygame.key.get_pressed(), timestamp*1000)\n\n        # Record the control\n        if self._mode == \"log\":\n            self._record_control()\n\n        return self._control\n\n    def _parse_vehicle_keys(self, keys, milliseconds):\n        \"\"\"\n        Calculate new vehicle controls based on input keys\n        \"\"\"\n\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                return \n            elif event.type == pygame.KEYUP:\n                if event.key == K_q:\n                    self._control.gear = 1 if self._control.reverse else -1\n                    self._control.reverse = self._control.gear < 0\n\n        if keys[K_UP] or keys[K_w]:\n            self._control.throttle = 0.8\n        else:\n            self._control.throttle = 0.0\n\n        steer_increment = 3e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n\n        self._control.steer = round(self._steer_cache, 1)\n        self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0\n        self._control.hand_brake = keys[K_SPACE]\n\n    def _parse_json_control(self):\n\n        if self._index < len(self._control_list):\n            self._control = self._control_list[self._index]\n            self._index += 1\n        else:\n            print(\"JSON file has no more entries\")\n\n    def _record_control(self):\n        new_record = {\n            'control': {\n                'throttle': self._control.throttle,\n                'steer': self._control.steer,\n                'brake': self._control.brake,\n                'hand_brake': self._control.hand_brake,\n                'reverse': self._control.reverse,\n                'manual_gear_shift': self._control.manual_gear_shift,\n                'gear': self._control.gear\n            }\n        }\n\n        self._log_data['records'].append(new_record)\n\n    def __del__(self):\n        # Get ready to log user commands\n        if self._mode == \"log\" and self._log_data:\n            with open(self._endpoint, 'w') as fd:\n                json.dump(self._log_data, fd, indent=4, sort_keys=True)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/human_agent_config.txt",
    "content": "mode: log                      # Either 'log' or 'playback'\nfile: test.json                     # path to the file with the controls\n\n\nThis is the configuration file of the human agent. This agent incorporates two modes.\nThe log mode parses the controls given to the vehicle into a dictionary and records them into a .json file.\nThis file can be read by the playback mode to control the vehicle in the same way, resulting in a deterministic agent.\nThe file name can be chosen, and is the second argument of this config file.\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/npc_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an NPC agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\ndef get_entry_point():\n    return 'NpcAgent'\n\nclass NpcAgent(AutonomousAgent):\n\n    \"\"\"\n    NPC autonomous agent to control the ego vehicle\n    \"\"\"\n\n    _agent = None\n    _route_assigned = False\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self.track = Track.SENSORS\n\n        self._agent = None\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n        ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation. \n        \"\"\"\n        if not self._agent:\n\n            # Search for the ego actor\n            hero_actor = None\n            for actor in CarlaDataProvider.get_world().get_actors():\n                if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero':\n                    hero_actor = actor\n                    break\n\n            if not hero_actor:\n                return carla.VehicleControl()\n\n            # Add an agent that follows the route to the ego\n            self._agent = BasicAgent(hero_actor, 30)\n\n            plan = []\n            prev_wp = None\n            for transform, _ in self._global_plan_world_coord:\n                wp = CarlaDataProvider.get_map().get_waypoint(transform.location)\n                if prev_wp:\n                    plan.extend(self._agent.trace_route(prev_wp, wp))\n                prev_wp = wp\n\n            self._agent.set_global_plan(plan)\n\n            return carla.VehicleControl()\n\n        else:\n            return self._agent.run_step()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/ros1_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a ROS autonomous agent interface to control the ego vehicle via a ROS stack\n\"\"\"\n\nfrom __future__ import print_function\n\nimport time\n\nfrom leaderboard.autoagents.ros_base_agent import BridgeHelper, ROSBaseAgent, ROSLauncher\n\nimport roslibpy\n\n\nclass ROS1Server(object):\n    client = roslibpy.Ros(host='localhost', port=9090)\n\n    def __init__(self, debug=True):\n        self._server_process = ROSLauncher(\"server\", ros_version=1, debug=debug)\n\n    def start(self):\n        self._server_process.run(\n            package=\"rosbridge_server\",\n            launch_file=\"rosbridge_websocket.launch\",\n            wait=False\n        )\n        ROS1Server.client.run(30)\n\n    def shutdown(self):\n        self._server_process.terminate()\n        assert not self._server_process.is_alive()\n        ROS1Server.client.close()\n\n\ndef wait_for_message(client, topic, topic_type, timeout=None):\n\n    class _WFM(object):\n        def __init__(self):\n            self.msg = None\n        def cb(self, msg):\n            if self.msg is None:\n                self.msg = msg\n\n    wfm = _WFM()\n    s = None\n    try:\n        s = roslibpy.Topic(client, topic, topic_type, reconnect_on_close=False)\n        s.subscribe(wfm.cb)\n        if timeout is not None:\n            timeout_t = time.time() + timeout\n        while client.is_connected and wfm.msg is None:\n            time.sleep(0.1)\n            if timeout is not None and time.time() >= timeout_t:\n                raise TimeoutError(\"timeout exceeded while waiting for message on topic {}\".format(topic))\n\n    finally:\n        if s is not None:\n            s.unsubscribe()\n\n    return wfm.msg\n\n\ndef wait_for_service(client, service, timeout=None):\n\n    if timeout is not None:\n        timeout_t = time.time() + timeout\n\n    services = client.get_services()\n    while service not in services:\n        time.sleep(0.1)\n        if timeout is not None and time.time() >= timeout_t:\n            raise TimeoutError(\"timeout exceeded while waiting for service {} to be ready\".format(service))\n        services = client.get_services()\n\n\nclass ROS1Agent(ROSBaseAgent):\n\n    ROS_VERSION = 1\n\n    def __init__(self, carla_host, carla_port, debug=False):\n        super(ROS1Agent, self).__init__(self.ROS_VERSION, carla_host, carla_port, debug)\n\n        client = ROS1Server.client\n\n        self._spawn_object_service = roslibpy.Service(client, \"/carla/spawn_object\", \"carla_msgs/SpawnObject\", reconnect_on_close=False)\n        self._destroy_object_service = roslibpy.Service(client, \"/carla/destroy_object\", \"carla_msgs/DestroyObject\", reconnect_on_close=False)\n\n        wait_for_service(client, \"/carla/spawn_object\")\n        wait_for_service(client, \"/carla/destroy_object\")\n\n        self._control_subscriber = roslibpy.Topic(client, \"/carla/hero/vehicle_control_cmd\", \"carla_msgs/CarlaEgoVehicleControl\", queue_length=1, reconnect_on_close=False)\n        self._control_subscriber.subscribe(self._vehicle_control_cmd_callback)\n\n        self._path_publisher = roslibpy.Topic(client, \"/carla/hero/global_plan\", \"carla_msgs/CarlaRoute\", latch=True, reconnect_on_close=False)\n        self._path_gnss_publisher = roslibpy.Topic(client, \"/carla/hero/global_plan_gnss\", \"carla_msgs/CarlaGnssRoute\", latch=True, reconnect_on_close=False)\n\n        wait_for_message(client, \"/carla/hero/status\", \"std_msgs/Bool\")\n\n    @staticmethod\n    def get_ros_version():\n        return ROS1Agent.ROS_VERSION\n\n    def spawn_object(self, type_, id_, transform, attributes, attach_to=0):\n        spawn_point = BridgeHelper.carla2ros_pose(\n            transform.location.x, transform.location.y, transform.location.z,\n            transform.rotation.roll, transform.rotation.pitch, transform.rotation.yaw,\n            to_quat=True\n        )\n        attributes = [{\"key\": str(key), \"value\": str(value)} for key, value in attributes.items()]\n\n        request = roslibpy.ServiceRequest({\n            \"type\": type_,\n            \"id\": id_,\n            \"attach_to\": attach_to,\n            \"transform\": spawn_point,\n            \"random_pose\": False,\n            \"attributes\": attributes,\n        })\n\n        response = self._spawn_object_service.call(request)\n        if response[\"id\"] == -1:\n            raise RuntimeError(\"{} could not be spawned. {}\".format(type_, response[\"error_string\"]))\n        return response[\"id\"]\n\n    def destroy_object(self, uid):\n        request = roslibpy.ServiceRequest({\"id\": uid})\n        response = self._destroy_object_service.call(request)\n        if not response[\"success\"]:\n            raise RuntimeError(\"{} could not be destroyed\".format(uid))\n        return response[\"success\"]\n\n    def run_step(self, input_data, timestamp):\n        return super(ROS1Agent, self).run_step(input_data, timestamp)\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        super(ROS1Agent, self).set_global_plan(global_plan_gps, global_plan_world_coord)\n\n        poses = []\n        for wp in self._global_plan_world_coord:\n            poses.append(BridgeHelper.carla2ros_pose(\n                wp[0].location.x, wp[0].location.y, wp[0].location.z,\n                wp[0].rotation.roll, wp[0].rotation.pitch, wp[0].rotation.yaw,\n                to_quat=True\n            ))\n\n        self._path_publisher.publish(roslibpy.Message(\n            {\n                \"header\": {\n                    \"frame_id\": \"/map\"\n                },\n                \"road_options\": [ int(wp[1]) for wp in self._global_plan_world_coord ],\n                \"poses\": [ pose for pose in poses ]\n            }))\n\n        self._path_gnss_publisher.publish(roslibpy.Message(\n            {\n                \"header\": {\n                    \"frame_id\": \"/map\"\n                },\n                \"road_options\": [ int(wp[1]) for wp in self._global_plan ],\n                \"coordinates\": [ {\"latitude\": wp[0][\"lat\"], \"longitude\": wp[0][\"lon\"], \"altitude\": wp[0][\"z\"]} for wp in self._global_plan ]\n            }))\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        self._control_subscriber.unsubscribe()\n        self._path_publisher.unadvertise()\n        self._spawn_object_service.unadvertise()\n        self._destroy_object_service.unadvertise()\n\n        super(ROS1Agent, self).destroy()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/ros2_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a ROS autonomous agent interface to control the ego vehicle via a ROS2 stack\n\"\"\"\n\nfrom __future__ import print_function\n\nimport threading\n\nimport carla\n\nfrom leaderboard.autoagents.ros_base_agent import BridgeHelper, ROSBaseAgent\n\nimport rclpy\nfrom rclpy.node import Node\nfrom rclpy.qos import DurabilityPolicy, QoSProfile\nfrom rclpy.task import Future\n\nfrom carla_msgs.msg import CarlaEgoVehicleControl, CarlaRoute, CarlaGnssRoute\nfrom carla_msgs.srv import SpawnObject, DestroyObject\nfrom diagnostic_msgs.msg import KeyValue\nfrom geometry_msgs.msg import Point, Pose, Quaternion\nfrom sensor_msgs.msg import NavSatFix\nfrom std_msgs.msg import Bool\n\n\ndef wait_for_message(node, topic, topic_type, timeout=None):\n\n    s = None\n    try:\n        future = Future()\n        s = node.create_subscription(\n            topic_type,\n            topic,\n            lambda msg: future.set_result(msg.data),\n            qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))\n        rclpy.spin_until_future_complete(node, future, timeout)\n\n    finally:\n        if s is not None:\n            node.destroy_subscription(s)\n\n    return future.result()\n\n\nclass ROS2Agent(ROSBaseAgent):\n\n    \"\"\"\n    Autonomous agent base class. All user agents have to be derived from this class\n    \"\"\"\n\n    ROS_VERSION = 2\n\n    def __init__(self, carla_host, carla_port, debug=False):\n        super(ROS2Agent, self).__init__(self.ROS_VERSION, carla_host, carla_port, debug)\n\n        rclpy.init(args=None)\n        self.ros_node = rclpy.create_node(\"leaderboard_node\")\n\n        self._spawn_object_service = self.ros_node.create_client(SpawnObject, \"/carla/spawn_object\")\n        self._destroy_object_service = self.ros_node.create_client(DestroyObject, \"/carla/destroy_object\")\n\n        self._spawn_object_service.wait_for_service()\n        self._destroy_object_service.wait_for_service()\n\n        self._path_publisher = self.ros_node.create_publisher(CarlaRoute, \"/carla/hero/global_plan\", qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))\n        self._path_gnss_publisher = self.ros_node.create_publisher(CarlaGnssRoute, \"/carla/hero/global_plan_gnss\", qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))\n        \n        self.ctrl_subscriber = self.ros_node.create_subscription(CarlaEgoVehicleControl, \"/carla/hero/vehicle_control_cmd\", self._vehicle_control_cmd_callback, qos_profile=QoSProfile(depth=1))\n\n        wait_for_message(self.ros_node, \"/carla/hero/status\", Bool)\n\n        self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros_node,))\n        self.spin_thread.start()\n\n    @staticmethod\n    def get_ros_version():\n        return ROS2Agent.ROS_VERSION\n\n    def spawn_object(self, type_, id_, transform, attributes, attach_to=0):\n        spawn_point = BridgeHelper.carla2ros_pose(\n            transform.location.x, transform.location.y, transform.location.z,\n            transform.rotation.roll, transform.rotation.pitch, transform.rotation.yaw,\n            to_quat=True\n        )\n\n        request = SpawnObject.Request()\n        request.type = type_\n        request.id = id_\n        request.attach_to = attach_to\n        request.transform = Pose(position=Point(**spawn_point[\"position\"]), orientation=Quaternion(**spawn_point[\"orientation\"]))\n        request.random_pose = False\n        request.attributes.extend([\n            KeyValue(key=str(k), value=str(v)) for k,v in attributes.items()\n        ])\n\n        # Call the service synchronously.\n        response = self._spawn_object_service.call(request)\n        if response.id == -1:\n            raise RuntimeError(\"{} could not be spawned. {}\".format(type_, response[\"error_string\"]))\n        return response.id\n\n    def destroy_object(self, uid):\n        request = DestroyObject.Request()\n        request.id = uid\n\n        # Call the servive syncrhonoulsy\n        response = self._destroy_object_service.call(request)\n        if not response.success:\n            raise RuntimeError(\"{} could not be destroyed\".format(uid))\n        return response.success\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        super(ROS2Agent, self).set_global_plan(global_plan_gps, global_plan_world_coord)\n\n        path = CarlaRoute()\n        for wp in self._global_plan_world_coord:\n            path.road_options.append(int(wp[1]))\n            pose = BridgeHelper.carla2ros_pose(\n                wp[0].location.x, wp[0].location.y, wp[0].location.z,\n                wp[0].rotation.roll, wp[0].rotation.pitch, wp[0].rotation.yaw,\n                to_quat=True\n            )\n            path.poses.append(\n                Pose(position=Point(**pose[\"position\"]), orientation=Quaternion(**pose[\"orientation\"])))\n        self._path_publisher.publish(path)\n\n        path_gnss = CarlaGnssRoute()\n        for wp in self._global_plan:\n            path_gnss.road_options.append(wp[1])\n            path.poses.append(\n                NavSatFix(latitude=wp[0][\"lat\"], longitude=wp[0][\"lon\"], altitude=wp[0][\"z\"]))\n        self._path_gnss_publisher.publish(path_gnss)\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        self.ros_node.destroy_node()\n        rclpy.shutdown()\n        self.spin_thread.join()\n\n        super(ROS2Agent, self).destroy()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/autoagents/ros_base_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a base ROS autonomous agent interface to control the ego vehicle via a ROS1/ROS2 stack\n\"\"\"\n\nfrom __future__ import print_function\n\nimport logging\nimport logging.handlers\nimport os\nimport queue\nimport threading\n\nimport carla\nimport pexpect\nimport transforms3d\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track\n\nEPSILON = 0.001\n\n\nclass ROSLogger(object):\n\n    def __init__(self, name):\n        self.name = name\n    \n        self.logger = logging.getLogger(self.name)\n        self.logger.setLevel(logging.INFO)\n\n        logger_path = os.path.join(\"log\", \"ros\")\n        if not os.path.isdir(logger_path):\n            os.makedirs(logger_path)\n\n        self.handler = logging.handlers.RotatingFileHandler(os.path.join(logger_path, self.name + \".log\"), maxBytes=25*1024*1024, backupCount=3)\n        self.handler.setLevel(logging.INFO)\n        self.handler.setFormatter(logging.Formatter(\"%(message)s\"))\n\n        self.logger.addHandler(self.handler)\n\n    def write(self, data):\n        self.logger.info(data.strip())\n\n    def flush(self):\n        pass\n\n    def fileno(self):\n        return self.handler.stream.fileno()\n    \n    def destroy(self):\n        self.logger.removeHandler(self.handler)\n\n\nclass ROSLauncher(object):\n\n    def __init__(self, app_name, ros_version, debug=False):\n        self.app_name = app_name\n        self.ros_version = ros_version\n        # force always debugging\n        self.debug = True\n\n        self._process = None\n\n        self._log_thread = threading.Thread(target=self.log)\n        if self.debug:\n            self._logger = ROSLogger(self.app_name)\n\n    def run(self, package, launch_file, parameters={}, wait=False):\n        cmdline = [\n            \"roslaunch\" if self.ros_version == 1 else \"ros2 launch\",\n            package,\n            launch_file,\n            \" \".join([\"{}:={}\".format(k, v) for k, v in parameters.items()]),\n            \"--wait\" if wait and self.ros_version == 1 else \"\"\n        ]\n        cmdline = \" \".join(cmdline)\n        self._process = pexpect.spawn(cmdline, encoding=\"utf-8\", logfile=self._logger if self.debug else None)\n        self._log_thread.start()\n\n    def log(self):\n        while True:\n            try:\n                self._process.expect([pexpect.TIMEOUT], timeout=0.1)\n            except pexpect.exceptions.EOF as e:\n                break\n\n    def is_alive(self):\n        if self._process is None:\n            return False\n        return self._process.isalive()\n\n    def terminate(self):\n        assert self._process is not None\n        self._process.terminate()\n\n        self._log_thread.join()\n        if self.debug:\n            self._logger.destroy()\n\n\nclass BridgeHelper(object):\n\n    @classmethod\n    def carla2ros_pose(cls, x, y, z, roll, pitch, yaw, to_quat=False):\n        out_position = {\"x\": x, \"y\": -y, \"z\": z}\n        out_orientation = {\"roll\": roll, \"pitch\": -pitch, \"yaw\": -yaw}\n        if to_quat:\n            out_orientation = cls.rpy2quat(\n                out_orientation[\"roll\"], out_orientation[\"pitch\"], out_orientation[\"yaw\"]\n            )\n        return {\n            \"position\": out_position,\n            \"orientation\": out_orientation\n        }\n\n    @staticmethod\n    def rpy2quat(roll, pitch, yaw):\n        quat = transforms3d.euler.euler2quat(roll, pitch, yaw)\n        return {\"x\": quat[1], \"y\": quat[2], \"z\": quat[3], \"w\": quat[0]}\n\n\nclass ROSBaseAgent(AutonomousAgent):\n\n    \"\"\"\n    Base class for ROS-based stacks.\n\n    The sensor data is published using carla-ros-bridge. You can find details about\n    the utilized datatypes there.\n    \"\"\"\n\n    def __init__(self, ros_version, carla_host, carla_port, debug=False):\n        super(ROSBaseAgent, self).__init__(carla_host, carla_port, debug)\n\n        self._bridge_process = ROSLauncher(\"bridge\", ros_version=ros_version, debug=debug)\n        self._bridge_process.run(\n            package=\"carla_ros_bridge\",\n            launch_file=\"carla_ros_bridge.launch\" if ros_version == 1 else \"carla_ros_bridge.launch.py\",\n            parameters={\n                \"host\": carla_host,\n                \"port\": carla_port,\n                \"timeout\": 60,\n                \"synchronous_mode\": True,\n                \"passive\": True,\n                \"register_all_sensors\": False,\n                \"ego_vehicle_role_name\": \"\\\"''\\\"\"\n            },\n            wait=True\n        )\n\n        self._agent_process = ROSLauncher(\"agent\", ros_version=ros_version, debug=debug)\n        self._agent_process.run(\n            **self.get_ros_entrypoint(),\n            wait=True\n        )\n\n        self._control_queue = queue.Queue(1)\n        self._last_control_timestamp = None\n\n    def get_ros_entrypoint(self):\n        raise NotImplementedError\n\n    def spawn_object(self, type_, id_, transform, attributes, attach_to=0):\n        raise NotImplementedError\n\n    def destroy_object(self, uid):\n        raise NotImplementedError\n\n    def _vehicle_control_cmd_callback(self, control_msg):\n        if isinstance(control_msg, dict):\n            control_timestamp = control_msg[\"header\"][\"stamp\"][\"secs\"] + control_msg[\"header\"][\"stamp\"][\"nsecs\"] * 1e-9\n            control = carla.VehicleControl(\n                steer=control_msg[\"steer\"],\n                throttle=control_msg[\"throttle\"],\n                brake=control_msg[\"brake\"],\n                hand_brake=control_msg[\"hand_brake\"],\n                reverse=control_msg[\"reverse\"],\n                manual_gear_shift=control_msg[\"manual_gear_shift\"],\n                gear=control_msg[\"gear\"]\n            )\n        else:\n            control_timestamp = control_msg.header.stamp.sec + control_msg.header.stamp.nanosec * 1e-9\n            control = carla.VehicleControl(\n                steer=control_msg.steer,\n                throttle=control_msg.throttle,\n                brake=control_msg.brake,\n                hand_brake=control_msg.hand_brake,\n                reverse=control_msg.reverse,\n                manual_gear_shift=control_msg.manual_gear_shift,\n                gear=control_msg.gear\n            )\n\n        # Checks that the received control timestamp is not repeated.\n        if self._last_control_timestamp is not None and abs(self._last_control_timestamp - control_timestamp) < EPSILON:\n            print(\n                \"\\033[93mWARNING: A new vehicle command with a repeated timestamp has been received {} .\\033[0m\".format(control_timestamp),\n                \"\\033[93mThis vehicle command will be ignored.\\033[0m\",\n                sep=\" \")\n            return\n\n        # Checks that the received control timestamp is the expected one.\n        # We need to retrieve the simulation time directly from the CARLA snapshot instead of using the GameTime object to avoid\n        # a race condition between the execution of this callback and the update of the GameTime internal variables.\n        carla_timestamp = CarlaDataProvider.get_world().get_snapshot().timestamp.elapsed_seconds\n        if abs(control_timestamp - carla_timestamp) > EPSILON:\n            print(\n                \"\\033[93mWARNING: Expecting a vehicle command with timestamp {} but the timestamp received was {} .\\033[0m\".format(carla_timestamp, control_timestamp),\n                \"\\033[93mThis vehicle command will be ignored.\\033[0m\",\n                sep=\" \")\n            return\n\n        self._last_control_timestamp = control_timestamp\n        try:\n            self._control_queue.put_nowait((control_timestamp, control))\n        except queue.Full:\n            print(\n                \"\\033[93mWARNING: A new vehicle command has been received while the previous one has not been yet processed.\\033[0m\",\n                \"\\033[93mThis vehicle command will be ignored.\\033[0m\",\n                sep=\" \")\n\n\n    def run_step(self, _, timestamp):\n        assert self._bridge_process.is_alive()\n        assert self._agent_process.is_alive()\n\n        #control_timestamp, control = self._control_queue.get(True)\n        try:\n            control_timestamp, control = self._control_queue.get(True, 1.0)\n        except queue.Empty:\n            control_timestamp, control = 0, carla.VehicleControl()\n\n        carla_timestamp = CarlaDataProvider.get_world().get_snapshot().timestamp.elapsed_seconds\n        if abs(control_timestamp - carla_timestamp) > EPSILON:\n            print(\n                \"\\033[93mWARNING: Expecting a vehicle command with timestamp {} but the timestamp received was {} .\\033[0m\".format(carla_timestamp, control_timestamp),\n                 sep=\" \")\n\n        return control\n\n    def destroy(self):\n        self._agent_process.terminate()\n        self._bridge_process.terminate()\n\n        assert not self._agent_process.is_alive()\n        assert not self._bridge_process.is_alive()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/envs/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/envs/sensor_interface.py",
    "content": "import copy\nimport logging\nimport numpy as np\nimport os\nimport time\nfrom threading import Thread\n\nfrom queue import Queue\nfrom queue import Empty\n\nimport carla\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\n\ndef threaded(fn):\n    def wrapper(*args, **kwargs):\n        thread = Thread(target=fn, args=args, kwargs=kwargs)\n        thread.setDaemon(True)\n        thread.start()\n\n        return thread\n    return wrapper\n\n\nclass SensorConfigurationInvalid(Exception):\n    \"\"\"\n    Exceptions thrown when the sensors used by the agent are not allowed for that specific submissions\n    \"\"\"\n\n    def __init__(self, message):\n        super(SensorConfigurationInvalid, self).__init__(message)\n\n\nclass SensorReceivedNoData(Exception):\n    \"\"\"\n    Exceptions thrown when the sensors used by the agent take too long to receive data\n    \"\"\"\n\n    def __init__(self, message):\n        super(SensorReceivedNoData, self).__init__(message)\n\n\nclass GenericMeasurement(object):\n    def __init__(self, data, frame):\n        self.data = data\n        self.frame = frame\n\n\nclass BaseReader(object):\n    def __init__(self, vehicle, reading_frequency=1.0):\n        self._vehicle = vehicle\n        self._reading_frequency = reading_frequency\n        self._callback = None\n        self._run_ps = True\n        self.run()\n\n    def __call__(self):\n        pass\n\n    @threaded\n    def run(self):\n        first_time = True\n        latest_time = GameTime.get_time()\n        while self._run_ps:\n            if self._callback is not None:\n                current_time = GameTime.get_time()\n\n                # Second part forces the sensors to send data at the first tick, regardless of frequency\n                if current_time - latest_time > (1 / self._reading_frequency) \\\n                        or (first_time and GameTime.get_frame() != 0):\n                    self._callback(GenericMeasurement(self.__call__(), GameTime.get_frame()))\n                    latest_time = GameTime.get_time()\n                    first_time = False\n\n                else:\n                    time.sleep(0.001)\n\n    def listen(self, callback):\n        # Tell that this function receives what the producer does.\n        self._callback = callback\n\n    def stop(self):\n        self._run_ps = False\n\n    def destroy(self):\n        self._run_ps = False\n\n\nclass SpeedometerReader(BaseReader):\n    \"\"\"\n    Sensor to measure the speed of the vehicle.\n    \"\"\"\n    MAX_CONNECTION_ATTEMPTS = 10\n\n    def _get_forward_speed(self, transform=None, velocity=None):\n        \"\"\" Convert the vehicle transform directly to forward speed \"\"\"\n        if not velocity:\n            velocity = self._vehicle.get_velocity()\n        if not transform:\n            transform = self._vehicle.get_transform()\n\n        vel_np = np.array([velocity.x, velocity.y, velocity.z])\n        pitch = np.deg2rad(transform.rotation.pitch)\n        yaw = np.deg2rad(transform.rotation.yaw)\n        orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)])\n        speed = np.dot(vel_np, orientation)\n        return speed\n\n    def __call__(self):\n        \"\"\" We convert the vehicle physics information into a convenient dictionary \"\"\"\n\n        # protect this access against timeout\n        attempts = 0\n        while attempts < self.MAX_CONNECTION_ATTEMPTS:\n            try:\n                velocity = self._vehicle.get_velocity()\n                transform = self._vehicle.get_transform()\n                break\n            except Exception:\n                attempts += 1\n                time.sleep(0.2)\n                continue\n\n        return {'speed': self._get_forward_speed(transform=transform, velocity=velocity)}\n\n\nclass OpenDriveMapReader(BaseReader):\n    def __call__(self):\n        return {'opendrive': CarlaDataProvider.get_map().to_opendrive()}\n\n\nclass CallBack(object):\n    def __init__(self, tag, sensor_type, sensor, data_provider):\n        self._tag = tag\n        self._data_provider = data_provider\n\n        self._data_provider.register_sensor(tag, sensor_type, sensor)\n\n    def __call__(self, data):\n        if isinstance(data, carla.libcarla.Image):\n            self._parse_image_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.LidarMeasurement):\n            self._parse_lidar_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.RadarMeasurement):\n            self._parse_radar_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.GnssMeasurement):\n            self._parse_gnss_cb(data, self._tag)\n        elif isinstance(data, carla.libcarla.IMUMeasurement):\n            self._parse_imu_cb(data, self._tag)\n        elif isinstance(data, GenericMeasurement):\n            self._parse_pseudosensor(data, self._tag)\n        else:\n            logging.error('No callback method for this sensor.')\n\n    # Parsing CARLA physical Sensors\n    def _parse_image_cb(self, image, tag):\n        array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n        array = copy.deepcopy(array)\n        array = np.reshape(array, (image.height, image.width, 4))\n        self._data_provider.update_sensor(tag, array, image.frame)\n\n    def _parse_lidar_cb(self, lidar_data, tag):\n        points = np.frombuffer(lidar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        self._data_provider.update_sensor(tag, points, lidar_data.frame)\n\n    def _parse_radar_cb(self, radar_data, tag):\n        # [depth, azimuth, altitute, velocity]\n        points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        points = np.flip(points, 1)\n        self._data_provider.update_sensor(tag, points, radar_data.frame)\n\n    def _parse_gnss_cb(self, gnss_data, tag):\n        array = np.array([gnss_data.latitude,\n                          gnss_data.longitude,\n                          gnss_data.altitude], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, gnss_data.frame)\n\n    def _parse_imu_cb(self, imu_data, tag):\n        array = np.array([imu_data.accelerometer.x,\n                          imu_data.accelerometer.y,\n                          imu_data.accelerometer.z,\n                          imu_data.gyroscope.x,\n                          imu_data.gyroscope.y,\n                          imu_data.gyroscope.z,\n                          imu_data.compass,\n                         ], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, imu_data.frame)\n\n    def _parse_pseudosensor(self, package, tag):\n        self._data_provider.update_sensor(tag, package.data, package.frame)\n\n\nclass SensorInterface(object):\n    def __init__(self):\n        self._sensors_objects = {}\n        self._data_buffers = Queue()\n        self._queue_timeout = 300\n\n        # Only sensor that doesn't get the data on tick, needs special treatment\n        self._opendrive_tag = None\n\n    def register_sensor(self, tag, sensor_type, sensor):\n        if tag in self._sensors_objects:\n            raise SensorConfigurationInvalid(\"Duplicated sensor tag [{}]\".format(tag))\n\n        self._sensors_objects[tag] = sensor\n\n        if sensor_type == 'sensor.opendrive_map': \n            self._opendrive_tag = tag\n\n    def update_sensor(self, tag, data, frame):\n        if tag not in self._sensors_objects:\n            raise SensorConfigurationInvalid(\"The sensor with tag [{}] has not been created!\".format(tag))\n\n        self._data_buffers.put((tag, frame, data))\n\n    def get_data(self, frame):\n        \"\"\"Read the queue to get the sensors data\"\"\"\n        try:\n            data_dict = {}\n            while len(data_dict.keys()) < len(self._sensors_objects.keys()):\n                # Don't wait for the opendrive sensor\n                if self._opendrive_tag and self._opendrive_tag not in data_dict.keys() \\\n                        and len(self._sensors_objects.keys()) == len(data_dict.keys()) + 1:\n                    break\n\n                sensor_data = self._data_buffers.get(True, self._queue_timeout)\n                if sensor_data[1] != frame:\n                    continue\n                data_dict[sensor_data[0]] = ((sensor_data[1], sensor_data[2]))\n\n        except Empty:\n            raise SensorReceivedNoData(\"A sensor took too long to send their data\")\n\n        return data_dict\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/leaderboard_evaluator.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Corporation.\n# authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCARLA Challenge Evaluator Routes\n\nProvisional code to evaluate Autonomous Agents for the CARLA Autonomous Driving challenge\n\"\"\"\nfrom __future__ import print_function\n\nimport traceback\nimport argparse\nfrom argparse import RawTextHelpFormatter\nfrom distutils.version import LooseVersion\nimport importlib\nimport os\nimport pkg_resources\nimport sys\nimport carla\nimport signal\n\nfrom srunner.scenariomanager.carla_data_provider import *\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.watchdog import Watchdog\n\nfrom leaderboard.scenarios.scenario_manager import ScenarioManager\nfrom leaderboard.scenarios.route_scenario import RouteScenario\nfrom leaderboard.envs.sensor_interface import SensorConfigurationInvalid\nfrom leaderboard.autoagents.agent_wrapper import AgentError, validate_sensor_configuration, TickRuntimeError\nfrom leaderboard.utils.statistics_manager import StatisticsManager, FAILURE_MESSAGES\nfrom leaderboard.utils.route_indexer import RouteIndexer\nimport atexit\nimport subprocess\nimport time\nimport random\nfrom datetime import datetime\n\nsensors_to_icons = {\n    'sensor.camera.rgb':        'carla_camera',\n    'sensor.lidar.ray_cast':    'carla_lidar',\n    'sensor.other.radar':       'carla_radar',\n    'sensor.other.gnss':        'carla_gnss',\n    'sensor.other.imu':         'carla_imu',\n    'sensor.opendrive_map':     'carla_opendrive_map',\n    'sensor.speedometer':       'carla_speedometer'\n}\n\nimport socket\n\ndef find_free_port(starting_port):\n    port = starting_port\n    while True:\n        try:\n            with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:\n                s.bind((\"localhost\", port))\n                return port\n        except OSError:\n            port += 1\n\ndef get_weather_id(weather_conditions):\n    from xml.etree import ElementTree as ET\n    tree = ET.parse('leaderboard/data/weather.xml')\n    root = tree.getroot()\n    def conditions_match(weather, conditions):\n        for (key, value) in weather:\n            if key == 'route_percentage' : continue\n            if str(getattr(conditions, key))!= value:\n                return False\n        return True\n    for case in root.findall('case'):\n        weather = case[0].items()\n        if conditions_match(weather, weather_conditions):\n            return case.items()[0][1]\n    return None\n\nclass LeaderboardEvaluator(object):\n    \"\"\"\n    Main class of the Leaderboard. Everything is handled from here,\n    from parsing the given files, to preparing the simulation, to running the route.\n    \"\"\"\n\n    # Tunable parameters\n    client_timeout = 300.0  # in seconds\n    frame_rate = 20.0      # in Hz\n\n    def __init__(self, args, statistics_manager):\n        \"\"\"\n        Setup CARLA client and world\n        Setup ScenarioManager\n        \"\"\"\n        self.world = None\n        self.manager = None\n        self.sensors = None\n        self.sensors_initialized = False\n        self.sensor_icons = []\n        self.agent_instance = None\n        self.route_scenario = None\n\n        self.statistics_manager = statistics_manager\n\n        # This is the ROS1 bridge server instance. This is not encapsulated inside the ROS1 agent because the same\n        # instance is used on all the routes (i.e., the server is not restarted between routes). This is done\n        # to avoid reconnection issues between the server and the roslibpy client.\n        self._ros1_server = None\n\n        # Setup the simulation\n        self.client, self.client_timeout, self.traffic_manager = self._setup_simulation(args)\n\n        dist = pkg_resources.get_distribution(\"carla\")\n        if dist.version != 'leaderboard':\n            if LooseVersion(dist.version) < LooseVersion('0.9.10'):\n                raise ImportError(\"CARLA version 0.9.10.1 or newer required. CARLA version found: {}\".format(dist))\n\n        # Load agent\n        module_name = os.path.basename(args.agent).split('.')[0]\n        sys.path.insert(0, os.path.dirname(args.agent))\n        self.module_agent = importlib.import_module(module_name)\n\n        # Create the ScenarioManager\n        self.manager = ScenarioManager(args.timeout, self.statistics_manager, args.debug)\n\n        # Time control for summary purposes\n        self._start_time = GameTime.get_time()\n        self._end_time = None\n\n        # Prepare the agent timer\n        self._agent_watchdog = None\n        signal.signal(signal.SIGINT, self._signal_handler)\n\n        self._client_timed_out = False\n\n    def _signal_handler(self, signum, frame):\n        \"\"\"\n        Terminate scenario ticking when receiving a signal interrupt.\n        Either the agent initialization watchdog is triggered, or the runtime one at scenario manager\n        \"\"\"\n        if self._agent_watchdog and not self._agent_watchdog.get_status():\n            raise RuntimeError(\"Timeout: Agent took longer than {}s to setup\".format(self.client_timeout))\n        elif self.manager:\n            self.manager.signal_handler(signum, frame)\n\n    def __del__(self):\n        \"\"\"\n        Cleanup and delete actors, ScenarioManager and CARLA world\n        \"\"\"\n        if hasattr(self, 'manager') and self.manager:\n            del self.manager\n        if hasattr(self, 'world') and self.world:\n            del self.world\n\n    def _get_running_status(self):\n        \"\"\"\n        returns:\n           bool: False if watchdog exception occured, True otherwise\n        \"\"\"\n        if self._agent_watchdog:\n            return self._agent_watchdog.get_status()\n        return False\n\n    def _cleanup(self):\n        \"\"\"\n        Remove and destroy all actors\n        \"\"\"\n        CarlaDataProvider.cleanup()\n\n        if self._agent_watchdog:\n            self._agent_watchdog.stop()\n\n        try:\n            if self.agent_instance:\n                self.agent_instance.destroy()\n                self.agent_instance = None\n        except Exception as e:\n            print(\"\\n\\033[91mFailed to stop the agent:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n        if self.route_scenario:\n            self.route_scenario.remove_all_actors()\n            self.route_scenario = None\n            if self.statistics_manager:\n                self.statistics_manager.remove_scenario()\n\n        if self.manager:\n            self._client_timed_out = not self.manager.get_running_status()\n            self.manager.cleanup()\n\n        # Make sure no sensors are left streaming\n        alive_sensors = self.world.get_actors().filter('*sensor*')\n        for sensor in alive_sensors:\n            sensor.stop()\n            sensor.destroy()\n\n    def _setup_simulation(self, args):\n        \"\"\"\n        Prepares the simulation by getting the client, and setting up the world and traffic manager settings\n        \"\"\"\n        self.carla_path = os.environ[\"CARLA_ROOT\"]\n        args.port = find_free_port(args.port)\n        cmd1 = f\"{os.path.join(self.carla_path, 'CarlaUE4.sh')} -RenderOffScreen -nosound -carla-rpc-port={args.port} -graphicsadapter={args.gpu_rank}\"\n        self.server = subprocess.Popen(cmd1, shell=True, preexec_fn=os.setsid)\n        print(cmd1, self.server.returncode, flush=True)\n        atexit.register(os.killpg, self.server.pid, signal.SIGKILL)\n        time.sleep(30)\n            \n        attempts = 0\n        num_max_restarts = 20\n        while attempts < num_max_restarts:\n            try:\n                client = carla.Client(args.host, args.port)\n                if args.timeout:\n                    client_timeout = args.timeout\n                client.set_timeout(client_timeout)\n\n                settings = carla.WorldSettings(\n                    synchronous_mode = True,\n                    fixed_delta_seconds = 1.0 / self.frame_rate,\n                    deterministic_ragdolls = True,\n                    spectator_as_ego = False\n                )\n                client.get_world().apply_settings(settings)\n                print(f\"load_world success , attempts={attempts}\", flush=True)\n                break\n            except Exception as e:\n                print(f\"load_world failed , attempts={attempts}\", flush=True)\n                print(e, flush=True)\n                attempts += 1\n                time.sleep(5)\n        attempts = 0\n        num_max_restarts = 40\n        while attempts < num_max_restarts:\n            try:\n                args.traffic_manager_port = find_free_port(args.traffic_manager_port)\n                traffic_manager = client.get_trafficmanager(args.traffic_manager_port)\n                traffic_manager.set_synchronous_mode(True)\n                traffic_manager.set_hybrid_physics_mode(True)\n                print(f\"traffic_manager init success, try_time={attempts}\", flush=True)\n                break\n            except Exception as e:\n                print(f\"traffic_manager init fail, try_time={attempts}\", flush=True)\n                print(e, flush=True)\n                attempts += 1\n                time.sleep(5)\n        return client, client_timeout, traffic_manager\n\n    def _reset_world_settings(self):\n        \"\"\"\n        Changes the modified world settings back to asynchronous\n        \"\"\"\n        # Has simulation failed?\n        if self.world and self.manager and not self._client_timed_out:\n            # Reset to asynchronous mode\n            self.world.tick()  # TODO: Make sure all scenario actors have been destroyed\n            settings = self.world.get_settings()\n            settings.synchronous_mode = False\n            settings.fixed_delta_seconds = None\n            settings.deterministic_ragdolls = False\n            settings.spectator_as_ego = True\n            self.world.apply_settings(settings)\n\n            # Make the TM back to async\n            self.traffic_manager.set_synchronous_mode(False)\n            self.traffic_manager.set_hybrid_physics_mode(False)\n\n    def _load_and_wait_for_world(self, args, town):\n        \"\"\"\n        Load a new CARLA world without changing the settings and provide data to CarlaDataProvider\n        \"\"\"\n        self.world = self.client.load_world(town, reset_settings=False)\n\n        # Large Map settings are always reset, for some reason\n        settings = self.world.get_settings()\n        settings.tile_stream_distance = 650\n        settings.actor_active_distance = 650\n        self.world.apply_settings(settings)\n\n        self.world.reset_all_traffic_lights()\n        CarlaDataProvider.set_client(self.client)\n        CarlaDataProvider.set_traffic_manager_port(args.traffic_manager_port)\n        CarlaDataProvider.set_world(self.world)\n\n        # This must be here so that all route repetitions use the same 'unmodified' seed\n        self.traffic_manager.set_random_device_seed(args.traffic_manager_seed)\n\n        # Wait for the world to be ready\n        self.world.tick()\n\n        map_name = CarlaDataProvider.get_map().name.split(\"/\")[-1]\n        if map_name != town:\n            raise Exception(\"The CARLA server uses the wrong map!\"\n                            \" This scenario requires the use of map {}\".format(town))\n\n    def _register_statistics(self, route_index, entry_status, crash_message=\"\"):\n        \"\"\"\n        Computes and saves the route statistics\n        \"\"\"\n        print(\"\\033[1m> Registering the route statistics\\033[0m\", flush=True)\n        self.statistics_manager.save_entry_status(entry_status)\n        self.statistics_manager.compute_route_statistics(\n            route_index, self.manager.scenario_duration_system, self.manager.scenario_duration_game, crash_message\n        )\n\n    def _load_and_run_scenario(self, args, config):\n        \"\"\"\n        Load and run the scenario given by config.\n\n        Depending on what code fails, the simulation will either stop the route and\n        continue from the next one, or report a crash and stop.\n        \"\"\"\n        crash_message = \"\"\n        entry_status = \"Started\"\n\n        print(\"\\n\\033[1m========= Preparing {} (repetition {}) =========\\033[0m\".format(config.name, config.repetition_index), flush=True)\n\n        # Prepare the statistics of the route\n        route_name = f\"{config.name}_rep{config.repetition_index}\"\n        scenario_name = config.scenario_configs[0].name\n        town_name = str(config.town)\n        weather_id = get_weather_id(config.weather[0][1])\n        currentDateAndTime = datetime.now()\n        currentTime = currentDateAndTime.strftime(\"%m_%d_%H_%M_%S\")\n        save_name = f\"{route_name}_{town_name}_{scenario_name}_{weather_id}_{currentTime}\"\n        self.statistics_manager.create_route_data(route_name, scenario_name, weather_id, save_name, town_name, config.index)\n\n        print(\"\\033[1m> Loading the world\\033[0m\", flush=True)\n\n        # Load the world and the scenario\n        try:\n            self._load_and_wait_for_world(args, config.town)\n            self.route_scenario = RouteScenario(world=self.world, config=config, debug_mode=args.debug)\n            self.statistics_manager.set_scenario(self.route_scenario)\n\n        except Exception:\n            # The scenario is wrong -> set the ejecution to crashed and stop\n            print(\"\\n\\033[91mThe scenario could not be loaded:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Simulation\"]\n            self._register_statistics(config.index, entry_status, crash_message)\n            self._cleanup()\n            return True\n\n        print(\"\\033[1m> Setting up the agent\\033[0m\", flush=True)\n\n        # Set up the user's agent, and the timer to avoid freezing the simulation\n        try:\n            self._agent_watchdog = Watchdog(args.timeout)\n            self._agent_watchdog.start()\n            agent_class_name = getattr(self.module_agent, 'get_entry_point')()\n            agent_class_obj = getattr(self.module_agent, agent_class_name)\n\n            # Start the ROS1 bridge server only for ROS1 based agents.\n            if getattr(agent_class_obj, 'get_ros_version')() == 1 and self._ros1_server is None:\n                from leaderboard.autoagents.ros1_agent import ROS1Server\n                self._ros1_server = ROS1Server()\n                self._ros1_server.start()\n\n            self.agent_instance = agent_class_obj(args.host, args.port, args.debug)\n            self.agent_instance.set_global_plan(self.route_scenario.gps_route, self.route_scenario.route)\n            args.agent_config = args.agent_config + '+' + save_name\n            #import pdb;pdb.set_trace()\n            self.agent_instance.setup(args.agent_config)\n\n            # Check and store the sensors\n            if not self.sensors:\n                self.sensors = self.agent_instance.sensors()\n                track = self.agent_instance.track\n\n                validate_sensor_configuration(self.sensors, track, args.track)\n\n                self.sensor_icons = [sensors_to_icons[sensor['type']] for sensor in self.sensors]\n                self.statistics_manager.save_sensors(self.sensor_icons)\n                self.statistics_manager.write_statistics()\n\n                self.sensors_initialized = True\n\n            self._agent_watchdog.stop()\n            self._agent_watchdog = None\n\n        except SensorConfigurationInvalid as e:\n            # The sensors are invalid -> set the ejecution to rejected and stop\n            print(\"\\n\\033[91mThe sensor's configuration used is invalid:\", flush=True)\n            print(f\"{e}\\033[0m\\n\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Sensors\"]\n            self._register_statistics(config.index, entry_status, crash_message)\n            self._cleanup()\n            return True\n\n        except Exception as e:\n            # The agent setup has failed -> start the next route\n            print(\"\\n\\033[91mCould not set up the required agent:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n            print(f\"{e}\\033[0m\\n\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Agent_init\"]\n            self._register_statistics(config.index, entry_status, crash_message)\n            self._cleanup()\n            return True\n\n        print(\"\\033[1m> Running the route\\033[0m\", flush=True)\n\n        # Run the scenario\n        try:\n            # Load scenario and run it\n            if args.record:\n                self.client.start_recorder(\"{}/{}_rep{}.log\".format(args.record, config.name, config.repetition_index))\n            self.manager.load_scenario(self.route_scenario, self.agent_instance, config.index, config.repetition_index)\n            self.manager.tick_count = 0\n            self.manager.run_scenario()\n\n        except AgentError:\n            # The agent has failed -> stop the route\n            print(\"\\n\\033[91mStopping the route, the agent has crashed:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\")\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Agent_runtime\"]\n\n        except KeyboardInterrupt:\n            return True\n        \n        except TickRuntimeError:\n            entry_status, crash_message = \"Started\", \"TickRuntime\"\n        \n        except Exception:\n            print(\"\\n\\033[91mError during the simulation:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n            entry_status, crash_message = FAILURE_MESSAGES[\"Simulation\"]\n\n        # Stop the scenario\n        try:\n            print(\"\\033[1m> Stopping the route\\033[0m\", flush=True)\n            self.manager.stop_scenario()\n            self._register_statistics(config.index, entry_status, crash_message)\n\n            if args.record:\n                self.client.stop_recorder()\n\n            self._cleanup()\n\n        except Exception:\n            print(\"\\n\\033[91mFailed to stop the scenario, the statistics might be empty:\", flush=True)\n            print(f\"\\n{traceback.format_exc()}\\033[0m\", flush=True)\n\n            _, crash_message = FAILURE_MESSAGES[\"Simulation\"]\n\n        # If the simulation crashed, stop the leaderboard, for the rest, move to the next route\n        return crash_message == \"Simulation crashed\"\n\n    def run(self, args):\n        \"\"\"\n        Run the challenge mode\n        \"\"\"\n        route_indexer = RouteIndexer(args.routes, args.repetitions, args.routes_subset)\n\n        #args.resume = True\n        if args.resume:\n            resume = route_indexer.validate_and_resume(args.checkpoint)\n        else:\n            resume = False\n\n        if resume:\n            self.statistics_manager.add_file_records(args.checkpoint)\n        else:\n            self.statistics_manager.clear_records()\n        self.statistics_manager.save_progress(route_indexer.index, route_indexer.total)\n        self.statistics_manager.write_statistics()\n\n        crashed = False\n        t1 = time.time()\n        while route_indexer.peek() and not crashed:\n\n            # Run the scenario\n            config = route_indexer.get_next_config()\n            crashed = self._load_and_run_scenario(args, config)\n            print(crashed, flush=True)\n            # Save the progress and write the route statistics\n            self.statistics_manager.save_progress(route_indexer.index, route_indexer.total)\n            self.statistics_manager.write_statistics()\n            if crashed:\n                print(f'{route_indexer.index} crash, [{route_indexer.index}/{route_indexer.total}], please restart', flush=True)\n                break\n\n        # Shutdown ROS1 bridge server if necessary\n        if self._ros1_server is not None:\n            self._ros1_server.shutdown()\n\n        # Go back to asynchronous mode\n        self._reset_world_settings()\n\n        if not crashed:\n            # Save global statistics\n            print(f\"cost time={time.time()-t1}\", flush=True)\n            print(\"\\033[1m> Registering the global statistics\\033[0m\", flush=True)\n            self.statistics_manager.compute_global_statistics()\n            self.statistics_manager.validate_and_write_statistics(self.sensors_initialized, crashed)\n        \n        if crashed:\n            cmd2 = \"ps -ef | grep '-graphicsadapter=\"+ str(args.gpu_rank) + \"' | grep -v grep | awk '{print $2}' | xargs -r kill -9\"\n            server = subprocess.Popen(cmd2, shell=True, preexec_fn=os.setsid)\n            atexit.register(os.killpg, server.pid, signal.SIGKILL)\n\n        return crashed\n\ndef main():\n    description = \"CARLA AD Leaderboard Evaluation: evaluate your Agent in CARLA scenarios\\n\"\n\n    # general parameters\n    parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter)\n    parser.add_argument('--host', default='localhost',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', default=2000, type=int,\n                        help='TCP port to listen to (default: 2000)')\n    parser.add_argument('--traffic-manager-port', default=8000, type=int,\n                        help='Port to use for the TrafficManager (default: 8000)')\n    parser.add_argument('--traffic-manager-seed', default=0, type=int,\n                        help='Seed used by the TrafficManager (default: 0)')\n    parser.add_argument('--debug', type=int,\n                        help='Run with debug output', default=0)\n    parser.add_argument('--record', type=str, default='',\n                        help='Use CARLA recording feature to create a recording of the scenario')\n    parser.add_argument('--timeout', default=600.0, type=float,\n                        help='Set the CARLA client timeout value in seconds')\n\n    # simulation setup\n    parser.add_argument('--routes', required=True,\n                        help='Name of the routes file to be executed.')\n    parser.add_argument('--routes-subset', default='', type=str,\n                        help='Execute a specific set of routes')\n    parser.add_argument('--repetitions', type=int, default=1,\n                        help='Number of repetitions per route.')\n\n    # agent-related options\n    parser.add_argument(\"-a\", \"--agent\", type=str,\n                        help=\"Path to Agent's py file to evaluate\", required=True)\n    parser.add_argument(\"--agent-config\", type=str,\n                        help=\"Path to Agent's configuration file\", default=\"\")\n\n    parser.add_argument(\"--track\", type=str, default='SENSORS',\n                        help=\"Participation track: SENSORS, MAP\")\n    parser.add_argument('--resume', type=bool, default=False,\n                        help='Resume execution from last checkpoint?')\n    parser.add_argument(\"--checkpoint\", type=str, default='./simulation_results.json',\n                        help=\"Path to checkpoint used for saving statistics and resuming\")\n    parser.add_argument(\"--debug-checkpoint\", type=str, default='./live_results.txt',\n                        help=\"Path to checkpoint used for saving live results\")\n    parser.add_argument(\"--gpu-rank\", type=int, default=0)\n    arguments = parser.parse_args()\n\n    statistics_manager = StatisticsManager(arguments.checkpoint, arguments.debug_checkpoint)\n    leaderboard_evaluator = LeaderboardEvaluator(arguments, statistics_manager)\n    crashed = leaderboard_evaluator.run(arguments)\n\n    del leaderboard_evaluator\n\n    if crashed:\n        sys.exit(-1)\n    else:\n        sys.exit(0)\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/scenarios/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/scenarios/route_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides Challenge routes as standalone scenarios\n\"\"\"\n\nfrom __future__ import print_function\n\nimport glob\nimport os\nimport sys\nimport importlib\nimport inspect\nimport py_trees\nimport traceback\nimport numpy as np\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ScenarioTriggerer, Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitForBlackboardVariable\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest,\n                                                                     InRouteTest,\n                                                                     RouteCompletionTest,\n                                                                     OutsideRouteLanesTest,\n                                                                     RunningRedLightTest,\n                                                                     RunningStopTest,\n                                                                     ActorBlockedTest,\n                                                                     MinimumSpeedRouteTest)\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.scenarios.background_activity import BackgroundBehavior\nfrom srunner.scenariomanager.weather_sim import RouteWeatherBehavior\nfrom srunner.scenariomanager.lights_sim import RouteLightsBehavior\nfrom srunner.scenariomanager.timer import RouteTimeoutBehavior\n\nfrom leaderboard.utils.route_parser import RouteParser, DIST_THRESHOLD\nfrom leaderboard.utils.route_manipulation import interpolate_trajectory\n\nimport leaderboard.utils.parked_vehicles as parked_vehicles\n\n\nclass RouteScenario(BasicScenario):\n\n    \"\"\"\n    Implementation of a RouteScenario, i.e. a scenario that consists of driving along a pre-defined route,\n    along which several smaller scenarios are triggered\n    \"\"\"\n\n    category = \"RouteScenario\"\n    INIT_THRESHOLD = 500 # Runtime initialization trigger distance to ego (m)\n    PARKED_VEHICLES_INIT_THRESHOLD = INIT_THRESHOLD - 50 # Runtime initialization trigger distance to parked vehicles (m)\n\n    def __init__(self, world, config, debug_mode=0, criteria_enable=True):\n        \"\"\"\n        Setup all relevant parameters and create scenarios along route\n        \"\"\"\n        self.client = CarlaDataProvider.get_client()\n        self.config = config\n        self.route = self._get_route(config)\n        self.world = world\n        self.map = CarlaDataProvider.get_map()\n        self.timeout = 10000\n\n        self.all_scenario_classes = None\n        self.ego_data = None\n\n        self.scenario_triggerer = None\n        self.behavior_node = None # behavior node created by _create_behavior()\n        self.criteria_node = None # criteria node created by _create_test_criteria()\n\n        self.list_scenarios = []\n        self.occupied_parking_locations = []\n        self.available_parking_locations = []\n\n        scenario_configurations = self._filter_scenarios(config.scenario_configs)\n        self.scenario_configurations = scenario_configurations\n        self.missing_scenario_configurations = scenario_configurations.copy()\n\n        ego_vehicle = self._spawn_ego_vehicle()\n        if ego_vehicle is None:\n            raise ValueError(\"Shutting down, couldn't spawn the ego vehicle\")\n\n        if debug_mode>0:\n            self._draw_waypoints(self.route, vertical_shift=0.1, size=0.1, downsample=10)\n\n        self._parked_ids = []\n        self._get_parking_slots()\n\n        super(RouteScenario, self).__init__(\n            config.name, [ego_vehicle], config, world, debug_mode > 3, False, criteria_enable\n        )\n\n        # Do it after the 'super', as we need the behavior and criteria tree to be initialized\n        self.build_scenarios(ego_vehicle, debug=debug_mode > 0)\n\n        # Set runtime init mode. Do this after the first set of scenarios has been initialized!\n        CarlaDataProvider.set_runtime_init_mode(True)\n\n    def _get_route(self, config):\n        \"\"\"\n        Gets the route from the configuration, interpolating it to the desired density,\n        saving it to the CarlaDataProvider and sending it to the agent\n\n        Parameters:\n        - world: CARLA world\n        - config: Scenario configuration (RouteConfiguration)\n        - debug_mode: boolean to decide whether or not the route poitns are printed\n        \"\"\"\n\n        # Prepare route's trajectory (interpolate and add the GPS route)\n        self.gps_route, self.route = interpolate_trajectory(config.keypoints)\n        return self.route\n\n    def _filter_scenarios(self, scenario_configs):\n        \"\"\"\n        Given a list of scenarios, filters out does that don't make sense to be triggered,\n        as they are either too far from the route or don't fit with the route shape\n\n        Parameters:\n        - scenario_configs: list of ScenarioConfiguration\n        \"\"\"\n        new_scenarios_config = []\n        for scenario_number, scenario_config in enumerate(scenario_configs):\n            trigger_point = scenario_config.trigger_points[0]\n            if not RouteParser.is_scenario_at_route(trigger_point, self.route):\n                print(\"WARNING: Ignoring scenario '{}' as it is too far from the route\".format(scenario_config.name))\n                continue\n\n            scenario_config.route_var_name = \"ScenarioRouteNumber{}\".format(scenario_number)\n            new_scenarios_config.append(scenario_config)\n\n        return new_scenarios_config\n\n    def _spawn_ego_vehicle(self):\n        \"\"\"Spawn the ego vehicle at the first waypoint of the route\"\"\"\n        elevate_transform = self.route[0][0]\n        elevate_transform.location.z += 0.5\n\n        ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz_2020',\n                                                          elevate_transform,\n                                                          rolename='hero')\n        if not ego_vehicle:\n            return\n\n        spectator = self.world.get_spectator()\n        spectator.set_transform(carla.Transform(elevate_transform.location + carla.Location(z=50),\n                                                    carla.Rotation(pitch=-90)))\n\n        self.world.tick()\n\n        return ego_vehicle\n\n    def _get_parking_slots(self, max_distance=100, route_step=10):\n        \"\"\"Spawn parked vehicles.\"\"\"\n\n        def is_close(slot_location):\n            for i in range(0, len(self.route), route_step):\n                route_transform = self.route[i][0]\n                if route_transform.location.distance(slot_location) < max_distance:\n                    return True\n            return False\n\n        min_x, min_y = float('inf'), float('inf')\n        max_x, max_y = float('-inf'), float('-inf')\n        for route_transform, _ in self.route:\n            min_x = min(min_x, route_transform.location.x - max_distance)\n            min_y = min(min_y, route_transform.location.y - max_distance)\n            max_x = max(max_x, route_transform.location.x + max_distance)\n            max_y = max(max_y, route_transform.location.y + max_distance)\n\n        # Occupied parking locations\n        occupied_parking_locations = []\n        for scenario in self.list_scenarios:\n            occupied_parking_locations.extend(scenario.get_parking_slots())\n\n        available_parking_locations = []\n        map_name = self.map.name.split('/')[-1]\n        available_parking_locations = getattr(parked_vehicles, map_name, [])\n\n        # Exclude parking slots that are too far from the route\n        for slot in available_parking_locations:\n            slot_transform = carla.Transform(\n                location=carla.Location(slot[\"location\"][0], slot[\"location\"][1], slot[\"location\"][2]),\n                rotation=carla.Rotation(slot[\"rotation\"][0], slot[\"rotation\"][1], slot[\"rotation\"][2])\n            )\n\n            in_area = (min_x < slot_transform.location.x < max_x) and (min_y < slot_transform.location.y < max_y)\n            close_to_route = is_close(slot_transform.location)\n            if not in_area or not close_to_route:\n                available_parking_locations.remove(slot)\n                continue\n\n        self.available_parking_locations = available_parking_locations\n\n    def spawn_parked_vehicles(self, ego_vehicle, max_scenario_distance=10):\n        \"\"\"Spawn parked vehicles.\"\"\"\n        def is_close(slot_location, ego_location):\n            return slot_location.distance(ego_location) < self.PARKED_VEHICLES_INIT_THRESHOLD\n        def is_free(slot_location):\n            for occupied_slot in self.occupied_parking_locations:\n                if slot_location.distance(occupied_slot) < max_scenario_distance:\n                    return False\n            return True\n\n        new_parked_vehicles = []\n\n        ego_location = CarlaDataProvider.get_location(ego_vehicle)\n        if ego_location is None:\n            return\n\n        for slot in self.available_parking_locations:\n            slot_transform = carla.Transform(\n                location=carla.Location(slot[\"location\"][0], slot[\"location\"][1], slot[\"location\"][2]),\n                rotation=carla.Rotation(slot[\"rotation\"][0], slot[\"rotation\"][1], slot[\"rotation\"][2])\n            )\n\n            # Add all vehicles that are close to the ego and in a free space\n            if is_close(slot_transform.location, ego_location) and is_free(slot_transform.location):\n                mesh_bp = CarlaDataProvider.get_world().get_blueprint_library().filter(\"static.prop.mesh\")[0]\n                mesh_bp.set_attribute(\"mesh_path\", slot[\"mesh\"])\n                mesh_bp.set_attribute(\"scale\", \"0.9\")\n                new_parked_vehicles.append(carla.command.SpawnActor(mesh_bp, slot_transform))\n                self.available_parking_locations.remove(slot)\n\n        # Add the actors to _parked_ids\n        for response in CarlaDataProvider.get_client().apply_batch_sync(new_parked_vehicles):\n            if not response.error:\n                self._parked_ids.append(response.actor_id)\n\n    # pylint: disable=no-self-use\n    def _draw_waypoints(self, waypoints, vertical_shift, size, downsample=1):\n        \"\"\"\n        Draw a list of waypoints at a certain height given in vertical_shift.\n        \"\"\"\n        for i, w in enumerate(waypoints):\n            if i % downsample != 0:\n                continue\n\n            wp = w[0].location + carla.Location(z=vertical_shift)\n\n            if w[1] == RoadOption.LEFT:  # Yellow\n                color = carla.Color(128, 128, 0)\n            elif w[1] == RoadOption.RIGHT:  # Cyan\n                color = carla.Color(0, 128, 128)\n            elif w[1] == RoadOption.CHANGELANELEFT:  # Orange\n                color = carla.Color(128, 32, 0)\n            elif w[1] == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n                color = carla.Color(0, 32, 128)\n            elif w[1] == RoadOption.STRAIGHT:  # Gray\n                color = carla.Color(64, 64, 64)\n            else:  # LANEFOLLOW\n                color = carla.Color(0, 128, 0)  # Green\n\n            self.world.debug.draw_point(wp, size=size, color=color, life_time=self.timeout)\n\n        self.world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=2*size,\n                                    color=carla.Color(0, 0, 128), life_time=self.timeout)\n        self.world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=2*size,\n                                    color=carla.Color(128, 128, 128), life_time=self.timeout)\n\n    def get_all_scenario_classes(self):\n        \"\"\"\n        Searches through the 'scenarios' folder for all the Python classes\n        \"\"\"\n        # Path of all scenario at \"srunner/scenarios\" folder\n        scenarios_list = glob.glob(\"{}/srunner/scenarios/*.py\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n\n        all_scenario_classes = {}\n\n        for scenario_file in scenarios_list:\n\n            # Get their module\n            module_name = os.path.basename(scenario_file).split('.')[0]\n            sys.path.insert(0, os.path.dirname(scenario_file))\n            scenario_module = importlib.import_module(module_name)\n\n            # And their members of type class\n            for member in inspect.getmembers(scenario_module, inspect.isclass):\n                # TODO: Filter out any class that isn't a child of BasicScenario\n                all_scenario_classes[member[0]] = member[1]\n\n        return all_scenario_classes\n\n    def build_scenarios(self, ego_vehicle, debug=False):\n        \"\"\"\n        Initializes the class of all the scenarios that will be present in the route.\n        If a class fails to be initialized, a warning is printed but the route execution isn't stopped\n        \"\"\"\n        new_scenarios = []\n\n        if self.all_scenario_classes is None:\n            self.all_scenario_classes = self.get_all_scenario_classes()\n        if self.ego_data is None:\n            self.ego_data = ActorConfigurationData(ego_vehicle.type_id, ego_vehicle.get_transform(), 'hero')\n\n        # Part 1. Check all scenarios that haven't been initialized, starting them if close enough to the ego vehicle\n        for scenario_config in self.missing_scenario_configurations:\n            scenario_config.ego_vehicles = [self.ego_data]\n            scenario_config.route = self.route\n\n            try:\n                scenario_class = self.all_scenario_classes[scenario_config.type]\n                trigger_location = scenario_config.trigger_points[0].location\n\n                ego_location = CarlaDataProvider.get_location(ego_vehicle)\n                if ego_location is None:\n                    continue\n\n                # Only init scenarios that are close to ego\n                if trigger_location.distance(ego_location) < self.INIT_THRESHOLD:\n                    scenario_instance = scenario_class(self.world, [ego_vehicle], scenario_config, timeout=self.timeout)\n\n                    # Add new scenarios to list\n                    self.list_scenarios.append(scenario_instance)\n                    new_scenarios.append(scenario_instance)\n                    self.missing_scenario_configurations.remove(scenario_config)\n\n                    self.occupied_parking_locations.extend(scenario_instance.get_parking_slots())\n\n                    if debug:\n                        scenario_loc = scenario_config.trigger_points[0].location\n                        debug_loc = self.map.get_waypoint(scenario_loc).transform.location + carla.Location(z=0.2)\n                        self.world.debug.draw_point(\n                            debug_loc, size=0.2, color=carla.Color(128, 0, 0), life_time=self.timeout\n                        )\n                        self.world.debug.draw_string(\n                            debug_loc, str(scenario_config.name), draw_shadow=False,\n                            color=carla.Color(0, 0, 128), life_time=self.timeout, persistent_lines=True\n                        )\n\n            except Exception as e:\n                print(f\"\\033[93mSkipping scenario '{scenario_config.name}' due to setup error: {e}\")\n                if debug:\n                    print(f\"\\n{traceback.format_exc()}\")\n                print(\"\\033[0m\", end=\"\")\n                self.missing_scenario_configurations.remove(scenario_config)\n                continue\n\n        # Part 2. Add their behavior onto the route's behavior tree\n        for scenario in new_scenarios:\n\n            # Add behavior\n            if scenario.behavior_tree is not None:\n                self.behavior_node.add_child(scenario.behavior_tree)\n                self.scenario_triggerer.add_blackboard(\n                    [scenario.config.route_var_name, scenario.config.trigger_points[0].location]\n                )\n\n            # Add the criteria criteria\n            scenario_criteria = scenario.get_criteria()\n            if len(scenario_criteria) == 0:\n                continue\n\n            self.criteria_node.add_child(\n                self._create_criterion_tree(scenario, scenario_criteria)\n            )\n\n    # pylint: enable=no-self-use\n    def _initialize_actors(self, config):\n        \"\"\"\n        Set other_actors to the superset of all scenario actors\n        \"\"\"\n        # Add all the actors of the specific scenarios to self.other_actors\n        for scenario in self.list_scenarios:\n            self.other_actors.extend(scenario.other_actors)\n\n    def _create_behavior(self):\n        \"\"\"\n        Creates a parallel behavior that runs all of the scenarios part of the route.\n        These subbehaviors have had a trigger condition added so that they wait until\n        the agent is close to their trigger point before activating.\n\n        It also adds the BackgroundActivity scenario, which will be active throughout the whole route.\n        This behavior never ends and the end condition is given by the RouteCompletionTest criterion.\n        \"\"\"\n        scenario_trigger_distance = DIST_THRESHOLD  # Max trigger distance between route and scenario\n\n        behavior = py_trees.composites.Parallel(name=\"Route Behavior\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n\n        self.behavior_node = behavior\n        scenario_behaviors = []\n        blackboard_list = []\n\n        # Add the behavior that manages the scenario trigger conditions\n        scenario_triggerer = ScenarioTriggerer(\n            self.ego_vehicles[0], self.route, blackboard_list, scenario_trigger_distance)\n        behavior.add_child(scenario_triggerer)  # Tick the ScenarioTriggerer before the scenarios\n\n        # register var\n        self.scenario_triggerer = scenario_triggerer\n\n        # Add the Background Activity\n        behavior.add_child(BackgroundBehavior(self.ego_vehicles[0], self.route, name=\"BackgroundActivity\"))\n\n        behavior.add_children(scenario_behaviors)\n        return behavior\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Create the criteria tree. It starts with some route criteria (which are always active),\n        and adds the scenario specific ones, which will only be active during their scenario\n        \"\"\"\n        criteria = py_trees.composites.Parallel(name=\"Criteria\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        self.criteria_node = criteria\n\n        # End condition\n        criteria.add_child(RouteCompletionTest(self.ego_vehicles[0], route=self.route))\n\n        # 'Normal' criteria\n        criteria.add_child(OutsideRouteLanesTest(self.ego_vehicles[0], route=self.route))\n        criteria.add_child(CollisionTest(self.ego_vehicles[0], name=\"CollisionTest\"))\n        criteria.add_child(RunningRedLightTest(self.ego_vehicles[0]))\n        criteria.add_child(RunningStopTest(self.ego_vehicles[0]))\n        criteria.add_child(MinimumSpeedRouteTest(self.ego_vehicles[0], self.route, checkpoints=20, name=\"MinSpeedTest\"))\n\n        # These stop the route early to save computational time\n        criteria.add_child(InRouteTest(\n            self.ego_vehicles[0], route=self.route, offroad_max=30, terminate_on_failure=True))\n        criteria.add_child(ActorBlockedTest(\n            self.ego_vehicles[0], min_speed=0.1, max_time=60.0, terminate_on_failure=True, name=\"AgentBlockedTest\")\n        )\n\n        return criteria\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Create the weather behavior\n        \"\"\"\n        if len(self.config.weather) == 1:\n            return  # Just set the weather at the beginning and done\n        return RouteWeatherBehavior(self.ego_vehicles[0], self.route, self.config.weather)\n\n    def _create_lights_behavior(self):\n        \"\"\"\n        Create the street lights behavior\n        \"\"\"\n        return RouteLightsBehavior(self.ego_vehicles[0], 100)\n\n    def _create_timeout_behavior(self):\n        \"\"\"\n        Create the timeout behavior\n        \"\"\"\n        return RouteTimeoutBehavior(self.ego_vehicles[0], self.route)\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Set the weather\n        \"\"\"\n        # Set the appropriate weather conditions\n        world.set_weather(self.config.weather[0][1])\n\n    def _create_criterion_tree(self, scenario, criteria):\n        \"\"\"\n        We can make use of the blackboard variables used by the behaviors themselves,\n        as we already have an atomic that handles their (de)activation.\n        The criteria will wait until that variable is active (the scenario has started),\n        and will automatically stop when it deactivates (as the scenario has finished)\n        \"\"\"\n        scenario_name = scenario.name\n        var_name = scenario.config.route_var_name\n        check_name = \"WaitForBlackboardVariable: {}\".format(var_name)\n\n        criteria_tree = py_trees.composites.Sequence(name=scenario_name)\n        criteria_tree.add_child(WaitForBlackboardVariable(var_name, True, False, name=check_name))\n\n        scenario_criteria = py_trees.composites.Parallel(name=scenario_name,\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        for criterion in criteria:\n            scenario_criteria.add_child(criterion)\n        scenario_criteria.add_child(WaitForBlackboardVariable(var_name, False, None, name=check_name))\n\n        criteria_tree.add_child(scenario_criteria)\n        criteria_tree.add_child(Idle())  # Avoid the indiviual criteria stopping the simulation\n        return criteria_tree\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.client.apply_batch([carla.command.DestroyActor(x) for x in self._parked_ids])\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/scenarios/scenario_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the ScenarioManager implementations.\nIt must not be modified and is for reference only!\n\"\"\"\n\nfrom __future__ import print_function\nimport signal\nimport sys\nimport time\n\nimport py_trees\nimport carla\nimport threading\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.watchdog import Watchdog\n\nfrom leaderboard.autoagents.agent_wrapper import AgentWrapperFactory, AgentError, TickRuntimeError\nfrom leaderboard.envs.sensor_interface import SensorReceivedNoData\nfrom leaderboard.utils.result_writer import ResultOutputProvider\n\n\nclass ScenarioManager(object):\n\n    \"\"\"\n    Basic scenario manager class. This class holds all functionality\n    required to start, run and stop a scenario.\n\n    The user must not modify this class.\n\n    To use the ScenarioManager:\n    1. Create an object via manager = ScenarioManager()\n    2. Load a scenario via manager.load_scenario()\n    3. Trigger the execution of the scenario manager.run_scenario()\n       This function is designed to explicitly control start and end of\n       the scenario execution\n    4. If needed, cleanup with manager.stop_scenario()\n    \"\"\"\n\n    def __init__(self, timeout, statistics_manager, debug_mode=0):\n        \"\"\"\n        Setups up the parameters, which will be filled at load_scenario()\n        \"\"\"\n        self.route_index = None\n        self.scenario = None\n        self.scenario_tree = None\n        self.ego_vehicles = None\n        self.other_actors = None\n\n        self._debug_mode = debug_mode\n        self._agent_wrapper = None\n        self._running = False\n        self._timestamp_last_run = 0.0\n        self._timeout = float(timeout)\n\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = 0.0\n        self.start_game_time = 0.0\n        self.end_system_time = 0.0\n        self.end_game_time = 0.0\n\n        self._watchdog = None\n        self._agent_watchdog = None\n        self._scenario_thread = None\n\n        self._statistics_manager = statistics_manager\n\n        self.tick_count = 0\n\n        # Use the callback_id inside the signal handler to allow external interrupts\n        signal.signal(signal.SIGINT, self.signal_handler)\n\n    def signal_handler(self, signum, frame):\n        \"\"\"\n        Terminate scenario ticking when receiving a signal interrupt\n        \"\"\"\n        if self._agent_watchdog and not self._agent_watchdog.get_status():\n            raise RuntimeError(\"Agent took longer than {}s to send its command\".format(self._timeout))\n        elif self._watchdog and not self._watchdog.get_status():\n            raise RuntimeError(\"The simulation took longer than {}s to update\".format(self._timeout))\n        self._running = False\n\n    def cleanup(self):\n        \"\"\"\n        Reset all parameters\n        \"\"\"\n        self._timestamp_last_run = 0.0\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = 0.0\n        self.start_game_time = 0.0\n        self.end_system_time = 0.0\n        self.end_game_time = 0.0\n\n        self._spectator = None\n        self._watchdog = None\n        self._agent_watchdog = None\n\n    def load_scenario(self, scenario, agent, route_index, rep_number):\n        \"\"\"\n        Load a new scenario\n        \"\"\"\n\n        GameTime.restart()\n        self._agent_wrapper = AgentWrapperFactory.get_wrapper(agent)\n        self.route_index = route_index\n        self.scenario = scenario\n        self.scenario_tree = scenario.scenario_tree\n        self.ego_vehicles = scenario.ego_vehicles\n        self.other_actors = scenario.other_actors\n        self.repetition_number = rep_number\n\n        self._spectator = CarlaDataProvider.get_world().get_spectator()\n\n        # To print the scenario tree uncomment the next line\n        # py_trees.display.render_dot_tree(self.scenario_tree)\n\n        self._agent_wrapper.setup_sensors(self.ego_vehicles[0])\n\n    def build_scenarios_loop(self, debug):\n        \"\"\"\n        Keep periodically trying to start the scenarios that are close to the ego vehicle\n        Additionally, do the same for the spawned vehicles\n        \"\"\"\n        while self._running:\n            self.scenario.build_scenarios(self.ego_vehicles[0], debug=debug)\n            self.scenario.spawn_parked_vehicles(self.ego_vehicles[0])\n            time.sleep(1)\n\n    def run_scenario(self):\n        \"\"\"\n        Trigger the start of the scenario and wait for it to finish/fail\n        \"\"\"\n        self.start_system_time = time.time()\n        self.start_game_time = GameTime.get_time()\n\n        # Detects if the simulation is down\n        self._watchdog = Watchdog(self._timeout)\n        self._watchdog.start()\n\n        # Stop the agent from freezing the simulation\n        self._agent_watchdog = Watchdog(self._timeout)\n        self._agent_watchdog.start()\n\n        self._running = True\n\n        # Thread for build_scenarios\n        self._scenario_thread = threading.Thread(target=self.build_scenarios_loop, args=(self._debug_mode > 0, ))\n        self._scenario_thread.start()\n\n        while self._running:\n            self._tick_scenario()\n\n    def _tick_scenario(self):\n        \"\"\"\n        Run next tick of scenario and the agent and tick the world.\n        \"\"\"\n        if self._running and self.get_running_status():\n            CarlaDataProvider.get_world().tick(self._timeout)\n\n        timestamp = CarlaDataProvider.get_world().get_snapshot().timestamp\n\n        if self._timestamp_last_run < timestamp.elapsed_seconds and self._running:\n            self._timestamp_last_run = timestamp.elapsed_seconds\n\n            self._watchdog.update()\n            # Update game time and actor information\n            GameTime.on_carla_tick(timestamp)\n            CarlaDataProvider.on_carla_tick()\n            self.tick_count += 1\n            self._watchdog.pause()\n\n            if self.tick_count > 4000:\n                raise TickRuntimeError(\"RuntimeError, tick_count > 4000\")\n\n            try:\n                self._agent_watchdog.resume()\n                self._agent_watchdog.update()\n                ego_action = self._agent_wrapper()\n                self._agent_watchdog.pause()\n\n            # Special exception inside the agent that isn't caused by the agent\n            except SensorReceivedNoData as e:\n                raise RuntimeError(e)\n\n            except Exception as e:\n                raise AgentError(e)\n\n            self._watchdog.resume()\n            self.ego_vehicles[0].apply_control(ego_action)\n\n            # Tick scenario. Add the ego control to the blackboard in case some behaviors want to change it\n            py_trees.blackboard.Blackboard().set(\"AV_control\", ego_action, overwrite=True)\n            self.scenario_tree.tick_once()\n\n            if self._debug_mode > 1:\n                self.compute_duration_time()\n\n                # Update live statistics\n                self._statistics_manager.compute_route_statistics(\n                    self.route_index,\n                    self.scenario_duration_system,\n                    self.scenario_duration_game,\n                    failure_message=\"\"\n                )\n                self._statistics_manager.write_live_results(\n                    self.route_index,\n                    self.ego_vehicles[0].get_velocity().length(),\n                    ego_action,\n                    self.ego_vehicles[0].get_location()\n                )\n\n            if self._debug_mode > 2:\n                print(\"\\n\")\n                py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True)\n                sys.stdout.flush()\n\n            if self.scenario_tree.status != py_trees.common.Status.RUNNING:\n                self._running = False\n\n            ego_trans = self.ego_vehicles[0].get_transform()\n            self._spectator.set_transform(carla.Transform(ego_trans.location + carla.Location(z=70),\n                                                          carla.Rotation(pitch=-90)))\n\n    def get_running_status(self):\n        \"\"\"\n        returns:\n           bool: False if watchdog exception occured, True otherwise\n        \"\"\"\n        if self._watchdog:\n            return self._watchdog.get_status()\n        return True\n\n    def stop_scenario(self):\n        \"\"\"\n        This function triggers a proper termination of a scenario\n        \"\"\"\n        if self._watchdog:\n            self._watchdog.stop()\n\n        if self._agent_watchdog:\n            self._agent_watchdog.stop()\n\n        self.compute_duration_time()\n\n        if self.get_running_status():\n            if self.scenario is not None:\n                self.scenario.terminate()\n\n            if self._agent_wrapper is not None:\n                self._agent_wrapper.cleanup()\n                self._agent_wrapper = None\n\n            self.analyze_scenario()\n\n        # Make sure the scenario thread finishes to avoid blocks\n        self._running = False\n        self._scenario_thread.join()\n        self._scenario_thread = None\n\n    def compute_duration_time(self):\n        \"\"\"\n        Computes system and game duration times\n        \"\"\"\n        self.end_system_time = time.time()\n        self.end_game_time = GameTime.get_time()\n\n        self.scenario_duration_system = self.end_system_time - self.start_system_time\n        self.scenario_duration_game = self.end_game_time - self.start_game_time\n\n    def analyze_scenario(self):\n        \"\"\"\n        Analyzes and prints the results of the route\n        \"\"\"\n        ResultOutputProvider(self)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/checkpoint_tools.py",
    "content": "import json\ntry:\n    import simplejson as json\nexcept ImportError:\n    import json\nimport requests\nimport os.path\n\n\ndef autodetect_proxy():\n    proxies = {}\n\n    proxy_https = os.getenv('HTTPS_PROXY', os.getenv('https_proxy', None))\n    proxy_http = os.getenv('HTTP_PROXY', os.getenv('http_proxy', None))\n\n    if proxy_https:\n        proxies['https'] = proxy_https\n    if proxy_http:\n        proxies['http'] = proxy_http\n\n    return proxies\n\n\ndef fetch_dict(endpoint):\n    data = None\n    if endpoint.startswith(('http:', 'https:', 'ftp:')):\n        proxies = autodetect_proxy()\n\n        if proxies:\n            response = requests.get(url=endpoint, proxies=proxies)\n        else:\n            response = requests.get(url=endpoint)\n\n        try:\n            data = response.json()\n        except json.decoder.JSONDecodeError:\n            data = {}\n    else:\n        data = {}\n        if os.path.exists(endpoint):\n            with open(endpoint) as fd:\n                try:\n                    data = json.load(fd)\n                except json.JSONDecodeError:\n                    data = {}\n\n    return data\n\n\ndef save_dict(endpoint, data):\n    if endpoint.startswith(('http:', 'https:', 'ftp:')):\n        proxies = autodetect_proxy()\n\n        if proxies:\n            _ = requests.patch(url=endpoint, headers={'content-type':'application/json'}, data=json.dumps(data, indent=4, sort_keys=True), proxies=proxies)\n        else:\n            _ = requests.patch(url=endpoint, headers={'content-type':'application/json'}, data=json.dumps(data, indent=4, sort_keys=True))\n    else:\n        with open(endpoint, 'w') as fd:\n            json.dump(data, fd, indent=4)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/parked_vehicles.py",
    "content": "Town12 = [\n {'tilex':2, 'tiley':1, 'location':(-602.3104296900001, 4002.51804688, 371.64960937999996), 'rotation':(-0.598236, -89.864105, -0.61084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.3477734400001, 4018.99757812, 371.80917969), 'rotation':(-0.538605, -89.86499, -0.548798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.36023438, 4024.49070312, 371.85746094), 'rotation':(-0.508789, -89.86554, -0.517883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.3851171900001, 4035.47828125, 371.94628905999997), 'rotation':(-0.448853, -89.866547, -0.455933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.39746094, 4040.97117188, 371.98671875), 'rotation':(-0.418762, -89.866455, -0.424927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.40996094, 4046.46460938, 372.02476562000004), 'rotation':(-0.388916, -89.867432, -0.394226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.42242188, 4051.95796875, 372.06074219000004), 'rotation':(-0.374969, -89.86673, -0.379883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.43492188, 4057.45140625, 372.09535156), 'rotation':(-0.361298, -89.867737, -0.365845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.4473437500001, 4062.94601562, 372.12757812), 'rotation':(-0.336487, -89.868042, -0.340454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.4597656200001, 4068.43921875, 372.15816406), 'rotation':(-0.311218, -89.868347, -0.314606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.53230469, 4100.39546875, 372.30773437999994), 'rotation':(-0.234192, -89.868958, -0.236115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.5446093799999, 4105.83835938, 372.3290625), 'rotation':(-0.234192, -89.868958, -0.236115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.56925781, 4116.7265625, 372.3678125), 'rotation':(-0.192841, -89.869263, -0.194153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.5939843799999, 4127.61375, 372.40175781), 'rotation':(-0.172272, -89.869385, -0.173309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.61871094, 4138.50242188, 372.43351562000004), 'rotation':(-0.166718, -89.869019, -0.167664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-602.63109375, 4143.94679688, 372.45039062), 'rotation':(-0.176178, -89.869537, -0.177277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.6434375, 4149.39109375, 372.468125), 'rotation':(-0.185699, -89.869476, -0.18689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.66820312, 4160.27976562, 372.50605469000004), 'rotation':(-0.204681, -89.868744, -0.206146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.68058594, 4165.72414062, 372.52632812), 'rotation':(-0.213593, -89.869263, -0.215179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-602.7053125, 4176.6128125, 372.56925780999995), 'rotation':(-0.232849, -89.869141, -0.234741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.86527344, 4100.43210938, 372.56164062000005), 'rotation':(-0.766205, -90.242493, -0.786896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.76597655999996, 4122.91648438, 372.83417969000004), 'rotation':(-0.676758, -90.244751, -0.692871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-494.71632812, 4134.1596875, 372.95371094), 'rotation':(-0.609192, -90.246124, -0.622223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-494.69152344, 4139.7803125, 373.01101562), 'rotation':(-0.588867, -90.246857, -0.601044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.64183594, 4151.02390625, 373.11710938), 'rotation':(-0.548126, -90.247498, -0.558685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.61703125, 4156.64648438, 373.16691405999995), 'rotation':(-0.507202, -90.24823, -0.516235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.59226562000003, 4162.26757812, 373.21421875), 'rotation':(-0.507202, -90.24823, -0.516235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.54257812000003, 4173.51171875, 373.30402344000004), 'rotation':(-0.445892, -90.249359, -0.452881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-494.51773438, 4179.13429688, 373.34773437999996), 'rotation':(-0.445892, -90.249359, -0.452881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.29738281, 4002.536875, 370.85113280999997), 'rotation':(-1.25235, -90.224182, -1.308044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-495.27335938, 4007.9856250000003, 370.96808594000004), 'rotation':(-1.237549, -90.226135, -1.291901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.22523437999996, 4018.8828125, 371.19429687999997), 'rotation':(-1.182648, -90.228149, -1.232269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.20121094, 4024.3315625, 371.30359375), 'rotation':(-1.155334, -90.229584, -1.202667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.17714844, 4029.78054688, 371.41035156), 'rotation':(-1.12796, -90.230682, -1.173065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.1290625, 4040.67820312, 371.61613280999995), 'rotation':(-1.073029, -90.232788, -1.113831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.105, 4046.12796875, 371.71539062000005), 'rotation':(-1.045715, -90.233826, -1.084442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.0809375, 4051.5771875, 371.81261719), 'rotation':(-1.031891, -90.234161, -1.06958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.056875, 4057.02539062, 371.90828125), 'rotation':(-1.009155, -90.234894, -1.045197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-495.0328125, 4062.475625, 371.99992188), 'rotation':(-0.963043, -90.236725, -0.995819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-495.00875, 4067.92382812, 372.0884375), 'rotation':(-0.916931, -90.238007, -0.946655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.93015625, 4073.36351562, 372.22453125), 'rotation':(0.650603, 90.042068, 0.635961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.926875, 4067.915, 372.16148438), 'rotation':(0.650603, 90.042068, 0.635961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.92039062000003, 4057.01734375, 372.02992187999996), 'rotation':(0.706802, 90.04319, 0.689509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.90734375, 4035.22195312, 371.74839844), 'rotation':(0.761867, 90.044632, 0.741798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.90082031, 4024.32398438, 371.60050780999995), 'rotation':(0.787753, 90.045532, 0.76632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.89753906, 4018.87570312, 371.52433594), 'rotation':(0.787753, 90.045532, 0.76632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.89429687999996, 4013.42625, 371.44691406), 'rotation':(0.813687, 90.046089, 0.790816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.89097656, 4007.97828125, 371.36765625), 'rotation':(0.813687, 90.046089, 0.790816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.88769531, 4002.5290625, 371.28773437999996), 'rotation':(0.839608, 90.046814, 0.815265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.99171875, 4175.91109375, 373.14503906), 'rotation':(0.394764, 90.037468, 0.389359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.98839843999997, 4170.47359375, 373.10746094), 'rotation':(0.39499, 90.037209, 0.389567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.98515625000005, 4165.03609375, 373.06910156), 'rotation':(0.401424, 90.037186, 0.39583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.97863281, 4154.16164062, 372.98867187999997), 'rotation':(0.426989, 90.037567, 0.420674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.97203125, 4143.28710938, 372.90324219), 'rotation':(0.452821, 90.037956, 0.445705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.96886718999997, 4137.85007812, 372.85867188), 'rotation':(0.465908, 90.03849, 0.458385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.96558594, 4132.41257812, 372.81285155999996), 'rotation':(0.478728, 90.038712, 0.470777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.96234374999995, 4126.97609375, 372.765625), 'rotation':(0.491453, 90.038605, 0.483071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.95906249999996, 4121.53859375, 372.7171875), 'rotation':(0.510126, 90.039085, 0.50111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-392.95582031000004, 4116.1015625, 372.66707031), 'rotation':(0.510126, 90.039085, 0.50111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-392.94605469, 4099.79101562, 372.50859375), 'rotation':(0.558853, 90.040016, 0.548032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.4942968800001, 4180.9721875, 373.00605469000004), 'rotation':(0.318526, 89.73568, 0.314989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.56992188000004, 4164.6709375, 372.91507812000003), 'rotation':(0.318417, 89.735542, 0.314903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.5952343800001, 4159.2378125, 372.88429687999997), 'rotation':(0.324038, 89.735825, 0.320378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.62039061999997, 4153.80375, 372.8525), 'rotation':(0.334631, 89.735939, 0.330742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.645625, 4148.36960938, 372.82035156), 'rotation':(0.334631, 89.735939, 0.330742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.72140625, 4132.06882812, 372.72027344), 'rotation':(0.356379, 89.736008, 0.351963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.74664062, 4126.63523438, 372.68585937999995), 'rotation':(0.361836, 89.736206, 0.357293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.79710938000005, 4115.76804688, 372.6153125), 'rotation':(0.367881, 89.73642, 0.363177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.8224218800001, 4110.33445312, 372.57914062000003), 'rotation':(0.380025, 89.736374, 0.375015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.84765625, 4104.90085938, 372.54191405999995), 'rotation':(0.392148, 89.736549, 0.38682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-286.8728906199999, 4099.46726562, 372.50410156), 'rotation':(0.392148, 89.736549, 0.38682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-286.99546875, 4073.0590625, 372.31058594), 'rotation':(0.436231, 89.737267, 0.429619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.02070312, 4067.63304688, 372.26863281), 'rotation':(0.436231, 89.737267, 0.429619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.04593750000004, 4062.2057812499997, 372.2259375), 'rotation':(0.450594, 89.73748, 0.443556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.1215625, 4045.92648438, 372.09175781), 'rotation':(0.479527, 89.737961, 0.471544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-287.14679688, 4040.49976562, 372.04570312000004), 'rotation':(0.486774, 89.738106, 0.47856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.17203125000003, 4035.07328125, 371.99914062000005), 'rotation':(0.486774, 89.738106, 0.47856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.19726561999994, 4029.64671875, 371.95230469), 'rotation':(0.493727, 89.738159, 0.485289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.22249999999997, 4024.2200000000003, 371.90421875), 'rotation':(0.507736, 89.738403, 0.498797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-287.27296875, 4013.36671875, 371.80601562000004), 'rotation':(0.521949, 89.738663, 0.512506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.68117188000008, 4007.8957812500003, 371.51730469), 'rotation':(-0.635101, -90.243591, -0.649323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.65757811999993, 4013.27515625, 371.57480469), 'rotation':(-0.618713, -90.243958, -0.632202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.63406250000003, 4018.65429688, 371.63078125), 'rotation':(-0.602356, -90.244293, -0.615143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.61046875, 4024.0339062499997, 371.68519531), 'rotation':(-0.585968, -90.244812, -0.598083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.56343749999996, 4034.79273438, 371.78933594), 'rotation':(-0.552917, -90.2453, -0.56369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.53984375000005, 4040.17210938, 371.8390625), 'rotation':(-0.536896, -90.245605, -0.547028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-174.4928125, 4050.93140625, 371.93464844000005), 'rotation':(-0.501251, -90.246277, -0.510071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.44570311999996, 4061.6909375, 372.02570312000006), 'rotation':(-0.479095, -90.246643, -0.487183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-173.98593749999998, 4166.72023438, 372.6359375), 'rotation':(-0.225189, -90.249847, -0.226959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.01046874999997, 4161.11523438, 372.61355469), 'rotation':(-0.232635, -90.249634, -0.234528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.05953124999996, 4149.90429688, 372.56640625), 'rotation':(-0.262817, -90.249451, -0.265259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.08414061999997, 4144.29882812, 372.54109375), 'rotation':(-0.277496, -90.249329, -0.280182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.1086718800001, 4138.69382812, 372.51492188), 'rotation':(-0.277496, -90.249329, -0.280182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.13320311999996, 4133.08835938, 372.48777344), 'rotation':(-0.285156, -90.249268, -0.287994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.15773438000008, 4127.48289062, 372.45988280999995), 'rotation':(-0.297668, -90.249115, -0.300781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.18226561999995, 4121.87796875, 372.43113281), 'rotation':(-0.297668, -90.249115, -0.300781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.23132811999994, 4110.66796875, 372.36980469), 'rotation':(-0.34726, -90.248566, -0.351501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-174.25585938000006, 4105.06296875, 372.33625), 'rotation':(-0.372131, -90.24823, -0.377014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-174.28039061999993, 4099.45851562, 372.30132812000005), 'rotation':(-0.372131, -90.24823, -0.377014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.90242188000002, 4376.78320312, 373.11617187999997), 'rotation':(0.034472, -90.051086, 0.034445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.91210938000006, 4365.87402344, 373.12300781), 'rotation':(0.037675, -90.051056, 0.03763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.91703125000004, 4360.41992188, 373.12660156), 'rotation':(0.037675, -90.051056, 0.03763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.921875, 4354.96582031, 373.13019531), 'rotation':(0.03036, -90.051147, 0.030327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.92671874999996, 4349.51171875, 373.13351562), 'rotation':(0.03036, -90.051147, 0.030327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.93765625000003, 4338.60351562, 373.13671875), 'rotation':(0.001018, -90.051025, 0.001028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.94140625, 4333.15039062, 373.13609375), 'rotation':(-0.027985, -90.051178, -0.028015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.79171874999997, 4500.80226562, 373.13351562), 'rotation':(-0.041138, -90.051147, -0.041199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.79664061999995, 4495.38914062, 373.12925780999996), 'rotation':(-0.041138, -90.051147, -0.041199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.80140625, 4489.9765625, 373.12535155999996), 'rotation':(-0.034821, -90.051056, -0.034882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.80624999999998, 4484.56398438, 373.12191406), 'rotation':(-0.034821, -90.051056, -0.034882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.82070311999996, 4468.32570312, 373.11335937999996), 'rotation':(-0.025696, -90.051117, -0.025726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.83039062, 4457.50046875, 373.10851562000005), 'rotation':(-0.025696, -90.051117, -0.025726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.84007811999993, 4446.6753125, 373.10367188), 'rotation':(-0.017029, -90.051086, -0.017029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.84484375, 4441.2621875, 373.10175781), 'rotation':(0.001366, -90.051086, 0.001366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.85453125000004, 4430.43601562, 373.10195312), 'rotation':(0.010143, -90.051056, 0.010135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.859375, 4425.0234375, 373.10292969), 'rotation':(0.010143, -90.051208, 0.010135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.68359375, 4607.18261719, 373.26082031), 'rotation':(-0.088745, -90.051025, -0.08902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.6896093800001, 4601.50390625, 373.25203125), 'rotation':(-0.086365, -90.050964, -0.086609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.69562499999995, 4595.82617188, 373.24347656), 'rotation':(-0.082336, -90.051086, -0.082581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.71359374999997, 4578.79054688, 373.21925781), 'rotation':(-0.073914, -90.051117, -0.074097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.71953125000005, 4573.11230469, 373.21179687999995), 'rotation':(-0.073914, -90.051117, -0.074097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.72562500000004, 4567.4340625, 373.20449219), 'rotation':(-0.071899, -90.050934, -0.072083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.73148437999998, 4561.75585938, 373.19734375), 'rotation':(-0.071899, -90.051056, -0.072083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.74351561999993, 4550.39890625, 373.18332031), 'rotation':(-0.065277, -90.051056, -0.06543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.74953125000002, 4544.72023438, 373.1765625), 'rotation':(-0.065277, -90.051056, -0.06543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.75546874999998, 4539.04199219, 373.17011719000004), 'rotation':(-0.061127, -90.051086, -0.061249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.76742188000003, 4527.68507812, 373.158125), 'rotation':(-0.056732, -90.051086, -0.056854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.64453125, 4634.18992188, 373.30203125), 'rotation':(-0.084595, -90.050995, -0.084839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.63867188000006, 4645.15332031, 373.31769531), 'rotation':(-0.082001, -90.050995, -0.082245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.63578125000004, 4650.63574219, 373.32539062), 'rotation':(-0.080536, -90.050964, -0.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.6328125, 4656.11765625, 373.33308594000005), 'rotation':(-0.080261, -90.051086, -0.080505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62984374999996, 4661.59960938, 373.34078125), 'rotation':(-0.080536, -90.050964, -0.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62695311999994, 4667.0815625, 373.34847656), 'rotation':(-0.080536, -90.051086, -0.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62406250000004, 4672.56396484, 373.35613280999996), 'rotation':(-0.079773, -90.051056, -0.079987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.62109375, 4678.04589844, 373.36367187999997), 'rotation':(-0.077667, -90.051056, -0.077881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.61812499999996, 4683.52783203, 373.37105469), 'rotation':(-0.077667, -90.051056, -0.077881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.61515625000004, 4689.00976562, 373.37828125), 'rotation':(-0.076172, -90.050903, -0.076355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.61226562000002, 4694.49169922, 373.38535156), 'rotation':(-0.074646, -90.051086, -0.074829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.60929688, 4699.97412109, 373.39238280999996), 'rotation':(-0.073486, -90.051056, -0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-171.60640624999996, 4705.45605469, 373.39945312000003), 'rotation':(-0.073486, -90.051056, -0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-171.60343750000004, 4710.93798828, 373.40644531), 'rotation':(-0.073792, -90.051056, -0.073975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.97617188000004, 4322.24757812, 373.13039062), 'rotation':(0.042996, 89.948837, 0.042926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.96148438, 4338.60742188, 373.13667969), 'rotation':(-0.015717, 89.948814, -0.015717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.95664061999992, 4344.06054688, 373.13585937999994), 'rotation':(-0.030365, 89.949013, -0.030396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.94203125, 4360.42140625, 373.12660156), 'rotation':(-0.037506, 89.948853, -0.037567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.93718750000005, 4365.875, 373.12300781), 'rotation':(-0.037506, 89.948853, -0.037567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.9225781199999, 4382.23730469, 373.11335937999996), 'rotation':(-0.021637, 89.948776, -0.021667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.91773438000007, 4387.6909375, 373.11101562000005), 'rotation':(-0.021637, 89.948776, -0.021667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.91281249999997, 4393.14550781, 373.10910156), 'rotation':(-0.015594, 89.948906, -0.015594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.88929688000007, 4419.60890625, 373.10386719), 'rotation':(-0.010132, 89.948952, -0.010132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.87960938000003, 4430.4340625, 373.10195312), 'rotation':(-0.009766, 89.948952, -0.009796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.87476561999995, 4435.8471875, 373.10128906), 'rotation':(-0.001373, 89.948929, -0.001373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.87, 4441.26023438, 373.10175781), 'rotation':(0.017021, 89.948761, 0.017013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.8650781199999, 4446.67335938, 373.10367188), 'rotation':(0.025436, 89.948868, 0.025413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.86031249999996, 4452.0859375, 373.10609375), 'rotation':(0.025688, 89.948868, 0.025676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.85546875, 4457.49851562, 373.10847656), 'rotation':(0.025688, 89.948868, 0.025676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.8458593800001, 4468.32375, 373.11335937999996), 'rotation':(0.028741, 89.948929, 0.028708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.84101562, 4473.73632812, 373.1159375), 'rotation':(0.028741, 89.948929, 0.028708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.83617188000005, 4479.14890625, 373.11867187999997), 'rotation':(0.034841, 89.948837, 0.034794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.83132811999997, 4484.56203125, 373.12191406), 'rotation':(0.041145, 89.948952, 0.041075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.82656250000002, 4489.97460938, 373.12535155999996), 'rotation':(0.041145, 89.948952, 0.041075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.82171874999995, 4495.3871875, 373.12925780999996), 'rotation':(0.047238, 89.948845, 0.047159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.81687499999998, 4500.8003125, 373.13351562), 'rotation':(0.047238, 89.948845, 0.047159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.72195311999997, 4607.18898438, 373.26082031), 'rotation':(0.08843, 89.948967, 0.088166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.72695311999996, 4601.50976562, 373.25203125), 'rotation':(0.088738, 89.94912, 0.088467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.73203124999998, 4595.83105469, 373.24347656), 'rotation':(0.086347, 89.948929, 0.086083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.73710938, 4590.151875, 373.23515625), 'rotation':(0.086347, 89.948929, 0.086083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.74726562, 4578.79445312, 373.21925781), 'rotation':(0.07811, 89.948906, 0.077902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.75234375000002, 4573.11523438, 373.21175781), 'rotation':(0.07811, 89.948906, 0.077902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.75742188000004, 4567.43652344, 373.20445312000004), 'rotation':(0.073882, 89.949005, 0.073696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.76242188000003, 4561.7578125, 373.19734375), 'rotation':(0.071895, 89.948929, 0.071704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.77257811999993, 4550.39941406, 373.18328125), 'rotation':(0.069641, 89.948959, 0.069462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.77765624999995, 4544.72070312, 373.1765625), 'rotation':(0.069641, 89.948959, 0.069462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.78781249999997, 4533.3628125, 373.16398438), 'rotation':(0.06111, 89.948921, 0.060975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.79281249999997, 4527.68359375, 373.158125), 'rotation':(0.06111, 89.948921, 0.060975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.62937499999998, 4710.94433594, 373.40644531), 'rotation':(0.073466, 89.948944, 0.073284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.63429688000008, 4705.46240234, 373.39945312000003), 'rotation':(0.073752, 89.948936, 0.073571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.63914061999992, 4699.98046875, 373.39238280999996), 'rotation':(0.073466, 89.949089, 0.073296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.64890624999998, 4689.01660156, 373.37828125), 'rotation':(0.07464, 89.948914, 0.074446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.66359375000002, 4672.57080078, 373.35613280999996), 'rotation':(0.077646, 89.948936, 0.077436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':1, 'location':(-179.66843749999998, 4667.08835938, 373.34847656), 'rotation':(0.079763, 89.949089, 0.079544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.67335938000008, 4661.60644531, 373.34078125), 'rotation':(0.080514, 89.948898, 0.080295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.68804688, 4645.160625, 373.31769531), 'rotation':(0.080514, 89.949036, 0.080298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.69296874999998, 4639.67871094, 373.30992188), 'rotation':(0.080514, 89.949036, 0.080298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':1, 'location':(-179.69781250000005, 4634.19726562, 373.30203125), 'rotation':(0.082003, 89.948845, 0.081772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.23986328, 3718.19484375, 366.77601562), 'rotation':(-1.177185, -90.000366, -1.226318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.23265625, 3734.828125, 367.11480469), 'rotation':(-1.157379, -90.00119, -1.204865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2302929699999, 3740.37257812, 367.22664062), 'rotation':(-1.157379, -90.00119, -1.204865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.22546875, 3751.46140625, 367.44835937999994), 'rotation':(-1.143158, -90.002686, -1.189484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2230859399999, 3757.00609375, 367.55792969000004), 'rotation':(-1.131439, -90.002228, -1.176819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2207617199999, 3762.5503125, 367.66613280999997), 'rotation':(-1.131439, -90.002228, -1.176819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.21837891, 3768.09445312, 367.77347656), 'rotation':(-1.109131, -90.003082, -1.15271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2159960900001, 3773.63914062, 367.87871094), 'rotation':(-1.086975, -90.003937, -1.128845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.21363281, 3779.18335938, 367.98289062000003), 'rotation':(-1.086975, -90.003937, -1.128845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2112500000001, 3784.72828125, 368.08601562), 'rotation':(-1.064667, -90.005188, -1.104797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.20642578, 3795.8176562500003, 368.29011719000005), 'rotation':(-1.053528, -90.005188, -1.092804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.20404297, 3801.36257812, 368.39210937999997), 'rotation':(-1.053467, -90.005188, -1.092743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.25390625, 3685.756875, 366.10066406), 'rotation':(-1.201416, -89.999573, -1.252625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2586718800001, 3674.6940624999997, 365.86851562000004), 'rotation':(-1.202759, -89.999268, -1.254089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2634375, 3663.6315624999997, 365.63617187999995), 'rotation':(-1.203064, -89.999237, -1.254425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2658007800001, 3658.1003124999997, 365.52), 'rotation':(-1.202789, -89.999878, -1.25415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.26818359, 3652.56910156, 365.40378906), 'rotation':(-1.202759, -89.999268, -1.254089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.27294922, 3641.50632812, 365.17132812000006), 'rotation':(-1.205017, -89.999268, -1.256561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2753320300001, 3635.97535156, 365.055), 'rotation':(-1.205017, -89.999268, -1.256561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2800976599999, 3624.91285156, 364.82207030999996), 'rotation':(-1.206421, -89.999207, -1.258087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.2848437499999, 3613.85035156, 364.58890625), 'rotation':(-1.208832, -89.999451, -1.260681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.294375, 3591.72535156, 364.12195312000006), 'rotation':(-1.208832, -89.999451, -1.260681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.29914062, 3580.66308594, 363.88777344000005), 'rotation':(-1.221527, -89.998718, -1.274506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.30152344, 3575.13183594, 363.77), 'rotation':(-1.221863, -89.998688, -1.274841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-708.30621094, 3564.06957031, 363.53398438), 'rotation':(-1.221527, -89.998718, -1.274506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.30859375, 3558.53832031, 363.41597656), 'rotation':(-1.222626, -89.998352, -1.275665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.3110351600001, 3553.00707031, 363.29792969000005), 'rotation':(-1.224182, -89.998291, -1.277374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.31580078, 3541.94484375, 363.06125), 'rotation':(-1.227692, -89.998108, -1.281189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.31818359, 3536.41332031, 362.94265625), 'rotation':(-1.229675, -89.998047, -1.283356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.3206250000001, 3530.88234375, 362.82390625), 'rotation':(-1.231293, -89.998627, -1.285095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.32300781, 3525.3513281200003, 362.705), 'rotation':(-1.233185, -89.997894, -1.28714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.32775391, 3514.2890625, 362.46660155999996), 'rotation':(-1.23584, -89.998199, -1.290039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.3301367199999, 3508.7575781200003, 362.3471875), 'rotation':(-1.23587, -89.998199, -1.2901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-708.33251953, 3503.2265625, 362.2278125), 'rotation':(-1.23587, -89.998199, -1.2901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.30371094, 3685.74953125, 365.57570312), 'rotation':(-1.40332, -89.99881, -1.473389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.306875, 3680.21632812, 365.44066405999996), 'rotation':(-1.40332, -89.99881, -1.473389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31011719, 3674.68335938, 365.30496094), 'rotation':(-1.41864, -89.998474, -1.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31335938, 3669.1496875000003, 365.16785156), 'rotation':(-1.434204, -89.997711, -1.507416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31664062, 3663.61648438, 365.02992187999996), 'rotation':(-1.434204, -89.997711, -1.507416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.31984375, 3658.0832812500003, 364.89128905999996), 'rotation':(-1.441833, -89.997284, -1.515839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.32640625, 3647.01609375, 364.61226562), 'rotation':(-1.458771, -89.996552, -1.534546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.32960938, 3641.48316406, 364.47179687999994), 'rotation':(-1.470337, -89.995972, -1.547333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.33601562, 3630.41699219, 364.18738281), 'rotation':(-1.493073, -89.994781, -1.57251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.3490625, 3608.2846875, 363.6046875), 'rotation':(-1.533051, -89.992462, -1.616852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.35546875, 3597.21828125, 363.30839844), 'rotation':(-1.534149, -89.992279, -1.618073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.35871094, 3591.68480469, 363.16007812000004), 'rotation':(-1.536621, -89.992157, -1.620789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.36199219, 3586.15160156, 363.01152344), 'rotation':(-1.539124, -89.992401, -1.623596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.3651562499999, 3580.61839844, 362.86292969000004), 'rotation':(-1.539124, -89.992401, -1.623596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.36839844, 3575.08496094, 362.71417969000004), 'rotation':(-1.541534, -89.991913, -1.626251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.37480469, 3564.01832031, 362.41621094000004), 'rotation':(-1.54248, -89.992188, -1.627319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.37816406, 3558.4841406200003, 362.26761719), 'rotation':(-1.518341, -89.992859, -1.600525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.38132812, 3552.94898438, 362.12195312000006), 'rotation':(-1.469147, -89.996094, -1.546051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.38777344, 3541.87742188, 361.84503906), 'rotation':(-1.37085, -90.000946, -1.437714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.3941796900001, 3530.80617188, 361.58730469), 'rotation':(-1.27298, -90.004822, -1.330536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.39738281, 3525.27, 361.465625), 'rotation':(-1.223999, -90.007629, -1.277161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.4007031200001, 3519.73390625, 361.34871094000005), 'rotation':(-1.174622, -90.009033, -1.223572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.4038281200001, 3514.19875, 361.23589844), 'rotation':(-1.150177, -90.010498, -1.197083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.40703125, 3508.66453125, 361.12476562000006), 'rotation':(-1.150177, -90.010498, -1.197052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.4102734400001, 3503.12964844, 361.01359375), 'rotation':(-0.894958, -89.986023, -0.923248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.27824219, 3729.225625, 366.61851562000004), 'rotation':(-1.351746, -90.001648, -1.416718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2750390599999, 3734.75632812, 366.748125), 'rotation':(-1.342499, -90.002045, -1.406586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2653124999999, 3751.3489062500003, 367.13476562000005), 'rotation':(-1.332703, -90.002319, -1.395844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2620312500001, 3756.879375, 367.26222656), 'rotation':(-1.322083, -90.002808, -1.384216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.25878906, 3762.41015625, 367.38878905999997), 'rotation':(-1.312103, -90.003845, -1.373291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.255625, 3767.9409375, 367.51445312000004), 'rotation':(-1.301422, -90.003723, -1.361633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.24589844, 3784.53367188, 367.88578125), 'rotation':(-1.270172, -90.005157, -1.327484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.24261719, 3790.06445312, 368.00769531), 'rotation':(-1.259613, -90.005615, -1.315948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-602.2362109400001, 3801.12671875, 368.25027344), 'rotation':(-1.254486, -90.006165, -1.310364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.73621094000003, 3798.92820312, 366.71011719), 'rotation':(0.814732, 89.782356, 0.791803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.7578125, 3793.52585938, 366.63328125), 'rotation':(0.814835, 89.782303, 0.791901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.77941405999997, 3788.12351562, 366.55644530999996), 'rotation':(0.814835, 89.782303, 0.791901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.80101562000004, 3782.72070312, 366.47976562), 'rotation':(0.813578, 89.782387, 0.790721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.82261719, 3777.31835938, 366.40324219), 'rotation':(0.811556, 89.782333, 0.78881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.84417969000003, 3771.91578125, 366.32699219), 'rotation':(0.8092, 89.782288, 0.786584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-499.90898438, 3755.70851562, 366.09921875), 'rotation':(0.802561, 89.782082, 0.780311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-499.93058594, 3750.305625, 366.02367187999994), 'rotation':(0.800245, 89.782013, 0.778117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.95222656, 3744.90328125, 365.94832031), 'rotation':(0.797916, 89.781952, 0.77592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.97382812, 3739.50070312, 365.873125), 'rotation':(0.796776, 89.781929, 0.774849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-499.99539062, 3734.09859375, 365.79757812), 'rotation':(0.802506, 89.78196, 0.780266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.03863280999997, 3723.2946875, 365.64417969000004), 'rotation':(0.813318, 89.782547, 0.790464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.8746875, 3514.1059375, 362.87519531), 'rotation':(0.32052, 89.772644, 0.316957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.85257812000003, 3519.64304688, 362.90289062000005), 'rotation':(0.32052, 89.772644, 0.316957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.83054688, 3525.17796875, 362.93382812000004), 'rotation':(0.408227, 89.77375, 0.402454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-500.80839844, 3530.71679688, 362.96914062), 'rotation':(0.408227, 89.77375, 0.402454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-500.76414062000003, 3541.79101562, 363.05472656), 'rotation':(0.495749, 89.775139, 0.487228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.74210938, 3547.32984375, 363.10328125), 'rotation':(0.58325, 89.776787, 0.571469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.69792969, 3558.40160156, 363.21753906), 'rotation':(0.627332, 89.777657, 0.613695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.65367188, 3569.473125, 363.34113281), 'rotation':(0.657406, 89.778328, 0.642454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-500.54328125, 3597.15578125, 363.70320312), 'rotation':(0.87048, 89.784149, 0.84432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.52113281, 3602.69214844, 363.78496094), 'rotation':(0.87048, 89.784149, 0.84432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.476875, 3613.76171875, 363.95390625), 'rotation':(0.880541, 89.784233, 0.85379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.45472656, 3619.296875, 364.03925781), 'rotation':(0.88703, 89.78476, 0.85987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.43257812, 3624.83179688, 364.12523437999994), 'rotation':(0.89386, 89.784653, 0.866292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.41050780999996, 3630.3669531200003, 364.211875), 'rotation':(0.900724, 89.785172, 0.872728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.38832031, 3635.901875, 364.29917969), 'rotation':(0.907199, 89.78508, 0.878802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.36628906, 3641.43675781, 364.38707030999996), 'rotation':(0.914036, 89.785301, 0.885208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.32195312000005, 3652.50660156, 364.56464844000004), 'rotation':(0.920375, 89.785553, 0.891147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.29980469000003, 3658.04125, 364.65332030999997), 'rotation':(0.912301, 89.785301, 0.883589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.27765625, 3663.5754687500003, 364.74128906), 'rotation':(0.904624, 89.785034, 0.87639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-500.1890625, 3685.71335938, 365.08558594000004), 'rotation':(0.872837, 89.784035, 0.846544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-396.26269531, 3502.8303125, 365.64453125), 'rotation':(0.359165, 89.619179, 0.354688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.22558594, 3508.37109375, 365.67925780999997), 'rotation':(0.358967, 89.619354, 0.354501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.18859375, 3513.91164062, 365.71402344), 'rotation':(0.376985, 89.619408, 0.372041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.15160156, 3519.4528906200003, 365.74941406), 'rotation':(0.376985, 89.619408, 0.372041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.07757812, 3530.536875, 365.82867187999994), 'rotation':(0.448375, 89.620415, 0.441402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-396.04058594, 3536.07910156, 365.87351562000003), 'rotation':(0.484035, 89.62101, 0.475912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.89257812000005, 3558.2465625, 366.08789062000005), 'rotation':(0.627093, 89.623764, 0.613491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.85558593999997, 3563.78785156, 366.149375), 'rotation':(0.644811, 89.624199, 0.630423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.81855469000004, 3569.32859375, 366.21238281), 'rotation':(0.658225, 89.624535, 0.643233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.78148437999994, 3574.87035156, 366.27617188), 'rotation':(0.684808, 89.625153, 0.668588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.67054687999996, 3591.49367188, 366.479375), 'rotation':(0.738405, 89.626488, 0.719554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-395.59644531000004, 3602.5746875, 366.623125), 'rotation':(0.752318, 89.626595, 0.732758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.52238280999995, 3613.65527344, 366.76863281), 'rotation':(0.75296, 89.626915, 0.733365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.48535156, 3619.19578125, 366.84148437999994), 'rotation':(0.754148, 89.626945, 0.734487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.41125, 3630.27636719, 366.9875), 'rotation':(0.755678, 89.626984, 0.735933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-395.37425781, 3635.816875, 367.060625), 'rotation':(0.756928, 89.627007, 0.737126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.30015625, 3646.89746094, 367.20714844), 'rotation':(0.758732, 89.627075, 0.738823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-395.26320312000007, 3652.4377343799997, 367.28054688), 'rotation':(0.758656, 89.626892, 0.738764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.22609375, 3657.9775, 367.35316406), 'rotation':(0.747182, 89.626724, 0.727887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.11492188, 3674.59671875, 367.56554687999994), 'rotation':(0.699862, 89.625534, 0.682925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.07789062000006, 3680.1371875, 367.63324219000003), 'rotation':(0.676134, 89.624954, 0.660313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.04082030999996, 3685.67648438, 367.70027344000005), 'rotation':(0.676134, 89.624954, 0.660313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-395.00378906000003, 3691.21703125, 367.76566406), 'rotation':(0.664065, 89.624825, 0.648805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.30925780999996, 3795.10351562, 368.76171875), 'rotation':(0.458975, 89.61998, 0.451656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.34617187999993, 3789.60007812, 368.71765625), 'rotation':(0.459009, 89.619766, 0.451691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.38304687999994, 3784.09695312, 368.67320312000004), 'rotation':(0.459009, 89.619766, 0.451691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.45683594, 3773.0903125, 368.5821875), 'rotation':(0.468052, 89.619698, 0.460454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.4937890599999, 3767.586875, 368.53542969), 'rotation':(0.486658, 89.619812, 0.478446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.5675, 3756.58109375, 368.4384375), 'rotation':(0.505058, 89.619957, 0.496209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.60449219, 3751.07765625, 368.38820312), 'rotation':(0.523486, 89.620468, 0.51398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.64136719, 3745.57445312, 368.33757812000005), 'rotation':(0.523486, 89.620468, 0.51398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.67820312000003, 3740.07125, 368.28585938), 'rotation':(0.532686, 89.620796, 0.522864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-394.71519531, 3734.56882812, 368.23332030999995), 'rotation':(0.543417, 89.620834, 0.533176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.75207031, 3729.0651562499997, 368.17902344000004), 'rotation':(0.565376, 89.621498, 0.55431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.78898438, 3723.5625, 368.123125), 'rotation':(0.586918, 89.622147, 0.574997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-394.8259375, 3718.0598437500003, 368.06597655999997), 'rotation':(0.586918, 89.622147, 0.574997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.62234375, 3718.03148438, 368.57753906), 'rotation':(-0.639435, -90.372314, -0.653839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.5859375, 3723.52882812, 368.6403125), 'rotation':(-0.639435, -90.372314, -0.653839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.54953125, 3729.02585938, 368.70449219), 'rotation':(-0.666229, -90.371704, -0.681854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.51320311999996, 3734.5221874999997, 368.77097656), 'rotation':(-0.692719, -90.37088, -0.709656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.47671875000003, 3740.0190625, 368.8390625), 'rotation':(-0.692719, -90.37088, -0.709656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-280.40398438, 3751.01195312, 368.9784375), 'rotation':(-0.730438, -90.370178, -0.749237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.2947656199999, 3767.49953125, 369.18617187999996), 'rotation':(-0.716949, -90.370514, -0.735046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.2584375, 3772.995625, 369.25441406), 'rotation':(-0.712097, -90.3703, -0.72995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.1491406199999, 3789.48390625, 369.45640625), 'rotation':(-0.698242, -90.370972, -0.715424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.1128125, 3794.98, 369.52316406), 'rotation':(-0.695862, -90.370789, -0.712921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-280.8366406199999, 3685.64085938, 368.24242187999994), 'rotation':(-0.477539, -90.375427, -0.485565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.8734375, 3680.0928125, 368.19441406), 'rotation':(-0.477539, -90.375427, -0.485565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-280.90999999999997, 3674.54734375, 368.14820312000006), 'rotation':(-0.406067, -90.376526, -0.411865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-280.9466406199999, 3668.99929688, 368.10851562000005), 'rotation':(-0.334595, -90.377472, -0.338531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.02015625, 3657.9053125, 368.03789062000004), 'rotation':(-0.29895, -90.377869, -0.302094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.056875, 3652.35839844, 368.00671875), 'rotation':(-0.29895, -90.377869, -0.302094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.09351561999995, 3646.81152344, 367.97804687999997), 'rotation':(-0.269592, -90.378174, -0.272156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.13023438000005, 3641.2658593799997, 367.95195312000004), 'rotation':(-0.210938, -90.378418, -0.212463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.16695312, 3635.71777344, 367.93066405999997), 'rotation':(-0.152252, -90.379059, -0.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.20367188, 3630.1696875, 367.91359375), 'rotation':(-0.152252, -90.379059, -0.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.27703125000005, 3619.07496094, 367.89195312000004), 'rotation':(-0.064148, -90.379333, -0.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.31375, 3613.52929688, 367.88570312), 'rotation':(-0.064148, -90.379333, -0.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.35046875, 3607.98363281, 367.87953125), 'rotation':(-0.064148, -90.379333, -0.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.3871875, 3602.43796875, 367.87328125), 'rotation':(-0.064148, -90.379364, -0.064301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.4239843800001, 3596.89257812, 367.86710938), 'rotation':(-0.021179, -90.379395, -0.02121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.46054688000004, 3591.34496094, 367.86460938), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.49734375, 3585.79761719, 367.86355469), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.5340625, 3580.2521875, 367.86566406), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.57078125, 3574.70628906, 367.86777344), 'rotation':(0.021447, -90.379395, 0.02144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.60749999999996, 3569.160625, 367.86988281), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.64421875000005, 3563.615, 367.87195312000006), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.71765625, 3552.52390625, 367.87613281), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.754375, 3546.97828125, 367.87824219000004), 'rotation':(0.021447, -90.379395, 0.02144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.7911718800001, 3541.43261719, 367.8803125), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.82789061999995, 3535.88695312, 367.88242188), 'rotation':(0.021686, -90.379395, 0.021689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-281.90140625000004, 3524.7971093799997, 367.88175780999995), 'rotation':(-0.066559, -90.379547, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-281.938125, 3519.25316406, 367.87535155999996), 'rotation':(-0.066559, -90.379272, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-282.01156249999997, 3508.161875, 367.86242187999994), 'rotation':(-0.066559, -90.379272, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-282.04828124999995, 3502.61621094, 367.85601562000005), 'rotation':(-0.066559, -90.379272, -0.066711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.42562499999997, 3691.20945312, 366.49726562), 'rotation':(-0.951324, -90.365692, -0.983337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.46242188000008, 3685.67382812, 366.40367188), 'rotation':(-0.845551, -90.369019, -0.870789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.49914061999993, 3680.1379687500003, 366.32054687999994), 'rotation':(-0.739685, -90.371948, -0.758972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.57273438000004, 3669.06421875, 366.18601562000003), 'rotation':(-0.528259, -90.376465, -0.538055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.68320311999992, 3652.44800781, 366.06347655999997), 'rotation':(-0.263733, -90.380249, -0.266144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.72000000000003, 3646.91480469, 366.03796875), 'rotation':(-0.263977, -90.380371, -0.266388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.75679688000002, 3641.38132812, 366.0125), 'rotation':(-0.166992, -90.38092, -0.167969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.86703124999997, 3624.75707031, 365.99121094000003), 'rotation':(0.21998, -90.380707, 0.218302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.90374999999995, 3619.21410156, 366.01621094), 'rotation':(0.413875, -90.378418, 0.407934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.94046875000004, 3613.67578125, 366.05710938), 'rotation':(0.510495, -90.376984, 0.501466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.01414061999992, 3602.6091406200003, 366.15578125), 'rotation':(0.510488, -90.376892, 0.501464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.05093750000003, 3597.07324219, 366.20570312), 'rotation':(0.557658, -90.37616, 0.546883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.12460938000004, 3586.00269531, 366.316875), 'rotation':(0.651627, -90.374084, 0.636928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.198125, 3574.931875, 366.44835937999994), 'rotation':(0.745952, -90.371796, 0.726718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.27171875, 3563.86230469, 366.60023437999996), 'rotation':(0.83986, -90.369171, 0.815509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.30843749999997, 3558.32910156, 366.68148438), 'rotation':(0.85249, -90.368683, 0.8274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.38234375000002, 3547.2690625, 366.83742187999997), 'rotation':(0.715934, -90.372589, 0.698207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.41929688000005, 3541.73875, 366.90507812000004), 'rotation':(0.647475, -90.374207, 0.63296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.49312499999996, 3530.67726562, 367.01964844), 'rotation':(0.510529, -90.377014, 0.501497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-177.52999999999997, 3525.14671875, 367.06660156), 'rotation':(0.442391, -90.378113, 0.435595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.56695312, 3519.61570312, 367.10664062), 'rotation':(0.373557, -90.379089, 0.368709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.640625, 3508.54980469, 367.17402344000004), 'rotation':(0.33944, -90.379456, 0.335431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-177.67648438000003, 3503.02101562, 367.20675781), 'rotation':(1.022657, -90.493286, 0.986624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.24531249999995, 3718.306875, 367.02347656), 'rotation':(-1.143402, -90.358673, -1.189728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.20773438000003, 3723.95507812, 367.13832031), 'rotation':(-1.160797, -90.357941, -1.208588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-176.09492188000002, 3740.89796875, 367.49183594000004), 'rotation':(-1.205048, -90.35611, -1.256592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-176.05734374999997, 3746.54445312, 367.60914062000006), 'rotation':(-1.192505, -90.356689, -1.24295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.98203124999998, 3757.8385937499997, 367.83707031), 'rotation':(-1.14444, -90.358673, -1.190887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.906875, 3769.13210938, 368.05582031), 'rotation':(-1.095795, -90.360443, -1.138367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.83164061999992, 3780.42601562, 368.26574219), 'rotation':(-1.047394, -90.362366, -1.086243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.75640625000005, 3791.72023438, 368.46757812000004), 'rotation':(-1.023529, -90.363098, -1.060638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-175.71882812, 3797.36789062, 368.56726562000006), 'rotation':(-1.011169, -90.363708, -1.047363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.67617188000008, 3794.18382812, 367.88445312000005), 'rotation':(1.217338, 89.958611, 1.166398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.68898438000008, 3783.29226562, 367.64957031), 'rotation':(1.244358, 89.959763, 1.191161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.70187499999997, 3772.3996875000003, 367.39738280999995), 'rotation':(1.352562, 89.964676, 1.289793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.71492188000002, 3761.51, 367.12566405999996), 'rotation':(1.460793, 89.970009, 1.387648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.73445312000001, 3745.17625, 366.68234375), 'rotation':(1.62303, 89.978691, 1.532917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.74039061999997, 3739.73390625, 366.52550780999997), 'rotation':(1.431198, 90.035789, 1.360968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.74726562000001, 3734.286875, 366.36613280999995), 'rotation':(1.668035, 89.981377, 1.572903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.75374999999997, 3728.84078125, 366.20394531), 'rotation':(1.704358, 89.983459, 1.605088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.76656249999996, 3717.9518749999997, 365.87226562), 'rotation':(1.740407, 89.985649, 1.636934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-73.01625000000001, 3502.73390625, 364.52347656), 'rotation':(-0.551819, 89.938011, -0.562531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-73.00968750000004, 3508.27492188, 364.47007812000004), 'rotation':(-0.551819, 89.938011, -0.562531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':2, 'tiley':2, 'location':(-73.00320311999997, 3513.81542969, 364.41671875), 'rotation':(-0.552185, 89.938095, -0.562897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.99671875000001, 3519.35523438, 364.36316406), 'rotation':(-0.578705, 89.938515, -0.590485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.99015625000004, 3524.8940625, 364.30628906), 'rotation':(-0.632904, 89.939735, -0.647003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.98359374999995, 3530.43238281, 364.24382812000005), 'rotation':(-0.687073, 89.940903, -0.703705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.97703124999998, 3535.97070312, 364.17570312000004), 'rotation':(-0.740936, 89.942322, -0.760284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.97054688000003, 3541.50855469, 364.10191405999996), 'rotation':(-0.795074, 89.943687, -0.817383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.96398438000006, 3547.046875, 364.02253906), 'rotation':(-0.903442, 89.946922, -0.932281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.95093750000001, 3558.12183594, 363.84679687999994), 'rotation':(-0.983887, 89.948875, -1.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.94453124999995, 3563.66332031, 363.75660156), 'rotation':(-0.790619, 89.943672, -0.812653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.93812500000001, 3569.20972656, 363.67640625), 'rotation':(-0.66156, 89.940331, -0.676971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.93164061999994, 3574.75632812, 363.6090625), 'rotation':(-0.532196, 89.937637, -0.542145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.92523438, 3580.30371094, 363.55457031), 'rotation':(-0.403137, 89.935532, -0.408844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.90609374999997, 3596.94628906, 363.46796875), 'rotation':(-0.015533, 89.932693, -0.015533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.89320311999995, 3608.03859375, 363.46882812), 'rotation':(0.129432, 89.932983, 0.128855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.88039061999996, 3619.1330468799997, 363.49449219), 'rotation':(0.289381, 89.934158, 0.286477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.87429688000009, 3624.68164062, 363.53046875), 'rotation':(0.610243, 89.939201, 0.597343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.85539061999998, 3641.32421875, 363.74179688), 'rotation':(1.090692, 89.953461, 1.049747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.84914061999996, 3646.87742188, 363.84792969), 'rotation':(1.250724, 89.960022, 1.196978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-72.83640624999998, 3657.95921875, 364.10035156), 'rotation':(1.398276, 89.966873, 1.331209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.83015624999996, 3663.4965625, 364.23558594), 'rotation':(1.533152, 89.973763, 1.45266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.82359374999999, 3669.03859375, 364.37730469), 'rotation':(1.533152, 89.973763, 1.45266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.80460937999999, 3685.65453125, 364.84679687999994), 'rotation':(1.803149, 89.989571, 1.692155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-72.79828124999995, 3691.18992188, 365.02125), 'rotation':(1.869539, 89.993706, 1.750316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':2, 'tiley':2, 'location':(-495.26792969, 3997.54664062, 370.74253905999996), 'rotation':(-1.251068, -90.225403, -1.306641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':2, 'tiley':2, 'location':(-495.30183594000005, 3995.40304688, 370.69566405999996), 'rotation':(-1.251251, -90.225555, -1.306854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-392.89378906, 3997.54148438, 371.21351562), 'rotation':(0.852373, 90.047218, 0.827294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':2, 'tiley':2, 'location':(-392.91027343999997, 3992.25804688, 371.13484375), 'rotation':(0.852373, 90.047218, 0.827294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':2, 'tiley':2, 'location':(-174.73906250000005, 3994.6667187499997, 371.37035155999996), 'rotation':(-0.64328, -90.243347, -0.657867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(252.03812500000004, 4098.24953125, 369.95632812), 'rotation':(-0.907104, -90.174164, -0.936188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.09367188, 4115.12304688, 370.19902344), 'rotation':(-0.776459, -90.177887, -0.797729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(252.1121875, 4120.74609375, 370.27003906), 'rotation':(-0.710999, -90.179688, -0.728821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.14921875000005, 4131.99757812, 370.40335938), 'rotation':(-0.659637, -90.180878, -0.674957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.16781249999997, 4137.62257812, 370.46449219000004), 'rotation':(-0.622314, -90.181732, -0.635956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.18624999999997, 4143.24804688, 370.52207031), 'rotation':(-0.58551, -90.182617, -0.597565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(252.20484375, 4148.87304688, 370.57605469000003), 'rotation':(-0.548431, -90.183197, -0.559021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(252.22335938000003, 4154.49804688, 370.62640625), 'rotation':(-0.511078, -90.183899, -0.520264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(252.24187500000005, 4160.12304688, 370.67320312000004), 'rotation':(-0.473999, -90.18454, -0.481903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(252.26046874999997, 4165.74804688, 370.71636719), 'rotation':(-0.436646, -90.18512, -0.443329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(252.2975, 4176.9990625, 370.79359375), 'rotation':(-0.380981, -90.185974, -0.386078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.72296874999995, 4002.5490625, 367.8821875), 'rotation':(-1.610138, -90.142731, -1.702667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.75773438, 4013.12476562, 368.16949219), 'rotation':(-1.551727, -90.146393, -1.637604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(251.79257811999992, 4023.70140625, 368.44207030999996), 'rotation':(-1.471558, -90.150635, -1.548676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(251.8274218800001, 4034.27804688, 368.69984375), 'rotation':(-1.391418, -90.154816, -1.460297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(251.84484375, 4039.56640625, 368.82320312), 'rotation':(-1.351257, -90.156586, -1.416168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.86226562000002, 4044.85453125, 368.94339844), 'rotation':(-1.291748, -90.159088, -1.351013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(251.89703125000005, 4055.43289062, 369.17296875), 'rotation':(-1.259552, -90.160736, -1.315918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(251.91445311999996, 4060.7196875, 369.28347656), 'rotation':(-1.196899, -90.163544, -1.247742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(251.94929688000002, 4071.29882812, 369.49023437999995), 'rotation':(-1.133728, -90.165985, -1.179291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(352.84375, 4065.66578125, 369.34808594000003), 'rotation':(0.67821, 89.786667, 0.662301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.76234375, 4044.61648438, 369.10199219000003), 'rotation':(0.666271, 89.786194, 0.650907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(352.72175781, 4034.0910937500003, 368.98332030999995), 'rotation':(0.634702, 89.785507, 0.620749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.70148438, 4028.828125, 368.92667969), 'rotation':(0.614655, 89.785088, 0.601573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(352.66082030999996, 4018.30226562, 368.81890625), 'rotation':(0.574917, 89.784248, 0.563471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.64050781000003, 4013.03929688, 368.76777344000004), 'rotation':(0.555226, 89.783852, 0.544537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.62023437999994, 4007.77664062, 368.7184375), 'rotation':(0.535514, 89.783821, 0.525568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(353.28589844, 4179.93601562, 370.43664062000005), 'rotation':(0.333539, 89.780548, 0.329668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(353.26457030999995, 4174.46140625, 370.40472656), 'rotation':(0.333539, 89.780548, 0.329668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.24339843999996, 4168.9878125, 370.37285155999996), 'rotation':(0.333791, 89.780533, 0.329913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.22230469, 4163.51414062, 370.33957031), 'rotation':(0.349043, 89.7808, 0.344819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.17980468999997, 4152.569375, 370.26425781), 'rotation':(0.410358, 89.781593, 0.404507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.15867187999993, 4147.09671875, 370.22203125), 'rotation':(0.441271, 89.781761, 0.434516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(353.13746094, 4141.62351562, 370.17683594000005), 'rotation':(0.471939, 89.782562, 0.464211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(353.09507812000004, 4130.67773438, 370.07746094000004), 'rotation':(0.533158, 89.783333, 0.523297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(353.07398437999996, 4125.20507812, 370.02347656), 'rotation':(0.563832, 89.784218, 0.552814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(353.05273437999995, 4119.73140625, 369.96714844), 'rotation':(0.591119, 89.784798, 0.579016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(353.03160156, 4114.25828125, 369.90984375), 'rotation':(0.591119, 89.784798, 0.579016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(353.01039062000007, 4108.78421875, 369.85109375), 'rotation':(0.614751, 89.78508, 0.601663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(352.98917969, 4103.3115625, 369.79027344), 'rotation':(0.638418, 89.785797, 0.624304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.39039062000006, 4176.51710938, 370.73753905999996), 'rotation':(-0.043335, 89.969818, -0.043396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.38746094, 4170.9053125, 370.74179688), 'rotation':(-0.043335, 89.969818, -0.043396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.38160156000004, 4159.68164062, 370.75011719), 'rotation':(-0.041626, 89.96991, -0.041687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.36976562000007, 4137.23484375, 370.76453125), 'rotation':(-0.032532, 89.970108, -0.032593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.36390625, 4126.01171875, 370.77070312), 'rotation':(-0.031097, 89.969841, -0.031158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.3609765599999, 4120.39992188, 370.77363281), 'rotation':(-0.031097, 89.969826, -0.031128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(460.35804687999996, 4114.78859375, 370.77613281), 'rotation':(-0.026764, 89.969887, -0.026794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.35503905999997, 4109.17671875, 370.77789062000005), 'rotation':(-0.018524, 89.970131, -0.018555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.35203125, 4103.56492188, 370.77894531), 'rotation':(-0.01004, 89.969879, -0.01004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.32054687999994, 4071.01101562, 370.77816406), 'rotation':(0.0025, 89.970016, 0.002503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.3141015599999, 4065.74289062, 370.77777344000003), 'rotation':(0.00405, 89.969894, 0.004036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.31281249999995, 4060.47265625, 370.77710937999996), 'rotation':(0.007479, 89.969887, 0.007474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.3103125, 4049.93210938, 370.77535156), 'rotation':(0.010307, 89.970085, 0.010302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(460.30781249999995, 4039.39257812, 370.77289062000006), 'rotation':(0.0, 89.999985, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30652344, 4034.12132812, 370.7715625), 'rotation':(0.014808, 89.969933, 0.014799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30523438, 4028.85109375, 370.77019530999996), 'rotation':(0.014808, 89.969933, 0.014799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30402344000004, 4023.5807812499997, 370.76890625), 'rotation':(0.01435, 89.969933, 0.014346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30273437999995, 4018.3103125, 370.76765625), 'rotation':(0.013462, 89.969933, 0.013454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.30152344, 4013.04, 370.76644531), 'rotation':(0.013462, 89.969933, 0.013454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.26640625, 4002.49265625, 371.11972656), 'rotation':(0.105007, -90.146271, 0.104624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.2809374999999, 4008.16820312, 371.10933594), 'rotation':(0.104843, -90.146301, 0.104464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(572.32445312, 4025.1940624999997, 371.07742188), 'rotation':(0.110171, -90.146027, 0.109757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.3389843799999, 4030.86960938, 371.06632812000004), 'rotation':(0.1122, -90.146667, 0.111759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.3534374999999, 4036.54492188, 371.05511719000003), 'rotation':(0.113279, -90.146088, 0.112843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.36796875, 4042.22023438, 371.04390625), 'rotation':(0.113279, -90.146698, 0.112828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.4115625, 4059.24632812, 371.00863281), 'rotation':(0.12153, -90.146576, 0.121024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.42601562, 4064.92140625, 370.99605469), 'rotation':(0.127076, -90.146118, 0.126525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.50957031, 4097.5303125, 370.9175), 'rotation':(0.146316, -90.146362, 0.14557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.52351562, 4102.98195312, 370.9034375), 'rotation':(0.146316, -90.146362, 0.14557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.5374609400001, 4108.4340625, 370.88914062000003), 'rotation':(0.150483, -90.145935, 0.149698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.55140625, 4113.88625, 370.87453125), 'rotation':(0.150483, -90.145935, 0.149698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.56535156, 4119.33789062, 370.85980469000003), 'rotation':(0.154069, -90.146301, 0.153246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.5792968799999, 4124.79, 370.84472655999997), 'rotation':(0.158249, -90.146271, 0.157379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.59320312, 4130.2421875, 370.82960937999997), 'rotation':(0.15999, -90.145813, 0.159109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(572.6350781200001, 4146.59859375, 370.78410155999995), 'rotation':(0.15844, -90.145905, 0.157565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(572.6490625, 4152.05078125, 370.76910155999997), 'rotation':(0.15844, -90.145905, 0.157565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.66296875, 4157.50296875, 370.75414062000004), 'rotation':(0.157142, -90.146362, 0.156288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.67695312, 4162.95460938, 370.73933594000005), 'rotation':(0.155844, -90.145935, 0.155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(572.6908593799999, 4168.40671875, 370.72453125), 'rotation':(0.155844, -90.145935, 0.155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(572.71875, 4179.31101562, 370.69496094000004), 'rotation':(0.155271, -90.145935, 0.154431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.99529297, 4113.65382812, 370.64484375), 'rotation':(0.201511, -90.033691, 0.200105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.99865234, 4119.085, 370.62464844000004), 'rotation':(0.212979, -90.033966, 0.2114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.00195312, 4124.515625, 370.60359375), 'rotation':(0.212979, -90.033966, 0.2114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(680.00525391, 4129.94679688, 370.58234375), 'rotation':(0.224433, -90.033875, 0.222674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(680.01177734, 4140.8090625, 370.53816406), 'rotation':(0.233217, -90.033783, 0.231332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.01507812, 4146.24070312, 370.51542969), 'rotation':(0.239781, -90.033722, 0.237786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.02166016, 4157.10304688, 370.46910155999996), 'rotation':(0.246522, -90.033264, 0.244401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(680.02820312, 4167.96484375, 370.42128906), 'rotation':(0.252895, -90.0336, 0.250675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(679.98529297, 4013.816875, 370.9328125), 'rotation':(0.133353, -90.034363, 0.132733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.98382812, 4019.47703125, 370.91929688), 'rotation':(0.137307, -90.034332, 0.136656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.98101562, 4030.79710938, 370.89140625), 'rotation':(0.141269, -90.034302, 0.140573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97960938, 4036.45726562, 370.87703125), 'rotation':(0.145032, -90.034302, 0.144306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97828125, 4042.11742188, 370.86261719000004), 'rotation':(0.147006, -90.034119, 0.146259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.9768750000001, 4047.77757812, 370.84785156), 'rotation':(0.150073, -90.034302, 0.149292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97546875, 4053.4375, 370.8328125), 'rotation':(0.150073, -90.034302, 0.149292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(679.97400391, 4059.09789062, 370.81742188), 'rotation':(0.155715, -90.034271, 0.154874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(679.9711914100001, 4070.41773438, 370.7853125), 'rotation':(0.161582, -90.033813, 0.160666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.33718750000003, 4633.76023438, 372.19890625), 'rotation':(0.004686, -90.07962, 0.004676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.34554688000003, 4639.2621875, 372.1984375), 'rotation':(0.004686, -90.07962, 0.004676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.37874999999997, 4661.26953125, 372.19664062000004), 'rotation':(0.004877, -90.07959, 0.004881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.395390619999944, 4672.27296875, 372.1959375), 'rotation':(0.003545, -90.07959, 0.003543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.40367188000005, 4677.77490234, 372.19578125), 'rotation':(0.001462, -90.07959, 0.001457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.41195311999991, 4683.27685547, 372.19574219000003), 'rotation':(0.001462, -90.07959, 0.001457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.42031250000002, 4688.77880859, 372.19570312), 'rotation':(0.000376, -90.07959, 0.000377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.436874999999986, 4699.78222656, 372.19566405999996), 'rotation':(0.000376, -90.07959, 0.000374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.44515624999997, 4705.28417969, 372.19558594), 'rotation':(0.000376, -90.07959, 0.000377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(40.98593749999998, 4381.0034375, 372.21941405999996), 'rotation':(0.009426, -90.079651, 0.009428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.97804688000008, 4375.34132812, 372.22035156), 'rotation':(0.008825, -90.079559, 0.008824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.970156249999945, 4369.67921875, 372.22121094), 'rotation':(0.009091, -90.07959, 0.009089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.962265619999926, 4364.01757812, 372.22210937999995), 'rotation':(0.008825, -90.07959, 0.008827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.938671880000015, 4347.03171875, 372.22464844), 'rotation':(0.004228, -90.07959, 0.004224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(40.922968749999995, 4335.70851562, 372.22546875), 'rotation':(0.002411, -90.07959, 0.002398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.907187499999964, 4324.38429688, 372.2259375), 'rotation':(0.002623, -90.07959, 0.002617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(40.899374999999964, 4318.72265625, 372.22621094000004), 'rotation':(0.002411, -90.07959, 0.002398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.15164061999997, 4500.31398438, 372.18585937999995), 'rotation':(0.006058, -90.07959, 0.006053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.14414061999992, 4494.90476562, 372.18621094), 'rotation':(0.006058, -90.07959, 0.006053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.12906250000003, 4484.08546875, 372.18789062), 'rotation':(0.017622, -90.07959, 0.017618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.12156249999998, 4478.67578125, 372.18941406), 'rotation':(0.023421, -90.07959, 0.023399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.114062500000045, 4473.26609375, 372.19136719), 'rotation':(0.023421, -90.07959, 0.023399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.09156250000001, 4457.03808594, 372.19835937999994), 'rotation':(0.022765, -90.079559, 0.022756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.08406249999996, 4451.6284375, 372.20054688), 'rotation':(0.021556, -90.07959, 0.021546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.07648438000001, 4446.21921875, 372.20257812000006), 'rotation':(0.02004, -90.07959, 0.02003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.068984380000074, 4440.81007812, 372.20449219), 'rotation':(0.018817, -90.079559, 0.018814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.05398438000009, 4429.99171875, 372.20804688), 'rotation':(0.016085, -90.079559, 0.016085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(41.04648438000004, 4424.58203125, 372.20960937999996), 'rotation':(0.015218, -90.07959, 0.015212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.03890624999997, 4419.17285156, 372.21105469), 'rotation':(0.015163, -90.07959, 0.015144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.29148438000004, 4601.03417969, 372.19796875), 'rotation':(-0.00705, -90.07959, -0.00705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(41.28359375000002, 4595.35449219, 372.19730469), 'rotation':(-0.007965, -90.07959, -0.007965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.26781249999999, 4583.99460938, 372.195625), 'rotation':(-0.010162, -90.07962, -0.010162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.25992188000009, 4578.31445312, 372.19453125), 'rotation':(-0.01236, -90.079559, -0.01236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.25203124999996, 4572.63476562, 372.19328125), 'rotation':(-0.014282, -90.07959, -0.014282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.24421874999996, 4566.95460938, 372.19175780999996), 'rotation':(-0.015625, -90.07959, -0.015625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(41.23625000000004, 4561.27441406, 372.19023438), 'rotation':(-0.015381, -90.079559, -0.015381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.22835938000003, 4555.59472656, 372.18871094), 'rotation':(-0.015625, -90.07959, -0.015656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(41.22054688000003, 4549.91453125, 372.18714844000004), 'rotation':(-0.015381, -90.079559, -0.015381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.21257811999999, 4544.23484375, 372.185625), 'rotation':(-0.006256, -90.07959, -0.006226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.20468749999998, 4538.55421875, 372.18449219), 'rotation':(-0.006256, -90.07959, -0.006226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.19687499999998, 4532.87453125, 372.18398437999997), 'rotation':(0.003429, -90.07962, 0.003421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(41.18898438000008, 4527.19433594, 372.18433594000004), 'rotation':(0.003142, -90.07959, 0.003144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(32.866406249999955, 4313.07125, 372.22648438), 'rotation':(-0.002625, 89.92041, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(32.87429688000009, 4318.7334375, 372.22621094000004), 'rotation':(-0.002625, 89.92041, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(32.889999999999986, 4330.05710938, 372.22570312000005), 'rotation':(-0.002625, 89.920395, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(32.91367188000004, 4347.0425, 372.22464844), 'rotation':(-0.007141, 89.92041, -0.007141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(32.92148438000004, 4352.70410156, 372.22386719), 'rotation':(-0.009094, 89.920395, -0.009094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(32.94507811999995, 4369.68992188, 372.22121094), 'rotation':(-0.00882, 89.920395, -0.00882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(32.95296874999997, 4375.35203125, 372.22035156), 'rotation':(-0.00943, 89.92041, -0.00943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(32.9765625, 4392.33789062, 372.21738281), 'rotation':(-0.01181, 89.920403, -0.01178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.01382811999997, 4419.18359375, 372.21105469), 'rotation':(-0.015228, 89.920403, -0.015228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.02132811999991, 4424.59277344, 372.20960937999996), 'rotation':(-0.016113, 89.920395, -0.016113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.02890624999998, 4430.00242188, 372.20804688), 'rotation':(-0.017303, 89.920418, -0.017334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.043906249999964, 4440.82078125, 372.20449219), 'rotation':(-0.02005, 89.920403, -0.02005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.05148438000003, 4446.23, 372.20257812000006), 'rotation':(-0.021545, 89.920418, -0.021576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.05898438000008, 4451.63964844, 372.20054688), 'rotation':(-0.022766, 89.920395, -0.022797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.06648438000002, 4457.04882812, 372.19835937999994), 'rotation':(-0.024292, 89.920418, -0.024323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.07398438000007, 4462.45851562, 372.19609375), 'rotation':(-0.025818, 89.920418, -0.025848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.081484380000006, 4467.86765625, 372.19363281), 'rotation':(-0.025543, 89.92038, -0.025543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.09648437999999, 4478.68703125, 372.18941406), 'rotation':(-0.017639, 89.920403, -0.017639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.10398438000004, 4484.09667969, 372.18789062), 'rotation':(-0.012115, 89.920395, -0.012115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.11148438000009, 4489.50632812, 372.18675780999996), 'rotation':(-0.006042, 89.920418, -0.006042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.11898438000003, 4494.91601562, 372.18621094), 'rotation':(-0.003235, 89.92041, -0.003235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.12656249999998, 4500.32519531, 372.18585937999995), 'rotation':(-0.003235, 89.92041, -0.003235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.16390624999997, 4527.20507812, 372.18433594000004), 'rotation':(-0.003418, 89.920395, -0.003418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.17171874999997, 4532.88523438, 372.18398437999997), 'rotation':(0.006236, 89.920395, 0.006246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.17960937999999, 4538.56492188, 372.18449219), 'rotation':(0.015368, 89.920403, 0.01537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.1875, 4544.245625, 372.185625), 'rotation':(0.015368, 89.920403, 0.01537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.19546875000003, 4549.9253125, 372.18714844000004), 'rotation':(0.015634, 89.920403, 0.015625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.20328125000003, 4555.60546875, 372.18871094), 'rotation':(0.015368, 89.920395, 0.015365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.21906249999995, 4566.9653125, 372.19179687999997), 'rotation':(0.014282, 89.920395, 0.01427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.22695311999996, 4572.64550781, 372.19328125), 'rotation':(0.012356, 89.920395, 0.012351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.23484374999998, 4578.32519531, 372.19453125), 'rotation':(0.010163, 89.920403, 0.010156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.242812500000014, 4584.00539062, 372.195625), 'rotation':(0.007964, 89.920395, 0.007961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(33.25851561999991, 4595.36523438, 372.19730469), 'rotation':(0.007049, 89.92041, 0.007044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.266484380000065, 4601.04492188, 372.19796875), 'rotation':(0.007049, 89.92041, 0.007044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.418906249999964, 4710.79785156, 372.19554687999994), 'rotation':(-0.000183, 89.920395, -0.000183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.411093749999964, 4705.29589844, 372.19558594), 'rotation':(-0.000183, 89.920395, -0.000183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.403437499999995, 4699.79443359, 372.19566405999996), 'rotation':(-0.000366, 89.92041, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.39570312000001, 4694.29248047, 372.19566405999996), 'rotation':(-0.000366, 89.92041, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(33.38796875000003, 4688.79052734, 372.19570312), 'rotation':(-0.000366, 89.920395, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(33.372499999999945, 4677.78710938, 372.19578125), 'rotation':(-0.000366, 89.92041, -0.000366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(33.34937500000001, 4661.28171875, 372.19664062000004), 'rotation':(-0.00354, 89.92041, -0.00354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.34164061999991, 4655.77976562, 372.19707030999996), 'rotation':(-0.004883, 89.920395, -0.004883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(33.33382811999991, 4650.2778125, 372.1975), 'rotation':(-0.004883, 89.920395, -0.004883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(33.31070311999997, 4633.77246094, 372.19890625), 'rotation':(-0.004883, 89.920395, -0.004883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.6335156199999, 4392.18015625, 371.17664062000006), 'rotation':(0.044745, -90.045471, 0.04468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.62914061999993, 4386.66945312, 371.18085937999996), 'rotation':(0.048972, -90.045715, 0.048895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.62039061999997, 4375.64695312, 371.19015625), 'rotation':(0.053194, -90.045685, 0.053109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.61593749999997, 4370.13574219, 371.19523438), 'rotation':(0.055202, -90.045593, 0.05509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.6071875, 4359.11375, 371.20585938), 'rotation':(0.055188, -90.045776, 0.055088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.59835938000003, 4348.09226562, 371.21601562), 'rotation':(0.045878, -90.045624, 0.045795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.58953125000005, 4337.07125, 371.22296875), 'rotation':(0.008401, -90.045654, 0.008394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.58507811999993, 4331.56054688, 371.22453125), 'rotation':(0.008401, -90.045654, 0.008394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.57632811999997, 4320.53953125, 371.22417969), 'rotation':(-0.019318, -90.045685, -0.019348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.57187499999998, 4315.02882812, 371.22265625), 'rotation':(-0.019623, -90.045685, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.71703125, 4494.4253125, 371.11566406), 'rotation':(0.034028, -90.045776, 0.033986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.71414061999997, 4489.0190625, 371.11886719), 'rotation':(0.032573, -90.045776, 0.032545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.71117188000005, 4483.6128125, 371.12199219), 'rotation':(0.032573, -90.045776, 0.032545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.70539062, 4472.80078125, 371.128125), 'rotation':(0.031303, -90.045593, 0.031274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.7025, 4467.39453125, 371.13105469000004), 'rotation':(0.03075, -90.045715, 0.030714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.69953124999995, 4461.98828125, 371.13398437999996), 'rotation':(0.03075, -90.045715, 0.030714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.69664061999993, 4456.5825, 371.136875), 'rotation':(0.031002, -90.045654, 0.030974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.68789061999996, 4440.36328125, 371.14589844), 'rotation':(0.033338, -90.045654, 0.033302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.68499999999995, 4434.95703125, 371.1490625), 'rotation':(0.034342, -90.045654, 0.0343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.67914062, 4424.14453125, 371.15566406), 'rotation':(0.036002, -90.045654, 0.035963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.80421875000002, 4606.245625, 371.08050781), 'rotation':(-0.020233, -90.045654, -0.020233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.79515625, 4594.88328125, 371.07648437999995), 'rotation':(-0.000885, -90.045776, -0.000885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.78609374999996, 4583.52, 371.07578125), 'rotation':(0.018674, -90.045593, 0.018656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.78164061999996, 4577.83835938, 371.07757812000006), 'rotation':(0.018455, -90.045807, 0.018437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.77250000000004, 4566.47609375, 371.08128905999996), 'rotation':(0.018674, -90.045807, 0.018649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.7634375, 4555.11375, 371.08496094000003), 'rotation':(0.020217, -90.045715, 0.020202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.75437499999998, 4543.75097656, 371.08886719000003), 'rotation':(0.023434, -90.045715, 0.023413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.74539061999997, 4532.38867188, 371.09371094), 'rotation':(0.02687, -90.045715, 0.026853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.8302343800001, 4638.84570312, 371.09257812000004), 'rotation':(-0.023773, -90.045563, -0.023804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.83460938000007, 4644.36476562, 371.09492187999996), 'rotation':(-0.024475, -90.045563, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.83898438000006, 4649.88378906, 371.09730469000004), 'rotation':(-0.024475, -90.045898, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.84343750000005, 4655.40234375, 371.09964844), 'rotation':(-0.024506, -90.045593, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.8522656199999, 4666.44042969, 371.10441405999995), 'rotation':(-0.024475, -90.045563, -0.024506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(254.85664062, 4671.95945312, 371.10675781), 'rotation':(-0.024506, -90.045898, -0.024536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.86101562, 4677.47851562, 371.10910156), 'rotation':(-0.024841, -90.045563, -0.024841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(254.86546875, 4682.99707031, 371.11074219), 'rotation':(-0.024841, -90.045563, -0.024841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.86984374999997, 4688.51513672, 371.11171875), 'rotation':(-0.012939, -90.045685, -0.012939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(254.8742968800001, 4694.03369141, 371.11078125), 'rotation':(0.009603, -90.045685, 0.00959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.87874999999997, 4699.55224609, 371.10917969), 'rotation':(0.020853, -90.045807, 0.02084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.88312499999995, 4705.07128906, 371.10714844), 'rotation':(0.021201, -90.045807, 0.021181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(254.88750000000005, 4710.59033203, 371.10511719000004), 'rotation':(0.020853, -90.045471, 0.020841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.546875, 4315.03515625, 371.22265625), 'rotation':(0.019323, 89.954323, 0.019316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.55562499999996, 4326.05710938, 371.22515625), 'rotation':(-0.008392, 89.95433, -0.008392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.56015624999998, 4331.56734375, 371.22453125), 'rotation':(-0.027344, 89.954239, -0.027374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.56445311999994, 4337.07765625, 371.22296875), 'rotation':(-0.027344, 89.954239, -0.027374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.56890625000005, 4342.58835938, 371.2203125), 'rotation':(-0.045868, 89.954361, -0.045929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.57328125000004, 4348.09863281, 371.21601562), 'rotation':(-0.055206, 89.954292, -0.055298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.58648438, 4364.63132812, 371.20054688), 'rotation':(-0.055206, 89.954384, -0.055298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.59531249999998, 4375.65382812, 371.19015625), 'rotation':(-0.048981, 89.954292, -0.049042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.60398438000004, 4386.67578125, 371.18085937999996), 'rotation':(-0.044739, 89.954407, -0.04483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.60843750000004, 4392.18703125, 371.17664062000006), 'rotation':(-0.040771, 89.954269, -0.040833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.57085938, 4429.558125, 371.15234375), 'rotation':(-0.034332, 89.954338, -0.034393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.5802343800001, 4434.964375, 371.1490625), 'rotation':(-0.033356, 89.954323, -0.033386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.59882812, 4445.776875, 371.14277344000004), 'rotation':(-0.031677, 89.954163, -0.031708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.60812499999997, 4451.18359375, 371.13980469), 'rotation':(-0.031006, 89.954323, -0.031036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.61742188000005, 4456.58984375, 371.136875), 'rotation':(-0.030762, 89.954361, -0.030792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.64546874999996, 4472.808125, 371.128125), 'rotation':(-0.032593, 89.954216, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.65476561999992, 4478.21386719, 371.12507812), 'rotation':(-0.032593, 89.954216, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.68273438000006, 4494.43261719, 371.11566406), 'rotation':(-0.035461, 89.9543, -0.035522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.69210938000003, 4499.83886719, 371.11234375), 'rotation':(-0.035461, 89.9543, -0.035522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.71578124999996, 4526.71484375, 371.09648438), 'rotation':(-0.026886, 89.954292, -0.026886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.72031249999998, 4532.39648438, 371.09371094), 'rotation':(-0.023438, 89.954285, -0.023468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.73390625000002, 4549.441875, 371.08683594), 'rotation':(-0.018646, 89.9543, -0.018677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.7428906199999, 4560.80566406, 371.083125), 'rotation':(-0.018646, 89.9543, -0.018677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.74742188000005, 4566.48730469, 371.08128905999996), 'rotation':(-0.018463, 89.954208, -0.018463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.75656249999997, 4577.85058594, 371.07757812000006), 'rotation':(-0.018646, 89.9543, -0.018677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.76101561999997, 4583.53273438, 371.07578125), 'rotation':(0.000888, 89.954285, 0.000886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.77468750000003, 4600.57910156, 371.07847655999996), 'rotation':(0.020033, 89.954254, 0.020028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(246.7791406199999, 4606.26074219, 371.08050781), 'rotation':(0.020033, 89.954254, 0.020028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(246.86234375000004, 4710.59814453, 371.10511719000004), 'rotation':(-0.02121, 89.954323, -0.02124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.85796875000005, 4705.07958984, 371.10714844), 'rotation':(-0.020844, 89.954369, -0.020874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.85359374999996, 4699.56152344, 371.10917969), 'rotation':(-0.021179, 89.95417, -0.02121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(246.84921874999998, 4694.04345703, 371.11078125), 'rotation':(-0.020844, 89.954361, -0.020874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.84476561999998, 4688.52490234, 371.11171875), 'rotation':(-0.009583, 89.9543, -0.009613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.84031249999998, 4683.00732422, 371.11074219), 'rotation':(0.012936, 89.954193, 0.012932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.83156250000002, 4666.45070312, 371.10441405999995), 'rotation':(0.0245, 89.954247, 0.024466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.82273438000004, 4660.93457031, 371.10203125), 'rotation':(0.0245, 89.954414, 0.024475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.81835938000006, 4655.41601562, 371.0996875), 'rotation':(0.024486, 89.954247, 0.02447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(246.80953124999996, 4644.37890625, 371.09492187999996), 'rotation':(0.0245, 89.954247, 0.024466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.80515624999998, 4638.86085938, 371.09257812000004), 'rotation':(0.0245, 89.954414, 0.024475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(246.80078125, 4633.34226562, 371.09027344000003), 'rotation':(0.023776, 89.954254, 0.023754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(468.95671875000005, 4605.76269531, 370.27242187999997), 'rotation':(0.014494, -90.270996, 0.014483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.90296875, 4594.3984375, 370.27542969), 'rotation':(0.016024, -90.271179, 0.016016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.87609375, 4588.71632812, 370.27699219000004), 'rotation':(0.018168, -90.270996, 0.01816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.8492578099999, 4583.03417969, 370.27882812), 'rotation':(0.020511, -90.270996, 0.020501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(468.82238281, 4577.3515625, 370.28070312000006), 'rotation':(0.020511, -90.270996, 0.020501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(468.79546875000005, 4571.66945312, 370.28273437999997), 'rotation':(0.022861, -90.27121, 0.022848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(468.74171875, 4560.3046875, 370.28726562), 'rotation':(0.024131, -90.270874, 0.024117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.68792969000003, 4548.94042969, 370.29203125), 'rotation':(0.026617, -90.271057, 0.026591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(468.63414062000004, 4537.57617188, 370.29761719000004), 'rotation':(0.036473, -90.271057, 0.036429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(468.60730469, 4531.89355469, 370.30097656), 'rotation':(0.036473, -90.271057, 0.036429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(468.5804296900001, 4526.21140625, 370.3046875), 'rotation':(0.04165, -90.271027, 0.041584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.45019531, 4709.87011719, 370.25234375), 'rotation':(0.010915, -90.271149, 0.01091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.42652344, 4704.36621094, 370.25339844), 'rotation':(0.010908, -90.270905, 0.01091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.40269531, 4698.86279297, 370.25449219), 'rotation':(0.010908, -90.270905, 0.01091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.35523437999996, 4687.85498047, 370.25660156), 'rotation':(0.010819, -90.271179, 0.010817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(469.30773437999994, 4676.84765625, 370.25859375), 'rotation':(0.010184, -90.271179, 0.01018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(469.28398438, 4671.34375, 370.25957030999996), 'rotation':(0.009863, -90.270874, 0.009857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(469.26023437999993, 4665.8403125, 370.26054688), 'rotation':(0.00987, -90.27121, 0.009864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(469.18898437999997, 4649.32910156, 370.26335937999994), 'rotation':(0.010273, -90.271149, 0.010267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(469.16523438, 4643.82519531, 370.26429687999996), 'rotation':(0.010273, -90.271149, 0.010267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(469.14148437999995, 4638.32179688, 370.2653125), 'rotation':(0.011509, -90.270935, 0.011514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.55542969, 4526.24953125, 370.3046875), 'rotation':(-0.036469, 89.728928, -0.03653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(460.58234374999995, 4531.93164062, 370.30097656), 'rotation':(-0.031555, 89.728943, -0.031586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.63609375, 4543.29640625, 370.29460937999994), 'rotation':(-0.026611, 89.728943, -0.026642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.66296875, 4548.97898438, 370.29203125), 'rotation':(-0.023865, 89.728851, -0.023895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.71671875000004, 4560.34328125, 370.28726562), 'rotation':(-0.022858, 89.728813, -0.022888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.74367187999997, 4566.02539062, 370.28496094), 'rotation':(-0.022858, 89.728813, -0.022888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.82421875, 4583.07226562, 370.27882812), 'rotation':(-0.018158, 89.729004, -0.018188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(460.85113280999997, 4588.75488281, 370.27699219000004), 'rotation':(-0.016022, 89.728783, -0.016022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(460.87800781, 4594.43703125, 370.27542969), 'rotation':(-0.015167, 89.728973, -0.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(460.90484375000005, 4600.11914062, 370.27386719000003), 'rotation':(-0.014496, 89.728996, -0.014496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(460.93175781, 4605.80125, 370.27242187999997), 'rotation':(-0.013824, 89.728996, -0.013824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(461.33113281, 4693.3984375, 370.25550781), 'rotation':(-0.010925, 89.729073, -0.010925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(461.08769530999996, 4649.36867188, 370.26335937999994), 'rotation':(-0.009674, 89.728973, -0.009674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(461.05726562000007, 4643.86476562, 370.26429687999996), 'rotation':(-0.009674, 89.728973, -0.009674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(460.99644531, 4632.85742188, 370.26640625), 'rotation':(-0.010284, 89.728844, -0.010284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1515.96558594, 4000.78835938, 360.75785156), 'rotation':(-0.6427, 0.007206, -0.657257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1513.3287500000001, 4006.36257812, 360.62074219000004), 'rotation':(-0.245544, -80.961365, -0.24765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1504.91003906, 4005.01804688, 360.62074219000004), 'rotation':(0.26997, 99.03846, 0.26743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1716.9056249999999, 4007.3125, 358.52128905999996), 'rotation':(-0.760651, -80.658356, -0.781036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1715.244375, 4017.3503124999997, 358.65773437999997), 'rotation':(-0.767151, -80.657257, -0.787903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1714.41359375, 4022.36914062, 358.72640625), 'rotation':(-0.772949, -80.658112, -0.794037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1713.58296875, 4027.38820312, 358.79539062000003), 'rotation':(-0.772949, -80.658112, -0.794037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1712.75242188, 4032.40695312, 358.86457031), 'rotation':(-0.779388, -80.657166, -0.800812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1711.9217187499999, 4037.42601562, 358.93402344000003), 'rotation':(-0.78241, -80.657898, -0.804016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1703.5084375000001, 4036.03195312, 358.93386719), 'rotation':(0.782145, 99.342094, 0.761017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1705.09289062, 4026.3896875, 358.80070312000004), 'rotation':(0.779393, 99.3423, 0.75841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1706.67734375, 4016.7473437500003, 358.6684375), 'rotation':(0.772959, 99.342651, 0.752303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1707.4696875, 4011.92601562, 358.60273437999996), 'rotation':(0.772959, 99.342651, 0.752303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1708.2618750000001, 4007.10523438, 358.53730469000004), 'rotation':(0.767126, 99.341705, 0.746785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1709.0540624999999, 4002.28367188, 358.47222655999997), 'rotation':(0.760767, 99.342239, 0.740773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1493.58972656, 4125.67671875, 361.73082030999996), 'rotation':(-0.769073, -80.585693, -0.789948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1495.40003906, 4114.745625, 361.58195312000004), 'rotation':(-0.749237, -80.587769, -0.769043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1497.2103124999999, 4103.81492188, 361.43894531), 'rotation':(-0.719116, -80.586487, -0.737335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1498.11546875, 4098.34859375, 361.36921875), 'rotation':(-0.701599, -80.58902, -0.718933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1499.02074219, 4092.88234375, 361.30183594000005), 'rotation':(-0.665009, -80.588196, -0.680573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1499.92601562, 4087.41625, 361.23800781), 'rotation':(-0.628326, -80.590698, -0.642242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1500.83117188, 4081.9496875, 361.17773437999995), 'rotation':(-0.592377, -80.591064, -0.604706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1501.73644531, 4076.48289062, 361.12101562000004), 'rotation':(-0.555725, -80.590515, -0.566589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1502.64171875, 4071.0168750000003, 361.06789062), 'rotation':(-0.519073, -80.592896, -0.528534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1504.4524999999999, 4060.08375, 360.97222655999997), 'rotation':(-0.446442, -80.593719, -0.453461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1505.35765625, 4054.61765625, 360.929375), 'rotation':(-0.428284, -80.593964, -0.434723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1506.2628125, 4049.15234375, 360.88796875), 'rotation':(-0.428314, -80.593658, -0.434753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1489.20484375, 4152.15328125, 362.11421875), 'rotation':(-0.841064, -80.584137, -0.866028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1487.40003906, 4163.05273438, 362.27847656), 'rotation':(-0.852966, -80.58429, -0.878662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1486.4971875, 4168.50296875, 362.36300781), 'rotation':(-0.877228, -80.583282, -0.904388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1485.59484375, 4173.95265625, 362.44804688), 'rotation':(-0.877228, -80.583282, -0.904388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1484.69238281, 4179.401875, 362.53496094), 'rotation':(-0.901489, -80.58255, -0.930206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1483.7899218799998, 4184.85203125, 362.62277344), 'rotation':(-0.901489, -80.58255, -0.930206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1482.8873437500001, 4190.30125, 362.71203125), 'rotation':(-0.925598, -80.581787, -0.955872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1481.98472656, 4195.7509375, 362.80199219), 'rotation':(-0.937836, -80.581787, -0.968933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1481.0825, 4201.1996875, 362.8925), 'rotation':(-0.938538, -80.580994, -0.969666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1478.37511719, 4217.54734375, 363.16484375), 'rotation':(-0.941895, -80.581635, -0.973267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1477.47277344, 4222.9965625, 363.25585937999995), 'rotation':(-0.943604, -80.581543, -0.975098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1474.76574219, 4239.34421875, 363.52992187999996), 'rotation':(-0.948486, -80.58139, -0.980316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1470.34007812, 4266.06789062, 363.97773437999996), 'rotation':(-0.939819, -80.581146, -0.971069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1468.48707031, 4277.25632812, 364.16289062000004), 'rotation':(-0.934204, -80.581909, -0.965027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1465.7076562500001, 4294.04, 364.4375), 'rotation':(-0.922394, -80.581726, -0.952484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1464.78113281, 4299.63429688, 364.52835938), 'rotation':(-0.919525, -80.582672, -0.949402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1462.92847656, 4310.82273438, 364.70726562000004), 'rotation':(-0.902588, -80.582214, -0.931396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1462.00195312, 4316.41703125, 364.795), 'rotation':(-0.891052, -80.583832, -0.919098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1460.14917969, 4327.60546875, 364.96699219000004), 'rotation':(-0.85733, -80.583588, -0.883301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1459.22265625, 4333.1996875, 365.05117187999997), 'rotation':(-0.845764, -80.585205, -0.871033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1457.36976562, 4344.38867188, 365.21652344), 'rotation':(-0.828888, -80.584656, -0.853149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1456.44324219, 4349.98339844, 365.29859375), 'rotation':(-0.828888, -80.584656, -0.853149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1497.85179688, 4047.76125, 360.88800781), 'rotation':(0.428294, 99.406059, 0.421918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1496.94652344, 4053.22703125, 360.92941406), 'rotation':(0.446448, 99.407555, 0.439535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1495.13574219, 4064.16039062, 361.01828125), 'rotation':(0.519067, 99.407097, 0.509733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1494.23035156, 4069.6276562499997, 361.06789062), 'rotation':(0.555725, 99.409454, 0.545022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1493.32496094, 4075.09445312, 361.12105469), 'rotation':(0.592362, 99.408936, 0.580214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1492.4196875, 4080.56179688, 361.1778125), 'rotation':(0.62833, 99.410553, 0.614663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1491.51402344, 4086.0285937500003, 361.23808594), 'rotation':(0.664994, 99.410545, 0.649688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1490.6087499999999, 4091.495625, 361.30191406), 'rotation':(0.701617, 99.4114, 0.684598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1489.70335938, 4096.96242188, 361.36933594000004), 'rotation':(0.719089, 99.413498, 0.701218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1488.79808594, 4102.42875, 361.43902344), 'rotation':(0.729696, 99.411697, 0.711288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1487.8928125, 4107.895, 361.50960938), 'rotation':(0.749279, 99.413765, 0.729884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1486.9876562499999, 4113.36085938, 361.58207031), 'rotation':(0.769018, 99.412727, 0.748581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1486.08238281, 4118.82664062, 361.65585938), 'rotation':(0.788853, 99.414848, 0.767349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1485.17726562, 4124.29296875, 361.7309375), 'rotation':(0.788853, 99.414848, 0.767349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1466.35265625, 4237.961875, 363.53011719), 'rotation':(0.949943, 99.41864, 0.918822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1469.05980469, 4221.61421875, 363.25605469000004), 'rotation':(0.945428, 99.419243, 0.914594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1469.96214844, 4216.165, 363.16496094), 'rotation':(0.943611, 99.419563, 0.912908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1470.86460938, 4210.71578125, 363.07410156), 'rotation':(0.943611, 99.419563, 0.912908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1472.66957031, 4199.81734375, 362.89265625), 'rotation':(0.940148, 99.418312, 0.90968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1474.47472656, 4188.91890625, 362.71222656), 'rotation':(0.937846, 99.41819, 0.907513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1475.37707031, 4183.4696875, 362.62296875), 'rotation':(0.925607, 99.418213, 0.896054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1476.27964844, 4178.01953125, 362.53511719), 'rotation':(0.925607, 99.418213, 0.896054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1477.18210938, 4172.5703125, 362.44816405999995), 'rotation':(0.901537, 99.417908, 0.873501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1478.08460938, 4167.120625, 362.36320312000004), 'rotation':(0.901537, 99.417908, 0.873501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1479.88964844, 4156.22070312, 362.19636719000005), 'rotation':(0.852927, 99.41597, 0.82782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1480.79210938, 4150.77101562, 362.114375), 'rotation':(0.852927, 99.41597, 0.82782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1448.0321093799998, 4348.59179688, 365.29863280999996), 'rotation':(0.829082, 99.414742, 0.805344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1448.95851562, 4342.99757812, 365.2165625), 'rotation':(0.829082, 99.414742, 0.805344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1450.81128906, 4331.80953125, 365.05121094000003), 'rotation':(0.834847, 99.414467, 0.810778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1451.7376562499999, 4326.21578125, 364.96699219000004), 'rotation':(0.84583, 99.416878, 0.82113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1453.5903125, 4315.02828125, 364.79507812), 'rotation':(0.880131, 99.415817, 0.853399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1455.443125, 4303.84132812, 364.61851562000004), 'rotation':(0.902603, 99.416504, 0.874489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1456.369375, 4298.24757812, 364.5284375), 'rotation':(0.913838, 99.418152, 0.885028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1458.2221875, 4287.05953125, 364.34636719), 'rotation':(0.922417, 99.418274, 0.89306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1459.14855469, 4281.46578125, 364.25488280999997), 'rotation':(0.922417, 99.418274, 0.89306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1461.92773438, 4264.6840625, 363.97789062000004), 'rotation':(0.93424, 99.418663, 0.904136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1297.29761719, 4088.56054688, 363.7721875), 'rotation':(0.06406, -80.475769, 0.06392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1298.19787109, 4083.19507812, 363.778125), 'rotation':(0.053617, -80.474426, 0.053521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1300.89880859, 4067.09789062, 363.79238281), 'rotation':(0.04887, -80.475861, 0.048775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1302.69945312, 4056.36625, 363.80167969), 'rotation':(0.04887, -80.474731, 0.048778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1303.59972656, 4051.00023438, 363.80628906), 'rotation':(0.04887, -80.474731, 0.048778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1304.5, 4045.6354687499997, 363.81058594), 'rotation':(0.018783, -80.475555, 0.018758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1309.90125, 4013.44382812, 363.78191405999996), 'rotation':(-0.071777, -80.475128, -0.07196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1290.15857422, 4131.10890625, 363.6903125), 'rotation':(0.129664, -80.475006, 0.129075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1289.244375, 4136.55765625, 363.67941406), 'rotation':(0.106551, -80.474335, 0.106153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1288.33007812, 4142.00585938, 363.67054687999996), 'rotation':(0.083718, -80.474396, 0.083472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1287.41578125, 4147.45460938, 363.66375), 'rotation':(0.060591, -80.47641, 0.060462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1286.50158203, 4152.9028125, 363.6584375), 'rotation':(0.060591, -80.47641, 0.060462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1285.58765625, 4158.350625, 363.65371094), 'rotation':(0.049061, -80.475189, 0.048989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1284.67333984, 4163.79984375, 363.64929687999995), 'rotation':(0.049341, -80.474487, 0.049247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1283.75927734, 4169.24757812, 363.64734375), 'rotation':(0.020634, -80.475708, 0.020616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1281.93029297, 4180.1475, 363.65886719), 'rotation':(-0.093689, -80.474792, -0.093994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1281.01585938, 4185.59765625, 363.67179688), 'rotation':(-0.151123, -80.475281, -0.151917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1280.09960938, 4191.04734375, 363.68957030999997), 'rotation':(-0.208008, -80.474213, -0.209503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1279.18701172, 4196.49703125, 363.71207031), 'rotation':(-0.208008, -80.474213, -0.209503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1278.27246094, 4201.94679688, 363.73929688), 'rotation':(-0.265442, -80.473724, -0.267914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1272.8907421899999, 4234.0190625, 363.98144530999997), 'rotation':(-0.545013, -80.46933, -0.55545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1271.03064453, 4245.10546875, 364.10273437999996), 'rotation':(-0.630707, -80.468445, -0.644714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1270.10095703, 4250.64601562, 364.17300781), 'rotation':(-0.716125, -80.466125, -0.734192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1268.24097656, 4261.7309375, 364.32917969000005), 'rotation':(-0.802063, -80.464142, -0.824768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1267.31140625, 4267.27046875, 364.41132812), 'rotation':(-0.840149, -80.462463, -0.865051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1266.38195312, 4272.81054688, 364.49257812), 'rotation':(-0.831268, -80.463928, -0.855652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1265.45238281, 4278.35007812, 364.57304688), 'rotation':(-0.822388, -80.462982, -0.846252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1262.66382812, 4294.96921875, 364.80914062000005), 'rotation':(-0.795746, -80.464935, -0.818085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1260.8048046899999, 4306.04929688, 364.96234375), 'rotation':(-0.777985, -80.464203, -0.799316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1259.87523438, 4311.58984375, 365.03820312000005), 'rotation':(-0.773499, -80.464722, -0.794586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1258.94568359, 4317.12984375, 365.1140625), 'rotation':(-0.773499, -80.464722, -0.794586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1287.98804688, 4092.52414062, 363.76523438), 'rotation':(-0.083557, 99.524269, -0.083801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1288.88830078, 4087.1584375, 363.7721875), 'rotation':(-0.073822, 99.52562, -0.074005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1289.78857422, 4081.79273438, 363.778125), 'rotation':(-0.064056, 99.523758, -0.064209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1290.68896484, 4076.42648438, 363.783125), 'rotation':(-0.053619, 99.525574, -0.053711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1291.58935547, 4071.06007812, 363.78773437999996), 'rotation':(-0.048859, 99.524132, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1292.48974609, 4065.69359375, 363.79238281), 'rotation':(-0.048859, 99.524132, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1293.39013672, 4060.32742188, 363.79703125), 'rotation':(-0.048859, 99.525238, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1294.29052734, 4054.9609375, 363.80167969), 'rotation':(-0.048859, 99.524956, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1296.09130859, 4044.22898438, 363.81058594), 'rotation':(-0.048859, 99.524956, -0.04895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1296.99169922, 4038.8628125, 363.81238281), 'rotation':(-0.018768, 99.524796, -0.018799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1298.79175781, 4028.13328125, 363.80238281), 'rotation':(0.072052, 99.524864, 0.071871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1299.69226562, 4022.7668750000003, 363.79554687999996), 'rotation':(0.071772, 99.524506, 0.071601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1268.94847656, 4205.99609375, 363.77140625), 'rotation':(0.379738, 99.527542, 0.374731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1270.77734375, 4195.09671875, 363.71210937999996), 'rotation':(0.265435, 99.526268, 0.262983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1272.60632812, 4184.19679688, 363.67183594), 'rotation':(0.207993, 99.525787, 0.206492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1275.34972656, 4167.8471875, 363.64730469), 'rotation':(0.036808, 99.525055, 0.036758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1276.26378906, 4162.399375, 363.64929687999995), 'rotation':(-0.02063, 99.5243, -0.02066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1278.09203125, 4151.50296875, 363.6584375), 'rotation':(-0.049072, 99.524796, -0.049164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1279.92029297, 4140.6059375, 363.67054687999996), 'rotation':(-0.060577, 99.523598, -0.060699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1280.83472656, 4135.15773438, 363.67941406), 'rotation':(-0.08371, 99.525581, -0.083954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1281.74890625, 4129.70898438, 363.69027344), 'rotation':(-0.106537, 99.524887, -0.106934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1283.57703125, 4118.8134375, 363.71617188), 'rotation':(-0.136139, 99.525787, -0.13678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1252.39648438, 4304.64109375, 364.96238281), 'rotation':(0.773485, 99.53524, 0.752809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1254.25525391, 4293.5625, 364.80921875), 'rotation':(0.786858, 99.534813, 0.765458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1257.04333984, 4276.94484375, 364.57308594), 'rotation':(0.813489, 99.536766, 0.790633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1257.97289062, 4271.40578125, 364.49269531), 'rotation':(0.822382, 99.535805, 0.799015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1258.9022265600001, 4265.86671875, 364.41144531), 'rotation':(0.831254, 99.53727, 0.807394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1259.83166016, 4260.3271875, 364.32929687999996), 'rotation':(0.840147, 99.537521, 0.815765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1261.69140625, 4249.24367188, 364.173125), 'rotation':(0.802062, 99.535851, 0.779831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1262.6209765600001, 4243.70359375, 364.10289062000004), 'rotation':(0.716125, 99.533859, 0.698385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1105.33507812, 4002.26171875, 367.14648437999995), 'rotation':(0.121987, -80.972778, 0.121465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1104.48572266, 4007.6081249999997, 367.13460938), 'rotation':(0.12629, -80.973419, 0.125738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1103.63647461, 4012.9540625, 367.12234375), 'rotation':(0.130477, -80.973389, 0.129893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1101.93798828, 4023.64671875, 367.09675781), 'rotation':(0.138216, -80.972961, 0.13756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1100.239375, 4034.33914062, 367.06960938), 'rotation':(0.145633, -80.973145, 0.144896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1099.39001953, 4039.6848437500003, 367.0553125), 'rotation':(0.145633, -80.973145, 0.144896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1098.54077148, 4045.03125, 367.04054687999997), 'rotation':(0.156589, -80.973083, 0.155744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1097.69152344, 4050.37742188, 367.02492187999997), 'rotation':(0.156589, -80.973083, 0.155744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1096.84240234, 4055.723125, 367.0090625), 'rotation':(0.16736, -80.973022, 0.166392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1090.89685547, 4093.23875, 366.88300781), 'rotation':(0.207248, -80.973328, 0.205746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1090.02917969, 4098.6953125, 366.86253905999996), 'rotation':(0.214632, -80.972534, 0.213019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1088.29394531, 4109.60742188, 366.81996094000004), 'rotation':(0.221749, -80.972137, 0.220044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1086.55847656, 4120.52046875, 366.77648437999994), 'rotation':(0.22526, -80.97229, 0.223505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1084.82299805, 4131.433125, 366.73296875), 'rotation':(0.225861, -80.973175, 0.224088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1082.2199707, 4147.80226562, 366.6671875), 'rotation':(0.227589, -80.97287, 0.225788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1080.48449707, 4158.714375, 366.62324219000004), 'rotation':(0.227794, -80.972107, 0.225981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1079.61694336, 4164.1709375, 366.60074219), 'rotation':(0.231612, -80.972809, 0.229735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1078.74914551, 4169.62648438, 366.57753906), 'rotation':(0.239753, -80.972717, 0.237755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1073.63928223, 4201.78664062, 366.42644530999996), 'rotation':(0.278412, -80.971893, 0.275715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1072.75402832, 4207.35984375, 366.39769530999996), 'rotation':(0.292216, -80.972137, 0.289256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1071.86865234, 4212.93265625, 366.36792969000004), 'rotation':(0.292216, -80.972137, 0.289256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1070.09802246, 4224.0790625, 366.3028125), 'rotation':(0.347069, -80.971527, 0.342891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1069.21276855, 4229.651875, 366.26804688), 'rotation':(0.347069, -80.971527, 0.342891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1068.32739258, 4235.22507812, 366.23121094000004), 'rotation':(0.374383, -80.971161, 0.369524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1067.4420166, 4240.79882812, 366.19386719), 'rotation':(0.381166, -80.970886, 0.376118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1065.67089844, 4251.94726562, 366.12195312000006), 'rotation':(0.352916, -80.972076, 0.348597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1064.78540039, 4257.52148438, 366.08808594000004), 'rotation':(0.339133, -80.972229, 0.335134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1063.01428223, 4268.66992188, 366.02449219000005), 'rotation':(0.310951, -80.971771, 0.307591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1061.24328613, 4279.81835938, 365.9665625), 'rotation':(0.282722, -80.972839, 0.279945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1060.35778809, 4285.39257812, 365.93914062000005), 'rotation':(0.282722, -80.972839, 0.279945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1095.87414062, 4007.48023438, 367.13191406), 'rotation':(-0.130493, 99.026581, -0.131073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1095.04431641, 4012.70382812, 367.11984375), 'rotation':(-0.134338, 99.026619, -0.134979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1094.21435547, 4017.92820312, 367.10746094), 'rotation':(-0.138214, 99.028313, -0.138885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1092.55493164, 4028.37429688, 367.0815625), 'rotation':(-0.14563, 99.026848, -0.146362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1090.89550781, 4038.82078125, 367.05402344000004), 'rotation':(-0.156586, 99.026901, -0.15744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1090.06554688, 4044.04445312, 367.03953125), 'rotation':(-0.167358, 99.02697, -0.168335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1089.23583984, 4049.2678125, 367.02425781), 'rotation':(-0.167358, 99.02697, -0.168335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1087.56970703, 4059.7160937500003, 366.99226562), 'rotation':(-0.183655, 99.025673, -0.184845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1069.46325684, 4173.734375, 366.55363280999995), 'rotation':(-0.255768, 99.027382, -0.258057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1070.32897949, 4168.27734375, 366.57761719), 'rotation':(-0.24762, 99.027328, -0.249756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1071.19470215, 4162.8203125, 366.60078125), 'rotation':(-0.239746, 99.027252, -0.24176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1072.06030273, 4157.36328125, 366.62328125), 'rotation':(-0.231598, 99.027191, -0.23349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1072.92602539, 4151.90671875, 366.6453125), 'rotation':(-0.231598, 99.027191, -0.23349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1074.65734863, 4140.9921875, 366.68921875), 'rotation':(-0.22757, 99.026634, -0.229401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1075.52307129, 4135.53515625, 366.71113281), 'rotation':(-0.22757, 99.026634, -0.229401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1076.38879395, 4130.07765625, 366.73304687999996), 'rotation':(-0.226898, 99.028145, -0.228699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1077.2545166, 4124.620625, 366.75480469), 'rotation':(-0.225861, 99.02681, -0.227631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1078.98596191, 4113.70609375, 366.79828125), 'rotation':(-0.22525, 99.027138, -0.22702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1079.8515625, 4108.2490625, 366.82003906), 'rotation':(-0.22525, 99.027702, -0.227051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1080.71728516, 4102.79203125, 366.8415625), 'rotation':(-0.221741, 99.027176, -0.22345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1081.58288574, 4097.335, 366.86261719000004), 'rotation':(-0.221741, 99.027176, -0.22345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1051.93835449, 4284.05320312, 365.93917969), 'rotation':(-0.275909, 99.027428, -0.278595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1053.70959473, 4272.90382812, 365.99488281), 'rotation':(-0.282745, 99.027939, -0.285553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1054.59521484, 4267.3290625, 366.02453125), 'rotation':(-0.29715, 99.028534, -0.300232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1055.48083496, 4261.754375, 366.05558594), 'rotation':(-0.310944, 99.027435, -0.314331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1056.36645508, 4256.1796875, 366.08808594000004), 'rotation':(-0.325043, 99.027596, -0.328735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1057.25195312, 4250.605, 366.12199219), 'rotation':(-0.339172, 99.029785, -0.343201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1058.13769531, 4245.0303125, 366.15726562000003), 'rotation':(-0.352936, 99.027931, -0.3573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1059.02331543, 4239.45507812, 366.19394531), 'rotation':(-0.367035, 99.029343, -0.371765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1064.33581543, 4206.01320312, 366.39777344000004), 'rotation':(-0.31955, 99.02816, -0.32312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1065.22119141, 4200.43945312, 366.42652344000004), 'rotation':(-0.292236, 99.027863, -0.295197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1041.38195801, 4398.84667969, 365.943125), 'rotation':(-0.268158, -80.481445, -0.270691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1043.21838379, 4387.89304688, 365.89484375), 'rotation':(-0.209351, -80.481934, -0.210876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1044.13647461, 4382.41796875, 365.87457030999997), 'rotation':(-0.150543, -80.481049, -0.151337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1045.9732666, 4371.46289062, 365.84628906), 'rotation':(-0.121277, -80.483002, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1047.80932617, 4360.51074219, 365.82277344), 'rotation':(-0.121033, -80.481995, -0.121552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1048.72741699, 4355.035625, 365.81101562000003), 'rotation':(-0.121277, -80.483002, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1049.64550781, 4349.55957031, 365.79929688), 'rotation':(-0.121277, -80.483002, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1051.48266602, 4338.60351562, 365.79160156), 'rotation':(0.11739, -80.482971, 0.116919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1035.15490723, 4435.98828125, 366.20332031), 'rotation':(-0.460419, -80.478149, -0.467865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1034.25793457, 4441.33789062, 366.25089844), 'rotation':(-0.498535, -80.478424, -0.507294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1033.36132812, 4446.68652344, 366.30171875), 'rotation':(-0.536865, -80.478333, -0.546997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1031.56762695, 4457.38429688, 366.40996094), 'rotation':(-0.574982, -80.476074, -0.586609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1030.67102051, 4462.73242188, 366.46617188), 'rotation':(-0.594299, -80.476868, -0.60672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1029.77441406, 4468.08054688, 366.5234375), 'rotation':(-0.606232, -80.475494, -0.619171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1028.87744141, 4473.42921875, 366.58289062000006), 'rotation':(-0.631012, -80.476257, -0.64502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1027.08398438, 4484.12742188, 366.70878905999996), 'rotation':(-0.679871, -80.475159, -0.696167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1025.29052734, 4494.82519531, 366.84410155999996), 'rotation':(-0.728729, -80.473938, -0.747467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1022.6003418, 4510.87011719, 367.06347655999997), 'rotation':(-0.790131, -80.471222, -0.812164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1021.70385742, 4516.21777344, 367.13828125), 'rotation':(-0.790131, -80.471222, -0.812164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1032.05700684, 4402.90773438, 365.97289062000004), 'rotation':(0.327166, 99.519157, 0.323446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1032.97521973, 4397.4296875, 365.94304687999994), 'rotation':(0.327166, 99.519157, 0.323446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1033.89318848, 4391.95507812, 365.91707031), 'rotation':(0.268174, 99.518547, 0.265668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1034.81152344, 4386.47703125, 365.89484375), 'rotation':(0.268174, 99.518547, 0.265668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1035.7298584, 4381.00148438, 365.87453125), 'rotation':(0.209366, 99.518059, 0.20783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1037.56640625, 4370.04785156, 365.84628906), 'rotation':(0.150551, 99.518204, 0.149759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1039.40234375, 4359.09667969, 365.82273438), 'rotation':(0.121297, 99.516975, 0.12078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1040.3203125, 4353.6215625, 365.81101562000003), 'rotation':(0.121031, 99.517982, 0.12053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1041.23828125, 4348.14648438, 365.79929688), 'rotation':(0.121031, 99.517982, 0.12053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1042.15698242, 4342.66648438, 365.79179688), 'rotation':(0.121304, 99.517647, 0.120784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1043.07519531, 4337.1909375, 365.79160156), 'rotation':(0.001858, 99.517586, 0.001862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1043.99401855, 4331.71046875, 365.79921875), 'rotation':(-0.117401, 99.517029, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1044.9119873, 4326.23585938, 365.81058594), 'rotation':(-0.117401, 99.517876, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1045.82995605, 4320.76023438, 365.82195312000005), 'rotation':(-0.117401, 99.517876, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1014.19256592, 4509.45898438, 367.0634375), 'rotation':(0.789884, 99.528297, 0.768322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1015.98614502, 4498.76074219, 366.91515625), 'rotation':(0.777924, 99.527992, 0.757006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1016.88305664, 4493.41210938, 366.84402344), 'rotation':(0.753172, 99.527321, 0.733559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1017.77984619, 4488.0625, 366.77519530999996), 'rotation':(0.728733, 99.526695, 0.71037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1018.67669678, 4482.71335938, 366.70875), 'rotation':(0.704561, 99.52523, 0.687393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1020.47039795, 4472.01414062, 366.5828125), 'rotation':(0.655111, 99.52491, 0.640259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1021.36737061, 4466.66503906, 366.52335938), 'rotation':(0.630993, 99.524376, 0.617213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1023.16082764, 4455.96875, 366.40988281), 'rotation':(0.594295, 99.52359, 0.58206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1024.95458984, 4445.26953125, 366.30167969), 'rotation':(0.574999, 99.523468, 0.563539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1026.74829102, 4434.57128906, 366.20328125), 'rotation':(0.498556, 99.521591, 0.489922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1437.0711718799998, 4468.0546875, 366.83863281), 'rotation':(-0.703674, -80.722046, -0.72113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1439.70835938, 4451.89550781, 366.6378125), 'rotation':(-0.697571, -80.723358, -0.714752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1440.58753906, 4446.50878906, 366.57136719000005), 'rotation':(-0.693451, -80.722717, -0.710388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1441.4665625, 4441.12207031, 366.50496094000005), 'rotation':(-0.693451, -80.722717, -0.710388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1443.22472656, 4430.34914062, 366.37296875), 'rotation':(-0.689545, -80.723053, -0.706268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1444.10203125, 4424.97507812, 366.30742188), 'rotation':(-0.4422, -81.115906, -0.449097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1444.98277344, 4419.57617188, 366.24132812000005), 'rotation':(-0.70343, -80.723572, -0.720856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1445.86195312, 4414.18992188, 366.17457031), 'rotation':(-0.714813, -80.721191, -0.732849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1446.74085938, 4408.80371094, 366.10671875), 'rotation':(-0.72525, -80.722198, -0.743774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1447.61988281, 4403.4175, 366.03789062000004), 'rotation':(-0.736206, -80.722717, -0.75531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1449.37792969, 4392.64550781, 365.8971875), 'rotation':(-0.757629, -80.722168, -0.777863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1441.84253906, 4385.8871875, 365.82527344000005), 'rotation':(0.7577, 99.279884, 0.737856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1440.96351562, 4391.27296875, 365.8971875), 'rotation':(0.747236, 99.277542, 0.727926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1440.08445312, 4396.65917969, 365.96804688), 'rotation':(0.736267, 99.278076, 0.717526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1439.20542969, 4402.04492188, 366.03789062000004), 'rotation':(0.725168, 99.278236, 0.70699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1437.44761719, 4412.81738281, 366.17457031), 'rotation':(0.703489, 99.278511, 0.68636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1435.68945312, 4423.58984375, 366.30726562), 'rotation':(0.689487, 99.277184, 0.673052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1434.81042969, 4428.9765625, 366.37296875), 'rotation':(0.693449, 99.27655, 0.676814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1433.05226562, 4439.74953125, 366.50496094000005), 'rotation':(0.697615, 99.27787, 0.680795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1432.17320312, 4445.13625, 366.57132812000003), 'rotation':(0.697615, 99.27787, 0.680795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1430.41503906, 4455.90917969, 366.7046875), 'rotation':(0.70368, 99.277, 0.686549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1428.6568750000001, 4466.68210938, 366.83863281), 'rotation':(0.703667, 99.277939, 0.686549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1636.99046875, 4496.8403125, 365.3165625), 'rotation':(-0.729065, -80.819641, -0.747803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1637.8678125000001, 4491.40625, 365.24644530999996), 'rotation':(-0.738403, -80.81897, -0.757599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1638.74511719, 4485.973125, 365.17550781), 'rotation':(-0.747803, -80.820007, -0.767517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1641.37683594, 4469.67089844, 364.95695312000004), 'rotation':(-0.776306, -80.819214, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1642.25414062, 4464.23632812, 364.88226562000006), 'rotation':(-0.781311, -80.818787, -0.802856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1644.00878906, 4453.36765625, 364.73164062), 'rotation':(-0.79364, -80.819031, -0.815826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1644.8860937499999, 4447.93359375, 364.655625), 'rotation':(-0.79364, -80.819031, -0.815826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1647.51792969, 4431.63085938, 364.4246875), 'rotation':(-0.809845, -80.818054, -0.832977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1648.39527344, 4426.19726562, 364.34679687999994), 'rotation':(-0.814117, -80.817566, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1649.2725781200002, 4420.76269531, 364.26855469000003), 'rotation':(-0.814087, -80.818115, -0.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1650.14992188, 4415.328125, 364.19035155999995), 'rotation':(-0.814087, -80.818115, -0.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1618.41136719, 4611.92578125, 366.78183594), 'rotation':(-0.757202, -80.81958, -0.777405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1619.3053125000001, 4606.38867188, 366.70765625), 'rotation':(-0.757202, -80.81958, -0.777405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1621.0931249999999, 4595.31445312, 366.56003906), 'rotation':(-0.741821, -80.819702, -0.76123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1621.98707031, 4589.776875, 366.48707031), 'rotation':(-0.741821, -80.819702, -0.76123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1622.88085938, 4584.24023438, 366.41441405999996), 'rotation':(-0.731323, -80.819946, -0.750183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1623.77492188, 4578.70265625, 366.3428125), 'rotation':(-0.721008, -80.820221, -0.739319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1625.56273438, 4567.62695312, 366.2009375), 'rotation':(-0.715881, -80.819427, -0.733948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1627.3507031200002, 4556.55320312, 366.06070312), 'rotation':(-0.713318, -80.820557, -0.731232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1629.1384375, 4545.47898438, 365.92132812000006), 'rotation':(-0.708405, -80.820984, -0.726074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1630.03234375, 4539.9409375, 365.85203125), 'rotation':(-0.703857, -80.820282, -0.721313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1631.8201953100001, 4528.86671875, 365.71449219000004), 'rotation':(-0.6987, -80.820435, -0.715912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1641.73328125, 4413.96921875, 364.19035155999995), 'rotation':(0.814124, 99.182434, 0.791236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1640.8559375, 4419.40382812, 364.26855469000003), 'rotation':(0.814124, 99.182434, 0.791236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1639.97863281, 4424.83789062, 364.34679687999994), 'rotation':(0.809821, 99.181931, 0.787175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1639.1014453100001, 4430.27246094, 364.4246875), 'rotation':(0.801646, 99.182541, 0.779446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1633.83777344, 4462.87742188, 364.88226562000006), 'rotation':(0.776306, 99.180756, 0.755472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1631.20582031, 4479.1796875, 365.10359375), 'rotation':(0.747783, 99.18, 0.728453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1630.3284765600001, 4484.61476562, 365.17550781), 'rotation':(0.738384, 99.181038, 0.719545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1629.45128906, 4490.04882812, 365.24648437999997), 'rotation':(0.729054, 99.180351, 0.710679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1628.57398438, 4495.48195312, 365.3165625), 'rotation':(0.719274, 99.17926, 0.701382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1627.69679688, 4500.91601562, 365.38566405999995), 'rotation':(0.709486, 99.179474, 0.692077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1609.9947656200002, 4610.5659375, 366.78179687999994), 'rotation':(0.757434, 99.180435, 0.737604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1610.88867188, 4605.02882812, 366.70765625), 'rotation':(0.757434, 99.180435, 0.737604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1612.67652344, 4593.95460938, 366.56003906), 'rotation':(0.752154, 99.18058, 0.732592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1613.5703125, 4588.41699219, 366.48707031), 'rotation':(0.752154, 99.18058, 0.732592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1615.35828125, 4577.34277344, 366.3428125), 'rotation':(0.731322, 99.180023, 0.712831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1616.2521875, 4571.80515625, 366.2715625), 'rotation':(0.731322, 99.180023, 0.712831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1618.03980469, 4560.7309375, 366.13070312), 'rotation':(0.721015, 99.179779, 0.703029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1620.72179688, 4544.11960938, 365.92132812000006), 'rotation':(0.713304, 99.179436, 0.695706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1621.61570312, 4538.58203125, 365.85203125), 'rotation':(0.7084, 99.179024, 0.691043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1623.40355469, 4527.50828125, 365.71449219000004), 'rotation':(0.703844, 99.179703, 0.686711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1834.7790625, 4535.10839844, 363.38140625), 'rotation':(-0.834045, -80.115082, -0.858582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1835.70859375, 4529.76757812, 363.30589844), 'rotation':(-0.834045, -80.115082, -0.858582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1837.568125, 4519.08351562, 363.1459375), 'rotation':(-0.879333, -80.11322, -0.906647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1839.42734375, 4508.39992188, 362.97625), 'rotation':(-0.924774, -80.111755, -0.955017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1840.35726562, 4503.05710938, 362.88871094), 'rotation':(-0.928131, -80.112488, -0.958588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1841.2875, 4497.71335938, 362.80101562000004), 'rotation':(-0.889923, -80.113678, -0.917877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1844.07773438, 4481.68117188, 362.56074219000004), 'rotation':(-0.775299, -80.116089, -0.796509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1845.0080468800002, 4476.33640625, 362.48820312000004), 'rotation':(-0.73764, -80.117981, -0.756836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1846.86828125, 4465.64796875, 362.35449219000003), 'rotation':(-0.660889, -80.118958, -0.6763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1848.728125, 4454.9609375, 362.231875), 'rotation':(-0.641907, -80.119781, -0.656433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1816.0310156199998, 4642.83105469, 364.67191406), 'rotation':(-0.593842, -80.121521, -0.606262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1817.9225781199998, 4631.96242188, 364.55753905999995), 'rotation':(-0.593567, -80.120605, -0.605957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1818.86828125, 4626.5278125, 364.50007812), 'rotation':(-0.603729, -80.120422, -0.616547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1819.8140625, 4621.09375, 364.44191406), 'rotation':(-0.623688, -80.120544, -0.63739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1820.75960938, 4615.6596875, 364.38226562000006), 'rotation':(-0.643738, -80.119537, -0.658325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1821.7053125, 4610.2265625, 364.32171875), 'rotation':(-0.643738, -80.119537, -0.658325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1822.65109375, 4604.79199219, 364.25972656), 'rotation':(-0.663696, -80.119629, -0.679199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1825.4884375000001, 4588.49070312, 364.0671875), 'rotation':(-0.680939, -80.118042, -0.697266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1826.4342187500001, 4583.05617188, 364.00160156), 'rotation':(-0.695679, -80.118958, -0.712738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1827.37984375, 4577.62257812, 363.93464844000005), 'rotation':(-0.7099, -80.118103, -0.727661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1828.32554688, 4572.18898438, 363.8671875), 'rotation':(-0.7099, -80.118103, -0.727661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1829.27132812, 4566.75488281, 363.79882812000005), 'rotation':(-0.724609, -80.118256, -0.743134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1841.2585156199998, 4448.15867188, 362.17113280999996), 'rotation':(0.641908, 99.880219, 0.627649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1839.39804688, 4458.84765625, 362.29273437999996), 'rotation':(0.660834, 99.880096, 0.645727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1837.5375, 4469.53859375, 362.41957031), 'rotation':(0.73766, 99.881996, 0.718849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1836.60703125, 4474.88476562, 362.48835937999996), 'rotation':(0.775226, 99.882988, 0.754448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1834.74609375, 4485.57570312, 362.6371875), 'rotation':(0.852025, 99.885162, 0.826959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1832.88515625, 4496.26757812, 362.80125), 'rotation':(0.928127, 99.888863, 0.898419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1831.9546875, 4501.61328125, 362.88902344), 'rotation':(0.924773, 99.887482, 0.895275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1831.02476562, 4506.9565625, 362.9765625), 'rotation':(0.879284, 99.886269, 0.852596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1830.095, 4512.29929688, 363.06300781), 'rotation':(0.879284, 99.886269, 0.852596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1829.16492188, 4517.64355469, 363.14628905999996), 'rotation':(0.834068, 99.885437, 0.810045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1826.3751562500001, 4533.67285156, 363.38175780999995), 'rotation':(0.788941, 99.884384, 0.767441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1821.81335938, 4559.88574219, 363.72984375), 'rotation':(0.709896, 99.881897, 0.692463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1817.0860937500001, 4587.04734375, 364.06738280999997), 'rotation':(0.674133, 99.878708, 0.658413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1816.1404687499999, 4592.48, 364.13269531), 'rotation':(0.663724, 99.88092, 0.648474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1815.1951562499999, 4597.91210938, 364.19664062000004), 'rotation':(0.643718, 99.88047, 0.62938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1814.2497656199998, 4603.34421875, 364.25992188), 'rotation':(0.643718, 99.88047, 0.62938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1812.3587499999999, 4614.20898438, 364.38234375), 'rotation':(0.623692, 99.879463, 0.610218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1811.4133593800002, 4619.64160156, 364.44203125), 'rotation':(0.603727, 99.879593, 0.591112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1810.46789062, 4625.07421875, 364.50011719), 'rotation':(0.593502, 99.878479, 0.58131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1808.576875, 4635.93945312, 364.61476562), 'rotation':(0.593905, 99.879425, 0.581686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1807.63125, 4641.37207031, 364.67191406), 'rotation':(0.593557, 99.879402, 0.581366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.3899999999999, 4856.73095703, 364.2190625), 'rotation':(-0.277313, -90.229706, -0.280029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.3444531199998, 4845.44726562, 364.16460937999994), 'rotation':(-0.283173, -90.229675, -0.286011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.32164062, 4839.8046875, 364.13675781), 'rotation':(-0.2854, -90.229248, -0.288269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.29882812, 4834.16308594, 364.10859375), 'rotation':(-0.289642, -90.229889, -0.292572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.27601562, 4828.52099609, 364.08007812000005), 'rotation':(-0.296875, -90.229797, -0.299988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.2532812499999, 4822.87890625, 364.05101562000004), 'rotation':(-0.304169, -90.229736, -0.307404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.23046875, 4817.23730469, 364.02144531), 'rotation':(-0.304169, -90.229736, -0.307404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.2077343800001, 4811.59521484, 363.99140625), 'rotation':(-0.311859, -90.229645, -0.315277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.18507812, 4805.953125, 363.96070312000006), 'rotation':(-0.315582, -90.229156, -0.319061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.13953125, 4794.66943359, 363.8984375), 'rotation':(-0.320679, -90.229309, -0.32428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.0939843800002, 4783.38623047, 363.83296875), 'rotation':(-0.353516, -90.228882, -0.35788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.07117188, 4777.74462891, 363.79847656), 'rotation':(-0.364594, -90.230164, -0.369232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.04859375, 4772.10253906, 363.76277344000005), 'rotation':(-0.375305, -90.228638, -0.380249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.00304688, 4760.81982422, 363.68769531), 'rotation':(-0.397125, -90.228333, -0.402679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1966.9802343800002, 4755.17773438, 363.64851562), 'rotation':(-0.402832, -90.228302, -0.408508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1966.9575, 4749.53613281, 363.60882812000006), 'rotation':(-0.402771, -90.228271, -0.408478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.5232812499999, 4889.71923828, 364.36851562000004), 'rotation':(-0.247498, -90.230347, -0.249634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.5462499999999, 4895.40039062, 364.3928125), 'rotation':(-0.247498, -90.230347, -0.249634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.5690625, 4901.08105469, 364.41660156), 'rotation':(-0.239532, -90.230408, -0.241547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.59203125, 4906.76171875, 364.43992188), 'rotation':(-0.239532, -90.230408, -0.241547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.615, 4912.44287109, 364.46292969), 'rotation':(-0.23175, -90.229767, -0.233643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.63796875, 4918.12353516, 364.48527344), 'rotation':(-0.23175, -90.229767, -0.233643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.70664062, 4935.16650391, 364.55226562), 'rotation':(-0.229431, -90.22995, -0.231262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1967.75242188, 4946.52832031, 364.59949219000003), 'rotation':(-0.242065, -90.229858, -0.24411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.82125, 4963.57177734, 364.67460938), 'rotation':(-0.261017, -90.229675, -0.263397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.84414062, 4969.25244141, 364.70082031), 'rotation':(-0.261017, -90.229675, -0.263397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1967.8670312499999, 4974.93408203, 364.72746094), 'rotation':(-0.267029, -90.229614, -0.269531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1958.45507812, 4755.21191406, 363.64851562), 'rotation':(0.39708, 89.771675, 0.391614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.5006250000001, 4766.49560547, 363.72589844000004), 'rotation':(0.375298, 89.771362, 0.370411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.5232812499999, 4772.13671875, 363.76277344000005), 'rotation':(0.364602, 89.769836, 0.359996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.54601562, 4777.77880859, 363.79847656), 'rotation':(0.353517, 89.771103, 0.349174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.56882812, 4783.42041016, 363.83296875), 'rotation':(0.342794, 89.770966, 0.33871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.5915625, 4789.06201172, 363.86628906), 'rotation':(0.332063, 89.770844, 0.328236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.614375, 4794.70361328, 363.8984375), 'rotation':(0.315596, 89.770828, 0.312134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.6599218800002, 4805.98681641, 363.96070312000006), 'rotation':(0.31186, 89.770355, 0.308483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.68265625, 4811.62890625, 363.99140625), 'rotation':(0.304148, 89.770279, 0.300918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1958.728125, 4822.91259766, 364.05101562000004), 'rotation':(0.296895, 89.77018, 0.293828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.7509375, 4828.5546875, 364.08007812000005), 'rotation':(0.289627, 89.770126, 0.286705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1958.86484375, 4856.76464844, 364.2190625), 'rotation':(0.27193, 89.770241, 0.26935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.34179688, 4974.96826172, 364.72746094), 'rotation':(0.270462, 89.769775, 0.267928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1959.27304688, 4957.92480469, 364.64898437999994), 'rotation':(0.261016, 89.770302, 0.258657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.2501562500001, 4952.24365234, 364.62394530999995), 'rotation':(0.254684, 89.769127, 0.252426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1959.2271875000001, 4946.5625, 364.59949219000003), 'rotation':(0.248113, 89.77018, 0.245963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.20421875, 4940.88134766, 364.57558594), 'rotation':(0.242082, 89.770142, 0.240029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.18125, 4935.20019531, 364.55226562), 'rotation':(0.23573, 89.768951, 0.233802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.13546875, 4923.83837891, 364.50746094000004), 'rotation':(0.222828, 89.769997, 0.221092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.0896093800002, 4912.47705078, 364.46292969), 'rotation':(0.223798, 89.769455, 0.222049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.0666406199998, 4906.79638672, 364.43992188), 'rotation':(0.231748, 89.769524, 0.229887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1959.02085938, 4895.43457031, 364.3928125), 'rotation':(0.239542, 89.770302, 0.237538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1958.99789062, 4889.75341797, 364.36851562000004), 'rotation':(0.239542, 89.770302, 0.237538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.54742432, 5274.33642578, 371.60351562000005), 'rotation':(0.041288, -89.897644, 0.041238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.55743408, 5268.71777344, 371.60769531), 'rotation':(0.041288, -89.897644, 0.041238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.56750488, 5263.09960938, 371.61175781), 'rotation':(0.040155, -89.897552, 0.040094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.58758545, 5251.86279297, 371.61921875), 'rotation':(0.034458, -89.897583, 0.034411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.59759521, 5246.24462891, 371.62257812), 'rotation':(0.03161, -89.897552, 0.03158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.61761475, 5235.0078125, 371.62835937999995), 'rotation':(0.025914, -89.897583, 0.025902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.62762451, 5229.38916016, 371.63082031), 'rotation':(0.023072, -89.897583, 0.023055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.63769531, 5223.77099609, 371.63300781), 'rotation':(0.020224, -89.897583, 0.020214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.64770508, 5218.15283203, 371.635), 'rotation':(0.019002, -89.897766, 0.018992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.65777588, 5212.53417969, 371.63683594), 'rotation':(0.018995, -89.897766, 0.018982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.71795654, 5178.82470703, 371.6428125), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.72796631, 5173.20605469, 371.6415625), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.73803711, 5167.58740234, 371.64035156), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.74804688, 5161.96923828, 371.6390625), 'rotation':(-0.012787, -89.897705, -0.012787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.75811768, 5156.35058594, 371.6378125), 'rotation':(-0.018127, -89.897644, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.76812744, 5150.73242188, 371.63628905999997), 'rotation':(-0.018127, -89.897644, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.77850342, 5145.12011719, 371.63453125), 'rotation':(-0.028839, -89.897644, -0.02887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.78820801, 5139.49560547, 371.63191406), 'rotation':(-0.028839, -89.897644, -0.02887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.8182373, 5122.64160156, 371.62105469), 'rotation':(-0.050293, -89.897614, -0.050385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.82830811, 5117.02294922, 371.61613280999995), 'rotation':(-0.055939, -89.897614, -0.056061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.83831787, 5111.40429688, 371.6109375), 'rotation':(-0.055939, -89.897614, -0.056061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.84832764, 5105.78613281, 371.60539062000004), 'rotation':(-0.059387, -89.897766, -0.059509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.8684082, 5094.54980469, 371.59335938), 'rotation':(-0.066986, -89.8974, -0.067139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.878479, 5088.93115234, 371.58679687999995), 'rotation':(-0.074249, -89.897736, -0.074432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.88848877, 5083.31298828, 371.57972656), 'rotation':(-0.074249, -89.897736, -0.074432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.93859863, 5055.22119141, 371.53914062), 'rotation':(-0.091553, -89.897552, -0.091858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.96868896, 5038.36621094, 371.51082031), 'rotation':(-0.104004, -89.897522, -0.10437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.97875977, 5032.74804688, 371.50058594), 'rotation':(-0.108521, -89.897491, -0.108948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.98876953, 5027.12939453, 371.49003905999996), 'rotation':(-0.112183, -89.896912, -0.11264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.99884033, 5021.51171875, 371.47910156), 'rotation':(-0.116699, -89.897461, -0.117188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(990.0088501, 5015.89306641, 371.46777344000003), 'rotation':(-0.118591, -89.897522, -0.11908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.49951172, 5301.18945312, 371.57667969), 'rotation':(0.069989, -89.897675, 0.069817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.47937012, 5312.46240234, 371.56230469), 'rotation':(0.074394, -89.897522, 0.0742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.46929932, 5318.09912109, 371.55488281), 'rotation':(0.074695, -89.897522, 0.074496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.45922852, 5323.73535156, 371.54691406), 'rotation':(0.078738, -89.897705, 0.078525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.44915771, 5329.37207031, 371.53804687999997), 'rotation':(0.086538, -89.897064, 0.086291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.43914795, 5335.00828125, 371.52839844000005), 'rotation':(0.095015, -89.897675, 0.094703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.42907715, 5340.645, 371.51789062000006), 'rotation':(0.103143, -89.897644, 0.102764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.41906738, 5346.28125, 371.50652344), 'rotation':(0.119405, -89.896942, 0.118913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.40899658, 5351.91796875, 371.49433594000004), 'rotation':(0.127554, -89.897552, 0.12699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.39892578, 5357.55421875, 371.48136719), 'rotation':(0.135361, -89.897522, 0.134707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.38885498, 5363.1909375, 371.46769530999995), 'rotation':(0.139705, -89.897461, 0.139032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.36871338, 5374.46335938, 371.439375), 'rotation':(0.145927, -89.897339, 0.145192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.35864258, 5380.09960938, 371.42402344000004), 'rotation':(0.145927, -89.897339, 0.145192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.32849121, 5397.00929688, 371.37410156), 'rotation':(0.170864, -89.89682, 0.169851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.30834961, 5408.28222656, 371.33753906), 'rotation':(0.189722, -89.897522, 0.188482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.28820801, 5419.55566406, 371.30015625), 'rotation':(0.190514, -89.896942, 0.189254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.27813721, 5425.19238281, 371.28136719), 'rotation':(0.190788, -89.896942, 0.189527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.26806641, 5430.82960938, 371.2625), 'rotation':(0.191396, -89.896912, 0.190113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.25805664, 5436.46582031, 371.24367187999997), 'rotation':(0.191976, -89.897522, 0.190705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.24798584, 5442.10253906, 371.22472655999997), 'rotation':(0.192277, -89.896912, 0.190979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(989.23791504, 5447.73925781, 371.20582031), 'rotation':(0.192857, -89.896912, 0.19156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.22784424, 5453.37597656, 371.18679688), 'rotation':(0.192857, -89.896912, 0.19156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.20770264, 5464.64941406, 371.14871094), 'rotation':(0.193786, -89.897247, 0.192472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.18756104, 5475.92234375, 371.11035155999997), 'rotation':(0.196996, -89.897125, 0.195652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.17749023, 5481.5590625, 371.09039062000005), 'rotation':(0.203369, -89.897095, 0.20193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.16748047, 5487.1953125, 371.06976562000006), 'rotation':(0.209755, -89.897034, 0.208228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.15740967, 5492.83203125, 371.04847656), 'rotation':(0.216128, -89.896332, 0.214508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.14733887, 5498.46828125, 371.026875), 'rotation':(0.219488, -89.897034, 0.217802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.13726807, 5504.105, 371.00527344), 'rotation':(0.219488, -89.897034, 0.217802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.12719727, 5509.74171875, 370.98371094000004), 'rotation':(0.219474, -89.896667, 0.217806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.11712646, 5515.37792969, 370.96179687999995), 'rotation':(0.223463, -89.896973, 0.221715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.1071167, 5521.01464844, 370.93910156), 'rotation':(0.230936, -89.896942, 0.229085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(989.0970459, 5526.65136719, 370.91566406), 'rotation':(0.239084, -89.89621, 0.23709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.0869751, 5532.28757812, 370.89132812), 'rotation':(0.246857, -89.89682, 0.24473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.0769043, 5537.92382812, 370.86621094000003), 'rotation':(0.254677, -89.896729, 0.252427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.0668335, 5543.56054688, 370.84027344000003), 'rotation':(0.262491, -89.895996, 0.260093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(989.05682373, 5549.19679688, 370.81355469000005), 'rotation':(0.270298, -89.896606, 0.267751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.04675293, 5554.83300781, 370.78609375), 'rotation':(0.278084, -89.896515, 0.275389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(989.03668213, 5560.46972656, 370.75835937999994), 'rotation':(0.281937, -89.896179, 0.279177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.02233887, 5274.34082031, 371.60351562000005), 'rotation':(-0.045013, 90.102646, -0.045074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.07250977, 5246.24707031, 371.62253906), 'rotation':(-0.034454, 90.102432, -0.034485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.08251953, 5240.62841797, 371.62558594), 'rotation':(-0.031616, 90.102432, -0.031647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.0925293, 5235.00927734, 371.62835937999995), 'rotation':(-0.028778, 90.102417, -0.028809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.10253906, 5229.390625, 371.63082031), 'rotation':(-0.025909, 90.102417, -0.02594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.11260986, 5223.77148438, 371.63300781), 'rotation':(-0.023071, 90.102417, -0.023102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.13269043, 5212.53417969, 371.63683594), 'rotation':(-0.019012, 90.102234, -0.019012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.1427002, 5206.91552734, 371.63871094), 'rotation':(-0.019012, 90.102249, -0.019012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(981.15270996, 5201.296875, 371.64054688), 'rotation':(-0.019012, 90.102234, -0.019012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.17279053, 5190.05908203, 371.64382812), 'rotation':(-0.0112, 90.102226, -0.01123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.18286133, 5184.44042969, 371.64390625), 'rotation':(0.004938, 90.10289, 0.004952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.19287109, 5178.82226562, 371.64285156), 'rotation':(0.012786, 90.102295, 0.01278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.21295166, 5167.58447266, 371.64035156), 'rotation':(0.012793, 90.102287, 0.012782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.23303223, 5156.34667969, 371.63785156), 'rotation':(0.012786, 90.102295, 0.01278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.24304199, 5150.72802734, 371.63628905999997), 'rotation':(0.012786, 90.102295, 0.01278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.26312256, 5139.49072266, 371.63191406), 'rotation':(0.018114, 90.102333, 0.018093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.27313232, 5133.87255859, 371.62910156), 'rotation':(0.028837, 90.102341, 0.028801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.30322266, 5117.01611328, 371.61613280999995), 'rotation':(0.050284, 90.102379, 0.050197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.31323242, 5111.39746094, 371.6109375), 'rotation':(0.050284, 90.102379, 0.050197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.33331299, 5100.15966797, 371.59953125), 'rotation':(0.059402, 90.102234, 0.05927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.34332275, 5094.54150391, 371.59335938), 'rotation':(0.059402, 90.102234, 0.05927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.36340332, 5083.30419922, 371.57972656), 'rotation':(0.066997, 90.1026, 0.066844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.37341309, 5077.68505859, 371.57242188), 'rotation':(0.07423, 90.102249, 0.074053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.39349365, 5066.44775391, 371.55632812000005), 'rotation':(0.081853, 90.102287, 0.081616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.40356445, 5060.82910156, 371.54789062000003), 'rotation':(0.08589, 90.102882, 0.085642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(981.41357422, 5055.21044922, 371.53914062), 'rotation':(0.087604, 90.102432, 0.087338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.42358398, 5049.59179688, 371.53007812000004), 'rotation':(0.091559, 90.10244, 0.091267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(981.44360352, 5038.35449219, 371.51082031), 'rotation':(0.100042, 90.102463, 0.099688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(981.45367432, 5032.73535156, 371.500625), 'rotation':(0.10399, 90.102486, 0.103616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(981.47375488, 5021.49804688, 371.47910156), 'rotation':(0.112186, 90.102509, 0.111752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.51159668, 5560.4565625, 370.75835937999994), 'rotation':(-0.282166, 90.103813, -0.284943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.53173828, 5549.18457031, 370.81355469000005), 'rotation':(-0.278076, 90.103477, -0.280792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.54180908, 5543.54785156, 370.84027344000003), 'rotation':(-0.270294, 90.103394, -0.272858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.55187988, 5537.91210938, 370.86617187999997), 'rotation':(-0.262512, 90.10334, -0.264923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.57196045, 5526.640625, 370.915625), 'rotation':(-0.246857, 90.10318, -0.248993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.58203125, 5521.00488281, 370.93910156), 'rotation':(-0.239075, 90.103127, -0.241089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.59204102, 5515.36816406, 370.96175781), 'rotation':(-0.230957, 90.103706, -0.232819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.61218262, 5504.09570312, 371.00523438), 'rotation':(-0.219482, 90.102959, -0.221161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.64239502, 5487.18703125, 371.06976562000006), 'rotation':(-0.216156, 90.102997, -0.217773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.66247559, 5475.91453125, 371.1103125), 'rotation':(-0.2034, 90.103577, -0.204834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.68261719, 5464.64257812, 371.14867187999994), 'rotation':(-0.193542, 90.102715, -0.194855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.69268799, 5459.00632812, 371.16773437999996), 'rotation':(-0.193787, 90.10321, -0.195099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.70275879, 5453.37011719, 371.18675780999996), 'rotation':(-0.193451, 90.103065, -0.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.71282959, 5447.73390625, 371.20574219), 'rotation':(-0.193451, 90.103065, -0.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.72290039, 5442.0971875, 371.2246875), 'rotation':(-0.192871, 90.102501, -0.194153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.74304199, 5430.82519531, 371.2625), 'rotation':(-0.191986, 90.103081, -0.193268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.75305176, 5425.18847656, 371.28128906), 'rotation':(-0.191376, 90.103065, -0.192688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.76312256, 5419.55226562, 371.30007812), 'rotation':(-0.190826, 90.103065, -0.192078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.78326416, 5408.27929688, 371.3375), 'rotation':(-0.189941, 90.102463, -0.191193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.79333496, 5402.64355469, 371.35601562000005), 'rotation':(-0.189728, 90.10318, -0.190979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.83361816, 5380.09863281, 371.42402344000004), 'rotation':(-0.158325, 90.102722, -0.15918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(980.85375977, 5368.82664062, 371.45371094), 'rotation':(-0.145935, 90.102646, -0.146698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.87384033, 5357.5546875, 371.48128906), 'rotation':(-0.139709, 90.103065, -0.140381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.88391113, 5351.91894531, 371.49433594000004), 'rotation':(-0.135345, 90.102478, -0.135986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.89398193, 5346.28222656, 371.50648437999996), 'rotation':(-0.127563, 90.102455, -0.128113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.9039917, 5340.64648438, 371.51785156), 'rotation':(-0.110962, 90.103027, -0.111389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(980.9140625, 5335.01023438, 371.52835938), 'rotation':(-0.103149, 90.102341, -0.103516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(980.93414307, 5323.73828125, 371.546875), 'rotation':(-0.086548, 90.102287, -0.086823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.94421387, 5318.10205078, 371.55488281), 'rotation':(-0.078766, 90.102928, -0.078949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(980.97442627, 5301.19384766, 371.57664062000003), 'rotation':(-0.074402, 90.10247, -0.074585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.1405078100001, 5273.0390625, 371.17398438), 'rotation':(0.138755, -90.052338, 0.138088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.1251171899999, 5256.21191406, 371.21414062), 'rotation':(0.12892, -90.05191, 0.128329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.12, 5250.60302734, 371.22675781), 'rotation':(0.123312, -90.05191, 0.12279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.10974609, 5239.38525391, 371.25023437999994), 'rotation':(0.111824, -90.053223, 0.111399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.09949219, 5228.16748047, 371.2715625), 'rotation':(0.100329, -90.052002, 0.099983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.09435547, 5222.55810547, 371.28136719), 'rotation':(0.094735, -90.052032, 0.094413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.08410156, 5211.33984375, 371.29957031), 'rotation':(0.086607, -90.051697, 0.086337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.07910156, 5205.73095703, 371.30835937999996), 'rotation':(0.086607, -90.051697, 0.086337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.07398438, 5200.12207031, 371.31683594000003), 'rotation':(0.076109, -90.052551, 0.075916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.06371094, 5188.90429688, 371.33152344), 'rotation':(0.065829, -90.051758, 0.065674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.05333984, 5177.68603516, 371.34351562000006), 'rotation':(0.050127, -90.052124, 0.050037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.04822266, 5172.07714844, 371.34875), 'rotation':(0.050127, -90.052124, 0.050037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.0430859399999, 5166.46777344, 371.35367188), 'rotation':(0.048972, -90.052795, 0.04889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.03796875, 5160.85839844, 371.35847656), 'rotation':(0.046766, -90.051697, 0.046692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.02771484, 5149.640625, 371.36753905999996), 'rotation':(0.042374, -90.051697, 0.0423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.01746094, 5138.42236328, 371.37585937999995), 'rotation':(0.040168, -90.052795, 0.040111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.00720703, 5127.20410156, 371.38335937999994), 'rotation':(0.035763, -90.052795, 0.035717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.00207031, 5121.59521484, 371.38683594), 'rotation':(0.033564, -90.052826, 0.033526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.99181641, 5110.37695312, 371.39332031), 'rotation':(0.0326, -90.052887, 0.032566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.98669922, 5104.76757812, 371.39648437999995), 'rotation':(0.032307, -90.051666, 0.032262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1178.9815625, 5099.15820312, 371.39964844), 'rotation':(0.032307, -90.052887, 0.03226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.9764453100001, 5093.54931641, 371.4028125), 'rotation':(0.018086, -90.051666, 0.018079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.97130859, 5087.94042969, 371.40476562000003), 'rotation':(-0.010345, -90.052979, -0.010345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.9509375, 5065.50537109, 371.39691406), 'rotation':(-0.024689, -90.052185, -0.024719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1178.94066406, 5054.28662109, 371.39210937999997), 'rotation':(-0.036194, -90.052765, -0.036255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.93554688, 5048.67822266, 371.38902344), 'rotation':(-0.036194, -90.052765, -0.036255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.92517578, 5037.46044922, 371.37996094000005), 'rotation':(-0.081085, -90.05191, -0.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.92003906, 5031.85205078, 371.37367187999996), 'rotation':(-0.081085, -90.05191, -0.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1178.91492188, 5026.24267578, 371.36570312000003), 'rotation':(-0.103699, -90.052612, -0.104065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1178.90466797, 5015.02539062, 371.34628906), 'rotation':(-0.114838, -90.052063, -0.115295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.18042969, 5316.62011719, 371.06125), 'rotation':(0.153536, -90.052185, 0.152716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.19568359, 5333.42625, 371.015), 'rotation':(0.160277, -90.052124, 0.159389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.20080078, 5339.0278125, 370.99910156), 'rotation':(0.160277, -90.052124, 0.159389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.2110546899999, 5350.23242188, 370.96644531), 'rotation':(0.165031, -90.051392, 0.164081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.21619141, 5355.83445312, 370.94988280999996), 'rotation':(0.169594, -90.052063, 0.168592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.22130859, 5361.43652344, 370.93308594), 'rotation':(0.172011, -90.05127, 0.17098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.2264453100001, 5367.03859375, 370.91621094000004), 'rotation':(0.171984, -90.05249, 0.170961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.23167969, 5372.640625, 370.89890625), 'rotation':(0.176943, -90.051727, 0.175855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.23681641, 5378.24265625, 370.88125), 'rotation':(0.176943, -90.051727, 0.175855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.24181641, 5383.84472656, 370.86292969000004), 'rotation':(0.187106, -90.051636, 0.185885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.24695312, 5389.44628906, 370.84402344), 'rotation':(0.187106, -90.051636, 0.185885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.25207031, 5395.04835938, 370.82472656), 'rotation':(0.197263, -90.051575, 0.195912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.26757812, 5411.85449219, 370.76332031), 'rotation':(0.212405, -90.052307, 0.21084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.28296875, 5428.660625, 370.70074219), 'rotation':(0.213833, -90.051331, 0.212254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.28796875, 5434.26269531, 370.67976562), 'rotation':(0.214427, -90.051331, 0.212831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.29822266, 5445.46726562, 370.63777344000005), 'rotation':(0.21526, -90.0513, 0.213645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.30333984, 5451.06933594, 370.61667969), 'rotation':(0.216128, -90.051331, 0.214504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.3084765600001, 5456.67140625, 370.59550780999996), 'rotation':(0.216107, -90.0513, 0.214482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.31359375, 5462.27390625, 370.574375), 'rotation':(0.216107, -90.0513, 0.214482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.32384766, 5473.47804688, 370.53199219000004), 'rotation':(0.216578, -90.051758, 0.21494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.349375, 5501.48828125, 370.42332031), 'rotation':(0.225642, -90.051758, 0.223866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.35960938, 5512.69238281, 370.37921875), 'rotation':(0.225314, -90.051758, 0.22355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1179.36988281, 5523.89695312, 370.33488280999995), 'rotation':(0.226708, -90.051788, 0.224921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.375, 5529.49851562, 370.31257812), 'rotation':(0.227725, -90.051788, 0.225926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.38011719, 5535.10058594, 370.29019531), 'rotation':(0.228784, -90.050415, 0.226968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.39539062, 5551.90722656, 370.22242187999996), 'rotation':(0.232575, -90.050354, 0.230701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.40050781, 5557.50929688, 370.19964844000003), 'rotation':(0.232868, -90.051575, 0.230986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1179.40564453, 5563.11132812, 370.176875), 'rotation':(0.232868, -90.051575, 0.230986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.38464844, 5020.64453125, 371.35644530999997), 'rotation':(0.081061, 89.948074, 0.080838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.38976562, 5026.25341797, 371.36570312000003), 'rotation':(0.081061, 89.948074, 0.080838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.40001953, 5037.47167969, 371.37996094000005), 'rotation':(0.058446, 89.947266, 0.058325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.41039062, 5048.68994141, 371.38902344), 'rotation':(0.024691, 89.947815, 0.024665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.41552734, 5054.29931641, 371.39210937999997), 'rotation':(0.024691, 89.947815, 0.024665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.42066406, 5059.90869141, 371.39453125), 'rotation':(0.024677, 89.94783, 0.024667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.42578125, 5065.51855469, 371.39691406), 'rotation':(0.024677, 89.94783, 0.024667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.44103516, 5082.34667969, 371.40410155999996), 'rotation':(0.010334, 89.948311, 0.010332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.45128906, 5093.56445312, 371.4028125), 'rotation':(-0.032318, 89.948326, -0.032349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.45642578, 5099.17382812, 371.39964844), 'rotation':(-0.032318, 89.947098, -0.032349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.46667969, 5110.39306641, 371.39332031), 'rotation':(-0.032318, 89.947098, -0.032349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.47693359, 5121.61230469, 371.38683594), 'rotation':(-0.035767, 89.947197, -0.035828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.4871875, 5132.83105469, 371.3796875), 'rotation':(-0.040161, 89.947197, -0.040222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.4923046899999, 5138.44042969, 371.37585937999995), 'rotation':(-0.042389, 89.948296, -0.04245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5076953100001, 5155.26904297, 371.36308594), 'rotation':(-0.046783, 89.947212, -0.046844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5128125, 5160.87841797, 371.35847656), 'rotation':(-0.048981, 89.948311, -0.049072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.51794922, 5166.48779297, 371.35367188), 'rotation':(-0.05014, 89.947845, -0.050232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.52306641, 5172.09765625, 371.34875), 'rotation':(-0.055328, 89.947388, -0.05545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.52820312, 5177.70703125, 371.34351562000006), 'rotation':(-0.055328, 89.947388, -0.05545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5334375, 5183.31591797, 371.33792969), 'rotation':(-0.065826, 89.948235, -0.065979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.54371094, 5194.53466797, 371.32441406), 'rotation':(-0.076111, 89.947426, -0.076324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.55394531, 5205.75390625, 371.30832031), 'rotation':(-0.091766, 89.948349, -0.092072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.55896484, 5211.36279297, 371.29953125), 'rotation':(-0.091766, 89.948349, -0.092072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.56408203, 5216.97265625, 371.29054687999997), 'rotation':(-0.094727, 89.947975, -0.095062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5743359399999, 5228.19189453, 371.27152344), 'rotation':(-0.105927, 89.948013, -0.106323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.57947266, 5233.80078125, 371.26113281), 'rotation':(-0.111816, 89.948029, -0.112274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.58458984, 5239.41064453, 371.25019531), 'rotation':(-0.117401, 89.948044, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.5897265600001, 5245.01953125, 371.23875), 'rotation':(-0.123322, 89.948074, -0.12384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.59484375, 5250.62890625, 371.22671875), 'rotation':(-0.128906, 89.948097, -0.129486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.59998047, 5256.23828125, 371.2140625), 'rotation':(-0.134521, 89.94812, -0.135132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.60509766, 5261.84765625, 371.20097655999996), 'rotation':(-0.137451, 89.948082, -0.138092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.88037109, 5563.12011719, 370.176875), 'rotation':(-0.232635, 89.948425, -0.234558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.87523438, 5557.51855469, 370.19964844000003), 'rotation':(-0.232635, 89.948425, -0.234558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.87011719, 5551.91648438, 370.22242187999996), 'rotation':(-0.23288, 89.949341, -0.234772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.865, 5546.31492188, 370.24511719000003), 'rotation':(-0.232574, 89.948257, -0.234467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.85986328, 5540.71289062, 370.26769530999997), 'rotation':(-0.231232, 89.948242, -0.233093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.84972656, 5529.50976562, 370.31257812), 'rotation':(-0.22879, 89.948219, -0.230621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.84460938, 5523.90820312, 370.33488280999995), 'rotation':(-0.227722, 89.948204, -0.229553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.83947266, 5518.30664062, 370.35707031), 'rotation':(-0.226715, 89.948189, -0.228516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.83435547, 5512.70460938, 370.37917969), 'rotation':(-0.225983, 89.949577, -0.227783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.82921875, 5507.10304688, 370.40125), 'rotation':(-0.225311, 89.948235, -0.227081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.8241015600001, 5501.50148438, 370.42328125), 'rotation':(-0.225647, 89.948242, -0.227417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.81896484, 5495.89941406, 370.44535156), 'rotation':(-0.225647, 89.948242, -0.227417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.81384766, 5490.29785156, 370.46734375), 'rotation':(-0.225311, 89.949509, -0.227081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.80359375, 5479.09421875, 370.51066405999995), 'rotation':(-0.218689, 89.948929, -0.220337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.79333984, 5467.89109375, 370.55316406), 'rotation':(-0.216553, 89.948257, -0.218201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.78832031, 5462.28953125, 370.57433594), 'rotation':(-0.216766, 89.948257, -0.218414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.78320312, 5456.6875, 370.59550780999996), 'rotation':(-0.216766, 89.948257, -0.218414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.77808594, 5451.0859375, 370.61664062000006), 'rotation':(-0.216095, 89.948685, -0.217743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.77294922, 5445.48390625, 370.63773438), 'rotation':(-0.216125, 89.948692, -0.217743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.76269531, 5434.28027344, 370.67976562), 'rotation':(-0.214691, 89.948677, -0.216309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.75757812, 5428.67871094, 370.70070312), 'rotation':(-0.214417, 89.947533, -0.216034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.75244141, 5423.07714844, 370.72160155999995), 'rotation':(-0.213837, 89.948677, -0.215424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.74730469, 5417.47507812, 370.7425), 'rotation':(-0.213287, 89.948662, -0.214874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.7421875, 5411.87351562, 370.76332031), 'rotation':(-0.213013, 89.948654, -0.2146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.73707031, 5406.27195312, 370.78410155999995), 'rotation':(-0.212433, 89.947685, -0.213989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.73193359, 5400.66992188, 370.80449219), 'rotation':(-0.212433, 89.947685, -0.213989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.72693359, 5395.06882812, 370.8246875), 'rotation':(-0.207611, 89.948479, -0.209106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.72191406, 5389.46679688, 370.84398437999994), 'rotation':(-0.197266, 89.94841, -0.198639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.71167969, 5378.26414062, 370.88121094), 'rotation':(-0.187103, 89.948326, -0.188324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.70654297, 5372.66257812, 370.89890625), 'rotation':(-0.187103, 89.948326, -0.188324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.69617188, 5361.45898438, 370.93300781), 'rotation':(-0.171997, 89.948723, -0.173035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.68591797, 5350.25585938, 370.96644531), 'rotation':(-0.169586, 89.947906, -0.170593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.68078125, 5344.65429688, 370.98292969), 'rotation':(-0.169586, 89.947906, -0.170593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.6756640600001, 5339.05273438, 370.99910156), 'rotation':(-0.165039, 89.948624, -0.165985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.66552734, 5327.84914062, 371.030625), 'rotation':(-0.160278, 89.947861, -0.161194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.66039062, 5322.24755859, 371.04597656), 'rotation':(-0.160278, 89.947861, -0.161194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.65527344, 5316.64550781, 371.06117187999996), 'rotation':(-0.155731, 89.947845, -0.156586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1170.65015625, 5311.04394531, 371.07621094), 'rotation':(-0.153534, 89.949104, -0.154358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.64501953, 5305.44189453, 371.09117188), 'rotation':(-0.153534, 89.947792, -0.154358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1170.63988281, 5299.84082031, 371.10605469), 'rotation':(-0.1521, 89.948303, -0.152924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.81382812, 5271.62548828, 370.63347655999996), 'rotation':(0.114802, -90.161621, 0.114351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.79785156, 5265.94824219, 370.64492187999997), 'rotation':(0.11347, -90.162354, 0.113016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.76574219, 5254.59375, 370.66730469000004), 'rotation':(0.110314, -90.161621, 0.109882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.74964844, 5248.91601562, 370.67820312000003), 'rotation':(0.103942, -90.161621, 0.103553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.71765625, 5237.56152344, 370.69871094), 'rotation':(0.097945, -90.161652, 0.097608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.70152344, 5231.88427734, 370.70839844), 'rotation':(0.091572, -90.161652, 0.091281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.68554688, 5226.20654297, 370.71769530999995), 'rotation':(0.091572, -90.161652, 0.091281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.66957031, 5220.52929688, 370.72675781), 'rotation':(0.088608, -90.161591, 0.088329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.6534375, 5214.85205078, 370.73554687999996), 'rotation':(0.088615, -90.161621, 0.088338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.63746094, 5209.17431641, 370.74433594000004), 'rotation':(0.084489, -90.161987, 0.084238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.60535156, 5197.81982422, 370.76089844), 'rotation':(0.076423, -90.162048, 0.076217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.57324219, 5186.46533203, 370.77535156), 'rotation':(0.060092, -90.162079, 0.059971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.55726562, 5180.78857422, 370.78191405999996), 'rotation':(0.060092, -90.162079, 0.059971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.54113281, 5175.11083984, 370.78789062000004), 'rotation':(0.055987, -90.161774, 0.055876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.52503906, 5169.43359375, 370.79351562000005), 'rotation':(0.055987, -90.161774, 0.055876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.50902344, 5163.75634766, 370.7990625), 'rotation':(0.055311, -90.161743, 0.0552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.49292969, 5158.07861328, 370.80449219), 'rotation':(0.053658, -90.161743, 0.053555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.47691406, 5152.40136719, 370.80984375), 'rotation':(0.052265, -90.161743, 0.052178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.4609375, 5146.72363281, 370.815), 'rotation':(0.050625, -90.161743, 0.050536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.44484375, 5141.04638672, 370.82003906), 'rotation':(0.048972, -90.161713, 0.048882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.36460938, 5112.65966797, 370.84324219), 'rotation':(0.038413, -90.162292, 0.038364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.34863281, 5106.98193359, 370.84714844), 'rotation':(0.028332, -90.161316, 0.028301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.3326562500001, 5101.30517578, 370.85042969), 'rotation':(0.028332, -90.161316, 0.028301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.31652344, 5095.62792969, 370.85292969), 'rotation':(0.018004, -90.162292, 0.017993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.2845312499999, 5084.27294922, 370.85554687999996), 'rotation':(0.0025, -90.162292, 0.002499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.2684375, 5078.59619141, 370.85589844000003), 'rotation':(0.0025, -90.162292, 0.002499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.25242188, 5072.91845703, 370.85617188), 'rotation':(0.002322, -90.16156, 0.002318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.23632812, 5067.24121094, 370.85636719), 'rotation':(0.002507, -90.161591, 0.002504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.22035156, 5061.56396484, 370.85664062), 'rotation':(0.002507, -90.161591, 0.002504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1367.1241406200002, 5027.50048828, 370.85359375), 'rotation':(-0.034546, -90.161011, -0.034607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.10804688, 5021.82275391, 370.85015625), 'rotation':(-0.039673, -90.162323, -0.039734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.09203125, 5016.14550781, 370.84621094), 'rotation':(-0.039673, -90.161407, -0.039734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.90601562, 5304.24023438, 370.56257812), 'rotation':(0.130545, -90.160492, 0.129966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.92199219, 5309.88134766, 370.54945312), 'rotation':(0.132588, -90.161835, 0.131991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.93796875, 5315.52197266, 370.53609375), 'rotation':(0.136378, -90.16333, 0.135732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.95386719, 5321.16210938, 370.52238280999995), 'rotation':(0.139158, -90.160645, 0.138482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.96984375, 5326.80273438, 370.50816405999996), 'rotation':(0.14439, -90.161835, 0.143665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1367.98570312, 5332.44335938, 370.49335937999996), 'rotation':(0.150517, -90.161804, 0.149738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.00171875, 5338.08398438, 370.47800781), 'rotation':(0.155756, -90.160553, 0.154916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.03355469, 5349.36476562, 370.44566405999996), 'rotation':(0.167128, -90.161713, 0.166156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.04945312, 5355.00585938, 370.42863280999995), 'rotation':(0.172954, -90.161682, 0.17191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.06554688, 5360.64648438, 370.41109375), 'rotation':(0.178179, -90.160431, 0.177075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.0814062499999, 5366.28664062, 370.39320312), 'rotation':(0.181266, -90.161743, 0.180121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.09742188, 5371.92773438, 370.37492188), 'rotation':(0.184647, -90.161804, 0.183461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.11328125, 5377.56789062, 370.35597656), 'rotation':(0.191122, -90.160492, 0.189837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.12925781, 5383.20851562, 370.33636719000003), 'rotation':(0.197536, -90.161743, 0.19618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.16113281, 5394.48976562, 370.29511719000004), 'rotation':(0.210766, -90.161652, 0.209225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.17710938, 5400.12988281, 370.27347656), 'rotation':(0.217514, -90.160309, 0.215871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1368.19300781, 5405.77050781, 370.25113281), 'rotation':(0.223989, -90.16156, 0.222239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.22484375, 5417.05175781, 370.20527344000004), 'rotation':(0.233545, -90.161407, 0.23165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.27269531, 5433.97460938, 370.13636719000004), 'rotation':(0.232916, -90.160126, 0.231014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.30457031, 5445.25539062, 370.09054688), 'rotation':(0.232568, -90.161407, 0.230677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1368.32042969, 5450.89601562, 370.06765625), 'rotation':(0.232588, -90.160126, 0.230697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.33640625, 5456.53710938, 370.04480469000003), 'rotation':(0.23194, -90.161438, 0.230068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.35230469, 5462.17773438, 370.02195312000003), 'rotation':(0.231967, -90.160095, 0.230095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.36828125, 5467.81835938, 369.99917969), 'rotation':(0.231782, -90.161438, 0.229915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.38414062, 5473.45945312, 369.97644531), 'rotation':(0.230451, -90.161438, 0.228608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.44800781, 5496.02296875, 369.88671875), 'rotation':(0.22653, -90.161469, 0.224739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.46386719, 5501.66359375, 369.86457031), 'rotation':(0.225574, -90.161499, 0.223797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1368.49574219, 5512.9453125, 369.82054687999994), 'rotation':(0.224392, -90.161255, 0.222645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.52757812, 5524.22703125, 369.7784375), 'rotation':(0.206634, -90.160645, 0.205145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.55945312, 5535.50929688, 369.73929688), 'rotation':(0.192857, -90.160736, 0.191561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.59132812, 5546.79101562, 369.70296875), 'rotation':(0.178753, -90.162109, 0.177642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1368.63902344, 5563.71386719, 369.65269530999996), 'rotation':(0.168419, -90.161102, 0.167434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1358.5670312500001, 5016.17089844, 370.84621094), 'rotation':(0.03967, 89.838577, 0.039605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1358.58300781, 5021.84863281, 370.85015625), 'rotation':(0.034568, 89.837631, 0.034512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.59914062, 5027.52636719, 370.85359375), 'rotation':(0.023817, 89.837608, 0.023797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.61511719, 5033.203125, 370.85597656), 'rotation':(0.013428, 89.838943, 0.01342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.64722656, 5044.55761719, 370.85734375), 'rotation':(-0.002319, 89.838432, -0.002319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.6632031200002, 5050.23535156, 370.85710937999994), 'rotation':(-0.002502, 89.8377, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.67933594, 5055.91308594, 370.856875), 'rotation':(-0.002502, 89.8377, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.6953125, 5061.59082031, 370.85664062), 'rotation':(-0.002319, 89.838432, -0.002319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.75953125, 5084.30078125, 370.85554687999996), 'rotation':(-0.007446, 89.8377, -0.007446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.77550781, 5089.97851562, 370.85472655999996), 'rotation':(-0.018005, 89.838669, -0.018036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.79148438, 5095.65625, 370.85292969), 'rotation':(-0.02832, 89.8377, -0.028351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.80761719, 5101.33349609, 370.85042969), 'rotation':(-0.038422, 89.838692, -0.038483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1358.83960938, 5112.68798828, 370.84324219), 'rotation':(-0.044159, 89.836784, -0.04422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.85570312, 5118.36621094, 370.83882812), 'rotation':(-0.045959, 89.838249, -0.046021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.8878125, 5129.72070312, 370.82972656), 'rotation':(-0.047607, 89.838249, -0.047668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.90382812, 5135.3984375, 370.82492188), 'rotation':(-0.048981, 89.838257, -0.049072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1358.9678906200002, 5158.109375, 370.80449219), 'rotation':(-0.055298, 89.837151, -0.05542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.00011719, 5169.46435547, 370.79351562000005), 'rotation':(-0.060089, 89.83873, -0.060211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.03222656, 5180.81982422, 370.781875), 'rotation':(-0.068176, 89.837929, -0.068329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.04820312, 5186.49707031, 370.77535156), 'rotation':(-0.068176, 89.837929, -0.068329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.06433594, 5192.17431641, 370.76847655999995), 'rotation':(-0.076416, 89.837967, -0.07663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.0803125, 5197.85205078, 370.76085937999994), 'rotation':(-0.084503, 89.838783, -0.084747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.09632812, 5203.52978516, 370.75273438), 'rotation':(-0.084503, 89.838783, -0.084747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.1284375, 5214.88427734, 370.73554687999996), 'rotation':(-0.088593, 89.838402, -0.088898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.14453125, 5220.56201172, 370.72675781), 'rotation':(-0.091553, 89.838348, -0.091858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.17652344, 5231.91748047, 370.70839844), 'rotation':(-0.097931, 89.837601, -0.098297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.19261719, 5237.59521484, 370.69867187999995), 'rotation':(-0.103943, 89.838371, -0.104309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.20863281, 5243.27246094, 370.68855469000005), 'rotation':(-0.103943, 89.838371, -0.104309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.22460938, 5248.95019531, 370.67820312000003), 'rotation':(-0.110291, 89.838387, -0.110748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.25671875, 5260.3046875, 370.65621094), 'rotation':(-0.113464, 89.838943, -0.113922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.2728124999999, 5265.98242188, 370.64492187999997), 'rotation':(-0.114807, 89.838379, -0.115265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.28882812, 5271.66015625, 370.6334375), 'rotation':(-0.118103, 89.838387, -0.118591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.09777344, 5558.098125, 369.66929688), 'rotation':(-0.168488, 89.838829, -0.169464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1360.08191406, 5552.4575, 369.68589844), 'rotation':(-0.168427, 89.838875, -0.169434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.0659375, 5546.81640625, 369.70296875), 'rotation':(-0.172211, 89.837799, -0.173248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1360.0501562499999, 5541.17578125, 369.72074219), 'rotation':(-0.178741, 89.83918, -0.179871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.01832031, 5529.8940625, 369.75851562), 'rotation':(-0.192841, 89.839264, -0.194153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1360.00230469, 5524.2534375, 369.7784375), 'rotation':(-0.199768, 89.839302, -0.201141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.97046875, 5512.97167969, 369.82054687999994), 'rotation':(-0.220428, 89.83947, -0.222107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.90671875, 5490.40917969, 369.90898438), 'rotation':(-0.226532, 89.838509, -0.228333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.89085938, 5484.76855469, 369.93140625), 'rotation':(-0.227539, 89.838524, -0.22934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.87488281, 5479.12792969, 369.95386719000004), 'rotation':(-0.228485, 89.839851, -0.230316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.85902344, 5473.48730469, 369.97644531), 'rotation':(-0.229492, 89.838539, -0.231354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.81117188, 5456.56542969, 370.04476562), 'rotation':(-0.231964, 89.83873, -0.233856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.7634375, 5439.64355469, 370.11339844), 'rotation':(-0.232574, 89.839882, -0.234467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.71558594, 5422.7221875, 370.18226562), 'rotation':(-0.233215, 89.839874, -0.235138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.68371094, 5411.4409375, 370.22828125), 'rotation':(-0.233521, 89.8386, -0.235443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.63597656, 5394.52, 370.29507812), 'rotation':(-0.217529, 89.838402, -0.219177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.60414062, 5383.23925781, 370.33632812), 'rotation':(-0.204315, 89.83831, -0.20578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.588125, 5377.59914062, 370.3559375), 'rotation':(-0.19754, 89.839546, -0.198914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.54039062, 5360.67820312, 370.41109375), 'rotation':(-0.181274, 89.838249, -0.182404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.52441406, 5355.03757812, 370.42863280999995), 'rotation':(-0.178192, 89.838318, -0.179291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.5084375000001, 5349.39695312, 370.445625), 'rotation':(-0.172943, 89.83831, -0.173981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.49242188, 5343.75683594, 370.46207031), 'rotation':(-0.167114, 89.8395, -0.168091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.4765625, 5338.11621094, 370.47796875), 'rotation':(-0.161591, 89.838242, -0.162506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.46058594, 5332.47558594, 370.49335937999996), 'rotation':(-0.155762, 89.838203, -0.156616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.4446874999999, 5326.83544922, 370.50816405999996), 'rotation':(-0.150513, 89.839417, -0.151306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':1, 'location':(1359.41285156, 5315.5546875, 370.53605469), 'rotation':(-0.13916, 89.838142, -0.139832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.39683594, 5309.91455078, 370.54941406), 'rotation':(-0.13504, 89.83815, -0.135651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':1, 'location':(1359.36511719, 5298.63330078, 370.57542969), 'rotation':(-0.130554, 89.838127, -0.131165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(31.10734375000004, 3502.27660156, 361.24867187999996), 'rotation':(-0.228333, 89.62056, -0.230133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(31.217968749999955, 3518.93824219, 361.1840625), 'rotation':(-0.175598, 89.620201, -0.176666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.254687500000045, 3524.49632812, 361.17050781), 'rotation':(-0.069275, 89.619728, -0.069427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(31.328281250000032, 3535.61351562, 361.17339844), 'rotation':(0.142819, 89.62001, 0.142097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.365078119999907, 3541.17308594, 361.18980469), 'rotation':(0.248516, 89.620735, 0.246377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.401875000000018, 3546.73265625, 361.21632812), 'rotation':(0.354849, 89.621864, 0.350479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.438671880000015, 3552.29222656, 361.25285155999995), 'rotation':(0.46058, 89.623352, 0.453216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(31.475390619999985, 3557.85230469, 361.29933594), 'rotation':(0.566557, 89.625259, 0.55543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.512187499999982, 3563.40941406, 361.35511719000004), 'rotation':(0.6204, 89.62632, 0.607075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.54882811999994, 3568.96679688, 361.41992187999995), 'rotation':(0.802028, 89.630875, 0.779812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(31.622343750000027, 3580.08863281, 361.58335938), 'rotation':(1.044821, 89.638718, 1.007213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(31.658984379999993, 3585.64941406, 361.683125), 'rotation':(1.166166, 89.643402, 1.119386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.73249999999996, 3596.77, 361.91875), 'rotation':(1.408651, 89.654335, 1.340595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.805937500000027, 3607.88914062, 362.20234375), 'rotation':(1.590293, 89.663864, 1.503746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.879374999999982, 3619.0, 362.51585937999994), 'rotation':(1.729868, 89.671959, 1.62763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.916328120000003, 3624.55710938, 362.68125), 'rotation':(1.729868, 89.671959, 1.62763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(31.952968749999968, 3630.11328125, 362.85195312), 'rotation':(1.82293, 89.677734, 1.70951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(32.026406250000036, 3641.22070312, 363.21402344), 'rotation':(1.962245, 89.686989, 1.831037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.063281250000045, 3646.7736718799997, 363.40222656), 'rotation':(1.962245, 89.686989, 1.831037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.13710938000008, 3657.87429688, 363.78105469), 'rotation':(1.935997, 89.685188, 1.80824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.21101562000001, 3668.9739062500003, 364.1515625), 'rotation':(1.830566, 89.67823, 1.71621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.358515619999935, 3691.17554688, 364.85851562000005), 'rotation':(1.751663, 89.67308, 1.64684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(33.042343749999986, 3794.01242188, 367.33554688), 'rotation':(1.079252, 89.639984, 1.039144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(33.00625000000002, 3788.5746875, 367.23304687999996), 'rotation':(1.07902, 89.639984, 1.03894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.93398438000008, 3777.7009375, 367.02421875), 'rotation':(1.128607, 89.641884, 1.084785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(32.897812499999986, 3772.2646875, 366.91519531), 'rotation':(1.161965, 89.643227, 1.115525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.86171875000002, 3766.82835938, 366.80292969000004), 'rotation':(1.195269, 89.644608, 1.146148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(32.78945311999996, 3755.9557812499997, 366.56828125), 'rotation':(1.261351, 89.647438, 1.206687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.753281249999986, 3750.51953125, 366.44597655999996), 'rotation':(1.294348, 89.648911, 1.236817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.71718750000002, 3745.08351562, 366.32039062), 'rotation':(1.327352, 89.650421, 1.266872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.681015619999926, 3739.64820312, 366.19257812), 'rotation':(1.34429, 89.65123, 1.282268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.60867188000009, 3728.77664062, 365.92597656), 'rotation':(1.442194, 89.655991, 1.370885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.57265625000002, 3723.34226562, 365.785625), 'rotation':(1.442194, 89.655991, 1.370885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(32.53640625000003, 3717.90820312, 365.64082031), 'rotation':(1.508085, 89.659401, 1.430179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.60222655999996, 3722.7356250000003, 367.78867188), 'rotation':(-0.335266, -90.029968, -0.339203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.60527344, 3728.2018749999997, 367.81855469000004), 'rotation':(-0.300934, -90.030365, -0.304108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.60832030999995, 3733.66796875, 367.84589844000004), 'rotation':(-0.300934, -90.030365, -0.304108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.61144531, 3739.135, 367.87105469), 'rotation':(-0.267151, -90.030701, -0.269653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.61445312, 3744.60179688, 367.89433594), 'rotation':(-0.249786, -90.030579, -0.251953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.61753906, 3750.068125, 367.91605469), 'rotation':(-0.233856, -90.031128, -0.235779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(358.62367187999996, 3761.0021875, 367.95144531), 'rotation':(-0.168915, -90.031311, -0.169922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.62671875, 3766.46851562, 367.96511719), 'rotation':(-0.136841, -90.031494, -0.137512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.6328125, 3777.40164062, 367.98507812), 'rotation':(-0.104492, -90.031891, -0.104889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.64515625, 3799.26882812, 367.99523437999994), 'rotation':(0.008736, -90.031921, 0.008725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.58128906, 3685.39601562, 367.51414062000003), 'rotation':(-0.510864, -90.027283, -0.52005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.57824218999997, 3679.994375, 367.46640625), 'rotation':(-0.527435, -90.027008, -0.537201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.57519531, 3674.59226562, 367.4171875), 'rotation':(-0.543945, -90.026672, -0.554352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.57226562000005, 3669.1901562499997, 367.36648438), 'rotation':(-0.560791, -90.026367, -0.571838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.56921875, 3663.78859375, 367.31429688), 'rotation':(-0.577026, -90.026062, -0.588745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.563125, 3652.984375, 367.20554688), 'rotation':(-0.593842, -90.025696, -0.606262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.5601953099999, 3647.5825, 367.14921875), 'rotation':(-0.608429, -90.025635, -0.62146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.55710937999993, 3642.18042969, 367.09167969000003), 'rotation':(-0.621613, -90.024994, -0.635223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.55109374999995, 3631.37671875, 366.97285156), 'rotation':(-0.6474, -90.02478, -0.66217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.54511719000004, 3620.5725, 366.84902344), 'rotation':(-0.673523, -90.02417, -0.689484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.54207031, 3615.17089844, 366.78523437999996), 'rotation':(-0.686768, -90.023499, -0.703369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.5390625, 3609.7690625, 366.72023437999997), 'rotation':(-0.69928, -90.023193, -0.716522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.52429687999995, 3583.41039062, 366.38960937999997), 'rotation':(-0.759491, -90.021729, -0.779846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.52128905999996, 3578.00488281, 366.31835937999995), 'rotation':(-0.776276, -90.021515, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.51832031000004, 3572.59914062, 366.24589844), 'rotation':(-0.776276, -90.021515, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(358.50921874999995, 3556.38160156, 366.02167969000004), 'rotation':(-0.809448, -90.020294, -0.832581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(358.5062109400001, 3550.97558594, 365.94515625), 'rotation':(-0.82608, -90.020111, -0.850159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(358.49714844000005, 3534.75828125, 365.70660155999997), 'rotation':(-0.875, -90.018646, -0.902039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(358.49421874999996, 3529.35277344, 365.62410156), 'rotation':(-0.891296, -90.017853, -0.919373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(358.49113280999995, 3523.94726562, 365.54011719000005), 'rotation':(-0.907928, -90.017639, -0.937042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(358.48816406000003, 3518.54175781, 365.45472656), 'rotation':(-0.924225, -90.016785, -0.954407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(358.47906250000005, 3502.32445312, 365.19203125), 'rotation':(-0.932373, -90.01651, -0.963104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(465.07105469, 3583.22507812, 368.77511719), 'rotation':(-0.792816, -90.146057, -0.815002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.0413671900001, 3572.39625, 368.62367187999996), 'rotation':(-0.818909, -90.145691, -0.84256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.02648437999994, 3566.98195312, 368.54613280999996), 'rotation':(-0.825348, -90.145386, -0.849365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.01160156000003, 3561.56714844, 368.468125), 'rotation':(-0.831451, -90.145142, -0.855865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.99675780999996, 3556.15234375, 368.38984375), 'rotation':(-0.831451, -90.145142, -0.855865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.98195312000007, 3550.73804688, 368.31097656), 'rotation':(-0.842865, -90.144806, -0.86795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(464.96703125, 3545.32375, 368.23109375), 'rotation':(-0.854828, -90.144745, -0.880646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.95214844, 3539.9096875, 368.15027344000003), 'rotation':(-0.866516, -90.144104, -0.893036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.90753906, 3523.66625, 367.90164062), 'rotation':(-0.901855, -90.143311, -0.930603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.89269531, 3518.25195312, 367.81679687999997), 'rotation':(-0.913544, -90.142639, -0.943054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(464.8778125, 3512.83789062, 367.73101562000005), 'rotation':(-0.913544, -90.142639, -0.943054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(464.86292969, 3507.42359375, 367.64445312000004), 'rotation':(-0.919189, -90.142426, -0.949036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(464.84808594000003, 3502.00878906, 367.55753905999995), 'rotation':(-0.919525, -90.1427, -0.949402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.35179687999994, 3684.21390625, 369.96523437999997), 'rotation':(-0.56192, -90.151672, -0.572998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(465.28589844, 3661.42359375, 369.73828125), 'rotation':(-0.622894, -90.150452, -0.636536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.27027344, 3655.725625, 369.67632812000005), 'rotation':(-0.638245, -90.150085, -0.652588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(465.25464844, 3650.0278125, 369.61335937999996), 'rotation':(-0.645416, -90.150177, -0.660065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.23902344, 3644.33007812, 369.54933594), 'rotation':(-0.660461, -90.149536, -0.675812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.20765625, 3632.9353125, 369.41707031), 'rotation':(-0.689941, -90.148834, -0.706696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.19203125, 3627.2378125, 369.34871094000005), 'rotation':(-0.705292, -90.148773, -0.722809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.16070312, 3615.84277344, 369.20730469), 'rotation':(-0.734772, -90.147736, -0.753784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.43921875, 3717.19828125, 370.24574219000004), 'rotation':(-0.440063, -90.153809, -0.446838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.51625, 3745.26414062, 370.43242188), 'rotation':(-0.347198, -90.155426, -0.35144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.53171875, 3750.87742188, 370.46425781), 'rotation':(-0.327576, -90.155334, -0.331329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(465.5625, 3762.10398438, 370.52148437999995), 'rotation':(-0.287598, -90.156097, -0.290497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.57792969, 3767.7174999999997, 370.54699219), 'rotation':(-0.267944, -90.155914, -0.270447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(465.59339844, 3773.3307812499997, 370.57039062), 'rotation':(-0.228333, -90.156281, -0.230133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.60875, 3778.944375, 370.59167969000003), 'rotation':(-0.208344, -90.156769, -0.209869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.62425781, 3784.55789062, 370.61148438), 'rotation':(-0.198547, -90.156494, -0.199951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(465.63964844, 3790.17210938, 370.6309375), 'rotation':(-0.198547, -90.156494, -0.199951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.4022265599999, 3798.54617188, 371.55351562000004), 'rotation':(-0.057281, 89.922218, -0.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.39195312, 3793.0825, 371.55894530999996), 'rotation':(-0.057281, 89.922218, -0.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.38457031, 3787.618125, 371.56441406), 'rotation':(-0.057281, 89.922218, -0.057373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.35484375, 3765.76195312, 371.58394531), 'rotation':(-0.032043, 89.922134, -0.032074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.33984375, 3754.83617188, 371.58), 'rotation':(0.043556, 89.922249, 0.043493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.3323828099999, 3749.37179688, 371.57582031), 'rotation':(0.043556, 89.922249, 0.043493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.325, 3743.9075000000003, 371.57164062000004), 'rotation':(0.043829, 89.922234, 0.043755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.31757812, 3738.443125, 371.5675), 'rotation':(0.043556, 89.921707, 0.043498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.3026562499999, 3727.51515625, 371.55824219000004), 'rotation':(0.057777, 89.92231, 0.057672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.2952734400001, 3722.05171875, 371.55070312000004), 'rotation':(0.085295, 89.922379, 0.08505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.15777344, 3621.33519531, 370.95925781), 'rotation':(0.534353, 89.926765, 0.524466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.16554688, 3627.0234375, 371.01179687999996), 'rotation':(0.51447, 89.927071, 0.505291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.17335938, 3632.71191406, 371.06214844000004), 'rotation':(0.494287, 89.926048, 0.485827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.18101562, 3638.39992188, 371.11046875), 'rotation':(0.474418, 89.926369, 0.466616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.2042968799999, 3655.46460938, 371.24378906), 'rotation':(0.409395, 89.924477, 0.40358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.21984375, 3666.84078125, 371.32148437999996), 'rotation':(0.362881, 89.92453, 0.358307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.2364062500001, 3678.21804688, 371.38925781), 'rotation':(0.293111, 89.923065, 0.290133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.24308594, 3683.90578125, 371.41941406), 'rotation':(0.269506, 89.9235, 0.266979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(565.9946875, 3501.5034375, 369.57210938), 'rotation':(0.721213, 89.931305, 0.703211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.0020703099999, 3506.93796875, 369.64054688), 'rotation':(0.720926, 89.931305, 0.702949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.01683594, 3517.806875, 369.77734375), 'rotation':(0.716903, 89.930611, 0.699131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(566.02421875, 3523.24144531, 369.84554688), 'rotation':(0.716903, 89.930611, 0.699131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.0316015599999, 3528.67554688, 369.91335938), 'rotation':(0.708318, 89.930908, 0.69096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.05378906, 3544.97851562, 370.1128125), 'rotation':(0.68709, 89.930183, 0.670769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.06117188, 3550.41285156, 370.17820312000003), 'rotation':(0.68709, 89.930183, 0.670769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.06855469, 3555.84742188, 370.24335937999996), 'rotation':(0.687062, 89.930824, 0.670732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(566.0758593799999, 3561.28171875, 370.30824219000004), 'rotation':(0.679686, 89.929871, 0.663704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(566.0907031200001, 3572.15039062, 370.43578125), 'rotation':(0.650856, 89.929199, 0.636198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.098125, 3577.58421875, 370.49796875), 'rotation':(0.636512, 89.929329, 0.622481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(566.10546875, 3583.01832031, 370.55921875), 'rotation':(0.636512, 89.929329, 0.622481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(671.94097656, 3506.96019531, 371.3134375), 'rotation':(0.455724, 89.578033, 0.448521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(671.98332031, 3512.63453125, 371.35871094000004), 'rotation':(0.435035, 89.577103, 0.428467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.06769531, 3523.9821875, 371.44347655999997), 'rotation':(0.394484, 89.577126, 0.389075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.10992188, 3529.6560156200003, 371.48296875), 'rotation':(0.374062, 89.576263, 0.369205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.15210938, 3535.32984375, 371.52054688), 'rotation':(0.353947, 89.576004, 0.349589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.19433594, 3541.00414062, 371.55617187999997), 'rotation':(0.333224, 89.575752, 0.329367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.23652344, 3546.67796875, 371.58988281), 'rotation':(0.312809, 89.576126, 0.309414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.27875, 3552.3517968799997, 371.62164062000005), 'rotation':(0.302871, 89.575569, 0.299688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.32091797, 3558.02613281, 371.65203125), 'rotation':(0.289627, 89.575211, 0.286721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.3631054699999, 3563.70019531, 371.68125), 'rotation':(0.289627, 89.575211, 0.286721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(672.40527344, 3569.37402344, 371.70894531), 'rotation':(0.26372, 89.575447, 0.261303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(672.44757812, 3575.04761719, 371.7346875), 'rotation':(0.237786, 89.574753, 0.235822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.4897460899999, 3580.72242188, 371.75824219000003), 'rotation':(0.211879, 89.57502, 0.210312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(672.70582031, 3609.75121094, 371.85109375), 'rotation':(0.137, 89.574394, 0.136343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(672.7479882800001, 3615.43042969, 371.8640625), 'rotation':(0.113757, 89.574318, 0.113304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.83251953, 3626.78832031, 371.88242188), 'rotation':(0.045434, 89.573425, 0.045359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(672.95921875, 3643.82519531, 371.89101562), 'rotation':(-0.011993, 89.574173, -0.012024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.00140625, 3649.505625, 371.88992188), 'rotation':(-0.011993, 89.574173, -0.012024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.12816406, 3666.54367188, 371.88613281), 'rotation':(-0.027832, 89.574013, -0.027863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.1704101600001, 3672.223125, 371.88339844), 'rotation':(-0.059387, 89.574081, -0.059509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.2971093799999, 3689.25953125, 371.85773437999995), 'rotation':(-0.138702, 89.573959, -0.139374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(674.10857422, 3798.38992188, 371.52910155999996), 'rotation':(-0.184235, 89.574631, -0.185425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(674.0678710899999, 3792.91453125, 371.54667969), 'rotation':(-0.184235, 89.574631, -0.185425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(674.0271679699999, 3787.43921875, 371.56429688), 'rotation':(-0.184235, 89.574631, -0.185425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.9457421899999, 3776.48851562, 371.5996875), 'rotation':(-0.185089, 89.574936, -0.186279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.90503906, 3771.0129687500003, 371.61738281), 'rotation':(-0.185638, 89.574364, -0.186859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.86431641, 3765.53757812, 371.63523438), 'rotation':(-0.186218, 89.574364, -0.187439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.82361328, 3760.06226562, 371.65304688), 'rotation':(-0.186798, 89.574936, -0.188019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.78296875, 3754.5871875000003, 371.6709375), 'rotation':(-0.187378, 89.574379, -0.188599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(673.74224609, 3749.11179688, 371.68886719), 'rotation':(-0.187927, 89.574959, -0.189178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.66095703, 3738.15820312, 371.7246875), 'rotation':(-0.265228, 89.470718, -0.2677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.62011719, 3732.6862499999997, 371.74214844), 'rotation':(-0.183838, 89.5746, -0.184998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(673.5794140600001, 3727.2109375, 371.75886719000005), 'rotation':(-0.174744, 89.574554, -0.175781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.53869141, 3721.73609375, 371.77488281), 'rotation':(-0.165161, 89.574486, -0.166138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(673.4979882800001, 3716.26101562, 371.79035156), 'rotation':(-0.165161, 89.574486, -0.166138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(251.70640625, 3997.5659375, 367.74261719000003), 'rotation':(-1.611816, -90.143005, -1.704529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(251.69554688000005, 3994.24679688, 367.64917969000004), 'rotation':(-1.611725, -90.143127, -1.704437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(353.78820312000005, 4000.00046875, 368.64875), 'rotation':(-0.493835, -179.995743, -0.502411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(350.86253906, 4000.00046875, 368.80867187999996), 'rotation':(-0.493835, -179.995743, -0.502411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(460.29449219, 3993.8385937499997, 370.7621875), 'rotation':(0.012943, 89.969887, 0.012944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(460.29640625, 3997.5012500000003, 370.76296875), 'rotation':(0.012199, 89.96949, 0.012192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(572.2674999999999, 3994.3776562499997, 371.13457030999996), 'rotation':(0.104543, -90.146301, 0.104171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(572.2471875, 3991.25828125, 371.14027344000004), 'rotation':(0.104543, -90.146301, 0.104171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(676.9262109399999, 3999.4978125, 370.96628906), 'rotation':(0.131467, -90.034363, 0.130874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(679.30175781, 4000.00023438, 370.96511719), 'rotation':(0.131467, -90.034363, 0.130874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1543.07640625, 3819.32515625, 359.79875), 'rotation':(-0.611664, -80.956879, -0.624847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1542.18601562, 3824.92335938, 359.85824219), 'rotation':(-0.611664, -80.956879, -0.624847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1540.40515625, 3836.1198437499997, 359.96910155999996), 'rotation':(-0.540558, -80.957642, -0.550842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1539.5149999999999, 3841.7178125, 360.01820312), 'rotation':(-0.493195, -80.959473, -0.50174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1538.6248828100001, 3847.3151562499997, 360.06386719), 'rotation':(-0.445557, -80.958984, -0.452545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1537.734375, 3852.91359375, 360.10707031), 'rotation':(-0.445557, -80.958984, -0.452545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1536.8438671899999, 3858.5129687500003, 360.14878905999996), 'rotation':(-0.421722, -80.959167, -0.427948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1535.06296875, 3869.71046875, 360.22902344), 'rotation':(-0.391052, -80.960083, -0.396423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1532.39210938, 3886.504375, 360.32433594), 'rotation':(-0.267944, -80.961517, -0.270447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1531.50183594, 3892.10132812, 360.34867188), 'rotation':(-0.267944, -80.961517, -0.270447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1530.61144531, 3897.70070312, 360.3690625), 'rotation':(-0.206177, -80.962036, -0.207642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1516.365, 3987.2721874999997, 360.55042969000004), 'rotation':(-0.145935, -80.962402, -0.146667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1517.19800781, 3982.03585938, 360.53734375), 'rotation':(-0.096405, -80.962585, -0.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1518.0303906200002, 3976.80101562, 360.5284375), 'rotation':(-0.071472, -80.963135, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1519.6956640600001, 3966.3303125, 360.51429687999996), 'rotation':(-0.071503, -80.96283, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1520.52832031, 3961.09546875, 360.50765625), 'rotation':(-0.071472, -80.963135, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1522.19359375, 3950.6259375, 360.49445312000006), 'rotation':(-0.071503, -80.96283, -0.071655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1523.85863281, 3940.15625, 360.48023437999996), 'rotation':(-0.102783, -80.963074, -0.103149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1525.52367188, 3929.68820312, 360.46066406), 'rotation':(-0.12384, -80.961945, -0.12439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1526.3560937500001, 3924.4540625, 360.44871094), 'rotation':(-0.144653, -80.963226, -0.145386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1534.661875, 3817.95632812, 359.7984375), 'rotation':(0.587929, 99.043289, 0.575958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1533.77136719, 3823.55445312, 359.85792969), 'rotation':(0.587929, 99.043289, 0.575958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1531.99070312, 3834.7512500000003, 359.96878906), 'rotation':(0.493201, 99.041801, 0.484758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1531.10046875, 3840.34859375, 360.01792969), 'rotation':(0.445561, 99.039749, 0.438669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1530.2100781200002, 3845.94625, 360.06367187999996), 'rotation':(0.421703, 99.040848, 0.415532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1528.4290624999999, 3857.14382812, 360.14859375), 'rotation':(0.421976, 99.03981, 0.415796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1527.53882812, 3862.7421875, 360.19015625), 'rotation':(0.391062, 99.039909, 0.38575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1526.6483203100001, 3868.3415625, 360.22886719), 'rotation':(0.329304, 99.039116, 0.32554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1525.7581640600001, 3873.9384375, 360.26457030999995), 'rotation':(0.329304, 99.039116, 0.32554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1523.08714844, 3890.7321875, 360.34855469), 'rotation':(0.206169, 99.037956, 0.204686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1522.19679688, 3896.3315625, 360.36894530999996), 'rotation':(0.175529, 99.036926, 0.174463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1517.09328125, 3928.4192187500003, 360.46082031), 'rotation':(0.10276, 99.036934, 0.102401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1515.39734375, 3939.0825, 360.48058594), 'rotation':(0.081949, 99.03756, 0.08172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1513.70128906, 3949.74679688, 360.49503905999995), 'rotation':(0.071478, 99.037148, 0.071309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1512.00511719, 3960.4114062500003, 360.50847655999996), 'rotation':(0.071485, 99.03685, 0.071308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1511.15699219, 3965.74390625, 360.51523438), 'rotation':(0.071485, 99.038094, 0.071297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1509.46058594, 3976.40945312, 360.53007812000004), 'rotation':(0.096408, 99.036545, 0.096086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1507.76402344, 3987.07570312, 360.55335937999996), 'rotation':(0.195453, 99.03791, 0.194125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1506.06714844, 3997.74390625, 360.58914062), 'rotation':(0.245197, 99.038841, 0.243111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1153.12695312, 3715.84304688, 367.35386719), 'rotation':(-0.058136, -80.453064, -0.058258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1155.83227539, 3699.7565624999997, 367.33746094), 'rotation':(-0.062958, -80.454041, -0.06311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1156.73413086, 3694.3940625, 367.33148437999995), 'rotation':(-0.067627, -80.453308, -0.06778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1157.63585938, 3689.03171875, 367.32515625), 'rotation':(-0.067627, -80.453308, -0.06778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1158.53759766, 3683.6696875, 367.31875), 'rotation':(-0.069763, -80.453552, -0.069916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1160.34106445, 3672.9453125, 367.30515625), 'rotation':(-0.07605, -80.453674, -0.076233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1161.24279297, 3667.58296875, 367.2978125), 'rotation':(-0.080231, -80.454102, -0.080444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1162.14464844, 3662.2209375, 367.29011719000005), 'rotation':(-0.084106, -80.453644, -0.084351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1163.04626953, 3656.85867188, 367.28199219000004), 'rotation':(-0.088287, -80.452362, -0.088562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1163.948125, 3651.49632812, 367.27351562), 'rotation':(-0.092468, -80.453613, -0.092773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1164.84984375, 3646.13429688, 367.26464844000003), 'rotation':(-0.096344, -80.454041, -0.096649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1165.75171875, 3640.77195312, 367.25539062), 'rotation':(-0.100525, -80.453583, -0.100861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1166.6534375, 3635.4096875, 367.24578125), 'rotation':(-0.102661, -80.453491, -0.103027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1167.55529297, 3630.04734375, 367.23609375), 'rotation':(-0.102356, -80.453491, -0.102722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1133.34607422, 3833.46414062, 367.39796875), 'rotation':(0.0089, -80.454102, 0.008897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1135.15587891, 3822.70289062, 367.39921875), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1136.0607910200001, 3817.32179688, 367.39945312000003), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1136.96570312, 3811.94070312, 367.3996875), 'rotation':(0.002677, -80.453369, 0.002676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1137.87072266, 3806.55953125, 367.39992187999997), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1138.7756347700001, 3801.1784374999997, 367.40019530999996), 'rotation':(0.002684, -80.453918, 0.002681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1141.49035156, 3785.03609375, 367.39921875), 'rotation':(-0.020142, -80.453156, -0.020203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1143.30029297, 3774.274375, 367.39464844), 'rotation':(-0.027832, -80.453918, -0.027863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1145.11010742, 3763.5121875, 367.38933594), 'rotation':(-0.029358, -80.454163, -0.029388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1146.01501953, 3758.13132812, 367.38644531), 'rotation':(-0.032227, -80.452911, -0.032257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1128.92382812, 3859.7590625000003, 367.37738281), 'rotation':(0.065085, -80.450256, 0.064942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1128.0095214799999, 3865.19578125, 367.37101562000004), 'rotation':(0.065877, -80.453918, 0.065726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1126.18103516, 3876.0690624999997, 367.35757812), 'rotation':(0.072448, -80.452881, 0.072273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1125.26671875, 3881.50585938, 367.35039062000004), 'rotation':(0.072448, -80.452881, 0.072273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1124.35242188, 3886.9426562500003, 367.34296875), 'rotation':(0.07673, -80.454163, 0.076527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1121.609375, 3903.2526562499997, 367.31914062000004), 'rotation':(0.083383, -80.453857, 0.083157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1120.69506836, 3908.68945312, 367.31101562000003), 'rotation':(0.083793, -80.454346, 0.083553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1117.95226562, 3925.0, 367.28601562000006), 'rotation':(0.087324, -80.453064, 0.087071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1117.0378418, 3930.4365625, 367.27746094), 'rotation':(0.087973, -80.453064, 0.087711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1116.12353516, 3935.87328125, 367.26882812), 'rotation':(0.090227, -80.453064, 0.089941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1115.20922852, 3941.31007812, 367.26007812000006), 'rotation':(0.091504, -80.454346, 0.091222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1145.62146484, 3709.066875, 367.34871094000005), 'rotation':(0.053303, 99.545914, 0.053215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1147.42504883, 3698.3424999999997, 367.33746094), 'rotation':(0.058152, 99.546928, 0.058022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1148.3269043, 3692.98, 367.33148437999995), 'rotation':(0.062981, 99.545944, 0.062832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1150.13037109, 3682.255625, 367.31875), 'rotation':(0.067612, 99.5467, 0.067459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1151.03210938, 3676.8932812499997, 367.31207030999997), 'rotation':(0.06975, 99.546463, 0.069593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1153.73742188, 3660.806875, 367.29011719000005), 'rotation':(0.080221, 99.545914, 0.080003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1154.63916016, 3655.44460938, 367.28199219000004), 'rotation':(0.0841, 99.546364, 0.083846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1155.54089844, 3650.08226562, 367.27351562), 'rotation':(0.088273, 99.547638, 0.088011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1156.44262695, 3644.72023438, 367.26464844000003), 'rotation':(0.09246, 99.546371, 0.092171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1157.34448242, 3639.35789062, 367.25539062), 'rotation':(0.096319, 99.545944, 0.096012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1158.24621094, 3633.99585938, 367.24578125), 'rotation':(0.10052, 99.54641, 0.100176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1159.14806641, 3628.63328125, 367.23609375), 'rotation':(0.102671, 99.546494, 0.102304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1124.93738281, 3832.0590625, 367.39796875), 'rotation':(-0.021484, 99.545464, -0.021484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1127.65234375, 3815.9153125000003, 367.39945312000003), 'rotation':(-0.002472, 99.545807, -0.002472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1128.55737305, 3810.53367188, 367.3996875), 'rotation':(-0.002686, 99.546906, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1129.46240234, 3805.15210938, 367.39992187999997), 'rotation':(-0.002686, 99.545807, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1131.27246094, 3794.38890625, 367.40042969), 'rotation':(-0.002686, 99.546906, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1132.17761719, 3789.0078125, 367.40019530999996), 'rotation':(0.005157, 99.545586, 0.00516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1133.08251953, 3783.62671875, 367.39921875), 'rotation':(0.005157, 99.545586, 0.00516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1133.98754883, 3778.24515625, 367.39726562000004), 'rotation':(0.02017, 99.546837, 0.020142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1135.79760742, 3767.4821875, 367.39203125), 'rotation':(0.027833, 99.546387, 0.027819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1136.70263672, 3762.100625, 367.38933594), 'rotation':(0.027826, 99.546082, 0.027805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1137.60753906, 3756.71945312, 367.38644531), 'rotation':(0.029349, 99.54583, 0.029314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1138.51257812, 3751.33789062, 367.38328125), 'rotation':(0.032211, 99.547089, 0.032189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1139.41759766, 3745.9565625, 367.37980469), 'rotation':(0.035401, 99.545837, 0.035358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1107.71606445, 3934.46164062, 367.26882812), 'rotation':(-0.091492, 99.546928, -0.091797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1109.54443359, 3923.589375, 367.28601562000006), 'rotation':(-0.087982, 99.545654, -0.088257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1111.37292969, 3912.7165625, 367.30277344), 'rotation':(-0.08606, 99.545654, -0.086304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1112.28722656, 3907.2803125, 367.31097656), 'rotation':(-0.085083, 99.547333, -0.085358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1113.20141602, 3901.84398438, 367.31910156), 'rotation':(-0.083801, 99.545647, -0.084045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1114.11572266, 3896.40773438, 367.3271875), 'rotation':(-0.083801, 99.545647, -0.084045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1115.02990234, 3890.97171875, 367.33515625), 'rotation':(-0.083405, 99.547089, -0.083649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1115.94421875, 3885.53539062, 367.34296875), 'rotation':(-0.081268, 99.546188, -0.081482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1117.77270508, 3874.6628124999997, 367.35757812), 'rotation':(-0.076752, 99.545853, -0.076935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1119.60095703, 3863.79054688, 367.37101562000004), 'rotation':(-0.068176, 99.54615, -0.068329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1120.51513672, 3858.3542187499997, 367.37738281), 'rotation':(-0.065887, 99.546883, -0.06604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1348.6740625, 3753.79296875, 363.00398437999996), 'rotation':(-0.04068, -80.8302, -0.040741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1351.29796875, 3737.53882812, 362.99742188), 'rotation':(-0.001312, -80.82959, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1352.1725000000001, 3732.12132812, 362.99730469), 'rotation':(-0.001312, -80.829865, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1353.04699219, 3726.70382812, 362.9971875), 'rotation':(-0.001312, -80.829865, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1354.7960156200002, 3715.86867188, 362.99695312000006), 'rotation':(-0.001312, -80.830566, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1355.67054688, 3710.45117188, 362.99679688), 'rotation':(-0.001312, -80.829865, -0.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1357.41980469, 3699.61570312, 362.99695312000006), 'rotation':(0.008278, -80.830048, 0.00828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1358.29429688, 3694.1975, 362.99824219000004), 'rotation':(0.026774, -80.829285, 0.026768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1360.0434375, 3683.36179688, 363.00441406), 'rotation':(0.036582, -80.830078, 0.036538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1360.91796875, 3677.944375, 363.00792969), 'rotation':(0.036582, -80.830078, 0.036538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1363.53675781, 3661.7239062500003, 363.01839844), 'rotation':(7e-06, -81.869873, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1330.61988281, 3865.6328125, 363.28800780999995), 'rotation':(-0.211212, -80.829254, -0.212769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1331.4837499999999, 3860.28171875, 363.26761719), 'rotation':(-0.211212, -80.829254, -0.212769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1332.34765625, 3854.930625, 363.24761719), 'rotation':(-0.198883, -80.829102, -0.200256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1333.21140625, 3849.5793750000003, 363.22847656), 'rotation':(-0.198883, -80.829102, -0.200256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1336.66675781, 3828.1745312499997, 363.15882812), 'rotation':(-0.167511, -80.829926, -0.168488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1343.57738281, 3785.365, 363.05050781), 'rotation':(-0.105682, -80.829895, -0.106079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1344.44117188, 3780.01414062, 363.0409375), 'rotation':(-0.090942, -80.832642, -0.091217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1313.43859375, 3972.06664062, 363.72101562000006), 'rotation':(-0.200317, -80.82959, -0.201721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1314.30322266, 3966.7109375, 363.70207030999995), 'rotation':(-0.204163, -80.82959, -0.205597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1315.16773438, 3961.35546875, 363.68289062), 'rotation':(-0.204163, -80.82959, -0.205597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1316.89660156, 3950.64429688, 363.64320312), 'rotation':(-0.218781, -80.829468, -0.220428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1318.62574219, 3939.933125, 363.60105469), 'rotation':(-0.233398, -80.829346, -0.235291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1320.35472656, 3929.2221875, 363.55628906), 'rotation':(-0.247742, -80.829224, -0.249878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1321.21923828, 3923.86671875, 363.53304688), 'rotation':(-0.255188, -80.829163, -0.257477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1322.08289062, 3918.51078125, 363.50914062000004), 'rotation':(-0.25528, -80.828979, -0.257568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1322.94835938, 3913.15554688, 363.485), 'rotation':(-0.25528, -80.828979, -0.257568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1323.81298828, 3907.7995312499997, 363.46089844), 'rotation':(-0.248352, -80.828369, -0.250519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1324.6775, 3902.44382812, 363.43738281), 'rotation':(-0.241669, -80.829407, -0.243713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1326.40673828, 3891.73195312, 363.39171875), 'rotation':(-0.234985, -80.828827, -0.236908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1354.25132812, 3665.74804688, 363.01492188), 'rotation':(-0.036377, 99.16964, -0.036407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1353.37695312, 3671.16476562, 363.01144531), 'rotation':(-0.036591, 99.16964, -0.036621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1352.50257812, 3676.58132812, 363.00792969), 'rotation':(-0.036591, 99.170494, -0.036621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1351.62816406, 3681.99804688, 363.00441406), 'rotation':(-0.036591, 99.170494, -0.036621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1350.75378906, 3687.41453125, 363.0009375), 'rotation':(-0.026794, 99.169601, -0.026825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1349.00476562, 3698.2490625, 362.99699219), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1347.25597656, 3709.0825, 362.99679688), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1346.38160156, 3714.4990625, 362.99695312000006), 'rotation':(0.001318, 99.169655, 0.001311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1345.5071874999999, 3719.91578125, 362.99707030999997), 'rotation':(0.001318, 99.169655, 0.001311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1344.6328125, 3725.33226562, 362.9971875), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1343.7584375000001, 3730.7487499999997, 362.99730469), 'rotation':(0.001311, 99.170151, 0.001316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1342.88402344, 3736.16554688, 362.99742188), 'rotation':(0.009159, 99.169746, 0.009151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1342.00953125, 3741.58226562, 362.998125), 'rotation':(0.024746, 99.169319, 0.02473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1340.260625, 3752.4167187499997, 363.00398437999996), 'rotation':(0.056301, 99.170219, 0.056188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1336.0279687500001, 3778.63625, 363.0409375), 'rotation':(0.096039, 99.170502, 0.095729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1335.16417969, 3783.9870312499997, 363.05046875), 'rotation':(0.114986, 99.170151, 0.114518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1334.3003125, 3789.3385937499997, 363.0609375), 'rotation':(0.124617, 99.170639, 0.124083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1332.57261719, 3800.04078125, 363.08464844), 'rotation':(0.143564, 99.170288, 0.142845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1331.70886719, 3805.39234375, 363.09792969), 'rotation':(0.153543, 99.169449, 0.152717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1330.84507812, 3810.7434375000003, 363.11210938), 'rotation':(0.162511, 99.170822, 0.161594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1329.98121094, 3816.0946875, 363.1271875), 'rotation':(0.167517, 99.171028, 0.166538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1329.11742188, 3821.44578125, 363.14292969), 'rotation':(0.167517, 99.171028, 0.166538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1328.25355469, 3826.79664062, 363.15878906), 'rotation':(0.173801, 99.169678, 0.172754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1327.38964844, 3832.14796875, 363.17523437999995), 'rotation':(0.186348, 99.17083, 0.185131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1326.52587891, 3837.4990625, 363.19214844000004), 'rotation':(0.186348, 99.17083, 0.185131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1323.93445312, 3853.55273438, 363.24757812), 'rotation':(0.211189, 99.170998, 0.209646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1323.07054688, 3858.90382812, 363.26753906), 'rotation':(0.217808, 99.170715, 0.216158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1305.02283203, 3970.7053125, 363.72101562000006), 'rotation':(0.200323, 99.170395, 0.19893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1305.88746094, 3965.34859375, 363.70203125), 'rotation':(0.200323, 99.170639, 0.198934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1307.61695312, 3954.6354687499997, 363.66332030999996), 'rotation':(0.204134, 99.170418, 0.202697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1310.2108203100001, 3938.56570312, 363.60101562000006), 'rotation':(0.225642, 99.170586, 0.223884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1311.07556641, 3933.20921875, 363.57890625), 'rotation':(0.233381, 99.170647, 0.231502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1312.8048046899999, 3922.49632812, 363.53300780999996), 'rotation':(0.247717, 99.17189, 0.245588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1313.66955078, 3917.13992188, 363.50910156), 'rotation':(0.255183, 99.17083, 0.252916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1315.39904297, 3906.42625, 363.46085938), 'rotation':(0.255258, 99.170731, 0.252999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1316.26378906, 3901.069375, 363.43730469), 'rotation':(0.248352, 99.171898, 0.246208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1317.99316406, 3890.35546875, 363.39167969000005), 'rotation':(0.241652, 99.170601, 0.239631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1729.5592187500001, 3930.07960938, 357.58035156), 'rotation':(-0.567444, -80.662628, -0.578796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1730.48007812, 3924.47507812, 357.52308594000004), 'rotation':(-0.567444, -80.662628, -0.578796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1731.40109375, 3918.870625, 357.46703125), 'rotation':(-0.543762, -80.662811, -0.554169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1733.2428906199998, 3907.66257812, 357.36078125), 'rotation':(-0.52005, -80.663513, -0.529572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1734.1638281199998, 3902.05859375, 357.30945312000006), 'rotation':(-0.50824, -80.664093, -0.517303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1735.08460938, 3896.45507812, 357.2590625), 'rotation':(-0.504791, -80.663605, -0.513763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1736.00546875, 3890.85132812, 357.20894531), 'rotation':(-0.498322, -80.663452, -0.50705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1736.92625, 3885.2473437500003, 357.15910155999995), 'rotation':(-0.498322, -80.663452, -0.50705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1737.8471875, 3879.6440625, 357.10972655999996), 'rotation':(-0.491821, -80.664642, -0.500305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1738.76804688, 3874.03976562, 357.06085937999995), 'rotation':(-0.485138, -80.663696, -0.493408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1739.68898438, 3868.43601562, 357.01226562000005), 'rotation':(-0.485138, -80.663696, -0.493408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1740.60984375, 3862.83226562, 356.96417969000004), 'rotation':(-0.482147, -80.663513, -0.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1741.5306249999999, 3857.22875, 356.91632812000006), 'rotation':(-0.481781, -80.663971, -0.489929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1742.4515625, 3851.625, 356.86855469), 'rotation':(-0.482117, -80.664886, -0.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1743.37234375, 3846.02125, 356.82078125), 'rotation':(-0.481781, -80.663513, -0.48996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1718.43539062, 3997.77195312, 358.39292969), 'rotation':(-0.757721, -80.658264, -0.777985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1720.96609375, 3982.3715625, 358.18867187999996), 'rotation':(-0.713593, -80.659241, -0.731537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1721.80984375, 3977.23734375, 358.12320312), 'rotation':(-0.713593, -80.659241, -0.731537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1722.65328125, 3972.10398438, 358.05839844), 'rotation':(-0.684357, -80.659729, -0.700867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1724.3405468800001, 3961.83617188, 357.93367187999996), 'rotation':(-0.65509, -80.661133, -0.670227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1721.1452343800001, 3928.7057812499997, 357.58042969), 'rotation':(0.591344, 99.337303, 0.579222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1722.0662499999999, 3923.10085938, 357.523125), 'rotation':(0.591344, 99.337303, 0.579222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1722.98734375, 3917.49585938, 357.46714844), 'rotation':(0.567479, 99.337639, 0.556309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1723.90820312, 3911.8915625, 357.41320312000005), 'rotation':(0.543758, 99.336914, 0.53351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1724.82921875, 3906.286875, 357.36085937999997), 'rotation':(0.543758, 99.336914, 0.53351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1726.6711718800002, 3895.078125, 357.25914062000004), 'rotation':(0.508207, 99.336517, 0.499253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1727.59203125, 3889.47414062, 357.20902344), 'rotation':(0.504799, 99.335846, 0.495965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1728.51304688, 3883.8698437499997, 357.15917969000003), 'rotation':(0.504799, 99.335846, 0.495965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1729.4340625, 3878.265625, 357.10976562), 'rotation':(0.498296, 99.336281, 0.489689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1731.27601562, 3867.05710938, 357.01230469), 'rotation':(0.491835, 99.336426, 0.483439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1732.196875, 3861.45289062, 356.96421875), 'rotation':(0.485121, 99.336037, 0.476969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1734.03867188, 3850.24460938, 356.86855469), 'rotation':(0.481795, 99.336472, 0.47374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':3, 'tiley':2, 'location':(1716.77171875, 3955.31882812, 357.87394530999995), 'rotation':(0.684358, 99.340263, 0.668157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':3, 'tiley':2, 'location':(1715.8996875, 3960.6262500000003, 357.93574219000004), 'rotation':(0.684358, 99.340263, 0.668157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1714.1555468800002, 3971.23921875, 358.06492188), 'rotation':(0.713618, 99.340958, 0.696009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':3, 'tiley':2, 'location':(1713.28359375, 3976.54539062, 358.13191406), 'rotation':(0.74322, 99.341019, 0.724125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1710.6675, 3992.4653125, 358.3403125), 'rotation':(0.757693, 99.3424, 0.737857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':3, 'tiley':2, 'location':(1108.40429688, 3982.94070312, 367.18617187999996), 'rotation':(0.108327, -80.973724, 0.107923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1107.62121094, 3987.87085938, 367.1765625), 'rotation':(0.110512, -80.97348, 0.11008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1099.98535156, 3981.59960938, 367.18621094), 'rotation':(-0.110504, 99.026512, -0.110931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':3, 'tiley':2, 'location':(1098.27709961, 3992.35375, 367.1646875), 'rotation':(-0.118561, 99.026939, -0.119049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':3, 'tiley':2, 'location':(1097.42285156, 3997.73070312, 367.15339844000005), 'rotation':(-0.122162, 99.025688, -0.122681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2023.62320312, 4005.26195312, 357.936875), 'rotation':(-0.806641, -80.748016, -0.82959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2020.99351562, 4021.42554688, 358.15851562000006), 'rotation':(-0.774719, -80.749939, -0.795898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2020.1171875, 4026.81296875, 358.22921875), 'rotation':(-0.742859, -80.749756, -0.762329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2018.3639062500001, 4037.59007812, 358.36417969), 'rotation':(-0.695343, -80.752197, -0.712372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2017.48734375, 4042.97851562, 358.42910156), 'rotation':(-0.678131, -80.750732, -0.694336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2016.61085938, 4048.3659374999997, 358.49121094000003), 'rotation':(-0.643219, -80.753143, -0.657806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2015.734375, 4053.75367188, 358.55015625), 'rotation':(-0.608368, -80.75351, -0.621399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2014.85789062, 4059.14132812, 358.6059375), 'rotation':(-0.574066, -80.752991, -0.585663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2013.98132812, 4064.5290625, 358.65859375), 'rotation':(-0.539185, -80.754913, -0.549408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2013.1048437499999, 4069.9167187499997, 358.70808594000005), 'rotation':(-0.504608, -80.755554, -0.51355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2011.3517968800002, 4080.69210938, 358.79761719000004), 'rotation':(-0.469696, -80.75531, -0.477417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2010.47523438, 4086.08054688, 358.83835938), 'rotation':(-0.435089, -80.756683, -0.441742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2002.9376562500001, 4079.32078125, 358.79761719000004), 'rotation':(0.435083, 99.24292, 0.428513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2004.6907812499999, 4068.5442187500003, 358.70808594000005), 'rotation':(0.469698, 99.243874, 0.462041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2006.44382812, 4057.76757812, 358.60589844000003), 'rotation':(0.539189, 99.245087, 0.529111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2007.3204687500001, 4052.379375, 358.55007812), 'rotation':(0.574077, 99.245773, 0.562664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2008.19703125, 4046.99125, 358.49113280999995), 'rotation':(0.608338, 99.247292, 0.595515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2009.95007812, 4036.21414062, 358.3640625), 'rotation':(0.678135, 99.248047, 0.662228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2010.82679688, 4030.8254687500003, 358.29691406), 'rotation':(0.695327, 99.249924, 0.678612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2012.58023438, 4020.0478125, 358.15839844000004), 'rotation':(0.742851, 99.250244, 0.723774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2014.33351562, 4009.27046875, 358.01269530999997), 'rotation':(0.774728, 99.250832, 0.753989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2035.4759374999999, 4556.77832031, 361.81542969000003), 'rotation':(-0.443787, -80.659302, -0.450714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2037.2576562499999, 4545.93945312, 361.73074219), 'rotation':(-0.433044, -80.659454, -0.439636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2038.1486718800002, 4540.52050781, 361.68921875), 'rotation':(-0.427002, -80.661621, -0.433411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2039.9346875, 4529.65773438, 361.60753905999997), 'rotation':(-0.503571, -79.87088, -0.512451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2040.8215625, 4524.26320312, 361.56753906), 'rotation':(-0.420532, -80.659607, -0.426758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2041.71242188, 4518.84421875, 361.52726562000004), 'rotation':(-0.421143, -80.661682, -0.427368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2043.49414062, 4508.00632812, 361.44640625), 'rotation':(-0.423431, -80.659546, -0.429718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2044.38515625, 4502.58742188, 361.40582030999997), 'rotation':(-0.424347, -80.661652, -0.430664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2045.27601562, 4497.16796875, 361.36515625), 'rotation':(-0.425018, -80.660797, -0.431366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2046.166875, 4491.74902344, 361.32441406), 'rotation':(-0.426239, -80.661621, -0.432648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2047.94875, 4480.91113281, 361.24265625), 'rotation':(-0.426636, -80.661407, -0.433014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2015.8865624999999, 4675.93164062, 362.73976562), 'rotation':(-0.410706, -80.661072, -0.416626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2016.78429688, 4670.47167969, 362.70011719), 'rotation':(-0.410706, -80.661072, -0.416626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2018.57960938, 4659.55125, 362.62066405999997), 'rotation':(-0.415253, -80.661896, -0.421295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2019.4772656199998, 4654.09132812, 362.58054688), 'rotation':(-0.418304, -80.66098, -0.424469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2020.3747656199998, 4648.63183594, 362.54019531), 'rotation':(-0.421692, -80.660919, -0.427917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2021.2725, 4643.17140625, 362.49945312000006), 'rotation':(-0.425049, -80.659546, -0.431396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2022.17015625, 4637.71140625, 362.45835938), 'rotation':(-0.427704, -80.661682, -0.434143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2023.06773438, 4632.25195312, 362.41699219000003), 'rotation':(-0.431122, -80.660767, -0.437653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2024.8630468800002, 4621.3315625, 362.33328125), 'rotation':(-0.43576, -80.660614, -0.442413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2025.760625, 4615.8715625, 362.29121094000004), 'rotation':(-0.43924, -80.660767, -0.446014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2027.55601562, 4604.95214844, 362.20621094), 'rotation':(-0.44574, -80.660278, -0.452728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2038.6452343800001, 4484.94875, 361.28359375), 'rotation':(0.426293, 99.339226, 0.419985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2036.86328125, 4495.78757812, 361.36519531), 'rotation':(0.424373, 99.340454, 0.418124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2035.97226562, 4501.2075, 361.40585938), 'rotation':(0.423417, 99.339172, 0.417189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2035.0813281199999, 4506.62695312, 361.44644531), 'rotation':(0.422092, 99.338326, 0.415917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2034.1903125, 4512.04640625, 361.48691406), 'rotation':(0.421177, 99.340401, 0.415023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2033.29929688, 4517.46582031, 361.52726562000004), 'rotation':(0.420501, 99.338295, 0.414366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2031.51734375, 4528.3046875, 361.60777344), 'rotation':(0.421634, 99.338318, 0.415469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2030.62632812, 4533.72460938, 361.64824219), 'rotation':(0.427044, 99.340454, 0.42072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2029.73523438, 4539.1440625, 361.68925780999996), 'rotation':(0.433054, 99.339287, 0.426546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2027.9532812500001, 4549.98390625, 361.77289062000006), 'rotation':(0.443792, 99.33947, 0.43696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2026.1711718800002, 4560.82324219, 361.85859375), 'rotation':(0.455157, 99.340889, 0.447969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2025.28015625, 4566.24265625, 361.90226562000004), 'rotation':(0.460491, 99.338913, 0.453123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2020.9373437499999, 4592.65773438, 362.11921875), 'rotation':(0.452582, 99.339806, 0.445474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2020.0397656199998, 4598.11671875, 362.16300780999995), 'rotation':(0.445793, 99.339333, 0.438888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2019.14234375, 4603.57664062, 362.20625), 'rotation':(0.439236, 99.340302, 0.432532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2018.24476562, 4609.035625, 362.24898437999997), 'rotation':(0.439236, 99.340302, 0.432532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2015.55210938, 4625.41453125, 362.37535155999996), 'rotation':(0.431081, 99.338333, 0.424629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2014.65453125, 4630.87351562, 362.41703125), 'rotation':(0.427747, 99.340492, 0.421406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2011.96179688, 4647.25195312, 362.54023437999996), 'rotation':(0.418315, 99.340355, 0.412242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2011.06429688, 4652.71140625, 362.58058594), 'rotation':(0.415289, 99.338974, 0.409302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2010.16671875, 4658.17089844, 362.62070312000003), 'rotation':(0.41225, 99.338936, 0.406357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2009.26914062, 4663.63039062, 362.66046875), 'rotation':(0.410706, 99.338936, 0.404853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2232.0598437500003, 4600.07078125, 362.55230469), 'rotation':(-0.679962, -80.440918, -0.696259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2232.98804688, 4594.5625, 362.48601562000005), 'rotation':(-0.674713, -80.440186, -0.690735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2234.84421875, 4583.546875, 362.35515625), 'rotation':(-0.663696, -80.44043, -0.679199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2235.7725, 4578.0390625, 362.29058594), 'rotation':(-0.65802, -80.440582, -0.673279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2236.70070312, 4572.53125, 362.22660156), 'rotation':(-0.652618, -80.438934, -0.667633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2237.62867188, 4567.02296875, 362.16316406), 'rotation':(-0.647339, -80.440796, -0.662109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2238.556875, 4561.51515625, 362.10019531), 'rotation':(-0.64444, -80.439453, -0.659058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2239.48507812, 4556.00734375, 362.03734375), 'rotation':(-0.639832, -80.439087, -0.654236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2240.41359375, 4550.49953125, 361.97472655999997), 'rotation':(-0.639832, -80.439087, -0.654236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2243.1979687499997, 4533.97558594, 361.79074219), 'rotation':(-0.611481, -80.440369, -0.624634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2244.1262500000003, 4528.46777344, 361.73097656), 'rotation':(-0.60675, -80.441742, -0.61969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2245.05445312, 4522.95945312, 361.67167969), 'rotation':(-0.60675, -80.441742, -0.61969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2245.98242188, 4517.45164062, 361.61253905999996), 'rotation':(-0.606689, -80.440765, -0.619659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2213.9184375, 4707.87109375, 363.65429687999995), 'rotation':(-0.441345, -80.444702, -0.448181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2215.74289062, 4697.03027344, 363.56925780999995), 'rotation':(-0.450012, -80.44339, -0.457123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2219.3915625, 4675.34960938, 363.38273438), 'rotation':(-0.522827, -80.444702, -0.53244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2220.30320312, 4669.92921875, 363.33175781), 'rotation':(-0.558929, -80.441467, -0.569916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2221.2153125, 4664.50976562, 363.27894531), 'rotation':(-0.576965, -80.443665, -0.588684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2222.12742188, 4659.089375, 363.22441405999996), 'rotation':(-0.586426, -80.441223, -0.598511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2223.95164062, 4648.24902344, 363.11179688), 'rotation':(-0.596832, -80.44104, -0.609375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2224.86375, 4642.82859375, 363.05417969), 'rotation':(-0.617859, -80.441193, -0.631317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2226.68820312, 4631.98828125, 362.93394530999996), 'rotation':(-0.660187, -80.440857, -0.675537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2237.55539062, 4516.0346875, 361.61253905999996), 'rotation':(0.606726, 99.55825, 0.593981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2232.9209375, 4543.5746875, 361.91265625), 'rotation':(0.639825, 99.560913, 0.625645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2231.99414062, 4549.08300781, 361.97476562), 'rotation':(0.644449, 99.557953, 0.63007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2230.14015625, 4560.09863281, 362.10019531), 'rotation':(0.647352, 99.559189, 0.63284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2229.213125, 4565.60644531, 362.16316406), 'rotation':(0.652631, 99.561043, 0.637884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2228.2864062500003, 4571.11476562, 362.22660156), 'rotation':(0.65802, 99.559418, 0.643045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2227.359375, 4576.62257812, 362.29058594), 'rotation':(0.663689, 99.559555, 0.648454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2226.43265625, 4582.13132812, 362.35519531), 'rotation':(0.669304, 99.561432, 0.653791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2225.505625, 4587.63914062, 362.4203125), 'rotation':(0.6747, 99.559814, 0.65895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2223.651875, 4598.65527344, 362.55230469), 'rotation':(0.685642, 99.559189, 0.669384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2219.19289062, 4625.15382812, 362.871875), 'rotation':(0.639155, 99.559265, 0.625014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2218.28101562, 4630.57375, 362.93394530999996), 'rotation':(0.639155, 99.559265, 0.625014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2214.63234375, 4652.254375, 363.16859375), 'rotation':(0.58642, 99.558769, 0.574504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2212.808125, 4663.09523438, 363.27894531), 'rotation':(0.558989, 99.559364, 0.54816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2211.8957812500003, 4668.51464844, 363.33175781), 'rotation':(0.540883, 99.558174, 0.53074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.98390625, 4673.93505859, 363.38277344), 'rotation':(0.504799, 99.557518, 0.495955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.0715625000003, 4679.35546875, 363.43207031), 'rotation':(0.486419, 99.557198, 0.478211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.2473437500003, 4690.1953125, 363.5253125), 'rotation':(0.45, 99.556602, 0.442972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2207.33546875, 4695.61572266, 363.56925780999995), 'rotation':(0.441353, 99.555283, 0.434593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2419.84644531, 4625.25929688, 364.00375), 'rotation':(-0.931396, -81.108948, -0.962067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2420.70628906, 4619.75390625, 363.913125), 'rotation':(-0.928009, -81.109039, -0.958435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2421.56617188, 4614.24804688, 363.82277344), 'rotation':(-0.924591, -81.106689, -0.954803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2422.42601562, 4608.7421875, 363.73277344), 'rotation':(-0.921173, -81.109253, -0.951172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2425.005625, 4592.22507812, 363.46480469), 'rotation':(-0.912506, -81.110657, -0.941925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2426.72558594, 4581.21289062, 363.28894531), 'rotation':(-0.883118, -81.10791, -0.910675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2428.4455468799997, 4570.20070312, 363.11792969000004), 'rotation':(-0.859222, -81.108643, -0.885284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2429.30566406, 4564.69484375, 363.03433594), 'rotation':(-0.847504, -81.109833, -0.872864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2431.02539062, 4553.68210938, 362.87097656), 'rotation':(-0.823608, -81.110535, -0.847534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2431.88523438, 4548.17625, 362.79101562000005), 'rotation':(-0.817505, -81.11264, -0.841095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2402.16039062, 4738.50146484, 365.50664062000004), 'rotation':(-0.564789, -81.115936, -0.575989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2403.00632812, 4733.08496094, 365.45257812000006), 'rotation':(-0.565125, -81.118591, -0.576355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2403.85230469, 4727.66845703, 365.39851562), 'rotation':(-0.564789, -81.115936, -0.575989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2406.38964844, 4711.42089844, 365.22914062), 'rotation':(-0.633911, -81.116058, -0.648071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2407.23558594, 4706.00439453, 365.16851562000005), 'rotation':(-0.680023, -81.115021, -0.69632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2408.08128906, 4700.58984375, 365.10460937999994), 'rotation':(-0.680023, -81.115021, -0.69632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2408.92699219, 4695.17333984, 365.03953125), 'rotation':(-0.725952, -81.113892, -0.744537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2410.61867188, 4684.34277344, 364.90027344000003), 'rotation':(-0.748871, -81.111694, -0.768646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2411.464375, 4678.92724609, 364.82851562), 'rotation':(-0.765442, -81.113983, -0.786102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2412.3103125, 4673.51123047, 364.75527344), 'rotation':(-0.79837, -81.112457, -0.820862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2414.00171875, 4662.68066406, 364.60148438), 'rotation':(-0.831207, -81.110138, -0.855591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2414.84742188, 4657.265625, 364.52113281), 'rotation':(-0.863831, -81.111176, -0.890167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2423.46214844, 4546.85890625, 362.79101562000005), 'rotation':(0.823666, 98.890305, 0.800241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2422.60253906, 4552.36425781, 362.8709375), 'rotation':(0.835209, 98.887093, 0.811122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2421.74265625, 4557.87011719, 362.95195312000004), 'rotation':(0.847592, 98.891022, 0.822782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2420.8828125, 4563.37597656, 363.03425781), 'rotation':(0.85921, 98.888664, 0.833729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2420.02269531, 4568.88132812, 363.11785155999996), 'rotation':(0.87074, 98.890862, 0.844568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2419.16285156, 4574.3871875, 363.20277344000004), 'rotation':(0.883123, 98.892082, 0.856203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2418.30296875, 4579.89304688, 363.28886719), 'rotation':(0.894666, 98.888908, 0.867035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2417.443125, 4585.39890625, 363.37628906), 'rotation':(0.907042, 98.89283, 0.878652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2416.58324219, 4590.90382812, 363.46472656), 'rotation':(0.914371, 98.890511, 0.885523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2415.72363281, 4596.4096875, 363.55371094000003), 'rotation':(0.917772, 98.893089, 0.888705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2414.86375, 4601.91503906, 363.64304688), 'rotation':(0.921181, 98.890732, 0.891904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2414.00390625, 4607.41992188, 363.73269531), 'rotation':(0.924582, 98.89328, 0.89509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2413.1440625, 4612.9253125, 363.82269531), 'rotation':(0.927997, 98.890945, 0.89829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2411.42429688, 4623.93554688, 364.00363281), 'rotation':(0.934807, 98.893616, 0.904661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2405.57984375, 4661.35695312, 364.60136719), 'rotation':(0.798312, 98.888916, 0.776308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2404.73390625, 4666.77296875, 364.67945312000006), 'rotation':(0.798312, 98.888916, 0.776308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2402.19605469, 4683.02148438, 364.90019530999996), 'rotation':(0.725953, 98.886116, 0.707725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2401.35035156, 4688.4375, 364.97011719), 'rotation':(0.725953, 98.886116, 0.707725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2398.81296875, 4704.68457031, 365.1684375), 'rotation':(0.63391, 98.882477, 0.619999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2397.96703125, 4710.10205078, 365.22914062), 'rotation':(0.587963, 98.882942, 0.575994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2397.12109375, 4715.51757812, 365.28757812000003), 'rotation':(0.587963, 98.882942, 0.575994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2396.27515625, 4720.93457031, 365.34382812), 'rotation':(0.564768, 98.884048, 0.553719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2394.58324219, 4731.76806641, 365.45253906), 'rotation':(0.564768, 98.884048, 0.553719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2393.73730469, 4737.18505859, 365.50660156), 'rotation':(0.564945, 98.881233, 0.553882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3448.25046875, 4797.3671875, 367.96097656), 'rotation':(0.053357, -80.436371, 0.053262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3449.16796875, 4791.92041016, 367.96613281), 'rotation':(0.055639, -80.438049, 0.055528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3450.08546875, 4786.47363281, 367.97148438), 'rotation':(0.058214, -80.438904, 0.058103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3451.0034375, 4781.02587891, 367.97710937999994), 'rotation':(0.060474, -80.438049, 0.060354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3452.83835938, 4770.13232422, 367.98910156), 'rotation':(0.065338, -80.43634, 0.065184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3453.75609375, 4764.68554688, 367.99546875), 'rotation':(0.068247, -80.438049, 0.068093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3454.67359375, 4759.23876953, 368.00203125), 'rotation':(0.069046, -80.437134, 0.06888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3455.59105469, 4753.79150391, 368.00867187999995), 'rotation':(0.069046, -80.439758, 0.068884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3456.50855469, 4748.34472656, 368.01535156), 'rotation':(0.069046, -80.437134, 0.06888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3457.42601562, 4742.89794922, 368.02199219), 'rotation':(0.068384, -80.437134, 0.068219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3458.34375, 4737.45117188, 368.02859375), 'rotation':(0.068384, -80.437134, 0.068219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3459.26125, 4732.00439453, 368.03519531), 'rotation':(0.068377, -80.439758, 0.068224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3460.17871094, 4726.55761719, 368.04175781), 'rotation':(0.068049, -80.437134, 0.067889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3461.09644531, 4721.11035156, 368.04832031), 'rotation':(0.067721, -80.438049, 0.067555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3462.01390625, 4715.66357422, 368.05484375), 'rotation':(0.067674, -80.437622, 0.067527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3443.77417969, 4823.94042969, 367.938125), 'rotation':(0.047955, -80.438751, 0.047876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3442.84472656, 4829.45898438, 367.93347656), 'rotation':(0.047948, -80.437042, 0.047873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3441.91503906, 4834.97705078, 367.9290625), 'rotation':(0.045182, -80.438873, 0.045103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3440.98558594, 4840.49511719, 367.92484375), 'rotation':(0.042996, -80.43866, 0.04293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3439.12648438, 4851.53125, 367.91648438), 'rotation':(0.042996, -80.43866, 0.04293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3438.19679688, 4857.04931641, 367.91230469000004), 'rotation':(0.042996, -80.43866, 0.04293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3436.33765625, 4868.08496094, 367.9034375), 'rotation':(0.044949, -80.437378, 0.044874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3435.40820312, 4873.60302734, 367.89851562), 'rotation':(0.052435, -80.437378, 0.05234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3434.47851562, 4879.12109375, 367.89320312), 'rotation':(0.056021, -80.437378, 0.055908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3433.5490625, 4884.63867188, 367.88753906), 'rotation':(0.059928, -80.439087, 0.059813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3432.61960938, 4890.15673828, 367.88148437999996), 'rotation':(0.0635, -80.437378, 0.063373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3430.76050781, 4901.19287109, 367.86816405999997), 'rotation':(0.071, -80.439911, 0.070829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3453.60570312, 4714.25244141, 368.05484375), 'rotation':(-0.067719, 99.560204, -0.067871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3452.6877343799997, 4719.70068359, 368.04828125), 'rotation':(-0.068054, 99.562828, -0.068207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3451.77, 4725.14892578, 368.04175781), 'rotation':(-0.06839, 99.561951, -0.068542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3449.01683594, 4741.49414062, 368.02195312000003), 'rotation':(-0.069061, 99.560204, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3448.09886719, 4746.94238281, 368.0153125), 'rotation':(-0.069061, 99.562836, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3447.18117188, 4752.390625, 368.00867187999995), 'rotation':(-0.069061, 99.562836, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3445.34546875, 4763.28710938, 367.99542969000004), 'rotation':(-0.065338, 99.561958, -0.065491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3444.42773438, 4768.73535156, 367.9890625), 'rotation':(-0.063385, 99.561089, -0.063538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3442.59226562, 4779.63232422, 367.97707031), 'rotation':(-0.058228, 99.561066, -0.058319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3440.75632812, 4790.52929688, 367.96609375), 'rotation':(-0.053375, 99.561928, -0.053467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3421.42308594, 4905.29833984, 367.86109375), 'rotation':(-0.07309, 99.5616, -0.073273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3422.35230469, 4899.78222656, 367.86816405999997), 'rotation':(-0.07309, 99.5616, -0.073273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3424.2109375, 4888.74902344, 367.88148437999996), 'rotation':(-0.067444, 99.560944, -0.067566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3425.1403906200003, 4883.23242188, 367.88753906), 'rotation':(-0.063507, 99.562637, -0.06366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3426.99851562, 4872.19970703, 367.89851562), 'rotation':(-0.05603, 99.560913, -0.056122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3427.92796875, 4866.68310547, 367.9034375), 'rotation':(-0.048523, 99.562607, -0.048615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3428.8571875, 4861.16699219, 367.90800780999996), 'rotation':(-0.044952, 99.560898, -0.045013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3430.71582031, 4850.13378906, 367.91644531), 'rotation':(-0.042725, 99.562737, -0.042786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3431.645, 4844.6171875, 367.920625), 'rotation':(-0.042999, 99.56131, -0.04306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3432.57445312, 4839.10058594, 367.92484375), 'rotation':(-0.042999, 99.562737, -0.04306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3433.50367188, 4833.58398438, 367.92902344000004), 'rotation':(-0.042999, 99.560593, -0.04306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3216.89671875, 4760.13916016, 367.13617187999995), 'rotation':(-0.119446, -80.86261, -0.119965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3217.77027344, 4754.70751953, 367.12472656), 'rotation':(-0.118805, -80.863708, -0.119293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3219.51734375, 4743.84423828, 367.10195312), 'rotation':(-0.117188, -80.863037, -0.117676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3221.26441406, 4732.98095703, 367.07941406), 'rotation':(-0.117401, -80.863068, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3223.01148438, 4722.11767578, 367.05679688), 'rotation':(-0.119263, -80.861908, -0.119751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3224.75878906, 4711.25537109, 367.03339844000004), 'rotation':(-0.127747, -80.864044, -0.128326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3225.63232422, 4705.82373047, 367.02117187999994), 'rotation':(-0.131592, -80.861877, -0.132202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3227.37939453, 4694.96044922, 366.995625), 'rotation':(-0.139801, -80.861816, -0.140503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3229.12597656, 4684.09765625, 366.96878906), 'rotation':(-0.143921, -80.863953, -0.144653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3230.87304688, 4673.234375, 366.940625), 'rotation':(-0.149963, -80.861542, -0.150757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3211.7678125, 4792.02832031, 367.19773438), 'rotation':(-0.101166, -80.863953, -0.101532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3209.13550781, 4808.39501953, 367.22316406), 'rotation':(-0.085541, -80.862762, -0.085815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3208.25804688, 4813.85058594, 367.23066406), 'rotation':(-0.077576, -80.863861, -0.077789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3207.380625, 4819.30615234, 367.23789062000003), 'rotation':(-0.073639, -80.863556, -0.073822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3206.50316406, 4824.76171875, 367.24519531), 'rotation':(-0.077148, -80.862183, -0.077332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3204.74853516, 4835.67382812, 367.26152344), 'rotation':(-0.084534, -80.862915, -0.084778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3203.87109375, 4841.12988281, 367.27058594000005), 'rotation':(-0.091675, -80.865234, -0.091949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3202.99339844, 4846.58544922, 367.28035156), 'rotation':(-0.098785, -80.862122, -0.099121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3202.11597656, 4852.04150391, 367.29082030999996), 'rotation':(-0.106201, -80.862854, -0.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3201.23851562, 4857.49755859, 367.301875), 'rotation':(-0.113007, -80.865143, -0.113464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3200.36109375, 4862.95361328, 367.31355469000005), 'rotation':(-0.120728, -80.86203, -0.121246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3199.48363281, 4868.40917969, 367.32589844), 'rotation':(-0.127563, -80.862732, -0.128113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3222.45582031, 4671.88039062, 366.940625), 'rotation':(0.148038, 99.136055, 0.147274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3221.58226562, 4677.31201172, 366.95488280999996), 'rotation':(0.143919, 99.138206, 0.143198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3220.70898438, 4682.74365234, 366.96878906), 'rotation':(0.139807, 99.136009, 0.139125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3218.96214844, 4693.60644531, 366.995625), 'rotation':(0.135709, 99.135994, 0.135057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3218.08837891, 4699.03808594, 367.00855469000004), 'rotation':(0.131584, 99.13813, 0.130981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3217.21484375, 4704.46972656, 367.02117187999994), 'rotation':(0.127745, 99.135963, 0.127176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3216.34130859, 4709.90136719, 367.03339844000004), 'rotation':(0.123374, 99.138107, 0.122831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3215.46777344, 4715.33203125, 367.04527344), 'rotation':(0.119241, 99.135925, 0.118752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3212.84716797, 4731.62695312, 367.07941406), 'rotation':(0.117206, 99.136925, 0.116725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3211.09984375, 4742.49023438, 367.10195312), 'rotation':(0.117834, 99.135674, 0.117351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3209.35277344, 4753.35351562, 367.12472656), 'rotation':(0.119467, 99.134636, 0.118965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3208.47925781, 4758.78515625, 367.13617187999995), 'rotation':(0.119521, 99.139053, 0.119022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3192.82128906, 4856.14306641, 367.301875), 'rotation':(0.12073, 99.137207, 0.120215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3193.69873047, 4850.68701172, 367.29082030999996), 'rotation':(0.113026, 99.137932, 0.112581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3195.45386719, 4839.77539062, 367.27058594000005), 'rotation':(0.098771, 99.134789, 0.098438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3196.33128906, 4834.31933594, 367.26152344), 'rotation':(0.091661, 99.137856, 0.091379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3197.21117188, 4828.86523438, 367.25300781), 'rotation':(0.091661, 99.137856, 0.091379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3199.84082031, 4812.49609375, 367.23066406), 'rotation':(0.07365, 99.137199, 0.073457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3200.71826172, 4807.04052734, 367.22316406), 'rotation':(0.07757, 99.135628, 0.077361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3203.35058594, 4790.67382812, 367.19773438), 'rotation':(0.093533, 99.135681, 0.093228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3204.22802734, 4785.21875, 367.18828125), 'rotation':(0.093533, 99.135681, 0.093228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2987.21044922, 4723.1015625, 366.34242187999996), 'rotation':(-0.571289, -80.400848, -0.582764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2988.1315918, 4717.65039062, 366.28730469000004), 'rotation':(-0.574646, -80.401672, -0.586273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2990.89599609, 4701.29541016, 366.1196875), 'rotation':(-0.584625, -80.401489, -0.596649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2992.73901367, 4690.39257812, 366.00621094), 'rotation':(-0.59317, -80.402618, -0.60553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2993.66040039, 4684.94091797, 365.94902344), 'rotation':(-0.592224, -80.399658, -0.604584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2995.50341797, 4674.03759766, 365.83488280999995), 'rotation':(-0.588104, -80.398804, -0.600281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2996.42480469, 4668.5859375, 365.778125), 'rotation':(-0.586029, -80.401611, -0.598114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2999.18920898, 4652.23046875, 365.60917969), 'rotation':(-0.579742, -80.398987, -0.591583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3000.1105957, 4646.77882812, 365.55335937999996), 'rotation':(-0.577637, -80.402679, -0.589355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3001.03222656, 4641.32714844, 365.49761719), 'rotation':(-0.576477, -80.399017, -0.588165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3001.95361328, 4635.87546875, 365.44195312000005), 'rotation':(-0.576721, -80.401825, -0.588409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2982.75, 4749.49072266, 366.60441405999995), 'rotation':(-0.55249, -80.40094, -0.563232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2981.83447266, 4754.90625, 366.65710937999995), 'rotation':(-0.55249, -80.40094, -0.563232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2980.91918945, 4760.32275391, 366.70945312000003), 'rotation':(-0.545868, -80.402649, -0.556366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2980.00366211, 4765.73828125, 366.76125), 'rotation':(-0.539093, -80.400635, -0.549316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2977.25732422, 4781.98632812, 366.91449219000003), 'rotation':(-0.529144, -80.407288, -0.539001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2976.34228516, 4787.40185547, 366.96429687999995), 'rotation':(-0.524109, -80.399902, -0.533783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2975.42675781, 4792.81787109, 367.01320312), 'rotation':(-0.513885, -80.402527, -0.523163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2973.59619141, 4803.64892578, 367.10804687999996), 'rotation':(-0.493408, -80.402893, -0.501984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2972.68066406, 4809.06542969, 367.15410155999996), 'rotation':(-0.483154, -80.401428, -0.491333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2971.76538086, 4814.48095703, 367.19914062000004), 'rotation':(-0.472961, -80.403229, -0.480804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2970.84985352, 4819.89648438, 367.24324219000005), 'rotation':(-0.462738, -80.403381, -0.470245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2969.01928711, 4830.72900391, 367.32941406), 'rotation':(-0.447296, -80.402618, -0.454315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2993.54638672, 4634.45851562, 365.44203125), 'rotation':(0.576441, 99.600281, 0.564927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2992.62475586, 4639.91164062, 365.49769531), 'rotation':(0.57767, 99.598236, 0.566104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2991.703125, 4645.36476562, 365.55339844), 'rotation':(0.579746, 99.601013, 0.568106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2990.78125, 4650.81789062, 365.60929688), 'rotation':(0.581843, 99.598312, 0.570118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2988.93798828, 4661.72414062, 365.72171875), 'rotation':(0.586017, 99.598404, 0.574118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2987.09472656, 4672.63037109, 365.835), 'rotation':(0.590203, 99.59848, 0.578138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2985.2512207, 4683.53662109, 365.94921875), 'rotation':(0.593147, 99.597359, 0.580972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2984.32958984, 4688.98974609, 366.00644531), 'rotation':(0.591884, 99.602264, 0.579748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2983.40795898, 4694.44287109, 366.06335937999995), 'rotation':(0.584623, 99.598495, 0.572786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2982.48632812, 4699.89550781, 366.11992188), 'rotation':(0.581577, 99.602058, 0.569865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2981.56469727, 4705.34814453, 366.17613280999996), 'rotation':(0.577752, 99.598366, 0.566182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2980.64282227, 4710.80126953, 366.23199219), 'rotation':(0.574665, 99.598282, 0.563213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2978.79980469, 4721.70703125, 366.34269530999995), 'rotation':(0.56778, 99.600868, 0.556613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2961.52661133, 4823.89746094, 367.2865625), 'rotation':(0.447295, 99.597374, 0.440352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2962.44116211, 4818.48291016, 367.24332031), 'rotation':(0.452452, 99.598061, 0.445346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2963.35571289, 4813.06835938, 367.19921875), 'rotation':(0.462725, 99.596596, 0.455299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2966.09936523, 4796.82519531, 367.06121094), 'rotation':(0.493427, 99.597107, 0.484973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2967.01416016, 4791.41064453, 367.01332031), 'rotation':(0.503651, 99.599754, 0.494855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2967.92871094, 4785.99658203, 366.96445312000003), 'rotation':(0.513849, 99.596649, 0.504687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2969.7578125, 4775.16796875, 366.86402344000004), 'rotation':(0.529121, 99.604134, 0.519427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2970.67236328, 4769.75292969, 366.81296875), 'rotation':(0.532441, 99.598686, 0.522611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2972.50170898, 4758.92382812, 366.7096875), 'rotation':(0.539093, 99.599358, 0.529013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2973.41650391, 4753.50927734, 366.65734375), 'rotation':(0.545889, 99.597351, 0.53556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2757.99488281, 4686.08984375, 365.07148437999996), 'rotation':(-0.697784, -80.604004, -0.714935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2758.90257812, 4680.6015625, 365.00375), 'rotation':(-0.706909, -80.601196, -0.724518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2761.62523438, 4664.1371875, 364.79496094), 'rotation':(-0.735046, -80.603088, -0.754089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2762.53246094, 4658.64890625, 364.7234375), 'rotation':(-0.744171, -80.600281, -0.763702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2763.44019531, 4653.16015625, 364.65101562), 'rotation':(-0.753326, -80.6026, -0.773346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2764.34765625, 4647.67140625, 364.57785156), 'rotation':(-0.753357, -80.600525, -0.773376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2765.25537109, 4642.18261719, 364.50496094000005), 'rotation':(-0.742859, -80.6008, -0.762329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2768.88574219, 4620.22609375, 364.22324219), 'rotation':(-0.702454, -80.602631, -0.719849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2750.85791016, 4729.25341797, 365.57121094), 'rotation':(-0.617126, -80.604004, -0.630524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2749.94703125, 4734.76269531, 365.63101562), 'rotation':(-0.617126, -80.604004, -0.630524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2748.12523438, 4745.78173828, 365.74777344), 'rotation':(-0.593811, -80.604736, -0.606232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2747.21410156, 4751.29101562, 365.80570312000003), 'rotation':(-0.594269, -80.605316, -0.606689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2746.30322266, 4756.80029297, 365.86386719), 'rotation':(-0.596558, -80.604431, -0.6091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2744.48121094, 4767.81933594, 365.98070312000004), 'rotation':(-0.600067, -80.60437, -0.612732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2742.65894531, 4778.83837891, 366.09828125), 'rotation':(-0.603882, -80.604248, -0.61673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2740.83691406, 4789.85644531, 366.21660155999996), 'rotation':(-0.607666, -80.605042, -0.620667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2739.92601562, 4795.36572266, 366.2759375), 'rotation':(-0.608704, -80.603943, -0.621765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2749.57910156, 4684.72607422, 365.07179687999997), 'rotation':(0.688674, 99.399208, 0.672257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2750.48681641, 4679.23632812, 365.0040625), 'rotation':(0.697765, 99.395981, 0.680924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2751.39453125, 4673.74658203, 364.93542969000003), 'rotation':(0.706911, 99.398781, 0.689625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2752.30224609, 4668.25734375, 364.86578125), 'rotation':(0.716391, 99.399033, 0.698637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2754.11742188, 4657.2778125, 364.72371094000005), 'rotation':(0.735017, 99.39949, 0.716338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2755.93310547, 4646.29734375, 364.57804688), 'rotation':(0.753322, 99.399971, 0.7337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2756.84082031, 4640.80761719, 364.50515625), 'rotation':(0.753288, 99.398636, 0.733677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2757.74878906, 4635.316875, 364.43320312000003), 'rotation':(0.742872, 99.396698, 0.723786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2758.65673828, 4629.82617188, 364.36222655999995), 'rotation':(0.732702, 99.398949, 0.714134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2759.5646875, 4624.3359375, 364.29230469000004), 'rotation':(0.722531, 99.398674, 0.704477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2761.380625, 4613.35449219, 364.15539062000005), 'rotation':(0.702505, 99.398186, 0.685447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2763.19677734, 4602.37402344, 364.02234375), 'rotation':(0.682117, 99.396851, 0.666027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2764.10449219, 4596.88378906, 363.95660155999997), 'rotation':(0.67707, 99.397003, 0.661215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2731.51390625, 4793.97949219, 366.27597656), 'rotation':(0.608713, 99.393356, 0.595896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2732.42457031, 4788.47167969, 366.21667969000003), 'rotation':(0.608659, 99.395164, 0.595827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2733.33544922, 4782.96386719, 366.15742187999996), 'rotation':(0.607709, 99.39579, 0.594925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2734.24609375, 4777.45605469, 366.09835938), 'rotation':(0.605804, 99.39576, 0.593087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2735.15722656, 4771.94775391, 366.03949219000003), 'rotation':(0.603836, 99.39489, 0.591212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2736.97875, 4760.93164062, 365.92230469000003), 'rotation':(0.600005, 99.394791, 0.587549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2737.88941406, 4755.42382812, 365.86402344000004), 'rotation':(0.598147, 99.395599, 0.585765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2738.80029297, 4749.91601562, 365.80585937999996), 'rotation':(0.596508, 99.39473, 0.584177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2739.7109375, 4744.40820312, 365.74796875), 'rotation':(0.594322, 99.395508, 0.582094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2741.53246094, 4733.39257812, 365.63121094), 'rotation':(0.601159, 99.395119, 0.588649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2742.443125, 4727.88476562, 365.57144531), 'rotation':(0.601159, 99.395119, 0.588649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2743.35375, 4722.37744141, 365.51105469000004), 'rotation':(0.617067, 99.39547, 0.60389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2744.26464844, 4716.86962891, 365.44941406), 'rotation':(0.632434, 99.396309, 0.618582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2745.17503906, 4711.36230469, 365.38691406), 'rotation':(0.632434, 99.396309, 0.618582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3484.36425781, 4567.26953125, 367.90417969000003), 'rotation':(0.031801, -81.692657, 0.031758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3485.1794531200003, 4561.68703125, 367.90523437999997), 'rotation':(0.032027, -81.693176, 0.031999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3485.994375, 4556.1059375, 367.90839844000004), 'rotation':(0.032027, -81.693176, 0.031999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3488.43871094, 4539.36425781, 367.9178125), 'rotation':(0.050086, -81.692505, 0.049998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3489.25367188, 4533.78222656, 367.92167969), 'rotation':(0.050086, -81.692505, 0.049998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3491.69824219, 4517.03953125, 367.94246094000005), 'rotation':(0.122226, -81.692688, 0.121703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3492.51367188, 4511.45703125, 367.95441406), 'rotation':(0.158576, -81.692078, 0.157695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3494.1486718799997, 4500.25929688, 367.98304687999996), 'rotation':(0.392442, -80.534973, 0.387099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3496.58714844, 4483.55421875, 368.02507812000005), 'rotation':(0.076184, -81.693115, 0.075988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3497.401875, 4477.97507812, 368.03421875), 'rotation':(0.076184, -81.693115, 0.075988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3499.03125, 4466.81445312, 368.04476562), 'rotation':(0.015921, -81.693268, 0.015908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3499.8459375, 4461.23484375, 368.04703125), 'rotation':(0.015921, -81.693268, 0.015908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3501.47558594, 4450.07375, 368.05019531), 'rotation':(0.016181, -81.692688, 0.016177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3502.29027344, 4444.49316406, 368.05179688), 'rotation':(0.015921, -81.695374, 0.015916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3503.9196875, 4433.33351562, 368.04972655999995), 'rotation':(-0.101074, -81.694122, -0.10141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3504.7341406200003, 4427.75488281, 368.04179688), 'rotation':(-0.101074, -81.693451, -0.10144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3505.5490625, 4422.17382812, 368.031875), 'rotation':(-0.101074, -81.691833, -0.10141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3506.36375, 4416.59328125, 368.02191406), 'rotation':(-0.101074, -81.691833, -0.10141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3507.99316406, 4405.433125, 368.00148437999997), 'rotation':(-0.115997, -81.693024, -0.116455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3508.80785156, 4399.85203125, 367.99003905999996), 'rotation':(-0.145721, -81.692902, -0.146454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3509.62257812, 4394.27246094, 367.97691405999996), 'rotation':(-0.145721, -81.692902, -0.146454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3510.4375, 4388.691875, 367.96257812000005), 'rotation':(-0.175659, -81.692749, -0.176727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3511.25195312, 4383.11230469, 367.94578125), 'rotation':(-0.175659, -81.692749, -0.176727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3512.06664062, 4377.53273438, 367.92832031), 'rotation':(-0.205383, -81.692535, -0.206879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3512.88132812, 4371.95164062, 367.908125), 'rotation':(-0.220703, -81.692291, -0.222412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3480.4611718799997, 4594.0034375, 367.94886719000004), 'rotation':(-0.111877, -81.693451, -0.112305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3479.6440625, 4599.59960938, 367.96035156), 'rotation':(-0.116486, -81.694366, -0.116974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3478.82691406, 4605.19484375, 367.97226562000003), 'rotation':(-0.121368, -81.692078, -0.121857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3478.01, 4610.79054688, 367.98457031), 'rotation':(-0.125946, -81.692078, -0.126495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3477.193125, 4616.38671875, 367.99738281), 'rotation':(-0.130829, -81.694336, -0.131439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3476.37597656, 4621.98195312, 368.01054688), 'rotation':(-0.135406, -81.692017, -0.136047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3473.92480469, 4638.7690625, 368.05265625), 'rotation':(-0.144867, -81.691986, -0.145599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3473.10789062, 4644.36476562, 368.0671875), 'rotation':(-0.147369, -81.6922, -0.148132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3472.29125, 4649.95945312, 368.07828125), 'rotation':(-0.108429, -81.69458, -0.108826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3470.65796875, 4661.14550781, 368.0825), 'rotation':(0.007602, -81.693604, 0.007613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3469.02390625, 4672.33691406, 368.08101562), 'rotation':(0.007336, -81.693604, 0.007343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3504.4455468799997, 4370.71828125, 367.908125), 'rotation':(0.205377, 98.307465, 0.203919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3503.63085938, 4376.29835938, 367.92832031), 'rotation':(0.175652, 98.307266, 0.174572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3502.81640625, 4381.87695312, 367.94578125), 'rotation':(0.145729, 98.307098, 0.144995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3502.00195312, 4387.45554688, 367.96253906), 'rotation':(0.145729, 98.307098, 0.144995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3500.37304688, 4398.61476562, 367.99003905999996), 'rotation':(0.115977, 98.306946, 0.115519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3499.558125, 4404.19484375, 368.00148437999997), 'rotation':(0.10136, 98.306526, 0.101009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3498.74367188, 4409.7734375, 368.01191406), 'rotation':(0.101073, 98.306526, 0.100726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3497.92894531, 4415.35351562, 368.021875), 'rotation':(0.101059, 98.308151, 0.100711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3496.29957031, 4426.51367188, 368.04179688), 'rotation':(0.101073, 98.306526, 0.100726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3495.48511719, 4432.09132812, 368.04972655999995), 'rotation':(0.042443, 98.305832, 0.042376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3493.8559375, 4443.24953125, 368.05179688), 'rotation':(-0.016174, 98.306717, -0.016205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3492.2265625, 4454.4096875, 368.04863280999996), 'rotation':(-0.01593, 98.306717, -0.01593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3491.411875, 4459.98925781, 368.04707031), 'rotation':(-0.01593, 98.306717, -0.01593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3489.78246094, 4471.1484375, 368.04121094000004), 'rotation':(-0.076202, 98.30571, -0.076385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3488.96800781, 4476.72753906, 368.03421875), 'rotation':(-0.116608, 98.307037, -0.117065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3486.51878906, 4493.50046875, 367.99839844), 'rotation':(-0.392456, 99.465012, -0.397858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3484.89476562, 4504.62402344, 367.96742187999996), 'rotation':(-0.122223, 98.307304, -0.122742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3484.08007812, 4510.20507812, 367.95445312000004), 'rotation':(-0.122223, 98.307304, -0.122742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3481.63550781, 4526.94773438, 367.92664062000006), 'rotation':(-0.050079, 98.307083, -0.050171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3480.00609375, 4538.10789062, 367.91785156), 'rotation':(-0.032043, 98.304939, -0.032074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3479.19140625, 4543.68847656, 367.9146875), 'rotation':(-0.031799, 98.30735, -0.03183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3478.37671875, 4549.26855469, 367.9115625), 'rotation':(-0.032043, 98.306801, -0.032074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3462.223125, 4659.90578125, 368.0825), 'rotation':(-0.007355, 98.306389, -0.007355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3464.67382812, 4643.12011719, 368.06714844000004), 'rotation':(0.108416, 98.307777, 0.10801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3465.49097656, 4637.52296875, 368.05257812), 'rotation':(0.147375, 98.306152, 0.146623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3466.308125, 4631.92578125, 368.03820312000005), 'rotation':(0.144875, 98.308022, 0.144147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3467.1252343799997, 4626.32910156, 368.02414062), 'rotation':(0.140285, 98.307983, 0.13961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3467.94261719, 4620.73144531, 368.01050781), 'rotation':(0.140285, 98.307983, 0.13961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3468.76, 4615.13378906, 367.99730469), 'rotation':(0.135415, 98.305695, 0.134777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3469.57714844, 4609.53710938, 367.98457031), 'rotation':(0.130825, 98.307945, 0.130231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3470.39429688, 4603.93898438, 367.9721875), 'rotation':(0.125935, 98.305664, 0.125394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3472.02882812, 4592.74460938, 367.94882812000003), 'rotation':(0.116482, 98.305618, 0.116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3254.09351562, 4530.31054688, 366.10445312), 'rotation':(-0.404144, -80.756256, -0.409882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3255.00048828, 4524.73535156, 366.06457030999997), 'rotation':(-0.397186, -80.754639, -0.40271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3255.90771484, 4519.1596875, 366.0253125), 'rotation':(-0.3909, -80.756439, -0.396271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3256.8146875, 4513.58445312, 365.98675781), 'rotation':(-0.38736, -80.756744, -0.392639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3258.62890625, 4502.43359375, 365.91046875), 'rotation':(-0.382629, -80.755493, -0.387787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3260.44335938, 4491.28367188, 365.83539062000006), 'rotation':(-0.375549, -80.75473, -0.380493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3261.35058594, 4485.70800781, 365.79839844), 'rotation':(-0.372284, -80.755615, -0.377136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3263.16480469, 4474.55761719, 365.72546875), 'rotation':(-0.365479, -80.755707, -0.370178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3264.07177734, 4468.98242188, 365.68953125), 'rotation':(-0.361603, -80.755737, -0.366211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3264.97900391, 4463.40722656, 365.65390625), 'rotation':(-0.360077, -80.757202, -0.364655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3265.88597656, 4457.83203125, 365.61835937999996), 'rotation':(-0.362122, -80.755432, -0.366699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3268.60742188, 4441.10644531, 365.51046875), 'rotation':(-0.370422, -80.756897, -0.375244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3270.42164062, 4429.95703125, 365.43714844000004), 'rotation':(-0.374573, -80.75528, -0.379486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3271.32861328, 4424.38183594, 365.40023438), 'rotation':(-0.376495, -80.755859, -0.38147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3272.23583984, 4418.80664062, 365.363125), 'rotation':(-0.37677, -80.758057, -0.381775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3273.1428125, 4413.23144531, 365.32601562), 'rotation':(-0.37738, -80.755432, -0.382385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3274.05003906, 4407.65625, 365.28878906), 'rotation':(-0.379669, -80.756714, -0.384735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3274.95703125, 4402.08105469, 365.25144531), 'rotation':(-0.379669, -80.756714, -0.384735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3275.86402344, 4396.50585938, 365.21398437999994), 'rotation':(-0.381409, -80.755371, -0.386505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3276.77099609, 4390.93066406, 365.17636719), 'rotation':(-0.383148, -80.757324, -0.388306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3277.67822266, 4385.35546875, 365.13859375), 'rotation':(-0.384277, -80.755219, -0.389465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3278.58519531, 4379.78078125, 365.10070312000005), 'rotation':(-0.377869, -80.756348, -0.382904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3279.49267578, 4374.20507812, 365.06328125), 'rotation':(-0.36438, -80.755707, -0.369049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3281.306875, 4363.05421875, 364.99199219), 'rotation':(-0.337952, -80.759399, -0.341949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3282.21410156, 4357.47851562, 364.95835938), 'rotation':(-0.324768, -80.756195, -0.328461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3284.02832031, 4346.32714844, 364.89523438), 'rotation':(-0.29834, -80.75647, -0.301453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3284.93578125, 4340.75148438, 364.86570312000003), 'rotation':(-0.28479, -80.757416, -0.287628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3248.95679688, 4561.88132812, 366.34007812000004), 'rotation':(-0.426971, -80.754944, -0.43338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3247.21949219, 4572.5590625, 366.42039062000003), 'rotation':(-0.423492, -80.755005, -0.42981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3245.48242188, 4583.23679688, 366.49882812000004), 'rotation':(-0.413208, -80.755798, -0.419189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3242.87646484, 4599.25292969, 366.61320312000004), 'rotation':(-0.401886, -80.754852, -0.407562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3242.0078125, 4604.59132812, 366.64804688), 'rotation':(-0.379059, -80.756836, -0.384094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3240.27050781, 4615.26804688, 366.71136719000003), 'rotation':(-0.333008, -80.757416, -0.336884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3238.53369141, 4625.94484375, 366.76632812), 'rotation':(-0.287598, -80.755432, -0.290497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3237.66480469, 4631.28273438, 366.79066406), 'rotation':(-0.264374, -80.758911, -0.266846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3236.79613281, 4636.6215625, 366.81320312), 'rotation':(-0.241821, -80.756653, -0.243866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3276.52099609, 4339.38328125, 364.86574219), 'rotation':(0.298336, 99.24353, 0.295249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3273.79931641, 4356.11132812, 364.95835938), 'rotation':(0.337965, 99.243965, 0.333998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3271.98486328, 4367.26269531, 365.02695312000003), 'rotation':(0.36435, 99.243462, 0.359744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3269.26318359, 4383.98976562, 365.13859375), 'rotation':(0.383174, 99.245277, 0.378065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3268.35595703, 4389.56492188, 365.17636719), 'rotation':(0.381398, 99.242645, 0.376347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3267.44898438, 4395.14015625, 365.21398437999994), 'rotation':(0.379642, 99.244606, 0.374634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3266.54199219, 4400.71582031, 365.25148437999997), 'rotation':(0.377423, 99.243233, 0.372485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3264.72777344, 4411.86671875, 365.32605469000003), 'rotation':(0.376781, 99.244141, 0.371853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3263.82054688, 4417.441875, 365.36316406), 'rotation':(0.3765, 99.244141, 0.371584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3261.09912109, 4434.1675, 365.47398438), 'rotation':(0.370415, 99.244659, 0.365647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3260.19214844, 4439.74316406, 365.51050781), 'rotation':(0.36646, 99.24305, 0.361801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3259.28492188, 4445.31835938, 365.54667969), 'rotation':(0.362109, 99.242996, 0.357555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3257.47070312, 4456.46921875, 365.61835937999996), 'rotation':(0.360053, 99.244484, 0.355558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3255.65625, 4467.62011719, 365.68957030999997), 'rotation':(0.365524, 99.242561, 0.360883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3254.74925781, 4473.1953125, 365.72550780999995), 'rotation':(0.3684, 99.244331, 0.363694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3253.84203125, 4478.77050781, 365.76179687999996), 'rotation':(0.372279, 99.24437, 0.367477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3252.93480469, 4484.34617188, 365.7984375), 'rotation':(0.375524, 99.241875, 0.370618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3252.02783203, 4489.921875, 365.83546875), 'rotation':(0.378748, 99.244476, 0.373768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3249.30615234, 4506.6484375, 365.94859375), 'rotation':(0.387367, 99.24559, 0.382158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3248.39892578, 4512.22414062, 365.98679688), 'rotation':(0.390871, 99.24276, 0.385579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3246.58472656, 4523.37546875, 366.06464844000004), 'rotation':(0.404122, 99.242943, 0.398446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3228.38134766, 4635.25488281, 366.81320312), 'rotation':(0.230205, 99.243568, 0.228367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3230.11865234, 4624.57910156, 366.76632812), 'rotation':(0.26441, 99.241875, 0.261976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3232.72412109, 4608.56492188, 366.68078125), 'rotation':(0.332979, 99.244247, 0.329127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3234.46117188, 4597.88914062, 366.61324219), 'rotation':(0.379014, 99.244827, 0.374035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3235.32933594, 4592.55125, 366.57636719000004), 'rotation':(0.401916, 99.243462, 0.396315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3236.19800781, 4587.21289062, 366.53792969), 'rotation':(0.401916, 99.243462, 0.396315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3237.9353125, 4576.53613281, 366.45988280999995), 'rotation':(0.413199, 99.244202, 0.407278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3238.80394531, 4571.19726562, 366.42046875), 'rotation':(0.416949, 99.244911, 0.410911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3239.67236328, 4565.85839844, 366.38042969), 'rotation':(0.423458, 99.244118, 0.417237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3241.40966797, 4555.18164062, 366.29988281), 'rotation':(0.426784, 99.245033, 0.420453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3024.48046875, 4493.44578125, 364.0215625), 'rotation':(-0.576263, -81.132507, -0.587952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3025.34692383, 4487.88867188, 363.965), 'rotation':(-0.576782, -81.132507, -0.588501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3026.21337891, 4482.3315625, 363.90839844000004), 'rotation':(-0.576782, -81.132507, -0.588501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3027.9465332, 4471.21726562, 363.79511719000004), 'rotation':(-0.577393, -81.133057, -0.589111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3028.81298828, 4465.66015625, 363.73835937999996), 'rotation':(-0.580902, -81.131714, -0.592773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3030.54614258, 4454.54589844, 363.62382812000004), 'rotation':(-0.587646, -81.131592, -0.599792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3032.27905273, 4443.43210938, 363.50777344), 'rotation':(-0.601349, -81.131287, -0.614075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3033.14550781, 4437.875, 363.44921875), 'rotation':(-0.601349, -81.131287, -0.614075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3034.87866211, 4426.76125, 363.33089844), 'rotation':(-0.605743, -81.130768, -0.618652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3035.74511719, 4421.20410156, 363.27152344), 'rotation':(-0.605743, -81.130768, -0.618652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3036.61157227, 4415.64648438, 363.21203125), 'rotation':(-0.608032, -81.13028, -0.621033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3038.34448242, 4404.53273438, 363.09261719), 'rotation':(-0.610046, -81.132172, -0.623138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3040.07739258, 4393.41796875, 362.97273437999996), 'rotation':(-0.612305, -81.130646, -0.625488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3040.94384766, 4387.86085938, 362.91265625), 'rotation':(-0.613281, -81.130798, -0.626526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3041.81054688, 4382.30371094, 362.85246094), 'rotation':(-0.613251, -81.131409, -0.626495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3043.54345703, 4371.18945312, 362.73210937999994), 'rotation':(-0.609924, -81.128632, -0.623016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3044.41015625, 4365.63183594, 362.67246094), 'rotation':(-0.603119, -81.131348, -0.615936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3045.27661133, 4360.0746875, 362.61347656), 'rotation':(-0.596619, -81.132263, -0.609161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3046.14331055, 4354.51757812, 362.55515625), 'rotation':(-0.589874, -81.131622, -0.602142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3047.00976562, 4348.95996094, 362.49738281), 'rotation':(-0.586792, -81.131653, -0.598907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3047.8762207, 4343.4028125, 362.43980469), 'rotation':(-0.578613, -81.130188, -0.590393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3049.60961914, 4332.28757812, 362.32699219), 'rotation':(-0.546051, -81.131622, -0.556519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3050.47583008, 4326.73, 362.27292969), 'rotation':(-0.530273, -81.13446, -0.540131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3051.3425293, 4321.171875, 362.22050780999996), 'rotation':(-0.513824, -81.132233, -0.523102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3052.20922852, 4315.61375, 362.16972655999996), 'rotation':(-0.497711, -81.132507, -0.506439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3053.94238281, 4304.49851562, 362.07304688), 'rotation':(-0.465546, -81.134796, -0.473175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3054.80883789, 4298.94046875, 362.02722656), 'rotation':(-0.457397, -81.13327, -0.464722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3020.31811523, 4520.14160156, 364.29261719000004), 'rotation':(-0.574188, -81.130737, -0.585785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3019.4440918, 4525.7465625, 364.34921875), 'rotation':(-0.571655, -81.132629, -0.58316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3016.82226562, 4542.56101562, 364.51695312000004), 'rotation':(-0.560699, -81.132324, -0.571747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3015.07446289, 4553.77050781, 364.62707030999997), 'rotation':(-0.555603, -81.131287, -0.566437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3014.20068359, 4559.37546875, 364.68179688), 'rotation':(-0.552673, -81.133118, -0.563416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3013.32666016, 4564.98, 364.73652344000004), 'rotation':(-0.552673, -81.133118, -0.563416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3012.45263672, 4570.58496094, 364.79125), 'rotation':(-0.552979, -81.130615, -0.563721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3011.57885742, 4576.19042969, 364.84609375), 'rotation':(-0.552673, -81.133118, -0.563416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3010.70483398, 4581.79539062, 364.90125), 'rotation':(-0.55545, -81.131989, -0.566315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3009.83081055, 4587.39992188, 364.95683594), 'rotation':(-0.56015, -81.130188, -0.571198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3043.78564453, 4314.29882812, 362.16972655999996), 'rotation':(0.513821, 98.867767, 0.504673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3042.91894531, 4319.85640625, 362.22046875), 'rotation':(0.530303, 98.866318, 0.520553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3041.18579102, 4330.97117188, 362.32695312000004), 'rotation':(0.562459, 98.868675, 0.551496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3039.45263672, 4342.0859375, 362.43972656), 'rotation':(0.586782, 98.871078, 0.574853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3038.58618164, 4347.64304688, 362.49734375), 'rotation':(0.586788, 98.868355, 0.574866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3036.85327148, 4358.75734375, 362.6134375), 'rotation':(0.603126, 98.868645, 0.590533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3035.12011719, 4369.8715625, 362.73207031), 'rotation':(0.613289, 98.871124, 0.600265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3034.25341797, 4375.42820312, 362.7921875), 'rotation':(0.613255, 98.868591, 0.600224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3033.38696289, 4380.98535156, 362.85242187999995), 'rotation':(0.613255, 98.868591, 0.600224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3031.65405273, 4392.10007812, 362.97269531), 'rotation':(0.610086, 98.868294, 0.597195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3027.32177734, 4419.88378906, 363.27140625), 'rotation':(0.604724, 98.868462, 0.592059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3026.45532227, 4425.4409375, 363.33085938), 'rotation':(0.604724, 98.868462, 0.592059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3025.58886719, 4430.99804688, 363.39011719), 'rotation':(0.60135, 98.868713, 0.588822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3023.85595703, 4442.11132812, 363.50773438), 'rotation':(0.594582, 98.868561, 0.582347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3022.98950195, 4447.66796875, 363.56605469000004), 'rotation':(0.587649, 98.869896, 0.575686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3022.12304688, 4453.22460938, 363.62375), 'rotation':(0.580894, 98.868286, 0.569213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3021.2565918, 4458.78171875, 363.68121094), 'rotation':(0.580894, 98.868286, 0.569213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3019.5234375, 4469.895, 363.795), 'rotation':(0.577048, 98.8675, 0.565506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3017.79077148, 4481.00929688, 363.90832030999997), 'rotation':(0.576263, 98.867485, 0.564755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2999.65893555, 4597.29445312, 365.06824219000003), 'rotation':(0.562678, 98.869476, 0.551706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3000.53295898, 4591.68898438, 365.0125), 'rotation':(0.562685, 98.866997, 0.551716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3001.40698242, 4586.08351562, 364.95679687999996), 'rotation':(0.562678, 98.869476, 0.551706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3002.28125, 4580.47804688, 364.90121094), 'rotation':(0.560212, 98.86808, 0.549337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3003.15527344, 4574.87304688, 364.84605469), 'rotation':(0.555451, 98.867981, 0.544758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3004.02929688, 4569.26710938, 364.79121094000004), 'rotation':(0.552624, 98.866104, 0.542045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3004.90332031, 4563.66164062, 364.73648438), 'rotation':(0.552979, 98.869377, 0.542394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3006.65112305, 4552.45070312, 364.62703125), 'rotation':(0.552665, 98.86937, 0.542078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3008.39916992, 4541.24023438, 364.51691406), 'rotation':(0.555629, 98.867554, 0.544932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3009.27319336, 4535.63523438, 364.46136719000003), 'rotation':(0.560663, 98.867149, 0.549774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3010.1472168, 4530.02976562, 364.40539062000005), 'rotation':(0.566202, 98.869438, 0.555082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3011.02124023, 4524.42429688, 364.34914062), 'rotation':(0.566202, 98.869438, 0.555082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3011.89501953, 4518.81882812, 364.2925), 'rotation':(0.571694, 98.867874, 0.560369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2795.71851562, 4456.70117188, 362.30617187999997), 'rotation':(-0.689636, -80.613647, -0.706421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2796.635, 4451.15234375, 362.23847656), 'rotation':(-0.69162, -80.611786, -0.708466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2797.55152344, 4445.60351562, 362.17054687999996), 'rotation':(-0.692322, -80.613678, -0.709229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2799.38453125, 4434.50632812, 362.0346875), 'rotation':(-0.692322, -80.613678, -0.709229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2801.21753906, 4423.40867188, 361.89902344), 'rotation':(-0.685272, -80.612732, -0.701813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2802.13402344, 4417.85984375, 361.8315625), 'rotation':(-0.685272, -80.612732, -0.701813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2803.05054688, 4412.31101562, 361.76425781), 'rotation':(-0.680847, -80.612335, -0.697205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2803.96703125, 4406.7621875, 361.69738280999997), 'rotation':(-0.676025, -80.613953, -0.692139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2805.80003906, 4395.66453125, 361.564375), 'rotation':(-0.67392, -80.614044, -0.689911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2806.7165625, 4390.11570312, 361.498125), 'rotation':(-0.669617, -80.611328, -0.685394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2808.54957031, 4379.01757812, 361.36742187999994), 'rotation':(-0.653015, -80.612579, -0.66806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2810.3828125, 4367.91894531, 361.24042969000004), 'rotation':(-0.636169, -80.615692, -0.650421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2812.21558594, 4356.82078125, 361.11699219), 'rotation':(-0.618988, -80.616058, -0.632477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2814.04859375, 4345.723125, 360.99691406), 'rotation':(-0.598511, -80.615051, -0.611115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2816.79833984, 4329.07570312, 360.82203125), 'rotation':(-0.566559, -80.615234, -0.57785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2817.71484375, 4323.52640625, 360.76550781), 'rotation':(-0.566559, -80.615234, -0.57785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2818.63160156, 4317.9775, 360.70988280999995), 'rotation':(-0.550568, -80.616028, -0.561218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2820.46460938, 4306.87890625, 360.60144531), 'rotation':(-0.54248, -80.615967, -0.552826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2821.38109375, 4301.33007812, 360.54820312000004), 'rotation':(-0.538849, -80.614655, -0.549042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2822.29761719, 4295.78078125, 360.49507812), 'rotation':(-0.538849, -80.614655, -0.549042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2823.21410156, 4290.23195312, 360.4421875), 'rotation':(-0.531097, -80.616486, -0.541016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2824.13085938, 4284.68265625, 360.39), 'rotation':(-0.52359, -80.616638, -0.533203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2825.04736328, 4279.13375, 360.33824219), 'rotation':(-0.52359, -80.616638, -0.533203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2826.88037109, 4268.035625, 360.23625), 'rotation':(-0.512268, -80.61615, -0.521484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2828.71337891, 4256.9375, 360.13554688), 'rotation':(-0.512299, -80.617554, -0.521545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2791.32128906, 4483.32179688, 362.62972656), 'rotation':(-0.68338, -80.61264, -0.699829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2790.400625, 4488.89550781, 362.69648437999996), 'rotation':(-0.677734, -80.613586, -0.693909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2789.48023438, 4494.46875, 362.76269530999997), 'rotation':(-0.672211, -80.612915, -0.688141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2787.63916016, 4505.61570312, 362.89347655999995), 'rotation':(-0.661102, -80.615601, -0.676483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2785.79808594, 4516.76269531, 363.02210937999996), 'rotation':(-0.649933, -80.613434, -0.664795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2784.87792969, 4522.33398438, 363.08558594000004), 'rotation':(-0.650574, -80.530273, -0.665466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2783.03636719, 4533.48390625, 363.21210937999996), 'rotation':(-0.641083, -80.614258, -0.655548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2782.11572266, 4539.05761719, 363.2753125), 'rotation':(-0.641083, -80.614258, -0.655548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2780.27441406, 4550.20460938, 363.4015625), 'rotation':(-0.639771, -80.614288, -0.654175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2778.43335938, 4561.35203125, 363.52769530999996), 'rotation':(-0.639465, -80.610779, -0.65387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2788.22167969, 4449.77246094, 362.23859375), 'rotation':(0.689651, 99.386322, 0.673202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2789.13818359, 4444.223125, 362.17070312000004), 'rotation':(0.691625, 99.388222, 0.675077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2790.0546875, 4438.67429688, 362.10273437999996), 'rotation':(0.691625, 99.388222, 0.675077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2792.80445312, 4422.02734375, 361.89910155999996), 'rotation':(0.690122, 99.387878, 0.673641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2793.7209375, 4416.47804688, 361.83160155999997), 'rotation':(0.690122, 99.387878, 0.673641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2795.55394531, 4405.38039062, 361.69746094000004), 'rotation':(0.680867, 99.386139, 0.664822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2796.47046875, 4399.83105469, 361.63082031), 'rotation':(0.680867, 99.386139, 0.664822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2799.22021484, 4383.1840625, 361.43242188), 'rotation':(0.669604, 99.388695, 0.654085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2800.13671875, 4377.63378906, 361.36753905999996), 'rotation':(0.660944, 99.384865, 0.645829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2801.05322266, 4372.08445312, 361.30351562000004), 'rotation':(0.653034, 99.38739, 0.638269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2801.96996094, 4366.53515625, 361.24046875), 'rotation':(0.644094, 99.384483, 0.629724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2802.88648438, 4360.98632812, 361.17828125), 'rotation':(0.636171, 99.387016, 0.622169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2803.80296875, 4355.43703125, 361.11703125), 'rotation':(0.627565, 99.386841, 0.613938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2805.63623047, 4344.33835938, 360.99695312000006), 'rotation':(0.606692, 99.384842, 0.59394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2806.55273438, 4338.78953125, 360.93796875), 'rotation':(0.606692, 99.384842, 0.59394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2807.46949219, 4333.23921875, 360.87925780999996), 'rotation':(0.598523, 99.384933, 0.58611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2808.38597656, 4327.68992188, 360.82207030999996), 'rotation':(0.582519, 99.384605, 0.570782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2810.21923828, 4316.59179688, 360.70988280999995), 'rotation':(0.566578, 99.384766, 0.555452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2812.0525, 4305.4921875, 360.60148438), 'rotation':(0.550547, 99.383972, 0.540051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2813.88550781, 4294.3940625, 360.49511719000003), 'rotation':(0.542467, 99.384041, 0.53227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2814.80199219, 4288.8446875, 360.4421875), 'rotation':(0.53884, 99.385338, 0.528776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2816.63525391, 4277.74609375, 360.33828125), 'rotation':(0.531102, 99.383499, 0.521317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2817.55199219, 4272.19679688, 360.28691405999996), 'rotation':(0.523568, 99.383369, 0.514067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2818.46851562, 4266.6475, 360.23625), 'rotation':(0.516069, 99.383789, 0.506844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2819.385, 4261.09765625, 360.18582031), 'rotation':(0.512278, 99.383827, 0.503178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2820.30152344, 4255.54882812, 360.13554688), 'rotation':(0.512278, 99.383827, 0.503178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2774.62378906, 4532.09914062, 363.21214844), 'rotation':(0.641088, 99.385735, 0.626868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2777.38525391, 4515.379375, 363.02214844), 'rotation':(0.644667, 99.386444, 0.630282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2778.30566406, 4509.80617188, 362.958125), 'rotation':(0.649927, 99.386559, 0.635313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2779.22632812, 4504.23339844, 362.89355469000003), 'rotation':(0.655821, 99.384262, 0.640934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2780.14648438, 4498.660625, 362.82847655999996), 'rotation':(0.661074, 99.386818, 0.645957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2781.06689453, 4493.08742188, 362.7628125), 'rotation':(0.666968, 99.386963, 0.651567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2781.98753906, 4487.51464844, 362.6965625), 'rotation':(0.672227, 99.387085, 0.656595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2782.90796875, 4481.94140625, 362.62980469), 'rotation':(0.677746, 99.386406, 0.661856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2722.07421875, 4907.63623047, 367.58523438), 'rotation':(-0.674805, -80.962494, -0.690857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2722.93433594, 4902.22412109, 367.52066406), 'rotation':(-0.683807, -80.961304, -0.700287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2724.6540625, 4891.40136719, 367.39019530999997), 'rotation':(-0.692902, -80.960602, -0.709808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2725.51416016, 4885.98974609, 367.32402344), 'rotation':(-0.697235, -80.961609, -0.714355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2727.234375, 4875.16650391, 367.19105469000004), 'rotation':(-0.693756, -80.961334, -0.710724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2729.81494141, 4858.93017578, 366.99460938), 'rotation':(-0.672028, -80.959229, -0.687927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2730.67503906, 4853.51855469, 366.93054687999995), 'rotation':(-0.66507, -80.96283, -0.680634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2732.39501953, 4842.69433594, 366.80453125), 'rotation':(-0.65033, -80.962341, -0.665222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2733.25537109, 4837.28222656, 366.74261719000003), 'rotation':(-0.643372, -80.963318, -0.657928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2734.11546875, 4831.87011719, 366.68121094), 'rotation':(-0.639496, -80.96106, -0.6539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2716.97851562, 4939.70019531, 367.95773438), 'rotation':(-0.635254, -80.963074, -0.649475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2715.20140625, 4950.8828125, 368.07972656), 'rotation':(-0.61322, -80.962341, -0.626465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2714.31273438, 4956.47509766, 368.13816406), 'rotation':(-0.591217, -80.964569, -0.603516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2713.4240625, 4962.06640625, 368.19492188), 'rotation':(-0.569214, -80.963226, -0.580627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2710.75830078, 4978.84082031, 368.35753905999997), 'rotation':(-0.51712, -80.965515, -0.52652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2709.869375, 4984.43164062, 368.40722655999997), 'rotation':(-0.490234, -80.96521, -0.498657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2708.09253906, 4995.61425781, 368.49867187999996), 'rotation':(-0.43573, -80.966095, -0.442383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2706.31542969, 5006.796875, 368.57941406), 'rotation':(-0.408478, -80.966492, -0.414337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2704.53808594, 5017.97998047, 368.65011719), 'rotation':(-0.353973, -80.967224, -0.358368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2712.79541016, 4911.70068359, 367.64910155999996), 'rotation':(0.665752, 99.038742, 0.650417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2713.65550781, 4906.28955078, 367.58511719), 'rotation':(0.665752, 99.038742, 0.650417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2714.51539062, 4900.87792969, 367.52058594000005), 'rotation':(0.674795, 99.037483, 0.659049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2715.37548828, 4895.46728516, 367.45550781), 'rotation':(0.674795, 99.037483, 0.659049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2716.23535156, 4890.05566406, 367.39011719), 'rotation':(0.683811, 99.038704, 0.667633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2717.09546875, 4884.64501953, 367.32394531), 'rotation':(0.692888, 99.039391, 0.676282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2719.67554688, 4868.41064453, 367.12480469), 'rotation':(0.693756, 99.038666, 0.677103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2720.53564453, 4862.99951172, 367.05929688), 'rotation':(0.686454, 99.037674, 0.670153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2721.39550781, 4857.58740234, 366.99453125), 'rotation':(0.679221, 99.037498, 0.663256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2722.255625, 4852.17626953, 366.93046875), 'rotation':(0.671981, 99.03994, 0.656349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2723.11572266, 4846.76464844, 366.86710938), 'rotation':(0.665131, 99.037987, 0.649822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2724.8359375, 4835.94140625, 366.74257812), 'rotation':(0.650261, 99.036812, 0.635632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2726.55589844, 4825.11865234, 366.62003905999995), 'rotation':(0.639504, 99.038918, 0.625344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2696.11839844, 5016.64013672, 368.65011719), 'rotation':(0.340464, 99.033272, 0.336442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2697.00707031, 5011.04736328, 368.61574219), 'rotation':(0.353981, 99.032761, 0.349629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2698.78613281, 4999.86376953, 368.54035156), 'rotation':(0.408473, 99.033485, 0.402687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2700.56152344, 4988.68066406, 368.45425781), 'rotation':(0.435691, 99.033127, 0.429094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2701.45019531, 4983.08886719, 368.4071875), 'rotation':(0.462964, 99.034325, 0.455532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2702.33886719, 4977.49755859, 368.3575), 'rotation':(0.490216, 99.034767, 0.481879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2703.22753906, 4971.90625, 368.30511719000003), 'rotation':(0.517107, 99.034492, 0.507839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2704.11644531, 4966.31347656, 368.25066405999996), 'rotation':(0.557876, 99.034401, 0.547093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2706.78271484, 4949.53759766, 368.07964844), 'rotation':(0.591221, 99.035408, 0.579118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2707.67113281, 4943.9453125, 368.01933594), 'rotation':(0.613214, 99.037666, 0.600193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2952.36181641, 4933.84960938, 367.90125), 'rotation':(-0.175964, -80.950226, -0.177032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2953.22827148, 4928.40966797, 367.88390625), 'rotation':(-0.185577, -80.947449, -0.186768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2954.09448242, 4922.96972656, 367.86558594), 'rotation':(-0.204468, -80.950043, -0.205933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2954.96118164, 4917.52929688, 367.84632812), 'rotation':(-0.209229, -80.948456, -0.210754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2956.6940918, 4906.64941406, 367.80535155999996), 'rotation':(-0.242676, -80.949829, -0.244751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2957.56030273, 4901.21044922, 367.78261719), 'rotation':(-0.264923, -80.948059, -0.267426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2958.42700195, 4895.77099609, 367.75789062), 'rotation':(-0.287231, -80.947845, -0.2901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2960.15966797, 4884.89208984, 367.70273438), 'rotation':(-0.309784, -80.947632, -0.313141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2961.02587891, 4879.453125, 367.67222655999996), 'rotation':(-0.332336, -80.949646, -0.336212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2962.75878906, 4868.57470703, 367.60539062000004), 'rotation':(-0.376862, -80.946808, -0.381866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2944.73339844, 4981.7421875, 368.02183594), 'rotation':(-0.131958, -80.950317, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2943.8828125, 4987.08203125, 368.03433594), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2943.0324707, 4992.42236328, 368.04679688), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2942.18188477, 4997.76220703, 368.05921875), 'rotation':(-0.132141, -80.94986, -0.132751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2941.33129883, 5003.10205078, 368.07167969), 'rotation':(-0.132141, -80.94986, -0.132751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2940.48071289, 5008.44238281, 368.08417969000004), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2939.63012695, 5013.78222656, 368.09660155999995), 'rotation':(-0.131958, -80.948883, -0.132568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2938.77954102, 5019.12207031, 368.10910156), 'rotation':(-0.132172, -80.949554, -0.132782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2937.07861328, 5029.80175781, 368.13445312000005), 'rotation':(-0.136444, -80.949707, -0.137115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2935.37744141, 5040.48242188, 368.16054687999997), 'rotation':(-0.139069, -80.948425, -0.13974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2934.52661133, 5045.82226562, 368.17390625), 'rotation':(-0.141937, -80.950287, -0.14267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2933.67626953, 5051.16259766, 368.18742188), 'rotation':(-0.141937, -80.950287, -0.14267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2931.97509766, 5061.84228516, 368.21449219000004), 'rotation':(-0.14325, -80.949646, -0.143982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2954.33984375, 4867.22998047, 367.60535156), 'rotation':(0.354316, 99.052902, 0.34996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2953.47338867, 4872.66796875, 367.63972656), 'rotation':(0.332357, 99.053368, 0.32852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2952.60742188, 4878.10644531, 367.6721875), 'rotation':(0.309776, 99.050095, 0.306439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2951.74121094, 4883.54443359, 367.70269530999997), 'rotation':(0.28723, 99.052139, 0.284352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2950.875, 4888.98339844, 367.73125), 'rotation':(0.26495, 99.051933, 0.262497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2950.00878906, 4894.42138672, 367.75789062), 'rotation':(0.26495, 99.051933, 0.262497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2949.14233398, 4899.85986328, 367.78257812000004), 'rotation':(0.24269, 99.051727, 0.240622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2948.27636719, 4905.29785156, 367.8053125), 'rotation':(0.220417, 99.049988, 0.218733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2945.67724609, 4921.61572266, 367.86558594), 'rotation':(0.194838, 99.05262, 0.193522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2943.94482422, 4932.49316406, 367.90121094), 'rotation':(0.167005, 99.052437, 0.166036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2941.34594727, 4948.80957031, 367.94734375), 'rotation':(0.138141, 99.052284, 0.137484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2923.54443359, 5060.56396484, 368.21464844), 'rotation':(0.163146, 101.165352, 0.162224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2924.40673828, 5055.15771484, 368.20097655999996), 'rotation':(0.143448, 99.051857, 0.142737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2926.1081543, 5044.47558594, 368.17390625), 'rotation':(0.143448, 99.050354, 0.142738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2927.80981445, 5033.79394531, 368.14738280999995), 'rotation':(0.139076, 99.04969, 0.138399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2928.66064453, 5028.45263672, 368.13441406), 'rotation':(0.139076, 99.04969, 0.138399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2929.51123047, 5023.11181641, 368.12164062000005), 'rotation':(0.136454, 99.052155, 0.135808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2930.36206055, 5017.77050781, 368.1090625), 'rotation':(0.133332, 99.04966, 0.132723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2931.21264648, 5012.4296875, 368.09660155999995), 'rotation':(0.132164, 99.050949, 0.131567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2932.06323242, 5007.08886719, 368.08414062), 'rotation':(0.132164, 99.050949, 0.131567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2933.76464844, 4996.40722656, 368.05921875), 'rotation':(0.131966, 99.049683, 0.131356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2934.61547852, 4991.06640625, 368.04675781), 'rotation':(0.132137, 99.051102, 0.131534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2936.31689453, 4980.38427734, 368.02179687999995), 'rotation':(0.131966, 99.049683, 0.131356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2937.16748047, 4975.04345703, 368.00933594), 'rotation':(0.131959, 99.051102, 0.131356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3182.60667969, 4966.08447266, 367.56953125), 'rotation':(-0.116241, -80.07843, -0.116699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3184.48460938, 4955.35058594, 367.54746094), 'rotation':(-0.125854, -80.076111, -0.126404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3187.30054688, 4939.25, 367.50890625), 'rotation':(-0.141663, -80.078461, -0.142365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3188.23902344, 4933.8828125, 367.49535155999996), 'rotation':(-0.14502, -80.07843, -0.145782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3189.17796875, 4928.515625, 367.48152344000005), 'rotation':(-0.148071, -80.07843, -0.148834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3190.11695312, 4923.14892578, 367.46738281), 'rotation':(-0.151123, -80.077484, -0.151917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3191.05566406, 4917.78222656, 367.45292969), 'rotation':(-0.152527, -80.077087, -0.153351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3192.93310547, 4907.04785156, 367.42390625), 'rotation':(-0.152863, -80.078674, -0.153687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3173.23779297, 5019.64746094, 367.64039062000006), 'rotation':(-0.074463, -80.077606, -0.074646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3172.26246094, 5025.22314453, 367.64878905999996), 'rotation':(-0.083099, -80.078552, -0.083344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3170.31175781, 5036.375, 367.66859375), 'rotation':(-0.10144, -80.078491, -0.101807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3169.33667969, 5041.95117188, 367.68003905999996), 'rotation':(-0.119446, -80.0784, -0.119965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3168.36132812, 5047.52685547, 367.69242188), 'rotation':(-0.128815, -80.078369, -0.129364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3167.38597656, 5053.10302734, 367.705625), 'rotation':(-0.132904, -80.076324, -0.133545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3166.41064453, 5058.67919922, 367.71980469000005), 'rotation':(-0.139374, -80.078278, -0.140045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3164.45947266, 5069.83056641, 367.75195312000005), 'rotation':(-0.164062, -80.078156, -0.165009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3163.484375, 5075.40673828, 367.76988280999996), 'rotation':(-0.176117, -80.078064, -0.177185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3161.53344727, 5086.55908203, 367.80941406), 'rotation':(-0.20047, -80.078796, -0.201874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3160.55859375, 5092.13427734, 367.83109375), 'rotation':(-0.225189, -80.077728, -0.226959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3159.58325195, 5097.70996094, 367.85367188), 'rotation':(-0.225189, -80.077728, -0.226959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3184.53394531, 4905.58837891, 367.42390625), 'rotation':(0.152518, 99.922928, 0.151712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3183.59496094, 4910.95800781, 367.4384375), 'rotation':(0.152539, 99.921303, 0.151729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3177.95996094, 4943.17431641, 367.52230469), 'rotation':(0.135169, 99.921631, 0.134532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3177.02074219, 4948.54345703, 367.53527344), 'rotation':(0.125839, 99.921608, 0.125293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3176.08154297, 4953.91259766, 367.5475), 'rotation':(0.116229, 99.921547, 0.115756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3175.14234375, 4959.28173828, 367.55894530999996), 'rotation':(0.106612, 99.921509, 0.106226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3174.203125, 4964.65087891, 367.56957030999996), 'rotation':(0.106612, 99.921509, 0.106226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3173.26390625, 4970.02001953, 367.579375), 'rotation':(0.096702, 99.92067, 0.096384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3172.32470703, 4975.38964844, 367.58835938), 'rotation':(0.087379, 99.923744, 0.087123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3171.38574219, 4980.75830078, 367.59648438), 'rotation':(0.078062, 99.921417, 0.077861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3152.15917969, 5090.67480469, 367.83113281), 'rotation':(0.231509, 99.92231, 0.22964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3153.1340332, 5085.1015625, 367.80949219), 'rotation':(0.213157, 99.922173, 0.211573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3154.10913086, 5079.52832031, 367.7890625), 'rotation':(0.200487, 99.922073, 0.199088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3155.08398438, 5073.95507812, 367.76992187999997), 'rotation':(0.188445, 99.922005, 0.187216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3157.03393555, 5062.80810547, 367.7353125), 'rotation':(0.164047, 99.920959, 0.163111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3158.00854492, 5057.23486328, 367.71988281), 'rotation':(0.151384, 99.924286, 0.150595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3158.98388672, 5051.66113281, 367.70570312), 'rotation':(0.139356, 99.92173, 0.138683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3163.85839844, 5023.79394531, 367.64886719000003), 'rotation':(0.092433, 99.921494, 0.092148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3409.4340625, 5024.67578125, 367.73875), 'rotation':(-0.011871, -80.185944, -0.011871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3410.40039062, 5019.09082031, 367.73753905999996), 'rotation':(0.01922, -80.184387, 0.019207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3411.36644531, 5013.50439453, 367.73777344), 'rotation':(0.01922, -80.184387, 0.019207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3412.33300781, 5007.91796875, 367.74023437999995), 'rotation':(0.050407, -80.185791, 0.050326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3413.2990625, 5002.33251953, 367.74523437999994), 'rotation':(0.050687, -80.185791, 0.050606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3414.2653906200003, 4996.74804688, 367.75023437999994), 'rotation':(0.050407, -80.185791, 0.050326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3416.19773438, 4985.57714844, 367.76023438), 'rotation':(0.054361, -80.184814, 0.054259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3417.1640625, 4979.99169922, 367.76550781), 'rotation':(0.054361, -80.184814, 0.054259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3418.13039062, 4974.40625, 367.77101562), 'rotation':(0.062148, -80.185303, 0.062011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3419.09667969, 4968.82080078, 367.77714844), 'rotation':(0.070126, -80.185272, 0.069953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3420.06296875, 4963.23583984, 367.78367188), 'rotation':(0.070126, -80.185272, 0.069953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3421.0290625, 4957.65039062, 367.790625), 'rotation':(0.077734, -80.185242, 0.077518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3421.99535156, 4952.06494141, 367.79816406), 'rotation':(0.077734, -80.185242, 0.077518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3422.96140625, 4946.47949219, 367.80589844), 'rotation':(0.081614, -80.186035, 0.081376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3423.92773438, 4940.89453125, 367.81398437999997), 'rotation':(0.081908, -80.185272, 0.081678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3404.79808594, 5051.47314453, 367.74433594000004), 'rotation':(-0.012054, -80.18573, -0.012085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3402.89378906, 5062.48242188, 367.75066405999996), 'rotation':(-0.025482, -80.184998, -0.025482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3401.94164062, 5067.98632812, 367.75582031), 'rotation':(-0.053192, -80.186005, -0.053284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3399.08445312, 5084.50097656, 367.78304688), 'rotation':(-0.108215, -80.184265, -0.108612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3397.18015625, 5095.51025391, 367.80664062000005), 'rotation':(-0.121826, -80.185181, -0.122345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3395.27585938, 5106.51855469, 367.83144531), 'rotation':(-0.129761, -80.187042, -0.130341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3394.32347656, 5112.02246094, 367.84453125), 'rotation':(-0.134888, -80.184784, -0.135529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3393.37109375, 5117.52734375, 367.858125), 'rotation':(-0.14032, -80.184753, -0.140991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3392.41871094, 5123.03076172, 367.87199219), 'rotation':(-0.142822, -80.182648, -0.143524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3391.4665625, 5128.53564453, 367.88589844), 'rotation':(-0.142792, -80.186188, -0.143524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(3390.51441406, 5134.03955078, 367.89984375), 'rotation':(-0.142822, -80.185272, -0.143524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3415.52660156, 4939.44287109, 367.81398437999997), 'rotation':(-0.081604, 99.8162, -0.081848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3413.59375, 4950.61523438, 367.798125), 'rotation':(-0.070129, 99.814713, -0.070282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3411.66113281, 4961.78808594, 367.78367188), 'rotation':(-0.062134, 99.814705, -0.062286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3410.69484375, 4967.37451172, 367.77714844), 'rotation':(-0.062134, 99.814705, -0.062286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3409.72828125, 4972.9609375, 367.77101562), 'rotation':(-0.054352, 99.81469, -0.054443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3408.76171875, 4978.54736328, 367.76550781), 'rotation':(-0.050415, 99.814224, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3407.79539062, 4984.13378906, 367.76023438), 'rotation':(-0.050415, 99.814224, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3406.82910156, 4989.71972656, 367.75523438), 'rotation':(-0.050415, 99.815002, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3405.86253906, 4995.30664062, 367.75023437999994), 'rotation':(-0.05069, 99.814224, -0.050781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3404.89625, 5000.89257812, 367.74519531), 'rotation':(-0.050415, 99.816444, -0.050507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3403.9299218799997, 5006.47851562, 367.74019531), 'rotation':(-0.019226, 99.813049, -0.019226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3402.96335938, 5012.06640625, 367.73777344), 'rotation':(0.011878, 99.815918, 0.011869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3401.99683594, 5017.65332031, 367.73753905999996), 'rotation':(0.011878, 99.815918, 0.011869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3401.03050781, 5023.23974609, 367.73875), 'rotation':(0.011871, 99.814049, 0.01187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(3382.11375, 5132.58837891, 367.89984375), 'rotation':(0.142812, 99.81472, 0.142104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3383.06566406, 5127.08544922, 367.8859375), 'rotation':(0.142806, 99.816437, 0.142096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3384.0178125, 5121.58203125, 367.87199219), 'rotation':(0.142812, 99.81472, 0.142104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3384.96972656, 5116.07910156, 367.85816406), 'rotation':(0.142812, 99.81382, 0.142098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3385.921875, 5110.57519531, 367.84453125), 'rotation':(0.140306, 99.815239, 0.139629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3390.68210938, 5083.05859375, 367.78304688), 'rotation':(0.121844, 99.815315, 0.121322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3391.63402344, 5077.55566406, 367.77253906), 'rotation':(0.10819, 99.815186, 0.107782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(3392.5861718799997, 5072.05175781, 367.76359375), 'rotation':(0.10819, 99.815186, 0.107782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(3393.53859375, 5066.54736328, 367.75582031), 'rotation':(0.08048, 99.814056, 0.080259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(3394.49046875, 5061.04443359, 367.75066405999996), 'rotation':(0.053173, 99.81559, 0.053089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(3396.39453125, 5050.03710938, 367.744375), 'rotation':(0.02547, 99.815544, 0.025455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.265625, 4862.27978516, 365.21335938), 'rotation':(-0.595245, -89.342529, -0.607697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2209.32835938, 4856.77441406, 365.15648437999994), 'rotation':(-0.595245, -89.342529, -0.607697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.45359375, 4845.76318359, 365.04171875), 'rotation':(-0.600616, -89.342438, -0.613312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.51609375, 4840.25830078, 364.98398438), 'rotation':(-0.605835, -89.342346, -0.618744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.57882812, 4834.75292969, 364.92574219), 'rotation':(-0.608246, -89.338287, -0.621277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.7040625, 4823.7421875, 364.80878906), 'rotation':(-0.613434, -89.341736, -0.626678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.8293750000003, 4812.73095703, 364.69113281), 'rotation':(-0.616516, -89.341675, -0.629883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2209.8918750000003, 4807.22558594, 364.63199219), 'rotation':(-0.616516, -89.341675, -0.629883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2210.01710938, 4796.21533203, 364.51316406), 'rotation':(-0.617218, -89.342163, -0.630615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2210.07984375, 4790.70947266, 364.45363281), 'rotation':(-0.617218, -89.342163, -0.630615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.26757812, 4774.19238281, 364.2784375), 'rotation':(-0.590942, -89.342773, -0.60321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.33054688, 4768.68652344, 364.2215625), 'rotation':(-0.58197, -89.342926, -0.593903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.4557812499997, 4757.67529297, 364.11), 'rotation':(-0.564636, -89.343262, -0.575867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2210.5182812499997, 4752.16894531, 364.0553125), 'rotation':(-0.564636, -89.343262, -0.575867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.9582812500003, 4889.32763672, 365.49027344), 'rotation':(-0.59021, -89.342285, -0.602478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.89382812, 4894.98730469, 365.54886719), 'rotation':(-0.59021, -89.342285, -0.602478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.76515625, 4906.30517578, 365.66761719000004), 'rotation':(-0.598267, -89.342102, -0.61084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2208.70070312, 4911.96484375, 365.7275), 'rotation':(-0.606628, -89.341919, -0.619568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2208.63648438, 4917.62402344, 365.78824219), 'rotation':(-0.614441, -89.343262, -0.627716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.57375, 4923.22167969, 365.84832030999996), 'rotation':(-0.650299, -87.390076, -0.665192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2208.44335938, 4934.60009766, 365.9690625), 'rotation':(-0.607239, -89.342621, -0.620209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.37890625, 4940.25878906, 366.02796875), 'rotation':(-0.599884, -89.342712, -0.612549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.25046875, 4951.57666016, 366.14347655999995), 'rotation':(-0.576904, -89.343262, -0.588623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2208.1215625, 4962.89404297, 366.25578125), 'rotation':(-0.562073, -89.340942, -0.573181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2207.99289062, 4974.21191406, 366.36617187999997), 'rotation':(-0.558105, -89.344452, -0.569061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2202.0559375000003, 4746.57177734, 364.00140625), 'rotation':(0.564645, 90.656731, 0.553597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.993125, 4752.07910156, 364.05539062), 'rotation':(0.573312, 90.656906, 0.561922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.86789062, 4763.09375, 364.16550781), 'rotation':(0.582028, 90.657112, 0.570288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.80539062, 4768.60107422, 364.22167969000003), 'rotation':(0.590927, 90.659485, 0.578838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.74242188, 4774.10839844, 364.27855469), 'rotation':(0.599595, 90.657433, 0.587143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.6171875, 4785.12255859, 364.3946875), 'rotation':(0.617196, 90.657806, 0.604013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.42921875, 4801.64355469, 364.57292969), 'rotation':(0.616507, 90.65831, 0.60334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.30398438, 4812.65771484, 364.69136719), 'rotation':(0.613467, 90.658295, 0.600435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.17875, 4823.671875, 364.8090625), 'rotation':(0.610182, 90.65818, 0.597284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2201.1159374999997, 4829.17822266, 364.86773437999994), 'rotation':(0.608242, 90.655746, 0.595435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2201.0534374999997, 4834.68505859, 364.92605469), 'rotation':(0.605824, 90.657669, 0.593123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.99070312, 4840.19238281, 364.98429688), 'rotation':(0.600626, 90.659096, 0.588133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.9284374999997, 4845.69921875, 365.04207031), 'rotation':(0.595189, 90.65741, 0.582927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.80320312, 4856.71289062, 365.156875), 'rotation':(0.590183, 90.65731, 0.578117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.74046875, 4862.21972656, 365.21375), 'rotation':(0.590183, 90.65731, 0.578117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.4678125, 4974.11816406, 366.36621094000003), 'rotation':(0.558313, 90.657478, 0.547515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.5964062499997, 4962.8046875, 366.25589844), 'rotation':(0.558108, 90.657524, 0.547326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.66085938, 4957.14794922, 366.20011719), 'rotation':(0.562063, 90.656441, 0.551111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':1, 'location':(2199.91796875, 4934.52148438, 365.96925781), 'rotation':(0.59982, 90.657211, 0.58736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.04664062, 4923.20800781, 365.84917969), 'rotation':(0.614997, 90.660126, 0.601898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.1753125, 4911.89501953, 365.7278125), 'rotation':(0.614423, 90.658226, 0.601362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.2395312500003, 4906.23730469, 365.66789062000004), 'rotation':(0.606637, 90.658096, 0.593898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.30398438, 4900.58056641, 365.60828125), 'rotation':(0.606637, 90.658096, 0.593898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':1, 'location':(2200.368125, 4894.92333984, 365.54917969), 'rotation':(0.598208, 90.657867, 0.585835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':1, 'location':(2200.43265625, 4889.26611328, 365.490625), 'rotation':(0.598208, 90.657867, 0.585835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2041.44273438, 3895.1284375, 356.17269531), 'rotation':(-0.89801, -80.745819, -0.926514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2038.72359375, 3911.8410937500003, 356.43882812000004), 'rotation':(-0.903107, -80.745178, -0.931946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2037.81726562, 3917.41210938, 356.52882812), 'rotation':(-0.912781, -80.744843, -0.9422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2036.0045312500001, 3928.55445312, 356.71183594), 'rotation':(-0.932037, -80.744629, -0.962738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2035.0982812500001, 3934.12546875, 356.80476562), 'rotation':(-0.942047, -80.745117, -0.973419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2034.19179688, 3939.69625, 356.89867187999994), 'rotation':(-0.951691, -80.743591, -0.983704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2033.28554688, 3945.26734375, 356.99351562000004), 'rotation':(-0.961639, -80.743256, -0.994354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2032.38039062, 3950.8307812499997, 357.08898437999994), 'rotation':(-0.941589, -80.522217, -0.972931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2031.47304688, 3956.40820312, 357.18382812000004), 'rotation':(-0.961182, -80.743958, -0.993835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2030.566875, 3961.97804688, 357.27675781), 'rotation':(-0.961182, -80.743958, -0.993835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2028.754375, 3973.11867188, 357.45710937999996), 'rotation':(-0.901154, -80.745911, -0.929871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':4, 'tiley':2, 'location':(2027.8483593800001, 3978.68820312, 357.54429688), 'rotation':(-0.901154, -80.745911, -0.929871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':4, 'tiley':2, 'location':(2032.1215625, 3899.32859375, 356.26121094), 'rotation':(0.897999, 99.254189, 0.870175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2030.3090625, 3910.46945312, 356.43875), 'rotation':(0.912759, 99.253914, 0.884027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':4, 'tiley':2, 'location':(2028.49648438, 3921.6106250000003, 356.61976562), 'rotation':(0.932068, 99.255745, 0.902106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2027.5900781199998, 3927.18117188, 356.71171875), 'rotation':(0.942026, 99.256081, 0.911421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':4, 'tiley':2, 'location':(2026.6838281199998, 3932.75171875, 356.80464844), 'rotation':(0.951637, 99.256012, 0.920407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2024.8713281199998, 3943.8928125, 356.9934375), 'rotation':(0.971287, 99.255836, 0.938773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2023.96523438, 3949.46265625, 357.08902344), 'rotation':(0.961178, 99.256821, 0.929318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':4, 'tiley':2, 'location':(2022.1530468800001, 3960.60179688, 357.27664062), 'rotation':(0.931071, 99.255028, 0.901164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':4, 'tiley':2, 'location':(2020.3409375, 3971.74148438, 357.45695312000004), 'rotation':(0.87117, 99.253159, 0.844972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n ]\nTown13 = [\n {'tilex':5, 'tiley':2, 'location':(2649.8596093799997, 2022.97703125, 173.62414062), 'rotation':(0.493317, 90.635384, 0.484885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2657.85570312, 2006.53085938, 173.47964843999998), 'rotation':(-0.507233, -89.36438, -0.516296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2657.79515625, 2012.0345312499999, 173.52808593999998), 'rotation':(-0.503723, -89.364441, -0.512634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2657.7346093799997, 2017.5383593800002, 173.57617188), 'rotation':(-0.500214, -89.364471, -0.509003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2657.61351562, 2028.54578125, 173.67142578), 'rotation':(-0.493317, -89.364624, -0.501862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.27050781, 2073.4609375, 174.04148438), 'rotation':(0.433287, 90.633385, 0.426766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.20921875, 2079.015625, 174.08351562), 'rotation':(0.427877, 90.634163, 0.421523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.96460938, 2101.2317187500003, 174.24759766), 'rotation':(0.403186, 90.633789, 0.397554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.53636719, 2140.1106250000003, 174.50421875), 'rotation':(0.349549, 90.633698, 0.345302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.4140625, 2151.2200000000003, 174.57169922), 'rotation':(0.332808, 90.633469, 0.328962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.22949219, 2162.32515625, 174.63564452999998), 'rotation':(0.315917, 90.633263, 0.312456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2656.9060156200003, 2095.7634375, 174.20730468999997), 'rotation':(-0.419769, -89.365967, -0.425934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.84472656, 2101.31710938, 174.24757812), 'rotation':(-0.419769, -89.365967, -0.425934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2656.72242188, 2112.42507812, 174.32484375), 'rotation':(-0.403198, -89.366211, -0.408905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.66113281, 2117.97953125, 174.36234375), 'rotation':(-0.386719, -89.36499, -0.391968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2656.47753906, 2134.6418750000003, 174.46931641), 'rotation':(-0.362, -89.366455, -0.366608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.35546875, 2145.75023438, 174.53839843999998), 'rotation':(-0.349518, -89.366333, -0.353821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.29417969, 2151.30492188, 174.57167969), 'rotation':(-0.340912, -89.366394, -0.345001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2656.24023438, 2167.9678125, 174.66625), 'rotation':(-0.315918, -89.366699, -0.319427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.68285156, 2205.8559375, 174.85730468999998), 'rotation':(0.257013, 90.632904, 0.254724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.609375, 2217.00828125, 174.90634766), 'rotation':(0.234446, 90.630646, 0.232533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.6013281200003, 2222.58351562, 174.92947266), 'rotation':(0.228743, 90.632446, 0.226927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.566875, 2228.1575000000003, 174.95201172), 'rotation':(0.228743, 90.632446, 0.226927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.50539062, 2233.73265625, 174.97427734000001), 'rotation':(0.228893, 90.632431, 0.22707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.3825781200003, 2244.88234375, 175.01775390999998), 'rotation':(0.204892, 90.632561, 0.203434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.25976562, 2256.0325000000003, 175.05716797000002), 'rotation':(0.188827, 90.632439, 0.187578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.19847656, 2261.60789062, 175.07556641), 'rotation':(0.172968, 90.630653, 0.17192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2655.44703125, 2228.24148438, 174.95199218999997), 'rotation':(-0.234467, -89.369354, -0.236359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2655.07859375, 2261.691875, 175.07554688), 'rotation':(-0.188812, -89.367554, -0.190063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2646.77929688, 2299.64039062, 175.18417968999998), 'rotation':(0.120881, 90.631805, 0.120369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2646.53417969, 2321.92164062, 175.23117188), 'rotation':(0.109549, 90.630554, 0.109131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2646.41136719, 2333.06203125, 175.2521875), 'rotation':(0.100062, 90.630898, 0.099709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2646.10472656, 2360.91453125, 175.29404297000002), 'rotation':(0.068056, 90.630806, 0.067898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.536875, 2310.86476562, 175.209375), 'rotation':(-0.12088, -89.368195, -0.121399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.35304688, 2327.5759375, 175.24179688), 'rotation':(-0.109558, -89.369446, -0.109985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.23023438, 2338.71578125, 175.26189452999998), 'rotation':(-0.100067, -89.36911, -0.100433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2654.16894531, 2344.28609375, 175.27091797), 'rotation':(-0.093506, -89.369141, -0.093811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.98484375, 2360.9978125, 175.29404297000002), 'rotation':(-0.074646, -89.369171, -0.074829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.92359375, 2366.56835938, 175.30042969), 'rotation':(-0.068054, -89.369202, -0.068207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.55957031, 2409.99851562, 175.33064453), 'rotation':(0.008463, 90.631073, 0.008455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.50292969, 2415.53515625, 175.33148438), 'rotation':(0.008463, 90.63105, 0.008461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.441875, 2421.07375, 175.33228516), 'rotation':(0.008463, 90.63105, 0.008461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.38085938, 2426.61230469, 175.33310547000002), 'rotation':(0.008463, 90.631073, 0.008455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.31984375, 2432.15085938, 175.33394531000002), 'rotation':(0.008463, 90.631073, 0.008455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2645.25878906, 2437.6896875, 175.33474609), 'rotation':(0.008463, 90.63105, 0.008461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.19773438, 2443.22828125, 175.33556640999998), 'rotation':(0.0, 90.633072, 4e-06), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2645.01488281, 2459.84179688, 175.33376952999998), 'rotation':(-0.025116, 90.630775, -0.025116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.95386719, 2465.38039062, 175.33136718999998), 'rotation':(-0.024963, 90.63076, -0.024994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.8928125, 2470.91894531, 175.32892578), 'rotation':(-0.024963, 90.630783, -0.024994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.83179688, 2476.4575, 175.32650390999999), 'rotation':(-0.025116, 90.630775, -0.025116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.77101562, 2481.99632812, 175.32408203), 'rotation':(-0.028656, 90.631248, -0.028687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.64890625, 2493.0725, 175.31871094), 'rotation':(-0.03595, 90.631233, -0.036011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2644.40476562, 2515.2265625, 175.30220702999998), 'rotation':(-0.05426, 90.630066, -0.054352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.34375, 2520.76488281, 175.29708984), 'rotation':(-0.054077, 90.632675, -0.054169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.22167969, 2531.84132812, 175.28644531), 'rotation':(-0.056366, 90.630913, -0.056458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2644.0388281200003, 2548.45703125, 175.26919922000002), 'rotation':(-0.064819, 90.63092, -0.064972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.7946875, 2570.61109375, 175.24294922), 'rotation':(-0.071259, 90.632179, -0.071411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.26125, 2426.6950781200003, 175.33310547000002), 'rotation':(-0.008453, -89.368927, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.20019531, 2432.23363281, 175.33394531000002), 'rotation':(-0.008453, -89.368927, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2653.078125, 2443.31078125, 175.33556640999998), 'rotation':(-0.008453, -89.367371, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2653.01710938, 2448.84863281, 175.33595703), 'rotation':(-0.008453, -89.367371, -0.008453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.95605469, 2454.38648438, 175.33546875), 'rotation':(7e-06, -89.368988, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.83398438, 2465.46289062, 175.33136718999998), 'rotation':(0.025087, -89.369202, 0.02508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.5290625, 2493.1540625, 175.31873047000002), 'rotation':(0.028673, -89.368713, 0.028633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.16285156, 2526.38523438, 175.29183593999997), 'rotation':(0.054088, -89.36731, 0.053984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2652.1017968799997, 2531.92335938, 175.28644531), 'rotation':(0.054088, -89.36731, 0.053984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2651.98, 2543.00046875, 175.27515625), 'rotation':(0.060591, -89.36908, 0.060452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2651.796875, 2559.61570312, 175.25646484), 'rotation':(0.064812, -89.369049, 0.064666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.29515625, 2605.99171875, 175.19671875), 'rotation':(-0.080383, 90.630814, -0.080597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.2534375, 2619.76, 175.17726562), 'rotation':(-0.082764, 90.63166, -0.083008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2643.00828125, 2642.0121875, 175.14492188), 'rotation':(-0.0849, 90.629608, -0.085175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.88234375, 2653.13746094, 175.12837890999998), 'rotation':(-0.085693, 90.631645, -0.085938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.76292969, 2664.26464844, 175.11164062), 'rotation':(-0.087219, 90.631638, -0.087463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.70164062, 2669.8278906200003, 175.10318359000001), 'rotation':(-0.087494, 90.630386, -0.087738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2651.43089844, 2604.60570312, 175.19878906000002), 'rotation':(0.077755, -89.367798, 0.077544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2651.07226562, 2625.4040625, 175.16925781), 'rotation':(0.08199, -89.368347, 0.081758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.8884375, 2642.09328125, 175.14492188), 'rotation':(0.084291, -89.368347, 0.084043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.82714844, 2647.65625, 175.13667969), 'rotation':(0.084933, -89.370361, 0.084664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.58203125, 2669.9084375, 175.10318359000001), 'rotation':(0.087208, -89.368347, 0.086955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2650.52050781, 2675.47144531, 175.0946875), 'rotation':(0.087474, -89.369629, 0.087218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2640.0646875, 2945.53979492, 174.69880859), 'rotation':(-0.088806, 90.536217, -0.089081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2640.17089844, 2934.20214844, 174.71613281), 'rotation':(-0.087067, 90.536186, -0.087341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.22414062, 2928.53320312, 174.72460938), 'rotation':(-0.085449, 90.537727, -0.085693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.27710938, 2922.86425781, 174.73300781), 'rotation':(-0.085449, 90.537727, -0.085693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.3303125, 2917.1953125, 174.74128906), 'rotation':(-0.08371, 90.536194, -0.083954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.38328125, 2911.52661133, 174.74951172000002), 'rotation':(-0.08371, 90.536194, -0.083954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.59546875, 2888.85107422, 174.78226562), 'rotation':(-0.082703, 90.537888, -0.082947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.70164062, 2877.51318359, 174.79853516), 'rotation':(-0.082214, 90.53788, -0.082458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2640.80785156, 2866.17529297, 174.81472656000003), 'rotation':(-0.081848, 90.536758, -0.082062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2641.07300781, 2837.83081055, 174.85521484), 'rotation':(-0.081818, 90.537552, -0.082062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2641.12621094, 2832.161875, 174.86332031), 'rotation':(-0.082062, 90.535522, -0.082306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.33863281, 2809.48609375, 174.89585938), 'rotation':(-0.082275, 90.536873, -0.08252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.55078125, 2786.8103125, 174.92859375), 'rotation':(-0.082947, 90.535828, -0.083191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.60375, 2781.14160156, 174.93683593999998), 'rotation':(-0.083252, 90.535828, -0.083496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2641.65699219, 2775.47265625, 174.94507812), 'rotation':(-0.083527, 90.535828, -0.083801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.8159375, 2758.46582031, 174.97001953), 'rotation':(-0.083984, 90.534668, -0.084229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.86914062, 2752.796875, 174.97835938), 'rotation':(-0.084259, 90.537338, -0.084503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2641.9221093799997, 2747.12792969, 174.98673828), 'rotation':(-0.084747, 90.534775, -0.084991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2642.13453125, 2724.45214844, 175.02050781000003), 'rotation':(-0.085876, 90.537361, -0.086151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.96191406, 2730.19628906, 175.01203125), 'rotation':(0.085869, -89.462646, 0.085617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.90867188, 2735.86523438, 175.00357422000002), 'rotation':(0.085555, -89.46521, 0.085304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.85570312, 2741.53394531, 174.99513672), 'rotation':(0.085234, -89.462616, 0.084978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.8025, 2747.20289062, 174.98673828), 'rotation':(0.085063, -89.462646, 0.084816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.74953125, 2752.87183594, 174.97835938), 'rotation':(0.084421, -89.462646, 0.084173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.69628906, 2758.54078125, 174.97001953), 'rotation':(0.084278, -89.462616, 0.084018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.64332031, 2764.20947266, 174.96167968999998), 'rotation':(0.083984, -89.465332, 0.083743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2649.43117188, 2786.885, 174.92861327999998), 'rotation':(0.083246, -89.464172, 0.082999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.37816406, 2792.55394531, 174.92037109), 'rotation':(0.082939, -89.461731, 0.082697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.27195312, 2803.89183594, 174.90400391), 'rotation':(0.082645, -89.464172, 0.082394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.1128125, 2820.8984375, 174.87958984), 'rotation':(0.082283, -89.463104, 0.082048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2649.00660156, 2832.23609375, 174.86332031), 'rotation':(0.082194, -89.463074, 0.081954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.90039062, 2843.57397461, 174.84710938), 'rotation':(0.081819, -89.462463, 0.081597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.79417969, 2854.91162109, 174.83091797), 'rotation':(0.081819, -89.465088, 0.081596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.68824219, 2866.24951172, 174.81474609), 'rotation':(0.081723, -89.463226, 0.081482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.52882812, 2883.25610352, 174.79042969), 'rotation':(0.082229, -89.46463, 0.08199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.42285156, 2894.59399414, 174.77408203), 'rotation':(0.0827, -89.462097, 0.082459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.26367188, 2911.6003418, 174.74951172000002), 'rotation':(0.082761, -89.463867, 0.08252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2648.2107031200003, 2917.26928711, 174.74128906), 'rotation':(0.082761, -89.463867, 0.08252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.15746094, 2922.93798828, 174.73300781), 'rotation':(0.083718, -89.46225, 0.08346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2648.05125, 2934.27587891, 174.71613281), 'rotation':(0.085439, -89.463806, 0.085181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2647.99828125, 2939.94482422, 174.70751952999998), 'rotation':(0.087071, -89.463806, 0.086802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2647.89210938, 2951.28198242, 174.69001953), 'rotation':(0.088792, -89.463806, 0.088518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2485.34914062, 2190.62867188, 170.90208984), 'rotation':(1.586093, 0.518347, 1.499994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2496.41648438, 2190.72023438, 171.20707031), 'rotation':(1.554264, 0.517766, 1.471553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2518.55101562, 2190.9040625, 171.79449218999997), 'rotation':(1.459031, 0.511837, 1.386054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2529.61960938, 2190.99609375, 172.076875), 'rotation':(1.446894, 0.513674, 1.375138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2535.15503906, 2191.04203125, 172.21677734000002), 'rotation':(1.4469, 0.511206, 1.37513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2568.36523438, 2191.30421875, 173.04580077999998), 'rotation':(1.405742, 0.511014, 1.337968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2584.97117188, 2191.42234375, 173.45083984000001), 'rotation':(1.32604, 0.50693, 1.265679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2590.50488281, 2191.46828125, 173.58105468999997), 'rotation':(1.32604, 0.50693, 1.265679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2601.57445312, 2191.55953125, 173.82900390999998), 'rotation':(1.227638, 0.500273, 1.175837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2612.64476562, 2191.65164062, 174.06035156000002), 'rotation':(1.129249, 0.498464, 1.085372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2623.71828125, 2191.7434375000003, 174.27417968999998), 'rotation':(1.030696, 0.4925, 0.994098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2634.79078125, 2191.83523438, 174.47267578), 'rotation':(1.005998, 0.493506, 0.971125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2623.84496094, 2183.89625, 174.27535156000002), 'rotation':(-1.079956, -179.505661, -1.121277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2612.77757812, 2183.80421875, 174.06167968999998), 'rotation':(-1.178345, -179.499527, -1.2276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2601.71265625, 2183.71289062, 173.83058594), 'rotation':(-1.276825, -179.497574, -1.334717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2590.64941406, 2183.62109375, 173.58289062), 'rotation':(-1.32605, -179.493073, -1.38855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2574.04957031, 2183.48289062, 173.18378906), 'rotation':(-1.405762, -179.490509, -1.476074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2568.51441406, 2183.43679688, 173.04787109), 'rotation':(-1.417511, -179.488403, -1.489014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2557.44433594, 2183.3450000000003, 172.77433594), 'rotation':(-1.429199, -179.489349, -1.501923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2546.3747656200003, 2183.25320312, 172.49789062), 'rotation':(-1.441071, -179.488754, -1.515015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2540.83960938, 2183.20726562, 172.35857422), 'rotation':(-1.446899, -179.486328, -1.521454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2529.77101562, 2183.11523438, 172.07904297000002), 'rotation':(-1.459076, -179.485977, -1.534912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2518.70433594, 2183.0234375, 171.79677734), 'rotation':(-1.483276, -179.486908, -1.561646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2513.17359375, 2182.9778125000003, 171.65310547), 'rotation':(-1.507355, -179.485657, -1.588318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2502.10523438, 2182.88578125, 171.35933594), 'rotation':(-1.55426, -179.482239, -1.640411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2485.50902344, 2182.74828125, 170.90470703), 'rotation':(-1.590912, -179.478943, -1.681213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2452.88109375, 2190.35960938, 169.97748047000002), 'rotation':(1.668144, 0.524094, 1.573006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2447.21921875, 2190.3125, 169.81044922), 'rotation':(1.685984, 0.525161, 1.588822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2441.55710938, 2190.265625, 169.64166016), 'rotation':(1.703674, 0.526187, 1.604493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2435.89550781, 2190.21851562, 169.47125), 'rotation':(1.721522, 0.527282, 1.620255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2418.90992188, 2190.07742188, 168.95746093999998), 'rotation':(1.730401, 0.528405, 1.628099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2407.58640625, 2189.9834375, 168.60800781), 'rotation':(1.790896, 0.530378, 1.681399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2396.26488281, 2189.8893749999997, 168.25082031000002), 'rotation':(1.811229, 0.533013, 1.699247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2390.60304688, 2189.8424999999997, 168.07160156), 'rotation':(1.811229, 0.533013, 1.699247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.61914062, 2189.70140625, 167.53101562), 'rotation':(1.820846, 0.534111, 1.707684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2367.95703125, 2189.65476562, 167.34890625), 'rotation':(1.840244, 0.533875, 1.724699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2356.63746094, 2189.56078125, 166.98103516), 'rotation':(1.859567, 0.536606, 1.741586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2350.97582031, 2189.51367188, 166.79509765999998), 'rotation':(1.87906, 0.537893, 1.758626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2345.31664062, 2189.4665625, 166.60839843999997), 'rotation':(1.87906, 0.537893, 1.758626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2322.67164062, 2189.2790625, 165.85550781), 'rotation':(1.903505, 0.5392, 1.779953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2300.02929688, 2189.0910937500003, 165.09583984), 'rotation':(1.927138, 0.541031, 1.800548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2288.7065625, 2188.99703125, 164.71439453), 'rotation':(1.927035, 0.541024, 1.800462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2271.723125, 2188.8559375, 164.1421875), 'rotation':(1.928367, 0.539057, 1.801599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2260.40085938, 2188.76195312, 163.75973633), 'rotation':(1.933025, 0.539366, 1.805661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2254.74, 2188.7153125, 163.56819336), 'rotation':(1.935348, 0.542275, 1.807674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2243.4175, 2188.62109375, 163.18489258), 'rotation':(1.936577, 0.541312, 1.808742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2237.75632812, 2188.57421875, 162.99325195), 'rotation':(1.936427, 0.5413, 1.808619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2452.95214844, 2182.4775, 169.97763672000002), 'rotation':(-1.686005, -179.474838, -1.787567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2447.29003906, 2182.43039062, 169.81060547), 'rotation':(-1.703705, -179.473816, -1.807404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2435.9665625, 2182.33664062, 169.47140625), 'rotation':(-1.730316, -179.473236, -1.837341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2430.30394531, 2182.28976562, 169.30017578), 'rotation':(-1.730408, -179.471588, -1.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2424.64136719, 2182.24289062, 169.12894531), 'rotation':(-1.730408, -179.471588, -1.837463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2418.98070312, 2182.19578125, 168.95761718999998), 'rotation':(-1.750549, -179.470276, -1.860168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2396.3359375, 2182.0078125, 168.25101562), 'rotation':(-1.811096, -179.468506, -1.928497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.68992188, 2181.81984375, 167.53119141), 'rotation':(-1.84021, -179.46463, -1.961456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2368.0278125, 2181.77273438, 167.34908202999998), 'rotation':(-1.859589, -179.464859, -1.98349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2345.38746094, 2181.585, 166.60857422), 'rotation':(-1.895966, -179.461456, -2.02478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2334.0651562499997, 2181.49070312, 166.23246093999998), 'rotation':(-1.903412, -179.460785, -2.033295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2328.4035937500003, 2181.44359375, 166.0440625), 'rotation':(-1.903564, -179.46077, -2.033478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2322.74242188, 2181.39671875, 165.85570312), 'rotation':(-1.903351, -179.463272, -2.033203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2311.42257812, 2181.30273438, 165.47744140999998), 'rotation':(-1.927155, -179.458969, -2.060303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2300.09984375, 2181.20875, 165.09601562), 'rotation':(-1.927155, -179.458969, -2.060303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2288.77710938, 2181.11476562, 164.71458984), 'rotation':(-1.927185, -179.458939, -2.060364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2277.45460938, 2181.0207812500003, 164.33316406000003), 'rotation':(-1.928284, -179.460968, -2.061584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2271.79367188, 2180.97359375, 164.14234375), 'rotation':(-1.930603, -179.458023, -2.06427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2260.47117188, 2180.8801562500003, 163.75990234), 'rotation':(-1.935425, -179.460464, -2.069763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2249.149375, 2180.78609375, 163.37670898), 'rotation':(-1.936584, -179.458694, -2.071075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2237.82664062, 2180.69234375, 162.99342773), 'rotation':(-1.936584, -179.458694, -2.071075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2231.26632812, 2180.60789062, 162.77150390999998), 'rotation':(-1.931061, -179.459396, -2.064789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2177.2043750000003, 2188.0134375, 160.97357422), 'rotation':(1.889387, 0.722732, 1.767651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2171.67039062, 2187.9496875, 160.79232421999998), 'rotation':(1.873473, 0.721662, 1.753754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2166.13578125, 2187.88601562, 160.61224609), 'rotation':(1.857927, 0.718711, 1.740163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2155.0651562499997, 2187.75851562, 160.25514648), 'rotation':(1.842198, 0.71965, 1.726397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2149.53101562, 2187.69460938, 160.07771484), 'rotation':(1.834268, 0.719699, 1.719444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2138.46046875, 2187.56710938, 159.72389648), 'rotation':(1.827752, 0.717659, 1.71373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2132.92578125, 2187.50320312, 159.54856445), 'rotation':(1.814802, 0.719221, 1.702388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2121.8525, 2187.37546875, 159.20130859), 'rotation':(1.789093, 0.715211, 1.679791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2094.17554688, 2187.05710938, 158.35381836), 'rotation':(1.730968, 0.709839, 1.62859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2083.10109375, 2186.92945312, 158.02272461), 'rotation':(1.713025, 0.711026, 1.612744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2077.56617188, 2186.86570312, 157.86050781), 'rotation':(1.677187, 0.708901, 1.581021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2155.1575000000003, 2179.87671875, 160.25518555), 'rotation':(-1.834259, -179.282974, -1.954742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2149.62351562, 2179.81296875, 160.07777344), 'rotation':(-1.834259, -179.280304, -1.954742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2138.5534374999997, 2179.68554688, 159.72396484), 'rotation':(-1.814819, -179.283173, -1.932709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2133.01882812, 2179.62179688, 159.54864258), 'rotation':(-1.802032, -179.283966, -1.918243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2127.48414062, 2179.558125, 159.37448242), 'rotation':(-1.789093, -179.282394, -1.903625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2116.41085938, 2179.430625, 159.02959961), 'rotation':(-1.763214, -179.286392, -1.87442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2105.3415625, 2179.30320312, 158.68967773), 'rotation':(-1.737335, -179.287994, -1.845245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2094.26976562, 2179.17554688, 158.35391601999999), 'rotation':(-1.713013, -179.288956, -1.817902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2083.19554688, 2179.0481250000003, 158.02283203000002), 'rotation':(-1.677216, -179.291092, -1.777679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2077.660625, 2178.984375, 157.86061523), 'rotation':(-1.641357, -179.293167, -1.737549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2066.58273438, 2178.8567187500003, 157.54061523000001), 'rotation':(-1.605652, -179.295181, -1.697632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2055.51101562, 2178.7292187499997, 157.2284668), 'rotation':(-1.587616, -179.29689, -1.677521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3997.34742188, 2203.13625, 161.43270508), 'rotation':(-1.796753, 0.481027, -1.912262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3991.81226562, 2203.09546875, 161.60711914), 'rotation':(-1.802795, 0.478824, -1.919098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3986.27710938, 2203.05445312, 161.78154297), 'rotation':(-1.803009, 0.4811, -1.919342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3980.74046875, 2203.01367188, 161.95649414), 'rotation':(-1.808533, 0.479905, -1.925629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3975.20507812, 2202.97289062, 162.13200195), 'rotation':(-1.808533, 0.479905, -1.925629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3964.13429688, 2202.89109375, 162.48526367), 'rotation':(-1.83078, 0.481324, -1.950806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3953.0637500000003, 2202.80859375, 162.84133789), 'rotation':(-1.826294, 0.50709, -1.945709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3947.52929688, 2202.76265625, 163.02039062), 'rotation':(-1.849976, 0.53234, -1.972565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3941.99460938, 2202.71679688, 163.19951172), 'rotation':(-1.851685, 0.535929, -1.974487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3936.4596874999997, 2202.6709375, 163.37863281), 'rotation':(-1.851532, 0.535912, -1.974335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3930.9245312499997, 2202.62453125, 163.55796875), 'rotation':(-1.851532, 0.535912, -1.974335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3925.38914062, 2202.57882812, 163.73762695), 'rotation':(-1.854767, 0.535039, -1.977997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3908.78445312, 2202.42601562, 164.27935547), 'rotation':(-1.873505, 0.536261, -1.999268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3897.71507812, 2202.31617188, 164.64226562), 'rotation':(-1.876678, 0.538393, -2.002869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3881.1106250000003, 2202.1784374999997, 165.18691406000002), 'rotation':(-1.876556, 0.538381, -2.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3875.57570312, 2202.13234375, 165.36853516), 'rotation':(-1.876556, 0.538381, -2.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3864.50609375, 2202.04054688, 165.73224609000002), 'rotation':(-1.881104, 0.535815, -2.007874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3864.49070312, 2194.1909375, 165.73490234000002), 'rotation':(1.882605, -179.464218, 1.761727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3870.02390625, 2194.23679688, 165.55296875), 'rotation':(1.881089, -179.462204, 1.760398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3875.55710938, 2194.28296875, 165.37126952999998), 'rotation':(1.878138, -179.462387, 1.757828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3897.68898438, 2194.4665625, 164.64527343999998), 'rotation':(1.876547, -179.463684, 1.75645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3919.82179688, 2194.65039062, 163.92085938), 'rotation':(1.867216, -179.464157, 1.748293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3925.35523438, 2194.69625, 163.74085938), 'rotation':(1.861056, -179.462631, 1.742894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3936.42257812, 2194.788125, 163.38195312), 'rotation':(1.854765, -179.464966, 1.737388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3953.02195312, 2194.92601562, 162.84480469), 'rotation':(1.849977, -179.467651, 1.733202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3958.55882812, 2194.9678125, 162.66624023), 'rotation':(1.841904, -179.517944, 1.726135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3986.22875, 2195.17210938, 161.78489258), 'rotation':(1.8086, -179.520065, 1.696934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3991.7621875, 2195.21289062, 161.61053711), 'rotation':(1.802924, -179.521164, 1.691951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3826.48757812, 2201.88765625, 166.98167969), 'rotation':(-1.874359, 0.53625, -2.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3819.5989062500003, 2201.8303125, 167.20720702999998), 'rotation':(-1.872253, 0.536113, -1.997864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3793.288125, 2201.48242188, 168.06533202999998), 'rotation':(-1.862457, 0.542624, -1.986725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3787.75460938, 2201.4362499999997, 168.24488281), 'rotation':(-1.858124, 0.53601, -1.981781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3776.68703125, 2201.34445312, 168.601875), 'rotation':(-1.841095, 0.534907, -1.962463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3771.1535937500003, 2201.29859375, 168.77933593999998), 'rotation':(-1.832581, 0.534358, -1.95282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3760.08640625, 2201.20679688, 169.13244140999998), 'rotation':(-1.823059, 0.533192, -1.942078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3754.55273438, 2201.16085938, 169.30779297), 'rotation':(-1.812378, 0.532507, -1.929962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3749.01882812, 2201.11914062, 169.48289062), 'rotation':(-1.812378, 0.532507, -1.929962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3834.56734375, 2193.81320312, 166.71898438), 'rotation':(1.876444, -179.461029, 1.756352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3828.92015625, 2193.76632812, 166.90421875), 'rotation':(1.874354, -179.463745, 1.754526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3811.74828125, 2193.66554688, 167.46597656000003), 'rotation':(1.86777, -179.464188, 1.748762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3800.6796875, 2193.6396875, 167.82697266), 'rotation':(1.863433, -179.461868, 1.744975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3787.8134375, 2193.55445312, 168.24509766), 'rotation':(1.849731, -179.464523, 1.732994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3776.745625, 2193.46265625, 168.60208984000002), 'rotation':(1.832635, -179.465622, 1.718026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3771.21164062, 2193.4167187499997, 168.77957031000003), 'rotation':(1.823018, -179.466827, 1.709599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3760.14382812, 2193.32515625, 169.13271484), 'rotation':(1.81237, -179.467484, 1.70026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3754.60960938, 2193.27929688, 169.30806640999998), 'rotation':(1.807029, -179.466614, 1.695562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3707.5807812499997, 2192.8428125, 170.76783203), 'rotation':(1.72172, -179.473526, 1.620433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3700.08890625, 2192.82640625, 170.99359375), 'rotation':(1.72157, -179.4711, 1.620293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3683.4665625, 2192.6884375, 171.49041015999998), 'rotation':(1.676135, -179.474823, 1.580091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3666.84445312, 2192.55078125, 171.97240234), 'rotation':(1.615394, -179.478317, 1.526114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3650.2189843799997, 2192.4128124999997, 172.43955078), 'rotation':(1.600245, -179.481354, 1.512619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3638.87964844, 2192.22851562, 172.75576172), 'rotation':(1.563765, -179.481125, 1.480042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3694.484375, 2200.66210938, 171.16023438), 'rotation':(-1.721558, 0.528889, -1.827515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3683.4035937500003, 2200.5703125, 171.49033203), 'rotation':(-1.706421, 0.525374, -1.810516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3677.86179688, 2200.524375, 171.65265625), 'rotation':(-1.676147, 0.525177, -1.776489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3661.23921875, 2200.38625, 172.12876953), 'rotation':(-1.615387, 0.520078, -1.708527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3639.07300781, 2200.28664062, 172.74853516), 'rotation':(-1.587891, 0.520197, -1.677856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3573.52585938, 2191.77664062, 174.4290625), 'rotation':(1.346592, -179.493149, 1.284359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3556.90796875, 2191.63890625, 174.81015625), 'rotation':(1.276651, -179.495834, 1.220667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3545.82691406, 2191.546875, 175.05720703), 'rotation':(1.258654, -179.495224, 1.204218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3540.28589844, 2191.5009375, 175.17902343999998), 'rotation':(1.222966, -179.498657, 1.171553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3527.40210938, 2191.3307812499997, 175.45306641), 'rotation':(1.187121, -179.500168, 1.138667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3601.16164062, 2199.92796875, 173.74755859), 'rotation':(-1.462952, 0.512973, -1.539185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3590.08886719, 2199.7959375, 174.02689453), 'rotation':(-1.444275, 0.512097, -1.518555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3584.54859375, 2199.75, 174.16306641), 'rotation':(-1.407074, 0.510247, -1.477539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3573.47167969, 2199.65773438, 174.42880859000002), 'rotation':(-1.374451, 0.510379, -1.44162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3567.93359375, 2199.6115625, 174.55810547000002), 'rotation':(-1.346588, 0.506842, -1.411072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3556.85425781, 2199.51976562, 174.80988281), 'rotation':(-1.290619, 0.504261, -1.349823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3540.23265625, 2199.381875, 175.17875), 'rotation':(-1.258667, 0.502887, -1.314911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3529.15453125, 2199.32125, 175.41533203), 'rotation':(-1.222961, 0.501329, -1.276062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3523.61375, 2199.37203125, 175.53017577999998), 'rotation':(-1.187134, 0.501714, -1.237122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3480.24707031, 2190.96703125, 176.35404297000002), 'rotation':(0.967804, -179.507492, 0.935509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3463.64234375, 2190.86523438, 176.63263672000002), 'rotation':(0.905164, -179.51091, 0.876895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3452.56933594, 2190.7734375, 176.80902343999998), 'rotation':(0.882276, -179.510971, 0.855405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3447.03417969, 2190.7275, 176.89498047), 'rotation':(0.882276, -179.510971, 0.855405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3435.96019531, 2190.63578125, 177.06121094), 'rotation':(0.790786, -179.512146, 0.769193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3430.42652344, 2190.58984375, 177.14072266), 'rotation':(0.790786, -179.512146, 0.769193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3424.88867188, 2190.54390625, 177.2171875), 'rotation':(0.745023, -179.514877, 0.725833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3419.35253906, 2190.4978125, 177.2909375), 'rotation':(0.745023, -179.514877, 0.725833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3413.8146875, 2190.4518749999997, 177.36296875), 'rotation':(0.722176, -179.515579, 0.704137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3408.27855469, 2190.40578125, 177.43292968999998), 'rotation':(0.722176, -179.515579, 0.704137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3402.74046875, 2190.35984375, 177.50275391), 'rotation':(0.706522, -179.51622, 0.689261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3480.17554688, 2198.9196875, 176.35414062), 'rotation':(-1.009674, 0.492361, -1.045746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3463.57179688, 2198.74585938, 176.63271484), 'rotation':(-0.926056, 0.489537, -0.95639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3458.03664062, 2198.69992188, 176.72158202999998), 'rotation':(-0.926056, 0.489537, -0.95639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3441.42652344, 2198.56179688, 176.98037109), 'rotation':(-0.882294, 0.489023, -0.90976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3430.35742188, 2198.4700000000003, 177.14078125), 'rotation':(-0.836548, 0.487658, -0.861237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3419.2834375, 2198.3784375, 177.29097656000002), 'rotation':(-0.790802, 0.486362, -0.812866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3402.6716406200003, 2198.24023438, 177.50279297), 'rotation':(-0.722168, 0.484419, -0.74057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3397.13746094, 2198.29929688, 177.57115234), 'rotation':(-0.706512, 0.483787, -0.724121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3353.79589844, 2189.95382812, 178.02324219), 'rotation':(0.530398, -179.519791, 0.520646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3342.72753906, 2189.86179688, 178.12523438), 'rotation':(0.516963, -179.520035, 0.507694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3337.193125, 2189.8159375, 178.17517578), 'rotation':(0.503426, -179.520279, 0.494646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3331.65941406, 2189.77, 178.224375), 'rotation':(0.503426, -179.520279, 0.494646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3320.59105469, 2189.67820312, 178.32060547), 'rotation':(0.490005, -179.519089, 0.481681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3303.99121094, 2189.5403125000003, 178.45951172000002), 'rotation':(0.416648, -179.521713, 0.410628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3292.92945312, 2189.44898438, 178.53636719), 'rotation':(0.328074, -179.522842, 0.324344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3276.33544922, 2189.3112499999997, 178.61695312), 'rotation':(0.195002, -179.521362, 0.193689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3265.26976562, 2189.21945312, 178.64867188), 'rotation':(0.128449, -179.525452, 0.127869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3259.73511719, 2189.17359375, 178.66107422000002), 'rotation':(0.128455, -179.523315, 0.127872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3353.73070312, 2197.83421875, 178.02324219), 'rotation':(-0.537109, 0.481624, -0.547241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3348.19628906, 2197.78835938, 178.07447266), 'rotation':(-0.530396, 0.480202, -0.540283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3326.05957031, 2197.60476562, 178.27298828), 'rotation':(-0.503418, 0.479701, -0.512329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3309.45800781, 2197.46679688, 178.41460938), 'rotation':(-0.483246, 0.48156, -0.491455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3298.39306641, 2197.37476562, 178.50023438), 'rotation':(-0.416687, 0.478307, -0.42276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3287.33349609, 2197.2834375, 178.56775391), 'rotation':(-0.328094, 0.477155, -0.331848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3281.80054688, 2197.23757812, 178.59462890999998), 'rotation':(-0.2836, 0.47666, -0.286407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3276.27001953, 2197.19164062, 178.61695312), 'rotation':(-0.239319, 0.476278, -0.241302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3210.64039062, 2196.64648438, 178.77095702999998), 'rotation':(-0.128448, 0.475288, -0.128998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3199.51390625, 2196.55445312, 178.79345702999998), 'rotation':(-0.112732, 0.475994, -0.113159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3188.38916016, 2196.4621875000003, 178.80570312), 'rotation':(-0.050446, 0.475816, -0.050537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3160.56787109, 2196.23117188, 178.80900391), 'rotation':(-0.003601, 0.475394, -0.003571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3138.31103516, 2196.04640625, 178.80916016), 'rotation':(0.009596, 0.475339, 0.0096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3127.18579102, 2195.9540625, 178.80103516), 'rotation':(0.035934, 0.477417, 0.035893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3121.62133789, 2195.90796875, 178.794375), 'rotation':(0.068678, 0.474636, 0.06852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3093.80126953, 2195.6770312500003, 178.74876953), 'rotation':(0.111851, 0.477483, 0.111421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3077.11035156, 2195.53859375, 178.71103516), 'rotation':(0.140121, 0.477608, 0.139439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3071.54614258, 2195.49242188, 178.69640625), 'rotation':(0.149649, 0.474854, 0.148883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3077.17578125, 2187.65867188, 178.71103516), 'rotation':(-0.149658, -179.525146, -0.150421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3088.30249023, 2187.7509375, 178.73720702999998), 'rotation':(-0.130768, -179.522461, -0.131348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3093.86645508, 2187.79710938, 178.74876953), 'rotation':(-0.121216, -179.525253, -0.121735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3104.99511719, 2187.8893749999997, 178.76886718999998), 'rotation':(-0.102509, -179.525345, -0.102844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3116.12353516, 2187.9817187500003, 178.78625), 'rotation':(-0.088257, -179.523254, -0.088531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3138.37646484, 2188.16648438, 178.80916016), 'rotation':(-0.03595, -179.524643, -0.03598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3143.93969727, 2188.21265625, 178.81005859), 'rotation':(-0.009613, -179.524658, -0.009613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3149.50415039, 2188.25875, 178.80970703), 'rotation':(0.003668, -179.523163, 0.003669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3166.19800781, 2188.3975, 178.80865234), 'rotation':(0.003661, -179.524597, 0.003674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3171.76246094, 2188.44359375, 178.80830078), 'rotation':(0.003572, -179.524597, 0.003585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3177.32714844, 2188.48976562, 178.80792968999998), 'rotation':(0.003572, -179.524597, 0.003585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3188.45484375, 2188.58226562, 178.80570312), 'rotation':(0.019234, -179.524216, 0.019218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3199.57933594, 2188.6745312499997, 178.79345702999998), 'rotation':(0.081662, -179.524109, 0.081431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3210.70556641, 2188.7668750000003, 178.77095702999998), 'rotation':(0.112739, -179.523987, 0.11229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3044.52099609, 2195.26804688, 178.61673828), 'rotation':(0.183794, 0.475101, 0.182621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3022.28393555, 2195.08375, 178.53431641), 'rotation':(0.232513, 0.473957, 0.230642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3016.72412109, 2195.03757812, 178.51144531000003), 'rotation':(0.235601, 0.477172, 0.233673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2988.92797852, 2194.806875, 178.39017578), 'rotation':(0.262149, 0.475473, 0.259772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2983.36816406, 2194.76078125, 178.36304688), 'rotation':(0.279689, 0.477284, 0.276971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2972.24975586, 2194.6684375, 178.30527343999998), 'rotation':(0.297332, 0.47746, 0.29426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2966.68969727, 2194.6223437500003, 178.27556640999998), 'rotation':(0.306177, 0.477141, 0.302912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2916.65722656, 2194.20726562, 177.97078125), 'rotation':(0.386869, 0.478362, 0.381666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2905.5390625, 2194.115, 177.89382812), 'rotation':(0.403869, 0.477983, 0.398213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2877.74511719, 2193.88453125, 177.68074219), 'rotation':(0.459815, 0.478826, 0.452486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3039.02685547, 2187.34179688, 178.59773438), 'rotation':(-0.209686, -179.522476, -0.211212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3033.4675293, 2187.2956249999997, 178.57761718999998), 'rotation':(-0.222778, -179.524582, -0.224518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3027.90795898, 2187.24953125, 178.55642577999998), 'rotation':(-0.232513, -179.52153, -0.234406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2988.99316406, 2186.92625, 178.39017578), 'rotation':(-0.279694, -179.524353, -0.28244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2961.19604492, 2186.69578125, 178.24564453), 'rotation':(-0.321381, -179.522079, -0.324982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2955.63671875, 2186.649375, 178.21490234), 'rotation':(-0.33139, -179.521957, -0.335236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2950.07714844, 2186.60328125, 178.183125), 'rotation':(-0.341431, -179.521851, -0.34552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2938.95922852, 2186.51125, 178.11638672), 'rotation':(-0.361664, -179.521606, -0.366241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2900.04516602, 2186.1884375, 177.85363281000002), 'rotation':(-0.426361, -179.521698, -0.432739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2894.48803711, 2186.14234375, 177.8121875), 'rotation':(-0.437317, -179.52153, -0.444061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2888.92871094, 2186.09617188, 177.76955078), 'rotation':(-0.448669, -179.521347, -0.45575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2883.36938477, 2186.05007812, 177.72572266), 'rotation':(-0.459808, -179.518448, -0.467224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2672.97558594, 2184.30375, 175.14236327999998), 'rotation':(-1.006042, -179.506485, -1.04187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2684.08667969, 2184.39601562, 175.33664062), 'rotation':(-0.994751, -179.509125, -1.029755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2689.6428125, 2184.44210938, 175.43125), 'rotation':(-0.972015, -179.507294, -1.005432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.75464844, 2184.5346875, 175.61361327999998), 'rotation':(-0.926514, -179.508804, -0.956879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2734.08960938, 2184.8112499999997, 176.11080077999998), 'rotation':(-0.824249, -179.512299, -0.848206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2750.75707031, 2184.94945312, 176.34130859), 'rotation':(-0.779297, -179.514175, -0.800751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2756.3146875, 2184.995625, 176.41402344), 'rotation':(-0.749298, -179.514984, -0.769104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2761.87085938, 2185.04148438, 176.48460938), 'rotation':(-0.749298, -179.514984, -0.769104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2778.54175781, 2185.17992188, 176.69033202999998), 'rotation':(-0.704407, -179.516724, -0.721893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2800.76904297, 2185.3645312500003, 176.94863281000002), 'rotation':(-0.649536, -179.518433, -0.664368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2822.99730469, 2185.5490625, 177.18279297), 'rotation':(-0.586792, -179.517258, -0.598907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2839.66943359, 2185.68726562, 177.34712890999998), 'rotation':(-0.556, -179.518692, -0.566864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2845.22680664, 2185.7334375, 177.39939453), 'rotation':(-0.540527, -179.519012, -0.550812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2845.17626953, 2193.61398438, 177.39953125), 'rotation':(0.525105, 0.480696, 0.515546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2834.06201172, 2193.52171875, 177.29369140999998), 'rotation':(0.555998, 0.481297, 0.545281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2828.50464844, 2193.475625, 177.23876952999998), 'rotation':(0.571263, 0.481578, 0.559956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2817.39160156, 2193.38328125, 177.12642577999998), 'rotation':(0.57894, 0.480459, 0.567329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2811.83472656, 2193.3371875000003, 177.06875), 'rotation':(0.586788, 0.482741, 0.574868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2806.27734375, 2193.29125, 177.00953125), 'rotation':(0.618153, 0.483403, 0.604924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2784.05199219, 2193.1067187500003, 176.75742188), 'rotation':(0.681018, 0.484806, 0.66497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2778.49511719, 2193.06054688, 176.69056641), 'rotation':(0.696563, 0.485199, 0.67979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2772.93945312, 2193.0143749999997, 176.62259766), 'rotation':(0.704404, 0.483277, 0.687239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2756.27027344, 2192.8762500000003, 176.41429688), 'rotation':(0.71939, 0.484246, 0.7015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2745.15966797, 2192.7839062499997, 176.26646484), 'rotation':(0.779304, 0.485817, 0.758317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2739.60351562, 2192.7378125, 176.18962890999998), 'rotation':(0.779304, 0.485817, 0.758317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2722.93382812, 2192.599375, 175.95121093999998), 'rotation':(0.82424, 0.487705, 0.80078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2711.82373047, 2192.50734375, 175.78716797), 'rotation':(0.858323, 0.486477, 0.832879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.71800781, 2192.4153125000003, 175.61408203), 'rotation':(0.903777, 0.490456, 0.875587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2689.60644531, 2192.3229687499997, 175.43173828), 'rotation':(0.949266, 0.491926, 0.91819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2684.05029297, 2192.27710938, 175.33714844), 'rotation':(0.972052, 0.490107, 0.939484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2180.8884375, 2472.21460938, 161.24761719), 'rotation':(1.838509, -5.22818, 1.723167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2169.92648438, 2472.93066406, 160.8953418), 'rotation':(1.821673, -3.857788, 1.708406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2164.421875, 2473.27296875, 160.71928711), 'rotation':(1.817623, -3.515411, 1.704855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2142.36960938, 2474.04273438, 160.02303711000002), 'rotation':(1.786135, -0.834381, 1.677198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2136.8410937500003, 2474.08105469, 159.8503418), 'rotation':(1.782133, -0.491028, 1.673686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2125.80539062, 2473.9865625, 159.50895508), 'rotation':(1.757059, 0.925772, 1.651613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2120.28515625, 2473.87988281, 159.33842773), 'rotation':(1.767516, 1.161314, 1.660823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2109.22875, 2473.66601562, 159.00019531), 'rotation':(1.742511, 1.159778, 1.638785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2103.7004687500003, 2473.55933594, 158.83271484), 'rotation':(1.730005, 1.159021, 1.627743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2081.58226562, 2473.13160156, 158.17234375), 'rotation':(1.678328, 1.155894, 1.582027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2070.51929688, 2473.05933594, 157.8515332), 'rotation':(1.660214, 1.157312, 1.565969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2053.9245312499997, 2472.74144531, 157.38286133), 'rotation':(1.6056, 1.15171, 1.517402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2049.23484375, 2464.59375, 157.24862305), 'rotation':(-1.578369, -178.849121, -1.667206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2059.349375, 2464.67359375, 157.5299707), 'rotation':(-1.605621, -178.84584, -1.697601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2064.8671875, 2464.78027344, 157.68571289), 'rotation':(-1.605621, -178.84584, -1.697601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2070.38351562, 2464.89015625, 157.84310546999998), 'rotation':(-1.623779, -178.84726, -1.717926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2120.03445312, 2465.84691406, 159.32587891), 'rotation':(-1.754883, -178.837189, -1.865021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2125.55078125, 2465.9533593799997, 159.4962793), 'rotation':(-1.767517, -178.838684, -1.879272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2136.65578125, 2466.0546875, 159.8449707), 'rotation':(-1.815826, 179.98555, -1.933868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2147.76320312, 2465.91554688, 160.19832030999999), 'rotation':(-1.830933, 178.885712, -1.950958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2153.30539062, 2465.75148438, 160.37570312), 'rotation':(-1.839203, 178.200226, -1.960327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2180.9270312500003, 2464.18285156, 161.27249023000002), 'rotation':(-1.877777, 175.118118, -2.00412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2186.40796875, 2463.6528125, 161.4530957), 'rotation':(-1.886261, 174.430176, -2.013763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2229.0715625000003, 2457.36425781, 162.88359375), 'rotation':(-1.911682, 169.365891, -2.042694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2262.17359375, 2449.69703125, 164.01322266), 'rotation':(-1.901459, 165.561142, -2.031036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2273.13453125, 2446.6753125, 164.38851562), 'rotation':(-1.893036, 164.188675, -2.021484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2284.005625, 2443.41503906, 164.76105468999998), 'rotation':(-1.886627, 163.086761, -2.014191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2294.79757812, 2440.09328125, 165.12816406000002), 'rotation':(-1.859467, 162.95195, -1.983307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2300.19164062, 2438.433125, 165.31162109000002), 'rotation':(-1.859528, 162.952698, -1.983398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2305.58570312, 2436.77269531, 165.49501952999998), 'rotation':(-1.859467, 162.95195, -1.983307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2327.16359375, 2430.13867188, 166.22490234), 'rotation':(-1.84433, 162.949738, -1.966156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2348.79003906, 2423.66015625, 166.95119140999998), 'rotation':(-1.838684, 162.951797, -1.959747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2359.5778906200003, 2420.33960938, 167.31048828), 'rotation':(-1.82666, 162.949738, -1.946106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2375.76, 2415.35863281, 167.84339844), 'rotation':(-1.800354, 162.946579, -1.916351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2381.15527344, 2413.69800781, 168.0196875), 'rotation':(-1.787079, 162.947235, -1.901367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2391.94410156, 2410.37695312, 168.3709375), 'rotation':(-1.780548, 162.946945, -1.893982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.52222656, 2403.73535156, 169.06480469), 'rotation':(-1.736267, 162.946121, -1.844055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2418.91871094, 2402.08203125, 169.235), 'rotation':(-1.707123, 163.102066, -1.811279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2429.744375, 2398.94652344, 169.57095703), 'rotation':(-1.698944, 164.490448, -1.802094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2435.19117188, 2397.46558594, 169.73910156000002), 'rotation':(-1.698669, 164.851379, -1.801788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2446.098125, 2394.6975, 170.07216797), 'rotation':(-1.677002, 166.391724, -1.777496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2240.7934375, 2463.18335938, 163.22496094), 'rotation':(1.867811, -12.193176, 1.748809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2273.5495312499997, 2454.90503906, 164.3275), 'rotation':(1.849151, -15.813477, 1.73248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2278.9575, 2453.33667969, 164.51015625), 'rotation':(1.844294, -16.635925, 1.728238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2284.3584375, 2451.69703125, 164.69275391), 'rotation':(1.86167, -17.047241, 1.743453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2289.75632812, 2450.035625, 164.87652343999997), 'rotation':(1.859362, -17.049713, 1.741414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2305.94484375, 2445.03394531, 165.42720702999998), 'rotation':(1.859621, -17.048035, 1.74164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2343.72804688, 2433.39648438, 166.70412109), 'rotation':(1.838714, -17.050446, 1.723352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2349.12648438, 2431.7346093799997, 166.885625), 'rotation':(1.826591, -17.049805, 1.712731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2354.52464844, 2430.07273438, 167.06591797000002), 'rotation':(1.813354, -17.051086, 1.701123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2370.71875, 2425.088125, 167.60255859), 'rotation':(1.787037, -17.052307, 1.677984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2376.11644531, 2423.42699219, 167.77992188), 'rotation':(1.787037, -17.052307, 1.677984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2386.9138281200003, 2420.10328125, 168.13230468999998), 'rotation':(1.780555, -17.05307, 1.672295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2392.3122656200003, 2418.44164062, 168.30806640999998), 'rotation':(1.77423, -17.053711, 1.666724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2403.10984375, 2415.11816406, 168.65816406000002), 'rotation':(1.761567, -17.054474, 1.655581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.90625, 2411.79492188, 169.00400391), 'rotation':(1.736241, -17.05603, 1.633251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2419.31789062, 2410.13109375, 169.17582031), 'rotation':(1.747832, -16.897064, 1.643488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2430.26804688, 2406.9138281200003, 169.52179688), 'rotation':(1.73928, -15.507721, 1.635937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2435.754375, 2405.40503906, 169.69402344), 'rotation':(1.736487, -14.81134, 1.633479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2441.2814843799997, 2403.95191406, 169.86652343999998), 'rotation':(1.726515, -14.208038, 1.624663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2632.3159375, 2380.38574219, 174.93419922), 'rotation':(-1.252106, -179.972626, -1.30777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2621.2621875, 2380.38597656, 174.69238281000003), 'rotation':(-1.261749, -179.972183, -1.318298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2610.2107031200003, 2380.38597656, 174.44599609), 'rotation':(-1.300995, -179.970428, -1.361115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2604.68507812, 2380.38597656, 174.31978515999998), 'rotation':(-1.320587, -179.969528, -1.382568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2599.1596875, 2380.38597656, 174.19150391), 'rotation':(-1.34021, -179.968613, -1.404053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2571.53367188, 2380.53078125, 173.5225), 'rotation':(-1.422333, -179.964661, -1.494354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2566.01464844, 2380.53050781, 173.38535156), 'rotation':(-1.425598, 179.801376, -1.497955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2560.49511719, 2380.54761719, 173.24759766), 'rotation':(-1.438385, 179.337112, -1.512024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2554.97609375, 2380.62671875, 173.10800781), 'rotation':(-1.450836, 178.869431, -1.525787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2549.47023438, 2380.76148438, 172.96724609), 'rotation':(-1.476135, 177.937302, -1.553741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2543.94382812, 2380.9553125, 172.82445312), 'rotation':(-1.488861, 177.469284, -1.567841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2527.4142968799997, 2381.90699219, 172.38703125), 'rotation':(-1.520477, 175.70752, -1.602875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2500.04640625, 2384.536875, 171.64421875), 'rotation':(-1.588989, 172.465591, -1.679077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2489.22242188, 2386.05371094, 171.33740234), 'rotation':(-1.619873, 171.30658, -1.713562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2494.35890625, 2393.55835938, 171.45113281000002), 'rotation':(1.639457, -7.941803, 1.547529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2510.81859375, 2391.484375, 171.91730468999998), 'rotation':(1.57567, -5.899628, 1.490692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2516.33765625, 2390.9138281200003, 172.06927734), 'rotation':(1.563007, -5.489563, 1.47937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2544.09082031, 2388.98289062, 172.81957031000002), 'rotation':(1.511275, -2.062286, 1.43303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2566.34253906, 2388.556875, 173.39351562), 'rotation':(1.422339, 0.03534, 1.352967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2593.90039062, 2388.556875, 174.06753906000003), 'rotation':(1.359809, 0.032298, 1.296355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2604.92382812, 2388.55664062, 174.32527344), 'rotation':(1.300994, 0.029561, 1.242861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2621.45972656, 2388.37890625, 174.69673827999998), 'rotation':(1.252097, 0.027379, 1.198234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2632.48558594, 2388.37890625, 174.93791016), 'rotation':(1.252069, 0.027378, 1.198202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2670.3669531200003, 2380.4253125, 175.76626953), 'rotation':(-1.252075, -179.972626, -1.307739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2686.95921875, 2380.53050781, 176.12240234), 'rotation':(-1.18866, -179.975327, -1.2388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2698.02027344, 2380.53050781, 176.3415625), 'rotation':(-1.104065, -179.978714, -1.147247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2703.55078125, 2380.53078125, 176.44494140999998), 'rotation':(-1.061798, -179.980316, -1.101715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2714.61376953, 2380.53050781, 176.63933594), 'rotation':(-0.977264, -179.983322, -1.011047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2720.14599609, 2380.53050781, 176.7303125), 'rotation':(-0.934967, -179.984726, -0.965881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2725.67847656, 2380.53050781, 176.81890625), 'rotation':(-0.913849, -179.985413, -0.943359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2731.21265625, 2380.53050781, 176.90720703), 'rotation':(-0.913696, -179.985413, -0.943176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2736.74683594, 2380.53050781, 176.99535156000002), 'rotation':(-0.912323, -179.985458, -0.941742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2769.95140625, 2380.53050781, 177.52066406000003), 'rotation':(-0.901672, -179.985809, -0.93042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2775.48558594, 2380.53050781, 177.60779297000002), 'rotation':(-0.901672, -179.985809, -0.93042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2786.55273438, 2380.525625, 177.779375), 'rotation':(-0.880341, -179.986465, -0.907715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2819.75660156, 2380.56324219, 178.25931641), 'rotation':(-0.795166, -179.988968, -0.817474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2836.35913086, 2380.4533593799997, 178.48623047), 'rotation':(-0.773438, -179.989563, -0.794525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2830.85400391, 2388.41601562, 178.41189452999998), 'rotation':(0.77343, 0.010439, 0.75275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2814.25439453, 2388.41113281, 178.18320312), 'rotation':(0.795157, 0.011034, 0.773312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2808.72046875, 2388.41113281, 178.10542969), 'rotation':(0.809439, 0.011434, 0.786805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2803.18628906, 2388.41113281, 178.02621093999997), 'rotation':(0.823721, 0.011841, 0.800285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2797.65257812, 2388.41136719, 177.94554688), 'rotation':(0.837668, 0.012246, 0.813434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2786.58740234, 2388.41136719, 177.77990234), 'rotation':(0.866013, 0.01309, 0.840127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2781.05419922, 2388.41136719, 177.69482422000002), 'rotation':(0.880343, 0.013527, 0.853588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2775.52148438, 2388.41136719, 177.60833984), 'rotation':(0.894625, 0.013969, 0.866998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2747.85132812, 2388.41136719, 177.17177734), 'rotation':(0.90627, 0.014336, 0.877932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2731.24902344, 2388.41136719, 176.90779297), 'rotation':(0.912336, 0.014529, 0.883618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2725.71533203, 2388.41136719, 176.81951172), 'rotation':(0.913688, 0.014572, 0.88488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2720.18457031, 2388.41136719, 176.73095702999998), 'rotation':(0.913859, 0.014577, 0.885043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2709.125, 2388.41136719, 176.54496093999998), 'rotation':(0.97725, 0.016671, 0.94433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2703.59300781, 2388.41136719, 176.44572266), 'rotation':(1.019624, 0.01815, 0.983799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2692.53441406, 2388.411875, 176.23496093999998), 'rotation':(1.104045, 0.021282, 1.06209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2687.00855469, 2388.411875, 176.1234375), 'rotation':(1.146563, 0.022955, 1.101339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2681.47705078, 2388.411875, 176.00769531000003), 'rotation':(1.188665, 0.024673, 1.140074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2675.95166016, 2388.43261719, 175.88839843999997), 'rotation':(1.230855, 0.026457, 1.178783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2879.89111328, 2380.40085938, 179.03128906), 'rotation':(-0.691345, -179.991669, -0.708191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2913.10253906, 2380.53027344, 179.40433593999998), 'rotation':(-0.618195, -179.993332, -0.631622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2935.24438477, 2380.53003906, 179.63351562), 'rotation':(-0.575104, -179.994232, -0.586731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2946.31542969, 2380.53003906, 179.74214844), 'rotation':(-0.558746, -179.994553, -0.569733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2957.38574219, 2380.53003906, 179.84554688), 'rotation':(-0.542297, -179.994873, -0.552612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2962.92138672, 2380.53003906, 179.89609375), 'rotation':(-0.523438, -179.995224, -0.533081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2968.45751953, 2380.53027344, 179.94566406), 'rotation':(-0.513031, -179.995407, -0.522278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2979.52905273, 2380.53027344, 180.043125), 'rotation':(-0.500946, -179.995621, -0.509735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2985.06445312, 2380.53027344, 180.09001952999998), 'rotation':(-0.500946, -179.995621, -0.509735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2990.60083008, 2380.53027344, 180.13611328), 'rotation':(-0.476929, -179.996033, -0.484894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3012.7421875, 2380.53027344, 180.30628906), 'rotation':(-0.42868, -179.996796, -0.43515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3018.27856445, 2380.53027344, 180.34654297), 'rotation':(-0.416718, -179.996979, -0.422821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3023.81445312, 2380.53027344, 180.38648438), 'rotation':(-0.416687, -179.996979, -0.422791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3029.35083008, 2380.53027344, 180.42572266), 'rotation':(-0.406067, -179.997131, -0.411835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3040.42138672, 2380.53027344, 180.49878906), 'rotation':(-0.38504, -179.997406, -0.390228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3045.95703125, 2380.53027344, 180.53330078), 'rotation':(-0.363922, -179.997696, -0.368591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3045.96313477, 2388.41039062, 180.53332031000002), 'rotation':(0.342657, 0.002044, 0.338579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3040.42700195, 2388.410625, 180.49882811999998), 'rotation':(0.363919, 0.002307, 0.359331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3034.89306641, 2388.410625, 180.46296875), 'rotation':(0.363919, 0.002307, 0.359331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3029.35766602, 2388.410625, 180.42576172), 'rotation':(0.385031, 0.002583, 0.379891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3018.28588867, 2388.410625, 180.34658202999998), 'rotation':(0.416703, 0.003026, 0.410674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3007.21459961, 2388.410625, 180.26525390999998), 'rotation':(0.416723, 0.003026, 0.410693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3001.6784668, 2388.410625, 180.22380859), 'rotation':(0.428683, 0.003203, 0.422307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2968.46728516, 2388.410625, 179.94576172), 'rotation':(0.500933, 0.004375, 0.492227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2962.93139648, 2388.410625, 179.89617188), 'rotation':(0.513029, 0.004589, 0.503906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2957.39599609, 2388.41089844, 179.84564453), 'rotation':(0.523445, 0.004778, 0.51395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2951.86279297, 2388.41089844, 179.79464843999997), 'rotation':(0.523445, 0.004778, 0.51395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2946.32666016, 2388.41089844, 179.74226562), 'rotation':(0.542283, 0.005128, 0.532089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2935.25561523, 2388.41089844, 179.63361328), 'rotation':(0.55875, 0.005445, 0.54793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2929.72021484, 2388.41089844, 179.57775390999998), 'rotation':(0.575095, 0.005768, 0.56364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2924.18383789, 2388.41113281, 179.52058594), 'rotation':(0.591692, 0.006106, 0.579556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2913.11547852, 2388.41113281, 179.40447265999998), 'rotation':(0.606111, 0.006408, 0.593386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2902.04443359, 2388.41113281, 179.28488281000003), 'rotation':(0.630392, 0.006932, 0.616638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2879.90600586, 2388.54078125, 179.03146484), 'rotation':(0.679126, 0.008047, 0.663169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3094.95581055, 2380.53003906, 180.78646484), 'rotation':(-0.243347, -179.998978, -0.245422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3106.06079102, 2380.53003906, 180.82949219), 'rotation':(-0.210846, -179.999237, -0.212402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3111.61303711, 2380.53003906, 180.84886719), 'rotation':(-0.194489, -179.999344, -0.195831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3128.26831055, 2380.53003906, 180.90181640999998), 'rotation':(-0.186401, -179.99939, -0.187592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3144.91967773, 2380.52976562, 180.93013672), 'rotation':(-0.071045, -179.999908, -0.071228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3150.47290039, 2380.52976562, 180.93328125), 'rotation':(-0.03244, -179.999985, -0.032471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3161.5793457, 2380.52976562, 180.93960938), 'rotation':(-0.032593, -179.999985, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3167.13257812, 2380.52976562, 180.94275391), 'rotation':(-0.03244, -179.999985, -0.032471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3178.23876953, 2380.52976562, 180.9490625), 'rotation':(-0.032593, -179.999985, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3183.79199219, 2380.52976562, 180.95222656), 'rotation':(-0.032593, -179.999985, -0.032623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3178.23779297, 2388.41015625, 180.9490625), 'rotation':(0.032594, 1.4e-05, 0.032554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3172.68480469, 2388.41015625, 180.94589843999998), 'rotation':(0.032594, 1.4e-05, 0.032555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3161.57836914, 2388.41015625, 180.93958984), 'rotation':(0.032437, 1.3e-05, 0.032395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3150.47216797, 2388.41015625, 180.93328125), 'rotation':(0.032594, 1.4e-05, 0.032555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3133.82080078, 2388.41015625, 180.91615234), 'rotation':(0.071048, 8.3e-05, 0.070872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3117.16430664, 2388.41039062, 180.86728516), 'rotation':(0.186382, 0.000601, 0.185175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3094.95532227, 2388.41039062, 180.78646484), 'rotation':(0.227179, 0.000896, 0.225379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3255.01806641, 2380.52953125, 180.76390625), 'rotation':(0.298691, -179.998459, 0.295591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3260.55957031, 2380.52953125, 180.73173828), 'rotation':(0.328607, -179.998123, 0.324851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3266.10009766, 2380.52953125, 180.69931641), 'rotation':(0.335089, -179.998047, 0.331179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3271.63941406, 2380.52953125, 180.66572266), 'rotation':(0.349023, -179.997879, 0.344793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3293.79273438, 2380.52929688, 180.50335938), 'rotation':(0.459733, -179.996323, 0.452403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3299.32984375, 2380.52929688, 180.45566406), 'rotation':(0.487546, -179.99585, 0.479311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3310.40820312, 2380.5290625, 180.35222656000002), 'rotation':(0.542925, -179.994858, 0.53271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3315.94677734, 2380.5290625, 180.29826172), 'rotation':(0.556975, -179.994583, 0.546232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3349.17308594, 2380.52882812, 179.91619140999998), 'rotation':(0.750522, -179.990173, 0.731043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3349.18285156, 2388.4096875, 179.91607422), 'rotation':(-0.780396, 0.010628, -0.80188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3343.64601562, 2388.4096875, 179.98761718999998), 'rotation':(-0.750519, 0.009829, -0.770386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3327.03076172, 2388.4096875, 180.18341797000002), 'rotation':(-0.631317, 0.006953, -0.645355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3282.72021484, 2388.4096875, 180.59023438), 'rotation':(-0.43222, 0.003256, -0.438782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3271.64332031, 2388.4096875, 180.66570312), 'rotation':(-0.376709, 0.002472, -0.381683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3255.0234375, 2388.40992188, 180.76386718999998), 'rotation':(-0.328644, 0.00188, -0.332428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3243.94482422, 2388.40992188, 180.81894531), 'rotation':(-0.298706, 0.001552, -0.301819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3238.40771484, 2388.40992188, 180.84246094), 'rotation':(-0.251831, 0.001102, -0.254059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3221.78882812, 2388.40992188, 180.89314453), 'rotation':(-0.158295, 0.000432, -0.15918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3403.76464844, 2380.5178125, 179.07064452999998), 'rotation':(1.028927, -179.981506, 0.992465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3414.86375, 2380.52832031, 178.86576172000002), 'rotation':(1.070796, -179.979965, 1.031312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3420.41480469, 2380.52808594, 178.76005859), 'rotation':(1.10326, -179.978745, 1.06136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3431.51390625, 2380.52808594, 178.53851562), 'rotation':(1.168099, -179.976166, 1.121175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3442.60742188, 2380.52808594, 178.30341797), 'rotation':(1.232945, -179.973434, 1.180696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3453.70679688, 2380.52808594, 178.05445312), 'rotation':(1.297763, -179.970581, 1.239926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3459.2580468799997, 2380.5278125, 177.92705078), 'rotation':(1.314053, -179.969833, 1.254768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3470.35472656, 2380.5278125, 177.66585938), 'rotation':(1.340397, -179.968613, 1.278735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3475.90578125, 2380.5278125, 177.53078125), 'rotation':(1.393215, -179.966095, 1.326638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3453.75121094, 2388.40917969, 178.05341797), 'rotation':(-1.314056, 0.030159, -1.375427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3448.2009375, 2388.40917969, 178.17951172000002), 'rotation':(-1.29776, 0.029415, -1.357605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3437.1017968799997, 2388.40941406, 178.42181641), 'rotation':(-1.232941, 0.026547, -1.286896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3426.00097656, 2388.40941406, 178.65023438), 'rotation':(-1.168121, 0.023826, -1.216492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3414.89941406, 2388.40941406, 178.86509766), 'rotation':(-1.103271, 0.021252, -1.146393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3602.78027344, 2388.43433594, 173.69638672000002), 'rotation':(-2.01358, 0.103057, -2.159149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3586.13523438, 2388.42503906, 174.27542968999998), 'rotation':(-1.987274, 0.100536, -2.128998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3580.58445312, 2388.421875, 174.46310547000002), 'rotation':(-1.934265, 0.096893, -2.06842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3569.48804688, 2388.41601562, 174.83033203), 'rotation':(-1.881287, 0.093352, -2.008118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3563.93921875, 2388.41308594, 175.00875), 'rotation':(-1.881287, 0.093352, -2.008118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3558.3903906200003, 2388.41015625, 175.18603516), 'rotation':(-1.828308, 0.088479, -1.947998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3552.838125, 2388.40917969, 175.3609375), 'rotation':(-1.801941, 0.05676, -1.918152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3541.73730469, 2388.41722656, 175.70722656), 'rotation':(-1.776947, 0.055193, -1.889923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3536.1877343799997, 2388.41992188, 175.87566406000002), 'rotation':(-1.726929, 0.052126, -1.833588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3530.63820312, 2388.4221093799997, 176.04189452999998), 'rotation':(-1.726929, 0.052126, -1.833588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3525.08667969, 2388.38792969, 176.20458984), 'rotation':(-1.677063, 0.049153, -1.777527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3525.0434375, 2380.52734375, 176.20585938), 'rotation':(1.627135, -179.95372, 1.536564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3541.6909375, 2380.52710938, 175.70867188), 'rotation':(1.726959, -179.947861, 1.625049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3547.2424218799997, 2380.52710938, 175.53628906000003), 'rotation':(1.776949, -179.944809, 1.669122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3558.3403125, 2380.52808594, 175.18773438), 'rotation':(1.80177, -179.905228, 1.69095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3563.88820312, 2380.53078125, 175.01052734), 'rotation':(1.828373, -179.911499, 1.714281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3574.98730469, 2380.53664062, 174.64962891), 'rotation':(1.881307, -179.906647, 1.760581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3586.0803125, 2380.54273438, 174.27744141), 'rotation':(1.934255, -179.903107, 1.806725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3640.78785156, 2380.57203125, 172.31742188), 'rotation':(2.161174, -179.888077, 2.002379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3668.53421875, 2380.58691406, 171.25958984000002), 'rotation':(2.190052, -179.884995, 2.02704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3674.08421875, 2380.58984375, 171.04443359), 'rotation':(2.216792, -179.882935, 2.049831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3690.72632812, 2380.59886719, 170.38769531000003), 'rotation':(2.270246, -179.878738, 2.095237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3696.27539062, 2380.6017968799997, 170.16605468999998), 'rotation':(2.283517, -179.877319, 2.106489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3701.82328125, 2380.605, 169.944375), 'rotation':(2.283667, -179.877304, 2.106613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3712.92117188, 2380.61085938, 169.49886718999997), 'rotation':(2.291508, -179.878006, 2.113251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3712.97898438, 2388.49390625, 169.49636718999997), 'rotation':(-2.30722, 0.124748, -2.499176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3690.78078125, 2388.48195312, 170.38535156), 'rotation':(-2.283539, 0.122679, -2.471497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3685.2317187500003, 2388.47898438, 170.60599609000002), 'rotation':(-2.270264, 0.121264, -2.455994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3679.683125, 2388.47582031, 170.82507812), 'rotation':(-2.270264, 0.121264, -2.455994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3657.48460938, 2388.46386719, 171.68212891), 'rotation':(-2.190125, 0.114995, -2.362793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3646.38328125, 2388.46507812, 172.10470703), 'rotation':(-2.176697, 0.113354, -2.347229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3640.83324219, 2388.42847656, 172.31552734000002), 'rotation':(-2.176697, 0.113354, -2.347229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3745.4340625, 2380.6284375, 168.17316406), 'rotation':(2.35535, -179.872757, 2.167145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3756.5065624999997, 2380.63429688, 167.71599609), 'rotation':(2.361067, -179.87085, 2.171952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3767.5793750000003, 2380.64015625, 167.25855468999998), 'rotation':(2.361087, -179.872421, 2.171982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3773.11570312, 2380.64332031, 167.02962890999999), 'rotation':(2.363075, -179.870804, 2.173651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3789.72460938, 2380.65210938, 166.34142577999998), 'rotation':(2.369536, -179.869064, 2.179081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3795.26101562, 2380.65503906, 166.11197266), 'rotation':(2.369529, -179.871796, 2.17908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3800.79734375, 2380.65820312, 165.88246094), 'rotation':(2.369474, -179.869064, 2.179037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3811.8723437500003, 2380.6642968799997, 165.42462891), 'rotation':(2.360909, -179.871765, 2.171838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3817.4089062499997, 2380.6675, 165.19666016), 'rotation':(2.35537, -179.872223, 2.167176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3828.48265625, 2380.67335938, 164.74248047), 'rotation':(2.338247, -179.873642, 2.15273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3839.55617188, 2380.6794531200003, 164.29078125), 'rotation':(2.326984, -179.874557, 2.143232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3845.09007812, 2380.62425781, 164.06574218999998), 'rotation':(2.326984, -179.874557, 2.143232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3850.10226562, 2380.55566406, 163.86199219), 'rotation':(2.323965, -179.87471, 2.140683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3839.6640625, 2388.5627343799997, 164.28619141), 'rotation':(-2.323914, 0.125279, -2.518707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3834.12796875, 2388.55980469, 164.51171875), 'rotation':(-2.327087, 0.125452, -2.52243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3828.5915625, 2388.55664062, 164.73785156000002), 'rotation':(-2.33252, 0.125892, -2.528778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3823.05539062, 2388.55371094, 164.96458984), 'rotation':(-2.343964, 0.126829, -2.542175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3817.5190625, 2388.55078125, 165.19193359000002), 'rotation':(-2.349487, 0.127287, -2.548676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3789.8385937499997, 2388.53953125, 166.33652343999998), 'rotation':(-2.369537, 0.128208, -2.572205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3778.7668750000003, 2388.49683594, 166.79541016), 'rotation':(-2.369659, 0.128215, -2.572327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3773.2309375, 2388.49367188, 167.02466797), 'rotation':(-2.36731, 0.129538, -2.56958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3762.15945312, 2388.48730469, 167.48232422), 'rotation':(-2.363159, 0.129193, -2.564697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3751.08765625, 2388.48144531, 167.93960938), 'rotation':(-2.361084, 0.127573, -2.562286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.36304688, 2034.39296875, 161.41496094000001), 'rotation':(0.259588, 90.59185, 0.25724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2204.41773438, 2029.0787500000001, 161.39057617), 'rotation':(0.262949, 90.591103, 0.260542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2204.52734375, 2018.4503125, 161.34055664), 'rotation':(0.269301, 90.592865, 0.266785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.243125, 2034.47445312, 161.41496094000001), 'rotation':(-0.262939, -89.407166, -0.265381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.2981250000003, 2029.150625, 161.39054688), 'rotation':(-0.269318, -89.407104, -0.271851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.35304688, 2023.826875, 161.36561523), 'rotation':(-0.275879, -89.408752, -0.278534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.40796875, 2018.5032812499999, 161.34041992000002), 'rotation':(-0.275879, -89.408752, -0.278534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.46289062, 2013.1795312499999, 161.31480469), 'rotation':(-0.282227, -89.407013, -0.285034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2212.57273438, 2002.53257812, 161.26245117), 'rotation':(-0.285461, -89.407806, -0.2883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.02882812, 2066.75804688, 161.55864258), 'rotation':(0.236284, 90.590584, 0.234343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.97171875, 2072.29617188, 161.58169922), 'rotation':(0.22931, 90.592491, 0.227472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.91453125, 2077.83421875, 161.60426758), 'rotation':(0.22931, 90.592491, 0.227472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.85742188, 2083.3723437500003, 161.62635742), 'rotation':(0.222575, 90.592445, 0.220842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.8003125, 2088.91085938, 161.64787109), 'rotation':(0.218996, 90.591888, 0.217331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.743125, 2094.44875, 161.66910156), 'rotation':(0.218996, 90.591888, 0.217331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.68601562, 2099.98632812, 161.69020508), 'rotation':(0.213833, 90.592567, 0.212245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.62890625, 2105.52492188, 161.71085938), 'rotation':(0.203362, 90.591011, 0.201924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.5146875, 2116.60109375, 161.75076171999999), 'rotation':(0.192919, 90.592438, 0.191611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.45726562, 2122.1393749999997, 161.76969727), 'rotation':(0.192919, 90.592438, 0.191611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.34304688, 2133.21554688, 161.80598633), 'rotation':(0.177182, 90.590424, 0.176093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2203.22875, 2144.29148438, 161.84060546999999), 'rotation':(0.177168, 90.592987, 0.176091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.1535937500003, 2149.82859375, 161.85761719), 'rotation':(0.173459, 90.590813, 0.17241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2202.87085938, 2166.44289062, 161.90560546999998), 'rotation':(0.150524, 90.590706, 0.149731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2211.0425, 2163.36625, 161.89688476999999), 'rotation':(-0.165833, -89.40921, -0.166779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.069375, 2151.70164062, 161.86303711), 'rotation':(-0.173462, -89.407043, -0.1745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.109375, 2144.35570312, 161.84055664), 'rotation':(-0.177185, -89.406982, -0.178284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2211.33789062, 2122.20289062, 161.76963867), 'rotation':(-0.203369, -89.407501, -0.204834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.50929688, 2105.588125, 161.71080078), 'rotation':(-0.213837, -89.408875, -0.215454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.56640625, 2100.04929688, 161.69012695), 'rotation':(-0.218994, -89.408112, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.62351562, 2094.51195312, 161.6690332), 'rotation':(-0.222565, -89.407532, -0.224304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.680625, 2088.9739062500003, 161.64779296999998), 'rotation':(-0.222565, -89.407532, -0.224304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.7378125, 2083.43554688, 161.62629883), 'rotation':(-0.229309, -89.407501, -0.23114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.79492188, 2077.89695312, 161.60418945), 'rotation':(-0.236267, -89.40744, -0.238251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2211.90921875, 2066.82078125, 161.55856445), 'rotation':(-0.243134, -89.409363, -0.245209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2202.035625, 2259.9426562500003, 162.08918945), 'rotation':(0.068036, 90.590195, 0.067878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2202.15039062, 2248.8215625000003, 162.0746875), 'rotation':(0.07643, 90.59227, 0.076242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2202.26515625, 2237.70070312, 162.05789062), 'rotation':(0.088738, 90.592995, 0.088465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2202.29539062, 2232.14132812, 162.04888671999998), 'rotation':(0.088738, 90.592995, 0.088465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2202.316875, 2226.58054688, 162.03974609), 'rotation':(0.09412, 90.591331, 0.093811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2210.5793750000003, 2208.25710938, 162.00453125), 'rotation':(-0.126617, -89.408539, -0.127167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2210.23023438, 2232.20703125, 162.04885742), 'rotation':(-0.094116, -89.408661, -0.094421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2210.03078125, 2248.88742188, 162.07467773), 'rotation':(-0.084564, -89.407715, -0.084839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.97335938, 2254.4479687499997, 162.08222656), 'rotation':(-0.076416, -89.40976, -0.07663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.91601562, 2260.00875, 162.08916992000002), 'rotation':(-0.076416, -89.40976, -0.07663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.3893749999997, 2419.4765625, 162.08369141), 'rotation':(-0.071686, 90.591309, -0.071869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.44625, 2413.94996094, 162.08984375), 'rotation':(-0.063232, 90.591309, -0.063385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.5034375, 2408.42335938, 162.09570312), 'rotation':(-0.063232, 90.591309, -0.063385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2200.61742188, 2397.37011719, 162.10600586), 'rotation':(-0.050537, 90.591057, -0.050629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.6745312499997, 2391.84328125, 162.11086914), 'rotation':(-0.050537, 90.591057, -0.050629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.73140625, 2386.31761719, 162.11553711), 'rotation':(-0.050537, 90.591064, -0.050629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.84570312, 2375.26441406, 162.12298828000002), 'rotation':(-0.033203, 90.591347, -0.033234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2200.90257812, 2369.73804688, 162.12535156), 'rotation':(-0.021576, 90.591339, -0.021576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2200.9596874999997, 2364.21140625, 162.12695312), 'rotation':(-0.021576, 90.591339, -0.021576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2201.07375, 2353.15867188, 162.12823242000002), 'rotation':(-0.004303, 90.591484, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.13085938, 2347.63183594, 162.12864258), 'rotation':(-0.004303, 90.591484, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.18773438, 2342.105, 162.12907227), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.2448437499997, 2336.578125, 162.12948242000002), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.30171875, 2331.05101562, 162.12990234), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.35890625, 2325.52414062, 162.1303125), 'rotation':(-0.004303, 90.591461, -0.004303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.41578125, 2319.9973437500003, 162.13074219), 'rotation':(-0.004242, 90.590065, -0.004242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2201.586875, 2303.41992188, 162.12519531), 'rotation':(0.028448, 90.591087, 0.028412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2201.6440625, 2297.89304688, 162.12141602), 'rotation':(0.039233, 90.59185, 0.039182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.4674999999997, 2303.48734375, 162.12519531), 'rotation':(-0.039246, -89.410126, -0.039307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.1823437499997, 2331.11914062, 162.12990234), 'rotation':(0.004228, -89.408508, 0.00422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2209.12523438, 2336.64625, 162.12948242000002), 'rotation':(0.004317, -89.408508, 0.004307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.068125, 2342.1731250000003, 162.12907227), 'rotation':(0.004317, -89.408508, 0.004307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2209.01101562, 2347.70019531, 162.12864258), 'rotation':(0.004317, -89.408508, 0.004309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.9540625, 2353.22730469, 162.12823242000002), 'rotation':(0.004317, -89.408508, 0.004309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2208.89695312, 2358.75414062, 162.1278418), 'rotation':(0.004317, -89.408508, 0.004307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.6120312499997, 2386.3871875, 162.11555664), 'rotation':(0.044704, -89.40863, 0.044644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.3840625000003, 2408.49339844, 162.09572265999998), 'rotation':(0.054799, -89.408691, 0.054697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.26976562, 2419.546875, 162.08371094), 'rotation':(0.063248, -89.408722, 0.063113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2208.15578125, 2430.60058594, 162.06952148), 'rotation':(0.071683, -89.408691, 0.071515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.98460938, 2447.18066406, 162.04557617), 'rotation':(0.084462, -89.40802, 0.084219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.67875, 2573.76097656, 161.77206055), 'rotation':(0.152047, -89.40863, 0.151252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2206.79296875, 2562.6753125, 161.80167969000001), 'rotation':(0.147744, -89.40863, 0.14698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.85007812, 2557.13207031, 161.81597656), 'rotation':(0.143229, -89.408661, 0.142507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.96460938, 2546.0466406200003, 161.84397461), 'rotation':(0.141214, -89.406281, 0.140521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2207.02171875, 2540.50367188, 161.85766602), 'rotation':(0.141043, -89.408966, 0.140349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.0790625, 2534.9607031200003, 161.87130859), 'rotation':(0.13799, -89.409302, 0.137326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.365, 2507.24707031, 161.93495117), 'rotation':(0.118914, -89.407837, 0.118413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2207.4792187499997, 2496.16136719, 161.95782227), 'rotation':(0.115888, -89.409424, 0.115424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2207.5364062500003, 2490.61839844, 161.96902344), 'rotation':(0.115758, -89.407227, 0.115294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2198.9700000000003, 2557.05859375, 161.8159668), 'rotation':(-0.147736, 90.591347, -0.148499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.02710938, 2551.51609375, 161.83009765999998), 'rotation':(-0.147736, 90.591347, -0.148499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.25585938, 2529.34546875, 161.8846582), 'rotation':(-0.138, 90.592255, -0.138672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.37039062, 2518.26023438, 161.91055663999998), 'rotation':(-0.131531, 90.592201, -0.132141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.48484375, 2507.17480469, 161.93494141), 'rotation':(-0.125366, 90.590614, -0.125916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2199.54203125, 2501.63207031, 161.94644531), 'rotation':(-0.118896, 90.592155, -0.119415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2199.65601562, 2490.546875, 161.96901367), 'rotation':(-0.115906, 90.590569, -0.116364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.07398438, 2837.7109375, 160.91826172), 'rotation':(-0.197754, 90.592552, -0.199097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.2487499999997, 2820.77246094, 160.97671875), 'rotation':(-0.197723, 90.59256, -0.199097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2196.306875, 2815.12695312, 160.99618164), 'rotation':(-0.197418, 90.592552, -0.198792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.42359375, 2803.83447266, 161.03503906), 'rotation':(-0.197144, 90.590225, -0.198486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.59835938, 2786.89625, 161.09321289), 'rotation':(-0.196686, 90.593445, -0.198059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2196.65648438, 2781.25, 161.11260742000002), 'rotation':(-0.196838, 90.591339, -0.198181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2196.77320312, 2769.95800781, 161.15134766), 'rotation':(-0.196411, 90.591324, -0.197754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.06445312, 2741.72753906, 161.24736328), 'rotation':(-0.194092, 90.592819, -0.195404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.23921875, 2724.78955078, 161.30453125), 'rotation':(-0.192719, 90.59169, -0.194031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.47242188, 2702.2053125, 161.3796582), 'rotation':(-0.189362, 90.59166, -0.190613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.53054688, 2696.55908203, 161.39822266), 'rotation':(-0.188507, 90.59166, -0.189728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.58890625, 2690.91285156, 161.41671875), 'rotation':(-0.187469, 90.594009, -0.18869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.64695312, 2685.26683594, 161.43516602), 'rotation':(-0.187103, 90.590561, -0.188324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2197.82179688, 2668.32886719, 161.48993164), 'rotation':(-0.18338, 90.591957, -0.18457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2198.46265625, 2606.22265625, 161.68039062), 'rotation':(-0.167786, 90.590721, -0.168762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2206.16820312, 2623.2341406200003, 161.63029297), 'rotation':(0.171451, -89.407837, 0.170429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2206.11007812, 2628.88011719, 161.61314453), 'rotation':(0.171451, -89.407837, 0.170429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2206.05171875, 2634.52660156, 161.59588867), 'rotation':(0.175215, -89.409241, 0.17415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.9934375000003, 2640.17261719, 161.57844727), 'rotation':(0.1771, -89.406555, 0.176004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.93507812, 2645.81859375, 161.56098633), 'rotation':(0.176943, -89.408997, 0.175852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.81859375, 2657.11085938, 161.52576172), 'rotation':(0.17837, -89.40802, 0.177269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.7021875, 2668.40332031, 161.48996094), 'rotation':(0.180822, -89.408051, 0.179692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2205.64382812, 2674.04931641, 161.471875), 'rotation':(0.183391, -89.40802, 0.182214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.52734375, 2685.3415625, 161.43517578), 'rotation':(0.185843, -89.409515, 0.18464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.41085938, 2696.63402344, 161.39825195), 'rotation':(0.187461, -89.408325, 0.186241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.2942187500003, 2707.92652344, 161.36102539), 'rotation':(0.189374, -89.408325, 0.188129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.17773438, 2719.21875, 161.3234375), 'rotation':(0.191122, -89.408325, 0.189856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2205.119375, 2724.86523438, 161.30455078), 'rotation':(0.191997, -89.408295, 0.190712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2205.06101562, 2730.51123047, 161.28556641), 'rotation':(0.192727, -89.405945, 0.191436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.94460938, 2741.80371094, 161.24737305), 'rotation':(0.19421, -89.409119, 0.192898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.88625, 2747.44970703, 161.22824219), 'rotation':(0.19421, -89.409119, 0.192898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.828125, 2753.09619141, 161.20910156), 'rotation':(0.194087, -89.407166, 0.19277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.59523438, 2775.68115234, 161.13200195), 'rotation':(0.196402, -89.408691, 0.195061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.536875, 2781.32714844, 161.11262695), 'rotation':(0.196696, -89.406555, 0.195351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2204.47875, 2786.97339844, 161.09321289), 'rotation':(0.196826, -89.408691, 0.195479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.42039062, 2792.61988281, 161.07383789), 'rotation':(0.196696, -89.408691, 0.195346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.30398438, 2803.91210938, 161.03504883), 'rotation':(0.196839, -89.409729, 0.195507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.1875, 2815.20484375, 160.99618164), 'rotation':(0.19714, -89.40744, 0.195793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.12914062, 2820.85082031, 160.97672852), 'rotation':(0.197433, -89.40744, 0.196079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2204.01242188, 2832.14306641, 160.93776367), 'rotation':(0.197734, -89.407471, 0.196382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2203.9543750000003, 2837.78955078, 160.91826172), 'rotation':(0.197864, -89.407471, 0.196502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2480.27613281, 2007.73789062, 169.78128906), 'rotation':(0.202174, 99.520744, 0.200748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2477.25976562, 2024.2423437500001, 169.8290625), 'rotation':(0.140716, 100.911774, 0.140021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2475.15257812, 2035.19273438, 169.85640625), 'rotation':(0.138967, 100.728981, 0.13829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2489.11035156, 2002.74914062, 169.75697266), 'rotation':(-0.236023, -81.304108, -0.237976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2488.18285156, 2008.23226562, 169.77841797000002), 'rotation':(-0.209961, -80.754822, -0.211517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2487.24757812, 2013.7142187499999, 169.79693359), 'rotation':(-0.184265, -80.198914, -0.185455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2485.2065625, 2024.6516406199999, 169.82634765999998), 'rotation':(-0.140747, -79.088409, -0.141449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2484.1872656200003, 2030.1396875, 169.84005859), 'rotation':(-0.140747, -79.088409, -0.141449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2483.23558594, 2035.64101562, 169.85376953), 'rotation':(-0.140717, -79.088226, -0.141418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.31398438, 2072.75710938, 169.97052734000002), 'rotation':(0.209093, 96.192558, 0.207578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.86449219, 2078.26125, 169.99066406000003), 'rotation':(0.209093, 95.607422, 0.207576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.45019531, 2094.80492188, 170.05347656), 'rotation':(0.232042, 93.839989, 0.230178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.10007812, 2100.336875, 170.07638672000002), 'rotation':(0.242424, 93.254059, 0.240392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2466.81054688, 2105.87476562, 170.10037109), 'rotation':(0.252498, 92.663353, 0.250287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2466.20972656, 2133.59859375, 170.23519531000002), 'rotation':(0.280987, 90.448204, 0.278246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2466.16648438, 2139.14914062, 170.2628125), 'rotation':(0.271855, 90.448112, 0.269282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2466.12351562, 2144.70015625, 170.28949218999998), 'rotation':(0.262539, 90.445274, 0.260146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2466.0803125, 2150.2512500000003, 170.31517578), 'rotation':(0.253236, 90.447952, 0.250999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.8728125, 2161.51125, 170.36402343999998), 'rotation':(-0.24411, -89.552124, -0.246185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.95945312, 2150.4426562500003, 170.31576172), 'rotation':(-0.262543, -89.551941, -0.264954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2474.04566406, 2139.3723437500003, 170.26361328), 'rotation':(-0.280975, -89.551788, -0.283752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2474.43554688, 2117.19234375, 170.15166016), 'rotation':(-0.279449, -88.520844, -0.282196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2474.83546875, 2106.06617188, 170.09955078), 'rotation':(-0.253021, -87.042114, -0.25528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2475.48265625, 2094.96460938, 170.05185547000002), 'rotation':(-0.232086, -85.864532, -0.233948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2475.79566406, 2089.4153125000003, 170.02972656000003), 'rotation':(-0.221771, -85.269714, -0.223511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2476.23632812, 2083.88132812, 170.00865234), 'rotation':(-0.21405, -84.678711, -0.215668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2477.38039062, 2072.85765625, 169.96759766), 'rotation':(-0.209595, -83.415527, -0.211121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2465.17820312, 2266.03367188, 170.67324219), 'rotation':(0.090295, 90.445869, 0.09001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2465.26488281, 2254.90773438, 170.65275391), 'rotation':(0.106742, 90.445961, 0.106339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2465.3513281200003, 2243.78273438, 170.62886719), 'rotation':(0.131249, 90.446075, 0.13064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2465.43824219, 2232.65695312, 170.60160156), 'rotation':(0.147518, 90.448814, 0.14677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.058125, 2266.0950000000003, 170.67326172), 'rotation':(-0.098511, -89.551392, -0.098846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.18796875, 2249.4071875, 170.64123047), 'rotation':(-0.123169, -89.553955, -0.123718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.23121094, 2243.84421875, 170.62888672), 'rotation':(-0.139465, -89.553894, -0.140137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.36132812, 2227.15578125, 170.58701172000002), 'rotation':(-0.151733, -89.551636, -0.152527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.40476562, 2221.5924999999997, 170.57226562), 'rotation':(-0.151733, -89.551636, -0.152527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.46191406, 2216.03148438, 170.55744141), 'rotation':(-0.157166, -89.555115, -0.15802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2473.57640625, 2210.47023438, 170.54189452999998), 'rotation':(-0.167877, -89.552307, -0.168854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.3203125, 2376.14257812, 170.71810547), 'rotation':(-0.038788, 90.446022, -0.038818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.36351562, 2370.5915625, 170.72185547), 'rotation':(-0.038605, 90.446037, -0.038666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.57984375, 2342.84007812, 170.72927734), 'rotation':(0.015204, 90.446571, 0.015186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2464.62304688, 2337.2890625, 170.72777344), 'rotation':(0.015204, 90.446571, 0.015186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2464.92578125, 2298.4340625, 170.71458984), 'rotation':(0.025306, 90.446915, 0.02528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.24339844, 2370.65308594, 170.72185547), 'rotation':(0.038782, -89.551208, 0.038732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.33007812, 2359.55273438, 170.72894531000003), 'rotation':(0.025183, -89.555115, 0.025166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.37304688, 2354.00242188, 170.7309375), 'rotation':(-0.001801, -89.552948, -0.001801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2472.41625, 2348.453125, 170.73076172), 'rotation':(-0.015198, -89.553406, -0.015228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.45972656, 2342.90210938, 170.72927734), 'rotation':(-0.015289, -89.553436, -0.015289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.50292969, 2337.35109375, 170.72777344), 'rotation':(-0.015289, -89.553436, -0.015289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.54613281, 2331.80007812, 170.72630859), 'rotation':(-0.015198, -89.553406, -0.015228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2472.6328125, 2320.6979687499997, 170.72335938), 'rotation':(-0.015289, -89.553436, -0.015289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2463.88328125, 2415.56984375, 170.68042968999998), 'rotation':(-0.086456, 90.447166, -0.0867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.85230469, 2436.16234375, 170.64796875), 'rotation':(-0.099304, 90.44632, -0.09964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.80933594, 2441.69066406, 170.63839843999997), 'rotation':(-0.103699, 90.44632, -0.104095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2463.68042969, 2458.27585938, 170.60685547), 'rotation':(-0.11731, 90.446365, -0.117798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.59449219, 2469.3325, 170.58351562), 'rotation':(-0.126312, 90.446404, -0.126892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2463.37890625, 2496.97265625, 170.51945312), 'rotation':(-0.142212, 90.446159, -0.142944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.3359375, 2502.50097656, 170.505625), 'rotation':(-0.14621, 90.448601, -0.146942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.2497656200003, 2513.55738281, 170.47685547), 'rotation':(-0.153992, 90.446198, -0.154846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.20679688, 2519.0859375, 170.46193359), 'rotation':(-0.15799, 90.446213, -0.158844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2463.12035156, 2530.14183594, 170.43125), 'rotation':(-0.162231, 90.447266, -0.163177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.99121094, 2546.7265625, 170.38402344), 'rotation':(-0.17157, 90.447296, -0.172577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2462.75609375, 2568.83472656, 170.31707031000002), 'rotation':(-0.178619, 90.446922, -0.179718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.7419531200003, 2563.37378906, 170.33416015999998), 'rotation':(0.176294, -89.552673, 0.175223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.78492188, 2557.84570312, 170.35115234), 'rotation':(0.171547, -89.552704, 0.170526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.828125, 2552.31714844, 170.36771484000002), 'rotation':(0.166882, -89.552734, 0.165925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.87109375, 2546.7890625, 170.38402344), 'rotation':(0.166882, -89.552734, 0.165925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2470.9142968799997, 2541.26074219, 170.40007812), 'rotation':(0.162231, -89.552734, 0.161315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.9575, 2535.73242188, 170.41574218999997), 'rotation':(0.159861, -89.553772, 0.158971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.00046875, 2530.20410156, 170.43125), 'rotation':(0.159861, -89.553772, 0.158971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.12964844, 2513.61960938, 170.47685547), 'rotation':(0.150039, -89.553772, 0.149248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.21582031, 2502.56296875, 170.505625), 'rotation':(0.142225, -89.553833, 0.141517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.30199219, 2491.50660156, 170.53291016), 'rotation':(0.134411, -89.553894, 0.133791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.34496094, 2485.97828125, 170.54599609000002), 'rotation':(0.13058, -89.553894, 0.129995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.38820312, 2480.45019531, 170.55875), 'rotation':(0.128571, -89.552917, 0.127998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.51710938, 2463.86597656, 170.59541016), 'rotation':(0.117315, -89.553619, 0.116827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.56007812, 2458.33765625, 170.60685547), 'rotation':(0.112725, -89.55365, 0.112284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2471.64625, 2447.2810156200003, 170.62833984), 'rotation':(0.103703, -89.55368, 0.103335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.68945312, 2441.75292969, 170.63839843999997), 'rotation':(0.099284, -89.553711, 0.098947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2471.775625, 2430.69703125, 170.65705078), 'rotation':(0.092399, -89.553436, 0.092102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2472.02246094, 2415.6328125, 170.68042968999998), 'rotation':(0.074005, -89.552856, 0.07383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.40308594, 2750.53369141, 169.70882812), 'rotation':(-0.192383, 90.446037, -0.193695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.53246094, 2733.94605469, 169.76492188), 'rotation':(-0.194427, 90.447693, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.57542969, 2728.41699219, 169.78375), 'rotation':(-0.194427, 90.447693, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2461.66164062, 2717.35816406, 169.82152344), 'rotation':(-0.195862, 90.447411, -0.197174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.70484375, 2711.82910156, 169.84044922), 'rotation':(-0.195862, 90.447411, -0.197174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.92015625, 2684.18310547, 169.93501952999998), 'rotation':(-0.196106, 90.448143, -0.197449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.00632812, 2673.12451172, 169.97287109), 'rotation':(-0.196106, 90.44632, -0.197449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2462.22167969, 2645.47828125, 170.06716797), 'rotation':(-0.193481, 90.444885, -0.194794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.26488281, 2639.94921875, 170.08578125), 'rotation':(-0.192474, 90.447624, -0.193756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.35082031, 2628.8908593799997, 170.12285156000002), 'rotation':(-0.191925, 90.44696, -0.193237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2462.43703125, 2617.83277344, 170.15984375), 'rotation':(-0.191925, 90.44696, -0.193237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.5234375, 2606.77417969, 170.19646484), 'rotation':(-0.188965, 90.446335, -0.190216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2462.56640625, 2601.24511719, 170.21451172000002), 'rotation':(-0.186981, 90.446312, -0.188202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.28320312, 2750.59570312, 169.70882812), 'rotation':(0.19352, -89.553955, 0.192207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.32617188, 2745.06640625, 169.72748047000002), 'rotation':(0.19352, -89.553955, 0.192207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.41234375, 2734.0078125, 169.76492188), 'rotation':(0.195466, -89.552307, 0.194146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.49851562, 2722.94945312, 169.80263672), 'rotation':(0.195856, -89.554169, 0.194522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.58472656, 2711.89111328, 169.84044922), 'rotation':(0.195951, -89.552582, 0.194618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.62769531, 2706.36207031, 169.85935547), 'rotation':(0.196013, -89.553223, 0.194677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2469.67089844, 2700.83251953, 169.87826172), 'rotation':(0.196013, -89.551514, 0.194688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.8003125, 2684.24488281, 169.93501952999998), 'rotation':(0.196095, -89.551849, 0.194766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2469.84328125, 2678.71558594, 169.95394531000002), 'rotation':(0.196095, -89.551849, 0.194766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2470.14476562, 2640.01125, 170.08578125), 'rotation':(0.191942, -89.55304, 0.190654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2470.2309375, 2628.953125, 170.12285156000002), 'rotation':(0.191942, -89.55304, 0.190654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.30101562, 3020.32592773, 168.87845703), 'rotation':(-0.163971, 90.446831, -0.164917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2459.38914062, 3009.01464844, 168.91085938), 'rotation':(-0.163971, 90.446831, -0.164917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.47730469, 2997.70361328, 168.94328125), 'rotation':(-0.164429, 90.44706, -0.165344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.52125, 2992.04760742, 168.95955078), 'rotation':(-0.164429, 90.44706, -0.165344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2459.56542969, 2986.39233398, 168.97587891), 'rotation':(-0.165314, 90.447083, -0.16629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2459.78589844, 2958.11450195, 169.05775391), 'rotation':(-0.166504, 90.446434, -0.16745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2459.96191406, 2935.4921875, 169.12421875), 'rotation':(-0.169281, 90.446465, -0.170258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2460.00609375, 2929.83691406, 169.14105468999998), 'rotation':(-0.170746, 90.447952, -0.171753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.09105469, 2918.52319336, 169.17486327999998), 'rotation':(-0.171387, 90.446106, -0.172394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.13820312, 2912.87011719, 169.19177734000002), 'rotation':(-0.171387, 90.448463, -0.172394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.18238281, 2907.21435547, 169.20869141), 'rotation':(-0.171387, 90.446083, -0.172394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.40257812, 2878.93652344, 169.29476562), 'rotation':(-0.17627, 90.447823, -0.177338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.44679688, 2873.28076172, 169.3121875), 'rotation':(-0.17627, 90.445496, -0.177368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.57886719, 2856.31396484, 169.36457031), 'rotation':(-0.177399, 90.446236, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.66699219, 2845.00292969, 169.4), 'rotation':(-0.179382, 90.447693, -0.180511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2460.84328125, 2822.38037109, 169.47226562), 'rotation':(-0.184601, 90.447655, -0.185791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2460.93140625, 2811.06910156, 169.50869140999998), 'rotation':(-0.184601, 90.447655, -0.185791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2460.97558594, 2805.41382812, 169.52689453), 'rotation':(-0.184448, 90.447678, -0.185638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2461.01953125, 2799.75804688, 169.54525390999999), 'rotation':(-0.186005, 90.446198, -0.187225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.98753906, 2788.50707031, 169.58242188), 'rotation':(0.190439, -89.552979, 0.189183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.89941406, 2799.818125, 169.54525390999999), 'rotation':(0.188875, -89.553772, 0.187642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.85546875, 2805.4709375, 169.52691406000002), 'rotation':(0.186007, -89.552124, 0.184803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.81128906, 2811.12914062, 169.50869140999998), 'rotation':(0.184436, -89.554932, 0.183258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.76734375, 2816.78492188, 169.49046875), 'rotation':(0.1846, -89.552338, 0.183416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.635, 2833.75195312, 169.4359375), 'rotation':(0.183452, -89.553741, 0.182293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2468.546875, 2845.0625, 169.4), 'rotation':(0.181464, -89.552277, 0.180315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.45875, 2856.37426758, 169.36457031), 'rotation':(0.179388, -89.553741, 0.178259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.370625, 2867.68505859, 169.32957031), 'rotation':(0.17738, -89.552307, 0.176286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.32664062, 2873.34106445, 169.3121875), 'rotation':(0.176417, -89.554504, 0.175338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.28273438, 2878.99633789, 169.29476562), 'rotation':(0.176253, -89.552155, 0.175188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.10644531, 2901.61865234, 169.22564452999998), 'rotation':(0.172578, -89.554138, 0.171552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2468.01832031, 2912.93017578, 169.19177734000002), 'rotation':(0.171369, -89.553894, 0.17035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.88597656, 2929.89672852, 169.14105468999998), 'rotation':(0.171369, -89.551514, 0.170353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2467.79785156, 2941.20825195, 169.1075), 'rotation':(0.169266, -89.553528, 0.16827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.70972656, 2952.51904297, 169.07425781), 'rotation':(0.16779, -89.552063, 0.16681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.66578125, 2958.17456055, 169.05775391), 'rotation':(0.16779, -89.552063, 0.16681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2467.6215625, 2963.83032227, 169.04132812), 'rotation':(0.166493, -89.553558, 0.165529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.48925781, 2980.79711914, 168.99222656), 'rotation':(0.165694, -89.554016, 0.164736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.3571875, 2997.76416016, 168.94328125), 'rotation':(0.165318, -89.554749, 0.16437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.26929688, 3009.07519531, 168.91085938), 'rotation':(0.164136, -89.553162, 0.163193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.22507812, 3014.73071289, 168.89466797), 'rotation':(0.163986, -89.553192, 0.163045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2467.18117188, 3020.38623047, 168.87845703), 'rotation':(0.164, -89.553162, 0.163051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2868.17211914, 2040.15039062, 176.24130859000002), 'rotation':(-0.516022, -83.506897, -0.52536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2871.11035156, 2018.65539062, 176.04748047), 'rotation':(-0.512817, -81.134888, -0.522064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2871.95581055, 2013.29835938, 175.99908202999998), 'rotation':(-0.512817, -80.546692, -0.522064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2872.70703125, 2007.9415625000001, 175.95101562), 'rotation':(-0.512634, -80.402649, -0.521851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.59399414, 2075.70632812, 176.56617188), 'rotation':(-0.526703, -87.861572, -0.536438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.02075195, 2173.19875, 177.40873047000002), 'rotation':(0.460416, 90.191574, 0.453052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.0390625, 2167.59835938, 177.36373047), 'rotation':(0.460416, 90.191574, 0.453052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.12060547, 2161.99804688, 177.31873047000002), 'rotation':(0.460416, 90.193161, 0.453054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.17260742, 2150.7978125, 177.22751953), 'rotation':(0.469712, 90.19278, 0.462063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.20751953, 2145.19773438, 177.18105469), 'rotation':(0.475928, 90.192879, 0.468073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.25878906, 2139.59789062, 177.13400391), 'rotation':(0.482129, 90.190567, 0.474058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2857.38671875, 2105.99804688, 176.84017577999998), 'rotation':(0.510024, 90.193962, 0.501019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.42333984, 2094.79734375, 176.73998047), 'rotation':(0.514006, 90.192497, 0.504852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.45092773, 2089.20382812, 176.68990234), 'rotation':(0.510099, 90.412117, 0.501075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.52587891, 2083.6184375000003, 176.63986328), 'rotation':(0.511451, 90.8452, 0.502386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2865.40307617, 2083.85328125, 176.64060547), 'rotation':(-0.524567, -88.717102, -0.534271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.33007812, 2089.45140625, 176.6915625), 'rotation':(-0.523621, -89.153168, -0.533264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.21166992, 2122.975625, 176.990625), 'rotation':(-0.506958, -89.80658, -0.515991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.19311523, 2128.5598437500003, 177.03927734), 'rotation':(-0.500732, -89.806702, -0.509552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2865.15625, 2139.72703125, 177.13486328), 'rotation':(-0.488342, -89.806885, -0.496704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2865.13793945, 2145.31101562, 177.18177734), 'rotation':(-0.482117, -89.807007, -0.490295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2865.11914062, 2150.895, 177.228125), 'rotation':(-0.475952, -89.807098, -0.483917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.72363281, 2268.03609375, 178.10859375), 'rotation':(0.370326, 90.18988, 0.365564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.76928711, 2260.33421875, 178.05855469), 'rotation':(0.371883, 90.191963, 0.367082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.94628906, 2239.80789062, 177.92324219), 'rotation':(0.385202, 90.192062, 0.380066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.96484375, 2234.16382812, 177.88443359000001), 'rotation':(0.385202, 90.192062, 0.380066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.00195312, 2222.8728125, 177.80310547000002), 'rotation':(0.419524, 90.192719, 0.41342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.02050781, 2217.2275, 177.76037109), 'rotation':(0.435828, 90.191086, 0.429247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.03930664, 2211.58226562, 177.7165625), 'rotation':(0.435828, 90.191086, 0.429247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2857.05786133, 2205.93796875, 177.67183594), 'rotation':(0.452247, 90.193207, 0.445143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.93798828, 2205.96390625, 177.67183594), 'rotation':(-0.460327, -89.806274, -0.467773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.91943359, 2211.6081249999997, 177.7165625), 'rotation':(-0.452271, -89.808655, -0.459442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.88208008, 2222.89867188, 177.80310547000002), 'rotation':(-0.435822, -89.807037, -0.442505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.8449707, 2234.1896875, 177.88443359000001), 'rotation':(-0.403107, -89.807526, -0.408813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.79760742, 2249.0703125, 177.98480468999998), 'rotation':(-0.375732, -89.809937, -0.380707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.86303711, 2268.0625, 178.10859375), 'rotation':(-0.371887, -89.808044, -0.37674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2856.70825195, 2312.10226562, 178.38837891), 'rotation':(0.347984, 90.192223, 0.34379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.68969727, 2317.74242188, 178.4225), 'rotation':(0.342063, 90.190056, 0.337988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2856.65258789, 2329.02273438, 178.48955078), 'rotation':(0.335704, 90.18927, 0.331781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.6340332, 2334.6628124999997, 178.52269531000002), 'rotation':(0.328928, 90.190155, 0.325177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.57836914, 2351.58324219, 178.61908203), 'rotation':(0.315241, 90.189995, 0.311787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.55981445, 2357.22339844, 178.65003906), 'rotation':(0.308533, 90.189934, 0.305222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2856.52270508, 2368.50367188, 178.71046875), 'rotation':(0.305193, 90.191742, 0.301971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.62548828, 2300.8464062499997, 178.31869140999999), 'rotation':(-0.359741, -89.809723, -0.364288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.60693359, 2306.4870312499997, 178.35376953), 'rotation':(-0.359741, -89.809723, -0.364288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.58837891, 2312.1271875, 178.38835938), 'rotation':(-0.353821, -89.807709, -0.358215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.57006836, 2317.76757812, 178.4225), 'rotation':(-0.348022, -89.809875, -0.352264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.55151367, 2323.40773438, 178.45615234000002), 'rotation':(-0.342072, -89.809937, -0.346161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.53295898, 2329.04859375, 178.48955078), 'rotation':(-0.339081, -89.808838, -0.343109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.49584961, 2340.32859375, 178.55541015999998), 'rotation':(-0.335724, -89.808594, -0.339661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.47729492, 2345.9689843799997, 178.58751952999998), 'rotation':(-0.328918, -89.809814, -0.332733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2864.42163086, 2362.89015625, 178.68042968999998), 'rotation':(-0.308533, -89.810059, -0.311859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.375, 2332.1042187499997, 179.03287109000001), 'rotation':(0.526075, 90.452911, 0.51648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3374.50539062, 2315.47046875, 178.87863281000003), 'rotation':(0.532413, 90.453049, 0.522586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.54859375, 2309.92554688, 178.82693359), 'rotation':(0.534121, 90.452812, 0.524236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.63550781, 2298.83617188, 178.72367188), 'rotation':(0.533322, 90.452156, 0.52345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.67894531, 2293.29148438, 178.67207031), 'rotation':(0.533001, 90.454475, 0.523163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.8090625, 2276.6575000000003, 178.51753906000002), 'rotation':(0.531703, 90.452126, 0.521913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.89601562, 2265.568125, 178.41472656000002), 'rotation':(0.530829, 90.454437, 0.52106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3374.98265625, 2254.4778125000003, 178.31232422000002), 'rotation':(0.529114, 90.453415, 0.519414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3375.02613281, 2248.933125, 178.26154297000002), 'rotation':(0.526143, 90.453362, 0.516545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3375.1996875, 2226.75367188, 178.06117188), 'rotation':(0.513678, 90.453125, 0.504535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3383.16699219, 2215.71679688, 177.96259766), 'rotation':(-0.506134, -89.546478, -0.515167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3383.0803125, 2226.80664062, 178.06109375), 'rotation':(-0.510712, -89.546875, -0.519867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.6896875, 2276.7096874999997, 178.51746093999998), 'rotation':(-0.531403, -89.547882, -0.541351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3382.64625, 2282.25460938, 178.56894531), 'rotation':(-0.531677, -89.545532, -0.541626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.5158593799997, 2298.88867188, 178.72357422000002), 'rotation':(-0.53302, -89.547852, -0.542999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.2990625, 2326.61179688, 178.98154297000002), 'rotation':(-0.53241, -89.546936, -0.542389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.21214844, 2337.70070312, 179.08388672), 'rotation':(-0.529236, -89.546997, -0.539093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.16871094, 2343.24539062, 179.13480468999998), 'rotation':(-0.526093, -89.545654, -0.535828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3382.08203125, 2354.33472656, 179.23613281000002), 'rotation':(-0.522827, -89.547119, -0.53244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.03859375, 2359.87890625, 179.28662109), 'rotation':(-0.521271, -89.546326, -0.530823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3382.06957031, 2367.23167969, 179.35337891), 'rotation':(-0.519287, -89.548096, -0.528748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3371.61035156, 2685.38134766, 181.17951172000002), 'rotation':(0.028557, 90.446693, 0.028537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3371.69875, 2674.10253906, 181.17234375), 'rotation':(0.042224, 90.447563, 0.042171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3371.74292969, 2668.46191406, 181.16550781), 'rotation':(0.069641, 90.449806, 0.069474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.05152344, 2628.98363281, 181.07347656000002), 'rotation':(0.166363, 90.450401, 0.165402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.13988281, 2617.70460938, 181.03796875), 'rotation':(0.189087, 90.450539, 0.187853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.22828125, 2606.42480469, 180.99757812), 'rotation':(0.211989, 90.450691, 0.210428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.27246094, 2600.78492188, 180.97552734), 'rotation':(0.223443, 90.448097, 0.221701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.31664062, 2595.14550781, 180.95292969), 'rotation':(0.229057, 90.450401, 0.227227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.36085938, 2589.50511719, 180.92966797), 'rotation':(0.234433, 90.447968, 0.232539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.49292969, 2572.5859375, 180.85310547), 'rotation':(0.266418, 90.450951, 0.26395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.53710938, 2566.9455468799997, 180.8253125), 'rotation':(0.28779, 90.451164, 0.28492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.62546875, 2555.66527344, 180.76634765999998), 'rotation':(0.308984, 90.448677, 0.305677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.66945312, 2550.02585938, 180.73554688000002), 'rotation':(0.314414, 90.450188, 0.310984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.71363281, 2544.38625, 180.70425781000003), 'rotation':(0.314414, 90.450188, 0.310984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.7578125, 2538.745625, 180.67244141), 'rotation':(0.323205, 90.451195, 0.31957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.80199219, 2533.1059375, 180.63941406), 'rotation':(0.323205, 90.451195, 0.31957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3372.84617188, 2527.46507812, 180.60585938), 'rotation':(0.340956, 90.449951, 0.336922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3372.93433594, 2516.18675781, 180.53476562), 'rotation':(0.358605, 90.450157, 0.354132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.02246094, 2504.9064843799997, 180.46017578), 'rotation':(0.376166, 90.451851, 0.371241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.11085938, 2493.62671875, 180.38361328), 'rotation':(0.389068, 90.451256, 0.383805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3373.15503906, 2487.9865625, 180.34423827999998), 'rotation':(0.397107, 90.451363, 0.391628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.19898438, 2482.34667969, 180.3040625), 'rotation':(0.404948, 90.451447, 0.399263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.24316406, 2476.70777344, 180.26304688), 'rotation':(0.420692, 90.451668, 0.414542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.28710938, 2471.06789062, 180.22119141), 'rotation':(0.428902, 90.451813, 0.422531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.4196875, 2454.14796875, 180.09099609), 'rotation':(0.444604, 90.452034, 0.437763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.55226562, 2437.22851562, 179.95697266), 'rotation':(0.453887, 90.451759, 0.446738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.59617188, 2431.58835938, 179.91123047000002), 'rotation':(0.464548, 90.45195, 0.457066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3373.6403906200003, 2425.94800781, 179.86443359), 'rotation':(0.475074, 90.45211, 0.467261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.68457031, 2420.308125, 179.81712890999998), 'rotation':(0.475074, 90.45211, 0.467261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3373.81566406, 2403.55273438, 179.67400390999998), 'rotation':(0.491015, 90.452057, 0.482666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.65332031, 2409.08082031, 179.72085938), 'rotation':(-0.491028, -89.545441, -0.499512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.56519531, 2420.36058594, 179.81705078), 'rotation':(-0.485748, -89.547699, -0.494049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3381.52101562, 2426.00046875, 179.86435547000002), 'rotation':(-0.485748, -89.547699, -0.494049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3381.43261719, 2437.2810156200003, 179.95689453), 'rotation':(-0.464539, -89.548065, -0.472137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.3884375, 2442.92089844, 180.00208984), 'rotation':(-0.464539, -89.548065, -0.472137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.21191406, 2465.48070312, 180.17847656), 'rotation':(-0.444641, -89.547974, -0.451569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3381.07960938, 2482.400625, 180.30400391), 'rotation':(-0.412811, -89.548401, -0.418793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.99144531, 2493.68089844, 180.38355468999998), 'rotation':(-0.397095, -89.548645, -0.402649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.85890625, 2510.60082031, 180.49767577999998), 'rotation':(-0.385101, -89.547668, -0.390289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.7263281200003, 2527.52027344, 180.60582031), 'rotation':(-0.358612, -89.54837, -0.363098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.68238281, 2533.16136719, 180.63939453), 'rotation':(-0.340942, -89.550049, -0.345032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.6384375, 2538.80101562, 180.67240234000002), 'rotation':(-0.340942, -89.550049, -0.345032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.50609375, 2555.72144531, 180.76630859), 'rotation':(-0.314423, -89.549805, -0.317871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.46191406, 2561.36179688, 180.79636718999998), 'rotation':(-0.30899, -89.548615, -0.312347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3380.4175, 2567.00171875, 180.82529297000002), 'rotation':(-0.298401, -89.548737, -0.301514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.37328125, 2572.64210938, 180.85306641), 'rotation':(-0.277008, -89.54895, -0.279724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.19652344, 2595.20238281, 180.95291016), 'rotation':(-0.234436, -89.549316, -0.236359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.15234375, 2600.84226562, 180.97550781), 'rotation':(-0.229065, -89.549591, -0.230896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3380.10816406, 2606.48265625, 180.99755859), 'rotation':(-0.22345, -89.55191, -0.225189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.97582031, 2623.40210938, 181.05632812), 'rotation':(-0.189087, -89.552155, -0.190338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3379.88769531, 2634.68261719, 181.08945312), 'rotation':(-0.166351, -89.552277, -0.167328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.66675781, 2662.88328125, 181.15626953), 'rotation':(-0.124207, -89.552216, -0.124725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.57859375, 2674.16308594, 181.17234375), 'rotation':(-0.069641, -89.552399, -0.069824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.53441406, 2679.80296875, 181.17652343999998), 'rotation':(-0.042236, -89.550232, -0.042297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.49023438, 2685.443125, 181.17951172000002), 'rotation':(-0.028564, -89.553284, -0.028595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3379.44628906, 2691.08349609, 181.18234375), 'rotation':(-0.028564, -89.55072, -0.028595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3379.40210938, 2696.724375, 181.18515625), 'rotation':(-0.028717, -89.55069, -0.028748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.21507812, 2756.79736328, 183.73201172), 'rotation':(0.138994, 90.200233, 0.138324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.23486328, 2751.13476562, 183.71775391), 'rotation':(0.14523, 90.198875, 0.144497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.25439453, 2745.47167969, 183.70238281000002), 'rotation':(0.15749, 90.198959, 0.156626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.27417969, 2739.80859375, 183.68574218999998), 'rotation':(0.169566, 90.199028, 0.168584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.29371094, 2734.14550781, 183.66785156000003), 'rotation':(0.181984, 90.199104, 0.180838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.33300781, 2722.82128906, 183.62833984), 'rotation':(0.206326, 90.199265, 0.204853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.39208984, 2705.83349609, 183.55982422), 'rotation':(0.241249, 90.198051, 0.239236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.41162109, 2700.17041016, 183.53494141), 'rotation':(0.249848, 90.200836, 0.247689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.4509375, 2688.84521484, 183.48246093999998), 'rotation':(0.266726, 90.200989, 0.264251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.47070312, 2683.18212891, 183.45484375), 'rotation':(0.283617, 90.198463, 0.280812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.49023438, 2677.51904297, 183.42632812), 'rotation':(0.292032, 90.201233, 0.289068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.51, 2671.8559375, 183.39689453), 'rotation':(0.300638, 90.201324, 0.297497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.52953125, 2666.19335938, 183.366875), 'rotation':(0.304879, 90.200661, 0.301649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.58837891, 2649.20507812, 183.27177734), 'rotation':(0.331018, 90.200218, 0.327211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.62769531, 2637.88039062, 183.20357422), 'rotation':(0.348401, 90.201881, 0.344182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.66675781, 2626.55515625, 183.13113281000003), 'rotation':(0.365962, 90.20063, 0.361331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.78466797, 2592.57933594, 182.89625), 'rotation':(0.414948, 90.202003, 0.408971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.80445312, 2586.91625, 182.85363281000002), 'rotation':(0.431053, 90.202225, 0.424608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.82398438, 2581.25390625, 182.81083984), 'rotation':(0.431053, 90.202225, 0.424608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.84375, 2575.59226562, 182.76712891), 'rotation':(0.439229, 90.203537, 0.432541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.86351562, 2569.92921875, 182.72298827999998), 'rotation':(0.446271, 90.201752, 0.439361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.88304688, 2564.26636719, 182.67789062), 'rotation':(0.446271, 90.201752, 0.439361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.92236328, 2552.94042969, 182.58550781000002), 'rotation':(0.474835, 90.203621, 0.467012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.94189453, 2547.2778125, 182.53830078), 'rotation':(0.474835, 90.203621, 0.467012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3200.96142578, 2541.61449219, 182.48994141), 'rotation':(0.489151, 90.202454, 0.480861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3200.98095703, 2535.9533593799997, 182.44130859), 'rotation':(0.489151, 90.202454, 0.480861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.04003906, 2518.96558594, 182.29193359), 'rotation':(0.502572, 90.202499, 0.493819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.05957031, 2513.30320312, 182.24091797), 'rotation':(0.514723, 90.204285, 0.505551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.11865234, 2496.31445312, 182.08271484), 'rotation':(0.539489, 90.204735, 0.529401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.15771484, 2484.99171875, 181.97478515999998), 'rotation':(0.545602, 90.204613, 0.53528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.21679688, 2468.00316406, 181.80966797000002), 'rotation':(0.560137, 90.204391, 0.549256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.23632812, 2462.3403125, 181.75333984), 'rotation':(0.569665, 90.204575, 0.558424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3201.275625, 2451.0158593799997, 181.63882812), 'rotation':(0.579241, 90.204758, 0.567617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.31494141, 2439.6909375, 181.52302734), 'rotation':(0.583981, 90.20401, 0.572174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.35400391, 2428.36546875, 181.40572265999998), 'rotation':(0.597157, 90.204842, 0.584829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.39332031, 2417.03980469, 181.28644531), 'rotation':(0.605913, 90.205017, 0.593199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.41308594, 2411.37742188, 181.2259375), 'rotation':(0.605913, 90.205017, 0.593199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3201.45238281, 2400.05273438, 181.10396484), 'rotation':(0.619013, 90.204346, 0.605748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.31371094, 2405.71972656, 181.16492188), 'rotation':(-0.619019, -89.795654, -0.632507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.27417969, 2417.04394531, 181.28619141), 'rotation':(-0.614594, -89.793304, -0.627899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.17601562, 2445.35765625, 181.58085938), 'rotation':(-0.588409, -89.795349, -0.600586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.13671875, 2456.683125, 181.69603515999998), 'rotation':(-0.583984, -89.79599, -0.595978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.1171875, 2462.3459375, 181.753125), 'rotation':(-0.579254, -89.795227, -0.591034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.09765625, 2468.00878906, 181.80943359), 'rotation':(-0.569672, -89.79541, -0.581085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.05835938, 2479.33421875, 181.92015625), 'rotation':(-0.56012, -89.795593, -0.571167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3209.01904297, 2490.6596875, 182.02859375), 'rotation':(-0.545593, -89.79538, -0.556061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.95996094, 2507.64796875, 182.18863281000003), 'rotation':(-0.53949, -89.796844, -0.549713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.94042969, 2513.31078125, 182.24074219), 'rotation':(-0.527222, -89.795471, -0.536987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.90113281, 2524.63648438, 182.34226562), 'rotation':(-0.514771, -89.797272, -0.524048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.86181641, 2535.96214844, 182.44115234), 'rotation':(-0.496185, -89.798584, -0.504852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.84228516, 2541.62453125, 182.48978516), 'rotation':(-0.496185, -89.798584, -0.504852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.80296875, 2552.95019531, 182.58535156000002), 'rotation':(-0.489166, -89.796112, -0.497559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.78296875, 2558.61304688, 182.63222656000002), 'rotation':(-0.474854, -89.797791, -0.482758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.66503906, 2592.59058594, 182.89613281), 'rotation':(-0.431061, -89.79776, -0.437592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.56689453, 2620.90503906, 183.09376953), 'rotation':(-0.382721, -89.798462, -0.387878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.52978516, 2632.23121094, 183.16744140999998), 'rotation':(-0.374603, -89.799988, -0.379517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.37451172, 2671.87257812, 183.39683594), 'rotation':(-0.304871, -89.799316, -0.308105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.30273438, 2688.86207031, 183.48238281000002), 'rotation':(-0.275177, -89.801605, -0.277832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.2790625, 2694.52490234, 183.50910156), 'rotation':(-0.266724, -89.798981, -0.269226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.23925781, 2705.8515625, 183.55978516), 'rotation':(-0.249878, -89.801849, -0.252045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3208.21972656, 2711.51441406, 183.58375), 'rotation':(-0.241272, -89.799225, -0.243286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.19996094, 2717.17773438, 183.60666016), 'rotation':(-0.230835, -89.800537, -0.232697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.18017578, 2722.84082031, 183.62832031000002), 'rotation':(-0.21875, -89.800629, -0.220398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.16064453, 2728.50341797, 183.64869141), 'rotation':(-0.206329, -89.80072, -0.207825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3208.08203125, 2751.15601562, 183.71773438), 'rotation':(-0.157501, -89.798492, -0.158356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3061.81616211, 2007.62710938, 176.75921875), 'rotation':(-0.582153, -89.216187, -0.594055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3061.6784668, 2017.76828125, 176.86236327999998), 'rotation':(-0.582397, -89.216675, -0.59433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3061.60961914, 2022.83898438, 176.91396484), 'rotation':(-0.582855, -89.215088, -0.594818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3061.54077148, 2027.9096875, 176.96556640999998), 'rotation':(-0.582855, -89.215088, -0.594818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3061.42749023, 2038.04929688, 177.06880859), 'rotation':(-0.583496, -89.215393, -0.595459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.89135742, 2075.6965625000003, 177.45378906000002), 'rotation':(-0.588715, -89.216187, -0.600891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.73974609, 2086.848125, 177.56839843999998), 'rotation':(-0.588745, -89.216095, -0.600952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.58813477, 2097.99976562, 177.68304688), 'rotation':(-0.589294, -89.217163, -0.601532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.51245117, 2103.57570312, 177.74050781000003), 'rotation':(-0.590607, -89.214539, -0.602875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3060.43676758, 2109.15140625, 177.79808594), 'rotation':(-0.591766, -89.214539, -0.604065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.36108398, 2114.7275, 177.85578125), 'rotation':(-0.592896, -89.217133, -0.605255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.28515625, 2120.30320312, 177.91355468999998), 'rotation':(-0.593597, -89.214935, -0.606018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.20947266, 2125.87914062, 177.97134766), 'rotation':(-0.593597, -89.214935, -0.606018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3060.13378906, 2131.45507812, 178.02912109000002), 'rotation':(-0.593506, -89.214935, -0.605896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3059.90625, 2148.1823437499997, 178.20246093999998), 'rotation':(-0.593506, -89.216675, -0.605896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3059.83032227, 2153.75828125, 178.26017578), 'rotation':(-0.593384, -89.213287, -0.605743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3059.75463867, 2159.33398438, 178.31789062), 'rotation':(-0.592896, -89.215515, -0.605255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3059.67895508, 2164.90992188, 178.37560547), 'rotation':(-0.592896, -89.215515, -0.605255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2451.08105469, 2050.0246875000003, 169.21173828), 'rotation':(-1.642456, -179.273926, -1.73877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2439.74511719, 2049.89039062, 168.88509765999999), 'rotation':(-1.669769, -179.273193, -1.769379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2417.06859375, 2049.62179688, 168.21298828), 'rotation':(-1.711243, -179.271027, -1.815887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2411.40039062, 2049.55492188, 168.04328125), 'rotation':(-1.723267, -179.269318, -1.829437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2400.06203125, 2049.4209375, 167.70033203), 'rotation':(-1.747345, -179.268707, -1.856537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2394.39648438, 2049.35375, 167.52703125), 'rotation':(-1.771515, -179.267181, -1.883789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2388.7267968799997, 2049.28664062, 167.35150391), 'rotation':(-1.795746, -179.264862, -1.911133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2383.05859375, 2049.21945312, 167.17457031), 'rotation':(-1.795746, -179.264862, -1.911133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2377.39136719, 2049.15234375, 166.99662109000002), 'rotation':(-1.807709, -179.264786, -1.924683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2366.05296875, 2049.01804688, 166.63839843999997), 'rotation':(-1.807709, -179.264786, -1.924683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2360.38378906, 2048.95117188, 166.45925781000003), 'rotation':(-1.807709, -179.264786, -1.924683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2337.71390625, 2048.6823437499997, 165.73414062), 'rotation':(-1.858643, -179.261185, -1.982391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2303.70289062, 2048.2799999999997, 164.62736328), 'rotation':(-1.871155, -179.260849, -1.996582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2269.69289062, 2047.87757812, 163.50921875), 'rotation':(-1.887238, -179.259338, -2.014862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2264.02414062, 2047.81039062, 163.3222168), 'rotation':(-1.887146, -179.259384, -2.014771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2247.01539062, 2047.60898438, 162.76258789), 'rotation':(-1.872192, -179.260269, -1.997803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2235.67773438, 2047.47476562, 162.39154297), 'rotation':(-1.872192, -179.260269, -1.997803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2224.3403125, 2047.3405468800001, 162.02052734), 'rotation':(-1.872253, -179.261154, -1.997864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2229.69945312, 2055.29, 162.19895508), 'rotation':(1.872257, 0.740657, 1.752699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2235.36890625, 2055.35375, 162.38449219), 'rotation':(1.872209, 0.738809, 1.752649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2241.03734375, 2055.4209375, 162.56999023), 'rotation':(1.872209, 0.738809, 1.752649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2275.0495312499997, 2055.82375, 163.68899414), 'rotation':(1.887229, 0.740648, 1.765762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2303.3918750000003, 2056.1262500000003, 164.62023438), 'rotation':(1.86736, 0.740166, 1.748409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2314.72875, 2056.2604687499997, 164.99019531000002), 'rotation':(1.860298, 0.739702, 1.742233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2320.3971874999997, 2056.32765625, 165.17460938), 'rotation':(1.858542, 0.738794, 1.7407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2326.06617188, 2056.39476562, 165.35878906000002), 'rotation':(1.858542, 0.738794, 1.7407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2331.73460938, 2056.46164062, 165.54292969), 'rotation':(1.858583, 0.738777, 1.740745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2337.4035937500003, 2056.52882812, 165.72708984000002), 'rotation':(1.845824, 0.73761, 1.729562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2354.40894531, 2056.72976562, 166.27322266), 'rotation':(1.807705, 0.73397, 1.696163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2360.07859375, 2056.796875, 166.45255859), 'rotation':(1.80763, 0.736425, 1.69609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2365.7478125, 2056.86398438, 166.63167968999997), 'rotation':(1.807712, 0.736458, 1.696163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2377.0857031200003, 2056.99828125, 166.98990234000001), 'rotation':(1.795732, 0.735132, 1.685651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2399.76414062, 2057.2665625, 167.69408203), 'rotation':(1.723277, 0.730672, 1.621799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2405.43285156, 2057.33375, 167.86638672), 'rotation':(1.723277, 0.730672, 1.621799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2416.77296875, 2057.46804688, 168.20691406000003), 'rotation':(1.711215, 0.728976, 1.611142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2428.11351562, 2057.60226562, 168.54548828), 'rotation':(1.697438, 0.729266, 1.598951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2433.78320312, 2057.66945312, 168.71367188), 'rotation':(1.669817, 0.727655, 1.574484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2445.12546875, 2057.80375, 169.04355468999998), 'rotation':(1.642455, 0.724395, 1.550194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2456.464375, 2057.93796875, 169.36625), 'rotation':(1.60101, 0.721758, 1.513298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2505.80371094, 2058.5546875, 170.70382812), 'rotation':(1.460294, 0.71602, 1.387201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2527.99121094, 2058.81734375, 171.26505859), 'rotation':(1.396937, 0.712501, 1.330008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2539.0825, 2058.94851562, 171.53591797), 'rotation':(1.361735, 0.710823, 1.298107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2555.72507812, 2059.14523438, 171.92439453), 'rotation':(1.308719, 0.708125, 1.249909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2561.2736718799997, 2059.2109375, 172.05123047), 'rotation':(1.308794, 0.708106, 1.249977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2577.91699219, 2059.40773438, 172.42728516), 'rotation':(1.249091, 0.70554, 1.195484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2583.46582031, 2059.47335938, 172.54833984), 'rotation':(1.209387, 0.703833, 1.159099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2600.10863281, 2059.6706249999997, 172.89609375), 'rotation':(1.149678, 0.701226, 1.104208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2611.20460938, 2059.8020312500003, 173.119375), 'rotation':(1.133914, 0.700333, 1.089664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2633.39671875, 2060.16601562, 173.54740234000002), 'rotation':(1.03894, 0.696726, 1.001754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2505.90039062, 2050.67359375, 170.70390625), 'rotation':(-1.481079, -179.285263, -1.559235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2522.53980469, 2050.870625, 171.12632812), 'rotation':(-1.449951, -179.285233, -1.524811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2544.72730469, 2051.13304688, 171.66796875), 'rotation':(-1.361694, -179.289185, -1.427643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2550.27464844, 2051.19875, 171.79683594), 'rotation':(-1.326447, -179.290863, -1.388977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2555.82128906, 2051.2643749999997, 171.92447266), 'rotation':(-1.326447, -179.290863, -1.388977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2578.01320312, 2051.52710938, 172.42734375), 'rotation':(-1.288818, -179.292709, -1.347839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2583.5622656200003, 2051.59304688, 172.54841797), 'rotation':(-1.249084, -179.294449, -1.304504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2589.10789062, 2051.6584375, 172.66650391), 'rotation':(-1.249084, -179.294449, -1.304504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2594.65550781, 2051.724375, 172.78277343999997), 'rotation':(-1.209381, -179.296158, -1.261292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2600.20484375, 2051.79, 172.89613281), 'rotation':(-1.169556, -179.297821, -1.218079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2605.75269531, 2051.85570312, 173.00804688), 'rotation':(-1.169556, -179.297821, -1.218079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2616.85007812, 2051.9870312499997, 173.22931641), 'rotation':(-1.133911, -179.299667, -1.179504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2628.67796875, 2052.10328125, 173.45742188), 'rotation':(-1.102203, -179.300888, -1.145264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2837.83203125, 2062.48390625, 176.22111328), 'rotation':(0.458982, 0.681275, 0.451676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2815.64867188, 2062.22117188, 176.02830078), 'rotation':(0.518077, 0.682251, 0.508762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2810.10253906, 2062.15554688, 175.97634766), 'rotation':(0.532864, 0.68255, 0.523032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2799.01123047, 2062.02414062, 175.86820312), 'rotation':(0.562384, 0.685742, 0.551434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2793.46410156, 2061.95851562, 175.81302734000002), 'rotation':(0.569665, 0.683418, 0.558433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2782.37328125, 2061.8271875, 175.69947266), 'rotation':(0.584794, 0.684051, 0.572935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2776.82691406, 2061.76171875, 175.63992188), 'rotation':(0.615099, 0.684681, 0.602005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2771.28369141, 2061.69601562, 175.57851562), 'rotation':(0.615099, 0.684681, 0.602005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2765.73828125, 2061.63039062, 175.51580077999998), 'rotation':(0.645419, 0.685349, 0.630999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2749.10058594, 2061.43359375, 175.31734375), 'rotation':(0.690846, 0.686877, 0.674334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2732.46558594, 2061.2365625, 175.10884765999998), 'rotation':(0.737339, 0.688211, 0.718537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2721.37792969, 2061.10523438, 174.96041015999998), 'rotation':(0.774823, 0.689202, 0.754065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2715.83226562, 2061.03953125, 174.88335938), 'rotation':(0.793463, 0.689709, 0.771723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2710.286875, 2060.97414062, 174.80445312), 'rotation':(0.81213, 0.69023, 0.789354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2704.74292969, 2060.9084375, 174.72384766), 'rotation':(0.830947, 0.690773, 0.807104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2699.19703125, 2060.84328125, 174.64248047), 'rotation':(0.8401, 0.688545, 0.81573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2682.56273438, 2060.64648438, 174.39146484), 'rotation':(0.89345, 0.692002, 0.865902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2677.02246094, 2060.5807812499997, 174.30318359), 'rotation':(0.89345, 0.692002, 0.865902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2837.92358398, 2054.60375, 176.22109375), 'rotation':(-0.473755, -179.315826, -0.481659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2832.37769531, 2054.538125, 176.17513672), 'rotation':(-0.488373, -179.318237, -0.496765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2821.286875, 2054.40671875, 176.07875), 'rotation':(-0.518097, -179.317734, -0.527527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2810.19410156, 2054.27539062, 175.97632812), 'rotation':(-0.547455, -179.3172, -0.557983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2804.64794922, 2054.2096874999997, 175.92287109), 'rotation':(-0.562408, -179.316879, -0.573547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2754.73828125, 2053.61914062, 175.38421875), 'rotation':(-0.690857, -179.313095, -0.707672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2749.19164062, 2053.55320312, 175.31732422000002), 'rotation':(-0.700165, -179.315384, -0.717438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2738.10107422, 2053.42210938, 175.18017577999998), 'rotation':(-0.737335, -179.311768, -0.7565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2727.01390625, 2053.29078125, 175.03554688), 'rotation':(-0.774811, -179.310791, -0.79599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2715.92236328, 2053.15945312, 174.88332031000002), 'rotation':(-0.812134, -179.312393, -0.835419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2704.83300781, 2053.0285937500003, 174.72378906000003), 'rotation':(-0.840118, -179.308823, -0.865021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2699.28710938, 2052.96289062, 174.64244141), 'rotation':(-0.840271, -179.308823, -0.865204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2682.65257812, 2052.76585938, 174.39140625), 'rotation':(-0.929077, -179.306885, -0.959595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2677.11207031, 2052.70015625, 174.303125), 'rotation':(-0.929077, -179.306885, -0.959595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2892.50708008, 2063.13109375, 176.61798828), 'rotation':(0.357834, 0.680114, 0.353384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2903.60375977, 2063.2621875, 176.68726562), 'rotation':(0.347124, 0.67998, 0.342935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2909.15234375, 2063.32789062, 176.72041016), 'rotation':(0.336571, 0.679853, 0.332638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2920.24780273, 2063.45921875, 176.78345703), 'rotation':(0.304592, 0.6795, 0.30136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2936.89355469, 2063.65648438, 176.86986328), 'rotation':(0.277866, 0.678102, 0.275187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2964.63549805, 2063.98460938, 177.00082031000002), 'rotation':(0.242718, 0.678424, 0.240669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2970.18359375, 2064.0503125, 177.02447266), 'rotation':(0.228572, 0.680086, 0.226754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2981.2800293, 2064.18164062, 177.06949218999998), 'rotation':(0.221592, 0.678472, 0.219889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2992.37719727, 2064.31296875, 177.11191406), 'rotation':(0.207727, 0.67911, 0.20622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2997.92602539, 2064.37867188, 177.13208984000002), 'rotation':(0.198513, 0.679069, 0.197148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3009.0234375, 2064.51, 177.17001953), 'rotation':(0.179934, 0.678945, 0.178819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3020.11962891, 2064.64132812, 177.20476562), 'rotation':(0.170727, 0.678888, 0.169715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3025.66845703, 2064.70703125, 177.2209375), 'rotation':(0.161513, 0.678811, 0.160594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3036.76367188, 2064.85375, 177.25099609), 'rotation':(0.147607, 0.677144, 0.146842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3042.31030273, 2065.00757812, 177.26529297000002), 'rotation':(0.147689, 0.678775, 0.146941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3039.16577148, 2056.93382812, 177.25693359000002), 'rotation':(-0.152283, -179.321228, -0.153107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3031.3112793, 2056.8928125, 177.23632812), 'rotation':(-0.161499, -179.321152, -0.162415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3025.76245117, 2056.8268749999997, 177.2209375), 'rotation':(-0.170715, -179.321106, -0.171753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3003.56933594, 2056.56421875, 177.15146484000002), 'rotation':(-0.198517, -179.320953, -0.19989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2998.02050781, 2056.49851562, 177.13208984000002), 'rotation':(-0.207733, -179.320862, -0.209259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2981.37475586, 2056.30148438, 177.06949218999998), 'rotation':(-0.228577, -179.321671, -0.230408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2970.27856445, 2056.17015625, 177.02447266), 'rotation':(-0.242737, -179.319794, -0.244781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2942.53662109, 2055.84179688, 176.896875), 'rotation':(-0.277863, -179.319427, -0.280548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2936.98876953, 2055.77640625, 176.86986328), 'rotation':(-0.283173, -179.320724, -0.28598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2931.44018555, 2055.71070312, 176.84216797000002), 'rotation':(-0.293884, -179.320602, -0.296906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2925.89160156, 2055.645, 176.81337890999998), 'rotation':(-0.304596, -179.320496, -0.307861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2920.34326172, 2055.5793750000003, 176.78347656000003), 'rotation':(-0.315155, -179.320389, -0.318604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2898.15087891, 2055.31664062, 176.65300781000002), 'rotation':(-0.363159, -179.318527, -0.367798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2892.60327148, 2055.2509375, 176.61800781000002), 'rotation':(-0.363159, -179.318527, -0.367798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2883.88427734, 2055.0676562500003, 176.56203125), 'rotation':(-0.389984, -179.318817, -0.395294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2446.98511719, 2286.75296875, 170.06927734), 'rotation':(1.632552, 0.537204, 1.541386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2435.74730469, 2286.65671875, 169.74677734), 'rotation':(1.632511, 0.535753, 1.541354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2424.50953125, 2286.56078125, 169.41316406), 'rotation':(1.728256, 0.542968, 1.626198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2418.89671875, 2286.51265625, 169.24019531000002), 'rotation':(1.728256, 0.542968, 1.626198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.27929688, 2286.46460938, 169.06414062), 'rotation':(1.79205, 0.545262, 1.682399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2396.42652344, 2286.32078125, 168.5128125), 'rotation':(1.887919, 0.551423, 1.766366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.95042969, 2286.1284375, 167.77076172), 'rotation':(1.889169, 0.553898, 1.767469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2362.71265625, 2286.0321875, 167.39957031000003), 'rotation':(1.889701, 0.551543, 1.767909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2351.47460938, 2285.9362499999997, 167.02822265999998), 'rotation':(1.890583, 0.5516, 1.768685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2323.38375, 2285.69625, 166.09291016), 'rotation':(1.922056, 0.555238, 1.796113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2317.76609375, 2285.64820312, 165.90378906), 'rotation':(1.926646, 0.554917, 1.80011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2312.1475, 2285.60007812, 165.71455078), 'rotation':(1.926557, 0.554884, 1.800041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2300.9114062500003, 2285.50390625, 165.33558594), 'rotation':(1.930867, 0.555416, 1.803792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2289.6740625, 2285.40796875, 164.95539062), 'rotation':(1.936522, 0.555802, 1.808697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2284.055625, 2285.35984375, 164.76486328), 'rotation':(1.939432, 0.555998, 1.811224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2278.43703125, 2285.31179688, 164.57404297000002), 'rotation':(1.942164, 0.556184, 1.81361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2244.72507812, 2285.02320312, 163.42751953), 'rotation':(1.941952, 0.556793, 1.813428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2239.1067187500003, 2284.9753124999997, 163.23728516), 'rotation':(1.937151, 0.556472, 1.809241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2233.48804688, 2284.92726562, 163.04744141), 'rotation':(1.932131, 0.554413, 1.804881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2222.2487499999997, 2284.83109375, 162.66818359), 'rotation':(1.929761, 0.555528, 1.802816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2222.14625, 2276.94726562, 162.66244140999999), 'rotation':(-1.929688, -179.444489, -2.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2227.76515625, 2276.99539062, 162.85199219), 'rotation':(-1.929688, -179.444489, -2.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2244.62179688, 2277.1396875, 163.42173828), 'rotation':(-1.937164, -179.443512, -2.071716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2255.85960938, 2277.23585938, 163.80313476999999), 'rotation':(-1.941956, -179.444916, -2.077209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2278.33398438, 2277.42820312, 164.56824218999998), 'rotation':(-1.945068, -179.443619, -2.08075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2300.80835938, 2277.62039062, 165.32982422), 'rotation':(-1.933807, -179.444366, -2.067871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2306.4270312500003, 2277.66820312, 165.51949219), 'rotation':(-1.930878, -179.444595, -2.064575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2317.66429688, 2277.7643749999997, 165.89810547000002), 'rotation':(-1.926575, -179.445114, -2.059631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2323.28296875, 2277.80640625, 166.08726562), 'rotation':(-1.926575, -179.445114, -2.059631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2334.51953125, 2277.94140625, 166.46384766), 'rotation':(-1.913116, -179.447723, -2.044312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2351.37597656, 2278.0859375, 167.02275391), 'rotation':(-1.890533, -179.447372, -2.018616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2356.99488281, 2278.1340625000003, 167.2084375), 'rotation':(-1.890656, -179.445999, -2.018768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2362.61402344, 2278.18210938, 167.39408203), 'rotation':(-1.890137, -179.448425, -2.018188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2373.8517968799997, 2278.27804688, 167.7653125), 'rotation':(-1.889771, -179.44606, -2.017761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2401.94703125, 2278.51859375, 168.69277344), 'rotation':(-1.887787, -179.446518, -2.015503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2413.18675781, 2278.61476562, 169.05898438), 'rotation':(-1.855927, -179.449005, -1.979309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2430.04835938, 2278.7590625000003, 169.57837891), 'rotation':(-1.728241, -179.457031, -1.835022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2441.2888281200003, 2278.855, 169.90486328), 'rotation':(-1.66449, -179.4608, -1.763458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2446.90941406, 2278.90328125, 170.06519531), 'rotation':(-1.632507, -179.464249, -1.727661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2485.24953125, 2287.08007812, 171.16076172), 'rotation':(1.616064, 0.536299, 1.526723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2490.77613281, 2287.12742188, 171.31681641), 'rotation':(1.583108, 0.534449, 1.497337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2518.4138281200003, 2287.36375, 172.07386719), 'rotation':(1.517238, 0.530881, 1.438391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2523.943125, 2287.41109375, 172.22044922), 'rotation':(1.490839, 0.527709, 1.414685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2540.52710938, 2287.55296875, 172.64837891), 'rotation':(1.460609, 0.528072, 1.38749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2546.05640625, 2287.6003124999997, 172.78945312), 'rotation':(1.438547, 0.525321, 1.367596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2562.64183594, 2287.743125, 173.20144531000003), 'rotation':(1.369063, 0.527222, 1.304765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2568.16992188, 2287.7903125000003, 173.33494141), 'rotation':(1.366577, 0.522246, 1.3025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2573.6996875, 2287.84523438, 173.46693359), 'rotation':(1.352377, 0.522981, 1.289613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2584.7578125, 2287.89820312, 173.72808593999997), 'rotation':(1.323991, 0.519849, 1.263827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2595.81714844, 2287.99265625, 173.98162109), 'rotation':(1.267485, 0.517289, 1.212292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2606.87648438, 2288.08742188, 174.22802734), 'rotation':(1.24388, 0.517087, 1.190719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2617.93554688, 2288.181875, 174.46603516), 'rotation':(1.206648, 0.515497, 1.156588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2623.46558594, 2288.22898438, 174.58214843999997), 'rotation':(1.187975, 0.514692, 1.139441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2629.1171875, 2280.42898438, 174.69769531000003), 'rotation':(-1.188019, -179.485291, -1.238098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2612.52832031, 2280.28710938, 174.34916016), 'rotation':(-1.243835, -179.482941, -1.298767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2606.99851562, 2280.24, 174.22921875), 'rotation':(-1.267517, -179.480881, -1.324585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2590.41453125, 2280.098125, 173.85734375), 'rotation':(-1.324036, -179.478317, -1.386353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2579.35570312, 2280.0034375, 173.59949218999998), 'rotation':(-1.366547, -179.476181, -1.432953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2573.82765625, 2279.95609375, 173.46837890999998), 'rotation':(-1.366547, -179.476181, -1.432953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2562.77101562, 2279.86132812, 173.20294922000002), 'rotation':(-1.394501, -179.475388, -1.463684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2557.24144531, 2279.81398438, 173.06826172), 'rotation':(-1.438538, -179.47319, -1.512238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2546.18703125, 2279.71921875, 172.79105468999998), 'rotation':(-1.460602, -179.47467, -1.536591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2540.65746094, 2279.67210938, 172.64998047), 'rotation':(-1.460785, -179.471909, -1.536774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2501.9665625, 2279.34132812, 171.62699218999998), 'rotation':(-1.583099, -179.46698, -1.672516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2485.38429688, 2279.19945312, 171.16267578), 'rotation':(-1.632538, -179.46347, -1.727692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2845.1472168, 2290.15796875, 178.058125), 'rotation':(0.616131, 0.497363, 0.602982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2834.02125, 2290.06273438, 177.93708984), 'rotation':(0.625215, 0.497099, 0.611676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2828.45703125, 2290.01539062, 177.87457031000002), 'rotation':(0.643534, 0.49752, 0.629201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2811.76953125, 2289.87257812, 177.67808594), 'rotation':(0.679993, 0.498367, 0.663997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2795.08154297, 2289.72976562, 177.46900391), 'rotation':(0.732121, 0.503517, 0.713587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2789.51757812, 2289.68210938, 177.39691406000003), 'rotation':(0.742223, 0.49892, 0.723173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2783.95433594, 2289.63453125, 177.32316406), 'rotation':(0.762591, 0.501206, 0.742496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2772.82958984, 2289.53929688, 177.17230468999998), 'rotation':(0.782856, 0.500001, 0.761678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2733.88916016, 2289.20632812, 176.60980468999998), 'rotation':(0.841472, 0.501748, 0.817015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2728.32542969, 2289.1589062499997, 176.52742188), 'rotation':(0.848057, 0.503369, 0.823225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2711.63623047, 2289.01609375, 176.27851562), 'rotation':(0.859258, 0.501737, 0.833764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2706.07666016, 2288.96851562, 176.19251953), 'rotation':(0.859258, 0.501737, 0.833764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.5134375, 2288.9206249999997, 176.10519531000003), 'rotation':(0.899106, 0.50534, 0.871216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2678.28636719, 2288.7309375, 175.70595702999998), 'rotation':(1.058802, 0.509366, 1.020197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2672.72363281, 2288.68359375, 175.5953125), 'rotation':(1.138668, 0.513866, 1.09407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2667.16578125, 2288.63601562, 175.48224609000002), 'rotation':(1.138668, 0.513866, 1.09407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2667.1877343799997, 2280.75460938, 175.48130859), 'rotation':(-1.17868, -179.48555, -1.227966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2672.74755859, 2280.80226562, 175.59445312), 'rotation':(-1.17868, -179.48555, -1.227966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2700.54638672, 2281.03976562, 176.10466797), 'rotation':(-0.979004, -179.493469, -1.012909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2706.10960938, 2281.08765625, 176.19199218999998), 'rotation':(-0.899109, -179.496094, -0.927673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2711.67066406, 2281.13523438, 176.27800781000002), 'rotation':(-0.899109, -179.496094, -0.927673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2722.79736328, 2281.23046875, 176.44431641), 'rotation':(-0.854828, -179.496429, -0.880646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2728.36058594, 2281.27804688, 176.52695312), 'rotation':(-0.854828, -179.496429, -0.880646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2756.1775, 2281.51609375, 176.93482422), 'rotation':(-0.831268, -179.500656, -0.855652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2767.30322266, 2281.61132812, 177.09392577999998), 'rotation':(-0.822388, -179.497086, -0.846222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2778.43017578, 2281.70632812, 177.24791016), 'rotation':(-0.782867, -179.49823, -0.804474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2783.99292969, 2281.75390625, 177.32277344), 'rotation':(-0.782867, -179.49823, -0.804474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2789.55589844, 2281.80148438, 177.39652343999998), 'rotation':(-0.762573, -179.500549, -0.783081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2806.24658203, 2281.9387500000003, 177.60966797), 'rotation':(-0.721375, -179.499863, -0.739716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2817.3728125, 2282.04984375, 177.74470703), 'rotation':(-0.699829, -179.502151, -0.717072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2822.93603516, 2282.10695312, 177.81021484000001), 'rotation':(-0.679993, -179.501617, -0.696289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2834.06347656, 2282.2153125, 177.93679688), 'rotation':(-0.643524, -179.502472, -0.658112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.75242188, 2211.34226562, 175.95236328), 'rotation':(-0.249847, -89.585388, -0.252014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.67234375, 2222.47609375, 176.00125), 'rotation':(-0.25174, -89.588348, -0.253967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.59226562, 2233.60914062, 176.05134766), 'rotation':(-0.26001, -89.586182, -0.26236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3509.55226562, 2239.17578125, 176.07691406), 'rotation':(-0.263916, -89.586121, -0.266357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.43210938, 2255.87570312, 176.15546875), 'rotation':(-0.272034, -89.588165, -0.274628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.35203125, 2267.00875, 176.20951172000002), 'rotation':(-0.280273, -89.585968, -0.283051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.27195312, 2278.1428125, 176.26431641), 'rotation':(-0.282196, -89.586395, -0.284973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.23195312, 2283.70921875, 176.29179688), 'rotation':(-0.282196, -89.586395, -0.284973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.15160156, 2294.84203125, 176.34710938), 'rotation':(-0.28598, -89.585388, -0.288849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3509.1115625, 2300.40867188, 176.37496094), 'rotation':(-0.287109, -89.586792, -0.290009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3509.03171875, 2311.54148438, 176.43074219), 'rotation':(-0.287109, -89.586792, -0.290009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.99171875, 2317.1081249999997, 176.45855468999997), 'rotation':(-0.286194, -89.585327, -0.289062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3508.91164062, 2328.24125, 176.51365234000002), 'rotation':(-0.28244, -89.585327, -0.285248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.83128906, 2339.3740625, 176.56816406000002), 'rotation':(-0.280487, -89.587402, -0.283234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.7111718799997, 2356.07300781, 176.64880859000002), 'rotation':(-0.27475, -89.585388, -0.277405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3508.67113281, 2361.63964844, 176.67537109), 'rotation':(-0.272827, -89.587494, -0.275452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3508.63109375, 2367.20582031, 176.70181641), 'rotation':(-0.272827, -89.587494, -0.275452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3500.79101562, 2361.5857031200003, 176.67537109), 'rotation':(0.271937, 90.412849, 0.269374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3500.87109375, 2350.4528906200003, 176.62210938), 'rotation':(0.274765, 90.412506, 0.272148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3500.99121094, 2333.75320312, 176.54099609000002), 'rotation':(0.280489, 90.414642, 0.277746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.07152344, 2322.620625, 176.48617188), 'rotation':(0.282428, 90.41259, 0.279656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.1115625, 2317.05421875, 176.45857422), 'rotation':(0.284389, 90.41468, 0.281566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.19164062, 2305.92140625, 176.40287109000002), 'rotation':(0.287107, 90.41317, 0.284238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.23167969, 2300.355, 176.37496094), 'rotation':(0.287107, 90.41317, 0.284238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.27171875, 2294.78835938, 176.34712890999998), 'rotation':(0.287121, 90.413193, 0.284249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.31175781, 2289.22171875, 176.31933593999997), 'rotation':(0.28598, 90.414635, 0.283137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.3908593799997, 2278.08890625, 176.26433594), 'rotation':(0.282176, 90.413574, 0.279419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.431875, 2272.52195312, 176.23691406), 'rotation':(0.282176, 90.413574, 0.279419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.55199219, 2255.8215625000003, 176.15548828), 'rotation':(0.27622, 90.413979, 0.273566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.59203125, 2250.25484375, 176.12896484), 'rotation':(0.272026, 90.413918, 0.269457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3501.63207031, 2244.68820312, 176.10277344), 'rotation':(0.268105, 90.413887, 0.265608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.71214844, 2233.5546875, 176.05136718999998), 'rotation':(0.263905, 90.411743, 0.26148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3501.7521875, 2227.98828125, 176.02611328), 'rotation':(0.259984, 90.413811, 0.257642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.15867188, 2367.36816406, 173.09376953), 'rotation':(-0.030853, 90.384315, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.27050781, 2350.6877343799997, 173.10257812), 'rotation':(-0.03009, 90.384781, -0.030121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.30785156, 2345.12769531, 173.10541016), 'rotation':(-0.02951, 90.384804, -0.029541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.3825781200003, 2334.00710938, 173.11097656), 'rotation':(-0.028473, 90.384781, -0.028503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.41992188, 2328.44679688, 173.11367188), 'rotation':(-0.028046, 90.384781, -0.028046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3616.49460938, 2317.32664062, 173.11896484000002), 'rotation':(-0.027008, 90.384804, -0.027039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.53222656, 2311.76585938, 173.1215625), 'rotation':(-0.026794, 90.386124, -0.026825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3616.60695312, 2300.64523438, 173.12722656000003), 'rotation':(-0.029602, 90.385918, -0.029633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.64429688, 2295.085, 173.13033202999998), 'rotation':(-0.031616, 90.385895, -0.031647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.79371094, 2272.84375, 173.14488281), 'rotation':(-0.041412, 90.385918, -0.041473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3616.83082031, 2267.28273438, 173.14894531000002), 'rotation':(-0.042419, 90.384125, -0.04248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.86816406, 2261.7221875, 173.15316406000002), 'rotation':(-0.044312, 90.386406, -0.044373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3616.90550781, 2256.16164062, 173.15769531), 'rotation':(-0.047791, 90.383644, -0.047852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3617.20433594, 2211.67820312, 173.20740234000002), 'rotation':(-0.074432, 90.385605, -0.074615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.08445312, 2211.7309375, 173.20740234000002), 'rotation':(0.080419, -89.614349, 0.080193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3625.0471093799997, 2217.29148438, 173.20013672000002), 'rotation':(0.074429, -89.61438, 0.07424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.89769531, 2239.5334375, 173.17371093999998), 'rotation':(0.062373, -89.613525, 0.062236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.82300781, 2250.65429688, 173.16263672000002), 'rotation':(0.055072, -89.613556, 0.054965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.67382812, 2272.89695312, 173.14488281), 'rotation':(0.042422, -89.615845, 0.042357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.63648438, 2278.45679688, 173.1409375), 'rotation':(0.039417, -89.614075, 0.03936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3624.59914062, 2284.01734375, 173.13722656000002), 'rotation':(0.037416, -89.61676, 0.037368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.56175781, 2289.57742188, 173.13369140999998), 'rotation':(0.035592, -89.614075, 0.035552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.41234375, 2311.8190624999997, 173.1215625), 'rotation':(0.027772, -89.61676, 0.02775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.33742188, 2322.93945312, 173.11634766), 'rotation':(0.026993, -89.615204, 0.026973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.22535156, 2339.62015625, 173.10822266), 'rotation':(0.028468, -89.615204, 0.028446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3624.18796875, 2345.18042969, 173.10542969), 'rotation':(0.029062, -89.615204, 0.029036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3624.11351562, 2356.30054688, 173.0996875), 'rotation':(0.029506, -89.615173, 0.029479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.07617188, 2361.86085938, 173.09673827999998), 'rotation':(0.030107, -89.615204, 0.030066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3624.0388281200003, 2367.42113281, 173.09376953), 'rotation':(0.030538, -89.615204, 0.030508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.30320312, 2179.1706249999997, 173.26115234), 'rotation':(0.108675, -89.614655, 0.108266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.3415625, 2173.47117188, 173.27203125), 'rotation':(0.111817, -89.615814, 0.111377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.41820312, 2162.07273438, 173.2953125), 'rotation':(0.124303, -89.615784, 0.123781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.4565625, 2156.37328125, 173.30796875), 'rotation':(0.130634, -89.615784, 0.13005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.57152344, 2139.27539062, 173.34996094), 'rotation':(0.15581, -89.612946, 0.154967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.72460938, 2116.4765625, 173.41392578), 'rotation':(0.178712, -89.615051, 0.177599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.76292969, 2110.77757812, 173.43167968999998), 'rotation':(0.191997, -89.61496, 0.190712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3625.839375, 2099.37890625, 173.46929688), 'rotation':(0.205199, -89.613281, 0.203732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.91601562, 2087.97953125, 173.51042969), 'rotation':(0.211825, -89.614563, 0.210274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3625.95433594, 2082.2803125, 173.53148438), 'rotation':(0.218293, -89.615112, 0.216639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3626.0310156200003, 2070.880625, 173.57511719), 'rotation':(0.231523, -89.613556, 0.229667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.14574219, 2053.7834375, 173.64617188), 'rotation':(0.257635, -89.613342, 0.255328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.26050781, 2036.68453125, 173.72384766), 'rotation':(0.276882, -89.613525, 0.27422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.33714844, 2025.28601562, 173.77888672), 'rotation':(0.285051, -89.613434, 0.282228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3626.41359375, 2013.8869531199998, 173.83708984), 'rotation':(0.301969, -89.613281, 0.298804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3618.60984375, 2002.4693750000001, 173.89832031000003), 'rotation':(-0.310303, 90.386833, -0.31366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.57152344, 2008.1673437499999, 173.86722656), 'rotation':(-0.301971, 90.386703, -0.305176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.45679688, 2025.26257812, 173.77873047), 'rotation':(-0.276886, 90.386482, -0.279572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.38039062, 2036.65867188, 173.72371094), 'rotation':(-0.26825, 90.384048, -0.270813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.22703125, 2059.45242188, 173.62173828), 'rotation':(-0.231537, 90.386406, -0.233398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3618.150625, 2070.84789062, 173.57503906000002), 'rotation':(-0.218323, 90.384888, -0.219971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3618.11230469, 2076.54664062, 173.55304688), 'rotation':(-0.218323, 90.384888, -0.219971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3617.84449219, 2116.43453125, 173.41388672000002), 'rotation':(-0.165497, 90.384872, -0.166473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.80617188, 2122.13328125, 173.39728516), 'rotation':(-0.158722, 90.38607, -0.159607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.7678125, 2127.8325, 173.38103515999998), 'rotation':(-0.158722, 90.38607, -0.159607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.61476562, 2150.62546875, 173.32128906000003), 'rotation':(-0.13681, 90.384254, -0.137451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.57640625, 2156.32375, 173.30794922), 'rotation':(-0.124329, 90.384232, -0.124847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3617.53808594, 2162.02171875, 173.2953125), 'rotation':(-0.117981, 90.384186, -0.118469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3617.42308594, 2179.11671875, 173.26115234), 'rotation':(-0.106537, 90.382812, -0.106964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.3854687499997, 2218.16796875, 169.90158203), 'rotation':(0.432235, -89.80838, 0.425758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2942187500003, 2245.90453125, 169.69707031000002), 'rotation':(0.41324, -89.810669, 0.407312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2760937499997, 2251.45164062, 169.65775391), 'rotation':(0.408001, -89.808105, 0.402234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2578125, 2256.9990625, 169.61898438), 'rotation':(0.402421, -89.808167, 0.396807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.2214062499997, 2268.09398438, 169.54294922), 'rotation':(0.391595, -89.810944, 0.38628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.203125, 2273.64085938, 169.5053125), 'rotation':(0.388911, -89.80899, 0.383671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.1848437500003, 2279.1884375, 169.46785156), 'rotation':(0.388911, -89.80899, 0.383671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.16648438, 2284.7356250000003, 169.430625), 'rotation':(0.385762, -89.808441, 0.380586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.1484375, 2290.28273438, 169.39390625), 'rotation':(0.379267, -89.808563, 0.37428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.11179688, 2301.37695312, 169.32169922), 'rotation':(0.372792, -89.810303, 0.367965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3733.9475, 2351.30199219, 169.00941406), 'rotation':(0.349829, -89.809479, 0.345568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3733.91109375, 2362.39671875, 168.94236328), 'rotation':(0.345082, -89.80954, 0.340942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.04882812, 2356.82570312, 168.97576172), 'rotation':(-0.345093, 90.190445, -0.349274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.12203125, 2334.6371875, 169.11162109), 'rotation':(-0.354706, 90.190567, -0.359131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.14039062, 2329.0903125, 169.14615234000001), 'rotation':(-0.356995, 90.190598, -0.361481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.17671875, 2317.99609375, 169.21585938), 'rotation':(-0.361755, 90.190659, -0.366333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.21335938, 2306.90085938, 169.28623047000002), 'rotation':(-0.363068, 90.191605, -0.367706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.2317187500003, 2301.35375, 169.32167969), 'rotation':(-0.366272, 90.189575, -0.371002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.26804688, 2290.25953125, 169.39388672), 'rotation':(-0.372772, 90.191376, -0.377655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.30445312, 2279.165, 169.46783202999998), 'rotation':(-0.385742, 90.191544, -0.390991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.32273438, 2273.61742188, 169.50529297), 'rotation':(-0.385742, 90.191544, -0.390991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.3410937500003, 2268.07054688, 169.54292969), 'rotation':(-0.388947, 90.190994, -0.394226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.37742188, 2256.97585938, 169.61896484000002), 'rotation':(-0.397186, 90.18914, -0.40271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.43210938, 2240.33398438, 169.73691406), 'rotation':(-0.413269, 90.191971, -0.41925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.52320312, 2212.59789062, 169.94341797), 'rotation':(-0.432251, 90.191612, -0.438812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.21414062, 2002.4493750000001, 171.97642578), 'rotation':(-0.671906, 90.196579, -0.687805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.19578125, 2008.0, 171.91140625), 'rotation':(-0.66153, 90.196342, -0.676941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.14109375, 2024.6528125, 171.72126953), 'rotation':(-0.645905, 90.196983, -0.660583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3727.04984375, 2052.40648438, 171.41314452999998), 'rotation':(-0.611298, 90.193939, -0.624451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3727.03148438, 2057.95875, 171.35361328), 'rotation':(-0.603668, 90.196373, -0.616486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3727.0134375, 2063.50953125, 171.29488281000002), 'rotation':(-0.595856, 90.193604, -0.608337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.97679688, 2074.61109375, 171.17970703), 'rotation':(-0.58432, 90.193954, -0.596313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.9401562499997, 2085.713125, 171.06636719), 'rotation':(-0.584473, 90.19603, -0.596466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.9035937500003, 2096.81570312, 170.9540625), 'rotation':(-0.566864, 90.19384, -0.578156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.88523438, 2102.36671875, 170.89917968999998), 'rotation':(-0.555084, 90.193596, -0.565918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.86695312, 2107.91726562, 170.84539062), 'rotation':(-0.543457, 90.193382, -0.553864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.81226562, 2124.57125, 170.68830078), 'rotation':(-0.53363, 90.192802, -0.54364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.7942187500003, 2130.12304688, 170.63650391), 'rotation':(-0.525879, 90.192673, -0.535614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.77585938, 2135.67382812, 170.58537109), 'rotation':(-0.518036, 90.19252, -0.527466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.7395312500003, 2146.775625, 170.48525390999998), 'rotation':(-0.502289, 90.194633, -0.511139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.6848437500003, 2163.43039062, 170.34039062), 'rotation':(-0.486664, 90.191971, -0.494995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3726.6484375, 2174.5334375, 170.24726562), 'rotation':(-0.475037, 90.193207, -0.482971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3726.6301562500003, 2180.08421875, 170.20126953), 'rotation':(-0.471069, 90.191872, -0.478851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.54710938, 2169.01882812, 170.29345702999998), 'rotation':(0.486685, -89.808014, 0.478462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.56546875, 2163.46726562, 170.34029297), 'rotation':(0.494547, -89.807861, 0.486071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.58351562, 2157.91601562, 170.38787109), 'rotation':(0.502278, -89.807739, 0.493537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.62015625, 2146.81179688, 170.48517578), 'rotation':(0.51016, -89.807587, 0.501129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.71140625, 2119.05421875, 170.7403125), 'rotation':(0.537652, -89.805267, 0.527639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.7478125, 2107.95070312, 170.8453125), 'rotation':(0.555096, -89.806396, 0.544411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.78445312, 2096.84789062, 170.95398438), 'rotation':(0.578462, -89.805908, 0.56689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.8025, 2091.29664062, 171.00984375), 'rotation':(0.584432, -89.80603, 0.572601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.82078125, 2085.7448437499997, 171.06630859), 'rotation':(0.584323, -89.80603, 0.572492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3734.83914062, 2080.19382812, 171.12292968999998), 'rotation':(0.584323, -89.80603, 0.572492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.87570312, 2069.09078125, 171.23685547000002), 'rotation':(0.595838, -89.806396, 0.583544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.91234375, 2057.98828125, 171.35357422), 'rotation':(0.611295, -89.803467, 0.598353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(3734.96703125, 2041.33359375, 171.53443359000002), 'rotation':(0.634388, -89.802948, 0.620462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(3735.0034375, 2030.2310937500001, 171.65865234), 'rotation':(0.645876, -89.803009, 0.63144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(3735.02171875, 2024.6803125000001, 171.72125), 'rotation':(0.645897, -89.805389, 0.631468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2427.88867188, 2586.04296875, 169.05853516), 'rotation':(-1.796478, 179.989639, -1.911957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2422.23195312, 2586.04957031, 168.88166016), 'rotation':(-1.796478, 179.989639, -1.911957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2405.26292969, 2586.06957031, 168.34509766), 'rotation':(-1.822418, 179.990829, -1.941345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2393.9496875, 2586.08277344, 167.98439453), 'rotation':(-1.834778, 179.991638, -1.955322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2388.29296875, 2586.08910156, 167.80320312), 'rotation':(-1.841187, 179.99205, -1.962585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2382.63648438, 2586.09570312, 167.62144531), 'rotation':(-1.847168, 179.992432, -1.96936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2371.32496094, 2586.1091406200003, 167.25625), 'rotation':(-1.853516, 179.992844, -1.976562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2360.01148438, 2586.12230469, 166.88869140999998), 'rotation':(-1.865906, 179.993637, -1.990662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2354.3559375, 2586.12890625, 166.70414062), 'rotation':(-1.869049, 179.9935, -1.994202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2348.69921875, 2586.13574219, 166.51935547000002), 'rotation':(-1.869202, 179.9935, -1.994354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2320.41773438, 2586.16894531, 165.59148438), 'rotation':(-1.884613, 179.995331, -2.011871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2314.76125, 2586.17554688, 165.40515625), 'rotation':(-1.884613, 179.995331, -2.011871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2309.10453125, 2586.18210938, 165.21880859), 'rotation':(-1.884705, 179.995346, -2.011993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2297.79125, 2586.1955468799997, 164.84615234), 'rotation':(-1.886017, 179.996063, -2.013489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2292.13476562, 2586.20214844, 164.65976562), 'rotation':(-1.886017, 179.996063, -2.013489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2286.47804688, 2586.20851562, 164.47328125), 'rotation':(-1.887512, 179.99559, -2.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2280.82203125, 2586.2153125, 164.28671875), 'rotation':(-1.88736, 179.993439, -2.015015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2269.50875, 2586.22851562, 163.91351562), 'rotation':(-1.887512, 179.99559, -2.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':2, 'location':(2258.193125, 2586.24171875, 163.54030273), 'rotation':(-1.883636, 179.995331, -2.010803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':2, 'location':(2252.53664062, 2586.24851562, 163.3540625), 'rotation':(-1.875977, 179.992981, -2.002075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2246.87960938, 2586.25511719, 163.16851562), 'rotation':(-1.868561, 179.994324, -1.993622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2235.56570312, 2586.26832031, 162.79890625), 'rotation':(-1.861053, 179.993835, -1.985107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2615.84375, 2585.82226562, 174.42771484000002), 'rotation':(-1.455902, 179.970673, -1.531372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2604.77757812, 2585.83546875, 174.14417969), 'rotation':(-1.486084, 179.972229, -1.564758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2599.24339844, 2585.84179688, 174.00048827999998), 'rotation':(-1.501373, 179.97081, -1.581696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':2, 'location':(2593.70972656, 2585.84839844, 173.85537109), 'rotation':(-1.516418, 179.973816, -1.598358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2566.04320312, 2585.88085938, 173.11427734), 'rotation':(-1.55368, 179.973999, -1.639771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2560.51, 2585.8871875, 172.96392577999998), 'rotation':(-1.582825, 179.977081, -1.672211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':2, 'location':(2554.9763281200003, 2585.89378906, 172.81087890999999), 'rotation':(-1.597565, 179.978149, -1.688629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2516.24535156, 2585.93921875, 171.71992188000002), 'rotation':(-1.657043, 179.979019, -1.755127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2505.18335938, 2585.95214844, 171.39900391), 'rotation':(-1.683441, 179.982803, -1.784698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':2, 'location':(2494.1171875, 2585.9653125, 171.07351562), 'rotation':(-1.696533, 179.983582, -1.799408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':2, 'location':(2488.58640625, 2585.97191406, 170.90935547), 'rotation':(-1.7034, 179.984039, -1.807098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.2956249999997, 363.0452734400001, 157.57901367), 'rotation':(-0.018127, -89.870178, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.24414062, 385.81281249999995, 157.58602539), 'rotation':(-0.018127, -89.870178, -0.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.2053125, 402.88820312000007, 157.58546875), 'rotation':(0.00849, -89.868774, 0.008482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.19234375, 408.5803125, 157.58462891), 'rotation':(0.00849, -89.87027, 0.008481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.17945312, 414.27246094, 157.58378906), 'rotation':(0.00849, -89.87027, 0.008481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.16648438, 419.96460937999996, 157.58295898), 'rotation':(0.00849, -89.87027, 0.008481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2147.140625, 431.348125, 157.58125), 'rotation':(0.008381, -89.868774, 0.008392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.11476562, 442.73210938, 157.57849609000002), 'rotation':(0.012233, -89.870544, 0.012231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.10179688, 448.4241796900001, 157.57655273), 'rotation':(0.01963, -89.868958, 0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2147.05007812, 471.19109375000005, 157.56380859), 'rotation':(0.038256, -89.870911, 0.038202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.99828125, 493.95914062, 157.54629882999998), 'rotation':(0.046903, -89.86908, 0.04684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.95945312, 511.03523437999996, 157.53038086), 'rotation':(0.056766, -89.869049, 0.056653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.93359375, 522.41871094, 157.51881836), 'rotation':(0.058139, -89.869598, 0.058023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.90773438, 533.80273438, 157.50645508), 'rotation':(0.064252, -89.868286, 0.064115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.78195312, 589.10566406, 157.43226562), 'rotation':(0.083943, -89.869751, 0.083696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.7690625, 594.7865625, 157.42352539), 'rotation':(0.088144, -89.869751, 0.087877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.743125, 606.14769531, 157.40519531), 'rotation':(0.092255, -89.869751, 0.091968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.73023438, 611.8284765599999, 157.39583984), 'rotation':(0.094243, -89.870575, 0.093951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.71726562, 617.50902344, 157.38644531), 'rotation':(0.094257, -89.868042, 0.093941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.69140625, 628.8705468799999, 157.36710938), 'rotation':(0.098799, -89.870453, 0.098456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.66578125, 640.23199219, 157.34675780999999), 'rotation':(0.104734, -89.870422, 0.104346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.6528125, 645.91257812, 157.33631836), 'rotation':(0.106182, -89.868896, 0.105794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.61398438, 662.9547265599999, 157.30452148), 'rotation':(0.108586, -89.870239, 0.108173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.60109375, 668.63539062, 157.29365234), 'rotation':(0.110171, -89.867706, 0.109754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.57515625, 679.99701172, 157.27145508), 'rotation':(0.11334, -89.870239, 0.112898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.5625, 685.67773438, 157.26009765999999), 'rotation':(0.114774, -89.867676, 0.114316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.5495312499997, 691.3585156199999, 157.24859375), 'rotation':(0.116516, -89.870239, 0.116052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.536875, 697.0392968799999, 157.23693359), 'rotation':(0.117957, -89.870209, 0.117465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.51101562, 708.40070312, 157.21339844), 'rotation':(0.118797, -89.871094, 0.118295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.4853125, 719.7620312500001, 157.18953125), 'rotation':(0.121386, -89.870544, 0.120886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.47242188, 725.4428125, 157.17738281), 'rotation':(0.121386, -89.870544, 0.120886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.39476562, 759.52740234, 157.10269531), 'rotation':(0.126816, -89.869324, 0.126251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.2578125, 819.68957031, 156.96612305), 'rotation':(0.13131, -89.869781, 0.130715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.23265625, 830.74078125, 156.94075195), 'rotation':(0.131741, -89.868073, 0.131143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.18265625, 852.84356445, 156.88994141), 'rotation':(0.13172, -89.870789, 0.131115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.1575000000003, 863.89483398, 156.86463867), 'rotation':(0.13114, -89.870178, 0.13055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.09445312, 891.52332031, 156.80198242), 'rotation':(0.129432, -89.869965, 0.128864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2146.04445312, 913.62609375, 156.75304688), 'rotation':(0.125225, -89.869965, 0.124677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2146.03445312, 931.08374023, 156.71554688), 'rotation':(0.122315, -89.869995, 0.121784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.9275, 524.1565625000001, 159.06637695), 'rotation':(-0.049225, 90.543251, -0.049316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.98, 518.61480469, 159.07091796999998), 'rotation':(-0.047211, 90.544357, -0.047272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.13765625, 501.9909375, 159.08205078), 'rotation':(-0.034668, 90.541718, -0.034729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.1901562499997, 496.44972656, 159.08493164), 'rotation':(-0.030426, 90.544319, -0.030457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.29539062, 485.36730468999997, 159.08944336000002), 'rotation':(-0.022125, 90.544334, -0.022156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.34789062, 479.8265234400001, 159.09112305), 'rotation':(-0.017883, 90.544319, -0.017914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.40039062, 474.28515625, 159.09266602), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.45289062, 468.74367187999997, 159.09418945), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.50539062, 463.20226562000005, 159.09573242), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.55789062, 457.66089844, 159.09725586000002), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.6103125, 452.12046875, 159.09857422), 'rotation':(-0.015839, 90.542862, -0.015869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.7678125, 435.4971875, 159.09692383), 'rotation':(0.011406, 90.541801, 0.011395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.8203125, 429.95585938, 159.09581055), 'rotation':(0.0114, 90.544518, 0.011403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.87304688, 424.41437499999995, 159.09470703), 'rotation':(0.011577, 90.541794, 0.011565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.92554688, 418.87304687999995, 159.09359375), 'rotation':(0.0114, 90.544518, 0.011393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.97804688, 413.3315625, 159.09248047), 'rotation':(0.011406, 90.541801, 0.011391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2236.08296875, 402.24976562000006, 159.09010742), 'rotation':(0.011406, 90.541801, 0.011395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2236.2934375, 380.08539062, 159.0768457), 'rotation':(0.049478, 90.544647, 0.049382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2236.4509375, 363.46214843999996, 159.06094726999999), 'rotation':(0.054894, 90.54409, 0.054795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.09695312, 717.27984375, 158.77083984), 'rotation':(-0.118958, 90.543137, -0.119446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.30664062, 695.12054688, 158.81583984), 'rotation':(-0.11319, 90.544235, -0.113617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.5690624999997, 667.42132812, 158.86849609), 'rotation':(-0.105835, 90.54335, -0.106232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.62179688, 661.88140625, 158.87874023), 'rotation':(-0.105988, 90.54335, -0.106384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.72679688, 650.80195312, 158.89871094), 'rotation':(-0.104034, 90.5439, -0.104431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.77929688, 645.26195312, 158.90841797), 'rotation':(-0.10025, 90.543892, -0.100616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.83179688, 639.72203125, 158.91780273), 'rotation':(-0.096558, 90.542267, -0.096863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.93703125, 628.6424609400001, 158.93600586), 'rotation':(-0.092743, 90.543861, -0.093048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.1996875, 600.94359375, 158.97868164), 'rotation':(-0.084106, 90.542976, -0.084351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.5146875, 567.70464844, 159.02189453), 'rotation':(-0.069061, 90.542427, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.56710938, 562.16484375, 159.02847656), 'rotation':(-0.069061, 90.542427, -0.069214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.26539062, 910.49212891, 158.34681641), 'rotation':(-0.120575, 90.542747, -0.121094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.4228125, 893.86016602, 158.3821582), 'rotation':(-0.122589, 90.543266, -0.123108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.63304688, 871.68432617, 158.43046875), 'rotation':(-0.126129, 90.543289, -0.126678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2231.73828125, 860.59637695, 158.45509765999998), 'rotation':(-0.127289, 90.543633, -0.127838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2231.94851562, 838.4205957, 158.50456055), 'rotation':(-0.128052, 90.544662, -0.128632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.0534374999997, 827.33263672, 158.52948242), 'rotation':(-0.128571, 90.543045, -0.12915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.15867188, 816.24474609, 158.55449219), 'rotation':(-0.129456, 90.544327, -0.130035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.21117188, 810.70085938, 158.56701171999998), 'rotation':(-0.129456, 90.544327, -0.130035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2232.36890625, 794.06916016, 158.6044043), 'rotation':(-0.128113, 90.542236, -0.128693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2232.47414062, 782.98132812, 158.62910156), 'rotation':(-0.127472, 90.54393, -0.128052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2232.5790625, 771.89355469, 158.65362305), 'rotation':(-0.126617, 90.543938, -0.127167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2229.8525, 1059.50476074, 158.09428711), 'rotation':(-0.063934, 90.542557, -0.064087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2229.9049999999997, 1053.95324707, 158.10049805), 'rotation':(-0.063934, 90.544174, -0.064056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.11546875, 1031.74902344, 158.12819336), 'rotation':(-0.076202, 90.544014, -0.076416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.16796875, 1026.19787598, 158.13600586), 'rotation':(-0.079498, 90.541405, -0.079712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.37867188, 1003.99316406, 158.17039062), 'rotation':(-0.092834, 90.54158, -0.09314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.48390625, 992.89105225, 158.1887793), 'rotation':(-0.096771, 90.54158, -0.097107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.53664062, 987.34014893, 158.19827148000002), 'rotation':(-0.098755, 90.544205, -0.099091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.58914062, 981.78912354, 158.20797851999998), 'rotation':(-0.100861, 90.544228, -0.101227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.6418750000003, 976.23809814, 158.21786133), 'rotation':(-0.102661, 90.541588, -0.103027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2230.694375, 970.68713379, 158.22794922), 'rotation':(-0.104797, 90.544243, -0.105164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.77320312, 948.71459961, 158.26928711), 'rotation':(-0.109009, 90.542625, -0.109436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.33296875, 378.24914062000005, 160.59979492), 'rotation':(-0.089966, -89.6185, -0.090271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.26929688, 386.00660156000004, 160.61134765999998), 'rotation':(-0.084656, -89.617218, -0.0849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2340.0846874999997, 413.64093749999995, 160.64207031), 'rotation':(-0.052917, -89.61731, -0.053009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.04757812, 419.16820312000004, 160.64666992), 'rotation':(-0.047668, -89.615631, -0.04776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.93703125, 435.74890625, 160.6593457), 'rotation':(-0.042786, -89.618744, -0.042847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.89992188, 441.27617188, 160.66251953), 'rotation':(-0.03299, -89.616943, -0.03302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.75242188, 463.38378906, 160.66867188), 'rotation':(-0.008514, -89.617676, -0.008514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.7153125, 468.91105469, 160.66949219), 'rotation':(-0.008514, -89.617676, -0.008514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2339.6784374999997, 474.43835937999995, 160.67032226999999), 'rotation':(-0.008606, -89.617676, -0.008606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.53078125, 496.54644530999997, 160.67345703), 'rotation':(-0.008606, -89.616211, -0.008606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.49390625, 502.07378905999997, 160.67288086), 'rotation':(0.006024, -89.617981, 0.00603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.16726562, 551.02082031, 160.65327148), 'rotation':(0.031733, -89.617584, 0.031695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2339.09351562, 562.0660937499999, 160.6452832), 'rotation':(0.039062, -89.617584, 0.039014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.05664062, 567.5882031200001, 160.64078125), 'rotation':(0.046698, -89.617554, 0.046614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2339.01953125, 573.1109765599999, 160.6359082), 'rotation':(0.050263, -89.616364, 0.050176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.98265625, 578.63328125, 160.6309375), 'rotation':(0.051773, -89.617737, 0.051694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.94578125, 584.1559374999999, 160.62571289), 'rotation':(0.054566, -89.617706, 0.054456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.9089062499997, 589.67863281, 160.62025391), 'rotation':(0.057333, -89.617737, 0.057219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.87203125, 595.2012890599999, 160.61452148), 'rotation':(0.059955, -89.615234, 0.059827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.72460938, 617.29207031, 160.58898438), 'rotation':(0.071205, -89.617706, 0.071028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.68773438, 622.8143749999999, 160.58205078), 'rotation':(0.072352, -89.61673, 0.072174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.61375, 633.85957031, 160.56791992), 'rotation':(0.07449, -89.616547, 0.074307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.50320312, 650.42753906, 160.54495117), 'rotation':(0.082597, -89.616516, 0.082364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.42945312, 661.47265625, 160.52820312), 'rotation':(0.086784, -89.618408, 0.08652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.35570312, 672.5180664100001, 160.51106445), 'rotation':(0.088758, -89.617828, 0.088477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2338.28171875, 683.56347656, 160.49348633), 'rotation':(0.092119, -89.617615, 0.091818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2338.20796875, 694.60876953, 160.47521484), 'rotation':(0.094332, -89.615601, 0.094017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.91796875, 738.0379101599999, 160.39799805), 'rotation':(0.105567, -89.617004, 0.105177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.84421875, 749.08660156, 160.37738281), 'rotation':(0.107384, -89.616974, 0.10699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.73367188, 765.65949219, 160.34573242), 'rotation':(0.110089, -89.618286, 0.109661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.69679688, 771.18382812, 160.33511719), 'rotation':(0.110089, -89.618286, 0.109661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.65992188, 776.708125, 160.32451172), 'rotation':(0.110191, -89.616669, 0.109763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.5859375, 787.75683594, 160.30317383), 'rotation':(0.11084, -89.618286, 0.110418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.5490625, 793.28107422, 160.29245117), 'rotation':(0.111428, -89.615936, 0.110982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.4753124999997, 804.32984375, 160.27087891), 'rotation':(0.111851, -89.618256, 0.111419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.40164062, 815.37853516, 160.24926758), 'rotation':(0.112227, -89.61618, 0.11178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.32765625, 826.42730469, 160.22769531), 'rotation':(0.111735, -89.61734, 0.11129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.18015625, 848.52490234, 160.18505859), 'rotation':(0.110014, -89.61734, 0.109581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.10640625, 859.57367188, 160.16401367), 'rotation':(0.109194, -89.61734, 0.108774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2337.06960938, 865.09808594, 160.15354492), 'rotation':(0.108812, -89.617004, 0.108397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.66890625, 925.075625, 160.046875), 'rotation':(0.096449, -89.617767, 0.096128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.55835938, 941.65234375, 160.0202832), 'rotation':(0.089107, -89.617767, 0.088837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.52148438, 947.17785645, 160.01196289), 'rotation':(0.085493, -89.617798, 0.085247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.4475, 958.22912598, 159.99574219), 'rotation':(0.083629, -89.61676, 0.083393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.3737499999997, 969.28070068, 159.97996094), 'rotation':(0.079722, -89.618744, 0.079494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.29984375, 980.33184814, 159.96511719), 'rotation':(0.074422, -89.618744, 0.074234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.22609375, 991.38293457, 159.95125977), 'rotation':(0.069285, -89.616272, 0.069116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.11523438, 1007.96002197, 159.93229492), 'rotation':(0.063999, -89.616272, 0.06385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2336.04148438, 1019.01177979, 159.92076172), 'rotation':(0.05846, -89.618042, 0.058334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2335.9678125, 1030.06335449, 159.91094727), 'rotation':(0.050175, -89.618073, 0.050085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2335.8940625, 1041.11462402, 159.90327148), 'rotation':(0.041794, -89.616516, 0.041727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2335.91210938, 1057.78637695, 159.89428711), 'rotation':(0.029261, -89.617188, 0.029231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.69628906, 498.29, 162.22680664), 'rotation':(-0.004059, 90.286415, -0.004059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.81957031, 487.12902343999997, 162.2259082), 'rotation':(0.004166, 90.287025, 0.004161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.87546875, 475.96386719, 162.22079102), 'rotation':(0.028823, 90.286591, 0.028796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.90355469, 470.38085937999995, 162.21796875), 'rotation':(0.02868, 90.288841, 0.028657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.95972656, 459.21484375, 162.21237305), 'rotation':(0.02868, 90.288841, 0.028657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.015625, 448.04992187999994, 162.20548828), 'rotation':(0.033133, 90.288589, 0.033102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2426.04371094, 442.46710938, 162.20128906), 'rotation':(0.041814, 90.286797, 0.041757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.09984375, 431.30140625, 162.19078125), 'rotation':(0.059279, 90.286819, 0.059168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.1840625, 414.55363280999995, 162.17211914), 'rotation':(0.066902, 90.286278, 0.066756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.21214844, 408.97082031, 162.16505859), 'rotation':(0.073179, 90.288475, 0.073005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.24023438, 403.38812499999995, 162.15745117), 'rotation':(0.079483, 90.288498, 0.079252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.26832031, 397.8053125, 162.14932617), 'rotation':(0.085896, 90.288521, 0.085632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2426.29640625, 392.22343750000005, 162.14067383), 'rotation':(0.085896, 90.288521, 0.085632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2426.380625, 375.47507812000003, 162.11155273), 'rotation':(0.104878, 90.288574, 0.104482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.75902344, 675.9975, 162.10049805), 'rotation':(-0.079865, 90.287132, -0.080109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.92652344, 664.84242188, 162.11540039), 'rotation':(-0.077026, 90.288811, -0.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.95433594, 659.263125, 162.12275391), 'rotation':(-0.075714, 90.287476, -0.075928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.03859375, 642.52433594, 162.14364258), 'rotation':(-0.06897, 90.287849, -0.069122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.06664062, 636.94488281, 162.15012695), 'rotation':(-0.06897, 90.287849, -0.069122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.12257812, 625.78589844, 162.16232422), 'rotation':(-0.064453, 90.287865, -0.064575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.150625, 620.20660156, 162.16813477), 'rotation':(-0.060028, 90.287849, -0.06015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.17871094, 614.6270312500001, 162.1737793), 'rotation':(-0.057709, 90.288727, -0.057831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.29101562, 592.30933594, 162.19404297), 'rotation':(-0.048309, 90.287239, -0.04837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.40308594, 569.99152344, 162.20999023000002), 'rotation':(-0.037384, 90.287224, -0.037415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2425.45898438, 558.83292969, 162.21668945), 'rotation':(-0.032074, 90.287819, -0.032104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.54320312, 542.09453125, 162.223125), 'rotation':(-0.016052, 90.287811, -0.016022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.599375, 530.93628906, 162.22449219), 'rotation':(-0.00412, 90.286934, -0.00412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2423.9216406200003, 864.82049805, 161.79919922), 'rotation':(-0.08963, 90.286903, -0.089905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2423.97777344, 853.66503906, 161.81665039), 'rotation':(-0.089691, 90.28833, -0.089996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.005625, 848.08709961, 161.82539062), 'rotation':(-0.089691, 90.28833, -0.089996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.08984375, 831.35375, 161.85210938), 'rotation':(-0.092621, 90.288383, -0.092926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.11792969, 825.7759375, 161.86119141), 'rotation':(-0.093475, 90.288383, -0.093781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.17382812, 814.62035156, 161.87960938), 'rotation':(-0.095184, 90.288391, -0.09549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.20191406, 809.0425390600001, 161.88894531), 'rotation':(-0.096039, 90.288399, -0.096344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.23, 803.46472656, 161.89833008), 'rotation':(-0.096405, 90.288109, -0.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.2580468799997, 797.88695312, 161.90771484), 'rotation':(-0.096405, 90.288109, -0.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.37011719, 775.57599609, 161.94511719), 'rotation':(-0.09552, 90.287018, -0.095825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.4821875, 753.26507812, 161.98214844), 'rotation':(-0.095154, 90.287659, -0.095459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.51023438, 747.6875, 161.99131836), 'rotation':(-0.094208, 90.287666, -0.094543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.53832031, 742.1098046899999, 162.00045898), 'rotation':(-0.094208, 90.287666, -0.094543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.62230469, 725.37664062, 162.02712891), 'rotation':(-0.090637, 90.287674, -0.090942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.67847656, 714.22130859, 162.0444043), 'rotation':(-0.088074, 90.28775, -0.088348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2424.7065625, 708.64355469, 162.05295898), 'rotation':(-0.088074, 90.28775, -0.088348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.13890625, 371.37980469, 163.67946289), 'rotation':(-0.126556, -90.6138, -0.127136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.13328125, 382.45238281, 163.70363281), 'rotation':(-0.126678, -90.615387, -0.127228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.25242188, 393.52769531, 163.72575195), 'rotation':(-0.107391, -90.614258, -0.107758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.37109375, 404.60304687999997, 163.74493164), 'rotation':(-0.094666, -90.614319, -0.095001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.49, 415.67718749999995, 163.76106445), 'rotation':(-0.081757, -90.614349, -0.082001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.54929688, 421.21507812000004, 163.76833984), 'rotation':(-0.07547, -90.614899, -0.075684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.66820312, 432.29023438, 163.78269531), 'rotation':(-0.07547, -90.614899, -0.075684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.78710938, 443.36578125000005, 163.79576172), 'rotation':(-0.063812, -90.614868, -0.063934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.90578125, 454.44128906000003, 163.80701172), 'rotation':(-0.056122, -90.614868, -0.056213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.9653125, 459.9788671900001, 163.81176758), 'rotation':(-0.048431, -90.613312, -0.048492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2533.02464844, 465.51609375, 163.81632812), 'rotation':(-0.048431, -90.613312, -0.048492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.3359375, 485.13750000000005, 163.82957031), 'rotation':(-0.029968, -90.615662, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2533.13695312, 474.06347656, 163.82273438), 'rotation':(-0.044525, -90.615051, -0.044586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.45117188, 493.20265625, 163.8330957), 'rotation':(-0.029968, -90.615662, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.87378906, 531.1730468799999, 163.83902344), 'rotation':(-0.00592, -90.614716, -0.00592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.93335938, 536.71003906, 163.83959961), 'rotation':(-0.00592, -90.614716, -0.00592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.05226562, 547.78363281, 163.84009766), 'rotation':(0.000266, -90.615448, 0.00027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2534.1115625, 553.3196875, 163.8390332), 'rotation':(0.012554, -90.613342, 0.012553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.23023438, 564.39324219, 163.83558594), 'rotation':(0.01881, -90.614563, 0.018801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2534.42726562, 592.07867188, 163.82508789), 'rotation':(0.025593, -90.614075, 0.025562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.44800781, 597.6160156200001, 163.82209961), 'rotation':(0.030128, -90.614075, 0.030093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.50046875, 603.15234375, 163.81869140999999), 'rotation':(0.034527, -90.614105, 0.034491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.55152344, 608.68675781, 163.81486328), 'rotation':(0.039793, -90.527527, 0.039746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2534.45019531, 675.08099609, 163.74265625), 'rotation':(0.080835, -89.089722, 0.080617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.73632812, 707.53699219, 163.69088867), 'rotation':(0.099892, -88.455231, 0.099558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2533.40699219, 718.59375, 163.67108398), 'rotation':(0.103033, -88.277588, 0.102664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.11230469, 724.1168749999999, 163.6609082), 'rotation':(0.104263, -88.143799, 0.103893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.88550781, 729.64275391, 163.65046875), 'rotation':(0.107152, -88.028229, 0.106762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.46386719, 740.69605469, 163.62874023), 'rotation':(0.112773, -87.797058, 0.112326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.99683594, 751.74804688, 163.60592773), 'rotation':(0.118381, -87.56842, 0.117903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.48363281, 762.79802734, 163.58208008), 'rotation':(0.124009, -87.337189, 0.123466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2530.92578125, 773.84240234, 163.5578418), 'rotation':(0.125389, -87.00351, 0.124838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.66257812, 779.37042969, 163.54571289), 'rotation':(0.125389, -87.00351, 0.124838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2530.16308594, 790.4227343800001, 163.5215625), 'rotation':(0.125081, -86.818054, 0.124529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2529.57375, 801.48236328, 163.49744141), 'rotation':(0.12476, -86.999969, 0.12422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2529.03417969, 812.5464453100001, 163.47336914), 'rotation':(0.124767, -87.197784, 0.124227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2528.78273438, 818.08154297, 163.46161132999998), 'rotation':(0.123039, -87.359009, 0.122512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2528.54273438, 823.61566406, 163.45017578), 'rotation':(0.119576, -87.477631, 0.119084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2528.31542969, 829.15039062, 163.43910156), 'rotation':(0.115977, -87.598785, 0.1155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2528.10007812, 834.68537109, 163.42837891), 'rotation':(0.112514, -87.717346, 0.112072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.70554688, 845.76006836, 163.40795898), 'rotation':(0.102139, -88.078186, 0.101783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.22753906, 856.82751953, 163.38886719), 'rotation':(0.096941, -88.312866, 0.09662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.05980469, 862.36291016, 163.37966796999999), 'rotation':(0.094878, -88.426453, 0.094565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.39964844, 894.6418457, 163.33360352), 'rotation':(0.074101, -89.067139, 0.073898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2526.38964844, 900.17950195, 163.32701172), 'rotation':(0.068206, -89.250214, 0.068049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.41234375, 905.7175293, 163.32066406), 'rotation':(0.065303, -89.412384, 0.065145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.36449219, 911.25415039, 163.31436523), 'rotation':(0.065153, -89.553741, 0.065018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.29371094, 927.86401367, 163.29833984), 'rotation':(0.050325, -89.833374, 0.05023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.30640625, 938.94140625, 163.29177734), 'rotation':(0.030654, -90.108734, 0.030619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.41796875, 955.55493164, 163.28429688), 'rotation':(0.025804, -90.527283, 0.025779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.47949219, 961.09307861, 163.28182617000002), 'rotation':(0.025798, -90.66864, 0.025779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.63453125, 972.16546631, 163.2790332), 'rotation':(0.017772, -90.809479, 0.017774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.71921875, 977.70019531, 163.27921875), 'rotation':(0.000492, -90.876007, 0.000486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2526.80394531, 983.23223877, 163.28008789), 'rotation':(-0.008881, -90.877258, -0.008881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.88867188, 988.76416016, 163.28094726999998), 'rotation':(-0.00885, -90.877258, -0.008881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.22730469, 1010.89208984, 163.28436523), 'rotation':(-0.008728, -90.877258, -0.008698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.42113281, 1033.02355957, 163.29050781), 'rotation':(-0.026917, -90.87561, -0.026947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.50585938, 1038.55615234, 163.29410156), 'rotation':(-0.039185, -90.877563, -0.039246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.70359375, 1049.61889648, 163.30360352), 'rotation':(-0.051056, -90.877563, -0.051147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.0158593799997, 487.64179688, 165.25582031000002), 'rotation':(0.010396, 89.730972, 0.010396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.98976562, 482.09363281000003, 165.25439452999998), 'rotation':(0.010396, 89.730972, 0.010396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.8596093799997, 454.34984375, 165.24580078), 'rotation':(0.017294, 89.731392, 0.017284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.83351562, 448.80132812, 165.24345703), 'rotation':(0.02174, 89.731621, 0.021719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.75511719, 432.15527344, 165.23222656000002), 'rotation':(0.040155, 89.731636, 0.040104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.72925781, 426.6071875, 165.22734375), 'rotation':(0.049259, 89.729752, 0.049168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2617.703125, 421.05835937999996, 165.22212890999998), 'rotation':(0.053931, 89.731102, 0.053832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.625, 404.41277344, 165.20482422), 'rotation':(0.066369, 89.730667, 0.066216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.59886719, 398.86406250000005, 165.19808593999997), 'rotation':(0.071594, 89.730667, 0.071429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.57273438, 393.3153125, 165.19085938), 'rotation':(0.076498, 89.730675, 0.076306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.52074219, 382.21789062000005, 165.17484375), 'rotation':(0.086634, 89.730721, 0.086385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2617.49460938, 376.66917968999996, 165.16611328), 'rotation':(0.091538, 89.730728, 0.091254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.76734375, 675.23503906, 165.13373047000002), 'rotation':(-0.06665, 89.730721, -0.066803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.82128906, 669.86101562, 165.13986328), 'rotation':(-0.065247, 89.730721, -0.065399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.84546875, 664.31707031, 165.14617188), 'rotation':(-0.065247, 89.730721, -0.065399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.81933594, 658.77125, 165.15242188), 'rotation':(-0.064667, 89.731247, -0.064819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.7934375, 653.22546875, 165.15859375), 'rotation':(-0.064667, 89.731239, -0.064819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.68921875, 631.04167969, 165.18181640999998), 'rotation':(-0.057495, 89.730408, -0.057587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.66332031, 625.49589844, 165.18712890999998), 'rotation':(-0.054688, 89.732063, -0.05481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.61132812, 614.4042187499999, 165.19751953), 'rotation':(-0.053162, 89.731041, -0.053253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.5590625, 603.31257812, 165.20748047), 'rotation':(-0.050476, 89.730042, -0.050537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.53320312, 597.76667969, 165.21222656), 'rotation':(-0.048676, 89.732651, -0.048737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.4809375, 586.67488281, 165.22109375), 'rotation':(-0.044891, 89.730019, -0.044952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.45507812, 581.12898438, 165.22525391), 'rotation':(-0.043243, 89.732643, -0.043304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.4028125, 570.03742188, 165.23302734), 'rotation':(-0.03949, 89.732635, -0.039551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.37671875, 564.4919531200001, 165.23662109), 'rotation':(-0.038452, 89.730255, -0.038513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.35082031, 558.94597656, 165.24), 'rotation':(-0.035004, 89.730919, -0.035065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2618.27269531, 542.30851562, 165.24732422), 'rotation':(-0.020477, 89.730904, -0.020477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.7790625, 863.10949219, 164.92076172), 'rotation':(-0.050293, 89.731804, -0.050385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.7009375, 846.47748047, 164.93539062), 'rotation':(-0.050293, 89.729179, -0.050385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.64890625, 835.38958984, 164.945625), 'rotation':(-0.052246, 89.731239, -0.052338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.54492188, 813.21380859, 164.96851562), 'rotation':(-0.059784, 89.731247, -0.059906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.49265625, 802.12566406, 164.98099609000002), 'rotation':(-0.065399, 89.729828, -0.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.4665625, 796.58166016, 164.98732422), 'rotation':(-0.065399, 89.729828, -0.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.3884375, 779.94996094, 165.00666016), 'rotation':(-0.067139, 89.730705, -0.067291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.28441406, 757.77441406, 165.03351562), 'rotation':(-0.07016, 89.731323, -0.070343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2619.12816406, 724.51105469, 165.07431641), 'rotation':(-0.070465, 89.73288, -0.070618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2619.05003906, 707.87939453, 165.09480469), 'rotation':(-0.070557, 89.730385, -0.07074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.89039062, 493.99929688, 166.61132812), 'rotation':(-0.035217, 90.334564, -0.035248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.11695312, 477.40699219, 166.61958984), 'rotation':(-0.026611, 90.334564, -0.026642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2712.18164062, 466.344375, 166.62431641), 'rotation':(-0.024384, 90.334953, -0.024414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.24632812, 455.28257812000004, 166.62837890999998), 'rotation':(-0.017181, 90.336113, -0.017212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2712.27855469, 449.75171875, 166.6290625), 'rotation':(-0.002808, 90.334053, -0.002808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2712.34326172, 438.69000000000005, 166.62859375), 'rotation':(0.00433, 90.336021, 0.004332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.37574219, 433.15863281, 166.62818359000002), 'rotation':(0.00433, 90.333473, 0.004321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.44042969, 422.09613281, 166.62734375), 'rotation':(0.00433, 90.336021, 0.004332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.53734375, 405.5023046900001, 166.62607422000002), 'rotation':(0.00433, 90.336021, 0.004332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.60205078, 394.44109375000005, 166.62367188), 'rotation':(0.021351, 90.336166, 0.021333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.63453125, 388.91015625, 166.62085938), 'rotation':(0.032703, 90.333473, 0.032672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.556875, 382.3046875, 166.61595703), 'rotation':(-0.049744, -89.664917, -0.049835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.51464844, 388.95617187999994, 166.62085938), 'rotation':(-0.044067, -89.663788, -0.044128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.4821875, 394.4871875, 166.62367188), 'rotation':(-0.032684, -89.666504, -0.032745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.41748047, 405.54835937999997, 166.62607422000002), 'rotation':(-0.01001, -89.666534, -0.009979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.38525391, 411.07953124999995, 166.62650391), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.35277344, 416.6109765599999, 166.62693359000002), 'rotation':(-0.004333, -89.666504, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.32007812, 422.14238280999996, 166.62734375), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.28808594, 427.6734765599999, 166.62775391), 'rotation':(-0.004333, -89.666504, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.25585938, 433.2047265599999, 166.62816406000002), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.22339844, 438.73609375, 166.62859375), 'rotation':(-0.004333, -89.666504, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.19117188, 444.26726562, 166.62900391), 'rotation':(-0.004333, -89.66394, -0.004333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.12646484, 455.32859375, 166.62837890999998), 'rotation':(0.0028, -89.665924, 0.002808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2720.02953125, 471.92175781000003, 166.62195312), 'rotation':(0.024486, -89.666565, 0.024466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.99730469, 477.45300781000003, 166.61958984), 'rotation':(0.024384, -89.665039, 0.024369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2720.02978516, 494.04691406, 166.61132812), 'rotation':(0.0309, -89.665405, 0.030863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.82886719, 675.65337891, 166.40589844), 'rotation':(-0.080444, 90.33429, -0.080658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.95410156, 666.89, 166.41820312), 'rotation':(-0.080292, 90.33429, -0.080505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.11988281, 648.01367188, 166.44443359000002), 'rotation':(-0.078674, 90.335495, -0.078888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.15210938, 642.48558594, 166.45199218999997), 'rotation':(-0.078064, 90.33548, -0.078278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.21679688, 631.4294531200001, 166.46689453), 'rotation':(-0.07666, 90.33548, -0.076843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.28125, 620.37324219, 166.48158203), 'rotation':(-0.075409, 90.335487, -0.075592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.31371094, 614.84515625, 166.48882812), 'rotation':(-0.075409, 90.335487, -0.075592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.34619141, 609.3172656200001, 166.49603516), 'rotation':(-0.075012, 90.336395, -0.075195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.41064453, 598.26109375, 166.51005859), 'rotation':(-0.073761, 90.33371, -0.073944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.50757812, 581.676875, 166.53011718999997), 'rotation':(-0.068573, 90.335152, -0.068726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2711.57226562, 570.62085938, 166.54277344), 'rotation':(-0.06601, 90.335152, -0.066162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.66917969, 554.03691406, 166.5609375), 'rotation':(-0.061798, 90.336906, -0.061951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.73363281, 542.9807812500001, 166.57212891), 'rotation':(-0.055786, 90.334221, -0.055908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2711.76611328, 537.4528124999999, 166.57742188), 'rotation':(-0.053986, 90.336899, -0.054077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.67847656, 531.97070312, 166.58251952999998), 'rotation':(0.050127, -89.665771, 0.05004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.64625, 537.49871094, 166.57742188), 'rotation':(0.051964, -89.665802, 0.051872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.51683594, 559.61089844, 166.55507812), 'rotation':(0.061827, -89.663086, 0.061691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.41992188, 576.19464844, 166.53648438), 'rotation':(0.064607, -89.664948, 0.064454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.35546875, 587.25085938, 166.52355468999997), 'rotation':(0.066014, -89.664856, 0.065856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.29078125, 598.3069921900001, 166.51005859), 'rotation':(0.071116, -89.66629, 0.070935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.25855469, 603.83507812, 166.503125), 'rotation':(0.071116, -89.66629, 0.070935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.22632812, 609.3631640599999, 166.49601562), 'rotation':(0.073752, -89.664795, 0.073567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.09691406, 631.47535156, 166.46689453), 'rotation':(0.076013, -89.667023, 0.075818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2719.03222656, 642.5313671900001, 166.45199218999997), 'rotation':(0.077277, -89.66449, 0.077068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.96777344, 653.58757812, 166.43681641), 'rotation':(0.078684, -89.66449, 0.078468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2718.75244141, 708.78753906, 166.35962891), 'rotation':(0.080029, -89.664307, 0.079802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.51976562, 730.20056641, 166.33001953), 'rotation':(0.078199, -89.665588, 0.07798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.4553125, 741.25335938, 166.31507812), 'rotation':(0.076812, -89.664124, 0.076616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.42308594, 746.77972656, 166.30771484000002), 'rotation':(0.076812, -89.664124, 0.076616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2718.26123047, 774.41222656, 166.27197266), 'rotation':(0.07143, -89.666229, 0.071249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.16455078, 790.99158203, 166.25201172), 'rotation':(0.067086, -89.663757, 0.066917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.13207031, 796.51806641, 166.24564453), 'rotation':(0.065522, -89.66626, 0.065371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2718.06761719, 807.57111328, 166.23326172), 'rotation':(0.064129, -89.663757, 0.063981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2718.00292969, 818.62425781, 166.22123047000002), 'rotation':(0.061759, -89.665741, 0.061633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2717.97070312, 824.15082031, 166.21546875), 'rotation':(0.061759, -89.665741, 0.061633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.90601562, 835.20373047, 166.20451172), 'rotation':(0.055167, -89.665771, 0.05506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.84130859, 846.2565918, 166.19435547), 'rotation':(0.051862, -89.664185, 0.051772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2709.86449219, 862.79064453, 166.18046875), 'rotation':(-0.043671, 90.336174, -0.043762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.89671875, 857.26404297, 166.18486328), 'rotation':(-0.043671, 90.336174, -0.043762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.92894531, 851.73760742, 166.18949218999998), 'rotation':(-0.047974, 90.334503, -0.048065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.02587891, 835.15783203, 166.20451172), 'rotation':(-0.05188, 90.335831, -0.051971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.05810547, 829.63134766, 166.20984375), 'rotation':(-0.055176, 90.334229, -0.055267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.09058594, 824.10492188, 166.21546875), 'rotation':(-0.058472, 90.335831, -0.058594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.15503906, 813.05193359, 166.22716797), 'rotation':(-0.061768, 90.334251, -0.06189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.21972656, 801.99853516, 166.23939453), 'rotation':(-0.063385, 90.334534, -0.063538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.28441406, 790.9457421899999, 166.25201172), 'rotation':(-0.065521, 90.333733, -0.065674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.31664062, 785.419375, 166.25853515999998), 'rotation':(-0.067078, 90.336235, -0.06723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.44580078, 763.31347656, 166.28595703), 'rotation':(-0.072845, 90.336258, -0.073029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2710.47828125, 757.78679688, 166.29316406), 'rotation':(-0.074249, 90.333771, -0.074432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.63964844, 730.15466797, 166.33001953), 'rotation':(-0.076813, 90.334381, -0.077026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2710.671875, 724.62830078, 166.33755859000001), 'rotation':(-0.078186, 90.335854, -0.0784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2710.70605469, 713.5772656199999, 166.35289062), 'rotation':(-0.079376, 90.334396, -0.07959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.65015625, 708.05175781, 166.36058594), 'rotation':(-0.079926, 90.335693, -0.080139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2717.32886719, 933.94726562, 166.14769531000002), 'rotation':(-9.2e-05, -89.665527, -9.2e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.26441406, 945.00140625, 166.14769531000002), 'rotation':(-9.2e-05, -89.664124, -9.2e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.10277344, 972.63763428, 166.14808594), 'rotation':(-0.004181, -89.665375, -0.004181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.03808594, 983.69238281, 166.15087891), 'rotation':(-0.020477, -89.662964, -0.020477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2717.00585938, 989.21984863, 166.15339844), 'rotation':(-0.028534, -89.665344, -0.028564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.97339844, 994.74768066, 166.15640625), 'rotation':(-0.028534, -89.665344, -0.028564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.74730469, 1033.43908691, 166.1853125), 'rotation':(-0.06012, -89.665222, -0.060242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.8671875, 1033.39318848, 166.1853125), 'rotation':(0.071177, 90.336411, 0.071017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.89941406, 1027.8659668, 166.17951172000002), 'rotation':(0.060119, 90.334763, 0.059989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.931875, 1022.33843994, 166.17441406), 'rotation':(0.060119, 90.334763, 0.059989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.99632812, 1011.28387451, 166.16609375), 'rotation':(0.038078, 90.334724, 0.038037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.22265625, 972.59161377, 166.14808594), 'rotation':(0.012247, 90.334602, 0.012239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.25488281, 967.06378174, 166.14773438), 'rotation':(0.004187, 90.33461, 0.004184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.28734375, 961.53668213, 166.14771484000002), 'rotation':(7.5e-05, 90.334488, 8.8e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2709.31957031, 956.00958008, 166.14771484000002), 'rotation':(7.5e-05, 90.334488, 8.8e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.41650391, 939.42834473, 166.14769531000002), 'rotation':(8.9e-05, 90.335884, 8.4e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.48095703, 928.37408203, 166.14769531000002), 'rotation':(7.5e-05, 90.334488, 8.8e-05), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.5134375, 922.8463134799999, 166.14826172000002), 'rotation':(-0.006683, 90.335136, -0.006683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2709.578125, 911.7909570300001, 166.15238281), 'rotation':(-0.019745, 90.335152, -0.019775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.34057617, 379.40539062000005, 170.16193359000002), 'rotation':(0.09634, -90.588562, 0.096022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.51416016, 396.28710937999995, 170.13277344), 'rotation':(0.10233, -90.588989, 0.101971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2982.57177734, 401.91417968999997, 170.12251952999998), 'rotation':(0.104939, -90.586212, 0.104547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.62963867, 407.54148437999993, 170.11203125), 'rotation':(0.107343, -90.588989, 0.106953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.8034668, 424.42285156, 170.07892578), 'rotation':(0.115765, -90.586304, 0.115301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.77026367, 446.91820312000004, 170.03230469), 'rotation':(0.121782, -90.098206, 0.121261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2982.63574219, 469.42234375, 169.98140625), 'rotation':(0.133899, -89.417725, 0.133278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.36791992, 486.30480468999997, 169.94136719), 'rotation':(0.136706, -88.920471, 0.136059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.24731445, 491.93914062000005, 169.92769531000002), 'rotation':(0.136706, -88.920471, 0.136059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2982.11450195, 497.56644531, 169.91386719), 'rotation':(0.140128, -88.689545, 0.13944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2981.79516602, 508.81671875, 169.88541016), 'rotation':(0.146753, -88.229309, 0.146001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2981.61499023, 514.45039062, 169.87091797000002), 'rotation':(0.146753, -88.229309, 0.146001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2981.20507812, 525.6988671900001, 169.84173828), 'rotation':(0.148447, -87.815338, 0.14768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2980.97387695, 531.3236718799999, 169.82705077999998), 'rotation':(0.149458, -87.59906, 0.148683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2980.73071289, 536.95433594, 169.81228516), 'rotation':(0.149458, -87.59906, 0.148683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2979.6003418, 559.4371874999999, 169.75193359000002), 'rotation':(0.155271, -86.902863, 0.154453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2979.27758789, 565.0540625, 169.7365625), 'rotation':(0.15637, -86.694214, 0.155508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2978.94116211, 570.67039062, 169.72121094), 'rotation':(0.15635, -86.527313, 0.155509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2977.98120117, 587.5194140599999, 169.67511718999998), 'rotation':(0.156357, -86.098511, 0.15551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2977.16650391, 598.735, 169.64443359), 'rotation':(0.15635, -85.809784, 0.155506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2976.73608398, 604.33941406, 169.62908202999998), 'rotation':(0.156186, -85.666718, 0.155329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2975.45239258, 621.18644531, 169.583125), 'rotation':(0.155175, -85.755493, 0.154334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.67382812, 632.4395312500001, 169.55400391), 'rotation':(0.14715, -86.075867, 0.146398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.96118164, 643.7008593799999, 169.52654297), 'rotation':(0.139295, -86.396118, 0.138624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.31420898, 654.97441406, 169.50066406000002), 'rotation':(0.127178, -86.873657, 0.126619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.0144043, 660.60945312, 169.48824219), 'rotation':(0.125395, -87.013763, 0.124851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2964.43115234, 671.9371874999999, 169.46355469), 'rotation':(-0.113312, 92.50412, -0.11377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.82885742, 660.6941406200001, 169.48714843999997), 'rotation':(-0.122253, 92.848267, -0.122772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.12646484, 655.0775, 169.49945312), 'rotation':(-0.124634, 92.990799, -0.125183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2966.47338867, 632.63300781, 169.55216797), 'rotation':(-0.142334, 93.76442, -0.143066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2966.85107422, 627.025625, 169.56634766), 'rotation':(-0.14624, 93.923615, -0.147003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2967.65527344, 615.8180468799999, 169.59595703), 'rotation':(-0.154236, 94.244637, -0.15506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2968.08300781, 610.21699219, 169.61123047), 'rotation':(-0.155396, 94.325706, -0.156219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.95288086, 599.00105469, 169.64199219), 'rotation':(-0.157257, 94.477531, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2969.37133789, 593.37574219, 169.65746094), 'rotation':(-0.157257, 94.186981, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.8894043, 570.86402344, 169.71931641), 'rotation':(-0.157257, 93.614532, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2971.55371094, 559.6065625, 169.75023438), 'rotation':(-0.157288, 93.305969, -0.158142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.43359375, 542.6839453099999, 169.79609375), 'rotation':(-0.154266, 92.864075, -0.155121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.93798828, 531.4117578099999, 169.8259375), 'rotation':(-0.152252, 92.633492, -0.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.38598633, 520.13023438, 169.85542969), 'rotation':(-0.149323, 92.183464, -0.150085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.58374023, 514.48304688, 169.87013672), 'rotation':(-0.14917, 91.9869, -0.149963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.76538086, 508.83992187999996, 169.88472656000002), 'rotation':(-0.14917, 91.9869, -0.149963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.70947266, 458.03691405999996, 170.00757812), 'rotation':(-0.132141, 90.445862, -0.132751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.73510742, 452.3968359400001, 170.02027343999998), 'rotation':(-0.129791, 90.308952, -0.130341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.74023438, 441.11460937999993, 170.04476562), 'rotation':(-0.122498, 89.901237, -0.123016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.68237305, 429.83472656000004, 170.06816406000002), 'rotation':(-0.117401, 89.630409, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.63061523, 424.20179687999996, 170.07955077999998), 'rotation':(-0.116272, 89.487808, -0.11676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.34130859, 396.07484375, 170.13328125), 'rotation':(-0.10495, 89.411018, -0.105316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.28344727, 390.44984375, 170.14324219), 'rotation':(-0.102356, 89.410988, -0.102692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.16796875, 379.19984375, 170.16242188), 'rotation':(-0.097504, 89.410995, -0.097839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.43652344, 837.51085938, 169.30771484000002), 'rotation':(0.003893, 89.116989, 0.003894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.26538086, 826.41234375, 169.30716797000002), 'rotation':(0.001127, 89.116188, 0.001129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.09399414, 815.31396484, 169.30841797000002), 'rotation':(-0.010773, 89.116188, -0.010742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.92285156, 804.21539062, 169.31175781000002), 'rotation':(-0.019623, 89.116966, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.8371582, 798.66638672, 169.31367188000002), 'rotation':(-0.019623, 89.116966, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.75170898, 793.11724609, 169.31560547), 'rotation':(-0.019592, 89.115143, -0.019623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2962.49291992, 770.92578125, 169.32716797), 'rotation':(-0.03833, 89.598129, -0.038391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.48339844, 748.73474609, 169.34642578), 'rotation':(-0.057007, 90.267006, -0.057129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.57592773, 737.63757812, 169.35841797), 'rotation':(-0.063507, 90.533195, -0.06366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.83398438, 721.0063476600001, 169.37978515999998), 'rotation':(-0.080414, 91.1334, -0.080658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2962.95166016, 715.46289062, 169.3878125), 'rotation':(-0.084595, 91.281372, -0.084869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.96777344, 709.92865234, 169.39658203), 'rotation':(0.091586, -88.430237, 0.09129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.67211914, 732.11224609, 169.36519531000002), 'rotation':(0.072496, -89.165802, 0.07231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.60180664, 737.6582617199999, 169.35849609000002), 'rotation':(0.068268, -89.314697, 0.068122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.50854492, 748.75408203, 169.34644531), 'rotation':(0.059675, -89.612366, 0.059552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2970.48803711, 754.30394531, 169.34095703), 'rotation':(0.055488, -89.850952, 0.055377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.49121094, 765.39898438, 169.33121093999998), 'rotation':(0.047121, -90.124634, 0.047057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2970.6940918, 787.59435547, 169.31769531), 'rotation':(0.02603, -90.814819, 0.02601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.20532227, 820.83947266, 169.3075), 'rotation':(0.010758, -90.88382, 0.010759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.29077148, 826.38, 169.30716797000002), 'rotation':(0.004979, -90.883789, 0.004982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.3762207, 831.92029297, 169.30734375), 'rotation':(-0.001129, -90.88382, -0.001129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.46166992, 837.46026367, 169.30771484000002), 'rotation':(-0.003906, -90.883026, -0.003906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2971.57324219, 854.08282227, 169.30884766), 'rotation':(-0.003998, -90.884796, -0.003998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2966.07470703, 1008.59387207, 169.44416016), 'rotation':(0.098662, 89.116859, 0.09832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.98925781, 1003.04907227, 169.43519531), 'rotation':(0.098662, 89.116859, 0.09832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.90356445, 997.50384521, 169.42652343999998), 'rotation':(0.090138, 89.116814, 0.089864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.64697266, 980.87005615, 169.40205078), 'rotation':(0.082516, 89.117088, 0.082282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.56152344, 975.32537842, 169.39443359), 'rotation':(0.082516, 89.117088, 0.082282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.390625, 964.23620605, 169.38029297), 'rotation':(0.075692, 89.117065, 0.075487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2965.30493164, 958.69170898, 169.37363281), 'rotation':(0.068937, 89.115654, 0.06877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2965.1340332, 947.60199219, 169.36164062), 'rotation':(0.062189, 89.117035, 0.062058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.96313477, 936.51245117, 169.35054688), 'rotation':(0.055687, 89.116264, 0.05558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.87768555, 930.96783203, 169.34529297), 'rotation':(0.055687, 89.116264, 0.05558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2964.70654297, 919.87866211, 169.33599609), 'rotation':(0.049355, 89.116257, 0.049275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.62109375, 914.33428711, 169.33181641), 'rotation':(0.043112, 89.117683, 0.043057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.53564453, 908.78960938, 169.32808594), 'rotation':(0.043112, 89.117683, 0.043057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2964.36450195, 897.70007812, 169.32125), 'rotation':(0.033598, 89.116707, 0.033561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2972.32958984, 903.1319531199999, 169.32453125), 'rotation':(-0.0336, -90.883301, -0.03363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.50048828, 914.22051758, 169.33183594), 'rotation':(-0.036896, -90.883728, -0.036926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.58618164, 919.76464844, 169.33599609), 'rotation':(-0.043121, -90.883759, -0.043182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2972.67163086, 925.30902344, 169.34050781000002), 'rotation':(-0.043121, -90.883759, -0.043182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.09912109, 953.03100586, 169.36759766), 'rotation':(-0.058777, -90.883301, -0.058899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.18457031, 958.57549805, 169.37363281), 'rotation':(-0.062195, -90.884369, -0.062347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2973.27001953, 964.11956787, 169.3803125), 'rotation':(-0.068939, -90.882935, -0.069092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.35571289, 969.66394043, 169.38712891), 'rotation':(-0.068939, -90.882935, -0.069092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.44116211, 975.20800781, 169.39445312), 'rotation':(-0.075684, -90.882935, -0.075897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.52661133, 980.75244141, 169.40205078), 'rotation':(-0.075684, -90.882935, -0.075897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2973.78320312, 997.38537598, 169.42654297), 'rotation':(-0.085938, -90.882812, -0.086182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.21069336, 1025.10766602, 169.47441406000002), 'rotation':(-0.107269, -90.883118, -0.107666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.45166016, 1036.19213867, 169.49707031000003), 'rotation':(-0.120026, -90.881989, -0.120514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3152.83056641, 380.999375, 172.22105469), 'rotation':(0.183486, -89.100708, 0.182316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3152.47314453, 397.57378905999997, 172.16806641), 'rotation':(0.182858, -89.101654, 0.181691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3152.38647461, 403.09984375, 172.15056640999998), 'rotation':(0.181628, -89.100037, 0.180484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.95288086, 430.73058593999997, 172.06400391), 'rotation':(0.178247, -89.10141, 0.177148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3151.60620117, 452.8353125, 171.99572265999998), 'rotation':(0.173432, -89.100037, 0.172386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.17285156, 480.4664453099999, 171.9146875), 'rotation':(0.165577, -89.100525, 0.164622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.99951172, 491.51878905999996, 171.88296875), 'rotation':(0.163474, -89.101379, 0.162544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3152.98706055, 373.07164062000004, 172.24646484000002), 'rotation':(0.183636, -89.100708, 0.182479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.11914062, 491.46152344, 171.88277344), 'rotation':(-0.159485, 90.898537, -0.16037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.20581055, 485.92921875, 171.89857422), 'rotation':(-0.163483, 90.898613, -0.164398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.46630859, 469.33179687999996, 171.94652344), 'rotation':(-0.165588, 90.899467, -0.166534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.63989258, 458.26703124999995, 171.97904297000002), 'rotation':(-0.17041, 90.897911, -0.171417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.7265625, 452.73460937999994, 171.99566406000002), 'rotation':(-0.17041, 90.897911, -0.171417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.90014648, 441.6695703099999, 172.02958984), 'rotation':(-0.176575, 90.897957, -0.177704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.98681641, 436.13734375, 172.04679688), 'rotation':(-0.178253, 90.900055, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.07373047, 430.60503905999997, 172.06400391), 'rotation':(-0.178253, 90.900055, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.16040039, 425.07269531, 172.08123047), 'rotation':(-0.178253, 90.898567, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.24731445, 419.54027343999996, 172.09847656000002), 'rotation':(-0.178253, 90.898567, -0.179352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.73706055, 386.3471875, 172.20353516), 'rotation':(-0.182831, 90.898323, -0.184021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.40209961, 529.6129296900001, 171.78080078), 'rotation':(0.146248, -89.100342, 0.145492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.87988281, 562.9096093799999, 171.69980468999998), 'rotation':(0.133325, -89.10022, 0.132706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.61865234, 579.5582421900001, 171.663125), 'rotation':(0.124685, -89.100281, 0.124156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.53149414, 585.10773438, 171.65125), 'rotation':(0.123326, -89.101227, 0.122799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.65112305, 585.0569531200001, 171.65109375), 'rotation':(-0.120972, 90.899162, -0.12149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.91308594, 568.35625, 171.68726562), 'rotation':(-0.124695, 90.899742, -0.125244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3142.00048828, 562.7893750000001, 171.69978516), 'rotation':(-0.130341, 90.897118, -0.13092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.08764648, 557.22265625, 171.71261718999997), 'rotation':(-0.133331, 90.89978, -0.133942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.17504883, 551.6558984400001, 171.72574218999998), 'rotation':(-0.136139, 90.89978, -0.13678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.34960938, 540.5222656200001, 171.75287109), 'rotation':(-0.141937, 90.899818, -0.142639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.43701172, 534.955625, 171.766875), 'rotation':(-0.144775, 90.899841, -0.145508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.52416992, 529.38847656, 171.78107422000002), 'rotation':(-0.146118, 90.899544, -0.146851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.80053711, 639.68488281, 171.54994141), 'rotation':(-0.092865, 90.8106, -0.09317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.58862305, 656.35484375, 171.5246875), 'rotation':(-0.077728, 90.606339, -0.077942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.5300293, 661.9102734400001, 171.51716797), 'rotation':(-0.070099, 90.504242, -0.070251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.47924805, 667.4665625, 171.51021484), 'rotation':(-0.066376, 90.40844, -0.066498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.39257812, 678.58117188, 171.49705078), 'rotation':(-0.062317, 90.311211, -0.062439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.36083984, 684.14007812, 171.4909375), 'rotation':(-0.062317, 90.311211, -0.062439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.93701172, 622.9957812499999, 171.57826172), 'rotation':(0.099106, -89.101562, 0.09877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.85009766, 628.55144531, 171.56871094), 'rotation':(0.099106, -89.101562, 0.09877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.76318359, 634.106875, 171.55933593999998), 'rotation':(0.096804, -89.10144, 0.096475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.68188477, 639.66339844, 171.55015625), 'rotation':(0.096886, -89.118286, 0.096557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.53735352, 650.7808984400001, 171.53283202999998), 'rotation':(0.085507, -89.291443, 0.08525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.24145508, 684.12810547, 171.49099609), 'rotation':(0.066526, -89.590576, 0.066358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.23706055, 733.07097656, 171.45402344), 'rotation':(0.030114, -90.1828, 0.030078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.34008789, 744.13152344, 171.44886719), 'rotation':(0.030019, -90.276794, 0.029982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.50244141, 755.19548828, 171.4465625), 'rotation':(0.00517, -90.478455, 0.005162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.55322266, 760.72705078, 171.44650391), 'rotation':(-0.003021, -90.55835, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.546875, 766.2580468799999, 171.44679688), 'rotation':(-0.003021, -90.620087, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.65087891, 777.31580078, 171.44738281000002), 'rotation':(-0.003174, -90.648407, -0.003143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.70263672, 782.84423828, 171.44769531000003), 'rotation':(-0.003021, -90.650452, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3148.75439453, 788.37255859, 171.44796875), 'rotation':(-0.003021, -90.648438, -0.003021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3148.96606445, 810.486875, 171.4509375), 'rotation':(-0.014557, -90.648376, -0.014587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.02880859, 816.01544922, 171.45271484), 'rotation':(-0.014557, -90.648376, -0.014587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.09155273, 821.54371094, 171.45484375), 'rotation':(-0.022156, -90.649963, -0.022186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.15405273, 827.07208984, 171.45767578), 'rotation':(-0.029724, -90.648346, -0.029785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3149.2878418, 838.12890625, 171.46396484000002), 'rotation':(-0.03363, -90.649384, -0.033691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.39477539, 843.65625, 171.46738281), 'rotation':(-0.035828, -90.648956, -0.035858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.50146484, 849.18365234, 171.47115234), 'rotation':(-0.035828, -90.648956, -0.035858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3149.61328125, 856.15478516, 171.47626953), 'rotation':(-0.040131, -90.648956, -0.040192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.50512695, 860.3215332, 171.47945312), 'rotation':(0.048972, 89.351044, 0.048896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3141.42773438, 849.26068359, 171.47115234), 'rotation':(0.040127, 89.349297, 0.040076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3141.35986328, 838.20043945, 171.46394531), 'rotation':(0.035804, 89.351013, 0.035771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.30834961, 832.67035156, 171.46064453), 'rotation':(0.033639, 89.350594, 0.033595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3141.27368164, 827.13947266, 171.45765625), 'rotation':(0.033639, 89.350594, 0.033595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.96044922, 799.48957031, 171.44880859), 'rotation':(0.006885, 89.350029, 0.006883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.89770508, 793.95904297, 171.44828125), 'rotation':(0.006885, 89.350029, 0.006883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.83520508, 788.4292578100001, 171.44796875), 'rotation':(0.003026, 89.351578, 0.003033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.77246094, 782.89947266, 171.44767578), 'rotation':(0.003026, 89.351578, 0.003033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.70996094, 777.36957031, 171.44738281000002), 'rotation':(0.003033, 89.349548, 0.00303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.58642578, 766.31, 171.44681641), 'rotation':(0.003149, 89.351578, 0.003159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.52954102, 760.78107422, 171.44650391), 'rotation':(0.003012, 89.381371, 0.003018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3140.47753906, 755.25238281, 171.4465625), 'rotation':(0.003019, 89.440292, 0.003013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.39331055, 744.19695312, 171.44884765999998), 'rotation':(-0.02179, 89.625298, -0.02179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3140.33227539, 733.1394726599999, 171.45400390999998), 'rotation':(-0.029938, 89.723869, -0.029968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.10253906, 899.33587891, 171.51691406), 'rotation':(-0.060638, -90.649414, -0.06076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.23120117, 914.71880859, 171.53519531), 'rotation':(-0.071198, -90.649445, -0.071381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.25415039, 920.2491455100001, 171.54234375), 'rotation':(-0.071198, -90.649445, -0.071381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.39794922, 936.8392334, 171.56503906), 'rotation':(-0.080475, -90.648499, -0.080688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.5859375, 953.42950195, 171.58945312), 'rotation':(-0.085785, -90.65094, -0.08606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.6484375, 958.95941406, 171.59810547), 'rotation':(-0.088531, -90.648499, -0.088806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3150.77392578, 970.01959229, 171.61617188), 'rotation':(-0.094025, -90.648468, -0.09433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.83642578, 975.54974365, 171.62558593999998), 'rotation':(-0.096771, -90.650909, -0.097107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3150.96191406, 986.61004639, 171.64494141), 'rotation':(-0.1008, -90.649414, -0.101166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3151.0246582, 992.14050293, 171.65484375), 'rotation':(-0.1008, -90.649414, -0.101166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3151.27490234, 1014.26074219, 171.69734375), 'rotation':(-0.115204, -90.648834, -0.115692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.33764648, 1019.79101562, 171.70888672), 'rotation':(-0.115204, -90.648834, -0.115692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3151.57275391, 1030.84643555, 171.73253906000002), 'rotation':(-0.123962, -90.649353, -0.124512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3143.50390625, 1026.07751465, 171.72205078), 'rotation':(0.123954, 89.350632, 0.123422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.33227539, 1008.81787109, 171.68621094), 'rotation':(0.115205, 89.351158, 0.114742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3143.14428711, 992.22650146, 171.65484375), 'rotation':(0.103689, 89.35112, 0.103309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.89355469, 970.10424805, 171.61617188), 'rotation':(0.096777, 89.351532, 0.09645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.45507812, 931.39105469, 171.55732422), 'rotation':(0.080466, 89.351471, 0.080246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.38793945, 925.86138672, 171.54970702999998), 'rotation':(0.079018, 89.351974, 0.078815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.28564453, 920.33178711, 171.54232422), 'rotation':(0.076437, 89.350548, 0.076241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3142.16455078, 913.79449219, 171.53394531), 'rotation':(0.076437, 89.350548, 0.076241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.41648438, 498.44351562, 174.23935547000002), 'rotation':(-0.111938, 90.147209, -0.112366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.43066406, 492.89144531, 174.25072265999998), 'rotation':(-0.116364, 90.144501, -0.116852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.45898438, 481.78722656, 174.27472656), 'rotation':(-0.125214, 90.144524, -0.125763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.47289062, 476.23542969000005, 174.28707031000002), 'rotation':(-0.127228, 90.144951, -0.127808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.55710938, 442.92320312000004, 174.36699219), 'rotation':(-0.150757, 90.144836, -0.15152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.6271875, 415.16273437999996, 174.44224609), 'rotation':(-0.160126, 90.146751, -0.161011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.64109375, 409.61070312000004, 174.45820312), 'rotation':(-0.16391, 90.14402, -0.164856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.683125, 392.95484375, 174.50857422), 'rotation':(-0.175812, 90.144089, -0.17691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.54957031, 398.52613281000004, 174.49138672), 'rotation':(0.175816, -89.855896, 0.174739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.52148438, 409.63, 174.45820312), 'rotation':(0.167879, -89.855957, 0.166893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.47925781, 426.28644531, 174.41160156), 'rotation':(0.155967, -89.853271, 0.155131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.45117188, 437.39015625, 174.38173827999998), 'rotation':(0.154157, -89.854126, 0.153338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.4372656200003, 442.9425, 174.36699219), 'rotation':(0.154157, -89.854126, 0.153338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.39527344, 459.59851562000006, 174.32509765999998), 'rotation':(0.137362, -89.855194, 0.13671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.3671875, 470.70300781000003, 174.29941406), 'rotation':(0.130627, -89.855255, 0.130021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.339375, 481.80664062000005, 174.27472656), 'rotation':(0.12724, -89.855042, 0.126679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.32519531, 487.35890625, 174.26253906000002), 'rotation':(0.125225, -89.855438, 0.124679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.296875, 498.46289062000005, 174.23935547000002), 'rotation':(0.116373, -89.855469, 0.115908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.20777344, 581.2189843799999, 174.11542968999998), 'rotation':(-0.059784, 90.143173, -0.059906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.23585938, 570.04316406, 174.12755859), 'rotation':(-0.062012, 90.145576, -0.062134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.25, 564.455625, 174.13400391), 'rotation':(-0.06601, 90.143997, -0.066162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.27808594, 553.28046875, 174.14800781000002), 'rotation':(-0.073883, 90.145546, -0.074066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.29222656, 547.69261719, 174.15585938), 'rotation':(-0.081726, 90.144043, -0.08197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.14429688, 558.88777344, 174.14082031), 'rotation':(0.073855, -89.854462, 0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.13039062, 564.47550781, 174.13400391), 'rotation':(0.073855, -89.854462, 0.073669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3349.07375, 586.82660156, 174.10962891), 'rotation':(0.059778, -89.856812, 0.059656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3341.0971875, 624.8770312500001, 174.08136718999998), 'rotation':(-0.03125, 90.145073, -0.031281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3341.04101562, 647.2033593799999, 174.07125), 'rotation':(-0.011658, 90.144417, -0.011658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.95042969, 663.94683594, 174.06990234), 'rotation':(0.000212, 90.146111, 0.000223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.8903906200003, 669.5276562500001, 174.06992188), 'rotation':(0.000212, 90.146111, 0.000223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.82691406, 680.69177734, 174.06994140999998), 'rotation':(0.000109, 90.144318, 0.000116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.97875, 675.75212891, 174.06992188), 'rotation':(-0.000214, -89.855652, -0.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.95921875, 669.54796875, 174.06992188), 'rotation':(-0.000244, -89.853882, -0.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.89527344, 658.38597656, 174.06986328), 'rotation':(0.003791, -89.855591, 0.003786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.90722656, 652.8049218799999, 174.07021484), 'rotation':(0.011652, -89.85556, 0.011644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.92140625, 647.22332031, 174.07125), 'rotation':(0.01935, -89.855591, 0.019358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.9353125, 641.64171875, 174.07298828), 'rotation':(0.027218, -89.85556, 0.027204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.97753906, 624.8968359400001, 174.08136718999998), 'rotation':(0.031241, -89.854919, 0.031205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.7267968799997, 724.27105469, 174.0775), 'rotation':(-0.025299, -89.855194, -0.02533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.71265625, 729.8184179699999, 174.08025390999998), 'rotation':(-0.028809, -89.855316, -0.028809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.68457031, 740.91345703, 174.08609375), 'rotation':(-0.030121, -89.853485, -0.030182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.67066406, 746.46099609, 174.08939453), 'rotation':(-0.032806, -89.85611, -0.032837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.64671875, 757.55773438, 174.09677734000002), 'rotation':(-0.041138, -89.853455, -0.041168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.61449219, 768.65076172, 174.10529297000002), 'rotation':(-0.046448, -89.85611, -0.046539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.54445312, 796.38849609, 174.13033202999998), 'rotation':(-0.056305, -89.855225, -0.056427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.474375, 824.12580078, 174.16083984), 'rotation':(-0.067566, -89.855194, -0.067749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.46046875, 829.67316406, 174.1675), 'rotation':(-0.068787, -89.855865, -0.068939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.49097656, 838.36834961, 174.17816406000003), 'rotation':(-0.071564, -89.853302, -0.071777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.53027344, 853.3190332, 174.19757812), 'rotation':(-0.076935, -89.856049, -0.077148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.51515625, 859.3574804699999, 174.20582031), 'rotation':(-0.078857, -89.853271, -0.079071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.36671875, 862.93787109, 174.21083984), 'rotation':(0.080576, 90.143974, 0.080345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.3825781200003, 856.60625977, 174.20205077999998), 'rotation':(0.078841, 90.146729, 0.078629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.48875, 840.23779297, 174.18050781000002), 'rotation':(0.073308, 90.146713, 0.07312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.58007812, 829.65332031, 174.1675), 'rotation':(0.069682, 90.143913, 0.069518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.59421875, 824.10607422, 174.16083984), 'rotation':(0.068773, 90.146126, 0.068615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.65039062, 801.91601562, 174.13595703), 'rotation':(0.060925, 90.14476, 0.060785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.67847656, 790.8211718800001, 174.12494141), 'rotation':(0.056315, 90.144753, 0.056202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.69238281, 785.2737500000001, 174.11978516), 'rotation':(0.053918, 90.144745, 0.053822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.72046875, 774.17822266, 174.10996093999998), 'rotation':(0.050557, 90.144691, 0.050455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.74828125, 763.08337891, 174.10089843999998), 'rotation':(0.046452, 90.143875, 0.046375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.77660156, 751.9885937500001, 174.09294922), 'rotation':(0.03829, 90.143852, 0.038236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.79027344, 746.4410937499999, 174.08939453), 'rotation':(0.035456, 90.143867, 0.035414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.83226562, 729.79851562, 174.08025390999998), 'rotation':(0.028782, 90.14463, 0.028772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.84644531, 724.25121094, 174.0775), 'rotation':(0.028782, 90.14463, 0.028772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.77, 718.70740234, 174.075), 'rotation':(0.025313, 90.144806, 0.025293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.06421875, 1017.6427002, 174.47060547), 'rotation':(0.10735, 90.145081, 0.106943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.11960938, 1012.0880127, 174.46021484000002), 'rotation':(0.10735, 90.145081, 0.106943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.14769531, 1000.97406006, 174.43960938), 'rotation':(0.105786, 90.143654, 0.105398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.17578125, 989.86029053, 174.41925781), 'rotation':(0.104611, 90.145363, 0.104234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.1896875, 984.30334473, 174.40921875), 'rotation':(0.103648, 90.14537, 0.103278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.20359375, 978.74639893, 174.39917968999998), 'rotation':(0.103648, 90.14537, 0.103278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.24585938, 962.07537842, 174.36939453), 'rotation':(0.101476, 90.144127, 0.101117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.25976562, 956.51836914, 174.35962891), 'rotation':(0.100452, 90.144119, 0.100092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.27390625, 950.96148438, 174.35), 'rotation':(0.099407, 90.146484, 0.099067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.28785156, 945.40454102, 174.34042968999998), 'rotation':(0.098232, 90.144119, 0.097894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.30199219, 939.84753418, 174.33095702999998), 'rotation':(0.097207, 90.144112, 0.096868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3340.31347656, 912.06415039, 174.28490234), 'rotation':(0.093546, 90.14505, 0.093244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3340.27074219, 900.94818359, 174.26722656), 'rotation':(0.089667, 90.142967, 0.089392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.41015625, 900.96863281, 174.26722656), 'rotation':(-0.087738, -89.85495, -0.087982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.31128906, 912.08410156, 174.28490234), 'rotation':(-0.091614, -89.854919, -0.091888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.224375, 923.19628906, 174.303125), 'rotation':(-0.094513, -89.855042, -0.094818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.19628906, 934.31030273, 174.32160156), 'rotation':(-0.095123, -89.853516, -0.095459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.18238281, 939.86737305, 174.33095702999998), 'rotation':(-0.096161, -89.855865, -0.096497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.15429688, 950.98120117, 174.35), 'rotation':(-0.098236, -89.853516, -0.098572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.098125, 973.20892334, 174.38919922000002), 'rotation':(-0.102509, -89.855835, -0.102875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.08398438, 978.76605225, 174.39917968999998), 'rotation':(-0.103088, -89.854736, -0.103455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.06984375, 984.32305908, 174.40921875), 'rotation':(-0.103088, -89.854736, -0.103455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.05589844, 989.88006592, 174.41925781), 'rotation':(-0.103668, -89.856323, -0.104034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.04199219, 995.43695068, 174.42939453), 'rotation':(-0.104614, -89.854614, -0.105011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.01390625, 1006.55078125, 174.44986328), 'rotation':(-0.105774, -89.854614, -0.106171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.0, 1012.10784912, 174.46021484000002), 'rotation':(-0.10675, -89.856323, -0.107147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3348.02734375, 1017.66278076, 174.47060547), 'rotation':(-0.10675, -89.856323, -0.107147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.0959375, 1023.21868896, 174.48099609000002), 'rotation':(-0.107361, -89.854919, -0.107758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3619.8259375, 499.9884375, 177.57283203), 'rotation':(-0.002625, 91.01828, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.92480469, 494.43121094, 177.57363281000002), 'rotation':(-0.002625, 91.01828, -0.002625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.0234375, 488.87472656, 177.575625), 'rotation':(-0.020508, 91.016693, -0.020538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.12207031, 483.31726562000006, 177.57826172), 'rotation':(-0.020508, 91.016693, -0.020538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.2209375, 477.76074219, 177.58113281), 'rotation':(-0.02948, 91.018509, -0.02951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.41820312, 466.6468359400001, 177.58708984), 'rotation':(-0.029572, 91.01693, -0.029602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.51683594, 461.0903125, 177.59042968999998), 'rotation':(-0.034424, 91.017616, -0.034485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.714375, 449.9765625, 177.599375), 'rotation':(-0.044403, 91.017632, -0.044464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.91164062, 438.86316406000003, 177.61068359), 'rotation':(-0.064392, 91.01767, -0.064545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3621.01050781, 433.30578125, 177.61703125), 'rotation':(-0.064392, 91.01767, -0.064545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.30664062, 416.63523437999993, 177.63763672000002), 'rotation':(-0.075226, 91.017471, -0.075409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3621.40527344, 411.07824218999997, 177.64529297), 'rotation':(-0.075226, 91.017471, -0.075409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.60253906, 399.96484375, 177.66316406), 'rotation':(-0.099213, 91.01754, -0.099548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.70117188, 394.40789062, 177.67318359), 'rotation':(-0.099213, 91.01754, -0.099548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.79980469, 388.85144531000003, 177.68398438), 'rotation':(-0.111267, 91.017593, -0.111694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3629.7053125, 387.84691406, 177.68623047), 'rotation':(0.117158, -88.982941, 0.116693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.48023438, 400.10414062000007, 177.66316406), 'rotation':(0.111264, -88.982391, 0.110842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.3828125, 405.66164062000007, 177.65375), 'rotation':(0.099215, -88.982452, 0.098876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.28417969, 411.21808594000004, 177.64529297), 'rotation':(0.087256, -88.980774, 0.087003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3629.18554688, 416.7750390599999, 177.63763672000002), 'rotation':(0.087256, -88.980774, 0.087003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3629.08667969, 422.33265625, 177.63046875), 'rotation':(0.075214, -88.982513, 0.075009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.98804688, 427.88914062000003, 177.62375), 'rotation':(0.069272, -88.9823, 0.0691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.79078125, 439.00300781, 177.61068359), 'rotation':(0.069265, -88.9823, 0.069097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.59328125, 450.11644531, 177.599375), 'rotation':(0.054341, -88.982361, 0.054241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.39601562, 461.23023437999996, 177.59042968999998), 'rotation':(0.044383, -88.982361, 0.044318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.19875, 472.34410156, 177.58398438), 'rotation':(0.034445, -88.982361, 0.034394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3628.10007812, 477.900625, 177.58111327999998), 'rotation':(0.029575, -88.983032, 0.029543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3628.00121094, 483.45714843999997, 177.57826172), 'rotation':(0.029479, -88.983032, 0.029445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3627.90257812, 489.01464844000003, 177.575625), 'rotation':(0.029479, -88.983032, 0.029445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.73121094, 554.96417969, 177.58175781000003), 'rotation':(-0.024719, -88.983429, -0.02475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.63160156, 560.5636718799999, 177.58457031), 'rotation':(-0.029907, -88.983429, -0.029938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.43261719, 571.76277344, 177.59177734000002), 'rotation':(-0.040405, -88.983398, -0.040466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.13429688, 588.56203125, 177.60578125), 'rotation':(-0.05011, -88.981995, -0.050201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.18480469, 537.9415234400001, 177.57648438), 'rotation':(0.014227, 91.019142, 0.014223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.08546875, 543.5409374999999, 177.57769531000002), 'rotation':(0.019568, 91.016563, 0.019548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3618.3903906200003, 582.67382812, 177.60076172), 'rotation':(0.050113, 91.017982, 0.050022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3618.29125, 588.26128906, 177.60564452999998), 'rotation':(0.054027, 91.01796, 0.053925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3616.58640625, 682.39373047, 177.73123047), 'rotation':(0.097474, 91.0186, 0.097149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3616.78492188, 671.2066796900001, 177.71253906), 'rotation':(0.095841, 91.016647, 0.095516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3616.88429688, 665.6133984400001, 177.70341797), 'rotation':(0.094598, 91.019775, 0.094281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3616.98363281, 660.0198437500001, 177.69457031000002), 'rotation':(0.09147, 91.017128, 0.09119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3617.18238281, 648.83308594, 177.67777343999998), 'rotation':(0.083089, 91.017105, 0.082862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3617.28171875, 643.2398828099999, 177.66980468999998), 'rotation':(0.080316, 91.019737, 0.080088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3617.38109375, 637.64628906, 177.66214843999998), 'rotation':(0.077352, 91.01709, 0.077146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3617.57960938, 626.4590625000001, 177.64755859000002), 'rotation':(0.07322, 91.017166, 0.073039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.45875, 626.59894531, 177.64755859000002), 'rotation':(-0.070709, -88.982697, -0.070862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3625.3596093799997, 632.19261719, 177.65474609), 'rotation':(-0.073212, -88.980347, -0.073425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.26023438, 637.78621094, 177.66214843999998), 'rotation':(-0.074707, -88.98291, -0.074921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.16089844, 643.37964844, 177.66980468999998), 'rotation':(-0.077362, -88.98291, -0.077576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3625.06152344, 648.9730078099999, 177.67777343999998), 'rotation':(-0.080322, -88.98291, -0.080536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3624.96214844, 654.56617188, 177.68603516), 'rotation':(-0.08606, -88.980255, -0.086304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3624.6640625, 671.3465625, 177.71253906), 'rotation':(-0.094604, -88.982849, -0.09491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3624.5646875, 676.9403125, 177.72185547), 'rotation':(-0.094604, -88.982849, -0.09491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3614.9175, 776.33990234, 177.91253906000003), 'rotation':(0.120068, 91.017876, 0.119568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3615.4140625, 748.37914062, 177.85482422), 'rotation':(0.115977, 91.01828, 0.115514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3615.5134375, 742.78693359, 177.84371094), 'rotation':(0.113825, 91.018265, 0.113375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3615.6128125, 737.19482422, 177.83267578), 'rotation':(0.113825, 91.018265, 0.113375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3615.71214844, 731.60259766, 177.82179688), 'rotation':(0.111476, 91.016624, 0.111038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3615.81152344, 726.01037109, 177.81099609), 'rotation':(0.110273, 91.018982, 0.109854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3615.91089844, 720.4182812500001, 177.80021484), 'rotation':(0.110273, 91.018982, 0.109854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3623.39257812, 742.92669922, 177.84371094), 'rotation':(-0.111481, -88.98175, -0.111908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3622.99535156, 765.29552734, 177.88917969), 'rotation':(-0.118225, -88.98172, -0.118713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3622.79640625, 776.47972656, 177.91253906000003), 'rotation':(-0.119537, -88.982117, -0.120026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3613.74390625, 842.40099609, 178.05322266), 'rotation':(0.121284, 91.017693, 0.120771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3613.84328125, 836.80902344, 178.04128906000003), 'rotation':(0.12226, 91.0177, 0.121729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3614.04175781, 825.62482422, 178.01730468999997), 'rotation':(0.123032, 91.017677, 0.122516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3614.09449219, 820.03369141, 178.00527344), 'rotation':(0.123401, 91.019073, 0.12288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3614.21046875, 808.84625, 177.98130859), 'rotation':(0.122513, 91.019127, 0.121992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3622.31324219, 810.97705078, 177.98554688000002), 'rotation':(-0.122528, -88.983276, -0.123047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.62304688, 842.54083008, 178.05322266), 'rotation':(-0.122253, -88.982269, -0.122772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3621.42429688, 853.72498047, 178.07695311999998), 'rotation':(-0.121307, -88.980896, -0.121796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3610.9924218799997, 997.31799316, 178.34691406000002), 'rotation':(0.079128, 91.017944, 0.078912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.09105469, 991.76013184, 178.33867188), 'rotation':(0.085063, 91.017975, 0.084813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.48609375, 969.52880859, 178.3028125), 'rotation':(0.096654, 91.016556, 0.096323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.68359375, 958.41375977, 178.28345703), 'rotation':(0.100458, 91.016525, 0.100107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3611.88109375, 947.29797363, 178.26363281000002), 'rotation':(0.103395, 91.016556, 0.103018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3611.97972656, 941.74017578, 178.25351562), 'rotation':(0.104939, 91.016556, 0.104564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3612.17726562, 930.62451172, 178.23273438), 'rotation':(0.108047, 91.016579, 0.107647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3612.27585938, 925.06677246, 178.22208984), 'rotation':(0.109604, 91.019318, 0.109186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3612.473125, 913.95117188, 178.20044922), 'rotation':(0.111769, 91.017639, 0.111322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.45117188, 908.53308594, 178.18953125), 'rotation':(-0.112854, -88.982758, -0.113312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.15503906, 925.2064209, 178.22208984), 'rotation':(-0.110992, -88.983398, -0.11142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.05617188, 930.7642822299999, 178.23271484), 'rotation':(-0.109619, -88.983398, -0.110016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3619.85890625, 941.87988281, 178.25349609), 'rotation':(-0.106506, -88.983429, -0.106903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3619.36523438, 969.66851807, 178.3028125), 'rotation':(-0.09964, -88.982666, -0.100006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3619.06910156, 986.34197998, 178.33019531000002), 'rotation':(-0.090912, -88.981995, -0.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3618.68945312, 1008.57104492, 178.36230468999997), 'rotation':(-0.079132, -88.982025, -0.079346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3618.68675781, 1014.12908936, 178.36970703), 'rotation':(-0.076294, -88.982788, -0.076477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.20289062, 502.2590625, 179.55226562), 'rotation':(0.063398, 90.248123, 0.063272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.2473437500003, 496.69691406, 179.54669922000002), 'rotation':(0.058753, 90.245628, 0.058642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3872.42796875, 480.02148437999995, 179.53226562), 'rotation':(0.047203, 90.246155, 0.04712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.69070312, 418.86601562, 179.51664062), 'rotation':(0.002411, 90.245895, 0.002405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.76515625, 385.50867187999995, 179.52914062), 'rotation':(-0.048431, 90.24678, -0.048523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.86328125, 381.00132812000004, 179.53298827999998), 'rotation':(0.048522, -89.753235, 0.048438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.703125, 390.08355469, 179.52529297), 'rotation':(0.048419, -89.754639, 0.048346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.64257812, 402.21921875, 179.51791015999999), 'rotation':(0.029506, -89.754639, 0.029464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.5946875, 413.33910156, 179.51642578), 'rotation':(0.004002, -89.752014, 0.003996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.57078125, 418.89832031000003, 179.51664062), 'rotation':(-0.002502, -89.754089, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.52320312, 430.01660156, 179.51710938), 'rotation':(-0.002411, -89.754089, -0.002411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.4753124999997, 441.13488281, 179.51759765999998), 'rotation':(-0.002411, -89.754089, -0.002411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.42773438, 452.25414062000004, 179.51833984), 'rotation':(-0.002502, -89.754089, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.37984375, 463.37292969, 179.52125), 'rotation':(-0.019226, -89.754944, -0.019226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.3559375, 468.93242188, 179.52419922), 'rotation':(-0.030396, -89.752899, -0.030426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.33226562, 474.49207031000003, 179.52796875), 'rotation':(-0.041565, -89.754883, -0.041626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.28445312, 485.61121094, 179.536875), 'rotation':(-0.047211, -89.753845, -0.047272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.30539062, 491.16914062, 179.54160156), 'rotation':(-0.049622, -89.754395, -0.049683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3880.34546875, 496.72789062000004, 179.54669922000002), 'rotation':(-0.054108, -89.751892, -0.054199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3880.0012500000003, 551.54734375, 179.61814453), 'rotation':(-0.089905, -89.753601, -0.09021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.97703125, 557.14972656, 179.62736328), 'rotation':(-0.089905, -89.753601, -0.09021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.953125, 562.7520703099999, 179.63683593999997), 'rotation':(-0.096802, -89.753601, -0.097107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.92898438, 568.35414062, 179.64699219), 'rotation':(-0.103668, -89.75354, -0.104034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.88085938, 579.5589062500001, 179.66773438), 'rotation':(-0.107178, -89.753998, -0.107574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.8325, 590.76347656, 179.68914062), 'rotation':(-0.109222, -89.753998, -0.10965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.95242188, 590.73601562, 179.68914062), 'rotation':(0.113518, 90.24601, 0.11307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3872.00046875, 579.5311328099999, 179.66773438), 'rotation':(0.109228, 90.245987, 0.108814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.024375, 573.92890625, 179.65726562), 'rotation':(0.107179, 90.245979, 0.106778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3872.09671875, 557.12128906, 179.62736328), 'rotation':(0.096791, 90.246399, 0.09647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3872.16890625, 540.31398438, 179.60107422000002), 'rotation':(0.089926, 90.246391, 0.089646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.63867188, 679.1536328100001, 179.89076172), 'rotation':(0.144998, 90.058434, 0.144269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.64453125, 673.56390625, 179.87675781000002), 'rotation':(0.143571, 90.059952, 0.14286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.65015625, 667.97375, 179.86283203), 'rotation':(0.142785, 90.057114, 0.142061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.65601562, 662.38410156, 179.84904297), 'rotation':(0.141228, 90.059807, 0.140533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.69234375, 651.21003906, 179.82201172), 'rotation':(0.137587, 90.244926, 0.136932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.7165625, 645.62019531, 179.80882812), 'rotation':(0.135012, 90.24678, 0.134392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.74046875, 640.03039062, 179.79580077999998), 'rotation':(0.135012, 90.24678, 0.134392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.7643749999997, 634.4405468799999, 179.78292968999997), 'rotation':(0.132232, 90.246765, 0.131608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.8125, 623.26074219, 179.75777344), 'rotation':(0.128182, 90.246582, 0.127615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.6926562500003, 623.28253906, 179.75775391), 'rotation':(-0.127289, -89.754333, -0.127869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.620625, 640.049375, 179.79576172), 'rotation':(-0.132233, -89.753235, -0.132843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.59671875, 645.63824219, 179.80876952999998), 'rotation':(-0.132233, -89.753235, -0.132843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.57273438, 651.22722656, 179.82197266), 'rotation':(-0.13504, -89.753235, -0.135651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.5190625, 679.17833984, 179.89080077999998), 'rotation':(-0.143585, -89.941559, -0.144287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.51320312, 684.76726562, 179.90488281), 'rotation':(-0.143585, -89.941559, -0.144287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.48, 717.28441406, 179.98859375), 'rotation':(-0.149841, -89.940735, -0.150635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.474375, 722.87927734, 180.00324218999998), 'rotation':(-0.150299, -89.941071, -0.151062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.44578125, 750.85345703, 180.07634765999998), 'rotation':(-0.149292, -89.941071, -0.150055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.43429688, 762.04308594, 180.10542969), 'rotation':(-0.148834, -89.941071, -0.149597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.53757812, 773.22869141, 180.13439452999998), 'rotation':(-0.148407, -89.939575, -0.14917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.55953125, 756.43298828, 180.09085938), 'rotation':(0.14883, 90.058907, 0.148065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.57101562, 745.24292969, 180.06175781000002), 'rotation':(0.14926, 90.058907, 0.148495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.5825, 734.05296875, 180.03253906), 'rotation':(0.149848, 90.058929, 0.149077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.588125, 728.45800781, 180.01789062), 'rotation':(0.149848, 90.058929, 0.149077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.59398438, 722.8629687499999, 180.00322266), 'rotation':(0.150141, 90.058929, 0.149363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.44601562, 867.21923828, 180.36205078), 'rotation':(0.124665, 90.05838, 0.124123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.4518749999997, 861.62445312, 180.34978515999998), 'rotation':(0.127212, 90.059502, 0.126642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.46335938, 850.43481445, 180.32466797), 'rotation':(0.129972, 90.06105, 0.129381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.47484375, 839.24481445, 180.29878906000002), 'rotation':(0.133933, 90.058434, 0.133309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.48632812, 828.0549218799999, 180.27214844), 'rotation':(0.137567, 90.058449, 0.136919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.3723437500003, 822.47351562, 180.25855468999998), 'rotation':(-0.141357, -89.941528, -0.142059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.35523438, 839.25792969, 180.29878906000002), 'rotation':(-0.135742, -89.941528, -0.136414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.349375, 844.85259766, 180.31183593999998), 'rotation':(-0.133942, -89.941559, -0.134583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.33226562, 861.63683594, 180.34978515999998), 'rotation':(-0.128174, -89.941589, -0.128723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.32640625, 867.23144531, 180.36207031), 'rotation':(-0.127197, -89.940491, -0.127777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.1770312500003, 1004.00067139, 180.56853515999998), 'rotation':(0.036255, 90.058151, 0.036208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.31617188, 994.32543945, 180.56240234), 'rotation':(0.036255, 90.058151, 0.036211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.32203125, 988.76147461, 180.55835938), 'rotation':(0.041589, 90.059723, 0.041533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.32765625, 983.19781494, 180.55373047), 'rotation':(0.041589, 90.059723, 0.041533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.35617188, 955.37933594, 180.52046875), 'rotation':(0.079169, 90.058006, 0.078952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.3620312499997, 949.81591797, 180.51269531000003), 'rotation':(0.079319, 90.060539, 0.079104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3871.401875, 910.86895508, 180.44912109), 'rotation':(0.10455, 90.058815, 0.104167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3871.413125, 899.74115234, 180.42851561999998), 'rotation':(0.106189, 90.058624, 0.105807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2878124999997, 905.31640625, 180.43890625), 'rotation':(-0.106201, -89.941345, -0.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2821875, 910.88006836, 180.44912109), 'rotation':(-0.106201, -89.941345, -0.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3879.27640625, 916.44335938, 180.45916015999998), 'rotation':(-0.104553, -89.941162, -0.104919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2707812500003, 922.00726562, 180.46900391), 'rotation':(-0.10144, -89.941681, -0.101807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.26492188, 927.57092285, 180.47845703), 'rotation':(-0.10144, -89.941681, -0.101807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.25929688, 933.13446289, 180.48769531000002), 'rotation':(-0.095032, -89.940186, -0.095367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2478125, 944.26202148, 180.50470703), 'rotation':(-0.088745, -89.941742, -0.088989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.21945312, 972.07965088, 180.54236328), 'rotation':(-0.073883, -89.941956, -0.074066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.1965625000003, 994.33428955, 180.56240234), 'rotation':(-0.041595, -89.940277, -0.041656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3879.2990625, 1002.61431885, 180.56765625), 'rotation':(-0.036255, -89.941833, -0.036285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2123.92648438, 344.78296875, 157.28583007999998), 'rotation':(-0.84198, -179.499496, -0.867004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2112.75976562, 344.78859375, 157.1221582), 'rotation':(-0.837311, -179.499619, -0.862061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2084.83960938, 344.55062499999997, 156.71650391), 'rotation':(-0.822815, -179.500107, -0.846741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2079.25585938, 344.50320311999997, 156.63630859), 'rotation':(-0.817108, -179.500259, -0.840668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2063.80664062, 344.28140625000003, 156.41609375), 'rotation':(-0.814117, -179.500305, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2123.85351562, 352.8648828099999, 157.28576171999998), 'rotation':(0.845181, 0.500603, 0.820532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2107.10398438, 352.62144531, 157.04046875), 'rotation':(0.837327, 0.500395, 0.813121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2084.7665625, 352.43117187999997, 156.71642578), 'rotation':(0.82868, 0.500057, 0.804963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2073.598125, 352.33601562, 156.55645508), 'rotation':(0.817089, 0.499914, 0.794033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2068.01609375, 352.30828125000005, 156.47689453), 'rotation':(0.817089, 0.499914, 0.794033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2062.43265625, 352.35242187999995, 156.39753905999999), 'rotation':(0.814288, 0.499507, 0.791387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2161.97460938, 353.08898437999994, 157.85286133), 'rotation':(0.860809, 0.501138, 0.835227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2167.56296875, 353.13660156000003, 157.9368457), 'rotation':(0.860822, 0.500936, 0.835254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2173.15140625, 353.18421875, 158.02083984), 'rotation':(0.862339, 0.500984, 0.836661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2178.74, 353.23179687999993, 158.10492188), 'rotation':(0.865419, 0.5014, 0.839566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2195.50539062, 353.37464844, 158.35880859), 'rotation':(0.873007, 0.501665, 0.846694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2206.68210938, 353.46984375, 158.52913086), 'rotation':(0.873001, 0.501312, 0.846704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2217.85890625, 353.56507812000007, 158.69951172), 'rotation':(0.874783, 0.501632, 0.848365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2223.44703125, 353.61265625, 158.78486328), 'rotation':(0.878321, 0.501455, 0.851707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2223.52320312, 345.7321875, 158.785), 'rotation':(-0.874786, -179.498611, -0.901825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2206.7565624999997, 345.589375, 158.52924805), 'rotation':(-0.873016, -179.498672, -0.899933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2201.16773438, 345.54175781000004, 158.4440625), 'rotation':(-0.873016, -179.498672, -0.899933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2189.98921875, 345.44652343999996, 158.27395508), 'rotation':(-0.8685, -179.498489, -0.895142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2184.40039062, 345.39890625, 158.18931641), 'rotation':(-0.865417, -179.498901, -0.891876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2173.2221875, 345.30371094, 158.02088867), 'rotation':(-0.860809, -179.498856, -0.886993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2323.004375, 354.39820312000006, 160.34195312), 'rotation':(0.906503, 0.405557, 0.878145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2317.4245312499997, 354.36011719, 160.25364258), 'rotation':(0.906503, 0.405557, 0.878145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2300.68453125, 354.24585937999996, 159.98871094), 'rotation':(0.906503, 0.405557, 0.878145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2295.10453125, 354.20777344, 159.90052734), 'rotation':(0.904973, 0.405189, 0.87671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2283.94578125, 354.12804687999994, 159.72490234), 'rotation':(0.889823, 0.452758, 0.862502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2278.36765625, 354.08054687999993, 159.63737305), 'rotation':(0.898655, 0.502394, 0.8708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2250.46726562, 353.84289062000005, 159.20198242), 'rotation':(0.893655, 0.501967, 0.866098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2317.49242188, 346.47960937999994, 160.25387695), 'rotation':(-0.906464, -179.594452, -0.935516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2289.5924999999997, 346.28914062, 159.81276367), 'rotation':(-0.911102, -179.544418, -0.94046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2284.01101562, 346.24757812000007, 159.72487305), 'rotation':(-0.898651, -179.497849, -0.927155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2272.85179688, 346.15246093999997, 159.55009766), 'rotation':(-0.893768, -179.498016, -0.921997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2261.6926562500003, 346.05738281000004, 159.37591797), 'rotation':(-0.893677, -179.497818, -0.921875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2250.53320312, 345.96226562000004, 159.20196289), 'rotation':(-0.891205, -179.498062, -0.919281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2401.51757812, 347.0530859400001, 161.59660156), 'rotation':(-0.922699, -179.594147, -0.952789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2410.40210938, 346.99101562, 161.73986328), 'rotation':(-0.923737, -179.59404, -0.953888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2389.17773438, 346.96886718999997, 161.39792969), 'rotation':(-0.920563, -179.594009, -0.950531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2377.98851562, 346.89250000000004, 161.21832031), 'rotation':(-0.916412, -179.594147, -0.946075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2366.80101562, 346.81230469, 161.03922852), 'rotation':(-0.915375, -179.594193, -0.944977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2361.20824219, 346.7025, 160.94984375), 'rotation':(-0.915405, -179.594528, -0.945007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2355.61109375, 346.61023437999995, 160.86038086), 'rotation':(-0.915405, -179.594177, -0.945007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2400.30199219, 354.92589843999997, 161.57788086), 'rotation':(0.923728, 0.405968, 0.894304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2394.70726562, 354.88769531, 161.48774414), 'rotation':(0.92269, 0.406061, 0.893319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2355.54199219, 354.74992188, 160.86015625), 'rotation':(0.915402, 0.405821, 0.886495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2511.05054688, 347.80078125, 163.36444336), 'rotation':(-0.923431, -179.593842, -0.953552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2477.57445312, 347.57226562000005, 162.82451172), 'rotation':(-0.925446, -179.594025, -0.955719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2466.41578125, 347.49609375, 162.64422851999998), 'rotation':(-0.925323, -179.594025, -0.955597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2455.25707031, 347.41992187999995, 162.46394530999999), 'rotation':(-0.925415, -179.593826, -0.955688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2449.6775, 347.38183594, 162.37379883), 'rotation':(-0.925323, -179.594025, -0.955597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.09839844, 347.34375, 162.28364258), 'rotation':(-0.92511, -179.593918, -0.955353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.24925781, 355.56726562000006, 163.09442382999998), 'rotation':(0.923428, 0.406151, 0.894006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2471.93164062, 355.41492187999995, 162.73421875), 'rotation':(0.925429, 0.406182, 0.89589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2466.35203125, 355.37683594, 162.64407227), 'rotation':(0.925429, 0.406182, 0.89589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2455.19335938, 355.30058594, 162.46378906), 'rotation':(0.925327, 0.405977, 0.895785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2449.61425781, 355.26250000000005, 162.37364258), 'rotation':(0.925395, 0.405966, 0.895862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.0346875, 355.22441405999996, 162.28347656), 'rotation':(0.925327, 0.406178, 0.895794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2582.75464844, 348.29027343999996, 164.51375), 'rotation':(-0.911652, -179.594559, -0.94101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2577.16601562, 348.2521875, 164.42482422), 'rotation':(-0.9133, -179.594208, -0.94278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2560.39992188, 348.13769531, 164.15716797000002), 'rotation':(-0.916656, -179.594391, -0.94632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2549.22265625, 348.06140625, 163.97818359000001), 'rotation':(-0.917603, -179.594299, -0.947357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2593.8728125, 356.2471875, 164.69107422000002), 'rotation':(0.906646, 0.405288, 0.878287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2582.6953125, 356.17089844, 164.51367188), 'rotation':(0.909979, 0.405396, 0.881404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2577.10644531, 356.1328125, 164.42472656), 'rotation':(0.911639, 0.405724, 0.88297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2571.51757812, 356.09460937999995, 164.33564453), 'rotation':(0.913271, 0.405761, 0.884497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2554.75171875, 355.98023437999996, 164.06759766), 'rotation':(0.916632, 0.405882, 0.887651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2543.57398438, 355.9039453099999, 163.88855468999998), 'rotation':(0.917458, 0.405711, 0.888428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.06005859, 357.06007812000007, 166.3234375), 'rotation':(0.867577, 0.404147, 0.841592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2693.48167969, 356.92707031, 166.23888672), 'rotation':(0.867577, 0.404442, 0.841592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.89794922, 356.88898438, 166.15410156000002), 'rotation':(0.869708, 0.404145, 0.8436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2671.14722656, 356.77464843999996, 165.89755859000002), 'rotation':(0.878219, 0.40439, 0.851605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.98046875, 356.69843749999995, 165.72525391), 'rotation':(0.884537, 0.404797, 0.857534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2648.81347656, 356.6221875, 165.55265625), 'rotation':(0.886026, 0.404838, 0.858939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2637.64625, 356.54601562000005, 165.37927734000002), 'rotation':(0.888922, 0.404679, 0.86166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2632.0625, 356.50792968999997, 165.29222656000002), 'rotation':(0.892084, 0.405029, 0.864627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.11890625, 348.98949218999996, 166.32347656000002), 'rotation':(-0.867584, -179.59584, -0.894165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.78808594, 348.93210937999993, 165.9834375), 'rotation':(-0.882355, -179.595459, -0.909851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2665.62085938, 348.8559375, 165.81152343999997), 'rotation':(-0.884521, -179.5952, -0.91217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2648.86988281, 348.7415625, 165.55269531000002), 'rotation':(-0.888947, -179.595062, -0.91684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2637.70265625, 348.66539062000004, 165.37929688), 'rotation':(-0.89209, -179.594971, -0.920197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2956.36206055, 350.78539062000004, 169.92509766), 'rotation':(-0.737091, -179.599655, -0.756256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2947.66259766, 350.78105469, 169.81324218999998), 'rotation':(-0.740875, -179.599274, -0.760223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2930.59838867, 350.66453125, 169.59169922), 'rotation':(-0.752106, -179.598984, -0.772034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2913.53491211, 350.54808593999996, 169.36714844), 'rotation':(-0.759338, -179.598801, -0.779694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2902.15942383, 350.47046875, 169.21580078), 'rotation':(-0.765045, -179.598679, -0.785675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2896.47143555, 350.43164062000005, 169.13986328), 'rotation':(-0.764893, -179.598694, -0.785522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2890.78344727, 350.3928125, 169.06388672), 'rotation':(-0.767517, -179.598541, -0.7883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2885.09594727, 350.35398437999993, 168.98769531000002), 'rotation':(-0.772339, -179.598419, -0.793365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.3449707, 350.19875, 168.67835938), 'rotation':(-0.78479, -179.598022, -0.806519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2856.65698242, 350.15984375000005, 168.60044922), 'rotation':(-0.786652, -179.598297, -0.808472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2850.9699707, 350.12101562, 168.52238281), 'rotation':(-0.790466, -179.597916, -0.812531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2833.90673828, 350.00464844, 168.28638672), 'rotation':(-0.798218, -179.597717, -0.820709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2822.53076172, 349.92695312, 168.12740234), 'rotation':(-0.805878, -179.597488, -0.828796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2805.46728516, 349.81046875000004, 167.88628906000002), 'rotation':(-0.815369, -179.597214, -0.838837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2742.90941406, 349.32617187999995, 166.98013672000002), 'rotation':(-0.846832, -179.596329, -0.872131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2953.29174805, 358.7025, 169.88638672000002), 'rotation':(0.735242, 0.400546, 0.716548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2947.60546875, 358.66164062000007, 169.81322265999998), 'rotation':(0.737087, 0.400626, 0.718306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2941.91748047, 358.6228125, 169.73970702999998), 'rotation':(0.740871, 0.400724, 0.721898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2913.47753906, 358.42859375, 169.36708984), 'rotation':(0.755583, 0.40111, 0.735858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2885.03808594, 358.23457031, 168.98763672), 'rotation':(0.767508, 0.401445, 0.74714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2873.66235352, 358.156875, 168.83382812), 'rotation':(0.777453, 0.401408, 0.756563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2867.97460938, 358.11804687999995, 168.75619140999999), 'rotation':(0.782282, 0.401839, 0.761131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.28686523, 358.07929688, 168.67830078), 'rotation':(0.784638, 0.401971, 0.763374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2856.59887695, 358.04039062000004, 168.60037109), 'rotation':(0.784789, 0.401694, 0.763505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2845.22387695, 357.96281250000004, 168.44398438), 'rotation':(0.790465, 0.40208, 0.768886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2839.53588867, 357.92402344000004, 168.36533203), 'rotation':(0.790465, 0.40208, 0.768886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2833.84839844, 357.8851171900001, 168.28634766), 'rotation':(0.794296, 0.401917, 0.77249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2799.72144531, 357.65222656000003, 167.80533203), 'rotation':(0.815402, 0.402806, 0.792433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2788.34667969, 357.57457031, 167.64279297000002), 'rotation':(0.818332, 0.40271, 0.795208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2782.65869141, 357.53578125, 167.5609375), 'rotation':(0.824253, 0.403081, 0.800784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2776.97119141, 357.49695312000006, 167.47880859), 'rotation':(0.824253, 0.403081, 0.800784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2765.59546875, 357.41929687999993, 167.31341797000002), 'rotation':(0.836042, 0.403234, 0.811902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2759.90869141, 357.3805078099999, 167.23035156000003), 'rotation':(0.836042, 0.403234, 0.811902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2754.22070312, 357.34167969, 167.14701172000002), 'rotation':(0.839014, 0.403665, 0.814706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3119.06225586, 359.92625, 171.94140625), 'rotation':(0.689794, 0.3994, 0.673334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3113.51586914, 359.84226562000003, 171.87455078), 'rotation':(0.689794, 0.3994, 0.673334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3102.42260742, 359.71828125, 171.74046875), 'rotation':(0.692725, 0.39953, 0.67613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3096.87548828, 359.68042969, 171.67339843999997), 'rotation':(0.692697, 0.399515, 0.676096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3091.328125, 359.64257812000005, 171.60632812), 'rotation':(0.692725, 0.39953, 0.67613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.59130859, 359.45324218999997, 171.27216797), 'rotation':(0.687479, 0.399428, 0.67112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3052.49633789, 359.37742187999993, 171.13900390999999), 'rotation':(0.687506, 0.399443, 0.671152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3035.85644531, 359.26390625, 170.93777343999997), 'rotation':(0.693517, 0.39938, 0.676879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3030.30908203, 359.22609375, 170.86945312), 'rotation':(0.70536, 0.399856, 0.688159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3019.21508789, 359.15039062000005, 170.73107422), 'rotation':(0.717375, 0.399977, 0.699582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3013.66821289, 359.11249999999995, 170.66074218999998), 'rotation':(0.717375, 0.399977, 0.699582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3008.12084961, 359.0746875, 170.59011718999997), 'rotation':(0.729218, 0.400453, 0.710828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3002.57788086, 359.10902344, 170.51898438), 'rotation':(0.73527, 0.400551, 0.716574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3130.04150391, 351.89648437999995, 172.07271484), 'rotation':(-0.687866, -179.600662, -0.704529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3118.95825195, 351.85722655999996, 171.93949218999998), 'rotation':(-0.691803, -179.600571, -0.708649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3107.87670898, 351.87382812, 171.80580078), 'rotation':(-0.692719, -179.600464, -0.709625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3080.17382812, 351.68562499999996, 171.47087890999998), 'rotation':(-0.688812, -179.60051, -0.705505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3074.6328125, 351.64777344000004, 171.40414062), 'rotation':(-0.688812, -179.60051, -0.705505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3058.01000977, 351.53429687999994, 171.20455077999998), 'rotation':(-0.6875, -179.600845, -0.704163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3052.46923828, 351.49644531, 171.13802734), 'rotation':(-0.6875, -179.600845, -0.704163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3041.38916016, 351.42089844, 171.00443359000002), 'rotation':(-0.705383, -179.600327, -0.7229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3035.84887695, 351.38304687999994, 170.93701172000002), 'rotation':(-0.705383, -179.600327, -0.7229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3019.22705078, 351.26960938, 170.73056641), 'rotation':(-0.729218, -179.599716, -0.747955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3013.68701172, 351.23175781, 170.6603125), 'rotation':(-0.729218, -179.599716, -0.747955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3006.92822266, 351.17015625, 170.57412109), 'rotation':(-0.735291, -179.599426, -0.754364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2998.29321289, 350.99707031, 170.46328125), 'rotation':(-0.735168, -179.599442, -0.754242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3328.54835938, 353.38097656, 174.42201172), 'rotation':(-0.673462, -179.601303, -0.689453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3323.01269531, 353.34328125, 174.35697266), 'rotation':(-0.673462, -179.601303, -0.689453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3317.47679688, 353.30542969, 174.29189452999998), 'rotation':(-0.674652, -179.600723, -0.690704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3311.94117188, 353.26769531, 174.22669922), 'rotation':(-0.67453, -179.601181, -0.690552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3306.40527344, 353.22984375, 174.16150391), 'rotation':(-0.67453, -179.601181, -0.690552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3295.33375, 353.15429687999995, 174.03113281000003), 'rotation':(-0.67453, -179.601181, -0.690552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3289.79808594, 353.11644531, 173.9659375), 'rotation':(-0.674988, -179.600845, -0.69104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3273.19066406, 353.00312499999995, 173.77025390999998), 'rotation':(-0.675934, -179.601196, -0.692047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3228.90453125, 352.7008203099999, 173.24761718999997), 'rotation':(-0.677734, -179.600327, -0.693909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3212.29761719, 352.5875390599999, 173.05107422), 'rotation':(-0.678375, -179.600754, -0.69458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3206.76148438, 352.5496875, 172.98550781000003), 'rotation':(-0.678406, -179.600739, -0.694611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3195.68994141, 352.47414062000007, 172.85439452999998), 'rotation':(-0.678925, -179.601288, -0.69516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3190.15453125, 352.43632812, 172.78882812), 'rotation':(-0.678925, -179.601288, -0.69516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3173.546875, 352.32300781000004, 172.59171875), 'rotation':(-0.682129, -179.600723, -0.698517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3328.9216406200003, 361.26441406000004, 174.42701172), 'rotation':(0.671394, 0.398837, 0.655796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3317.83300781, 361.18871093999996, 174.29669922000002), 'rotation':(0.67347, 0.399105, 0.657766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3312.28857422, 361.15085937999993, 174.23140625), 'rotation':(0.674631, 0.399037, 0.6589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3290.11083984, 360.99953125, 173.97025391), 'rotation':(0.674556, 0.399053, 0.658804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3262.38890625, 360.81023438, 173.6434375), 'rotation':(0.675943, 0.399199, 0.660135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3251.30003906, 360.73457031, 173.51259765999998), 'rotation':(0.675943, 0.399001, 0.660137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3201.40087891, 360.39390625, 172.92267578), 'rotation':(0.678381, 0.399252, 0.662467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3195.85667969, 360.35609375, 172.85701172), 'rotation':(0.678381, 0.399011, 0.66247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3179.22339844, 360.24253906, 172.65982422000002), 'rotation':(0.679973, 0.399213, 0.663984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3599.17285156, 363.10902344, 177.47037109000001), 'rotation':(0.584049, 0.39703, 0.572229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3587.85230469, 363.03171875, 177.35427734), 'rotation':(0.588755, 0.39703, 0.57676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3582.191875, 362.99308594, 177.29546875), 'rotation':(0.588755, 0.39703, 0.57676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3570.87085938, 362.91582030999996, 177.17644531000002), 'rotation':(0.607047, 0.397599, 0.594291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3565.21019531, 362.8771875, 177.11626952999998), 'rotation':(0.607047, 0.397599, 0.594291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3559.54957031, 362.83863281000004, 177.05537109), 'rotation':(0.616261, 0.397614, 0.603106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3542.56835938, 362.72265625, 176.87158202999998), 'rotation':(0.620851, 0.397867, 0.607501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3531.2478125, 362.64539062000006, 176.74830078), 'rotation':(0.623234, 0.397885, 0.609783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3525.58742188, 362.60679687999993, 176.68619141), 'rotation':(0.627817, 0.397982, 0.614174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3485.96386719, 362.33628906, 176.24419922), 'rotation':(0.642693, 0.398499, 0.628398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3474.6428125, 362.25902343999996, 176.11634766), 'rotation':(0.647283, 0.398586, 0.632785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3463.32179688, 362.18175781, 175.98761718999998), 'rotation':(0.651627, 0.398401, 0.636939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3457.66113281, 362.14320312000007, 175.92294922000002), 'rotation':(0.653984, 0.398737, 0.639189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3452.00121094, 362.10449219, 175.85808594), 'rotation':(0.656258, 0.398509, 0.641344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3446.34058594, 362.06585938, 175.79314452999998), 'rotation':(0.657242, 0.398714, 0.642299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3429.3591406200003, 361.94996094, 175.59810547), 'rotation':(0.659523, 0.398786, 0.644474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3423.69875, 361.91136718999996, 175.53267577999998), 'rotation':(0.659523, 0.398786, 0.644474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3412.37769531, 361.83406249999996, 175.40115234), 'rotation':(0.666312, 0.398822, 0.650956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3406.71726562, 361.79539062000003, 175.3353125), 'rotation':(0.666312, 0.398822, 0.650956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3401.05664062, 361.75675780999995, 175.26947266), 'rotation':(0.666292, 0.399001, 0.650938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3395.39601562, 361.718125, 175.20363281000002), 'rotation':(0.666305, 0.398813, 0.650936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3389.73535156, 361.67945312000006, 175.13779297000002), 'rotation':(0.666305, 0.398813, 0.650936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3384.0746875, 361.64085937999994, 175.07195312), 'rotation':(0.666305, 0.398813, 0.650936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3372.75390625, 361.56359375, 174.93996094), 'rotation':(0.669304, 0.398861, 0.653795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3361.43285156, 361.48632812000005, 174.80751952999998), 'rotation':(0.670164, 0.3989, 0.654625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3604.12425781, 355.26203124999995, 177.5203125), 'rotation':(-0.584045, -179.602768, -0.596039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3598.47046875, 355.22339844, 177.46265625), 'rotation':(-0.588776, -179.602966, -0.600952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3592.81761719, 355.18480468999996, 177.40474609), 'rotation':(-0.588776, -179.602966, -0.600952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3587.16359375, 355.14625, 177.34664062), 'rotation':(-0.597931, -179.602768, -0.610504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3564.54980469, 354.99195312000006, 177.10857422), 'rotation':(-0.616272, -179.602386, -0.629639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3547.58960938, 354.87609375, 176.92542969), 'rotation':(-0.62085, -179.602127, -0.63443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3541.93578125, 354.8375390599999, 176.86416015999998), 'rotation':(-0.62323, -179.602112, -0.636902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3536.28273438, 354.79894531, 176.80269531000002), 'rotation':(-0.627808, -179.60202, -0.641693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3530.62914062, 354.76039062000007, 176.7409375), 'rotation':(-0.627808, -179.60202, -0.641693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3513.6684375, 354.64460938, 176.55351561999998), 'rotation':(-0.639404, -179.601913, -0.653809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3502.36179688, 354.56746094000005, 176.42734375), 'rotation':(-0.640594, -179.601257, -0.655029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3491.0549218799997, 354.49023437999995, 176.30082031), 'rotation':(-0.645081, -179.601746, -0.659729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3485.40136719, 354.45164062000003, 176.23726562), 'rotation':(-0.647278, -179.601715, -0.662048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3474.09449219, 354.37453125, 176.10951172), 'rotation':(-0.649567, -179.601639, -0.664398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3468.4409375, 354.3359375, 176.0453125), 'rotation':(-0.651642, -179.600998, -0.666595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3445.82714844, 354.18156250000004, 175.78664062), 'rotation':(-0.657379, -179.601456, -0.672577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3428.86671875, 354.06578125, 175.59179688), 'rotation':(-0.664001, -179.601105, -0.679535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3417.55980469, 353.98863281, 175.46080078), 'rotation':(-0.666321, -179.601181, -0.681946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3400.59914062, 353.8728125, 175.26351562), 'rotation':(-0.66629, -179.601181, -0.681946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3383.63820312, 353.75707031, 175.06623047000002), 'rotation':(-0.667358, -179.600861, -0.683044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3377.9846093799997, 353.71843750000005, 175.00039062), 'rotation':(-0.669312, -179.600815, -0.685089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3372.33105469, 353.67980468999997, 174.93439453), 'rotation':(-0.670166, -179.601318, -0.686005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3857.9096875, 356.89929687999995, 179.47611328), 'rotation':(-0.253387, -179.607498, -0.255615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3852.2370312499997, 356.95539062, 179.4509375), 'rotation':(-0.263214, -179.607635, -0.265625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3846.56054688, 356.91664062000007, 179.42484375), 'rotation':(-0.274109, -179.607742, -0.276764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3840.885, 356.87792969, 179.39826172000002), 'rotation':(-0.274109, -179.607742, -0.276764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3818.1823437499997, 356.72300781, 179.28107422000002), 'rotation':(-0.339508, -179.607025, -0.343567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.5065624999997, 356.68433594, 179.24855469), 'rotation':(-0.339508, -179.607025, -0.343567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.83007812, 356.64558594000005, 179.21492188), 'rotation':(-0.350464, -179.606583, -0.354767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3789.8034374999997, 356.52929687999995, 179.11027344), 'rotation':(-0.365356, -179.6064, -0.370056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3778.45164062, 356.45183594, 179.03630859), 'rotation':(-0.385162, -179.606155, -0.390381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3750.07375, 356.25816406, 178.83314453), 'rotation':(-0.429901, -179.605865, -0.436371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.72242188, 356.18074219000005, 178.74724609), 'rotation':(-0.453247, -179.605194, -0.460449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3733.04640625, 356.14195312000004, 178.70335938), 'rotation':(-0.453247, -179.605194, -0.460449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.37039062, 356.10320312, 178.65845703), 'rotation':(-0.468811, -179.605331, -0.476562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.69578125, 356.06445312000005, 178.61248047), 'rotation':(-0.468811, -179.605331, -0.476562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3716.02046875, 356.0257421900001, 178.5659375), 'rotation':(-0.484406, -179.604691, -0.492645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3710.34398438, 355.98707031000004, 178.51792969), 'rotation':(-0.492188, -179.604675, -0.500671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3704.66890625, 355.94832031, 178.46958984), 'rotation':(-0.492188, -179.604675, -0.500671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3698.99390625, 355.90953125, 178.42078125), 'rotation':(-0.495819, -179.604584, -0.504456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3693.3176562500003, 355.87085937999996, 178.37158202999998), 'rotation':(-0.503052, -179.604462, -0.511963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3687.6418750000003, 355.83210938, 178.32171875), 'rotation':(-0.510132, -179.60434, -0.519287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3676.28976562, 355.75457030999996, 178.21992188000002), 'rotation':(-0.524506, -179.604065, -0.534149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3659.2634375, 355.6384375, 178.0621875), 'rotation':(-0.546234, -179.603653, -0.556702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3653.58765625, 355.59960937999995, 178.00826172), 'rotation':(-0.549866, -179.603973, -0.560516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3642.23632812, 355.52214844, 177.89941406000003), 'rotation':(-0.549896, -179.603409, -0.560516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3858.92484375, 364.99644531, 179.48085938), 'rotation':(0.233565, 0.392094, 0.231672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3853.24414062, 364.85144531000003, 179.45574219), 'rotation':(0.253386, 0.391997, 0.251148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3847.56320312, 364.80421875, 179.42970703), 'rotation':(0.263201, 0.392347, 0.260795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3841.88085938, 364.76539062000006, 179.40328125), 'rotation':(0.263201, 0.392347, 0.260795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3824.83132812, 364.6490625, 179.31818359000002), 'rotation':(0.295973, 0.392653, 0.292928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3813.4674999999997, 364.57148438, 179.25457031000002), 'rotation':(0.317734, 0.392887, 0.31423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3802.10179688, 364.49390625, 179.18650391), 'rotation':(0.339515, 0.39296, 0.335513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3768.00539062, 364.26125, 178.96488281), 'rotation':(0.395106, 0.393656, 0.389682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3762.3225, 364.22246094, 178.92427734), 'rotation':(0.40501, 0.394107, 0.399312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3756.6396875, 364.18371093999997, 178.88259766), 'rotation':(0.424988, 0.394398, 0.418731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3750.9575, 364.14496094000003, 178.84017577999998), 'rotation':(0.429892, 0.394128, 0.423475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3745.27367188, 364.10613280999996, 178.79751953), 'rotation':(0.429892, 0.394468, 0.423474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3739.5915625, 364.06738281, 178.75427734000002), 'rotation':(0.429892, 0.394468, 0.423474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3728.2253124999997, 363.98976562000007, 178.66564452999998), 'rotation':(0.453238, 0.3948, 0.446109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3722.5442187500003, 363.95097655999996, 178.61988281), 'rotation':(0.453238, 0.3948, 0.446109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3716.86085938, 363.91222656, 178.57335938), 'rotation':(0.468817, 0.394856, 0.461206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3711.17820312, 363.8733984400001, 178.52542968999998), 'rotation':(0.484417, 0.395118, 0.476271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3694.130625, 363.75707031, 178.37914062), 'rotation':(0.495824, 0.395426, 0.487288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3688.4475, 363.71828125, 178.32927734), 'rotation':(0.503057, 0.395548, 0.494289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3671.40015625, 363.60191406, 178.17568359), 'rotation':(0.524483, 0.395932, 0.514961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3660.03445312, 363.52441406, 178.06992188), 'rotation':(0.53912, 0.396206, 0.529045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3642.98632812, 363.40808594, 177.90712890999998), 'rotation':(0.549871, 0.396565, 0.539391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3997.4553125, 359.58167969, 179.68173828), 'rotation':(-0.117188, -5.580261, -0.117676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3986.3293750000003, 360.60863281, 179.70404297000002), 'rotation':(-0.105042, -5.014008, -0.105408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3975.18554688, 361.53222656, 179.71894531), 'rotation':(-0.056458, -4.547119, -0.05658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3964.02195312, 362.22070312000005, 179.72283202999998), 'rotation':(-0.008057, -4.080811, -0.008087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3952.85570312, 362.91882812000006, 179.71572265999998), 'rotation':(0.040332, -3.613525, 0.040272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3947.2690625, 363.23445312, 179.70878906000002), 'rotation':(0.064702, -3.379486, 0.064558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3936.09546875, 363.7946875, 179.69365234), 'rotation':(0.076853, -2.775848, 0.076652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3924.92554688, 364.39019530999997, 179.6753125), 'rotation':(0.103307, -2.140778, 0.10293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3913.74, 364.73644531, 179.65109375), 'rotation':(0.120833, -1.825104, 0.120331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3991.84523438, 352.05226562000007, 179.69175781), 'rotation':(0.118272, 174.719727, 0.117789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3980.56640625, 353.04613281, 179.71216797), 'rotation':(0.057018, 175.452621, 0.05691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3974.92578125, 353.50242187999993, 179.71857422000002), 'rotation':(0.03258, 175.686371, 0.032547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.28171875, 353.9325, 179.72224609), 'rotation':(0.008148, 175.920151, 0.008146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3957.9865625, 354.70769530999996, 179.72066406000002), 'rotation':(-0.040741, 176.386826, -0.040771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3946.67578125, 355.33167969, 179.70855468999997), 'rotation':(-0.077637, 176.89978, -0.07785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3929.6975, 356.18089843999996, 179.68451172000002), 'rotation':(-0.10434, 177.859344, -0.104706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3924.03539062, 356.39257812000005, 179.67421875), 'rotation':(-0.12204, 178.174561, -0.122559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3912.7160937500003, 356.73546875, 179.64910156000002), 'rotation':(-0.148773, 178.749725, -0.149536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3901.40453125, 356.97613280999997, 179.62015625), 'rotation':(-0.148773, 179.158585, -0.149567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3895.74953125, 357.05296875, 179.60550781), 'rotation':(-0.148773, 179.362244, -0.149536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3324.18871094, 518.39800781, 173.94878906000002), 'rotation':(0.705996, 0.595005, 0.688755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3318.64039062, 518.34117188, 173.88056641), 'rotation':(0.704397, 0.594945, 0.687243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3285.34984375, 518.00046875, 173.47277343999997), 'rotation':(0.695791, 0.594997, 0.679048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3257.60791016, 517.7165625, 173.13703125), 'rotation':(0.693141, 0.594734, 0.676519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3246.51097656, 517.60304688, 173.00324218999998), 'rotation':(0.689029, 0.594402, 0.672606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3207.67164062, 517.20550781, 172.53951172), 'rotation':(0.681988, 0.594309, 0.665893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3191.02636719, 517.03515625, 172.34259766), 'rotation':(0.676721, 0.59401, 0.660886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3185.47802734, 516.97832031, 172.27740234), 'rotation':(0.673211, 0.594393, 0.657521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3174.380625, 516.86480469, 172.14775391), 'rotation':(0.668068, 0.593652, 0.652624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3168.83226562, 516.8080468799999, 172.08304688), 'rotation':(0.668033, 0.594303, 0.652594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3163.28393555, 516.75128906, 172.01833984), 'rotation':(0.668068, 0.594333, 0.652622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3163.34545898, 508.87082031, 172.01810547000002), 'rotation':(-0.667877, -179.40567, -0.683594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3168.89378906, 508.92761719000003, 172.0828125), 'rotation':(-0.66806, -179.406006, -0.683777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3191.08740234, 509.15476562000003, 172.34238281), 'rotation':(-0.673218, -179.405838, -0.689178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3202.18433594, 509.26832031, 172.47339843999998), 'rotation':(-0.676727, -179.405762, -0.692871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3207.73265625, 509.32503906, 172.53927734), 'rotation':(-0.680267, -179.405685, -0.696564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3218.82933594, 509.43863281, 172.67134765999998), 'rotation':(-0.681976, -179.405472, -0.698364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3224.37769531, 509.49539062, 172.73740234000002), 'rotation':(-0.681976, -179.405685, -0.698364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3229.92626953, 509.5521875, 172.80359375), 'rotation':(-0.68338, -179.405502, -0.699829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3241.02294922, 509.66578125, 172.93632811999998), 'rotation':(-0.686096, -179.405472, -0.702667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3252.119375, 509.77929687999995, 173.06978515999998), 'rotation':(-0.689056, -179.40538, -0.70575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3263.21605469, 509.89285156, 173.20386718999998), 'rotation':(-0.693146, -179.405548, -0.710083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3274.31273438, 510.00644531, 173.33814453), 'rotation':(-0.693176, -179.405228, -0.710114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3279.86083984, 510.06320312, 173.4053125), 'rotation':(-0.693146, -179.405243, -0.710083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3285.40917969, 510.12, 173.47251953), 'rotation':(-0.693146, -179.405243, -0.710083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3290.95751953, 510.17675780999997, 173.53992188), 'rotation':(-0.69577, -179.405243, -0.71283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3296.50609375, 510.23351562000005, 173.60779297000002), 'rotation':(-0.701141, -179.40509, -0.718475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3302.05445312, 510.29027344, 173.67582031), 'rotation':(-0.703583, -179.405289, -0.721008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3307.60253906, 510.34707031, 173.74396484000002), 'rotation':(-0.703796, -179.404907, -0.721252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3324.24730469, 510.51289062, 173.94851562), 'rotation':(-0.704437, -179.405029, -0.721924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3329.79566406, 510.56566405999996, 174.01681641), 'rotation':(-0.704437, -179.405029, -0.721924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3606.09742188, 521.28265625, 177.37931641), 'rotation':(0.640795, 0.592036, 0.626576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3600.4275, 521.22460938, 177.31546875), 'rotation':(0.643363, 0.593956, 0.629033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3577.7465625, 520.9925390599999, 177.05603516), 'rotation':(0.66039, 0.59434, 0.645304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3566.4064843799997, 520.87648438, 176.92386718999998), 'rotation':(0.668969, 0.593948, 0.653497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3543.7267968799997, 520.64433594, 176.65623047), 'rotation':(0.677883, 0.594097, 0.661988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3538.05664062, 520.58636719, 176.58863281), 'rotation':(0.682875, 0.594642, 0.666755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3526.7165625, 520.4703515599999, 176.45246093999998), 'rotation':(0.687902, 0.594319, 0.671531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3521.04640625, 520.41242188, 176.38388672000002), 'rotation':(0.692834, 0.594902, 0.676224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3515.37671875, 520.354375, 176.31507812), 'rotation':(0.695327, 0.594687, 0.678608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3509.70703125, 520.29640625, 176.24623047), 'rotation':(0.695327, 0.594687, 0.678608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3504.036875, 520.23835938, 176.17726562), 'rotation':(0.696351, 0.594809, 0.679573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3492.69628906, 520.12230469, 176.03876953), 'rotation':(0.700238, 0.594902, 0.683274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3487.02660156, 520.06425781, 175.96927734000002), 'rotation':(0.702109, 0.594948, 0.685054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3464.34570312, 519.83222656, 175.689375), 'rotation':(0.710025, 0.595145, 0.692582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.32542969, 519.4840624999999, 175.26677734), 'rotation':(0.712177, 0.595309, 0.694649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3396.30421875, 519.13597656, 174.84304688), 'rotation':(0.713488, 0.595062, 0.695879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3390.63402344, 519.07792969, 174.77246093999997), 'rotation':(0.713051, 0.595372, 0.695473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3373.62351562, 518.9038281200001, 174.5609375), 'rotation':(0.711993, 0.59491, 0.694457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3362.28296875, 518.78773438, 174.41994140999998), 'rotation':(0.712156, 0.595589, 0.694619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3368.00390625, 510.96515625, 174.49005859000002), 'rotation':(-0.712158, -179.405075, -0.730042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3379.34421875, 511.08121094, 174.63103515999998), 'rotation':(-0.711975, -179.404739, -0.729858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3385.01464844, 511.13925781, 174.70154297000002), 'rotation':(-0.712158, -179.405075, -0.730042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3390.68457031, 511.19730469, 174.77207031), 'rotation':(-0.712433, -179.404892, -0.730316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3424.70554688, 511.54542969, 175.19578125), 'rotation':(-0.713379, -179.404938, -0.731323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3453.05640625, 511.83554688, 175.54824219), 'rotation':(-0.710999, -179.404892, -0.72879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3464.39671875, 511.9515625, 175.68900391), 'rotation':(-0.710999, -179.404877, -0.728821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3470.06640625, 512.00953125, 175.75923827999998), 'rotation':(-0.710022, -179.404846, -0.727783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3475.73679688, 512.06757812, 175.82931641), 'rotation':(-0.70816, -179.404892, -0.72583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3481.40671875, 512.125625, 175.89919922), 'rotation':(-0.706146, -179.404953, -0.723724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3487.07738281, 512.18367188, 175.96890625), 'rotation':(-0.704132, -179.405243, -0.721619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3504.08765625, 512.3577734400001, 176.17691406000003), 'rotation':(-0.698242, -179.405136, -0.715393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3509.7575781200003, 512.41570312, 176.24585938), 'rotation':(-0.696381, -179.405151, -0.71347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3515.42773438, 512.47375, 176.31472656000003), 'rotation':(-0.696381, -179.405151, -0.71347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3526.7678125, 512.58976562, 176.45210938), 'rotation':(-0.69281, -179.405334, -0.709717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3549.44847656, 512.81648438, 176.72304688), 'rotation':(-0.677887, -179.405685, -0.694061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3555.11839844, 512.87171875, 176.79), 'rotation':(-0.677887, -179.405685, -0.694061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3566.45851562, 513.0178906200001, 176.92353516), 'rotation':(-0.673309, -179.40564, -0.68927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3577.79882812, 513.145, 177.05570312), 'rotation':(-0.664734, -179.405823, -0.680267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3583.4689843799997, 513.20304688, 177.12117188), 'rotation':(-0.6604, -179.40625, -0.675751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3594.80933594, 513.31910156, 177.25091797000002), 'rotation':(-0.651825, -179.406418, -0.666809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3606.14964844, 513.43511719, 177.37900391), 'rotation':(-0.643402, -179.406311, -0.657959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3655.59695312, 513.89191406, 177.91416016), 'rotation':(-0.595978, -179.407501, -0.60849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3678.35203125, 514.1409375000001, 178.1465625), 'rotation':(-0.574646, -179.408173, -0.586273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3689.72953125, 514.25738281, 178.25810547), 'rotation':(-0.559753, -179.408447, -0.57077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3706.79734375, 514.4319531200001, 178.41960938), 'rotation':(-0.533997, -179.408813, -0.544037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3712.4870312499997, 514.4901171900001, 178.47263672), 'rotation':(-0.53418, -179.408783, -0.54422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3729.5546875, 514.66480469, 178.6275), 'rotation':(-0.50708, -179.409134, -0.516113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3735.24265625, 514.7230078099999, 178.67671875), 'rotation':(-0.50708, -179.409134, -0.516113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3752.31078125, 514.89765625, 178.81791016), 'rotation':(-0.4617, -179.409653, -0.469208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3763.6896875, 515.01410156, 178.90921875), 'rotation':(-0.456665, -179.409668, -0.463989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3786.4465625000003, 515.2469531200001, 179.08037109), 'rotation':(-0.415527, -179.41095, -0.42157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3803.51492188, 515.4215624999999, 179.19732422), 'rotation':(-0.384583, -179.410751, -0.389771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3820.58273438, 515.5961718799999, 179.30472656), 'rotation':(-0.339111, -179.411621, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3843.339375, 515.82902344, 179.4253125), 'rotation':(-0.274811, -179.412918, -0.277466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3849.02882812, 515.8871875, 179.45134765999998), 'rotation':(-0.258789, -179.412445, -0.261139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3854.71804688, 515.94539062, 179.47638672000002), 'rotation':(-0.250702, -179.412445, -0.252899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3848.95359375, 523.76734375, 179.45136718999998), 'rotation':(0.250688, 0.587106, 0.248514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3843.26414062, 523.7091015599999, 179.42533203), 'rotation':(0.258789, 0.58754, 0.256458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3837.57492188, 523.6509375, 179.39767578), 'rotation':(0.274806, 0.587715, 0.272178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3831.8854687499997, 523.59269531, 179.36833984), 'rotation':(0.290952, 0.587852, 0.288006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3826.19851562, 523.53449219, 179.33738281), 'rotation':(0.307126, 0.588047, 0.303846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3820.50875, 523.4762499999999, 179.30478516), 'rotation':(0.323116, 0.587561, 0.31949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3809.12984375, 523.35992188, 179.23458984), 'rotation':(0.355279, 0.588576, 0.3509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3797.7526562499997, 523.24347656, 179.159375), 'rotation':(0.384594, 0.588612, 0.379458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3780.68429688, 523.06898438, 179.03931641), 'rotation':(0.415515, 0.589044, 0.409515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3757.92921875, 522.83613281, 178.86384766), 'rotation':(0.456673, 0.589669, 0.449441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3752.2395312500003, 522.7778906200001, 178.81796875), 'rotation':(0.461707, 0.590339, 0.454305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3740.86109375, 522.66144531, 178.72507812), 'rotation':(0.470846, 0.590251, 0.463162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.171875, 522.60320312, 178.67681641), 'rotation':(0.488796, 0.590554, 0.480516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3723.79492188, 522.48695312, 178.57724609000002), 'rotation':(0.507053, 0.590854, 0.49814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3718.1059375, 522.42871094, 178.52527343999998), 'rotation':(0.525023, 0.590778, 0.515465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3712.4175, 522.37046875, 178.47275391), 'rotation':(0.525023, 0.590778, 0.515465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3706.7278125000003, 522.3122656200001, 178.41970702999998), 'rotation':(0.534162, 0.591188, 0.524266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3689.66039062, 522.1375781200001, 178.25820312), 'rotation':(0.552549, 0.591413, 0.541968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3672.59398438, 521.96308594, 178.0896875), 'rotation':(0.574672, 0.591847, 0.563233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3661.2160937500003, 521.84660156, 177.97324218999998), 'rotation':(0.589227, 0.592115, 0.577196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3654.09277344, 521.8058593799999, 177.89933594), 'rotation':(0.593079, 0.592223, 0.580911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3644.14769531, 521.80152344, 177.79501953), 'rotation':(0.602033, 0.59233, 0.589483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2984.32397461, 691.18201172, 169.60773438), 'rotation':(-0.641052, -173.744156, -0.655518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3000.7890625, 692.85552734, 169.79363281000002), 'rotation':(-0.648804, -174.44281, -0.663635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3006.31518555, 693.34423828, 169.85617188), 'rotation':(-0.64856, -174.908936, -0.663361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3022.95507812, 694.44585938, 170.04716797), 'rotation':(-0.665527, -177.017471, -0.681152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3028.50952148, 694.6873242199999, 170.11154297000002), 'rotation':(-0.665558, -177.635803, -0.681152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.62573242, 694.9829101600001, 170.24025390999998), 'rotation':(-0.665497, -178.872101, -0.681122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.7019043, 695.05285156, 170.36857422), 'rotation':(-0.667542, -179.658875, -0.683258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3056.22412109, 695.0646875, 170.43244141), 'rotation':(-0.66214, -179.868759, -0.677582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3105.86425781, 695.31646484, 171.0153125), 'rotation':(-0.679352, -179.868622, -0.695618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3111.37988281, 695.3283007800001, 171.08101562), 'rotation':(-0.68158, -179.868576, -0.697937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3122.41088867, 695.35974609, 171.21304688), 'rotation':(-0.685852, -179.868469, -0.702423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3127.34179688, 703.3881835899999, 171.27251952999998), 'rotation':(0.690102, 0.131625, 0.673619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.27514648, 703.364375, 171.13972656), 'rotation':(0.685833, 0.131523, 0.669556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3105.20849609, 703.34050781, 171.00771484), 'rotation':(0.681605, 0.131426, 0.66552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3099.67504883, 703.3285546899999, 170.94205078), 'rotation':(0.679358, 0.131366, 0.663386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3083.07446289, 703.2927929699999, 170.74619141), 'rotation':(0.674092, 0.131009, 0.658374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3077.54150391, 703.28033203, 170.68125), 'rotation':(0.672316, 0.131473, 0.656666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3055.40795898, 703.0884375, 170.42316406), 'rotation':(0.665506, 0.131314, 0.650171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3044.34619141, 703.05779297, 170.29560547), 'rotation':(0.652037, 0.341491, 0.637316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3038.82104492, 702.99828125, 170.23251953), 'rotation':(0.650883, 0.762179, 0.636236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3027.79052734, 702.69128906, 170.10679688), 'rotation':(0.650357, 2.054985, 0.635709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.26171875, 701.9198632800001, 169.91890625), 'rotation':(0.645863, 3.682369, 0.631432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2983.90161133, 699.28460938, 169.61289062), 'rotation':(0.641184, 6.255831, 0.626948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.28637695, 695.43365234, 171.67183594), 'rotation':(-0.702271, -179.867966, -0.719666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3171.32933594, 695.4574609399999, 171.80796875), 'rotation':(-0.708221, -179.867813, -0.725891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3182.37207031, 695.48121094, 171.94492188), 'rotation':(-0.711121, -179.867874, -0.728943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.89404297, 695.49310547, 172.01353516), 'rotation':(-0.711121, -179.867874, -0.728943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.93652344, 695.5169140600001, 172.15166016), 'rotation':(-0.719574, -179.867493, -0.737823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3209.97949219, 695.54070312, 172.29119140999998), 'rotation':(-0.726288, -179.868011, -0.744904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.50074219, 695.55261719, 172.36150390999998), 'rotation':(-0.729797, -179.867233, -0.748566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3226.54394531, 695.57640625, 172.50320312), 'rotation':(-0.736572, -179.86705, -0.755676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3232.06519531, 695.58826172, 172.57433593999997), 'rotation':(-0.73819, -179.866974, -0.757416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.58617188, 695.60015625, 172.64548828), 'rotation':(-0.738342, -179.866974, -0.757568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3248.62914062, 695.62396484, 172.78794922), 'rotation':(-0.73819, -179.867661, -0.757416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3254.15039062, 695.63580078, 172.85955077999998), 'rotation':(-0.742004, -179.866959, -0.761414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3276.23535156, 695.68335938, 173.14951172000002), 'rotation':(-0.753174, -179.866638, -0.773193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3281.75707031, 695.6953125, 173.22212890999998), 'rotation':(-0.753174, -179.866638, -0.773193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.32080078, 695.73095703, 173.44144531), 'rotation':(-0.760498, -179.866455, -0.780884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.36304688, 695.75470703, 173.58910156000002), 'rotation':(-0.766235, -179.866302, -0.786926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3320.05640625, 703.65857422, 173.73341797), 'rotation':(0.775021, 0.13329, 0.754261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3314.53125, 703.64666016, 173.65882812), 'rotation':(0.771914, 0.133856, 0.751331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.00660156, 703.63476562, 173.58455078), 'rotation':(0.769148, 0.133782, 0.748704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3303.48167969, 703.62287109, 173.51054688), 'rotation':(0.766204, 0.133703, 0.745922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3297.95703125, 703.61089844, 173.43683593999998), 'rotation':(0.763267, 0.133624, 0.74314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3275.85693359, 703.56330078, 173.14476562), 'rotation':(0.754633, 0.133395, 0.734942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3270.33203125, 703.55138672, 173.07210938), 'rotation':(0.753172, 0.133351, 0.733567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3264.80738281, 703.5394921899999, 172.99947265999998), 'rotation':(0.753103, 0.132994, 0.73351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3259.28222656, 703.52757812, 172.92691406000003), 'rotation':(0.753103, 0.132994, 0.73351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3248.23242188, 703.50384766, 172.78304688), 'rotation':(0.741963, 0.133029, 0.722936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.18238281, 703.47998047, 172.64052734), 'rotation':(0.738193, 0.13302, 0.719345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3226.13257812, 703.45617188, 172.498125), 'rotation':(0.738193, 0.13302, 0.719345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3220.60667969, 703.44427734, 172.42705078), 'rotation':(0.736554, 0.132946, 0.717812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.08203125, 703.43238281, 172.35638672000002), 'rotation':(0.733091, 0.132167, 0.714513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.50707031, 703.39666016, 172.14646484000002), 'rotation':(0.722825, 0.132592, 0.70477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3176.40648438, 703.3490625, 171.87105469), 'rotation':(0.711118, 0.132119, 0.693621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3165.35595703, 703.32525391, 171.73433594), 'rotation':(0.708209, 0.132179, 0.690859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3363.83351562, 695.87207031, 174.32884765999998), 'rotation':(-0.786041, -179.865891, -0.807831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3392.06398438, 695.93285156, 174.71626952999998), 'rotation':(-0.786041, -179.865891, -0.807831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3397.70996094, 695.9449999999999, 174.79384765999998), 'rotation':(-0.787476, -179.865509, -0.809326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.3559375, 695.95714844, 174.87173828), 'rotation':(-0.790161, -179.865952, -0.812164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3414.6482031200003, 695.98150391, 175.02777343999998), 'rotation':(-0.791595, -179.865631, -0.81369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3425.93992188, 696.00585938, 175.18380859), 'rotation':(-0.791626, -179.865631, -0.813721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3431.5859375, 696.01800781, 175.26183593999997), 'rotation':(-0.791595, -179.865631, -0.81369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3437.2321875, 696.03015625, 175.33986328), 'rotation':(-0.791595, -179.865631, -0.81369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3471.10816406, 696.10308594, 175.80634766), 'rotation':(-0.78775, -179.865646, -0.809662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3476.75390625, 696.11523438, 175.88392578), 'rotation':(-0.787903, -179.86618, -0.809784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3482.39992188, 696.1274414100001, 175.96138672), 'rotation':(-0.785767, -179.865814, -0.807526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3493.69164062, 696.15173828, 176.11558594), 'rotation':(-0.781494, -179.865921, -0.80304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3499.33789062, 696.1638281200001, 176.19220703), 'rotation':(-0.777405, -179.866043, -0.798706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3504.98363281, 696.17601562, 176.26867188), 'rotation':(-0.777405, -179.866043, -0.798706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3521.9216406200003, 696.2035546899999, 176.49697265999998), 'rotation':(-0.771057, -179.866119, -0.792053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3533.21335938, 696.26335938, 176.64841797), 'rotation':(-0.767975, -179.866226, -0.788788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3555.79734375, 696.31853516, 176.94664062), 'rotation':(-0.749237, -179.86673, -0.769043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3578.38160156, 696.19703125, 177.23978516), 'rotation':(-0.738251, -179.867004, -0.757477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3584.0278125, 696.20916016, 177.31193359), 'rotation':(-0.732849, -179.867142, -0.751801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3595.3200781200003, 696.2335156199999, 177.45455077999998), 'rotation':(-0.722321, -179.867416, -0.740692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3600.96605469, 696.24560547, 177.52505859000001), 'rotation':(-0.71698, -179.867554, -0.735107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3595.24878906, 704.38068359, 177.45388672), 'rotation':(0.716944, 0.132441, 0.699174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3578.29296875, 704.2840039099999, 177.23888672), 'rotation':(0.732859, 0.132844, 0.714289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3572.64109375, 704.2378515600001, 177.16611328), 'rotation':(0.738255, 0.132339, 0.719407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3566.98976562, 704.1917187500001, 177.09283202999998), 'rotation':(0.743411, 0.133115, 0.724309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3555.6875, 704.16601562, 176.94542968999997), 'rotation':(0.746082, 0.133377, 0.726847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3527.42796875, 704.1051562499999, 176.57113281000002), 'rotation':(0.767973, 0.133769, 0.7476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3516.12453125, 704.08082031, 176.41916016), 'rotation':(0.771067, 0.133873, 0.750521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3499.16917969, 704.04431641, 176.19015625), 'rotation':(0.773123, 0.13385, 0.752464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3487.86546875, 704.02001953, 176.03632812), 'rotation':(0.781483, 0.134077, 0.760374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3482.21335938, 704.0078125, 175.95904297), 'rotation':(0.781483, 0.134077, 0.760374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3470.91039062, 703.9835156199999, 175.80386718999998), 'rotation':(0.787862, 0.134359, 0.766407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3465.25855469, 703.97130859, 175.72613281000002), 'rotation':(0.787862, 0.134359, 0.766407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3436.99878906, 703.9104687500001, 175.336875), 'rotation':(0.791612, 0.134374, 0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.3471875, 703.8982617199999, 175.25876953), 'rotation':(0.791612, 0.134374, 0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3414.39109375, 703.86175781, 175.02445312), 'rotation':(0.791612, 0.134374, 0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3408.73902344, 703.8495507800001, 174.94632812), 'rotation':(0.791592, 0.13437, 0.769939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3391.78320312, 703.81310547, 174.71263672), 'rotation':(0.787466, 0.133983, 0.766045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3386.130625, 703.80089844, 174.63503906000003), 'rotation':(0.786032, 0.134545, 0.764686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3380.47875, 703.7887499999999, 174.5575), 'rotation':(0.786032, 0.134545, 0.764686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.17480469, 703.76441406, 174.40238281), 'rotation':(0.786052, 0.13411, 0.764703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3636.23875, 704.4689257800001, 177.95544922000002), 'rotation':(0.67388, 0.13152, 0.658154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3859.5051562500003, 704.8222070300001, 179.87433593999998), 'rotation':(0.247615, 0.124363, 0.245483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3848.19164062, 704.79529297, 179.82542969), 'rotation':(0.247615, 0.124363, 0.245483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3842.53539062, 704.78308594, 179.79984375), 'rotation':(0.257266, 0.124665, 0.254965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3819.913125, 704.7345507800001, 179.67707031), 'rotation':(0.334276, 0.125461, 0.330403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3802.94554688, 704.698125, 179.5640625), 'rotation':(0.392012, 0.126196, 0.386667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3797.29, 704.68591797, 179.52408203), 'rotation':(0.40156, 0.126274, 0.39597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3780.32273438, 704.64941406, 179.39769531000002), 'rotation':(0.434632, 0.126724, 0.428078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3769.01023438, 704.62511719, 179.30623047), 'rotation':(0.456516, 0.127065, 0.449283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3763.355, 704.61291016, 179.25892578), 'rotation':(0.478482, 0.127417, 0.470545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3752.0425, 704.58849609, 179.16210938), 'rotation':(0.489472, 0.127791, 0.481164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3746.38648438, 704.57634766, 179.11275390999998), 'rotation':(0.49495, 0.127341, 0.486465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.07398438, 704.5520703100001, 179.01046875), 'rotation':(0.528629, 0.128629, 0.518943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3729.4196875, 704.53986328, 178.95755859000002), 'rotation':(0.539824, 0.128154, 0.529718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3689.82835938, 704.45464844, 178.55847656000003), 'rotation':(0.601419, 0.129763, 0.588896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3672.86179688, 704.4182812500001, 178.37427734000002), 'rotation':(0.628371, 0.130341, 0.614707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3667.20609375, 704.4060742199999, 178.31103516), 'rotation':(0.637298, 0.130542, 0.62324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3655.89429688, 704.38171875, 178.18279297), 'rotation':(0.650692, 0.130864, 0.63604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3650.24121094, 704.4019140600001, 178.11833984), 'rotation':(0.655466, 0.130466, 0.640599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3638.88160156, 696.33484375, 177.98632812), 'rotation':(-0.683044, -179.868271, -0.699493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3655.85304688, 696.50091797, 178.18212891), 'rotation':(-0.650848, -179.869125, -0.665771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3661.5104687499997, 696.51306641, 178.24638672), 'rotation':(-0.650696, -179.869125, -0.665619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3667.16796875, 696.52527344, 178.31041016), 'rotation':(-0.64624, -179.869247, -0.66095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3678.48289062, 696.5496875, 178.43605469), 'rotation':(-0.628418, -179.869644, -0.642303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3712.4275, 696.62273438, 178.79103515999998), 'rotation':(-0.578979, -179.870865, -0.590759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3718.08445312, 696.63488281, 178.84763672), 'rotation':(-0.573303, -179.870514, -0.584839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3723.74585938, 696.64513672, 178.90306640999998), 'rotation':(-0.562256, -179.871414, -0.573364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3740.71414062, 696.68359375, 179.06191406000002), 'rotation':(-0.528595, -179.871368, -0.538422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3746.37179688, 696.69580078, 179.11248047), 'rotation':(-0.506348, -179.871765, -0.51535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3752.02929688, 696.70794922, 179.16185547), 'rotation':(-0.494965, -179.87265, -0.503571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3757.68703125, 696.72015625, 179.21037109), 'rotation':(-0.494965, -179.87265, -0.503571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3774.6596875, 696.7566601599999, 179.35244140999998), 'rotation':(-0.478516, -179.872971, -0.486542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3780.318125, 696.76878906, 179.39751952999998), 'rotation':(-0.456512, -179.872925, -0.463806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3785.97484375, 696.7809374999999, 179.44082031000002), 'rotation':(-0.434631, -179.87326, -0.441284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3791.63234375, 696.7931445300001, 179.48320311999998), 'rotation':(-0.434631, -179.87326, -0.441284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3797.29078125, 696.80529297, 179.52396484000002), 'rotation':(-0.412659, -179.873596, -0.41864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3819.9206249999997, 696.8540039100001, 179.67701172), 'rotation':(-0.353577, -179.874298, -0.357971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3825.57859375, 696.86621094, 179.71080078), 'rotation':(-0.33429, -179.875198, -0.338196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3831.2356250000003, 696.87830078, 179.74253906), 'rotation':(-0.315002, -179.874741, -0.318481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3836.89359375, 696.89050781, 179.77222656), 'rotation':(-0.295685, -179.874954, -0.298767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3848.20875, 696.91486328, 179.82542969), 'rotation':(-0.257263, -179.875336, -0.259583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3853.86648438, 696.92699219, 179.84988281000003), 'rotation':(-0.24762, -179.875641, -0.249756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3840.58890625, 795.24414062, 180.03359375), 'rotation':(0.296635, 0.062004, 0.293576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3829.23484375, 795.23210938, 179.97136719), 'rotation':(0.312707, 0.062228, 0.309304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.87914062, 795.22015625, 179.90425781000002), 'rotation':(0.327139, 0.062805, 0.323415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.20359375, 795.21417969, 179.86890625), 'rotation':(0.35603, 0.062796, 0.351624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.52515625, 795.20818359, 179.83074219), 'rotation':(0.384717, 0.063164, 0.379586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3789.49289062, 795.19025391, 179.70902343999998), 'rotation':(0.413595, 0.063565, 0.407669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3778.13820312, 795.17822266, 179.62267577999998), 'rotation':(0.43511, 0.064097, 0.428543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3772.46023438, 795.17224609, 179.57759765999998), 'rotation':(0.449187, 0.064313, 0.442189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.10742188, 795.16021484, 179.48316406), 'rotation':(0.477382, 0.064767, 0.469485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3744.07398438, 795.14220703, 179.33082031), 'rotation':(0.533779, 0.065763, 0.523904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3732.72070312, 795.13019531, 179.22373047000002), 'rotation':(0.540999, 0.065889, 0.530864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.36523438, 795.11816406, 179.11345702999998), 'rotation':(0.550991, 0.065693, 0.540467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3715.68703125, 795.11224609, 179.056875), 'rotation':(0.570963, 0.066457, 0.559657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3698.65601562, 795.0941796899999, 178.87908202999998), 'rotation':(0.61109, 0.066919, 0.598161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3687.30296875, 795.0823437500001, 178.75644531), 'rotation':(0.621131, 0.067637, 0.607766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3675.9479687499997, 795.0703125, 178.63107422000002), 'rotation':(0.636758, 0.068047, 0.622723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3670.27046875, 795.06427734, 178.56677734000002), 'rotation':(0.647099, 0.067645, 0.632612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3658.91796875, 795.05224609, 178.43501952999998), 'rotation':(0.668013, 0.068761, 0.652577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3653.24023438, 795.04626953, 178.36751952999998), 'rotation':(0.678525, 0.068373, 0.662598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3641.88648438, 795.03429688, 178.22951172), 'rotation':(0.699439, 0.068871, 0.682527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3636.20851562, 795.02826172, 178.15966797000002), 'rotation':(0.704753, 0.069336, 0.687577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3641.87085938, 787.15349609, 178.22921875), 'rotation':(-0.704773, -179.930649, -0.72226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3653.22414062, 787.16558594, 178.36722656), 'rotation':(-0.688995, -179.931366, -0.70575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3670.25414062, 787.18353516, 178.56648438), 'rotation':(-0.657745, -179.931473, -0.672974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3675.93117188, 787.18957031, 178.63078125), 'rotation':(-0.647125, -179.932343, -0.661865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3681.6081249999997, 787.1955468799999, 178.69400391), 'rotation':(-0.63678, -179.931946, -0.651031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3692.9621875000003, 787.20757812, 178.81773438), 'rotation':(-0.621124, -179.93277, -0.634705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3704.31617188, 787.21966797, 178.93935547), 'rotation':(-0.611115, -179.932709, -0.624237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.3471875, 787.23761719, 179.11320312), 'rotation':(-0.570953, -179.933533, -0.582428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3732.70164062, 787.2496874999999, 179.22345703), 'rotation':(-0.550995, -179.933914, -0.561676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.37867188, 787.255625, 179.27730469), 'rotation':(-0.541016, -179.934097, -0.5513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3749.73265625, 787.26763672, 179.38277344), 'rotation':(-0.519867, -179.934479, -0.529358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3755.40992188, 787.2736718799999, 179.43355469), 'rotation':(-0.505585, -179.934738, -0.514557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.0871875000003, 787.27960938, 179.48292969), 'rotation':(-0.491516, -179.934967, -0.5), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3766.76367188, 787.28564453, 179.53085938), 'rotation':(-0.477386, -179.935211, -0.485382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3778.118125, 787.29767578, 179.62246094), 'rotation':(-0.449188, -179.935684, -0.456268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3783.7956249999997, 787.30365234, 179.66613281000002), 'rotation':(-0.43512, -179.935883, -0.441772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3800.82765625, 787.32166016, 179.7915625), 'rotation':(-0.413605, -179.936432, -0.419586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.504375, 787.32763672, 179.83054688), 'rotation':(-0.413605, -179.936432, -0.419586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.1823437499997, 787.33375, 179.86869141), 'rotation':(-0.384735, -179.936493, -0.389923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3823.535625, 787.34570312, 179.93878906), 'rotation':(-0.356018, -179.937195, -0.360474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3829.21414062, 787.35167969, 179.97121094), 'rotation':(-0.327148, -179.937561, -0.330902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3851.92335938, 787.37566406, 180.08953125), 'rotation':(-0.264404, -179.938309, -0.266876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3991.83109375, 794.37798828, 180.15460938), 'rotation':(-0.259369, -0.454132, -0.261749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3986.17359375, 794.42308594, 180.17789062), 'rotation':(-0.237, -0.454895, -0.238983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3974.85351562, 794.513125, 180.21613281), 'rotation':(-0.209564, -0.454895, -0.21109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.19851562, 794.5581640600001, 180.23078125), 'rotation':(-0.154449, -0.455658, -0.155273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3957.87820312, 794.64826172, 180.24697265999998), 'rotation':(-0.099426, -0.455475, -0.099762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3952.2196875, 794.69335938, 180.25089844), 'rotation':(-0.044312, -0.455627, -0.044373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3940.89773438, 794.7834375, 180.25421875), 'rotation':(-0.016754, -0.45575, -0.016754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3935.2365625, 794.82849609, 180.25587890999998), 'rotation':(-0.016846, -0.45578, -0.016846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3912.5964062499997, 795.00861328, 180.26050781), 'rotation':(-0.016846, -0.45575, -0.016846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3906.93820312, 795.05365234, 180.25697266), 'rotation':(0.019705, -0.45578, 0.019688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3901.27734375, 795.09880859, 180.24783202999998), 'rotation':(0.092638, -0.455627, 0.092336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3893.24976562, 795.25769531, 180.22757812), 'rotation':(0.153727, -0.390411, 0.152899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3935.21, 786.94792969, 180.25585938), 'rotation':(0.016741, 179.544235, 0.016729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3940.87179688, 786.90294922, 180.25421875), 'rotation':(0.016843, 179.544235, 0.016823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3946.53367188, 786.85791016, 180.25253906), 'rotation':(0.016843, 179.544235, 0.016823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.17625, 786.67767578, 180.23070312), 'rotation':(0.09942, 179.54451, 0.099078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3980.49195312, 786.58757812, 180.19841797), 'rotation':(0.154437, 179.544754, 0.153607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3161.47729492, 596.79375, 171.81083984), 'rotation':(-0.680115, -179.320404, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3167.015625, 596.85863281, 171.87658202999998), 'rotation':(-0.680115, -179.320404, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3172.55419922, 596.92359375, 171.94234375), 'rotation':(-0.680115, -179.320801, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3178.09300781, 596.98847656, 172.00832031000002), 'rotation':(-0.680115, -179.320801, -0.696411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3200.24755859, 597.2479687499999, 172.27482422), 'rotation':(-0.692902, -179.32048, -0.709808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.32470703, 597.3778125, 172.40996094), 'rotation':(-0.698181, -179.320343, -0.715363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3227.93945312, 597.57246094, 172.61320312), 'rotation':(-0.700623, -179.320145, -0.717926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3233.47828125, 597.63738281, 172.68113281), 'rotation':(-0.702545, -179.320068, -0.71991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3244.55566406, 597.76714844, 172.81804688), 'rotation':(-0.710083, -179.31987, -0.727875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3250.09398438, 597.83203125, 172.88705077999998), 'rotation':(-0.71405, -179.319748, -0.732025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3255.6328125, 597.89695312, 172.95623047), 'rotation':(-0.71582, -179.319717, -0.733887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3261.17113281, 597.96183594, 173.02546875), 'rotation':(-0.71582, -179.319717, -0.733887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3266.70972656, 598.02671875, 173.0946875), 'rotation':(-0.715942, -179.319717, -0.734009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3277.78636719, 598.1565625000001, 173.23357422), 'rotation':(-0.719543, -179.320282, -0.737793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3283.32496094, 598.22144531, 173.30341797), 'rotation':(-0.722076, -179.31955, -0.740479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3299.94019531, 598.4161328099999, 173.51447266), 'rotation':(-0.729584, -179.319351, -0.748322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3322.09398438, 598.67570312, 173.79865234000002), 'rotation':(-0.735687, -179.31897, -0.754761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3327.63232422, 598.7405859400001, 173.86980469), 'rotation':(-0.735687, -179.31955, -0.754761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3321.94214844, 606.55511719, 173.79789062), 'rotation':(0.735686, 0.681027, 0.716967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3310.86962891, 606.42535156, 173.65570312), 'rotation':(0.735536, 0.681023, 0.716832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3305.33277344, 606.36046875, 173.58464844), 'rotation':(0.734505, 0.680776, 0.71585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3294.26050781, 606.2307812500001, 173.44324218999998), 'rotation':(0.729573, 0.679965, 0.711172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3277.65136719, 606.03613281, 173.23302734), 'rotation':(0.722088, 0.680458, 0.704058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3272.11474609, 605.97132812, 173.16349609), 'rotation':(0.719533, 0.680398, 0.701624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3261.04175781, 605.8415625, 173.025), 'rotation':(0.715927, 0.680274, 0.698208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3249.96851562, 605.71179688, 172.88664062), 'rotation':(0.715817, 0.680271, 0.698108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3238.89599609, 605.58210938, 172.7490625), 'rotation':(0.710087, 0.679523, 0.692649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3222.28613281, 605.3875, 172.54515625), 'rotation':(0.700627, 0.679848, 0.683637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3216.75, 605.3226171900001, 172.47744140999998), 'rotation':(0.700627, 0.679848, 0.683637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3200.14013672, 605.12800781, 172.27464844), 'rotation':(0.698168, 0.680054, 0.68131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3189.06714844, 604.99828125, 172.14080077999998), 'rotation':(0.692875, 0.679519, 0.676273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.99414062, 604.86847656, 172.00822266), 'rotation':(0.682705, 0.679684, 0.666575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3166.92089844, 604.73871094, 171.8765625), 'rotation':(0.680116, 0.679197, 0.664114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3363.91210938, 607.17640625, 174.34125), 'rotation':(0.744538, 0.681032, 0.725381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3601.63207031, 609.83210938, 177.38644531000003), 'rotation':(0.677159, 0.679212, 0.661285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3591.70191406, 609.71582031, 177.26755859000002), 'rotation':(0.688763, 0.67982, 0.672341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3580.40113281, 609.58335938, 177.13072266), 'rotation':(0.697506, 0.680028, 0.680687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3529.54859375, 608.98753906, 176.49683593999998), 'rotation':(0.724512, 0.680419, 0.706351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3518.24757812, 608.8551171900001, 176.35246094), 'rotation':(0.734245, 0.680665, 0.715609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3495.64648438, 608.5903125, 176.06175781000002), 'rotation':(0.736602, 0.680944, 0.717847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3473.04492188, 608.32550781, 175.76894531000002), 'rotation':(0.744989, 0.681223, 0.725799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3467.39453125, 608.2594140599999, 175.69511719), 'rotation':(0.748343, 0.680866, 0.728985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3456.0939843799997, 608.12695312, 175.54722656), 'rotation':(0.750037, 0.681338, 0.730588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3444.79296875, 607.99457031, 175.39923828), 'rotation':(0.75003, 0.680764, 0.730589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3439.14234375, 607.92835938, 175.32523438), 'rotation':(0.750064, 0.681366, 0.730615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3427.8415625, 607.79597656, 175.17716797), 'rotation':(0.750747, 0.681316, 0.731258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3416.54054688, 607.66351562, 175.02898438), 'rotation':(0.75113, 0.68106, 0.731637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3410.89015625, 607.5973437499999, 174.95488281000002), 'rotation':(0.751116, 0.681033, 0.731619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3405.23976562, 607.5311328099999, 174.88078125), 'rotation':(0.75113, 0.68106, 0.731637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3393.93847656, 607.3987500000001, 174.73261718999998), 'rotation':(0.750221, 0.681138, 0.730761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3376.98679688, 607.2000781200001, 174.51125), 'rotation':(0.746929, 0.681026, 0.727642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3376.96140625, 599.31855469, 174.50970703), 'rotation':(-0.745392, -179.319, -0.764984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3382.6247656200003, 599.3848828099999, 174.58351562), 'rotation':(-0.746948, -179.31897, -0.766602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3388.28832031, 599.45136719, 174.65748047), 'rotation':(-0.74881, -179.318893, -0.768585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3405.27882812, 599.6503124999999, 174.88007812), 'rotation':(-0.751251, -179.318954, -0.771149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3433.59644531, 599.9821093799999, 175.25138672), 'rotation':(-0.750763, -179.319122, -0.77066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3439.26, 600.04851562, 175.32558594), 'rotation':(-0.750305, -179.318665, -0.770142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3444.92335938, 600.1148828099999, 175.39974609), 'rotation':(-0.750031, -179.319229, -0.769867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3456.25046875, 600.2475781200001, 175.54806641), 'rotation':(-0.750031, -179.318649, -0.769867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3467.57714844, 600.38023438, 175.69630859), 'rotation':(-0.750031, -179.319229, -0.769867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3478.9040625, 600.51300781, 175.84396484), 'rotation':(-0.744995, -179.319183, -0.764557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3484.56789062, 600.57933594, 175.91746093999998), 'rotation':(-0.744995, -179.319183, -0.764557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3490.23070312, 600.64570312, 175.99076172000002), 'rotation':(-0.741699, -179.318878, -0.761078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3507.22117188, 600.84480469, 176.20951172000002), 'rotation':(-0.736633, -179.319412, -0.755737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3512.88476562, 600.91113281, 176.28234375), 'rotation':(-0.736603, -179.319046, -0.755737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3518.54808594, 600.9730078099999, 176.35511719), 'rotation':(-0.736603, -179.319046, -0.755737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3529.8747656200003, 601.12089844, 176.49982422000002), 'rotation':(-0.729462, -179.319458, -0.748199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3546.86476562, 601.34226562, 176.71371093999997), 'rotation':(-0.717377, -179.319519, -0.735504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3558.191875, 601.4749609400001, 176.85550781), 'rotation':(-0.717346, -179.320053, -0.735504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3563.85546875, 601.5413281200001, 176.92603516), 'rotation':(-0.715179, -179.319534, -0.733215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3580.8459375, 601.7403515599999, 177.135), 'rotation':(-0.702057, -179.319855, -0.719421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3586.50929688, 601.8067578099999, 177.20378906000002), 'rotation':(-0.69751, -179.320602, -0.714661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3592.17234375, 601.8731250000001, 177.27212891), 'rotation':(-0.693298, -179.320084, -0.710236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3601.7221875, 601.98503906, 177.38640625), 'rotation':(-0.681702, -179.319611, -0.69809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3833.88351562, 611.11207031, 179.52818359), 'rotation':(0.299114, 0.28829, 0.295998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3822.53492188, 611.05535156, 179.46392577999998), 'rotation':(0.32774, 0.288599, 0.32402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3811.18773438, 610.99859375, 179.39355468999997), 'rotation':(0.370613, 0.288451, 0.36585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3805.5134375, 610.97027344, 179.35607422), 'rotation':(0.384867, 0.289325, 0.379725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3799.839375, 610.941875, 179.31707031000002), 'rotation':(0.399081, 0.289508, 0.393551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3794.16554688, 610.9134375, 179.27703125), 'rotation':(0.406198, 0.289714, 0.400467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3782.81710938, 610.85667969, 179.195), 'rotation':(0.422625, 0.289617, 0.416429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3771.46726562, 610.7999218799999, 179.10832031), 'rotation':(0.444768, 0.290647, 0.4379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3754.44726562, 610.71484375, 178.96892577999998), 'rotation':(0.477799, 0.290483, 0.469888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3743.10007812, 610.6580859400001, 178.87117188), 'rotation':(0.494369, 0.291281, 0.485887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3737.42601562, 610.6296875, 178.82138672000002), 'rotation':(0.499403, 0.290954, 0.490756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3686.36109375, 610.374375, 178.32962891), 'rotation':(0.581194, 0.29253, 0.569489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3680.68679688, 610.3460156200001, 178.27117188), 'rotation':(0.581194, 0.29253, 0.569489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3663.66429688, 610.2608593799999, 178.09085938), 'rotation':(0.609663, 0.293111, 0.596789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3652.31714844, 610.20417969, 177.96673828), 'rotation':(0.630987, 0.293383, 0.617204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3641.89722656, 610.2815625000001, 177.85113281000002), 'rotation':(0.635932, 0.293658, 0.621925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3650.68992188, 602.3035156200001, 177.94830077999998), 'rotation':(-0.635925, -179.706345, -0.650177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3658.54367188, 602.35457031, 178.03466797000002), 'rotation':(-0.630981, -179.706604, -0.64502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3664.22359375, 602.3829296900001, 178.09650391), 'rotation':(-0.623871, -179.706573, -0.637543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3669.9028125, 602.41136719, 178.15738281000003), 'rotation':(-0.623871, -179.706573, -0.637543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3698.30007812, 602.55339844, 178.44974609000002), 'rotation':(-0.574005, -179.707382, -0.585602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3703.97898438, 602.58183594, 178.50644531), 'rotation':(-0.574005, -179.707382, -0.585602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3709.6584375, 602.61023438, 178.56238281000003), 'rotation':(-0.569092, -179.707748, -0.580475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.01757812, 602.66707031, 178.67119141), 'rotation':(-0.539185, -179.708313, -0.549408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3726.69625, 602.69539062, 178.72402344), 'rotation':(-0.529327, -179.708511, -0.539154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3732.3759375, 602.72386719, 178.77583984), 'rotation':(-0.519135, -179.708694, -0.528595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.055625, 602.7523046900001, 178.82662109), 'rotation':(-0.50943, -179.708862, -0.518555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3749.41476562, 602.80902344, 178.92546875), 'rotation':(-0.494385, -179.709244, -0.50296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3760.7734375, 602.86578125, 179.02171875), 'rotation':(-0.477814, -179.709503, -0.48584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3766.45242188, 602.8942187499999, 179.068125), 'rotation':(-0.466919, -179.709702, -0.474548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3772.1315624999997, 602.92265625, 179.11318359), 'rotation':(-0.455841, -179.709869, -0.463135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3783.4909374999997, 602.97941406, 179.19966797), 'rotation':(-0.433868, -179.709518, -0.440491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.56859375, 603.14984375, 179.43365234), 'rotation':(-0.356232, -179.711044, -0.360657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3828.9275, 603.2066796900001, 179.50070312), 'rotation':(-0.327759, -179.711395, -0.331512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3834.6071875, 603.23503906, 179.53191406000002), 'rotation':(-0.313354, -179.711563, -0.316772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3840.2864062500003, 603.2634375, 179.56160156), 'rotation':(-0.299103, -179.712372, -0.302246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3992.06398438, 611.90300781, 179.79724609000002), 'rotation':(-0.150696, 0.28686, -0.151489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3986.64429688, 611.87578125, 179.81148438), 'rotation':(-0.150604, 0.287292, -0.151398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3981.22585938, 611.84871094, 179.82519531000003), 'rotation':(-0.150604, 0.287292, -0.151398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3943.29664062, 611.6590625, 179.86148438), 'rotation':(-0.012177, 0.286532, -0.012177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3932.4596874999997, 611.6049218799999, 179.85703125), 'rotation':(0.036542, 0.286565, 0.036485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3921.62351562, 611.55070312, 179.84443359), 'rotation':(0.085391, 0.286652, 0.085141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3916.20460938, 611.52363281, 179.83509766), 'rotation':(0.085391, 0.286652, 0.085141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3897.12648438, 603.4815625, 179.78667968999997), 'rotation':(-0.170654, -179.713242, -0.171661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3906.66773438, 603.59546875, 179.81388672), 'rotation':(-0.158447, -179.713028, -0.159332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3918.0207812500003, 603.6522265599999, 179.83851562), 'rotation':(-0.109589, -179.712677, -0.110016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3935.05078125, 603.73738281, 179.85867188), 'rotation':(-0.03653, -179.71344, -0.036591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3946.40304688, 603.79414062, 179.8609375), 'rotation':(-0.012177, -179.713455, -0.012177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3957.7578125, 603.85089844, 179.85683594), 'rotation':(0.024418, -179.713867, 0.024387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3963.43453125, 603.8792578099999, 179.85351562), 'rotation':(0.040298, -179.713501, 0.040232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3969.11132812, 603.90765625, 179.84779297), 'rotation':(0.071621, -179.713425, 0.071446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3980.463125, 603.96441406, 179.82708984), 'rotation':(0.134883, -179.713196, 0.134248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3991.8176562500003, 604.0211718799999, 179.79798828), 'rotation':(0.150592, -179.713135, 0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3997.495625, 604.04957031, 179.78304688), 'rotation':(0.150927, -179.712372, 0.150136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.97802734, 883.74267578, 171.12859375), 'rotation':(0.727101, 0.284404, 0.708813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3111.45141602, 883.71612305, 171.05867188), 'rotation':(0.727101, 0.284404, 0.708813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3105.92456055, 883.68957031, 170.98902343999998), 'rotation':(0.722081, 0.284266, 0.704051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3100.39746094, 883.66302734, 170.91972656000002), 'rotation':(0.722081, 0.284266, 0.704051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3094.87036133, 883.6365332, 170.85054688), 'rotation':(0.716917, 0.283784, 0.699132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3089.34350586, 883.60992188, 170.78164062), 'rotation':(0.714499, 0.284236, 0.696833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3083.81616211, 883.5834375, 170.7128125), 'rotation':(0.712976, 0.28357, 0.695403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3072.76245117, 883.53033203, 170.5759375), 'rotation':(0.707676, 0.283438, 0.69036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3056.18164062, 883.45074219, 170.37255859), 'rotation':(0.699726, 0.283869, 0.682786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3045.12792969, 883.39770508, 170.23822266), 'rotation':(0.694425, 0.283118, 0.677732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3039.60058594, 883.37115234, 170.17130859), 'rotation':(0.692923, 0.283646, 0.676319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3034.07397461, 883.34466797, 170.10445312), 'rotation':(0.693114, 0.283013, 0.676502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3028.54711914, 883.31811523, 170.03757812), 'rotation':(0.69308, 0.28365, 0.676474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.96606445, 883.23852539, 169.83796875), 'rotation':(0.688681, 0.283001, 0.672278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2995.38549805, 883.15893555, 169.63988281000002), 'rotation':(0.68433, 0.28312, 0.668129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2989.85888672, 883.13244141, 169.57386719), 'rotation':(0.68444, 0.283131, 0.668236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2984.33178711, 883.10589844, 169.50785156), 'rotation':(0.68444, 0.283131, 0.668236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2984.35424805, 875.22521484, 169.50765625), 'rotation':(-0.684357, -179.716873, -0.700836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2995.40795898, 875.27826172, 169.63970702999998), 'rotation':(-0.684418, -179.716476, -0.700928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.98852539, 875.35785156, 169.83779297), 'rotation':(-0.684357, -179.716873, -0.700836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.67797852, 875.54364258, 170.30507812), 'rotation':(-0.694427, -179.716263, -0.711395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3056.20483398, 875.57012695, 170.37238281), 'rotation':(-0.697083, -179.716187, -0.714203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3061.73193359, 875.59667969, 170.43990234), 'rotation':(-0.699768, -179.716736, -0.71701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3072.78564453, 875.6497168, 170.57576172), 'rotation':(-0.705017, -179.716629, -0.722534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3078.3125, 875.67626953, 170.64408203), 'rotation':(-0.707672, -179.715927, -0.725342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3089.36645508, 875.72930664, 170.78144531), 'rotation':(-0.712982, -179.715805, -0.730896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3111.47363281, 875.83740234, 171.05849609), 'rotation':(-0.722076, -179.715729, -0.740479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3122.52807617, 875.88848633, 171.19855468999998), 'rotation':(-0.727112, -179.715958, -0.745728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3171.49535156, 876.03033203, 171.83068359), 'rotation':(-0.754059, -179.714737, -0.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.01878906, 876.11707031, 171.90359375), 'rotation':(-0.754059, -179.714737, -0.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3182.54125, 876.17664062, 171.97679688), 'rotation':(-0.758179, -179.71463, -0.778442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3188.06519531, 876.203125, 172.05011718999998), 'rotation':(-0.760315, -179.715057, -0.780701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.59007812, 876.22960938, 172.12357422000002), 'rotation':(-0.762207, -179.714447, -0.782684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3210.16259766, 876.30919922, 172.34605469), 'rotation':(-0.773315, -179.714172, -0.794403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3226.73511719, 876.38878906, 172.57208984000002), 'rotation':(-0.78421, -179.714569, -0.805908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.78320312, 876.44183594, 172.72429688), 'rotation':(-0.789764, -179.713913, -0.811768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3254.35570312, 876.52136719, 172.95306641), 'rotation':(-0.793884, -179.71402, -0.816132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.4040625, 876.5744043, 173.10738281000002), 'rotation':(-0.802277, -179.713776, -0.824982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3270.92822266, 876.60095703, 173.18517577999998), 'rotation':(-0.806549, -179.713654, -0.829498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3276.45191406, 876.62744141, 173.26292969), 'rotation':(-0.806549, -179.713654, -0.829498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3287.5, 876.6805468800001, 173.41859375), 'rotation':(-0.808014, -179.713593, -0.831055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3293.02367188, 876.70703125, 173.49669922), 'rotation':(-0.811249, -179.713516, -0.834473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.54761719, 876.7335156199999, 173.57513672000002), 'rotation':(-0.814331, -179.713425, -0.837738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3315.119375, 876.82525391, 173.81226562), 'rotation':(-0.823639, -179.713135, -0.847595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3326.16748047, 876.89916992, 173.97191406000002), 'rotation':(-0.829895, -179.712952, -0.854187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.58277344, 884.66736328, 173.73326172), 'rotation':(0.823639, 0.286845, 0.800212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3304.05882812, 884.64086914, 173.65421875), 'rotation':(0.820572, 0.286767, 0.797327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3287.48730469, 884.56133789, 173.41894531000003), 'rotation':(0.811235, 0.286492, 0.788506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3281.96289062, 884.53478516, 173.34105469), 'rotation':(0.807977, 0.2864, 0.785425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.39111328, 884.45526367, 173.10773438), 'rotation':(0.806529, 0.286343, 0.784053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3259.86669922, 884.42871094, 173.0303125), 'rotation':(0.802301, 0.286222, 0.780071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3254.34253906, 884.40228516, 172.95341797), 'rotation':(0.802301, 0.286222, 0.780071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3232.24632812, 884.29608398, 172.64849609), 'rotation':(0.789782, 0.28608, 0.768218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3221.19726562, 884.2430468800001, 172.49667968999998), 'rotation':(0.784215, 0.286137, 0.762966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.67333984, 884.21649414, 172.42134765999998), 'rotation':(0.780574, 0.28534, 0.759529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3204.625, 884.16345703, 172.27183594), 'rotation':(0.773287, 0.285142, 0.752641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.57691406, 884.11041016, 172.12390625), 'rotation':(0.765849, 0.284949, 0.74557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3188.05152344, 884.0839257800001, 172.05042969), 'rotation':(0.762201, 0.285541, 0.742131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3177.00585938, 884.06366211, 171.90392577999998), 'rotation':(0.758158, 0.285367, 0.738288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3171.4821875, 884.09735352, 171.83101562), 'rotation':(0.758158, 0.285367, 0.738288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3165.95386719, 884.1073632800001, 171.75841797), 'rotation':(0.754026, 0.284658, 0.734358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3584.36058594, 885.9863867199999, 177.70615234000002), 'rotation':(0.763519, 0.285559, 0.743368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3573.0646875, 885.9321875, 177.55240234000001), 'rotation':(0.784707, 0.285751, 0.763421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3544.8259375, 885.79657227, 177.16128906000003), 'rotation':(0.80099, 0.286124, 0.778827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3539.17796875, 885.76953125, 177.08166015999998), 'rotation':(0.808264, 0.286331, 0.785705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3533.53003906, 885.74243164, 177.00164062), 'rotation':(0.808264, 0.286331, 0.785705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3522.234375, 885.68823242, 176.84044922), 'rotation':(0.819158, 0.286482, 0.795986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3516.58691406, 885.66113281, 176.75966797), 'rotation':(0.819336, 0.286487, 0.796145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3510.93871094, 885.6340332, 176.67867188), 'rotation':(0.820531, 0.287042, 0.797266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3505.29078125, 885.60693359, 176.59742188), 'rotation':(0.823284, 0.28711, 0.79988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3493.99488281, 885.55273438, 176.43410156000002), 'rotation':(0.828584, 0.287263, 0.804868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3488.3459375, 885.52789062, 176.35201172), 'rotation':(0.833911, 0.286769, 0.809891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3482.69898438, 885.49841797, 176.26966797), 'rotation':(0.836514, 0.287491, 0.812354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3454.45972656, 885.36285156, 175.85556641), 'rotation':(0.8404, 0.287634, 0.816014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3448.81175781, 885.33582031, 175.77259766), 'rotation':(0.8404, 0.287634, 0.816014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3443.1640625, 885.30865234, 175.68939453), 'rotation':(0.842777, 0.287182, 0.818249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3414.92382812, 885.1730957, 175.27271484000002), 'rotation':(0.845058, 0.287505, 0.820393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.62742188, 885.11883789, 175.10611328), 'rotation':(0.844259, 0.287386, 0.819657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3392.33128906, 885.06463867, 174.93990234), 'rotation':(0.84264, 0.287859, 0.818122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.03539062, 885.01037109, 174.77388672), 'rotation':(0.841664, 0.287499, 0.817203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3375.3871875, 884.98333984, 174.69087890999998), 'rotation':(0.841664, 0.287499, 0.817203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3364.09644531, 877.04828125, 174.52439453), 'rotation':(-0.839539, -179.712585, -0.864441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.744375, 877.07538086, 174.60738281000002), 'rotation':(-0.841766, -179.712952, -0.86676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.04078125, 877.12969727, 174.77339844), 'rotation':(-0.841797, -179.712479, -0.866791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3386.68898438, 877.15679688, 174.85640625), 'rotation':(-0.841644, -179.712494, -0.866638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3392.33691406, 877.18383789, 174.93941406000002), 'rotation':(-0.841797, -179.712479, -0.866791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3397.98511719, 877.21099609, 175.02248047), 'rotation':(-0.842621, -179.712646, -0.867676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3426.22582031, 877.3465625, 175.43892577999998), 'rotation':(-0.845093, -179.712479, -0.8703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.87402344, 877.37359375, 175.52224609), 'rotation':(-0.845184, -179.712479, -0.870392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3437.52171875, 877.40069336, 175.60556641), 'rotation':(-0.845184, -179.712479, -0.870392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3460.11402344, 877.50921875, 175.93798827999998), 'rotation':(-0.840424, -179.712936, -0.865387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3471.41039062, 877.56341797, 176.10375), 'rotation':(-0.840393, -179.712952, -0.865326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3482.70628906, 877.61767578, 176.26921875), 'rotation':(-0.838989, -179.712433, -0.863831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3494.00195312, 877.67181641, 176.43365234), 'rotation':(-0.831055, -179.712662, -0.855438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3505.29808594, 877.72601562, 176.59699218999998), 'rotation':(-0.825775, -179.712814, -0.849854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3533.53859375, 877.8943457, 177.00123047), 'rotation':(-0.815552, -179.71347, -0.83902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3539.18628906, 877.92175781, 177.08125), 'rotation':(-0.815552, -179.71347, -0.83902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3544.83445312, 877.94884766, 177.16087890999998), 'rotation':(-0.808258, -179.713669, -0.831329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3567.42726562, 878.05731445, 177.47443359000002), 'rotation':(-0.789917, -179.713989, -0.81192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3573.07542969, 878.08447266, 177.55203125), 'rotation':(-0.789917, -179.713989, -0.81192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3578.72363281, 878.11157227, 177.62939452999998), 'rotation':(-0.784698, -179.714249, -0.806427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3590.01953125, 878.16571289, 177.78181641), 'rotation':(-0.774109, -179.714539, -0.795258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3601.3159375, 878.2199707, 177.93167968999998), 'rotation':(-0.763519, -179.714828, -0.784058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3633.7478125, 878.38910156, 178.34972656000002), 'rotation':(-0.723358, -179.5746, -0.741821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3639.40332031, 878.43017578, 178.42015625), 'rotation':(-0.710693, -179.574905, -0.728516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3645.0590625, 878.47125, 178.48978516), 'rotation':(-0.710693, -179.574905, -0.728516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3656.37039062, 878.5534668, 178.62628906), 'rotation':(-0.685638, -179.575516, -0.702179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3662.025625, 878.59454102, 178.69349609), 'rotation':(-0.685638, -179.575516, -0.702179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3678.99195312, 878.71783203, 178.89191406), 'rotation':(-0.669067, -179.575806, -0.684845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3684.64820312, 878.75897461, 178.95595702999998), 'rotation':(-0.648621, -179.576294, -0.663422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3690.3025, 878.80004883, 179.01882812), 'rotation':(-0.648621, -179.576294, -0.663422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3695.95875, 878.84112305, 179.08083984), 'rotation':(-0.628113, -179.577103, -0.642029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3701.61421875, 878.88220703, 179.14123047), 'rotation':(-0.628113, -179.577103, -0.642029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3707.26953125, 878.92322266, 179.20119140999998), 'rotation':(-0.607635, -179.577179, -0.620667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.54757812, 879.12866211, 179.48691406), 'rotation':(-0.559784, -179.578293, -0.570801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3763.82765625, 879.33410156, 179.73992188), 'rotation':(-0.497101, -179.579605, -0.505768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3786.44992188, 879.49841797, 179.92333984), 'rotation':(-0.458832, -179.579758, -0.466217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3797.7621875, 879.580625, 180.00603515999998), 'rotation':(-0.407715, -179.580902, -0.413544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3831.6965625000003, 879.82703125, 180.21734375), 'rotation':(-0.295532, -179.58226, -0.298584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3843.00851562, 879.90917969, 180.26982422), 'rotation':(-0.251404, -179.582687, -0.253601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3859.97703125, 880.0324707, 180.33554688), 'rotation':(-0.21817, -179.582733, -0.219849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3848.61328125, 887.83056641, 180.29251953), 'rotation':(0.21817, 0.417245, 0.216519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3842.95945312, 887.78949219, 180.26986327999998), 'rotation':(0.229248, 0.41712, 0.227421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3831.64773438, 887.70733398, 180.21738281), 'rotation':(0.273371, 0.41751, 0.270779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3825.99515625, 887.66625977, 180.18763672), 'rotation':(0.295529, 0.418402, 0.292491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3814.68382812, 887.58422852, 180.12105469), 'rotation':(0.339658, 0.418222, 0.335648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3809.0278125, 887.54308594, 180.08421875), 'rotation':(0.383959, 0.418781, 0.378838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3792.06203125, 887.4198632800001, 179.96585938), 'rotation':(0.407701, 0.419069, 0.401937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3786.40671875, 887.37878906, 179.92345702999998), 'rotation':(0.433218, 0.419841, 0.426702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3780.7534375, 887.33770508, 179.88007812), 'rotation':(0.433218, 0.419841, 0.426702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3775.09695312, 887.29675781, 179.83478516), 'rotation':(0.458818, 0.419855, 0.451511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3758.1328125, 887.17279297, 179.69099609), 'rotation':(0.497115, 0.421048, 0.488538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3746.819375, 887.09130859, 179.59140625), 'rotation':(0.509648, 0.420774, 0.500645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3741.1640625, 887.05023438, 179.53990234), 'rotation':(0.509648, 0.420774, 0.500645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.5078125, 887.00916016, 179.48710938), 'rotation':(0.534756, 0.42122, 0.524844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3729.85476562, 886.96807617, 179.43224609), 'rotation':(0.559789, 0.42171, 0.548931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3724.19945312, 886.92700195, 179.37654297), 'rotation':(0.559789, 0.42171, 0.548931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3701.578125, 886.76269531, 179.14146484), 'rotation':(0.607668, 0.422824, 0.594876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3684.61375, 886.63946289, 178.95621093999998), 'rotation':(0.628118, 0.423252, 0.614472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3673.3025, 886.55731445, 178.82679688), 'rotation':(0.648595, 0.42371, 0.634043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3656.338125, 886.43408203, 178.62658202999998), 'rotation':(0.679331, 0.424664, 0.66336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3639.37132812, 886.31084961, 178.42048828), 'rotation':(0.698168, 0.424781, 0.681305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2657.98804688, 1997.5484375, 173.39988281), 'rotation':(-0.51413, -89.364227, -0.523407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.23535156, 1975.071875, 173.195625), 'rotation':(-0.557159, -89.364502, -0.568085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.42089844, 1958.21726562, 173.02904297), 'rotation':(-0.612183, -89.361938, -0.625397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2658.5446875, 1946.97953125, 172.91070312), 'rotation':(-0.625946, -89.362183, -0.63974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.60667969, 1941.36171875, 172.84988281000003), 'rotation':(-0.625946, -89.362183, -0.63974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.35472656, 1975.02585938, 173.19599609), 'rotation':(0.529599, 90.636398, 0.519869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.54078125, 1958.15625, 173.02929688), 'rotation':(0.584637, 90.637482, 0.572799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.66453125, 1946.90835938, 172.91087890999998), 'rotation':(0.612203, 90.638031, 0.599226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2650.7263281200003, 1941.2853125000001, 172.85), 'rotation':(0.612203, 90.638031, 0.599226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2650.85035156, 1930.03625, 172.72708984000002), 'rotation':(0.625959, 90.637817, 0.612386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2651.24804688, 1890.78039062, 172.29810547), 'rotation':(0.625959, 90.637497, 0.612402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2651.63914062, 1858.41890625, 171.9378125), 'rotation':(0.646955, 90.638519, 0.632476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2651.76195312, 1847.25695312, 171.80992188), 'rotation':(0.65548, 90.638702, 0.640619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.2732031200003, 1880.8288281199998, 172.18789062), 'rotation':(-0.638611, -89.361664, -0.652985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.33472656, 1875.24734375, 172.12605469), 'rotation':(-0.638611, -89.361664, -0.652985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2659.39625, 1869.66554688, 172.06382812), 'rotation':(-0.646973, -89.361481, -0.661682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.51929688, 1858.50257812, 171.93777343999997), 'rotation':(-0.655487, -89.361267, -0.670624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.58082031, 1852.92078125, 171.87390625), 'rotation':(-0.659668, -89.361511, -0.675018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2659.64234375, 1847.3400000000001, 171.80988281), 'rotation':(-0.659668, -89.361511, -0.675018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.36570312, 1792.4646093800002, 171.17064453), 'rotation':(0.676448, 90.639359, 0.660621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.42726562, 1786.8784375, 171.10460938), 'rotation':(0.677425, 90.639389, 0.661546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2652.48875, 1781.2922656199999, 171.03849609), 'rotation':(0.678204, 90.636856, 0.662284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.67335938, 1764.53390625, 170.83966797000002), 'rotation':(0.680772, 90.639473, 0.664746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2652.79640625, 1753.36171875, 170.70667969), 'rotation':(0.682513, 90.639519, 0.666401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2660.55371094, 1764.6109375, 170.83955078), 'rotation':(-0.681732, -89.360474, -0.69812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2660.61523438, 1759.02453125, 170.77308594), 'rotation':(-0.682526, -89.360474, -0.698944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2660.73828125, 1747.8517187500001, 170.63996093999998), 'rotation':(-0.682983, -89.361359, -0.699432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2653.31664062, 1692.9871875, 169.98943359), 'rotation':(0.678511, 90.639366, 0.662596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2653.74535156, 1654.06398438, 169.53318359000002), 'rotation':(0.667309, 90.638451, 0.651894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2654.01269531, 1642.94410156, 169.40439453), 'rotation':(0.661538, 90.638504, 0.646392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2654.19628906, 1626.26269531, 169.21396484000002), 'rotation':(0.649783, 90.638245, 0.635175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2654.44140625, 1604.02, 168.965), 'rotation':(0.635884, 90.638145, 0.621897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2654.51953125, 1598.4635156200002, 168.90353516), 'rotation':(0.631608, 90.756744, 0.617796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2654.63160156, 1592.9175, 168.84263672), 'rotation':(0.627018, 91.223045, 0.613397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2654.93238281, 1581.8284765600001, 168.725), 'rotation':(0.591303, 92.125046, 0.579194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2661.37351562, 1690.1784375, 169.95511718999998), 'rotation':(-0.677124, -89.362183, -0.693298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2661.59546875, 1670.853125, 169.7278125), 'rotation':(-0.668732, -89.359924, -0.684479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2661.68554688, 1665.296875, 169.66298827999998), 'rotation':(-0.66745, -89.361542, -0.683136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2661.76683594, 1659.740625, 169.59826172), 'rotation':(-0.667297, -89.361542, -0.682983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.03710938, 1643.07128906, 169.40482422000002), 'rotation':(-0.657532, -89.359192, -0.67276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.09839844, 1637.51464844, 169.34105469), 'rotation':(-0.653656, -89.361664, -0.668701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.1596875, 1631.95777344, 169.27761718999997), 'rotation':(-0.64978, -89.361755, -0.664642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2662.28199219, 1620.8441015600001, 169.15181640999998), 'rotation':(-0.641907, -89.361938, -0.656403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2662.46558594, 1604.16980469, 168.96566406000002), 'rotation':(-0.640747, -89.24469, -0.655182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.65699219, 1593.03125, 168.84179688), 'rotation':(-0.627075, -88.554443, -0.64093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.90820312, 1581.88769531, 168.72255859), 'rotation':(-0.590851, -87.64798, -0.603149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2657.60863281, 1538.18566406, 168.30095702999998), 'rotation':(0.522011, 94.949226, 0.512569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2658.8278906200003, 1527.1328125, 168.20363281000002), 'rotation':(0.493304, 95.746567, 0.484876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2660.05371094, 1516.06921875, 168.11158203), 'rotation':(0.464391, 96.545189, 0.456912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2662.17359375, 1499.49757812, 167.97902344), 'rotation':(0.441551, 97.754501, 0.434789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2662.95433594, 1493.9715625, 167.93691406000002), 'rotation':(0.429469, 98.090187, 0.42306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2663.775625, 1488.45777344, 167.89638672), 'rotation':(0.417345, 98.422806, 0.411304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2665.52660156, 1477.44910156, 167.81933593999997), 'rotation':(0.392975, 99.092636, 0.387607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2667.41945312, 1466.47523438, 167.74738281), 'rotation':(0.362594, 100.04805, 0.358021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2668.42261719, 1461.004375, 167.71207031000003), 'rotation':(0.362854, 100.524345, 0.358279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2671.51125, 1444.59886719, 167.61119141), 'rotation':(0.333081, 101.443039, 0.32923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2665.65578125, 1538.65320312, 168.29863281000002), 'rotation':(-0.519867, -84.786316, -0.529358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2666.29027344, 1533.1139062500001, 168.24871094), 'rotation':(-0.500427, -84.251953, -0.509216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2666.8515625, 1527.57152344, 168.20029297000002), 'rotation':(-0.490723, -83.988129, -0.499207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2667.44921875, 1522.02492188, 168.153125), 'rotation':(-0.4711, -83.456696, -0.478912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2668.76125, 1510.9420312500001, 168.06193359), 'rotation':(-0.460205, -82.579346, -0.467651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2670.22144531, 1499.87597656, 167.97333984), 'rotation':(-0.435638, -81.91098, -0.442322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2671.01074219, 1494.35375, 167.93119141), 'rotation':(-0.42337, -81.576233, -0.429657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2671.83691406, 1488.83726562, 167.89042969), 'rotation':(-0.411102, -81.241302, -0.417023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2673.60082031, 1477.81433594, 167.81289062), 'rotation':(-0.374054, -80.237488, -0.378998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2675.50976562, 1466.83789062, 167.74050781000003), 'rotation':(-0.367828, -79.713104, -0.372559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2678.5134375, 1450.41039062, 167.63578125), 'rotation':(-0.337891, -78.555267, -0.341888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2679.63623047, 1444.95386719, 167.60392578), 'rotation':(-0.297852, -77.80307, -0.300964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2680.23902344, 1407.58070312, 167.43222656), 'rotation':(0.24726, 104.251015, 0.245134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2681.49339844, 1402.17726562, 167.40863281000003), 'rotation':(0.243182, 104.565308, 0.241121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2685.70751953, 1386.02882812, 167.34003906), 'rotation':(0.229474, 104.122993, 0.227657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.04492188, 1380.61742188, 167.31804688), 'rotation':(0.226223, 103.866447, 0.224442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2690.82445312, 1364.31066406, 167.25443359000002), 'rotation':(0.216749, 102.621918, 0.21511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2693.14820312, 1353.39257812, 167.21167968999998), 'rotation':(0.221687, 101.723366, 0.219983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2696.33226562, 1336.96851562, 167.14595702999998), 'rotation':(0.228654, 100.377701, 0.226834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.29613281, 1320.53455078, 167.07851562), 'rotation':(0.23418, 99.284912, 0.232266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2700.15576172, 1315.04601562, 167.05591797), 'rotation':(0.233729, 98.991104, 0.231827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2700.97582031, 1309.55333984, 167.0334375), 'rotation':(0.232732, 98.591545, 0.230846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2688.40429688, 1408.05628906, 167.42546875), 'rotation':(-0.246704, -75.434692, -0.24881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2689.81957031, 1402.65589844, 167.40160156000002), 'rotation':(-0.242554, -75.125031, -0.244629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2693.87085938, 1386.46886719, 167.33388672), 'rotation':(-0.222839, -76.134827, -0.224548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2695.19238281, 1381.06898438, 167.31236328), 'rotation':(-0.216614, -76.65271, -0.218262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2697.72730469, 1370.22816406, 167.27052734), 'rotation':(-0.21347, -77.378998, -0.215088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2700.10328125, 1359.35460938, 167.22863281000002), 'rotation':(-0.218353, -78.273926, -0.220001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2702.3259375, 1348.4444531200002, 167.18589844), 'rotation':(-0.221771, -78.946472, -0.223511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2703.37816406, 1342.98390625, 167.16423827999998), 'rotation':(-0.22406, -79.394104, -0.22583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2704.39039062, 1337.5184375, 167.14240234000002), 'rotation':(-0.226624, -79.840851, -0.228424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2705.50488281, 1332.07347656, 167.12033203), 'rotation':(-0.228943, -80.291748, -0.230774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2707.32910156, 1321.1173046899999, 167.07570312), 'rotation':(-0.230194, -81.01004, -0.232056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.18285156, 1315.63757812, 167.05339844), 'rotation':(-0.229218, -81.406128, -0.231079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.99683594, 1310.15710938, 167.03121094), 'rotation':(-0.228271, -81.806732, -0.230103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.52808594, 1087.62255859, 166.26625), 'rotation':(0.1125, 89.771744, 0.112064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.56396484, 1116.73583984, 166.32873047), 'rotation':(0.140483, 89.771873, 0.139797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.5859375, 1122.2800293, 166.34253906), 'rotation':(0.147546, 89.771904, 0.146793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.60816406, 1127.82433594, 166.35693359), 'rotation':(0.154608, 89.769646, 0.15378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.630625, 1133.36853516, 166.37195312), 'rotation':(0.161391, 89.771988, 0.160488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.65257812, 1138.9123535200001, 166.38757812), 'rotation':(0.165031, 89.770851, 0.164081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.69703125, 1150.0, 166.42007812), 'rotation':(0.183281, 89.769508, 0.18211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.71923828, 1155.54443359, 166.43720703), 'rotation':(0.183281, 89.769508, 0.18211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.74169922, 1161.10058594, 166.455), 'rotation':(0.195589, 89.771301, 0.194264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.76390625, 1166.63257812, 166.47386719), 'rotation':(0.207692, 89.771378, 0.206193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.80835938, 1177.72130859, 166.51351562), 'rotation':(0.213744, 89.772438, 0.212157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.8303125, 1183.26488281, 166.53421875), 'rotation':(0.213901, 89.769814, 0.212309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.85277344, 1188.80859375, 166.55490234), 'rotation':(0.215014, 89.77092, 0.213419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.88232422, 1199.92785156, 166.59691406000002), 'rotation':(0.220192, 90.21286, 0.218511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2708.85009766, 1205.50304688, 166.61833984), 'rotation':(0.223053, 90.803055, 0.221337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.78076172, 1211.06921875, 166.63994141), 'rotation':(0.224618, 91.09996, 0.222858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.66722656, 1216.64697266, 166.66179688), 'rotation':(0.226161, 91.393372, 0.224386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.32398438, 1227.7940625, 166.70603516), 'rotation':(0.229727, 92.27668, 0.227892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2708.09033203, 1233.3631640600001, 166.72833984000002), 'rotation':(0.229535, 92.900681, 0.227696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2707.15429688, 1250.03710938, 166.79501953), 'rotation':(0.22862, 93.989197, 0.226813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2705.85693359, 1266.64234375, 166.86123047), 'rotation':(0.22791, 95.079163, 0.226116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2705.3459375, 1272.17150391, 166.88328125), 'rotation':(0.227507, 95.764717, 0.225716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2714.06787109, 1266.54455078, 166.85802734), 'rotation':(-0.22467, -85.283783, -0.22644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2714.53199219, 1261.03980469, 166.83632812), 'rotation':(-0.225006, -85.649139, -0.226776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2715.20068359, 1249.99767578, 166.79275391), 'rotation':(-0.225555, -86.376617, -0.227325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2715.85277344, 1238.93994141, 166.74900391), 'rotation':(-0.226074, -87.103577, -0.227844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.12207031, 1233.4034375, 166.72707031000002), 'rotation':(-0.226288, -87.428162, -0.228058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.54125, 1222.32384766, 166.68326172000002), 'rotation':(-0.22406, -88.310822, -0.2258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.80445312, 1211.23498047, 166.64005859), 'rotation':(-0.219727, -89.195129, -0.221405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.87402344, 1205.6873828100001, 166.61875), 'rotation':(-0.218414, -89.490997, -0.220062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.90673828, 1200.14917969, 166.59769531), 'rotation':(-0.215576, -90.082733, -0.217194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.90087891, 1194.59546875, 166.57675781), 'rotation':(-0.215027, -90.229065, -0.216644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.85644531, 1183.49353516, 166.53519531), 'rotation':(-0.213745, -90.230164, -0.215332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.83421875, 1177.94238281, 166.51447266), 'rotation':(-0.207703, -90.228607, -0.209198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.78980469, 1166.83875, 166.4746875), 'rotation':(-0.195587, -90.228699, -0.19693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.76757812, 1161.28759766, 166.45574219), 'rotation':(-0.183289, -90.22879, -0.184448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.74535156, 1155.73632812, 166.43792968999998), 'rotation':(-0.171143, -90.228851, -0.17218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.72314453, 1150.18494141, 166.42072266), 'rotation':(-0.171143, -90.228851, -0.17218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.82324219, 1139.0809375, 166.38814452999998), 'rotation':(-0.161407, -90.230316, -0.162292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2716.734375, 1116.87475586, 166.32916016), 'rotation':(-0.133545, -90.228149, -0.134186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.68994141, 1105.77160156, 166.30333984), 'rotation':(-0.126465, -90.230469, -0.127045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.66773438, 1100.2199707, 166.29136719), 'rotation':(-0.119568, -90.22821, -0.120056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.64574219, 1094.66833984, 166.28), 'rotation':(-0.112488, -90.23056, -0.112946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3303.86207031, 1719.37109375, 175.34667968999997), 'rotation':(-0.250671, -179.462601, -0.252869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3314.95824219, 1719.47484375, 175.39439453), 'rotation':(-0.246277, -179.462631, -0.248413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3320.50634766, 1719.5267187499999, 175.41783203), 'rotation':(-0.242035, -179.462708, -0.24408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3326.0546875, 1719.5787500000001, 175.44105469), 'rotation':(-0.239868, -179.462769, -0.241882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3331.60230469, 1719.630625, 175.46421875), 'rotation':(-0.239868, -179.462769, -0.241882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3337.15039062, 1719.6825, 175.48707031), 'rotation':(-0.237671, -179.462952, -0.239655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3342.69824219, 1719.7345312500001, 175.50953125), 'rotation':(-0.233459, -179.462997, -0.235382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.2465625, 1719.78640625, 175.53152343999997), 'rotation':(-0.229218, -179.463043, -0.231079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3359.34253906, 1719.89015625, 175.57427734), 'rotation':(-0.216431, -179.463135, -0.218079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3364.8908593799997, 1719.9420312500001, 175.59501953), 'rotation':(-0.212189, -179.46315, -0.213776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3375.9865625, 1720.0459375, 175.63533203), 'rotation':(-0.207825, -179.463211, -0.20932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.53492188, 1720.0978125000001, 175.65525391), 'rotation':(-0.205719, -179.462799, -0.207214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3392.63109375, 1720.20164062, 175.69464843999998), 'rotation':(-0.201569, -179.463028, -0.203003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.72703125, 1720.3053906199998, 175.73183594), 'rotation':(-0.193146, -179.463089, -0.194458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3409.27492188, 1720.35742188, 175.74955078), 'rotation':(-0.184967, -179.463135, -0.186188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.4665625, 1720.56484375, 175.81650391), 'rotation':(-0.172546, -179.463776, -0.173584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3437.01488281, 1720.61671875, 175.83246093999998), 'rotation':(-0.164642, -179.463058, -0.165588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3442.5627343799997, 1720.6685937500001, 175.84742188), 'rotation':(-0.164642, -179.463058, -0.165588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3459.20582031, 1720.8243750000001, 175.8875), 'rotation':(-0.133453, -179.463257, -0.134094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3481.32496094, 1729.04164062, 175.93125), 'rotation':(0.109925, 0.53635, 0.109512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3459.13328125, 1728.70445312, 175.8875), 'rotation':(0.117821, 0.535945, 0.117341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3431.39453125, 1728.44484375, 175.81652343999997), 'rotation':(0.164649, 0.536925, 0.163704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3414.75121094, 1728.2890625, 175.76666016), 'rotation':(0.172408, 0.537167, 0.171375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3403.65503906, 1728.18554688, 175.73183594), 'rotation':(0.184968, 0.535885, 0.183792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3398.1071875, 1728.13367188, 175.71353516), 'rotation':(0.184968, 0.535885, 0.183792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3381.463125, 1727.97789062, 175.65525391), 'rotation':(0.205725, 0.537186, 0.204257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3370.3671875, 1727.87414062, 175.61533203), 'rotation':(0.205725, 0.536172, 0.204257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3364.81933594, 1727.82210938, 175.59503906), 'rotation':(0.207808, 0.536776, 0.206318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3359.27101562, 1727.7702343800001, 175.57427734), 'rotation':(0.2122, 0.538132, 0.21064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3353.72289062, 1727.71835938, 175.553125), 'rotation':(0.220636, 0.536873, 0.218942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3348.17503906, 1727.66640625, 175.53152343999997), 'rotation':(0.22485, 0.536931, 0.223101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3342.62671875, 1727.61453125, 175.50953125), 'rotation':(0.229228, 0.53694, 0.227404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3337.07859375, 1727.5626562500001, 175.48708984), 'rotation':(0.233456, 0.537, 0.231562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3325.98316406, 1727.45875, 175.44107422000002), 'rotation':(0.237663, 0.537008, 0.235706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3309.33886719, 1727.30296875, 175.37068359), 'rotation':(0.242028, 0.536377, 0.239982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3260.17261719, 1726.84289062, 175.14992188), 'rotation':(0.26273, 0.537204, 0.26034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3254.60277344, 1726.79085938, 175.12402343999997), 'rotation':(0.266268, 0.537223, 0.263802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3249.03320312, 1726.73875, 175.09789062), 'rotation':(0.270072, 0.537272, 0.267539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3243.463125, 1726.68664062, 175.07148438000002), 'rotation':(0.270072, 0.537272, 0.267539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3232.32398438, 1726.58242188, 175.01808594), 'rotation':(0.275571, 0.537019, 0.272927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3210.0446875, 1726.37390625, 174.91041016), 'rotation':(0.279403, 0.537784, 0.276687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3204.47509766, 1726.32179688, 174.88314452999998), 'rotation':(0.281131, 0.537799, 0.27838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.90527344, 1726.2696875000001, 174.85570312), 'rotation':(0.28251, 0.537813, 0.279732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3187.765625, 1726.16554688, 174.80029297000002), 'rotation':(0.285775, 0.537847, 0.282938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3176.62646484, 1726.06125, 174.74431640999998), 'rotation':(0.288056, 0.53746, 0.285173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3260.24658203, 1718.96289062, 175.14992188), 'rotation':(-0.266266, -179.462769, -0.268768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3249.1071875, 1718.8586718800002, 175.09789062), 'rotation':(-0.273621, -179.462692, -0.276245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3243.53710938, 1718.80648438, 175.07148438000002), 'rotation':(-0.273621, -179.462692, -0.276245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3232.39794922, 1718.70226562, 175.01808594), 'rotation':(-0.275482, -179.462036, -0.278107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3221.25830078, 1718.59804688, 174.96445312), 'rotation':(-0.277863, -179.462234, -0.280548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3198.97875, 1718.38953125, 174.85568359), 'rotation':(-0.284241, -179.462158, -0.287048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.40917969, 1718.33742188, 174.82808594), 'rotation':(-0.285767, -179.462143, -0.288635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.83910156, 1718.2853906199998, 174.80029297000002), 'rotation':(-0.287323, -179.462128, -0.290222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3176.69996094, 1718.18117188, 174.74431640999998), 'rotation':(-0.289154, -179.462585, -0.292053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.06518555, 1725.75671875, 174.57759765999998), 'rotation':(0.297878, 0.537778, 0.294799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3127.31494141, 1725.6, 174.48982422), 'rotation':(0.300699, 0.537794, 0.297556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3121.73144531, 1725.54773438, 174.46039062), 'rotation':(0.302154, 0.537365, 0.298973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3104.98120117, 1725.39101562, 174.37181640999998), 'rotation':(0.304756, 0.53685, 0.301541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3144.13867188, 1717.8765625, 174.57759765999998), 'rotation':(-0.30069, -179.462921, -0.303864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3138.55517578, 1717.8243750000001, 174.54849609000001), 'rotation':(-0.30069, -179.462921, -0.303864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3127.38842773, 1717.72, 174.48982422), 'rotation':(-0.302155, -179.461929, -0.305359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3121.80493164, 1717.6677343800002, 174.46039062), 'rotation':(-0.302063, -179.462616, -0.305267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3105.0546875, 1717.51085938, 174.37181640999998), 'rotation':(-0.309845, -179.461807, -0.313202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3088.3046875, 1717.35414062, 174.28072265999998), 'rotation':(-0.312378, -179.461899, -0.315796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3077.13818359, 1717.2497656199998, 174.21980469), 'rotation':(-0.314209, -179.461517, -0.317657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.14624023, 1716.9971875, 174.06888672000002), 'rotation':(-0.329193, -179.461578, -0.333008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.0402832, 1716.89320312, 174.00472656000002), 'rotation':(-0.335999, -179.461472, -0.339966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3027.93432617, 1716.7892968800002, 173.93955078), 'rotation':(-0.339569, -179.462616, -0.343597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.27587891, 1716.6334375000001, 173.83996093999997), 'rotation':(-0.350555, -179.461105, -0.354858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2994.6171875, 1716.4775, 173.73689453), 'rotation':(-0.361542, -179.462311, -0.366119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2989.06420898, 1716.4255468800002, 173.70175781), 'rotation':(-0.365295, -179.460922, -0.369995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2983.51196289, 1716.37367188, 173.66630859), 'rotation':(-0.367218, -179.461258, -0.371918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2977.95996094, 1716.32164062, 173.63070312), 'rotation':(-0.370117, -179.461975, -0.374939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2972.40698242, 1716.2696875000001, 173.59482422000002), 'rotation':(-0.376099, -179.461884, -0.381042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2966.85424805, 1716.2178125, 173.55835938), 'rotation':(-0.382019, -179.460571, -0.387177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2955.7487793, 1716.11375, 173.48367188), 'rotation':(-0.394165, -179.461655, -0.399597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2950.19604492, 1716.0618749999999, 173.44546875), 'rotation':(-0.399963, -179.460312, -0.405579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2939.09033203, 1715.95796875, 173.36728516), 'rotation':(-0.412079, -179.460144, -0.41803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2922.43261719, 1715.80226562, 173.24693359), 'rotation':(-0.4216, -179.460236, -0.427826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2911.32861328, 1715.69835938, 173.16496094), 'rotation':(-0.434875, -179.46109, -0.441498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2900.22363281, 1715.59421875, 173.07890625), 'rotation':(-0.461609, -179.45961, -0.469116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3038.96630859, 1724.7732812499999, 174.00472656000002), 'rotation':(0.332678, 0.537367, 0.328834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3033.41333008, 1724.72132812, 173.97222656000002), 'rotation':(0.336025, 0.538516, 0.33209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3011.20214844, 1724.51351562, 173.83994141), 'rotation':(0.346953, 0.53885, 0.342764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3000.09619141, 1724.4096875, 173.77166015999998), 'rotation':(0.354343, 0.538965, 0.349982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2994.54345703, 1724.35765625, 173.73689453), 'rotation':(0.357916, 0.537612, 0.353479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2988.99047852, 1724.305625, 173.70175781), 'rotation':(0.361549, 0.539057, 0.357005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2977.88623047, 1724.20179688, 173.63070312), 'rotation':(0.367191, 0.53874, 0.362515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2972.33325195, 1724.14976562, 173.59482422000002), 'rotation':(0.370121, 0.538035, 0.365354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2966.78051758, 1724.0978906199998, 173.55835938), 'rotation':(0.376084, 0.53937, 0.371171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2961.2277832, 1724.0459375, 173.52130859000002), 'rotation':(0.382047, 0.538169, 0.376969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2955.67504883, 1723.99390625, 173.48367188), 'rotation':(0.388023, 0.538267, 0.382809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2950.12231445, 1723.9420312500001, 173.44546875), 'rotation':(0.394157, 0.539611, 0.388765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2944.56933594, 1723.8899999999999, 173.40666016), 'rotation':(0.399976, 0.538435, 0.394417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2939.01660156, 1723.83804688, 173.36730468999997), 'rotation':(0.405945, 0.539775, 0.400226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2927.91186523, 1723.7342187499999, 173.28714843999998), 'rotation':(0.414995, 0.538824, 0.409016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2916.80737305, 1723.63039062, 173.20634766), 'rotation':(0.414995, 0.538824, 0.409016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2905.70239258, 1723.52648438, 173.12248047), 'rotation':(0.434858, 0.538896, 0.428302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2673.49316406, 1721.354375, 170.52980469), 'rotation':(0.879366, 0.549396, 0.852677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2679.03929688, 1721.4060937499999, 170.61496093999997), 'rotation':(0.879366, 0.549396, 0.852677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2690.13011719, 1721.51015625, 170.78441406000002), 'rotation':(0.852046, 0.549517, 0.826983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2701.22144531, 1721.61375, 170.94816406), 'rotation':(0.815777, 0.547279, 0.792781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2706.76734375, 1721.66554688, 171.02751952999998), 'rotation':(0.797349, 0.547939, 0.775394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2712.31078125, 1721.71742188, 171.10513672000002), 'rotation':(0.779284, 0.546237, 0.758289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2723.40234375, 1721.8210156199998, 171.25541016), 'rotation':(0.742838, 0.545291, 0.723761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2756.67822266, 1722.13242188, 171.67710938), 'rotation':(0.675308, 0.544306, 0.659536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2762.22314453, 1722.1842968800001, 171.74308594), 'rotation':(0.675308, 0.544306, 0.659536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2767.76904297, 1722.23609375, 171.80824219), 'rotation':(0.652017, 0.542997, 0.637301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2784.4084375, 1722.391875, 171.99599609), 'rotation':(0.634415, 0.543445, 0.620472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2801.04736328, 1722.5475000000001, 172.17761718999998), 'rotation':(0.599083, 0.542682, 0.586652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2812.14039062, 1722.65140625, 172.29283203), 'rotation':(0.57532, 0.540874, 0.563843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2828.77929688, 1722.81015625, 172.45666015999998), 'rotation':(0.545958, 0.541525, 0.535627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2845.41992188, 1722.9728906199998, 172.61414062), 'rotation':(0.522318, 0.541126, 0.512858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2856.51293945, 1723.04148438, 172.71451172000002), 'rotation':(0.50652, 0.540843, 0.497624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.05957031, 1723.08546875, 172.76349609000002), 'rotation':(0.490838, 0.539715, 0.482478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2867.60668945, 1723.13710938, 172.81099609), 'rotation':(0.479384, 0.539825, 0.471419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2862.15161133, 1715.2380468800002, 172.76363281000002), 'rotation':(-0.506531, -179.459152, -0.515533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2851.05859375, 1715.134375, 172.66488281000002), 'rotation':(-0.522308, -179.459732, -0.531921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2839.96508789, 1715.0306249999999, 172.56220703), 'rotation':(-0.545959, -179.458466, -0.556427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2834.41943359, 1714.97875, 172.50972656000002), 'rotation':(-0.545959, -179.458466, -0.556427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2828.87255859, 1714.926875, 172.45685547000002), 'rotation':(-0.55191, -179.458237, -0.562592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2817.78076172, 1714.82296875, 172.34886719), 'rotation':(-0.575317, -179.457794, -0.586945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2812.23414062, 1714.77109375, 172.29302734), 'rotation':(-0.587219, -179.457535, -0.599365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2806.68945312, 1714.71921875, 172.23603516), 'rotation':(-0.599091, -179.457306, -0.611725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2795.59667969, 1714.61546875, 172.1184375), 'rotation':(-0.622528, -179.456802, -0.636169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2778.95800781, 1714.46, 171.93423828), 'rotation':(-0.652008, -179.456223, -0.666992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2773.41285156, 1714.40804688, 171.87164062), 'rotation':(-0.652008, -179.456223, -0.666992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2751.22998047, 1714.20046875, 171.60974609000002), 'rotation':(-0.721985, -179.454529, -0.740387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2740.13769531, 1714.09671875, 171.47076172), 'rotation':(-0.733704, -179.454376, -0.752686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2729.04859375, 1713.9928906199998, 171.32835938), 'rotation':(-0.742859, -179.454697, -0.762299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2723.50269531, 1713.9411718800002, 171.25576172), 'rotation':(-0.761047, -179.454254, -0.781464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2701.32421875, 1713.73351562, 170.94859375), 'rotation':(-0.833801, -179.452209, -0.858368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2695.77832031, 1713.68148438, 170.86757812), 'rotation':(-0.852051, -179.451675, -0.877686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2690.23265625, 1713.62984375, 170.78486328), 'rotation':(-0.8703, -179.449936, -0.897034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2684.68945312, 1713.5779687499999, 170.70058594), 'rotation':(-0.879364, -179.450607, -0.906708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2673.59691406, 1713.47414062, 170.53025391), 'rotation':(-0.879456, -179.450623, -0.906769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2641.04589844, 1721.05078125, 170.03162109000002), 'rotation':(0.879394, 0.550136, 0.8527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2635.51855469, 1720.99914062, 169.94673827999998), 'rotation':(0.879359, 0.549082, 0.852667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2624.46726562, 1720.89578125, 169.77175781000003), 'rotation':(0.939875, 0.550869, 0.909411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2618.94410156, 1720.84414062, 169.67908203), 'rotation':(0.980084, 0.553436, 0.94697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2591.32300781, 1720.5859375, 169.15949218999998), 'rotation':(1.141167, 0.559406, 1.096362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2574.74683594, 1720.4309375, 168.81257812), 'rotation':(1.205057, 0.561423, 1.155144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2563.69457031, 1720.3274218800002, 168.57898438), 'rotation':(1.211935, 0.561717, 1.161448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2541.59082031, 1720.120625, 168.10720702999998), 'rotation':(1.225985, 0.562328, 1.17433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2536.06445312, 1720.06898438, 167.98855468999997), 'rotation':(1.229434, 0.561822, 1.17749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2519.48925781, 1719.9140625, 167.62851562), 'rotation':(1.259179, 0.563529, 1.204703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2513.96363281, 1719.86242188, 167.5053125), 'rotation':(1.279014, 0.56441, 1.222808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2513.99683594, 1711.9809375, 167.50439452999998), 'rotation':(-1.298737, -179.434677, -1.358673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2519.52171875, 1712.03273438, 167.62761719), 'rotation':(-1.278992, -179.435577, -1.337128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2552.67480469, 1712.3430468800002, 168.34300781000002), 'rotation':(-1.226013, -179.437668, -1.279327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2563.7265625, 1712.44640625, 168.57808594), 'rotation':(-1.219086, -179.437973, -1.27182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2574.77832031, 1712.54984375, 168.81169922), 'rotation':(-1.211945, -179.438263, -1.264069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2585.8303125, 1712.6530468800001, 169.04402344), 'rotation':(-1.201599, -179.438889, -1.252808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2591.35546875, 1712.7046875, 169.15861328), 'rotation':(-1.181335, -179.438965, -1.230865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2602.40527344, 1712.79929688, 169.37775391), 'rotation':(-1.10083, -179.442169, -1.143768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2607.9299218799997, 1712.8787499999999, 169.48173828), 'rotation':(-1.060699, -179.444885, -1.100525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2630.03222656, 1713.09960938, 169.86019531000002), 'rotation':(-0.93988, -179.447906, -0.9711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2635.55882812, 1713.15125, 169.94625), 'rotation':(-0.899567, -179.450394, -0.928162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2641.0861718799997, 1713.2029687499999, 170.03109375), 'rotation':(-0.879364, -179.449875, -0.906677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2459.276875, 1711.4689843800002, 166.21548828), 'rotation':(-1.410767, -179.429199, -1.481598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2442.31296875, 1711.3103125, 165.79363281000002), 'rotation':(-1.44281, -179.427017, -1.516907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2436.65746094, 1711.25742188, 165.65109375), 'rotation':(-1.442657, -179.428177, -1.516754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2431.00242188, 1711.20445312, 165.50857422), 'rotation':(-1.452209, -179.427399, -1.527313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.34914062, 1711.1516406199999, 165.36521484000002), 'rotation':(-1.471222, -179.425415, -1.548309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2419.69484375, 1711.09875, 165.22050781000002), 'rotation':(-1.490112, -179.425446, -1.569214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2414.04054688, 1711.04578125, 165.07439452999998), 'rotation':(-1.490112, -179.425446, -1.569214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2408.38597656, 1710.9928906199998, 164.92691406000003), 'rotation':(-1.509064, -179.424438, -1.59021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2402.73070312, 1710.94007812, 164.7778125), 'rotation':(-1.518494, -179.423553, -1.600677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2391.42382812, 1710.83421875, 164.47792969), 'rotation':(-1.518585, -179.423538, -1.600769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2385.76878906, 1710.78125, 164.32792969), 'rotation':(-1.524902, -179.422699, -1.607819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2380.11570312, 1710.72835938, 164.17769531000002), 'rotation':(-1.524902, -179.422699, -1.607819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2363.15257812, 1710.5696093800002, 163.72208984), 'rotation':(-1.562897, -179.420639, -1.649994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2357.49804688, 1710.516875, 163.56825195), 'rotation':(-1.562897, -179.420639, -1.649994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2351.84570312, 1710.46398438, 163.41374023), 'rotation':(-1.569366, -179.420746, -1.657227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2340.5364062500003, 1710.358125, 163.10367188), 'rotation':(-1.569275, -179.420761, -1.657104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2323.5725, 1710.1993750000001, 162.63855469), 'rotation':(-1.577118, -179.420486, -1.665833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2317.9192187500003, 1710.14648438, 162.48295898), 'rotation':(-1.584839, -179.420334, -1.674469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2306.61109375, 1710.040625, 162.1700293), 'rotation':(-1.584991, -179.41954, -1.674622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2300.9565625, 1709.9878125, 162.01344727), 'rotation':(-1.584839, -179.420334, -1.674469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2295.3020312500003, 1709.93484375, 161.85685547), 'rotation':(-1.584839, -179.420334, -1.674469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2278.33742188, 1709.7775000000001, 161.38712891), 'rotation':(-1.584167, -179.419724, -1.673706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2261.3740625, 1709.6173437500001, 160.91842773), 'rotation':(-1.578308, -179.420349, -1.667175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2245.828125, 1709.34226562, 160.4896875), 'rotation':(-1.578369, -179.420303, -1.667267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2470.50390625, 1719.579375, 166.490625), 'rotation':(1.368039, 0.568724, 1.303814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2459.19875, 1719.35007812, 166.21537109000002), 'rotation':(1.389452, 0.569755, 1.323223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2453.54296875, 1719.29734375, 166.07599609000002), 'rotation':(1.410776, 0.5708, 1.342509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2442.2341406200003, 1719.1915625000001, 165.79349609000002), 'rotation':(1.43199, 0.571857, 1.361678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2436.57886719, 1719.13851562, 165.65097656), 'rotation':(1.442768, 0.572963, 1.37142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2430.92359375, 1719.08554688, 165.50845703), 'rotation':(1.442652, 0.572959, 1.371289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2425.27, 1719.03273438, 165.36509766), 'rotation':(1.452221, 0.572605, 1.379932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2419.61570312, 1718.9797656199999, 165.22039062), 'rotation':(1.471161, 0.573575, 1.396992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2413.9611718799997, 1718.926875, 165.07427734), 'rotation':(1.471161, 0.573575, 1.396992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2408.306875, 1718.87390625, 164.92677734), 'rotation':(1.490163, 0.575559, 1.414084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2402.65136719, 1718.8210156199998, 164.77767577999998), 'rotation':(1.509041, 0.575547, 1.431047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2391.34375, 1718.7153125, 164.47777344), 'rotation':(1.518494, 0.576448, 1.439518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2380.035625, 1718.6095312500001, 164.17753906000002), 'rotation':(1.518583, 0.576453, 1.439596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2374.38132812, 1718.55664062, 164.02675781000002), 'rotation':(1.524928, 0.576341, 1.445282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2368.72609375, 1718.5037499999999, 163.87484375), 'rotation':(1.53753, 0.577, 1.456571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2357.4175, 1718.39804688, 163.56806641), 'rotation':(1.550234, 0.578669, 1.467952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2351.76488281, 1718.34523438, 163.41354492), 'rotation':(1.569468, 0.583017, 1.48515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2346.10984375, 1718.2923437499999, 163.25849609), 'rotation':(1.569373, 0.579256, 1.485072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2329.1457812500003, 1718.13367188, 162.79337891), 'rotation':(1.56925, 0.579249, 1.484969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2317.83742188, 1718.0278125, 162.48272461), 'rotation':(1.577097, 0.579526, 1.491963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2300.87453125, 1717.86914062, 162.01323242), 'rotation':(1.584986, 0.579672, 1.499005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2283.91039062, 1717.7103124999999, 161.54345703), 'rotation':(1.584898, 0.580451, 1.498919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2272.600625, 1717.60453125, 161.23046875), 'rotation':(1.582459, 0.578774, 1.496748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2261.29101562, 1717.49875, 160.91816406), 'rotation':(1.579174, 0.579981, 1.493814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2255.64109375, 1717.5076562499999, 160.76237305), 'rotation':(1.578293, 0.579661, 1.493039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2062.8762500000003, 1707.3982812499999, 155.82804688), 'rotation':(-1.246552, -179.28389, -1.301727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2079.44382812, 1707.5974999999999, 156.20106445), 'rotation':(-1.316193, -179.280746, -1.377747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2090.48757812, 1707.7303124999999, 156.45871094), 'rotation':(-1.350983, -179.279129, -1.415863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2096.00929688, 1707.7966406199998, 156.59024413999998), 'rotation':(-1.368286, -179.278351, -1.434875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2107.05296875, 1707.92929688, 156.85609375), 'rotation':(-1.382568, -179.277008, -1.450562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2123.61695312, 1708.12851562, 157.26185547), 'rotation':(-1.416718, -179.275299, -1.488159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2129.1384375, 1708.19492188, 157.39932617), 'rotation':(-1.427917, -179.276047, -1.500488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2140.180625, 1708.30773438, 157.67750977), 'rotation':(-1.450592, -179.273636, -1.525543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2145.7018749999997, 1708.3626562499999, 157.81825195), 'rotation':(-1.461945, -179.274292, -1.538055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2151.22195312, 1708.4803124999999, 157.95966797), 'rotation':(-1.467468, -179.273392, -1.544189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2178.82515625, 1708.82515625, 158.6755957), 'rotation':(-1.510376, -179.271408, -1.591675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2184.3464062499997, 1708.8915625, 158.82240234), 'rotation':(-1.527588, -179.270508, -1.610779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2189.86625, 1708.95789062, 158.97001953), 'rotation':(-1.527588, -179.270508, -1.610779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2195.3879687500003, 1709.0197656199998, 159.11827148), 'rotation':(-1.537872, -179.3078, -1.622192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2200.90820312, 1709.0787500000001, 159.26654297), 'rotation':(-1.537872, -179.3078, -1.622192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2211.9540625, 1709.01773438, 159.56336914), 'rotation':(-1.540405, -179.422943, -1.625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2189.87796875, 1716.8075, 158.97287109), 'rotation':(1.534313, 0.69155, 1.453696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2184.35640625, 1716.74109375, 158.82517578), 'rotation':(1.536068, 0.730324, 1.455273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2167.79320312, 1716.54171875, 158.38869140999998), 'rotation':(1.493387, 0.727694, 1.416978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2162.27171875, 1716.47523438, 158.24584961), 'rotation':(1.476052, 0.726792, 1.401389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2140.18359375, 1716.2096875, 157.67999023000002), 'rotation':(1.461865, 0.726942, 1.388614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2112.57226562, 1715.8778125, 156.99251953), 'rotation':(1.405291, 0.722858, 1.337567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2107.05054688, 1715.81140625, 156.85832031), 'rotation':(1.393966, 0.722271, 1.327322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2090.48046875, 1715.6121875, 156.46078125), 'rotation':(1.368367, 0.721698, 1.304118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2068.385, 1715.34640625, 155.95239258), 'rotation':(1.281569, 0.717676, 1.225161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2057.3403125, 1715.21351562, 155.7090918), 'rotation':(1.246619, 0.716132, 1.193211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2051.82125, 1715.2336718800002, 155.58957031), 'rotation':(1.238033, 0.71471, 1.185353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2199.13890625, 1288.56103516, 157.47300781), 'rotation':(1.123334, 0.5052, 1.079914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2182.44335938, 1288.42015625, 157.1478418), 'rotation':(1.106634, 0.506077, 1.064481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2176.8784375, 1288.37316406, 157.04071289), 'rotation':(1.100043, 0.504567, 1.058397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2160.18164062, 1288.23230469, 156.72317383), 'rotation':(1.079989, 0.503806, 1.039824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2154.61648438, 1288.1853125, 156.61863281), 'rotation':(1.073412, 0.503556, 1.033731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2143.48507812, 1288.09130859, 156.41073242000002), 'rotation':(1.066561, 0.503567, 1.027385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2126.7890625, 1287.95042969, 156.10356445), 'rotation':(1.044759, 0.502737, 1.007163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2110.09132812, 1287.80957031, 155.80348633), 'rotation':(1.023067, 0.501975, 0.987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2104.52492188, 1287.76246094, 155.70486328), 'rotation':(1.015745, 0.501714, 0.980204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2098.95796875, 1287.71544922, 155.60660156), 'rotation':(1.012343, 0.501054, 0.977021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2093.39234375, 1287.66857422, 155.50908203), 'rotation':(1.006476, 0.502242, 0.971581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2087.82664062, 1287.62158203, 155.41271484), 'rotation':(0.994831, 0.500525, 0.960713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2071.12648438, 1287.48046875, 155.13053711), 'rotation':(0.960188, 0.499361, 0.928399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2059.99460938, 1287.3866015600001, 154.94824219), 'rotation':(0.937075, 0.498574, 0.906786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2054.43359375, 1287.39794922, 154.85866211), 'rotation':(0.925292, 0.498193, 0.895756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2210.3385937499997, 1280.77429688, 157.69170898000002), 'rotation':(-1.126801, -179.494705, -1.171814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2204.7734375, 1280.72730469, 157.58224609), 'rotation':(-1.123352, -179.493927, -1.16806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2199.20875, 1280.68029297, 157.47308594), 'rotation':(-1.119965, -179.494675, -1.164398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2188.078125, 1280.58630859, 157.25567383), 'rotation':(-1.106628, -179.495178, -1.150024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2176.9479687499997, 1280.4923046899999, 157.04077148), 'rotation':(-1.093323, -179.495697, -1.135651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2165.81640625, 1280.3984375, 156.82842773000002), 'rotation':(-1.080048, -179.49617, -1.121368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2132.42359375, 1280.11669922, 156.20521484), 'rotation':(-1.04483, -179.497238, -1.083466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2126.8581249999997, 1280.06982422, 156.10360352), 'rotation':(-1.037506, -179.497498, -1.075623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2115.725625, 1279.97582031, 155.90275391), 'rotation':(-1.023071, -179.498016, -1.06012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2110.15992188, 1279.92882812, 155.80351561999998), 'rotation':(-1.015747, -179.498276, -1.052277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2099.02664062, 1279.83484375, 155.60663086), 'rotation':(-1.006439, -179.499069, -1.042297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2093.46117188, 1279.78796875, 155.50912109), 'rotation':(-0.994873, -179.499451, -1.029907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2087.89523438, 1279.74097656, 155.41276367), 'rotation':(-0.983215, -179.499878, -1.017395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2082.32960938, 1279.69384766, 155.31756836), 'rotation':(-0.971771, -179.498962, -1.005157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2076.7604687499997, 1279.64671875, 155.22344727), 'rotation':(-0.960144, -179.500671, -0.992737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2071.19507812, 1279.59984375, 155.13056641), 'rotation':(-0.948578, -179.501022, -0.980377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2060.06296875, 1279.50597656, 154.94829102), 'rotation':(-0.925293, -179.501801, -0.955566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2248.40820312, 1289.00757812, 158.45388671999999), 'rotation':(1.155443, 0.556538, 1.109513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2282.4582812500003, 1289.32470703, 159.14444336), 'rotation':(1.172552, 0.557198, 1.125267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2293.80789062, 1289.43042969, 159.37673828), 'rotation':(1.17247, 0.55816, 1.125195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2305.1575000000003, 1289.53601562, 159.60915039), 'rotation':(1.172586, 0.557217, 1.125303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2310.83226562, 1289.58886719, 159.72536133), 'rotation':(1.172586, 0.557217, 1.125303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2344.88085938, 1289.90601562, 160.42227538999998), 'rotation':(1.17191, 0.557378, 1.124683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2356.23023438, 1290.01171875, 160.6544043), 'rotation':(1.167443, 0.558008, 1.120567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2361.90476562, 1290.06457031, 160.77018555), 'rotation':(1.164465, 0.556793, 1.117829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2384.60398438, 1290.24292969, 161.23086913999998), 'rotation':(1.157198, 0.557077, 1.111133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2401.6284375, 1290.40148438, 161.57416992), 'rotation':(1.14616, 0.555939, 1.100972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2412.97804688, 1290.50707031, 161.8012207), 'rotation':(1.137247, 0.555582, 1.092755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2418.65257812, 1290.55980469, 161.91414062), 'rotation':(1.137247, 0.555582, 1.092755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2424.32765625, 1290.61267578, 162.02666992000002), 'rotation':(1.132869, 0.556543, 1.088706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2452.70238281, 1290.87707031, 162.5840332), 'rotation':(1.116961, 0.555807, 1.07403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2458.37695312, 1290.92992188, 162.69450195), 'rotation':(1.107372, 0.554447, 1.065172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2469.7267968799997, 1291.03564453, 162.91305664), 'rotation':(1.08807, 0.553708, 1.04731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2481.07691406, 1291.14136719, 163.12876953), 'rotation':(1.083309, 0.55406, 1.042897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.7521875, 1291.19421875, 163.23613281), 'rotation':(1.083254, 0.554038, 1.042872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2498.10058594, 1291.46996094, 163.45052734), 'rotation':(1.071062, 0.553018, 1.031558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2503.77585938, 1291.52283203, 163.55694336), 'rotation':(1.062818, 0.553827, 1.023918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2498.69824219, 1283.40673828, 163.46039062), 'rotation':(-1.079346, -179.44664, -1.120605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2492.58472656, 1283.40001953, 163.34509766), 'rotation':(-1.083282, -179.445953, -1.124847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2464.21167969, 1283.13585938, 162.8059082), 'rotation':(-1.107391, -179.444565, -1.150818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2447.18824219, 1282.97730469, 162.47479492), 'rotation':(-1.121704, -179.44455, -1.166321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2441.5134375, 1282.92443359, 162.36361328), 'rotation':(-1.124054, -179.444962, -1.168823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2435.83960938, 1282.87158203, 162.25228515999999), 'rotation':(-1.128326, -179.443634, -1.173462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2407.4665625, 1282.60730469, 161.6897168), 'rotation':(-1.146179, -179.442917, -1.192749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2396.1171875, 1282.50158203, 161.46186523), 'rotation':(-1.154907, -179.442581, -1.202209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2373.42039062, 1282.29027344, 161.00290039), 'rotation':(-1.164459, -179.443192, -1.212555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2367.74609375, 1282.23742188, 160.88760742), 'rotation':(-1.16745, -179.443054, -1.21579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2356.39695312, 1282.13171875, 160.65630859), 'rotation':(-1.17038, -179.441864, -1.218964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2350.72289062, 1282.07886719, 160.5403125), 'rotation':(-1.171906, -179.442612, -1.220612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2345.04808594, 1282.02599609, 160.42416015999999), 'rotation':(-1.171783, -179.442627, -1.22049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2322.349375, 1281.81457031, 159.95962891), 'rotation':(-1.172272, -179.443039, -1.221008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2305.32515625, 1281.6561328100001, 159.61106445), 'rotation':(-1.172546, -179.442795, -1.221313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2293.97609375, 1281.55041016, 159.37868164), 'rotation':(-1.172546, -179.441849, -1.221313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2288.30125, 1281.49755859, 159.26245117), 'rotation':(-1.170441, -179.442688, -1.219025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2282.62570312, 1281.44470703, 159.14636719), 'rotation':(-1.170441, -179.442688, -1.219025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2276.95070312, 1281.39183594, 159.03046875), 'rotation':(-1.16626, -179.442856, -1.214478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2265.60109375, 1281.28613281, 158.79978516), 'rotation':(-1.157623, -179.442245, -1.205139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2254.25023438, 1281.18042969, 158.5703125), 'rotation':(-1.155426, -179.443451, -1.202789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.63623047, 1285.11376953, 166.48472656), 'rotation':(-0.868805, -179.453613, -0.895477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2686.11351562, 1285.07640625, 166.62714843999998), 'rotation':(-0.860779, -179.453049, -0.886963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2664.67382812, 1285.00255859, 166.30265625), 'rotation':(-0.884399, -179.452438, -0.912048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2647.97191406, 1284.84705078, 166.04216797), 'rotation':(-0.915955, -179.451431, -0.945618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2636.83742188, 1284.74339844, 165.86408203), 'rotation':(-0.923798, -179.451935, -0.953949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2631.26976562, 1284.6915234399999, 165.77427734), 'rotation':(-0.923798, -179.451935, -0.953949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2609.00097656, 1284.48414062, 165.41185547), 'rotation':(-0.955994, -179.450302, -0.988312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2597.86597656, 1284.38037109, 165.22505859), 'rotation':(-0.975403, -179.450027, -1.009064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2592.29980469, 1284.32861328, 165.13060547), 'rotation':(-0.97522, -179.450043, -1.008881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2581.16578125, 1284.22509766, 164.94082031000002), 'rotation':(-0.985229, -179.44928, -1.019592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2575.59863281, 1284.17322266, 164.8453125), 'rotation':(-0.992004, -179.449051, -1.026825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2570.03125, 1284.12132812, 164.74912109000002), 'rotation':(-0.998718, -179.45015, -1.034027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2558.89648438, 1284.01769531, 164.55470703), 'rotation':(-1.011963, -179.448334, -1.048187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2553.32910156, 1283.96582031, 164.45646484), 'rotation':(-1.018829, -179.44812, -1.055573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2547.76171875, 1283.9139453100001, 164.35753906000002), 'rotation':(-1.025482, -179.447861, -1.062714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2670.1640625, 1292.93494141, 166.38767578), 'rotation':(0.868807, 0.546382, 0.842746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2636.76074219, 1292.62390625, 165.86402343999998), 'rotation':(0.915969, 0.548572, 0.887027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2625.625, 1292.52027344, 165.68441406000002), 'rotation':(0.92379, 0.549, 0.894347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2620.05859375, 1292.46837891, 165.59427734000002), 'rotation':(0.92379, 0.549, 0.894347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2608.92382812, 1292.36474609, 165.41179688), 'rotation':(0.94301, 0.548284, 0.912342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2603.35621094, 1292.31287109, 165.31886719), 'rotation':(0.955981, 0.54969, 0.924467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2597.7892968799997, 1292.26097656, 165.225), 'rotation':(0.968773, 0.550137, 0.936417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2592.22289062, 1292.20921875, 165.13054688), 'rotation':(0.975385, 0.549967, 0.94259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2581.08910156, 1292.10546875, 164.94078125), 'rotation':(0.978643, 0.550498, 0.945623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2569.95460938, 1292.00183594, 164.7490625), 'rotation':(0.991996, 0.550959, 0.958081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2564.3871875, 1291.94996094, 164.65220703), 'rotation':(0.998724, 0.551168, 0.96434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2558.81984375, 1291.89806641, 164.55464844), 'rotation':(1.005356, 0.551422, 0.970534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2553.25242188, 1291.84619141, 164.45640625), 'rotation':(1.011961, 0.551656, 0.976674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2547.6853125, 1291.79455078, 164.3575), 'rotation':(1.018846, 0.550555, 0.983074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2852.24316406, 1286.74925781, 168.90923827999998), 'rotation':(-0.724762, -179.456909, -0.743286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2830.11279297, 1286.54320312, 168.62667968999997), 'rotation':(-0.737823, -179.457138, -0.757019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2819.04736328, 1286.44019531, 168.48417969), 'rotation':(-0.737305, -179.45636, -0.756439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2813.51441406, 1286.38867188, 168.41296875), 'rotation':(-0.736359, -179.457214, -0.755463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2807.98167969, 1286.33714844, 168.34185547), 'rotation':(-0.735291, -179.45723, -0.754333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2802.44898438, 1286.28552734, 168.27078125), 'rotation':(-0.735291, -179.45723, -0.754333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2774.78662109, 1286.02808594, 167.91542969), 'rotation':(-0.757599, -179.456161, -0.777832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2758.19042969, 1285.87341797, 167.69273438), 'rotation':(-0.805298, -179.455963, -0.828186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2752.661875, 1285.82189453, 167.61587891), 'rotation':(-0.805298, -179.455963, -0.828186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2747.12988281, 1285.77027344, 167.53763672000002), 'rotation':(-0.821045, -179.454407, -0.844849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2741.59789062, 1285.71875, 167.45804688), 'rotation':(-0.837128, -179.453934, -0.861877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2736.06591797, 1285.66722656, 167.37712890999998), 'rotation':(-0.852966, -179.453461, -0.878632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2730.5334375, 1285.61572266, 167.29474609000002), 'rotation':(-0.860779, -179.4534, -0.886932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2725.00316406, 1285.56433594, 167.21167968999998), 'rotation':(-0.860931, -179.4534, -0.887115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2730.44482422, 1293.4962109399999, 167.29451172), 'rotation':(0.852947, 0.546533, 0.827835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2735.97777344, 1293.54773438, 167.37691406000002), 'rotation':(0.837122, 0.546049, 0.812921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2741.51, 1293.59923828, 167.45783203), 'rotation':(0.82105, 0.544464, 0.797763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2747.04273438, 1293.650625, 167.53742188), 'rotation':(0.8053, 0.545153, 0.782887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2752.57470703, 1293.70214844, 167.61568359), 'rotation':(0.789461, 0.544695, 0.767922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2758.10498047, 1293.75367188, 167.69255859), 'rotation':(0.789461, 0.544695, 0.767922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2763.63720703, 1293.80505859, 167.76814453), 'rotation':(0.773382, 0.544256, 0.752711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2769.1696875, 1293.8565625, 167.84238281), 'rotation':(0.757591, 0.542717, 0.737743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2774.70214844, 1293.90808594, 167.9153125), 'rotation':(0.741683, 0.543437, 0.722662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2780.23388672, 1293.95958984, 167.98689453), 'rotation':(0.733726, 0.54297, 0.715111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2791.30029297, 1294.06273438, 168.12871094), 'rotation':(0.734252, 0.542727, 0.71561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2796.83349609, 1294.11425781, 168.19964843999998), 'rotation':(0.73527, 0.543574, 0.716587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2802.36644531, 1294.16578125, 168.27066406000003), 'rotation':(0.736356, 0.54278, 0.717619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2813.42919922, 1294.26904297, 168.41283203), 'rotation':(0.737292, 0.54282, 0.718498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2818.96582031, 1294.3203125, 168.48408203), 'rotation':(0.737831, 0.543564, 0.718997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2824.49902344, 1294.37183594, 168.55533203), 'rotation':(0.737831, 0.543564, 0.718997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2830.03199219, 1294.42345703, 168.62658202999998), 'rotation':(0.735925, 0.542046, 0.717197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2846.63061523, 1294.5780078100001, 168.8390625), 'rotation':(0.724758, 0.543079, 0.706584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2857.69677734, 1294.68115234, 168.97888672000002), 'rotation':(0.717361, 0.54289, 0.699564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2863.22998047, 1294.73265625, 169.04824219), 'rotation':(0.713543, 0.542772, 0.695937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3045.09130859, 1289.09814453, 171.23769531000002), 'rotation':(-0.680847, -179.233276, -0.697144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.56005859, 1289.02490234, 171.17197266), 'rotation':(-0.679413, -179.233353, -0.695648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3028.49731445, 1288.87841797, 171.04080077999998), 'rotation':(-0.679016, -179.233078, -0.695251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3022.96606445, 1288.80517578, 170.97525391), 'rotation':(-0.679016, -179.233078, -0.695251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.90332031, 1288.65869141, 170.8440625), 'rotation':(-0.679657, -179.233063, -0.695953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3006.37207031, 1288.58544922, 170.77841797000002), 'rotation':(-0.679993, -179.233063, -0.696289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3000.84057617, 1288.51232422, 170.71273438), 'rotation':(-0.680298, -179.233093, -0.696594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2995.30957031, 1288.43908203, 170.64703125), 'rotation':(-0.681, -179.233032, -0.697327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2989.77832031, 1288.36583984, 170.58128906000002), 'rotation':(-0.681488, -179.233017, -0.697845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2973.18432617, 1288.14611328, 170.38388672000002), 'rotation':(-0.681427, -179.232971, -0.697784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2967.65283203, 1288.07287109, 170.31804688), 'rotation':(-0.68161, -179.232971, -0.697968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2962.12182617, 1287.99962891, 170.25224609), 'rotation':(-0.684235, -179.233978, -0.700714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2945.52905273, 1287.77990234, 170.05324219), 'rotation':(-0.692383, -179.233368, -0.70929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2928.93505859, 1287.5603125, 169.85261719), 'rotation':(-0.692505, -179.233368, -0.709412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2906.8137207, 1287.26746094, 169.58482422), 'rotation':(-0.691284, -179.347321, -0.70813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2901.28686523, 1287.20605469, 169.51748047), 'rotation':(-0.703217, -179.457352, -0.720642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2906.734375, 1295.14783203, 169.58513672), 'rotation':(0.695614, 0.766672, 0.678882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2912.265625, 1295.2209375, 169.65230469), 'rotation':(0.692506, 0.766637, 0.675913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2923.32788086, 1295.36742188, 169.78609375), 'rotation':(0.692506, 0.767475, 0.675914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2939.92114258, 1295.58714844, 169.98671875), 'rotation':(0.692424, 0.766653, 0.675839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2950.98291016, 1295.73351562, 170.12023438), 'rotation':(0.684228, 0.767055, 0.668033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2956.51416016, 1295.806875, 170.18658202999998), 'rotation':(0.684228, 0.767055, 0.668033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2967.57592773, 1295.9532421899999, 170.31839843999998), 'rotation':(0.681468, 0.767068, 0.6654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2978.63818359, 1296.09972656, 170.45001953), 'rotation':(0.681427, 0.765741, 0.665362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2984.16943359, 1296.17296875, 170.51580077999998), 'rotation':(0.681496, 0.766979, 0.665417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3011.82495117, 1296.5391796899999, 170.84435547), 'rotation':(0.67918, 0.766923, 0.663221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3028.41845703, 1296.75890625, 171.04109375), 'rotation':(0.67877, 0.766768, 0.662823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3039.48071289, 1296.90527344, 171.17226562), 'rotation':(0.680806, 0.766692, 0.664763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3050.54321289, 1297.05175781, 171.30378906), 'rotation':(0.681981, 0.766721, 0.665883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3083.00488281, 1297.4815625, 171.69171875), 'rotation':(0.685915, 0.766598, 0.669626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3099.68994141, 1297.70251953, 171.89179688000002), 'rotation':(0.693462, 0.766542, 0.676831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.37548828, 1297.92333984, 172.09375), 'rotation':(0.696037, 0.767939, 0.679281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3127.4987793, 1298.07068359, 172.22890625), 'rotation':(0.695846, 0.766648, 0.679103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3133.06054688, 1298.14429688, 172.29648438), 'rotation':(0.698073, 0.767008, 0.681211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3144.18408203, 1298.29150391, 172.43199219), 'rotation':(0.701986, 0.767047, 0.684936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3138.68457031, 1290.33740234, 172.36371093999998), 'rotation':(-0.695892, -179.232056, -0.712952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3127.5612793, 1290.19005859, 172.22841797), 'rotation':(-0.696014, -179.233337, -0.713074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3116.4387207, 1290.0428515600001, 172.09324218999998), 'rotation':(-0.696045, -179.233307, -0.713104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3110.87744141, 1289.96923828, 172.02572265999999), 'rotation':(-0.693451, -179.232727, -0.710419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3099.75415039, 1289.82189453, 171.89130859), 'rotation':(-0.688477, -179.233337, -0.7052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3088.6315918, 1289.6746875, 171.75785156), 'rotation':(-0.685913, -179.233398, -0.702484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.50097656, 1292.01623047, 173.95478516), 'rotation':(-0.735779, -179.231812, -0.754883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3259.953125, 1291.94287109, 173.88326172), 'rotation':(-0.735779, -179.231812, -0.754883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3215.56910156, 1291.35523438, 173.31761719), 'rotation':(-0.724792, -179.232376, -0.743317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3193.37695312, 1291.06140625, 173.03867188), 'rotation':(-0.712402, -179.232697, -0.730286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.82933594, 1290.98804688, 172.9696875), 'rotation':(-0.710327, -179.232666, -0.728088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3176.66455078, 1298.7215625, 172.83246093999998), 'rotation':(0.710312, 0.767322, 0.692865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3187.76148438, 1298.86853516, 172.97015625), 'rotation':(0.712402, 0.767297, 0.694852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3193.30957031, 1298.94189453, 173.03914062), 'rotation':(0.716528, 0.768244, 0.698783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3198.85816406, 1299.01539062, 173.10853516), 'rotation':(0.720558, 0.767502, 0.702598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3215.50341797, 1299.23583984, 173.318125), 'rotation':(0.726848, 0.767714, 0.70858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3237.69703125, 1299.52966797, 173.59984375), 'rotation':(0.73208, 0.76738, 0.713547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3243.24535156, 1299.60314453, 173.67050781), 'rotation':(0.73208, 0.76738, 0.713547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3248.79371094, 1299.67664062, 173.74144531000002), 'rotation':(0.735789, 0.768181, 0.717063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3265.43871094, 1299.89697266, 173.95533203), 'rotation':(0.739224, 0.768267, 0.720332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.33886719, 1300.75757812, 176.76416016), 'rotation':(0.735762, 0.092824, 0.717039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3463.75097656, 1300.6368359399999, 176.55111327999998), 'rotation':(0.735762, 0.092824, 0.717039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3452.69484375, 1300.58777344, 176.40865234), 'rotation':(0.737947, 0.092484, 0.719113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.57960938, 1300.55554688, 176.11914062), 'rotation':(0.753636, 0.093726, 0.733997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3425.05054688, 1300.54748047, 176.04640625), 'rotation':(0.75352, 0.093723, 0.733897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3419.52171875, 1300.53929688, 175.97367188), 'rotation':(0.753903, 0.093204, 0.734255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3413.99292969, 1300.53125, 175.90087891), 'rotation':(0.754053, 0.093208, 0.734402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3402.93507812, 1300.51513672, 175.75519531), 'rotation':(0.754674, 0.094466, 0.734994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3391.8771875, 1300.49902344, 175.60939453), 'rotation':(0.755439, 0.093243, 0.73573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.76148438, 1300.46679688, 175.31734375), 'rotation':(0.756764, 0.093373, 0.736977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3364.23265625, 1300.45875, 175.24427734), 'rotation':(0.756874, 0.093376, 0.737084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3358.70359375, 1300.45068359, 175.17128906000002), 'rotation':(0.755924, 0.093541, 0.736173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3336.58714844, 1300.41833984, 174.88066406000002), 'rotation':(0.750112, 0.092551, 0.730666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3331.05835938, 1300.4102734399999, 174.80826172000002), 'rotation':(0.750119, 0.093929, 0.730668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3325.52929688, 1300.4022265600001, 174.73585938), 'rotation':(0.750112, 0.092551, 0.730666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3303.41210938, 1300.36853516, 174.44681641), 'rotation':(0.747339, 0.093498, 0.728037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3297.93994141, 1300.32726562, 174.37615234), 'rotation':(0.736595, 0.600996, 0.717833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.35277344, 1292.61767578, 176.76419922000002), 'rotation':(-0.735748, -179.907166, -0.754852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3452.714375, 1292.70703125, 176.40875), 'rotation':(-0.742493, -179.907394, -0.761932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3441.65894531, 1292.69091797, 176.26462891), 'rotation':(-0.753601, -179.906265, -0.773621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3419.54808594, 1292.65869141, 175.97384766), 'rotation':(-0.754059, -179.906784, -0.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3414.02027344, 1292.650625, 175.90109375), 'rotation':(-0.754669, -179.906784, -0.77475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3391.90941406, 1292.61828125, 175.60966797), 'rotation':(-0.755768, -179.906754, -0.775909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3380.85375, 1292.60216797, 175.46371093999997), 'rotation':(-0.756531, -179.905472, -0.776733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3375.32617188, 1292.59412109, 175.39070312), 'rotation':(-0.756775, -179.906631, -0.776947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3369.79835938, 1292.5860546899999, 175.31767578), 'rotation':(-0.756866, -179.906616, -0.777069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3364.27050781, 1292.5780078100001, 175.24462891), 'rotation':(-0.75592, -179.906448, -0.776093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3331.10328125, 1292.52966797, 174.80869141), 'rotation':(-0.750122, -179.90744, -0.769958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.04957031, 1292.44726562, 174.37621094), 'rotation':(-0.743835, -179.231827, -0.763306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2052.95609375, 1545.31382812, 155.14123046999998), 'rotation':(-1.090576, -179.089035, -1.13269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2058.475625, 1545.39964844, 155.24712891), 'rotation':(-1.098511, -179.088226, -1.141266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2080.64914062, 1545.744375, 155.68633789), 'rotation':(-1.162292, -179.085724, -1.210175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2086.19164062, 1545.83054688, 155.79958008), 'rotation':(-1.162292, -179.085724, -1.210175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2113.90453125, 1546.26125, 156.38408203), 'rotation':(-1.226532, -179.082901, -1.279938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2119.44726562, 1546.3473046899999, 156.50358398), 'rotation':(-1.226532, -179.082901, -1.279938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2124.98898438, 1546.4334765600001, 156.62396484), 'rotation':(-1.243652, -179.082962, -1.298584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2130.5321875, 1546.5196484399999, 156.7459082), 'rotation':(-1.260712, -179.08223, -1.317169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2141.61570312, 1546.691875, 156.99227539), 'rotation':(-1.27774, -179.080643, -1.335724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2163.7839062499997, 1547.0228124999999, 157.49378906), 'rotation':(-1.309601, -179.080307, -1.370514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2180.40867188, 1547.3277734399999, 157.87765625), 'rotation':(-1.328186, -179.078354, -1.3909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2185.95015625, 1547.4139453100001, 158.00710938), 'rotation':(-1.337433, -179.079056, -1.401031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2197.0339062499997, 1547.5862890600001, 158.26858398000002), 'rotation':(-1.35611, -179.07814, -1.421509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2202.5768749999997, 1547.66945312, 158.40039062), 'rotation':(-1.362122, -179.124603, -1.428101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2208.0546875, 1555.59914062, 158.53376953), 'rotation':(1.366912, 0.874919, 1.302793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2191.4296875, 1555.3482812500001, 158.13888672), 'rotation':(1.3561, 0.922936, 1.292993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2185.88765625, 1555.2620703100001, 158.00851562), 'rotation':(1.346743, 0.92246, 1.2845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2180.34570312, 1555.17601562, 157.87902344), 'rotation':(1.337494, 0.920982, 1.276086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2163.7174999999997, 1554.9176171899999, 157.49506836), 'rotation':(1.318834, 0.920078, 1.259124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2158.17578125, 1554.8314062499999, 157.36862305), 'rotation':(1.309593, 0.92077, 1.250693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2152.63328125, 1554.74535156, 157.24289062), 'rotation':(1.300222, 0.920312, 1.242165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2141.54710938, 1554.573125, 156.99348633), 'rotation':(1.286343, 0.919384, 1.22951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2136.0051562500003, 1554.4869531200002, 156.86978516), 'rotation':(1.277723, 0.918536, 1.221654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2130.46242188, 1554.40074219, 156.74708984), 'rotation':(1.277723, 0.918536, 1.221654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2119.37570312, 1554.22839844, 156.50469727), 'rotation':(1.24362, 0.917009, 1.19047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2108.29078125, 1554.05617188, 156.26643555), 'rotation':(1.226558, 0.917115, 1.174857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2102.74703125, 1553.96996094, 156.14849609), 'rotation':(1.218055, 0.915835, 1.167068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2097.20289062, 1553.8836718799998, 156.03120117), 'rotation':(1.210091, 0.916253, 1.159756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2086.11671875, 1553.71140625, 155.80055664), 'rotation':(1.178064, 0.914921, 1.130339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2075.02640625, 1553.5389453100001, 155.5753125), 'rotation':(1.16228, 0.914273, 1.115808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2069.4831249999997, 1553.4527734399999, 155.46482422), 'rotation':(1.146331, 0.91363, 1.101125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2257.29078125, 1556.3225, 159.72727539), 'rotation':(1.402798, 0.875768, 1.335315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2262.9674999999997, 1556.4058984399999, 159.86629883), 'rotation':(1.405284, 0.875892, 1.337548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2274.32101562, 1556.57261719, 160.14506836), 'rotation':(1.409573, 0.876104, 1.341427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2279.9978125, 1556.6561328100001, 160.28482422), 'rotation':(1.412046, 0.876228, 1.343659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2297.02828125, 1556.90625, 160.70540039), 'rotation':(1.415495, 0.876361, 1.346783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2308.3815624999997, 1557.07300781, 160.98613281), 'rotation':(1.415434, 0.876318, 1.346733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2314.058125, 1557.1563671899999, 161.12649414), 'rotation':(1.412128, 0.876986, 1.343741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2319.73460938, 1557.23988281, 161.26652344000001), 'rotation':(1.408972, 0.875408, 1.340895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2353.7946875, 1557.70726562, 162.10414062), 'rotation':(1.397368, 0.87584, 1.330397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2359.47167969, 1557.79054688, 162.24270508), 'rotation':(1.388864, 0.875446, 1.32269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2393.53171875, 1558.29101562, 163.06394531), 'rotation':(1.367684, 0.874176, 1.303507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2399.20875, 1558.3743749999999, 163.19957031), 'rotation':(1.361578, 0.873588, 1.297962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.5625, 1558.54113281, 163.46926758), 'rotation':(1.349195, 0.873954, 1.286724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2416.23902344, 1558.62453125, 163.60289062), 'rotation':(1.336852, 0.872447, 1.275513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2421.91601562, 1558.70800781, 163.73543945), 'rotation':(1.324544, 0.872803, 1.264314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2433.27050781, 1558.87476562, 163.99800781000002), 'rotation':(1.318356, 0.872011, 1.258688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2438.94773438, 1558.95824219, 164.12873047000002), 'rotation':(1.318329, 0.871982, 1.258654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.62453125, 1559.0416406200002, 164.25945312), 'rotation':(1.309497, 0.871683, 1.250616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2450.30226562, 1559.1248828100001, 164.38949218999997), 'rotation':(1.291541, 0.870843, 1.234245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2251.74070312, 1548.3587499999999, 159.58875977), 'rotation':(-1.397247, -179.123993, -1.466736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2257.4175, 1548.44214844, 159.72753906), 'rotation':(-1.400665, -179.123001, -1.470459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2280.125, 1548.77574219, 160.28509766), 'rotation':(-1.409637, -179.12384, -1.480347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2285.80171875, 1548.85914062, 160.42507812), 'rotation':(-1.412048, -179.122452, -1.483002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2314.1853125, 1549.27613281, 161.12676758), 'rotation':(-1.415436, -179.123688, -1.486725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2319.8620312499997, 1549.35960938, 161.26681641), 'rotation':(-1.41214, -179.123749, -1.483093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2348.24511719, 1549.79113281, 161.96533203), 'rotation':(-1.405212, -179.123932, -1.475494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2359.59839844, 1549.97632812, 162.24299805), 'rotation':(-1.3974, -179.124146, -1.466888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2365.27464844, 1550.05980469, 162.38102539), 'rotation':(-1.3974, -179.124146, -1.466888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2370.95164062, 1550.1432031200002, 162.51875), 'rotation':(-1.388824, -179.124573, -1.457458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2376.62816406, 1550.2265625, 162.65570312), 'rotation':(-1.380402, -179.124954, -1.448181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2382.3046875, 1550.3099218799998, 162.79236328000002), 'rotation':(-1.380402, -179.124954, -1.448181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.68921875, 1550.72703125, 163.46954102), 'rotation':(-1.361572, -179.125458, -1.427521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2422.04296875, 1550.89378906, 163.73573242), 'rotation':(-1.336853, -179.126587, -1.400391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2427.71949219, 1550.97703125, 163.86726562), 'rotation':(-1.324554, -179.128143, -1.386902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.75121094, 1551.22730469, 164.25972656000002), 'rotation':(-1.318329, -179.128006, -1.380096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2450.42894531, 1551.31066406, 164.38976562), 'rotation':(-1.309509, -179.128311, -1.370453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2473.13769531, 1551.64429688, 164.89962891), 'rotation':(-1.273804, -179.129959, -1.331451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2516.80710938, 1552.2528125, 165.83931640999998), 'rotation':(-1.198761, -179.133301, -1.249725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.89941406, 1552.41578125, 166.06666016), 'rotation':(-1.168457, -179.134537, -1.216888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.44679688, 1552.4971875, 166.17916015999998), 'rotation':(-1.160889, -179.13475, -1.208649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2538.994375, 1552.5787500000001, 166.29162109), 'rotation':(-1.160706, -179.134781, -1.208466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2555.63453125, 1552.82324219, 166.62419922), 'rotation':(-1.132172, -179.135284, -1.177612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2561.18015625, 1552.90464844, 166.73261718999998), 'rotation':(-1.120789, -179.137115, -1.165314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2566.72730469, 1552.98621094, 166.83988281), 'rotation':(-1.109436, -179.136139, -1.153046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2583.36890625, 1553.2305859399999, 167.15474609), 'rotation':(-1.075012, -179.138855, -1.115967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2588.91578125, 1553.3121484399999, 167.25824218999998), 'rotation':(-1.069275, -179.137939, -1.109772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2594.463125, 1553.39355469, 167.36087891), 'rotation':(-1.062378, -179.139542, -1.102356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2600.01023438, 1553.47523438, 167.46207031000003), 'rotation':(-1.048157, -179.138733, -1.087067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2616.651875, 1553.7196093799998, 167.75673827999998), 'rotation':(-0.991669, -179.140747, -1.026459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2627.74683594, 1553.8824609399999, 167.94583984000002), 'rotation':(-0.963562, -179.143036, -0.996399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2633.29445312, 1553.96398438, 168.03869140999998), 'rotation':(-0.956665, -179.141449, -0.989014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2638.84253906, 1554.04554688, 168.13138672000002), 'rotation':(-0.956512, -179.142792, -0.988892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2633.1955468799997, 1561.8443750000001, 168.03896484), 'rotation':(0.95652, 0.857198, 0.924962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2622.10109375, 1561.68128906, 167.85232422), 'rotation':(0.963562, 0.858326, 0.931556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2616.55347656, 1561.59984375, 167.75705078), 'rotation':(0.977844, 0.858773, 0.94489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2605.4607031200003, 1561.4368749999999, 167.56208984), 'rotation':(1.020055, 0.860286, 0.984205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2572.17820312, 1560.94824219, 166.94632812), 'rotation':(1.086587, 0.861573, 1.045942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2566.63085938, 1560.86671875, 166.84025391), 'rotation':(1.097809, 0.863369, 1.056321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2561.08375, 1560.7852734399999, 166.73298828), 'rotation':(1.109434, 0.863855, 1.067069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2549.9919531200003, 1560.6221875, 166.51492188), 'rotation':(1.132165, 0.86471, 1.088061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2544.44484375, 1560.54066406, 166.40400391), 'rotation':(1.143749, 0.863804, 1.098735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.80394531, 1560.29640625, 166.06708984), 'rotation':(1.160866, 0.865257, 1.114516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.25878906, 1560.2149609399999, 165.95410156000003), 'rotation':(1.168468, 0.865454, 1.121506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2516.71214844, 1560.1334375000001, 165.83974609), 'rotation':(1.183549, 0.866039, 1.135375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2511.16527344, 1560.051875, 165.72388672), 'rotation':(1.198746, 0.866704, 1.149345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2864.65917969, 1557.3628125, 171.14316406), 'rotation':(-0.60611, -179.151459, -0.619019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2858.96801758, 1557.27917969, 171.08375), 'rotation':(-0.60611, -179.151459, -0.619019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2853.27734375, 1557.19554688, 171.02339844), 'rotation':(-0.618835, -179.152161, -0.632294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2841.89526367, 1557.0284375, 170.89943359), 'rotation':(-0.638184, -179.151108, -0.652527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2807.75074219, 1556.526875, 170.51341797), 'rotation':(-0.677551, -179.150696, -0.693726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2802.06152344, 1556.44335938, 170.44640625), 'rotation':(-0.686157, -179.149261, -0.702759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2796.37060547, 1556.3597265600001, 170.37851562), 'rotation':(-0.695099, -179.150284, -0.712128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2790.67945312, 1556.27613281, 170.30974609), 'rotation':(-0.703735, -179.150055, -0.721191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2773.60791016, 1556.02527344, 170.09947266), 'rotation':(-0.70929, -179.149353, -0.727051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2762.22582031, 1555.85804688, 169.95837891), 'rotation':(-0.711365, -179.15004, -0.729187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2756.53466797, 1555.77441406, 169.88767578), 'rotation':(-0.713684, -179.149246, -0.731628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2750.84351562, 1555.6907812499999, 169.81679688), 'rotation':(-0.715729, -179.149216, -0.733765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2745.15257812, 1555.6071875, 169.74583984), 'rotation':(-0.715729, -179.149216, -0.733765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2739.46142578, 1555.5235546899999, 169.67470702999998), 'rotation':(-0.716888, -179.149124, -0.734985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2728.07958984, 1555.35632812, 169.53228516), 'rotation':(-0.731903, -179.148895, -0.750793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2722.39208984, 1555.2728124999999, 169.45957031), 'rotation':(-0.761841, -179.148117, -0.782318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.70556641, 1555.18945312, 169.38361328), 'rotation':(-0.791779, -179.148621, -0.813904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2693.95458984, 1554.85523438, 169.04802734), 'rotation':(-0.91156, -179.143753, -0.940918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2682.57738281, 1554.68796875, 168.86191406), 'rotation':(-0.956665, -179.141647, -0.989014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.74339844, 1562.48414062, 168.76638672), 'rotation':(0.956602, 0.857355, 0.925059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2682.43382812, 1562.56761719, 168.86142578), 'rotation':(0.941651, 0.857224, 0.911077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2688.12255859, 1562.65125, 168.95574219), 'rotation':(0.91155, 0.856253, 0.882884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2699.49951172, 1562.81824219, 169.13626953), 'rotation':(0.85167, 0.854409, 0.82663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2710.87695312, 1562.98535156, 169.30412109), 'rotation':(0.79179, 0.852691, 0.770125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2716.56664062, 1563.06882812, 169.38330077999998), 'rotation':(0.761839, 0.851876, 0.741785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2722.25464844, 1563.15234375, 169.45929688), 'rotation':(0.731903, 0.851099, 0.713369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2727.943125, 1563.23597656, 169.53203125), 'rotation':(0.716876, 0.850875, 0.699107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2750.70726562, 1563.5704296899999, 169.81652343999997), 'rotation':(0.713666, 0.850738, 0.696051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2762.08960938, 1563.73753906, 169.958125), 'rotation':(0.709315, 0.850653, 0.691904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2790.54417969, 1564.15550781, 170.30951172000002), 'rotation':(0.695101, 0.850951, 0.678396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2796.23511719, 1564.23914062, 170.37828125), 'rotation':(0.686168, 0.849503, 0.669883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2801.92601562, 1564.32273438, 170.44619140999998), 'rotation':(0.677527, 0.849301, 0.661651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2813.30738281, 1564.49, 170.57935547), 'rotation':(0.65996, 0.848887, 0.644899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2830.38011719, 1564.74085938, 170.77275391), 'rotation':(0.638001, 0.848885, 0.623917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2836.07128906, 1564.82445312, 170.83615234), 'rotation':(0.638179, 0.84756, 0.624078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2841.76196289, 1564.90808594, 170.89923828), 'rotation':(0.631704, 0.849093, 0.617896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2847.453125, 1564.9915624999999, 170.96173828), 'rotation':(0.618822, 0.848785, 0.605558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2858.83520508, 1565.1588281200002, 171.08355468999997), 'rotation':(0.593325, 0.848245, 0.581127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2864.52612305, 1565.24242188, 171.14298828), 'rotation':(0.593325, 0.848245, 0.581127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2902.45239258, 1565.92921875, 171.52673828), 'rotation':(0.562924, 0.847212, 0.551941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2913.51220703, 1566.03601562, 171.63466797), 'rotation':(0.547426, 0.846909, 0.537043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2919.04101562, 1566.0628515600001, 171.68759766), 'rotation':(0.543567, 0.846833, 0.533329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2924.56933594, 1566.12453125, 171.74019531000002), 'rotation':(0.543567, 0.846833, 0.533329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2941.15576172, 1566.3680468799998, 171.89671875), 'rotation':(0.532208, 0.845539, 0.522386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2963.27148438, 1566.69289062, 172.10023438), 'rotation':(0.518671, 0.846419, 0.509341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.80029297, 1566.77417969, 172.15015625), 'rotation':(0.514149, 0.846336, 0.504995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2974.3293457, 1566.8553515600001, 172.1996875), 'rotation':(0.509491, 0.846224, 0.500477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2985.38696289, 1567.0178125, 172.2978125), 'rotation':(0.50736, 0.846287, 0.498426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2990.91601562, 1567.0989843799998, 172.34679688), 'rotation':(0.505618, 0.846384, 0.496758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3013.03222656, 1567.42394531, 172.54056641), 'rotation':(0.493754, 0.846109, 0.485295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3029.62060547, 1567.66566406, 172.68361328), 'rotation':(0.492525, 0.846074, 0.484109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3035.14892578, 1567.74890625, 172.73123047), 'rotation':(0.492525, 0.846074, 0.484109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3046.20654297, 1567.91136719, 172.82601562), 'rotation':(0.487566, 0.845987, 0.479331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3051.86083984, 1560.1129296899999, 172.87314453), 'rotation':(-0.487579, -179.154007, -0.495911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3029.74414062, 1559.78796875, 172.68367188), 'rotation':(-0.493744, -179.153885, -0.502319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3024.21508789, 1559.7066796899999, 172.63601562), 'rotation':(-0.493744, -179.1539, -0.502319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3018.68579102, 1559.62546875, 172.58835938), 'rotation':(-0.4953, -179.153793, -0.503906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3013.15698242, 1559.5442968799998, 172.54064452999998), 'rotation':(-0.4953, -179.153793, -0.503906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2985.51171875, 1559.13820312, 172.29789062), 'rotation':(-0.507385, -179.153687, -0.516418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.4543457, 1558.9757031200002, 172.19978516), 'rotation':(-0.51413, -179.153687, -0.523438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2957.86743164, 1558.73195312, 172.05001953), 'rotation':(-0.523193, -179.153503, -0.532806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2946.80932617, 1558.5696874999999, 171.94828125), 'rotation':(-0.532196, -179.15332, -0.542175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2919.16723633, 1558.1440625, 171.68771484), 'rotation':(-0.547455, -179.153061, -0.557983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2908.11206055, 1557.87316406, 171.58117188), 'rotation':(-0.562958, -179.152771, -0.574097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3095.27832031, 1568.63234375, 173.23800781000003), 'rotation':(0.477669, 0.845561, 0.469753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3100.84179688, 1568.71398438, 173.28439453), 'rotation':(0.477382, 0.845554, 0.469479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3106.4050293, 1568.79578125, 173.33078125), 'rotation':(0.477382, 0.845554, 0.469479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3111.96826172, 1568.87742188, 173.37712890999998), 'rotation':(0.477246, 0.845537, 0.469346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3123.09472656, 1569.04089844, 173.46984375), 'rotation':(0.477341, 0.845538, 0.469437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3128.65795898, 1569.12269531, 173.51621093999998), 'rotation':(0.477253, 0.845563, 0.469351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3134.22119141, 1569.20445312, 173.56255859), 'rotation':(0.477253, 0.845563, 0.469351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3139.78442383, 1569.28613281, 173.60890625), 'rotation':(0.477246, 0.846297, 0.469337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3139.90356445, 1561.4063671899999, 173.60892578), 'rotation':(-0.477234, -179.154449, -0.485229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3134.34057617, 1561.3245703100001, 173.56259766), 'rotation':(-0.477356, -179.154449, -0.485352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3123.21386719, 1561.16113281, 173.46988281000003), 'rotation':(-0.477234, -179.154449, -0.485229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3106.52416992, 1560.91589844, 173.33082031), 'rotation':(-0.477692, -179.154434, -0.485687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3084.27099609, 1560.58898438, 173.14523438), 'rotation':(-0.477844, -179.154343, -0.48587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3250.00609375, 1563.02390625, 174.52642577999998), 'rotation':(-0.477753, -179.153671, -0.485779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3244.46070312, 1562.94238281, 174.48017578), 'rotation':(-0.477814, -179.154739, -0.48584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3238.91503906, 1562.86097656, 174.43390625), 'rotation':(-0.477814, -179.154007, -0.48584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.18847656, 1562.45359375, 174.20263672000002), 'rotation':(-0.4776, -179.154602, -0.485626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3205.64306641, 1562.3721875, 174.15638672), 'rotation':(-0.477142, -179.154617, -0.485168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3194.5525, 1562.20921875, 174.06400391), 'rotation':(-0.476959, -179.153473, -0.484955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3172.25195312, 1569.76320312, 173.87929688), 'rotation':(0.476945, 0.845607, 0.469056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.79710938, 1569.8446093799998, 173.92546875), 'rotation':(0.476945, 0.845607, 0.469056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3194.43359375, 1570.08898438, 174.06398438), 'rotation':(0.47715, 0.845372, 0.469253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3205.52417969, 1570.25195312, 174.15634766), 'rotation':(0.477628, 0.845379, 0.4697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.06957031, 1570.3333593799998, 174.20261718999998), 'rotation':(0.477813, 0.845985, 0.4699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3216.61474609, 1570.41480469, 174.24886718999997), 'rotation':(0.477901, 0.845987, 0.469988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3222.16015625, 1570.49632812, 174.29511718999998), 'rotation':(0.477901, 0.845987, 0.469988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3233.25074219, 1570.65929688, 174.38763672000002), 'rotation':(0.477813, 0.845985, 0.4699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3238.79613281, 1570.74070312, 174.43390625), 'rotation':(0.477813, 0.845985, 0.4699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3260.97412109, 1571.12621094, 174.61882812), 'rotation':(0.477328, 0.84492, 0.469423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3310.57910156, 1563.9139453100001, 175.03046875), 'rotation':(-0.47467, -179.154495, -0.482574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3321.96289062, 1564.08117188, 175.12451172000002), 'rotation':(-0.473083, -179.154251, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3327.65453125, 1564.16480469, 175.17152344), 'rotation':(-0.473053, -179.155197, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3333.34617188, 1564.24839844, 175.21847656000003), 'rotation':(-0.473053, -179.155197, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3339.03785156, 1564.33203125, 175.2653125), 'rotation':(-0.470459, -179.153976, -0.47821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3356.11328125, 1564.58289062, 175.40462890999999), 'rotation':(-0.46521, -179.154068, -0.472809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3361.80515625, 1564.66648438, 175.45072266), 'rotation':(-0.463531, -179.155396, -0.471069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3367.49683594, 1564.7501171899999, 175.49660156000002), 'rotation':(-0.462006, -179.154083, -0.469513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3373.18847656, 1564.83375, 175.54230468999998), 'rotation':(-0.460144, -179.155502, -0.46756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3378.880625, 1564.9173437499999, 175.58792968999998), 'rotation':(-0.459259, -179.154617, -0.466644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3401.64746094, 1565.25183594, 175.76927734), 'rotation':(-0.453094, -179.154663, -0.460297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3407.33910156, 1565.33546875, 175.81388672), 'rotation':(-0.449005, -179.154739, -0.456085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3413.0310156200003, 1565.4190625, 175.85818359), 'rotation':(-0.444916, -179.154785, -0.451874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3418.72265625, 1565.50269531, 175.90228516), 'rotation':(-0.444916, -179.154785, -0.451874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3424.41453125, 1565.5862890600001, 175.94626953), 'rotation':(-0.44281, -179.154602, -0.449707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.10621094, 1565.66992188, 175.99027343999998), 'rotation':(-0.442841, -179.155441, -0.449707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3435.79808594, 1565.7535546899999, 176.03394531), 'rotation':(-0.442841, -179.155441, -0.449707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3483.22703125, 1566.3206640600001, 176.37716797000002), 'rotation':(-0.401733, -179.155609, -0.40741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3464.14992188, 1574.05125, 176.24382812), 'rotation':(0.401902, 0.844423, 0.396293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3452.76636719, 1573.88414062, 176.16181641), 'rotation':(0.417222, 0.844333, 0.411187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3447.07496094, 1573.80054688, 176.11986328), 'rotation':(0.417222, 0.844333, 0.411187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3441.3830468799997, 1573.71691406, 176.07738281000002), 'rotation':(0.427454, 0.845253, 0.421107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3430.00046875, 1573.5496875, 175.99035156000002), 'rotation':(0.437644, 0.844615, 0.431003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3412.9253125, 1573.29882812, 175.85824218999997), 'rotation':(0.442822, 0.844527, 0.436014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3401.54175781, 1573.13160156, 175.76935547000002), 'rotation':(0.448996, 0.845266, 0.442007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3390.1584375, 1572.964375, 175.67914062), 'rotation':(0.453087, 0.845331, 0.445969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3367.39183594, 1572.62988281, 175.49667968999998), 'rotation':(0.460109, 0.845854, 0.452781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3361.69996094, 1572.5462499999999, 175.45080077999998), 'rotation':(0.462001, 0.84457, 0.454606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3333.24121094, 1572.12816406, 175.21857422000002), 'rotation':(0.470429, 0.846023, 0.462767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3327.54980469, 1572.04457031, 175.17160156000003), 'rotation':(0.472157, 0.844738, 0.464424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3299.09058594, 1571.62648438, 174.93621094), 'rotation':(0.475456, 0.845486, 0.467613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3293.39917969, 1571.5428515600001, 174.88892578), 'rotation':(0.475456, 0.845486, 0.467613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.06398438, 1110.59386719, 158.02313476999998), 'rotation':(-0.035675, 90.221283, -0.035736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.02710938, 1132.70361328, 158.01324219), 'rotation':(-0.002747, 90.223701, -0.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.005625, 1138.23193359, 158.01283203), 'rotation':(-0.002747, 90.223701, -0.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.96265625, 1149.2868652299999, 158.01231445), 'rotation':(-0.002747, 90.223717, -0.002716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.83351562, 1182.45263672, 158.01150391), 'rotation':(0.011345, 90.222633, 0.011335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2227.81179688, 1187.9803515600001, 158.01275391), 'rotation':(0.020873, 90.225052, 0.02086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.7903125000003, 1193.50804688, 158.01487305), 'rotation':(0.030094, 90.222641, 0.030065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.72585938, 1210.09130859, 158.02455078), 'rotation':(0.039718, 90.22242, 0.039664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.7043750000003, 1215.61962891, 158.0280957), 'rotation':(0.039718, 90.22242, 0.039664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.6396875, 1232.20203125, 158.04107421999998), 'rotation':(0.058849, 90.222466, 0.058732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.45554688, 1248.81591797, 158.05902344), 'rotation':(-0.068604, -89.777496, -0.068756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.54148438, 1226.70544922, 158.03631836), 'rotation':(-0.039703, -89.776123, -0.039764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.56320312, 1221.17773438, 158.03192382999998), 'rotation':(-0.039703, -89.776123, -0.039764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.6276562499997, 1204.59484375, 158.02121094), 'rotation':(-0.034943, -89.777191, -0.034973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.6706249999997, 1193.5390625, 158.01487305), 'rotation':(-0.020874, -89.777344, -0.020905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.69210938, 1188.01123047, 158.01275391), 'rotation':(-0.011353, -89.777344, -0.011353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.7135937499997, 1182.48351562, 158.01150391), 'rotation':(-0.001953, -89.777374, -0.001953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.7565624999997, 1171.42736328, 158.01125977), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.77804688, 1165.89990234, 158.01152344), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.82101562, 1154.84509766, 158.01204102), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.8428125, 1149.31762695, 158.01231445), 'rotation':(0.002725, -89.776276, 0.002727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.86421875, 1143.7902832, 158.01257812), 'rotation':(0.002725, -89.776276, 0.002728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.9071875, 1132.73449219, 158.01324219), 'rotation':(0.007506, -89.776031, 0.007515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.97195312, 1116.15125, 158.01939453), 'rotation':(0.040401, -89.776611, 0.040344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.87695312, 1397.38441406, 158.39224609000001), 'rotation':(-0.193176, -89.776184, -0.194489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.94164062, 1380.7728124999999, 158.33839844), 'rotation':(-0.173309, -89.776306, -0.174347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.00632812, 1364.16125, 158.28930664), 'rotation':(-0.158112, -89.776398, -0.158997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.0278125, 1358.62316406, 158.2740332), 'rotation':(-0.155762, -89.776947, -0.156586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.07078125, 1347.54820312, 158.24412109000002), 'rotation':(-0.147552, -89.776398, -0.148315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.0924999999997, 1342.01125, 158.2297168), 'rotation':(-0.142303, -89.776428, -0.143005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.11398438, 1336.47386719, 158.21586914), 'rotation':(-0.137054, -89.776428, -0.137695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.1354687499997, 1330.9366406200002, 158.20254882999998), 'rotation':(-0.131653, -89.776489, -0.132233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.1571875, 1325.39941406, 158.18974609), 'rotation':(-0.126221, -89.776489, -0.12677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.17875, 1319.86230469, 158.17749023), 'rotation':(-0.120972, -89.77652, -0.12149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.2004687500003, 1314.32496094, 158.16577148), 'rotation':(-0.115723, -89.77655, -0.11618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2235.2221875, 1308.78673828, 158.15458984), 'rotation':(-0.113068, -89.777039, -0.113495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2235.24367188, 1303.24976562, 158.14367188), 'rotation':(-0.109467, -89.776428, -0.109863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.95359375, 1408.41992188, 158.42998047), 'rotation':(0.1977, 90.221619, 0.196342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.99679688, 1397.34570312, 158.39220703), 'rotation':(0.195822, 90.224083, 0.194483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.03976562, 1386.27148438, 158.35577148000002), 'rotation':(0.183227, 90.223732, 0.182074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.14773438, 1358.58558594, 158.27400391), 'rotation':(0.158133, 90.223595, 0.15727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2227.19070312, 1347.51085938, 158.24411133), 'rotation':(0.152962, 90.22361, 0.152166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.21242188, 1341.97386719, 158.22970703000001), 'rotation':(0.147553, 90.223587, 0.1468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.23390625, 1336.4368749999999, 158.21584961), 'rotation':(0.1423, 90.223564, 0.141602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2227.25539062, 1330.89964844, 158.2025293), 'rotation':(0.137055, 90.223534, 0.136402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2227.34179688, 1308.75048828, 158.15457031), 'rotation':(0.115703, 90.223442, 0.115252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.50414062, 1523.93601562, 158.92296875), 'rotation':(0.29335, 90.225304, 0.290361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.5903125, 1501.78078125, 158.81564453000001), 'rotation':(0.274273, 90.22422, 0.271659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.61179688, 1496.24121094, 158.78916992), 'rotation':(0.274382, 90.224228, 0.271766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.63328125, 1490.70265625, 158.763125), 'rotation':(0.269362, 90.22467, 0.266843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.6549999999997, 1485.16359375, 158.73744141), 'rotation':(0.269362, 90.22467, 0.266843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.7196875, 1468.54734375, 158.66375976999998), 'rotation':(0.249671, 90.224503, 0.247506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.74125, 1463.0084375000001, 158.64054688), 'rotation':(0.239781, 90.224396, 0.237772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.805625, 1446.39097656, 158.57209961), 'rotation':(0.234829, 90.222237, 0.232911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.8489062500003, 1435.31347656, 158.52801757999998), 'rotation':(0.230082, 90.224419, 0.228255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.70773438, 1440.89074219, 158.54988280999999), 'rotation':(-0.220551, -89.777222, -0.22226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.59984375, 1468.58628906, 158.66379883), 'rotation':(-0.239777, -89.777069, -0.241791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.578125, 1474.125, 158.68792969), 'rotation':(-0.249664, -89.775482, -0.251862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.5134375, 1490.74195312, 158.76316406), 'rotation':(-0.259491, -89.775421, -0.261841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.49195312, 1496.2806249999999, 158.78921875), 'rotation':(-0.269379, -89.77533, -0.271912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.47046875, 1501.82019531, 158.81569336), 'rotation':(-0.274384, -89.775757, -0.277008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.44875, 1507.35902344, 158.84220703), 'rotation':(-0.274384, -89.775757, -0.277008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.42726562, 1512.89769531, 158.86873047), 'rotation':(-0.274261, -89.775757, -0.276917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.3410937500003, 1535.0538281200002, 158.97952148000002), 'rotation':(-0.293335, -89.776733, -0.296356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.8371875000003, 1689.09421875, 159.88907226999999), 'rotation':(0.375879, 90.226173, 0.370971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.88257812, 1683.56515625, 159.85294922), 'rotation':(0.373686, 90.225388, 0.368851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.92554688, 1672.5032031199999, 159.78170898), 'rotation':(0.369329, 90.225342, 0.364597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.94703125, 1666.9720312499999, 159.74664062), 'rotation':(0.364821, 90.225281, 0.360207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.96875, 1661.4409375, 159.71188476999998), 'rotation':(0.360613, 90.225227, 0.356098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.01171875, 1650.3790234399999, 159.64268555), 'rotation':(0.358414, 90.224739, 0.353953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.03320312, 1644.84839844, 159.6080957), 'rotation':(0.358312, 90.226143, 0.353861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.0546875, 1639.316875, 159.57365234), 'rotation':(0.358312, 90.226143, 0.353861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.09789062, 1628.25488281, 159.5055957), 'rotation':(0.349965, 90.225601, 0.345711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.14109375, 1617.1927343799998, 159.43887695), 'rotation':(0.344412, 90.225517, 0.340286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.24851562, 1589.53675781, 159.27683594), 'rotation':(0.332849, 90.225357, 0.328995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2226.27023438, 1584.00585938, 159.24533203000001), 'rotation':(0.326497, 90.225281, 0.322788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.83742188, 1694.67015625, 159.92544922), 'rotation':(-0.375885, -89.775665, -0.380829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.76265625, 1683.61109375, 159.85305664), 'rotation':(-0.369324, -89.774658, -0.374146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.8271875, 1667.01734375, 159.74673828000002), 'rotation':(-0.360596, -89.77478, -0.365173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.8918750000003, 1650.4240625, 159.64277344), 'rotation':(-0.358337, -89.775238, -0.362823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.91335938, 1644.8928125, 159.60817383), 'rotation':(-0.355621, -89.774323, -0.360046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.9348437500003, 1639.36132812, 159.57375), 'rotation':(-0.355621, -89.774323, -0.360046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.95632812, 1633.83007812, 159.53946288999998), 'rotation':(-0.349945, -89.774414, -0.354248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.97828125, 1628.2990625, 159.50567383), 'rotation':(-0.344421, -89.776123, -0.348572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.99976562, 1622.7678125, 159.4721875), 'rotation':(-0.344421, -89.776123, -0.348572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.04273438, 1611.70554688, 159.40623047), 'rotation':(-0.33606, -89.774811, -0.340027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.0859375, 1600.64269531, 159.3412207), 'rotation':(-0.332855, -89.774628, -0.336731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.10742188, 1595.11109375, 159.30900391), 'rotation':(-0.332855, -89.774628, -0.336731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2234.12890625, 1589.57996094, 159.27691406), 'rotation':(-0.326477, -89.776245, -0.330231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2234.21507812, 1567.45507812, 159.15275391), 'rotation':(-0.313751, -89.774841, -0.3172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.39992188, 1793.69265625, 160.58720703), 'rotation':(0.391664, 90.226212, 0.386342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.4753124999997, 1788.1365624999999, 160.54926758), 'rotation':(0.391664, 90.226212, 0.386342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.49703125, 1782.5774999999999, 160.51136719), 'rotation':(0.390578, 90.225739, 0.385283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.58375, 1760.3415625, 160.36125), 'rotation':(0.384403, 90.225647, 0.379272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.60523438, 1754.7821875, 160.32400391), 'rotation':(0.383474, 90.225929, 0.37836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.62695312, 1749.2233593800001, 160.28680664), 'rotation':(0.383474, 90.225929, 0.37836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2225.67015625, 1738.10546875, 160.21240234), 'rotation':(0.383474, 90.225929, 0.37836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2225.61234375, 1732.5503125, 160.17529297), 'rotation':(0.382415, 90.227104, 0.377336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.55054688, 1738.1403906199998, 160.21243164), 'rotation':(-0.382416, -89.775055, -0.387543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2233.4206249999997, 1771.50148438, 160.43612305), 'rotation':(-0.386505, -89.774323, -0.391754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.35570312, 1788.18210938, 160.54936523), 'rotation':(-0.390564, -89.774261, -0.395935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2233.38820312, 1793.74, 160.58731445), 'rotation':(-0.390564, -89.774261, -0.395935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2216.28367188, 1897.6, 160.99893555), 'rotation':(0.034506, 101.403885, 0.03447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2218.27046875, 1886.64367188, 160.99226562), 'rotation':(0.034513, 100.187187, 0.034464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2220.06859375, 1875.64296875, 160.98526367), 'rotation':(0.034506, 98.975456, 0.034475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2224.01078125, 1842.4446093800002, 160.87428711), 'rotation':(0.261528, 94.631805, 0.259147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2224.73898438, 1831.37453125, 160.82224609000002), 'rotation':(0.281588, 93.289124, 0.278825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2230.3090625, 1859.38851562, 160.94558594), 'rotation':(-0.213623, -83.589966, -0.21521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2229.6496875000003, 1864.92875, 160.96362305), 'rotation':(-0.185822, -83.227203, -0.187042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.92578125, 1870.44921875, 160.97658203), 'rotation':(-0.130524, -82.496033, -0.131104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2228.13695312, 1875.95945312, 160.98453125), 'rotation':(-0.074921, -81.768494, -0.075104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2226.36328125, 1886.93859375, 160.99161132999998), 'rotation':(-0.033386, -80.210571, -0.033447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2225.37820312, 1892.4172656199999, 160.99489258), 'rotation':(-0.033661, -79.813599, -0.033691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2207.6510937499997, 1950.12460938, 161.06849609), 'rotation':(0.128899, 96.306984, 0.128316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2206.60617188, 1960.5782812500001, 161.09323242), 'rotation':(0.152771, 95.000145, 0.15195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2206.1706249999997, 1965.8146875, 161.10804688), 'rotation':(0.172046, 94.433807, 0.171016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2205.46898438, 1976.2834375, 161.14335938), 'rotation':(0.219693, 93.011032, 0.218008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2204.6996875, 1991.9815625, 161.21067383), 'rotation':(0.277162, 91.31089, 0.27449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2204.60476562, 1997.20015625, 161.23632812), 'rotation':(0.285229, 90.59446, 0.2824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2212.62476562, 1997.68125, 161.23826172), 'rotation':(-0.289032, -89.262756, -0.291962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2212.89648438, 1986.3001562499999, 161.18304688), 'rotation':(-0.254608, -87.839233, -0.256866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2213.51414062, 1974.9060937499999, 161.13650391), 'rotation':(-0.205383, -86.418457, -0.206848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2214.40695312, 1963.51757812, 161.09939453), 'rotation':(-0.156555, -85.00116, -0.15741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2214.9196875, 1957.83164062, 161.08439453), 'rotation':(-0.137177, -84.438354, -0.137817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2216.005625, 1946.4609375, 161.05802734), 'rotation':(-0.131836, -82.888489, -0.132446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2217.50320312, 1935.1646875000001, 161.03369141), 'rotation':(-0.103912, -81.694, -0.104279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2218.3528125000003, 1929.5325, 161.02419921999999), 'rotation':(-0.079346, -80.843689, -0.079559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.82300781, 1104.40014648, 163.40893555), 'rotation':(0.089981, 89.222206, 0.089707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.12304688, 1126.50353516, 163.44755859), 'rotation':(0.120389, 89.222313, 0.119881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.348125, 1143.08019531, 163.48399414), 'rotation':(0.139199, 89.222206, 0.138535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.49828125, 1154.13232422, 163.51120117), 'rotation':(0.145251, 89.220901, 0.144533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.72363281, 1170.70910156, 163.55578125), 'rotation':(0.169184, 89.222427, 0.16818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2523.87402344, 1181.75976562, 163.58886719), 'rotation':(0.181102, 89.2211, 0.179962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2524.099375, 1198.33728516, 163.64222656), 'rotation':(0.191006, 89.223885, 0.189742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2524.39964844, 1220.44019531, 163.72072265999998), 'rotation':(0.221018, 89.224098, 0.21933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2524.70019531, 1242.54236328, 163.81130859), 'rotation':(0.247526, 89.221725, 0.245399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2525.00046875, 1264.64476562, 163.90998047000002), 'rotation':(0.272443, 89.224251, 0.26986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.95554688, 1270.0646875, 163.93626953), 'rotation':(-0.27243, -90.77771, -0.275055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.88039062, 1264.5391796899999, 163.90998047000002), 'rotation':(-0.262482, -90.777802, -0.264893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.80515625, 1259.01367188, 163.88439452999998), 'rotation':(-0.252533, -90.777893, -0.254761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.73, 1253.48791016, 163.85949218999997), 'rotation':(-0.252533, -90.777893, -0.254761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.4294531200003, 1231.38525391, 163.76456055), 'rotation':(-0.228699, -90.775818, -0.23056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.27929688, 1220.33447266, 163.72072265999998), 'rotation':(-0.213684, -90.778625, -0.215302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.12914062, 1209.28246094, 163.67995117), 'rotation':(-0.198334, -90.778717, -0.199738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.97898438, 1198.23121094, 163.64222656), 'rotation':(-0.187103, -90.77829, -0.188354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.82859375, 1187.17882812, 163.60633789), 'rotation':(-0.181122, -90.777496, -0.182251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.67847656, 1176.12792969, 163.57209961), 'rotation':(-0.169189, -90.777588, -0.170197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.52832031, 1165.07726562, 163.54039062), 'rotation':(-0.157196, -90.779053, -0.158051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.4533593799997, 1159.551875, 163.52522461), 'rotation':(-0.145264, -90.777679, -0.145996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.22804688, 1142.97363281, 163.48399414), 'rotation':(-0.135498, -90.777588, -0.136169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.15308594, 1137.448125, 163.47113281), 'rotation':(-0.127808, -90.777649, -0.128387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.0778906200003, 1131.92236328, 163.45898438), 'rotation':(-0.120392, -90.777679, -0.120911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.00292969, 1126.39708984, 163.44755859), 'rotation':(-0.112671, -90.780151, -0.113129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.85277344, 1115.34460938, 163.42681641), 'rotation':(-0.097717, -90.777771, -0.098022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.77757812, 1109.81921875, 163.4175293), 'rotation':(-0.089966, -90.780273, -0.090271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.70265625, 1104.29345703, 163.40893555), 'rotation':(-0.082581, -90.777771, -0.082794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2530.63890625, 1098.76977539, 163.40099609), 'rotation':(-0.078796, -90.778503, -0.07901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.66699219, 1093.24511719, 163.3934375), 'rotation':(-0.078674, -90.778503, -0.078888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2533.04003906, 1308.62132812, 164.12814453), 'rotation':(-0.259857, -87.638733, -0.262207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2531.8246875, 1324.91931641, 164.195625), 'rotation':(-0.218689, -84.470062, -0.220367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2531.21921875, 1330.3836718799998, 164.21576172000002), 'rotation':(-0.207214, -83.566406, -0.20874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.37425781, 1335.81605469, 164.23462891), 'rotation':(-0.189697, -82.209839, -0.190948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2527.67015625, 1352.17542969, 164.28654297), 'rotation':(-0.16214, -79.463654, -0.163055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2526.5746875, 1357.58386719, 164.30039062), 'rotation':(-0.132629, -78.064941, -0.13324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2525.38011719, 1362.984375, 164.31216797000002), 'rotation':(-0.112823, -77.132965, -0.113281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2524.09132812, 1368.35765625, 164.32185547), 'rotation':(-0.093384, -76.196655, -0.093689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.73144531, 1373.7037500000001, 164.32933594), 'rotation':(-0.073608, -75.267761, -0.073792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2521.3669531200003, 1379.03808594, 164.33474609), 'rotation':(-0.054169, -74.335327, -0.05426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2519.80371094, 1384.28648438, 164.33818359), 'rotation':(-0.029297, -72.93927, -0.029327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2514.58835938, 1399.7662500000001, 164.34660156), 'rotation':(-0.029663, -70.221558, -0.029694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.703125, 1324.03064453, 164.19537109), 'rotation':(0.221387, 95.982758, 0.219665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2523.08960938, 1329.56007812, 164.21628906), 'rotation':(0.209099, 96.887283, 0.207582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2522.37207031, 1335.10351562, 164.2359375), 'rotation':(0.193793, 98.191063, 0.192492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2519.5859375, 1351.70628906, 164.28949218999998), 'rotation':(0.147962, 101.469421, 0.147196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2511.25683594, 1384.2493749999999, 164.33951172000002), 'rotation':(0.030463, 107.968842, 0.030427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2507.723125, 1394.73082031, 164.34535156), 'rotation':(0.030838, 109.778976, 0.030804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2496.47972656, 1474.3131250000001, 164.5715625), 'rotation':(-0.367218, -83.103485, -0.371948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.46046875, 1507.83484375, 164.83060547000002), 'rotation':(-0.486145, -89.519745, -0.494446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.45898438, 1513.3665624999999, 164.87867188), 'rotation':(-0.493134, -89.890747, -0.501678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.4665625, 1518.8721875, 164.92705078), 'rotation':(-0.503235, -90.076111, -0.512115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.47460938, 1524.37390625, 164.97814452999998), 'rotation':(-0.534851, -90.075531, -0.544891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.42308594, 1529.8746484399999, 165.02988281), 'rotation':(-0.534851, -90.075531, -0.544891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.35277344, 1540.87390625, 165.13556641), 'rotation':(-0.550476, -90.074341, -0.561127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.32664062, 1540.52964844, 165.13214843999998), 'rotation':(0.550486, 89.925629, 0.539985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.31910156, 1534.99097656, 165.07892578), 'rotation':(0.550486, 89.925629, 0.539985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.29566406, 1518.37109375, 164.92253906000002), 'rotation':(0.534838, 89.924461, 0.524928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.43945312, 1507.2940625, 164.82654297000002), 'rotation':(0.475005, 90.105095, 0.467166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.99632812, 1490.7178906200002, 164.69765625), 'rotation':(0.423943, 93.199463, 0.41771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2488.42039062, 1474.1517187499999, 164.57648438), 'rotation':(0.384751, 96.207191, 0.379616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2489.08519531, 1468.6640625, 164.54216797), 'rotation':(0.337965, 97.250694, 0.333996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2490.55640625, 1457.7265625, 164.48677734), 'rotation':(0.244364, 99.338486, 0.242295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2491.50074219, 1452.31410156, 164.46560547), 'rotation':(0.198007, 100.382851, 0.196638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.51734375, 1573.1596875, 165.45175781), 'rotation':(0.576536, 89.925896, 0.565035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.54078125, 1589.76246094, 165.61888672), 'rotation':(0.578592, 89.926605, 0.567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.54835938, 1595.29640625, 165.67490234000002), 'rotation':(0.583052, 89.926704, 0.571277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.57152344, 1611.89867188, 165.84556641), 'rotation':(0.595756, 89.924332, 0.583459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.59472656, 1628.5008593799998, 166.02011718999998), 'rotation':(0.610913, 89.92662, 0.597978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.60230469, 1634.03539062, 166.07904297000002), 'rotation':(0.610913, 89.92662, 0.597978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.61011719, 1639.56933594, 166.13806641), 'rotation':(0.613126, 89.925087, 0.600118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.63328125, 1656.17140625, 166.31626953), 'rotation':(0.622121, 89.926735, 0.608716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.64109375, 1661.70546875, 166.37615234), 'rotation':(0.622121, 89.926735, 0.608716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.65671875, 1672.7734375, 166.49667968999998), 'rotation':(0.626588, 89.926834, 0.612981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.68015625, 1689.3752343800002, 166.67871093999997), 'rotation':(0.629648, 89.926201, 0.615919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.60644531, 1694.90734375, 166.73949219), 'rotation':(0.631226, 89.928078, 0.617438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.40550781, 1578.68554688, 165.50748047000002), 'rotation':(-0.576538, -90.074097, -0.588226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.41332031, 1584.21949219, 165.56316406000002), 'rotation':(-0.576569, -90.074097, -0.588257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.42113281, 1589.75414062, 165.61890625), 'rotation':(-0.576569, -90.074097, -0.588257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.44433594, 1606.3565625, 165.78826172), 'rotation':(-0.587189, -90.075836, -0.599304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.45214844, 1611.8905078100001, 165.84560547), 'rotation':(-0.591644, -90.07312, -0.603943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.45996094, 1617.42480469, 165.90333984), 'rotation':(-0.595764, -90.075684, -0.608246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.46777344, 1622.95886719, 165.96152343999998), 'rotation':(-0.60434, -90.072845, -0.617188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.49878906, 1645.09570312, 166.19730468999998), 'rotation':(-0.613129, -90.073425, -0.626343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.51414062, 1656.16367188, 166.31630859), 'rotation':(-0.617584, -90.074799, -0.631012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.52976562, 1667.23171875, 166.43628906), 'rotation':(-0.622131, -90.073242, -0.635773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.53757812, 1672.7657812500001, 166.49669922), 'rotation':(-0.622131, -90.073242, -0.635773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.55320312, 1683.83375, 166.61798828), 'rotation':(-0.628754, -90.072876, -0.64267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.82226562, 1790.69351562, 167.80066406000003), 'rotation':(0.632059, 89.92717, 0.618231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.72828125, 1797.2459374999999, 167.87294922), 'rotation':(0.627804, 89.927086, 0.61415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2486.80347656, 1777.29882812, 167.65240234), 'rotation':(0.634053, 89.926292, 0.620148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.79566406, 1771.74109375, 167.59089844), 'rotation':(0.634053, 89.926292, 0.620148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.78003906, 1760.62546875, 167.46779297), 'rotation':(0.634723, 89.926537, 0.620779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.74878906, 1738.39453125, 167.22087890999998), 'rotation':(0.636642, 89.925644, 0.622625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.74097656, 1732.83703125, 167.15914062), 'rotation':(0.636662, 89.92804, 0.622626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.62183594, 1732.82679688, 167.15914062), 'rotation':(-0.636627, -90.074341, -0.650909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.62964844, 1738.384375, 167.22089843999998), 'rotation':(-0.636688, -90.07196, -0.65094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.63746094, 1743.94234375, 167.28267577999998), 'rotation':(-0.636627, -90.074341, -0.650909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.65308594, 1755.05773438, 167.40615234), 'rotation':(-0.636078, -90.073425, -0.650299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.66089844, 1760.61546875, 167.4678125), 'rotation':(-0.636078, -90.073425, -0.650299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.67625, 1771.7309375, 167.59089844), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.6840625, 1777.28867188, 167.65242188), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.6996875, 1788.40414062, 167.77544922), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.75902344, 1793.95945312, 167.83681640999998), 'rotation':(-0.634064, -90.073669, -0.648224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.85082031, 1843.0080468800002, 168.36923828), 'rotation':(0.614369, 89.925415, 0.601287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.93457031, 1870.8157812499999, 168.66310547), 'rotation':(0.593612, 89.925804, 0.581418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.95019531, 1881.9407031199999, 168.77835938), 'rotation':(0.589896, 89.925476, 0.577852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.9409375, 1887.50171875, 168.83587891), 'rotation':(0.589896, 89.925476, 0.577852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.8471875, 1900.8282812500001, 168.97150391), 'rotation':(0.567923, 89.925041, 0.556755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.89210938, 1837.4353125, 168.30931640999998), 'rotation':(-0.61731, -90.074402, -0.630737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.82105469, 1842.9967968800001, 168.36923828), 'rotation':(-0.61731, -90.072876, -0.630737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.83105469, 1881.93203125, 168.77837891), 'rotation':(-0.593597, -90.074188, -0.606018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.92652344, 1893.0548437500001, 168.89300781000003), 'rotation':(-0.589874, -90.074493, -0.602142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.98558594, 1899.79796875, 168.96126952999998), 'rotation':(-0.582581, -90.074646, -0.594513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.9396875, 1930.81726562, 169.26294922), 'rotation':(0.549393, 90.632812, 0.538924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2486.61816406, 1941.96984375, 169.36742188), 'rotation':(0.506288, 91.972, 0.497402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2485.8049218799997, 1958.70273438, 169.50408202999998), 'rotation':(0.421272, 93.823685, 0.415111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2484.42675781, 1975.40273438, 169.61542968999998), 'rotation':(0.354125, 95.942574, 0.349767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2483.84449219, 1980.94679688, 169.64974609), 'rotation':(0.347657, 96.479561, 0.343463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2482.63476562, 1992.0193749999999, 169.71240234), 'rotation':(0.281493, 97.864281, 0.278739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.86914062, 1931.1071875, 169.26501953), 'rotation':(-0.536255, -89.654449, -0.546356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.7846875, 1936.64734375, 169.31693359000002), 'rotation':(-0.530426, -88.821777, -0.540314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2494.640625, 1942.19875, 169.36720703), 'rotation':(-0.506836, -88.295349, -0.515869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2494.16648438, 1953.2967187499999, 169.45929688), 'rotation':(-0.446991, -86.972412, -0.454041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2493.83863281, 1958.8483593800001, 169.50134766), 'rotation':(-0.423065, -86.439209, -0.429352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2493.4475, 1964.3939062499999, 169.54044922), 'rotation':(-0.399536, -85.911377, -0.405121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2492.99804688, 1969.92539062, 169.576875), 'rotation':(-0.363983, -85.119476, -0.368622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2492.48585938, 1975.45859375, 169.61089843999997), 'rotation':(-0.346252, -84.593323, -0.350433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2491.9142968799997, 1980.9728906199998, 169.64453125), 'rotation':(-0.345886, -83.793488, -0.350067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2489.98265625, 1997.4719531199999, 169.73371093999998), 'rotation':(-0.274933, -82.135223, -0.277588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.77954102, 1318.23621094, 169.46904297), 'rotation':(0.331599, 90.098579, 0.32778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.76977539, 1323.83044922, 169.50121094), 'rotation':(0.338456, 90.101265, 0.334486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.72167969, 1351.80210938, 169.67253906000002), 'rotation':(0.372559, 90.101677, 0.367748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.71191406, 1357.39613281, 169.70890625), 'rotation':(0.3762, 90.099442, 0.371272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.70263672, 1362.99070312, 169.74564453), 'rotation':(0.380141, 90.102409, 0.375125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.68334961, 1374.17921875, 169.81992188), 'rotation':(0.388146, 90.100624, 0.382907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.6640625, 1385.3671875, 169.89644531000002), 'rotation':(0.40406, 90.100861, 0.398372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.63525391, 1402.14992188, 170.01552734), 'rotation':(0.415474, 90.1017, 0.409487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.62573242, 1407.74367188, 170.05609375), 'rotation':(0.415303, 90.098938, 0.409312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.50610352, 1407.76039062, 170.05611327999998), 'rotation':(-0.415466, -89.898285, -0.421539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.515625, 1402.16675781, 170.01554688), 'rotation':(-0.411804, -89.898865, -0.417755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.53491211, 1390.97789062, 169.93564453), 'rotation':(-0.396027, -89.899231, -0.40155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.56347656, 1374.19566406, 169.81996094), 'rotation':(-0.380127, -89.899475, -0.385223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.57324219, 1368.60144531, 169.78261719), 'rotation':(-0.376221, -89.898743, -0.381165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.58276367, 1363.00683594, 169.74564453), 'rotation':(-0.376221, -89.898743, -0.381165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.59228516, 1357.41234375, 169.70894531000002), 'rotation':(-0.372589, -89.898285, -0.377441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.60180664, 1351.81824219, 169.67257812), 'rotation':(-0.365906, -89.901001, -0.370575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.61157227, 1346.22398438, 169.63689452999998), 'rotation':(-0.359009, -89.898499, -0.363525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.640625, 1329.44042969, 169.53408202999998), 'rotation':(-0.33847, -89.898712, -0.342468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.67895508, 1307.06347656, 169.40609375), 'rotation':(-0.32135, -89.8992, -0.324982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.51220703, 1474.0006250000001, 170.57027344), 'rotation':(0.481399, 90.101082, 0.473354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.50268555, 1479.59875, 170.61654297), 'rotation':(0.481399, 90.101082, 0.473354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.49316406, 1485.19664062, 170.66359375), 'rotation':(0.491036, 90.102661, 0.482655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.47387695, 1496.39292969, 170.75902344), 'rotation':(0.495783, 90.104462, 0.487253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.46411133, 1501.9913281200002, 170.80732422), 'rotation':(0.495708, 90.102058, 0.487197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.42578125, 1524.3836718799998, 171.00386719), 'rotation':(0.515925, 90.101906, 0.50669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.40649414, 1535.57960938, 171.10490234), 'rotation':(0.52488, 90.102058, 0.515313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.39697266, 1541.1775, 171.15611328), 'rotation':(0.529258, 90.102135, 0.519548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.28735352, 1535.59742188, 171.10494140999998), 'rotation':(-0.520142, -89.89801, -0.529663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.30639648, 1524.40148438, 171.00390625), 'rotation':(-0.511383, -89.898193, -0.520569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.33496094, 1507.60742188, 170.85589843999998), 'rotation':(-0.495728, -89.897949, -0.504364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.37353516, 1485.21398438, 170.66363281000002), 'rotation':(-0.481384, -89.898926, -0.489532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.38305664, 1479.61597656, 170.61658203), 'rotation':(-0.471924, -89.897644, -0.479767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.46606445, 1448.6221875, 170.36542968999998), 'rotation':(-0.453857, -89.898682, -0.46106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.33154297, 1579.4096875, 171.51480468999998), 'rotation':(0.557541, 90.104034, 0.54678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.32177734, 1584.99839844, 171.56886719), 'rotation':(0.557541, 90.104034, 0.54678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.31225586, 1590.58691406, 171.62326172000002), 'rotation':(0.561674, 90.10321, 0.550755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.2644043, 1618.53050781, 171.89820312), 'rotation':(0.569221, 90.103195, 0.557992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.25488281, 1624.11902344, 171.95373047), 'rotation':(0.572158, 90.103264, 0.560818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.24707031, 1629.70851562, 172.00953125), 'rotation':(0.575198, 90.105049, 0.563735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.2355957, 1635.2962499999999, 172.06546875), 'rotation':(0.575198, 90.105049, 0.563735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.22607422, 1640.88476562, 172.1215625), 'rotation':(0.57683, 90.102722, 0.565301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.20703125, 1652.06273438, 172.23445312), 'rotation':(0.584651, 90.10421, 0.572824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.1875, 1663.23984375, 172.34912109), 'rotation':(0.595388, 90.104424, 0.583123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.17797852, 1668.82859375, 172.40720703), 'rotation':(0.600469, 90.10453, 0.58797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.16845703, 1674.41710938, 172.46582031000003), 'rotation':(0.605838, 90.10466, 0.593115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.15893555, 1680.00570312, 172.52494141), 'rotation':(0.61122, 90.104774, 0.598291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.14916992, 1685.5944531199998, 172.58455078), 'rotation':(0.616418, 90.104866, 0.603263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.00146484, 1702.38546875, 172.76558594), 'rotation':(-0.619141, -89.895355, -0.632629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.02050781, 1691.2077343800001, 172.64478516), 'rotation':(-0.616425, -89.895142, -0.629822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.03979492, 1680.0306249999999, 172.52505859000001), 'rotation':(-0.605835, -89.895355, -0.618744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.06835938, 1663.2646875, 172.34923827999998), 'rotation':(-0.589874, -89.895691, -0.602112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.078125, 1657.6759375000001, 172.29164062), 'rotation':(-0.584656, -89.895782, -0.59668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2888.08764648, 1652.08742188, 172.23455077999998), 'rotation':(-0.579437, -89.895874, -0.591248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.11645508, 1635.32007812, 172.06556641), 'rotation':(-0.572174, -89.894989, -0.583679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.12597656, 1629.73144531, 172.00960938), 'rotation':(-0.572174, -89.894989, -0.583679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2888.14526367, 1618.55445312, 171.89832031000003), 'rotation':(-0.566071, -89.896851, -0.577332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.93579102, 1740.66171875, 173.17923828), 'rotation':(-0.619049, -89.894409, -0.632538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.88769531, 1768.72875, 173.48373047), 'rotation':(-0.624908, -89.894989, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.87817383, 1774.34226562, 173.54511718999998), 'rotation':(-0.624908, -89.894989, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.84936523, 1791.18234375, 173.72976562), 'rotation':(-0.62851, -89.894836, -0.642395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.84936523, 1796.79421875, 173.79132812), 'rotation':(-0.628387, -89.894836, -0.642303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.06469727, 1735.03609375, 173.11859375), 'rotation':(0.619136, 90.104073, 0.605865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.05493164, 1740.64953125, 173.17925781000002), 'rotation':(0.619136, 90.104073, 0.605865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.03588867, 1751.87648438, 173.30066406000003), 'rotation':(0.62027, 90.104919, 0.60696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.02612305, 1757.49, 173.36150390999998), 'rotation':(0.622585, 90.104958, 0.609177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2880.01660156, 1763.10351562, 173.42251953), 'rotation':(0.624908, 90.105003, 0.611401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2880.00683594, 1768.71679688, 173.48375), 'rotation':(0.627209, 90.105064, 0.613611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2879.98779297, 1779.94382812, 173.60662109), 'rotation':(0.628487, 90.105148, 0.614817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.97802734, 1785.55726562, 173.66820312), 'rotation':(0.628405, 90.105156, 0.61474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2879.96850586, 1791.17054688, 173.72978516), 'rotation':(0.628405, 90.105156, 0.61474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.88378906, 1840.58359375, 174.27242188), 'rotation':(0.628705, 90.106033, 0.615025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.80493164, 1851.8201562499999, 174.39560547000002), 'rotation':(0.626683, 90.104507, 0.613102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.69091797, 1868.6751562499999, 174.57960938), 'rotation':(0.622988, 90.105896, 0.609554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.68115234, 1874.2932031199998, 174.64068359), 'rotation':(0.621691, 90.097359, 0.608311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2879.59741211, 1885.57226562, 174.76392578), 'rotation':(0.627059, 91.301765, 0.613442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2879.13720703, 1902.48265625, 174.94585938), 'rotation':(0.603789, 93.129616, 0.59117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.8996582, 1846.27609375, 174.33474609), 'rotation':(-0.628723, -89.895447, -0.642639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.88037109, 1857.5378125, 174.45802734), 'rotation':(-0.626678, -89.895477, -0.640503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.81445312, 1863.1647656199998, 174.51941406000003), 'rotation':(-0.624939, -89.894043, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2887.74609375, 1868.79421875, 174.58074219), 'rotation':(-0.624939, -89.894043, -0.638672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2887.39306641, 1896.8759375, 174.88289062), 'rotation':(-0.603546, -87.970642, -0.616364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2874.953125, 1945.20617188, 175.3803125), 'rotation':(0.555813, 98.268021, 0.54512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2874.19702148, 1950.45078125, 175.43162109000002), 'rotation':(0.550773, 98.647171, 0.540273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2873.38134766, 1955.69796875, 175.48226562), 'rotation':(0.54119, 99.410355, 0.531047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2870.75537109, 1971.33773438, 175.62851562), 'rotation':(0.52001, 99.599358, 0.510641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2869.87475586, 1976.54773438, 175.67646484), 'rotation':(0.520016, 99.59951, 0.510646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2868.99414062, 1981.7575781199998, 175.72443359000002), 'rotation':(0.519784, 99.600815, 0.510419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2867.37548828, 1992.20101562, 175.82011719), 'rotation':(0.516711, 99.599762, 0.507449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2866.49462891, 1997.41101562, 175.86777343999998), 'rotation':(0.510113, 99.59996, 0.501098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2878.10351562, 1976.88632812, 175.66705077999998), 'rotation':(-0.52002, -80.398804, -0.52951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2878.88476562, 1971.65054688, 175.61900391), 'rotation':(-0.526093, -80.401428, -0.535828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2881.45727539, 1956.01320312, 175.47324218999998), 'rotation':(-0.537994, -81.353485, -0.548157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2883.00390625, 1945.5788281199998, 175.37322265999998), 'rotation':(-0.552521, -82.492126, -0.563263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3160.40722656, 1309.49841797, 172.73232422), 'rotation':(0.194736, 90.642365, 0.193411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.28051758, 1320.81921875, 172.77082031), 'rotation':(0.196839, 90.640884, 0.195482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.15405273, 1332.1397656200002, 172.80988281), 'rotation':(0.201231, 90.640923, 0.199818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3160.09057617, 1337.80003906, 172.82976562), 'rotation':(0.205343, 90.640953, 0.20388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.96411133, 1349.120625, 172.87021484000002), 'rotation':(0.209748, 90.642403, 0.208214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.64794922, 1377.42234375, 172.97482422000002), 'rotation':(0.216858, 90.639664, 0.215225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.58447266, 1383.08289062, 172.99623047), 'rotation':(0.218614, 90.64225, 0.216965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3159.45800781, 1394.4034375, 173.03966797), 'rotation':(0.222487, 90.642303, 0.220765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3159.33129883, 1405.72386719, 173.08390625), 'rotation':(0.226516, 90.642311, 0.224739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3159.078125, 1428.36535156, 173.17416015999999), 'rotation':(0.233524, 90.64119, 0.231621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.95166016, 1439.68601562, 173.22048827999998), 'rotation':(0.237472, 90.64122, 0.235514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.76171875, 1456.66699219, 173.2915625), 'rotation':(0.243537, 90.642624, 0.241475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3158.69848633, 1462.32714844, 173.315625), 'rotation':(0.245675, 90.64167, 0.243576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.63500977, 1467.9876562499999, 173.33974609), 'rotation':(0.245675, 90.64167, 0.243576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.50854492, 1479.308125, 173.38857422), 'rotation':(0.250162, 90.641701, 0.247989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.12890625, 1513.2698828100001, 173.54056641), 'rotation':(0.263481, 90.642578, 0.261064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3158.06567383, 1518.93015625, 173.56650391), 'rotation':(0.263481, 90.642578, 0.261064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3158.00219727, 1524.5903125, 173.59253906), 'rotation':(0.268085, 90.641144, 0.265583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.8125, 1541.5711718799998, 173.67248047), 'rotation':(0.277176, 90.641235, 0.274513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3154.85083008, 1806.39023438, 175.22439452999998), 'rotation':(0.408561, 90.643074, 0.402769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.22436523, 1772.98828125, 174.99089844), 'rotation':(0.391199, 90.641205, 0.385885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.28662109, 1767.4216406199998, 174.95333984), 'rotation':(0.38719, 90.643799, 0.381978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.59790039, 1739.5861718800002, 174.77039062), 'rotation':(0.369288, 90.643478, 0.364554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3153.63134766, 1905.6374218800001, 175.99242188), 'rotation':(0.477772, 90.645645, 0.469857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3153.77905273, 1900.07296875, 175.94599609), 'rotation':(0.477772, 90.643997, 0.469862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3153.86572266, 1894.5080468800002, 175.89974609), 'rotation':(0.475299, 90.643433, 0.467472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3154.05249023, 1877.80765625, 175.76371093999998), 'rotation':(0.4603, 90.645729, 0.452945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3154.42578125, 1844.40585938, 175.50414062), 'rotation':(0.43746, 90.644157, 0.430825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3154.48803711, 1838.8392187499999, 175.461875), 'rotation':(0.435247, 90.644089, 0.428684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2469.88039062, 1425.38695312, 163.70475586), 'rotation':(1.173303, 0.728776, 1.125953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2447.12109375, 1425.1071875, 163.23079102), 'rotation':(1.204374, 0.730066, 1.154497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2441.43117188, 1425.03722656, 163.11035156), 'rotation':(1.212085, 0.73039, 1.161592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2430.05152344, 1424.89734375, 162.86867188), 'rotation':(1.216006, 0.729766, 1.165173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2418.6721093799997, 1424.75734375, 162.62550781), 'rotation':(1.229694, 0.731072, 1.177726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2412.98242188, 1424.68738281, 162.50262695), 'rotation':(1.239044, 0.731474, 1.186282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2407.29273438, 1424.61742188, 162.37888672), 'rotation':(1.24808, 0.73187, 1.194553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2395.91359375, 1424.4774218799998, 162.13007812), 'rotation':(1.252698, 0.731392, 1.198779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2356.0857031200003, 1423.9876562499999, 161.25287109), 'rotation':(1.273509, 0.732964, 1.217795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2316.256875, 1423.4978125, 160.36401367), 'rotation':(1.281193, 0.733341, 1.224821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2293.4965625, 1423.21800781, 159.85418945), 'rotation':(1.28148, 0.732714, 1.225076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2287.806875, 1423.14796875, 159.72702148), 'rotation':(1.279028, 0.733917, 1.222833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2282.11671875, 1423.07800781, 159.60011719), 'rotation':(1.276583, 0.732498, 1.220589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2276.42671875, 1423.00804688, 159.4734668), 'rotation':(1.273796, 0.733682, 1.218057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2253.66601562, 1422.72804688, 158.96958984), 'rotation':(1.263646, 0.733233, 1.208793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2247.97609375, 1422.65808594, 158.84413086), 'rotation':(1.26254, 0.731468, 1.207777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2653.02929688, 1427.63890625, 167.07583984000001), 'rotation':(0.903327, 0.718963, 0.875171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2647.46386719, 1427.57054688, 166.98541016), 'rotation':(0.934035, 0.719927, 0.903946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2608.49925781, 1427.0915625, 166.33361327999998), 'rotation':(0.974484, 0.720835, 0.941745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2597.36839844, 1426.95460938, 166.14068359), 'rotation':(0.994482, 0.722632, 0.960405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2575.10472656, 1426.68089844, 165.74447265999999), 'rotation':(1.033715, 0.722118, 0.996907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2552.84132812, 1426.4071093799998, 165.33478516), 'rotation':(1.067511, 0.724705, 1.028271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2547.27539062, 1426.33863281, 165.23019531000003), 'rotation':(1.075823, 0.724984, 1.035967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2541.70945312, 1426.2701562500001, 165.12474609), 'rotation':(1.084224, 0.725332, 1.043753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2530.57765625, 1426.13316406, 164.91185547), 'rotation':(1.096997, 0.726679, 1.055557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2519.44628906, 1425.99632812, 164.69796875), 'rotation':(1.102201, 0.725948, 1.060377), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2713.42164062, 1428.38160156, 167.99746094), 'rotation':(0.820572, 0.716795, 0.797304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2730.10863281, 1428.5867968799998, 168.23630859000002), 'rotation':(0.809534, 0.715987, 0.786895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2741.234375, 1428.72351562, 168.39292969), 'rotation':(0.794863, 0.715577, 0.773035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2757.92164062, 1428.92871094, 168.62210938), 'rotation':(0.772576, 0.714934, 0.751955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2763.48460938, 1428.9971875, 168.69703125), 'rotation':(0.765364, 0.714775, 0.745116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2769.04736328, 1429.06554688, 168.77126952999998), 'rotation':(0.761696, 0.713903, 0.741646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2774.609375, 1429.13390625, 168.84511719), 'rotation':(0.758629, 0.714615, 0.738736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2780.17261719, 1429.20238281, 168.91855468999998), 'rotation':(0.752093, 0.714442, 0.732552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2785.73535156, 1429.27074219, 168.99132812), 'rotation':(0.745911, 0.714281, 0.726679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2807.98779297, 1429.54445312, 169.27591797000002), 'rotation':(0.714281, 0.713474, 0.696643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2819.11328125, 1429.68128906, 169.41458984000002), 'rotation':(0.711248, 0.713525, 0.693754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2824.67675781, 1429.74964844, 169.48363281000002), 'rotation':(0.7059, 0.713323, 0.68866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2830.23949219, 1429.818125, 169.55220702999998), 'rotation':(0.695115, 0.713037, 0.678404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2835.8025, 1429.88648438, 169.62021484000002), 'rotation':(0.695115, 0.713037, 0.678404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2863.61474609, 1430.3303125, 169.95011719), 'rotation':(0.66845, 0.712084, 0.652992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2470.24121094, 1821.401875, 167.58382812), 'rotation':(1.448307, 0.495441, 1.376394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2444.44605469, 1821.06546875, 166.91427734), 'rotation':(1.498946, 0.498394, 1.42198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2438.78296875, 1821.0202343800001, 166.76525390999998), 'rotation':(1.512019, 0.499087, 1.433703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2416.13523438, 1820.83859375, 166.15558593999998), 'rotation':(1.563621, 0.501859, 1.479929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.47265625, 1820.7932031199998, 165.99972656000003), 'rotation':(1.576346, 0.502563, 1.491298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2404.8122656200003, 1820.74789062, 165.84253906), 'rotation':(1.589494, 0.503314, 1.503021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2393.4865625, 1820.65710938, 165.52673828), 'rotation':(1.595833, 0.50348, 1.508679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2382.1640625, 1820.56640625, 165.20988281), 'rotation':(1.603291, 0.503525, 1.515341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2370.839375, 1820.47570312, 164.88818359), 'rotation':(1.633201, 0.506324, 1.541967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2336.86960938, 1820.2033593800002, 163.90568359), 'rotation':(1.663732, 0.507136, 1.569077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2325.54539062, 1820.1125781199999, 163.57482421999998), 'rotation':(1.674004, 0.507734, 1.5782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2319.88328125, 1820.0671093800001, 163.40852539), 'rotation':(1.679414, 0.508052, 1.582985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2308.5590625, 1819.9763281199998, 163.07416016), 'rotation':(1.695089, 0.510374, 1.59688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2302.89914062, 1819.93101562, 162.90633789), 'rotation':(1.69776, 0.509189, 1.599242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2285.9114062500003, 1819.79476562, 162.40293945), 'rotation':(1.693593, 0.508979, 1.595565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2280.2487499999997, 1819.74953125, 162.23543945), 'rotation':(1.693593, 0.508979, 1.595565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2268.9240625, 1819.65867188, 161.90085938), 'rotation':(1.690526, 0.508815, 1.592843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2263.26171875, 1819.61328125, 161.73379882999998), 'rotation':(1.688887, 0.5087, 1.591389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2257.59914062, 1819.56789062, 161.56686523), 'rotation':(1.687323, 0.509757, 1.589992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2246.27367188, 1819.4771875000001, 161.23334961), 'rotation':(1.685028, 0.509431, 1.58797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2251.8290625, 1811.63953125, 161.39504883), 'rotation':(-1.684967, -179.490585, -1.786407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2263.15429688, 1811.7303124999999, 161.72875977), 'rotation':(-1.687378, -179.490204, -1.789124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2268.816875, 1811.77578125, 161.89583984), 'rotation':(-1.688873, -179.491287, -1.790802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2274.47898438, 1811.82117188, 162.06303711), 'rotation':(-1.69046, -179.490051, -1.792572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2280.1415625, 1811.8664843800002, 162.23039062), 'rotation':(-1.6922, -179.491089, -1.794495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2291.46632812, 1811.9572656199998, 162.56553711), 'rotation':(-1.693665, -179.490982, -1.796173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2297.12890625, 1812.00265625, 162.73333984), 'rotation':(-1.695312, -179.489746, -1.798035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2302.79101562, 1812.048125, 162.90125), 'rotation':(-1.696899, -179.490814, -1.799805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2308.453125, 1812.0935156199998, 163.06914061999998), 'rotation':(-1.697754, -179.489487, -1.800751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2314.11546875, 1812.13890625, 163.23665039), 'rotation':(-1.695099, -179.491013, -1.79776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2325.43992188, 1812.2258593800002, 163.56987305), 'rotation':(-1.679413, -179.491959, -1.780182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2331.10203125, 1812.26648438, 163.73561523), 'rotation':(-1.674011, -179.490875, -1.774109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2365.07640625, 1812.58046875, 164.72060547), 'rotation':(-1.655762, -179.492813, -1.753693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2382.06347656, 1812.7165625, 165.20525390999998), 'rotation':(-1.618347, -179.494522, -1.711853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2387.72558594, 1812.7619531199998, 165.36412109), 'rotation':(-1.603363, -179.495361, -1.695099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2404.71460938, 1812.8982031199998, 165.83806640999998), 'rotation':(-1.595825, -179.496521, -1.686707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2410.3784375, 1812.94359375, 165.99539062), 'rotation':(-1.589417, -179.496704, -1.679565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2421.7028906200003, 1813.0344531199999, 166.30578125), 'rotation':(-1.56369, -179.498108, -1.650909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2427.36765625, 1813.07984375, 166.45902343999998), 'rotation':(-1.55072, -179.49884, -1.636475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2433.03050781, 1813.125, 166.61080077999998), 'rotation':(-1.537659, -179.499527, -1.621948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2455.68433594, 1813.30679688, 167.20597656), 'rotation':(-1.492584, -179.501709, -1.57196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2461.349375, 1813.18203125, 167.35339843999998), 'rotation':(-1.492432, -179.501709, -1.571777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2472.67726562, 1813.2728124999999, 167.64380859000002), 'rotation':(-1.466003, -179.503677, -1.542572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2510.77101562, 1813.7153125, 168.57300781), 'rotation':(-1.371948, -179.507797, -1.438904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2521.848125, 1813.8040624999999, 168.83238281), 'rotation':(-1.336761, -179.509491, -1.400299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2532.92382812, 1813.8928125, 169.08488281), 'rotation':(-1.301636, -179.511108, -1.361816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2538.46265625, 1813.93710938, 169.20861327999998), 'rotation':(-1.284058, -179.511917, -1.342621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2549.54078125, 1814.02609375, 169.45117188), 'rotation':(-1.248932, -179.513474, -1.304291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2566.15773438, 1814.1594531199999, 169.80662109000002), 'rotation':(-1.213043, -179.514725, -1.265289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2571.69703125, 1814.2037500000001, 169.92177734), 'rotation':(-1.195129, -179.515442, -1.245819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2577.23558594, 1814.24820312, 170.03517578), 'rotation':(-1.177124, -179.516205, -1.226288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2582.77492188, 1814.2925, 170.14679688), 'rotation':(-1.159149, -179.518204, -1.206787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2604.9340625, 1814.46695312, 170.57732422), 'rotation':(-1.096191, -179.519913, -1.138763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2610.47363281, 1814.50539062, 170.68195312), 'rotation':(-1.096191, -179.519913, -1.138763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2616.01269531, 1814.57703125, 170.78607422000002), 'rotation':(-1.07843, -179.520645, -1.119629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2627.09226562, 1814.680625, 170.98685547000002), 'rotation':(-1.042969, -179.521225, -1.081482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2632.6330468799997, 1814.72507812, 171.08433594), 'rotation':(-1.007568, -179.523209, -1.043488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2638.150625, 1822.6174218800002, 171.18068359), 'rotation':(0.972154, 0.475558, 0.939584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2632.61085938, 1822.573125, 171.08505859000002), 'rotation':(0.972154, 0.475558, 0.939584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2627.0705468799997, 1822.52867188, 170.98757812), 'rotation':(1.007569, 0.477503, 0.97258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2604.91578125, 1822.35117188, 170.57818359), 'rotation':(1.078466, 0.479368, 1.038418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2599.3752343799997, 1822.306875, 170.47212890999998), 'rotation':(1.096177, 0.480901, 1.054808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2593.83714844, 1822.2624218800001, 170.36558594), 'rotation':(1.105159, 0.479641, 1.063113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2577.2185156200003, 1822.129375, 170.03611328), 'rotation':(1.159145, 0.483067, 1.112917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2571.68285156, 1822.085, 169.9228125), 'rotation':(1.177142, 0.483799, 1.129479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2549.5278125, 1821.90734375, 169.45226562), 'rotation':(1.240123, 0.486014, 1.187269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2543.99046875, 1821.8630468800002, 169.33175781000003), 'rotation':(1.248921, 0.486531, 1.19532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2538.45117188, 1821.81875, 169.20974609), 'rotation':(1.266488, 0.487303, 1.211383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2532.91210938, 1821.774375, 169.08603516), 'rotation':(1.284048, 0.488086, 1.227426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2527.37328125, 1821.73, 168.960625), 'rotation':(1.301629, 0.488882, 1.243442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2521.83910156, 1821.68570312, 168.83363281), 'rotation':(1.319251, 0.48971, 1.259494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2676.10863281, 1823.0228124999999, 171.79873047), 'rotation':(0.871136, 0.471978, 0.844939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2681.640625, 1822.97804688, 171.88287109), 'rotation':(0.846096, 0.472108, 0.821379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.1696875, 1823.01023438, 171.96484375), 'rotation':(0.82092, 0.471374, 0.797649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2709.29761719, 1823.1876562500001, 172.28037109000002), 'rotation':(0.784324, 0.47004, 0.763069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2731.42503906, 1823.36484375, 172.57353516), 'rotation':(0.720619, 0.468345, 0.702659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2736.95777344, 1823.40921875, 172.64267578), 'rotation':(0.704657, 0.467965, 0.687482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2770.15308594, 1823.6753125, 173.03337890999998), 'rotation':(0.63087, 0.46647, 0.617105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2781.21800781, 1823.7640625, 173.15335938), 'rotation':(0.602313, 0.465835, 0.589752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2786.75097656, 1823.80820312, 173.21111327999998), 'rotation':(0.588332, 0.465567, 0.576346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2792.28394531, 1823.8525, 173.26734375), 'rotation':(0.573975, 0.463894, 0.562565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2836.54760742, 1824.2116406199998, 173.68267577999998), 'rotation':(0.484008, 0.462954, 0.475877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2842.08056641, 1824.2578125, 173.72894531000003), 'rotation':(0.471222, 0.464079, 0.463519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2864.14770508, 1824.558125, 173.90679688), 'rotation':(0.436763, 0.462127, 0.43014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2854.83789062, 1816.473125, 173.83226562), 'rotation':(-0.464783, -179.537109, -0.472382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2862.67822266, 1816.42773438, 173.89460938), 'rotation':(-0.455505, -179.536835, -0.462769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2842.16113281, 1816.3715625, 173.72910156), 'rotation':(-0.483978, -179.53569, -0.492218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2808.96533203, 1816.1053124999999, 173.43160156000002), 'rotation':(-0.560364, -179.534317, -0.571411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2803.43310547, 1816.06101562, 173.37738281000003), 'rotation':(-0.566833, -179.5354, -0.578125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2797.89964844, 1816.01671875, 173.32263672000002), 'rotation':(-0.573975, -179.534729, -0.585571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2786.83472656, 1815.92796875, 173.21130859000002), 'rotation':(-0.602356, -179.534134, -0.615112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2781.30199219, 1815.8835156199998, 173.15355469), 'rotation':(-0.616699, -179.533829, -0.630096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2753.6428125, 1815.66210938, 172.84238281), 'rotation':(-0.680664, -179.532791, -0.696991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2742.57835938, 1815.57335938, 172.71044922000002), 'rotation':(-0.704651, -179.532028, -0.722137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2737.04613281, 1815.5290625, 172.64296875), 'rotation':(-0.720642, -179.531631, -0.738953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(2714.91992188, 1815.3517187500001, 172.35658203), 'rotation':(-0.784332, -179.529953, -0.80603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2703.85742188, 1815.26296875, 172.20335938), 'rotation':(-0.808319, -179.530121, -0.83136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2687.26195312, 1815.13, 171.96529297), 'rotation':(-0.8461, -179.527893, -0.871368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(2678.00074219, 1814.98398438, 171.82654297000002), 'rotation':(-0.89624, -179.526352, -0.924622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3018.52636719, 1825.66585938, 174.81632812), 'rotation':(0.258448, 0.460326, 0.256128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3012.98657227, 1825.62148438, 174.79107422), 'rotation':(0.258448, 0.460326, 0.256128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3001.90795898, 1825.53273438, 174.7390625), 'rotation':(0.27247, 0.459666, 0.269897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2990.8293457, 1825.44398438, 174.68603516), 'rotation':(0.272497, 0.46099, 0.269908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2974.21069336, 1825.31070312, 174.60306641), 'rotation':(0.290426, 0.460366, 0.287483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.6706543, 1825.26648438, 174.57382812), 'rotation':(0.302386, 0.461214, 0.299198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2957.59130859, 1825.17757812, 174.51382812), 'rotation':(0.31425, 0.460612, 0.310824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(2952.05249023, 1825.13320312, 174.48310547), 'rotation':(0.32035, 0.461612, 0.316781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2946.51269531, 1825.08875, 174.45214843999997), 'rotation':(0.320199, 0.461631, 0.316641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2907.73828125, 1824.7778125, 174.21583984), 'rotation':(0.377429, 0.462332, 0.372474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2904.72973633, 1816.8674218800002, 174.19556641), 'rotation':(-0.385651, -179.537857, -0.390839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(2918.87524414, 1816.98648438, 174.28761719), 'rotation':(-0.377441, -179.538376, -0.382446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2924.4152832, 1817.03085938, 174.32255859), 'rotation':(-0.361084, -179.538574, -0.365631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2946.5715332, 1817.20851562, 174.45210938), 'rotation':(-0.3284, -179.538254, -0.332184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(2957.65063477, 1817.29734375, 174.51380859), 'rotation':(-0.320374, -179.538361, -0.323975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2968.72998047, 1817.3860937499999, 174.57380859), 'rotation':(-0.31427, -179.539383, -0.317719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(2996.42749023, 1817.60804688, 174.71267577999998), 'rotation':(-0.278534, -179.539749, -0.281281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3007.5065918, 1817.696875, 174.76517578), 'rotation':(-0.272491, -179.539001, -0.275085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3013.04663086, 1817.74132812, 174.79105468999998), 'rotation':(-0.267853, -179.539566, -0.270386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3018.58642578, 1817.7857812500001, 174.81630859), 'rotation':(-0.267853, -179.539566, -0.270386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3040.74536133, 1817.96335938, 174.91259766), 'rotation':(-0.239624, -179.539825, -0.241638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3046.28222656, 1817.9641406199999, 174.93560547), 'rotation':(-0.239624, -179.539825, -0.241638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3089.88696289, 1818.3318749999999, 175.10728516), 'rotation':(-0.210388, -179.540527, -0.211945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3101.03198242, 1818.44679688, 175.14789062), 'rotation':(-0.20813, -179.539505, -0.209656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3112.17871094, 1818.53609375, 175.18789062), 'rotation':(-0.203522, -179.540329, -0.204987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3117.75244141, 1818.58070312, 175.20748047), 'rotation':(-0.200562, -179.540329, -0.201965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3123.32592773, 1818.62539062, 175.22673827999998), 'rotation':(-0.197418, -179.539108, -0.198761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3128.89916992, 1818.67007812, 175.24568359), 'rotation':(-0.194427, -179.540359, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3128.83691406, 1826.5501562499999, 175.24570312), 'rotation':(0.191109, 0.459584, 0.189844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3123.26318359, 1826.50546875, 175.22673827999998), 'rotation':(0.194428, 0.460882, 0.193112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3112.11645508, 1826.41625, 175.18789062), 'rotation':(0.200541, 0.459649, 0.199145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3084.25146484, 1826.28640625, 175.08666015999998), 'rotation':(0.210383, 0.460758, 0.208843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3178.05640625, 1818.93445312, 175.40214844), 'rotation':(-0.172729, -179.540405, -0.173767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3194.72900391, 1819.19765625, 175.450625), 'rotation':(-0.16449, -179.53952, -0.165436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3200.28710938, 1819.2421875, 175.46638672), 'rotation':(-0.162506, -179.540894, -0.163422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3211.40257812, 1819.3313281199999, 175.49759766), 'rotation':(-0.158386, -179.540237, -0.159271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3216.96044922, 1819.37585938, 175.51269531000003), 'rotation':(-0.158386, -179.540237, -0.159271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3222.51855469, 1819.42039062, 175.52724609), 'rotation':(-0.149933, -179.540314, -0.150726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3239.19261719, 1819.5540624999999, 175.56761719), 'rotation':(-0.133484, -179.540375, -0.134094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3244.74878906, 1819.55507812, 175.58023438), 'rotation':(-0.129089, -179.539963, -0.1297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3250.30712891, 1819.5434375, 175.59277343999997), 'rotation':(-0.129242, -179.541046, -0.129822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3255.80273438, 1827.6975, 175.6053125), 'rotation':(0.129234, 0.460039, 0.128648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3250.24267578, 1827.62320312, 175.59277343999997), 'rotation':(0.129234, 0.460039, 0.128648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3239.13011719, 1827.4342968800001, 175.56761719), 'rotation':(0.129111, 0.458948, 0.128517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3228.01416016, 1827.34523438, 175.54115234), 'rotation':(0.133482, 0.459629, 0.132861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3216.89820312, 1827.25609375, 175.51269531000003), 'rotation':(0.149943, 0.459709, 0.149165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3211.34007812, 1827.2115625000001, 175.49759766), 'rotation':(0.149943, 0.459709, 0.149165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3200.22484375, 1827.12242188, 175.46640625), 'rotation':(0.162504, 0.460165, 0.161575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3194.66675781, 1827.07773438, 175.450625), 'rotation':(0.162483, 0.460145, 0.161576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3189.10986328, 1827.07289062, 175.43470703), 'rotation':(0.164491, 0.459553, 0.163542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3183.55199219, 1827.07617188, 175.41855468999998), 'rotation':(0.164491, 0.459553, 0.163542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3177.9921875, 1827.07375, 175.40214844), 'rotation':(0.168549, 0.459579, 0.167557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.06274414, 1547.89429688, 172.86677734), 'rotation':(-0.37442, -89.218597, -0.379333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.13867188, 1542.3211718799998, 172.83033203), 'rotation':(-0.372528, -89.219147, -0.377411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.21435547, 1536.7474218799998, 172.79404297000002), 'rotation':(-0.368713, -89.219177, -0.373474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.44165039, 1520.02757812, 172.68710938), 'rotation':(-0.357056, -89.21933, -0.361511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.59301758, 1508.88085938, 172.61757812), 'rotation':(-0.353241, -89.21936, -0.357574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.66894531, 1503.30761719, 172.58335938), 'rotation':(-0.349396, -89.219421, -0.353668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3068.74462891, 1497.73425781, 172.54949219), 'rotation':(-0.345398, -89.219482, -0.349579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.8203125, 1492.16039062, 172.51591797), 'rotation':(-0.342926, -89.219604, -0.347046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3068.97192383, 1481.0134375, 172.44919922), 'rotation':(-0.340607, -89.218628, -0.344696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.04760742, 1475.44019531, 172.41611328), 'rotation':(-0.33606, -89.221283, -0.340027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3069.19897461, 1464.29332031, 172.35134766), 'rotation':(-0.326935, -89.218781, -0.330688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.50195312, 1441.99964844, 172.22548827999998), 'rotation':(-0.314453, -89.219299, -0.317932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.57763672, 1436.42625, 172.1946875), 'rotation':(-0.314453, -89.219299, -0.317932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3069.72924805, 1425.27820312, 172.13396484), 'rotation':(-0.306458, -89.22113, -0.309753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3070.10766602, 1397.41175781, 171.98800781000003), 'rotation':(-0.292969, -89.219849, -0.29599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3070.25927734, 1386.26488281, 171.93117188), 'rotation':(-0.286469, -89.221893, -0.289368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3070.63793945, 1358.39769531, 171.79501953), 'rotation':(-0.271973, -89.220703, -0.274567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3070.94091797, 1336.10316406, 171.69109375), 'rotation':(-0.255951, -89.220825, -0.25824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3071.01660156, 1330.52976562, 171.66607422), 'rotation':(-0.251892, -89.220856, -0.254089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3071.09228516, 1324.95642578, 171.64142578), 'rotation':(-0.247803, -89.220886, -0.249939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3071.31933594, 1308.23523438, 171.56957031000002), 'rotation':(-0.241821, -89.219269, -0.243866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3065.94287109, 1703.9296875, 173.99476562), 'rotation':(-0.468597, -89.219666, -0.476318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3066.01904297, 1698.32460938, 173.94890625), 'rotation':(-0.468597, -89.21698, -0.476318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.32763672, 1675.90367188, 173.769375), 'rotation':(-0.437134, -89.218323, -0.443848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3066.3996582, 1670.2961718800002, 173.72714843999998), 'rotation':(-0.418732, -89.217896, -0.424866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.55224609, 1659.08546875, 173.64492188), 'rotation':(-0.41925, -89.219604, -0.425446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.62817383, 1653.48046875, 173.60388672000002), 'rotation':(-0.420502, -89.219574, -0.426697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.7043457, 1647.8751171899999, 173.56271484), 'rotation':(-0.421539, -89.216797, -0.427765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.78051758, 1642.27027344, 173.52142578), 'rotation':(-0.42276, -89.219543, -0.429047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3066.93286133, 1631.0603125, 173.4384375), 'rotation':(-0.426788, -89.218018, -0.433167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3067.3137207, 1603.03367188, 173.23269531000003), 'rotation':(-0.394165, -89.21933, -0.399597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3067.38989258, 1597.426875, 173.19351562), 'rotation':(-0.394165, -89.21933, -0.399597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3067.46606445, 1591.82152344, 173.15494141), 'rotation':(-0.381104, -89.219543, -0.3862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3067.61816406, 1580.6100000000001, 173.080625), 'rotation':(-0.37442, -89.219177, -0.379333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3065.03881836, 1770.4521875, 174.54367188), 'rotation':(-0.482574, -89.216156, -0.490753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3064.85791016, 1791.770625, 174.72695312), 'rotation':(-0.496918, -89.21756, -0.505585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3064.72363281, 1803.2003125, 174.82673828), 'rotation':(-0.500977, -89.217468, -0.509796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3064.05859375, 1842.60070312, 175.17796875), 'rotation':(-0.518219, -89.218964, -0.527649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.98217773, 1848.2267187500001, 175.22931641), 'rotation':(-0.518219, -89.218964, -0.527649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3063.8293457, 1859.47765625, 175.33224609), 'rotation':(-0.524048, -89.217529, -0.533722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.60009766, 1876.3547656199999, 175.48759766), 'rotation':(-0.530762, -89.218506, -0.540649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.52368164, 1881.9803124999999, 175.53994140999998), 'rotation':(-0.533478, -89.215729, -0.543488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3063.14135742, 1910.1086718800002, 175.80580078), 'rotation':(-0.545532, -89.216858, -0.556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.77319336, 1937.2109375, 176.06394531), 'rotation':(-0.545715, -89.21521, -0.556183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.69873047, 1942.69703125, 176.11619141), 'rotation':(-0.545593, -89.217041, -0.556061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.40039062, 1964.6407812500001, 176.32572266), 'rotation':(-0.545593, -89.217041, -0.556061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.2512207, 1975.61289062, 176.43410156000002), 'rotation':(-0.572815, -89.214661, -0.584351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3062.17675781, 1981.09976562, 176.48966797), 'rotation':(-0.58194, -89.216125, -0.593842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3062.10229492, 1986.5853124999999, 176.54541016), 'rotation':(-0.581848, -89.21579, -0.593781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3061.953125, 1997.55679688, 176.65685547), 'rotation':(-0.58197, -89.21579, -0.593903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.18210938, 1436.6673437499999, 176.64849609), 'rotation':(0.600428, 0.468658, 0.587947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3451.71921875, 1436.3884375, 176.34681641), 'rotation':(0.61469, 0.469054, 0.601613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3446.025625, 1436.34253906, 176.28554688), 'rotation':(0.617907, 0.469144, 0.604685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3440.33226562, 1436.29640625, 176.22396484), 'rotation':(0.621055, 0.469192, 0.60771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3434.63867188, 1436.2506250000001, 176.16208984000002), 'rotation':(0.624279, 0.469281, 0.610784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3428.94628906, 1436.20460938, 176.09996094), 'rotation':(0.626438, 0.469986, 0.612851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3423.25242188, 1436.15867188, 176.03763672000002), 'rotation':(0.627421, 0.468634, 0.613798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3417.5590625, 1436.1126562499999, 175.97519531), 'rotation':(0.628432, 0.470005, 0.614758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3406.1721093799997, 1436.02074219, 175.85), 'rotation':(0.630611, 0.470052, 0.616852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3400.47851562, 1435.97472656, 175.78722656000002), 'rotation':(0.631792, 0.47008, 0.617975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3377.70460938, 1435.79089844, 175.53523438), 'rotation':(0.634367, 0.469109, 0.62043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3372.01125, 1435.745, 175.47220703), 'rotation':(0.634361, 0.469824, 0.620427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3366.31761719, 1435.69910156, 175.40904297), 'rotation':(0.635652, 0.469334, 0.621672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3360.62402344, 1435.65308594, 175.34578125), 'rotation':(0.635652, 0.469334, 0.621672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.23730469, 1435.56117188, 175.21917968999998), 'rotation':(0.636908, 0.470286, 0.622867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3326.463125, 1435.37730469, 174.96597656000003), 'rotation':(0.636287, 0.469573, 0.622269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3297.994375, 1435.27699219, 174.65048828), 'rotation':(0.634477, 0.470319, 0.620545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3298.03929688, 1427.1373437500001, 174.65027343999998), 'rotation':(-0.634369, -179.529678, -0.648499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3320.8125, 1427.45070312, 174.90253906), 'rotation':(-0.63504, -179.530457, -0.649231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3326.50585938, 1427.4965625, 174.96574219), 'rotation':(-0.63504, -179.530457, -0.649231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3349.28050781, 1427.6805468799998, 175.21894531), 'rotation':(-0.637024, -179.530563, -0.651306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3372.0544531200003, 1427.864375, 175.47197266), 'rotation':(-0.635651, -179.53067, -0.649872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3389.13476562, 1428.00230469, 175.66109375), 'rotation':(-0.634369, -179.530167, -0.648529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3400.52195312, 1428.09421875, 175.78701172), 'rotation':(-0.632629, -179.529907, -0.646729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3406.2153125, 1428.14015625, 175.84978515999998), 'rotation':(-0.631805, -179.531235, -0.645874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3411.90867188, 1428.18617188, 175.91244140999999), 'rotation':(-0.630615, -179.529953, -0.644623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3417.60230469, 1428.23207031, 175.975), 'rotation':(-0.629456, -179.531326, -0.643372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3423.29589844, 1428.27808594, 176.03742188), 'rotation':(-0.628479, -179.529968, -0.642365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3428.98949219, 1428.32398438, 176.09972656000002), 'rotation':(-0.627411, -179.531357, -0.641266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3434.69800781, 1428.36960938, 176.16203125), 'rotation':(0.0, 179.999985, 0.0), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3440.37597656, 1428.41589844, 176.22375), 'rotation':(-0.624237, -179.530731, -0.63797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3446.06933594, 1428.4617968799998, 176.28533202999998), 'rotation':(-0.621094, -179.530792, -0.634674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3451.76292969, 1428.5078125, 176.34660156), 'rotation':(-0.617889, -179.530853, -0.631348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3463.14992188, 1428.59972656, 176.46820312), 'rotation':(-0.611542, -179.530991, -0.624695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3468.84300781, 1428.645625, 176.52853516), 'rotation':(-0.60849, -179.531082, -0.62149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3480.22972656, 1428.68882812, 176.64832031000003), 'rotation':(-0.602112, -179.531219, -0.614868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.54808594, 1993.868125, 173.94705077999998), 'rotation':(0.331332, -89.612732, 0.327532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3626.66601562, 1988.54054688, 173.97773438000002), 'rotation':(0.331332, -89.612732, 0.327532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.11132812, 1997.4553125, 172.03585938), 'rotation':(0.685519, -89.799774, 0.669243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.7239062500003, 1839.19640625, 174.075), 'rotation':(0.778109, -89.801056, 0.75718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.60226562, 1848.08460938, 173.95433594), 'rotation':(0.778109, -89.802551, 0.757201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.5659375, 1859.18929688, 173.80423828), 'rotation':(0.775814, -89.80072, 0.755017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.43796875, 1898.05679688, 173.28595703), 'rotation':(0.759667, -89.801758, 0.739719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.4196875, 1903.60976562, 173.21236327999998), 'rotation':(0.759667, -89.801758, 0.739719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.40140625, 1909.16234375, 173.13919922000002), 'rotation':(0.756519, -89.800079, 0.736744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3735.365, 1920.26757812, 172.99482422), 'rotation':(0.744149, -89.800415, 0.724998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.3103125, 1936.9264843800001, 172.78101562), 'rotation':(0.734826, -89.803619, 0.716165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3735.23734375, 1959.13710938, 172.50066406000002), 'rotation':(0.716132, -89.802399, 0.698388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.63476562, 1836.95609375, 174.10507812), 'rotation':(-0.778107, 90.198929, -0.799469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.69359375, 1842.5078125, 174.02964844), 'rotation':(-0.775818, 90.199265, -0.797058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.7214062499997, 1848.0587500000001, 173.95433594), 'rotation':(-0.775818, 90.199265, -0.797058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.703125, 1853.6109375, 173.87914062), 'rotation':(-0.771149, 90.199135, -0.792114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.6667187499997, 1864.7159375, 173.72945312), 'rotation':(-0.766632, 90.197571, -0.787384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.6301562500003, 1875.82117188, 173.58087891), 'rotation':(-0.761963, 90.198883, -0.78244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.59375, 1886.9260156199998, 173.43322265999998), 'rotation':(-0.759674, 90.198227, -0.780029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.48414062, 1920.2419531199998, 172.99480469), 'rotation':(-0.737885, 90.199425, -0.75708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.46578125, 1925.79492188, 172.9234375), 'rotation':(-0.734833, 90.196342, -0.753876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3727.44773438, 1931.3474999999999, 172.85222656000002), 'rotation':(-0.734833, 90.198441, -0.753876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.42945312, 1936.90085938, 172.78101562), 'rotation':(-0.73111, 90.197975, -0.749939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.41109375, 1942.4533593800002, 172.71013672), 'rotation':(-0.723663, 90.197792, -0.742126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.37476562, 1953.5588281199998, 172.57), 'rotation':(-0.716125, 90.197594, -0.734192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3873.29296875, 1301.33007812, 179.90822265999998), 'rotation':(-0.030853, 0.083801, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3863.1354687499997, 1301.30773438, 179.91367188), 'rotation':(-0.030853, 0.083801, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3846.37015625, 1301.1639453100001, 179.92273438), 'rotation':(-0.030853, 0.083036, -0.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3823.5950000000003, 1301.12816406, 179.88537109), 'rotation':(0.150831, 0.084995, 0.150029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.944375, 1301.11988281, 179.87050781000002), 'rotation':(0.150647, 0.083607, 0.149857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3806.64523438, 1301.10339844, 179.83960938), 'rotation':(0.161233, 0.084426, 0.16032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3784.04882812, 1301.07068359, 179.75421875), 'rotation':(0.243216, 0.085, 0.241162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.45140625, 1301.03785156, 179.63669922), 'rotation':(0.322679, 0.085828, 0.319068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3750.1510937499997, 1301.02136719, 179.56957031000002), 'rotation':(0.352663, 0.086186, 0.348337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3744.5009375, 1301.01306641, 179.53357422000002), 'rotation':(0.368079, 0.08638, 0.363364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3733.2043750000003, 1300.99658203, 179.45664062), 'rotation':(0.39805, 0.085422, 0.392554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.55445312, 1300.9883984399999, 179.41566406), 'rotation':(0.413302, 0.086997, 0.407359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3721.90554688, 1300.98023438, 179.37326172000002), 'rotation':(0.428191, 0.087214, 0.421831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3704.9557812499997, 1300.95544922, 179.24283203), 'rotation':(0.446715, 0.087272, 0.439791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3688.00851562, 1300.93078125, 179.10107422000002), 'rotation':(0.491241, 0.087899, 0.482876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3671.0612499999997, 1300.90601562, 178.94730468999998), 'rotation':(0.527161, 0.088687, 0.517525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3665.41164062, 1300.89794922, 178.89472656), 'rotation':(0.532789, 0.088786, 0.522957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3642.81445312, 1300.865, 178.67439453), 'rotation':(0.577772, 0.089659, 0.566222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3637.16453125, 1300.85667969, 178.61695312), 'rotation':(0.577772, 0.089659, 0.566222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3631.51488281, 1300.84851562, 178.55855469), 'rotation':(0.588926, 0.089888, 0.576916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3620.21460938, 1300.83203125, 178.43890625), 'rotation':(0.611493, 0.089282, 0.598552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3614.56738281, 1300.82373047, 178.37808593999998), 'rotation':(0.617224, 0.090967, 0.604022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3586.31789062, 1300.78246094, 178.06712890999998), 'rotation':(0.637079, 0.090848, 0.623028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3563.72070312, 1300.74951172, 177.81072265999998), 'rotation':(0.649203, 0.091701, 0.634603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3558.0705468799997, 1300.74144531, 177.745625), 'rotation':(0.65996, 0.091342, 0.644881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3546.775625, 1300.72498047, 177.61078125), 'rotation':(0.681571, 0.091132, 0.665508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3541.12574219, 1300.71679688, 177.54140625), 'rotation':(0.703305, 0.092373, 0.686201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3529.82691406, 1300.7003125, 177.39951172000002), 'rotation':(0.724861, 0.092908, 0.70669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3512.87914062, 1300.80517578, 177.18210938), 'rotation':(0.735823, 0.092475, 0.717111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3868.7995312499997, 1293.18408203, 179.91064452999998), 'rotation':(0.030845, -179.916199, 0.030814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3863.1475, 1293.18335938, 179.91367188), 'rotation':(0.030845, -179.916962, 0.030806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3840.5490625, 1293.27257812, 179.92154297000002), 'rotation':(-0.105469, -179.91597, -0.105835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3834.90453125, 1293.26427734, 179.91320312), 'rotation':(-0.150818, -179.916397, -0.151611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3823.60640625, 1293.2478125, 179.88537109), 'rotation':(-0.150635, -179.914993, -0.151459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3817.9557812499997, 1293.23949219, 179.87050781000002), 'rotation':(-0.150818, -179.916397, -0.151642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3812.306875, 1293.23132812, 179.855625), 'rotation':(-0.161224, -179.915573, -0.16214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3784.0603125, 1293.19005859, 179.75421875), 'rotation':(-0.263733, -179.914825, -0.266174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3778.410625, 1293.181875, 179.72751953), 'rotation':(-0.284241, -179.914612, -0.287048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3772.7604687499997, 1293.17382812, 179.69869140999998), 'rotation':(-0.304871, -179.914413, -0.308136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3761.46289062, 1293.15722656, 179.63669922), 'rotation':(-0.337738, -179.914001, -0.341766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3755.81273438, 1293.14892578, 179.60394531000003), 'rotation':(-0.352661, -179.913818, -0.357025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3750.16234375, 1293.1407421899999, 179.56957031000002), 'rotation':(-0.368073, -179.91362, -0.372833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3744.51265625, 1293.13244141, 179.53357422000002), 'rotation':(-0.382965, -179.914764, -0.388123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3738.86523438, 1293.12425781, 179.49597656000003), 'rotation':(-0.398071, -179.913208, -0.403595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3733.2160937500003, 1293.11609375, 179.45664062), 'rotation':(-0.4133, -179.912994, -0.419281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3727.5659375, 1293.10791016, 179.41566406), 'rotation':(-0.428192, -179.914124, -0.434631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3721.91726562, 1293.09972656, 179.37326172000002), 'rotation':(-0.435944, -179.91275, -0.442596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3716.2665625, 1293.09142578, 179.33027343999998), 'rotation':(-0.435944, -179.91275, -0.442596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3699.3176562500003, 1293.06664062, 179.19679688), 'rotation':(-0.491272, -179.912094, -0.499725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3693.67039062, 1293.0584765600001, 179.14951172000002), 'rotation':(-0.491272, -179.912094, -0.499725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3688.01976562, 1293.05017578, 179.10105468999998), 'rotation':(-0.515167, -179.911667, -0.524506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3682.370625, 1293.04210938, 179.05052734), 'rotation':(-0.527161, -179.911301, -0.536926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3631.52636719, 1292.96789062, 178.55855469), 'rotation':(-0.60022, -179.91095, -0.612885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3597.62890625, 1292.91845703, 178.193125), 'rotation':(-0.637085, -179.909134, -0.651367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3591.97898438, 1292.9102734399999, 178.1303125), 'rotation':(-0.645111, -179.908966, -0.65976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3586.32960938, 1292.90197266, 178.06712890999998), 'rotation':(-0.645111, -179.908966, -0.65976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3580.67921875, 1292.89378906, 178.00349609), 'rotation':(-0.6492, -179.909409, -0.664032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3575.03050781, 1292.885625, 177.93951172), 'rotation':(-0.64917, -179.909424, -0.664001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3552.433125, 1292.85253906, 177.67845703), 'rotation':(-0.703308, -179.907623, -0.720734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3546.78734375, 1292.84423828, 177.61078125), 'rotation':(-0.703308, -179.907623, -0.720734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3541.13746094, 1292.8359375, 177.54140625), 'rotation':(-0.724854, -179.907089, -0.743378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3535.48828125, 1292.82775391, 177.47101562), 'rotation':(-0.724854, -179.907089, -0.743378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3524.19410156, 1292.76416016, 177.32728516), 'rotation':(-0.735687, -179.906311, -0.754761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.40820312, 1577.70519531, 173.84923827999998), 'rotation':(0.288582, 90.640945, 0.285685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.28491211, 1588.7196093799998, 173.90507811999998), 'rotation':(0.296096, 90.641014, 0.293054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.22338867, 1594.22679688, 173.93341797000002), 'rotation':(0.296096, 90.641014, 0.293054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3157.16186523, 1599.73414062, 173.96197266), 'rotation':(0.299859, 90.642937, 0.29673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.10058594, 1605.24109375, 173.99080078), 'rotation':(0.301689, 90.641235, 0.298538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3157.03857422, 1610.74867188, 174.01978516), 'rotation':(0.301689, 90.643723, 0.298523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.85375977, 1627.27074219, 174.10755859), 'rotation':(0.309811, 90.641808, 0.306488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.73071289, 1638.28492188, 174.16769531000003), 'rotation':(0.320616, 90.64193, 0.317049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.66918945, 1643.79222656, 174.19833984000002), 'rotation':(0.323259, 90.641808, 0.319631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.60766602, 1649.29980469, 174.22923828), 'rotation':(0.323259, 90.641808, 0.319631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.54589844, 1654.806875, 174.2603125), 'rotation':(0.323252, 90.643494, 0.319634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.484375, 1660.31398438, 174.29138672000002), 'rotation':(0.326326, 90.642189, 0.322627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.23803711, 1682.34328125, 174.41791016), 'rotation':(0.338975, 90.642342, 0.334986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':5, 'tiley':3, 'location':(3156.11499023, 1693.35765625, 174.48349609000002), 'rotation':(0.345362, 90.642426, 0.341214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':5, 'tiley':3, 'location':(3156.0534668, 1698.86507812, 174.51673828), 'rotation':(0.348394, 90.642319, 0.344186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':5, 'tiley':3, 'location':(3155.99194336, 1704.3721875, 174.55023438), 'rotation':(0.350095, 90.644478, 0.345836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':5, 'tiley':3, 'location':(3155.93017578, 1709.8747656199998, 174.58380859000002), 'rotation':(0.3425, 90.500244, 0.338426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4777.06005859, 4004.83523438, 156.93963867), 'rotation':(-0.368042, 89.545334, -0.372772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4777.37548828, 4044.20507812, 156.67168945), 'rotation':(-0.424469, 89.543701, -0.430786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.42041016, 4049.8303125, 156.63), 'rotation':(-0.44101, 89.546745, -0.447845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.46533203, 4055.45484375, 156.58738281), 'rotation':(-0.44101, 89.546745, -0.447845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4777.51074219, 4061.07960938, 156.54410156), 'rotation':(-0.449127, 89.54203, -0.456207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.60058594, 4072.32765625, 156.45586914), 'rotation':(-0.459839, 89.545303, -0.467255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.69091797, 4083.5771875, 156.3653418), 'rotation':(-0.474152, 89.545525, -0.482056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.73583984, 4089.2018749999997, 156.31893555), 'rotation':(-0.481323, 89.545654, -0.489441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4777.91601562, 4111.69773438, 156.12586914), 'rotation':(-0.506378, 89.545761, -0.515411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.09619141, 4134.19625, 155.92458008), 'rotation':(-0.52417, 89.549454, -0.533844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.23144531, 4151.06882812, 155.76808594), 'rotation':(-0.544403, 89.544342, -0.55481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.32177734, 4162.31789062, 155.66119141), 'rotation':(-0.548859, 89.543388, -0.559418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.41162109, 4173.56640625, 155.55316406), 'rotation':(-0.556274, 89.548401, -0.567139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.68212891, 4207.3134375, 155.22058594), 'rotation':(-0.576324, 89.543892, -0.588013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.7265625, 4212.9375, 155.1640332), 'rotation':(-0.577393, 89.545456, -0.589111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.81689453, 4224.18601562, 155.05047851999998), 'rotation':(-0.58078, 89.545532, -0.592621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.86181641, 4229.81101562, 154.99342773), 'rotation':(-0.582642, 89.545563, -0.594574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4778.90722656, 4235.43601562, 154.93617188), 'rotation':(-0.58432, 89.545593, -0.596344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4778.99707031, 4246.68507812, 154.82113281), 'rotation':(-0.58786, 89.545677, -0.600037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4779.08740234, 4257.9340625, 154.70540039), 'rotation':(-0.590454, 89.548828, -0.602722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4779.13232422, 4263.558125, 154.64743164), 'rotation':(-0.590454, 89.543259, -0.602722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.26757812, 4280.43210938, 154.47347656), 'rotation':(-0.592072, 89.546768, -0.604401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.3125, 4286.05710938, 154.41539062), 'rotation':(-0.592438, 89.546654, -0.604797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.40283203, 4297.30664062, 154.29907227), 'rotation':(-0.592438, 89.549652, -0.604797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4779.44775391, 4302.93164062, 154.24088867), 'rotation':(-0.592438, 89.549652, -0.604797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.49267578, 4308.55617188, 154.18272461), 'rotation':(-0.591766, 89.545265, -0.604095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.53808594, 4314.180625, 154.12466797), 'rotation':(-0.590149, 89.545288, -0.602386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.62792969, 4325.430625, 154.00895508), 'rotation':(-0.587189, 89.545174, -0.599304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.71826172, 4336.680625, 153.89384766), 'rotation':(-0.584137, 89.550224, -0.59613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4779.76318359, 4342.3046875, 153.8365332), 'rotation':(-0.582764, 89.54509, -0.594696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4788.09863281, 4336.6396875, 153.89358398000002), 'rotation':(0.585552, -90.454803, 0.573668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.82861328, 4302.890625, 154.24061523), 'rotation':(0.592444, -90.453339, 0.580284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.73828125, 4291.64109375, 154.35696289), 'rotation':(0.592041, -90.453186, 0.579883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.55810547, 4269.14210938, 154.58919921999998), 'rotation':(0.590463, -90.451172, 0.578381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4787.46777344, 4257.89257812, 154.70513671999998), 'rotation':(0.590463, -90.451172, 0.578381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.24267578, 4229.76953125, 154.99316406), 'rotation':(0.58075, -90.449036, 0.569079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4787.0625, 4207.27195312, 155.22032227), 'rotation':(0.574603, -90.456085, 0.563187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4786.92724609, 4190.3975, 155.38823242), 'rotation':(0.563422, -90.451416, 0.552424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.83740234, 4179.1484375, 155.49839844), 'rotation':(0.556203, -90.456451, 0.545485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.79248047, 4173.5234375, 155.55292969), 'rotation':(0.552576, -90.45166, 0.541984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.65673828, 4156.65039062, 155.71459961), 'rotation':(0.544407, -90.455627, 0.534142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.61181641, 4151.02492188, 155.76787109), 'rotation':(0.539448, -90.450256, 0.529347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.52197266, 4139.77585938, 155.87275391), 'rotation':(0.524183, -90.450531, 0.514648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.4765625, 4134.151875, 155.924375), 'rotation':(0.519149, -90.456055, 0.509813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.43164062, 4128.52734375, 155.97544922), 'rotation':(0.513883, -90.456177, 0.504745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.38671875, 4122.901875, 156.0259668), 'rotation':(0.508917, -90.450806, 0.499956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.34179688, 4117.27828125, 156.07594727), 'rotation':(0.506349, -90.454193, 0.497449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.29638672, 4111.6528125, 156.12567382999998), 'rotation':(0.502818, -90.453979, 0.494045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.25146484, 4106.02828125, 156.17507812), 'rotation':(0.49581, -90.459412, 0.487295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.11669922, 4089.15476562, 156.31876953), 'rotation':(0.474165, -90.454468, 0.46638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.07519531, 4083.5299999999997, 156.36517578000002), 'rotation':(0.467158, -90.454559, 0.459581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4786.03222656, 4077.9053125, 156.41081055), 'rotation':(0.459856, -90.454712, 0.452513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.98876953, 4072.28078125, 156.45570312), 'rotation':(0.452828, -90.454803, 0.44572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4785.94580078, 4066.65578125, 156.50001953), 'rotation':(0.449126, -90.453918, 0.442135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.82763672, 4055.40625, 156.58724609), 'rotation':(0.424476, -90.456299, 0.418224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.6328125, 4032.9075000000003, 156.75225586), 'rotation':(0.391643, -90.456757, 0.386328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4785.49755859, 4016.0334375, 156.86683594), 'rotation':(0.378372, -90.454529, 0.373398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4980.60253906, 4352.48828125, 156.2037793), 'rotation':(0.626813, -90.46991, 0.613218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4980.29785156, 4330.06007812, 156.44957031), 'rotation':(0.630543, -90.473419, 0.616775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4980.06298828, 4302.01859375, 156.75883789), 'rotation':(0.632571, -90.471893, 0.618716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4980.01611328, 4296.41015625, 156.82077148), 'rotation':(0.631574, -90.471924, 0.617759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.92236328, 4285.19382812, 156.94433594), 'rotation':(0.629907, -90.471924, 0.616167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.87548828, 4279.58546875, 157.00597656), 'rotation':(0.628917, -90.471985, 0.61521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.82861328, 4273.97804688, 157.06751953), 'rotation':(0.627913, -90.471985, 0.61426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.73486328, 4262.76171875, 157.1903418), 'rotation':(0.626246, -90.472015, 0.61267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4979.5, 4234.72023438, 157.49577148), 'rotation':(0.614177, -90.472656, 0.601122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.21826172, 4201.07125, 157.85416016), 'rotation':(0.603078, -90.474487, 0.590491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.17138672, 4195.46289062, 157.91319336), 'rotation':(0.594834, -90.471558, 0.5826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4979.07763672, 4184.2465625, 158.0300293), 'rotation':(0.58657, -90.474792, 0.57466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.93945312, 4167.421875, 158.20130859), 'rotation':(0.5742, -90.478271, 0.562791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.73632812, 4144.98976562, 158.42510742000002), 'rotation':(0.556763, -90.475281, 0.546026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.625, 4133.77390625, 158.53375), 'rotation':(0.545281, -90.475494, 0.534981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4978.43408203, 4111.3403125, 158.74387695), 'rotation':(0.527762, -90.475433, 0.51812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.34033203, 4100.12351562, 158.84646484), 'rotation':(0.505495, -90.472961, 0.496648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.24609375, 4088.9071875, 158.94631836), 'rotation':(0.490578, -90.476196, 0.482235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4978.19921875, 4083.2990625, 158.99473633), 'rotation':(0.490578, -90.476196, 0.482235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4978.05859375, 4066.4739062500003, 159.13549805), 'rotation':(0.46836, -90.475616, 0.460736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4977.96435547, 4055.256875, 159.2265625), 'rotation':(0.459487, -90.475372, 0.452157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4977.72998047, 4027.2153125, 159.44037109), 'rotation':(0.406799, -90.478973, 0.401047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4977.68261719, 4021.60640625, 159.48019531), 'rotation':(0.398104, -90.471893, 0.392605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4969.19433594, 4004.82984375, 159.59592773), 'rotation':(-0.388275, 89.525246, -0.393555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.24121094, 4010.43820312, 159.55791992000002), 'rotation':(-0.398132, 89.522293, -0.403687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.42919922, 4032.870625, 159.39962891), 'rotation':(-0.424408, 89.524063, -0.430695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.5703125, 4049.69359375, 159.27174805), 'rotation':(-0.459473, 89.524605, -0.466919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.6171875, 4055.30226562, 159.22675781), 'rotation':(-0.468353, 89.524406, -0.476044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.6640625, 4060.90992188, 159.18155273), 'rotation':(-0.468353, 89.524406, -0.476044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4969.7109375, 4066.5182812499997, 159.13571289), 'rotation':(-0.475677, 89.523537, -0.483612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4969.89892578, 4088.94992188, 158.9465625), 'rotation':(-0.505493, 89.527061, -0.514465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4969.99267578, 4100.16601562, 158.84670898000002), 'rotation':(-0.520416, 89.524315, -0.529938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.08642578, 4111.38132812, 158.74416015999998), 'rotation':(-0.5336, 89.52713, -0.54361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.32128906, 4139.42140625, 158.47992188), 'rotation':(-0.556732, 89.52475, -0.567657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.36816406, 4145.02976562, 158.42541015999998), 'rotation':(-0.56842, 89.527779, -0.579803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.50878906, 4161.85304688, 158.25794922), 'rotation':(-0.574188, 89.521706, -0.585815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.55566406, 4167.46046875, 158.20163086), 'rotation':(-0.578339, 89.528122, -0.590118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.74365234, 4189.89359375, 157.97211914), 'rotation':(-0.603058, 89.525528, -0.615845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4970.79052734, 4195.5009375, 157.91352539), 'rotation':(-0.603058, 89.525528, -0.615845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4970.83740234, 4201.109375, 157.85449219), 'rotation':(-0.60733, 89.528793, -0.6203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(4970.97802734, 4217.933125, 157.67618163999998), 'rotation':(-0.609558, 89.527229, -0.62262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.02490234, 4223.54148438, 157.61650391), 'rotation':(-0.614166, 89.527336, -0.627441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(4971.07226562, 4229.149375, 157.55645508), 'rotation':(-0.618805, 89.527412, -0.632263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.26025391, 4251.5815625, 157.31326171999999), 'rotation':(-0.625732, 89.529327, -0.639526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.35400391, 4262.79734375, 157.19072266), 'rotation':(-0.627106, 89.527985, -0.64093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.40087891, 4268.40578125, 157.1293457), 'rotation':(-0.627899, 89.522682, -0.641785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.44775391, 4274.01414062, 157.06790039), 'rotation':(-0.628845, 89.528076, -0.642761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.49462891, 4279.62203125, 157.00634766), 'rotation':(-0.629913, 89.528061, -0.64389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.54150391, 4285.23046875, 156.9447168), 'rotation':(-0.630585, 89.528061, -0.644562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.58886719, 4290.83890625, 156.88296875), 'rotation':(-0.631561, 89.528084, -0.645599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.63574219, 4296.44679688, 156.82113281), 'rotation':(-0.632538, 89.528107, -0.646637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.82324219, 4318.87984375, 156.5734082), 'rotation':(-0.630493, 89.526619, -0.644501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.87011719, 4324.4878125, 156.51164062), 'rotation':(-0.62912, 89.526566, -0.643036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.96386719, 4335.70507812, 156.38834961), 'rotation':(-0.627502, 89.526535, -0.641327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(4971.98876953, 4352.52390625, 156.20417969), 'rotation':(-0.626709, 89.52636, -0.640533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.40185547, 4008.17554688, 160.24273438), 'rotation':(-0.277679, 89.845947, -0.280365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.43212891, 4019.5525, 160.18796875), 'rotation':(-0.284271, 89.847649, -0.287079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.46289062, 4030.9309375000003, 160.1309082), 'rotation':(-0.297516, 89.850861, -0.300598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.49316406, 4042.30882812, 160.07068359000002), 'rotation':(-0.324219, 89.848045, -0.327911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.5390625, 4059.375, 159.97460938), 'rotation':(-0.330841, 89.845253, -0.334686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.56933594, 4070.75242188, 159.90860351999999), 'rotation':(-0.336609, 89.849632, -0.340576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.61474609, 4087.81960938, 159.80561523), 'rotation':(-0.359314, 89.849915, -0.363831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.62988281, 4093.50875, 159.76994141), 'rotation':(-0.370636, 89.846863, -0.375427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.64501953, 4099.19726562, 159.73328125), 'rotation':(-0.376373, 89.852631, -0.381348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.67578125, 4110.57421875, 159.65890625), 'rotation':(-0.378906, 89.849075, -0.383942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.69091797, 4116.26265625, 159.6212793), 'rotation':(-0.384033, 89.849129, -0.389191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.72119141, 4127.64109375, 159.54446289), 'rotation':(-0.394531, 89.849258, -0.399963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.75146484, 4139.0190625, 159.465625), 'rotation':(-0.404999, 89.849403, -0.410767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.78173828, 4150.39695312, 159.38478515999998), 'rotation':(-0.415344, 89.849571, -0.421387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.84277344, 4173.15140625, 159.21837890999998), 'rotation':(-0.42868, 89.852791, -0.43512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.87353516, 4184.52929688, 159.13287109), 'rotation':(-0.435822, 89.849907, -0.442474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5217.88867188, 4190.21828125, 159.08958008), 'rotation':(-0.443054, 89.850006, -0.449921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5217.97998047, 4224.3515625, 158.82380859), 'rotation':(-0.453491, 89.852974, -0.460724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.02539062, 4241.4184375, 158.68725586), 'rotation':(-0.465332, 89.85437, -0.4729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.04052734, 4247.10695312, 158.64109375), 'rotation':(-0.465332, 89.849564, -0.4729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.07128906, 4258.484375, 158.54861328), 'rotation':(-0.468109, 89.85244, -0.47583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.1015625, 4269.8628125, 158.45556641), 'rotation':(-0.471832, 89.847778, -0.479645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.13183594, 4281.24023438, 158.36179688), 'rotation':(-0.475525, 89.852562, -0.483459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.16259766, 4292.61867188, 158.26733398), 'rotation':(-0.47937, 89.852623, -0.487427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.20800781, 4309.68507812, 158.12453125), 'rotation':(-0.480194, 89.848396, -0.488281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.23828125, 4321.0634375, 158.02914062), 'rotation':(-0.480927, 89.851006, -0.489044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5218.25927734, 4332.43898438, 157.93351562), 'rotation':(-0.482666, 89.850487, -0.490845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5218.17773438, 4343.81640625, 157.83766602), 'rotation':(-0.482666, 89.850487, -0.490845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.80175781, 4343.8125, 157.83749023000001), 'rotation':(0.482662, -90.149536, 0.474589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.73046875, 4338.12453125, 157.88541992), 'rotation':(0.482655, -90.145264, 0.474588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.63427734, 4326.74851562, 157.9812207), 'rotation':(0.480893, -90.148987, 0.472879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.60400391, 4315.37109375, 158.07667969), 'rotation':(0.480169, -90.14859, 0.472184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.58886719, 4309.68265625, 158.12435546999998), 'rotation':(0.480169, -90.14859, 0.472184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.55859375, 4298.30515625, 158.21967773), 'rotation':(0.477437, -90.15213, 0.469526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.52832031, 4286.92726562, 158.31450195), 'rotation':(0.475511, -90.14743, 0.467681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.51269531, 4281.23875, 158.36163086), 'rotation':(0.473756, -90.147461, 0.465971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.48242188, 4269.86132812, 158.45540039), 'rotation':(0.47004, -90.147522, 0.462395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.43701172, 4252.79539062, 158.59470703), 'rotation':(0.465354, -90.150452, 0.457832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.42138672, 4247.10742188, 158.64091797), 'rotation':(0.4653, -90.150452, 0.457805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.40625, 4241.41796875, 158.68708984), 'rotation':(0.462937, -90.146851, 0.455512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.39111328, 4235.72898438, 158.73302734), 'rotation':(0.45834, -90.151245, 0.451047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.37597656, 4230.04054688, 158.77853516), 'rotation':(0.453538, -90.147034, 0.446392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.33056641, 4212.97507812, 158.91271484), 'rotation':(0.446612, -90.149719, 0.439685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.29980469, 4201.5971875, 159.00141602), 'rotation':(0.443088, -90.149963, 0.436259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.26953125, 4190.2196875, 159.0894043), 'rotation':(0.435807, -90.150085, 0.429229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.25439453, 4184.53078125, 159.13269531), 'rotation':(0.428683, -90.150177, 0.4223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.20849609, 4167.464375, 159.26019531), 'rotation':(0.418103, -90.147186, 0.412034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.19335938, 4161.77640625, 159.30197266), 'rotation':(0.418103, -90.147186, 0.412034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.16259766, 4150.39890625, 159.38460938), 'rotation':(0.410085, -90.150513, 0.404257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.14746094, 4144.71046875, 159.42529297), 'rotation':(0.404982, -90.150574, 0.399315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.13232422, 4139.02148438, 159.46544921999998), 'rotation':(0.399764, -90.150665, 0.394202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5226.07617188, 4116.2665625, 159.62109375), 'rotation':(0.378918, -90.15094, 0.373948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5226.01806641, 4093.51195312, 159.76979492), 'rotation':(0.359309, -90.150085, 0.354829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.98974609, 4082.13375, 159.84049805), 'rotation':(0.348012, -90.150208, 0.343788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.91748047, 4065.06734375, 159.94160156), 'rotation':(0.330841, -90.150146, 0.327042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.87744141, 4053.6901562499997, 160.00710938), 'rotation':(0.324209, -90.151917, 0.320564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.85742188, 4048.0012500000003, 160.03928711), 'rotation':(0.310965, -90.152069, 0.307589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5225.82568359, 4036.6240625, 160.10123047), 'rotation':(0.297509, -90.152222, 0.294429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.81054688, 4030.93453125, 160.13078125), 'rotation':(0.284231, -90.149261, 0.281438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.76513672, 4013.868125, 160.21544921999998), 'rotation':(0.270715, -90.149872, 0.268153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5225.74951172, 4008.17921875, 160.24261719), 'rotation':(0.270715, -90.149872, 0.268153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5757.319375, 5223.87744141, 161.66050781), 'rotation':(1.082243, 0.227805, 1.041912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5751.796875, 5223.85693359, 161.55613281), 'rotation':(1.082394, 0.232868, 1.042059), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5746.2734375, 5223.83691406, 161.45173828), 'rotation':(1.082339, 0.227823, 1.04201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5740.75046875, 5223.81640625, 161.34732422), 'rotation':(1.082237, 0.232862, 1.041912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5718.65820312, 5223.73535156, 160.92863281), 'rotation':(1.085843, 0.229042, 1.045249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5696.5659375, 5223.65429688, 160.50979492), 'rotation':(1.08574, 0.229038, 1.04516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5691.0434375, 5223.63427734, 160.40515625), 'rotation':(1.085324, 0.231298, 1.044767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5685.52046875, 5223.61425781, 160.30053711), 'rotation':(1.085324, 0.231298, 1.044767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.95117188, 5223.55322266, 159.9869043), 'rotation':(1.083924, 0.230431, 1.04346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5657.90429688, 5223.51269531, 159.77786133), 'rotation':(1.083746, 0.230423, 1.043304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5652.38039062, 5223.49267578, 159.67350586), 'rotation':(1.082667, 0.22719, 1.042312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5646.85789062, 5223.47216797, 159.56944336), 'rotation':(1.080058, 0.232674, 1.039899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.81101562, 5223.43164062, 159.36208984), 'rotation':(1.072565, 0.226807, 1.03295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5624.76515625, 5223.39111328, 159.15579102), 'rotation':(1.067675, 0.232213, 1.028421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5613.72414062, 5223.44824219, 158.95052734), 'rotation':(1.063857, 0.230961, 1.024885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5619.22363281, 5214.99072266, 159.05210938), 'rotation':(-1.063843, -179.769043, -1.103943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5624.7465625, 5215.01074219, 159.15487305), 'rotation':(-1.065063, -179.767883, -1.105255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.7934375, 5215.05126953, 159.36117188), 'rotation':(-1.069946, -179.7677, -1.110504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5646.83984375, 5215.09130859, 159.56852539), 'rotation':(-1.077454, -179.767426, -1.118561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5657.88671875, 5215.13183594, 159.77694336000002), 'rotation':(-1.082672, -179.767242, -1.124207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5663.41015625, 5215.15234375, 159.88143555), 'rotation':(-1.08374, -179.769577, -1.125366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.933125, 5215.17236328, 159.98597656), 'rotation':(-1.08374, -179.769577, -1.125366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5685.50296875, 5215.23291016, 160.29963867), 'rotation':(-1.08429, -179.771744, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5691.02640625, 5215.25341797, 160.40424805), 'rotation':(-1.08429, -179.771744, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5696.54929688, 5215.27392578, 160.50890625), 'rotation':(-1.085327, -179.768692, -1.127045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5707.59523438, 5215.31445312, 160.71832031), 'rotation':(-1.085754, -179.767899, -1.127502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5713.11914062, 5215.33447266, 160.82305664), 'rotation':(-1.085785, -179.770966, -1.127533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5724.165, 5215.36962891, 161.0324707), 'rotation':(-1.085846, -179.767899, -1.127594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5729.68796875, 5215.38525391, 161.13717773), 'rotation':(-1.085846, -179.767899, -1.127594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5740.734375, 5215.46875, 161.34643555), 'rotation':(-1.084137, -179.771011, -1.125793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5800.84570312, 5215.65576172, 162.48024414), 'rotation':(-1.073608, -179.769501, -1.114441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.46484375, 5215.67626953, 162.58542969), 'rotation':(-1.072052, -179.77272, -1.112762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5812.08296875, 5215.69677734, 162.69058594), 'rotation':(-1.072235, -179.767395, -1.112946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5817.70265625, 5215.71728516, 162.79567383), 'rotation':(-1.071075, -179.771667, -1.111725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5885.13039062, 5215.96484375, 164.04382812), 'rotation':(-1.049622, -179.771027, -1.088654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5890.74953125, 5215.98535156, 164.1465625), 'rotation':(-1.049622, -179.771027, -1.088654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5901.98734375, 5216.01855469, 164.35111328), 'rotation':(-1.04129, -179.771332, -1.079651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5907.60640625, 5216.06396484, 164.45308594), 'rotation':(-1.039032, -179.7715, -1.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5913.22507812, 5216.10058594, 164.55501952999998), 'rotation':(-1.039032, -179.7715, -1.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.46335938, 5216.14160156, 164.75892578), 'rotation':(-1.039032, -179.767944, -1.077271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5935.70164062, 5216.18310547, 164.96261718999997), 'rotation':(-1.039093, -179.771484, -1.077332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5946.93992188, 5216.22412109, 165.16509766), 'rotation':(-1.029663, -179.770035, -1.067169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.17875, 5216.26513672, 165.36714844), 'rotation':(-1.029663, -179.77388, -1.0672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5963.79734375, 5216.28564453, 165.46816406000002), 'rotation':(-1.029663, -179.770035, -1.067169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.035625, 5216.32714844, 165.67005859), 'rotation':(-1.027771, -179.772324, -1.065186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.274375, 5216.36865234, 165.87125), 'rotation':(-1.024078, -179.772461, -1.061218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5997.5121875, 5216.40966797, 166.07132812), 'rotation':(-1.016754, -179.771027, -1.053345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5795.2075, 5224.10351562, 162.37511719), 'rotation':(1.073617, 0.226679, 1.033923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5800.82375, 5224.03662109, 162.48041016), 'rotation':(1.07206, 0.232588, 1.03248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.44335938, 5224.05712891, 162.58560547), 'rotation':(1.07223, 0.227279, 1.032638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5812.06296875, 5224.07763672, 162.69078125), 'rotation':(1.071076, 0.232496, 1.031576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5823.30273438, 5224.11914062, 162.90080078), 'rotation':(1.067046, 0.232345, 1.027842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5834.54148438, 5224.16015625, 163.11008789), 'rotation':(1.063023, 0.228031, 1.024101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5840.16109375, 5224.18066406, 163.21451172), 'rotation':(1.063023, 0.228031, 1.024101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.78078125, 5224.20117188, 163.31875976999999), 'rotation':(1.061015, 0.232139, 1.022242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5851.40039062, 5224.22167969, 163.42285156), 'rotation':(1.05885, 0.227875, 1.020247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5857.02046875, 5224.2421875, 163.52677734), 'rotation':(1.056985, 0.231992, 1.018501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5862.6396875, 5224.26318359, 163.63050781), 'rotation':(1.055961, 0.227981, 1.017556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5879.49851562, 5224.32470703, 163.94115234), 'rotation':(1.049636, 0.228966, 1.011691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5890.73828125, 5224.36621094, 164.14691406000003), 'rotation':(1.045326, 0.228794, 1.007686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5907.5971875, 5224.42773438, 164.45345702999998), 'rotation':(1.03909, 0.228517, 1.001895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5913.21679688, 5224.44824219, 164.55542968999998), 'rotation':(1.03909, 0.228517, 1.001895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.4565625, 5224.48974609, 164.75935547), 'rotation':(1.03909, 0.228517, 1.001895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.0771875, 5224.51611328, 164.86134765999998), 'rotation':(1.034377, 0.230195, 0.997516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5935.69679688, 5224.54199219, 164.96308593999998), 'rotation':(1.034377, 0.230195, 0.997516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.316875, 5224.52685547, 165.06455078), 'rotation':(1.029658, 0.229958, 0.993131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5963.79539062, 5224.60058594, 165.46869141), 'rotation':(1.029576, 0.226099, 0.993063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.27492188, 5224.68310547, 165.87179688), 'rotation':(1.020403, 0.22741, 0.984528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.89453125, 5224.70361328, 165.97193359000002), 'rotation':(1.016708, 0.227114, 0.98109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.81734375, 4339.89796875, 160.64285156), 'rotation':(0.277688, 90.858124, 0.275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.06492188, 4323.2821875, 160.56230469), 'rotation':(0.277845, 90.853348, 0.275167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.14796875, 4317.74367188, 160.53542969), 'rotation':(0.277845, 90.853348, 0.275167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.56054688, 4290.05078125, 160.40109375), 'rotation':(0.277941, 90.855347, 0.275252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.64304688, 4284.51265625, 160.37426758), 'rotation':(0.27749, 90.854836, 0.274809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.890625, 4267.89648438, 160.29414062), 'rotation':(0.275858, 90.854813, 0.273213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.973125, 4262.3584375, 160.26754883), 'rotation':(0.275031, 90.858002, 0.272403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.055625, 4256.819375, 160.2409668), 'rotation':(0.275031, 90.858002, 0.272403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.30320312, 4240.20359375, 160.16132812), 'rotation':(0.274676, 90.853912, 0.272049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.38578125, 4234.665, 160.13476562), 'rotation':(0.274553, 90.85862, 0.271935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.46828125, 4229.12648438, 160.10834961), 'rotation':(0.273208, 90.855125, 0.270618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.63328125, 4218.04929688, 160.0559668), 'rotation':(0.270291, 90.855156, 0.267748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.71578125, 4212.51078125, 160.0299707), 'rotation':(0.268925, 90.854004, 0.266403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5785.88085938, 4201.43359375, 159.97797852), 'rotation':(0.268932, 90.854065, 0.266423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5785.96335938, 4195.895, 159.95198242), 'rotation':(0.268925, 90.854004, 0.266403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.04640625, 4190.35640625, 159.92608398000002), 'rotation':(0.26745, 90.856506, 0.264954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.12890625, 4184.816875, 159.9002832), 'rotation':(0.26745, 90.856506, 0.264954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5786.21140625, 4179.27828125, 159.87469726999998), 'rotation':(0.264793, 90.853485, 0.262359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.51757812, 4157.12648438, 159.77378906), 'rotation':(0.259267, 90.853401, 0.256927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5786.50976562, 4151.58789062, 159.74886719), 'rotation':(0.257874, 90.858139, 0.255558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.27929688, 4334.48390625, 160.61599609), 'rotation':(-0.277863, -89.146606, -0.280579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.444375, 4323.40671875, 160.56230469), 'rotation':(-0.277954, -89.144653, -0.28064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.52734375, 4317.868125, 160.53542969), 'rotation':(-0.277954, -89.144653, -0.28064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.69234375, 4306.79148438, 160.48168945), 'rotation':(-0.277954, -89.144653, -0.28064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5792.77492188, 4301.25242188, 160.45481445), 'rotation':(-0.277954, -89.144592, -0.28067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5792.93992188, 4290.1753125, 160.40109375), 'rotation':(-0.277496, -89.145203, -0.280182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5793.0225, 4284.63671875, 160.37424805), 'rotation':(-0.276672, -89.145172, -0.279358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5793.105, 4279.098125, 160.34751953), 'rotation':(-0.275848, -89.141968, -0.278503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5793.3525, 4262.48289062, 160.26754883), 'rotation':(-0.274689, -89.146027, -0.277344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5793.60007812, 4245.86671875, 160.18787109000002), 'rotation':(-0.274689, -89.146027, -0.277344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5793.84765625, 4229.2509375, 160.10834961), 'rotation':(-0.270264, -89.144897, -0.272827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.01265625, 4218.17382812, 160.05595703), 'rotation':(-0.268921, -89.145905, -0.271484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.3428125, 4196.01953125, 159.95198242), 'rotation':(-0.267456, -89.146515, -0.269958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.50828125, 4184.94140625, 159.9002832), 'rotation':(-0.264801, -89.143494, -0.267242), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5794.59078125, 4179.4028125, 159.87469726999998), 'rotation':(-0.262115, -89.146576, -0.264526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5794.83835938, 4162.78710938, 159.79882812), 'rotation':(-0.257874, -89.145386, -0.260223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.54984375, 4483.37648438, 161.32052734), 'rotation':(0.255709, 90.851395, 0.253445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.1753125, 4450.07714844, 161.16832031), 'rotation':(0.265387, 90.856606, 0.262947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.42382812, 4433.42625, 161.09092773), 'rotation':(0.266862, 90.856613, 0.264383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.58890625, 4422.32519531, 161.03881836), 'rotation':(0.268973, 90.856621, 0.266468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.67140625, 4416.77492188, 161.01250977), 'rotation':(0.270674, 90.852097, 0.268137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.836875, 4405.67429688, 160.95955078), 'rotation':(0.273604, 90.856201, 0.271004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.00296875, 4394.57375, 160.90654297), 'rotation':(0.273617, 90.853249, 0.27103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5783.16796875, 4383.473125, 160.85339844), 'rotation':(0.274669, 90.855133, 0.272055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.2509375, 4377.92234375, 160.82673828), 'rotation':(0.274669, 90.855133, 0.272055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.71289062, 4372.49460938, 160.80001953000001), 'rotation':(-0.276154, -89.144867, -0.278809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.63039062, 4378.04492188, 160.82673828), 'rotation':(-0.275482, -89.144867, -0.278137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.46484375, 4389.14601562, 160.8799707), 'rotation':(-0.274689, -89.144867, -0.277313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5791.21679688, 4405.796875, 160.95955078), 'rotation':(-0.273621, -89.146729, -0.276245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5791.05125, 4416.89746094, 161.0125), 'rotation':(-0.272644, -89.143341, -0.275269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5790.96875, 4422.44773438, 161.03879883), 'rotation':(-0.270691, -89.147888, -0.273254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.80320312, 4433.54882812, 161.0909082), 'rotation':(-0.268982, -89.143311, -0.271545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.5546875, 4450.1996875, 161.16830078), 'rotation':(-0.265991, -89.144562, -0.268463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.4409375, 4461.29929688, 161.21963867), 'rotation':(-0.263641, -89.143494, -0.266052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.390625, 4466.85058594, 161.24508789), 'rotation':(-0.261932, -89.148468, -0.264313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.25390625, 4479.08398438, 161.30064453), 'rotation':(-0.258911, -89.143433, -0.261261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.17234375, 4484.56347656, 161.3252832), 'rotation':(-0.257172, -89.14859, -0.25946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.09078125, 4490.04492188, 161.34977539), 'rotation':(-0.255768, -89.143463, -0.258026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.81296875, 4742.828125, 162.25583008), 'rotation':(0.135866, 90.853363, 0.135215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5777.8975, 4737.14599609, 162.24212891), 'rotation':(0.137826, 90.856926, 0.137165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5777.98242188, 4731.46435547, 162.22800781), 'rotation':(0.141481, 90.851631, 0.140787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.066875, 4725.78271484, 162.21348633), 'rotation':(0.145483, 90.857056, 0.144759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.151875, 4720.10058594, 162.19856445), 'rotation':(0.149137, 90.851669, 0.148354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.32125, 4708.73681641, 162.16746094), 'rotation':(0.160598, 90.857048, 0.159708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.57515625, 4691.69287109, 162.11833008), 'rotation':(0.166431, 90.854691, 0.165471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5778.6596875, 4686.01074219, 162.10151367), 'rotation':(0.167995, 90.857025, 0.167019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5778.9140625, 4668.9653125, 162.04879883), 'rotation':(0.182311, 90.857117, 0.181151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.08351562, 4657.60203125, 162.01176758), 'rotation':(0.189387, 90.857239, 0.188152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.25242188, 4646.23875, 161.97338867), 'rotation':(0.194613, 90.856934, 0.193293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.50632812, 4629.19382812, 161.91459961), 'rotation':(0.197474, 90.856506, 0.196121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.59132812, 4623.5121875, 161.89445312), 'rotation':(0.20298, 90.853409, 0.201556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.76023438, 4612.14890625, 161.85286133), 'rotation':(0.208703, 90.853447, 0.207186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.9296875, 4600.785625, 161.81013672), 'rotation':(0.214311, 90.856583, 0.21272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5780.0146875, 4595.10398438, 161.78857422), 'rotation':(0.217125, 90.85273, 0.215486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.09914062, 4589.42234375, 161.76686523), 'rotation':(0.218498, 90.856956, 0.216841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5780.26859375, 4578.05859375, 161.72260742), 'rotation':(0.223764, 90.856995, 0.222023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.5225, 4561.01269531, 161.65426758), 'rotation':(0.231796, 90.852104, 0.229939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.691875, 4549.64941406, 161.60739258), 'rotation':(0.237055, 90.852158, 0.235108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.84179688, 4532.6059375, 161.53610351999998), 'rotation':(0.242062, 90.859016, 0.240027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5789.50390625, 4529.3828125, 161.52189453), 'rotation':(-0.244507, -89.145813, -0.246582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5789.15578125, 4544.089375, 161.5837207), 'rotation':(-0.239777, -89.140991, -0.241791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5789.07078125, 4549.77148438, 161.60737305), 'rotation':(-0.238525, -89.147461, -0.24054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.73289062, 4572.49851562, 161.70008789), 'rotation':(-0.229034, -89.147827, -0.230865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.47851562, 4589.54445312, 161.7668457), 'rotation':(-0.22113, -89.147949, -0.222839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.3090625, 4600.90773438, 161.81011719), 'rotation':(-0.217133, -89.147308, -0.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.14015625, 4612.27101562, 161.85286133), 'rotation':(-0.214325, -89.143402, -0.215942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5788.05515625, 4617.95265625, 161.87375977), 'rotation':(-0.214325, -89.143402, -0.215942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5787.97070312, 4623.63476562, 161.89444336), 'rotation':(-0.20871, -89.146515, -0.210236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5787.631875, 4646.36132812, 161.97336914), 'rotation':(-0.194458, -89.148376, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5787.46289062, 4657.72507812, 162.01176758), 'rotation':(-0.192749, -89.148193, -0.194061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5787.2934375, 4669.08789062, 162.0487793), 'rotation':(-0.185669, -89.148254, -0.18689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.87015625, 4697.49707031, 162.13488281), 'rotation':(-0.166443, -89.145294, -0.167389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5786.53125, 4720.22363281, 162.19854492000002), 'rotation':(-0.152954, -89.148285, -0.153778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.36179688, 4731.58740234, 162.22800781), 'rotation':(-0.145477, -89.148315, -0.14621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5786.276875, 4737.26904297, 162.24212891), 'rotation':(-0.141479, -89.142975, -0.142212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5773.45898438, 5034.97314453, 162.42604492), 'rotation':(-0.079224, 90.852577, -0.079437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5773.71140625, 5018.02978516, 162.44691406), 'rotation':(-0.066345, 90.858047, -0.066498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5773.79539062, 5012.38183594, 162.45291016), 'rotation':(-0.062225, 90.852448, -0.062347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5773.96390625, 5001.0859375, 162.46365234), 'rotation':(-0.053619, 90.857925, -0.053711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.13234375, 4989.79003906, 162.47326171999998), 'rotation':(-0.045959, 90.855362, -0.046021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.21679688, 4984.14257812, 162.47729492), 'rotation':(-0.045959, 90.855362, -0.046021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5774.38476562, 4972.84667969, 162.48318359), 'rotation':(-0.024261, 90.855347, -0.024292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.55320312, 4961.55078125, 162.48640625), 'rotation':(-0.013367, 90.852051, -0.013367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5774.8896875, 4938.95898438, 162.48955078), 'rotation':(-0.007812, 90.852013, -0.007812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5774.97414062, 4933.31054688, 162.49032227), 'rotation':(-0.007904, 90.854919, -0.007904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.31054688, 4910.71972656, 162.48962891), 'rotation':(0.019616, 90.852089, 0.019603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.395, 4905.07177734, 162.48683594), 'rotation':(0.02868, 90.854362, 0.028644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.47898438, 4899.42382812, 162.48399414), 'rotation':(0.02881, 90.854294, 0.028784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.6475, 4888.12744141, 162.47833008), 'rotation':(0.028673, 90.854294, 0.028643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.8159375, 4876.83251953, 162.47189453000001), 'rotation':(0.033673, 90.854828, 0.033644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5775.98390625, 4865.53662109, 162.46287109000002), 'rotation':(0.043597, 90.851662, 0.043533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.06835938, 4859.88818359, 162.45760742000002), 'rotation':(0.053515, 90.854805, 0.05342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.40476562, 4837.29736328, 162.43142578), 'rotation':(0.06822, 90.856834, 0.068061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.48875, 4831.64941406, 162.42428711), 'rotation':(0.072666, 90.853897, 0.072477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.9096875, 4803.40966797, 162.38083008), 'rotation':(0.09845, 90.853973, 0.098117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5776.99414062, 4797.76220703, 162.37089844), 'rotation':(0.09845, 90.853973, 0.098117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.13625, 4784.84570312, 162.34749023), 'rotation':(0.102719, 90.854012, 0.102353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.95265625, 4826.12597656, 162.41648438), 'rotation':(-0.081207, -89.146057, -0.081421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.78421875, 4837.42236328, 162.43142578), 'rotation':(-0.072662, -89.146088, -0.072845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.36375, 4865.66113281, 162.46287109000002), 'rotation':(-0.053528, -89.148315, -0.053619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.1953125, 4876.95703125, 162.47189453000001), 'rotation':(-0.04361, -89.145203, -0.043671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5784.11132812, 4882.60546875, 162.47521484), 'rotation':(-0.033691, -89.145203, -0.033722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.026875, 4888.25244141, 162.47833008), 'rotation':(-0.033691, -89.145203, -0.033722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5783.0165625, 4956.02832031, 162.4872168), 'rotation':(0.007821, -89.145081, 0.007816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.93265625, 4961.67578125, 162.48640625), 'rotation':(0.007903, -89.145081, 0.007907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.84859375, 4967.32421875, 162.48507812), 'rotation':(0.01336, -89.147949, 0.013355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.68015625, 4978.61962891, 162.48074219), 'rotation':(0.024268, -89.144623, 0.024246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.09078125, 5018.15478516, 162.44691406), 'rotation':(0.062216, -89.147461, 0.06208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5782.006875, 5023.80273438, 162.44042969), 'rotation':(0.066335, -89.147522, 0.066181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.92234375, 5029.45068359, 162.43347656), 'rotation':(0.070631, -89.141937, 0.070455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5781.83835938, 5035.09863281, 162.42602539), 'rotation':(0.075112, -89.14743, 0.074908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.5859375, 5052.04248047, 162.40134766), 'rotation':(0.085712, -89.144562, 0.085463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5771.06789062, 5195.39453125, 162.06765625), 'rotation':(-0.174103, 90.852814, -0.175171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5771.15085938, 5189.84423828, 162.08445312), 'rotation':(-0.174103, 90.852814, -0.175171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5771.31640625, 5178.74316406, 162.11723633), 'rotation':(-0.165771, 90.853752, -0.166748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.06054688, 5128.79052734, 162.24964844), 'rotation':(-0.144318, 90.855789, -0.14505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.14304688, 5123.24023438, 162.26291992), 'rotation':(-0.13678, 90.852867, -0.137451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5772.22609375, 5117.69042969, 162.2756543), 'rotation':(-0.13678, 90.852867, -0.137451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.47414062, 5101.04003906, 162.31167969), 'rotation':(-0.121918, 90.852745, -0.122406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5781.10203125, 5084.51269531, 162.34567383), 'rotation':(0.109283, -89.145782, 0.108869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.77101562, 5106.71386719, 162.2999707), 'rotation':(0.118053, -89.144012, 0.117574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.52296875, 5123.36425781, 162.26291992), 'rotation':(0.129439, -89.144226, 0.128849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.44046875, 5128.91455078, 162.24964844), 'rotation':(0.136775, -89.147156, 0.136129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5780.35742188, 5134.46533203, 162.23599609000001), 'rotation':(0.136775, -89.147156, 0.136129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5780.109375, 5151.11523438, 162.19337890999998), 'rotation':(0.14801, -89.146423, 0.147247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5779.94382812, 5162.21630859, 162.16390625), 'rotation':(0.15301, -89.146393, 0.152192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.86132812, 5167.76660156, 162.14868164), 'rotation':(0.156172, -89.146301, 0.155325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.77828125, 5173.31689453, 162.13311523000002), 'rotation':(0.159294, -89.146362, 0.15842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.44726562, 5195.51806641, 162.06765625), 'rotation':(0.172387, -89.146301, 0.171358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5779.36914062, 5200.76367188, 162.05172851999998), 'rotation':(0.174102, -89.147156, 0.173054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5766.5434375, 5499.00734375, 160.97911133), 'rotation':(-0.200897, 90.853966, -0.202332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5766.7959375, 5482.04589844, 161.03874023), 'rotation':(-0.202454, 90.854652, -0.203888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5766.964375, 5470.73828125, 161.07902344000001), 'rotation':(-0.205292, 90.854721, -0.206787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5767.04882812, 5465.08496094, 161.09942383), 'rotation':(-0.205292, 90.854721, -0.206787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.30171875, 5448.12351562, 161.16160156), 'rotation':(-0.21109, 90.854721, -0.212646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.4696875, 5436.8159375, 161.20356445), 'rotation':(-0.212555, 90.858223, -0.214142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5767.63867188, 5425.50828125, 161.24568359), 'rotation':(-0.213074, 90.854637, -0.214661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.80710938, 5414.20070312, 161.28808594), 'rotation':(-0.214294, 90.854637, -0.215912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.89109375, 5408.546875, 161.30935546999999), 'rotation':(-0.215515, 90.854652, -0.217133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.3125, 5380.27882812, 161.41641601999999), 'rotation':(-0.216919, 90.85511, -0.218597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.4809375, 5368.97117188, 161.45912109), 'rotation':(-0.216217, 90.855087, -0.217865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.56546875, 5363.31738281, 161.48038086), 'rotation':(-0.215515, 90.85228, -0.217163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.90234375, 5340.70265625, 161.56520508), 'rotation':(-0.214539, 90.854179, -0.216156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5768.98679688, 5335.04929688, 161.58636719), 'rotation':(-0.214508, 90.859558, -0.216125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.1553125, 5323.74267578, 161.62858398), 'rotation':(-0.213104, 90.85244, -0.214661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5769.23976562, 5318.08886719, 161.64953125), 'rotation':(-0.213104, 90.85244, -0.214661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.40820312, 5306.78125, 161.6909375), 'rotation':(-0.210083, 90.855339, -0.211639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.4921875, 5301.12744141, 161.71151367000002), 'rotation':(-0.208679, 90.855095, -0.210175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.8290625, 5278.51269531, 161.79313477), 'rotation':(-0.203796, 90.857819, -0.205231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5769.99757812, 5267.20654297, 161.83291992), 'rotation':(-0.201599, 90.853157, -0.203033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5770.25046875, 5250.24511719, 161.8912207), 'rotation':(-0.19577, 90.853119, -0.197113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5770.39890625, 5240.27929688, 161.92483398000002), 'rotation':(-0.192688, 90.856255, -0.19397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.006875, 5493.47753906, 160.99894531), 'rotation':(0.200917, -89.14267, 0.199509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5775.09132812, 5487.82375, 161.0187793), 'rotation':(0.20244, -89.145294, 0.201016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.1753125, 5482.16992188, 161.03874023), 'rotation':(0.205302, -89.148193, 0.203832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5775.93359375, 5431.28664062, 161.22458984000002), 'rotation':(0.214277, -89.145325, 0.212687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.01804688, 5425.63234375, 161.24568359), 'rotation':(0.214277, -89.145325, 0.212687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.1865625, 5414.32519531, 161.28808594), 'rotation':(0.215499, -89.145325, 0.213882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.355, 5403.01804688, 161.33073242), 'rotation':(0.217255, -89.145966, 0.215612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.43945312, 5397.36425781, 161.3521582), 'rotation':(0.217255, -89.145966, 0.215612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5776.86085938, 5369.09570312, 161.45912109), 'rotation':(0.21552, -89.144897, 0.213896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5776.94484375, 5363.44238281, 161.48038086), 'rotation':(0.214891, -89.147766, 0.213294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.11328125, 5352.13476562, 161.5228418), 'rotation':(0.214536, -89.145813, 0.212927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.61914062, 5318.21289062, 161.64953125), 'rotation':(0.210069, -89.147583, 0.208543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5777.78757812, 5306.90625, 161.6909375), 'rotation':(0.208649, -89.144958, 0.207135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5777.95554688, 5295.59863281, 161.73211914), 'rotation':(0.207713, -89.14679, 0.206214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.12453125, 5284.29150391, 161.77296875), 'rotation':(0.203779, -89.14682, 0.202343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5778.20851562, 5278.63769531, 161.79313477), 'rotation':(0.2016, -89.146851, 0.200195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.29296875, 5272.98388672, 161.813125), 'rotation':(0.199701, -89.146851, 0.198325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5778.62984375, 5250.36962891, 161.8912207), 'rotation':(0.193745, -89.146912, 0.192443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5587.11132812, 5060.3828125, 158.78357422), 'rotation':(-1.028687, -179.25386, -1.066132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5598.19140625, 5060.52294922, 158.98393555), 'rotation':(-1.033478, -179.255325, -1.071289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5614.80859375, 5060.73339844, 159.28863281), 'rotation':(-1.053284, -179.254593, -1.09256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5620.348125, 5060.80322266, 159.39148438), 'rotation':(-1.063049, -179.254227, -1.103088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5631.42675781, 5060.94384766, 159.59792969), 'rotation':(-1.068115, -179.253311, -1.108521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5653.58351562, 5061.22412109, 160.01191406), 'rotation':(-1.072113, -179.253998, -1.112823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5659.12257812, 5061.29443359, 160.11645508), 'rotation':(-1.080353, -179.253754, -1.121704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5670.20117188, 5061.43457031, 160.32625), 'rotation':(-1.084381, -179.256378, -1.126038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5675.73976562, 5061.50488281, 160.43113281), 'rotation':(-1.08429, -179.251617, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5686.81789062, 5061.64501953, 160.64109375), 'rotation':(-1.086517, -179.252777, -1.128326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5708.97414062, 5061.92578125, 161.06358398), 'rotation':(-1.095154, -179.255493, -1.137634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5742.20703125, 5062.37988281, 161.70261719), 'rotation':(-1.101685, -179.252274, -1.144714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5747.74609375, 5062.45019531, 161.80924805), 'rotation':(-1.102356, -179.255859, -1.145416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5753.2846875, 5062.52001953, 161.91599609000002), 'rotation':(-1.103546, -179.252548, -1.146729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5758.82617188, 5062.42041016, 162.02279296999998), 'rotation':(-1.104462, -179.252731, -1.147705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5747.69289062, 5070.79833984, 161.81027344), 'rotation':(1.103629, 0.747476, 1.0617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5708.92039062, 5070.30761719, 161.06457031), 'rotation':(1.09951, 0.747716, 1.057894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5703.381875, 5070.23730469, 160.95865234000001), 'rotation':(1.095146, 0.744508, 1.053861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5697.84226562, 5070.16699219, 160.85286133), 'rotation':(1.095146, 0.744508, 1.053861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5681.22507812, 5069.95654297, 160.53702148), 'rotation':(1.086505, 0.74722, 1.045869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5675.6865625, 5069.88623047, 160.43214844), 'rotation':(1.084443, 0.743563, 1.043949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5664.6084375, 5069.74609375, 160.22235351999998), 'rotation':(1.084292, 0.743557, 1.04381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5659.06984375, 5069.67626953, 160.11748047), 'rotation':(1.084388, 0.748439, 1.043899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5647.99070312, 5069.53564453, 159.90899414), 'rotation':(1.072135, 0.745989, 1.032548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5636.91113281, 5069.39550781, 159.70219727), 'rotation':(1.06805, 0.742034, 1.028767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5631.37257812, 5069.32519531, 159.59889648), 'rotation':(1.06805, 0.742034, 1.028767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5620.29296875, 5069.18505859, 159.39242188), 'rotation':(1.06805, 0.746751, 1.028769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5614.754375, 5069.11474609, 159.28960938), 'rotation':(1.063057, 0.745755, 1.024144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5609.2153125, 5069.04443359, 159.18751953), 'rotation':(1.063057, 0.745755, 1.024144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5598.13671875, 5068.90429688, 158.98488281), 'rotation':(1.043462, 0.745036, 1.005962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5587.058125, 5068.76318359, 158.78453125), 'rotation':(1.033469, 0.741506, 0.996674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5796.88085938, 5063.03955078, 162.75662109), 'rotation':(-1.103912, -179.25415, -1.147095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5802.45460938, 5063.10986328, 162.86393555), 'rotation':(-1.102783, -179.249023, -1.145874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5808.02828125, 5063.18066406, 162.97124023), 'rotation':(-1.102295, -179.254333, -1.145355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5835.89648438, 5063.53369141, 163.50764648), 'rotation':(-1.102386, -179.254333, -1.145447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5841.47023438, 5063.60449219, 163.61483398000001), 'rotation':(-1.101135, -179.251663, -1.144104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5847.04390625, 5063.67480469, 163.72183594), 'rotation':(-1.101135, -179.251663, -1.144104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5852.6171875, 5063.74560547, 163.82875), 'rotation':(-1.098602, -179.254868, -1.141357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.19140625, 5063.81591797, 163.93558593999998), 'rotation':(-1.097565, -179.25177, -1.140228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5863.76515625, 5063.88671875, 164.04240234), 'rotation':(-1.097565, -179.25177, -1.140228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5880.4853125, 5064.09814453, 164.36253906000002), 'rotation':(-1.095459, -179.249146, -1.137939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5908.35453125, 5064.45117188, 164.89349609), 'rotation':(-1.088623, -179.249405, -1.130585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.50148438, 5064.59228516, 165.10501953), 'rotation':(-1.086487, -179.255402, -1.128296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.649375, 5064.72460938, 165.31644531), 'rotation':(-1.086487, -179.252045, -1.128296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5947.36960938, 5064.97851562, 165.63205078), 'rotation':(-1.078705, -179.25386, -1.119904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5952.94335938, 5065.04931641, 165.73677734), 'rotation':(-1.07608, -179.25592, -1.117096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.8125, 5065.40234375, 166.26046875), 'rotation':(-1.075989, -179.252655, -1.116974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56101562, 5073.96337891, 166.57578125), 'rotation':(1.069327, 0.748385, 1.02997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.68164062, 5073.61035156, 166.05330078), 'rotation':(1.07598, 0.747351, 1.036122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.52976562, 5073.46875, 165.84375), 'rotation':(1.07598, 0.747351, 1.036122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.80226562, 5073.25683594, 165.52917968999998), 'rotation':(1.078637, 0.746098, 1.038579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.65085938, 5073.11572266, 165.31845703), 'rotation':(1.083842, 0.746334, 1.043398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5925.07515625, 5073.04492188, 165.21279297), 'rotation':(1.083842, 0.746334, 1.043398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.348125, 5072.83349609, 164.89539062), 'rotation':(1.087141, 0.745333, 1.046449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.19625, 5072.69189453, 164.68335938), 'rotation':(1.089907, 0.745439, 1.049007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.62015625, 5072.62158203, 164.57712891), 'rotation':(1.091307, 0.745556, 1.050308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5880.46875, 5072.48046875, 164.36427734), 'rotation':(1.094142, 0.745596, 1.05293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5874.89359375, 5072.40966797, 164.25763672000002), 'rotation':(1.095439, 0.750858, 1.054135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5869.31789062, 5072.33935547, 164.15087891), 'rotation':(1.096901, 0.745701, 1.05549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5863.7421875, 5072.26855469, 164.04402344), 'rotation':(1.09755, 0.744917, 1.056086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5858.16601562, 5072.19775391, 163.93712890999998), 'rotation':(1.09755, 0.744917, 1.056086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5824.711875, 5071.77392578, 163.29445312), 'rotation':(1.102399, 0.745673, 1.06056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5819.13625, 5071.70361328, 163.18711914), 'rotation':(1.10229, 0.749052, 1.060465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5807.98390625, 5071.56201172, 162.97243164), 'rotation':(1.10229, 0.745669, 1.060462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.930625, 4353.41796875, 163.50040038999998), 'rotation':(-0.931824, -179.93602, -0.962524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5964.29492188, 4353.40476562, 163.23107421999998), 'rotation':(-0.916718, -179.939941, -0.946411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.75, 4353.40039062, 163.14233398), 'rotation':(-0.916656, -179.939941, -0.94635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5942.11421875, 4353.38769531, 162.87706055), 'rotation':(-0.895264, -179.940262, -0.923584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.93359375, 4353.37011719, 162.53255859), 'rotation':(-0.866516, -179.944, -0.893036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5914.38914062, 4353.36570312, 162.44868164), 'rotation':(-0.859558, -179.939407, -0.88562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.84179688, 4353.36132812, 162.3649707), 'rotation':(-0.859558, -179.939407, -0.88562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.7509375, 4353.35304688, 162.19957031), 'rotation':(-0.847107, -179.942062, -0.872437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5892.20609375, 4353.34863281, 162.1178418), 'rotation':(-0.83902, -179.946838, -0.863892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5886.660625, 4353.34421875, 162.03681641), 'rotation':(-0.830719, -179.942535, -0.855103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5858.93265625, 4353.32273438, 161.64251953000002), 'rotation':(-0.793854, -179.949753, -0.816101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5842.29390625, 4353.30957031, 161.4147168), 'rotation':(-0.765533, -179.946304, -0.786224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5836.74757812, 4353.30515625, 161.34104492), 'rotation':(-0.753937, -179.946625, -0.773987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5831.19921875, 4353.30078125, 161.26855469), 'rotation':(-0.731049, -179.947205, -0.749878), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5820.1084375, 4353.29199219, 161.12714844), 'rotation':(-0.708313, -179.947784, -0.725983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5814.5625, 4353.28757812, 161.05821289), 'rotation':(-0.702698, -179.945999, -0.720093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5803.4696875, 4353.27882812, 160.92201172), 'rotation':(-0.702698, -179.945999, -0.720093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56203125, 4361.81152344, 163.77701172), 'rotation':(0.925784, 0.014961, 0.896226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5992.01859375, 4361.80710938, 163.684375), 'rotation':(0.956985, 0.061185, 0.925406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.47359375, 4361.80273438, 163.59204102), 'rotation':(0.951944, 0.059749, 0.920692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5975.3828125, 4361.79445312, 163.40982422), 'rotation':(0.931836, 0.059089, 0.901876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5942.11085938, 4361.76855469, 162.87710938), 'rotation':(0.90946, 0.057331, 0.880918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.9296875, 4361.75097656, 162.53260742), 'rotation':(0.880848, 0.059296, 0.85406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.83789062, 4361.7421875, 162.36500977), 'rotation':(0.866512, 0.055997, 0.8406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.7465625, 4361.73390625, 162.19959961), 'rotation':(0.855181, 0.058168, 0.829941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5892.20117188, 4361.72949219, 162.11787109), 'rotation':(0.847107, 0.057927, 0.822333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5886.65625, 4361.72507812, 162.03686523), 'rotation':(0.839096, 0.053156, 0.814781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5875.5634375, 4361.71632812, 161.87689453000002), 'rotation':(0.822642, 0.057219, 0.799273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5870.01804688, 4361.71191406, 161.79804688000002), 'rotation':(0.814363, 0.056979, 0.791452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5864.47265625, 4361.7075, 161.71994141), 'rotation':(0.806276, 0.05675, 0.783821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5842.288125, 4361.69042969, 161.41473632999998), 'rotation':(0.776838, 0.053983, 0.755978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5836.74171875, 4361.68601562, 161.34106445), 'rotation':(0.765548, 0.053684, 0.745284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5831.19335938, 4361.68164062, 161.26857422), 'rotation':(0.742646, 0.05851, 0.723579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5825.6475, 4361.67726562, 161.19726562), 'rotation':(0.731049, 0.052777, 0.712559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5814.55617188, 4361.66796875, 161.05821289), 'rotation':(0.708304, 0.052205, 0.690956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5809.00828125, 4361.66359375, 160.99001953), 'rotation':(0.702731, 0.053994, 0.685641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5803.46289062, 4361.65917969, 160.92201172), 'rotation':(0.702731, 0.053994, 0.685641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5510.05617188, 4503.75734375, 158.28889648), 'rotation':(-0.454193, -179.930908, -0.461456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5515.70265625, 4503.76367188, 158.33369141), 'rotation':(-0.454224, -179.935577, -0.461487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5521.34914062, 4503.77, 158.37907227), 'rotation':(-0.458923, -179.932068, -0.466309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5532.64210938, 4503.78273438, 158.47291992), 'rotation':(-0.478149, -179.931747, -0.486176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5543.93507812, 4503.79539062, 158.57083008), 'rotation':(-0.49762, -179.931427, -0.506317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5549.5815625, 4503.80125, 158.62131836), 'rotation':(-0.516785, -179.931076, -0.526184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5555.22753906, 4503.80761719, 158.67282226999998), 'rotation':(-0.52655, -179.930908, -0.536285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5583.45800781, 4503.839375, 158.93893555), 'rotation':(-0.555023, -179.932251, -0.565857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5589.105, 4503.84570312, 158.9946875), 'rotation':(-0.555023, -179.932251, -0.565857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5594.75097656, 4503.85203125, 159.05097656), 'rotation':(-0.570984, -179.92897, -0.582458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5600.39648438, 4503.85789062, 159.10880859), 'rotation':(-0.586945, -179.931625, -0.59906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5606.0434375, 4503.86425781, 159.16693359), 'rotation':(-0.586945, -179.931625, -0.59906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5617.33496094, 4503.87695312, 159.28445312), 'rotation':(-0.594849, -179.929855, -0.6073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5622.9809375, 4503.88328125, 159.34404297), 'rotation':(-0.604492, -179.930542, -0.617371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5628.62695312, 4503.88964844, 159.40475586), 'rotation':(-0.604492, -179.930542, -0.617371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5651.2109375, 4503.91453125, 159.65831055), 'rotation':(-0.662506, -179.92926, -0.677948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5673.79390625, 4503.93992188, 159.92385742), 'rotation':(-0.680786, -179.926743, -0.697113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5679.43992188, 4503.94628906, 159.99213867), 'rotation':(-0.680786, -179.926743, -0.697113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5690.73140625, 4503.95898438, 160.13157227), 'rotation':(-0.714996, -179.929016, -0.733032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5696.37742188, 4503.9653125, 160.20292969), 'rotation':(-0.714996, -179.929016, -0.733032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5713.3134375, 4503.9809375, 160.42123046999998), 'rotation':(-0.740631, -179.927811, -0.759949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5730.25, 4504.03027344, 160.64580078), 'rotation':(-0.765594, -179.92363, -0.786285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5735.89601562, 4504.0425, 160.72251953), 'rotation':(-0.775452, -179.928101, -0.796631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5747.1865625, 4504.05515625, 160.87874023), 'rotation':(-0.795349, -179.927551, -0.817657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5752.83203125, 4504.06101562, 160.95827148), 'rotation':(-0.805206, -179.922562, -0.828094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5764.12257812, 4504.07375, 161.11951172), 'rotation':(-0.82019, -179.921005, -0.843933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5769.76757812, 4504.08007812, 161.20045898), 'rotation':(-0.820251, -179.926193, -0.843994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5752.85546875, 4512.40917969, 160.95874023), 'rotation':(0.81532, 0.073007, 0.792351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5747.21, 4512.40332031, 160.87920898000002), 'rotation':(0.805218, 0.077441, 0.782814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5735.91945312, 4512.390625, 160.72295898000002), 'rotation':(0.785369, 0.076893, 0.764058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5724.62648438, 4512.37792969, 160.57041992), 'rotation':(0.765603, 0.076357, 0.745349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5707.6884375, 4512.35890625, 160.34838867), 'rotation':(0.745631, 0.075827, 0.726409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5690.7509375, 4512.33984375, 160.13194336), 'rotation':(0.732053, 0.074504, 0.713525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.16796875, 4512.31445312, 159.85708984000001), 'rotation':(0.680792, 0.073242, 0.664755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5628.64304688, 4512.27050781, 159.4050293), 'rotation':(0.623822, 0.072726, 0.610347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5622.9965625, 4512.26414062, 159.34429688), 'rotation':(0.623822, 0.072726, 0.610347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5617.35109375, 4512.2578125, 159.28472656), 'rotation':(0.604499, 0.069446, 0.591857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5611.70359375, 4512.25148438, 159.22580078000001), 'rotation':(0.594841, 0.070138, 0.582594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5589.11960938, 4512.2265625, 158.99495117), 'rotation':(0.570983, 0.071017, 0.559686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5583.47070312, 4512.22023438, 158.93915039), 'rotation':(0.570983, 0.071017, 0.559686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5572.17921875, 4512.2075, 158.83076172), 'rotation':(0.555035, 0.06773, 0.54436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5566.53367188, 4512.20117188, 158.77763672), 'rotation':(0.53923, 0.070394, 0.529159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5532.651875, 4512.16308594, 158.47306641), 'rotation':(0.48786, 0.068402, 0.4796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56445312, 4512.68210938, 165.01263672000002), 'rotation':(1.053707, 0.086572, 1.015457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.98585938, 4512.67578125, 164.91029297), 'rotation':(1.049438, 0.083299, 1.011512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.24851562, 4512.65722656, 164.60509765999998), 'rotation':(1.040873, 0.08298, 1.003555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.61328125, 4512.60742188, 163.80584961), 'rotation':(1.013491, 0.083247, 0.978107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.4540625, 4512.59472656, 163.61072266), 'rotation':(0.996852, 0.079035, 0.962601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5902.71578125, 4512.57617188, 163.32040039), 'rotation':(0.992659, 0.080826, 0.958701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.5546875, 4512.56398438, 163.12804688), 'rotation':(0.986313, 0.081539, 0.952776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5885.975625, 4512.55761719, 163.03325195), 'rotation':(0.973404, 0.081093, 0.940734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5869.23679688, 4512.5390625, 162.75276367), 'rotation':(0.960441, 0.080653, 0.928643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.07664062, 4512.526875, 162.56882812), 'rotation':(0.941261, 0.080607, 0.910703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5846.91648438, 4512.51414062, 162.38604492000002), 'rotation':(0.937382, 0.07636, 0.907079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5841.33640625, 4512.5078125, 162.29573242), 'rotation':(0.929589, 0.081656, 0.899779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5830.1753125, 4512.49511719, 162.11759766), 'rotation':(0.906387, 0.08091, 0.878039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5819.015625, 4512.48289062, 161.9428125), 'rotation':(0.8908, 0.08042, 0.863414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5807.85453125, 4512.47023438, 161.77094727), 'rotation':(0.879114, 0.077815, 0.852448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5802.27539062, 4512.464375, 161.68533203), 'rotation':(0.879114, 0.077815, 0.852448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5807.828125, 4504.089375, 161.77041992), 'rotation':(-0.87912, -179.92218, -0.906433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5813.40820312, 4504.09570312, 161.85607421999998), 'rotation':(-0.87912, -179.92218, -0.906433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5863.62453125, 4504.151875, 162.65985351999998), 'rotation':(-0.941254, -179.919388, -0.972565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5869.20460938, 4504.15820312, 162.75207031), 'rotation':(-0.947723, -179.922836, -0.979492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5880.36328125, 4504.17039062, 162.93823242), 'rotation':(-0.960449, -179.919342, -0.993073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.52195312, 4504.18261719, 163.12735351999999), 'rotation':(-0.973419, -179.9189, -1.006927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5902.68117188, 4504.1953125, 163.3196582), 'rotation':(-0.986328, -179.918457, -1.020721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.99757812, 4504.22023438, 163.70713867), 'rotation':(-0.996857, -179.920975, -1.032013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.7353125, 4504.234375, 164.00253906), 'rotation':(-1.013489, -179.916748, -1.049835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5947.31398438, 4504.254375, 164.10208984000002), 'rotation':(-1.021881, -179.920074, -1.058838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5958.47171875, 4504.29054688, 164.30212891), 'rotation':(-1.028137, -179.917465, -1.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5964.05078125, 4504.296875, 164.4025), 'rotation':(-1.028137, -179.917465, -1.065552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.629375, 4504.30320312, 164.50318359000002), 'rotation':(-1.032379, -179.917328, -1.070099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.20851562, 4504.3090625, 164.60419922), 'rotation':(-1.036621, -179.921173, -1.074677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.36625, 4504.32179688, 164.80734375), 'rotation':(-1.045258, -179.916855, -1.083923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.9453125, 4504.328125, 164.909375), 'rotation':(-1.045258, -179.916855, -1.083923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.52390625, 4504.33398438, 165.01173828), 'rotation':(-1.049438, -179.916702, -1.08844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5765.37203125, 4764.97314453, 161.99801758), 'rotation':(1.05314, 0.370782, 1.014947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5748.38039062, 4764.86914062, 161.69026367), 'rotation':(1.031502, 0.366815, 0.99485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5731.390625, 4764.765625, 161.38638672), 'rotation':(1.024303, 0.370801, 0.988151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5725.72703125, 4764.73046875, 161.28524414), 'rotation':(1.021202, 0.372082, 0.985266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5714.39890625, 4764.66113281, 161.08473633), 'rotation':(1.00871, 0.36616, 0.973638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5708.73632812, 4764.62646484, 160.98551758), 'rotation':(1.002672, 0.371423, 0.968037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5697.40820312, 4764.55712891, 160.78914062), 'rotation':(0.990268, 0.370997, 0.956468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5686.07960938, 4764.48779297, 160.59535156), 'rotation':(0.977701, 0.370563, 0.944744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5657.75875, 4764.31445312, 160.11723633), 'rotation':(0.955004, 0.365055, 0.923544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5629.43945312, 4764.14111328, 159.65803711), 'rotation':(0.92213, 0.366124, 0.892784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5623.7734375, 4764.10644531, 159.56730469000001), 'rotation':(0.92213, 0.366124, 0.892784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5606.78125, 4764.00244141, 159.29896484), 'rotation':(0.901701, 0.366723, 0.873646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5601.1171875, 4763.96777344, 159.21113281), 'rotation':(0.888027, 0.363424, 0.860819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5595.453125, 4763.93310547, 159.12416016), 'rotation':(0.888027, 0.363424, 0.860819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5584.12304688, 4763.86376953, 158.95181641), 'rotation':(0.867625, 0.365906, 0.841642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5578.4575, 4763.82910156, 158.86626953), 'rotation':(0.863029, 0.36281, 0.837306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5555.79785156, 4763.69042969, 158.53234375), 'rotation':(0.826248, 0.36665, 0.802677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5550.13328125, 4763.65576172, 158.45114258), 'rotation':(0.817246, 0.361497, 0.794177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5544.46875, 4763.62109375, 158.37083008), 'rotation':(0.807943, 0.361203, 0.785395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5538.80761719, 4755.20556641, 158.29077148), 'rotation':(-0.794189, -179.641113, -0.816437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5550.13523438, 4755.27490234, 158.45041992), 'rotation':(-0.808014, -179.638763, -0.831055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5555.79980469, 4755.30957031, 158.53163086), 'rotation':(-0.817169, -179.638535, -0.840759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5567.129375, 4755.37890625, 158.69675781), 'rotation':(-0.83548, -179.638016, -0.860138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5578.4575, 4755.44824219, 158.86549805), 'rotation':(-0.85379, -179.632538, -0.879547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5589.78710938, 4755.51757812, 159.03688477), 'rotation':(-0.867584, -179.637787, -0.894165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5595.45070312, 4755.55224609, 159.12334961), 'rotation':(-0.874359, -179.634125, -0.901367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5612.44335938, 4755.65625, 159.38683594), 'rotation':(-0.888031, -179.636566, -0.915894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5618.10695312, 4755.69091797, 159.47601562), 'rotation':(-0.901703, -179.636154, -0.93042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5623.77101562, 4755.72558594, 159.56645508), 'rotation':(-0.915314, -179.632828, -0.944946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5635.09863281, 4755.79492188, 159.74832031), 'rotation':(-0.922119, -179.633865, -0.952179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5640.76269531, 4755.82958984, 159.83951172), 'rotation':(-0.922119, -179.637527, -0.952179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5652.0903125, 4755.89892578, 160.02316406), 'rotation':(-0.928741, -179.632111, -0.959229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5663.41796875, 4755.96826172, 160.21058594), 'rotation':(-0.954987, -179.631241, -0.987244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5669.08203125, 4756.00292969, 160.30574219), 'rotation':(-0.954987, -179.631241, -0.987244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5674.74609375, 4756.03564453, 160.40161133), 'rotation':(-0.968018, -179.634521, -1.00119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5691.73632812, 4756.16894531, 160.6909668), 'rotation':(-0.977722, -179.634888, -1.011505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5697.399375, 4756.20898438, 160.78810547), 'rotation':(-0.983917, -179.629272, -1.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5703.06398438, 4756.24365234, 160.8859375), 'rotation':(-0.990295, -179.634445, -1.024963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5708.72703125, 4756.27832031, 160.98445312), 'rotation':(-0.996399, -179.628799, -1.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5714.39109375, 4756.31298828, 161.08371094), 'rotation':(-1.002594, -179.634064, -1.038147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5742.7075, 4756.48632812, 161.58787109000002), 'rotation':(-1.024384, -179.634659, -1.061554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5754.03421875, 4756.55566406, 161.79104492), 'rotation':(-1.031494, -179.630005, -1.069183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5759.69773438, 4756.59033203, 161.89344727), 'rotation':(-1.031494, -179.630005, -1.069183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5797.87257812, 4756.79199219, 162.59607422), 'rotation':(-1.064362, -179.629852, -1.104462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5808.964375, 4756.85986328, 162.80325195), 'rotation':(-1.073303, -179.629517, -1.114105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5820.05617188, 4756.92724609, 163.01234375), 'rotation':(-1.082092, -179.629196, -1.123566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5825.6015625, 4756.96142578, 163.11767578), 'rotation':(-1.082092, -179.629196, -1.123566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5836.69382812, 4757.02929688, 163.32936523), 'rotation':(-1.095398, -179.628647, -1.137909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.87648438, 4757.16455078, 163.75420898000002), 'rotation':(-1.102264, -179.627853, -1.145325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5864.4228125, 4757.19873047, 163.86128906000002), 'rotation':(-1.102264, -179.627853, -1.145325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5869.96875, 4757.23291016, 163.96871094), 'rotation':(-1.109009, -179.628799, -1.152557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5875.5146875, 4757.26660156, 164.07611328), 'rotation':(-1.109009, -179.628799, -1.152557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5881.05953125, 4757.30078125, 164.18349609), 'rotation':(-1.109009, -179.628799, -1.152557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5892.15085938, 4757.36865234, 164.39826172000002), 'rotation':(-1.108887, -179.628799, -1.152466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5897.69625, 4757.40234375, 164.50576172), 'rotation':(-1.108887, -179.628799, -1.152466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5903.24171875, 4757.43310547, 164.6134375), 'rotation':(-1.110931, -179.626938, -1.154663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.78664062, 4757.45996094, 164.72142578), 'rotation':(-1.114624, -179.626801, -1.158661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5914.33296875, 4757.52929688, 164.82974609000001), 'rotation':(-1.118469, -179.631042, -1.162811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.87796875, 4757.57080078, 164.93841797000002), 'rotation':(-1.122162, -179.626495, -1.166809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5925.42335938, 4757.60498047, 165.04724609000002), 'rotation':(-1.124146, -179.627838, -1.168945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5930.96875, 4757.63867188, 165.15607422000002), 'rotation':(-1.123993, -179.627838, -1.168762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5936.5146875, 4757.67285156, 165.26496093999998), 'rotation':(-1.123993, -179.62262, -1.168762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5947.6059375, 4757.74072266, 165.48273438), 'rotation':(-1.124908, -179.6297, -1.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5953.151875, 4757.77490234, 165.59179688), 'rotation':(-1.124908, -179.6297, -1.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5964.2421875, 4757.84277344, 165.81017577999998), 'rotation':(-1.128296, -179.626038, -1.173431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.33296875, 4757.91064453, 166.02904297), 'rotation':(-1.130188, -179.625977, -1.175446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.879375, 4757.94433594, 166.13857422), 'rotation':(-1.131012, -179.627975, -1.176361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.515625, 4758.04638672, 166.46716797000002), 'rotation':(-1.131042, -179.627991, -1.176392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56789062, 4766.39501953, 166.46919922), 'rotation':(1.131066, 0.368807, 1.087042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5986.47507812, 4766.32714844, 166.25011718999997), 'rotation':(1.131059, 0.37199, 1.087032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5980.92875, 4766.29345703, 166.14056641), 'rotation':(1.131018, 0.375692, 1.086994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5975.381875, 4766.25927734, 166.03101562), 'rotation':(1.130943, 0.371986, 1.086926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5953.19578125, 4766.12353516, 165.59365234), 'rotation':(1.12681, 0.373913, 1.083115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5936.555625, 4766.02148438, 165.26677734), 'rotation':(1.124153, 0.372162, 1.080657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5931.00929688, 4765.98730469, 165.15789062), 'rotation':(1.123996, 0.372153, 1.08051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5925.46242188, 4765.95361328, 165.04900390999998), 'rotation':(1.123996, 0.372153, 1.08051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.91554688, 4765.91943359, 164.94015625), 'rotation':(1.124256, 0.372193, 1.08076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5914.36867188, 4765.88574219, 164.83144531000002), 'rotation':(1.122084, 0.37346, 1.078753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5908.82179688, 4765.8515625, 164.72310547), 'rotation':(1.118464, 0.373349, 1.075407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5897.72804688, 4765.78369141, 164.50736328), 'rotation':(1.110923, 0.373052, 1.068447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5886.63375, 4765.71582031, 164.29244140999998), 'rotation':(1.108874, 0.371196, 1.066553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5875.54054688, 4765.64794922, 164.07759765999998), 'rotation':(1.10897, 0.371199, 1.066652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5864.44773438, 4765.58007812, 163.86277343999998), 'rotation':(1.109052, 0.374556, 1.066705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5858.89992188, 4765.54638672, 163.75566406), 'rotation':(1.109052, 0.374556, 1.066705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5853.3525, 4765.51220703, 163.64898438), 'rotation':(1.102188, 0.372124, 1.060372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.80617188, 4765.47851562, 163.54289062), 'rotation':(1.095474, 0.371383, 1.054169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5814.52390625, 4765.27441406, 162.90876953), 'rotation':(1.082066, 0.370806, 1.041754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5808.97609375, 4765.24072266, 162.80444336), 'rotation':(1.082066, 0.370806, 1.041754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5797.88234375, 4765.17236328, 162.5972168), 'rotation':(1.073316, 0.370487, 1.033648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5733.10546875, 5518.66894531, 160.218125), 'rotation':(1.08546, 0.270561, 1.044903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5743.390625, 5518.79539062, 160.41319336), 'rotation':(1.083159, 0.273882, 1.042767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5691.08109375, 5518.43992188, 159.41905273), 'rotation':(1.089265, 0.270588, 1.048408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5685.538125, 5518.41554688, 159.31363281), 'rotation':(1.089265, 0.270588, 1.048408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5679.995625, 5518.39160156, 159.20819336), 'rotation':(1.089354, 0.270272, 1.048494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.91015625, 5518.34328125, 158.99733398), 'rotation':(1.089354, 0.273642, 1.0485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5663.36765625, 5518.31882812, 158.89189453), 'rotation':(1.089313, 0.270284, 1.048458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5657.8246875, 5518.29445312, 158.78645508), 'rotation':(1.089354, 0.270272, 1.048494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5646.73925781, 5518.24609375, 158.57614258), 'rotation':(1.086936, 0.275592, 1.046264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5641.19773438, 5518.23390625, 158.47149414), 'rotation':(1.082155, 0.271165, 1.041839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.65527344, 5518.26125, 158.36700195), 'rotation':(1.079662, 0.269864, 1.039522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5624.566875, 5518.27882812, 158.15793945), 'rotation':(1.07973, 0.269886, 1.039589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5624.56492188, 5509.63867188, 158.15719726999998), 'rotation':(-1.079773, -179.730118, -1.121094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5630.10984375, 5509.67625, 158.26173828), 'rotation':(-1.079742, -179.730103, -1.121033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5635.65234375, 5509.75242188, 158.36624023000002), 'rotation':(-1.079773, -179.730118, -1.121094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5641.19433594, 5509.828125, 158.47073242), 'rotation':(-1.079651, -179.726105, -1.120941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5646.73679688, 5509.86523438, 158.57541016), 'rotation':(-1.082184, -179.728821, -1.123657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5652.27929688, 5509.88914062, 158.68040039), 'rotation':(-1.082184, -179.728821, -1.123657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5668.90820312, 5509.96242188, 158.99658203), 'rotation':(-1.089325, -179.726334, -1.131348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5674.45117188, 5509.98632812, 159.10202148), 'rotation':(-1.089325, -179.726334, -1.131348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5685.53710938, 5510.03515625, 159.31290038999998), 'rotation':(-1.089355, -179.729721, -1.131409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5713.25148438, 5510.15625, 159.84), 'rotation':(-1.088867, -179.727737, -1.13089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5718.79390625, 5510.18066406, 159.94537109), 'rotation':(-1.089081, -179.727722, -1.131073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5724.336875, 5510.20507812, 160.05080078), 'rotation':(-1.08905, -179.733322, -1.131073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5732.27101562, 5510.20214844, 160.20157226999999), 'rotation':(-1.08786, -179.725937, -1.129791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5743.35640625, 5510.16257812, 160.41181641), 'rotation':(-1.08548, -179.729431, -1.127197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5986.34375, 5519.73242188, 164.83732422), 'rotation':(0.99354, 0.26696, 0.95952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5963.91257812, 5519.63429688, 164.44630859), 'rotation':(0.999496, 0.268399, 0.965065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5952.69773438, 5519.58546875, 164.2496875), 'rotation':(1.00457, 0.267944, 0.969793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5941.48195312, 5519.53613281, 164.05179688), 'rotation':(1.011155, 0.268178, 0.975922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5924.65921875, 5519.46242188, 163.75259766), 'rotation':(1.020874, 0.2685, 0.984966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.05171875, 5519.43796875, 163.65228516), 'rotation':(1.024337, 0.268648, 0.988176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5907.8359375, 5519.38867188, 163.45136719), 'rotation':(1.025949, 0.266559, 0.989679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5902.22851562, 5519.36425781, 163.35091796999998), 'rotation':(1.025853, 0.271498, 0.989594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5891.01367188, 5519.31542969, 163.14921875), 'rotation':(1.032417, 0.268669, 0.995685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5885.40671875, 5519.29101562, 163.0475), 'rotation':(1.039288, 0.270522, 1.002078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5879.79882812, 5519.26609375, 162.94574219), 'rotation':(1.039118, 0.270516, 1.001926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5851.76171875, 5519.14355469, 162.43563477), 'rotation':(1.046563, 0.271867, 1.008837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5840.5459375, 5519.09421875, 162.22986328000002), 'rotation':(1.052587, 0.27209, 1.014423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5834.93796875, 5519.06984375, 162.12658203), 'rotation':(1.055606, 0.267607, 1.017215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.90429688, 5518.98144531, 161.60699219), 'rotation':(1.064895, 0.270082, 1.025833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5801.296875, 5519.00683594, 161.50259766), 'rotation':(1.064895, 0.270082, 1.025833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5991.96046875, 5511.37648438, 164.93412109000002), 'rotation':(-0.993561, -179.733047, -1.028473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.74609375, 5511.32714844, 164.73935547000002), 'rotation':(-0.997559, -179.732895, -1.032776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.53171875, 5511.2778125, 164.54378906000002), 'rotation':(-1.001221, -179.732162, -1.036682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5963.9253125, 5511.2534375, 164.44589843999998), 'rotation':(-1.001221, -179.732162, -1.036682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5952.71140625, 5511.20460938, 164.24927734000002), 'rotation':(-1.00769, -179.731964, -1.04364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5947.10453125, 5511.1796875, 164.15050781000002), 'rotation':(-1.011169, -179.726913, -1.047333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5935.890625, 5511.13085938, 163.95203125), 'rotation':(-1.017609, -179.731598, -1.05426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5919.06984375, 5511.05761719, 163.65194336000002), 'rotation':(-1.025848, -179.733475, -1.06311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5913.46289062, 5511.03273438, 163.55151367), 'rotation':(-1.02594, -179.72847, -1.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5902.2490625, 5510.98339844, 163.35063477), 'rotation':(-1.02594, -179.72847, -1.063202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5885.42921875, 5510.9096875, 163.04725586), 'rotation':(-1.039124, -179.729477, -1.077362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5879.82179688, 5510.88523438, 162.94549805), 'rotation':(-1.039307, -179.729462, -1.077545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5868.60890625, 5510.83640625, 162.74200195), 'rotation':(-1.04068, -179.732941, -1.07901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5840.57421875, 5510.71335938, 162.22970703000001), 'rotation':(-1.055603, -179.727783, -1.095062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5823.75390625, 5510.63964844, 161.91911133), 'rotation':(-1.062927, -179.726349, -1.102936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5801.33054688, 5510.4575, 161.5025293), 'rotation':(-1.068604, -179.729767, -1.10907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5795.7221875, 5510.38769531, 161.39786132999998), 'rotation':(-1.072144, -179.72966, -1.112854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5790.11523438, 5510.36328125, 161.29288086), 'rotation':(-1.07605, -179.725647, -1.117096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5997.56101562, 5727.20015625, 164.925), 'rotation':(1.080222, 0.562874, 1.040054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5980.64109375, 5727.04148438, 164.60263672000002), 'rotation':(1.095091, 0.560405, 1.05381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5918.6025, 5726.46, 163.39764648), 'rotation':(1.130273, 0.559502, 1.086324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5884.76414062, 5726.14359375, 162.72496094), 'rotation':(1.148018, 0.558943, 1.102681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5879.12453125, 5726.0903125, 162.61189453), 'rotation':(1.148018, 0.558943, 1.102681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5873.48484375, 5726.03757812, 162.49882811999998), 'rotation':(1.148025, 0.563131, 1.102678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5867.8446875, 5725.98484375, 162.385625), 'rotation':(1.148025, 0.563131, 1.102678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5867.88375, 5717.60304688, 162.38482421999998), 'rotation':(-1.150604, -179.439011, -1.19754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5879.15921875, 5717.70851562, 162.61102539), 'rotation':(-1.148041, -179.44104, -1.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5890.43453125, 5717.81445312, 162.83708008), 'rotation':(-1.148041, -179.44104, -1.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5896.07179688, 5717.8671875, 162.95008789), 'rotation':(-1.14801, -179.436859, -1.194763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5907.34523438, 5717.97359375, 163.17390625), 'rotation':(-1.13028, -179.440491, -1.175568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5918.620625, 5718.0790625, 163.39645508), 'rotation':(-1.13028, -179.440491, -1.175568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5929.89546875, 5718.18507812, 163.61878906), 'rotation':(-1.128143, -179.441925, -1.173248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5941.17039062, 5718.29054688, 163.83975586), 'rotation':(-1.119202, -179.437744, -1.163605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5946.808125, 5718.34328125, 163.94962891), 'rotation':(-1.11496, -179.442444, -1.158997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5952.44578125, 5718.39601562, 164.05912109000002), 'rotation':(-1.110321, -179.442673, -1.154022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5963.72070312, 5718.50195312, 164.27691406000002), 'rotation':(-1.106018, -179.442795, -1.149353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5969.35789062, 5718.5503125, 164.38521484), 'rotation':(-1.101532, -179.438477, -1.144531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5974.99609375, 5718.60351562, 164.49320312), 'rotation':(-1.097229, -179.44313, -1.139893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5997.54640625, 5718.85203125, 164.92324219), 'rotation':(-1.08609, -179.445206, -1.127869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5627.18898438, 5715.28515625, 157.44571288999998), 'rotation':(-1.155579, -179.439743, -1.202911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5636.65382812, 5715.43601562, 157.6369043), 'rotation':(-1.157074, -179.440033, -1.204529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5648.00828125, 5715.5425, 157.86729492), 'rotation':(-1.163757, -179.439758, -1.211792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5659.36328125, 5715.64890625, 158.09884766), 'rotation':(-1.170197, -179.439499, -1.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5665.04101562, 5715.7021875, 158.21508789), 'rotation':(-1.173431, -179.439407, -1.22229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5676.39601562, 5715.80859375, 158.4484082), 'rotation':(-1.17688, -179.439224, -1.226013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5682.07375, 5715.86179688, 158.56545898000002), 'rotation':(-1.180084, -179.439087, -1.229492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5699.1059375, 5716.02101562, 158.91694336), 'rotation':(-1.181732, -179.440552, -1.231262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5716.13820312, 5716.180625, 159.26922851999998), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5727.49367188, 5716.2778125, 159.50428711), 'rotation':(-1.185394, -179.440292, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5733.16945312, 5716.36328125, 159.62179688), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5738.8471875, 5716.42726562, 159.7393457), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5744.524375, 5716.48046875, 159.856875), 'rotation':(-1.185394, -179.437469, -1.235229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5755.879375, 5716.58640625, 160.09170898), 'rotation':(-1.184418, -179.439026, -1.234192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5761.55664062, 5716.6396875, 160.20893555), 'rotation':(-1.182739, -179.439102, -1.232361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.234375, 5716.69289062, 160.32609375), 'rotation':(-1.181671, -179.438232, -1.231201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5772.910625, 5716.74609375, 160.44327148), 'rotation':(-1.181793, -179.438232, -1.231323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.26609375, 5716.85304688, 160.67762695), 'rotation':(-1.181732, -179.438202, -1.231293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5789.94289062, 5716.90625, 160.79478516), 'rotation':(-1.181793, -179.438232, -1.231323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5806.97609375, 5717.06546875, 161.14532227), 'rotation':(-1.174225, -179.439758, -1.223145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5812.65382812, 5717.11867188, 161.26168945), 'rotation':(-1.174225, -179.439758, -1.223145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5818.33007812, 5717.171875, 161.3778418), 'rotation':(-1.171783, -179.436676, -1.22049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5630.89746094, 5723.76367188, 157.5221582), 'rotation':(1.157068, 0.559965, 1.111011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5636.57570312, 5723.816875, 157.63691406), 'rotation':(1.160333, 0.560055, 1.114011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5642.25292969, 5723.87015625, 157.75197265999998), 'rotation':(1.163755, 0.564706, 1.117179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5647.9296875, 5723.92335938, 157.86729492), 'rotation':(1.166958, 0.560368, 1.120129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5676.316875, 5724.18945312, 158.4484082), 'rotation':(1.180086, 0.560905, 1.132192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5687.6709375, 5724.2959375, 158.68259766), 'rotation':(1.181623, 0.559397, 1.133615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5699.02585938, 5724.401875, 158.91693359), 'rotation':(1.181739, 0.564698, 1.133709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5733.089375, 5724.6884375, 159.62176757999998), 'rotation':(1.185393, 0.559704, 1.137075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5744.444375, 5724.79492188, 159.8568457), 'rotation':(1.184416, 0.565085, 1.136178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5750.12109375, 5724.848125, 159.97430664), 'rotation':(1.18275, 0.56089, 1.134639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5755.79835938, 5724.90140625, 160.09166016), 'rotation':(1.18275, 0.56089, 1.134639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5767.1528125, 5725.0078125, 160.32605469), 'rotation':(1.181773, 0.561769, 1.133747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5772.83007812, 5725.06101562, 160.44320312), 'rotation':(1.181664, 0.561765, 1.133651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5784.18359375, 5725.1675, 160.67754883), 'rotation':(1.181841, 0.558484, 1.133814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5795.5390625, 5725.27390625, 160.91181641), 'rotation':(1.179273, 0.563742, 1.131438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5806.89359375, 5725.38039062, 161.14524414), 'rotation':(1.171671, 0.563249, 1.124458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.35546875, 5736.80765625, 162.04470703), 'rotation':(-0.054932, 90.530998, -0.055054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.20117188, 5753.5225, 162.02921875), 'rotation':(-0.0495, 90.530952, -0.049591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5847.14992188, 5759.09375, 162.02450195), 'rotation':(-0.046844, 90.52652, -0.046936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.99609375, 5775.80859375, 162.01174805), 'rotation':(-0.038605, 90.526512, -0.038666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5846.94484375, 5781.37984375, 162.00797852), 'rotation':(-0.03598, 90.526451, -0.036011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.89304688, 5786.95164062, 162.00445312), 'rotation':(-0.034668, 90.530479, -0.034698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.84179688, 5792.5234375, 162.00106445), 'rotation':(-0.034668, 90.530479, -0.034698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.79054688, 5798.0946875, 161.99771484000001), 'rotation':(-0.033722, 90.528191, -0.033752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5846.73921875, 5803.66648438, 161.99444336), 'rotation':(-0.03183, 90.528214, -0.03183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.68796875, 5809.23828125, 161.99128905999999), 'rotation':(-0.03183, 90.528214, -0.03183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.43117188, 5837.09570312, 161.97710938), 'rotation':(-0.026978, 90.531715, -0.027008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.37984375, 5842.66703125, 161.97447266), 'rotation':(-0.026672, 90.527008, -0.026703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5846.02, 5881.66703125, 161.95681641), 'rotation':(-0.02478, 90.527, -0.02478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.9175, 5892.81007812, 161.95201172), 'rotation':(-0.025513, 90.526863, -0.025543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.81492188, 5903.95265625, 161.94691406), 'rotation':(-0.028473, 90.531609, -0.028503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.76367188, 5909.52390625, 161.94415039), 'rotation':(-0.029968, 90.526863, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.71242188, 5915.09570312, 161.94125), 'rotation':(-0.031433, 90.52681, -0.031464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5845.66109375, 5920.66703125, 161.93820312), 'rotation':(-0.032928, 90.526855, -0.032959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.60984375, 5926.2378125, 161.93503906), 'rotation':(-0.034546, 90.531616, -0.034607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5845.558125, 5931.80953125, 161.93171875), 'rotation':(-0.036041, 90.526825, -0.036072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':1, 'location':(5855.73585938, 5736.88476562, 162.04470703), 'rotation':(0.056301, -89.471161, 0.056183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5855.47898438, 5764.743125, 162.02001953), 'rotation':(0.046855, -89.47348, 0.046769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5855.2734375, 5787.02882812, 162.00445312), 'rotation':(0.035975, -89.47348, 0.035928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':1, 'location':(5855.2221875, 5792.60007812, 162.00106445), 'rotation':(0.035975, -89.47348, 0.035928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':1, 'location':(5855.06835938, 5809.31546875, 161.99128905999999), 'rotation':(0.033714, -89.471802, 0.033678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.96578125, 5820.45851562, 161.98529297), 'rotation':(0.029889, -89.471802, 0.029862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.70898438, 5848.31546875, 161.97186523), 'rotation':(0.026966, -89.472961, 0.026939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.6571875, 5853.88671875, 161.96929688), 'rotation':(0.026672, -89.472992, 0.026648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.5546875, 5865.02976562, 161.96421875), 'rotation':(0.026091, -89.472992, 0.026066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.5034375, 5870.60109375, 161.96172852), 'rotation':(0.025784, -89.468323, 0.025775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5854.40039062, 5881.74414062, 161.95681641), 'rotation':(0.02506, -89.472992, 0.025047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.2465625, 5898.45851562, 161.94954102), 'rotation':(0.025504, -89.473145, 0.025492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5854.04148438, 5920.74414062, 161.93821289), 'rotation':(0.031439, -89.473145, 0.031413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':1, 'location':(5853.9384375, 5931.88671875, 161.93171875), 'rotation':(0.034568, -89.468384, 0.034515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':1, 'location':(5853.8871875, 5937.45796875, 161.92827148), 'rotation':(0.036036, -89.473114, 0.036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4145.39109375, 2204.22828125, 156.9969043), 'rotation':(-1.622162, 0.467897, -1.716095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4123.40039062, 2204.0659375, 157.62112305), 'rotation':(-1.631561, 0.470357, -1.726593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4106.90773438, 2203.94460938, 158.09942383), 'rotation':(-1.668518, 0.47042, -1.767944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4101.40921875, 2203.9040625, 158.26155273), 'rotation':(-1.68692, 0.47357, -1.788605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4095.91164062, 2203.86351562, 158.42450195), 'rotation':(-1.69632, 0.472024, -1.799164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4090.4153125000003, 2203.8229687499997, 158.58742188), 'rotation':(-1.696136, 0.474024, -1.79895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4079.4206249999997, 2203.74171875, 158.91422852), 'rotation':(-1.70694, 0.472918, -1.811066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4068.42671875, 2203.66039062, 159.24365234), 'rotation':(-1.721222, 0.476377, -1.827118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4062.92945312, 2203.6198437499997, 159.40944336), 'rotation':(-1.728363, 0.474205, -1.835144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4040.94289062, 2203.42484375, 160.07931641), 'rotation':(-1.749756, 0.478114, -1.859253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4018.9565625, 2203.26265625, 160.75671875), 'rotation':(-1.771973, 0.478567, -1.884308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4002.4665625, 2203.14109375, 161.27185547), 'rotation':(-1.796783, 0.478194, -1.912323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4007.9075000000003, 2195.33179688, 161.1028125), 'rotation':(1.796674, -179.521149, 1.686477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4018.9053125, 2195.413125, 160.76009765999999), 'rotation':(1.784305, -179.52066, 1.675592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4051.89867188, 2195.65648438, 159.74603516), 'rotation':(1.749758, -179.524475, 1.645173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4057.3971874999997, 2195.69703125, 159.5787793), 'rotation':(1.74262, -179.524933, 1.638875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4068.39601562, 2195.77828125, 159.24633789), 'rotation':(1.728345, -179.523193, 1.626278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4073.89523438, 2195.81882812, 159.08119141), 'rotation':(1.721214, -179.52623, 1.619975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4079.39429688, 2195.859375, 158.91676758), 'rotation':(1.714077, -179.526642, 1.613666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4090.39304688, 2195.94046875, 158.58981445), 'rotation':(1.699795, -179.524902, 1.601041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4101.39109375, 2196.02171875, 158.26382812), 'rotation':(1.696318, -179.52594, 1.597968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4106.89304688, 2196.06226562, 158.1015625), 'rotation':(1.686927, -179.528488, 1.589647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4123.3915625, 2196.1840625, 157.62302734000002), 'rotation':(1.650215, -179.528534, 1.557081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4128.8940625, 2196.22460938, 157.46617188), 'rotation':(1.631541, -179.531723, 1.540492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4139.89304688, 2196.305625, 157.154375), 'rotation':(1.622334, -179.532089, 1.532287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4145.39210938, 2196.34617188, 156.99850586), 'rotation':(1.622464, -179.532043, 1.532414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.47414062, 2182.39601562, 156.92179688), 'rotation':(-1.226837, 89.829018, -1.280243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.45460938, 2176.77273438, 157.04310547), 'rotation':(-1.234222, 89.827484, -1.2883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.41554688, 2165.52710938, 157.2877832), 'rotation':(-1.247101, 89.828789, -1.302338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.37648438, 2154.28078125, 157.53619141), 'rotation':(-1.27301, 89.829933, -1.330566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.35695312, 2148.65820312, 157.66177734000001), 'rotation':(-1.281494, 89.830292, -1.339813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.23976562, 2114.9231250000003, 158.43329101999998), 'rotation':(-1.326538, 89.835213, -1.389069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.12304688, 2081.18898438, 159.235), 'rotation':(-1.377899, 89.832024, -1.445435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4157.08398438, 2069.94484375, 159.50672852), 'rotation':(-1.383698, 89.833809, -1.451813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.0390625, 2047.4572656199998, 160.06178711), 'rotation':(-1.424713, 89.837029, -1.496948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.00046875, 2036.21398438, 160.34173828000002), 'rotation':(-1.424683, 89.837044, -1.496948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4156.9028125, 2008.1052343800002, 161.05197266), 'rotation':(-1.45636, 89.838455, -1.531921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4164.77046875, 2013.5771875, 160.91154297), 'rotation':(1.468853, -90.160889, 1.394914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4164.82859375, 2030.35976562, 160.48739258), 'rotation':(1.443581, -90.16217, 1.37215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4164.86765625, 2041.54921875, 160.20814453), 'rotation':(1.431034, -90.162811, 1.360828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4164.88671875, 2047.14320312, 160.06892578), 'rotation':(1.424689, -90.162933, 1.355088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4164.94484375, 2063.9275, 159.6530957), 'rotation':(1.407149, -90.165039, 1.339246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4164.964375, 2069.52195312, 159.51635742), 'rotation':(1.395394, -90.165619, 1.328601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.00632812, 2080.71046875, 159.24586914), 'rotation':(1.377916, -90.167969, 1.312752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.0225, 2086.30664062, 159.11117188), 'rotation':(1.377888, -90.162659, 1.312758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.04203125, 2091.9028125, 158.97680664), 'rotation':(1.373244, -90.167358, 1.308566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.0590625, 2097.49828125, 158.84318359), 'rotation':(1.363996, -90.167786, 1.300163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.08054688, 2103.09179688, 158.71047852), 'rotation':(1.354481, -90.163483, 1.291518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.09960938, 2108.6865625, 158.57861328), 'rotation':(1.345117, -90.168671, 1.283008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.11671875, 2114.285625, 158.44750977), 'rotation':(1.345117, -90.168671, 1.283008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.17773438, 2131.0690624999997, 158.05978516), 'rotation':(1.316997, -90.169983, 1.25745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.19679688, 2136.66554688, 157.93210938), 'rotation':(1.30333, -90.175873, 1.244993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.21632812, 2142.26171875, 157.80511719), 'rotation':(1.298658, -90.168915, 1.24074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.23585938, 2147.85695312, 157.67911132999998), 'rotation':(1.290175, -90.169281, 1.233005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.25539062, 2153.45164062, 157.55401367000002), 'rotation':(1.281473, -90.169678, 1.225076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.29390625, 2164.64523438, 157.30652344), 'rotation':(1.264302, -90.170441, 1.209378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4181.6371875, 2408.57910156, 152.34600586), 'rotation':(-1.148987, 72.104126, -1.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4179.99851562, 2403.348125, 152.45646484), 'rotation':(-1.149017, 72.823311, -1.195831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4176.85789062, 2392.71949219, 152.67963867), 'rotation':(-1.148987, 73.907257, -1.195801), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4172.56789062, 2376.57347656, 153.01779297), 'rotation':(-1.157166, 76.055382, -1.204651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4167.66554688, 2354.62328125, 153.47423828), 'rotation':(-1.156372, 78.574532, -1.203796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4162.85695312, 2326.68796875, 154.04490234000002), 'rotation':(-1.141846, 81.56237, -1.188049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4162.0815625, 2321.0590625, 154.15852539), 'rotation':(-1.141022, 82.309853, -1.187195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4160.72804688, 2309.8098437500003, 154.38481445), 'rotation':(-1.136169, 83.579033, -1.181946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4160.14796875, 2304.19460938, 154.49655273), 'rotation':(-1.126617, 84.388161, -1.1716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4159.6259375, 2298.51953125, 154.60867188), 'rotation':(-1.120392, 84.922913, -1.164886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4158.78273438, 2287.2721874999997, 154.82831055), 'rotation':(-1.104431, 86.252892, -1.147644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.77734375, 2259.16257812, 155.36709961), 'rotation':(-1.09024, 89.446373, -1.132355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.65773438, 2225.9653125, 156.02069336), 'rotation':(-1.137726, 89.823753, -1.183594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4157.55953125, 2220.49804688, 156.12958984), 'rotation':(-1.137726, 89.823753, -1.183594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.50195312, 2225.03101562, 156.03869140999998), 'rotation':(1.145231, -90.175659, 1.100111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4165.70554688, 2241.97679688, 155.70222655999999), 'rotation':(1.137684, -90.173126, 1.09315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4165.84570312, 2264.66601562, 155.25894531), 'rotation':(1.116531, -90.811279, 1.073625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4166.19773438, 2276.15476562, 155.03580078000002), 'rotation':(1.116183, -92.147186, 1.073305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4167.71046875, 2299.21117188, 154.58114258), 'rotation':(1.143599, -94.808258, 1.098608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4168.87351562, 2310.74289062, 154.348125), 'rotation':(1.159841, -96.147339, 1.113565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4170.30765625, 2322.25171875, 154.11257812), 'rotation':(1.168126, -97.696136, 1.121187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4171.12546875, 2327.99046875, 153.9947168), 'rotation':(1.168092, -98.041504, 1.12117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4173.9765625, 2345.14453125, 153.63962891), 'rotation':(1.177504, -100.139465, 1.129825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4176.20015625, 2356.4607031200003, 153.40232422), 'rotation':(1.183911, -101.429871, 1.135714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4178.67921875, 2367.70507812, 153.16496094000001), 'rotation':(1.185031, -102.881348, 1.136743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4182.85640625, 2384.32714844, 152.81171875), 'rotation':(1.181507, -105.011902, 1.133502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4184.36523438, 2389.79957031, 152.69537109), 'rotation':(1.179649, -105.369614, 1.131794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5991.92921875, 2779.68310547, 154.32901367), 'rotation':(0.514539, -0.157379, 0.505367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.4809375, 2779.74658203, 154.13544922), 'rotation':(0.484083, -0.157654, 0.47596), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5958.256875, 2779.77808594, 154.04475586), 'rotation':(0.457295, -0.158112, 0.450044), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.64257812, 2779.79394531, 154.00162109000001), 'rotation':(0.443669, -0.158295, 0.436835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5947.03125, 2779.80980469, 153.95998047), 'rotation':(0.430254, -0.158508, 0.423824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.41890625, 2779.82568359, 153.91978516), 'rotation':(0.40307, -0.158905, 0.397426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5935.80765625, 2779.8415625, 153.88105469), 'rotation':(0.389649, -0.159088, 0.384374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5913.3584375, 2779.90478516, 153.73505859), 'rotation':(0.352499, -0.160706, 0.348179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5902.1328125, 2779.93628906, 153.66870117), 'rotation':(0.328238, -0.16098, 0.324487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5890.90867188, 2779.96777344, 153.60711914), 'rotation':(0.303773, -0.161255, 0.300573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5862.848125, 2780.04710938, 153.47032227), 'rotation':(0.260094, -0.160767, 0.257744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5857.2334375, 2780.06273438, 153.44582031), 'rotation':(0.249828, -0.160858, 0.247665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5840.39890625, 2780.11035156, 153.37864258), 'rotation':(0.218983, -0.161133, 0.217317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5834.78609375, 2780.12621094, 153.35824219), 'rotation':(0.208847, -0.161194, 0.207329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5812.33890625, 2780.1896875, 153.28225586), 'rotation':(0.184763, -0.16095, 0.183584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.72507812, 2780.20556641, 153.26515625), 'rotation':(0.176868, -0.161011, 0.175784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5801.11328125, 2780.22144531, 153.24886719), 'rotation':(0.169457, -0.161041, 0.16846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5784.276875, 2780.26878906, 153.20457031), 'rotation':(0.142765, -0.161133, 0.142052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5778.66453125, 2780.28466797, 153.19072266), 'rotation':(0.142765, -0.161133, 0.142052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5773.05226562, 2780.30054688, 153.17724609), 'rotation':(0.134719, -0.160034, 0.134073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5750.60546875, 2780.36376953, 153.12885742), 'rotation':(0.113688, -0.160126, 0.113239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5739.381875, 2780.39550781, 153.10792969), 'rotation':(0.10317, -0.162811, 0.102806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5733.774375, 2780.4978125, 153.09805663999998), 'rotation':(0.100493, -0.160248, 0.100146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5997.53367188, 2771.28662109, 154.38025391), 'rotation':(-0.53009, 179.842239, -0.539978), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.921875, 2771.3025, 154.32915039), 'rotation':(-0.498749, 179.842361, -0.507507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.31007812, 2771.31835938, 154.27964844), 'rotation':(-0.490967, 179.843002, -0.49942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.69625, 2771.33447266, 154.2312207), 'rotation':(-0.490967, 179.843002, -0.49942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5975.085, 2771.35035156, 154.18313477), 'rotation':(-0.48407, 179.842361, -0.49231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.6328125, 2771.41357422, 154.00172852), 'rotation':(-0.430237, 179.841492, -0.436737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5947.02101562, 2771.42945312, 153.96007812), 'rotation':(-0.416718, 179.841278, -0.422791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5935.79640625, 2771.46117188, 153.88115234), 'rotation':(-0.383026, 179.841766, -0.388153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5918.95851562, 2771.50855469, 153.77009766), 'rotation':(-0.352509, 179.839294, -0.356873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5907.73390625, 2771.54003906, 153.70135742), 'rotation':(-0.328247, 179.841507, -0.332001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5896.50734375, 2771.57177734, 153.63737305), 'rotation':(-0.303772, 179.841248, -0.307007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5885.28320312, 2771.60351562, 153.57818359), 'rotation':(-0.285767, 179.84108, -0.288635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5874.05710938, 2771.635, 153.52244141), 'rotation':(-0.270233, 179.83931, -0.272797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5857.21726562, 2771.68261719, 153.44584961), 'rotation':(-0.239532, 179.83905, -0.241547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5845.99414062, 2771.71435547, 153.40001953), 'rotation':(-0.218994, 179.838867, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5829.1553125, 2771.76171875, 153.33833008), 'rotation':(-0.199768, 179.839111, -0.201172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5823.54390625, 2771.77757812, 153.31884766), 'rotation':(-0.192169, 179.839096, -0.193451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5817.93164062, 2771.79345703, 153.30015625), 'rotation':(-0.184784, 179.839035, -0.185944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.70554688, 2771.82519531, 153.26516602), 'rotation':(-0.169464, 179.838943, -0.170441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5801.09328125, 2771.84105469, 153.24888672), 'rotation':(-0.161896, 179.838882, -0.162811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5789.86867188, 2771.8728125, 153.2187207), 'rotation':(-0.142761, 179.838852, -0.143494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5778.64304688, 2771.90453125, 153.19072266), 'rotation':(-0.140137, 179.839981, -0.140839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5767.4184375, 2771.93628906, 153.16433594), 'rotation':(-0.124207, 179.83728, -0.124756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5744.9696875, 2771.99925781, 153.11811523), 'rotation':(-0.10318, 179.837189, -0.103546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5733.74953125, 2771.94433594, 153.09805663999998), 'rotation':(-0.100372, 179.839752, -0.100708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5993.94484375, 2875.85400391, 155.05930664), 'rotation':(-0.271576, -73.230774, -0.27417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5989.04882812, 2892.10180664, 155.14040039), 'rotation':(-0.27655, -73.232117, -0.279236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5987.41703125, 2897.51757812, 155.16796875), 'rotation':(-0.279907, -73.227814, -0.282654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5984.1528125, 2908.34912109, 155.22390625), 'rotation':(-0.283142, -73.231415, -0.28595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.88914062, 2919.18066406, 155.28013672), 'rotation':(-0.284851, -73.229858, -0.287689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5977.62546875, 2930.01220703, 155.33645508), 'rotation':(-0.285248, -73.227142, -0.288116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.36132812, 2940.84375, 155.39292969), 'rotation':(-0.286102, -73.230042, -0.288971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.46578125, 2957.09106445, 155.47802734), 'rotation':(-0.287842, -73.230042, -0.290741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5966.20164062, 2967.92260742, 155.53493164), 'rotation':(-0.2883, -73.22998, -0.291199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5962.93796875, 2978.75390625, 155.5918457), 'rotation':(-0.2883, -73.22998, -0.291199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5959.67429688, 2989.58544922, 155.64866211), 'rotation':(-0.287903, -73.230713, -0.290802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5954.77882812, 3005.83251953, 155.7337207), 'rotation':(-0.286957, -73.228027, -0.289825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.14695312, 3011.24853516, 155.76205078), 'rotation':(-0.287048, -73.231354, -0.289948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5949.88328125, 3022.07958984, 155.81849609), 'rotation':(-0.284637, -73.227966, -0.287476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5946.61914062, 3032.91113281, 155.874375), 'rotation':(-0.281433, -73.228027, -0.28421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5944.98734375, 3038.3269043, 155.90207031), 'rotation':(-0.279755, -73.232727, -0.282501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.72359375, 3049.15844727, 155.95700195), 'rotation':(-0.276703, -73.228058, -0.279388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5938.45945312, 3059.98974609, 156.01134765999998), 'rotation':(-0.275024, -73.232788, -0.277679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5930.43898438, 3057.56079102, 156.01130859), 'rotation':(0.274314, 106.769073, 0.271688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5933.66554688, 3046.85400391, 155.95757812), 'rotation':(0.275024, 106.771904, 0.272391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5938.50484375, 3030.79370117, 155.87591797), 'rotation':(0.279737, 106.771957, 0.277026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.118125, 3025.43969727, 155.84838867), 'rotation':(0.281445, 106.767296, 0.278683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.7309375, 3020.08642578, 155.82071288999998), 'rotation':(0.283098, 106.77198, 0.280312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5943.34421875, 3014.73266602, 155.79288086), 'rotation':(0.284648, 106.772697, 0.281829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5944.9575, 3009.37963867, 155.76492188), 'rotation':(0.286158, 106.767334, 0.283318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5949.796875, 2993.31933594, 155.68088867), 'rotation':(0.286957, 106.769058, 0.284095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.0234375, 2982.61230469, 155.62478516), 'rotation':(0.287353, 106.772545, 0.284485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5956.24953125, 2971.9050293, 155.56855469), 'rotation':(0.288275, 106.770012, 0.285388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5957.8628125, 2966.55175781, 155.54043945), 'rotation':(0.288118, 106.769318, 0.285232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5962.70265625, 2950.4909668, 155.45608398000002), 'rotation':(0.287831, 106.769958, 0.284947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5964.31546875, 2945.13745117, 155.42802734), 'rotation':(0.287831, 106.769958, 0.284947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5967.54203125, 2934.43017578, 155.37208984), 'rotation':(0.28697, 106.769958, 0.284107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.15476562, 2929.07666016, 155.34416016), 'rotation':(0.286117, 106.769928, 0.283267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5970.76804688, 2923.72314453, 155.31631836), 'rotation':(0.285256, 106.769936, 0.282426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5977.22070312, 2902.30859375, 155.20509765999998), 'rotation':(0.28486, 106.770149, 0.282043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5983.67335938, 2880.89428711, 155.09630859), 'rotation':(0.273208, 106.768494, 0.270615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.89992188, 2870.18676758, 155.04323242), 'rotation':(0.271582, 106.772972, 0.269017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.73976562, 2854.1262207, 154.96373047), 'rotation':(0.271582, 106.772972, 0.269017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5994.96578125, 2843.41894531, 154.91113281), 'rotation':(0.26872, 106.769127, 0.266209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5996.5790625, 2838.06518555, 154.88537109), 'rotation':(0.263154, 106.769539, 0.26075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4749.39111328, 3561.55125, 155.78344727), 'rotation':(-1.049927, 179.817749, -1.088959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4736.54736328, 3561.68898438, 155.54695312), 'rotation':(-1.065155, 179.818314, -1.105316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4725.49804688, 3561.76441406, 155.34063477), 'rotation':(-1.075531, 179.818848, -1.116516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4719.97363281, 3561.78394531, 155.23689453), 'rotation':(-1.080841, 179.821609, -1.122223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4708.92285156, 3561.8225, 155.02788086), 'rotation':(-1.091492, 179.819458, -1.133698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.87207031, 3561.86132812, 154.81677734000002), 'rotation':(-1.102173, 179.81987, -1.145203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.82080078, 3561.90015625, 154.60360352), 'rotation':(-1.112823, 179.820297, -1.156708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4681.29492188, 3561.91917969, 154.49623047), 'rotation':(-1.11554, 179.820374, -1.159637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4675.77099609, 3561.93898438, 154.38864258), 'rotation':(-1.11554, 179.820374, -1.159637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4659.19484375, 3561.99707031, 154.06569336), 'rotation':(-1.116486, 179.820999, -1.160675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4653.66894531, 3562.01660156, 153.95789062), 'rotation':(-1.118622, 179.821091, -1.162964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4648.14355469, 3562.03589844, 153.84996094), 'rotation':(-1.119781, 179.819107, -1.164215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4637.09226562, 3562.0746875, 153.63389648), 'rotation':(-1.119507, 179.821655, -1.16394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4631.566875, 3562.09421875, 153.52584961), 'rotation':(-1.119781, 179.819107, -1.164215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4637.08789062, 3570.45605469, 153.63322266), 'rotation':(1.119789, -0.180878, 1.076633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4642.61328125, 3570.43675781, 153.74125977), 'rotation':(1.119789, -0.178345, 1.076624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4653.66503906, 3570.39796875, 153.95722656), 'rotation':(1.116497, -0.180786, 1.073588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4681.29248047, 3570.30101562, 154.49560547), 'rotation':(1.112904, -0.179718, 1.070284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.81787109, 3570.2814843799997, 154.60297852), 'rotation':(1.107399, -0.179932, 1.065199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4692.34326172, 3570.2621875, 154.70980469), 'rotation':(1.10216, -0.180115, 1.060347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.86914062, 3570.24265625, 154.81616211), 'rotation':(1.096744, -0.180328, 1.055345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4951.10351562, 3560.23070312, 158.72325195), 'rotation':(-0.581024, 179.42923, -0.592896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4945.60888672, 3560.37453125, 158.6675293), 'rotation':(-0.612335, 179.429916, -0.625549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4934.57128906, 3560.526875, 158.55072266), 'rotation':(-0.643829, 179.428848, -0.658447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4929.04931641, 3560.5825, 158.48866211), 'rotation':(-0.659668, 179.430725, -0.674988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4923.52880859, 3560.63820312, 158.42567383), 'rotation':(-0.659668, 179.430725, -0.674988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4912.48730469, 3560.70117188, 158.29763671999999), 'rotation':(-0.68576, 179.431717, -0.702332), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4901.44335938, 3560.7892968799997, 158.16386719), 'rotation':(-0.720428, 179.430176, -0.738708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4890.40380859, 3560.90746094, 158.02378906), 'rotation':(-0.755249, 179.433472, -0.77536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4879.36132812, 3560.93824219, 157.87739258), 'rotation':(-0.790192, 179.432007, -0.812225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4873.84228516, 3561.07691406, 157.8018457), 'rotation':(-0.798706, 179.434708, -0.821198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4862.79443359, 3561.10523438, 157.64712891), 'rotation':(-0.836578, 179.623611, -0.861267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4851.74804688, 3561.2421875, 157.48710938), 'rotation':(-0.861908, 179.811844, -0.888123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4840.70849609, 3561.3459375, 157.32174805), 'rotation':(-0.882507, 179.812469, -0.910034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4835.18701172, 3561.36328125, 157.23667969), 'rotation':(-0.903015, 179.81311, -0.931824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4829.66699219, 3561.3986718799997, 157.15003906), 'rotation':(-0.913391, 179.812668, -0.942871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4824.14697266, 3561.41820312, 157.06254883), 'rotation':(-0.913391, 179.812668, -0.942871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4818.62548828, 3561.4377343799997, 156.97450195), 'rotation':(-0.922607, 179.813538, -0.952698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4807.5859375, 3561.38820312, 156.79605469), 'rotation':(-0.940857, 179.814163, -0.972137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4796.54394531, 3561.38523438, 156.61259766), 'rotation':(-0.977783, 179.817291, -1.011597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4796.56396484, 3570.04054688, 156.61242188), 'rotation':(0.959471, -0.185242, 0.92773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4802.08691406, 3570.02101562, 156.70494141), 'rotation':(0.940913, -0.185852, 0.91038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4807.60693359, 3570.00195312, 156.79589844), 'rotation':(0.922601, -0.186462, 0.893235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4813.12890625, 3569.91527344, 156.88568359), 'rotation':(0.922601, -0.186462, 0.893235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4818.64990234, 3569.85449219, 156.97441406), 'rotation':(0.913387, -0.185822, 0.884601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4835.21533203, 3569.76414062, 157.23666015999999), 'rotation':(0.882501, -0.187531, 0.855628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4846.25927734, 3569.72144531, 157.40510742), 'rotation':(0.841274, -0.188782, 0.816836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4862.8125, 3569.630625, 157.64618164), 'rotation':(0.810388, -0.564911, 0.787701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4868.33447266, 3569.57519531, 157.72417969), 'rotation':(0.798695, -0.565277, 0.776662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4879.37841797, 3569.484375, 157.87646484), 'rotation':(0.772569, -0.568451, 0.751939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4884.89990234, 3569.4450781200003, 157.95048828), 'rotation':(0.755241, -0.566528, 0.735521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4890.42236328, 3569.40429688, 158.02292969), 'rotation':(0.737913, -0.566986, 0.719084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4895.94433594, 3569.33742188, 158.09379883), 'rotation':(0.720496, -0.567474, 0.70254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4918.03369141, 3569.21921875, 158.36135742), 'rotation':(0.65966, -0.569275, 0.644605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4940.12304688, 3568.9965625, 158.609375), 'rotation':(0.581024, -0.57251, 0.569321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4945.64453125, 3568.9409375, 158.66702148000002), 'rotation':(0.581024, -0.57251, 0.569321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4989.00048828, 3559.870625, 159.06695312), 'rotation':(-0.484528, 179.427216, -0.492767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5005.98046875, 3559.80738281, 159.19564453), 'rotation':(-0.429291, 179.4263, -0.43576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5011.640625, 3559.75046875, 159.2350293), 'rotation':(-0.401672, 179.425934, -0.407318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5039.94726562, 3559.4653125, 159.4112207), 'rotation':(-0.322144, 179.424408, -0.325806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5045.60595703, 3559.40820312, 159.44128906), 'rotation':(-0.303497, 179.42424, -0.306732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5062.58984375, 3559.23730469, 159.52107422), 'rotation':(-0.247192, 179.423691, -0.249329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5068.25097656, 3559.18015625, 159.54484375), 'rotation':(-0.247192, 179.423691, -0.249329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5073.91308594, 3559.12304688, 159.56833984000002), 'rotation':(-0.237732, 179.423492, -0.239716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5090.89550781, 3558.95214844, 159.62869141), 'rotation':(-0.21048, 179.423935, -0.212006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5096.55273438, 3558.89527344, 159.64401367), 'rotation':(-0.155792, 179.423584, -0.156647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5102.21777344, 3558.838125, 159.65670898), 'rotation':(-0.128448, 179.421738, -0.129028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5113.54199219, 3558.72414062, 159.68210938), 'rotation':(-0.128448, 179.424118, -0.128998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5119.20410156, 3558.66699219, 159.69480469), 'rotation':(-0.128448, 179.421738, -0.129028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5130.52294922, 3558.55273438, 159.71405273), 'rotation':(-0.096619, 179.424149, -0.096954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5136.18505859, 3558.49585938, 159.71730469), 'rotation':(-0.032928, 179.422577, -0.03299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5141.84472656, 3558.43871094, 159.71939453000002), 'rotation':(-0.032928, 179.422577, -0.03299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5147.50683594, 3558.38160156, 159.71950195), 'rotation':(-0.001068, 179.423248, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5153.16894531, 3558.3246875, 159.71958984), 'rotation':(-0.001068, 179.423248, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5175.81787109, 3558.09644531, 159.72001953), 'rotation':(-0.001068, 179.423233, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5181.47900391, 3558.03953125, 159.71957031), 'rotation':(-0.001068, 179.423233, -0.001068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5192.80029297, 3557.92554688, 159.71311523), 'rotation':(0.038311, 179.422897, 0.038269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5204.12255859, 3557.81128906, 159.69740234), 'rotation':(0.09093, 179.423019, 0.09065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4992.8671875, 3568.36304688, 159.09710938), 'rotation':(0.429277, -0.5737, 0.42288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5000.37695312, 3568.24488281, 159.15457031), 'rotation':(0.401663, -0.574066, 0.396061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5006.03808594, 3568.1877343799997, 159.19546875), 'rotation':(0.401663, -0.574066, 0.396061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5017.359375, 3568.07398438, 159.27299805), 'rotation':(0.378413, -0.57486, 0.373457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5023.02148438, 3568.01683594, 159.31014648000001), 'rotation':(0.359691, -0.575165, 0.355194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5028.68212891, 3567.95972656, 159.34556641), 'rotation':(0.341045, -0.575348, 0.337003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5045.66552734, 3567.7888281200003, 159.44116211), 'rotation':(0.284593, -0.575958, 0.281774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5062.65039062, 3567.61765625, 159.5209668), 'rotation':(0.237725, -0.574921, 0.235757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5079.63427734, 3567.44652344, 159.59077148), 'rotation':(0.210452, -0.57605, 0.208917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5090.95654297, 3567.3325, 159.62863281), 'rotation':(0.155776, -0.576416, 0.154944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5113.60351562, 3567.10449219, 159.68205078), 'rotation':(0.128449, -0.575928, 0.127875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5124.92626953, 3566.99023438, 159.7049707), 'rotation':(0.096627, -0.577271, 0.096302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5130.58496094, 3566.933125, 159.7140332), 'rotation':(0.032922, -0.577393, 0.032893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5147.5703125, 3566.7621875, 159.71950195), 'rotation':(0.001072, -0.576752, 0.001067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5170.21972656, 3566.53417969, 159.71991211), 'rotation':(0.001072, -0.576752, 0.001067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5204.18798828, 3566.191875, 159.69743164), 'rotation':(-0.104095, -0.577484, -0.104492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5247.54150391, 3557.37402344, 159.60069336), 'rotation':(0.153734, 179.423233, 0.152916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5258.58496094, 3557.26269531, 159.56708984), 'rotation':(0.179607, 179.423386, 0.178485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5264.10595703, 3557.20703125, 159.54920898), 'rotation':(0.185972, 179.423218, 0.184775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5275.14794922, 3557.0959375, 159.51177734), 'rotation':(0.199476, 179.423477, 0.198107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5286.19091797, 3556.98484375, 159.47125), 'rotation':(0.217603, 179.425842, 0.21597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5297.23291016, 3556.87328125, 159.42759766), 'rotation':(0.226817, 179.423965, 0.225028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5302.75439453, 3556.81761719, 159.40473633), 'rotation':(0.236065, 179.424011, 0.234114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5313.796875, 3556.7065625, 159.35810547), 'rotation':(0.243366, 179.423264, 0.241302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5319.31884766, 3556.65085938, 159.33419922), 'rotation':(0.248708, 179.425903, 0.246561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5330.36132812, 3556.53980469, 159.28483398), 'rotation':(0.259397, 179.423416, 0.257049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5346.92578125, 3556.3728125, 159.20681641), 'rotation':(0.275421, 179.423553, 0.272789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5357.96777344, 3556.26171875, 159.15240234), 'rotation':(0.283337, 179.426025, 0.28055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5363.48976562, 3556.20605469, 159.12489258), 'rotation':(0.284716, 179.425583, 0.281908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5374.53222656, 3556.09496094, 159.06911133), 'rotation':(0.289955, 179.425629, 0.287039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5391.098125, 3555.92796875, 158.98348633), 'rotation':(0.297885, 179.423172, 0.294803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5402.14015625, 3555.816875, 158.92518555), 'rotation':(0.304647, 179.421799, 0.301423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5236.56494141, 3565.86546875, 159.63061523), 'rotation':(-0.153748, -0.576752, -0.154572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5247.60791016, 3565.75414062, 159.60074219), 'rotation':(-0.166656, -0.576691, -0.167633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5253.12890625, 3565.69875, 159.58444336), 'rotation':(-0.179596, -0.576599, -0.180756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5258.65087891, 3565.64304688, 159.56713867), 'rotation':(-0.185974, -0.574158, -0.187195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5264.17236328, 3565.58765625, 159.54928711), 'rotation':(-0.19043, -0.576599, -0.191711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5269.69335938, 3565.53199219, 159.53092773), 'rotation':(-0.199493, -0.576538, -0.200867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5275.21533203, 3565.4763281200003, 159.51183594), 'rotation':(-0.208557, -0.576477, -0.210052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5280.73681641, 3565.42066406, 159.49197266), 'rotation':(-0.21759, -0.576385, -0.219238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5286.25830078, 3565.365, 159.47132812), 'rotation':(-0.226837, -0.57608, -0.228638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5297.30078125, 3565.25390625, 159.42767578000002), 'rotation':(-0.236053, -0.575989, -0.238007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5313.86474609, 3565.08714844, 159.35818359), 'rotation':(-0.248718, -0.576691, -0.250885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5319.38671875, 3565.0314843799997, 159.33427734), 'rotation':(-0.254059, -0.57663, -0.256317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5335.95214844, 3564.86449219, 159.25943359000001), 'rotation':(-0.27005, -0.576447, -0.272614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5346.99511719, 3564.7534375, 159.206875), 'rotation':(-0.280762, -0.576385, -0.283539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5358.03757812, 3564.64210938, 159.15248047), 'rotation':(-0.284729, -0.574432, -0.287567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5374.60304688, 3564.47535156, 159.06916992), 'rotation':(-0.292694, -0.574402, -0.295685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5380.125, 3564.4196875, 159.04089844), 'rotation':(-0.295349, -0.576843, -0.298401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5391.1684375, 3564.30859375, 158.98356445), 'rotation':(-0.300598, -0.576843, -0.303772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5402.21140625, 3564.19726562, 158.92524414), 'rotation':(-0.304718, -0.575775, -0.307983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5781.73976562, 3551.994375, 157.72501953), 'rotation':(-0.077057, 179.422272, -0.077271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5776.04734375, 3552.05152344, 157.71614258), 'rotation':(-0.077057, 179.422272, -0.077271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5764.6596875, 3552.16625, 157.70558594), 'rotation':(-0.018524, 179.42421, -0.018524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5747.58296875, 3552.338125, 157.70306641), 'rotation':(-0.003784, 179.422546, -0.003784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5736.1996875, 3552.4528906200003, 157.70231445), 'rotation':(-0.003784, 179.423996, -0.003784), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5719.12257812, 3552.6247656200003, 157.70144531), 'rotation':(0.007472, 179.423523, 0.007471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5707.73828125, 3552.73949219, 157.70591797), 'rotation':(0.052572, 179.42363, 0.05248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5702.04539062, 3552.796875, 157.71134766), 'rotation':(0.074989, 179.42363, 0.074787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5690.660625, 3552.91164062, 157.72743164), 'rotation':(0.086368, 179.42186, 0.086105), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5684.96875, 3552.9689843799997, 157.73602539), 'rotation':(0.095001, 179.42363, 0.094682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5662.19921875, 3553.19773438, 157.7771582), 'rotation':(0.130108, 179.42215, 0.129526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5645.12304688, 3553.36988281, 157.81945312), 'rotation':(0.156527, 179.42395, 0.155677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5633.73925781, 3553.484375, 157.85081055), 'rotation':(0.167913, 179.423584, 0.166933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5622.35546875, 3553.59914062, 157.88470703000002), 'rotation':(0.183124, 179.421021, 0.181965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5616.66210938, 3553.6564843799997, 157.90296875), 'rotation':(0.190917, 179.423782, 0.189656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5610.97070312, 3553.71386719, 157.92207031), 'rotation':(0.19856, 179.423782, 0.197185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5588.203125, 3553.94289062, 158.00578125), 'rotation':(0.22319, 179.422897, 0.221456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5576.81882812, 3554.05761719, 158.05055664), 'rotation':(0.234316, 179.424515, 0.2324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5565.43601562, 3554.17234375, 158.09795898000002), 'rotation':(0.245416, 179.423111, 0.243328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5536.9765625, 3554.45898438, 158.22610352), 'rotation':(0.268222, 179.424698, 0.265719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5514.21046875, 3554.68824219, 158.33547852), 'rotation':(0.283876, 179.42485, 0.281082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5502.82664062, 3554.80296875, 158.39274414), 'rotation':(0.293753, 179.425812, 0.290745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5497.13476562, 3554.86035156, 158.421875), 'rotation':(0.293746, 179.423447, 0.290752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5468.67726562, 3555.14671875, 158.56956055), 'rotation':(0.306006, 179.426346, 0.302748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5451.60253906, 3555.31859375, 158.66085938), 'rotation':(0.307406, 179.425461, 0.304117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5445.91113281, 3555.37597656, 158.69142578), 'rotation':(0.30727, 179.425415, 0.303993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5434.52832031, 3555.49070312, 158.75239258), 'rotation':(0.306498, 179.422913, 0.303224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5440.28710938, 3563.81371094, 158.72201171999998), 'rotation':(-0.307281, -0.577087, -0.310577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5445.97898438, 3563.75632812, 158.69149414), 'rotation':(-0.307404, -0.574524, -0.31073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5457.36179688, 3563.64183594, 158.63037109), 'rotation':(-0.306, -0.5755, -0.309296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5468.74609375, 3563.52710938, 158.5696582), 'rotation':(-0.302551, -0.575531, -0.305756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5491.51269531, 3563.29785156, 158.45114258), 'rotation':(-0.293732, -0.574188, -0.296783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5497.20460938, 3563.24046875, 158.42195312), 'rotation':(-0.293762, -0.576569, -0.296783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5502.89695312, 3563.18335938, 158.39282227), 'rotation':(-0.291962, -0.575073, -0.294952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5519.9721875, 3563.01125, 158.30756836), 'rotation':(-0.27597, -0.575226, -0.278625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5525.6640625, 3562.95410156, 158.28000977), 'rotation':(-0.271912, -0.575226, -0.274475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5531.35644531, 3562.89671875, 158.25288086), 'rotation':(-0.268188, -0.575256, -0.270721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5542.73976562, 3562.78222656, 158.19989257999998), 'rotation':(-0.262115, -0.577271, -0.264526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5554.125, 3562.66722656, 158.14805664), 'rotation':(-0.256622, -0.575287, -0.258942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5565.5078125, 3562.55273438, 158.09802734000002), 'rotation':(-0.234314, -0.576996, -0.236237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5571.20019531, 3562.49535156, 158.07388672), 'rotation':(-0.234314, -0.576996, -0.236237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5593.96828125, 3562.26609375, 157.98420898), 'rotation':(-0.213776, -0.57605, -0.215363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5599.66113281, 3562.20875, 157.96280273), 'rotation':(-0.206177, -0.576111, -0.207642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5628.12304688, 3561.9221093799997, 157.86737305), 'rotation':(-0.167908, -0.576416, -0.168915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5633.81542969, 3561.86476562, 157.85084961), 'rotation':(-0.160126, -0.576385, -0.161011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5645.1996875, 3561.75, 157.81947266), 'rotation':(-0.147675, -0.576141, -0.148438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5650.89304688, 3561.69289062, 157.80450195), 'rotation':(-0.147675, -0.576141, -0.148438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5702.1259375, 3561.17699219, 157.71136719), 'rotation':(-0.052551, -0.576355, -0.052673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5713.51125, 3561.0622656200003, 157.70263672), 'rotation':(-0.007477, -0.578796, -0.007477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5741.973125, 3560.77585938, 157.70269531), 'rotation':(0.003798, -0.577454, 0.003785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5753.35695312, 3560.66113281, 157.70344727), 'rotation':(0.003791, -0.576019, 0.00379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5759.04882812, 3560.60398438, 157.70382812), 'rotation':(0.018517, -0.57785, 0.018501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5764.74265625, 3560.5466406200003, 157.70558594), 'rotation':(0.047723, -0.57782, 0.047639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5980.87695312, 3555.53808594, 158.7330957), 'rotation':(0.492129, -2.082672, 0.483725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.09375, 3556.55078125, 158.50703125), 'rotation':(0.443013, -2.081818, 0.436201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5947.53757812, 3556.7534375, 158.4653125), 'rotation':(0.431682, -2.084778, 0.42521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.98195312, 3556.95582031, 158.42482422), 'rotation':(0.420555, -2.085175, 0.414426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5930.86867188, 3557.36085938, 158.34744141), 'rotation':(0.386582, -2.083344, 0.3814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5891.97703125, 3558.77855469, 158.09150391), 'rotation':(0.373174, -2.086121, 0.368335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5886.42140625, 3558.9809375, 158.05557617), 'rotation':(0.370155, -2.084564, 0.365403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5880.86421875, 3559.18359375, 158.02056641), 'rotation':(0.357041, -2.087646, 0.352605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5875.3003125, 3559.36011719, 157.98830078), 'rotation':(0.332521, -1.893555, 0.328681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5858.64304688, 3559.60109375, 157.90811523), 'rotation':(0.257553, -0.575897, 0.255246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5847.52101562, 3559.713125, 157.86860352), 'rotation':(0.179511, -0.576508, 0.178388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5841.9609375, 3559.7690625, 157.85273438000002), 'rotation':(0.179511, -0.576508, 0.178388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5830.84671875, 3559.94214844, 157.82748046999998), 'rotation':(0.121051, -0.578125, 0.120545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5836.25875, 3551.30078125, 157.8390918), 'rotation':(-0.121063, 179.424118, -0.121552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5852.94289062, 3551.1325781200003, 157.88669922), 'rotation':(-0.179504, 179.423492, -0.180634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5858.50195312, 3551.07664062, 157.90790039), 'rotation':(-0.218475, 179.423752, -0.220154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5864.0634375, 3551.02074219, 157.93239258), 'rotation':(-0.257538, 179.424088, -0.259888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5880.80765625, 3550.65476562, 158.0221582), 'rotation':(-0.34082, 178.10231, -0.344879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5903.04, 3549.84449219, 158.16543945), 'rotation':(-0.373138, 177.915482, -0.378052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5925.26515625, 3549.03441406, 158.31198242), 'rotation':(-0.378967, 177.915558, -0.384003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5941.93507812, 3548.42675781, 158.42670898), 'rotation':(-0.40918, 177.917664, -0.41507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5947.4921875, 3548.224375, 158.46726562), 'rotation':(-0.420532, 177.915024, -0.426727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5953.04929688, 3548.02171875, 158.5090332), 'rotation':(-0.431671, 177.915207, -0.438232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5964.16359375, 3547.61621094, 158.59629883), 'rotation':(-0.454193, 177.915558, -0.461426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.72023438, 3547.4138281200003, 158.64175781), 'rotation':(-0.465332, 177.915726, -0.472961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.83789062, 3547.14453125, 158.73538086), 'rotation':(-0.482239, 177.916275, -0.490387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.39453125, 3546.9509375, 158.78314453000002), 'rotation':(-0.492157, 177.915451, -0.500671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.93453125, 3546.77976562, 158.83198242), 'rotation':(-0.508087, 178.482285, -0.517151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.19140625, 3786.49289062, 159.64396484), 'rotation':(0.572602, -0.554382, 0.56125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.51125, 3786.54859375, 159.58805664), 'rotation':(0.561496, -0.554596, 0.550575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.83109375, 3786.60398438, 159.53335938), 'rotation':(0.550226, -0.55481, 0.53974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5957.788125, 3786.77046875, 159.37489258), 'rotation':(0.533274, -0.553833, 0.52342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5946.42726562, 3786.88132812, 159.27381836), 'rotation':(0.497641, -0.555328, 0.489066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.74460938, 3786.93703125, 159.22507812), 'rotation':(0.497641, -0.555328, 0.489066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.70359375, 3787.10328125, 159.08780273), 'rotation':(0.449843, -0.556122, 0.442821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5912.34078125, 3787.214375, 159.00086914), 'rotation':(0.437904, -0.556519, 0.431252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5900.97953125, 3787.3254687500003, 158.91737305), 'rotation':(0.426518, -0.555786, 0.420215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5883.93554688, 3787.49195312, 158.80180664), 'rotation':(0.380537, -0.556427, 0.375512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5855.52929688, 3787.76929688, 158.63416016), 'rotation':(0.30563, -0.556305, 0.302398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5844.16453125, 3787.88039062, 158.57712891), 'rotation':(0.273091, -0.559113, 0.270494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.4834375, 3787.93578125, 158.55105469), 'rotation':(0.256856, -0.556732, 0.254569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.75929688, 3788.15773438, 158.46055664), 'rotation':(0.216387, -0.55838, 0.214763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5810.0790625, 3788.21335938, 158.43912109000001), 'rotation':(0.216216, -0.55835, 0.214594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.6753125, 3779.77734375, 158.46053711000002), 'rotation':(-0.216248, 179.441605, -0.217865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5821.35742188, 3779.72195312, 158.48199219), 'rotation':(-0.21637, 179.44165, -0.218018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5832.723125, 3779.61085938, 158.5265918), 'rotation':(-0.224335, 179.442978, -0.226074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.4053125, 3779.55539062, 158.55107422), 'rotation':(-0.24054, 179.440598, -0.242554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5861.13867188, 3779.33351562, 158.66512695), 'rotation':(-0.305664, 179.441238, -0.308929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5872.504375, 3779.2221875, 158.7315332), 'rotation':(-0.338043, 179.444061, -0.342041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5889.55171875, 3779.0559375000003, 158.83930664), 'rotation':(-0.380554, 179.442032, -0.385651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5900.91796875, 3778.94484375, 158.91750977), 'rotation':(-0.403473, 179.443863, -0.40921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5912.28273438, 3778.83398438, 159.00105469), 'rotation':(-0.426544, 179.444199, -0.432922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5917.96578125, 3778.7785937500003, 159.04435547), 'rotation':(-0.437897, 179.443451, -0.444641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5923.64890625, 3778.72289062, 159.08800781), 'rotation':(-0.437897, 179.443451, -0.444641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5974.79054688, 3778.22335938, 159.53375), 'rotation':(-0.539124, 179.444977, -0.549316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.4721875, 3778.16796875, 159.58848633), 'rotation':(-0.550232, 179.447845, -0.560883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.836875, 3778.05710938, 159.70154297), 'rotation':(-0.572632, 179.445618, -0.584137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4765.40429688, 3981.28585938, 156.76623046999998), 'rotation':(-1.08429, 179.728531, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4759.70849609, 3981.3146875, 156.65983398), 'rotation':(-1.08429, 179.728531, -1.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4731.22851562, 3981.45945312, 156.10876953000002), 'rotation':(-1.134827, 179.730652, -1.180481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4725.53125, 3981.48851562, 155.99586914), 'rotation':(-1.14151, 179.731567, -1.187714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4714.13916016, 3981.54664062, 155.76899414), 'rotation':(-1.15509, 179.732132, -1.202393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4679.96289062, 3981.72023438, 155.07012695), 'rotation':(-1.188721, 179.733093, -1.238861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4668.56984375, 3981.77828125, 154.83357422), 'rotation':(-1.188843, 179.733078, -1.238953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4657.17773438, 3981.83617188, 154.59675780999999), 'rotation':(-1.200714, 179.735199, -1.251862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4645.78515625, 3981.8940625, 154.35817383), 'rotation':(-1.204742, 179.733795, -1.256256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4640.08886719, 3981.9231250000003, 154.23833008), 'rotation':(-1.204651, 179.73378, -1.256134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4634.39257812, 3981.9518749999997, 154.11848633), 'rotation':(-1.204651, 179.73378, -1.256134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4611.60695312, 3982.06789062, 153.63913086), 'rotation':(-1.20401, 179.733185, -1.255432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4588.82078125, 3982.18382812, 153.16035156), 'rotation':(-1.202332, 179.734909, -1.253632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4577.42726562, 3982.24171875, 152.9212207), 'rotation':(-1.199188, 179.732681, -1.250214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4560.33640625, 3982.32859375, 152.56575195), 'rotation':(-1.178864, 179.731873, -1.228149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4554.63769531, 3982.35765625, 152.4484082), 'rotation':(-1.172272, 179.733856, -1.221008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4543.24414062, 3982.41578125, 152.21580078), 'rotation':(-1.158813, 179.733292, -1.206421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4520.45164062, 3982.53148438, 151.75686523000002), 'rotation':(-1.140961, 179.730896, -1.187103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4514.75539062, 3982.56054688, 151.64339844), 'rotation':(-1.124817, 179.730301, -1.169647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4503.36035156, 3982.6184375000003, 151.41945312), 'rotation':(-1.109009, 179.72966, -1.152588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4497.6640625, 3982.6475, 151.30914062), 'rotation':(-1.092865, 179.730759, -1.135193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4486.26515625, 3982.7053125, 151.09157227), 'rotation':(-1.084991, 179.729523, -1.126709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4463.47167969, 3982.8215625000003, 150.66498047), 'rotation':(-1.027161, 179.728226, -1.064514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4429.28273438, 3982.90867188, 150.07220703000002), 'rotation':(-0.95285, 179.725571, -0.984955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4429.55957031, 3991.45632812, 150.07609375), 'rotation':(0.952846, -0.274445, 0.921538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4434.91308594, 3991.34742188, 150.16539062), 'rotation':(0.961212, -0.276611, 0.929363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4440.61132812, 3991.31859375, 150.26150391), 'rotation':(0.977584, -0.273499, 0.944631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4457.7065625, 3991.2317187500003, 150.56005859), 'rotation':(1.027151, -0.274323, 0.990804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4497.58984375, 3991.02929688, 151.30686523), 'rotation':(1.108943, -0.270325, 1.066617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4503.28613281, 3991.00023438, 151.41717773), 'rotation':(1.124809, -0.269714, 1.081263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4508.98339844, 3990.9714062499997, 151.52867188), 'rotation':(1.140956, -0.267395, 1.096166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4526.07519531, 3990.88429688, 151.86875977), 'rotation':(1.152349, -0.266968, 1.106673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4531.77148438, 3990.85523438, 151.98313477), 'rotation':(1.152349, -0.266968, 1.106673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4543.16554688, 3990.80710938, 152.21332031), 'rotation':(1.165681, -0.268677, 1.118948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4548.86132812, 3990.74460938, 152.32929688000002), 'rotation':(1.172279, -0.266144, 1.125016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4560.254375, 3990.6775, 152.56320312), 'rotation':(1.185755, -0.265594, 1.137399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4571.64796875, 3990.619375, 152.79951172), 'rotation':(1.199169, -0.265045, 1.149729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4577.34523438, 3990.5903125, 152.91862305), 'rotation':(1.202318, -0.266785, 1.152621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4588.7378125, 3990.5325000000003, 153.15771484), 'rotation':(1.202434, -0.266785, 1.15272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4594.4340625, 3990.50367188, 153.27732422), 'rotation':(1.203028, -0.265137, 1.15327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4600.13039062, 3990.47460938, 153.39697266), 'rotation':(1.203028, -0.265137, 1.15327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4611.52390625, 3990.4167187499997, 153.63649414), 'rotation':(1.204681, -0.266205, 1.15479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4622.91648438, 3990.35867188, 153.87614258), 'rotation':(1.204743, -0.264587, 1.154852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4634.30957031, 3990.30078125, 154.11583984), 'rotation':(1.204743, -0.266205, 1.154847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4640.00585938, 3990.27171875, 154.23568359), 'rotation':(1.204743, -0.266205, 1.154847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4645.70214844, 3990.24265625, 154.35552734), 'rotation':(1.200699, -0.266724, 1.151142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4674.18408203, 3990.09789062, 154.94926758), 'rotation':(1.188822, -0.264465, 1.140225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4679.88085938, 3990.0690624999997, 155.06754883), 'rotation':(1.188726, -0.266907, 1.140132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4685.57861328, 3990.04, 155.18570312), 'rotation':(1.182114, -0.268188, 1.134065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4691.27539062, 3990.01101562, 155.30331055), 'rotation':(1.16857, -0.267334, 1.121611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4696.97119141, 3989.9821875, 155.42025390999999), 'rotation':(1.16857, -0.267334, 1.121611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4702.66748047, 3989.953125, 155.53648438), 'rotation':(1.155128, -0.267883, 1.109235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4719.75732422, 3989.86625, 155.88014648), 'rotation':(1.134843, -0.269348, 1.09052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4748.2421875, 3989.7214062499997, 156.44056641), 'rotation':(1.084292, -0.271454, 1.043818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4759.63769531, 3989.66359375, 156.65769531), 'rotation':(1.063986, -0.270691, 1.025005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4797.78955078, 3981.12109375, 157.35479492000002), 'rotation':(-1.014282, 179.725571, -1.05069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4814.35351562, 3981.036875, 157.64025390999998), 'rotation':(-0.972076, 179.72583, -1.005524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.875, 3981.00875, 157.73242188), 'rotation':(-0.950745, 179.723404, -0.982697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4847.484375, 3980.8684375000003, 158.17875977), 'rotation':(-0.896332, 179.722778, -0.924744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4869.57177734, 3980.75585938, 158.50767578), 'rotation':(-0.826447, 179.720673, -0.850525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4897.18212891, 3980.61523438, 158.88820312), 'rotation':(-0.782166, 179.719391, -0.803741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4908.2265625, 3980.5590625, 159.02878906), 'rotation':(-0.710236, 179.717514, -0.728027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4924.79443359, 3980.47484375, 159.22523438), 'rotation':(-0.656311, 179.714417, -0.671478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4935.83984375, 3980.4140625, 159.35070312), 'rotation':(-0.641235, 179.715881, -0.655701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4941.36181641, 3980.38351562, 159.41150391), 'rotation':(-0.641235, 179.715881, -0.655701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4957.93017578, 3980.32789062, 159.58094727), 'rotation':(-0.580658, 179.7146, -0.592499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4803.35302734, 3989.47359375, 157.45123046999998), 'rotation':(0.993171, -0.275177, 0.959175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4808.87304688, 3989.44554688, 157.54652344), 'rotation':(0.972031, -0.274139, 0.939455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.91699219, 3989.3893749999997, 157.73242188), 'rotation':(0.940237, -0.275208, 0.909751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4825.43896484, 3989.36132812, 157.8237793), 'rotation':(0.940237, -0.275208, 0.909751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4830.95996094, 3989.3332812500003, 157.91439453), 'rotation':(0.931385, -0.276123, 0.901468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4836.48144531, 3989.30515625, 158.00417969), 'rotation':(0.913913, -0.276672, 0.885101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4842.00439453, 3989.27710938, 158.09230469), 'rotation':(0.89636, -0.277222, 0.868624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4875.13525391, 3989.1084375, 158.58572266), 'rotation':(0.800047, -0.280975, 0.777934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4880.65771484, 3989.0803125, 158.66291992), 'rotation':(0.782152, -0.280609, 0.761017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4891.70214844, 3989.02390625, 158.81496094), 'rotation':(0.746143, -0.281555, 0.7269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4924.8359375, 3988.85570312, 159.22523438), 'rotation':(0.656361, -0.282898, 0.641458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4941.40380859, 3988.7785937500003, 159.41150391), 'rotation':(0.610926, -0.28476, 0.598017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4946.92724609, 3988.75242188, 159.47040039), 'rotation':(0.580648, -0.2854, 0.568966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4990.33251953, 3980.14132812, 159.86749023000002), 'rotation':(-0.475861, 179.713776, -0.483826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5007.31835938, 3980.05515625, 159.99666016), 'rotation':(-0.401855, 179.710922, -0.407501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5012.98095703, 3980.02640625, 160.03464844), 'rotation':(-0.401855, 179.710922, -0.407501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5018.64306641, 3979.99757812, 160.07064453), 'rotation':(-0.364868, 179.710403, -0.369537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5024.30664062, 3979.96898438, 160.10489257999998), 'rotation':(-0.346497, 179.710663, -0.350708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5035.63232422, 3979.91109375, 160.17209961), 'rotation':(-0.336487, 179.708298, -0.340424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5041.29589844, 3979.88234375, 160.20300781), 'rotation':(-0.316925, 179.7108, -0.320435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5046.95898438, 3979.85351562, 160.23177734), 'rotation':(-0.297211, 179.710602, -0.300293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5075.27294922, 3979.70945312, 160.34453125), 'rotation':(-0.188904, 179.709991, -0.190155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5092.26123047, 3979.6228125, 160.39817383), 'rotation':(-0.17038, 179.710129, -0.171387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5097.92529297, 3979.59398438, 160.41132812), 'rotation':(-0.132904, 179.70784, -0.133514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5103.58642578, 3979.5651562499997, 160.42132812), 'rotation':(-0.095703, 179.709778, -0.096008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5114.91162109, 3979.50757812, 160.43318359), 'rotation':(-0.058502, 179.707596, -0.058594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5120.57568359, 3979.47875, 160.43711914), 'rotation':(-0.039734, 179.709457, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5131.90380859, 3979.42117188, 160.44496094), 'rotation':(-0.039734, 179.707855, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5137.56787109, 3979.39234375, 160.44889648), 'rotation':(-0.039734, 179.709457, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5143.23193359, 3979.36351562, 160.45283203), 'rotation':(-0.039734, 179.707855, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5148.89355469, 3979.3346874999997, 160.45583984), 'rotation':(-0.039734, 179.707855, -0.039795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5160.21972656, 3979.27710938, 160.45410156), 'rotation':(-0.011993, 179.70932, -0.012024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5194.20019531, 3979.1042187499997, 160.41386719), 'rotation':(0.070918, 179.707855, 0.07074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4996.03710938, 3988.4934375000003, 159.91325195), 'rotation':(0.438997, -0.288544, 0.432303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5007.36083984, 3988.43554688, 159.99666016), 'rotation':(0.364848, -0.287872, 0.360226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5018.68554688, 3988.3776562499997, 160.07064453), 'rotation':(0.346489, -0.289337, 0.342327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5024.34912109, 3988.3489062500003, 160.10489257999998), 'rotation':(0.346338, -0.289337, 0.342176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5030.01171875, 3988.32007812, 160.13908203), 'rotation':(0.336469, -0.288971, 0.33253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5041.33837891, 3988.26242188, 160.20300781), 'rotation':(0.297209, -0.289398, 0.294139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5047.00146484, 3988.23367188, 160.23177734), 'rotation':(0.277517, -0.289612, 0.274846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5052.66259766, 3988.20484375, 160.25841796999998), 'rotation':(0.257785, -0.289764, 0.255475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5075.31542969, 3988.08960938, 160.34453125), 'rotation':(0.188896, -0.290009, 0.187661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5080.97949219, 3988.06078125, 160.36320312), 'rotation':(0.188896, -0.290009, 0.187661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5086.64111328, 3988.03195312, 160.38148438), 'rotation':(0.170365, -0.291962, 0.169362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5092.30371094, 3988.00320312, 160.39817383), 'rotation':(0.132915, -0.29007, 0.132291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5103.62890625, 3987.94554688, 160.42132812), 'rotation':(0.058494, -0.290314, 0.058369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5109.29150391, 3987.9167187499997, 160.42833008), 'rotation':(0.039731, -0.292145, 0.039672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5114.95410156, 3987.8879687500003, 160.43318359), 'rotation':(0.039731, -0.292145, 0.039672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5120.61816406, 3987.85914062, 160.43711914), 'rotation':(0.039731, -0.290527, 0.039676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5126.28222656, 3987.8303125, 160.44103515999998), 'rotation':(0.039731, -0.292145, 0.039683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5131.94628906, 3987.80148438, 160.44496094), 'rotation':(0.039731, -0.292145, 0.039683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5143.27441406, 3987.74390625, 160.45283203), 'rotation':(0.012007, -0.292206, 0.012009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5154.60009766, 3987.6862499999997, 160.45705078), 'rotation':(-0.043274, -0.290649, -0.043335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5160.26220703, 3987.6575000000003, 160.45410156), 'rotation':(-0.043274, -0.290649, -0.043335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5165.92382812, 3987.62867188, 160.44935547), 'rotation':(-0.070923, -0.292145, -0.071075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5194.24267578, 3987.484375, 160.41386719), 'rotation':(-0.087311, -0.290283, -0.087585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5199.90673828, 3987.4553125, 160.40524414), 'rotation':(-0.11969, -0.291656, -0.120178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5205.56982422, 3987.42648438, 160.39451172), 'rotation':(-0.11969, -0.291656, -0.120178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5237.91064453, 3978.881875, 160.30390625), 'rotation':(0.180795, 179.709412, 0.179653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5243.43457031, 3978.85375, 160.28591796999999), 'rotation':(0.189285, 179.709488, 0.188047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5254.48291016, 3978.79757812, 160.24733398), 'rotation':(0.206497, 179.709579, 0.20502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5260.00537109, 3978.76953125, 160.22672852), 'rotation':(0.215014, 179.70697, 0.213412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5265.52978516, 3978.74125, 160.20526367), 'rotation':(0.223511, 179.709732, 0.221769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5276.57714844, 3978.68507812, 160.15969727), 'rotation':(0.24073, 179.709854, 0.23871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5287.62597656, 3978.62890625, 160.11244141), 'rotation':(0.245033, 179.708679, 0.242954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5309.72119141, 3978.51632812, 160.01293945), 'rotation':(0.269342, 179.709244, 0.266813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5315.24511719, 3978.48828125, 159.98626953000002), 'rotation':(0.279095, 179.709351, 0.276394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5326.29248047, 3978.4323437499997, 159.93177734), 'rotation':(0.283951, 179.710785, 0.281156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5331.816875, 3978.40429688, 159.9044043), 'rotation':(0.283938, 179.7108, 0.281139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5348.38914062, 3978.32007812, 159.82124023), 'rotation':(0.290105, 179.71167, 0.287179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5364.96140625, 3978.2356250000003, 159.73585938), 'rotation':(0.297605, 179.711746, 0.294528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5370.48585938, 3978.2075, 159.70691406), 'rotation':(0.300084, 179.709137, 0.296953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5381.53320312, 3978.15140625, 159.6484375), 'rotation':(0.303807, 179.70993, 0.300602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5387.05566406, 3978.06445312, 159.61924805), 'rotation':(0.303014, 179.709152, 0.29983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5396.73242188, 3977.94460938, 159.56837890999998), 'rotation':(0.299968, 179.709106, 0.296847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5398.15332031, 3986.57664062, 159.56115234), 'rotation':(-0.298676, -0.288574, -0.301788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5376.05566406, 3986.55953125, 159.67771484000002), 'rotation':(-0.303802, -0.29007, -0.307037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5370.53171875, 3986.58765625, 159.70689453), 'rotation':(-0.302338, -0.290802, -0.305542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5359.48289062, 3986.64382812, 159.76456055), 'rotation':(-0.297607, -0.290863, -0.30072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5348.43554688, 3986.69992188, 159.82123047), 'rotation':(-0.292572, -0.290924, -0.295593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5331.8628125, 3986.78445312, 159.90438477), 'rotation':(-0.285217, -0.290985, -0.288055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5315.29101562, 3986.86765625, 159.98625), 'rotation':(-0.283936, -0.291168, -0.286774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5293.19482422, 3986.9809375, 160.0884668), 'rotation':(-0.259552, -0.290833, -0.261902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5254.52783203, 3987.17773438, 160.24731445), 'rotation':(-0.215027, -0.290344, -0.216644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5249.00390625, 3987.2057812499997, 160.26704102), 'rotation':(-0.206512, -0.290405, -0.208008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5243.47949219, 3987.23390625, 160.28591796999999), 'rotation':(-0.197815, -0.290436, -0.199158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5237.95556641, 3987.26195312, 160.30390625), 'rotation':(-0.189301, -0.290527, -0.190582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5755.04984375, 3976.2521875, 158.87109375), 'rotation':(-0.191986, 179.709915, -0.193268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5743.6553125, 3976.3103125, 158.83386719), 'rotation':(-0.166016, 179.708344, -0.166962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5737.95898438, 3976.339375, 158.81736328), 'rotation':(-0.153015, 179.708832, -0.153839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5703.77390625, 3976.51265625, 158.73797851999998), 'rotation':(-0.076752, 179.708893, -0.076935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.285625, 3976.6575000000003, 158.71037109), 'rotation':(-0.017487, 179.708313, -0.017487), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5669.586875, 3976.6865625, 158.70865234000001), 'rotation':(-0.017334, 179.708298, -0.017365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5652.49707031, 3976.77367188, 158.70344727), 'rotation':(0.001694, 179.709213, 0.001697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5606.91648438, 3977.00539062, 158.74203125), 'rotation':(0.086648, 179.70723, 0.086388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5595.52101562, 3977.06296875, 158.76131836000002), 'rotation':(0.120129, 179.707321, 0.11963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5578.4296875, 3977.14992188, 158.79956055), 'rotation':(0.148085, 179.708633, 0.147319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5567.0346875, 3977.20796875, 158.82954102), 'rotation':(0.155906, 179.709351, 0.155058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5561.33789062, 3977.23679688, 158.84504883), 'rotation':(0.171424, 179.709473, 0.170399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5544.2465625, 3977.32375, 158.89814453), 'rotation':(0.202659, 179.708252, 0.201228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5532.85203125, 3977.381875, 158.93771484), 'rotation':(0.210513, 179.710037, 0.20898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5521.4575, 3977.4396875, 158.97951172), 'rotation':(0.213819, 179.708679, 0.212215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5515.76074219, 3977.46875, 159.00103516), 'rotation':(0.221073, 179.711334, 0.219368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5504.3671875, 3977.525625, 159.04629882999998), 'rotation':(0.241966, 179.708862, 0.239927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5492.973125, 3977.58445312, 159.09454102), 'rotation':(0.256091, 179.709, 0.253822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5481.57960938, 3977.64257812, 159.14578125), 'rotation':(0.266603, 179.709991, 0.26413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5475.88183594, 3977.67140625, 159.17222656), 'rotation':(0.266569, 179.709991, 0.264114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5464.48875, 3977.72953125, 159.22541992), 'rotation':(0.26982, 179.709305, 0.267284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5458.79199219, 3977.75828125, 159.25244141), 'rotation':(0.276636, 179.711258, 0.273979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5755.09179688, 3984.63234375, 158.87109375), 'rotation':(0.218013, -0.289886, 0.216362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.395, 3984.6614062500003, 158.85199219), 'rotation':(0.191969, -0.291504, 0.190693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5738.0009375, 3984.71945312, 158.81736328), 'rotation':(0.165994, -0.290222, 0.165039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5726.60453125, 3984.77734375, 158.78648438), 'rotation':(0.153017, -0.291168, 0.152215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5715.2109375, 3984.83523438, 158.75925781), 'rotation':(0.127656, -0.290924, 0.127098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5692.41890625, 3984.9509375, 158.72253906), 'rotation':(0.076737, -0.291107, 0.076529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.32765625, 3985.0378124999997, 158.71037109), 'rotation':(0.025941, -0.291199, 0.025919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5669.62890625, 3985.066875, 158.70865234000001), 'rotation':(0.017492, -0.291656, 0.01748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5658.23585938, 3985.12476562, 158.70516602), 'rotation':(0.017492, -0.291687, 0.017478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5652.5390625, 3985.15382812, 158.70344727), 'rotation':(0.017492, -0.291656, 0.01748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5646.8403125, 3985.18265625, 158.70332031), 'rotation':(-0.001709, -0.290741, -0.001678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5641.14257812, 3985.21164062, 158.70568359), 'rotation':(-0.001709, -0.290741, -0.001678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5629.7465625, 3985.26953125, 158.71608398), 'rotation':(-0.058685, -0.291626, -0.058777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5624.04980469, 3985.29859375, 158.7219043), 'rotation':(-0.058685, -0.291626, -0.058777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5618.35304688, 3985.32742188, 158.72773438000002), 'rotation':(-0.058655, -0.290131, -0.058777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5612.65578125, 3985.35640625, 158.73426758), 'rotation':(-0.064178, -0.292847, -0.064301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5595.56296875, 3985.44335938, 158.76131836000002), 'rotation':(-0.108948, -0.292694, -0.109375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5578.47167969, 3985.5299999999997, 158.79956055), 'rotation':(-0.142456, -0.289795, -0.143158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5572.77390625, 3985.5590625, 158.81426758), 'rotation':(-0.148102, -0.291351, -0.148865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5561.37988281, 3985.61695312, 158.84504883), 'rotation':(-0.155914, -0.290619, -0.156738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5555.68261719, 3985.64601562, 158.86208984), 'rotation':(-0.171417, -0.290527, -0.172455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5544.28808594, 3985.70382812, 158.89814453), 'rotation':(-0.187042, -0.29187, -0.188263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5532.8940625, 3985.76195312, 158.93771484), 'rotation':(-0.202667, -0.290314, -0.204102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5504.4096875, 3985.90671875, 159.04629882999998), 'rotation':(-0.235046, -0.291168, -0.236969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5475.92382812, 3986.05148438, 159.17222656), 'rotation':(-0.266602, -0.289978, -0.269073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5470.22753906, 3986.08054688, 159.19873047), 'rotation':(-0.266602, -0.289978, -0.269073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5453.1371875, 3986.1675, 159.27995117), 'rotation':(-0.276672, -0.290649, -0.279327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5447.4409375, 3986.1965625000003, 159.30808594), 'rotation':(-0.283234, -0.288666, -0.286041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5441.74414062, 3986.225625, 159.33669921999999), 'rotation':(-0.289948, -0.290497, -0.292877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5810.234375, 3975.84203125, 159.12469726999998), 'rotation':(-0.324677, 179.710297, -0.328369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.913125, 3975.84328125, 159.15768555), 'rotation':(-0.324677, 179.710297, -0.328369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.61476562, 3975.82765625, 159.30089844), 'rotation':(-0.371368, 179.708908, -0.376221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5844.29, 3975.79882812, 159.33916016), 'rotation':(-0.384216, 179.711685, -0.389374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5849.9653125, 3975.77, 159.37874023), 'rotation':(-0.396912, 179.711823, -0.402435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5872.66890625, 3975.6540625, 159.5503125), 'rotation':(-0.447662, 179.712601, -0.454712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5884.02101562, 3975.5964062499997, 159.6428418), 'rotation':(-0.473053, 179.711563, -0.480927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5889.69625, 3975.5676562500003, 159.69040039), 'rotation':(-0.485626, 179.714157, -0.493927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5901.04640625, 3975.50976562, 159.78921875), 'rotation':(-0.510956, 179.712204, -0.520111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5912.39796875, 3975.4521875, 159.89292969), 'rotation':(-0.523834, 179.714828, -0.533478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.74851562, 3975.39429688, 160.00158203), 'rotation':(-0.549042, 179.715286, -0.559631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5929.42429688, 3975.36546875, 160.0575), 'rotation':(-0.561707, 179.713135, -0.572815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5946.45015625, 3975.2790625, 160.22916992), 'rotation':(-0.578186, 179.715073, -0.589966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.12453125, 3975.25023438, 160.2884668), 'rotation':(-0.598724, 179.713974, -0.611359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5957.80125, 3975.2214062499997, 160.34938477), 'rotation':(-0.598724, 179.713974, -0.611359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5969.15039062, 3975.16359375, 160.47441406), 'rotation':(-0.639618, 179.714844, -0.654022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.82570312, 3975.13453125, 160.53834961), 'rotation':(-0.649933, 179.71582, -0.664825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5986.17578125, 3975.0768749999997, 160.66758789), 'rotation':(-0.64978, 179.71582, -0.664673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5997.52585938, 3975.01929688, 160.79985352), 'rotation':(-0.680847, 179.718155, -0.697205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5810.2778125, 3984.48140625, 159.12469726999998), 'rotation':(0.340902, -0.28952, 0.336868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5815.95554688, 3984.42257812, 159.15766602), 'rotation':(0.340902, -0.28952, 0.336868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5832.97804688, 3984.2365625, 159.26394531), 'rotation':(0.371412, -0.288513, 0.366627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5838.65234375, 3984.20773438, 159.30086914), 'rotation':(0.384205, -0.290924, 0.379072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5844.3271875, 3984.17898438, 159.33913086), 'rotation':(0.396861, -0.288147, 0.39139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5850.00148438, 3984.15015625, 159.37869141), 'rotation':(0.409518, -0.287964, 0.403699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5855.67773438, 3984.12109375, 159.41961914), 'rotation':(0.422345, -0.287781, 0.416148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5884.05125, 3983.97703125, 159.64273438), 'rotation':(0.485585, -0.285828, 0.477409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5895.39992188, 3983.91945312, 159.7390625), 'rotation':(0.510946, -0.28537, 0.501896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5901.07421875, 3983.890625, 159.78908203), 'rotation':(0.523807, -0.287598, 0.514307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5912.42382812, 3983.83273438, 159.89277344), 'rotation':(0.536347, -0.287354, 0.526383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.77296875, 3983.77515625, 160.00140625), 'rotation':(0.561715, -0.286865, 0.550772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5935.12257812, 3983.71726562, 160.11358398000002), 'rotation':(0.578189, -0.284912, 0.566607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5940.7959375, 3983.6887500000003, 160.17083984), 'rotation':(0.598762, -0.286041, 0.586342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5952.1440625, 3983.63109375, 160.28822266), 'rotation':(0.619177, -0.284058, 0.605906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5974.84179688, 3983.515625, 160.53803711), 'rotation':(0.64979, -0.28418, 0.635178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.515625, 3983.4865625, 160.60242188), 'rotation':(0.64979, -0.28418, 0.635178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5986.18992188, 3983.45773438, 160.66725586), 'rotation':(0.660254, -0.284607, 0.645166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.86328125, 3983.42898438, 160.73263672), 'rotation':(0.680758, -0.282471, 0.664731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4942.96777344, 3327.94261719, 155.69584961), 'rotation':(-0.596069, 179.88179, -0.608551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4937.34228516, 3327.95484375, 155.63714844), 'rotation':(-0.60614, 179.88472, -0.61908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4931.71826172, 3327.96703125, 155.57739258), 'rotation':(-0.616455, 179.882233, -0.629822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4926.09179688, 3327.97898438, 155.51652344000001), 'rotation':(-0.626404, 179.885147, -0.640228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4920.46630859, 3327.99121094, 155.45458984), 'rotation':(-0.63678, 179.88266, -0.651062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4914.84082031, 3328.0034375, 155.39157226999998), 'rotation':(-0.652008, 179.885315, -0.666962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4909.21582031, 3328.0153906200003, 155.32777344), 'rotation':(-0.652008, 179.885315, -0.666962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4903.59082031, 3328.02734375, 155.26365234000002), 'rotation':(-0.65686, 179.884354, -0.672028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4897.96435547, 3328.03953125, 155.19888672), 'rotation':(-0.66687, 179.884598, -0.682556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4886.71386719, 3328.06371094, 155.06624023), 'rotation':(-0.686615, 179.885056, -0.703217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4881.08935547, 3328.0759375, 154.99836914), 'rotation':(-0.706329, 179.885544, -0.723938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4869.83789062, 3328.10007812, 154.85948242), 'rotation':(-0.726074, 179.883362, -0.744659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4858.58789062, 3328.12425781, 154.71681640999998), 'rotation':(-0.73111, 179.885864, -0.749939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4852.96191406, 3328.13648438, 154.645), 'rotation':(-0.73111, 179.885864, -0.749939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4836.08691406, 3328.17261719, 154.42667969000001), 'rotation':(-0.764679, 179.887039, -0.785309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4830.46191406, 3328.18480469, 154.35194336), 'rotation':(-0.777954, 179.885468, -0.799316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.21289062, 3328.20921875, 154.19973633), 'rotation':(-0.784698, 179.889175, -0.806396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4813.58691406, 3328.22117188, 154.12267578), 'rotation':(-0.784698, 179.887085, -0.806427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4807.95996094, 3328.23316406, 154.0455957), 'rotation':(-0.78772, 179.88652, -0.809631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4785.4609375, 3328.28199219, 153.73293945), 'rotation':(-0.811737, 179.889771, -0.834991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4768.58447266, 3328.318125, 153.49196289), 'rotation':(-0.829773, 179.887711, -0.854095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4762.96044922, 3328.3303125, 153.41044922), 'rotation':(-0.832825, 179.888901, -0.85733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4757.33544922, 3328.34253906, 153.32866211), 'rotation':(-0.832886, 179.888901, -0.857361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4751.70947266, 3328.35449219, 153.2468457), 'rotation':(-0.832886, 179.888901, -0.857361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4746.08398438, 3328.36671875, 153.16503906), 'rotation':(-0.838104, 179.889008, -0.862885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4740.45996094, 3328.37867188, 153.0828418), 'rotation':(-0.848602, 179.889313, -0.874023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4729.20947266, 3328.4028125, 152.91697266), 'rotation':(-0.853882, 179.889145, -0.879608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4717.95898438, 3328.42699219, 152.74946289), 'rotation':(-0.853882, 179.889145, -0.879608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4706.70800781, 3328.45117188, 152.58176758), 'rotation':(-0.85379, 179.890701, -0.879517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4695.45703125, 3328.47558594, 152.41404297), 'rotation':(-0.853241, 179.888733, -0.878937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4689.83105469, 3328.48753906, 152.33018555), 'rotation':(-0.853241, 179.888733, -0.878937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4684.20556641, 3328.4997656200003, 152.24638672), 'rotation':(-0.852631, 179.888748, -0.878296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4678.58300781, 3328.47875, 152.16267578), 'rotation':(-0.852692, 179.89061, -0.878357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4672.91943359, 3336.98753906, 152.0780957), 'rotation':(0.852626, -0.109375, 0.827525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4678.54443359, 3336.92652344, 152.16183594), 'rotation':(0.852626, -0.109375, 0.827525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4689.79443359, 3336.86867188, 152.329375), 'rotation':(0.853883, -0.11084, 0.828712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4706.67138672, 3336.83226562, 152.58094727), 'rotation':(0.853876, -0.109283, 0.828711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4712.296875, 3336.8200781200003, 152.66481445), 'rotation':(0.853876, -0.109283, 0.828711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4717.92236328, 3336.808125, 152.74865234), 'rotation':(0.853883, -0.11084, 0.828712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4757.30078125, 3336.72339844, 153.32788086), 'rotation':(0.832832, -0.111115, 0.808869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4762.92626953, 3336.7111718799997, 153.4096875), 'rotation':(0.829779, -0.112305, 0.806006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4768.55175781, 3336.69898438, 153.49123047), 'rotation':(0.823871, -0.109894, 0.800432), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4779.80273438, 3336.67699219, 153.65250977), 'rotation':(0.811734, -0.112823, 0.788977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4785.42773438, 3336.66648438, 153.73222656), 'rotation':(0.805846, -0.110382, 0.783413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4791.05371094, 3336.6560156200003, 153.81130859), 'rotation':(0.799699, -0.113159, 0.777607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4802.3046875, 3336.63550781, 153.96765625), 'rotation':(0.787726, -0.113464, 0.766288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4807.93017578, 3336.59984375, 154.04494140999998), 'rotation':(0.784693, -0.112915, 0.763407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4813.55615234, 3336.5759375, 154.12201172), 'rotation':(0.784693, -0.112915, 0.763407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4824.80761719, 3336.5446875, 154.27560547), 'rotation':(0.764674, -0.112976, 0.744469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4830.43261719, 3336.53273438, 154.35129883), 'rotation':(0.764674, -0.112976, 0.744469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4836.05810547, 3336.52050781, 154.42607422), 'rotation':(0.751143, -0.113342, 0.731646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4841.68408203, 3336.50855469, 154.49988281), 'rotation':(0.737913, -0.113678, 0.719096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4847.30908203, 3336.49632812, 154.57238281), 'rotation':(0.73111, -0.114136, 0.712631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4852.93505859, 3336.484375, 154.64444336), 'rotation':(0.731165, -0.114136, 0.712667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4858.56103516, 3336.4721875, 154.71623047), 'rotation':(0.731165, -0.114136, 0.712667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4875.43798828, 3336.43578125, 154.92890625), 'rotation':(0.706344, -0.114441, 0.689089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4881.06445312, 3336.42382812, 154.99785156), 'rotation':(0.696481, -0.114685, 0.679702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4892.31640625, 3336.39964844, 155.13259766), 'rotation':(0.666879, -0.115387, 0.651486), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4920.44580078, 3336.33910156, 155.45416016), 'rotation':(0.626424, -0.114838, 0.612831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4926.07177734, 3336.32691406, 155.51611328), 'rotation':(0.616452, -0.117767, 0.60329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4931.69775391, 3336.31492188, 155.57698242), 'rotation':(0.606138, -0.117981, 0.593419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4937.32470703, 3336.30273438, 155.63676758), 'rotation':(0.596016, -0.115479, 0.583701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4942.95019531, 3336.29027344, 155.69547852), 'rotation':(0.585921, -0.118408, 0.574036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4948.57617188, 3336.27832031, 155.7530957), 'rotation':(0.575566, -0.115906, 0.564089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5179.08789062, 3327.43433594, 157.28860352), 'rotation':(-0.196594, 179.877548, -0.197937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5156.43115234, 3327.48339844, 157.20607422), 'rotation':(-0.227722, 179.879059, -0.229523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5145.10009766, 3327.50757812, 157.16104492), 'rotation':(-0.23642, 179.876373, -0.238373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5133.77197266, 3327.53199219, 157.11392578000002), 'rotation':(-0.253754, 179.878876, -0.255981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5116.77929688, 3327.56859375, 157.031875), 'rotation':(-0.297394, 179.877243, -0.300537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5111.11376953, 3327.58082031, 157.0024707), 'rotation':(-0.297272, 179.879349, -0.300385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5099.78466797, 3327.60498047, 156.94311523), 'rotation':(-0.31543, 179.878311, -0.318939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5094.11962891, 3327.6171875, 156.91197266), 'rotation':(-0.327362, 179.878433, -0.331116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5082.79052734, 3327.64183594, 156.84610351999999), 'rotation':(-0.351379, 179.878738, -0.355713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5077.12841797, 3327.6540625, 156.81141602), 'rotation':(-0.363556, 179.878891, -0.368225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5071.46337891, 3327.66625, 156.77550781), 'rotation':(-0.37561, 179.879044, -0.380554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5043.14160156, 3327.72703125, 156.58194336), 'rotation':(-0.426605, 179.880692, -0.432983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5031.81201172, 3327.75148438, 156.49833984), 'rotation':(-0.448669, 179.879578, -0.455719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5026.15039062, 3327.76367188, 156.45408203), 'rotation':(-0.470612, 179.881378, -0.478394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4997.83105469, 3327.77757812, 156.21975586), 'rotation':(-0.50174, 179.879868, -0.510559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4992.16748047, 3327.72804688, 156.17054688), 'rotation':(-0.514954, 179.882446, -0.524261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5190.43554688, 3335.79054688, 157.32248047), 'rotation':(0.155086, -0.122711, 0.15426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5179.10546875, 3335.8146875, 157.28860352), 'rotation':(0.175884, -0.122589, 0.174808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5167.77783203, 3335.83910156, 157.24957031), 'rotation':(0.196586, -0.122467, 0.195243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5162.11230469, 3335.8513281200003, 157.22808594), 'rotation':(0.217282, -0.122314, 0.215651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5150.78320312, 3335.87574219, 157.18354492), 'rotation':(0.227698, -0.122589, 0.2259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5145.11767578, 3335.88792969, 157.16102539), 'rotation':(0.227718, -0.122589, 0.225909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5133.78955078, 3335.91234375, 157.11390625), 'rotation':(0.2364, -0.121277, 0.234461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5116.79638672, 3335.94898438, 157.031875), 'rotation':(0.288555, -0.123138, 0.285667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5111.13085938, 3335.9611718799997, 157.0024707), 'rotation':(0.297427, -0.120636, 0.294341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5099.80175781, 3335.98535156, 156.9430957), 'rotation':(0.30326, -0.121826, 0.300072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5082.80761719, 3336.02195312, 156.84610351999999), 'rotation':(0.339508, -0.121399, 0.335498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5077.14550781, 3336.03441406, 156.81141602), 'rotation':(0.351386, -0.121246, 0.34709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5065.81591797, 3336.05882812, 156.73839844), 'rotation':(0.375599, -0.120941, 0.370695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5037.49462891, 3336.11960938, 156.54050781), 'rotation':(0.404641, -0.121063, 0.398964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5020.50292969, 3336.15625, 156.40915039), 'rotation':(0.448627, -0.120422, 0.441649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4997.84814453, 3336.25195312, 156.21974609), 'rotation':(0.488358, -0.118011, 0.480089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4992.18505859, 3336.3259375, 156.17054688), 'rotation':(0.501712, -0.120148, 0.492985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4986.51855469, 3336.3591406200003, 156.12005859), 'rotation':(0.514921, -0.117554, 0.50574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5399.879375, 3326.95921875, 157.45195311999998), 'rotation':(0.070344, 179.876755, 0.070167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5383.30273438, 3326.99488281, 157.47030273000001), 'rotation':(0.047306, 179.876694, 0.04723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5322.52392578, 3327.12574219, 157.49899414), 'rotation':(-0.015167, 179.876144, -0.015167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5289.37060547, 3327.19703125, 157.48991211), 'rotation':(-0.028717, 179.876923, -0.028748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5283.84472656, 3327.20898438, 157.48741211), 'rotation':(-0.037445, 179.876923, -0.037506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5278.31933594, 3327.22070312, 157.48399414), 'rotation':(-0.046478, 179.876953, -0.04657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5272.79443359, 3327.23265625, 157.4796582), 'rotation':(-0.055237, 179.876953, -0.055328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5267.27001953, 3327.244375, 157.47439453), 'rotation':(-0.06427, 179.876984, -0.064423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5256.21923828, 3327.26832031, 157.46099609), 'rotation':(-0.082031, 179.877029, -0.082306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5245.16894531, 3327.29199219, 157.44466796999998), 'rotation':(-0.092651, 179.875778, -0.092957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5239.64697266, 3327.21582031, 157.43581055), 'rotation':(-0.105377, 179.877792, -0.105743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5394.3715625, 3335.3513281200003, 157.45874023), 'rotation':(-0.070343, -0.121826, -0.070526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5383.32078125, 3335.375, 157.47030273000001), 'rotation':(-0.058899, -0.12326, -0.059021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5372.26953125, 3335.39890625, 157.47919922), 'rotation':(-0.047302, -0.123291, -0.047394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5361.21972656, 3335.42261719, 157.48586914), 'rotation':(-0.035889, -0.123291, -0.035919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5355.69382812, 3335.43457031, 157.48878906), 'rotation':(-0.03009, -0.124084, -0.030121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5350.16796875, 3335.44652344, 157.49167969), 'rotation':(-0.03009, -0.124084, -0.030121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5339.11671875, 3335.47023438, 157.49748047), 'rotation':(-0.029968, -0.124084, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5333.59179688, 3335.4821875, 157.49961914), 'rotation':(-0.01886, -0.122162, -0.01886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5328.06640625, 3335.49414062, 157.50001953), 'rotation':(0.004043, -0.124542, 0.004041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5305.96484375, 3335.54148438, 157.49458008), 'rotation':(0.015259, -0.12384, 0.015262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5300.43896484, 3335.55347656, 157.49311523), 'rotation':(0.015265, -0.12384, 0.015266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5294.91357422, 3335.56519531, 157.49164062), 'rotation':(0.015272, -0.122162, 0.015261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5289.38867188, 3335.57714844, 157.48991211), 'rotation':(0.019657, -0.123077, 0.019641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5278.33740234, 3335.60109375, 157.48399414), 'rotation':(0.037429, -0.123047, 0.037383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5267.28808594, 3335.6247656200003, 157.47439453), 'rotation':(0.055208, -0.123016, 0.055104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5261.76318359, 3335.63671875, 157.46817382999998), 'rotation':(0.064286, -0.123016, 0.064129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5250.71240234, 3335.66039062, 157.45300781), 'rotation':(0.082037, -0.122955, 0.081812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5245.18701172, 3335.67234375, 157.44466796999998), 'rotation':(0.086491, -0.122589, 0.08623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5834.55273438, 3326.02441406, 157.07856445), 'rotation':(-0.164246, 179.875671, -0.165192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5817.54640625, 3326.06103516, 157.03303711), 'rotation':(-0.122284, 179.876999, -0.122803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.20898438, 3326.08496094, 157.00911133), 'rotation':(-0.111725, 179.877548, -0.112152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5800.54101562, 3326.09716797, 156.99806640999998), 'rotation':(-0.100891, 179.876785, -0.101227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5789.203125, 3326.12158203, 156.97827148), 'rotation':(-0.079132, 179.876724, -0.079346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5777.86421875, 3326.14599609, 156.96365234), 'rotation':(-0.057281, 179.876663, -0.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5772.19625, 3326.15820312, 156.95797851999998), 'rotation':(-0.035614, 179.876633, -0.035645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5766.5278125, 3326.17041016, 156.95404297), 'rotation':(-0.035614, 179.876633, -0.035645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5760.85890625, 3326.18261719, 156.9506543), 'rotation':(-0.024597, 179.877686, -0.024628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5749.52296875, 3326.20703125, 156.94575195), 'rotation':(-0.024719, 179.876007, -0.02475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5743.855, 3326.21923828, 156.94331055), 'rotation':(-0.024719, 179.877701, -0.024719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5726.84914062, 3326.255625, 156.93661133), 'rotation':(0.002677, 179.876572, 0.002679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5721.17921875, 3326.2678125, 156.93755859), 'rotation':(0.030053, 179.877274, 0.030028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5715.51125, 3326.28003906, 156.94050780999999), 'rotation':(0.029957, 179.87561, 0.029927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5687.16992188, 3326.34105469, 156.95556641), 'rotation':(0.036931, 179.875824, 0.03689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5681.50195312, 3326.35328125, 156.95922852), 'rotation':(0.050858, 179.877335, 0.050781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.83351562, 3326.36546875, 156.96375977), 'rotation':(0.050858, 179.877335, 0.050781), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5670.16554688, 3326.37769531, 156.96879883), 'rotation':(0.064709, 179.877365, 0.064565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5641.82375, 3326.43847656, 157.0065625), 'rotation':(0.088123, 179.876266, 0.087861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5630.48730469, 3326.46289062, 157.02415039), 'rotation':(0.093642, 179.876297, 0.093351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5619.15085938, 3326.48730469, 157.04319336), 'rotation':(0.104379, 179.876328, 0.104002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5596.47851562, 3326.53613281, 157.08493164), 'rotation':(0.107978, 179.876114, 0.107576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5585.14210938, 3326.56054688, 157.10661133), 'rotation':(0.111489, 179.878479, 0.11106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5573.80617188, 3326.58496094, 157.12899414), 'rotation':(0.11515, 179.876129, 0.114693), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5568.13820312, 3326.59691406, 157.14042969), 'rotation':(0.116899, 179.878494, 0.116424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5562.47070312, 3326.60914062, 157.15202148), 'rotation':(0.118811, 179.876144, 0.118324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5551.13429688, 3326.63355469, 157.17572266), 'rotation':(0.121475, 179.875809, 0.120965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5545.46632812, 3326.64574219, 157.18774414), 'rotation':(0.120847, 179.877441, 0.120346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5534.13039062, 3326.67015625, 157.21162109), 'rotation':(0.119877, 179.87587, 0.119385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5522.79492188, 3326.69433594, 157.23526367), 'rotation':(0.118811, 179.877441, 0.118323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5511.45898438, 3326.71875, 157.25867188), 'rotation':(0.117404, 179.87677, 0.116919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5477.45214844, 3326.79222656, 157.32688477), 'rotation':(0.107282, 179.87616, 0.106874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5460.44824219, 3326.82886719, 157.358125), 'rotation':(0.101312, 179.876694, 0.100963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5454.78027344, 3326.84105469, 157.36818359), 'rotation':(0.101312, 179.876694, 0.100963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5439.78757812, 3326.74365234, 157.39416015999998), 'rotation':(0.092201, 179.877075, 0.0919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5439.80617188, 3335.3830468799997, 157.39416015999998), 'rotation':(-0.098267, -0.122894, -0.098602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5449.13085938, 3335.23804688, 157.37817383), 'rotation':(-0.101318, -0.123291, -0.101685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5454.79734375, 3335.22144531, 157.36818359), 'rotation':(-0.101318, -0.123291, -0.101685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5460.46484375, 3335.20921875, 157.35813477), 'rotation':(-0.103363, -0.12384, -0.103729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5466.1328125, 3335.19703125, 157.34791992), 'rotation':(-0.107269, -0.122284, -0.107697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5494.4721875, 3335.13574219, 157.2934082), 'rotation':(-0.117249, -0.12323, -0.117737), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5500.13964844, 3335.12351562, 157.281875), 'rotation':(-0.117401, -0.12323, -0.117889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5539.81542969, 3335.03832031, 157.19970703), 'rotation':(-0.12085, -0.122559, -0.121368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5551.15136719, 3335.01367188, 157.17573242), 'rotation':(-0.120544, -0.12149, -0.121063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5562.48730469, 3334.98925781, 157.15202148), 'rotation':(-0.116913, -0.12384, -0.117371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5568.15527344, 3334.97753906, 157.14042969), 'rotation':(-0.115143, -0.121521, -0.115601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5573.82324219, 3334.9653125, 157.12899414), 'rotation':(-0.113403, -0.12384, -0.113831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5579.49121094, 3334.953125, 157.11772461), 'rotation':(-0.111481, -0.123871, -0.111908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5585.15917969, 3334.9409375, 157.10663086), 'rotation':(-0.109741, -0.121521, -0.110138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5590.82765625, 3334.92871094, 157.09568359000002), 'rotation':(-0.107971, -0.123871, -0.108398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5602.16359375, 3334.90429688, 157.07427734), 'rotation':(-0.107056, -0.122772, -0.107452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5630.504375, 3334.84328125, 157.02415039), 'rotation':(-0.088135, -0.123718, -0.088379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5653.17820312, 3334.7946875, 156.98983398000001), 'rotation':(-0.078552, -0.124084, -0.078766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5658.84617188, 3334.78246094, 156.98207031), 'rotation':(-0.064728, -0.12262, -0.06485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5675.85109375, 3334.74585938, 156.96375977), 'rotation':(-0.036926, -0.122681, -0.036987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5687.1875, 3334.72144531, 156.95556641), 'rotation':(-0.029968, -0.122711, -0.029999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5715.52882812, 3334.66039062, 156.94050780999999), 'rotation':(-0.03006, -0.122711, -0.03009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5721.19679688, 3334.6482031200003, 156.93755859), 'rotation':(-0.002686, -0.123413, -0.002686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5732.53710938, 3334.62378906, 156.93842773), 'rotation':(0.024712, -0.122314, 0.024698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5738.20507812, 3334.6115625, 156.94086914), 'rotation':(0.024712, -0.122314, 0.024698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.54101562, 3334.58714844, 156.94575195), 'rotation':(0.024602, -0.123993, 0.024586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5766.54640625, 3334.55054688, 156.95404297), 'rotation':(0.057278, -0.123322, 0.057162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5789.22171875, 3334.50195312, 156.97827148), 'rotation':(0.100875, -0.123199, 0.100532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5800.55953125, 3334.47753906, 156.99806640999998), 'rotation':(0.111721, -0.124084, 0.111294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5806.2275, 3334.46558594, 157.00911133), 'rotation':(0.122295, -0.122986, 0.121761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5811.89648438, 3334.4533593799997, 157.02083984), 'rotation':(0.122295, -0.122986, 0.121761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5817.56546875, 3334.44117188, 157.03304688), 'rotation':(0.143181, -0.122894, 0.142466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5823.2334375, 3334.42894531, 157.04720703), 'rotation':(0.164259, -0.122772, 0.163321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5828.90382812, 3334.41675781, 157.06231445), 'rotation':(0.164259, -0.122772, 0.163321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5834.57179688, 3334.40453125, 157.07856445), 'rotation':(0.185146, -0.12265, 0.183967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5991.84617188, 3325.68603516, 157.96142578), 'rotation':(-0.483887, 179.881516, -0.492096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5980.47414062, 3325.71070312, 157.86694336), 'rotation':(-0.459198, 179.878387, -0.466614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.10203125, 3325.73511719, 157.77783203), 'rotation':(-0.43454, 179.880722, -0.441162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5963.41648438, 3325.74730469, 157.73529297), 'rotation':(-0.409851, 179.87764, -0.415741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5957.7309375, 3325.75953125, 157.69411133), 'rotation':(-0.39743, 179.880188, -0.402954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.67335938, 3325.79613281, 157.5769043), 'rotation':(-0.372131, 179.879395, -0.377014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5934.9878125, 3325.80835938, 157.53974609), 'rotation':(-0.359436, 179.879242, -0.363983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5923.61421875, 3325.83251953, 157.46958984), 'rotation':(-0.333893, 179.876266, -0.337799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5917.92875, 3325.84472656, 157.43663086), 'rotation':(-0.321198, 179.878784, -0.324799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5906.55765625, 3325.869375, 157.37480469), 'rotation':(-0.295776, 179.87851, -0.298859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5889.50195312, 3325.87671875, 157.28860352), 'rotation':(-0.281738, 179.878723, -0.284515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5883.81640625, 3325.82300781, 157.26131836000002), 'rotation':(-0.266724, 179.878586, -0.269226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5991.8515625, 3334.06664062, 157.96131836), 'rotation':(0.489847, -0.119354, 0.481533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5986.16554688, 3334.07886719, 157.9134082), 'rotation':(0.483878, -0.118469, 0.47575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5974.79640625, 3334.10328125, 157.82164062), 'rotation':(0.459146, -0.118866, 0.451837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5969.10984375, 3334.11546875, 157.77775391), 'rotation':(0.446606, -0.121796, 0.439685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5940.68453125, 3334.17652344, 157.57685547), 'rotation':(0.384874, -0.120422, 0.379734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5929.31398438, 3334.2009375, 157.50392578), 'rotation':(0.359446, -0.120758, 0.354965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5900.88625, 3334.26195312, 157.34567383), 'rotation':(0.295788, -0.12149, 0.292747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5895.20117188, 3334.27417969, 157.31695312), 'rotation':(0.289368, -0.120728, 0.286459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5883.83398438, 3334.3940625, 157.26131836000002), 'rotation':(0.281738, -0.123779, 0.278977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.63085938, 3778.90453125, 157.49297852), 'rotation':(-0.115723, -90.457825, -0.11618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.54199219, 3767.81203125, 157.47056641), 'rotation':(-0.127899, -90.460632, -0.128448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.49755859, 3762.26734375, 157.45898438), 'rotation':(-0.127899, -90.460632, -0.128448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.453125, 3756.72195312, 157.44648438000002), 'rotation':(-0.1521, -90.456543, -0.152924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4783.40869141, 3751.17601562, 157.43174805), 'rotation':(-0.176453, -90.460388, -0.177521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.31982422, 3740.0871875000003, 157.39688476999999), 'rotation':(-0.200653, -90.456238, -0.202057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.23095703, 3728.9965625, 157.3565625), 'rotation':(-0.212769, -90.458984, -0.214355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4783.14208984, 3717.90625, 157.3147168), 'rotation':(-0.232544, -90.456757, -0.234436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4783.09765625, 3712.36109375, 157.29205078), 'rotation':(-0.246033, -90.462067, -0.248138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.05322266, 3706.8151562499997, 157.26804688), 'rotation':(-0.259308, -90.456543, -0.261658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4782.91992188, 3690.180625, 157.18783203), 'rotation':(-0.299011, -90.456177, -0.302155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4782.87548828, 3684.6354687499997, 157.15838867), 'rotation':(-0.312134, -90.461395, -0.315552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.56445312, 3645.8203125, 156.92662109), 'rotation':(-0.39447, -90.454773, -0.399902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.47558594, 3634.73, 156.84983398), 'rotation':(-0.405243, -90.456909, -0.41098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.20898438, 3601.46167969, 156.59976562), 'rotation':(-0.496033, -90.45285, -0.504669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4782.12011719, 3590.37109375, 156.50545898000001), 'rotation':(-0.508881, -90.457336, -0.518005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4773.56982422, 3583.17847656, 156.44142578), 'rotation':(0.508911, 89.542625, 0.499937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4773.74023438, 3590.4997656200003, 156.50599609), 'rotation':(0.496015, 89.547127, 0.487493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4773.78466797, 3596.04371094, 156.55400391), 'rotation':(0.470074, 89.543694, 0.462413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4774.00634766, 3623.7578125, 156.77128906), 'rotation':(0.405187, 89.543114, 0.399498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.18408203, 3645.93066406, 156.92691406), 'rotation':(0.37284, 89.54187, 0.368015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.22851562, 3651.47386719, 156.96311523), 'rotation':(0.351188, 89.544662, 0.34691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.31738281, 3662.55953125, 157.03257812), 'rotation':(0.329659, 89.54438, 0.325893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.36181641, 3668.1025, 157.06526367), 'rotation':(0.329659, 89.54438, 0.325893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.40625, 3673.64671875, 157.09714844), 'rotation':(0.318847, 89.542091, 0.315315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.62841797, 3701.3628125, 157.24279296999998), 'rotation':(0.259315, 89.543442, 0.256977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.67285156, 3706.90476562, 157.26814453), 'rotation':(0.246017, 89.537949, 0.243903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4774.80615234, 3723.53492188, 157.33601562), 'rotation':(0.212747, 89.541016, 0.211171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4774.89501953, 3734.6228125, 157.3772168), 'rotation':(0.20065, 89.543747, 0.199253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.07275391, 3756.79492188, 157.44650391), 'rotation':(0.127895, 89.539352, 0.12732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.16162109, 3767.8815624999997, 157.47056641), 'rotation':(0.115717, 89.542198, 0.115246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.20605469, 3773.42578125, 157.48177734), 'rotation':(0.115717, 89.542198, 0.11525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.25048828, 3778.9696875, 157.49296875), 'rotation':(0.107883, 89.539871, 0.107482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4783.97998047, 3822.4973437500003, 157.52165039), 'rotation':(0.001571, -90.458954, 0.001584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.06933594, 3833.5946875, 157.52134766), 'rotation':(0.001489, -90.458984, 0.001494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.11376953, 3839.14359375, 157.52119141), 'rotation':(0.001489, -90.458984, 0.001494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.15820312, 3844.6896875, 157.52101562), 'rotation':(0.001489, -90.458954, 0.001491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.20214844, 3850.23734375, 157.51925781), 'rotation':(0.015252, -90.460602, 0.015239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.33544922, 3866.879375, 157.49728516), 'rotation':(0.09733, -90.460419, 0.096993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4784.42431641, 3877.97679688, 157.47580078000001), 'rotation':(0.110854, -90.458984, 0.110424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.51318359, 3889.07273438, 157.45188477), 'rotation':(0.130525, -90.454956, 0.129928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.60205078, 3900.16945312, 157.42300781), 'rotation':(0.156794, -90.459747, 0.155941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4784.64648438, 3905.71578125, 157.40670898), 'rotation':(0.169942, -90.454742, 0.168933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.69091797, 3911.26414062, 157.38916016), 'rotation':(0.183083, -90.459625, 0.181926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.86914062, 3933.45507812, 157.30772461), 'rotation':(0.226025, -90.460205, 0.224252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4784.95800781, 3944.55171875, 157.26145508), 'rotation':(0.246399, -90.45697, 0.244279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4785.09179688, 3961.19460938, 157.1827832), 'rotation':(0.286929, -90.456604, 0.28407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.51074219, 3811.4665625, 157.52194336), 'rotation':(-0.001495, 89.541046, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.59960938, 3822.56421875, 157.52165039), 'rotation':(-0.001495, 89.541046, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4775.64453125, 3828.1128125, 157.52150390999998), 'rotation':(-0.001495, 89.541046, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.68896484, 3833.66164062, 157.52134766), 'rotation':(-0.001495, 89.541023, -0.001495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.82177734, 3850.30445312, 157.51925781), 'rotation':(-0.042511, 89.544907, -0.042572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4775.95507812, 3866.94625, 157.49728516), 'rotation':(-0.11087, 89.540977, -0.111298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4776.04394531, 3878.0442187500003, 157.47580078000001), 'rotation':(-0.117523, 89.544991, -0.118011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.08837891, 3883.59179688, 157.46444336000002), 'rotation':(-0.130524, 89.540085, -0.131104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.1328125, 3889.14015625, 157.45188477), 'rotation':(-0.143799, 89.540161, -0.144531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.17724609, 3894.68796875, 157.43807617000002), 'rotation':(-0.156799, 89.540207, -0.157654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.35498047, 3916.87914062, 157.37036133), 'rotation':(-0.209381, 89.540573, -0.210907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.39941406, 3922.42726562, 157.3503125), 'rotation':(-0.216034, 89.545151, -0.217682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.44433594, 3927.97484375, 157.32953125), 'rotation':(-0.226044, 89.542839, -0.227814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.57763672, 3944.61890625, 157.26145508), 'rotation':(-0.266571, 89.543205, -0.269073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4776.66650391, 3955.7135937499997, 157.21055664), 'rotation':(-0.286926, 89.543396, -0.289825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4961.55029297, 3095.22729492, 152.47675781), 'rotation':(0.794003, 89.531105, 0.772225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4962.10644531, 3158.17407227, 153.37109375), 'rotation':(0.832853, 89.529823, 0.808899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.24902344, 3175.18480469, 153.61929688), 'rotation':(0.839703, 89.535385, 0.815362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.29638672, 3180.85449219, 153.70248046999998), 'rotation':(0.841848, 89.530121, 0.817368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4962.34375, 3186.52441406, 153.78594727), 'rotation':(0.845407, 89.531532, 0.82073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.58105469, 3214.875, 154.20448242), 'rotation':(0.849853, 89.533775, 0.824907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.81787109, 3243.22509766, 154.626875), 'rotation':(0.854245, 89.530243, 0.82906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4962.90332031, 3254.56542969, 154.79600586), 'rotation':(0.853118, 89.535767, 0.82798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4962.98046875, 3260.23511719, 154.88050781), 'rotation':(0.853118, 89.535767, 0.82798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4963.04101562, 3265.90453125, 154.96492188), 'rotation':(0.851089, 89.53186, 0.826073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.08837891, 3271.57470703, 155.04916015999999), 'rotation':(0.849997, 89.534637, 0.82506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.18359375, 3282.91455078, 155.2174707), 'rotation':(0.850024, 89.531403, 0.825084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.23095703, 3288.58472656, 155.30162109), 'rotation':(0.849921, 89.534622, 0.824985), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4963.27832031, 3294.25439453, 155.38576172), 'rotation':(0.849997, 89.531403, 0.825065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.67333984, 3299.89183594, 155.47043945), 'rotation':(-0.849915, -90.465363, -0.875397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.57861328, 3288.55175781, 155.3021582), 'rotation':(-0.850037, -90.468628, -0.875519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.53076172, 3282.88160156, 155.21799805), 'rotation':(-0.850037, -90.465363, -0.875549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.48339844, 3277.21167969, 155.13386719), 'rotation':(-0.850037, -90.465363, -0.875549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4971.38867188, 3265.87158203, 154.96546875), 'rotation':(-0.853119, -90.464233, -0.878815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4971.34130859, 3260.20214844, 154.88107422), 'rotation':(-0.854279, -90.466736, -0.880035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4971.29394531, 3254.53246094, 154.79655273), 'rotation':(-0.854279, -90.466736, -0.880035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4971.00927734, 3220.51246094, 154.28917969), 'rotation':(-0.849823, -90.466217, -0.875336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.96191406, 3214.8415625, 154.2050293), 'rotation':(-0.845276, -90.463715, -0.870514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.86669922, 3203.50171875, 154.03749023), 'rotation':(-0.845276, -90.468475, -0.870514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.81933594, 3197.83179688, 153.95380859), 'rotation':(-0.845276, -90.468475, -0.870514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.77197266, 3192.161875, 153.87013672), 'rotation':(-0.845428, -90.468475, -0.870636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.53466797, 3163.81030273, 153.45410156), 'rotation':(-0.832825, -90.470154, -0.8573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4970.43945312, 3152.47021484, 153.28936523000002), 'rotation':(-0.828339, -90.470306, -0.85257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.29736328, 3135.45800781, 153.0440332), 'rotation':(-0.820618, -90.46817, -0.84436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.25, 3129.78759766, 152.96293945), 'rotation':(-0.816162, -90.468292, -0.839661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.15478516, 3118.44726562, 152.80202148), 'rotation':(-0.807251, -90.468536, -0.830231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.10742188, 3112.77685547, 152.7221875), 'rotation':(-0.802917, -90.468628, -0.825653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.06005859, 3107.10644531, 152.64277344), 'rotation':(-0.798645, -90.46875, -0.821136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4970.01269531, 3101.4362793, 152.5637793), 'rotation':(-0.794037, -90.468903, -0.816284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4969.97900391, 3095.77172852, 152.48526367), 'rotation':(-0.79187, -90.470642, -0.813995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4972.0859375, 3349.17015625, 156.19275391), 'rotation':(-0.831482, -90.467987, -0.855896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.18115234, 3360.53785156, 156.35673828), 'rotation':(-0.824219, -90.465332, -0.848206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4972.27636719, 3371.9064843799997, 156.51912109), 'rotation':(-0.816956, -90.468384, -0.840485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4972.51416016, 3400.32542969, 156.91775391), 'rotation':(-0.796753, -90.468567, -0.819153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.56152344, 3406.00929688, 156.99592773), 'rotation':(-0.790619, -90.46875, -0.812683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.70410156, 3423.06054688, 157.22682617), 'rotation':(-0.771881, -90.469238, -0.792908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.75146484, 3428.74460938, 157.30261719), 'rotation':(-0.765747, -90.469421, -0.786438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.84667969, 3440.1128125, 157.45291016), 'rotation':(-0.756348, -90.468872, -0.77655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4972.89404297, 3445.7966406200003, 157.52786133), 'rotation':(-0.756348, -90.468872, -0.77655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.03710938, 3462.84839844, 157.74763672), 'rotation':(-0.725586, -90.473724, -0.744141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4973.08447266, 3468.53246094, 157.81871094), 'rotation':(-0.713318, -90.469727, -0.731262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.18017578, 3479.90015625, 157.95916992), 'rotation':(-0.707153, -90.470032, -0.724762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.22753906, 3485.58421875, 158.02875), 'rotation':(-0.70166, -90.472839, -0.718994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4973.27539062, 3491.26832031, 158.09730469), 'rotation':(-0.690887, -90.468964, -0.707733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.32324219, 3496.95265625, 158.16495117), 'rotation':(-0.680145, -90.473389, -0.696442), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.37060547, 3502.63625, 158.23170898), 'rotation':(-0.66925, -90.469482, -0.685028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.41845703, 3508.3203125, 158.29760742), 'rotation':(-0.66925, -90.469482, -0.685028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.46582031, 3514.00464844, 158.36262695), 'rotation':(-0.658478, -90.473877, -0.673767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.56103516, 3525.37328125, 158.48999023), 'rotation':(-0.636871, -90.474365, -0.651154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.61083984, 3531.05710938, 158.5521875), 'rotation':(-0.626099, -90.470459, -0.639893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4973.75927734, 3548.11011719, 158.73478516), 'rotation':(-0.611694, -90.473022, -0.624847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.03857422, 3389.02417969, 156.75955078), 'rotation':(0.803039, 89.531601, 0.780765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.18115234, 3406.0759375, 156.99587891), 'rotation':(0.784338, 89.531075, 0.763072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.22900391, 3411.75929688, 157.0734375), 'rotation':(0.778034, 89.530907, 0.757115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.32373047, 3423.1271875, 157.22677734), 'rotation':(0.765746, 89.530571, 0.745493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.37109375, 3428.81128906, 157.30256836), 'rotation':(0.759305, 89.530403, 0.739384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.51367188, 3445.86328125, 157.5278125), 'rotation':(0.750119, 89.531174, 0.73067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.60888672, 3457.23144531, 157.67545898), 'rotation':(0.725578, 89.526253, 0.707378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.70410156, 3468.59914062, 157.81868164), 'rotation':(0.707116, 89.529976, 0.689824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4964.75195312, 3474.28320312, 157.88910156), 'rotation':(0.707116, 89.529976, 0.689824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4964.94287109, 3497.02, 158.16492188), 'rotation':(0.669283, 89.530487, 0.653778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.17089844, 3525.4409375, 158.48996094), 'rotation':(0.626076, 89.529533, 0.612518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.29736328, 3536.8090625, 158.61388671999998), 'rotation':(0.611684, 89.526962, 0.598732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.92822266, 3614.7621875, 159.35677734), 'rotation':(0.460457, 89.523224, 0.453104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4965.97558594, 3620.45238281, 159.40255859), 'rotation':(0.447473, 89.52301, 0.440522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.11865234, 3637.52027344, 159.53404297), 'rotation':(0.429373, 89.524811, 0.422974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.35693359, 3665.96898438, 159.72856445), 'rotation':(0.348476, 89.522728, 0.344248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.45214844, 3677.34835938, 159.79782226999998), 'rotation':(0.333757, 89.521423, 0.329893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.59521484, 3694.41773438, 159.89396484), 'rotation':(0.2751, 89.520805, 0.272471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.64257812, 3700.10523438, 159.92295898), 'rotation':(0.2751, 89.520805, 0.272471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.69042969, 3705.7959375, 159.95027344), 'rotation':(0.245791, 89.520523, 0.243681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4966.83349609, 3722.86570312, 160.02308594), 'rotation':(0.231168, 89.524422, 0.229312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.92919922, 3734.245625, 160.06835938), 'rotation':(0.218136, 89.521843, 0.216481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4966.9765625, 3739.9353125, 160.08941406), 'rotation':(0.192379, 89.517723, 0.19109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.64257812, 3774.00585938, 160.1784668), 'rotation':(-0.127747, -90.48114, -0.128296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.54785156, 3762.62476562, 160.1530957), 'rotation':(-0.140717, -90.478638, -0.141418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.45214844, 3751.245625, 160.12510742), 'rotation':(-0.166351, -90.478516, -0.167328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.40429688, 3745.5573437499997, 160.10853516), 'rotation':(-0.192383, -90.478333, -0.193665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.35693359, 3739.8671875, 160.08941406), 'rotation':(-0.21814, -90.482086, -0.219818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.30908203, 3734.1770312500003, 160.06835938), 'rotation':(-0.231171, -90.475555, -0.233032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.16601562, 3717.1084375, 160.0000293), 'rotation':(-0.245789, -90.479431, -0.247894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.11816406, 3711.4175, 159.97563477), 'rotation':(-0.275116, -90.476379, -0.277771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4975.02294922, 3700.03757812, 159.92295898), 'rotation':(-0.304443, -90.478912, -0.307678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.97558594, 3694.350625, 159.89398438), 'rotation':(-0.304443, -90.478912, -0.307678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.92773438, 3688.6596875, 159.86374023), 'rotation':(-0.333771, -90.478577, -0.337677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.83251953, 3677.28148438, 159.79785156), 'rotation':(-0.348328, -90.477264, -0.35257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.78515625, 3671.59132812, 159.76323242), 'rotation':(-0.34848, -90.477295, -0.352753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.68994141, 3660.21117188, 159.69282227), 'rotation':(-0.383087, -90.47583, -0.388214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.59423828, 3648.83421875, 159.61683594), 'rotation':(-0.406189, -90.479095, -0.411957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.49902344, 3637.45386719, 159.53407227), 'rotation':(-0.440796, -90.476074, -0.447632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.45166016, 3631.76515625, 159.49083008), 'rotation':(-0.440796, -90.476074, -0.447632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.40380859, 3626.07617188, 159.44705078), 'rotation':(-0.447449, -90.476959, -0.454498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.35644531, 3620.38648438, 159.40258789), 'rotation':(-0.460449, -90.476746, -0.467896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.30859375, 3614.69628906, 159.35681641), 'rotation':(-0.473755, -90.476562, -0.481659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4974.16601562, 3597.62964844, 159.2115918), 'rotation':(-0.513245, -90.475891, -0.522491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4974.02294922, 3580.56128906, 159.05457031), 'rotation':(-0.546112, -90.472778, -0.55661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.87695312, 3966.911875, 159.82166992), 'rotation':(-0.312134, 89.520859, -0.315552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.83105469, 3961.37890625, 159.85133789), 'rotation':(-0.306976, 89.5214, -0.310272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.78466797, 3955.84671875, 159.8799707), 'rotation':(-0.296082, 89.520935, -0.299164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4968.64550781, 3939.25070312, 159.95938476999999), 'rotation':(-0.2742, 89.523811, -0.276825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.55273438, 3928.1848437500003, 160.00587890999998), 'rotation':(-0.230499, 89.520348, -0.232361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.45996094, 3917.1198437499997, 160.04888671999998), 'rotation':(-0.219543, 89.522476, -0.221252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.41357422, 3911.58789062, 160.0690625), 'rotation':(-0.219543, 89.522476, -0.221252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.32080078, 3900.52273438, 160.10609375), 'rotation':(-0.179474, 89.519028, -0.180603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4968.27441406, 3894.9921875, 160.1225), 'rotation':(-0.179474, 89.519028, -0.180603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4968.08935547, 3872.86132812, 160.17353516), 'rotation':(-0.112732, 89.520767, -0.11319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4967.95019531, 3856.26320312, 160.20494141), 'rotation':(-0.098236, 89.516937, -0.098572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4967.85791016, 3845.2018749999997, 160.21495117), 'rotation':(-0.040619, 89.522346, -0.04068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4967.63476562, 3828.605, 160.21522461), 'rotation':(0.002561, 89.520264, 0.002558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4967.45361328, 3812.37429688, 160.21449219), 'rotation':(0.002657, 89.520248, 0.002656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.09277344, 3812.3020312500003, 160.21449219), 'rotation':(-0.002563, -90.476807, -0.002563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.16650391, 3821.1015625, 160.21489258), 'rotation':(-0.002655, -90.479736, -0.002655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.19238281, 3834.06710938, 160.21548828000002), 'rotation':(-0.002655, -90.479736, -0.002655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.20117188, 3839.600625, 160.21574219000001), 'rotation':(-0.002563, -90.479736, -0.002563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.23828125, 3845.1315624999997, 160.21495117), 'rotation':(0.011803, -90.483215, 0.011798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.28417969, 3850.66359375, 160.21148438), 'rotation':(0.040605, -90.477661, 0.040552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.46972656, 3872.79101562, 160.17353516), 'rotation':(0.11263, -90.479218, 0.112188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.51611328, 3878.32273438, 160.16254883), 'rotation':(0.112739, -90.479248, 0.11229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.56201172, 3883.85617188, 160.15037109000002), 'rotation':(0.125983, -90.478333, 0.125431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4976.70117188, 3900.45140625, 160.10609375), 'rotation':(0.152757, -90.47818, 0.151953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4976.79394531, 3911.51710938, 160.0690625), 'rotation':(0.206162, -90.477844, 0.204684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4977.02587891, 3939.17921875, 159.95938476999999), 'rotation':(0.252403, -90.479492, 0.250184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4977.11865234, 3950.24289062, 159.90790039), 'rotation':(0.274205, -90.479309, 0.27158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4977.16503906, 3955.77515625, 159.8799707), 'rotation':(0.274205, -90.479309, 0.27158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4977.21142578, 3961.306875, 159.85133789), 'rotation':(0.296089, -90.475952, 0.293033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4977.2578125, 3966.84007812, 159.82168945), 'rotation':(0.306962, -90.478638, 0.303687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5436.73976562, 3791.85914062, 159.38009766), 'rotation':(-0.381805, -0.55661, -0.386932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5447.14992188, 3791.75757812, 159.31103516), 'rotation':(-0.37619, -0.556671, -0.381165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5452.84765625, 3791.7018749999997, 159.27380859000002), 'rotation':(-0.370331, -0.556763, -0.375153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5458.54539062, 3791.64625, 159.23700195), 'rotation':(-0.364624, -0.558807, -0.369263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5464.24316406, 3791.59054688, 159.20073242), 'rotation':(-0.361755, -0.556213, -0.366364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5475.63769531, 3791.4792187499997, 159.12874023), 'rotation':(-0.361664, -0.558105, -0.366241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5492.73144531, 3791.31226562, 159.02250977), 'rotation':(-0.345337, -0.558258, -0.349518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5498.42871094, 3791.256875, 158.98816406), 'rotation':(-0.334534, -0.556946, -0.33844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5509.8246875, 3791.14546875, 158.92133789), 'rotation':(-0.323486, -0.558502, -0.327148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5515.52195312, 3791.08960938, 158.88916016), 'rotation':(-0.318176, -0.558502, -0.321747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5521.22070312, 3791.0339062499997, 158.85711914), 'rotation':(-0.318176, -0.558502, -0.321747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5526.91796875, 3790.97828125, 158.82548828), 'rotation':(-0.313873, -0.556305, -0.317322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5532.61621094, 3790.92257812, 158.79424805), 'rotation':(-0.306061, -0.55899, -0.309326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5549.71140625, 3790.75585938, 158.70568359), 'rotation':(-0.281647, -0.559296, -0.284393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5561.10742188, 3790.64429688, 158.6509375), 'rotation':(-0.26532, -0.559418, -0.267761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5572.5034375, 3790.53296875, 158.59944336), 'rotation':(-0.253143, -0.557892, -0.255402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5606.69238281, 3790.19921875, 158.46194336), 'rotation':(-0.19397, -0.561096, -0.195282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5612.390625, 3790.14359375, 158.44251953), 'rotation':(-0.184723, -0.55835, -0.185944), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5618.08886719, 3790.08789062, 158.42412109), 'rotation':(-0.180267, -0.558319, -0.181396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5623.78664062, 3790.0321875, 158.40620117), 'rotation':(-0.168762, -0.560272, -0.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5629.48585938, 3789.9765625, 158.38897461), 'rotation':(-0.168762, -0.560272, -0.169769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5635.18359375, 3789.9209375, 158.3721875), 'rotation':(-0.145813, -0.558899, -0.146545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5646.58300781, 3789.80953125, 158.34376953), 'rotation':(-0.122833, -0.55899, -0.123383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5652.28078125, 3789.75414062, 158.33154297), 'rotation':(-0.099884, -0.559113, -0.10022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5657.97898438, 3789.69851562, 158.32078125), 'rotation':(-0.099884, -0.559113, -0.10022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5663.67625, 3789.6428125, 158.31084961), 'rotation':(-0.088379, -0.560669, -0.088684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5680.77046875, 3789.47585938, 158.28445312), 'rotation':(-0.076996, -0.559357, -0.077209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5686.4696875, 3789.42015625, 158.27655273), 'rotation':(-0.076996, -0.559357, -0.077209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5703.56546875, 3789.25320312, 158.25919922), 'rotation':(-0.042938, -0.559326, -0.042999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5732.05320312, 3788.97484375, 158.23788086000002), 'rotation':(-0.042938, -0.559326, -0.042999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5737.7509375, 3788.9192187500003, 158.23362305), 'rotation':(-0.010437, -0.558777, -0.010437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.1528125, 3788.80789062, 158.23332031), 'rotation':(0.054259, -0.560913, 0.054154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5760.55953125, 3788.69679688, 158.25483398), 'rotation':(0.183916, -0.558136, 0.182742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5771.95703125, 3788.6667187499997, 158.29521484), 'rotation':(0.216244, -0.558899, 0.214627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5779.27492188, 3780.00367188, 158.3231543), 'rotation':(-0.216278, 179.441055, -0.217926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5771.8715625, 3780.12429688, 158.29521484), 'rotation':(-0.216125, 179.441055, -0.217743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5760.475625, 3780.31664062, 158.25483398), 'rotation':(-0.11911, 179.441498, -0.119598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5749.07078125, 3780.42773438, 158.23332031), 'rotation':(0.01043, 179.439011, 0.010428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5737.66992188, 3780.5390625, 158.23362305), 'rotation':(0.042935, 179.440613, 0.042875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5709.18164062, 3780.81734375, 158.25494141), 'rotation':(0.042935, 179.440613, 0.042875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5697.78515625, 3780.9284374999997, 158.26394531), 'rotation':(0.054259, 179.439041, 0.054158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5692.08742188, 3780.984375, 158.26933594), 'rotation':(0.076997, 179.440659, 0.076786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5686.38867188, 3781.04, 158.27655273), 'rotation':(0.088396, 179.440872, 0.088131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5674.99265625, 3781.15140625, 158.29323242), 'rotation':(0.088396, 179.440872, 0.088131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5663.59570312, 3781.26242188, 158.31084961), 'rotation':(0.099871, 179.440887, 0.099536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5646.50242188, 3781.42945312, 158.34376953), 'rotation':(0.145797, 179.441086, 0.145073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5640.80226562, 3781.48507812, 158.35758789), 'rotation':(0.145797, 179.441086, 0.145073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5629.40625, 3781.59617188, 158.38896484), 'rotation':(0.180249, 179.439972, 0.179126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5618.00976562, 3781.70773438, 158.42410156), 'rotation':(0.184743, 179.44165, 0.183553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5612.31152344, 3781.7634375, 158.4425), 'rotation':(0.19395, 179.441727, 0.192639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5600.91554688, 3781.87476562, 158.48239258), 'rotation':(0.212193, 179.439072, 0.210626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5595.21679688, 3781.93039062, 158.50384766), 'rotation':(0.221243, 179.441864, 0.219554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5561.02929688, 3782.26414062, 158.65092773), 'rotation':(0.273453, 179.440674, 0.270855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5532.53710938, 3782.54273438, 158.79423828), 'rotation':(0.313868, 179.441086, 0.310444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5521.14355469, 3782.6535937500003, 158.85708984000001), 'rotation':(0.323471, 179.441498, 0.319834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5481.25929688, 3783.0434375, 159.09283203), 'rotation':(0.361679, 179.443756, 0.357128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5464.16699219, 3783.21023438, 159.20070312), 'rotation':(0.364589, 179.443192, 0.359967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5458.46921875, 3783.26585938, 159.23695312), 'rotation':(0.370319, 179.443253, 0.365563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5447.07375, 3783.3771875, 159.31098633), 'rotation':(0.381808, 179.441437, 0.376749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5441.37695312, 3783.43289062, 159.34863281), 'rotation':(0.381808, 179.441437, 0.376749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5396.58546875, 3783.87039062, 159.64950195), 'rotation':(0.387647, 179.442184, 0.382426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5370.145, 3784.12867188, 159.82807617), 'rotation':(0.3829, 179.441528, 0.377816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5359.09375, 3784.2365625, 159.9015625), 'rotation':(0.376555, 179.441452, 0.371631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5353.56789062, 3784.29054688, 159.93788086), 'rotation':(0.373386, 179.443619, 0.368543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5342.51609375, 3784.3984375, 160.00973633), 'rotation':(0.367177, 179.441345, 0.36249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5336.99070312, 3784.45242188, 160.04527344), 'rotation':(0.364001, 179.443497, 0.359396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5331.46484375, 3784.50632812, 160.08054688), 'rotation':(0.364001, 179.443497, 0.359396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5320.41308594, 3784.6145312500003, 160.15055664), 'rotation':(0.356563, 179.442947, 0.352148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5309.36279297, 3784.72265625, 160.21879883), 'rotation':(0.344802, 179.44281, 0.340673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5298.31152344, 3784.8303125, 160.28415039), 'rotation':(0.32119, 179.440826, 0.317608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5287.26123047, 3784.93820312, 160.34663086), 'rotation':(0.315391, 179.442169, 0.311934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5281.73486328, 3784.9921875, 160.37704102), 'rotation':(0.315282, 179.442139, 0.311827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5276.20947266, 3785.04617188, 160.40745117), 'rotation':(0.310384, 179.441406, 0.307043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5270.68359375, 3785.1003124999997, 160.43755859), 'rotation':(0.300433, 179.443863, 0.297294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5265.15820312, 3785.15429688, 160.46682617), 'rotation':(0.290584, 179.441208, 0.287651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5259.6328125, 3785.2082812500003, 160.49511719), 'rotation':(0.280598, 179.441101, 0.277867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5254.10693359, 3785.2621875, 160.52243164), 'rotation':(0.27081, 179.440964, 0.268269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5396.6675, 3792.25070312, 159.64949219), 'rotation':(-0.386322, -0.557831, -0.391571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5386.80421875, 3792.3471875, 159.71623047), 'rotation':(-0.387634, -0.556244, -0.392914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5381.27882812, 3792.4010937499997, 159.75361328), 'rotation':(-0.387634, -0.55777, -0.392883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5359.17625, 3792.61695312, 159.90155273), 'rotation':(-0.379852, -0.558502, -0.384918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5348.12453125, 3792.72484375, 159.97393555), 'rotation':(-0.373383, -0.556366, -0.378265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5326.02148438, 3792.94070312, 160.11560547), 'rotation':(-0.364014, -0.558716, -0.368652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5320.49609375, 3792.99460938, 160.15054688), 'rotation':(-0.362488, -0.555878, -0.367096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5309.4453125, 3793.1025, 160.21879883), 'rotation':(-0.356567, -0.558746, -0.361023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5303.91992188, 3793.15648438, 160.25203125), 'rotation':(-0.344818, -0.55719, -0.348999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5298.39404297, 3793.21070312, 160.28415039), 'rotation':(-0.332947, -0.557312, -0.336853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5292.86865234, 3793.2643749999997, 160.3156543), 'rotation':(-0.332947, -0.557312, -0.336853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5287.34375, 3793.31835938, 160.34662109), 'rotation':(-0.321198, -0.557465, -0.324799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5276.29199219, 3793.42625, 160.40745117), 'rotation':(-0.315247, -0.557831, -0.318726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5270.76611328, 3793.48023438, 160.43754883), 'rotation':(-0.310425, -0.558655, -0.313782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5248.66650391, 3793.74851562, 160.54874023), 'rotation':(-0.270813, -0.55899, -0.273376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5182.50292969, 3785.96140625, 160.78876953), 'rotation':(0.149028, 179.440826, 0.148247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5148.52001953, 3786.29390625, 160.84299805), 'rotation':(0.007418, 179.444626, 0.007416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5142.85742188, 3786.34960938, 160.84396484), 'rotation':(0.007254, 179.427383, 0.007255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5125.86230469, 3786.51953125, 160.84613281), 'rotation':(0.007254, 179.427383, 0.007255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5114.53173828, 3786.6328125, 160.84756836), 'rotation':(-0.012054, 179.427673, -0.012054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5103.20507812, 3786.74609375, 160.84556641), 'rotation':(-0.050568, 179.427704, -0.050659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5091.87939453, 3786.85960938, 160.83137695), 'rotation':(-0.127869, 179.427948, -0.128448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5086.21582031, 3786.91601562, 160.81884766), 'rotation':(-0.147125, 179.426727, -0.147888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5080.55224609, 3786.97289062, 160.80460938), 'rotation':(-0.147095, 179.426758, -0.147858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5046.56982422, 3787.3125, 160.69470703000002), 'rotation':(-0.283722, 179.429688, -0.28656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5018.25097656, 3787.59570312, 160.54888671999998), 'rotation':(-0.323181, 179.428711, -0.326843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5006.92236328, 3787.70898438, 160.48039062), 'rotation':(-0.402893, 179.429718, -0.4086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5001.26220703, 3787.765625, 160.44180663999998), 'rotation':(-0.402893, 179.429718, -0.4086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4995.59912109, 3787.82226562, 160.40112305), 'rotation':(-0.442719, 179.430298, -0.449585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4989.93457031, 3787.87890625, 160.35734375), 'rotation':(-0.462616, 179.430618, -0.470123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5205.24316406, 3794.12039062, 160.72494140999999), 'rotation':(-0.189758, -0.560242, -0.19101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5188.25097656, 3794.2864062500003, 160.77404296999998), 'rotation':(-0.149017, -0.559174, -0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5182.5859375, 3794.34179688, 160.78876953), 'rotation':(-0.149017, -0.559174, -0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5176.92041016, 3794.3971874999997, 160.80349609), 'rotation':(-0.149017, -0.559174, -0.149811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5165.59423828, 3794.50804688, 160.82706055), 'rotation':(-0.095886, -0.560822, -0.096191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5142.93798828, 3794.73, 160.84396484), 'rotation':(-0.007721, -0.617401, -0.007721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5137.27441406, 3794.78664062, 160.84467773), 'rotation':(-0.007263, -0.572601, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5125.94433594, 3794.89992188, 160.84613281), 'rotation':(-0.007263, -0.572662, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5114.61425781, 3795.01320312, 160.84756836), 'rotation':(-0.007263, -0.572662, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5108.95166016, 3795.06960938, 160.84760742), 'rotation':(-0.007263, -0.572662, -0.007263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5097.62695312, 3795.18289062, 160.84017578), 'rotation':(0.050584, -0.572296, 0.050482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5086.29833984, 3795.29640625, 160.81884766), 'rotation':(0.127861, -0.572052, 0.127292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5069.30761719, 3795.46632812, 160.77514648), 'rotation':(0.147109, -0.573242, 0.146361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5046.65283203, 3795.69289062, 160.69470703000002), 'rotation':(0.24478, -0.572327, 0.242714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5035.32617188, 3795.80617188, 160.64010742), 'rotation':(0.283747, -0.57196, 0.280947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5018.33398438, 3795.97609375, 160.54888671999998), 'rotation':(0.303336, -0.571716, 0.300142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5012.67089844, 3796.0325000000003, 160.51629882999998), 'rotation':(0.323198, -0.571289, 0.319568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4995.68261719, 3796.20242188, 160.40112305), 'rotation':(0.402906, -0.570282, 0.397274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4990.01757812, 3796.2590625000003, 160.35734375), 'rotation':(0.442699, -0.568024, 0.435903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4941.06933594, 3796.7487499999997, 159.91470703000002), 'rotation':(0.597771, -0.566376, 0.585401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4930.02197266, 3796.859375, 159.79307617), 'rotation':(0.638247, -0.566376, 0.624151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4907.92724609, 3797.08007812, 159.53540039), 'rotation':(0.693517, -0.563354, 0.676872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4891.35986328, 3797.24585938, 159.31931641), 'rotation':(0.767283, -0.563049, 0.746924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4874.79296875, 3797.41164062, 159.09144531), 'rotation':(0.795259, -0.560211, 0.773404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4852.70410156, 3797.63257812, 158.76597656), 'rotation':(0.872154, -0.560425, 0.845897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4847.18066406, 3797.68796875, 158.68000977), 'rotation':(0.891381, -0.557312, 0.863971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4841.65722656, 3797.7434375000003, 158.59217773), 'rotation':(0.91071, -0.559265, 0.882093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4819.56787109, 3797.964375, 158.22921875), 'rotation':(0.95415, -0.556915, 0.922758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4814.04541016, 3798.01929688, 158.13539062), 'rotation':(0.95415, -0.556915, 0.922758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4808.52636719, 3798.07445312, 158.04009766), 'rotation':(0.983766, -0.555908, 0.95041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4803.00341797, 3798.12960938, 157.94238281), 'rotation':(1.013286, -0.554871, 0.977903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4797.48046875, 3798.1848437500003, 157.84266602), 'rotation':(1.013286, -0.554871, 0.977903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4952.02832031, 3788.1770312500003, 160.02813477), 'rotation':(-0.570648, 179.433075, -0.582092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4940.98681641, 3788.36867188, 159.9147168), 'rotation':(-0.624634, 179.434204, -0.638367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4929.93847656, 3788.47898438, 159.79307617), 'rotation':(-0.656738, 179.434204, -0.671906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4913.36865234, 3788.64476562, 159.60229492), 'rotation':(-0.693481, 179.435104, -0.710419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4891.27587891, 3788.86570312, 159.31931641), 'rotation':(-0.785736, 179.438004, -0.807495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4885.75390625, 3788.9209375, 159.24405273), 'rotation':(-0.785736, 179.438004, -0.807495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4874.70849609, 3789.03148438, 159.09144531), 'rotation':(-0.814575, 179.437881, -0.838013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4869.18457031, 3789.08664062, 159.0127832), 'rotation':(-0.833679, 179.440948, -0.858215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4858.14208984, 3789.19726562, 158.85007812), 'rotation':(-0.872223, 179.442047, -0.899109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4852.61914062, 3789.25242188, 158.76594727), 'rotation':(-0.891388, 179.44017, -0.919464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4847.09521484, 3789.3073437499997, 158.67998047), 'rotation':(-0.910614, 179.440781, -0.939941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4841.57177734, 3789.36257812, 158.59214844), 'rotation':(-0.929932, 179.443848, -0.96051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4825.00585938, 3789.52828125, 158.32123047), 'rotation':(-0.954163, 179.443085, -0.986359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4808.43994141, 3789.69359375, 158.04005859), 'rotation':(-1.013275, 179.445129, -1.049622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4797.39404297, 3789.80421875, 157.84261719), 'rotation':(-1.042786, 179.446182, -1.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4759.47509766, 3790.05398438, 157.1347168), 'rotation':(-1.108215, 179.447632, -1.151733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4742.68554688, 3790.33296875, 156.80476562), 'rotation':(-1.149902, 179.450546, -1.196777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4753.94580078, 3790.11742188, 157.02748047), 'rotation':(-1.124847, 179.450256, -1.169678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4725.69580078, 3790.52125, 156.46234375), 'rotation':(-1.171906, 179.451874, -1.220612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4720.06494141, 3790.57742188, 156.34741211), 'rotation':(-1.180634, 179.452225, -1.230103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4703.17578125, 3790.74632812, 155.99820312), 'rotation':(-1.198303, 179.452972, -1.249237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.54589844, 3790.8025, 155.8802832), 'rotation':(-1.206909, 179.453323, -1.258606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.28515625, 3790.915, 155.64207031), 'rotation':(-1.220215, 179.451736, -1.273041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4675.02539062, 3791.0278125, 155.40220703), 'rotation':(-1.222931, 179.45192, -1.276001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4669.39601562, 3791.08398438, 155.28198242), 'rotation':(-1.228821, 179.454285, -1.28244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4618.72363281, 3791.59054688, 154.18513672), 'rotation':(-1.242157, 179.452835, -1.296936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4613.09375, 3791.64695312, 154.06300781), 'rotation':(-1.240051, 179.454987, -1.294647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4601.8325, 3791.75953125, 153.81915039), 'rotation':(-1.239105, 179.453903, -1.293579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4590.57179688, 3791.8723437500003, 153.57546875), 'rotation':(-1.239166, 179.453888, -1.293701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4579.31101562, 3791.98484375, 153.33175781), 'rotation':(-1.235138, 179.454132, -1.289307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4568.04835938, 3792.09742188, 153.08916992000002), 'rotation':(-1.227539, 179.453766, -1.281036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4562.41699219, 3792.1535937500003, 152.96858398), 'rotation':(-1.219727, 179.45343, -1.272552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4545.5234375, 3792.3225, 152.61024414), 'rotation':(-1.208099, 179.451828, -1.259888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4539.89304688, 3792.37890625, 152.49143555), 'rotation':(-1.202271, 179.453857, -1.253571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4517.36671875, 3792.60398438, 152.02362305), 'rotation':(-1.155151, 179.449478, -1.202454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4506.09863281, 3792.7165625, 151.79626953000002), 'rotation':(-1.143616, 179.451385, -1.189972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4500.46726562, 3792.77296875, 151.68432617), 'rotation':(-1.131714, 179.448532, -1.177124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4494.81835938, 3801.21117188, 151.5715332), 'rotation':(1.131728, -0.549042, 1.087658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4511.71191406, 3801.04226562, 151.90727539), 'rotation':(1.155149, -0.548096, 1.109241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4539.86914062, 3800.7604687499997, 152.48916992), 'rotation':(1.208103, -0.545441, 1.157929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4545.5, 3800.7043750000003, 152.60799805), 'rotation':(1.208226, -0.548218, 1.15803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4556.7621875, 3800.59179688, 152.84634766), 'rotation':(1.219667, -0.546539, 1.168524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4568.02390625, 3800.4792187499997, 153.08685547), 'rotation':(1.235219, -0.545898, 1.182789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4573.65429688, 3800.4228125, 153.20789062), 'rotation':(1.235219, -0.545898, 1.182789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4584.91601562, 3800.3103125, 153.45125), 'rotation':(1.239078, -0.546082, 1.186329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4596.17726562, 3800.1975, 153.69496094), 'rotation':(1.239174, -0.546112, 1.186399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4601.80761719, 3800.14132812, 153.81681641), 'rotation':(1.239174, -0.546112, 1.186399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4613.06835938, 3800.01171875, 154.06063477), 'rotation':(1.242159, -0.544922, 1.189129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4618.69875, 3799.93945312, 154.1827832), 'rotation':(1.243129, -0.547028, 1.190027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4624.32960938, 3799.88304688, 154.30501953), 'rotation':(1.243012, -0.545166, 1.189912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4635.59082031, 3799.77046875, 154.54951172), 'rotation':(1.243047, -0.545135, 1.189951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4641.22070312, 3799.714375, 154.67173828), 'rotation':(1.243129, -0.547028, 1.190027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(4663.74265625, 3799.48921875, 155.15898438), 'rotation':(1.228833, -0.547882, 1.176928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(4669.37257812, 3799.43289062, 155.27969726999999), 'rotation':(1.222918, -0.545898, 1.171511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4686.26513672, 3799.26414062, 155.63987305), 'rotation':(1.215657, -0.546295, 1.164858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4697.52587891, 3799.15140625, 155.87811523), 'rotation':(1.198282, -0.547028, 1.148921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4725.6796875, 3798.8698437499997, 156.4603418), 'rotation':(1.16314, -0.548492, 1.116603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(4731.31054688, 3798.8134375, 156.57454102), 'rotation':(1.154521, -0.551025, 1.108667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(4736.94189453, 3798.75734375, 156.68803711), 'rotation':(1.15004, -0.5495, 1.104534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(4742.57519531, 3798.87109375, 156.80085938), 'rotation':(1.141693, -0.549072, 1.096846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(4748.20556641, 3798.81492188, 156.91300781), 'rotation':(1.124816, -0.551727, 1.08129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5214.97949219, 3102.50195312, 154.57261719), 'rotation':(0.713447, 89.85791, 0.69585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5214.99462891, 3108.17895508, 154.64328125), 'rotation':(0.714287, 89.857918, 0.696646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.00976562, 3113.85546875, 154.71405273), 'rotation':(0.715462, 89.852547, 0.697766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.02490234, 3119.53320312, 154.78491211), 'rotation':(0.716138, 89.857971, 0.698412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.05517578, 3130.88720703, 154.92695312), 'rotation':(0.71816, 89.858025, 0.700323), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.08544922, 3142.24121094, 155.06942383), 'rotation':(0.719704, 89.857086, 0.701788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.11572266, 3153.59521484, 155.21207031), 'rotation':(0.719547, 89.857086, 0.701658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.13085938, 3159.27197266, 155.28338867), 'rotation':(0.719704, 89.857086, 0.701788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.14599609, 3164.94921875, 155.3546875), 'rotation':(0.719349, 89.856216, 0.701447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.19140625, 3181.98023438, 155.5684082), 'rotation':(0.71842, 89.855927, 0.700563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.25244141, 3204.68847656, 155.85305664), 'rotation':(0.71536, 89.859093, 0.697657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.28271484, 3216.04199219, 155.99481445), 'rotation':(0.713092, 89.853485, 0.695507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.31298828, 3227.39599609, 156.13603516), 'rotation':(0.710497, 89.853409, 0.693039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.38916016, 3255.78076172, 156.48704102), 'rotation':(0.702533, 89.855667, 0.685475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.40429688, 3261.45800781, 156.55666992), 'rotation':(0.698291, 89.855583, 0.68142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.41943359, 3267.135, 156.62614258), 'rotation':(0.698291, 89.855583, 0.68142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.44384766, 3278.48902344, 156.76427734), 'rotation':(0.694173, 89.855461, 0.6775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.49560547, 3289.84300781, 156.90166992000002), 'rotation':(0.689692, 89.855438, 0.673226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.47460938, 3295.51976562, 156.97015625), 'rotation':(0.689692, 89.855438, 0.673226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.43701172, 3301.19677734, 157.03841796999998), 'rotation':(0.684911, 89.855324, 0.668687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.89746094, 3295.52367188, 156.97047852), 'rotation':(-0.692078, -90.143951, -0.708954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.86083984, 3289.84839844, 156.90201172), 'rotation':(-0.692078, -90.143951, -0.708954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.84570312, 3284.17138672, 156.83341797), 'rotation':(-0.694183, -90.144501, -0.711121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.81542969, 3272.81761719, 156.69569336), 'rotation':(-0.698334, -90.144409, -0.715485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.80029297, 3267.140625, 156.62648438), 'rotation':(-0.702545, -90.144318, -0.71994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.78515625, 3261.46363281, 156.55702148), 'rotation':(-0.702545, -90.144318, -0.71994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.73974609, 3244.43310547, 156.34732422), 'rotation':(-0.708801, -90.143921, -0.726501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.70898438, 3233.07933594, 156.20680664), 'rotation':(-0.71051, -90.146576, -0.728302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5223.6484375, 3210.37109375, 155.92436523), 'rotation':(-0.715302, -90.1409, -0.733337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.58789062, 3187.66382812, 155.63995117000002), 'rotation':(-0.718475, -90.144073, -0.736633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.57275391, 3181.9865625, 155.56875976999999), 'rotation':(-0.718414, -90.144073, -0.736603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5223.54248047, 3170.6328125, 155.42632812), 'rotation':(-0.71933, -90.143768, -0.737579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5223.52734375, 3164.95556641, 155.35505859), 'rotation':(-0.719696, -90.142883, -0.737946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.49658203, 3153.6015625, 155.21243164), 'rotation':(-0.719727, -90.142883, -0.738007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.45117188, 3136.57006836, 154.99850586), 'rotation':(-0.71817, -90.141968, -0.736359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.43603516, 3130.89331055, 154.92732422), 'rotation':(-0.717316, -90.1474, -0.735474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.42089844, 3125.21606445, 154.85625), 'rotation':(-0.716125, -90.142029, -0.734222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5223.390625, 3113.86157227, 154.7144043), 'rotation':(-0.714294, -90.142059, -0.732269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.14550781, 3538.5346875, 159.48570312), 'rotation':(0.463073, 89.853554, 0.455632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.11523438, 3527.14160156, 159.39208984), 'rotation':(0.473653, 89.851578, 0.465871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.06933594, 3510.05273438, 159.24714844), 'rotation':(0.490927, 89.847527, 0.482564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.03857422, 3498.66113281, 159.14675781), 'rotation':(0.508316, 89.852188, 0.499355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.0234375, 3492.96460938, 159.09537109000001), 'rotation':(0.516895, 89.852333, 0.50763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.99316406, 3481.57179688, 158.99025390999998), 'rotation':(0.534285, 89.852654, 0.524386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.97753906, 3475.8771875, 158.93678711), 'rotation':(0.538615, 89.847679, 0.528559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.90185547, 3447.39601562, 158.65983398), 'rotation':(0.56793, 89.852371, 0.55674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.88671875, 3441.69921875, 158.6021875), 'rotation':(0.579787, 89.8526, 0.568142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.84082031, 3424.61207031, 158.42757812), 'rotation':(0.588407, 89.851578, 0.576423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.82568359, 3418.91625, 158.36845703), 'rotation':(0.594295, 89.857224, 0.582065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.78027344, 3401.82714844, 158.18716797), 'rotation':(0.611493, 89.852074, 0.598561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.76464844, 3396.13085938, 158.12545898), 'rotation':(0.623214, 89.85231, 0.609779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.74951172, 3390.43480469, 158.063125), 'rotation':(0.628931, 89.85244, 0.61524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.71923828, 3379.04320312, 157.93755859), 'rotation':(0.631772, 89.853767, 0.617955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5215.68847656, 3367.651875, 157.81092773), 'rotation':(0.635918, 89.853714, 0.621925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5215.65820312, 3356.25929688, 157.68209961), 'rotation':(0.652317, 89.854088, 0.637587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.02392578, 3350.52390625, 157.61667969), 'rotation':(-0.6604, -90.145721, -0.675751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.0390625, 3356.21996094, 157.68191406), 'rotation':(-0.6604, -90.145721, -0.675751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.09960938, 3379.004375, 157.93738281), 'rotation':(-0.635956, -90.146271, -0.650177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.14550781, 3396.09253906, 158.12529297), 'rotation':(-0.628937, -90.147552, -0.642853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.16064453, 3401.7888281200003, 158.18699219), 'rotation':(-0.617371, -90.147797, -0.630798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.20654297, 3418.87792969, 158.36828125), 'rotation':(-0.600006, -90.148163, -0.61264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.23681641, 3430.26953125, 158.48589844), 'rotation':(-0.58844, -90.148407, -0.600616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.25195312, 3435.96632812, 158.54413086), 'rotation':(-0.585571, -90.147369, -0.597656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.28222656, 3447.3591406200003, 158.6596875), 'rotation':(-0.579773, -90.1474, -0.591614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.29736328, 3453.0549218799997, 158.71628906), 'rotation':(-0.567902, -90.147644, -0.579254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.328125, 3464.44773438, 158.82785156), 'rotation':(-0.556244, -90.147858, -0.567139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.34326172, 3470.14378906, 158.88250976999998), 'rotation':(-0.556244, -90.147858, -0.567139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.45019531, 3510.0178125, 159.24702148), 'rotation':(-0.499603, -90.147949, -0.508392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.49560547, 3527.10695312, 159.39198242), 'rotation':(-0.482239, -90.148254, -0.490387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.51074219, 3532.80347656, 159.43893555), 'rotation':(-0.473633, -90.148407, -0.481506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.54150391, 3544.19679688, 159.53166016), 'rotation':(-0.463104, -90.150879, -0.470642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.24707031, 3576.68507812, 159.77482422), 'rotation':(0.405522, 89.849533, 0.399827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.29296875, 3593.77417969, 159.89453125), 'rotation':(0.38499, 89.849258, 0.379841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.33886719, 3610.86328125, 160.00537109), 'rotation':(0.354384, 89.848862, 0.35002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.35400391, 3616.56007812, 160.04026367), 'rotation':(0.344023, 89.84874, 0.339917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.36914062, 3622.25683594, 160.07416016), 'rotation':(0.333983, 89.84861, 0.330106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.39941406, 3633.65015625, 160.13986328000001), 'rotation':(0.320281, 89.848267, 0.316709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.49121094, 3667.828125, 160.31464844), 'rotation':(0.260941, 89.846359, 0.258575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.50634766, 3673.525625, 160.3405957), 'rotation':(0.260941, 89.846359, 0.258575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.52148438, 3679.22195312, 160.36613281), 'rotation':(0.250176, 89.849327, 0.248004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.56738281, 3696.3125, 160.43728516), 'rotation':(0.207501, 89.848999, 0.206003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.59814453, 3707.7043750000003, 160.47848633), 'rotation':(0.186068, 89.846031, 0.184869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.61328125, 3713.40164062, 160.49699219000001), 'rotation':(0.175392, 89.847404, 0.174328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.65917969, 3730.4921875, 160.5499707), 'rotation':(0.16637, 89.847366, 0.165395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.67431641, 3736.18820312, 160.5665625), 'rotation':(0.148338, 89.847252, 0.147562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.68945312, 3741.885, 160.5818457), 'rotation':(0.130416, 89.84716, 0.129831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.70458984, 3747.5815625, 160.59579102), 'rotation':(0.130416, 89.84716, 0.129831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.71972656, 3753.27828125, 160.60837891), 'rotation':(0.112261, 89.847092, 0.111828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.14648438, 3770.34789062, 160.64011719), 'rotation':(-0.10321, -90.152893, -0.103607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.13134766, 3764.650625, 160.62985351999998), 'rotation':(-0.10321, -90.152893, -0.103607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.11572266, 3758.95484375, 160.61955078), 'rotation':(-0.112274, -90.152893, -0.112701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.10058594, 3753.25734375, 160.60837891), 'rotation':(-0.130432, -90.152832, -0.131012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.0703125, 3741.86421875, 160.5818457), 'rotation':(-0.148315, -90.15274, -0.149109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.05517578, 3736.16773438, 160.5665625), 'rotation':(-0.166382, -90.156555, -0.167328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.97900391, 3707.68429688, 160.47849609000002), 'rotation':(-0.20752, -90.153809, -0.209015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.94824219, 3696.29296875, 160.43730469), 'rotation':(-0.228851, -90.150818, -0.230652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.91748047, 3684.8996875000003, 160.39100586), 'rotation':(-0.250183, -90.153473, -0.25235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.90234375, 3679.20242188, 160.36613281), 'rotation':(-0.260956, -90.148804, -0.263336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.88720703, 3673.50632812, 160.3405957), 'rotation':(-0.260956, -90.153625, -0.263336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.84130859, 3656.41726562, 160.26109375), 'rotation':(-0.286377, -90.152069, -0.289246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.81103516, 3645.0234375, 160.20274414), 'rotation':(-0.320282, -90.148132, -0.323883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.79589844, 3639.32691406, 160.17179688), 'rotation':(-0.320282, -90.148132, -0.323883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.76513672, 3627.93480469, 160.10720703), 'rotation':(-0.333984, -90.151367, -0.337891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5224.71972656, 3610.84523438, 160.00540039), 'rotation':(-0.364594, -90.151001, -0.369232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.68896484, 3599.45359375, 159.93253906), 'rotation':(-0.384979, -90.150757, -0.390167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.65869141, 3588.0603125, 159.85555664), 'rotation':(-0.405518, -90.150452, -0.411316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5224.64355469, 3582.36351562, 159.81554688), 'rotation':(-0.410583, -90.148132, -0.416473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.26660156, 3957.8776562499997, 160.44946289), 'rotation':(-0.21109, 89.848442, -0.212646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.23730469, 3946.7990625, 160.48770507999998), 'rotation':(-0.203247, 89.845871, -0.204681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.20751953, 3935.72117188, 160.52235352), 'rotation':(-0.171448, 89.845657, -0.172485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5217.19287109, 3930.18210938, 160.53838867000002), 'rotation':(-0.171448, 89.845657, -0.172485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.16308594, 3919.10328125, 160.56791992), 'rotation':(-0.155609, 89.84861, -0.156464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5217.1484375, 3913.56492188, 160.58195312), 'rotation':(-0.147614, 89.846977, -0.148376), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.11865234, 3902.48609375, 160.60760742), 'rotation':(-0.137726, 89.847641, -0.138367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.10400391, 3896.94625, 160.61902344), 'rotation':(-0.118073, 89.847565, -0.118561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.07421875, 3885.86914062, 160.63821289), 'rotation':(-0.098267, 89.844551, -0.098602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.04492188, 3874.79078125, 160.65307617), 'rotation':(-0.078552, 89.847427, -0.078766), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5217.00048828, 3858.17140625, 160.67300781), 'rotation':(-0.068665, 89.846657, -0.068817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.98583984, 3852.63375, 160.67797852), 'rotation':(-0.049133, 89.847328, -0.049225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.97070312, 3847.09546875, 160.68112305), 'rotation':(-0.049133, 89.847328, -0.049225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5216.94140625, 3836.01804688, 160.68117188), 'rotation':(0.009924, 89.848381, 0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.91162109, 3824.9387500000003, 160.67925781), 'rotation':(0.009931, 89.845505, 0.009921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5216.86669922, 3808.319375, 160.67638671999998), 'rotation':(0.009835, 89.848373, 0.009829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.26269531, 3813.83742188, 160.67735352), 'rotation':(-0.009918, -90.151611, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.27734375, 3819.3771875, 160.67830078), 'rotation':(-0.009827, -90.15448, -0.009827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.30664062, 3830.4565625, 160.68022461), 'rotation':(-0.009918, -90.151611, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.32177734, 3835.99632812, 160.68117188), 'rotation':(-0.009918, -90.151611, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.33642578, 3841.53367188, 160.68207031), 'rotation':(-0.009918, -90.15448, -0.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.3515625, 3847.07351562, 160.68112305), 'rotation':(0.00976, -90.15271, 0.009756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.38134766, 3858.14914062, 160.67300781), 'rotation':(0.049123, -90.152649, 0.049048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.39599609, 3863.68898438, 160.66634765999999), 'rotation':(0.06865, -90.15332, 0.068485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.44042969, 3880.3073437499997, 160.64583008), 'rotation':(0.068732, -90.15332, 0.068573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.45507812, 3885.84695312, 160.63821289), 'rotation':(0.078527, -90.152588, 0.078331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.47021484, 3891.38601562, 160.62887695), 'rotation':(0.098266, -90.152527, 0.097939), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.49951172, 3902.4635937499997, 160.60760742), 'rotation':(0.11808, -90.155365, 0.117606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.51416016, 3908.0026562499997, 160.59529297), 'rotation':(0.11808, -90.155365, 0.117606), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.57373047, 3930.15945312, 160.53838867000002), 'rotation':(0.155592, -90.151398, 0.154757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5225.61816406, 3946.77640625, 160.48770507999998), 'rotation':(0.187304, -90.151184, 0.18607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.6328125, 3952.3151562499997, 160.46912109000002), 'rotation':(0.187304, -90.151184, 0.18607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5225.66259766, 3963.39359375, 160.42931640999998), 'rotation':(0.203225, -90.151093, 0.201787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.56933594, 3103.70996094, 155.47054688), 'rotation':(0.543663, 90.307266, 0.533417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5416.5390625, 3109.39038086, 155.52432617), 'rotation':(0.539093, 90.307152, 0.529031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.41894531, 3132.11157227, 155.73683594), 'rotation':(0.529674, 90.306999, 0.519952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.38867188, 3137.79150391, 155.78927734), 'rotation':(0.527379, 90.306938, 0.517743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.35890625, 3143.47192383, 155.84152344), 'rotation':(0.526075, 90.312126, 0.5165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.32859375, 3149.15209961, 155.89369141), 'rotation':(0.523739, 90.308029, 0.514227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.08835938, 3194.59423828, 156.3022168), 'rotation':(0.506281, 90.308029, 0.497393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.058125, 3200.27441406, 156.35232421999999), 'rotation':(0.503501, 90.308174, 0.494708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5416.02832031, 3205.95458984, 156.40225586), 'rotation':(0.497866, 90.305069, 0.489273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.90773438, 3228.67601562, 156.59854492), 'rotation':(0.486774, 90.307884, 0.478559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.84765625, 3240.03662109, 156.69485352), 'rotation':(0.483885, 90.307335, 0.475777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.72703125, 3262.7578125, 156.8850293), 'rotation':(0.467007, 90.308243, 0.459447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.69726562, 3268.43824219, 156.9315918), 'rotation':(0.467007, 90.308243, 0.459447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.66699219, 3274.11839844, 156.97787109), 'rotation':(0.460266, 90.308151, 0.452932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.6371875, 3279.79882812, 157.02351562), 'rotation':(0.45681, 90.305771, 0.449573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.51660156, 3302.52050781, 157.20477539), 'rotation':(0.451708, 90.308586, 0.444632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.4565625, 3313.88109375, 157.29378906), 'rotation':(0.441558, 90.305588, 0.434786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.89746094, 3302.57666016, 157.20486328), 'rotation':(-0.456909, -89.691071, -0.464264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5423.92773438, 3296.89697266, 157.1597168), 'rotation':(-0.456909, -89.691071, -0.464264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5423.98730469, 3285.53589844, 157.06912109), 'rotation':(-0.460297, -89.691864, -0.467743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.01757812, 3279.85570312, 157.02362305), 'rotation':(-0.460297, -89.691864, -0.467743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.04785156, 3274.17529297, 156.97797852), 'rotation':(-0.46701, -89.694824, -0.47467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.07765625, 3268.49511719, 156.93168945), 'rotation':(-0.473816, -89.69162, -0.48172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.10789062, 3262.81494141, 156.88513672), 'rotation':(-0.473816, -89.69162, -0.48172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.16796875, 3251.45410156, 156.79066406), 'rotation':(-0.480652, -89.694611, -0.48877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5424.19824219, 3245.77464844, 156.74294921999999), 'rotation':(-0.483917, -89.692657, -0.492126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.28808594, 3228.73339844, 156.59865234), 'rotation':(-0.49234, -89.692017, -0.500854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5424.40867188, 3206.01246094, 156.40236328), 'rotation':(-0.50351, -89.691803, -0.512421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.43847656, 3200.33179688, 156.35245117), 'rotation':(-0.506256, -89.691956, -0.515289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.49851562, 3188.97167969, 156.25214844), 'rotation':(-0.508698, -89.692261, -0.517761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.55859375, 3177.6115625, 156.15133789), 'rotation':(-0.513763, -89.692139, -0.523041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5424.58886719, 3171.93089844, 156.10039061999998), 'rotation':(-0.518768, -89.692047, -0.528229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.64890625, 3160.57055664, 155.99775391), 'rotation':(-0.523712, -89.691986, -0.533356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.73925781, 3143.5300293, 155.84166016), 'rotation':(-0.527405, -89.693054, -0.53717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.76953125, 3137.85009766, 155.78939453), 'rotation':(-0.529694, -89.687378, -0.539551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.82960938, 3126.48974609, 155.68423828000002), 'rotation':(-0.534393, -89.692902, -0.544403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.88964844, 3115.12915039, 155.57798828), 'rotation':(-0.539093, -89.692841, -0.549316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5424.9496875, 3103.76855469, 155.47067383), 'rotation':(-0.543671, -89.692749, -0.554047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.70410156, 3534.65671875, 158.71674805), 'rotation':(-0.292847, -89.694092, -0.295868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.69824219, 3529.12207031, 158.68861328), 'rotation':(-0.292847, -89.694092, -0.295868), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.78613281, 3512.51195312, 158.60255859), 'rotation':(-0.306671, -89.693817, -0.309967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.84472656, 3501.43824219, 158.54285156), 'rotation':(-0.315765, -89.693695, -0.319244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5422.90382812, 3490.36476562, 158.48115234), 'rotation':(-0.324829, -89.696472, -0.328522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.96242188, 3479.29148438, 158.41791992), 'rotation':(-0.331696, -89.694244, -0.335541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.02101562, 3468.2185156200003, 158.3534082), 'rotation':(-0.341003, -89.694122, -0.345093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.0503125, 3462.681875, 158.32049805), 'rotation':(-0.345856, -89.694061, -0.350037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.25488281, 3423.9253125, 158.07818359), 'rotation':(-0.370636, -89.695953, -0.375458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.28417969, 3418.3884375, 158.04236328000002), 'rotation':(-0.378479, -89.692932, -0.383514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.31398438, 3412.8517968799997, 158.00581055), 'rotation':(-0.386353, -89.69577, -0.391602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.43117188, 3390.70484375, 157.8559082), 'rotation':(-0.398071, -89.693481, -0.403625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.46046875, 3385.16871094, 157.81753906), 'rotation':(-0.399963, -89.692719, -0.405579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.48925781, 3379.6325781200003, 157.77899414), 'rotation':(-0.399963, -89.692719, -0.405579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5423.57765625, 3363.02246094, 157.66115234), 'rotation':(-0.415894, -89.692474, -0.421967), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5423.63625, 3351.94921875, 157.58051758), 'rotation':(-0.423859, -89.697876, -0.430176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.3471875, 3523.54125, 158.66029297), 'rotation':(0.292858, 90.30265, 0.289882), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.37648438, 3518.00414062, 158.63154297), 'rotation':(0.29753, 90.306091, 0.294451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.40578125, 3512.46753906, 158.60255859), 'rotation':(0.29753, 90.306091, 0.294451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5414.464375, 3501.39378906, 158.54285156), 'rotation':(0.306696, 90.303322, 0.30341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5414.49367188, 3495.85695312, 158.51232421999998), 'rotation':(0.31576, 90.306282, 0.312305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.52296875, 3490.3200781200003, 158.48114257999998), 'rotation':(0.31576, 90.306282, 0.312305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.55175781, 3484.78246094, 158.44973633), 'rotation':(0.32483, 90.303528, 0.321153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.5815625, 3479.24730469, 158.41791992), 'rotation':(0.329557, 90.309181, 0.325775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.64015625, 3468.17382812, 158.3534082), 'rotation':(0.336517, 90.300842, 0.332586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.90382812, 3418.34375, 158.04236328000002), 'rotation':(0.37062, 90.306938, 0.365854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.96242188, 3407.27074219, 157.96905273000002), 'rotation':(0.378481, 90.304115, 0.373507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.07960938, 3385.12425781, 157.81753906), 'rotation':(0.398043, 90.306511, 0.392553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.19679688, 3362.97777344, 157.66115234), 'rotation':(0.411901, 90.301903, 0.40602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5415.22609375, 3357.44140625, 157.62104492), 'rotation':(0.415897, 90.307526, 0.409895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5415.2846875, 3346.36792969, 157.53953125), 'rotation':(0.423847, 90.307632, 0.417628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5414.02882812, 3583.67308594, 158.94568359000002), 'rotation':(0.248195, 90.302498, 0.246062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.99953125, 3589.21019531, 158.96967773), 'rotation':(0.238128, 90.305443, 0.236159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.94140625, 3600.28367188, 159.01583984), 'rotation':(0.227951, 90.305351, 0.226153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.88234375, 3611.35789062, 159.05949219000001), 'rotation':(0.217692, 90.302254, 0.216045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.85304688, 3616.895, 159.08054688), 'rotation':(0.212658, 90.304848, 0.211089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.82375, 3622.43140625, 159.10123047), 'rotation':(0.212658, 90.304848, 0.211089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.765625, 3633.50488281, 159.14200195), 'rotation':(0.207597, 90.301987, 0.206099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.67726562, 3650.11570312, 159.19976562), 'rotation':(0.187468, 90.305023, 0.186259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.53078125, 3677.79984375, 159.2853418), 'rotation':(0.164157, 90.301743, 0.163214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.50148438, 3683.33664062, 159.30138671999998), 'rotation':(0.158857, 90.301704, 0.157971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.4721875, 3688.8737499999997, 159.316875), 'rotation':(0.153365, 90.307175, 0.15256), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5413.38429688, 3705.48460938, 159.35994141), 'rotation':(0.137116, 90.307091, 0.136468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.23828125, 3733.16945312, 159.42242188), 'rotation':(0.113852, 90.302841, 0.113412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.20898438, 3738.70632812, 159.43345703), 'rotation':(0.103833, 90.305817, 0.103464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.17921875, 3744.243125, 159.44417969), 'rotation':(0.103833, 90.305817, 0.103464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.120625, 3755.31710938, 159.46362305), 'rotation':(0.093731, 90.302765, 0.093412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5413.06203125, 3766.39085938, 159.4812793), 'rotation':(0.084845, 90.303162, 0.084601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.41359375, 3771.973125, 159.48972656), 'rotation':(-0.088684, -89.695343, -0.088959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.44289062, 3766.43601562, 159.4812793), 'rotation':(-0.088684, -89.695343, -0.088959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5421.47167969, 3760.8996875000003, 159.47268555), 'rotation':(-0.093719, -89.697235, -0.094025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.55957031, 3744.28835938, 159.44417969), 'rotation':(-0.113861, -89.697144, -0.114319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.589375, 3738.75171875, 159.43345703), 'rotation':(-0.113861, -89.697144, -0.114319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.61867188, 3733.21460938, 159.42242188), 'rotation':(-0.124084, -89.694092, -0.124603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.67726562, 3722.14109375, 159.39828125), 'rotation':(-0.128998, -89.696106, -0.129578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.76515625, 3705.5303125, 159.35994141), 'rotation':(-0.142609, -89.692871, -0.143311), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.82375, 3694.45679688, 159.33180664), 'rotation':(-0.153381, -89.698303, -0.154205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5421.85304688, 3688.91945312, 159.316875), 'rotation':(-0.158844, -89.69281, -0.159729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.9409375, 3672.30953125, 159.26884766), 'rotation':(-0.172302, -89.695862, -0.17334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.97023438, 3666.7721874999997, 159.25217773), 'rotation':(-0.177368, -89.695038, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.99953125, 3661.23585938, 159.23518555), 'rotation':(-0.177368, -89.695038, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.058125, 3650.161875, 159.19978516), 'rotation':(-0.197601, -89.698059, -0.198975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.20460938, 3622.47777344, 159.10124023), 'rotation':(-0.212677, -89.699951, -0.214233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.26320312, 3611.40453125, 159.05951172), 'rotation':(-0.227966, -89.694641, -0.229767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.32128906, 3600.3303125, 159.01583984), 'rotation':(-0.238129, -89.697571, -0.240112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5422.35058594, 3594.79394531, 158.99291992), 'rotation':(-0.24823, -89.694458, -0.250366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5422.37988281, 3589.25683594, 158.96967773), 'rotation':(-0.24823, -89.694458, -0.250366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5422.40917969, 3583.71972656, 158.94568359000002), 'rotation':(-0.253357, -89.695557, -0.255615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5420.39109375, 3965.12203125, 159.49078125), 'rotation':(0.079941, -89.69809, 0.079724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5420.4496875, 3954.04054688, 159.50605469), 'rotation':(0.074517, -89.697845, 0.074318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.53757812, 3937.4184375, 159.52516602), 'rotation':(0.053296, -89.697906, 0.053207), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.59617188, 3926.33640625, 159.53436523), 'rotation':(0.037416, -89.69519, 0.037368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.62546875, 3920.79664062, 159.53814453), 'rotation':(0.037409, -89.695221, 0.037364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.88964844, 3870.92945312, 159.55457031), 'rotation':(-0.002533, -89.696381, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5420.91894531, 3865.3884375, 159.55431640999998), 'rotation':(-0.002502, -89.696381, -0.002502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.00683594, 3848.76539062, 159.55360352), 'rotation':(-0.007965, -89.698975, -0.007965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.06542969, 3837.68453125, 159.55203125), 'rotation':(-0.019135, -89.693878, -0.019135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.09472656, 3832.14382812, 159.54980469), 'rotation':(-0.030121, -89.698975, -0.030151), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.12402344, 3826.60304688, 159.54650390999998), 'rotation':(-0.041138, -89.693848, -0.041199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5421.183125, 3815.52195312, 159.53779297), 'rotation':(-0.046661, -89.69632, -0.046722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5421.24171875, 3804.4401562499997, 159.52848633), 'rotation':(-0.051849, -89.69574, -0.051941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.01023438, 3965.07789062, 159.49078125), 'rotation':(-0.079834, 90.301872, -0.080048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.03953125, 3959.536875, 159.49851562), 'rotation':(-0.079926, 90.301895, -0.08017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.18601562, 3931.8332812500003, 159.53022461), 'rotation':(-0.053314, 90.305656, -0.053406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.2153125, 3926.29226562, 159.53436523), 'rotation':(-0.042664, 90.302094, -0.042694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.24460938, 3920.7521875, 159.53814453), 'rotation':(-0.037415, 90.304794, -0.037476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.30371094, 3909.66992188, 159.54538086), 'rotation':(-0.037262, 90.304779, -0.037292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.33300781, 3904.12890625, 159.54898438), 'rotation':(-0.037415, 90.304779, -0.037476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.36230469, 3898.58914062, 159.55166992), 'rotation':(-0.027435, 90.302002, -0.027466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.39160156, 3893.04859375, 159.55398438), 'rotation':(-0.027435, 90.302002, -0.027466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.45019531, 3881.9674999999997, 159.55505859000002), 'rotation':(-0.007416, 90.304802, -0.007416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.50878906, 3870.88523438, 159.55457031), 'rotation':(0.002507, 90.303589, 0.002504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.53808594, 3865.34421875, 159.55431640999998), 'rotation':(0.002514, 90.300735, 0.002511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.62648438, 3848.7209375, 159.55360352), 'rotation':(0.002589, 90.303589, 0.002593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':2, 'location':(5412.80226562, 3815.4778125000003, 159.53779297), 'rotation':(0.046766, 90.303658, 0.046688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':2, 'location':(5412.86085938, 3804.39601562, 159.52848633), 'rotation':(0.04665, 90.303673, 0.046572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4002.14773438, 351.05218749999995, 179.67042969), 'rotation':(0.072093, 174.374222, 0.071911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4024.7317187500003, 348.38519531, 179.61855469), 'rotation':(0.158051, 173.116562, 0.157176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4041.66554688, 346.15429687999995, 179.55853516), 'rotation':(0.231352, 172.072632, 0.229491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4047.30617188, 345.34406249999995, 179.53492188), 'rotation':(0.238811, 171.848923, 0.236828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4052.94601562, 344.50125, 179.51119140999998), 'rotation':(0.238811, 171.373627, 0.236817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4058.58054688, 343.62765625, 179.48744141), 'rotation':(0.238585, 171.137238, 0.236608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4069.8293750000003, 341.77828124999996, 179.43546875), 'rotation':(0.281513, 170.360275, 0.278749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4081.0534374999997, 339.8033593800001, 179.37517577999998), 'rotation':(0.315773, 169.835556, 0.312309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4086.651875, 338.76578125000003, 179.34169922), 'rotation':(0.333026, 169.572372, 0.329164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4108.9853125, 334.2990625, 179.19445312), 'rotation':(0.37592, 168.192902, 0.371012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4131.19289062, 329.46929688, 179.02396484000002), 'rotation':(0.479165, 166.729767, 0.471201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4008.36007812, 358.4765625, 179.65929688), 'rotation':(-0.117126, -6.178955, -0.117584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4019.28296875, 357.26429687999996, 179.63570312), 'rotation':(-0.141479, -6.673859, -0.142181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4030.17875, 355.79003906, 179.60480468999998), 'rotation':(-0.185059, -7.301147, -0.186249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4062.8645312500003, 351.06824219, 179.47431641), 'rotation':(-0.261353, -9.37561, -0.263733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4068.30101562, 350.17640625, 179.44953125), 'rotation':(-0.278198, -9.639648, -0.280884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4079.16210938, 348.2975, 179.39373047), 'rotation':(-0.312042, -10.164215, -0.31546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4084.57445312, 347.31542969, 179.36300781000003), 'rotation':(-0.345917, -10.690369, -0.350098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4089.98898438, 346.30273437999995, 179.33029297000002), 'rotation':(-0.362732, -10.952087, -0.36734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4100.80226562, 344.18640625, 179.25990234), 'rotation':(-0.371155, -11.392487, -0.376007), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4111.578125, 341.951875, 179.18814453), 'rotation':(-0.380524, -12.03125, -0.38562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4116.94679688, 340.79312500000003, 179.15054688), 'rotation':(-0.417908, -12.527802, -0.424042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4133.04101562, 337.27882811999996, 179.02394531000002), 'rotation':(-0.491943, -13.516907, -0.500458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4138.38039062, 336.00304688000006, 178.97726562), 'rotation':(-0.51062, -13.764709, -0.519775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4007.7370312499997, 794.25158203, 180.08177734), 'rotation':(-0.304382, -0.454285, -0.307617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4012.9856250000003, 794.20972656, 180.05388672), 'rotation':(-0.349152, -0.453796, -0.353424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4018.22976562, 794.16796875, 180.02244141), 'rotation':(-0.394043, -0.45282, -0.399506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4023.4765625, 794.12621094, 179.98974609), 'rotation':(-0.394043, -0.45282, -0.399506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4002.4714062499997, 786.41271484, 180.10769531000003), 'rotation':(0.259383, 179.545288, 0.257047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4012.9557812499997, 786.32933594, 180.05371093999997), 'rotation':(0.304387, 179.545685, 0.301167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4018.19359375, 786.28759766, 180.02228516), 'rotation':(0.349166, 179.5466, 0.344922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4077.77976562, 785.81330078, 179.52695312), 'rotation':(0.589438, 179.550186, 0.577402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4111.046875, 785.54839844, 179.13171875), 'rotation':(0.734252, 179.553452, 0.715626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4122.13820312, 785.4600781199999, 178.97707031000002), 'rotation':(0.788142, 179.555252, 0.766671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4144.3159375, 785.28351562, 178.64208984), 'rotation':(0.886559, 179.558334, 0.859435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4155.401875, 785.19525391, 178.45970703), 'rotation':(0.95723, 179.560608, 0.925632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4183.11476562, 784.97455078, 177.94251953), 'rotation':(1.13377, 179.567062, 1.089544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4072.29226562, 793.73779297, 179.58554688), 'rotation':(-0.632019, -0.448914, -0.646088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4088.930625, 793.60535156, 179.40277343999998), 'rotation':(-0.680359, -0.447876, -0.696655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4100.0234375, 793.51708984, 179.27263672), 'rotation':(-0.734253, -0.446167, -0.753265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4105.56789062, 793.47302734, 179.20302734), 'rotation':(-0.734253, -0.446167, -0.753265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4122.20117188, 793.34058594, 178.97707031000002), 'rotation':(-0.842102, -0.443207, -0.867126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4127.74804688, 793.2964453100001, 178.89550781000003), 'rotation':(-0.86911, -0.442688, -0.895782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4138.836875, 793.20818359, 178.72798827999998), 'rotation':(-0.886566, -0.442322, -0.914337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4144.381875, 793.16417969, 178.64205077999998), 'rotation':(-0.92215, -0.440552, -0.952179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4149.92382812, 793.12, 178.55263672), 'rotation':(-0.957245, -0.440033, -0.989655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4155.46828125, 793.0759375, 178.45962891), 'rotation':(-0.992645, -0.438171, -1.027496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4161.01078125, 793.03173828, 178.36316406000003), 'rotation':(-1.027893, -0.437592, -1.065308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4166.55515625, 792.98767578, 178.263125), 'rotation':(-1.063293, -0.435638, -1.103333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4172.09617188, 792.94353516, 178.15962890999998), 'rotation':(-1.098541, -0.434967, -1.141296), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4188.72953125, 792.81128906, 177.83087891), 'rotation':(-1.15152, -0.432434, -1.198517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4028.223125, 604.07359375, 179.66820312), 'rotation':(0.266166, -179.712006, 0.263705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4023.1896875, 604.11792969, 179.69158202999998), 'rotation':(0.219994, -179.712402, 0.218309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4018.01953125, 604.15214844, 179.71494141), 'rotation':(0.219994, -179.712402, 0.218309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4012.84328125, 604.12632812, 179.73480468999998), 'rotation':(0.173726, -179.713104, 0.172675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4002.4934375000003, 604.07464844, 179.76892578), 'rotation':(0.111134, -179.752823, 0.1107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4018.08664062, 611.99992188, 179.71453125), 'rotation':(-0.266174, 0.287983, -0.268646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4181.80375, 612.6876171900001, 178.09115234), 'rotation':(-0.902344, -2.49646, -0.931122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4165.2534375, 612.76878906, 178.34234375), 'rotation':(-0.84549, -0.015961, -0.870728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4143.0825, 612.67820312, 178.64658203), 'rotation':(-0.739624, 0.296382, -0.758911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4115.35398438, 612.66414062, 178.98078125), 'rotation':(-0.633026, 0.293779, -0.647095), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4109.8090625, 612.6364062499999, 179.04035156), 'rotation':(-0.607269, 0.293251, -0.620239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4098.71828125, 612.58097656, 179.15167968999998), 'rotation':(-0.555603, 0.292174, -0.566437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4093.17257812, 612.55320312, 179.2034375), 'rotation':(-0.529785, 0.291688, -0.539642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4087.6262500000003, 612.5254687500001, 179.25365234), 'rotation':(-0.516815, 0.291369, -0.526215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4076.53296875, 612.4699218799999, 179.35152344), 'rotation':(-0.497711, 0.290963, -0.506409), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4177.32179688, 604.65730469, 178.15804688), 'rotation':(0.912117, 178.727142, 0.883408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4144.00242188, 604.6370312500001, 178.63523438), 'rotation':(0.723542, -179.704193, 0.705435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4138.4575, 604.60929688, 178.70595702999998), 'rotation':(0.723542, -179.704193, 0.705435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4127.36671875, 604.55382812, 178.84332031000002), 'rotation':(0.68461, -179.705032, 0.668398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4110.73242188, 604.4707812500001, 179.03099609), 'rotation':(0.581563, -179.707306, 0.56984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4088.55125, 604.42597656, 179.24566406000002), 'rotation':(0.516813, -179.708633, 0.507553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4077.45945312, 604.3941796900001, 179.34382812), 'rotation':(0.459248, -179.709686, 0.451934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4219.0078125, 608.8200781200001, 177.4665625), 'rotation':(-1.021667, -9.434418, -1.058624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4229.65382812, 606.91734375, 177.26994141), 'rotation':(-1.058807, -11.340302, -1.098511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4240.3628125, 604.61210938, 177.06537109), 'rotation':(-1.063751, -13.241241, -1.103821), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4245.70554688, 603.3158593799999, 176.96246093999997), 'rotation':(-1.073181, -14.378174, -1.113983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4261.91015625, 598.75828125, 176.6409375), 'rotation':(-1.103729, -17.253906, -1.146912), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4272.68015625, 595.1973437500001, 176.41876953), 'rotation':(-1.124817, -19.40451, -1.169678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4283.36570312, 591.22589844, 176.19345703), 'rotation':(-1.124908, -21.493256, -1.169739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4299.17726562, 584.50886719, 175.85369140999998), 'rotation':(-1.126129, -24.730316, -1.171082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4304.30664062, 582.10332031, 175.74160156000002), 'rotation':(-1.126923, -25.985748, -1.171936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4324.44921875, 571.5133203099999, 175.29078125), 'rotation':(-1.113525, -30.201996, -1.157501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4329.359375, 568.63609375, 175.17951172000002), 'rotation':(-1.093964, -31.426422, -1.136383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4348.151875, 556.46367188, 174.75847656000002), 'rotation':(-1.034882, -35.10498, -1.072815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4356.99265625, 550.0410937500001, 174.56261718999997), 'rotation':(-0.995331, -37.546173, -1.030365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4361.31789062, 546.72535156, 174.46712890999999), 'rotation':(-0.985809, -38.162659, -1.020172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4365.50390625, 543.40476562, 174.37503906), 'rotation':(-0.970764, -39.249725, -1.004089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4360.30761719, 537.2846093799999, 174.37837890999998), 'rotation':(1.014167, 141.226959, 0.978723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4355.95996094, 540.73585938, 174.47658203), 'rotation':(1.034234, 142.451477, 0.997401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4337.57273438, 553.97941406, 174.89541015999998), 'rotation':(1.106026, 146.737366, 1.063915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4327.78171875, 560.21953125, 175.12076172000002), 'rotation':(1.146611, 149.188354, 1.101373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4317.67726562, 566.13414062, 175.35564452999998), 'rotation':(1.172381, 151.007309, 1.125104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4291.29734375, 579.2530468799999, 175.95478516), 'rotation':(1.169376, 156.519821, 1.122349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4285.90476562, 581.55253906, 176.07376953), 'rotation':(1.168816, 157.776321, 1.121817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4269.36914062, 587.8615625, 176.43283203), 'rotation':(1.166405, 160.95079, 1.119609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4263.83054688, 589.7315625, 176.55074219), 'rotation':(1.15478, 162.025085, 1.108908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4241.60109375, 596.07304688, 177.00503906000003), 'rotation':(1.106955, 166.346878, 1.064792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4236.06445312, 597.3712109400001, 177.11408203), 'rotation':(1.105111, 167.710266, 1.063069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4230.54882812, 598.5590625, 177.22234375), 'rotation':(1.100111, 168.660385, 1.05845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4217.3603125, 992.95812988, 176.77472656), 'rotation':(0.306723, -92.704651, 0.303447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4217.0971875, 987.37988281, 176.80490234), 'rotation':(0.299196, -92.704712, 0.296083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4216.83351562, 981.80145264, 176.83435547000002), 'rotation':(0.291369, -92.700104, 0.288429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4215.79148438, 959.48864746, 176.94515625), 'rotation':(0.268515, -92.705017, 0.266001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4215.27195312, 948.33190918, 176.99644531), 'rotation':(0.256822, -92.703003, 0.254533), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4215.04203125, 942.75238281, 177.02115234000001), 'rotation':(0.252123, -92.702515, 0.249915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.7978125, 937.17297363, 177.04572266), 'rotation':(0.241966, -92.705414, 0.239926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.5615625, 931.59338379, 177.06933593999997), 'rotation':(0.231967, -92.702637, 0.230113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.34328125, 926.013125, 177.09273438), 'rotation':(0.231967, -92.702637, 0.230113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4214.0790625, 920.43451172, 177.11535156000002), 'rotation':(0.222002, -92.702728, 0.220286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4213.8159375, 914.8565625, 177.13757812), 'rotation':(0.222002, -92.702728, 0.220286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4212.76171875, 892.54242188, 177.22242188), 'rotation':(0.205022, -92.70282, 0.203565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4212.49804688, 886.96429688, 177.24277343999998), 'rotation':(0.205022, -92.70282, 0.203565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4211.97117188, 875.8075, 177.28201172), 'rotation':(0.189183, -92.702942, 0.187949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4211.17820312, 859.07166016, 177.33748047), 'rotation':(0.179689, -92.702576, 0.178574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4210.65382812, 847.91522461, 177.37292968999998), 'rotation':(0.168665, -92.702606, 0.167669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4210.12695312, 836.75927734, 177.40556641), 'rotation':(0.157613, -92.706238, 0.156751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4209.59960938, 825.59789062, 177.43519531), 'rotation':(0.140927, -92.558533, 0.140234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4209.14992188, 814.40148438, 177.46232422), 'rotation':(0.131263, -91.51947, 0.130667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4209.34914062, 993.44970703, 176.77412109), 'rotation':(-0.314392, 87.295425, -0.317871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.82125, 982.27459717, 176.83384766), 'rotation':(-0.299194, 87.29528, -0.302338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.02929688, 965.51190186, 176.91818359), 'rotation':(-0.283844, 87.295105, -0.286682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.765625, 959.92443848, 176.94488281000002), 'rotation':(-0.276184, 87.299728, -0.27887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4207.50148438, 954.33672852, 176.97089843999998), 'rotation':(-0.268494, 87.294991, -0.271027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.97359375, 943.16107422, 177.02103516), 'rotation':(-0.256836, 87.296997, -0.259155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.70945312, 937.57287598, 177.04564453), 'rotation':(-0.252106, 87.29467, -0.254364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.18210938, 926.39794922, 177.09275391), 'rotation':(-0.241974, 87.297417, -0.244019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4205.65429688, 915.22241211, 177.13765625), 'rotation':(-0.231995, 87.297325, -0.233856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4205.1259375, 904.04638672, 177.18068359), 'rotation':(-0.222015, 87.297256, -0.223724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4204.125, 881.69195312, 177.26304688), 'rotation':(-0.205048, 87.297142, -0.206512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4203.63671875, 870.5144043, 177.30123047), 'rotation':(-0.197266, 87.297104, -0.198639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4203.399375, 864.92517578, 177.31972656000002), 'rotation':(-0.189178, 87.297035, -0.19043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4201.839375, 831.39527344, 177.42134765999998), 'rotation':(-0.157623, 87.297295, -0.158478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4201.12890625, 814.65863281, 177.46228516), 'rotation':(-0.130859, 88.176445, -0.13147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.85109375, 809.09082031, 177.47464843999998), 'rotation':(-0.125244, 88.780983, -0.125793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.44140625, 768.68396484, 177.54798828), 'rotation':(-0.087921, 89.224083, -0.088165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.31835938, 759.5850781199999, 177.56113281), 'rotation':(-0.082733, 89.223831, -0.082977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.16648438, 748.39708984, 177.57724609000002), 'rotation':(-0.082733, 89.223839, -0.082977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4200.01515625, 737.2089257800001, 177.59294922), 'rotation':(-0.07962, 89.221352, -0.079834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.78757812, 720.4271875, 177.61597656), 'rotation':(-0.078369, 89.227287, -0.078583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.63625, 709.23908203, 177.63095703), 'rotation':(-0.076355, 89.223373, -0.076538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4199.484375, 698.05089844, 177.64541015999998), 'rotation':(-0.073578, 89.223381, -0.073761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.33296875, 686.8629687499999, 177.65933593999998), 'rotation':(-0.070831, 89.223373, -0.070984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.10546875, 670.08105469, 177.67929688), 'rotation':(-0.067169, 89.225212, -0.067322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4199.02976562, 664.48695312, 177.68585938), 'rotation':(-0.067169, 89.225212, -0.067322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4198.87796875, 653.2987109400001, 177.69900391), 'rotation':(-0.067383, 89.225525, -0.067535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4198.7265625, 642.11046875, 177.71220703), 'rotation':(-0.067505, 89.221794, -0.067657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4198.65039062, 636.51648438, 177.71878906), 'rotation':(-0.067719, 89.225525, -0.067871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4198.4990625, 625.32832031, 177.73203125), 'rotation':(-0.067749, 89.223503, -0.067902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.27296875, 765.0, 177.55316406000003), 'rotation':(0.082734, -90.776154, 0.082497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.19726562, 759.40851562, 177.56123047), 'rotation':(0.082734, -90.776154, 0.082497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4208.04539062, 748.22576172, 177.57732422), 'rotation':(0.081655, -90.778656, 0.081427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.81835938, 731.45134766, 177.60074218999998), 'rotation':(0.078349, -90.776794, 0.078147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.74265625, 725.85998047, 177.60837891), 'rotation':(0.078349, -90.776794, 0.078147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.66703125, 720.26873047, 177.61603516), 'rotation':(0.077728, -90.776611, 0.077526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.59132812, 714.67712891, 177.62359375), 'rotation':(0.076341, -90.771729, 0.076148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4207.51515625, 709.08587891, 177.63103515999998), 'rotation':(0.074961, -90.776611, 0.074772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.288125, 692.31152344, 177.6525), 'rotation':(0.070815, -90.776642, 0.070646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4207.13671875, 681.1287304699999, 177.66613281000002), 'rotation':(0.067892, -90.776642, 0.06774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.98484375, 669.94605469, 177.67931640999998), 'rotation':(0.067373, -90.778198, 0.067212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.90921875, 664.35457031, 177.68587890999999), 'rotation':(0.067373, -90.778198, 0.067212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.68164062, 647.5799609400001, 177.70560547000002), 'rotation':(0.067728, -90.774475, 0.067568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4206.6059375, 641.98847656, 177.71222656), 'rotation':(0.067728, -90.774475, 0.067568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.45460938, 630.80554688, 177.72542968999997), 'rotation':(0.067742, -90.776489, 0.06758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4206.37890625, 625.21410156, 177.73203125), 'rotation':(0.067742, -90.776489, 0.06758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.7981250000003, 623.1331250000001, 179.60867188), 'rotation':(-0.082184, -89.302368, -0.082397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.52757812, 645.31140625, 179.64119141), 'rotation':(-0.08551, -89.301178, -0.085785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.256875, 667.48949219, 179.67546875), 'rotation':(-0.089539, -89.301147, -0.089844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':6, 'tiley':3, 'location':(4046.1215625, 678.5785546899999, 179.69320312), 'rotation':(-0.092407, -89.301147, -0.092712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.91867188, 695.2122265600001, 179.72021484), 'rotation':(-0.093079, -89.300049, -0.093384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.78320312, 706.30132812, 179.73826172), 'rotation':(-0.093201, -89.300018, -0.093475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4045.71554688, 711.84587891, 179.74730469), 'rotation':(-0.093292, -89.301788, -0.093597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.58054688, 722.93457031, 179.7653125), 'rotation':(-0.092865, -89.299255, -0.09314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':6, 'tiley':3, 'location':(4045.51265625, 728.4790625, 179.77423828), 'rotation':(-0.092865, -89.299255, -0.09314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.3098437500003, 745.11242188, 179.80042969), 'rotation':(-0.089508, -89.299255, -0.089783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.2421875, 750.65705078, 179.80898438), 'rotation':(-0.088409, -89.301483, -0.088684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':6, 'tiley':3, 'location':(4045.1067187500003, 761.74597656, 179.82580077999998), 'rotation':(-0.086334, -89.301514, -0.086578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4045.0390625, 767.29041016, 179.83408203), 'rotation':(-0.085052, -89.299286, -0.085327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':6, 'tiley':3, 'location':(4044.9714062499997, 772.83484375, 179.84228516), 'rotation':(-0.084686, -89.301941, -0.08493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6623.98867188, 4233.895, 172.98279297000002), 'rotation':(-0.582001, -89.477234, -0.593903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6624.06335938, 4211.3271875, 172.75441406000002), 'rotation':(-0.572205, -89.477875, -0.58371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.21617188, 4194.40039062, 172.58564453), 'rotation':(-0.566376, -89.476227, -0.577667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.26695312, 4188.75828125, 172.52982422000002), 'rotation':(-0.566498, -89.476227, -0.577759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.31773438, 4183.11625, 172.47404297), 'rotation':(-0.566498, -89.476227, -0.577759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.36851562, 4177.47414062, 172.41824218999997), 'rotation':(-0.564636, -89.476685, -0.575836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.47058594, 4166.18898438, 172.30708984), 'rotation':(-0.560852, -89.480347, -0.571899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.57265625, 4154.90476562, 172.19695312), 'rotation':(-0.553436, -89.476929, -0.564209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6624.6234375, 4149.26265625, 172.14226562), 'rotation':(-0.553436, -89.476929, -0.564209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6624.8275, 4126.69289062, 171.92503906000002), 'rotation':(-0.546783, -89.481018, -0.557281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.03113281, 4104.1240625, 171.711875), 'rotation':(-0.533752, -89.481232, -0.543762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.18398438, 4087.19679688, 171.55539062), 'rotation':(-0.525696, -89.478088, -0.535431), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.28554688, 4075.91234375, 171.45183594), 'rotation':(-0.525604, -89.478088, -0.535309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.38757812, 4064.6276562499997, 171.34865234), 'rotation':(-0.513092, -89.47644, -0.522339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6625.69324219, 4030.7725, 171.04691406), 'rotation':(-0.503143, -89.477875, -0.512024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.74402344, 4025.13039062, 170.99732422), 'rotation':(-0.499359, -89.477936, -0.508118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6625.84609375, 4013.84570312, 170.89929688), 'rotation':(-0.491669, -89.478058, -0.500153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.896875, 4008.20335938, 170.85082031000002), 'rotation':(-0.487732, -89.478149, -0.496094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.51648438, 4008.17015625, 170.85117188), 'rotation':(0.491671, 90.521935, 0.48329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.41445312, 4019.4518749999997, 170.94847656000002), 'rotation':(0.499348, 90.522057, 0.490711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6617.36367188, 4025.0928125, 170.99765625), 'rotation':(0.503139, 90.517288, 0.494355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.21082031, 4042.0165625, 171.14728516), 'rotation':(0.508876, 90.522476, 0.499887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6617.16003906, 4047.6575000000003, 171.19738281000002), 'rotation':(0.508876, 90.522476, 0.499887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.05796875, 4058.93921875, 171.29796875), 'rotation':(0.521478, 90.520119, 0.512055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6617.0071875, 4064.5803125, 171.34890625), 'rotation':(0.521478, 90.520119, 0.512055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6616.9559375, 4070.22171875, 171.4003125), 'rotation':(0.525597, 90.521912, 0.516028), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.90515625, 4075.8628125, 171.45208984), 'rotation':(0.525665, 90.521896, 0.516108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.803125, 4087.14429688, 171.55560547000002), 'rotation':(0.52725, 90.52372, 0.517619), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.7015625, 4098.42625, 171.65958984), 'rotation':(0.533745, 90.518738, 0.523867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.65027344, 4104.066875, 171.71205078), 'rotation':(0.537133, 90.523949, 0.527121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.34507812, 4137.913125, 172.03357422000002), 'rotation':(0.551599, 90.525703, 0.541055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6616.03894531, 4171.75828125, 172.36259766), 'rotation':(0.564631, 90.523293, 0.553584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6615.93738281, 4183.03953125, 172.47402344), 'rotation':(0.566339, 90.523727, 0.555229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6615.73328125, 4205.60304688, 172.69785156), 'rotation':(0.576161, 90.525711, 0.564659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6615.63171875, 4216.88476562, 172.81107422000002), 'rotation':(0.580115, 90.522285, 0.568453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.791875, 4104.00539062, 163.00803711), 'rotation':(0.48786, 90.433594, 0.479604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.96078125, 4081.453125, 162.81922852), 'rotation':(0.47282, 90.431145, 0.465076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.08726562, 4064.53976562, 162.6825), 'rotation':(0.459986, 90.430939, 0.452646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.17171875, 4053.26390625, 162.593125), 'rotation':(0.453538, 90.433311, 0.446405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.21375, 4047.6262500000003, 162.54847656), 'rotation':(0.453429, 90.429306, 0.446292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.34023438, 4030.7121875000003, 162.41723633), 'rotation':(0.436579, 90.430443, 0.429971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.3821875, 4025.07445312, 162.37466797), 'rotation':(0.436579, 90.430443, 0.429971), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.46671875, 4013.79859375, 162.29055664), 'rotation':(0.426286, 90.431618, 0.419976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.50867188, 4008.16085938, 162.24861328), 'rotation':(0.426286, 90.431618, 0.419976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6095.88953125, 4008.18164062, 162.24829102), 'rotation':(-0.422302, -89.567963, -0.428558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.84703125, 4013.8215625000003, 162.29025391), 'rotation':(-0.42627, -89.568359, -0.432648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.80507812, 4019.46140625, 162.33222656), 'rotation':(-0.4263, -89.568359, -0.432678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.67859375, 4036.38257812, 162.46017578000001), 'rotation':(-0.436584, -89.56955, -0.443268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.63609375, 4042.02273438, 162.50395508), 'rotation':(-0.443207, -89.569427, -0.450104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.59414062, 4047.663125, 162.54828125), 'rotation':(-0.450195, -89.569336, -0.457306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.55210938, 4053.30296875, 162.59292969), 'rotation':(-0.45343, -89.566681, -0.460632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6095.51015625, 4058.943125, 162.63757812), 'rotation':(-0.453552, -89.56665, -0.460785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.425625, 4070.22335938, 162.72748047), 'rotation':(-0.460022, -89.569031, -0.467438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.25671875, 4092.78367188, 162.91267578), 'rotation':(-0.477051, -89.568756, -0.485046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.2146875, 4098.42429688, 162.96012695), 'rotation':(-0.481476, -89.568665, -0.489624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6095.13023438, 4109.7040625, 163.05603516), 'rotation':(-0.487854, -89.566406, -0.496216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6012.98765625, 5224.81396484, 166.34632812), 'rotation':(1.014877, 0.230017, 0.979399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6033.81625, 5224.89013672, 166.71515625), 'rotation':(1.011401, 0.230601, 0.976142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6059.84898438, 5225.11328125, 167.17447266), 'rotation':(1.009283, 0.22726, 0.974178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6002.58289062, 5216.39501953, 166.16136719), 'rotation':(-1.016693, -179.775345, -1.053253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6012.99984375, 5216.43310547, 166.34599609), 'rotation':(-1.015045, -179.769958, -1.051514), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6018.2103125, 5216.45214844, 166.43832031000002), 'rotation':(-1.014893, -179.772995, -1.051331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6023.41882812, 5216.47119141, 166.53060547), 'rotation':(-1.014893, -179.772995, -1.051331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6033.83726562, 5216.50927734, 166.715), 'rotation':(-1.012787, -179.773132, -1.049072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6059.88125, 5216.47705078, 167.17449219), 'rotation':(-1.009369, -179.77272, -1.045441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6126.144375, 5216.84765625, 168.34058593999998), 'rotation':(-1.006989, -179.771362, -1.042877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6131.81921875, 5216.86816406, 168.44037109), 'rotation':(-1.006989, -179.771362, -1.042877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6143.16734375, 5216.91015625, 168.63996093999998), 'rotation':(-1.007477, -179.771423, -1.043365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6160.19078125, 5216.97216797, 168.93949218999998), 'rotation':(-1.00769, -179.771942, -1.04361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6182.88859375, 5217.05566406, 169.33888672), 'rotation':(-1.008392, -179.775314, -1.044373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6194.23671875, 5217.09716797, 169.53896484), 'rotation':(-1.01001, -179.770935, -1.046112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6216.93492188, 5217.18017578, 169.93955078), 'rotation':(-1.010651, -179.77327, -1.046814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6228.28359375, 5217.21923828, 170.13988281000002), 'rotation':(-1.010834, -179.773254, -1.046997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6239.6321875, 5217.27929688, 170.34050781000002), 'rotation':(-1.011719, -179.772202, -1.047913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6245.30601562, 5217.31494141, 170.44095703), 'rotation':(-1.013733, -179.772125, -1.05011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6262.32945312, 5217.37939453, 170.74255859000002), 'rotation':(-1.014618, -179.77182, -1.051056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6273.678125, 5217.42089844, 170.94361328), 'rotation':(-1.01474, -179.77182, -1.051208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6285.0271875, 5217.46289062, 171.14488281), 'rotation':(-1.016388, -179.772797, -1.052979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6097.74203125, 5225.12402344, 167.84175781000002), 'rotation':(1.006818, 0.22537, 0.971892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6103.416875, 5225.14501953, 167.94154297), 'rotation':(1.006968, 0.228632, 0.972038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6126.11414062, 5225.22851562, 168.34058593999998), 'rotation':(1.007091, 0.228553, 0.97214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6131.78890625, 5225.24902344, 168.44037109), 'rotation':(1.007091, 0.228553, 0.97214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6154.48625, 5225.33251953, 168.83966797000002), 'rotation':(1.007678, 0.228063, 0.972687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6165.834375, 5225.37402344, 169.03931641), 'rotation':(1.007576, 0.224968, 0.972593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6171.50914062, 5225.39453125, 169.13916016), 'rotation':(1.007576, 0.224968, 0.972593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6177.18398438, 5225.41552734, 169.23900390999998), 'rotation':(1.008395, 0.229, 0.97335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6182.8578125, 5225.43603516, 169.33888672), 'rotation':(1.010007, 0.229057, 0.974853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6188.53257812, 5225.45703125, 169.43888672), 'rotation':(1.010007, 0.229057, 0.974853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6211.2303125, 5225.54003906, 169.83941406000002), 'rotation':(1.010725, 0.230051, 0.975518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6222.57851562, 5225.58203125, 170.0396875), 'rotation':(1.011701, 0.227793, 0.976435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6233.92710938, 5225.63134766, 170.24013672), 'rotation':(1.013723, 0.227865, 0.978324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6262.29921875, 5225.69433594, 170.74255859000002), 'rotation':(1.014625, 0.228165, 0.979148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6267.97398438, 5225.71533203, 170.84308593999998), 'rotation':(1.014748, 0.22817, 0.979257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6284.99648438, 5225.77734375, 171.14488281), 'rotation':(1.017322, 0.227216, 0.981651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6290.67078125, 5225.79833984, 171.24570312), 'rotation':(1.01849, 0.227257, 0.982741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6339.82265625, 5226.01123047, 172.1203125), 'rotation':(1.020369, 0.226735, 0.984499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6345.34460938, 5226.03125, 172.21869141), 'rotation':(1.020369, 0.226735, 0.984499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6350.86757812, 5226.05175781, 172.31708984), 'rotation':(1.020533, 0.230013, 0.984644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6367.4359375, 5226.11230469, 172.61230468999997), 'rotation':(1.020533, 0.230013, 0.984644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6372.95789062, 5226.1328125, 172.71070312), 'rotation':(1.020533, 0.230013, 0.984644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6378.47984375, 5226.15283203, 172.80910156000002), 'rotation':(1.02043, 0.227561, 0.984543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6400.57019531, 5226.23388672, 173.20267578), 'rotation':(1.020369, 0.225548, 0.984485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6411.61609375, 5226.27441406, 173.39949219), 'rotation':(1.020369, 0.230262, 0.984483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6417.13804688, 5226.29492188, 173.49785156000002), 'rotation':(1.019761, 0.229084, 0.983934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6422.66003906, 5226.31494141, 173.59615234), 'rotation':(1.018231, 0.226046, 0.98251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6428.18296875, 5226.33496094, 173.69439452999998), 'rotation':(1.018231, 0.226046, 0.98251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6433.7059375, 5226.35546875, 173.79257812), 'rotation':(1.016749, 0.228965, 0.981127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6439.22789062, 5226.37548828, 173.890625), 'rotation':(1.01526, 0.228912, 0.979747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6444.75039062, 5226.39550781, 173.98865234000002), 'rotation':(1.01526, 0.228912, 0.979747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6466.84023438, 5226.44580078, 174.38007812), 'rotation':(1.014584, 0.227062, 0.979111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6472.36316406, 5226.46386719, 174.47792969), 'rotation':(1.014659, 0.227084, 0.979179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6328.8084375, 5217.58984375, 171.92365234000002), 'rotation':(-1.019104, -179.76976, -1.055847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6345.37632812, 5217.65087891, 172.21871094), 'rotation':(-1.02002, -179.772354, -1.056854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6356.42175781, 5217.69140625, 172.41550781), 'rotation':(-1.020538, -179.773239, -1.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6367.46667969, 5217.73144531, 172.61230468999997), 'rotation':(-1.020416, -179.773239, -1.057281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6378.51109375, 5217.77197266, 172.80910156000002), 'rotation':(-1.020538, -179.769989, -1.057404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6389.55652344, 5217.81298828, 173.00589843999998), 'rotation':(-1.020294, -179.772446, -1.057159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6406.124375, 5217.87353516, 173.30109375), 'rotation':(-1.020447, -179.774429, -1.057312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6417.16929688, 5217.9140625, 173.49785156000002), 'rotation':(-1.020355, -179.774445, -1.05722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6433.73671875, 5217.97460938, 173.79257812), 'rotation':(-1.01825, -179.770981, -1.054932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6439.25867188, 5217.99462891, 173.89064453), 'rotation':(-1.016754, -179.774002, -1.053345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6444.78164062, 5218.01464844, 173.98865234000002), 'rotation':(-1.016754, -179.774002, -1.053345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6455.8265625, 5218.046875, 174.18439453), 'rotation':(-1.015259, -179.771088, -1.051727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6461.34949219, 5218.09228516, 174.28226562), 'rotation':(-1.014648, -179.772903, -1.051117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6472.39492188, 5218.14941406, 174.47792969), 'rotation':(-1.014587, -179.772934, -1.051025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.33335938, 5218.25537109, 175.14804688), 'rotation':(-1.00946, -179.76973, -1.045502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6521.61757812, 5218.29638672, 175.34658202999998), 'rotation':(-1.007507, -179.773972, -1.043427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6544.18398438, 5218.37939453, 175.74167968999998), 'rotation':(-0.999695, -179.774246, -1.035065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6555.4671875, 5218.42041016, 175.93828125), 'rotation':(-0.997742, -179.770142, -1.032959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6561.10925781, 5218.44140625, 176.03636719), 'rotation':(-0.995789, -179.774384, -1.030884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.959375, 5218.56542969, 176.62240234), 'rotation':(-0.985535, -179.773895, -1.019867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6611.88515625, 5218.62695312, 176.91363281000002), 'rotation':(-0.985535, -179.773895, -1.019867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6617.52671875, 5218.64355469, 177.010625), 'rotation':(-0.984436, -179.774368, -1.018738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6628.80992188, 5218.70800781, 177.20390625), 'rotation':(-0.980316, -179.769012, -1.014313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6640.09414062, 5218.76367188, 177.39628906000002), 'rotation':(-0.976227, -179.774658, -1.009918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6651.37632812, 5218.80517578, 177.58775391), 'rotation':(-0.970062, -179.769363, -1.003326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6662.66101562, 5218.84619141, 177.77871094), 'rotation':(-0.968842, -179.778214, -1.002014), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6679.58679688, 5218.90820312, 178.06404297), 'rotation':(-0.962463, -179.775208, -0.995209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6690.86951172, 5218.94970703, 178.25300781), 'rotation':(-0.958038, -179.772202, -0.990509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6702.15417969, 5218.99072266, 178.44089843999998), 'rotation':(-0.953766, -179.775482, -0.985931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6713.43738281, 5219.03222656, 178.62837890999998), 'rotation':(-0.951599, -179.773376, -0.983612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6730.36365234, 5219.09423828, 178.90921875), 'rotation':(-0.948944, -179.773819, -0.980774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6736.00525391, 5219.11474609, 179.00232422000002), 'rotation':(-0.948944, -179.773819, -0.980774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6747.28992188, 5218.98632812, 179.18792968999998), 'rotation':(-0.940674, -179.774475, -0.971954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.303125, 5226.63574219, 175.14804688), 'rotation':(1.007501, 0.230186, 0.972523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6515.94519531, 5226.65625, 175.24738281), 'rotation':(1.007501, 0.230186, 0.972523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6527.22742188, 5226.69775391, 175.44558593999997), 'rotation':(1.003607, 0.225884, 0.968891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6538.51109375, 5226.73925781, 175.64314453), 'rotation':(0.999701, 0.225747, 0.965258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6544.15320312, 5226.75976562, 175.74166015999998), 'rotation':(0.997747, 0.229844, 0.963443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6555.43640625, 5226.80126953, 175.93828125), 'rotation':(0.995801, 0.225614, 0.961618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6572.36171875, 5226.86328125, 176.23234375), 'rotation':(0.994824, 0.225044, 0.960708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6578.00429688, 5226.88378906, 176.33035156000003), 'rotation':(0.990131, 0.22881, 0.956345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6583.64492188, 5226.90429688, 176.42796875), 'rotation':(0.985507, 0.226097, 0.952029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6589.28648438, 5226.92480469, 176.52533203), 'rotation':(0.985507, 0.226097, 0.952029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.928125, 5226.94580078, 176.62240234), 'rotation':(0.985507, 0.226097, 0.952029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6611.85390625, 5227.0078125, 176.91363281000002), 'rotation':(0.984442, 0.225625, 0.951035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6623.13757812, 5227.05810547, 177.10738281000002), 'rotation':(0.980323, 0.225484, 0.947199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6634.42125, 5227.05761719, 177.30019531000002), 'rotation':(0.976212, 0.225341, 0.943363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6640.06335938, 5227.078125, 177.39630859000002), 'rotation':(0.974156, 0.225273, 0.941441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6656.98867188, 5227.14013672, 177.68324219), 'rotation':(0.968828, 0.226553, 0.936475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6662.63074219, 5227.16064453, 177.77871094), 'rotation':(0.966875, 0.228101, 0.934652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6673.91443359, 5227.20214844, 177.96923827999998), 'rotation':(0.962435, 0.224792, 0.930504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6679.55603516, 5227.22314453, 178.06404297), 'rotation':(0.95805, 0.227797, 0.926393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6685.19763672, 5227.24365234, 178.15865234), 'rotation':(0.95805, 0.227797, 0.926393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6707.76550781, 5227.32617188, 178.53462890999998), 'rotation':(0.951596, 0.226618, 0.920364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6730.33386719, 5227.40917969, 178.90921875), 'rotation':(0.943324, 0.225976, 0.912631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6741.61707031, 5227.45068359, 179.09525391), 'rotation':(0.94066, 0.225518, 0.910145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(7006.03748047, 5219.97851562, 183.22103515999999), 'rotation':(-0.829865, -179.778198, -0.854187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6994.71912109, 5220.02978516, 183.05675781000002), 'rotation':(-0.836334, -179.778214, -0.861023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6989.05798828, 5220.00927734, 182.97398438), 'rotation':(-0.840454, -179.778091, -0.865387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6977.73523438, 5219.96777344, 182.80707031000003), 'rotation':(-0.85318, -179.777725, -0.878906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6972.07507812, 5219.94677734, 182.72292968999997), 'rotation':(-0.857574, -179.777557, -0.883545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6955.09167969, 5219.88476562, 182.46789062), 'rotation':(-0.863647, -179.774811, -0.889984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6949.43201172, 5219.86376953, 182.38251953), 'rotation':(-0.866364, -179.777786, -0.892883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6938.10974609, 5219.82226562, 182.21111327999998), 'rotation':(-0.871063, -179.777649, -0.897858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6932.448125, 5219.80175781, 182.125), 'rotation':(-0.876129, -179.777496, -0.903229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6926.78796875, 5219.78076172, 182.03853515999998), 'rotation':(-0.876129, -179.777496, -0.903229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6921.12585938, 5219.76025391, 181.95191406), 'rotation':(-0.880951, -179.774353, -0.908386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6898.48279297, 5219.67724609, 181.60306641), 'rotation':(-0.883423, -179.77684, -0.911011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6875.83923828, 5219.59423828, 181.25136719), 'rotation':(-0.902863, -179.772003, -0.931671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6870.17859375, 5219.57373047, 181.16220703), 'rotation':(-0.905701, -179.777161, -0.934662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6864.51892578, 5219.55273438, 181.07275391), 'rotation':(-0.905579, -179.777161, -0.93454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6847.53552734, 5219.49023438, 180.80423828), 'rotation':(-0.905579, -179.777161, -0.93454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6836.21326172, 5219.44873047, 180.62517577999998), 'rotation':(-0.9086, -179.775253, -0.937744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6830.55310547, 5219.42822266, 180.53525391), 'rotation':(-0.914337, -179.77507, -0.943848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6824.89197266, 5219.40722656, 180.44482422000002), 'rotation':(-0.917328, -179.774597, -0.947052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6813.57019531, 5219.36572266, 180.26349609000002), 'rotation':(-0.917328, -179.774597, -0.947052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6802.25183594, 5219.32226562, 180.08220702999998), 'rotation':(-0.918732, -179.774551, -0.948578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6790.92761719, 5219.15332031, 179.90017577999998), 'rotation':(-0.924469, -179.774353, -0.954681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6796.51794922, 5227.75830078, 179.99068359), 'rotation':(0.918729, 0.220055, 0.889611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6802.17859375, 5227.70800781, 180.08152343999998), 'rotation':(0.917308, 0.225399, 0.888288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6813.49890625, 5227.74658203, 180.26285156000003), 'rotation':(0.91739, 0.225422, 0.888352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6824.82068359, 5227.78808594, 180.44416016), 'rotation':(0.914323, 0.224927, 0.885476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6836.14148438, 5227.82958984, 180.62451172000002), 'rotation':(0.905587, 0.222835, 0.877289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6841.80261719, 5227.85058594, 180.7140625), 'rotation':(0.90569, 0.222842, 0.877384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6847.46375, 5227.87109375, 180.80357422), 'rotation':(0.90569, 0.222842, 0.877384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6864.44714844, 5227.93359375, 181.07210938), 'rotation':(0.90569, 0.222842, 0.877384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6870.10730469, 5227.95410156, 181.1615625), 'rotation':(0.902848, 0.223349, 0.874735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6875.76892578, 5227.97509766, 181.25074218999998), 'rotation':(0.897343, 0.227829, 0.869549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6887.09070312, 5228.01611328, 181.42751952999998), 'rotation':(0.886101, 0.222812, 0.858999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6892.75085938, 5228.03710938, 181.51511718999998), 'rotation':(0.88343, 0.22316, 0.856495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6904.073125, 5228.07861328, 181.68976562), 'rotation':(0.88343, 0.22316, 0.856495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6909.73425781, 5228.09960938, 181.77708984), 'rotation':(0.880958, 0.222652, 0.854175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6921.05701172, 5228.14111328, 181.95132812), 'rotation':(0.876115, 0.225493, 0.849612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6949.3621875, 5228.24560547, 182.38193359000002), 'rotation':(0.86365, 0.225187, 0.837895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6955.02234375, 5228.26904297, 182.46732422000002), 'rotation':(0.863814, 0.219889, 0.838047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6960.68396484, 5228.29394531, 182.55265625), 'rotation':(0.86171, 0.222548, 0.836083), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6966.34460938, 5228.29345703, 182.63773438), 'rotation':(0.857496, 0.222404, 0.832111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.23085938, 4171.27539062, 163.59333984), 'rotation':(0.519409, 90.608437, 0.510064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.17078125, 4176.95851562, 163.64426758), 'rotation':(0.519409, 90.608437, 0.510064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.050625, 4188.32570312, 163.74791016), 'rotation':(0.525535, 90.608688, 0.515955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.990625, 4194.00875, 163.80004883), 'rotation':(0.525535, 90.608688, 0.515955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.93101562, 4199.691875, 163.8521875), 'rotation':(0.526293, 90.611145, 0.516703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.8109375, 4211.058125, 163.95671875), 'rotation':(0.529394, 90.611282, 0.519676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6085.69125, 4222.42429688, 164.06183593999998), 'rotation':(0.532768, 90.606194, 0.522927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.57164062, 4233.79054688, 164.16763672000002), 'rotation':(0.535985, 90.606255, 0.526018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.4515625, 4245.1571875, 164.27410156000002), 'rotation':(0.538308, 90.60672, 0.528266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.39195312, 4250.8403125, 164.3275), 'rotation':(0.538192, 90.609932, 0.528165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.271875, 4262.2065625, 164.43431640999998), 'rotation':(0.538868, 90.607475, 0.528798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6085.15171875, 4273.57226562, 164.54128906000003), 'rotation':(0.540698, 90.607506, 0.530572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6085.03210938, 4284.9384375, 164.64869141), 'rotation':(0.54218, 90.611885, 0.532004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.97203125, 4290.6215625, 164.7025), 'rotation':(0.542112, 90.608299, 0.531934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6084.9125, 4296.3046875, 164.75628906000003), 'rotation':(0.542201, 90.608253, 0.532003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6084.85242188, 4301.9878125, 164.81007812), 'rotation':(0.542201, 90.608253, 0.532003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.79234375, 4307.6709375, 164.86386718999998), 'rotation':(0.542201, 90.608253, 0.532003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6084.67273438, 4319.03664062, 164.97140625), 'rotation':(0.541176, 90.60833, 0.531037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.553125, 4330.4028125, 165.07884765999998), 'rotation':(0.540917, 90.607788, 0.530786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.49304688, 4336.0859375, 165.1325), 'rotation':(0.540958, 90.611351, 0.53082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.43296875, 4341.7690625, 165.18617188), 'rotation':(0.540958, 90.611351, 0.53082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.97984375, 4148.63234375, 163.39381836), 'rotation':(-0.501099, -89.394409, -0.509918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.90171875, 4154.31734375, 163.44354492), 'rotation':(-0.50116, -89.389954, -0.509979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.78359375, 4159.99953125, 163.49325195), 'rotation':(-0.50116, -89.389954, -0.509979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.550625, 4177.046875, 163.64426758), 'rotation':(-0.507202, -89.388641, -0.516235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.43101562, 4188.4140625, 163.74792969), 'rotation':(-0.525543, -89.391296, -0.535248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6094.25132812, 4205.46390625, 163.904375), 'rotation':(-0.526367, -89.393921, -0.536102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.19125, 4211.14648438, 163.95671875), 'rotation':(-0.527893, -89.388794, -0.537689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.07164062, 4222.51265625, 164.06183593999998), 'rotation':(-0.531158, -89.388672, -0.541077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6094.0115625, 4228.19578125, 164.11464844), 'rotation':(-0.532776, -89.393799, -0.542755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.9515625, 4233.87890625, 164.16765625), 'rotation':(-0.53421, -89.388611, -0.54425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.89148438, 4239.56203125, 164.22078125), 'rotation':(-0.53598, -89.38858, -0.546082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.6521875, 4262.29492188, 164.43431640999998), 'rotation':(-0.538208, -89.390045, -0.548401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6093.4125, 4285.026875, 164.64869141), 'rotation':(-0.541687, -89.392456, -0.552032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.35242188, 4290.71, 164.7025), 'rotation':(-0.542206, -89.391724, -0.552521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.2328125, 4302.07617188, 164.81007812), 'rotation':(-0.542114, -89.391724, -0.55246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.053125, 4319.12546875, 164.97140625), 'rotation':(-0.541901, -89.391693, -0.552216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.99304688, 4324.808125, 165.02515625), 'rotation':(-0.541901, -89.391693, -0.552216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.033125, 4379.7075, 165.5415625), 'rotation':(0.528643, 90.61174, 0.518962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.975, 4385.24023438, 165.59271484), 'rotation':(0.528643, 90.61174, 0.518962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.7996875, 4401.83789062, 165.74523438), 'rotation':(0.525201, 90.608971, 0.515636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.7415625, 4407.370625, 165.79597656), 'rotation':(0.525201, 90.608971, 0.515636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.68296875, 4412.90332031, 165.84669922), 'rotation':(0.521068, 90.60952, 0.51165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.50820312, 4429.50046875, 165.99664062), 'rotation':(0.508603, 90.612015, 0.499626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.44960938, 4435.03273438, 166.04582031), 'rotation':(0.508719, 90.608086, 0.499753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.39148438, 4440.56542969, 166.09494141), 'rotation':(0.508719, 90.608086, 0.499753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.15953125, 4456.85644531, 166.23865234000002), 'rotation':(0.497149, 90.606606, 0.48858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.32945312, 4445.79148438, 166.14128906000002), 'rotation':(0.506288, 90.606758, 0.497412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.030625, 4465.24609375, 166.31146484), 'rotation':(0.492532, 90.606476, 0.484128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6082.92171875, 4472.79003906, 166.37621094), 'rotation':(0.488003, 90.610634, 0.479742), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.82703125, 4481.79054688, 166.45255859), 'rotation':(0.478858, 90.610481, 0.470901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.73234375, 4490.79148438, 166.52800781000002), 'rotation':(0.474131, 90.606171, 0.466321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6092.29625, 4390.86230469, 165.64371093999998), 'rotation':(-0.528656, -89.392334, -0.538452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.238125, 4396.395, 165.69453125), 'rotation':(-0.526367, -89.392395, -0.536102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.12148438, 4407.4609375, 165.79599609000002), 'rotation':(-0.525177, -89.391052, -0.534851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6092.00476562, 4418.52492188, 165.89708984), 'rotation':(-0.521088, -89.390472, -0.530609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.94664062, 4424.058125, 165.94714843999998), 'rotation':(-0.521088, -89.390472, -0.530609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.83, 4435.12257812, 166.04583984), 'rotation':(-0.508606, -89.391907, -0.5177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.77140625, 4440.65527344, 166.09496094), 'rotation':(-0.508606, -89.391907, -0.5177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.64882812, 4458.8984375, 166.25566406000002), 'rotation':(-0.501801, -89.393372, -0.510651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6091.5853125, 4469.96335938, 166.35125), 'rotation':(-0.492554, -89.389343, -0.501068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6091.47789062, 4480.78125, 166.44328125), 'rotation':(-0.488007, -89.393555, -0.496368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.3553125, 4528.25878906, 166.83175781000003), 'rotation':(0.440868, 90.607208, 0.434129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.2875, 4545.24902344, 166.96160156000002), 'rotation':(0.435787, 90.605026, 0.429191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.16835938, 4556.57664062, 167.04720702999998), 'rotation':(0.418308, 90.608009, 0.412234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.9290625, 4579.23289062, 167.21173828), 'rotation':(0.394997, 90.607697, 0.389573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.80992188, 4590.56101562, 167.29), 'rotation':(0.389191, 90.607719, 0.38393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.75039062, 4596.22558594, 167.32845702999998), 'rotation':(0.38566, 90.605774, 0.380507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.57117188, 4613.21777344, 167.44142578), 'rotation':(0.365046, 90.605499, 0.360419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.331875, 4635.87351562, 167.58226562), 'rotation':(0.337534, 90.60524, 0.333579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.97351562, 4669.85789062, 167.77525391), 'rotation':(0.300911, 90.605125, 0.297763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.79484375, 4686.85107422, 167.86181641), 'rotation':(0.278856, 90.604897, 0.276158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.67515625, 4698.17919922, 167.91644531000003), 'rotation':(0.275127, 90.604355, 0.27249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.61515625, 4703.84277344, 167.94326172), 'rotation':(0.267491, 90.605583, 0.265011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.4959375, 4715.17138672, 167.99472656), 'rotation':(0.236741, 90.605309, 0.234786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.376875, 4726.50048828, 168.04251953), 'rotation':(0.221271, 90.605217, 0.219563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.25765625, 4737.828125, 168.08650391), 'rotation':(0.21358, 90.601303, 0.212003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6080.19765625, 4743.49267578, 168.10759765999998), 'rotation':(0.213764, 90.606247, 0.212178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.92515625, 4529.57128906, 166.84117188), 'rotation':(-0.451141, -89.392639, -0.458313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.72742188, 4539.671875, 166.91851562), 'rotation':(-0.435669, -89.39151, -0.442352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.60828125, 4551.00097656, 167.00466797), 'rotation':(-0.435791, -89.391541, -0.442444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6090.4290625, 4567.99265625, 167.13080078), 'rotation':(-0.418304, -89.391998, -0.424438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6090.30945312, 4579.32078125, 167.21173828), 'rotation':(-0.406555, -89.392151, -0.412384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6090.13023438, 4596.31296875, 167.32845702999998), 'rotation':(-0.389191, -89.395538, -0.394501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.95109375, 4613.30566406, 167.44142578), 'rotation':(-0.371857, -89.394348, -0.376709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.831875, 4624.6328125, 167.51326172), 'rotation':(-0.358124, -89.394562, -0.36264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.77234375, 4630.296875, 167.54810547), 'rotation':(-0.351379, -89.394653, -0.355682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.65273438, 4641.62546875, 167.61568359), 'rotation':(-0.337524, -89.389587, -0.341553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.59265625, 4647.28953125, 167.64875), 'rotation':(-0.334045, -89.397095, -0.337952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6089.533125, 4652.953125, 167.68148438), 'rotation':(-0.3302, -89.394531, -0.334045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.47351562, 4658.61765625, 167.71355469), 'rotation':(-0.32312, -89.389313, -0.326752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6089.41390625, 4664.28222656, 167.74480469), 'rotation':(-0.315582, -89.394714, -0.319061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6089.35390625, 4669.9453125, 167.77525391), 'rotation':(-0.308289, -89.394836, -0.311615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.29429688, 4675.60986328, 167.80488281), 'rotation':(-0.300903, -89.394897, -0.304077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.23421875, 4681.2734375, 167.83375), 'rotation':(-0.293518, -89.394958, -0.296509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6089.11515625, 4692.60205078, 167.88923828), 'rotation':(-0.27887, -89.395081, -0.281586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6088.9359375, 4709.59570312, 167.9696875), 'rotation':(-0.267487, -89.397522, -0.269989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6088.87632812, 4715.25927734, 167.99472656), 'rotation':(-0.252136, -89.394531, -0.254364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6088.69664062, 4732.25195312, 168.06476562), 'rotation':(-0.236755, -89.394684, -0.238708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6088.57796875, 4743.58056641, 168.10759765999998), 'rotation':(-0.213593, -89.393799, -0.215179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.00820312, 5046.02929688, 168.19578125), 'rotation':(-0.158203, 90.606834, -0.159088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.18640625, 5029.13720703, 168.2415625), 'rotation':(-0.152863, 90.60466, -0.153656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.24546875, 5023.50634766, 168.25550781), 'rotation':(-0.141815, 90.604614, -0.142517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.36460938, 5012.24462891, 168.28195312), 'rotation':(-0.130951, 90.604553, -0.131561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.48328125, 5000.98339844, 168.30582031000003), 'rotation':(-0.120087, 90.604485, -0.120605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.541875, 4995.35302734, 168.31693359000002), 'rotation':(-0.114563, 90.604462, -0.115051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.60140625, 4989.72265625, 168.32751953), 'rotation':(-0.11026, 90.60331, -0.110687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.72007812, 4978.46044922, 168.34632812), 'rotation':(-0.093353, 90.607986, -0.093658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.89828125, 4961.56933594, 168.36861327999998), 'rotation':(-0.067963, 90.60321, -0.068146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.01695312, 4950.30712891, 168.37945312), 'rotation':(-0.050903, 90.607887, -0.050995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6078.19515625, 4933.41455078, 168.39326172), 'rotation':(-0.046844, 90.603226, -0.046906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.314375, 4922.15478516, 168.40109375), 'rotation':(-0.046722, 90.603226, -0.046783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.3734375, 4916.52539062, 168.40189453), 'rotation':(-0.017975, 90.60463, -0.017975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.49203125, 4905.26318359, 168.39976562), 'rotation':(0.010867, 90.609085, 0.010875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.55164062, 4899.63183594, 168.39867188), 'rotation':(0.011044, 90.603653, 0.011043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.78890625, 4877.10888672, 168.39435547000002), 'rotation':(0.010874, 90.603653, 0.010873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.9671875, 4860.21630859, 168.38464843999998), 'rotation':(0.039239, 90.604042, 0.039196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.08578125, 4848.95507812, 168.37140625), 'rotation':(0.076881, 90.604126, 0.076681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.20445312, 4837.69482422, 168.35478516), 'rotation':(0.086457, 90.605026, 0.086203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.2640625, 4832.06445312, 168.34623047000002), 'rotation':(0.086334, 90.604988, 0.086081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.323125, 4826.43359375, 168.33701172000002), 'rotation':(0.093792, 90.601875, 0.093483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.5609375, 4803.91064453, 168.28992188), 'rotation':(0.138591, 90.60202, 0.137927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6079.67953125, 4792.64990234, 168.26154297000002), 'rotation':(0.146016, 90.603149, 0.145274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6079.68984375, 4781.39111328, 168.23222656000002), 'rotation':(0.15217, 90.603111, 0.151361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.94078125, 4803.99951172, 168.28992188), 'rotation':(-0.146027, -89.39682, -0.146759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.70351562, 4826.52246094, 168.33701172000002), 'rotation':(-0.108765, -89.398102, -0.109161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.58484375, 4837.78369141, 168.35478516), 'rotation':(-0.086334, -89.394989, -0.086609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.5253125, 4843.41455078, 168.36328125), 'rotation':(-0.086456, -89.398926, -0.086731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6087.2284375, 4871.56640625, 168.39234375), 'rotation':(-0.039246, -89.392273, -0.039307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6087.050625, 4888.45800781, 168.39652343999998), 'rotation':(-0.011047, -89.396362, -0.011047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.99109375, 4894.08886719, 168.39757812), 'rotation':(-0.010895, -89.396393, -0.010864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.87242188, 4905.35107422, 168.39976562), 'rotation':(-0.011047, -89.396362, -0.011047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.75328125, 4916.61328125, 168.40189453), 'rotation':(-0.010895, -89.396332, -0.010895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.69421875, 4922.24316406, 168.40109375), 'rotation':(0.01795, -89.395386, 0.01795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.57554688, 4933.50292969, 168.39326172), 'rotation':(0.046705, -89.396759, 0.046633), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.456875, 4944.76513672, 168.3840625), 'rotation':(0.046835, -89.392334, 0.046775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.21960938, 4967.2890625, 168.36199219), 'rotation':(0.06796, -89.396851, 0.067799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.16, 4972.91894531, 168.35455077999998), 'rotation':(0.076423, -89.392059, 0.076217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6086.10046875, 4978.54882812, 168.34632812), 'rotation':(0.084879, -89.39679, 0.08463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.92226562, 4995.44091797, 168.31693359000002), 'rotation':(0.110253, -89.396729, 0.109829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.863125, 5001.07177734, 168.30582031000003), 'rotation':(0.114583, -89.395538, 0.114124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.80359375, 5006.70214844, 168.29404297000002), 'rotation':(0.120095, -89.395508, 0.119589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.68492188, 5017.96386719, 168.26908203), 'rotation':(0.130955, -89.395447, 0.130356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.56625, 5029.22509766, 168.2415625), 'rotation':(0.141802, -89.395386, 0.141109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.4471875, 5040.48632812, 168.21134766), 'rotation':(0.152866, -89.395325, 0.152045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6085.38804688, 5046.1171875, 168.19578125), 'rotation':(0.158214, -89.393158, 0.157345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.44125, 5194.68115234, 167.63638672000002), 'rotation':(-0.256958, 90.605675, -0.259277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.49984375, 5189.1484375, 167.66113281000003), 'rotation':(-0.256134, 90.605164, -0.258453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6075.79140625, 5161.48291016, 167.78134766), 'rotation':(-0.24353, 90.607712, -0.245605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.84953125, 5155.95019531, 167.80451172000002), 'rotation':(-0.240631, 90.602234, -0.242645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6075.96617188, 5144.88427734, 167.85003906000003), 'rotation':(-0.235107, 90.60218, -0.23703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.02382812, 5139.35107422, 167.87261718999997), 'rotation':(-0.233765, 90.609047, -0.235687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.54875, 5089.55371094, 168.05996094), 'rotation':(-0.202179, 90.605797, -0.203613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.8709375, 5095.17382812, 168.04042969), 'rotation':(0.202174, -89.398438, 0.200752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.57898438, 5122.83886719, 167.93871094), 'rotation':(0.214092, -89.397247, 0.212492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.4628125, 5133.90478516, 167.89498047), 'rotation':(0.229884, -89.394104, 0.228038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.40421875, 5139.4375, 167.87263672), 'rotation':(0.229884, -89.394104, 0.228038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6084.345625, 5144.97119141, 167.85005859), 'rotation':(0.233756, -89.396179, 0.231866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.93789062, 5183.70166016, 167.68576172000002), 'rotation':(0.251829, -89.392151, 0.249618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.9828125, 5238.13818359, 167.43830078), 'rotation':(-0.266113, 90.602806, -0.268616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.92320312, 5243.77490234, 167.41210938), 'rotation':(-0.266632, 90.605278, -0.269104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.86414062, 5249.41162109, 167.38585938), 'rotation':(-0.266602, 90.605225, -0.269104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.745, 5260.68457031, 167.33339844), 'rotation':(-0.266174, 90.605484, -0.268646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6074.32945312, 5300.14111328, 167.15101562), 'rotation':(-0.263, 90.603928, -0.265411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.26992188, 5305.77783203, 167.12515625), 'rotation':(-0.25943, 90.606972, -0.26178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.2103125, 5311.41455078, 167.09955078), 'rotation':(-0.25943, 90.606972, -0.26178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6074.15125, 5317.05078125, 167.07408203), 'rotation':(-0.256165, 90.603851, -0.258453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.9725, 5333.96046875, 166.99902343999997), 'rotation':(-0.250885, 90.602043, -0.253113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.8534375, 5345.234375, 166.94960938), 'rotation':(-0.247772, 90.604942, -0.249908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.79429688, 5350.8715625, 166.92515625), 'rotation':(-0.247772, 90.604942, -0.249908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.67515625, 5362.145, 166.87707031000002), 'rotation':(-0.234894, 90.604828, -0.236816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6073.31875, 5395.96582031, 166.74109375), 'rotation':(-0.2211, 90.605103, -0.222839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.14046875, 5412.87648438, 166.67693359), 'rotation':(-0.204498, 90.604988, -0.205994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.0809375, 5418.51320312, 166.65650391), 'rotation':(-0.204498, 90.604988, -0.205994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6073.02140625, 5424.14941406, 166.63640625), 'rotation':(-0.196106, 90.604889, -0.197449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6072.84265625, 5441.06054688, 166.57894531000002), 'rotation':(-0.189026, 90.605995, -0.190277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6072.60484375, 5463.609375, 166.50789062), 'rotation':(-0.165527, 90.605827, -0.166473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6072.36757812, 5486.15773438, 166.44625), 'rotation':(-0.144958, 90.604851, -0.145691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6080.62875, 5497.52148438, 166.41773438), 'rotation':(0.144827, -89.395142, 0.144087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.68835938, 5491.88476562, 166.43199219), 'rotation':(0.144964, -89.399384, 0.144234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.74796875, 5486.24804688, 166.44625), 'rotation':(0.14771, -89.394226, 0.146949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.8665625, 5474.97414062, 166.47589843999998), 'rotation':(0.159546, -89.394135, 0.158665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.92617188, 5469.33691406, 166.49158203), 'rotation':(0.165523, -89.3992, 0.164569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.04484375, 5458.06296875, 166.52476562), 'rotation':(0.17736, -89.394043, 0.176272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.104375, 5452.42625, 166.54224609000002), 'rotation':(0.183179, -89.394043, 0.18201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.16390625, 5446.7890625, 166.5603125), 'rotation':(0.189019, -89.399048, 0.18777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.40125, 5424.24121094, 166.63638672000002), 'rotation':(0.204516, -89.39502, 0.203054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.46078125, 5418.60449219, 166.65648438), 'rotation':(0.212801, -89.394989, 0.21123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6081.52039062, 5412.96828125, 166.67691406000003), 'rotation':(0.212801, -89.394989, 0.21123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.69859375, 5396.05761719, 166.74107422), 'rotation':(0.225294, -89.399109, 0.223524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.81773438, 5384.78417969, 166.78539062), 'rotation':(0.228415, -89.395203, 0.226602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6081.876875, 5379.14746094, 166.80785156000002), 'rotation':(0.234897, -89.395172, 0.232982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.05554688, 5362.23679688, 166.87705078), 'rotation':(0.241358, -89.395142, 0.239334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.1746875, 5350.96386719, 166.92513672), 'rotation':(0.25103, -89.397949, 0.248833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.29335938, 5339.69042969, 166.97429688), 'rotation':(0.25088, -89.393524, 0.248704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.41203125, 5328.41648438, 167.02386718999998), 'rotation':(0.256153, -89.393036, 0.253864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.4715625, 5322.78027344, 167.04886718999998), 'rotation':(0.256153, -89.393036, 0.253864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6082.76890625, 5294.59765625, 167.17697266), 'rotation':(0.264608, -89.393311, 0.262185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.88757812, 5283.32421875, 167.22904297000002), 'rotation':(0.264636, -89.39325, 0.262203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6082.9471875, 5277.6875, 167.25507812), 'rotation':(0.264622, -89.397583, 0.26219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.18492188, 5255.14111328, 167.35960938), 'rotation':(0.266623, -89.394714, 0.264153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6083.24453125, 5249.50439453, 167.38583984000002), 'rotation':(0.266623, -89.394714, 0.264153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6083.363125, 5238.23144531, 167.43830078), 'rotation':(0.264923, -89.397217, 0.262468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6071.70640625, 5536.56007812, 166.33707031000003), 'rotation':(-0.099609, 90.604362, -0.099945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6071.7328125, 5546.38039062, 166.32013672000002), 'rotation':(-0.09259, 90.603531, -0.092865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.6746875, 5551.90382812, 166.31121094), 'rotation':(-0.078033, 90.603493, -0.078278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6071.44125, 5574.0, 166.28560547), 'rotation':(-0.042175, 90.602852, -0.042236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.32507812, 5585.04882812, 166.27724609), 'rotation':(-0.042175, 90.602852, -0.042236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.1503125, 5601.62011719, 166.26503906000002), 'rotation':(-0.029114, 90.601044, -0.029144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6071.03359375, 5612.66992188, 166.26080077999998), 'rotation':(-0.002991, 90.604988, -0.002991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.91734375, 5623.71875, 166.26189452999998), 'rotation':(0.010006, 90.60228, 0.010001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.85875, 5629.2421875, 166.26287109), 'rotation':(0.010006, 90.60228, 0.010001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.800625, 5634.76609375, 166.26382812), 'rotation':(0.010006, 90.605232, 0.009994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6070.27625, 5684.48195312, 166.28697266), 'rotation':(0.069326, 90.605133, 0.069166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.218125, 5690.006875, 166.29333984000002), 'rotation':(0.069176, 90.605133, 0.069009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6070.10195312, 5701.05515625, 166.30691406000003), 'rotation':(0.073363, 90.603455, 0.073175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6080.345625, 5536.65136719, 166.33707031000003), 'rotation':(0.099693, -89.39563, 0.09936), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6080.1278125, 5545.2421875, 166.32212891), 'rotation':(0.099598, -89.39563, 0.09926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.87976562, 5568.56542969, 166.29035156), 'rotation':(0.06376, -89.396484, 0.063634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6079.82164062, 5574.08886719, 166.28560547), 'rotation':(0.049375, -89.396545, 0.049284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.705, 5585.13769531, 166.27724609), 'rotation':(0.04219, -89.397156, 0.042124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.35585938, 5618.28367188, 166.26091797), 'rotation':(0.002992, -89.39502, 0.002981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.24109375, 5629.33203125, 166.26287109), 'rotation':(-0.01001, -89.397675, -0.01001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6079.00625, 5651.42578125, 166.26669922000002), 'rotation':(-0.01001, -89.394775, -0.01001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.94765625, 5656.95070312, 166.26794922000002), 'rotation':(-0.01001, -89.394775, -0.01001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.88953125, 5662.47414062, 166.26962891), 'rotation':(-0.017395, -89.394653, -0.017395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6078.65664062, 5684.57078125, 166.28697266), 'rotation':(-0.061768, -89.394592, -0.06192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.42375, 5706.66703125, 166.31414062), 'rotation':(-0.073364, -89.396545, -0.073547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6067.666875, 5932.04882812, 166.89994141), 'rotation':(0.17042, 90.602409, 0.169399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6067.84609375, 5915.01320312, 166.84867188), 'rotation':(0.173255, 90.603256, 0.172211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6067.90609375, 5909.335, 166.83136718999998), 'rotation':(0.175276, 90.603218, 0.174206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.02578125, 5897.97804688, 166.79634765999998), 'rotation':(0.177496, 90.603294, 0.176396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6068.26546875, 5875.26414062, 166.72558593999997), 'rotation':(0.177817, 90.605766, 0.176715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.32507812, 5869.58546875, 166.70808594), 'rotation':(0.177817, 90.605766, 0.176715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.4446875, 5858.22804688, 166.67357422), 'rotation':(0.172551, 90.605736, 0.171516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.50476562, 5852.54929688, 166.65654297), 'rotation':(0.172551, 90.605736, 0.171516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6068.624375, 5841.191875, 166.62296875), 'rotation':(0.168542, 90.602882, 0.167562), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6068.86367188, 5818.4765625, 166.55736328), 'rotation':(0.160093, 90.603386, 0.159211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6069.22304688, 5784.40382812, 166.46757811999998), 'rotation':(0.145941, 90.602493, 0.145196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6069.283125, 5778.72507812, 166.45347656), 'rotation':(0.143632, 90.608459, 0.142914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6069.34265625, 5773.0459375, 166.43988281000003), 'rotation':(0.139008, 90.602951, 0.138338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6069.40273438, 5767.36765625, 166.42677734), 'rotation':(0.129938, 90.608391, 0.12935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6069.58242188, 5750.33109375, 166.39044922000002), 'rotation':(0.116243, 90.602844, 0.115775), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.2259375, 5915.1015625, 166.84867188), 'rotation':(-0.174103, -89.391296, -0.175171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.28601562, 5909.42335938, 166.83136718999998), 'rotation':(-0.176483, -89.396698, -0.177551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.34609375, 5903.74515625, 166.81392577999998), 'rotation':(-0.17749, -89.396729, -0.178589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.52578125, 5886.70898438, 166.7609375), 'rotation':(-0.179077, -89.392822, -0.180206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.5853125, 5881.03078125, 166.74320312), 'rotation':(-0.177826, -89.397339, -0.178925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6076.70546875, 5869.67335938, 166.70808594), 'rotation':(-0.175079, -89.394226, -0.176147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6076.765, 5863.99460938, 166.69072266), 'rotation':(-0.172546, -89.394257, -0.173584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6076.88515625, 5852.63765625, 166.6565625), 'rotation':(-0.16983, -89.397369, -0.170837), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.00476562, 5841.27976562, 166.62296875), 'rotation':(-0.168549, -89.397095, -0.169556), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.064375, 5835.6015625, 166.60626953), 'rotation':(-0.165741, -89.396576, -0.166718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.18398438, 5824.24414062, 166.57328125), 'rotation':(-0.160095, -89.393707, -0.161011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.2440625, 5818.56492188, 166.55736328), 'rotation':(-0.154388, -89.396667, -0.155212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.3040625, 5812.88671875, 166.54160156), 'rotation':(-0.154388, -89.396667, -0.155212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.42375, 5801.52882812, 166.51126953), 'rotation':(-0.148712, -89.396667, -0.149506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6077.54335938, 5790.17140625, 166.48201172), 'rotation':(-0.143646, -89.397003, -0.144348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.6634375, 5778.8134375, 166.45347656), 'rotation':(-0.139008, -89.391571, -0.139679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.72304688, 5773.13429688, 166.43988281000003), 'rotation':(-0.134552, -89.397034, -0.135193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6077.783125, 5767.45609375, 166.42677734), 'rotation':(-0.125305, -89.397095, -0.125854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6078.08242188, 5739.0615625, 166.36849609), 'rotation':(-0.109344, -89.395691, -0.109772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6062.39, 5074.85791016, 167.78097656000003), 'rotation':(1.058727, 0.745556, 1.020129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6056.95640625, 5074.71582031, 167.68048828), 'rotation':(1.058645, 0.745488, 1.020046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.5184375, 5074.64697266, 167.57986327999998), 'rotation':(1.059403, 0.744604, 1.020755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6046.08, 5074.578125, 167.47912109), 'rotation':(1.06066, 0.7446, 1.021911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6040.64148438, 5074.50927734, 167.37826172), 'rotation':(1.061992, 0.744644, 1.023154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6024.32703125, 5074.30224609, 167.07509765999998), 'rotation':(1.064867, 0.749069, 1.025818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6062.4915625, 5066.33056641, 167.78085938), 'rotation':(-1.058746, -179.25444, -1.098419), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.6053125, 5066.265625, 167.57951172), 'rotation':(-1.060669, -179.255402, -1.100525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6040.71671875, 5066.12792969, 167.37769531), 'rotation':(-1.063416, -179.255249, -1.103455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.38367188, 5065.92089844, 167.07416016), 'rotation':(-1.065979, -179.255203, -1.106232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6018.939375, 5065.85205078, 166.97277343999997), 'rotation':(-1.067444, -179.255142, -1.107788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.1971875, 5066.83544922, 168.58658203), 'rotation':(-1.05368, -179.254761, -1.092957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6128.97351562, 5067.24560547, 169.00542968999997), 'rotation':(-1.05246, -179.254654, -1.091675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6157.448125, 5067.60644531, 169.52734375), 'rotation':(-1.049225, -179.253174, -1.088196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6168.83828125, 5067.75097656, 169.73603516), 'rotation':(-1.049225, -179.253174, -1.088196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.92320312, 5067.96728516, 170.04845702999998), 'rotation':(-1.045654, -179.255829, -1.084381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6197.31335938, 5068.11132812, 170.25644531), 'rotation':(-1.045807, -179.25293, -1.084534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6203.00867188, 5068.18310547, 170.36042969), 'rotation':(-1.045227, -179.258408, -1.083893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6220.09265625, 5068.42626953, 170.67199218999997), 'rotation':(-1.044128, -179.253647, -1.082733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6231.4828125, 5068.57714844, 170.87939452999998), 'rotation':(-1.042816, -179.253708, -1.081299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6237.17765625, 5068.64941406, 170.98298828), 'rotation':(-1.04184, -179.253799, -1.080261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6248.56773438, 5068.79345703, 171.19001953), 'rotation':(-1.040619, -179.253784, -1.078918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6254.26257812, 5068.86572266, 171.29345702999998), 'rotation':(-1.040375, -179.25415, -1.078674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6259.95742188, 5068.93798828, 171.39691406000003), 'rotation':(-1.040253, -179.257568, -1.078552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6265.65273438, 5069.00976562, 171.5003125), 'rotation':(-1.040253, -179.257568, -1.078552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6271.3475, 5069.08203125, 171.60365234), 'rotation':(-1.039001, -179.255692, -1.07724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.77820312, 5077.79101562, 172.11986328), 'rotation':(1.035648, 0.743526, 0.998706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6294.08335938, 5077.71923828, 172.01685547), 'rotation':(1.035525, 0.743523, 0.998582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6282.69328125, 5077.57470703, 171.81087890999999), 'rotation':(1.035648, 0.743526, 0.998706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6248.52328125, 5077.14208984, 171.19113281000003), 'rotation':(1.04034, 0.745846, 1.003066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6231.43835938, 5076.92578125, 170.88050781), 'rotation':(1.041843, 0.746208, 1.004449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6225.74351562, 5076.85351562, 170.77685547000002), 'rotation':(1.042806, 0.7463, 1.005357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6208.65859375, 5076.63720703, 170.46544922), 'rotation':(1.044725, 0.746368, 1.007138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6191.5740625, 5076.42089844, 170.15357422), 'rotation':(1.045736, 0.747036, 1.008079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.87929688, 5076.34912109, 170.04958984), 'rotation':(1.045736, 0.747036, 1.008079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6180.18445312, 5076.27685547, 169.94560547), 'rotation':(1.045654, 0.744167, 1.007997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6174.48914062, 5076.20458984, 169.84142577999998), 'rotation':(1.047567, 0.74588, 1.009773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6163.09898438, 5076.06005859, 169.6328125), 'rotation':(1.049172, 0.743487, 1.01125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6157.40421875, 5075.98828125, 169.52847656000003), 'rotation':(1.049329, 0.743532, 1.011406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6151.709375, 5075.91601562, 169.42414062), 'rotation':(1.049329, 0.743532, 1.011406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6123.23421875, 5075.55517578, 168.90193359), 'rotation':(1.052464, 0.745328, 1.014313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.15273438, 5075.45996094, 168.58777343999998), 'rotation':(1.053536, 0.745217, 1.015306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6100.45351562, 5075.39648438, 168.48291016), 'rotation':(1.053584, 0.745172, 1.015347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.21960938, 5744.12304688, 170.32771484), 'rotation':(0.165837, 90.901688, 0.16488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.0409375, 5755.49460938, 170.36085938), 'rotation':(0.171451, 90.90181, 0.17043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6300.9515625, 5761.18015625, 170.37798827999998), 'rotation':(0.183008, 90.898155, 0.18186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.7728125, 5772.55078125, 170.41517578), 'rotation':(0.205876, 90.898323, 0.204408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.6834375, 5778.23632812, 170.43501952999998), 'rotation':(0.205876, 90.898323, 0.204408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.59414062, 5783.92234375, 170.45556641), 'rotation':(0.211633, 90.90448, 0.210086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6300.50523438, 5789.60789062, 170.4765625), 'rotation':(0.211633, 90.899513, 0.210079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6300.3265625, 5800.97898438, 170.51896484), 'rotation':(0.219235, 90.9039, 0.21757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6299.79039062, 5835.0903125, 170.6578125), 'rotation':(0.249944, 90.899178, 0.247776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.4325, 5857.83203125, 170.75818359000002), 'rotation':(0.260647, 90.900993, 0.258272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6299.25429688, 5869.20265625, 170.8103125), 'rotation':(0.271391, 90.9011, 0.268829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.07554688, 5880.57328125, 170.86398438), 'rotation':(0.274171, 90.901024, 0.27156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.98625, 5886.25828125, 170.89121093999998), 'rotation':(0.27415, 90.900963, 0.271545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.896875, 5891.94335938, 170.91841797), 'rotation':(0.274287, 90.901009, 0.271679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6298.718125, 5903.3134375, 170.97283202999998), 'rotation':(0.27415, 90.900963, 0.271545), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.62929688, 5908.99851562, 171.00003906), 'rotation':(0.276507, 90.90287, 0.273853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.53992188, 5914.6840625, 171.0275), 'rotation':(0.278938, 90.900658, 0.276238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.08140625, 5935.64695312, 171.12943359000002), 'rotation':(0.278918, 90.904465, 0.276223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.720625, 5935.69234375, 171.12900391), 'rotation':(-0.278809, -89.099365, -0.281525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.8690625, 5918.32179688, 171.04443359), 'rotation':(-0.27652, -89.10022, -0.279205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.7928125, 5929.69289062, 171.09978515999998), 'rotation':(-0.278809, -89.099365, -0.281525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.00820312, 5909.13375, 171.00005859), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.0975, 5903.44828125, 170.97283202999998), 'rotation':(-0.274292, -89.095184, -0.276917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.186875, 5897.76320312, 170.945625), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.27625, 5892.078125, 170.91841797), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.365625, 5886.39304688, 170.89121093999998), 'rotation':(-0.27417, -89.09903, -0.276794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.54429688, 5875.0225, 170.83699219), 'rotation':(-0.266022, -89.098938, -0.268494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.7225, 5863.651875, 170.78404297), 'rotation':(-0.26062, -89.098999, -0.263031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.811875, 5857.96679688, 170.75818359000002), 'rotation':(-0.255005, -89.09906, -0.257294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.90125, 5852.28171875, 170.73285156000003), 'rotation':(-0.25238, -89.10144, -0.254608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6308.34851562, 5823.85351562, 170.60949218999997), 'rotation':(-0.234436, -89.100922, -0.236359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.43734375, 5818.16890625, 170.58611327999998), 'rotation':(-0.229462, -89.096069, -0.231293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.52671875, 5812.484375, 170.56322265999998), 'rotation':(-0.224365, -89.101013, -0.226135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.61609375, 5806.79835938, 170.54083984000002), 'rotation':(-0.219238, -89.096069, -0.220917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.70546875, 5801.11328125, 170.51898438), 'rotation':(-0.214111, -89.101166, -0.215729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.88414062, 5789.74125, 170.47658203), 'rotation':(-0.211639, -89.100494, -0.213196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.97351562, 5784.05664062, 170.45556641), 'rotation':(-0.205872, -89.0979, -0.207367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6309.06289062, 5778.37015625, 170.43501952999998), 'rotation':(-0.194427, -89.098022, -0.19577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6309.2415625, 5766.9990625, 170.39613281), 'rotation':(-0.183014, -89.101837, -0.184174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6309.41984375, 5755.6284375, 170.36087891), 'rotation':(-0.165833, -89.098328, -0.166809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.87875, 5700.68898438, 170.22242188), 'rotation':(0.113053, 90.898552, 0.112605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6301.98867188, 5695.16554688, 170.21191406000003), 'rotation':(0.113053, 90.898552, 0.112605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.1625, 5684.11375, 170.19201172), 'rotation':(0.098444, 90.900833, 0.098112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.24890625, 5678.58789062, 170.18363281), 'rotation':(0.098444, 90.900833, 0.098112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.5096875, 5662.01078125, 170.16597656000002), 'rotation':(0.043433, 90.900742, 0.043368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6302.76992188, 5645.43457031, 170.15564453), 'rotation':(0.034247, 90.898438, 0.034214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6302.85632812, 5639.90917969, 170.15234375), 'rotation':(0.034247, 90.902122, 0.034209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.03015625, 5628.85695312, 170.14587891), 'rotation':(0.034247, 90.898438, 0.034214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.1165625, 5623.33203125, 170.14404297000002), 'rotation':(0.018824, 90.900299, 0.018826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.29039062, 5612.27882812, 170.14630859000002), 'rotation':(-0.012177, 90.900337, -0.012177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6303.37734375, 5606.7534375, 170.14896484000002), 'rotation':(-0.027527, 90.898773, -0.027557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.72453125, 5584.6528125, 170.15960938), 'rotation':(-0.027527, 90.898827, -0.027557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.81140625, 5579.12792969, 170.16228515999998), 'rotation':(-0.027618, 90.898773, -0.027649), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6303.98476562, 5568.07570312, 170.17066406), 'rotation':(-0.046448, 90.901329, -0.046539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.15859375, 5557.02195312, 170.18662109000002), 'rotation':(-0.08432, 90.898605, -0.084564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.41882812, 5540.44679688, 170.21648438), 'rotation':(-0.103241, 90.898819, -0.103607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.3040625, 5700.82078125, 170.22242188), 'rotation':(-0.107605, -89.098602, -0.108002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.62828125, 5678.71921875, 170.18363281), 'rotation':(-0.080139, -89.099213, -0.080383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.23570312, 5640.04003906, 170.15234375), 'rotation':(-0.034241, -89.097809, -0.034271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.32265625, 5634.51515625, 170.14904297), 'rotation':(-0.034241, -89.097809, -0.034271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.40953125, 5628.9878125, 170.14587891), 'rotation':(-0.01886, -89.099701, -0.018829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.4959375, 5623.46289062, 170.14404297000002), 'rotation':(0.012158, -89.099701, 0.012155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.84359375, 5601.35984375, 170.15162109000002), 'rotation':(0.027621, -89.101166, 0.027595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6311.93007812, 5595.83445312, 170.15429688), 'rotation':(0.027512, -89.098206, 0.027505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.10390625, 5584.78417969, 170.15960938), 'rotation':(0.027621, -89.101166, 0.027595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.19078125, 5579.25929688, 170.16228515999998), 'rotation':(0.046473, -89.098663, 0.046396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.71179688, 5546.10253906, 170.20652343999998), 'rotation':(0.103245, -89.101166, 0.10286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6308.99890625, 5248.92626953, 171.49783202999998), 'rotation':(-0.329773, 90.902222, -0.333588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6308.91, 5254.56396484, 171.46537109000002), 'rotation':(-0.329865, 90.899261, -0.333679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6308.644375, 5271.47802734, 171.36806640999998), 'rotation':(-0.326752, 90.901352, -0.330505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.9359375, 5316.58203125, 171.11412109), 'rotation':(-0.312744, 90.902184, -0.316162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6307.75867188, 5327.85890625, 171.05234375), 'rotation':(-0.307037, 90.902153, -0.310333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6307.49304688, 5344.77296875, 170.96234375), 'rotation':(-0.298553, 90.900734, -0.301666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6307.31578125, 5356.04929688, 170.90345703), 'rotation':(-0.298462, 90.900803, -0.301575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6307.22742188, 5361.6875, 170.87408202999998), 'rotation':(-0.294342, 90.901489, -0.297394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.96179688, 5378.60253906, 170.78859375), 'rotation':(-0.277863, 90.901321, -0.280548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.78453125, 5389.87890625, 170.73478516), 'rotation':(-0.265533, 90.904068, -0.267975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.60734375, 5401.15625, 170.68244141), 'rotation':(-0.265503, 90.900429, -0.267975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6306.51890625, 5406.79492188, 170.65636718999997), 'rotation':(-0.259613, 90.900574, -0.261963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.34171875, 5418.07179688, 170.60578125), 'rotation':(-0.247925, 90.900459, -0.250092), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6306.16445312, 5429.348125, 170.55785156000002), 'rotation':(-0.236145, 90.900352, -0.238098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.98671875, 5440.62453125, 170.51263672000002), 'rotation':(-0.218628, 90.90033, -0.220276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.89828125, 5446.26320312, 170.49078125), 'rotation':(-0.218628, 90.90033, -0.220276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.72109375, 5457.54101562, 170.44800781), 'rotation':(-0.20813, 90.899536, -0.209656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.63265625, 5463.1796875, 170.42746093999997), 'rotation':(-0.201233, 90.899399, -0.202637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6313.65757812, 5485.86816406, 170.35302734), 'rotation':(0.180549, -89.100708, 0.179423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.74648438, 5480.22949219, 170.37050781000002), 'rotation':(0.187291, -89.100616, 0.186072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6313.92320312, 5468.953125, 170.40771484), 'rotation':(0.201231, -89.100586, 0.199822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6314.10046875, 5457.67625, 170.44800781), 'rotation':(0.215199, -89.100403, 0.213598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.27773438, 5446.39890625, 170.49076172000002), 'rotation':(0.224563, -89.09671, 0.222819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.63265625, 5423.84570312, 170.58134766), 'rotation':(0.247929, -89.099518, 0.24579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.89828125, 5406.93117188, 170.65634766), 'rotation':(0.26551, -89.099548, 0.263066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.98671875, 5401.2925, 170.68242188), 'rotation':(0.265503, -89.095917, 0.26306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.16390625, 5390.01515625, 170.73476562), 'rotation':(0.269601, -89.098755, 0.267071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.25234375, 5384.37742188, 170.76126953), 'rotation':(0.277845, -89.098663, 0.27517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.34070312, 5378.73976562, 170.78857422000002), 'rotation':(0.286089, -89.098572, 0.283248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.42953125, 5373.10109375, 170.81648438), 'rotation':(0.29434, -89.098511, 0.291337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.60679688, 5361.82375, 170.8740625), 'rotation':(0.298452, -89.099243, 0.295346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.69515625, 5356.18601562, 170.90341797000002), 'rotation':(0.298561, -89.099182, 0.29547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.78359375, 5350.54785156, 170.9328125), 'rotation':(0.301307, -89.097931, 0.298145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.87195312, 5344.91015625, 170.96230469), 'rotation':(0.301307, -89.097931, 0.298145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.13804688, 5327.995625, 171.05230468999997), 'rotation':(0.312741, -89.100769, 0.309347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6316.40367188, 5311.08105469, 171.14542969), 'rotation':(0.321347, -89.095917, 0.317761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.49257812, 5305.44287109, 171.17697266), 'rotation':(0.321347, -89.095917, 0.317761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.66929688, 5294.16699219, 171.24019531000002), 'rotation':(0.322364, -89.098694, 0.318758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6316.75765625, 5288.52929688, 171.27191406000003), 'rotation':(0.324468, -89.098724, 0.320806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.93492188, 5277.25292969, 171.33583984), 'rotation':(0.326722, -89.098724, 0.323029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.1121875, 5265.97705078, 171.40041015999998), 'rotation':(0.329884, -89.097748, 0.326113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.55507812, 5237.78759766, 171.56251953), 'rotation':(0.327644, -89.097412, 0.323915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.03257812, 5183.11279297, 171.86980469), 'rotation':(-0.315338, 90.900093, -0.318848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.11953125, 5177.578125, 171.90005859000001), 'rotation':(-0.313019, 90.900146, -0.316467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.38023438, 5160.97509766, 171.98931641), 'rotation':(-0.305756, 90.899986, -0.309052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.4671875, 5155.44042969, 172.01875), 'rotation':(-0.304718, 90.902725, -0.307983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.5540625, 5149.90673828, 172.04800781000003), 'rotation':(-0.304718, 90.902725, -0.307983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6310.72789062, 5138.83740234, 172.10556641), 'rotation':(-0.300873, 90.902084, -0.304047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6310.81484375, 5133.30322266, 172.13375), 'rotation':(-0.293274, 90.902077, -0.296295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.16296875, 5111.16601562, 172.24195312), 'rotation':(-0.274231, 90.900352, -0.276825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.24984375, 5105.63085938, 172.2684375), 'rotation':(-0.274353, 90.905151, -0.277008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6311.33679688, 5100.09667969, 172.2946875), 'rotation':(-0.271271, 90.90126, -0.273865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.803125, 5094.69335938, 172.32037109), 'rotation':(0.259274, -89.098877, 0.256937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.62929688, 5105.76220703, 172.2684375), 'rotation':(0.271275, -89.098755, 0.268716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.54234375, 5111.296875, 172.24195312), 'rotation':(0.274355, -89.099609, 0.271748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6319.36851562, 5122.36523438, 172.18855469), 'rotation':(0.278071, -89.098145, 0.275392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.19421875, 5133.43457031, 172.13375), 'rotation':(0.285679, -89.098022, 0.282849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.02039062, 5144.50292969, 172.07708984), 'rotation':(0.293268, -89.101105, 0.290286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.9334375, 5150.03759766, 172.04802734), 'rotation':(0.300877, -89.097839, 0.297739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.67273438, 5166.64013672, 171.95978516), 'rotation':(0.305753, -89.100006, 0.302512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.58578125, 5172.17480469, 171.93005859000002), 'rotation':(0.308308, -89.099884, 0.30501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.49890625, 5177.70898438, 171.90005859000001), 'rotation':(0.310466, -89.094574, 0.307116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.32507812, 5188.77832031, 171.83931640999998), 'rotation':(0.315336, -89.099884, 0.311884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.23765625, 5194.31298828, 171.80859375), 'rotation':(0.317727, -89.094421, 0.314215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.06382812, 5205.38134766, 171.74644531), 'rotation':(0.322405, -89.099792, 0.318793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.10734375, 5051.00292969, 172.50283202999998), 'rotation':(-0.229767, 90.898247, -0.231598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.19570312, 5045.37255859, 172.52474609), 'rotation':(-0.223175, 90.900284, -0.224915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.2840625, 5039.74267578, 172.54546875), 'rotation':(-0.210022, 90.903999, -0.211578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.54921875, 5022.85498047, 172.60232422), 'rotation':(-0.183807, 90.899956, -0.184998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.63804688, 5017.22460938, 172.61974609), 'rotation':(-0.177216, 90.898819, -0.178314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.72640625, 5011.59521484, 172.63716797), 'rotation':(-0.177216, 90.898819, -0.178314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6312.81484375, 5005.96679688, 172.65447265999998), 'rotation':(-0.177216, 90.902245, -0.178314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6312.90320312, 5000.33691406, 172.67119141), 'rotation':(-0.170166, 90.899452, -0.171173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6313.345625, 4972.19091797, 172.74179688), 'rotation':(-0.127197, 90.899246, -0.127777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.52234375, 4960.93017578, 172.76517578), 'rotation':(-0.120087, 90.901237, -0.120575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.61070312, 4955.30029297, 172.77613281), 'rotation':(-0.111481, 90.90036, -0.111908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.7875, 4944.04101562, 172.79539062), 'rotation':(-0.094452, 90.900352, -0.094757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6313.9646875, 4932.78320312, 172.8103125), 'rotation':(-0.077301, 90.900246, -0.077515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.14148438, 4921.52392578, 172.82164062), 'rotation':(-0.060181, 90.897263, -0.060303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.22984375, 4915.89404297, 172.82669922000002), 'rotation':(-0.051544, 90.90284, -0.051636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.40664062, 4904.63378906, 172.83685547000002), 'rotation':(-0.051666, 90.899025, -0.051758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6314.760625, 4882.11914062, 172.84142577999998), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6314.84898438, 4876.48925781, 172.83833984), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6314.93734375, 4870.859375, 172.83525391), 'rotation':(0.031494, 90.90036, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.02578125, 4865.22949219, 172.83214843999997), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.11414062, 4859.59912109, 172.8290625), 'rotation':(0.031494, 90.900314, 0.03147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.2909375, 4848.34033203, 172.82203125), 'rotation':(0.041698, 90.898911, 0.041631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.37929688, 4842.71191406, 172.81742188), 'rotation':(0.041698, 90.898911, 0.041631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.468125, 4837.08154297, 172.81134766), 'rotation':(0.062155, 90.902039, 0.062008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.5565625, 4831.453125, 172.80388672), 'rotation':(0.062155, 90.902039, 0.062008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.64492188, 4825.82421875, 172.79564453), 'rotation':(0.082516, 90.898994, 0.082265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.73328125, 4820.19433594, 172.78552734000002), 'rotation':(0.102958, 90.899078, 0.10259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6315.82164062, 4814.56494141, 172.77492188), 'rotation':(0.102958, 90.899078, 0.10259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.91054688, 4808.93603516, 172.76359375), 'rotation':(0.11319, 90.90065, 0.11275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6315.99890625, 4803.30664062, 172.75171875), 'rotation':(0.120765, 90.900795, 0.120264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.175625, 4792.04785156, 172.72527344), 'rotation':(0.136214, 90.900871, 0.135563), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6316.2640625, 4786.41796875, 172.71041015999998), 'rotation':(0.151453, 90.90094, 0.150651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6324.73179688, 4780.92041016, 172.69474609), 'rotation':(-0.166809, -89.098969, -0.167755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.55507812, 4792.18017578, 172.72527344), 'rotation':(-0.151428, -89.102234, -0.152252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.46671875, 4797.80908203, 172.73880859000002), 'rotation':(-0.1362, -89.099152, -0.136871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.20109375, 4814.69775391, 172.77494141), 'rotation':(-0.11319, -89.099335, -0.113647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6324.11265625, 4820.32617188, 172.78552734000002), 'rotation':(-0.11319, -89.099335, -0.113647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.9359375, 4831.58496094, 172.80388672), 'rotation':(-0.08252, -89.097839, -0.082733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.8475, 4837.21337891, 172.81134766), 'rotation':(-0.08252, -89.097839, -0.082733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.75867188, 4842.84326172, 172.81742188), 'rotation':(-0.062134, -89.101074, -0.062286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6323.40515625, 4865.36132812, 172.83214843999997), 'rotation':(-0.031494, -89.09967, -0.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.14, 4882.25146484, 172.84142577999998), 'rotation':(-0.031494, -89.09967, -0.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6323.05164062, 4887.88134766, 172.84451172), 'rotation':(-0.031494, -89.09967, -0.031525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.96328125, 4893.50830078, 172.84550781000002), 'rotation':(0.009965, -89.09906, 0.009962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6322.874375, 4899.13574219, 172.84191406000002), 'rotation':(0.009965, -89.09906, 0.009962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.78601562, 4904.765625, 172.83685547000002), 'rotation':(0.051657, -89.100983, 0.051564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.69765625, 4910.39550781, 172.83177734), 'rotation':(0.05167, -89.100922, 0.051571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.52085938, 4921.65576172, 172.82164062), 'rotation':(0.051547, -89.097076, 0.051457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.34414062, 4932.91455078, 172.8103125), 'rotation':(0.060167, -89.099792, 0.06004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.166875, 4944.17285156, 172.79539062), 'rotation':(0.077311, -89.099701, 0.077108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.99015625, 4955.43115234, 172.77613281), 'rotation':(0.094441, -89.102661, 0.09414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.90171875, 4961.06103516, 172.76517578), 'rotation':(0.111489, -89.099609, 0.111058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.81335938, 4966.69091797, 172.75361328), 'rotation':(0.111489, -89.099609, 0.111058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6321.72453125, 4972.32226562, 172.74179688), 'rotation':(0.120075, -89.098755, 0.11958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.19421875, 5006.09814453, 172.65447265999998), 'rotation':(0.17016, -89.100525, 0.169152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.10585938, 5011.72607422, 172.63716797), 'rotation':(0.17723, -89.097687, 0.176131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6320.92859375, 5022.98583984, 172.60232422), 'rotation':(0.177223, -89.101227, 0.176121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.6634375, 5039.87402344, 172.54546875), 'rotation':(0.196969, -89.09613, 0.195613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6320.57507812, 5045.50341797, 172.52474609), 'rotation':(0.210028, -89.099792, 0.208488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.48671875, 5051.13330078, 172.50283202999998), 'rotation':(0.223176, -89.099701, 0.221455), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.30554688, 4720.08740234, 172.47470703), 'rotation':(0.250087, 90.90065, 0.247918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.394375, 4714.42578125, 172.44916016), 'rotation':(0.257334, 90.904724, 0.255027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.48328125, 4708.76464844, 172.42300781000003), 'rotation':(0.261863, 90.898354, 0.259481), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.66101562, 4697.44140625, 172.36794922), 'rotation':(0.279703, 90.898537, 0.276988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.74984375, 4691.78125, 172.33904297), 'rotation':(0.288958, 90.903778, 0.286063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6317.83875, 4686.12011719, 172.30923828), 'rotation':(0.297694, 90.898712, 0.294622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.01695312, 4674.796875, 172.24683593999998), 'rotation':(0.324782, 90.904091, 0.321115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.10585938, 4669.13574219, 172.21447265999998), 'rotation':(0.329413, 90.901634, 0.325639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.1946875, 4663.47363281, 172.18193359), 'rotation':(0.32927, 90.901718, 0.325511), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.37242188, 4652.15234375, 172.11505859000002), 'rotation':(0.337111, 90.902496, 0.333168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.46179688, 4646.49070312, 172.08019531000002), 'rotation':(0.35269, 90.902733, 0.348373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.550625, 4640.82960938, 172.04396484), 'rotation':(0.368243, 90.899414, 0.36354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.63953125, 4635.1684375, 172.00679688), 'rotation':(0.368243, 90.899414, 0.36354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.7284375, 4629.5078125, 171.96878906), 'rotation':(0.383706, 90.90313, 0.378592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6318.81726562, 4623.84617188, 171.93009766), 'rotation':(0.391411, 90.902901, 0.38609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6318.90664062, 4618.18457031, 171.89140625), 'rotation':(0.391547, 90.902885, 0.386221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.17320312, 4601.20070312, 171.77175781000003), 'rotation':(0.413821, 90.903358, 0.407862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.2615625, 4595.54148438, 171.73042969), 'rotation':(0.413821, 90.903358, 0.407862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.439375, 4584.21828125, 171.64482422), 'rotation':(0.428656, 90.903519, 0.422282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6319.88414062, 4555.91308594, 171.42068359), 'rotation':(0.467643, 90.903076, 0.460062), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6319.97304688, 4550.25195312, 171.3740625), 'rotation':(0.474165, 90.903183, 0.466364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6320.061875, 4544.58984375, 171.32669922000002), 'rotation':(0.480722, 90.903374, 0.472718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.15078125, 4538.92921875, 171.27867188), 'rotation':(0.487368, 90.903412, 0.479132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.23960938, 4533.26757812, 171.22992188), 'rotation':(0.494055, 90.908882, 0.48559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6320.32507812, 4527.83300781, 171.18244141), 'rotation':(0.500578, 90.903641, 0.491899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.59609375, 4725.87890625, 172.49951172000002), 'rotation':(-0.250092, -89.099365, -0.252258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.9515625, 4703.234375, 172.3959375), 'rotation':(-0.279724, -89.096283, -0.282471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.12929688, 4691.91259766, 172.33904297), 'rotation':(-0.297729, -89.101288, -0.300812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6326.3075, 4680.58886719, 172.27847656000003), 'rotation':(-0.315857, -89.101105, -0.319366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.5740625, 4663.605, 172.18193359), 'rotation':(-0.337128, -89.097443, -0.341125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.66296875, 4657.94484375, 172.14884766), 'rotation':(-0.352692, -89.100769, -0.357056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.84117188, 4646.62207031, 172.08017578), 'rotation':(-0.368256, -89.097046, -0.373016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6326.93007812, 4640.96046875, 172.04396484), 'rotation':(-0.383698, -89.096863, -0.388855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.1078125, 4629.63914062, 171.96878906), 'rotation':(-0.391418, -89.097107, -0.39679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6327.19664062, 4623.97753906, 171.93009766), 'rotation':(-0.391541, -89.097107, -0.396942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.28601562, 4618.3159375, 171.89140625), 'rotation':(-0.398926, -89.096893, -0.40451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.72984375, 4590.01074219, 171.68802734000002), 'rotation':(-0.443542, -89.099091, -0.450439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6327.90757812, 4578.6875, 171.60097656000002), 'rotation':(-0.450958, -89.093384, -0.458099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6327.99648438, 4573.02734375, 171.55654297), 'rotation':(-0.454468, -89.097046, -0.461731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6328.44125, 4544.72117188, 171.32669922000002), 'rotation':(-0.487366, -89.096588, -0.495728), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6328.53015625, 4539.06054688, 171.27867188), 'rotation':(-0.49411, -89.096405, -0.502686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6321.01109375, 4484.16308594, 170.78740234), 'rotation':(0.538328, 90.904564, 0.528286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.18492188, 4473.09523438, 170.68257812), 'rotation':(0.542488, 90.905098, 0.532283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.35875, 4462.02734375, 170.57724609000002), 'rotation':(0.546504, 90.905426, 0.536156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.44570312, 4456.49367188, 170.52390625), 'rotation':(0.546504, 90.905426, 0.536156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.61953125, 4445.42578125, 170.41589843999998), 'rotation':(0.562548, 90.905739, 0.551579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.70640625, 4439.89210938, 170.36115234000002), 'rotation':(0.562548, 90.905739, 0.551579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6321.88078125, 4428.82421875, 170.25054688), 'rotation':(0.57459, 90.903397, 0.563154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.14148438, 4412.223125, 170.08330078), 'rotation':(0.578988, 90.904541, 0.567381), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.2284375, 4406.68898438, 170.02697265999998), 'rotation':(0.581953, 90.904602, 0.570215), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.4021875, 4395.62109375, 169.91347656000002), 'rotation':(0.587847, 90.909973, 0.575891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6322.66296875, 4379.01953125, 169.74105468999997), 'rotation':(0.596719, 90.9049, 0.584392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6322.74984375, 4373.48535156, 169.68324219), 'rotation':(0.598338, 90.908684, 0.58595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6329.39046875, 4484.29640625, 170.78742188), 'rotation':(-0.54248, -89.094879, -0.552826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6329.82507812, 4456.62695312, 170.52392577999998), 'rotation':(-0.554413, -89.094421, -0.565247), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.08578125, 4440.02539062, 170.36115234000002), 'rotation':(-0.570557, -89.094086, -0.582031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.43398438, 4417.89109375, 170.13933594), 'rotation':(-0.579041, -89.090118, -0.590851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.52085938, 4412.35695312, 170.08332031), 'rotation':(-0.58194, -89.095367, -0.593872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6330.6078125, 4406.82324219, 170.02701172000002), 'rotation':(-0.585083, -89.095337, -0.597107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.6946875, 4401.28953125, 169.97041016), 'rotation':(-0.58786, -89.095276, -0.600037), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.95546875, 4384.68796875, 169.79880859000002), 'rotation':(-0.596802, -89.095001, -0.609314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.48625, 4353.45164062, 164.22880859), 'rotation':(-0.969025, -179.938156, -1.002228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6008.05117188, 4361.81984375, 163.95224609000002), 'rotation':(0.96098, 0.058542, 0.929126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.52867188, 4361.82421875, 164.04412109), 'rotation':(0.968999, 0.061839, 0.93664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6019.00625, 4361.82859375, 164.13621093999998), 'rotation':(0.968999, 0.061839, 0.93664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.4828125, 4361.8325, 164.22886719), 'rotation':(0.976997, 0.062107, 0.944096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6029.9603125, 4361.83691406, 164.32195312), 'rotation':(0.976997, 0.062107, 0.944096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6040.9134375, 4361.84570312, 164.50945312), 'rotation':(0.989168, 0.060855, 0.955434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.86757812, 4361.85398438, 164.69832031), 'rotation':(0.989039, 0.060851, 0.955319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6057.34414062, 4361.85839844, 164.79289062), 'rotation':(0.992242, 0.063003, 0.958313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6068.29484375, 4361.99070312, 164.9825), 'rotation':(0.998505, 0.063222, 0.964138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6111.89296875, 4353.52, 165.74869141), 'rotation':(-1.011139, -179.938263, -1.047302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6123.23914062, 4353.52929688, 165.94912109), 'rotation':(-1.012024, -179.938232, -1.048279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6134.5853125, 4353.53808594, 166.14980469), 'rotation':(-1.012817, -179.93483, -1.049103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6140.25867188, 4353.5425, 166.25019531), 'rotation':(-1.013641, -179.938171, -1.050018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6145.93203125, 4353.546875, 166.35066406), 'rotation':(-1.014069, -179.939301, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6157.27820312, 4353.55617188, 166.5515625), 'rotation':(-1.014069, -179.935425, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6162.95109375, 4353.56054688, 166.65199219), 'rotation':(-1.014069, -179.935425, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6168.624375, 4353.56492188, 166.75244141), 'rotation':(-1.014069, -179.939301, -1.050446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6191.31679688, 4353.5825, 167.15396484000001), 'rotation':(-1.013214, -179.934555, -1.049561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6196.98960938, 4353.58691406, 167.25431641), 'rotation':(-1.013245, -179.938522, -1.049561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6202.66296875, 4353.59132812, 167.3546875), 'rotation':(-1.013245, -179.938522, -1.049561), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6208.33046875, 4353.59523438, 167.45486327999998), 'rotation':(-1.011902, -179.936127, -1.048157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6219.6815625, 4353.60449219, 167.65505859), 'rotation':(-1.009033, -179.936234, -1.045074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6231.0271875, 4353.61328125, 167.854375), 'rotation':(-1.006317, -179.939606, -1.042175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6236.70054688, 4353.61765625, 167.95378906000002), 'rotation':(-1.003601, -179.936417, -1.039246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6248.04671875, 4353.62011719, 168.15236328), 'rotation':(-1.002167, -179.938736, -1.037689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6253.72007812, 4353.64304688, 168.25166016), 'rotation':(-1.002258, -179.933273, -1.037811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.73914062, 4353.67773438, 168.54871093999998), 'rotation':(-0.997864, -179.941818, -1.033112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.75867188, 4353.6909375, 168.84345703), 'rotation':(-0.990326, -179.937561, -1.025024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.1053125, 4353.6996875, 169.03951172), 'rotation':(-0.988861, -179.938705, -1.023438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.77820312, 4353.70410156, 169.13724609000002), 'rotation':(-0.986328, -179.938766, -1.020752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6310.45109375, 4353.70851562, 169.2346875), 'rotation':(-0.98349, -179.938873, -1.0177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6310.48328125, 4362.05664062, 169.23533203), 'rotation':(0.98087, 0.061027, 0.947703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6299.13710938, 4362.04785156, 169.04019531000003), 'rotation':(0.986238, 0.06121, 0.952713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6293.46375, 4362.04296875, 168.94220703), 'rotation':(0.988847, 0.0613, 0.955144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.7909375, 4362.03859375, 168.84412109000002), 'rotation':(0.990336, 0.062446, 0.956524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6282.11757812, 4362.03417969, 168.74603516), 'rotation':(0.990398, 0.062452, 0.956591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.771875, 4362.02539062, 168.54939453), 'rotation':(0.994851, 0.063177, 0.960731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6265.09851562, 4362.02101562, 168.45064452999998), 'rotation':(0.997788, 0.058171, 0.963476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6248.07945312, 4362.0078125, 168.15306640999998), 'rotation':(1.002153, 0.066716, 0.967544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6242.40609375, 4362.00292969, 168.05376952999998), 'rotation':(1.002262, 0.061258, 0.967635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6236.73328125, 4361.99851562, 167.95449219), 'rotation':(1.002337, 0.061255, 0.967707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6208.36804688, 4361.9765625, 167.45564453), 'rotation':(1.009058, 0.063771, 0.973962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6202.69515625, 4361.9721875, 167.35537109), 'rotation':(1.011927, 0.063873, 0.976634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6197.021875, 4361.96777344, 167.255), 'rotation':(1.013218, 0.061472, 0.977847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6191.34898438, 4361.96335938, 167.15464844), 'rotation':(1.013218, 0.061472, 0.977847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6162.98328125, 4361.9409375, 166.65267577999998), 'rotation':(1.014051, 0.06458, 0.978617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6151.63710938, 4361.93210938, 166.45179688), 'rotation':(1.013983, 0.060691, 0.978551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6140.2909375, 4361.92335938, 166.25089844), 'rotation':(1.014058, 0.060692, 0.978624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6117.59804688, 4361.90578125, 165.84957031000002), 'rotation':(1.011968, 0.061762, 0.97668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.251875, 4361.89648438, 165.64919922), 'rotation':(1.011189, 0.061734, 0.975956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6348.42320312, 4353.70554688, 169.88019531), 'rotation':(-0.967682, -179.938965, -1.000793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6353.94910156, 4353.70996094, 169.97345703), 'rotation':(-0.967682, -179.938965, -1.000793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6359.475, 4353.714375, 170.06658202999998), 'rotation':(-0.96582, -179.940201, -0.99881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6370.52773438, 4353.72265625, 170.25201172), 'rotation':(-0.95874, -179.94043, -0.991241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6376.0540625, 4353.72703125, 170.34439453), 'rotation':(-0.95874, -179.94043, -0.991241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6387.10632812, 4353.73585938, 170.52853516), 'rotation':(-0.953339, -179.938736, -0.985474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6398.1590625, 4353.74414062, 170.7125), 'rotation':(-0.953339, -179.938736, -0.985474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6409.21132812, 4353.75292969, 170.89626952999998), 'rotation':(-0.953339, -179.938736, -0.985474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6442.36851562, 4353.77882812, 171.44076172), 'rotation':(-0.936737, -179.941376, -0.967743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6458.948125, 4353.785625, 171.71089844), 'rotation':(-0.93219, -179.93721, -0.962921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6464.47449219, 4353.78613281, 171.80056641), 'rotation':(-0.930115, -179.941605, -0.960663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6481.05359375, 4353.84226562, 172.06849609), 'rotation':(-0.92334, -179.941818, -0.953461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6486.57996094, 4353.84667969, 172.15742188000002), 'rotation':(-0.921112, -179.941895, -0.95108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.10632812, 4353.85109375, 172.24623047), 'rotation':(-0.921112, -179.941895, -0.95108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6342.89046875, 4362.0815625, 169.78683593999997), 'rotation':(0.967633, 0.061036, 0.935352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6348.416875, 4362.0859375, 169.88019531), 'rotation':(0.965864, 0.059798, 0.933705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6353.94324219, 4362.0903125, 169.97345703), 'rotation':(0.965864, 0.059798, 0.933705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6359.46914062, 4362.09472656, 170.06658202999998), 'rotation':(0.962353, 0.063307, 0.930425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6387.1009375, 4362.11671875, 170.52855469), 'rotation':(0.953474, 0.061266, 0.922122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6392.62734375, 4362.120625, 170.62054688), 'rotation':(0.953337, 0.061259, 0.921992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6431.31042969, 4362.15085938, 171.25990234), 'rotation':(0.937874, 0.058682, 0.90753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6442.36316406, 4362.1596875, 171.44078125), 'rotation':(0.934479, 0.05853, 0.90437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6453.41589844, 4362.1684375, 171.62103516), 'rotation':(0.930094, 0.058392, 0.900258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6458.94273438, 4362.1753125, 171.71089844), 'rotation':(0.930094, 0.058392, 0.900258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6464.46914062, 4362.18359375, 171.80058594), 'rotation':(0.927792, 0.058319, 0.898103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6469.995, 4362.19140625, 171.89007812), 'rotation':(0.925641, 0.062578, 0.896079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6475.521875, 4362.16601562, 171.97939452999998), 'rotation':(0.923257, 0.058167, 0.893866), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6481.04820312, 4362.15671875, 172.06851562), 'rotation':(0.921174, 0.058107, 0.891898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.1009375, 4362.16554688, 172.24626952999998), 'rotation':(0.920129, 0.062201, 0.890918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6547.13609375, 4362.24171875, 173.12669922), 'rotation':(0.91071, 0.06032, 0.882082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6569.73328125, 4362.25929688, 173.48521484), 'rotation':(0.904474, 0.060129, 0.876239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6575.38269531, 4362.26414062, 173.57449218999997), 'rotation':(0.902685, 0.055482, 0.874564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6592.33046875, 4362.27734375, 173.84158202999998), 'rotation':(0.901892, 0.057749, 0.873825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.62929688, 4362.28613281, 174.01949219), 'rotation':(0.901284, 0.059203, 0.873243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6631.87488281, 4362.308125, 174.46314453), 'rotation':(0.899065, 0.056447, 0.871168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6637.52476562, 4362.3125, 174.55185547000002), 'rotation':(0.898559, 0.059567, 0.870685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6648.82265625, 4362.32128906, 174.72908203), 'rotation':(0.897412, 0.059529, 0.869623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6654.47253906, 4362.32570312, 174.81759766), 'rotation':(0.896189, 0.059492, 0.868465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.77085938, 4362.33445312, 174.99443359), 'rotation':(0.895042, 0.056426, 0.867399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6682.71863281, 4362.35890625, 175.25921875), 'rotation':(0.894557, 0.060079, 0.866946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6705.31628906, 4362.3325, 175.611875), 'rotation':(0.892282, 0.057494, 0.864805), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.61511719, 4362.34132812, 175.78789061999998), 'rotation':(0.891558, 0.057473, 0.864114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6722.26453125, 4362.34570312, 175.87580078), 'rotation':(0.890984, 0.060491, 0.863589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6727.91394531, 4362.35007812, 175.96369141), 'rotation':(0.891107, 0.056253, 0.863718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.56335938, 4362.35449219, 176.05158203), 'rotation':(0.891046, 0.060498, 0.863648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6739.21228516, 4362.35890625, 176.13945311999998), 'rotation':(0.890984, 0.060491, 0.863589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6744.8621875, 4362.36328125, 176.22734375), 'rotation':(0.890984, 0.060491, 0.863589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6750.51111328, 4362.36765625, 176.31521484), 'rotation':(0.890513, 0.055125, 0.863154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6524.54382812, 4353.84328125, 172.76609375), 'rotation':(-0.914703, -179.940552, -0.944275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6535.8421875, 4353.85203125, 172.94652344), 'rotation':(-0.914764, -179.940552, -0.944336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6547.14, 4353.86085938, 173.12666016), 'rotation':(-0.912354, -179.939621, -0.941772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.78945312, 4353.86523438, 173.21650391), 'rotation':(-0.910706, -179.939667, -0.940002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.43882812, 4353.86960938, 173.30621093999997), 'rotation':(-0.90921, -179.944305, -0.938416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6575.38609375, 4353.88328125, 173.57445312), 'rotation':(-0.904388, -179.93988, -0.933319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6581.03601562, 4353.88769531, 173.66357422000002), 'rotation':(-0.904388, -179.93988, -0.933319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6592.334375, 4353.89648438, 173.84154297), 'rotation':(-0.902008, -179.942245, -0.930756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6597.98328125, 4353.90085938, 173.93048828), 'rotation':(-0.901886, -179.942245, -0.930634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6609.28113281, 4353.9096875, 174.10830077999998), 'rotation':(-0.901337, -179.940781, -0.930054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6626.229375, 4353.92285156, 174.37443359), 'rotation':(-0.899078, -179.943558, -0.927643), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6631.87828125, 4353.92726562, 174.463125), 'rotation':(-0.8992, -179.938843, -0.927795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6648.82605469, 4353.94042969, 174.72902344), 'rotation':(-0.89856, -179.94043, -0.927094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6654.4759375, 4353.94484375, 174.81755859), 'rotation':(-0.8974, -179.94046, -0.925873), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.77429688, 4353.94382812, 174.994375), 'rotation':(-0.896149, -179.940506, -0.9245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6671.42371094, 4353.97753906, 175.08269531000002), 'rotation':(-0.89505, -179.940552, -0.92334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6699.67029297, 4354.01320312, 175.52373047), 'rotation':(-0.894043, -179.942444, -0.922302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6710.96863281, 4354.02246094, 175.69984375), 'rotation':(-0.892273, -179.942505, -0.92041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.21521484, 4354.04445312, 176.13939453), 'rotation':(-0.890991, -179.943741, -0.919006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6744.86462891, 4354.04882812, 176.22728515999998), 'rotation':(-0.890991, -179.943741, -0.919006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6756.16345703, 4354.05761719, 176.40294922), 'rotation':(-0.890533, -179.944855, -0.918549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6794.26257812, 4354.05421875, 176.99410156000002), 'rotation':(-0.888733, -179.937698, -0.916626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6805.57507812, 4354.06296875, 177.16933594), 'rotation':(-0.887634, -179.942413, -0.915466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6811.23181641, 4354.06789062, 177.25677734), 'rotation':(-0.885651, -179.94249, -0.913361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6816.88806641, 4354.07226562, 177.34414062), 'rotation':(-0.884583, -179.941406, -0.912231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6822.54529297, 4354.07664062, 177.43148438), 'rotation':(-0.884583, -179.941406, -0.912231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.85828125, 4354.08546875, 177.60621093999998), 'rotation':(-0.884491, -179.941406, -0.91214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6845.17175781, 4354.09421875, 177.7809375), 'rotation':(-0.884644, -179.941406, -0.912292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6856.48474609, 4354.10304688, 177.95539062), 'rotation':(-0.882538, -179.944473, -0.910034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6862.14099609, 4354.10742188, 178.04248047000002), 'rotation':(-0.881897, -179.940582, -0.909363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6867.79822266, 4354.11179688, 178.12957031000002), 'rotation':(-0.881897, -179.940582, -0.909363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6884.76794922, 4354.125, 178.39087891), 'rotation':(-0.881927, -179.943436, -0.909424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6930.02136719, 4354.1528125, 179.08570312), 'rotation':(-0.878174, -179.940643, -0.905426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.33484375, 4354.19726562, 179.25916016), 'rotation':(-0.878326, -179.940643, -0.905579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.27478516, 4354.22898438, 179.77835938), 'rotation':(-0.875732, -179.940552, -0.902832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.58777344, 4354.2378125, 179.95130859), 'rotation':(-0.87558, -179.943832, -0.902679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6997.90125, 4354.2465625, 180.12419922), 'rotation':(-0.875397, -179.940216, -0.902466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(7003.15027344, 4354.25097656, 180.20431641), 'rotation':(-0.87442, -179.944473, -0.901428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7009.21472656, 4354.08546875, 180.29683594), 'rotation':(-0.873932, -179.940063, -0.900909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6805.57458984, 4362.44382812, 177.16941406), 'rotation':(0.885643, 0.057511, 0.858571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6828.20154297, 4362.46191406, 177.51894531000002), 'rotation':(0.884482, 0.058582, 0.857479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.85828125, 4362.46632812, 177.60630859), 'rotation':(0.884585, 0.058585, 0.857573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6845.17175781, 4362.47507812, 177.78103516), 'rotation':(0.883997, 0.060811, 0.857016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6850.82800781, 4362.47949219, 177.86833984), 'rotation':(0.882501, 0.055521, 0.85564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.48474609, 4362.48390625, 177.95548828), 'rotation':(0.881948, 0.059422, 0.855086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6884.76794922, 4362.50585938, 178.39097656), 'rotation':(0.881948, 0.059422, 0.855086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6907.39441406, 4362.5234375, 178.73886718999998), 'rotation':(0.878294, 0.059349, 0.851666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6918.70837891, 4362.53222656, 178.91234375), 'rotation':(0.878192, 0.059346, 0.851576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.33533203, 4362.5503125, 179.25925781), 'rotation':(0.877618, 0.056289, 0.851035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6952.64832031, 4362.56054688, 179.43248047), 'rotation':(0.875644, 0.056155, 0.849176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6958.30505859, 4362.56984375, 179.51900390999998), 'rotation':(0.875644, 0.056155, 0.849176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6963.96179688, 4362.55761719, 179.60550781), 'rotation':(0.875746, 0.059447, 0.849275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6980.93152344, 4362.54835938, 179.86492188), 'rotation':(0.875644, 0.056155, 0.849176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6992.245, 4362.55710938, 180.03787109), 'rotation':(0.875337, 0.059766, 0.848893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6997.90222656, 4362.56152344, 180.12429688), 'rotation':(0.874414, 0.055523, 0.84802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7003.55798828, 4362.73632812, 180.210625), 'rotation':(0.873991, 0.05993, 0.847626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(7009.21521484, 4362.74023438, 180.29697266), 'rotation':(0.87393, 0.059928, 0.847559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6067.47203125, 4504.37890625, 166.31103516), 'rotation':(-1.068604, -179.913712, -1.109039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6056.66, 4504.3671875, 166.10931641), 'rotation':(-1.068512, -179.916733, -1.108948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6045.84703125, 4504.355, 165.90753906), 'rotation':(-1.068604, -179.916718, -1.109039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6035.0340625, 4504.34328125, 165.70587891), 'rotation':(-1.066284, -179.916092, -1.106567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6029.6278125, 4504.33691406, 165.6053125), 'rotation':(-1.062286, -179.916245, -1.102264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.2215625, 4504.33105469, 165.50509766), 'rotation':(-1.060059, -179.916382, -1.099854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6003.09507812, 4504.30710938, 165.10505859), 'rotation':(-1.05368, -179.921432, -1.092957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6007.98625, 4512.69382812, 165.20480468999997), 'rotation':(1.060148, 0.083626, 1.02146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.20546875, 4512.71191406, 165.50498047000002), 'rotation':(1.062292, 0.083761, 1.023418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6035.0175, 4512.72414062, 165.70574219), 'rotation':(1.06859, 0.083274, 1.029271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6045.83, 4512.73585938, 165.90740234), 'rotation':(1.068487, 0.08327, 1.029184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6051.23625, 4512.74171875, 166.00828125), 'rotation':(1.06859, 0.08629, 1.029271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6056.6425, 4512.74804688, 166.10914062), 'rotation':(1.06859, 0.08629, 1.029271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6304.46375, 4513.07078125, 170.65865234), 'rotation':(1.000438, 0.078703, 0.965943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.40953125, 4513.00488281, 170.35941406), 'rotation':(1.009878, 0.08053, 0.974739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6276.03796875, 4512.9921875, 170.15810547), 'rotation':(1.017555, 0.080804, 0.981883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.35242188, 4512.98585938, 170.05689453), 'rotation':(1.021407, 0.085771, 0.985467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6264.66640625, 4512.97949219, 169.95529297000002), 'rotation':(1.021407, 0.085771, 0.985467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6258.9803125, 4512.973125, 169.85333984000002), 'rotation':(1.02517, 0.081081, 0.988966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6236.23867188, 4512.94824219, 169.443125), 'rotation':(1.037444, 0.082082, 1.000369), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6230.55265625, 4512.941875, 169.33990234), 'rotation':(1.040081, 0.08218, 1.002812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.8665625, 4512.93554688, 169.23642578), 'rotation':(1.042813, 0.082286, 1.005345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6207.80992188, 4512.91648438, 168.92435547000002), 'rotation':(1.050708, 0.082572, 1.012687), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6196.43835938, 4512.90382812, 168.71550781000002), 'rotation':(1.051713, 0.08542, 1.013617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6179.38171875, 4512.88429688, 168.40125), 'rotation':(1.056938, 0.083804, 1.01846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6116.83921875, 4512.81492188, 167.23599609000001), 'rotation':(1.072852, 0.087061, 1.033222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6105.42125, 4504.34472656, 167.02169922000002), 'rotation':(-1.074677, -179.914917, -1.11557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6111.10195312, 4504.42726562, 167.12826172), 'rotation':(-1.074493, -179.914917, -1.115417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6116.78796875, 4504.4340625, 167.23484375), 'rotation':(-1.074158, -179.918045, -1.11499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6145.21617188, 4504.46582031, 167.76603516), 'rotation':(-1.067566, -179.913147, -1.10791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6173.644375, 4504.49707031, 168.29484375), 'rotation':(-1.063904, -179.915939, -1.103973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.01648438, 4504.50976562, 168.50511719), 'rotation':(-1.056946, -179.916199, -1.096497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6190.7015625, 4504.51609375, 168.60984375), 'rotation':(-1.056946, -179.916199, -1.096497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6196.38757812, 4504.52296875, 168.71439453), 'rotation':(-1.053711, -179.92009, -1.093018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6202.073125, 4504.52929688, 168.81880859), 'rotation':(-1.051727, -179.914581, -1.090881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6213.4446875, 4504.53417969, 169.02757812), 'rotation':(-1.05072, -179.917435, -1.089813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6219.13078125, 4504.56152344, 169.13160156), 'rotation':(-1.047821, -179.912262, -1.0867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.81625, 4504.58398438, 169.23535156000003), 'rotation':(-1.045197, -179.917633, -1.083862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6258.9315625, 4504.62546875, 169.85228515999998), 'rotation':(-1.029022, -179.918777, -1.066498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.30265625, 4504.63820312, 170.05583984), 'rotation':(-1.025177, -179.918915, -1.062378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6275.98914062, 4504.64453125, 170.15707031000002), 'rotation':(-1.021393, -179.91423, -1.058319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6281.67421875, 4504.65085938, 170.25791016), 'rotation':(-1.017548, -179.919189, -1.054199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6293.04578125, 4504.66359375, 170.45849609), 'rotation':(-1.009888, -179.919464, -1.045959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6298.73234375, 4504.66992188, 170.55824219), 'rotation':(-1.006195, -179.914764, -1.042023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6304.41835938, 4504.50585938, 170.65767577999998), 'rotation':(-1.002289, -179.919724, -1.037811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6041.178125, 4758.28125, 167.32857422), 'rotation':(-1.129364, -179.625763, -1.174591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6035.66835938, 4758.24707031, 167.21992188000002), 'rotation':(-1.129364, -179.625763, -1.174591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.64882812, 4758.1796875, 167.00261719), 'rotation':(-1.129333, -179.628769, -1.17453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6019.1390625, 4758.14599609, 166.89392578), 'rotation':(-1.129333, -179.628769, -1.17453), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.62828125, 4758.11230469, 166.78523438), 'rotation':(-1.130219, -179.627686, -1.175476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6057.66296875, 4766.76269531, 167.65451172000002), 'rotation':(1.125772, 0.373616, 1.08216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6046.64882812, 4766.6953125, 167.43746094), 'rotation':(1.128115, 0.370702, 1.084327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6030.12828125, 4766.59423828, 167.11166015999999), 'rotation':(1.129372, 0.371208, 1.08547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6024.62195312, 4766.56054688, 167.00306641), 'rotation':(1.129426, 0.37426, 1.08553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.60828125, 4766.49316406, 166.78585938), 'rotation':(1.129276, 0.374237, 1.085384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6008.10140625, 4766.45947266, 166.67720702999998), 'rotation':(1.129276, 0.374237, 1.085384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6002.59460938, 4766.42578125, 166.56849609), 'rotation':(1.130212, 0.372307, 1.086253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6101.17375, 4758.6484375, 168.50742188), 'rotation':(-1.12027, -179.627975, -1.164764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6106.85679688, 4758.68310547, 168.61839844), 'rotation':(-1.12027, -179.627975, -1.164764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6112.54039062, 4758.71777344, 168.72927734), 'rotation':(-1.117462, -179.628067, -1.161713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6123.90710938, 4758.78710938, 168.95037109), 'rotation':(-1.114746, -179.624924, -1.158783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6135.27429688, 4758.85693359, 169.1709375), 'rotation':(-1.110443, -179.628799, -1.154144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6163.69179688, 4759.03027344, 169.71953125), 'rotation':(-1.099915, -179.629242, -1.142761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6169.37484375, 4759.06542969, 169.8284375), 'rotation':(-1.099915, -179.629242, -1.142761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6186.4246875, 4759.16992188, 170.15419922), 'rotation':(-1.093475, -179.626938, -1.135834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6192.1078125, 4759.20458984, 170.26257812), 'rotation':(-1.093475, -179.626938, -1.135834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6203.4759375, 4759.26806641, 170.47857422), 'rotation':(-1.085205, -179.631012, -1.126923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6209.15953125, 4759.31884766, 170.58609375), 'rotation':(-1.085205, -179.631012, -1.126923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6226.209375, 4759.44628906, 170.9065625), 'rotation':(-1.074341, -179.628342, -1.115204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6231.89296875, 4759.48095703, 171.01292969), 'rotation':(-1.071472, -179.631729, -1.112152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6243.2596875, 4759.55078125, 171.22539061999998), 'rotation':(-1.071564, -179.627563, -1.112244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6248.94328125, 4759.58544922, 171.33136718999998), 'rotation':(-1.068817, -179.628174, -1.109253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6254.62734375, 4759.62060547, 171.43689453), 'rotation':(-1.063171, -179.631439, -1.10321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6260.3109375, 4759.65478516, 171.54208984000002), 'rotation':(-1.063171, -179.631439, -1.10321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6265.9940625, 4759.68994141, 171.64705078), 'rotation':(-1.057678, -179.628571, -1.097321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6271.67765625, 4759.72460938, 171.75148438), 'rotation':(-1.052002, -179.631851, -1.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6277.3621875, 4759.75927734, 171.85582031), 'rotation':(-1.052002, -179.631851, -1.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6288.72890625, 4759.82910156, 172.06400391), 'rotation':(-1.049286, -179.627747, -1.088257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6294.41296875, 4759.86376953, 172.16777344), 'rotation':(-1.046967, -179.632141, -1.085754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6305.78945312, 4768.28125, 172.37519531), 'rotation':(1.034446, 0.372096, 0.997576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6260.3196875, 4768.00244141, 171.54320312), 'rotation':(1.057627, 0.368345, 1.019114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6243.26890625, 4767.89892578, 171.22652344), 'rotation':(1.068802, 0.371824, 1.029465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6237.58632812, 4767.86376953, 171.12041016), 'rotation':(1.068802, 0.371824, 1.029465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6226.21859375, 4767.79443359, 170.90769531), 'rotation':(1.071493, 0.372413, 1.031957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6220.535, 4767.75976562, 170.80113281), 'rotation':(1.074327, 0.368568, 1.034592), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6203.48476562, 4767.65527344, 170.47970703), 'rotation':(1.079805, 0.371861, 1.039665), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6192.11757812, 4767.5859375, 170.26373047), 'rotation':(1.090774, 0.372277, 1.04982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6180.75039062, 4767.51611328, 170.04683594), 'rotation':(1.093547, 0.369131, 1.052382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6175.06679688, 4767.48144531, 169.93830078), 'rotation':(1.093431, 0.373083, 1.052268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6152.33289062, 4767.34228516, 169.50197265999998), 'rotation':(1.104168, 0.370916, 1.062198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6123.916875, 4767.16845703, 168.9515625), 'rotation':(1.111886, 0.371684, 1.069342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6112.5496875, 4767.09863281, 168.73044922), 'rotation':(1.114817, 0.371817, 1.072043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6449.0140625, 4769.15771484, 174.86367188), 'rotation':(0.949478, 0.365604, 0.918399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6443.47695312, 4769.12402344, 174.77144531000002), 'rotation':(0.953952, 0.365754, 0.92257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6426.86707031, 4769.02246094, 174.49273438), 'rotation':(0.963139, 0.366061, 0.931153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6399.18152344, 4768.85302734, 174.02111327999998), 'rotation':(0.981614, 0.368103, 0.948394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6388.1078125, 4768.78515625, 173.82998047), 'rotation':(0.988875, 0.368354, 0.955159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6382.57117188, 4768.75146484, 173.73396484), 'rotation':(0.99242, 0.368475, 0.958468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6371.49792969, 4768.68359375, 173.54164062), 'rotation':(0.994079, 0.367751, 0.960025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6365.96082031, 4768.64941406, 173.44521484), 'rotation':(0.997467, 0.369538, 0.963175), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6360.42273438, 4768.61572266, 173.34824218999998), 'rotation':(1.003812, 0.366372, 0.969086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6343.81234375, 4768.51367188, 173.05507812), 'rotation':(1.016701, 0.366832, 0.981077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.31335938, 4760.98095703, 175.40998047000002), 'rotation':(-0.931, -179.634995, -0.961639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6476.77527344, 4760.94677734, 175.31986328), 'rotation':(-0.935669, -179.634872, -0.966583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6438.00964844, 4760.70947266, 174.67916015999998), 'rotation':(-0.963074, -179.633972, -0.99588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6426.93542969, 4760.64160156, 174.49302734), 'rotation':(-0.967285, -179.632385, -1.000336), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6415.85925781, 4760.57373047, 174.30541015999998), 'rotation':(-0.974365, -179.632141, -1.007935), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6410.32164062, 4760.54003906, 174.21107422), 'rotation':(-0.978058, -179.632019, -1.011902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6404.7840625, 4760.50585938, 174.11638672), 'rotation':(-0.981628, -179.631897, -1.015686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6399.24597656, 4760.47216797, 174.02132812), 'rotation':(-0.985168, -179.631775, -1.019501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6382.63320312, 4760.37060547, 173.73414062), 'rotation':(-0.994232, -179.632248, -1.029205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6377.09558594, 4760.33642578, 173.63802734), 'rotation':(-0.99408, -179.632248, -1.029053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6366.02039062, 4760.26904297, 173.44535156), 'rotation':(-1.003815, -179.630234, -1.039459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6360.4828125, 4760.23535156, 173.34839843999998), 'rotation':(-1.010284, -179.633392, -1.046387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6354.94519531, 4760.20117188, 173.25109375), 'rotation':(-1.010284, -179.633392, -1.046387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6349.40710938, 4760.16748047, 173.15341797000002), 'rotation':(-1.016632, -179.629807, -1.053223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6343.86953125, 4760.13330078, 173.05519531000002), 'rotation':(-1.019897, -179.631912, -1.056732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6338.33289062, 4760.09960938, 172.95679688), 'rotation':(-1.019897, -179.631912, -1.056732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.280625, 4378.453125, 172.71128906), 'rotation':(0.595797, 90.888573, 0.583506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.11070312, 4389.50683594, 172.82619140999998), 'rotation':(0.593373, 90.887482, 0.581179), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.9403125, 4400.56007812, 172.94027343999997), 'rotation':(0.584084, 90.887283, 0.572257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.85535156, 4406.08742188, 172.99679688), 'rotation':(0.584084, 90.887283, 0.572257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.77039062, 4411.61476562, 173.05300781000003), 'rotation':(0.579405, 90.88726, 0.567773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.68542969, 4417.14109375, 173.10890625), 'rotation':(0.577151, 90.886726, 0.565611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6502.60046875, 4422.6684375, 173.16458984000002), 'rotation':(0.577151, 90.886726, 0.565611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.34507812, 4439.24851562, 173.33154297000002), 'rotation':(0.57377, 90.889389, 0.562372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.08972656, 4455.82960938, 173.49585938), 'rotation':(0.554686, 90.889023, 0.544016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.00429688, 4461.35644531, 173.54960938), 'rotation':(0.551422, 90.887291, 0.540879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.91929688, 4466.88328125, 173.60298827999998), 'rotation':(0.551422, 90.887291, 0.540879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.834375, 4472.410625, 173.65621094), 'rotation':(0.551422, 90.887291, 0.540879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.57898438, 4488.99070312, 173.81478515999999), 'rotation':(0.539284, 90.890831, 0.529199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.40859375, 4500.04492188, 173.91832031), 'rotation':(0.529524, 90.885674, 0.519807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.23816406, 4511.09863281, 174.01998047), 'rotation':(0.519825, 90.890488, 0.51046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.15320312, 4516.62597656, 174.07007812), 'rotation':(0.514921, 90.885323, 0.505739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6500.98328125, 4527.68015625, 174.16919922), 'rotation':(0.508193, 90.88504, 0.499239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6500.89832031, 4533.2065625, 174.21853516), 'rotation':(0.508193, 90.88504, 0.499239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6509.36265625, 4527.81398438, 174.16925781), 'rotation':(-0.512421, -89.112976, -0.521637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6509.61804688, 4511.23339844, 174.02001952999998), 'rotation':(-0.524567, -89.114502, -0.534241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6509.78796875, 4500.1796875, 173.91835938), 'rotation':(-0.534393, -89.114319, -0.544403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.04335938, 4483.598125, 173.76236328), 'rotation':(-0.54892, -89.114044, -0.559509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6510.29871094, 4467.01804688, 173.60304688), 'rotation':(-0.554688, -89.110962, -0.565491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.38367188, 4461.49121094, 173.54964843999997), 'rotation':(-0.554688, -89.110962, -0.565491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.46863281, 4455.964375, 173.49591797000002), 'rotation':(-0.561066, -89.110901, -0.572113), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.72449219, 4439.38429688, 173.33160156000002), 'rotation':(-0.577148, -89.113281, -0.588867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.80945312, 4433.85789062, 173.27601562), 'rotation':(-0.576996, -89.10791, -0.588684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6510.89441406, 4428.33105469, 173.22033202999998), 'rotation':(-0.577209, -89.11322, -0.588928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6510.97984375, 4422.80371094, 173.16464843999998), 'rotation':(-0.577148, -89.113281, -0.588867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6511.3196875, 4400.69578125, 172.94033202999998), 'rotation':(-0.588837, -89.108673, -0.601013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6511.4046875, 4395.16945312, 172.88353515999998), 'rotation':(-0.593384, -89.112518, -0.605774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6511.49011719, 4389.64210938, 172.82626953), 'rotation':(-0.595795, -89.11142, -0.608307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6511.745, 4373.08984375, 172.65416016), 'rotation':(-0.537079, -89.994965, -0.547211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6500.22839844, 4576.67578125, 174.58570312), 'rotation':(0.461325, 90.888329, 0.453948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.803125, 4604.30371094, 174.80226562), 'rotation':(0.419872, 90.884918, 0.413752), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.63320312, 4615.35546875, 174.88388672000002), 'rotation':(0.412871, 90.885071, 0.406957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.54820312, 4620.88085938, 174.92392578), 'rotation':(0.412871, 90.885071, 0.406957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.46277344, 4626.40578125, 174.96369141), 'rotation':(0.405139, 90.884216, 0.39945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.3778125, 4631.93210938, 175.00279297), 'rotation':(0.389512, 90.886841, 0.384237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.29285156, 4637.45800781, 175.04140625), 'rotation':(0.389512, 90.886841, 0.384237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.20789062, 4642.984375, 175.07896484), 'rotation':(0.373809, 90.883774, 0.368968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.12292969, 4648.50878906, 175.11568359), 'rotation':(0.373809, 90.883774, 0.368968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.03796875, 4654.03515625, 175.15175781000002), 'rotation':(0.358196, 90.883606, 0.35374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.9525, 4659.56101562, 175.18660156), 'rotation':(0.358196, 90.883606, 0.35374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.86757812, 4665.0859375, 175.22111328), 'rotation':(0.350259, 90.8871, 0.345995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.69714844, 4676.13818359, 175.28871094), 'rotation':(0.342029, 90.88459, 0.337964), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.44226562, 4692.71630859, 175.38546875), 'rotation':(0.308677, 90.88427, 0.305357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.35730469, 4698.24121094, 175.415625), 'rotation':(0.308677, 90.88427, 0.305357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.186875, 4709.29296875, 175.47332031000002), 'rotation':(0.283753, 90.883087, 0.280941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.10195312, 4714.81835938, 175.50105469), 'rotation':(0.283753, 90.883087, 0.280941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.01695312, 4720.34472656, 175.52841797000002), 'rotation':(0.283753, 90.883087, 0.280941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.93152344, 4725.87158203, 175.55578125), 'rotation':(0.275489, 90.881744, 0.272849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6497.8465625, 4731.39648438, 175.58244141), 'rotation':(0.259076, 90.885544, 0.25674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6497.59167969, 4747.97363281, 175.65587890999998), 'rotation':(0.226387, 90.885262, 0.2246), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6508.6078125, 4576.80515625, 174.58570312), 'rotation':(-0.468262, -89.115265, -0.475952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6508.43789062, 4587.855, 174.67453125), 'rotation':(-0.461334, -89.111633, -0.468811), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6507.92761719, 4621.01023438, 174.92392578), 'rotation':(-0.419861, -89.115082, -0.426056), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.8421875, 4626.53515625, 174.96369141), 'rotation':(-0.412872, -89.114929, -0.418854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.7571875, 4632.06152344, 175.00279297), 'rotation':(-0.405151, -89.115784, -0.410919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.67226562, 4637.58691406, 175.04140625), 'rotation':(-0.405151, -89.115784, -0.410919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.58726562, 4643.11375, 175.07898438), 'rotation':(-0.389496, -89.113159, -0.394836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.50234375, 4648.63867188, 175.11568359), 'rotation':(-0.389496, -89.113159, -0.394836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.33191406, 4659.69042969, 175.18660156), 'rotation':(-0.37381, -89.116211, -0.378723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.24695312, 4665.2153125, 175.22111328), 'rotation':(-0.358215, -89.116394, -0.362701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.16148438, 4670.74171875, 175.25492188), 'rotation':(-0.350281, -89.112915, -0.354584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.0765625, 4676.26806641, 175.28871094), 'rotation':(-0.350403, -89.117828, -0.354736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.82164062, 4692.84570312, 175.38548828), 'rotation':(-0.325348, -89.115601, -0.329041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.73671875, 4698.37060547, 175.415625), 'rotation':(-0.325348, -89.115601, -0.329041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.48132812, 4714.94775391, 175.50105469), 'rotation':(-0.291992, -89.115906, -0.294983), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6506.3109375, 4726.00048828, 175.55578125), 'rotation':(-0.283752, -89.116821, -0.286591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6506.05554688, 4742.57763672, 175.63253906000003), 'rotation':(-0.259094, -89.114441, -0.261444), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6505.97058594, 4748.10253906, 175.65587890999998), 'rotation':(-0.242798, -89.11853, -0.244843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.93007812, 5050.69238281, 175.70142578), 'rotation':(-0.211151, 90.882355, -0.212708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.10339844, 5039.42871094, 175.74013672), 'rotation':(-0.190063, 90.882202, -0.191315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.27722656, 5028.16503906, 175.77576172000002), 'rotation':(-0.175751, 90.882111, -0.176819), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.45054688, 5016.90332031, 175.80826172000002), 'rotation':(-0.161652, 90.882095, -0.162567), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.53699219, 5011.27148438, 175.82380859), 'rotation':(-0.158173, 90.881248, -0.159058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.7103125, 5000.00830078, 175.85386719), 'rotation':(-0.150238, 90.88121, -0.151031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.88367188, 4988.74560547, 175.88027344), 'rotation':(-0.134338, 90.881165, -0.134979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6494.0575, 4977.48193359, 175.90251952999998), 'rotation':(-0.118439, 90.884232, -0.118927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.49109375, 4949.32470703, 175.94890625), 'rotation':(-0.084656, 90.881088, -0.0849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.66445312, 4938.06298828, 175.95941406000003), 'rotation':(-0.044556, 90.88102, -0.044647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.75085938, 4932.43261719, 175.96162109), 'rotation':(-0.02478, 90.880898, -0.02478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.83777344, 4926.80029297, 175.96306640999998), 'rotation':(-0.014862, 90.884415, -0.014862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.01109375, 4915.53613281, 175.96597656000003), 'rotation':(-0.014862, 90.884346, -0.014893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.18445312, 4904.27197266, 175.96886718999997), 'rotation':(-0.014862, 90.884346, -0.014893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.4446875, 4887.37792969, 175.97220703), 'rotation':(-0.014709, 90.884346, -0.014709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.53164062, 4881.74755859, 175.97064453), 'rotation':(0.003907, 90.881714, 0.003894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.70496094, 4870.48535156, 175.96048828), 'rotation':(0.060215, 90.880844, 0.060091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.87878906, 4859.22119141, 175.94867188), 'rotation':(0.060208, 90.885719, 0.060089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.96523438, 4853.59033203, 175.94275391), 'rotation':(0.060215, 90.880844, 0.060091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6496.13855469, 4842.32714844, 175.92818359), 'rotation':(0.068739, 90.883568, 0.068579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6496.22546875, 4836.69580078, 175.91933594), 'rotation':(0.086067, 90.879982, 0.085806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.74546875, 4802.91015625, 175.84357422000002), 'rotation':(0.150961, 90.881088, 0.150164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6505.47203125, 4780.51074219, 175.77521484000002), 'rotation':(-0.194916, -89.113403, -0.196228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6505.29820312, 4791.77441406, 175.81117188), 'rotation':(-0.177338, -89.118774, -0.178467), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.69128906, 4831.19287109, 175.90919922), 'rotation':(-0.120483, -89.116272, -0.121002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.43152344, 4848.08740234, 175.93599609), 'rotation':(-0.08606, -89.119995, -0.086304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.34507812, 4853.71972656, 175.94275391), 'rotation':(-0.068756, -89.116425, -0.068909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6504.17125, 4864.98242188, 175.95457031), 'rotation':(-0.060242, -89.114258, -0.060333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6504.084375, 4870.61474609, 175.96048828), 'rotation':(-0.060211, -89.119141, -0.060333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.99742188, 4876.24609375, 175.96640625), 'rotation':(-0.060211, -89.119141, -0.060333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6503.91101562, 4881.87646484, 175.97064453), 'rotation':(-0.041534, -89.118317, -0.041565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.82410156, 4887.50683594, 175.97220703), 'rotation':(-0.003906, -89.118286, -0.003906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.47742188, 4910.03369141, 175.96742188), 'rotation':(0.014869, -89.115662, 0.014858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.30359375, 4921.29785156, 175.96453125), 'rotation':(0.014869, -89.115662, 0.014858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.2171875, 4926.9296875, 175.96306640999998), 'rotation':(0.014712, -89.120758, 0.014697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6503.04382812, 4938.19189453, 175.95941406000003), 'rotation':(0.024766, -89.118988, 0.024755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6502.95691406, 4943.82324219, 175.95529297000002), 'rotation':(0.044546, -89.113556, 0.044488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.87046875, 4949.45361328, 175.94890625), 'rotation':(0.064696, -89.118958, 0.064547), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.69714844, 4960.71679688, 175.93113281), 'rotation':(0.094632, -89.118835, 0.094328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.52332031, 4971.98046875, 175.91253906000003), 'rotation':(0.094537, -89.115753, 0.094237), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.35, 4983.2421875, 175.89191406), 'rotation':(0.102555, -89.118958, 0.102185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.17664062, 4994.50585938, 175.86742188), 'rotation':(0.13435, -89.118805, 0.133719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.08972656, 5000.13720703, 175.85386719), 'rotation':(0.13435, -89.118805, 0.133719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6502.00328125, 5005.76904297, 175.83910156000002), 'rotation':(0.15023, -89.118774, 0.149456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.91640625, 5011.40039062, 175.82380859), 'rotation':(0.158194, -89.113098, 0.157321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.82996094, 5017.03222656, 175.80826172000002), 'rotation':(0.158194, -89.118652, 0.15732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.74304688, 5022.66308594, 175.79238281000002), 'rotation':(0.161623, -89.11795, 0.160718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.65664062, 5028.29394531, 175.77576172000002), 'rotation':(0.168774, -89.11792, 0.167779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6501.39636719, 5045.18945312, 175.72117188), 'rotation':(0.190036, -89.117798, 0.188785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.30945312, 5050.82128906, 175.70142578), 'rotation':(0.20399, -89.117676, 0.202541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6501.22253906, 5056.453125, 175.68091797), 'rotation':(0.211142, -89.117645, 0.209584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.5540625, 5204.99560547, 174.96708984), 'rotation':(-0.326263, 90.882492, -0.329987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.89539062, 5182.84375, 175.09113281), 'rotation':(-0.316528, 90.882408, -0.320038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.06578125, 5171.76806641, 175.1509375), 'rotation':(-0.31012, 90.885262, -0.313477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.40664062, 5149.61621094, 175.26728516), 'rotation':(-0.298309, 90.883759, -0.301422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.49207031, 5144.07861328, 175.29558594), 'rotation':(-0.293396, 90.883705, -0.296417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.6625, 5133.00244141, 175.35078125), 'rotation':(-0.28421, 90.883606, -0.287018), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.74792969, 5127.46484375, 175.37769531), 'rotation':(-0.279449, 90.883575, -0.282196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.83335938, 5121.92675781, 175.40412109000002), 'rotation':(-0.274841, 90.883522, -0.277496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.91835938, 5116.38916016, 175.43007812), 'rotation':(-0.270111, 90.883484, -0.272644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.00378906, 5110.85107422, 175.45566406), 'rotation':(-0.265503, 90.883438, -0.267975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.0965625, 5099.77539062, 175.50605468999998), 'rotation':(-0.260071, 90.881821, -0.262451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6492.13074219, 5094.23535156, 175.53042968999998), 'rotation':(-0.253723, 90.881851, -0.255981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6500.38320312, 5110.97753906, 175.45566406), 'rotation':(0.263072, -89.115845, 0.260663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.87148438, 5144.20507812, 175.29558594), 'rotation':(0.288828, -89.116272, 0.285926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6499.36023438, 5177.43212891, 175.12113281), 'rotation':(0.303732, -89.117706, 0.300517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.27476562, 5182.97021484, 175.09113281), 'rotation':(0.310097, -89.114746, 0.306763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6499.01890625, 5199.58447266, 174.99849609), 'rotation':(0.323, -89.114563, 0.319379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.05507812, 5237.40429688, 174.78121094), 'rotation':(-0.33548, 90.885345, -0.339417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.88171875, 5248.67822266, 174.71509766), 'rotation':(-0.336639, 90.885712, -0.340607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.70789062, 5259.953125, 174.64882812), 'rotation':(-0.336639, 90.880463, -0.340607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.62097656, 5265.58984375, 174.61572266), 'rotation':(-0.33667, 90.886238, -0.340637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.53453125, 5271.22705078, 174.58259766), 'rotation':(-0.33667, 90.882431, -0.340637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.01355469, 5305.05029297, 174.38375), 'rotation':(-0.336823, 90.882576, -0.34082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.57945312, 5333.23632812, 174.21988281000003), 'rotation':(-0.324646, 90.883369, -0.328339), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.405625, 5344.51074219, 174.15574218999998), 'rotation':(-0.322906, 90.884964, -0.326569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.31921875, 5350.14796875, 174.12392577999998), 'rotation':(-0.322906, 90.884964, -0.326569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.23230469, 5355.7846875, 174.09216797000002), 'rotation':(-0.321289, 90.884514, -0.324921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.14539062, 5361.42285156, 174.06056640999998), 'rotation':(-0.317963, 90.884476, -0.321503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.05898438, 5367.06054688, 174.02931640999998), 'rotation':(-0.314972, 90.884521, -0.318451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.79820312, 5383.9721875, 173.93759766), 'rotation':(-0.305084, 90.884331, -0.30835), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.71132812, 5389.60984375, 173.90771484), 'rotation':(-0.30191, 90.8843, -0.305084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6487.624375, 5395.2465625, 173.87816406000002), 'rotation':(-0.297028, 90.881531, -0.30011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.45105469, 5406.52246094, 173.81986328), 'rotation':(-0.289581, 90.884308, -0.292542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6487.10390625, 5429.07179688, 173.7084375), 'rotation':(-0.269684, 90.879395, -0.272217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.01695312, 5434.70898438, 173.68171875), 'rotation':(-0.264801, 90.884087, -0.267273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6486.843125, 5445.984375, 173.62970703), 'rotation':(-0.257263, 90.889008, -0.259613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6486.66980469, 5457.26074219, 173.57919922000002), 'rotation':(-0.248413, 90.882072, -0.25058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6486.58289062, 5462.89890625, 173.55472656), 'rotation':(-0.242737, 90.882095, -0.244812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6486.4090625, 5474.17335938, 173.50763672000002), 'rotation':(-0.230865, 90.887222, -0.232727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6486.23523438, 5485.44773438, 173.46298828), 'rotation':(-0.219116, 90.881912, -0.220795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6485.97449219, 5502.36425781, 173.39998047), 'rotation':(-0.207031, 90.883331, -0.208527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.61460938, 5485.58007812, 173.46298828), 'rotation':(0.224966, -89.118103, 0.223198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6494.78796875, 5474.30566406, 173.50763672000002), 'rotation':(0.2367, -89.11795, 0.234767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.04921875, 5457.39304688, 173.57917969), 'rotation':(0.254459, -89.117798, 0.252213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.13609375, 5451.75539062, 173.60423828), 'rotation':(0.257286, -89.110992, 0.254977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6495.39636719, 5434.84277344, 173.68167968999998), 'rotation':(0.26967, -89.120575, 0.267146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.48328125, 5429.20507812, 173.70839844), 'rotation':(0.274697, -89.115845, 0.272071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.74351562, 5412.2934375, 173.79128906000003), 'rotation':(0.289593, -89.115662, 0.286674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6495.916875, 5401.01757812, 173.84886719), 'rotation':(0.297024, -89.118469, 0.293963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.26453125, 5378.46875, 173.9678125), 'rotation':(0.311429, -89.120941, 0.308067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.52476562, 5361.55664062, 174.06052734000002), 'rotation':(0.321292, -89.115479, 0.317708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6496.78503906, 5344.64453125, 174.15572265999998), 'rotation':(0.324632, -89.116608, 0.320959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.1321875, 5322.09521484, 174.28482422000002), 'rotation':(0.335089, -89.113342, 0.331191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.21914062, 5316.45849609, 174.31761719), 'rotation':(0.335089, -89.113342, 0.331191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.30601562, 5310.82128906, 174.35060547), 'rotation':(0.336824, -89.117432, 0.332885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.65320312, 5288.27246094, 174.48316406), 'rotation':(0.336762, -89.113831, 0.332832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.74011719, 5282.63574219, 174.51628906000002), 'rotation':(0.336667, -89.117554, 0.332732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.82703125, 5276.99804688, 174.54943359), 'rotation':(0.336667, -89.117554, 0.332732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6497.91394531, 5271.36132812, 174.58255859000002), 'rotation':(0.336667, -89.117554, 0.332732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.00039062, 5265.72412109, 174.61568359), 'rotation':(0.33664, -89.114288, 0.332702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6498.08726562, 5260.08691406, 174.64882812), 'rotation':(0.33664, -89.114288, 0.332702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.26109375, 5248.8125, 174.71507812), 'rotation':(0.33664, -89.119537, 0.332705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6498.43445312, 5237.53857422, 174.78117188), 'rotation':(0.333327, -89.114746, 0.329472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6485.30554688, 5545.82859375, 173.26324218999997), 'rotation':(-0.148529, 90.881561, -0.149292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.96523438, 5567.93601562, 173.20773438), 'rotation':(-0.118195, 90.881416, -0.118652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.88023438, 5573.46386719, 173.19597656000002), 'rotation':(-0.118195, 90.881416, -0.118652), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.70984375, 5584.51757812, 173.17457031), 'rotation':(-0.095551, 90.882072, -0.095856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.624375, 5590.04492188, 173.16472656000002), 'rotation':(-0.095551, 90.882072, -0.095856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.45445312, 5601.098125, 173.14628906000002), 'rotation':(-0.095551, 90.882133, -0.095856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.36953125, 5606.62597656, 173.13726562), 'rotation':(-0.086853, 90.88607, -0.087097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.2840625, 5612.15382812, 173.129375), 'rotation':(-0.069214, 90.880829, -0.069397), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6484.19910156, 5617.68066406, 173.12324218999998), 'rotation':(-0.051575, 90.880791, -0.051666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.94375, 5634.2621875, 173.11351562), 'rotation':(-0.025238, 90.882011, -0.025269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.68882812, 5650.84179688, 173.10623047), 'rotation':(-0.025146, 90.882004, -0.025177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6483.5184375, 5661.895, 173.10138672000002), 'rotation':(-0.011139, 90.881401, -0.011169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.43347656, 5667.42335938, 173.10007812), 'rotation':(0.017069, 90.881386, 0.017079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6483.34804688, 5672.95117188, 173.1003125), 'rotation':(0.017069, 90.881386, 0.017079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.26304688, 5678.47898438, 173.10212891), 'rotation':(0.031323, 90.881859, 0.031274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6483.17761719, 5684.00539062, 173.10513672000002), 'rotation':(0.03118, 90.881805, 0.031139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.92273438, 5700.585, 173.11416015999998), 'rotation':(0.03118, 90.881805, 0.031139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.83777344, 5706.1128125, 173.11728516), 'rotation':(0.036719, 90.882607, 0.036679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.2171875, 5706.24171875, 173.11728516), 'rotation':(-0.031158, -89.118195, -0.031219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.30210938, 5700.71390625, 173.11416015999998), 'rotation':(-0.031189, -89.114014, -0.031219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6491.47203125, 5689.66109375, 173.10814453), 'rotation':(-0.031158, -89.118195, -0.031219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6491.64246094, 5678.60789062, 173.10212891), 'rotation':(-0.01709, -89.118591, -0.01709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6491.72742188, 5673.08007812, 173.1003125), 'rotation':(0.011154, -89.118591, 0.011155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.49351562, 5623.33640625, 173.11890625), 'rotation':(0.051588, -89.119202, 0.05149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.57851562, 5617.80957031, 173.12324218999998), 'rotation':(0.069217, -89.119171, 0.069053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6492.74890625, 5606.75488281, 173.13726562), 'rotation':(0.095541, -89.117889, 0.095224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6492.91882812, 5595.70117188, 173.15550781000002), 'rotation':(0.095541, -89.117859, 0.095229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.08921875, 5584.64695312, 173.17457031), 'rotation':(0.103163, -89.118652, 0.102803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.25964844, 5573.59328125, 173.19597656000002), 'rotation':(0.133359, -89.115631, 0.132735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.34460938, 5568.06542969, 173.20773438), 'rotation':(0.133359, -89.115631, 0.132735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6493.6, 5551.48535156, 173.2484375), 'rotation':(0.155967, -89.117554, 0.155131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6493.68492188, 5545.95800781, 173.26324218999997), 'rotation':(0.155967, -89.117554, 0.155131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6482.16589844, 5749.73921875, 173.17222656), 'rotation':(0.103327, 90.879044, 0.102962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.990625, 5761.11421875, 173.19373047000002), 'rotation':(0.114809, 90.879005, 0.114358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.90320312, 5766.80125, 173.20542969), 'rotation':(0.126502, 90.884636, 0.125946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.72789062, 5778.17671875, 173.23070312), 'rotation':(0.138011, 90.884689, 0.137345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.46523438, 5795.23921875, 173.27310547000002), 'rotation':(0.14924, 90.88018, 0.148471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6481.02722656, 5823.67773438, 173.35279297), 'rotation':(0.176233, 90.885475, 0.175149), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.93984375, 5829.36523438, 173.37042968999998), 'rotation':(0.181471, 90.880356, 0.180334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.76453125, 5840.74070312, 173.40728516), 'rotation':(0.189654, 90.882088, 0.188395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6480.58921875, 5852.11570312, 173.44529297), 'rotation':(0.195118, 90.882339, 0.19379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.50183594, 5857.80320312, 173.46484375), 'rotation':(0.202413, 90.882271, 0.200996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.3265625, 5869.17773438, 173.50513672), 'rotation':(0.209769, 90.882423, 0.208229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.15125, 5880.55273438, 173.54708984), 'rotation':(0.217091, 90.888062, 0.215445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6480.06382812, 5886.24070312, 173.56867188), 'rotation':(0.218873, 90.882812, 0.217216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.88855469, 5897.61523438, 173.61228516), 'rotation':(0.221004, 90.880959, 0.219305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.80117188, 5903.30226562, 173.63423827999998), 'rotation':(0.225205, 90.883919, 0.223441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.71375, 5908.98921875, 173.6565625), 'rotation':(0.229214, 90.883896, 0.227384), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.5384375, 5920.36375, 173.70175781), 'rotation':(0.233415, 90.881073, 0.231517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6479.45105469, 5926.05125, 173.72470703), 'rotation':(0.233415, 90.881073, 0.231517), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.74257812, 5931.86960938, 173.74787109000002), 'rotation':(-0.233429, -89.116058, -0.235321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6487.82996094, 5926.183125, 173.72470703), 'rotation':(-0.229218, -89.116089, -0.231049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6488.093125, 5909.12109375, 173.6565625), 'rotation':(-0.22522, -89.116089, -0.22699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.26796875, 5897.7465625, 173.61228516), 'rotation':(-0.218872, -89.117157, -0.220551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.7059375, 5869.3090625, 173.50515625), 'rotation':(-0.206116, -89.117615, -0.207611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.79382812, 5863.6215625, 173.48478516), 'rotation':(-0.202423, -89.117706, -0.203857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.88125, 5857.9340625, 173.46484375), 'rotation':(-0.198792, -89.117645, -0.200165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6488.96863281, 5852.2465625, 173.44529297), 'rotation':(-0.191467, -89.117676, -0.192749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.05652344, 5846.55953125, 173.42617188), 'rotation':(-0.189636, -89.117889, -0.190918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.40664062, 5823.80859375, 173.35279297), 'rotation':(-0.170685, -89.119781, -0.171661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.49402344, 5818.12109375, 173.33572266), 'rotation':(-0.165436, -89.114502, -0.166412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6489.58191406, 5812.43359375, 173.31921875), 'rotation':(-0.160034, -89.119843, -0.160919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6489.66929688, 5806.745625, 173.30328125), 'rotation':(-0.154785, -89.114563, -0.15564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6489.84460938, 5795.36960938, 173.273125), 'rotation':(-0.146637, -89.114502, -0.1474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6490.01941406, 5783.99460938, 173.24431640999998), 'rotation':(-0.138, -89.115295, -0.138672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.1946875, 5772.61960938, 173.21775391), 'rotation':(-0.126495, -89.115356, -0.127075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6490.28257812, 5766.93164062, 173.20544922000002), 'rotation':(-0.120667, -89.115387, -0.121185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.37, 5761.24460938, 173.19373047000002), 'rotation':(-0.109161, -89.115417, -0.109589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6490.63269531, 5744.18164062, 173.16220703), 'rotation':(-0.0961, -89.121887, -0.096436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6529.83335938, 5071.00976562, 176.17414062), 'rotation':(-0.974121, -179.404373, -1.00769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6541.12878906, 5071.12451172, 176.36523438), 'rotation':(-0.96698, -179.404602, -1.000061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.42421875, 5071.23876953, 176.555), 'rotation':(-0.960083, -179.404816, -0.992676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6580.6625, 5071.52539062, 177.02416015999998), 'rotation':(-0.947449, -179.40419, -0.979187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.31042969, 5071.58300781, 177.11757812), 'rotation':(-0.947571, -179.40419, -0.979309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6591.95835938, 5071.64013672, 177.210625), 'rotation':(-0.942749, -179.40361, -0.974152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.25328125, 5071.75488281, 177.39541015999998), 'rotation':(-0.933411, -179.400955, -0.964203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6614.5496875, 5071.86914062, 177.57878906000002), 'rotation':(-0.928558, -179.405594, -0.959015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6625.84507812, 5071.98046875, 177.76189452999998), 'rotation':(-0.928619, -179.402634, -0.959106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6665.37929688, 5072.41845703, 178.39277343999998), 'rotation':(-0.903778, -179.404205, -0.932617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6671.02722656, 5072.47558594, 178.4815625), 'rotation':(-0.900238, -179.404068, -0.928894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6682.32361328, 5072.59033203, 178.65886719), 'rotation':(-0.897308, -179.406021, -0.925751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6687.9715625, 5072.64746094, 178.74707031000003), 'rotation':(-0.897308, -179.406021, -0.925751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6693.61902344, 5072.70507812, 178.83496093999997), 'rotation':(-0.891388, -179.406174, -0.919434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6710.56335938, 5072.87646484, 179.0959375), 'rotation':(-0.879425, -179.406601, -0.906738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6721.85974609, 5072.99121094, 179.26878906000002), 'rotation':(-0.876587, -179.405045, -0.903717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6744.45203125, 5073.22070312, 179.61306641), 'rotation':(-0.869202, -179.404022, -0.895905), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6750.07214844, 5081.62548828, 179.69898438), 'rotation':(0.859661, 0.595693, 0.834144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6744.42419922, 5081.56835938, 179.61394531000002), 'rotation':(0.864422, 0.595788, 0.838639), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.1278125, 5081.45361328, 179.44242188), 'rotation':(0.874059, 0.59613, 0.847691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6727.48083984, 5081.39648438, 179.35613281000002), 'rotation':(0.87658, 0.594962, 0.850066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.18445312, 5081.28222656, 179.18326172000002), 'rotation':(0.87658, 0.594962, 0.850066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6699.24060547, 5081.11035156, 178.92316406), 'rotation':(0.879421, 0.593403, 0.852731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6693.59363281, 5081.05273438, 178.83587891), 'rotation':(0.885418, 0.59702, 0.858365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6687.94568359, 5080.99560547, 178.74798828), 'rotation':(0.891374, 0.593809, 0.863947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6676.65125, 5080.88085938, 178.57130859), 'rotation':(0.897316, 0.597391, 0.869528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6648.41148438, 5080.59423828, 178.12560547), 'rotation':(0.910908, 0.593239, 0.882282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6637.115625, 5080.47949219, 177.945), 'rotation':(0.918018, 0.596275, 0.888941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6608.87734375, 5080.19287109, 177.48822266), 'rotation':(0.928537, 0.597357, 0.898802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.22984375, 5080.13574219, 177.39642578), 'rotation':(0.928537, 0.597357, 0.898802), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6591.93445312, 5080.02099609, 177.21160156000002), 'rotation':(0.933407, 0.596115, 0.903356), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.2875, 5079.96337891, 177.11861327999998), 'rotation':(0.94275, 0.596389, 0.912099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.05066406, 5079.67724609, 176.65046875), 'rotation':(0.952846, 0.599572, 0.921546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.40222656, 5079.62011719, 176.55605469), 'rotation':(0.956343, 0.59502, 0.924815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6535.45984375, 5079.44824219, 176.27091797), 'rotation':(0.966991, 0.600049, 0.93475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6529.81140625, 5079.390625, 176.17519531000002), 'rotation':(0.970577, 0.595546, 0.938094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6512.86953125, 5079.21875, 175.88667969), 'rotation':(0.975986, 0.598756, 0.943154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(7008.76453125, 5075.87011719, 183.34714843999998), 'rotation':(-0.755768, -179.411163, -0.775909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(7003.44373047, 5075.81591797, 183.27695312), 'rotation':(-0.758698, -179.406418, -0.778992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6992.11804688, 5075.70117188, 183.12671875), 'rotation':(-0.764679, -179.410934, -0.785309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6980.79138672, 5075.5859375, 182.97535156), 'rotation':(-0.770782, -179.410767, -0.791748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6969.46570312, 5075.47119141, 182.82287109), 'rotation':(-0.776764, -179.410599, -0.798065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6958.13904297, 5075.35595703, 182.66933594), 'rotation':(-0.778351, -179.405563, -0.799744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6952.47693359, 5075.29882812, 182.59238281), 'rotation':(-0.780304, -179.410645, -0.801758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6929.82458984, 5075.06884766, 182.28234375), 'rotation':(-0.792053, -179.406937, -0.814209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6912.83582031, 5074.89648438, 182.04732422), 'rotation':(-0.793915, -179.41011, -0.816132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6907.17224609, 5074.83886719, 181.96882812), 'rotation':(-0.793915, -179.41011, -0.816132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6890.18396484, 5074.66650391, 181.7325), 'rotation':(-0.806946, -179.409592, -0.829956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6878.85779297, 5074.55175781, 181.57292969), 'rotation':(-0.812195, -179.405045, -0.83548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6873.19568359, 5074.49414062, 181.49257812), 'rotation':(-0.814758, -179.41124, -0.838196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6861.86951172, 5074.37939453, 181.33144531000002), 'rotation':(-0.814789, -179.406128, -0.838196), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.20642578, 5074.32177734, 181.25087890999998), 'rotation':(-0.81485, -179.406067, -0.838287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.88025391, 5074.20703125, 181.08941406000002), 'rotation':(-0.820679, -179.405029, -0.844452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6839.21716797, 5074.14941406, 181.00826172), 'rotation':(-0.824554, -179.404953, -0.848572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6799.57898438, 5073.74707031, 180.43337891), 'rotation':(-0.841431, -179.405991, -0.866425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6788.13269531, 5082.01220703, 180.26634765999998), 'rotation':(0.841411, 0.59052, 0.816958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6793.79578125, 5082.06933594, 180.34972656000002), 'rotation':(0.841411, 0.59052, 0.816958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.12195312, 5082.18457031, 180.51560547), 'rotation':(0.8326, 0.593745, 0.808656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6810.78455078, 5082.2421875, 180.59806641), 'rotation':(0.8326, 0.593745, 0.808656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6827.77332031, 5082.4140625, 180.84445312), 'rotation':(0.828434, 0.591117, 0.804733), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.76257812, 5082.58642578, 181.08894531), 'rotation':(0.816665, 0.594814, 0.793627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6850.42517578, 5082.64404297, 181.16976562), 'rotation':(0.814842, 0.593928, 0.791901), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.08826172, 5082.70166016, 181.25041016), 'rotation':(0.814773, 0.58876, 0.791847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6867.41394531, 5082.81689453, 181.41152344), 'rotation':(0.814773, 0.593871, 0.791838), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6901.39148438, 5083.16162109, 181.88986328), 'rotation':(0.7939, 0.592794, 0.77213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6907.05457031, 5083.21875, 181.96835938), 'rotation':(0.794037, 0.592825, 0.77226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6912.71814453, 5083.27636719, 182.04689453), 'rotation':(0.794037, 0.592825, 0.77226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6929.70789062, 5083.44873047, 182.28191406000002), 'rotation':(0.788019, 0.59289, 0.766568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6935.37097656, 5083.50634766, 182.35982422), 'rotation':(0.784188, 0.589457, 0.76293), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.03357422, 5083.56347656, 182.43740234), 'rotation':(0.780294, 0.592713, 0.759255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6946.69666016, 5083.62109375, 182.51480468999998), 'rotation':(0.780294, 0.592713, 0.759255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6963.68689453, 5083.80371094, 182.74580078), 'rotation':(0.776777, 0.594065, 0.755917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6969.34949219, 5083.83300781, 182.82244140999998), 'rotation':(0.77386, 0.589317, 0.75316), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.01355469, 5083.87890625, 182.89884766), 'rotation':(0.770794, 0.593903, 0.75026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6980.67615234, 5083.93310547, 182.97494140999999), 'rotation':(0.767795, 0.593871, 0.747417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.33923828, 5083.99023438, 183.05076172), 'rotation':(0.764674, 0.589072, 0.744458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7008.67761719, 5084.21728516, 183.34712890999998), 'rotation':(0.754121, 0.590965, 0.734457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6755.85583984, 4560.20117188, 178.18984375), 'rotation':(0.829315, 0.080985, 0.805552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6750.28650391, 4560.19484375, 178.10894531000002), 'rotation':(0.831869, 0.078178, 0.807974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6731.39734375, 4560.0703125, 177.83365234000001), 'rotation':(0.837122, 0.08121, 0.812916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.85730469, 4560.13671875, 177.95716797), 'rotation':(0.834594, 0.081135, 0.810552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6700.16394531, 4560.00585938, 177.37638672), 'rotation':(0.838385, 0.076977, 0.814111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6689.02527344, 4559.99265625, 177.21232422), 'rotation':(0.845612, 0.080215, 0.820918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6677.88708984, 4559.97949219, 177.04791016), 'rotation':(0.845612, 0.080215, 0.820918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6672.31773438, 4559.97265625, 176.96570312), 'rotation':(0.845468, 0.080209, 0.820788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6666.74890625, 4559.96582031, 176.88339843999998), 'rotation':(0.845468, 0.080209, 0.820788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6650.04234375, 4559.94628906, 176.63542969), 'rotation':(0.851977, 0.082904, 0.826911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6638.90320312, 4559.933125, 176.46892577999998), 'rotation':(0.856232, 0.08022, 0.830914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6633.334375, 4559.92675781, 176.38525391), 'rotation':(0.860488, 0.080346, 0.834926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6622.19714844, 4559.91359375, 176.21765625), 'rotation':(0.862742, 0.080324, 0.837049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6605.49011719, 4559.89355469, 175.96599609), 'rotation':(0.862742, 0.085136, 0.837043), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.35144531, 4559.87988281, 175.79722656), 'rotation':(0.869667, 0.08234, 0.843555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6583.21328125, 4559.8671875, 175.62761719), 'rotation':(0.872249, 0.080269, 0.845996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6577.64539062, 4559.86035156, 175.5428125), 'rotation':(0.872099, 0.08361, 0.84585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6560.93835938, 4559.8403125, 175.28710938), 'rotation':(0.880364, 0.08446, 0.853608), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6549.7996875, 4559.82714844, 175.11533203), 'rotation':(0.883676, 0.080394, 0.856731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6538.66199219, 4559.81398438, 174.94251953), 'rotation':(0.890192, 0.08477, 0.862845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6533.09265625, 4559.80710938, 174.85566406), 'rotation':(0.893382, 0.08069, 0.865844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6521.9559375, 4559.79394531, 174.68132812), 'rotation':(0.896715, 0.0808, 0.868961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6748.06189453, 4551.55226562, 178.07648438), 'rotation':(-0.834625, -179.918869, -0.859192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.15808594, 4551.59226562, 177.94683593999997), 'rotation':(-0.837067, -179.918777, -0.861816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6728.02039062, 4551.65332031, 177.78414062), 'rotation':(-0.83844, -179.923004, -0.863281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.88269531, 4551.645, 177.62113281), 'rotation':(-0.838379, -179.918396, -0.86319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6700.17517578, 4551.625, 177.37640625), 'rotation':(-0.84198, -179.917725, -0.867004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6694.60583984, 4551.61867188, 177.29453125), 'rotation':(-0.845612, -179.919785, -0.87085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6689.03699219, 4551.61179688, 177.21236327999998), 'rotation':(-0.845459, -179.919785, -0.870697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6677.89832031, 4551.59863281, 177.04792969), 'rotation':(-0.845459, -179.919785, -0.870697), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6666.76015625, 4551.58496094, 176.88339843999998), 'rotation':(-0.847687, -179.920029, -0.873047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6650.053125, 4551.56542969, 176.63544922), 'rotation':(-0.856232, -179.919785, -0.882111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6638.91492188, 4551.55226562, 176.46894531), 'rotation':(-0.860474, -179.919647, -0.886627), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6633.34507812, 4551.54589844, 176.38527344), 'rotation':(-0.862671, -179.919693, -0.888947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6622.20789062, 4551.53273438, 176.21767577999998), 'rotation':(-0.862762, -179.919678, -0.889038), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6616.6390625, 4551.52585938, 176.13380859), 'rotation':(-0.862518, -179.919693, -0.888794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6611.06921875, 4551.5190625, 176.04990234000002), 'rotation':(-0.862671, -179.914871, -0.888947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6605.50039062, 4551.51269531, 175.96599609), 'rotation':(-0.865112, -179.922729, -0.891541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6594.36265625, 4551.49902344, 175.79724609000002), 'rotation':(-0.872284, -179.919724, -0.899139), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6588.79285156, 4551.49265625, 175.71244141), 'rotation':(-0.872101, -179.916382, -0.898956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6572.08726562, 4551.473125, 175.45789062), 'rotation':(-0.877045, -179.919815, -0.904205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6566.51746094, 4551.46632812, 175.37261718999997), 'rotation':(-0.880371, -179.915527, -0.907745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6560.94910156, 4551.45945312, 175.28710938), 'rotation':(-0.883698, -179.919601, -0.911285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6549.8109375, 4551.44628906, 175.11533203), 'rotation':(-0.886871, -179.91951, -0.914673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6544.24207031, 4551.43992188, 175.02908202999998), 'rotation':(-0.890198, -179.919403, -0.918182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6521.96667969, 4551.41308594, 174.68134766), 'rotation':(-0.898346, -179.916718, -0.926849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7006.17859375, 4551.89992188, 181.7596875), 'rotation':(-0.808105, -179.919235, -0.831146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6989.06384766, 4551.96777344, 181.51818359), 'rotation':(-0.809204, -179.921082, -0.832306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6983.49353516, 4551.96140625, 181.43951172), 'rotation':(-0.809052, -179.921082, -0.832153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6972.35144531, 4551.94824219, 181.28212890999998), 'rotation':(-0.809052, -179.915894, -0.832123), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6966.78162109, 4551.94140625, 181.2034375), 'rotation':(-0.809357, -179.924164, -0.832458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6955.64050781, 4551.92820312, 181.04597656), 'rotation':(-0.810211, -179.91954, -0.833374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6950.07019531, 4551.921875, 180.96716797000002), 'rotation':(-0.810791, -179.919525, -0.833984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6927.78796875, 4551.89550781, 180.65152343999998), 'rotation':(-0.812653, -179.919464, -0.835968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6922.21716797, 4551.88867188, 180.5725), 'rotation':(-0.812988, -179.920776, -0.836304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6916.64636719, 4551.88234375, 180.49345703), 'rotation':(-0.812988, -179.920776, -0.836304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6911.07605469, 4551.87546875, 180.41439452999998), 'rotation':(-0.812988, -179.920776, -0.836304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6866.51111328, 4551.82226562, 179.780625), 'rotation':(-0.816528, -179.920288, -0.840057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6860.94080078, 4551.8159375, 179.70123047), 'rotation':(-0.816528, -179.920288, -0.840057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6855.37048828, 4551.8090625, 179.62183593999998), 'rotation':(-0.81839, -179.920227, -0.842041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6833.08777344, 4551.78273438, 179.30294922000002), 'rotation':(-0.822205, -179.92012, -0.846069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6821.94714844, 4551.77, 179.14296875), 'rotation':(-0.823181, -179.91745, -0.847107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6799.66541016, 4551.74316406, 178.82265625), 'rotation':(-0.826477, -179.919861, -0.850555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6794.09460938, 4551.73679688, 178.74240234), 'rotation':(-0.826477, -179.919861, -0.850555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6794.04480469, 4560.1171875, 178.74181640999998), 'rotation':(0.824178, 0.080056, 0.800715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6799.61560547, 4560.12402344, 178.82208984000002), 'rotation':(0.824178, 0.080056, 0.800715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6821.89832031, 4560.14992188, 179.14240234000002), 'rotation':(0.823188, 0.082555, 0.799778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.03796875, 4560.16359375, 179.30238281), 'rotation':(0.820347, 0.079816, 0.797099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6849.74988281, 4560.183125, 179.54166016), 'rotation':(0.818393, 0.07976, 0.795261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6855.32019531, 4560.18992188, 179.62125), 'rotation':(0.816535, 0.079707, 0.793505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6866.46130859, 4560.203125, 179.78003906), 'rotation':(0.815545, 0.080039, 0.792568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6872.03210938, 4560.20996094, 179.859375), 'rotation':(0.81562, 0.080033, 0.792648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6877.60291016, 4560.21632812, 179.93869141), 'rotation':(0.815545, 0.080039, 0.792568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6883.17322266, 4560.223125, 180.01800781000003), 'rotation':(0.81562, 0.080033, 0.792648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6888.74353516, 4560.22949219, 180.09732422000002), 'rotation':(0.81422, 0.078845, 0.79132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6899.88513672, 4560.24265625, 180.25570312), 'rotation':(0.81297, 0.07922, 0.790143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6905.4559375, 4560.24953125, 180.33476561999998), 'rotation':(0.81297, 0.07922, 0.790143), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6922.16736328, 4560.26953125, 180.57195312), 'rotation':(0.812656, 0.080524, 0.789844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6944.45007812, 4560.29882812, 180.88775391), 'rotation':(0.810791, 0.080471, 0.788081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6950.02039062, 4560.30957031, 180.96660156000002), 'rotation':(0.810211, 0.080455, 0.787539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6961.16150391, 4560.29492188, 181.12416016), 'rotation':(0.809357, 0.075828, 0.78673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6972.30310547, 4560.29589844, 181.28158202999998), 'rotation':(0.809207, 0.08411, 0.786586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6977.87341797, 4560.30273438, 181.36025390999998), 'rotation':(0.809043, 0.078915, 0.786429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6989.01404297, 4560.3159375, 181.51761718999998), 'rotation':(0.808578, 0.078504, 0.785991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7005.72644531, 4560.50585938, 181.75345703), 'rotation':(0.807984, 0.077109, 0.785424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7011.29626953, 4560.51269531, 181.83201172), 'rotation':(0.80808, 0.080762, 0.785535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6766.65710938, 5242.40332031, 179.50457031000002), 'rotation':(-0.228088, 90.486, -0.229889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.67371094, 5253.67236328, 179.45955078), 'rotation':(-0.229828, 90.488319, -0.231689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.57800781, 5264.94482422, 179.41429688), 'rotation':(-0.230774, 90.489281, -0.232635), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.43494141, 5281.85302734, 179.34570312), 'rotation':(-0.236328, 90.485031, -0.238281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6766.38708984, 5287.48925781, 179.3225), 'rotation':(-0.237366, 90.489288, -0.239349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6766.24402344, 5304.39697266, 179.25251953), 'rotation':(-0.237579, 90.485962, -0.239532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.14832031, 5315.66943359, 179.20582031), 'rotation':(-0.237732, 90.488876, -0.239716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6766.05261719, 5326.94091797, 179.15904297), 'rotation':(-0.237915, 90.485954, -0.239899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.95691406, 5338.21335938, 179.11220702999998), 'rotation':(-0.238281, 90.488899, -0.240265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.86072266, 5349.48484375, 179.0653125), 'rotation':(-0.237976, 90.485779, -0.23996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.81287109, 5355.1215625, 179.041875), 'rotation':(-0.237976, 90.485779, -0.23996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.47791016, 5394.57273438, 178.88095703), 'rotation':(-0.229156, 90.488434, -0.230988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6765.43005859, 5400.20945312, 178.85839843999997), 'rotation':(-0.229126, 90.488388, -0.230957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.38220703, 5405.84472656, 178.83585938), 'rotation':(-0.227692, 90.487076, -0.229492), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.19080078, 5428.38964844, 178.74724609), 'rotation':(-0.219025, 90.487022, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.14294922, 5434.02585938, 178.72554688), 'rotation':(-0.219025, 90.487022, -0.220673), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6765.09509766, 5439.66210938, 178.70400390999998), 'rotation':(-0.217438, 90.484566, -0.219116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6764.95203125, 5456.57128906, 178.64003906000002), 'rotation':(-0.212311, 90.485252, -0.213867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6764.85632812, 5467.84421875, 178.59876953), 'rotation':(-0.205688, 90.490723, -0.207153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6764.61707031, 5496.02492188, 178.50185547), 'rotation':(-0.190369, 90.484612, -0.19162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6764.56921875, 5501.66113281, 178.483125), 'rotation':(-0.190369, 90.484612, -0.19162), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.94958984, 5501.73535156, 178.48310547), 'rotation':(0.190344, -89.512024, 0.189099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.04529297, 5490.46335938, 178.52060547000002), 'rotation':(0.192058, -89.514862, 0.190771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.09314453, 5484.82664062, 178.53958984000002), 'rotation':(0.195473, -89.509338, 0.194146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.14099609, 5479.1909375, 178.55896484000002), 'rotation':(0.198861, -89.514832, 0.197488), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.18884766, 5473.55371094, 178.57869141), 'rotation':(0.205684, -89.509277, 0.204205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.23669922, 5467.9184375, 178.59876953), 'rotation':(0.209058, -89.514771, 0.207546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.33240234, 5456.64550781, 178.64003906000002), 'rotation':(0.215889, -89.509216, 0.214262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.76257812, 5405.91992188, 178.83583984), 'rotation':(0.229153, -89.516541, 0.227313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.85828125, 5394.64796875, 178.88095703), 'rotation':(0.229795, -89.514282, 0.227958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.0496875, 5372.10449219, 178.97214843999998), 'rotation':(0.234228, -89.514252, 0.232309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.24158203, 5349.56054688, 179.06529297), 'rotation':(0.23838, -89.514191, 0.236403), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.28943359, 5343.92429688, 179.08875), 'rotation':(0.238278, -89.511108, 0.236302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.38513672, 5332.65234375, 179.13560547), 'rotation':(0.237909, -89.514038, 0.235948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.52869141, 5315.74462891, 179.20580078), 'rotation':(0.23754, -89.514038, 0.235585), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.62390625, 5304.47216797, 179.2525), 'rotation':(0.237274, -89.510712, 0.235309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.71960938, 5293.20068359, 179.29919922000002), 'rotation':(0.236338, -89.514923, 0.234393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.76746094, 5287.56445312, 179.3225), 'rotation':(0.236338, -89.514923, 0.234393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.81482422, 5281.92822266, 179.34568359000002), 'rotation':(0.23459, -89.510742, 0.232686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.91003906, 5270.65576172, 179.39160156000003), 'rotation':(0.230744, -89.510742, 0.22889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6775.05408203, 5253.74755859, 179.45953125), 'rotation':(0.229843, -89.51532, 0.228), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.18445312, 5193.44189453, 179.68974609), 'rotation':(-0.211578, 90.486282, -0.213135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.23181641, 5187.90771484, 179.70986327999998), 'rotation':(-0.208191, 90.48613, -0.209686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.27869141, 5182.37304688, 179.72939452999998), 'rotation':(-0.201874, 90.486107, -0.203308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.41931641, 5165.77246094, 179.78523438), 'rotation':(-0.188721, 90.490028, -0.189941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.65417969, 5138.10205078, 179.87324218999998), 'rotation':(-0.181152, 90.487091, -0.182312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.70154297, 5132.56787109, 179.88992188), 'rotation':(-0.172577, 90.484116, -0.173584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.74841797, 5127.03369141, 179.90580078), 'rotation':(-0.16394, 90.487, -0.164886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6767.84216797, 5115.96582031, 179.93648438), 'rotation':(-0.155334, 90.486969, -0.156189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6767.93591797, 5104.89794922, 179.96587891), 'rotation':(-0.151093, 90.487633, -0.151886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.03015625, 5093.83007812, 179.99414062), 'rotation':(-0.147125, 90.485794, -0.147888), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.47107422, 5204.58154297, 179.64892577999998), 'rotation':(0.211572, -89.513702, 0.210021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.51794922, 5199.04785156, 179.669375), 'rotation':(0.211572, -89.513702, 0.210021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6775.6590625, 5182.4453125, 179.72939452999998), 'rotation':(0.195152, -89.513977, 0.193824), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.7059375, 5176.91162109, 179.74845703), 'rotation':(0.188698, -89.509949, 0.187473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.7528125, 5171.37744141, 179.76705077999998), 'rotation':(0.188698, -89.509949, 0.187473), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.84705078, 5160.31005859, 179.80314453), 'rotation':(0.185433, -89.513367, 0.184235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6775.98767578, 5143.70800781, 179.85628906000002), 'rotation':(0.172558, -89.515869, 0.171518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6776.08191406, 5132.64013672, 179.88992188), 'rotation':(0.163945, -89.513, 0.163012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.12878906, 5127.10595703, 179.90580078), 'rotation':(0.155339, -89.513031, 0.154495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.26941406, 5110.50390625, 179.95128906000002), 'rotation':(0.151084, -89.51236, 0.150288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.31628906, 5104.96972656, 179.96585938), 'rotation':(0.147129, -89.514191, 0.146373), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6776.36316406, 5099.43652344, 179.98019531000003), 'rotation':(0.139363, -89.514221, 0.138695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.30457031, 5061.44287109, 180.06484375), 'rotation':(-0.11145, 90.485931, -0.111877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.53943359, 5033.78222656, 180.11179688), 'rotation':(-0.083069, 90.484306, -0.083313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.63367188, 5022.71679688, 180.12654297), 'rotation':(-0.070526, 90.489105, -0.070679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.72742188, 5011.65185547, 180.13910156000003), 'rotation':(-0.064148, 90.484245, -0.064301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6768.77429688, 5006.11914062, 180.14498047), 'rotation':(-0.060944, 90.487587, -0.061066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6768.82117188, 5000.58789062, 180.15039062), 'rotation':(-0.055145, 90.486389, -0.055267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6768.86804688, 4995.05566406, 180.15509766), 'rotation':(-0.055145, 90.486389, -0.055267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6768.96228516, 4983.99072266, 180.16207031000002), 'rotation':(-0.03186, 90.486366, -0.031921), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.05603516, 4972.92578125, 180.165625), 'rotation':(-0.014374, 90.484917, -0.014374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.19714844, 4956.32861328, 180.1690625), 'rotation':(-0.01001, 90.487, -0.009979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.29089844, 4945.26367188, 180.16814452999998), 'rotation':(0.007377, 90.487, 0.00738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6776.68542969, 5061.51464844, 180.06484375), 'rotation':(0.108327, -89.515594, 0.107927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.10779297, 5011.72363281, 180.13910156000003), 'rotation':(0.060932, -89.512421, 0.060814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6777.15466797, 5006.19091797, 180.14498047), 'rotation':(0.055154, -89.51355, 0.055048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6777.29529297, 4989.59472656, 180.15900391), 'rotation':(0.03187, -89.513641, 0.031826), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.38953125, 4978.52929688, 180.1640625), 'rotation':(0.014364, -89.515076, 0.014359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.43640625, 4972.99755859, 180.165625), 'rotation':(0.014494, -89.515076, 0.014489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.48328125, 4967.46484375, 180.16703125), 'rotation':(0.014494, -89.515076, 0.014489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6777.57751953, 4956.40039062, 180.1690625), 'rotation':(0.00138, -89.513, 0.001386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6777.67126953, 4945.33544922, 180.16814452999998), 'rotation':(-0.015991, -89.513, -0.015991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6769.56580078, 4912.87744141, 180.146875), 'rotation':(0.055277, 90.481056, 0.055176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.61267578, 4907.35449219, 180.14128906000002), 'rotation':(0.058057, 90.488518, 0.057937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.84705078, 4879.74169922, 180.10595702999998), 'rotation':(0.095418, 90.488022, 0.095114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.89392578, 4874.21972656, 180.09623047000002), 'rotation':(0.095418, 90.488022, 0.095114), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6769.94080078, 4868.69628906, 180.08560547000002), 'rotation':(0.110335, 90.484665, 0.109925), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.03455078, 4857.65136719, 180.06294922), 'rotation':(0.117834, 90.488693, 0.117358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.08142578, 4852.12939453, 180.05136718999998), 'rotation':(0.117821, 90.484779, 0.117355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.12830078, 4846.60644531, 180.03929688), 'rotation':(0.125416, 90.487236, 0.124865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.17517578, 4841.08398438, 180.02605469), 'rotation':(0.140517, 90.487274, 0.139831), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.26892578, 4830.03808594, 179.99710938), 'rotation':(0.155646, 90.484024, 0.154791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.36267578, 4818.99462891, 179.96433593999998), 'rotation':(0.17085, 90.487465, 0.169836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.40955078, 4813.47119141, 179.94714843999998), 'rotation':(0.17837, 90.485916, 0.177274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6770.4559375, 4807.94824219, 179.92994141), 'rotation':(0.17837, 90.48941, 0.177263), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.5496875, 4796.90332031, 179.89460938), 'rotation':(0.185446, 90.485397, 0.184241), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.83142578, 4763.76757812, 179.76726562), 'rotation':(0.235075, 90.486801, 0.233167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.92419922, 4752.72314453, 179.720625), 'rotation':(0.248988, 90.487854, 0.246834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6770.97107422, 4747.20019531, 179.69625), 'rotation':(0.248988, 90.487854, 0.246834), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.01794922, 4741.67773438, 179.67113281000002), 'rotation':(0.258188, 90.48793, 0.255876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.13367188, 4890.85888672, 180.12269531), 'rotation':(-0.080505, -89.515411, -0.080719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.18054688, 4885.3359375, 180.11494141), 'rotation':(-0.095428, -89.511963, -0.095734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.22742188, 4879.81298828, 180.10595702999998), 'rotation':(-0.110352, -89.515289, -0.110779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.55554688, 4841.15576172, 180.02605469), 'rotation':(-0.15564, -89.515991, -0.156464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6778.64929688, 4830.11035156, 179.99710938), 'rotation':(-0.170868, -89.512512, -0.171875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6778.74304688, 4819.06591797, 179.96431640999998), 'rotation':(-0.178406, -89.514069, -0.179504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6778.78992188, 4813.54345703, 179.94714843999998), 'rotation':(-0.178375, -89.51059, -0.179474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.02429688, 4785.9296875, 179.85533203), 'rotation':(-0.213806, -89.510742, -0.215393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.07117188, 4780.40820312, 179.83445312), 'rotation':(-0.228058, -89.514252, -0.229889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.11755859, 4774.88476562, 179.81246094), 'rotation':(-0.234924, -89.513245, -0.236847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.21130859, 4763.83935547, 179.76726562), 'rotation':(-0.239624, -89.512207, -0.241669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6779.35144531, 4747.27246094, 179.69625), 'rotation':(-0.258209, -89.512024, -0.260559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.29285156, 4709.28955078, 179.50966797), 'rotation':(0.297919, 90.488083, 0.294839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.38660156, 4698.23535156, 179.45126953), 'rotation':(0.303383, 90.48555, 0.300184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.43347656, 4692.70751953, 179.42087891), 'rotation':(0.31479, 90.489914, 0.311357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.48035156, 4687.18017578, 179.38945311999998), 'rotation':(0.326046, 90.485779, 0.322355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.57410156, 4676.12646484, 179.32427734), 'rotation':(0.342992, 90.48616, 0.338908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.66833984, 4665.07128906, 179.25800781), 'rotation':(0.342875, 90.490608, 0.338803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.71521484, 4659.54394531, 179.22443359000002), 'rotation':(0.3464, 90.484276, 0.342234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.85583984, 4642.96289062, 179.11978516), 'rotation':(0.367505, 90.489357, 0.362809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.90271484, 4637.43554688, 179.08359375), 'rotation':(0.374759, 90.489494, 0.369885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6771.94958984, 4631.90773438, 179.04677734), 'rotation':(0.381541, 90.489586, 0.376477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6771.99646484, 4626.38085938, 179.00927734), 'rotation':(0.388727, 90.484833, 0.383491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.04333984, 4620.85351562, 178.97113281000003), 'rotation':(0.395707, 90.489792, 0.390268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.09021484, 4615.32664062, 178.93265625), 'rotation':(0.399368, 90.487785, 0.393829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.13708984, 4609.79929688, 178.89412109), 'rotation':(0.399225, 90.492393, 0.393695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.23083984, 4598.74460938, 178.81587890999998), 'rotation':(0.403657, 90.486336, 0.398003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.37195312, 4582.16359375, 178.69345703), 'rotation':(0.429755, 90.486725, 0.423338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.46570312, 4571.10839844, 178.6096875), 'rotation':(0.434079, 90.492729, 0.427538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.67322266, 4709.36132812, 179.50966797), 'rotation':(-0.303375, -89.514435, -0.30661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6779.72009766, 4703.83447266, 179.48072266), 'rotation':(-0.303375, -89.514435, -0.30661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6779.76697266, 4698.30712891, 179.45126953), 'rotation':(-0.314789, -89.510071, -0.318268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6779.90759766, 4681.72509766, 179.35714843999997), 'rotation':(-0.343018, -89.513763, -0.347137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.04871094, 4665.14355469, 179.25802734), 'rotation':(-0.346436, -89.515656, -0.350647), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.09558594, 4659.61570312, 179.22443359000002), 'rotation':(-0.353485, -89.510803, -0.35788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6780.14246094, 4654.08886719, 179.19019531), 'rotation':(-0.360596, -89.510681, -0.365173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6780.18884766, 4648.56101562, 179.1553125), 'rotation':(-0.367523, -89.510559, -0.372284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.28308594, 4637.50734375, 179.08361327999998), 'rotation':(-0.381531, -89.510406, -0.386658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.42371094, 4620.9253125, 178.97115234), 'rotation':(-0.399384, -89.507599, -0.404968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.75232422, 4582.23585938, 178.69345703), 'rotation':(-0.434082, -89.511536, -0.440674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6780.79919922, 4576.70800781, 178.65158203), 'rotation':(-0.434082, -89.507263, -0.440674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6780.84607422, 4571.18066406, 178.60970702999998), 'rotation':(-0.435547, -89.512939, -0.4422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.09998047, 4378.53710938, 176.94125), 'rotation':(0.537809, 90.487335, 0.527778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.05310547, 4384.06054688, 176.99320312), 'rotation':(0.537809, 90.487335, 0.527778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.95935547, 4395.10644531, 177.09660156), 'rotation':(0.533458, 90.491524, 0.523591), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.77136719, 4417.19921875, 177.30125), 'rotation':(0.525023, 90.491409, 0.515462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.67761719, 4428.24414062, 177.40255859), 'rotation':(0.522557, 90.493477, 0.513101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.53699219, 4444.81347656, 177.55283203), 'rotation':(0.513671, 90.487946, 0.504535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.49011719, 4450.33640625, 177.60230468999998), 'rotation':(0.510994, 90.493263, 0.501942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.44324219, 4455.859375, 177.65150391), 'rotation':(0.507982, 90.487854, 0.499029), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.39685547, 4461.3828125, 177.70041016), 'rotation':(0.505079, 90.493141, 0.496226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6773.34998047, 4466.90625, 177.74902343999997), 'rotation':(0.502258, 90.487762, 0.493512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.20886719, 4483.47460938, 177.89375), 'rotation':(0.497586, 90.490837, 0.489003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6773.06873047, 4500.04394531, 178.03625), 'rotation':(0.484766, 90.490601, 0.476626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.97498047, 4511.08984375, 178.12925781), 'rotation':(0.478441, 90.490532, 0.470497), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6772.83435547, 4527.65917969, 178.26677734), 'rotation':(0.467943, 90.490524, 0.460341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6772.74060547, 4538.70554688, 178.35673828), 'rotation':(0.458128, 90.490326, 0.450853), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.12097656, 4538.78859375, 178.35683594), 'rotation':(-0.462982, -89.509552, -0.47049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.16785156, 4533.265625, 178.31208984), 'rotation':(-0.467957, -89.514587, -0.475616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.26160156, 4522.21972656, 178.22125), 'rotation':(-0.475159, -89.509827, -0.483093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6781.30847656, 4516.69679688, 178.17544922000002), 'rotation':(-0.478394, -89.509491, -0.48645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.35535156, 4511.17335938, 178.12935547), 'rotation':(-0.484772, -89.509369, -0.493042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.49548828, 4494.605, 177.98921875), 'rotation':(-0.491119, -89.509277, -0.499603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.58923828, 4483.558125, 177.89386718999998), 'rotation':(-0.500702, -89.511505, -0.509521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6781.77673828, 4461.46726562, 177.70052734), 'rotation':(-0.507935, -89.512177, -0.516998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6781.82361328, 4455.94433594, 177.65162109000002), 'rotation':(-0.510986, -89.506714, -0.520172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6781.96423828, 4439.375, 177.50316406000002), 'rotation':(-0.519501, -89.511963, -0.528992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.01111328, 4433.8515625, 177.45306641), 'rotation':(-0.522583, -89.5065, -0.532166), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.15222656, 4417.28367188, 177.30136718999998), 'rotation':(-0.52713, -89.508575, -0.536896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.19910156, 4411.76074219, 177.25046875), 'rotation':(-0.529327, -89.508514, -0.539185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.24597656, 4406.2378125, 177.19941406), 'rotation':(-0.531342, -89.508484, -0.54126), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.43347656, 4384.14550781, 176.99333984), 'rotation':(-0.539948, -89.508301, -0.550201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6782.52673828, 4373.09960938, 176.88931641), 'rotation':(-0.540985, -89.508667, -0.55127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.9403125, 4279.47359375, 175.99423828), 'rotation':(0.553341, 90.489311, 0.542727), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.84607422, 4290.59179688, 176.1015625), 'rotation':(0.552023, 90.489288, 0.541466), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.75183594, 4301.71, 176.20865234000001), 'rotation':(0.550582, 90.489258, 0.540078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6774.70447266, 4307.26859375, 176.26210938), 'rotation':(0.550049, 90.493446, 0.539574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.61023438, 4318.38625, 176.36884766), 'rotation':(0.549263, 90.489227, 0.538809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.56335938, 4323.9453125, 176.42214843999997), 'rotation':(0.548635, 90.493469, 0.538216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6774.51599609, 4329.50484375, 176.47539061999998), 'rotation':(0.548246, 90.490685, 0.537843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6783.27380859, 4285.10351562, 176.04792969), 'rotation':(-0.553375, -89.510681, -0.564148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6783.17957031, 4296.2221875, 176.15511718999997), 'rotation':(-0.552032, -89.510712, -0.562744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.94373047, 4324.01804688, 176.42216797), 'rotation':(-0.549255, -89.510773, -0.559875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6782.89636719, 4329.5771875, 176.47541016), 'rotation':(-0.548645, -89.506531, -0.559235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6790.54919922, 4730.26123047, 179.80535156000002), 'rotation':(0.787678, 0.150199, 0.766245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6796.15076172, 4730.27490234, 179.88240234), 'rotation':(0.785943, 0.154796, 0.7646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6801.75232422, 4730.28857422, 179.95929688), 'rotation':(0.783914, 0.150097, 0.762674), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6807.35291016, 4730.30224609, 180.03601562), 'rotation':(0.782166, 0.150047, 0.76103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6818.55603516, 4730.32958984, 180.18898438), 'rotation':(0.780137, 0.149995, 0.759102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6824.15759766, 4730.34375, 180.26521484), 'rotation':(0.778484, 0.154581, 0.757537), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6829.75916016, 4730.35742188, 180.34126952999998), 'rotation':(0.776517, 0.149897, 0.755669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6857.76599609, 4730.42578125, 180.71927734000002), 'rotation':(0.769755, 0.151218, 0.749281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6863.36755859, 4730.43945312, 180.79447266), 'rotation':(0.767385, 0.151156, 0.747034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6868.96912109, 4730.453125, 180.86958984), 'rotation':(0.766375, 0.151127, 0.746076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6896.97693359, 4730.52197266, 181.24375), 'rotation':(0.764756, 0.152703, 0.744555), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6908.17957031, 4730.54931641, 181.39302734), 'rotation':(0.759046, 0.148833, 0.739132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6919.38269531, 4730.57666016, 181.54148438), 'rotation':(0.759046, 0.148833, 0.739132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6930.58582031, 4730.60449219, 181.68996094), 'rotation':(0.75837, 0.150065, 0.738483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6936.18738281, 4730.61816406, 181.76414062), 'rotation':(0.75837, 0.150065, 0.738483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6952.99158203, 4730.66650391, 181.98626953), 'rotation':(0.75561, 0.149992, 0.73587), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6958.59363281, 4730.66308594, 182.06015625), 'rotation':(0.754319, 0.149962, 0.734654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6969.79675781, 4730.66748047, 182.20765625), 'rotation':(0.753288, 0.151755, 0.733666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.39832031, 4730.68115234, 182.28130859), 'rotation':(0.752605, 0.151737, 0.73303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6980.99988281, 4730.69482422, 182.35492188), 'rotation':(0.751997, 0.147433, 0.732447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.60144531, 4730.70849609, 182.42847656), 'rotation':(0.751532, 0.151709, 0.732011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7014.60974609, 4730.77685547, 182.79550781), 'rotation':(0.749121, 0.151649, 0.729713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7014.6590625, 4722.4296875, 182.79587891), 'rotation':(-0.749664, -179.848343, -0.76947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7009.0575, 4722.41552734, 182.72255859), 'rotation':(-0.750244, -179.852615, -0.770111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6986.65076172, 4722.36083984, 182.42884766), 'rotation':(-0.751923, -179.85257, -0.771881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6975.44763672, 4722.33349609, 182.28169922), 'rotation':(-0.753296, -179.848236, -0.773285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6964.24451172, 4722.30615234, 182.13431641), 'rotation':(-0.754272, -179.850052, -0.774353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6953.04138672, 4722.27880859, 181.98664062), 'rotation':(-0.75708, -179.84996, -0.777283), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.83826172, 4722.25097656, 181.83867188), 'rotation':(-0.758362, -179.846893, -0.778656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6913.83044922, 4722.18261719, 181.46763672), 'rotation':(-0.759064, -179.851166, -0.779388), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6908.229375, 4722.16894531, 181.39341797), 'rotation':(-0.761902, -179.849213, -0.782379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6902.62732422, 4722.15527344, 181.31890625), 'rotation':(-0.764709, -179.847321, -0.785309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6880.2215625, 4722.10009766, 181.01980468999997), 'rotation':(-0.765198, -179.848892, -0.785828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6874.61951172, 4722.08642578, 180.94494140999998), 'rotation':(-0.766449, -179.848862, -0.78717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6869.01794922, 4722.07226562, 180.86998047), 'rotation':(-0.767395, -179.848846, -0.788147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6857.81482422, 4722.04492188, 180.71964844), 'rotation':(-0.771027, -179.84874, -0.791992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6846.6121875, 4722.01757812, 180.56884766), 'rotation':(-0.773132, -179.848694, -0.79422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6841.01111328, 4722.00390625, 180.49326172000002), 'rotation':(-0.77478, -179.850159, -0.795959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6835.41003906, 4721.99023438, 180.41753906000002), 'rotation':(-0.77652, -179.850098, -0.797791), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6829.80847656, 4721.9765625, 180.34166016), 'rotation':(-0.778534, -179.845398, -0.799927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6818.60535156, 4721.94921875, 180.189375), 'rotation':(-0.782166, -179.849945, -0.803741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6813.00378906, 4721.93505859, 180.11296875), 'rotation':(-0.782166, -179.849945, -0.803741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6796.19958984, 4721.89404297, 179.88279297), 'rotation':(-0.787689, -179.845154, -0.80957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6790.59851562, 4721.88037109, 179.80576172000002), 'rotation':(-0.788483, -179.850739, -0.810425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7011.27917969, 4925.51171875, 183.30513672), 'rotation':(-0.723572, 179.915451, -0.742035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(7005.71179688, 4925.52099609, 183.23480468999998), 'rotation':(-0.725494, 179.911606, -0.744049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(7000.1434375, 4925.53027344, 183.16427734), 'rotation':(-0.727722, 179.915543, -0.746399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6994.57605469, 4925.53955078, 183.09363281000003), 'rotation':(-0.729614, 179.915604, -0.748383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6966.73816406, 4925.69677734, 182.73804688), 'rotation':(-0.735779, 179.915771, -0.754852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6938.90076172, 4925.76171875, 182.37919922), 'rotation':(-0.74295, 179.913315, -0.76239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6916.63171875, 4925.79833984, 182.09005859), 'rotation':(-0.748718, 179.913849, -0.768463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6905.49597656, 4925.81689453, 181.94447266), 'rotation':(-0.75116, 179.91391, -0.771057), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6872.09167969, 4925.87207031, 181.50269531), 'rotation':(-0.763031, 179.915253, -0.783569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6860.95691406, 4925.890625, 181.35431641), 'rotation':(-0.7677, 179.91539, -0.788483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.25525391, 4925.91845703, 181.13017578), 'rotation':(-0.771301, 179.914688, -0.792297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6827.55310547, 4925.94580078, 180.90460938), 'rotation':(-0.779388, 179.916306, -0.800812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6821.98572266, 4925.95507812, 180.82892578), 'rotation':(-0.782471, 179.916382, -0.804077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6810.85095703, 4925.97363281, 180.67675781000003), 'rotation':(-0.78595, 179.912186, -0.807739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.28357422, 4925.98291016, 180.60027344), 'rotation':(-0.789032, 179.916565, -0.811005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6794.14832031, 4926.00146484, 180.44652344), 'rotation':(-0.795593, 179.916748, -0.817932), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6788.5809375, 4926.01074219, 180.36921875), 'rotation':(-0.796875, 179.916687, -0.819275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6799.69666016, 4934.37304688, 180.52308594), 'rotation':(0.789017, -0.083435, 0.767508), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.26404297, 4934.36376953, 180.59982422000002), 'rotation':(0.78595, -0.087799, 0.764599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6810.83142578, 4934.35498047, 180.67630859000002), 'rotation':(0.782466, -0.083618, 0.761304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6816.39832031, 4934.34570312, 180.7525), 'rotation':(0.782466, -0.083618, 0.761304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6833.10046875, 4934.31787109, 180.97958984000002), 'rotation':(0.772829, -0.083862, 0.752181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6844.23523438, 4934.29931641, 181.12970703), 'rotation':(0.770186, -0.084534, 0.749692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6849.80212891, 4934.29003906, 181.20460938), 'rotation':(0.770186, -0.084534, 0.749692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6855.36951172, 4934.28076172, 181.27933593999998), 'rotation':(0.767706, -0.084595, 0.747329), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6860.93738281, 4934.27148438, 181.35384765999999), 'rotation':(0.765357, -0.084686, 0.745116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6866.50476562, 4934.26220703, 181.428125), 'rotation':(0.763014, -0.084747, 0.742896), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6888.77478516, 4934.22509766, 181.72404297), 'rotation':(0.755897, -0.085968, 0.736138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6905.47693359, 4934.19775391, 181.94404297), 'rotation':(0.748759, -0.086151, 0.729383), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6916.61169922, 4934.17919922, 182.08962891), 'rotation':(0.746464, -0.086212, 0.727188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6933.31433594, 4934.15185547, 182.3065625), 'rotation':(0.742892, -0.08667, 0.723817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6950.01697266, 4934.125, 182.52283203), 'rotation':(0.736745, -0.085754, 0.71798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6961.15173828, 4934.11425781, 182.66609375), 'rotation':(0.735727, -0.084229, 0.717008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6978.49597656, 4934.1484375, 182.88853516), 'rotation':(0.731698, -0.088226, 0.713187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6988.99011719, 4934.19628906, 183.02240234), 'rotation':(0.727675, -0.084442, 0.709365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(7000.12537109, 4934.17822266, 183.16386719), 'rotation':(0.725482, -0.088409, 0.707278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(7011.26013672, 4934.15966797, 183.30470703), 'rotation':(0.721575, -0.088501, 0.703575), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6002.5809375, 5511.42285156, 165.11753906), 'rotation':(-0.988922, -179.74205, -1.023529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6039.75820312, 5511.58546875, 165.75560547), 'rotation':(-0.978943, -179.732925, -1.012848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6045.06875, 5511.60890625, 165.84619141), 'rotation':(-0.976166, -179.733002, -1.009857), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6055.69125, 5511.65527344, 166.02681640999998), 'rotation':(-0.972961, -179.733124, -1.006439), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6002.56578125, 5519.80371094, 165.11791015999998), 'rotation':(0.985432, 0.270056, 0.951957), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6007.87484375, 5519.82664062, 165.20925781000003), 'rotation':(0.983322, 0.268149, 0.949993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6018.4940625, 5519.87304688, 165.39164062), 'rotation':(0.983452, 0.265243, 0.950127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6034.42273438, 5519.94289062, 165.665), 'rotation':(0.978957, 0.267076, 0.945911), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6039.73234375, 5519.96632812, 165.75578125), 'rotation':(0.976164, 0.266999, 0.943303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6292.71421875, 5512.69238281, 169.99410156000002), 'rotation':(-0.958405, -179.732254, -0.990906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6281.33140625, 5512.64257812, 169.80375), 'rotation':(-0.955811, -179.737915, -0.988098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6241.49109375, 5512.46875, 169.13929688), 'rotation':(-0.954407, -179.732773, -0.986603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6235.7996875, 5512.44382812, 169.04443359), 'rotation':(-0.954407, -179.732773, -0.986603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6230.10828125, 5512.41894531, 168.94958984000002), 'rotation':(-0.953979, -179.734146, -0.986176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.416875, 5512.3940625, 168.85476562), 'rotation':(-0.954102, -179.734131, -0.986298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6218.72546875, 5512.36914062, 168.75994140999998), 'rotation':(-0.954102, -179.734131, -0.986298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6213.0340625, 5512.34375, 168.66513672000002), 'rotation':(-0.954163, -179.734116, -0.986359), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6207.34265625, 5512.31882812, 168.57033203), 'rotation':(-0.954102, -179.730759, -0.986298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6184.57703125, 5512.21972656, 168.19103515999998), 'rotation':(-0.954529, -179.735168, -0.986725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6178.885625, 5512.19484375, 168.09621094), 'rotation':(-0.95462, -179.729614, -0.986847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6173.19421875, 5512.16945312, 168.00134766), 'rotation':(-0.954529, -179.735168, -0.986725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6156.12, 5512.09472656, 167.71673828), 'rotation':(-0.955841, -179.734589, -0.988159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6144.7371875, 5512.04492188, 167.52667968999998), 'rotation':(-0.95755, -179.734528, -0.98999), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6292.68054688, 5521.07324219, 169.99416015999998), 'rotation':(0.959812, 0.267791, 0.928054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6286.98914062, 5521.04835938, 169.89888672), 'rotation':(0.958412, 0.267744, 0.926749), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6275.60632812, 5520.99851562, 169.70882812), 'rotation':(0.955796, 0.267662, 0.924292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6264.22398438, 5520.94875, 169.51900390999998), 'rotation':(0.955236, 0.265156, 0.923769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6252.84070312, 5520.89890625, 169.32916016), 'rotation':(0.95512, 0.268925, 0.923666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6213.00085938, 5520.72507812, 168.66519531000003), 'rotation':(0.954109, 0.265853, 0.92271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6201.61804688, 5520.67480469, 168.47556641), 'rotation':(0.95415, 0.269248, 0.92276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6184.54382812, 5520.60007812, 168.19109375), 'rotation':(0.95443, 0.265949, 0.923017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6161.77867188, 5520.50046875, 167.81169922), 'rotation':(0.954608, 0.27038, 0.923189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6156.08726562, 5520.47558594, 167.71679688), 'rotation':(0.954826, 0.265351, 0.923385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6150.39585938, 5520.45070312, 167.62181640999998), 'rotation':(0.955844, 0.265407, 0.924334), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6139.01304688, 5520.40085938, 167.43158203), 'rotation':(0.957551, 0.270449, 0.925943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6127.62976562, 5520.35109375, 167.24101561999998), 'rotation':(0.959266, 0.265522, 0.927535), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6099.17375, 5520.2265625, 166.76328125), 'rotation':(0.963562, 0.267145, 0.931544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6093.4828125, 5520.20164062, 166.66738281000002), 'rotation':(0.965065, 0.267195, 0.932955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.15125, 5521.2153125, 170.53853515999998), 'rotation':(0.961492, 0.266157, 0.929624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6341.77234375, 5521.28859375, 170.81777344), 'rotation':(0.96516, 0.266194, 0.933046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6347.31289062, 5521.31296875, 170.91109375), 'rotation':(0.96516, 0.266194, 0.933046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6352.85289062, 5521.33691406, 171.00445312), 'rotation':(0.965215, 0.269558, 0.93309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6363.93296875, 5521.38574219, 171.19119141), 'rotation':(0.96527, 0.266197, 0.933144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6380.5540625, 5521.45800781, 171.47144531), 'rotation':(0.968172, 0.265582, 0.935862), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6391.63414062, 5521.50632812, 171.659375), 'rotation':(0.976539, 0.266773, 0.943669), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6402.71472656, 5521.5546875, 171.84824218999998), 'rotation':(0.976676, 0.266778, 0.943789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6413.79480469, 5521.60351562, 172.03714843999998), 'rotation':(0.976539, 0.270877, 0.943662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6424.87539062, 5521.651875, 172.22619140999998), 'rotation':(0.980016, 0.268325, 0.946904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6435.9559375, 5521.70070312, 172.41578125), 'rotation':(0.982454, 0.268426, 0.949177), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6452.5765625, 5521.77296875, 172.70140625), 'rotation':(0.985924, 0.26999, 0.952415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6458.1165625, 5521.80078125, 172.79677734), 'rotation':(0.987584, 0.267522, 0.953959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6463.65613281, 5521.8671875, 172.89224609000001), 'rotation':(0.987584, 0.267522, 0.953959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6461.60195312, 5513.41503906, 172.85619140999998), 'rotation':(-0.985931, -179.734695, -1.020294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6452.6434375, 5513.39304688, 172.70193359), 'rotation':(-0.985931, -179.730011, -1.020325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6436.02332031, 5513.31984375, 172.41628906000003), 'rotation':(-0.980011, -179.735672, -1.013977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6430.4828125, 5513.29589844, 172.32140625), 'rotation':(-0.977844, -179.731735, -1.011658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6424.94273438, 5513.27148438, 172.22671875), 'rotation':(-0.977844, -179.731735, -1.011658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6419.40171875, 5513.24707031, 172.13214843999998), 'rotation':(-0.976532, -179.733215, -1.010284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6413.86171875, 5513.22265625, 172.03767578), 'rotation':(-0.976471, -179.733246, -1.010193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6402.78113281, 5513.17429688, 171.84873047000002), 'rotation':(-0.976532, -179.733215, -1.010284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6391.70054688, 5513.12597656, 171.65988281000003), 'rotation':(-0.973633, -179.734253, -1.007172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6386.16054688, 5513.10203125, 171.56568359000002), 'rotation':(-0.96817, -179.730804, -1.001312), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6380.62, 5513.07765625, 171.47193359000002), 'rotation':(-0.96521, -179.73381, -0.998169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6369.53945312, 5513.02882812, 171.28505859), 'rotation':(-0.965271, -179.733795, -0.99823), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6358.45886719, 5512.98046875, 171.09832031000002), 'rotation':(-0.96521, -179.73381, -0.998169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6341.8378125, 5512.90773438, 170.81826172), 'rotation':(-0.964081, -179.733734, -0.996948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6336.29726562, 5512.88328125, 170.725), 'rotation':(-0.961517, -179.733841, -0.994202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.7571875, 5512.85890625, 170.63199218999998), 'rotation':(-0.960297, -179.733856, -0.992889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6325.2171875, 5512.83496094, 170.53902344), 'rotation':(-0.960297, -179.733856, -0.992889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6739.30554688, 5514.64746094, 177.86796875), 'rotation':(-1.083435, -179.72644, -1.125031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.64734375, 5514.62257812, 177.76074218999997), 'rotation':(-1.083435, -179.72644, -1.125031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.67224609, 5514.54835938, 177.44068359000002), 'rotation':(-1.07428, -179.726425, -1.115173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6705.35535156, 5514.49902344, 177.22833984000002), 'rotation':(-1.072662, -179.731934, -1.113434), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6688.38025391, 5514.42429688, 176.91103515999998), 'rotation':(-1.063782, -179.727585, -1.103851), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6671.405625, 5514.35007812, 176.59615234), 'rotation':(-1.057922, -179.732483, -1.097565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.74792969, 5514.32519531, 176.49173828), 'rotation':(-1.054993, -179.727905, -1.094421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6660.08875, 5514.30078125, 176.38759765999998), 'rotation':(-1.052002, -179.732712, -1.091187), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6654.43007812, 5514.27585938, 176.28367188), 'rotation':(-1.05069, -179.729889, -1.089783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6648.77136719, 5514.25097656, 176.17988281), 'rotation':(-1.048706, -179.730286, -1.087646), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6631.79625, 5514.17675781, 175.86949219), 'rotation':(-1.041077, -179.730576, -1.079468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6626.13804688, 5514.15234375, 175.7665625), 'rotation':(-1.03714, -179.730728, -1.075195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6614.82117188, 5514.10253906, 175.56134766), 'rotation':(-1.035461, -179.731003, -1.073395), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.50429688, 5514.05273438, 175.35669922), 'rotation':(-1.035278, -179.731033, -1.073212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6592.186875, 5514.0034375, 175.15234375), 'rotation':(-1.027802, -179.728821, -1.065216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.52820312, 5513.97851562, 175.05054688), 'rotation':(-1.027802, -179.728821, -1.065216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6580.87, 5513.95410156, 174.9490625), 'rotation':(-1.022827, -179.732605, -1.059845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6575.21132812, 5513.92921875, 174.84800781), 'rotation':(-1.017883, -179.729187, -1.054565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6563.8934375, 5513.87988281, 174.646875), 'rotation':(-1.015259, -179.730225, -1.051758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.23523438, 5513.855, 174.54654297000002), 'rotation':(-1.015289, -179.734039, -1.051758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.57703125, 5513.83007812, 174.44623047000002), 'rotation':(-1.013672, -179.731415, -1.050049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6518.62585938, 5513.68164062, 173.84775391), 'rotation':(-1.003662, -179.728821, -1.039307), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6512.96667969, 5513.65671875, 173.74859375), 'rotation':(-1.001831, -179.733673, -1.037354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.30847656, 5513.63183594, 173.64960938000002), 'rotation':(-1.000885, -179.732956, -1.036346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6507.21523438, 5522.0121875, 173.64861327999998), 'rotation':(1.001825, 0.266329, 0.967244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6512.87390625, 5522.03710938, 173.74761718999997), 'rotation':(1.003655, 0.268236, 0.968934), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6524.19078125, 5522.08691406, 173.94597656000002), 'rotation':(1.006906, 0.268337, 0.971972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6529.84949219, 5522.11179688, 174.04544922000002), 'rotation':(1.01028, 0.268466, 0.975109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6535.5071875, 5522.13625, 174.14511718999998), 'rotation':(1.01028, 0.268466, 0.975109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6541.16589844, 5522.16113281, 174.24494141), 'rotation':(1.013689, 0.268585, 0.978282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6552.4828125, 5522.21046875, 174.44521484), 'rotation':(1.01528, 0.269776, 0.979757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6558.14050781, 5522.23535156, 174.54550781), 'rotation':(1.01528, 0.269776, 0.979757), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6563.79921875, 5522.25976562, 174.64583984), 'rotation':(1.017896, 0.267201, 0.982188), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6575.11609375, 5522.30957031, 174.84695312), 'rotation':(1.022807, 0.270997, 0.986764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6580.77429688, 5522.33445312, 174.94802734), 'rotation':(1.027814, 0.267555, 0.991411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6586.43296875, 5522.35890625, 175.04949219), 'rotation':(1.032888, 0.271348, 0.996122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6592.09117188, 5522.38378906, 175.15126952999998), 'rotation':(1.032888, 0.271348, 0.996122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6603.40808594, 5522.43359375, 175.355625), 'rotation':(1.035443, 0.268975, 0.998513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6609.06628906, 5522.45851562, 175.45792969), 'rotation':(1.035443, 0.268975, 0.998513), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6626.04089844, 5522.53273438, 175.76546875), 'rotation':(1.041098, 0.269423, 1.003755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6643.01550781, 5522.61570312, 176.07511719), 'rotation':(1.0487, 0.269703, 1.010818), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6648.67371094, 5522.61085938, 176.17875), 'rotation':(1.050695, 0.270104, 1.012661), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6659.99011719, 5522.64796875, 176.38646484), 'rotation':(1.055005, 0.272084, 1.016666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6665.64832031, 5522.67285156, 176.49058594), 'rotation':(1.057921, 0.26751, 1.019379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6676.96472656, 5522.7221875, 176.69966797), 'rotation':(1.060988, 0.272304, 1.022221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6688.28064453, 5522.77195312, 176.90984375), 'rotation':(1.066834, 0.272523, 1.027631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6693.93982422, 5522.796875, 177.01537109), 'rotation':(1.069744, 0.27263, 1.030341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6705.25525391, 5522.84617188, 177.22714843999998), 'rotation':(1.074122, 0.273563, 1.0344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6716.57166016, 5522.89601562, 177.43949218999998), 'rotation':(1.075946, 0.273246, 1.036088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6722.229375, 5522.92039062, 177.54583984), 'rotation':(1.0796, 0.269604, 1.039477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6727.88757812, 5522.9453125, 177.65251952999998), 'rotation':(1.083446, 0.269772, 1.043023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6733.54578125, 5522.97023438, 177.75951172), 'rotation':(1.087018, 0.273666, 1.046345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6744.86072266, 5523.18945312, 177.97416016), 'rotation':(1.089012, 0.271815, 1.048189), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6750.51892578, 5523.214375, 178.08175781000003), 'rotation':(1.088978, 0.27183, 1.048145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6993.19861328, 5515.75878906, 182.73949219), 'rotation':(-1.058228, -179.732269, -1.09787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6987.51746094, 5515.73390625, 182.634375), 'rotation':(-1.063385, -179.726562, -1.103424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6981.83630859, 5515.70898438, 182.52865234), 'rotation':(-1.068726, -179.731888, -1.109161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6976.15564453, 5515.6840625, 182.42238281000002), 'rotation':(-1.079376, -179.731476, -1.120667), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6964.79382812, 5515.63429688, 182.20804688), 'rotation':(-1.090057, -179.731079, -1.132141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6942.06970703, 5515.53515625, 181.77351562), 'rotation':(-1.098022, -179.728714, -1.140747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6930.70789062, 5515.48535156, 181.55548828), 'rotation':(-1.100494, -179.729385, -1.143402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6925.02673828, 5515.46046875, 181.44632812), 'rotation':(-1.105316, -179.726288, -1.14859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6919.34558594, 5515.43554688, 181.33666015999998), 'rotation':(-1.107788, -179.728973, -1.151276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6896.62195312, 5515.3359375, 180.89726561999998), 'rotation':(-1.107788, -179.728973, -1.151276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6885.25916016, 5515.28613281, 180.67744141), 'rotation':(-1.107788, -179.728973, -1.151276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6879.57800781, 5515.26125, 180.56753906000003), 'rotation':(-1.109497, -179.727371, -1.153107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6873.89685547, 5515.23632812, 180.45748047), 'rotation':(-1.111023, -179.726242, -1.154755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6868.21619141, 5515.21140625, 180.34730469), 'rotation':(-1.111176, -179.726242, -1.154938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6862.53503906, 5515.18652344, 180.23707031), 'rotation':(-1.111053, -179.731308, -1.154816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6856.85388672, 5515.16164062, 180.12685547), 'rotation':(-1.111023, -179.726242, -1.154755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6851.17273438, 5515.13671875, 180.01664062), 'rotation':(-1.110596, -179.727386, -1.154297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6839.80994141, 5515.08742188, 179.79634765999998), 'rotation':(-1.108765, -179.727448, -1.152313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6834.12878906, 5515.0625, 179.68634766), 'rotation':(-1.107635, -179.727509, -1.151093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6822.76599609, 5515.01269531, 179.46660156000002), 'rotation':(-1.105713, -179.727585, -1.149017), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6817.08435547, 5514.9878125, 179.356875), 'rotation':(-1.104919, -179.7276, -1.148193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.72253906, 5514.93796875, 179.13773438), 'rotation':(-1.103271, -179.72995, -1.146393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6794.36511719, 5514.88328125, 178.91888672000002), 'rotation':(-1.101654, -179.725388, -1.144653), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6788.68591797, 5514.76320312, 178.80962891), 'rotation':(-1.098267, -179.729156, -1.141022), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6805.62097656, 5523.31882812, 179.13646484), 'rotation':(1.103786, 0.272339, 1.06185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6811.30212891, 5523.34375, 179.24599609), 'rotation':(1.104913, 0.272407, 1.062885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6816.98328125, 5523.36867188, 179.35564452999998), 'rotation':(1.105705, 0.272412, 1.063629), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6834.02722656, 5523.44289062, 179.68507812), 'rotation':(1.108745, 0.272554, 1.06644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6862.43347656, 5523.56738281, 180.23580077999998), 'rotation':(1.111169, 0.27376, 1.068682), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6885.15808594, 5523.66648438, 180.67621093999998), 'rotation':(1.107788, 0.271019, 1.065542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6913.56384766, 5523.79296875, 181.22568359000002), 'rotation':(1.105302, 0.270786, 1.063249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6930.60681641, 5523.83300781, 181.55425781000002), 'rotation':(1.098021, 0.271287, 1.056512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6941.96912109, 5523.88234375, 181.77228516), 'rotation':(1.098042, 0.271276, 1.056543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6947.65076172, 5523.90722656, 181.88123047000002), 'rotation':(1.098042, 0.271276, 1.056543), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6964.69373047, 5523.98195312, 182.20685547000002), 'rotation':(1.084736, 0.274236, 1.044211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6976.05603516, 5524.03171875, 182.42119141), 'rotation':(1.074163, 0.273858, 1.03443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6981.73669922, 5524.05515625, 182.52748047), 'rotation':(1.063372, 0.273429, 1.024449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6987.41833984, 5524.0815625, 182.63320312), 'rotation':(1.058208, 0.267726, 1.019654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6993.09949219, 5524.10644531, 182.73832031), 'rotation':(1.05536, 0.268795, 1.017005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6998.78015625, 5524.30125, 182.84308593999998), 'rotation':(1.055496, 0.273419, 1.017138), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6325.41882812, 5730.27390625, 170.59378906), 'rotation':(0.915307, 0.550166, 0.886414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6330.95640625, 5730.32570312, 170.68230469), 'rotation':(0.91239, 0.553102, 0.883662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6342.030625, 5730.4296875, 170.85871093999998), 'rotation':(0.909324, 0.550002, 0.880796), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6358.64441406, 5730.58546875, 171.12203125), 'rotation':(0.904816, 0.552877, 0.876572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6380.79382812, 5730.79296875, 171.47185547), 'rotation':(0.902275, 0.549953, 0.874181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6386.3309375, 5730.84523438, 171.55914062), 'rotation':(0.900676, 0.549901, 0.872695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6391.86902344, 5730.89695312, 171.64632812), 'rotation':(0.900676, 0.549901, 0.872695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6397.40664062, 5730.94875, 171.73339843999997), 'rotation':(0.898826, 0.553206, 0.870949), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6408.48132812, 5731.05273438, 171.90720703), 'rotation':(0.898115, 0.551706, 0.870291), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6430.6321875, 5731.26023438, 172.25482422000002), 'rotation':(0.900069, 0.551999, 0.872101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6436.16980469, 5731.31203125, 172.341875), 'rotation':(0.900731, 0.551978, 0.872734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6441.70742188, 5731.36421875, 172.42902343999998), 'rotation':(0.901722, 0.552052, 0.873662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6452.78257812, 5731.4678125, 172.60349609000002), 'rotation':(0.903374, 0.552105, 0.875223), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6463.8578125, 5731.57179688, 172.77828125), 'rotation':(0.90446, 0.552272, 0.876235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6469.499375, 5723.24367188, 172.86613281), 'rotation':(-0.904449, -179.451828, -0.93338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6458.42371094, 5723.1396875, 172.69125), 'rotation':(-0.90332, -179.447937, -0.932159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6452.88660156, 5723.08789062, 172.60390625), 'rotation':(-0.902466, -179.447922, -0.931244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6441.81140625, 5722.98390625, 172.42941406000003), 'rotation':(-0.900818, -179.447983, -0.929474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6430.7371875, 5722.88039062, 172.25523438), 'rotation':(-0.899292, -179.452866, -0.927887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6408.58582031, 5722.67234375, 171.90761719), 'rotation':(-0.898895, -179.446762, -0.927429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6403.04871094, 5722.620625, 171.82076172), 'rotation':(-0.898895, -179.446762, -0.927429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6397.51257812, 5722.56882812, 171.73382812), 'rotation':(-0.900696, -179.450104, -0.929352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6386.43738281, 5722.46484375, 171.55957031000003), 'rotation':(-0.902222, -179.450089, -0.931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6375.36265625, 5722.36132812, 171.38492188), 'rotation':(-0.904694, -179.451111, -0.933624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6358.75085938, 5722.20554688, 171.12248047), 'rotation':(-0.90625, -179.450119, -0.935272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6353.21277344, 5722.15382812, 171.03484375), 'rotation':(-0.909271, -179.446991, -0.938477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6336.6009375, 5721.99757812, 170.77103516), 'rotation':(-0.915375, -179.449799, -0.944977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6111.00523438, 5719.8828125, 167.00169922), 'rotation':(-1.016052, -179.444199, -1.052582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6116.698125, 5719.93601562, 167.10244140999998), 'rotation':(-1.013397, -179.443207, -1.049744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6128.08390625, 5720.04296875, 167.30353516), 'rotation':(-1.011261, -179.445419, -1.047424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6133.77671875, 5720.09617188, 167.40353516), 'rotation':(-1.006561, -179.445648, -1.042389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6150.85585938, 5720.25632812, 167.70101562), 'rotation':(-0.993103, -179.441483, -1.028015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6167.93445312, 5720.41648438, 167.99460938), 'rotation':(-0.979553, -179.446579, -1.013489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6179.32015625, 5720.5234375, 168.18900391), 'rotation':(-0.977417, -179.445511, -1.0112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6185.01359375, 5720.57664062, 168.28617188), 'rotation':(-0.977325, -179.448822, -1.011078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6196.39929688, 5720.683125, 168.47925781), 'rotation':(-0.972595, -179.443649, -1.006073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6207.78601562, 5720.78859375, 168.67029297000002), 'rotation':(-0.958313, -179.449188, -0.990814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6224.86460938, 5720.97507812, 168.95601562), 'rotation':(-0.958313, -179.444031, -0.990814), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6241.94421875, 5721.14359375, 169.23994141), 'rotation':(-0.948669, -179.447144, -0.980499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6247.63710938, 5721.19679688, 169.33375), 'rotation':(-0.948669, -179.447144, -0.980499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6253.33046875, 5721.25046875, 169.42734375), 'rotation':(-0.942261, -179.447372, -0.973663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6259.02328125, 5721.30375, 169.52035156000002), 'rotation':(-0.935822, -179.447586, -0.966797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6264.7171875, 5721.35695312, 169.61324219), 'rotation':(-0.935822, -179.447586, -0.966797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.41054688, 5721.41015625, 169.70595702999998), 'rotation':(-0.932617, -179.448074, -0.963348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6281.79820312, 5721.34671875, 169.89128906000002), 'rotation':(-0.932556, -179.44812, -0.963318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6287.49203125, 5721.40039062, 169.98376953), 'rotation':(-0.930206, -179.449814, -0.960785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6099.54484375, 5728.24851562, 166.79966797), 'rotation':(1.016038, 0.555792, 0.98047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6116.62148438, 5728.31640625, 167.10246094), 'rotation':(1.013457, 0.556828, 0.97807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6128.0071875, 5728.4228125, 167.30355468999997), 'rotation':(1.006633, 0.554401, 0.971711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6139.39296875, 5728.52976562, 167.50316406000002), 'rotation':(0.997597, 0.554044, 0.963292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6156.47203125, 5728.68992188, 167.79933594), 'rotation':(0.9841, 0.553621, 0.950712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6162.16445312, 5728.743125, 167.89720703), 'rotation':(0.97962, 0.553464, 0.946542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6184.93640625, 5728.95703125, 168.28617188), 'rotation':(0.972612, 0.552927, 0.940005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6196.32265625, 5729.0634375, 168.47927734), 'rotation':(0.963063, 0.555989, 0.931087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6202.015, 5729.1171875, 168.575), 'rotation':(0.958405, 0.550869, 0.926731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6207.70890625, 5729.17039062, 168.6703125), 'rotation':(0.958166, 0.555956, 0.926498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6219.09507812, 5729.28273438, 168.86082031), 'rotation':(0.958405, 0.550869, 0.926731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6224.78796875, 5729.34132812, 168.95607422), 'rotation':(0.955072, 0.553034, 0.923623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6230.48132812, 5729.36132812, 169.05101562), 'rotation':(0.948624, 0.55282, 0.917593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6236.17515625, 5729.40429688, 169.14568359), 'rotation':(0.948624, 0.55282, 0.917593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6241.86804688, 5729.4575, 169.23998047), 'rotation':(0.942313, 0.552641, 0.91169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6247.5609375, 5729.51078125, 169.33376952999998), 'rotation':(0.942313, 0.552641, 0.91169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6253.25429688, 5729.56445312, 169.42734375), 'rotation':(0.935811, 0.552402, 0.905609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':1, 'location':(6258.9471875, 5729.61765625, 169.52039062), 'rotation':(0.93256, 0.555033, 0.902569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6270.334375, 5729.72460938, 169.70597656), 'rotation':(0.932621, 0.551911, 0.90261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6281.718125, 5730.00148438, 169.89130859), 'rotation':(0.93021, 0.550186, 0.900363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6002.56679688, 5727.24703125, 165.01949219), 'rotation':(1.07445, 0.554385, 1.034703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6013.229375, 5727.3471875, 165.21960938), 'rotation':(1.071527, 0.558789, 1.031986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':1, 'location':(6018.55992188, 5727.3975, 165.31933593999997), 'rotation':(1.07154, 0.555308, 1.031997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6029.2215625, 5727.51515625, 165.51865234000002), 'rotation':(1.067422, 0.556937, 1.028186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6039.88320312, 5727.68992188, 165.71683593999998), 'rotation':(1.059267, 0.556636, 1.020632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6045.21421875, 5727.77640625, 165.81541016), 'rotation':(1.051228, 0.55634, 1.013164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':1, 'location':(6050.5453125, 5727.82664062, 165.91326172), 'rotation':(1.042984, 0.556035, 1.005523), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':1, 'location':(6054.39539062, 5719.22265625, 165.98244140999998), 'rotation':(-1.051239, -179.443665, -1.090363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':1, 'location':(6023.94570312, 5719.06640625, 165.41863281000002), 'rotation':(-1.071533, -179.441208, -1.112213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6018.60875, 5719.0165625, 165.31878906000003), 'rotation':(-1.071533, -179.441208, -1.112213), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':1, 'location':(6013.27234375, 5718.96679688, 165.21892577999998), 'rotation':(-1.074371, -179.445648, -1.115265), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6508.86375, 2478.89527344, 161.68060547), 'rotation':(0.964177, 28.7421, 0.932129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6489.13375, 2468.08277344, 161.29760742), 'rotation':(0.988759, 28.740435, 0.955064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6474.33785156, 2459.97460938, 161.00075195), 'rotation':(1.018456, 28.741476, 0.982704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6469.40570312, 2457.27148438, 160.89990234), 'rotation':(1.028367, 28.739697, 0.991928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6464.47359375, 2454.56859375, 160.79807617), 'rotation':(1.038243, 28.742193, 1.00111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6459.54242188, 2451.86597656, 160.69574219), 'rotation':(1.043202, 28.746025, 1.005716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6449.67820312, 2446.46046875, 160.48986328), 'rotation':(1.048796, 28.740164, 1.010907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6439.8134375, 2441.0544531200003, 160.28102539), 'rotation':(1.059895, 28.74358, 1.021204), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6434.8817968799995, 2438.35203125, 160.17576172), 'rotation':(1.071151, 28.744005, 1.031644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6415.15476562, 2427.54101562, 159.74820312), 'rotation':(1.097222, 28.74584, 1.055778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6395.42769531, 2416.73023438, 159.31291016), 'rotation':(1.115554, 28.744545, 1.072723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6380.6317968799995, 2408.6215625, 158.9809375), 'rotation':(1.13429, 28.747284, 1.090031), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6370.76898438, 2403.2165625, 158.75743164), 'rotation':(1.140573, 28.747879, 1.095816), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6360.9052343799995, 2397.81078125, 158.53251953), 'rotation':(1.147151, 28.745146, 1.101883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6331.3139062499995, 2381.59421875, 157.84904297), 'rotation':(1.163687, 28.748636, 1.117108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6326.38226562, 2378.89160156, 157.73464844), 'rotation':(1.165435, 28.747595, 1.118721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6316.51804688, 2373.48609375, 157.50503906), 'rotation':(1.168632, 28.747719, 1.121657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6311.58640625, 2370.78320312, 157.38980469), 'rotation':(1.172122, 28.745913, 1.124874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6306.65523438, 2368.08082031, 157.27435547), 'rotation':(1.175428, 28.747999, 1.127916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6296.79148438, 2362.6753125, 157.04313477), 'rotation':(1.177149, 28.749214, 1.129496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6286.9271874999995, 2357.26953125, 156.81192382999998), 'rotation':(1.177204, 28.747414, 1.129534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6281.9950781200005, 2354.56664062, 156.69630859), 'rotation':(1.177169, 28.747561, 1.129516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6267.19867188, 2346.45777344, 156.35025391), 'rotation':(1.173324, 28.748777, 1.125976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6262.2665625, 2343.75484375, 156.23501953000002), 'rotation':(1.173256, 28.746964, 1.125914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6252.40234375, 2338.34914062, 156.00455078000002), 'rotation':(1.173256, 28.746964, 1.125914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6247.4701562499995, 2335.64625, 155.88931641), 'rotation':(1.173324, 28.748777, 1.125976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6242.53703125, 2332.94289062, 155.77427734), 'rotation':(1.170961, 28.747408, 1.123793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6237.60492188, 2330.24, 155.65966797), 'rotation':(1.166712, 28.747236, 1.119897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6512.89058594, 2471.54539062, 161.68058594000001), 'rotation':(-0.96405, -151.259796, -0.996948), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6503.0263281200005, 2466.13914062, 161.49077148), 'rotation':(-0.979004, -151.259888, -1.012909), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6498.09371094, 2463.43628906, 161.39466797), 'rotation':(-0.98877, -151.259552, -1.023346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6468.5009375, 2447.21875, 160.79806641), 'rotation':(-1.043152, -151.257721, -1.081696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6438.90960938, 2431.00171875, 160.17576172), 'rotation':(-1.082214, -151.255585, -1.123718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6429.04632812, 2425.59644531, 159.96291015999998), 'rotation':(-1.090973, -151.254395, -1.133118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6409.31832031, 2414.78492188, 159.53154297), 'rotation':(-1.109558, -151.255676, -1.153168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6399.45554688, 2409.37988281, 159.31291016), 'rotation':(-1.121887, -151.253189, -1.166504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6374.79683594, 2395.86671875, 158.75743164), 'rotation':(-1.147186, -151.251846, -1.193848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.0692968799995, 2385.05515625, 158.30578125), 'rotation':(-1.160431, -151.251328, -1.208191), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6340.27390625, 2376.94703125, 157.96332031), 'rotation':(-1.163635, -151.254333, -1.21167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6330.41015625, 2371.54148438, 157.73463867), 'rotation':(-1.168732, -151.250137, -1.217163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6325.4784375, 2368.83886719, 157.61998047), 'rotation':(-1.172119, -151.252121, -1.220825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6310.68304688, 2360.73046875, 157.27432617), 'rotation':(-1.177094, -151.252594, -1.226227), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6305.7514062499995, 2358.0278125, 157.1587207), 'rotation':(-1.177185, -151.252426, -1.226318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6295.8871875, 2352.62207031, 156.92749023), 'rotation':(-1.177216, -151.252579, -1.226349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6290.955, 2349.91917969, 156.8119043), 'rotation':(-1.177155, -151.250778, -1.226288), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6286.02289062, 2347.21632812, 156.69626953), 'rotation':(-1.175171, -151.25296, -1.224152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6281.0912499999995, 2344.51367188, 156.58083984), 'rotation':(-1.173248, -151.253021, -1.222076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6276.15867188, 2341.81054688, 156.46546875), 'rotation':(-1.173248, -151.253021, -1.222076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6271.2265625, 2339.10765625, 156.35023438), 'rotation':(-1.173309, -151.251221, -1.222168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6266.2943749999995, 2336.40476562, 156.23498046999998), 'rotation':(-1.173248, -151.253021, -1.222076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6251.49796875, 2328.29617188, 155.88929688), 'rotation':(-1.171021, -151.250244, -1.219666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6246.5653906200005, 2325.5928125, 155.77425781), 'rotation':(-1.166718, -151.252762, -1.214996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6241.63328125, 2322.88992188, 155.6596875), 'rotation':(-1.162018, -151.252945, -1.2099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6236.70109375, 2320.18679688, 155.54549805), 'rotation':(-1.157776, -151.253128, -1.205322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6202.2465625, 2301.1575000000003, 154.75417969), 'rotation':(-1.133087, -151.253189, -1.178589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6188.83148438, 2293.90820312, 154.45494141), 'rotation':(-1.111481, -151.253891, -1.155273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6173.45992188, 2285.52929688, 154.11637695), 'rotation':(-1.106171, -151.254745, -1.149536), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6168.4853125, 2282.80273438, 154.00680664), 'rotation':(-1.093872, -151.255127, -1.136261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6158.5341406200005, 2277.34960938, 153.78957031), 'rotation':(-1.069397, -151.257446, -1.109863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6143.60789062, 2269.1696875, 153.47279297), 'rotation':(-1.057159, -151.257889, -1.096741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6123.70648438, 2258.2629687500003, 153.05582031), 'rotation':(-1.026825, -151.256683, -1.064148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.82609375, 2244.62867188, 152.55923828000002), 'rotation':(-0.976379, -151.26236, -1.010101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6093.85101562, 2241.90210938, 152.46249023000001), 'rotation':(-0.966095, -151.260208, -0.999115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6083.8984375, 2236.4479687499997, 152.27104492), 'rotation':(-0.945496, -151.26088, -0.977112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6078.9232812499995, 2233.7214062499997, 152.17738281), 'rotation':(-0.924835, -151.260208, -0.955078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6073.9453125, 2230.993125, 152.08431640999999), 'rotation':(-0.924835, -151.260208, -0.955078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6063.9935937499995, 2225.53953125, 151.90222656), 'rotation':(-0.904266, -151.262222, -0.933167), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6039.11179688, 2211.9035937500003, 151.46378906), 'rotation':(-0.843872, -151.262787, -0.869019), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6009.5497656200005, 2195.55492188, 150.98782227), 'rotation':(-0.779572, -151.265076, -0.800995), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6005.1849999999995, 2202.8671875, 150.98356445), 'rotation':(0.779557, 28.734911, 0.758564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6015.13671875, 2208.32125, 151.13837891), 'rotation':(0.801024, 28.733589, 0.778861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6030.064375, 2216.50242188, 151.37951171999998), 'rotation':(0.84389, 28.734819, 0.819298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6049.9701562499995, 2227.41085938, 151.7230957), 'rotation':(0.894031, 28.737883, 0.866448), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6059.92132812, 2232.86476562, 151.90141602), 'rotation':(0.924794, 28.738426, 0.895287), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6079.82421875, 2243.77195312, 152.27015625), 'rotation':(0.966158, 28.74114, 0.933969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.77585938, 2249.225625, 152.46158203000002), 'rotation':(0.976348, 28.740055, 0.943489), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.7265625, 2254.67898438, 152.65541016), 'rotation':(0.986511, 28.740448, 0.952959), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6104.70164062, 2257.40554688, 152.75314453000001), 'rotation':(1.006824, 28.742718, 0.971886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.62835938, 2265.58570312, 153.05479492), 'rotation':(1.046986, 28.742596, 1.00923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6129.578125, 2271.04, 153.26229492000002), 'rotation':(1.057149, 28.74333, 1.018657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6139.535625, 2276.4778125000003, 153.47170898000002), 'rotation':(1.05706, 28.74209, 1.018586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.4701562499995, 2284.6418750000003, 153.7884375), 'rotation':(1.0938, 28.744751, 1.052611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6159.44429688, 2287.36789062, 153.89677734), 'rotation':(1.106156, 28.745235, 1.064039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.34320312, 2298.2734375, 154.33433594), 'rotation':(1.111408, 28.745945, 1.068897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6184.23625, 2301.14890625, 154.44427734), 'rotation':(1.122323, 28.74473, 1.078976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6999.32710938, 2768.45898438, 167.06550781), 'rotation':(-0.344299, 179.840866, -0.34848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6988.03658203, 2768.49097656, 166.9975), 'rotation':(-0.348724, 179.840927, -0.352966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.39058594, 2768.50707031, 166.96320312), 'rotation':(-0.3508, 179.840942, -0.355133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6976.74605469, 2768.52294922, 166.92867188), 'rotation':(-0.352997, 179.838608, -0.357391), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6971.09957031, 2768.53882812, 166.89396484), 'rotation':(-0.355286, 179.841003, -0.35968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6965.4540625, 2768.5546875, 166.8590625), 'rotation':(-0.3573, 179.841034, -0.361786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6942.87349609, 2768.61839844, 166.71746094), 'rotation':(-0.366669, 179.838913, -0.371399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6931.58296875, 2768.65039062, 166.64492188), 'rotation':(-0.375061, 179.83902, -0.379974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6920.29146484, 2768.68212891, 166.57064452999998), 'rotation':(-0.383118, 179.841782, -0.388275), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6892.06587891, 2768.76171875, 166.37824218999998), 'rotation':(-0.39856, 179.839569, -0.404144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6886.42085938, 2768.77783203, 166.33896484000002), 'rotation':(-0.408997, 179.841324, -0.414856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6869.48482422, 2768.82568359, 166.21675781000002), 'rotation':(-0.429962, 179.841644, -0.436462), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.83931641, 2768.8415625, 166.17455078), 'rotation':(-0.435242, 179.841431, -0.441895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6841.26021484, 2768.90527344, 166.00205078), 'rotation':(-0.453369, 179.840454, -0.460602), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6835.61470703, 2768.92113281, 165.95753906000002), 'rotation':(-0.46048, 179.842896, -0.467926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.9696875, 2768.93701172, 165.91234375), 'rotation':(-0.46759, 179.840683, -0.475281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6813.03560547, 2768.98486328, 165.77275391), 'rotation':(-0.489288, 179.843384, -0.497711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6807.38960938, 2769.00244141, 165.72488281000003), 'rotation':(-0.489288, 179.843384, -0.497711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.74605469, 2769.01660156, 165.67652343999998), 'rotation':(-0.492859, 179.842957, -0.501404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.16792969, 2769.0803125, 165.47763672000002), 'rotation':(-0.529694, 179.843246, -0.539551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6767.87789062, 2769.11207031, 165.37232422), 'rotation':(-0.544281, 179.843536, -0.554718), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6762.24019531, 2769.10546875, 165.31867188), 'rotation':(-0.551697, 179.842117, -0.562408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6761.33296875, 2777.55761719, 165.3096875), 'rotation':(0.544284, -0.156464, 0.53402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6767.88765625, 2777.49292969, 165.37220703), 'rotation':(0.529702, -0.156738, 0.519972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6773.5321875, 2777.47705078, 165.4253125), 'rotation':(0.529702, -0.156738, 0.519972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.17769531, 2777.46117188, 165.4775), 'rotation':(0.514955, -0.157013, 0.505771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6784.82271484, 2777.4453125, 165.52839844), 'rotation':(0.500223, -0.157257, 0.491529), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6807.40181641, 2777.38134766, 165.72478515999998), 'rotation':(0.482164, -0.156738, 0.474099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6813.04683594, 2777.36546875, 165.77263672), 'rotation':(0.482164, -0.156738, 0.474099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6824.33736328, 2777.33349609, 165.86638672), 'rotation':(0.467602, -0.156982, 0.460013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6841.27193359, 2777.28564453, 166.00197265999998), 'rotation':(0.446045, -0.157318, 0.439152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6852.56246094, 2777.25367188, 166.0890625), 'rotation':(0.435226, -0.158569, 0.428648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.85298828, 2777.22167969, 166.17447266), 'rotation':(0.429988, -0.158356, 0.423568), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6875.14351562, 2777.18994141, 166.25800781), 'rotation':(0.408978, -0.158661, 0.403176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6886.43404297, 2777.15820312, 166.33890625), 'rotation':(0.398589, -0.158813, 0.393073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.36910156, 2777.11035156, 166.45591797), 'rotation':(0.391295, -0.160767, 0.385974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6914.66060547, 2777.07861328, 166.53277343999997), 'rotation':(0.383119, -0.158203, 0.378032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6931.59664062, 2777.03076172, 166.64486327999998), 'rotation':(0.370893, -0.158356, 0.366129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6937.24166016, 2777.01488281, 166.68134766), 'rotation':(0.366686, -0.161072, 0.362009), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6942.88814453, 2776.99878906, 166.71740234), 'rotation':(0.362663, -0.158447, 0.358102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6954.17867188, 2776.96679688, 166.78855468999998), 'rotation':(0.357308, -0.158966, 0.352875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6959.82417969, 2776.9509375, 166.82390625), 'rotation':(0.357308, -0.158966, 0.352875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6971.11519531, 2776.91917969, 166.89392578), 'rotation':(0.353011, -0.159027, 0.348689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6982.40621094, 2776.88695312, 166.96314453), 'rotation':(0.348715, -0.159058, 0.344494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6993.69722656, 2776.85498047, 167.03154297), 'rotation':(0.344276, -0.159119, 0.340157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6718.5321875, 2769.25171875, 164.88146484), 'rotation':(-0.615082, 179.846008, -0.628418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6707.22115234, 2769.28369141, 164.76035156), 'rotation':(-0.620361, 179.843658, -0.633881), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6701.56490234, 2769.29980469, 164.69910156000003), 'rotation':(-0.6203, 179.843674, -0.63382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6667.63226562, 2769.39527344, 164.31410156), 'rotation':(-0.687347, 179.847015, -0.70401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6650.6684375, 2769.44335938, 164.11074219), 'rotation':(-0.695709, 179.84671, -0.712769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6645.01167969, 2769.45921875, 164.04205077999998), 'rotation':(-0.712311, 179.847122, -0.730194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.70113281, 2769.49121094, 163.90212891), 'rotation':(-0.728943, 179.847504, -0.747681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.38960938, 2769.52320312, 163.75729492), 'rotation':(-0.745605, 179.847961, -0.765198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6611.08003906, 2769.55517578, 163.60921875), 'rotation':(-0.753998, 179.848099, -0.774048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6599.77, 2769.58691406, 163.45985352), 'rotation':(-0.761963, 179.848923, -0.78244), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6582.805625, 2769.63476562, 163.23027344), 'rotation':(-0.794281, 179.848251, -0.816559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6571.4950781200005, 2769.66699219, 163.07214844), 'rotation':(-0.81842, 179.850815, -0.842041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6560.18550781, 2769.69898438, 162.91118164), 'rotation':(-0.81842, 179.848694, -0.842072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6548.87640625, 2769.73095703, 162.74896484), 'rotation':(-0.841156, 179.849792, -0.86615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.91109375, 2769.77880859, 162.49956055), 'rotation':(-0.871613, 179.850708, -0.898438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6526.25582031, 2769.7946875, 162.41455078), 'rotation':(-0.871613, 179.850708, -0.898438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6514.94773438, 2769.82666016, 162.24186523), 'rotation':(-0.879211, 179.852264, -0.906525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6729.86763672, 2777.60035156, 164.99941406000002), 'rotation':(0.583066, -0.156708, 0.571286), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6724.211875, 2777.61644531, 164.94087890999998), 'rotation':(0.593612, -0.154449, 0.58141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6712.89986328, 2777.6484375, 164.82125), 'rotation':(0.60428, -0.156281, 0.591636), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6701.5888281200005, 2777.68042969, 164.69910156000003), 'rotation':(0.620331, -0.156342, 0.607011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6695.93453125, 2777.69628906, 164.63746093999998), 'rotation':(0.620277, -0.153656, 0.606963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6684.62300781, 2777.72828125, 164.51158203), 'rotation':(0.645453, -0.155029, 0.631033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6667.65621094, 2777.77613281, 164.31410156), 'rotation':(0.678996, -0.154236, 0.663033), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6662.00191406, 2777.79222656, 164.24646484000002), 'rotation':(0.687301, -0.152985, 0.670958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6656.34617188, 2777.80810547, 164.17859375), 'rotation':(0.687301, -0.152985, 0.670958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6650.69234375, 2777.82398438, 164.11074219), 'rotation':(0.687349, -0.152985, 0.671), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6645.03609375, 2777.83984375, 164.04205077999998), 'rotation':(0.695716, -0.15329, 0.678968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.06882812, 2777.88792969, 163.83013671999998), 'rotation':(0.728952, -0.152466, 0.710578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6616.75972656, 2777.9196875, 163.68370117), 'rotation':(0.745604, -0.152039, 0.726389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6605.4482031200005, 2777.95166016, 163.53480469), 'rotation':(0.753998, -0.151886, 0.734352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6599.79390625, 2777.96777344, 163.45985352), 'rotation':(0.753998, -0.151886, 0.734352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6582.82953125, 2778.015625, 163.23027344), 'rotation':(0.778081, -0.150635, 0.757159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6577.17378906, 2778.03173828, 163.15183594), 'rotation':(0.794283, -0.150177, 0.772485), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6565.86421875, 2778.06371094, 162.99199219), 'rotation':(0.810334, -0.151276, 0.787658), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6560.20945312, 2778.07958984, 162.91119141), 'rotation':(0.818421, -0.14917, 0.795289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6554.55367188, 2778.09546875, 162.83038086), 'rotation':(0.818421, -0.151306, 0.795284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.935, 2778.15941406, 162.49956055), 'rotation':(0.856485, -0.148132, 0.831157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6509.31585938, 2778.22339844, 162.15504883), 'rotation':(0.879209, -0.147705, 0.852518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6173.90671875, 2770.78929688, 156.58808594), 'rotation':(-0.870667, 179.852051, -0.897461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6190.73625, 2770.74195312, 156.84703125), 'rotation':(-0.878998, 179.851089, -0.906281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6201.95648438, 2770.71019531, 157.02404296999998), 'rotation':(-0.912262, 179.853577, -0.941681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6207.566875, 2770.69433594, 157.11376953), 'rotation':(-0.912262, 179.853577, -0.941681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6218.78609375, 2770.66259766, 157.29611328000001), 'rotation':(-0.928925, 179.852661, -0.959412), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6224.395, 2770.64671875, 157.38789062), 'rotation':(-0.937195, 179.853439, -0.968231), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6241.22359375, 2770.599375, 157.66460938), 'rotation':(-0.941315, 179.852493, -0.972656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6246.83296875, 2770.58349609, 157.75787109), 'rotation':(-0.949615, 179.85463, -0.981506), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6258.0521874999995, 2770.55175781, 157.94631836), 'rotation':(-0.966125, 179.853317, -0.999146), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6263.6615624999995, 2770.53589844, 158.04120117), 'rotation':(-0.970123, 179.855728, -1.003418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6269.27046875, 2770.52001953, 158.13620117), 'rotation':(-0.970123, 179.855728, -1.003418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6274.87984375, 2770.50414062, 158.23123046999999), 'rotation':(-0.970184, 179.8535, -1.003479), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6297.316875, 2770.43652344, 158.61311523), 'rotation':(-0.975433, 179.855392, -1.009064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6319.75390625, 2770.41064453, 159.00099609), 'rotation':(-0.991241, 179.856049, -1.026001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6325.36273438, 2770.39476562, 159.09803711), 'rotation':(-0.990753, 179.856308, -1.025452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6330.97265625, 2770.37890625, 159.19499023), 'rotation':(-0.990021, 179.853683, -1.024689), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6347.79929688, 2770.33128906, 159.48530273), 'rotation':(-0.987274, 179.853577, -1.021729), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6359.0165625, 2770.29980469, 159.67835938), 'rotation':(-0.985474, 179.856125, -1.019836), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.6264062499995, 2770.28394531, 159.77478516), 'rotation':(-0.984497, 179.8535, -1.018799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6370.2353125, 2770.26806641, 159.87115234), 'rotation':(-0.983887, 179.855103, -1.018127), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6381.45359375, 2770.2365625, 160.06376953), 'rotation':(-0.981842, 179.856644, -1.01593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6392.67183594, 2770.20484375, 160.25535156), 'rotation':(-0.977661, 179.854279, -1.011475), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6403.8896093799995, 2770.17308594, 160.44547852), 'rotation':(-0.969177, 179.856216, -1.002411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6415.1083593799995, 2770.14160156, 160.63490234), 'rotation':(-0.967133, 179.854568, -1.000214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6420.71820312, 2770.12574219, 160.72946289), 'rotation':(-0.964233, 179.853668, -0.997101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6431.93601562, 2770.09398438, 160.91714844), 'rotation':(-0.953278, 179.855881, -0.985413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6443.15425781, 2770.06226562, 161.10258789), 'rotation':(-0.942322, 179.852921, -0.973694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6454.3724999999995, 2770.03050781, 161.28581055), 'rotation':(-0.931366, 179.85257, -0.962036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6459.98140625, 2770.01464844, 161.37657227), 'rotation':(-0.925812, 179.852371, -0.956085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6465.5912499999995, 2769.99902344, 161.46704102), 'rotation':(-0.923035, 179.853439, -0.953156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6476.90671875, 2778.31494141, 161.64868164), 'rotation':(0.915799, -0.147369, 0.886861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6471.2978125, 2778.33082031, 161.55862305), 'rotation':(0.915799, -0.147369, 0.886861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6465.68796875, 2778.34667969, 161.46821289), 'rotation':(0.923018, -0.146545, 0.893634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6454.47117188, 2778.37816406, 161.28703125), 'rotation':(0.925805, -0.147614, 0.896243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6448.86179688, 2778.39404297, 161.19569336), 'rotation':(0.931365, -0.144836, 0.90144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6437.64398438, 2778.42578125, 161.01139648), 'rotation':(0.942313, -0.147064, 0.911692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6432.03460938, 2778.44140625, 160.91837891), 'rotation':(0.947723, -0.144318, 0.916743), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6420.81636719, 2778.47314453, 160.73073242), 'rotation':(0.958829, -0.146545, 0.92713), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6392.7724218799995, 2778.55224609, 160.25666992), 'rotation':(0.973425, -0.145874, 0.940762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6387.1630468799995, 2778.568125, 160.16105469000001), 'rotation':(0.97766, -0.143494, 0.944709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6381.55414062, 2778.58398438, 160.06509766), 'rotation':(0.97766, -0.143494, 0.944709), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6375.94578125, 2778.59984375, 159.96885742), 'rotation':(0.981826, -0.145569, 0.948604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6308.6371875, 2778.78980469, 158.80818359), 'rotation':(0.991224, -0.143951, 0.957352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6303.02734375, 2778.80566406, 158.71109375), 'rotation':(0.991327, -0.145508, 0.957449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6291.80804688, 2778.83740234, 158.51820312), 'rotation':(0.985992, -0.144257, 0.952477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6286.19867188, 2778.85328125, 158.42266602), 'rotation':(0.975419, -0.144623, 0.942625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6280.58835938, 2778.86890625, 158.32751953000002), 'rotation':(0.970276, -0.146515, 0.937813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6269.37054688, 2778.900625, 158.1375), 'rotation':(0.970126, -0.144287, 0.937683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6258.1503125, 2778.93238281, 157.94756836), 'rotation':(0.970126, -0.144287, 0.937683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6246.9315625, 2778.96410156, 157.75912109), 'rotation':(0.957797, -0.146973, 0.92618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6235.7123437499995, 2778.99560547, 157.57310547), 'rotation':(0.949628, -0.145355, 0.918527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6230.1015625, 2779.01148438, 157.48087891), 'rotation':(0.94133, -0.14563, 0.910765), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6218.8828125, 2779.04320312, 157.29731445), 'rotation':(0.937191, -0.146576, 0.906897), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6207.66203125, 2779.07496094, 157.11491211), 'rotation':(0.928906, -0.147308, 0.899137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6196.4384375, 2779.10644531, 156.93582031), 'rotation':(0.912267, -0.146423, 0.883546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6190.8290625, 2779.12207031, 156.8480957), 'rotation':(0.895622, -0.148376, 0.867947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6185.21875, 2779.13818359, 156.76084961), 'rotation':(0.895622, -0.148376, 0.867947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.60984375, 2779.1540625, 156.67477539), 'rotation':(0.878977, -0.147461, 0.852313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6173.99796875, 2779.1696875, 156.58911133), 'rotation':(0.878977, -0.147461, 0.852313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6041.78609375, 2771.161875, 154.83030273), 'rotation':(-0.620789, 179.844574, -0.634338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6052.86375, 2771.130625, 154.95363281), 'rotation':(-0.643616, 179.845078, -0.658203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.4037499999995, 2771.115, 155.01787109), 'rotation':(-0.666687, 179.847183, -0.682343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6063.94234375, 2771.099375, 155.08300781), 'rotation':(-0.666687, 179.847183, -0.682343), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.4809375, 2771.08375, 155.14967773), 'rotation':(-0.689484, 179.846146, -0.706238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6075.01953125, 2771.068125, 155.21712890999999), 'rotation':(-0.700989, 179.846802, -0.718292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6080.5590625, 2771.0525, 155.28521484), 'rotation':(-0.700989, 179.846802, -0.718292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.1732812499995, 2771.005625, 155.49579101999998), 'rotation':(-0.74411, 179.848724, -0.763641), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6108.2514062499995, 2770.974375, 155.64235352), 'rotation':(-0.769165, 179.84938, -0.790039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6124.86664062, 2770.9275, 155.87095703), 'rotation':(-0.799866, 179.848007, -0.822449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6130.40421875, 2770.911875, 155.94830078), 'rotation':(-0.799927, 179.850723, -0.82254), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6124.90085938, 2779.30810547, 155.87111328), 'rotation':(0.799938, -0.151978, 0.777832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.36125, 2779.32373047, 155.79392578), 'rotation':(0.799863, -0.149261, 0.777762), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6113.82273438, 2779.33935547, 155.71758789), 'rotation':(0.793805, -0.152557, 0.772032), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6108.28460938, 2779.35498047, 155.6424707), 'rotation':(0.781326, -0.150299, 0.760225), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6086.129375, 2779.41773438, 155.35429688), 'rotation':(0.732032, -0.151581, 0.713504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6063.9740624999995, 2779.48023438, 155.08311523), 'rotation':(0.68948, -0.152252, 0.673048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.4349999999995, 2779.49585938, 155.01795898), 'rotation':(0.68948, -0.152252, 0.673048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.3559375, 2779.52710938, 154.89148438), 'rotation':(0.643622, -0.154907, 0.629273), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6144.92375, 3041.48876953, 157.96986328), 'rotation':(0.37495, 90.252213, 0.370064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6144.94773438, 3035.90185547, 157.9331543), 'rotation':(0.376043, 90.252228, 0.371125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.0209374999995, 3019.14111328, 157.82237305), 'rotation':(0.379315, 90.252281, 0.374325), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.04484375, 3013.55419922, 157.78526367), 'rotation':(0.380421, 90.252281, 0.375382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.06976562, 3007.96728516, 157.748125), 'rotation':(0.38081, 90.251984, 0.375771), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.14304688, 2991.20629883, 157.63660156), 'rotation':(0.381582, 90.252563, 0.376518), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.16742188, 2985.61938477, 157.5993457), 'rotation':(0.382135, 90.250389, 0.377058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.19140625, 2980.03271484, 157.56208984), 'rotation':(0.382135, 90.255669, 0.377049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.24015625, 2968.85864258, 157.48756836), 'rotation':(0.382293, 90.255669, 0.377214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.26460938, 2963.27148438, 157.4503125), 'rotation':(0.381849, 90.249702, 0.376794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.3134375, 2952.09765625, 157.37588867), 'rotation':(0.381316, 90.252571, 0.376271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.3378125, 2946.51049805, 157.33875), 'rotation':(0.381316, 90.252571, 0.376271), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.36179688, 2940.92358398, 157.30160156), 'rotation':(0.380776, 90.252563, 0.375751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.38617188, 2935.33666992, 157.26451172), 'rotation':(0.380776, 90.252563, 0.375751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.410625, 2929.74951172, 157.22743164), 'rotation':(0.380332, 90.252548, 0.375303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.50828125, 2907.40136719, 157.07926758), 'rotation':(0.380114, 90.247978, 0.375097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.5321875, 2901.81445312, 157.04239257999998), 'rotation':(0.378065, 90.253403, 0.373104), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.5810156200005, 2890.64013672, 156.96893555), 'rotation':(0.376302, 90.250534, 0.371393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.62984375, 2879.46606445, 156.89556641), 'rotation':(0.376302, 90.253609, 0.371393), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.65421875, 2873.87890625, 156.85897461000002), 'rotation':(0.375606, 90.251907, 0.370719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.703125, 2862.70483398, 156.78618164), 'rotation':(0.37204, 90.251862, 0.367229), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.7275, 2857.11791992, 156.74995117), 'rotation':(0.370886, 90.251831, 0.366101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.77585938, 2845.94384766, 156.67789062), 'rotation':(0.368468, 90.251801, 0.363751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.80023438, 2840.35668945, 156.64203125), 'rotation':(0.367314, 90.251785, 0.362625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.8246875, 2834.76976562, 156.60625), 'rotation':(0.366706, 90.257095, 0.362042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.89742188, 2818.0078125, 156.49946289), 'rotation':(0.362055, 90.25341, 0.357504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6145.970625, 2801.24609375, 156.39485352), 'rotation':(0.355552, 90.248993, 0.351164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.4003125, 2790.099375, 156.32573242), 'rotation':(-0.354065, -89.749359, -0.358459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6154.3515625, 2801.27320312, 156.39479492), 'rotation':(-0.354065, -89.746063, -0.35849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.254375, 2823.62183594, 156.53478515999998), 'rotation':(-0.362061, -89.746582, -0.366638), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.20554688, 2834.79638672, 156.60618164), 'rotation':(-0.366699, -89.748413, -0.371429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.1810937499995, 2840.38330078, 156.64197266), 'rotation':(-0.366699, -89.748413, -0.371429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.10789062, 2857.14453125, 156.74989258), 'rotation':(-0.369751, -89.748138, -0.374573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.01023438, 2879.49243164, 156.89550781), 'rotation':(-0.37561, -89.748108, -0.380554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.8646874999995, 2913.01489258, 157.11618164), 'rotation':(-0.380127, -89.746552, -0.385193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.7909375, 2929.77563477, 157.22735352), 'rotation':(-0.379944, -89.746552, -0.38501), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.74265625, 2940.94995117, 157.3015332), 'rotation':(-0.380341, -89.747437, -0.385406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.71820312, 2946.53686523, 157.33867188), 'rotation':(-0.380798, -89.747437, -0.385864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.6693749999995, 2957.71069336, 157.41300781), 'rotation':(-0.381317, -89.747406, -0.386414), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.62109375, 2968.88476562, 157.48749023), 'rotation':(-0.381866, -89.747406, -0.386993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.5721875, 2980.05859375, 157.56203125), 'rotation':(-0.382111, -89.749634, -0.387238), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.5478125, 2985.64526367, 157.59928711), 'rotation':(-0.382141, -89.744324, -0.387268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.49898438, 2996.81958008, 157.67375), 'rotation':(-0.381592, -89.747437, -0.386688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.47453125, 3002.40649414, 157.7109082), 'rotation':(-0.38092, -89.747986, -0.385986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.42578125, 3013.58032227, 157.78518555), 'rotation':(-0.380798, -89.747986, -0.385895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.3529687499995, 3030.34106445, 157.89625977), 'rotation':(-0.378204, -89.747742, -0.38324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.30414062, 3041.51489258, 157.96978516), 'rotation':(-0.376038, -89.747772, -0.381012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.27976562, 3047.10180664, 158.00639648), 'rotation':(-0.374939, -89.747772, -0.379883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6153.2309375, 3058.27587891, 158.07928711), 'rotation':(-0.372742, -89.747803, -0.377625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6309.71578125, 2095.54054688, 156.04670898), 'rotation':(-0.159515, 113.439232, -0.1604), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6305.21671875, 2105.91726562, 156.01454102), 'rotation':(-0.167969, 113.439285, -0.168945), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6302.96726562, 2111.10570312, 155.99782227), 'rotation':(-0.172241, 113.439301, -0.173309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6298.46921875, 2121.4821875, 155.96299805), 'rotation':(-0.184845, 113.439384, -0.186035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6296.2196875, 2126.6706249999997, 155.94491211000002), 'rotation':(-0.187012, 113.438866, -0.188232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6293.970625, 2131.8584375, 155.92654296999999), 'rotation':(-0.187012, 113.438866, -0.188232), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6291.72117188, 2137.046875, 155.90808594), 'rotation':(-0.189209, 113.43972, -0.19046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6289.4716406200005, 2142.23484375, 155.88945311999998), 'rotation':(-0.189209, 113.43972, -0.19046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6287.22265625, 2147.42335938, 155.87068359), 'rotation':(-0.193756, 113.440384, -0.195068), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6284.973125, 2152.6115625, 155.8515625), 'rotation':(-0.198181, 113.436874, -0.199554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6282.72359375, 2157.79984375, 155.83216797), 'rotation':(-0.198181, 113.436874, -0.199554), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6278.22507812, 2168.17648438, 155.79255859), 'rotation':(-0.204956, 113.439728, -0.206421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6271.47703125, 2183.74148438, 155.73188477), 'rotation':(-0.208069, 113.443466, -0.209564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6269.2275, 2188.9296875, 155.71136719), 'rotation':(-0.210022, 113.438141, -0.211548), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6262.47992188, 2204.4948437499997, 155.64862305), 'rotation':(-0.2164, 113.442574, -0.218048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6257.9809375, 2214.87132812, 155.60580078), 'rotation':(-0.220459, 113.438217, -0.222168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6253.48234375, 2225.24804688, 155.56228516), 'rotation':(-0.221436, 113.440475, -0.223145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6246.73382812, 2240.81273438, 155.49666016), 'rotation':(-0.222595, 113.439415, -0.224335), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6244.484375, 2246.00148438, 155.47466796999998), 'rotation':(-0.224854, 113.440224, -0.226624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6239.9857812499995, 2256.37820312, 155.43020508), 'rotation':(-0.22583, 113.440933, -0.227631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6235.48679688, 2266.75484375, 155.385625), 'rotation':(-0.225922, 113.440933, -0.227722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6233.23773438, 2271.94335938, 155.36333008), 'rotation':(-0.225922, 113.440933, -0.227722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6230.98828125, 2277.1315624999997, 155.34101562), 'rotation':(-0.225861, 113.437576, -0.227631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6226.48921875, 2287.50875, 155.29644531), 'rotation':(-0.225464, 113.442719, -0.227234), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6229.7509375, 2301.05421875, 155.2528125), 'rotation':(0.224324, -66.557312, 0.22258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6234.2465625, 2290.6848437500003, 155.29713867), 'rotation':(0.22584, -66.559662, 0.224064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6240.99015625, 2275.130625, 155.36395507999998), 'rotation':(0.225847, -66.559052, 0.22407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6245.4857812499995, 2264.76125, 155.40850586), 'rotation':(0.22584, -66.559662, 0.224064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6247.73335938, 2259.5768749999997, 155.43078125), 'rotation':(0.22584, -66.559662, 0.224064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6252.22898438, 2249.2075, 155.47521484), 'rotation':(0.222589, -66.560577, 0.220869), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6254.47703125, 2244.02296875, 155.4971875), 'rotation':(0.221428, -66.562225, 0.219731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6263.46773438, 2223.2846875, 155.58456055), 'rotation':(0.220465, -66.561798, 0.218767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6270.2109375, 2207.73070312, 155.64901367000002), 'rotation':(0.214188, -66.561829, 0.212586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6274.7060156200005, 2197.3615625, 155.69099609), 'rotation':(0.209994, -66.561859, 0.208464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6279.20164062, 2186.9921875, 155.73220703), 'rotation':(0.205964, -66.56189, 0.204491), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6281.44921875, 2181.8073437499997, 155.75251953), 'rotation':(0.20496, -66.560242, 0.203495), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6283.6971875, 2176.6228125, 155.77273438), 'rotation':(0.202727, -66.55954, 0.201298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6292.6884375, 2155.88476562, 155.85178711), 'rotation':(0.193745, -66.559631, 0.192436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6297.18359375, 2145.51539062, 155.88962891), 'rotation':(0.18699, -66.557343, 0.185788), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6301.6796875, 2135.14648438, 155.92669922), 'rotation':(0.187017, -66.561157, 0.185798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6312.91796875, 2109.22359375, 156.01462891), 'rotation':(0.163808, -66.56073, 0.162883), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6321.8046875, 2088.9296875, 156.07609375), 'rotation':(0.153256, -66.561188, 0.152441), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6212.32757812, 2341.2434375000003, 155.08214844), 'rotation':(0.221558, -66.560699, 0.219847), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6210.0834374999995, 2346.41945312, 155.06079102), 'rotation':(0.217111, -66.56073, 0.215464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6198.86273438, 2372.29957031, 154.95529297), 'rotation':(0.213382, -66.55954, 0.211792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6192.13078125, 2387.82738281, 154.89439453), 'rotation':(0.201846, -66.558624, 0.200426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6189.88671875, 2393.00390625, 154.87464844), 'rotation':(0.199018, -66.563293, 0.197634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6185.39890625, 2403.35546875, 154.83609375), 'rotation':(0.193315, -66.558685, 0.192015), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6180.910625, 2413.70800781, 154.79826172), 'rotation':(0.19171, -66.563263, 0.190425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6178.6669531200005, 2418.88402344, 154.77943359), 'rotation':(0.191833, -66.558594, 0.190552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6174.17867188, 2429.23609375, 154.74286132999998), 'rotation':(0.182578, -66.560333, 0.181406), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6169.6903906200005, 2439.58835938, 154.70819336), 'rotation':(0.176253, -66.561157, 0.175176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6160.7138281200005, 2460.29371094, 154.64238281), 'rotation':(0.164587, -66.558197, 0.163648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.4701562499995, 2465.46996094, 154.62666016), 'rotation':(0.159772, -66.562805, 0.158889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6156.22601562, 2470.64601562, 154.61141602), 'rotation':(0.15495, -66.561829, 0.154112), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6149.4935937499995, 2486.1740625, 154.56855469), 'rotation':(0.140463, -66.55835, 0.139769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.24945312, 2491.35007812, 154.55522461), 'rotation':(0.13549, -66.561951, 0.134852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.0053124999995, 2496.52734375, 154.54234375), 'rotation':(0.130805, -66.562958, 0.130212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6140.5165625, 2506.87964844, 154.51735352), 'rotation':(0.12838, -66.561493, 0.127808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6136.02828125, 2517.23195312, 154.49395508), 'rotation':(0.113484, -66.562012, 0.113041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6131.5404687499995, 2527.58398438, 154.47282227), 'rotation':(0.103628, -66.562012, 0.103253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6129.29632812, 2532.76050781, 154.46318359), 'rotation':(0.103628, -66.562012, 0.103253), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6120.31976562, 2553.4665625, 154.42803711), 'rotation':(0.08882, -66.563873, 0.088542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6118.07515625, 2558.6428125, 154.42008789), 'rotation':(0.082782, -66.559631, 0.082541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6106.8544531200005, 2584.52441406, 154.39303711), 'rotation':(0.040681, -66.560089, 0.04063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6104.6103125, 2589.70042969, 154.38902344), 'rotation':(0.040687, -66.561005, 0.040622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.1224999999995, 2600.05273438, 154.38099609), 'rotation':(0.040687, -66.565308, 0.040632), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.8778906200005, 2605.22972656, 154.37785156), 'rotation':(0.028618, -66.560333, 0.028599), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6077.6810937499995, 2651.81566406, 154.38081055), 'rotation':(-0.007996, -66.561188, -0.007996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6073.191875, 2662.16945312, 154.38375976999998), 'rotation':(-0.014801, -66.558746, -0.014832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6061.970625, 2688.0525, 154.41), 'rotation':(-0.062897, -66.563049, -0.063049), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6057.48289062, 2698.40478516, 154.42366211), 'rotation':(-0.070221, -66.564148, -0.070374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6055.23875, 2703.58082031, 154.43128906), 'rotation':(-0.080017, -66.564148, -0.080261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6052.9940625, 2708.75660156, 154.43943359000002), 'rotation':(-0.084991, -66.559082, -0.085266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6037.28515625, 2744.99046875, 154.50851562), 'rotation':(-0.108795, -66.561493, -0.109222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6206.90085938, 2332.66234375, 155.10416016), 'rotation':(-0.217102, 113.439255, -0.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6204.65570312, 2337.84695312, 155.08240234000002), 'rotation':(-0.217102, 113.439255, -0.21875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6202.4115624999995, 2343.03125, 155.06100586), 'rotation':(-0.214783, 113.437813, -0.2164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6197.91648438, 2353.39917969, 155.01855469), 'rotation':(-0.214783, 113.441284, -0.2164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6182.1903906200005, 2389.6875, 154.87458984), 'rotation':(-0.195984, 113.435677, -0.197327), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.9428124999995, 2394.87109375, 154.85513672), 'rotation':(-0.193329, 113.441307, -0.194611), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6177.69578125, 2400.0549218799997, 154.8359668), 'rotation':(-0.191711, 113.440575, -0.192993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6175.4482031200005, 2405.23875, 154.81698242000002), 'rotation':(-0.191833, 113.437569, -0.193115), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6168.7060156200005, 2420.79027344, 154.76063477), 'rotation':(-0.182587, 113.439629, -0.183746), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6164.2109375, 2431.15796875, 154.72503906), 'rotation':(-0.170074, 113.442345, -0.171082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6161.9638281200005, 2436.34179688, 154.70790039), 'rotation':(-0.170074, 113.442345, -0.171082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6157.46875, 2446.70945312, 154.6747168), 'rotation':(-0.166931, 113.438614, -0.167908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6143.98382812, 2477.8127343799997, 154.58197266), 'rotation':(-0.140472, 113.437088, -0.141144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6137.24164062, 2493.365, 154.54193359), 'rotation':(-0.128387, 113.438499, -0.128937), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6134.9940625, 2498.54882812, 154.52926758), 'rotation':(-0.123444, 113.438622, -0.123962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6132.7465625, 2503.73339844, 154.51692383), 'rotation':(-0.123444, 113.438622, -0.123962), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6126.004375, 2519.2846875, 154.48260742), 'rotation':(-0.103607, 113.43795, -0.104004), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6117.01460938, 2540.02074219, 154.44477539), 'rotation':(-0.088806, 113.439995, -0.089081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6108.024375, 2560.75683594, 154.41275391), 'rotation':(-0.058777, 113.437782, -0.058929), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6101.28171875, 2576.30859375, 154.39681640999999), 'rotation':(-0.04068, 113.438988, -0.040741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6099.0341406200005, 2581.49316406, 154.39280273), 'rotation':(-0.04068, 113.438988, -0.040741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.7865624999995, 2586.67699219, 154.38878906), 'rotation':(-0.040833, 113.439911, -0.040894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.2919531200005, 2597.04417969, 154.38075195), 'rotation':(-0.028656, 113.439659, -0.028656), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.0443749999995, 2602.22925781, 154.37768555), 'rotation':(-0.004242, 113.436386, -0.004211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6085.54929688, 2612.59742188, 154.37540038999998), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6083.30171875, 2617.78246094, 154.37617188000002), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6081.05414062, 2622.96605469, 154.37695312), 'rotation':(0.007827, 113.438805, 0.007829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6072.064375, 2643.70070312, 154.38007812), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.81734375, 2648.88453125, 154.38087890999998), 'rotation':(0.007991, 113.438805, 0.007992), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6067.56929688, 2654.06910156, 154.38192383), 'rotation':(0.014808, 113.436623, 0.014809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6060.82609375, 2669.62207031, 154.39220703), 'rotation':(0.056096, 113.440292, 0.055987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6056.33148438, 2679.99046875, 154.40427734000002), 'rotation':(0.062892, 113.436966, 0.062756), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6054.08390625, 2685.17529297, 154.41056641), 'rotation':(0.065563, 113.440857, 0.065416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.34171875, 2700.72632812, 154.43201172), 'rotation':(0.085009, 113.435867, 0.084763), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6042.8466406200005, 2711.09351562, 154.44897461), 'rotation':(0.094653, 113.435898, 0.094337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6038.3515625, 2721.46240234, 154.46806641), 'rotation':(0.101968, 113.438454, 0.101607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6033.8568749999995, 2731.82958984, 154.48819336), 'rotation':(0.108805, 113.438484, 0.108396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6031.609375, 2737.01416016, 154.49847656), 'rotation':(0.108805, 113.438484, 0.108396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.7665625, 2797.76683594, 154.69857421999998), 'rotation':(0.22806, 106.946373, 0.226252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6007.27195312, 2802.70703125, 154.71981445), 'rotation':(0.240354, 106.768562, 0.238347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6016.41203125, 2801.31542969, 154.70328125), 'rotation':(-0.233704, -73.054077, -0.235626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6014.7841406200005, 2806.70777344, 154.72678711), 'rotation':(-0.240356, -73.227356, -0.242371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6011.53703125, 2817.4821875, 154.77604492), 'rotation':(-0.253601, -73.230774, -0.255859), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6009.9140625, 2822.86914062, 154.80160156), 'rotation':(-0.260345, -73.232452, -0.262726), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6003.42132812, 2844.41674805, 154.90424805), 'rotation':(-0.263153, -73.230469, -0.265594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.8525, 3310.14964844, 169.14882812), 'rotation':(-0.465179, -89.549408, -0.472778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.98677734, 3293.05761719, 169.01007812), 'rotation':(-0.463409, -89.545441, -0.470947), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6912.07613281, 3281.66308594, 168.91824218999997), 'rotation':(-0.456116, -89.545563, -0.46344), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.16548828, 3270.26832031, 168.8275), 'rotation':(-0.452576, -89.549438, -0.459778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.20992188, 3264.57080078, 168.7825), 'rotation':(-0.450775, -89.542847, -0.457886), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6912.25484375, 3258.87353516, 168.73767578), 'rotation':(-0.450623, -89.547333, -0.457764), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.65669922, 3207.59644531, 168.3440625), 'rotation':(-0.425629, -89.547424, -0.431976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.70162109, 3201.89892578, 168.30173828), 'rotation':(-0.425781, -89.547424, -0.432159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6912.79097656, 3190.50367188, 168.21742188), 'rotation':(-0.416962, -89.545166, -0.423065), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.88033203, 3179.10888672, 168.13445312), 'rotation':(-0.411102, -89.548523, -0.417053), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6912.92476562, 3173.41162109, 168.09355469), 'rotation':(-0.405365, -89.548584, -0.411133), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6913.14839844, 3144.92260742, 167.89367188), 'rotation':(-0.388153, -89.547974, -0.393463), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6913.19283203, 3139.22485352, 167.85488281000002), 'rotation':(-0.382446, -89.548065, -0.387573), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6913.2821875, 3127.82983398, 167.77892577999998), 'rotation':(-0.370972, -89.548218, -0.375793), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6905.03609375, 3110.66333008, 167.66890625), 'rotation':(0.365238, 90.451714, 0.360612), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6904.94673828, 3122.05834961, 167.74169922000002), 'rotation':(0.376712, 90.451866, 0.371792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.85738281, 3133.45336914, 167.81658202999998), 'rotation':(0.382436, 90.451927, 0.377363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6904.76802734, 3144.84863281, 167.89361327999998), 'rotation':(0.393774, 90.45211, 0.388386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.72310547, 3150.54614258, 167.93292968999998), 'rotation':(0.399628, 90.452164, 0.394085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.67867188, 3156.24438477, 167.97269531), 'rotation':(0.402325, 90.451073, 0.396696), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.49947266, 3179.03466797, 168.134375), 'rotation':(0.416956, 90.451576, 0.410927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6904.32076172, 3201.82445312, 168.30166015999998), 'rotation':(0.425644, 90.452583, 0.419358), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.23189453, 3213.21923828, 168.38648438), 'rotation':(0.430432, 90.452721, 0.423994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.09761719, 3230.31152344, 168.51585938), 'rotation':(0.439789, 90.452881, 0.43308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6904.05318359, 3236.00878906, 168.55960938), 'rotation':(0.442904, 90.452927, 0.436099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6903.96382812, 3247.40380859, 168.64808594), 'rotation':(0.449146, 90.453026, 0.442148), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.78511719, 3270.19335938, 168.82742188), 'rotation':(0.45614, 90.454414, 0.448926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6903.74019531, 3275.89039062, 168.87265625), 'rotation':(0.459726, 90.454506, 0.452404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.65083984, 3287.28564453, 168.96392577999998), 'rotation':(0.463408, 90.450722, 0.45597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6903.60591797, 3292.98265625, 169.01), 'rotation':(0.465156, 90.454018, 0.457645), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.5165625, 3304.37744141, 169.1025), 'rotation':(0.46517, 90.454063, 0.457659), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6903.086875, 3359.20824219, 169.55470703), 'rotation':(0.478496, 90.45343, 0.470552), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.82613281, 3392.4841406200003, 169.83447266), 'rotation':(0.48605, 90.453873, 0.477855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.78267578, 3398.03003906, 169.88152344), 'rotation':(0.48605, 90.453873, 0.477855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.73873047, 3403.5759375, 169.92859375), 'rotation':(0.486159, 90.449623, 0.477975), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.69527344, 3409.12183594, 169.97564452999998), 'rotation':(0.48605, 90.453873, 0.477855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.56490234, 3425.75976562, 170.11707031000003), 'rotation':(0.489977, 90.452217, 0.48165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6902.26021484, 3464.58128906, 170.45023438), 'rotation':(0.492463, 90.45295, 0.48404), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.21675781, 3470.12695312, 170.49789062), 'rotation':(0.493495, 90.453026, 0.485051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6902.17330078, 3475.67308594, 170.54566406), 'rotation':(0.495414, 90.453049, 0.486906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6902.04292969, 3492.31101562, 170.68955078), 'rotation':(0.496425, 90.453117, 0.487891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.99947266, 3497.85695312, 170.73761718999998), 'rotation':(0.496425, 90.453117, 0.487891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.91255859, 3508.94824219, 170.83375), 'rotation':(0.496828, 90.450562, 0.488278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.86910156, 3514.49460938, 170.881875), 'rotation':(0.497258, 90.455032, 0.488688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.7821875, 3525.5861718799997, 170.97822266), 'rotation':(0.498358, 90.450577, 0.48974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.51070312, 3353.72804688, 169.50837891), 'rotation':(-0.478516, -89.54657, -0.486542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6911.46724609, 3359.2736718799997, 169.55470703), 'rotation':(-0.478668, -89.54657, -0.486725), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.38033203, 3370.36570312, 169.64738281), 'rotation':(-0.478516, -89.54657, -0.486542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.336875, 3375.91164062, 169.69388672000002), 'rotation':(-0.479523, -89.542999, -0.48761), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.29341797, 3381.45777344, 169.74054688), 'rotation':(-0.481384, -89.548462, -0.489502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.20650391, 3392.55003906, 169.83447266), 'rotation':(-0.486176, -89.550354, -0.494476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.11910156, 3403.64160156, 169.92859375), 'rotation':(-0.486023, -89.546143, -0.494324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6911.0321875, 3414.73339844, 170.02269531000002), 'rotation':(-0.486053, -89.546112, -0.494354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.98873047, 3420.27929688, 170.06982422000002), 'rotation':(-0.486908, -89.547821, -0.495239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.94527344, 3425.82519531, 170.11707031000003), 'rotation':(-0.488525, -89.543518, -0.496918), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.72798828, 3453.5549218799997, 170.35488281000002), 'rotation':(-0.49234, -89.543121, -0.500854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.68453125, 3459.10082031, 170.40253906), 'rotation':(-0.49234, -89.543121, -0.500854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.64107422, 3464.64671875, 170.45021484), 'rotation':(-0.492462, -89.547058, -0.500977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.59761719, 3470.19261719, 170.49789062), 'rotation':(-0.492462, -89.547058, -0.500977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.55416016, 3475.73851562, 170.54566406), 'rotation':(-0.493469, -89.546967, -0.502045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.51070312, 3481.2846875, 170.59351562), 'rotation':(-0.493469, -89.546967, -0.502045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6910.37984375, 3497.92234375, 170.73761718999998), 'rotation':(-0.49646, -89.546875, -0.505096), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6910.16255859, 3525.651875, 170.97822266), 'rotation':(-0.497833, -89.544922, -0.506531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.86421875, 3563.71242188, 171.31023438), 'rotation':(-0.500458, -89.547058, -0.509277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.77730469, 3574.79980469, 171.4071875), 'rotation':(-0.501495, -89.545807, -0.510315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.64693359, 3591.43066406, 171.55332031), 'rotation':(-0.504364, -89.548035, -0.513306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6909.60347656, 3596.97460938, 171.60212891), 'rotation':(-0.504364, -89.548035, -0.513306), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6909.38619141, 3624.69261719, 171.84623047000002), 'rotation':(-0.505188, -89.546631, -0.51416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6909.21236328, 3646.8669531200003, 172.04244140999998), 'rotation':(-0.507507, -89.5466, -0.516571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.99458984, 3674.585, 172.28798827999998), 'rotation':(-0.507507, -89.5466, -0.516571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6908.90767578, 3685.67257812, 172.38679688), 'rotation':(-0.511292, -89.54599, -0.520477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6908.77730469, 3702.3034374999997, 172.53523438), 'rotation':(-0.511292, -89.54599, -0.520477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.69039062, 3713.390625, 172.63417969), 'rotation':(-0.511292, -89.54599, -0.520447), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.64693359, 3718.93429688, 172.68371093999997), 'rotation':(-0.511902, -89.548676, -0.521088), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.5165625, 3735.56546875, 172.8328125), 'rotation':(-0.514038, -89.548676, -0.523315), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6908.42964844, 3746.65257812, 172.93257812), 'rotation':(-0.51593, -89.54541, -0.525269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.38619141, 3752.19601562, 172.9825), 'rotation':(-0.515717, -89.54541, -0.525085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.52730469, 3558.10328125, 171.26179688), 'rotation':(0.50038, 90.452965, 0.491702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.48335938, 3563.64671875, 171.31023438), 'rotation':(0.50038, 90.452965, 0.491702), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.43990234, 3569.19042969, 171.35867188), 'rotation':(0.501493, 90.454193, 0.492772), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.39644531, 3574.7341406200003, 171.4071875), 'rotation':(0.503364, 90.454231, 0.494594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.35347656, 3580.27808594, 171.45582031), 'rotation':(0.503364, 90.454231, 0.494594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6901.09273438, 3613.53980469, 171.74853516), 'rotation':(0.504368, 90.45536, 0.495544), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6901.04927734, 3619.08351562, 171.79734375), 'rotation':(0.505181, 90.453354, 0.496345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.961875, 3630.17066406, 171.89519531000002), 'rotation':(0.506684, 90.453377, 0.497783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.70113281, 3663.4323437499997, 172.18978515999999), 'rotation':(0.50751, 90.4534, 0.498581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.57076172, 3680.0634375, 172.33730469), 'rotation':(0.511274, 90.454002, 0.502216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6900.52730469, 3685.6071875, 172.38679688), 'rotation':(0.511376, 90.454018, 0.502321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.39693359, 3702.2378125, 172.53523438), 'rotation':(0.511274, 90.454002, 0.502216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.2665625, 3718.86867188, 172.68371093999997), 'rotation':(0.513104, 90.455666, 0.503987), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6900.22310547, 3724.41234375, 172.73332031), 'rotation':(0.514026, 90.455658, 0.504867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.17964844, 3729.9557812499997, 172.78302734000002), 'rotation':(0.514026, 90.455658, 0.504867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.13570312, 3735.49953125, 172.8328125), 'rotation':(0.515133, 90.451363, 0.505941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.04878906, 3746.58664062, 172.93257812), 'rotation':(0.515748, 90.454597, 0.506531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6900.00533203, 3752.130625, 172.9825), 'rotation':(0.51572, 90.454575, 0.506509), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.96236328, 3757.6740625, 173.03240234), 'rotation':(0.515748, 90.454597, 0.506531), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.48970703, 3817.91085938, 173.57841797), 'rotation':(0.521451, 90.45562, 0.51202), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.35933594, 3834.55445312, 173.73041016), 'rotation':(0.525535, 90.454239, 0.515972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.31587891, 3840.1028125000003, 173.78128906), 'rotation':(0.525515, 90.454224, 0.515938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.27242188, 3845.650625, 173.83216797), 'rotation':(0.525515, 90.454224, 0.515938), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.18550781, 3856.74632812, 173.93394531), 'rotation':(0.525535, 90.454239, 0.515972), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.14205078, 3862.29445312, 173.98488281000002), 'rotation':(0.526136, 90.454971, 0.51655), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6899.05464844, 3873.39015625, 174.08691406000003), 'rotation':(0.528766, 90.455025, 0.519067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6899.01119141, 3878.93820312, 174.13806641), 'rotation':(0.528766, 90.455025, 0.519067), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.96773438, 3884.48632812, 174.18927734000002), 'rotation':(0.530146, 90.455032, 0.520411), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.92427734, 3890.03421875, 174.240625), 'rotation':(0.530938, 90.453087, 0.521185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.83736328, 3901.12984375, 174.34341797000002), 'rotation':(0.530808, 90.453087, 0.521051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6898.57613281, 3934.41796875, 174.65244141), 'rotation':(0.534763, 90.4524, 0.524846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6898.40230469, 3956.609375, 174.85960938), 'rotation':(0.53477, 90.456047, 0.524846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6908.0009375, 3801.3303125, 173.42703125), 'rotation':(-0.520905, -89.544312, -0.530426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.91402344, 3812.42625, 173.52792968999998), 'rotation':(-0.520874, -89.549133, -0.530426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.87056641, 3817.974375, 173.57837891), 'rotation':(-0.520874, -89.544312, -0.530426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.82710938, 3823.5221874999997, 173.62894531), 'rotation':(-0.521454, -89.544373, -0.531006), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.73970703, 3834.61789062, 173.73039062), 'rotation':(-0.524872, -89.544312, -0.534546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.69771484, 3840.16726562, 173.78126953), 'rotation':(-0.525543, -89.545746, -0.535248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.65279297, 3845.71414062, 173.83214843999997), 'rotation':(-0.525543, -89.545746, -0.535248), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.47896484, 3867.90601562, 174.03582031000002), 'rotation':(-0.526154, -89.548462, -0.535889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.43550781, 3873.45382812, 174.08689453), 'rotation':(-0.527557, -89.545013, -0.537354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.3915625, 3879.00195312, 174.13804688), 'rotation':(-0.527557, -89.545013, -0.537354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.34810547, 3884.54984375, 174.18927734000002), 'rotation':(-0.528748, -89.544952, -0.538574), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.26119141, 3895.6457812500003, 174.29199218999997), 'rotation':(-0.530151, -89.544922, -0.540039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.21773438, 3901.19359375, 174.34339844), 'rotation':(-0.530945, -89.546906, -0.540863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.17427734, 3906.74148438, 174.39480468999997), 'rotation':(-0.530823, -89.546906, -0.54071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6907.13082031, 3912.28929688, 174.44621094), 'rotation':(-0.530792, -89.546906, -0.54071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.08736328, 3917.83742188, 174.49763672), 'rotation':(-0.530823, -89.542664, -0.54071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6907.04390625, 3923.3854687499997, 174.54912109), 'rotation':(-0.531799, -89.547485, -0.541748), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.95650391, 3934.48140625, 174.65244141), 'rotation':(-0.533844, -89.54361, -0.543854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.86958984, 3945.5771875, 174.75603515999998), 'rotation':(-0.534882, -89.543945, -0.544922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.82613281, 3951.12523438, 174.8078125), 'rotation':(-0.534882, -89.543945, -0.544922), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6906.78267578, 3956.6731250000003, 174.85960938), 'rotation':(-0.53476, -89.547607, -0.54483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.45554688, 3285.25292969, 166.14322266), 'rotation':(-0.340271, -89.480957, -0.34433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.48140625, 3279.57177734, 166.10945312), 'rotation':(-0.340271, -89.480957, -0.34433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.53265625, 3273.88964844, 166.07572266), 'rotation':(-0.339539, -89.480988, -0.343597), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.58394531, 3268.20777344, 166.04203125), 'rotation':(-0.339111, -89.481476, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.63523438, 3262.52587891, 166.00839843999998), 'rotation':(-0.339111, -89.481476, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6632.73773438, 3251.16162109, 165.94117188), 'rotation':(-0.33902, -89.481506, -0.343079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6632.78902344, 3245.47949219, 165.90751953), 'rotation':(-0.339142, -89.478363, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6632.8403125, 3239.79761719, 165.87388672), 'rotation':(-0.339142, -89.478363, -0.34317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6632.9428125, 3228.43359375, 165.80667968999998), 'rotation':(-0.336456, -89.47879, -0.340424), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6633.04585938, 3217.06957031, 165.73992188), 'rotation':(-0.335663, -89.480743, -0.33963), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.2509375, 3194.3415625, 165.60693359), 'rotation':(-0.333282, -89.4841, -0.337158), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.3021875, 3188.65941406, 165.57390625), 'rotation':(-0.331818, -89.479553, -0.335663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.40476562, 3177.29541016, 165.50828125), 'rotation':(-0.328674, -89.479584, -0.332428), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6633.4560156200005, 3171.61376953, 165.47568359000002), 'rotation':(-0.32724, -89.484161, -0.330994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.60984375, 3154.56762695, 165.37876953), 'rotation':(-0.323212, -89.481903, -0.326904), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.76414062, 3137.52026367, 165.28292968999997), 'rotation':(-0.316956, -89.481262, -0.320435), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.8153906200005, 3131.83837891, 165.25150391), 'rotation':(-0.312561, -89.481323, -0.315979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.91792969, 3120.47412109, 165.18921875), 'rotation':(-0.30835, -89.478394, -0.311676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6633.96921875, 3114.79223633, 165.15853515999999), 'rotation':(-0.30835, -89.478394, -0.311676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6634.138125, 3104.90405273, 165.10548828), 'rotation':(-0.306274, -89.479248, -0.30954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.586875, 3103.34912109, 165.09757812), 'rotation':(0.306252, 90.517075, 0.302993), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6625.48628906, 3126.07495117, 165.22019531), 'rotation':(0.316921, 90.518723, 0.313429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.435, 3131.75732422, 165.25146484), 'rotation':(0.316921, 90.518723, 0.313429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.3325, 3143.12133789, 165.31472656000003), 'rotation':(0.323225, 90.518082, 0.319593), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6625.22992188, 3154.48608398, 165.37873047000002), 'rotation':(0.324072, 90.52037, 0.320413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.075625, 3171.53222656, 165.47564452999998), 'rotation':(0.328662, 90.520447, 0.324913), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.92183594, 3188.57789062, 165.57386719), 'rotation':(0.333252, 90.5159, 0.329402), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.71675781, 3211.30640625, 165.70662109), 'rotation':(0.335663, 90.519249, 0.331736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.35738281, 3251.07984375, 165.94111328), 'rotation':(0.339133, 90.518494, 0.335125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.30609375, 3256.76195312, 165.97474609), 'rotation':(0.339133, 90.518494, 0.335125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6624.25484375, 3262.44384766, 166.00837891), 'rotation':(0.339133, 90.518494, 0.335125), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6624.20359375, 3268.12597656, 166.04201172), 'rotation':(0.339536, 90.51899, 0.335528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6623.9325781200005, 3290.85277344, 166.17699219), 'rotation':(0.340731, 90.518173, 0.336707), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6623.84078125, 3296.53394531, 166.21076172000002), 'rotation':(0.340724, 90.521248, 0.336704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6623.7153125, 3307.8984375, 166.27837891), 'rotation':(0.340826, 90.518166, 0.336804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6623.50191406, 3345.849375, 166.50373047000002), 'rotation':(0.339795, 90.518005, 0.335786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6623.20210938, 3379.03222656, 166.7003125), 'rotation':(0.337807, 90.518906, 0.333832), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.95257812, 3406.68457031, 166.86339843999997), 'rotation':(0.337787, 90.518898, 0.33382), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.9028125, 3412.21507812, 166.89601562), 'rotation':(0.337138, 90.519547, 0.333183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.7528906200005, 3428.80640625, 166.99353516), 'rotation':(0.334877, 90.521225, 0.330988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.35347656, 3473.0503125, 167.25220703), 'rotation':(0.334208, 90.522903, 0.330337), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6622.25335938, 3484.11085938, 167.31671875), 'rotation':(0.333948, 90.515106, 0.330077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6622.10347656, 3500.70238281, 167.41341797), 'rotation':(0.334078, 90.519211, 0.330206), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6622.00335938, 3511.76320312, 167.47794922), 'rotation':(0.33442, 90.519234, 0.330515), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.95359375, 3517.29394531, 167.51023438), 'rotation':(0.334816, 90.519234, 0.330919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.23382812, 3528.43554688, 167.57492188), 'rotation':(-0.334808, -89.480743, -0.338745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.33394531, 3517.37453125, 167.51027344), 'rotation':(-0.334412, -89.480743, -0.338318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.43355469, 3506.31371094, 167.44570312), 'rotation':(-0.334076, -89.480774, -0.338013), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6630.48382812, 3500.78296875, 167.41345703), 'rotation':(-0.333954, -89.479919, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.58394531, 3489.72242188, 167.34896484), 'rotation':(-0.333923, -89.484894, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6630.68355469, 3478.66113281, 167.28449218999998), 'rotation':(-0.334229, -89.477081, -0.338135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6630.78316406, 3467.60058594, 167.21994141), 'rotation':(-0.334991, -89.481934, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.8334375, 3462.06984375, 167.18759766), 'rotation':(-0.334991, -89.47876, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.93304688, 3451.00902344, 167.12294922), 'rotation':(-0.334991, -89.481934, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6630.98335938, 3445.47851562, 167.09058593999998), 'rotation':(-0.334991, -89.481934, -0.338928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.4325781200005, 3395.70410156, 166.79822266), 'rotation':(-0.337891, -89.481079, -0.341919), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.48238281, 3390.17382812, 166.76560547), 'rotation':(-0.337799, -89.481079, -0.341797), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.5825, 3379.1128125, 166.70035156000003), 'rotation':(-0.338257, -89.482513, -0.342285), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.68210938, 3368.05199219, 166.63494140999998), 'rotation':(-0.339813, -89.481964, -0.343842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6631.7821875, 3356.99097656, 166.56935547), 'rotation':(-0.339813, -89.477722, -0.343842), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6621.50972656, 3566.47898438, 167.79816406), 'rotation':(0.336318, 90.519974, 0.332389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.3559375, 3583.53953125, 167.89867188), 'rotation':(0.33821, 90.519051, 0.334235), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6621.30414062, 3589.2263281200003, 167.93222656), 'rotation':(0.338047, 90.519028, 0.33407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.20113281, 3600.60007812, 167.99939453), 'rotation':(0.339262, 90.520218, 0.335278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.14984375, 3606.28664062, 168.03306641), 'rotation':(0.341366, 90.517426, 0.337318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6621.09859375, 3611.97363281, 168.06683593999998), 'rotation':(0.341366, 90.517426, 0.337318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6621.04734375, 3617.66089844, 168.10072266), 'rotation':(0.343565, 90.520271, 0.33946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.94476562, 3629.03441406, 168.16886719), 'rotation':(0.345744, 90.520294, 0.341594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6620.84226562, 3640.40820312, 168.2375), 'rotation':(0.346837, 90.520317, 0.342664), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.79097656, 3646.09472656, 168.27193359), 'rotation':(0.346844, 90.517303, 0.342668), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.63667969, 3663.1553125, 168.37529297), 'rotation':(0.350245, 90.517883, 0.345973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.48289062, 3680.21632812, 168.48035156000003), 'rotation':(0.35603, 90.521004, 0.351618), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.43109375, 3685.90304688, 168.51568359), 'rotation':(0.356106, 90.518105, 0.351694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.32859375, 3697.276875, 168.58636718999998), 'rotation':(0.357881, 90.520317, 0.353417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.27730469, 3702.96390625, 168.62185547), 'rotation':(0.357881, 90.520317, 0.353417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.1747656200005, 3714.33765625, 168.69328125), 'rotation':(0.36519, 90.520393, 0.360566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6620.07171875, 3725.7109375, 168.76556641), 'rotation':(0.368905, 90.517555, 0.364183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.81492188, 3754.14601562, 168.94925781), 'rotation':(0.377484, 90.520164, 0.372539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.2978125, 3742.85304688, 168.87550781000002), 'rotation':(-0.370697, -89.484009, -0.375519), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.34957031, 3737.16554688, 168.83869141), 'rotation':(-0.368896, -89.479553, -0.373688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.50335938, 3720.105, 168.72933593999997), 'rotation':(-0.361481, -89.479675, -0.366058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.55464844, 3714.41820312, 168.69332031000002), 'rotation':(-0.361481, -89.479675, -0.366058), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.60640625, 3708.7317187500003, 168.65742188000002), 'rotation':(-0.35788, -89.482574, -0.362366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.70894531, 3697.35742188, 168.58638672), 'rotation':(-0.35611, -89.479004, -0.360565), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6628.76023438, 3691.6706249999997, 168.55105468999997), 'rotation':(-0.356018, -89.481873, -0.360443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6628.96578125, 3668.9231250000003, 168.41011719), 'rotation':(-0.35022, -89.482117, -0.354553), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.01703125, 3663.23609375, 168.3753125), 'rotation':(-0.3479, -89.476837, -0.352142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.06832031, 3657.5490625, 168.34080078), 'rotation':(-0.346832, -89.482697, -0.351074), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.37640625, 3623.42796875, 168.13480468999998), 'rotation':(-0.34137, -89.479767, -0.345459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6629.42769531, 3617.74121094, 168.10076172), 'rotation':(-0.34137, -89.479767, -0.345459), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.53023438, 3606.3671875, 168.03310547), 'rotation':(-0.339264, -89.479797, -0.343292), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.63328125, 3594.99339844, 167.96583984), 'rotation':(-0.338043, -89.480988, -0.342041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6629.73578125, 3583.61988281, 167.89869141), 'rotation':(-0.338196, -89.480957, -0.342224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.78757812, 3577.93285156, 167.86513672), 'rotation':(-0.337463, -89.480042, -0.341461), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6629.94136719, 3560.87257812, 167.76484375), 'rotation':(-0.335602, -89.481323, -0.339539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.35007812, 3797.78664062, 169.24115234), 'rotation':(0.388651, 90.519432, 0.383418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.37105469, 3803.316875, 169.27875), 'rotation':(0.391192, 90.521172, 0.385885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.2709375, 3814.38304688, 169.35476562), 'rotation':(0.400577, 90.517525, 0.395012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.22117188, 3819.91625, 169.39332031), 'rotation':(0.400577, 90.517525, 0.395012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.12105469, 3830.98265625, 169.47128906), 'rotation':(0.407619, 90.520439, 0.40184), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6619.0209375, 3842.0490625, 169.55003906000002), 'rotation':(0.409162, 90.522972, 0.403357), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.97117188, 3847.58226562, 169.58953125), 'rotation':(0.412093, 90.51812, 0.406193), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6618.92132812, 3853.11546875, 169.62929688), 'rotation':(0.414975, 90.518112, 0.408998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6618.77144531, 3869.71484375, 169.75023438), 'rotation':(0.423711, 90.523155, 0.417483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.7216406200005, 3875.24757812, 169.79107422), 'rotation':(0.426798, 90.518326, 0.420465), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.67183594, 3880.78125, 169.83220702999998), 'rotation':(0.429694, 90.523247, 0.423276), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.6215625, 3886.31421875, 169.87363281), 'rotation':(0.431203, 90.521439, 0.424755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.57171875, 3891.84742188, 169.91521484), 'rotation':(0.432713, 90.517624, 0.42621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.32171875, 3919.5129687500003, 170.12716797000002), 'rotation':(0.448771, 90.517876, 0.441792), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.22210938, 3930.5793750000003, 170.21408203), 'rotation':(0.455191, 90.51799, 0.448005), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.17183594, 3936.11234375, 170.25798827999998), 'rotation':(0.456735, 90.522446, 0.449493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6618.07222656, 3947.17875, 170.34625), 'rotation':(0.459726, 90.519302, 0.4524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6617.97210938, 3958.24515625, 170.4353125), 'rotation':(0.465593, 90.522285, 0.458075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6626.40230469, 3952.7946875, 170.39072266), 'rotation':(-0.459747, -89.477783, -0.467163), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.45257812, 3947.26171875, 170.34630859), 'rotation':(-0.456726, -89.477539, -0.46405), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.5521875, 3936.19507812, 170.25804688), 'rotation':(-0.45517, -89.482025, -0.462433), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.75191406, 3914.0625, 170.08421875), 'rotation':(-0.442383, -89.477234, -0.449249), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.8021875, 3908.5299999999997, 170.04154297000002), 'rotation':(-0.439117, -89.482239, -0.445892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.85203125, 3902.9965625, 169.99914062), 'rotation':(-0.435974, -89.477325, -0.442657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6626.90230469, 3897.46390625, 169.95707031), 'rotation':(-0.432709, -89.482361, -0.43927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6626.95210938, 3891.92992188, 169.91527344), 'rotation':(-0.431183, -89.478577, -0.437714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.0521875, 3880.86351562, 169.83226562), 'rotation':(-0.426788, -89.481659, -0.433197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.10203125, 3875.3303125, 169.79113281000002), 'rotation':(-0.423706, -89.476837, -0.430023), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.15179688, 3869.79757812, 169.75029297), 'rotation':(-0.420959, -89.48175, -0.427185), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.20164062, 3864.26414062, 169.70970703), 'rotation':(-0.417908, -89.476898, -0.424042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.25191406, 3858.73117188, 169.66939452999998), 'rotation':(-0.414978, -89.481873, -0.421021), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.30171875, 3853.19828125, 169.62935547), 'rotation':(-0.412079, -89.481903, -0.41803), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6627.35152344, 3847.66476562, 169.58960938), 'rotation':(-0.40918, -89.47702, -0.415039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.4013281200005, 3842.13132812, 169.55009766), 'rotation':(-0.407776, -89.479553, -0.413605), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.45164062, 3836.598125, 169.51070312), 'rotation':(-0.407654, -89.479553, -0.413483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.55125, 3825.53171875, 169.4321875), 'rotation':(-0.400604, -89.478699, -0.406219), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.60152344, 3819.99851562, 169.39335938), 'rotation':(-0.395905, -89.47876, -0.401398), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.70113281, 3808.93210938, 169.31658202999998), 'rotation':(-0.391205, -89.478851, -0.396576), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6627.7865625, 3800.7925, 169.26103516), 'rotation':(-0.388672, -89.48053, -0.393982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6625.99019531, 3994.79984375, 170.73710938), 'rotation':(-0.480164, -89.478271, -0.488281), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6617.66402344, 3996.0525, 170.74828125), 'rotation':(0.484015, 90.51915, 0.475894), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.76023438, 3311.86890625, 162.62011719), 'rotation':(-0.303131, -89.872101, -0.306366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.78460938, 3300.52783203, 162.5602832), 'rotation':(-0.304901, -89.87323, -0.308136), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.79734375, 3294.8571875, 162.53011719), 'rotation':(-0.305084, -89.87323, -0.308319), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.80953125, 3289.18652344, 162.49994141), 'rotation':(-0.305786, -89.872925, -0.309052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.85933594, 3266.50414062, 162.37770508), 'rotation':(-0.312988, -89.872833, -0.316437), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.89695312, 3249.4921875, 162.28415039), 'rotation':(-0.318329, -89.872803, -0.321899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.90960938, 3243.82177734, 162.25262695), 'rotation':(-0.319153, -89.871704, -0.322754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.92183594, 3238.15087891, 162.22100586), 'rotation':(-0.319153, -89.871704, -0.322754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.9340625, 3232.48095703, 162.1894043), 'rotation':(-0.320496, -89.874817, -0.324066), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.94625, 3226.80980469, 162.15769531), 'rotation':(-0.322662, -89.870667, -0.326324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.95894531, 3221.13941406, 162.12575195), 'rotation':(-0.325104, -89.874756, -0.328827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.98382812, 3209.79833984, 162.06129883), 'rotation':(-0.327545, -89.870605, -0.331299), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6364.00875, 3198.45703125, 161.99631836), 'rotation':(-0.328583, -89.871979, -0.332367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.03367188, 3187.11572266, 161.93121094), 'rotation':(-0.329773, -89.873596, -0.333588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.05855469, 3175.77441406, 161.86574219), 'rotation':(-0.333954, -89.870361, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.07078125, 3170.10400391, 161.8328125), 'rotation':(-0.333954, -89.870361, -0.33786), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6364.0834374999995, 3164.43335938, 161.79975586), 'rotation':(-0.33606, -89.873535, -0.339996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.09617188, 3158.76269531, 161.76654297), 'rotation':(-0.337006, -89.871582, -0.341003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6364.17039062, 3124.73876953, 161.56638672), 'rotation':(-0.338104, -89.874237, -0.342102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.20015625, 3119.06982422, 161.53295898), 'rotation':(-0.338104, -89.874237, -0.342102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6364.33003906, 3107.72973633, 161.46601562), 'rotation':(-0.338226, -89.874237, -0.342224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.7045312499995, 3107.70458984, 161.46598633), 'rotation':(0.33821, 90.129745, 0.334239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.74460938, 3113.37475586, 161.49945312), 'rotation':(0.338094, 90.125763, 0.334116), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.78460938, 3119.04516602, 161.53292969), 'rotation':(0.337685, 90.127274, 0.333714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.7153125, 3158.73876953, 161.76649414), 'rotation':(0.336032, 90.12645, 0.332118), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.70257812, 3164.40941406, 161.79972656), 'rotation':(0.333948, 90.126434, 0.33008), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.6903906200005, 3170.08007812, 161.83276367), 'rotation':(0.33177, 90.129593, 0.32794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.665, 3181.42138672, 161.89854492), 'rotation':(0.329755, 90.126381, 0.325982), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.6528125, 3187.09179688, 161.93117188), 'rotation':(0.328594, 90.128029, 0.324839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.64007812, 3192.76246094, 161.96375), 'rotation':(0.328594, 90.128029, 0.324839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.61570312, 3204.10375, 162.02880859), 'rotation':(0.327542, 90.125282, 0.323827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.60347656, 3209.77441406, 162.06125977), 'rotation':(0.325103, 90.129356, 0.321438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.59078125, 3215.44507812, 162.09359375), 'rotation':(0.325103, 90.129356, 0.321438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.56585938, 3226.78613281, 162.15766602), 'rotation':(0.320479, 90.125198, 0.316915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.55320312, 3232.45679688, 162.189375), 'rotation':(0.319182, 90.128288, 0.315623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.54097656, 3238.1271875, 162.22097656), 'rotation':(0.319182, 90.128288, 0.315623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.5287499999995, 3243.79808594, 162.25259766), 'rotation':(0.318335, 90.127213, 0.314806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.51609375, 3249.46851562, 162.28412109), 'rotation':(0.3166, 90.127182, 0.313106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.50386719, 3255.13941406, 162.31547852), 'rotation':(0.314728, 90.127174, 0.311278), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.4911718799995, 3260.81005859, 162.34666016), 'rotation':(0.312993, 90.127151, 0.309569), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.45359375, 3277.82203125, 162.43913086), 'rotation':(0.307659, 90.12709, 0.304364), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.44136719, 3283.49292969, 162.46960938), 'rotation':(0.305774, 90.127083, 0.302524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.41648438, 3294.83375, 162.53008789), 'rotation':(0.304906, 90.126778, 0.301679), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.2958593799995, 3349.94214844, 162.81603515999998), 'rotation':(0.287674, 90.126221, 0.284798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.28316406, 3355.6384375, 162.84481445), 'rotation':(0.287674, 90.126221, 0.284798), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.27046875, 3361.33496094, 162.87341797), 'rotation':(0.28404, 90.129082, 0.281239), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.24554688, 3372.72777344, 162.92988281), 'rotation':(0.280325, 90.126167, 0.277598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.23289062, 3378.42429688, 162.9577832), 'rotation':(0.27833, 90.12606, 0.27564), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.17039062, 3406.9064843799997, 163.09533203), 'rotation':(0.273153, 90.125771, 0.270557), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.12054688, 3429.69238281, 163.20280273), 'rotation':(0.267183, 90.125717, 0.264695), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.09566406, 3441.08546875, 163.25583008), 'rotation':(0.266357, 90.12574, 0.263887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.07078125, 3452.47851562, 163.30868164), 'rotation':(0.264697, 90.127686, 0.262272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6355.03316406, 3469.56789062, 163.38685547), 'rotation':(0.25982, 90.127251, 0.257477), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6355.02046875, 3475.26441406, 163.41268555), 'rotation':(0.259718, 90.127258, 0.257366), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.99554688, 3486.65773438, 163.46432617), 'rotation':(0.258775, 90.12365, 0.256436), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.9833593799995, 3492.35398438, 163.49006836), 'rotation':(0.258004, 90.128548, 0.255691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.95796875, 3503.74707031, 163.54136719), 'rotation':(0.256795, 90.123642, 0.254502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.94578125, 3509.44382812, 163.56689453), 'rotation':(0.256009, 90.128525, 0.253732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.93304688, 3515.140625, 163.59236328), 'rotation':(0.255394, 90.128532, 0.253145), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.3139062499995, 3515.16257812, 163.59237305), 'rotation':(-0.256012, -89.87146, -0.258331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.3388281200005, 3503.76929688, 163.54138672), 'rotation':(-0.257385, -89.87146, -0.259705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.35152344, 3498.07273438, 163.51578125), 'rotation':(-0.257996, -89.871429, -0.260345), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.41402344, 3469.59007812, 163.386875), 'rotation':(-0.261475, -89.875549, -0.263855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.42671875, 3463.89332031, 163.36097656), 'rotation':(-0.261475, -89.875549, -0.263855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.47652344, 3441.10765625, 163.25583984000002), 'rotation':(-0.266235, -89.870697, -0.268738), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.5014062499995, 3429.71460938, 163.20282226999998), 'rotation':(-0.268677, -89.874268, -0.27121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.5263281200005, 3418.32152344, 163.14938476999998), 'rotation':(-0.271637, -89.869446, -0.274261), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.53902344, 3412.6252343799997, 163.12244141), 'rotation':(-0.273163, -89.874237, -0.275787), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.5639062499995, 3401.23195312, 163.06811523), 'rotation':(-0.274658, -89.874207, -0.277313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.57664062, 3395.53589844, 163.04074219), 'rotation':(-0.276154, -89.874207, -0.278809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.60152344, 3384.1428125, 162.98556641), 'rotation':(-0.27832, -89.873901, -0.281036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.6513281200005, 3361.3571875, 162.87344726999999), 'rotation':(-0.287689, -89.87085, -0.290558), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.67671875, 3349.964375, 162.81605469), 'rotation':(-0.291382, -89.873718, -0.294342), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.81246094, 3570.12207031, 163.83738281), 'rotation':(0.25689, 90.129089, 0.254609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.80023438, 3575.8025, 163.86285156000002), 'rotation':(0.25689, 90.129089, 0.254609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.77535156, 3587.16257812, 163.91376953), 'rotation':(0.25689, 90.129089, 0.254609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.71285156, 3615.56347656, 164.04234375), 'rotation':(0.261419, 90.126038, 0.259041), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.67574219, 3632.60449219, 164.12025391), 'rotation':(0.263372, 90.127083, 0.260958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.6259375, 3655.32519531, 164.22626953), 'rotation':(0.274649, 90.12719, 0.272026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.61375, 3661.0051562500003, 164.25335938), 'rotation':(0.274649, 90.12719, 0.272026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.60101562, 3666.68554688, 164.28056641), 'rotation':(0.27652, 90.125717, 0.27386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.55125, 3689.40648438, 164.39033203), 'rotation':(0.280318, 90.126915, 0.2776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.41453125, 3751.8893749999997, 164.711875), 'rotation':(0.313588, 90.128212, 0.310171), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6362.80710938, 3746.2321875, 164.68130859000001), 'rotation':(-0.306793, -89.871826, -0.310089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.81976562, 3740.55226562, 164.65103516), 'rotation':(-0.30014, -89.871887, -0.303314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.8325, 3734.87179688, 164.62111328), 'rotation':(-0.296997, -89.871948, -0.300079), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.8446875, 3729.19164062, 164.59152343999997), 'rotation':(-0.293488, -89.871979, -0.296539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.85738281, 3723.51148438, 164.56228516), 'rotation':(-0.291779, -89.875397, -0.294769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.88226562, 3712.150625, 164.50435547), 'rotation':(-0.29187, -89.872253, -0.294861), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6362.9071875, 3700.79, 164.44666016), 'rotation':(-0.287964, -89.872986, -0.290863), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.91988281, 3695.109375, 164.41814452999998), 'rotation':(-0.280304, -89.873047, -0.283081), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.94476562, 3683.7490625, 164.3628125), 'rotation':(-0.27652, -89.871429, -0.279205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.99460938, 3661.0278125, 164.25335938), 'rotation':(-0.270905, -89.872833, -0.273468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.01898438, 3649.66773438, 164.19945312), 'rotation':(-0.26712, -89.872864, -0.269623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.03171875, 3643.98707031, 164.17285156000003), 'rotation':(-0.26712, -89.872864, -0.269623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.04390625, 3638.30710938, 164.14638672), 'rotation':(-0.263397, -89.872894, -0.265808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.06882812, 3626.94605469, 164.09419922), 'rotation':(-0.261414, -89.873932, -0.263794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.08148438, 3621.26609375, 164.06828125), 'rotation':(-0.261414, -89.873932, -0.263794), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.09371094, 3615.5859375, 164.04238281000002), 'rotation':(-0.261566, -89.873962, -0.263977), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.14398438, 3592.86523438, 163.93925781000002), 'rotation':(-0.256897, -89.870911, -0.259216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6363.15621094, 3587.18507812, 163.91380859), 'rotation':(-0.256897, -89.874878, -0.259216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.16890625, 3581.50488281, 163.88833984000001), 'rotation':(-0.256897, -89.874878, -0.259216), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.1810937499995, 3575.8246875, 163.86287109), 'rotation':(-0.256775, -89.870911, -0.259064), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6363.2060156200005, 3564.464375, 163.81193359), 'rotation':(-0.256531, -89.874481, -0.25885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.3060937499995, 3801.18265625, 164.99027343999998), 'rotation':(0.341591, 90.126114, 0.33754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.29390625, 3806.70851562, 165.02320312), 'rotation':(0.345088, 90.128235, 0.340958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.26949219, 3817.75976562, 165.08978516), 'rotation':(0.34931, 90.129044, 0.345075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.25726562, 3823.2864062500003, 165.12335938), 'rotation':(0.34931, 90.129044, 0.345075), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.22117188, 3839.86421875, 165.22625), 'rotation':(0.365722, 90.129265, 0.361086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.1849999999995, 3856.44164062, 165.33332031), 'rotation':(0.378065, 90.130516, 0.373101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.160625, 3867.49414062, 165.40628906), 'rotation':(0.382327, 90.126305, 0.377255), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.14839844, 3873.01976562, 165.44318359000002), 'rotation':(0.391083, 90.129379, 0.385768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6354.13617188, 3878.5456249999997, 165.48044922), 'rotation':(0.391083, 90.129379, 0.385768), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.1239843799995, 3884.07125, 165.51816406), 'rotation':(0.399648, 90.126556, 0.394099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.10007812, 3895.12328125, 165.59511719), 'rotation':(0.408281, 90.129608, 0.402512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.08785156, 3900.64890625, 165.63451172), 'rotation':(0.412646, 90.130119, 0.406732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.0756249999995, 3906.1753125, 165.67400390999998), 'rotation':(0.412646, 90.130119, 0.406732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.0634375, 3911.7009375, 165.71382812), 'rotation':(0.412625, 90.12558, 0.406723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.03953125, 3922.75320312, 165.79396484), 'rotation':(0.427898, 90.127899, 0.421542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6354.02730469, 3928.2790625, 165.83482422), 'rotation':(0.427898, 90.127899, 0.421542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6353.9911718799995, 3944.85640625, 165.96128906), 'rotation':(0.44834, 90.131569, 0.441355), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6353.97898438, 3950.38257812, 166.00457031000002), 'rotation':(0.453361, 90.129395, 0.44624), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6353.96675781, 3955.90820312, 166.04830077999998), 'rotation':(0.453443, 90.126083, 0.446321), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6362.37203125, 3944.88109375, 165.96132812), 'rotation':(-0.43811, -89.871948, -0.444855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.38375, 3939.35523438, 165.91849609000002), 'rotation':(-0.43811, -89.871948, -0.444855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.3959374999995, 3933.82960938, 165.87623047), 'rotation':(-0.427887, -89.872101, -0.434326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.40816406, 3928.3034374999997, 165.83486327999998), 'rotation':(-0.417786, -89.872253, -0.42392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.46871094, 3900.6731250000003, 165.63453125), 'rotation':(-0.408295, -89.873322, -0.414154), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.493125, 3889.6215625, 165.5565625), 'rotation':(-0.391083, -89.870605, -0.396454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.5170312499995, 3878.56984375, 165.48050781), 'rotation':(-0.382324, -89.873688, -0.387451), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.56585938, 3856.46507812, 165.33335938), 'rotation':(-0.373932, -89.873596, -0.378845), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.58980469, 3845.41359375, 165.2615625), 'rotation':(-0.365753, -89.870728, -0.370422), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.61421875, 3834.36132812, 165.19158202999998), 'rotation':(-0.357513, -89.873779, -0.362), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.6259375, 3828.83570312, 165.15708984), 'rotation':(-0.349335, -89.870911, -0.353607), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.6381249999995, 3823.31007812, 165.12339844), 'rotation':(-0.345245, -89.871765, -0.349426), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.66257812, 3812.25757812, 165.05654297), 'rotation':(-0.345093, -89.871765, -0.349274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.6747656200005, 3806.73140625, 165.02324219), 'rotation':(-0.341614, -89.873871, -0.345703), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6362.69867188, 3795.67992188, 164.95765625), 'rotation':(-0.334442, -89.870789, -0.338348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6602.46089844, 3540.56542969, 167.34994140999999), 'rotation':(-0.793182, 179.43364, -0.815399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6591.14203125, 3540.6796875, 167.19269531), 'rotation':(-0.800781, 179.433746, -0.823425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6557.1840625, 3541.02171875, 166.71486328), 'rotation':(-0.817993, 179.435104, -0.841614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6540.20554688, 3541.19289062, 166.47064453), 'rotation':(-0.828369, 179.43602, -0.8526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6534.54539062, 3541.2497656200003, 166.38876953), 'rotation':(-0.828369, 179.43602, -0.8526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6517.566875, 3541.42089844, 166.14296875), 'rotation':(-0.838409, 179.434891, -0.863251), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6511.90765625, 3541.47777344, 166.06021484000001), 'rotation':(-0.845245, 179.435104, -0.870483), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6506.2475, 3541.5346875, 165.97677734), 'rotation':(-0.852112, 179.43779, -0.877747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6500.58835938, 3541.59179688, 165.89267578), 'rotation':(-0.855408, 179.434219, -0.881226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6494.92964844, 3541.6486718799997, 165.80820312), 'rotation':(-0.855316, 179.436798, -0.881165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6489.26949219, 3541.70582031, 165.72367188), 'rotation':(-0.855499, 179.43428, -0.881317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6483.60984375, 3541.76269531, 165.63912109), 'rotation':(-0.855316, 179.436798, -0.881165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6455.31246094, 3542.04785156, 165.21384766), 'rotation':(-0.872223, 179.435654, -0.899078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6449.65230469, 3542.105, 165.1278125), 'rotation':(-0.872223, 179.435654, -0.899078), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6410.03609375, 3542.50390625, 164.52253906), 'rotation':(-0.881561, 179.436539, -0.909027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6398.71675781, 3542.61792969, 164.34796875), 'rotation':(-0.883911, 179.43692, -0.91153), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6387.3974218799995, 3542.73195312, 164.17330077999998), 'rotation':(-0.883881, 179.436935, -0.911469), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6381.73824219, 3542.7888281200003, 164.08595703), 'rotation':(-0.883881, 179.43544, -0.911499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6376.07859375, 3542.8459375, 163.99863281), 'rotation':(-0.883881, 179.43544, -0.911499), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6376.11960938, 3551.2265625, 163.99794922), 'rotation':(0.883881, -0.564545, 0.85691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6381.77925781, 3551.16945312, 164.08529297), 'rotation':(0.883881, -0.564545, 0.85691), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6387.4389062499995, 3551.11253906, 164.17261718999998), 'rotation':(0.883929, -0.56308, 0.856961), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6398.75777344, 3550.99851562, 164.34730469), 'rotation':(0.883867, -0.563049, 0.856917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6427.0560937499995, 3550.71335938, 164.78164062), 'rotation':(0.874667, -0.564697, 0.848266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6449.6942968799995, 3550.48535156, 165.12714843999998), 'rotation':(0.8674, -0.562714, 0.841429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6455.35398438, 3550.42847656, 165.21320312), 'rotation':(0.8674, -0.562714, 0.841429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6472.3325, 3550.2575781200003, 165.46921875), 'rotation':(0.85781, -0.564789, 0.832407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6483.65230469, 3550.14355469, 165.63851562), 'rotation':(0.855474, -0.563202, 0.830203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6511.95015625, 3549.86449219, 166.05958984), 'rotation':(0.838426, -0.565094, 0.814142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6517.60933594, 3549.81128906, 166.14234375), 'rotation':(0.831739, -0.565308, 0.807844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6528.92867188, 3549.6560156200003, 166.30632812), 'rotation':(0.828386, -0.565796, 0.80468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6534.58835938, 3549.59742188, 166.38818359), 'rotation':(0.828379, -0.563995, 0.804685), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6545.90765625, 3549.48339844, 166.55179688), 'rotation':(0.824902, -0.566345, 0.801417), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6562.8871875, 3549.31203125, 166.79486328), 'rotation':(0.811194, -0.565033, 0.788456), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6585.5263281200005, 3549.08421875, 167.11300781000003), 'rotation':(0.800799, -0.566254, 0.778634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6596.84617188, 3548.97023438, 167.27099609), 'rotation':(0.793258, -0.566406, 0.771516), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6602.50582031, 3548.91332031, 167.34941406000002), 'rotation':(0.788375, -0.566528, 0.766914), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6608.16546875, 3548.85621094, 167.42734375), 'rotation':(0.783184, -0.56662, 0.761974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6889.18501953, 3537.6753125, 170.92267578), 'rotation':(-0.672485, 179.426941, -0.688385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6883.53121094, 3537.73289062, 170.85628906000002), 'rotation':(-0.672577, 179.425034, -0.688538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6877.87837891, 3537.79027344, 170.78994140999998), 'rotation':(-0.672577, 179.425034, -0.688538), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6872.22457031, 3537.84765625, 170.72355469), 'rotation':(-0.672485, 179.425018, -0.688385), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6855.26460938, 3538.01953125, 170.52429688), 'rotation':(-0.674377, 179.429916, -0.690399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6843.95748047, 3538.13355469, 170.39115234000002), 'rotation':(-0.674561, 179.429886, -0.690582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6832.65083984, 3538.24730469, 170.25798827999998), 'rotation':(-0.674713, 179.429886, -0.690735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6826.99751953, 3538.30421875, 170.19142578), 'rotation':(-0.6763, 179.430923, -0.692413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6821.34419922, 3538.36109375, 170.12470703), 'rotation':(-0.6763, 179.430923, -0.692413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6804.38472656, 3538.53199219, 169.92345702999998), 'rotation':(-0.686584, 179.431168, -0.703186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6798.73140625, 3538.58886719, 169.85591797), 'rotation':(-0.686584, 179.431168, -0.703186), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6787.42476562, 3538.7028906200003, 169.72025391), 'rotation':(-0.688354, 179.429932, -0.705048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6781.77144531, 3538.75976562, 169.65230469), 'rotation':(-0.689758, 179.432251, -0.706512), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.46578125, 3538.87351562, 169.5159375), 'rotation':(-0.695312, 179.432388, -0.712341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6753.50630859, 3539.04445312, 169.30923828), 'rotation':(-0.703857, 179.432602, -0.721313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6747.8525, 3539.1013281200003, 169.23974609), 'rotation':(-0.706787, 179.432632, -0.724396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6730.89400391, 3539.27195312, 169.02974609), 'rotation':(-0.713654, 179.431686, -0.731598), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6725.24068359, 3539.32886719, 168.95931640999999), 'rotation':(-0.718872, 179.431824, -0.737061), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6713.93404297, 3539.44289062, 168.81763672), 'rotation':(-0.724243, 179.431976, -0.742706), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6708.28121094, 3539.4997656200003, 168.74619141), 'rotation':(-0.729584, 179.432098, -0.748322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6680.0165625, 3539.78441406, 168.38494140999998), 'rotation':(-0.737, 179.432404, -0.756165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6668.71140625, 3539.8982031200003, 168.23912109), 'rotation':(-0.74884, 179.431046, -0.768616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6646.15035156, 3548.50660156, 167.94046875), 'rotation':(0.76464, -0.566559, 0.744425), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6651.80367188, 3548.4496875, 168.0159375), 'rotation':(0.756723, -0.566803, 0.736931), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6663.10933594, 3548.3359375, 168.16503906000003), 'rotation':(0.748855, -0.566956, 0.729464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6674.415, 3548.2221875, 168.31179688), 'rotation':(0.736984, -0.567596, 0.718211), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6685.72115234, 3548.10816406, 168.45726562), 'rotation':(0.734553, -0.568634, 0.715893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6691.37447266, 3548.05125, 168.52982422000002), 'rotation':(0.729573, -0.567902, 0.711176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6697.02730469, 3547.99414062, 168.60214843999998), 'rotation':(0.729573, -0.567902, 0.711176), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6702.68013672, 3547.9372656200003, 168.67414062), 'rotation':(0.724232, -0.566498, 0.706085), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6713.98628906, 3547.82347656, 168.81724609), 'rotation':(0.71885, -0.568176, 0.70098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6725.29292969, 3547.70972656, 168.95892578), 'rotation':(0.713604, -0.568268, 0.695989), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6736.59957031, 3547.59570312, 169.09957031000002), 'rotation':(0.709418, -0.567261, 0.692011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6742.25240234, 3547.5388281200003, 169.16960938), 'rotation':(0.706774, -0.569916, 0.689507), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6747.90621094, 3547.48167969, 169.23935547000002), 'rotation':(0.703865, -0.567383, 0.686736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6764.86617188, 3547.31101562, 169.44695312), 'rotation':(0.6953, -0.567596, 0.678583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.51851562, 3547.25414062, 169.51554688), 'rotation':(0.69252, -0.567719, 0.675928), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6810.09175781, 3546.85863281, 169.99042968999998), 'rotation':(0.679795, -0.56897, 0.663808), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6821.39839844, 3546.75148438, 170.12433593999998), 'rotation':(0.674693, -0.567932, 0.658952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6855.31880859, 3546.3669531200003, 170.52392577999998), 'rotation':(0.673539, -0.570099, 0.65785), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6866.62496094, 3546.25269531, 170.65679688), 'rotation':(0.672466, -0.573029, 0.656822), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6877.93208984, 3546.13769531, 170.78957031000002), 'rotation':(0.672473, -0.574982, 0.656815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6883.58541016, 3546.0803125, 170.8559375), 'rotation':(0.672473, -0.574982, 0.656815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6889.23873047, 3546.02296875, 170.92230468999998), 'rotation':(0.672473, -0.574982, 0.656815), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6943.79048828, 3537.12035156, 171.56972656000002), 'rotation':(-0.686188, 179.42392, -0.702759), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6965.96041016, 3536.895, 171.83775391), 'rotation':(-0.695709, 179.426498, -0.712769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6971.50240234, 3536.83863281, 171.90548828), 'rotation':(-0.698944, 179.42662, -0.716156), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.58833984, 3536.72582031, 172.04183593999997), 'rotation':(-0.705261, 179.424393, -0.722778), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6988.12935547, 3536.6696875, 172.11023438), 'rotation':(-0.707092, 179.42688, -0.724701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6993.67232422, 3536.61328125, 172.17908203), 'rotation':(-0.707092, 179.42688, -0.724701), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(7021.38570312, 3536.33179688, 172.53177734000002), 'rotation':(-0.734558, 179.426453, -0.753601), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7026.92671875, 3536.26246094, 172.60396484), 'rotation':(-0.745605, 179.428238, -0.765198), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7027.024375, 3544.66871094, 172.60414062), 'rotation':(0.751287, -0.572205, 0.731777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7015.94039062, 3544.76804688, 172.45998047), 'rotation':(0.745611, -0.573273, 0.726394), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6993.77095703, 3544.99339844, 172.17923828), 'rotation':(0.712498, -0.572601, 0.694942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.68501953, 3545.10621094, 172.04199218999997), 'rotation':(0.707034, -0.57486, 0.689745), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6977.14253906, 3545.16257812, 171.97367188), 'rotation':(0.705306, -0.573242, 0.688108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6971.60005859, 3545.21875, 171.90564453), 'rotation':(0.702253, -0.573273, 0.685195), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6954.97310547, 3545.38769531, 171.70330077999998), 'rotation':(0.692697, -0.575958, 0.676102), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6943.88863281, 3545.50046875, 171.56988281000002), 'rotation':(0.689337, -0.573578, 0.672895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6938.34566406, 3545.55664062, 171.50359375), 'rotation':(0.686236, -0.5737, 0.669942), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6932.80269531, 3545.61304688, 171.43757812), 'rotation':(0.683026, -0.57373, 0.666887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6927.26021484, 3545.66945312, 171.37164062), 'rotation':(0.681305, -0.574982, 0.66525), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.00578125, 3546.55199219, 158.98149414), 'rotation':(-0.543854, 179.428543, -0.55423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6018.95359375, 3546.441875, 159.08923828000002), 'rotation':(-0.567749, 179.427811, -0.579071), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6029.9013281200005, 3546.33179688, 159.19962891), 'rotation':(-0.584045, 179.429428, -0.596039), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6040.84859375, 3546.22144531, 159.31401367), 'rotation':(-0.605774, 179.429886, -0.618683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6046.32367188, 3546.16625, 159.37272461), 'rotation':(-0.616486, 179.430115, -0.629852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6051.79734375, 3546.11132812, 159.43243164), 'rotation':(-0.627411, 179.430283, -0.641266), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6073.691875, 3545.8908593799997, 159.67987305), 'rotation':(-0.654541, 179.431183, -0.669617), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6002.555625, 3554.98804688, 158.92862305), 'rotation':(0.543034, -0.572083, 0.532817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6018.99015625, 3554.8225, 159.08875977), 'rotation':(0.57321, -0.570831, 0.561829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6029.9467187499995, 3554.71242188, 159.19923828), 'rotation':(0.594793, -0.570404, 0.582551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6040.9028125, 3554.60230469, 159.31369141), 'rotation':(0.616479, -0.572357, 0.603318), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6046.38226562, 3554.5471093799997, 159.37245117), 'rotation':(0.627407, -0.569702, 0.613776), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6051.859375, 3554.4919531200003, 159.4321875), 'rotation':(0.638363, -0.569397, 0.624257), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6068.2943749999995, 3554.32617188, 159.61716797), 'rotation':(0.654544, -0.570465, 0.639704), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6338.1044531200005, 3543.22804688, 163.41259766), 'rotation':(-0.883423, 179.434692, -0.91098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6326.7821875, 3543.34226562, 163.23805664), 'rotation':(-0.881897, 179.437088, -0.909363), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6321.12109375, 3543.39917969, 163.1509082), 'rotation':(-0.881042, 179.437027, -0.908478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6315.45945312, 3543.45628906, 163.06382812), 'rotation':(-0.88028, 179.437012, -0.907654), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6309.7982812499995, 3543.51320312, 162.97683594), 'rotation':(-0.879456, 179.43457, -0.906769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6287.15328125, 3543.74144531, 162.62958984), 'rotation':(-0.877502, 179.43576, -0.904724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6281.4921875, 3543.79859375, 162.54291992), 'rotation':(-0.875183, 179.436661, -0.902252), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6275.83, 3543.85546875, 162.45648438), 'rotation':(-0.870789, 179.436523, -0.897583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6258.8466406200005, 3544.02636719, 162.19962891), 'rotation':(-0.859619, 179.435608, -0.885712), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6247.52140625, 3544.140625, 162.02972656), 'rotation':(-0.857269, 179.434982, -0.883209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6230.53757812, 3544.31152344, 161.77737305), 'rotation':(-0.842133, 179.436798, -0.867157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6168.2578125, 3544.93871094, 160.88739257999998), 'rotation':(-0.780365, 179.434814, -0.801849), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6151.27, 3545.1096093799997, 160.65598633), 'rotation':(-0.768555, 179.43399, -0.789368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.60789062, 3545.16675781, 160.57977539), 'rotation':(-0.760498, 179.433792, -0.780884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6139.9467187499995, 3545.22363281, 160.50436523), 'rotation':(-0.752838, 179.430893, -0.772827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6111.6328125, 3545.50878906, 160.13978516), 'rotation':(-0.717224, 179.43158, -0.735352), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6134.3403125, 3553.66113281, 160.42941406), 'rotation':(0.752748, -0.566406, 0.733173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6145.6640625, 3553.5471093799997, 160.57939453), 'rotation':(0.76854, -0.56601, 0.748132), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6151.32609375, 3553.49, 160.65560546999998), 'rotation':(0.776429, -0.565796, 0.755594), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6156.98828125, 3553.433125, 160.73250977), 'rotation':(0.780452, -0.567627, 0.75941), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6162.649375, 3553.37597656, 160.80962891), 'rotation':(0.780294, -0.565155, 0.759264), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6173.9740624999995, 3553.26195312, 160.96484375), 'rotation':(0.795007, -0.564514, 0.773173), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6179.6357031200005, 3553.20507812, 161.04350586), 'rotation':(0.804863, -0.566376, 0.782484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6185.296875, 3553.14796875, 161.12304688), 'rotation':(0.814582, -0.566101, 0.791663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6219.26804688, 3552.80589844, 161.61095703), 'rotation':(0.837183, -0.563324, 0.812969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6230.59078125, 3552.691875, 161.77691406), 'rotation':(0.84708, -0.563049, 0.822304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6236.25242188, 3552.635, 161.86057617), 'rotation':(0.852175, -0.565155, 0.827103), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6241.91351562, 3552.5778906200003, 161.94470703000002), 'rotation':(0.857264, -0.565002, 0.831899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6253.23625, 3552.46386719, 162.11414062), 'rotation':(0.859613, -0.564392, 0.834106), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6258.8984375, 3552.40699219, 162.19913086), 'rotation':(0.861949, -0.563751, 0.836314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6264.5599999999995, 3552.34984375, 162.2843457), 'rotation':(0.86643, -0.56366, 0.840521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6298.5278125, 3552.0078125, 162.80257812), 'rotation':(0.878738, -0.563049, 0.852087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6304.1889062499995, 3551.95070312, 162.88942383), 'rotation':(0.879435, -0.562958, 0.852739), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6315.51117188, 3551.83691406, 163.06332031), 'rotation':(0.880958, -0.565369, 0.854181), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6321.1728125, 3551.77976562, 163.15041015999998), 'rotation':(0.881969, -0.562958, 0.855117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6326.83390625, 3551.7263281200003, 163.23754883), 'rotation':(0.882727, -0.562927, 0.85583), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6875.23335938, 3772.80101562, 172.79945312), 'rotation':(-0.808899, 179.821945, -0.832001), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.915, 3772.8385937499997, 172.63955077999998), 'rotation':(-0.810364, 179.820404, -0.833527), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6846.93648438, 3772.89476562, 172.39884766), 'rotation':(-0.814117, 179.819534, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6841.27730469, 3772.91382812, 172.31839843999998), 'rotation':(-0.814148, 179.822327, -0.837524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.95796875, 3772.95140625, 172.15751953), 'rotation':(-0.81601, 179.821442, -0.839478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6824.29878906, 3772.97023438, 172.07695311999998), 'rotation':(-0.81601, 179.821442, -0.839478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6818.63912109, 3772.98898438, 171.99632812), 'rotation':(-0.819489, 179.821548, -0.843201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6812.97994141, 3773.0078125, 171.91535156), 'rotation':(-0.823212, 179.821655, -0.847137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6807.32076172, 3773.02664062, 171.83429688), 'rotation':(-0.823212, 179.821655, -0.847137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.66109375, 3773.04539062, 171.75294922), 'rotation':(-0.826782, 179.821762, -0.850891), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6790.34224609, 3773.08296875, 171.58972656000003), 'rotation':(-0.828369, 179.822342, -0.8526), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.02339844, 3773.120625, 171.42601562), 'rotation':(-0.828461, 179.819611, -0.852692), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6750.7275, 3773.214375, 171.01435547), 'rotation':(-0.84201, 179.822311, -0.867035), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6745.06783203, 3773.2331249999997, 170.93117188), 'rotation':(-0.841949, 179.822342, -0.866974), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6728.09029297, 3773.28953125, 170.68150391), 'rotation':(-0.844574, 179.822449, -0.869751), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6722.430625, 3773.30835938, 170.59806641), 'rotation':(-0.849945, 179.822601, -0.875458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6711.1122656200005, 3773.3459375, 170.43013672), 'rotation':(-0.855164, 179.821121, -0.880981), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6705.45259766, 3773.36476562, 170.34564453), 'rotation':(-0.860229, 179.822922, -0.886353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6688.47554688, 3773.42117188, 170.09042968999998), 'rotation':(-0.863007, 179.822083, -0.889313), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6682.81734375, 3773.43992188, 170.00519531), 'rotation':(-0.862854, 179.822083, -0.88916), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6671.49800781, 3773.4775, 169.83464844), 'rotation':(-0.866577, 179.822739, -0.893097), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6665.83929688, 3773.49632812, 169.74912109000002), 'rotation':(-0.873901, 179.822952, -0.900848), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6660.17964844, 3773.51492188, 169.66294922), 'rotation':(-0.877625, 179.821487, -0.904846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6654.52484375, 3773.48976562, 169.57640625), 'rotation':(-0.877472, 179.823807, -0.904663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6648.86570312, 3773.44773438, 169.48970702999998), 'rotation':(-0.877472, 179.823807, -0.904663), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6643.20210938, 3773.441875, 169.40292968999998), 'rotation':(-0.877686, 179.823807, -0.904907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6641.22359375, 3782.08835938, 169.3721875), 'rotation':(0.877474, -0.176208, 0.850907), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6654.513125, 3781.95921875, 169.57580077999998), 'rotation':(0.877625, -0.176178, 0.851042), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6660.16988281, 3781.89601562, 169.66238281000003), 'rotation':(0.8738, -0.177032, 0.847454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6677.14693359, 3781.839375, 169.91933594), 'rotation':(0.862933, -0.17572, 0.837222), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6722.41890625, 3781.68921875, 170.59748047000002), 'rotation':(0.844621, -0.177551, 0.819994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6739.39644531, 3781.6328125, 170.84738281000003), 'rotation':(0.84193, -0.177673, 0.817457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6745.055625, 3781.61421875, 170.93056640999998), 'rotation':(0.84193, -0.177673, 0.817457), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6756.37398438, 3781.57664062, 171.09671875), 'rotation':(0.838686, -0.179413, 0.814396), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6762.03267578, 3781.55765625, 171.17943359), 'rotation':(0.831931, -0.177979, 0.808025), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6779.01021484, 3781.48609375, 171.42542969), 'rotation':(0.828536, -0.177643, 0.804827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6790.32857422, 3781.430625, 171.58912109000002), 'rotation':(0.82674, -0.179688, 0.803131), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.64693359, 3781.3928125, 171.75234375), 'rotation':(0.823249, -0.178345, 0.79984), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6807.30660156, 3781.3740625, 171.83367188), 'rotation':(0.819479, -0.178436, 0.796289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.94332031, 3781.2990625, 172.15691406000002), 'rotation':(0.814391, -0.177673, 0.791484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6858.23921875, 3781.20507812, 172.55884766), 'rotation':(0.810416, -0.179596, 0.787716), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6869.55806641, 3781.16726562, 172.71890625), 'rotation':(0.808913, -0.17804, 0.786303), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6576.82222656, 3773.7917187499997, 168.37453125), 'rotation':(-0.900574, 179.823273, -0.92923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6571.1528125, 3773.81054688, 168.28548827999998), 'rotation':(-0.905212, 179.825241, -0.934174), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6554.14304688, 3773.86695312, 168.01644531000002), 'rotation':(-0.91214, 179.824203, -0.941559), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6525.79390625, 3773.96117188, 167.56507812), 'rotation':(-0.916107, 179.824493, -0.94577), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6514.45554688, 3773.9987499999997, 167.38375), 'rotation':(-0.920135, 179.824982, -0.950073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6508.78511719, 3774.01757812, 167.29267578), 'rotation':(-0.920227, 179.824982, -0.950165), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6497.44578125, 3774.05515625, 167.11048828), 'rotation':(-0.920837, 179.825027, -0.950806), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6491.77585938, 3774.07398438, 167.01935547000002), 'rotation':(-0.921936, 179.822754, -0.951996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6486.1059375, 3774.0928125, 166.92816406000003), 'rotation':(-0.923187, 179.825104, -0.953308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6469.0966406200005, 3774.14914062, 166.65382812), 'rotation':(-0.925507, 179.82518, -0.95578), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6457.75726562, 3774.18703125, 166.47039062), 'rotation':(-0.927887, 179.822922, -0.958282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6452.0873437499995, 3774.2057812499997, 166.37851562), 'rotation':(-0.929108, 179.825317, -0.959625), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6412.399375, 3774.33765625, 165.73427734), 'rotation':(-0.930267, 179.823837, -0.960846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6401.0599999999995, 3774.37523438, 165.55011718999998), 'rotation':(-0.930176, 179.82547, -0.960754), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6389.7196875, 3774.4128124999997, 165.3659375), 'rotation':(-0.930267, 179.823837, -0.960846), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6384.05023438, 3774.431875, 165.27386718999998), 'rotation':(-0.929474, 179.826584, -0.959991), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6378.3871875, 3774.37523438, 165.18195312), 'rotation':(-0.927704, 179.824371, -0.95813), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6376.80953125, 3782.94382812, 165.15585938), 'rotation':(0.92952, -0.175568, 0.899721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6395.3935156200005, 3782.77492188, 165.45763672), 'rotation':(0.930265, -0.176178, 0.900418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6401.06296875, 3782.75609375, 165.54970702999998), 'rotation':(0.930265, -0.176178, 0.900418), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6412.40179688, 3782.71851562, 165.73386718999998), 'rotation':(0.930046, -0.176331, 0.900209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6418.0717187499995, 3782.6996875, 165.82595702999998), 'rotation':(0.930046, -0.176331, 0.900209), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6423.7411718799995, 3782.6809375000003, 165.91800781), 'rotation':(0.929794, -0.174316, 0.899979), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6429.410625, 3782.661875, 166.01003906000003), 'rotation':(0.929636, -0.175476, 0.899827), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6435.08054688, 3782.64304688, 166.10208984000002), 'rotation':(0.929582, -0.175476, 0.899777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6440.75046875, 3782.62429688, 166.19410156), 'rotation':(0.929582, -0.175476, 0.899777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6452.08929688, 3782.58664062, 166.37810547), 'rotation':(0.927786, -0.174713, 0.89809), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6463.4286718799995, 3782.5490625, 166.56175781000002), 'rotation':(0.92545, -0.174805, 0.895898), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6474.7670312499995, 3782.51148438, 166.74496093999997), 'rotation':(0.923093, -0.174866, 0.89371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6480.43746094, 3782.49242188, 166.83638672), 'rotation':(0.923093, -0.174866, 0.89371), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6486.1068749999995, 3782.4739062500003, 166.92771484000002), 'rotation':(0.922007, -0.174927, 0.892684), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6491.7763281200005, 3782.45460938, 167.01894531000002), 'rotation':(0.92075, -0.174957, 0.891521), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6497.44578125, 3782.43601562, 167.11005859), 'rotation':(0.920231, -0.175018, 0.89101), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6514.45503906, 3782.37960938, 167.38332031000002), 'rotation':(0.916161, -0.175507, 0.887208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.4638281200005, 3782.30445312, 167.65494141), 'rotation':(0.911967, -0.175781, 0.883274), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6537.13277344, 3782.27195312, 167.74521484000002), 'rotation':(0.912035, -0.175812, 0.88333), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6542.80269531, 3782.25242188, 167.83548828), 'rotation':(0.912158, -0.173828, 0.883446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6548.47210938, 3782.23367188, 167.92576172), 'rotation':(0.912158, -0.173828, 0.883446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6565.48140625, 3782.17726562, 168.19568359000002), 'rotation':(0.900574, -0.174896, 0.87258), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6576.82078125, 3782.1396875, 168.3740625), 'rotation':(0.896025, -0.176849, 0.868324), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6588.16011719, 3782.10203125, 168.55128906000002), 'rotation':(0.893717, -0.176605, 0.866142), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6593.82953125, 3782.08296875, 168.63974609000002), 'rotation':(0.893792, -0.176636, 0.86622), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6605.169375, 3782.04539062, 168.81671875), 'rotation':(0.890991, -0.177551, 0.86361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6340.3466406200005, 3774.56320312, 164.56697266), 'rotation':(-0.920959, 179.48996, -0.950958), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6317.6732812499995, 3774.87476562, 164.2034375), 'rotation':(-0.913208, 179.454971, -0.942688), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6300.66351562, 3775.04101562, 163.9328125), 'rotation':(-0.908569, 179.4561, -0.937744), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6289.32367188, 3775.151875, 163.75292969), 'rotation':(-0.90506, 179.454956, -0.93399), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6272.3134375, 3775.318125, 163.48467773000002), 'rotation':(-0.894958, 179.455322, -0.923279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6255.30320312, 3775.48414062, 163.21879883), 'rotation':(-0.892548, 179.454666, -0.920715), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6249.6328125, 3775.53953125, 163.13042969), 'rotation':(-0.887878, 179.454514, -0.915741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6243.9628125, 3775.5950000000003, 163.04248047), 'rotation':(-0.883148, 179.454315, -0.910675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6226.953125, 3775.76101562, 162.78130859), 'rotation':(-0.868713, 179.451645, -0.895386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6221.2826562499995, 3775.81640625, 162.69509766), 'rotation':(-0.863892, 179.453766, -0.890259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6215.61273438, 3775.87179688, 162.60932617), 'rotation':(-0.863892, 179.453766, -0.890259), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.94234375, 3775.92726562, 162.52398438), 'rotation':(-0.859192, 179.453629, -0.885284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6187.2596875, 3776.14867188, 162.18576172), 'rotation':(-0.842255, 179.452194, -0.86731), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6181.5888281200005, 3776.2040625, 162.10250976999998), 'rotation':(-0.832733, 179.45195, -0.857208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6175.9184375, 3776.25929688, 162.02006836), 'rotation':(-0.823059, 179.453537, -0.846954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.90671875, 3776.42554688, 161.77620117), 'rotation':(-0.818237, 179.451721, -0.841858), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.564375, 3776.5364062500003, 161.6146875), 'rotation':(-0.798462, 179.452164, -0.820923), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.2128125, 3776.81320312, 161.22335938), 'rotation':(-0.765533, 179.4505, -0.786194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6113.56734375, 3785.24929688, 161.14651367), 'rotation':(0.772105, -0.548553, 0.751498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6119.23875, 3785.19382812, 161.22260742), 'rotation':(0.772105, -0.548553, 0.751498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6124.90867188, 3785.1384375, 161.29904297), 'rotation':(0.785274, -0.549805, 0.763956), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6130.57859375, 3785.08296875, 161.37663086), 'rotation':(0.798442, -0.547821, 0.776408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6136.24898438, 3785.0278125, 161.45480469), 'rotation':(0.798442, -0.547821, 0.776408), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6141.91890625, 3784.97242188, 161.53384766), 'rotation':(0.811645, -0.547455, 0.78889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6147.58929688, 3784.91703125, 161.61387695), 'rotation':(0.811645, -0.547455, 0.78889), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6153.2592187499995, 3784.8615625, 161.69436523000002), 'rotation':(0.818222, -0.548279, 0.795094), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.92914062, 3784.80617188, 161.7753418), 'rotation':(0.818263, -0.548309, 0.795137), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6164.5990624999995, 3784.7509375, 161.85633789), 'rotation':(0.822997, -0.548309, 0.799603), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6175.939375, 3784.64039062, 162.01917969), 'rotation':(0.832778, -0.546173, 0.808828), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6192.9496875, 3784.47414062, 162.26875), 'rotation':(0.852052, -0.547485, 0.82699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6198.62109375, 3784.42039062, 162.35324219), 'rotation':(0.856806, -0.547394, 0.831468), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.95890625, 3784.30789062, 162.52300781), 'rotation':(0.863889, -0.546234, 0.838129), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6215.629375, 3784.25242188, 162.60833984), 'rotation':(0.868718, -0.546082, 0.84267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6221.29875, 3784.19726562, 162.6940918), 'rotation':(0.868718, -0.546082, 0.84267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6226.96875, 3784.1418750000003, 162.78030273000002), 'rotation':(0.87354, -0.545929, 0.847205), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6232.6381249999995, 3784.08640625, 162.86691406), 'rotation':(0.878226, -0.545807, 0.851609), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6249.64742188, 3783.92039062, 163.129375), 'rotation':(0.892569, -0.545349, 0.865069), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6260.98625, 3783.79835938, 163.30631836), 'rotation':(0.894973, -0.546448, 0.867322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6272.3256249999995, 3783.66578125, 163.48359375), 'rotation':(0.898368, -0.545227, 0.870522), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6306.34273438, 3783.33351562, 164.02171875), 'rotation':(0.910116, -0.545105, 0.881541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6312.0121875, 3783.27804688, 164.11189453), 'rotation':(0.913142, -0.544983, 0.884379), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6317.6815625, 3783.22289062, 164.20228516), 'rotation':(0.91629, -0.544922, 0.887314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6323.3515625, 3783.1675, 164.29292969), 'rotation':(0.91629, -0.544922, 0.887314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6329.0209374999995, 3783.11234375, 164.38369140999998), 'rotation':(0.919473, -0.54483, 0.890304), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6334.69140625, 3783.05664062, 164.47472656000002), 'rotation':(0.923175, -0.51123, 0.893777), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6075.51414062, 3777.24, 160.65414062), 'rotation':(-0.703156, 179.448273, -0.720581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.90085938, 3777.2946875, 160.5847168), 'rotation':(-0.703156, 179.448273, -0.720581), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6064.28757812, 3777.34960938, 160.51583984), 'rotation':(-0.69574, 179.448685, -0.712799), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.67523438, 3777.40429688, 160.44764648), 'rotation':(-0.695892, 179.448685, -0.712952), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6041.83492188, 3777.56882812, 160.24597656), 'rotation':(-0.66861, 179.448624, -0.684387), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6036.22117188, 3777.6237499999997, 160.18104492), 'rotation':(-0.650482, 179.446335, -0.665375), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6019.3803124999995, 3777.788125, 159.99402344), 'rotation':(-0.623138, 179.446838, -0.63681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.1537499999995, 3777.89796875, 159.87217773), 'rotation':(-0.606506, 179.446274, -0.619446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6008.17671875, 3786.2785937500003, 159.87155273), 'rotation':(0.617722, -0.553436, 0.604502), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6013.79390625, 3786.22359375, 159.93235352), 'rotation':(0.623125, -0.553162, 0.609681), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6025.02828125, 3786.11398438, 160.05484375), 'rotation':(0.632387, -0.552216, 0.61855), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6036.2621875, 3786.00414062, 160.18057617), 'rotation':(0.668634, -0.551392, 0.653155), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.49609375, 3785.89453125, 160.31170898), 'rotation':(0.686823, -0.552795, 0.670494), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6058.73046875, 3785.78492188, 160.44732421999998), 'rotation':(0.695723, -0.548859, 0.678988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6064.3466406200005, 3785.73023438, 160.51556641), 'rotation':(0.703168, -0.551727, 0.686048), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6075.5795312499995, 3785.62039062, 160.65394531), 'rotation':(0.717655, -0.551361, 0.699839), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6069.44382812, 3974.6535937500003, 161.72480469), 'rotation':(-0.785889, 179.719742, -0.807678), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.29632812, 3974.71023438, 161.57302734), 'rotation':(-0.770569, 179.719345, -0.791504), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6030.42523438, 3974.85203125, 161.20800781), 'rotation':(-0.73233, 179.718063, -0.751221), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6019.27679688, 3974.90867188, 161.06619141), 'rotation':(-0.721954, 179.718323, -0.740326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6013.7040625, 3974.93703125, 160.9959375), 'rotation':(-0.701324, 179.716385, -0.718628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6002.56101562, 3983.37453125, 160.85915039), 'rotation':(0.70131, -0.2836, 0.684302), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6013.71578125, 3983.31789062, 160.99555664), 'rotation':(0.721985, -0.281708, 0.703953), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6030.4453125, 3983.23265625, 161.20770507999998), 'rotation':(0.732073, -0.281921, 0.71354), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6036.02195312, 3983.2043750000003, 161.27931640999998), 'rotation':(0.739921, -0.281464, 0.72099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6047.17375, 3983.1475, 161.42439453), 'rotation':(0.75531, -0.282501, 0.735582), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6058.328125, 3983.09078125, 161.57289062), 'rotation':(0.785861, -0.280243, 0.764528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6063.90421875, 3983.0625, 161.64821289), 'rotation':(0.785861, -0.280243, 0.764528), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6075.05710938, 3983.00585938, 161.80160156), 'rotation':(0.793682, -0.280396, 0.771926), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6339.16109375, 3973.1953125, 165.90478516), 'rotation':(-0.942474, 179.723557, -0.973877), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6305.22992188, 3973.45460938, 165.34689453), 'rotation':(-0.937775, 179.724075, -0.968872), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6276.9775, 3973.598125, 164.88582031), 'rotation':(-0.93396, 179.725372, -0.964783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6265.67671875, 3973.65578125, 164.70183594), 'rotation':(-0.925934, 179.723694, -0.956268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6226.12296875, 3973.85695312, 164.06644531), 'rotation':(-0.912445, 179.724854, -0.941895), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.17085938, 3973.943125, 163.79733398), 'rotation':(-0.900818, 179.722107, -0.929474), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6203.5209374999995, 3973.97195312, 163.7084668), 'rotation':(-0.893158, 179.723541, -0.921326), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6192.21875, 3974.02929688, 163.53234375), 'rotation':(-0.885376, 179.721619, -0.913055), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6186.56882812, 3974.058125, 163.44500976999998), 'rotation':(-0.881653, 179.721649, -0.909119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6180.9169531200005, 3974.086875, 163.35796875), 'rotation':(-0.881409, 179.72435, -0.908844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6175.2670312499995, 3974.11546875, 163.27101562), 'rotation':(-0.881653, 179.721649, -0.909119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6169.61617188, 3974.14429688, 163.18405273), 'rotation':(-0.881409, 179.72168, -0.908844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.0121875, 3974.25929688, 162.84019531), 'rotation':(-0.850555, 179.720428, -0.876099), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6135.70945312, 3974.316875, 162.67265625), 'rotation':(-0.846069, 179.72049, -0.871338), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6130.05859375, 3974.34546875, 162.58918945), 'rotation':(-0.846008, 179.72052, -0.871277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6118.7578125, 3974.40304688, 162.42228516), 'rotation':(-0.846008, 179.72052, -0.871277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6113.10734375, 3974.431875, 162.33881836), 'rotation':(-0.839355, 179.720917, -0.864197), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6107.455, 3974.46046875, 162.25601562), 'rotation':(-0.825836, 179.720551, -0.849884), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6333.52140625, 3981.69164062, 165.81130859), 'rotation':(0.942409, -0.276428, 0.911779), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6322.22117188, 3981.7490625, 165.62554688), 'rotation':(0.941596, -0.277069, 0.911011), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6310.92039062, 3981.80664062, 165.43976562), 'rotation':(0.94148, -0.275208, 0.910903), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6299.61960938, 3981.86398438, 165.25433593999998), 'rotation':(0.937764, -0.275909, 0.907443), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6293.96921875, 3981.8928125, 165.16220703), 'rotation':(0.93394, -0.274628, 0.903852), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6288.31882812, 3981.92164062, 165.07005859), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6282.6684375, 3981.95015625, 164.97792969), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6277.0185156200005, 3981.97898438, 164.88578125), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6271.36765625, 3982.0078125, 164.79365234), 'rotation':(0.93394, -0.276642, 0.90386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6265.71773438, 3982.03664062, 164.70179688), 'rotation':(0.93118, -0.276123, 0.901269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6248.76609375, 3982.12257812, 164.42777343999998), 'rotation':(0.925907, -0.276306, 0.896331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6243.11570312, 3982.15140625, 164.33695312), 'rotation':(0.920532, -0.276489, 0.891308), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6237.46578125, 3982.18015625, 164.24666016), 'rotation':(0.915225, -0.276672, 0.886322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6231.8139062499995, 3982.20875, 164.15642577999998), 'rotation':(0.915225, -0.276672, 0.886322), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6209.211875, 3982.32375, 163.79728516), 'rotation':(0.908641, -0.276001, 0.880152), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6197.910625, 3982.38132812, 163.62017578), 'rotation':(0.893184, -0.278137, 0.865657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6175.30804688, 3982.49609375, 163.27097656), 'rotation':(0.881402, -0.27832, 0.854579), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6169.6571875, 3982.52492188, 163.18402344), 'rotation':(0.881572, -0.27832, 0.854736), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6158.3544531200005, 3982.58226562, 163.01060547), 'rotation':(0.877058, -0.278717, 0.850505), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6152.7040625, 3982.61109375, 162.92496094), 'rotation':(0.868219, -0.279022, 0.842201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6147.05320312, 3982.63992188, 162.84016602), 'rotation':(0.859313, -0.277008, 0.833825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6141.4028125, 3982.66867188, 162.75619140999999), 'rotation':(0.85055, -0.279541, 0.825571), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6135.75046875, 3982.6975, 162.67263671999999), 'rotation':(0.846014, -0.27948, 0.821297), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6124.4496875, 3982.75484375, 162.50572266), 'rotation':(0.846001, -0.277466, 0.821298), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6118.79875, 3982.78367188, 162.42225586), 'rotation':(0.846069, -0.27951, 0.82135), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6597.57222656, 3971.96804688, 170.18123047), 'rotation':(-0.941284, 179.725067, -0.972626), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6563.649375, 3972.14039062, 169.62371094), 'rotation':(-0.941895, 179.724869, -0.973267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6529.72601562, 3972.31273438, 169.06388672), 'rotation':(-0.947327, 179.725128, -0.979034), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6524.07222656, 3972.3415625, 168.97039062), 'rotation':(-0.947266, 179.723373, -0.978973), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6507.11078125, 3972.42796875, 168.68984375), 'rotation':(-0.947906, 179.723663, -0.979675), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6495.80320312, 3972.4856250000003, 168.50253906), 'rotation':(-0.950226, 179.726059, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6484.49605469, 3972.54296875, 168.31492188), 'rotation':(-0.950226, 179.726059, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6473.18796875, 3972.600625, 168.12732422000002), 'rotation':(-0.950226, 179.723328, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6467.5341406200005, 3972.62914062, 168.03351562), 'rotation':(-0.950226, 179.723328, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6461.8803124999995, 3972.65796875, 167.93972656000003), 'rotation':(-0.950226, 179.723328, -0.982147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6427.95699219, 3972.83054688, 167.37642577999998), 'rotation':(-0.951416, 179.724731, -0.983429), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6399.68746094, 3972.974375, 166.90691406000002), 'rotation':(-0.950378, 179.723236, -0.98233), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6388.37984375, 3973.03171875, 166.71929688), 'rotation':(-0.950195, 179.723328, -0.982086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6382.72601562, 3973.06054688, 166.62550781000002), 'rotation':(-0.950256, 179.725418, -0.982178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6377.07222656, 3973.089375, 166.53169922), 'rotation':(-0.950195, 179.723328, -0.982086), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6603.26898438, 3980.31984375, 170.27396484000002), 'rotation':(0.937546, -0.275787, 0.907226), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6597.61570312, 3980.34859375, 170.18125), 'rotation':(0.940135, -0.275696, 0.90966), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6580.65425781, 3980.4348437500003, 169.90251952999998), 'rotation':(0.941296, -0.276672, 0.910735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6575.00046875, 3980.46335938, 169.80958984), 'rotation':(0.941296, -0.276672, 0.910735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6569.34710938, 3980.4921875, 169.71667968999998), 'rotation':(0.941296, -0.276672, 0.910735), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6558.03902344, 3980.54984375, 169.53074218999998), 'rotation':(0.94189, -0.275146, 0.911294), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6535.42378906, 3980.66476562, 169.15742188000002), 'rotation':(0.947245, -0.276611, 0.916305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6529.77, 3980.69335938, 169.06390625), 'rotation':(0.947245, -0.276611, 0.916305), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6518.46234375, 3980.7509375, 168.87689453), 'rotation':(0.94732, -0.276642, 0.916365), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6507.15523438, 3980.80835938, 168.68990234), 'rotation':(0.947258, -0.274841, 0.916317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6501.50140625, 3980.83742188, 168.59628906), 'rotation':(0.947907, -0.276337, 0.916915), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6490.19332031, 3980.89476562, 168.40873047000002), 'rotation':(0.950141, -0.273926, 0.918998), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6478.8857031200005, 3980.95242188, 168.22115234), 'rotation':(0.950223, -0.276672, 0.919091), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6461.92429688, 3981.03859375, 167.93974609), 'rotation':(0.950216, -0.273926, 0.919089), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6439.30953125, 3981.1535937500003, 167.56429688), 'rotation':(0.951418, -0.275269, 0.920199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6428.00191406, 3981.21117188, 167.37646484), 'rotation':(0.951411, -0.277985, 0.920192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6411.04, 3981.29734375, 167.09470703), 'rotation':(0.951329, -0.275238, 0.920108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6405.38617188, 3981.32617188, 167.00080078), 'rotation':(0.951418, -0.275269, 0.920199), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6388.4247656200005, 3981.41234375, 166.71933593999998), 'rotation':(0.950243, -0.276703, 0.919111), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6382.7709374999995, 3981.44117188, 166.62552734000002), 'rotation':(0.950175, -0.274567, 0.919051), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6646.80515625, 3980.2278125000003, 170.98496093999998), 'rotation':(0.930128, -0.276611, 0.900277), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6658.09226562, 3980.1440625, 171.16816406), 'rotation':(0.927061, -0.276672, 0.897415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6680.66353516, 3979.92601562, 171.5328125), 'rotation':(0.923482, -0.276886, 0.894072), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6697.59322266, 3979.84007812, 171.80558594), 'rotation':(0.918066, -0.275818, 0.888994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6714.52339844, 3979.75390625, 172.07714843999997), 'rotation':(0.916359, -0.278473, 0.887389), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6737.0966406200005, 3979.63914062, 172.43830078), 'rotation':(0.914979, -0.276764, 0.886093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6742.73970703, 3979.6103125, 172.52845703), 'rotation':(0.912076, -0.276855, 0.883374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6748.38228516, 3979.58179688, 172.61841797), 'rotation':(0.909303, -0.276947, 0.880782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.95552734, 3979.46703125, 172.97621094), 'rotation':(0.905137, -0.277405, 0.876871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6776.59908203, 3979.441875, 173.06539062), 'rotation':(0.905137, -0.277405, 0.876871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6782.24263672, 3979.41820312, 173.15455078), 'rotation':(0.905143, -0.27536, 0.876864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6787.88570312, 3979.36476562, 173.24375), 'rotation':(0.905143, -0.27536, 0.876864), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6793.52876953, 3979.3225, 173.33283203), 'rotation':(0.902206, -0.277924, 0.874121), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6799.17183594, 3979.2903125000003, 173.42175781000003), 'rotation':(0.896503, -0.276642, 0.868783), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6810.45845703, 3979.23289062, 173.59865234), 'rotation':(0.893628, -0.278748, 0.866063), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6821.74556641, 3979.17554688, 173.77478516), 'rotation':(0.893525, -0.277069, 0.865968), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6838.67574219, 3979.089375, 174.03890625), 'rotation':(0.893682, -0.277069, 0.866122), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6861.24898438, 3978.97484375, 174.38994141), 'rotation':(0.886702, -0.277008, 0.859572), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6866.89205078, 3978.94601562, 174.47730468999998), 'rotation':(0.886859, -0.27948, 0.859721), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6878.17916016, 3978.8884375, 174.65205078), 'rotation':(0.886859, -0.277008, 0.859717), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6883.82320312, 3979.0303125, 174.73941406000003), 'rotation':(0.886319, -0.278168, 0.859208), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6878.19136719, 3970.54054688, 174.65291016), 'rotation':(-0.886719, 179.722977, -0.91449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6872.54732422, 3970.569375, 174.56552734000002), 'rotation':(-0.886871, 179.722992, -0.914642), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6866.90425781, 3970.598125, 174.47814452999998), 'rotation':(-0.886719, 179.72052, -0.91449), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6861.26119141, 3970.62695312, 174.39080077999998), 'rotation':(-0.888489, 179.724152, -0.916351), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6844.33150391, 3970.71289062, 174.1278125), 'rotation':(-0.893646, 179.721252, -0.921844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6827.40132812, 3970.79882812, 173.86369141), 'rotation':(-0.893524, 179.722931, -0.921722), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6816.11421875, 3970.85617188, 173.68757812), 'rotation':(-0.893646, 179.722931, -0.921844), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6810.47115234, 3970.885, 173.59951172), 'rotation':(-0.896515, 179.721878, -0.924927), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6804.82808594, 3970.91382812, 173.51119140999998), 'rotation':(-0.902222, 179.723557, -0.930969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6799.18501953, 3970.94234375, 173.42261718999998), 'rotation':(-0.902222, 179.723557, -0.930969), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6793.54195312, 3970.97117188, 173.33375), 'rotation':(-0.905151, 179.72258, -0.934082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6776.61177734, 3971.0573437499997, 173.06625), 'rotation':(-0.905151, 179.72258, -0.934082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6770.96871094, 3971.0859375, 172.97708984000002), 'rotation':(-0.905151, 179.72258, -0.934082), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6754.03902344, 3971.17210938, 172.70908203), 'rotation':(-0.912079, 179.723145, -0.941498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6748.39595703, 3971.2009375, 172.61931640999998), 'rotation':(-0.912079, 179.723145, -0.941498), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6737.10982422, 3971.25828125, 172.43917968999997), 'rotation':(-0.916229, 179.723602, -0.945892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6725.82369141, 3971.31570312, 172.25861328), 'rotation':(-0.916229, 179.723602, -0.945892), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6720.17964844, 3971.34421875, 172.16832031), 'rotation':(-0.916351, 179.723602, -0.946045), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6669.39253906, 3971.56882812, 171.35167968999997), 'rotation':(-0.925659, 179.723267, -0.955933), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6663.74945312, 3971.56296875, 171.26046875), 'rotation':(-0.927155, 179.723297, -0.95755), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6652.461875, 3971.5590625, 171.07755859), 'rotation':(-0.930115, 179.726044, -0.960724), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6641.17523438, 3971.61671875, 170.89404297000002), 'rotation':(-0.932861, 179.723511, -0.963623), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(7021.34371094, 3969.683125, 176.85523438), 'rotation':(-0.883636, 179.722992, -0.911194), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(7005.47847656, 3969.8815624999997, 176.61046875), 'rotation':(-0.881439, 179.724228, -0.908875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6988.1415625, 3969.98140625, 176.34402343999997), 'rotation':(-0.879272, 179.722763, -0.906586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.60787109, 3970.00953125, 176.25908203), 'rotation':(-0.879272, 179.722763, -0.906586), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6960.47261719, 3970.12203125, 175.91925781), 'rotation':(-0.879364, 179.720993, -0.906677), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6949.40572266, 3970.1784374999997, 175.749375), 'rotation':(-0.879303, 179.723175, -0.906616), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6943.87203125, 3970.2065625, 175.66439452999998), 'rotation':(-0.879547, 179.721863, -0.90686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6932.80416016, 3970.2629687500003, 175.49445312), 'rotation':(-0.879547, 179.721863, -0.90686), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6921.76509766, 3978.69992188, 175.32429688), 'rotation':(0.879544, -0.278137, 0.852843), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6949.43599609, 3978.55929688, 175.74917968999998), 'rotation':(0.879298, -0.276825, 0.852614), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6954.9696875, 3978.53125, 175.83414062), 'rotation':(0.879353, -0.279999, 0.852662), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6966.03804688, 3978.47484375, 176.00404297), 'rotation':(0.879271, -0.277222, 0.852589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6977.10640625, 3978.4184375, 176.17396484), 'rotation':(0.879271, -0.279968, 0.852595), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6982.64058594, 3978.39039062, 176.25892578), 'rotation':(0.879271, -0.277222, 0.852589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6993.70845703, 3978.33421875, 176.42880859000002), 'rotation':(0.879271, -0.277222, 0.852589), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7005.50435547, 3978.28585938, 176.61019531000002), 'rotation':(0.883676, -0.277008, 0.856714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7016.57320312, 3978.32007812, 176.78095703), 'rotation':(0.883676, -0.277008, 0.856714), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7026.91402344, 3978.2946875, 176.94048827999998), 'rotation':(0.883663, -0.278778, 0.85672), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.07757812, 3529.30710938, 159.85644531), 'rotation':(0.216264, 90.428017, 0.21464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.17625, 3518.21726562, 159.8143457), 'rotation':(0.218429, 90.42717, 0.216758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.21773438, 3512.67066406, 159.793125), 'rotation':(0.218429, 90.42717, 0.216758), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.38375, 3490.4846093799997, 159.70740234000002), 'rotation':(0.22181, 90.431915, 0.220109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.4247656200005, 3484.93824219, 159.68587890999999), 'rotation':(0.22181, 90.431915, 0.220109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.54929688, 3468.30054688, 159.62057617), 'rotation':(0.226086, 90.429153, 0.224309), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6091.63226562, 3457.20628906, 159.57614258), 'rotation':(0.228934, 90.429176, 0.227109), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.83929688, 3429.47386719, 159.46337891), 'rotation':(0.234542, 90.426888, 0.232634), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.8803124999995, 3423.92773438, 159.44050780999999), 'rotation':(0.237499, 90.431641, 0.235542), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.921875, 3418.38109375, 159.41736328000002), 'rotation':(0.240457, 90.426933, 0.238452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6091.96335938, 3412.83472656, 159.39395507999998), 'rotation':(0.240457, 90.426933, 0.238452), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.00484375, 3407.28859375, 159.3703418), 'rotation':(0.243264, 90.431664, 0.241203), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.17085938, 3385.10304688, 159.27501953), 'rotation':(0.249001, 90.429314, 0.246833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.2123437499995, 3379.556875, 159.2506543), 'rotation':(0.252034, 90.429367, 0.249825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.25390625, 3374.01023438, 159.22598632999998), 'rotation':(0.254909, 90.429382, 0.252651), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6092.29539062, 3368.46410156, 159.20105469), 'rotation':(0.257915, 90.429382, 0.255615), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6092.3778906200005, 3357.37109375, 159.15030273), 'rotation':(0.263652, 90.429436, 0.26124), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6092.4609375, 3346.27855469, 159.09855469000001), 'rotation':(0.26803, 90.429878, 0.265532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6099.51507812, 3523.82640625, 159.83544922), 'rotation':(-0.218414, -89.572815, -0.220093), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.5565625, 3518.27976562, 159.8143457), 'rotation':(-0.21991, -89.568481, -0.221588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6099.598125, 3512.73339844, 159.793125), 'rotation':(-0.21991, -89.568481, -0.221588), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.72265625, 3496.09375, 159.72888672), 'rotation':(-0.221832, -89.571594, -0.223541), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.8881249999995, 3473.90820312, 159.64246094), 'rotation':(-0.226074, -89.570862, -0.227875), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.97117188, 3462.81519531, 159.5984082), 'rotation':(-0.231689, -89.570801, -0.233551), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.05414062, 3451.7221875, 159.55371094), 'rotation':(-0.233124, -89.57312, -0.235046), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.26117188, 3423.99023438, 159.44050780999999), 'rotation':(-0.240448, -89.568359, -0.242493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6100.30265625, 3418.44359375, 159.41736328000002), 'rotation':(-0.243256, -89.573029, -0.245361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.34421875, 3412.89746094, 159.39395507999998), 'rotation':(-0.243256, -89.573029, -0.245361), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.42671875, 3401.8044531200003, 159.34665039), 'rotation':(-0.244812, -89.569366, -0.246887), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.5096875, 3390.71191406, 159.29913086), 'rotation':(-0.249023, -89.570679, -0.25119), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6100.55125, 3385.16578125, 159.27501953), 'rotation':(-0.252014, -89.570648, -0.254272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6100.59273438, 3379.619375, 159.25064453000002), 'rotation':(-0.254883, -89.570618, -0.257172), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6100.8412499999995, 3346.34132812, 159.09857422), 'rotation':(-0.267853, -89.570129, -0.270386), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.8090625, 3567.34667969, 160.00011719), 'rotation':(0.216722, 90.429024, 0.215077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.7675, 3572.89183594, 160.02110352), 'rotation':(0.216811, 90.429008, 0.215164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.6849999999995, 3583.98289062, 160.06306641), 'rotation':(0.216722, 90.429024, 0.215077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.6435156200005, 3589.52832031, 160.08404296999998), 'rotation':(0.216722, 90.429024, 0.215077), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.60203125, 3595.07375, 160.1050293), 'rotation':(0.216811, 90.429008, 0.215164), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.47703125, 3611.71019531, 160.16808594), 'rotation':(0.220212, 90.431297, 0.218534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.39453125, 3622.80101562, 160.21071289), 'rotation':(0.220212, 90.431297, 0.218534), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.2284375, 3644.98316406, 160.29635742), 'rotation':(0.224754, 90.429596, 0.223012), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6090.06296875, 3667.165, 160.38427734), 'rotation':(0.232028, 90.429649, 0.23016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6090.02140625, 3672.71070312, 160.40666016), 'rotation':(0.232028, 90.429649, 0.23016), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.9384375, 3683.80148438, 160.4518457), 'rotation':(0.234733, 90.428993, 0.23282), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.89695312, 3689.3471875, 160.47458008), 'rotation':(0.234863, 90.428993, 0.232943), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.8139062499995, 3700.43796875, 160.52029296999999), 'rotation':(0.244043, 90.430931, 0.241976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.689375, 3717.0746875, 160.59092773), 'rotation':(0.247273, 90.428238, 0.245144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.64789062, 3722.62039062, 160.61483398000001), 'rotation':(0.247273, 90.428238, 0.245144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6089.5990624999995, 3728.16554688, 160.63878906), 'rotation':(0.248441, 90.432495, 0.246301), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6089.45015625, 3739.25539062, 160.68731445), 'rotation':(0.25439, 90.427414, 0.252134), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.8544531200005, 3763.2959375, 160.79608398), 'rotation':(-0.265778, -89.567322, -0.26825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.9389062499995, 3752.0078125, 160.74422852), 'rotation':(-0.259979, -89.57254, -0.26236), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.97507812, 3740.52023438, 160.69264648), 'rotation':(-0.251495, -89.567474, -0.253723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.02828125, 3722.68578125, 160.61485352), 'rotation':(-0.247131, -89.567627, -0.249268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.06976562, 3717.14015625, 160.5909375), 'rotation':(-0.247131, -89.567627, -0.249268), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.1528125, 3706.04929688, 160.54348633), 'rotation':(-0.237823, -89.569122, -0.239807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.19429688, 3700.50367188, 160.5203125), 'rotation':(-0.237823, -89.569122, -0.239807), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.40179688, 3672.775625, 160.40666016), 'rotation':(-0.230316, -89.570374, -0.232178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.44328125, 3667.23023438, 160.38429688), 'rotation':(-0.230316, -89.570374, -0.232178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.56734375, 3650.59375, 160.31811523), 'rotation':(-0.224762, -89.570374, -0.226532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.60882812, 3645.04835938, 160.29636719), 'rotation':(-0.222931, -89.570404, -0.22464), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6098.73335938, 3628.41164062, 160.23202148000001), 'rotation':(-0.220215, -89.568726, -0.221893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.7748437499995, 3622.86621094, 160.21071289), 'rotation':(-0.220398, -89.568695, -0.222107), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.81640625, 3617.32078125, 160.18939453000002), 'rotation':(-0.220215, -89.574219, -0.221924), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.899375, 3606.22949219, 160.14699219), 'rotation':(-0.216797, -89.570984, -0.218445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6098.98234375, 3595.13890625, 160.1050293), 'rotation':(-0.216705, -89.570984, -0.218353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.0653906200005, 3584.04785156, 160.06306641), 'rotation':(-0.216797, -89.570984, -0.218445), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.14789062, 3572.95703125, 160.02110352), 'rotation':(-0.216705, -89.570984, -0.218353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6099.189375, 3567.41164062, 160.00013672), 'rotation':(-0.216614, -89.569, -0.218262), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.94867188, 3816.1284375, 161.05419922), 'rotation':(0.295064, 90.430962, 0.292047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.8246875, 3832.77640625, 161.14051758), 'rotation':(0.305542, 90.429138, 0.302284), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.783125, 3838.32570312, 161.16994140999998), 'rotation':(0.309763, 90.429169, 0.306427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.65867188, 3854.9739062500003, 161.26052734), 'rotation':(0.322016, 90.434326, 0.318413), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.5756249999995, 3866.07226562, 161.32294922), 'rotation':(0.328218, 90.427589, 0.324476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.5341406200005, 3871.62203125, 161.3546582), 'rotation':(0.328218, 90.427589, 0.324476), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.45109375, 3882.72046875, 161.41868164), 'rotation':(0.339522, 90.430023, 0.335524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.40960938, 3888.27, 161.45135742), 'rotation':(0.339522, 90.430023, 0.335524), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.32664062, 3899.3684375000003, 161.51792969), 'rotation':(0.354774, 90.430214, 0.350407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6088.28515625, 3904.91773438, 161.55192383), 'rotation':(0.354774, 90.430214, 0.350407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6087.99460938, 3943.76320312, 161.79844727), 'rotation':(0.378741, 90.432289, 0.373767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6087.8700781200005, 3960.41085938, 161.91009766), 'rotation':(0.39096, 90.431343, 0.385648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6096.2509375, 3960.4778125000003, 161.91012695), 'rotation':(-0.386932, -89.567596, -0.392212), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.33390625, 3949.37867188, 161.83515625), 'rotation':(-0.378754, -89.570679, -0.383789), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.37546875, 3943.82960938, 161.79847656), 'rotation':(-0.370728, -89.567841, -0.375549), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.5, 3927.181875, 161.69083984), 'rotation':(-0.36261, -89.570923, -0.367218), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.62398438, 3910.53320312, 161.58630859000002), 'rotation':(-0.354797, -89.569794, -0.359192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.6654687499995, 3904.98390625, 161.55194336), 'rotation':(-0.347229, -89.569885, -0.351471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.70703125, 3899.43453125, 161.51794922), 'rotation':(-0.347229, -89.569885, -0.351471), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6096.79, 3888.33617188, 161.45136719), 'rotation':(-0.332001, -89.570038, -0.335876), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.0390625, 3855.03953125, 161.26055664), 'rotation':(-0.317932, -89.57074, -0.321472), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.08054688, 3849.49, 161.22995117), 'rotation':(-0.313721, -89.57077, -0.317169), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.12203125, 3843.9409375, 161.19975586), 'rotation':(-0.309753, -89.570831, -0.313141), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.2465625, 3827.29296875, 161.11152344), 'rotation':(-0.297363, -89.570953, -0.300446), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.28804688, 3821.743125, 161.08282227), 'rotation':(-0.295258, -89.574463, -0.298279), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6097.3295312499995, 3816.1940624999997, 161.05421875), 'rotation':(-0.293304, -89.570953, -0.296295), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6097.41015625, 3810.64648438, 161.02574219), 'rotation':(-0.289154, -89.565918, -0.292084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6076.921875, 3325.39183594, 158.7937207), 'rotation':(-0.634216, 179.882874, -0.648346), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6055.67429688, 3325.54882812, 158.56507812), 'rotation':(-0.587982, 179.882645, -0.600159), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6050.3603125, 3325.5603125, 158.51022461), 'rotation':(-0.587952, 179.882645, -0.600128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6045.0482812499995, 3325.57177734, 158.45570312), 'rotation':(-0.587952, 179.882645, -0.600128), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6039.734375, 3325.58277344, 158.40128906), 'rotation':(-0.575714, 179.883347, -0.587372), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6029.109375, 3325.60570312, 158.29541016), 'rotation':(-0.551239, 179.881348, -0.56192), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6023.796875, 3325.6171875, 158.24429688), 'rotation':(-0.526672, 179.882401, -0.536407), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6076.94085938, 3333.99511719, 158.79373046999999), 'rotation':(0.652713, -0.11499, 0.637976), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6066.31640625, 3333.90671875, 158.67727539), 'rotation':(0.634176, -0.117126, 0.620269), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6055.6889062499995, 3333.9296875, 158.5650293), 'rotation':(0.597177, -0.11792, 0.584817), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6050.375, 3333.94117188, 158.51019531), 'rotation':(0.587936, -0.11734, 0.575965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6045.06148438, 3333.95265625, 158.4556543), 'rotation':(0.587936, -0.11734, 0.575965), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6029.1200781200005, 3333.9865625, 158.29535156), 'rotation':(0.57571, -0.116638, 0.56423), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6018.4896874999995, 3334.00953125, 158.19460938), 'rotation':(0.551237, -0.118652, 0.540708), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6013.17671875, 3334.02074219, 158.14577148), 'rotation':(0.526662, -0.117584, 0.517047), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6002.5478125, 3334.04371094, 158.05275390999998), 'rotation':(0.502087, -0.119568, 0.493347), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6329.7943749999995, 3324.95947266, 162.26286133), 'rotation':(-0.860565, 179.890778, -0.886719), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6318.48289062, 3324.98363281, 162.093125), 'rotation':(-0.857086, 179.890686, -0.883026), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6307.171875, 3325.00804688, 161.92396484), 'rotation':(-0.85437, 179.889877, -0.880157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6301.515625, 3325.02027344, 161.83955078), 'rotation':(-0.85437, 179.889877, -0.880157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6284.54875, 3325.05664062, 161.58645508), 'rotation':(-0.854553, 179.888138, -0.880341), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6273.2372656200005, 3325.08105469, 161.41770508), 'rotation':(-0.846313, 179.889633, -0.871613), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6261.9247656200005, 3325.10523438, 161.25076171999999), 'rotation':(-0.838074, 179.889389, -0.862885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6256.26953125, 3325.11742188, 161.16801758), 'rotation':(-0.837952, 179.889374, -0.862732), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6244.9575, 3325.14183594, 161.0025), 'rotation':(-0.838074, 179.889389, -0.862885), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6239.30171875, 3325.1540625, 160.91973633), 'rotation':(-0.835327, 179.889481, -0.859955), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6227.98828125, 3325.17822266, 160.75544922), 'rotation':(-0.824341, 179.88916, -0.848328), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6222.3325, 3325.19042969, 160.67420898), 'rotation':(-0.818939, 179.886215, -0.842621), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6211.02046875, 3325.21460938, 160.51351562), 'rotation':(-0.802582, 179.888535, -0.825317), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6199.7084374999995, 3325.23876953, 160.35522461), 'rotation':(-0.794464, 179.88736, -0.816711), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6182.73828125, 3325.27539062, 160.12003906), 'rotation':(-0.78833, 179.88707, -0.810272), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6177.08148438, 3325.28759766, 160.0422168), 'rotation':(-0.776306, 179.888565, -0.797546), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6171.42523438, 3325.29980469, 159.96555664), 'rotation':(-0.76413, 179.886398, -0.784698), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6160.11273438, 3325.32421875, 159.81469727), 'rotation':(-0.751892, 179.886078, -0.77182), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6148.79929688, 3325.34839844, 159.66679688), 'rotation':(-0.74588, 179.886581, -0.765503), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6131.83148438, 3325.318125, 159.4471875), 'rotation':(-0.721039, 179.886124, -0.739349), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6120.51359375, 3325.27978516, 159.30566406), 'rotation':(-0.704651, 179.884018, -0.722168), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6115.501875, 3325.29052734, 159.24400391), 'rotation':(-0.68808, 179.8853, -0.704773), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6120.501875, 3333.9196875, 159.30529296999998), 'rotation':(0.721029, -0.113892, 0.703054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6126.1615624999995, 3333.88941406, 159.37557617000002), 'rotation':(0.721029, -0.113892, 0.703054), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6131.81734375, 3333.83300781, 159.44677734), 'rotation':(0.737592, -0.113464, 0.718782), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6137.473125, 3333.776875, 159.51953125), 'rotation':(0.745891, -0.113403, 0.726657), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6148.78460938, 3333.72949219, 159.66638672), 'rotation':(0.745768, -0.113434, 0.726539), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6154.44140625, 3333.71726562, 159.74001953), 'rotation':(0.751881, -0.113922, 0.732348), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6171.41015625, 3333.68066406, 159.96511719), 'rotation':(0.776292, -0.11142, 0.755458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6177.06585938, 3333.6684375, 160.04174805), 'rotation':(0.788347, -0.112946, 0.766874), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6182.72265625, 3333.65625, 160.11958008), 'rotation':(0.794447, -0.11264, 0.772644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6194.03460938, 3333.63183594, 160.27625977), 'rotation':(0.794447, -0.11264, 0.772644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6199.69140625, 3333.61960938, 160.35473633), 'rotation':(0.797165, -0.111603, 0.775217), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6222.31492188, 3333.57105469, 160.67371094), 'rotation':(0.824342, -0.11084, 0.800871), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6239.28367188, 3333.53492188, 160.91921875), 'rotation':(0.838091, -0.112823, 0.813841), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6244.939375, 3333.52269531, 161.00197265999998), 'rotation':(0.838153, -0.110626, 0.813893), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6256.2509375, 3333.49828125, 161.16748047), 'rotation':(0.838091, -0.110626, 0.813833), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6261.90671875, 3333.48632812, 161.25022461), 'rotation':(0.846308, -0.110352, 0.82157), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6273.21820312, 3333.46828125, 161.4171582), 'rotation':(0.854375, -0.111847, 0.829178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6278.87398438, 3333.4607031200003, 161.50152344), 'rotation':(0.854532, -0.110107, 0.829331), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6290.1849999999995, 3333.39234375, 161.67025390999999), 'rotation':(0.854395, -0.110107, 0.829178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6295.84078125, 3333.38011719, 161.75461914), 'rotation':(0.854395, -0.110107, 0.829178), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6318.46335938, 3333.33128906, 162.09255859), 'rotation':(0.858575, -0.111328, 0.833117), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6324.1190625, 3333.31933594, 162.17735352), 'rotation':(0.860583, -0.111267, 0.835002), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6329.7753125, 3333.30710938, 162.26231445), 'rotation':(0.861266, -0.109711, 0.83566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6335.4310937499995, 3333.46507812, 162.34732422), 'rotation':(0.861266, -0.109711, 0.83566), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6576.856875, 3324.4275, 165.77150390999998), 'rotation':(-0.732727, 179.884598, -0.751648), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6571.20453125, 3324.4396875, 165.699375), 'rotation':(-0.737854, 179.887375, -0.75705), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6565.55320312, 3324.45166016, 165.62671875), 'rotation':(-0.743011, 179.884857, -0.762482), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6542.94578125, 3324.50048828, 165.33052734), 'rotation':(-0.761383, 179.886826, -0.78183), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6531.6415625, 3324.52490234, 165.18025391), 'rotation':(-0.766174, 179.888046, -0.786865), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6509.035625, 3324.57347656, 164.87490234), 'rotation':(-0.79483, 179.886826, -0.817108), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6503.38328125, 3324.58544922, 164.79664062), 'rotation':(-0.799591, 179.887115, -0.822144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6497.73289062, 3324.59765625, 164.71794922), 'rotation':(-0.799591, 179.889694, -0.822144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6492.08054688, 3324.60986328, 164.63902344), 'rotation':(-0.799591, 179.887115, -0.822144), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6469.4740624999995, 3324.65869141, 164.32244140999998), 'rotation':(-0.810547, 179.887009, -0.83374), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6458.1708593799995, 3324.68310547, 164.16140625), 'rotation':(-0.825195, 179.889465, -0.849243), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6441.21578125, 3324.71949219, 163.91646484), 'rotation':(-0.828766, 179.888321, -0.852997), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6435.5639062499995, 3324.73167969, 163.8346875), 'rotation':(-0.831757, 179.888306, -0.856201), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6424.26117188, 3324.75609375, 163.67063477), 'rotation':(-0.837677, 179.890152, -0.862427), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6418.60933594, 3324.76832031, 163.58799805), 'rotation':(-0.843567, 179.888641, -0.868683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6412.9575, 3324.78050781, 163.50499023), 'rotation':(-0.843567, 179.888641, -0.868683), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6407.3060937499995, 3324.79248047, 163.42170898), 'rotation':(-0.849426, 179.888809, -0.874908), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6401.65425781, 3324.8046875, 163.33789062), 'rotation':(-0.852234, 179.890091, -0.877899), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6390.35152344, 3324.82910156, 163.16980469), 'rotation':(-0.852417, 179.890091, -0.878052), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6384.6996875, 3324.84130859, 163.08569336), 'rotation':(-0.85318, 179.888916, -0.878906), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6384.6786718799995, 3333.22191406, 163.08511719), 'rotation':(0.852401, -0.109894, 0.827314), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6407.28609375, 3333.17359375, 163.42114258), 'rotation':(0.843508, -0.111359, 0.818951), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6412.93695312, 3333.16136719, 163.50442383), 'rotation':(0.837716, -0.111511, 0.813478), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6424.2411718799995, 3333.13695312, 163.67008789), 'rotation':(0.83176, -0.110016, 0.807867), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6435.54390625, 3333.11253906, 163.83414062), 'rotation':(0.828755, -0.111694, 0.805036), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6441.19625, 3333.10035156, 163.91591797), 'rotation':(0.828802, -0.111694, 0.805073), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6452.49996094, 3333.0759375, 164.07947266), 'rotation':(0.825203, -0.110535, 0.801676), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6469.45554688, 3333.03953125, 164.32191406), 'rotation':(0.803278, -0.111176, 0.780996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6475.1068749999995, 3333.02734375, 164.4015625), 'rotation':(0.803278, -0.111176, 0.780996), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6486.41109375, 3333.00292969, 164.55962891), 'rotation':(0.799576, -0.112885, 0.777496), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6497.71480469, 3332.97875, 164.71742188), 'rotation':(0.799583, -0.110291, 0.777493), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6509.0185156200005, 3332.95433594, 164.87441406000002), 'rotation':(0.785301, -0.11145, 0.764003), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6525.9740625, 3332.91796875, 165.10441406), 'rotation':(0.761457, -0.113159, 0.741415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6531.6259375, 3332.90578125, 165.17978516), 'rotation':(0.761457, -0.113159, 0.741415), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6548.5825, 3332.85863281, 165.40496094), 'rotation':(0.753452, -0.112213, 0.733825), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6559.88617188, 3332.8122656200003, 165.55308594), 'rotation':(0.743002, -0.112488, 0.72392), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6571.18992188, 3332.78734375, 165.69898438), 'rotation':(0.732729, -0.112762, 0.714161), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6582.49460938, 3332.76320312, 165.84267577999998), 'rotation':(0.722115, -0.115692, 0.704084), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6593.79828125, 3332.73902344, 165.98478516), 'rotation':(0.716132, -0.113708, 0.698401), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6599.45113281, 3332.7267968799997, 166.05546875), 'rotation':(0.709308, -0.116272, 0.691917), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6868.87984375, 3323.79882812, 168.92226562), 'rotation':(-0.55014, 179.881714, -0.56076), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.23726562, 3323.81103516, 168.86808594), 'rotation':(-0.550903, 179.881729, -0.561584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6857.59517578, 3323.82324219, 168.81386719), 'rotation':(-0.550903, 179.881729, -0.561584), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6835.024375, 3323.87183594, 168.59671875), 'rotation':(-0.551147, 179.881744, -0.561829), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6829.38228516, 3323.88402344, 168.54236328), 'rotation':(-0.553711, 179.883408, -0.564484), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6823.73970703, 3323.89625, 168.48783203), 'rotation':(-0.558258, 179.882019, -0.569214), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6795.52681641, 3323.95679688, 168.21125), 'rotation':(-0.570007, 179.882172, -0.581421), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6767.31539062, 3324.01757812, 167.93), 'rotation':(-0.578857, 179.882263, -0.590637), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6761.6728125, 3324.02978516, 167.87291016), 'rotation':(-0.584717, 179.884384, -0.596741), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6756.03023438, 3324.04199219, 167.81533202999998), 'rotation':(-0.590759, 179.882492, -0.603027), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6744.74605469, 3324.06617188, 167.69884765999998), 'rotation':(-0.593567, 179.882904, -0.605988), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6739.10347656, 3324.07835938, 167.64039062), 'rotation':(-0.596344, 179.882248, -0.608856), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6733.46236328, 3324.09058594, 167.58167969), 'rotation':(-0.601624, 179.88237, -0.61438), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6727.81978516, 3324.10253906, 167.52253906), 'rotation':(-0.607117, 179.884613, -0.620087), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6722.17769531, 3324.11474609, 167.46294922), 'rotation':(-0.61264, 179.882584, -0.625854), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6710.89302734, 3324.13916016, 167.34242188), 'rotation':(-0.61792, 179.882706, -0.631378), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6660.1146875, 3324.24828125, 166.77837891), 'rotation':(-0.659454, 179.884308, -0.674774), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6648.83003906, 3324.27246094, 166.64753906), 'rotation':(-0.672882, 179.883484, -0.688812), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6654.46773438, 3332.64136719, 166.71310547000002), 'rotation':(0.659455, -0.115692, 0.644416), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6677.03707031, 3332.59277344, 166.96998047), 'rotation':(0.636929, -0.114655, 0.62289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6682.67818359, 3332.58054688, 167.03296875), 'rotation':(0.636929, -0.114655, 0.62289), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6693.961875, 3332.55640625, 167.15792968999997), 'rotation':(0.62878, -0.117065, 0.615098), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6705.24751953, 3332.53222656, 167.28126953), 'rotation':(0.61792, -0.117279, 0.604699), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6710.88960938, 3332.52, 167.3421875), 'rotation':(0.612627, -0.117401, 0.599631), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6722.17427734, 3332.495625, 167.46271484000002), 'rotation':(0.607108, -0.115387, 0.594353), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6733.45894531, 3332.47144531, 167.58146484), 'rotation':(0.596344, -0.117767, 0.584024), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6739.10103516, 3332.45921875, 167.64017578), 'rotation':(0.593578, -0.117096, 0.581367), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6744.74361328, 3332.44703125, 167.69863281000002), 'rotation':(0.59075, -0.117493, 0.578666), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6756.02779297, 3332.42261719, 167.81511719), 'rotation':(0.584719, -0.117645, 0.572879), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6772.95552734, 3332.38625, 167.98642578), 'rotation':(0.569993, -0.117828, 0.558747), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6801.16792969, 3332.32542969, 168.26695312), 'rotation':(0.562931, -0.117859, 0.551954), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6812.45308594, 3332.30101562, 168.37787109), 'rotation':(0.558252, -0.11795, 0.547458), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6829.38082031, 3332.26464844, 168.54216797), 'rotation':(0.551148, -0.118256, 0.540628), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6857.59419922, 3332.20582031, 168.81369141), 'rotation':(0.550131, -0.118286, 0.539644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6863.23628906, 3332.19679688, 168.86792968999998), 'rotation':(0.550131, -0.118286, 0.539644), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6868.87886719, 3332.1875, 168.92208984), 'rotation':(0.549721, -0.117798, 0.539245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6880.16451172, 3332.14015625, 169.03039062), 'rotation':(0.549721, -0.117798, 0.539245), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6891.45015625, 3332.09960938, 169.13876953), 'rotation':(0.551265, -0.118164, 0.540734), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7029.02291016, 3323.45458984, 170.54998047), 'rotation':(-0.648346, 179.885483, -0.663147), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(7023.48775391, 3323.4665625, 170.48697266), 'rotation':(-0.640259, 179.882706, -0.654694), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7017.95308594, 3323.47828125, 170.42474609), 'rotation':(-0.632385, 179.885117, -0.646454), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n {'tilex':7, 'tiley':2, 'location':(7001.34712891, 3323.51416016, 170.24283203), 'rotation':(-0.608337, 179.882004, -0.621368), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6995.81197266, 3323.52613281, 170.18376952999998), 'rotation':(-0.60025, 179.881851, -0.612946), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/NissanPatrol2021/SM_NissanPatrol2021_parked.SM_NissanPatrol2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6990.27681641, 3323.53808594, 170.12550781000002), 'rotation':(-0.596283, 179.884003, -0.608795), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6979.20601562, 3323.56175781, 170.01019531000003), 'rotation':(-0.592407, 179.881851, -0.604767), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(6962.60152344, 3323.59765625, 169.83943359), 'rotation':(-0.577271, 179.882996, -0.58902), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6951.53169922, 3323.62109375, 169.72759766), 'rotation':(-0.56958, 179.881378, -0.580994), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/VolkswagenT2/SM_VolkswagenT2_2021_Parked.SM_VolkswagenT2_2021_Parked'},\n {'tilex':7, 'tiley':2, 'location':(6929.3915625, 3323.66871094, 169.50824218999998), 'rotation':(-0.561646, 179.883163, -0.572723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6923.85640625, 3323.68066406, 169.45380859), 'rotation':(-0.561646, 179.883163, -0.572723), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(7037.38375, 3331.93921875, 170.64595702999998), 'rotation':(0.660315, -0.114136, 0.645224), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/TeslaM3/SM_TeslaM3_parked.SM_TeslaM3_parked'},\n {'tilex':7, 'tiley':2, 'location':(7023.50679688, 3331.84742188, 170.48697266), 'rotation':(0.648363, -0.114532, 0.633804), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6995.83101562, 3331.90671875, 170.18376952999998), 'rotation':(0.608351, -0.117981, 0.595532), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6984.76021484, 3331.93066406, 170.06777344), 'rotation':(0.600244, -0.11557, 0.587769), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6973.69039062, 3331.95460938, 169.95294922000002), 'rotation':(0.592423, -0.116699, 0.580267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Mini2021/SM_Mini2021_parked.SM_Mini2021_parked'},\n {'tilex':7, 'tiley':2, 'location':(6968.15523438, 3331.96632812, 169.89595702999998), 'rotation':(0.592423, -0.116699, 0.580267), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Lincoln/SM_LincolnParked.SM_LincolnParked'},\n {'tilex':7, 'tiley':2, 'location':(6962.62056641, 3331.97804688, 169.83945312), 'rotation':(0.584835, -0.118317, 0.572986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/Charger/SM_ChargerParked.SM_ChargerParked'},\n {'tilex':7, 'tiley':2, 'location':(6957.08589844, 3331.99, 169.78337890999998), 'rotation':(0.584835, -0.118317, 0.572986), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/FordCrown/SM_FordCrown_parked.SM_FordCrown_parked'},\n {'tilex':7, 'tiley':2, 'location':(6934.94527344, 3332.03757812, 169.5628125), 'rotation':(0.565833, -0.118103, 0.554753), 'mesh':'/Game/Carla/Static/Car/4Wheeled/ParkedVehicles/MercedesCCC/SM_MercedesCCC_Parked.SM_MercedesCCC_Parked'},\n ]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/result_writer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module contains the result gatherer and write for CARLA scenarios.\nIt shall be used from the ScenarioManager only.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport time\nfrom collections import OrderedDict\nfrom tabulate import tabulate\n\n\nCOLORED_STATUS = {\n    \"FAILURE\": '\\033[91mFAILURE\\033[0m',\n    \"SUCCESS\": '\\033[92mSUCCESS\\033[0m',\n    \"ACCEPTABLE\": '\\033[93mACCEPTABLE\\033[0m',\n}\n\nSTATUS_PRIORITY = {\n    \"FAILURE\": 0,\n    \"ACCEPTABLE\": 1,\n    \"SUCCESS\": 2,\n}  # Lower number is higher priority\n\n\nclass ResultOutputProvider(object):\n\n    \"\"\"\n    This module contains the _result gatherer and write for CARLA scenarios.\n    It shall be used from the ScenarioManager only.\n    \"\"\"\n\n    def __init__(self, data):\n        \"\"\"\n        - data contains all scenario-related information\n        - global_result is overall pass/fail info\n        \"\"\"\n        self._data = data\n        self._start_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.start_system_time))\n        self._end_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.end_system_time))\n\n        self._global_result = '\\033[92m'+'SUCCESS'+'\\033[0m'\n        for criterion in self._data.scenario.get_criteria():\n            if criterion.test_status != \"SUCCESS\":\n                self._global_result = '\\033[91m'+'FAILURE'+'\\033[0m'\n        if self._data.scenario.timeout_node.timeout:\n            self._global_result = '\\033[91m'+'FAILURE'+'\\033[0m'\n\n        print(self.create_output_text())\n\n    def create_output_text(self):\n        \"\"\"\n        Creates the output message\n        \"\"\"\n\n        # Create the title\n        output = \"\\n\"\n        output += \"\\033[1m========= Results of {} (repetition {}) ------ {} \\033[1m=========\\033[0m\\n\".format(\n            self._data.scenario_tree.name, self._data.repetition_number, self._global_result)\n        output += \"\\n\"\n\n        # Simulation part\n        system_time = round(self._data.scenario_duration_system, 2)\n        game_time = round(self._data.scenario_duration_game, 2)\n        ratio = round(self._data.scenario_duration_game / self._data.scenario_duration_system, 3)\n\n        list_statistics = [[\"Start Time\", \"{}\".format(self._start_time)]]\n        list_statistics.extend([[\"End Time\", \"{}\".format(self._end_time)]])\n        list_statistics.extend([[\"System Time\", \"{}s\".format(system_time)]])\n        list_statistics.extend([[\"Game Time\", \"{}s\".format(game_time)]])\n        list_statistics.extend([[\"Ratio (Game / System)\", \"{}\".format(ratio)]])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\\n\"\n\n        # Criteria part\n        header = ['Criterion', 'Result', 'Value']\n        list_statistics = [header]\n        criteria_data = OrderedDict()\n\n        for criterion in self._data.scenario.get_criteria():\n\n            name = criterion.name\n\n            if name in criteria_data:\n                result = criterion.test_status\n                if STATUS_PRIORITY[result] < STATUS_PRIORITY[criteria_data[name]['result']]:\n                    criteria_data[name]['result'] = result\n                criteria_data[name]['actual_value'] += criterion.actual_value\n\n            else:\n                criteria_data[name] = {\n                    'result': criterion.test_status,\n                    'actual_value': criterion.actual_value,\n                    'units': criterion.units\n                }\n\n        for criterion_name in criteria_data:\n            criterion = criteria_data[criterion_name]\n\n            result = criterion['result']\n            if result in COLORED_STATUS:\n                result = COLORED_STATUS[result]\n\n            if criterion['units'] is None:\n                actual_value = \"\"\n            else:\n                actual_value = str(criterion['actual_value']) + \" \" + criterion['units']\n\n            list_statistics.extend([[criterion_name, result, actual_value]])\n\n        # Timeout\n        name = \"Timeout\"\n\n        actual_value = self._data.scenario_duration_game\n\n        if self._data.scenario_duration_game < self._data.scenario.timeout:\n            result = '\\033[92m'+'SUCCESS'+'\\033[0m'\n        else:\n            result = '\\033[91m'+'FAILURE'+'\\033[0m'\n\n        list_statistics.extend([[name, result, '']])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\"\n\n        return output\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/route_indexer.py",
    "content": "from collections import OrderedDict\nfrom dictor import dictor\n\nimport copy\n\nfrom leaderboard.utils.route_parser import RouteParser\nfrom leaderboard.utils.checkpoint_tools import fetch_dict\n\n\nclass RouteIndexer():\n    def __init__(self, routes_file, repetitions, routes_subset):\n        self._configs_dict = OrderedDict()\n        self._configs_list = []\n        self.index = 0\n\n        route_configurations = RouteParser.parse_routes_file(routes_file, routes_subset)\n        self.total = len(route_configurations) * repetitions\n\n        for i, config in enumerate(route_configurations):\n            for repetition in range(repetitions):\n                config.index = i * repetitions + repetition\n                config.repetition_index = repetition\n                self._configs_dict['{}.{}'.format(config.name, repetition)] = copy.copy(config)\n\n        self._configs_list = list(self._configs_dict.values())\n\n\n    def peek(self):\n        return self.index < self.total\n\n    def get_next_config(self):\n        if self.index >= self.total:\n            return None\n\n        config = self._configs_list[self.index]\n        self.index += 1\n\n        return config\n\n    def validate_and_resume(self, endpoint):\n        \"\"\"\n        Validates the endpoint by comparing several of its values with the current running routes.\n        If all checks pass, the simulation starts from the last route.\n        Otherwise, the resume is canceled, and the leaderboard goes back to normal behavior\n        \"\"\"\n        data = fetch_dict(endpoint)\n        if not data:\n            print('Problem reading checkpoint. Found no data')\n            return False\n\n        entry_status = dictor(data, 'entry_status')\n        if not entry_status:\n            print(\"Problem reading checkpoint. Given checkpoint is malformed\")\n            return False\n        if entry_status == \"Invalid\":\n            print(\"Problem reading checkpoint. The 'entry_status' is 'Invalid'\")\n            return False\n\n        checkpoint_dict = dictor(data, '_checkpoint')\n        if not checkpoint_dict or 'progress' not in checkpoint_dict:\n            print(\"Problem reading checkpoint. Given endpoint is malformed\")\n            return False\n\n        progress = checkpoint_dict['progress']\n        if progress[1] != self.total:\n            print(\"Problem reading checkpoint. Endpoint's amount of routes does not match the given one\")\n            return False\n\n        route_data = dictor(checkpoint_dict, 'records')\n\n        check_index = 0\n        resume_index = progress[0]\n        while check_index < resume_index:\n            try:\n                route_id = self._configs_list[check_index].name\n                route_id += \"_rep\" + str(self._configs_list[check_index].repetition_index)\n                checkpoint_route_id = route_data[check_index]['route_id']\n\n                if route_id != checkpoint_route_id:\n                    print(\"Problem reading checkpoint. Checkpoint routes don't match the current ones\")\n                    return False\n\n                if route_data[check_index]['status'] not in ['Failed', 'Failed - Simulation crashed', 'Failed - Agent crashed', 'Failed - Simulation crashed']:\n                    check_index += 1\n                else:\n                    resume_index = check_index\n                    break\n            except IndexError:\n                # Patch to fix some cases where the progress might be higher than the actual results\n                resume_index = max(check_index - 1, 0)\n\n        if entry_status == \"Crashed\":\n            self.index = max(0, resume_index - 1)  # Something went wrong, repeat the last route\n        else: \n            self.index = max(0, resume_index)\n        return True\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/route_manipulation.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Labs.\n# authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule to manipulate the routes, by making then more or less dense (Up to a certain parameter).\nIt also contains functions to convert the CARLA world location do GPS coordinates.\n\"\"\"\n\nimport math\nimport xml.etree.ElementTree as ET\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\n\n\ndef _location_to_gps(lat_ref, lon_ref, location):\n    \"\"\"\n    Convert from world coordinates to GPS coordinates\n    :param lat_ref: latitude reference for the current map\n    :param lon_ref: longitude reference for the current map\n    :param location: location to translate\n    :return: dictionary with lat, lon and height\n    \"\"\"\n\n    EARTH_RADIUS_EQUA = 6378137.0   # pylint: disable=invalid-name\n    scale = math.cos(lat_ref * math.pi / 180.0)\n    mx = scale * lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n    my = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + lat_ref) * math.pi / 360.0))\n    mx += location.x\n    my -= location.y\n\n    lon = mx * 180.0 / (math.pi * EARTH_RADIUS_EQUA * scale)\n    lat = 360.0 * math.atan(math.exp(my / (EARTH_RADIUS_EQUA * scale))) / math.pi - 90.0\n    z = location.z\n\n    return {'lat': lat, 'lon': lon, 'z': z}\n\n\ndef location_route_to_gps(route, lat_ref, lon_ref):\n    \"\"\"\n        Locate each waypoint of the route into gps, (lat long ) representations.\n    :param route:\n    :param lat_ref:\n    :param lon_ref:\n    :return:\n    \"\"\"\n    gps_route = []\n\n    for transform, connection in route:\n        gps_point = _location_to_gps(lat_ref, lon_ref, transform.location)\n        gps_route.append((gps_point, connection))\n\n    return gps_route\n\n\ndef _get_latlon_ref(world):\n    \"\"\"\n    Convert from waypoints world coordinates to CARLA GPS coordinates\n    :return: tuple with lat and lon coordinates\n    \"\"\"\n    xodr = world.get_map().to_opendrive()\n    tree = ET.ElementTree(ET.fromstring(xodr))\n\n    # default reference\n    lat_ref = 42.0\n    lon_ref = 2.0\n\n    for opendrive in tree.iter(\"OpenDRIVE\"):\n        for header in opendrive.iter(\"header\"):\n            for georef in header.iter(\"geoReference\"):\n                if georef.text:\n                    str_list = georef.text.split(' ')\n                    for item in str_list:\n                        if '+lat_0' in item:\n                            lat_ref = float(item.split('=')[1])\n                        if '+lon_0' in item:\n                            lon_ref = float(item.split('=')[1])\n    return lat_ref, lon_ref\n\n\ndef downsample_route(route, sample_factor):\n    \"\"\"\n    Downsample the route by some factor.\n    :param route: the trajectory , has to contain the waypoints and the road options\n    :param sample_factor: Maximum distance between samples\n    :return: returns the ids of the final route that can\n    \"\"\"\n\n    ids_to_sample = []\n    prev_option = None\n    dist = 0\n\n    for i, point in enumerate(route):\n        curr_option = point[1]\n\n        # At the beginning\n        if prev_option is None:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # Lane changing\n        elif curr_option in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # When entering or exitting intersections\n        elif prev_option != curr_option and prev_option not in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # After a certain max distance\n        elif dist > sample_factor:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # At the end\n        elif i == len(route) - 1:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # Compute the distance traveled\n        else:\n            curr_location = point[0].location\n            prev_location = route[i-1][0].location\n            dist += curr_location.distance(prev_location)\n\n        prev_option = curr_option\n\n    return ids_to_sample\n\n\ndef interpolate_trajectory(waypoints_trajectory, hop_resolution=1.0):\n    \"\"\"\n    Given some raw keypoints interpolate a full dense trajectory to be used by the user.\n    returns the full interpolated route both in GPS coordinates and also in its original form.\n    \n    Args:\n        - waypoints_trajectory: the current coarse trajectory\n        - hop_resolution: distance between the trajectory's waypoints\n    \"\"\"\n\n    grp = GlobalRoutePlanner(CarlaDataProvider.get_map(), hop_resolution)\n    # Obtain route plan\n    lat_ref, lon_ref = _get_latlon_ref(CarlaDataProvider.get_world())\n\n    route = []\n    gps_route = []\n\n    for i in range(len(waypoints_trajectory) - 1):\n\n        waypoint = waypoints_trajectory[i]\n        waypoint_next = waypoints_trajectory[i + 1]\n        interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n        for wp, connection in interpolated_trace:\n            route.append((wp.transform, connection))\n            gps_coord = _location_to_gps(lat_ref, lon_ref, wp.transform.location)\n            gps_route.append((gps_coord, connection))\n\n    return gps_route, route\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/route_parser.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule used to parse all the route and scenario configuration parameters.\n\"\"\"\nimport math\nimport xml.etree.ElementTree as ET\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\nfrom srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData\n\n# Threshold to say if a scenarios trigger position is part of the route\nDIST_THRESHOLD = 2.0\nANGLE_THRESHOLD = 10\n\n\ndef convert_elem_to_transform(elem):\n    \"\"\"Convert an ElementTree.Element to a CARLA transform\"\"\"\n    return carla.Transform(\n        carla.Location(\n            float(elem.attrib.get('x')),\n            float(elem.attrib.get('y')),\n            float(elem.attrib.get('z'))\n        ),\n        carla.Rotation(\n            roll=0.0,\n            pitch=0.0,\n            yaw=float(elem.attrib.get('yaw'))\n        )\n    )\n\n\nclass RouteParser(object):\n\n    \"\"\"\n    Pure static class used to parse all the route and scenario configuration parameters.\n    \"\"\"\n\n    @staticmethod\n    def parse_routes_file(route_filename, routes_subset=''):\n        \"\"\"\n        Returns a list of route configuration elements.\n        :param route_filename: the path to a set of routes.\n        :param single_route: If set, only this route shall be returned\n        :return: List of dicts containing the waypoints, id and town of the routes\n        \"\"\"\n        def get_routes_subset():\n            \"\"\"\n            The route subset can be indicated by single routes separated by commas,\n            or group of routes separated by dashes (or a combination of the two)\"\"\"\n            subset_ids = []\n            subset_groups = routes_subset.replace(\" \",\"\").split(',')\n            for group in subset_groups:\n                if \"-\" in group:\n                    # Group of route, iterate from start to end, making sure both ids exist\n                    start, end = group.split('-')\n                    found_start, found_end = (False, False)\n\n                    for route in tree.iter(\"route\"):\n                        route_id = route.attrib['id']\n                        if not found_start and route_id == start:\n                            found_start = True\n                        if not found_start and route_id == end:\n                            raise ValueError(f\"Malformed route subset '{group}', found the end id before the starting one\")\n                        if not found_end and found_start:\n                            if route_id in subset_ids:\n                                raise ValueError(f\"Found a repeated route with id '{route_id}'\")\n                            else:\n                                subset_ids.append(route_id)\n                            if route_id == end:\n                                found_end = True\n\n                    if not found_start:\n                        raise ValueError(f\"Couldn\\'t find the route with id '{start}' inside the given routes file\")\n                    if not found_end:\n                        raise ValueError(f\"Couldn\\'t find the route with id '{end}' inside the given routes file\")\n\n                else:\n                    # Just one route, get its id while making sure it exists\n\n                    found = False\n                    for route in tree.iter(\"route\"):\n                        route_id = route.attrib['id']\n                        if route_id == group:\n                            if route_id in subset_ids:\n                                raise ValueError(f\"Found a repeated route with id '{route_id}'\")\n                            else:\n                                subset_ids.append(route_id)\n                            found = True\n\n                    if not found:\n                        raise ValueError(f\"Couldn't find the route with id '{group}' inside the given routes file\")\n\n            subset_ids.sort(key=lambda k: int(k))\n            return subset_ids\n\n        route_configs = []\n        tree = ET.parse(route_filename)\n        if routes_subset:\n            subset_list = get_routes_subset()\n        for route in tree.iter(\"route\"):\n\n            route_id = route.attrib['id']\n            if routes_subset and route_id not in subset_list:\n                continue\n\n            route_config = RouteScenarioConfiguration()\n            route_config.town = route.attrib['town']\n            route_config.name = \"RouteScenario_{}\".format(route_id)\n            route_config.weather = RouteParser.parse_weather(route)\n\n            # The list of carla.Location that serve as keypoints on this route\n            positions = []\n            for position in route.find('waypoints').iter('position'):\n                positions.append(carla.Location(x=float(position.attrib['x']),\n                                                y=float(position.attrib['y']),\n                                                z=float(position.attrib['z'])))\n            route_config.keypoints = positions\n\n            # The list of ScenarioConfigurations that store the scenario's data\n            scenario_configs = []\n            for scenario in route.find('scenarios').iter('scenario'):\n                scenario_config = ScenarioConfiguration()\n                scenario_config.name = scenario.attrib.get('name')\n                scenario_config.type = scenario.attrib.get('type')\n\n                for elem in scenario.getchildren():\n                    if elem.tag == 'trigger_point':\n                        scenario_config.trigger_points.append(convert_elem_to_transform(elem))\n                    elif elem.tag == 'other_actor':\n                        scenario_config.other_actors.append(ActorConfigurationData.parse_from_node(elem, 'scenario'))\n                    else:\n                        scenario_config.other_parameters[elem.tag] = elem.attrib\n\n                scenario_configs.append(scenario_config)\n            route_config.scenario_configs = scenario_configs\n\n            route_configs.append(route_config)\n\n        return route_configs\n\n    @staticmethod\n    def parse_weather(route):\n        \"\"\"\n        Parses all the weather information as a list of [position, carla.WeatherParameters],\n        where the position represents a % of the route.\n        \"\"\"\n        weathers = []\n\n        weathers_elem = route.find(\"weathers\")\n        if weathers_elem is None:\n            return [[0, carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)]]\n\n        for weather_elem in weathers_elem.iter('weather'):\n            route_percentage = float(weather_elem.attrib['route_percentage'])\n\n            weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)  # Base weather\n            for weather_attrib in weather_elem.attrib:\n                if hasattr(weather, weather_attrib):\n                    setattr(weather, weather_attrib, float(weather_elem.attrib[weather_attrib]))\n                elif weather_attrib != 'route_percentage':\n                    print(f\"WARNING: Ignoring '{weather_attrib}', as it isn't a weather parameter\")\n\n            weathers.append([route_percentage, weather])\n\n        weathers.sort(key=lambda x: x[0])\n        return weathers\n\n    @staticmethod\n    def is_scenario_at_route(trigger_transform, route):\n        \"\"\"\n        Check if the scenario is affecting the route.\n        This is true if the trigger position is very close to any route point\n        \"\"\"\n        def is_trigger_close(trigger_transform, route_transform):\n            \"\"\"Check if the two transforms are similar\"\"\"\n            dx = trigger_transform.location.x - route_transform.location.x\n            dy = trigger_transform.location.y - route_transform.location.y\n            dz = trigger_transform.location.z - route_transform.location.z\n            dpos = math.sqrt(dx * dx + dy * dy)\n\n            dyaw = (float(trigger_transform.rotation.yaw) - route_transform.rotation.yaw) % 360\n\n            return dz < DIST_THRESHOLD and dpos < DIST_THRESHOLD \\\n                and (dyaw < ANGLE_THRESHOLD or dyaw > (360 - ANGLE_THRESHOLD))\n\n        for route_transform, _ in route:\n            if is_trigger_close(trigger_transform, route_transform):\n                return True\n\n        return False\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/leaderboard/utils/statistics_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module contains a statistics manager for the CARLA AD leaderboard\n\"\"\"\n\nfrom __future__ import print_function\n\nfrom dictor import dictor\nimport math\n\nfrom srunner.scenariomanager.traffic_events import TrafficEventType\n\nfrom leaderboard.utils.checkpoint_tools import fetch_dict, save_dict\n\nPENALTY_VALUE_DICT = {\n    # Traffic events that substract a set amount of points.\n    TrafficEventType.COLLISION_PEDESTRIAN: 0.5,\n    TrafficEventType.COLLISION_VEHICLE: 0.6,\n    TrafficEventType.COLLISION_STATIC: 0.65,\n    TrafficEventType.TRAFFIC_LIGHT_INFRACTION: 0.7,\n    TrafficEventType.STOP_INFRACTION: 0.8,\n    TrafficEventType.SCENARIO_TIMEOUT: 0.7,\n    TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE: 0.7\n}\nPENALTY_PERC_DICT = {\n    # Traffic events that substract a varying amount of points. This is the per unit value.\n    # 'increases' means that the higher the value, the higher the penalty.\n    # 'decreases' means that the ideal value is 100 and the lower the value, the higher the penalty.\n    TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION: [0, 'increases'],  # All route traversed through outside lanes is ignored\n    # TrafficEventType.MIN_SPEED_INFRACTION: [0.7, 'decreases'],\n    TrafficEventType.MIN_SPEED_INFRACTION: [0.7, 'unused'],\n}\n\nPENALTY_NAME_DICT = {\n    TrafficEventType.COLLISION_STATIC: 'collisions_layout',\n    TrafficEventType.COLLISION_PEDESTRIAN: 'collisions_pedestrian',\n    TrafficEventType.COLLISION_VEHICLE: 'collisions_vehicle',\n    TrafficEventType.TRAFFIC_LIGHT_INFRACTION: 'red_light',\n    TrafficEventType.STOP_INFRACTION: 'stop_infraction',\n    TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION: 'outside_route_lanes',\n    TrafficEventType.MIN_SPEED_INFRACTION: 'min_speed_infractions',\n    TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE: 'yield_emergency_vehicle_infractions',\n    TrafficEventType.SCENARIO_TIMEOUT: 'scenario_timeouts',\n    TrafficEventType.ROUTE_DEVIATION: 'route_dev',\n    TrafficEventType.VEHICLE_BLOCKED: 'vehicle_blocked',\n}\n\n# Limit the entry status to some values. Eligible should always be gotten from this table\nENTRY_STATUS_VALUES = ['Started', 'Finished', 'Rejected', 'Crashed', 'Invalid']\nELIGIBLE_VALUES = {'Started': False, 'Finished': True, 'Rejected': False, 'Crashed': False, 'Invalid': False}\n\n# Dictionary mapping a route failure with the 'entry status' and 'status'\nFAILURE_MESSAGES = {\n    \"Simulation\" : [\"Crashed\", \"Simulation crashed\"],\n    \"Sensors\": [\"Rejected\", \"Agent's sensors were invalid\"],\n    \"Agent_init\": [\"Started\", \"Agent couldn't be set up\"],\n    \"Agent_runtime\": [\"Started\", \"Agent crashed\"]\n}\n\nROUND_DIGITS = 3\nROUND_DIGITS_SCORE = 6\n\n\nclass RouteRecord():\n    def __init__(self):\n        self.index = -1\n        self.route_id = None\n        self.scenario_name = None\n        self.weather_id = None\n        self.save_name = None\n        self.status = 'Started'\n        self.num_infractions = 0\n        self.infractions = {}\n        for event_name in PENALTY_NAME_DICT.values():\n            self.infractions[event_name] = []\n        self.infractions['route_timeout'] = []\n\n        self.scores = {\n            'score_route': 0,\n            'score_penalty': 0,\n            'score_composed': 0\n        }\n\n        self.meta = {\n            'route_length': 0,\n            'duration_game': 0,\n            'duration_system': 0,\n        }\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        return vars(self)\n\n\nclass GlobalRecord():\n    def __init__(self):\n        self.index = -1\n        self.route_id = -1\n        self.status = 'Perfect'\n        self.infractions = {}\n        for event_name in PENALTY_NAME_DICT.values():\n            self.infractions[event_name] = 0\n        self.infractions['route_timeout'] = 0\n\n        self.scores_mean = {\n            'score_composed': 0,\n            'score_route': 0,\n            'score_penalty': 0\n        }\n        self.scores_std_dev = self.scores_mean.copy()\n\n        self.meta = {\n            \"total_length\": 0,\n            \"duration_game\": 0,\n            \"duration_system\": 0,\n            'exceptions': []\n        }\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        return vars(self)\n\nclass Checkpoint():\n\n    def __init__(self):\n        self.global_record = {}\n        self.progress = []\n        self.records = []\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        d = {}\n        d['global_record'] = self.global_record.to_json() if self.global_record else {}\n        d['progress'] = self.progress\n        d['records'] = []\n        d['records'] = [x.to_json() for x in self.records if x.index != -1]  # Index -1 = Route in progress\n\n        return d\n\n\nclass Results():\n\n    def __init__(self):\n        self.checkpoint = Checkpoint()\n        self.entry_status = \"Started\"\n        self.eligible = ELIGIBLE_VALUES[self.entry_status]\n        self.sensors = []\n        self.values = []\n        self.labels = []\n\n    def to_json(self):\n        \"\"\"Return a JSON serializable object\"\"\"\n        d = {}\n        d['_checkpoint'] = self.checkpoint.to_json()\n        d['entry_status'] = self.entry_status\n        d['eligible'] = self.eligible\n        d['sensors'] = self.sensors\n        d['values'] = self.values\n        d['labels'] = self.labels\n\n        return d\n\n\ndef to_route_record(record_dict):\n    record = RouteRecord()\n    for key, value in record_dict.items():\n        setattr(record, key, value)\n\n    return record\n\n\ndef compute_route_length(route):\n    route_length = 0.0\n    previous_location = None\n\n    for transform, _ in route:\n        location = transform.location\n        if previous_location:\n            dist_vec = location - previous_location\n            route_length += dist_vec.length()\n        previous_location = location\n\n    return route_length\n\n\n\nclass StatisticsManager(object):\n\n    \"\"\"\n    This is the statistics manager for the CARLA leaderboard.\n    It gathers data at runtime via the scenario evaluation criteria.\n    \"\"\"\n\n    def __init__(self, endpoint, debug_endpoint):\n        self._scenario = None\n        self._route_length = 0\n        self._total_routes = 0\n        self._results = Results()\n        self._endpoint = endpoint\n        self._debug_endpoint = debug_endpoint\n\n    def add_file_records(self, endpoint):\n        \"\"\"Reads a file and saves its records onto the statistics manager\"\"\"\n        data = fetch_dict(endpoint)\n\n        if data:\n            route_records = dictor(data, '_checkpoint.records')\n            if route_records:\n                for record in route_records:\n                    self._results.checkpoint.records.append(to_route_record(record))\n\n    def clear_records(self):\n        \"\"\"Cleanes up the file\"\"\"\n        if not self._endpoint.startswith(('http:', 'https:', 'ftp:')):\n            with open(self._endpoint, 'w') as fd:\n                fd.truncate(0)\n\n    def sort_records(self):\n        \"\"\"Sorts the route records according to their route id (This being i.e RouteScenario0_rep0)\"\"\"\n        self._results.checkpoint.records.sort(key=lambda x: (\n            int(x.route_id.split('_')[1]),\n            int(x.route_id.split('_rep')[-1])\n        ))\n\n        for i, record in enumerate(self._results.checkpoint.records):\n            record.index = i\n\n    def write_live_results(self, index, ego_speed, ego_control, ego_location):\n        \"\"\"Writes live results\"\"\"\n        route_record = self._results.checkpoint.records[index]\n\n        all_events = []\n        if self._scenario:\n            for node in self._scenario.get_criteria():\n                all_events.extend(node.events)\n\n        all_events.sort(key=lambda e: e.get_frame(), reverse=True)\n\n        with open(self._debug_endpoint, 'w') as f:\n            f.write(\"Route id: {}\\n\\n\"\n                    \"Scenario: {}\\n\\n\"\n                    \"Town name: {}\\n\\n\"\n                    \"Weather id: {}\\n\\n\"\n                    \"Save name: {}\\n\\n\"\n                    \"Scores:\\n\"\n                    \"    Driving score:      {:.3f}\\n\"\n                    \"    Route completion:   {:.3f}\\n\"\n                    \"    Infraction penalty: {:.3f}\\n\\n\"\n                    \"    Route length:    {:.3f}\\n\"\n                    \"    Game duration:   {:.3f}\\n\"\n                    \"    System duration: {:.3f}\\n\\n\"\n                    \"Ego:\\n\"\n                    \"    Throttle:           {:.3f}\\n\"\n                    \"    Brake:              {:.3f}\\n\"\n                    \"    Steer:              {:.3f}\\n\\n\"\n                    \"    Speed:           {:.3f} km/h\\n\\n\"\n                    \"    Location:           ({:.3f} {:.3f} {:.3f})\\n\\n\"\n                    \"Total infractions: {}\\n\"\n                    \"Last 5 infractions:\\n\".format(\n                        route_record.route_id,\n                        route_record.scenario_name,\n                        route_record.town_name,\n                        route_record.weather_id,\n                        route_record.save_name,\n                        route_record.scores[\"score_composed\"],\n                        route_record.scores[\"score_route\"],\n                        route_record.scores[\"score_penalty\"],\n                        route_record.meta[\"route_length\"],\n                        route_record.meta[\"duration_game\"],\n                        route_record.meta[\"duration_system\"],\n                        ego_control.throttle,\n                        ego_control.brake,\n                        ego_control.steer,\n                        ego_speed * 3.6,\n                        ego_location.x,\n                        ego_location.y,\n                        ego_location.z,\n                        route_record.num_infractions\n                    )\n                )\n            for e in all_events[:5]:\n                # Prevent showing the ROUTE_COMPLETION event.\n                event_type = e.get_type()\n                if event_type == TrafficEventType.ROUTE_COMPLETION:\n                    continue\n                string = \"    \" + str(e.get_type()).replace(\"TrafficEventType.\", \"\")\n                if event_type in PENALTY_VALUE_DICT:\n                    string += \" (penalty: \" + str(PENALTY_VALUE_DICT[event_type]) + \")\\n\"\n                elif event_type in PENALTY_PERC_DICT:\n                    string += \" (value: \" + str(round(e.get_dict()['percentage'], 3)) + \"%)\\n\"\n\n                f.write(string)\n\n    def save_sensors(self, sensors):\n        self._results.sensors = sensors\n\n    def save_entry_status(self, entry_status):\n        if entry_status not in ENTRY_STATUS_VALUES:\n            raise ValueError(\"Found an invalid value for 'entry_status'\")\n        self._results.entry_status = entry_status\n        self._results.eligible = ELIGIBLE_VALUES[entry_status]\n\n    def save_progress(self, route_index, total_routes):\n        self._results.checkpoint.progress = [route_index, total_routes]\n        self._total_routes = total_routes\n\n    def create_route_data(self, route_id, scenario_name, weather_id, save_name, town_name, index):\n        \"\"\"\n        Creates the basic route data.\n        This is done at the beginning to ensure the data is saved, even if a crash occurs\n        \"\"\"\n        route_record = RouteRecord()\n        route_record.route_id = route_id\n        route_record.scenario_name = scenario_name\n        route_record.weather_id = weather_id\n        route_record.save_name = save_name\n        route_record.town_name = town_name\n\n        # Check if we have to overwrite an element (when resuming), or create a new one\n        route_records = self._results.checkpoint.records\n        if index < len(route_records):\n            self._results.checkpoint.records[index] = route_record\n        else:\n            self._results.checkpoint.records.append(route_record)\n\n    def set_scenario(self, scenario):\n        \"\"\"Sets the scenario from which the statistics will be taken\"\"\"\n        self._scenario = scenario\n        self._route_length = round(compute_route_length(scenario.route), ROUND_DIGITS)\n\n    def remove_scenario(self):\n        \"\"\"Removes the scenario\"\"\"\n        self._scenario = None\n        self._route_length = 0\n\n    def compute_route_statistics(self, route_index, duration_time_system=-1, duration_time_game=-1, failure_message=\"\"):\n        \"\"\"\n        Compute the current statistics by evaluating all relevant scenario criteria.\n        Failure message will not be empty if an external source has stopped the simulations (i.e simulation crash).\n        For the rest of the cases, it will be filled by this function depending on the criteria.\n        \"\"\"\n        def set_infraction_message():\n            infraction_name = PENALTY_NAME_DICT[event.get_type()]\n            route_record.infractions[infraction_name].append(event.get_message())\n\n        def set_score_penalty(score_penalty):\n            event_value = event.get_dict()['percentage']\n            penalty_value, penalty_type = PENALTY_PERC_DICT[event.get_type()]\n            if penalty_type == \"decreases\":\n                score_penalty *= (1 - (1 - penalty_value) * (1 - event_value / 100))\n            elif penalty_type == \"increases\":\n                score_penalty *= (1 - (1 - penalty_value) * event_value / 100)\n            elif penalty_type == \"unused\":\n                pass\n            else:\n                raise ValueError(\"Found a criteria with an unknown penalty type\")\n            return score_penalty\n\n        route_record = self._results.checkpoint.records[route_index]\n        route_record.index = route_index\n\n        target_reached = False\n        score_penalty = 1.0\n        score_route = 0.0\n        for event_name in PENALTY_NAME_DICT.values():\n            route_record.infractions[event_name] = []\n\n        # Update the route meta\n        route_record.meta['route_length'] = self._route_length\n        route_record.meta['duration_game'] = round(duration_time_game, ROUND_DIGITS)\n        route_record.meta['duration_system'] = round(duration_time_system, ROUND_DIGITS)\n\n        # Update the route infractions\n        if self._scenario:\n            if self._scenario.timeout_node.timeout:\n                route_record.infractions['route_timeout'].append('Route timeout.')\n                failure_message = \"Agent timed out\"\n\n            for node in self._scenario.get_criteria():\n                for event in node.events:\n                    # Traffic events that substract a set amount of points\n                    if event.get_type() in PENALTY_VALUE_DICT:\n                        score_penalty *= PENALTY_VALUE_DICT[event.get_type()]\n                        set_infraction_message()\n\n                    # Traffic events that substract a varying amount of points\n                    elif event.get_type() in PENALTY_PERC_DICT:\n                        score_penalty = set_score_penalty(score_penalty)\n                        set_infraction_message()\n\n                    # Traffic events that stop the simulation\n                    elif event.get_type() == TrafficEventType.ROUTE_DEVIATION:\n                        failure_message = \"Agent deviated from the route\"\n                        set_infraction_message()\n\n                    elif event.get_type() == TrafficEventType.VEHICLE_BLOCKED:\n                        failure_message = \"Agent got blocked\"\n                        set_infraction_message()\n\n                    elif event.get_type() == TrafficEventType.ROUTE_COMPLETION:\n                        score_route = event.get_dict()['route_completed']\n                        target_reached = score_route >= 100\n\n        # Update route scores\n        route_record.scores['score_route'] = round(score_route, ROUND_DIGITS_SCORE)\n        route_record.scores['score_penalty'] = round(score_penalty, ROUND_DIGITS_SCORE)\n        route_record.scores['score_composed'] = round(max(score_route * score_penalty, 0.0), ROUND_DIGITS_SCORE)\n\n        # Update result\n        route_record.num_infractions = sum([len(route_record.infractions[key]) for key in route_record.infractions])\n\n        if target_reached:\n            route_record.status = 'Completed' if route_record.num_infractions > 0 else 'Perfect'\n        else:\n            route_record.status = 'Failed'\n            if failure_message:\n                route_record.status += ' - ' + failure_message\n\n        # Add the new data, or overwrite a previous result (happens when resuming the simulation)\n        record_len = len(self._results.checkpoint.records)\n        if route_index == record_len:\n            self._results.checkpoint.records.append(route_record)\n        elif route_index < record_len:\n            self._results.checkpoint.records[route_index] = route_record\n        else:\n            raise ValueError(\"Not enough entries in the route record\")\n\n    def compute_global_statistics(self):\n        \"\"\"Computes and saves the global statistics of the routes\"\"\"\n        def get_infractions_value(route_record, key):\n            # Special case for the % based criteria. Extract the meters from the message. Very ugly, but it works\n            if key == PENALTY_NAME_DICT[TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION]:\n                if not route_record.infractions[key]:\n                    return 0.0\n                return float(route_record.infractions[key][0].split(\" \")[8])/1000\n\n            return len(route_record.infractions[key])\n\n        global_record = GlobalRecord()\n        global_result = global_record.status\n\n        route_records = self._results.checkpoint.records\n\n        # Calculate the score's means and result\n        for route_record in route_records:\n\n            global_record.scores_mean['score_route'] += route_record.scores['score_route'] / self._total_routes\n            global_record.scores_mean['score_penalty'] += route_record.scores['score_penalty'] / self._total_routes\n            global_record.scores_mean['score_composed'] += route_record.scores['score_composed'] / self._total_routes\n\n            global_record.meta['total_length'] += route_record.meta['route_length']\n            global_record.meta['duration_game'] += route_record.meta['duration_game']\n            global_record.meta['duration_system'] += route_record.meta['duration_system']\n\n            # Downgrade the global result if need be ('Perfect' -> 'Completed' -> 'Failed'), and record the failed routes\n            route_result = 'Failed' if 'Failed' in route_record.status else route_record.status\n            if route_result == 'Failed':\n                global_record.meta['exceptions'].append((route_record.route_id,\n                                                         route_record.index,\n                                                         route_record.status))\n                global_result = route_result\n            elif global_result == 'Perfect' and route_result != 'Perfect':\n                global_result = route_result\n\n        for item in global_record.scores_mean:\n            global_record.scores_mean[item] = round(global_record.scores_mean[item], ROUND_DIGITS_SCORE)\n        global_record.status = global_result\n\n        # Calculate the score's standard deviation\n        if self._total_routes == 1:\n            for key in global_record.scores_std_dev:\n                global_record.scores_std_dev[key] = 0\n        else:\n            for route_record in route_records:\n                for key in global_record.scores_std_dev:\n                    diff = route_record.scores[key] - global_record.scores_mean[key]\n                    global_record.scores_std_dev[key] += math.pow(diff, 2)\n\n            for key in global_record.scores_std_dev:\n                value = round(math.sqrt(global_record.scores_std_dev[key] / float(self._total_routes - 1)), ROUND_DIGITS)\n                global_record.scores_std_dev[key] = value\n\n        # Calculate the number of infractions per km\n        km_driven = 0\n        for route_record in route_records:\n            km_driven += route_record.meta['route_length'] / 1000 * route_record.scores['score_route'] / 100\n            for key in global_record.infractions:\n                global_record.infractions[key] += get_infractions_value(route_record, key)\n        km_driven = max(km_driven, 0.001)\n\n        for key in global_record.infractions:\n            # Special case for the % based criteria.\n            if key != PENALTY_NAME_DICT[TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION]:\n                global_record.infractions[key] /= km_driven\n            global_record.infractions[key] = round(global_record.infractions[key], ROUND_DIGITS)\n\n        # Save the global records\n        self._results.checkpoint.global_record = global_record\n\n        # Change the values and labels. These MUST HAVE A MATCHING ORDER\n        self._results.values = [\n            str(global_record.scores_mean['score_composed']),\n            str(global_record.scores_mean['score_route']),\n            str(global_record.scores_mean['score_penalty']),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.COLLISION_PEDESTRIAN]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.COLLISION_VEHICLE]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.COLLISION_STATIC]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.TRAFFIC_LIGHT_INFRACTION]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.STOP_INFRACTION]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.ROUTE_DEVIATION]]),\n            str(global_record.infractions['route_timeout']),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.VEHICLE_BLOCKED]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.SCENARIO_TIMEOUT]]),\n            str(global_record.infractions[PENALTY_NAME_DICT[TrafficEventType.MIN_SPEED_INFRACTION]]),\n        ]\n\n        self._results.labels = [\n            \"Avg. driving score\",\n            \"Avg. route completion\",\n            \"Avg. infraction penalty\",\n            \"Collisions with pedestrians\",\n            \"Collisions with vehicles\",\n            \"Collisions with layout\",\n            \"Red lights infractions\",\n            \"Stop sign infractions\",\n            \"Off-road infractions\",\n            \"Route deviations\",\n            \"Route timeouts\",\n            \"Agent blocked\",\n            \"Yield emergency vehicles infractions\",\n            \"Scenario timeouts\",\n            \"Min speed infractions\"\n        ]\n\n        # Change the entry status and eligible\n        entry_status = 'Finished'\n        for route_record in route_records:\n            route_status = route_record.status\n            if 'Simulation crashed' in route_status:\n                entry_status = 'Crashed'\n            elif \"Agent's sensors were invalid\" in route_status:\n                entry_status = 'Rejected'\n\n        self.save_entry_status(entry_status)\n\n    def validate_and_write_statistics(self, sensors_initialized, crashed):\n        \"\"\"\n        Makes sure that all the relevant data is there.\n        Changes the 'entry status' to 'Invalid' if this isn't the case\n        \"\"\"\n        error_message = \"\"\n        if sensors_initialized and not self._results.sensors:\n            error_message = \"Missing 'sensors' data\"\n\n        elif not self._results.values:\n            error_message = \"Missing 'values' data\"\n\n        elif self._results.entry_status == 'Started':\n            error_message = \"'entry_status' has the 'Started' value\"\n\n        else:\n            global_records = self._results.checkpoint.global_record\n            progress = self._results.checkpoint.progress\n            route_records = self._results.checkpoint.records\n\n            if not global_records:\n                error_message = \"Missing 'global_records' data\"\n\n            elif not progress:\n                error_message = \"Missing 'progress' data\"\n\n            elif not crashed and (progress[0] != progress[1] or progress[0] != len(route_records)):\n                error_message = \"'progress' data doesn't match its expected value\"\n\n            else:\n                for record in route_records:\n                    if record.status == 'Started':\n                        error_message = \"Found a route record with missing data\"\n                        break\n\n        if error_message:\n            print(\"\\n\\033[91mThe statistics are badly formed. Setting their status to 'Invalid':\")\n            print(\"> {}\\033[0m\\n\".format(error_message))\n\n            self.save_entry_status('Invalid')\n\n        self.write_statistics()\n\n    def write_statistics(self):\n        \"\"\"\n        Writes the results into the endpoint. Meant to be used only for partial evaluations,\n        use 'validate_and_write_statistics' for the final one as it only validates the data.\n        \"\"\"\n        save_dict(self._endpoint, self._results.to_json())\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/requirements.txt",
    "content": "dictor\nrequests\nopencv-python==4.2.0.32\npygame\ntabulate\npexpect\ntransforms3d\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/run_leaderboard.sh",
    "content": " #!/bin/bash\n\nexport TEAM_AGENT=$LEADERBOARD_ROOT/leaderboard/autoagents/human_agent.py\n\nexport ROUTES=$LEADERBOARD_ROOT/data/routes_devtest.xml\nexport ROUTES_SUBSET=0\nexport REPETITIONS=1\n\nexport DEBUG_CHALLENGE=1\nexport CHALLENGE_TRACK_CODENAME=SENSORS\nexport CHECKPOINT_ENDPOINT=\"${LEADERBOARD_ROOT}/results.json\"\nexport RECORD_PATH=\nexport RESUME=\n\n#!/bin/bash\n\npython3 ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \\\n--routes=${ROUTES} \\\n--routes-subset=${ROUTES_SUBSET} \\\n--repetitions=${REPETITIONS} \\\n--track=${CHALLENGE_TRACK_CODENAME} \\\n--checkpoint=${CHECKPOINT_ENDPOINT} \\\n--debug-checkpoint=${DEBUG_CHECKPOINT_ENDPOINT} \\\n--agent=${TEAM_AGENT} \\\n--agent-config=${TEAM_CONFIG} \\\n--debug=${DEBUG_CHALLENGE} \\\n--record=${RECORD_PATH} \\\n--resume=${RESUME}"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/Dockerfile.master",
    "content": "FROM nvidia/cuda:11.7.1-cudnn8-devel-ubuntu20.04\n\nARG HTTP_PROXY\nARG HTTPS_PROXY\nARG http_proxy\n\nRUN apt-get update && apt-get install --reinstall -y locales && locale-gen en_US.UTF-8 && rm -rf /var/lib/apt/lists/*\nENV LANG en_US.UTF-8\nENV LANGUAGE en_US\nENV LC_ALL en_US.UTF-8\nENV DEBIAN_FRONTEND=noninteractive\n\n# Install dependencies\nRUN apt-get update && apt-get install -y --no-install-recommends \\\n    build-essential \\\n    cmake \\\n    git \\\n    curl \\\n    vim \\\n    ca-certificates \\\n    libjpeg-dev \\\n    libpng16-16 \\\n    libtiff5 \\\n    libpng-dev \\\n    python3-dev \\\n    python3-pip \\\n    python3-setuptools && \\\n    python3 -m pip install --upgrade pip && \\\n    rm -rf /var/lib/apt/lists/*\n\n# Installing conda\nRUN curl -o ~/miniconda.sh -LO https://repo.continuum.io/miniconda/Miniconda3-latest-Linux-x86_64.sh  && \\\n    chmod +x ~/miniconda.sh && \\\n    ~/miniconda.sh -b -p /opt/conda && \\\n    rm ~/miniconda.sh && \\\n    /opt/conda/bin/conda clean -ya && \\\n    /opt/conda/bin/conda create -n python37 python=3.7 numpy networkx scipy six requests\n\nENV PATH \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\":\"/opt/conda/envs/python37/bin\":\"/opt/conda/envs/bin\":$PATH\n\n# Copy the files into the docker\nWORKDIR /workspace\n\nENV CARLA_ROOT \"/workspace/CARLA\"\nENV SCENARIO_RUNNER_ROOT \"/workspace/scenario_runner\"\nENV LEADERBOARD_ROOT \"/workspace/leaderboard\"\nENV TEAM_CODE_ROOT \"/workspace/team_code\"\n\nCOPY PythonAPI ${CARLA_ROOT}/PythonAPI\nCOPY scenario_runner ${SCENARIO_RUNNER_ROOT}\nCOPY leaderboard ${LEADERBOARD_ROOT}\nCOPY team_code ${TEAM_CODE_ROOT}\n\nRUN pip3 install -r ${SCENARIO_RUNNER_ROOT}/requirements.txt\nRUN pip3 install -r ${LEADERBOARD_ROOT}/requirements.txt\n\nRUN mkdir -p /workspace/results\nRUN chmod +x /workspace/leaderboard/run_leaderboard.sh\n\nENV PYTHONPATH \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\":\"${SCENARIO_RUNNER_ROOT}\":\"${CARLA_ROOT}/PythonAPI/carla\":\"${LEADERBOARD_ROOT}\":\"${TEAM_CODE_ROOT}\":${PYTHONPATH}\n\n############################################################################################\n####                     BEGINNING OF AGENT SPECIFIC COMMANDS                           ####\n############################################################################################\n\nENV TEAM_AGENT ${TEAM_CODE_ROOT}/npc_agent.py\n# ENV TEAM_CONFIG ${TEAM_CODE_ROOT}/YOUR_CONFIG_FILE\nENV CHALLENGE_TRACK_CODENAME SENSORS\n\n############################################################################################\n####                        END OF AGENT SPECIFIC COMMANDS                              ####\n############################################################################################\n\nENV ROUTES ${LEADERBOARD_ROOT}/data/routes_training.xml\nENV REPETITIONS 1\nENV CHECKPOINT_ENDPOINT /workspace/results/results.json\nENV DEBUG_CHALLENGE 0\n\nENV HTTP_PROXY \"\"\nENV HTTPS_PROXY \"\"\nENV http_proxy \"\"\nENV https_proxy \"\"\n\nCMD [\"/bin/bash\"]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/Dockerfile.ros",
    "content": "ARG ROS_DISTRO\n\nFROM ros:$ROS_DISTRO-ros-base\n\nWORKDIR /workspace\n\nENV DEBIAN_FRONTEND \"noninteractive\"\n\nRUN apt-get update; \\\n  if [ \"$ROS_DISTRO\" = \"melodic\" ]; then \\\n    apt-get install -y --no-install-recommends \\\n      ros-${ROS_DISTRO}-rosbridge-suite \\\n      python-setuptools \\\n      python3-setuptools \\\n      python-wheel \\\n      python3-wheel \\\n      python-pip \\\n      python3-pip \\\n      && python2 -m pip install --upgrade pip \\\n      && python3 -m pip install --upgrade pip; \\\n  elif [ \"$ROS_DISTRO\" = \"noetic\" ]; then \\\n    apt-get install -y --no-install-recommends \\\n      ros-${ROS_DISTRO}-rosbridge-suite \\\n      python-is-python3 \\\n      python3-setuptools \\\n      python3-wheel \\\n      python3-pip \\\n      && python3 -m pip install --upgrade pip; \\\n  elif [ \"$ROS_DISTRO\" = \"foxy\" ]; then \\\n    apt-get install -y --no-install-recommends \\\n      # TODO: This should be installed by rosdep\n      python3-opencv \\\n      python3-setuptools \\\n      python3-wheel \\\n      python3-pip \\\n      && python3 -m pip install --upgrade pip; \\\n  fi; \\\n  rm -rf /var/lib/apt/lists/*\n\nENV CARLA_ROOT \"/workspace/CARLA\"\nENV SCENARIO_RUNNER_ROOT \"/workspace/scenario_runner\"\nENV LEADERBOARD_ROOT \"/workspace/leaderboard\"\nENV CARLA_ROS_BRIDGE_ROOT \"/workspace/carla_ros_bridge\"\nENV TEAM_CODE_ROOT \"/workspace/team_code\"\n\nCOPY PythonAPI ${CARLA_ROOT}/PythonAPI\nCOPY scenario_runner ${SCENARIO_RUNNER_ROOT}\nCOPY leaderboard ${LEADERBOARD_ROOT}\n\nCOPY carla_ros_bridge/carla_ros_bridge ${CARLA_ROS_BRIDGE_ROOT}/src/carla_ros_bridge\nCOPY carla_ros_bridge/carla_common ${CARLA_ROS_BRIDGE_ROOT}/src/carla_common\nCOPY carla_ros_bridge/carla_msgs ${CARLA_ROS_BRIDGE_ROOT}/src/carla_msgs\nCOPY carla_ros_bridge/ros_compatibility ${CARLA_ROS_BRIDGE_ROOT}/src/ros_compatibility\n\nCOPY team_code ${TEAM_CODE_ROOT}\n\n# Install carla ros bridge\nRUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \\\n  apt-get update && rosdep update; \\\n  cd /workspace/carla_ros_bridge; \\\n  rm -rf build devel install log; \\\n  rosdep install --from-paths src --ignore-src -r -y; \\\n  if [ \"$ROS_VERSION\" = \"1\" ]; then \\\n    catkin_make install -DCMAKE_INSTALL_PREFIX=/opt/ros/$ROS_DISTRO; \\\n  else \\\n    colcon build; \\\n  fi; \\\n  rm -rf build devel log; \\\n  rm -rf /var/lib/apt/lists/*'\n  #colcon build --merge-install --install-base /opt/ros/$ROS_DISTRO; \\\n  #catkin_make install --only-pkg-with-deps carla_ros_bridge -DCMAKE_INSTALL_PREFIX=/opt/ros/melodic'\n\n# Install agent\nRUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \\\n  apt-get update && rosdep update; \\\n  cd /workspace/team_code; \\\n  rm -rf build devel install log; \\\n  rosdep install --from-paths src --ignore-src -r -y; \\\n  if [ \"$ROS_VERSION\" = \"1\" ]; then \\\n    catkin_make install; \\\n  else \\\n    colcon build; \\\n  fi; \\\n  rm -rf build devel log; \\\n  rm -rf /var/lib/apt/lists/*'\n\nRUN mkdir -p /workspace/results\nRUN chmod +x /workspace/leaderboard/run_leaderboard.sh\n\nENV PYTHONPATH \"${CARLA_ROOT}/PythonAPI/carla\":\"${SCENARIO_RUNNER_ROOT}\":\"${LEADERBOARD_ROOT}\":${PYTHONPATH}\n\nRUN if [ \"$ROS_DISTRO\" = \"melodic\" ]; then \\\n    echo \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py2.7.egg\" > /usr/local/lib/python2.7/dist-packages/carla.pth; \\\n    echo \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\" > /usr/local/lib/python3.6/dist-packages/carla.pth; \\\n  else \\\n    echo \"${CARLA_ROOT}/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\" > /usr/local/lib/python3.8/dist-packages/carla.pth; \\\n  fi\n\nRUN pip3 install \\\n     transforms3d \\\n     roslibpy \\\n     pexpect \\\n     networkx \\\n     numpy \\\n     py_trees==0.8.3 \\\n     psutil \\\n     shapely \\\n     six \\\n     dictor \\\n     requests \\\n     ephem \\\n     tabulate \\\n     simple-watchdog-timer\n\n############################################################################################\n####                     BEGINNING OF AGENT SPECIFIC COMMANDS                           ####\n############################################################################################\n\nENV TEAM_AGENT ${TEAM_CODE_ROOT}/my_ros_agent.py\nENV CHALLENGE_TRACK_CODENAME MAP\n\n############################################################################################\n####                        END OF AGENT SPECIFIC COMMANDS                              ####\n############################################################################################\n\nENV ROUTES ${LEADERBOARD_ROOT}/data/routes_training.xml\nENV REPETITIONS 1\nENV CHECKPOINT_ENDPOINT /workspace/results/results.json\nENV DEBUG_CHALLENGE 0\n\n# Agent sources\nRUN /bin/echo \\\n  'source /opt/ros/$ROS_DISTRO/setup.bash; \\\n  if [ \"$ROS_VERSION\" = \"2\" ]; then \\\n    source $CARLA_ROS_BRIDGE_ROOT/install/setup.bash; \\\n  fi; \\\n  source $TEAM_CODE_ROOT/install/setup.bash;' >> ${HOME}/agent_sources.sh\n\nCOPY agent_entrypoint.sh /\nENTRYPOINT [\"/agent_entrypoint.sh\"]\n\nCMD [\"/bin/bash\"]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/agent_entrypoint.sh",
    "content": "#!/bin/bash\nset -e\n\nsource \"${HOME}/agent_sources.sh\"\n\nexec \"$@\""
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/code_check_and_formatting.sh",
    "content": "#!/bin/bash\n\nautopep8_params=\"--in-place --max-line-length=120\"\npylint_params=\"--rcfile=.pylintrc\"\n\nfiles=`find leaderboard/ -type f -name \"*.py\"`\nfor file in ${files[@]}\ndo\n  autopep8 $file ${autopep8_params}\n  pylint --rcfile=.pylintrc ${pylint_params} $file\ndone\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/make_docker.sh",
    "content": "#!/bin/bash\n\nDOC_STRING=\"Build agent leadearboard image.\"\n\nUSAGE_STRING=$(cat <<- END\nUsage: $0 [-h|--help] [-r|--ros-distro ROS_DISTRO]\n\nThe following ROS distributions are supported:\n    * melodic\n    * noetic\n    * foxy\nEND\n)\n\nusage() { echo \"$DOC_STRING\"; echo \"$USAGE_STRING\"; exit 1; }\n\nROS_DISTRO=\"\"\n\nwhile [[ $# -gt 0 ]]; do\n  case \"$1\" in\n    -r |--ros-distro )\n      ROS_DISTRO=$2\n      if [ \"$ROS_DISTRO\" != \"melodic\" ] && [ \"$ROS_DISTRO\" != \"noetic\" ] && [ \"$ROS_DISTRO\" != \"foxy\" ]; then\n        usage\n      fi\n      shift 2 ;;\n    -h | --help )\n      usage\n      ;;\n    * )\n      shift ;;\n  esac\ndone\n\nif [ -z \"$CARLA_ROOT\" ]; then\n  echo \"Error $CARLA_ROOT is empty. Set \\$CARLA_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ -z \"$SCENARIO_RUNNER_ROOT\" ]; then\n  echo \"Error $SCENARIO_RUNNER_ROOT is empty. Set \\$SCENARIO_RUNNER_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ ! -z \"$ROS_DISTRO\" ] && [ -z $CARLA_ROS_BRIDGE_ROOT ]; then\n  echo \"Error $CARLA_ROS_BRIDGE_ROOT is empty. Set \\$CARLA_ROS_BRIDGE_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ -z \"$LEADERBOARD_ROOT\" ]; then\n  echo \"Error $LEADERBOARD_ROOT is empty. Set \\$LEADERBOARD_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nif [ -z \"$TEAM_CODE_ROOT\" ]; then\n  echo \"Error $TEAM_CODE_ROOT is empty. Set \\$TEAM_CODE_ROOT as an environment variable first.\"\n  exit 1\nfi\n\nrm -fr .lbtmp\nmkdir -p .lbtmp\n\necho \"Copying CARLA Python API\"\ncp -fr ${CARLA_ROOT}/PythonAPI  .lbtmp\nmv .lbtmp/PythonAPI/carla/dist/carla*-py2*.egg .lbtmp/PythonAPI/carla/dist/carla-leaderboard-py2.7.egg\nmv .lbtmp/PythonAPI/carla/dist/carla*-py3*.egg .lbtmp/PythonAPI/carla/dist/carla-leaderboard-py3x.egg\n\necho \"Copying Scenario Runner\"\ncp -fr ${SCENARIO_RUNNER_ROOT}/ .lbtmp\nrm -fr .lbtmp/scenario_runner/.git\n\necho \"Copying Leaderboard\"\ncp -fr ${LEADERBOARD_ROOT}/ .lbtmp\nrm -fr .lbtmp/leaderboard/.git\n\nif [ ! -z \"$ROS_DISTRO\" ]; then\n  echo \"Copying ROS Bridge\"\n  cp -fr ${CARLA_ROS_BRIDGE_ROOT}/ .lbtmp/carla_ros_bridge\nfi\n\necho \"Copying team code folder\"\ncp -fr ${TEAM_CODE_ROOT}/ .lbtmp/team_code\n\ncp ${LEADERBOARD_ROOT}/scripts/agent_entrypoint.sh .lbtmp/agent_entrypoint.sh\n\necho \"Building docker\"\n# build docker image\nif [ -z \"$ROS_DISTRO\" ]; then\n  docker build \\\n    --force-rm  \\\n    -t leaderboard-user \\\n    -f ${LEADERBOARD_ROOT}/scripts/Dockerfile.master .lbtmp\nelse\n  docker build \\\n    --force-rm  \\\n    -t leaderboard-user:ros-$ROS_DISTRO \\\n    -f ${LEADERBOARD_ROOT}/scripts/Dockerfile.ros .lbtmp \\\n    --build-arg ROS_DISTRO=$ROS_DISTRO\nfi\n\nrm -fr .lbtmp\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/manage_scenarios.py",
    "content": "import argparse\nfrom argparse import RawTextHelpFormatter\nimport math\n\nimport carla\n\nfrom leaderboard.utils.checkpoint_tools import fetch_dict\nfrom leaderboard.utils.route_parser import DIST_THRESHOLD\n\nSCENARIO_COLOR = {\n    \"Scenario1\": [carla.Color(255, 0, 0), \"Red\"],\n    \"Scenario2\": [carla.Color(0, 255, 0), \"Green\"],\n    \"Scenario3\": [carla.Color(0, 0, 255), \"Blue\"],\n    \"Scenario4\": [carla.Color(255, 100, 0), \"Orange\"],\n    \"Scenario5\": [carla.Color(0, 255, 100), \"Blueish green\"],\n    \"Scenario6\": [carla.Color(100, 0, 255), \"Purple\"],\n    \"Scenario7\": [carla.Color(255, 100, 255), \"Pink\"],\n    \"Scenario8\": [carla.Color(255, 255, 100), \"Yellow\"],\n    \"Scenario9\": [carla.Color(100, 255, 255), \"Light Blue\"], \n    \"Scenario10\": [carla.Color(100, 100, 100), \"Gray\"]\n}\n\nDEBUG_HEIGHT_INTERVAL = 0.3\n\ndef get_scenario_transform(scenario_dict):\n    return carla.Transform(\n        carla.Location(\n            float(scenario_dict['transform']['x']),\n            float(scenario_dict['transform']['y']),\n            float(scenario_dict['transform']['z'])\n        ),\n        carla.Rotation(\n            float(scenario_dict['transform']['pitch']),\n            float(scenario_dict['transform']['yaw']),\n            0\n        )\n    )\n\ndef get_color_validity(waypoint_transform, scenario_transform, scenario_type, scenario_index, debug):\n    \"\"\"\n    Uses the same condition as in route_scenario to see if they will\n    be differentiated\n    \"\"\"\n    ANGLE_THRESHOLD = 10\n\n    dx = float(waypoint_transform.location.x) - scenario_transform.location.x\n    dy = float(waypoint_transform.location.y) - scenario_transform.location.y\n    dz = float(waypoint_transform.location.z) - scenario_transform.location.z\n    dpos = math.sqrt(dx * dx + dy * dy + dz * dz)\n    dyaw = (float(waypoint_transform.rotation.yaw) - scenario_transform.rotation.yaw) % 360\n\n    if dpos > DIST_THRESHOLD:\n        if not debug:\n            print(\"WARNING: Found a scenario with the wrong position \"\n                  \"(Type: {}, Index: {})\".format(scenario_type, scenario_index))\n        return carla.Color(255, 0, 0)\n    if dyaw > ANGLE_THRESHOLD and dyaw < (360 - ANGLE_THRESHOLD):\n        if not debug:\n            print(\"WARNING: Found a scenario with the wrong orientation \"\n                  \"(Type: {}, Index: {})\".format(scenario_type, scenario_index))\n        return carla.Color(0, 0, 255)\n    return carla.Color(0, 255, 0)\n\n\ndef create_scenarios(world, town_data, tmap, scenarios, debug):\n    \"\"\"\n    Creates new S7 to S10 by moving 5 meters backwards from an already existing S4.\n    They have to be manually added to the json file but information is given to simplify that process\n    \"\"\"\n    for scenario_data in town_data:\n        # Get the desired scenario data\n        scenario_type = scenario_data[\"scenario_type\"]\n        if scenario_type not in scenarios:\n            continue\n\n        number = float(scenario_type[8:])\n        debug_loc_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number)\n        debug_str_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number + 0.1)\n        color = SCENARIO_COLOR[scenario_type][0]\n\n        scenario_list = scenario_data[\"available_event_configurations\"]\n        for i in range(len(scenario_list)):\n            # Get the individual scenario data\n            scenario_dict = scenario_list[i]\n            scenario_transform = get_scenario_transform(scenario_dict)\n            scenario_location = scenario_transform.location\n            world.debug.draw_point(\n                scenario_location + debug_loc_height, float(0.15), color)\n            world.debug.draw_string(\n                scenario_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            # Get the new scenario data\n            scenario_wp = tmap.get_waypoint(scenario_location)\n            new_transform = scenario_wp.previous(5)[0].transform\n            new_location = new_transform.location\n            world.debug.draw_point(\n                new_location + debug_loc_height, float(0.15), carla.Color(0,0,0))\n            world.debug.draw_string(\n                new_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            if debug:\n                spectator = world.get_spectator()\n                spectator.set_transform(carla.Transform(new_location + carla.Location(z=50),\n                                                        carla.Rotation(pitch=-90)))\n                input(\" New Scenario [{}/{}] at (x={}, y={}, z={}, yaw={}). Press Enter to continue\".format(\n                    i, len(scenario_list) -1,\n                    round(new_location.x, 1),\n                    round(new_location.y, 1),\n                    round(new_location.z, 1),\n                    round(new_transform.rotation.yaw, 1))\n                )\n\n        world.wait_for_tick()\n\n\ndef validate_scenarios(world, town_data, tmap, scenarios, debug):\n    \"\"\"\n    Validates that all the scenarios can be triggered (by having a waypoint closeby). Color code\n    - Can be triggered: Green\n    - Didn't pass the position check: Red\n    - Didn't pass the yaw check: Blue\n    \"\"\"\n    for scenario_data in town_data:\n        # Get the desired scenario data\n        scenario_type = scenario_data[\"scenario_type\"]\n        if scenario_type not in scenarios:\n            continue\n\n        number = float(scenario_type[8:])\n        debug_loc_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number)\n        debug_str_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number + 0.1)\n\n        scenario_list = scenario_data[\"available_event_configurations\"]\n        for i in range(len(scenario_list)):\n            # Get the individual scenario data\n            scenario_dict = scenario_list[i]\n            scenario_transform = get_scenario_transform(scenario_dict)\n            scenario_location = scenario_transform.location\n\n            # Check if the scenario is close enough to the wp\n            scenario_wp = tmap.get_waypoint(scenario_location)\n            color = get_color_validity(scenario_wp.transform, scenario_transform, scenario_type, i, debug)\n\n            world.debug.draw_point(\n                scenario_location + debug_loc_height, float(0.15), color)\n            world.debug.draw_string(\n                scenario_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            if debug:\n                spectator = world.get_spectator()\n                spectator.set_transform(carla.Transform(scenario_location + carla.Location(z=50),\n                                                        carla.Rotation(pitch=-90)))\n                input(\" Scenario [{}/{}] at (x={}, y={}, z={}, yaw={}). Press Enter to continue\".format(\n                    i, len(scenario_list) - 1,\n                    round(scenario_location.x, 1),\n                    round(scenario_location.y, 1),\n                    round(scenario_location.z, 1),\n                    round(scenario_transform.rotation.yaw, 1))\n                )\n\n        world.wait_for_tick()\n\ndef draw_scenarios(world, town_data, scenarios, debug):\n    \"\"\"\n    Draws all the scenario trigger positions. Each scenario is of a specific color\n    \"\"\"\n    final_message = \"\\n------------------------------\\n\"\n    for scenario_data in town_data:\n        # Get the desired scenario data\n        scenario_type = scenario_data[\"scenario_type\"]\n        if scenario_type not in scenarios:\n            continue\n\n        number = float(scenario_type[8:])\n        debug_loc_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number)\n        debug_str_height = carla.Location(z=DEBUG_HEIGHT_INTERVAL * number + 0.1)\n        color = SCENARIO_COLOR[scenario_type][0]\n        end_color= \"\\x1b[0m\"\n        true_color = \"\\x1b[38;2;\" + str(color.r) +\";\" + str(color.g) + \";\" + str(color.b) + \"m\"\n        final_message += \"{}{} is colored as {}{}\\n\".format(true_color, scenario_type, SCENARIO_COLOR[scenario_type][1], end_color)\n\n        scenario_list = scenario_data[\"available_event_configurations\"]\n        for i in range(len(scenario_list)):\n            # Get the individual scenario data\n            scenario_dict = scenario_list[i]\n            scenario_transform = get_scenario_transform(scenario_dict)\n            scenario_location = scenario_transform.location\n            world.debug.draw_point(\n                scenario_location + debug_loc_height, float(0.15), color)\n            world.debug.draw_string(\n                scenario_location + debug_str_height , str(i), False, carla.Color(0, 0, 0), 1000)\n\n            if debug:\n                spectator = world.get_spectator()\n                spectator.set_transform(carla.Transform(scenario_location + carla.Location(z=50),\n                                                        carla.Rotation(pitch=-90)))\n                input(\" Scenario [{}/{}] at (x={}, y={}, z={}, yaw={}). Press Enter to continue\".format(\n                    i, len(scenario_list) - 1,\n                    round(scenario_location.x, 1),\n                    round(scenario_location.y, 1),\n                    round(scenario_location.z, 1),\n                    round(scenario_transform.rotation.yaw, 1))\n                )\n\n        world.wait_for_tick()\n    final_message += \"------------------------------\\n\"\n\ndef main():\n    \"\"\"Used to help with the visualization of the scenario trigger points\"\"\"\n    # general parameters\n    parser = argparse.ArgumentParser(formatter_class=RawTextHelpFormatter,\n                                     description=\"Draw, validate or create Leaderboard scenarios. \"\n                                                 \"For multiple scenarios, separate them by spaces (example '1 3 6 9')\")\n    parser.add_argument('--host', default='localhost',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', default='2000',\n                        help='TCP port to listen to (default: 2000)')\n\n    # Path from which all scenarios will be taken\n    parser.add_argument('-f', '--file-path', default=\"../data/all_towns_traffic_scenarios_public.json\",\n                        help='path to the .json file containing the scenarios')\n\n    # Different tests. CHOOSE ONLY ONE.\n    parser.add_argument('--draw-scenarios', nargs='+',\n                        help='Draw the scenarios.')\n    parser.add_argument('--validate-scenarios', nargs='+',\n                        help='Checks whether or not a scenario is well positioned in lane')\n    parser.add_argument('--create-junction-scenarios', action='store_true',\n                        help='Creates scenarios 7 to 10 using scenario 4 as reference')\n\n    # Debug tool, to easily differentiate between scenarios\n    parser.add_argument('--debug', action='store_true',\n                        help='Scenarios are printed one by one, and additional information is given')\n\n    # Town loading arguments\n    parser.add_argument('--load-town',\n                        help='Loads a specific town (example \"Town01\")')\n    parser.add_argument('--reload-town', action='store_true',\n                        help='Reloads the town')\n    args = parser.parse_args()\n\n    if args.load_town and args.reload_town:\n        raise ValueError(\"'load_town' and 'reload' can't be active at the same time\")\n\n    try:\n        client = carla.Client(args.host, int(args.port))\n        client.set_timeout(20)\n        if args.load_town:\n            world = client.load_world(args.load_town)\n        elif args.reload_town:\n            world = client.reload_world()\n        else:\n            world = client.get_world()\n        tmap = world.get_map()\n\n        settings = world.get_settings()\n        settings.fixed_delta_seconds = None\n        settings.synchronous_mode = False\n        world.apply_settings(settings)\n\n        # Read the json file\n        data = fetch_dict(args.file_path)\n        town_name = world.get_map().name.split(\"/\")[-1]\n        town_data = data[\"available_scenarios\"][0][town_name]\n\n        if args.draw_scenarios:\n            scenarios = [\"Scenario\" + ar_sc for ar_sc in args.draw_scenarios]\n            draw_scenarios(world, town_data, scenarios, args.debug)\n        elif args.validate_scenarios:\n            scenarios = [\"Scenario\" + ar_sc for ar_sc in args.validate_scenarios]\n            validate_scenarios(world, town_data, tmap, scenarios, args.debug)\n        elif args.create_junction_scenarios:\n            scenarios = [\"Scenario4\"]\n            create_scenarios(world, town_data, tmap, scenarios, args.debug)\n\n    except KeyboardInterrupt:\n        pass\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/merge_statistics.py",
    "content": "import argparse\n\nfrom leaderboard.utils.checkpoint_tools import fetch_dict\nfrom leaderboard.utils.statistics_manager import StatisticsManager\n\n\ndef check_duplicates(route_ids):\n    \"\"\"Checks that all route ids are present only once in the files\"\"\"\n    for id in route_ids:\n        if route_ids.count(id) > 1:\n            raise ValueError(f\"Stopping. Found that the route {id} has more than one record\")\n\n\ndef check_missing_data(route_ids):\n    \"\"\"Checks that there is no missing data, by changing their route id to an integer\"\"\"\n    rep_num = 1\n    prev_rep_int = 0\n    prev_total_int = 0\n    prev_id = \"\"\n\n    for id in route_ids:\n        route_int = int(id.split('_')[1])\n        rep_int = int(id.split('_rep')[-1])\n\n        # Get the amount of repetitions. Done when a reset of the repetition number is found\n        if rep_int < prev_rep_int:\n            rep_num = prev_rep_int + 1\n\n        # Missing data will create a jump of 2 units\n        # (i.e if 'Route0_rep1' is missing, 'Route0_rep0' will be followed by 'Route0_rep2', which are two units)\n        total_int = route_int * rep_num + rep_int\n        if total_int - prev_total_int > 1: \n            raise ValueError(f\"Stopping. Missing some data as the ids jumped from {prev_id} to {id}\")\n\n        prev_rep_int = rep_int\n        prev_total_int = total_int\n        prev_id = id\n\n\ndef main():\n    \"\"\"\n    Utility script to merge two or more statistics into one.\n    While some checks are done, it is best to ensure that merging all files makes sense\n    \"\"\"\n    argparser = argparse.ArgumentParser()\n    argparser.add_argument('-f', '--file-paths', nargs=\"+\", required=True, help='path to all the files containing the partial results')\n    argparser.add_argument('-e', '--endpoint', required=True, help='path to the endpoint containing the joined results')\n    args = argparser.parse_args()\n\n    # Initialize the statistics manager\n    statistics_manager = StatisticsManager(args.endpoint, 0)\n\n    # Make sure that the data is correctly formed\n    sensors = []\n    route_ids = []\n    total_routes = 0\n    total_progress = 0\n\n    for file in args.file_paths:\n        data = fetch_dict(file)\n        if not data:\n            continue\n\n        route_ids.extend([x['route_id'] for x in data['_checkpoint']['records']])\n        total_routes += len(data['_checkpoint']['records'])\n        total_progress += data['_checkpoint']['progress'][1]\n\n        if data['sensors']:\n            if not sensors:\n                sensors = data['sensors']\n            elif data['sensors'] != sensors:\n                raise ValueError(\"Stopping. Found two files with different sensor configurations\")\n\n    route_ids.sort(key=lambda x: (\n        int(x.split('_')[1]),\n        int(x.split('_rep')[-1])\n    ))\n\n    global_statistics = total_progress != 0 and total_routes == total_progress\n\n    if global_statistics:\n        check_duplicates(route_ids)\n        check_missing_data(route_ids)\n\n    # All good, join the data and get the global results\n    for file in args.file_paths:\n        statistics_manager.add_file_records(file)\n\n    statistics_manager.sort_records()\n    statistics_manager.save_sensors(sensors)\n    statistics_manager.save_progress(total_routes, total_progress)\n    statistics_manager.save_entry_status('Started')\n    if global_statistics:\n        statistics_manager.compute_global_statistics()\n        statistics_manager.validate_and_write_statistics(True, False)\n    else:\n        statistics_manager.write_statistics()\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/pretty_print_json.py",
    "content": "# !/usr/bin/env python\n# Copyright (c) 2020 Intel Corporation.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCreate a human readable version of the scores provided by the leaderboard.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport argparse\nfrom argparse import RawTextHelpFormatter\nfrom dictor import dictor\nimport json\nfrom tabulate import tabulate\n\n\ndef prettify_json(args):\n    with open(args.file) as fd:\n        json_dict = json.load(fd)\n\n    if not json_dict:\n        print('[Error] The file [{}] could not be parsed.'.format(args.file))\n        return -1\n\n    progress = dictor(json_dict, '_checkpoint.progress')\n    records_table = dictor(json_dict, '_checkpoint.records')\n    sensors = dictor(json_dict, 'sensors')\n    labels_scores = dictor(json_dict, 'labels')\n    scores = dictor(json_dict, 'values')\n\n    # compose output\n    output = \"\"\n\n    if progress:\n        output += '* {}% ({}/{}) routes completed\\n'.format(100.0*progress[0]/float(progress[1]),\n                                                            progress[0],\n                                                            progress[1])\n    if sensors:\n        output += '* The agent used the following sensors: {}\\n\\n'.format(', '.join(sensors))\n\n    if scores and labels_scores:\n        metrics = list(zip(*[labels_scores[0:3], scores[0:3]]))\n        infractions = list(zip(*[labels_scores[3:], scores[3:]]))\n\n        output += '=== Global average metrics: ===\\n'\n        output += tabulate(metrics, tablefmt=args.format)\n        output += '\\n\\n'\n        output += '=== Total infractions: ===\\n'\n        output += tabulate(infractions, tablefmt=args.format)\n        output += '\\n\\n'\n\n    if records_table:\n        header = ['Metric', 'Value', 'Additional information']\n        list_statistics = [header]\n        total_duration_game = 0\n        total_duration_system = 0\n        total_route_length = 0\n        for route in records_table:\n            route_completed_kms = 0.01 * route['scores']['Route completion'] * route['meta']['Route length'] / 1000.0\n            metrics_route = [[key, '{:.3f}'.format(values), ''] for key, values in route['scores'].items()]\n            infractions_route = [[key, '{:.3f} ({} occurrences)'.format(len(values)/route_completed_kms, len(values)),\n                                 '\\n'.join(values)] for key, values in route['infractions'].items()]\n\n            times = [['Game duration', '{:.3f}'.format(route['meta']['Game duration']), 'seconds'],\n                     ['System duration', '{:.3f}'.format(route['meta']['System duration']), 'seconds']]\n\n            route_completed_length = [ ['distance driven', '{:.3f}'.format(route_completed_kms), 'Km']]\n\n            total_duration_game += route['meta']['Game duration']\n            total_duration_system += route['meta']['System duration']\n            total_route_length += route_completed_kms\n\n            list_statistics.extend([['{}'.format(route['route_id']), '', '']])\n            list_statistics.extend([*metrics_route, *infractions_route, *times, *route_completed_length])\n            list_statistics.extend([['', '', '']])\n\n        list_statistics.extend([['Total game duration', '{:.3f}'.format(total_duration_game), 'seconds']])\n        list_statistics.extend([['Total system duration', '{:.3f}'.format(total_duration_system), 'seconds']])\n        list_statistics.extend([['Total distance driven', '{:.3f}'.format(total_route_length), 'Km']])\n\n        output += '==== Per-route analysis: ===\\n'.format()\n        output += tabulate(list_statistics, tablefmt=args.format)\n\n    if args.output:\n        with open(args.output, 'w') as fd:\n            fd.write(output)\n    else:\n        print(output)\n\n    return 0\n\n\ndef main():\n    description = 'Create a human readable version of the scores provided by the leaderboard.\\n'\n    # general parameters\n    parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter)\n    parser.add_argument('-f', '--file', help='JSON file containing the results of the leaderboard', required=True)\n    parser.add_argument('--format', default='fancy_grid',\n                        help='Format in which the table will be printed, e.g.: fancy_grid, latex, github, html, jira')\n    parser.add_argument('-o', '--output', help='Output file to print the results into')\n    arguments = parser.parse_args()\n\n    return prettify_json(arguments)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/route_creator.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport sys\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\n\nLIFE_TIME = 10000\n\ndef draw_point(world, wp, option):\n    if option == RoadOption.LEFT:  # Yellow\n        color = carla.Color(128, 128, 0)\n    elif option == RoadOption.RIGHT:  # Cyan\n        color = carla.Color(0, 128, 128)\n    elif option == RoadOption.CHANGELANELEFT:  # Orange\n        color = carla.Color(128, 32, 0)\n    elif option == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n        color = carla.Color(0, 32, 128)\n    elif option == RoadOption.STRAIGHT:  # Gray\n        color = carla.Color(64, 64, 64)\n    else:  # LANEFOLLOW\n        color = carla.Color(0, 128, 0)  # Green\n\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.05, color=color, life_time=LIFE_TIME)\n\ndef draw_keypoint(world, location):\n    world.debug.draw_point(location + carla.Location(z=0.2), size=0.1, color=carla.Color(128, 0, 128), life_time=LIFE_TIME)\n    string = \"(\" + str(round(location.x, 1)) + \", \" + str(round(location.y, 1)) + \", \" + str(round(location.z, 1)) + \")\"\n    world.debug.draw_string(location + carla.Location(z=0.5), string, True, color=carla.Color(0, 0 , 128), life_time=LIFE_TIME)\n\ndef get_saved_data(filename, route_id, world, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    distance = 0\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    found_id = False\n\n    points = []\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        found_id = True\n\n        for position in route.find('waypoints').iter('position'):\n            points.append(convert_elem_to_location(position))\n\n        if points:\n            for i in range(len(points) - 1):\n                waypoint = points[i]\n                waypoint_next = points[i + 1]\n                interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n                for j in range(len(interpolated_trace) - 1):\n                    wp, option = interpolated_trace[j]\n                    wp_next = interpolated_trace[j + 1][0]\n                    draw_point(world, wp, option)\n                    distance += wp.transform.location.distance(wp_next.transform.location)\n\n                draw_keypoint(world, waypoint)\n            draw_keypoint(world, points[-1])\n\n    if not found_id:\n        print(f\"\\033[91mCouldn't find the id '{route_id}' in the given routes file\\033[0m\")\n\n\n    return points, distance\n\ndef add_data(points, tmap, world, spectator, grp):\n    waypoint = tmap.get_waypoint(spectator.get_location())\n    draw_keypoint(world, waypoint.transform.location)\n    added_distance = 0\n    if points:\n        interpolated_trace = grp.trace_route(points[-1], waypoint.transform.location)\n        for j in range(len(interpolated_trace) - 1):\n            wp, option = interpolated_trace[j]\n            wp_next = interpolated_trace[j + 1][0]\n            draw_point(world, wp, option)\n            added_distance += wp.transform.location.distance(wp_next.transform.location)\n    points.append(waypoint.transform.location)\n    return added_distance\n\ndef save_data(filename, route_id, points):\n    def indent(elem, spaces=3, level=0):\n        i = \"\\n\" + level * spaces * \" \"\n        j = \"\\n\" + (level + 1) * spaces * \" \"\n        if len(elem):\n            if not elem.text or not elem.text.strip():\n                elem.text = j\n            if not elem.tail or not elem.tail.strip():\n                elem.tail = i\n            for subelem in elem:\n                indent(subelem, spaces, level+1)\n        else:\n            if level and (not elem.tail or not elem.tail.strip()):\n                elem.tail = i\n        return elem\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    found_id = False\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n        \n        found_id = True\n\n        waypoints = route.find('waypoints')\n        for position in waypoints.iter('position'):\n            waypoints.remove(position)\n\n        for point in points:\n            new_point = etree.SubElement(waypoints, \"position\")\n            new_point.set(\"x\", str(round(point.x, 1)))\n            new_point.set(\"y\", str(round(point.y, 1)))\n            new_point.set(\"z\", str(round(point.z, 1)))\n        break\n\n    if not found_id:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\n    # Prettify the xml. A bit of automatic indentation, a bit of manual one\n    spaces = 3\n    indent(root, spaces)\n    tree.write(filename)\n\n    with open(filename, 'r') as f:\n        data = f.read()\n    temp = data.replace(\"   </\", \"</\")  # The 'indent' function fails for these cases\n\n    weather_spaces = spaces*4*\" \"\n    temp = temp.replace(\" cloudiness\", \"\\n\" + weather_spaces + \"cloudiness\")\n    temp = temp.replace(\" wind_intensity\", \"\\n\" + weather_spaces + \"wind_intensity\")\n    temp = temp.replace(\" fog_density\", \"\\n\" + weather_spaces + \"fog_density\")\n    new_data = temp.replace(\" mie_scattering_scale\", \"\\n\" + weather_spaces + \"mie_scattering_scale\")\n\n    with open(filename, 'w') as f:\n        f.write(new_data)\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, nargs=\"+\", help='File at which to place the scenarios')\n    args = argparser.parse_args()\n\n    # Get the client\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n\n    # # Get the rest\n    world = client.get_world()\n    spectator = world.get_spectator()\n    tmap = world.get_map()\n    grp = GlobalRoutePlanner(tmap, 2.0)\n    points = []\n\n    file_path = args.file[0]\n    route_id = args.file[1] if len(args.file) > 1 else 0\n\n    # Get the data already at the file\n    points, distance = get_saved_data(file_path, route_id, world, grp)\n\n    print(\" ------------------------------------------------------------ \")\n    print(\" |               Use Ctrl+C to stop the script              | \")\n    print(\" |          Any unsaved route points will be lost           | \")\n    print(\" ------------------------------------------------------------ \")\n\n    print(f\"Total accumulated distance is {round(distance, 1)}\")\n\n    try:\n        while True:\n            # Get the scenario type\n            action = input(f\"\\033[1m> Specify the next action ('Add' / 'Save') \\033[0m\")\n            if action == \"Add\":\n                print(\"Adding a new point\")\n                added_distance = add_data(points, tmap, world, spectator, grp)\n                distance += added_distance\n                print(f\"Total accumulated distance is {round(distance, 1)}\")\n            elif action == \"Save\":\n                print(\"Saving data to the xml file\")\n                save_data(file_path, route_id, points)\n            else:\n                print(f\"\\033[1m\\033[93mUnknown action '{action}'. Try again\\033[0m\")\n\n    except KeyboardInterrupt as e:\n        print(\"\\n Detected a keyboard interruption, stopping the script. \")\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/route_displayer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport sys\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\nfrom numpy import random\n\nLIFE_TIME = 10000\n\nCOLORS = [\n    carla.Color(255, 255, 255),\n    carla.Color(255, 0, 0),\n    carla.Color(0, 255, 0),\n    carla.Color(0, 0, 255),\n    carla.Color(255, 255, 0),\n    carla.Color(255, 0, 255),\n    carla.Color(0, 255, 255),\n\n    carla.Color(192, 192, 192),\n    carla.Color(192, 0, 0),\n    carla.Color(0, 192, 0),\n    carla.Color(0, 0, 192),\n    carla.Color(192, 192, 0),\n    carla.Color(192, 0, 192),\n    carla.Color(0, 192, 192),\n\n    carla.Color(128, 128, 128),\n    carla.Color(128, 0, 0),\n    carla.Color(0, 128, 0),\n    carla.Color(0, 0, 128),\n    carla.Color(128, 128, 0),\n    carla.Color(128, 0, 128),\n    carla.Color(0, 128, 128),\n\n    carla.Color(64, 64, 64),\n    carla.Color(64, 0, 0),\n    carla.Color(0, 64, 0),\n    carla.Color(0, 0, 64),\n    carla.Color(64, 64, 0),\n    carla.Color(64, 0, 64),\n    carla.Color(0, 64, 64),\n\n    carla.Color(0, 0, 0),\n]\n\n\ndef draw_point(world, wp, color):\n    world.debug.draw_point( wp.transform.location + carla.Location(z=0.2), size=0.05, color=color, life_time=LIFE_TIME)\n\n\ndef draw_keypoint(world, location):\n    world.debug.draw_point(location + carla.Location(z=0.2), size=0.1, color=carla.Color(128, 0, 128), life_time=LIFE_TIME)\n    string = \"(\" + str(round(location.x, 1)) + \", \" + str(round(location.y, 1)) + \", \" + str(round(location.z, 1)) + \")\"\n    world.debug.draw_string(location + carla.Location(z=0.5), string, True, color=carla.Color(0, 0 , 128), life_time=LIFE_TIME)\n\n\ndef show_all_routes(filename, show_scenarios, world, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    def get_random_color(rng):\n        \"\"\"Gets a random CARLA RGB color\"\"\"\n        r = rng.randint(0, 256)\n        g = rng.randint(0, 256)\n        b = rng.randint(0, 256)\n        return carla.Color(r, g, b)\n\n    rng = random.RandomState(2002)\n    colors = list(COLORS)\n    rng.shuffle(colors)\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n    for i, route in enumerate(root.iter(\"route\")):\n        prev_point = None\n        color = get_random_color(rng)\n        # color = colors[i]\n\n        for position in route.find('waypoints').iter('position'):\n            point = convert_elem_to_location(position)\n            # draw_keypoint(world, point)\n\n            if prev_point:\n                interpolated_trace = grp.trace_route(prev_point, point)\n                for wp, _ in interpolated_trace:\n                    draw_point(world, wp, color)\n            else:\n                world.debug.draw_string(point + carla.Location(z=1), route.attrib['id'], color=color, life_time=10000)\n            prev_point = point\n\n        if show_scenarios:\n            show_saved_scenarios(route, world)\n\n\ndef show_route(filename, route_id, show_keypoints, show_scenarios, world, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n    def get_color(option):\n        if option == RoadOption.LEFT:  # Yellow\n            return carla.Color(128, 128, 0)\n        elif option == RoadOption.RIGHT:  # Cyan\n            return carla.Color(0, 128, 128)\n        elif option == RoadOption.CHANGELANELEFT:  # Orange\n            return carla.Color(128, 32, 0)\n        elif option == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n            return carla.Color(0, 32, 128)\n        elif option == RoadOption.STRAIGHT:  # Gray\n            return carla.Color(64, 64, 64)\n        else:  # LANEFOLLOW\n            return carla.Color(0, 128, 0)  # Green\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        points = []\n        for position in route.find('waypoints').iter('position'):\n            points.append(convert_elem_to_location(position))\n\n        if points:\n            for i in range(len(points) - 1):\n                waypoint = points[i]\n                waypoint_next = points[i + 1]\n                interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n                for j in range(len(interpolated_trace) - 1):\n                    wp, option = interpolated_trace[j]\n                    draw_point(world, wp, get_color(option))\n\n                if show_keypoints:\n                    draw_keypoint(world, waypoint)\n            if show_keypoints:\n                draw_keypoint(world, points[-1])\n\n        if show_scenarios:\n            show_saved_scenarios(route, world)\n\n        # spec_transform = carla.Transform(points[0] + carla.Location(z=100), carla.Rotation(pitch=-90))\n        # world.get_spectator().set_transform(spec_transform)\n\ndef show_saved_scenarios(route, world):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    for scenario in route.find('scenarios').iter('scenario'):\n        name = scenario.attrib.get('name')\n        trigger_location = convert_elem_to_location(scenario.find('trigger_point'))\n        world.debug.draw_point(trigger_location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n        world.debug.draw_string(trigger_location + carla.Location(z=0.5), name, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, help='File at which to place the scenarios')\n    argparser.add_argument('-sr', '--show-route', help='Shows the given route')\n    argparser.add_argument('-sa', '--show-all', action='store_true', help='Shows all the routes')\n    argparser.add_argument('-sk', '--show-keypoints', action='store_true', help='Shows the keypoints that define the route')\n    argparser.add_argument('-ss', '--show-scenarios', action='store_true', help='Shows the scemarios part of the route')\n    args = argparser.parse_args()\n\n    # Get the client\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n\n    # Get the rest\n    world = client.get_world()\n    tmap = world.get_map()\n    grp = GlobalRoutePlanner(tmap, 2.0)\n\n    if not args.show_route and not args.show_all:\n        print(\"No instructions to show were given, stopping the script\")\n\n    # Show all routes\n    if args.show_all:\n        show_all_routes(args.file, args.show_scenarios, world, grp)\n\n    # Show one route\n    if args.show_route:\n        show_route(args.file, args.show_route, args.show_keypoints, args.show_scenarios, world, grp)\n\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/route_summarizer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nimport os\nimport sys\nfrom lxml import etree\nfrom tabulate import tabulate\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nMAPS_LOCATIONS = {\n    \"Town01\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01.xodr\",\n    \"Town01_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01_Opt.xodr\",\n    \"Town02\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02.xodr\",\n    \"Town02_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02_Opt.xodr\",\n    \"Town03\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town03.xodr\",\n    \"Town03_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town04\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04.xodr\",\n    \"Town04_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town05\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05.xodr\",\n    \"Town05_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05_Opt.xodr\",\n    \"Town06\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06.xodr\",\n    \"Town06_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06_Opt.xodr\",\n    \"Town07\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07.xodr\",\n    \"Town07_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07_Opt.xodr\",\n    \"Town10HD\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD.xodr\",\n    \"Town10HD_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD_Opt.xodr\",\n    \"Town11\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town11/OpenDrive/Town11.xodr\",\n    \"Town12\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town12/OpenDrive/Town12.xodr\",\n    \"Town13\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town13/OpenDrive/Town13.xodr\",\n}\n\ndef convert_elem_to_location(elem):\n    \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n    return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, help=\"Route's file path\")\n    argparser.add_argument('--endpoint', default=\"\", help='Output file')\n    argparser.add_argument('--show', action=\"store_true\", help='Print the results on stdout')\n    args = argparser.parse_args()\n\n    if not args.endpoint and not args.show:\n        print(\"No output method was selected. Use either '--endpoint', or '--show' to get the route results\")\n        sys.exit(0)\n\n    root = etree.parse(args.file).getroot()\n    total_distance = 0\n    total_num_scenarios = 0\n    total_scenarios = {}\n\n    statistics = [['Route id', 'Distance (m)', 'Scenarios (type)', 'Scenarios (nº)', 'Avg dist between scenarios']]\n\n    prev_town = None\n\n    for route in root.iter(\"route\"):\n\n        route_id = route.attrib['id']\n        route_town = route.attrib['town']\n\n        if route_town not in MAPS_LOCATIONS:\n            print(f\"Ignoring route '{route_id}' as it uses an unknown map '{route_town}\")\n            continue\n        elif route_town != prev_town:\n            full_name = os.environ[\"CARLA_ROOT\"] + \"/\" + MAPS_LOCATIONS[route_town]\n            with open(full_name, 'r') as f:\n                map_contents = f.read()\n            tmap = carla.Map(route_town, map_contents)\n            grp = GlobalRoutePlanner(tmap, 2.0)\n\n        print(f\"Parsing route '{route_id}'\")\n\n        # Get the route distance\n        route_distance = 0\n\n        route_points = []\n        for position in route.find('waypoints').iter('position'):\n            route_points.append(convert_elem_to_location(position))\n\n        for i in range(len(route_points) - 1):\n            waypoint = route_points[i]\n            waypoint_next = route_points[i + 1]\n            interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n            for j in range(len(interpolated_trace) - 1):\n                wp = interpolated_trace[j][0]\n                wp_next = interpolated_trace[j + 1][0]\n                route_distance += wp.transform.location.distance(wp_next.transform.location)\n\n        # Get the route scenarios\n        route_scenarios = {}\n\n        for scenario in route.find('scenarios').iter('scenario'):\n            scenario_type = scenario.attrib.get('type')\n            if not scenario_type in route_scenarios:\n                route_scenarios[scenario_type] = 0\n\n            route_scenarios[scenario_type] += 1\n\n        num_scenarios = sum([x for x in route_scenarios.values()])\n        dist_scenarios = route_distance / num_scenarios\n\n        print_scenarios = \"\"\n        route_scenario_items = sorted(list(route_scenarios.items()), key=lambda x: x[0])\n        for s_type, s_num in route_scenario_items:\n            print_scenarios += f\"{s_type}: {s_num}\\n\"\n\n        statistics += [[\n            route_id,\n            round(route_distance, 1),\n            print_scenarios,\n            sum([x for x in route_scenarios.values()]),\n            round(dist_scenarios, 1)\n        ]]\n\n        # Get the total amounts\n        total_distance += route_distance\n        total_num_scenarios += num_scenarios\n\n        for s_type, s_num in route_scenario_items:\n            if s_type not in total_scenarios:\n                total_scenarios[s_type] = 0\n            total_scenarios[s_type] += s_num\n\n        prev_town = route_town\n\n    print_total_scenarios = \"\"\n    total_scenario_items = sorted(list(total_scenarios.items()), key=lambda x: x[0])\n    for s_type, s_num in total_scenario_items:\n        print_total_scenarios += f\"{s_type}: {s_num}\\n\"\n\n    statistics += [[\n        \"Total\",\n        round(total_distance, 1),\n        print_total_scenarios,\n        total_num_scenarios,\n        round(total_distance / total_num_scenarios, 1)\n    ]]\n\n    output = tabulate(statistics, tablefmt='fancy_grid')\n    if args.show:\n        print(output)\n\n    if args.endpoint:\n        with open(args.endpoint, 'w', encoding='utf-8') as fd:\n            fd.write(output)\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation.sh",
    "content": "#!/bin/bash\n# Must set CARLA_ROOT\nexport CARLA_ROOT=/data/songziying/workspace/carla\nexport CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla\nexport PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-0.9.15-py3.7-linux-x86_64.egg\nexport PYTHONPATH=$PYTHONPATH:leaderboard\nexport PYTHONPATH=$PYTHONPATH:leaderboard/team_code\nexport PYTHONPATH=$PYTHONPATH:scenario_runner\nexport SCENARIO_RUNNER_ROOT=scenario_runner\n\nexport LEADERBOARD_ROOT=leaderboard\nexport CHALLENGE_TRACK_CODENAME=SENSORS\nexport PORT=$1\nexport TM_PORT=$2\nexport DEBUG_CHALLENGE=0\nexport REPETITIONS=1 # multiple evaluation runs\nexport RESUME=True\nexport IS_BENCH2DRIVE==$3\nexport PLANNER_TYPE=$9\nexport GPU_RANK=${10}\n\n# TCP evaluation\nexport ROUTES=$4\nexport TEAM_AGENT=$5\nexport TEAM_CONFIG=$6\nexport CHECKPOINT_ENDPOINT=$7\nexport SAVE_PATH=$8\n\nCUDA_VISIBLE_DEVICES=${GPU_RANK} python ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \\\n--routes=${ROUTES} \\\n--repetitions=${REPETITIONS} \\\n--track=${CHALLENGE_TRACK_CODENAME} \\\n--checkpoint=${CHECKPOINT_ENDPOINT} \\\n--agent=${TEAM_AGENT} \\\n--agent-config=${TEAM_CONFIG} \\\n--debug=${DEBUG_CHALLENGE} \\\n--record=${RECORD_PATH} \\\n--resume=${RESUME} \\\n--port=${PORT} \\\n--traffic-manager-port=${TM_PORT} \\\n--gpu-rank=${GPU_RANK} \\"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation_debug.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/vad_b2d_agent.py\nTEAM_CONFIG=/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py+/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/work_dirs/MomAD_base_e2e_b2d/epoch_5.pth\n# /data/songziying/workspace/Bench2Drive/Bench2DriveZoo/ckpts/vad_b2d_base.pth\nBASE_CHECKPOINT_ENDPOINT=eval\nSAVE_PATH=./eval_v1/\nPLANNER_TYPE=only_traj\n\nGPU_RANK=3\nPORT=$BASE_PORT\nTM_PORT=$BASE_TM_PORT\nROUTES=\"${BASE_ROUTES}.xml\"\nCHECKPOINT_ENDPOINT=\"${BASE_CHECKPOINT_ENDPOINT}.json\"\nbash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation_multi_admlp.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/admlp_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=YOUR_CKPT_PATH/admlp_b2d.ckpt\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=traj\nALGO=admlp\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=12\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 4*A6000, 3 task per gpu\nGPU_RANK_LIST=(0 0 0 1 1 1 2 2 2 3 3 3)\nTASK_LIST=(0 1 2 3 4 5 6 7 8 9 10 11)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation_multi_tcp.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/tcp_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=YOUR_CKPT_PATH/tcp_b2d.ckpt\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=merge_ctrl_traj # You can choose from only_ctrl, only_traj and merge_ctrl_traj\nALGO=tcp\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=12\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 4*A6000, 3 task per gpu\nGPU_RANK_LIST=(0 0 0 1 1 1 2 2 2 3 3 3)\nTASK_LIST=(0 1 2 3 4 5 6 7 8 9 10 11)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation_multi_uniad.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/uniad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/base_e2e_b2d.py+YOUR_CKPT_PATH/uniad_base_b2d.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=traj\nALGO=uniad\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation_multi_uniad_tiny.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/uniad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=Bench2DriveZoo/adzoo/uniad/configs/stage2_e2e/tiny_e2e_b2d.py+YOUR_CKPT_PATH/uniad_tiny_b2d.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220\nPLANNER_TYPE=traj\nALGO=uniad_tiny\nSAVE_PATH=./eval_bench2drive220_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evaluation_multi_vad.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/vad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py+/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/work_dirs/MomAD_base_e2e_b2d/epoch_5.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220_momad\nPLANNER_TYPE=traj\nALGO=vad\nSAVE_PATH=./eval_bench2drive220_momad_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(0 1 2 3 4 5 6 7)\nTASK_LIST=(0 1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/run_evalutaion_multi_sparsedrive.sh",
    "content": "#!/bin/bash\nBASE_PORT=30000\nBASE_TM_PORT=50000\nIS_BENCH2DRIVE=True\nBASE_ROUTES=leaderboard/data/bench2drive220\nTEAM_AGENT=team_code/vad_b2d_agent.py\n# Must set YOUR_CKPT_PATH\nTEAM_CONFIG=/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py+/data/songziying/workspace/Bench2Drive/Bench2DriveZoo/work_dirs/MomAD_base_e2e_b2d/epoch_5.pth\nBASE_CHECKPOINT_ENDPOINT=eval_bench2drive220_momad\nPLANNER_TYPE=traj\nALGO=vad\nSAVE_PATH=./eval_bench2drive220_momad_${ALGO}_${PLANNER_TYPE}\n\nif [ ! -d \"${ALGO}_b2d_${PLANNER_TYPE}\" ]; then\n    mkdir ${ALGO}_b2d_${PLANNER_TYPE}\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Directory ${ALGO}_b2d_${PLANNER_TYPE} already exists. \\033[0m\"\nfi\n\n# Check if the split_xml script needs to be executed\nif [ ! -f \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\" ]; then\n    echo -e \"****************************\\033[33m Attention \\033[0m ****************************\"\n    echo -e \"\\033[33m Running split_xml.py \\033[0m\"\n    TASK_NUM=8 # 8*H100, 1 task per gpu\n    python tools/split_xml.py $BASE_ROUTES $TASK_NUM $ALGO $PLANNER_TYPE\n    touch \"${BASE_ROUTES}_${ALGO}_${PLANNER_TYPE}_split_done.flag\"\n    echo -e \"\\033[32m Splitting complete. Flag file created. \\033[0m\"\nelse\n    echo -e \"\\033[32m Splitting already done. \\033[0m\"\nfi\n\necho -e \"**************\\033[36m Please Manually adjust GPU or TASK_ID \\033[0m **************\"\n# Example, 8*H100, 1 task per gpu\nGPU_RANK_LIST=(1 2 3 4 5 6 7)\nTASK_LIST=(1 2 3 4 5 6 7)\necho -e \"\\033[32m GPU_RANK_LIST: $GPU_RANK_LIST \\033[0m\"\necho -e \"\\033[32m TASK_LIST: $TASK_LIST \\033[0m\"\necho -e \"***********************************************************************************\"\n\nlength=${#GPU_RANK_LIST[@]}\nfor ((i=0; i<$length; i++ )); do\n    PORT=$((BASE_PORT + i * 150))\n    TM_PORT=$((BASE_TM_PORT + i * 150))\n    ROUTES=\"${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.xml\"\n    CHECKPOINT_ENDPOINT=\"${ALGO}_b2d_${PLANNER_TYPE}/${BASE_CHECKPOINT_ENDPOINT}_${TASK_LIST[$i]}.json\"\n    GPU_RANK=${GPU_RANK_LIST[$i]}\n    echo -e \"\\033[32m ALGO: $ALGO \\033[0m\"\n    echo -e \"\\033[32m PLANNER_TYPE: $PLANNER_TYPE \\033[0m\"\n    echo -e \"\\033[32m TASK_ID: $i \\033[0m\"\n    echo -e \"\\033[32m PORT: $PORT \\033[0m\"\n    echo -e \"\\033[32m TM_PORT: $TM_PORT \\033[0m\"\n    echo -e \"\\033[32m CHECKPOINT_ENDPOINT: $CHECKPOINT_ENDPOINT \\033[0m\"\n    echo -e \"\\033[32m GPU_RANK: $GPU_RANK \\033[0m\"\n    echo -e \"\\033[32m bash leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK \\033[0m\"\n    echo -e \"***********************************************************************************\"\n    bash -e leaderboard/scripts/run_evaluation.sh $PORT $TM_PORT $IS_BENCH2DRIVE $ROUTES $TEAM_AGENT $TEAM_CONFIG $CHECKPOINT_ENDPOINT $SAVE_PATH $PLANNER_TYPE $GPU_RANK 2>&1 > ${BASE_ROUTES}_${TASK_LIST[$i]}_${ALGO}_${PLANNER_TYPE}.log &\n    sleep 5\ndone\nwait"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/scenario_creator.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport sys\n\nimport carla\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nLIFE_TIME = 10000\n\nSCENARIO_TYPES ={\n\n    # Junction scenarios\n    \"SignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"SignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleRunningRedLight\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"NonSignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"NonSignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleTakingPriority\": [\n        [\"direction\", \"choice\"],\n    ],\n\n    # Crossing actors\n    \"DynamicObjectCrossing\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"blocker_model\", \"value\"],\n        [\"crossing_angle\", \"value\"]\n    ],\n    \"ParkingCrossingPedestrian\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n        [\"crossing_angle\", \"value\"],\n    ],\n    \"PedestrianCrossing\": [\n    ],\n    \"VehicleTurningRoute\": [\n    ],\n    \"VehicleTurningRoutePedestrian\": [\n    ],\n    \"BlockedIntersection\": [\n    ],\n\n    # Actor flows\n    \"EnterActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"EnterActorFlowV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanAdvancedActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"HighwayExit\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTraffic\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTrafficV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"CrossingBicycleFlow\": [\n        [\"start_actor_flow\", \"location bicycle\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n\n    # Route obstacles\n    \"ConstructionObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ConstructionObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"Accident\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"AccidentTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"ParkedObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ParkedObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"VehicleOpensDoorTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"HazardAtSideLane\": [\n        [\"distance\", \"value\"],\n        [\"speed\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"HazardAtSideLaneTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"InvadingTurn\": [\n        [\"distance\", \"value\"],\n        [\"offset\", \"value\"],\n    ],\n\n    # Cut ins\n    \"HighwayCutIn\": [\n        [\"other_actor_location\", \"location driving\"],\n    ],\n    \"ParkingCutIn\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"StaticCutIn\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n    ],\n\n    # Others\n    \"ControlLoss\": [\n    ],\n    \"HardBreakRoute\": [\n    ],\n    \"ParkingExit\": [\n        [\"direction\", \"choice\"],\n        [\"front_vehicle_distance\", \"value\"],\n        [\"behind_vehicle_distance\", \"value\"],\n    ],\n    \"YieldToEmergencyVehicle\": [\n        [\"distance\", \"value\"],\n    ],\n\n    # Special ones\n    \"BackgroundActivityParametrizer\": [\n        [\"num_front_vehicles\", \"value\"],\n        [\"num_back_vehicles\", \"value\"],\n        [\"road_spawn_dist\", \"value\"],\n        [\"opposite_source_dist\", \"value\"],\n        [\"opposite_max_actors\", \"value\"],\n        [\"opposite_spawn_dist\", \"value\"],\n        [\"opposite_active\", \"bool\"],\n        [\"junction_source_dist\", \"value\"],\n        [\"junction_max_actors\", \"value\"],\n        [\"junction_spawn_dist\", \"value\"],\n        [\"junction_source_perc\", \"value\"],\n    ],\n    \"PriorityAtJunction\": [\n    ],\n}\n\ndef show_saved_scenarios(filename, route_id, world):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    found_id = False\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        found_id = True\n\n        for scenario in route.find('scenarios').iter('scenario'):\n            name = scenario.attrib.get('name')\n            trigger_location = convert_elem_to_location(scenario.find('trigger_point'))\n            world.debug.draw_point(trigger_location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n            world.debug.draw_string(trigger_location + carla.Location(z=0.5), name, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n\n    if not found_id:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\ndef get_scenario_type(tmap, world, spectator):\n    while True:\n        scen_type = input(\"\\033[1m> Specify the scenario type \\033[0m\")\n        if scen_type not in list(SCENARIO_TYPES):\n            print(f\"\\033[1m\\033[93mScenario type '{scen_type}' doesn't match any of the know scenarios\\033[0m\")\n        else:\n            break\n\n    wp = tmap.get_waypoint(spectator.get_location())\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n    world.debug.draw_string(wp.transform.location + carla.Location(z=0.5), scen_type, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n    trigger_point = (\n        str(round(wp.transform.location.x, 1)),\n        str(round(wp.transform.location.y, 1)),\n        str(round(wp.transform.location.z, 1)),\n        str(round(wp.transform.rotation.yaw, 1))\n    )\n    return scen_type, trigger_point\n\ndef get_attributes_data(scen_type, trigger_point, tmap, world, spectator):\n    attribute_list = SCENARIO_TYPES[scen_type]\n    scenario_attributes = [['trigger_point', 'transform', trigger_point]]\n    for attribute in attribute_list:\n        a_name, a_type = attribute\n        if a_type == 'transform':\n            a_data = get_transform_data(a_name, scen_type, tmap, world, spectator)\n        elif 'location' in a_type:\n            a_data = get_location_data(a_name, scen_type, tmap, world, spectator, a_type)\n        elif a_type in ('value', 'choice', 'bool'):\n            a_data = get_value_data(a_name)\n        elif a_type == 'interval':\n            a_data = get_interval_data(a_name)\n        else:\n            raise ValueError(\"Unknown attribute type\")\n\n        if a_data:  # Ignore the attributes that use default values\n            scenario_attributes.append([a_name, a_type, a_data])\n    return scenario_attributes\n\ndef get_transform_data(a_name, scen_type, tmap, world, spectator):\n    input(f\"\\033[1m> Enter the '{a_name}' transform \\033[0m\")\n    wp = tmap.get_waypoint(spectator.get_location())\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n    world.debug.draw_string(wp.transform.location + carla.Location(z=0.5), scen_type, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n    return (\n        str(round(wp.transform.location.x, 1)),\n        str(round(wp.transform.location.y, 1)),\n        str(round(wp.transform.location.z, 1)),\n        str(round(wp.transform.rotation.yaw, 1))\n    )\n\ndef get_location_data(a_name, scen_type, tmap, world, spectator, a_type):\n    input(f\"\\033[1m> Enter the '{a_name}' location \\033[0m\")\n    if \"sidewalk\" in a_type:\n        lane_type = carla.LaneType.Sidewalk\n    elif \"bicycle\" in a_type:\n        lane_type = carla.LaneType.Biking\n    elif \"driving\" in a_type:\n        lane_type = carla.LaneType.Driving\n    else:\n        lane_type = carla.LaneType.Driving\n\n    wp = tmap.get_waypoint(spectator.get_location(), lane_type=lane_type)\n    world.debug.draw_point(wp.transform.location + carla.Location(z=0.2), size=0.1, color=carla.Color(125, 0, 0))\n    world.debug.draw_string(wp.transform.location + carla.Location(z=0.5), scen_type, True, color=carla.Color(0, 0 , 125), life_time=LIFE_TIME)\n\n    loc =  (\n            str(round(wp.transform.location.x, 1)),\n            str(round(wp.transform.location.y, 1)),\n            str(round(wp.transform.location.z, 1))\n        )\n\n    if \"probability\" in a_type:\n        p = input(f\"\\033[1m> Enter the '{a_name}' probability \\033[0m\")\n        loc += (p,)\n    return loc\n\n\ndef get_value_data(a_name):\n    value = input(f\"\\033[1m> Specify the '{a_name}' value \\033[0m\")\n    return value\n\ndef get_interval_data(a_name):\n    lower_value = input(f\"\\033[1m> Specify the '{a_name}' from \\033[0m\")\n    upper_value = input(f\"\\033[1m> Specify the '{a_name}' from \\033[0m{lower_value}\\033[1m to \\033[0m\")\n    return (lower_value, upper_value)\n\ndef print_scenario_data(scen_type, scen_attributes):\n    print_dict = f\"\\n   scenario_type: {scen_type}\\n\"\n    for print_attribute in scen_attributes:\n        print_dict += f\"   {print_attribute[0]}: {print_attribute[2]}\\n\"\n    print(print_dict)\n\ndef save_scenario(filename, route_id, scenario_type, scenario_attributes):\n\n    while True:\n        save = input(\"\\033[1m> Save the scenario? ('Yes' / 'No'): \\033[0m\")\n        if save == \"Yes\":\n            break\n        elif save == \"No\":\n            return\n        else:\n            print(f\"\\033[1m\\033[93mThis is a 'Yes' or 'No' question, try again.\\033[0m\")\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    scenario_names = {}\n    for scen_type in list(SCENARIO_TYPES):\n        scenario_names[scen_type] = 1\n\n    found_id = False\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        found_id = True\n\n        scenarios = route.find('scenarios')\n        for scenario in scenarios.iter('scenario'):\n            scen_type = scenario.attrib['type']\n            scenario_names[scen_type] += 1\n\n        number = scenario_names[scenario_type]\n        new_scenario = etree.SubElement(scenarios, \"scenario\")\n\n        new_scenario.set(\"name\", scenario_type + \"_\" + str(number))\n        new_scenario.set(\"type\", scenario_type)\n\n        for a_name, a_type, a_value in scenario_attributes:\n            data = etree.SubElement(new_scenario, a_name)\n            if a_type == 'transform':\n                data.set(\"x\", a_value[0])\n                data.set(\"y\", a_value[1])\n                data.set(\"z\", a_value[2])\n                data.set(\"yaw\", a_value[3])\n            elif 'location' in a_type:\n                data.set(\"x\", a_value[0])\n                data.set(\"y\", a_value[1])\n                data.set(\"z\", a_value[2])\n                if 'probability' in a_type:\n                    data.set(\"p\", a_value[3])\n            elif a_type in ('value', 'choice', 'bool'):\n                data.set(\"value\", a_value)\n            elif a_type == 'interval':\n                data.set(\"from\", a_value[0])\n                data.set(\"to\", a_value[1])\n        break\n\n    if not found_id:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\n    prettify_and_save_tree(filename, tree)\n\ndef prettify_and_save_tree(filename, tree):\n    def indent(elem, spaces=3, level=0):\n        i = \"\\n\" + level * spaces * \" \"\n        j = \"\\n\" + (level + 1) * spaces * \" \"\n        if len(elem):\n            if not elem.text or not elem.text.strip():\n                elem.text = j\n            if not elem.tail or not elem.tail.strip():\n                elem.tail = i\n            for subelem in elem:\n                indent(subelem, spaces, level+1)\n        else:\n            if level and (not elem.tail or not elem.tail.strip()):\n                elem.tail = i\n        return elem\n\n    # Prettify the xml. A bit of automatic indentation, a bit of manual one\n    spaces = 3\n    indent(tree.getroot(), spaces)\n    tree.write(filename)\n\n    with open(filename, 'r') as f:\n        data = f.read()\n    temp = data.replace(\"   </\", \"</\")  # The 'indent' function fails for these cases\n\n    weather_spaces = spaces*4*\" \"\n    temp = temp.replace(\" cloudiness\", \"\\n\" + weather_spaces + \"cloudiness\")\n    temp = temp.replace(\" wind_intensity\", \"\\n\" + weather_spaces + \"wind_intensity\")\n    new_data = temp.replace(\" mie_scattering_scale\", \"\\n\" + weather_spaces + \"mie_scattering_scale\")\n\n    with open(filename, 'w') as f:\n        f.write(new_data)\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, nargs=\"+\", help='File at which to place the scenarios')\n    argparser.add_argument('-s', '--show-only', action='store_true', help='Only shows the route')\n    args = argparser.parse_args()\n\n    # Get the client\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n\n    # # Get the rest\n    world = client.get_world()\n    spectator = world.get_spectator()\n    tmap = world.get_map()\n\n    file_path = args.file[0]\n    route_id = args.file[1] if len(args.file) > 1 else 0\n\n    # Get the data already at the file\n    show_saved_scenarios(file_path, route_id, world)\n    if args.show_only:\n        sys.exit(0)\n\n    print(\" ------------------------------------------------------------ \")\n    print(\" |               Use Ctrl+C to stop the script              | \")\n    print(\" |            Any ongoing scenario will be ignored          | \")\n    print(\" |                                                          | \")\n    print(\" |   Transform and location parameters will automatically   | \")\n    print(\" |     get the closest waypoint to the spectator camera     | \")\n    try:\n        while True:\n            print(\" ------------------------------------------------------------ \")\n\n            # Get the scenario type\n            scen_type, trigger_point = get_scenario_type(tmap, world, spectator)\n\n            # Get the attributes\n            scen_attributes = get_attributes_data(scen_type, trigger_point, tmap, world, spectator)\n\n            # Give feedback to the user\n            print_scenario_data(scen_type, scen_attributes)\n\n            # Save the data\n            save_scenario(file_path, route_id, scen_type, scen_attributes)\n\n    except KeyboardInterrupt as e:\n        print(\"\\n Detected a keyboard interruption, stopping the script \")\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/scenario_orderer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nimport argparse\nfrom lxml import etree\nimport os\n\nimport carla\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nSCENARIO_TYPES = {\n\n    # Junction scenarios\n    \"SignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"SignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleRunningRedLight\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"NonSignalizedJunctionLeftTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"NonSignalizedJunctionRightTurn\": [\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"OppositeVehicleTakingPriority\": [\n        [\"direction\", \"choice\"],\n    ],\n\n    # Crossing actors\n    \"DynamicObjectCrossing\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"blocker_model\", \"value\"],\n        [\"crossing_angle\", \"value\"]\n    ],\n    \"ParkingCrossingPedestrian\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n        [\"crossing_angle\", \"value\"],\n    ],\n    \"PedestrianCrossing\": [\n    ],\n    \"VehicleTurningRoute\": [\n    ],\n    \"VehicleTurningRoutePedestrian\": [\n    ],\n    \"BlockedIntersection\": [\n    ],\n\n    # Actor flows\n    \"EnterActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"EnterActorFlowV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"InterurbanAdvancedActorFlow\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"HighwayExit\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTraffic\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"MergerIntoSlowTrafficV2\": [\n        [\"start_actor_flow\", \"location driving\"],\n        [\"end_actor_flow\", \"location driving\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n    \"CrossingBicycleFlow\": [\n        [\"start_actor_flow\", \"location bicycle\"],\n        [\"flow_speed\", \"value\"],\n        [\"source_dist_interval\", \"interval\"],\n    ],\n\n    # Route obstacles\n    \"ConstructionObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ConstructionObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"Accident\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"AccidentTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"ParkedObstacle\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"value\"],\n        [\"speed\", \"value\"],\n    ],\n    \"ParkedObstacleTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"VehicleOpensDoorTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"interval\"],\n    ],\n    \"HazardAtSideLane\": [\n        [\"distance\", \"value\"],\n        [\"speed\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"HazardAtSideLaneTwoWays\": [\n        [\"distance\", \"value\"],\n        [\"frequency\", \"value\"],\n        [\"bicycle_drive_distance\", \"value\"],\n        [\"bicycle_speed\", \"value\"],\n    ],\n    \"InvadingTurn\": [\n        [\"distance\", \"value\"],\n        [\"offset\", \"value\"],\n    ],\n\n    # Cut ins\n    \"HighwayCutIn\": [\n        [\"other_actor_location\", \"location driving\"],\n    ],\n    \"ParkingCutIn\": [\n        [\"direction\", \"choice\"],\n    ],\n    \"StaticCutIn\": [\n        [\"distance\", \"value\"],\n        [\"direction\", \"choice\"],\n    ],\n\n    # Others\n    \"ControlLoss\": [\n    ],\n    \"HardBreakRoute\": [\n    ],\n    \"ParkingExit\": [\n        [\"direction\", \"choice\"],\n        [\"front_vehicle_distance\", \"value\"],\n        [\"behind_vehicle_distance\", \"value\"],\n    ],\n    \"YieldToEmergencyVehicle\": [\n        [\"distance\", \"value\"],\n    ],\n\n    # Special ones\n    \"BackgroundActivityParametrizer\": [\n        [\"num_front_vehicles\", \"value\"],\n        [\"num_back_vehicles\", \"value\"],\n        [\"road_spawn_dist\", \"value\"],\n        [\"opposite_source_dist\", \"value\"],\n        [\"opposite_max_actors\", \"value\"],\n        [\"opposite_spawn_dist\", \"value\"],\n        [\"opposite_active\", \"bool\"],\n        [\"junction_source_dist\", \"value\"],\n        [\"junction_max_actors\", \"value\"],\n        [\"junction_spawn_dist\", \"value\"],\n        [\"junction_source_perc\", \"value\"],\n    ],\n    \"PriorityAtJunction\": [\n    ],\n\n}\n\nMAPS_LOCATIONS = {\n    \"Town01\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01.xodr\",\n    \"Town01_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01_Opt.xodr\",\n    \"Town02\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02.xodr\",\n    \"Town02_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02_Opt.xodr\",\n    \"Town03\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town03.xodr\",\n    \"Town03_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town04\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04.xodr\",\n    \"Town04_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr\",\n    \"Town05\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05.xodr\",\n    \"Town05_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05_Opt.xodr\",\n    \"Town06\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06.xodr\",\n    \"Town06_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06_Opt.xodr\",\n    \"Town07\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07.xodr\",\n    \"Town07_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07_Opt.xodr\",\n    \"Town10HD\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD.xodr\",\n    \"Town10HD_Opt\": \"Unreal/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD_Opt.xodr\",\n    \"Town11\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town11/OpenDrive/Town11.xodr\",\n    \"Town12\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town12/OpenDrive/Town12.xodr\",\n    \"Town13\": \"Unreal/CarlaUE4/Content/Carla/Maps/Town13/OpenDrive/Town13.xodr\",\n}\n\ndef order_saved_scenarios(filename, route_id, tmap, grp):\n    def convert_elem_to_location(elem):\n        \"\"\"Convert an ElementTree.Element to a CARLA Location\"\"\"\n        return carla.Location(float(elem.attrib.get('x')), float(elem.attrib.get('y')), float(elem.attrib.get('z')))\n\n    def get_scenario_route_position(trigger_location):\n        position = 0\n        distance = float('inf')\n        for i, (wp, _) in enumerate(route_wps):\n            route_distance = wp.transform.location.distance(trigger_location)\n            if route_distance < distance:\n                distance = route_distance\n                position = i\n        return position\n\n    def indent(elem, spaces=3, level=0):\n        i = \"\\n\" + level * spaces * \" \"\n        j = \"\\n\" + (level + 1) * spaces * \" \"\n        if len(elem):\n            if not elem.text or not elem.text.strip():\n                elem.text = j\n            if not elem.tail or not elem.tail.strip():\n                elem.tail = i\n            for subelem in elem:\n                indent(subelem, spaces, level+1)\n        else:\n            if level and (not elem.tail or not elem.tail.strip()):\n                elem.tail = i\n        return elem\n\n    tree = etree.parse(filename)\n    root = tree.getroot()\n\n    scenarios = None\n    route_wps = []\n    prev_route_keypoint = None\n    scenarios = []\n\n    for route in root.iter(\"route\"):\n        if route.attrib['id'] != route_id:\n            continue\n\n        # Scenarios data\n        for scenario in route.find('scenarios').iter('scenario'):\n            scenarios.append(scenario)\n\n        # Route data\n        for position in route.find('waypoints').iter('position'):\n            route_keypoint = convert_elem_to_location(position)\n            if prev_route_keypoint:\n                route_wps.extend(grp.trace_route(prev_route_keypoint, route_keypoint))\n            prev_route_keypoint = route_keypoint\n\n    if scenarios is None:\n        print(f\"\\n\\033[91mCouldn't find the id '{route_id} in the given routes file\\033[0m\")\n        return\n\n    # Order the scenarios according to route position\n    scenario_and_pos = []\n    for scenario in scenarios:\n        trigger_location = convert_elem_to_location(scenario.find('trigger_point'))\n        route_position = get_scenario_route_position(trigger_location)\n        scenario_and_pos.append([scenario, route_position])\n    scenario_and_pos = sorted(scenario_and_pos, key=lambda x: x[1])\n\n    # Update the scenarios. TODO: reorder them\n    scenario_names = {}\n    for scen_type in list(SCENARIO_TYPES):\n        scenario_names[scen_type] = 1\n\n    for scenario, _ in scenario_and_pos:\n        scen_type = scenario.attrib['type']\n        scen_name = f\"{scen_type}_{scenario_names[scen_type]}\"\n        scenario.set(\"name\", scen_name)\n        scenario_names[scen_type] += 1\n\n    # Prettify the xml. A bit of automatic indentation, a bit of manual one\n    spaces = 3\n    indent(tree.getroot(), spaces)\n    tree.write(filename)\n\n    with open(filename, 'r') as f:\n        data = f.read()\n    temp = data.replace(\"   </\", \"</\")  # The 'indent' function fails for these cases\n\n    weather_spaces = spaces*4*\" \"\n    temp = temp.replace(\" cloudiness\", \"\\n\" + weather_spaces + \"cloudiness\")\n    temp = temp.replace(\" wind_intensity\", \"\\n\" + weather_spaces + \"wind_intensity\")\n    temp = temp.replace(\" fog_density\", \"\\n\" + weather_spaces + \"fog_density\")\n    new_data = temp.replace(\" mie_scattering_scale\", \"\\n\" + weather_spaces + \"mie_scattering_scale\")\n\n    with open(filename, 'w') as f:\n        f.write(new_data)\n\ndef main():\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', required=True, help='File at which to place the scenarios')\n    args = argparser.parse_args()\n\n    root = etree.parse(args.file).getroot()\n    prev_town = None\n    for route in root.iter(\"route\"):\n\n        route_id = route.attrib['id']\n        route_town = route.attrib['town']\n\n        if route_town not in MAPS_LOCATIONS:\n            print(f\"Ignoring route '{route_id}' as it uses an unknown map '{route_town}\")\n            continue\n        elif route_town != prev_town:\n            full_name = os.environ[\"CARLA_ROOT\"] + \"/\" + MAPS_LOCATIONS[route_town]\n            with open(full_name, 'r') as f:\n                map_contents = f.read()\n            tmap = carla.Map(route_town, map_contents)\n            grp = GlobalRoutePlanner(tmap, 1.0)\n\n        print(f\"Parsing route '{route_id}'\")\n\n    file_path = args.file[0]\n    route_id = args.file[1] if len(args.file) > 1 else 0\n\n    order_saved_scenarios(file_path, route_id, tmap)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/scripts/weather_creator.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\nimport argparse\nimport carla\n\n\n\ndef main():\n    argparser = argparse.ArgumentParser(\n        description=__doc__)\n    argparser.add_argument('--host', metavar='H', default='localhost', help='IP of the host CARLA Simulator (default: localhost)')\n    argparser.add_argument('--port', metavar='P', default=2000, type=int, help='TCP port of CARLA Simulator (default: 2000)')\n    argparser.add_argument('-f', '--file', action=\"store_true\", help='File to start')\n    argparser.add_argument('-r', '--route', default=\"\", help='Route')\n    # argparser.add_argument('-t', '--time', default=60, help='Time')\n    args = argparser.parse_args()\n\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(10.0)\n    world = client.get_world()\n    weather = world.get_weather()\n\n    weather_string = f\"         <weather\\n\"\n    weather_string += f\"            route_percentage=\\\"0\\\"\\n\"\n    weather_string += f\"            cloudiness=\\\"{weather.cloudiness}\\\" \"\n    weather_string += f\"precipitation=\\\"{weather.precipitation}\\\" \"\n    weather_string += f\"precipitation_deposits=\\\"{weather.precipitation_deposits}\\\" \"\n    weather_string += f\"wetness=\\\"{weather.wetness}\\\"\\n\"\n    weather_string += f\"            wind_intensity=\\\"{weather.wind_intensity}\\\" \"\n    weather_string += f\"sun_azimuth_angle=\\\"{weather.sun_azimuth_angle}\\\" \"\n    weather_string += f\"sun_altitude_angle=\\\"{weather.sun_altitude_angle}\\\"\\n\"\n    weather_string += f\"            fog_density=\\\"{weather.fog_density}\\\" \"\n    weather_string += f\"fog_distance=\\\"{weather.fog_distance}\\\" \"\n    weather_string += f\"fog_falloff=\\\"{round(weather.fog_falloff, 2)}\\\" \"\n    weather_string += f\"scattering_intensity=\\\"{weather.scattering_intensity}\\\"\\n\"\n    weather_string += f\"            mie_scattering_scale=\\\"{round(weather.mie_scattering_scale, 2)}\\\"/>\"\n\n    print(weather_string)\n\nif __name__ == '__main__':\n    try:\n        main()\n    except RuntimeError as e:\n        print(e)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/team_code/pid_controller.py",
    "content": "from collections import deque\nimport numpy as np\n\nclass PID(object):\n\tdef __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20):\n\t\tself._K_P = K_P\n\t\tself._K_I = K_I\n\t\tself._K_D = K_D\n\n\t\tself._window = deque([0 for _ in range(n)], maxlen=n)\n\t\tself._max = 0.0\n\t\tself._min = 0.0\n\n\tdef step(self, error):\n\t\tself._window.append(error)\n\t\tself._max = max(self._max, abs(error))\n\t\tself._min = -abs(self._max)\n\n\t\tif len(self._window) >= 2:\n\t\t\tintegral = np.mean(self._window)\n\t\t\tderivative = (self._window[-1] - self._window[-2])\n\t\telse:\n\t\t\tintegral = 0.0\n\t\t\tderivative = 0.0\n\n\t\treturn self._K_P * error + self._K_I * integral + self._K_D * derivative\n\n\n\nclass PIDController(object):\n    \n    def __init__(self, turn_KP=0.75, turn_KI=0.75, turn_KD=0.3, turn_n=40, speed_KP=5.0, speed_KI=0.5,speed_KD=1.0, speed_n = 40,max_throttle=0.75, brake_speed=0.4,brake_ratio=1.1, clip_delta=0.25, aim_dist=4.0, angle_thresh=0.3, dist_thresh=10):\n        \n        self.turn_controller = PID(K_P=turn_KP, K_I=turn_KI, K_D=turn_KD, n=turn_n)\n        self.speed_controller = PID(K_P=speed_KP, K_I=speed_KI, K_D=speed_KD, n=speed_n)\n        self.max_throttle = max_throttle\n        self.brake_speed = brake_speed\n        self.brake_ratio = brake_ratio\n        self.clip_delta = clip_delta\n        self.aim_dist = aim_dist\n        self.angle_thresh = angle_thresh\n        self.dist_thresh = dist_thresh\n\n    def control_pid(self, waypoints, speed, target):\n        ''' Predicts vehicle control with a PID controller.\n        Args:\n            waypoints (tensor): output of self.plan()\n            speed (tensor): speedometer input\n        '''\n\n        # iterate over vectors between predicted waypoints\n        num_pairs = len(waypoints) - 1\n        best_norm = 1e5\n        desired_speed = 0\n        aim = waypoints[0]\n        for i in range(num_pairs):\n            # magnitude of vectors, used for speed\n            desired_speed += np.linalg.norm(\n                    waypoints[i+1] - waypoints[i]) * 2.0 / num_pairs\n\n            # norm of vector midpoints, used for steering\n            norm = np.linalg.norm((waypoints[i+1] + waypoints[i]) / 2.0)\n            if abs(self.aim_dist-best_norm) > abs(self.aim_dist-norm):\n                aim = waypoints[i]\n                best_norm = norm\n\n        aim_last = waypoints[-1] - waypoints[-2]\n\n        angle = np.degrees(np.pi / 2 - np.arctan2(aim[1], aim[0])) / 90\n        angle_last = np.degrees(np.pi / 2 - np.arctan2(aim_last[1], aim_last[0])) / 90\n        angle_target = np.degrees(np.pi / 2 - np.arctan2(target[1], target[0])) / 90\n\n        # choice of point to aim for steering, removing outlier predictions\n        # use target point if it has a smaller angle or if error is large\n        # predicted point otherwise\n        # (reduces noise in eg. straight roads, helps with sudden turn commands)\n        use_target_to_aim = np.abs(angle_target) < np.abs(angle)\n        use_target_to_aim = use_target_to_aim or (np.abs(angle_target-angle_last) > self.angle_thresh and target[1] < self.dist_thresh)\n        if use_target_to_aim:\n            angle_final = angle_target\n        else:\n            angle_final = angle\n\n        steer = self.turn_controller.step(angle_final)\n        steer = np.clip(steer, -1.0, 1.0)\n\n        brake = desired_speed < self.brake_speed or (speed / desired_speed) > self.brake_ratio\n\n        delta = np.clip(desired_speed - speed, 0.0, self.clip_delta)\n        throttle = self.speed_controller.step(delta)\n        throttle = np.clip(throttle, 0.0, self.max_throttle)\n        throttle = throttle if not brake else 0.0\n\n        metadata = {\n            'speed': float(speed.astype(np.float64)),\n            'steer': float(steer),\n            'throttle': float(throttle),\n            'brake': float(brake),\n            'wp_4': tuple(waypoints[3].astype(np.float64)),\n            'wp_3': tuple(waypoints[2].astype(np.float64)),\n            'wp_2': tuple(waypoints[1].astype(np.float64)),\n            'wp_1': tuple(waypoints[0].astype(np.float64)),\n            'aim': tuple(aim.astype(np.float64)),\n            'target': tuple(target.astype(np.float64)),\n            'desired_speed': float(desired_speed.astype(np.float64)),\n            'angle': float(angle.astype(np.float64)),\n            'angle_last': float(angle_last.astype(np.float64)),\n            'angle_target': float(angle_target.astype(np.float64)),\n            'angle_final': float(angle_final.astype(np.float64)),\n            'delta': float(delta.astype(np.float64)),\n        }\n\n        return steer, throttle, brake, metadata"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/team_code/planner.py",
    "content": "import os\nfrom collections import deque\n\nimport numpy as np\nimport math\nEARTH_RADIUS_EQUA = 6378137.0\n\n\nDEBUG = int(os.environ.get('HAS_DISPLAY', 0))\n\n\nclass Plotter(object):\n    def __init__(self, size):\n        self.size = size\n        self.clear()\n        self.title = str(self.size)\n\n    def clear(self):\n        from PIL import Image, ImageDraw\n\n        self.img = Image.fromarray(np.zeros((self.size, self.size, 3), dtype=np.uint8))\n        self.draw = ImageDraw.Draw(self.img)\n\n    def dot(self, pos, node, color=(255, 255, 255), r=2):\n        x, y = 5.5 * (pos - node)\n        x += self.size / 2\n        y += self.size / 2\n\n        self.draw.ellipse((x-r, y-r, x+r, y+r), color)\n\n    def show(self):\n        if not DEBUG:\n            return\n\n        import cv2\n\n        cv2.imshow(self.title, cv2.cvtColor(np.array(self.img), cv2.COLOR_BGR2RGB))\n        cv2.waitKey(1)\n\n\nclass RoutePlanner(object):\n    def __init__(self, min_distance, max_distance, debug_size=256, lat_ref=42.0, lon_ref=2.0):\n        self.route = deque()\n        self.min_distance = min_distance\n        self.max_distance = max_distance\n\n        # self.mean = np.array([49.0, 8.0]) # for carla 9.9\n        # self.scale = np.array([111324.60662786, 73032.1570362]) # for carla 9.9\n        self.mean = np.array([0.0, 0.0]) # for carla 9.10\n        self.scale = np.array([111324.60662786, 111319.490945]) # for carla 9.10\n\n        self.debug = Plotter(debug_size)\n        # self.lat_ref, self.lon_ref = self._get_latlon_ref()\n        self.lat_ref = lat_ref\n        self.lon_ref = lon_ref\n\n    def set_route(self, global_plan, gps=False, global_plan_world = None):\n        self.route.clear()\n\n        if global_plan_world:\n            for (pos, cmd), (pos_word, _ )in zip(global_plan, global_plan_world):\n                if gps:\n                    pos = self.gps_to_location(np.array([pos['lat'], pos['lon']]))\n                    # pos -= self.mean\n                    # pos *= self.scale\n                else:\n                    pos = np.array([pos.location.x, pos.location.y])\n                    # pos -= self.mean\n                \n                self.route.append((pos, cmd, pos_word))\n        else:\n            for pos, cmd in global_plan:\n                if gps:\n                    pos = self.gps_to_location(np.array([pos['lat'], pos['lon']]))\n                    # pos -= self.mean\n                    # pos *= self.scale\n                else:\n                    pos = np.array([pos.location.x, pos.location.y])\n                    # pos -= self.mean\n\n                self.route.append((pos, cmd))\n\n    def run_step(self, gps):\n        self.debug.clear()\n\n        if len(self.route) == 1:\n            return self.route[0]\n\n        to_pop = 0\n        farthest_in_range = -np.inf\n        cumulative_distance = 0.0\n\n        for i in range(1, len(self.route)):\n            if cumulative_distance > self.max_distance:\n                break\n\n            cumulative_distance += np.linalg.norm(self.route[i][0] - self.route[i-1][0])\n            distance = np.linalg.norm(self.route[i][0] - gps)\n\n            if distance <= self.min_distance and distance > farthest_in_range:\n                farthest_in_range = distance\n                to_pop = i\n\n            r = 255 * int(distance > self.min_distance)\n            g = 255 * int(self.route[i][1].value == 4)\n            b = 255\n            self.debug.dot(gps, self.route[i][0], (r, g, b))\n\n        for _ in range(to_pop):\n            if len(self.route) > 2:\n                self.route.popleft()\n\n        self.debug.dot(gps, self.route[0][0], (0, 255, 0))\n        self.debug.dot(gps, self.route[1][0], (255, 0, 0))\n        self.debug.dot(gps, gps, (0, 0, 255))\n        self.debug.show()\n\n        return self.route[1]\n    \n    def gps_to_location(self, gps):\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/team_code/uniad_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom Bench2DriveZoo.team_code.pid_controller import PIDController\nfrom Bench2DriveZoo.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\nfrom scipy.optimize import fsolve\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\ndef get_entry_point():\n    return 'UniadAgent'\n\nclass UniadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steers = deque()\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        cfg.model['motion_head']['anchor_info_path'] = os.path.join('Bench2DriveZoo',cfg.model['motion_head']['anchor_info_path'])\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.last_steers = deque()\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            # string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string = self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        # write extrinsics directly\n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                                  [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                                  [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                                 [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n          'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n          'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                       [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n         'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                                 [ 0.  ,  0.  , -1.  , -0.24],\n                                 [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                      [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n          'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n    def _init(self):\n        \n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0        \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n                \n            ]\n        \n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n    \n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n  \n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n  \n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n  \n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        out_truck =  output_data_batch[0]['planning']['result_planning']['sdc_traj'][0].cpu().numpy()\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n        if tick_data['speed']>5:\n            throttle_traj = 0\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)\n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n        if SAVE_PATH is not None and self.step % 1 == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        return control\n\n    def save(self, tick_data):\n        frame = self.step // 10\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/team_code/vad_b2d_agent.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nfrom scipy.optimize import fsolve\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom team_code.pid_controller import PIDController\nfrom team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,\n                        wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\n\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\n\ndef get_entry_point():\n    return 'VadAgent'\n\n\nclass VadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string += self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                              [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                              [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                              [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                    [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                              [ 0.  ,  0.  , -1.  , -0.24],\n                              [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        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]])\n        unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        self.coor2topdown = unreal2cam @ topdown_extrinsics\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown\n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n        self.metric_info = {}\n  \n  \n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n  \n        if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        \n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = can_bus[0:2].copy()\n        ego_lcf_feat[2:4] = can_bus[10:12].copy()\n        ego_lcf_feat[4] = rotation[-1]\n        ego_lcf_feat[5] = 4.89238167\n        ego_lcf_feat[6] = 1.83671331\n        ego_lcf_feat[7] = np.sqrt(can_bus[0]**2+can_bus[1]**2)\n\n        if len(self.prev_control_cache)<10:\n            ego_lcf_feat[8] = 0\n        else:\n            ego_lcf_feat[8] = self.prev_control_cache[0].steer\n\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n        command_onehot = np.zeros(6)\n        command_onehot[command] = 1\n        results['ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        #import pdb;pdb.set_trace()\n        #all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds_refine'].cpu().numpy()\n        all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds_refine'].cpu().numpy() # [6,6,2]\n        all_cls = output_data_batch[0]['pts_bbox']['ego_fut_classification_refine'].reshape(6,6,-1).sum(dim=-1)\n        all_cls = all_cls.cpu().numpy()\n        nnums = np.arange(all_out_truck_d1.shape[0])\n        all_out_truck_d1 = all_out_truck_d1[nnums,all_cls.argmax(-1), :, :]\n        #all_cls = all_cls.reshape(6,6,-1).sum(dim=-1)\n        #import pdb;pdb.set_trace()\n        all_out_truck =  np.cumsum(all_out_truck_d1,axis=1)\n        out_truck = all_out_truck[command]\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['all_plan'] = all_out_truck.tolist()\n\n        metric_info = self.get_metric_info()\n        self.metric_info[self.step] = metric_info\n        if SAVE_PATH is not None and self.step % 1 == 0:\n            self.save(tick_data)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n        return control\n\n\n    def save(self, tick_data):\n        frame = self.step // 10\n\n        Image.fromarray(tick_data['imgs']['CAM_FRONT']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_LEFT']).save(self.save_path / 'rgb_front_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_FRONT_RIGHT']).save(self.save_path / 'rgb_front_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_LEFT']).save(self.save_path / 'rgb_back_left' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['imgs']['CAM_BACK_RIGHT']).save(self.save_path / 'rgb_back_right' / ('%04d.png' % frame))\n        Image.fromarray(tick_data['bev']).save(self.save_path / 'bev' / ('%04d.png' % frame))\n\n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n\n        # metric info\n        outfile = open(self.save_path / 'metric_info.json', 'w')\n        json.dump(self.metric_info, outfile, indent=4)\n        outfile.close()\n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/leaderboard/team_code/vad_b2d_agent_visualize.py",
    "content": "import os\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nimport carla\nfrom collections import deque\nimport math\nfrom collections import OrderedDict\nfrom scipy.optimize import fsolve\nimport torch\nimport carla\nimport numpy as np\nfrom PIL import Image\nfrom torchvision import transforms as T\nfrom Bench2DriveZoo.team_code.pid_controller import PIDController\nfrom Bench2DriveZoo.team_code.planner import RoutePlanner\nfrom leaderboard.autoagents import autonomous_agent\nfrom mmcv import Config\nfrom mmcv.models import build_model\nfrom mmcv.utils import (get_dist_info, init_dist, load_checkpoint,\n                        wrap_fp16_model)\nfrom mmcv.datasets.pipelines import Compose\nfrom mmcv.parallel.collate import collate as  mm_collate_to_batch_form\nfrom mmcv.core.bbox import get_box_type\nfrom pyquaternion import Quaternion\nfrom scipy.interpolate import splprep, splev\nimport copy\nimport seaborn as sns\n\nSAVE_PATH = os.environ.get('SAVE_PATH', None)\nIS_BENCH2DRIVE = os.environ.get('IS_BENCH2DRIVE', None)\n\ndef float_to_uint8_color(float_clr):\n    assert all([c >= 0. for c in float_clr])\n    assert all([c <= 1. for c in float_clr])\n    return [int(c * 255.) for c in float_clr]\n\n\nCOLORS = [float_to_uint8_color(clr) for clr in sns.color_palette(\"bright\", n_colors=10)]\nCOLORMAP = OrderedDict({\n    6: COLORS[8],  # yellow\n    4: COLORS[8],\n    3: COLORS[0],  # blue\n    1: COLORS[6],  # pink\n    0: COLORS[2],  # green\n    8: COLORS[7],  # gray\n    7: COLORS[1],  # orange\n    5: COLORS[3],  # red\n    2: COLORS[5],  # brown\n})\n\ndef get_entry_point():\n    return 'VadAgent'\n\n\nclass VadAgent(autonomous_agent.AutonomousAgent):\n    def setup(self, path_to_conf_file):\n        self.track = autonomous_agent.Track.SENSORS\n        self.steer_step = 0\n        self.last_moving_status = 0\n        self.last_moving_step = -1\n        self.last_steer = 0\n        self.pidcontroller = PIDController() \n        self.config_path = path_to_conf_file.split('+')[0]\n        self.ckpt_path = path_to_conf_file.split('+')[1]\n        if IS_BENCH2DRIVE:\n            self.save_name = path_to_conf_file.split('+')[-1]\n        else:\n            self.save_name = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second)))\n        self.step = -1\n        self.wall_start = time.time()\n        self.initialized = False\n        cfg = Config.fromfile(self.config_path)\n        if hasattr(cfg, 'plugin'):\n            if cfg.plugin:\n                import importlib\n                if hasattr(cfg, 'plugin_dir'):\n                    plugin_dir = cfg.plugin_dir\n                    plugin_dir = os.path.join(\"Bench2DriveZoo\", plugin_dir)\n                    _module_dir = os.path.dirname(plugin_dir)\n                    _module_dir = _module_dir.split('/')\n                    _module_path = _module_dir[0]\n                    for m in _module_dir[1:]:\n                        _module_path = _module_path + '.' + m\n                    print(_module_path)\n                    plg_lib = importlib.import_module(_module_path)  \n  \n        self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg'))\n        checkpoint = load_checkpoint(self.model, self.ckpt_path, map_location='cpu', strict=True)\n        self.model.cuda()\n        self.model.eval()\n        self.inference_only_pipeline = []\n        for inference_only_pipeline in cfg.inference_only_pipeline:\n            if inference_only_pipeline[\"type\"] not in ['LoadMultiViewImageFromFilesInCeph','LoadMultiViewImageFromFiles']:\n                self.inference_only_pipeline.append(inference_only_pipeline)\n        self.inference_only_pipeline = Compose(self.inference_only_pipeline)\n\n        self.takeover = False\n        self.stop_time = 0\n        self.takeover_time = 0\n        self.save_path = None\n        self._im_transform = T.Compose([T.ToTensor(), T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])])\n        self.lat_ref, self.lon_ref = 42.0, 2.0\n\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\t\n        self.prev_control = control\n        self.prev_control_cache = []\n        if SAVE_PATH is not None:\n            now = datetime.datetime.now()\n            string = pathlib.Path(os.environ['ROUTES']).stem + '_'\n            string += self.save_name\n            self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string\n            self.save_path.mkdir(parents=True, exist_ok=False)\n            (self.save_path / 'rgb_front').mkdir()\n            (self.save_path / 'rgb_front_right').mkdir()\n            (self.save_path / 'rgb_front_left').mkdir()\n            (self.save_path / 'rgb_back').mkdir()\n            (self.save_path / 'rgb_back_right').mkdir()\n            (self.save_path / 'rgb_back_left').mkdir()\n            (self.save_path / 'meta').mkdir()\n            (self.save_path / 'bev').mkdir()\n   \n        self.lidar2img = {\n        'CAM_FRONT':np.array([[ 1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -9.52000000e+02],\n                              [ 0.00000000e+00,  4.50000000e+02, -1.14251841e+03, -8.09704417e+02],\n                              [ 0.00000000e+00,  1.00000000e+00,  0.00000000e+00, -1.19000000e+00],\n                              [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_LEFT':np.array([[ 6.03961325e-14,  1.39475744e+03,  0.00000000e+00, -9.20539908e+02],\n                                   [-3.68618420e+02,  2.58109396e+02, -1.14251841e+03, -6.47296750e+02],\n                                   [-8.19152044e-01,  5.73576436e-01,  0.00000000e+00, -8.29094072e-01],\n                                   [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_FRONT_RIGHT':np.array([[ 1.31064327e+03, -4.77035138e+02,  0.00000000e+00,-4.06010608e+02],\n                                    [ 3.68618420e+02,  2.58109396e+02, -1.14251841e+03,-6.47296750e+02],\n                                    [ 8.19152044e-01,  5.73576436e-01,  0.00000000e+00,-8.29094072e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00, 1.00000000e+00]]),\n        'CAM_BACK':np.array([[-5.60166031e+02, -8.00000000e+02,  0.00000000e+00, -1.28800000e+03],\n                     [ 5.51091060e-14, -4.50000000e+02, -5.60166031e+02, -8.58939847e+02],\n                     [ 1.22464680e-16, -1.00000000e+00,  0.00000000e+00, -1.61000000e+00],\n                     [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n        'CAM_BACK_LEFT':np.array([[-1.14251841e+03,  8.00000000e+02,  0.00000000e+00, -6.84385123e+02],\n                                  [-4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                  [-9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                  [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]]),\n  \n        'CAM_BACK_RIGHT': np.array([[ 3.60989788e+02, -1.34723223e+03,  0.00000000e+00, -1.04238127e+02],\n                                    [ 4.22861679e+02, -1.53909064e+02, -1.14251841e+03, -4.96004706e+02],\n                                    [ 9.39692621e-01, -3.42020143e-01,  0.00000000e+00, -4.92889531e-01],\n                                    [ 0.00000000e+00,  0.00000000e+00,  0.00000000e+00,  1.00000000e+00]])\n        }\n        self.lidar2cam = {\n        'CAM_FRONT':np.array([[ 1.  ,  0.  ,  0.  ,  0.  ],\n                              [ 0.  ,  0.  , -1.  , -0.24],\n                              [ 0.  ,  1.  ,  0.  , -1.19],\n                              [ 0.  ,  0.  ,  0.  ,  1.  ]]),\n        'CAM_FRONT_LEFT':np.array([[ 0.57357644,  0.81915204,  0.  , -0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [-0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_FRONT_RIGHT':np.array([[ 0.57357644, -0.81915204, 0.  ,  0.22517331],\n                                   [ 0.        ,  0.        , -1.  , -0.24      ],\n                                   [ 0.81915204,  0.57357644,  0.  , -0.82909407],\n                                   [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n        'CAM_BACK':np.array([[-1. ,  0.,  0.,  0.  ],\n                             [ 0. ,  0., -1., -0.24],\n                             [ 0. , -1.,  0., -1.61],\n                             [ 0. ,  0.,  0.,  1.  ]]),\n     \n        'CAM_BACK_LEFT':np.array([[-0.34202014,  0.93969262,  0.  , -0.25388956],\n                                  [ 0.        ,  0.        , -1.  , -0.24      ],\n                                  [-0.93969262, -0.34202014,  0.  , -0.49288953],\n                                  [ 0.        ,  0.        ,  0.  ,  1.        ]]),\n  \n        'CAM_BACK_RIGHT':np.array([[-0.34202014, -0.93969262,  0.  ,  0.25388956],\n                                  [ 0.        ,  0.         , -1.  , -0.24      ],\n                                  [ 0.93969262, -0.34202014 ,  0.  , -0.49288953],\n                                  [ 0.        ,  0.         ,  0.  ,  1.        ]])\n        }\n        self.lidar2ego = np.array([[ 0. ,  1. ,  0. , -0.39],\n                                   [-1. ,  0. ,  0. ,  0.  ],\n                                   [ 0. ,  0. ,  1. ,  1.84],\n                                   [ 0. ,  0. ,  0. ,  1.  ]])\n        \n        # topdown_extrinsics =  np.array([[0.0, -0.0, -1.0, 50.0], \n        #                                 [0.0,  1.0, -0.0,  0.0], \n        #                                 [1.0, -0.0,  0.0, -0.0], \n        #                                 [0.0,  0.0,  0.0,  1.0]])\n        # unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]])\n        #unreal2cam @ topdown_extrinsics\n        self.coor2topdown = np.array([[1.0,  0.0,  0.0,  0.0], \n                                      [0.0, -1.0,  0.0,  0.0], \n                                      [0.0,  0.0, -1.0, 50.0], \n                                      [0.0,  0.0,  0.0,  1.0]])\n        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]])\n        self.coor2topdown = topdown_intrinsics @ self.coor2topdown         \n\n    def _init(self):\n        try:\n            locx, locy = self._global_plan_world_coord[0][0].location.x, self._global_plan_world_coord[0][0].location.y\n            lon, lat = self._global_plan[0][0]['lon'], self._global_plan[0][0]['lat']\n            EARTH_RADIUS_EQUA = 6378137.0\n            def equations(vars):\n                x, y = vars\n                eq1 = lon * math.cos(x * math.pi / 180) - (locx * x * 180) / (math.pi * EARTH_RADIUS_EQUA) - math.cos(x * math.pi / 180) * y\n                eq2 = math.log(math.tan((lat + 90) * math.pi / 360)) * EARTH_RADIUS_EQUA * math.cos(x * math.pi / 180) + locy - math.cos(x * math.pi / 180) * EARTH_RADIUS_EQUA * math.log(math.tan((90 + x) * math.pi / 360))\n                return [eq1, eq2]\n            initial_guess = [0, 0]\n            solution = fsolve(equations, initial_guess)\n            self.lat_ref, self.lon_ref = solution[0], solution[1]\n        except Exception as e:\n            print(e, flush=True)\n            self.lat_ref, self.lon_ref = 0, 0      \n        self._route_planner = RoutePlanner(4.0, 50.0, lat_ref=self.lat_ref, lon_ref=self.lon_ref)\n        self._route_planner.set_route(self._global_plan, True)\n        self.initialized = True\n  \n  \n\n    def sensors(self):\n        sensors =[\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                },\n            ]\n        if IS_BENCH2DRIVE:\n            sensors += [\n                    {\t\n                        'type': 'sensor.camera.rgb',\n                        'x': 0.0, 'y': 0.0, 'z': 50.0,\n                        'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                        'width': 512, 'height': 512, 'fov': 5 * 10.0,\n                        'id': 'bev'\n                    }]\n        return sensors\n\n    def tick(self, input_data):\n        self.step += 1\n        encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 20]\n        imgs = {}\n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            img = cv2.cvtColor(input_data[cam][1][:, :, :3], cv2.COLOR_BGR2RGB)\n            _, img = cv2.imencode('.jpg', img, encode_param)\n            img = cv2.imdecode(img, cv2.IMREAD_COLOR)\n            imgs[cam] = img\n        bev = cv2.cvtColor(input_data['bev'][1][:, :, :3], cv2.COLOR_BGR2RGB)\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n  \n        pos = self.gps_to_location(gps)\n        near_node, near_command = self._route_planner.run_step(pos)\n  \n        if math.isnan(compass): #It can happen that the compass sends nan for a few frames\n            compass = 0.0\n            acceleration = np.zeros(3)\n            angular_velocity = np.zeros(3)\n\n        result = {\n                'imgs': imgs,\n                'gps': gps,\n                'pos':pos,\n                'speed': speed,\n                'compass': compass,\n                'bev': bev,\n                'acceleration':acceleration,\n                'angular_velocity':angular_velocity,\n                'command_near':near_command,\n                'command_near_xy':near_node\n                }\n        \n        return result\n    \n    @torch.no_grad()\n    def run_step(self, input_data, timestamp):\n        if not self.initialized:\n            self._init()\n        tick_data = self.tick(input_data)\n        results = {}\n        results['lidar2img'] = []\n        results['lidar2cam'] = []\n        results['img'] = []\n        results['folder'] = ' '\n        results['scene_token'] = ' '  \n        results['frame_idx'] = 0\n        results['timestamp'] = self.step / 20\n        results['box_type_3d'], _ = get_box_type('LiDAR')\n  \n        for cam in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK','CAM_BACK_LEFT','CAM_BACK_RIGHT']:\n            results['lidar2img'].append(self.lidar2img[cam])\n            results['lidar2cam'].append(self.lidar2cam[cam])\n            results['img'].append(tick_data['imgs'][cam])\n        results['lidar2img'] = np.stack(results['lidar2img'],axis=0)\n        results['lidar2cam'] = np.stack(results['lidar2cam'],axis=0)\n        raw_theta = tick_data['compass']   if not np.isnan(tick_data['compass']) else 0\n        ego_theta = -raw_theta + np.pi/2\n        rotation = list(Quaternion(axis=[0, 0, 1], radians=ego_theta))\n        can_bus = np.zeros(18)\n        can_bus[0] = tick_data['pos'][0]\n        can_bus[1] = -tick_data['pos'][1]\n        can_bus[3:7] = rotation\n        can_bus[7] = tick_data['speed']\n        can_bus[10:13] = tick_data['acceleration']\n        can_bus[11] *= -1\n        can_bus[13:16] = -tick_data['angular_velocity']\n        can_bus[16] = ego_theta\n        can_bus[17] = ego_theta / np.pi * 180 \n        results['can_bus'] = can_bus\n        ego_lcf_feat = np.zeros(9)\n        ego_lcf_feat[0:2] = can_bus[0:2].copy()\n        ego_lcf_feat[2:4] = can_bus[10:12].copy()\n        ego_lcf_feat[4] = rotation[-1]\n        ego_lcf_feat[5] = 4.89238167\n        ego_lcf_feat[6] = 1.83671331\n        ego_lcf_feat[7] = np.sqrt(can_bus[0]**2+can_bus[1]**2)\n\n        if len(self.prev_control_cache)<10:\n            ego_lcf_feat[8] = 0\n        else:\n            ego_lcf_feat[8] = self.prev_control_cache[0].steer\n\n        command = tick_data['command_near']\n        if command < 0:\n            command = 4\n        command -= 1\n        results['command'] = command\n        command_onehot = np.zeros(6)\n        command_onehot[command] = 1\n        results['ego_fut_cmd'] = command_onehot\n        theta_to_lidar = raw_theta\n        command_near_xy = np.array([tick_data['command_near_xy'][0]-can_bus[0],-tick_data['command_near_xy'][1]-can_bus[1]])\n        rotation_matrix = np.array([[np.cos(theta_to_lidar),-np.sin(theta_to_lidar)],[np.sin(theta_to_lidar),np.cos(theta_to_lidar)]])\n        local_command_xy = rotation_matrix @ command_near_xy\n  \n        ego2world = np.eye(4)\n        ego2world[0:3,0:3] = Quaternion(axis=[0, 0, 1], radians=ego_theta).rotation_matrix\n        ego2world[0:2,3] = can_bus[0:2]\n        lidar2global = ego2world @ self.lidar2ego\n        results['l2g_r_mat'] = lidar2global[0:3,0:3]\n        results['l2g_t'] = lidar2global[0:3,3]\n        stacked_imgs = np.stack(results['img'],axis=-1)\n        results['img_shape'] = stacked_imgs.shape\n        results['ori_shape'] = stacked_imgs.shape\n        results['pad_shape'] = stacked_imgs.shape\n        results = self.inference_only_pipeline(results)\n        self.device=\"cuda\"\n        input_data_batch = mm_collate_to_batch_form([results], samples_per_gpu=1)\n        for key, data in input_data_batch.items():\n            if key != 'img_metas':\n                if torch.is_tensor(data[0]):\n                    data[0] = data[0].to(self.device)\n        output_data_batch = self.model(input_data_batch, return_loss=False, rescale=True)\n        all_out_truck_d1 = output_data_batch[0]['pts_bbox']['ego_fut_preds'].cpu().numpy()\n        all_out_truck =  np.cumsum(all_out_truck_d1,axis=1)\n        out_truck = all_out_truck[command]\n        steer_traj, throttle_traj, brake_traj, metadata_traj = self.pidcontroller.control_pid(out_truck, tick_data['speed'], local_command_xy)\n        if brake_traj < 0.05: brake_traj = 0.0\n        if throttle_traj > brake_traj: brake_traj = 0.0\n\n        control = carla.VehicleControl()\n        self.pid_metadata = metadata_traj\n        self.pid_metadata['agent'] = 'only_traj'\n        control.steer = np.clip(float(steer_traj), -1, 1)\n        control.throttle = np.clip(float(throttle_traj), 0, 0.75)\n        control.brake = np.clip(float(brake_traj), 0, 1)     \n        self.pid_metadata['steer'] = control.steer\n        self.pid_metadata['throttle'] = control.throttle\n        self.pid_metadata['brake'] = control.brake\n        self.pid_metadata['steer_traj'] = float(steer_traj)\n        self.pid_metadata['throttle_traj'] = float(throttle_traj)\n        self.pid_metadata['brake_traj'] = float(brake_traj)\n        self.pid_metadata['plan'] = out_truck.tolist()\n        self.pid_metadata['command'] = command\n        self.pid_metadata['all_plan'] = all_out_truck.tolist()\n\n        #if SAVE_PATH is not None and self.step % 10 == 0:\n        self.save(tick_data,out_truck,output_data_batch)\n        self.prev_control = control\n        \n        if len(self.prev_control_cache)==10:\n            self.prev_control_cache.pop(0)\n        self.prev_control_cache.append(control)\n        return control\n\n\n    def save(self, tick_data,ego_traj,result=None):\n        frame = self.step\n        imgs_with_box = {}\n        for cam, img in tick_data['imgs'].items():\n            imgs_with_box[cam] = self.draw_lidar_bbox3d_on_img(result[0]['pts_bbox']['boxes_3d'], tick_data['imgs'][cam], self.lidar2img[cam], scores=result[0]['pts_bbox']['scores_3d'],labels=result[0]['pts_bbox']['labels_3d'],canvas_size=(900,1600))\n        imgs_with_box['bev'] = self.draw_lidar_bbox3d_on_img(result[0]['pts_bbox']['boxes_3d'], tick_data['bev'], self.coor2topdown, scores=result[0]['pts_bbox']['scores_3d'],labels=result[0]['pts_bbox']['labels_3d'],trajs=result[0]['pts_bbox']['trajs_3d'],canvas_size=(512,512))\n        imgs_with_box['bev'] = self.draw_traj_bev(ego_traj, imgs_with_box['bev'],is_ego=True)\n        imgs_with_box['CAM_FRONT'] = self.draw_traj(ego_traj, imgs_with_box['CAM_FRONT'])\n        for cam, img in imgs_with_box.items():\n            Image.fromarray(img).save(self.save_path / str.lower(cam).replace('cam','rgb') / ('%04d.png' % frame))   \n                \n        outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w')\n        json.dump(self.pid_metadata, outfile, indent=4)\n        outfile.close()\n        \n    def draw_traj(self, traj, raw_img,canvas_size=(900,1600),thickness=3,is_ego=True,hue_start=120,hue_end=80):\n        line = traj\n        lidar2img_rt = self.lidar2img['CAM_FRONT']\n        img = raw_img.copy()\n        pts_4d = np.stack([line[:,0],line[:,1],np.ones((line.shape[0]))*(-1.84),np.ones((line.shape[0]))])\n        pts_2d = ((lidar2img_rt @ pts_4d).T)\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        mask = (pts_2d[:, 0]>0) & (pts_2d[:, 0]<canvas_size[1]) & (pts_2d[:, 1]>0) & (pts_2d[:, 1]<canvas_size[0])\n        if not mask.any():\n            return img\n        pts_2d = pts_2d[mask,0:2]\n        if is_ego:\n            pts_2d = np.concatenate([np.array([[800,900]]),pts_2d],axis=0)\n        try:\n            tck, u = splprep([pts_2d[:, 0], pts_2d[:, 1]], s=0)\n        except:\n            return img\n        unew = np.linspace(0, 1, 100)\n        smoothed_pts = np.stack(splev(unew, tck)).astype(int).T\n        \n        num_points = len(smoothed_pts)\n        for i in range(num_points-1):\n            hue = hue_start + (hue_end - hue_start) * (i / num_points)\n            hsv_color = np.array([hue, 255, 255], dtype=np.uint8)\n            rgb_color = cv2.cvtColor(hsv_color[np.newaxis, np.newaxis, :], cv2.COLOR_HSV2RGB).reshape(-1)\n            rgb_color_tuple = (float(rgb_color[0]),float(rgb_color[1]),float(rgb_color[2]))\n            cv2.line(img,(smoothed_pts[i,0],smoothed_pts[i,1]),(smoothed_pts[i+1,0],smoothed_pts[i+1,1]),color=rgb_color_tuple, thickness=thickness)  \n      \n        return img\n\n\n\n    def draw_traj_bev(self, traj, raw_img,canvas_size=(512,512),thickness=3,is_ego=False,hue_start=120,hue_end=80):\n        if is_ego:\n            line = np.concatenate([np.zeros((1,2)),traj],axis=0)\n        else:\n            line = traj\n        img = raw_img.copy()        \n        pts_4d = np.stack([line[:,0],line[:,1],np.zeros((line.shape[0])),np.ones((line.shape[0]))])\n        pts_2d = (self.coor2topdown @ pts_4d).T\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        mask = (pts_2d[:, 0]>0) & (pts_2d[:, 0]<canvas_size[1]) & (pts_2d[:, 1]>0) & (pts_2d[:, 1]<canvas_size[0])\n        if not mask.any():\n            return img\n        pts_2d = pts_2d[mask,0:2]\n        try:\n            tck, u = splprep([pts_2d[:, 0], pts_2d[:, 1]], s=0)\n        except:\n            return img\n        unew = np.linspace(0, 1, 100)\n        smoothed_pts = np.stack(splev(unew, tck)).astype(int).T\n\n        num_points = len(smoothed_pts)\n        for i in range(num_points-1):\n            hue = hue_start + (hue_end - hue_start) * (i / num_points)\n            hsv_color = np.array([hue, 255, 255], dtype=np.uint8)\n            rgb_color = cv2.cvtColor(hsv_color[np.newaxis, np.newaxis, :], cv2.COLOR_HSV2RGB).reshape(-1)\n            rgb_color_tuple = (float(rgb_color[0]),float(rgb_color[1]),float(rgb_color[2]))\n            if smoothed_pts[i,0]>0 and smoothed_pts[i,0]<canvas_size[1] and smoothed_pts[i,1]>0 and smoothed_pts[i,1]<canvas_size[0]:\n                cv2.line(img,(smoothed_pts[i,0],smoothed_pts[i,1]),(smoothed_pts[i+1,0],smoothed_pts[i+1,1]),color=rgb_color_tuple, thickness=thickness)   \n            elif i==0:\n                break\n        return img\n    \n    def draw_lidar_bbox3d_on_img(self,bboxes3d,raw_img,lidar2img_rt,canvas_size=(900,1600),img_metas=None,scores=None,labels=None,trajs=None,color=(0, 255, 0),thickness=1):\n        img = raw_img.copy()\n        bboxes3d_numpy = bboxes3d.tensor.cpu().numpy()\n        if len(bboxes3d_numpy) == 0:\n            return img\n        corners_3d = bboxes3d.corners\n        num_bbox = corners_3d.shape[0]\n        pts_4d = np.concatenate(\n            [corners_3d.reshape(-1, 3),\n            np.ones((num_bbox * 8, 1))], axis=-1)\n        lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n        if isinstance(lidar2img_rt, torch.Tensor):\n            lidar2img_rt = lidar2img_rt.cpu().numpy()\n        if isinstance(scores, torch.Tensor):\n            scores = scores.cpu().numpy()            \n        if isinstance(labels, torch.Tensor):\n            labels = labels.cpu().numpy()            \n            \n        pts_2d = (lidar2img_rt @ pts_4d.T).T\n        pts_2d[:, 0] /= pts_2d[:, 2]\n        pts_2d[:, 1] /= pts_2d[:, 2]\n        imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)\n        depth = pts_2d[..., 2].reshape(num_bbox, 8)\n        mask1 = ((imgfov_pts_2d[:,:,0]>-1e5) & (imgfov_pts_2d[:,:,0]<1e5)&(imgfov_pts_2d[:,:,1]>-1e5) & (imgfov_pts_2d[:,:,1]<1e5) & (depth > -1) ).all(-1)\n        mask2 = (imgfov_pts_2d.reshape(num_bbox,16).max(axis=-1) - imgfov_pts_2d.reshape(num_bbox,16).min(axis=-1))< 2000\n        mask = mask1 & mask2\n        if scores is not None:\n            mask3 = (scores>=0.3)\n            mask = mask & mask3\n            \n        if not mask.any():\n            return img\n\n        scores = scores[mask] if scores is not None else None\n        labels = labels[mask] if labels is not None else None\n        \n        imgfov_pts_2d = imgfov_pts_2d[mask]\n        num_bbox = mask.sum()\n        if trajs is not None:\n            \n            trajs = trajs[mask]\n            agent_boxes = bboxes3d_numpy[mask]\n            for traj,agent_box,label in zip(trajs,agent_boxes,labels):\n                if label in [0,1,2,3,7]:\n                    for i in range(6):\n                        traj1 = np.concatenate([np.zeros((1,2)),traj[i].reshape(6,2)],axis=0)\n                        traj1 = np.cumsum(traj1,axis=0) + agent_box[None,0:2]\n                        #traj1 = (r_m @ traj1.T).T + agent_box[None,0:2]\n                        if canvas_size==(900,1600):\n                            img = self.draw_traj(traj1,img,hue_start=0,hue_end=20)\n                        else:\n                            img = self.draw_traj_bev(traj1,img,hue_start=0,hue_end=20)\n\n        return self.plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, scores, labels, color, thickness,bev=(canvas_size!=(900,1600))) \n    \n    \n\n    \n    def plot_rect3d_on_img(self,img,num_rects,rect_corners,scores=None,labels=None,color=(0, 255, 0),thickness=1,bev=False):\n        line_indices = ((0, 1), (0, 3), (0, 4), (1, 2), (1, 5), (3, 2), (3, 7),\n                        (4, 5), (4, 7), (2, 6), (5, 6), (6, 7))\n        if bev:\n            line_indices = ((0, 3), (3, 7),(4, 7), (0, 4))\n        for i in range(num_rects):\n            c = COLORMAP[labels[i]]\n            thinck = 2\n            corners = rect_corners[i].astype(np.int)\n            # if scores is not None:\n            #     cv2.putText(img, \"{:.2f}\".format(scores[i]), corners[0], cv2.FONT_HERSHEY_SIMPLEX, 0.3, (0,0,0), 1)\n            if scores[i] < 0.3:\n                continue\n                #     c=(255,255,255)\n                #     thinck=1\n            for start, end in line_indices:\n                cv2.line(img, (corners[start, 0], corners[start, 1]),\n                        (corners[end, 0], corners[end, 1]), c, thinck,\n                        cv2.LINE_AA)\n        return img.astype(np.uint8)\n    \n\n        \n\n    def destroy(self):\n        del self.model\n        torch.cuda.empty_cache()\n\n    def gps_to_location(self, gps):\n        EARTH_RADIUS_EQUA = 6378137.0\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/.pylintrc",
    "content": "[MESSAGES CONTROL]\nmax-line-length=120\ndisable=no-self-use,anomalous-backslash-in-string,too-many-arguments,too-few-public-methods,too-many-instance-attributes,redefined-variable-type,unused-argument,bad-continuation,too-many-lines,too-many-branches,locally-disabled,too-many-locals,too-many-statements,duplicate-code,too-many-nested-blocks,fixme,useless-object-inheritance,no-else-raise,no-else-break,unnecessary-pass,no-else-return,super-with-arguments,no-else-continue,bad-option-value,consider-using-dict-items,consider-using-f-string\nignored-modules=carla,carla.command,agents.navigation.basic_agent,agents.navigation.roaming_agent,agents.tools.misc,agents.navigation.local_planner,agents.navigation.global_route_planner,agents.navigation.global_route_planner_dao,shutil,carla_msgs,nav_msgs,sensor_msgs,std_msgs,tf,cv_bridge,geometry_msgs,rosgraph_msgs,rospy\nvariable-rgx=[a-z0-9_]{1,40}$\nfunction-rgx=[a-z0-9_]{1,40}$\nextension-pkg-whitelist=cv2,pygame,numpy\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/.readthedocs.yml",
    "content": "# Read the Docs configuration file\n# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details\n\nversion: 2\n\nmkdocs:\n  configuration: mkdocs.yml\n\nformats: all\n\npython:\n  version: 3.7\n  install:\n  - requirements: Docs/requirements.txt\n\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/CARLA_VER",
    "content": "HOST = https://carla-releases.s3.eu-west-3.amazonaws.com/Linux\nRELEASE=CARLA_0.9.13\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Dockerfile",
    "content": "from ubuntu:18.04\n\n# Install base libs\nrun apt-get update && apt-get install --no-install-recommends -y libpng16-16=1.6.34-1ubuntu0.18.04.2 \\\nlibtiff5=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 \\\n python3.6 python3.6-dev python3-pip libxerces-c-dev \\\n && rm -rf /var/lib/apt/lists/* \n\n# Install python requirements\nrun 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 \\\n    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\\\n&& mkdir -p /app/scenario_runner \n\n# Install scenario_runner \ncopy . /app/scenario_runner\n\n# setup environment :\n# \n#   CARLA_HOST :    uri for carla package without trailing slash. \n#                   For example, \"https://carla-releases.s3.eu-west-3.amazonaws.com/Linux\".\n#                   If this environment is not passed to docker build, the value\n#                   is taken from CARLA_VER file inside the repository.\n#\n#   CARLA_RELEASE : Name of the package to be used. For example, \"CARLA_0.9.9\".\n#                   If this environment is not passed to docker build, the value\n#                   is taken from CARLA_VER file inside the repository.\n# \n#\n#  It's expected that $(CARLA_HOST)/$(CARLA_RELEASE).tar.gz is a downloadable resource.\n#\n\nenv CARLA_HOST \"\"\nenv CARLA_RELEASE \"\"\n\n# Extract and install python API and resources from CARLA\nrun export DEFAULT_CARLA_HOST=\"$(sed -e 's/^\\s*HOST\\s*=\\s*//;t;d' /app/scenario_runner/CARLA_VER)\" && \\\n    echo \"$DEFAULT_CARLA_HOST\" && \\\n    export CARLA_HOST=\"${CARLA_HOST:-$DEFAULT_CARLA_HOST}\" && \\\n    export DEFAULT_CARLA_RELEASE=\"$(sed -e 's/^\\s*RELEASE\\s*=\\s*//;t;d' /app/scenario_runner/CARLA_VER)\" && \\\n    export CARLA_RELEASE=\"${CARLA_RELEASE:-$DEFAULT_CARLA_RELEASE}\" && \\\n    echo \"$CARLA_HOST/$CARLA_RELEASE.tar.gz\" && \\\n    wget -qO- \"$CARLA_HOST/$CARLA_RELEASE.tar.gz\" | tar -xzv PythonAPI/carla -C / && \\\n    mv /PythonAPI/carla /app/ && \\\n    python3 -m easy_install --no-find-links --no-deps \"$(find /app/carla/ -iname '*py3.*.egg' )\"\n\n\n# Setup working environment\nworkdir /app/scenario_runner\nenv PYTHONPATH \"${PYTHONPATH}:/app/carla/agents:/app/carla\"\nentrypoint [\"/bin/sh\" ]\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/CHANGELOG.md",
    "content": "## Table of Contents\n* [Latest Changes](#latest-changes)\n* [CARLA ScenarioRunner 0.9.13](#carla-scenariorunner-0913)\n* [CARLA ScenarioRunner 0.9.12](#carla-scenariorunner-0912)\n* [CARLA ScenarioRunner 0.9.11](#carla-scenariorunner-0911)\n* [CARLA ScenarioRunner 0.9.10](#carla-scenariorunner-0910)\n* [CARLA ScenarioRunner 0.9.9](#carla-scenariorunner-099)\n* [CARLA ScenarioRunner 0.9.8](#carla-scenariorunner-098)\n* [CARLA ScenarioRunner 0.9.7](#carla-scenariorunner-097)\n* [CARLA ScenarioRunner 0.9.6](#carla-scenariorunner-096)\n* [CARLA ScenarioRunner 0.9.5.1](#carla-scenariorunner-0951)\n* [CARLA ScenarioRunner 0.9.5](#carla-scenariorunner-095)\n* [CARLA ScenarioRunner 0.9.2](#carla-scenariorunner-092)\n\n## Latest changes\n### :rocket: New Features\n\n* New scenarios:\n    - InvadingTurn: vehicles at the opposite direction lane partially invade the ego's one, forcing it to leave space for them,moving slightly off-center.\n    - EnterActorFlow: the ego has to enter a highway lane filled with incoming traffic\n    - MergerIntoslowtraffic. variation of `EnterActorFlow` but with slow traffic.\n    - InterurbanActorFlow and InterurbanAdvancedActorFlow: actor flow scenarios for the new interurban intersections with dedicated lanes present at Town12 and Town13.\n    - Accident: the ego is met with an accident, forcing it to lane change to avoid it.\n    - AccidentTwoWays:  same as `Accident` but having to invade an opposite direction lane.\n    - ParkedObstacle: similar to `Accident` but with a parked obstacle instead.\n    - ParkedObstacleTwoWays:  same as `ParkedObstacle` but having to invade an opposite direction lane.\n    - HazardAtSideLane: similar to `Accident` but with a moving group of bicycles in the rightmost park of the lane\n    - HazardAtSideLaneTwoWays:  same as `HazardAtSideLane` but having to invade an opposite direction lane.\n    - ConstructionObstacleTwoWays: same as `ConstructionObstacle` but having to invade an opposite direction lane.\n    - VehicleOpensDoorTwoWays: similar to `Accident` but this time the blockage is cause by a vehicle opening its door.\n    - StaticCutIn: the ego is meant with an adversary that exits a stopped lane, cutting in front of the ego.\n    - ParkingCutIn: similar to `StaticCutIn` but the adversary starts at a parking lane.\n    - HighwayCutIn: the ego is met with a vehicle that tries to enter the highway by cutting in front of it.\n    - ParkingExit: Only usable at the beginning of the routes, makes the ego start at a parking lane.\n    - HardBreakRoute: uses the BackgroundActivity to make all vehicles in front of the ego hard break.\n    - YieldToEmergencyVehicle: the ego finds an emergency vehicle behind, having to lane chane to give way.\n    - VehicleTurningRoutePedestrian: variation of `VehicleTurningRoute` but with a pedestrian crossing instead of a bycicle.\n    - BlockedIntersection: with low visibility, the ego performs a turn only to find out that the end is blocked by another vehicle.\n    - CrossingBicycleFlow: the ego has to do a turn at an intersection but it has to cross a bycicle lane full of traffic.\n    - PedestrianCrossing: a group of pedestrians crossing a crosswalk. Easier version of `DynamicObjectCrossing` with no occluder.\n    - ParkingCrossingPedestrian: variation of `DynamicObjectCrossing`, but using a parked vehicle as the occluder.\n    - OppositeVehicleTakingPriority: variation of `OppositeVehicleRunningRedLight` but without traffic lights.\n    - NonSignalizedJunctionLeftTurn: variation of `SignalizedJunctionLeftTurn` but without traffic lights.\n    - NonSignalizedJunctionRightTurn: variation of `SignalizedJunctionRightTurn` but without traffic lights.\n    - PriorityAtJunction: utility scenario during routes to add a green traffic light at the next intersection.\n    - NoSignalJunctionCrossingRoute: Does nothing but wait for the ego to exit an intersection.\n* Improvements to old scenarios:\n    - ControlLoss: Added actual noise to the ego's control (currently only during routes).\n    - All VehicleTurning variations: more robustness and better synchronization.\n    - OppositeVehicleRunningRedLight: Improvement synchronization and the opposite vehicle's behavior.\n    - SignalizedJunctionLeftTurn: it is now an actor flow that ego has to cross.\n    - SignalizedJunctionRightTurn. it is now an actor flow that the ego has to merge into.\n    - Renamed `ConstructionSetupCrossing` to `ConstructionObstacle`, and prepared it for routes.\n* Improvements to the CarlaDataProvider:\n    - Added a lock when checking the dictionaries to avoid issues in multithreading\n    - Added the `transform` argument to all register function to avoid returning None during the first frame\n    - Added the `get_global_route_planner` and `get_all_actors` to avoid repeating these costly calls more than necessary\n    - Added `set_runtime_init_mode` and `is_runtime_init_mode`, used by the Leaderboard to initialize scenarios during the simulation\n    - At the `create_blueprint` function, replaced the `safe` argument with the `attribute_filter`, for a more generic parsing of any of the blueprint attributes.\n    - Removed the `CarlaDataProvider.get_ego_vehicle_route()` and `CarlaDataProvider.set_ego_vehicle_route()` functions as this is now information available to all scenarios.\n* Improvements to the routes:\n    - Scenarios are no longer position based, but instead part of a route's xml.\n    - Routes now also include the criteria of its scenarios.\n    - `waypoint` have been renamed to `position` and are part of the `waypoints` category.\n    - More than one `weather` are allowed, creating a dynamic one based on the ego vehicle's completed percentage of the route.\n    - Changed the timeout to also be dependent on the distance driven by the ego vehicle.\n    - Added the `RouteLightsBehavior` to control of all scene and vehicle lights during runtime\n    - Added a new criteria for routes, `CheckMinSpeed`, that checks the ego's speed and compares it with the rest of the traffic\n    - Separated the route argument into two, `route` for the file path, and `route-id`, for the name of route. the functionality remains unchanged.\n    - Simplified the overall parsing.\n* The BackgroundActivity part of the routes has been completely remade, with the objective of creating the sensation of traffic around the ego will increasing the performance\n* Added a Backgroundmanager to interact with the new BackgroundActivity, to allow it to adapt to incoming scenarios\n* Added new atomic behaviors:\n    - SyncArrivalWithAgent\n    - CutIn\n    - AddNoiseToRouteEgo\n    - ConstantVelocityAgentBehavior\n    - AdaptiveConstantVelocityAgentBehavior\n    - WaitForever\n    - BatchActorTransformSetter\n    - OppositeActorFlow\n    - InvadingActorFlow\n    - BicycleFlow\n    - OpenVehicleDoor\n    - SwitchWrongDirectionTest\n    - SwitchMinSpeedCriteria\n    - WalkerFlow\n    - AIWalkerBehavior\n    - ScenarioTimeout\n    - MovePedestrianWithEgo\n* Improved the Criterion class for a more comprehensive base criteria and easier use in the `results_writer` class.\n* Added new atomic criteria:\n    - MinimumSpeedRouteTest\n    - YieldToEmergencyVehicleTest\n    - ScenarioTimeoutTest\n* Added new atomic trigger conditions\n    - WaitUntilInFrontPosition\n* Merged the `Scenario` class into the `BasicScenario` one.\n* Scenarios can now have parameters as part of the their xml definition, which is saved as a dictionary at `config.other_parameters`\n* Simplified and improved how routes are parsed.\n* Added the `wait-for-repetitions` argument at the manual control for a smoother transition between scenarios / repetitions\n* Updated numpy's version to avoid issues with newer version of Python 3\n\n### :bug: Bug Fixes\n* Fixed bug at OtherLeadingVehicle scenario causing the vehicles to move faster than intended\n* Fixed bug causing some debris at ControlLoss scenario to be floating, instead of at ground level\n\n## CARLA ScenarioRunner 0.9.13\n### :rocket: New Features\n* OpenSCENARIO support:\n    - Added support for `ParameterAction`\n    - Extended `ParameterCondition` support to use as an event trigger condition\n\n### :bug: Bug Fixes\n* Fixed metrics parsing and remade the example recordings\n* Fixed a bug with repetitions / scenario groups causing the simulation to crash after the second one.\n* Fixed use of OSC Parameters as entry names for catalogs\n\n### :ghost: Maintenance\n* Removed CARLA example dependencies\n\n## CARLA ScenarioRunner 0.9.12\n### :rocket: New Features\n* OpenSCENARIO support:\n    - Added support for LongitudinalDistanceAction\n    - Extended RelativeDistanceCondition with support for 'longitudinal' and 'lateral' distance along with freespace.\n    - Added support for RelativeRoadPosition\n    - Added support for RoadPosition\n    - Added `--openscenarioparams` argument to overwrite global `ParameterDeclaration`\n    - Added controller using CARLA's autopilot (in replacement for ActivateControllerAction)\n    - Added support for storyboards with multiple stories\n    - Eliminated unnecessary reloads of OpenDRIVE maps\n* Additional Scenarios:\n    - Added Construction setup scenario.\n### :bug: Bug Fixes\n* Fixed LaneOffset (+ vs. -) for OpenSCENARIO\n* Fixed RelativeLanePosition for OpenSCENARIO causing exception when using ds != 0\n* Fixed bug at the Getting Started docs which caused an import error\n* Fixed neverending lane change maneuver in OpenSCENARIO\n* Fixed bug causing the spawning of an actor with `request_new_actor` to never activate the autopilot.\n* Fixed handling of evaluation criteria in OpenSCENARIO (using a delay value of .0 caused an exception)\n### :ghost: Maintenance\n* Extended SimpleVehicleController (OSC) to handle traffic lights\n* Generalized visualizer attached to OSC controllers\n* Fixed bug at the Getting Started docs which caused an import error\n* Improved the watchdog. It can now be paused, resumed and uses the same thread, instead of opening and closing new ones each frame.\n* Added `simple-watchdog-timer` library to the requirements, as it is used by the new watchdog. This requires Python 3.x from now on!\n* Extended CarlaDataProvider's spawning functions to allow filtering the safer blueprint, and optionally tick the server\n* Improved cleanup handling to resolve memory leak issues and resolve timeouts\n\n## CARLA ScenarioRunner 0.9.11\n### :rocket: New Features\n* Added a sensor barrier for the agents to ensure that the simulation waits for them to render their data.\n* Added an option to produce a machine-readable JSON version of the scenario report.\n* Added a static obstacle evasion OpenSCENARIO scenario\n* Added support for OSC Routing options\n* Added support for OSC SynchronizeAction\n* Added support for OSC LaneOffsetAction\n* Added support to place OSC controller implementation alongside the OSC scenario\n* Updated *GameTime.restart()* at *srunner/scenariomanager/timer.py* to also reset the frame number\n### :bug: Bug Fixes\n* Fixed metrics-manager.py failing to run with port argument\n* Fixed exception when using OSC scenarios without EnvironmentAction inside Storyboard-Init\n* Fixed bug causing the TrafficManager to not be correctly updated at asynchronous simualtions\n* Fixed shutdown issue in ScenarioRunner causing to not switch to asynchronous mode\n* Fixed OSC TeleportAction within Story\n* Fixed runtime exception on RouteScenario without an agent parameter \n* Fixed bug causing the InTimeToArrivalToVehicle atomic to crash if one of the actors was a a static object\n* Fixed writing result files when using OpenSCENARIO under Windows (CARLA: prefix is removed from the filename)\n### :ghost: Maintenance\n* Added check to ensure OSC names (for story/act/maneuver) are unique\n\n\n## CARLA ScenarioRunner 0.9.10\n### :rocket: New Features\n* Renamed some agent labels inside Jenkins CI pipelines for new standard proposals.\n* Added support for Jenkins CI pipelines doing automated testing and docker images creation.\n* **Very important:** CarlaActorPool has been removed and all its functions moved to the CarlaDataProvider:\n    - 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.\n    - Changed *ActorConfiguration* to *ActorConfigurationData.parse_from_node*\n    - Renamed the _map_ element at routes to _town_, matching the scenario configuration files\n\n* Added new environment variables needed. They can be seen at (Docs/getting_scenariorunner.md).\n* Improved the visual display of the information from the *output* and *file* arguments.\n* Routes are now deterministic in regards to the spawning scenarios when more than one are at the same location\n* 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.\n* 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.\n* The new weather parameters (related to fog) are now correctly read when running scenarios outside routes.\n* Enable weather animation during scenario execution (requires ephem pip package)\n* Changed manual control to be in par with the CARLA version. Among others, added vehicle lights, recording and some new sensors\n* Removed unsupported scenarios (ChallengeBasic and BackgroundActivity, VehicleTurnLeftAtJunction)\n* 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)\n* Removed the default randomness at the ControlLoss scenario\n* OpenSCENARIO support:\n    - 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:\n        - Pedestrian controller\n        - NPC vehicle controller (based on CARLA LocalPlanner)\n        - Simple vehicle controller to set velocities not brake/throttle, and consider obstacles in the forward-facing region.\n        - External controller (to forward control to external entities)\n    - Added initial speed support for pedestrians for OpenSCENARIO\n    - Support for EnvironmentActions within Story (before only within Init). This allows changing weather conditions during scenario execution\n    - Added support for RelativeSpeedCondition\n    - Added support for AccelerationCondition\n    - Added support for TimeOfDayCondition\n    - Added support for OffroadCondition\n    - Added support for CollisionCondition\n    - Added support for EndOfRoadCondition\n    - Added support for TimeHeadwayCondition\n    - Added support for TrafficSignalCondition\n    - Added support for AcquirePositionAction\n    - Extended FollowLeadingVehicle example to illustrate weather changes\n    - Created example scenarios to illustrate usage of controllers and weather changes\n    - Extended LaneChangeAction to allow lane changes of multiple lanes\n    - Reworked the handling of Catalogs to make it compliant to the 1.0 version (relative paths have to be relative to the scenario file)\n    - The RoadNetwork can be defined as global Parameter\n    - Fixed handling of relative positions with negative offset\n    - Added support for local ParamaterDeclarations\n    - Added support for Parameters within Catalogs\n    - Added support for ParameterAssignments for CatalogReferences\n    - Fixed name handling of Parameters: Parameter declerations must not start with a leading '$', but when the parameter is used a leading '$' is required.\n    - Fixed use of Parameters for multiple instances of the same Catalog element\n    - Fixed use of relative initial positions for any actor\n    - Added possibility to use synchronous execution mode with OpenSCENARIO\n    - Fixed use of relative paths in CustomCommandAction\n    - Fixed use of ControllerCatalogs\n* Atomics:\n    - Several new atomics to enable usage of OSC controllers\n    - WeatherBehavior to simulate weather over time\n    - UpdateWeather to update weather to a new setting, e.g. sun to rain\n    - UpdateRoadFriction to update the road friction while running\n    - new RelativeVelocityToOtherActor trigger condition, used to compare velocities of two actors\n    - new TriggerAcceleration trigger condition which compares a reference acceleration with the actor's one.\n    - new TimeOfDayComparison trigger condition, comparing the simulation time (set up by the new weather system) with a given *datetime*.\n    - Added new *OffRoadTest* criteria.\n    - Added new *EndofRoadTest* criteria, to detect when a vehicle changes between OpenDRIVE roads.\n    - CollisionTest criterion can now filter the collisions for a specific actor, or actor type_id.\n    - 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.\n    - InTimeToArrivalToVehicle has had its two actor arguments swapped, to match all the other behaviors.\n    - Added *along_route* flag to InTimeToArrivalToVehicle, to take into account the topology of the road\n    - Changed the inputs to TrafficLightStateSetter to match the other atomics, but the functionality remains unchanged\n    - Improved LaneChange atomic to allow lane changes of multiple lanes\n\n### :bug: Bug Fixes\n* Fixed bug causing parsing RelativeTargetSpeed tag to fail. \n* Fixed missing 'six' in requirements.txt\n* Support OpenSCENARIO parameters also if they're only part of a string value\n* Support Routes in Catalogs\n* Fix parsing of properties within ControllerCatalogs\n* Add cleanup of instantiated OpenSCENARIO controllers\n* Do not register SIGHUP signal in windows\n* Fixed initial speed of vehicles using OpenSCENARIO\n* Fixed bug causing an exception when calling BasicScenario's *_initialize_actors* with no other_actors.\n* Fixed bug causing the route to be downsampled (introduced by mistake at 0.9.9)\n* Fixed bug causing _output_ argument to not display the correct number with _InRouteTest_ and _RouteCompletionTest_ criterias (the succces and failure was correctly displayed)\n* Fixed bug causing OpenSCENARIO's SpeedCondition to not work as intended\n* Fixed bug causing CollisionConditions not to work properly in OpenSCENARIO\n* Fixed bug causing the *group:* functionality to behave incorrectly when moving scenarios around.\n* Fixed bug causing FollowLeadingVehicle and FollowLeadingVehicleWithObstacle scenarios to not properly end\n* Fixed bug causing CollisionTest to ignore multiple collisions with scene objects\n* Fixed bug causing NoSignalJunctionCrossing to not output the results of the scenario\n* Fixed bug causing SyncArrival to fail when the actor was destroyed after the behavior ended\n* Fixed bug with ending roads near stop signals to break the simulation\n* Fixed exception bug in spawn function of CarlaDataProvider\n* Fixed access to private member of CARLA LocalPlanner inside OSC NpcVehicleControl\n* Fixed bug causing LaneChange to break the simulation if the asked lane change was impossible, instead of correctly stopping it\n* Fixed bug causing ChangeLane scenarios to never end\n* Fixed handling of OSC LanePosition (#625)\n* Fixed bug causing the route repetitions to spawn different background activity\n* Fixed bug causing the rotate_point function inside RunningRedLightTest to not function properly.\n### :ghost: Maintenance\n* Exposed traffic manager port flag to enable the execution of multiple scenarios on a single machine.\n\n## CARLA ScenarioRunner 0.9.9\n### :rocket: New Features\n* OpenSCENARIO support:\n    - Support for OpenSCENARIO 1.0 (a converter for old scenarios is available)\n    - Added support for position with Lane information (roadId and laneId)\n    - Added support to use a non-CARLA OpenDRIVE map (instead of CARLA towns)\n    - Added support for TimeOfDay tag\n    - Added support for scenarios with no actors\n    - Added support for TimeToCollisionCondition with freespace.\n    - Added support for TimeHeadwayCondition with freespace.\n* Scenario updates:\n    - 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.\n* Atomics:\n    - ChangeAutopilot now calls a TM instance, and allows to change its parameters\n    - Added WaitUntilInFront behavior and InTimeToArrivalToVehicleSideLane trigger condition, useful for cut ins\n    - Added new trigger condition, AtRightestLane, which checks if the actor is at the rightmost driving lane\n    - Added new criteria, ActorSpeedAboveThresholdTest, useful to check if the ego vehicle has been standing still for long periods of time.\n* Setting up actors in batch now also randomizes their colors\n* 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.\n* **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:\n    - The path to the autoagents has changed from .../challenge/autoagents to .../autoagents\n    - The path to the route and scenario descriptions has changed from .../challenge to .../data\n### :bug: Bug Fixes\n* Fixed spawning bugs for scenario DynamicObjectCrossing when it is part of a route\n* Fixed spawning bugs for scenarios VehicleTurningRight, VehicleTurningLeft when they are part of a route\n* Fixed bug causing the GPS coordinates given to the agents to be wrongly calculated\n* Fixed bug when setting up actors in batch causing to ignore the spawn points given.\n* Fixed bug where CollisionTest was counting as multiple hits collisions that displaced the actor for a long distance.\n* Fixed bug causing the simulation to end after running in synchronous mode\n* Fixed bug when using the WaypointFollower atomic to create new LocalPlanners for on-the-fly created actors (#502)\n* Fixed bug causing the scenarios to run faster than real time.\n### :ghost: Maintenance\n* Removed perform_carla_tick() function at CarlaDataProvider, which was a workaround for world.tick()\n\n\n## CARLA ScenarioRunner 0.9.8\n### :rocket: New Features\n* Added \"--timeout\" command line parameter to set a user-defined timeout value\n* Scenario updates:\n    - 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.\n* OpenSCENARIO support:\n    - Added initial support for Catalogs (Vehicle, Pedestrian, Environment, Maneuver, and and MiscObject types only)\n### :bug: Bug Fixes\n* Fixed #471: Handling of weather parameter (cloudyness -> cloudiness adaption)\n* Fixed #472: Spawning issue of pedestrians in OpenSCENARIO\n* Fixed #374: Usage of evaluation critieria with multiple ego vehicles in OpenSCENARIO\n* Fixed #459: Add initial support for Catalogs (Vehicle, Pedestrian, Environment, Maneuver, and and MiscObject types only)\n* Fixed wrong StandStill behavior which return SUCCESS immediatly on a standing actor\n* Fixed scenario bug causing junction related scenarios (4, 7, 8 and 9) to not spawn due to lane changes.\n### :ghost: Maintenance\n* Added watchdog to ScenarioManager to handle timeouts and CARLA crashes\n* Added timeout for CARLA tick() calls to avoid blocking CARLA server calls\n\n\n## CARLA ScenarioRunner 0.9.7\n**This is the _first_ release to work with CARLA 0.9.7 (not the patch versions 0.9.7.x)**\n### :rocket: New Features\n* Challenge routes can be directly executed with the ScenarioRunner using the --route option\n* Agents can be used with the ScenarioRunner (currently only for route-based scenarios)\n* New scenarios:\n    - Added example scenario for lane change\n    - Added cut-in example scenario\n* Scenario updates:\n    - Scenarios 7 to 10 are now visible when running routes (instead of being triggered in the background). Their\n      methodology has remained unchanged\n* Scenario atomics:\n    - Added new OutsideRouteLanesTest atomic criter that encompasses both SidewalkTest and WrongLaneTest, returning\n      the percentage of route that has been traveled outside the lane.\n    - InRouteTest is now more forgiving. The max distance has been increased, but staying above the previous one will eventually \n      also cause failure\n    - Changed SidewalkTest atomic criteria to also track other type of out of lane conditions\n    - SidewalkTest and WrongLaneTest atomic criterias now track the amount of meters traversed\n    - CollisionTest atomic criteria now correctly ignores multiple micro-collisions with the same object\n    - Added LaneChange and TrafficLightSateSetter behavior atomics\n    - Added AccelerateToCatchUp behavior atomic\n    - Added get_transform() method for CarlaDataProvider\n    - Added support for weather conditions\n    - Added basic version check to ensure usage of correct CARLA version\n    - WaypointFollower atomic can handle pedestrians\n    - Extensions in WaypointFollower atomic for consecutive WaypointFollowers (one WF cancels the previous one)\n* Extended OpenScenario support:\n    - Added support for UserDefinedActions (e.g. to run additional scripts)\n    - Added init speed behavior for vehicles\n    - Added support for relative velocities\n    - Extended convert_position_to_transform with RelativeWorld, RelativeObject and RelativeLane osc_positions\n    - Added new trigger atomics InTriggerDistanceToOSCPosition and InTimeToArrivalToOSCPosition to support relative osc_positions\n    - Added new atomic behaviour ActorTransformSetterToOSCPosition\n    - Workaround for relative osc_positions: World is started earlier to support relative osc_positions in story init\n    - Added delay condition support in convert_condition_to_atomic\n    - Added support for pedestrians\n    - Full support for SimulationTime condition\n    - Added weather support\n    - Updated implementation to be closer to upcoming OpenSCENARIO standard\n    - AfterTermination, AtStart conditions are supported\n    - Added initial support for lateral action: LaneChange\n    - Added initial support for OSCGlobalAction to set state of traffic signal\n    - FollowRoute action is supported for vehicles and pedestrians, for global world positions.\n    - Added support for RoadCondition: Friction\n    - Redundant rolename object property is no longer required\n    - Added support for global parameters\n    - 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.\n    - Added support to change actor color\n    - Added support for a default actor model, in case the stated model is not available\n    - Added support for MiscObjects (besides vehicles and pedestrians)\n    - 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\n    - Actor physics can now be set via Object Properties (<Property name=\"physics\" value=\"off\" />)\n### :bug: Bug Fixes\n* Fixed wrong handling of OpenSCENARIO ConditionGroups, which should be handled as parallel composites, not sequences\n* Fixed #443: Repetitions in OpenSCENARIO were not properly working\n* Fixed bug causing RunningStopTest atomic criteria to trigger when lane changing near a STOP signal\n* Fixed bug causing RunningRedLightTest atomic criteria to occasionally not trigger\n* Fixed bug causing occasional frame_errors\n* Fixed #426: Avoid underground vehicles fall forever by disabling physics when spawning underground.\n* Fixed #427: Removed unnecessary warnings when using get_next_traffic_light() with non-cached locations\n* Fixed missing ego_vehicle: compare actor IDs instead of object in CarlaDataProvider in get_velocity, get_transform and get_location\n* Avoided use of 'controller.ai.walker' as walker type in DynamicObjectCrossing scenario\n* Fixed WaypointFollower behavior to use m/s instead of km/h\n* Fixed starting position of VehicleTurnLeft/Right scenarios\n* Fixed spawn_point modification inside CarlaActorPool.setup_actor()\n* Fixed result of DrivenDistanceTest\n* Fixed exception in manual_control on fps visualization\n* Cleanup of pylint errors for all autonomous agents\n* Fixed randomness of route-based scenarios\n* Fixed usage of radians instead of degrees for OpenSCENARIO\n* Fixed ActorTransformSetter behavior to avoid vehicles not reaching the desired transform\n* Fixed spawning of debris for ControlLoss scenario (Scenario01)\n* Fixed CTRL+C termination of ScenarioRunner\n### :ghost: Maintenance\n* Increased speed of actor initialization by using CARLA batch mode and buffering CARLA blueprint library\n* Split of behaviors into behaviors and conditions\n* Moved atomics into new submodule scenarioatomics\n* Updated documentation for all behaviors, conditions and test criteria\n* Refactoring of scenario configurations and parsers\n* Extended WaypointFollower atomic behavior to be able to use the current actor speed\n* Removed usage of 'import *' to have cleaner Python imports\n* Removed broad-except and bare-except where possible\n* Python-Scenarios: Removed obsolete categories\n* ScenarioRunner: Removed scenario dictonary, use imports directly\n* CarlaDataProvider: Simplified update_light_states() to remove code duplication\n* Timer: class TimeOut() is derived from SimulationTimeCondition() to  avoid code duplication\n* Moved backported py_trees classes and methods to tools/py_trees_port.py to avoid code duplication\n* Removed setup_environment.sh\n* Adaptions to CARLA API Changes\n     - Renamed GnssEvent to GnssMeasurement\n\n## CARLA ScenarioRunner 0.9.6\n**This is the _first_ release to work with CARLA 0.9.6**\n### :ghost: Maintenance\n* Adapted to CARLA API changes\n    - Frame rate is set now via Python\n    - Renamed frame_count and frame_number to frame\n    - Removed wait_for_tick() calls\n\n\n## CARLA ScenarioRunner 0.9.5.1\n**This is the _last_ release that works with CARLA 0.9.5**\n### :rocket: New Features\n* Added initial support for OpenScenario v0.9.1\n* Added support for multiple ego vehicles plus an example\n* Added commandline option for output directory\n* Added option to load external scenario implementations (in python)\n* Added option to scenario_runner to load external scenario XMLs\n* Atomic behaviors:\n    - Extended KeepVelocity atomic behavior to support duration/distance\n      based termination\n    - Extended StandStill atomic behavior to support duration based\n      termination\n    - Added behavior to activate/deactivate autopilot\n### :bug: Bug Fixes\n* Fixed WaypointFollower initialization\n\n\n## CARLA ScenarioRunner 0.9.5\n**This is the _first_ release to work with CARLA 0.9.5**\n### :rocket: New Features\n* Added support for CARLA challenge\n    - Added logging functionalities to challenge_evaluator_routes.py\n    - Added wall clock timeout for the CARLA challenge\n    - Added background scenario to generate dynamic traffic using autopilot\n    - Updated compatibility with Python 2.7 for the challenge evaluator\n    - Updated WaypointFollower behavior\n    - Added detect_lane_obstacle() helper function which identifies if an obstacle is present in front of the reference actor\n    - Added test to detect vehicles running a stop\n    - Updated the reference position for a scenario is now called trigger_point\n    - Added universal access to the map without re-calling get_map()\n    - Added criteria_enable flag to enable/disable criteria tree\n    - Added multiple helper methods for generic scenario execution.\n    - Added pseudo-sensors for SceneLayoutMeasurements and ObjectMeasurements for Track4 of the CARLA AD challenge\n    - Added track identification for autonomous_agent.py\n    - Added HDMap pseudo-sensor\n    - Added new traffic event logger\n    - Added various helper methods to allow generic scenario execution\n    - Added method to calculate distance along a route\n    - In challenge mode spawn exception are caught and the corresponding scenario is removed\n* Added new atomic behaviors using py_trees behavior tree library\n    - BasicAgentBehavior: drive to target location using CARLA's BasicAgent\n    - StandStill: check if a vehicle stands still\n    - InTriggerDistanceToNextIntersection: check if a vehicle is within certain distance with respect to the next intersection\n    - WaypointFollower: follows auto-generated waypoints indefinitely or follows a given waypoint list\n    - HandBrakeVehicle: sets the handbrake value for a given actor\n    - ActorDestroy: destroys a given actor\n    - ActorTransformSetter: sets transform of given actor\n    - ActorSource: creates actors indefinitely around a location if no other vehicles are present within a threshold\n    - ActorSink: indefinitely destroys vehicles that wander close to a location within a threshold\n    - InTriggerDistanceToLocationAlongRoute: check if an actor is within a certain distance to a given location along a given route\n* Added new atomic evaluation criteria\n    - Added running red light test\n    - Added running stop test\n    - Added wrong way test\n* Added NHTSA Traffic Scenarios\n    - Updated all traffic scenarios to let the other actors appear upon scenario triggering and removal on scenario end\n    - ManeuverOppositeDirection: hero vehicle must maneuver in the opposite lane to pass a leading vehicle.\n    - OtherLeadingVehicle: hero vehicle must react to the deceleration of leading vehicle and change lane to avoid collision and follow the vehicle in changed lane\n    - 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.\n    - SignalizedJunctionLeftTurn : hero vehicle is turning left at signalized intersection, cuts across the path of another vehicle coming straight crossing from an opposite direction.\n### :bug: Bug Fixes\n* Fixed SteerVehicle atomic behavior to keep vehicle velocity    \n### :ghost: Maintenance\n* Reworked scenario execution\n    - Updated folder structure and naming convention in lowercase\n    - Extended CarlaDataProvider with method to get next relevant traffic light\n    - Every scenario has to have a configuration provided as XML file.\n      Currently there is one XML file for each scenario class\n    - The scenario runner is now responsible for spawning/destroying the ego vehicle\n    - Added a CarlaActorPool to share scenario-related actors between scenarios and the scenario_runner\n    - Renamed vehicle -> actor\n    - If all scenarios in one configurations file should be executed, the scenario_runner can be started with --scenario group:<CONFIG_FILE>\n    - Generalized ControlLoss and FollowLeadingVehicle scenarios\n    - Added randomization option to scenario_runner and scenarios\n    - The scenario behavior always starts with a wait behavior until the ego vehicle reached the scenario starting position\n    - Created method _initialize_actors in basic scenario that can be overridden for scenario specific actor initialization\n* Updated NHTSA Traffic Scenarios\n    - OppositeVehicleRunningRedLight: Updated to allow execution at different locations    \n\n\n## CARLA ScenarioRunner 0.9.2\n**This release is designed to work with CARLA 0.9.2**\n### :rocket: New Features\n* Added Traffic Scenarios engine to reproduce complex traffic situations for training and evaluating driving agents\n* Added NHTSA Traffic Scenarios\n    - FollowLeadingVehicle: hero vehicle must react to the deceleration of a leading vehicle\n    - FollowLeadingVehicleWithObstacle: hero vehicle must react to a leading vehicle due to an obstacle blocking the road\n    - StationaryObjectCrossing: hero vehicle must react to a cyclist or pedestrian blocking the road\n    - DynamicObjectCrossing: hero vehicle must react to a cyclist or pedestrian suddenly crossing in front of it\n    - OppositeVehicleRunningRedLight: hero vehicle must avoid a collision at an intersection regulated by traffic lights when the crossing traffic runs a red light\n    - NoSignalJunctionCrossing: hero vehicle must cross a non-signalized intersection\n    - VehicleTurningRight: hero vehicle must react to a cyclist or pedestrian crossing ahead after a right turn\n    - VehicleTurningLeft: hero vehicle must react to a cyclist or pedestrian crossing ahead after a left turn\n    - ControlLoss: Hero vehicle must react to a control loss and regain its control\n* Added atomic behaviors using py_trees behavior trees library\n    - InTriggerRegion: new behavior to check if an object is within a trigger region\n    - InTriggerDistanceToVehicle: check if a vehicle is within certain distance with respect to a reference vehicle\n    - InTriggerDistanceToLocation: check if a vehicle is within certain distance with respect to a reference location\n    - TriggerVelocity: triggers if a velocity is met\n    - InTimeToArrivalToLocation:  check if a vehicle arrives within a given time budget to a reference location\n    - InTimeToArrivalToVehicle: check if a vehicle arrives within a given time budget to a reference vehicle\n    - AccelerateToVelocity: accelerate until reaching requested velocity\n    - KeepVelocity: keep constant velocity\n    - DriveDistance: drive certain distance\n    - UseAutoPilot: enable autopilot\n    - StopVehicle: stop vehicle\n    - WaitForTrafficLightState: wait for the traffic light to have a given state\n    - SyncArrival: sync the arrival of two vehicles to a given target\n    - AddNoiseToVehicle: Add noise to steer as well as throttle of the vehicle\n    - CutInWithStaticVehicle:Based on the code of ParkingCutIn,realized the cutin function of a static vehicle on the highway\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/CODE_OF_CONDUCT.md",
    "content": "# Contributor Covenant Code of Conduct\n\n## Our Pledge\n\nIn the interest of fostering an open and welcoming environment, we as\ncontributors and maintainers pledge to making participation in our project and\nour community a harassment-free experience for everyone, regardless of age, body\nsize, disability, ethnicity, gender identity and expression, level of experience,\neducation, socio-economic status, nationality, personal appearance, race,\nreligion, or sexual identity and orientation.\n\n## Our Standards\n\nExamples of behavior that contributes to creating a positive environment\ninclude:\n\n* Using welcoming and inclusive language\n* Being respectful of differing viewpoints and experiences\n* Gracefully accepting constructive criticism\n* Focusing on what is best for the community\n* Showing empathy towards other community members\n\nExamples of unacceptable behavior by participants include:\n\n* The use of sexualized language or imagery and unwelcome sexual attention or\n  advances\n* Trolling, insulting/derogatory comments, and personal or political attacks\n* Public or private harassment\n* Publishing others' private information, such as a physical or electronic\n  address, without explicit permission\n* Other conduct which could reasonably be considered inappropriate in a\n  professional setting\n\n## Our Responsibilities\n\nProject maintainers are responsible for clarifying the standards of acceptable\nbehavior and are expected to take appropriate and fair corrective action in\nresponse to any instances of unacceptable behavior.\n\nProject maintainers have the right and responsibility to remove, edit, or\nreject comments, commits, code, wiki edits, issues, and other contributions\nthat are not aligned to this Code of Conduct, or to ban temporarily or\npermanently any contributor for other behaviors that they deem inappropriate,\nthreatening, offensive, or harmful.\n\n## Scope\n\nThis Code of Conduct applies both within project spaces and in public spaces\nwhen an individual is representing the project or its community. Examples of\nrepresenting a project or community include using an official project e-mail\naddress, posting via an official social media account, or acting as an appointed\nrepresentative at an online or offline event. Representation of a project may be\nfurther defined and clarified by project maintainers.\n\n## Enforcement\n\nInstances of abusive, harassing, or otherwise unacceptable behavior may be\nreported by contacting the project team at [INSERT EMAIL ADDRESS]. All\ncomplaints will be reviewed and investigated and will result in a response that\nis deemed necessary and appropriate to the circumstances. The project team is\nobligated to maintain confidentiality with regard to the reporter of an incident.\nFurther details of specific enforcement policies may be posted separately.\n\nProject maintainers who do not follow or enforce the Code of Conduct in good\nfaith may face temporary or permanent repercussions as determined by other\nmembers of the project's leadership.\n\n## Attribution\n\nThis Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4,\navailable at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html\n\n[homepage]: https://www.contributor-covenant.org\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/CONTRIBUTING.md",
    "content": "Contributing to CARLA\n=====================\n\nWe are more than happy to accept contributions!\n\nHow can I contribute?\n\n  * Reporting bugs\n  * Feature requests\n  * Improving documentation\n  * Code contributions\n\nReporting bugs\n--------------\n\nUse our [issue section][issueslink] on GitHub. Please check before that the\nissue is not already reported, and make sure you have read our CARLA\n[Documentation][docslink] and [FAQ][faqlink].\n\n[issueslink]: https://github.com/carla-simulator/scenario_runner/issues\n[docslink]: http://carla.readthedocs.io\n[faqlink]: http://carla.readthedocs.io/en/latest/faq/\n\nFeature requests\n----------------\n\nPlease check first the list of [feature requests][frlink]. If it is not there\nand you think is a feature that might be interesting for users, please submit\nyour request as a new issue.\n\n[frlink]: https://github.com/carla-simulator/scenario_runner/issues?q=is%3Aissue+is%3Aopen+label%3A%22feature+request%22+sort%3Acomments-desc\n\nImproving documentation\n-----------------------\n\nIf you feel something is missing in the documentation, please don't hesitate to\nopen an issue to let us know. Even better, if you think you can improve it\nyourself, it would be a great contribution to the community!\n\nWe build our documentation with [MkDocs](http://www.mkdocs.org/) based on the\nMarkdown files inside the \"Docs\" folder. You can either directly modify them on\nGitHub or locally in your machine.\n\nOnce you are done with your changes, please submit a pull-request.\n\n**TIP:** You can build and serve it locally by running `mkdocs` in the project's\nmain folder\n\n    $ sudo pip install mkdocs\n    $ mkdocs serve\n\nCode contributions\n------------------\n\nSo you are considering making a code contribution, great! we love to have\ncontributions from the community.\n\nBefore starting hands-on on coding, please check out our\n[issue board][wafflelink] to see if we are already working on that, it would\nbe a pity putting an effort into something just to discover that someone else\nwas already working on that. In case of doubt or to discuss how to proceed,\nplease contact one of us (or send an email to carla.simulator@gmail.com).\n\n[wafflelink]: https://waffle.io/carla-simulator/scenario_runner\n\n#### What should I know before I get started?\n\nCheck out the [\"CARLA Documentation\"][docslink] to get an idea on CARLA. In\naddition you may want to check the [Getting started](getting_started.md) document.\n\n[docslink]: http://carla.readthedocs.io\n\n#### Coding standard\n\nPlease follow the current [coding standard](coding_standard.md) when submitting\nnew code.\n\n#### Pull-requests\n\nOnce you think your contribution is ready to be added to CARLA, please submit a\npull-request.\n\nTry to be as descriptive as possible when filling the pull-request description.\nAdding images and gifs may help people to understand your changes or new\nfeatures.\n\nPlease note that there are some checks that the new code is required to pass\nbefore we can do the merge. The checks are automatically run by the continuous\nintegration system, you will see a green tick mark if all the checks succeeded.\nIf you see a red mark, please correct your code accordingly.\n\n###### Checklist\n\n  - [ ] Your branch is up-to-date with the `master` branch and tested with latest changes\n  - [ ] Extended the README / documentation, if necessary\n  - [ ] Code compiles correctly\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/FAQ.md",
    "content": "# Frequently Asked Questions\n\n## I receive the error \"TypeError: 'instancemethod' object has no attribute '__getitem__'\" in the agent navigation\n\nThis issue is most likely caused by an outdated version of the Python Networkx package. Please remove the current installation\n(e.g. sudo apt-get remove python-networkx) and install it using \"pip install --user networkx==2.2\".\n\n## No scenario visible and I receive the message \"No more scenarios .... Exiting\"\n\nIn case you receive the following output\n```\nPreparing scenario: FollowLeadingVehicle_1\nScenarioManager: Running scenario FollowVehicle\nResetting ego-vehicle!\nFailure!\nResetting ego-vehicle!\nERROR: failed to destroy actor 527 : unable to destroy actor: not found\nNo more scenarios .... Exiting\n```\nand you see nothing happening, it is most likely due to the fact, that you did not launch a program to control\nthe ego vehicle. Run for example manual_control.py, and you should now see something happening.\n\n\n## Scenario Runner exits with error when using --debug commandline parameter\n\nIn case you receive the following output\n```\nUnicodeEncodeError: 'ascii' codec can't encode character '\\u2713' in position 58: ordinal not in range(128)\n```\nPlease set environment variable\n```\nPYTHONIOENCODING=utf-8\n```\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/agent_evaluation.md",
    "content": "#### Setting up your agent for evaluation\n\n## 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\n\nTo have your agent evaluated by the challenge evaluation system\nyou must define an Agent class that inherits the\n[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.\n\nOn your agent class there are three main functions to be overwritten\nthat need to be defined in order to set your agent to run.\nFurther you also should consider the route to the goal that is\ninitially set as a variable.\n\n\n##### The \"setup\" function:\nThis is the function where you should make all the necessary setup\nfor the your agent.\n\nThis function receives as a parameter the path to a configuration\nfile to be parsed by the user.\n\nWhen executing the \"challenge_evaluator.py\" you should pass the\nconfiguration file path as a parameter. For example:\n\n```\npython srunner/challenge/challenge_evaluator_routes.py  --agent=<path_to_my_agent> --config=myconfigfilename.format\n```\n\n\n##### The \"sensors\" function:\n\nThis function is where you set all the sensors required by your agent.\nFor instance, on the dummy agent sample class the following sensors are defined:\n\n```Python\ndef sensors(self):\n    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'},\n               {'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'},\n               {'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'},\n               {'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'},\n               {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'},\n               {'type': 'sensor.speedometer','reading_frequency': 25, 'id': 'speed'}\n              ]\n    return sensors\n```\n\n\nEvery sensor is a dictionary where you should\nspecify:\n\n* 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.\n* id: the label that will be given to the sensor in order for it to be accessed later.\n* other parameters: these are sensor dependent, such as position, 'x' and 'y', or the field of view for a camera, 'fov'\n\n\n\n\n##### The \"run_step\" function:\n\nThis function is called on every step of the simulation from the challenge evaluation\nan receives some input data as parameter.\n\nThis input data is a dictionary with all the sensors specified on the \"sensors\" function.\n\nThis function should return a [vehicle control](https://carla.readthedocs.io/en/latest/python_api_tutorial/#vehicles)\n to be applied into the ego vehicle.\n\n\n\n\n##### The initial route:\n\nOn the beginning of the execution, the entire route that the hero agent\nshould travel is set on  the \"self.global_plan\" variable:\n\n```\n[({'z': 0.0, 'lat': 48.99822669411668, 'lon': 8.002271601998707}, <RoadOption.LANEFOLLOW: 4>),\n ({'z': 0.0, 'lat': 48.99822669411668, 'lon': 8.002709765148996}, <RoadOption.LANEFOLLOW: 4>),\n ...\n ({'z': 0.0, 'lat': 48.99822679980298, 'lon': 8.002735250105061}, <RoadOption.LANEFOLLOW: 4>)]`\n ```\n\n It is represented as a list of tuples, containing the route waypoints, expressed in latitude\n and longitude and the current road option recommended. For an intersection, the option can\n be go straight, turn left or turn right. For the rest of the route the recommended option\n is lane follow.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/coding_standard.md",
    "content": "<h1>Coding standard</h1>\n\n> _This document is a work in progress and might be incomplete._\n\nGeneral\n-------\n\n  * Use spaces, not tabs.\n  * Avoid adding trailing whitespace as it creates noise in the diffs.\n  * Comments should not exceed 120 columns, code may exceed this limit a bit in\n    rare occasions if it results in clearer code.\n\nPython\n------\n\n  * All code must be compatible with Python 2.7, 3.5, and 3.6.\n  * [Pylint][pylintlink] should not give any error or warning (few exceptions\n    apply with external classes like `numpy`, see our `.pylintrc`).\n  * Python code follows [PEP8 style guide][pep8link] (use `autopep8` whenever\n    possible).\n\n[pylintlink]: https://www.pylint.org/\n[pep8link]: https://www.python.org/dev/peps/pep-0008/\n\nC++\n---\n\n  * Compilation should not give any error or warning\n    (`clang++ -Wall -Wextra -std=C++14 -Wno-missing-braces`).\n  * Unreal C++ code (CarlaUE4 and Carla plugin) follow the\n    [Unreal Engine's Coding Standard][ue4link] with the exception of using\n    spaces instead of tabs.\n  * LibCarla uses a variation of [Google's style guide][googlelink].\n\n[ue4link]: https://docs.unrealengine.com/latest/INT/Programming/Development/CodingStandard/\n[googlelink]: https://google.github.io/styleguide/cppguide.html\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/creating_new_scenario.md",
    "content": "# Create a new scenario tutorial\n\nThis tutorial describes how you can create and run a new scenario using the\nScenarioRunner and the ScenarioManager suite.\n\nLet us call the new scenario _NewScenario_. To create it, there are only few\nsteps required.\n\n## Creating an empty Python class\nGo to the Scenarios folder and create a new Python class with the name\n_NewScenario_ in a new Python file (_new_scenario.py_). The class should be\nderived from the _BasicScenario_ class. As a result, the class should look as\nfollows:\n\n   ```\n   class NewScenario(BasicScenario):\n       \"\"\"\n       Some documentation on NewScenario\n       :param world is the CARLA world\n       :param ego_vehicles is a list of ego vehicles for this scenario\n       :param config is the scenario configuration (ScenarioConfiguration)\n       :param randomize can be used to select parameters randomly (optional, default=False)\n       :param debug_mode can be used to provide more comprehensive console output (optional, default=False)\n       :param criteria_enable can be used to disable/enable scenario evaluation based on test criteria (optional, default=True)\n       :param timeout is the overall scenario timeout (optional, default=60 seconds)\n       \"\"\"\n\n       # some ego vehicle parameters\n       # some parameters for the other vehicles\n\n       def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                    timeout=60):\n           \"\"\"\n           Initialize all parameters required for NewScenario\n           \"\"\"\n\n           # Call constructor of BasicScenario\n           super(NewScenario, self).__init__(\n             \"NewScenario\",\n             ego_vehicles,\n             config,\n             world,\n             debug_mode,\n             criteria_enable=criteria_enable)\n\n\n       def _create_behavior(self):\n           \"\"\"\n           Setup the behavior for NewScenario\n           \"\"\"\n\n       def _create_test_criteria(self):\n           \"\"\"\n           Setup the evaluation criteria for NewScenario\n           \"\"\"\n   ```\n\n## Filling the Python class\n\nIn the NewScenario class, you have to define the following methods mentioned\nin the code example.\n\n### Initialize Method\nThe initialize method is intended to setup all parameters required\nfor the scenario and all vehicles. This includes selecting the correct vehicles,\nspawning them at the correct location, etc. To simplify this, you may want to\nuse the _setup_vehicle()_ function defined in basic_scenario.py\n\n### CreateBehavior method\nThis method should setup the behavior tree that contains the behavior of all\nnon-ego vehicles during the scenario. The behavior tree should use py_trees and\nthe atomic behaviors defined in _atomic_scenario_behavior.py_\n\n### CreateTestCriteria method\nThis method should setup a list with all evaluation criteria for the scenario.\nThe criteria should be based on the atomic criteria defined in\n_atomic_scenario_criteria.py_.\n\nNote: From this list a parallel py_tree will be created automatically!\n\n## Adding the scenario configuration\nFinally the scenario configuration should be added to the examples/ folder. If you\nextend an already existing scenario module, you can simply extend the corresponding\nXML, otherwise add a new XML file. In this case you can use any of the existing\nXML files as blueprint.\n\nIf you want to add multiple ego vehicles for a scenario, make sure that they use different\nrole names, e.g.\n```\n    <scenario name=\"MultiEgoTown03\" type=\"FreeRide\" town=\"Town03\">\n        <ego_vehicle x=\"207\" y=\"59\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" rolename=\"hero\"/>\n        <ego_vehicle x=\"237\" y=\"-95.0754252474\" z=\"0\" yaw=\"90\" model=\"vehicle.tesla.model3\" rolename=\"hero2\"/>\n    </scenario>\n```\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/extra.css",
    "content": ".build-buttons{\n    text-align: center;\n}\n\n.build-buttons > p {\n    display: inline-block;\n    vertical-align: top;\n    padding: 5px;\n}\n\n.vector-zero {\n    text-align: center;\n}\n\n\n/************************* DEFAULT TABLES **************************/\n\ntable {\n  border: 1px solid #242424;\n  background-color: #f3f6f6;\n  text-align: left;\n  border-collapse: collapse;\n}\n\ntable thead {\n  background: #ffffff; \n  border-bottom: 1px solid #444444;\n}\n\ntable tr:nth-child(even) {\n  background: #ffffff;\n}\n\ntable thead th {\n  padding: 7px 13px;\n}\n\ntable tbody td{\n  padding: 7px 13px;\n}\n\n/************************* TOWN SLIDER **************************/\n\n * {box-sizing:border-box}\n\n/* Container */\n.townslider-container {\n  max-width: 1000px;\n  position: relative;\n  margin: auto;\n}\n\n/* Hide the images by default */\n.townslide {\n  display: none;\n  text-align: center; \n\n}\n\n/* Fading animation for slides */\n.fade {\n  -webkit-animation-name: fade;\n  -webkit-animation-duration: 1.5s;\n  animation-name: fade;\n  animation-duration: 1.5s;\n}\n\n@-webkit-keyframes fade {\n  from {opacity: .4}\n  to {opacity: 1}\n}\n\n@keyframes fade {\n  from {opacity: .4}\n  to {opacity: 1}\n}\n\n/* \"next\" and \"previous\" buttons */\n.prev, .next {\n  cursor: pointer;\n  position: absolute;\n  top: 50%;\n  width: auto;\n  margin-top: -22px;\n  padding: 16px;\n  color: white;\n  font-weight: bold;\n  font-size: 18px;\n  transition: 0.6s ease;\n  border-radius: 0 3px 3px 0;\n  user-select: none;\n}\n\n/* Position the \"next\" button*/\n.next {\n  right: 0;\n  border-radius: 3px 0 0 3px;\n}\n\n/* Black background color to buttons when hovering*/\n.prev:hover, .next:hover {\n  background-color: rgba(0,0,0,0.8);\n}\n\n/* Caption text for towns */\n.text {\n  color: #f2f2f2;\n  font-size: 15px;\n  padding: 8px 12px;\n  position: absolute;\n  bottom: 8px;\n  width: 100%;\n  text-align: center;\n  /*background-color:rgba(0,0,0,0.5);*/\n}\n\n/* The dot indicators for slides */\n.dot {\n  cursor: pointer;\n  height: 15px;\n  width: 15px;\n  margin: 0 2px;\n  background-color: #bbb;\n  border-radius: 50%;\n  display: inline-block;\n  transition: background-color 0.6s ease;\n}\n\n.active, .dot:hover {\n  background-color: #717171;\n}\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/getting_scenariorunner.md",
    "content": "# Get ScenarioRunner\n\nThis 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.  \n\n*   __[Installation summary](#installation-summary)__  \n*   __[A. Download a ScenarioRunner release](#a.-download-a-scenariorunner-release)__  \n\t*   [Update the release](#update-the-release)  \n*   __[B. Download ScenarioRunner from source](#b.-build-scenariorunner-from-source)__  \n\t*   [Update the build from source](#update-the-build-from-source)  \n*   __[Run a test](#run-a-test)__  \n\n---\n## Installation summary\n\n<details>\n   <summary>\n    Show command line summary for the quick start installation\n   </summary>\n\n```sh\n# Decide whether to use a package or make the build from source\n\n\n# Option A) Use a ScenarioRunner package\n   # 1. Install a CARLA package: \n      https://carla.readthedocs.io/en/latest/start_quickstart/\n   # 2. Download the matching ScenarioRunner package: \n      https://github.com/carla-simulator/scenario_runner/releases\n   # 3. Extract the content wherever needed. \n\n   # Update the release: \n   # 1. Delete previous CARLA and ScenarioRunner versions.\n   # 2. Download the latest CARLA release. \n   # 3. Download the matching ScenarioRunner release.\n\n\n# Option B) Download ScenarioRunner from source\n   # 1. Build CARLA from source:\n      https://carla.readthedocs.io/en/latest/build_linux/\n   # 2. Clone the ScenarioRunner repository: \ngit clone https://github.com/carla-simulator/scenario_runner.git\n   # 3. Install requirements according to the Python version to be used: \n   # For Python 2.x:\nsudo apt remove python-networkx #if installed, remove old version of networkx\npip2 install --user -r requirements.txt\n   # For Python 3.x: \nsudo apt remove python3-networkx #if installed, remove old version of networkx\npip3 install --user -r requirements.txt\n\n   # To update ScenarioRunner from source:\n   # 1. Update CARLA: \n      https://carla.readthedocs.io/en/latest/build_update/\n   # 2. Go to the ScenarioRunner repository, master branch\ncd ~/scenario_runner\ngit branch master\n   # 3. Pull the latest changes from the repository\ngit pull \n\n```\n</details>\n\n\n---\n## A. Download a ScenarioRunner release\n\nThe releases of ScenarioRunner are packages containing:  \n*   A ScenarioRunner version tied to a specific CARLA release.  \n*   A few example scenarios written in Python.  \n\nThe process to run a ScenarioRunner release is quite straightforward.  \n\n__1. Download a CARLA release.__ Follow the process in the [CARLA quick start](https://github.com/carla-simulator/carla/releases).  \n__2. Download the matching ScenarioRunner release.__ All of the releases are listed [here](https://github.com/carla-simulator/scenario_runner/releases).\n\n!!! Important\n    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.  \n\n__3. Extract the content.__ The directory does not matter.  \n\n\n### Update the release\n\nThe 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:  \n\n*   [CARLA releases](https://github.com/carla-simulator/carla/releases)  \n*   [Scenario Runner releases](https://github.com/carla-simulator/scenario_runner/releases)  \n\nTo run the latest or any other release, delete the previous and install the one desired.  \n\n---\n## B. Download ScenarioRunner from source\n\nThe 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.  \n\n__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/).  \n\n!!! Important\n    ScenarioRunner needs CARLA to run, so the minimum requirements for CARLA stated in the docs are also necessary to run ScenarioRunner.  \n\n__2. Clone the ScenarioRunner repository.__\n\n```sh\ngit clone https://github.com/carla-simulator/scenario_runner.git\n```\n\n__3. Install the requirements according to the Python version to be used.__  First go to the main ScenarioRunner directory\n\n```sh\ncd ~/scenario_runner/\n```\n\n*   __For Python 2.x.__  \n\n```sh\nsudo apt remove python-networkx #if installed, remove old version of networkx\npip2 install --user -r requirements.txt\n```\n\n*   __For Python 3.x__  \n```sh\nsudo apt remove python3-networkx #if installed, remove old version of networkx\npip3 install --user -r requirements.txt\n```\n\n!!! Warning\n    py-trees newer than v0.8 are __not__ supported.\n\n\n### Update from source  \n\n__1. Update the CARLA build__ Follow the [docs](https://carla.readthedocs.io/en/latest/build_update/) to update CARLA.  \n\n__2. Go to the main ScenarioRunner directory.__ Make sure to be in the local master branch.  \n\n```sh\ncd ~/scenario_runner\ngit branch master\n```\n__3. Pull the latest changes from the repository.__  \n\n```sh\ngit pull\n```\n\n__4. Add environment variables and Python paths__ These are necessary for the system to find CARLA, and add the PythonAPI to the Python path.\n\n*   __For Linux__\n\n```sh\n# ${CARLA_ROOT} is the CARLA installation directory\n# ${SCENARIO_RUNNER} is the ScenarioRunner installation directory\n# <VERSION> is the correct string for the Python version being used\n# In a build from source, the .egg files may be in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI\nexport CARLA_ROOT=/path/to/your/carla/installation\nexport SCENARIO_RUNNER_ROOT=/path/to/your/scenario/runner/installation\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-<VERSION>.egg\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla\n```\n\n!!! Note\n    Change the command lines with the proper paths, according to the comments. \n\n*   __For Windows__\n\n\n```sh\n# %CARLA_ROOT% is the CARLA installation directory\n# %SCENARIO_RUNNER% is the ScenarioRunner installation directory\n# <VERSION> is the correct string for the Python version being used\n# In a build from source, the .egg files may be in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI\nset CARLA_ROOT=\\path\\to\\your\\carla\\installation\nset SCENARIO_RUNNER_ROOT=\\path\\to\\your\\scenario\\runner\\installation\nset PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\\PythonAPI\\carla\\dist\\carla-<VERSION>.egg\nset PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\\PythonAPI\\carla\n```\n\n!!! Note\n    Change the command lines with the proper paths, according to the comments. \n\nTo 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.\n\n---\n## Run a test \n\nRunning the follow vehicle example\nFirst of all, you need to get latest master branch from CARLA. Then you have to\ninclude CARLA Python API to the Python path:\n\n!!! Important\n    If working with builds from source, make sure to upload these. Download the latest content in the master branches.  \n\n\n__1. Run the CARLA server.__\n\n*   __A) In a build from source__ go to the CARLA directory and launch the server in the editor. \n\n```sh\ncd ~/carla # Change the path accordingly\nmake launch\n# Press Play in the UE Editor\n```\n\n*   __B) In a CARLA package__ run the server directly. \n\n```sh\n./CarlaUE4.sh\n```\n\n__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. \n\n```sh\n# Inside the ScenarioRunner root directory\npython scenario_runner.py --scenario FollowLeadingVehicle_1 --reloadWorld\n```\n\n!!! Note\n    If using a Python 3.x version, run the command with `python3`. \n\n__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. \n\n```sh\n# Inside the ScenarioRunner root directory\npython manual_control.py\n```\n\nThe 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.  \n\n!!! Warning\n    Run the `manual_control.py` found in the ScenarioRunner package/repository, __not CARLA__. \n\n__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`.\n\n```sh\npython scenario_runner.py --help\n```\n\n---\n\nThus 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. \n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/getting_started.md",
    "content": "# Getting Started Tutorial\n\n!!! important\n    This tutorial refers to the latest versions of CARLA (at least 0.9.5)\n\nWelcome to the ScenarioRunner for CARLA! This tutorial provides the basic steps\nfor getting started using the ScenarioRunner for CARLA.\n\nDownload the latest release from our GitHub page and extract all the contents of\nthe package in a folder of your choice.\n\nThe release package contains the following\n\n  * The ScenarioRunner for CARLA\n  * A few example scenarios written in Python.\n\n## Installing prerequisites\nThe current version is designed to be used with Ubuntu 16.04, Python 2.7 or\nPython 3.5. Depending on your Python version, execute:\n```\n\n\n#Python 2.x\nsudo apt remove python-networkx #if installed, remove old version of networkx\npip2 install --user -r requirements.txt\n#Python 3.x\nsudo apt remove python3-networkx #if installed, remove old version of networkx\npip3 install --user -r requirements.txt\n```\nNote: py-trees newer than v0.8 is *NOT* supported.\n\n\n\n## Running the follow vehicle example\nFirst of all, you need to get latest master branch from CARLA. Then you have to\ninclude CARLA Python API to the Python path:\n```Bash\nexport CARLA_ROOT=/path/to/your/carla/installation\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-<VERSION>.egg:${CARLA_ROOT}/PythonAPI/carla/agents:${CARLA_ROOT}/PythonAPI/carla\n```\nNOTE: ${CARLA_ROOT} needs to be replaced with your CARLA installation directory,\n      and <VERSION> needs to be replaced with the correct string.\n      If you build CARLA from source, the egg files maybe located in:\n      ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI.\n\nNow, you can start the CARLA server from ${CARLA_ROOT}\n```\n./CarlaUE4.sh\n```\n\nStart the example scenario (follow a leading vehicle) in an extra terminal:\n```\npython scenario_runner.py --scenario FollowLeadingVehicle_1 --reloadWorld\n```\n\nIf you require help or want to explore other command line parameters, start the scenario\nrunner as follows:\n```\npython scenario_runner.py --help\n```\n\nTo control the ego vehicle within the scenario, open another terminal and run:\n```\npython manual_control.py\n```\n\nNote: If you do not wish to automatically (re-)load the CARLA world, you can\nskip the command line option _--reloadWorld_\n\n## Running all scenarios of one scenario class\nSimilar to the previous example, it is also possible to execute a sequence of scenarios,\nthat belong to the same class, e.g. the \"FollowLeadingVehicle\" class.\n\nThe only difference is, that you start the scenario_runner as follows:\n```\npython scenario_runner.py --scenario group:FollowLeadingVehicle\n```\n\n## Running other scenarios\nA list of supported scenarios is provided in\n[List of Supported Scenarios](list_of_scenarios.md). Please note that\ndifferent scenarios may take place in different CARLA towns. This has to be\nrespected when launching the CARLA server.\n\n## Running scenarios using the OpenSCENARIO format\nTo run a scenario, which is based on the OpenSCENARIO format, please run the ScenarioRunner as follows:\n```\npython scenario_runner.py --openscenario <path/to/xosc-file>\n```\nPlease note that the OpenSCENARIO support and the OpenSCENARIO format itself are still work in progress.\nMore information you can find in [OpenSCENARIO support](openscenario_support.md)\n\n### Running scenarios using the OpenSCENARIO format with Global ParameterDeclaration overwrite\n```\npython scenario_runner.py --openscenario <path/to/xosc-file> --openscenarioparams 'param1: value1, param2: value2'\n```\n\n## Running route-based scenario (similar to the CARLA AD Challenge)\nTo run a route-based scenario, please run the ScenarioRunner as follows:\n```\npython scenario_runner.py --route <path/to/route-file> <path/to/scenario_sample_file> [route id] --agent <path/to/agent_file>\n```\nExample:\n```\npython 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\n```\n\nIf no route id is provided, all routes within the given file will be executed.\n\n\nBy 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)\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/index.md",
    "content": "[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT)\n![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/carla-simulator/scenario_runner.svg)\n[![Build Status](https://travis-ci.com/carla-simulator/scenario_runner.svg?branch=master)](https://travis-ci.com/carla/scenario_runner)\n\n# ScenarioRunner\n\nScenarioRunner 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.  \n  \nScenarioRunner 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.\n\n\nThe 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.  \n<div class=\"build-buttons\">\n<a href=\"https://forum.carla.org/\" target=\"_blank\" class=\"btn btn-neutral\" title=\"Go to the latest CARLA release\">\nCARLA forum</a>\n</div>\n\n---\n\n## Quick start\n\n[**Get ScenarioRunner**](<getting_scenariorunner>) — Tutorial on how to download and launch ScenarioRunner.<br>\n\n[**First steps**](<getting_started>) — Brief tutorials on how to run different types of scenarios.<br>\n\n[**Create a new scenario**](<creating_new_scenario>) — Tutorial on how to create a new scenario using ScenarioRunner.<br>\n\n[**Metrics module**](<metrics_module>) — Explanation of the metrics module.<br>\n\n[**F.A.Q.**](<FAQ>) — Some of the most frequent installation issues.<br>\n\n[**Release notes**](<CHANGELOG>) — Features, fixes and other changes listed per release.<br>\n\n\n## References\n\n[**List of scenarios**](<list_of_scenarios>) — Example scenarios available in ScenarioRunner.<br>\n\n[**OpenScenario support**](<openscenario_support>) — Support status of OpenSCENARIO features.<br>\n\n\n## Contributing\n[**Code of conduct**](<CODE_OF_CONDUCT>) — Standard rights and duties for contributors.<br>\n\n[**Coding standard**](<coding_standard>) — Guidelines to write proper code.<br>\n\n[**Contribution guidelines**](<CONTRIBUTING>) — The different ways to contribute to ScenarioRunner.<br>\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/list_of_scenarios.md",
    "content": "# List of Supported Scenarios\n\nWelcome to the ScenarioRunner for CARLA! This document provides a list of all\ncurrently supported scenarios, and a short description for each one.\n\n### FollowLeadingVehicle\nThe scenario realizes a common driving behavior, in which the user-controlled\nego vehicle follows a leading car driving down a given road in Town01. At some\npoint the leading car slows down and finally stops. The ego vehicle has to react\naccordingly to avoid a collision. The scenario ends either via a timeout, or if\nthe ego vehicle stopped close enough to the leading vehicle\n\n### FollowLeadingVehicleWithObstacle\nThis scenario is very similar to 'FollowLeadingVehicle'. The only difference is,\nthat in front of the leading vehicle is a (hidden) obstacle that blocks the way.\n\n### VehicleTurningRight\nIn this scenario the ego vehicle takes a right turn from an intersection where\na cyclist suddenly drives into the way of the ego vehicle,which has to stop\naccordingly. After some time, the cyclist clears the road, such that ego vehicle\ncan continue driving.\n\n### VehicleTurningLeft\nThis scenario is similar to 'VehicleTurningRight'. The difference is that the ego\nvehicle takes a left turn from an intersection.\n\n### OppositeVehicleRunningRedLight\nIn this scenario an illegal behavior at an intersection is tested. An other\nvehicle waits at an intersection, but illegally runs a red traffic light. The\napproaching ego vehicle has to handle this situation correctly, i.e. despite of\na green traffic light, it has to stop and wait until the intersection is clear\nagain. Afterwards, it should continue driving.\n\n### StationaryObjectCrossing\nIn this scenario a cyclist is stationary waiting in the middle of the road and\nblocking the way for the ego vehicle. Hence, the ego vehicle has to stop in\nfront of the cyclist.\n\n### DynamicObjectCrossing\nThis is similar to 'StationaryObjectCrossing', but with the difference that the\ncyclist is dynamic. It suddenly drives into the way of the ego vehicle, which\nhas to stop accordingly. After some time, the cyclist will clear the road, such\nthat the ego vehicle can continue driving.\n\n### NoSignalJunctionCrossing\nThis scenario tests negotiation between two vehicles crossing cross each other\nthrough a junction without signal.\nThe ego vehicle is passing through a junction without traffic lights\nAnd encounters another vehicle passing across the junction. The ego vehicle has\nto avoid collision and navigate across the junction to succeed.\n\n### ControlLoss\nIn this scenario control loss of a vehicle is tested due to bad road conditions, etc\nand it checks whether the vehicle is regained its control and corrected its course.\n\n### ManeuverOppositeDirection\nIn this scenario vehicle is passing another vehicle in a rural area, in daylight, under clear\nweather conditions, at a non-junction and encroaches into another\nvehicle traveling in the opposite direction.\n\n### OtherLeadingVehicle\nThe scenario realizes a common driving behavior, in which the user-controlled ego\nvehicle follows a leading car driving down a given road.\nAt some point the leading car has to decelerate. The ego vehicle has to react\naccordingly by changing lane to avoid a collision and follow the leading car in\nother lane. The scenario ends via timeout, or if the ego vehicle drives certain\ndistance.\n\n### SignalizedJunctionRightTurn\nIn this scenario right turn of hero actor without collision at signalized intersection\nis tested. Hero Vehicle is turning right in an urban area, at a signalized intersection and\nturns into the same direction of another vehicle crossing straight initially from\na lateral direction.\n\n### SignalizedJunctionLeftTurn\nIn this scenario hero vehicle is turning left in an urban area,\nat a signalized intersection and cuts across the path of another vehicle\ncoming straight crossing from an opposite direction.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/metrics_module.md",
    "content": "# Metrics module\n\n\nThe 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. \n\nThis 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.  \n\n* [__Structure of the module__](#structure-of-the-module)  \n* [__How to use the metrics module__](#how-to-use-the-metrics-module)  \n\t* [1. Record a scenario](#1.-record-a-scenario)  \n\t* [2. Define the metrics](#2.-run-the-metrics-manager)  \n\t* [3. Run the metrics manager](#3.-run-the-metrics-manager)  \n* [__Recording queries reference__](#recording-queries-reference)  \n\t* [Generic actor data](#generic-actor-data)  \n\t* [Generic simulation data](#generic-simulation-data)  \n\t* [Actor accelerations](#actor-accelerations)  \n\t* [Actor angular velocities](#actor-angular-velocities)  \n\t* [Actor controls](#actor-controls)  \n\t* [Actor transforms](#actor-transforms)  \n\t* [Actor velocities](#actor-velocities)  \n\t* [Scene lights](#scene-lights)  \n\t* [Traffic lights](#traffic-lights)  \n\t* [Vehicle lights](#vehicle-lights)  \n\n---\n## Structure of the module\n\nSimilarly 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.  \n\n*   __`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.  \n\t*   `host` *(string)* – IP address where a CARLA simulation is running. Default is `(127.0.0.1)`.  \n\t*   `port` *(int)* – TCP port where the CARLA simulation is running. Default are `2000` and `2001`.  \n\t*   `metrics` — Path to the metrics to be used.  \n\t*   `log` — Path to the `.log` file containing the recording (relative to the environment variable `SCENARIO_RUNNER_ROOT`).  \n\t*   `criteria` *(optional)* — Path to a JSON file with the criteria of the scenario.  \n\nThe rest of the elements that shape the module can be found in the `srunner/metrics` folder. These folder has been divided in three subfolders.\n\n* __`srunner/metrics/data`__ — Stores information about the scenarios. By default, it has six files, which are part of the examples metric.  \n\n* __`srunner/metrics/examples`__ — Contains some example metrics, and the metric containing the base class `BaseMetric` to create new metrics.  \n\t*   `basic_metric.py` – Contains the base class `BaseMetric`. All the metrics are inherited from it.  \n\t*   `criteria_filter.py` – Returns a JSON with the most important attributes of the criteria. \n\t*   `distance_between_vehicles.py` – Returns the distance betwen two vehicles. Useful to show how to query the recording.  \n\t*   `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..  \n\n* __`srunner/metrics/tools`__ — Contains two key scripts that allow to query the recording.  \n\t*   `metrics_parser.py` – Transforms the string provided by the recording to a dictionary.  \n\t*   `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.  \n\n---\n## How to use the metrics module\n\n### 1. Record a scenario\n\nThe 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.  \n\nUse 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`.  \n\n```sh\npython scenario_runner.py --scenario <scenario_name> --record <path/to/save/the/recorder/file>\n```\n\nBy 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`.  \n__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/).  \n__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.\n\n!!! Note\n    Only the JSON serializable attributes will be parsed, the rest will be ignored.\n\n 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`.  \n\n\n### 2. Define the metrics\n\nIt 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.  \n\n    class DistanceBetweenVehicles(BasicMetric):\n    \"\"\"\n    Metric class DistanceBetweenVehicles\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric. This is an example to show how to use the recorder,\n        accessed via the log.\n        \"\"\"\n\n        # Get the ID of the two vehicles\n        ego_id = log.get_ego_vehicle_id()\n        adv_id = log.get_actor_ids_with_role_name(\"scenario\")[0]  # Could have also used its type_id\n\n        dist_list = []\n        frames_list = []\n\n        # Get the frames both actors were alive\n        start_ego, end_ego = log.get_actor_alive_frames(ego_id)\n        start_adv, end_adv = log.get_actor_alive_frames(adv_id)\n        start = max(start_ego, start_adv)\n        end = min(end_ego, end_adv)\n\n        # Get the distance between the two\n        for i in range(start, end):\n\n            # Get the transforms\n            ego_location = log.get_actor_transform(ego_id, i).location\n            adv_location = log.get_actor_transform(adv_id, i).location\n\n            # Filter some points for a better graph\n            if adv_location.z < -10:\n                continue\n\n            dist_v = ego_location - adv_location\n            dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n            dist_list.append(dist)\n            frames_list.append(i)\n\n        # Use matplotlib to show the results\n        plt.plot(frames_list, dist_list)\n        plt.ylabel('Distance [m]')\n        plt.xlabel('Frame number')\n        plt.title('Distance between the ego vehicle and the adversary over time')\n        plt.show()\n\n__2.1. Name the metric__. First of all, as it was previously mentioned, all metrics are childs of the `BasicMetric` class.\n\n```py\n    class DistanceBetweenVehicles(BasicMetric):\n```\n\n__2.2. Name the main method__. A metric only requires one method in order to run, `_create_metric()`, which has three arguments.  \n\n*   __`town_map`__ — Instance of the [carla.Map()](https://carla.readthedocs.io/en/latest/python_api/#carlamap) where the scenario took place in.  \n*   __`log`__ — Instance to the `MetricsLog` class, with all the functions needed to access the recorder dictionary.  \n*   __`criteria`__ — A JSOn with the criteria dictionary. The file provided when recording a scenario that is later provided to the `metrics_manager.py`.  \n\n```py\n    def _create_metric(self, town_map, log, criteria):\n```\n\n__2.3. Implement the metric__. The code will vary depending on the metric itself.  \n\nThe 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. \n\n```py\n    # Get the ID of the two vehicles\n    ego_id = log.get_ego_vehicle_id()\n    adv_id = log.get_actor_ids_with_role_name(\"scenario\")[0]  # Could have also used its type_id\n```\n\nThe `id` are used to retrieve the frames where the vehicles were alive using `get_actor_alive_frames(actor_id)`. \n```py\n    # Get the frames both actors were alive\n    start_ego, end_ego = log.get_actor_alive_frames(ego_id)\n    start_adv, end_adv = log.get_actor_alive_frames(adv_id)\n    start = max(start_ego, start_adv)\n    end = min(end_ego, end_adv)\n```\n\nNow 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. \n\n```py\n    dist_list = []\n    frames_list = []\n\n...\n\n    # Get the distance between the two\n    for i in range(start, end):\n\n        # Get the transforms\n        ego_location = log.get_actor_transform(ego_id, i).location\n        adv_location = log.get_actor_transform(adv_id, i).location\n\n        # Filter some points for a better graph\n        if adv_location.z < -10:\n            continue\n\n        dist_v = ego_location - adv_location\n        dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n        dist_list.append(dist)\n```\n!!! Note\n    The vertical condition of the adversary is to only take into account the adversary when it is driving normally.\n\nLastly, use [matplotlib](https://matplotlib.org/) to define which should be the output of the metric when running `metrics_manager.py`.  \n\n```py\n        # Use matplotlib to show the results\n        plt.plot(frames_list, dist_list)\n        plt.ylabel('Distance [m]')\n        plt.xlabel('Frame number')\n        plt.title('Distance between the ego vehicle and the adversary over time')\n        plt.show()\n```\n\n### 3. Run the metrics manager\n\nFinally 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.  \n\n```sh\npython metrics_manager.py --metric srunner/metrics/examples/distance_between_vehicles.py --log srunner/metrics/data/DistanceBetweenVehicles.log\n```\n\n!!! Warning\n    A simulation must be running. Otherwise, the module will not be able to acces the map API.\n\n\nThis will create a new window with the results plotted. The script will not finish until the ouput window is closed.\n\n![metrics_plot](img/metrics_example.jpg)\n\n---\n## Recording queries reference\n\nWhen 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.  \n\n### Generic actor data\n\n- <a name=\"get_ego_vehicle_id\"></a>__<font color=\"#7fb800\">get_ego_vehicle_id</font>__(<font color=\"#00a6ed\">__self__</font>)  \nReturns the `id` of the ego vehicle.\n    - __Return —__ int\n\n- <a name=\"get_actor_ids_with_role_name\"></a>__<font color=\"#7fb800\">get_actor_ids_with_role_name</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__role_name__</font>)  \nReturns a list of actor `id` that match the given `role_name`.\n    - __Return —__ list\n    - __Parameters__\n        - `role_name` (_str_) — `role_name` of the actor.\n\n- <a name=\"get_actor_ids_with_type_id\"></a>__<font color=\"#7fb800\">get_actor_ids_with_type_id</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__type_id__</font>)  \nReturns a list of actor `id` that match the given `type_id`, according to fnmatch standard.\n    - __Return —__ list\n    - __Parameters__\n        - `type_id` (_str_) — `type_id` of the actor.\n\n- <a name=\"get_actor_attributes\"></a>__<font color=\"#7fb800\">get_actor_attributes</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>)  \nReturns a dictionary with all the attributes of an actor.\n    - __Return —__ dict\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n- <a name=\"get_actor_bounding_box\"></a>__<font color=\"#7fb800\">get_actor_bounding_box</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>)  \nReturns the bounding box of the specified actor.\n    - __Return —__ [carla.BoundingBox](https://carla.readthedocs.io/en/latest/python_api/#carlaboundingbox)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n- <a name=\"get_traffic_light_trigger_volume\"></a>__<font color=\"#7fb800\">get_traffic_light_trigger_volume</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>)  \nReturns the trigger volume of the specified traffic light.\n    - __Return —__ [carla.BoundingBox](https://carla.readthedocs.io/en/latest/python_api/#carlaboundingbox)\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n\n- <a name=\"get_actor_alive_frames\"></a>__<font color=\"#7fb800\">get_actor_alive_frames</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>)  \nReturns a tuple with the first and last frame an actor was alive. Note that frames start at 1, not 0.\n    - __Return —__ tuple\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n\n### Generic simulation data\n\n- <a name=\"get_collisions\"></a>__<font color=\"#7fb800\">get_collisions</font>__(<font color=\"#00a6ed\">__self__</font>,<font color=\"#00a6ed\">__actor_id__</font>)  \nReturns 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.\n    - __Return —__ list\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n\n- <a name=\"get_total_frame_count\"></a>__<font color=\"#7fb800\">get_total_frame_count</font>__(<font color=\"#00a6ed\">__self__</font>)  \nReturns an int with the total amount of frames the simulation lasted.\n    - __Return —__ int\n\n- <a name=\"get_elapsed_time\"></a>__<font color=\"#7fb800\">get_elapsed_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns a float with the elapsed time of a specific frame.\n    - __Return —__ float\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_delta_time\"></a>__<font color=\"#7fb800\">get_delta_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns an float with the delta time of a specific frame.\n    - __Return —__ float\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_platform_time\"></a>__<font color=\"#7fb800\">get_platform_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns a float with the platform time of a specific frame.\n    - __Return —__ float\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n\n### Actor accelerations\n\n- <a name=\"get_actor_acceleration\"></a>__<font color=\"#7fb800\">get_actor_acceleration</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the acceleration of the actor at a given frame. Returns <b>None</b> if the actor `id` doesn't exist, the actor has no acceleration, or the actor wasn't alive at that frame.\n    - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_accelerations\"></a>__<font color=\"#7fb800\">get_all_actor_accelerations</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the accelerations of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list(carla.Vector3D)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_accelerations_at_frame\"></a>__<font color=\"#7fb800\">get_actor_accelerations_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list(carla.Vector3D)\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n        - `actor_list` (_int_) — List of actor `id`.\n\n### Actor angular velocities\n\n- <a name=\"get_actor_angular_velocity\"></a>__<font color=\"#7fb800\">get_actor_angular_velocity</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the angular velocity of the actor at a given frame. Returns <b>None</b> if the actor id doesn't exist, the actor has no angular velocity, or the actor wasn't alive at that frame.\n    - __Return —__ carla.Vector3D\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_angular_velocities\"></a>__<font color=\"#7fb800\">get_all_actor_angular_velocities</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the angular velocities of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list(carla.Vector3D)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_angular_velocities_at_frame\"></a>__<font color=\"#7fb800\">get_actor_angular_velocities_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d))\n    - __Parameters__\n        - `frame` (_int_) — frame number.\n        - `actor_list` (_int_) — List of actor ids.\n\n### Actor controls\n\n- <a name=\"get_vehicle_control\"></a>__<font color=\"#7fb800\">get_vehicle_control</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the control of a vehicle at a given frame. The `manual_gear_shift` attribute will always be False.\n    - __Return —__ [carla.VehicleCotnrol](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclecontrol)\n    - __Parameters__\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_vehicle_physics_control\"></a>__<font color=\"#7fb800\">get_vehicle_physics_control</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the physics control of a vehicle at a given frame.\n    - __Return —__ [carla.VehiclePhysicsControl](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclephysicscontrol)\n    - __Parameters__\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_walker_speed\"></a>__<font color=\"#7fb800\">get_walker_speed</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__walker_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the speed of a walker at a given frame.\n    - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `walker_id` (_int_) — `id` of the walker.\n        - `frame` (_int_) — Frame number.\n\n\n### Actor transforms\n\n- <a name=\"get_actor_transform\"></a>__<font color=\"#7fb800\">get_actor_transform</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the transform of the actor at a given frame. Returns <b>None</b> if the actor id doesn't exist, the actor has no transform, or the actor wasn't alive at that frame.\n    - __Return —__ [carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_transforms\"></a>__<font color=\"#7fb800\">get_all_actor_transforms</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the transforms of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list([carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform))\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_transforms_at_frame\"></a>__<font color=\"#7fb800\">get_actor_transforms_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list([carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform))\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n        - `actor_list` (_int_) — List of actor `id`. \n\n### Actor velocities\n\n- <a name=\"get_actor_velocity\"></a>__<font color=\"#7fb800\">get_actor_velocity</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the velocity of the actor at a given frame. Returns <b>None</b> if the actor id doesn't exist, the actor has no velocity, or the actor wasn't alive at that frame.\n    - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_all_actor_velocities\"></a>__<font color=\"#7fb800\">get_all_actor_velocities</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__actor_id__</font>, <font color=\"#00a6ed\">__first_frame__=None</font>, <font color=\"#00a6ed\">__last_frame__=None</font>)  \nReturns a list with all the velocities of the actor at the frame interval. By default, the frame interval comprises all the recording.\n    - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d))\n    - __Parameters__\n        - `actor_id` (_int_) — `id` of the actor.\n        - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation.\n        - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation.\n\n- <a name=\"get_actor_velocities_at_frame\"></a>__<font color=\"#7fb800\">get_actor_velocities_at_frame</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__frame__</font>, <font color=\"#00a6ed\">__actor_list__=None</font>)  \nReturns 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.\n    - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)\n    - __Parameters__\n        - `frame` (_int_) — Frame number.\n        - `actor_list` (_int_) — List of actor `id`. \n\n### Scene lights\n\n- <a name=\"get_scene_light_state\"></a>__<font color=\"#7fb800\">get_scene_light_state</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__light__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns 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).\n    - __Return —__ carla.LightState\n    - __Parameters__\n        - `light_id` (_int_) — `id` of the scene light.\n        - `frame` (_int_) — Frame number.\n\n\n### Traffic lights\n\n- <a name=\"get_traffic_light_state\"></a>__<font color=\"#7fb800\">get_traffic_light_state</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the state of a traffic light at a given frame.\n    - __Return —__ [carla.TrafficLightState](https://carla.readthedocs.io/en/latest/python_api/#carlatrafficlightstate).\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"is_traffic_light_frozen\"></a>__<font color=\"#7fb800\">is_traffic_light_frozen</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns whether or not a traffic light is frozen at a given frame.\n    - __Return —__ bool\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_traffic_light_elapsed_time\"></a>__<font color=\"#7fb800\">get_traffic_light_elapsed_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the elapsed time of a traffic light at a given frame.\n    - __Return —__ float\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"get_traffic_light_state_time\"></a>__<font color=\"#7fb800\">get_traffic_light_state_time</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__traffic_light_id__</font>, <font color=\"#00a6ed\">__state__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns the maximum time of a specific state of a traffic light at a given frame.\n    - __Return —__ float\n    - __Parameters__\n        - `traffic_light_id` (_int_) — `id` of the traffic light.\n        - `state` ([carla.TrafficLightState](https://carla.readthedocs.io/en/latest/python_api/#carlatrafficlightstate)) — `id` of the actor.\n        - `frame` (_int_) — Frame number.\n\n### Vehicle lights\n\n- <a name=\"get_vehicle_lights\"></a>__<font color=\"#7fb800\">get_vehicle_lights</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nReturns a list with the active lights of a specific vehicle at a given frame.\n    - __Return —__ list([carla.VehicleLightState](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclelightstate))\n    - __Parameters__\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n\n- <a name=\"is_vehicle_light_active\"></a>__<font color=\"#7fb800\">is_vehicle_light_active</font>__(<font color=\"#00a6ed\">__self__</font>, <font color=\"#00a6ed\">__light__</font>, <font color=\"#00a6ed\">__vehicle_id__</font>, <font color=\"#00a6ed\">__frame__</font>)  \nChecks whether or not a given vehicle light is active for a vehicle at a specific frame.\n    - __Return —__ bool\n    - __Parameters__\n        - `light` ([carla.VehicleLightState](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclelightstate)) — The light state to be compared with the vehicle.\n        - `vehicle_id` (_int_) — `id` of the vehicle.\n        - `frame` (_int_) — Frame number.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/openscenario_support.md",
    "content": "## OpenSCENARIO Support\n\nThe scenario_runner provides support for the [OpenSCENARIO](http://www.openscenario.org/) 1.0 standard.\nThe current implementation covers initial support for maneuver Actions, Conditions, Stories and the Storyboard.\nIf you would like to use evaluation criteria for a scenario to evaluate pass/fail results, these can be implemented\nas StopTriggers (see below). However, not all features for these elements are yet available. If in doubt, please see the\nmodule documentation in srunner/tools/openscenario_parser.py\n\nAn example for a supported scenario based on OpenSCENARIO is available [here](https://github.com/carla-simulator/scenario_runner/blob/master/srunner/examples/FollowLeadingVehicle.xosc)\n\nIn 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).\n\n### Migrating OpenSCENARIO 0.9.x to 1.0\nThe 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.\nExample:\n\n```bash\nxsltproc -o newScenario.xosc migration0_9_1to1_0.xslt oldScenario.xosc\n```\n\n\n### Level of support\nIn the following the OpenSCENARIO attributes are listed with their current support status.\n\n#### General OpenSCENARIO setup\n\nThis covers all part that are defined outside the OpenSCENARIO Storyboard\n\n| Attribute                          | Support                            | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `FileHeader`                       | &#9989;                              | Use \"CARLA:\" at the beginning of the description to use the CARLA coordinate system.                                |\n| `CatalogLocations`<br>`ControllerCatalog`                                      | &#9989;                              | While the catalog is supported, the reference/usage may not work.                |\n| `CatalogLocations`<br>`EnvironmentCatalog`                                     | &#9989;                              |                                    |\n| `CatalogLocations`<br>`ManeuverCatalog`                                        | &#9989;                              |                                    |\n| `CatalogLocations`<br>`MiscObjectCatalog`                                      | &#9989;                              |                                    |\n| `CatalogLocations`<br>`PedestrianCatalog`                                      | &#9989;                              |                                    |\n| `CatalogLocations`<br>`RouteCatalog`                                           | &#9989;                              | While the catalog is supported, the reference/usage may not work.                |\n| `CatalogLocations`<br>`TrajectoryCatalog`                                      | &#9989;                              | While the catalog is supported, the reference/usage may not work.                |\n| `CatalogLocations`<br>`VehicleCatalog`                                         | &#9989;                              |                                    |\n| `ParameterDeclarations`            | &#9989;                              |                                    |\n| `RoadNetwork`<br>`LogicFile`                                                   | &#9989;                              | The CARLA level can be used directly (e.g. LogicFile=Town01). Also any OpenDRIVE path can be provided.              |\n| `RoadNetwork`<br>`SceneGraphFile`                                              | &#10060;                               | The provided information is not used.                                            |\n| `RoadNetwork`<br>`TafficSignals`                                               | &#10060;                               | The provided information is not used.                                            |\n| `Entities`<br>`EntitySelection`                                                | &#10060;                               | The provided information is not used.                                            |\n| `Entities` `ScenarioObject`<br>`CatalogReference`                               | &#9989;                              | The provided information is not used.                                            |\n| `Entities` `ScenarioObject`<br>`MiscObject`                                     | &#9989;                              | The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. BoundingBox entries are ignored.                   |\n| `Entities` `ScenarioObject`<br>`ObjectController`                               | &#10060;                               | The provided information is not used.                                            |\n| `Entities` `ScenarioObject`<br>`Pedestrian`                                     | &#9989;                              | The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. BoundingBox entries are ignored.                   |\n| `Entities` `ScenarioObject`<br>`Vehicle`                                        | &#9989;                              | 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. |\n\n<br>\n\n\n#### OpenSCENARIO Storyboard\n\n##### OpenSCENARIO Actions\n\nThe OpenSCENARIO Actions can be used for two different purposes. First, Actions can be used to\ndefine the initial behavior of something, e.g. a traffic participant. Therefore, Actions can be\nused within the OpenSCENARIO Init. In addition, Actions are also used within the OpenSCENARIO\nstory. In the following, the support status for both application areas is listed. If an action\ncontains of submodules, which are not listed, the support status applies to all submodules.\n\n###### GlobalAction\n\n\n\n| GlobalAction                          | Init  support                            | Story support                              | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `EntityAction`                | &#10060;                          | &#10060;                          |                               |\n| `EnvironmentAction`           | &#9989;                         | &#10060;                          |                               |\n| `ParameterAction`             | &#9989;                          | &#9989;                          |                               |\n| `InfrastructureAction` `TrafficSignalAction`<br>`TrafficAction`                                               | &#10060;                          | &#10060;                          |                               |\n| `InfrastructureAction` `TrafficSignalAction`<br>`TrafficSignalControllerAction`                               | &#10060;                          | &#10060;                          |                               |\n| `InfrastructureAction` `TrafficSignalAction`<br>`TrafficSignalStateAction`                                    | &#10060;                          | &#9989;                         | 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\") |\n\n<br>\n\n\n\n###### UserDefinedAction\n\n\n\n| UserDefinedAction                          | Init  support                            | Story support                              | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `CustomCommandAction`                       | &#10060;                                        | &#9989;                                       | This action is currently used to trigger the execution of an additional script. Example: type=\"python /path/to/script args\". |\n\n<br>\n\n\n###### PrivateAction\n\n\n| PrivateAction                          | Init  support                            | Story support                              | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `ActivateControllerAction`                          | &#10060;             | &#9989;            | Can be used to activate/deactive the CARLA autopilot.                                             |\n| `ControllerAction`                                  | &#9989;            | &#9989;            | AssignControllerAction is supported, but a Python module has to be provided for the controller implementation, and in OverrideControllerValueAction all values need to be `False`. |\n| `LateralAction`<br> `LaneChangeAction`             | &#10060;             | &#9989;            | Currently all lane changes have a linear dynamicShape, the dynamicDimension is defined as the distance and are relative to the actor itself (RelativeTargetLane).                  |\n| `LateralAction`<br>`LaneOffsetAction`             | &#10060;             | &#9989;             |  Currently all type of dynamicShapes are ignored and depend on the controller. This action might not work as intended if the offset is high enough to make the vehicle exit its lane  |\n| `LateralAction`<br> `LateralDistanceAction`        | &#10060;             | &#10060;             |                  |\n| `LongitudinalAction`<br> `LongitudinalDistanceAction`| &#10060;             | &#9989;              |`timeGap` attribute is not supported              |\n| `LongitudinalAction`<br> `SpeedAction`             | &#9989;            | &#9989;            |                  |\n| `SynchronizeAction`                                 | &#10060;             | &#10060;             |                  |\n| `TeleportAction`                                    | &#9989;            | &#9989;            |                  |\n| `VisibilityAction`                                  | &#10060;             | &#10060;             |                  |\n| `RoutingAction`<br> `AcquirePositionAction`        | &#10060;             | &#9989;            |                  |\n| `RoutingAction`<br> `AssignRouteAction`            | &#10060;             | &#9989;            | Route Options (shortest/fastest/etc) are supported. Shortests means direct path between A and B, all other will use the shortest path along the road network between A and B       |\n| `RoutingAction`<br> `FollowTrajectoryAction`       | &#10060;             | &#10060;             |                  |\n\n<br>\n\n\n\n##### OpenSCENARIO Conditions\n\nConditions in OpenSCENARIO can be defined either as ByEntityCondition or as ByValueCondition.\nBoth can be used for StartTrigger and StopTrigger conditions.\nThe following two tables list the support status for each.\n\n###### ByEntityCondition\n\n\n| EntityCondition                                | Support                                        | Notes                                          |\n| ---------------------------------------------- | ---------------------------------------------- | ---------------------------------------------- |\n| `AccelerationCondition`                        | &#9989;                                          |                                                |\n| `CollisionCondition`                           | &#9989;                                          |                                                |\n| `DistanceCondition`                            | &#9989;                                          | \\*freespace\\* attribute is still not supported |\n| `EndOfRoadCondition`                           | &#9989;                                          |                                                |\n| `OffroadCondition`                             | &#9989;                                          |                                                |\n| `ReachPositionCondition`                       | &#9989;                                          |                                                |\n| `RelativeDistanceCondition`                    | &#9989;                                          |                                                |\n| `RelativeSpeedCondition`                       | &#9989;                                          |                                                |\n| `SpeedCondition`                               | &#9989;                                          |                                                |\n| `StandStillCondition`                          | &#9989;                                          |                                                |\n| `TimeHeadwayCondition`                         | &#9989;                                          |                                                |\n| `TimeToCollisionCondition`                     | &#9989;                                          |                                                |\n| `TraveledDistanceCondition`                    | &#9989;                                          |                                                |\n\n<br>\n\n###### ByValueCondition\n\n\n| ValueCondition            | Support                   | Notes                     |\n| -------------------------------------------------------- | -------------------------------------------------------- | -------------------------------------------------------- |\n| `ParameterCondition`         | &#9989;                     | The level of support depends on the parameter. It is recommended to use other conditions if possible. Please also consider the note below.                                                  |\n| `SimulationTimeCondition`                                    | &#9989;                     |                           |\n| `StoryboardElementStateCondition`                            | &#9989;                     | startTransition, stopTransition, endTransition and completeState are currently supported.                  |\n| `TimeOfDayCondition`         | &#9989;                     |                           |\n| `TrafficSignalCondition`                                     | &#9989;                     | 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\") |\n| `TrafficSignalControllerCondition`                           | &#10060;                      |                           |\n| `UserDefinedValueCondition`                                  | &#10060;                      |                           |\n\n<br>\n\n!!! Note\n     In the OpenSCENARIO 1.0 standard, a definition of test / evaluation criteria is not\n     defined. For this purpose, you can re-use StopTrigger conditions with CARLA. The following\n     StopTrigger conditions for evaluation criteria are supported through ParameterConditions by\n     providing the criteria name for the condition:\n\n     * criteria_RunningStopTest\n     * criteria_RunningRedLightTest\n     * criteria_WrongLaneTest\n     * criteria_OnSideWalkTest\n     * criteria_KeepLaneTest\n     * criteria_CollisionTest\n     * criteria_DrivenDistanceTest\n\n\n##### OpenSCENARIO Positions\n\nThere are several ways of defining positions in OpenSCENARIO. In the following we list the\ncurrent support status for each definition format.\n\n| Position                          | Support                            | Notes                              |\n| ---------------------------------------- | ---------------------------------------- | ---------------------------------------- |\n| `LanePosition`           | &#9989;                    |                          |\n| `RelativeLanePosition`   | &#9989;                    |                          |\n| `RelativeObjectPosition` | &#9989;                    |                          |\n| `RelativeRoadPosition`   | &#9989;                     |                          |\n| `RelativeWorldPosition`  | &#9989;                    |                          |\n| `RoadPosition`           | &#9989;                     |                          |\n| `RoutePosition`          | &#10060;                     |                          |\n| `WorldPosition`          | &#9989;                    |                          |\n\n<br>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/requirements.txt",
    "content": "mkdocs >= 1.0\nmarkdown-include\nmkdocs-redirects\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Docs/ros_agent.md",
    "content": "# ROS-based Challenge Agent\n\nInterfacing CARLA from ROS is normally done via [CARLA ROS Bridge](https://github.com/carla-simulator/ros-bridge).\nIn 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.\n \n# Requirements\n\n* `roscore` is expected to be running in the docker container. Please adapt your entrypoint.\n\n## Setup\n\nTo enable your stack within challenge mode, the following steps need to be taken:\n\n1. Define Sensor Setup\n2. Define Startup\n\n### Define Sensor Setup\n\nDerive from RosAgent and implement the sensors() method.\n\n    from srunner.autoagents.ros_agent import RosAgent\n\n    class MyRosAgent(RosAgent):\n\n        def sensors(self):\n            return [ <sensor-definition> ]\n\nAs an example for the sensor definition, see [HumanAgent.py](../srunner/autoagents/human_agent.py).\n\n\n### Define Startup\n\nThe startup of the stack is done within the shell script `$TEAM_CODE_ROOT/start.sh`.\nTherefore the environment variable `TEAM_CODE_ROOT` must be set.\n\nRosAgent takes care of executing and monitoring. The script shall remain running as long as the stack is active.\n\nExample for start.sh\n\n    #!/bin/bash -e\n    roslaunch $TEAM_CODE_ROOT/challenge.launch\n\n\n## Testing\n\nIn general, the challenge execution is headless. For diagnosis you're still able to use ros-tools like rviz or rqt. Additionally you\ncan 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).\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/Jenkinsfile",
    "content": "#!/usr/bin/env groovy\n\n\nString CARLA_HOST \nString CARLA_RELEASE\nString TEST_HOST\nString COMMIT\nString ECR_REPOSITORY = \"456841689987.dkr.ecr.eu-west-3.amazonaws.com/scenario_runner\"\nboolean CARLA_RUNNING = false\nboolean CONCURRENCY = true\n\n// V3 - include detection of concurrent builds\n\npipeline\n{\n    agent none\n\n    options\n    {\n        buildDiscarder(logRotator(numToKeepStr: '3', artifactNumToKeepStr: '3'))\n        skipDefaultCheckout()\n    }\n\n    stages\n    {\n        stage('setup')\n        {\n            agent { label \"master\" }\n            steps\n            {\n                checkout scm\n                script\n                {\n                    jenkinsLib = load(\"/home/jenkins/scenario_runner.groovy\")\n                    TEST_HOST = jenkinsLib.getUbuntuTestNodeHost()\n                    CARLA_HOST= sh(\n                        script: \"cat ./CARLA_VER | grep HOST | sed 's/HOST\\\\s*=\\\\s*//g'\",\n                        returnStdout: true).trim()\n                    CARLA_RELEASE = sh(\n                        script: \"cat ./CARLA_VER | grep RELEASE | sed 's/RELEASE\\\\s*=\\\\s*//g'\",\n                        returnStdout: true).trim()\n                    COMMIT = sh(returnStdout: true, script: \"git log -n 1 --pretty=format:'%h'\").trim()\n                }\n                println \"using CARLA version ${CARLA_RELEASE} from ${TEST_HOST}\"\n            }\n        }\n        stage('get concurrency status')\n        {\n            options\n            {\n                lock resource: 'ubuntu_gpu', skipIfLocked: true\n            }\n            agent { label \"master\" }\n            steps\n            {\n                script\n                {\n                    CONCURRENCY = false\n                    println \"no concurrent builds detected.\"\n                }\n            }\n        }\n        stage('act on concurrency')\n        {\n            agent { label \"master\" }\n            steps\n            {\n                script\n                {\n                    if ( CONCURRENCY == true )\n                    {\n                        println \"concurrent builds detected, prebuilding SR image.\"\n                        stage('prebuild SR docker image')\n                        {\n                            //checkout scm\n                            sh \"docker build -t jenkins/scenario_runner:${COMMIT} .\"\n                            sh \"docker tag jenkins/scenario_runner:${COMMIT} ${ECR_REPOSITORY}:${COMMIT}\"\n                            sh '$(aws ecr get-login | sed \\'s/ -e none//g\\' )' \n                            sh \"docker push ${ECR_REPOSITORY}\"\n\t\t\t    sh \"docker image rmi -f \\\"\\$(docker images -q ${ECR_REPOSITORY}:${COMMIT})\\\"\"\n                        }\n                    }\n                }\n            }\n        }\n        stage('lock ubuntu_gpu instance')\n        {\n            options\n            {\n                lock resource: \"ubuntu_gpu\"\n            }\n            stages\n            {\n                stage('start server')\n                {\n                        agent { label \"master\" }\n                        steps\n                        {\n                            script\n                            {\n                                jenkinsLib = load(\"/home/jenkins/scenario_runner.groovy\")\n                                jenkinsLib.StartUbuntuTestNode()\n                            }\n                        }\n                }\n                stage('deploy')\n                {\n                        parallel\n                        {\n                            stage('build SR docker image')\n                            {\n                                    agent { label \"master\" }\n                                    steps\n                                    {\n                                        script\n                                        {\n                                            if ( CONCURRENCY == false )\n                                            {\n                                                //checkout scm\n                                                sh \"docker build -t jenkins/scenario_runner:${COMMIT} .\"\n                                                sh \"docker tag jenkins/scenario_runner:${COMMIT} ${ECR_REPOSITORY}:${COMMIT}\"\n                                                sh '$(aws ecr get-login | sed \\'s/ -e none//g\\' )'\n                                                sh \"docker push ${ECR_REPOSITORY}\"\n\t\t\t\t\t\tsh \"docker image rmi -f \\\"\\$(docker images -q ${ECR_REPOSITORY}:${COMMIT})\\\"\"\n                                            }\n                                            else\n                                            {\n                                                println \"SR docker image already built due concurrency\"\n                                            }\n                                        }\n                                    }\n                            }\n                            stage('deploy CARLA')\n                            {\n                                    stages\n                                    {\n                                        stage('install CARLA')\n                                        {\n                                                agent { label \"secondary && ubuntu && gpu && sr\" }\n                                                steps\n                                                {\n                                                    println \"using CARLA version ${CARLA_RELEASE}\"\n                                                    sh \"wget -qO- ${CARLA_HOST}/${CARLA_RELEASE}.tar.gz | tar -xzv -C .\"\n                                                }\n                                        }\n                                    }\n                            }\n                        }\n                }\n                stage('run test')\n                {\n                    agent { label \"secondary && ubuntu && gpu && sr\" }\n                        steps\n                        {\n                            sh 'DISPLAY= ./CarlaUE4.sh -opengl -nosound > CarlaUE4.log&'\n                        sleep 10\n                            script\n                            {\n                                    sh '$(aws ecr get-login | sed \\'s/ -e none//g\\' )' \n                                    sh \"docker pull ${ECR_REPOSITORY}:${COMMIT}\"\n                                    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 \\\"\"\n                                    deleteDir()\n                            }\n                        }\n                }\n            }\n            post\n            {\n                always\n                {\n                        node('master')\n                        {\n                            script  \n                            {\n                                    jenkinsLib = load(\"/home/jenkins/scenario_runner.groovy\")\n                                    jenkinsLib.StopUbuntuTestNode()\n                                    echo 'test node stopped'\n                                    sh 'docker system prune --volumes -f'\n                            }\n                            deleteDir()\n                        }\n                }\n            }\n        }\n    }\n}\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/LICENSE",
    "content": "MIT License\n\nCopyright (c) 2018 CARLA\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/README.md",
    "content": "[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT)\n![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/carla-simulator/scenario_runner.svg)\n[![Build Status](https://travis-ci.com/carla-simulator/scenario_runner.svg?branch=master)](https://travis-ci.com/carla/scenario_runner)\n\nScenarioRunner for CARLA\n========================\nThis repository contains traffic scenario definition and an execution engine\nfor CARLA. It also allows the execution of a simulation of the CARLA Challenge.\nYou can use this system to prepare your agent for the CARLA Challenge.\n\nScenarios can be defined through a Python interface, and with the newest version\nthe scenario_runner also the upcoming [OpenSCENARIO](http://www.openscenario.org/) standard is supported.\n\n[![Scenario_Runner for CARLA](Docs/img/scenario_runner_video.png)](https://youtu.be/ChmF8IFagpo?t=68)\n\nGetting the ScenarioRunner\n---------------------------\n\nUse `git clone` or download the project from this page. Note that the master\nbranch contains the latest fixes and features, and may be required to use the latest features from CARLA.\n\nIt is important to also consider the release version that has to match the CARLA version.\n\n* [Version 0.9.13](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.13) and the 0.9.13 Branch: Compatible with [CARLA 0.9.13](https://github.com/carla-simulator/carla/releases/tag/0.9.13)\n* [Version 0.9.12](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.12) and the 0.9.12 Branch: Compatible with [CARLA 0.9.12](https://github.com/carla-simulator/carla/releases/tag/0.9.12)\n* [Version 0.9.11](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.11) and the 0.9.11 Branch: Compatible with [CARLA 0.9.11](https://github.com/carla-simulator/carla/releases/tag/0.9.11)\n* [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)\n* [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.\n* [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)\n* [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.\n* [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)\n* [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)\n* [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)\n\nTo 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)\n\nCurrently no build is required, as all code is in Python.\n\nUsing the ScenarioRunner\n------------------------\n\nPlease take a look at our [Getting started](Docs/getting_scenariorunner.md)\ndocumentation.\n\nChallenge Evaluation\n---------------------\n\nThe CARLA Challenge has moved to the [CARLA Autonomous Driving Leaderboard](https://leaderboard.carla.org/). Please see the [leaderboard repository](https://github.com/carla-simulator/leaderboard) and the [getting started guide](https://leaderboard.carla.org/get_started/) for more information.\n\nContributing\n------------\n\nPlease take a look at our [Contribution guidelines](https://carla.readthedocs.io/en/latest/#contributing).\n\nFAQ\n------\n\nIf you run into problems, check our\n[FAQ](http://carla.readthedocs.io/en/latest/faq/).\n\nLicense\n-------\n\nScenarioRunner specific code is distributed under MIT License.\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/manual_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n# Allows controlling a vehicle with a keyboard. For a simpler and more\n# documented example, please take a look at tutorial.py.\n\n\"\"\"\nWelcome to CARLA manual control.\n\nUse ARROWS or WASD keys for control.\n\n    W            : throttle\n    S            : brake\n    A/D          : steer left/right\n    Q            : toggle reverse\n    Space        : hand-brake\n    P            : toggle autopilot\n    M            : toggle manual transmission\n    ,/.          : gear up/down\n\n    L            : toggle next light type\n    SHIFT + L    : toggle high beam\n    Z/X          : toggle right/left blinker\n    I            : toggle interior light\n\n    TAB          : change camera position\n\n    R            : toggle recording images to disk\n\n    CTRL + R     : toggle recording of simulation (replacing any previous)\n    CTRL + P     : start replaying last recorded simulation\n    CTRL + +     : increments the start time of the replay by 1 second (+SHIFT = 10 seconds)\n    CTRL + -     : decrements the start time of the replay by 1 second (+SHIFT = 10 seconds)\n\n    F1           : toggle HUD\n    H/?          : toggle help\n    ESC          : quit\n\"\"\"\n\nfrom __future__ import print_function\n\n# ==============================================================================\n# -- imports -------------------------------------------------------------------\n# ==============================================================================\n\nimport carla\nfrom carla import ColorConverter as cc\n\nimport argparse\nimport os\nimport sys\nimport time\nimport collections\nimport datetime\nimport logging\nimport math\nimport weakref\n\ntry:\n    import pygame\n    from pygame.locals import K_ESCAPE\n    from pygame.locals import K_F1\n    from pygame.locals import KMOD_CTRL\n    from pygame.locals import KMOD_SHIFT\n    from pygame.locals import K_TAB\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_UP\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_w\n    from pygame.locals import K_a\n    from pygame.locals import K_s\n    from pygame.locals import K_d\n    from pygame.locals import K_q\n    from pygame.locals import K_m\n    from pygame.locals import K_COMMA\n    from pygame.locals import K_PERIOD\n    from pygame.locals import K_p\n    from pygame.locals import K_i\n    from pygame.locals import K_l\n    from pygame.locals import K_z\n    from pygame.locals import K_x\n    from pygame.locals import K_r\n    from pygame.locals import K_MINUS\n    from pygame.locals import K_EQUALS\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\ntry:\n    import numpy as np\nexcept ImportError:\n    raise RuntimeError('cannot import numpy, make sure numpy package is installed')\n\n\n# ==============================================================================\n# -- Global functions ----------------------------------------------------------\n# ==============================================================================\n\ndef get_actor_display_name(actor, truncate=250):\n    name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])\n    return (name[:truncate - 1] + u'\\u2026') if len(name) > truncate else name\n\n\n# ==============================================================================\n# -- World ---------------------------------------------------------------------\n# ==============================================================================\n\nclass World(object):\n\n    def __init__(self, carla_world, hud, args):\n        self.world = carla_world\n        try:\n            self.map = self.world.get_map()\n        except RuntimeError as error:\n            print('RuntimeError: {}'.format(error))\n            print('  The server could not send the OpenDRIVE (.xodr) file:')\n            print('  Make sure it exists, has the same name of your town, and is correct.')\n            sys.exit(1)\n        self.hud = hud\n        self.player = None\n        self.collision_sensor = None\n        self.lane_invasion_sensor = None\n        self.gnss_sensor = None\n        self.imu_sensor = None\n        self.radar_sensor = None\n        self.camera_manager = None\n        self.restart()\n        self.world.on_tick(hud.on_world_tick)\n        self.recording_enabled = False\n        self.recording_start = 0\n\n    def restart(self):\n\n        self.player_max_speed = 1.589\n        self.player_max_speed_fast = 3.713\n\n        # Keep same camera config if the camera manager exists.\n        cam_index = self.camera_manager.index if self.camera_manager is not None else 0\n        cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0\n\n        # Get the ego vehicle\n        while self.player is None:\n            print(\"Waiting for the ego vehicle...\")\n            time.sleep(1)\n            possible_vehicles = self.world.get_actors().filter('vehicle.*')\n            for vehicle in possible_vehicles:\n                if vehicle.attributes['role_name'] == 'hero':\n                    print(\"Ego vehicle found\")\n                    self.player = vehicle\n                    break\n\n        self.player_name = self.player.type_id\n\n        # Set up the sensors.\n        self.collision_sensor = CollisionSensor(self.player, self.hud)\n        self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)\n        self.gnss_sensor = GnssSensor(self.player)\n        self.imu_sensor = IMUSensor(self.player)\n        self.camera_manager = CameraManager(self.player, self.hud)\n        self.camera_manager.transform_index = cam_pos_index\n        self.camera_manager.set_sensor(cam_index, notify=False)\n        actor_type = get_actor_display_name(self.player)\n        self.hud.notification(actor_type)\n\n        self.world.wait_for_tick()\n\n    def tick(self, clock, wait_for_repetitions):\n        if len(self.world.get_actors().filter(self.player_name)) < 1:\n            if not wait_for_repetitions:\n                return False\n            else:\n                self.player = None\n                self.destroy()\n                self.restart()\n\n        self.hud.tick(self, clock)\n        return True\n\n    def render(self, display):\n        self.camera_manager.render(display)\n        self.hud.render(display)\n\n    def destroy_sensors(self):\n        self.camera_manager.sensor.destroy()\n        self.camera_manager.sensor = None\n        self.camera_manager.index = None\n\n    def destroy(self):\n        sensors = [\n            self.camera_manager.sensor,\n            self.collision_sensor.sensor,\n            self.lane_invasion_sensor.sensor,\n            self.gnss_sensor.sensor,\n            self.imu_sensor.sensor]\n        for sensor in sensors:\n            if sensor is not None:\n                sensor.stop()\n                sensor.destroy()\n        if self.player is not None:\n            self.player.destroy()\n\n\n# ==============================================================================\n# -- KeyboardControl -----------------------------------------------------------\n# ==============================================================================\n\n\nclass KeyboardControl(object):\n    \"\"\"Class that handles keyboard input.\"\"\"\n    def __init__(self, world, start_in_autopilot):\n        self._autopilot_enabled = start_in_autopilot\n        self._control = carla.VehicleControl()\n        self._lights = carla.VehicleLightState.NONE\n        self._steer_cache = 0.0\n        world.player.set_autopilot(self._autopilot_enabled)\n        world.player.set_light_state(self._lights)\n        world.hud.notification(\"Press 'H' or '?' for help.\", seconds=4.0)\n\n    def parse_events(self, client, world, clock):\n        current_lights = self._lights\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                return True\n            elif event.type == pygame.KEYUP:\n                if self._is_quit_shortcut(event.key):\n                    return True\n                elif event.key == K_F1:\n                    world.hud.toggle_info()\n                elif event.key == K_TAB:\n                    world.camera_manager.toggle_camera()\n                elif event.key == K_r and not (pygame.key.get_mods() & KMOD_CTRL):\n                    world.camera_manager.toggle_recording()\n                elif event.key == K_r and (pygame.key.get_mods() & KMOD_CTRL):\n                    if (world.recording_enabled):\n                        client.stop_recorder()\n                        world.recording_enabled = False\n                        world.hud.notification(\"Recorder is OFF\")\n                    else:\n                        client.start_recorder(\"manual_recording.rec\")\n                        world.recording_enabled = True\n                        world.hud.notification(\"Recorder is ON\")\n                elif event.key == K_p and (pygame.key.get_mods() & KMOD_CTRL):\n                    # stop recorder\n                    client.stop_recorder()\n                    world.recording_enabled = False\n                    # work around to fix camera at start of replaying\n                    current_index = world.camera_manager.index\n                    world.destroy_sensors()\n                    # disable autopilot\n                    self._autopilot_enabled = False\n                    world.player.set_autopilot(self._autopilot_enabled)\n                    world.hud.notification(\"Replaying file 'manual_recording.rec'\")\n                    # replayer\n                    client.replay_file(\"manual_recording.rec\", world.recording_start, 0, 0)\n                    world.camera_manager.set_sensor(current_index)\n                elif event.key == K_MINUS and (pygame.key.get_mods() & KMOD_CTRL):\n                    if pygame.key.get_mods() & KMOD_SHIFT:\n                        world.recording_start -= 10\n                    else:\n                        world.recording_start -= 1\n                    world.hud.notification(\"Recording start time is %d\" % (world.recording_start))\n                elif event.key == K_EQUALS and (pygame.key.get_mods() & KMOD_CTRL):\n                    if pygame.key.get_mods() & KMOD_SHIFT:\n                        world.recording_start += 10\n                    else:\n                        world.recording_start += 1\n                    world.hud.notification(\"Recording start time is %d\" % (world.recording_start))\n                elif event.key == K_q:\n                    self._control.gear = 1 if self._control.reverse else -1\n                elif event.key == K_m:\n                    self._control.manual_gear_shift = not self._control.manual_gear_shift\n                    self._control.gear = world.player.get_control().gear\n                    world.hud.notification('%s Transmission' %\n                                            ('Manual' if self._control.manual_gear_shift else 'Automatic'))\n                elif self._control.manual_gear_shift and event.key == K_COMMA:\n                    self._control.gear = max(-1, self._control.gear - 1)\n                elif self._control.manual_gear_shift and event.key == K_PERIOD:\n                    self._control.gear = self._control.gear + 1\n                elif event.key == K_p and not pygame.key.get_mods() & KMOD_CTRL:\n                    self._autopilot_enabled = not self._autopilot_enabled\n                    world.player.set_autopilot(self._autopilot_enabled)\n                    world.hud.notification(\n                        'Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))\n                elif event.key == K_l and pygame.key.get_mods() & KMOD_CTRL:\n                    current_lights ^= carla.VehicleLightState.Special1\n                elif event.key == K_l and pygame.key.get_mods() & KMOD_SHIFT:\n                    current_lights ^= carla.VehicleLightState.HighBeam\n                elif event.key == K_l:\n                    # Use 'L' key to switch between lights:\n                    # closed -> position -> low beam -> fog\n                    if not self._lights & carla.VehicleLightState.Position:\n                        world.hud.notification(\"Position lights\")\n                        current_lights |= carla.VehicleLightState.Position\n                    else:\n                        world.hud.notification(\"Low beam lights\")\n                        current_lights |= carla.VehicleLightState.LowBeam\n                    if self._lights & carla.VehicleLightState.LowBeam:\n                        world.hud.notification(\"Fog lights\")\n                        current_lights |= carla.VehicleLightState.Fog\n                    if self._lights & carla.VehicleLightState.Fog:\n                        world.hud.notification(\"Lights off\")\n                        current_lights ^= carla.VehicleLightState.Position\n                        current_lights ^= carla.VehicleLightState.LowBeam\n                        current_lights ^= carla.VehicleLightState.Fog\n                elif event.key == K_i:\n                    current_lights ^= carla.VehicleLightState.Interior\n                elif event.key == K_z:\n                    current_lights ^= carla.VehicleLightState.LeftBlinker\n                elif event.key == K_x:\n                    current_lights ^= carla.VehicleLightState.RightBlinker\n\n        if not self._autopilot_enabled:\n            self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time())\n            self._control.reverse = self._control.gear < 0\n            # Set automatic control-related vehicle lights\n            if self._control.brake:\n                current_lights |= carla.VehicleLightState.Brake\n            else: # Remove the Brake flag\n                current_lights &= ~carla.VehicleLightState.Brake\n            if self._control.reverse:\n                current_lights |= carla.VehicleLightState.Reverse\n            else: # Remove the Reverse flag\n                current_lights &= ~carla.VehicleLightState.Reverse\n            if current_lights != self._lights: # Change the light state only if necessary\n                self._lights = current_lights\n                world.player.set_light_state(carla.VehicleLightState(self._lights))\n            world.player.apply_control(self._control)\n\n    def _parse_vehicle_keys(self, keys, milliseconds):\n        if keys[K_UP] or keys[K_w]:\n            self._control.throttle = min(self._control.throttle + 0.1, 1.00)\n        else:\n            self._control.throttle = 0.0\n\n        if keys[K_DOWN] or keys[K_s]:\n            self._control.brake = min(self._control.brake + 0.2, 1)\n        else:\n            self._control.brake = 0\n\n        steer_increment = 5e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            if self._steer_cache > 0:\n                self._steer_cache = 0\n            else:\n                self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            if self._steer_cache < 0:\n                self._steer_cache = 0\n            else:\n                self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n        self._steer_cache = min(0.7, max(-0.7, self._steer_cache))\n        self._control.steer = round(self._steer_cache, 1)\n        self._control.hand_brake = keys[K_SPACE]\n\n    @staticmethod\n    def _is_quit_shortcut(key):\n        return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)\n\n\n# ==============================================================================\n# -- HUD -----------------------------------------------------------------------\n# ==============================================================================\n\n\nclass HUD(object):\n    def __init__(self, width, height):\n        self.dim = (width, height)\n        font = pygame.font.Font(pygame.font.get_default_font(), 20)\n        font_name = 'courier' if os.name == 'nt' else 'mono'\n        fonts = [x for x in pygame.font.get_fonts() if font_name in x]\n        default_font = 'ubuntumono'\n        mono = default_font if default_font in fonts else fonts[0]\n        mono = pygame.font.match_font(mono)\n        self._font_mono = pygame.font.Font(mono, 12 if os.name == 'nt' else 14)\n        self._notifications = FadingText(font, (width, 40), (0, height - 40))\n        self.help = HelpText(pygame.font.Font(mono, 16), width, height)\n        self.server_fps = 0\n        self.frame = 0\n        self.simulation_time = 0\n        self._show_info = True\n        self._info_text = []\n        self._server_clock = pygame.time.Clock()\n\n    def on_world_tick(self, timestamp):\n        self._server_clock.tick()\n        self.server_fps = self._server_clock.get_fps()\n        self.frame = timestamp.frame\n        self.simulation_time = timestamp.elapsed_seconds\n\n    def tick(self, world, clock):\n        self._notifications.tick(world, clock)\n        if not self._show_info:\n            return\n        t = world.player.get_transform()\n        v = world.player.get_velocity()\n        c = world.player.get_control()\n        compass = world.imu_sensor.compass\n        heading = 'N' if compass > 270.5 or compass < 89.5 else ''\n        heading += 'S' if 90.5 < compass < 269.5 else ''\n        heading += 'E' if 0.5 < compass < 179.5 else ''\n        heading += 'W' if 180.5 < compass < 359.5 else ''\n        colhist = world.collision_sensor.get_collision_history()\n        collision = [colhist[x + self.frame - 200] for x in range(0, 200)]\n        max_col = max(1.0, max(collision))\n        collision = [x / max_col for x in collision]\n        vehicles = world.world.get_actors().filter('vehicle.*')\n        self._info_text = [\n            'Server:  % 16.0f FPS' % self.server_fps,\n            'Client:  % 16.0f FPS' % clock.get_fps(),\n            '',\n            'Vehicle: % 20s' % get_actor_display_name(world.player, truncate=20),\n            'Map:     % 20s' % world.map.name.split('/')[-1],\n            'Simulation time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),\n            '',\n            'Speed:   % 15.0f km/h' % (3.6 * math.sqrt(v.x**2 + v.y**2 + v.z**2)),\n            u'Compass:% 17.0f\\N{DEGREE SIGN} % 2s' % (compass, heading),\n            'Accelero: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.accelerometer),\n            'Gyroscop: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.gyroscope),\n            'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (t.location.x, t.location.y)),\n            'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (world.gnss_sensor.lat, world.gnss_sensor.lon)),\n            'Height:  % 18.0f m' % t.location.z,\n            '']\n        self._info_text += [\n            ('Throttle:', c.throttle, 0.0, 1.0),\n            ('Steer:', c.steer, -1.0, 1.0),\n            ('Brake:', c.brake, 0.0, 1.0),\n            ('Reverse:', c.reverse),\n            ('Hand brake:', c.hand_brake),\n            ('Manual:', c.manual_gear_shift),\n            'Gear:        %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear)]\n        self._info_text += [\n            '',\n            'Collision:',\n            collision,\n            '',\n            'Number of vehicles: % 8d' % len(vehicles)]\n        if len(vehicles) > 1:\n            self._info_text += ['Nearby vehicles:']\n            distance = lambda l: math.sqrt((l.x - t.location.x)**2 + (l.y - t.location.y)**2 + (l.z - t.location.z)**2)\n            vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.player.id]\n            for d, vehicle in sorted(vehicles, key=lambda vehicles: vehicles[0]):\n                if d > 200.0:\n                    break\n                vehicle_type = get_actor_display_name(vehicle, truncate=22)\n                self._info_text.append('% 4dm %s' % (d, vehicle_type))\n\n    def toggle_info(self):\n        self._show_info = not self._show_info\n\n    def notification(self, text, seconds=2.0):\n        self._notifications.set_text(text, seconds=seconds)\n\n    def error(self, text):\n        self._notifications.set_text('Error: %s' % text, (255, 0, 0))\n\n    def render(self, display):\n        if self._show_info:\n            info_surface = pygame.Surface((220, self.dim[1]))\n            info_surface.set_alpha(100)\n            display.blit(info_surface, (0, 0))\n            v_offset = 4\n            bar_h_offset = 100\n            bar_width = 106\n            for item in self._info_text:\n                if v_offset + 18 > self.dim[1]:\n                    break\n                if isinstance(item, list):\n                    if len(item) > 1:\n                        points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)]\n                        pygame.draw.lines(display, (255, 136, 0), False, points, 2)\n                    item = None\n                    v_offset += 18\n                elif isinstance(item, tuple):\n                    if isinstance(item[1], bool):\n                        rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6))\n                        pygame.draw.rect(display, (255, 255, 255), rect, 0 if item[1] else 1)\n                    else:\n                        rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6))\n                        pygame.draw.rect(display, (255, 255, 255), rect_border, 1)\n                        f = (item[1] - item[2]) / (item[3] - item[2])\n                        if item[2] < 0.0:\n                            rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6))\n                        else:\n                            rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))\n                        pygame.draw.rect(display, (255, 255, 255), rect)\n                    item = item[0]\n                if item:  # At this point has to be a str.\n                    surface = self._font_mono.render(item, True, (255, 255, 255))\n                    display.blit(surface, (8, v_offset))\n                v_offset += 18\n        self._notifications.render(display)\n        self.help.render(display)\n\n\n# ==============================================================================\n# -- FadingText ----------------------------------------------------------------\n# ==============================================================================\n\n\nclass FadingText(object):\n    def __init__(self, font, dim, pos):\n        self.font = font\n        self.dim = dim\n        self.pos = pos\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n\n    def set_text(self, text, color=(255, 255, 255), seconds=2.0):\n        text_texture = self.font.render(text, True, color)\n        self.surface = pygame.Surface(self.dim)\n        self.seconds_left = seconds\n        self.surface.fill((0, 0, 0, 0))\n        self.surface.blit(text_texture, (10, 11))\n\n    def tick(self, _, clock):\n        delta_seconds = 1e-3 * clock.get_time()\n        self.seconds_left = max(0.0, self.seconds_left - delta_seconds)\n        self.surface.set_alpha(500.0 * self.seconds_left)\n\n    def render(self, display):\n        display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- HelpText ------------------------------------------------------------------\n# ==============================================================================\n\n\nclass HelpText(object):\n    \"\"\"Helper class to handle text output using pygame\"\"\"\n    def __init__(self, font, width, height):\n        lines = __doc__.split('\\n')\n        self.font = font\n        self.line_space = 18\n        self.dim = (780, len(lines) * self.line_space + 12)\n        self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n        self.surface.fill((0, 0, 0, 0))\n        for n, line in enumerate(lines):\n            text_texture = self.font.render(line, True, (255, 255, 255))\n            self.surface.blit(text_texture, (22, n * self.line_space))\n            self._render = False\n        self.surface.set_alpha(220)\n\n    def toggle(self):\n        self._render = not self._render\n\n    def render(self, display):\n        if self._render:\n            display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- CollisionSensor -----------------------------------------------------------\n# ==============================================================================\n\n\nclass CollisionSensor(object):\n    def __init__(self, parent_actor, hud):\n        self.sensor = None\n        self.history = []\n        self._parent = parent_actor\n        self.hud = hud\n        world = self._parent.get_world()\n        bp = world.get_blueprint_library().find('sensor.other.collision')\n        self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)\n        # We need to pass the lambda a weak reference to self to avoid circular\n        # reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(lambda event: CollisionSensor._on_collision(weak_self, event))\n\n    def get_collision_history(self):\n        history = collections.defaultdict(int)\n        for frame, intensity in self.history:\n            history[frame] += intensity\n        return history\n\n    @staticmethod\n    def _on_collision(weak_self, event):\n        self = weak_self()\n        if not self:\n            return\n        actor_type = get_actor_display_name(event.other_actor)\n        self.hud.notification('Collision with %r' % actor_type)\n        impulse = event.normal_impulse\n        intensity = math.sqrt(impulse.x**2 + impulse.y**2 + impulse.z**2)\n        self.history.append((event.frame, intensity))\n        if len(self.history) > 4000:\n            self.history.pop(0)\n\n\n# ==============================================================================\n# -- LaneInvasionSensor --------------------------------------------------------\n# ==============================================================================\n\n\nclass LaneInvasionSensor(object):\n    def __init__(self, parent_actor, hud):\n        self.sensor = None\n\n        # If the spawn object is not a vehicle, we cannot use the Lane Invasion Sensor\n        if parent_actor.type_id.startswith(\"vehicle.\"):\n            self._parent = parent_actor\n            self.hud = hud\n            world = self._parent.get_world()\n            bp = world.get_blueprint_library().find('sensor.other.lane_invasion')\n            self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)\n            # We need to pass the lambda a weak reference to self to avoid circular\n            # reference.\n            weak_self = weakref.ref(self)\n            self.sensor.listen(lambda event: LaneInvasionSensor._on_invasion(weak_self, event))\n\n    @staticmethod\n    def _on_invasion(weak_self, event):\n        self = weak_self()\n        if not self:\n            return\n        lane_types = set(x.type for x in event.crossed_lane_markings)\n        text = ['%r' % str(x).split()[-1] for x in lane_types]\n        self.hud.notification('Crossed line %s' % ' and '.join(text))\n\n\n# ==============================================================================\n# -- GnssSensor ----------------------------------------------------------------\n# ==============================================================================\n\n\nclass GnssSensor(object):\n    def __init__(self, parent_actor):\n        self.sensor = None\n        self._parent = parent_actor\n        self.lat = 0.0\n        self.lon = 0.0\n        world = self._parent.get_world()\n        bp = world.get_blueprint_library().find('sensor.other.gnss')\n        self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)), attach_to=self._parent)\n        # We need to pass the lambda a weak reference to self to avoid circular\n        # reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(lambda event: GnssSensor._on_gnss_event(weak_self, event))\n\n    @staticmethod\n    def _on_gnss_event(weak_self, event):\n        self = weak_self()\n        if not self:\n            return\n        self.lat = event.latitude\n        self.lon = event.longitude\n\n\n# ==============================================================================\n# -- IMUSensor -----------------------------------------------------------------\n# ==============================================================================\n\n\nclass IMUSensor(object):\n    def __init__(self, parent_actor):\n        self.sensor = None\n        self._parent = parent_actor\n        self.accelerometer = (0.0, 0.0, 0.0)\n        self.gyroscope = (0.0, 0.0, 0.0)\n        self.compass = 0.0\n        world = self._parent.get_world()\n        bp = world.get_blueprint_library().find('sensor.other.imu')\n        self.sensor = world.spawn_actor(\n            bp, carla.Transform(), attach_to=self._parent)\n        # We need to pass the lambda a weak reference to self to avoid circular\n        # reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(\n            lambda sensor_data: IMUSensor._IMU_callback(weak_self, sensor_data))\n\n    @staticmethod\n    def _IMU_callback(weak_self, sensor_data):\n        self = weak_self()\n        if not self:\n            return\n        limits = (-99.9, 99.9)\n        self.accelerometer = (\n            max(limits[0], min(limits[1], sensor_data.accelerometer.x)),\n            max(limits[0], min(limits[1], sensor_data.accelerometer.y)),\n            max(limits[0], min(limits[1], sensor_data.accelerometer.z)))\n        self.gyroscope = (\n            max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.x))),\n            max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.y))),\n            max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.z))))\n        self.compass = math.degrees(sensor_data.compass)\n\n\n# ==============================================================================\n# -- RadarSensor ---------------------------------------------------------------\n# ==============================================================================\n\n\nclass RadarSensor(object):\n    def __init__(self, parent_actor):\n        self.sensor = None\n        self._parent = parent_actor\n        bound_x = 0.5 + self._parent.bounding_box.extent.x\n        bound_y = 0.5 + self._parent.bounding_box.extent.y\n        bound_z = 0.5 + self._parent.bounding_box.extent.z\n\n        self.velocity_range = 7.5 # m/s\n        world = self._parent.get_world()\n        self.debug = world.debug\n        bp = world.get_blueprint_library().find('sensor.other.radar')\n        bp.set_attribute('horizontal_fov', str(35))\n        bp.set_attribute('vertical_fov', str(20))\n        self.sensor = world.spawn_actor(\n            bp,\n            carla.Transform(\n                carla.Location(x=bound_x + 0.05, z=bound_z+0.05),\n                carla.Rotation(pitch=5)),\n            attach_to=self._parent)\n        # We need a weak reference to self to avoid circular reference.\n        weak_self = weakref.ref(self)\n        self.sensor.listen(\n            lambda radar_data: RadarSensor._Radar_callback(weak_self, radar_data))\n\n    @staticmethod\n    def _Radar_callback(weak_self, radar_data):\n        self = weak_self()\n        if not self:\n            return\n        # To get a numpy [[vel, altitude, azimuth, depth],...[,,,]]:\n        # points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))\n        # points = np.reshape(points, (len(radar_data), 4))\n\n        current_rot = radar_data.transform.rotation\n        for detect in radar_data:\n            azi = math.degrees(detect.azimuth)\n            alt = math.degrees(detect.altitude)\n            # The 0.25 adjusts a bit the distance so the dots can\n            # be properly seen\n            fw_vec = carla.Vector3D(x=detect.depth - 0.25)\n            carla.Transform(\n                carla.Location(),\n                carla.Rotation(\n                    pitch=current_rot.pitch + alt,\n                    yaw=current_rot.yaw + azi,\n                    roll=current_rot.roll)).transform(fw_vec)\n\n            def clamp(min_v, max_v, value):\n                return max(min_v, min(value, max_v))\n\n            norm_velocity = detect.velocity / self.velocity_range # range [-1, 1]\n            r = int(clamp(0.0, 1.0, 1.0 - norm_velocity) * 255.0)\n            g = int(clamp(0.0, 1.0, 1.0 - abs(norm_velocity)) * 255.0)\n            b = int(abs(clamp(- 1.0, 0.0, - 1.0 - norm_velocity)) * 255.0)\n            self.debug.draw_point(\n                radar_data.transform.location + fw_vec,\n                size=0.075,\n                life_time=0.06,\n                persistent_lines=False,\n                color=carla.Color(r, g, b))\n\n# ==============================================================================\n# -- CameraManager -------------------------------------------------------------\n# ==============================================================================\n\n\nclass CameraManager(object):\n    def __init__(self, parent_actor, hud):\n        self.sensor = None\n        self.surface = None\n        self._parent = parent_actor\n        self.hud = hud\n        self.recording = False\n        bound_x = 0.5 + self._parent.bounding_box.extent.x\n        bound_y = 0.5 + self._parent.bounding_box.extent.y\n        bound_z = 0.5 + self._parent.bounding_box.extent.z\n        Attachment = carla.AttachmentType\n\n        self._camera_transforms = [\n            (carla.Transform(carla.Location(x=-2.0*bound_x, y=+0.0*bound_y, z=2.0*bound_z), carla.Rotation(pitch=8.0)), Attachment.SpringArm),\n            (carla.Transform(carla.Location(x=+0.8*bound_x, y=+0.0*bound_y, z=1.3*bound_z)), Attachment.Rigid),\n            (carla.Transform(carla.Location(x=+1.9*bound_x, y=+1.0*bound_y, z=1.2*bound_z)), Attachment.SpringArm),\n            (carla.Transform(carla.Location(x=-2.8*bound_x, y=+0.0*bound_y, z=4.6*bound_z), carla.Rotation(pitch=6.0)), Attachment.SpringArm),\n            (carla.Transform(carla.Location(x=-1.0, y=-1.0*bound_y, z=0.4*bound_z)), Attachment.Rigid)]\n\n        self.transform_index = 1\n        self.sensors = [['sensor.camera.rgb', cc.Raw, 'Camera RGB']]\n        world = self._parent.get_world()\n        bp_library = world.get_blueprint_library()\n        for item in self.sensors:\n            bp = bp_library.find(item[0])\n            bp.set_attribute('image_size_x', str(hud.dim[0]))\n            bp.set_attribute('image_size_y', str(hud.dim[1]))\n            bp.set_attribute('gamma', '2.2')\n            item.append(bp)\n        self.index = None\n\n    def toggle_camera(self):\n        self.transform_index = (self.transform_index + 1) % len(self._camera_transforms)\n        self.set_sensor(self.index, notify=False, force_respawn=True)\n\n    def set_sensor(self, index, notify=True, force_respawn=False):\n        index = index % len(self.sensors)\n        needs_respawn = True if self.index is None else \\\n            (force_respawn or (self.sensors[index][2] != self.sensors[self.index][2]))\n        if needs_respawn:\n            if self.sensor is not None:\n                self.sensor.destroy()\n                self.surface = None\n            self.sensor = self._parent.get_world().spawn_actor(\n                self.sensors[index][-1],\n                self._camera_transforms[self.transform_index][0],\n                attach_to=self._parent,\n                attachment_type=self._camera_transforms[self.transform_index][1])\n            # We need to pass the lambda a weak reference to self to avoid\n            # circular reference.\n            weak_self = weakref.ref(self)\n            self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image))\n        if notify:\n            self.hud.notification(self.sensors[index][2])\n        self.index = index\n\n    def toggle_recording(self):\n        self.recording = not self.recording\n        self.hud.notification('Recording %s' % ('On' if self.recording else 'Off'))\n\n    def render(self, display):\n        if self.surface is not None:\n            display.blit(self.surface, (0, 0))\n\n    @staticmethod\n    def _parse_image(weak_self, image):\n        self = weak_self()\n        if not self:\n            return\n        if self.sensors[self.index][0].startswith('sensor.lidar'):\n            points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))\n            points = np.reshape(points, (int(points.shape[0] / 4), 4))\n            lidar_data = np.array(points[:, :2])\n            lidar_data *= min(self.hud.dim) / (2.0 * self.lidar_range)\n            lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1])\n            lidar_data = np.fabs(lidar_data)  # pylint: disable=E1111\n            lidar_data = lidar_data.astype(np.int32)\n            lidar_data = np.reshape(lidar_data, (-1, 2))\n            lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3)\n            lidar_img = np.zeros((lidar_img_size), dtype=np.uint8)\n            lidar_img[tuple(lidar_data.T)] = (255, 255, 255)\n            self.surface = pygame.surfarray.make_surface(lidar_img)\n        elif self.sensors[self.index][0].startswith('sensor.camera.dvs'):\n            # Example of converting the raw_data from a carla.DVSEventArray\n            # sensor into a NumPy array and using it as an image\n            dvs_events = np.frombuffer(image.raw_data, dtype=np.dtype([\n                ('x', np.uint16), ('y', np.uint16), ('t', np.int64), ('pol', np.bool)]))\n            dvs_img = np.zeros((image.height, image.width, 3), dtype=np.uint8)\n            # Blue is positive, red is negative\n            dvs_img[dvs_events[:]['y'], dvs_events[:]['x'], dvs_events[:]['pol'] * 2] = 255\n            self.surface = pygame.surfarray.make_surface(dvs_img.swapaxes(0, 1))\n        elif self.sensors[self.index][0].startswith('sensor.camera.optical_flow'):\n            image = image.get_color_coded_flow()\n            array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n            array = np.reshape(array, (image.height, image.width, 4))\n            array = array[:, :, :3]\n            array = array[:, :, ::-1]\n            self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))\n        else:\n            image.convert(self.sensors[self.index][1])\n            array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n            array = np.reshape(array, (image.height, image.width, 4))\n            array = array[:, :, :3]\n            array = array[:, :, ::-1]\n            self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))\n        if self.recording:\n            image.save_to_disk('_out/%08d' % image.frame)\n\n\n# ==============================================================================\n# -- game_loop() ---------------------------------------------------------------\n# ==============================================================================\n\ndef game_loop(args):\n    pygame.init()\n    pygame.font.init()\n    world = None\n\n    try:\n        client = carla.Client(args.host, args.port)\n        client.set_timeout(20.0)\n        sim_world = client.get_world()\n\n        display = pygame.display.set_mode(\n            (args.width, args.height),\n            pygame.HWSURFACE | pygame.DOUBLEBUF)\n        display.fill((0,0,0))\n        pygame.display.flip()\n\n        hud = HUD(args.width, args.height)\n        world = World(sim_world, hud, args)\n        controller = KeyboardControl(world, args.autopilot)\n\n        sim_world.wait_for_tick()\n\n        clock = pygame.time.Clock()\n        while True:\n            clock.tick_busy_loop(60)\n            if controller.parse_events(client, world, clock):\n                return\n            if not world.tick(clock, args.wait_for_repetitions):\n                return\n            world.render(display)\n            pygame.display.flip()\n\n    finally:\n\n        if (world and world.recording_enabled):\n            client.stop_recorder()\n\n        if world is not None:\n            # prevent destruction of ego vehicle\n            if args.keep_ego_vehicle:\n                world.player = None\n            world.destroy()\n\n        pygame.quit()\n\n\n# ==============================================================================\n# -- main() --------------------------------------------------------------------\n# ==============================================================================\n\n\ndef main():\n    argparser = argparse.ArgumentParser(\n        description='CARLA Manual Control Client')\n    argparser.add_argument(\n        '-v', '--verbose',\n        action='store_true',\n        dest='debug',\n        help='print debug information')\n    argparser.add_argument(\n        '--host',\n        metavar='H',\n        default='127.0.0.1',\n        help='IP of the host server (default: 127.0.0.1)')\n    argparser.add_argument(\n        '-p', '--port',\n        metavar='P',\n        default=2000,\n        type=int,\n        help='TCP port to listen to (default: 2000)')\n    argparser.add_argument(\n        '-a', '--autopilot',\n        action='store_true',\n        help='enable autopilot. This does not autocomplete the scenario')\n    argparser.add_argument(\n        '--rolename',\n        metavar='NAME',\n        default='hero',\n        help='role name of ego vehicle to control (default: \"hero\")')\n    argparser.add_argument(\n        '--res',\n        metavar='WIDTHxHEIGHT',\n        default='1280x720',\n        help='window resolution (default: 1280x720)')\n    argparser.add_argument(\n        '--keep_ego_vehicle',\n        action='store_true',\n        help='do not destroy ego vehicle on exit')\n    argparser.add_argument(\n        '--wait-for-repetitions',\n        action='store_true',\n        help='Avoids stopping the manual control when the scenario ends.')\n    args = argparser.parse_args()\n\n    args.width, args.height = [int(x) for x in args.res.split('x')]\n\n    log_level = logging.DEBUG if args.debug else logging.INFO\n    logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)\n\n    logging.info('listening to server %s:%s', args.host, args.port)\n\n    print(__doc__)\n\n    try:\n\n        game_loop(args)\n\n    except KeyboardInterrupt:\n        print('\\nCancelled by user. Bye!')\n    except Exception as error:\n        logging.exception(error)\n\n\nif __name__ == '__main__':\n\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/metrics_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n# Allows the execution of user-implemented metrics\n\n\"\"\"\nWelcome to the ScenarioRunner's metric module\n\nThis is the main script to be executed when running a metric.\nIt is responsible of parsing all the information and executing\nthe metric specified by the user.\n\"\"\"\n\nimport os\nimport sys\nimport importlib\nimport inspect\nimport json\nimport argparse\nfrom argparse import RawTextHelpFormatter\n\nimport carla\nfrom srunner.metrics.tools.metrics_log import MetricsLog\n\n\nclass MetricsManager(object):\n    \"\"\"\n    Main class of the metrics module. Handles the parsing and execution of\n    the metrics.\n    \"\"\"\n\n    def __init__(self, args):\n        \"\"\"\n        Initialization of the metrics manager. This creates the client, needed to parse\n        the information from the recorder, extract the metrics class, and runs it\n        \"\"\"\n        self._args = args\n\n        # Parse the arguments\n        recorder_str = self._get_recorder(self._args.log)\n        criteria_dict = self._get_criteria(self._args.criteria)\n\n        # Get the correct world and load it\n        map_name = self._get_recorder_map(recorder_str)\n        world = self._client.load_world(map_name)\n        town_map = world.get_map()\n\n        # Instanciate the MetricsLog, used to querry the needed information\n        log = MetricsLog(recorder_str)\n\n        # Read and run the metric class\n        metric_class = self._get_metric_class(self._args.metric)\n        metric_class(town_map, log, criteria_dict)\n\n    def _get_recorder(self, log):\n        \"\"\"\n        Parses the log argument into readable information\n        \"\"\"\n\n        # Get the log information.\n        self._client = carla.Client(self._args.host, int(self._args.port))\n        recorder_file = \"{}/{}\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\"), log)\n\n        # Check that the file is correct\n        if recorder_file[-4:] != '.log':\n            print(\"ERROR: The log argument has to point to a .log file\")\n            sys.exit(-1)\n        if not os.path.exists(recorder_file):\n            print(\"ERROR: The specified log file does not exist\")\n            sys.exit(-1)\n\n        recorder_str = self._client.show_recorder_file_info(recorder_file, True)\n\n        return recorder_str\n\n    def _get_criteria(self, criteria_file):\n        \"\"\"\n        Parses the criteria argument into a dictionary\n        \"\"\"\n        if criteria_file:\n            with open(criteria_file) as fd:\n                criteria_dict = json.load(fd)\n        else:\n            criteria_dict = None\n\n        return criteria_dict\n\n    def _get_metric_class(self, metric_file):\n        \"\"\"\n        Function to extract the metrics class from the path given by the metrics\n        argument. Returns the first class found that is a child of BasicMetric\n\n        Args:\n            metric_file (str): path to the metric's file.\n        \"\"\"\n        # Get their module\n        module_name = os.path.basename(metric_file).split('.')[0]\n        sys.path.insert(0, os.path.dirname(metric_file))\n        metric_module = importlib.import_module(module_name)\n\n        # And their members of type class\n        for member in inspect.getmembers(metric_module, inspect.isclass):\n            # Get the first one with parent BasicMetrics\n            member_parent = member[1].__bases__[0]\n            if 'BasicMetric' in str(member_parent):\n                return member[1]\n\n        print(\"No child class of BasicMetric was found ... Exiting\")\n        sys.exit(-1)\n\n    def _get_recorder_map(self, recorder_str):\n        \"\"\"\n        Returns the name of the map the simulation took place in\n        \"\"\"\n\n        header = recorder_str.split(\"\\n\")\n        sim_map = header[1][5:]\n\n        return sim_map\n\n\ndef main():\n    \"\"\"\n    main function\n    \"\"\"\n\n    # pylint: disable=line-too-long\n    description = (\"Scenario Runner's metrics module. Evaluate the execution of a specific scenario by developing your own metric.\\n\")\n\n    parser = argparse.ArgumentParser(description=description,\n                                    formatter_class=RawTextHelpFormatter)\n    parser.add_argument('--host', default='127.0.0.1',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', '-p', default=2000,\n                        help='TCP port to listen to (default: 2000)')\n    parser.add_argument('--log', required=True,\n                        help='Path to the CARLA recorder .log file (relative to SCENARIO_RUNNER_ROOT).\\nThis file is created by the record functionality at ScenarioRunner')\n    parser.add_argument('--metric', required=True,\n                        help='Path to the .py file defining the used metric.\\nSome examples at srunner/metrics')\n    parser.add_argument('--criteria', default=\"\",\n                        help='Path to the .json file with the criteria information.\\nThis file is created by the record functionality at ScenarioRunner')\n    # pylint: enable=line-too-long\n\n    args = parser.parse_args()\n\n    MetricsManager(args)\n\nif __name__ == \"__main__\":\n    sys.exit(main())\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/mkdocs.yml",
    "content": "site_name: CARLA ScenarioRunner\nrepo_url: https://github.com/carla-simulator/scenario_runner\ndocs_dir: Docs\nedit_uri: 'edit/master/Docs/'\ntheme: readthedocs\nextra_css: [extra.css]\n\nnav:\n- Home: index.md\n- Quick start:\n  - Get ScenarioRunner: getting_scenariorunner.md\n  - First steps: getting_started.md\n  - Create a new scenario: creating_new_scenario.md\n  - Metrics module: metrics_module.md\n  - FAQ: FAQ.md\n  - Release Notes: CHANGELOG.md\n- References:\n  - List of scenarios: list_of_scenarios.md\n  - OpenSCENARIO support: openscenario_support.md\n- Contributing:\n  - Code of conduct: CODE_OF_CONDUCT.md\n  - Coding standard: coding_standard.md\n  - Contribution guidelines: CONTRIBUTING.md\n\nmarkdown_extensions:\n  - admonition\n  - markdown_include.include:\n      base_path: '.'\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/no_rendering_mode.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n# Allows visualising a 2D map generated by vehicles.\n\n\"\"\"\nWelcome to CARLA No-Rendering Mode Visualizer\n\n    TAB          : toggle hero mode\n    Mouse Wheel  : zoom in / zoom out\n    Mouse Drag   : move map (map mode only)\n\n    W            : throttle\n    S            : brake\n    AD           : steer\n    Q            : toggle reverse\n    Space        : hand-brake\n    P            : toggle autopilot\n    M            : toggle manual transmission\n    ,/.          : gear up/down\n\n    F1           : toggle HUD\n    I            : toggle actor ids\n    H/?          : toggle help\n    ESC          : quit\n\"\"\"\n\n# ==============================================================================\n# -- find carla module ---------------------------------------------------------\n# ==============================================================================\n\nimport glob\nimport os\nimport sys\n\ntry:\n    sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % (\n        sys.version_info.major,\n        sys.version_info.minor,\n        'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])\nexcept IndexError:\n    pass\n\n# ==============================================================================\n# -- imports -------------------------------------------------------------------\n# ==============================================================================\n\nimport carla\nfrom carla import TrafficLightState as tls\n\nimport argparse\nimport logging\nimport datetime\nimport weakref\nimport math\nimport random\n\ntry:\n    import pygame\n    from pygame.locals import KMOD_CTRL\n    from pygame.locals import KMOD_SHIFT\n    from pygame.locals import K_COMMA\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_ESCAPE\n    from pygame.locals import K_F1\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_PERIOD\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_SLASH\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_TAB\n    from pygame.locals import K_UP\n    from pygame.locals import K_a\n    from pygame.locals import K_d\n    from pygame.locals import K_h\n    from pygame.locals import K_i\n    from pygame.locals import K_m\n    from pygame.locals import K_p\n    from pygame.locals import K_q\n    from pygame.locals import K_s\n    from pygame.locals import K_w\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\n# ==============================================================================\n# -- Constants -----------------------------------------------------------------\n# ==============================================================================\n\n# Colors\n\n# We will use the color palette used in Tango Desktop Project (Each color is indexed depending on brightness level)\n# See: https://en.wikipedia.org/wiki/Tango_Desktop_Project\n\nCOLOR_BUTTER_0 = pygame.Color(252, 233, 79)\nCOLOR_BUTTER_1 = pygame.Color(237, 212, 0)\nCOLOR_BUTTER_2 = pygame.Color(196, 160, 0)\n\nCOLOR_ORANGE_0 = pygame.Color(252, 175, 62)\nCOLOR_ORANGE_1 = pygame.Color(245, 121, 0)\nCOLOR_ORANGE_2 = pygame.Color(209, 92, 0)\n\nCOLOR_CHOCOLATE_0 = pygame.Color(233, 185, 110)\nCOLOR_CHOCOLATE_1 = pygame.Color(193, 125, 17)\nCOLOR_CHOCOLATE_2 = pygame.Color(143, 89, 2)\n\nCOLOR_CHAMELEON_0 = pygame.Color(138, 226, 52)\nCOLOR_CHAMELEON_1 = pygame.Color(115, 210, 22)\nCOLOR_CHAMELEON_2 = pygame.Color(78, 154, 6)\n\nCOLOR_SKY_BLUE_0 = pygame.Color(114, 159, 207)\nCOLOR_SKY_BLUE_1 = pygame.Color(52, 101, 164)\nCOLOR_SKY_BLUE_2 = pygame.Color(32, 74, 135)\n\nCOLOR_PLUM_0 = pygame.Color(173, 127, 168)\nCOLOR_PLUM_1 = pygame.Color(117, 80, 123)\nCOLOR_PLUM_2 = pygame.Color(92, 53, 102)\n\nCOLOR_SCARLET_RED_0 = pygame.Color(239, 41, 41)\nCOLOR_SCARLET_RED_1 = pygame.Color(204, 0, 0)\nCOLOR_SCARLET_RED_2 = pygame.Color(164, 0, 0)\n\nCOLOR_ALUMINIUM_0 = pygame.Color(238, 238, 236)\nCOLOR_ALUMINIUM_1 = pygame.Color(211, 215, 207)\nCOLOR_ALUMINIUM_2 = pygame.Color(186, 189, 182)\nCOLOR_ALUMINIUM_3 = pygame.Color(136, 138, 133)\nCOLOR_ALUMINIUM_4 = pygame.Color(85, 87, 83)\nCOLOR_ALUMINIUM_4_5 = pygame.Color(66, 62, 64)\nCOLOR_ALUMINIUM_5 = pygame.Color(46, 52, 54)\n\n\nCOLOR_WHITE = pygame.Color(255, 255, 255)\nCOLOR_BLACK = pygame.Color(0, 0, 0)\n\n\n# Module Defines\nMODULE_WORLD = 'WORLD'\nMODULE_HUD = 'HUD'\nMODULE_INPUT = 'INPUT'\n\nPIXELS_PER_METER = 12\n\nMAP_DEFAULT_SCALE = 0.1\nHERO_DEFAULT_SCALE = 1.0\n\nPIXELS_AHEAD_VEHICLE = 150\n\n# ==============================================================================\n# -- Util -----------------------------------------------------------\n# ==============================================================================\n\n\ndef get_actor_display_name(actor, truncate=250):\n    name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])\n    return (name[:truncate - 1] + u'\\u2026') if len(name) > truncate else name\n\n\nclass Util(object):\n\n    @staticmethod\n    def blits(destination_surface, source_surfaces, rect=None, blend_mode=0):\n        for surface in source_surfaces:\n            destination_surface.blit(surface[0], surface[1], rect, blend_mode)\n\n    @staticmethod\n    def length(v):\n        return math.sqrt(v.x**2 + v.y**2 + v.z**2)\n\n    @staticmethod\n    def get_bounding_box(actor):\n        bb = actor.trigger_volume.extent\n        corners = [carla.Location(x=-bb.x, y=-bb.y),\n                   carla.Location(x=bb.x, y=-bb.y),\n                   carla.Location(x=bb.x, y=bb.y),\n                   carla.Location(x=-bb.x, y=bb.y),\n                   carla.Location(x=-bb.x, y=-bb.y)]\n        corners = [x + actor.trigger_volume.location for x in corners]\n        t = actor.get_transform()\n        t.transform(corners)\n        return corners\n\n# ==============================================================================\n# -- ModuleManager -------------------------------------------------------------\n# ==============================================================================\n\n\nclass ModuleManager(object):\n    def __init__(self):\n        self.modules = []\n\n    def register_module(self, module):\n        self.modules.append(module)\n\n    def clear_modules(self):\n        del self.modules[:]\n\n    def tick(self, clock):\n        # Update all the modules\n        for module in self.modules:\n            module.tick(clock)\n\n    def render(self, display):\n        display.fill(COLOR_ALUMINIUM_4)\n        for module in self.modules:\n            module.render(display)\n\n    def get_module(self, name):\n        for module in self.modules:\n            if module.name == name:\n                return module\n\n    def start_modules(self):\n        for module in self.modules:\n            module.start()\n\n\n# ==============================================================================\n# -- FadingText ----------------------------------------------------------------\n# ==============================================================================\n\n\nclass FadingText(object):\n    def __init__(self, font, dim, pos):\n        self.font = font\n        self.dim = dim\n        self.pos = pos\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n\n    def set_text(self, text, color=COLOR_WHITE, seconds=2.0):\n        text_texture = self.font.render(text, True, color)\n        self.surface = pygame.Surface(self.dim)\n        self.seconds_left = seconds\n        self.surface.fill(COLOR_BLACK)\n        self.surface.blit(text_texture, (10, 11))\n\n    def tick(self, clock):\n        delta_seconds = 1e-3 * clock.get_time()\n        self.seconds_left = max(0.0, self.seconds_left - delta_seconds)\n        self.surface.set_alpha(500.0 * self.seconds_left)\n\n    def render(self, display):\n        display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- HelpText ------------------------------------------------------------------\n# ==============================================================================\n\n\nclass HelpText(object):\n    def __init__(self, font, width, height):\n        lines = __doc__.split('\\n')\n        self.font = font\n        self.dim = (680, len(lines) * 22 + 12)\n        self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])\n        self.seconds_left = 0\n        self.surface = pygame.Surface(self.dim)\n        self.surface.fill(COLOR_BLACK)\n        for n, line in enumerate(lines):\n            text_texture = self.font.render(line, True, COLOR_WHITE)\n            self.surface.blit(text_texture, (22, n * 22))\n            self._render = False\n        self.surface.set_alpha(220)\n\n    def toggle(self):\n        self._render = not self._render\n\n    def render(self, display):\n        if self._render:\n            display.blit(self.surface, self.pos)\n\n\n# ==============================================================================\n# -- ModuleHUD -----------------------------------------------------------------\n# ==============================================================================\n\n\nclass ModuleHUD (object):\n\n    def __init__(self, name, width, height):\n        self.name = name\n        self.dim = (width, height)\n        self._init_hud_params()\n        self._init_data_params()\n\n    def start(self):\n        pass\n\n    def _init_hud_params(self):\n        fonts = [x for x in pygame.font.get_fonts() if 'mono' in x]\n        default_font = 'ubuntumono'\n        mono = default_font if default_font in fonts else fonts[0]\n        mono = pygame.font.match_font(mono)\n        self._font_mono = pygame.font.Font(mono, 14)\n        self._header_font = pygame.font.SysFont('Arial', 14, True)\n        self.help = HelpText(pygame.font.Font(mono, 24), *self.dim)\n        self._notifications = FadingText(\n            pygame.font.Font(pygame.font.get_default_font(), 20),\n            (self.dim[0], 40), (0, self.dim[1] - 40))\n\n    def _init_data_params(self):\n        self.show_info = True\n        self.show_actor_ids = False\n        self._info_text = {}\n\n    def notification(self, text, seconds=2.0):\n        self._notifications.set_text(text, seconds=seconds)\n\n    def tick(self, clock):\n        self._notifications.tick(clock)\n\n    def add_info(self, module_name, info):\n        self._info_text[module_name] = info\n\n    def render_vehicles_ids(self, vehicle_id_surface, list_actors, world_to_pixel, hero_actor, hero_transform):\n        vehicle_id_surface.fill(COLOR_BLACK)\n        if self.show_actor_ids:\n            vehicle_id_surface.set_alpha(150)\n            for actor in list_actors:\n                x, y = world_to_pixel(actor[1].location)\n\n                angle = 0\n                if hero_actor is not None:\n                    angle = -hero_transform.rotation.yaw - 90\n\n                color = COLOR_SKY_BLUE_0\n                if int(actor[0].attributes['number_of_wheels']) == 2:\n                    color = COLOR_CHOCOLATE_0\n                if actor[0].attributes['role_name'] == 'hero':\n                    color = COLOR_CHAMELEON_0\n\n                font_surface = self._header_font.render(str(actor[0].id), True, color)\n                rotated_font_surface = pygame.transform.rotate(font_surface, angle)\n                rect = rotated_font_surface.get_rect(center=(x, y))\n                vehicle_id_surface.blit(rotated_font_surface, rect)\n\n        return vehicle_id_surface\n\n    def render(self, display):\n        if self.show_info:\n            info_surface = pygame.Surface((240, self.dim[1]))\n            info_surface.set_alpha(100)\n            display.blit(info_surface, (0, 0))\n            v_offset = 4\n            bar_h_offset = 100\n            bar_width = 106\n            i = 0\n            for module_name, module_info in self._info_text.items():\n                if not module_info:\n                    continue\n                surface = self._header_font.render(module_name, True, COLOR_ALUMINIUM_0).convert_alpha()\n                display.blit(surface, (8 + bar_width / 2, 18 * i + v_offset))\n                v_offset += 12\n                i += 1\n                for item in module_info:\n                    if v_offset + 18 > self.dim[1]:\n                        break\n                    if isinstance(item, list):\n                        if len(item) > 1:\n                            points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)]\n                            pygame.draw.lines(display, (255, 136, 0), False, points, 2)\n                        item = None\n                    elif isinstance(item, tuple):\n                        if isinstance(item[1], bool):\n                            rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6))\n                            pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect, 0 if item[1] else 1)\n                        else:\n                            rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6))\n                            pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect_border, 1)\n                            f = (item[1] - item[2]) / (item[3] - item[2])\n                            if item[2] < 0.0:\n                                rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6))\n                            else:\n                                rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))\n                            pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect)\n                        item = item[0]\n                    if item:  # At this point has to be a str.\n                        surface = self._font_mono.render(item, True, COLOR_ALUMINIUM_0).convert_alpha()\n                        display.blit(surface, (8, 18 * i + v_offset))\n                    v_offset += 18\n                v_offset += 24\n        self._notifications.render(display)\n        self.help.render(display)\n\n\n# ==============================================================================\n# -- TrafficLightSurfaces ------------------------------------------------------\n# ==============================================================================\n\n\nclass TrafficLightSurfaces(object):\n    \"\"\"Holds the surfaces (scaled and rotated) for painting traffic lights\"\"\"\n\n    def __init__(self):\n        def make_surface(tl):\n            w = 40\n            surface = pygame.Surface((w, 3 * w), pygame.SRCALPHA)\n            surface.fill(COLOR_ALUMINIUM_5 if tl != 'h' else COLOR_ORANGE_2)\n            if tl != 'h':\n                hw = int(w / 2)\n                off = COLOR_ALUMINIUM_4\n                red = COLOR_SCARLET_RED_0\n                yellow = COLOR_BUTTER_0\n                green = COLOR_CHAMELEON_0\n                pygame.draw.circle(surface, red if tl == tls.Red else off, (hw, hw), int(0.4 * w))\n                pygame.draw.circle(surface, yellow if tl == tls.Yellow else off, (hw, w + hw), int(0.4 * w))\n                pygame.draw.circle(surface, green if tl == tls.Green else off, (hw, 2 * w + hw), int(0.4 * w))\n            return pygame.transform.smoothscale(surface, (15, 45) if tl != 'h' else (19, 49))\n        self._original_surfaces = {\n            'h': make_surface('h'),\n            tls.Red: make_surface(tls.Red),\n            tls.Yellow: make_surface(tls.Yellow),\n            tls.Green: make_surface(tls.Green),\n            tls.Off: make_surface(tls.Off),\n            tls.Unknown: make_surface(tls.Unknown)\n        }\n        self.surfaces = dict(self._original_surfaces)\n\n    def rotozoom(self, angle, scale):\n        for key, surface in self._original_surfaces.items():\n            self.surfaces[key] = pygame.transform.rotozoom(surface, angle, scale)\n\n\n# ==============================================================================\n# -- World ---------------------------------------------------------------------\n# ==============================================================================\n\n\nclass MapImage(object):\n    def __init__(self, carla_world, carla_map, pixels_per_meter, show_triggers, show_connections, show_spawn_points):\n        self._pixels_per_meter = pixels_per_meter\n        self.scale = 1.0\n        self.show_triggers = show_triggers\n        self.show_connections = show_connections\n        self.show_spawn_points = show_spawn_points\n\n        waypoints = carla_map.generate_waypoints(2)\n        margin = 50\n        max_x = max(waypoints, key=lambda x: x.transform.location.x).transform.location.x + margin\n        max_y = max(waypoints, key=lambda x: x.transform.location.y).transform.location.y + margin\n        min_x = min(waypoints, key=lambda x: x.transform.location.x).transform.location.x - margin\n        min_y = min(waypoints, key=lambda x: x.transform.location.y).transform.location.y - margin\n\n        self.width = max(max_x - min_x, max_y - min_y)\n        self._world_offset = (min_x, min_y)\n\n        width_in_pixels = int(self._pixels_per_meter * self.width)\n\n        self.big_map_surface = pygame.Surface((width_in_pixels, width_in_pixels)).convert()\n        self.draw_road_map(self.big_map_surface, carla_world, carla_map, self.world_to_pixel, self.world_to_pixel_width)\n        self.surface = self.big_map_surface\n\n    def draw_road_map(self, map_surface, carla_world, carla_map, world_to_pixel, world_to_pixel_width):\n        map_surface.fill(COLOR_ALUMINIUM_4)\n        precision = 0.05\n\n        def lane_marking_color_to_tango(lane_marking_color):\n            tango_color = COLOR_BLACK\n\n            if lane_marking_color == carla.LaneMarkingColor.White:\n                tango_color = COLOR_ALUMINIUM_2\n\n            elif lane_marking_color == carla.LaneMarkingColor.Blue:\n                tango_color = COLOR_SKY_BLUE_0\n\n            elif lane_marking_color == carla.LaneMarkingColor.Green:\n                tango_color = COLOR_CHAMELEON_0\n\n            elif lane_marking_color == carla.LaneMarkingColor.Red:\n                tango_color = COLOR_SCARLET_RED_0\n\n            elif lane_marking_color == carla.LaneMarkingColor.Yellow:\n                tango_color = COLOR_ORANGE_0\n\n            return tango_color\n\n        def draw_solid_line(surface, color, closed, points, width):\n            if len(points) >= 2:\n                pygame.draw.lines(surface, color, closed, points, width)\n\n        def draw_broken_line(surface, color, closed, points, width):\n            broken_lines = [x for n, x in enumerate(zip(*(iter(points),) * 20)) if n % 3 == 0]\n            for line in broken_lines:\n                pygame.draw.lines(surface, color, closed, line, width)\n\n        def get_lane_markings(lane_marking_type, lane_marking_color, waypoints, sign):\n            margin = 0.20\n            if lane_marking_type == carla.LaneMarkingType.Broken or (lane_marking_type == carla.LaneMarkingType.Solid):\n                marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints]\n                return [(lane_marking_type, lane_marking_color, marking_1)]\n            elif lane_marking_type == carla.LaneMarkingType.SolidBroken or lane_marking_type == carla.LaneMarkingType.BrokenSolid:\n                marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints]\n                marking_2 = [world_to_pixel(lateral_shift(w.transform,\n                                                          sign * (w.lane_width * 0.5 + margin * 2))) for w in waypoints]\n                return [(carla.LaneMarkingType.Solid, lane_marking_color, marking_1),\n                        (carla.LaneMarkingType.Broken, lane_marking_color, marking_2)]\n            elif lane_marking_type == carla.LaneMarkingType.BrokenBroken:\n                marking = [world_to_pixel(lateral_shift(w.transform,\n                                                        sign * (w.lane_width * 0.5 - margin))) for w in waypoints]\n                return [(carla.LaneMarkingType.Broken, lane_marking_color, marking)]\n            elif lane_marking_type == carla.LaneMarkingType.SolidSolid:\n                marking = [world_to_pixel(lateral_shift(w.transform,\n                                                        sign * ((w.lane_width * 0.5) - margin))) for w in waypoints]\n                return [(carla.LaneMarkingType.Solid, lane_marking_color, marking)]\n\n            return [(carla.LaneMarkingType.NONE, carla.LaneMarkingColor.Other, [])]\n\n        def draw_lane_marking(surface, waypoints, is_left):\n            sign = -1 if is_left else 1\n            lane_marking = None\n\n            marking_type = carla.LaneMarkingType.NONE\n            previous_marking_type = carla.LaneMarkingType.NONE\n\n            marking_color = carla.LaneMarkingColor.Other\n            previous_marking_color = carla.LaneMarkingColor.Other\n\n            waypoints_list = []\n            temp_waypoints = []\n            current_lane_marking = carla.LaneMarkingType.NONE\n            for sample in waypoints:\n                lane_marking = sample.left_lane_marking if sign < 0 else sample.right_lane_marking\n\n                if lane_marking is None:\n                    continue\n\n                marking_type = lane_marking.type\n                marking_color = lane_marking.color\n\n                if current_lane_marking != marking_type:\n                    markings = get_lane_markings(\n                        previous_marking_type,\n                        lane_marking_color_to_tango(previous_marking_color),\n                        temp_waypoints,\n                        sign)\n                    current_lane_marking = marking_type\n\n                    for marking in markings:\n                        waypoints_list.append(marking)\n\n                    temp_waypoints = temp_waypoints[-1:]\n\n                else:\n                    temp_waypoints.append((sample))\n                    previous_marking_type = marking_type\n                    previous_marking_color = marking_color\n\n            # Add last marking\n            last_markings = get_lane_markings(\n                previous_marking_type,\n                lane_marking_color_to_tango(previous_marking_color),\n                temp_waypoints,\n                sign)\n            for marking in last_markings:\n                waypoints_list.append(marking)\n\n            for markings in waypoints_list:\n                if markings[0] == carla.LaneMarkingType.Solid:\n                    draw_solid_line(surface, markings[1], False, markings[2], 2)\n                elif markings[0] == carla.LaneMarkingType.Broken:\n                    draw_broken_line(surface, markings[1], False, markings[2], 2)\n\n        def draw_arrow(surface, transform, color=COLOR_ALUMINIUM_2):\n            transform.rotation.yaw += 180\n            forward = transform.get_forward_vector()\n            transform.rotation.yaw += 90\n            right_dir = transform.get_forward_vector()\n            end = transform.location\n            start = end - 2.0 * forward\n            right = start + 0.8 * forward + 0.4 * right_dir\n            left = start + 0.8 * forward - 0.4 * right_dir\n            pygame.draw.lines(\n                surface, color, False, [\n                    world_to_pixel(x) for x in [\n                        start, end]], 4)\n            pygame.draw.lines(\n                surface, color, False, [\n                    world_to_pixel(x) for x in [\n                        left, start, right]], 4)\n\n        def draw_traffic_signs(surface, font_surface, actor, color=COLOR_ALUMINIUM_2, trigger_color=COLOR_PLUM_0):\n            transform = actor.get_transform()\n            waypoint = carla_map.get_waypoint(transform.location)\n\n            angle = -waypoint.transform.rotation.yaw - 90.0\n            font_surface = pygame.transform.rotate(font_surface, angle)\n            pixel_pos = world_to_pixel(waypoint.transform.location)\n            offset = font_surface.get_rect(center=(pixel_pos[0], pixel_pos[1]))\n            surface.blit(font_surface, offset)\n\n            # Draw line in front of stop\n            forward_vector = carla.Location(waypoint.transform.get_forward_vector())\n            left_vector = carla.Location(-forward_vector.y, forward_vector.x,\n                                         forward_vector.z) * waypoint.lane_width / 2 * 0.7\n\n            line = [(waypoint.transform.location + (forward_vector * 1.5) + (left_vector)),\n                    (waypoint.transform.location + (forward_vector * 1.5) - (left_vector))]\n\n            line_pixel = [world_to_pixel(p) for p in line]\n            pygame.draw.lines(surface, color, True, line_pixel, 2)\n\n            # draw bounding box\n            if self.show_triggers:\n                corners = Util.get_bounding_box(actor)\n                corners = [world_to_pixel(p) for p in corners]\n                pygame.draw.lines(surface, trigger_color, True, corners, 2)\n\n        def lateral_shift(transform, shift):\n            transform.rotation.yaw += 90\n            return transform.location + shift * transform.get_forward_vector()\n\n        def draw_topology(carla_topology, index):\n            topology = [x[index] for x in carla_topology]\n            topology = sorted(topology, key=lambda w: w.transform.location.z)\n            for waypoint in topology:\n                # if waypoint.road_id == 150 or waypoint.road_id == 16:\n                waypoints = [waypoint]\n\n                nxt = waypoint.next(precision)\n                if len(nxt) > 0:\n                    nxt = nxt[0]\n                    while nxt.road_id == waypoint.road_id:\n                        waypoints.append(nxt)\n                        nxt = nxt.next(precision)\n                        if len(nxt) > 0:\n                            nxt = nxt[0]\n                        else:\n                            break\n\n                # Draw Road\n                road_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in waypoints]\n                road_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in waypoints]\n\n                polygon = road_left_side + [x for x in reversed(road_right_side)]\n                polygon = [world_to_pixel(x) for x in polygon]\n\n                if len(polygon) > 2:\n                    pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon, 5)\n                    pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon)\n\n                # Draw Shoulders and Parkings\n                PARKING_COLOR = COLOR_ALUMINIUM_4_5\n                SHOULDER_COLOR = COLOR_ALUMINIUM_5\n\n                final_color = SHOULDER_COLOR\n\n                # Draw Right\n                shoulder = []\n                for w in waypoints:\n                    r = w.get_right_lane()\n                    if r is not None and (\n                            r.lane_type == carla.LaneType.Shoulder or r.lane_type == carla.LaneType.Parking):\n                        if r.lane_type == carla.LaneType.Parking:\n                            final_color = PARKING_COLOR\n                        shoulder.append(r)\n\n                shoulder_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in shoulder]\n                shoulder_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in shoulder]\n\n                polygon = shoulder_left_side + [x for x in reversed(shoulder_right_side)]\n                polygon = [world_to_pixel(x) for x in polygon]\n\n                if len(polygon) > 2:\n                    pygame.draw.polygon(map_surface, final_color, polygon, 5)\n                    pygame.draw.polygon(map_surface, final_color, polygon)\n\n                draw_lane_marking(\n                    map_surface,\n                    shoulder,\n                    False)\n\n                # Draw Left\n                shoulder = []\n                for w in waypoints:\n                    r = w.get_left_lane()\n                    if r is not None and (\n                            r.lane_type == carla.LaneType.Shoulder or r.lane_type == carla.LaneType.Parking):\n                        if r.lane_type == carla.LaneType.Parking:\n                            final_color = PARKING_COLOR\n                        shoulder.append(r)\n\n                shoulder_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in shoulder]\n                shoulder_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in shoulder]\n\n                polygon = shoulder_left_side + [x for x in reversed(shoulder_right_side)]\n                polygon = [world_to_pixel(x) for x in polygon]\n\n                if len(polygon) > 2:\n                    pygame.draw.polygon(map_surface, final_color, polygon, 5)\n                    pygame.draw.polygon(map_surface, final_color, polygon)\n\n                draw_lane_marking(\n                    map_surface,\n                    shoulder,\n                    True)\n\n                # Draw Lane Markings and Arrows\n                if not waypoint.is_intersection:\n                    draw_lane_marking(\n                        map_surface,\n                        waypoints,\n                        True)\n                    draw_lane_marking(\n                        map_surface,\n                        waypoints,\n                        False)\n                    for n, wp in enumerate(waypoints):\n                        if ((n + 1) % 400) == 0:\n                            draw_arrow(map_surface, wp.transform)\n\n        topology = carla_map.get_topology()\n        draw_topology(topology, 0)\n        draw_topology(topology, 1)\n\n        if self.show_spawn_points:\n            for sp in carla_map.get_spawn_points():\n                draw_arrow(map_surface, sp, color=COLOR_CHOCOLATE_0)\n\n        if self.show_connections:\n            dist = 1.5\n            to_pixel = lambda wp: world_to_pixel(wp.transform.location)\n            for wp in carla_map.generate_waypoints(dist):\n                col = (0, 255, 255) if wp.is_intersection else (0, 255, 0)\n                for nxt in wp.next(dist):\n                    pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(nxt), 2)\n                if wp.lane_change & carla.LaneChange.Right:\n                    r = wp.get_right_lane()\n                    if r and r.lane_type == carla.LaneType.Driving:\n                        pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(r), 2)\n                if wp.lane_change & carla.LaneChange.Left:\n                    l = wp.get_left_lane()\n                    if l and l.lane_type == carla.LaneType.Driving:\n                        pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(l), 2)\n\n        actors = carla_world.get_actors()\n\n        # Draw Traffic Signs\n        font_size = world_to_pixel_width(1)\n        font = pygame.font.SysFont('Arial', font_size, True)\n\n        stops = [actor for actor in actors if 'stop' in actor.type_id]\n        yields = [actor for actor in actors if 'yield' in actor.type_id]\n\n        stop_font_surface = font.render(\"STOP\", False, COLOR_ALUMINIUM_2)\n        stop_font_surface = pygame.transform.scale(\n            stop_font_surface, (stop_font_surface.get_width(), stop_font_surface.get_height() * 2))\n\n        yield_font_surface = font.render(\"YIELD\", False, COLOR_ALUMINIUM_2)\n        yield_font_surface = pygame.transform.scale(\n            yield_font_surface, (yield_font_surface.get_width(), yield_font_surface.get_height() * 2))\n\n        for ts_stop in stops:\n            draw_traffic_signs(map_surface, stop_font_surface, ts_stop, trigger_color=COLOR_SCARLET_RED_1)\n\n        for ts_yield in yields:\n            draw_traffic_signs(map_surface, yield_font_surface, ts_yield, trigger_color=COLOR_ORANGE_1)\n\n    def world_to_pixel(self, location, offset=(0, 0)):\n        x = self.scale * self._pixels_per_meter * (location.x - self._world_offset[0])\n        y = self.scale * self._pixels_per_meter * (location.y - self._world_offset[1])\n        return [int(x - offset[0]), int(y - offset[1])]\n\n    def world_to_pixel_width(self, width):\n        return int(self.scale * self._pixels_per_meter * width)\n\n    def scale_map(self, scale):\n        if scale != self.scale:\n            self.scale = scale\n            width = int(self.big_map_surface.get_width() * self.scale)\n            self.surface = pygame.transform.smoothscale(self.big_map_surface, (width, width))\n\n\nclass ModuleWorld(object):\n    def __init__(self, name, args, timeout):\n        self.client = None\n        self.name = name\n        self.args = args\n        self.timeout = timeout\n        self.server_fps = 0.0\n        self.simulation_time = 0\n        self.server_clock = pygame.time.Clock()\n\n        # World data\n        self.world = None\n        self.town_map = None\n        self.actors_with_transforms = []\n        # Store necessary modules\n        self.module_hud = None\n        self.module_input = None\n\n        self.surface_size = [0, 0]\n        self.prev_scaled_size = 0\n        self.scaled_size = 0\n        # Hero actor\n        self.hero_actor = None\n        self.spawned_hero = None\n        self.hero_transform = None\n\n        self.scale_offset = [0, 0]\n\n        self.vehicle_id_surface = None\n        self.result_surface = None\n\n        self.traffic_light_surfaces = TrafficLightSurfaces()\n        self.affected_traffic_light = None\n\n        # Map info\n        self.map_image = None\n        self.border_round_surface = None\n        self.original_surface_size = None\n        self.hero_surface = None\n        self.actors_surface = None\n\n    def _get_data_from_carla(self):\n        try:\n            self.client = carla.Client(self.args.host, self.args.port)\n            self.client.set_timeout(self.timeout)\n\n            if self.args.map is None:\n                world = self.client.get_world()\n            else:\n                world = self.client.load_world(self.args.map)\n\n            town_map = world.get_map()\n            return (world, town_map)\n\n        except RuntimeError as ex:\n            logging.error(ex)\n            exit_game()\n\n    def start(self):\n        self.world, self.town_map = self._get_data_from_carla()\n\n        # Create Surfaces\n        self.map_image = MapImage(\n            carla_world=self.world,\n            carla_map=self.town_map,\n            pixels_per_meter=PIXELS_PER_METER,\n            show_triggers=self.args.show_triggers,\n            show_connections=self.args.show_connections,\n            show_spawn_points=self.args.show_spawn_points)\n\n        # Store necessary modules\n        self.module_hud = module_manager.get_module(MODULE_HUD)\n        self.module_input = module_manager.get_module(MODULE_INPUT)\n\n        self.original_surface_size = min(self.module_hud.dim[0], self.module_hud.dim[1])\n        self.surface_size = self.map_image.big_map_surface.get_width()\n\n        self.scaled_size = int(self.surface_size)\n        self.prev_scaled_size = int(self.surface_size)\n\n        # Render Actors\n        self.actors_surface = pygame.Surface((self.map_image.surface.get_width(), self.map_image.surface.get_height()))\n        self.actors_surface.set_colorkey(COLOR_BLACK)\n\n        self.vehicle_id_surface = pygame.Surface((self.surface_size, self.surface_size)).convert()\n        self.vehicle_id_surface.set_colorkey(COLOR_BLACK)\n\n        self.border_round_surface = pygame.Surface(self.module_hud.dim, pygame.SRCALPHA).convert()\n        self.border_round_surface.set_colorkey(COLOR_WHITE)\n        self.border_round_surface.fill(COLOR_BLACK)\n\n        center_offset = (int(self.module_hud.dim[0] / 2), int(self.module_hud.dim[1] / 2))\n        pygame.draw.circle(self.border_round_surface, COLOR_ALUMINIUM_1, center_offset, int(self.module_hud.dim[1] / 2))\n        pygame.draw.circle(self.border_round_surface, COLOR_WHITE, center_offset, int((self.module_hud.dim[1] - 8) / 2))\n\n        scaled_original_size = self.original_surface_size * (1.0 / 0.9)\n        self.hero_surface = pygame.Surface((scaled_original_size, scaled_original_size)).convert()\n\n        self.result_surface = pygame.Surface((self.surface_size, self.surface_size)).convert()\n        self.result_surface.set_colorkey(COLOR_BLACK)\n\n        # Start hero mode by default\n        self.select_hero_actor()\n        self.hero_actor.set_autopilot(False)\n        self.module_input.wheel_offset = HERO_DEFAULT_SCALE\n        self.module_input.control = carla.VehicleControl()\n\n        weak_self = weakref.ref(self)\n        self.world.on_tick(lambda timestamp: ModuleWorld.on_world_tick(weak_self, timestamp))\n\n    def select_hero_actor(self):\n        hero_vehicles = [actor for actor in self.world.get_actors(\n        ) if 'vehicle' in actor.type_id and actor.attributes['role_name'] == 'hero']\n        if len(hero_vehicles) > 0:\n            self.hero_actor = random.choice(hero_vehicles)\n            self.hero_transform = self.hero_actor.get_transform()\n        else:\n            self._spawn_hero()\n\n    def _spawn_hero(self):\n        # Get a random blueprint.\n        blueprint = random.choice(self.world.get_blueprint_library().filter(self.args.filter))\n        blueprint.set_attribute('role_name', 'hero')\n        if blueprint.has_attribute('color'):\n            color = random.choice(blueprint.get_attribute('color').recommended_values)\n            blueprint.set_attribute('color', color)\n        # Spawn the player.\n        while self.hero_actor is None:\n            spawn_points = self.world.get_map().get_spawn_points()\n            spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()\n            self.hero_actor = self.world.try_spawn_actor(blueprint, spawn_point)\n        self.hero_transform = self.hero_actor.get_transform()\n\n        # Save it in order to destroy it when closing program\n        self.spawned_hero = self.hero_actor\n\n    def tick(self, clock):\n        actors = self.world.get_actors()\n        self.actors_with_transforms = [(actor, actor.get_transform()) for actor in actors]\n        if self.hero_actor is not None:\n            self.hero_transform = self.hero_actor.get_transform()\n        self.update_hud_info(clock)\n\n    def update_hud_info(self, clock):\n        hero_mode_text = []\n        if self.hero_actor is not None:\n            hero_speed = self.hero_actor.get_velocity()\n            hero_speed_text = 3.6 * math.sqrt(hero_speed.x ** 2 + hero_speed.y ** 2 + hero_speed.z ** 2)\n\n            affected_traffic_light_text = 'None'\n            if self.affected_traffic_light is not None:\n                state = self.affected_traffic_light.state\n                if state == carla.TrafficLightState.Green:\n                    affected_traffic_light_text = 'GREEN'\n                elif state == carla.TrafficLightState.Yellow:\n                    affected_traffic_light_text = 'YELLOW'\n                else:\n                    affected_traffic_light_text = 'RED'\n\n            affected_speed_limit_text = self.hero_actor.get_speed_limit()\n\n            hero_mode_text = [\n                'Hero Mode:                 ON',\n                'Hero ID:              %7d' % self.hero_actor.id,\n                'Hero Vehicle:  %14s' % get_actor_display_name(self.hero_actor, truncate=14),\n                'Hero Speed:          %3d km/h' % hero_speed_text,\n                'Hero Affected by:',\n                '  Traffic Light: %12s' % affected_traffic_light_text,\n                '  Speed Limit:       %3d km/h' % affected_speed_limit_text\n            ]\n        else:\n            hero_mode_text = ['Hero Mode:                OFF']\n\n        self.server_fps = self.server_clock.get_fps()\n        self.server_fps = 'inf' if self.server_fps == float('inf') else round(self.server_fps)\n        module_info_text = [\n            'Server:  % 16s FPS' % self.server_fps,\n            'Client:  % 16s FPS' % round(clock.get_fps()),\n            'Simulation Time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),\n            'Map Name:          %10s' % self.town_map.name.split('/')[-1],\n        ]\n\n        module_info_text = module_info_text\n        module_hud = module_manager.get_module(MODULE_HUD)\n        module_hud.add_info(self.name, module_info_text)\n        module_hud.add_info('HERO', hero_mode_text)\n\n    @staticmethod\n    def on_world_tick(weak_self, timestamp):\n        self = weak_self()\n        if not self:\n            return\n\n        self.server_clock.tick()\n        self.server_fps = self.server_clock.get_fps()\n        self.simulation_time = timestamp.elapsed_seconds\n\n    def _split_actors(self):\n        vehicles = []\n        traffic_lights = []\n        speed_limits = []\n        walkers = []\n\n        for actor_with_transform in self.actors_with_transforms:\n            actor = actor_with_transform[0]\n            if 'vehicle' in actor.type_id:\n                vehicles.append(actor_with_transform)\n            elif 'traffic_light' in actor.type_id:\n                traffic_lights.append(actor_with_transform)\n            elif 'speed_limit' in actor.type_id:\n                speed_limits.append(actor_with_transform)\n            elif 'walker' in actor.type_id:\n                walkers.append(actor_with_transform)\n\n        info_text = []\n        if self.hero_actor is not None and len(vehicles) > 1:\n            location = self.hero_transform.location\n            vehicle_list = [x[0] for x in vehicles if x[0].id != self.hero_actor.id]\n\n            def distance(v): return location.distance(v.get_location())\n            for n, vehicle in enumerate(sorted(vehicle_list, key=distance)):\n                if n > 15:\n                    break\n                vehicle_type = get_actor_display_name(vehicle, truncate=22)\n                info_text.append('% 5d %s' % (vehicle.id, vehicle_type))\n        module_manager.get_module(MODULE_HUD).add_info(\n            'NEARBY VEHICLES',\n            info_text)\n\n        return (vehicles, traffic_lights, speed_limits, walkers)\n\n    def _render_traffic_lights(self, surface, list_tl, world_to_pixel):\n        self.affected_traffic_light = None\n\n        for tl in list_tl:\n            world_pos = tl.get_location()\n            pos = world_to_pixel(world_pos)\n\n            if self.args.show_triggers:\n                corners = Util.get_bounding_box(tl)\n                corners = [world_to_pixel(p) for p in corners]\n                pygame.draw.lines(surface, COLOR_BUTTER_1, True, corners, 2)\n\n            if self.hero_actor is not None:\n                corners = Util.get_bounding_box(tl)\n                corners = [world_to_pixel(p) for p in corners]\n                tl_t = tl.get_transform()\n\n                transformed_tv = tl_t.transform(tl.trigger_volume.location)\n                hero_location = self.hero_actor.get_location()\n                d = hero_location.distance(transformed_tv)\n                s = Util.length(tl.trigger_volume.extent) + Util.length(self.hero_actor.bounding_box.extent)\n                if (d <= s):\n                    # Highlight traffic light\n                    self.affected_traffic_light = tl\n                    srf = self.traffic_light_surfaces.surfaces['h']\n                    surface.blit(srf, srf.get_rect(center=pos))\n\n            srf = self.traffic_light_surfaces.surfaces[tl.state]\n            surface.blit(srf, srf.get_rect(center=pos))\n\n    def _render_speed_limits(self, surface, list_sl, world_to_pixel, world_to_pixel_width):\n\n        font_size = world_to_pixel_width(2)\n        radius = world_to_pixel_width(2)\n        font = pygame.font.SysFont('Arial', font_size)\n\n        for sl in list_sl:\n\n            x, y = world_to_pixel(sl.get_location())\n\n            # Render speed limit\n            white_circle_radius = int(radius * 0.75)\n\n            pygame.draw.circle(surface, COLOR_SCARLET_RED_1, (x, y), radius)\n            pygame.draw.circle(surface, COLOR_ALUMINIUM_0, (x, y), white_circle_radius)\n\n            limit = sl.type_id.split('.')[2]\n            font_surface = font.render(limit, True, COLOR_ALUMINIUM_5)\n\n            if self.args.show_triggers:\n                corners = Util.get_bounding_box(sl)\n                corners = [world_to_pixel(p) for p in corners]\n                pygame.draw.lines(surface, COLOR_PLUM_2, True, corners, 2)\n\n            # Blit\n            if self.hero_actor is not None:\n                # Rotate font surface with respect to hero vehicle front\n                angle = -self.hero_transform.rotation.yaw - 90.0\n                font_surface = pygame.transform.rotate(font_surface, angle)\n                offset = font_surface.get_rect(center=(x, y))\n                surface.blit(font_surface, offset)\n\n            else:\n                surface.blit(font_surface, (x - radius / 2, y - radius / 2))\n\n    def _render_walkers(self, surface, list_w, world_to_pixel):\n        for w in list_w:\n            color = COLOR_PLUM_0\n\n            # Compute bounding box points\n            bb = w[0].bounding_box.extent\n            corners = [\n                carla.Location(x=-bb.x, y=-bb.y),\n                carla.Location(x=bb.x, y=-bb.y),\n                carla.Location(x=bb.x, y=bb.y),\n                carla.Location(x=-bb.x, y=bb.y)]\n\n            w[1].transform(corners)\n            corners = [world_to_pixel(p) for p in corners]\n            pygame.draw.polygon(surface, color, corners)\n\n    def _render_vehicles(self, surface, list_v, world_to_pixel):\n\n        for v in list_v:\n            color = COLOR_SKY_BLUE_0\n            if int(v[0].attributes['number_of_wheels']) == 2:\n                color = COLOR_CHOCOLATE_1\n            if v[0].attributes['role_name'] == 'hero':\n                color = COLOR_CHAMELEON_0\n            # Compute bounding box points\n            bb = v[0].bounding_box.extent\n            corners = [carla.Location(x=-bb.x, y=-bb.y),\n                       carla.Location(x=bb.x - 0.8, y=-bb.y),\n                       carla.Location(x=bb.x, y=0),\n                       carla.Location(x=bb.x - 0.8, y=bb.y),\n                       carla.Location(x=-bb.x, y=bb.y),\n                       carla.Location(x=-bb.x, y=-bb.y)\n                       ]\n            v[1].transform(corners)\n            corners = [world_to_pixel(p) for p in corners]\n            pygame.draw.lines(surface, color, False, corners, int(math.ceil(4.0 * self.map_image.scale)))\n\n    def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers):\n        # Static actors\n        self._render_traffic_lights(surface, [tl[0] for tl in traffic_lights], self.map_image.world_to_pixel)\n        self._render_speed_limits(surface, [sl[0] for sl in speed_limits], self.map_image.world_to_pixel,\n                                  self.map_image.world_to_pixel_width)\n\n        # Dynamic actors\n        self._render_vehicles(surface, vehicles, self.map_image.world_to_pixel)\n        self._render_walkers(surface, walkers, self.map_image.world_to_pixel)\n\n    def clip_surfaces(self, clipping_rect):\n        self.actors_surface.set_clip(clipping_rect)\n        self.vehicle_id_surface.set_clip(clipping_rect)\n        self.result_surface.set_clip(clipping_rect)\n\n    def _compute_scale(self, scale_factor):\n        m = self.module_input.mouse_pos\n\n        # Percentage of surface where mouse position is actually\n        px = (m[0] - self.scale_offset[0]) / float(self.prev_scaled_size)\n        py = (m[1] - self.scale_offset[1]) / float(self.prev_scaled_size)\n\n        # Offset will be the previously accumulated offset added with the\n        # difference of mouse positions in the old and new scales\n        diff_between_scales = ((float(self.prev_scaled_size) * px) - (float(self.scaled_size) * px),\n                               (float(self.prev_scaled_size) * py) - (float(self.scaled_size) * py))\n\n        self.scale_offset = (self.scale_offset[0] + diff_between_scales[0],\n                             self.scale_offset[1] + diff_between_scales[1])\n\n        # Update previous scale\n        self.prev_scaled_size = self.scaled_size\n\n        # Scale performed\n        self.map_image.scale_map(scale_factor)\n\n    def render(self, display):\n        if self.actors_with_transforms is None:\n            return\n        self.result_surface.fill(COLOR_BLACK)\n        vehicles, traffic_lights, speed_limits, walkers = self._split_actors()\n\n        scale_factor = self.module_input.wheel_offset\n        self.scaled_size = int(self.map_image.width * scale_factor)\n        if self.scaled_size != self.prev_scaled_size:\n            self._compute_scale(scale_factor)\n\n        # Render Actors\n\n        self.actors_surface.fill(COLOR_BLACK)\n        self.render_actors(\n            self.actors_surface,\n            vehicles,\n            traffic_lights,\n            speed_limits,\n            walkers)\n\n        # Render Ids\n        self.module_hud.render_vehicles_ids(self.vehicle_id_surface, vehicles,\n                                            self.map_image.world_to_pixel, self.hero_actor, self.hero_transform)\n\n        # Blit surfaces\n        surfaces = ((self.map_image.surface, (0, 0)),\n                    (self.actors_surface, (0, 0)),\n                    (self.vehicle_id_surface, (0, 0)),\n                    )\n\n        angle = 0.0 if self.hero_actor is None else self.hero_transform.rotation.yaw + 90.0\n        self.traffic_light_surfaces.rotozoom(-angle, self.map_image.scale)\n\n        center_offset = (0, 0)\n        if self.hero_actor is not None:\n\n            hero_location_screen = self.map_image.world_to_pixel(self.hero_transform.location)\n            hero_front = self.hero_transform.get_forward_vector()\n            translation_offset = (\n                hero_location_screen[0] -\n                self.hero_surface.get_width() /\n                2 +\n                hero_front.x *\n                PIXELS_AHEAD_VEHICLE,\n                (hero_location_screen[1] -\n                 self.hero_surface.get_height() /\n                 2 +\n                 hero_front.y *\n                 PIXELS_AHEAD_VEHICLE))\n\n            # Apply clipping rect\n            clipping_rect = pygame.Rect(translation_offset[0],\n                                        translation_offset[1],\n                                        self.hero_surface.get_width(),\n                                        self.hero_surface.get_height())\n            self.clip_surfaces(clipping_rect)\n\n            Util.blits(self.result_surface, surfaces)\n\n            self.border_round_surface.set_clip(clipping_rect)\n\n            self.hero_surface.fill(COLOR_ALUMINIUM_4)\n            self.hero_surface.blit(self.result_surface, (-translation_offset[0],\n                                                         -translation_offset[1]))\n\n            rotated_result_surface = pygame.transform.rotozoom(self.hero_surface, angle, 0.9).convert()\n\n            center = (display.get_width() / 2, display.get_height() / 2)\n            rotation_pivot = rotated_result_surface.get_rect(center=center)\n            display.blit(rotated_result_surface, rotation_pivot)\n\n            display.blit(self.border_round_surface, (0, 0))\n        else:\n            # Translation offset\n            translation_offset = (self.module_input.mouse_offset[0] * scale_factor + self.scale_offset[0],\n                                  self.module_input.mouse_offset[1] * scale_factor + self.scale_offset[1])\n            center_offset = (abs(display.get_width() - self.surface_size) / 2 * scale_factor, 0)\n\n            # Apply clipping rect\n            clipping_rect = pygame.Rect(-translation_offset[0] - center_offset[0], -translation_offset[1],\n                                        self.module_hud.dim[0], self.module_hud.dim[1])\n            self.clip_surfaces(clipping_rect)\n            Util.blits(self.result_surface, surfaces)\n\n            display.blit(self.result_surface, (translation_offset[0] + center_offset[0],\n                                               translation_offset[1]))\n\n    def destroy(self):\n        if self.spawned_hero is not None:\n            self.spawned_hero.destroy()\n# ==============================================================================\n# -- Input -----------------------------------------------------------\n# ==============================================================================\n\n\nclass ModuleInput(object):\n    def __init__(self, name):\n        self.name = name\n        self.mouse_pos = (0, 0)\n        self.mouse_offset = [0.0, 0.0]\n        self.wheel_offset = 0.1\n        self.wheel_amount = 0.025\n        self._steer_cache = 0.0\n        self.control = None\n        self._autopilot_enabled = False\n\n    def start(self):\n        hud = module_manager.get_module(MODULE_HUD)\n        hud.notification(\"Press 'H' or '?' for help.\", seconds=4.0)\n\n    def render(self, display):\n        pass\n\n    def tick(self, clock):\n        self.parse_input(clock)\n\n    def _parse_events(self):\n        self.mouse_pos = pygame.mouse.get_pos()\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                exit_game()\n            elif event.type == pygame.KEYUP:\n                if self._is_quit_shortcut(event.key):\n                    exit_game()\n                elif event.key == K_h or (event.key == K_SLASH and pygame.key.get_mods() & KMOD_SHIFT):\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    module_hud.help.toggle()\n                elif event.key == K_TAB:\n                    module_world = module_manager.get_module(MODULE_WORLD)\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    if module_world.hero_actor is None:\n                        module_world.select_hero_actor()\n                        self.wheel_offset = HERO_DEFAULT_SCALE\n                        self.control = carla.VehicleControl()\n                        module_hud.notification('Hero Mode')\n                    else:\n                        self.wheel_offset = MAP_DEFAULT_SCALE\n                        self.mouse_offset = [0, 0]\n                        self.mouse_pos = [0, 0]\n                        module_world.scale_offset = [0, 0]\n                        module_world.hero_actor = None\n                        module_hud.notification('Map Mode')\n                elif event.key == K_F1:\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    module_hud.show_info = not module_hud.show_info\n                elif event.key == K_i:\n                    module_hud = module_manager.get_module(MODULE_HUD)\n                    module_hud.show_actor_ids = not module_hud.show_actor_ids\n                elif isinstance(self.control, carla.VehicleControl):\n                    if event.key == K_q:\n                        self.control.gear = 1 if self.control.reverse else -1\n                    elif event.key == K_m:\n                        self.control.manual_gear_shift = not self.control.manual_gear_shift\n                        world = module_manager.get_module(MODULE_WORLD)\n                        self.control.gear = world.hero_actor.get_control().gear\n                        module_hud = module_manager.get_module(MODULE_HUD)\n                        module_hud.notification('%s Transmission' % (\n                            'Manual' if self.control.manual_gear_shift else 'Automatic'))\n                    elif self.control.manual_gear_shift and event.key == K_COMMA:\n                        self.control.gear = max(-1, self.control.gear - 1)\n                    elif self.control.manual_gear_shift and event.key == K_PERIOD:\n                        self.control.gear = self.control.gear + 1\n                    elif event.key == K_p:\n                        world = module_manager.get_module(MODULE_WORLD)\n                        if world.hero_actor is not None:\n                            self._autopilot_enabled = not self._autopilot_enabled\n                            world.hero_actor.set_autopilot(self._autopilot_enabled)\n                            module_hud = module_manager.get_module(MODULE_HUD)\n                            module_hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))\n            elif event.type == pygame.MOUSEBUTTONDOWN:\n                if event.button == 4:\n                    self.wheel_offset += self.wheel_amount\n                    if self.wheel_offset >= 1.0:\n                        self.wheel_offset = 1.0\n                elif event.button == 5:\n                    self.wheel_offset -= self.wheel_amount\n                    if self.wheel_offset <= 0.1:\n                        self.wheel_offset = 0.1\n\n    def _parse_keys(self, milliseconds):\n        keys = pygame.key.get_pressed()\n        self.control.throttle = 1.0 if keys[K_UP] or keys[K_w] else 0.0\n        steer_increment = 5e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n        self._steer_cache = min(0.7, max(-0.7, self._steer_cache))\n        self.control.steer = round(self._steer_cache, 1)\n        self.control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0\n        self.control.hand_brake = keys[K_SPACE]\n\n    def _parse_mouse(self):\n        if pygame.mouse.get_pressed()[0]:\n            x, y = pygame.mouse.get_pos()\n            self.mouse_offset[0] += (1.0 / self.wheel_offset) * (x - self.mouse_pos[0])\n            self.mouse_offset[1] += (1.0 / self.wheel_offset) * (y - self.mouse_pos[1])\n            self.mouse_pos = (x, y)\n\n    def parse_input(self, clock):\n        self._parse_events()\n        self._parse_mouse()\n        if not self._autopilot_enabled:\n            if isinstance(self.control, carla.VehicleControl):\n                self._parse_keys(clock.get_time())\n                self.control.reverse = self.control.gear < 0\n            world = module_manager.get_module(MODULE_WORLD)\n            if (world.hero_actor is not None):\n                world.hero_actor.apply_control(self.control)\n\n    @staticmethod\n    def _is_quit_shortcut(key):\n        return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)\n\n\n# ==============================================================================\n# -- Global Objects ------------------------------------------------------------\n# ==============================================================================\nmodule_manager = ModuleManager()\n\n\n# ==============================================================================\n# -- Game Loop ---------------------------------------------------------------\n# ==============================================================================\n\n\ndef game_loop(args):\n    try:\n        # Init Pygame\n        pygame.init()\n        display = pygame.display.set_mode(\n            (args.width, args.height),\n            pygame.HWSURFACE | pygame.DOUBLEBUF)\n        pygame.display.set_caption(args.description)\n\n        font = pygame.font.Font(pygame.font.get_default_font(), 20)\n        text_surface = font.render('Rendering map...', True, COLOR_WHITE)\n        display.blit(text_surface, text_surface.get_rect(center=(args.width / 2, args.height / 2)))\n        pygame.display.flip()\n\n        # Init modules\n        input_module = ModuleInput(MODULE_INPUT)\n        hud_module = ModuleHUD(MODULE_HUD, args.width, args.height)\n        world_module = ModuleWorld(MODULE_WORLD, args, timeout=2.0)\n\n        # Register Modules\n        module_manager.register_module(world_module)\n        module_manager.register_module(hud_module)\n        module_manager.register_module(input_module)\n\n        module_manager.start_modules()\n\n        clock = pygame.time.Clock()\n        while True:\n            clock.tick_busy_loop(60)\n\n            module_manager.tick(clock)\n            module_manager.render(display)\n\n            pygame.display.flip()\n\n    except KeyboardInterrupt:\n        print('\\nCancelled by user. Bye!')\n\n    finally:\n        if world_module is not None:\n            world_module.destroy()\n\ndef exit_game():\n    module_manager.clear_modules()\n    pygame.quit()\n    sys.exit()\n\n# ==============================================================================\n# -- Main --------------------------------------------------------------------\n# ==============================================================================\n\n\ndef main():\n    # Parse arguments\n    argparser = argparse.ArgumentParser(\n        description='CARLA No Rendering Mode Visualizer')\n    argparser.add_argument(\n        '-v', '--verbose',\n        action='store_true',\n        dest='debug',\n        help='print debug information')\n    argparser.add_argument(\n        '--host',\n        metavar='H',\n        default='127.0.0.1',\n        help='IP of the host server (default: 127.0.0.1)')\n    argparser.add_argument(\n        '-p', '--port',\n        metavar='P',\n        default=2000,\n        type=int,\n        help='TCP port to listen to (default: 2000)')\n    argparser.add_argument(\n        '--res',\n        metavar='WIDTHxHEIGHT',\n        default='1280x720',\n        help='window resolution (default: 1280x720)')\n    argparser.add_argument(\n        '--filter',\n        metavar='PATTERN',\n        default='vehicle.*',\n        help='actor filter (default: \"vehicle.*\")')\n    argparser.add_argument(\n        '--map',\n        metavar='TOWN',\n        default=None,\n        help='start a new episode at the given TOWN')\n    argparser.add_argument(\n        '--no-rendering',\n        action='store_true',\n        default=True,\n        help='switch off server rendering')\n    argparser.add_argument(\n        '--show-triggers',\n        action='store_true',\n        help='show trigger boxes of traffic signs')\n    argparser.add_argument(\n        '--show-connections',\n        action='store_true',\n        help='show waypoint connections')\n    argparser.add_argument(\n        '--show-spawn-points',\n        action='store_true',\n        help='show recommended spawn points')\n\n    args = argparser.parse_args()\n    args.description = argparser.description\n    args.width, args.height = [int(x) for x in args.res.split('x')]\n\n    log_level = logging.DEBUG if args.debug else logging.INFO\n    logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)\n\n    logging.info('listening to server %s:%s', args.host, args.port)\n    print(__doc__)\n\n    game_loop(args)\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/requirements.txt",
    "content": "py-trees==0.8.3\nnumpy==1.18.4; python_version >= '3.0'\nnetworkx==2.2\nShapely==1.7.1\npsutil\nxmlschema==1.0.18\nephem\ntabulate\nopencv-python==4.2.0.32\nmatplotlib\nsix\nsimple-watchdog-timer\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/scenario_runner.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nWelcome to CARLA scenario_runner\n\nThis is the main script to be executed when running a scenario.\nIt loads the scenario configuration, loads the scenario and manager,\nand finally triggers the scenario execution.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport glob\nimport traceback\nimport argparse\nfrom argparse import RawTextHelpFormatter\nfrom datetime import datetime\ntry:\n    from packaging.version import Version\nexcept ImportError:\n    from distutils.version import LooseVersion as Version # Python 2 fallback\nimport importlib\nimport inspect\nimport os\nimport signal\nimport sys\nimport time\nimport json\n\ntry:\n    # requires Python 3.8+\n    from importlib.metadata import metadata\n    def get_carla_version():\n        return Version(metadata(\"carla\")[\"Version\"])\nexcept ModuleNotFoundError:\n    # backport checking for older Python versions; module is deprecated\n    import pkg_resources\n    def get_carla_version():\n        return Version(pkg_resources.get_distribution(\"carla\").version)\n\nimport carla\n\nfrom srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenario_manager import ScenarioManager\nfrom srunner.scenarios.open_scenario import OpenScenario\nfrom srunner.scenarios.route_scenario import RouteScenario\nfrom srunner.tools.scenario_parser import ScenarioConfigurationParser\nfrom srunner.tools.route_parser import RouteParser\n\n# Version of scenario_runner\nVERSION = '0.9.13'\n\n# Minimum version of CARLA that is required\nMIN_CARLA_VERSION = '0.9.12'\n\n\nclass ScenarioRunner(object):\n\n    \"\"\"\n    This is the core scenario runner module. It is responsible for\n    running (and repeating) a single scenario or a list of scenarios.\n\n    Usage:\n    scenario_runner = ScenarioRunner(args)\n    scenario_runner.run()\n    del scenario_runner\n    \"\"\"\n\n    ego_vehicles = []\n\n    # Tunable parameters\n    client_timeout = 30.0  # in seconds\n    wait_for_world = 30.0  # in seconds\n    frame_rate = 20.0      # in Hz\n\n    # CARLA world and scenario handlers\n    world = None\n    manager = None\n\n    finished = False\n\n    additional_scenario_module = None\n\n    agent_instance = None\n    module_agent = None\n\n    def __init__(self, args):\n        \"\"\"\n        Setup CARLA client and world\n        Setup ScenarioManager\n        \"\"\"\n        self._args = args\n\n        if args.timeout:\n            self.client_timeout = float(args.timeout)\n\n        # First of all, we need to create the client that will send the requests\n        # to the simulator. Here we'll assume the simulator is accepting\n        # requests in the localhost at port 2000.\n        self.client = carla.Client(args.host, int(args.port))\n        self.client.set_timeout(self.client_timeout)\n        carla_version = get_carla_version()\n        if carla_version < Version(MIN_CARLA_VERSION):\n            raise ImportError(\"CARLA version {} or newer required. CARLA version found: {}\".format(MIN_CARLA_VERSION, carla_version))\n\n        # Load agent if requested via command line args\n        # If something goes wrong an exception will be thrown by importlib (ok here)\n        if self._args.agent is not None:\n            module_name = os.path.basename(args.agent).split('.')[0]\n            sys.path.insert(0, os.path.dirname(args.agent))\n            self.module_agent = importlib.import_module(module_name)\n\n        # Create the ScenarioManager\n        self.manager = ScenarioManager(self._args.debug, self._args.sync, self._args.timeout)\n\n        # Create signal handler for SIGINT\n        self._shutdown_requested = False\n        if sys.platform != 'win32':\n            signal.signal(signal.SIGHUP, self._signal_handler)\n        signal.signal(signal.SIGINT, self._signal_handler)\n        signal.signal(signal.SIGTERM, self._signal_handler)\n\n        self._start_wall_time = datetime.now()\n\n    def destroy(self):\n        \"\"\"\n        Cleanup and delete actors, ScenarioManager and CARLA world\n        \"\"\"\n\n        self._cleanup()\n        if self.manager is not None:\n            del self.manager\n        if self.world is not None:\n            del self.world\n        if self.client is not None:\n            del self.client\n\n    def _signal_handler(self, signum, frame):\n        \"\"\"\n        Terminate scenario ticking when receiving a signal interrupt\n        \"\"\"\n        self._shutdown_requested = True\n        if self.manager:\n            self.manager.stop_scenario()\n\n    def _get_scenario_class_or_fail(self, scenario):\n        \"\"\"\n        Get scenario class by scenario name\n        If scenario is not supported or not found, exit script\n        \"\"\"\n\n        # Path of all scenario at \"srunner/scenarios\" folder + the path of the additional scenario argument\n        scenarios_list = glob.glob(\"{}/srunner/scenarios/*.py\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        scenarios_list.append(self._args.additionalScenario)\n\n        for scenario_file in scenarios_list:\n\n            # Get their module\n            module_name = os.path.basename(scenario_file).split('.')[0]\n            sys.path.insert(0, os.path.dirname(scenario_file))\n            scenario_module = importlib.import_module(module_name)\n\n            # And their members of type class\n            for member in inspect.getmembers(scenario_module, inspect.isclass):\n                if scenario in member:\n                    return member[1]\n\n            # Remove unused Python paths\n            sys.path.pop(0)\n\n        print(\"Scenario '{}' not supported ... Exiting\".format(scenario))\n        sys.exit(-1)\n\n    def _cleanup(self):\n        \"\"\"\n        Remove and destroy all actors\n        \"\"\"\n        if self.finished:\n            return\n\n        self.finished = True\n\n        # Simulation still running and in synchronous mode?\n        if self.world is not None and self._args.sync:\n            try:\n                # Reset to asynchronous mode\n                settings = self.world.get_settings()\n                settings.synchronous_mode = False\n                settings.fixed_delta_seconds = None\n                self.world.apply_settings(settings)\n                self.client.get_trafficmanager(int(self._args.trafficManagerPort)).set_synchronous_mode(False)\n            except RuntimeError:\n                sys.exit(-1)\n\n        self.manager.cleanup()\n\n        CarlaDataProvider.cleanup()\n\n        for i, _ in enumerate(self.ego_vehicles):\n            if self.ego_vehicles[i]:\n                if not self._args.waitForEgo and self.ego_vehicles[i] is not None and self.ego_vehicles[i].is_alive:\n                    print(\"Destroying ego vehicle {}\".format(self.ego_vehicles[i].id))\n                    self.ego_vehicles[i].destroy()\n                self.ego_vehicles[i] = None\n        self.ego_vehicles = []\n\n        if self.agent_instance:\n            self.agent_instance.destroy()\n            self.agent_instance = None\n\n    def _prepare_ego_vehicles(self, ego_vehicles):\n        \"\"\"\n        Spawn or update the ego vehicles\n        \"\"\"\n\n        if not self._args.waitForEgo:\n            for vehicle in ego_vehicles:\n                self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model,\n                                                                             vehicle.transform,\n                                                                             vehicle.rolename,\n                                                                             color=vehicle.color,\n                                                                             actor_category=vehicle.category))\n        else:\n            ego_vehicle_missing = True\n            while ego_vehicle_missing:\n                self.ego_vehicles = []\n                ego_vehicle_missing = False\n                for ego_vehicle in ego_vehicles:\n                    ego_vehicle_found = False\n                    carla_vehicles = CarlaDataProvider.get_world().get_actors().filter('vehicle.*')\n                    for carla_vehicle in carla_vehicles:\n                        if carla_vehicle.attributes['role_name'] == ego_vehicle.rolename:\n                            ego_vehicle_found = True\n                            self.ego_vehicles.append(carla_vehicle)\n                            break\n                    if not ego_vehicle_found:\n                        ego_vehicle_missing = True\n                        break\n\n            for i, _ in enumerate(self.ego_vehicles):\n                self.ego_vehicles[i].set_transform(ego_vehicles[i].transform)\n                self.ego_vehicles[i].set_target_velocity(carla.Vector3D())\n                self.ego_vehicles[i].set_target_angular_velocity(carla.Vector3D())\n                self.ego_vehicles[i].apply_control(carla.VehicleControl())\n                CarlaDataProvider.register_actor(self.ego_vehicles[i], ego_vehicles[i].transform)\n\n        # sync state\n        if CarlaDataProvider.is_sync_mode():\n            self.world.tick()\n        else:\n            self.world.wait_for_tick()\n\n    def _analyze_scenario(self, config):\n        \"\"\"\n        Provide feedback about success/failure of a scenario\n        \"\"\"\n\n        # Create the filename\n        current_time = str(datetime.now().strftime('%Y-%m-%d-%H-%M-%S'))\n        junit_filename = None\n        json_filename = None\n        config_name = config.name\n        if self._args.outputDir != '':\n            config_name = os.path.join(self._args.outputDir, config_name)\n\n        if self._args.junit:\n            junit_filename = config_name + current_time + \".xml\"\n        if self._args.json:\n            json_filename = config_name + current_time + \".json\"\n        filename = None\n        if self._args.file:\n            filename = config_name + current_time + \".txt\"\n\n        if not self.manager.analyze_scenario(self._args.output, filename, junit_filename, json_filename):\n            print(\"All scenario tests were passed successfully!\")\n        else:\n            print(\"Not all scenario tests were successful\")\n            if not (self._args.output or filename or junit_filename):\n                print(\"Please run with --output for further information\")\n\n    def _record_criteria(self, criteria, name):\n        \"\"\"\n        Filter the JSON serializable attributes of the criterias and\n        dumps them into a file. This will be used by the metrics manager,\n        in case the user wants specific information about the criterias.\n        \"\"\"\n        file_name = name[:-4] + \".json\"\n\n        # Filter the attributes that aren't JSON serializable\n        with open('temp.json', 'w', encoding='utf-8') as fp:\n\n            criteria_dict = {}\n            for criterion in criteria:\n\n                criterion_dict = criterion.__dict__\n                criteria_dict[criterion.name] = {}\n\n                for key in criterion_dict:\n                    if key != \"name\":\n                        try:\n                            key_dict = {key: criterion_dict[key]}\n                            json.dump(key_dict, fp, sort_keys=False, indent=4)\n                            criteria_dict[criterion.name].update(key_dict)\n                        except TypeError:\n                            pass\n\n        os.remove('temp.json')\n\n        # Save the criteria dictionary into a .json file\n        with open(file_name, 'w', encoding='utf-8') as fp:\n            json.dump(criteria_dict, fp, sort_keys=False, indent=4)\n\n    def _load_and_wait_for_world(self, town, ego_vehicles=None):\n        \"\"\"\n        Load a new CARLA world and provide data to CarlaDataProvider\n        \"\"\"\n\n        if self._args.reloadWorld:\n            self.world = self.client.load_world(town)\n        else:\n            # if the world should not be reloaded, wait at least until all ego vehicles are ready\n            ego_vehicle_found = False\n            if self._args.waitForEgo:\n                while not ego_vehicle_found and not self._shutdown_requested:\n                    vehicles = self.client.get_world().get_actors().filter('vehicle.*')\n                    for ego_vehicle in ego_vehicles:\n                        ego_vehicle_found = False\n                        for vehicle in vehicles:\n                            if vehicle.attributes['role_name'] == ego_vehicle.rolename:\n                                ego_vehicle_found = True\n                                break\n                        if not ego_vehicle_found:\n                            print(\"Not all ego vehicles ready. Waiting ... \")\n                            time.sleep(1)\n                            break\n\n        self.world = self.client.get_world()\n\n        if self._args.sync:\n            settings = self.world.get_settings()\n            settings.synchronous_mode = True\n            settings.fixed_delta_seconds = 1.0 / self.frame_rate\n            self.world.apply_settings(settings)\n\n        CarlaDataProvider.set_client(self.client)\n        CarlaDataProvider.set_world(self.world)\n\n        # Wait for the world to be ready\n        if CarlaDataProvider.is_sync_mode():\n            self.world.tick()\n        else:\n            self.world.wait_for_tick()\n\n        map_name = CarlaDataProvider.get_map().name.split('/')[-1]\n        if map_name not in (town, \"OpenDriveMap\"):\n            print(\"The CARLA server uses the wrong map: {}\".format(map_name))\n            print(\"This scenario requires to use map: {}\".format(town))\n            return False\n\n        return True\n\n    def _load_and_run_scenario(self, config):\n        \"\"\"\n        Load and run the scenario given by config\n        \"\"\"\n        result = False\n        if not self._load_and_wait_for_world(config.town, config.ego_vehicles):\n            self._cleanup()\n            return False\n\n        if self._args.agent:\n            agent_class_name = self.module_agent.__name__.title().replace('_', '')\n            try:\n                self.agent_instance = getattr(self.module_agent, agent_class_name)(self._args.agentConfig)\n                config.agent = self.agent_instance\n            except Exception as e:          # pylint: disable=broad-except\n                traceback.print_exc()\n                print(\"Could not setup required agent due to {}\".format(e))\n                self._cleanup()\n                return False\n\n        CarlaDataProvider.set_traffic_manager_port(int(self._args.trafficManagerPort))\n        tm = self.client.get_trafficmanager(int(self._args.trafficManagerPort))\n        tm.set_random_device_seed(int(self._args.trafficManagerSeed))\n        if self._args.sync:\n            tm.set_synchronous_mode(True)\n\n        # Prepare scenario\n        print(\"Preparing scenario: \" + config.name)\n        try:\n            self._prepare_ego_vehicles(config.ego_vehicles)\n            if self._args.openscenario:\n                scenario = OpenScenario(world=self.world,\n                                        ego_vehicles=self.ego_vehicles,\n                                        config=config,\n                                        config_file=self._args.openscenario,\n                                        timeout=100000)\n            elif self._args.route:\n                scenario = RouteScenario(world=self.world,\n                                         config=config,\n                                         debug_mode=self._args.debug)\n            else:\n                scenario_class = self._get_scenario_class_or_fail(config.type)\n                scenario = scenario_class(world=self.world,\n                                          ego_vehicles=self.ego_vehicles,\n                                          config=config,\n                                          randomize=self._args.randomize,\n                                          debug_mode=self._args.debug)\n        except Exception as exception:                  # pylint: disable=broad-except\n            print(\"The scenario cannot be loaded\")\n            traceback.print_exc()\n            print(exception)\n            self._cleanup()\n            return False\n\n        try:\n            if self._args.record:\n                recorder_name = \"{}/{}/{}.log\".format(\n                    os.getenv('SCENARIO_RUNNER_ROOT', \"./\"), self._args.record, config.name)\n                self.client.start_recorder(recorder_name, True)\n\n            # Load scenario and run it\n            self.manager.load_scenario(scenario, self.agent_instance)\n            self.manager.run_scenario()\n\n            # Provide outputs if required\n            self._analyze_scenario(config)\n\n            # Remove all actors, stop the recorder and save all criterias (if needed)\n            scenario.remove_all_actors()\n            if self._args.record:\n                self.client.stop_recorder()\n                self._record_criteria(self.manager.scenario.get_criteria(), recorder_name)\n\n            result = True\n\n        except Exception as e:              # pylint: disable=broad-except\n            traceback.print_exc()\n            print(e)\n            result = False\n\n        self._cleanup()\n        return result\n\n    def _run_scenarios(self):\n        \"\"\"\n        Run conventional scenarios (e.g. implemented using the Python API of ScenarioRunner)\n        \"\"\"\n        result = False\n\n        # Load the scenario configurations provided in the config file\n        scenario_configurations = ScenarioConfigurationParser.parse_scenario_configuration(\n            self._args.scenario,\n            self._args.configFile)\n        if not scenario_configurations:\n            print(\"Configuration for scenario {} cannot be found!\".format(self._args.scenario))\n            return result\n\n        # Execute each configuration\n        for config in scenario_configurations:\n            for _ in range(self._args.repetitions):\n                self.finished = False\n                result = self._load_and_run_scenario(config)\n\n            self._cleanup()\n        return result\n\n    def _run_route(self):\n        \"\"\"\n        Run the route scenario\n        \"\"\"\n        result = False\n\n        # retrieve routes\n        route_configurations = RouteParser.parse_routes_file(self._args.route, self._args.route_id)\n\n        for config in route_configurations:\n            for _ in range(self._args.repetitions):\n                result = self._load_and_run_scenario(config)\n\n                self._cleanup()\n        return result\n\n    def _run_openscenario(self):\n        \"\"\"\n        Run a scenario based on OpenSCENARIO\n        \"\"\"\n\n        # Load the scenario configurations provided in the config file\n        if not os.path.isfile(self._args.openscenario):\n            print(\"File does not exist\")\n            self._cleanup()\n            return False\n\n        openscenario_params = {}\n        if self._args.openscenarioparams is not None:\n            for entry in self._args.openscenarioparams.split(','):\n                [key, val] = [m.strip() for m in entry.split(':')]\n                openscenario_params[key] = val\n        config = OpenScenarioConfiguration(self._args.openscenario, self.client, openscenario_params)\n\n        result = self._load_and_run_scenario(config)\n        self._cleanup()\n        return result\n\n    def run(self):\n        \"\"\"\n        Run all scenarios according to provided commandline args\n        \"\"\"\n        result = True\n        if self._args.openscenario:\n            result = self._run_openscenario()\n        elif self._args.route:\n            result = self._run_route()\n        else:\n            result = self._run_scenarios()\n\n        print(\"No more scenarios .... Exiting\")\n        return result\n\n\ndef main():\n    \"\"\"\n    main function\n    \"\"\"\n    description = (\"CARLA Scenario Runner: Setup, Run and Evaluate scenarios using CARLA\\n\"\n                   \"Current version: \" + VERSION)\n\n    # pylint: disable=line-too-long\n    parser = argparse.ArgumentParser(description=description,\n                                     formatter_class=RawTextHelpFormatter)\n    parser.add_argument('-v', '--version', action='version', version='%(prog)s ' + VERSION)\n    parser.add_argument('--host', default='127.0.0.1',\n                        help='IP of the host server (default: localhost)')\n    parser.add_argument('--port', default='2000',\n                        help='TCP port to listen to (default: 2000)')\n    parser.add_argument('--timeout', default=\"10.0\",\n                        help='Set the CARLA client timeout value in seconds')\n    parser.add_argument('--trafficManagerPort', default='8000',\n                        help='Port to use for the TrafficManager (default: 8000)')\n    parser.add_argument('--trafficManagerSeed', default='0',\n                        help='Seed used by the TrafficManager (default: 0)')\n    parser.add_argument('--sync', action='store_true',\n                        help='Forces the simulation to run synchronously')\n    parser.add_argument('--list', action=\"store_true\", help='List all supported scenarios and exit')\n\n    parser.add_argument(\n        '--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')\n    parser.add_argument('--openscenario', help='Provide an OpenSCENARIO definition')\n    parser.add_argument('--openscenarioparams', help='Overwrited for OpenSCENARIO ParameterDeclaration')\n    parser.add_argument('--route', help='Run a route as a scenario', type=str)\n    parser.add_argument('--route-id', help='Run a specific route inside that \\'route\\' file', default='', type=str)\n    parser.add_argument(\n        '--agent', help=\"Agent used to execute the route. Not compatible with non-route-based scenarios.\")\n    parser.add_argument('--agentConfig', type=str, help=\"Path to Agent's configuration file\", default=\"\")\n\n    parser.add_argument('--output', action=\"store_true\", help='Provide results on stdout')\n    parser.add_argument('--file', action=\"store_true\", help='Write results into a txt file')\n    parser.add_argument('--junit', action=\"store_true\", help='Write results into a junit file')\n    parser.add_argument('--json', action=\"store_true\", help='Write results into a JSON file')\n    parser.add_argument('--outputDir', default='', help='Directory for output files (default: this directory)')\n\n    parser.add_argument('--configFile', default='', help='Provide an additional scenario configuration file (*.xml)')\n    parser.add_argument('--additionalScenario', default='', help='Provide additional scenario implementations (*.py)')\n\n    parser.add_argument('--debug', action=\"store_true\", help='Run with debug output')\n    parser.add_argument('--reloadWorld', action=\"store_true\",\n                        help='Reload the CARLA world before starting a scenario (default=True)')\n    parser.add_argument('--record', type=str, default='',\n                        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.')\n    parser.add_argument('--randomize', action=\"store_true\", help='Scenario parameters are randomized')\n    parser.add_argument('--repetitions', default=1, type=int, help='Number of scenario executions')\n    parser.add_argument('--waitForEgo', action=\"store_true\", help='Connect the scenario to an existing ego vehicle')\n\n    arguments = parser.parse_args()\n    # pylint: enable=line-too-long\n\n    if arguments.list:\n        print(\"Currently the following scenarios are supported:\")\n        print(*ScenarioConfigurationParser.get_list_of_scenarios(arguments.configFile), sep='\\n')\n        return 1\n\n    if not arguments.scenario and not arguments.openscenario and not arguments.route:\n        print(\"Please specify either a scenario or use the route mode\\n\\n\")\n        parser.print_help(sys.stdout)\n        return 1\n\n    if arguments.route and (arguments.openscenario or arguments.scenario):\n        print(\"The route mode cannot be used together with a scenario (incl. OpenSCENARIO)'\\n\\n\")\n        parser.print_help(sys.stdout)\n        return 1\n\n    if arguments.agent and (arguments.openscenario or arguments.scenario):\n        print(\"Agents are currently only compatible with route scenarios'\\n\\n\")\n        parser.print_help(sys.stdout)\n        return 1\n\n    if arguments.openscenarioparams and not arguments.openscenario:\n        print(\"WARN: Ignoring --openscenarioparams when --openscenario is not specified\")\n\n    if arguments.route:\n        arguments.reloadWorld = True\n\n    if arguments.agent:\n        arguments.sync = True\n\n    scenario_runner = None\n    result = True\n    try:\n        scenario_runner = ScenarioRunner(arguments)\n        result = scenario_runner.run()\n    except Exception:   # pylint: disable=broad-except\n        traceback.print_exc()\n\n    finally:\n        if scenario_runner is not None:\n            scenario_runner.destroy()\n            del scenario_runner\n    return not result\n\n\nif __name__ == \"__main__\":\n    sys.exit(main())\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/agent_wrapper.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nWrapper for autonomous agents required for tracking and checking of used sensors\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom srunner.autoagents.sensor_interface import CallBack\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass AgentWrapper(object):\n\n    \"\"\"\n    Wrapper for autonomous agents required for tracking and checking of used sensors\n    \"\"\"\n\n    _agent = None\n    _sensors_list = []\n\n    def __init__(self, agent):\n        \"\"\"\n        Set the autonomous agent\n        \"\"\"\n        self._agent = agent\n\n    def __call__(self):\n        \"\"\"\n        Pass the call directly to the agent\n        \"\"\"\n        return self._agent()\n\n    def setup_sensors(self, vehicle, debug_mode=False):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        bp_library = CarlaDataProvider.get_world().get_blueprint_library()\n        for sensor_spec in self._agent.sensors():\n            # These are the sensors spawned on the carla world\n            bp = bp_library.find(str(sensor_spec['type']))\n            if sensor_spec['type'].startswith('sensor.camera'):\n                bp.set_attribute('image_size_x', str(sensor_spec['width']))\n                bp.set_attribute('image_size_y', str(sensor_spec['height']))\n                bp.set_attribute('fov', str(sensor_spec['fov']))\n                sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                 z=sensor_spec['z'])\n                sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                 roll=sensor_spec['roll'],\n                                                 yaw=sensor_spec['yaw'])\n            elif sensor_spec['type'].startswith('sensor.lidar'):\n                bp.set_attribute('range', str(sensor_spec['range']))\n                bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency']))\n                bp.set_attribute('channels', str(sensor_spec['channels']))\n                bp.set_attribute('upper_fov', str(sensor_spec['upper_fov']))\n                bp.set_attribute('lower_fov', str(sensor_spec['lower_fov']))\n                bp.set_attribute('points_per_second', str(sensor_spec['points_per_second']))\n                sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                 z=sensor_spec['z'])\n                sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                 roll=sensor_spec['roll'],\n                                                 yaw=sensor_spec['yaw'])\n            elif sensor_spec['type'].startswith('sensor.other.gnss'):\n                sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                 z=sensor_spec['z'])\n                sensor_rotation = carla.Rotation()\n\n            # create sensor\n            sensor_transform = carla.Transform(sensor_location, sensor_rotation)\n            sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)\n            # setup callback\n            sensor.listen(CallBack(sensor_spec['id'], sensor, self._agent.sensor_interface))\n            self._sensors_list.append(sensor)\n\n        # Tick once to spawn the sensors\n        CarlaDataProvider.get_world().tick()\n\n    def cleanup(self):\n        \"\"\"\n        Remove and destroy all sensors\n        \"\"\"\n        for i, _ in enumerate(self._sensors_list):\n            if self._sensors_list[i] is not None:\n                self._sensors_list[i].stop()\n                self._sensors_list[i].destroy()\n                self._sensors_list[i] = None\n        self._sensors_list = []\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/autonomous_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the base class for all autonomous agents\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom srunner.autoagents.sensor_interface import SensorInterface\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.tools.route_manipulation import downsample_route\n\n\nclass AutonomousAgent(object):\n\n    \"\"\"\n    Autonomous agent base class. All user agents have to be derived from this class\n    \"\"\"\n\n    def __init__(self, path_to_conf_file):\n        #  current global plans to reach a destination\n        self._global_plan = None\n        self._global_plan_world_coord = None\n\n        # this data structure will contain all sensor data\n        self.sensor_interface = SensorInterface()\n\n        # agent's initialization\n        self.setup(path_to_conf_file)\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Initialize everything needed by your agent and set the track attribute to the right type:\n        \"\"\"\n        pass\n\n    def sensors(self):  # pylint: disable=no-self-use\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n\n        \"\"\"\n        sensors = []\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        :return: control\n        \"\"\"\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Destroy (clean-up) the agent\n        :return:\n        \"\"\"\n        pass\n\n    def __call__(self):\n        \"\"\"\n        Execute the agent call, e.g. agent()\n        Returns the next vehicle controls\n        \"\"\"\n        input_data = self.sensor_interface.get_data()\n\n        timestamp = GameTime.get_time()\n        wallclock = GameTime.get_wallclocktime()\n        print('======[Agent] Wallclock_time = {} / Sim_time = {}'.format(wallclock, timestamp), flush=True)\n\n        control = self.run_step(input_data, timestamp)\n        control.manual_gear_shift = False\n\n        return control\n\n    def set_global_plan(self, global_plan_gps, global_plan_world_coord):\n        \"\"\"\n        Set the plan (route) for the agent\n        \"\"\"\n\n        ds_ids = downsample_route(global_plan_world_coord, 1)\n        self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1])\n                                         for x in ds_ids]\n        self._global_plan = [global_plan_gps[x] for x in ds_ids]\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/dummy_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a dummy agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\n\n\nclass DummyAgent(AutonomousAgent):\n\n    \"\"\"\n    Dummy autonomous agent to control the ego vehicle\n    \"\"\"\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n\n\n        \"\"\"\n        sensors = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'},\n                   {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n                    'yaw': -45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'},\n                   {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0,\n                    'width': 800, 'height': 600, 'fov': 100, 'id': 'Right'},\n                   {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,\n                    'yaw': -45.0, 'id': 'LIDAR'},\n                   {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'},\n                   {'type': 'sensor.can_bus', 'reading_frequency': 25, 'id': 'can_bus'},\n                   {'type': 'sensor.hd_map', 'reading_frequency': 1, 'id': 'hdmap'},\n                   ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        print(\"=====================>\")\n        for key, val in input_data.items():\n            if hasattr(val[1], 'shape'):\n                shape = val[1].shape\n                print(\"[{} -- {:06d}] with shape {}\".format(key, val[0], shape))\n            else:\n                print(\"[{} -- {:06d}] \".format(key, val[0]))\n        print(\"<=====================\")\n\n        # DO SOMETHING SMART\n\n        # RETURN CONTROL\n        control = carla.VehicleControl()\n        control.steer = 0.0\n        control.throttle = 0.0\n        control.brake = 0.0\n        control.hand_brake = False\n\n        return control\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/human_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a human agent to control the ego vehicle via keyboard\n\"\"\"\n\nfrom __future__ import print_function\n\nimport json\n\ntry:\n    import pygame\n    from pygame.locals import K_DOWN\n    from pygame.locals import K_LEFT\n    from pygame.locals import K_RIGHT\n    from pygame.locals import K_SPACE\n    from pygame.locals import K_UP\n    from pygame.locals import K_a\n    from pygame.locals import K_d\n    from pygame.locals import K_s\n    from pygame.locals import K_w\n    from pygame.locals import K_q\nexcept ImportError:\n    raise RuntimeError('cannot import pygame, make sure pygame package is installed')\n\nimport carla\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\n\n\nclass HumanInterface(object):\n\n    \"\"\"\n    Class to control a vehicle manually for debugging purposes\n    \"\"\"\n\n    def __init__(self, width, height):\n        self._width = width\n        self._height = height\n        self._surface = None\n\n        pygame.init()\n        pygame.font.init()\n        self._clock = pygame.time.Clock()\n        self._display = pygame.display.set_mode((self._width, self._height), pygame.HWSURFACE | pygame.DOUBLEBUF)\n        pygame.display.set_caption(\"Human Agent\")\n\n    def run_interface(self, input_data):\n        \"\"\"\n        Run the GUI\n        \"\"\"\n        # process sensor data\n        image_center = input_data['Center'][1][:, :, -2::-1]\n\n        # display image\n        self._surface = pygame.surfarray.make_surface(image_center.swapaxes(0, 1))\n        if self._surface is not None:\n            self._display.blit(self._surface, (0, 0))\n        pygame.display.flip()\n\n    def quit_interface(self):\n        \"\"\"\n        Stops the pygame window\n        \"\"\"\n        pygame.quit()\n\n\nclass HumanAgent(AutonomousAgent):\n\n    \"\"\"\n    Human agent to control the ego vehicle via keyboard\n    \"\"\"\n\n    current_control = None\n    agent_engaged = False\n    prev_timestamp = 0\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n\n        self.agent_engaged = False\n        self.camera_width = 800\n        self.camera_height = 500\n\n        self._hic = HumanInterface(self.camera_width, self.camera_height)\n        self._controller = KeyboardControl(path_to_conf_file)\n        self.prev_timestamp = 0\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            ['sensor.camera.rgb', {'x':x_rel, 'y': y_rel, 'z': z_rel,\n                                   'yaw': yaw, 'pitch': pitch, 'roll': roll,\n                                   'width': width, 'height': height, 'fov': fov}, 'Sensor01'],\n            ['sensor.camera.rgb', {'x':x_rel, 'y': y_rel, 'z': z_rel,\n                                   'yaw': yaw, 'pitch': pitch, 'roll': roll,\n                                   'width': width, 'height': height, 'fov': fov}, 'Sensor02'],\n\n            ['sensor.lidar.ray_cast', {'x':x_rel, 'y': y_rel, 'z': z_rel,\n                                       'yaw': yaw, 'pitch': pitch, 'roll': roll}, 'Sensor03']\n        ]\n\n        \"\"\"\n        sensors = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': self.camera_width, 'height': self.camera_height, 'fov': 100, 'id': 'Center'},\n                   {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'}\n                   ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        self.agent_engaged = True\n        self._hic.run_interface(input_data)\n\n        control = self._controller.parse_events(timestamp - self.prev_timestamp)\n        self.prev_timestamp = timestamp\n\n        return control\n\n    def destroy(self):\n        \"\"\"\n        Cleanup\n        \"\"\"\n        self._hic.quit_interface = True\n\n\nclass KeyboardControl(object):\n\n    \"\"\"\n    Keyboard control for the human agent\n    \"\"\"\n\n    def __init__(self, path_to_conf_file):\n        \"\"\"\n        Init\n        \"\"\"\n        self._control = carla.VehicleControl()\n        self._steer_cache = 0.0\n        self._clock = pygame.time.Clock()\n\n        # Get the mode\n        if path_to_conf_file:\n\n            with (open(path_to_conf_file, \"r\")) as f:\n                lines = f.read().split(\"\\n\")\n                self._mode = lines[0].split(\" \")[1]\n                self._endpoint = lines[1].split(\" \")[1]\n\n            # Get the needed vars\n            if self._mode == \"log\":\n                self._log_data = {'records': []}\n\n            elif self._mode == \"playback\":\n                self._index = 0\n                self._control_list = []\n\n                with open(self._endpoint) as fd:\n                    try:\n                        self._records = json.load(fd)\n                        self._json_to_control()\n                    except ValueError:\n                        # Moving to Python 3.5+ this can be replaced with json.JSONDecodeError\n                        pass\n        else:\n            self._mode = \"normal\"\n            self._endpoint = None\n\n    def _json_to_control(self):\n        \"\"\"\n        Parses the json file into a list of carla.VehicleControl\n        \"\"\"\n\n        # transform strs into VehicleControl commands\n        for entry in self._records['records']:\n            control = carla.VehicleControl(throttle=entry['control']['throttle'],\n                                           steer=entry['control']['steer'],\n                                           brake=entry['control']['brake'],\n                                           hand_brake=entry['control']['hand_brake'],\n                                           reverse=entry['control']['reverse'],\n                                           manual_gear_shift=entry['control']['manual_gear_shift'],\n                                           gear=entry['control']['gear'])\n            self._control_list.append(control)\n\n    def parse_events(self, timestamp):\n        \"\"\"\n        Parse the keyboard events and set the vehicle controls accordingly\n        \"\"\"\n        # Move the vehicle\n        if self._mode == \"playback\":\n            self._parse_json_control()\n        else:\n            self._parse_vehicle_keys(pygame.key.get_pressed(), timestamp * 1000)\n\n        # Record the control\n        if self._mode == \"log\":\n            self._record_control()\n\n        return self._control\n\n    def _parse_vehicle_keys(self, keys, milliseconds):\n        \"\"\"\n        Calculate new vehicle controls based on input keys\n        \"\"\"\n        for event in pygame.event.get():\n            if event.type == pygame.QUIT:\n                return\n            elif event.type == pygame.KEYUP:\n                if event.key == K_q:\n                    self._control.gear = 1 if self._control.reverse else -1\n                    self._control.reverse = self._control.gear < 0\n\n        if keys[K_UP] or keys[K_w]:\n            self._control.throttle = 0.6\n        else:\n            self._control.throttle = 0.0\n\n        steer_increment = 3e-4 * milliseconds\n        if keys[K_LEFT] or keys[K_a]:\n            self._steer_cache -= steer_increment\n        elif keys[K_RIGHT] or keys[K_d]:\n            self._steer_cache += steer_increment\n        else:\n            self._steer_cache = 0.0\n\n        self._steer_cache = min(0.95, max(-0.95, self._steer_cache))\n        self._control.steer = round(self._steer_cache, 1)\n        self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0\n        self._control.hand_brake = keys[K_SPACE]\n\n    def _parse_json_control(self):\n        \"\"\"\n        Gets the control corresponding to the current frame\n        \"\"\"\n\n        if self._index < len(self._control_list):\n            self._control = self._control_list[self._index]\n            self._index += 1\n        else:\n            print(\"JSON file has no more entries\")\n\n    def _record_control(self):\n        \"\"\"\n        Saves the list of control into a json file\n        \"\"\"\n\n        new_record = {\n            'control': {\n                'throttle': self._control.throttle,\n                'steer': self._control.steer,\n                'brake': self._control.brake,\n                'hand_brake': self._control.hand_brake,\n                'reverse': self._control.reverse,\n                'manual_gear_shift': self._control.manual_gear_shift,\n                'gear': self._control.gear\n            }\n        }\n\n        self._log_data['records'].append(new_record)\n\n    def __del__(self):\n        \"\"\"\n        Delete method\n        \"\"\"\n        # Get ready to log user commands\n        if self._mode == \"log\" and self._log_data:\n            with open(self._endpoint, 'w') as fd:\n                json.dump(self._log_data, fd, indent=4, sort_keys=True)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/human_agent_config.txt",
    "content": "mode: log                      # Either 'log' or 'playback'\nfile: test.json                     # path to the file with the controls\n\n\nThis is the configuration file of the human agent. This agent incorporates two modes.\nThe log mode parses the controls given to the vehicle into a dictionary and records them into a .json file.\nThis file can be read by the playback mode to control the vehicle in the same way, resulting in a deterministic agent.\nThe file name can be chosen, and is the second argument of this config file.\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/npc_agent.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an NPC agent to control the ego vehicle\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass NpcAgent(AutonomousAgent):\n\n    \"\"\"\n    NPC autonomous agent to control the ego vehicle\n    \"\"\"\n\n    _agent = None\n    _route_assigned = False\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        Setup the agent parameters\n        \"\"\"\n        self._agent = None\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors in the following format:\n\n        [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                      'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'},\n\n            {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0,\n             'id': 'LIDAR'}\n        ]\n        \"\"\"\n\n        sensors = [\n            {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n             'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'},\n        ]\n\n        return sensors\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        if not self._agent:\n\n            # Search for the ego actor\n            hero_actor = None\n            for actor in CarlaDataProvider.get_world().get_actors():\n                if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero':\n                    hero_actor = actor\n                    break\n\n            if not hero_actor:\n                return carla.VehicleControl()\n\n            # Add an agent that follows the route to the ego\n            self._agent = BasicAgent(hero_actor, 30)\n\n            plan = []\n            prev_wp = None\n            for transform, _ in self._global_plan_world_coord:\n                wp = CarlaDataProvider.get_map().get_waypoint(transform.location)\n                if prev_wp:\n                    plan.extend(self._agent.trace_route(prev_wp, wp))\n                prev_wp = wp\n\n            self._agent.set_global_plan(plan)\n\n            return carla.VehicleControl()\n\n        else:\n            return self._agent.run_step()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/ros_agent.py",
    "content": "#!/usr/bin/env python\n#\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n#\n\n\"\"\"\nThis module provides a ROS autonomous agent interface to control the ego vehicle via a ROS stack\n\"\"\"\n\nimport math\nimport os\nimport subprocess\nimport signal\nimport threading\nimport time\n\nimport numpy\n\nimport carla\n\nimport rospy\nfrom cv_bridge import CvBridge\nfrom geometry_msgs.msg import PoseStamped\nfrom nav_msgs.msg import Odometry, Path\nfrom rosgraph_msgs.msg import Clock\nfrom sensor_msgs.msg import Image, PointCloud2, NavSatFix, NavSatStatus, CameraInfo\nfrom sensor_msgs.point_cloud2 import create_cloud_xyz32\nfrom std_msgs.msg import Header, String\nimport tf\n# pylint: disable=line-too-long\nfrom carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, CarlaEgoVehicleControl, CarlaWorldInfo\n# pylint: enable=line-too-long\n\nfrom srunner.autoagents.autonomous_agent import AutonomousAgent\n\n\nclass RosAgent(AutonomousAgent):\n\n    \"\"\"\n    Base class for ROS-based stacks.\n\n    Derive from it and implement the sensors() method.\n\n    Please define TEAM_CODE_ROOT in your environment.\n    The stack is started by executing $TEAM_CODE_ROOT/start.sh\n\n    The sensor data is published on similar topics as with the carla-ros-bridge. You can find details about\n    the utilized datatypes there.\n\n    This agent expects a roscore to be running.\n    \"\"\"\n\n    speed = None\n    current_control = None\n    stack_process = None\n    timestamp = None\n    current_map_name = None\n    step_mode_possible = None\n    vehicle_info_publisher = None\n    global_plan_published = None\n\n    def setup(self, path_to_conf_file):\n        \"\"\"\n        setup agent\n        \"\"\"\n        self.stack_thread = None\n\n        # get start_script from environment\n        team_code_path = os.environ['TEAM_CODE_ROOT']\n        if not team_code_path or not os.path.exists(team_code_path):\n            raise IOError(\"Path '{}' defined by TEAM_CODE_ROOT invalid\".format(team_code_path))\n        start_script = \"{}/start.sh\".format(team_code_path)\n        if not os.path.exists(start_script):\n            raise IOError(\"File '{}' defined by TEAM_CODE_ROOT invalid\".format(start_script))\n\n        # set use_sim_time via commandline before init-node\n        process = subprocess.Popen(\n            \"rosparam set use_sim_time true\", shell=True, stderr=subprocess.STDOUT, stdout=subprocess.PIPE)\n        process.wait()\n        if process.returncode:\n            raise RuntimeError(\"Could not set use_sim_time\")\n\n        # initialize ros node\n        rospy.init_node('ros_agent', anonymous=True)\n\n        # publish first clock value '0'\n        self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10, latch=True)\n        self.clock_publisher.publish(Clock(rospy.Time.from_sec(0)))\n\n        # execute script that starts the ad stack (remains running)\n        rospy.loginfo(\"Executing stack...\")\n        self.stack_process = subprocess.Popen(start_script, shell=True, preexec_fn=os.setpgrp)\n\n        self.vehicle_control_event = threading.Event()\n        self.timestamp = None\n        self.speed = 0\n        self.global_plan_published = False\n\n        self.vehicle_info_publisher = None\n        self.vehicle_status_publisher = None\n        self.odometry_publisher = None\n        self.world_info_publisher = None\n        self.map_file_publisher = None\n        self.current_map_name = None\n        self.tf_broadcaster = None\n        self.step_mode_possible = False\n\n        self.vehicle_control_subscriber = rospy.Subscriber(\n            '/carla/ego_vehicle/vehicle_control_cmd', CarlaEgoVehicleControl, self.on_vehicle_control)\n\n        self.current_control = carla.VehicleControl()\n\n        self.waypoint_publisher = rospy.Publisher(\n            '/carla/ego_vehicle/waypoints', Path, queue_size=1, latch=True)\n\n        self.publisher_map = {}\n        self.id_to_sensor_type_map = {}\n        self.id_to_camera_info_map = {}\n        self.cv_bridge = CvBridge()\n\n        # setup ros publishers for sensors\n        # pylint: disable=line-too-long\n        for sensor in self.sensors():\n            self.id_to_sensor_type_map[sensor['id']] = sensor['type']\n            if sensor['type'] == 'sensor.camera.rgb':\n                self.publisher_map[sensor['id']] = rospy.Publisher(\n                    '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + \"/image_color\", Image, queue_size=1, latch=True)\n                self.id_to_camera_info_map[sensor['id']] = self.build_camera_info(sensor)\n                self.publisher_map[sensor['id'] + '_info'] = rospy.Publisher(\n                    '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + \"/camera_info\", CameraInfo, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.lidar.ray_cast':\n                self.publisher_map[sensor['id']] = rospy.Publisher(\n                    '/carla/ego_vehicle/lidar/' + sensor['id'] + \"/point_cloud\", PointCloud2, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.other.gnss':\n                self.publisher_map[sensor['id']] = rospy.Publisher(\n                    '/carla/ego_vehicle/gnss/' + sensor['id'] + \"/fix\", NavSatFix, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.can_bus':\n                if not self.vehicle_info_publisher:\n                    self.vehicle_info_publisher = rospy.Publisher(\n                        '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True)\n                if not self.vehicle_status_publisher:\n                    self.vehicle_status_publisher = rospy.Publisher(\n                        '/carla/ego_vehicle/vehicle_status', CarlaEgoVehicleStatus, queue_size=1, latch=True)\n            elif sensor['type'] == 'sensor.hd_map':\n                if not self.odometry_publisher:\n                    self.odometry_publisher = rospy.Publisher(\n                        '/carla/ego_vehicle/odometry', Odometry, queue_size=1, latch=True)\n                if not self.world_info_publisher:\n                    self.world_info_publisher = rospy.Publisher(\n                        '/carla/world_info', CarlaWorldInfo, queue_size=1, latch=True)\n                if not self.map_file_publisher:\n                    self.map_file_publisher = rospy.Publisher('/carla/map_file', String, queue_size=1, latch=True)\n                if not self.tf_broadcaster:\n                    self.tf_broadcaster = tf.TransformBroadcaster()\n            else:\n                raise TypeError(\"Invalid sensor type: {}\".format(sensor['type']))\n        # pylint: enable=line-too-long\n\n    def destroy(self):\n        \"\"\"\n        Cleanup of all ROS publishers\n        \"\"\"\n        if self.stack_process and self.stack_process.poll() is None:\n            rospy.loginfo(\"Sending SIGTERM to stack...\")\n            os.killpg(os.getpgid(self.stack_process.pid), signal.SIGTERM)\n            rospy.loginfo(\"Waiting for termination of stack...\")\n            self.stack_process.wait()\n            time.sleep(5)\n            rospy.loginfo(\"Terminated stack.\")\n\n        rospy.loginfo(\"Stack is no longer running\")\n        self.world_info_publisher.unregister()\n        self.map_file_publisher.unregister()\n        self.vehicle_status_publisher.unregister()\n        self.vehicle_info_publisher.unregister()\n        self.waypoint_publisher.unregister()\n        self.stack_process = None\n        rospy.loginfo(\"Cleanup finished\")\n\n    def on_vehicle_control(self, data):\n        \"\"\"\n        callback if a new vehicle control command is received\n        \"\"\"\n        cmd = carla.VehicleControl()\n        cmd.throttle = data.throttle\n        cmd.steer = data.steer\n        cmd.brake = data.brake\n        cmd.hand_brake = data.hand_brake\n        cmd.reverse = data.reverse\n        cmd.gear = data.gear\n        cmd.manual_gear_shift = data.manual_gear_shift\n        self.current_control = cmd\n        if not self.vehicle_control_event.is_set():\n            self.vehicle_control_event.set()\n        # After the first vehicle control is sent out, it is possible to use the stepping mode\n        self.step_mode_possible = True\n\n    def build_camera_info(self, attributes):  # pylint: disable=no-self-use\n        \"\"\"\n        Private function to compute camera info\n\n        camera info doesn't change over time\n        \"\"\"\n        camera_info = CameraInfo()\n        # store info without header\n        camera_info.header = None\n        camera_info.width = int(attributes['width'])\n        camera_info.height = int(attributes['height'])\n        camera_info.distortion_model = 'plumb_bob'\n        cx = camera_info.width / 2.0\n        cy = camera_info.height / 2.0\n        fx = camera_info.width / (\n            2.0 * math.tan(float(attributes['fov']) * math.pi / 360.0))\n        fy = fx\n        camera_info.K = [fx, 0, cx, 0, fy, cy, 0, 0, 1]\n        camera_info.D = [0, 0, 0, 0, 0]\n        camera_info.R = [1.0, 0, 0, 0, 1.0, 0, 0, 0, 1.0]\n        camera_info.P = [fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1.0, 0]\n        return camera_info\n\n    def publish_plan(self):\n        \"\"\"\n        publish the global plan\n        \"\"\"\n        msg = Path()\n        msg.header.frame_id = \"/map\"\n        msg.header.stamp = rospy.Time.now()\n        for wp in self._global_plan_world_coord:\n            pose = PoseStamped()\n            pose.pose.position.x = wp[0].location.x\n            pose.pose.position.y = -wp[0].location.y\n            pose.pose.position.z = wp[0].location.z\n            quaternion = tf.transformations.quaternion_from_euler(\n                0, 0, -math.radians(wp[0].rotation.yaw))\n            pose.pose.orientation.x = quaternion[0]\n            pose.pose.orientation.y = quaternion[1]\n            pose.pose.orientation.z = quaternion[2]\n            pose.pose.orientation.w = quaternion[3]\n            msg.poses.append(pose)\n\n        rospy.loginfo(\"Publishing Plan...\")\n        self.waypoint_publisher.publish(msg)\n\n    def sensors(self):\n        \"\"\"\n        Define the sensor suite required by the agent\n\n        :return: a list containing the required sensors\n        \"\"\"\n        raise NotImplementedError(\n            \"This function has to be implemented by the derived classes\")\n\n    def get_header(self):\n        \"\"\"\n        Returns ROS message header\n        \"\"\"\n        header = Header()\n        header.stamp = rospy.Time.from_sec(self.timestamp)\n        return header\n\n    def publish_lidar(self, sensor_id, data):\n        \"\"\"\n        Function to publish lidar data\n        \"\"\"\n        header = self.get_header()\n        header.frame_id = 'ego_vehicle/lidar/{}'.format(sensor_id)\n\n        lidar_data = numpy.frombuffer(\n            data, dtype=numpy.float32)\n        lidar_data = numpy.reshape(\n            lidar_data, (int(lidar_data.shape[0] / 3), 3))\n        # we take the oposite of y axis\n        # (as lidar point are express in left handed coordinate system, and ros need right handed)\n        # we need a copy here, because the data are read only in carla numpy\n        # array\n        lidar_data = -1.0 * lidar_data\n        # we also need to permute x and y\n        lidar_data = lidar_data[..., [1, 0, 2]]\n        msg = create_cloud_xyz32(header, lidar_data)\n        self.publisher_map[sensor_id].publish(msg)\n\n    def publish_gnss(self, sensor_id, data):\n        \"\"\"\n        Function to publish gnss data\n        \"\"\"\n        msg = NavSatFix()\n        msg.header = self.get_header()\n        msg.header.frame_id = 'gps'\n        msg.latitude = data[0]\n        msg.longitude = data[1]\n        msg.altitude = data[2]\n        msg.status.status = NavSatStatus.STATUS_SBAS_FIX\n        # pylint: disable=line-too-long\n        msg.status.service = NavSatStatus.SERVICE_GPS | NavSatStatus.SERVICE_GLONASS | NavSatStatus.SERVICE_COMPASS | NavSatStatus.SERVICE_GALILEO\n        # pylint: enable=line-too-long\n        self.publisher_map[sensor_id].publish(msg)\n\n    def publish_camera(self, sensor_id, data):\n        \"\"\"\n        Function to publish camera data\n        \"\"\"\n        msg = self.cv_bridge.cv2_to_imgmsg(data, encoding='bgra8')\n        # the camera data is in respect to the camera's own frame\n        msg.header = self.get_header()\n        msg.header.frame_id = 'ego_vehicle/camera/rgb/{}'.format(sensor_id)\n\n        cam_info = self.id_to_camera_info_map[sensor_id]\n        cam_info.header = msg.header\n        self.publisher_map[sensor_id + '_info'].publish(cam_info)\n        self.publisher_map[sensor_id].publish(msg)\n\n    def publish_can(self, sensor_id, data):\n        \"\"\"\n        publish can data\n        \"\"\"\n        if not self.vehicle_info_publisher:\n            self.vehicle_info_publisher = rospy.Publisher(\n                '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True)\n            info_msg = CarlaEgoVehicleInfo()\n            for wheel in data['wheels']:\n                wheel_info = CarlaEgoVehicleInfoWheel()\n                wheel_info.tire_friction = wheel['tire_friction']\n                wheel_info.damping_rate = wheel['damping_rate']\n                wheel_info.steer_angle = wheel['steer_angle']\n                wheel_info.disable_steering = wheel['disable_steering']\n                info_msg.wheels.append(wheel_info)\n            info_msg.max_rpm = data['max_rpm']\n            info_msg.moi = data['moi']\n            info_msg.damping_rate_full_throttle = data['damping_rate_full_throttle']\n            info_msg.damping_rate_zero_throttle_clutch_disengaged = data['damping_rate_zero_throttle_clutch_disengaged']\n            info_msg.use_gear_autobox = data['use_gear_autobox']\n            info_msg.clutch_strength = data['clutch_strength']\n            info_msg.mass = data['mass']\n            info_msg.drag_coefficient = data['drag_coefficient']\n            info_msg.center_of_mass.x = data['center_of_mass']['x']\n            info_msg.center_of_mass.y = data['center_of_mass']['y']\n            info_msg.center_of_mass.z = data['center_of_mass']['z']\n            self.vehicle_info_publisher.publish(info_msg)\n        msg = CarlaEgoVehicleStatus()\n        msg.header = self.get_header()\n        msg.velocity = data['speed']\n        self.speed = data['speed']\n        # todo msg.acceleration\n        msg.control.throttle = self.current_control.throttle\n        msg.control.steer = self.current_control.steer\n        msg.control.brake = self.current_control.brake\n        msg.control.hand_brake = self.current_control.hand_brake\n        msg.control.reverse = self.current_control.reverse\n        msg.control.gear = self.current_control.gear\n        msg.control.manual_gear_shift = self.current_control.manual_gear_shift\n\n        self.vehicle_status_publisher.publish(msg)\n\n    def publish_hd_map(self, sensor_id, data):\n        \"\"\"\n        publish hd map data\n        \"\"\"\n        roll = -math.radians(data['transform']['roll'])\n        pitch = -math.radians(data['transform']['pitch'])\n        yaw = -math.radians(data['transform']['yaw'])\n        quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw)\n        x = data['transform']['x']\n        y = -data['transform']['y']\n        z = data['transform']['z']\n\n        if self.odometry_publisher:\n\n            odometry = Odometry()\n            odometry.header.frame_id = 'map'\n            odometry.header.stamp = rospy.Time.from_sec(self.timestamp)\n            odometry.child_frame_id = 'base_link'\n            odometry.pose.pose.position.x = x\n            odometry.pose.pose.position.y = y\n            odometry.pose.pose.position.z = z\n\n            odometry.pose.pose.orientation.x = quat[0]\n            odometry.pose.pose.orientation.y = quat[1]\n            odometry.pose.pose.orientation.z = quat[2]\n            odometry.pose.pose.orientation.w = quat[3]\n\n            odometry.twist.twist.linear.x = self.speed\n            odometry.twist.twist.linear.y = 0\n            odometry.twist.twist.linear.z = 0\n\n            self.odometry_publisher.publish(odometry)\n\n        if self.world_info_publisher:\n            # extract map name\n            map_name = os.path.basename(data['map_file'])[:-4]\n            if self.current_map_name != map_name:\n                self.current_map_name = map_name\n                world_info = CarlaWorldInfo()\n                world_info.map_name = self.current_map_name\n                world_info.opendrive = data['opendrive']\n                self.world_info_publisher.publish(world_info)\n        if self.map_file_publisher:\n            self.map_file_publisher.publish(data['map_file'])\n\n    def use_stepping_mode(self):  # pylint: disable=no-self-use\n        \"\"\"\n        Overload this function to use stepping mode!\n        \"\"\"\n        return False\n\n    def run_step(self, input_data, timestamp):\n        \"\"\"\n        Execute one step of navigation.\n        \"\"\"\n        self.vehicle_control_event.clear()\n        self.timestamp = timestamp\n        self.clock_publisher.publish(Clock(rospy.Time.from_sec(timestamp)))\n\n        # check if stack is still running\n        if self.stack_process and self.stack_process.poll() is not None:\n            raise RuntimeError(\"Stack exited with: {} {}\".format(\n                self.stack_process.returncode, self.stack_process.communicate()[0]))\n\n        # publish global plan to ROS once\n        if self._global_plan_world_coord and not self.global_plan_published:\n            self.global_plan_published = True\n            self.publish_plan()\n\n        new_data_available = False\n\n        # publish data of all sensors\n        for key, val in input_data.items():\n            new_data_available = True\n            sensor_type = self.id_to_sensor_type_map[key]\n            if sensor_type == 'sensor.camera.rgb':\n                self.publish_camera(key, val[1])\n            elif sensor_type == 'sensor.lidar.ray_cast':\n                self.publish_lidar(key, val[1])\n            elif sensor_type == 'sensor.other.gnss':\n                self.publish_gnss(key, val[1])\n            elif sensor_type == 'sensor.can_bus':\n                self.publish_can(key, val[1])\n            elif sensor_type == 'sensor.hd_map':\n                self.publish_hd_map(key, val[1])\n            else:\n                raise TypeError(\"Invalid sensor type: {}\".format(sensor_type))\n\n        if self.use_stepping_mode():\n            if self.step_mode_possible and new_data_available:\n                self.vehicle_control_event.wait()\n        # if the stepping mode is not used or active, there is no need to wait here\n\n        return self.current_control\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/autoagents/sensor_interface.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis file containts CallBack class and SensorInterface, responsible of\nhandling the use of sensors for the agents\n\"\"\"\n\nimport copy\nimport logging\n\ntry:\n    from queue import Queue\n    from queue import Empty\nexcept ImportError:\n    from Queue import Queue\n    from Queue import Empty\n\nimport numpy as np\n\nimport carla\n\n\nclass SensorReceivedNoData(Exception):\n\n    \"\"\"\n    Exceptions thrown when the sensors used by the agent take too long to receive data\n    \"\"\"\n\n\nclass CallBack(object):\n\n    \"\"\"\n    Class the sensors listen to in order to receive their data each frame\n    \"\"\"\n\n    def __init__(self, tag, sensor, data_provider):\n        \"\"\"\n        Initializes the call back\n        \"\"\"\n        self._tag = tag\n        self._data_provider = data_provider\n\n        self._data_provider.register_sensor(tag, sensor)\n\n    def __call__(self, data):\n        \"\"\"\n        call function\n        \"\"\"\n        if isinstance(data, carla.Image):\n            self._parse_image_cb(data, self._tag)\n        elif isinstance(data, carla.LidarMeasurement):\n            self._parse_lidar_cb(data, self._tag)\n        elif isinstance(data, carla.RadarMeasurement):\n            self._parse_radar_cb(data, self._tag)\n        elif isinstance(data, carla.GnssMeasurement):\n            self._parse_gnss_cb(data, self._tag)\n        elif isinstance(data, carla.IMUMeasurement):\n            self._parse_imu_cb(data, self._tag)\n        else:\n            logging.error('No callback method for this sensor.')\n\n    # Parsing CARLA physical Sensors\n    def _parse_image_cb(self, image, tag):\n        \"\"\"\n        parses cameras\n        \"\"\"\n        array = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n        array = copy.deepcopy(array)\n        array = np.reshape(array, (image.height, image.width, 4))\n        self._data_provider.update_sensor(tag, array, image.frame)\n\n    def _parse_lidar_cb(self, lidar_data, tag):\n        \"\"\"\n        parses lidar sensors\n        \"\"\"\n        points = np.frombuffer(lidar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        self._data_provider.update_sensor(tag, points, lidar_data.frame)\n\n    def _parse_radar_cb(self, radar_data, tag):\n        \"\"\"\n        parses radar sensors\n        \"\"\"\n        # [depth, azimuth, altitute, velocity]\n        points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4'))\n        points = copy.deepcopy(points)\n        points = np.reshape(points, (int(points.shape[0] / 4), 4))\n        points = np.flip(points, 1)\n        self._data_provider.update_sensor(tag, points, radar_data.frame)\n\n    def _parse_gnss_cb(self, gnss_data, tag):\n        \"\"\"\n        parses gnss sensors\n        \"\"\"\n        array = np.array([gnss_data.latitude,\n                          gnss_data.longitude,\n                          gnss_data.altitude], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, gnss_data.frame)\n\n    def _parse_imu_cb(self, imu_data, tag):\n        \"\"\"\n        parses IMU sensors\n        \"\"\"\n        array = np.array([imu_data.accelerometer.x,\n                          imu_data.accelerometer.y,\n                          imu_data.accelerometer.z,\n                          imu_data.gyroscope.x,\n                          imu_data.gyroscope.y,\n                          imu_data.gyroscope.z,\n                          imu_data.compass,\n                          ], dtype=np.float64)\n        self._data_provider.update_sensor(tag, array, imu_data.frame)\n\n\nclass SensorInterface(object):\n\n    \"\"\"\n    Class that contains all sensor data\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the class\n        \"\"\"\n        self._sensors_objects = {}\n        self._new_data_buffers = Queue()\n        self._queue_timeout = 30\n\n    def register_sensor(self, tag, sensor):\n        \"\"\"\n        Registers the sensors\n        \"\"\"\n        if tag in self._sensors_objects:\n            raise ValueError(\"Duplicated sensor tag [{}]\".format(tag))\n\n        self._sensors_objects[tag] = sensor\n\n    def update_sensor(self, tag, data, timestamp):\n        \"\"\"\n        Updates the sensor\n        \"\"\"\n        if tag not in self._sensors_objects:\n            raise ValueError(\"The sensor with tag [{}] has not been created!\".format(tag))\n\n        self._new_data_buffers.put((tag, timestamp, data))\n\n    def get_data(self):\n        \"\"\"\n        Returns the data of a sensor\n        \"\"\"\n        try:\n            data_dict = {}\n            while len(data_dict.keys()) < len(self._sensors_objects.keys()):\n\n                sensor_data = self._new_data_buffers.get(True, self._queue_timeout)\n                data_dict[sensor_data[0]] = ((sensor_data[1], sensor_data[2]))\n\n        except Empty:\n            raise SensorReceivedNoData(\"A sensor took too long to send its data\")\n\n        return data_dict\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/ActorFlow.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"EnterActorFlow_1\" type=\"EnterActorFlow\" town=\"Town04\">\n        <ego_vehicle x=\"86.9\" y=\"144.0\" z=\"1.9\" yaw=\"170\" model=\"vehicle.lincoln.mkz_2017\" />\n        <start_actor_flow x=\"16.2\" y=\"220.6\" z=\"0.2\"/>\n        <end_actor_flow x=\"15.50\" y=\"35.0\" z=\"0.2\"/>\n        <flow_speed value=\"30\"/>\n        <source_dist_interval from=\"35\" to=\"50\"/>\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/CatalogExample.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:PedestrianCrossing\" author=\"\"/>\n  <ParameterDeclarations>\n    <ParameterDeclaration name=\"weather\" parameterType=\"string\" value=\"ClearNoon\" />\n    <ParameterDeclaration name=\"carcolor\" parameterType=\"string\" value=\"122,122,122\" />\n  </ParameterDeclarations>\n  <CatalogLocations>\n    <VehicleCatalog>\n      <Directory path=\"catalogs\"/>\n    </VehicleCatalog>\n    <PedestrianCatalog>\n      <Directory path=\"catalogs\"/>\n    </PedestrianCatalog>\n    <MiscObjectCatalog>\n      <Directory path=\"catalogs\"/>\n    </MiscObjectCatalog>\n    <EnvironmentCatalog>\n      <Directory path=\"catalogs\"/>\n    </EnvironmentCatalog>\n    <ManeuverCatalog>\n      <Directory path=\"catalogs\"/>\n    </ManeuverCatalog>\n    <ControllerCatalog>\n      <Directory path=\"catalogs\"/>\n    </ControllerCatalog>\n  </CatalogLocations>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <CatalogReference catalogName=\"VehicleCatalog\" entryName=\"vehicle.volkswagen.t2\"/> \n    </ScenarioObject>\n    <ScenarioObject name=\"vehicle\">\n      <CatalogReference catalogName=\"VehicleCatalog\" entryName=\"vehicle.tesla.model3\">\n        <ParameterAssignments>\n          <ParameterAssignment parameterRef=\"carcolor\" value=\"255,255,0\" />\n        </ParameterAssignments>\n      </CatalogReference>\n    </ScenarioObject>\n    <ScenarioObject name=\"vehicle2\">\n      <CatalogReference catalogName=\"VehicleCatalog\" entryName=\"vehicle.tesla.model3\">\n        <ParameterAssignments>\n          <ParameterAssignment parameterRef=\"carcolor\" value=\"122,122,122\" />\n        </ParameterAssignments>\n      </CatalogReference>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <CatalogReference catalogName=\"PedestrianCatalog\" entryName=\"Pedestrian1\"/>\n    </ScenarioObject>\n    <ScenarioObject name=\"barrier1\">\n      <CatalogReference catalogName=\"MiscObjectCatalog\" entryName=\"Barrier1\"/>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <CatalogReference catalogName=\"EnvironmentCatalog\" entryName=\"$weather\"/>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"170\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <CatalogReference catalogName=\"ControllerCatalog\" entryName=\"ExternalControl\"/>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"vehicle\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"150\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"vehicle2\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"150\" y=\"60\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"110\" y=\"52\" z=\"0.3\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"barrier1\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"100\" y=\"58\" z=\"0\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"AutopilotSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"vehicle\"/>\n          </Actors>\n          <CatalogReference catalogName=\"ManeuverCatalog\" entryName=\"Autopilot\"/>\n        </ManeuverGroup>\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"PedestrianCrossingSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"PedestrianCrossingManeuver\">\n            <Event name=\"PedestrianStartsWalking\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalking\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"3\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"10.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"vehicle\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <ReachPositionCondition tolerance=\"1.0\">\n                          <Position>\n                            <WorldPosition x=\"140\" y=\"55\" z=\"0\"/>\n                          </Position>\n                        </ReachPositionCondition>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianStopsAndWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianStopsAndWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"5\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianWalks\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalking\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWalksAway\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalkingAway\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"6.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"vehicle\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStopsAndWaits\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStopsAndWaits\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalkingAway\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"20.0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/ChangeLane.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"ChangeLane_1\" type=\"ChangeLane\" town=\"Town04\">\n        <ego_vehicle x=\"284.4\" y=\"16.4\" z=\"2.5\" yaw=\"-173\" model=\"vehicle.lincoln.mkz_2017\" />\n\t<!-- spawn actors-->\n\t<other_actor x=\"264.4\" y=\"16.3\" z=\"-500\" yaw=\"-179\" model=\"vehicle.tesla.model3\" />\n\t<other_actor x=\"184.4\" y=\"14.9\" z=\"-500\" yaw=\"-176\" model=\"vehicle.volkswagen.t2\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n    <scenario name=\"ChangeLane_2\" type=\"ChangeLane\" town=\"Town01\">\n        <ego_vehicle x=\"107\" y=\"133.5\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/ChangingWeather.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T12:00:00\" description=\"CARLA:ChangingWeatherExample\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n          <Property name=\"color\" value=\"0,0,255\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"true\" dateTime=\"2020-01-01T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <LanePosition roadId=\"4\" laneId=\"-1\" offset=\"1.0\" s=\"48.58\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"ManeuverSequence\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\"/>\n          <Maneuver name=\"WeatherChange\">\n            <Event name=\"WeatherChangeEvent\" priority=\"overwrite\">\n              <Action name=\"WeatherChangeAction\">\n                <GlobalAction>\n                  <EnvironmentAction>\n                    <Environment name=\"Environment1\">\n                      <TimeOfDay animation=\"true\" dateTime=\"2020-01-01T22:00:00\"/>\n                      <Weather cloudState=\"free\">\n                        <Sun intensity=\"0.05\" azimuth=\"0\" elevation=\"1.31\"/>\n                        <Fog visualRange=\"100000.0\"/>\n                        <Precipitation precipitationType=\"rain\" intensity=\"0.9\"/>\n                      </Weather>\n                      <RoadCondition frictionScaleFactor=\"1.0\"/>\n                    </Environment>\n                  </EnvironmentAction>\n                </GlobalAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"WeatherChangeStartTime\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"20\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n          <Maneuver name=\"DummyManeuver\">\n            <Event name=\"DummyManeuver\" priority=\"overwrite\">\n              <Action name=\"DummyManeuver\"/>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"DummyManeuverStartTime\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"10000000\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"5\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger/>\n      </Act>\n    </Story>\n    <StopTrigger/>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/ControlLoss.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"ControlLoss_1\" type=\"ControlLoss\" town=\"Town01\">\n        <ego_vehicle x=\"392.5\" y=\"195\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_2\" type=\"ControlLoss\" town=\"Town01\">\n        <ego_vehicle x=\"-2.0\" y=\"160\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_3\" type=\"ControlLoss\" town=\"Town01\">\n        <ego_vehicle x=\"168.9\" y=\"59.8\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_4\" type=\"ControlLoss\" town=\"Town02\">\n        <ego_vehicle x=\"27\" y=\"110\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_5\" type=\"ControlLoss\" town=\"Town02\">\n        <ego_vehicle x=\"54.8\" y=\"307.2\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_6\" type=\"ControlLoss\" town=\"Town02\">\n        <ego_vehicle x=\"57.4\" y=\"191.7\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_7\" type=\"ControlLoss\" town=\"Town03\">\n        <ego_vehicle x=\"15\" y=\"207.5\" z=\"2\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_8\" type=\"ControlLoss\" town=\"Town03\">\n        <ego_vehicle x=\"-74\" y=\"-12\" z=\"0.1\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_9\" type=\"ControlLoss\" town=\"Town03\">\n        <ego_vehicle x=\"-85.1\" y=\"-87.4\" z=\"0.3\" yaw=\"89\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_10\" type=\"ControlLoss\" town=\"Town04\">\n        <ego_vehicle x=\"218.4\" y=\"193\" z=\"0\" yaw=\"338\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_11\" type=\"ControlLoss\" town=\"Town04\">\n        <ego_vehicle x=\"-40.4\" y=\"-229.5\" z=\"0\" yaw=\"131\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_12\" type=\"ControlLoss\" town=\"Town04\">\n        <ego_vehicle x=\"-45\" y=\"37.2\" z=\"11\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_13\" type=\"ControlLoss\" town=\"Town05\">\n        <ego_vehicle x=\"90.9\" y=\"-66\" z=\"0\" yaw=\"67\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_14\" type=\"ControlLoss\" town=\"Town05\">\n        <ego_vehicle x=\"-54.7\" y=\"110.9\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ControlLoss_15\" type=\"ControlLoss\" town=\"Town05\">\n        <ego_vehicle x=\"119.1\" y=\"-142.7\" z=\"0.1\" yaw=\"-170\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/CutIn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <!-- scenario name MUST contain 'left' or 'right', defines whether car comes from left or right lane-->\n    <scenario name=\"CutInFrom_left_Lane\" type=\"CutIn\" town=\"Town04\">\n        <ego_vehicle x=\"284.4\" y=\"16.4\" z=\"2.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n\t    <other_actor x=\"324.2\" y=\"20.7\" z=\"-100\" yaw=\"180\" model=\"vehicle.tesla.model3\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n    <scenario name=\"CutInFrom_right_Lane\" type=\"CutIn\" town=\"Town04\">\n        <ego_vehicle x=\"284.4\" y=\"16.4\" z=\"2.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n\t    <other_actor x=\"336.6\" y=\"14.4\" z=\"-100\" yaw=\"180\" model=\"vehicle.tesla.model3\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/CyclistCrossing.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:CyclistCrossing\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.diamondback.century\" vehicleCategory=\"bicycle\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"130\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"95.5\" y=\"41\" z=\"0.2\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"AdversaryAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"vehicle_longitudinal_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"CyclistCrossingManeuver\">\n            <Event name=\"CyclistStartsWalking\" priority=\"overwrite\">\n              <Action name=\"CyclistStartsWalking\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"1.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"14.0\" freespace=\"false\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"CyclistStopsAndWaits\" priority=\"overwrite\">\n              <Action name=\"CyclistStopsAndWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterCyclistStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"CyclistStartsWalking\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"CyclistWalksAway\" priority=\"overwrite\">\n              <Action name=\"CyclistStartsWalkingAway\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"6.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterCyclistStopsAndWaits\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"CyclistStopsAndWaits\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"CyclistWaits\" priority=\"overwrite\">\n              <Action name=\"CyclistWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterCyclistStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"CyclistStartsWalkingAway\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"10.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/FollowLeadingVehicle.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"FollowLeadingVehicle_1\" type=\"FollowLeadingVehicle\" town=\"Town01\">\n        <ego_vehicle x=\"107\" y=\"133\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n        <weather cloudiness=\"0\" precipitation=\"0\" precipitation_deposits=\"0\" wind_intensity=\"0\" sun_azimuth_angle=\"0\" sun_altitude_angle=\"75\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_1\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town01\">\n        <ego_vehicle x=\"107\" y=\"133.5\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_2\" type=\"FollowLeadingVehicle\" town=\"Town01\">\n        <ego_vehicle x=\"105\" y=\"199.1\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_2\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town01\">\n        <ego_vehicle x=\"105\" y=\"199.1\" z=\"0.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_3\" type=\"FollowLeadingVehicle\" town=\"Town02\">\n        <ego_vehicle x=\"28.7\" y=\"302.5\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_3\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town02\">\n        <ego_vehicle x=\"28.7\" y=\"302.5\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_4\" type=\"FollowLeadingVehicle\" town=\"Town03\">\n        <ego_vehicle x=\"120\" y=\"193\" z=\"3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_4\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town03\">\n        <ego_vehicle x=\"150\" y=\"193.2\" z=\"3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_5\" type=\"FollowLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-326.2  \" y=\"435.8\" z=\"0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_5\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"-337  \" y=\"435.8\" z=\"5.5\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_6\" type=\"FollowLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"44.8\" y=\"-98.3\" z=\"0\" yaw=\"-18\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_6\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"44.8\" y=\"-98.3\" z=\"0\" yaw=\"-18\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_7\" type=\"FollowLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"178\" y=\"-395.8\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_7\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"178\" y=\"-395.8\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_8\" type=\"FollowLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"170.6\" y=\"-182\" z=\"0\" yaw=\"-136\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_8\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town05\">\n         <ego_vehicle x=\"170.6\" y=\"-182.0\" z=\"0\" yaw=\"-137\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_9\" type=\"FollowLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-150\" y=\"-190\" z=\"11\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_9\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town05\">\n        <ego_vehicle x=\"-150\" y=\"-190\" z=\"11\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_10\" type=\"FollowLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-141\" y=\"208.5\" z=\"9\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_10\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town05\">\n        <ego_vehicle x=\"-141\" y=\"208.5\" z=\"9\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicle_11\" type=\"FollowLeadingVehicle\" town=\"Town02\">\n        <ego_vehicle x=\"137\" y=\"105.3\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"FollowLeadingVehicleWithObstacle_11\" type=\"FollowLeadingVehicleWithObstacle\" town=\"Town02\">\n        <ego_vehicle x=\"137\" y=\"105.3\" z=\"0.4\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/FollowLeadingVehicle.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T12:00:00\" description=\"CARLA:FollowLeadingVehicle\" author=\"\"/>\n  <ParameterDeclarations>\n    <ParameterDeclaration name=\"leadingSpeed\" parameterType=\"double\" value=\"2.0\"/>\n  </ParameterDeclarations>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n          <Property name=\"color\" value=\"0,0,255\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n          <Property name=\"color\" value=\"255,0,0\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2020-03-20T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <RoadPosition roadId=\"4\" s=\"48.58\" t=\"2.75\"/>\n<!--                <LanePosition roadId=\"4\" laneId=\"-1\" offset=\"1.0\" s=\"48.58\"/>-->\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <RelativeRoadPosition entityRef=\"hero\" ds=\"50\" dt=\"-1.0\"/>\n<!--                <WorldPosition x=\"190\" y=\"133\" z=\"0\" h=\"0\"/>-->\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"ManeuverSequence\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"FollowLeadingVehicleManeuver\">\n            <Event name=\"LeadingVehicleKeepsVelocity\" priority=\"overwrite\">\n              <Action name=\"LeadingVehicleKeepsVelocity\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"20\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"$leadingSpeed\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartConditionLeadingVehicleKeepsVelocity\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n<!--                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"40.0\" freespace=\"false\" rule=\"lessThan\"/>-->\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"longitudinal\" value=\"40.0\" freespace=\"true\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"LeadingVehicleWaits\" priority=\"overwrite\">\n              <Action name=\"LeadingVehicleWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"AfterLeadingVehicleKeepsVelocity\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"LeadingVehicleKeepsVelocity\" state=\"endTransition\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"1.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"equalTo\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/FreeRide.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"FreeRide_1\" type=\"FreeRide\" town=\"Town01\">\n        <ego_vehicle x=\"312\" y=\"129\" z=\"0\" yaw=\"180\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"FreeRide_2\" type=\"FreeRide\" town=\"Town02\">\n        <ego_vehicle x=\"132\" y=\"215\" z=\"0\" yaw=\"90\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"FreeRide_3\" type=\"FreeRide\" town=\"Town03\">\n        <ego_vehicle x=\"207\" y=\"59\" z=\"0\" yaw=\"180\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"FreeRide_4\" type=\"FreeRide\" town=\"Town04\">\n        <ego_vehicle x=\"269\" y=\"-246\" z=\"0\" yaw=\"0\" model=\"vehicle.tesla.model3\" rolename=\"hero\"/>\n    </scenario>\n    <scenario name=\"MultiEgo_1\" type=\"FreeRide\" town=\"Town01\">\n        <ego_vehicle x=\"270\" y=\"129\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" rolename=\"hero\"/>\n        <ego_vehicle x=\"100\" y=\"133\" z=\"0\" yaw=\"0\" model=\"vehicle.tesla.model3\" rolename=\"hero2\"/>\n    </scenario>\n    <scenario name=\"MultiEgo_2\" type=\"FreeRide\" town=\"Town03\">\n        <ego_vehicle x=\"207\" y=\"59\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" rolename=\"hero\"/>\n        <ego_vehicle x=\"237\" y=\"-95.0754252474\" z=\"0\" yaw=\"90\" model=\"vehicle.tesla.model3\" rolename=\"hero2\"/>\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/HighwayCutIn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"HighwayCutIn_1\" type=\"HighwayCutIn\" town=\"Highway\">\n        <ego_vehicle x=\"-619.20\" y=\"1055.3\" z=\"0\" yaw=\"-120\" model=\"vehicle.lincoln.mkz_2017\" />\n        <other_actor x=\"-515.70\" y=\"1048.5\" z=\"0\" yaw=\"150\" model=\"vehicle.tesla.model3\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/IntersectionCollisionAvoidance.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:SynchronizeIntersectionEntry\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.audi.tt\" vehicleCategory=\"bicycle\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"140\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"92.5\" y=\"91\" z=\"0.2\" h=\"-1.56\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"AdversaryAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"npc_vehicle_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"SynchronizeManeuver\">\n            <Event name=\"RouteCreation\" priority=\"overwrite\">\n              <Action name=\"RouteCreation\">\n                <PrivateAction>\n                  <RoutingAction>\n                    <AcquirePositionAction>\n                      <Position>\n                        <WorldPosition x=\"92\" y=\"13.5\" z=\"0\" h=\"0\"/>\n                      </Position>\n                    </AcquirePositionAction>\n                  </RoutingAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"0.1\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"ActorSynchronization\" priority=\"overwrite\">\n              <Action name=\"ActorSynchronization\">\n                <PrivateAction>\n                  <SynchronizeAction masterEntityRef=\"hero\">\n                    <TargetPositionMaster>\n                      <WorldPosition x=\"103\" y=\"55\" z=\"0\" h=\"3.14159\"/>\n                    </TargetPositionMaster>\n                    <TargetPosition>\n                      <WorldPosition x=\"92\" y=\"63.8\" z=\"0\" h=\"-1.56\"/>\n                    </TargetPosition>\n                    <FinalSpeed>\n                      <RelativeSpeedToMaster value='3' speedTargetValueType='delta'/>\n                    </FinalSpeed>\n                  </SynchronizeAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <SimulationTimeCondition value=\"0.1\" rule=\"greaterThan\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"0.1\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/LaneChangeSimple.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:LaneChangeSimple\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town04\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"standing\">\n      <Vehicle name=\"vehicle.volkswagen.t2\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"-9.4\" y=\"-152.8\" z=\"0.5\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"-9.4\" y=\"-71.0\" z=\"0.5\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"standing\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"-8.2\" y=\"29.2\" z=\"0.5\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"LaneChangeSimpleManeuver\">\n            <Event name=\"AdversaryAccelerates\" priority=\"overwrite\">\n              <Action name=\"AdversaryAccelerates\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"50\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"5.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"40.0\" freespace=\"false\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"AdversaryChangesLane\" priority=\"overwrite\">\n              <Action name=\"AdversaryChangesLane\">\n                <PrivateAction>\n                  <LateralAction>\n                    <LaneChangeAction>\n                      <LaneChangeActionDynamics dynamicsShape=\"linear\" value=\"25\" dynamicsDimension=\"distance\"/>\n                      <LaneChangeTarget>\n                        <RelativeTargetLane entityRef=\"adversary\" value=\"-1\"/>\n                      </LaneChangeTarget>\n                    </LaneChangeAction>\n                  </LateralAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"AfterAdversaryAccelerates\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"AdversaryAccelerates\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"1.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"equalTo\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/LeadingVehicle.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"OtherLeadingVehicle_1\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"388.9\" y=\"-140\" z=\"0\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_2\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-510\" y=\"88\" z=\"0\" yaw=\"91\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_3\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"82\" y=\"249.1\" z=\"0\" yaw=\"-33\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_4\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"138.9\" y=\"34.9\" z=\"10\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_5\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-110\" y=\"9.1\" z=\"9.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_6\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"-12.5\" y=\"-17\" z=\"0\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_7\" type=\"OtherLeadingVehicle\" town=\"Town04\">\n        <ego_vehicle x=\"125.5\" y=\"225.1\" z=\"0\" yaw=\"-25\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_8\" type=\"OtherLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-226.9\" y=\"100\" z=\"11\" yaw=\"-88\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_9\" type=\"OtherLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"-10\" y=\"191.1\" z=\"3\" yaw=\"-180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OtherLeadingVehicle_10\" type=\"OtherLeadingVehicle\" town=\"Town05\">\n        <ego_vehicle x=\"188.9\" y=\"-100\" z=\"0\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/NoSignalJunction.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"NoSignalJunctionCrossing\" type=\"NoSignalJunctionCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"-74.32\" y=\"-50\" z=\"0.5\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n        <other_actor x=\"-105\" y=\"-136\" z=\"0.5\" yaw=\"0\" model=\"vehicle.tesla.model3\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/ObjectCrossing.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"StationaryObjectCrossing_1\" type=\"StationaryObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"7.63\" y=\"109.91\" z=\"1.22\" yaw=\"359\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_1\" type=\"DynamicObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"7.63\" y=\"109.91\" z=\"1.22\" yaw=\"359\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_2\" type=\"StationaryObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"180.93\" y=\"105.31\" z=\"1.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_2\" type=\"DynamicObjectCrossing\" town=\"Town02\">\n        <ego_vehicle x=\"180.93\" y=\"105.31\" z=\"1.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_3\" type=\"StationaryObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"239.39\" y=\"113.42\" z=\"2.36\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_3\" type=\"DynamicObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"110\" y=\"129\" z=\"1\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_4\" type=\"StationaryObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"232.36\" y=\"113.29\" z=\"2.46\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_4\" type=\"DynamicObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"232.36\" y=\"113.29\" z=\"2.46\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_5\" type=\"StationaryObjectCrossing\" town=\"Town04\">\n        <ego_vehicle x=\"156.27\" y=\"18.7\" z=\"10.31\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_5\" type=\"DynamicObjectCrossing\" town=\"Town04\">\n        <ego_vehicle x=\"151.8\" y=\"17.7\" z=\"10.31\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_6\" type=\"StationaryObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"-150.70\" y=\"204.97\" z=\"9.65\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_6\" type=\"DynamicObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"-150.70\" y=\"204.97\" z=\"9.65\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_7\" type=\"StationaryObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"149.0\" y=\"-104.4\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_7\" type=\"DynamicObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"149.0\" y=\"-108.4\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"StationaryObjectCrossing_8\" type=\"StationaryObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"138.2\" y=\"116.4\" z=\"0.1\" yaw=\"130\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_8\" type=\"DynamicObjectCrossing\" town=\"Town05\">\n        <ego_vehicle x=\"138.2\" y=\"116.4\" z=\"0.1\" yaw=\"130\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"DynamicObjectCrossing_9\" type=\"DynamicObjectCrossing\" town=\"Town03\">\n        <ego_vehicle x=\"90\" y=\"129\" z=\"1\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ConstructionObstacle\" type=\"ConstructionObstacle\" town=\"Town02\">\n        <ego_vehicle x=\"7.63\" y=\"109.91\" z=\"1.22\" yaw=\"359\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/OppositeDirection.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"ManeuverOppositeDirection_1\" type=\"ManeuverOppositeDirection\" town=\"Town03\">\n        <ego_vehicle x=\"17\" y=\"136\" z=\"2\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ManeuverOppositeDirection_2\" type=\"ManeuverOppositeDirection\" town=\"Town04\">\n        <ego_vehicle x=\"63.3\" y=\"-190.3\" z=\"2\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ManeuverOppositeDirection_3\" type=\"ManeuverOppositeDirection\" town=\"Town04\">\n        <ego_vehicle x=\"192\" y=\"-311.5\" z=\"2\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"ManeuverOppositeDirection_4\" type=\"ManeuverOppositeDirection\" town=\"Town05\">\n        <ego_vehicle x=\"94\" y=\"144.7\" z=\"2\" yaw=\"-19\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/OscControllerExample.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T12:00:00\" description=\"CARLA:ControllerExample\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.lincoln.mkz_2017\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n          <Property name=\"color\" value=\"0,0,255\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n          <Property name=\"color\" value=\"255,0,0\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2020-03-20T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.85\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <LanePosition roadId=\"4\" laneId=\"-1\" offset=\"1.0\" s=\"48.58\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"190\" y=\"133\" z=\"0\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"AdversaryAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"npc_vehicle_control\"/>\n                    <Property name=\"an_unused_property\" value=\"an_unused_value\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n          <PrivateAction>\n            <LongitudinalAction>\n              <SpeedAction>\n                <SpeedActionDynamics dynamicsShape=\"step\" value=\"20\" dynamicsDimension=\"distance\"/>\n                <SpeedActionTarget>\n                  <AbsoluteTargetSpeed value=\"1\"/>\n                </SpeedActionTarget>\n              </SpeedAction>\n            </LongitudinalAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"ManeuverSequence\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"FollowLeadingVehicleManeuver\">\n            <Event name=\"LeadingVehicleKeepsVelocity\" priority=\"overwrite\">\n              <Action name=\"LeadingVehicleKeepsVelocity\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10000\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"10\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartConditionLeadingVehicleKeepsVelocity\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <RelativeDistanceCondition entityRef=\"adversary\" relativeDistanceType=\"cartesianDistance\" value=\"20.0\" freespace=\"false\" rule=\"lessThan\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"1.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n            <Condition name=\"StartTime\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"equalTo\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"20000.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger/>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/PedestrianCrossingFront.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-24T12:00:00\" description=\"CARLA:PedestrianCrossing\" author=\"\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.volkswagen.t2\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"adversary\">\n      <Pedestrian model=\"walker.pedestrian.0001\" mass=\"90.0\" name=\"walker.pedestrian.0001\" pedestrianCategory=\"pedestrian\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </Pedestrian>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.35\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"rain\" intensity=\"0.2\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"150\" y=\"55\" z=\"0\" h=\"3.14159265359\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"adversary\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"110\" y=\"52\" z=\"0.3\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup maximumExecutionCount=\"1\" name=\"ManeuverSequence\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"adversary\"/>\n          </Actors>\n          <Maneuver name=\"PedestrianCrossingManeuver\">\n            <Event name=\"PedestrianStartsWalking\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalking\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"1.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"10.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <ReachPositionCondition tolerance=\"2.0\">\n                          <Position>\n                            <WorldPosition x=\"140\" y=\"55\" z=\"0\" h=\"180\"/>\n                          </Position>\n                        </ReachPositionCondition>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianStopsAndWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianStopsAndWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"AfterPedestrianWalks\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalking\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWalksAway\" priority=\"overwrite\">\n              <Action name=\"PedestrianStartsWalkingAway\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"6.5\" dynamicsDimension=\"distance\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"2.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"hero\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStopsAndWaits\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStopsAndWaits\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n            <Event name=\"PedestrianWaits\" priority=\"overwrite\">\n              <Action name=\"PedestrianWaits\">\n                <PrivateAction>\n                  <LongitudinalAction>\n                    <SpeedAction>\n                      <SpeedActionDynamics dynamicsShape=\"step\" value=\"10\" dynamicsDimension=\"time\"/>\n                      <SpeedActionTarget>\n                        <AbsoluteTargetSpeed value=\"0.0\"/>\n                      </SpeedActionTarget>\n                    </SpeedAction>\n                  </LongitudinalAction>\n                </PrivateAction>\n              </Action>\n              <StartTrigger>\n                <ConditionGroup>\n                  <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByEntityCondition>\n                      <TriggeringEntities triggeringEntitiesRule=\"any\">\n                        <EntityRef entityRef=\"adversary\"/>\n                      </TriggeringEntities>\n                      <EntityCondition>\n                        <StandStillCondition duration=\"0.1\"/>\n                      </EntityCondition>\n                    </ByEntityCondition>\n                  </Condition>\n                  <Condition name=\"AfterPedestrianStartsWalking\" delay=\"0\" conditionEdge=\"rising\">\n                    <ByValueCondition>\n                      <StoryboardElementStateCondition storyboardElementType=\"action\" storyboardElementRef=\"PedestrianStartsWalkingAway\" state=\"completeState\"/>\n                    </ByValueCondition>\n                  </Condition>\n                </ConditionGroup>\n              </StartTrigger>\n            </Event>\n          </Maneuver>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"10.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByEntityCondition>\n                <TriggeringEntities triggeringEntitiesRule=\"any\">\n                  <EntityRef entityRef=\"hero\"/>\n                </TriggeringEntities>\n                <EntityCondition>\n                  <TraveledDistanceCondition value=\"200.0\"/>\n                </EntityCondition>\n              </ByEntityCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"100\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/RouteObstacles.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"Accident_1\" type=\"Accident\" town=\"Town04\">\n        <ego_vehicle x=\"30.39\" y=\"-285.92\" z=\"2.8\" yaw=\"-70\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"Construction_1\" type=\"ConstructionObstacle\" town=\"Town04\">\n        <ego_vehicle x=\"30.39\" y=\"-285.92\" z=\"2.8\" yaw=\"-70\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/RunningRedLight.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"OppositeVehicleRunningRedLight_1\" type=\"OppositeVehicleRunningRedLight\" town=\"Town03\">\n        <ego_vehicle x=\"-2.8\" y=\"-184\" z=\"1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_2\" type=\"OppositeVehicleRunningRedLight\" town=\"Town03\">\n        <ego_vehicle x=\"69\" y=\"130\" z=\"1\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_3\" type=\"OppositeVehicleRunningRedLight\" town=\"Town03\">\n        <ego_vehicle x=\"-48\" y=\"134.7\" z=\"1\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_4\" type=\"OppositeVehicleRunningRedLight\" town=\"Town04\">\n        <ego_vehicle x=\"274.1\" y=\"-246.2\" z=\"0.3\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"OppositeVehicleRunningRedLight_5\" type=\"OppositeVehicleRunningRedLight\" town=\"Town04\">\n        <ego_vehicle x=\"255\" y=\"-224.4\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/SignalizedJunctionLeftTurn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"SignalizedJunctionLeftTurn_1\" type=\"SignalizedJunctionLeftTurn\" town=\"Town03\">\n        <ego_vehicle x=\"-133.7\" y=\"137.4\" z=\"0.2\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n     </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_2\" type=\"SignalizedJunctionLeftTurn\" town=\"Town04\">\n        <ego_vehicle x=\"202.8\" y=\"-209.8\" z=\"0.3\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_3\" type=\"SignalizedJunctionLeftTurn\" town=\"Town04\">\n        <ego_vehicle x=\"274.1\" y=\"-246.2\" z=\"0.3\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_4\" type=\"SignalizedJunctionLeftTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-145.5\" y=\"-1\" z=\"0.3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_5\" type=\"SignalizedJunctionLeftTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-76.5\" y=\"-0.8\" z=\"0.3\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionLeftTurn_6\" type=\"SignalizedJunctionLeftTurn\" town=\"Town05\">\n        <ego_vehicle x=\"76.4\" y=\"83\" z=\"0.3\" yaw=\"157\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/SignalizedJunctionRightTurn.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"SignalizedJunctionRightTurn_1\" type=\"SignalizedJunctionRightTurn\" town=\"Town03\">\n        <ego_vehicle x=\"-2.8\" y=\"-182.8\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_2\" type=\"SignalizedJunctionRightTurn\" town=\"Town04\">\n        <ego_vehicle x=\"244.7\" y=\"-249.4\" z=\"0.5\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_3\" type=\"SignalizedJunctionRightTurn\" town=\"Town04\">\n        <ego_vehicle x=\"246\" y=\"-311\" z=\"0.1\" yaw=\"-179\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_4\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-54.9\" y=\"25.3\" z=\"0.1\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_5\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-25.7\" y=\"95\" z=\"0.0\" yaw=\"1\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_6\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"72.2\" y=\"-5.6\" z=\"0.0\" yaw=\"-180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"SignalizedJunctionRightTurn_7\" type=\"SignalizedJunctionRightTurn\" town=\"Town05\">\n        <ego_vehicle x=\"-170.3\" y=\"94.9\" z=\"0.0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/Slalom.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-07-30T12:00:00\" description=\"CARLA:Slalom\" author=\"Dimitri Scheftelowitsch\"/>\n  <ParameterDeclarations/>\n  <CatalogLocations/>\n  <RoadNetwork>\n    <LogicFile filepath=\"Town01\"/>\n    <SceneGraphFile filepath=\"\"/>\n  </RoadNetwork>\n  <Entities>\n    <ScenarioObject name=\"hero\">\n      <Vehicle name=\"vehicle.nissan.micra\" vehicleCategory=\"car\">\n        <ParameterDeclarations/>\n        <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n        <BoundingBox>\n          <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n          <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n        </BoundingBox>\n        <Axles>\n          <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n          <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n        </Axles>\n        <Properties>\n          <Property name=\"type\" value=\"ego_vehicle\"/>\n        </Properties>\n      </Vehicle>\n    </ScenarioObject>\n    <ScenarioObject name=\"c1\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n     <ScenarioObject name=\"c2\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n     <ScenarioObject name=\"c3\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n     <ScenarioObject name=\"c4\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n    <ScenarioObject name=\"c5\">\n      <MiscObject mass=\"500.0\" name=\"static.prop.container\" miscObjectCategory=\"obstacle\">\n        <ParameterDeclarations/>\n        <BoundingBox>\n          <Center x=\"-1.0\" y=\"0.0\" z=\"0.85\"/>\n          <Dimensions width=\"1.0\" length=\"2.0\" height=\"1.7\"/>\n        </BoundingBox>\n        <Properties>\n          <Property name=\"type\" value=\"simulation\"/>\n        </Properties>\n      </MiscObject>\n    </ScenarioObject>\n  </Entities>\n  <Storyboard>\n    <Init>\n      <Actions>\n        <GlobalAction>\n          <EnvironmentAction>\n            <Environment name=\"Environment1\">\n              <TimeOfDay animation=\"false\" dateTime=\"2019-06-25T12:00:00\"/>\n              <Weather cloudState=\"free\">\n                <Sun intensity=\"0.35\" azimuth=\"0\" elevation=\"1.31\"/>\n                <Fog visualRange=\"100000.0\"/>\n                <Precipitation precipitationType=\"rain\" intensity=\"0.2\"/>\n              </Weather>\n              <RoadCondition frictionScaleFactor=\"1.0\"/>\n            </Environment>\n          </EnvironmentAction>\n        </GlobalAction>\n        <Private entityRef=\"hero\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"92.44\" y=\"314\" z=\"0\" h=\"-1.5707963267948966\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n          <PrivateAction>\n            <ControllerAction>\n              <AssignControllerAction>\n                <Controller name=\"HeroAgent\">\n                  <Properties>\n                    <Property name=\"module\" value=\"external_control\"/>\n                  </Properties>\n                </Controller>\n              </AssignControllerAction>\n              <OverrideControllerValueAction>\n                <Throttle value=\"0\" active=\"false\"/>\n                <Brake value=\"0\" active=\"false\"/>\n                <Clutch value=\"0\" active=\"false\"/>\n                <ParkingBrake value=\"0\" active=\"false\"/>\n                <SteeringWheel value=\"0\" active=\"false\"/>\n                <Gear number=\"0\" active=\"false\"/>\n              </OverrideControllerValueAction>\n            </ControllerAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c1\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"90\" y=\"308\" z=\"0.0\" h=\"-1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c2\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"95\" y=\"298\" z=\"0.3\" h=\"1.57079632679\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c3\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"91\" y=\"288\" z=\"0.3\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c4\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"93\" y=\"278\" z=\"0.0\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n        <Private entityRef=\"c5\">\n          <PrivateAction>\n            <TeleportAction>\n              <Position>\n                <WorldPosition x=\"91\" y=\"268\" z=\"0.0\" h=\"0\"/>\n              </Position>\n            </TeleportAction>\n          </PrivateAction>\n        </Private>\n      </Actions>\n    </Init>\n    <Story name=\"MyStory\">\n      <Act name=\"Behavior\">\n        <ManeuverGroup name=\"NoManeuver\" maximumExecutionCount=\"1\">\n          <Actors selectTriggeringEntities=\"false\">\n            <EntityRef entityRef=\"hero\"/>\n          </Actors>\n        </ManeuverGroup>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"OverallStartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"120.0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n        <StopTrigger>\n          <ConditionGroup>\n            <Condition name=\"EndCondition\" delay=\"1\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"120.0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StopTrigger>\n      </Act>\n    </Story>\n    <StopTrigger>\n      <ConditionGroup>\n        <Condition name=\"criteria_RunningStopTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_RunningRedLightTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_WrongLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_OnSidewalkTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_KeepLaneTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_CollisionTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"\" value=\"\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n        <Condition name=\"criteria_DrivenDistanceTest\" delay=\"0\" conditionEdge=\"rising\">\n          <ByValueCondition>\n            <ParameterCondition parameterRef=\"distance_success\" value=\"70\" rule=\"lessThan\"/>\n          </ByValueCondition>\n        </Condition>\n      </ConditionGroup>\n    </StopTrigger>\n  </Storyboard>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/VehicleOpensDoor.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"VehicleOpensDoorTwoWays_1\" type=\"VehicleOpensDoorTwoWays\" town=\"Town10HD_Opt\">\n        <ego_vehicle x=\"-19.4\" y=\"69.5\" z=\"0.3\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n        <direction value=\"right\"/>\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/VehicleTurning.xml",
    "content": "<?xml version=\"1.0\"?>\n<scenarios>\n    <scenario name=\"VehicleTurningRight_1\" type=\"VehicleTurningRight\" town=\"Town01\">\n        <ego_vehicle x=\"130\" y=\"55\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_1\" type=\"VehicleTurningLeft\" town=\"Town01\">\n        <ego_vehicle x=\"130\" y=\"55\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n     <scenario name=\"VehicleTurningRight_2\" type=\"VehicleTurningRight\" town=\"Town01\">\n        <ego_vehicle x=\"132\" y=\"195.5\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_2\" type=\"VehicleTurningLeft\" town=\"Town01\">\n        <ego_vehicle x=\"132\" y=\"195.5\" z=\"0\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_3\" type=\"VehicleTurningRight\" town=\"Town01\">\n        <ego_vehicle x=\"282.5\" y=\"199.4\" z=\"0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_3\" type=\"VehicleTurningLeft\" town=\"Town01\">\n        <ego_vehicle x=\"282.5\" y=\"199.4\" z=\"0\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_4\" type=\"VehicleTurningRight\" town=\"Town02\">\n        <ego_vehicle x=\"30.1\" y=\"187.4\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_4\" type=\"VehicleTurningLeft\" town=\"Town02\">\n        <ego_vehicle x=\"30.1\" y=\"187.4\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_5\" type=\"VehicleTurningRight\" town=\"Town02\">\n        <ego_vehicle x=\"90\" y=\"237.1\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_5\" type=\"VehicleTurningLeft\" town=\"Town02\">\n        <ego_vehicle x=\"87.5\" y=\"237.1\" z=\"0.22\" yaw=\"180\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_6\" type=\"VehicleTurningRight\" town=\"Town02\">\n        <ego_vehicle x=\"146.2\" y=\"191.7\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_6\" type=\"VehicleTurningLeft\" town=\"Town02\">\n        <ego_vehicle x=\"146.2\" y=\"191.7\" z=\"0.22\" yaw=\"0\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_7\" type=\"VehicleTurningRight\" town=\"Town03\">\n        <ego_vehicle x=\"-74.32\" y=\"-50\" z=\"0.5\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_7\" type=\"VehicleTurningLeft\" town=\"Town03\">\n        <ego_vehicle x=\"-74.32\" y=\"-50\" z=\"0.5\" yaw=\"270\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningRight_8\" type=\"VehicleTurningRight\" town=\"Town04\">\n        <ego_vehicle x=\"255.2\" y=\"-300.4\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n    <scenario name=\"VehicleTurningLeft_8\" type=\"VehicleTurningLeft\" town=\"Town04\">\n        <ego_vehicle x=\"255.2\" y=\"-300.4\" z=\"0.5\" yaw=\"90\" model=\"vehicle.lincoln.mkz_2017\" />\n    </scenario>\n</scenarios>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/catalogs/ControllerCatalog.xosc",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"1\" revMinor=\"0\" date=\"2020-03-20T00:00:00\" description=\"CARLA:ControllerCatalog\" author=\"\" />\n  <Catalog name=\"ControllerCatalog\">\n    <Controller name=\"ExternalControl\">\n      <Properties>\n        <Property name=\"module\" value=\"external_control\" />\n      </Properties>\n    </Controller>\n  </Catalog>\n</OpenSCENARIO>"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/catalogs/EnvironmentCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-20\" description=\"CARLA:EnvironmentCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"EnvironmentCatalog\">\n    <Environment name=\"ClearNoon\">\n      <TimeOfDay animation=\"false\" dateTime=\"2020-01-01T12:00:00\"/>\n      <Weather cloudState=\"free\">\n        <Sun intensity=\"1.0\" azimuth=\"0.0\" elevation=\"1.5\"/>\n        <Fog visualRange=\"10000.0\"/>\n        <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n      </Weather>\n      <RoadCondition frictionScaleFactor=\"1.0\"/>\n    </Environment>\n    <Environment name=\"ClearMidnight\">\n      <TimeOfDay animation=\"false\" dateTime=\"2020-01-01T00:00:00\"/>\n      <Weather cloudState=\"free\">\n        <Sun intensity=\"1.0\" azimuth=\"0.26\" elevation=\"-1.1\"/>\n        <Fog visualRange=\"10000.0\"/>\n        <Precipitation precipitationType=\"dry\" intensity=\"0.0\"/>\n      </Weather>\n      <RoadCondition frictionScaleFactor=\"1.0\"/>\n    </Environment>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/catalogs/ManeuverCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-21\" description=\"CARLA:ManeuverCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"ManeuverCatalog\">\n    <Maneuver name=\"Autopilot\">\n      <Event name=\"StartAutopilot\" priority=\"overwrite\">\n        <Action name=\"StartAutopilot\">\n          <PrivateAction>\n            <ActivateControllerAction longitudinal=\"true\"/>\n          </PrivateAction>\n        </Action>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"0\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n      </Event>\n      <Event name=\"StopAutopilot\" priority=\"overwrite\">\n        <Action name=\"StopAutopilot\">\n          <PrivateAction>\n            <ActivateControllerAction longitudinal=\"false\"/>\n          </PrivateAction>\n        </Action>\n        <StartTrigger>\n          <ConditionGroup>\n            <Condition name=\"StartCondition\" delay=\"0\" conditionEdge=\"rising\">\n              <ByValueCondition>\n                <SimulationTimeCondition value=\"20\" rule=\"greaterThan\"/>\n              </ByValueCondition>\n            </Condition>\n          </ConditionGroup>\n        </StartTrigger>\n      </Event>\n    </Maneuver>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/catalogs/MiscObjectCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-25\" description=\"CARLA:MiscObjectCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"MiscObjectCatalog\">\n    <MiscObject miscObjectCategory=\"barrier\" mass=\"0.0\" name=\"Barrier1\">\n      <ParameterDeclarations/>\n      <BoundingBox>\n        <Center x=\"0.0\" y=\"0.0\" z=\"0.0\"/>\n        <Dimensions width=\"0.0\" length=\"0.0\" height=\"0.0\"/>\n      </BoundingBox>\n      <Properties/>\n    </MiscObject>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/catalogs/PedestrianCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-20\" description=\"CARLA:PedestrianCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"PedestrianCatalog\">\n    <Pedestrian model=\"walker.pedestrian.0001\" mass=\"0.0\" name=\"Pedestrian1\" pedestrianCategory=\"pedestrian\">\n      <BoundingBox>\n        <Center x=\"0.0\" y=\"0.0\" z=\"0.0\"/>\n        <Dimensions width=\"0.0\" length=\"0.0\" height=\"0.0\"/>\n      </BoundingBox>\n      <Properties/>\n    </Pedestrian>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/examples/catalogs/VehicleCatalog.xosc",
    "content": "<?xml version=\"1.0\"?>\n<OpenSCENARIO>\n  <FileHeader revMajor=\"0\" revMinor=\"9\" date=\"2020-02-17\" description=\"CARLA:VehicleCatalog\" author=\"Anja Sheppard\"/>\n  <Catalog name=\"VehicleCatalog\">\n    <Vehicle name=\"vehicle.volkswagen.t2\" vehicleCategory=\"car\">\n      <ParameterDeclarations/>\n      <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n      <BoundingBox>\n        <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n        <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n      </BoundingBox>\n      <Axles>\n        <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n        <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n      </Axles>\n      <Properties>\n        <Property name=\"type\" value=\"ego_vehicle\"/>\n      </Properties>\n    </Vehicle>\n    <Vehicle name=\"vehicle.tesla.model3\" vehicleCategory=\"car\">\n      <ParameterDeclarations>\n        <ParameterDeclaration name=\"carcolor\" parameterType=\"string\" value=\"0,0,0\" />\n      </ParameterDeclarations>\n      <Performance maxSpeed=\"69.444\" maxAcceleration=\"200\" maxDeceleration=\"10.0\"/>\n      <BoundingBox>\n        <Center x=\"1.5\" y=\"0.0\" z=\"0.9\"/>\n        <Dimensions width=\"2.1\" length=\"4.5\" height=\"1.8\"/>\n      </BoundingBox>\n      <Axles>\n        <FrontAxle maxSteering=\"0.5\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"3.1\" positionZ=\"0.3\"/>\n        <RearAxle maxSteering=\"0.0\" wheelDiameter=\"0.6\" trackWidth=\"1.8\" positionX=\"0.0\" positionZ=\"0.3\"/>\n      </Axles>\n      <Properties>\n        <Property name=\"color\" value=\"$carcolor\"/>\n      </Properties>\n    </Vehicle>\n  </Catalog>\n</OpenSCENARIO>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/metrics/examples/basic_metric.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provide BasicMetric, the basic class of all the metrics.\n\"\"\"\n\nclass BasicMetric(object):\n    \"\"\"\n    Base class of all the metrics.\n    \"\"\"\n\n    def __init__(self, town_map, log, criteria=None):\n        \"\"\"\n        Initialization of the metric class. This calls the metrics log and creates the metrics\n\n        Args:\n            town_map (carla.Map): Map of the simulation. Used to access the Waypoint API.\n            log (srunner.metrics.tools.Metricslog): instance of a class used to access the recorder information\n            criteria (dict): list of dictionaries with all the criteria information\n        \"\"\"\n\n        # Create the metrics of the simulation. This part is left to the user\n        self._create_metric(town_map, log, criteria)\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Pure virtual function to setup the metrics by the user.\n\n        Args:\n            town_map (carla.Map): Map of the simulation. Used to access the Waypoint API.\n            log (srunner.metrics.tools.Metricslog): instance of a class used to access the recorder information\n            criteria (dict): dictionaries with all the criteria information\n        \"\"\"\n        raise NotImplementedError(\n            \"This function should be re-implemented by all metrics\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/metrics/examples/criteria_filter.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis metric filters the useful information of the criteria (sucess / fail ...),\nand dump it into a json file\n\nIt is meant to serve as an example of how to use the criteria\n\"\"\"\n\nimport json\n\nfrom srunner.metrics.examples.basic_metric import BasicMetric\n\n\nclass CriteriaFilter(BasicMetric):\n    \"\"\"\n    Metric class CriteriaFilter\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric. This is an example to show how to use the criteria\n        \"\"\"\n\n        ### Parse the criteria information, filtering only the useful information, and dump it into a json ###\n\n        results = {}\n        for criterion_name in criteria:\n            criterion = criteria[criterion_name]\n            results.update({criterion_name:\n                {\n                    \"test_status\": criterion[\"test_status\"],\n                    \"actual_value\": criterion[\"actual_value\"],\n                    \"success_value\": criterion[\"success_value\"]\n                }\n            }\n        )\n\n        with open('srunner/metrics/data/CriteriaFilter_results.json', 'w') as fw:\n            json.dump(results, fw, sort_keys=False, indent=4)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/metrics/examples/distance_between_vehicles.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis metric calculates the distance between the ego vehicle and\nanother actor, dumping it to a json file.\n\nIt is meant to serve as an example of how to use the information from\nthe recorder\n\"\"\"\n\nimport math\nimport matplotlib.pyplot as plt\n\nfrom srunner.metrics.examples.basic_metric import BasicMetric\n\n\nclass DistanceBetweenVehicles(BasicMetric):\n    \"\"\"\n    Metric class DistanceBetweenVehicles\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric. This is an example to show how to use the recorder,\n        accessed via the log.\n        \"\"\"\n\n        # Get the ID of the two vehicles\n        ego_id = log.get_ego_vehicle_id()\n        adv_id = log.get_actor_ids_with_role_name(\"scenario\")[0]  # Could have also used its type_id\n\n        dist_list = []\n        frames_list = []\n\n        # Get the frames both actors were alive\n        start_ego, end_ego = log.get_actor_alive_frames(ego_id)\n        start_adv, end_adv = log.get_actor_alive_frames(adv_id)\n        start = max(start_ego, start_adv)\n        end = min(end_ego, end_adv)\n\n        # Get the distance between the two\n        for i in range(start, end):\n\n            # Get the transforms\n            ego_location = log.get_actor_transform(ego_id, i).location\n            adv_location = log.get_actor_transform(adv_id, i).location\n\n            # Filter some points for a better graph\n            if adv_location.z < -10:\n                continue\n\n            dist_v = ego_location - adv_location\n            dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n            dist_list.append(dist)\n            frames_list.append(i)\n\n        # Use matplotlib to show the results\n        plt.plot(frames_list, dist_list)\n        plt.ylabel('Distance [m]')\n        plt.xlabel('Frame number')\n        plt.title('Distance between the ego vehicle and the adversary over time')\n        plt.show()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/metrics/examples/distance_to_lane_center.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis metric calculates the distance between the ego vehicle and\nthe center of the lane, dumping it to a json file.\n\nIt is meant to serve as an example of how to use the map API\n\"\"\"\n\nimport math\nimport json\n\nfrom srunner.metrics.examples.basic_metric import BasicMetric\n\n\nclass DistanceToLaneCenter(BasicMetric):\n    \"\"\"\n    Metric class DistanceToLaneCenter\n    \"\"\"\n\n    def _create_metric(self, town_map, log, criteria):\n        \"\"\"\n        Implementation of the metric.\n        \"\"\"\n\n        # Get ego vehicle id\n        ego_id = log.get_ego_vehicle_id()\n\n        dist_list = []\n        frames_list = []\n\n        # Get the frames the ego actor was alive and its transforms\n        start, end = log.get_actor_alive_frames(ego_id)\n\n        # Get the projected distance vector to the center of the lane\n        for i in range(start, end + 1):\n\n            ego_location = log.get_actor_transform(ego_id, i).location\n            ego_waypoint = town_map.get_waypoint(ego_location)\n\n            # Get the distance vector and project it\n            a = ego_location - ego_waypoint.transform.location      # Ego to waypoint vector\n            b = ego_waypoint.transform.get_right_vector()           # Waypoint perpendicular vector\n            b_norm = math.sqrt(b.x * b.x + b.y * b.y + b.z * b.z)\n\n            ab_dot = a.x * b.x + a.y * b.y + a.z * b.z\n            dist_v = ab_dot/(b_norm*b_norm)*b\n            dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z)\n\n            # Get the sign of the distance (left side is positive)\n            c = ego_waypoint.transform.get_forward_vector()         # Waypoint forward vector\n            ac_cross = c.x * a.y - c.y * a.x\n            if ac_cross < 0:\n                dist *= -1\n\n            dist_list.append(dist)\n            frames_list.append(i)\n\n        # Save the results to a file\n        results = {'frames': frames_list, 'distance': dist_list}\n        with open('srunner/metrics/data/DistanceToLaneCenter_results.json', 'w') as fw:\n            json.dump(results, fw, sort_keys=False, indent=4)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/metrics/tools/metrics_log.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSupport class of the MetricsManager to query the information available\nto the metrics.\n\nIt also provides a series of functions to help the user querry\nspecific information\n\"\"\"\n\nimport fnmatch\nfrom srunner.metrics.tools.metrics_parser import MetricsParser\n\nclass MetricsLog(object):  # pylint: disable=too-many-public-methods\n    \"\"\"\n    Utility class to query the log.\n    \"\"\"\n\n    def __init__(self, recorder):\n        \"\"\"\n        Initializes the log class and parses it to extract the dictionaries.\n        \"\"\"\n        # Parse the information\n        parser = MetricsParser(recorder)\n        self._simulation, self._actors, self._frames = parser.parse_recorder_info()\n\n    ### Functions used to get general info of the simulation ###\n    def get_actor_collisions(self, actor_id):\n        \"\"\"\n        Returns a dict where the keys are the frame number and the values,\n        a list of actor ids the actor collided with.\n\n        Args:\n            actor_id (int): ID of the actor.\n        \"\"\"\n        actor_collisions = {}\n\n        for i, frame in enumerate(self._frames):\n            collisions = frame[\"events\"][\"collisions\"]\n\n            if actor_id in collisions:\n                actor_collisions.update({i: collisions[actor_id]})\n\n        return actor_collisions\n\n    def get_total_frame_count(self):\n        \"\"\"\n        Returns an int with the total amount of frames the simulation lasted.\n        \"\"\"\n\n        return self._simulation[\"total_frames\"]\n\n    def get_elapsed_time(self, frame):\n        \"\"\"\n        Returns a float with the elapsed time of a specific frame.\n        \"\"\"\n\n        return self._frames[frame][\"frame\"][\"elapsed_time\"]\n\n    def get_delta_time(self, frame):\n        \"\"\"\n        Returns a float with the delta time of a specific frame.\n        \"\"\"\n\n        return self._frames[frame][\"frame\"][\"delta_time\"]\n\n    def get_platform_time(self, frame):\n        \"\"\"\n        Returns a float with the platform time time of a specific frame.\n        \"\"\"\n\n        return self._frames[frame][\"frame\"][\"platform_time\"]\n\n    ### Functions used to get info about the actors ###\n    def get_ego_vehicle_id(self):\n        \"\"\"\n        Returns the id of the ego vehicle.\n        \"\"\"\n        return self.get_actor_ids_with_role_name(\"hero\")[0]\n\n    def get_actor_ids_with_role_name(self, role_name):\n        \"\"\"\n        Returns a list of actor ids that match the given role_name.\n\n        Args:\n            role_name (str): string with the desired role_name to filter the actors.\n        \"\"\"\n        actor_list = []\n\n        for actor_id in self._actors:\n            actor = self._actors[actor_id]\n            if \"role_name\" in actor and actor[\"role_name\"] == role_name:\n                actor_list.append(actor_id)\n\n        return actor_list\n\n    def get_actor_ids_with_type_id(self, type_id):\n        \"\"\"\n        Returns a list of actor ids that match the given type_id, matching fnmatch standard.\n\n        Args:\n            type_id (str): string with the desired type id to filter the actors.\n        \"\"\"\n        actor_list = []\n\n        for actor_id in self._actors:\n            actor = self._actors[actor_id]\n            if \"type_id\" in actor and fnmatch.fnmatch(actor[\"type_id\"], type_id):\n                actor_list.append(actor_id)\n\n        return actor_list\n\n    def get_actor_attributes(self, actor_id):\n        \"\"\"\n        Returns a dictionary with all the attributes of an actor.\n\n        Args:\n            actor_id (int): ID of the actor.\n        \"\"\"\n        if actor_id in self._actors:\n            return self._actors[actor_id]\n\n        return None\n\n    def get_actor_bounding_box(self, actor_id):\n        \"\"\"\n        Returns the bounding box of the specified actor\n\n        Args:\n            actor_id (int): Id of the actor\n        \"\"\"\n\n        if actor_id in self._actors:\n            if \"bounding_box\" in self._actors[actor_id]:\n                return self._actors[actor_id][\"bounding_box\"]\n            return None\n\n        return None\n\n    def get_traffic_light_trigger_volume(self, traffic_light_id):\n        \"\"\"\n        Returns the trigger volume of the specified traffic light\n\n        Args:\n            actor_id (int): Id of the traffic light\n        \"\"\"\n\n        if traffic_light_id in self._actors:\n            if \"trigger_volume\" in self._actors[traffic_light_id]:\n                return self._actors[traffic_light_id][\"trigger_volume\"]\n            return None\n\n        return None\n\n    def get_actor_alive_frames(self, actor_id):\n        \"\"\"\n        Returns a tuple with the first and last frame an actor was alive.\n        It is important to note that frames start at 1, not 0.\n\n        Args:\n            actor_id (int): Id of the actor\n        \"\"\"\n\n        if actor_id in self._actors:\n\n            actor_info = self._actors[actor_id]\n            first_frame = actor_info[\"created\"]\n            if \"destroyed\" in actor_info:\n                last_frame = actor_info[\"destroyed\"] - 1\n            else:\n                last_frame = self.get_total_frame_count()\n\n            return first_frame, last_frame\n\n        return None, None\n\n    ### Functions used to get the actor states ###\n    def _get_actor_state(self, actor_id, state, frame):\n        \"\"\"\n        Given an actor id, returns the specific variable of that actor at a given frame.\n        Returns None if the actor_id or the state are missing.\n\n        Args:\n            actor_id (int): Id of the actor to be checked.\n            frame: (int): frame number of the simulation.\n            attribute (str): name of the actor's attribute to be returned.\n        \"\"\"\n        frame_state = self._frames[frame - 1][\"actors\"]\n\n        # Check if the actor exists\n        if actor_id in frame_state:\n\n            # Check if the state exists\n            if state not in frame_state[actor_id]:\n                return None\n\n            state_info = frame_state[actor_id][state]\n            return state_info\n\n        return None\n\n    def _get_all_actor_states(self, actor_id, state, first_frame=None, last_frame=None):\n        \"\"\"\n        Given an actor id, returns a list of the specific variable of that actor during\n        a frame interval. Some elements might be None.\n\n        By default, first_frame and last_frame are the start and end of the simulation, respectively.\n\n        Args:\n            actor_id (int): ID of the actor.\n            attribute: name of the actor's attribute to be returned.\n            first_frame (int): First frame checked. By default, 0.\n            last_frame (int): Last frame checked. By default, max number of frames.\n        \"\"\"\n        if first_frame is None:\n            first_frame = 1\n        if last_frame is None:\n            last_frame = self.get_total_frame_count()\n\n        state_list = []\n\n        for frame_number in range(first_frame, last_frame + 1):\n            state_info = self._get_actor_state(actor_id, state, frame_number)\n            state_list.append(state_info)\n\n        return state_list\n\n    def _get_states_at_frame(self, frame, state, actor_list=None):\n        \"\"\"\n        Returns a dict where the keys are the frame number, and the values are the\n        carla.Transform of the actor at the given frame.\n\n        By default, all actors will be considered.\n        \"\"\"\n        states = {}\n        actor_info = self._frames[frame][\"actors\"]\n\n        for actor_id in actor_info:\n            if not actor_list:\n                _state = self._get_actor_state(actor_id, state, frame)\n                if _state:\n                    states.update({actor_id: _state})\n            elif actor_id in actor_list:\n                _state = self._get_actor_state(actor_id, state, frame)\n                states.update({actor_id: _state})\n\n        return states\n\n    # Transforms\n    def get_actor_transform(self, actor_id, frame):\n        \"\"\"\n        Returns the transform of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"transform\", frame)\n\n    def get_all_actor_transforms(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the transforms of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"transform\", first_frame, last_frame)\n\n    def get_actor_transforms_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Transform} with the actor ID and transform\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"transform\", actor_list)\n\n    # Velocities\n    def get_actor_velocity(self, actor_id, frame):\n        \"\"\"\n        Returns the velocity of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"velocity\", frame)\n\n    def get_all_actor_velocities(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the velocities of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"velocity\", first_frame, last_frame)\n\n    def get_actor_velocities_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Vector3D} with the actor ID and velocity\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"velocity\", actor_list)\n\n    # Angular velocities\n    def get_actor_angular_velocity(self, actor_id, frame):\n        \"\"\"\n        Returns the angular velocity of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"angular_velocity\", frame)\n\n    def get_all_actor_angular_velocities(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the angular velocities of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"angular_velocity\", first_frame, last_frame)\n\n    def get_actor_angular_velocities_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Vector3D} with the actor ID and angular velocity\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"angular_velocity\", actor_list)\n\n    # Acceleration\n    def get_actor_acceleration(self, actor_id, frame):\n        \"\"\"\n        Returns the acceleration of the actor at a given frame.\n        \"\"\"\n        return self._get_actor_state(actor_id, \"acceleration\", frame)\n\n    def get_all_actor_accelerations(self, actor_id, first_frame=None, last_frame=None):\n        \"\"\"\n        Returns a list with all the accelerations of the actor at the frame interval.\n        \"\"\"\n        return self._get_all_actor_states(actor_id, \"acceleration\", first_frame, last_frame)\n\n    def get_actor_accelerations_at_frame(self, frame, actor_list=None):\n        \"\"\"\n        Returns a dictionary {int - carla.Vector3D} with the actor ID and angular velocity\n        at a given frame of all the actors at actor_list.\n        \"\"\"\n        return self._get_states_at_frame(frame, \"acceleration\", actor_list)\n\n    # Controls\n    def get_vehicle_control(self, vehicle_id, frame):\n        \"\"\"\n        Returns the control of the vehicle at a given frame.\n        \"\"\"\n        return self._get_actor_state(vehicle_id, \"control\", frame)\n\n    def get_vehicle_physics_control(self, vehicle_id, frame):\n        \"\"\"\n        Returns the carla.VehiclePhysicsControl of a vehicle at a given frame.\n        Returns None if the id can't be found.\n        \"\"\"\n\n        for i in range(frame - 1, -1, -1):  # Go backwards from the frame until 0\n            physics_info = self._frames[i][\"events\"][\"physics_control\"]\n\n            if vehicle_id in physics_info:\n                return physics_info[vehicle_id]\n\n        return None\n\n    def get_walker_speed(self, walker_id, frame):\n        \"\"\"\n        Returns the speed of the walker at a specific frame.\n        \"\"\"\n        return self._get_actor_state(walker_id, \"speed\", frame)\n\n    # Traffic lights\n    def get_traffic_light_state(self, traffic_light_id, frame):\n        \"\"\"\n        Returns the state of the traffic light at a specific frame.\n        \"\"\"\n        return self._get_actor_state(traffic_light_id, \"state\", frame)\n\n    def is_traffic_light_frozen(self, traffic_light_id, frame):\n        \"\"\"\n        Returns whether or not the traffic light is frozen at a specific frame.\n        \"\"\"\n        return self._get_actor_state(traffic_light_id, \"frozen\", frame)\n\n    def get_traffic_light_elapsed_time(self, traffic_light_id, frame):\n        \"\"\"\n        Returns the elapsed time of the traffic light at a specific frame.\n        \"\"\"\n        return self._get_actor_state(traffic_light_id, \"elapsed_time\", frame)\n\n    def get_traffic_light_state_time(self, traffic_light_id, state, frame):\n        \"\"\"\n        Returns the state time of the traffic light at a specific frame.\n        Returns None if the id can't be found.\n        \"\"\"\n\n        for i in range(frame - 1, -1, -1):  # Go backwards from the frame until 0\n            state_times_info = self._frames[i][\"events\"][\"traffic_light_state_time\"]\n\n            if traffic_light_id in state_times_info:\n                states = state_times_info[traffic_light_id]\n                if state in states:\n                    return state_times_info[traffic_light_id][state]\n\n        return None\n\n    # Vehicle lights\n    def get_vehicle_lights(self, vehicle_id, frame):\n        \"\"\"\n        Returns the vehicle lights of the vehicle at a specific frame.\n        \"\"\"\n        return self._get_actor_state(vehicle_id, \"lights\", frame)\n\n    def is_vehicle_light_active(self, light, vehicle_id, frame):\n        \"\"\"\n        Returns the elapsed time of the traffic light at a specific frame.\n        \"\"\"\n        lights = self.get_vehicle_lights(vehicle_id, frame)\n\n        if light in lights:\n            return True\n\n        return False\n\n    # Scene lights\n    def get_scene_light_state(self, light_id, frame):\n        \"\"\"\n        Returns the state of the scene light at a specific frame.\n        Returns None if the id can't be found.\n        \"\"\"\n\n        for i in range(frame - 1, -1, -1):  # Go backwards from the frame until 0\n            scene_lights_info = self._frames[i][\"events\"][\"scene_lights\"]\n\n            if light_id in scene_lights_info:\n                return scene_lights_info[light_id]\n\n        return None\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/metrics/tools/metrics_parser.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de\n# Barcelona (UAB).\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSupport class of the MetricsManager to parse the information of\nthe CARLA recorder into a readable dictionary\n\"\"\"\n\nimport carla\n\n\ndef parse_actor(info):\n    \"\"\"Returns a dictionary with the basic actor information\"\"\"\n    actor = {\n        \"type_id\": info[2],\n        \"location\": carla.Location(\n            x=float(info[5][1:-1]) / 100,\n            y=float(info[6][:-1]) / 100,\n            z=float(info[7][:-1]) / 100\n        )\n    }\n    return actor\n\ndef parse_transform(info):\n    \"\"\"Parses a list into a carla.Transform\"\"\"\n    transform = carla.Transform(\n        carla.Location(\n            x=float(info[3][1:-1]) / 100,\n            y=float(info[4][:-1]) / 100,\n            z=float(info[5][:-1]) / 100,\n        ),\n        carla.Rotation(\n            roll=float(info[7][1:-1]),\n            pitch=float(info[8][:-1]), \n            yaw=float(info[9][:-1])\n        )\n    )\n    return transform\n\ndef parse_control(info):\n    \"\"\"Parses a list into a carla.VehicleControl\"\"\"\n    control = carla.VehicleControl(\n        throttle=float(info[5]),\n        steer=float(info[3]),\n        brake=float(info[7]),\n        hand_brake=bool(int(info[9])),\n        reverse=int(info[11]) < 0,\n        manual_gear_shift=False,\n        gear=int(info[11]),\n    )\n    return control\n\ndef parse_vehicle_lights(info):\n    \"\"\"Parses a list into a carla.VehicleLightState\"\"\"\n    srt_to_vlight = {\n        \"None\": carla.VehicleLightState.NONE,\n        \"Position\": carla.VehicleLightState.Position,\n        \"LowBeam\": carla.VehicleLightState.LowBeam,\n        \"HighBeam\": carla.VehicleLightState.HighBeam,\n        \"Brake\": carla.VehicleLightState.Brake,\n        \"RightBlinker\": carla.VehicleLightState.RightBlinker,\n        \"LeftBlinker\": carla.VehicleLightState.LeftBlinker,\n        \"Reverse\": carla.VehicleLightState.Reverse,\n        \"Fog\": carla.VehicleLightState.Fog,\n        \"Interior\": carla.VehicleLightState.Interior,\n        \"Special1\": carla.VehicleLightState.Special1,\n        \"Special2\": carla.VehicleLightState.Special2,\n    }\n\n    lights = []\n    for i in range(2, len(info)):\n        lights.append(srt_to_vlight[info[i]])\n\n    return lights\n\ndef parse_traffic_light(info):\n    \"\"\"Parses a list into a dictionary with all the traffic light's information\"\"\"\n    number_to_state = {\n        \"0\": carla.TrafficLightState.Red,\n        \"1\": carla.TrafficLightState.Yellow,\n        \"2\": carla.TrafficLightState.Green,\n        \"3\": carla.TrafficLightState.Off,\n        \"4\": carla.TrafficLightState.Unknown,\n    }\n    traffic_light = {\n        \"state\": number_to_state[info[3]],\n        \"frozen\": bool(int(info[5])),\n        \"elapsed_time\": float(info[7]),\n    }\n    return traffic_light\n\ndef parse_velocity(info):\n    \"\"\"Parses a list into a carla.Vector3D with the velocity\"\"\"\n    velocity = carla.Vector3D(\n        x=float(info[3][1:-1]),\n        y=float(info[4][:-1]),\n        z=float(info[5][:-1])\n    )\n    return velocity\n\ndef parse_angular_velocity(info):\n    \"\"\"Parses a list into a carla.Vector3D with the angular velocity\"\"\"\n    velocity = carla.Vector3D(\n        x=float(info[7][1:-1]),\n        y=float(info[8][:-1]),\n        z=float(info[9][:-1])\n    )\n    return velocity\n\ndef parse_scene_lights(info):\n    \"\"\"Parses a list into a carla.VehicleLightState\"\"\"\n\n    red = int(float(info[7][1:-1]) * 255)\n    green = int(float(info[8][:-1]) * 255)\n    blue = int(float(info[9][:-1]) * 255)\n\n    scene_light = carla.LightState(\n        intensity=int(float(info[5])),\n        color=carla.Color(red, green, blue),\n        group=carla.LightGroup.NONE,\n        active=bool(info[3])\n    )\n    return scene_light\n\ndef parse_bounding_box(info):\n    \"\"\"\n    Parses a list into a carla.BoundingBox.\n    Some actors like sensors might have 'nan' location and 'inf' extent, so filter those.\n    \"\"\"\n    if 'nan' in info[3]:\n        location = carla.Location()\n    else:\n        location = carla.Location(\n            float(info[3][1:-1])/100,\n            float(info[4][:-1])/100,\n            float(info[5][:-1])/100,\n        )\n\n    if 'inf' in info[7]:\n        extent = carla.Vector3D()\n    else:\n        extent = carla.Vector3D(\n            float(info[7][1:-1])/100,\n            float(info[8][:-1])/100,\n            float(info[9][:-1])/100,\n        )\n\n    bbox = carla.BoundingBox(location, extent)\n\n    return bbox\n\ndef parse_state_times(info):\n    \"\"\"Parses a list into a dict containing the state times of the traffic lights\"\"\"\n    state_times = {\n        carla.TrafficLightState.Green: float(info[3]),\n        carla.TrafficLightState.Yellow: float(info[5]),\n        carla.TrafficLightState.Red: float(info[7]),\n    }\n    return state_times\n\ndef parse_vector_list(info):\n    \"\"\"Parses a list of string into a list of Vector2D\"\"\"\n    vector_list = []\n    for i in range(0, len(info), 2):\n        vector = carla.Vector2D(\n            x=float(info[i][1:-1]),\n            y=float(info[i+1][:-1]),\n        )\n        vector_list.append(vector)\n\n    return vector_list\n\ndef parse_gears_control(info):\n    \"\"\"Parses a list into a GearPhysicsControl\"\"\"\n    gears_control = carla.GearPhysicsControl(\n        ratio=float(info[3]),\n        down_ratio=float(info[5]),\n        up_ratio=float(info[7]),\n    )\n    return gears_control\n\ndef parse_wheels_control(info):\n    \"\"\"Parses a list into a WheelsPhysicsControl\"\"\"\n    wheels_control = carla.WheelPhysicsControl(\n        tire_friction=float(info[3]),\n        damping_rate=float(info[5]),\n        max_steer_angle=float(info[7]),\n        radius=float(info[9]),\n        max_brake_torque=float(info[11]),\n        max_handbrake_torque=float(info[13]),\n        position=carla.Vector3D(\n            x=float(info[17][1:-1]) / 100,\n            y=float(info[17][:-1]) / 100,\n            z=float(info[17][:-1]) / 100)\n    )\n    return wheels_control\n\n\nclass MetricsParser(object):\n    \"\"\"\n    Class used to parse the CARLA recorder into readable information\n    \"\"\"\n\n    def __init__(self, recorder_info):\n\n        self.recorder_info = recorder_info\n        self.frame_list = None\n        self.frame_row = None\n        self.i = 0\n\n    def get_row_elements(self, indent_num, split_string):\n        \"\"\"\n        returns a list with the elements of the row\n        \"\"\"\n        return self.frame_row[indent_num:].split(split_string)\n\n    def next_row(self):\n        \"\"\"\n        Gets the next row of the recorder\n        \"\"\"\n        self.i += 1\n        self.frame_row = self.frame_list[self.i]\n\n    def parse_recorder_info(self):\n        \"\"\"\n        Parses the recorder into readable information.\n\n        Args:\n            recorder_info (str): string given by the recorder\n        \"\"\"\n\n        # Divide it into frames\n        recorder_list = self.recorder_info.split(\"Frame\")\n\n        # Get general information\n        header = recorder_list[0].split(\"\\n\")\n        sim_map = header[1][5:]\n        sim_date = header[2][6:]\n\n        annex = recorder_list[-1].split(\"\\n\")\n        sim_frames = int(annex[0][3:])\n        sim_duration = float(annex[1][10:-8])\n\n        recorder_list = recorder_list[1:-1]\n\n        simulation_info = {\n            \"map\": sim_map,\n            \"date:\": sim_date,\n            \"total_frames\": sim_frames,\n            \"duration\": sim_duration\n        }\n\n        actors_info = {}\n        frames_info = []\n\n        for frame in recorder_list:\n\n            # Divide the frame in lines\n            self.frame_list = frame.split(\"\\n\")\n\n            # Get the general frame information\n            frame_info = self.frame_list[0].split(\" \")\n            frame_number = int(frame_info[1])\n            frame_time = float(frame_info[3])\n\n            try:\n                prev_frame = frames_info[frame_number - 2]\n                prev_time = prev_frame[\"frame\"][\"elapsed_time\"]\n                delta_time = round(frame_time - prev_time, 6)\n            except IndexError:\n                delta_time = 0\n\n            # Variable to store all the information about the frame\n            frame_state = {\n                \"frame\": {\n                    \"elapsed_time\": frame_time,\n                    \"delta_time\": delta_time,\n                    \"platform_time\": None\n                },\n                \"actors\": {},\n                \"events\":{\n                    \"scene_lights\": {},\n                    \"physics_control\": {},\n                    \"traffic_light_state_time\": {},\n                    \"collisions\": {}\n                }\n            }\n\n            # Loop through all the other rows.\n            self.i = 0\n            self.next_row()\n\n            while self.frame_row.startswith(' Create') or self.frame_row.startswith('  '):\n\n                if self.frame_row.startswith(' Create'):\n                    elements = self.get_row_elements(1, \" \")\n                    actor_id = int(elements[1][:-1])\n\n                    actor = parse_actor(elements)\n                    actors_info.update({actor_id: actor})\n                    actors_info[actor_id].update({\"created\": frame_number})\n                else:\n                    elements = self.get_row_elements(2, \" = \")\n                    actors_info[actor_id].update({elements[0]: elements[1]})\n\n                self.next_row()\n\n            while self.frame_row.startswith(' Destroy'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                actor_id = int(elements[1])\n                actors_info[actor_id].update({\"destroyed\": frame_number})\n\n                self.next_row()\n\n            while self.frame_row.startswith(' Collision'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                actor_id = int(elements[4])\n                other_id = int(elements[-1])\n\n                if actor_id not in frame_state[\"events\"][\"collisions\"]:\n                    frame_state[\"events\"][\"collisions\"][actor_id] = [other_id]\n                else:\n                    collisions = frame_state[\"events\"][\"collisions\"][actor_id]\n                    collisions.append(other_id)\n                    frame_state[\"events\"][\"collisions\"].update({actor_id: collisions})\n\n                self.next_row()\n\n            while self.frame_row.startswith(' Parenting'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                actor_id = int(elements[1])\n                parent_id = int(elements[3])\n                actors_info[actor_id].update({\"parent\": parent_id})\n\n                self.next_row()\n\n            if self.frame_row.startswith(' Positions'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    transform = parse_transform(elements)\n                    frame_state[\"actors\"].update({actor_id: {\"transform\": transform}})\n\n                    self.next_row()\n\n            if self.frame_row.startswith(' State traffic lights'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    traffic_light = parse_traffic_light(elements)\n                    frame_state[\"actors\"].update({actor_id: traffic_light})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Vehicle animations'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    control = parse_control(elements)\n                    frame_state[\"actors\"][actor_id].update({\"control\": control})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Walker animations'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    frame_state[\"actors\"][actor_id].update({\"speed\": elements[3]})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Vehicle light animations'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    lights = parse_vehicle_lights(elements)\n                    frame_state[\"actors\"][actor_id].update({\"lights\": lights})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Scene light changes'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    scene_light = parse_scene_lights(elements)\n                    frame_state[\"events\"][\"scene_lights\"].update({actor_id: scene_light})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Dynamic actors'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    velocity = parse_velocity(elements)\n                    frame_state[\"actors\"][actor_id].update({\"velocity\": velocity})\n\n                    angular_v = parse_angular_velocity(elements)\n                    frame_state[\"actors\"][actor_id].update({\"angular_velocity\": angular_v})\n\n                    if delta_time == 0:\n                        acceleration = carla.Vector3D(0, 0, 0)\n                    else:\n                        prev_velocity = frame_state[\"actors\"][actor_id][\"velocity\"]\n                        acceleration = (velocity - prev_velocity) / delta_time\n\n                    frame_state[\"actors\"][actor_id].update({\"acceleration\": acceleration})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Actor bounding boxes'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    bbox = parse_bounding_box(elements)\n                    actors_info[actor_id].update({\"bounding_box\": bbox})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Actor trigger volumes'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    trigvol = parse_bounding_box(elements)\n                    actors_info[actor_id].update({\"trigger_volume\": trigvol})\n                    self.next_row()\n\n            if self.frame_row.startswith(' Current platform time'):\n\n                elements = self.get_row_elements(1, \" \")\n\n                platform_time = float(elements[-1])\n                frame_state[\"frame\"][\"platform_time\"] = platform_time\n                self.next_row()\n\n            if self.frame_row.startswith(' Physics Control'):\n                self.next_row()\n\n                actor_id = None\n                while self.frame_row.startswith('  '):\n\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n                    physics_control = carla.VehiclePhysicsControl()\n                    self.next_row()\n\n                    forward_gears = []\n                    wheels = []\n                    while self.frame_row.startswith('   '):\n\n                        if self.frame_row.startswith('    '):\n                            elements = self.get_row_elements(4, \" \")\n                            if elements[0] == \"gear\":\n                                forward_gears.append(parse_gears_control(elements))\n                            elif elements[0] == \"wheel\":\n                                wheels.append(parse_wheels_control(elements))\n\n                        else:\n                            elements = self.get_row_elements(3, \" = \")\n                            name = elements[0]\n\n                            if name == \"center_of_mass\":\n                                values = elements[1].split(\" \")\n                                value = carla.Vector3D(\n                                    float(values[0][1:-1]),\n                                    float(values[1][:-1]),\n                                    float(values[2][:-1]),\n                                )\n                                setattr(physics_control, name, value)\n                            elif name == \"torque_curve\" or name == \"steering_curve\":\n                                values = elements[1].split(\" \")\n                                value = parse_vector_list(values)\n                                setattr(physics_control, name, value)\n\n                            elif name == \"use_gear_auto_box\":\n                                name = \"use_gear_autobox\"\n                                value = True if elements[1] == \"true\" else False\n                                setattr(physics_control, name, value)\n\n                            elif \"forward_gears\" in name or \"wheels\" in name:\n                                pass\n\n                            else:\n                                name = name.lower()\n                                value = float(elements[1])\n                                setattr(physics_control, name, value)\n\n                        self.next_row()\n\n                    setattr(physics_control, \"forward_gears\", forward_gears)\n                    setattr(physics_control, \"wheels\", wheels)\n                    frame_state[\"events\"][\"physics_control\"].update({actor_id: physics_control})\n\n            if self.frame_row.startswith(' Traffic Light time events'):\n                self.next_row()\n\n                while self.frame_row.startswith('  '):\n                    elements = self.get_row_elements(2, \" \")\n                    actor_id = int(elements[1])\n\n                    state_times = parse_state_times(elements)\n                    frame_state[\"events\"][\"traffic_light_state_time\"].update({actor_id: state_times})\n                    self.next_row()\n\n            frames_info.append(frame_state)\n\n        return simulation_info, actors_info, frames_info\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_Catalog.xsd",
    "content": "<?xml version=\"1.0\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n    \n    <xsd:include schemaLocation=\"OpenSCENARIO_TypeDefs.xsd\"/>\n    \n    <xsd:import namespace=\"http://www.w3.org/XML/1998/namespace\" schemaLocation=\"http://www.w3.org/2001/xml.xsd\"/>\n    \n    <xsd:annotation>\n        <xsd:documentation>\n            XML Schema Definition for OpenSCENARIO Catalog XML files - Version Draft 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany\n        </xsd:documentation>\n    </xsd:annotation>\n    \n    <xsd:element name=\"OpenSCENARIO\">\n        <xsd:complexType>\n            <xsd:sequence>\n                <xsd:element name=\"FileHeader\"  type=\"OSCFileHeader\"/>\n                \n                <xsd:element name=\"Catalog\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Vehicle\"                 type=\"OSCVehicle\"               minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Driver\"                  type=\"OSCDriver\"                minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Pedestrian\"              type=\"OSCPedestrian\"            minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"PedestrianController\"    type=\"OSCPedestrianController\"  minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"MiscObject\"              type=\"OSCMiscObject\"            minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Environment\"             type=\"OSCEnvironment\"           minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Maneuver\"                type=\"OSCManeuver\"              minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Trajectory\"              type=\"OSCTrajectory\"            minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                            <xsd:element name=\"Route\"                   type=\"OSCRoute\"                 minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                        </xsd:sequence>\n                        <xsd:attribute name=\"name\" type=\"xsd:string\"/>\n                    </xsd:complexType>\n                </xsd:element>\n            </xsd:sequence>\n        </xsd:complexType>\n    </xsd:element>\n    \n</xsd:schema>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_TypeDefs.xsd",
    "content": "<?xml version=\"1.0\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n    \n    <xsd:import namespace=\"http://www.w3.org/XML/1998/namespace\" schemaLocation=\"http://www.w3.org/2001/xml.xsd\"/>\n    \n    <xsd:annotation>\n        <xsd:documentation>\n            XML Schema Type Definitions for OpenSCENARIO XML files - Version Draft 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany\n        </xsd:documentation>\n    </xsd:annotation>\n\n    <xsd:complexType name=\"OSCParameterDeclaration\">\n        <xsd:sequence>\n            <xsd:element name=\"Parameter\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"name\"  type=\"xsd:string\"               use=\"required\"/>\n                    <xsd:attribute name=\"type\"  type=\"Enum_OSC_Parameter_type\"  use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\"               use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCFile\">\n        <xsd:attribute name=\"filepath\"  type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCDirectory\">\n        <xsd:attribute name=\"path\"  type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCCatalogs\">\n        <xsd:all>\n            <xsd:element name=\"VehicleCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"DriverCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"PedestrianCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"PedestrianControllerCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"MiscObjectCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"EnvironmentCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"ManeuverCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"TrajectoryCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RouteCatalog\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Directory\"   type=\"OSCDirectory\"/>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCConditionGroup\">\n        <xsd:sequence>\n            <xsd:element name=\"Condition\" type=\"OSCCondition\" maxOccurs=\"unbounded\"/>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCCatalogReference\">\n        <xsd:sequence>\n            <xsd:element name=\"OSCParameterAssignment\" minOccurs=\"0\"/>\n        </xsd:sequence>\n        <xsd:attribute name=\"catalogName\"   type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"entryName\"     type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCParameterAssignment\">\n        <xsd:sequence>\n            <xsd:element name=\"Parameter\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCUserDataList\">\n        <xsd:sequence>\n            <xsd:element name=\"UserData\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"code\"  type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCFileHeader\">\n        <xsd:attribute name=\"revMajor\"      type=\"xsd:unsignedShort\" use=\"required\"/>\n        <xsd:attribute name=\"revMinor\"      type=\"xsd:unsignedShort\" use=\"required\"/>\n        <xsd:attribute name=\"date\"          type=\"xsd:dateTime\" use=\"required\"/>\n        <xsd:attribute name=\"description\"   type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"author\"        type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPedestrian\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\"/>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:all>\n        <xsd:attribute name=\"model\"     type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"mass\"      type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"category\"  type=\"Enum_Pedestrian_category\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCVehicle\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\"/>\n            <xsd:element name=\"Performance\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"maxSpeed\"          type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"maxDeceleration\"   type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"mass\"              type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Axles\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Front\" type=\"OSCAxle\"/>\n                        <xsd:element name=\"Rear\" type=\"OSCAxle\"/>\n                        <xsd:element name=\"Additional\" type=\"OSCAxle\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                    </xsd:sequence>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:all>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"category\"  type=\"Enum_Vehicle_category\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCAxle\">\n        <xsd:attribute name=\"maxSteering\"   type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"wheelDiameter\" type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"trackWidth\"    type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"positionX\"     type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"positionZ\"     type=\"xsd:double\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCMiscObject\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\"/>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:all>\n        <xsd:attribute name=\"category\"  type=\"Enum_MiscObject_category\" use=\"required\"/>\n        <xsd:attribute name=\"mass\"      type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCCondition\">\n        <xsd:choice>\n            <xsd:element name=\"ByEntity\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"TriggeringEntities\">\n                            <xsd:complexType>\n                                <xsd:sequence>\n                                    <xsd:element name=\"Entity\" maxOccurs=\"unbounded\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:sequence>\n                                <xsd:attribute name=\"rule\" type=\"Enum_TriggeringEntities_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"EntityCondition\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"EndOfRoad\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"duration\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Collision\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"ByEntity\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"ByType \">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"type\" type=\"OSCObjectType\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Offroad\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"duration\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TimeHeadway\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"entity\"        type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\"     type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"alongRoute\"    type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"          type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TimeToCollision\">\n                                        <xsd:complexType>\n                                            <xsd:all>\n                                                <xsd:element name=\"Target\">\n                                                    <xsd:complexType>\n                                                        <xsd:choice>\n                                                            <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                                            <xsd:element name=\"Entity\">\n                                                                <xsd:complexType>\n                                                                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                                </xsd:complexType>\n                                                            </xsd:element>\n                                                        </xsd:choice>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:all>\n                                            <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\"     type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"alongRoute\"    type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"          type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Acceleration\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"StandStill\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"duration\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Speed\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"RelativeSpeed\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"entity\"    type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"      type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TraveledDistance\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"ReachPosition\">\n                                        <xsd:complexType>\n                                            <xsd:all>\n                                                <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                            </xsd:all>\n                                            <xsd:attribute name=\"tolerance\" type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Distance\">\n                                        <xsd:complexType>\n                                            <xsd:all>\n                                                <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                            </xsd:all>\n                                            <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\"     type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"alongRoute\"    type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"          type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"RelativeDistance\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"entity\"    type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"type\"      type=\"Enum_RelativeDistance_type\" use=\"required\"/>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"freespace\" type=\"xsd:boolean\" use=\"required\"/>\n                                            <xsd:attribute name=\"rule\"      type=\"Enum_rule\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"ByState\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"AtStart\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"type\"  type=\"Enum_Story_Element_type\" use=\"required\"/>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"AfterTermination\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"type\"  type=\"Enum_Story_Element_type\" use=\"required\"/>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_AfterTermination_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Command\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Signal\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Controller\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"ByValue\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Parameter\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"TimeOfDay\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Time\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"hour\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"min\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"sec\"   type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Date\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"day\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"month\" type=\"xsd:unsignedInt\" use=\"required\"/>\n                                            <xsd:attribute name=\"year\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"SimulationTime\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"rule\"  type=\"Enum_rule\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n        <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"delay\" type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"edge\"  type=\"Enum_Condition_edge\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:simpleType name=\"OSCObjectType\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"pedestrian\" />\n            <xsd:enumeration value=\"vehicle\" />\n            <xsd:enumeration value=\"miscellaneous\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:complexType name=\"OSCPrivateAction\">\n        <xsd:choice>\n            <xsd:element name=\"Longitudinal\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Speed\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"shape\"     type=\"Enum_Dynamics_shape\" use=\"required\"/>\n                                            <xsd:attribute name=\"rate\"      type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"time\"      type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"distance\"  type=\"xsd:double\" use=\"optional\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Target\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Relative\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"object\"        type=\"xsd:string\" use=\"required\"/>\n                                                        <xsd:attribute name=\"value\"         type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"valueType\"     type=\"Enum_Speed_Target_valueType\" use=\"required\"/>\n                                                        <xsd:attribute name=\"continuous\"    type=\"xsd:boolean\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Absolute\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\"  type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Distance\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"None\"/>\n                                                <xsd:element name=\"Limited\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"maxAcceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxDeceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxSpeed\"          type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"object\"    type=\"xsd:string\"   use=\"required\"/>\n                                <xsd:attribute name=\"distance\"  type=\"xsd:double\"   use=\"optional\"/>\n                                <xsd:attribute name=\"timeGap\"   type=\"xsd:double\"   use=\"optional\"/>\n                                <xsd:attribute name=\"freespace\" type=\"xsd:boolean\"  use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Lateral\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"LaneChange\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"time\"      type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"distance\"  type=\"xsd:double\" use=\"optional\"/>\n                                            <xsd:attribute name=\"shape\"     type=\"Enum_Dynamics_shape\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Target\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Relative\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                                                        <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Absolute\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\"  type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"targetLaneOffset\" type=\"xsd:double\" use=\"optional\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"LaneOffset\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"maxLateralAcc\" type=\"xsd:double\"/>\n                                            <xsd:attribute name=\"duration\"      type=\"xsd:double\"/>\n                                            <xsd:attribute name=\"shape\"         type=\"Enum_Dynamics_shape\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Target\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Relative\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                                                        <xsd:attribute name=\"value\"     type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Absolute\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\"  type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Distance\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Dynamics\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"None\"/>\n                                                <xsd:element name=\"Limited\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"maxAcceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxDeceleration\"   type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"maxSpeed\"          type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                                <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"distance\"  type=\"xsd:double\"/>\n                                <xsd:attribute name=\"freespace\" type=\"xsd:boolean\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Visibility\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"graphics\"  type=\"xsd:boolean\" use=\"required\"/>\n                    <xsd:attribute name=\"traffic\"   type=\"xsd:boolean\" use=\"required\"/>\n                    <xsd:attribute name=\"sensors\"   type=\"xsd:boolean\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Meeting\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"mode\"          type=\"Enum_Meeting_Position_mode\" use=\"required\"/>\n                    <xsd:attribute name=\"timingOffset\"  type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Autonomous\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"activate\"  type=\"xsd:boolean\" use=\"required\"/>\n                    <xsd:attribute name=\"domain\"    type=\"Enum_Controller_domain\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Controller\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Assign\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Driver\"                  type=\"OSCDriver\"/>\n                                    <xsd:element name=\"PedestrianController\"    type=\"OSCPedestrianController\"/>\n                                    <xsd:element name=\"CatalogReference\"        type=\"OSCCatalogReference\"/>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Override\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Throttle\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Brake\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Clutch\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"ParkingBrake\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"SteeringWheel\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"value\"     type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Gear\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"number\"    type=\"xsd:double\"   use=\"required\"/>\n                                            <xsd:attribute name=\"active\"    type=\"xsd:boolean\"  use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n            <xsd:element name=\"Routing\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"FollowRoute\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Route\"               type=\"OSCRoute\"/>\n                                    <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"FollowTrajectory\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Trajectory\"          type=\"OSCTrajectory\"        minOccurs=\"0\"/> <!--todo: only one of Trajectory or CatalogReference is allowed -->\n                                    <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"  minOccurs=\"0\"/> <!--todo: only one of Trajectory or CatalogReference is allowed -->\n                                    <xsd:element name=\"Longitudinal\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"None\"/>\n                                                <xsd:element name=\"Timing\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"domain\"    type=\"Enum_domain_absolute_relative\" use=\"required\"/>\n                                                        <xsd:attribute name=\"scale\"     type=\"xsd:double\" use=\"required\"/>\n                                                        <xsd:attribute name=\"offset\"    type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Lateral\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"purpose\" type=\"Enum_Lateral_purpose\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"AcquirePosition\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCUserDefinedAction\">\n        <xsd:choice>\n            <xsd:element name=\"Command\" type=\"xsd:string\"/>\n            <xsd:element name=\"Script\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"OSCParameterAssignment\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"file\"      type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"execution\" type=\"Enum_Script_execution\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCGlobalAction\">\n        <xsd:choice>\n            <xsd:element name=\"SetEnvironment\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Environment\"         type=\"OSCEnvironment\"/>\n                        <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Entity\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Add\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Delete\"/>\n                    </xsd:choice>\n                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Parameter\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Set\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Modify\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Rule\">\n                                        <xsd:complexType>\n                                            <xsd:choice>\n                                                <xsd:element name=\"Add\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"Multiply\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"value\" type=\"xsd:double\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:choice>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:all>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Infrastructure\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Signal\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"SetController\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"SetState\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                            <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Traffic\">\n                <xsd:complexType>\n                    <xsd:choice>\n                        <xsd:element name=\"Source\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\"            type=\"OSCPosition\"/>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"rate\"      type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"radius\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Sink\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\"            type=\"OSCPosition\"/>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"rate\"      type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"radius\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Swarm\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"CentralObject\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"semiMajorAxis\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"semiMinorAxis\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"innerRadius\"   type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"offset\"        type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Jam\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"Position\"            type=\"OSCPosition\"/>\n                                    <xsd:element name=\"TrafficDefinition\"   type=\"OSCTrafficDefinition\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"direction\" type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"speed\"     type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"length\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:choice>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCManeuver\">\n        <xsd:sequence>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Event\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Action\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Global\"      type=\"OSCGlobalAction\"/>\n                                    <xsd:element name=\"UserDefined\" type=\"OSCUserDefinedAction\"/>\n                                    <xsd:element name=\"Private\"     type=\"OSCPrivateAction\"/>\n                                </xsd:choice>\n                                <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"StartConditions\">\n                            <xsd:complexType>\n                                <xsd:sequence>\n                                    <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                </xsd:sequence>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"priority\"  type=\"Enum_event_priority\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCTrafficDefinition\">\n        <xsd:all>\n            <xsd:element name=\"VehicleDistribution\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Vehicle\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"category\"      type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"percentage\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"DriverDistribution\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Driver\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"percentage\"    type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCEnvironment\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"TimeOfDay\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Time\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"hour\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"min\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"sec\"   type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Date\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"day\"   type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"month\" type=\"xsd:unsignedInt\" use=\"required\"/>\n                                <xsd:attribute name=\"year\"  type=\"xsd:unsignedInt\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                    <xsd:attribute name=\"animation\" type=\"xsd:boolean\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Weather\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Sun\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"intensity\" type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"azimuth\"   type=\"xsd:double\" use=\"required\"/>\n                                <xsd:attribute name=\"elevation\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Fog\">\n                            <xsd:complexType>\n                                <xsd:all>\n                                    <xsd:element name=\"BoundingBox\" type=\"OSCBoundingBox\" minOccurs=\"0\"/>\n                                </xsd:all>\n                                <xsd:attribute name=\"visualRange\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Precipitation\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"type\"      type=\"Enum_Precipitation_type\" use=\"required\"/>\n                                <xsd:attribute name=\"intensity\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                    <xsd:attribute name=\"cloudState\" type=\"Enum_cloudState\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RoadCondition\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Effect\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                            <xsd:complexType>\n                                <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                                <xsd:attribute name=\"intensity\" type=\"xsd:double\" use=\"required\"/>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"frictionScale\" type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n        <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPedestrianController\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Description\" type=\"OSCPersonDescription\"/>\n        </xsd:all>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCDriver\">\n        <xsd:all>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Description\" type=\"OSCPersonDescription\"/>\n        </xsd:all>\n        <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPersonDescription\">\n        <xsd:sequence>\n            <xsd:element name=\"Properties\" type=\"OSCProperties\"/>\n        </xsd:sequence>\n        <xsd:attribute name=\"weight\"        type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"height\"        type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"eyeDistance\"   type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"age\"           type=\"xsd:double\" use=\"required\"/>\n        <xsd:attribute name=\"sex\"           type=\"Enum_sex\"   use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCRoute\">\n        <xsd:sequence>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Waypoint\" minOccurs=\"2\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"strategy\"  type=\"Enum_Route_strategy\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"closed\"    type=\"xsd:boolean\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCTrajectory\">\n        <xsd:sequence>\n            <xsd:element name=\"ParameterDeclaration\" type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n            <xsd:element name=\"Vertex\" minOccurs=\"2\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:sequence>\n                        <xsd:element name=\"Position\" type=\"OSCPosition\"/>\n                        <xsd:element name=\"Shape\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Polyline\"/>\n                                    <xsd:element name=\"Clothoid\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"curvature\"     type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"curvatureDot\"  type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"length\"        type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"Spline\">\n                                        <xsd:complexType>\n                                            <xsd:sequence>\n                                                <xsd:element name=\"ControlPoint1\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"status\"    type=\"xsd:string\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                                <xsd:element name=\"ControlPoint2\">\n                                                    <xsd:complexType>\n                                                        <xsd:attribute name=\"status\"    type=\"xsd:string\" use=\"required\"/>\n                                                    </xsd:complexType>\n                                                </xsd:element>\n                                            </xsd:sequence>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:sequence>\n                    <xsd:attribute name=\"reference\" type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:sequence>\n        <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n        <xsd:attribute name=\"closed\"    type=\"xsd:boolean\" use=\"required\"/>\n        <xsd:attribute name=\"domain\"    type=\"Enum_domain_time_distance\" use=\"required\"/>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCPosition\">\n        <xsd:choice>\n            <xsd:element name=\"World\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"x\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"y\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"z\"  type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"h\"  type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"p\"  type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"r\"  type=\"xsd:double\" use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeWorld\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"dx\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dy\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dz\"        type=\"xsd:double\" use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeObject\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"dx\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dy\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dz\"        type=\"xsd:double\" use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Road\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"roadId\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"s\"         type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"t\"         type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeRoad\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"ds\"        type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"dt\"        type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Lane\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"roadId\"    type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"laneId\"    type=\"xsd:int\" use=\"required\"/>\n                    <xsd:attribute name=\"offset\"    type=\"xsd:double\" use=\"optional\"/>\n                    <xsd:attribute name=\"s\"         type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"RelativeLane\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                    </xsd:all>\n                    <xsd:attribute name=\"object\"    type=\"xsd:string\"   use=\"required\"/>\n                    <xsd:attribute name=\"dLane\"     type=\"xsd:int\"      use=\"required\"/>\n                    <xsd:attribute name=\"ds\"        type=\"xsd:double\"   use=\"required\"/>\n                    <xsd:attribute name=\"offset\"    type=\"xsd:double\"   use=\"optional\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Route\">\n                <xsd:complexType>\n                    <xsd:all>\n                        <xsd:element name=\"RouteRef\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Route\"               type=\"OSCRoute\"/>\n                                    <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                        <xsd:element name=\"Orientation\" type=\"OSCOrientation\" minOccurs=\"0\"/>\n                        <xsd:element name=\"Position\">\n                            <xsd:complexType>\n                                <xsd:choice>\n                                    <xsd:element name=\"Current\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"object\"    type=\"xsd:string\"   use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"RoadCoord\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"pathS\" type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"t\"     type=\"xsd:double\" use=\"required\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                    <xsd:element name=\"LaneCoord\">\n                                        <xsd:complexType>\n                                            <xsd:attribute name=\"pathS\"         type=\"xsd:double\" use=\"required\"/>\n                                            <xsd:attribute name=\"laneId\"        type=\"xsd:int\" use=\"required\"/>\n                                            <xsd:attribute name=\"laneOffset\"    type=\"xsd:double\" use=\"optional\"/>\n                                        </xsd:complexType>\n                                    </xsd:element>\n                                </xsd:choice>\n                            </xsd:complexType>\n                        </xsd:element>\n                    </xsd:all>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:choice>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCBoundingBox\">\n        <xsd:all>\n            <xsd:element name=\"Center\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"x\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"y\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"z\"  type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"Dimension\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"width\"  type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"length\" type=\"xsd:double\" use=\"required\"/>\n                    <xsd:attribute name=\"height\" type=\"xsd:double\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n        </xsd:all>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCProperties\">\n        <xsd:sequence>\n            <xsd:element name=\"Property\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                <xsd:complexType>\n                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                    <xsd:attribute name=\"value\" type=\"xsd:string\" use=\"required\"/>\n                </xsd:complexType>\n            </xsd:element>\n            <xsd:element name=\"File\" type=\"OSCFile\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n        </xsd:sequence>\n    </xsd:complexType>\n    \n    <xsd:complexType name=\"OSCOrientation\">\n        <xsd:attribute name=\"type\"  type=\"Enum_Orientation_type\" use=\"optional\"/>\n        <xsd:attribute name=\"h\"     type=\"xsd:double\" use=\"optional\"/>\n        <xsd:attribute name=\"p\"     type=\"xsd:double\" use=\"optional\"/>\n        <xsd:attribute name=\"r\"     type=\"xsd:double\" use=\"optional\"/>\n    </xsd:complexType>\n    \n    \n    <!-- **************************************************************\n    ************************ Enumerations ************************\n    ************************************************************** -->\n    \n    <xsd:simpleType name=\"Enum_Route_strategy\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"fastest\" />\n            <xsd:enumeration value=\"shortest\" />\n            <xsd:enumeration value=\"leastIntersections\" />\n            <xsd:enumeration value=\"random\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_sex\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"male\" />\n            <xsd:enumeration value=\"female\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Precipitation_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"dry\" />\n            <xsd:enumeration value=\"rain\" />\n            <xsd:enumeration value=\"snow\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_cloudState\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"skyOff\" />\n            <xsd:enumeration value=\"free\" />\n            <xsd:enumeration value=\"cloudy\" />\n            <xsd:enumeration value=\"overcast\" />\n            <xsd:enumeration value=\"rainy\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Orientation_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"relative\" />\n            <xsd:enumeration value=\"absolute\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_domain_time_distance\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"time\" />\n            <xsd:enumeration value=\"distance\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_domain_absolute_relative\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"absolute\" />\n            <xsd:enumeration value=\"relative\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_event_priority\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"overwrite\" />\n            <xsd:enumeration value=\"following\" />\n            <xsd:enumeration value=\"skip\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Script_execution\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"single\" />\n            <xsd:enumeration value=\"continuous\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Dynamics_shape\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"linear\" />\n            <xsd:enumeration value=\"cubic\" />\n            <xsd:enumeration value=\"sinusoidal\" />\n            <xsd:enumeration value=\"step\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Speed_Target_valueType\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"delta\" />\n            <xsd:enumeration value=\"factor\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Meeting_Position_mode\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"straight\" />\n            <xsd:enumeration value=\"route\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Controller_domain\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"longitudinal\" />\n            <xsd:enumeration value=\"lateral\" />\n            <xsd:enumeration value=\"both\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Lateral_purpose\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"position\" />\n            <xsd:enumeration value=\"steering\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Condition_edge\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"rising\" />\n            <xsd:enumeration value=\"falling\" />\n            <xsd:enumeration value=\"any\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_TriggeringEntities_rule\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"any\" />\n            <xsd:enumeration value=\"all\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_rule\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"greater_than\" />\n            <xsd:enumeration value=\"less_than\" />\n            <xsd:enumeration value=\"equal_to\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_RelativeDistance_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"longitudinal\" />\n            <xsd:enumeration value=\"lateral\" />\n            <xsd:enumeration value=\"inertial\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Story_Element_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"act\" />\n            <xsd:enumeration value=\"scene\" />\n            <xsd:enumeration value=\"maneuver\" />\n            <xsd:enumeration value=\"event\" />\n            <xsd:enumeration value=\"action\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_AfterTermination_rule\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"end\" />\n            <xsd:enumeration value=\"cancel\" />\n            <xsd:enumeration value=\"any\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_MiscObject_category\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"barrier\" />\n            <xsd:enumeration value=\"guardRail\" />\n            <xsd:enumeration value=\"other\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Vehicle_category\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"car\" />\n            <xsd:enumeration value=\"van\" />\n            <xsd:enumeration value=\"truck\" />\n            <xsd:enumeration value=\"trailer\" />\n            <xsd:enumeration value=\"semitrailer\" />\n            <xsd:enumeration value=\"bus\" />\n            <xsd:enumeration value=\"motorbike\" />\n            <xsd:enumeration value=\"bicycle\" />\n            <xsd:enumeration value=\"train\" />\n            <xsd:enumeration value=\"tram\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_Pedestrian_category\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"pedestrian\" />\n            <xsd:enumeration value=\"wheelchair\" />\n            <xsd:enumeration value=\"animal\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_ByCondition_actor\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"triggeringEntity\" />\n            <xsd:enumeration value=\"anyEntity\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n    <xsd:simpleType name=\"Enum_OSC_Parameter_type\">\n        <xsd:restriction base=\"xsd:string\">\n            <xsd:enumeration value=\"integer\" />\n            <xsd:enumeration value=\"double\" />\n            <xsd:enumeration value=\"string\" />\n        </xsd:restriction>\n    </xsd:simpleType>\n    \n</xsd:schema>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_v0.9.1.xsd",
    "content": "<?xml version=\"1.0\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n    \n    <xsd:include schemaLocation=\"OpenSCENARIO_TypeDefs.xsd\"/>\n    \n    <xsd:import namespace=\"http://www.w3.org/XML/1998/namespace\" schemaLocation=\"http://www.w3.org/2001/xml.xsd\"/>\n    \n    <xsd:annotation>\n        <xsd:documentation>\n            XML Schema Definition for OpenSCENARIO XML files - Version 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany\n        </xsd:documentation>\n    </xsd:annotation>\n    \n    <xsd:element name=\"OpenSCENARIO\">\n        <xsd:complexType>\n            <xsd:sequence>\n                <xsd:element name=\"FileHeader\"              type=\"OSCFileHeader\"/>\n                <xsd:element name=\"ParameterDeclaration\"    type=\"OSCParameterDeclaration\" minOccurs=\"0\"/>\n                <xsd:element name=\"Catalogs\"                type=\"OSCCatalogs\"/>\n                <xsd:element name=\"RoadNetwork\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Logics\"      type=\"OSCFile\"/>\n                            <xsd:element name=\"SceneGraph\"  type=\"OSCFile\"/>\n                            <xsd:element name=\"Signals\"     minOccurs=\"0\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Controller\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:element name=\"Phase\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Signal\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                                                        <xsd:attribute name=\"state\" type=\"xsd:string\" use=\"required\"/>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                            </xsd:sequence>\n                                                            <xsd:attribute name=\"type\"      type=\"xsd:string\" use=\"required\"/>\n                                                            <xsd:attribute name=\"duration\"  type=\"xsd:double\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:sequence>\n                                                <xsd:attribute name=\"name\"      type=\"xsd:string\" use=\"required\"/>\n                                                <xsd:attribute name=\"delay\"     type=\"xsd:double\" use=\"optional\"/>\n                                                <xsd:attribute name=\"reference\" type=\"xsd:string\" use=\"optional\"/>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                        </xsd:sequence>\n                    </xsd:complexType>\n                </xsd:element>\n                <xsd:element name=\"Entities\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Object\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:choice>\n                                            <xsd:element name=\"CatalogReference\"    type=\"OSCCatalogReference\"/>\n                                            <xsd:element name=\"Vehicle\"             type=\"OSCVehicle\"/>\n                                            <xsd:element name=\"Pedestrian\"          type=\"OSCPedestrian\"/>\n                                            <xsd:element name=\"MiscObject\"          type=\"OSCMiscObject\"/>\n                                        </xsd:choice>\n                                        <xsd:element name=\"Controller\" minOccurs=\"0\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:choice>\n                                                        <xsd:element name=\"CatalogReference\"        type=\"OSCCatalogReference\"/>\n                                                        <xsd:element name=\"Driver\"                  type=\"OSCDriver\"/>\n                                                        <xsd:element name=\"PedestrianController\"    type=\"OSCPedestrianController\"/>\n                                                    </xsd:choice>\n                                                </xsd:sequence>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                            <xsd:element name=\"Selection\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Members\">\n                                            <xsd:complexType>\n                                                <xsd:choice>\n                                                    <xsd:element name=\"ByEntity\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                    <xsd:element name=\"ByType\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:attribute name=\"type\" type=\"OSCObjectType\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:choice>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                        </xsd:sequence>\n                    </xsd:complexType>\n                </xsd:element>\n                <xsd:element name=\"Storyboard\">\n                    <xsd:complexType>\n                        <xsd:sequence>\n                            <xsd:element name=\"Init\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Actions\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:element name=\"Global\" type=\"OSCGlobalAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                    <xsd:element name=\"UserDefined\" type=\"OSCUserDefinedAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                    <xsd:element name=\"Private\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Action\" type=\"OSCPrivateAction\" maxOccurs=\"unbounded\"/>\n                                                            </xsd:sequence>\n                                                            <xsd:attribute name=\"object\"  type=\"xsd:string\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:sequence>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                </xsd:complexType>\n                            </xsd:element>\n                            <xsd:element name=\"Story\" maxOccurs=\"unbounded\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"Act\" maxOccurs=\"unbounded\">\n                                            <xsd:complexType>\n                                                <xsd:sequence>\n                                                    <xsd:element name=\"Sequence\" maxOccurs=\"unbounded\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Actors\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"Entity\" minOccurs=\"0\" maxOccurs=\"unbounded\">\n                                                                                <xsd:complexType>\n                                                                                    <xsd:attribute name=\"name\" type=\"xsd:string\" use=\"required\"/>\n                                                                                </xsd:complexType>\n                                                                            </xsd:element>\n                                                                            <xsd:element name=\"ByCondition\" minOccurs=\"0\">\n                                                                                <xsd:complexType>\n                                                                                    <xsd:attribute name=\"actor\" type=\"Enum_ByCondition_actor\" use=\"required\"/>\n                                                                                </xsd:complexType>\n                                                                            </xsd:element>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                                <xsd:element name=\"CatalogReference\" type=\"OSCCatalogReference\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                                <xsd:element name=\"Maneuver\" type=\"OSCManeuver\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                                            </xsd:sequence>\n                                                            <xsd:attribute name=\"numberOfExecutions\"    type=\"xsd:int\" use=\"required\"/>\n                                                            <xsd:attribute name=\"name\"                  type=\"xsd:string\" use=\"required\"/>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                    <xsd:element name=\"Conditions\">\n                                                        <xsd:complexType>\n                                                            <xsd:sequence>\n                                                                <xsd:element name=\"Start\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                                <xsd:element name=\"End\" minOccurs=\"0\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                                <xsd:element name=\"Cancel\" minOccurs=\"0\">\n                                                                    <xsd:complexType>\n                                                                        <xsd:sequence>\n                                                                            <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" maxOccurs=\"unbounded\"/>\n                                                                        </xsd:sequence>\n                                                                    </xsd:complexType>\n                                                                </xsd:element>\n                                                            </xsd:sequence>\n                                                        </xsd:complexType>\n                                                    </xsd:element>\n                                                </xsd:sequence>\n                                                <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                            </xsd:complexType>\n                                        </xsd:element>\n                                    </xsd:sequence>\n                                    <xsd:attribute name=\"owner\" type=\"xsd:string\" use=\"optional\"/>\n                                    <xsd:attribute name=\"name\"  type=\"xsd:string\" use=\"required\"/>\n                                </xsd:complexType>\n                            </xsd:element>\n                            <xsd:element name=\"EndConditions\">\n                                <xsd:complexType>\n                                    <xsd:sequence>\n                                        <xsd:element name=\"ConditionGroup\" type=\"OSCConditionGroup\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n                                    </xsd:sequence>\n                                </xsd:complexType>\n                            </xsd:element>\n                        </xsd:sequence>\n                    </xsd:complexType>\n                </xsd:element>\n            </xsd:sequence>\n        </xsd:complexType>\n    </xsd:element>\n    \n</xsd:schema>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/openscenario/0.9.x/migration0_9_1to1_0.xslt",
    "content": "<!--\nASAM OpenSCENARIO V1.0.0\n\nThis file allows transformation from version 0.9.1 to V 1.0.0\n\n© by ASAM e.V., 2020\n-->\n<xsl:stylesheet version='1.0' xmlns:xsl='http://www.w3.org/1999/XSL/Transform'>\n  <xsl:output method='xml' indent='yes' />\n  <xsl:strip-space elements='*' />\n  <xsl:template name='RelativeDistanceType'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"longitudinal\"'>longitudinal</xsl:when>\n      <xsl:when test='$oldValue=\"lateral\"'>lateral</xsl:when>\n      <xsl:otherwise>cartesianDistance</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='Rule'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"greater_than\"'>greaterThan</xsl:when>\n      <xsl:when test='$oldValue=\"less_than\"'>lessThan</xsl:when>\n      <xsl:otherwise>equalTo</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='MiscObjectCategory'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"other\"'>none</xsl:when>\n      <xsl:when test='$oldValue=\"guardRail\"'>railing</xsl:when>\n      <xsl:otherwise>barrier</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='StoryboardElementState'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"end\"'>endTransition</xsl:when>\n      <xsl:when test='$oldValue=\"cancel\"'>stopTransition</xsl:when>\n      <xsl:otherwise>completeState</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='ConditionEdge'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"any\"'>risingOrFalling</xsl:when>\n      <xsl:when test='$oldValue=\"falling\"'>falling</xsl:when>\n      <xsl:otherwise>rising</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template name='FollowingMode'>\n    <xsl:param name='oldValue' />\n    <xsl:choose>\n      <xsl:when test='$oldValue=\"position\"'>position</xsl:when>\n      <xsl:otherwise>follow</xsl:otherwise>\n    </xsl:choose>\n  </xsl:template>\n  <xsl:template match='/'>\n    <xsl:call-template name='unsupportedMigration' />\n    <OpenSCENARIO>\n      <xsl:for-each select='*'>\n        <xsl:copy-of select='@*' />\n        <xsl:call-template name='OpenScenario' />\n      </xsl:for-each>\n    </OpenSCENARIO>\n  </xsl:template><xsl:template name=\"unsupportedMigration\"/>\n\n  <xsl:template name='OpenScenario'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"FileHeader\"'>\n        <FileHeader>\n          <xsl:call-template name='FileHeader' />\n        </FileHeader>\n      </xsl:if>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Catalogs\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"RoadNetwork\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Entities\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Storyboard\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n      <xsl:if test='name()=\"Catalog\"'>\n        <xsl:call-template name='OpenScenarioCategory' />\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='OpenScenarioCategory'>\n    <xsl:if test='name()=\"ParameterDeclaration\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Catalogs\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"RoadNetwork\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Entities\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Storyboard\"'>\n      <xsl:call-template name='ScenarioDefinition' />\n    </xsl:if>\n    <xsl:if test='name()=\"Catalog\"'>\n      <xsl:call-template name='CatalogDefinition' />\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='CatalogDefinition'>\n    <xsl:if test='name()=\"Catalog\"'>\n      <Catalog>\n        <xsl:call-template name='Catalog' />\n      </Catalog>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ScenarioDefinition'>\n    <xsl:if test='name()=\"ParameterDeclaration\"'>\n      <ParameterDeclarations>\n        <xsl:call-template name='ParameterDeclarations' />\n      </ParameterDeclarations>\n    </xsl:if>\n    <xsl:if test='name()=\"Catalogs\"'>\n      <CatalogLocations>\n        <xsl:call-template name='CatalogLocations' />\n      </CatalogLocations>\n    </xsl:if>\n    <xsl:if test='name()=\"RoadNetwork\"'>\n      <RoadNetwork>\n        <xsl:call-template name='RoadNetwork' />\n      </RoadNetwork>\n    </xsl:if>\n    <xsl:if test='name()=\"Entities\"'>\n      <Entities>\n        <xsl:call-template name='Entities' />\n      </Entities>\n    </xsl:if>\n    <xsl:if test='name()=\"Storyboard\"'>\n      <Storyboard>\n        <xsl:call-template name='Storyboard' />\n      </Storyboard>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='EntityObject'>\n    <xsl:if test='name()=\"CatalogReference\"'>\n      <CatalogReference>\n        <xsl:call-template name='CatalogReference' />\n      </CatalogReference>\n    </xsl:if>\n    <xsl:if test='name()=\"Vehicle\"'>\n      <Vehicle>\n        <xsl:call-template name='Vehicle' />\n      </Vehicle>\n    </xsl:if>\n    <xsl:if test='name()=\"Pedestrian\"'>\n      <Pedestrian>\n        <xsl:call-template name='Pedestrian' />\n      </Pedestrian>\n    </xsl:if>\n    <xsl:if test='name()=\"MiscObject\"'>\n      <MiscObject>\n        <xsl:call-template name='MiscObject' />\n      </MiscObject>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ParameterDeclarations'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterDeclaration>\n          <xsl:call-template name='ParameterDeclaration' />\n        </ParameterDeclaration>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='File'>\n    <xsl:if test='@filepath'>\n      <xsl:attribute name='filepath'>\n        <xsl:value-of select='@filepath' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Directory'>\n    <xsl:if test='@path'>\n      <xsl:attribute name='path'>\n        <xsl:value-of select='@path' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"CatalogLocations\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;VehicleCatalog&quot;\">\n      <VehicleCatalog>\n        <xsl:call-template name=\"VehicleCatalogLocation\"/>\n      </VehicleCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;DriverCatalog&quot;\">\n      <ControllerCatalog>\n        <xsl:call-template name=\"ControllerCatalogLocation\"/>\n      </ControllerCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianCatalog&quot;\">\n      <PedestrianCatalog>\n        <xsl:call-template name=\"PedestrianCatalogLocation\"/>\n      </PedestrianCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;MiscObjectCatalog&quot;\">\n      <MiscObjectCatalog>\n        <xsl:call-template name=\"MiscObjectCatalogLocation\"/>\n      </MiscObjectCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;EnvironmentCatalog&quot;\">\n      <EnvironmentCatalog>\n        <xsl:call-template name=\"EnvironmentCatalogLocation\"/>\n      </EnvironmentCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;ManeuverCatalog&quot;\">\n      <ManeuverCatalog>\n        <xsl:call-template name=\"ManeuverCatalogLocation\"/>\n      </ManeuverCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrajectoryCatalog&quot;\">\n      <TrajectoryCatalog>\n        <xsl:call-template name=\"TrajectoryCatalogLocation\"/>\n      </TrajectoryCatalog>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;RouteCatalog&quot;\">\n      <RouteCatalog>\n        <xsl:call-template name=\"RouteCatalogLocation\"/>\n      </RouteCatalog>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianControllerCatalog\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='ConditionGroup'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Condition\"'>\n        <Condition>\n          <xsl:call-template name='Condition' />\n        </Condition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='CatalogReference'>\n    <xsl:if test='@catalogName'>\n      <xsl:attribute name='catalogName'>\n        <xsl:value-of select='@catalogName' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@entryName'>\n      <xsl:attribute name='entryName'>\n        <xsl:value-of select='@entryName' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterAssignment\"'>\n        <ParameterAssignments>\n          <xsl:call-template name='ParameterAssignments' />\n        </ParameterAssignments>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterAssignments'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterAssignment>\n          <xsl:call-template name='ParameterAssignment' />\n        </ParameterAssignment>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='UserDataList'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"UserData\"'>\n        <UserData>\n          <xsl:call-template name='UserData' />\n        </UserData>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='FileHeader'>\n    <xsl:if test='@revMajor'>\n      <xsl:attribute name='revMajor'>\n        <xsl:value-of select='@revMajor' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@revMinor'>\n      <xsl:attribute name='revMinor'>\n        <xsl:value-of select='@revMinor' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@date'>\n      <xsl:attribute name='date'>\n        <xsl:value-of select='@date' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@description'>\n      <xsl:attribute name='description'>\n        <xsl:value-of select='@description' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@author'>\n      <xsl:attribute name='author'>\n        <xsl:value-of select='@author' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Pedestrian'>\n    <xsl:if test='@model'>\n      <xsl:attribute name='model'>\n        <xsl:value-of select='@model' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@mass'>\n      <xsl:attribute name='mass'>\n        <xsl:value-of select='@mass' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@category'>\n      <xsl:attribute name='pedestrianCategory'>\n        <xsl:value-of select='@category' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n      <xsl:if test='name()=\"Properties\"'>\n        <Properties>\n          <xsl:call-template name='Properties' />\n        </Properties>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Vehicle'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@category'>\n      <xsl:attribute name='vehicleCategory'>\n        <xsl:value-of select='@category' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n      <xsl:if test='name()=\"Performance\"'>\n        <Performance>\n          <xsl:call-template name='Performance' />\n        </Performance>\n      </xsl:if>\n      <xsl:if test='name()=\"Axles\"'>\n        <Axles>\n          <xsl:call-template name='Axles' />\n        </Axles>\n      </xsl:if>\n      <xsl:if test='name()=\"Properties\"'>\n        <Properties>\n          <xsl:call-template name='Properties' />\n        </Properties>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Axle'>\n    <xsl:if test='@maxSteering'>\n      <xsl:attribute name='maxSteering'>\n        <xsl:value-of select='@maxSteering' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@wheelDiameter'>\n      <xsl:attribute name='wheelDiameter'>\n        <xsl:value-of select='@wheelDiameter' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@trackWidth'>\n      <xsl:attribute name='trackWidth'>\n        <xsl:value-of select='@trackWidth' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@positionX'>\n      <xsl:attribute name='positionX'>\n        <xsl:value-of select='@positionX' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@positionZ'>\n      <xsl:attribute name='positionZ'>\n        <xsl:value-of select='@positionZ' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='MiscObject'>\n    <xsl:if test='@category'>\n      <xsl:attribute name='miscObjectCategory'>\n        <xsl:call-template name='MiscObjectCategory'>\n          <xsl:with-param name='oldValue' select='@category' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@mass'>\n      <xsl:attribute name='mass'>\n        <xsl:value-of select='@mass' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n      <xsl:if test='name()=\"Properties\"'>\n        <Properties>\n          <xsl:call-template name='Properties' />\n        </Properties>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Condition\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@delay\">\n    <xsl:attribute name=\"delay\">\n      <xsl:value-of select=\"@delay\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@edge\">\n    <xsl:attribute name=\"conditionEdge\">\n      <xsl:call-template name=\"ConditionEdge\">\n        <xsl:with-param name=\"oldValue\" select=\"@edge\"/>\n      </xsl:call-template>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;ByEntity&quot;\">\n      <ByEntityCondition>\n        <xsl:call-template name=\"ByEntityCondition\"/>\n      </ByEntityCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;ByState&quot;\">\n      <ByValueCondition>\n        <xsl:call-template name=\"ByStateCondition\"/>\n      </ByValueCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;ByValue&quot;\">\n      <ByValueCondition>\n        <xsl:call-template name=\"ByValueCondition\"/>\n      </ByValueCondition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"PrivateAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Longitudinal&quot;\">\n      <LongitudinalAction>\n        <xsl:call-template name=\"LongitudinalAction\"/>\n      </LongitudinalAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Lateral&quot;\">\n      <LateralAction>\n        <xsl:call-template name=\"LateralAction\"/>\n      </LateralAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Visibility&quot;\">\n      <VisibilityAction>\n        <xsl:call-template name=\"VisibilityAction\"/>\n      </VisibilityAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Meeting&quot;\">\n      <MeetingAction>\n        <xsl:call-template name=\"MeetingAction\"/>\n      </MeetingAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Autonomous&quot;\">\n      <ActivateControllerAction>\n        <xsl:call-template name=\"ActivateControllerAction\"/>\n      </ActivateControllerAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Controller&quot;\">\n      <ControllerAction>\n        <xsl:call-template name=\"ControllerAction\"/>\n      </ControllerAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <TeleportAction>\n        <Position>\n          <xsl:call-template name=\"Position\"/>\n        </Position>\n      </TeleportAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Routing&quot;\">\n      <RoutingAction>\n        <xsl:call-template name=\"RoutingAction\"/>\n      </RoutingAction>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='UserDefinedAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Command\"'>\n        <CommandAction>\n          <xsl:call-template name='CustomCommandAction' />\n        </CommandAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Script\"'>\n        <Script>\n          <xsl:call-template name='ScriptAction' />\n        </Script>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='GlobalAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"SetEnvironment\"'>\n        <EnvironmentAction>\n          <xsl:call-template name='EnvironmentAction' />\n        </EnvironmentAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Entity\"'>\n        <EntityAction>\n          <xsl:call-template name='EntityAction' />\n        </EntityAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterAction>\n          <xsl:call-template name='ParameterAction' />\n        </ParameterAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Infrastructure\"'>\n        <InfrastructureAction>\n          <xsl:call-template name='InfrastructureAction' />\n        </InfrastructureAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Traffic\"'>\n        <TrafficAction>\n          <xsl:call-template name='TrafficAction' />\n        </TrafficAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Maneuver'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"Event\"'>\n        <Event>\n          <xsl:call-template name='Event' />\n        </Event>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficDefinition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"VehicleDistribution\"'>\n        <VehicleCategoryDistribution>\n          <xsl:call-template name='VehicleCategoryDistribution' />\n        </VehicleCategoryDistribution>\n      </xsl:if>\n      <xsl:if test='name()=\"DriverDistribution\"'>\n        <ControllerDistribution>\n          <xsl:call-template name='ControllerDistribution' />\n        </ControllerDistribution>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Environment'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeOfDay\"'>\n        <TimeOfDay>\n          <xsl:call-template name='TimeOfDay' />\n        </TimeOfDay>\n      </xsl:if>\n      <xsl:if test='name()=\"Weather\"'>\n        <Weather>\n          <xsl:call-template name='Weather' />\n        </Weather>\n      </xsl:if>\n      <xsl:if test='name()=\"RoadCondition\"'>\n        <RoadCondition>\n          <xsl:call-template name='RoadCondition' />\n        </RoadCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Controller\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;ParameterDeclaration&quot;\">\n      <ParameterDeclarations>\n        <xsl:call-template name=\"ParameterDeclarations\"/>\n      </ParameterDeclarations>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Description&quot;\">\n      <Properties>\n        <xsl:call-template name=\"PersonDescription\"/>\n      </Properties>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"PersonDescription\">\n  <xsl:if test=\"@weight\">\n    <Property name=\"weight\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@weight\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@height\">\n    <Property name=\"height\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@height\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@eyeDistance\">\n    <Property name=\"eyeDistance\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@eyeDistance\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@age\">\n    <Property name=\"age\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@age\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:if test=\"@sex\">\n    <Property name=\"sex\">\n      <xsl:attribute name=\"value\">\n        <xsl:value-of select=\"@sex\"/>\n      </xsl:attribute>\n    </Property>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Properties&quot;\">\n      <xsl:call-template name=\"Properties\"/>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='Route'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@closed'>\n      <xsl:attribute name='closed'>\n        <xsl:value-of select='@closed' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterDeclaration\"'>\n        <ParameterDeclarations>\n          <xsl:call-template name='ParameterDeclarations' />\n        </ParameterDeclarations>\n      </xsl:if>\n      <xsl:if test='name()=\"Waypoint\"'>\n        <Waypoint>\n          <xsl:call-template name='Waypoint' />\n        </Waypoint>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Trajectory\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@closed\">\n    <xsl:attribute name=\"closed\">\n      <xsl:value-of select=\"@closed\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;ParameterDeclaration&quot;\">\n      <ParameterDeclarations>\n        <xsl:call-template name=\"ParameterDeclarations\"/>\n      </ParameterDeclarations>\n    </xsl:if>\n  </xsl:for-each>\n  <Shape>\n    <Polyline>\n      <xsl:for-each select=\"*\">\n        <xsl:if test=\"name()=&quot;Vertex&quot;\">\n          <Vertex>\n            <xsl:call-template name=\"Vertex\"/>\n          </Vertex>\n        </xsl:if>\n      </xsl:for-each>\n    </Polyline>\n  </Shape>\n  <xsl:message terminate=\"no\">\n    WARNING: OSCTrajectory is restructured and connot be automatically migrated. Review XML\n  </xsl:message>\n</xsl:template>\n\n  <xsl:template name='Position'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"World\"'>\n        <WorldPosition>\n          <xsl:call-template name='WorldPosition' />\n        </WorldPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeWorld\"'>\n        <RelativeWorldPosition>\n          <xsl:call-template name='RelativeWorldPosition' />\n        </RelativeWorldPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeObject\"'>\n        <RelativeObjectPosition>\n          <xsl:call-template name='RelativeObjectPosition' />\n        </RelativeObjectPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"Road\"'>\n        <RoadPosition>\n          <xsl:call-template name='RoadPosition' />\n        </RoadPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeRoad\"'>\n        <RelativeRoadPosition>\n          <xsl:call-template name='RelativeRoadPosition' />\n        </RelativeRoadPosition>\n      </xsl:if>\n      <xsl:if test='name()=\"Lane\"'>\n        <LanePosition>\n          <xsl:call-template name='LanePosition' />\n        </LanePosition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeLane\"'>\n        <RelativeLanePosition>\n          <xsl:call-template name='RelativeLanePosition' />\n        </RelativeLanePosition>\n      </xsl:if>\n      <xsl:if test='name()=\"Route\"'>\n        <RoutePosition>\n          <xsl:call-template name='RoutePosition' />\n        </RoutePosition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='BoundingBox'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Center\"'>\n        <Center>\n          <xsl:call-template name='Center' />\n        </Center>\n      </xsl:if>\n      <xsl:if test='name()=\"Dimension\"'>\n        <Dimensions>\n          <xsl:call-template name='Dimensions' />\n        </Dimensions>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Properties'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Property\"'>\n        <Property>\n          <xsl:call-template name='Property' />\n        </Property>\n      </xsl:if>\n      <xsl:if test='name()=\"File\"'>\n        <File>\n          <xsl:call-template name='File' />\n        </File>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Orientation'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@h'>\n      <xsl:attribute name='h'>\n        <xsl:value-of select='@h' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@p'>\n      <xsl:attribute name='p'>\n        <xsl:value-of select='@p' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@r'>\n      <xsl:attribute name='r'>\n        <xsl:value-of select='@r' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"Catalog\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Vehicle&quot;\">\n      <Vehicle>\n        <xsl:call-template name=\"Vehicle\"/>\n      </Vehicle>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Driver&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Pedestrian&quot;\">\n      <Pedestrian>\n        <xsl:call-template name=\"Pedestrian\"/>\n      </Pedestrian>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianController&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;MiscObject&quot;\">\n      <MiscObject>\n        <xsl:call-template name=\"MiscObject\"/>\n      </MiscObject>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Environment&quot;\">\n      <Environment>\n        <xsl:call-template name=\"Environment\"/>\n      </Environment>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Maneuver&quot;\">\n      <Maneuver>\n        <xsl:call-template name=\"Maneuver\"/>\n      </Maneuver>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Trajectory&quot;\">\n      <Trajectory>\n        <xsl:call-template name=\"Trajectory\"/>\n      </Trajectory>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Route&quot;\">\n      <Route>\n        <xsl:call-template name=\"Route\"/>\n      </Route>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianController\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='RoadNetwork'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Logics\"'>\n        <LogicFile>\n          <xsl:call-template name='File' />\n        </LogicFile>\n      </xsl:if>\n      <xsl:if test='name()=\"SceneGraph\"'>\n        <SceneGraphFile>\n          <xsl:call-template name='File' />\n        </SceneGraphFile>\n      </xsl:if>\n      <xsl:if test='name()=\"Signals\"'>\n        <TrafficSignals>\n          <xsl:call-template name='TrafficSignals' />\n        </TrafficSignals>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"TrafficSignals\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Controller&quot;\">\n      <TrafficSignalController>\n        <xsl:call-template name=\"TrafficSignalController\"/>\n      </TrafficSignalController>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='TrafficSignalController'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@delay'>\n      <xsl:attribute name='delay'>\n        <xsl:value-of select='@delay' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@reference'>\n      <xsl:attribute name='reference'>\n        <xsl:value-of select='@reference' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Phase\"'>\n        <Phase>\n          <xsl:call-template name='Phase' />\n        </Phase>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Phase'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Signal\"'>\n        <TrafficSignalState>\n          <xsl:call-template name='TrafficSignalState' />\n        </TrafficSignalState>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficSignalState'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='trafficSignalId'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='state'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Entities'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Object\"'>\n        <ScenarioObject>\n          <xsl:call-template name='ScenarioObject' />\n        </ScenarioObject>\n      </xsl:if>\n      <xsl:if test='name()=\"Selection\"'>\n        <EntitySelection>\n          <xsl:call-template name='EntitySelection' />\n        </EntitySelection>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ScenarioObject'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"Vehicle\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"Pedestrian\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"MiscObject\"'>\n        <xsl:call-template name='EntityObject' />\n      </xsl:if>\n      <xsl:if test='name()=\"Controller\"'>\n        <ObjectController>\n          <xsl:call-template name='ObjectController' />\n        </ObjectController>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"ObjectController\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;CatalogReference&quot;\">\n      <CatalogReference>\n        <xsl:call-template name=\"CatalogReference\"/>\n      </CatalogReference>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Driver&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianController&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianController\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='EntitySelection'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Members\"'>\n        <Members>\n          <xsl:call-template name='SelectedEntities' />\n        </Members>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='SelectedEntities'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ByEntity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n      <xsl:if test='name()=\"ByType\"'>\n        <ByType>\n          <xsl:call-template name='ByType' />\n        </ByType>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EntityRef'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ByType'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='objectType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Storyboard'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Init\"'>\n        <Init>\n          <xsl:call-template name='Init' />\n        </Init>\n      </xsl:if>\n      <xsl:if test='name()=\"Story\"'>\n        <Story>\n          <xsl:call-template name='Story' />\n        </Story>\n      </xsl:if>\n      <xsl:if test='name()=\"EndConditions\"'>\n        <StopTrigger>\n          <xsl:call-template name='Trigger' />\n        </StopTrigger>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Init'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Actions\"'>\n        <Actions>\n          <xsl:call-template name='InitActions' />\n        </Actions>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"InitActions\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Global&quot;\">\n      <xsl:if test=\"not(Traffic/Jam)\">\n        <GlobalAction>\n          <xsl:call-template name=\"GlobalAction\"/>\n        </GlobalAction>\n      </xsl:if>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;UserDefined&quot;\">\n      <xsl:if test=\"not(Script)\">\n        <UserDefinedAction>\n          <xsl:call-template name=\"UserDefinedAction\"/>\n        </UserDefinedAction>\n      </xsl:if>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Private&quot;\">\n      <Private>\n        <xsl:call-template name=\"Private\"/>\n      </Private>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"Global/Traffic/Jam\">\n    <xsl:message terminate=\"no\">\n      WARNING: Jam is desupported: removed during migration\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"UserDefined/Script\">\n    <xsl:message terminate=\"no\">\n      WARNING: Script is desupported: removed during migration\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n<xsl:template name=\"Private\">\n  <xsl:if test=\"@object\">\n    <xsl:attribute name=\"entityRef\">\n      <xsl:value-of select=\"@object\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Action&quot;\">\n      <xsl:if test=\"not(Meeting)\">\n        <PrivateAction>\n          <xsl:call-template name=\"PrivateAction\"/>\n        </PrivateAction>\n      </xsl:if>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"Action/Meeting\">\n    <xsl:message terminate=\"no\">\n      WARNING: OSCPrivateAction.Meeting is desupported: removed during migration\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n<xsl:template name=\"Story\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@owner and @owner != &quot;&quot;\">\n    <ParameterDeclarations>\n      <ParameterDeclaration parameterType=\"string\" name=\"$owner\">\n        <xsl:attribute name=\"value\">\n          <xsl:value-of select=\"@owner\"/>\n        </xsl:attribute>\n      </ParameterDeclaration>\n    </ParameterDeclarations>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Act&quot;\">\n      <Act>\n        <xsl:call-template name=\"Act\"/>\n      </Act>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"Act\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Sequence&quot;\">\n      <ManeuverGroup>\n        <xsl:call-template name=\"ManeuverGroup\"/>\n      </ManeuverGroup>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Conditions&quot;\">\n      <xsl:for-each select=\"*\">\n        <xsl:if test=\"name()=&quot;Start&quot;\">\n          <StartTrigger>\n            <xsl:call-template name=\"Trigger\"/>\n          </StartTrigger>\n        </xsl:if>\n        <xsl:if test=\"name()=&quot;End&quot;\">\n          <StopTrigger>\n            <xsl:call-template name=\"Trigger\"/>\n          </StopTrigger>\n        </xsl:if>\n        <xsl:if test=\"name()=&quot;Cancel&quot;\">\n          <StopTrigger>\n            <xsl:call-template name=\"Trigger\"/>\n          </StopTrigger>\n        </xsl:if>\n      </xsl:for-each>\n    </xsl:if>\n    <xsl:if test=\"Cancel and End\">\n      <xsl:message terminate=\"no\">\n        ERROR: Act: Cancel and End are both defined: Version 1.0 only supports Stop Trigger. Invalid XML is produced and needs to be revisited.\n      </xsl:message>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='ManeuverGroup'>\n    <xsl:if test='@numberOfExecutions'>\n      <xsl:attribute name='maximumExecutionCount'>\n        <xsl:value-of select='@numberOfExecutions' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Actors\"'>\n        <Actors>\n          <xsl:call-template name='Actors' />\n        </Actors>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n      <xsl:if test='name()=\"Maneuver\"'>\n        <Maneuver>\n          <xsl:call-template name='Maneuver' />\n        </Maneuver>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Actors\">\n  <xsl:choose>\n    <xsl:when test=\"ByCondition\">\n      <xsl:if test=\"ByCondition[@actor = &quot;triggeringEntity&quot;]\">\n        <xsl:attribute name=\"selectTriggeringEntities\">\n          <xsl:value-of select=\"&quot;true&quot;\"/>\n        </xsl:attribute>\n      </xsl:if>\n      <xsl:if test=\"ByCondition[@actor = &quot;anyEntity&quot;]\">\n        <xsl:attribute name=\"selectTriggeringEntities\">\n          <xsl:value-of select=\"&quot;false&quot;\"/>\n        </xsl:attribute>\n        <xsl:message terminate=\"no\">\n          WARNING: Storyboard.Story.Act.Sequence.Actors.ByCondition: \"anyEntity\" is de-supported for version 1.0\n        </xsl:message>\n      </xsl:if>\n    </xsl:when>\n    <xsl:otherwise>\n      <xsl:attribute name=\"selectTriggeringEntities\">\n        <xsl:value-of select=\"&quot;false&quot;\"/>\n      </xsl:attribute>\n    </xsl:otherwise>\n  </xsl:choose>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Entity&quot;\">\n      <EntityRef>\n        <xsl:call-template name=\"EntityRef\"/>\n      </EntityRef>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='SelectActorByTrigger'>\n    <xsl:if test='@actor'>\n      <xsl:attribute name='selectionFilter'>\n        <xsl:value-of select='@actor' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ConditionSet'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Start\"'>\n        <StartConditions>\n          <xsl:call-template name='Trigger' />\n        </StartConditions>\n      </xsl:if>\n      <xsl:if test='name()=\"End\"'>\n        <EndConditions>\n          <xsl:call-template name='Trigger' />\n        </EndConditions>\n      </xsl:if>\n      <xsl:if test='name()=\"Cancel\"'>\n        <CancelConditions>\n          <xsl:call-template name='Trigger' />\n        </CancelConditions>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Trigger'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ConditionGroup\"'>\n        <ConditionGroup>\n          <xsl:call-template name='ConditionGroup' />\n        </ConditionGroup>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterDeclaration'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@type'>\n      <xsl:attribute name='parameterType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='VehicleCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ControllerCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='PedestrianCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='MiscObjectCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EnvironmentCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ManeuverCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrajectoryCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RouteCatalogLocation'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Directory\"'>\n        <Directory>\n          <xsl:call-template name='Directory' />\n        </Directory>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterAssignment'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='parameterRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='UserData'>\n    <xsl:if test='@code'>\n      <xsl:attribute name='code'>\n        <xsl:value-of select='@code' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"Performance\">\n  <xsl:if test=\"@maxSpeed\">\n    <xsl:attribute name=\"maxSpeed\">\n      <xsl:value-of select=\"@maxSpeed\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@maxAcceleration\">\n    <xsl:attribute name=\"maxAcceleration\">\n      <xsl:value-of select=\"@maxAcceleration\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@maxDeceleration\">\n    <xsl:attribute name=\"maxDeceleration\">\n      <xsl:value-of select=\"@maxDeceleration\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='Axles'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Front\"'>\n        <FrontAxle>\n          <xsl:call-template name='Axle' />\n        </FrontAxle>\n      </xsl:if>\n      <xsl:if test='name()=\"Rear\"'>\n        <RearAxle>\n          <xsl:call-template name='Axle' />\n        </RearAxle>\n      </xsl:if>\n      <xsl:if test='name()=\"Additional\"'>\n        <AdditionalAxle>\n          <xsl:call-template name='Axle' />\n        </AdditionalAxle>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ByEntityCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"TriggeringEntities\"'>\n        <TriggeringEntities>\n          <xsl:call-template name='TriggeringEntities' />\n        </TriggeringEntities>\n      </xsl:if>\n      <xsl:if test='name()=\"EntityCondition\"'>\n        <EntityCondition>\n          <xsl:call-template name='EntityCondition' />\n        </EntityCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TriggeringEntities'>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='triggeringEntitiesRule'>\n        <xsl:value-of select='@rule' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Entity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EntityCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"EndOfRoad\"'>\n        <EndOfRoadCondition>\n          <xsl:call-template name='EndOfRoadCondition' />\n        </EndOfRoadCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Collision\"'>\n        <CollisionCondition>\n          <xsl:call-template name='CollisionCondition' />\n        </CollisionCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Offroad\"'>\n        <OffroadCondition>\n          <xsl:call-template name='OffroadCondition' />\n        </OffroadCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeHeadway\"'>\n        <TimeHeadwayCondition>\n          <xsl:call-template name='TimeHeadwayCondition' />\n        </TimeHeadwayCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeToCollision\"'>\n        <TimeToCollisionCondition>\n          <xsl:call-template name='TimeToCollisionCondition' />\n        </TimeToCollisionCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Acceleration\"'>\n        <AccelerationCondition>\n          <xsl:call-template name='AccelerationCondition' />\n        </AccelerationCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"StandStill\"'>\n        <StandStillCondition>\n          <xsl:call-template name='StandStillCondition' />\n        </StandStillCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Speed\"'>\n        <SpeedCondition>\n          <xsl:call-template name='SpeedCondition' />\n        </SpeedCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeSpeed\"'>\n        <RelativeSpeedCondition>\n          <xsl:call-template name='RelativeSpeedCondition' />\n        </RelativeSpeedCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TraveledDistance\"'>\n        <TraveledDistanceCondition>\n          <xsl:call-template name='TraveledDistanceCondition' />\n        </TraveledDistanceCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"ReachPosition\"'>\n        <ReachPositionCondition>\n          <xsl:call-template name='ReachPositionCondition' />\n        </ReachPositionCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"Distance\"'>\n        <DistanceCondition>\n          <xsl:call-template name='DistanceCondition' />\n        </DistanceCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"RelativeDistance\"'>\n        <RelativeDistanceCondition>\n          <xsl:call-template name='RelativeDistanceCondition' />\n        </RelativeDistanceCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EndOfRoadCondition'>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='CollisionCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ByEntity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n      <xsl:if test='name()=\"ByType\"'>\n        <ByType>\n          <xsl:call-template name='ByObjectType' />\n        </ByType>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ByObjectType'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OffroadCondition'>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TimeHeadwayCondition'>\n    <xsl:if test='@entity'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@entity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@alongRoute'>\n      <xsl:attribute name='alongRoute'>\n        <xsl:value-of select='@alongRoute' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TimeToCollisionCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@alongRoute'>\n      <xsl:attribute name='alongRoute'>\n        <xsl:value-of select='@alongRoute' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Target\"'>\n        <TimeToCollisionConditionTarget>\n          <xsl:call-template name='TimeToCollisionConditionTarget' />\n        </TimeToCollisionConditionTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TimeToCollisionConditionTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n      <xsl:if test='name()=\"Entity\"'>\n        <EntityRef>\n          <xsl:call-template name='EntityRef' />\n        </EntityRef>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='AccelerationCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='StandStillCondition'>\n    <xsl:if test='@duration'>\n      <xsl:attribute name='duration'>\n        <xsl:value-of select='@duration' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='SpeedCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='RelativeSpeedCondition'>\n    <xsl:if test='@entity'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@entity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TraveledDistanceCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ReachPositionCondition'>\n    <xsl:if test='@tolerance'>\n      <xsl:attribute name='tolerance'>\n        <xsl:value-of select='@tolerance' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='DistanceCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@alongRoute'>\n      <xsl:attribute name='alongRoute'>\n        <xsl:value-of select='@alongRoute' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeDistanceCondition'>\n    <xsl:if test='@entity'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@entity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@type'>\n      <xsl:attribute name='relativeDistanceType'>\n        <xsl:call-template name='RelativeDistanceType'>\n          <xsl:with-param name='oldValue' select='@type' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@freespace'>\n      <xsl:attribute name='freespace'>\n        <xsl:value-of select='@freespace' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"ByStateCondition\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;AtStart&quot;\">\n      <StoryboardElementStateCondition>\n        <xsl:if test=\"@type\">\n          <xsl:attribute name=\"storyboardElementType\">\n            <xsl:value-of select=\"@type\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:if test=\"@name\">\n          <xsl:attribute name=\"storyboardElementRef\">\n            <xsl:value-of select=\"@name\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:attribute name=\"state\">\n          <xsl:value-of select=\"'startTransition'\"/>\n        </xsl:attribute>\n      </StoryboardElementStateCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;AfterTermination&quot;\">\n      <StoryboardElementStateCondition>\n        <xsl:call-template name=\"StoryboardElementStateCondition\"/>\n      </StoryboardElementStateCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Command&quot;\">\n      <UserDefinedValueCondition>\n        <xsl:call-template name=\"UserDefinedValueCondition\"/>\n      </UserDefinedValueCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Signal&quot;\">\n      <TrafficSignalCondition>\n        <xsl:call-template name=\"TrafficSignalCondition\"/>\n      </TrafficSignalCondition>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Controller&quot;\">\n      <TrafficSignalControllerCondition>\n        <xsl:call-template name=\"TrafficSignalControllerCondition\"/>\n      </TrafficSignalControllerCondition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='AtStartCondition'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='StoryboardElementStateCondition'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='storyboardElementType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@name'>\n      <xsl:attribute name='storyboardElementRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='state'>\n        <xsl:call-template name='StoryboardElementState'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"UserDefinedValueCondition\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:attribute name=\"rule\">\n    <xsl:value-of select=\"'equalTo'\"/>\n  </xsl:attribute>\n  <xsl:attribute name=\"value\">\n    <xsl:value-of select=\"'true'\"/>\n  </xsl:attribute>\n</xsl:template>\n\n  <xsl:template name='TrafficSignalCondition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='state'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficSignalControllerCondition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='trafficSignalControllerRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='phase'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ByValueCondition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Parameter\"'>\n        <ParameterCondition>\n          <xsl:call-template name='ParameterCondition' />\n        </ParameterCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"TimeOfDay\"'>\n        <TimeOfDayCondition>\n          <xsl:call-template name='TimeOfDayCondition' />\n        </TimeOfDayCondition>\n      </xsl:if>\n      <xsl:if test='name()=\"SimulationTime\"'>\n        <SimulationTimeCondition>\n          <xsl:call-template name='SimulationTimeCondition' />\n        </SimulationTimeCondition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterCondition'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='parameterRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"TimeOfDayCondition\">\n  <xsl:if test=\"@rule\">\n    <xsl:attribute name=\"rule\">\n      <xsl:call-template name=\"Rule\">\n        <xsl:with-param name=\"oldValue\" select=\"@rule\"/>\n      </xsl:call-template>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:variable name=\"hour\" select=\"Time/@hour\"/>\n  <xsl:variable name=\"min\" select=\"Time/@min\"/>\n  <xsl:variable name=\"sec\" select=\"Time/@sec\"/>\n  <xsl:variable name=\"day\" select=\"Date/@day\"/>\n  <xsl:variable name=\"month\" select=\"Date/@month\"/>\n  <xsl:variable name=\"year\" select=\"Date/@year\"/>\n  <xsl:attribute name=\"dateTime\">\n    <xsl:value-of select=\"format-number($year,'0000')\"/>\n    <xsl:value-of select=\"format-number($month,'-00')\"/>\n    <xsl:value-of select=\"format-number($day,'-00')\"/>\n    <xsl:value-of select=\"format-number($hour,'T00')\"/>\n    <xsl:value-of select=\"format-number($min,':00')\"/>\n    <xsl:value-of select=\"format-number($sec,':00')\"/>\n  </xsl:attribute>\n</xsl:template>\n\n  <xsl:template name='Time'>\n    <xsl:if test='@hour'>\n      <xsl:attribute name='hour'>\n        <xsl:value-of select='@hour' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@min'>\n      <xsl:attribute name='min'>\n        <xsl:value-of select='@min' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@sec'>\n      <xsl:attribute name='sec'>\n        <xsl:value-of select='@sec' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Date'>\n    <xsl:if test='@day'>\n      <xsl:attribute name='day'>\n        <xsl:value-of select='@day' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@month'>\n      <xsl:attribute name='month'>\n        <xsl:value-of select='@month' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@year'>\n      <xsl:attribute name='year'>\n        <xsl:value-of select='@year' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='SimulationTimeCondition'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@rule'>\n      <xsl:attribute name='rule'>\n        <xsl:call-template name='Rule'>\n          <xsl:with-param name='oldValue' select='@rule' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LongitudinalAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Speed&quot;\">\n      <SpeedAction>\n        <xsl:call-template name=\"SpeedAction\"/>\n      </SpeedAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Distance&quot;\">\n      <LongitudinalDistanceAction continuous=\"true\">\n        <xsl:call-template name=\"LongitudinalDistanceAction\"/>\n      </LongitudinalDistanceAction>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='SpeedAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Dynamics\"'>\n        <SpeedActionDynamics>\n          <xsl:call-template name='TransitionDynamics' />\n        </SpeedActionDynamics>\n      </xsl:if>\n      <xsl:if test='name()=\"Target\"'>\n        <SpeedActionTarget>\n          <xsl:call-template name='SpeedActionTarget' />\n        </SpeedActionTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"TransitionDynamics\">\n  <xsl:if test=\"@shape\">\n    <xsl:attribute name=\"dynamicsShape\">\n      <xsl:value-of select=\"@shape\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@rate\">\n    <xsl:attribute name=\"value\">\n      <xsl:value-of select=\"@rate\"/>\n    </xsl:attribute>\n    <xsl:attribute name=\"dynamicsDimension\">\n      <xsl:value-of select=\"&quot;rate&quot;\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@time\">\n    <xsl:attribute name=\"value\">\n      <xsl:value-of select=\"@time\"/>\n    </xsl:attribute>\n    <xsl:attribute name=\"dynamicsDimension\">\n      <xsl:value-of select=\"&quot;time&quot;\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@distance\">\n    <xsl:attribute name=\"value\">\n      <xsl:value-of select=\"@distance\"/>\n    </xsl:attribute>\n    <xsl:attribute name=\"dynamicsDimension\">\n      <xsl:value-of select=\"&quot;distance&quot;\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"(@distance and @time) or (@distance and @rate) or  (@time and @rate)\">\n    <xsl:message terminate=\"no\">\n      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.\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"not(@distance) and not(@time) and not(@rate)\">\n    <xsl:message terminate=\"no\">\n      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.\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='SpeedActionTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Relative\"'>\n        <RelativeTargetSpeed>\n          <xsl:call-template name='RelativeTargetSpeed' />\n        </RelativeTargetSpeed>\n      </xsl:if>\n      <xsl:if test='name()=\"Absolute\"'>\n        <AbsoluteTargetSpeed>\n          <xsl:call-template name='AbsoluteTargetSpeed' />\n        </AbsoluteTargetSpeed>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeTargetSpeed'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@valueType'>\n      <xsl:attribute name='speedTargetValueType'>\n        <xsl:value-of select='@valueType' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@continuous'>\n      <xsl:attribute name='continuous'>\n        <xsl:value-of select='@continuous' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AbsoluteTargetSpeed'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LongitudinalDistanceAction\">\n  <xsl:if test=\"@object\">\n    <xsl:attribute name=\"entityRef\">\n      <xsl:value-of select=\"@object\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@distance\">\n    <xsl:attribute name=\"distance\">\n      <xsl:value-of select=\"@distance\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@timeGap\">\n    <xsl:attribute name=\"timeGap\">\n      <xsl:value-of select=\"@timeGap\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@freespace\">\n    <xsl:attribute name=\"freespace\">\n      <xsl:value-of select=\"@freespace\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Dynamics&quot;\">\n      <xsl:call-template name=\"DynamicConstraints\"/>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"DynamicConstraints\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Limited&quot;\">\n      <DynamicConstraints>\n        <xsl:if test=\"@maxAcceleration\">\n          <xsl:attribute name=\"maxAcceleration\">\n            <xsl:value-of select=\"@maxAcceleration\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:if test=\"@maxDeceleration\">\n          <xsl:attribute name=\"maxDeceleration\">\n            <xsl:value-of select=\"@maxDeceleration\"/>\n          </xsl:attribute>\n        </xsl:if>\n        <xsl:if test=\"@maxSpeed\">\n          <xsl:attribute name=\"maxSpeed\">\n            <xsl:value-of select=\"@maxSpeed\"/>\n          </xsl:attribute>\n        </xsl:if>\n      </DynamicConstraints>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='None' />\n  <xsl:template name='Limited'>\n    <xsl:if test='@maxAcceleration'>\n      <xsl:attribute name='maxAcceleration'>\n        <xsl:value-of select='@maxAcceleration' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@maxDeceleration'>\n      <xsl:attribute name='maxDeceleration'>\n        <xsl:value-of select='@maxDeceleration' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@maxSpeed'>\n      <xsl:attribute name='maxSpeed'>\n        <xsl:value-of select='@maxSpeed' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LateralAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;LaneChange&quot;\">\n      <LaneChangeAction>\n        <xsl:call-template name=\"LaneChangeAction\"/>\n      </LaneChangeAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;LaneOffset&quot;\">\n      <LaneOffsetAction continuous=\"true\">\n        <xsl:call-template name=\"LaneOffsetAction\"/>\n      </LaneOffsetAction>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;Distance&quot;\">\n      <LateralDistanceAction continuous=\"true\">\n        <xsl:call-template name=\"LateralDistanceAction\"/>\n      </LateralDistanceAction>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='LaneChangeAction'>\n    <xsl:if test='@targetLaneOffset'>\n      <xsl:attribute name='targetLaneOffset'>\n        <xsl:value-of select='@targetLaneOffset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Dynamics\"'>\n        <LaneChangeActionDynamics>\n          <xsl:call-template name='TransitionDynamics' />\n        </LaneChangeActionDynamics>\n      </xsl:if>\n      <xsl:if test='name()=\"Target\"'>\n        <LaneChangeTarget>\n          <xsl:call-template name='LaneChangeTarget' />\n        </LaneChangeTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='LaneChangeTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Relative\"'>\n        <RelativeTargetLane>\n          <xsl:call-template name='RelativeTargetLane' />\n        </RelativeTargetLane>\n      </xsl:if>\n      <xsl:if test='name()=\"Absolute\"'>\n        <AbsoluteTargetLane>\n          <xsl:call-template name='AbsoluteTargetLane' />\n        </AbsoluteTargetLane>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeTargetLane'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AbsoluteTargetLane'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='LaneOffsetAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Dynamics\"'>\n        <LaneOffsetActionDynamics>\n          <xsl:call-template name='LaneOffsetActionDynamics' />\n        </LaneOffsetActionDynamics>\n      </xsl:if>\n      <xsl:if test='name()=\"Target\"'>\n        <LaneOffsetTarget>\n          <xsl:call-template name='LaneOffsetTarget' />\n        </LaneOffsetTarget>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"LaneOffsetActionDynamics\">\n  <xsl:if test=\"@maxLateralAcc\">\n    <xsl:attribute name=\"maxLateralAcc\">\n      <xsl:value-of select=\"@maxLateralAcc\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@shape\">\n    <xsl:attribute name=\"dynamicsShape\">\n      <xsl:value-of select=\"@shape\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='LaneOffsetTarget'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Relative\"'>\n        <RelativeTargetLaneOffset>\n          <xsl:call-template name='RelativeTargetLaneOffset' />\n        </RelativeTargetLaneOffset>\n      </xsl:if>\n      <xsl:if test='name()=\"Absolute\"'>\n        <AbsoluteTargetLaneOffset>\n          <xsl:call-template name='AbsoluteTargetLaneOffset' />\n        </AbsoluteTargetLaneOffset>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeTargetLaneOffset'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AbsoluteTargetLaneOffset'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"LateralDistanceAction\">\n  <xsl:if test=\"@object\">\n    <xsl:attribute name=\"entityRef\">\n      <xsl:value-of select=\"@object\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@distance\">\n    <xsl:attribute name=\"distance\">\n      <xsl:value-of select=\"@distance\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@freespace\">\n    <xsl:attribute name=\"freespace\">\n      <xsl:value-of select=\"@freespace\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Dynamics&quot;\">\n      <xsl:call-template name=\"DynamicConstraints\"/>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='VisibilityAction'>\n    <xsl:if test='@graphics'>\n      <xsl:attribute name='graphics'>\n        <xsl:value-of select='@graphics' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@traffic'>\n      <xsl:attribute name='traffic'>\n        <xsl:value-of select='@traffic' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@sensors'>\n      <xsl:attribute name='sensors'>\n        <xsl:value-of select='@sensors' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='MeetingAction'>\n    <xsl:if test='@mode'>\n      <xsl:attribute name='meetingPositionMode'>\n        <xsl:value-of select='@mode' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@timingOffset'>\n      <xsl:attribute name='timingOffset'>\n        <xsl:value-of select='@timingOffset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"ActivateControllerAction\">\n  <xsl:if test=\"@activate and @domain = &quot;lateral&quot;\">\n    <xsl:attribute name=\"lateral\">\n      <xsl:value-of select=\"@activate\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@activate and @domain = &quot;longitudinal&quot;\">\n    <xsl:attribute name=\"longitudinal\">\n      <xsl:value-of select=\"@activate\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='ControllerAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Assign\"'>\n        <AssignControllerAction>\n          <xsl:call-template name='AssignControllerAction' />\n        </AssignControllerAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Override\"'>\n        <OverrideControllerValueAction>\n          <xsl:call-template name='OverrideControllerValueAction' />\n        </OverrideControllerValueAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"AssignControllerAction\">\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Driver&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;PedestrianController&quot;\">\n      <Controller>\n        <xsl:call-template name=\"Controller\"/>\n      </Controller>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;CatalogReference&quot;\">\n      <CatalogReference>\n        <xsl:call-template name=\"CatalogReference\"/>\n      </CatalogReference>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"PedestrianController\">\n    <xsl:message terminate=\"no\">\n      WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='OverrideControllerValueAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Throttle\"'>\n        <Throttle>\n          <xsl:call-template name='OverrideThrottleAction' />\n        </Throttle>\n      </xsl:if>\n      <xsl:if test='name()=\"Brake\"'>\n        <Brake>\n          <xsl:call-template name='OverrideBrakeAction' />\n        </Brake>\n      </xsl:if>\n      <xsl:if test='name()=\"Clutch\"'>\n        <Clutch>\n          <xsl:call-template name='OverrideClutchAction' />\n        </Clutch>\n      </xsl:if>\n      <xsl:if test='name()=\"ParkingBrake\"'>\n        <ParkingBrake>\n          <xsl:call-template name='OverrideParkingBrakeAction' />\n        </ParkingBrake>\n      </xsl:if>\n      <xsl:if test='name()=\"SteeringWheel\"'>\n        <SteeringWheel>\n          <xsl:call-template name='OverrideSteeringWheelAction' />\n        </SteeringWheel>\n      </xsl:if>\n      <xsl:if test='name()=\"Gear\"'>\n        <Gear>\n          <xsl:call-template name='OverrideGearAction' />\n        </Gear>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='OverrideThrottleAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideBrakeAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideClutchAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideParkingBrakeAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideSteeringWheelAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='OverrideGearAction'>\n    <xsl:if test='@number'>\n      <xsl:attribute name='number'>\n        <xsl:value-of select='@number' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@active'>\n      <xsl:attribute name='active'>\n        <xsl:value-of select='@active' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='RoutingAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"FollowRoute\"'>\n        <AssignRouteAction>\n          <xsl:call-template name='AssignRouteAction' />\n        </AssignRouteAction>\n      </xsl:if>\n      <xsl:if test='name()=\"FollowTrajectory\"'>\n        <FollowTrajectoryAction>\n          <xsl:call-template name='FollowTrajectoryAction' />\n        </FollowTrajectoryAction>\n      </xsl:if>\n      <xsl:if test='name()=\"AcquirePosition\"'>\n        <AcquirePositionAction>\n          <xsl:call-template name='AcquirePositionAction' />\n        </AcquirePositionAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='AssignRouteAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Route\"'>\n        <Route>\n          <xsl:call-template name='Route' />\n        </Route>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='FollowTrajectoryAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Trajectory\"'>\n        <Trajectory>\n          <xsl:call-template name='Trajectory' />\n        </Trajectory>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n      <xsl:if test='name()=\"Longitudinal\"'>\n        <TimeReference>\n          <xsl:call-template name='TimeReference' />\n        </TimeReference>\n      </xsl:if>\n      <xsl:if test='name()=\"Lateral\"'>\n        <TrajectoryFollowingMode>\n          <xsl:call-template name='TrajectoryFollowingMode' />\n        </TrajectoryFollowingMode>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TimeReference'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"None\"'>\n        <None>\n          <xsl:call-template name='None' />\n        </None>\n      </xsl:if>\n      <xsl:if test='name()=\"Timing\"'>\n        <Timing>\n          <xsl:call-template name='Timing' />\n        </Timing>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Timing'>\n    <xsl:if test='@domain'>\n      <xsl:attribute name='domainAbsoluteRelative'>\n        <xsl:value-of select='@domain' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@scale'>\n      <xsl:attribute name='scale'>\n        <xsl:value-of select='@scale' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@offset'>\n      <xsl:attribute name='offset'>\n        <xsl:value-of select='@offset' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrajectoryFollowingMode'>\n    <xsl:if test='@purpose'>\n      <xsl:attribute name='followingMode'>\n        <xsl:call-template name='FollowingMode'>\n          <xsl:with-param name='oldValue' select='@purpose' />\n        </xsl:call-template>\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='AcquirePositionAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='CustomCommandAction'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='type'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ScriptAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@file'>\n      <xsl:attribute name='file'>\n        <xsl:value-of select='@file' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@execution'>\n      <xsl:attribute name='execution'>\n        <xsl:value-of select='@execution' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ParameterAssignment\"'>\n        <ParameterAssignment>\n          <xsl:call-template name='ParameterAssignments' />\n        </ParameterAssignment>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EnvironmentAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Environment\"'>\n        <Environment>\n          <xsl:call-template name='Environment' />\n        </Environment>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='EntityAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Add\"'>\n        <AddEntityAction>\n          <xsl:call-template name='AddEntityAction' />\n        </AddEntityAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Delete\"'>\n        <DeleteEntityAction>\n          <xsl:call-template name='DeleteEntityAction' />\n        </DeleteEntityAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='AddEntityAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='DeleteEntityAction' />\n  <xsl:template name='ParameterAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='parameterRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Set\"'>\n        <SetAction>\n          <xsl:call-template name='ParameterSetAction' />\n        </SetAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Modify\"'>\n        <ModifyAction>\n          <xsl:call-template name='ParameterModifyAction' />\n        </ModifyAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterSetAction'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ParameterModifyAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Rule\"'>\n        <Rule>\n          <xsl:call-template name='ModifyRule' />\n        </Rule>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ModifyRule'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Add\"'>\n        <AddValue>\n          <xsl:call-template name='ParameterAddValueRule' />\n        </AddValue>\n      </xsl:if>\n      <xsl:if test='name()=\"Multiply\"'>\n        <MultiplyByValue>\n          <xsl:call-template name='ParameterMultiplyByValueRule' />\n        </MultiplyByValue>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ParameterAddValueRule'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ParameterMultiplyByValueRule'>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='InfrastructureAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Signal\"'>\n        <TrafficSignalAction>\n          <xsl:call-template name='TrafficSignalAction' />\n        </TrafficSignalAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficSignalAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"SetController\"'>\n        <TrafficSignalControllerAction>\n          <xsl:call-template name='TrafficSignalControllerAction' />\n        </TrafficSignalControllerAction>\n      </xsl:if>\n      <xsl:if test='name()=\"SetState\"'>\n        <TrafficSignalStateAction>\n          <xsl:call-template name='TrafficSignalStateAction' />\n        </TrafficSignalStateAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='TrafficSignalControllerAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='trafficSignalControllerRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='phase'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficSignalStateAction'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@state'>\n      <xsl:attribute name='state'>\n        <xsl:value-of select='@state' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficAction'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Source\"'>\n        <TrafficSourceAction>\n          <xsl:call-template name='TrafficSourceAction' />\n        </TrafficSourceAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Sink\"'>\n        <TrafficSinkAction>\n          <xsl:call-template name='TrafficSinkAction' />\n        </TrafficSinkAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Swarm\"'>\n        <TrafficSwarmAction>\n          <xsl:call-template name='TrafficSwarmAction' />\n        </TrafficSwarmAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Jam\"'>\n        <TrafficJamAction>\n          <xsl:call-template name='TrafficJamAction' />\n        </TrafficJamAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"TrafficSourceAction\">\n  <xsl:if test=\"@rate\">\n    <xsl:attribute name=\"rate\">\n      <xsl:value-of select=\"@rate\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@radius\">\n    <xsl:attribute name=\"radius\">\n      <xsl:value-of select=\"@radius\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <Position>\n        <xsl:call-template name=\"Position\"/>\n      </Position>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrafficDefinition&quot;\">\n      <TrafficDefinition>\n        <xsl:call-template name=\"TrafficDefinition\"/>\n      </TrafficDefinition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"TrafficSinkAction\">\n  <xsl:if test=\"@rate\">\n    <xsl:attribute name=\"rate\">\n      <xsl:value-of select=\"@rate\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@radius\">\n    <xsl:attribute name=\"radius\">\n      <xsl:value-of select=\"@radius\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <Position>\n        <xsl:call-template name=\"Position\"/>\n      </Position>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrafficDefinition&quot;\">\n      <TrafficDefinition>\n        <xsl:call-template name=\"TrafficDefinition\"/>\n      </TrafficDefinition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n<xsl:template name=\"TrafficSwarmAction\">\n  <xsl:if test=\"@semiMajorAxis\">\n    <xsl:attribute name=\"semiMajorAxis\">\n      <xsl:value-of select=\"@semiMajorAxis\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@semiMinorAxis\">\n    <xsl:attribute name=\"semiMinorAxis\">\n      <xsl:value-of select=\"@semiMinorAxis\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@innerRadius\">\n    <xsl:attribute name=\"innerRadius\">\n      <xsl:value-of select=\"@innerRadius\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@offset\">\n    <xsl:attribute name=\"offset\">\n      <xsl:value-of select=\"@offset\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@numberOfVehicles\">\n    <xsl:attribute name=\"numberOfVehicles\">\n      <xsl:value-of select=\"@numberOfVehicles\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;CentralObject&quot;\">\n      <CentralObject>\n        <xsl:call-template name=\"CentralSwarmObject\"/>\n      </CentralObject>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;TrafficDefinition&quot;\">\n      <TrafficDefinition>\n        <xsl:call-template name=\"TrafficDefinition\"/>\n      </TrafficDefinition>\n    </xsl:if>\n  </xsl:for-each>\n</xsl:template>\n\n  <xsl:template name='CentralSwarmObject'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='TrafficJamAction'>\n    <xsl:if test='@direction'>\n      <xsl:attribute name='direction'>\n        <xsl:value-of select='@direction' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@speed'>\n      <xsl:attribute name='speed'>\n        <xsl:value-of select='@speed' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@length'>\n      <xsl:attribute name='length'>\n        <xsl:value-of select='@length' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n      <xsl:if test='name()=\"TrafficDefinition\"'>\n        <TrafficDefinition>\n          <xsl:call-template name='TrafficDefinition' />\n        </TrafficDefinition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Event\">\n  <xsl:if test=\"@name\">\n    <xsl:attribute name=\"name\">\n      <xsl:value-of select=\"@name\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@priority\">\n    <xsl:choose>\n      <xsl:when test=\"@priority =&quot;following&quot;\">\n        <xsl:attribute name=\"priority\">\n          <xsl:value-of select=\"&quot;&quot;\"/>\n        </xsl:attribute>\n        <xsl:message terminate=\"no\">\n          WARNING: Event.priority: 'following' is desupported: removed during migration. This results in unvalifd XML code.\n        </xsl:message>\n      </xsl:when>\n      <xsl:otherwise>\n        <xsl:attribute name=\"priority\">\n          <xsl:value-of select=\"@priority\"/>\n        </xsl:attribute>\n      </xsl:otherwise>\n    </xsl:choose>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Action&quot;\">\n      <xsl:if test=\"not(Global/Traffic/Jam) and not(UserDefined/Script) and not(Private/Meeting)\">\n        <Action>\n          <xsl:call-template name=\"Action\"/>\n        </Action>\n      </xsl:if>\n    </xsl:if>\n    <xsl:if test=\"name()=&quot;StartConditions&quot;\">\n      <StartTrigger>\n        <xsl:call-template name=\"Trigger\"/>\n      </StartTrigger>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:if test=\"Action/Private/Meeting\">\n    <xsl:message terminate=\"no\">\n      WARNING: OSCPrivateAction.Meeting  is desupported: removed during migration: This may result in unvalid XML\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"Action/Global/Traffic/Jam\">\n    <xsl:message terminate=\"no\">\n      WARNING: Jam is desupported: removed during migration: This may result in unvalid XML\n    </xsl:message>\n  </xsl:if>\n  <xsl:if test=\"Action/UserDefined/Script\">\n    <xsl:message terminate=\"no\">\n      WARNING: Script is desupported: removed during migration: This may result in unvalid XML\n    </xsl:message>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='Action'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Global\"'>\n        <GlobalAction>\n          <xsl:call-template name='GlobalAction' />\n        </GlobalAction>\n      </xsl:if>\n      <xsl:if test='name()=\"UserDefined\"'>\n        <UserDefinedAction>\n          <xsl:call-template name='UserDefinedAction' />\n        </UserDefinedAction>\n      </xsl:if>\n      <xsl:if test='name()=\"Private\"'>\n        <PrivateAction>\n          <xsl:call-template name='PrivateAction' />\n        </PrivateAction>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='VehicleCategoryDistribution'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Vehicle\"'>\n        <VehicleCategoryDistributionEntry>\n          <xsl:call-template name='VehicleCategoryDistributionEntry' />\n        </VehicleCategoryDistributionEntry>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"VehicleCategoryDistributionEntry\">\n  <xsl:if test=\"@category\">\n    <xsl:attribute name=\"category\">\n      <xsl:choose>\n        <xsl:when test=\"@category='van' or @category='truck' or @category='trailer' or @category='semitrailer' or @category='bus' or @category='motorbike' or @category='bicycle' or @category='train' or @category='tram'\">\n          <xsl:value-of select=\"@category\"/>\n        </xsl:when>\n        <xsl:otherwise>\n          <xsl:value-of select=\"'car'\"/>\n        </xsl:otherwise>\n      </xsl:choose>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:if test=\"@percentage\">\n    <xsl:attribute name=\"weight\">\n      <xsl:value-of select=\"@percentage\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='ControllerDistribution'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Driver\"'>\n        <ControllerDistributionEntry>\n          <xsl:call-template name='ControllerDistributionEntry' />\n        </ControllerDistributionEntry>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"ControllerDistributionEntry\">\n  <xsl:if test=\"@percentage\">\n    <xsl:attribute name=\"weight\">\n      <xsl:value-of select=\"@percentage\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:comment>\n    Migration: Insert Controller here\n  </xsl:comment>\n  <Controller/>\n  <xsl:message terminate=\"no\">\n    ERROR: OSCTrafficDefinition.DriverDistribution.Driver cannot be migrated automatically and will result in unvalid XML output.\n  </xsl:message>\n</xsl:template>\n<xsl:template name=\"TimeOfDay\">\n  <xsl:if test=\"@animation\">\n    <xsl:attribute name=\"animation\">\n      <xsl:value-of select=\"@animation\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:variable name=\"hour\" select=\"Time/@hour\"/>\n  <xsl:variable name=\"min\" select=\"Time/@min\"/>\n  <xsl:variable name=\"sec\" select=\"Time/@sec\"/>\n  <xsl:variable name=\"day\" select=\"Date/@day\"/>\n  <xsl:variable name=\"month\" select=\"Date/@month\"/>\n  <xsl:variable name=\"year\" select=\"Date/@year\"/>\n  <xsl:attribute name=\"dateTime\">\n    <xsl:value-of select=\"format-number($year,'0000')\"/>\n    <xsl:value-of select=\"format-number($month,'-00')\"/>\n    <xsl:value-of select=\"format-number($day,'-00')\"/>\n    <xsl:value-of select=\"format-number($hour,'T00')\"/>\n    <xsl:value-of select=\"format-number($min,':00')\"/>\n    <xsl:value-of select=\"format-number($sec,':00')\"/>\n  </xsl:attribute>\n</xsl:template>\n\n  <xsl:template name='Weather'>\n    <xsl:if test='@cloudState'>\n      <xsl:attribute name='cloudState'>\n        <xsl:value-of select='@cloudState' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Sun\"'>\n        <Sun>\n          <xsl:call-template name='Sun' />\n        </Sun>\n      </xsl:if>\n      <xsl:if test='name()=\"Fog\"'>\n        <Fog>\n          <xsl:call-template name='Fog' />\n        </Fog>\n      </xsl:if>\n      <xsl:if test='name()=\"Precipitation\"'>\n        <Precipitation>\n          <xsl:call-template name='Precipitation' />\n        </Precipitation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Sun'>\n    <xsl:if test='@intensity'>\n      <xsl:attribute name='intensity'>\n        <xsl:value-of select='@intensity' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@azimuth'>\n      <xsl:attribute name='azimuth'>\n        <xsl:value-of select='@azimuth' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@elevation'>\n      <xsl:attribute name='elevation'>\n        <xsl:value-of select='@elevation' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Fog'>\n    <xsl:if test='@visualRange'>\n      <xsl:attribute name='visualRange'>\n        <xsl:value-of select='@visualRange' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"BoundingBox\"'>\n        <BoundingBox>\n          <xsl:call-template name='BoundingBox' />\n        </BoundingBox>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Precipitation'>\n    <xsl:if test='@type'>\n      <xsl:attribute name='precipitationType'>\n        <xsl:value-of select='@type' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@intensity'>\n      <xsl:attribute name='intensity'>\n        <xsl:value-of select='@intensity' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template><xsl:template name=\"RoadCondition\">\n  <xsl:if test=\"@frictionScale\">\n    <xsl:attribute name=\"frictionScaleFactor\">\n      <xsl:value-of select=\"@frictionScale\"/>\n    </xsl:attribute>\n  </xsl:if>\n</xsl:template>\n\n  <xsl:template name='SurfaceState'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@intensity'>\n      <xsl:attribute name='intensity'>\n        <xsl:value-of select='@intensity' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Waypoint'>\n    <xsl:if test='@strategy'>\n      <xsl:attribute name='routeStrategy'>\n        <xsl:value-of select='@strategy' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Position\"'>\n        <Position>\n          <xsl:call-template name='Position' />\n        </Position>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template><xsl:template name=\"Vertex\">\n  <xsl:if test=\"@reference\">\n    <xsl:attribute name=\"time\">\n      <xsl:value-of select=\"@reference\"/>\n    </xsl:attribute>\n  </xsl:if>\n  <xsl:for-each select=\"*\">\n    <xsl:if test=\"name()=&quot;Position&quot;\">\n      <Position>\n        <xsl:call-template name=\"Position\"/>\n      </Position>\n    </xsl:if>\n  </xsl:for-each>\n  <xsl:message terminate=\"no\">\n    WARNING: OSCTrajectory.Vertex: OSCTrajectory is restructured and connot be automatically migrated. Review XML.\n  </xsl:message>\n</xsl:template>\n\n  <xsl:template name='Shape'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Polyline\"'>\n        <Polyline>\n          <xsl:call-template name='Polyline' />\n        </Polyline>\n      </xsl:if>\n      <xsl:if test='name()=\"Clothoid\"'>\n        <Clothoid>\n          <xsl:call-template name='Clothoid' />\n        </Clothoid>\n      </xsl:if>\n      <xsl:if test='name()=\"Spline\"'>\n        <Spline>\n          <xsl:call-template name='Spline' />\n        </Spline>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='Polyline' />\n  <xsl:template name='Clothoid'>\n    <xsl:if test='@curvature'>\n      <xsl:attribute name='curvature'>\n        <xsl:value-of select='@curvature' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@curvatureDot'>\n      <xsl:attribute name='curvatureDot'>\n        <xsl:value-of select='@curvatureDot' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@length'>\n      <xsl:attribute name='length'>\n        <xsl:value-of select='@length' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Spline'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"ControlPoint1\"'>\n        <ControlPoint1>\n          <xsl:call-template name='ControlPoint1' />\n        </ControlPoint1>\n      </xsl:if>\n      <xsl:if test='name()=\"ControlPoint2\"'>\n        <ControlPoint2>\n          <xsl:call-template name='ControlPoint2' />\n        </ControlPoint2>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='ControlPoint1'>\n    <xsl:if test='@status'>\n      <xsl:attribute name='status'>\n        <xsl:value-of select='@status' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='ControlPoint2'>\n    <xsl:if test='@status'>\n      <xsl:attribute name='status'>\n        <xsl:value-of select='@status' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='WorldPosition'>\n    <xsl:if test='@x'>\n      <xsl:attribute name='x'>\n        <xsl:value-of select='@x' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@y'>\n      <xsl:attribute name='y'>\n        <xsl:value-of select='@y' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@z'>\n      <xsl:attribute name='z'>\n        <xsl:value-of select='@z' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@h'>\n      <xsl:attribute name='h'>\n        <xsl:value-of select='@h' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@p'>\n      <xsl:attribute name='p'>\n        <xsl:value-of select='@p' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@r'>\n      <xsl:attribute name='r'>\n        <xsl:value-of select='@r' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='RelativeWorldPosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dx'>\n      <xsl:attribute name='dx'>\n        <xsl:value-of select='@dx' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dy'>\n      <xsl:attribute name='dy'>\n        <xsl:value-of select='@dy' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dz'>\n      <xsl:attribute name='dz'>\n        <xsl:value-of select='@dz' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeObjectPosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dx'>\n      <xsl:attribute name='dx'>\n        <xsl:value-of select='@dx' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dy'>\n      <xsl:attribute name='dy'>\n        <xsl:value-of select='@dy' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dz'>\n      <xsl:attribute name='dz'>\n        <xsl:value-of select='@dz' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RoadPosition'>\n    <xsl:if test='@roadId'>\n      <xsl:attribute name='roadId'>\n        <xsl:value-of select='@roadId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@s'>\n      <xsl:attribute name='s'>\n        <xsl:value-of select='@s' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@t'>\n      <xsl:attribute name='t'>\n        <xsl:value-of select='@t' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeRoadPosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@ds'>\n      <xsl:attribute name='ds'>\n        <xsl:value-of select='@ds' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dt'>\n      <xsl:attribute name='dt'>\n        <xsl:value-of select='@dt' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='LanePosition'>\n    <xsl:if test='@roadId'>\n      <xsl:attribute name='roadId'>\n        <xsl:value-of select='@roadId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@laneId'>\n      <xsl:attribute name='laneId'>\n        <xsl:value-of select='@laneId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@offset'>\n      <xsl:attribute name='offset'>\n        <xsl:value-of select='@offset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@s'>\n      <xsl:attribute name='s'>\n        <xsl:value-of select='@s' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RelativeLanePosition'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@dLane'>\n      <xsl:attribute name='dLane'>\n        <xsl:value-of select='@dLane' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@ds'>\n      <xsl:attribute name='ds'>\n        <xsl:value-of select='@ds' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@offset'>\n      <xsl:attribute name='offset'>\n        <xsl:value-of select='@offset' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RoutePosition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"RouteRef\"'>\n        <RouteRef>\n          <xsl:call-template name='RouteRef' />\n        </RouteRef>\n      </xsl:if>\n      <xsl:if test='name()=\"Orientation\"'>\n        <Orientation>\n          <xsl:call-template name='Orientation' />\n        </Orientation>\n      </xsl:if>\n      <xsl:if test='name()=\"Position\"'>\n        <InRoutePosition>\n          <xsl:call-template name='InRoutePosition' />\n        </InRoutePosition>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='RouteRef'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Route\"'>\n        <Route>\n          <xsl:call-template name='Route' />\n        </Route>\n      </xsl:if>\n      <xsl:if test='name()=\"CatalogReference\"'>\n        <CatalogReference>\n          <xsl:call-template name='CatalogReference' />\n        </CatalogReference>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='InRoutePosition'>\n    <xsl:for-each select='*'>\n      <xsl:if test='name()=\"Current\"'>\n        <FromCurrentEntity>\n          <xsl:call-template name='PositionOfCurrentEntity' />\n        </FromCurrentEntity>\n      </xsl:if>\n      <xsl:if test='name()=\"RoadCoord\"'>\n        <FromRoadCoordinates>\n          <xsl:call-template name='PositionInRoadCoordinates' />\n        </FromRoadCoordinates>\n      </xsl:if>\n      <xsl:if test='name()=\"LaneCoord\"'>\n        <FromLaneCoordinates>\n          <xsl:call-template name='PositionInLaneCoordinates' />\n        </FromLaneCoordinates>\n      </xsl:if>\n    </xsl:for-each>\n  </xsl:template>\n  <xsl:template name='PositionOfCurrentEntity'>\n    <xsl:if test='@object'>\n      <xsl:attribute name='entityRef'>\n        <xsl:value-of select='@object' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='PositionInRoadCoordinates'>\n    <xsl:if test='@pathS'>\n      <xsl:attribute name='pathS'>\n        <xsl:value-of select='@pathS' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@t'>\n      <xsl:attribute name='t'>\n        <xsl:value-of select='@t' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='PositionInLaneCoordinates'>\n    <xsl:if test='@pathS'>\n      <xsl:attribute name='pathS'>\n        <xsl:value-of select='@pathS' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@laneId'>\n      <xsl:attribute name='laneId'>\n        <xsl:value-of select='@laneId' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@laneOffset'>\n      <xsl:attribute name='laneOffset'>\n        <xsl:value-of select='@laneOffset' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Center'>\n    <xsl:if test='@x'>\n      <xsl:attribute name='x'>\n        <xsl:value-of select='@x' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@y'>\n      <xsl:attribute name='y'>\n        <xsl:value-of select='@y' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@z'>\n      <xsl:attribute name='z'>\n        <xsl:value-of select='@z' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Dimensions'>\n    <xsl:if test='@width'>\n      <xsl:attribute name='width'>\n        <xsl:value-of select='@width' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@length'>\n      <xsl:attribute name='length'>\n        <xsl:value-of select='@length' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@height'>\n      <xsl:attribute name='height'>\n        <xsl:value-of select='@height' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n  <xsl:template name='Property'>\n    <xsl:if test='@name'>\n      <xsl:attribute name='name'>\n        <xsl:value-of select='@name' />\n      </xsl:attribute>\n    </xsl:if>\n    <xsl:if test='@value'>\n      <xsl:attribute name='value'>\n        <xsl:value-of select='@value' />\n      </xsl:attribute>\n    </xsl:if>\n  </xsl:template>\n</xsl:stylesheet>"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/openscenario/OpenSCENARIO.xsd",
    "content": "﻿<?xml version=\"1.0\" encoding=\"utf-8\"?>\n<xsd:schema xmlns:xsd=\"http://www.w3.org/2001/XMLSchema\">\n<!--\nASAM OpenSCENARIO V1.0.0\n\n© by ASAM e.V., 2020\n\nDescription of dynamic content in driving simulations\n\n\nAny use is limited to the scope described in the ASAM license terms. \nThis file is distributable in accordance with the ASAM license terms. \nSee www.asam.net/license.html for further details.\n-->\n    <xsd:element name=\"OpenSCENARIO\" type=\"OpenScenario\"/>\n\t<xsd:simpleType name=\"parameter\">\n\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t<xsd:pattern value=\"[$][A-Za-z_][A-Za-z0-9_]*\"/>\n\t\t</xsd:restriction>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Boolean\">\n\t\t<xsd:union memberTypes=\"parameter xsd:boolean\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"DateTime\">\n\t\t<xsd:union memberTypes=\"parameter xsd:dateTime\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Double\">\n\t\t<xsd:union memberTypes=\"parameter xsd:double\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Int\">\n\t\t<xsd:union memberTypes=\"parameter xsd:int\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"String\">\n\t\t<xsd:union memberTypes=\"parameter xsd:string\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"UnsignedInt\">\n\t\t<xsd:union memberTypes=\"parameter xsd:unsignedInt\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"UnsignedShort\">\n\t\t<xsd:union memberTypes=\"parameter xsd:unsignedShort\"/>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"CloudState\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"cloudy\"/>\n\t\t\t\t\t<xsd:enumeration value=\"free\"/>\n\t\t\t\t\t<xsd:enumeration value=\"overcast\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rainy\"/>\n\t\t\t\t\t<xsd:enumeration value=\"skyOff\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ConditionEdge\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"falling\"/>\n\t\t\t\t\t<xsd:enumeration value=\"none\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rising\"/>\n\t\t\t\t\t<xsd:enumeration value=\"risingOrFalling\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"DynamicsDimension\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"distance\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rate\"/>\n\t\t\t\t\t<xsd:enumeration value=\"time\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"DynamicsShape\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"cubic\"/>\n\t\t\t\t\t<xsd:enumeration value=\"linear\"/>\n\t\t\t\t\t<xsd:enumeration value=\"sinusoidal\"/>\n\t\t\t\t\t<xsd:enumeration value=\"step\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"FollowingMode\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"follow\"/>\n\t\t\t\t\t<xsd:enumeration value=\"position\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"MiscObjectCategory\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"barrier\"/>\n\t\t\t\t\t<xsd:enumeration value=\"building\"/>\n\t\t\t\t\t<xsd:enumeration value=\"crosswalk\"/>\n\t\t\t\t\t<xsd:enumeration value=\"gantry\"/>\n\t\t\t\t\t<xsd:enumeration value=\"none\"/>\n\t\t\t\t\t<xsd:enumeration value=\"obstacle\"/>\n\t\t\t\t\t<xsd:enumeration value=\"parkingSpace\"/>\n\t\t\t\t\t<xsd:enumeration value=\"patch\"/>\n\t\t\t\t\t<xsd:enumeration value=\"pole\"/>\n\t\t\t\t\t<xsd:enumeration value=\"railing\"/>\n\t\t\t\t\t<xsd:enumeration value=\"roadMark\"/>\n\t\t\t\t\t<xsd:enumeration value=\"soundBarrier\"/>\n\t\t\t\t\t<xsd:enumeration value=\"streetLamp\"/>\n\t\t\t\t\t<xsd:enumeration value=\"trafficIsland\"/>\n\t\t\t\t\t<xsd:enumeration value=\"tree\"/>\n\t\t\t\t\t<xsd:enumeration value=\"vegetation\"/>\n\t\t\t\t\t<xsd:enumeration value=\"wind\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ObjectType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"miscellaneous\"/>\n\t\t\t\t\t<xsd:enumeration value=\"pedestrian\"/>\n\t\t\t\t\t<xsd:enumeration value=\"vehicle\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ParameterType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"boolean\"/>\n\t\t\t\t\t<xsd:enumeration value=\"dateTime\"/>\n\t\t\t\t\t<xsd:enumeration value=\"double\"/>\n\t\t\t\t\t<xsd:enumeration value=\"integer\"/>\n\t\t\t\t\t<xsd:enumeration value=\"string\"/>\n\t\t\t\t\t<xsd:enumeration value=\"unsignedInt\"/>\n\t\t\t\t\t<xsd:enumeration value=\"unsignedShort\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"PedestrianCategory\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"animal\"/>\n\t\t\t\t\t<xsd:enumeration value=\"pedestrian\"/>\n\t\t\t\t\t<xsd:enumeration value=\"wheelchair\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"PrecipitationType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"dry\"/>\n\t\t\t\t\t<xsd:enumeration value=\"rain\"/>\n\t\t\t\t\t<xsd:enumeration value=\"snow\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Priority\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"overwrite\"/>\n\t\t\t\t\t<xsd:enumeration value=\"parallel\"/>\n\t\t\t\t\t<xsd:enumeration value=\"skip\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"ReferenceContext\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"absolute\"/>\n\t\t\t\t\t<xsd:enumeration value=\"relative\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"RelativeDistanceType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"cartesianDistance\"/>\n\t\t\t\t\t<xsd:enumeration value=\"lateral\"/>\n\t\t\t\t\t<xsd:enumeration value=\"longitudinal\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"RouteStrategy\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"fastest\"/>\n\t\t\t\t\t<xsd:enumeration value=\"leastIntersections\"/>\n\t\t\t\t\t<xsd:enumeration value=\"random\"/>\n\t\t\t\t\t<xsd:enumeration value=\"shortest\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"Rule\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"equalTo\"/>\n\t\t\t\t\t<xsd:enumeration value=\"greaterThan\"/>\n\t\t\t\t\t<xsd:enumeration value=\"lessThan\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"SpeedTargetValueType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"delta\"/>\n\t\t\t\t\t<xsd:enumeration value=\"factor\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"StoryboardElementState\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"completeState\"/>\n\t\t\t\t\t<xsd:enumeration value=\"endTransition\"/>\n\t\t\t\t\t<xsd:enumeration value=\"runningState\"/>\n\t\t\t\t\t<xsd:enumeration value=\"skipTransition\"/>\n\t\t\t\t\t<xsd:enumeration value=\"standbyState\"/>\n\t\t\t\t\t<xsd:enumeration value=\"startTransition\"/>\n\t\t\t\t\t<xsd:enumeration value=\"stopTransition\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"StoryboardElementType\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"act\"/>\n\t\t\t\t\t<xsd:enumeration value=\"action\"/>\n\t\t\t\t\t<xsd:enumeration value=\"event\"/>\n\t\t\t\t\t<xsd:enumeration value=\"maneuver\"/>\n\t\t\t\t\t<xsd:enumeration value=\"maneuverGroup\"/>\n\t\t\t\t\t<xsd:enumeration value=\"story\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"TriggeringEntitiesRule\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"all\"/>\n\t\t\t\t\t<xsd:enumeration value=\"any\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:simpleType name=\"VehicleCategory\">\n\t\t<xsd:union>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"xsd:string\">\n\t\t\t\t\t<xsd:enumeration value=\"bicycle\"/>\n\t\t\t\t\t<xsd:enumeration value=\"bus\"/>\n\t\t\t\t\t<xsd:enumeration value=\"car\"/>\n\t\t\t\t\t<xsd:enumeration value=\"motorbike\"/>\n\t\t\t\t\t<xsd:enumeration value=\"semitrailer\"/>\n\t\t\t\t\t<xsd:enumeration value=\"trailer\"/>\n\t\t\t\t\t<xsd:enumeration value=\"train\"/>\n\t\t\t\t\t<xsd:enumeration value=\"tram\"/>\n\t\t\t\t\t<xsd:enumeration value=\"truck\"/>\n\t\t\t\t\t<xsd:enumeration value=\"van\"/>\n\t\t\t\t</xsd:restriction>\n\t\t\t</xsd:simpleType>\n\t\t\t<xsd:simpleType>\n\t\t\t\t<xsd:restriction base=\"parameter\"/>\n\t\t\t</xsd:simpleType>\n\t\t</xsd:union>\n\t</xsd:simpleType>\n\t<xsd:complexType name=\"AbsoluteSpeed\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AbsoluteTargetLane\">\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AbsoluteTargetLaneOffset\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AbsoluteTargetSpeed\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AccelerationCondition\">\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AcquirePositionAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Act\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ManeuverGroup\" type=\"ManeuverGroup\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"StartTrigger\" type=\"Trigger\"/>\n\t\t\t<xsd:element name=\"StopTrigger\" type=\"Trigger\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Action\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"GlobalAction\" type=\"GlobalAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"UserDefinedAction\" type=\"UserDefinedAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"PrivateAction\" type=\"PrivateAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ActivateControllerAction\">\n\t\t<xsd:attribute name=\"lateral\" type=\"Boolean\"/>\n\t\t<xsd:attribute name=\"longitudinal\" type=\"Boolean\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Actors\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"selectTriggeringEntities\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AddEntityAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AssignControllerAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"AssignRouteAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Route\" type=\"Route\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Axle\">\n\t\t<xsd:attribute name=\"maxSteering\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"positionX\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"positionZ\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"trackWidth\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"wheelDiameter\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Axles\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"FrontAxle\" type=\"Axle\"/>\n\t\t\t<xsd:element name=\"RearAxle\" type=\"Axle\"/>\n\t\t\t<xsd:element name=\"AdditionalAxle\" type=\"Axle\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"BoundingBox\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Center\" type=\"Center\"/>\n\t\t\t<xsd:element name=\"Dimensions\" type=\"Dimensions\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByEntityCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TriggeringEntities\" type=\"TriggeringEntities\"/>\n\t\t\t<xsd:element name=\"EntityCondition\" type=\"EntityCondition\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByObjectType\">\n\t\t<xsd:attribute name=\"type\" type=\"ObjectType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByType\">\n\t\t<xsd:attribute name=\"objectType\" type=\"ObjectType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ByValueCondition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"ParameterCondition\" type=\"ParameterCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeOfDayCondition\" type=\"TimeOfDayCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SimulationTimeCondition\" type=\"SimulationTimeCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"StoryboardElementStateCondition\" type=\"StoryboardElementStateCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"UserDefinedValueCondition\" type=\"UserDefinedValueCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignalCondition\" type=\"TrafficSignalCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignalControllerCondition\" type=\"TrafficSignalControllerCondition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Catalog\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Vehicle\" type=\"Vehicle\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Pedestrian\" type=\"Pedestrian\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"MiscObject\" type=\"MiscObject\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Environment\" type=\"Environment\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Maneuver\" type=\"Maneuver\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Trajectory\" type=\"Trajectory\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Route\" type=\"Route\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\"/>\n\t</xsd:complexType>\n\t<xsd:group name=\"CatalogDefinition\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Catalog\" type=\"Catalog\"/>\n\t\t</xsd:sequence>\n\t</xsd:group>\n\t<xsd:complexType name=\"CatalogLocations\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"VehicleCatalog\" type=\"VehicleCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ControllerCatalog\" type=\"ControllerCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"PedestrianCatalog\" type=\"PedestrianCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"MiscObjectCatalog\" type=\"MiscObjectCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"EnvironmentCatalog\" type=\"EnvironmentCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ManeuverCatalog\" type=\"ManeuverCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrajectoryCatalog\" type=\"TrajectoryCatalogLocation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RouteCatalog\" type=\"RouteCatalogLocation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CatalogReference\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterAssignments\" type=\"ParameterAssignments\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"catalogName\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"entryName\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Center\">\n\t\t<xsd:attribute name=\"x\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"y\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"z\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CentralSwarmObject\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Clothoid\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"curvature\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"curvatureDot\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"length\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"startTime\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"stopTime\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CollisionCondition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ByType\" type=\"ByObjectType\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Condition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"ByEntityCondition\" type=\"ByEntityCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ByValueCondition\" type=\"ByValueCondition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"conditionEdge\" type=\"ConditionEdge\" use=\"required\"/>\n\t\t<xsd:attribute name=\"delay\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ConditionGroup\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Condition\" type=\"Condition\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Controller\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"AssignControllerAction\" type=\"AssignControllerAction\"/>\n\t\t\t<xsd:element name=\"OverrideControllerValueAction\" type=\"OverrideControllerValueAction\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerDistribution\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ControllerDistributionEntry\" type=\"ControllerDistributionEntry\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControllerDistributionEntry\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"weight\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ControlPoint\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"time\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"weight\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"CustomCommandAction\">\n\t\t<xsd:simpleContent>\n\t\t\t<xsd:extension base=\"xsd:string\">\n\t\t\t\t<xsd:attribute name=\"type\" type=\"String\" use=\"required\"/>\n\t\t\t</xsd:extension>\n\t\t</xsd:simpleContent>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"DeleteEntityAction\"/>\n\t<xsd:complexType name=\"Dimensions\">\n\t\t<xsd:attribute name=\"height\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"length\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"width\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Directory\">\n\t\t<xsd:attribute name=\"path\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"DistanceCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"alongRoute\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"DynamicConstraints\">\n\t\t<xsd:attribute name=\"maxAcceleration\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"maxDeceleration\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"maxSpeed\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EndOfRoadCondition\">\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Entities\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ScenarioObject\" type=\"ScenarioObject\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"EntitySelection\" type=\"EntitySelection\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EntityAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AddEntityAction\" type=\"AddEntityAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"DeleteEntityAction\" type=\"DeleteEntityAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EntityCondition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EndOfRoadCondition\" type=\"EndOfRoadCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CollisionCondition\" type=\"CollisionCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"OffroadCondition\" type=\"OffroadCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeHeadwayCondition\" type=\"TimeHeadwayCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeToCollisionCondition\" type=\"TimeToCollisionCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AccelerationCondition\" type=\"AccelerationCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"StandStillCondition\" type=\"StandStillCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SpeedCondition\" type=\"SpeedCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeSpeedCondition\" type=\"RelativeSpeedCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TraveledDistanceCondition\" type=\"TraveledDistanceCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ReachPositionCondition\" type=\"ReachPositionCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"DistanceCondition\" type=\"DistanceCondition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeDistanceCondition\" type=\"RelativeDistanceCondition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:group name=\"EntityObject\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Vehicle\" type=\"Vehicle\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Pedestrian\" type=\"Pedestrian\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"MiscObject\" type=\"MiscObject\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:group>\n\t<xsd:complexType name=\"EntityRef\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EntitySelection\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Members\" type=\"SelectedEntities\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Environment\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeOfDay\" type=\"TimeOfDay\"/>\n\t\t\t<xsd:element name=\"Weather\" type=\"Weather\"/>\n\t\t\t<xsd:element name=\"RoadCondition\" type=\"RoadCondition\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EnvironmentAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Environment\" type=\"Environment\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"EnvironmentCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Event\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Action\" type=\"Action\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"StartTrigger\" type=\"Trigger\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"maximumExecutionCount\" type=\"UnsignedInt\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"priority\" type=\"Priority\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"File\">\n\t\t<xsd:attribute name=\"filepath\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"FileHeader\">\n\t\t<xsd:attribute name=\"author\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"date\" type=\"DateTime\" use=\"required\"/>\n\t\t<xsd:attribute name=\"description\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"revMajor\" type=\"UnsignedShort\" use=\"required\"/>\n\t\t<xsd:attribute name=\"revMinor\" type=\"UnsignedShort\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"FinalSpeed\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AbsoluteSpeed\" type=\"AbsoluteSpeed\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeSpeedToMaster\" type=\"RelativeSpeedToMaster\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Fog\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"visualRange\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"FollowTrajectoryAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Trajectory\" type=\"Trajectory\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TimeReference\" type=\"TimeReference\"/>\n\t\t\t<xsd:element name=\"TrajectoryFollowingMode\" type=\"TrajectoryFollowingMode\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"GlobalAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EnvironmentAction\" type=\"EnvironmentAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"EntityAction\" type=\"EntityAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ParameterAction\" type=\"ParameterAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"InfrastructureAction\" type=\"InfrastructureAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficAction\" type=\"TrafficAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"InfrastructureAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TrafficSignalAction\" type=\"TrafficSignalAction\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Init\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Actions\" type=\"InitActions\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"InitActions\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"GlobalAction\" type=\"GlobalAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"UserDefinedAction\" type=\"UserDefinedAction\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Private\" type=\"Private\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"InRoutePosition\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"FromCurrentEntity\" type=\"PositionOfCurrentEntity\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"FromRoadCoordinates\" type=\"PositionInRoadCoordinates\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"FromLaneCoordinates\" type=\"PositionInLaneCoordinates\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Knot\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneChangeAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"LaneChangeActionDynamics\" type=\"TransitionDynamics\"/>\n\t\t\t<xsd:element name=\"LaneChangeTarget\" type=\"LaneChangeTarget\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"targetLaneOffset\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneChangeTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"RelativeTargetLane\" type=\"RelativeTargetLane\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AbsoluteTargetLane\" type=\"AbsoluteTargetLane\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneOffsetAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"LaneOffsetActionDynamics\" type=\"LaneOffsetActionDynamics\"/>\n\t\t\t<xsd:element name=\"LaneOffsetTarget\" type=\"LaneOffsetTarget\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneOffsetActionDynamics\">\n\t\t<xsd:attribute name=\"dynamicsShape\" type=\"DynamicsShape\" use=\"required\"/>\n\t\t<xsd:attribute name=\"maxLateralAcc\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LaneOffsetTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"RelativeTargetLaneOffset\" type=\"RelativeTargetLaneOffset\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AbsoluteTargetLaneOffset\" type=\"AbsoluteTargetLaneOffset\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LanePosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"laneId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"roadId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"s\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LateralAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"LaneChangeAction\" type=\"LaneChangeAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LaneOffsetAction\" type=\"LaneOffsetAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LateralDistanceAction\" type=\"LateralDistanceAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LateralDistanceAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"DynamicConstraints\" type=\"DynamicConstraints\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"distance\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LongitudinalAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"SpeedAction\" type=\"SpeedAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LongitudinalDistanceAction\" type=\"LongitudinalDistanceAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"LongitudinalDistanceAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"DynamicConstraints\" type=\"DynamicConstraints\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"distance\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"timeGap\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Maneuver\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Event\" type=\"Event\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ManeuverCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ManeuverGroup\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Actors\" type=\"Actors\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Maneuver\" type=\"Maneuver\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"maximumExecutionCount\" type=\"UnsignedInt\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"MiscObject\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"mass\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"miscObjectCategory\" type=\"MiscObjectCategory\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"MiscObjectCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ModifyRule\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AddValue\" type=\"ParameterAddValueRule\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"MultiplyByValue\" type=\"ParameterMultiplyByValueRule\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"None\"/>\n\t<xsd:complexType name=\"Nurbs\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ControlPoint\" type=\"ControlPoint\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"Knot\" type=\"Knot\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"order\" type=\"UnsignedInt\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ObjectController\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Controller\" type=\"Controller\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OffroadCondition\">\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OpenScenario\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"FileHeader\" type=\"FileHeader\"/>\n\t\t\t<xsd:group ref=\"OpenScenarioCategory\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:element name=\"OpenScenario\" type=\"OpenScenario\"/>\n\t<xsd:group name=\"OpenScenarioCategory\">\n\t\t<xsd:choice>\n\t\t\t<xsd:group ref=\"ScenarioDefinition\"/>\n\t\t\t<xsd:group ref=\"CatalogDefinition\"/>\n\t\t</xsd:choice>\n\t</xsd:group>\n\t<xsd:complexType name=\"Orientation\">\n\t\t<xsd:attribute name=\"h\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"p\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"r\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"type\" type=\"ReferenceContext\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideBrakeAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideClutchAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideControllerValueAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Throttle\" type=\"OverrideThrottleAction\"/>\n\t\t\t<xsd:element name=\"Brake\" type=\"OverrideBrakeAction\"/>\n\t\t\t<xsd:element name=\"Clutch\" type=\"OverrideClutchAction\"/>\n\t\t\t<xsd:element name=\"ParkingBrake\" type=\"OverrideParkingBrakeAction\"/>\n\t\t\t<xsd:element name=\"SteeringWheel\" type=\"OverrideSteeringWheelAction\"/>\n\t\t\t<xsd:element name=\"Gear\" type=\"OverrideGearAction\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideGearAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"number\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideParkingBrakeAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideSteeringWheelAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"OverrideThrottleAction\">\n\t\t<xsd:attribute name=\"active\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"SetAction\" type=\"ParameterSetAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ModifyAction\" type=\"ParameterModifyAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t\t<xsd:attribute name=\"parameterRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAddValueRule\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAssignment\">\n\t\t<xsd:attribute name=\"parameterRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterAssignments\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterAssignment\" type=\"ParameterAssignment\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterCondition\">\n\t\t<xsd:attribute name=\"parameterRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterDeclaration\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"parameterType\" type=\"ParameterType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterDeclarations\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclaration\" type=\"ParameterDeclaration\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterModifyAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Rule\" type=\"ModifyRule\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterMultiplyByValueRule\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ParameterSetAction\">\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Pedestrian\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"mass\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"model\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"pedestrianCategory\" type=\"PedestrianCategory\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PedestrianCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Performance\">\n\t\t<xsd:attribute name=\"maxAcceleration\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"maxDeceleration\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"maxSpeed\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Phase\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"TrafficSignalState\" type=\"TrafficSignalState\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Polyline\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Vertex\" type=\"Vertex\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Position\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"WorldPosition\" type=\"WorldPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeWorldPosition\" type=\"RelativeWorldPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeObjectPosition\" type=\"RelativeObjectPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RoadPosition\" type=\"RoadPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeRoadPosition\" type=\"RelativeRoadPosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LanePosition\" type=\"LanePosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RelativeLanePosition\" type=\"RelativeLanePosition\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RoutePosition\" type=\"RoutePosition\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PositionInLaneCoordinates\">\n\t\t<xsd:attribute name=\"laneId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"laneOffset\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"pathS\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PositionInRoadCoordinates\">\n\t\t<xsd:attribute name=\"pathS\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"t\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PositionOfCurrentEntity\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Precipitation\">\n\t\t<xsd:attribute name=\"intensity\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"precipitationType\" type=\"PrecipitationType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Private\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"PrivateAction\" type=\"PrivateAction\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"PrivateAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"LongitudinalAction\" type=\"LongitudinalAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"LateralAction\" type=\"LateralAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"VisibilityAction\" type=\"VisibilityAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SynchronizeAction\" type=\"SynchronizeAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ActivateControllerAction\" type=\"ActivateControllerAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"ControllerAction\" type=\"ControllerAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TeleportAction\" type=\"TeleportAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"RoutingAction\" type=\"RoutingAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Properties\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Property\" type=\"Property\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"File\" type=\"File\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Property\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"ReachPositionCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"tolerance\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeDistanceCondition\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"relativeDistanceType\" type=\"RelativeDistanceType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeLanePosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dLane\" type=\"Int\" use=\"required\"/>\n\t\t<xsd:attribute name=\"ds\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeObjectPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dx\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dy\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dz\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeRoadPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"ds\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dt\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeSpeedCondition\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeSpeedToMaster\">\n\t\t<xsd:attribute name=\"speedTargetValueType\" type=\"SpeedTargetValueType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeTargetLane\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Int\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeTargetLaneOffset\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeTargetSpeed\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"continuous\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"speedTargetValueType\" type=\"SpeedTargetValueType\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RelativeWorldPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dx\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dy\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dz\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoadCondition\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"frictionScaleFactor\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoadNetwork\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"LogicFile\" type=\"File\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"SceneGraphFile\" type=\"File\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignals\" type=\"TrafficSignals\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoadPosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"roadId\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"s\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"t\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Route\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Waypoint\" type=\"Waypoint\" minOccurs=\"2\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"closed\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RouteCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoutePosition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"RouteRef\" type=\"RouteRef\"/>\n\t\t\t<xsd:element name=\"Orientation\" type=\"Orientation\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"InRoutePosition\" type=\"InRoutePosition\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RouteRef\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Route\" type=\"Route\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogReference\" type=\"CatalogReference\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"RoutingAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"AssignRouteAction\" type=\"AssignRouteAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"FollowTrajectoryAction\" type=\"FollowTrajectoryAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AcquirePositionAction\" type=\"AcquirePositionAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:group name=\"ScenarioDefinition\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"CatalogLocations\" type=\"CatalogLocations\"/>\n\t\t\t<xsd:element name=\"RoadNetwork\" type=\"RoadNetwork\"/>\n\t\t\t<xsd:element name=\"Entities\" type=\"Entities\"/>\n\t\t\t<xsd:element name=\"Storyboard\" type=\"Storyboard\"/>\n\t\t</xsd:sequence>\n\t</xsd:group>\n\t<xsd:complexType name=\"ScenarioObject\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:group ref=\"EntityObject\"/>\n\t\t\t<xsd:element name=\"ObjectController\" type=\"ObjectController\" minOccurs=\"0\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SelectedEntities\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"ByType\" type=\"ByType\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Shape\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Polyline\" type=\"Polyline\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Clothoid\" type=\"Clothoid\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Nurbs\" type=\"Nurbs\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SimulationTimeCondition\">\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SpeedAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"SpeedActionDynamics\" type=\"TransitionDynamics\"/>\n\t\t\t<xsd:element name=\"SpeedActionTarget\" type=\"SpeedActionTarget\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SpeedActionTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"RelativeTargetSpeed\" type=\"RelativeTargetSpeed\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"AbsoluteTargetSpeed\" type=\"AbsoluteTargetSpeed\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SpeedCondition\">\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"StandStillCondition\">\n\t\t<xsd:attribute name=\"duration\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Story\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Act\" type=\"Act\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Storyboard\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Init\" type=\"Init\"/>\n\t\t\t<xsd:element name=\"Story\" type=\"Story\" maxOccurs=\"unbounded\"/>\n\t\t\t<xsd:element name=\"StopTrigger\" type=\"Trigger\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"StoryboardElementStateCondition\">\n\t\t<xsd:attribute name=\"storyboardElementRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"state\" type=\"StoryboardElementState\" use=\"required\"/>\n\t\t<xsd:attribute name=\"storyboardElementType\" type=\"StoryboardElementType\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Sun\">\n\t\t<xsd:attribute name=\"azimuth\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"elevation\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"intensity\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"SynchronizeAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TargetPositionMaster\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"TargetPosition\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"FinalSpeed\" type=\"FinalSpeed\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"masterEntityRef\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TeleportAction\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeHeadwayCondition\">\n\t\t<xsd:attribute name=\"entityRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"alongRoute\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeOfDay\">\n\t\t<xsd:attribute name=\"animation\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dateTime\" type=\"DateTime\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeOfDayCondition\">\n\t\t<xsd:attribute name=\"dateTime\" type=\"DateTime\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeReference\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"None\" type=\"None\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Timing\" type=\"Timing\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeToCollisionCondition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"TimeToCollisionConditionTarget\" type=\"TimeToCollisionConditionTarget\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"alongRoute\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"freespace\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TimeToCollisionConditionTarget\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Timing\">\n\t\t<xsd:attribute name=\"domainAbsoluteRelative\" type=\"ReferenceContext\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"scale\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"TrafficSourceAction\" type=\"TrafficSourceAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSinkAction\" type=\"TrafficSinkAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSwarmAction\" type=\"TrafficSwarmAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficDefinition\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"VehicleCategoryDistribution\" type=\"VehicleCategoryDistribution\"/>\n\t\t\t<xsd:element name=\"ControllerDistribution\" type=\"ControllerDistribution\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalAction\">\n\t\t<xsd:choice>\n\t\t\t<xsd:element name=\"TrafficSignalControllerAction\" type=\"TrafficSignalControllerAction\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"TrafficSignalStateAction\" type=\"TrafficSignalStateAction\" minOccurs=\"0\"/>\n\t\t</xsd:choice>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalCondition\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"state\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalController\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Phase\" type=\"Phase\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"delay\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"reference\" type=\"String\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignals\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"TrafficSignalController\" type=\"TrafficSignalController\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalControllerAction\">\n\t\t<xsd:attribute name=\"trafficSignalControllerRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"phase\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalControllerCondition\">\n\t\t<xsd:attribute name=\"trafficSignalControllerRef\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"phase\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalState\">\n\t\t<xsd:attribute name=\"state\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"trafficSignalId\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSignalStateAction\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"state\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSinkAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"TrafficDefinition\" type=\"TrafficDefinition\" minOccurs=\"0\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"radius\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rate\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSourceAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t\t<xsd:element name=\"TrafficDefinition\" type=\"TrafficDefinition\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"radius\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rate\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"velocity\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrafficSwarmAction\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"CentralObject\" type=\"CentralSwarmObject\"/>\n\t\t\t<xsd:element name=\"TrafficDefinition\" type=\"TrafficDefinition\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"innerRadius\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"numberOfVehicles\" type=\"UnsignedInt\" use=\"required\"/>\n\t\t<xsd:attribute name=\"offset\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"semiMajorAxis\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"semiMinorAxis\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"velocity\" type=\"Double\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Trajectory\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"Shape\" type=\"Shape\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"closed\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrajectoryCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TrajectoryFollowingMode\">\n\t\t<xsd:attribute name=\"followingMode\" type=\"FollowingMode\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TransitionDynamics\">\n\t\t<xsd:attribute name=\"dynamicsDimension\" type=\"DynamicsDimension\" use=\"required\"/>\n\t\t<xsd:attribute name=\"dynamicsShape\" type=\"DynamicsShape\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TraveledDistanceCondition\">\n\t\t<xsd:attribute name=\"value\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Trigger\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"ConditionGroup\" type=\"ConditionGroup\" minOccurs=\"0\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"TriggeringEntities\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"EntityRef\" type=\"EntityRef\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"triggeringEntitiesRule\" type=\"TriggeringEntitiesRule\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"UserDefinedAction\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"CustomCommandAction\" type=\"CustomCommandAction\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"UserDefinedValueCondition\">\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"rule\" type=\"Rule\" use=\"required\"/>\n\t\t<xsd:attribute name=\"value\" type=\"String\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Vehicle\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"ParameterDeclarations\" type=\"ParameterDeclarations\" minOccurs=\"0\"/>\n\t\t\t<xsd:element name=\"BoundingBox\" type=\"BoundingBox\"/>\n\t\t\t<xsd:element name=\"Performance\" type=\"Performance\"/>\n\t\t\t<xsd:element name=\"Axles\" type=\"Axles\"/>\n\t\t\t<xsd:element name=\"Properties\" type=\"Properties\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"name\" type=\"String\" use=\"required\"/>\n\t\t<xsd:attribute name=\"vehicleCategory\" type=\"VehicleCategory\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VehicleCatalogLocation\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Directory\" type=\"Directory\"/>\n\t\t</xsd:all>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VehicleCategoryDistribution\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"VehicleCategoryDistributionEntry\" type=\"VehicleCategoryDistributionEntry\" maxOccurs=\"unbounded\"/>\n\t\t</xsd:sequence>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VehicleCategoryDistributionEntry\">\n\t\t<xsd:attribute name=\"category\" type=\"VehicleCategory\" use=\"required\"/>\n\t\t<xsd:attribute name=\"weight\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Vertex\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"time\" type=\"Double\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"VisibilityAction\">\n\t\t<xsd:attribute name=\"graphics\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"sensors\" type=\"Boolean\" use=\"required\"/>\n\t\t<xsd:attribute name=\"traffic\" type=\"Boolean\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Waypoint\">\n\t\t<xsd:sequence>\n\t\t\t<xsd:element name=\"Position\" type=\"Position\"/>\n\t\t</xsd:sequence>\n\t\t<xsd:attribute name=\"routeStrategy\" type=\"RouteStrategy\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"Weather\">\n\t\t<xsd:all>\n\t\t\t<xsd:element name=\"Sun\" type=\"Sun\"/>\n\t\t\t<xsd:element name=\"Fog\" type=\"Fog\"/>\n\t\t\t<xsd:element name=\"Precipitation\" type=\"Precipitation\"/>\n\t\t</xsd:all>\n\t\t<xsd:attribute name=\"cloudState\" type=\"CloudState\" use=\"required\"/>\n\t</xsd:complexType>\n\t<xsd:complexType name=\"WorldPosition\">\n\t\t<xsd:attribute name=\"h\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"p\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"r\" type=\"Double\"/>\n\t\t<xsd:attribute name=\"x\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"y\" type=\"Double\" use=\"required\"/>\n\t\t<xsd:attribute name=\"z\" type=\"Double\"/>\n\t</xsd:complexType>\n</xsd:schema>\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarioconfigs/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarioconfigs/openscenario_configuration.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the key configuration parameters for a scenario based on OpenSCENARIO\n\"\"\"\n\nimport logging\nimport os\nimport xml.etree.ElementTree as ET\n\nimport xmlschema\n\nimport carla\n\n# pylint: disable=line-too-long\nfrom srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData, ScenarioConfiguration\n# pylint: enable=line-too-long\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider  # workaround\nfrom srunner.tools.openscenario_parser import OpenScenarioParser, ParameterRef\n\n\nclass OpenScenarioConfiguration(ScenarioConfiguration):\n\n    \"\"\"\n    Limitations:\n    - Only one Story + Init is supported per Storyboard\n    \"\"\"\n\n    def __init__(self, filename, client, custom_params):\n\n        super(OpenScenarioConfiguration, self).__init__()\n\n        self.xml_tree = ET.parse(filename)\n        self.filename = filename\n        self._custom_params = custom_params if custom_params is not None else {}\n\n        self._validate_openscenario_configuration()\n        self.client = client\n\n        self.catalogs = {}\n\n        self.other_actors = []\n        self.ego_vehicles = []\n        self.trigger_points = []\n        self.weather = carla.WeatherParameters()\n\n        self.storyboard = self.xml_tree.find(\"Storyboard\")\n        self.stories = self.storyboard.findall(\"Story\")\n        self.init = self.storyboard.find(\"Init\")\n\n        logging.basicConfig()\n        self.logger = logging.getLogger(\"[SR:OpenScenarioConfiguration]\")\n\n        self._global_parameters = {}\n\n        self._set_parameters()\n        self._parse_openscenario_configuration()\n\n    def _validate_openscenario_configuration(self):\n        \"\"\"\n        Validate the given OpenSCENARIO config against the 1.0 XSD\n\n        Note: This will throw if the config is not valid. But this is fine here.\n        \"\"\"\n        xsd_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), \"../openscenario/OpenSCENARIO.xsd\")\n        xsd = xmlschema.XMLSchema(xsd_file)\n        xsd.validate(self.xml_tree)\n\n    def _validate_openscenario_catalog_configuration(self, catalog_xml_tree):\n        \"\"\"\n        Validate the given OpenSCENARIO catalog config against the 1.0 XSD\n\n        Note: This will throw if the catalog config is not valid. But this is fine here.\n        \"\"\"\n        xsd_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), \"../openscenario/OpenSCENARIO.xsd\")\n        xsd = xmlschema.XMLSchema(xsd_file)\n        xsd.validate(catalog_xml_tree)\n\n    def _parse_openscenario_configuration(self):\n        \"\"\"\n        Parse the given OpenSCENARIO config file, set and validate parameters\n        \"\"\"\n        OpenScenarioParser.set_osc_filepath(os.path.dirname(self.filename))\n\n        self._check_version()\n        self._load_catalogs()\n        self._set_scenario_name()\n        self._set_carla_town()\n        self._set_actor_information()\n\n        self._validate_result()\n\n    def _check_version(self):\n        \"\"\"\n        Ensure correct OpenSCENARIO version is used\n        \"\"\"\n        header = self.xml_tree.find(\"FileHeader\")\n        if not (header.attrib.get('revMajor') == \"1\" and header.attrib.get('revMinor') == \"0\"):\n            raise AttributeError(\"Only OpenSCENARIO 1.0 is supported\")\n\n    def _load_catalogs(self):\n        \"\"\"\n        Read Catalog xml files into dictionary for later use\n\n        NOTE: Catalogs must have distinct names, even across different types\n        \"\"\"\n        catalogs = self.xml_tree.find(\"CatalogLocations\")\n        if list(catalogs) is None:\n            return\n\n        catalog_types = [\"Vehicle\",\n                         \"Controller\",\n                         \"Pedestrian\",\n                         \"MiscObject\",\n                         \"Environment\",\n                         \"Maneuver\",\n                         \"Trajectory\",\n                         \"Route\"]\n        for catalog_type in catalog_types:\n            catalog = catalogs.find(catalog_type + \"Catalog\")\n            if catalog is None:\n                continue\n\n            catalog_path = catalog.find(\"Directory\").attrib.get('path') + \"/\" + catalog_type + \"Catalog.xosc\"\n            if not os.path.isabs(catalog_path) and \"xosc\" in self.filename:\n                catalog_path = os.path.dirname(os.path.abspath(self.filename)) + \"/\" + catalog_path\n\n            if not os.path.isfile(catalog_path):\n                self.logger.warning(\" The %s path for the %s Catalog is invalid\", catalog_path, catalog_type)\n            else:\n                xml_tree = ET.parse(catalog_path)\n                self._validate_openscenario_catalog_configuration(xml_tree)\n                catalog = xml_tree.find(\"Catalog\")\n                catalog_name = catalog.attrib.get(\"name\")\n                self.catalogs[catalog_name] = {}\n                for entry in catalog:\n                    self.catalogs[catalog_name][entry.attrib.get(\"name\")] = entry\n\n    def _set_scenario_name(self):\n        \"\"\"\n        Extract the scenario name from the OpenSCENARIO header information\n        \"\"\"\n        header = self.xml_tree.find(\"FileHeader\")\n        self.name = header.attrib.get('description', 'Unknown')\n\n        if self.name.startswith(\"CARLA:\"):\n            self.name = self.name[6:]\n            OpenScenarioParser.set_use_carla_coordinate_system()\n\n    def _set_carla_town(self):\n        \"\"\"\n        Extract the CARLA town (level) from the RoadNetwork information from OpenSCENARIO\n\n        Note: The specification allows multiple Logics elements within the RoadNetwork element.\n              Hence, there can be multiple towns specified. We just use the _last_ one.\n        \"\"\"\n        for logic in self.xml_tree.find(\"RoadNetwork\").findall(\"LogicFile\"):\n            self.town = logic.attrib.get('filepath', None)\n\n        if self.town is not None and \".xodr\" in self.town:\n            if not os.path.isabs(self.town):\n                self.town = os.path.dirname(os.path.abspath(self.filename)) + \"/\" + self.town\n            if not os.path.exists(self.town):\n                raise AttributeError(\"The provided RoadNetwork '{}' does not exist\".format(self.town))\n\n        # workaround for relative positions during init\n        world = self.client.get_world()\n        wmap = None\n        if world:\n            world.get_settings()\n            wmap = world.get_map()\n\n        if world is None or (wmap is not None and wmap.name.split('/')[-1] != self.town):\n            if \".xodr\" in self.town:\n                with open(self.town, 'r', encoding='utf-8') as od_file:\n                    data = od_file.read()\n                index = data.find('<OpenDRIVE>')\n                data = data[index:]\n\n                old_map = \"\"\n                if wmap is not None:\n                    old_map = wmap.to_opendrive()\n                    index = old_map.find('<OpenDRIVE>')\n                    old_map = old_map[index:]\n\n                if data != old_map:\n                    self.logger.warning(\" Wrong OpenDRIVE map in use. Forcing reload of CARLA world\")\n\n                    vertex_distance = 2.0  # in meters\n                    wall_height = 1.0      # in meters\n                    extra_width = 0.6      # in meters\n                    world = self.client.generate_opendrive_world(str(data),\n                                                                 carla.OpendriveGenerationParameters(\n                                                                 vertex_distance=vertex_distance,\n                                                                 wall_height=wall_height,\n                                                                 additional_width=extra_width,\n                                                                 smooth_junctions=True,\n                                                                 enable_mesh_visibility=True))\n            else:\n                self.logger.warning(\" Wrong map in use. Forcing reload of CARLA world\")\n                self.client.load_world(self.town)\n                world = self.client.get_world()\n\n            CarlaDataProvider.set_world(world)\n            if CarlaDataProvider.is_sync_mode():\n                world.tick()\n            else:\n                world.wait_for_tick()\n        else:\n            CarlaDataProvider.set_world(world)\n\n    def _set_parameters(self):\n        \"\"\"\n        Parse the complete scenario definition file, and replace all parameter references\n        with the actual values\n\n        Set _global_parameters.\n        \"\"\"\n        self.xml_tree, self._global_parameters = OpenScenarioParser.set_parameters(self.xml_tree, self._custom_params)\n\n        for elem in self.xml_tree.iter():\n            if elem.find('ParameterDeclarations') is not None:\n                elem, _ = OpenScenarioParser.set_parameters(elem)\n\n        OpenScenarioParser.set_global_parameters(self._global_parameters)\n\n    def _set_actor_information(self):\n        \"\"\"\n        Extract all actors and their corresponding specification\n\n        NOTE: The rolename property has to be unique!\n        \"\"\"\n        for entity in self.xml_tree.iter(\"Entities\"):\n            for obj in entity.iter(\"ScenarioObject\"):\n                rolename = obj.attrib.get('name', 'simulation')\n                args = {}\n                for prop in obj.iter(\"Property\"):\n                    key = prop.get('name')\n                    value = prop.get('value')\n                    args[key] = value\n\n                for catalog_reference in obj.iter(\"CatalogReference\"):\n                    entry = OpenScenarioParser.get_catalog_entry(self.catalogs, catalog_reference)\n                    if entry.tag == \"Vehicle\":\n                        self._extract_vehicle_information(entry, rolename, entry, args)\n                    elif entry.tag == \"Pedestrian\":\n                        self._extract_pedestrian_information(entry, rolename, entry, args)\n                    elif entry.tag == \"MiscObject\":\n                        self._extract_misc_information(entry, rolename, entry, args)\n                    else:\n                        self.logger.debug(\n                            \" A CatalogReference specifies a reference that is not an Entity. Skipping...\")\n\n                for vehicle in obj.iter(\"Vehicle\"):\n                    self._extract_vehicle_information(obj, rolename, vehicle, args)\n\n                for pedestrian in obj.iter(\"Pedestrian\"):\n                    self._extract_pedestrian_information(obj, rolename, pedestrian, args)\n\n                for misc in obj.iter(\"MiscObject\"):\n                    self._extract_misc_information(obj, rolename, misc, args)\n\n        # Set transform for all actors\n        # This has to be done in a multi-stage loop to resolve relative position settings\n        all_actor_transforms_set = False\n        while not all_actor_transforms_set:\n            all_actor_transforms_set = True\n            for actor in self.other_actors + self.ego_vehicles:\n                if actor.transform is None:\n                    try:\n                        actor.transform = self._get_actor_transform(actor.rolename)\n                    except AttributeError as e:\n                        if \"Object '\" in str(e):\n                            ref_actor_rolename = str(e).split('\\'')[1]\n                            for ref_actor in self.other_actors + self.ego_vehicles:\n                                if ref_actor.rolename == ref_actor_rolename:\n                                    if ref_actor.transform is not None:\n                                        raise e\n                                    break\n                        else:\n                            raise e\n                    if actor.transform is None:\n                        all_actor_transforms_set = False\n\n    def _extract_vehicle_information(self, obj, rolename, vehicle, args):\n        \"\"\"\n        Helper function to _set_actor_information for getting vehicle information from XML tree\n        \"\"\"\n        color = None\n        model = vehicle.attrib.get('name', \"vehicle.*\")\n        category = vehicle.attrib.get('vehicleCategory', \"car\")\n        ego_vehicle = False\n        for prop in obj.iter(\"Property\"):\n            if prop.get('name', '') == 'type':\n                ego_vehicle = prop.get('value') == 'ego_vehicle'\n            if prop.get('name', '') == 'color':\n                color = prop.get('value')\n\n        speed = self._get_actor_speed(rolename)\n        new_actor = ActorConfigurationData(\n            model, None, rolename, speed, color=color, category=category, args=args)\n\n        if ego_vehicle:\n            self.ego_vehicles.append(new_actor)\n        else:\n            self.other_actors.append(new_actor)\n\n    def _extract_pedestrian_information(self, obj, rolename, pedestrian, args):\n        \"\"\"\n        Helper function to _set_actor_information for getting pedestrian information from XML tree\n        \"\"\"\n        model = pedestrian.attrib.get('model', \"walker.*\")\n\n        speed = self._get_actor_speed(rolename)\n        new_actor = ActorConfigurationData(model, None, rolename, speed, category=\"pedestrian\", args=args)\n\n        self.other_actors.append(new_actor)\n\n    def _extract_misc_information(self, obj, rolename, misc, args):\n        \"\"\"\n        Helper function to _set_actor_information for getting vehicle information from XML tree\n        \"\"\"\n        category = misc.attrib.get('miscObjectCategory')\n        if category == \"barrier\":\n            model = \"static.prop.streetbarrier\"\n        elif category == \"guardRail\":\n            model = \"static.prop.chainbarrier\"\n        else:\n            model = misc.attrib.get('name')\n        new_actor = ActorConfigurationData(model, None, rolename, category=\"misc\", args=args)\n\n        self.other_actors.append(new_actor)\n\n    def _get_actor_transform(self, actor_name):\n        \"\"\"\n        Get the initial actor transform provided by the Init section\n\n        Note: - The OpenScenario specification allows multiple definitions. We use the _first_ one\n              - The OpenScenario specification allows different ways of specifying a position.\n                We currently support the specification with absolute world coordinates and the relative positions\n                RelativeWorld, RelativeObject and RelativeLane\n              - When using relative positions the relevant reference point (e.g. transform of another actor)\n                should be defined before!\n        \"\"\"\n\n        actor_transform = carla.Transform()\n\n        actor_found = False\n\n        for private_action in self.init.iter(\"Private\"):\n            if private_action.attrib.get('entityRef', None) == actor_name:\n                if actor_found:\n                    # pylint: disable=line-too-long\n                    self.logger.warning(\n                        \" Warning: The actor '%s' was already assigned an initial position. Overwriting pose!\", actor_name)\n                    # pylint: enable=line-too-long\n                actor_found = True\n                for position in private_action.iter('Position'):\n                    transform = OpenScenarioParser.convert_position_to_transform(\n                        position, actor_list=self.other_actors + self.ego_vehicles)\n                    if transform:\n                        actor_transform = transform\n\n        if not actor_found:\n            # pylint: disable=line-too-long\n            self.logger.warning(\n                \" Warning: The actor '%s' was not assigned an initial position. Using (0,0,0)\", actor_name)\n            # pylint: enable=line-too-long\n\n        return actor_transform\n\n    def _get_actor_speed(self, actor_name):\n        \"\"\"\n        Get the initial actor speed provided by the Init section\n        \"\"\"\n        actor_speed = 0\n        actor_found = False\n\n        for private_action in self.init.iter(\"Private\"):\n            if private_action.attrib.get('entityRef', None) == actor_name:\n                if actor_found:\n                    # pylint: disable=line-too-long\n                    self.logger.warning(\n                        \" Warning: The actor '%s' was already assigned an initial speed. Overwriting inital speed!\", actor_name)\n                    # pylint: enable=line-too-long\n                actor_found = True\n\n                for longitudinal_action in private_action.iter('LongitudinalAction'):\n                    for speed in longitudinal_action.iter('SpeedAction'):\n                        for target in speed.iter('SpeedActionTarget'):\n                            for absolute in target.iter('AbsoluteTargetSpeed'):\n                                speed = float(ParameterRef(absolute.attrib.get('value', 0)))\n                                if speed >= 0:\n                                    actor_speed = speed\n                                else:\n                                    raise AttributeError(\n                                        \"Warning: Speed value of actor {} must be positive. Speed set to 0.\".format(actor_name))  # pylint: disable=line-too-long\n        return actor_speed\n\n    def _validate_result(self):\n        \"\"\"\n        Check that the current scenario configuration is valid\n        \"\"\"\n        if not self.name:\n            raise AttributeError(\"No scenario name found\")\n\n        if not self.town:\n            raise AttributeError(\"CARLA level not defined\")\n\n        if not self.ego_vehicles:\n            self.logger.warning(\" No ego vehicles defined in scenario\")\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarioconfigs/route_scenario_configuration.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the key configuration parameters for a route-based scenario\n\"\"\"\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration\n\n\nclass RouteConfiguration(object):\n\n    \"\"\"\n    This class provides the basic  configuration for a route\n    \"\"\"\n\n    def __init__(self, route=None):\n        self.data = route\n\n    def parse_xml(self, node):\n        \"\"\"\n        Parse route config XML\n        \"\"\"\n        self.data = []\n\n        for waypoint in node.iter(\"waypoint\"):\n            x = float(waypoint.attrib.get('x', 0))\n            y = float(waypoint.attrib.get('y', 0))\n            z = float(waypoint.attrib.get('z', 0))\n            c = waypoint.attrib.get('connection', '')\n            connection = RoadOption[c.split('.')[1]]\n\n            self.data.append((carla.Location(x, y, z), connection))\n\n\nclass RouteScenarioConfiguration(ScenarioConfiguration):\n\n    \"\"\"\n    Basic configuration of a RouteScenario\n    \"\"\"\n\n    def __init__(self):\n        super(RouteScenarioConfiguration, self).__init__()\n        self.keypoints = None\n        self.scenario_configs = []\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarioconfigs/scenario_configuration.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the key configuration parameters for an XML-based scenario\n\"\"\"\n\nimport carla\n\n\nclass ActorConfigurationData(object):\n\n    \"\"\"\n    This is a configuration base class to hold model and transform attributes\n    \"\"\"\n\n    def __init__(self, model, transform, rolename='other', speed=0, autopilot=False,\n                 random=False, color=None, category=\"car\", args=None):\n        self.model = model\n        self.rolename = rolename\n        self.transform = transform\n        self.speed = speed\n        self.autopilot = autopilot\n        self.random_location = random\n        self.color = color\n        self.category = category\n        self.args = args\n\n    @staticmethod\n    def parse_from_node(node, rolename):\n        \"\"\"\n        static method to initialize an ActorConfigurationData from a given ET tree\n        \"\"\"\n\n        model = node.attrib.get('model', 'vehicle.*')\n\n        pos_x = float(node.attrib.get('x', 0))\n        pos_y = float(node.attrib.get('y', 0))\n        pos_z = float(node.attrib.get('z', 0))\n        yaw = float(node.attrib.get('yaw', 0))\n\n        transform = carla.Transform(carla.Location(x=pos_x, y=pos_y, z=pos_z), carla.Rotation(yaw=yaw))\n\n        rolename = node.attrib.get('rolename', rolename)\n\n        speed = node.attrib.get('speed', 0)\n\n        autopilot = False\n        if 'autopilot' in node.keys():\n            autopilot = True\n\n        random_location = False\n        if 'random_location' in node.keys():\n            random_location = True\n\n        color = node.attrib.get('color', None)\n\n        return ActorConfigurationData(model, transform, rolename, speed, autopilot, random_location, color)\n\n    @staticmethod\n    def parse_from_dict(actor_dict, rolename):\n        \"\"\"\n        static method to initialize an ActorConfigurationData from a given ET tree\n        \"\"\"\n\n        model = actor_dict['model'] if 'model' in actor_dict else 'vehicle.*'\n\n        pos_x = float(actor_dict['x']) if 'x' in actor_dict else 0\n        pos_y = float(actor_dict['y']) if 'y' in actor_dict else 0\n        pos_z = float(actor_dict['z']) if 'z' in actor_dict else 0\n        yaw = float(actor_dict['yaw']) if 'yaw' in actor_dict else 0\n        transform = carla.Transform(carla.Location(x=pos_x, y=pos_y, z=pos_z), carla.Rotation(yaw=yaw))\n\n        rolename = actor_dict['rolename'] if 'rolename' in actor_dict else rolename\n        speed = actor_dict['speed'] if 'speed' in actor_dict else 0\n        autopilot = actor_dict['autopilot'] if 'autopilot' in actor_dict else False\n        random_location = actor_dict['random_location'] if 'random_location' in actor_dict else False\n        color = actor_dict['color'] if 'color' in actor_dict else None\n\n        return ActorConfigurationData(model, transform, rolename, speed, autopilot, random_location, color)\n\n\nclass ScenarioConfiguration(object):\n\n    \"\"\"\n    This class provides a basic scenario configuration incl.:\n    - configurations for all actors\n    - town, where the scenario should be executed\n    - name of the scenario (e.g. ControlLoss_1)\n    - type is the class of scenario (e.g. ControlLoss)\n    \"\"\"\n\n    def __init__(self):\n        self.trigger_points = []\n        self.ego_vehicles = []\n        self.other_actors = []\n        self.other_parameters = {}\n        self.town = None\n        self.name = None\n        self.type = None\n        self.route = None\n        self.agent = None\n        self.weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)\n        self.friction = None\n        self.subtype = None\n        self.route_var_name = None\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/actor_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a wrapper to access/use user-defined actor\ncontrols for example to realize OpenSCENARIO controllers.\n\nAt the moment only controls implemented in Python are supported.\n\nA user must not modify this module.\n\"\"\"\n\nimport importlib\nimport os\nimport sys\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.external_control import ExternalControl\nfrom srunner.scenariomanager.actorcontrols.npc_vehicle_control import NpcVehicleControl\nfrom srunner.scenariomanager.actorcontrols.pedestrian_control import PedestrianControl\n\n\nclass ActorControl(object):\n\n    \"\"\"\n    This class provides a wrapper (access mechanism) for user-defined actor controls.\n    The controllers are loaded via importlib. Therefore, the module name of the controller\n    has to match the control class name (e.g. my_own_control.py and MyOwnControl()).\n\n    At the moment only controllers implemented in Python are supported, or controllers that\n    are completely implemented outside of ScenarioRunner (see ExternalControl).\n\n    This wrapper is for example used to realize the OpenSCENARIO controllers.\n\n    Note:\n       If no controllers are provided in OpenSCENARIO a default controller for vehicles and\n       pedestrians is instantiated. For vehicles the NpcVehicleControl is used, for pedestrians\n       it is the PedestrianControl.\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the controller.\n        control_py_module (string): Fully qualified path to the controller python module.\n        args (dict): A dictionary containing all parameters of the controller as (key, value) pairs.\n        scenario_file_path (string): Path to search for the controller implementation.\n\n    Attributes:\n        control_instance: Instance of the user-defined controller.\n        _last_longitudinal_command: Timestamp of the last issued longitudinal control command (e.g. target speed).\n            Defaults to None. Used to avoid that 2 longitudinal control commands are issued at the same time.\n        _last_waypoint_command: Timestamp of the last issued waypoint control command.\n            Defaults to None. Used to avoid that 2 waypoint control commands are issued at the same time.\n    \"\"\"\n\n    control_instance = None\n\n    _last_longitudinal_command = None\n    _last_waypoint_command = None\n    _last_lane_offset_command = None\n\n    def __init__(self, actor, control_py_module, args, scenario_file_path):\n\n        # use importlib to import the control module\n        if not control_py_module:\n            if isinstance(actor, carla.Walker):\n                self.control_instance = PedestrianControl(actor)\n            elif isinstance(actor, carla.Vehicle):\n                self.control_instance = NpcVehicleControl(actor)\n            else:\n                # use ExternalControl for all misc objects to handle all actors the same way\n                self.control_instance = ExternalControl(actor)\n        else:\n            if scenario_file_path:\n                sys.path.append(scenario_file_path)\n            if \".py\" in control_py_module:\n                module_name = os.path.basename(control_py_module).split('.')[0]\n                sys.path.append(os.path.dirname(control_py_module))\n                module_control = importlib.import_module(module_name)\n                control_class_name = module_control.__name__.title().replace('_', '')\n            else:\n                sys.path.append(os.path.dirname(__file__))\n                module_control = importlib.import_module(control_py_module)\n                control_class_name = control_py_module.split('.')[-1].title().replace('_', '')\n\n            self.control_instance = getattr(module_control, control_class_name)(actor, args)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        self.control_instance.reset()\n\n    def update_target_speed(self, target_speed, start_time=None):\n        \"\"\"\n        Update the actor's target speed.\n\n        Args:\n            target_speed (float): New target speed [m/s].\n            start_time (float): Start time of the new \"maneuver\" [s].\n        \"\"\"\n        self.control_instance.update_target_speed(target_speed)\n        if start_time:\n            self._last_longitudinal_command = start_time\n\n    def update_waypoints(self, waypoints, start_time=None):\n        \"\"\"\n        Update the actor's waypoints\n\n        Args:\n            waypoints (List of carla.Transform): List of new waypoints.\n            start_time (float): Start time of the new \"maneuver\" [s].\n        \"\"\"\n        self.control_instance.update_waypoints(waypoints)\n        if start_time:\n            self._last_waypoint_command = start_time\n\n    def update_offset(self, offset, start_time=None):\n        \"\"\"\n        Update the actor's offset\n\n        Args:\n            offset (float): Value of the new offset.\n            start_time (float): Start time of the new \"maneuver\" [s].\n        \"\"\"\n        self.control_instance.update_offset(offset)\n        if start_time:\n            self._last_waypoint_command = start_time\n            self._last_lane_offset_command = start_time\n\n    def check_reached_waypoint_goal(self):\n        \"\"\"\n        Check if the actor reached the end of the waypoint list\n\n        returns:\n            True if the end was reached, False otherwise.\n        \"\"\"\n        return self.control_instance.check_reached_waypoint_goal()\n\n    def get_last_longitudinal_command(self):\n        \"\"\"\n        Get timestamp of the last issued longitudinal control command (target_speed)\n\n        returns:\n            Timestamp of last longitudinal control command\n        \"\"\"\n        return self._last_longitudinal_command\n\n    def get_last_waypoint_command(self):\n        \"\"\"\n        Get timestamp of the last issued waypoint control command\n\n        returns:\n            Timestamp of last waypoint control command\n        \"\"\"\n        return self._last_waypoint_command\n\n    def get_last_lane_offset_command(self):\n        \"\"\"\n        Get timestamp of the last issued lane offset control command\n\n        returns:\n            Timestamp of last lane offset control command\n        \"\"\"\n        return self._last_lane_offset_command\n\n    def set_init_speed(self):\n        \"\"\"\n        Update the actor's initial speed setting\n        \"\"\"\n        self.control_instance.set_init_speed()\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n        \"\"\"\n        self.control_instance.run_step()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/basic_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the base class for user-defined actor\ncontrollers. All user-defined controls must be derived from\nthis class.\n\nA user must not modify the module.\n\"\"\"\n\n\nclass BasicControl(object):\n\n    \"\"\"\n    This class is the base class for user-defined actor controllers\n    All user-defined agents must be derived from this class.\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the controller.\n\n    Attributes:\n        _actor (carla.Actor): Controlled actor.\n            Defaults to None.\n        _target_speed (float): Logitudinal target speed of the controller.\n            Defaults to 0.\n        _init_speed (float): Initial longitudinal speed of the controller.\n            Defaults to 0.\n        _waypoints (list of carla.Transform): List of target waypoints the actor\n            should travel along. A waypoint here is of type carla.Transform!\n            Defaults to [].\n        _waypoints_updated (boolean):\n            Defaults to False.\n        _reached_goal (boolean):\n            Defaults to False.\n    \"\"\"\n\n    _actor = None\n    _waypoints = []\n    _waypoints_updated = False\n    _offset = 0\n    _offset_updated = False\n    _target_speed = 0\n    _reached_goal = False\n    _init_speed = False\n\n    def __init__(self, actor):\n        \"\"\"\n        Initialize the actor\n        \"\"\"\n        self._actor = actor\n\n    def update_target_speed(self, speed):\n        \"\"\"\n        Update the actor's target speed and set _init_speed to False.\n\n        Args:\n            speed (float): New target speed [m/s].\n        \"\"\"\n        self._target_speed = speed\n        self._init_speed = False\n\n    def update_waypoints(self, waypoints, start_time=None):\n        \"\"\"\n        Update the actor's waypoints\n\n        Args:\n            waypoints (List of carla.Transform): List of new waypoints.\n        \"\"\"\n        self._waypoints = waypoints\n        self._waypoints_updated = True\n\n    def update_offset(self, offset, start_time=None):\n        \"\"\"\n        Update the actor's waypoints\n\n        Args:\n            waypoints (List of carla.Transform): List of new waypoints.\n        \"\"\"\n        self._offset = offset\n        self._offset_updated = True\n\n    def set_init_speed(self):\n        \"\"\"\n        Set _init_speed to True\n        \"\"\"\n        self._init_speed = True\n\n    def check_reached_waypoint_goal(self):\n        \"\"\"\n        Check if the actor reached the end of the waypoint list\n\n        returns:\n            True if the end was reached, False otherwise.\n        \"\"\"\n        return self._reached_goal\n\n    def reset(self):\n        \"\"\"\n        Pure virtual function to reset the controller. This should be implemented\n        in the user-defined agent implementation.\n        \"\"\"\n        raise NotImplementedError(\n            \"This function must be re-implemented by the user-defined actor control.\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n\n    def run_step(self):\n        \"\"\"\n        Pure virtual function to run one step of the controllers's control loop.\n        This should be implemented in the user-defined agent implementation.\n        \"\"\"\n        raise NotImplementedError(\n            \"This function must be re-implemented by the user-defined actor control.\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/carla_autopilot.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for vehicles which\nuse CARLA's autopilot functionality\n\nLimitations:\n- No direct velocity control\n- No lateral maneuvers can be enforced\n\"\"\"\n\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass CarlaAutoPilotControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller uses CARLA's autopilot functionality. As a result,\n    the vehicle respects other traffic participants and traffic rules.\n    However, no longitudinal or lateral maneuvers can be enforced.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n        args (dictionary): Dictonary of (key, value) arguments to be used by the controller.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(CarlaAutoPilotControl, self).__init__(actor)\n        self._actor.set_autopilot(enabled=True)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        self._actor.set_autopilot(enabled=False)\n\n    def run_step(self):\n        \"\"\"\n        Everything is controlled through CARLA's autopilot functionality.\n        Nothing to do here\n        \"\"\"\n        pass\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/external_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example controller for actors, that use an external\nsoftware for longitudinal and lateral control command calculation.\nExamples for external controls are: Autoware, CARLA manual_control, etc.\n\nThis module is not intended for modification.\n\"\"\"\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass ExternalControl(BasicControl):\n\n    \"\"\"\n    Actor control class for actors, with externally implemented longitudinal and\n    lateral controlers (e.g. Autoware).\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the agent.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(ExternalControl, self).__init__(actor)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        The control loop and setting the actor controls is implemented externally.\n        \"\"\"\n        pass\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/npc_vehicle_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for vehicles\n\"\"\"\n\nimport math\n\nimport carla\nfrom agents.navigation.basic_agent import LocalPlanner\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass NpcVehicleControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller makes use of the LocalPlanner implemented in CARLA.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n    \"\"\"\n\n    _args = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05}\n\n    def __init__(self, actor, args=None):\n        super(NpcVehicleControl, self).__init__(actor)\n\n        self._local_planner = LocalPlanner(  # pylint: disable=undefined-variable\n            self._actor, opt_dict={\n                'target_speed': self._target_speed * 3.6,\n                'lateral_control_dict': self._args})\n\n        if self._waypoints:\n            self._update_plan()\n\n        self._brake_lights_active = False\n\n    def _update_plan(self):\n        \"\"\"\n        Update the plan (waypoint list) of the LocalPlanner\n        \"\"\"\n        plan = []\n        for transform in self._waypoints:\n            waypoint = CarlaDataProvider.get_map().get_waypoint(\n                transform.location, project_to_road=True, lane_type=carla.LaneType.Any)\n            plan.append((waypoint, RoadOption.LANEFOLLOW))\n        self._local_planner.set_global_plan(plan)\n\n    def _update_offset(self):\n        \"\"\"\n        Update the plan (waypoint list) of the LocalPlanner\n        \"\"\"\n        self._local_planner._vehicle_controller._lat_controller._offset = self._offset   # pylint: disable=protected-access\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            if self._local_planner:\n                self._local_planner.reset_vehicle()\n                self._local_planner = None\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        Note: Negative target speeds are not yet supported.\n              Try using simple_vehicle_control or vehicle_longitudinal_control.\n\n        If _waypoints are provided, the vehicle moves towards the next waypoint\n        with the given _target_speed, until reaching the final waypoint. Upon reaching\n        the final waypoint, _reached_goal is set to True.\n\n        If _waypoints is empty, the vehicle moves in its current direction with\n        the given _target_speed.\n\n        If _init_speed is True, the control command is post-processed to ensure that\n        the initial actor velocity is maintained independent of physics.\n        \"\"\"\n        self._reached_goal = False\n\n        if self._waypoints_updated:\n            self._waypoints_updated = False\n            self._update_plan()\n\n        if self._offset_updated:\n            self._offset_updated = False\n            self._update_offset()\n\n        target_speed = self._target_speed\n        # If target speed is negavite, raise an exception\n        if target_speed < 0:\n            raise NotImplementedError(\"Negative target speeds are not yet supported\")\n\n        self._local_planner.set_speed(target_speed * 3.6)\n        control = self._local_planner.run_step(debug=False)\n\n        # Check if the actor reached the end of the plan\n        if self._local_planner.done():\n            self._reached_goal = True\n\n        self._actor.apply_control(control)\n\n        current_speed = math.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2)\n\n        if self._init_speed:\n\n            # If _init_speed is set, and the PID controller is not yet up to the point to take over,\n            # we manually set the vehicle to drive with the correct velocity\n            if abs(target_speed - current_speed) > 3:\n                yaw = self._actor.get_transform().rotation.yaw * (math.pi / 180)\n                vx = math.cos(yaw) * target_speed\n                vy = math.sin(yaw) * target_speed\n                self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0))\n\n        # Change Brake light state\n        if (current_speed > target_speed or target_speed < 0.2) and not self._brake_lights_active:\n            light_state = self._actor.get_light_state()\n            light_state |= carla.VehicleLightState.Brake\n            self._actor.set_light_state(carla.VehicleLightState(light_state))\n            self._brake_lights_active = True\n\n        if self._brake_lights_active and current_speed < target_speed:\n            self._brake_lights_active = False\n            light_state = self._actor.get_light_state()\n            light_state &= ~carla.VehicleLightState.Brake\n            self._actor.set_light_state(carla.VehicleLightState(light_state))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/pedestrian_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for pedestrians\n\"\"\"\n\nimport math\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass PedestrianControl(BasicControl):\n\n    \"\"\"\n    Controller class for pedestrians derived from BasicControl.\n\n    Args:\n        actor (carla.Actor): Pedestrian actor that should be controlled.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        if not isinstance(actor, carla.Walker):\n            raise RuntimeError(\"PedestrianControl: The to be controlled actor is not a pedestrian\")\n\n        super(PedestrianControl, self).__init__(actor)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        Note: Walkers / pedestrians are not able to walk backwards.\n\n        If _waypoints are provided, the pedestrian moves towards the next waypoint\n        with the given _target_speed, until reaching the final waypoint. Upon reaching\n        the final waypoint, _reached_goal is set to True.\n\n        If _waypoints is empty, the pedestrians moves in its current direction with\n        the given _target_speed.\n        \"\"\"\n        if not self._actor or not self._actor.is_alive:\n            return\n\n        control = self._actor.get_control()\n        control.speed = self._target_speed\n\n        # If target speed is negavite, raise an exception\n        if self._target_speed < 0:\n            raise NotImplementedError(\"Negative target speeds are not yet supported\")\n\n        if self._waypoints:\n            self._reached_goal = False\n            location = self._waypoints[0].location\n            direction = location - self._actor.get_location()\n            direction_norm = math.sqrt(direction.x**2 + direction.y**2)\n            control.direction = direction / direction_norm\n            self._actor.apply_control(control)\n            if direction_norm < 1.0:\n                self._waypoints = self._waypoints[1:]\n                if not self._waypoints:\n                    self._reached_goal = True\n        else:\n            control.direction = self._actor.get_transform().rotation.get_forward_vector()\n            self._actor.apply_control(control)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020-2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example control for vehicles which\ndoes not use CARLA's vehicle engine.\n\nLimitations:\n- Does not respect any traffic regulation: speed limit, priorities, etc.\n- Can only consider obstacles in forward facing reaching (i.e. in tight corners obstacles may be ignored).\n\"\"\"\n\nfrom distutils.util import strtobool\nimport math\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\nfrom srunner.scenariomanager.actorcontrols.visualizer import Visualizer\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\n\nclass SimpleVehicleControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller directly sets velocities in CARLA, therefore bypassing\n    CARLA's vehicle engine. This allows a very precise speed control, but comes\n    with limitations during cornering.\n\n    In addition, the controller can consider blocking obstacles, which are\n    classified as dynamic (i.e. vehicles, bikes, pedestrians). Activation of this\n    features is controlled by passing proper arguments to the class constructor.\n    The collision detection uses CARLA's obstacle sensor (sensor.other.obstacle),\n    which checks for obstacles in the direct forward channel of the vehicle, i.e.\n    there are limitation with sideways obstacles and while cornering.\n\n    The controller can also respect red traffic lights, and use a given deceleration\n    value for more realistic behavior. Both behaviors are activated via the corresponding\n    controller arguments.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n        args (dictionary): Dictonary of (key, value) arguments to be used by the controller.\n                           May include: (consider_obstacles, true/false)     - Enable consideration of obstacles\n                                        (proximity_threshold, distance)      - Distance in front of actor in which\n                                                                               obstacles are considered\n                                        (consider_trafficlights, true/false) - Enable consideration of traffic lights\n                                        (max_deceleration, float)            - Use a reasonable deceleration value for\n                                                                               this vehicle\n                                        (max_acceleration, float)            - Use a reasonable acceleration value for\n                                                                               this vehicle\n                                        (attach_camera, true/false)          - Attach OpenCV display to actor\n                                                                               (useful for debugging)\n\n    Attributes:\n\n        _generated_waypoint_list (list of carla.Transform): List of target waypoints the actor\n            should travel along. A waypoint here is of type carla.Transform!\n            Defaults to [].\n        _last_update (float): Last time step the update function (tick()) was called.\n            Defaults to None.\n        _consider_obstacles (boolean): Enable/Disable consideration of obstacles\n            Defaults to False.\n        _proximity_threshold (float): Distance in front of actor in which obstacles are considered\n            Defaults to infinity.\n        _cv_image (CV Image): Contains the OpenCV image, in case a debug camera is attached to the actor\n            Defaults to None.\n        _camera (sensor.camera.rgb): Debug camera attached to actor\n            Defaults to None.\n        _obstacle_sensor (sensor.other.obstacle): Obstacle sensor attached to actor\n            Defaults to None.\n        _obstacle_distance (float): Distance of the closest obstacle returned by the obstacle sensor\n            Defaults to infinity.\n        _obstacle_actor (carla.Actor): Closest obstacle returned by the obstacle sensor\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(SimpleVehicleControl, self).__init__(actor)\n        self._generated_waypoint_list = []\n        self._last_update = None\n        self._consider_traffic_lights = False\n        self._consider_obstacles = False\n        self._proximity_threshold = float('inf')\n        self._max_deceleration = None\n        self._max_acceleration = None\n\n        self._obstacle_sensor = None\n        self._obstacle_distance = float('inf')\n        self._obstacle_actor = None\n\n        self._visualizer = None\n\n        self._brake_lights_active = False\n\n        if args and 'consider_obstacles' in args and strtobool(args['consider_obstacles']):\n            self._consider_obstacles = strtobool(args['consider_obstacles'])\n            bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.other.obstacle')\n            bp.set_attribute('distance', '250')\n            if args and 'proximity_threshold' in args:\n                self._proximity_threshold = float(args['proximity_threshold'])\n                bp.set_attribute('distance', str(max(float(args['proximity_threshold']), 250)))\n            bp.set_attribute('hit_radius', '1')\n            bp.set_attribute('only_dynamics', 'True')\n            self._obstacle_sensor = CarlaDataProvider.get_world().spawn_actor(\n                bp, carla.Transform(carla.Location(x=self._actor.bounding_box.extent.x, z=1.0)), attach_to=self._actor)\n            self._obstacle_sensor.listen(lambda event: self._on_obstacle(event))  # pylint: disable=unnecessary-lambda\n\n        if args and 'consider_trafficlights' in args and strtobool(args['consider_trafficlights']):\n            self._consider_traffic_lights = strtobool(args['consider_trafficlights'])\n\n        if args and 'max_deceleration' in args:\n            self._max_deceleration = float(args['max_deceleration'])\n\n        if args and 'max_acceleration' in args:\n            self._max_acceleration = float(args['max_acceleration'])\n\n        if args and 'attach_camera' in args and strtobool(args['attach_camera']):\n            self._visualizer = Visualizer(self._actor)\n\n    def _on_obstacle(self, event):\n        \"\"\"\n        Callback for the obstacle sensor\n\n        Sets _obstacle_distance and _obstacle_actor according to the closest obstacle\n        found by the sensor.\n        \"\"\"\n        if not event:\n            return\n        self._obstacle_distance = event.distance\n        self._obstacle_actor = event.other_actor\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n\n        if self._visualizer:\n            self._visualizer.reset()\n        if self._obstacle_sensor:\n            self._obstacle_sensor.destroy()\n            self._obstacle_sensor = None\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        If _waypoints are provided, the vehicle moves towards the next waypoint\n        with the given _target_speed, until reaching the final waypoint. Upon reaching\n        the final waypoint, _reached_goal is set to True.\n\n        If _waypoints is empty, the vehicle moves in its current direction with\n        the given _target_speed.\n\n        For further details see :func:`_set_new_velocity`\n        \"\"\"\n\n        if self._reached_goal:\n            # Reached the goal, so stop\n            velocity = carla.Vector3D(0, 0, 0)\n            self._actor.set_target_velocity(velocity)\n            return\n\n        if self._visualizer:\n            self._visualizer.render()\n\n        self._reached_goal = False\n\n        if not self._waypoints:\n            # No waypoints are provided, so we have to create a list of waypoints internally\n            # get next waypoints from map, to avoid leaving the road\n            self._reached_goal = False\n\n            map_wp = None\n            if not self._generated_waypoint_list:\n                map_wp = CarlaDataProvider.get_map().get_waypoint(CarlaDataProvider.get_location(self._actor))\n            else:\n                map_wp = CarlaDataProvider.get_map().get_waypoint(self._generated_waypoint_list[-1].location)\n            while len(self._generated_waypoint_list) < 50:\n                map_wps = map_wp.next(2.0)\n                if map_wps:\n                    self._generated_waypoint_list.append(map_wps[0].transform)\n                    map_wp = map_wps[0]\n                else:\n                    break\n\n            # Remove all waypoints that are too close to the vehicle\n            while (self._generated_waypoint_list and\n                   self._generated_waypoint_list[0].location.distance(self._actor.get_location()) < 0.5):\n                self._generated_waypoint_list = self._generated_waypoint_list[1:]\n\n            direction_norm = self._set_new_velocity(self._offset_waypoint(self._generated_waypoint_list[0]))\n            if direction_norm < 2.0:\n                self._generated_waypoint_list = self._generated_waypoint_list[1:]\n        else:\n            # When changing from \"free\" driving without pre-defined waypoints to a defined route with waypoints\n            # it may happen that the first few waypoints are too close to the ego vehicle for obtaining a\n            # reasonable control command. Therefore, we drop these waypoints first.\n            while self._waypoints and self._waypoints[0].location.distance(self._actor.get_location()) < 0.5:\n                self._waypoints = self._waypoints[1:]\n\n            self._reached_goal = False\n            if not self._waypoints:\n                self._reached_goal = True\n            else:\n                direction_norm = self._set_new_velocity(self._offset_waypoint(self._waypoints[0]))\n                if direction_norm < 4.0:\n                    self._waypoints = self._waypoints[1:]\n                    if not self._waypoints:\n                        self._reached_goal = True\n\n    def _offset_waypoint(self, transform):\n        \"\"\"\n        Given a transform (which should be the position of a waypoint), displaces it to the side,\n        according to a given offset\n\n        Args:\n            transform (carla.Transform): Transform to be moved\n\n        returns:\n            offset_location (carla.Transform): Moved transform\n        \"\"\"\n        if self._offset == 0:\n            offset_location = transform.location\n        else:\n            right_vector = transform.get_right_vector()\n            offset_location = transform.location + carla.Location(x=self._offset*right_vector.x,\n                                                                  y=self._offset*right_vector.y)\n\n        return offset_location\n\n    def _set_new_velocity(self, next_location):\n        \"\"\"\n        Calculate and set the new actor veloctiy given the current actor\n        location and the _next_location_\n\n        If _consider_obstacles is true, the speed is adapted according to the closest\n        obstacle in front of the actor, if it is within the _proximity_threshold distance.\n        If _consider_trafficlights is true, the vehicle will enforce a stop at a red\n        traffic light.\n        If _max_deceleration is set, the vehicle will reduce its speed according to the\n        given deceleration value.\n        If the vehicle reduces its speed, braking lights will be activated.\n\n        Args:\n            next_location (carla.Location): Next target location of the actor\n\n        returns:\n            direction (carla.Vector3D): Length of direction vector of the actor\n        \"\"\"\n\n        current_time = GameTime.get_time()\n        target_speed = self._target_speed\n\n        if not self._last_update:\n            self._last_update = current_time\n\n        current_speed = math.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2)\n\n        if self._consider_obstacles:\n            # If distance is less than the proximity threshold, adapt velocity\n            if self._obstacle_distance < self._proximity_threshold:\n                distance = max(self._obstacle_distance, 0)\n                if distance > 0:\n                    current_speed_other = math.sqrt(\n                        self._obstacle_actor.get_velocity().x**2 + self._obstacle_actor.get_velocity().y**2)\n                    if current_speed_other < current_speed:\n                        acceleration = -0.5 * (current_speed - current_speed_other)**2 / distance\n                        target_speed = max(acceleration * (current_time - self._last_update) + current_speed, 0)\n                else:\n                    target_speed = 0\n\n        if self._consider_traffic_lights:\n            if (self._actor.is_at_traffic_light() and\n                    self._actor.get_traffic_light_state() == carla.TrafficLightState.Red):\n                target_speed = 0\n\n        if target_speed < current_speed:\n            if not self._brake_lights_active:\n                self._brake_lights_active = True\n                light_state = self._actor.get_light_state()\n                light_state |= carla.VehicleLightState.Brake\n                self._actor.set_light_state(carla.VehicleLightState(light_state))\n            if self._max_deceleration is not None:\n                target_speed = max(target_speed, current_speed - (current_time -\n                                                                  self._last_update) * self._max_deceleration)\n        else:\n            if self._brake_lights_active:\n                self._brake_lights_active = False\n                light_state = self._actor.get_light_state()\n                light_state &= ~carla.VehicleLightState.Brake\n                self._actor.set_light_state(carla.VehicleLightState(light_state))\n            if self._max_acceleration is not None:\n                tmp_speed = min(target_speed, current_speed + (current_time -\n                                                               self._last_update) * self._max_acceleration)\n                # If the tmp_speed is < 0.5 the vehicle may not properly accelerate.\n                # Therefore, we bump the speed to 0.5 m/s if target_speed allows.\n                target_speed = max(tmp_speed, min(0.5, target_speed))\n\n        # set new linear velocity\n        velocity = carla.Vector3D(0, 0, 0)\n        direction = next_location - CarlaDataProvider.get_location(self._actor)\n        direction_norm = math.sqrt(direction.x**2 + direction.y**2)\n        velocity.x = direction.x / direction_norm * target_speed\n        velocity.y = direction.y / direction_norm * target_speed\n\n        self._actor.set_target_velocity(velocity)\n\n        # set new angular velocity\n        current_yaw = CarlaDataProvider.get_transform(self._actor).rotation.yaw\n        # When we have a waypoint list, use the direction between the waypoints to calculate the heading (change)\n        # otherwise use the waypoint heading directly\n        if self._waypoints:\n            delta_yaw = math.degrees(math.atan2(direction.y, direction.x)) - current_yaw\n        else:\n            new_yaw = CarlaDataProvider.get_map().get_waypoint(next_location).transform.rotation.yaw\n            delta_yaw = new_yaw - current_yaw\n\n        if math.fabs(delta_yaw) > 360:\n            delta_yaw = delta_yaw % 360\n\n        if delta_yaw > 180:\n            delta_yaw = delta_yaw - 360\n        elif delta_yaw < -180:\n            delta_yaw = delta_yaw + 360\n\n        angular_velocity = carla.Vector3D(0, 0, 0)\n        if target_speed == 0:\n            angular_velocity.z = 0\n        else:\n            angular_velocity.z = delta_yaw / (direction_norm / target_speed)\n        self._actor.set_target_angular_velocity(angular_velocity)\n\n        self._last_update = current_time\n\n        return direction_norm\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/vehicle_longitudinal_control.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an example longitudinal control for vehicles\n\"\"\"\n\nimport math\n\nimport carla\n\nfrom srunner.scenariomanager.actorcontrols.basic_control import BasicControl\n\n\nclass VehicleLongitudinalControl(BasicControl):\n\n    \"\"\"\n    Controller class for vehicles derived from BasicControl.\n\n    The controller only controls the throttle of a vehicle, but not the steering.\n\n    Args:\n        actor (carla.Actor): Vehicle actor that should be controlled.\n    \"\"\"\n\n    def __init__(self, actor, args=None):\n        super(VehicleLongitudinalControl, self).__init__(actor)\n\n    def reset(self):\n        \"\"\"\n        Reset the controller\n        \"\"\"\n        if self._actor and self._actor.is_alive:\n            self._actor = None\n\n    def run_step(self):\n        \"\"\"\n        Execute on tick of the controller's control loop\n\n        The control loop is very simplistic:\n            If the actor speed is below the _target_speed, set throttle to 1.0,\n            otherwise, set throttle to 0.0\n        Note: This is a longitudinal controller only.\n\n        If _init_speed is True, the control command is post-processed to ensure that\n        the initial actor velocity is maintained independent of physics.\n        \"\"\"\n\n        control = self._actor.get_control()\n\n        velocity = self._actor.get_velocity()\n        current_speed = math.sqrt(velocity.x**2 + velocity.y**2)\n        if current_speed < self._target_speed and self._target_speed >= 0:\n            control.reverse = False\n            control.throttle = 1.0\n        elif current_speed > self._target_speed and self._target_speed < 0:\n            control.reverse = True\n            control.throttle = 1.0\n        else:\n            control.throttle = 0.0\n\n        self._actor.apply_control(control)\n\n        if self._init_speed:\n            if abs(self._target_speed - current_speed) > 3:\n                yaw = self._actor.get_transform().rotation.yaw * (math.pi / 180)\n                vx = math.cos(yaw) * self._target_speed\n                vy = math.sin(yaw) * self._target_speed\n                self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0))\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/actorcontrols/visualizer.py",
    "content": "#!/usr/bin/python\n\n# Copyright (c) 2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides an OpenCV based visualizer for camera sensors\nattached to an actor.\n\nThe modul can for example be used inside an OSC Actor controller,\nsuch as simple_vehicle_control.py\n\nIt can also be used as blueprint to implement custom visualizers.\n\"\"\"\n\nimport cv2\nimport numpy as np\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass Visualizer(object):\n\n    \"\"\"\n    Visualizer class for actor controllers.\n\n    The class provides a birdeye camera and a camera mounted in the front\n    bumper of the actor. The resolution is 1000x400 for both RGB cameras.\n\n    To use this class, it is only required to:\n    1. Add an instance inside the controller constructor\n        visualizer = Visualizer(actor)\n    2. Call the render method on a regular basis\n        visualizer.render()\n    3. Call the reset method during cleanup\n        visualizer.reset()\n\n    Args:\n        actor (carla.Actor): Vehicle actor the cameras should be attached to.\n\n    Attributes:\n        _actor (carla.Actor): The reference actor\n        _cv_image_bird (numpy array): OpenCV image for the birdeye camera\n        _cv_image_actor (numpy array): OpenCV image for the bumper camera\n        _camera_bird (carla.Camera): Birdeye camera\n        _camera_actor (carla.Camera): Bumper camera\n        _video_writer (boolean): Flag to disable/enable writing the image stream into a video\n    \"\"\"\n\n    _video_writer = False\n\n    def __init__(self, actor):\n        self._actor = actor\n        self._cv_image_bird = None\n        self._cv_image_actor = None\n        self._camera_bird = None\n        self._camera_actor = None\n\n        bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.camera.rgb')\n        bp.set_attribute('image_size_x', '1000')\n        bp.set_attribute('image_size_y', '400')\n        self._camera_bird = CarlaDataProvider.get_world().spawn_actor(bp, carla.Transform(\n            carla.Location(x=20.0, z=50.0), carla.Rotation(pitch=-90, yaw=-90)), attach_to=self._actor)\n        self._camera_bird.listen(lambda image: self._on_camera_update(\n            image, birdseye=True))  # pylint: disable=unnecessary-lambda\n\n        bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.camera.rgb')\n        bp.set_attribute('image_size_x', '1000')\n        bp.set_attribute('image_size_y', '400')\n        self._camera_actor = CarlaDataProvider.get_world().spawn_actor(bp, carla.Transform(\n            carla.Location(x=2.3, z=1.0)), attach_to=self._actor)\n        self._camera_actor.listen(lambda image: self._on_camera_update(\n            image, birdseye=False))  # pylint: disable=unnecessary-lambda\n\n        if self._video_writer:\n            fourcc = cv2.VideoWriter_fourcc(*'mp4v')\n            self._video = cv2.VideoWriter('recorded_video.avi', fourcc, 13, (1000, 800))\n\n    def reset(self):\n        \"\"\"\n        Reset cameras\n        \"\"\"\n        if self._camera_bird:\n            self._camera_bird.destroy()\n            self._camera_bird = None\n        if self._camera_actor:\n            self._camera_actor.destroy()\n            self._camera_actor = None\n\n    def _on_camera_update(self, image, birdseye):\n        \"\"\"\n        Callback for the camera sensor\n\n        Sets the OpenCV image (_cv_image). Requires conversion from BGRA to RGB.\n        \"\"\"\n        if not image:\n            return\n\n        image_data = np.frombuffer(image.raw_data, dtype=np.dtype(\"uint8\"))\n        np_image = np.reshape(image_data, (image.height, image.width, 4))\n        np_image = np_image[:, :, :3]\n        np_image = np_image[:, :, ::-1]\n        if not birdseye:\n            self._cv_image_actor = cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB)\n        else:\n            self._cv_image_bird = cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB)\n\n    def render(self):\n        \"\"\"\n        Render images in an OpenCV window (has to be called on a regular basis)\n        \"\"\"\n        if self._cv_image_actor is not None and self._cv_image_bird is not None:\n            im_v = cv2.vconcat([self._cv_image_actor, self._cv_image_bird])\n            cv2.circle(im_v, (900, 300), 80, (170, 170, 170), -1)\n            text = str(int(round((self._actor.get_velocity().x * 3.6))))+\" kph\"\n\n            speed = np.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2)\n\n            text = str(int(round((speed * 3.6))))+\" kph\"\n            text = ' '*(7-len(text)) + text\n            im_v = cv2.putText(im_v, text, (830, 310), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 0), 2, cv2.LINE_AA)\n            cv2.imshow(\"\", im_v)\n            cv2.waitKey(1)\n\n            if self._video_writer:\n                self._video.write(im_v)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/carla_data_provider.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all frequently used data from CARLA via\nlocal buffers to avoid blocking calls to CARLA\n\"\"\"\n\nfrom __future__ import print_function\n\nimport math\nimport re\nimport threading\nfrom numpy import random\nfrom six import iteritems\n\nimport carla\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\n\ndef calculate_velocity(actor):\n    \"\"\"\n    Method to calculate the velocity of a actor\n    \"\"\"\n    velocity_squared = actor.get_velocity().x**2\n    velocity_squared += actor.get_velocity().y**2\n    return math.sqrt(velocity_squared)\n\n\nclass CarlaDataProvider(object):  # pylint: disable=too-many-public-methods\n\n    \"\"\"\n    This class provides access to various data of all registered actors\n    It buffers the data and updates it on every CARLA tick\n\n    Currently available data:\n    - Absolute velocity\n    - Location\n    - Transform\n\n    Potential additions:\n    - Acceleration\n\n    In addition it provides access to the map and the transform of all traffic lights\n    \"\"\"\n\n    _actor_velocity_map = {}\n    _actor_location_map = {}\n    _actor_transform_map = {}\n    _traffic_light_map = {}\n    _carla_actor_pool = {}\n    _global_osc_parameters = {}\n    _client = None\n    _world = None\n    _map = None\n    _sync_flag = False\n    _spawn_points = None\n    _spawn_index = 0\n    _blueprint_library = None\n    _all_actors = None\n    _ego_vehicle_route = None\n    _traffic_manager_port = 8000\n    _random_seed = 2000\n    _rng = random.RandomState(_random_seed)\n    _grp = None\n    _runtime_init_flag = False\n    _lock = threading.Lock()\n\n    @staticmethod\n    def register_actor(actor, transform=None):\n        \"\"\"\n        Add new actor to dictionaries\n        If actor already exists, throw an exception\n        \"\"\"\n        with CarlaDataProvider._lock:\n            if actor in CarlaDataProvider._actor_velocity_map:\n                raise KeyError(\n                    \"Vehicle '{}' already registered. Cannot register twice!\".format(actor.id))\n            else:\n                CarlaDataProvider._actor_velocity_map[actor] = 0.0\n            if actor in CarlaDataProvider._actor_location_map:\n                raise KeyError(\n                    \"Vehicle '{}' already registered. Cannot register twice!\".format(actor.id))\n            elif transform:\n                CarlaDataProvider._actor_location_map[actor] = transform.location\n            else:\n                CarlaDataProvider._actor_location_map[actor] = None\n\n            if actor in CarlaDataProvider._actor_transform_map:\n                raise KeyError(\n                    \"Vehicle '{}' already registered. Cannot register twice!\".format(actor.id))\n            else:\n                CarlaDataProvider._actor_transform_map[actor] = transform\n\n    @staticmethod\n    def update_osc_global_params(parameters):\n        \"\"\"\n        updates/initializes global osc parameters.\n        \"\"\"\n        CarlaDataProvider._global_osc_parameters.update(parameters)\n\n    @staticmethod\n    def get_osc_global_param_value(ref):\n        \"\"\"\n        returns updated global osc parameter value.\n        \"\"\"\n        return CarlaDataProvider._global_osc_parameters.get(ref.replace(\"$\", \"\"))\n\n    @staticmethod\n    def register_actors(actors, transforms=None):\n        \"\"\"\n        Add new set of actors to dictionaries\n        \"\"\"\n        if transforms is None:\n            transforms = [None] * len(actors)\n\n        for actor, transform in zip(actors, transforms):\n            CarlaDataProvider.register_actor(actor, transform)\n\n    @staticmethod\n    def on_carla_tick():\n        \"\"\"\n        Callback from CARLA\n        \"\"\"\n        with CarlaDataProvider._lock:\n            for actor in CarlaDataProvider._actor_velocity_map:\n                if actor is not None and actor.is_alive:\n                    CarlaDataProvider._actor_velocity_map[actor] = calculate_velocity(actor)\n\n            for actor in CarlaDataProvider._actor_location_map:\n                if actor is not None and actor.is_alive:\n                    CarlaDataProvider._actor_location_map[actor] = actor.get_location()\n\n            for actor in CarlaDataProvider._actor_transform_map:\n                if actor is not None and actor.is_alive:\n                    CarlaDataProvider._actor_transform_map[actor] = actor.get_transform()\n\n            world = CarlaDataProvider._world\n            if world is None:\n                print(\"WARNING: CarlaDataProvider couldn't find the world\")\n\n            CarlaDataProvider._all_actors = None\n\n    @staticmethod\n    def get_velocity(actor):\n        \"\"\"\n        returns the absolute velocity for the given actor\n        \"\"\"\n        for key in CarlaDataProvider._actor_velocity_map:\n            if key.id == actor.id:\n                return CarlaDataProvider._actor_velocity_map[key]\n\n        # We are intentionally not throwing here\n        # This may cause exception loops in py_trees\n        print('{}.get_velocity: {} not found!' .format(__name__, actor))\n        return 0.0\n\n    @staticmethod\n    def get_location(actor):\n        \"\"\"\n        returns the location for the given actor\n        \"\"\"\n        for key in CarlaDataProvider._actor_location_map:\n            if key.id == actor.id:\n                return CarlaDataProvider._actor_location_map[key]\n\n        # We are intentionally not throwing here\n        # This may cause exception loops in py_trees\n        print('{}.get_location: {} not found!' .format(__name__, actor))\n        return None\n\n    @staticmethod\n    def get_transform(actor):\n        \"\"\"\n        returns the transform for the given actor\n        \"\"\"\n        for key in CarlaDataProvider._actor_transform_map:\n            if key.id == actor.id:\n                return CarlaDataProvider._actor_transform_map[key]\n\n        # We are intentionally not throwing here\n        # This may cause exception loops in py_trees\n        print('{}.get_transform: {} not found!' .format(__name__, actor))\n        return None\n\n    @staticmethod\n    def set_client(client):\n        \"\"\"\n        Set the CARLA client\n        \"\"\"\n        CarlaDataProvider._client = client\n\n    @staticmethod\n    def get_client():\n        \"\"\"\n        Get the CARLA client\n        \"\"\"\n        return CarlaDataProvider._client\n\n    @staticmethod\n    def set_world(world):\n        \"\"\"\n        Set the world and world settings\n        \"\"\"\n        CarlaDataProvider._world = world\n        CarlaDataProvider._sync_flag = world.get_settings().synchronous_mode\n        CarlaDataProvider._map = world.get_map()\n        CarlaDataProvider._blueprint_library = world.get_blueprint_library()\n        CarlaDataProvider._grp = GlobalRoutePlanner(CarlaDataProvider._map, 2.0)\n        CarlaDataProvider.generate_spawn_points()\n        CarlaDataProvider.prepare_map()\n\n    @staticmethod\n    def get_world():\n        \"\"\"\n        Return world\n        \"\"\"\n        return CarlaDataProvider._world\n\n    @staticmethod\n    def get_map(world=None):\n        \"\"\"\n        Get the current map\n        \"\"\"\n        if CarlaDataProvider._map is None:\n            if world is None:\n                if CarlaDataProvider._world is None:\n                    raise ValueError(\"class member \\'world'\\' not initialized yet\")\n                else:\n                    CarlaDataProvider._map = CarlaDataProvider._world.get_map()\n            else:\n                CarlaDataProvider._map = world.get_map()\n\n        return CarlaDataProvider._map\n\n    @staticmethod\n    def get_random_seed():\n        \"\"\"\n        @return the random seed.\n        \"\"\"\n        return CarlaDataProvider._rng\n\n    @staticmethod\n    def get_global_route_planner():\n        \"\"\"\n        @return the global route planner\n        \"\"\"\n        return CarlaDataProvider._grp\n\n    @staticmethod\n    def get_all_actors():\n        \"\"\"\n        @return all the world actors. This is an expensive call, hence why it is part of the CDP,\n        but as this might not be used by everyone, only get the actors the first time someone\n        calls asks for them. 'CarlaDataProvider._all_actors' is reset each tick to None.\n        \"\"\"\n        if CarlaDataProvider._all_actors:\n            return CarlaDataProvider._all_actors\n\n        CarlaDataProvider._all_actors = CarlaDataProvider._world.get_actors()\n        return CarlaDataProvider._all_actors\n\n    @staticmethod\n    def is_sync_mode():\n        \"\"\"\n        @return true if syncronuous mode is used\n        \"\"\"\n        return CarlaDataProvider._sync_flag\n\n    @staticmethod\n    def set_runtime_init_mode(flag):\n        \"\"\"\n        Set the runtime init mode\n        \"\"\"\n        CarlaDataProvider._runtime_init_flag = flag\n\n    @staticmethod\n    def is_runtime_init_mode():\n        \"\"\"\n        @return true if runtime init mode is used\n        \"\"\"\n        return CarlaDataProvider._runtime_init_flag\n\n    @staticmethod\n    def find_weather_presets():\n        \"\"\"\n        Get weather presets from CARLA\n        \"\"\"\n        rgx = re.compile('.+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)')\n        name = lambda x: ' '.join(m.group(0) for m in rgx.finditer(x))\n        presets = [x for x in dir(carla.WeatherParameters) if re.match('[A-Z].+', x)]\n        return [(getattr(carla.WeatherParameters, x), name(x)) for x in presets]\n\n    @staticmethod\n    def prepare_map():\n        \"\"\"\n        This function set the current map and loads all traffic lights for this map to\n        _traffic_light_map\n        \"\"\"\n        if CarlaDataProvider._map is None:\n            CarlaDataProvider._map = CarlaDataProvider._world.get_map()\n\n        # Parse all traffic lights\n        CarlaDataProvider._traffic_light_map.clear()\n        for traffic_light in CarlaDataProvider._world.get_actors().filter('*traffic_light*'):\n            if traffic_light not in list(CarlaDataProvider._traffic_light_map):\n                CarlaDataProvider._traffic_light_map[traffic_light] = traffic_light.get_transform()\n            else:\n                raise KeyError(\n                    \"Traffic light '{}' already registered. Cannot register twice!\".format(traffic_light.id))\n\n    @staticmethod\n    def annotate_trafficlight_in_group(traffic_light):\n        \"\"\"\n        Get dictionary with traffic light group info for a given traffic light\n        \"\"\"\n        dict_annotations = {'ref': [], 'opposite': [], 'left': [], 'right': []}\n\n        # Get the waypoints\n        ref_location = CarlaDataProvider.get_trafficlight_trigger_location(traffic_light)\n        ref_waypoint = CarlaDataProvider.get_map().get_waypoint(ref_location)\n        ref_yaw = ref_waypoint.transform.rotation.yaw\n\n        group_tl = traffic_light.get_group_traffic_lights()\n\n        for target_tl in group_tl:\n            if traffic_light.id == target_tl.id:\n                dict_annotations['ref'].append(target_tl)\n            else:\n                # Get the angle between yaws\n                target_location = CarlaDataProvider.get_trafficlight_trigger_location(target_tl)\n                target_waypoint = CarlaDataProvider.get_map().get_waypoint(target_location)\n                target_yaw = target_waypoint.transform.rotation.yaw\n\n                diff = (target_yaw - ref_yaw) % 360\n\n                if diff > 330:\n                    continue\n                elif diff > 225:\n                    dict_annotations['right'].append(target_tl)\n                elif diff > 135.0:\n                    dict_annotations['opposite'].append(target_tl)\n                elif diff > 30:\n                    dict_annotations['left'].append(target_tl)\n\n        return dict_annotations\n\n    @staticmethod\n    def get_trafficlight_trigger_location(traffic_light):    # pylint: disable=invalid-name\n        \"\"\"\n        Calculates the yaw of the waypoint that represents the trigger volume of the traffic light\n        \"\"\"\n        def rotate_point(point, angle):\n            \"\"\"\n            rotate a given point by a given angle\n            \"\"\"\n            x_ = math.cos(math.radians(angle)) * point.x - math.sin(math.radians(angle)) * point.y\n            y_ = math.sin(math.radians(angle)) * point.x - math.cos(math.radians(angle)) * point.y\n\n            return carla.Vector3D(x_, y_, point.z)\n\n        base_transform = traffic_light.get_transform()\n        base_rot = base_transform.rotation.yaw\n        area_loc = base_transform.transform(traffic_light.trigger_volume.location)\n        area_ext = traffic_light.trigger_volume.extent\n\n        point = rotate_point(carla.Vector3D(0, 0, area_ext.z), base_rot)\n        point_location = area_loc + carla.Location(x=point.x, y=point.y)\n\n        return carla.Location(point_location.x, point_location.y, point_location.z)\n\n    @staticmethod\n    def update_light_states(ego_light, annotations, states, freeze=False, timeout=1000000000):\n        \"\"\"\n        Update traffic light states\n        \"\"\"\n        reset_params = []\n\n        for state in states:\n            relevant_lights = []\n            if state == 'ego':\n                relevant_lights = [ego_light]\n            else:\n                relevant_lights = annotations[state]\n            for light in relevant_lights:\n                prev_state = light.get_state()\n                prev_green_time = light.get_green_time()\n                prev_red_time = light.get_red_time()\n                prev_yellow_time = light.get_yellow_time()\n                reset_params.append({'light': light,\n                                     'state': prev_state,\n                                     'green_time': prev_green_time,\n                                     'red_time': prev_red_time,\n                                     'yellow_time': prev_yellow_time})\n\n                light.set_state(states[state])\n                if freeze:\n                    light.set_green_time(timeout)\n                    light.set_red_time(timeout)\n                    light.set_yellow_time(timeout)\n\n        return reset_params\n\n    @staticmethod\n    def reset_lights(reset_params):\n        \"\"\"\n        Reset traffic lights\n        \"\"\"\n        for param in reset_params:\n            param['light'].set_state(param['state'])\n            param['light'].set_green_time(param['green_time'])\n            param['light'].set_red_time(param['red_time'])\n            param['light'].set_yellow_time(param['yellow_time'])\n\n    @staticmethod\n    def get_next_traffic_light(actor, use_cached_location=True):\n        \"\"\"\n        returns the next relevant traffic light for the provided actor\n        \"\"\"\n\n        if not use_cached_location:\n            location = actor.get_transform().location\n        else:\n            location = CarlaDataProvider.get_location(actor)\n\n        waypoint = CarlaDataProvider.get_map().get_waypoint(location)\n        # Create list of all waypoints until next intersection\n        list_of_waypoints = []\n        while waypoint and not waypoint.is_intersection:\n            list_of_waypoints.append(waypoint)\n            waypoint = waypoint.next(2.0)[0]\n\n        # If the list is empty, the actor is in an intersection\n        if not list_of_waypoints:\n            return None\n\n        relevant_traffic_light = None\n        distance_to_relevant_traffic_light = float(\"inf\")\n\n        for traffic_light in CarlaDataProvider._traffic_light_map:\n            if hasattr(traffic_light, 'trigger_volume'):\n                tl_t = CarlaDataProvider._traffic_light_map[traffic_light]\n                transformed_tv = tl_t.transform(traffic_light.trigger_volume.location)\n                distance = carla.Location(transformed_tv).distance(list_of_waypoints[-1].transform.location)\n\n                if distance < distance_to_relevant_traffic_light:\n                    relevant_traffic_light = traffic_light\n                    distance_to_relevant_traffic_light = distance\n\n        return relevant_traffic_light\n\n    @staticmethod\n    def generate_spawn_points():\n        \"\"\"\n        Generate spawn points for the current map\n        \"\"\"\n        spawn_points = list(CarlaDataProvider.get_map(CarlaDataProvider._world).get_spawn_points())\n        CarlaDataProvider._rng.shuffle(spawn_points)\n        CarlaDataProvider._spawn_points = spawn_points\n        CarlaDataProvider._spawn_index = 0\n\n    @staticmethod\n    def create_blueprint(model, rolename='scenario', color=None, actor_category=\"car\", attribute_filter=None):\n        \"\"\"\n        Function to setup the blueprint of an actor given its model and other relevant parameters\n        \"\"\"\n        def check_attribute_value(blueprint, name, value):\n            \"\"\"\n            Checks if the blueprint has that attribute with that value\n            \"\"\"\n            if not blueprint.has_attribute(name):\n                return False\n\n            attribute_type = blueprint.get_attribute(key).type\n            if attribute_type == carla.ActorAttributeType.Bool:\n                return blueprint.get_attribute(name).as_bool() == value\n            elif attribute_type == carla.ActorAttributeType.Int:\n                return blueprint.get_attribute(name).as_int() == value\n            elif attribute_type == carla.ActorAttributeType.Float:\n                return blueprint.get_attribute(name).as_float() == value\n            elif attribute_type == carla.ActorAttributeType.String:\n                return blueprint.get_attribute(name).as_str() == value\n\n            return False\n\n        _actor_blueprint_categories = {\n            'car': 'vehicle.tesla.model3',\n            'van': 'vehicle.volkswagen.t2',\n            'truck': 'vehicle.carlamotors.carlacola',\n            'trailer': '',\n            'semitrailer': '',\n            'bus': 'vehicle.volkswagen.t2',\n            'motorbike': 'vehicle.kawasaki.ninja',\n            'bicycle': 'vehicle.diamondback.century',\n            'train': '',\n            'tram': '',\n            'pedestrian': 'walker.pedestrian.0001',\n        }\n\n        # Set the model\n        try:\n            blueprints = CarlaDataProvider._blueprint_library.filter(model)\n            if attribute_filter is not None:\n                for key, value in attribute_filter.items():\n                    blueprints = [x for x in blueprints if check_attribute_value(x, key, value)]\n\n            blueprint = CarlaDataProvider._rng.choice(blueprints)\n        except ValueError:\n            # The model is not part of the blueprint library. Let's take a default one for the given category\n            bp_filter = \"vehicle.*\"\n            new_model = _actor_blueprint_categories[actor_category]\n            if new_model != '':\n                bp_filter = new_model\n            print(\"WARNING: Actor model {} not available. Using instead {}\".format(model, new_model))\n            blueprint = CarlaDataProvider._rng.choice(CarlaDataProvider._blueprint_library.filter(bp_filter))\n\n        # Set the color\n        if color:\n            if not blueprint.has_attribute('color'):\n                print(\n                    \"WARNING: Cannot set Color ({}) for actor {} due to missing blueprint attribute\".format(\n                        color, blueprint.id))\n            else:\n                default_color_rgba = blueprint.get_attribute('color').as_color()\n                default_color = '({}, {}, {})'.format(default_color_rgba.r, default_color_rgba.g, default_color_rgba.b)\n                try:\n                    blueprint.set_attribute('color', color)\n                except ValueError:\n                    # Color can't be set for this vehicle\n                    print(\"WARNING: Color ({}) cannot be set for actor {}. Using instead: ({})\".format(\n                        color, blueprint.id, default_color))\n                    blueprint.set_attribute('color', default_color)\n        else:\n            if blueprint.has_attribute('color') and rolename != 'hero':\n                color = CarlaDataProvider._rng.choice(blueprint.get_attribute('color').recommended_values)\n                blueprint.set_attribute('color', color)\n\n        # Make pedestrians mortal\n        if blueprint.has_attribute('is_invincible'):\n            blueprint.set_attribute('is_invincible', 'false')\n\n        # Set the rolename\n        if blueprint.has_attribute('role_name'):\n            blueprint.set_attribute('role_name', rolename)\n\n        return blueprint\n\n    @staticmethod\n    def handle_actor_batch(batch, tick=True):\n        \"\"\"\n        Forward a CARLA command batch to spawn actors to CARLA, and gather the responses.\n        Returns list of actors on success, none otherwise\n        \"\"\"\n        sync_mode = CarlaDataProvider.is_sync_mode()\n        actors = []\n\n        if CarlaDataProvider._client:\n            responses = CarlaDataProvider._client.apply_batch_sync(batch, sync_mode and tick)\n        else:\n            raise ValueError(\"class member \\'client'\\' not initialized yet\")\n\n        # Wait (or not) for the actors to be spawned properly before we do anything\n        if not tick:\n            pass\n        elif CarlaDataProvider.is_runtime_init_mode():\n            CarlaDataProvider._world.wait_for_tick()\n        elif sync_mode:\n            CarlaDataProvider._world.tick()\n        else:\n            CarlaDataProvider._world.wait_for_tick()\n\n        actor_ids = [r.actor_id for r in responses if not r.error]\n        for r in responses:\n            if r.error:\n                print(\"WARNING: Not all actors were spawned\")\n                break\n        actors = list(CarlaDataProvider._world.get_actors(actor_ids))\n        return actors\n\n    @staticmethod\n    def request_new_actor(model, spawn_point, rolename='scenario', autopilot=False,\n                          random_location=False, color=None, actor_category=\"car\",\n                          attribute_filter=None, tick=True):\n        \"\"\"\n        This method tries to create a new actor, returning it if successful (None otherwise).\n        \"\"\"\n        blueprint = CarlaDataProvider.create_blueprint(model, rolename, color, actor_category, attribute_filter)\n\n        if random_location:\n            actor = None\n            while not actor:\n                spawn_point = CarlaDataProvider._rng.choice(CarlaDataProvider._spawn_points)\n                actor = CarlaDataProvider._world.try_spawn_actor(blueprint, spawn_point)\n\n        else:\n            # For non prop models, slightly lift the actor to avoid collisions with the ground\n            z_offset = 0.2 if 'prop' not in model else 0\n\n            # DO NOT USE spawn_point directly, as this will modify spawn_point permanently\n            _spawn_point = carla.Transform(carla.Location(), spawn_point.rotation)\n            _spawn_point.location.x = spawn_point.location.x\n            _spawn_point.location.y = spawn_point.location.y\n            _spawn_point.location.z = spawn_point.location.z + z_offset\n            actor = CarlaDataProvider._world.try_spawn_actor(blueprint, _spawn_point)\n\n        if actor is None:\n            print(\"WARNING: Cannot spawn actor {} at position {}\".format(model, spawn_point.location))\n            return None\n\n        # De/activate the autopilot of the actor if it belongs to vehicle\n        if autopilot:\n            if isinstance(actor, carla.Vehicle):\n                actor.set_autopilot(autopilot, CarlaDataProvider._traffic_manager_port)\n            else:\n                print(\"WARNING: Tried to set the autopilot of a non vehicle actor\")\n\n        # Wait for the actor to be spawned properly before we do anything\n        if not tick:\n            pass\n        elif CarlaDataProvider.is_runtime_init_mode():\n            CarlaDataProvider._world.wait_for_tick()\n        elif CarlaDataProvider.is_sync_mode():\n            CarlaDataProvider._world.tick()\n        else:\n            CarlaDataProvider._world.wait_for_tick()\n\n        CarlaDataProvider._carla_actor_pool[actor.id] = actor\n        CarlaDataProvider.register_actor(actor, spawn_point)\n        return actor\n\n    @staticmethod\n    def request_new_actors(actor_list, attribute_filter=None, tick=True):\n        \"\"\"\n        This method tries to series of actor in batch. If this was successful,\n        the new actors are returned, None otherwise.\n\n        param:\n        - actor_list: list of ActorConfigurationData\n        \"\"\"\n\n        SpawnActor = carla.command.SpawnActor                      # pylint: disable=invalid-name\n        PhysicsCommand = carla.command.SetSimulatePhysics          # pylint: disable=invalid-name\n        FutureActor = carla.command.FutureActor                    # pylint: disable=invalid-name\n        ApplyTransform = carla.command.ApplyTransform              # pylint: disable=invalid-name\n        SetAutopilot = carla.command.SetAutopilot                  # pylint: disable=invalid-name\n        SetVehicleLightState = carla.command.SetVehicleLightState  # pylint: disable=invalid-name\n\n        batch = []\n\n        CarlaDataProvider.generate_spawn_points()\n\n        for actor in actor_list:\n\n            # Get the blueprint\n            blueprint = CarlaDataProvider.create_blueprint(\n                actor.model, actor.rolename, actor.color, actor.category, attribute_filter)\n\n            # Get the spawn point\n            transform = actor.transform\n            if actor.random_location:\n                if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points):\n                    print(\"No more spawn points to use\")\n                    break\n                else:\n                    _spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index]  # pylint: disable=unsubscriptable-object\n                    CarlaDataProvider._spawn_index += 1\n\n            else:\n                _spawn_point = carla.Transform()\n                _spawn_point.rotation = transform.rotation\n                _spawn_point.location.x = transform.location.x\n                _spawn_point.location.y = transform.location.y\n                if blueprint.has_tag('walker'):\n                    # On imported OpenDRIVE maps, spawning of pedestrians can fail.\n                    # By increasing the z-value the chances of success are increased.\n                    map_name = CarlaDataProvider._map.name.split(\"/\")[-1]\n                    if not map_name.startswith('OpenDrive'):\n                        _spawn_point.location.z = transform.location.z + 0.2\n                    else:\n                        _spawn_point.location.z = transform.location.z + 0.8\n                else:\n                    _spawn_point.location.z = transform.location.z + 0.2\n\n            # Get the command\n            command = SpawnActor(blueprint, _spawn_point)\n            command.then(SetAutopilot(FutureActor, actor.autopilot, CarlaDataProvider._traffic_manager_port))\n\n            if actor.args is not None and 'physics' in actor.args and actor.args['physics'] == \"off\":\n                command.then(ApplyTransform(FutureActor, _spawn_point)).then(PhysicsCommand(FutureActor, False))\n            elif actor.category == 'misc':\n                command.then(PhysicsCommand(FutureActor, True))\n            if actor.args is not None and 'lights' in actor.args and actor.args['lights'] == \"on\":\n                command.then(SetVehicleLightState(FutureActor, carla.VehicleLightState.All))\n\n            batch.append(command)\n\n        actors = CarlaDataProvider.handle_actor_batch(batch, tick)\n        for actor in actors:\n            if actor is None:\n                continue\n            CarlaDataProvider._carla_actor_pool[actor.id] = actor\n            CarlaDataProvider.register_actor(actor, _spawn_point)\n\n        return actors\n\n    @staticmethod\n    def request_new_batch_actors(model, amount, spawn_points, autopilot=False,\n                                 random_location=False, rolename='scenario',\n                                 attribute_filter=None, tick=True):\n        \"\"\"\n        Simplified version of \"request_new_actors\". This method also create several actors in batch.\n\n        Instead of needing a list of ActorConfigurationData, an \"amount\" parameter is used.\n        This makes actor spawning easier but reduces the amount of configurability.\n\n        Some parameters are the same for all actors (rolename, autopilot and random location)\n        while others are randomized (color)\n        \"\"\"\n\n        SpawnActor = carla.command.SpawnActor      # pylint: disable=invalid-name\n        SetAutopilot = carla.command.SetAutopilot  # pylint: disable=invalid-name\n        FutureActor = carla.command.FutureActor    # pylint: disable=invalid-name\n\n        CarlaDataProvider.generate_spawn_points()\n\n        batch = []\n\n        for i in range(amount):\n            # Get vehicle by model\n            blueprint = CarlaDataProvider.create_blueprint(model, rolename, attribute_filter=attribute_filter)\n\n            if random_location:\n                if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points):\n                    print(\"No more spawn points to use. Spawned {} actors out of {}\".format(i + 1, amount))\n                    break\n                else:\n                    spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index]  # pylint: disable=unsubscriptable-object\n                    CarlaDataProvider._spawn_index += 1\n            else:\n                try:\n                    spawn_point = spawn_points[i]\n                except IndexError:\n                    print(\"The amount of spawn points is lower than the amount of vehicles spawned\")\n                    break\n\n            if spawn_point:\n                batch.append(SpawnActor(blueprint, spawn_point).then(\n                    SetAutopilot(FutureActor, autopilot, CarlaDataProvider._traffic_manager_port)))\n\n        actors = CarlaDataProvider.handle_actor_batch(batch, tick)\n        for actor, command in zip(actors, batch):\n            if actor is None:\n                continue\n            CarlaDataProvider._carla_actor_pool[actor.id] = actor\n            CarlaDataProvider.register_actor(actor, command.transform)\n\n        return actors\n\n    @staticmethod\n    def get_actors():\n        \"\"\"\n        Return list of actors and their ids\n\n        Note: iteritems from six is used to allow compatibility with Python 2 and 3\n        \"\"\"\n        return iteritems(CarlaDataProvider._carla_actor_pool)\n\n    @staticmethod\n    def actor_id_exists(actor_id):\n        \"\"\"\n        Check if a certain id is still at the simulation\n        \"\"\"\n        if actor_id in CarlaDataProvider._carla_actor_pool:\n            return True\n\n        return False\n\n    @staticmethod\n    def get_hero_actor():\n        \"\"\"\n        Get the actor object of the hero actor if it exists, returns none otherwise.\n        \"\"\"\n        for actor_id in CarlaDataProvider._carla_actor_pool:\n            if CarlaDataProvider._carla_actor_pool[actor_id].attributes['role_name'] == 'hero':\n                return CarlaDataProvider._carla_actor_pool[actor_id]\n        return None\n\n    @staticmethod\n    def get_actor_by_id(actor_id):\n        \"\"\"\n        Get an actor from the pool by using its ID. If the actor\n        does not exist, None is returned.\n        \"\"\"\n        if actor_id in CarlaDataProvider._carla_actor_pool:\n            return CarlaDataProvider._carla_actor_pool[actor_id]\n\n        print(\"Non-existing actor id {}\".format(actor_id))\n        return None\n\n    @staticmethod\n    def remove_actor_by_id(actor_id):\n        \"\"\"\n        Remove an actor from the pool using its ID\n        \"\"\"\n        if actor_id in CarlaDataProvider._carla_actor_pool:\n            CarlaDataProvider._carla_actor_pool[actor_id].destroy()\n            CarlaDataProvider._carla_actor_pool[actor_id] = None\n            CarlaDataProvider._carla_actor_pool.pop(actor_id)\n        else:\n            print(\"Trying to remove a non-existing actor id {}\".format(actor_id))\n\n    @staticmethod\n    def remove_actors_in_surrounding(location, distance):\n        \"\"\"\n        Remove all actors from the pool that are closer than distance to the\n        provided location\n        \"\"\"\n        for actor_id in CarlaDataProvider._carla_actor_pool.copy():\n            if CarlaDataProvider._carla_actor_pool[actor_id].get_location().distance(location) < distance:\n                CarlaDataProvider._carla_actor_pool[actor_id].destroy()\n                CarlaDataProvider._carla_actor_pool.pop(actor_id)\n\n        # Remove all keys with None values\n        CarlaDataProvider._carla_actor_pool = dict({k: v for k, v in CarlaDataProvider._carla_actor_pool.items() if v})\n\n    @staticmethod\n    def get_traffic_manager_port():\n        \"\"\"\n        Get the port of the traffic manager.\n        \"\"\"\n        return CarlaDataProvider._traffic_manager_port\n\n    @staticmethod\n    def set_traffic_manager_port(tm_port):\n        \"\"\"\n        Set the port to use for the traffic manager.\n        \"\"\"\n        CarlaDataProvider._traffic_manager_port = tm_port\n\n    @staticmethod\n    def cleanup():\n        \"\"\"\n        Cleanup and remove all entries from all dictionaries\n        \"\"\"\n        DestroyActor = carla.command.DestroyActor       # pylint: disable=invalid-name\n        batch = []\n\n        for actor_id in CarlaDataProvider._carla_actor_pool.copy():\n            actor = CarlaDataProvider._carla_actor_pool[actor_id]\n            if actor is not None and actor.is_alive:\n                batch.append(DestroyActor(actor))\n\n        if CarlaDataProvider._client:\n            try:\n                CarlaDataProvider._client.apply_batch_sync(batch)\n            except RuntimeError as e:\n                if \"time-out\" in str(e):\n                    pass\n                else:\n                    raise e\n\n        CarlaDataProvider._actor_velocity_map.clear()\n        CarlaDataProvider._actor_location_map.clear()\n        CarlaDataProvider._actor_transform_map.clear()\n        CarlaDataProvider._traffic_light_map.clear()\n        CarlaDataProvider._map = None\n        CarlaDataProvider._world = None\n        CarlaDataProvider._sync_flag = False\n        CarlaDataProvider._ego_vehicle_route = None\n        CarlaDataProvider._all_actors = None\n        CarlaDataProvider._carla_actor_pool = {}\n        CarlaDataProvider._client = None\n        CarlaDataProvider._spawn_points = None\n        CarlaDataProvider._spawn_index = 0\n        CarlaDataProvider._rng = random.RandomState(CarlaDataProvider._random_seed)\n        CarlaDataProvider._grp = None\n        CarlaDataProvider._runtime_init_flag = False\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/lights_sim.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a weather class and py_trees behavior\nto simulate weather in CARLA according to the astronomic\nbehavior of the sun.\n\"\"\"\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass RouteLightsBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Behavior responsible for turning the street lights on and off depending on the weather conditions.\n    Only those around the ego vehicle will be turned on, regardless of weather conditions\n    \"\"\"\n    SUN_ALTITUDE_THRESHOLD_1 = 15\n    SUN_ALTITUDE_THRESHOLD_2 = 165\n\n    # For higher fog and cloudness values, the amount of light in scene starts to rapidly decrease\n    CLOUDINESS_THRESHOLD = 80\n    FOG_THRESHOLD = 40\n\n    # In cases where more than one weather conditition is active, decrease the thresholds\n    COMBINED_THRESHOLD = 10\n\n    def __init__(self, ego_vehicle, radius=50, radius_increase=15, name=\"LightsBehavior\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super().__init__(name)\n        self._ego_vehicle = ego_vehicle\n        self._radius = radius\n        self._radius_increase = radius_increase\n        self._world = CarlaDataProvider.get_world()\n        self._light_manager = self._world.get_lightmanager()\n        self._light_manager.set_day_night_cycle(False)\n        self._vehicle_lights = carla.VehicleLightState.Position | carla.VehicleLightState.LowBeam\n\n        self._prev_night_mode = False\n\n    def update(self):\n        \"\"\"\n        Turns on / off all the lghts around a radius of the ego vehicle\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._ego_vehicle)\n        if not location:\n            return new_status\n\n        night_mode = self._get_night_mode(self._world.get_weather())\n        if night_mode:\n            self._turn_close_lights_on(location)\n        elif self._prev_night_mode:\n            self._turn_all_lights_off()\n\n        self._prev_night_mode = night_mode\n        return new_status\n\n    def _get_night_mode(self, weather):\n        \"\"\"Check wheather or not the street lights need to be turned on\"\"\"\n        altitude_dist = weather.sun_altitude_angle - self.SUN_ALTITUDE_THRESHOLD_1\n        altitude_dist = min(altitude_dist, self.SUN_ALTITUDE_THRESHOLD_2 - weather.sun_altitude_angle)\n        cloudiness_dist = self.CLOUDINESS_THRESHOLD - weather.cloudiness\n        fog_density_dist = self.FOG_THRESHOLD - weather.fog_density\n\n        # Check each parameter independetly\n        if altitude_dist < 0 or cloudiness_dist < 0 or fog_density_dist < 0:\n            return True\n\n        # Check if two or more values are close to their threshold\n        joined_threshold = int(altitude_dist < self.COMBINED_THRESHOLD)\n        joined_threshold += int(cloudiness_dist < self.COMBINED_THRESHOLD)\n        joined_threshold += int(fog_density_dist < self.COMBINED_THRESHOLD)\n\n        if joined_threshold >= 2:\n            return True\n\n        return False\n\n    def _turn_close_lights_on(self, location):\n        \"\"\"Turns on the lights of all the objects close to the ego vehicle\"\"\"\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_vehicle)\n        radius = max(self._radius, self._radius_increase * ego_speed)\n\n        # Street lights\n        on_lights = []\n        off_lights = []\n\n        all_lights = self._light_manager.get_all_lights()\n        for light in all_lights:\n            if light.location.distance(location) > radius:\n                if light.is_on:\n                    off_lights.append(light)\n            else:\n                if not light.is_on:\n                    on_lights.append(light)\n\n        self._light_manager.turn_on(on_lights)\n        self._light_manager.turn_off(off_lights)\n\n        # Vehicles\n        all_vehicles = CarlaDataProvider.get_all_actors().filter('*vehicle.*')\n        scenario_vehicles = [v for v in all_vehicles if v.attributes['role_name'] == 'scenario']\n\n        for vehicle in scenario_vehicles:\n            try:\n                if vehicle.get_location().distance(location) > radius:\n                        lights = vehicle.get_light_state()\n                        lights &= ~self._vehicle_lights  # Remove those lights\n                        vehicle.set_light_state(carla.VehicleLightState(lights))\n                else:\n                    lights = vehicle.get_light_state()\n                    lights |= self._vehicle_lights  # Add those lights\n                    vehicle.set_light_state(carla.VehicleLightState(lights))\n            except RuntimeError:\n                pass\n\n        # Ego vehicle\n        lights = self._ego_vehicle.get_light_state()\n        lights |= self._vehicle_lights\n        self._ego_vehicle.set_light_state(carla.VehicleLightState(lights))\n\n    def _turn_all_lights_off(self):\n        \"\"\"Turns off the lights of all object\"\"\"\n        all_lights = self._light_manager.get_all_lights()\n        off_lights = [l for l in all_lights if l.is_on]\n        self._light_manager.turn_off(off_lights)\n\n        # Vehicles\n        all_vehicles = CarlaDataProvider.get_all_actors().filter('*vehicle.*')\n        scenario_vehicles = [v for v in all_vehicles if v.attributes['role_name'] == 'scenario']\n\n        for vehicle in scenario_vehicles:\n            lights = vehicle.get_light_state()\n            lights &= ~self._vehicle_lights  # Remove those lights\n            vehicle.set_light_state(carla.VehicleLightState(lights))\n\n        # Ego vehicle\n        lights = self._ego_vehicle.get_light_state()\n        lights &= ~self._vehicle_lights  # Remove those lights\n        self._ego_vehicle.set_light_state(carla.VehicleLightState(lights))\n\n    def terminate(self, new_status):\n        self._light_manager.set_day_night_cycle(True)\n        return super().terminate(new_status)"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/result_writer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module contains the result gatherer and write for CARLA scenarios.\nIt shall be used from the ScenarioManager only.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport time\nimport json\nfrom tabulate import tabulate\n\n\nclass ResultOutputProvider(object):\n\n    \"\"\"\n    This module contains the _result gatherer and write for CARLA scenarios.\n    It shall be used from the ScenarioManager only.\n    \"\"\"\n\n    def __init__(self, data, result, stdout=True, filename=None, junitfile=None, jsonfile=None):\n        \"\"\"\n        Setup all parameters\n        - _data contains all scenario-related information\n        - _result is overall pass/fail info\n        - _stdout (True/False) is used to (de)activate terminal output\n        - _filename is used to (de)activate file output in tabular form\n        - _junit is used to (de)activate file output in junit form\n        - _json is used to (de)activate file output in json form\n        \"\"\"\n        self._data = data\n        self._result = result\n        self._stdout = stdout\n        self._filename = filename\n        self._junit = junitfile\n        self._json = jsonfile\n\n        self._start_time = time.strftime('%Y-%m-%d %H:%M:%S',\n                                         time.localtime(self._data.start_system_time))\n        self._end_time = time.strftime('%Y-%m-%d %H:%M:%S',\n                                       time.localtime(self._data.end_system_time))\n\n    def write(self):\n        \"\"\"\n        Public write function\n        \"\"\"\n        if self._junit is not None:\n            self._write_to_junit()\n        if self._json is not None:\n            self._write_to_reportjson()\n\n        output = self.create_output_text()\n        if self._filename is not None:\n            with open(self._filename, 'w', encoding='utf-8') as fd:\n                fd.write(output)\n        if self._stdout:\n            print(output)\n\n    def create_output_text(self):\n        \"\"\"\n        Creates the output message\n        \"\"\"\n        output = \"\\n\"\n        output += \" ======= Results of Scenario: {} ---- {} =======\\n\".format(\n            self._data.scenario_tree.name, self._result)\n        end_line_length = len(output) - 3\n        output += \"\\n\"\n\n        # Lis of all the actors\n        output += \" > Ego vehicles:\\n\"\n        for ego_vehicle in self._data.ego_vehicles:\n            output += \"{}; \".format(ego_vehicle)\n        output += \"\\n\\n\"\n\n        output += \" > Other actors:\\n\"\n        for actor in self._data.other_actors:\n            output += \"{}; \".format(actor)\n        output += \"\\n\\n\"\n\n        # Simulation part\n        output += \" > Simulation Information\\n\"\n\n        system_time = round(self._data.scenario_duration_system, 2)\n        game_time = round(self._data.scenario_duration_game, 2)\n        ratio = round(self._data.scenario_duration_game / self._data.scenario_duration_system, 3)\n\n        list_statistics = [[\"Start Time\", \"{}\".format(self._start_time)]]\n        list_statistics.extend([[\"End Time\", \"{}\".format(self._end_time)]])\n        list_statistics.extend([[\"System Time\", \"{}s\".format(system_time)]])\n        list_statistics.extend([[\"Game Time\", \"{}s\".format(game_time)]])\n        list_statistics.extend([[\"Ratio (Game / System)\", \"{}\".format(ratio)]])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\\n\"\n\n        # Criteria part\n        output += \" > Criteria Information\\n\"\n        header = ['Actor', 'Criterion', 'Result', 'Actual Value', 'Success Value']\n        list_statistics = [header]\n\n        for criterion in self._data.scenario.get_criteria():\n            name = criterion.name\n            if criterion.optional:\n                name += \" (Opt.)\"\n            else:\n                name += \" (Req.)\"\n\n            actor = \"{} (id={})\".format(criterion.actor.type_id[8:], criterion.actor.id)\n\n            list_statistics.extend([[\n                actor, name, criterion.test_status, criterion.actual_value, criterion.success_value]])\n\n        # Timeout\n        actor = \"\"\n        criteria = \"Timeout (Req.)\"\n        result = \"SUCCESS\" if self._data.scenario_duration_game < self._data.scenario.timeout else \"FAILURE\"\n        actual_value = round(self._data.scenario_duration_game, 2)\n        expected_value = round(self._data.scenario.timeout, 2)\n\n        list_statistics.extend([[actor, criteria, result, actual_value, expected_value]])\n\n        # Global and final output message\n        list_statistics.extend([['', 'GLOBAL RESULT', self._result, '', '']])\n\n        output += tabulate(list_statistics, tablefmt='fancy_grid')\n        output += \"\\n\"\n        output += \" \" + \"=\" * end_line_length + \"\\n\"\n\n        return output\n\n    def _write_to_reportjson(self):\n        \"\"\"\n        Write a machine-readable report to JSON\n\n        The resulting report has the following format:\n        {\n            criteria: [\n                {\n                    name: \"CheckCollisions\",\n                    expected: \"0\",\n                    actual: \"2\",\n                    optional: false,\n                    success: false\n                }, ...\n            ]\n        }\n        \"\"\"\n        json_list = []\n\n        def result_dict(name, actor, optional, expected, actual, success):\n            \"\"\"\n            Convenience function to convert its arguments into a JSON-ready dict\n            :param name: Name of the test criterion\n            :param actor: Actor ID as string\n            :param optional: If the criterion is optional\n            :param expected: The expected value of the criterion (eg 0 for collisions)\n            :param actual: The actual value\n            :param success: If the test was passed\n            :return: A dict data structure that will be written to JSON\n            \"\"\"\n            return {\n                \"name\": name,\n                \"actor\": actor,\n                \"optional\": optional,\n                \"expected\": expected,\n                \"actual\": actual,\n                \"success\": success,\n            }\n\n        for criterion in self._data.scenario.get_criteria():\n            json_list.append(\n                result_dict(\n                    criterion.name,\n                    \"{}-{}\".format(criterion.actor.type_id[8:], criterion.actor.id),\n                    criterion.optional,\n                    criterion.success_value,\n                    criterion.actual_value,\n                    criterion.test_status in [\"SUCCESS\", \"ACCEPTABLE\"]\n                )\n            )\n\n        # add one entry for duration\n        timeout = self._data.scenario.timeout\n        duration = self._data.scenario_duration_game\n        json_list.append(\n            result_dict(\n                \"Duration\", \"all\", False, timeout, duration, duration <= timeout\n            )\n        )\n\n        result_object = {\n            \"scenario\": self._data.scenario_tree.name,\n            \"success\": self._result in [\"SUCCESS\", \"ACCEPTABLE\"],\n            \"criteria\": json_list\n        }\n\n        with open(self._json, \"w\", encoding='utf-8') as fp:\n            json.dump(result_object, fp, indent=4)\n\n    def _write_to_junit(self):\n        \"\"\"\n        Writing to Junit XML\n        \"\"\"\n        test_count = 0\n        failure_count = 0\n        for criterion in self._data.scenario.get_criteria():\n            test_count += 1\n            if criterion.test_status != \"SUCCESS\":\n                failure_count += 1\n\n        # handle timeout\n        test_count += 1\n        if self._data.scenario_duration_game >= self._data.scenario.timeout:\n            failure_count += 1\n\n        with open(self._junit, \"w\", encoding='utf-8') as junit_file:\n\n            junit_file.write(\"<?xml version=\\\"1.0\\\" encoding=\\\"UTF-8\\\"?>\\n\")\n\n            test_suites_string = (\"<testsuites tests=\\\"%d\\\" failures=\\\"%d\\\" disabled=\\\"0\\\" \"\n                                  \"errors=\\\"0\\\" timestamp=\\\"%s\\\" time=\\\"%5.2f\\\" \"\n                                  \"name=\\\"Simulation\\\" package=\\\"Scenarios\\\">\\n\" %\n                                  (test_count,\n                                   failure_count,\n                                   self._start_time,\n                                   self._data.scenario_duration_system))\n            junit_file.write(test_suites_string)\n\n            test_suite_string = (\"  <testsuite name=\\\"%s\\\" tests=\\\"%d\\\" failures=\\\"%d\\\" \"\n                                 \"disabled=\\\"0\\\" errors=\\\"0\\\" time=\\\"%5.2f\\\">\\n\" %\n                                 (self._data.scenario_tree.name,\n                                  test_count,\n                                  failure_count,\n                                  self._data.scenario_duration_system))\n            junit_file.write(test_suite_string)\n\n            for criterion in self._data.scenario.get_criteria():\n                testcase_name = criterion.name + \"_\" + \\\n                    criterion.actor.type_id[8:] + \"_\" + str(criterion.actor.id)\n                result_string = (\"    <testcase name=\\\"{}\\\" status=\\\"run\\\" \"\n                                 \"time=\\\"0\\\" classname=\\\"Scenarios.{}\\\">\\n\".format(\n                                     testcase_name, self._data.scenario_tree.name))\n                if criterion.test_status != \"SUCCESS\":\n                    result_string += \"      <failure message=\\\"{}\\\"  type=\\\"\\\"><![CDATA[\\n\".format(\n                        criterion.name)\n                    result_string += \"  Actual:   {}\\n\".format(\n                        criterion.actual_value)\n                    result_string += \"  Expected: {}\\n\".format(\n                        criterion.success_value)\n                    result_string += \"\\n\"\n                    result_string += \"  Exact Value: {} = {}]]></failure>\\n\".format(\n                        criterion.name, criterion.actual_value)\n                else:\n                    result_string += \"  Exact Value: {} = {}\\n\".format(\n                        criterion.name, criterion.actual_value)\n                result_string += \"    </testcase>\\n\"\n                junit_file.write(result_string)\n\n            # Handle timeout separately\n            result_string = (\"    <testcase name=\\\"Duration\\\" status=\\\"run\\\" time=\\\"{}\\\" \"\n                             \"classname=\\\"Scenarios.{}\\\">\\n\".format(\n                                 self._data.scenario_duration_system,\n                                 self._data.scenario_tree.name))\n            if self._data.scenario_duration_game >= self._data.scenario.timeout:\n                result_string += \"      <failure message=\\\"{}\\\"  type=\\\"\\\"><![CDATA[\\n\".format(\n                    \"Duration\")\n                result_string += \"  Actual:   {}\\n\".format(\n                    self._data.scenario_duration_game)\n                result_string += \"  Expected: {}\\n\".format(\n                    self._data.scenario.timeout)\n                result_string += \"\\n\"\n                result_string += \"  Exact Value: {} = {}]]></failure>\\n\".format(\n                    \"Duration\", self._data.scenario_duration_game)\n            else:\n                result_string += \"  Exact Value: {} = {}\\n\".format(\n                    \"Duration\", self._data.scenario_duration_game)\n            result_string += \"    </testcase>\\n\"\n            junit_file.write(result_string)\n\n            junit_file.write(\"  </testsuite>\\n\")\n            junit_file.write(\"</testsuites>\\n\")\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/scenario_manager.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides the ScenarioManager implementation.\nIt must not be modified and is for reference only!\n\"\"\"\n\nfrom __future__ import print_function\nimport sys\nimport time\n\nimport py_trees\n\nfrom srunner.autoagents.agent_wrapper import AgentWrapper\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.result_writer import ResultOutputProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.watchdog import Watchdog\n\n\nclass ScenarioManager(object):\n\n    \"\"\"\n    Basic scenario manager class. This class holds all functionality\n    required to start, and analyze a scenario.\n\n    The user must not modify this class.\n\n    To use the ScenarioManager:\n    1. Create an object via manager = ScenarioManager()\n    2. Load a scenario via manager.load_scenario()\n    3. Trigger the execution of the scenario manager.run_scenario()\n       This function is designed to explicitly control start and end of\n       the scenario execution\n    4. Trigger a result evaluation with manager.analyze_scenario()\n    5. If needed, cleanup with manager.stop_scenario()\n    \"\"\"\n\n    def __init__(self, debug_mode=False, sync_mode=False, timeout=2.0):\n        \"\"\"\n        Setups up the parameters, which will be filled at load_scenario()\n\n        \"\"\"\n        self.scenario = None\n        self.scenario_tree = None\n        self.ego_vehicles = None\n        self.other_actors = None\n\n        self._debug_mode = debug_mode\n        self._agent = None\n        self._sync_mode = sync_mode\n        self._watchdog = None\n        self._timeout = timeout\n\n        self._running = False\n        self._timestamp_last_run = 0.0\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = None\n        self.end_system_time = None\n\n    def _reset(self):\n        \"\"\"\n        Reset all parameters\n        \"\"\"\n        self._running = False\n        self._timestamp_last_run = 0.0\n        self.scenario_duration_system = 0.0\n        self.scenario_duration_game = 0.0\n        self.start_system_time = None\n        self.end_system_time = None\n        GameTime.restart()\n\n    def cleanup(self):\n        \"\"\"\n        This function triggers a proper termination of a scenario\n        \"\"\"\n\n        if self._watchdog is not None:\n            self._watchdog.stop()\n            self._watchdog = None\n\n        if self.scenario is not None:\n            self.scenario.terminate()\n\n        if self._agent is not None:\n            self._agent.cleanup()\n            self._agent = None\n\n        CarlaDataProvider.cleanup()\n\n    def load_scenario(self, scenario, agent=None):\n        \"\"\"\n        Load a new scenario\n        \"\"\"\n        self._reset()\n        self._agent = AgentWrapper(agent) if agent else None\n        if self._agent is not None:\n            self._sync_mode = True\n        self.scenario = scenario\n        self.scenario_tree = self.scenario.scenario_tree\n        self.ego_vehicles = scenario.ego_vehicles\n        self.other_actors = scenario.other_actors\n\n        # To print the scenario tree uncomment the next line\n        # py_trees.display.render_dot_tree(self.scenario_tree)\n\n        if self._agent is not None:\n            self._agent.setup_sensors(self.ego_vehicles[0], self._debug_mode)\n\n    def run_scenario(self):\n        \"\"\"\n        Trigger the start of the scenario and wait for it to finish/fail\n        \"\"\"\n        print(\"ScenarioManager: Running scenario {}\".format(self.scenario_tree.name))\n        self.start_system_time = time.time()\n        start_game_time = GameTime.get_time()\n\n        self._watchdog = Watchdog(float(self._timeout))\n        self._watchdog.start()\n        self._running = True\n\n        while self._running:\n            timestamp = None\n            world = CarlaDataProvider.get_world()\n            if world:\n                snapshot = world.get_snapshot()\n                if snapshot:\n                    timestamp = snapshot.timestamp\n            if timestamp:\n                self._tick_scenario(timestamp)\n\n        self.cleanup()\n\n        self.end_system_time = time.time()\n        end_game_time = GameTime.get_time()\n\n        self.scenario_duration_system = self.end_system_time - \\\n            self.start_system_time\n        self.scenario_duration_game = end_game_time - start_game_time\n\n        if self.scenario_tree.status == py_trees.common.Status.FAILURE:\n            print(\"ScenarioManager: Terminated due to failure\")\n\n    def _tick_scenario(self, timestamp):\n        \"\"\"\n        Run next tick of scenario and the agent.\n        If running synchornously, it also handles the ticking of the world.\n        \"\"\"\n\n        if self._timestamp_last_run < timestamp.elapsed_seconds and self._running:\n            self._timestamp_last_run = timestamp.elapsed_seconds\n\n            self._watchdog.update()\n\n            if self._debug_mode:\n                print(\"\\n--------- Tick ---------\\n\")\n\n            # Update game time and actor information\n            GameTime.on_carla_tick(timestamp)\n            CarlaDataProvider.on_carla_tick()\n\n            if self._agent is not None:\n                ego_action = self._agent()  # pylint: disable=not-callable\n\n            if self._agent is not None:\n                self.ego_vehicles[0].apply_control(ego_action)\n\n            # Tick scenario\n            self.scenario_tree.tick_once()\n\n            if self._debug_mode:\n                print(\"\\n\")\n                py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True)\n                sys.stdout.flush()\n\n            if self.scenario_tree.status != py_trees.common.Status.RUNNING:\n                self._running = False\n\n        if self._sync_mode and self._running and self._watchdog.get_status():\n            CarlaDataProvider.get_world().tick()\n\n    def get_running_status(self):\n        \"\"\"\n        returns:\n           bool:  False if watchdog exception occured, True otherwise\n        \"\"\"\n        return self._watchdog.get_status()\n\n    def stop_scenario(self):\n        \"\"\"\n        This function is used by the overall signal handler to terminate the scenario execution\n        \"\"\"\n        self._running = False\n\n    def analyze_scenario(self, stdout, filename, junit, json):\n        \"\"\"\n        This function is intended to be called from outside and provide\n        the final statistics about the scenario (human-readable, in form of a junit\n        report, etc.)\n        \"\"\"\n\n        failure = False\n        timeout = False\n        result = \"SUCCESS\"\n\n        criteria = self.scenario.get_criteria()\n        if len(criteria) == 0:\n            print(\"Nothing to analyze, this scenario has no criteria\")\n            return True\n\n        for criterion in criteria:\n            if (not criterion.optional and\n                    criterion.test_status != \"SUCCESS\" and\n                    criterion.test_status != \"ACCEPTABLE\"):\n                failure = True\n                result = \"FAILURE\"\n            elif criterion.test_status == \"ACCEPTABLE\":\n                result = \"ACCEPTABLE\"\n\n        if self.scenario.timeout_node.timeout and not failure:\n            timeout = True\n            result = \"TIMEOUT\"\n\n        output = ResultOutputProvider(self, result, stdout, filename, junit, json)\n        output.write()\n\n        return failure or timeout\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all atomic scenario behaviors required to realize\ncomplex, realistic scenarios such as \"follow a leading vehicle\", \"lane change\",\netc.\n\nThe atomic behaviors are implemented with py_trees.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport copy\nimport math\nimport operator\nimport os\nimport time\nimport subprocess\n\nimport numpy as np\nfrom numpy import random\nimport py_trees\nfrom py_trees.blackboard import Blackboard\nimport networkx\n\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\nfrom agents.navigation.constant_velocity_agent import ConstantVelocityAgent\nfrom agents.navigation.local_planner import RoadOption, LocalPlanner\nfrom agents.tools.misc import is_within_distance, get_speed\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.actorcontrols.actor_control import ActorControl\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.tools.scenario_helper import detect_lane_obstacle\nfrom srunner.tools.scenario_helper import generate_target_waypoint_list_multilane\n\n\nimport srunner.tools as sr_tools\n\nEPSILON = 0.001\n\n\ndef calculate_distance(location, other_location, global_planner=None):\n    \"\"\"\n    Method to calculate the distance between to locations\n\n    Note: It uses the direct distance between the current location and the\n          target location to estimate the time to arrival.\n          To be accurate, it would have to use the distance along the\n          (shortest) route between the two locations.\n    \"\"\"\n    if global_planner:\n        distance = 0\n\n        # Get the route\n        route = global_planner.trace_route(location, other_location)\n\n        # Get the distance of the route\n        for i in range(1, len(route)):\n            curr_loc = route[i][0].transform.location\n            prev_loc = route[i - 1][0].transform.location\n\n            distance += curr_loc.distance(prev_loc)\n\n        return distance\n\n    return location.distance(other_location)\n\n\ndef get_actor_control(actor):\n    \"\"\"\n    Method to return the type of control to the actor.\n    \"\"\"\n    control = actor.get_control()\n    actor_type = actor.type_id.split('.')[0]\n    if not isinstance(actor, carla.Walker):\n        control.steering = 0\n    else:\n        control.speed = 0\n\n    return control, actor_type\n\n\nclass AtomicBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Base class for all atomic behaviors used to setup a scenario\n\n    *All behaviors should use this class as parent*\n\n    Important parameters:\n    - name: Name of the atomic behavior\n    \"\"\"\n\n    def __init__(self, name, actor=None):\n        \"\"\"\n        Default init. Has to be called via super from derived class\n        \"\"\"\n        super(AtomicBehavior, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self.name = name\n        self._actor = actor\n\n    def setup(self, unused_timeout=15):\n        \"\"\"\n        Default setup\n        \"\"\"\n        self.logger.debug(\"%s.setup()\" % (self.__class__.__name__))\n        return True\n\n    def initialise(self):\n        \"\"\"\n        Initialise setup terminates WaypointFollowers\n        Check whether WF for this actor is running and terminate all active WFs\n        \"\"\"\n        if self._actor is not None:\n            try:\n                check_attr = operator.attrgetter(\"running_WF_actor_{}\".format(self._actor.id))\n                terminate_wf = copy.copy(check_attr(py_trees.blackboard.Blackboard()))\n                py_trees.blackboard.Blackboard().set(\n                    \"terminate_WF_actor_{}\".format(self._actor.id), terminate_wf, overwrite=True)\n            except AttributeError:\n                # It is ok to continue, if the Blackboard variable does not exist\n                pass\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        self.logger.debug(\"%s.terminate()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n\nclass RunScript(AtomicBehavior):\n\n    \"\"\"\n    This is an atomic behavior to start execution of an additional script.\n\n    Args:\n        script (str): String containing the interpreter, scriptpath and arguments\n            Example: \"python /path/to/script.py --arg1\"\n        base_path (str): String containing the base path of for the script\n\n    Attributes:\n        _script (str): String containing the interpreter, scriptpath and arguments\n            Example: \"python /path/to/script.py --arg1\"\n        _base_path (str): String containing the base path of for the script\n            Example: \"/path/to/\"\n\n    Note:\n        This is intended for the use with OpenSCENARIO. Be aware of security side effects.\n    \"\"\"\n\n    def __init__(self, script, base_path=None, name=\"RunScript\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(RunScript, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._script = script\n        self._base_path = base_path\n\n    def update(self):\n        \"\"\"\n        Start script\n        \"\"\"\n        path = None\n        script_components = self._script.split(' ')\n        if len(script_components) > 1:\n            path = script_components[1]\n\n        if not os.path.isfile(path):\n            path = os.path.join(self._base_path, path)\n        if not os.path.isfile(path):\n            new_status = py_trees.common.Status.FAILURE\n            print(\"Script file does not exists {}\".format(path))\n        else:\n            subprocess.Popen(self._script, shell=True, cwd=self._base_path)  # pylint: disable=consider-using-with\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass ChangeParameter(AtomicBehavior):\n    \"\"\"\n    This is an atomic behavior to change the osc parameter value.\n\n    Args:\n        parameter_ref (str): parameter name\n        value (any): ParameterRef or number\n    \"\"\"\n\n    def __init__(self, parameter_ref, value, rule=None, name=\"ChangeParameter\"):\n        super(ChangeParameter, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % self.__class__.__name__)\n        self._parameter_ref = parameter_ref\n        self._rule = rule\n        self._value = value\n\n    def update(self):\n        \"\"\"\n        update value of global osc parameter.\n        \"\"\"\n        old_value = CarlaDataProvider.get_osc_global_param_value(self._parameter_ref)\n\n        if self._rule == '+':\n            new_value = self._value + float(old_value)\n        elif self._rule == '*':\n            new_value = self._value * float(old_value)\n        else:\n            new_value = self._value\n\n        CarlaDataProvider.update_osc_global_params({self._parameter_ref: new_value})\n        new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass ChangeWeather(AtomicBehavior):\n\n    \"\"\"\n    Atomic to write a new weather configuration into the blackboard.\n    Used in combination with OSCWeatherBehavior() to have a continuous weather simulation.\n\n    The behavior immediately terminates with SUCCESS after updating the blackboard.\n\n    Args:\n        weather (srunner.scenariomanager.weather_sim.Weather): New weather settings.\n        name (string): Name of the behavior.\n            Defaults to 'UpdateWeather'.\n\n    Attributes:\n        _weather (srunner.scenariomanager.weather_sim.Weather): Weather settings.\n    \"\"\"\n\n    def __init__(self, weather, name=\"ChangeWeather\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeWeather, self).__init__(name)\n        self._weather = weather\n\n    def update(self):\n        \"\"\"\n        Write weather into blackboard and exit with success\n\n        returns:\n            py_trees.common.Status.SUCCESS\n        \"\"\"\n        py_trees.blackboard.Blackboard().set(\"CarlaWeather\", self._weather, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeRoadFriction(AtomicBehavior):\n\n    \"\"\"\n    Atomic to update the road friction in CARLA.\n\n    The behavior immediately terminates with SUCCESS after updating the friction.\n\n    Args:\n        friction (float): New friction coefficient.\n        name (string): Name of the behavior.\n            Defaults to 'UpdateRoadFriction'.\n\n    Attributes:\n        _friction (float): Friction coefficient.\n    \"\"\"\n\n    def __init__(self, friction, name=\"ChangeRoadFriction\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeRoadFriction, self).__init__(name)\n        self._friction = friction\n\n    def update(self):\n        \"\"\"\n        Update road friction. Spawns new friction blueprint and removes the old one, if existing.\n\n        returns:\n            py_trees.common.Status.SUCCESS\n        \"\"\"\n\n        for actor in CarlaDataProvider.get_all_actors().filter('static.trigger.friction'):\n            actor.destroy()\n\n        friction_bp = CarlaDataProvider.get_world().get_blueprint_library().find('static.trigger.friction')\n        extent = carla.Location(1000000.0, 1000000.0, 1000000.0)\n        friction_bp.set_attribute('friction', str(self._friction))\n        friction_bp.set_attribute('extent_x', str(extent.x))\n        friction_bp.set_attribute('extent_y', str(extent.y))\n        friction_bp.set_attribute('extent_z', str(extent.z))\n\n        # Spawn Trigger Friction\n        transform = carla.Transform()\n        transform.location = carla.Location(-10000.0, -10000.0, 0.0)\n        CarlaDataProvider.get_world().spawn_actor(friction_bp, transform)\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeActorControl(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the longitudinal/lateral control logic for an actor.\n    The (actor, controller) pair is stored inside the Blackboard.\n\n    The behavior immediately terminates with SUCCESS after the controller.\n\n    Args:\n        actor (carla.Actor): Actor that should be controlled by the controller.\n        control_py_module (string): Name of the python module containing the implementation\n            of the controller.\n        args (dictionary): Additional arguments for the controller.\n        scenario_file_path (string): Additional path to controller implementation.\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorControl'.\n\n    Attributes:\n        _actor_control (ActorControl): Instance of the actor control.\n    \"\"\"\n\n    def __init__(self, actor, control_py_module, args, scenario_file_path=None, name=\"ChangeActorControl\"):\n        \"\"\"\n        Setup actor controller.\n        \"\"\"\n        super(ChangeActorControl, self).__init__(name, actor)\n\n        self._actor_control = ActorControl(actor, control_py_module=control_py_module,\n                                           args=args, scenario_file_path=scenario_file_path)\n\n    def update(self):\n        \"\"\"\n        Write (actor, controler) pair to Blackboard, or update the controller\n        if actor already exists as a key.\n\n        returns:\n            py_trees.common.Status.SUCCESS\n        \"\"\"\n\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if actor_dict:\n            if self._actor.id in actor_dict:\n                actor_dict[self._actor.id].reset()\n\n        actor_dict[self._actor.id] = self._actor_control\n        py_trees.blackboard.Blackboard().set(\"ActorsWithController\", actor_dict, overwrite=True)\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass UpdateAllActorControls(AtomicBehavior):\n\n    \"\"\"\n    Atomic to update (run one control loop step) all actor controls.\n\n    The behavior is always in RUNNING state.\n\n    Args:\n        name (string): Name of the behavior.\n            Defaults to 'UpdateAllActorControls'.\n    \"\"\"\n\n    def __init__(self, name=\"UpdateAllActorControls\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        super(UpdateAllActorControls, self).__init__(name)\n\n    def update(self):\n        \"\"\"\n        Execute one control loop step for all actor controls.\n\n        returns:\n            py_trees.common.Status.RUNNING\n        \"\"\"\n\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        for actor_id in actor_dict:\n            actor_dict[actor_id].run_step()\n\n        return py_trees.common.Status.RUNNING\n\n\nclass ChangeActorTargetSpeed(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the target speed for an actor controller.\n\n    The behavior is in RUNNING state until the distance/duration\n    conditions are satisfied, or if a second ChangeActorTargetSpeed atomic\n    for the same actor is triggered.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        target_speed (float): New target speed [m/s].\n        init_speed (boolean): Flag to indicate if the speed is the initial actor speed.\n            Defaults to False.\n        duration (float): Duration of the maneuver [s].\n            Defaults to None.\n        distance (float): Distance of the maneuver [m].\n            Defaults to None.\n        relative_actor (carla.Actor): If the target speed setting should be relative to another actor.\n            Defaults to None.\n        value (float): Offset, if the target speed setting should be relative to another actor.\n            Defaults to None.\n        value_type (string): Either 'Delta' or 'Factor' influencing how the offset to the reference actors\n            velocity is applied. Defaults to None.\n        continuous (boolean): If True, the atomic remains in RUNNING, independent of duration or distance.\n            Defaults to False.\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorTargetSpeed'.\n\n    Attributes:\n        _target_speed (float): New target speed [m/s].\n        _init_speed (boolean): Flag to indicate if the speed is the initial actor speed.\n            Defaults to False.\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n        _start_location (carla.Location): Start location of the atomic.\n            Defaults to None.\n        _duration (float): Duration of the maneuver [s].\n            Defaults to None.\n        _distance (float): Distance of the maneuver [m].\n            Defaults to None.\n        _relative_actor (carla.Actor): If the target speed setting should be relative to another actor.\n            Defaults to None.\n        _value (float): Offset, if the target speed setting should be relative to another actor.\n            Defaults to None.\n        _value_type (string): Either 'Delta' or 'Factor' influencing how the offset to the reference actors\n            velocity is applied. Defaults to None.\n        _continuous (boolean): If True, the atomic remains in RUNNING, independent of duration or distance.\n            Defaults to False.\n    \"\"\"\n\n    def __init__(self, actor, target_speed, init_speed=False,\n                 duration=None, distance=None, relative_actor=None,\n                 value=None, value_type=None, continuous=False, name=\"ChangeActorTargetSpeed\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorTargetSpeed, self).__init__(name, actor)\n\n        self._target_speed = target_speed\n        self._init_speed = init_speed\n\n        self._start_time = None\n        self._start_location = None\n\n        self._relative_actor = relative_actor\n        self._value = value\n        self._value_type = value_type\n        self._continuous = continuous\n        self._duration = duration\n        self._distance = distance\n\n    def initialise(self):\n        \"\"\"\n        Set initial parameters such as _start_time and _start_location,\n        and get (actor, controller) pair from Blackboard.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n        self._start_location = CarlaDataProvider.get_location(self._actor)\n\n        if self._relative_actor:\n            relative_velocity = CarlaDataProvider.get_velocity(self._relative_actor)\n\n            # get target velocity\n            if self._value_type == 'delta':\n                self._target_speed = relative_velocity + self._value\n            elif self._value_type == 'factor':\n                self._target_speed = relative_velocity * self._value\n            else:\n                print('self._value_type must be delta or factor')\n\n        actor_dict[self._actor.id].update_target_speed(self._target_speed, start_time=self._start_time)\n\n        if self._init_speed:\n            actor_dict[self._actor.id].set_init_speed()\n\n        super(ChangeActorTargetSpeed, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's current state and update target speed, if it is relative to another actor.\n\n        returns:\n            py_trees.common.Status.SUCCESS, if the duration or distance driven exceeded limits\n                                            if another ChangeActorTargetSpeed atomic for the same actor was triggered.\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.FAILURE, else.\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._relative_actor:\n            relative_velocity = CarlaDataProvider.get_velocity(self._relative_actor)\n\n            # get target velocity\n            if self._value_type == 'delta':\n                actor_dict[self._actor.id].update_target_speed(relative_velocity + self._value)\n            elif self._value_type == 'factor':\n                actor_dict[self._actor.id].update_target_speed(relative_velocity * self._value)\n            else:\n                print('self._value_type must be delta or factor')\n\n        # check duration and driven_distance\n        if not self._continuous:\n            if (self._duration is not None) and (GameTime.get_time() - self._start_time > self._duration):\n                new_status = py_trees.common.Status.SUCCESS\n\n            driven_distance = CarlaDataProvider.get_location(self._actor).distance(self._start_location)\n            if (self._distance is not None) and (driven_distance > self._distance):\n                new_status = py_trees.common.Status.SUCCESS\n\n        if self._distance is None and self._duration is None:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass SyncArrivalOSC(AtomicBehavior):\n\n    \"\"\"\n    Atomic to make two actors arrive at their corresponding places at the same time\n\n    The behavior is in RUNNING state until the \"main\" actor has rezached its destination\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        master_actor (carla.Actor): Reference actor to sync up to.\n        actor_target (carla.Transform): Endpoint of the actor after the behavior finishes.\n        master_target (carla.Transform): Endpoint of the master_actor after the behavior finishes.\n        final_speed (float): Speed of the actor after the behavior ends.\n        relative_to_master (boolean): Whether or not the final speed is relative to master_actor.\n            Defaults to False.\n        relative_type (string): Type of relative speed. Either 'delta' or 'factor'.\n            Defaults to ''.\n        name (string): Name of the behavior.\n            Defaults to 'SyncArrivalOSC'.\n    \"\"\"\n\n    DISTANCE_THRESHOLD = 1\n\n    def __init__(self, actor, master_actor, actor_target, master_target, final_speed,\n                 relative_to_master=False, relative_type='', name=\"SyncArrivalOSC\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super(SyncArrivalOSC, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._actor = actor\n        self._actor_target = actor_target\n        self._master_actor = master_actor\n        self._master_target = master_target\n\n        self._final_speed = final_speed\n        self._final_speed_set = False\n        self._relative_to_master = relative_to_master\n        self._relative_type = relative_type\n\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set initial parameters and get (actor, controller) pair from Blackboard.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        # Get the distance of the actor to its endpoint\n        distance = calculate_distance(\n            CarlaDataProvider.get_location(self._actor), self._actor_target.location)\n\n        # Get the time to arrival of the reference to its endpoint\n        distance_reference = calculate_distance(\n            CarlaDataProvider.get_location(self._master_actor), self._master_target.location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._master_actor)\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n        else:\n            time_reference = float('inf')\n\n        # Get the required velocity of the actor\n        desired_velocity = distance / time_reference\n        actor_dict[self._actor.id].update_target_speed(desired_velocity, start_time=self._start_time)\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity to ensure that both actors reach their target\n        positions at the same time.\n        \"\"\"\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        # Get the distance of the actor to its endpoint\n        distance = calculate_distance(\n            CarlaDataProvider.get_location(self._actor), self._actor_target.location)\n\n        if distance < self.DISTANCE_THRESHOLD:\n            return py_trees.common.Status.SUCCESS  # Behaviour ends when the actor reaches its endpoint\n\n        # Get the time to arrival of the reference to its endpoint\n        distance_reference = calculate_distance(\n            CarlaDataProvider.get_location(self._master_actor), self._master_target.location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._master_actor)\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n        else:\n            time_reference = float('inf')\n\n        # Get the required velocity of the actor\n        desired_velocity = distance / time_reference\n        actor_dict[self._actor.id].update_target_speed(desired_velocity)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, set the target speed to its desired one.\n        This function is called several times, so the use of self._final_speed_set\n        is needed to avoid interfering with other running behaviors\n        \"\"\"\n        if not self._final_speed_set:\n            try:\n                check_actors = operator.attrgetter(\"ActorsWithController\")\n                actor_dict = check_actors(py_trees.blackboard.Blackboard())\n            except AttributeError:\n                pass\n\n            if actor_dict and self._actor.id in actor_dict:\n\n                if self._relative_to_master:\n                    master_speed = CarlaDataProvider.get_velocity(self._master_actor)\n                    if self._relative_type == 'delta':\n                        final_speed = master_speed + self._final_speed\n                    elif self._relative_type == 'factor':\n                        final_speed = master_speed * self._final_speed\n                    else:\n                        print(\"'relative_type' must be delta or factor\")\n                else:\n                    final_speed = self._final_speed\n\n                actor_dict[self._actor.id].update_target_speed(final_speed)\n\n            self._final_speed_set = True\n\n        super(SyncArrivalOSC, self).terminate(new_status)\n\n\nclass ChangeActorWaypoints(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the waypoints for an actor controller.\n\n    The behavior is in RUNNING state until the last waypoint is reached, or if a\n    second waypoint related atomic for the same actor is triggered. These are:\n    - ChangeActorWaypoints\n    - ChangeActorLateralMotion\n    - ChangeActorLaneOffset\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        waypoints (List of (OSC position, OSC route option)): List of (Position, Route Option) as OpenScenario elements.\n            position will be converted to Carla transforms, considering the corresponding\n            route option (e.g. shortest, fastest)\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorWaypoints'.\n\n    Attributes:\n        _waypoints (List of (OSC position, OSC route option)): List of (Position, Route Option) as OpenScenario elements\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n\n    '''Note: When using routing options such as fastest or shortest, it is advisable to run\n             in synchronous mode\n    \"\"\"\n\n    def __init__(self, actor, waypoints, name=\"ChangeActorWaypoints\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorWaypoints, self).__init__(name, actor)\n\n        self._waypoints = waypoints\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set _start_time and get (actor, controller) pair from Blackboard.\n\n        Set waypoint list for actor controller.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        # Transforming OSC waypoints to Carla waypoints\n        carla_route_elements = []\n        for (osc_point, routing_option) in self._waypoints:\n            carla_transforms = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n                osc_point)\n            carla_route_elements.append((carla_transforms, routing_option))\n\n        # Obtain final route, considering the routing option\n        # At the moment everything besides \"shortest\" will use the CARLA GlobalPlanner\n        grp = CarlaDataProvider.get_global_route_planner()\n        route = []\n        for i, _ in enumerate(carla_route_elements):\n            if carla_route_elements[i][1] == \"shortest\":\n                route.append(carla_route_elements[i][0])\n            else:\n                if i == 0:\n                    mmap = CarlaDataProvider.get_map()\n                    ego_location = CarlaDataProvider.get_location(self._actor)\n                    ego_waypoint = mmap.get_waypoint(ego_location)\n                    try:\n                        ego_next_wp = ego_waypoint.next(1)[0]\n                    except IndexError:\n                        ego_next_wp = ego_waypoint\n                    waypoint = ego_next_wp.transform.location\n                else:\n                    waypoint = carla_route_elements[i - 1][0].location\n                waypoint_next = carla_route_elements[i][0].location\n                try:\n                    interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n                except networkx.NetworkXNoPath:\n                    print(\"WARNING: No route from {} to {} - Using direct path instead\".format(waypoint, waypoint_next))\n                    route.append(carla_route_elements[i][0])\n                    continue\n                for wp_tuple in interpolated_trace:\n                    # The router sometimes produces points that go backward, or are almost identical\n                    # We have to filter these, to avoid problems\n                    if route and wp_tuple[0].transform.location.distance(route[-1].location) > 1.0:\n                        new_heading_vec = wp_tuple[0].transform.location - route[-1].location\n                        new_heading = np.arctan2(new_heading_vec.y, new_heading_vec.x)\n                        if len(route) > 1:\n                            last_heading_vec = route[-1].location - route[-2].location\n                        else:\n                            last_heading_vec = route[-1].location - ego_next_wp.transform.location\n                        last_heading = np.arctan2(last_heading_vec.y, last_heading_vec.x)\n\n                        heading_delta = math.fabs(new_heading - last_heading)\n                        if math.fabs(heading_delta) < 0.5 or math.fabs(heading_delta) > 5.5:\n                            route.append(wp_tuple[0].transform)\n                    elif not route:\n                        route.append(wp_tuple[0].transform)\n\n        actor_dict[self._actor.id].update_waypoints(route, start_time=self._start_time)\n\n        super(ChangeActorWaypoints, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's state along the waypoint route.\n\n        returns:\n            py_trees.common.Status.SUCCESS, if the final waypoint was reached, or\n                                            if another ChangeActorWaypoints atomic for the same actor was triggered.\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.FAILURE, else.\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if actor_dict[self._actor.id].check_reached_waypoint_goal():\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass ChangeActorLateralMotion(AtomicBehavior):\n\n    \"\"\"\n    Atomic to change the waypoints for an actor controller.\n\n    The behavior is in RUNNING state until the last waypoint is reached, or if a\n    second waypoint related atomic for the same actor is triggered. These are:\n    - ChangeActorWaypoints\n    - ChangeActorLateralMotion\n    - ChangeActorLaneOffset\n\n    If an impossible lane change is asked for (due to the lack of lateral lanes,\n    next waypoints, continuous line, etc) the atomic will return a plan with the\n    waypoints until such impossibility is found.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        direction (string): Lane change direction ('left' or 'right').\n            Defaults to 'left'.\n        distance_lane_change (float): Distance of the lance change [meters].\n            Defaults to 25.\n        distance_other_lane (float): Driven distance after the lange change [meters].\n            Defaults to 100.\n        name (string): Name of the behavior.\n            Defaults to 'ChangeActorLateralMotion'.\n\n    Attributes:\n        _waypoints (List of carla.Transform): List of waypoints representing the lane change (CARLA transforms).\n        _direction (string): Lane change direction ('left' or 'right').\n        _distance_same_lane (float): Distance on the same lane before the lane change starts [meters]\n            Constant to 5.\n        _distance_other_lane (float): Max. distance on the target lane after the lance change [meters]\n            Constant to 100.\n        _distance_lane_change (float): Max. total distance of the lane change [meters].\n        _pos_before_lane_change: carla.Location of the actor before the lane change.\n            Defaults to None.\n        _target_lane_id (int): Id of the target lane\n            Defaults to None.\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n    \"\"\"\n\n    def __init__(self, actor, direction='left', distance_lane_change=25, distance_other_lane=100,\n                 lane_changes=1, name=\"ChangeActorLateralMotion\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorLateralMotion, self).__init__(name, actor)\n\n        self._waypoints = []\n        self._direction = direction\n        self._distance_same_lane = 5\n        self._distance_other_lane = distance_other_lane\n        self._distance_lane_change = distance_lane_change\n        self._lane_changes = lane_changes\n        self._pos_before_lane_change = None\n        self._target_lane_id = None\n        self._plan = None\n\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set _start_time and get (actor, controller) pair from Blackboard.\n\n        Generate a waypoint list (route) which representes the lane change. Set\n        this waypoint list for the actor controller.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        # get start position\n        position_actor = CarlaDataProvider.get_map().get_waypoint(CarlaDataProvider.get_location(self._actor))\n\n        # calculate plan with scenario_helper function\n        self._plan, self._target_lane_id = generate_target_waypoint_list_multilane(\n            position_actor, self._direction, self._distance_same_lane,\n            self._distance_other_lane, self._distance_lane_change, check=False, lane_changes=self._lane_changes)\n\n        if self._plan:\n            for elem in self._plan:\n                self._waypoints.append(elem[0].transform)\n\n        actor_dict[self._actor.id].update_waypoints(self._waypoints, start_time=self._start_time)\n\n        super(ChangeActorLateralMotion, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's current state and if the lane change was completed\n\n        returns:\n            py_trees.common.Status.SUCCESS, if lane change was successful, or\n                                            if another ChangeActorLateralMotion atomic for the same actor was triggered.\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.FAILURE, else.\n        \"\"\"\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if not self._plan:\n            print(\"{} couldn't perform the expected lane change\".format(self._actor))\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location())\n        current_lane_id = current_position_actor.lane_id\n\n        if current_lane_id == self._target_lane_id:\n            # driving on new lane\n            distance = current_position_actor.transform.location.distance(self._pos_before_lane_change)\n\n            if distance > self._distance_other_lane:\n                # long enough distance on new lane --> SUCCESS\n                new_status = py_trees.common.Status.SUCCESS\n\n                new_waypoints = []\n                map_wp = current_position_actor\n                while len(new_waypoints) < 200:\n                    map_wps = map_wp.next(2.0)\n                    if map_wps:\n                        new_waypoints.append(map_wps[0].transform)\n                        map_wp = map_wps[0]\n                    else:\n                        break\n\n                actor_dict[self._actor.id].update_waypoints(new_waypoints, start_time=self._start_time)\n\n        else:\n            self._pos_before_lane_change = current_position_actor.transform.location\n\n        return new_status\n\n\nclass ChangeActorLaneOffset(AtomicBehavior):\n\n    \"\"\"\n    OpenSCENARIO atomic.\n    Atomic to change the offset of the controller.\n\n    The behavior is in RUNNING state until the offset os reached (if 'continuous' is set to False)\n    or forever (if 'continuous' is True). This behavior will automatically stop if a second waypoint\n    related atomic for the same actor is triggered. These are:\n    - ChangeActorWaypoints\n    - ChangeActorLateralMotion\n    - ChangeActorLaneOffset\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        offset (float): Float determined the distance to the center of the lane. Positive distance imply a\n            displacement to the right, while negative displacements are to the left.\n        relative_actor (carla.Actor): The actor from which the offset is taken from. Defaults to None\n        continuous (bool): If True, the behaviour never ends. If False, the behaviour ends when the lane\n            offset is reached. Defaults to True.\n\n    Attributes:\n        _offset (float): lane offset.\n        _relative_actor (carla.Actor): relative actor.\n        _continuous (bool): stored the value of the 'continuous' argument.\n        _start_time (float): Start time of the atomic [s].\n            Defaults to None.\n        _overwritten (bool): flag to check whether or not this behavior was overwritten by another. Helps\n            to avoid the missinteraction between two ChangeActorLaneOffsets.\n        _current_target_offset (float): stores the value of the offset when dealing with relative distances\n        _map (carla.Map): instance of the CARLA map.\n    \"\"\"\n\n    OFFSET_THRESHOLD = 0.1\n\n    def __init__(self, actor, offset, relative_actor=None, continuous=True, name=\"ChangeActorWaypoints\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeActorLaneOffset, self).__init__(name, actor)\n\n        self._offset = offset\n        self._relative_actor = relative_actor\n        self._continuous = continuous\n        self._start_time = None\n        self._current_target_offset = 0\n\n        self._overwritten = False\n        self._map = CarlaDataProvider.get_map()\n\n    def initialise(self):\n        \"\"\"\n        Set _start_time and get (actor, controller) pair from Blackboard.\n\n        Set offset for actor controller.\n\n        May throw if actor is not available as key for the ActorsWithController\n        dictionary from Blackboard.\n        \"\"\"\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n\n        actor_dict[self._actor.id].update_offset(self._offset, start_time=self._start_time)\n\n        super(ChangeActorLaneOffset, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check the actor's state along the waypoint route.\n\n        returns:\n            py_trees.common.Status.SUCCESS, if the lane offset was reached (and 'continuous' was False), or\n                                            if another waypoint atomic for the same actor was triggered\n            py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary.\n            py_trees.common.Status.RUNNING, else.\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or not self._actor.id in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_lane_offset_command() != self._start_time:\n            # Differentiate between lane offset and other lateral commands\n            self._overwritten = True\n            return py_trees.common.Status.SUCCESS\n\n        if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        if self._relative_actor:\n            # Calculate new offset\n            relative_actor_loc = CarlaDataProvider.get_location(self._relative_actor)\n            relative_center_wp = self._map.get_waypoint(relative_actor_loc)\n\n            # Value\n            relative_center_loc = relative_center_wp.transform.location\n            relative_actor_offset = relative_actor_loc.distance(relative_center_loc)\n\n            # Sign\n            f_vec = relative_center_wp.transform.get_forward_vector()\n            d_vec = relative_actor_loc - relative_center_loc\n            cross = f_vec.x * d_vec.y - f_vec.y * d_vec.x\n\n            if cross < 0:\n                relative_actor_offset *= -1.0\n\n            self._current_target_offset = relative_actor_offset + self._offset\n            # Set the new offset\n            actor_dict[self._actor.id].update_offset(self._current_target_offset)\n\n        if not self._continuous:\n            # Calculate new offset\n            actor_loc = CarlaDataProvider.get_location(self._actor)\n            center_wp = self._map.get_waypoint(actor_loc)\n\n            # Value\n            center_loc = center_wp.transform.location\n            actor_offset = actor_loc.distance(center_loc)\n\n            # Sign\n            f_vec = center_wp.transform.get_forward_vector()\n            d_vec = actor_loc - center_loc\n            cross = f_vec.x * d_vec.y - f_vec.y * d_vec.x\n\n            if cross < 0:\n                actor_offset *= -1.0\n\n            # Check if the offset has been reached\n            if abs(actor_offset - self._current_target_offset) < self.OFFSET_THRESHOLD:\n                return py_trees.common.Status.SUCCESS\n\n        # TODO: As their is no way to check the distance to a specific lane, both checks will fail if the\n        # actors are outside its 'route lane' or at an intersection\n\n        new_status = py_trees.common.Status.RUNNING\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, the offset is set back to zero\n        \"\"\"\n\n        if not self._overwritten:\n            try:\n                check_actors = operator.attrgetter(\"ActorsWithController\")\n                actor_dict = check_actors(py_trees.blackboard.Blackboard())\n            except AttributeError:\n                pass\n\n            if actor_dict and self._actor.id in actor_dict:\n                actor_dict[self._actor.id].update_offset(0)\n\n            self._overwritten = True\n\n        super(ChangeActorLaneOffset, self).terminate(new_status)\n\n\nclass ActorTransformSetterToOSCPosition(AtomicBehavior):\n\n    \"\"\"\n    OpenSCENARIO atomic\n    This class contains an atomic behavior to set the transform of an OpenSCENARIO actor.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - osc_position: OpenSCENARIO position\n    - physics [optional]: If physics is true, the actor physics will be reactivated upon success\n\n    The behavior terminates when actor is set to the new actor transform (closer than 1 meter)\n\n    NOTE:\n    It is very important to ensure that the actor location is spawned to the new transform because of the\n    appearence of a rare runtime processing error. WaypointFollower with LocalPlanner,\n    might fail if new_status is set to success before the actor is really positioned at the new transform.\n    Therefore: calculate_distance(actor, transform) < 1 meter\n    \"\"\"\n\n    def __init__(self, actor, osc_position, physics=True, name=\"ActorTransformSetterToOSCPosition\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ActorTransformSetterToOSCPosition, self).__init__(name, actor)\n        self._osc_position = osc_position\n        self._physics = physics\n        self._osc_transform = None\n\n    def initialise(self):\n\n        super(ActorTransformSetterToOSCPosition, self).initialise()\n\n        if self._actor.is_alive:\n            self._actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n            self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0))\n\n    def update(self):\n        \"\"\"\n        Transform actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # calculate transform with method in openscenario_parser.py\n        self._osc_transform = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n            self._osc_position)\n        self._actor.set_transform(self._osc_transform)\n\n        if not self._actor.is_alive:\n            new_status = py_trees.common.Status.FAILURE\n\n        if calculate_distance(self._actor.get_location(), self._osc_transform.location) < 1.0:\n            if self._physics:\n                self._actor.set_simulate_physics(enabled=True)\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass AccelerateToVelocity(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic acceleration behavior. The controlled\n    traffic participant will accelerate with _throttle_value_ until reaching\n    a given _target_velocity_\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - throttle_value: The amount of throttle used to accelerate in [0,1]\n    - target_velocity: The target velocity the actor should reach in m/s\n\n    The behavior will terminate, if the actor's velocity is at least target_velocity\n    \"\"\"\n\n    def __init__(self, actor, throttle_value, target_velocity, name=\"Acceleration\"):\n        \"\"\"\n        Setup parameters including acceleration value (via throttle_value)\n        and target velocity\n        \"\"\"\n        super(AccelerateToVelocity, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control, self._type = get_actor_control(actor)\n        self._throttle_value = throttle_value\n        self._target_velocity = target_velocity\n\n    def initialise(self):\n        # In case of walkers, we have to extract the current heading\n        if self._type == 'walker':\n            self._control.speed = self._target_velocity\n            self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector()\n\n        super(AccelerateToVelocity, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Set throttle to throttle_value, as long as velocity is < target_velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._type == 'vehicle':\n            if CarlaDataProvider.get_velocity(self._actor) < self._target_velocity:\n                self._control.throttle = self._throttle_value\n            else:\n                new_status = py_trees.common.Status.SUCCESS\n                self._control.throttle = 0\n\n        self._actor.apply_control(self._control)\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass AccelerateToCatchUp(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic acceleration behavior.\n    The car will accelerate until it is faster than another car, in order to catch up distance.\n    This behaviour is especially useful before a lane change (e.g. LaneChange atom).\n\n    Important parameters:\n    - actor: CARLA actor to execute the behaviour\n    - other_actor: Reference CARLA actor, actor you want to catch up to\n    - throttle_value: acceleration value between 0.0 and 1.0\n    - delta_velocity: speed up to the velocity of other actor plus delta_velocity\n    - trigger_distance: distance between the actors\n    - max_distance: driven distance to catch up has to be smaller than max_distance\n\n    The behaviour will terminate succesful, when the two actors are in trigger_distance.\n    If max_distance is driven by the actor before actors are in trigger_distance,\n    then the behaviour ends with a failure.\n    \"\"\"\n\n    def __init__(self, actor, other_actor, throttle_value=1, delta_velocity=10, trigger_distance=5,\n                 max_distance=500, name=\"AccelerateToCatchUp\"):\n        \"\"\"\n        Setup parameters\n        The target_speet is calculated on the fly.\n        \"\"\"\n        super(AccelerateToCatchUp, self).__init__(name, actor)\n\n        self._other_actor = other_actor\n        self._throttle_value = throttle_value\n        self._delta_velocity = delta_velocity  # 1m/s=3.6km/h\n        self._trigger_distance = trigger_distance\n        self._max_distance = max_distance\n\n        self._control, self._type = get_actor_control(actor)\n\n        self._initial_actor_pos = None\n\n    def initialise(self):\n\n        # get initial actor position\n        self._initial_actor_pos = CarlaDataProvider.get_location(self._actor)\n        super(AccelerateToCatchUp, self).initialise()\n\n    def update(self):\n\n        # get actor speed\n        actor_speed = CarlaDataProvider.get_velocity(self._actor)\n        target_speed = CarlaDataProvider.get_velocity(self._other_actor) + self._delta_velocity\n\n        # distance between actors\n        distance = CarlaDataProvider.get_location(self._actor).distance(\n            CarlaDataProvider.get_location(self._other_actor))\n\n        # driven distance of actor\n        driven_distance = CarlaDataProvider.get_location(self._actor).distance(self._initial_actor_pos)\n\n        if actor_speed < target_speed:\n            # set throttle to throttle_value to accelerate\n            self._control.throttle = self._throttle_value\n\n        if actor_speed >= target_speed:\n            # keep velocity until the actors are in trigger distance\n            self._control.throttle = 0\n\n        self._actor.apply_control(self._control)\n\n        # new status:\n        if distance <= self._trigger_distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        elif driven_distance > self._max_distance:\n            new_status = py_trees.common.Status.FAILURE\n        else:\n            new_status = py_trees.common.Status.RUNNING\n\n        return new_status\n\n\nclass KeepVelocity(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to keep the provided velocity.\n    The controlled traffic participant will accelerate as fast as possible\n    until reaching a given _target_velocity_, which is then maintained for\n    as long as this behavior is active.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_velocity: The target velocity the actor should reach\n    - forced_speed: Whether or not to forcefully set the actors speed. This will ony be active until a collision happens\n    - duration[optional]: Duration in seconds of this behavior\n    - distance[optional]: Maximum distance in meters covered by the actor during this behavior\n\n    A termination can be enforced by providing distance or duration values.\n    Alternatively, a parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, actor, target_velocity, force_speed=False,\n                 duration=float(\"inf\"), distance=float(\"inf\"), name=\"KeepVelocity\"):\n        \"\"\"\n        Setup parameters including acceleration value (via throttle_value)\n        and target velocity\n        \"\"\"\n        super(KeepVelocity, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._target_velocity = target_velocity\n\n        self._control, self._type = get_actor_control(actor)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._waypoint = self._map.get_waypoint(self._actor.get_location())\n\n        self._forced_speed = force_speed\n        self._duration = duration\n        self._target_distance = distance\n        self._distance = 0\n        self._start_time = 0\n        self._location = None\n\n    def initialise(self):\n        self._location = CarlaDataProvider.get_location(self._actor)\n        self._start_time = GameTime.get_time()\n\n        # In case of walkers, we have to extract the current heading\n        if self._type == 'walker':\n            self._control.speed = self._target_velocity\n            self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector()\n        elif self._type == 'vehicle':\n            self._control.hand_brake = False\n        self._actor.apply_control(self._control)\n\n        super(KeepVelocity, self).initialise()\n\n    def update(self):\n        \"\"\"\n        As long as the stop condition (duration or distance) is not violated, set a new vehicle control\n        For vehicles: set throttle to throttle_value, as long as velocity is < target_velocity\n        For walkers: simply apply the given self._control\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._type == 'vehicle':\n            if not self._forced_speed:\n                if CarlaDataProvider.get_velocity(self._actor) < self._target_velocity:\n                    self._control.throttle = 1.0\n                else:\n                    self._control.throttle = 0.0\n                self._actor.apply_control(self._control)\n            else:\n                yaw = CarlaDataProvider.get_transform(self._actor).rotation.yaw * (math.pi / 180)\n                self._actor.set_target_velocity(carla.Vector3D(\n                    math.cos(yaw) * self._target_velocity, math.sin(yaw) * self._target_velocity, 0))\n\n                # Add a throttle. Useless speed-wise, but makes the bicycle riders pedal.\n                self._actor.apply_control(carla.VehicleControl(throttle=1.0))\n\n        new_location = CarlaDataProvider.get_location(self._actor)\n        self._distance += calculate_distance(self._location, new_location)\n        self._location = new_location\n\n        if self._distance > self._target_distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, the throttle should be set back to 0.,\n        to avoid further acceleration.\n        \"\"\"\n        try:\n            if self._type == 'vehicle':\n                self._control.throttle = 0.0\n            elif self._type == 'walker':\n                self._control.speed = 0.0\n            if self._actor is not None and self._actor.is_alive:\n                self._actor.apply_control(self._control)\n        except RuntimeError:\n            pass\n        super(KeepVelocity, self).terminate(new_status)\n\n\nclass ChangeAutoPilot(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to disable/enable the use of the autopilot.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - activate: True (=enable autopilot) or False (=disable autopilot)\n    - lane_change: Traffic Manager parameter. True (=enable lane changes) or False (=disable lane changes)\n    - distance_between_vehicles: Traffic Manager parameter\n    - max_speed: Traffic Manager parameter. Max speed of the actor. This will only work for road segments\n                 with the same speed limit as the first one\n\n    The behavior terminates after changing the autopilot state\n    \"\"\"\n\n    def __init__(self, actor, activate, parameters=None, name=\"ChangeAutoPilot\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(ChangeAutoPilot, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._activate = activate\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(\n            CarlaDataProvider.get_traffic_manager_port())\n        self._parameters = parameters\n\n    def update(self):\n        \"\"\"\n        De/activate autopilot\n        \"\"\"\n        self._actor.set_autopilot(self._activate, CarlaDataProvider.get_traffic_manager_port())\n\n        if self._parameters is not None:\n            if \"auto_lane_change\" in self._parameters:\n                lane_change = self._parameters[\"auto_lane_change\"]\n                self._tm.auto_lane_change(self._actor, lane_change)\n\n            if \"max_speed\" in self._parameters:\n                max_speed = self._parameters[\"max_speed\"]\n                max_road_speed = self._actor.get_speed_limit()\n                if max_road_speed is not None:\n                    percentage = (max_road_speed - max_speed) / max_road_speed * 100.0\n                    self._tm.vehicle_percentage_speed_difference(self._actor, percentage)\n                else:\n                    print(\"ChangeAutopilot: Unable to find the vehicle's speed limit\")\n\n            if \"distance_between_vehicles\" in self._parameters:\n                dist_vehicles = self._parameters[\"distance_between_vehicles\"]\n                self._tm.distance_to_leading_vehicle(self._actor, dist_vehicles)\n\n            if \"force_lane_change\" in self._parameters:\n                force_lane_change = self._parameters[\"force_lane_change\"]\n                self._tm.force_lane_change(self._actor, force_lane_change)\n\n            if \"ignore_vehicles_percentage\" in self._parameters:\n                ignore_vehicles = self._parameters[\"ignore_vehicles_percentage\"]\n                self._tm.ignore_vehicles_percentage(self._actor, ignore_vehicles)\n\n        new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass StopVehicle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic stopping behavior. The controlled traffic\n    participant will decelerate with _bake_value_ until reaching a full stop.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - brake_value: Brake value in [0,1] applied\n\n    The behavior terminates when the actor stopped moving\n    \"\"\"\n\n    def __init__(self, actor, brake_value, name=\"Stopping\"):\n        \"\"\"\n        Setup _actor and maximum braking value\n        \"\"\"\n        super(StopVehicle, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control, self._type = get_actor_control(actor)\n        if self._type == 'walker':\n            self._control.speed = 0\n        self._brake_value = brake_value\n\n    def update(self):\n        \"\"\"\n        Set brake to brake_value until reaching full stop\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._type == 'vehicle':\n            if CarlaDataProvider.get_velocity(self._actor) > EPSILON:\n                self._control.brake = self._brake_value\n            else:\n                new_status = py_trees.common.Status.SUCCESS\n                self._control.brake = 0\n        else:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass SyncArrival(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to\n    set velocity of actor so that it reaches location at the same time as\n    actor_reference. The behavior assumes that the two actors are moving\n    towards location in a straight line.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - actor_reference: Reference actor with which arrival is synchronized\n    - target_location: CARLA location where the actors should \"meet\"\n    - gain[optional]: Coefficient for actor's throttle and break controls\n    Note: In parallel to this behavior a termination behavior has to be used\n          to keep continue synchronization for a certain duration, or for a\n          certain distance, etc.\n    \"\"\"\n\n    def __init__(self, actor, actor_reference, target_location, gain=1, name=\"SyncArrival\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super(SyncArrival, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control = carla.VehicleControl()\n        self._actor_reference = actor_reference\n        self._target_location = target_location\n        self._gain = gain\n\n        self._control.steering = 0\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        distance_reference = calculate_distance(CarlaDataProvider.get_location(self._actor_reference),\n                                                self._target_location)\n        distance = calculate_distance(CarlaDataProvider.get_location(self._actor),\n                                      self._target_location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._actor_reference)\n        time_reference = float('inf')\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n\n        velocity_current = CarlaDataProvider.get_velocity(self._actor)\n        time_current = float('inf')\n        if velocity_current > 0:\n            time_current = distance / velocity_current\n\n        control_value = (self._gain) * (time_current - time_reference)\n\n        if control_value > 0:\n            self._control.throttle = min([control_value, 1])\n            self._control.brake = 0\n        else:\n            self._control.throttle = 0\n            self._control.brake = min([abs(control_value), 1])\n\n        self._actor.apply_control(self._control)\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior, the throttle should be set back to 0.,\n        to avoid further acceleration.\n        \"\"\"\n        if self._actor is not None and self._actor.is_alive:\n            self._control.throttle = 0.0\n            self._control.brake = 0.0\n            self._actor.apply_control(self._control)\n        super(SyncArrival, self).terminate(new_status)\n\n\nclass SyncArrivalWithAgent(AtomicBehavior):\n\n    \"\"\"\n    Atomic to make two actors arrive at their corresponding places at the same time.\n    This uses a controller and presuposes that the actor can reach its destination by following the lane.\n\n    The behavior is in RUNNING state until the \"main\" actor has reached its destination.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        reference_actor (carla.Actor): Reference actor to sync up to.\n        actor_target (carla.Transform): Endpoint of the actor after the behavior finishes.\n        reference_target (carla.Transform): Endpoint of the reference_actor after the behavior finishes.\n        delay (float): Time difference between the actors synchronization.\n        end_dist (float): Minimum distance from the target to finish the behavior.\n        name (string): Name of the behavior.\n            Defaults to 'SyncArrivalWithAgent'.\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, actor_target, reference_target, end_dist=1,\n                 name=\"SyncArrivalWithAgent\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super().__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._actor = actor\n        self._actor_target = actor_target\n        self._reference_actor = reference_actor\n        self._reference_target = reference_target\n        self._end_dist = end_dist\n        self._agent = None\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        self._agent = ConstantVelocityAgent(\n            self._actor,\n            map_inst=CarlaDataProvider.get_map(),\n            grp_inst=CarlaDataProvider.get_global_route_planner())\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity to ensure that both actors reach their target\n        positions at the same time.\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Get the distance of the actor to its endpoint\n        distance = calculate_distance(\n            CarlaDataProvider.get_location(self._actor), self._actor_target.location)\n\n        # Check if the reference actor has passed its target\n        if distance < self._end_dist:\n            ref_dir = self._reference_target.get_forward_vector()\n            ref_veh = self._reference_target.location - self._reference_actor.get_location()\n            if ref_veh.dot(ref_dir) > 0:\n                return py_trees.common.Status.SUCCESS\n\n        # Get the time to arrival of the reference to its endpoint\n        distance_reference = calculate_distance(\n            CarlaDataProvider.get_location(self._reference_actor), self._reference_target.location)\n\n        velocity_reference = CarlaDataProvider.get_velocity(self._reference_actor)\n        if velocity_reference > 0:\n            time_reference = distance_reference / velocity_reference\n        else:\n            time_reference = float('inf')\n\n        # Get the required velocity of the actor\n        desired_velocity = distance / time_reference\n\n        self._agent.set_target_speed(3.6 * desired_velocity)\n        self._actor.apply_control(self._agent.run_step())\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Destroy the collision sensor of the agent\"\"\"\n        if self._agent:\n            self._agent.destroy_sensor()\n        return super().terminate(new_status)\n\n\nclass CutIn(AtomicBehavior):\n\n    \"\"\"\n    Atomic to make an actor lane change using a Python API agent, cutting in front of another one\n\n    The behavior creates a lane change path and is in RUNNING state until the \"main\" actor has finsihes it.\n\n    Args:\n        actor (carla.Actor): Controlled actor.\n        reference_actor (carla.Actor): Reference actor to cut in.\n        direction (string): Side from which the cut in happens. Either 'left' or 'right'.\n        speed_perc (float): Percentage of the reference actor speed on which the cut in is performed.\n        same_lane_time (float): Amount of time spent at the same lane before cutting in.\n        other_lane_time (float): Amount of time spent at the other lane after cutting in.\n        change_time (float): Amount of time spent changing into the other\n        name (string): Name of the behavior.\n            Defaults to 'CutIn'.\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, direction, speed_perc=100,\n                 same_lane_time=0, other_lane_time=0, change_time=2,\n                 name=\"CutIn\"):\n        \"\"\"\n        Setup required parameters\n        \"\"\"\n        super().__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._reference_actor = reference_actor\n        self._direction = direction\n        self._speed_perc = speed_perc\n        self._same_lane_time = same_lane_time\n        self._other_lane_time = other_lane_time\n        self._change_time = change_time\n\n        self._map = CarlaDataProvider.get_map()\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        speed = CarlaDataProvider.get_velocity(self._reference_actor)\n        self._agent = BasicAgent(\n            self._actor,\n            3.6 * speed * self._speed_perc / 100,\n            map_inst=CarlaDataProvider.get_map(),\n            grp_inst=CarlaDataProvider.get_global_route_planner())\n        self._agent.lane_change(self._direction, self._same_lane_time, self._other_lane_time, self._change_time)\n\n    def update(self):\n        \"\"\"\n        Dynamic control update for actor velocity to ensure that both actors reach their target\n        positions at the same time.\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        if self._agent.done():\n            return py_trees.common.Status.SUCCESS\n\n        self._actor.apply_control(self._agent.run_step())\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass AddNoiseToVehicle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic jitter behavior.\n    To add noise to steer as well as throttle of the vehicle.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - steer_value: Applied steering noise in [0,1]\n    - throttle_value: Applied throttle noise in [0,1]\n\n    The behavior terminates after setting the new actor controls\n    \"\"\"\n\n    def __init__(self, actor, steer_value, throttle_value, name=\"Jittering\"):\n        \"\"\"\n        Setup actor , maximum steer value and throttle value\n        \"\"\"\n        super(AddNoiseToVehicle, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._control = carla.VehicleControl()\n        self._steer_value = steer_value\n        self._throttle_value = throttle_value\n\n    def update(self):\n        \"\"\"\n        Set steer to steer_value and throttle to throttle_value until reaching full stop\n        \"\"\"\n        self._control = self._actor.get_control()\n        self._control.steer = self._steer_value\n        self._control.throttle = self._throttle_value\n        new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        self._actor.apply_control(self._control)\n\n        return new_status\n\n\nclass AddNoiseToRouteEgo(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic jitter behavior.\n    To add noise to steer as well as throttle of the vehicle.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - steer_value: Applied steering noise in [0,1]\n    - throttle_value: Applied throttle noise in [0,1]\n\n    The behavior terminates after setting the new actor controls\n    \"\"\"\n\n    def __init__(self, actor, throttle_mean, throttle_std, steer_mean, steer_std, name=\"AddNoiseToVehicle\"):\n        \"\"\"\n        Setup actor , maximum steer value and throttle value\n        \"\"\"\n        super().__init__(name, actor)\n        self._throttle_mean = throttle_mean\n        self._throttle_std = throttle_std\n        self._steer_mean = steer_mean\n        self._steer_std = steer_std\n\n        self._rng = CarlaDataProvider.get_random_seed()\n\n    def update(self):\n        \"\"\"\n        Set steer to steer_value and throttle to throttle_value until reaching full stop\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        control = py_trees.blackboard.Blackboard().get(\"AV_control\")\n        if not control:\n            print(\"WARNING: Couldn't add noise to the ego because the control couldn't be found\")\n            return new_status\n\n        throttle_noise = random.normal(self._throttle_mean, self._throttle_std)\n        control.throttle = max(0, min(1, control.throttle + throttle_noise))\n\n        steer_noise = random.normal(self._steer_mean, self._steer_std)\n        control.steer = max(-1, min(1, control.steer + steer_noise))\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        self._actor.apply_control(control)\n\n        return new_status\n\n\nclass ChangeNoiseParameters(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic jitter behavior.\n    To add noise to steer as well as throttle of the vehicle.\n\n    This behavior should be used in conjuction with AddNoiseToVehicle\n\n    The behavior terminates after one iteration\n    \"\"\"\n\n    def __init__(self, new_steer_noise, new_throttle_noise,\n                 noise_mean, noise_std, dynamic_mean_for_steer, dynamic_mean_for_throttle, name=\"ChangeJittering\"):\n        \"\"\"\n        Setup actor , maximum steer value and throttle value\n        \"\"\"\n        super(ChangeNoiseParameters, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._new_steer_noise = new_steer_noise\n        self._new_throttle_noise = new_throttle_noise\n        self._noise_mean = noise_mean\n        self._noise_std = noise_std\n        self._dynamic_mean_for_steer = dynamic_mean_for_steer\n        self._dynamic_mean_for_throttle = dynamic_mean_for_throttle\n\n        self._noise_to_apply = abs(random.normal(self._noise_mean, self._noise_std))\n\n    def update(self):\n        \"\"\"\n        Change the noise parameters from the structure copy that it receives.\n        \"\"\"\n\n        self._new_steer_noise[0] = min(0, -(self._noise_to_apply - self._dynamic_mean_for_steer))\n        self._new_throttle_noise[0] = min(self._noise_to_apply + self._dynamic_mean_for_throttle, 1)\n\n        new_status = py_trees.common.Status.SUCCESS\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass BasicAgentBehavior(AtomicBehavior):\n    \"\"\"\n    This class contains an atomic behavior, which uses the\n    basic_agent from CARLA to control the actor until\n    reaching a target location.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_location: Is the desired target location (carla.location),\n                       the actor should move to\n    The behavior terminates after reaching the target_location (within 2 meters)\n    \"\"\"\n\n    def __init__(self, actor, target_location=None, plan=None, target_speed=20, opt_dict=None, name=\"BasicAgentBehavior\"):\n        \"\"\"\n        Setup actor and maximum steer value\n        \"\"\"\n        super(BasicAgentBehavior, self).__init__(name, actor)\n        self._map = CarlaDataProvider.get_map()\n        self._target_location = target_location\n        self._target_speed = target_speed\n        self._plan = plan\n\n        self._opt_dict = opt_dict if opt_dict else {}\n        self._control = carla.VehicleControl()\n        self._agent = None\n\n        if self._target_location and self._plan:\n            raise ValueError(\"Choose either a destination or a plan, but not both\")\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        self._agent = BasicAgent(self._actor, self._target_speed, opt_dict=self._opt_dict,\n            map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner())\n        if self._plan:\n            self._agent.set_global_plan(self._plan)\n        elif self._target_location:\n            init_wp = self._map.get_waypoint(CarlaDataProvider.get_location(self._actor))\n            end_wp = self._map.get_waypoint(self._target_location)\n            self._plan = self._agent.trace_route(init_wp, end_wp)\n            self._agent.set_global_plan(self._plan)\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._agent.done():\n            new_status = py_trees.common.Status.SUCCESS\n        self._control = self._agent.run_step()\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Resets the control\"\"\"\n        self._control.throttle = 0.0\n        self._control.brake = 0.0\n        self._actor.apply_control(self._control)\n        super(BasicAgentBehavior, self).terminate(new_status)\n\n\nclass ConstantVelocityAgentBehavior(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior, which uses the\n    constant_velocity_agent from CARLA to control the actor until\n    reaching a target location.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_location: Is the desired target location (carla.location),\n                       the actor should move to\n    - plan: List of [carla.Waypoint, RoadOption] to pass to the controller\n    - target_speed: Desired speed of the actor\n    The behavior terminates after reaching the target_location (within 2 meters)\n    \"\"\"\n\n    def __init__(self, actor, target_location, target_speed=None,\n                 opt_dict=None, name=\"ConstantVelocityAgentBehavior\"):\n        \"\"\"\n        Set up actor and local planner\n        \"\"\"\n        super(ConstantVelocityAgentBehavior, self).__init__(name, actor)\n        self._target_speed = target_speed\n        self._map = CarlaDataProvider.get_map()\n        self._target_location = target_location\n        self._opt_dict = opt_dict if opt_dict else {}\n        self._control = carla.VehicleControl()\n        self._agent = None\n        self._plan = None\n\n        self._map = CarlaDataProvider.get_map()\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        self._agent = ConstantVelocityAgent(\n            self._actor, self._target_speed * 3.6, opt_dict=self._opt_dict,\n            map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner())\n        self._plan = self._agent.trace_route(\n            self._map.get_waypoint(CarlaDataProvider.get_location(self._actor)),\n            self._map.get_waypoint(self._target_location))\n        self._agent.set_global_plan(self._plan)\n\n    def update(self):\n        \"\"\"Moves the actor and waits for it to finish the plan\"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._agent.done():\n            new_status = py_trees.common.Status.SUCCESS\n\n        self._control = self._agent.run_step()\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Resets the control\"\"\"\n        self._control.throttle = 0.0\n        self._control.brake = 0.0\n        self._actor.apply_control(self._control)\n        if self._agent:\n            self._agent.destroy_sensor()\n        super(ConstantVelocityAgentBehavior, self).terminate(new_status)\n\nclass AdaptiveConstantVelocityAgentBehavior(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior, which uses the\n    constant_velocity_agent from CARLA to control the actor until\n    reaching a target location.\n    Important parameters:\n    - actor: CARLA actor to execute the behavior.\n    - reference_actor: Reference CARLA actor to get target speed.\n    - speed_increment: Float value (m/s). \n                       How much the actor will be faster then the reference_actor.\n    - target_location: Is the desired target location (carla.location),\n                       the actor should move to. \n                       If it's None, the actor will follow the lane and never stop.\n    - plan: List of [carla.Waypoint, RoadOption] to pass to the controller.\n    The behavior terminates after reaching the target_location (within 2 meters)\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, target_location=None, speed_increment=10,\n                 opt_dict=None, name=\"AdaptiveConstantVelocityAgentBehavior\"):\n        \"\"\"\n        Set up actor and local planner\n        \"\"\"\n        super().__init__(name, actor)\n        self._speed_increment = speed_increment\n        self._reference_actor = reference_actor\n        self._target_location = target_location\n        self._opt_dict = opt_dict if opt_dict else {}\n        self._control = carla.VehicleControl()\n        self._agent = None\n        self._plan = None\n\n        self._map = CarlaDataProvider.get_map()\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n    def initialise(self):\n        \"\"\"Initialises the agent\"\"\"\n        # Get target speed\n        target_speed = get_speed(self._reference_actor) + self._speed_increment * 3.6\n\n        self._agent = ConstantVelocityAgent(self._actor, target_speed, opt_dict=self._opt_dict,\n                                            map_inst=self._map, grp_inst=self._grp)\n\n        if self._target_location is not None:\n            self._plan = self._agent.trace_route(\n                self._map.get_waypoint(CarlaDataProvider.get_location(self._actor)),\n                self._map.get_waypoint(self._target_location))\n            self._agent.set_global_plan(self._plan)\n\n    def update(self):\n        \"\"\"Moves the actor and waits for it to finish the plan\"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        target_speed = get_speed(self._reference_actor) + self._speed_increment * 3.6\n        self._agent.set_target_speed(target_speed)\n\n        if self._agent.done():\n            new_status = py_trees.common.Status.SUCCESS\n\n        self._control = self._agent.run_step()\n        self._actor.apply_control(self._control)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Resets the control\"\"\"\n        self._control.throttle = 0.0\n        self._control.brake = 0.0\n        self._actor.apply_control(self._control)\n        if self._agent:\n            self._agent.destroy_sensor()\n        super().terminate(new_status)\n\nclass Idle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an idle behavior scenario\n\n    Important parameters:\n    - duration[optional]: Duration in seconds of this behavior\n\n    A termination can be enforced by providing a duration value.\n    Alternatively, a parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, duration=float(\"inf\"), name=\"Idle\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(Idle, self).__init__(name)\n        self._duration = duration\n        self._start_time = 0\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        super(Idle, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\nclass WaitForever(AtomicBehavior):\n\n    \"\"\"\n    This class contains a behavior that just waits forever.\n    Useful to stop some behavior sequences from stopping unwated parts of the behavior tree\n\n    Alternatively, a parallel termination behavior has to be used to stop it.\n    \"\"\"\n\n    def __init__(self, name=\"WaitForever\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super().__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        wait forever\n        \"\"\"\n        return py_trees.common.Status.RUNNING\n\n\nclass WaypointFollower(AtomicBehavior):\n\n    \"\"\"\n    This is an atomic behavior to follow waypoints while maintaining a given speed.\n    If no plan is provided, the actor will follow its foward waypoints indefinetely.\n    Otherwise, the behavior will end with SUCCESS upon reaching the end of the plan.\n    If no target velocity is provided, the actor continues with its current velocity.\n\n    Args:\n        actor (carla.Actor):  CARLA actor to execute the behavior.\n        target_speed (float, optional): Desired speed of the actor in m/s. Defaults to None.\n        plan ([carla.Location] or [(carla.Waypoint, carla.agent.navigation.local_planner)], optional):\n            Waypoint plan the actor should follow. Defaults to None.\n        blackboard_queue_name (str, optional):\n            Blackboard variable name, if additional actors should be created on-the-fly. Defaults to None.\n        avoid_collision (bool, optional):\n            Enable/Disable(=default) collision avoidance for vehicles/bikes. Defaults to False.\n        name (str, optional): Name of the behavior. Defaults to \"FollowWaypoints\".\n\n    Attributes:\n        actor (carla.Actor):  CARLA actor to execute the behavior.\n        name (str, optional): Name of the behavior.\n        _target_speed (float, optional): Desired speed of the actor in m/s. Defaults to None.\n        _plan ([carla.Location] or [(carla.Waypoint, carla.agent.navigation.local_planner)]):\n            Waypoint plan the actor should follow. Defaults to None.\n        _blackboard_queue_name (str):\n            Blackboard variable name, if additional actors should be created on-the-fly. Defaults to None.\n        _avoid_collision (bool): Enable/Disable(=default) collision avoidance for vehicles/bikes. Defaults to False.\n        _actor_dict: Dictonary of all actors, and their corresponding plans (e.g. {actor: plan}).\n        _local_planner_dict: Dictonary of all actors, and their corresponding local planners.\n            Either \"Walker\" for pedestrians, or a carla.agent.navigation.LocalPlanner for other actors.\n        _args_lateral_dict: Parameters for the PID of the used carla.agent.navigation.LocalPlanner.\n        _unique_id: Unique ID of the behavior based on timestamp in nanoseconds.\n\n    Note:\n        OpenScenario:\n        The WaypointFollower atomic must be called with an individual name if multiple consecutive WFs.\n        Blackboard variables with lists are used for consecutive WaypointFollower behaviors.\n        Termination of active WaypointFollowers in initialise of AtomicBehavior because any\n        following behavior must terminate the WaypointFollower.\n    \"\"\"\n\n    def __init__(self, actor, target_speed=None, plan=None, blackboard_queue_name=None,\n                 avoid_collision=False, name=\"FollowWaypoints\"):\n        \"\"\"\n        Set up actor and local planner\n        \"\"\"\n        super(WaypointFollower, self).__init__(name, actor)\n        self._actor_dict = {}\n        self._actor_dict[actor] = None\n        self._target_speed = target_speed\n        self._local_planner_dict = {}\n        self._local_planner_dict[actor] = None\n        self._plan = plan\n        self._blackboard_queue_name = blackboard_queue_name\n        if blackboard_queue_name is not None:\n            self._queue = Blackboard().get(blackboard_queue_name)\n        self._args_lateral_dict = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05}\n        self._avoid_collision = avoid_collision\n        self._unique_id = 0\n\n    def initialise(self):\n        \"\"\"\n        Delayed one-time initialization\n\n        Checks if another WaypointFollower behavior is already running for this actor.\n        If this is the case, a termination signal is sent to the running behavior.\n        \"\"\"\n        super(WaypointFollower, self).initialise()\n        self._unique_id = int(round(time.time() * 1e9))\n        try:\n            # check whether WF for this actor is already running and add new WF to running_WF list\n            check_attr = operator.attrgetter(\"running_WF_actor_{}\".format(self._actor.id))\n            running = check_attr(py_trees.blackboard.Blackboard())\n            active_wf = copy.copy(running)\n            active_wf.append(self._unique_id)\n            py_trees.blackboard.Blackboard().set(\n                \"running_WF_actor_{}\".format(self._actor.id), active_wf, overwrite=True)\n        except AttributeError:\n            # no WF is active for this actor\n            py_trees.blackboard.Blackboard().set(\"terminate_WF_actor_{}\".format(self._actor.id), [], overwrite=True)\n            py_trees.blackboard.Blackboard().set(\n                \"running_WF_actor_{}\".format(self._actor.id), [self._unique_id], overwrite=True)\n\n        for actor in self._actor_dict:\n            self._apply_local_planner(actor)\n        return True\n\n    def _apply_local_planner(self, actor):\n        \"\"\"\n        Convert the plan into locations for walkers (pedestrians), or to a waypoint list for other actors.\n        For non-walkers, activate the carla.agent.navigation.LocalPlanner module.\n        \"\"\"\n        if self._target_speed is None:\n            self._target_speed = CarlaDataProvider.get_velocity(actor)\n        else:\n            self._target_speed = self._target_speed\n\n        if isinstance(actor, carla.Walker):\n            self._local_planner_dict[actor] = \"Walker\"\n            if self._plan is not None:\n                if isinstance(self._plan[0], carla.Location):\n                    self._actor_dict[actor] = self._plan\n                else:\n                    self._actor_dict[actor] = [element[0].transform.location for element in self._plan]\n        else:\n            local_planner = LocalPlanner(  # pylint: disable=undefined-variable\n                actor, opt_dict={\n                    'target_speed': self._target_speed * 3.6,\n                    'lateral_control_dict': self._args_lateral_dict,\n                    'max_throttle': 1.0})\n\n            if self._plan is not None:\n                if isinstance(self._plan[0], carla.Location):\n                    plan = []\n                    for location in self._plan:\n                        waypoint = CarlaDataProvider.get_map().get_waypoint(location,\n                                                                            project_to_road=True,\n                                                                            lane_type=carla.LaneType.Any)\n                        plan.append((waypoint, RoadOption.LANEFOLLOW))\n                    local_planner.set_global_plan(plan)\n                else:\n                    local_planner.set_global_plan(self._plan)\n\n            self._local_planner_dict[actor] = local_planner\n            self._actor_dict[actor] = self._plan\n\n    def update(self):\n        \"\"\"\n        Compute next control step for the given waypoint plan, obtain and apply control to actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        check_term = operator.attrgetter(\"terminate_WF_actor_{}\".format(self._actor.id))\n        terminate_wf = check_term(py_trees.blackboard.Blackboard())\n\n        check_run = operator.attrgetter(\"running_WF_actor_{}\".format(self._actor.id))\n        active_wf = check_run(py_trees.blackboard.Blackboard())\n\n        # Termination of WF if the WFs unique_id is listed in terminate_wf\n        # only one WF should be active, therefore all previous WF have to be terminated\n        if self._unique_id in terminate_wf:\n            terminate_wf.remove(self._unique_id)\n            if self._unique_id in active_wf:\n                active_wf.remove(self._unique_id)\n\n            py_trees.blackboard.Blackboard().set(\n                \"terminate_WF_actor_{}\".format(self._actor.id), terminate_wf, overwrite=True)\n            py_trees.blackboard.Blackboard().set(\n                \"running_WF_actor_{}\".format(self._actor.id), active_wf, overwrite=True)\n            new_status = py_trees.common.Status.SUCCESS\n            return new_status\n\n        if self._blackboard_queue_name is not None:\n            while not self._queue.empty():\n                actor = self._queue.get()\n                if actor is not None and actor not in self._actor_dict:\n                    self._apply_local_planner(actor)\n\n        success = True\n        for actor in self._local_planner_dict:\n            local_planner = self._local_planner_dict[actor] if actor else None\n            if actor is not None and actor.is_alive and local_planner is not None:\n                # Check if the actor is a vehicle/bike\n                if not isinstance(actor, carla.Walker):\n                    control = local_planner.run_step(debug=False)\n                    if self._avoid_collision and detect_lane_obstacle(actor):\n                        control.throttle = 0.0\n                        control.brake = 1.0\n                    actor.apply_control(control)\n                    # Check if the actor reached the end of the plan\n                    # @TODO replace access to private _waypoints_queue with public getter\n                    if local_planner._waypoints_queue:  # pylint: disable=protected-access\n                        success = False\n                # If the actor is a pedestrian, we have to use the WalkerAIController\n                # The walker is sent to the next waypoint in its plan\n                else:\n                    actor_location = CarlaDataProvider.get_location(actor)\n                    success = False\n                    if self._actor_dict[actor]:\n                        location = self._actor_dict[actor][0]\n                        direction = location - actor_location\n                        direction_norm = math.sqrt(direction.x**2 + direction.y**2)\n                        control = actor.get_control()\n                        control.speed = self._target_speed\n                        control.direction = direction / direction_norm\n                        actor.apply_control(control)\n                        if direction_norm < 1.0:\n                            self._actor_dict[actor] = self._actor_dict[actor][1:]\n                            if self._actor_dict[actor] is None:\n                                success = True\n                    else:\n                        control = actor.get_control()\n                        control.speed = self._target_speed\n                        control.direction = CarlaDataProvider.get_transform(actor).rotation.get_forward_vector()\n                        actor.apply_control(control)\n\n        if success:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        On termination of this behavior,\n        the controls should be set back to 0.\n        \"\"\"\n        for actor in self._local_planner_dict:\n            if actor is not None and actor.is_alive:\n                control, _ = get_actor_control(actor)\n                actor.apply_control(control)\n                local_planner = self._local_planner_dict[actor]\n                if local_planner is not None and local_planner != \"Walker\":\n                    local_planner.reset_vehicle()\n                    local_planner = None\n\n        self._local_planner_dict = {}\n        self._actor_dict = {}\n        super(WaypointFollower, self).terminate(new_status)\n\n\nclass LaneChange(WaypointFollower):\n\n    \"\"\"\n    This class inherits from the class WaypointFollower.\n\n    This class contains an atomic lane change behavior to a parallel lane.\n    The vehicle follows a waypoint plan to the other lane, which is calculated in the initialise method.\n    This waypoint plan is calculated with a scenario helper function.\n\n    If an impossible lane change is asked for (due to the lack of lateral lanes,\n    next waypoints, continuous line, etc) the atomic will return a plan with the\n    waypoints until such impossibility is found.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - speed: speed of the actor for the lane change, in m/s\n    - direction: 'right' or 'left', depending on which lane to change\n    - distance_same_lane: straight distance before lane change, in m\n    - distance_other_lane: straight distance after lane change, in m\n    - distance_lane_change: straight distance for the lane change itself, in m\n\n    The total distance driven is greater than the sum of distance_same_lane and distance_other_lane.\n    It results from the lane change distance plus the distance_same_lane plus distance_other_lane.\n    The lane change distance is set to 25m (straight), the driven distance is slightly greater.\n\n    A parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, actor, speed=10, direction='left', distance_same_lane=5, distance_other_lane=100,\n                 distance_lane_change=25, lane_changes=1, name='LaneChange'):\n\n        self._direction = direction\n        self._distance_same_lane = distance_same_lane\n        self._distance_other_lane = distance_other_lane\n        self._distance_lane_change = distance_lane_change\n        self._lane_changes = lane_changes\n\n        self._target_lane_id = None\n        self._distance_new_lane = 0\n        self._pos_before_lane_change = None\n        self._plan = None\n\n        super(LaneChange, self).__init__(actor, target_speed=speed, name=name)\n\n    def initialise(self):\n\n        # get start position\n        position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location())\n\n        # calculate plan with scenario_helper function\n        self._plan, self._target_lane_id = generate_target_waypoint_list_multilane(\n            position_actor, self._direction, self._distance_same_lane,\n            self._distance_other_lane, self._distance_lane_change, check=True, lane_changes=self._lane_changes)\n        super(LaneChange, self).initialise()\n\n    def update(self):\n\n        if not self._plan:\n            print(\"{} couldn't perform the expected lane change\".format(self._actor))\n            return py_trees.common.Status.FAILURE\n\n        status = super(LaneChange, self).update()\n\n        current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location())\n        current_lane_id = current_position_actor.lane_id\n\n        if current_lane_id == self._target_lane_id:\n            # driving on new lane\n            distance = current_position_actor.transform.location.distance(self._pos_before_lane_change)\n\n            if distance > self._distance_other_lane:\n                # long enough distance on new lane --> SUCCESS\n                status = py_trees.common.Status.SUCCESS\n        else:\n            self._pos_before_lane_change = current_position_actor.transform.location\n\n        return status\n\n\nclass SetInitSpeed(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the init_speed of an actor,\n    succeding immeditely after initializing\n    \"\"\"\n\n    def __init__(self, actor, init_speed=10, name='SetInitSpeed'):\n\n        self._init_speed = init_speed\n        self._terminate = None\n        self._actor = actor\n\n        super(SetInitSpeed, self).__init__(name, actor)\n\n    def initialise(self):\n        \"\"\"\n        Initialize it's speed\n        \"\"\"\n\n        transform = self._actor.get_transform()\n        yaw = transform.rotation.yaw * (math.pi / 180)\n\n        vx = math.cos(yaw) * self._init_speed\n        vy = math.sin(yaw) * self._init_speed\n        self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0))\n\n    def update(self):\n        \"\"\"\n        Nothing to update, end the behavior\n        \"\"\"\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass HandBrakeVehicle(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic hand brake behavior.\n    To set the hand brake value of the vehicle.\n\n    Important parameters:\n    - vehicle: CARLA actor to execute the behavior\n    - hand_brake_value to be applied in [0,1]\n\n    The behavior terminates after setting the hand brake value\n    \"\"\"\n\n    def __init__(self, vehicle, hand_brake_value, name=\"Braking\"):\n        \"\"\"\n        Setup vehicle control and brake value\n        \"\"\"\n        super(HandBrakeVehicle, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._vehicle = vehicle\n        self._control, self._type = get_actor_control(vehicle)\n        self._hand_brake_value = hand_brake_value\n\n    def update(self):\n        \"\"\"\n        Set handbrake\n        \"\"\"\n        new_status = py_trees.common.Status.SUCCESS\n        if self._type == 'vehicle':\n            self._control.hand_brake = self._hand_brake_value\n            self._vehicle.apply_control(self._control)\n        else:\n            self._hand_brake_value = None\n            self.logger.debug(\"%s.update()[%s->%s]\" %\n                              (self.__class__.__name__, self.status, new_status))\n            self._vehicle.apply_control(self._control)\n\n        return new_status\n\n\nclass ActorDestroy(AtomicBehavior):\n\n    \"\"\"\n    This class contains an actor destroy behavior.\n    Given an actor this behavior will delete it.\n\n    Important parameters:\n    - actor: CARLA actor to be deleted\n\n    The behavior terminates after removing the actor\n    \"\"\"\n\n    def __init__(self, actor, name=\"ActorDestroy\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(ActorDestroy, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n        if self._actor:\n            CarlaDataProvider.remove_actor_by_id(self._actor.id)\n            self._actor = None\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass ActorTransformSetter(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the transform\n    of an actor.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - transform: New target transform (position + orientation) of the actor\n    - physics [optional]: Change the physics of the actors to true / false. To not change the physics, use None.\n\n    The behavior terminates when actor is set to the new actor transform (closer than 1 meter)\n\n    NOTE:\n    It is very important to ensure that the actor location is spawned to the new transform because of the\n    appearence of a rare runtime processing error. WaypointFollower with LocalPlanner,\n    might fail if new_status is set to success before the actor is really positioned at the new transform.\n    Therefore: calculate_distance(actor, transform) < 1 meter\n    \"\"\"\n\n    def __init__(self, actor, transform, physics=True, name=\"ActorTransformSetter\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super(ActorTransformSetter, self).__init__(name, actor)\n        self._transform = transform\n        self._physics = physics\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        if self._actor.is_alive:\n            self._actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n            self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0))\n            self._actor.set_transform(self._transform)\n        super(ActorTransformSetter, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Transform actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if not self._actor.is_alive:\n            new_status = py_trees.common.Status.FAILURE\n\n        if calculate_distance(self._actor.get_location(), self._transform.location) < 1.0:\n            if self._physics is not None:\n                self._actor.set_simulate_physics(self._physics)\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass BatchActorTransformSetter(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the transform\n    of an actor.\n\n    Important parameters:\n    - actor_transform_list: list [carla.Actor, carla.Transform]\n    - physics [optional]: Change the physics of the actors to true / false. To not change the physics, use None.\n\n    The behavior terminates immediately\n    \"\"\"\n\n    def __init__(self, actor_transform_list, physics=True, name=\"BatchActorTransformSetter\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super().__init__(name)\n        self._actor_transform_list = actor_transform_list\n        self._physics = physics\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Transform actor\n        \"\"\"\n\n        for actor, transform in self._actor_transform_list:\n            actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n            actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0))\n            actor.set_transform(transform)\n            if self._physics is not None:\n                actor.set_simulate_physics(self._physics)\n\n        return py_trees.common.Status.SUCCESS\n\n\nclass TrafficLightStateSetter(AtomicBehavior):\n\n    \"\"\"\n    This class contains an atomic behavior to set the state of a given traffic light\n\n    Args:\n        actor (carla.TrafficLight): ID of the traffic light that shall be changed\n        state (carla.TrafficLightState): New target state\n\n    The behavior terminates after trying to set the new state\n    \"\"\"\n\n    def __init__(self, actor, state, name=\"TrafficLightStateSetter\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super(TrafficLightStateSetter, self).__init__(name)\n\n        self._actor = actor if \"traffic_light\" in actor.type_id else None\n        self._state = state\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Change the state of the traffic light\n        \"\"\"\n        if self._actor is None:\n            return py_trees.common.Status.FAILURE\n\n        new_status = py_trees.common.Status.RUNNING\n        if self._actor.is_alive:\n            self._actor.set_state(self._state)\n            new_status = py_trees.common.Status.SUCCESS\n        else:\n            # For some reason the actor is gone...\n            new_status = py_trees.common.Status.FAILURE\n\n        return new_status\n\n\nclass ActorSource(AtomicBehavior):\n\n    \"\"\"\n    Implementation for a behavior that will indefinitely create actors\n    at a given transform if no other actor exists in a given radius\n    from the transform.\n\n    Important parameters:\n    - actor_type_list: Type of CARLA actors to be spawned\n    - transform: Spawn location\n    - threshold: Min available free distance between other actors and the spawn location\n    - blackboard_queue_name: Name of the blackboard used to control this behavior\n    - actor_limit [optional]: Maximum number of actors to be spawned (default=7)\n\n    A parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, actor_type_list, transform, threshold, blackboard_queue_name,\n                 actor_limit=7, name=\"ActorSource\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(ActorSource, self).__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._actor_types = actor_type_list\n        self._spawn_point = transform\n        self._threshold = threshold\n        self._queue = Blackboard().get(blackboard_queue_name)\n        self._actor_limit = actor_limit\n        self._last_blocking_actor = None\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n        if self._actor_limit > 0:\n            world_actors = CarlaDataProvider.get_all_actors()\n            spawn_point_blocked = False\n            if (self._last_blocking_actor and\n                    self._spawn_point.location.distance(self._last_blocking_actor.get_location()) < self._threshold):\n                spawn_point_blocked = True\n\n            if not spawn_point_blocked:\n                for actor in world_actors:\n                    if self._spawn_point.location.distance(actor.get_location()) < self._threshold:\n                        spawn_point_blocked = True\n                        self._last_blocking_actor = actor\n                        break\n\n            if not spawn_point_blocked:\n                try:\n                    new_actor = CarlaDataProvider.request_new_actor(\n                        random.choice(self._actor_types), self._spawn_point)\n                    self._actor_limit -= 1\n                    self._queue.put(new_actor)\n                except:                             # pylint: disable=bare-except\n                    print(\"ActorSource unable to spawn actor\")\n        return new_status\n\n\nclass ActorSink(AtomicBehavior):\n\n    \"\"\"\n    Implementation for a behavior that will indefinitely destroy actors\n    that wander near a given location within a specified threshold.\n\n    Important parameters:\n    - actor_type_list: Type of CARLA actors to be spawned\n    - sink_location: Location (carla.location) at which actors will be deleted\n    - threshold: Distance around sink_location in which actors will be deleted\n\n    A parallel termination behavior has to be used.\n    \"\"\"\n\n    def __init__(self, sink_location, threshold, name=\"ActorSink\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(ActorSink, self).__init__(name)\n        self._sink_location = sink_location\n        self._threshold = threshold\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n        CarlaDataProvider.remove_actors_in_surrounding(self._sink_location, self._threshold)\n        return new_status\n\n\nclass ActorFlow(AtomicBehavior):\n    \"\"\"\n    Behavior that indefinitely creates actors at a location,\n    controls them until another location, and then destroys them.\n    Therefore, a parallel termination behavior has to be used.\n\n    Important parameters:\n    - source_transform (carla.Transform): Transform at which actors will be spawned\n    - sink_location (carla.Location): Location at which actors will be deleted\n    - spawn_distance: Distance between spawned actors\n    - sink_distance: Actors closer to the sink than this distance will be deleted\n    - actors_speed: Speed of the actors part of the flow [m/s]\n    - initial_actors: Populates all the flow trajectory at the start\n    \"\"\"\n\n    def __init__(self, source_wp, sink_wp, spawn_dist_interval, sink_dist=2,\n                 actor_speed=20 / 3.6, initial_actors=False, initial_junction=False, name=\"ActorFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._rng = CarlaDataProvider.get_random_seed()\n        self._world = CarlaDataProvider.get_world()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(CarlaDataProvider.get_traffic_manager_port())\n\n        self._collision_bp = self._world.get_blueprint_library().find('sensor.other.collision')\n        self._is_constant_velocity_active = True\n\n        self._source_wp = source_wp\n        self._sink_wp = sink_wp\n\n        self._sink_location = self._sink_wp.transform.location\n        self._source_transform = self._source_wp.transform\n        self._source_location = self._source_transform.location\n\n        self._sink_dist = sink_dist\n        self._speed = actor_speed\n        self._initial_actors = initial_actors\n        self._initial_junction = initial_junction\n\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._attribute_filter = {'base_type': 'car', 'has_lights': True, 'special_type': ''}\n\n        self._actor_list = []\n        self._collision_sensor_list = []\n\n        self._terminated = False\n\n    def initialise(self):\n        if self._initial_actors:\n            grp = CarlaDataProvider.get_global_route_planner()\n            plan = grp.trace_route(self._source_location, self._sink_location)\n\n            ref_loc = plan[0][0].transform.location\n            for wp, _ in plan:\n                if wp.is_junction and not self._initial_junction:\n                    continue  # Spawning at junctions might break the path, so don't\n                if wp.transform.location.distance(ref_loc) < self._spawn_dist:\n                    continue\n                self._spawn_actor(wp.transform)\n                ref_loc = wp.transform.location\n                self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def _spawn_actor(self, transform):\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', transform, rolename='scenario',\n            attribute_filter=self._attribute_filter, tick=False\n        )\n        if actor is None:\n            return py_trees.common.Status.RUNNING\n\n        actor.set_autopilot(True, CarlaDataProvider.get_traffic_manager_port())\n        self._tm.set_path(actor, [self._sink_location])\n        self._tm.auto_lane_change(actor, False)\n        self._tm.set_desired_speed(actor, 3.6 * self._speed)\n        self._tm.update_vehicle_lights(actor, True)\n\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        sensor = None\n        if self._is_constant_velocity_active:\n            self._tm.ignore_vehicles_percentage(actor, 100)\n            actor.enable_constant_velocity(carla.Vector3D(self._speed, 0, 0))  # For when physics are active\n\n            sensor = self._world.spawn_actor(self._collision_bp, carla.Transform(), attach_to=actor)\n            sensor.listen(lambda _: self.stop_constant_velocity())\n\n        self._tm.ignore_lights_percentage(actor, 100)\n        self._tm.ignore_signs_percentage(actor, 100)\n        self._collision_sensor_list.append(sensor)\n        self._actor_list.append(actor)\n\n    def update(self):\n        \"\"\"Controls the created actors and creaes / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor, sensor in zip(list(self._actor_list), list(self._collision_sensor_list)):\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                if sensor is not None:\n                    sensor.stop()\n                    sensor.destroy()\n                self._collision_sensor_list.remove(sensor)\n                actor.destroy()\n                self._actor_list.remove(actor)\n\n        # Spawn new actors if needed\n        if len(self._actor_list) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_list[-1])\n            distance = self._source_location.distance(actor_location) if actor_location else 0\n\n        if distance > self._spawn_dist:\n            self._spawn_actor(self._source_transform)\n\n        return py_trees.common.Status.RUNNING\n\n    def stop_constant_velocity(self):\n        \"\"\"Stops the constant velocity behavior\"\"\"\n        self._is_constant_velocity_active = False\n        for actor in self._actor_list:\n            try:\n                actor.disable_constant_velocity()\n                self._tm.ignore_vehicles_percentage(actor, 0)\n            except RuntimeError:\n                pass\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for sensor in self._collision_sensor_list:\n            if sensor is None:\n                continue\n            try:\n                sensor.stop()\n                sensor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n        for actor in self._actor_list:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass OppositeActorFlow(AtomicBehavior):\n    \"\"\"\n    Similar to ActorFlow, but this is meant as an actor flow in the opposite direction.\n    As such, some configurations are different and for clarity, another behavior has been created\n\n    Important parameters:\n    - source_wp (carla.Waypoint): Waypoint at which actors will be spawned\n    - sink_wp (carla.Waypoint): Waypoint at which actors will be deleted\n    - spawn_dist_interval: Distance interval between spawned actors\n    - sink_dist: Actors closer to the sink than this distance will be deleted\n    - actors_speed: Speed of the actors part of the flow [m/s]\n    - offset: offset from the center lane of the actors\n    \"\"\"\n\n    def __init__(self, reference_wp, reference_actor, spawn_dist_interval,\n                 time_distance=1.5, base_distance=30, sink_dist=2, name=\"OppositeActorFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._rng = CarlaDataProvider.get_random_seed()\n        self._world = CarlaDataProvider.get_world()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(CarlaDataProvider.get_traffic_manager_port())\n\n        self._reference_wp = reference_wp\n        self._reference_actor = reference_actor\n        self._time_distance = time_distance\n        self._base_distance = base_distance\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._sink_dist = sink_dist\n\n        self._attribute_filter = {'base_type': 'car', 'has_lights': True, 'special_type': ''}\n\n        # Opposite direction needs earlier vehicle detection\n        self._opt_dict = {'base_vehicle_threshold': 10, 'detection_speed_ratio': 1.6}\n\n        self._actor_list = []\n        self._grp = CarlaDataProvider.get_global_route_planner()\n        self._map = CarlaDataProvider.get_map()\n\n        self._terminated = False\n\n    def _move_waypoint_forward(self, wp, distance):\n        \"\"\"Moves forward a certain distance, stopping at junctions\"\"\"\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n\n        return next_wp\n\n    def _move_waypoint_backwards(self, wp, distance):\n        \"\"\"Moves backwards a certain distance, stopping at junctions\"\"\"\n        dist = 0\n        prev_wp = wp\n        while dist < distance:\n            prev_wps = prev_wp.previous(1)\n            if prev_wps[0].is_junction:\n                break\n            prev_wp = prev_wps[0]\n            dist += 1\n\n        return prev_wp\n\n    def initialise(self):\n        \"\"\"Get the actor flow source and sink, depending on the reference actor speed\"\"\"\n        self._speed = self._reference_actor.get_speed_limit() # Km / h\n        self._flow_distance = self._time_distance * self._speed + self._base_distance\n\n        self._sink_wp = self._move_waypoint_forward(self._reference_wp, self._flow_distance)\n        self._source_wp = self._move_waypoint_backwards(self._reference_wp, self._flow_distance)\n\n        self._source_transform = self._source_wp.transform\n        self._source_location = self._source_transform.location\n        self._sink_location = self._sink_wp.transform.location\n\n        self._route = self._grp.trace_route(self._source_location, self._sink_location)\n\n        return super().initialise()\n\n    def _spawn_actor(self):\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._source_transform, rolename='scenario',\n            attribute_filter=self._attribute_filter, tick=False\n        )\n        if actor is None:\n            return py_trees.common.Status.RUNNING\n\n        controller = BasicAgent(actor, self._speed, self._opt_dict, self._map, self._grp)\n        controller.set_global_plan(self._route)\n        self._actor_list.append([actor, controller])\n\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def update(self):\n        \"\"\"Controls the created actors and creates / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor_data in list(self._actor_list):\n            actor, controller = actor_data\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                actor.destroy()\n                self._actor_list.remove(actor_data)\n            else:\n                actor.apply_control(controller.run_step())\n\n        # Spawn new actors if needed\n        if len(self._actor_list) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_list[-1][0])\n            distance = self._source_location.distance(actor_location) if actor_location else 0\n        if distance > self._spawn_dist:\n            self._spawn_actor()\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for actor, _ in self._actor_list:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass InvadingActorFlow(AtomicBehavior):\n    \"\"\"\n    Similar to ActorFlow, but this is meant as an actor flow in the opposite direction that invades the lane.\n    As such, some configurations are different and for clarity, another behavior has been created\n\n    Important parameters:\n    - source_wp (carla.Waypoint): Waypoint at which actors will be spawned\n    - sink_wp (carla.Waypoint): Waypoint at which actors will be deleted\n    - spawn_dist_interval: Distance interval between spawned actors\n    - sink_dist: Actors closer to the sink than this distance will be deleted\n    - actors_speed: Speed of the actors part of the flow [m/s]\n    - offset: offset from the center lane of the actors\n    \"\"\"\n\n    def __init__(self, source_wp, sink_wp, reference_actor, spawn_dist,\n                 sink_dist=2, offset=0, name=\"OppositeActorFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(CarlaDataProvider.get_traffic_manager_port())\n\n        self._reference_actor = reference_actor\n\n        self._source_wp  = source_wp\n        self._source_transform = self._source_wp.transform\n        self._source_location = self._source_transform.location\n\n        self._sink_wp = sink_wp\n        self._sink_location = self._sink_wp.transform.location\n\n        self._spawn_dist = spawn_dist\n\n        self._sink_dist = sink_dist\n\n        self._attribute_filter = {'base_type': 'car', 'has_lights': True, 'special_type': ''}\n\n        self._actor_list = []\n\n        # Opposite direction needs earlier vehicle detection\n        self._opt_dict = {'base_vehicle_threshold': 10, 'detection_speed_ratio': 2, 'distance_ratio': 0.2}\n        self._opt_dict['offset'] = offset\n\n        self._grp = CarlaDataProvider.get_global_route_planner()\n        self._map = CarlaDataProvider.get_map()\n\n        self._terminated = False\n\n    def initialise(self):\n        \"\"\"Get the actor flow source and sink, depending on the reference actor speed\"\"\"\n        self._speed = self._reference_actor.get_speed_limit()  # Km / h\n        self._route = self._grp.trace_route(self._source_location, self._sink_location)\n        return super().initialise()\n\n    def _spawn_actor(self):\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._source_transform, rolename='scenario',\n            attribute_filter=self._attribute_filter, tick=False\n        )\n        if actor is None:\n            return py_trees.common.Status.RUNNING\n\n        controller = BasicAgent(actor, self._speed, self._opt_dict, self._map, self._grp)\n        controller.set_global_plan(self._route)\n        self._actor_list.append([actor, controller])\n\n    def update(self):\n        \"\"\"Controls the created actors and creates / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor_data in list(self._actor_list):\n            actor, controller = actor_data\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                actor.destroy()\n                self._actor_list.remove(actor_data)\n            else:\n                actor.apply_control(controller.run_step())\n\n        # Spawn new actors if needed\n        if len(self._actor_list) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_list[-1][0])\n            distance = self._source_location.distance(actor_location) if actor_location else 0\n        if distance > self._spawn_dist:\n            self._spawn_actor()\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for actor, _ in self._actor_list:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass BicycleFlow(AtomicBehavior):\n    \"\"\"\n    Behavior that indefinitely creates bicycles at a location,\n    controls them until another location, and then destroys them.\n    Therefore, a parallel termination behavior has to be used.\n\n    Important parameters:\n    - plan (list(carla.Waypoint)): plan used by the bicycles.\n    - spawn_distance_interval (list(float, float)): Distance between spawned actors\n    - sink_distance (float): Actors at this distance from the sink will be deleted\n    - actors_speed (float): Speed of the actors part of the flow [m/s]\n    - initial_actors (bool): Boolean to initialy populate all the flow with bicycles\n    \"\"\"\n\n    def __init__(self, plan, spawn_dist_interval, sink_dist=2,\n                 actor_speed=20 / 3.6, initial_actors=False, name=\"BicycleFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super().__init__(name)\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._plan = plan\n        self._sink_dist = sink_dist\n        self._speed = actor_speed\n\n        self._source_transform = self._plan[0][0].transform\n        self._source_location = self._source_transform.location\n        self._sink_location = self._plan[-1][0].transform.location\n\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._initial_actors = initial_actors\n\n        self._opt_dict = {\"ignore_traffic_lights\": True, \"ignore_vehicles\": True}\n\n        self._actor_data = []\n        self._grp = CarlaDataProvider.get_global_route_planner()\n\n        self._terminated = False\n\n    def initialise(self):\n        if self._initial_actors:\n            ref_loc = self._plan[0][0].transform.location\n            for wp, _ in self._plan:\n                if wp.is_junction:\n                    continue  # Spawning at junctions might break the path, so don't\n                if wp.transform.location.distance(ref_loc) < self._spawn_dist:\n                    continue\n                self._spawn_actor(wp.transform)\n                ref_loc = wp.transform.location\n                self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def _spawn_actor(self, transform):\n        \"\"\"Spawn the actor\"\"\"\n        # Initial actors don't want all the plan. Remove the points behind them\n        plan = self._plan\n        actor_loc = transform.location\n        while len(plan) > 0:\n            wp, _ = plan[0]\n            loc = wp.transform.location\n            actor_heading = transform.get_forward_vector()\n            actor_wp_vec = loc - actor_loc\n            if actor_heading.dot(actor_wp_vec) < 0 or loc.distance(actor_loc) < 10:\n                plan.pop(0)\n            else:\n                break\n\n        if not plan:\n            return\n\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', transform, rolename='scenario no lights',\n            attribute_filter={'base_type': 'bicycle'}, tick=False\n        )\n        if actor is None:\n            return\n\n        controller = BasicAgent(actor, 3.6 * self._speed, opt_dict=self._opt_dict,\n            map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner())\n        controller.set_global_plan(plan)\n\n        initial_vec = plan[0][0].transform.get_forward_vector()\n        actor.set_target_velocity(self._speed * initial_vec)\n        actor.apply_control(carla.VehicleControl(throttle=1, gear=1, manual_gear_shift=True))\n\n        self._actor_data.append([actor, controller])\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n    def update(self):\n        \"\"\"Controls the created actors and creaes / removes other when needed\"\"\"\n        # Control the vehicles, removing them when needed\n        for actor_data in list(self._actor_data):\n            actor, controller = actor_data\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            sink_distance = self._sink_location.distance(location)\n            if sink_distance < self._sink_dist:\n                actor.destroy()\n                self._actor_data.remove(actor_data)\n            else:\n                actor.apply_control(controller.run_step())\n\n        # Spawn new actors if needed\n        if len(self._actor_data) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._actor_data[-1][0])\n            if actor_location is None:\n                distance = 0\n            else:\n                distance = self._source_location.distance(actor_location)\n\n        if distance > self._spawn_dist:\n            self._spawn_actor(self._source_transform)\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        if self._terminated:\n            return\n\n        self._terminated = True\n\n        for actor, _ in self._actor_data:\n            # TODO: Actors spawned in the same frame as the behavior termination won't be removed.\n            # Patched by removing its movement\n            try:\n                actor.disable_constant_velocity()\n                actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port())\n                actor.set_target_velocity(carla.Vector3D(0,0,0))\n                actor.set_target_angular_velocity(carla.Vector3D(0,0,0))\n                actor.destroy()\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\n\nclass OpenVehicleDoor(AtomicBehavior):\n\n    \"\"\"\n    Implementation for a behavior that will open the door of a vehicle,\n    then close it after a while.\n\n    Important parameters:\n    - actor: Type of CARLA actors to be spawned\n    - vehicle_door: The specific door that will be opened\n    - duration: Duration of the open door\n    \"\"\"\n\n    def __init__(self, actor, vehicle_door, name=\"OpenVehicleDoor\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(OpenVehicleDoor, self).__init__(name, actor)\n        self._vehicle_door = vehicle_door\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._actor.open_door(self._vehicle_door)\n        super().initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.SUCCESS\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass TrafficLightFreezer(AtomicBehavior):\n    \"\"\"\n    Behavior that freezes a group of traffic lights for a specific amount of time,\n    returning them to their original state after ending it\n\n    Important parameters:\n    - traffic_lights_dict dict{carla.TrafficLight: carla.TrafficLightState}\n    - timeout: Amount of time the traffic lights are frozen\n    \"\"\"\n\n    def __init__(self, traffic_lights_dict, duration=10000, name=\"TrafficLightFreezer\"):\n        \"\"\"Setup class members\"\"\"\n        super(TrafficLightFreezer, self).__init__(name)\n        self._traffic_lights_dict = traffic_lights_dict\n        self._duration = duration\n        self._previous_traffic_light_info = {}\n        self._start_time = None\n\n    def initialise(self):\n        \"\"\"\n        Sets the traffic lights to the desired states and remembers their previous one.\n        These should technically be frozen, but that freezes all tls in the town\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        for tl in self._traffic_lights_dict:\n            elapsed_time = tl.get_elapsed_time()\n            self._previous_traffic_light_info[tl] = {\n                'state': tl.get_state(),\n                'green_time': tl.get_green_time(),\n                'red_time': tl.get_red_time(),\n                'yellow_time': tl.get_yellow_time()\n            }\n            tl.set_state(self._traffic_lights_dict[tl])\n            tl.set_green_time(self._duration + elapsed_time)\n            tl.set_red_time(self._duration + elapsed_time)\n            tl.set_yellow_time(self._duration + elapsed_time)\n\n    def update(self):\n        \"\"\"Waits until the adequate time has passed\"\"\"\n        if GameTime.get_time() - self._start_time > self._duration:\n            return py_trees.common.Status.SUCCESS\n        else:\n            return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"Reset all traffic lights back to their previous states\"\"\"\n        if self._previous_traffic_light_info:\n            for tl in self._traffic_lights_dict:\n                tl.set_state(self._previous_traffic_light_info[tl]['state'])\n                tl.set_green_time(self._previous_traffic_light_info[tl]['green_time'])\n                tl.set_red_time(self._previous_traffic_light_info[tl]['red_time'])\n                tl.set_yellow_time(self._previous_traffic_light_info[tl]['yellow_time'])\n\n\nclass StartRecorder(AtomicBehavior):\n\n    \"\"\"\n    Atomic that starts the CARLA recorder. Only one can be active\n    at a time, and if this isn't the case, the recorder will\n    automatically stop the previous one.\n\n    Args:\n        recorder_name (str): name of the file to write the recorded data.\n            Remember that a simple name will save the recording in\n            'CarlaUE4/Saved/'. Otherwise, if some folder appears in the name,\n            it will be considered an absolute path.\n        name (str): name of the behavior\n    \"\"\"\n\n    def __init__(self, recorder_name, name=\"StartRecorder\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(StartRecorder, self).__init__(name)\n        self._client = CarlaDataProvider.get_client()\n        self._recorder_name = recorder_name\n\n    def update(self):\n        self._client.start_recorder(self._recorder_name)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StopRecorder(AtomicBehavior):\n\n    \"\"\"\n    Atomic that stops the CARLA recorder.\n\n    Args:\n        name (str): name of the behavior\n    \"\"\"\n\n    def __init__(self, name=\"StopRecorder\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(StopRecorder, self).__init__(name)\n        self._client = CarlaDataProvider.get_client()\n\n    def update(self):\n        self._client.stop_recorder()\n        return py_trees.common.Status.SUCCESS\n\n\nclass TrafficLightManipulator(AtomicBehavior):\n\n    \"\"\"\n    Atomic behavior that manipulates traffic lights around the ego_vehicle to trigger scenarios 7 to 10.\n    This is done by setting 2 of the traffic light at the intersection to green (with some complex precomputation\n    to set everything up).\n\n    Important parameters:\n    - ego_vehicle: CARLA actor that controls this behavior\n    - subtype: string that gathers information of the route and scenario number\n      (check SUBTYPE_CONFIG_TRANSLATION below)\n    \"\"\"\n\n    RED = carla.TrafficLightState.Red\n    YELLOW = carla.TrafficLightState.Yellow\n    GREEN = carla.TrafficLightState.Green\n\n    # Time constants\n    RED_TIME = 1.5  # Minimum time the ego vehicle waits in red (seconds)\n    YELLOW_TIME = 2  # Time spent at yellow state (seconds)\n    RESET_TIME = 6  # Time waited before resetting all the junction (seconds)\n\n    # Experimental values\n    TRIGGER_DISTANCE = 10  # Distance that makes all vehicles in the lane enter the junction (meters)\n    DIST_TO_WAITING_TIME = 0.04  # Used to wait longer at larger intersections (s/m)\n\n    INT_CONF_OPP1 = {'ego': RED, 'ref': RED, 'left': RED, 'right': RED, 'opposite': GREEN}\n    INT_CONF_OPP2 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': RED, 'opposite': GREEN}\n    INT_CONF_LFT1 = {'ego': RED, 'ref': RED, 'left': GREEN, 'right': RED, 'opposite': RED}\n    INT_CONF_LFT2 = {'ego': GREEN, 'ref': GREEN, 'left': GREEN, 'right': RED, 'opposite': RED}\n    INT_CONF_RGT1 = {'ego': RED, 'ref': RED, 'left': RED, 'right': GREEN, 'opposite': RED}\n    INT_CONF_RGT2 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': GREEN, 'opposite': RED}\n\n    INT_CONF_REF1 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': RED, 'opposite': RED}\n    INT_CONF_REF2 = {'ego': YELLOW, 'ref': YELLOW, 'left': RED, 'right': RED, 'opposite': RED}\n\n    # Depending on the scenario, IN ORDER OF IMPORTANCE, the traffic light changed\n    # The list has to contain only items of the INT_CONF\n    SUBTYPE_CONFIG_TRANSLATION = {\n        'S7left': ['left', 'opposite', 'right'],\n        'S7right': ['left', 'opposite'],\n        'S7opposite': ['right', 'left', 'opposite'],\n        'S8left': ['opposite'],\n        'S9right': ['left', 'opposite']\n    }\n\n    CONFIG_TLM_TRANSLATION = {\n        'left': [INT_CONF_LFT1, INT_CONF_LFT2],\n        'right': [INT_CONF_RGT1, INT_CONF_RGT2],\n        'opposite': [INT_CONF_OPP1, INT_CONF_OPP2]\n    }\n\n    def __init__(self, ego_vehicle, subtype, debug=False, name=\"TrafficLightManipulator\"):\n        super(TrafficLightManipulator, self).__init__(name)\n        self.ego_vehicle = ego_vehicle\n        self.subtype = subtype\n        self.current_step = 1\n        self.debug = debug\n\n        self.traffic_light = None\n        self.annotations = None\n        self.configuration = None\n        self.prev_junction_state = None\n        self.junction_location = None\n        self.seconds_waited = 0\n        self.prev_time = None\n        self.max_trigger_distance = None\n        self.waiting_time = None\n        self.inside_junction = False\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n\n        new_status = py_trees.common.Status.RUNNING\n\n        # 1) Set up the parameters\n        if self.current_step == 1:\n\n            # Traffic light affecting the ego vehicle\n            self.traffic_light = CarlaDataProvider.get_next_traffic_light(self.ego_vehicle, use_cached_location=False)\n            if not self.traffic_light:\n                # nothing else to do in this iteration...\n                return new_status\n\n            # \"Topology\" of the intersection\n            self.annotations = CarlaDataProvider.annotate_trafficlight_in_group(self.traffic_light)\n\n            # Which traffic light will be modified (apart from the ego lane)\n            self.configuration = self.get_traffic_light_configuration(self.subtype, self.annotations)\n            if self.configuration is None:\n                self.current_step = 0  # End the behavior\n                return new_status\n\n            # Modify the intersection. Store the previous state\n            self.prev_junction_state = self.set_intersection_state(self.INT_CONF_REF1)\n\n            self.current_step += 1\n            if self.debug:\n                print(\"--- All set up\")\n\n        # 2) Modify the ego lane to yellow when closeby\n        elif self.current_step == 2:\n\n            ego_location = CarlaDataProvider.get_location(self.ego_vehicle)\n\n            if self.junction_location is None:\n                ego_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n                junction_waypoint = ego_waypoint.next(0.5)[0]\n                while not junction_waypoint.is_junction:\n                    next_wp = junction_waypoint.next(0.5)[0]\n                    junction_waypoint = next_wp\n                self.junction_location = junction_waypoint.transform.location\n\n            distance = ego_location.distance(self.junction_location)\n\n            # Failure check\n            if self.max_trigger_distance is None:\n                self.max_trigger_distance = distance + 1\n            if distance > self.max_trigger_distance:\n                self.current_step = 0\n\n            elif distance < self.TRIGGER_DISTANCE:\n                _ = self.set_intersection_state(self.INT_CONF_REF2)\n                self.current_step += 1\n\n            if self.debug:\n                print(\"--- Distance until traffic light changes: {}\".format(distance))\n\n        # 3) Modify the ego lane to red and the chosen one to green after several seconds\n        elif self.current_step == 3:\n\n            if self.passed_enough_time(self.YELLOW_TIME):\n                _ = self.set_intersection_state(self.CONFIG_TLM_TRANSLATION[self.configuration][0])\n\n                self.current_step += 1\n\n        # 4) Wait a bit to let vehicles enter the intersection, then set the ego lane to green\n        elif self.current_step == 4:\n\n            # Get the time in red, dependent on the intersection dimensions\n            if self.waiting_time is None:\n                self.waiting_time = self.get_waiting_time(self.annotations, self.configuration)\n\n            if self.passed_enough_time(self.waiting_time):\n                _ = self.set_intersection_state(self.CONFIG_TLM_TRANSLATION[self.configuration][1])\n\n                self.current_step += 1\n\n        # 5) Wait for the end of the intersection\n        elif self.current_step == 5:\n            # the traffic light has been manipulated, wait until the vehicle finsihes the intersection\n            ego_location = CarlaDataProvider.get_location(self.ego_vehicle)\n            ego_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n            if not self.inside_junction:\n                if ego_waypoint.is_junction:\n                    # Wait for the ego_vehicle to enter a junction\n                    self.inside_junction = True\n                else:\n                    if self.debug:\n                        print(\"--- Waiting to ENTER a junction\")\n\n            else:\n                if ego_waypoint.is_junction:\n                    if self.debug:\n                        print(\"--- Waiting to EXIT a junction\")\n                else:\n                    # And to leave it\n                    self.inside_junction = False\n                    self.current_step += 1\n\n        # 6) At the end (or if something failed), reset to the previous state\n        else:\n            if self.prev_junction_state:\n                CarlaDataProvider.reset_lights(self.prev_junction_state)\n                if self.debug:\n                    print(\"--- Returning the intersection to its previous state\")\n\n            self.variable_cleanup()\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n    def passed_enough_time(self, time_limit):\n        \"\"\"\n        Returns true or false depending on the time that has passed from the\n        first time this function was called\n        \"\"\"\n        # Start the timer\n        if self.prev_time is None:\n            self.prev_time = GameTime.get_time()\n\n        timestamp = GameTime.get_time()\n        self.seconds_waited += (timestamp - self.prev_time)\n        self.prev_time = timestamp\n\n        if self.debug:\n            print(\"--- Waited seconds: {}\".format(self.seconds_waited))\n\n        if self.seconds_waited >= time_limit:\n            self.seconds_waited = 0\n            self.prev_time = None\n\n            return True\n        return False\n\n    def set_intersection_state(self, choice):\n        \"\"\"\n        Changes the intersection to the desired state\n        \"\"\"\n        prev_state = CarlaDataProvider.update_light_states(\n            self.traffic_light,\n            self.annotations,\n            choice,\n            freeze=True)\n\n        return prev_state\n\n    def get_waiting_time(self, annotation, direction):\n        \"\"\"\n        Calculates the time the ego traffic light will remain red\n        to let vehicles enter the junction\n        \"\"\"\n\n        tl = annotation[direction][0]\n        ego_tl = annotation[\"ref\"][0]\n\n        tl_location = CarlaDataProvider.get_trafficlight_trigger_location(tl)\n        ego_tl_location = CarlaDataProvider.get_trafficlight_trigger_location(ego_tl)\n\n        distance = ego_tl_location.distance(tl_location)\n\n        return self.RED_TIME + distance * self.DIST_TO_WAITING_TIME\n\n    def get_traffic_light_configuration(self, subtype, annotations):\n        \"\"\"\n        Checks the list of possible altered traffic lights and gets\n        the first one that exists in the intersection\n\n        Important parameters:\n        - subtype: Subtype of the scenario\n        - annotations: list of the traffic light of the junction, with their direction (right, left...)\n        \"\"\"\n        configuration = None\n\n        if subtype in self.SUBTYPE_CONFIG_TRANSLATION:\n            possible_configurations = self.SUBTYPE_CONFIG_TRANSLATION[self.subtype]\n            while possible_configurations:\n                # Chose the first one and delete it\n                configuration = possible_configurations[0]\n                possible_configurations = possible_configurations[1:]\n                if configuration in annotations:\n                    if annotations[configuration]:\n                        # Found a valid configuration\n                        break\n                    else:\n                        # The traffic light doesn't exist, get another one\n                        configuration = None\n                else:\n                    if self.debug:\n                        print(\"This configuration name is wrong\")\n                    configuration = None\n\n            if configuration is None and self.debug:\n                print(\"This subtype has no traffic light available\")\n        else:\n            if self.debug:\n                print(\"This subtype is unknown\")\n\n        return configuration\n\n    def variable_cleanup(self):\n        \"\"\"\n        Resets all variables to the intial state\n        \"\"\"\n        self.current_step = 1\n        self.traffic_light = None\n        self.annotations = None\n        self.configuration = None\n        self.prev_junction_state = None\n        self.junction_location = None\n        self.max_trigger_distance = None\n        self.waiting_time = None\n        self.inside_junction = False\n\n\nclass ScenarioTriggerer(AtomicBehavior):\n\n    \"\"\"\n    Handles the triggering of the scenarios that are part of a route.\n\n    Initializes a list of blackboard variables to False, and only sets them to True when\n    the ego vehicle is very close to the scenarios\n    \"\"\"\n\n    WINDOWS_SIZE = 5\n\n    def __init__(self, actor, route, blackboard_list, distance, debug=False, name=\"ScenarioTriggerer\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(ScenarioTriggerer, self).__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._debug = debug\n\n        self._actor = actor\n        self._route = route\n        self._distance = distance\n        self._blackboard_list = blackboard_list\n        self._triggered_scenarios = []  # List of already done scenarios\n\n        self._current_index = 0\n        self._route_length = len(self._route)\n        self._waypoints, _ = zip(*self._route)\n\n    def add_blackboard(self, blackboard):\n        \"\"\"\n        Adds new blackboards to the list. Used by the runtime initialization of scenarios\n        \"\"\"\n        self._blackboard_list.append(blackboard)\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n        if location is None:\n            return new_status\n\n        lower_bound = self._current_index\n        upper_bound = min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)\n\n        shortest_distance = float('inf')\n        closest_index = -1\n\n        for index in range(lower_bound, upper_bound):\n            ref_waypoint = self._waypoints[index]\n            ref_location = ref_waypoint.location\n\n            dist_to_route = ref_location.distance(location)\n            if dist_to_route <= shortest_distance:\n                closest_index = index\n                shortest_distance = dist_to_route\n\n        if closest_index == -1 or shortest_distance == float('inf'):\n            return new_status\n\n        # Update the ego position at the route\n        self._current_index = closest_index\n\n        route_location = self._waypoints[closest_index].location\n\n        # Check which scenarios can be triggered\n        blackboard = py_trees.blackboard.Blackboard()\n        for black_var_name, scen_location in self._blackboard_list:\n\n            # Close enough\n            scen_distance = route_location.distance(scen_location)\n            condition1 = bool(scen_distance < self._distance)\n\n            # Not being currently done\n            value = blackboard.get(black_var_name)\n            condition2 = bool(not value)\n\n            # Already done, if needed\n            condition3 = bool(black_var_name not in self._triggered_scenarios)\n\n            if condition1 and condition2 and condition3:\n                _ = blackboard.set(black_var_name, True)\n                self._triggered_scenarios.append(black_var_name)\n\n                if self._debug:\n                    self._world.debug.draw_point(\n                        scen_location + carla.Location(z=4),\n                        size=0.5,\n                        life_time=0.5,\n                        color=carla.Color(255, 255, 0)\n                    )\n                    self._world.debug.draw_string(\n                        scen_location + carla.Location(z=5),\n                        str(black_var_name),\n                        False,\n                        color=carla.Color(0, 0, 0),\n                        life_time=1000\n                    )\n\n        return new_status\n\n\nclass KeepLongitudinalGap(AtomicBehavior):\n    \"\"\"\n    This class contains an atomic behavior to maintain a set gap with leading/adjacent vehicle.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - reference_actor: Reference actor the distance shall be kept to.\n    - distance: target gap between the two actors in meters\n    - distance_type: Specifies how distance should be calculated between the two actors\n\n    The behavior terminates after overwritten by other events / when target distance is reached(if continues).\n    \"\"\"\n\n    def __init__(self, actor, reference_actor, gap, gap_type=\"distance\", max_speed=None, continues=False,\n                 freespace=False, name=\"AutoKeepDistance\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(KeepLongitudinalGap, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._reference_actor = reference_actor\n        self._gap = gap\n        self._gap_type = gap_type\n        self._continues = continues\n        self._freespace = freespace\n        self._global_rp = None\n        max_speed_limit = 100\n        self.max_speed = max_speed_limit if max_speed is None else float(max_speed)\n        if freespace and self._gap_type == \"distance\":\n            self._gap += self._reference_actor.bounding_box.extent.x + self._actor.bounding_box.extent.x\n\n        self._start_time = None\n\n    def initialise(self):\n        actor_dict = {}\n\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or self._actor.id not in actor_dict:\n            raise RuntimeError(\"Actor not found in ActorsWithController BlackBoard\")\n\n        self._start_time = GameTime.get_time()\n        actor_dict[self._actor.id].update_target_speed(self.max_speed, start_time=self._start_time)\n\n        self._global_rp = CarlaDataProvider.get_global_route_planner()\n\n        super(KeepLongitudinalGap, self).initialise()\n\n    def update(self):\n        \"\"\"\n        keeps track of gap and update the controller accordingly\n        \"\"\"\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if not actor_dict or self._actor.id not in actor_dict:\n            return py_trees.common.Status.FAILURE\n\n        if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time:\n            return py_trees.common.Status.SUCCESS\n\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_velocity = CarlaDataProvider.get_velocity(self._actor)\n        reference_velocity = CarlaDataProvider.get_velocity(self._reference_actor)\n\n        gap = sr_tools.scenario_helper.get_distance_between_actors(self._actor, self._reference_actor,\n                                                                   distance_type=\"longitudinal\",\n                                                                   freespace=self._freespace,\n                                                                   global_planner=self._global_rp)\n        actor_transform = CarlaDataProvider.get_transform(self._actor)\n        ref_actor_transform = CarlaDataProvider.get_transform(self._reference_actor)\n        if is_within_distance(ref_actor_transform, actor_transform, float('inf'), [0, 90]) and \\\n                operator.le(gap, self._gap):\n            try:\n                factor = abs(actor_velocity - reference_velocity)/actor_velocity\n                if actor_velocity > reference_velocity:\n                    actor_velocity = actor_velocity - (factor*actor_velocity)\n                elif actor_velocity < reference_velocity and operator.gt(gap, self._gap):\n                    actor_velocity = actor_velocity + (factor*actor_velocity)\n            except ZeroDivisionError:\n                pass\n            actor_dict[self._actor.id].update_target_speed(actor_velocity)\n\n            if not self._continues:\n                if operator.le(gap, self._gap):\n                    new_status = py_trees.common.Status.SUCCESS\n        else:\n            actor_dict[self._actor.id].update_target_speed(self.max_speed)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass SwitchWrongDirectionTest(AtomicBehavior):\n\n    \"\"\"\n    Atomic that switch the OutsideRouteLanesTest criterion.\n\n    Args:\n        active (bool): True: activated; False: deactivated\n        name (str): name of the behavior\n    \"\"\"\n\n    def __init__(self, active, name=\"SwitchWrongDirectionTest\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        self._active = active\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"AC_SwitchWrongDirectionTest\", self._active, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass SwitchMinSpeedCriteria(AtomicBehavior):\n\n    def __init__(self, active, name=\"ChangeMinSpeed\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super().__init__(name)\n        self._active = active\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        keeps track of gap and update the controller accordingly\n        \"\"\"\n        new_status = py_trees.common.Status.SUCCESS\n        py_trees.blackboard.Blackboard().set(\"SwitchMinSpeedCriteria\", self._active, overwrite=True)\n        return new_status\n\n\nclass WalkerFlow(AtomicBehavior):\n    \"\"\"\n    Behavior that indefinitely creates walkers at a location,\n    controls them until another location, and then destroys them.\n    Therefore, a parallel termination behavior has to be used.\n\n    There can be more than one target location.\n\n    Important parameters:\n    - source_location (carla.Location): Location at which actors will be spawned\n    - sink_locations (list(carla.Location)): Locations at which actors will be deleted\n    - sink_locations_prob (list(float)): The probability of each sink_location\n    - spawn_dist_interval (list(float)): Distance between spawned actors\n    - random_seed : Optional. The seed of numpy's random\n    - sink_distance: Actors closer to the sink than this distance will be deleted. \n                     Probably due to the navigation module rerouting the walkers, a sink distance of 2 is reasonable.\n    \"\"\"\n    def __init__(self, source_location, sink_locations, sink_locations_prob, spawn_dist_interval, random_seed=None, sink_dist=2,\n                 name=\"WalkerFlow\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(WalkerFlow, self).__init__(name)\n\n        if random_seed is not None:\n            self._rng = random.RandomState(random_seed)\n        else:\n            self._rng = CarlaDataProvider.get_random_seed()\n        self._world = CarlaDataProvider.get_world()\n\n        self._controller_bp = self._world.get_blueprint_library().find('controller.ai.walker')\n\n        self._source_location = source_location\n\n        self._sink_locations = sink_locations\n        self._sink_locations_prob = sink_locations_prob\n        self._sink_dist = sink_dist\n\n        self._min_spawn_dist = spawn_dist_interval[0]\n        self._max_spawn_dist = spawn_dist_interval[1]\n        self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        self._batch_size_list = [1,2,3]\n\n        self._walkers = []\n\n    def update(self):\n        \"\"\"Controls the created actors and creates / removes other when needed\"\"\"\n        # Remove walkers when needed\n        for item in self._walkers:\n            walker, controller, sink_location = item\n            loc = CarlaDataProvider.get_location(walker)\n            if loc.distance(sink_location) < self._sink_dist:\n                self._destroy_walker(walker, controller)\n                self._walkers.remove(item)\n\n        # Spawn new walkers\n        if len(self._walkers) == 0:\n            distance = self._spawn_dist + 1\n        else:\n            actor_location = CarlaDataProvider.get_location(self._walkers[-1][0])\n            distance = self._source_location.distance(actor_location)\n\n        if distance > self._spawn_dist:\n            # spawn new walkers\n            walker_amount = self._rng.choice(self._batch_size_list)\n            for i in range(walker_amount):\n                spawn_tran = carla.Transform(self._source_location)\n                spawn_tran.location.y -= i\n                walker = CarlaDataProvider.request_new_actor(\n                    'walker.*', spawn_tran, rolename='scenario'\n                )\n                if walker is None:\n                    continue\n                # Use ai.walker to controll walkers\n                controller = self._world.try_spawn_actor(self._controller_bp, carla.Transform(), walker)\n                sink_location = self._rng.choice(a = self._sink_locations, p = self._sink_locations_prob)\n                controller.start()\n                controller.go_to_location(sink_location)\n                # Add to walkers list\n                self._walkers.append((walker, controller, sink_location))\n\n            self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist)\n\n        return py_trees.common.Status.RUNNING\n\n    def _destroy_walker(self, walker, controller):\n        controller.stop()\n        controller.destroy()\n        walker.destroy()\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        for walker, controller, _ in self._walkers:\n            try:\n                self._destroy_walker(walker, controller)\n            except RuntimeError:\n                pass  # Actor was already destroyed\n\nclass AIWalkerBehavior(AtomicBehavior):\n    \"\"\"\n    Behavior that creates a walker controlled by AI Walker controller.\n    The walker go from source location to sink location.\n    A parallel termination behavior has to be used.\n\n    Important parameters:\n    - source_location (carla.Location): Location at which the actor will be spawned\n    - sink_location (carla.Location): Location at which the actor will be deleted\n    \"\"\"\n\n    def __init__(self, source_location, sink_location,\n                 name=\"AIWalkerBehavior\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(AIWalkerBehavior, self).__init__(name)\n\n        self._world = CarlaDataProvider.get_world()\n        self._controller_bp = self._world.get_blueprint_library().find('controller.ai.walker')\n\n        self._source_location = source_location\n\n        self._sink_location = sink_location\n        self._sink_dist = 2\n\n        self._walker = None\n        self._controller = None\n\n    def initialise(self):\n        \"\"\"\n        Spawn the walker at source location.\n        Setup the AI controller.\n\n        May throw RuntimeError if the walker can not be\n        spawned at given location.\n        \"\"\"\n        spawn_tran = carla.Transform(self._source_location)\n        self._walker = CarlaDataProvider.request_new_actor(\n            'walker.*', spawn_tran, rolename='scenario'\n        )\n        if self._walker is None:\n            raise RuntimeError(\"Couldn't spawn the walker\")\n        # Use ai.walker to controll the walker\n        self._controller = self._world.try_spawn_actor(\n            self._controller_bp, carla.Transform(), self._walker)\n        self._controller.start()\n        self._controller.go_to_location(self._sink_location)\n\n        super(AIWalkerBehavior, self).initialise()\n\n    def update(self):\n        \"\"\"Controls the created walker\"\"\"\n        # Remove walkers when needed\n        if self._walker is not None:\n            loc = CarlaDataProvider.get_location(self._walker)\n            # At the very beginning of the scenario, the get_location may return None\n            if loc is not None:\n                if loc.distance(self._sink_location) < self._sink_dist:\n                    self.terminate(py_trees.common.Status.SUCCESS)\n\n        return py_trees.common.Status.RUNNING\n\n    def _destroy_walker(self, walker, controller):\n        if controller:\n            controller.stop()\n            controller.destroy()\n        if walker:\n            walker.destroy()\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        try:\n            self._destroy_walker(self._walker, self._controller)\n        except RuntimeError:\n            pass  # Actor was already destroyed\n\n\nclass ScenarioTimeout(AtomicBehavior):\n\n    \"\"\"\n    This class is an idle behavior that waits for a set amount of time\n    before stoping.\n\n    It is meant to be used with the `ScenarioTimeoutTest` to be used at scenarios\n    that block the ego's route (such as adding obstacles) so that if the ego is\n    incapable of surpassing them, it isn't blocked forever. Instead,\n    the scenario will timeout, but it will be penalized by the `ScenarioTimeoutTest`\n\n    Parameters:\n    - duration: Duration in seconds of this behavior\n    \"\"\"\n\n    def __init__(self, duration, scenario_name, name=\"ScenarioTimeout\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super().__init__(name)\n        self._duration = duration\n        self._scenario_name = scenario_name\n        self._start_time = 0\n        self._scenario_timeout = False\n        self._terminated = False\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        py_trees.blackboard.Blackboard().set(\"AC_SwitchActorBlockedTest\", False, overwrite=True)\n        super().initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            self._scenario_timeout = True\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Modifies the blackboard to tell the `ScenarioTimeoutTest` if the timeout was triggered\n        \"\"\"\n        if not self._terminated:  # py_trees calls the terminate several times for some reason.\n            py_trees.blackboard.Blackboard().set(f\"ScenarioTimeout_{self._scenario_name}\", self._scenario_timeout, overwrite=True)\n            py_trees.blackboard.Blackboard().set(\"AC_SwitchActorBlockedTest\", True, overwrite=True)\n            self._terminated = True\n        super().terminate(new_status)\n\n\nclass MovePedestrianWithEgo(AtomicBehavior):\n\n    def __init__(self, reference_actor, actor, distance, displacement=0, name=\"TrackActor\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super().__init__(name)\n        self._actor = actor\n        self._reference_actor = reference_actor\n        self._distance = distance\n        self._displacement = displacement\n\n        added_location = carla.Location(x=self._displacement, z=-self._distance)\n        self._actor.set_location(self._reference_actor.get_location() + added_location)\n\n        self._start_time = 0\n        self._teleport_time = 5\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def initialise(self):\n        \"\"\"\n        Set start time\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        added_location = carla.Location(x=self._displacement, z=-self._distance)\n        self._actor.set_location(self._reference_actor.get_location() + added_location)\n        super().initialise()\n\n    def update(self):\n        \"\"\"\n        Keep running until termination condition is satisfied\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if GameTime.get_time() - self._start_time > self._teleport_time:\n            added_location = carla.Location(x=self._displacement, z=-self._distance)\n            self._actor.set_location(self._reference_actor.get_location() + added_location)\n            self._start_time = GameTime.get_time()\n        return new_status\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_criteria.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all atomic evaluation criteria required to analyze if a\nscenario was completed successfully or failed.\n\nCriteria should run continuously to monitor the state of a single actor, multiple\nactors or environmental parameters. Hence, a termination is not required.\n\nThe atomic criteria are implemented with py_trees.\n\"\"\"\n\nimport math\nimport numpy as np\nimport py_trees\nimport shapely.geometry\n\nimport carla\nfrom agents.tools.misc import get_speed\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.traffic_events import TrafficEvent, TrafficEventType\n\n\nclass Criterion(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Base class for all criteria used to evaluate a scenario for success/failure\n\n    Important parameters (PUBLIC):\n    - name: Name of the criterion\n    - actor: Actor of the criterion\n    - optional: Indicates if a criterion is optional (not used for overall analysis)\n    - terminate on failure: Whether or not the criteria stops on failure\n\n    - test_status: Used to access the result of the criterion\n    - success_value: Result in case of success (e.g. max_speed, zero collisions, ...)\n    - acceptable_value: Result that does not mean a failure,  but is not good enough for a success\n    - actual_value: Actual result after running the scenario\n    - units: units of the 'actual_value'. This is a string and is used by the result writter\n    \"\"\"\n\n    def __init__(self,\n                 name,\n                 actor,\n                 optional=False,\n                 terminate_on_failure=False):\n        super(Criterion, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self.name = name\n        self.actor = actor\n        self.optional = optional\n        self._terminate_on_failure = terminate_on_failure\n        self.test_status = \"INIT\"   # Either \"INIT\", \"RUNNING\", \"SUCCESS\", \"ACCEPTABLE\" or \"FAILURE\"\n\n        # Attributes to compare the current state (actual_value), with the expected ones\n        self.success_value = 0\n        self.acceptable_value = None\n        self.actual_value = 0\n        self.units = \"times\"\n\n        self.events = []  # List of events (i.e collision, sidewalk invasion...)\n\n    def initialise(self):\n        \"\"\"\n        Initialise the criterion. Can be extended by the user-derived class\n        \"\"\"\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def terminate(self, new_status):\n        \"\"\"\n        Terminate the criterion. Can be extended by the user-derived class\n        \"\"\"\n        if self.test_status in ('RUNNING', 'INIT'):\n            self.test_status = \"SUCCESS\"\n\n        self.logger.debug(\"%s.terminate()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n\nclass MaxVelocityTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test for maximum velocity.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - max_velocity_allowed: maximum allowed velocity in m/s\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, max_velocity, optional=False, name=\"CheckMaximumVelocity\"):\n        \"\"\"\n        Setup actor and maximum allowed velovity\n        \"\"\"\n        super(MaxVelocityTest, self).__init__(name, actor, optional)\n        self.success_value = max_velocity\n\n    def update(self):\n        \"\"\"\n        Check velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actor is None:\n            return new_status\n\n        velocity = CarlaDataProvider.get_velocity(self.actor)\n\n        self.actual_value = max(velocity, self.actual_value)\n\n        if velocity > self.success_value:\n            self.test_status = \"FAILURE\"\n        else:\n            self.test_status = \"SUCCESS\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass DrivenDistanceTest(Criterion):\n    \"\"\"\n    This class contains an atomic test to check the driven distance\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - distance_success: If the actor's driven distance is more than this value (in meters),\n                        the test result is SUCCESS\n    - distance_acceptable: If the actor's driven distance is more than this value (in meters),\n                           the test result is ACCEPTABLE\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, distance, acceptable_distance=None, optional=False, name=\"CheckDrivenDistance\"):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(DrivenDistanceTest, self).__init__(name, actor, optional)\n        self.success_value = distance\n        self.acceptable_value = acceptable_distance\n        self._last_location = None\n\n    def initialise(self):\n        self._last_location = CarlaDataProvider.get_location(self.actor)\n        super(DrivenDistanceTest, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check distance\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actor is None:\n            return new_status\n\n        location = CarlaDataProvider.get_location(self.actor)\n\n        if location is None:\n            return new_status\n\n        if self._last_location is None:\n            self._last_location = location\n            return new_status\n\n        self.actual_value += location.distance(self._last_location)\n        self._last_location = location\n\n        if self.actual_value > self.success_value:\n            self.test_status = \"SUCCESS\"\n        elif (self.acceptable_value is not None and\n              self.actual_value > self.acceptable_value):\n            self.test_status = \"ACCEPTABLE\"\n        else:\n            self.test_status = \"RUNNING\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set final status\n        \"\"\"\n        if self.test_status != \"SUCCESS\":\n            self.test_status = \"FAILURE\"\n        self.actual_value = round(self.actual_value, 2)\n        super(DrivenDistanceTest, self).terminate(new_status)\n\n\nclass AverageVelocityTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test for average velocity.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - avg_velocity_success: If the actor's average velocity is more than this value (in m/s),\n                            the test result is SUCCESS\n    - avg_velocity_acceptable: If the actor's average velocity is more than this value (in m/s),\n                               the test result is ACCEPTABLE\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, velocity, acceptable_velocity=None, optional=False,\n                 name=\"CheckAverageVelocity\"):\n        \"\"\"\n        Setup actor and average velovity expected\n        \"\"\"\n        super(AverageVelocityTest, self).__init__(name, actor, optional)\n        self.success_value = velocity\n        self.acceptable_value = acceptable_velocity\n        self._last_location = None\n        self._distance = 0.0\n\n    def initialise(self):\n        self._last_location = CarlaDataProvider.get_location(self.actor)\n        super(AverageVelocityTest, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check velocity\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actor is None:\n            return new_status\n\n        location = CarlaDataProvider.get_location(self.actor)\n\n        if location is None:\n            return new_status\n\n        if self._last_location is None:\n            self._last_location = location\n            return new_status\n\n        self._distance += location.distance(self._last_location)\n        self._last_location = location\n\n        elapsed_time = GameTime.get_time()\n        if elapsed_time > 0.0:\n            self.actual_value = self._distance / elapsed_time\n\n        if self.actual_value > self.success_value:\n            self.test_status = \"SUCCESS\"\n        elif (self.acceptable_value is not None and\n              self.actual_value > self.acceptable_value):\n            self.test_status = \"ACCEPTABLE\"\n        else:\n            self.test_status = \"RUNNING\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set final status\n        \"\"\"\n        if self.test_status == \"RUNNING\":\n            self.test_status = \"FAILURE\"\n        super(AverageVelocityTest, self).terminate(new_status)\n\n\nclass CollisionTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test for collisions.\n\n    Args:\n    - actor (carla.Actor): CARLA actor to be used for this test\n    - other_actor (carla.Actor): only collisions with this actor will be registered\n    - other_actor_type (str): only collisions with actors including this type_id will count.\n        Additionally, the \"miscellaneous\" tag can also be used to include all static objects in the scene\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    COLLISION_RADIUS = 5  # Two collisions that happen within this distance count as one\n    MAX_ID_TIME = 5  # Two collisions with the same id that happen within this time count as one\n    EPSILON = 0.1  # Collisions at lower this speed won't be counted as the actor's fault\n\n    def __init__(self, actor, other_actor=None, other_actor_type=None,\n                 optional=False, terminate_on_failure=False, name=\"CollisionTest\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(CollisionTest, self).__init__(name, actor, optional, terminate_on_failure)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._other_actor = other_actor\n        self._other_actor_type = other_actor_type\n\n        # Attributes to store the last collisions's data\n        self._collision_sensor = None\n        self._collision_id = None\n        self._collision_time = None\n        self._collision_location = None\n\n    def initialise(self):\n        \"\"\"\n        Creates the sensor and callback\"\"\"\n        world = CarlaDataProvider.get_world()\n        blueprint = world.get_blueprint_library().find('sensor.other.collision')\n        self._collision_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor)\n        self._collision_sensor.listen(lambda event: self._count_collisions(event))\n        super(CollisionTest, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check collision count\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        actor_location = CarlaDataProvider.get_location(self.actor)\n\n        # Check if the last collision can be ignored\n        if self._collision_location:\n            distance_vector = actor_location - self._collision_location\n            if distance_vector.length() > self.COLLISION_RADIUS:\n                self._collision_location = None\n        if self._collision_id:\n            elapsed_time = GameTime.get_time() - self._collision_time\n            if elapsed_time > self.MAX_ID_TIME:\n                self._collision_id = None\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Cleanup sensor\n        \"\"\"\n        if self._collision_sensor is not None:\n            self._collision_sensor.stop()\n            self._collision_sensor.destroy()\n        self._collision_sensor = None\n        super(CollisionTest, self).terminate(new_status)\n\n    def _count_collisions(self, event):     # pylint: disable=too-many-return-statements\n        \"\"\"Update collision count\"\"\"\n        actor_location = CarlaDataProvider.get_location(self.actor)\n\n        # Check if the care about the other actor\n        if self._other_actor and self._other_actor.id != event.other_actor.id:\n            return\n\n        if self._other_actor_type:\n            if self._other_actor_type == \"miscellaneous\":  # Special OpenScenario case\n                if \"traffic\" not in event.other_actor.type_id and \"static\" not in event.other_actor.type_id:\n                    return\n            elif self._other_actor_type not in event.other_actor.type_id:\n                    return\n\n        # To avoid multiple counts of the same collision, filter some of them.\n        if self._collision_id == event.other_actor.id:\n            return\n        if self._collision_location:\n            distance_vector = actor_location - self._collision_location\n            if distance_vector.length() <= self.COLLISION_RADIUS:\n                return\n\n        # If the actor speed is 0, the collision isn't its fault\n        if CarlaDataProvider.get_velocity(self.actor) < self.EPSILON:\n            return\n\n        # The collision is valid, save the data\n        self.test_status = \"FAILURE\"\n        self.actual_value += 1\n\n        self._collision_time = GameTime.get_time()\n        self._collision_location = actor_location\n        if event.other_actor.id != 0: # Number 0: static objects -> ignore it\n            self._collision_id = event.other_actor.id\n\n        if ('static' in event.other_actor.type_id or 'traffic' in event.other_actor.type_id) \\\n                and 'sidewalk' not in event.other_actor.type_id:\n            actor_type = TrafficEventType.COLLISION_STATIC\n        elif 'vehicle' in event.other_actor.type_id:\n            actor_type = TrafficEventType.COLLISION_VEHICLE\n        elif 'walker' in event.other_actor.type_id:\n            actor_type = TrafficEventType.COLLISION_PEDESTRIAN\n        else:\n            return\n\n        collision_event = TrafficEvent(event_type=actor_type, frame=GameTime.get_frame())\n        collision_event.set_dict({'other_actor': event.other_actor, 'location': actor_location})\n        collision_event.set_message(\n            \"Agent collided against object with type={} and id={} at (x={}, y={}, z={})\".format(\n                event.other_actor.type_id,\n                event.other_actor.id,\n                round(actor_location.x, 3),\n                round(actor_location.y, 3),\n                round(actor_location.z, 3)))\n        self.events.append(collision_event)\n\n\nclass ActorBlockedTest(Criterion):\n\n    \"\"\"\n    This test will fail if the actor has had its linear velocity lower than a specific value for\n    a specific amount of time\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - min_speed: speed required [m/s]\n    - max_time: Maximum time (in seconds) the actor can remain under the speed threshold\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n\n    def __init__(self, actor, min_speed, max_time, name=\"ActorBlockedTest\", optional=False, terminate_on_failure=False):\n        \"\"\"\n        Class constructor\n        \"\"\"\n        super().__init__(name, actor, optional, terminate_on_failure)\n        self._min_speed = min_speed\n        self._max_time = max_time\n        self._time_last_valid_state = None\n        self._active = True\n        self.units = None  # We care about whether or not it fails, no units attached\n\n    def update(self):\n        \"\"\"\n        Check if the actor speed is above the min_speed\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Deactivate/Activate checking by blackboard message\n        active = py_trees.blackboard.Blackboard().get('AC_SwitchActorBlockedTest')\n        if active is not None:\n            self._active = active\n            self._time_last_valid_state = GameTime.get_time()\n            py_trees.blackboard.Blackboard().set(\"AC_SwitchActorBlockedTest\", None, overwrite=True)\n\n        if self._active:\n            linear_speed = CarlaDataProvider.get_velocity(self.actor)\n            if linear_speed is not None:\n                if linear_speed < self._min_speed and self._time_last_valid_state:\n                    if (GameTime.get_time() - self._time_last_valid_state) > self._max_time:\n                        # The actor has been \"blocked\" for too long, save the data\n                        self.test_status = \"FAILURE\"\n\n                        vehicle_location = CarlaDataProvider.get_location(self.actor)\n                        event = TrafficEvent(event_type=TrafficEventType.VEHICLE_BLOCKED, frame=GameTime.get_frame())\n                        event.set_message('Agent got blocked at (x={}, y={}, z={})'.format(\n                            round(vehicle_location.x, 3),\n                            round(vehicle_location.y, 3),\n                            round(vehicle_location.z, 3))\n                        )\n                        event.set_dict({'location': vehicle_location})\n                        self.events.append(event)\n                else:\n                    self._time_last_valid_state = GameTime.get_time()\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass KeepLaneTest(Criterion):\n    \"\"\"\n    This class contains an atomic test for keeping lane.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, optional=False, name=\"CheckKeepLane\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(KeepLaneTest, self).__init__(name, actor, optional)\n\n        world = self.actor.get_world()\n        blueprint = world.get_blueprint_library().find('sensor.other.lane_invasion')\n        self._lane_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor)\n        self._lane_sensor.listen(lambda event: self._count_lane_invasion(event))\n\n    def update(self):\n        \"\"\"\n        Check lane invasion count\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self.actual_value > 0:\n            self.test_status = \"FAILURE\"\n        else:\n            self.test_status = \"SUCCESS\"\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Cleanup sensor\n        \"\"\"\n        if self._lane_sensor is not None:\n            self._lane_sensor.destroy()\n            self._lane_sensor = None\n        super(KeepLaneTest, self).terminate(new_status)\n\n    def _count_lane_invasion(self, event):\n        \"\"\"\n        Callback to update lane invasion count\n        \"\"\"\n        self.actual_value += 1\n\n\nclass ReachedRegionTest(Criterion):\n\n    \"\"\"\n    This class contains the reached region test\n    The test is a success if the actor reaches a specified region\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - min_x, max_x, min_y, max_y: Bounding box of the checked region\n    \"\"\"\n\n    def __init__(self, actor, min_x, max_x, min_y, max_y, name=\"ReachedRegionTest\"):\n        \"\"\"\n        Setup trigger region (rectangle provided by\n        [min_x,min_y] and [max_x,max_y]\n        \"\"\"\n        super(ReachedRegionTest, self).__init__(name, actor)\n        self._min_x = min_x\n        self._max_x = max_x\n        self._min_y = min_y\n        self._max_y = max_y\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        in_region = False\n        if self.test_status != \"SUCCESS\":\n            in_region = (location.x > self._min_x and location.x < self._max_x) and (\n                location.y > self._min_y and location.y < self._max_y)\n            if in_region:\n                self.test_status = \"SUCCESS\"\n            else:\n                self.test_status = \"RUNNING\"\n\n        if self.test_status == \"SUCCESS\":\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass OffRoadTest(Criterion):\n\n    \"\"\"\n    Atomic containing a test to detect when an actor deviates from the driving lanes. This atomic can\n    fail when actor has spent a specific time outside driving lanes (defined by OpenDRIVE). Simplified\n    version of OnSidewalkTest, and doesn't relly on waypoints with *Sidewalk* lane types\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        duration (float): Time spent at sidewalks before the atomic fails.\n            If terminate_on_failure isn't active, this is ignored.\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n            when using the output argument\n        terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met.\n    \"\"\"\n\n    def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name=\"OffRoadTest\"):\n        \"\"\"\n        Setup of the variables\n        \"\"\"\n        super(OffRoadTest, self).__init__(name, actor, optional, terminate_on_failure)\n\n        self._map = CarlaDataProvider.get_map()\n        self._offroad = False\n\n        self._duration = duration\n        self._prev_time = None\n        self._time_offroad = 0\n\n    def update(self):\n        \"\"\"\n        First, transforms the actor's current position to its corresponding waypoint. This is\n        filtered to only use waypoints of type Driving or Parking. Depending on these results,\n        the actor will be considered to be outside (or inside) driving lanes.\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self.actor)\n\n        # Get the waypoint at the current location to see if the actor is offroad\n        drive_waypoint = self._map.get_waypoint(\n            current_location,\n            project_to_road=False\n        )\n        park_waypoint = self._map.get_waypoint(\n            current_location,\n            project_to_road=False,\n            lane_type=carla.LaneType.Parking\n        )\n        if drive_waypoint or park_waypoint:\n            self._offroad = False\n        else:\n            self._offroad = True\n\n        # Counts the time offroad\n        if self._offroad:\n            if self._prev_time is None:\n                self._prev_time = GameTime.get_time()\n            else:\n                curr_time = GameTime.get_time()\n                self._time_offroad += curr_time - self._prev_time\n                self._prev_time = curr_time\n        else:\n            self._prev_time = None\n\n        if self._time_offroad > self._duration:\n            self.test_status = \"FAILURE\"\n\n        if self._terminate_on_failure and self.test_status == \"FAILURE\":\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass EndofRoadTest(Criterion):\n\n    \"\"\"\n    Atomic containing a test to detect when an actor has changed to a different road\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        duration (float): Time spent after ending the road before the atomic fails.\n            If terminate_on_failure isn't active, this is ignored.\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n            when using the output argument\n        terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met.\n    \"\"\"\n\n    def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name=\"EndofRoadTest\"):\n        \"\"\"\n        Setup of the variables\n        \"\"\"\n        super(EndofRoadTest, self).__init__(name, actor, optional, terminate_on_failure)\n\n        self._map = CarlaDataProvider.get_map()\n        self._end_of_road = False\n\n        self._duration = duration\n        self._start_time = None\n        self._time_end_road = 0\n        self._road_id = None\n\n    def update(self):\n        \"\"\"\n        First, transforms the actor's current position to its corresponding waypoint. Then the road id\n        is compared with the initial one and if that's the case, a time is started\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self.actor)\n        current_waypoint = self._map.get_waypoint(current_location)\n\n        # Get the current road id\n        if self._road_id is None:\n            self._road_id = current_waypoint.road_id\n\n        else:\n            # Wait until the actor has left the road\n            if self._road_id != current_waypoint.road_id or self._start_time:\n\n                # Start counting\n                if self._start_time is None:\n                    self._start_time = GameTime.get_time()\n                    return new_status\n\n                curr_time = GameTime.get_time()\n                self._time_end_road = curr_time - self._start_time\n\n                if self._time_end_road > self._duration:\n                    self.test_status = \"FAILURE\"\n                    self.actual_value += 1\n                    return py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass OnSidewalkTest(Criterion):\n\n    \"\"\"\n    Atomic containing a test to detect sidewalk invasions of a specific actor. This atomic can\n    fail when actor has spent a specific time outside driving lanes (defined by OpenDRIVE).\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        duration (float): Time spent at sidewalks before the atomic fails.\n            If terminate_on_failure isn't active, this is ignored.\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n            when using the output argument\n        terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met.\n    \"\"\"\n\n    def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name=\"OnSidewalkTest\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(OnSidewalkTest, self).__init__(name, actor, optional, terminate_on_failure)\n\n        self._map = CarlaDataProvider.get_map()\n        self._onsidewalk_active = False\n        self._outside_lane_active = False\n\n        self._actor_location = self.actor.get_location()\n        self._wrong_sidewalk_distance = 0\n        self._wrong_outside_lane_distance = 0\n        self._sidewalk_start_location = None\n        self._outside_lane_start_location = None\n        self._duration = duration\n        self._prev_time = None\n        self._time_outside_lanes = 0\n\n    def update(self):\n        \"\"\"\n        First, transforms the actor's current position as well as its four corners to their\n        corresponding waypoints. Depending on their lane type, the actor will be considered to be\n        outside (or inside) driving lanes.\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has spent a given duration outside\n                driving lanes and terminate_on_failure is active\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and self.test_status == \"FAILURE\":\n            new_status = py_trees.common.Status.FAILURE\n\n        # Some of the vehicle parameters\n        current_tra = CarlaDataProvider.get_transform(self.actor)\n        current_loc = current_tra.location\n        current_wp = self._map.get_waypoint(current_loc, lane_type=carla.LaneType.Any)\n\n        # Case 1) Car center is at a sidewalk\n        if current_wp.lane_type == carla.LaneType.Sidewalk:\n            if not self._onsidewalk_active:\n                self._onsidewalk_active = True\n                self._sidewalk_start_location = current_loc\n\n        # Case 2) Not inside allowed zones (Driving and Parking)\n        elif current_wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n\n            # Get the vertices of the vehicle\n            heading_vec = current_tra.get_forward_vector()\n            heading_vec.z = 0\n            heading_vec = heading_vec / math.sqrt(math.pow(heading_vec.x, 2) + math.pow(heading_vec.y, 2))\n            perpendicular_vec = carla.Vector3D(-heading_vec.y, heading_vec.x, 0)\n\n            extent = self.actor.bounding_box.extent\n            x_boundary_vector = heading_vec * extent.x\n            y_boundary_vector = perpendicular_vec * extent.y\n\n            bbox = [\n                current_loc + carla.Location(x_boundary_vector - y_boundary_vector),\n                current_loc + carla.Location(x_boundary_vector + y_boundary_vector),\n                current_loc + carla.Location(-1 * x_boundary_vector - y_boundary_vector),\n                current_loc + carla.Location(-1 * x_boundary_vector + y_boundary_vector)]\n\n            bbox_wp = [\n                self._map.get_waypoint(bbox[0], lane_type=carla.LaneType.Any),\n                self._map.get_waypoint(bbox[1], lane_type=carla.LaneType.Any),\n                self._map.get_waypoint(bbox[2], lane_type=carla.LaneType.Any),\n                self._map.get_waypoint(bbox[3], lane_type=carla.LaneType.Any)]\n\n            lane_type_list = [bbox_wp[0].lane_type, bbox_wp[1].lane_type, bbox_wp[2].lane_type, bbox_wp[3].lane_type]\n\n            # Case 2.1) Not quite outside yet\n            if bbox_wp[0].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \\\n                or bbox_wp[1].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \\\n                or bbox_wp[2].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \\\n                    or bbox_wp[3].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking):\n\n                self._onsidewalk_active = False\n                self._outside_lane_active = False\n\n            # Case 2.2) At the mini Shoulders between Driving and Sidewalk\n            elif carla.LaneType.Sidewalk in lane_type_list:\n                if not self._onsidewalk_active:\n                    self._onsidewalk_active = True\n                    self._sidewalk_start_location = current_loc\n\n            else:\n                distance_vehicle_wp = current_loc.distance(current_wp.transform.location)\n\n                # Case 2.3) Outside lane\n                if distance_vehicle_wp >= current_wp.lane_width / 2:\n\n                    if not self._outside_lane_active:\n                        self._outside_lane_active = True\n                        self._outside_lane_start_location = current_loc\n\n                # Case 2.4) Very very edge case (but still inside driving lanes)\n                else:\n                    self._onsidewalk_active = False\n                    self._outside_lane_active = False\n\n        # Case 3) Driving and Parking conditions\n        else:\n            # Check for false positives at junctions\n            if current_wp.is_junction:\n                distance_vehicle_wp = math.sqrt(\n                    math.pow(current_wp.transform.location.x - current_loc.x, 2) +\n                    math.pow(current_wp.transform.location.y - current_loc.y, 2))\n\n                if distance_vehicle_wp <= current_wp.lane_width / 2:\n                    self._onsidewalk_active = False\n                    self._outside_lane_active = False\n                # Else, do nothing, the waypoint is too far to consider it a correct position\n            else:\n\n                self._onsidewalk_active = False\n                self._outside_lane_active = False\n\n        # Counts the time offroad\n        if self._onsidewalk_active or self._outside_lane_active:\n            if self._prev_time is None:\n                self._prev_time = GameTime.get_time()\n            else:\n                curr_time = GameTime.get_time()\n                self._time_outside_lanes += curr_time - self._prev_time\n                self._prev_time = curr_time\n        else:\n            self._prev_time = None\n\n        if self._time_outside_lanes > self._duration:\n            self.test_status = \"FAILURE\"\n\n        # Update the distances\n        distance_vector = CarlaDataProvider.get_location(self.actor) - self._actor_location\n        distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2))\n\n        if distance >= 0.02:  # Used to avoid micro-changes adding to considerable sums\n            self._actor_location = CarlaDataProvider.get_location(self.actor)\n\n            if self._onsidewalk_active:\n                self._wrong_sidewalk_distance += distance\n            elif self._outside_lane_active:\n                # Only add if car is outside the lane but ISN'T in a junction\n                self._wrong_outside_lane_distance += distance\n\n        # Register the sidewalk event\n        if not self._onsidewalk_active and self._wrong_sidewalk_distance > 0:\n\n            self.actual_value += 1\n\n            onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n            self._set_event_dict(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n\n            self._onsidewalk_active = False\n            self._wrong_sidewalk_distance = 0\n            self.events.append(onsidewalk_event)\n\n        # Register the outside of a lane event\n        if not self._outside_lane_active and self._wrong_outside_lane_distance > 0:\n\n            self.actual_value += 1\n\n            outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n            self._set_event_dict(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n\n            self._outside_lane_active = False\n            self._wrong_outside_lane_distance = 0\n            self.events.append(outsidelane_event)\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        If there is currently an event running, it is registered\n        \"\"\"\n        # If currently at a sidewalk, register the event\n        if self._onsidewalk_active:\n\n            self.actual_value += 1\n\n            onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n            self._set_event_dict(\n                onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance)\n\n            self._onsidewalk_active = False\n            self._wrong_sidewalk_distance = 0\n            self.events.append(onsidewalk_event)\n\n        # If currently outside of our lane, register the event\n        if self._outside_lane_active:\n\n            self.actual_value += 1\n\n            outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n            self._set_event_dict(\n                outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance)\n\n            self._outside_lane_active = False\n            self._wrong_outside_lane_distance = 0\n            self.events.append(outsidelane_event)\n\n        super(OnSidewalkTest, self).terminate(new_status)\n\n    def _set_event_message(self, event, location, distance):\n        \"\"\"\n        Sets the message of the event\n        \"\"\"\n        if event.get_type() == TrafficEventType.ON_SIDEWALK_INFRACTION:\n            message_start = 'Agent invaded the sidewalk'\n        else:\n            message_start = 'Agent went outside the lane'\n\n        event.set_message(\n            '{} for about {} meters, starting at (x={}, y={}, z={})'.format(\n                message_start,\n                round(distance, 3),\n                round(location.x, 3),\n                round(location.y, 3),\n                round(location.z, 3)))\n\n    def _set_event_dict(self, event, location, distance):\n        \"\"\"\n        Sets the dictionary of the event\n        \"\"\"\n        event.set_dict({'location': location, 'distance': distance})\n\n\nclass OutsideRouteLanesTest(Criterion):\n\n    \"\"\"\n    Atomic to detect if the vehicle is either on a sidewalk or at a wrong lane. The distance spent outside\n    is computed and it is returned as a percentage of the route distance traveled.\n\n    Args:\n        actor (carla.ACtor): CARLA actor to be used for this test\n        route (list [carla.Location, connection]): series of locations representing the route waypoints\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    ALLOWED_OUT_DISTANCE = 0.5  # At least 0.5, due to the mini-shoulder between lanes and sidewalks\n    MAX_VEHICLE_ANGLE = 120.0  # Maximum angle between the yaw and waypoint lane\n    MAX_WAYPOINT_ANGLE = 150.0  # Maximum change between the yaw-lane angle between frames\n    WINDOWS_SIZE = 3  # Amount of additional waypoints checked (in case the first on fails)\n\n    def __init__(self, actor, route, optional=False, name=\"OutsideRouteLanesTest\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        super(OutsideRouteLanesTest, self).__init__(name, actor, optional)\n        self.units = \"%\"\n\n        self._route = route\n        self._current_index = 0\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n\n        self._map = CarlaDataProvider.get_map()\n        self._last_ego_waypoint = self._map.get_waypoint(self.actor.get_location())\n\n        self._outside_lane_active = False\n        self._wrong_lane_active = False\n        self._last_road_id = None\n        self._last_lane_id = None\n        self._total_distance = 0\n        self._wrong_distance = 0\n        self._wrong_direction_active = True\n\n        self._traffic_event = None\n\n    def update(self):\n        \"\"\"\n        Transforms the actor location and its four corners to waypoints. Depending on its types,\n        the actor will be considered to be at driving lanes, sidewalk or offroad.\n\n        returns:\n            py_trees.common.Status.FAILURE: when the actor has left driving and terminate_on_failure is active\n            py_trees.common.Status.RUNNING: the rest of the time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Some of the vehicle parameters\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        # Deactivate / activate checking by blackboard message\n        active = py_trees.blackboard.Blackboard().get('AC_SwitchWrongDirectionTest')\n        if active is not None:\n            self._wrong_direction_active = active\n            py_trees.blackboard.Blackboard().set(\"AC_SwitchWrongDirectionTest\", None, overwrite=True)\n\n        self._is_outside_driving_lanes(location)\n        self._is_at_wrong_lane(location)\n\n        if self._outside_lane_active or (self._wrong_direction_active and self._wrong_lane_active):\n            self.test_status = \"FAILURE\"\n\n        # Get the traveled distance\n        for index in range(self._current_index + 1,\n                           min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)):\n            # Get the dot product to know if it has passed this location\n            route_transform = self._route_transforms[index]\n            route_location = route_transform.location\n\n            wp_dir = route_transform.get_forward_vector()  # Waypoint's forward vector\n            wp_veh = location - route_location  # vector waypoint - vehicle\n\n            if wp_veh.dot(wp_dir) > 0:\n                # Get the distance traveled and add it to the total distance\n                prev_route_location = self._route_transforms[self._current_index].location\n                new_dist = prev_route_location.distance(route_location)\n                self._total_distance += new_dist\n\n                # And to the wrong one if outside route lanes\n                if self._outside_lane_active or (self._wrong_direction_active and self._wrong_lane_active):\n                    self._wrong_distance += new_dist\n\n                if self._wrong_distance:\n                    self._set_traffic_event()\n\n                self._current_index = index\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def _set_traffic_event(self):\n        \"\"\"\n        Creates the traffic event / updates it\n        \"\"\"\n        if self._traffic_event is None:\n            self._traffic_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION, frame=GameTime.get_frame())\n            self.events.append(self._traffic_event)\n\n        percentage = self._wrong_distance / self._total_distance * 100\n        self.actual_value = round(percentage, 2)\n\n        self._traffic_event.set_message(\n            \"Agent went outside its route lanes for about {} meters \"\n            \"({}% of the completed route)\".format(\n                round(self._wrong_distance, 3),\n                round(percentage, 2)))\n\n        self._traffic_event.set_dict({\n            'distance': self._wrong_distance,\n            'percentage': percentage\n        })\n\n        self._traffic_event.set_frame(GameTime.get_frame())\n\n    def _is_outside_driving_lanes(self, location):\n        \"\"\"\n        Detects if the ego_vehicle is outside driving lanes\n        \"\"\"\n        driving_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving)\n        parking_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Parking)\n\n        driving_distance = location.distance(driving_wp.transform.location)\n        if parking_wp is not None:  # Some towns have no parking\n            parking_distance = location.distance(parking_wp.transform.location)\n        else:\n            parking_distance = float('inf')\n\n        if driving_distance >= parking_distance:\n            distance = parking_distance\n            lane_width = parking_wp.lane_width\n        else:\n            distance = driving_distance\n            lane_width = driving_wp.lane_width\n\n        self._outside_lane_active = bool(distance > (lane_width / 2 + self.ALLOWED_OUT_DISTANCE))\n\n    def _is_at_wrong_lane(self, location):\n        \"\"\"\n        Detects if the ego_vehicle has invaded a wrong lane\n        \"\"\"\n        waypoint = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving)\n        lane_id = waypoint.lane_id\n        road_id = waypoint.road_id\n\n        # Lanes and roads are too chaotic at junctions\n        if waypoint.is_junction:\n            self._wrong_lane_active = False\n        elif self._last_road_id != road_id or self._last_lane_id != lane_id:\n\n            if self._last_ego_waypoint.is_junction:\n                # Just exited a junction, check the wp direction vs the ego's one\n                wp_yaw = waypoint.transform.rotation.yaw % 360\n                actor_yaw = self.actor.get_transform().rotation.yaw % 360\n                angle = (wp_yaw - actor_yaw) % 360\n\n                if angle < self.MAX_VEHICLE_ANGLE or angle > (360 - self.MAX_VEHICLE_ANGLE):\n                    self._wrong_lane_active = False\n                else:\n                    self._wrong_lane_active = True\n\n            else:\n                # Route direction can be considered continuous, check for a big gap.\n                last_wp_yaw = self._last_ego_waypoint.transform.rotation.yaw % 360\n                wp_yaw = waypoint.transform.rotation.yaw % 360\n                angle = (last_wp_yaw - wp_yaw) % 360\n\n                if angle > self.MAX_WAYPOINT_ANGLE and angle < (360 - self.MAX_WAYPOINT_ANGLE):\n\n                    # Is the ego vehicle going back to the lane, or going out? Take the opposite\n                    self._wrong_lane_active = not bool(self._wrong_lane_active)\n\n        # Remember the last state\n        self._last_lane_id = lane_id\n        self._last_road_id = road_id\n        self._last_ego_waypoint = waypoint\n\n\nclass WrongLaneTest(Criterion):\n\n    \"\"\"\n    This class contains an atomic test to detect invasions to wrong direction lanes.\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - optional [optional]: If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n    MAX_ALLOWED_ANGLE = 120.0\n    MAX_WAYPOINT_ANGLE = 150.0\n\n    def __init__(self, actor, optional=False, name=\"WrongLaneTest\"):\n        \"\"\"\n        Construction with sensor setup\n        \"\"\"\n        super(WrongLaneTest, self).__init__(name, actor, optional)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        self._map = CarlaDataProvider.get_map()\n        self._last_lane_id = None\n        self._last_road_id = None\n\n        self._in_lane = True\n        self._wrong_distance = 0\n        self._actor_location = self.actor.get_location()\n        self._previous_lane_waypoint = self._map.get_waypoint(self.actor.get_location())\n        self._wrong_lane_start_location = None\n\n    def update(self):\n        \"\"\"\n        Check lane invasion count\n        \"\"\"\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        lane_waypoint = self._map.get_waypoint(self.actor.get_location())\n        current_lane_id = lane_waypoint.lane_id\n        current_road_id = lane_waypoint.road_id\n\n        if (self._last_road_id != current_road_id or self._last_lane_id != current_lane_id) \\\n                and not lane_waypoint.is_junction:\n            next_waypoint = lane_waypoint.next(2.0)[0]\n\n            if not next_waypoint:\n                return new_status\n\n            # The waypoint route direction can be considered continuous.\n            # Therefore just check for a big gap in waypoint directions.\n            previous_lane_direction = self._previous_lane_waypoint.transform.get_forward_vector()\n            current_lane_direction = lane_waypoint.transform.get_forward_vector()\n\n            p_lane_vector = np.array([previous_lane_direction.x, previous_lane_direction.y])\n            c_lane_vector = np.array([current_lane_direction.x, current_lane_direction.y])\n\n            waypoint_angle = math.degrees(\n                math.acos(np.clip(np.dot(p_lane_vector, c_lane_vector) /\n                                  (np.linalg.norm(p_lane_vector) * np.linalg.norm(c_lane_vector)), -1.0, 1.0)))\n\n            if waypoint_angle > self.MAX_WAYPOINT_ANGLE and self._in_lane:\n\n                self.test_status = \"FAILURE\"\n                self._in_lane = False\n                self.actual_value += 1\n                self._wrong_lane_start_location = self._actor_location\n\n            else:\n                # Reset variables\n                self._in_lane = True\n\n            # Continuity is broken after a junction so check vehicle-lane angle instead\n            if self._previous_lane_waypoint.is_junction:\n\n                vector_wp = np.array([next_waypoint.transform.location.x - lane_waypoint.transform.location.x,\n                                      next_waypoint.transform.location.y - lane_waypoint.transform.location.y])\n\n                vector_actor = np.array([math.cos(math.radians(self.actor.get_transform().rotation.yaw)),\n                                         math.sin(math.radians(self.actor.get_transform().rotation.yaw))])\n\n                vehicle_lane_angle = math.degrees(\n                    math.acos(np.clip(np.dot(vector_actor, vector_wp) / (np.linalg.norm(vector_wp)), -1.0, 1.0)))\n\n                if vehicle_lane_angle > self.MAX_ALLOWED_ANGLE:\n\n                    self.test_status = \"FAILURE\"\n                    self._in_lane = False\n                    self.actual_value += 1\n                    self._wrong_lane_start_location = self.actor.get_location()\n\n        # Keep adding \"meters\" to the counter\n        distance_vector = self.actor.get_location() - self._actor_location\n        distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2))\n\n        if distance >= 0.02:  # Used to avoid micro-changes adding add to considerable sums\n            self._actor_location = CarlaDataProvider.get_location(self.actor)\n\n            if not self._in_lane and not lane_waypoint.is_junction:\n                self._wrong_distance += distance\n\n        # Register the event\n        if self._in_lane and self._wrong_distance > 0:\n\n            wrong_way_event = TrafficEvent(event_type=TrafficEventType.WRONG_WAY_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(wrong_way_event, self._wrong_lane_start_location,\n                                    self._wrong_distance, current_road_id, current_lane_id)\n            self._set_event_dict(wrong_way_event, self._wrong_lane_start_location,\n                                 self._wrong_distance, current_road_id, current_lane_id)\n\n            self.events.append(wrong_way_event)\n            self._wrong_distance = 0\n\n        # Remember the last state\n        self._last_lane_id = current_lane_id\n        self._last_road_id = current_road_id\n        self._previous_lane_waypoint = lane_waypoint\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        If there is currently an event running, it is registered\n        \"\"\"\n        if not self._in_lane:\n\n            lane_waypoint = self._map.get_waypoint(self.actor.get_location())\n            current_lane_id = lane_waypoint.lane_id\n            current_road_id = lane_waypoint.road_id\n\n            wrong_way_event = TrafficEvent(event_type=TrafficEventType.WRONG_WAY_INFRACTION, frame=GameTime.get_frame())\n            self._set_event_message(wrong_way_event, self._wrong_lane_start_location,\n                                    self._wrong_distance, current_road_id, current_lane_id)\n            self._set_event_dict(wrong_way_event, self._wrong_lane_start_location,\n                                 self._wrong_distance, current_road_id, current_lane_id)\n\n            self._wrong_distance = 0\n            self._in_lane = True\n            self.events.append(wrong_way_event)\n\n        super(WrongLaneTest, self).terminate(new_status)\n\n    def _set_event_message(self, event, location, distance, road_id, lane_id):\n        \"\"\"\n        Sets the message of the event\n        \"\"\"\n\n        event.set_message(\n            \"Agent invaded a lane in opposite direction for {} meters, starting at (x={}, y={}, z={}). \"\n            \"road_id={}, lane_id={}\".format(\n                round(distance, 3),\n                round(location.x, 3),\n                round(location.y, 3),\n                round(location.z, 3),\n                road_id,\n                lane_id))\n\n    def _set_event_dict(self, event, location, distance, road_id, lane_id):\n        \"\"\"\n        Sets the dictionary of the event\n        \"\"\"\n        event.set_dict({\n            'location': location,\n            'distance': distance,\n            'road_id': road_id,\n            'lane_id': lane_id})\n\n\nclass InRadiusRegionTest(Criterion):\n\n    \"\"\"\n    The test is a success if the actor is within a given radius of a specified region\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - x, y, radius: Position (x,y) and radius (in meters) used to get the checked region\n    \"\"\"\n\n    def __init__(self, actor, x, y, radius, name=\"InRadiusRegionTest\"):\n        \"\"\"\n        \"\"\"\n        super(InRadiusRegionTest, self).__init__(name, actor)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._x = x     # pylint: disable=invalid-name\n        self._y = y     # pylint: disable=invalid-name\n        self._radius = radius\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        if self.test_status != \"SUCCESS\":\n            in_radius = math.sqrt(((location.x - self._x)**2) + ((location.y - self._y)**2)) < self._radius\n            if in_radius:\n                route_completion_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETED, frame=GameTime.get_frame())\n                route_completion_event.set_message(\"Destination was successfully reached\")\n                self.events.append(route_completion_event)\n                self.test_status = \"SUCCESS\"\n            else:\n                self.test_status = \"RUNNING\"\n\n        if self.test_status == \"SUCCESS\":\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InRouteTest(Criterion):\n\n    \"\"\"\n    The test is a success if the actor is never outside route. The actor can go outside of the route\n    but only for a certain amount of distance\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - route: Route to be checked\n    - offroad_max: Maximum distance (in meters) the actor can deviate from the route\n    - offroad_min: Maximum safe distance (in meters). Might eventually cause failure\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    MAX_ROUTE_PERCENTAGE = 30  # %\n    WINDOWS_SIZE = 5  # Amount of additional waypoints checked\n\n    def __init__(self, actor, route, offroad_min=None, offroad_max=30, name=\"InRouteTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super(InRouteTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self.units = None  # We care about whether or not it fails, no units attached\n\n        self._route = route\n        self._offroad_max = offroad_max\n        # Unless specified, halve of the max value\n        if offroad_min is None:\n            self._offroad_min = self._offroad_max / 2\n        else:\n            self._offroad_min = self._offroad_min\n\n        self._world = CarlaDataProvider.get_world()\n        self._route_transforms, _ = zip(*self._route)\n        self._route_length = len(self._route)\n        self._current_index = 0\n        self._out_route_distance = 0\n        self._in_safe_route = True\n\n        self._accum_meters = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            loc = tran.location\n            d = loc.distance(prev_loc)\n            accum = 0 if i == 0 else self._accum_meters[i - 1]\n\n            self._accum_meters.append(d + accum)\n            prev_loc = loc\n\n        # Blackboard variable\n        blackv = py_trees.blackboard.Blackboard()\n        _ = blackv.set(\"InRoute\", True)\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        elif self.test_status in ('RUNNING', 'INIT'):\n\n            off_route = True\n\n            shortest_distance = float('inf')\n            closest_index = -1\n\n            # Get the closest distance\n            for index in range(self._current_index,\n                               min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)):\n                ref_location = self._route_transforms[index].location\n                distance = math.sqrt(((location.x - ref_location.x) ** 2) + ((location.y - ref_location.y) ** 2))\n                if distance <= shortest_distance:\n                    closest_index = index\n                    shortest_distance = distance\n\n            if closest_index == -1 or shortest_distance == float('inf'):\n                return new_status\n\n            # Check if the actor is out of route\n            if shortest_distance < self._offroad_max:\n                off_route = False\n                self._in_safe_route = bool(shortest_distance < self._offroad_min)\n\n            # If actor advanced a step, record the distance\n            if self._current_index != closest_index:\n\n                new_dist = self._accum_meters[closest_index] - self._accum_meters[self._current_index]\n\n                # If too far from the route, add it and check if its value\n                if not self._in_safe_route:\n                    self._out_route_distance += new_dist\n                    out_route_percentage = 100 * self._out_route_distance / self._accum_meters[-1]\n                    if out_route_percentage > self.MAX_ROUTE_PERCENTAGE:\n                        off_route = True\n\n                self._current_index = closest_index\n\n            if off_route:\n                # Blackboard variable\n                blackv = py_trees.blackboard.Blackboard()\n                _ = blackv.set(\"InRoute\", False)\n\n                route_deviation_event = TrafficEvent(event_type=TrafficEventType.ROUTE_DEVIATION, frame=GameTime.get_frame())\n                route_deviation_event.set_message(\n                    \"Agent deviated from the route at (x={}, y={}, z={})\".format(\n                        round(location.x, 3),\n                        round(location.y, 3),\n                        round(location.z, 3)))\n                route_deviation_event.set_dict({'location': location})\n\n                self.events.append(route_deviation_event)\n\n                self.test_status = \"FAILURE\"\n                self.actual_value += 1\n                new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass RouteCompletionTest(Criterion):\n\n    \"\"\"\n    Check at which stage of the route is the actor at each tick\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - route: Route to be checked\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    WINDOWS_SIZE = 2\n\n    # Thresholds to return that a route has been completed\n    DISTANCE_THRESHOLD = 10.0  # meters\n    PERCENTAGE_THRESHOLD = 99  # %\n\n    def __init__(self, actor, route, name=\"RouteCompletionTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super(RouteCompletionTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self.units = \"%\"\n        self.success_value = 100\n        self._route = route\n        self._map = CarlaDataProvider.get_map()\n\n        self._index = 0\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n        self._route_accum_perc = self._get_acummulated_percentages()\n\n        self.target_location = self._route_transforms[-1].location\n\n        self._traffic_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETION, frame=0)\n        self._traffic_event.set_dict({'route_completed': self.actual_value})\n        self._traffic_event.set_message(\"Agent has completed {} of the route\".format(self.actual_value))\n        self.events.append(self._traffic_event)\n\n    def _get_acummulated_percentages(self):\n        \"\"\"Gets the accumulated percentage of each of the route transforms\"\"\"\n        accum_meters = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            d = tran.location.distance(prev_loc)\n            new_d = 0 if i == 0 else accum_meters[i - 1]\n\n            accum_meters.append(d + new_d)\n            prev_loc = tran.location\n\n        max_dist = accum_meters[-1]\n        return [x / max_dist * 100 for x in accum_meters]\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        elif self.test_status in ('RUNNING', 'INIT'):\n\n            for index in range(self._index, min(self._index + self.WINDOWS_SIZE + 1, self._route_length)):\n                # Get the dot product to know if it has passed this location\n                route_transform = self._route_transforms[index]\n                route_location = route_transform.location\n                wp_dir = route_transform.get_forward_vector()          # Waypoint's forward vector\n                wp_veh = location - route_location                     # vector route - vehicle\n\n                if wp_veh.dot(wp_dir) > 0:\n                    self._index = index\n                    self.actual_value = self._route_accum_perc[self._index]\n\n            self.actual_value = round(self.actual_value, 2)\n            self._traffic_event.set_dict({'route_completed': self.actual_value})\n            self._traffic_event.set_message(\"Agent has completed {} of the route\".format(self.actual_value))\n\n            if self.actual_value > self.PERCENTAGE_THRESHOLD \\\n                    and location.distance(self.target_location) < self.DISTANCE_THRESHOLD:\n                self.test_status = \"SUCCESS\"\n                self.actual_value = 100\n\n        elif self.test_status == \"SUCCESS\":\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set test status to failure if not successful and terminate\n        \"\"\"\n        self.actual_value = round(self.actual_value, 2)\n\n        self._traffic_event.set_dict({'route_completed': self.actual_value})\n        self._traffic_event.set_message(\"Agent has completed {} of the route\".format(self.actual_value))\n\n        if self.test_status == \"INIT\":\n            self.test_status = \"FAILURE\"\n        super(RouteCompletionTest, self).terminate(new_status)\n\n\nclass RunningRedLightTest(Criterion):\n\n    \"\"\"\n    Check if an actor is running a red light\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    DISTANCE_LIGHT = 15  # m\n\n    def __init__(self, actor, name=\"RunningRedLightTest\", terminate_on_failure=False):\n        \"\"\"\n        Init\n        \"\"\"\n        super(RunningRedLightTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._list_traffic_lights = []\n        self._last_red_light_id = None\n        self.debug = False\n\n        all_actors = CarlaDataProvider.get_all_actors()\n        for _actor in all_actors:\n            if 'traffic_light' in _actor.type_id:\n                center, waypoints = self.get_traffic_light_waypoints(_actor)\n                self._list_traffic_lights.append((_actor, center, waypoints))\n\n    # pylint: disable=no-self-use\n    def is_vehicle_crossing_line(self, seg1, seg2):\n        \"\"\"\n        check if vehicle crosses a line segment\n        \"\"\"\n        line1 = shapely.geometry.LineString([(seg1[0].x, seg1[0].y), (seg1[1].x, seg1[1].y)])\n        line2 = shapely.geometry.LineString([(seg2[0].x, seg2[0].y), (seg2[1].x, seg2[1].y)])\n        inter = line1.intersection(line2)\n\n        return not inter.is_empty\n\n    def update(self):\n        \"\"\"\n        Check if the actor is running a red light\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        transform = CarlaDataProvider.get_transform(self.actor)\n        location = transform.location\n        if location is None:\n            return new_status\n\n        veh_extent = self.actor.bounding_box.extent.x\n\n        tail_close_pt = self.rotate_point(carla.Vector3D(-0.8 * veh_extent, 0, 0), transform.rotation.yaw)\n        tail_close_pt = location + carla.Location(tail_close_pt)\n\n        tail_far_pt = self.rotate_point(carla.Vector3D(-veh_extent - 1, 0, 0), transform.rotation.yaw)\n        tail_far_pt = location + carla.Location(tail_far_pt)\n\n        for traffic_light, center, waypoints in self._list_traffic_lights:\n\n            if self.debug:\n                z = 2.1\n                if traffic_light.state == carla.TrafficLightState.Red:\n                    color = carla.Color(155, 0, 0)\n                elif traffic_light.state == carla.TrafficLightState.Green:\n                    color = carla.Color(0, 155, 0)\n                else:\n                    color = carla.Color(155, 155, 0)\n                self._world.debug.draw_point(center + carla.Location(z=z), size=0.2, color=color, life_time=0.01)\n                for wp in waypoints:\n                    text = \"{}.{}\".format(wp.road_id, wp.lane_id)\n                    self._world.debug.draw_string(\n                        wp.transform.location + carla.Location(x=1, z=z), text, color=color, life_time=0.01)\n                    self._world.debug.draw_point(\n                        wp.transform.location + carla.Location(z=z), size=0.1, color=color, life_time=0.01)\n\n            center_loc = carla.Location(center)\n\n            if self._last_red_light_id and self._last_red_light_id == traffic_light.id:\n                continue\n            if center_loc.distance(location) > self.DISTANCE_LIGHT:\n                continue\n            if traffic_light.state != carla.TrafficLightState.Red:\n                continue\n\n            for wp in waypoints:\n\n                tail_wp = self._map.get_waypoint(tail_far_pt)\n\n                # Calculate the dot product (Might be unscaled, as only its sign is important)\n                ve_dir = CarlaDataProvider.get_transform(self.actor).get_forward_vector()\n                wp_dir = wp.transform.get_forward_vector()\n\n                # Check the lane until all the \"tail\" has passed\n                if tail_wp.road_id == wp.road_id and tail_wp.lane_id == wp.lane_id and ve_dir.dot(wp_dir) > 0:\n                    # This light is red and is affecting our lane\n                    yaw_wp = wp.transform.rotation.yaw\n                    lane_width = wp.lane_width\n                    location_wp = wp.transform.location\n\n                    lft_lane_wp = self.rotate_point(carla.Vector3D(0.6 * lane_width, 0, 0), yaw_wp + 90)\n                    lft_lane_wp = location_wp + carla.Location(lft_lane_wp)\n                    rgt_lane_wp = self.rotate_point(carla.Vector3D(0.6 * lane_width, 0, 0), yaw_wp - 90)\n                    rgt_lane_wp = location_wp + carla.Location(rgt_lane_wp)\n\n                    # Is the vehicle traversing the stop line?\n                    if self.is_vehicle_crossing_line((tail_close_pt, tail_far_pt), (lft_lane_wp, rgt_lane_wp)):\n\n                        self.test_status = \"FAILURE\"\n                        self.actual_value += 1\n                        location = traffic_light.get_transform().location\n                        red_light_event = TrafficEvent(event_type=TrafficEventType.TRAFFIC_LIGHT_INFRACTION, frame=GameTime.get_frame())\n                        red_light_event.set_message(\n                            \"Agent ran a red light {} at (x={}, y={}, z={})\".format(\n                                traffic_light.id,\n                                round(location.x, 3),\n                                round(location.y, 3),\n                                round(location.z, 3)))\n                        red_light_event.set_dict({'id': traffic_light.id, 'location': location})\n\n                        self.events.append(red_light_event)\n                        self._last_red_light_id = traffic_light.id\n                        break\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def rotate_point(self, point, angle):\n        \"\"\"\n        rotate a given point by a given angle\n        \"\"\"\n        x_ = math.cos(math.radians(angle)) * point.x - math.sin(math.radians(angle)) * point.y\n        y_ = math.sin(math.radians(angle)) * point.x + math.cos(math.radians(angle)) * point.y\n        return carla.Vector3D(x_, y_, point.z)\n\n    def get_traffic_light_waypoints(self, traffic_light):\n        \"\"\"\n        get area of a given traffic light\n        \"\"\"\n        base_transform = traffic_light.get_transform()\n        base_rot = base_transform.rotation.yaw\n        area_loc = base_transform.transform(traffic_light.trigger_volume.location)\n\n        # Discretize the trigger box into points\n        area_ext = traffic_light.trigger_volume.extent\n        x_values = np.arange(-0.9 * area_ext.x, 0.9 * area_ext.x, 1.0)  # 0.9 to avoid crossing to adjacent lanes\n\n        area = []\n        for x in x_values:\n            point = self.rotate_point(carla.Vector3D(x, 0, area_ext.z), base_rot)\n            point_location = area_loc + carla.Location(x=point.x, y=point.y)\n            area.append(point_location)\n\n        # Get the waypoints of these points, removing duplicates\n        ini_wps = []\n        for pt in area:\n            wpx = self._map.get_waypoint(pt)\n            # As x_values are arranged in order, only the last one has to be checked\n            if not ini_wps or ini_wps[-1].road_id != wpx.road_id or ini_wps[-1].lane_id != wpx.lane_id:\n                ini_wps.append(wpx)\n\n        # Advance them until the intersection\n        wps = []\n        for wpx in ini_wps:\n            while not wpx.is_intersection:\n                next_wp = wpx.next(0.5)[0]\n                if next_wp and not next_wp.is_intersection:\n                    wpx = next_wp\n                else:\n                    break\n            wps.append(wpx)\n\n        return area_loc, wps\n\n\nclass RunningStopTest(Criterion):\n\n    \"\"\"\n    Check if an actor is running a stop sign\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    PROXIMITY_THRESHOLD = 4.0  # Stops closer than this distance will be detected [m]\n    SPEED_THRESHOLD = 0.1 # Minimum speed to consider the actor has stopped [m/s]\n    WAYPOINT_STEP = 0.5  # m\n\n    def __init__(self, actor, name=\"RunningStopTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super(RunningStopTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map()\n        self._list_stop_signs = []\n        self._target_stop_sign = None\n        self._stop_completed = False\n\n        self._last_failed_stop = None\n\n        for _actor in CarlaDataProvider.get_all_actors():\n            if 'traffic.stop' in _actor.type_id:\n                self._list_stop_signs.append(_actor)\n\n    def point_inside_boundingbox(self, point, bb_center, bb_extent, multiplier=1.2):\n        \"\"\"Checks whether or not a point is inside a bounding box.\"\"\"\n\n        # pylint: disable=invalid-name\n        A = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        B = carla.Vector2D(bb_center.x + multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        D = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y + multiplier * bb_extent.y)\n        M = carla.Vector2D(point.x, point.y)\n\n        AB = B - A\n        AD = D - A\n        AM = M - A\n        am_ab = AM.x * AB.x + AM.y * AB.y\n        ab_ab = AB.x * AB.x + AB.y * AB.y\n        am_ad = AM.x * AD.x + AM.y * AD.y\n        ad_ad = AD.x * AD.x + AD.y * AD.y\n\n        return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad  # pylint: disable=chained-comparison\n\n    def is_actor_affected_by_stop(self, wp_list, stop):\n        \"\"\"\n        Check if the given actor is affected by the stop.\n        Without using waypoints, a stop might not be detected if the actor is moving at the lane edge.\n        \"\"\"\n        # Quick distance test\n        stop_location = stop.get_transform().transform(stop.trigger_volume.location)\n        actor_location = wp_list[0].transform.location\n        if stop_location.distance(actor_location) > self.PROXIMITY_THRESHOLD:\n            return False\n\n        # Check if the any of the actor wps is inside the stop's bounding box.\n        # Using more than one waypoint removes issues with small trigger volumes and backwards movement\n        stop_extent = stop.trigger_volume.extent\n        for actor_wp in wp_list:\n            if self.point_inside_boundingbox(actor_wp.transform.location, stop_location, stop_extent):\n                return True\n\n        return False\n\n    def _scan_for_stop_sign(self, actor_transform, wp_list):\n        \"\"\"\n        Check the stop signs to see if any of them affect the actor.\n        Ignore all checks when going backwards or through an opposite direction\"\"\"\n\n        actor_direction = actor_transform.get_forward_vector()\n\n        # Ignore all when going backwards\n        actor_velocity = self.actor.get_velocity()\n        if actor_velocity.dot(actor_direction) < -0.17:  # 100º, just in case\n            return None\n\n        # Ignore all when going in the opposite direction\n        lane_direction = wp_list[0].transform.get_forward_vector()\n        if actor_direction.dot(lane_direction) < -0.17:  # 100º, just in case\n            return None\n\n        for stop in self._list_stop_signs:\n            if self.is_actor_affected_by_stop(wp_list, stop):\n                return stop\n\n    def _get_waypoints(self, actor):\n        \"\"\"Returns a list of waypoints starting from the ego location and a set amount forward\"\"\"\n        wp_list = []\n        steps = int(self.PROXIMITY_THRESHOLD / self.WAYPOINT_STEP)\n\n        # Add the actor location\n        wp = self._map.get_waypoint(actor.get_location())\n        wp_list.append(wp)\n\n        # And its forward waypoints\n        next_wp = wp\n        for _ in range(steps):\n            next_wps = next_wp.next(self.WAYPOINT_STEP)\n            if not next_wps:\n                break\n            next_wp = next_wps[0]\n            wp_list.append(next_wp)\n\n        return wp_list\n\n    def update(self):\n        \"\"\"\n        Check if the actor is running a red light\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_transform = self.actor.get_transform()\n        check_wps = self._get_waypoints(self.actor)\n\n        if not self._target_stop_sign:\n            self._target_stop_sign = self._scan_for_stop_sign(actor_transform, check_wps)\n            return new_status\n\n        if not self._stop_completed:\n            current_speed = CarlaDataProvider.get_velocity(self.actor)\n            if current_speed < self.SPEED_THRESHOLD:\n                self._stop_completed = True\n\n        if not self.is_actor_affected_by_stop(check_wps, self._target_stop_sign):\n            if not self._stop_completed and self._last_failed_stop != self._target_stop_sign.id:\n                # did we stop?\n                self.actual_value += 1\n                self.test_status = \"FAILURE\"\n                stop_location = self._target_stop_sign.get_transform().location\n                running_stop_event = TrafficEvent(event_type=TrafficEventType.STOP_INFRACTION, frame=GameTime.get_frame())\n                running_stop_event.set_message(\n                    \"Agent ran a stop with id={} at (x={}, y={}, z={})\".format(\n                        self._target_stop_sign.id,\n                        round(stop_location.x, 3),\n                        round(stop_location.y, 3),\n                        round(stop_location.z, 3)))\n                running_stop_event.set_dict({'id': self._target_stop_sign.id, 'location': stop_location})\n\n                self.events.append(running_stop_event)\n\n                self._last_failed_stop = self._target_stop_sign.id\n\n            # Reset state\n            self._target_stop_sign = None\n            self._stop_completed = False\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass MinimumSpeedRouteTest(Criterion):\n\n    \"\"\"\n    Check at which stage of the route is the actor at each tick\n\n    Important parameters:\n    - actor: CARLA actor to be used for this test\n    - route: Route to be checked\n    - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test\n    \"\"\"\n    WINDOWS_SIZE = 2\n    RATIO = 1\n\n    def __init__(self, actor, route, checkpoints=1, name=\"MinimumSpeedRouteTest\", terminate_on_failure=False):\n        \"\"\"\n        \"\"\"\n        super().__init__(name, actor, terminate_on_failure=terminate_on_failure)\n        self.units = \"%\"\n        self.success_value = 100\n        self.actual_value = 100\n\n        self._route = route\n        self._accum_dist = []\n        prev_trans = None\n        for trans, _ in route:\n            if prev_trans:\n                dist = trans.location.distance(prev_trans.location)\n                self._accum_dist.append(dist + self._accum_dist[-1])\n            else:\n                self._accum_dist.append(0)\n            prev_trans = trans\n        self._route_length = len(self._route)\n\n        self._checkpoints = checkpoints\n        self._checkpoint_dist = self._accum_dist[-1] / self._checkpoints\n\n        self._mean_speed = 0\n        self._actor_speed = 0\n        self._speed_points = 0\n\n        self._current_dist = 0\n        self._checkpoint_values = []\n\n        self._index = 0\n\n\n    def update(self):\n        \"\"\"\n        Check if the actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._terminate_on_failure and (self.test_status == \"FAILURE\"):\n            new_status = py_trees.common.Status.FAILURE\n\n        # Check the actor progress through the route \n        location = CarlaDataProvider.get_location(self.actor)\n        if location is None:\n            return new_status\n\n        for index in range(self._index, min(self._index + self.WINDOWS_SIZE + 1, self._route_length)):\n            # Get the dot product to know if it has passed this location\n            route_transform = self._route[index][0]\n            route_location = route_transform.location\n            wp_dir = route_transform.get_forward_vector()\n            wp_veh = location - route_location\n\n            if wp_veh.dot(wp_dir) > 0:\n                self._index = index\n\n        if self._accum_dist[self._index] - self._current_dist > self._checkpoint_dist:\n            self._set_traffic_event()\n            self._current_dist = self._accum_dist[self._index]\n            self._mean_speed = 0\n            self._actor_speed = 0\n            self._speed_points = 0\n\n        # Get the actor speed\n        velocity = CarlaDataProvider.get_velocity(self.actor)\n        if velocity is None:\n            return new_status\n\n        # Get the speed of the surrounding Background Activity\n        all_vehicles = CarlaDataProvider.get_all_actors().filter('vehicle*')\n        background_vehicles = [v for v in all_vehicles if v.attributes['role_name'] == 'background']\n\n        if background_vehicles:\n            frame_mean_speed = 0\n            for vehicle in background_vehicles:\n                frame_mean_speed += CarlaDataProvider.get_velocity(vehicle)\n            frame_mean_speed /= len(background_vehicles)\n\n            # Record the data\n            self._mean_speed += frame_mean_speed\n            self._actor_speed += velocity\n            self._speed_points += 1\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n    def _set_traffic_event(self):\n\n        if self._speed_points > 0 and self._mean_speed:\n            self._mean_speed /= self._speed_points\n            self._actor_speed /= self._speed_points\n            checkpoint_value = round(self._actor_speed / (self.RATIO * self._mean_speed) * 100, 2)\n        else:\n            checkpoint_value = 100\n        \n        self.test_status = \"FAILURE\"\n        self._traffic_event = TrafficEvent(TrafficEventType.MIN_SPEED_INFRACTION, GameTime.get_frame())\n        self._traffic_event.set_dict({'percentage': checkpoint_value})\n        self._traffic_event.set_message(f\"Average speed is {checkpoint_value}% of the surrounding traffic's one\")\n        self.events.append(self._traffic_event)\n\n        self._checkpoint_values.append(checkpoint_value)\n\n    def terminate(self, new_status):\n        \"\"\"\n        Set the actual value as a percentage of the two mean speeds,\n        the test status to failure if not successful and terminate\n        \"\"\"\n        # Routes end at around 99%, so make sure the last checkpoint is recorded\n        if self._accum_dist[self._index] / self._accum_dist[-1] > 0.95:\n            self._set_traffic_event()\n\n        if len(self._checkpoint_values):\n            self.actual_value = round(sum(self._checkpoint_values) / len(self._checkpoint_values), 2)\n        super().terminate(new_status)\n\n\nclass YieldToEmergencyVehicleTest(Criterion):\n\n    \"\"\"\n    Atomic Criterion to detect if the actor yields its lane to the emergency vehicle behind it.\n    Detection is done by checking if the ev is in front of the actor\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        ev (carla.Actor): The emergency vehicle\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    WAITING_TIME_THRESHOLD = 15 # Maximum time for actor to block ev\n\n    def __init__(self, actor, ev, optional=False, name=\"YieldToEmergencyVehicleTest\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        self._ev = ev\n        self._terminated = False\n        super().__init__(name, actor, optional)\n\n    def update(self):\n        \"\"\"\n        Monitor that the EV ends up in front of the actor\n\n        returns:\n            py_trees.common.Status.RUNNING\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_location = CarlaDataProvider.get_location(self.actor)\n        if not actor_location:\n            return new_status\n        ev_location = CarlaDataProvider.get_location(self._ev)\n        if not ev_location:\n            return new_status\n\n        ev_direction = CarlaDataProvider.get_transform(self._ev).get_forward_vector()\n        actor_ev_vector = actor_location - ev_location\n\n        if ev_direction.dot(actor_ev_vector) > 0:\n            self.test_status = \"FAILURE\"\n        else:\n            self.test_status = \"SUCCESS\"\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"Set the traffic event, if needed\"\"\"\n        # Terminates are called multiple times. Do this only once\n        if not self._terminated:\n            if self.test_status == \"FAILURE\":\n                traffic_event = TrafficEvent(TrafficEventType.YIELD_TO_EMERGENCY_VEHICLE, GameTime.get_frame())\n                traffic_event.set_message(\"Agent failed to yield to an emergency vehicle\")\n                self.events.append(traffic_event)\n\n            self._terminated = True\n\n        super().terminate(new_status)\n\n\nclass ScenarioTimeoutTest(Criterion):\n\n    \"\"\"\n    Atomic Criterion to detect if the actor has been incapable of finishing an scenario\n\n    Args:\n        actor (carla.Actor): CARLA actor to be used for this test\n        optional (bool): If True, the result is not considered for an overall pass/fail result\n    \"\"\"\n\n    def __init__(self, actor, scenario_name, optional=False, name=\"ScenarioTimeoutTest\"):\n        \"\"\"\n        Constructor\n        \"\"\"\n        super().__init__(name, actor, optional)\n        self.success_value = 0\n        self.actual_value = 0\n        self._scenario_name = scenario_name\n\n    def update(self):\n        \"\"\"wait\"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n    def terminate(self, new_status):\n        \"\"\"check the blackboard for the data and update the criteria if one found\"\"\"\n\n        blackboard_name = f\"ScenarioTimeout_{self._scenario_name}\"\n\n        timeout = py_trees.blackboard.Blackboard().get(blackboard_name)\n        if timeout:\n            self.actual_value = 1\n            self.test_status = \"FAILURE\"\n\n            traffic_event = TrafficEvent(event_type=TrafficEventType.SCENARIO_TIMEOUT, frame=GameTime.get_frame())\n            traffic_event.set_message(\"Agent timed out a scenario\")\n            self.events.append(traffic_event)\n        py_trees.blackboard.Blackboard().set(blackboard_name, None, True)\n\n        super().terminate(new_status)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides all atomic scenario behaviors that reflect\ntrigger conditions to either activate another behavior, or to stop\nanother behavior.\n\nFor example, such a condition could be \"InTriggerRegion\", which checks\nthat a given actor reached a certain region on the map, and then starts/stops\na behavior of this actor.\n\nThe atomics are implemented with py_trees and make use of the AtomicCondition\nbase class\n\"\"\"\n\nfrom __future__ import print_function\n\nimport operator\nimport datetime\nimport math\nimport py_trees\nimport carla\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import calculate_distance\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.tools.scenario_helper import get_distance_along_route, get_distance_between_actors\n\nimport srunner.tools as sr_tools\n\nEPSILON = 0.001\n\n\nclass AtomicCondition(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Base class for all atomic conditions used to setup a scenario\n\n    *All behaviors should use this class as parent*\n\n    Important parameters:\n    - name: Name of the atomic condition\n    \"\"\"\n\n    def __init__(self, name):\n        \"\"\"\n        Default init. Has to be called via super from derived class\n        \"\"\"\n        super(AtomicCondition, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self.name = name\n\n    def setup(self, unused_timeout=15):\n        \"\"\"\n        Default setup\n        \"\"\"\n        self.logger.debug(\"%s.setup()\" % (self.__class__.__name__))\n        return True\n\n    def initialise(self):\n        \"\"\"\n        Initialise setup\n        \"\"\"\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def terminate(self, new_status):\n        \"\"\"\n        Default terminate. Can be extended in derived class\n        \"\"\"\n        self.logger.debug(\"%s.terminate()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n\nclass InTriggerDistanceToOSCPosition(AtomicCondition):\n\n    \"\"\"\n    OpenSCENARIO atomic\n    This class contains the trigger condition for a distance to an OpenSCENARIO position\n\n    Args:\n        actor (carla.Actor): CARLA actor to execute the behavior\n        osc_position (str): OpenSCENARIO position\n        distance (float): Trigger distance between the actor and the target location in meters\n        name (str): Name of the condition\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the openSCENARIO position\n    \"\"\"\n\n    def __init__(self, actor, osc_position, distance, along_route=False,\n                 comparison_operator=operator.lt, name=\"InTriggerDistanceToOSCPosition\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTriggerDistanceToOSCPosition, self).__init__(name)\n        self._actor = actor\n        self._osc_position = osc_position\n        self._distance = distance\n        self._along_route = along_route\n        self._comparison_operator = comparison_operator\n        self._map = CarlaDataProvider.get_map()\n\n        if self._along_route:\n            # Get the global route planner, used to calculate the route\n            self._grp = GlobalRoutePlanner(self._map, 0.5)\n        else:\n            self._grp = None\n\n    def initialise(self):\n        if self._distance < 0:\n            raise ValueError(\"distance value must be positive\")\n\n    def update(self):\n        \"\"\"\n        Check if actor is in trigger distance\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # calculate transform with method in openscenario_parser.py\n        osc_transform = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n            self._osc_position)\n\n        if osc_transform is not None:\n            osc_location = osc_transform.location\n            actor_location = CarlaDataProvider.get_location(self._actor)\n\n            if self._along_route:\n                # Global planner needs a location at a driving lane\n                actor_location = self._map.get_waypoint(actor_location).transform.location\n                osc_location = self._map.get_waypoint(osc_location).transform.location\n\n            distance = calculate_distance(actor_location, osc_location, self._grp)\n\n            if self._comparison_operator(distance, self._distance):\n                new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass InTimeToArrivalToOSCPosition(AtomicCondition):\n\n    \"\"\"\n    OpenSCENARIO atomic\n    This class contains a trigger if an actor arrives within a given time to an OpenSCENARIO position\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - osc_position: OpenSCENARIO position\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - name: Name of the condition\n\n    The condition terminates with SUCCESS, when the actor can reach the position within the given time\n    \"\"\"\n\n    def __init__(self, actor, osc_position, time, along_route=False,\n                 comparison_operator=operator.lt, name=\"InTimeToArrivalToOSCPosition\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTimeToArrivalToOSCPosition, self).__init__(name)\n        self._map = CarlaDataProvider.get_map()\n        self._actor = actor\n        self._osc_position = osc_position\n        self._time = float(time)\n        self._along_route = along_route\n        self._comparison_operator = comparison_operator\n\n        if self._along_route:\n            # Get the global route planner, used to calculate the route\n            self._grp = GlobalRoutePlanner(self._map, 0.5)\n        else:\n            self._grp = None\n\n    def initialise(self):\n        if self._time < 0:\n            raise ValueError(\"time value must be positive\")\n\n    def update(self):\n        \"\"\"\n        Check if actor can arrive within trigger time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # calculate transform with method in openscenario_parser.py\n        try:\n            osc_transform = sr_tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform(\n                self._osc_position)\n        except AttributeError:\n            return py_trees.common.Status.FAILURE\n        target_location = osc_transform.location\n        actor_location = CarlaDataProvider.get_location(self._actor)\n\n        if target_location is None or actor_location is None:\n            return new_status\n\n        if self._along_route:\n            # Global planner needs a location at a driving lane\n            actor_location = self._map.get_waypoint(actor_location).transform.location\n            target_location = self._map.get_waypoint(target_location).transform.location\n\n        distance = calculate_distance(actor_location, target_location, self._grp)\n\n        actor_velocity = CarlaDataProvider.get_velocity(self._actor)\n\n        # time to arrival\n        if actor_velocity > 0:\n            time_to_arrival = distance / actor_velocity\n        elif distance == 0:\n            time_to_arrival = 0\n        else:\n            time_to_arrival = float('inf')\n\n        if self._comparison_operator(time_to_arrival, self._time):\n            new_status = py_trees.common.Status.SUCCESS\n        return new_status\n\n\nclass StandStill(AtomicCondition):\n\n    \"\"\"\n    This class contains a standstill behavior of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - duration: Duration of the behavior in seconds\n\n    The condition terminates with SUCCESS, when the actor does not move\n    \"\"\"\n\n    def __init__(self, actor, name, duration=float(\"inf\")):\n        \"\"\"\n        Setup actor\n        \"\"\"\n        super(StandStill, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n\n        self._duration = duration\n        self._start_time = 0\n\n    def initialise(self):\n        \"\"\"\n        Initialize the start time of this condition\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        super(StandStill, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check if the _actor stands still (v=0)\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        velocity = CarlaDataProvider.get_velocity(self._actor)\n\n        if velocity > EPSILON:\n            self._start_time = GameTime.get_time()\n\n        if GameTime.get_time() - self._start_time > self._duration:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass RelativeVelocityToOtherActor(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between an actor's velocity\n    and another actor's one. The behavior returns SUCCESS when the\n    expected comparison (greater than / less than / equal to) is achieved\n\n    Args:\n        actor (carla.Actor): actor from which the velocity is taken\n        other_actor (carla.Actor): The actor with the reference velocity\n        speed (float): Difference of speed between the actors\n        name (string): Name of the condition\n        comparison_operator: Type \"operator\", used to compare the two velocities\n    \"\"\"\n\n    def __init__(self, actor, other_actor, speed, comparison_operator=operator.gt,\n                 name=\"RelativeVelocityToOtherActor\"):\n        \"\"\"\n        Setup the parameters\n        \"\"\"\n        super(RelativeVelocityToOtherActor, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._other_actor = other_actor\n        self._relative_speed = speed\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the speed of the two actors and compares them according to the comparison operator\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        curr_speed = CarlaDataProvider.get_velocity(self._actor)\n        other_speed = CarlaDataProvider.get_velocity(self._other_actor)\n\n        relative_speed = curr_speed - other_speed\n\n        if self._comparison_operator(relative_speed, self._relative_speed):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TriggerVelocity(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between an actor's speed and a reference one.\n    The behavior returns SUCCESS when the expected comparison (greater than /\n    less than / equal to) is achieved.\n\n    Args:\n        actor (carla.Actor): CARLA actor from which the speed will be taken.\n        name (string): Name of the atomic\n        target_velocity (float): velcoity to be compared with the actor's one\n        comparison_operator: Type \"operator\", used to compare the two velocities\n    \"\"\"\n\n    def __init__(self, actor, target_velocity, comparison_operator=operator.gt, name=\"TriggerVelocity\"):\n        \"\"\"\n        Setup the atomic parameters\n        \"\"\"\n        super(TriggerVelocity, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._target_velocity = target_velocity\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the speed of the actor and compares it with the reference one\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        actor_speed = CarlaDataProvider.get_velocity(self._actor)\n\n        if self._comparison_operator(actor_speed, self._target_velocity):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TriggerAcceleration(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between an actor's acceleration\n    and a reference one. The behavior returns SUCCESS when the\n    expected comparison (greater than / less than / equal to) is achieved\n\n    Args:\n        actor (carla.Actor): CARLA actor to execute the behavior\n        name (str): Name of the condition\n        target_acceleration (float): Acceleration reference (in m/s^2) on which the success is dependent\n        comparison_operator (operator): Type \"operator\", used to compare the two acceleration\n    \"\"\"\n\n    def __init__(self, actor, target_acceleration, comparison_operator=operator.gt, name=\"TriggerAcceleration\"):\n        \"\"\"\n        Setup trigger acceleration\n        \"\"\"\n        super(TriggerAcceleration, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._target_acceleration = target_acceleration\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the accleration of the actor and compares it with the reference one\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        acceleration = self._actor.get_acceleration()\n        linear_accel = math.sqrt(math.pow(acceleration.x, 2) +\n                                 math.pow(acceleration.y, 2) +\n                                 math.pow(acceleration.z, 2))\n\n        if self._comparison_operator(linear_accel, self._target_acceleration):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TimeOfDayComparison(AtomicCondition):\n\n    \"\"\"\n    Atomic containing a comparison between the current time of day of the simulation\n    and a given one. The behavior returns SUCCESS when the\n    expected comparison (greater than / less than / equal to) is achieved\n\n    Args:\n        datetime (datetime): CARLA actor to execute the behavior\n        name (str): Name of the condition\n        target_acceleration (float): Acceleration reference (in m/s^2) on which the success is dependent\n        comparison_operator (operator): Type \"operator\", used to compare the two acceleration\n    \"\"\"\n\n    def __init__(self, dattime, comparison_operator=operator.gt, name=\"TimeOfDayComparison\"):\n        \"\"\"\n        \"\"\"\n        super(TimeOfDayComparison, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._datetime = datetime.datetime.strptime(dattime, \"%Y-%m-%dT%H:%M:%S\")\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Gets the time of day of the simulation and compares it with the reference one\n\n        returns:\n            py_trees.common.Status.RUNNING when the comparison fails and\n            py_trees.common.Status.SUCCESS when it succeeds\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        try:\n            check_dtime = operator.attrgetter(\"Datetime\")\n            dtime = check_dtime(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if self._comparison_operator(dtime, self._datetime):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass OSCStartEndCondition(AtomicCondition):\n\n    \"\"\"\n    This class contains a check if a named story element has started/terminated.\n\n    Important parameters:\n    - element_name: The story element's name attribute\n    - element_type: The element type [act,scene,maneuver,event,action]\n    - rule: Either START or END\n\n    The condition terminates with SUCCESS, when the named story element starts\n    \"\"\"\n\n    def __init__(self, element_type, element_name, rule, name=\"OSCStartEndCondition\"):\n        \"\"\"\n        Setup element details\n        \"\"\"\n        super(OSCStartEndCondition, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._element_type = element_type.upper()\n        self._element_name = element_name\n        self._rule = rule.upper()\n        self._start_time = None\n        self._blackboard = py_trees.blackboard.Blackboard()\n\n    def initialise(self):\n        \"\"\"\n        Initialize the start time of this condition\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        super(OSCStartEndCondition, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check if the specified story element has started/ended since the beginning of the condition\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if new_status == py_trees.common.Status.RUNNING:\n            blackboard_variable_name = \"({}){}-{}\".format(self._element_type, self._element_name, self._rule)\n            element_start_time = self._blackboard.get(blackboard_variable_name)\n            if element_start_time and element_start_time >= self._start_time:\n                new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerRegion(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger region (condition) of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - min_x, max_x, min_y, max_y: bounding box of the trigger region\n\n    The condition terminates with SUCCESS, when the actor reached the target region\n    \"\"\"\n\n    def __init__(self, actor, min_x, max_x, min_y, max_y, name=\"TriggerRegion\"):\n        \"\"\"\n        Setup trigger region (rectangle provided by\n        [min_x,min_y] and [max_x,max_y]\n        \"\"\"\n        super(InTriggerRegion, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._min_x = min_x\n        self._max_x = max_x\n        self._min_y = min_y\n        self._max_y = max_y\n\n    def update(self):\n        \"\"\"\n        Check if the _actor location is within trigger region\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n\n        if location is None:\n            return new_status\n\n        not_in_region = (location.x < self._min_x or location.x > self._max_x) or \\\n                        (location.y < self._min_y or location.y > self._max_y)\n        if not not_in_region:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToVehicle(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger distance (condition) between to actors\n    of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - reference_actor: Reference CARLA actor\n    - name: Name of the condition\n    - distance: Trigger distance between the two actors in meters\n    - distance_type: Specifies how distance should be calculated between the two actors\n    - freespace: if True distance is calculated between closest boundary points else it will be from center-center\n    - dx, dy, dz: distance to reference_location (location of reference_actor)\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the other actor\n    \"\"\"\n\n    def __init__(self, reference_actor, actor, distance, comparison_operator=operator.lt,\n                 distance_type=\"cartesianDistance\", freespace=False, name=\"TriggerDistanceToVehicle\"):\n        \"\"\"\n        Setup trigger distance\n        \"\"\"\n        super(InTriggerDistanceToVehicle, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._reference_actor = reference_actor\n        self._actor = actor\n        self._distance = distance\n        self._distance_type = distance_type\n        self._freespace = freespace\n        self._comparison_operator = comparison_operator\n\n        if distance_type == \"longitudinal\":\n            self._global_rp = CarlaDataProvider.get_global_route_planner()\n        else:\n            self._global_rp = None\n\n    def update(self):\n        \"\"\"\n        Check if the ego vehicle is within trigger distance to other actor\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n        reference_location = CarlaDataProvider.get_location(self._reference_actor)\n\n        if location is None or reference_location is None:\n            return new_status\n\n        distance = get_distance_between_actors(\n            self._actor, self._reference_actor, self._distance_type, self._freespace, self._global_rp)\n\n        if self._comparison_operator(distance, self._distance):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToLocation(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger (condition) for a distance to a fixed\n    location of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - target_location: Reference location (carla.location)\n    - name: Name of the condition\n    - distance: Trigger distance between the actor and the target location in meters\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the given location\n    \"\"\"\n\n    def __init__(self,\n                 actor,\n                 target_location,\n                 distance,\n                 comparison_operator=operator.lt,\n                 name=\"InTriggerDistanceToLocation\"):\n        \"\"\"\n        Setup trigger distance\n        \"\"\"\n        super(InTriggerDistanceToLocation, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._target_location = target_location\n        self._actor = actor\n        self._distance = distance\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Check if the actor is within trigger distance to the target location\n        \"\"\"\n\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n\n        if location is None:\n            return new_status\n\n        if self._comparison_operator(calculate_distance(\n                location, self._target_location), self._distance):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToNextIntersection(AtomicCondition):\n\n    \"\"\"\n    This class contains the trigger (condition) for a distance to the\n    next intersection of a scenario\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - distance: Trigger distance between the actor and the next intersection in meters\n\n    The condition terminates with SUCCESS, when the actor reached the target distance to the next intersection\n    \"\"\"\n\n    def __init__(self, actor, distance, name=\"InTriggerDistanceToNextIntersection\"):\n        \"\"\"\n        Setup trigger distance\n        \"\"\"\n        super(InTriggerDistanceToNextIntersection, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._distance = distance\n        self._map = CarlaDataProvider.get_map()\n\n        waypoint = self._map.get_waypoint(self._actor.get_location())\n        while waypoint and not waypoint.is_intersection:\n            waypoint = waypoint.next(1)[-1]\n\n        self._final_location = waypoint.transform.location\n\n    def update(self):\n        \"\"\"\n        Check if the actor is within trigger distance to the intersection\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_waypoint = self._map.get_waypoint(CarlaDataProvider.get_location(self._actor))\n        distance = calculate_distance(current_waypoint.transform.location, self._final_location)\n\n        if distance < self._distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTriggerDistanceToLocationAlongRoute(AtomicCondition):\n\n    \"\"\"\n    Implementation for a behavior that will check if a given actor\n    is within a given distance to a given location considering a given route\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - distance: Trigger distance between the actor and the next intersection in meters\n    - route: Route to be checked\n    - location: Location on the route to be checked\n\n    The condition terminates with SUCCESS, when the actor reached the target distance\n    along its route to the given location\n    \"\"\"\n\n    def __init__(self, actor, route, location, distance, name=\"InTriggerDistanceToLocationAlongRoute\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(InTriggerDistanceToLocationAlongRoute, self).__init__(name)\n        self._map = CarlaDataProvider.get_map()\n        self._actor = actor\n        self._location = location\n        self._route = route\n        self._distance = distance\n\n        self._location_distance, _ = get_distance_along_route(self._route, self._location)\n\n    def update(self):\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self._actor)\n\n        if current_location is None:\n            return new_status\n\n        if current_location.distance(self._location) < self._distance + 20:\n\n            actor_distance, _ = get_distance_along_route(self._route, current_location)\n\n            # If closer than self._distance and hasn't passed the trigger point\n            if (self._location_distance < actor_distance + self._distance and\n                actor_distance < self._location_distance) or \\\n                    self._location_distance < 1.0:\n                new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass InTimeToArrivalToLocation(AtomicCondition):\n\n    \"\"\"\n    This class contains a check if a actor arrives within a given time\n    at a given location.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - location: Location to be checked in this behavior\n\n    The condition terminates with SUCCESS, when the actor can reach the target location within the given time\n    \"\"\"\n\n    _max_time_to_arrival = float('inf')  # time to arrival in seconds\n\n    def __init__(self, actor, time, location, comparison_operator=operator.lt, name=\"TimeToArrival\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTimeToArrivalToLocation, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._time = time\n        self._target_location = location\n        self._comparison_operator = comparison_operator\n\n    def update(self):\n        \"\"\"\n        Check if the actor can arrive at target_location within time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self._actor)\n\n        if current_location is None:\n            return new_status\n\n        distance = calculate_distance(current_location, self._target_location)\n        velocity = CarlaDataProvider.get_velocity(self._actor)\n\n        # if velocity is too small, simply use a large time to arrival\n        time_to_arrival = self._max_time_to_arrival\n        if velocity > EPSILON:\n            time_to_arrival = distance / velocity\n\n        if self._comparison_operator(time_to_arrival, self._time):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTimeToArrivalToVehicle(AtomicCondition):\n\n    \"\"\"\n    This class contains a check if a actor arrives within a given time\n    at another actor.\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - other_actor: Reference actor used in this behavior\n\n    The condition terminates with SUCCESS, when the actor can reach the other vehicle within the given time\n    \"\"\"\n\n    _max_time_to_arrival = float('inf')  # time to arrival in seconds\n\n    def __init__(self, actor, other_actor, time, condition_freespace=False,\n                 along_route=False, comparison_operator=operator.lt, name=\"TimeToArrival\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(InTimeToArrivalToVehicle, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._map = CarlaDataProvider.get_map()\n        self._actor = actor\n        self._other_actor = other_actor\n        self._time = time\n        self._condition_freespace = condition_freespace\n        self._along_route = along_route\n        self._comparison_operator = comparison_operator\n\n        if self._along_route:\n            # Get the global route planner, used to calculate the route\n            self._grp = GlobalRoutePlanner(self._map, 0.5)\n        else:\n            self._grp = None\n\n    def update(self):\n        \"\"\"\n        Check if the ego vehicle can arrive at other actor within time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        current_location = CarlaDataProvider.get_location(self._actor)\n        other_location = CarlaDataProvider.get_location(self._other_actor)\n\n        # Get the bounding boxes\n        if self._condition_freespace:\n            if isinstance(self._actor, (carla.Vehicle, carla.Walker)):\n                actor_extent = self._actor.bounding_box.extent.x\n            else:\n                # Patch, as currently static objects have no bounding boxes\n                actor_extent = 0\n\n            if isinstance(self._other_actor, (carla.Vehicle, carla.Walker)):\n                other_extent = self._other_actor.bounding_box.extent.x\n            else:\n                # Patch, as currently static objects have no bounding boxes\n                other_extent = 0\n\n        if current_location is None or other_location is None:\n            return new_status\n\n        current_velocity = CarlaDataProvider.get_velocity(self._actor)\n        other_velocity = CarlaDataProvider.get_velocity(self._other_actor)\n\n        if self._along_route:\n            # Global planner needs a location at a driving lane\n            current_location = self._map.get_waypoint(current_location).transform.location\n            other_location = self._map.get_waypoint(other_location).transform.location\n\n        distance = calculate_distance(current_location, other_location, self._grp)\n\n        # if velocity is too small, simply use a large time to arrival\n        time_to_arrival = self._max_time_to_arrival\n\n        if current_velocity > other_velocity:\n            if self._condition_freespace:\n                time_to_arrival = (distance - actor_extent - other_extent) / (current_velocity - other_velocity)\n            else:\n                time_to_arrival = distance / (current_velocity - other_velocity)\n\n        if self._comparison_operator(time_to_arrival, self._time):\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass InTimeToArrivalToVehicleSideLane(InTimeToArrivalToLocation):\n\n    \"\"\"\n    This class contains a check if a actor arrives within a given time\n    at another actor's side lane. Inherits from InTimeToArrivalToLocation\n\n    Important parameters:\n    - actor: CARLA actor to execute the behavior\n    - name: Name of the condition\n    - time: The behavior is successful, if TTA is less than _time_ in seconds\n    - cut_in_lane: the lane from where the other_actor will do the cut in\n    - other_actor: Reference actor used in this behavior\n\n    The condition terminates with SUCCESS, when the actor can reach the other vehicle within the given time\n    \"\"\"\n\n    _max_time_to_arrival = float('inf')  # time to arrival in seconds\n\n    def __init__(self, actor, other_actor, time, side_lane,\n                 comparison_operator=operator.lt, name=\"InTimeToArrivalToVehicleSideLane\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        self._other_actor = other_actor\n        self._side_lane = side_lane\n\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map(self._world)\n\n        other_location = other_actor.get_transform().location\n        other_waypoint = self._map.get_waypoint(other_location)\n\n        if self._side_lane == 'right':\n            other_side_waypoint = other_waypoint.get_left_lane()\n        elif self._side_lane == 'left':\n            other_side_waypoint = other_waypoint.get_right_lane()\n        else:\n            raise Exception(\"cut_in_lane must be either 'left' or 'right'\")\n\n        other_side_location = other_side_waypoint.transform.location\n\n        super(InTimeToArrivalToVehicleSideLane, self).__init__(\n            actor, time, other_side_location, comparison_operator, name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Check if the ego vehicle can arrive at other actor within time\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        other_location = CarlaDataProvider.get_location(self._other_actor)\n        other_waypoint = self._map.get_waypoint(other_location)\n\n        if self._side_lane == 'right':\n            other_side_waypoint = other_waypoint.get_left_lane()\n        elif self._side_lane == 'left':\n            other_side_waypoint = other_waypoint.get_right_lane()\n        else:\n            raise Exception(\"cut_in_lane must be either 'left' or 'right'\")\n        if other_side_waypoint is None:\n            return new_status\n\n        self._target_location = other_side_waypoint.transform.location\n\n        if self._target_location is None:\n            return new_status\n\n        new_status = super(InTimeToArrivalToVehicleSideLane, self).update()\n\n        return new_status\n\n\nclass WaitUntilInFront(AtomicCondition):\n\n    \"\"\"\n    Behavior that support the creation of cut ins. It waits until the actor has passed another actor\n\n    Parameters:\n    - actor: the one getting in front of the other actor\n    - other_actor: the reference vehicle that the actor will have to get in front of\n    - factor: How much in front the actor will have to get (from 0 to infinity):\n        0: They are right next to each other\n        1: The front of the other_actor and the back of the actor are right next to each other\n    \"\"\"\n\n    def __init__(self, actor, other_actor, factor=1, check_distance=True, name=\"WaitUntilInFront\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super(WaitUntilInFront, self).__init__(name)\n        self._actor = actor\n        self._other_actor = other_actor\n        self._distance = 10\n        self._factor = max(EPSILON, factor)  # Must be > 0\n        self._check_distance = check_distance\n\n        self._world = CarlaDataProvider.get_world()\n        self._map = CarlaDataProvider.get_map(self._world)\n\n        actor_extent = self._actor.bounding_box.extent.x\n        other_extent = self._other_actor.bounding_box.extent.x\n        self._length = self._factor * (actor_extent + other_extent)\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Checks if the two actors meet the requirements\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        in_front = False\n        close_by = False\n\n        # Location of our actor\n        actor_location = CarlaDataProvider.get_location(self._actor)\n        if actor_location is None:\n            return new_status\n\n        # Waypoint in front of the other actor\n        other_location = CarlaDataProvider.get_location(self._other_actor)\n        other_waypoint = self._map.get_waypoint(other_location)\n        if other_waypoint is None:\n            return new_status\n        other_next_waypoints = other_waypoint.next(self._length)\n        if other_next_waypoints is None:\n            return new_status\n        other_next_waypoint = other_next_waypoints[0]\n\n        # Wait for the vehicle to be in front\n        other_dir = other_next_waypoint.transform.get_forward_vector()\n        act_other_dir = actor_location - other_next_waypoint.transform.location\n\n        if other_dir.dot(act_other_dir) > 0.0:\n            in_front = True\n\n        # Wait for it to be close-by\n        if not self._check_distance:\n            close_by = True\n        elif actor_location.distance(other_next_waypoint.transform.location) < self._distance:\n            close_by = True\n\n        if in_front and close_by:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass WaitUntilInFrontPosition(AtomicCondition):\n\n    \"\"\"\n    Behavior that support the creation of cut ins. It waits until the actor has passed another actor\n\n    Parameters:\n    - actor: the one getting in front of the other actor\n    - transform: the reference transform that the actor will have to get in front of\n    \"\"\"\n\n    def __init__(self, actor, transform, check_distance=True, distance=10, name=\"WaitUntilInFrontPosition\"):\n        \"\"\"\n        Init\n        \"\"\"\n        super().__init__(name)\n\n        self._actor = actor\n        self._ref_transform = transform\n        self._ref_location = transform.location\n        self._ref_vector = transform.get_forward_vector()\n        self._check_distance = check_distance\n        self._distance = distance\n\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Checks if the two actors meet the requirements\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        # Is the actor in front?\n        location = CarlaDataProvider.get_location(self._actor)\n        if location is None:\n            return new_status\n\n        actor_dir = location - self._ref_location\n        in_front = actor_dir.dot(self._ref_vector) > 0.0\n\n        # Is the actor close-by?\n        if not self._check_distance or location.distance(self._ref_location) < self._distance:\n            close_by = True\n        else:\n            close_by = False\n\n        if in_front and close_by:\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass DriveDistance(AtomicCondition):\n\n    \"\"\"\n    This class contains an atomic behavior to drive a certain distance.\n\n    Important parameters:\n    - actor: CARLA actor to execute the condition\n    - distance: Distance for this condition in meters\n\n    The condition terminates with SUCCESS, when the actor drove at least the given distance\n    \"\"\"\n\n    def __init__(self, actor, distance, name=\"DriveDistance\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(DriveDistance, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._target_distance = distance\n        self._distance = 0\n        self._location = None\n        self._actor = actor\n\n    def initialise(self):\n        self._location = CarlaDataProvider.get_location(self._actor)\n        super(DriveDistance, self).initialise()\n\n    def update(self):\n        \"\"\"\n        Check driven distance\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._location is None:\n            return new_status\n\n        new_location = CarlaDataProvider.get_location(self._actor)\n        self._distance += calculate_distance(self._location, new_location)\n        self._location = new_location\n\n        if self._distance > self._target_distance:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass AtRightmostLane(AtomicCondition):\n\n    \"\"\"\n    This class contains an atomic behavior to check if the actor is at the rightest driving lane.\n\n    Important parameters:\n    - actor: CARLA actor to execute the condition\n\n    The condition terminates with SUCCESS, when the actor enters the rightest lane\n    \"\"\"\n\n    def __init__(self, actor, name=\"AtRightmostLane\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(AtRightmostLane, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor\n        self._map = CarlaDataProvider.get_map()\n\n    def update(self):\n        \"\"\"\n        Check actor waypoints\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self._actor)\n        waypoint = self._map.get_waypoint(location)\n        if waypoint is None:\n            return new_status\n        right_waypoint = waypoint.get_right_lane()\n        if right_waypoint is None:\n            return new_status\n        lane_type = right_waypoint.lane_type\n\n        if lane_type != carla.LaneType.Driving:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n        return new_status\n\n\nclass WaitForTrafficLightState(AtomicCondition):\n\n    \"\"\"\n    This class contains an atomic behavior to wait for a given traffic light\n    to have the desired state.\n\n    Args:\n        actor (carla.TrafficLight): CARLA traffic light to execute the condition\n        state (carla.TrafficLightState): State to be checked in this condition\n\n    The condition terminates with SUCCESS, when the traffic light switches to the desired state\n    \"\"\"\n\n    def __init__(self, actor, state, name=\"WaitForTrafficLightState\"):\n        \"\"\"\n        Setup traffic_light\n        \"\"\"\n        super(WaitForTrafficLightState, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._actor = actor if \"traffic_light\" in actor.type_id else None\n        self._state = state\n\n    def update(self):\n        \"\"\"\n        Set status to SUCCESS, when traffic light state matches the expected one\n        \"\"\"\n        if self._actor is None:\n            return py_trees.common.Status.FAILURE\n\n        new_status = py_trees.common.Status.RUNNING\n\n        if self._actor.state == self._state:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass WaitEndIntersection(AtomicCondition):\n\n    \"\"\"\n    Atomic behavior that waits until the vehicles has gone outside the junction.\n    If currently inside no intersection, it will wait until one is found.\n    If 'junction_id' is given, it will wait until that specific junction has finished\n    \"\"\"\n\n    def __init__(self, actor, junction_id=None, debug=False, name=\"WaitEndIntersection\"):\n        super(WaitEndIntersection, self).__init__(name)\n        self.actor = actor\n        self.debug = debug\n        self._junction_id = junction_id\n        self._inside_junction = False\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n    def update(self):\n\n        new_status = py_trees.common.Status.RUNNING\n\n        location = CarlaDataProvider.get_location(self.actor)\n        waypoint = CarlaDataProvider.get_map().get_waypoint(location)\n\n        # Wait for the actor to enter a / the junction\n        if not self._inside_junction:\n            junction = waypoint.get_junction()\n            if not junction:\n                return new_status\n            if not self._junction_id or junction.id == self._junction_id:\n                self._inside_junction = True\n\n        # And to leave it\n        elif self._inside_junction and not waypoint.is_junction:\n            if self.debug:\n                print(\"--- Leaving the junction\")\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass WaitForBlackboardVariable(AtomicCondition):\n\n    \"\"\"\n    Atomic behavior that keeps running until the blackboard variable is set to the corresponding value.\n    Used to avoid returning FAILURE if the blackboard comparison fails.\n\n    It also initially sets the variable to a given value, if given\n    \"\"\"\n\n    def __init__(self, variable_name, variable_value, var_init_value=None,\n                 debug=False, name=\"WaitForBlackboardVariable\"):\n        super(WaitForBlackboardVariable, self).__init__(name)\n        self._debug = debug\n        self._variable_name = variable_name\n        self._variable_value = variable_value\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n\n        if var_init_value is not None:\n            blackboard = py_trees.blackboard.Blackboard()\n            _ = blackboard.set(variable_name, var_init_value)\n\n    def update(self):\n\n        new_status = py_trees.common.Status.RUNNING\n\n        blackv = py_trees.blackboard.Blackboard()\n        value = blackv.get(self._variable_name)\n        if value == self._variable_value:\n            if self._debug:\n                print(\"Blackboard variable {} set to True\".format(self._variable_name))\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n\n\nclass CheckParameter(AtomicCondition):\n    \"\"\"\n    Atomic behavior that keeps checking global osc parameter value with the given value.\n    The condition terminates with SUCCESS, when the comparison_operator is evaluated successfully.\n    \"\"\"\n\n    def __init__(self, parameter_ref, value, comparison_operator, debug=False, name=\"CheckParameter\"):\n        super(CheckParameter, self).__init__(name)\n        self._parameter_ref = parameter_ref\n        self._value = value\n        self._comparison_operator = comparison_operator\n        self._debug = debug\n\n    def update(self):\n        \"\"\"\n        keeps comparing global osc value with given value till it is successful.\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n        current_value = CarlaDataProvider.get_osc_global_param_value(self._parameter_ref)\n        if self._comparison_operator(current_value, self._value):\n            new_status = py_trees.common.Status.SUCCESS\n\n        return new_status\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/timer.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides access to the CARLA game time and contains a py_trees\ntimeout behavior using the CARLA game time\n\"\"\"\n\nimport datetime\nimport operator\nimport py_trees\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass GameTime(object):\n\n    \"\"\"\n    This (static) class provides access to the CARLA game time.\n\n    The elapsed game time can be simply retrieved by calling:\n    GameTime.get_time()\n    \"\"\"\n\n    _current_game_time = 0.0  # Elapsed game time after starting this Timer\n    _carla_time = 0.0\n    _last_frame = 0\n    _platform_timestamp = 0\n    _init = False\n\n    @staticmethod\n    def on_carla_tick(timestamp):\n        \"\"\"\n        Callback receiving the CARLA time\n        Update time only when frame is more recent that last frame\n        \"\"\"\n        if GameTime._last_frame < timestamp.frame:\n            frames = timestamp.frame - GameTime._last_frame if GameTime._init else 1\n            GameTime._current_game_time += timestamp.delta_seconds * frames\n            GameTime._last_frame = timestamp.frame\n            GameTime._platform_timestamp = datetime.datetime.now()\n            GameTime._init = True\n            GameTime._carla_time = timestamp.elapsed_seconds\n\n    @staticmethod\n    def restart():\n        \"\"\"\n        Reset game timer to 0\n        \"\"\"\n        GameTime._current_game_time = 0.0\n        GameTime._carla_time = 0.0\n        GameTime._last_frame = 0\n        GameTime._init = False\n\n    @staticmethod\n    def get_time():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._current_game_time\n\n    @staticmethod\n    def get_carla_time():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._carla_time\n\n    @staticmethod\n    def get_wallclocktime():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._platform_timestamp\n\n    @staticmethod\n    def get_frame():\n        \"\"\"\n        Returns elapsed game time\n        \"\"\"\n        return GameTime._last_frame\n\n\nclass SimulationTimeCondition(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    This class contains an atomic simulation time condition behavior.\n    It uses the CARLA game time, not the system time which is used by\n    the py_trees timer.\n\n    Returns, if the provided rule was successfully evaluated\n    \"\"\"\n\n    def __init__(self, timeout, comparison_operator=operator.gt, name=\"SimulationTimeCondition\"):\n        \"\"\"\n        Setup timeout\n        \"\"\"\n        super(SimulationTimeCondition, self).__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._timeout_value = timeout\n        self._start_time = 0.0\n        self._comparison_operator = comparison_operator\n\n    def initialise(self):\n        \"\"\"\n        Set start_time to current GameTime\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Get current game time, and compare it to the timeout value\n        Upon successfully comparison using the provided comparison_operator,\n        the status changes to SUCCESS\n        \"\"\"\n\n        elapsed_time = GameTime.get_time() - self._start_time\n\n        if not self._comparison_operator(elapsed_time, self._timeout_value):\n            new_status = py_trees.common.Status.RUNNING\n        else:\n            new_status = py_trees.common.Status.SUCCESS\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n\n\nclass TimeOut(SimulationTimeCondition):\n\n    \"\"\"\n    This class contains an atomic timeout behavior.\n    It uses the CARLA game time, not the system time which is used by\n    the py_trees timer.\n    \"\"\"\n\n    def __init__(self, timeout, name=\"TimeOut\"):\n        \"\"\"\n        Setup timeout\n        \"\"\"\n        super(TimeOut, self).__init__(timeout, name=name)\n        self.timeout = False\n\n    def update(self):\n        \"\"\"\n        Upon reaching the timeout value the status changes to SUCCESS\n        \"\"\"\n\n        new_status = super(TimeOut, self).update()\n\n        if new_status == py_trees.common.Status.SUCCESS:\n            self.timeout = True\n\n        return new_status\n\n\nclass RouteTimeoutBehavior(py_trees.behaviour.Behaviour):\n    \"\"\"\n    Behavior responsible of the route's timeout. With an initial value,\n    it increases every time the agent advanced through the route, and is dependent on the road's speed.\n    \"\"\"\n    MIN_TIMEOUT = 300\n    TIMEOUT_ROUTE_PERC = 10\n\n    def __init__(self, ego_vehicle, route, debug=False, name=\"RouteTimeoutBehavior\"):\n        \"\"\"\n        Setup timeout\n        \"\"\"\n        super().__init__(name)\n        self.logger.debug(\"%s.__init__()\" % (self.__class__.__name__))\n        self._ego_vehicle = ego_vehicle\n        self._route = route\n        self._debug = debug\n\n        self._start_time = None\n        self._timeout_value = self.MIN_TIMEOUT\n        self.timeout = False\n\n        # Route variables\n        self._wsize = 3\n        self._current_index = 0\n\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n\n        self._route_accum_meters = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            loc = tran.location\n            d = loc.distance(prev_loc)\n            accum = 0 if i == 0 else self._route_accum_meters[i - 1]\n\n            self._route_accum_meters.append(d + accum)\n            prev_loc = loc\n\n    def initialise(self):\n        \"\"\"\n        Set start_time to current GameTime\n        \"\"\"\n        self._start_time = GameTime.get_time()\n        self.logger.debug(\"%s.initialise()\" % (self.__class__.__name__))\n\n    def update(self):\n        \"\"\"\n        Get current game time, and compare it to the timeout value\n        Upon successfully comparison using the provided comparison_operator,\n        the status changes to SUCCESS\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        ego_location = CarlaDataProvider.get_location(self._ego_vehicle)\n        if ego_location is None:\n            return new_status\n\n        new_index = self._current_index\n\n        for index in range(self._current_index, min(self._current_index + self._wsize + 1, self._route_length)):\n            route_transform = self._route_transforms[index]\n            route_veh_vec = ego_location - route_transform.location\n            if route_veh_vec.dot(route_transform.get_forward_vector()) > 0:\n                new_index = index\n\n        # Update the timeout value\n        if new_index > self._current_index:\n            dist = self._route_accum_meters[new_index] - self._route_accum_meters[self._current_index]\n            max_speed = self._ego_vehicle.get_speed_limit() / 3.6\n            timeout_speed = max_speed * self.TIMEOUT_ROUTE_PERC / 100\n            self._timeout_value += dist / timeout_speed\n            self._current_index = new_index\n\n        elapsed_time = GameTime.get_time() - self._start_time\n        if elapsed_time > self._timeout_value:\n            new_status = py_trees.common.Status.SUCCESS\n            self.timeout = True\n\n        self.logger.debug(\"%s.update()[%s->%s]\" % (self.__class__.__name__, self.status, new_status))\n\n        return new_status\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/traffic_events.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of TrafficEvents\n\"\"\"\n\nfrom enum import Enum\n\n\nclass TrafficEventType(Enum):\n\n    \"\"\"\n    This enum represents different traffic events that occur during driving.\n    \"\"\"\n\n    NORMAL_DRIVING = 0\n    COLLISION_STATIC = 1\n    COLLISION_VEHICLE = 2\n    COLLISION_PEDESTRIAN = 3\n    ROUTE_DEVIATION = 4\n    ROUTE_COMPLETION = 5\n    ROUTE_COMPLETED = 6\n    TRAFFIC_LIGHT_INFRACTION = 7\n    WRONG_WAY_INFRACTION = 8\n    ON_SIDEWALK_INFRACTION = 9\n    STOP_INFRACTION = 10\n    OUTSIDE_LANE_INFRACTION = 11\n    OUTSIDE_ROUTE_LANES_INFRACTION = 12\n    VEHICLE_BLOCKED = 13\n    MIN_SPEED_INFRACTION = 14\n    YIELD_TO_EMERGENCY_VEHICLE = 15\n    SCENARIO_TIMEOUT = 16\n\n\nclass TrafficEvent(object):\n\n    \"\"\"\n    TrafficEvent definition\n    \"\"\"\n\n    def __init__(self, event_type, frame, message=\"\", dictionary=None):\n        \"\"\"\n        Initialize object\n\n        :param event_type: TrafficEventType defining the type of traffic event\n        :param frame: frame in which the event happened \n        :param message: optional message to inform users of the event\n        :param dictionary: optional dictionary with arbitrary keys and values\n        \"\"\"\n        self._type = event_type\n        self._frame = frame\n        self._message = message\n        self._dict = dictionary\n\n    def get_type(self):\n        \"\"\"return the type\"\"\"\n        return self._type\n\n    def get_frame(self):\n        \"\"\"return the frame\"\"\"\n        return self._frame\n\n    def set_frame(self, frame):\n        \"\"\"return the frame\"\"\"\n        self._frame = frame\n\n    def set_message(self, message):\n        \"\"\"Set message\"\"\"\n        self._message = message\n\n    def get_message(self):\n        \"\"\"returns the message\"\"\"\n        return self._message\n\n    def set_dict(self, dictionary):\n        \"\"\"Set dictionary\"\"\"\n        self._dict = dictionary\n\n    def get_dict(self):\n        \"\"\"returns the dictionary\"\"\"\n        return self._dict\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/watchdog.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a simple watchdog timer to detect timeouts\nIt is for example used in the ScenarioManager\n\"\"\"\nfrom __future__ import print_function\n\nimport simple_watchdog_timer as swt\ntry:\n    import thread\nexcept ImportError:\n    import _thread as thread\n\n\nclass Watchdog(object):\n    \"\"\"\n    Simple watchdog timer to detect timeouts\n\n    Args:\n        timeout (float): Timeout value of the watchdog [seconds]. If triggered, raises a KeyboardInterrupt.\n        interval (float): Time between timeout checks [seconds]. Defaults to 1% of the timeout.\n\n    Attributes:\n        _timeout (float): Timeout value of the watchdog [seconds].\n        _interval (float): Time between timeout checks [seconds].\n        _failed (bool): True if watchdog exception occured, false otherwise\n    \"\"\"\n\n    def __init__(self, timeout=1.0, interval=None):\n        \"\"\"Class constructor\"\"\"\n        self._watchdog = None\n        self._timeout = timeout + 1.0\n        self._interval = min(interval if interval is not None else self._timeout / 100, 1.0)\n        self._failed = False\n        self._watchdog_stopped = False\n\n    def start(self):\n        \"\"\"Start the watchdog\"\"\"\n        self._watchdog = swt.WDT(\n            check_interval_sec=self._interval,\n            trigger_delta_sec=self._timeout,\n            callback=self._callback\n        )\n\n    def stop(self):\n        \"\"\"Stop the watchdog\"\"\"\n        if self._watchdog is not None and not self._watchdog_stopped:\n            self.resume()  # If not resumed, the stop will block. Does nothing if already resumed\n            self._watchdog.stop()\n            self._watchdog_stopped = True\n\n    def pause(self):\n        \"\"\"Pause the watchdog\"\"\"\n        if self._watchdog is not None:\n            self._watchdog.pause()\n\n    def resume(self):\n        \"\"\"Resume the watchdog.\"\"\"\n        if self._watchdog is not None:\n            self._watchdog.resume()\n\n    def update(self):\n        \"\"\"Reset the watchdog.\"\"\"\n        if self._watchdog_stopped:\n            return\n\n        if self._watchdog is not None:\n            self._watchdog.update()\n\n    def _callback(self, watchdog):\n        \"\"\"Method called when the timer triggers. Raises a KeyboardInterrupt on\n        the main thread and stops the watchdog.\"\"\"\n        self.pause()  # Good practice to stop it after the event occurs\n        print('Watchdog exception - Timeout of {} seconds occured'.format(self._timeout))\n        self._failed = True\n        thread.interrupt_main()\n\n    def get_status(self):\n        \"\"\"returns False if watchdog exception occured, True otherwise\"\"\"\n        return not self._failed\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenariomanager/weather_sim.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a weather class and py_trees behavior\nto simulate weather in CARLA according to the astronomic\nbehavior of the sun.\n\"\"\"\n\nimport datetime\nimport math\nimport operator\n\nimport ephem\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import GameTime\n\n\nclass Weather(object):\n\n    \"\"\"\n    Class to simulate weather in CARLA according to the astronomic behavior of the sun\n\n    The sun position (azimuth and altitude angles) is obtained by calculating its\n    astronomic position for the CARLA reference position (x=0, y=0, z=0) using the ephem\n    library.\n\n    Args:\n        carla_weather (carla.WeatherParameters): Initial weather settings.\n        dtime (datetime): Initial date and time in UTC (required for animation only).\n            Defaults to None.\n        animation (bool): Flag to allow animating the sun position over time.\n            Defaults to False.\n\n    Attributes:\n        carla_weather (carla.WeatherParameters): Weather parameters for CARLA.\n        animation (bool): Flag to allow animating the sun position over time.\n        _sun (ephem.Sun): The sun as astronomic entity.\n        _observer_location (ephem.Observer): Holds the geographical position (lat/lon/altitude)\n            for which the sun position is obtained.\n        datetime (datetime): Date and time in UTC (required for animation only).\n    \"\"\"\n\n    def __init__(self, carla_weather, dtime=None, animation=False):\n        \"\"\"\n        Class constructor\n        \"\"\"\n        self.carla_weather = carla_weather\n        self.animation = animation\n\n        self._sun = ephem.Sun()  # pylint: disable=no-member\n        self._observer_location = ephem.Observer()\n        geo_location = CarlaDataProvider.get_map().transform_to_geolocation(carla.Location(0, 0, 0))\n        self._observer_location.lon = str(geo_location.longitude)\n        self._observer_location.lat = str(geo_location.latitude)\n\n        # @TODO This requires the time to be in UTC to be accurate\n        self.datetime = dtime\n        if self.datetime:\n            self._observer_location.date = self.datetime\n\n        self.update()\n\n    def update(self, delta_time=0):\n        \"\"\"\n        If the weather animation is true, the new sun position is calculated w.r.t delta_time\n\n        Nothing happens if animation or datetime are None.\n\n        Args:\n            delta_time (float): Time passed since self.datetime [seconds].\n        \"\"\"\n        if not self.animation or not self.datetime:\n            return\n\n        self.datetime = self.datetime + datetime.timedelta(seconds=delta_time)\n        self._observer_location.date = self.datetime\n\n        self._sun.compute(self._observer_location)\n        self.carla_weather.sun_altitude_angle = math.degrees(self._sun.alt)\n        self.carla_weather.sun_azimuth_angle = math.degrees(self._sun.az)\n\n\nclass OSCWeatherBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Atomic to read weather settings from the blackboard and apply these in CARLA.\n    Used in combination with UpdateWeather() to have a continuous weather simulation.\n\n    This behavior is always in a running state and must never terminate.\n    The user must not add this behavior. It is automatically added by the ScenarioManager.\n\n    This atomic also sets the datetime to blackboard variable, used by TimeOfDayComparison atomic\n\n    Args:\n        name (string): Name of the behavior.\n            Defaults to 'WeatherBehavior'.\n\n    Attributes:\n        _weather (srunner.scenariomanager.weather_sim.Weather): Weather settings.\n        _current_time (float): Current CARLA time [seconds].\n    \"\"\"\n\n    def __init__(self, name=\"WeatherBehavior\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super(OSCWeatherBehavior, self).__init__(name)\n        self._weather = None\n        self._current_time = None\n\n    def initialise(self):\n        \"\"\"\n        Set current time to current CARLA time\n        \"\"\"\n        self._current_time = GameTime.get_time()\n\n    def update(self):\n        \"\"\"\n        Check if new weather settings are available on the blackboard, and if yes fetch these\n        into the _weather attribute.\n\n        Apply the weather settings from _weather to CARLA.\n\n        Note:\n            To minimize CARLA server interactions, the weather is only updated, when the blackboard\n            is updated, or if the weather animation flag is true. In the latter case, the update\n            frequency is 1 Hz.\n\n        returns:\n            py_trees.common.Status.RUNNING\n        \"\"\"\n\n        weather = None\n\n        try:\n            check_weather = operator.attrgetter(\"CarlaWeather\")\n            weather = check_weather(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n\n        if weather:\n            self._weather = weather\n            delattr(py_trees.blackboard.Blackboard(), \"CarlaWeather\")\n            CarlaDataProvider.get_world().set_weather(self._weather.carla_weather)\n            py_trees.blackboard.Blackboard().set(\"Datetime\", self._weather.datetime, overwrite=True)\n\n        if self._weather and self._weather.animation:\n            new_time = GameTime.get_time()\n            delta_time = new_time - self._current_time\n\n            if delta_time > 1:\n                self._weather.update(delta_time)\n                self._current_time = new_time\n                CarlaDataProvider.get_world().set_weather(self._weather.carla_weather)\n\n                py_trees.blackboard.Blackboard().set(\"Datetime\", self._weather.datetime, overwrite=True)\n\n        return py_trees.common.Status.RUNNING\n\n\nclass RouteWeatherBehavior(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    Given a set of route weathers ([position, carla.WeatherParameters]),\n    monitors the ego vehicle to dynamically change the weather as the ego advanced through the route.\n\n    This behavior interpolates the desired weather between two weather keypoints and if the extreme cases\n    (0% and 100%) aren't defined, the closest one will be chosen\n    (i.e, if the route weather is at 90%, all weathers from 90% to 100% will be the one defined at 90%)\n\n    Use the debug argument to print what is the route's percentage of each route position.\n    \"\"\"\n\n    def __init__(self, ego_vehicle, route, weathers, debug=False, name=\"RouteWeatherBehavior\"):\n        \"\"\"\n        Setup parameters\n        \"\"\"\n        super().__init__(name)\n        self._world = CarlaDataProvider.get_world()\n        self._ego_vehicle = ego_vehicle\n        self._route = route\n\n        self._weathers = weathers\n        if self._weathers[0][0] != 0:  # Make sure the weather is defined at 0%\n            self._weathers.insert(0, [0, self._weathers[0]])\n        if self._weathers[-1][0] != 100:  # Make sure the weather is defined at 100%\n            self._weathers.append([100, self._weathers[-1]])\n\n        self._wsize = 3\n\n        self._current_index = 0\n        self._route_length = len(self._route)\n        self._route_transforms, _ = zip(*self._route)\n        self._route_perc = self._get_route_percentages()\n        if debug:\n            debug_perc = -1\n            for transform, perc in zip(self._route_transforms, self._route_perc):\n                location = transform.location\n                new_perc = int(perc)\n                if new_perc > debug_perc:\n                    self._world.debug.draw_string(\n                        location + carla.Location(z=1),\n                        str(new_perc),\n                        color=carla.Color(50, 50, 50),\n                        life_time=100000\n                    )\n                    debug_perc = new_perc\n        self._route_weathers = self.get_route_weathers()\n\n    def _get_route_percentages(self):\n        \"\"\"\n        Calculate the accumulated distance percentage at each point in the route\n        \"\"\"\n        accum_m = []\n        prev_loc = self._route_transforms[0].location\n        for i, tran in enumerate(self._route_transforms):\n            new_dist = tran.location.distance(prev_loc)\n            added_dist = 0 if i == 0 else accum_m[i - 1]\n            accum_m.append(new_dist + added_dist)\n            prev_loc = tran.location\n\n        max_dist = accum_m[-1]\n        return [x / max_dist * 100 for x in accum_m]\n\n    def get_route_weathers(self):\n        \"\"\"Calculate the desired weather at each point in the route\"\"\"\n        def interpolate(prev_w, next_w, perc, name):\n            x0 = prev_w[0]\n            x1 = next_w[0]\n            if x0 == x1:\n                raise ValueError(\"Two weather keypoints have the same route percentage\")\n            y0 = getattr(prev_w[1], name)\n            y1 = getattr(next_w[1], name)\n            return y0 + (y1 - y0) * (perc - x0) / (x1 - x0)\n\n        route_weathers = []\n\n        weather_index = 0\n        prev_w = self._weathers[weather_index]\n        next_w = self._weathers[weather_index + 1]\n\n        for perc in self._route_perc:\n            if perc > next_w[0]:  # Must be strictly less, or an IndexError will occur at 100%\n                weather_index += 1\n                prev_w = self._weathers[weather_index]\n                next_w = self._weathers[weather_index + 1]\n\n            weather = carla.WeatherParameters()\n            weather.cloudiness = interpolate(prev_w, next_w, perc, 'cloudiness')\n            weather.precipitation = interpolate(prev_w, next_w, perc, 'precipitation')\n            weather.precipitation_deposits = interpolate(prev_w, next_w, perc, 'precipitation_deposits')\n            weather.wind_intensity = interpolate(prev_w, next_w, perc, 'wind_intensity')\n            weather.sun_azimuth_angle = interpolate(prev_w, next_w, perc, 'sun_azimuth_angle')\n            weather.sun_altitude_angle = interpolate(prev_w, next_w, perc, 'sun_altitude_angle')\n            weather.wetness = interpolate(prev_w, next_w, perc, 'wetness')\n            weather.fog_distance = interpolate(prev_w, next_w, perc, 'fog_distance')\n            weather.fog_density = interpolate(prev_w, next_w, perc, 'fog_density')\n            weather.fog_falloff = interpolate(prev_w, next_w, perc, 'fog_falloff')\n            weather.scattering_intensity = interpolate(prev_w, next_w, perc, 'scattering_intensity')\n            weather.mie_scattering_scale = interpolate(prev_w, next_w, perc, 'mie_scattering_scale')\n            weather.rayleigh_scattering_scale = interpolate(prev_w, next_w, perc, 'rayleigh_scattering_scale')\n\n            route_weathers.append(weather)\n\n        return route_weathers\n\n    def update(self):\n        \"\"\"\n        Check the location of the ego vehicle, updating the weather if it has advanced through the route\n        \"\"\"\n        new_status = py_trees.common.Status.RUNNING\n\n        ego_location = CarlaDataProvider.get_location(self._ego_vehicle)\n        if ego_location is None:\n            return new_status\n\n        new_index = self._current_index\n\n        for index in range(self._current_index, min(self._current_index + self._wsize + 1, self._route_length)):\n            route_transform = self._route_transforms[index]\n            route_veh_vec = ego_location - route_transform.location\n            if route_veh_vec.dot(route_transform.get_forward_vector()) > 0:\n                new_index = index\n\n        if new_index > self._current_index:\n            self._world.set_weather(self._route_weathers[new_index])\n        self._current_index = new_index\n\n        return new_status\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/actor_flow.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, ScenarioTimeout, WaitForever\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               WaitEndIntersection,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import (SwitchRouteSources,\n                                              ChangeOppositeBehavior,\n                                              HandleJunctionScenario,\n                                              RemoveRoadLane)\nfrom srunner.tools.scenario_helper import get_same_dir_lanes, generate_target_waypoint_in_route\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\nclass EnterActorFlow(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle runs a red light\n    in front of the ego, forcing it to react. This vehicles are 'special' ones such as police cars,\n    ambulances or firetrucks.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        ego_location = config.trigger_points[0].location\n        self._reference_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        self._sink_distance = 2\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"EnterActorFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        # Get all lanes\n        source_wps = get_same_dir_lanes(source_wp)\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        for source_wp, sink_wp in zip(source_wps, sink_wps):\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance))\n            root.add_child(ActorFlow(\n                source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n                self._flow_speed, initial_actors=True, initial_junction=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            extra_space = 20\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=source_wps,\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=extra_space\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass EnterActorFlowV2(EnterActorFlow):\n    \"\"\"\n    Variation of EnterActorFlow for special highway entry exits with dedicated lanes\n    \"\"\"\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        # Get all lanes\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n                source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n                self._flow_speed, initial_actors=True, initial_junction=True))\n        for sink_wp in sink_wps:\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        exit_wp = generate_target_waypoint_in_route(self._reference_waypoint, self.config.route)\n        exit_wp = exit_wp.next(10)[0]  # just in case the junction maneuvers don't match\n\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            self._extra_space = 20\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n            sequence_2 = py_trees.composites.Sequence()\n            sequence_2.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n            sequence_2.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=False,\n                remove_entries=[],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=self._extra_space\n            ))\n            sequence_2.add_child(WaitForever())\n            root.add_child(sequence_2)\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=[source_wp],\n                remove_exits= get_same_dir_lanes(exit_wp),\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n\nclass HighwayExit(BasicScenario):\n    \"\"\"\n    This scenario is similar to CrossActorFlow\n    It will remove the BackgroundActivity from the lane where ActorFlow starts.\n    Then vehicles (cars) will start driving from start_actor_flow location to end_actor_flow location\n    in a relatively high speed, forcing the ego to accelerate to cut in the actor flow \n    then exit from the highway.\n    This scenario works when Background Activity is running in route mode. And there should be no junctions in front of the ego.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._sink_distance = 2\n        self._end_distance = 40\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"HighwayExit\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Vehicles run from the start to the end continuously.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        grp = CarlaDataProvider.get_global_route_planner()\n        route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n        junction_id = None\n        for wp, _ in route:\n            if wp.is_junction:\n                junction_id = wp.get_junction().id\n                break\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n            source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n            self._flow_speed, initial_actors=True, initial_junction=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0], junction_id))\n\n        sequence = py_trees.composites.Sequence()\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(source_wp))\n        sequence.add_child(root)\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass MergerIntoSlowTraffic(BasicScenario):\n    \"\"\"\n    This scenario is similar to EnterActorFlow\n    It will remove the BackgroundActivity from the lane where ActorFlow starts.\n    Then vehicles (cars) will start driving from start_actor_flow location to end_actor_flow location\n    in a relatively low speed, ego car must merger into this slow traffic flow.\n    This scenario works when Background Activity is running in route mode. And applies to a confluence\n    area at a highway intersection.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        ego_location = config.trigger_points[0].location\n        self._reference_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n        self._trigger_point=config.trigger_points[0].location\n\n        self._sink_distance = 2\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"MergerIntoSlowTraffic\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        the ego vehicle mergers into a slow traffic flow from the freeway entrance.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        # Get all lanes\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        for wp in sink_wps:\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], wp.transform.location, self._sink_distance))\n        root.add_child(ActorFlow(\n            source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n            self._flow_speed, initial_actors=True, initial_junction=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            extra_space = 0\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[source_wp],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=extra_space + 20\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass MergerIntoSlowTrafficV2(MergerIntoSlowTraffic):\n    \"\"\"\n    Variation of MergerIntoSlowTraffic \n    \"\"\"\n\n    def _create_behavior(self):\n        \"\"\"\n        the ego vehicle mergers into a slow traffic flow from the freeway entrance.\n        \"\"\"\n        source_wp = self._map.get_waypoint(self._start_actor_flow)\n        sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        sink_wps = get_same_dir_lanes(sink_wp)\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n            source_wp, sink_wp, self._source_dist_interval, self._sink_distance,\n            self._flow_speed, initial_actors=True, initial_junction=True))\n        for sink_wp in sink_wps:\n            root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        exit_wp = generate_target_waypoint_in_route(self._reference_waypoint, self.config.route)\n        exit_wp = exit_wp.next(10)[0]  # just in case the junction maneuvers don't match\n\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location)\n            self._extra_space = 20\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    break\n\n        sequence_2 = py_trees.composites.Sequence()\n        sequence_2.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        sequence_2.add_child(HandleJunctionScenario(\n            clear_junction=False,\n            clear_ego_entry=False,\n            remove_entries=[],\n            remove_exits=[],\n            stop_entries=False,\n            extend_road_exit=self._extra_space\n        ))\n        sequence_2.add_child(WaitForever())\n        root.add_child(sequence_2)\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=[source_wp],\n                remove_exits=get_same_dir_lanes(exit_wp),\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n\n        return sequence\n\n\nclass InterurbanActorFlow(BasicScenario):\n    \"\"\"\n    Scenario specifically made for the interurban intersections,\n    where the ego leaves the interurban road by turning left, crossing an actor flow.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._sink_distance = 2\n        self._end_distance = 40\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        self._reference_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        route_entry_wp, route_exit_wp = self._get_entry_exit_route_lanes(self._reference_wp, config.route)\n        route_exit_wp = route_exit_wp.next(8)[0]  # Just in case the junction maneuvers don't match\n        other_entry_wp = route_exit_wp.get_left_lane()\n        if not other_entry_wp or other_entry_wp.lane_type != carla.LaneType.Driving:\n            raise ValueError(\"Couldn't find an end position\")\n\n        self._source_wp = self._map.get_waypoint(self._start_actor_flow)\n        self._sink_wp = self._map.get_waypoint(self._end_actor_flow)\n\n        self._remove_entries = [route_entry_wp, other_entry_wp, self._source_wp]\n\n        super().__init__(\"InterurbanActorFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _get_entry_exit_route_lanes(self, wp, route):\n\n        entry_wp = None\n        exit_wp = None\n\n        # Get the middle entry\n        dist = float('inf')\n        index = 0\n        for route_index, route_pos in enumerate(route):\n            route_location = route_pos[0].location\n            trigger_location = wp.transform.location\n\n            route_dist = trigger_location.distance(route_location)\n            if route_dist <= dist:\n                index = route_index\n                dist = route_dist\n\n        reached_junction = False\n        for i in range(index, len(route)):\n            route_transform, road_option = route[i]\n\n            # Enter the junction\n            if not reached_junction and (road_option in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n                reached_junction = True\n                entry_wp = self._map.get_waypoint(route[i-1][0].location)\n                entry_wp = entry_wp.previous(2)[0]  # Just in case\n\n            # End condition for the behavior, at the end of the junction\n            if reached_junction and (road_option not in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n                exit_wp = self._map.get_waypoint(route_transform.location)\n                exit_wp = exit_wp.next(2)[0]  # Just in case\n                break\n\n        return (entry_wp, exit_wp)\n\n\n    def _create_behavior(self):\n        \"\"\"\n        Create an actor flow at the opposite lane which the ego has to cross\n        \"\"\"\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, self._sink_distance, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        sequence = py_trees.composites.Sequence()\n\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=self._remove_entries,\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n        sequence.add_child(root)\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass InterurbanAdvancedActorFlow(BasicScenario):\n    \"\"\"\n    Scenario specifically made for the interurban intersections,\n    where the ego incorportates into the interurban road by turning left,\n    first crossing an actor flow, and then merging into another one.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._sink_distance = 2\n\n        self._reference_wp = self._map.get_waypoint(config.trigger_points[0].location)\n        self._exit_wp = generate_target_waypoint_in_route(self._reference_wp, config.route)\n\n        self._start_actor_flow_1 = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_actor_flow_1 = convert_dict_to_location(config.other_parameters['end_actor_flow'])\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n        self._scenario_timeout = 240\n\n        super().__init__(\"InterurbanAdvancedActorFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def get_lane_key(self, waypoint):\n        return str(waypoint.road_id) + '*' + str(waypoint.lane_id)\n\n    def _get_junction_entry_wp(self, entry_wp):\n        while entry_wp.is_junction:\n            entry_wps = entry_wp.previous(0.2)\n            if len(entry_wps) == 0:\n                return None  # Stop when there's no prev\n            entry_wp = entry_wps[0]\n        return entry_wp\n\n    def _get_junction_exit_wp(self, exit_wp):\n        while exit_wp.is_junction:\n            exit_wps = exit_wp.next(0.2)\n            if len(exit_wps) == 0:\n                return None  # Stop when there's no prev\n            exit_wp = exit_wps[0]\n        return exit_wp\n\n    def _initialize_actors(self, config):\n        \n        self._source_wp_1 = self._map.get_waypoint(self._start_actor_flow_1)\n        self._sink_wp_1 = self._map.get_waypoint(self._end_actor_flow_1)\n\n        self._source_wp_2 = self._sink_wp_1.get_left_lane()\n        if not self._source_wp_2 or self._source_wp_2.lane_type != carla.LaneType.Driving:\n            raise ValueError(\"Couldn't find a position for the actor flow\")\n        self._sink_wp_2 = self._source_wp_1.get_left_lane()\n        if not self._sink_wp_2 or self._sink_wp_2.lane_type != carla.LaneType.Driving:\n            raise ValueError(\"Couldn't find a position for the actor flow\")\n\n        if self.route_mode:\n            grp = CarlaDataProvider.get_global_route_planner()\n            route = grp.trace_route(self._source_wp_2.transform.location, self._sink_wp_2.transform.location)\n            self._extra_space = 20\n            route_exit_wp = None\n            for i in range(-2, -len(route)-1, -1):\n                current_wp = route[i][0]\n                self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location)\n                if current_wp.is_junction:\n                    junction = current_wp.get_junction()\n                    break\n                route_exit_wp = current_wp\n\n            route_exit_key = self.get_lane_key(route_exit_wp)\n\n            # Get the route entry waypoint\n            route_entry_wp = self._reference_wp\n            while True:\n                next_wps = route_entry_wp.next(1)\n                if not next_wps:\n                    break\n                if next_wps[0].is_junction:\n                    break\n                route_entry_wp = next_wps[0]\n            route_entry_key = self.get_lane_key(route_entry_wp)\n\n        entry_wps = []\n        entry_keys = []\n        exit_wps = []\n        exit_keys = []\n\n        for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n\n            entry_wp = self._get_junction_entry_wp(entry_wp)\n            entry_key = self.get_lane_key(entry_wp)\n            if entry_key != route_entry_key and entry_key not in entry_keys:\n                entry_wps.append(entry_wp)\n                entry_keys.append(entry_key)\n\n            exit_wp = self._get_junction_exit_wp(exit_wp)\n            exit_key = self.get_lane_key(exit_wp)\n            if exit_key != route_exit_key and exit_key not in exit_keys:\n                exit_wps.append(exit_wp)\n                exit_keys.append(exit_key)\n\n        self._remove_entries = entry_wps\n        self._remove_exits = exit_wps\n\n    def _create_behavior(self):\n        \"\"\"\n        the ego vehicle mergers into a slow traffic flow from the freeway entrance.\n        \"\"\"\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._sink_wp_2.transform))\n        root.add_child(ActorFlow(\n            self._source_wp_1, self._sink_wp_1, self._source_dist_interval, self._sink_distance, self._flow_speed))\n        root.add_child(ActorFlow(\n            self._source_wp_2, self._sink_wp_2, self._source_dist_interval, self._sink_distance, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence = py_trees.composites.Sequence()\n        if self.route_mode:\n\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=self._remove_entries,\n                remove_exits=self._remove_exits,\n                stop_entries=False,\n                extend_road_exit=self._extra_space\n            ))\n            sequence.add_child(SwitchRouteSources(False))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(SwitchRouteSources(True))\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/background_activity.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario spawning elements to make the town dynamic and interesting\n\"\"\"\n\nfrom collections import OrderedDict\nimport py_trees\n\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import AtomicBehavior\nfrom srunner.tools.scenario_helper import get_same_dir_lanes, get_opposite_dir_lanes\n\nJUNCTION_ENTRY = 'entry'\nJUNCTION_MIDDLE = 'middle'\nJUNCTION_EXIT = 'exit'\nJUNCTION_EXIT_ROAD = 'exit_road'\nJUNCTION_EXIT_INACTIVE = 'exit_inactive'\n\nEGO_JUNCTION = 'junction'\nEGO_ROAD = 'road'\n\ndef get_lane_key(waypoint):\n    \"\"\"Returns a key corresponding to the waypoint lane. Equivalent to a 'Lane'\n    object and used to compare waypoint lanes\"\"\"\n    return '' if waypoint is None else get_road_key(waypoint) + '*' + str(waypoint.lane_id)\n\ndef get_road_key(waypoint):\n    \"\"\"Returns a key corresponding to the waypoint road. Equivalent to a 'Road'\n    object and used to compare waypoint roads\"\"\"\n    return '' if waypoint is None else str(waypoint.road_id)\n\ndef is_lane_at_road(lane_key, road_key):\n    \"\"\"Returns whether or not a lane is part of a road\"\"\"\n    return lane_key.startswith(road_key)\n\ndef get_lane_key_from_ids(road_id, lane_id):\n    \"\"\"Returns the lane corresping to a given road and lane ids\"\"\"\n    return str(road_id) + '*' + str(lane_id)\n\n\n# Debug variables\nDEBUG_ROAD = 'road'\nDEBUG_OPPOSITE = 'opposite'\nDEBUG_JUNCTION = 'junction'\nDEBUG_ENTRY = 'entry'\nDEBUG_EXIT = 'exit'\nDEBUG_CONNECT = 'connect'\n\nDEBUG_SMALL = 'small'\nDEBUG_MEDIUM = 'medium'\nDEBUG_LARGE = 'large'\n\nDEBUG_COLORS = {\n    DEBUG_ROAD: carla.Color(0, 0, 255),      # Blue\n    DEBUG_OPPOSITE: carla.Color(255, 0, 0),  # Red\n    DEBUG_JUNCTION: carla.Color(0, 0, 0),    # Black\n    DEBUG_ENTRY: carla.Color(255, 255, 0),   # Yellow\n    DEBUG_EXIT: carla.Color(0, 255, 255),    # Teal\n    DEBUG_CONNECT: carla.Color(0, 255, 0),   # Green\n}\n\nDEBUG_TYPE = {\n    DEBUG_SMALL: [0.8, 0.1],\n    DEBUG_MEDIUM: [0.5, 0.15],\n    DEBUG_LARGE: [0.2, 0.2],\n}  # Size, height\n\ndef draw_string(world, location, string='', debug_type=DEBUG_ROAD, persistent=False):\n    \"\"\"Utility function to draw debugging strings\"\"\"\n    v_shift, _ = DEBUG_TYPE.get(DEBUG_SMALL)\n    l_shift = carla.Location(z=v_shift)\n    color = DEBUG_COLORS.get(debug_type, DEBUG_ROAD)\n    life_time = 0.06 if not persistent else 100000\n    world.debug.draw_string(location + l_shift, string, False, color, life_time)\n\ndef draw_point(world, location, point_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, persistent=False):\n    \"\"\"Utility function to draw debugging points\"\"\"\n    v_shift, size = DEBUG_TYPE.get(point_type, DEBUG_SMALL)\n    l_shift = carla.Location(z=v_shift)\n    color = DEBUG_COLORS.get(debug_type, DEBUG_ROAD)\n    life_time = 0.06 if not persistent else 100000\n    world.debug.draw_point(location + l_shift, size, color, life_time)\n\ndef draw_arrow(world, location1, location2, arrow_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, persistent=False):\n    \"\"\"Utility function to draw debugging points\"\"\"\n    if location1 == location2:\n        draw_point(world, location1, arrow_type, debug_type, persistent)\n    v_shift, thickness = DEBUG_TYPE.get(arrow_type, DEBUG_SMALL)\n    l_shift = carla.Location(z=v_shift)\n    color = DEBUG_COLORS.get(debug_type, DEBUG_ROAD)\n    life_time = 0.06 if not persistent else 100000\n    world.debug.draw_arrow(location1 + l_shift, location2 + l_shift, thickness, thickness, color, life_time)\n\n\nclass Source(object):\n\n    \"\"\"\n    Source object to store its position and its responsible actors\n    \"\"\"\n\n    def __init__(self, wp, actors, entry_lane_wp='', active=True):  # pylint: disable=invalid-name\n        self.wp = wp  # pylint: disable=invalid-name\n        self.actors = actors\n        self.active = active\n\n        # For junction sources\n        self.entry_lane_wp = entry_lane_wp\n        self.previous_lane_keys = []  # Source lane and connecting lanes of the previous junction\n\n\nclass Junction(object):\n\n    \"\"\"\n    Junction object. Stores its topology as well as its state, when active\n    \"\"\"\n\n    def __init__(self, junction, junction_id, route_entry_index=None, route_exit_index=None):\n        # Topology\n        self.junctions = [junction]\n        self.id = junction_id  # pylint: disable=invalid-name\n        self.route_entry_index = route_entry_index\n        self.route_exit_index = route_exit_index\n        self.entry_lane_keys = []\n        self.exit_lane_keys = []\n        self.route_entry_keys = []\n        self.route_exit_keys = []\n        self.opposite_entry_keys = []\n        self.opposite_exit_keys = []\n        self.entry_wps = []\n        self.exit_wps = []\n        self.entry_directions = {'ref': [], 'opposite': [], 'left': [], 'right': []}\n        self.exit_directions = {'ref': [], 'opposite': [], 'left': [], 'right': []}\n\n        # State\n        self.entry_sources = []\n        self.exit_dict = OrderedDict()\n        self.actor_dict = OrderedDict()\n\n        # Junction scenario variables \n        self.stop_non_route_entries = False\n        self.clear_middle = False\n        self.inactive_entry_keys = []\n        self.inactive_exit_keys = []\n\n    def contains_wp(self, wp):\n        \"\"\"Checks whether or not a carla.Waypoint is inside the junction\"\"\"\n        if not wp.is_junction:\n            return False\n        other_id = wp.get_junction().id\n        for junction in self.junctions:\n            if other_id == junction.id:\n                return True\n        return False\n\n\nclass BackgroundBehavior(AtomicBehavior):\n    \"\"\"\n    Handles the background activity\n    \"\"\"\n\n    def __init__(self, ego_actor, route, debug=False, name=\"BackgroundBehavior\"):\n        \"\"\"\n        Setup class members\n        \"\"\"\n        super(BackgroundBehavior, self).__init__(name)\n        self.debug = debug\n        self._map = CarlaDataProvider.get_map()\n        self._world = CarlaDataProvider.get_world()\n        self._tm_port = CarlaDataProvider.get_traffic_manager_port()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(self._tm_port)\n        self._tm.global_percentage_speed_difference(0.0)\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._attribute_filter = {'base_type': 'car', 'special_type': '', 'has_lights': True, }\n\n        # Global variables\n        self._ego_actor = ego_actor\n        self._ego_state = EGO_ROAD\n        self._ego_wp = None\n        self._ego_key = \"\"\n        self._route_index = 0\n        self._get_route_data(route)\n        self._actors_speed_perc = {}  # Dictionary actor - percentage\n        self._all_actors = []\n        self._lane_width_threshold = 2.25  # Used to stop some behaviors at narrow lanes to avoid problems [m]\n\n        self._spawn_vertical_shift = 0.2\n        self._reuse_dist = 10  # When spawning actors, might reuse actors closer to this distance\n        self._spawn_free_radius = 20  # Sources closer to the ego will not spawn actors\n        self._fake_junction_ids = []\n        self._fake_lane_pair_keys = []\n\n        # Initialisation values\n        self._vehicle_lane_change = False\n        self._vehicle_lights = True\n        self._vehicle_leading_distance = 10\n        self._vehicle_offset = 0.1\n\n        # Road variables\n        self._road_dict = {}  # Dictionary lane key -> actor source\n        self._road_checker_index = 0\n\n        self._road_front_vehicles = 2  # Amount of vehicles in front of the ego\n        self._road_back_vehicles = 2  # Amount of vehicles behind the ego\n        self._radius_increase_ratio = 1.7  # Meters the radius increases per m/s of the ego\n\n        self._base_junction_detection = 30\n        self._detection_ratio = 1.5  # Meters the radius increases per m/s of the ego\n\n        self._road_extra_front_actors = 0  # For cases where we want more space but not more vehicles\n        self._road_spawn_dist = 15  # Distance between spawned vehicles [m]\n        self._road_extra_space = 0  # Extra space for the road vehicles\n\n        self._active_road_sources = True\n\n        self._base_min_radius = 0\n        self._base_max_radius = 0\n        self._min_radius = 0\n        self._max_radius = 0\n        self._detection_dist = 0\n        self._get_road_radius()\n\n        # Junction variables\n        self._junctions = []  # List with all the junctions part of the route, in order of appearance\n        self._active_junctions = []  # List of all the active junctions\n\n        self._junction_sources_dist = 40  # Distance from the entry sources to the junction [m]\n        self._junction_sources_max_actors = 6  # Maximum vehicles alive at the same time per source\n        self._junction_spawn_dist = 15  # Distance between spawned vehicles [m]\n        self._junction_minimum_source_dist = 15  # Minimum distance between sources and their junction\n\n        self._junction_source_perc = 80  # Probability [%] of the source being created\n\n        # Opposite lane variables\n        self._opposite_actors = []\n        self._opposite_sources = []\n        self._opposite_route_index = 0\n\n        self._opposite_spawn_dist = 40  # Distance between spawned vehicles [m]\n        self._opposite_sources_dist = 80  # Distance from the ego to the opposite sources [m]. Twice the spawn distance\n\n        self._active_opposite_sources = True  # Flag to (de)activate all opposite sources\n\n        # Scenario variables:\n        self._scenario_stopped_actors = []  # Actors stopped by a hard break scenario\n        self._scenario_stopped_back_actors = []  # Actors stopped by a open doors scenario\n        self._scenario_max_speed = 0  # Max speed of the Background Activity. Deactivated with a value of 0\n        self._scenario_junction_entry = False  # Flag indicating the ego is entering a junction\n        self._scenario_junction_entry_distance = self._road_spawn_dist  # Min distance between vehicles and ego\n        self._scenario_removed_lane = False  # Flag indicating a scenario has removed a lane\n        self._scenario_remove_lane_offset = 0\n\n    def _get_route_data(self, route):\n        \"\"\"Extract the information from the route\"\"\"\n        self._route = []  # Transform the route into a list of waypoints\n        self._route_options = []  # Extract the RoadOptions from the route\n        self._accum_dist = []  # Save the total traveled distance for each waypoint\n        prev_trans = None\n        for trans, option in route:\n            self._route.append(self._map.get_waypoint(trans.location))\n            self._route_options.append(option)\n            if prev_trans:\n                dist = trans.location.distance(prev_trans.location)\n                self._accum_dist.append(dist + self._accum_dist[-1])\n            else:\n                self._accum_dist.append(0)\n            prev_trans = trans\n\n        self._route_length = len(route)\n        self._route_index = 0\n        self._route_buffer = 3\n\n    def _get_road_radius(self):\n        \"\"\"\n        Computes the min and max radius of the road behaviorm which will determine the speed of the vehicles.\n        Vehicles closer than the min radius maintain full speed, while those further than max radius are\n        stopped. Between the two, the velocity decreases linearly\"\"\"\n        self._base_min_radius = (self._road_front_vehicles + self._road_extra_front_actors) * self._road_spawn_dist\n        self._base_max_radius = (self._road_front_vehicles + self._road_extra_front_actors + 1) * self._road_spawn_dist\n        self._min_radius = self._base_min_radius + self._road_extra_space\n        self._max_radius = self._base_max_radius + self._road_extra_space\n\n    def initialise(self):\n        \"\"\"Creates the background activity actors. Pressuposes that the ego is at a road\"\"\"\n        self._create_junction_dict()\n        ego_wp = self._route[0]\n        same_dir_wps = get_same_dir_lanes(ego_wp)\n\n        self._initialise_road_behavior(same_dir_wps)\n        self._initialise_opposite_sources()\n        self._initialise_road_checker()\n\n    def update(self):\n        prev_ego_index = self._route_index\n\n        # Check if the TM destroyed an actor\n        if self._route_index > 0: # TODO: This check is due to intialization problem\n            self._check_background_actors()\n\n        # Update ego's route position. For robustness, the route point is used for most calculus\n        self._update_ego_data()\n\n        # Parameters and scenarios\n        self._update_parameters()\n\n        # Update ego state\n        if self._ego_state == EGO_JUNCTION:\n            self._monitor_ego_junction_exit()\n        self._monitor_incoming_junctions()\n\n        # Update_actors\n        if self._ego_state == EGO_JUNCTION:\n            self._update_junction_actors()\n            self._update_junction_sources()\n        else:\n            self._update_road_actors()\n\n            self._move_road_sources(prev_ego_index)\n            self._update_road_sources()\n\n            self._monitor_topology_changes(prev_ego_index)\n            self._monitor_road_changes(prev_ego_index)\n\n            self._move_opposite_sources(prev_ego_index)\n            self._update_opposite_sources()\n\n        # Update non junction sources\n        self._update_opposite_actors()\n\n        # Update the speed of all vehicles\n        self._set_actors_speed()\n\n        return py_trees.common.Status.RUNNING\n\n    def terminate(self, new_status):\n        \"\"\"Destroy all actors\"\"\"\n        all_actors = list(self._actors_speed_perc)\n        for actor in list(all_actors):\n            self._destroy_actor(actor)\n        super(BackgroundBehavior, self).terminate(new_status)\n\n    def _check_background_actors(self):\n        \"\"\"Checks if the Traffic Manager has removed a backgroudn actor\"\"\"\n        alive_ids = [actor.id for actor in CarlaDataProvider.get_all_actors().filter('vehicle*')]\n        for actor in list(self._all_actors):\n            if actor.id not in alive_ids:\n                self._remove_actor_info(actor)\n\n    ################################\n    ##       Junction cache       ##\n    ################################\n\n    def _create_junction_dict(self):\n        \"\"\"Extracts the junctions the ego vehicle will pass through.\"\"\"\n        data = self._get_junctions_data()\n        fake_data, filtered_data = self._filter_fake_junctions(data)\n        self._get_fake_lane_pairs(fake_data)\n        route_data = self._join_complex_junctions(filtered_data)\n        self._add_junctions_topology(route_data)\n        self._junctions = route_data\n\n    def _get_junctions_data(self):\n        \"\"\"Gets all the junctions the ego passes through\"\"\"\n        junction_data = []\n        junction_num = 0\n        start_index = 0\n\n        # Ignore the junction the ego spawns at\n        for i in range(0, self._route_length - 1):\n            if not self._is_junction(self._route[i]):\n                start_index = i\n                break\n\n        for i in range(start_index, self._route_length - 1):\n            next_wp = self._route[i+1]\n            prev_junction = junction_data[-1] if len(junction_data) > 0 else None\n\n            # Searching for the junction exit\n            if prev_junction and prev_junction.route_exit_index is None:\n                if not self._is_junction(next_wp) or next_wp.get_junction().id != junction_id:\n                    prev_junction.route_exit_index = i+1\n\n            # Searching for a junction\n            elif self._is_junction(next_wp):\n                junction_id = next_wp.get_junction().id\n                if prev_junction:\n                    start_dist = self._accum_dist[i]\n                    prev_end_dist = self._accum_dist[prev_junction.route_exit_index]\n\n                # Same junction as the prev one and closer than 2 meters\n                if prev_junction and prev_junction.junctions[-1].id == junction_id:\n                    start_dist = self._accum_dist[i]\n                    prev_end_dist = self._accum_dist[prev_junction.route_exit_index]\n                    distance = start_dist - prev_end_dist\n                    if distance < 2:\n                        prev_junction.junctions.append(next_wp.get_junction())\n                        prev_junction.route_exit_index = None\n                        continue\n\n                junction_data.append(Junction(next_wp.get_junction(), junction_num, i))\n                junction_num += 1\n\n        return junction_data\n\n    def _filter_fake_junctions(self, data):\n        \"\"\"\n        Filters fake junctions. A fake junction is that which has no intersecting maneuvers\n        (i.e, no two maneuvers start / end at the same lane).\n        However, this fails for highway entry / exits with dedicated lanes, so specifically check those\n        \"\"\"\n        fake_data = []\n        filtered_data = []\n\n        for junction_data in data:\n            if len (junction_data.junctions) > 1:\n                filtered_data.append(junction_data)\n                continue  # These are always junctions\n\n            junction = junction_data.junctions[0]\n\n            found_intersecting_maneuvers = False\n            used_entries = []\n            used_exits = []\n\n            # Search for intersecting maneuvers\n            for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n                entry_key = get_lane_key(self._get_junction_entry_wp(entry_wp))\n                exit_key = get_lane_key(self._get_junction_exit_wp(exit_wp))\n\n                # Check if a maneuver starts / ends at another one.\n                # Checking if it was used isn't enough as some maneuvers are repeated in CARLA maps.\n                # Instead, check if the index of both entry and exit are different.\n                entry_index = -1 if entry_key not in used_entries else used_entries.index(entry_key)\n                exit_index = -1 if exit_key not in used_exits else used_exits.index(exit_key)\n\n                if exit_index != entry_index:\n                    found_intersecting_maneuvers = True\n                    break\n\n                used_entries.append(entry_key)\n                used_exits.append(exit_key)\n\n            if found_intersecting_maneuvers:\n                filtered_data.append(junction_data)\n                continue\n\n            # Search for highway dedicated lane entries.\n            found_highway = False\n            used_entry_roads = {}\n            used_exit_roads = {}\n            for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n                entry_road_key = get_road_key(self._get_junction_entry_wp(entry_wp))\n                exit_road_key = get_road_key(self._get_junction_exit_wp(exit_wp))\n\n                # Entries / exits with dedicated lanes have no intersecting maneuvers\n                # (as the entry / exit is a lane that finishes, not a maneuvers part of a junction),\n                # so they are missfiltered as fake junctions.\n                # Detect them by an entry road having 3 or more lanes. TODO: Improve this\n                if entry_road_key in used_entry_roads:\n                    used_entry_roads[entry_road_key] += 1\n                else:\n                    used_entry_roads[entry_road_key] = 0\n\n                if exit_road_key in used_exit_roads:\n                    used_exit_roads[exit_road_key] += 1\n                else:\n                    used_exit_roads[exit_road_key] = 0\n\n                if used_entry_roads[entry_road_key] >= 3 or used_exit_roads[exit_road_key] >= 3:\n                    found_highway = True\n                    break\n\n            if found_highway:\n                filtered_data.append(junction_data)\n                continue\n\n            fake_data.append(junction_data)\n\n            # TODO: Recheck for old CARLA maps\n\n        return fake_data, filtered_data\n\n    def _get_complex_junctions(self):\n        \"\"\"\n        Function to hardcode the topology of some complex junctions. This is done for the roundabouts,\n        as the current API doesn't offer that info as well as others such as the gas station at Town04.\n        If there are micro lanes between connected junctions, add them to the fake_lane_keys, connecting\n        them when their topology is calculated\n        \"\"\"\n        complex_junctions = []\n        fake_lane_keys = []\n\n        if 'Town03' in self._map.name:\n            # Roundabout, take it all as one\n            complex_junctions.append([\n                self._map.get_waypoint_xodr(1100, -5, 16.6).get_junction(),\n                self._map.get_waypoint_xodr(1624, -5, 25.3).get_junction(),\n                self._map.get_waypoint_xodr(1655, -5, 8.3).get_junction(),\n                self._map.get_waypoint_xodr(1772, 3, 16.2).get_junction(),\n                self._map.get_waypoint_xodr(1206, -5, 5.9).get_junction()])\n            fake_lane_keys.extend([\n                ['37*-4', '36*-4'], ['36*-4', '37*-4'],\n                ['37*-5', '36*-5'], ['36*-5', '37*-5'],\n                ['38*-4', '12*-4'], ['12*-4', '38*-4'],\n                ['38*-5', '12*-5'], ['12*-5', '38*-5']])\n\n            # Gas station\n            complex_junctions.append([\n                self._map.get_waypoint_xodr(1031, -1, 11.3).get_junction(),\n                self._map.get_waypoint_xodr(100, -1, 18.8).get_junction(),\n                self._map.get_waypoint_xodr(1959, -1, 22.7).get_junction()])\n            fake_lane_keys.extend([\n                ['32*-2', '33*-2'], ['33*-2', '32*-2'],\n                ['32*-1', '33*-1'], ['33*-1', '32*-1'],\n                ['32*4', '33*4'], ['33*4', '32*4'],\n                ['32*5', '33*5'], ['33*5', '32*5']])\n\n        elif 'Town04' in self._map.name:\n            # Gas station\n            complex_junctions.append([\n                self._map.get_waypoint_xodr(518, -1, 8.1).get_junction(),\n                self._map.get_waypoint_xodr(886, 1, 10.11).get_junction(),\n                self._map.get_waypoint_xodr(467, 1, 25.8).get_junction()])\n\n        self._fake_lane_pair_keys.extend(fake_lane_keys)\n        return complex_junctions\n\n    def _join_complex_junctions(self, filtered_data):\n        \"\"\"\n        Joins complex junctions into one. This makes it such that all the junctions,\n        as well as their connecting lanes, are treated as the same junction\n        \"\"\"\n        route_data = []\n        prev_index = -1\n\n        # If entering a complex, add all its junctions to the list\n        for junction_data in filtered_data:\n            junction = junction_data.junctions[0]\n            prev_junction = route_data[-1] if len(route_data) > 0 else None\n            complex_junctions = self._get_complex_junctions()\n\n            # Get the complex index\n            current_index = -1\n            for i, complex_junctions in enumerate(complex_junctions):\n                complex_ids = [j.id for j in complex_junctions]\n                if junction.id in complex_ids:\n                    current_index = i\n                    break\n\n            if current_index == -1:\n                # Outside a complex, add it\n                route_data.append(junction_data)\n\n            elif current_index == prev_index:\n                # Same complex as the previous junction\n                prev_junction.route_exit_index = junction_data.route_exit_index\n\n            else:\n                # New complex, add it\n                junction_ids = [j.id for j in junction_data.junctions]\n                for complex_junction in complex_junctions:\n                    if complex_junction.id not in junction_ids:\n                        junction_data.junctions.append(complex_junction)\n\n                route_data.append(junction_data)\n\n            prev_index = current_index\n\n        return route_data\n\n    def _get_fake_lane_pairs(self, fake_data):\n        \"\"\"Gets a list of entry-exit lanes of the fake junctions\"\"\"\n        for fake_junctions_data in fake_data:\n            for junction in fake_junctions_data.junctions:\n                for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n                    while self._is_junction(entry_wp):\n                        entry_wps = entry_wp.previous(0.5)\n                        if len(entry_wps) == 0:\n                            break  # Stop when there's no prev\n                        entry_wp = entry_wps[0]\n                    if self._is_junction(entry_wp):\n                        continue  # Triggered by the loops break\n\n                    while self._is_junction(exit_wp):\n                        exit_wps = exit_wp.next(0.5)\n                        if len(exit_wps) == 0:\n                            break  # Stop when there's no prev\n                        exit_wp = exit_wps[0]\n                    if self._is_junction(exit_wp):\n                        continue  # Triggered by the loops break\n\n                    self._fake_junction_ids.append(junction.id)\n                    self._fake_lane_pair_keys.append([get_lane_key(entry_wp), get_lane_key(exit_wp)])\n\n    def _get_junction_entry_wp(self, entry_wp):\n        \"\"\"For a junction waypoint, returns a waypoint outside of it that entrys into its lane\"\"\"\n        # Exit the junction\n        while self._is_junction(entry_wp):\n            entry_wps = entry_wp.previous(0.2)\n            if len(entry_wps) == 0:\n                return None  # Stop when there's no prev\n            entry_wp = entry_wps[0]\n        return entry_wp\n\n    def _get_junction_exit_wp(self, exit_wp):\n        \"\"\"For a junction waypoint, returns a waypoint outside of it from which the lane exits the junction\"\"\"\n        while self._is_junction(exit_wp):\n            exit_wps = exit_wp.next(0.2)\n            if len(exit_wps) == 0:\n                return None  # Stop when there's no prev\n            exit_wp = exit_wps[0]\n        return exit_wp\n\n    def _get_closest_junction_waypoint(self, waypoint, junction_wps):\n        \"\"\"\n        Matches a given wp to another one inside the list.\n        This is first done by checking its key, and if this fails, the closest wp is chosen\n        \"\"\"\n        # Check the lane keys\n        junction_keys = [get_lane_key(waypoint_) for waypoint_ in junction_wps]\n        if get_lane_key(waypoint) in junction_keys:\n            return waypoint\n\n        # Get the closest one\n        closest_dist = float('inf')\n        closest_junction_wp = None\n        route_location = waypoint.transform.location\n        for junction_wp in junction_wps:\n            distance = junction_wp.transform.location.distance(route_location)\n            if distance < closest_dist:\n                closest_dist = distance\n                closest_junction_wp = junction_wp\n\n        return closest_junction_wp\n\n    def _is_route_wp_behind_junction_wp(self, route_wp, junction_wp):\n        \"\"\"Checks if an actor is behind the ego. Uses the route transform\"\"\"\n        route_location = route_wp.transform.location\n        junction_transform = junction_wp.transform\n        junction_heading = junction_transform.get_forward_vector()\n        wps_vec = route_location - junction_transform.location\n        if junction_heading.x * wps_vec.x + junction_heading.y * wps_vec.y < - 0.09:  # 85º\n            return True\n        return False\n\n    def _add_junctions_topology(self, route_data):\n        \"\"\"Gets the entering and exiting lanes of a multijunction\"\"\"\n        for junction_data in route_data:\n            used_entry_lanes = []\n            used_exit_lanes = []\n            entry_lane_wps = []\n            exit_lane_wps = []\n\n            if self.debug:\n                print(' --------------------- ')\n            for junction in junction_data.junctions:\n                for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n\n                    entry_wp = self._get_junction_entry_wp(entry_wp)\n                    if not entry_wp:\n                        continue\n                    if get_lane_key(entry_wp) not in used_entry_lanes:\n                        used_entry_lanes.append(get_lane_key(entry_wp))\n                        entry_lane_wps.append(entry_wp)\n                        if self.debug:\n                            draw_point(self._world, entry_wp.transform.location, DEBUG_SMALL, DEBUG_ENTRY, True)\n\n                    exit_wp = self._get_junction_exit_wp(exit_wp)\n                    if not exit_wp:\n                        continue\n                    if get_lane_key(exit_wp) not in used_exit_lanes:\n                        used_exit_lanes.append(get_lane_key(exit_wp))\n                        exit_lane_wps.append(exit_wp)\n                        if self.debug:\n                            draw_point(self._world, exit_wp.transform.location, DEBUG_SMALL, DEBUG_EXIT, True)\n\n            # Check for connecting lanes. This is pretty much for the roundabouts, but some weird geometries\n            # make it possible for single junctions to have the same road entering and exiting. Two cases,\n            # Lanes that exit one junction and enter another (or viceversa)\n            exit_lane_keys = [get_lane_key(wp) for wp in exit_lane_wps]\n            entry_lane_keys = [get_lane_key(wp) for wp in entry_lane_wps]\n            for wp in list(entry_lane_wps):\n                if get_lane_key(wp) in exit_lane_keys:\n                    entry_lane_wps.remove(wp)\n                    if self.debug:\n                        draw_point(self._world, wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n\n            for wp in list(exit_lane_wps):\n                if get_lane_key(wp) in entry_lane_keys:\n                    exit_lane_wps.remove(wp)\n                    if self.debug:\n                        draw_point(self._world, wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n\n            # Lanes with a fake junction in the middle (maps junction exit to fake junction entry and viceversa)\n            for entry_key, exit_key in self._fake_lane_pair_keys:\n                entry_wp = None\n                for wp in entry_lane_wps:\n                    if get_lane_key(wp) == exit_key:  # A junction exit is a fake junction entry\n                        entry_wp = wp\n                        break\n                exit_wp = None\n                for wp in exit_lane_wps:\n                    if get_lane_key(wp) == entry_key:  # A junction entry is a fake junction exit\n                        exit_wp = wp\n                        break\n                if entry_wp and exit_wp:\n                    entry_lane_wps.remove(entry_wp)\n                    exit_lane_wps.remove(exit_wp)\n                    if self.debug:\n                        draw_point(self._world, entry_wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n                        draw_point(self._world, exit_wp.transform.location, DEBUG_SMALL, DEBUG_CONNECT, True)\n\n            junction_data.entry_wps = entry_lane_wps\n            junction_data.exit_wps = exit_lane_wps\n            junction_data.entry_lane_keys = entry_lane_keys\n            junction_data.exit_lane_keys = exit_lane_keys\n            for exit_wp in exit_lane_wps:\n                junction_data.exit_dict[get_lane_key(exit_wp)] = {\n                    'actors': [],\n                    'max_actors': 0,\n                    'ref_wp': None,\n                    'max_distance': 0,\n                }\n\n            # Filter the entries and exits that correspond to the route\n            route_entry_wp = self._route[junction_data.route_entry_index]\n\n            # Junction entry\n            for wp in get_same_dir_lanes(route_entry_wp):\n                junction_wp = self._get_closest_junction_waypoint(wp, entry_lane_wps)\n                junction_data.route_entry_keys.append(get_lane_key(junction_wp))\n            for wp in get_opposite_dir_lanes(route_entry_wp):\n                junction_wp = self._get_closest_junction_waypoint(wp, exit_lane_wps)\n                junction_data.opposite_exit_keys.append(get_lane_key(junction_wp))\n\n            # Junction exit\n            if junction_data.route_exit_index:  # Can be None if route ends at a junction\n                route_exit_wp = self._route[junction_data.route_exit_index]\n                for wp in get_same_dir_lanes(route_exit_wp):\n                    junction_wp = self._get_closest_junction_waypoint(wp, exit_lane_wps)\n                    junction_data.route_exit_keys.append(get_lane_key(junction_wp))\n                for wp in get_opposite_dir_lanes(route_exit_wp):\n                    junction_wp = self._get_closest_junction_waypoint(wp, entry_lane_wps)\n                    junction_data.opposite_entry_keys.append(get_lane_key(junction_wp))\n\n            # Add the entry directions of each lane with respect to the route. Used for scenarios 7 to 9\n            route_entry_yaw = route_entry_wp.transform.rotation.yaw\n            for wp in entry_lane_wps:\n                diff = (wp.transform.rotation.yaw - route_entry_yaw) % 360\n                if diff > 330.0:\n                    direction = 'ref'\n                elif diff > 225.0:\n                    direction = 'right'\n                elif diff > 135.0:\n                    direction = 'opposite'\n                elif diff > 30.0:\n                    direction = 'left'\n                else:\n                    direction = 'ref'\n\n                junction_data.entry_directions[direction].append(get_lane_key(wp))\n\n            # Supposing scenario vehicles go straight, these correspond to the exit lanes of the entry directions\n            for wp in exit_lane_wps:\n                diff = (wp.transform.rotation.yaw - route_entry_yaw) % 360\n                if diff > 330.0:\n                    direction = 'ref'\n                elif diff > 225.0:\n                    direction = 'right'\n                elif diff > 135.0:\n                    direction = 'opposite'\n                elif diff > 30.0:\n                    direction = 'left'\n                else:\n                    direction = 'ref'\n\n                junction_data.exit_directions[direction].append(get_lane_key(wp))\n\n            if self.debug:\n                exit_lane = self._route[junction_data.route_exit_index] if junction_data.route_exit_index else None\n                print('> R Entry Lane: {}'.format(get_lane_key(self._route[junction_data.route_entry_index])))\n                print('> R Exit  Lane: {}'.format(get_lane_key(exit_lane)))\n                entry_print = '> J Entry Lanes: '\n                for entry_wp in entry_lane_wps:\n                    key = get_lane_key(entry_wp)\n                    entry_print += key + ' ' * (8 - len(key))\n                print(entry_print)\n                exit_print = '> J Exit  Lanes: '\n                for exit_wp in exit_lane_wps:\n                    key = get_lane_key(exit_wp)\n                    exit_print += key + ' ' * (8 - len(key))\n                print(exit_print)\n                route_entry = '> R-J Entry Lanes: '\n                for entry_key in junction_data.route_entry_keys:\n                    route_entry += entry_key + ' ' * (8 - len(entry_key))\n                print(route_entry)\n                route_exit = '> R-J Route Exit  Lanes: '\n                for exit_key in junction_data.route_exit_keys:\n                    route_exit += exit_key + ' ' * (8 - len(exit_key))\n                print(route_exit)\n                route_oppo_entry = '> R-J Oppo Entry Lanes: '\n                for oppo_entry_key in junction_data.opposite_entry_keys:\n                    route_oppo_entry += oppo_entry_key + ' ' * (8 - len(oppo_entry_key))\n                print(route_oppo_entry)\n                route_oppo_exit = '> R-J Oppo Exit  Lanes: '\n                for oppo_exit_key in junction_data.opposite_exit_keys:\n                    route_oppo_exit += oppo_exit_key + ' ' * (8 - len(oppo_exit_key))\n                print(route_oppo_exit)\n\n    def _is_junction(self, waypoint):\n        if not waypoint.is_junction or waypoint.junction_id in self._fake_junction_ids:\n            return False\n        return True\n\n    ################################\n    ##       Mode functions       ##\n    ################################\n\n    def _add_actor_dict_element(self, actor_dict, actor, exit_lane_key='', at_oppo_entry_lane=False):\n        \"\"\"\n        Adds a new actor to the actor dictionary.\n        'exit_lane_key' is used to know at which exit lane (if any) is the vehicle\n        'at_oppo_entry_lane' whether or not the actor is part of the entry at the opposite lane the route exits through.\n        This will be the ones that aren't removed\n        \"\"\"\n        actor_dict[actor] = {\n            'state': JUNCTION_ENTRY if not exit_lane_key else JUNCTION_EXIT,\n            'exit_lane_key': exit_lane_key,\n            'at_oppo_entry_lane': at_oppo_entry_lane\n        }\n\n    def _switch_to_junction_mode(self, junction):\n        \"\"\"\n        Prepares the junction mode, removing all road behaviours.\n        Actors that are stopped via a scenario will still wait.\n        \"\"\"\n        self._ego_state = EGO_JUNCTION\n        for lane in self._road_dict:\n            for actor in self._road_dict[lane].actors:\n                # TODO: Map the actors to the junction entry to have full control of them.\n                # This should remove the 'at_oppo_entry_lane'.\n                self._add_actor_dict_element(junction.actor_dict, actor)\n                if actor not in self._scenario_stopped_actors:\n                    self._actors_speed_perc[actor] = 100\n\n        for lane_key in self._road_dict:\n            source = self._road_dict[lane_key]\n            source_key = get_lane_key(source.wp)\n            if source_key in junction.route_entry_keys:\n                junction.entry_sources.append(Source(\n                    source.wp, source.actors, entry_lane_wp=source.wp, active=source.active)\n                )\n                if source_key in junction.inactive_entry_keys:\n                    for actor in source.actors:\n                        self._destroy_actor(actor)\n                    source.active = False\n                    junction.inactive_entry_keys.remove(source_key)\n\n            # TODO: Else should map the source to the entry and add it\n\n        self._road_dict.clear()\n        self._opposite_sources.clear()\n\n    def _end_junction_behavior(self, junction):\n        \"\"\"\n        Destroys unneeded actors (those that aren't part of the route's road),\n        moving the rest to other data structures and cleaning up the variables.\n        If no other junctions are active, starts road mode\n        \"\"\"\n        actor_dict = junction.actor_dict\n        route_exit_keys = junction.route_exit_keys\n        self._active_junctions.pop(0)\n\n        # Prepare the road dictionary\n        if not self._active_junctions:\n            for wp in junction.exit_wps:\n                if get_lane_key(wp) in route_exit_keys:\n                    self._road_dict[get_lane_key(wp)] = Source(wp, [], active=self._active_road_sources)\n\n        else:\n            for wp in junction.exit_wps:\n                if get_lane_key(wp) in route_exit_keys:\n                    # TODO: entry_lane_wp isn't really this one (for cases with road changes)\n                    self._active_junctions[0].entry_sources.append(\n                        Source(wp, [], entry_lane_wp=wp, active=self._active_road_sources)\n                    )\n\n        # Handle the actors\n        for actor in list(actor_dict):\n            location = CarlaDataProvider.get_location(actor)\n            if not location or self._is_location_behind_ego(location):\n                self._destroy_actor(actor)\n                continue\n\n            # Don't destroy those that are on the route's road opposite lane.\n            # Instead, let them move freely until they are automatically destroyed.\n            self._actors_speed_perc[actor] = 100\n            if actor_dict[actor]['at_oppo_entry_lane']:\n                self._opposite_actors.append(actor)\n                self._tm.ignore_lights_percentage(actor, 100)\n                self._tm.ignore_signs_percentage(actor, 100)\n                continue\n\n            # Save those that are on the route's road\n            exit_key = actor_dict[actor]['exit_lane_key']\n            if exit_key in route_exit_keys:\n                if not self._active_junctions:\n                    self._road_dict[exit_key].actors.append(actor)\n                else:\n                    entry_sources = self._active_junctions[0].entry_sources\n                    for entry_source in entry_sources: # Add it to the back source\n                        if exit_key == get_lane_key(entry_source.wp):\n                            entry_sources.actors.append(actor)\n                            break\n                continue\n\n            # Destroy the rest\n            self._destroy_actor(actor)\n\n        # If the junction was part of a scenario, forget about it\n        self._scenario_junction_entry = False\n\n        if not self._active_junctions:\n            self._ego_state = EGO_ROAD\n            self._initialise_opposite_sources()\n            self._initialise_road_checker()\n\n    def _search_for_next_junction(self):\n        \"\"\"Check if closeby to a junction. The closest one will always be the first\"\"\"\n        if not self._junctions:\n            return None\n\n        ego_accum_dist = self._accum_dist[self._route_index]\n        junction_accum_dist = self._accum_dist[self._junctions[0].route_entry_index]\n        if junction_accum_dist - ego_accum_dist < self._detection_dist:  # Junctions closeby\n            return self._junctions.pop(0)\n\n        return None\n\n    def _initialise_connecting_lanes(self, junction):\n        \"\"\"\n        Moves the actors currently at the exit lane of the last junction\n        to entry actors of the newly created junction\n        \"\"\"\n        if len(self._active_junctions) > 0:\n            prev_junction = self._active_junctions[-1]\n            route_exit_keys = prev_junction.route_exit_keys\n            exit_dict = prev_junction.exit_dict\n            for exit_key in route_exit_keys:\n                exit_actors = exit_dict[exit_key]['actors']\n                for actor in list(exit_actors):\n                    self._remove_actor_info(actor)\n                    self._add_actor_dict_element(junction.actor_dict, actor)\n                    self._actors_speed_perc[actor] = 100\n\n    def _monitor_incoming_junctions(self):\n        \"\"\"\n        Monitors when the ego approaches a junction, triggering that junction when it happens.\n        This can be triggered even if there is another junction happening are they work independently\n        \"\"\"\n        junction = self._search_for_next_junction()\n        if not junction:\n            return\n\n        if self._ego_state == EGO_ROAD:\n            self._switch_to_junction_mode(junction)\n        self._initialise_junction_sources(junction)\n        self._initialise_junction_exits(junction)\n\n        self._initialise_connecting_lanes(junction)\n        self._active_junctions.append(junction)\n\n        # Forget the fact that a lane was removed, so that it isn't readded in the middle of the junction\n        self._scenario_removed_lane = False\n        self._scenario_remove_lane_offset = 0\n\n    def _monitor_ego_junction_exit(self):\n        \"\"\"\n        Monitors when the ego exits the junctions, preparing the road mode when that happens\n        \"\"\"\n        current_junction = self._active_junctions[0]\n        exit_index = current_junction.route_exit_index\n        if exit_index and self._route_index >= exit_index:\n            self._end_junction_behavior(current_junction)\n\n    def _add_incoming_actors(self, junction, source):\n        \"\"\"Checks nearby actors that will pass through the source, adding them to it\"\"\"\n        source_location = source.wp.transform.location\n        if not source.previous_lane_keys:\n            source.previous_lane_keys = [get_lane_key(prev_wp) for prev_wp in source.wp.previous(self._reuse_dist)]\n            source.previous_lane_keys.append(get_lane_key(source.wp))\n\n        for actor in self._all_actors:\n            if actor in source.actors:\n                continue  # Don't use actors already part of the source\n\n            actor_location = CarlaDataProvider.get_location(actor)\n            if actor_location is None:\n                continue  # No idea where the actor is, ignore it\n            if source_location.distance(actor_location) > self._reuse_dist:\n                continue  # Don't use actors far away\n\n            actor_wp = self._map.get_waypoint(actor_location)\n            if get_lane_key(actor_wp) not in source.previous_lane_keys:\n                continue  # Don't use actors that won't pass through the source\n\n            self._actors_speed_perc[actor] = 100\n            self._remove_actor_info(actor)\n            source.actors.append(actor)\n\n            at_oppo_entry_lane = get_lane_key(source.entry_lane_wp) in junction.opposite_entry_keys\n            self._add_actor_dict_element(junction.actor_dict, actor, at_oppo_entry_lane=at_oppo_entry_lane)\n\n            return actor\n\n    def _move_road_sources(self, prev_ego_index):\n        \"\"\"\n        Moves the road sources so that they are always following the ego from behind\n        \"\"\"\n        if prev_ego_index != self._route_index:\n            min_distance = self._road_back_vehicles * self._road_spawn_dist\n            for lane_key in self._road_dict:\n                source = self._road_dict[lane_key]\n\n                # If no actors are found, let the last_location be ego's location \n                # to keep moving the source waypoint forward\n                if len(source.actors) == 0:\n                    last_location = self._ego_wp.transform.location\n                else:\n                    last_location = CarlaDataProvider.get_location(source.actors[-1])\n\n                if last_location is None:\n                    continue\n\n                # Stop the sources in front of the ego (created by new lanes)\n                if not self._is_location_behind_ego(source.wp.transform.location):\n                    continue\n\n                # Stop the source from being too close to the ego or last lane vehicle\n                source_location = source.wp.transform.location\n                ego_location = self._ego_wp.transform.location\n\n                actor_dist = max(0, last_location.distance(source_location) - self._road_spawn_dist)\n                ego_dist = max(0, ego_location.distance(source_location) - min_distance)\n                move_dist = min(actor_dist, ego_dist)\n\n                # Move the source forward if needed\n                if move_dist > 0:\n                    new_source_wps = source.wp.next(move_dist)\n                    if not new_source_wps:\n                        continue\n                    source.wp = new_source_wps[0]\n\n    def _update_road_sources(self):\n        \"\"\"\n        Manages the sources that spawn actors behind the ego.\n        These are always behind the ego and will continuously spawn actors.\n        These sources also track the amount of vehicles in front of the ego,\n        removing actors if the amount is too high.\n        \"\"\"\n        for lane_key in self._road_dict:\n            source = self._road_dict[lane_key]\n            if self.debug:\n                draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_ROAD, False)\n                draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_ROAD, False)\n\n            # Ensure not too many actors are in front of the ego\n            front_veh = 0\n            for actor in source.actors:\n                location = CarlaDataProvider.get_location(actor)\n                if location and not self._is_location_behind_ego(location):\n                    front_veh += 1\n            if front_veh > self._road_front_vehicles:\n                self._destroy_actor(source.actors[0])  # This is always the front most vehicle\n\n            if not source.active:\n                continue\n            if not self._is_location_behind_ego(source.wp.transform.location):\n                continue  # Stop the sources in front of the ego (created by new lanes)\n            if len(source.actors) >= self._road_back_vehicles + self._road_front_vehicles:\n                continue\n\n            if len(source.actors) == 0:\n                location = self._ego_wp.transform.location\n            else:\n                location = CarlaDataProvider.get_location(source.actors[-1])\n                if not location:\n                    continue\n\n            distance = location.distance(source.wp.transform.location)\n\n            # Spawn a new actor if the last one is far enough\n            if distance > self._road_spawn_dist:\n                actor = self._spawn_source_actor(source, self._road_spawn_dist)\n                if actor is None:\n                    continue\n\n                # Set their initial speed, so that they don't lag behind the ego.\n                # Set the speed to the ego's one, but never surpassing by the lane's last vehicle's one\n                forward_vec = source.wp.transform.get_forward_vector()\n                speed = self._ego_actor.get_velocity().length()\n                if len(source.actors):\n                    speed = min(speed, source.actors[-1].get_velocity().length())\n                actor.set_target_velocity(speed * forward_vec)\n\n                source.actors.append(actor)\n\n    ################################\n    ## Behavior related functions ##\n    ################################\n\n    def _initialise_road_behavior(self, road_wps):\n        \"\"\"\n        Initialises the road behavior, consisting on several vehicle in front of the ego,\n        and several on the back and are only spawned outside junctions.\n        If there aren't enough actors behind, road sources will be created that will do so later on\n        \"\"\"\n        # Vehicles in front\n        for wp in road_wps:\n            spawn_wps = []\n\n            # Front spawn points\n            next_wp = wp\n            for _ in range(self._road_front_vehicles):\n                next_wps = next_wp.next(self._road_spawn_dist)\n                if len(next_wps) != 1 or self._is_junction(next_wps[0]):\n                    break  # Stop when there's no next or found a junction\n                next_wp = next_wps[0]\n                spawn_wps.insert(0, next_wp)\n\n            # Back spawn points\n            source_dist = 0\n            prev_wp = wp\n            for _ in range(self._road_back_vehicles):\n                prev_wps = prev_wp.previous(self._road_spawn_dist)\n                if len(prev_wps) != 1 or self._is_junction(prev_wps[0]):\n                    break  # Stop when there's no next or found a junction\n                prev_wp = prev_wps[0]\n                spawn_wps.append(prev_wp)\n                source_dist += self._road_spawn_dist\n\n            # Spawn actors\n            actors = self._spawn_actors(spawn_wps)\n\n            self._road_dict[get_lane_key(wp)] = Source(\n                prev_wp, actors, active=self._active_road_sources\n            )\n\n    def _initialise_opposite_sources(self):\n        \"\"\"\n        All opposite lanes have actor sources that will continually create vehicles,\n        creating the sensation of permanent traffic. The actor spawning will be done later on\n        (_update_opposite_sources). These sources are at a (somewhat) fixed distance\n        from the ego, but they never entering junctions. \n        \"\"\"\n        self._opposite_route_index = None\n        if not self._junctions:\n            next_junction_index = self._route_length - 1\n        else:\n            next_junction_index = self._junctions[0].route_entry_index\n\n        ego_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._route_index, next_junction_index):\n            if self._accum_dist[i] - ego_accum_dist > self._opposite_sources_dist:\n                self._opposite_route_index = i\n                break\n        if not self._opposite_route_index:\n            # Junction is closer than the opposite source distance\n            self._opposite_route_index = next_junction_index\n\n        oppo_wp = self._route[self._opposite_route_index]\n\n        for wp in get_opposite_dir_lanes(oppo_wp):\n            self._opposite_sources.append(Source(wp, [], active=self._active_opposite_sources))\n\n    def _initialise_road_checker(self):\n        \"\"\"\n        Gets the waypoints in front of the ego to continuously check if the road changes\n        \"\"\"\n        self._road_checker_index = None\n\n        if not self._junctions:\n            upper_limit = self._route_length - 1\n        else:\n            upper_limit = self._junctions[0].route_entry_index\n\n        ego_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._route_index, upper_limit):\n            if self._accum_dist[i] - ego_accum_dist > self._max_radius:\n                self._road_checker_index = i\n                break\n        if not self._road_checker_index:\n            self._road_checker_index = upper_limit\n\n    def _initialise_junction_sources(self, junction):\n        \"\"\"\n        Initializes the actor sources to ensure the junction is always populated. They are\n        placed at certain distance from the junction, but are stopped if another junction is found,\n        to ensure the spawned actors always move towards the activated one.\n        \"\"\"\n        for wp in junction.entry_wps:\n            entry_lane_key = get_lane_key(wp)\n            if entry_lane_key in junction.route_entry_keys:\n                continue  # Ignore the road from which the route enters\n\n            moved_dist = 0\n            prev_wp = wp\n            while moved_dist < self._junction_sources_dist:\n                prev_wps = prev_wp.previous(5)\n                if len(prev_wps) == 0 or self._is_junction(prev_wps[0]):\n                    break\n                prev_wp = prev_wps[0]\n                moved_dist += 5\n\n            # Don't add junction sources too close to the junction\n            if moved_dist < self._junction_minimum_source_dist:\n                continue\n\n            source = Source(prev_wp, [], entry_lane_wp=wp)\n            entry_lane_key = get_lane_key(wp)\n            if entry_lane_key in junction.inactive_entry_keys:\n                source.active = False\n                junction.inactive_entry_keys.remove(entry_lane_key)\n\n            junction.entry_sources.append(source)\n\n        # Real junctions aren't always full of traffic in all lanes, so deactivate some of them.\n        # Doing this after the source have been created in case another behavior activates them\n        for source in junction.entry_sources:\n            if 100 * self._rng.random() > self._junction_source_perc:\n                source.active = False\n\n    def _initialise_junction_exits(self, junction):\n        \"\"\"\n        Computes and stores the max capacity of the exit. Prepares the behavior of the next road\n        by creating actors at the route exit, and the sources that'll create actors behind the ego\n        \"\"\"\n        exit_wps = junction.exit_wps\n        route_exit_keys = junction.route_exit_keys\n\n        for wp in exit_wps:\n            max_actors = 0\n            max_distance = junction.exit_dict[get_lane_key(wp)]['max_distance']\n            exiting_wps = []\n\n            next_wp = wp\n\n            # Move the initial distance (added by the `_extent_road_exit_space`)\n            if max_distance > 0:\n                next_wps = next_wp.next(max_distance)\n                if not next_wps:\n                    continue\n                next_wp = next_wps[0]\n\n            for i in range(max(self._road_front_vehicles, 1)):\n\n                # Get the moving distance (first jump is higher to allow space for another vehicle)\n                if i == 0:\n                    move_dist = 2 * self._junction_spawn_dist\n                else:\n                    move_dist = self._junction_spawn_dist\n\n                # And move such distance\n                next_wps = next_wp.next(move_dist)\n                if len(next_wps) == 0:\n                    break  # Stop when there's no next\n                next_wp = next_wps[0]\n                if max_actors > 0 and self._is_junction(next_wp):\n                    break  # Stop when a junction is found\n\n                max_actors += 1\n                max_distance += move_dist\n                exiting_wps.insert(0, next_wp)\n\n            junction.exit_dict[get_lane_key(wp)] = {\n                'actors': [], 'max_actors': max_actors, 'ref_wp': wp, 'max_distance': max_distance\n            }\n\n            exit_lane_key = get_lane_key(wp)\n            if exit_lane_key in junction.inactive_exit_keys:\n                continue  # The exit is inactive, don't spawn anything\n\n            if exit_lane_key in route_exit_keys:\n                actors = self._spawn_actors(exiting_wps)\n                for actor in actors:\n                    self._add_actor_dict_element(junction.actor_dict, actor, exit_lane_key=exit_lane_key)\n                junction.exit_dict[exit_lane_key]['actors'] = actors\n\n    def _update_junction_sources(self):\n        \"\"\"Checks the actor sources to see if new actors have to be created\"\"\"\n        for junction in self._active_junctions:\n            actor_dict = junction.actor_dict\n            for source in junction.entry_sources:\n                if self.debug:\n                    draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_JUNCTION, False)\n                    draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_JUNCTION, False)\n\n                entry_lane_key = get_lane_key(source.entry_lane_wp)\n                at_oppo_entry_lane = entry_lane_key in junction.opposite_entry_keys\n\n                if not source.active:\n                    continue\n\n                self._add_incoming_actors(junction, source)\n\n                # Cap the amount of alive actors\n                if len(source.actors) >= self._junction_sources_max_actors:\n                    continue\n\n                # Calculate distance to the last created actor\n                if len(source.actors) == 0:\n                    actor_location = CarlaDataProvider.get_location(self._ego_actor)\n                else:\n                    actor_location = CarlaDataProvider.get_location(source.actors[-1])\n\n                if not actor_location:\n                    continue\n                distance = actor_location.distance(source.wp.transform.location)\n\n                # Spawn a new actor if the last one is far enough\n                if distance > self._junction_spawn_dist:\n                    actor = self._spawn_source_actor(source, self._junction_spawn_dist)\n                    if not actor:\n                        continue\n                    if junction.stop_non_route_entries and get_lane_key(source.entry_lane_wp) not in junction.route_entry_keys:\n                        self._actors_speed_perc[actor] = 0\n                    self._add_actor_dict_element(actor_dict, actor, at_oppo_entry_lane=at_oppo_entry_lane)\n                    source.actors.append(actor)\n\n    def _monitor_topology_changes(self, prev_index):\n        \"\"\"\n        Continually check the road in front to see if it has changed its topology.\n        If the number of lanes reduces, merge the ending lane with a side one\n        If the number of lanes increases, add a new road source.\n        \"\"\"\n        def get_road_wp(wp):\n            \"\"\"Goes backwards in the lane to match the wp with the road key dictionary\"\"\"\n            road_wp = wp\n            if get_lane_key(road_wp) in self._road_dict:\n                return road_wp\n\n            road_wp = wp\n            distance = self._max_radius\n\n            while distance > 0:\n                prev_wps = road_wp.previous(1)\n                if not prev_wps:\n                    return None\n                road_wp = prev_wps[0]\n                if get_lane_key(road_wp) in self._road_dict:\n                    return road_wp\n                distance -= 1\n\n            return None\n\n        def get_source_wp(wp):\n            \"\"\"Moves the wp forward until the lane is wide enough to fit a vehicle\"\"\"\n            source_wp = wp\n            while source_wp.lane_width < self._lane_width_threshold + 0.2:\n                source_wps = source_wp.next(1)\n                if not source_wps:\n                    return None\n                source_wp = source_wps[0]\n            return source_wp\n\n        if self.debug:\n            checker_wp = self._route[self._road_checker_index]\n            draw_point(self._world, checker_wp.transform.location, DEBUG_SMALL, DEBUG_ROAD, False)\n\n        if prev_index == self._route_index:\n            return\n\n        # Get the new route tracking wp\n        checker_index = None\n        last_index = self._junctions[0].route_entry_index if self._junctions else self._route_length - 1\n        current_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._road_checker_index, last_index):\n            accum_dist = self._accum_dist[i]\n            if accum_dist - current_accum_dist >= self._max_radius:\n                checker_index = i\n                break\n        if not checker_index:\n            checker_index = last_index\n\n        if checker_index == self._road_checker_index:\n            return\n\n        new_wps = get_same_dir_lanes(self._route[checker_index])\n        old_wps = get_same_dir_lanes(self._route[self._road_checker_index])\n\n        new_accum_dist = self._accum_dist[checker_index]\n        prev_accum_dist = self._accum_dist[self._road_checker_index]\n        route_move_dist = max(new_accum_dist - prev_accum_dist, 0.1)\n\n        if len(new_wps) > len(old_wps):\n            # Don't add anything in front if the junction entry has to be empty\n            if not self._scenario_junction_entry:\n\n                for new_wp in list(new_wps):\n\n                    prev_wps = new_wp.previous(2 * route_move_dist)  # x2, just in case\n                    if prev_wps:\n                        continue\n\n                    # Found the new lane, add the actors and source.\n                    # Don't spawn actors while the source is in front of the ego\n                    source_wp = get_source_wp(new_wp)\n                    if not source_wp:\n                        continue\n\n                    next_wp = source_wp\n                    spawn_wps = []\n                    spawn_dist = self._road_front_vehicles + CarlaDataProvider.get_velocity(self._ego_actor)\n                    for _ in range(self._road_front_vehicles):\n                        next_wps = next_wp.next(spawn_dist)\n                        if len(next_wps) != 1 or self._is_junction(next_wps[0]):\n                            break  # Stop when there's no next or found a junction\n                        next_wp = next_wps[0]\n                        spawn_wps.insert(0, next_wp)\n\n                    actors = self._spawn_actors(spawn_wps)\n\n                    if get_lane_key(source_wp) not in self._road_dict:\n                        # Lanes created away from the center won't affect the ids of other lanes, so just add the new id\n                        self._road_dict[get_lane_key(source_wp)] = Source(source_wp, actors, active=self._active_road_sources)\n                    else:\n                        # If the lane is inwards, all lanes have their id shifted by 1 outwards\n                        # TODO: Doesn't work for more than one lane.\n                        added_id = 1 if source_wp.lane_id > 0 else -1\n                        new_lane_key = get_lane_key_from_ids(source_wp.road_id, source_wp.lane_id + added_id)\n                        self._road_dict[new_lane_key] = self._road_dict[get_lane_key(source_wp)]\n                        self._road_dict[get_lane_key(source_wp)] = Source(source_wp, actors, active=self._active_road_sources)\n\n        elif len(new_wps) < len(old_wps):\n            for old_wp in list(old_wps):\n                next_wps = old_wp.next(2 * route_move_dist)  # x2, just in case\n                if next_wps:\n                    continue\n\n                # Found the lane that ends, merge it with the one on its side\n                road_wp = get_road_wp(old_wp)\n                if not road_wp:\n                    continue\n\n                # Get a side lane\n                right_wp = old_wp.get_right_lane()\n                left_wp = old_wp.get_left_lane()\n                side_road_wp = None\n                if right_wp and right_wp.lane_type == carla.LaneType.Driving:\n                    side_road_wp = get_road_wp(right_wp)\n                    side_path = [right_wp.transform.location]\n                elif left_wp and left_wp.lane_type == carla.LaneType.Driving:\n                    side_road_wp = get_road_wp(left_wp)\n                    side_path = [left_wp.transform.location]\n\n                if not side_road_wp:\n                    # No side lane found part of the road dictionary, remove them\n                    for actor in list(self._road_dict[get_lane_key(road_wp)].actors):\n                        self._destroy_actor(actor)\n                    self._road_dict.pop(get_lane_key(road_wp), None)\n                    continue\n\n                # Get the actors\n                lane_actors = self._road_dict[get_lane_key(road_wp)].actors\n                side_lane_actors = self._road_dict[get_lane_key(side_road_wp)].actors\n\n                # Get their distance to the ego\n                actors_with_dist = []\n                ego_location = self._ego_wp.transform.location\n                for actor in lane_actors + side_lane_actors:\n                    actor_location = CarlaDataProvider.get_location(actor)\n                    if not actor_location:\n                        self._destroy_actor(actor)\n                        continue\n                    dist = ego_location.distance(actor_location)\n                    if not self._is_location_behind_ego(actor_location):\n                        dist *= -1\n                    actors_with_dist.append([actor, dist])\n\n                # Sort them by distance\n                actors_sorted_with_dist = sorted(actors_with_dist, key=lambda a: a[1])\n                zero_index = len([a for a in actors_sorted_with_dist if a[1] < 0])\n                min_index = max(zero_index - self._road_front_vehicles, 0)\n                max_index = min(zero_index + self._road_front_vehicles - 1, len(actors_sorted_with_dist) - 1)\n\n                # Remove the unneeded ones, and make the ending lane actors perform a lane change\n                source_actors = []\n                for i, (actor, _) in enumerate(actors_sorted_with_dist):\n                    if i >= min_index and i <= max_index:\n                        source_actors.append(actor)\n                        self._tm.set_path(actor, side_path)\n                    else:\n                        self._destroy_actor(actor)\n\n                # And update the road dict\n                self._road_dict[get_lane_key(side_road_wp)].actors = source_actors\n                self._road_dict.pop(get_lane_key(road_wp), None)\n\n        self._road_checker_index = checker_index\n\n    def _move_opposite_sources(self, prev_index):\n        \"\"\"\n        Moves the sources of the opposite direction back. Additionally, tracks a point a certain distance\n        in front of the ego to see if the road topology has to be recalculated\n        \"\"\"\n        if self.debug:\n            for source in self._opposite_sources:\n                draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_OPPOSITE, False)\n                draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_OPPOSITE, False)\n            route_wp = self._route[self._opposite_route_index]\n            draw_point(self._world, route_wp.transform.location, DEBUG_SMALL, DEBUG_OPPOSITE, False)\n\n        if prev_index == self._route_index:\n            return\n\n        # Get the new route tracking wp\n        oppo_route_index = None\n        last_index = self._junctions[0].route_entry_index if self._junctions else self._route_length - 1\n        current_accum_dist = self._accum_dist[self._route_index]\n        for i in range(self._opposite_route_index, last_index):\n            accum_dist = self._accum_dist[i]\n            if accum_dist - current_accum_dist >= self._opposite_sources_dist:\n                oppo_route_index = i\n                break\n        if not oppo_route_index:\n            oppo_route_index = last_index\n\n        # Get the distance moved by the route reference index\n        new_accum_dist = self._accum_dist[oppo_route_index]\n        prev_accum_dist = self._accum_dist[self._opposite_route_index]\n        route_move_dist = new_accum_dist - prev_accum_dist\n        if route_move_dist <= 0:\n            return  # Sometimes a route wp is behind the pervious one, filter these out\n\n        new_opposite_wps = get_opposite_dir_lanes(self._route[oppo_route_index])\n\n        if len(new_opposite_wps) != len(self._opposite_sources):\n            # The topology has changed. Remap the new lanes to the sources\n            new_opposite_sources = []\n            for wp in new_opposite_wps:\n                location = wp.transform.location\n                new_source = None\n                for source in self._opposite_sources:\n                    if location.distance(source.wp.transform.location) < 1.1 * route_move_dist:\n                        new_source = source\n                        break\n\n                if new_source:\n                    new_source.wp = wp\n                    new_opposite_sources.append(new_source)\n                    self._opposite_sources.remove(new_source)\n                else:\n                    new_opposite_sources.append(Source(wp, []))\n\n            self._opposite_sources = new_opposite_sources\n        else:\n            # The topology hasn't changed, move the distance backwards\n            for source in self._opposite_sources:\n                wp = source.wp\n                if not self._is_junction(wp):\n                    prev_wps = wp.previous(route_move_dist)\n                    if len(prev_wps) == 0:\n                        continue\n                    prev_wp = prev_wps[0]\n                    source.wp = prev_wp\n\n        self._opposite_route_index = oppo_route_index\n\n    def _update_opposite_sources(self):\n        \"\"\"Checks the opposite actor sources to see if new actors have to be created\"\"\"\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n        for source in self._opposite_sources:\n            if not source.active:\n                continue\n\n            # Ending / starting lanes create issues as the lane width gradually decreases until reaching 0,\n            # where the lane starts / ends. Avoid spawning anything inside those parts with small lane width\n            if source.wp.lane_width < self._lane_width_threshold:\n                continue\n\n            # Calculate distance to the last created actor\n            if len(source.actors) == 0:\n                distance = self._opposite_sources_dist + 1\n            else:\n                actor_location = CarlaDataProvider.get_location(source.actors[-1])\n                if not actor_location:\n                    continue\n                distance = source.wp.transform.location.distance(actor_location)\n\n            # Spawn a new actor if the last one is far enough\n            if distance > self._opposite_spawn_dist:\n                actor = self._spawn_source_actor(source)\n                if actor is None:\n                    continue\n                self._tm.ignore_lights_percentage(actor, 100)\n                self._tm.ignore_signs_percentage(actor, 100)\n                self._opposite_actors.append(actor)\n                source.actors.append(actor)\n\n    def _update_parameters(self):\n        \"\"\"\n        Changes those parameters that have dynamic behaviors and / or that can be changed by external source.\n        This is done using py_trees' Blackboard variables and all behaviors should be at `background_manager.py`.\n        The blackboard variable is reset to None to avoid changing them back again next time.\n        \"\"\"\n        # Road behavior\n        road_behavior_data = py_trees.blackboard.Blackboard().get('BA_ChangeRoadBehavior')\n        if road_behavior_data is not None:\n            num_front_vehicles, num_back_vehicles, spawn_dist, extra_space = road_behavior_data\n            if num_front_vehicles is not None:\n                self._road_front_vehicles = num_front_vehicles\n            if num_back_vehicles is not None:\n                self._road_back_vehicles = num_back_vehicles\n            if spawn_dist is not None:\n                self._road_spawn_dist = spawn_dist\n            if extra_space is not None:\n                self._road_extra_space = extra_space\n            self._get_road_radius()\n            py_trees.blackboard.Blackboard().set('BA_ChangeRoadBehavior', None, True)\n\n        # Opposite behavior\n        opposite_behavior_data = py_trees.blackboard.Blackboard().get('BA_ChangeOppositeBehavior')\n        if opposite_behavior_data is not None:\n            source_dist, spawn_dist, active = opposite_behavior_data\n            if source_dist is not None:\n                if source_dist < self._junction_sources_dist:\n                    print('WARNING: Opposite sources distance is lower than the junction ones. Ignoring it')\n                else:\n                    self._opposite_sources_dist = source_dist\n            if spawn_dist is not None:\n                self._opposite_spawn_dist = spawn_dist\n                self._opposite_sources_dist = 2 * spawn_dist\n            if active is not None:\n                self._active_opposite_sources = active\n                for source in self._opposite_sources:\n                    source.active = active\n            py_trees.blackboard.Blackboard().set('BA_ChangeOppositeBehavior', None, True)\n\n        # Junction behavior\n        junction_behavior_data = py_trees.blackboard.Blackboard().get('BA_ChangeJunctionBehavior')\n        if junction_behavior_data is not None:\n            source_dist, spawn_dist, max_actors, source_perc = junction_behavior_data\n            if source_dist is not None:\n                if source_dist > self._opposite_sources_dist:\n                    print('WARNING: Junction sources distance is higher than the opposite ones. Ignoring it')\n                else:\n                    self._junction_sources_dist = source_dist\n            if spawn_dist:\n                self._junction_spawn_dist = spawn_dist\n            if max_actors is not None:\n                self._junction_sources_max_actors = max_actors\n            if source_perc is not None:\n                self._junction_source_perc = source_perc\n            py_trees.blackboard.Blackboard().set('BA_ChangeJunctionBehavior', None, True)\n\n        # Max speed\n        max_speed = py_trees.blackboard.Blackboard().get('BA_SetMaxSpeed')\n        if max_speed is not None:\n            self._scenario_max_speed = max_speed\n            py_trees.blackboard.Blackboard().set('BA_SetMaxSpeed', None, True)\n\n        # Stop front vehicles\n        stop_data = py_trees.blackboard.Blackboard().get('BA_StopFrontVehicles')\n        if stop_data is not None:\n            self._stop_road_front_vehicles()\n            py_trees.blackboard.Blackboard().set('BA_StopFrontVehicles', None, True)\n\n        # Start front vehicles\n        start_data = py_trees.blackboard.Blackboard().get('BA_StartFrontVehicles')\n        if start_data is not None:\n            self._start_road_front_vehicles()\n            py_trees.blackboard.Blackboard().set(\"BA_StartFrontVehicles\", None, True)\n\n        # Stop back vehicles\n        stop_back_data = py_trees.blackboard.Blackboard().get('BA_StopBackVehicles')\n        if stop_back_data is not None:\n            self._stop_road_back_vehicles()\n            py_trees.blackboard.Blackboard().set('BA_StopBackVehicles', None, True)\n\n        # Start back vehicles\n        start_back_data = py_trees.blackboard.Blackboard().get('BA_StartBackVehicles')\n        if start_back_data is not None:\n            self._start_road_back_vehicles()\n            py_trees.blackboard.Blackboard().set(\"BA_StartBackVehicles\", None, True)\n\n        # Leave space in front\n        leave_space_data = py_trees.blackboard.Blackboard().get('BA_LeaveSpaceInFront')\n        if leave_space_data is not None:\n            self._leave_space_in_front(leave_space_data)\n            py_trees.blackboard.Blackboard().set('BA_LeaveSpaceInFront', None, True)\n\n        # Leave crosssing space\n        leave_crossing_space_data = py_trees.blackboard.Blackboard().get('BA_LeaveCrossingSpace')\n        if leave_crossing_space_data is not None:\n            self._leave_crossing_space(leave_crossing_space_data)\n            py_trees.blackboard.Blackboard().set('BA_LeaveCrossingSpace', None, True)\n\n        # Remove road lane\n        remove_road_lane_data = py_trees.blackboard.Blackboard().get('BA_RemoveRoadLane')\n        if remove_road_lane_data is not None:\n            self._remove_road_lane(remove_road_lane_data)\n            py_trees.blackboard.Blackboard().set('BA_RemoveRoadLane', None, True)\n\n        # Readd road lane\n        readd_road_lane_data = py_trees.blackboard.Blackboard().get('BA_ReAddRoadLane')\n        if readd_road_lane_data is not None:\n            self._readd_road_lane(readd_road_lane_data)\n            py_trees.blackboard.Blackboard().set('BA_ReAddRoadLane', None, True)\n\n        # Adapt the BA to the junction scenario\n        junction_scenario_data = py_trees.blackboard.Blackboard().get('BA_HandleJunctionScenario')\n        if junction_scenario_data is not None:\n            self._handle_junction_scenario(junction_scenario_data)\n            py_trees.blackboard.Blackboard().set(\"BA_HandleJunctionScenario\", None, True)\n\n        # Switch route sources\n        switch_sources_data = py_trees.blackboard.Blackboard().get('BA_SwitchRouteSources')\n        if switch_sources_data is not None:\n            self._switch_route_sources(switch_sources_data)\n            py_trees.blackboard.Blackboard().set(\"BA_SwitchRouteSources\", None, True)\n\n        self._compute_parameters()\n\n    def _compute_parameters(self):\n        \"\"\"Computes the parameters that are dependent on the speed of the ego. \"\"\"\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n        self._min_radius = self._base_min_radius + self._radius_increase_ratio * ego_speed + self._road_extra_space\n        self._max_radius = self._base_max_radius + self._radius_increase_ratio * ego_speed + self._road_extra_space\n        self._detection_dist = self._base_junction_detection + self._detection_ratio * ego_speed\n\n    def _stop_road_front_vehicles(self):\n        \"\"\"\n        Stops all road vehicles in front of the ego. Use `_start_road_front_vehicles` to make them move again.\n        \"\"\"\n        for lane in self._road_dict:\n            for actor in self._road_dict[lane].actors:\n                location = CarlaDataProvider.get_location(actor)\n                if location and not self._is_location_behind_ego(location):\n                    self._scenario_stopped_actors.append(actor)\n                    self._actors_speed_perc[actor] = 0\n                    self._tm.update_vehicle_lights(actor, False)\n                    lights = actor.get_light_state()\n                    lights |= carla.VehicleLightState.Brake\n                    actor.set_light_state(carla.VehicleLightState(lights))\n\n    def _start_road_front_vehicles(self):\n        \"\"\"\n        Restarts all road vehicles stopped by `_stop_road_front_vehicles`.\n        \"\"\"\n        for actor in self._scenario_stopped_actors:\n            self._actors_speed_perc[actor] = 100\n            self._tm.update_vehicle_lights(actor, True)\n            lights = actor.get_light_state()\n            lights &= ~carla.VehicleLightState.Brake\n            actor.set_light_state(carla.VehicleLightState(lights))\n        self._scenario_stopped_actors = []\n\n    def _stop_road_back_vehicles(self):\n        \"\"\"\n        Stops all road vehicles behind the ego. Use `_start_road_back_vehicles` to make them move again.\n        \"\"\"\n        for lane in self._road_dict:\n            for actor in self._road_dict[lane].actors:\n                location = CarlaDataProvider.get_location(actor)\n                if location and self._is_location_behind_ego(location):\n                    self._actors_speed_perc[actor] = 0\n                    self._scenario_stopped_back_actors.append(actor)\n\n    def _start_road_back_vehicles(self):\n        \"\"\"\n        Restarts all road vehicles stopped by `_stop_road_back_vehicles`.\n        \"\"\"\n        for actor in self._scenario_stopped_back_actors:\n            self._actors_speed_perc[actor] = 100\n        self._scenario_stopped_back_actors = []\n\n    def _move_actors_forward(self, actors, space):\n        \"\"\"Teleports the actors forward a set distance\"\"\"\n        for actor in list(actors):\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n\n            actor_wp = self._map.get_waypoint(location)\n            new_actor_wps = actor_wp.next(space)\n            if len(new_actor_wps) > 0:\n                new_transform = new_actor_wps[0].transform\n                new_transform.location.z += 0.2\n                actor.set_transform(new_transform)\n            else:\n                self._destroy_actor(actor)\n\n    def _switch_route_sources(self, enabled):\n        \"\"\"\n        Disables all sources that are part of the ego's route\n        \"\"\"\n        self._active_road_sources = enabled\n        for lane in self._road_dict:\n            self._road_dict[lane].active = enabled\n\n        for junction in self._active_junctions:\n            for source in junction.entry_sources:\n                if get_lane_key(source.entry_lane_wp) in junction.route_entry_keys:\n                    source.active = enabled\n\n    def _leave_space_in_front(self, space):\n        \"\"\"Teleports all the vehicles in front of the ego forward\"\"\"\n        if self._ego_key not in self._road_dict:\n            return\n\n        if self._active_junctions:\n            return\n\n        front_actors = []\n        min_distance = float('inf')\n        for actor in self._road_dict[self._ego_key].actors:\n            location = CarlaDataProvider.get_location(actor)\n            if not location or self._is_location_behind_ego(location):\n                continue\n\n            front_actors.append(actor)\n            distance = location.distance(self._ego_wp.transform.location)\n            if distance < min_distance:\n                min_distance = distance\n\n        step = space - min_distance\n        if step > 0:  # Only move them if needed and only the minimum required distance\n            self._move_actors_forward(front_actors, step)\n\n    def _leave_crossing_space(self, collision_wp):\n        \"\"\"Removes all vehicle in the middle of crossing trajectory and stops the nearby ones\"\"\"\n        destruction_dist = 20\n        stop_dist = 30\n\n        opposite_wp = collision_wp.get_left_lane()\n        if not opposite_wp:\n            return  # Nothing else to do\n        opposite_loc = opposite_wp.transform.location\n\n        for actor in list(self._opposite_actors):\n            location = actor.get_location()\n            if not location:\n                continue\n\n            collision_dist = location.distance(opposite_loc)\n            if collision_dist < destruction_dist:\n                self._destroy_actor(actor)\n            elif collision_dist < stop_dist:\n                actor.set_target_velocity(carla.Vector3D())\n\n    def _remove_road_lane(self, lane_wp):\n        \"\"\"Removes a road lane\"\"\"\n        self._scenario_removed_lane = True\n        self._scenario_remove_lane_offset = 0\n        lane_key = get_lane_key(lane_wp)\n        if lane_key not in list(self._road_dict):\n            print(f\"WARNING: Couldn't find the lane to be removed, '{lane_key}' isn't part of the road behavior\")\n            return\n\n        self._road_dict[lane_key].active = False\n        for actor in list(self._road_dict[lane_key].actors):\n            self._destroy_actor(actor)\n        self._road_dict.pop(lane_key, None)\n\n    def _readd_road_lane(self, lane_offset):\n        \"\"\"Adds a ego road lane. This is expected to be used after having previously removed such lane\"\"\"\n        # Check that the ego hasn't moved close to a junction, where we don't want to reinitialize the lane\n        if not self._scenario_removed_lane:\n            return\n\n        lane_offset += self._scenario_remove_lane_offset\n\n        if lane_offset == 0:\n            add_lane_wp = self._ego_wp\n            add_lane_key = self._ego_key\n        else:\n            side_wp = self._ego_wp\n            for _ in range(abs(lane_offset)):\n                side_wp = side_wp.get_right_lane() if lane_offset > 0 else side_wp.get_left_lane()\n                if not side_wp:\n                    print(f\"WARNING: Couldn't find a lane with the desired offset\")\n                    return\n\n            add_lane_wp = side_wp\n            add_lane_key = get_lane_key(side_wp)\n\n        if add_lane_key in list(self._road_dict):\n            print(f\"WARNING: Couldn't add a lane {add_lane_key} as it is already part of the road\")\n            return\n\n        ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n        spawn_dist = self._road_spawn_dist + 2 * ego_speed\n\n        spawn_wps = []\n\n        next_wp = add_lane_wp\n        for _ in range(self._road_front_vehicles):\n            next_wps = next_wp.next(spawn_dist)\n            if len(next_wps) != 1 or self._is_junction(next_wps[0]):\n                break  # Stop when there's no next or found a junction\n            next_wp = next_wps[0]\n            spawn_wps.insert(0, next_wp)\n\n        source_dist = 0\n        prev_wp = add_lane_wp\n        for _ in range(self._road_back_vehicles):\n            prev_wps = prev_wp.previous(spawn_dist)\n            if len(prev_wps) != 1 or self._is_junction(prev_wps[0]):\n                break  # Stop when there's no next or found a junction\n            prev_wp = prev_wps[0]\n            spawn_wps.append(prev_wp)\n            source_dist += spawn_dist\n\n        actors = []\n        for spawn_wp in spawn_wps:\n            actor = self._spawn_actor(spawn_wp)\n            if not actor:\n                continue\n            actor.set_target_velocity(spawn_wp.transform.get_forward_vector() * ego_speed)\n            actors.append(actor)\n\n        self._road_dict[add_lane_key] = Source(prev_wp, actors, active=self._active_road_sources)\n\n        self._scenario_removed_lane = False\n        self._scenario_remove_lane_offset = 0\n\n    def _handle_junction_scenario(self, junction_data):\n        \"\"\"\n        Adapts the BA to the junction scenario by clearing the junction,\n        its entries, exits, and by extending the road exit to add more space\n        \"\"\"\n        clear_junction, clear_ego_entry, remove_entries, remove_exits, stop_entries, extend_road_exit = junction_data\n\n        if clear_junction:\n            self._clear_junction_middle()\n\n        if clear_ego_entry:\n            self._clear_ego_entry()\n\n        if remove_entries:\n            self._remove_junction_entries(remove_entries)\n\n        if remove_exits:\n            self._remove_junction_exits(remove_exits)\n\n        if stop_entries:\n            self._stop_non_ego_route_entries()\n\n        if extend_road_exit:\n            self._extent_road_exit_space(extend_road_exit)\n\n        self._scenario_removed_lane = False\n        self._scenario_remove_lane_offset = 0\n\n    def _clear_junction_middle(self):\n        \"\"\"Clears the junction, and all subsequent actors that enter it\"\"\"\n        if self._active_junctions:\n            junction = self._active_junctions[0]\n            actor_dict = junction.actor_dict\n            for actor in list(actor_dict):\n                if actor_dict[actor]['state'] == JUNCTION_MIDDLE:\n                    self._destroy_actor(actor)\n            junction.clear_middle = True\n\n        elif self._junctions:\n            self._junctions[0].clear_middle = True\n\n    def _clear_ego_entry(self):\n        \"\"\"\n        Remove all actors in front of the vehicle.\n        \"\"\"\n        def handle_actors(actor_list):\n            for actor in list(actor_list):\n                location = CarlaDataProvider.get_location(actor)\n                if location and not self._is_location_behind_ego(location):\n                    self._destroy_actor(actor)\n\n        # This will make the actors behind never overtake the ego\n        self._scenario_junction_entry = True\n\n        if self._active_junctions:\n            for source in self._active_junctions[0].entry_sources:\n                handle_actors(source.actors)\n        else:\n            for lane_key in list(self._road_dict):\n                source = self._road_dict[lane_key]\n                handle_actors(source.actors)\n                source.active = False\n\n    def _remove_junction_entries(self, wps):\n        \"\"\"Removes a list of entries of the closest junction (or marks them so that they aren't spawned)\"\"\"\n        if len(self._active_junctions) > 0:\n            junction = self._active_junctions[0]\n        elif len(self._junctions) > 0:\n            junction = self._junctions[0]\n        else:\n            return\n\n        for wp in wps:\n            mapped_key = None\n            next_wp = wp\n            while not self._is_junction(next_wp):\n                lane_key = get_lane_key(next_wp)\n                if lane_key in junction.entry_lane_keys:\n                    mapped_key = lane_key\n                    break\n                next_wps = next_wp.next(1)\n                if not next_wps:\n                    break\n                next_wp = next_wps[0]\n\n            if not mapped_key:\n                print(\"WARNING: Couldn't find the asked entry to be removed\")\n                continue\n\n            if len(self._active_junctions) > 0:\n                for source in junction.entry_sources:\n                    if get_lane_key(source.wp) == mapped_key:\n                        for actor in list(source.actors):\n                            self._destroy_actor(actor)\n                        source.active = False\n            else:\n                junction.inactive_entry_keys.append(mapped_key)\n\n    def _remove_junction_exits(self, wps):\n        \"\"\"Removes a list of exit of the closest junction (or marks them so that they aren't spawned)\"\"\"\n        if len(self._active_junctions) > 0:\n            junction = self._active_junctions[0]\n        elif len(self._junctions) > 0:\n            junction = self._junctions[0]\n        else:\n            return\n\n        for wp in wps:\n\n            mapped_key = None\n            prev_wp = wp\n            while not self._is_junction(prev_wp):\n                lane_key = get_lane_key(prev_wp)\n                if lane_key in junction.exit_dict:\n                    mapped_key = lane_key\n                    break\n                prev_wps = prev_wp.next(1)\n                if not prev_wps:\n                    break\n                prev_wp = prev_wps[0]\n\n            if not mapped_key:\n                print(\"WARNING: Couldn't find the asked exit to be removed\")\n                continue\n\n            if len(self._active_junctions) > 0:\n                for actor in list(junction.exit_dict[mapped_key]['actors']):\n                    self._destroy_actor(actor)\n            else:\n                junction.inactive_exit_keys.append(mapped_key)\n\n    def _stop_non_ego_route_entries(self):\n        \"\"\"Clears the junction, and all subsequent actors that enter it\"\"\"\n        if self._active_junctions:\n\n            # Remove all actors in the middle\n            junction = self._active_junctions[0]\n            actor_dict = junction.actor_dict\n\n            entry_sources = junction.entry_sources\n            route_entry_keys = junction.route_entry_keys\n            for source in entry_sources:\n                if get_lane_key(source.entry_lane_wp) not in route_entry_keys:\n                    for actor in source.actors:\n                        if actor_dict[actor]['state'] == JUNCTION_ENTRY:\n                            self._actors_speed_perc[actor] = 0\n\n        elif self._junctions:\n            self._junctions[0].stop_non_route_entries = True\n\n    def _extent_road_exit_space(self, space):\n        \"\"\"Increases the space left by the exit vehicles at a specific road\"\"\"\n        if len(self._active_junctions) > 0:\n            junction = self._active_junctions[0]\n        elif len(self._junctions) > 0:\n            junction = self._junctions[0]\n        else:\n            return\n\n        route_lane_keys = junction.route_exit_keys\n\n        for exit_lane_key in route_lane_keys:\n            junction.exit_dict[exit_lane_key]['max_distance'] += space\n            actors = junction.exit_dict[exit_lane_key]['actors']\n            self._move_actors_forward(actors, space)\n            for actor in actors:\n                if junction.actor_dict[actor]['state'] == JUNCTION_EXIT_ROAD:\n                    self._actors_speed_perc[actor] = 100\n                    junction.actor_dict[actor]['state'] = JUNCTION_EXIT\n\n    #############################\n    ##     Actor functions     ##\n    #############################\n    def _initialise_actor(self, actor):\n        \"\"\"\n        Save the actor into the needed structures, disable its lane changes and set the leading distance.\n        \"\"\"\n        self._tm.auto_lane_change(actor, self._vehicle_lane_change)\n        self._tm.update_vehicle_lights(actor, self._vehicle_lights)\n        self._tm.distance_to_leading_vehicle(actor, self._vehicle_leading_distance)\n        self._tm.vehicle_lane_offset(actor, self._vehicle_offset)\n        self._all_actors.append(actor)\n\n    def _spawn_actor(self, spawn_wp, ego_dist=0):\n        \"\"\"Spawns an actor\"\"\"\n        ego_location = CarlaDataProvider.get_location(self._ego_actor)\n        if ego_location.distance(spawn_wp.transform.location) < ego_dist:\n            return None\n\n        spawn_transform = carla.Transform(\n            spawn_wp.transform.location + carla.Location(z=self._spawn_vertical_shift),\n            spawn_wp.transform.rotation\n        )\n\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', spawn_transform, 'background', True,\n            attribute_filter={'base_type': 'car', 'has_lights': True}, tick=False\n        )\n\n        if not actor:\n            return actor\n        self._initialise_actor(actor)\n        return actor\n\n    def _spawn_actors(self, spawn_wps, ego_dist=0):\n        \"\"\"Spawns several actors in batch\"\"\"\n        spawn_transforms = []\n        ego_location = CarlaDataProvider.get_location(self._ego_actor)\n        for wp in spawn_wps:\n            if ego_location.distance(wp.transform.location) < ego_dist:\n                continue\n            spawn_transforms.append(\n                carla.Transform(wp.transform.location + carla.Location(z=self._spawn_vertical_shift),\n                                wp.transform.rotation)\n            )\n\n        actors = CarlaDataProvider.request_new_batch_actors(\n            'vehicle.*', len(spawn_transforms), spawn_transforms, True, False, 'background',\n            attribute_filter=self._attribute_filter, tick=False)\n\n        if not actors:\n            return actors\n\n        for actor in actors:\n            self._initialise_actor(actor)\n\n        return actors\n\n    def _spawn_source_actor(self, source, ego_dist=20):\n        \"\"\"Given a source, spawns an actor at that source\"\"\"\n        ego_location = CarlaDataProvider.get_location(self._ego_actor)\n        source_transform = source.wp.transform\n        if ego_location.distance(source_transform.location) < ego_dist:\n            return None\n\n        new_transform = carla.Transform(\n            source_transform.location + carla.Location(z=self._spawn_vertical_shift),\n            source_transform.rotation\n        )\n        actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', new_transform, rolename='background',\n            autopilot=True, random_location=False, attribute_filter=self._attribute_filter, tick=False)\n\n        if not actor:\n            return actor\n\n        self._initialise_actor(actor)\n        return actor\n\n    def _is_location_behind_ego(self, location):\n        \"\"\"Checks if an actor is behind the ego. Uses the route transform\"\"\"\n        ego_transform = self._route[self._route_index].transform\n        ego_heading = ego_transform.get_forward_vector()\n        ego_actor_vec = location - ego_transform.location\n        if ego_heading.dot(ego_actor_vec) < - 0.17:  # 100º\n            return True\n        return False\n\n    def _update_road_actors(self):\n        \"\"\"\n        Dynamically controls the actor speed in front of the ego.\n        Not applied to those behind it so that they can catch up it\n        \"\"\"\n        # Updates their speed\n        scenario_actors = self._scenario_stopped_actors + self._scenario_stopped_back_actors\n        for lane_key in self._road_dict:\n            for i, actor in enumerate(self._road_dict[lane_key].actors):\n                location = CarlaDataProvider.get_location(actor)\n                if not location:\n                    continue\n                if self.debug:\n                    string = 'R_'\n                    string += 'B' if self._is_location_behind_ego(location) else 'F'\n                    string += '_(' + str(i) + ')'\n                    string += '_[' + lane_key + ']'\n                    draw_string(self._world, location, string, DEBUG_ROAD, False)\n\n                # Actors part of scenarios are their own category, ignore them\n                if actor in scenario_actors:\n                    continue\n\n                # TODO: Lane changes are weird with the TM, so just stop them\n                actor_wp = self._map.get_waypoint(location)\n                if actor_wp.lane_width < self._lane_width_threshold:\n\n                    # Ensure only ending lanes are affected. not sure if it is needed though\n                    next_wps = actor_wp.next(0.5)\n                    if next_wps and next_wps[0].lane_width < actor_wp.lane_width:\n                        actor.set_target_velocity(carla.Vector3D(0, 0, 0))\n                        self._actors_speed_perc[actor] = 0\n                        lights = actor.get_light_state()\n                        lights |= carla.VehicleLightState.RightBlinker\n                        lights |= carla.VehicleLightState.LeftBlinker\n                        lights |= carla.VehicleLightState.Position\n                        actor.set_light_state(carla.VehicleLightState(lights))\n                        actor.set_autopilot(False, self._tm_port)\n                        continue\n\n                self._set_road_actor_speed(location, actor)\n\n    def _set_road_actor_speed(self, location, actor, multiplier=1):\n        \"\"\"\n        Changes the speed of the vehicle depending on its distance to the ego.\n        - Front vehicles: Gradually reduces the speed the further they are.\n        - Back vehicles: Gradually reduces the speed the further they are to help them catch up to the ego.\n        - Junction scenario behavior: Don't let vehicles behind the ego surpass it.\n        \"\"\"\n        distance = location.distance(self._ego_wp.transform.location)\n        if not self._is_location_behind_ego(location):\n            percentage = (self._max_radius - distance) / (self._max_radius - self._min_radius) * 100\n            percentage *= multiplier\n            percentage = max(min(percentage, 100), 0)\n        elif not self._scenario_junction_entry:\n            percentage = distance / (self._max_radius - self._min_radius) * 100 + 100\n            percentage = max(min(percentage, 200), 0)\n        else:\n            ego_speed = CarlaDataProvider.get_velocity(self._ego_actor)\n            base_percentage = ego_speed / self._ego_target_speed * 100\n            true_distance = distance - self._scenario_junction_entry_distance\n            percentage = true_distance / (self._max_radius - self._min_radius) * 100 + base_percentage\n            percentage = max(min(percentage, 100), 0)\n\n        self._actors_speed_perc[actor] = percentage\n\n    def _monitor_road_changes(self, prev_route_index):\n        \"\"\"\n        Checks if the ego changes road, remapping the route keys.\n        \"\"\"\n        def get_lane_waypoints(reference_wp, index=0):\n            if not reference_wp.is_junction:\n                wps = get_same_dir_lanes(reference_wp)\n            else: # Handle fake junction by using its entry / exit wps\n                wps = []\n                for junction_wps in reference_wp.get_junction().get_waypoints(carla.LaneType.Driving):\n                    if get_road_key(junction_wps[index]) == get_road_key(reference_wp):\n                        wps.append(junction_wps[index])\n            return wps\n\n        def get_wp_pairs(old_wps_, new_wps_, dist):\n            wp_pairs = []\n\n            unmapped_wps = new_wps_\n            for old_wp_ in old_wps_:\n                mapped = False\n                location = old_wp_.transform.location\n                for new_wp_ in unmapped_wps:\n                    if location.distance(new_wp_.transform.location) < dist:\n                        unmapped_wps.remove(new_wp_)\n                        wp_pairs.append([old_wp_, new_wp_])\n                        mapped = True\n                        break\n\n                if not mapped:\n                    wp_pairs.append([old_wp_, None])\n\n            for unmapped_wp in unmapped_wps:\n                wp_pairs.append([None, unmapped_wp])\n\n            return wp_pairs\n\n        def is_remapping_needed(current_wp, prev_wp):\n            \"\"\"The road dict mapping is needed if \"\"\"\n            # If the ego just exitted a junction, remap isn't needed\n            if self._is_junction(prev_wp):\n                return False\n\n            # If the road changes, remap\n            if get_road_key(prev_wp) != get_road_key(current_wp):\n                return True\n\n            # Some roads have starting / ending lanes in the middle. Remap if that is detected\n            prev_wps = get_same_dir_lanes(prev_wp)\n            current_wps = get_same_dir_lanes(current_wp)\n            if len(prev_wps) != len(current_wps):\n                return True\n\n            return False\n\n        def is_road_dict_unchanging(wp_pairs):\n            \"\"\"Sometimes 'monitor_topology_changes' has already done the necessary changes\"\"\"\n            road_dict_keys = list(self._road_dict)\n            if len(wp_pairs) != len(road_dict_keys):\n                return False\n\n            for _, new_wp in wp_pairs:\n                if get_lane_key(new_wp) not in road_dict_keys:\n                    return False\n            return True\n\n        if prev_route_index == self._route_index:\n            return\n        route_wp = self._route[self._route_index]\n        prev_route_wp = self._route[prev_route_index]\n\n        if not is_remapping_needed(route_wp, prev_route_wp):\n            return\n\n        new_road_dict = {}\n        old_wps = get_lane_waypoints(prev_route_wp, 1)\n        new_wps = get_lane_waypoints(route_wp, 0)\n        check_dist = 1.1 * route_wp.transform.location.distance(prev_route_wp.transform.location)\n        wp_pairs = get_wp_pairs(old_wps, new_wps, check_dist)\n        # TODO: These pairs are sometimes wrong as some fake intersections have overlapping lanes (highway entries)\n\n        if is_road_dict_unchanging(wp_pairs):\n            return\n\n        for old_wp, new_wp in wp_pairs:\n            old_key = get_lane_key(old_wp)\n            new_key = get_lane_key(new_wp)\n\n            # Lane has ended / started, no need to remap it\n            if not new_wp or not old_wp:\n                continue\n\n            if self.debug:\n                draw_arrow(self._world, old_wp.transform.location, new_wp.transform.location, DEBUG_MEDIUM, DEBUG_ROAD, True)\n\n            # Check that the lane is part of the road dictionary\n            if old_key in list(self._road_dict):\n                new_road_dict[new_key] = self._road_dict[old_key]\n                self._road_dict.pop(old_key)\n                continue\n\n        # Add the rest of the unmapped road sources, mainly those created forward at lanes that are starting\n        for lane_key in list(self._road_dict):\n            new_road_dict[lane_key] = self._road_dict.pop(lane_key)\n\n        self._road_dict = new_road_dict\n\n    def _update_junction_actors(self):\n        \"\"\"\n        Handles an actor depending on their previous state. Actors entering the junction have its exit\n        monitored through their waypoint. When they exit, they are either moved to a connecting junction,\n        or added to the exit dictionary. Actors that exited the junction will stop after a certain distance\n        \"\"\"\n        if len(self._active_junctions) == 0:\n            return\n\n        max_index = len(self._active_junctions) - 1\n        for i, junction in enumerate(self._active_junctions):\n            if self.debug:\n                route_keys = junction.route_entry_keys + junction.route_exit_keys\n                route_oppo_keys = junction.opposite_entry_keys + junction.opposite_exit_keys\n                for wp in junction.entry_wps + junction.exit_wps:\n                    if get_lane_key(wp) in route_keys:\n                        draw_point(self._world, wp.transform.location, DEBUG_MEDIUM, DEBUG_ROAD, False)\n                    elif get_lane_key(wp) in route_oppo_keys:\n                        draw_point(self._world, wp.transform.location, DEBUG_MEDIUM, DEBUG_OPPOSITE, False)\n                    else:\n                        draw_point(self._world, wp.transform.location, DEBUG_MEDIUM, DEBUG_JUNCTION, False)\n\n            actor_dict = junction.actor_dict\n            exit_dict = junction.exit_dict\n\n            scenario_entry_actor_ids = []\n            if self._scenario_junction_entry:\n                for source in junction.entry_sources:\n                    if get_lane_key(source.wp) in junction.route_entry_keys:\n                        scenario_entry_actor_ids.extend([x.id for x in source.actors])\n\n            for actor in list(actor_dict):\n                if actor not in actor_dict:\n                    continue  # Actor was removed during the loop\n                location = CarlaDataProvider.get_location(actor)\n                if not location:\n                    continue\n\n                state, exit_lane_key, _ = actor_dict[actor].values()\n                if self.debug:\n                    string = 'J' + str(i+1) + '_' + state[:2]\n                    draw_string(self._world, location, string, DEBUG_JUNCTION, False)\n\n                # Special scenario actors. Treat them as road actors\n                if actor.id in scenario_entry_actor_ids:\n                    self._set_road_actor_speed(location, actor)\n\n                # Monitor its entry\n                elif state == JUNCTION_ENTRY:\n                    actor_wp = self._map.get_waypoint(location)\n                    if self._is_junction(actor_wp) and junction.contains_wp(actor_wp):\n                        if junction.clear_middle:\n                            self._destroy_actor(actor)  # Don't clutter the junction if a junction scenario is active\n                            continue\n                        actor_dict[actor]['state'] = JUNCTION_MIDDLE\n\n                # Monitor its exit and destroy an actor if needed\n                elif state == JUNCTION_MIDDLE:\n                    actor_wp = self._map.get_waypoint(location)\n                    actor_lane_key = get_lane_key(actor_wp)\n                    if not self._is_junction(actor_wp) and actor_lane_key in exit_dict:\n                        if i < max_index and actor_lane_key in junction.route_exit_keys:\n                            # Exited through a connecting lane in the route direction.\n                            self._remove_actor_info(actor)\n                            other_junction = self._active_junctions[i+1]\n                            self._add_actor_dict_element(other_junction.actor_dict, actor)\n\n                        elif i > 0 and actor_lane_key in junction.opposite_exit_keys:\n                            # Exited through a connecting lane in the opposite direction.\n                            # THIS SHOULD NEVER HAPPEN, an entry source should have already added it.\n                            other_junction = self._active_junctions[i-1]\n                            if actor not in other_junction.actor_dict:\n                                self._remove_actor_info(actor)\n                                self._add_actor_dict_element(other_junction.actor_dict, actor, at_oppo_entry_lane=True)\n\n                        else:\n                            # Check the lane capacity\n                            exit_dict[actor_lane_key]['ref_wp'] = actor_wp\n                            actor_dict[actor]['state'] = JUNCTION_EXIT\n                            actor_dict[actor]['exit_lane_key'] = actor_lane_key\n\n                            actors = exit_dict[actor_lane_key]['actors']\n                            if len(actors) > 0 and len(actors) >= exit_dict[actor_lane_key]['max_actors']:\n                                self._destroy_actor(actors[0])  # This is always the front most vehicle\n                            actors.append(actor)\n\n                # Change them to \"road mode\" when far enough from the junction\n                elif state == JUNCTION_EXIT:\n                    distance = location.distance(exit_dict[exit_lane_key]['ref_wp'].transform.location)\n                    if distance > exit_dict[exit_lane_key]['max_distance']:\n                        if exit_lane_key in junction.route_exit_keys:\n                            actor_dict[actor]['state'] = JUNCTION_EXIT_ROAD\n                        else:\n                            self._actors_speed_perc[actor] = 0\n                            actor_dict[actor]['state'] = JUNCTION_EXIT_INACTIVE\n\n                # Set them ready to move so that the ego can smoothly cross the junction\n                elif state == JUNCTION_EXIT_ROAD:\n                    self._set_road_actor_speed(location, actor, multiplier=1.5)\n                    pass\n\n                # Wait\n                elif state == JUNCTION_EXIT_INACTIVE:\n                    pass\n\n    def _update_opposite_actors(self):\n        \"\"\"\n        Updates the opposite actors. This involves tracking their position,\n        removing them if too far behind the ego.\n        \"\"\"\n        opposite_dist = max(self._opposite_sources_dist, self._opposite_spawn_dist)\n        for actor in list(self._opposite_actors):\n            location = CarlaDataProvider.get_location(actor)\n            if not location:\n                continue\n            if self.debug:\n                draw_string(self._world, location, 'O', DEBUG_OPPOSITE, False)\n\n            distance = location.distance(self._ego_wp.transform.location)\n            if distance > opposite_dist and self._is_location_behind_ego(location):\n                self._destroy_actor(actor)\n                continue\n\n            # Ending / starting lanes create issues as the lane width gradually decreases until reaching 0,\n            # where the lane starts / ends. Set their speed to 0, and they'll eventually dissapear.\n            actor_wp = self._map.get_waypoint(location)\n            if actor_wp.lane_width < self._lane_width_threshold:\n                self._actors_speed_perc[actor] = 0\n\n    def _set_actors_speed(self):\n        \"\"\"\n        Sets the speed of all the BA actors, using the ego's target speed as reference.\n        This avoids issues with the speed limits, as newly created actors don't have that information\n        \"\"\"\n        for actor, percentage in self._actors_speed_perc.items():\n            speed = self._ego_target_speed * percentage / 100\n            if self._scenario_max_speed:\n                speed = min(speed, self._scenario_max_speed)\n\n            # TODO: Fix very high speed traffic\n            speed = min(speed, 90)\n            self._tm.set_desired_speed(actor, speed)\n\n    def _remove_actor_info(self, actor):\n        \"\"\"Removes all the references of the actor\"\"\"\n\n        for lane in self._road_dict:\n            if actor in self._road_dict[lane].actors:\n                self._road_dict[lane].actors.remove(actor)\n                break\n\n        if actor in self._opposite_actors:\n            self._opposite_actors.remove(actor)\n        if actor in self._scenario_stopped_actors:\n            self._scenario_stopped_actors.remove(actor)\n        if actor in self._scenario_stopped_back_actors:\n            self._scenario_stopped_back_actors.remove(actor)\n\n        for opposite_source in self._opposite_sources:\n            if actor in opposite_source.actors:\n                opposite_source.actors.remove(actor)\n                break\n\n        for junction in self._active_junctions:\n            junction.actor_dict.pop(actor, None)\n\n            for entry_source in junction.entry_sources:\n                if actor in entry_source.actors:\n                    entry_source.actors.remove(actor)\n                    break\n\n            for exit_keys in junction.exit_dict:\n                exit_actors = junction.exit_dict[exit_keys]['actors']\n                if actor in exit_actors:\n                    exit_actors.remove(actor)\n                    break\n\n        self._actors_speed_perc.pop(actor, None)\n        if actor in self._all_actors:\n            self._all_actors.remove(actor)\n\n    def _destroy_actor(self, actor):\n        \"\"\"Destroy the actor and all its references\"\"\"\n        self._remove_actor_info(actor)\n        try:\n            actor.set_autopilot(False, self._tm_port)\n            actor.destroy()\n        except RuntimeError:\n            pass\n\n    def _update_ego_data(self):\n        \"\"\"\n        Checks the ego location to see if it has moved closer to the next route waypoint,\n        updating its information. This never checks for backwards movements to avoid unnedded confusion.\n        It also saves its max speed, used as a baseline for all BA vehicles.\n        \"\"\"\n        location = CarlaDataProvider.get_location(self._ego_actor)\n\n        prev_index = self._route_index\n        for index in range(self._route_index, min(self._route_index + self._route_buffer, self._route_length)):\n            route_wp = self._route[index]\n\n            route_wp_dir = route_wp.transform.get_forward_vector()    # Waypoint's forward vector\n            veh_wp_dir = location - route_wp.transform.location       # vector waypoint - vehicle\n            dot_ve_wp = veh_wp_dir.x * route_wp_dir.x + veh_wp_dir.y * route_wp_dir.y + veh_wp_dir.z * route_wp_dir.z\n\n            if dot_ve_wp > 0:\n                self._route_index = index\n\n        # Monitor route changes for those scenario that remove and readd a specific lane\n        if self._scenario_removed_lane:\n            for i in range(prev_index, self._route_index):\n                option_1 = self._route_options[i]\n                option_2 = self._route_options[i+1]\n                if option_1 == RoadOption.CHANGELANELEFT or option_2 == RoadOption.CHANGELANELEFT:\n                    loc_1 = self._route[i].transform.location\n                    loc_2 = self._route[i+1].transform.location\n                    if abs(loc_1.distance(loc_2)) > 2.5:  # Lane offset plus a bit forward\n                        self._scenario_remove_lane_offset += 1\n                elif option_1 == RoadOption.CHANGELANERIGHT or option_2 == RoadOption.CHANGELANERIGHT:\n                    loc_1 = self._route[i].transform.location\n                    loc_2 = self._route[i+1].transform.location\n                    if abs(loc_1.distance(loc_2)) > 2.5:  # Lane offset plus a bit forward\n                        self._scenario_remove_lane_offset -= 1\n\n        self._ego_wp = self._route[self._route_index]\n        self._ego_key = get_lane_key(self._ego_wp)\n        self._ego_target_speed = self._ego_actor.get_speed_limit()\n\n        if self.debug:\n            string = 'EGO_' + self._ego_state[0].upper()\n            debug_name = DEBUG_ROAD if self._ego_state == EGO_ROAD else DEBUG_JUNCTION\n            draw_string(self._world, location, string, debug_name, False)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/background_activity_parametrizer.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule used to parse all the route and scenario configuration parameters.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import (ChangeRoadBehavior,\n                                              ChangeOppositeBehavior,\n                                              ChangeJunctionBehavior)\n\ndef get_parameter(config, name):\n    if name in config.other_parameters:\n        return float(config.other_parameters[name]['value'])\n    else:\n        return None\n\nclass BackgroundActivityParametrizer(BasicScenario):\n    \"\"\"\n    This class holds everything required to change the parameters of the background activity.\n    Mainly used to change its behavior when, for example, moving from a highway into the city,\n    where we might want a different BA behavior.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        # Road\n        self._num_front_vehicles = get_parameter(config, \"num_front_vehicles\")\n        self._num_back_vehicles = get_parameter(config, \"num_back_vehicles\")\n        self._road_spawn_dist = get_parameter(config, \"road_spawn_dist\")\n\n        # Opposite\n        self._opposite_source_dist = get_parameter(config, \"opposite_source_dist\")\n        self._opposite_max_actors = get_parameter(config, \"opposite_max_actors\")\n        self._opposite_spawn_dist = get_parameter(config, \"opposite_spawn_dist\")\n        self._opposite_active = get_parameter(config, \"opposite_active\")\n\n        # Junction\n        self._junction_source_dist = get_parameter(config, \"junction_source_dist\")\n        self._junction_max_actors = get_parameter(config, \"junction_max_actors\")\n        self._junction_spawn_dist = get_parameter(config, \"junction_spawn_dist\")\n        self._junction_source_perc = get_parameter(config, \"junction_source_perc\")\n\n        super().__init__(\"BackgroundActivityParametrizer\",\n                          ego_vehicles,\n                          config,\n                          world,\n                          debug_mode,\n                          criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n\n        sequence = py_trees.composites.Sequence()\n        sequence.add_child(ChangeRoadBehavior(self._num_front_vehicles, self._num_back_vehicles, self._road_spawn_dist))\n        sequence.add_child(ChangeJunctionBehavior(\n            self._junction_source_dist, self._junction_max_actors, self._junction_spawn_dist, self._junction_source_perc))\n        sequence.add_child(ChangeOppositeBehavior(\n            self._opposite_source_dist, self._opposite_spawn_dist, self._opposite_active))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/basic_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provide BasicScenario, the basic class of all the scenarios.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport operator\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (WaitForBlackboardVariable,\n                                                                               InTimeToArrivalToLocation)\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import WaitForever\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.timer import TimeOut\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import UpdateAllActorControls\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import Criterion\n\n\nclass BasicScenario(object):\n\n    \"\"\"\n    Base class for user-defined scenario\n    \"\"\"\n\n    def __init__(self, name, ego_vehicles, config, world,\n                 debug_mode=False, terminate_on_failure=False, criteria_enable=False):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self.name = name\n        self.ego_vehicles = ego_vehicles\n        self.other_actors = []\n        self.parking_slots = []\n        self.config = config\n        self.world = world\n        self.debug_mode = debug_mode\n        self.terminate_on_failure = terminate_on_failure\n        self.criteria_enable = criteria_enable\n\n        self.route_mode = bool(config.route)\n        self.behavior_tree = None\n        self.criteria_tree = None\n\n        # If no timeout was provided, set it to 60 seconds\n        if not hasattr(self, 'timeout'):\n            self.timeout = 60 \n        if debug_mode:\n            py_trees.logging.level = py_trees.logging.Level.DEBUG\n\n        if not self.route_mode:\n            # Only init env for route mode, avoid duplicate initialization during runtime\n            self._initialize_environment(world)\n            \n        self._initialize_actors(config)\n\n        if CarlaDataProvider.is_runtime_init_mode():\n            world.wait_for_tick()\n        elif CarlaDataProvider.is_sync_mode():\n            world.tick()\n        else:\n            world.wait_for_tick()\n\n        # Main scenario tree\n        self.scenario_tree = py_trees.composites.Parallel(name, policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # Add a trigger and end condition to the behavior to ensure it is only activated when it is relevant\n        self.behavior_tree = py_trees.composites.Sequence()\n\n        trigger_behavior = self._setup_scenario_trigger(config)\n        if trigger_behavior:\n            self.behavior_tree.add_child(trigger_behavior)\n\n        scenario_behavior = self._create_behavior()\n        self.behavior_tree.add_child(scenario_behavior)\n        self.behavior_tree.name = scenario_behavior.name\n\n        end_behavior = self._setup_scenario_end(config)\n        if end_behavior:\n            self.behavior_tree.add_child(end_behavior)\n\n        # Create the lights behavior\n        lights = self._create_lights_behavior()\n        if lights:\n            self.scenario_tree.add_child(lights)\n\n        # Create the weather behavior\n        weather = self._create_weather_behavior()\n        if weather:\n            self.scenario_tree.add_child(weather)\n\n        # And then add it to the main tree\n        self.scenario_tree.add_child(self.behavior_tree)\n\n        # Create the criteria tree (if needed)\n        if self.criteria_enable:\n            criteria = self._create_test_criteria()\n\n            # All the work is done, thanks!\n            if isinstance(criteria, py_trees.composites.Composite):\n                self.criteria_tree = criteria\n\n            # Lazy mode, but its okay, we'll create the parallel behavior tree for you.\n            elif isinstance(criteria, list):\n                for criterion in criteria:\n                    criterion.terminate_on_failure = terminate_on_failure\n\n                self.criteria_tree = py_trees.composites.Parallel(name=\"Test Criteria\",\n                                                                  policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n                self.criteria_tree.add_children(criteria)\n                self.criteria_tree.setup(timeout=1)\n\n            else:\n                raise ValueError(\"WARNING: Scenario {} couldn't be setup, make sure the criteria is either \"\n                                 \"a list or a py_trees.composites.Composite\".format(self.name))\n\n            self.scenario_tree.add_child(self.criteria_tree)\n\n        # Create the timeout behavior\n        self.timeout_node = self._create_timeout_behavior()\n        if self.timeout_node:\n            self.scenario_tree.add_child(self.timeout_node)\n\n        # Add other nodes\n        self.scenario_tree.add_child(UpdateAllActorControls())\n\n        self.scenario_tree.setup(timeout=1)\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Default initialization of weather and road friction.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n\n        # Set the appropriate weather conditions\n        world.set_weather(self.config.weather)\n\n        # Set the appropriate road friction\n        if self.config.friction is not None:\n            friction_bp = world.get_blueprint_library().find('static.trigger.friction')\n            extent = carla.Location(1000000.0, 1000000.0, 1000000.0)\n            friction_bp.set_attribute('friction', str(self.config.friction))\n            friction_bp.set_attribute('extent_x', str(extent.x))\n            friction_bp.set_attribute('extent_y', str(extent.y))\n            friction_bp.set_attribute('extent_z', str(extent.z))\n\n            # Spawn Trigger Friction\n            transform = carla.Transform()\n            transform.location = carla.Location(-10000.0, -10000.0, 0.0)\n            world.spawn_actor(friction_bp, transform)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        if config.other_actors:\n            new_actors = CarlaDataProvider.request_new_actors(config.other_actors)\n            if not new_actors:\n                raise Exception(\"Error: Unable to add actors\")\n\n            for new_actor in new_actors:\n                self.other_actors.append(new_actor)\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"\n        This function creates a trigger maneuver, that has to be finished before the real scenario starts.\n        This implementation focuses on the first available ego vehicle.\n\n        The function can be overloaded by a user implementation inside the user-defined scenario class.\n        \"\"\"\n        if config.trigger_points and config.trigger_points[0]:\n            start_location = config.trigger_points[0].location\n        else:\n            return None\n\n        # Scenario is not part of a route, wait for the ego to move\n        if not self.route_mode or config.route_var_name is None:\n            return InTimeToArrivalToLocation(self.ego_vehicles[0], 2.0, start_location)\n\n        # Scenario is part of a route.\n        check_name = \"WaitForBlackboardVariable: {}\".format(config.route_var_name)\n        return WaitForBlackboardVariable(config.route_var_name, True, False, name=check_name)\n\n    def _setup_scenario_end(self, config):\n        \"\"\"\n        This function adds and additional behavior to the scenario, which is triggered\n        after it has ended. The Blackboard variable is set to False to indicate the scenario has ended.\n        The function can be overloaded by a user implementation inside the user-defined scenario class.\n        \"\"\"\n        if not self.route_mode or config.route_var_name is None:\n            return None\n\n        # Scenario is part of a route.\n        end_sequence = py_trees.composites.Sequence()\n        name = \"Reset Blackboard Variable: {} \".format(config.route_var_name)\n        end_sequence.add_child(py_trees.blackboard.SetBlackboardVariable(name, config.route_var_name, False))\n        end_sequence.add_child(WaitForever())  # scenario can't stop the route\n\n        return end_sequence\n\n    def _create_behavior(self):\n        \"\"\"\n        Pure virtual function to setup user-defined scenario behavior\n        \"\"\"\n        raise NotImplementedError(\n            \"This function is re-implemented by all scenarios\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Pure virtual function to setup user-defined evaluation criteria for the\n        scenario\n        \"\"\"\n        raise NotImplementedError(\n            \"This function is re-implemented by all scenarios\"\n            \"If this error becomes visible the class hierarchy is somehow broken\")\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Default empty initialization of the weather behavior,\n        responsible of controlling the weather during the simulation.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        pass\n\n    def _create_lights_behavior(self):\n        \"\"\"\n        Default empty initialization of the lights behavior,\n        responsible of controlling the street lights during the simulation.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        pass\n\n    def _create_timeout_behavior(self):\n        \"\"\"\n        Default initialization of the timeout behavior.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        return TimeOut(self.timeout, name=\"TimeOut\")  # Timeout node\n\n    def change_control(self, control):  # pylint: disable=no-self-use\n        \"\"\"\n        This is a function that changes the control based on the scenario determination\n        :param control: a carla vehicle control\n        :return: a control to be changed by the scenario.\n\n        Note: This method should be overriden by the user-defined scenario behavior\n        \"\"\"\n        return control\n\n    def get_criteria(self):\n        \"\"\"\n        Return the list of test criteria, including all the leaf nodes.\n        Some criteria might have trigger conditions, which have to be filtered out.\n        \"\"\"\n        criteria = []\n        if not self.criteria_tree:\n            return criteria\n\n        criteria_nodes = self._extract_nodes_from_tree(self.criteria_tree)\n        for criterion in criteria_nodes:\n            if isinstance(criterion, Criterion):\n                criteria.append(criterion)\n\n        return criteria\n\n    def _extract_nodes_from_tree(self, tree):  # pylint: disable=no-self-use\n        \"\"\"\n        Returns the list of all nodes from the given tree\n        \"\"\"\n        node_list = [tree]\n        more_nodes_exist = True\n        while more_nodes_exist:\n            more_nodes_exist = False\n            for node in node_list:\n                if node.children:\n                    node_list.remove(node)\n                    more_nodes_exist = True\n                    for child in node.children:\n                        node_list.append(child)\n\n        if len(node_list) == 1 and isinstance(node_list[0], py_trees.composites.Parallel):\n            return []\n\n        return node_list\n\n    def terminate(self):\n        \"\"\"\n        This function sets the status of all leaves in the scenario tree to INVALID\n        \"\"\"\n        # Get list of all nodes in the tree\n        node_list = self._extract_nodes_from_tree(self.scenario_tree)\n\n        # Set status to INVALID\n        for node in node_list:\n            node.terminate(py_trees.common.Status.INVALID)\n\n        # Cleanup all instantiated controllers\n        actor_dict = {}\n        try:\n            check_actors = operator.attrgetter(\"ActorsWithController\")\n            actor_dict = check_actors(py_trees.blackboard.Blackboard())\n        except AttributeError:\n            pass\n        for actor_id in actor_dict:\n            actor_dict[actor_id].reset()\n        py_trees.blackboard.Blackboard().set(\"ActorsWithController\", {}, overwrite=True)\n\n    def remove_all_actors(self):\n        \"\"\"\n        Remove all actors\n        \"\"\"\n        if not hasattr(self, 'other_actors'):\n            return\n        for i, _ in enumerate(self.other_actors):\n            if self.other_actors[i] is not None:\n                if CarlaDataProvider.actor_id_exists(self.other_actors[i].id):\n                    CarlaDataProvider.remove_actor_by_id(self.other_actors[i].id)\n                self.other_actors[i] = None\n        self.other_actors = []\n\n    def get_parking_slots(self):\n        \"\"\"\n        Returns occupied parking slots.\n        \"\"\"\n        return self.parking_slots\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/blocked_intersection.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario with low visibility, the ego performs a turn only to find out that the end is blocked by another vehicle.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport carla\nimport py_trees\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      Idle,\n                                                                      ScenarioTimeout,\n                                                                      ActorTransformSetter,\n                                                                      HandBrakeVehicle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\nfrom srunner.tools.scenario_helper import generate_target_waypoint_in_route\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\nclass BlockedIntersection(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which,\n    the ego performs a turn only to find out that the end is blocked by another vehicle.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(self._trigger_location)\n\n        self._blocker_distance = 5\n        self._trigger_distance = 13\n        self._stop_time = 10\n\n        self._scenario_timeout = 240\n\n        self._blocker_transform = None\n\n        super().__init__(\"BlockedIntersection\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        waypoint = generate_target_waypoint_in_route(self._reference_waypoint, config.route)\n        waypoint = waypoint.next(self._blocker_distance)[0]\n\n        self._blocker_transform = waypoint.transform\n\n        # Spawn the blocker vehicle\n        blocker = CarlaDataProvider.request_new_actor(\n            \"vehicle.*.*\", self._blocker_transform,\n            attribute_filter={'base_type': 'car', 'has_lights': True, 'special_type': ''}\n        )\n        if blocker is None:\n            raise Exception(\"Couldn't spawn the blocker vehicle\")\n        self.other_actors.append(blocker)\n\n        blocker.set_simulate_physics(False)\n        blocker.set_location(self._blocker_transform.location + carla.Location(z=-200))\n\n        lights = blocker.get_light_state()\n        lights |= carla.VehicleLightState.Brake\n        blocker.set_light_state(carla.VehicleLightState(lights))\n\n    def _create_behavior(self):\n        \"\"\"\n        Just wait for a while after the ego closes in on the blocker, then remove it.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"BlockedIntersection\")\n\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[],\n                remove_exits=[],\n                stop_entries=True,\n                extend_road_exit=0\n            ))\n        # Ego go behind the blocker\n        main_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        behavior = py_trees.composites.Sequence(name=\"Approach and Wait\")\n        behavior.add_child(ActorTransformSetter(self.other_actors[0], self._blocker_transform, True))\n        behavior.add_child(HandBrakeVehicle(self.other_actors[0], 1))\n        behavior.add_child(InTriggerDistanceToVehicle(\n            self.other_actors[-1], self.ego_vehicles[0], self._trigger_distance))\n        behavior.add_child(Idle(self._stop_time))\n        main_behavior.add_child(behavior)\n\n        sequence.add_child(main_behavior)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/change_lane.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nChange lane scenario:\n\nThe scenario realizes a driving behavior, in which the user-controlled ego vehicle\nfollows a fast driving car on the highway. There's a slow car driving in great distance to the fast vehicle.\nAt one point the fast vehicle is changing the lane to overtake a slow car, which is driving on the same lane.\n\nThe ego vehicle doesn't \"see\" the slow car before the lane change of the fast car, therefore it hast to react\nfast to avoid an collision. There are two options to avoid an accident:\nThe ego vehicle adjusts its velocity or changes the lane as well.\n\"\"\"\n\nimport random\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      StopVehicle,\n                                                                      LaneChange,\n                                                                      WaypointFollower,\n                                                                      Idle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle, StandStill\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass ChangeLane(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a \"change lane\" scenario involving three vehicles.\n    There are two vehicles driving in the same direction on the highway: A fast car and a slow car in front.\n    The fast car will change the lane, when it is close to the slow car.\n\n    The ego vehicle is driving right behind the fast car.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 1200\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=600):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n\n        If randomize is True, the scenario parameters are randomized\n        \"\"\"\n        self.timeout = timeout\n        self._map = CarlaDataProvider.get_map()\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        self._fast_vehicle_velocity = 70\n        self._slow_vehicle_velocity = 0\n        self._change_lane_velocity = 15\n\n        self._slow_vehicle_distance = 100\n        self._fast_vehicle_distance = 20\n        self._trigger_distance = 30\n        self._max_brake = 1\n\n        self.direction = 'left'  # direction of lane change\n        self.lane_check = 'true'  # check whether a lane change is possible\n\n        super(ChangeLane, self).__init__(\"ChangeLane\",\n                                         ego_vehicles,\n                                         config,\n                                         world,\n                                         debug_mode,\n                                         criteria_enable=criteria_enable)\n\n        if randomize:\n            self._fast_vehicle_distance = random.randint(10, 51)\n            self._fast_vehicle_velocity = random.randint(100, 201)\n            self._slow_vehicle_velocity = random.randint(1, 6)\n\n    def _initialize_actors(self, config):\n\n        # add actors from xml file\n        for actor in config.other_actors:\n            vehicle = CarlaDataProvider.request_new_actor(actor.model, actor.transform)\n            self.other_actors.append(vehicle)\n            vehicle.set_simulate_physics(enabled=False)\n\n        # fast vehicle, tesla\n        # transform visible\n        fast_car_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._fast_vehicle_distance)\n        self.fast_car_visible = carla.Transform(\n            carla.Location(fast_car_waypoint.transform.location.x,\n                           fast_car_waypoint.transform.location.y,\n                           fast_car_waypoint.transform.location.z + 1),\n            fast_car_waypoint.transform.rotation)\n\n        # slow vehicle, vw\n        # transform visible\n        slow_car_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._slow_vehicle_distance)\n        self.slow_car_visible = carla.Transform(\n            carla.Location(slow_car_waypoint.transform.location.x,\n                           slow_car_waypoint.transform.location.y,\n                           slow_car_waypoint.transform.location.z),\n            slow_car_waypoint.transform.rotation)\n\n    def _create_behavior(self):\n\n        # sequence vw\n        # make visible\n        sequence_vw = py_trees.composites.Sequence(\"VW T2\")\n        vw_visible = ActorTransformSetter(self.other_actors[1], self.slow_car_visible)\n        sequence_vw.add_child(vw_visible)\n\n        # brake, avoid rolling backwarts\n        brake = StopVehicle(self.other_actors[1], self._max_brake)\n        sequence_vw.add_child(brake)\n        sequence_vw.add_child(Idle())\n\n        # sequence tesla\n        # make visible\n        sequence_tesla = py_trees.composites.Sequence(\"Tesla\")\n        tesla_visible = ActorTransformSetter(self.other_actors[0], self.fast_car_visible)\n        sequence_tesla.add_child(tesla_visible)\n\n        # drive fast towards slow vehicle\n        just_drive = py_trees.composites.Parallel(\"DrivingTowardsSlowVehicle\",\n                                                  policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        tesla_driving_fast = WaypointFollower(self.other_actors[0], self._fast_vehicle_velocity)\n        just_drive.add_child(tesla_driving_fast)\n        distance_to_vehicle = InTriggerDistanceToVehicle(\n            self.other_actors[1], self.other_actors[0], self._trigger_distance)\n        just_drive.add_child(distance_to_vehicle)\n        sequence_tesla.add_child(just_drive)\n\n        # change lane\n        lane_change_atomic = LaneChange(self.other_actors[0], distance_other_lane=200)\n        sequence_tesla.add_child(lane_change_atomic)\n        sequence_tesla.add_child(Idle())\n\n        # ego vehicle\n        # end condition\n        endcondition = py_trees.composites.Parallel(\"Waiting for end position of ego vehicle\",\n                                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n        endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[1],\n                                                        self.ego_vehicles[0],\n                                                        distance=20,\n                                                        name=\"FinalDistance\")\n        endcondition_part2 = StandStill(self.ego_vehicles[0], name=\"FinalSpeed\", duration=1)\n        endcondition.add_child(endcondition_part1)\n        endcondition.add_child(endcondition_part2)\n\n        # build tree\n        root = py_trees.composites.Parallel(\"Parallel Behavior\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(sequence_vw)\n        root.add_child(sequence_tesla)\n        root.add_child(endcondition)\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/construction_crash_vehicle.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nObject crash without prior vehicle action scenario:\nThe scenario realizes the user controlled ego vehicle\nmoving along the road and encountering a construction setup.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      ActorTransformSetter,\n                                                                      SwitchWrongDirectionTest,\n                                                                      ScenarioTimeout,\n                                                                      Idle, WaitForever,\n                                                                      OppositeActorFlow)\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import (RemoveRoadLane,\n                                              ReAddRoadLane,\n                                              SetMaxSpeed,\n                                              ChangeOppositeBehavior)\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\nclass ConstructionObstacle(BasicScenario):\n    \"\"\"\n    This class holds everything required for a construction scenario\n    The ego vehicle is passing through a road and encounters\n    a stationary rectangular construction cones setup and traffic warning,\n    forcing it to lane change.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False,\n                 criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_distance = 30\n        self._opposite_wait_duration = 5\n        self._end_distance = 50\n\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._construction_wp = None\n\n        self._construction_transforms = []\n\n        self._distance = get_value_parameter(config, 'distance', float, 100)\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        super().__init__(\"ConstructionObstacle\", ego_vehicles, config, world, debug_mode, False, criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"Creates all props part of the construction\"\"\"\n        self._spawn_side_prop(self._reference_waypoint)\n\n        wps = self._reference_waypoint.next(self._distance)\n        if not wps:\n            raise ValueError(\"Couldn't find a viable position to set up the construction actors\")\n        self._construction_wp = wps[0]\n        self._create_construction_setup(self._construction_wp.transform, self._reference_waypoint.lane_width)\n\n        self._end_wp = self._move_waypoint_forward(self._construction_wp, self._end_distance)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_side_prop(self, wp):\n        \"\"\"Spawn the accident indication signal\"\"\"\n        prop_wp = wp\n        while True:\n            if self._direction == \"right\":\n                wp = prop_wp.get_right_lane()\n            else:\n                wp = prop_wp.get_left_lane()\n            if wp is None or wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n                break\n            prop_wp = wp\n\n        displacement = 0.3 * prop_wp.lane_width\n        r_vec = prop_wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.2)\n        spawn_transform.rotation.yaw += 90\n        signal_prop = CarlaDataProvider.request_new_actor('static.prop.warningconstruction', spawn_transform)\n        if not signal_prop:\n            raise ValueError(\"Couldn't spawn the indication prop asset\")\n        signal_prop.set_simulate_physics(False)\n        self.other_actors.append(signal_prop)\n\n    def _create_cones_side(self, start_transform, forward_vector, z_inc=0, cone_length=0, cone_offset=0):\n        \"\"\"Creates the cones at the side\"\"\"\n        _dist = 0\n        while _dist < (cone_length * cone_offset):\n            # Move forward\n            _dist += cone_offset\n            forward_dist = carla.Vector3D(0, 0, 0) + forward_vector * _dist\n\n            location = start_transform.location + forward_dist\n            location.z += z_inc\n            spawn_transform = carla.Transform(location, start_transform.rotation)\n            spawn_transform.location.z -= 200\n            cone_transform = carla.Transform(location, start_transform.rotation)\n\n            cone = CarlaDataProvider.request_new_actor('static.prop.constructioncone', spawn_transform)\n            cone.set_simulate_physics(False)\n            self.other_actors.append(cone)\n\n            self._construction_transforms.append([cone, cone_transform])\n\n    def _create_construction_setup(self, start_transform, lane_width):\n        \"\"\"Create construction setup\"\"\"\n\n        _initial_offset = {'cones': {'yaw': 270, 'k': 0.85 * lane_width / 2.0},\n                           'warning_sign': {'yaw': 180, 'k': 5, 'z': 0},\n                           'debris': {'yaw': 0, 'k': 2, 'z': 1}}\n        _prop_names = {'warning_sign': 'static.prop.trafficwarning',\n                       'debris': 'static.prop.dirtdebris02'}\n\n        _perp_angle = 90\n        _setup = {'lengths': [4, 3], 'offsets': [2, 1]}\n        _z_increment = 0.1\n\n        # Traffic warning and debris\n        for key, value in _initial_offset.items():\n            if key == 'cones':\n                continue\n            transform = carla.Transform(\n                start_transform.location,\n                start_transform.rotation)\n            transform.rotation.yaw += value['yaw']\n            transform.location += value['k'] * \\\n                transform.rotation.get_forward_vector()\n            transform.location.z += value['z']\n            transform.rotation.yaw += _perp_angle\n\n            spawn_transform = carla.Transform(transform.location, transform.rotation)\n            spawn_transform.location.z -= 200\n            static = CarlaDataProvider.request_new_actor(\n                _prop_names[key], spawn_transform)\n            static.set_simulate_physics(False)\n            self.other_actors.append(static)\n\n            self._construction_transforms.append([static, transform])\n\n        # Cones\n        side_transform = carla.Transform(\n            start_transform.location,\n            start_transform.rotation)\n        side_transform.rotation.yaw += _perp_angle\n        offset_vec = _initial_offset['cones']['k'] * side_transform.rotation.get_forward_vector()\n        if self._direction == 'right':\n            side_transform.location -= offset_vec\n        else:\n            side_transform.location += offset_vec\n\n        side_transform.rotation.yaw += _initial_offset['cones']['yaw']\n\n        for i in range(len(_setup['lengths'])):\n            self._create_cones_side(\n                side_transform,\n                forward_vector=side_transform.rotation.get_forward_vector(),\n                z_inc=_z_increment,\n                cone_length=_setup['lengths'][i],\n                cone_offset=_setup['offsets'][i])\n            side_transform.location += side_transform.get_forward_vector() * \\\n                _setup['lengths'][i] * _setup['offsets'][i]\n            if i == 0 and self._direction == 'left':\n                side_transform.rotation.yaw -= _perp_angle\n            else:\n                side_transform.rotation.yaw += _perp_angle\n\n    def _create_behavior(self):\n        \"\"\"\n        Remove the lane that would collide with the construction and add the construction props.\n        Wait until the ego is close to the construction (and a bit more) before changing the side traffic\n        Readd the traffic at the end\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"ConstructionObstacle\")\n        if self.route_mode:\n            root.add_child(RemoveRoadLane(self._reference_waypoint))\n\n        for actor, transform in self._construction_transforms:\n            root.add_child(ActorTransformSetter(actor, transform, True))\n    \n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._construction_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._opposite_wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n            root.add_child(ReAddRoadLane(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass ConstructionObstacleTwoWays(ConstructionObstacle):\n    \"\"\"\n    Variation of ConstructionObstacle where the ego has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Remove the lane that would collide with the construction and add the construction props.\n        Wait until the ego is close to the construction (and a bit more) before changing the opposite traffic\n        Readd the traffic at the end, and allow the ego to invade the opposite lane by deactivating the criteria\n        \"\"\"\n        reference_wp = self._construction_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"ConstructionObstacleTwoWays\")\n        if self.route_mode:\n            root.add_child(RemoveRoadLane(self._reference_waypoint))\n\n        for actor, transform in self._construction_transforms:\n            root.add_child(ActorTransformSetter(actor, transform, True))\n    \n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._construction_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._opposite_wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n            behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n            root.add_child(ReAddRoadLane(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/control_loss.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nControl Loss Vehicle scenario:\n\nThe scenario realizes that the vehicle looses control due to\nbad road conditions, etc. and checks to see if the vehicle\nregains control and corrects it's course.\n\"\"\"\n\nfrom numpy import random\nimport py_trees\nimport operator\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import AddNoiseToRouteEgo\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance, InTriggerDistanceToLocation\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass ControlLoss(BasicScenario):\n\n    \"\"\"\n    Implementation of \"Control Loss Vehicle\" (Traffic Scenario 01)\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self.timeout = timeout\n        self._randomize = randomize\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._map = CarlaDataProvider.get_map()\n        self._end_distance = 110\n\n        # Friction loss tends to have a much stronger steering compoenent then a throttle one\n        self._throttle_mean = 0.03\n        self._throttle_std = 0.01\n        self._steer_mean = 0.055\n        self._steer_std = 0.015\n\n        self._trigger_dist = 2\n\n        super().__init__(\"ControlLoss\", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        if self._randomize:\n            self._distance = list(self._rng.randint(low=10, high=80, size=3))\n            self._distance = sorted(self._distance)\n            self._offset = list(2 * random.rand(3) - 1)\n        else:\n            self._distance = [14, 48, 74]\n            self._offset = [-0.6, 0.8, 0.2]\n\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Get the debris locations\n        first_wp, _ = get_waypoint_in_distance(self._reference_waypoint, self._distance[0])\n        first_ground_loc = self.world.ground_projection(first_wp.transform.location + carla.Location(z=1), 2)\n        first_loc = first_ground_loc.location if first_ground_loc else first_wp.transform.location\n        self.first_transform = carla.Transform(first_loc, first_wp.transform.rotation)\n\n        second_wp, _ = get_waypoint_in_distance(self._reference_waypoint, self._distance[1])\n        second_ground_loc = self.world.ground_projection(second_wp.transform.location + carla.Location(z=1), 2)\n        second_loc = second_ground_loc.location if second_ground_loc else second_wp.transform.location\n        self.second_transform = carla.Transform(second_loc, second_wp.transform.rotation)\n\n        third_wp, _ = get_waypoint_in_distance(self._reference_waypoint, self._distance[2])\n        third_ground_loc = self.world.ground_projection(third_wp.transform.location + carla.Location(z=1), 2)\n        third_loc = third_ground_loc.location if third_ground_loc else third_wp.transform.location\n        self.third_transform = carla.Transform(third_loc, third_wp.transform.rotation)\n\n        # Spawn the debris\n        first_debris = CarlaDataProvider.request_new_actor(\n            'static.prop.dirtdebris01', self.first_transform, rolename='prop')\n        second_debris = CarlaDataProvider.request_new_actor(\n            'static.prop.dirtdebris01', self.second_transform, rolename='prop')\n        third_debris = CarlaDataProvider.request_new_actor(\n            'static.prop.dirtdebris01', self.third_transform, rolename='prop')\n\n        # Remove their physics\n        first_debris.set_simulate_physics(False)\n        second_debris.set_simulate_physics(False)\n        third_debris.set_simulate_physics(False)\n\n        self.other_actors.append(first_debris)\n        self.other_actors.append(second_debris)\n        self.other_actors.append(third_debris)\n\n    def _get_noise_parameters(self):\n        \"\"\"Randomizes the mean to be either positive or negative\"\"\"\n        return [\n            self._rng.choice([self._throttle_mean, -self._throttle_mean]),\n            self._throttle_std,\n            self._rng.choice([self._steer_mean, -self._steer_mean]),\n            self._steer_std\n        ]\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"control loss vehicle\" scenario.\n        \"\"\"\n        root = py_trees.composites.Parallel(\"ControlLoss\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        sequence = py_trees.composites.Sequence()\n\n        # First debris behavior\n        sequence.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.first_transform.location, self._trigger_dist))\n\n        noise_1 = self._get_noise_parameters()\n        noise_behavior_1 = py_trees.composites.Parallel(\"Add Noise 1\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        noise_behavior_1.add_child(AddNoiseToRouteEgo(self.ego_vehicles[0], *noise_1))\n        noise_behavior_1.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.first_transform.location, self._trigger_dist, operator.gt))\n        sequence.add_child(noise_behavior_1)\n\n        # Second debris behavior\n        sequence.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.second_transform.location, self._trigger_dist))\n\n        noise_2 = self._get_noise_parameters()\n        noise_behavior_2 = py_trees.composites.Parallel(\"Add Noise 2\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        noise_behavior_2.add_child(AddNoiseToRouteEgo(self.ego_vehicles[0], *noise_2))\n        noise_behavior_2.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.second_transform.location, self._trigger_dist, operator.gt))\n        sequence.add_child(noise_behavior_2)\n\n        # Third debris behavior\n        sequence.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.third_transform.location, self._trigger_dist))\n\n        noise_3 = self._get_noise_parameters()\n        noise_behavior_3 = py_trees.composites.Parallel(\"Add Noise 3\", py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        noise_behavior_3.add_child(AddNoiseToRouteEgo(self.ego_vehicles[0], *noise_3))\n        noise_behavior_3.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self.third_transform.location, self._trigger_dist, operator.gt))\n        sequence.add_child(noise_behavior_3)\n\n        end_distance = self._end_distance - self._distance[-1]\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], end_distance))\n\n        root.add_child(sequence)\n        root.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/cross_bicycle_flow.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2022 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which the ego has to cross a flow of bycicles\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import BicycleFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\nfrom agents.navigation.local_planner import RoadOption\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\nclass CrossingBicycleFlow(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle runs a red light\n    in front of the ego, forcing it to react. This vehicles are 'special' ones such as police cars,\n    ambulances or firetrucks.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._start_flow = convert_dict_to_location(config.other_parameters['start_actor_flow'])\n        self._end_dist_flow = 40  # m\n        self._sink_distance = 2\n\n        self._end_distance = 40\n\n        self._signalized_junction = False\n\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        self._green_light_delay = 5\n        self._scenario_timeout = 240\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 10)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [20, 50])\n\n        super().__init__(\"CrossingBicycleFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        junction = starting_wp.get_junction()\n\n        # Get the plan\n        self._source_wp = self._map.get_waypoint(self._start_flow, lane_type=carla.LaneType.Biking)\n        if not self._source_wp or self._source_wp.transform.location.distance(self._start_flow) > 10:\n            raise ValueError(\"Couldn't find a biking lane at the specified location\")\n\n        self._plan = []\n        plan_step = 0\n        wp = self._source_wp\n        while True:\n            next_wps = wp.next(2)\n            if not next_wps:\n                raise ValueError(\"Couldn't find a proper plan for the bicycle flow\")\n            next_wp = next_wps\n            wp = next_wp[0]\n            self._plan.append([next_wp[0], RoadOption.LANEFOLLOW])\n\n            if plan_step == 0 and wp.is_junction:\n                plan_step += 1\n            elif plan_step == 1 and not wp.is_junction:\n                plan_step += 1\n                exit_loc = wp.transform.location\n            elif plan_step == 2 and exit_loc.distance(wp.transform.location) > self._end_dist_flow:\n                break\n\n        tls = self._world.get_traffic_lights_in_junction(junction.id)\n        if not tls:\n            self._signalized_junction = False\n        else:\n            self._signalized_junction = True\n            self._get_traffic_lights(tls, ego_junction_dist)\n\n    def _get_traffic_lights(self, tls, ego_dist):\n        \"\"\"Get the traffic light of the junction, mapping their states\"\"\"\n\n        ego_landmark = self._ego_wp.get_landmarks_of_type(ego_dist + 2, \"1000001\")[0]\n        ego_tl = self._world.get_traffic_light(ego_landmark)\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n\n        root = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(BicycleFlow(self._plan, self._source_dist_interval, self._sink_distance, self._flow_speed, True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        # Freeze the traffic lights to allow the flow to populate the junction\n        if self._signalized_junction:\n            tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n            tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n            tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n            root.add_child(tl_freezer_sequence)\n\n        # Add the BackgroundActivity behaviors\n        if not self.route_mode:\n            return root\n\n        sequence = py_trees.composites.Sequence()\n        sequence.add_child(HandleJunctionScenario(\n            clear_junction=True,\n            clear_ego_entry=True,\n            remove_entries=[],\n            remove_exits=[],\n            stop_entries=True,\n            extend_road_exit=0\n        ))\n        sequence.add_child(root)\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/cut_in.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCut in scenario:\n\nThe scenario realizes a driving behavior on the highway.\nThe user-controlled ego vehicle is driving straight and keeping its velocity at a constant level.\nAnother car is cutting just in front, coming from left or right lane.\n\nThe ego vehicle may need to brake to avoid a collision.\n\"\"\"\n\nimport random\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      LaneChange,\n                                                                      WaypointFollower,\n                                                                      AccelerateToCatchUp)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle, DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass CutIn(BasicScenario):\n\n    \"\"\"\n    The ego vehicle is driving on a highway and another car is cutting in just in front.\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 1200\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=600):\n\n        self.timeout = timeout\n        self._map = CarlaDataProvider.get_map()\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n\n        self._velocity = 40\n        self._delta_velocity = 10\n        self._trigger_distance = 30\n\n        # get direction from config name\n        self._config = config\n        self._direction = None\n        self._transform_visible = None\n\n        super(CutIn, self).__init__(\"CutIn\",\n                                    ego_vehicles,\n                                    config,\n                                    world,\n                                    debug_mode,\n                                    criteria_enable=criteria_enable)\n\n        if randomize:\n            self._velocity = random.randint(20, 60)\n            self._trigger_distance = random.randint(10, 40)\n\n    def _initialize_actors(self, config):\n\n        # direction of lane, on which other_actor is driving before lane change\n        if 'LEFT' in self._config.name.upper():\n            self._direction = 'left'\n\n        if 'RIGHT' in self._config.name.upper():\n            self._direction = 'right'\n\n        # add actors from xml file\n        for actor in config.other_actors:\n            vehicle = CarlaDataProvider.request_new_actor(actor.model, actor.transform)\n            self.other_actors.append(vehicle)\n            vehicle.set_simulate_physics(enabled=False)\n\n        # transform visible\n        other_actor_transform = self.other_actors[0].get_transform()\n        self._transform_visible = carla.Transform(\n            carla.Location(other_actor_transform.location.x,\n                           other_actor_transform.location.y,\n                           other_actor_transform.location.z + 105),\n            other_actor_transform.rotation)\n\n    def _create_behavior(self):\n        \"\"\"\n        Order of sequence:\n        - car_visible: spawn car at a visible transform\n        - just_drive: drive until in trigger distance to ego_vehicle\n        - accelerate: accelerate to catch up distance to ego_vehicle\n        - lane_change: change the lane\n        - endcondition: drive for a defined distance\n        \"\"\"\n\n        # car_visible\n        behaviour = py_trees.composites.Sequence(\"CarOn_{}_Lane\" .format(self._direction))\n        car_visible = ActorTransformSetter(self.other_actors[0], self._transform_visible)\n        behaviour.add_child(car_visible)\n\n        # just_drive\n        just_drive = py_trees.composites.Parallel(\n            \"DrivingStraight\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        car_driving = WaypointFollower(self.other_actors[0], self._velocity)\n        just_drive.add_child(car_driving)\n\n        trigger_distance = InTriggerDistanceToVehicle(\n            self.other_actors[0], self.ego_vehicles[0], self._trigger_distance)\n        just_drive.add_child(trigger_distance)\n        behaviour.add_child(just_drive)\n\n        # accelerate\n        accelerate = AccelerateToCatchUp(self.other_actors[0], self.ego_vehicles[0], throttle_value=1,\n                                         delta_velocity=self._delta_velocity, trigger_distance=5, max_distance=500)\n        behaviour.add_child(accelerate)\n\n        # lane_change\n        if self._direction == 'left':\n            lane_change = LaneChange(\n                self.other_actors[0], speed=None, direction='right', distance_same_lane=5, distance_other_lane=300)\n            behaviour.add_child(lane_change)\n        else:\n            lane_change = LaneChange(\n                self.other_actors[0], speed=None, direction='left', distance_same_lane=5, distance_other_lane=300)\n            behaviour.add_child(lane_change)\n\n        # endcondition\n        endcondition = DriveDistance(self.other_actors[0], 200)\n\n        # build tree\n        root = py_trees.composites.Sequence(\"Behavior\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(behaviour)\n        root.add_child(endcondition)\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria is created, which is later used in the parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors after deletion.\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/cut_in_with_static_vehicle.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n# Copyright (c) 2019-2022 Intel Corporation\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      BatchActorTransformSetter,\n                                                                      CutIn,\n                                                                      BasicAgentBehavior,\n                                                                      Idle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import RemoveRoadLane, LeaveSpaceInFront, ReAddRoadLane, ChangeRoadBehavior\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass StaticCutIn(BasicScenario):\n\n    \"\"\"\n    Cut in(with static vehicle) scenario synchronizes a vehicle that is parked at a side lane\n    to cut in in front of the ego vehicle, forcing it to break\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n\n        self._reaction_time = 2.7  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 15.0  # Min distance to the collision location that triggers the adversary [m]\n\n        self._back_vehicles = 2\n        self._front_vehicles = 3\n        self._vehicle_gap = 11\n\n        self._speed = 60 # Km/h\n\n        self._adversary_end_distance = 70\n\n        self._extra_space = 30  # Leave extra space as a vehicle is invading the ego's lane (BA parameter)\n\n        self._side_transforms = []\n        self._side_wp = None\n\n        self._attributes = {'base_type': 'car', 'has_lights': True}\n\n        self._blocker_distance = get_value_parameter(config, 'distance', float, 100)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        super().__init__(\"StaticCutIn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn the blocker vehicle\n        next_wps = self._reference_waypoint.next(self._blocker_distance)\n        if not next_wps:\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        blocker_wp = next_wps[0]\n\n        # Spawn the vehicles behind the cut in one\n        for i in range(self._back_vehicles):\n            # Move to the side\n            side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane()\n            if not side_wp:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n\n            if i == 1:\n                self._side_wp = side_wp\n\n            # Spawn the actor\n            blocker_actor = CarlaDataProvider.request_new_actor(\n                'vehicle.*', side_wp.transform, 'scenario', attribute_filter=self._attributes)\n            if not blocker_actor:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't spawn an actor\")\n            blocker_actor.apply_control(carla.VehicleControl(hand_brake=True))\n\n            blocker_actor.set_simulate_physics(False)\n            blocker_actor.set_location(side_wp.transform.location + carla.Location(z=-500))\n            self._side_transforms.append([blocker_actor, side_wp.transform])\n            self.other_actors.append(blocker_actor)\n\n            # Move to the front\n            next_wps = blocker_wp.next(self._vehicle_gap)\n            if not next_wps:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n            blocker_wp = next_wps[0]\n\n        self._collision_wp = blocker_wp\n\n        # Get the cut in behavior\n        self._plan, dist, step = ([], 0, 5)\n        next_wp = self._collision_wp\n        while dist < self._adversary_end_distance:\n            next_wps = next_wp.next(step)\n            if not next_wps:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n            next_wp = next_wps[0]\n            self._plan.append([next_wp, RoadOption.STRAIGHT])\n\n            dist += step\n\n        # Spawn the cut in vehicle\n        side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane()\n        if not side_wp:\n            for actor in self.other_actors:\n                actor.destroy()\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n\n        self._adversary_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', side_wp.transform, 'scenario', attribute_filter=self._attributes)\n        if not self._adversary_actor:\n            for actor in self.other_actors:\n                actor.destroy()\n            raise ValueError(\"Couldn't spawn an actor\")\n\n        self._adversary_actor.set_simulate_physics(False)\n        self._adversary_actor.set_location(side_wp.transform.location + carla.Location(z=-500))\n        self._side_transforms.append([self._adversary_actor, side_wp.transform])\n        self.other_actors.append(self._adversary_actor)\n\n        # This starts the engine, to allow the adversary to instantly move \n        self._adversary_actor.apply_control(carla.VehicleControl(throttle=1.0, brake=1.0)) \n\n        # Move to the front\n        next_wps = blocker_wp.next(self._vehicle_gap)\n        if not next_wps:\n            for actor in self.other_actors:\n                actor.destroy()\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        blocker_wp = next_wps[0]\n\n        # Spawn the vehicles in front of the cut in one\n        for i in range(self._front_vehicles):\n            # Move to the side\n            side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane()\n            if not side_wp:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n\n            # Spawn the actor\n            blocker_actor = CarlaDataProvider.request_new_actor(\n                'vehicle.*', side_wp.transform, 'scenario', attribute_filter=self._attributes)\n            if not blocker_actor:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't spawn an actor\")\n            blocker_actor.apply_control(carla.VehicleControl(hand_brake=True))\n\n            blocker_actor.set_simulate_physics(False)\n            blocker_actor.set_location(side_wp.transform.location + carla.Location(z=-500))\n            self._side_transforms.append([blocker_actor, side_wp.transform])\n            self.other_actors.append(blocker_actor)\n\n            # Move to the front\n            next_wps = blocker_wp.next(self._vehicle_gap)\n            if not next_wps:\n                for actor in self.other_actors:\n                    actor.destroy()\n                raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n            blocker_wp = next_wps[0]\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, a parked vehicle will wait for the ego to\n        be close-by, merging into its lane, forcing it to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"StaticCutIn\")\n        if self.route_mode:\n            total_dist = self._blocker_distance\n            total_dist += self._vehicle_gap * (self._back_vehicles + self._front_vehicles + 1)\n            sequence.add_child(LeaveSpaceInFront(total_dist))\n\n        sequence.add_child(BatchActorTransformSetter(self._side_transforms))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(self._side_wp))\n\n        cut_in_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"CutIn\")\n        cut_in_direction = 'right' if self._direction == 'left' else 'left'\n\n        cut_in_movement = py_trees.composites.Sequence()\n        cut_in_movement.add_child(CutIn(\n            self._adversary_actor, self.ego_vehicles[0], cut_in_direction, change_time=3, other_lane_time=2))\n        cut_in_movement.add_child(BasicAgentBehavior(\n            self._adversary_actor, plan=self._plan, target_speed=self._speed))\n\n        cut_in_behavior.add_child(cut_in_movement)\n        cut_in_behavior.add_child(Idle(30))  # Timeout in case a collision happened\n\n        sequence.add_child(cut_in_behavior)\n\n        for actor in self.other_actors:\n            sequence.add_child(ActorDestroy(actor))\n\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=0))\n            sequence.add_child(ReAddRoadLane(1 if self._direction == 'right' else -1))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/follow_leading_vehicle.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nFollow leading vehicle scenario:\n\nThe scenario realizes a common driving behavior, in which the\nuser-controlled ego vehicle follows a leading car driving down\na given road. At some point the leading car has to slow down and\nfinally stop. The ego vehicle has to react accordingly to avoid\na collision. The scenario ends either via a timeout, or if the ego\nvehicle stopped close enough to the leading vehicle\n\"\"\"\n\nimport random\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      KeepVelocity,\n                                                                      StopVehicle,\n                                                                      WaypointFollower)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               InTriggerDistanceToNextIntersection,\n                                                                               DriveDistance,\n                                                                               StandStill)\nfrom srunner.scenariomanager.timer import TimeOut\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass FollowLeadingVehicle(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple \"Follow a leading vehicle\"\n    scenario involving two vehicles.  (Traffic Scenario 2)\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 120            # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n\n        If randomize is True, the scenario parameters are randomized\n        \"\"\"\n\n        self._map = CarlaDataProvider.get_map()\n        self._first_vehicle_location = 25\n        self._first_vehicle_speed = 10\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._other_actor_max_brake = 1.0\n        self._other_actor_stop_in_front_intersection = 20\n        self._other_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(FollowLeadingVehicle, self).__init__(\"FollowVehicle\",\n                                                   ego_vehicles,\n                                                   config,\n                                                   world,\n                                                   debug_mode,\n                                                   criteria_enable=criteria_enable)\n\n        if randomize:\n            self._ego_other_distance_start = random.randint(4, 8)\n\n            # Example code how to randomize start location\n            # distance = random.randint(20, 80)\n            # new_location, _ = get_location_in_distance(self.ego_vehicles[0], distance)\n            # waypoint = CarlaDataProvider.get_map().get_waypoint(new_location)\n            # waypoint.transform.location.z += 39\n            # self.other_actors[0].set_transform(waypoint.transform)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location)\n        transform = waypoint.transform\n        transform.location.z += 0.5\n        first_vehicle = CarlaDataProvider.request_new_actor('vehicle.nissan.patrol', transform)\n        self.other_actors.append(first_vehicle)\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"follow leading vehicle\" scenario. After\n        invoking this scenario, it will wait for the user controlled vehicle to\n        enter the start region, then make the other actor to drive until reaching\n        the next intersection. Finally, the user-controlled vehicle has to be close\n        enough to the other actor to end the scenario.\n        If this does not happen within 60 seconds, a timeout stops the scenario\n        \"\"\"\n\n        # let the other actor drive until next intersection\n        driving_to_next_intersection = py_trees.composites.Parallel(\n            \"DrivingTowardsIntersection\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        driving_to_next_intersection.add_child(WaypointFollower(self.other_actors[0], self._first_vehicle_speed))\n        driving_to_next_intersection.add_child(InTriggerDistanceToNextIntersection(\n            self.other_actors[0], self._other_actor_stop_in_front_intersection))\n\n        # stop vehicle\n        stop = StopVehicle(self.other_actors[0], self._other_actor_max_brake)\n\n        # end condition\n        endcondition = py_trees.composites.Parallel(\"Waiting for end position\",\n                                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n        endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[0],\n                                                        self.ego_vehicles[0],\n                                                        distance=20,\n                                                        name=\"FinalDistance\")\n        endcondition_part2 = StandStill(self.ego_vehicles[0], name=\"StandStill\", duration=1)\n        endcondition.add_child(endcondition_part1)\n        endcondition.add_child(endcondition_part2)\n\n        # Build behavior tree\n        sequence = py_trees.composites.Sequence(\"Sequence Behavior\")\n        sequence.add_child(driving_to_next_intersection)\n        sequence.add_child(stop)\n        sequence.add_child(endcondition)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass FollowLeadingVehicleWithObstacle(BasicScenario):\n\n    \"\"\"\n    This class holds a scenario similar to FollowLeadingVehicle\n    but there is an obstacle in front of the leading vehicle\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 120            # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._map = CarlaDataProvider.get_map()\n        self._first_actor_location = 25\n        self._second_actor_location = self._first_actor_location + 41\n        self._first_actor_speed = 10\n        self._second_actor_speed = 1.5\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._other_actor_max_brake = 1.0\n        self._first_actor_transform = None\n        self._second_actor_transform = None\n\n        super(FollowLeadingVehicleWithObstacle, self).__init__(\"FollowLeadingVehicleWithObstacle\",\n                                                               ego_vehicles,\n                                                               config,\n                                                               world,\n                                                               debug_mode,\n                                                               criteria_enable=criteria_enable)\n        if randomize:\n            self._ego_other_distance_start = random.randint(4, 8)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n\n        first_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_actor_location)\n        second_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_actor_location)\n        first_actor_transform = carla.Transform(\n            carla.Location(first_actor_waypoint.transform.location.x,\n                           first_actor_waypoint.transform.location.y,\n                           first_actor_waypoint.transform.location.z - 500),\n            first_actor_waypoint.transform.rotation)\n        self._first_actor_transform = carla.Transform(\n            carla.Location(first_actor_waypoint.transform.location.x,\n                           first_actor_waypoint.transform.location.y,\n                           first_actor_waypoint.transform.location.z + 1),\n            first_actor_waypoint.transform.rotation)\n        yaw_1 = second_actor_waypoint.transform.rotation.yaw + 90\n        second_actor_transform = carla.Transform(\n            carla.Location(second_actor_waypoint.transform.location.x,\n                           second_actor_waypoint.transform.location.y,\n                           second_actor_waypoint.transform.location.z - 500),\n            carla.Rotation(second_actor_waypoint.transform.rotation.pitch, yaw_1,\n                           second_actor_waypoint.transform.rotation.roll))\n        self._second_actor_transform = carla.Transform(\n            carla.Location(second_actor_waypoint.transform.location.x,\n                           second_actor_waypoint.transform.location.y,\n                           second_actor_waypoint.transform.location.z + 1),\n            carla.Rotation(second_actor_waypoint.transform.rotation.pitch, yaw_1,\n                           second_actor_waypoint.transform.rotation.roll))\n\n        first_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.nissan.patrol', first_actor_transform)\n        second_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.diamondback.century', second_actor_transform)\n\n        first_actor.set_simulate_physics(enabled=False)\n        second_actor.set_simulate_physics(enabled=False)\n        self.other_actors.append(first_actor)\n        self.other_actors.append(second_actor)\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"follow leading vehicle\" scenario. After\n        invoking this scenario, it will wait for the user controlled vehicle to\n        enter the start region, then make the other actor to drive towards obstacle.\n        Once obstacle clears the road, make the other actor to drive towards the\n        next intersection. Finally, the user-controlled vehicle has to be close\n        enough to the other actor to end the scenario.\n        If this does not happen within 60 seconds, a timeout stops the scenario\n        \"\"\"\n\n        # let the other actor drive until next intersection\n        driving_to_next_intersection = py_trees.composites.Parallel(\n            \"Driving towards Intersection\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        obstacle_clear_road = py_trees.composites.Parallel(\"Obstalce clearing road\",\n                                                           policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        obstacle_clear_road.add_child(DriveDistance(self.other_actors[1], 4))\n        obstacle_clear_road.add_child(KeepVelocity(self.other_actors[1], self._second_actor_speed))\n\n        stop_near_intersection = py_trees.composites.Parallel(\n            \"Waiting for end position near Intersection\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        stop_near_intersection.add_child(WaypointFollower(self.other_actors[0], 10))\n        stop_near_intersection.add_child(InTriggerDistanceToNextIntersection(self.other_actors[0], 20))\n\n        driving_to_next_intersection.add_child(WaypointFollower(self.other_actors[0], self._first_actor_speed))\n        driving_to_next_intersection.add_child(InTriggerDistanceToVehicle(self.other_actors[1],\n                                                                          self.other_actors[0], 15))\n\n        # end condition\n        endcondition = py_trees.composites.Parallel(\"Waiting for end position\",\n                                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n        endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[0],\n                                                        self.ego_vehicles[0],\n                                                        distance=20,\n                                                        name=\"FinalDistance\")\n        endcondition_part2 = StandStill(self.ego_vehicles[0], name=\"FinalSpeed\", duration=1)\n        endcondition.add_child(endcondition_part1)\n        endcondition.add_child(endcondition_part2)\n\n        # Build behavior tree\n        sequence = py_trees.composites.Sequence(\"Sequence Behavior\")\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform))\n        sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform))\n        sequence.add_child(driving_to_next_intersection)\n        sequence.add_child(StopVehicle(self.other_actors[0], self._other_actor_max_brake))\n        sequence.add_child(TimeOut(3))\n        sequence.add_child(obstacle_clear_road)\n        sequence.add_child(stop_near_intersection)\n        sequence.add_child(StopVehicle(self.other_actors[0], self._other_actor_max_brake))\n        sequence.add_child(endcondition)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n        sequence.add_child(ActorDestroy(self.other_actors[1]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/freeride.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSimple freeride scenario. No action, no triggers. Ego vehicle can simply cruise around.\n\"\"\"\n\nimport py_trees\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass FreeRide(BasicScenario):\n\n    \"\"\"\n    Implementation of a simple free ride scenario that consits only of the ego vehicle\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=10000000):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n        super(FreeRide, self).__init__(\"FreeRide\",\n                                       ego_vehicles,\n                                       config,\n                                       world,\n                                       debug_mode,\n                                       criteria_enable=criteria_enable)\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"\n        \"\"\"\n        return None\n\n    def _create_behavior(self):\n        \"\"\"\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"Sequence Behavior\")\n        sequence.add_child(Idle())\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        for ego_vehicle in self.ego_vehicles:\n            collision_criterion = CollisionTest(ego_vehicle)\n            criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/green_traffic_light.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSets the ego incoming traffic light to green. Support scenario at routes\nto let the ego gather speed\n\"\"\"\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import TrafficLightFreezer\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass PriorityAtJunction(BasicScenario):\n    \"\"\"\n    Sets the ego incoming traffic light to green. Support scenario at routes\n    to let the ego gather speed\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._tl_dict = {}\n\n        self.timeout = timeout\n        super().__init__(\"PriorityAtJunction\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Get the junction and traffic lights\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        self._get_traffic_lights(self._junction, ego_junction_dist)\n\n    def _get_traffic_lights(self, junction, junction_dist):\n        \"\"\"Get the traffic light of the junction, mapping their states\"\"\"\n        tls = self._world.get_traffic_lights_in_junction(junction.id)\n        if not tls:\n            raise ValueError(\"No traffic lights found, nothing to do here\")\n\n        ego_landmark = self._ego_wp.get_landmarks_of_type(junction_dist + 1, \"1000001\")[0]\n        ego_tl = self._world.get_traffic_light(ego_landmark)\n        for tl in tls:\n            self._tl_dict[tl] = carla.TrafficLightState.Green if tl.id == ego_tl.id else carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Freeze the traffic lights until the ego has exited the junction\n        \"\"\"\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0], self._junction.id))\n        root.add_child(TrafficLightFreezer(self._tl_dict))\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/hard_break.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2022 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nHard break scenario:\n\nThe scenario spawn a vehicle in front of the ego that drives for a while before\nsuddenly hard breaking, forcing the ego to avoid the collision\n\"\"\"\n\nimport py_trees\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import StopFrontVehicles, StartFrontVehicles\n\n\nclass HardBreakRoute(BasicScenario):\n\n    \"\"\"\n    This class uses the is the Background Activity at routes to create a hard break scenario.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    timeout = 120            # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self.timeout = timeout\n        self._stop_duration = 10\n        self.end_distance = 15\n\n        super().__init__(\"HardBreak\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        pass\n\n    def _create_behavior(self):\n        \"\"\"\n        Uses the Background Activity to force a hard break on the vehicles in front of the actor,\n        then waits for a bit to check if the actor has collided. After a set duration,\n        the front vehicles will resume their movement\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"HardBreak\")\n        sequence.add_child(StopFrontVehicles())\n        sequence.add_child(Idle(self._stop_duration))\n        sequence.add_child(StartFrontVehicles())\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self.end_distance))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Empty, the route already has a collision criteria\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/highway_cut_in.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      ActorTransformSetter,\n                                                                      SyncArrivalWithAgent,\n                                                                      CutIn)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\nfrom srunner.tools.scenario_helper import generate_target_waypoint\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\nclass HighwayCutIn(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle runs a red light\n    in front of the ego, forcing it to react. This vehicles are 'special' ones such as police cars,\n    ambulances or firetrucks.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._same_lane_time = 0.3\n        self._other_lane_time = 3\n        self._change_time = 2\n        self._speed_perc = 80\n        self._cut_in_distance = 10\n        self._extra_space = 170\n\n        self._start_location = convert_dict_to_location(config.other_parameters['other_actor_location'])\n\n        super().__init__(\"HighwayCutIn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        self._other_waypoint = self._map.get_waypoint(self._start_location)\n        self._other_transform = self._other_waypoint.transform\n\n        self._cut_in_vehicle = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._other_transform, rolename='scenario',\n            attribute_filter={'base_type': 'car', 'has_lights': True}\n        )\n        self.other_actors.append(self._cut_in_vehicle)\n\n        # Move below ground\n        self._cut_in_vehicle.set_location(self._other_transform.location - carla.Location(z=100))\n        self._cut_in_vehicle.set_simulate_physics(False)\n\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        behavior = py_trees.composites.Sequence(\"HighwayCutIn\")\n\n        if self.route_mode:\n            behavior.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=False,\n                remove_entries=[self._other_waypoint],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=self._extra_space\n            ))\n        behavior.add_child(ActorTransformSetter(self._cut_in_vehicle, self._other_transform))\n\n        # Sync behavior\n        target_wp = generate_target_waypoint(self._other_waypoint)\n        front_wps = target_wp.next(self._cut_in_distance)\n        if not front_wps:\n            raise ValueError(\"Couldn't find a waypoint to perform the cut in\")\n        target_wp = front_wps[0]\n\n        trigger_wp = self._map.get_waypoint(self.config.trigger_points[0].location)\n        reference_wp = generate_target_waypoint(trigger_wp)\n        behavior.add_child(SyncArrivalWithAgent(\n            self._cut_in_vehicle, self.ego_vehicles[0], target_wp.transform, reference_wp.transform, 5))\n\n        # Cut in\n        behavior.add_child(CutIn(\n            self._cut_in_vehicle, self.ego_vehicles[0], 'left', self._speed_perc,\n            self._same_lane_time, self._other_lane_time, self._change_time, name=\"Cut_in\")\n        )\n        behavior.add_child(ActorDestroy(self._cut_in_vehicle))\n        return behavior\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/invading_turn.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario in which the ego is about to turn right \nwhen a vehicle coming from the opposite lane invades the ego's lane, forcing the ego to move right to avoid a possible collision.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (InvadingActorFlow,\n                                                                      ScenarioTimeout,\n                                                                      ActorDestroy,\n                                                                      BatchActorTransformSetter)\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitUntilInFrontPosition\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import RemoveRoadLane, ChangeOppositeBehavior, ReAddRoadLane\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass InvadingTurn(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which the ego is about to turn right \n    when a vehicle coming from the opposite lane invades the ego's lane, \n    forcing the ego to move right to avoid a possible collision.\n\n    This scenario is expected to take place on a road that has only one lane in each direction.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(\n            self._trigger_location)\n\n        self._flow_frequency = 40 # m\n        self._source_dist = 30 # Distance between source and end point\n\n        self._check_distance = 50\n\n        self._distance = get_value_parameter(config, 'distance', float, 100)\n        self._offset = get_value_parameter(config, 'offset', float, 0.25)  # meters invaded in the opposite direction\n        self._scenario_timeout = 240\n\n        self._obstacle_transforms = []\n\n        super().__init__(\"InvadingTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn adversary actor\n        next_wps = self._reference_waypoint.next(self._distance + self._source_dist)\n        if not next_wps:\n            raise ValueError(\"Couldn't find the source location for the actor flow\")\n        self._forward_wp = next_wps[0]\n        self._source_wp = self._forward_wp.get_left_lane()\n        if not self._source_wp:\n            raise ValueError(\"Couldn't find the source location for the actor flow\")\n\n        self._sink_wp = self._reference_waypoint.get_left_lane()\n        if not self._sink_wp:\n            raise ValueError(\"Couldn't find the sink location for the actor flow\")\n\n        # Lane offset\n        self._offset_constant = 0.7  # Ideally, half the vehicle lane width\n        self._true_offset = self._offset + self._sink_wp.lane_width / 2 - self._offset_constant\n        self._true_offset *= -1 # Cause left direction\n\n        self._create_obstacle()\n\n    def _create_obstacle(self):\n\n        next_wp = self._source_wp.next(10)[0]\n        obstacle_distance = 0.5 * self._distance\n        dist = 0\n        while dist < obstacle_distance:\n            next_wp = next_wp.next(5)[0]\n\n            displacement = 0.8 * next_wp.lane_width / 2\n            r_vec = next_wp.transform.get_right_vector()\n            spawn_transform = next_wp.transform\n            spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.3)\n\n            cone = CarlaDataProvider.request_new_actor('*constructioncone*', spawn_transform)\n            self.other_actors.append(cone)\n\n            self._obstacle_transforms.append([cone, spawn_transform])\n\n            transform = carla.Transform(spawn_transform.location, spawn_transform.rotation)\n            transform.location.z -= 200\n            cone.set_transform(transform)\n            cone.set_simulate_physics(False)\n\n            dist += 5\n\n        self._obstacle_transforms.reverse()  # So that the closest cones are spawned first\n\n    def _create_behavior(self):\n        \"\"\"\n        The adversary vehicle will go to the target place while invading another lane.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"InvadingTurn\")\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(self._reference_waypoint))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        sequence.add_child(BatchActorTransformSetter(self._obstacle_transforms))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(InvadingActorFlow(\n            self._source_wp, self._sink_wp, self.ego_vehicles[0], self._flow_frequency, offset=self._true_offset))\n\n        main_behavior.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._forward_wp.transform, True, self._check_distance))\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(main_behavior)\n        if self.route_mode:\n            sequence.add_child(ReAddRoadLane(0))\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        for actor in self.other_actors:\n            sequence.add_child(ActorDestroy(actor))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/left_turn_enter_flow.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a left turn\n\"\"\"\n\nimport py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass JunctionLeftTurnEnterFlow(BasicScenario):\n    \"\"\"\n    Vehicle turning left at junction scenario, with actors coming in the opposite direction.\n    The ego has to react to them, safely crossing the opposite lane\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self.timeout = timeout\n\n        self._direction = 'opposite'\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        self._end_distance = 10\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 20)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [25, 50])\n        self._scenario_timeout = 240\n\n        # The faster the flow, the further they are spawned, leaving time to react to them\n        self._source_dist = 4 * self._flow_speed\n        self._sink_dist = 2.5 * self._flow_speed\n\n        super().__init__(\"JunctionLeftTurnEnterFlow\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the opposite entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Trying to find a lane in the {} direction but none was found\".format(self._direction))\n\n        # Get the source transform\n        source_entry_wp = self._rng.choice(source_entry_wps)\n\n        # Get the source transform\n        source_wp = source_entry_wp\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            source_wps = source_wp.previous(5)\n            if len(source_wps) == 0:\n                raise ValueError(\"Failed to find a source location as a waypoint with no previous was detected\")\n            if source_wps[0].is_junction:\n                break\n            source_wp = source_wps[0]\n            source_junction_dist += 5\n\n        self._source_wp = source_wp\n        source_transform = self._source_wp.transform\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 1)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location as a waypoint with no next was detected\")\n        self._sink_wp = sink_wps[0]\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass SignalizedJunctionLeftTurnEnterFlow(JunctionLeftTurnEnterFlow):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        # self.activate_scenario = activate_scenario\n        self.activate_scenario = True\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        source_tl = get_closest_traffic_light(self._source_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            elif tl.id == source_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"SignalizedJunctionLeftTurnEnterFlow\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=False,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        if self.activate_scenario:\n            end_condition = py_trees.composites.Sequence()\n            end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n            end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n            root.add_child(end_condition)\n            root.add_child(ActorFlow(\n                self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n            root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        # keep the traffic light behavior the same\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n\nclass NonSignalizedJunctionLeftTurnEnterFlow(JunctionLeftTurnEnterFlow):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        # self.activate_scenario = activate_scenario\n        self.activate_scenario = True\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"NonSignalizedJunctionLeftTurnEnterFlow\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=True,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        if self.activate_scenario:\n            root.add_child(ActorFlow(\n                self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/maneuver_opposite_direction.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nVehicle Maneuvering In Opposite Direction:\n\nVehicle is passing another vehicle in a rural area, in daylight, under clear\nweather conditions, at a non-junction and encroaches into another\nvehicle traveling in the opposite direction.\n\"\"\"\n\nfrom six.moves.queue import Queue   # pylint: disable=relative-import,bad-option-value\n\nimport math  # pylint: disable=wrong-import-order\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      ActorSource,\n                                                                      ActorSink,\n                                                                      WaypointFollower)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass ManeuverOppositeDirection(BasicScenario):\n\n    \"\"\"\n    \"Vehicle Maneuvering In Opposite Direction\" (Traffic Scenario 06)\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 obstacle_type='barrier', timeout=120):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        obstacle_type -> flag to select type of leading obstacle. Values: vehicle, barrier\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._first_vehicle_location = 50\n        self._second_vehicle_location = self._first_vehicle_location + 60\n        self._ego_vehicle_drive_distance = self._second_vehicle_location * 2\n        self._start_distance = self._first_vehicle_location * 0.9\n        self._opposite_speed = 5.56   # m/s\n        self._source_gap = 40   # m\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._source_transform = None\n        self._sink_location = None\n        self._blackboard_queue_name = 'ManeuverOppositeDirection/actor_flow_queue'\n        self._queue = py_trees.blackboard.Blackboard().set(self._blackboard_queue_name, Queue())\n        self._obstacle_type = obstacle_type\n        self._first_actor_transform = None\n        self._second_actor_transform = None\n        self._third_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(ManeuverOppositeDirection, self).__init__(\n            \"ManeuverOppositeDirection\",\n            ego_vehicles,\n            config,\n            world,\n            debug_mode,\n            criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        first_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location)\n        second_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_vehicle_location)\n        second_actor_waypoint = second_actor_waypoint.get_left_lane()\n\n        first_actor_transform = carla.Transform(\n            first_actor_waypoint.transform.location,\n            first_actor_waypoint.transform.rotation)\n        if self._obstacle_type == 'vehicle':\n            first_actor_model = 'vehicle.nissan.micra'\n        else:\n            first_actor_transform.rotation.yaw += 90\n            first_actor_model = 'static.prop.streetbarrier'\n            second_prop_waypoint = first_actor_waypoint.next(2.0)[0]\n            position_yaw = second_prop_waypoint.transform.rotation.yaw + 90\n            offset_location = carla.Location(\n                0.50 * second_prop_waypoint.lane_width * math.cos(math.radians(position_yaw)),\n                0.50 * second_prop_waypoint.lane_width * math.sin(math.radians(position_yaw)))\n            second_prop_transform = carla.Transform(\n                second_prop_waypoint.transform.location + offset_location, first_actor_transform.rotation)\n            second_prop_actor = CarlaDataProvider.request_new_actor(first_actor_model, second_prop_transform)\n            second_prop_actor.set_simulate_physics(True)\n        first_actor = CarlaDataProvider.request_new_actor(first_actor_model, first_actor_transform)\n        first_actor.set_simulate_physics(True)\n        second_actor = CarlaDataProvider.request_new_actor('vehicle.audi.tt', second_actor_waypoint.transform)\n\n        self.other_actors.append(first_actor)\n        self.other_actors.append(second_actor)\n        if self._obstacle_type != 'vehicle':\n            self.other_actors.append(second_prop_actor)\n\n        self._source_transform = second_actor_waypoint.transform\n        sink_waypoint = second_actor_waypoint.next(1)[0]\n        while not sink_waypoint.is_intersection:\n            sink_waypoint = sink_waypoint.next(1)[0]\n        self._sink_location = sink_waypoint.transform.location\n\n        self._first_actor_transform = first_actor_transform\n        self._second_actor_transform = second_actor_waypoint.transform\n        self._third_actor_transform = second_prop_transform\n\n    def _create_behavior(self):\n        \"\"\"\n        The behavior tree returned by this method is as follows:\n        The ego vehicle is trying to pass a leading vehicle in the same lane\n        by moving onto the oncoming lane while another vehicle is moving in the\n        opposite direction in the oncoming lane.\n        \"\"\"\n\n        # Leaf nodes\n        actor_source = ActorSource(\n            ['vehicle.audi.tt', 'vehicle.tesla.model3', 'vehicle.nissan.micra'],\n            self._source_transform, self._source_gap, self._blackboard_queue_name)\n        actor_sink = ActorSink(self._sink_location, 10)\n        ego_drive_distance = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_drive_distance)\n        waypoint_follower = WaypointFollower(\n            self.other_actors[1], self._opposite_speed,\n            blackboard_queue_name=self._blackboard_queue_name, avoid_collision=True)\n\n        # Non-leaf nodes\n        parallel_root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # Building tree\n        parallel_root.add_child(ego_drive_distance)\n        parallel_root.add_child(actor_source)\n        parallel_root.add_child(actor_sink)\n        parallel_root.add_child(waypoint_follower)\n\n        scenario_sequence = py_trees.composites.Sequence()\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform))\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform))\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[2], self._third_actor_transform))\n        scenario_sequence.add_child(parallel_root)\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[0]))\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[1]))\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[2]))\n\n        return scenario_sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/no_signal_junction_crossing.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nNon-signalized junctions: crossing negotiation:\n\nThe hero vehicle is passing through a junction without traffic lights\nAnd encounters another vehicle passing across the junction.\n\"\"\"\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      SyncArrival,\n                                                                      KeepVelocity,\n                                                                      StopVehicle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerRegion, DriveDistance, WaitEndIntersection\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\n\nclass NoSignalJunctionCrossing(BasicScenario):\n\n    \"\"\"\n    Implementation class for\n    'Non-signalized junctions: crossing negotiation' scenario,\n    (Traffic Scenario 10).\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    # ego vehicle parameters\n    _ego_vehicle_max_velocity = 20\n    _ego_vehicle_driven_distance = 105\n\n    # other vehicle\n    _other_actor_max_brake = 1.0\n    _other_actor_target_velocity = 15\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n\n        self._other_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(NoSignalJunctionCrossing, self).__init__(\"NoSignalJunctionCrossing\",\n                                                       ego_vehicles,\n                                                       config,\n                                                       world,\n                                                       debug_mode,\n                                                       criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        self._other_actor_transform = config.other_actors[0].transform\n        first_vehicle_transform = carla.Transform(\n            carla.Location(config.other_actors[0].transform.location.x,\n                           config.other_actors[0].transform.location.y,\n                           config.other_actors[0].transform.location.z - 500),\n            config.other_actors[0].transform.rotation)\n        first_vehicle = CarlaDataProvider.request_new_actor(config.other_actors[0].model, first_vehicle_transform)\n        first_vehicle.set_simulate_physics(enabled=False)\n        self.other_actors.append(first_vehicle)\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, it will wait for the user\n        controlled vehicle to enter the start region,\n        then make a traffic participant to accelerate\n        until it is going fast enough to reach an intersection point.\n        at the same time as the user controlled vehicle at the junction.\n        Once the user controlled vehicle comes close to the junction,\n        the traffic participant accelerates and passes through the junction.\n        After 60 seconds, a timeout stops the scenario.\n        \"\"\"\n\n        # Creating leaf nodes\n        start_other_trigger = InTriggerRegion(\n            self.ego_vehicles[0],\n            -80, -70,\n            -75, -60)\n\n        sync_arrival = SyncArrival(\n            self.other_actors[0], self.ego_vehicles[0],\n            carla.Location(x=-74.63, y=-136.34))\n\n        pass_through_trigger = InTriggerRegion(\n            self.ego_vehicles[0],\n            -90, -70,\n            -124, -119)\n\n        keep_velocity_other = KeepVelocity(\n            self.other_actors[0],\n            self._other_actor_target_velocity)\n\n        stop_other_trigger = InTriggerRegion(\n            self.other_actors[0],\n            -45, -35,\n            -140, -130)\n\n        stop_other = StopVehicle(\n            self.other_actors[0],\n            self._other_actor_max_brake)\n\n        end_condition = InTriggerRegion(\n            self.ego_vehicles[0],\n            -90, -70,\n            -170, -156\n        )\n\n        # Creating non-leaf nodes\n        root = py_trees.composites.Sequence()\n        scenario_sequence = py_trees.composites.Sequence()\n        sync_arrival_parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        keep_velocity_other_parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # Building tree\n        root.add_child(scenario_sequence)\n        scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform))\n        scenario_sequence.add_child(start_other_trigger)\n        scenario_sequence.add_child(sync_arrival_parallel)\n        scenario_sequence.add_child(keep_velocity_other_parallel)\n        scenario_sequence.add_child(stop_other)\n        scenario_sequence.add_child(end_condition)\n        scenario_sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        sync_arrival_parallel.add_child(sync_arrival)\n        sync_arrival_parallel.add_child(pass_through_trigger)\n        keep_velocity_other_parallel.add_child(keep_velocity_other)\n        keep_velocity_other_parallel.add_child(stop_other_trigger)\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collison_criteria = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collison_criteria)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass NoSignalJunctionCrossingRoute(BasicScenario):\n\n    \"\"\"\n    At routes, these scenarios are simplified, as they can be triggered making\n    use of the background activity. For unsignalized intersections, just wait\n    until the ego_vehicle has left the intersection.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n        self._end_distance = 50\n\n        super(NoSignalJunctionCrossingRoute, self).__init__(\"NoSignalJunctionCrossingRoute\",\n                                                            ego_vehicles,\n                                                            config,\n                                                            world,\n                                                            debug_mode,\n                                                            criteria_enable=criteria_enable)\n\n    def _create_behavior(self):\n        \"\"\"\n        Just wait for the ego to exit the junction, for route the BackgroundActivity already does all the job\n        \"\"\"\n        sequence = py_trees.composites.Sequence(\"UnSignalizedJunctionCrossingRoute\")\n        sequence.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return []\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/object_crash_intersection.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\"\"\"\nObject crash with prior vehicle action scenario:\nThe scenario realizes the user controlled ego vehicle\nmoving along the road and encounters a cyclist ahead after taking a right or left turn.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      HandBrakeVehicle,\n                                                                      KeepVelocity,\n                                                                      ActorTransformSetter,\n                                                                      MovePedestrianWithEgo)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           generate_target_waypoint_in_route,\n                                           get_same_dir_lanes,\n                                           get_opposite_dir_lanes)\n\nfrom srunner.tools.background_manager import LeaveCrossingSpace\n\n\ndef get_sidewalk_transform(waypoint, offset):\n    \"\"\"\n    Processes the waypoint transform to find a suitable spawning one at the sidewalk.\n    It first rotates the transform so that it is pointing towards the road and then moves a\n    bit to the side waypoint that aren't part of sidewalks, as they might be invading the road\n    \"\"\"\n\n    new_rotation = waypoint.transform.rotation\n    new_rotation.yaw += offset['yaw']\n\n    if waypoint.lane_type == carla.LaneType.Sidewalk:\n        new_location = waypoint.transform.location\n    else:\n        right_vector = waypoint.transform.get_right_vector()\n        offset_location = carla.Location(offset[\"k\"] * right_vector.x, offset[\"k\"] * right_vector.y)\n        new_location = waypoint.transform.location + offset_location\n    new_location.z += offset['z']\n\n    return carla.Transform(new_location, new_rotation)\n\n\nclass BaseVehicleTurning(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    with prior vehicle action involving a vehicle and a cyclist.\n    The ego vehicle is passing through a road and encounters\n    a cyclist after taking a turn.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n    _subtype = None\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60, name=\"BaseVehicleTurning\"):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._ego_route = config.route\n\n        self._start_distance = 11\n        self._spawn_dist = self._start_distance\n        self._number_of_attempts = 6\n        self._retry_dist = 0.4\n\n        self._adversary_transform = None\n\n        self._collision_wp = None\n        self._adversary_speed = 1.8  # Speed of the adversary [m/s]\n        self._reaction_time = 1.8  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n\n        self._offset = {\"yaw\": 270, \"z\": 0.2, \"k\": 1.5}\n\n        self.timeout = timeout\n        super(BaseVehicleTurning, self).__init__(\n            name, ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _get_target_waypoint(self):\n        \"\"\"\n        Gets the first waypoint after the junction.\n        This method depends on the subtype of VehicleTurning scenario\n        \"\"\"\n        if self._subtype == 'right':\n            return generate_target_waypoint(self._reference_waypoint, 1)\n        elif self._subtype == 'left':\n            return generate_target_waypoint(self._reference_waypoint, -1)\n        elif self._subtype == 'route':\n            return generate_target_waypoint_in_route(self._reference_waypoint, self._ego_route)\n        else:\n            raise ValueError(\"Trying to run a VehicleTurning scenario with a wrong subtype\")\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the waypoint right after the junction\n        waypoint = self._get_target_waypoint()\n        move_dist = self._start_distance\n        while self._number_of_attempts > 0:\n            parking_location = None\n\n            # Move to the front\n            waypoint = waypoint.next(move_dist)[0]\n            self._collision_wp = waypoint\n\n            # Move to the right\n            sidewalk_waypoint = waypoint\n            while sidewalk_waypoint.lane_type != carla.LaneType.Sidewalk:\n                right_wp = sidewalk_waypoint.get_right_lane()\n                if right_wp is None:\n                    break  # No more right lanes\n                sidewalk_waypoint = right_wp\n                if sidewalk_waypoint.lane_type == carla.LaneType.Parking:\n                    parking_location = sidewalk_waypoint.transform.location\n\n            # Get the adversary transform and spawn it\n            self._adversary_transform = get_sidewalk_transform(sidewalk_waypoint, self._offset)\n            adversary = CarlaDataProvider.request_new_actor('vehicle.diamondback.century', self._adversary_transform)\n            if adversary is None:\n                self._number_of_attempts -= 1\n                move_dist = self._retry_dist\n                self._spawn_dist += self._retry_dist\n                continue\n\n            # Both actors where summoned, end\n            break\n\n        if self._number_of_attempts == 0:\n            raise ValueError(\"Couldn't find viable position for the adversary\")\n\n        if parking_location:\n            self.parking_slots.append(parking_location)\n\n        if isinstance(adversary, carla.Vehicle):\n            adversary.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(adversary)\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter the in the trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        ego vehicle has to avoid the crash after a turn, but\n        continue driving after the road is clear.If this does not happen\n        within 90 seconds, a timeout stops the scenario.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"CrossingActorIntersection\")\n        collision_location = self._collision_wp.transform.location\n        collision_distance = collision_location.distance(self._adversary_transform.location)\n        collision_duration = collision_distance / self._adversary_speed\n\n        # Adversary trigger behavior\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n        sequence.add_child(HandBrakeVehicle(self.other_actors[0], False))\n\n        # Move the adversary.\n        speed_duration = 2.0 * collision_duration\n        speed_distance = 2.0 * collision_distance\n        if self.route_mode:\n            sequence.add_child(LeaveCrossingSpace(self._collision_wp))\n        sequence.add_child(KeepVelocity(\n            self.other_actors[0], self._adversary_speed, True,\n            speed_duration, speed_distance, name=\"AdversaryCrossing\")\n        )\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass VehicleTurningRight(BaseVehicleTurning):\n    \"\"\"\n    Version of the VehicleTurning scenario where\n    the adversary is placed at the right side after the junction\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._subtype = 'right'\n        super(VehicleTurningRight, self).__init__(\n            world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout, \"VehicleTurningRight\")\n\n\nclass VehicleTurningLeft(BaseVehicleTurning):\n    \"\"\"\n    Version of the VehicleTurning scenario where\n    the adversary is placed at the left side after the junction\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._subtype = 'left'\n        super(VehicleTurningLeft, self).__init__(\n            world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout, \"VehicleTurningLeft\")\n\n\nclass VehicleTurningRoute(BaseVehicleTurning):\n    \"\"\"\n    Version of the VehicleTurning scenario where\n    the adversary is placed using the route path\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._subtype = 'route'\n        super(VehicleTurningRoute, self).__init__(\n            world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout, \"VehicleTurningRoute\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Empty, the route already has a collision criteria\n        \"\"\"\n        return []\n\n\nclass VehicleTurningRoutePedestrian(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    with prior vehicle action involving a vehicle and a cyclist.\n    The ego vehicle is passing through a road and encounters\n    a cyclist after taking a turn.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n    _subtype = None\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60, name=\"VehicleTurningRoutePedestrian\"):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._ego_route = config.route\n\n        self._collision_wp = None\n        self._adversary_speed = 1.8  # Speed of the adversary [m/s]\n        self._reaction_time = 2.2  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n\n        self._offset = {\"yaw\": 270, \"z\": 1.2, \"k\": 1.5}\n\n        self.timeout = timeout\n        super().__init__(name, ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the waypoint right after the junction\n        parking_location = None\n        waypoint = generate_target_waypoint_in_route(self._reference_waypoint, self._ego_route)\n        self._collision_wp = waypoint.next(0.5)[0]  # Some wps are still part of the junction\n\n        # Get the right waypoint at the sidewalk\n        same_dir_wps = get_same_dir_lanes(self._collision_wp)\n        right_wp = same_dir_wps[0]\n        while right_wp.lane_type != carla.LaneType.Sidewalk:\n            side_wp = right_wp.get_right_lane()\n            if side_wp is None:\n                break\n            right_wp = side_wp\n            if right_wp.lane_type == carla.LaneType.Parking:\n                parking_location = right_wp.transform.location\n\n        # Get the left waypoint at the sidewalk\n        other_dir_wps = get_opposite_dir_lanes(self._collision_wp)\n        if other_dir_wps:\n            # With opposite lane\n            left_wp = other_dir_wps[-1]\n            while left_wp.lane_type != carla.LaneType.Sidewalk:\n                side_wp = left_wp.get_right_lane()\n                if side_wp is None:\n                    break\n                left_wp = side_wp\n                if left_wp.lane_type == carla.LaneType.Parking:\n                    parking_location = left_wp.transform.location\n        else:\n            # Without opposite lane\n            self._offset['yaw'] = 90\n            left_wp = same_dir_wps[-1]\n            while left_wp.lane_type != carla.LaneType.Sidewalk:\n                side_wp = left_wp.get_left_lane()\n                if side_wp is None:\n                    break\n                left_wp = side_wp\n                if left_wp.lane_type == carla.LaneType.Parking:\n                    parking_location = left_wp.transform.location\n\n        self._adversary_distance = right_wp.transform.location.distance(left_wp.transform.location)\n\n        entry_vec = self._reference_waypoint.transform.get_forward_vector()\n        exit_vec = waypoint.transform.get_forward_vector()\n        cross_prod = entry_vec.cross(exit_vec)\n        spawn_wp = right_wp if cross_prod.z < 0 else left_wp\n\n        # Get the adversary transform and spawn it\n        self._spawn_transform = get_sidewalk_transform(spawn_wp, self._offset)\n        adversary = CarlaDataProvider.request_new_actor('walker.*', self._spawn_transform)\n        if adversary is None:\n            raise ValueError(\"Couldn't spawn adversary\")\n\n        adversary.set_location(self._spawn_transform.location + carla.Location(z=-200))\n        adversary = self._replace_walker(adversary)\n\n        if parking_location:\n            self.parking_slots.append(parking_location)\n\n        self.other_actors.append(adversary)\n\n    def _create_behavior(self):\n        \"\"\"\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VehicleTurningRoutePedestrian\")\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._spawn_transform, True))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Adversary trigger behavior\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n        if self.route_mode:\n            sequence.add_child(LeaveCrossingSpace(self._collision_wp))\n\n        # Move the adversary.\n        speed_distance = self._adversary_distance\n        speed_duration = self._adversary_distance / self._adversary_speed\n        sequence.add_child(KeepVelocity(\n            self.other_actors[0], self._adversary_speed, True,\n            speed_duration, speed_distance, name=\"AdversaryCrossing\")\n        )\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, adversary):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = adversary.type_id\n        adversary.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        adversary = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not adversary:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        adversary.set_simulate_physics(False)\n        adversary.set_location(spawn_transform.location + carla.Location(z=-50))\n        return adversary\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], self.other_actors[0], 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/object_crash_vehicle.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nObject crash without prior vehicle action scenario:\nThe scenario realizes the user controlled ego vehicle\nmoving along the road and encountering a cyclist ahead.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport math\nimport py_trees\nimport carla\nfrom math import floor\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      KeepVelocity,\n                                                                      Idle,\n                                                                      ActorTransformSetter,\n                                                                      MovePedestrianWithEgo)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_location_in_distance_from_wp\n\nfrom srunner.tools.background_manager import LeaveSpaceInFront, LeaveCrossingSpace\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass StationaryObjectCrossing(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    without prior vehicle action involving a vehicle and a cyclist.\n    The ego vehicle is passing through a road and encounters\n    a stationary cyclist.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location)\n        # ego vehicle parameters\n        self._ego_vehicle_distance_driven = 40\n\n        # other vehicle parameters\n        self._other_actor_target_velocity = 10\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(StationaryObjectCrossing, self).__init__(\"Stationaryobjectcrossing\",\n                                                       ego_vehicles,\n                                                       config,\n                                                       world,\n                                                       debug_mode,\n                                                       criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        _distance = 40\n        lane_width = self._reference_waypoint.lane_width\n        location, _ = get_location_in_distance_from_wp(self._reference_waypoint, _distance)\n        waypoint = self._wmap.get_waypoint(location)\n        offset = {\"orientation\": 270, \"position\": 90, \"z\": 0.4, \"k\": 0.2}\n        position_yaw = waypoint.transform.rotation.yaw + offset['position']\n        orientation_yaw = waypoint.transform.rotation.yaw + offset['orientation']\n        offset_location = carla.Location(\n            offset['k'] * lane_width * math.cos(math.radians(position_yaw)),\n            offset['k'] * lane_width * math.sin(math.radians(position_yaw)))\n        location += offset_location\n        location.z += offset['z']\n        self.transform = carla.Transform(location, carla.Rotation(yaw=orientation_yaw))\n        static = CarlaDataProvider.request_new_actor('static.prop.container', self.transform)\n        static.set_simulate_physics(True)\n        self.other_actors.append(static)\n\n    def _create_behavior(self):\n        \"\"\"\n        Only behavior here is to wait\n        \"\"\"\n        lane_width = self.ego_vehicles[0].get_world().get_map().get_waypoint(\n            self.ego_vehicles[0].get_location()).lane_width\n        lane_width = lane_width + (1.25 * lane_width)\n\n        # leaf nodes\n        actor_stand = Idle(15)\n        actor_removed = ActorDestroy(self.other_actors[0])\n        end_condition = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_distance_driven)\n\n        # non leaf nodes\n        root = py_trees.composites.Parallel(\n            name=\"StaticObstacle\",\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        scenario_sequence = py_trees.composites.Sequence()\n\n        # building tree\n        root.add_child(scenario_sequence)\n        scenario_sequence.add_child(actor_stand)\n        scenario_sequence.add_child(actor_removed)\n        scenario_sequence.add_child(end_condition)\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass DynamicObjectCrossing(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple object crash\n    without prior vehicle action involving a vehicle and a cyclist/pedestrian,\n    The ego vehicle is passing through a road,\n    And encounters a cyclist/pedestrian crossing the road.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._num_lane_changes = 0\n\n        self._blocker_shift = 0.9\n        self._retry_dist = 0.4\n\n        self._adversary_transform = None\n        self._blocker_transform = None\n        self._collision_wp = None\n\n        self._adversary_speed = 2.0  # Speed of the adversary [m/s]\n        self._crossing_angle = get_value_parameter(config, 'crossing_angle', float, 0)\n        self._reaction_time = 2.1  # Time the agent has to react to avoid the collision [s]\n        self._reaction_time += 0.1 * floor(self._crossing_angle / 5)\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n        self.timeout = timeout\n\n        self._number_of_attempts = 6\n\n        self._distance = get_value_parameter(config, 'distance', float, 12)\n        self._blocker_model = get_value_parameter(config, 'blocker_model', str, 'static.prop.vendingmachine')\n        if abs(self._crossing_angle) > 90:\n            raise ValueError(\"'crossing_angle' must be between -90 and 90º for the pedestrian to cross the road\")\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        super(DynamicObjectCrossing, self).__init__(\"DynamicObjectCrossing\",\n                                                    ego_vehicles,\n                                                    config,\n                                                    world,\n                                                    debug_mode,\n                                                    criteria_enable=criteria_enable)\n\n    def _get_sidewalk_transform(self, waypoint, offset):\n        \"\"\"\n        Processes the waypoint transform to find a suitable spawning one at the sidewalk.\n        It first rotates the transform so that it is pointing towards the road and then moves a\n        bit to the side waypoint that aren't part of sidewalks, as they might be invading the road\n        \"\"\"\n        if self._direction == \"left\":\n            offset['yaw'] *= -1\n            offset['k'] *= -1\n\n        new_rotation = waypoint.transform.rotation\n        new_rotation.yaw += offset['yaw']\n\n        if waypoint.lane_type == carla.LaneType.Sidewalk:\n            new_location = waypoint.transform.location\n        else:\n            right_vector = waypoint.transform.get_right_vector()\n            offset_dist = offset[\"k\"]\n            offset_location = carla.Location(offset_dist * right_vector.x, offset_dist * right_vector.y)\n            new_location = waypoint.transform.location + offset_location\n        new_location.z += offset['z']\n\n        return carla.Transform(new_location, new_rotation)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the waypoint in front of the ego.\n        move_dist = self._distance\n        waypoint = self._reference_waypoint\n\n        while self._number_of_attempts > 0:\n            parking_location = None\n            self._collision_dist = 0\n\n            # Move to the front\n            location, _ = get_location_in_distance_from_wp(waypoint, move_dist, False)\n            waypoint = self._wmap.get_waypoint(location)\n            self._collision_wp = waypoint\n\n            # Move to the right\n            sidewalk_waypoint = waypoint\n            while sidewalk_waypoint.lane_type != carla.LaneType.Sidewalk:\n                if self._direction == \"right\":\n                    side_wp = sidewalk_waypoint.get_right_lane()\n                else:\n                    side_wp = sidewalk_waypoint.get_left_lane()\n                if side_wp is None:\n                    break  # No more side lanes\n                sidewalk_waypoint = side_wp\n                if side_wp.lane_type == carla.LaneType.Parking:\n                    parking_location = side_wp.transform.location\n\n            # Get the blocker transform and spawn it\n            offset = {\"yaw\": 0 if 'vehicle' in self._blocker_model else 90, \"z\": 0.0, \"k\": 1.5}\n            self._blocker_transform = self._get_sidewalk_transform(sidewalk_waypoint, offset)\n            blocker = CarlaDataProvider.request_new_actor(\n                self._blocker_model, self._blocker_transform, rolename=\"scenario no lights\")\n            if not blocker:\n                self._number_of_attempts -= 1\n                move_dist = self._retry_dist\n                print(\"Failed to spawn the blocker\")\n                continue\n\n            # Get the adversary transform and spawn it\n            walker_dist = blocker.bounding_box.extent.x + 0.5\n            wps = sidewalk_waypoint.next(walker_dist)\n            if not wps:\n                raise ValueError(\"Couldn't find a location to spawn the adversary\")\n            walker_wp = wps[0]\n\n            offset = {\"yaw\": 270 - self._crossing_angle, \"z\": 1.2, \"k\": 1.2}\n            self._adversary_transform = self._get_sidewalk_transform(walker_wp, offset)\n            adversary = CarlaDataProvider.request_new_actor('walker.*', self._adversary_transform)\n            if adversary is None:\n                blocker.destroy()\n                self._number_of_attempts -= 1\n                move_dist = self._retry_dist\n                print(\"Failed to spawn an adversary\")\n                continue\n\n            self._collision_dist += waypoint.transform.location.distance(self._adversary_transform.location)\n\n            # Both actors were succesfully spawned, end\n            break\n\n        if self._number_of_attempts == 0:\n            raise Exception(\"Couldn't find viable position for the adversary and blocker actors\")\n\n        blocker.set_simulate_physics(False)\n        adversary.set_location(self._adversary_transform.location + carla.Location(z=-200))\n        adversary = self._replace_walker(adversary)\n\n        if parking_location:\n            self.parking_slots.append(parking_location)\n\n        self.other_actors.append(adversary)\n        self.other_actors.append(blocker)\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        then after 60 seconds, a timeout stops the scenario\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"CrossingActor\")\n        if self.route_mode:\n            total_dist = self._distance + 10\n            sequence.add_child(LeaveSpaceInFront(total_dist))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._adversary_transform, True))\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        # Move the adversary\n        move_distance = 2 * self._collision_dist  # Cross the whole road (supposing symetry in both directions)\n        move_duration = move_distance / self._adversary_speed\n        if self.route_mode:\n            sequence.add_child(LeaveCrossingSpace(self._collision_wp))\n        sequence.add_child(KeepVelocity(\n            self.other_actors[0], self._adversary_speed,\n            duration=move_duration, distance=move_distance, name=\"AdversaryCrossing\"))\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(ActorDestroy(self.other_actors[1], name=\"DestroyBlocker\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, adversary):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = adversary.type_id\n        adversary.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        adversary = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not adversary:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        adversary.set_simulate_physics(False)\n        adversary.set_location(spawn_transform.location + carla.Location(z=-50))\n        return adversary\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], self.other_actors[0], 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n\n\nclass ParkingCrossingPedestrian(BasicScenario):\n\n    \"\"\"\n    Variation of DynamicObjectCrossing but now the blocker is now a vehicle\n    This class holds everything required for a simple object crash\n    without prior vehicle action involving a vehicle and a cyclist/pedestrian,\n    The ego vehicle is passing through a road,\n    And encounters a cyclist/pedestrian crossing the road.\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._num_lane_changes = 0\n\n        self._adversary_speed = 2.0  # Speed of the adversary [m/s]\n        self._min_trigger_dist = 6.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n        self.timeout = timeout\n\n        self._bp_attributes = {'base_type': 'car', 'generation': 2}\n\n        self._distance = get_value_parameter(config, 'distance', float, 12)\n        self._crossing_angle = get_value_parameter(config, 'crossing_angle', float, 0)\n        if abs(self._crossing_angle) > 90:\n            raise ValueError(\"'crossing_angle' must be between -90 and 90º for the pedestrian to cross the road\")\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        # Time the agent has to react to avoid the collision [s]\n        self._reaction_time = 2.15\n        self._reaction_time += 0.1 * floor(self._crossing_angle / 5)\n\n        super().__init__(\"ParkingCrossingPedestrian\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _get_blocker_transform(self, waypoint):\n        \"\"\"Processes the driving wp to get a waypoint at the side that looks at the road\"\"\"\n        if waypoint.lane_type == carla.LaneType.Sidewalk:\n            new_location = waypoint.transform.location\n        else:\n            vector = waypoint.transform.get_right_vector()\n            if self._direction == 'left':\n                vector *= -1\n\n            offset_location = carla.Location(waypoint.lane_width * vector.x, waypoint.lane_width * vector.y)\n            new_location = waypoint.transform.location + offset_location\n        new_location.z += 0.5\n\n        return carla.Transform(new_location, waypoint.transform.rotation)\n\n    def _get_walker_transform(self, waypoint):\n        \"\"\"Processes the driving wp to get a waypoint at the side that looks at the road\"\"\"\n\n        new_rotation = waypoint.transform.rotation\n        new_rotation.yaw += 270 - self._crossing_angle if self._direction == 'right' else 90 + self._crossing_angle\n\n        if waypoint.lane_type == carla.LaneType.Sidewalk:\n            new_location = waypoint.transform.location\n        else:\n            vector = waypoint.transform.get_right_vector()\n            if self._direction == 'left':\n                vector *= -1\n\n            offset_location = carla.Location(waypoint.lane_width * vector.x, waypoint.lane_width * vector.y)\n            new_location = waypoint.transform.location + offset_location\n        new_location.z += 1.2\n\n        return carla.Transform(new_location, new_rotation)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Get the adversary transform and spawn it\n        wps = self._reference_waypoint.next(self._distance)\n        if not wps:\n            raise ValueError(\"Couldn't find a location to spawn the adversary\")\n        blocker_wp = wps[0]\n\n        # Get the adversary transform and spawn it\n        self._blocker_transform = self._get_blocker_transform(blocker_wp)\n        self.parking_slots.append(self._blocker_transform.location)\n        blocker = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._blocker_transform, attribute_filter=self._bp_attributes)\n        if blocker is None:\n            raise ValueError(\"Couldn't spawn the adversary\")\n        self.other_actors.append(blocker)\n        blocker.apply_control(carla.VehicleControl(hand_brake=True))\n\n        walker_dist = blocker.bounding_box.extent.x + 0.5\n        wps = blocker_wp.next(walker_dist)\n        if not wps:\n            raise ValueError(\"Couldn't find a location to spawn the adversary\")\n        walker_wp = wps[0]\n\n        # Get the adversary transform and spawn it\n        self._walker_transform = self._get_walker_transform(walker_wp)\n        self.parking_slots.append(self._walker_transform.location)\n\n        walker = CarlaDataProvider.request_new_actor('walker.*', self._walker_transform)\n        if walker is None:\n            raise ValueError(\"Couldn't spawn the adversary\")\n\n        walker.set_location(self._walker_transform.location + carla.Location(z=-200))\n        walker = self._replace_walker(walker)\n \n        self.other_actors.append(walker)\n\n        self._collision_wp = walker_wp\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        then after 60 seconds, a timeout stops the scenario\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"ParkingCrossingPedestrian\")\n        if self.route_mode:\n            total_dist = self._distance + 15\n            sequence.add_child(LeaveSpaceInFront(total_dist))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[1], self._walker_transform, True))\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        # Move the adversary\n        distance = 8.0  # Scenario is meant to be used at a one lane - one direction road\n        duration = distance / self._adversary_speed\n\n        sequence.add_child(KeepVelocity(\n            self.other_actors[1], self._adversary_speed,\n            duration=duration, distance=distance, name=\"AdversaryCrossing\"))\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[1], name=\"DestroyAdversary\"))\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyBlocker\"))\n        sequence.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, walker):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = walker.type_id\n        walker.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        walker = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not walker:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        walker.set_simulate_physics(False)\n        walker.set_location(spawn_transform.location + carla.Location(z=-50))\n        return walker\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], self.other_actors[1], 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/open_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nBasic scenario class using the OpenSCENARIO definition\n\"\"\"\n\nfrom __future__ import print_function\n\nimport itertools\nimport os\nimport py_trees\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeWeather, ChangeRoadFriction, ChangeParameter\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeActorControl, ChangeActorTargetSpeed\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.weather_sim import OSCWeatherBehavior\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.openscenario_parser import OpenScenarioParser, oneshot_with_check, ParameterRef\nfrom srunner.tools.py_trees_port import Decorator\n\n\ndef repeatable_behavior(behaviour, name=None):\n    \"\"\"\n    This behaviour allows a composite with oneshot ancestors to run multiple\n    times, resetting the oneshot variables after each execution\n    \"\"\"\n    if not name:\n        name = behaviour.name\n    clear_descendant_variables = ClearBlackboardVariablesStartingWith(\n        name=\"Clear Descendant Variables of {}\".format(name),\n        variable_name_beginning=name + \">\"\n    )\n    # If it's a sequence, don't double-nest it in a redundant manner\n    if isinstance(behaviour, py_trees.composites.Sequence):\n        behaviour.add_child(clear_descendant_variables)\n        sequence = behaviour\n    else:\n        sequence = py_trees.composites.Sequence(name=\"RepeatableBehaviour of {}\".format(name))\n        sequence.add_children([behaviour, clear_descendant_variables])\n    return sequence\n\n\nclass ClearBlackboardVariablesStartingWith(py_trees.behaviours.Success):\n\n    \"\"\"\n    Clear the values starting with the specified string from the blackboard.\n\n    Args:\n        name (:obj:`str`): name of the behaviour\n        variable_name_beginning (:obj:`str`): beginning of the names of variable to clear\n    \"\"\"\n\n    def __init__(self,\n                 name=\"Clear Blackboard Variable Starting With\",\n                 variable_name_beginning=\"dummy\",\n                 ):\n        super(ClearBlackboardVariablesStartingWith, self).__init__(name)\n        self.variable_name_beginning = variable_name_beginning\n\n    def initialise(self):\n        \"\"\"\n        Delete the variables from the blackboard.\n        \"\"\"\n        blackboard_variables = [key for key, _ in py_trees.blackboard.Blackboard().__dict__.items(\n        ) if key.startswith(self.variable_name_beginning)]\n        for variable in blackboard_variables:\n            delattr(py_trees.blackboard.Blackboard(), variable)\n\n\nclass StoryElementStatusToBlackboard(Decorator):\n\n    \"\"\"\n    Reflect the status of the decorator's child story element to the blackboard.\n\n    Args:\n        child: the child behaviour or subtree\n        story_element_type: the element type [act,scene,maneuver,event,action]\n        element_name: the story element's name attribute\n    \"\"\"\n\n    def __init__(self, child, story_element_type, element_name):\n        super(StoryElementStatusToBlackboard, self).__init__(name=child.name, child=child)\n        self.story_element_type = story_element_type\n        self.element_name = element_name\n        self.blackboard = py_trees.blackboard.Blackboard()\n\n    def initialise(self):\n        \"\"\"\n        Record the elements's start time on the blackboard\n        \"\"\"\n        self.blackboard.set(\n            name=\"({}){}-{}\".format(self.story_element_type.upper(),\n                                    self.element_name, \"START\"),\n            value=GameTime.get_time(),\n            overwrite=True\n        )\n\n    def update(self):\n        \"\"\"\n        Reflect the decorated child's status\n        Returns: the decorated child's status\n        \"\"\"\n        return self.decorated.status\n\n    def terminate(self, new_status):\n        \"\"\"\n        Terminate and mark Blackboard entry with END\n        \"\"\"\n        # Report whether we ended with End or Cancel\n        # If we were ended or cancelled, our state will be INVALID and\n        # We will have an ancestor (a parallel SUCCESS_ON_ALL) with a successful child/children\n        # It's possible we ENDed AND CANCELled if both condition groups were true simultaneously\n        # NOTE 'py_trees.common.Status.INVALID' is the status of a behaviur which was terminated by a parent\n        rules = []\n        if new_status == py_trees.common.Status.INVALID:\n            # We were terminated from above unnaturally\n            # Figure out if were ended or cancelled\n            terminating_ancestor = self.parent\n            while terminating_ancestor.status == py_trees.common.Status.INVALID:\n                terminating_ancestor = terminating_ancestor.parent\n            # We have found an ancestory which was not terminated by a parent\n            # Check what caused it to terminate its children\n            if terminating_ancestor.status == py_trees.common.Status.SUCCESS:\n                successful_children = [\n                    child.name\n                    for child\n                    in terminating_ancestor.children\n                    if child.status == py_trees.common.Status.SUCCESS]\n                if \"StopTrigger\" in successful_children:\n                    rules.append(\"END\")\n\n        # END is the default status unless we have a more detailed one\n        rules = rules or [\"END\"]\n\n        for rule in rules:\n            self.blackboard.set(\n                name=\"({}){}-{}\".format(self.story_element_type.upper(),\n                                        self.element_name, rule),\n                value=GameTime.get_time(),\n                overwrite=True\n            )\n\n\ndef get_xml_path(tree, node):\n    \"\"\"\n    Extract the full path of a node within an XML tree\n\n    Note: Catalogs are pulled from a separate file so the XML tree is split.\n          This means that in order to get the XML path, it must be done in 2 steps.\n          Some places in this python script do that by concatenating the results\n          of 2 get_xml_path calls with another \">\".\n          Example: \"Behavior>AutopilotSequence\" + \">\" + \"StartAutopilot>StartAutopilot>StartAutopilot\"\n    \"\"\"\n\n    path = \"\"\n    parent_map = {c: p for p in tree.iter() for c in p}\n\n    cur_node = node\n    while cur_node != tree:\n        path = \"{}>{}\".format(cur_node.attrib.get('name'), path)\n        cur_node = parent_map[cur_node]\n\n    path = path[:-1]\n    return path\n\n\nclass OpenScenario(BasicScenario):\n\n    \"\"\"\n    Implementation of the OpenSCENARIO scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, config_file, debug_mode=False, criteria_enable=True, timeout=300):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self.config = config\n        self.route = None\n        self.config_file = config_file\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(OpenScenario, self).__init__(self.config.name, ego_vehicles=ego_vehicles, config=config,\n                                           world=world, debug_mode=debug_mode,\n                                           terminate_on_failure=False, criteria_enable=criteria_enable)\n\n    def _initialize_parameters(self):\n        \"\"\"\n        Parse ParameterAction from Init and update global osc parameters.\n        \"\"\"\n        param_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"ParametersInit\")\n        for i, global_action in enumerate(self.config.init.find('Actions').iter('GlobalAction')):\n            maneuver_name = 'InitParams'\n            if global_action.find('ParameterAction') is not None:\n                parameter_action = global_action.find('ParameterAction')\n                parameter_ref = parameter_action.attrib.get('parameterRef')\n                if parameter_action.find('ModifyAction') is not None:\n                    action_rule = parameter_action.find('ModifyAction').find(\"Rule\")\n                    if action_rule.find(\"AddValue\") is not None:\n                        rule, value = '+', action_rule.find(\"AddValue\").attrib.get('value')\n                    else:\n                        rule, value = '*', action_rule.find(\"MultiplyByValue\").attrib.get('value')\n                else:\n                    rule, value = None, parameter_action.find('SetAction').attrib.get('value')\n                parameter_update = ChangeParameter(parameter_ref, value=ParameterRef(value), rule=rule,\n                                                   name=maneuver_name + '_%d' % i)\n                param_behavior.add_child(oneshot_with_check(variable_name=\"InitialParameters\" + '_%d' % i,\n                                                            behaviour=parameter_update))\n\n        return param_behavior\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Initialization of weather and road friction.\n        \"\"\"\n        pass\n\n    def _create_environment_behavior(self):\n        # Set the appropriate weather conditions\n\n        env_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"EnvironmentBehavior\")\n\n        weather_update = ChangeWeather(\n            OpenScenarioParser.get_weather_from_env_action(self.config.init, self.config.catalogs))\n        road_friction = ChangeRoadFriction(\n            OpenScenarioParser.get_friction_from_env_action(self.config.init, self.config.catalogs))\n        env_behavior.add_child(oneshot_with_check(variable_name=\"InitialWeather\", behaviour=weather_update))\n        env_behavior.add_child(oneshot_with_check(variable_name=\"InitRoadFriction\", behaviour=road_friction))\n\n        return env_behavior\n\n    def _create_init_behavior(self):\n\n        init_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"InitBehaviour\")\n\n        for actor in self.config.other_actors + self.config.ego_vehicles:\n            for carla_actor in self.other_actors + self.ego_vehicles:\n                if (carla_actor is not None and 'role_name' in carla_actor.attributes and\n                        carla_actor.attributes['role_name'] == actor.rolename):\n                    actor_init_behavior = py_trees.composites.Sequence(name=\"InitActor{}\".format(actor.rolename))\n\n                    controller_atomic = None\n\n                    for private in self.config.init.iter(\"Private\"):\n                        if private.attrib.get('entityRef', None) == actor.rolename:\n                            for private_action in private.iter(\"PrivateAction\"):\n                                for controller_action in private_action.iter('ControllerAction'):\n                                    module, args = OpenScenarioParser.get_controller(\n                                        controller_action, self.config.catalogs)\n                                    controller_atomic = ChangeActorControl(\n                                        carla_actor, control_py_module=module, args=args,\n                                        scenario_file_path=os.path.dirname(self.config.filename))\n\n                    if controller_atomic is None:\n                        controller_atomic = ChangeActorControl(carla_actor, control_py_module=None, args={})\n\n                    actor_init_behavior.add_child(controller_atomic)\n\n                    if actor.speed > 0:\n                        actor_init_behavior.add_child(ChangeActorTargetSpeed(carla_actor, actor.speed, init_speed=True))\n\n                    init_behavior.add_child(actor_init_behavior)\n                    break\n\n        return init_behavior\n\n    def _create_behavior(self):\n        \"\"\"\n        Basic behavior do nothing, i.e. Idle\n        \"\"\"\n\n        stories_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL,\n                                                        name=\"OSCStories\")\n        joint_actor_list = self.other_actors + self.ego_vehicles + [None]\n\n        for story in self.config.stories:\n            story_name = story.get(\"name\")\n            story_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL,\n                                                          name=story_name)\n            for act in story.iter(\"Act\"):\n\n                act_sequence = py_trees.composites.Sequence(\n                    name=\"Act StartConditions and behaviours\")\n\n                start_conditions = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"StartConditions Group\")\n\n                parallel_behavior = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"Maneuver + EndConditions Group\")\n\n                parallel_sequences = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"Maneuvers\")\n\n                for sequence in act.iter(\"ManeuverGroup\"):\n                    sequence_behavior = py_trees.composites.Sequence(name=sequence.attrib.get('name'))\n                    repetitions = sequence.attrib.get('maximumExecutionCount', 1)\n\n                    for _ in range(int(repetitions)):\n\n                        actor_ids = []\n                        for actor in sequence.iter(\"Actors\"):\n                            for entity in actor.iter(\"EntityRef\"):\n                                entity_name = entity.attrib.get('entityRef', None)\n                                for k, _ in enumerate(joint_actor_list):\n                                    if (joint_actor_list[k] and\n                                            entity_name == joint_actor_list[k].attributes['role_name']):\n                                        actor_ids.append(k)\n                                        break\n\n                        if not actor_ids:\n                            print(\"Warning: Maneuvergroup {} does not use reference actors!\".format(\n                                sequence.attrib.get('name')))\n                            actor_ids.append(len(joint_actor_list) - 1)\n\n                    # Collect catalog reference maneuvers in order to process them at the same time as normal maneuvers\n                        catalog_maneuver_list = []\n                        for catalog_reference in sequence.iter(\"CatalogReference\"):\n                            catalog_maneuver = OpenScenarioParser.get_catalog_entry(self.config.catalogs,\n                                                                                    catalog_reference)\n                            catalog_maneuver_list.append(catalog_maneuver)\n                        all_maneuvers = itertools.chain(iter(catalog_maneuver_list), sequence.iter(\"Maneuver\"))\n                        single_sequence_iteration = py_trees.composites.Parallel(\n                            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=sequence_behavior.name)\n                        for maneuver in all_maneuvers:  # Iterates through both CatalogReferences and Maneuvers\n                            maneuver_parallel = py_trees.composites.Parallel(\n                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL,\n                                name=\"Maneuver \" + maneuver.attrib.get('name'))\n                            for event in maneuver.iter(\"Event\"):\n                                event_sequence = py_trees.composites.Sequence(\n                                    name=\"Event \" + event.attrib.get('name'))\n                                parallel_actions = py_trees.composites.Parallel(\n                                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"Actions\")\n                                for child in event.iter():\n                                    if child.tag == \"Action\":\n                                        for actor_id in actor_ids:\n                                            maneuver_behavior = OpenScenarioParser.convert_maneuver_to_atomic(\n                                                child, joint_actor_list[actor_id],\n                                                joint_actor_list, self.config.catalogs)\n                                            maneuver_behavior = StoryElementStatusToBlackboard(\n                                                maneuver_behavior, \"ACTION\", child.attrib.get('name'))\n                                            parallel_actions.add_child(\n                                                oneshot_with_check(variable_name=  # See note in get_xml_path\n                                                                   get_xml_path(story, sequence) + '>' + \\\n                                                                   get_xml_path(maneuver, child) + '>' + \\\n                                                                   str(actor_id),\n                                                                   behaviour=maneuver_behavior))\n\n                                    if child.tag == \"StartTrigger\":\n                                        # There is always one StartConditions block per Event\n                                        parallel_condition_groups = self._create_condition_container(\n                                            child, story, \"Parallel Condition Groups\", sequence, maneuver)\n                                        event_sequence.add_child(\n                                            parallel_condition_groups)\n\n                                parallel_actions = StoryElementStatusToBlackboard(\n                                    parallel_actions, \"EVENT\", event.attrib.get('name'))\n                                event_sequence.add_child(parallel_actions)\n                                maneuver_parallel.add_child(\n                                    oneshot_with_check(variable_name=get_xml_path(story, sequence) + '>' +\n                                                       get_xml_path(maneuver, event),  # See get_xml_path\n                                                       behaviour=event_sequence))\n                            maneuver_parallel = StoryElementStatusToBlackboard(\n                                maneuver_parallel, \"MANEUVER\", maneuver.attrib.get('name'))\n                            single_sequence_iteration.add_child(\n                                oneshot_with_check(variable_name=get_xml_path(story, sequence) + '>' +\n                                                   maneuver.attrib.get('name'),  # See get_xml_path\n                                                   behaviour=maneuver_parallel))\n\n                        # OpenSCENARIO refers to Sequences as Scenes in this instance\n                        single_sequence_iteration = StoryElementStatusToBlackboard(\n                            single_sequence_iteration, \"SCENE\", sequence.attrib.get('name'))\n                        single_sequence_iteration = repeatable_behavior(\n                            single_sequence_iteration, get_xml_path(story, sequence))\n\n                        sequence_behavior.add_child(single_sequence_iteration)\n\n                    if sequence_behavior.children:\n                        parallel_sequences.add_child(\n                            oneshot_with_check(variable_name=get_xml_path(story, sequence),\n                                               behaviour=sequence_behavior))\n\n                if parallel_sequences.children:\n                    parallel_sequences = StoryElementStatusToBlackboard(\n                        parallel_sequences, \"ACT\", act.attrib.get('name'))\n                    parallel_behavior.add_child(parallel_sequences)\n\n                start_triggers = act.find(\"StartTrigger\")\n                if list(start_triggers) is not None:\n                    for start_condition in start_triggers:\n                        parallel_start_criteria = self._create_condition_container(start_condition,\n                                                                                   story,\n                                                                                   \"StartConditions\")\n                        if parallel_start_criteria.children:\n                            start_conditions.add_child(parallel_start_criteria)\n                end_triggers = act.find(\"StopTrigger\")\n                if end_triggers is not None and list(end_triggers) is not None:\n                    for end_condition in end_triggers:\n                        parallel_end_criteria = self._create_condition_container(\n                            end_condition, story, \"EndConditions\", success_on_all=False)\n                        if parallel_end_criteria.children:\n                            parallel_behavior.add_child(parallel_end_criteria)\n\n                if start_conditions.children:\n                    act_sequence.add_child(start_conditions)\n                if parallel_behavior.children:\n                    act_sequence.add_child(parallel_behavior)\n\n                if act_sequence.children:\n                    story_behavior.add_child(act_sequence)\n\n            stories_behavior.add_child(oneshot_with_check(variable_name=get_xml_path(story, story) + '>' +\n                                                          story_name,  # See get_xml_path\n                                                          behaviour=story_behavior))\n\n        # Build behavior tree\n        behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"behavior\")\n\n        init_parameters = self._initialize_parameters()\n        if init_parameters is not None:\n            behavior.add_child(oneshot_with_check(variable_name=\"InitialParameterSettings\", behaviour=init_parameters))\n\n        env_behavior = self._create_environment_behavior()\n        if env_behavior is not None:\n            behavior.add_child(oneshot_with_check(variable_name=\"InitialEnvironmentSettings\", behaviour=env_behavior))\n\n        init_behavior = self._create_init_behavior()\n        if init_behavior is not None:\n            behavior.add_child(oneshot_with_check(variable_name=\"InitialActorSettings\", behaviour=init_behavior))\n\n        behavior.add_child(stories_behavior)\n\n        return behavior\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Sets the osc weather behavior, which will monitor other behaviors, changing the weather\n        \"\"\"\n        return OSCWeatherBehavior()\n\n    def _create_condition_container(self, node, story, name='Conditions Group', sequence=None,\n                                    maneuver=None, success_on_all=True):\n        \"\"\"\n        This is a generic function to handle conditions utilising ConditionGroups\n        Each ConditionGroup is represented as a Sequence of Conditions\n        The ConditionGroups are grouped under a SUCCESS_ON_ONE Parallel\n        \"\"\"\n\n        parallel_condition_groups = py_trees.composites.Parallel(name,\n                                                                 policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        for condition_group in node.iter(\"ConditionGroup\"):\n            if success_on_all:\n                condition_group_sequence = py_trees.composites.Parallel(\n                    name=\"Condition Group\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n            else:\n                condition_group_sequence = py_trees.composites.Parallel(\n                    name=\"Condition Group\", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n            for condition in condition_group.iter(\"Condition\"):\n                criterion = OpenScenarioParser.convert_condition_to_atomic(\n                    condition, self.other_actors + self.ego_vehicles)\n                if sequence is not None and maneuver is not None:\n                    xml_path = get_xml_path(story, sequence) + '>' + \\\n                        get_xml_path(maneuver, condition)  # See note in get_xml_path\n                else:\n                    xml_path = get_xml_path(story, condition)\n                criterion = oneshot_with_check(variable_name=xml_path, behaviour=criterion)\n                condition_group_sequence.add_child(criterion)\n\n            if condition_group_sequence.children:\n                parallel_condition_groups.add_child(condition_group_sequence)\n\n        return parallel_condition_groups\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        parallel_criteria = py_trees.composites.Parallel(\"EndConditions (Criteria Group)\",\n                                                         policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        criteria = []\n        for endcondition in self.config.storyboard.iter(\"StopTrigger\"):\n            for condition in endcondition.iter(\"Condition\"):\n                if condition.attrib.get('name').startswith('criteria_'):\n                    criteria.append(condition)\n\n        for condition in criteria:\n            criterion = OpenScenarioParser.convert_condition_to_atomic(condition, self.ego_vehicles)\n            parallel_criteria.add_child(criterion)\n\n        return parallel_criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/opposite_vehicle_taking_priority.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      TrafficLightFreezer,\n                                                                      ConstantVelocityAgentBehavior,\n                                                                      Idle)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               WaitEndIntersection)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (get_geometric_linear_intersection,\n                                           generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\n\n\nclass OppositeVehicleJunction(BasicScenario):\n    \"\"\"\n    Scenario in which another vehicle enters the junction a tthe same time as the ego,\n    forcing it to break to avoid a collision\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._source_dist = 30\n        self._sink_dist = 10\n        self._adversary_speed = 60 / 3.6 # m/s\n\n        if 'direction' in config.other_parameters:\n            self._direction = config.other_parameters['direction']['value']\n        else:\n            self._direction = \"right\"\n\n\n        self.timeout = timeout\n\n        self._sync_time = 2.2  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 12.0  # Min distance to the collision location that triggers the adversary [m]\n\n        self._lights = carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2\n\n        super().__init__(\"OppositeVehicleJunction\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the opposite entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Couldn't find a lane for the given direction\")\n\n        # Get the source transform\n        spawn_wp = source_entry_wps[0]\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            spawn_wps = spawn_wp.previous(1.0)\n            if len(spawn_wps) == 0:\n                raise ValueError(\"Failed to find a source location as a waypoint with no previous was detected\")\n            if spawn_wps[0].is_junction:\n                break\n            spawn_wp = spawn_wps[0]\n            source_junction_dist += 1\n        self._spawn_wp = spawn_wp\n\n        source_transform = spawn_wp.transform\n        self._spawn_location = carla.Transform(\n            source_transform.location + carla.Location(z=0.1),\n            source_transform.rotation\n        )\n        self.parking_slots.append(source_transform.location)\n\n        # Spawn the actor and move it below ground\n        opposite_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._spawn_location, attribute_filter={'special_type': 'emergency'})\n        if not opposite_actor:\n            raise Exception(\"Couldn't spawn the actor\")\n        lights = opposite_actor.get_light_state()\n        lights |= self._lights\n        opposite_actor.set_light_state(carla.VehicleLightState(lights))\n        self.other_actors.append(opposite_actor)\n\n        opposite_transform = carla.Transform(\n            source_transform.location - carla.Location(z=500),\n            source_transform.rotation\n        )\n        opposite_actor.set_transform(opposite_transform)\n        opposite_actor.set_simulate_physics(enabled=False)\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 0)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location as a waypoint with no next was detected\")\n        self._sink_wp = sink_wps[0]\n\n        # get the collision location\n        self._collision_location = get_geometric_linear_intersection(\n            starting_wp.transform.location, source_entry_wps[0].transform.location, True)\n        if not self._collision_location:\n            raise ValueError(\"Couldn't find an intersection point\")\n\n        # Get the z component\n        collision_wp = self._map.get_waypoint(self._collision_location)\n        self._collision_location.z = collision_wp.transform.location.z\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass OppositeVehicleRunningRedLight(OppositeVehicleJunction):\n    \"\"\"\n    Signalized junction version, where the other vehicle runs a red light\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        self._tl_dict = {}\n        for tl in tls:\n            if tl == ego_tl:\n                self._tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"OppositeVehicleRunningRedLight\")\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._sync_time, self._collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n\n        end_location = self._sink_wp.transform.location\n        start_location = self._spawn_wp.transform.location\n        time = start_location.distance(end_location) / self._adversary_speed\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ConstantVelocityAgentBehavior(\n            self.other_actors[0], target_location=end_location,\n            target_speed=self._adversary_speed,\n            opt_dict={'ignore_vehicles': True, 'ignore_traffic_lights': True},\n            name=\"AdversaryCrossing\")\n        )\n        main_behavior.add_child(Idle(time))\n\n        sequence.add_child(main_behavior)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n        sequence.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        tls_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        tls_behavior.add_child(TrafficLightFreezer(self._tl_dict))\n        tls_behavior.add_child(sequence)\n\n        root = py_trees.composites.Sequence()\n        if self.route_mode:\n            root.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[self._spawn_wp],\n                remove_exits=[self._sink_wp],\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n        root.add_child(ActorTransformSetter(self.other_actors[0], self._spawn_location))\n        root.add_child(tls_behavior)\n\n        return root\n\n\nclass OppositeVehicleTakingPriority(OppositeVehicleJunction):\n    \"\"\"\n    Non signalized version\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is entering a junction in an urban area, at a signalized intersection,\n        while another actor runs a red lift, forcing the ego to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"OppositeVehicleTakingPriority\")\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._sync_time, self._collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._collision_location, self._min_trigger_dist))\n\n        sequence.add_child(trigger_adversary)\n\n        end_location = self._sink_wp.transform.location\n        start_location = self._spawn_wp.transform.location\n        time = start_location.distance(end_location) / self._adversary_speed\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ConstantVelocityAgentBehavior(\n            self.other_actors[0], target_location=end_location,\n            target_speed=self._adversary_speed,\n            opt_dict={'ignore_vehicles': True, 'ignore_traffic_lights': True},\n            name=\"AdversaryCrossing\")\n        )\n        main_behavior.add_child(Idle(time))\n\n        sequence.add_child(main_behavior)\n\n        root = py_trees.composites.Sequence()\n        if self.route_mode:\n            root.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=[self._spawn_wp],\n                remove_exits=[self._sink_wp],\n                stop_entries=True,\n                extend_road_exit=0\n            ))\n\n        root.add_child(ActorTransformSetter(self.other_actors[0], self._spawn_location))\n        root.add_child(sequence)\n        root.add_child(ActorDestroy(self.other_actors[0]))\n        root.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n\n        return root\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/other_leading_vehicle.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nOther Leading Vehicle scenario:\n\nThe scenario realizes a common driving behavior, in which the\nuser-controlled ego vehicle follows a leading car driving down\na given road. At some point the leading car has to decelerate.\nThe ego vehicle has to react accordingly by changing lane to avoid a\ncollision and follow the leading car in other lane. The scenario ends\neither via a timeout, or if the ego vehicle drives some distance.\n\"\"\"\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      WaypointFollower,\n                                                                      ActorDestroy)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import get_waypoint_in_distance\n\n\nclass OtherLeadingVehicle(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a simple \"Other Leading Vehicle\"\n    scenario involving a user controlled vehicle and two other actors.\n    Traffic Scenario 05\n\n    This is a single ego vehicle scenario\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._first_vehicle_location = 35\n        self._second_vehicle_location = self._first_vehicle_location + 1\n        self._ego_vehicle_drive_distance = self._first_vehicle_location * 4\n        self._first_vehicle_speed = 55 / 3.6\n        self._second_vehicle_speed = 45 / 3.6\n        self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location)\n        self._other_actor_max_brake = 1.0\n        self._first_actor_transform = None\n        self._second_actor_transform = None\n        # Timeout of scenario in seconds\n        self.timeout = timeout\n\n        super(OtherLeadingVehicle, self).__init__(\"VehicleDeceleratingInMultiLaneSetUp\",\n                                                  ego_vehicles,\n                                                  config,\n                                                  world,\n                                                  debug_mode,\n                                                  criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        first_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location)\n        second_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_vehicle_location)\n        second_vehicle_waypoint = second_vehicle_waypoint.get_left_lane()\n\n        first_vehicle_transform = carla.Transform(first_vehicle_waypoint.transform.location,\n                                                  first_vehicle_waypoint.transform.rotation)\n        second_vehicle_transform = carla.Transform(second_vehicle_waypoint.transform.location,\n                                                   second_vehicle_waypoint.transform.rotation)\n\n        first_vehicle = CarlaDataProvider.request_new_actor('vehicle.nissan.patrol', first_vehicle_transform)\n        second_vehicle = CarlaDataProvider.request_new_actor('vehicle.audi.tt', second_vehicle_transform)\n\n        self.other_actors.append(first_vehicle)\n        self.other_actors.append(second_vehicle)\n\n        self._first_actor_transform = first_vehicle_transform\n        self._second_actor_transform = second_vehicle_transform\n\n    def _create_behavior(self):\n        \"\"\"\n        The scenario defined after is a \"other leading vehicle\" scenario. After\n        invoking this scenario, the user controlled vehicle has to drive towards the\n        moving other actors, then make the leading actor to decelerate when user controlled\n        vehicle is at some close distance. Finally, the user-controlled vehicle has to change\n        lane to avoid collision and follow other leading actor in other lane to end the scenario.\n        If this does not happen within 90 seconds, a timeout stops the scenario or the ego vehicle\n        drives certain distance and stops the scenario.\n        \"\"\"\n        # start condition\n        driving_in_same_direction = py_trees.composites.Parallel(\"All actors driving in same direction\",\n                                                                 policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        leading_actor_sequence_behavior = py_trees.composites.Sequence(\"Decelerating actor sequence behavior\")\n\n        # both actors moving in same direction\n        keep_velocity = py_trees.composites.Parallel(\"Trigger condition for deceleration\",\n                                                     policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        keep_velocity.add_child(WaypointFollower(self.other_actors[0], self._first_vehicle_speed, avoid_collision=True))\n        keep_velocity.add_child(InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], 55))\n\n        # Decelerating actor sequence behavior\n        decelerate = self._first_vehicle_speed / 3.2\n        leading_actor_sequence_behavior.add_child(keep_velocity)\n        leading_actor_sequence_behavior.add_child(WaypointFollower(self.other_actors[0], decelerate,\n                                                                   avoid_collision=True))\n        # end condition\n        ego_drive_distance = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_drive_distance)\n\n        # Build behavior tree\n        sequence = py_trees.composites.Sequence(\"Scenario behavior\")\n        parallel_root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        parallel_root.add_child(ego_drive_distance)\n        parallel_root.add_child(driving_in_same_direction)\n        driving_in_same_direction.add_child(leading_actor_sequence_behavior)\n        driving_in_same_direction.add_child(WaypointFollower(self.other_actors[1], self._second_vehicle_speed,\n                                                             avoid_collision=True))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform))\n        sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform))\n        sequence.add_child(parallel_root)\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n        sequence.add_child(ActorDestroy(self.other_actors[1]))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = []\n\n        collision_criterion = CollisionTest(self.ego_vehicles[0])\n        criteria.append(collision_criterion)\n\n        return criteria\n\n    def __del__(self):\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/parking_cut_in.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nParking cut in scenario synchronizes a vehicle that is parked at a side lane\nto cut in in front of the ego vehicle, forcing it to break\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      BasicAgentBehavior)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import LeaveSpaceInFront, ChangeRoadBehavior\n\n\nclass ParkingCutIn(BasicScenario):\n\n    \"\"\"\n    Parking cut in scenario synchronizes a vehicle that is parked at a side lane\n    to cut in in front of the ego vehicle, forcing it to break\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n\n        self._cut_in_distance = 35\n        self._blocker_distance = 28\n\n        self._adversary_speed = 13.0  # Speed of the adversary [m/s]\n        self._reaction_time = 2.35  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 10.0  # Min distance to the collision location that triggers the adversary [m]\n        self._end_distance = 30\n        self._extra_space = 20\n\n        self._bp_attributes = {'base_type': 'car', 'generation': 2, 'special_type': ''}\n\n        self.timeout = timeout\n\n        if 'direction' in config.other_parameters:\n            self._direction = config.other_parameters['direction']['value']\n        else:\n            self._direction = \"right\"\n\n        super().__init__(\"ParkingCutIn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn the blocker vehicle\n        blocker_wps = self._reference_waypoint.next(self._blocker_distance)\n        if not blocker_wps:\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        self._blocker_wp = blocker_wps[0]\n\n        if self._direction == 'left':\n            parking_wp = self._blocker_wp.get_left_lane()\n        else:\n            parking_wp = self._blocker_wp.get_right_lane()\n\n        self.parking_slots.append(parking_wp.transform.location)\n\n        self._blocker_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', parking_wp.transform, 'scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2})\n        if not self._blocker_actor:\n            raise ValueError(\"Couldn't spawn the parked actor\")\n        self._blocker_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(self._blocker_actor)\n\n        side_location = self._get_displaced_location(self._blocker_actor, parking_wp)\n        self._blocker_actor.set_location(side_location)\n\n        collision_wps = self._reference_waypoint.next(self._cut_in_distance)\n        if not collision_wps:\n            raise ValueError(\"Couldn't find a proper position for the cut in vehicle\")\n        self._collision_wp = collision_wps[0]\n\n        # Get the parking direction\n        if self._direction == 'left':\n            parking_wp = self._collision_wp.get_left_lane()\n        else:\n            parking_wp = self._collision_wp.get_right_lane()\n\n        self.parking_slots.append(parking_wp.transform.location)\n\n        self._parked_actor = CarlaDataProvider.request_new_actor(\n            'vehicle.*', parking_wp.transform, 'scenario', attribute_filter=self._bp_attributes)\n        if not self._parked_actor:\n            raise ValueError(\"Couldn't spawn the parked actor\")\n        self.other_actors.append(self._parked_actor)\n\n        side_location = self._get_displaced_location(self._parked_actor, parking_wp)\n        self._parked_actor.set_location(side_location)\n\n    def _get_displaced_location(self, actor, wp):\n        \"\"\"\n        Calculates the location such that the actor is at the sidemost part of the lane\n        \"\"\"\n        # Move the actor to the edge of the lane near the sidewalk\n        displacement = (wp.lane_width - actor.bounding_box.extent.y) / 4\n        displacement_vector = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            displacement_vector *= -1\n\n        new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x,\n                                                              y=displacement*displacement_vector.y,\n                                                              z=displacement*displacement_vector.z)\n        new_location.z += 0.05  # Just in case, avoid collisions with the ground\n        return new_location\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, a parked vehicle will wait for the ego to\n        be close-by, merging into its lane, forcing it to break.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"ParkingCutIn\")\n        if self.route_mode:\n            sequence.add_child(LeaveSpaceInFront(self._cut_in_distance + 10))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        # Move the adversary\n        cut_in = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"Cut in behavior\")\n        cut_in.add_child(BasicAgentBehavior(self.other_actors[1], opt_dict={'ignore_traffic_lights': True}))\n        cut_in.add_child(DriveDistance(self.other_actors[1], self._end_distance))\n        sequence.add_child(cut_in)\n\n        # Remove everything\n        sequence.add_child(ActorDestroy(self.other_actors[0], name=\"DestroyAdversary\"))\n        sequence.add_child(ActorDestroy(self.other_actors[1], name=\"DestroyBlocker\"))\n\n        if self.route_mode:\n            sequence.add_child(ChangeRoadBehavior(extra_space=0))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/parking_exit.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario in which the ego is parked between two vehicles and has to maneuver to start the route.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      ActorTransformSetter,\n                                                                      WaitForever,\n                                                                      ChangeAutoPilot,\n                                                                      ScenarioTimeout)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import ChangeRoadBehavior\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\nclass ParkingExit(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which the ego would be teleported to the parking lane.\n    Once the scenario is triggered, the OutsideRouteLanesTest will be deactivated since the ego is out of the driving lane.\n    Then blocking vehicles will be generated in front of and behind the parking point.\n    The ego need to exit from the parking lane and then merge into the driving lane.\n    After the ego is {end_distance} meters away from the parking point, the OutsideRouteLanesTest will be activated and the scenario ends.\n\n    Note 1: For route mode, this shall be the first scenario of the route. The trigger point shall be the first point of the route waypoints.\n\n    Note 2: Make sure there are enough space for spawning blocking vehicles.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._tm = CarlaDataProvider.get_client().get_trafficmanager(\n            CarlaDataProvider.get_traffic_manager_port())\n        self.timeout = timeout\n\n        self._bp_attributes = {'base_type': 'car', 'generation': 2}\n        self._side_end_distance = 50\n\n        self._front_vehicle_distance = get_value_parameter(config, 'front_vehicle_distance', float, 20)\n        self._behind_vehicle_distance = get_value_parameter(config, 'behind_vehicle_distance', float, 10)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._flow_distance = get_value_parameter(config, 'flow_distance', float, 25)\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        self._end_distance = self._front_vehicle_distance + 15\n\n        # Get parking_waypoint based on trigger_point\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(self._trigger_location)\n        if self._direction == \"left\":\n            self._parking_waypoint = self._reference_waypoint.get_left_lane()\n        else:\n            self._parking_waypoint = self._reference_waypoint.get_right_lane()\n\n        if self._parking_waypoint is None:\n            raise Exception(\n                \"Couldn't find parking point on the {} side\".format(self._direction))\n\n        super().__init__(\"ParkingExit\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n\n        # Spawn the actor in front of the ego\n        front_points = self._parking_waypoint.next(\n            self._front_vehicle_distance)\n        if not front_points:\n            raise ValueError(\"Couldn't find viable position for the vehicle in front of the parking point\")\n\n        self.parking_slots.append(front_points[0].transform.location)\n\n        actor_front = CarlaDataProvider.request_new_actor(\n            'vehicle.*', front_points[0].transform, rolename='scenario no lights', attribute_filter=self._bp_attributes)\n        if actor_front is None:\n            raise ValueError(\"Couldn't spawn the vehicle in front of the parking point\")\n        actor_front.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(actor_front)\n\n        # And move it to the side\n        side_location = self._get_displaced_location(actor_front, front_points[0])\n        actor_front.set_location(side_location)\n\n        # Spawn the actor behind the ego\n        behind_points = self._parking_waypoint.previous(\n            self._behind_vehicle_distance)\n        if not behind_points:\n            raise ValueError(\"Couldn't find viable position for the vehicle behind the parking point\")\n\n        self.parking_slots.append(behind_points[0].transform.location)\n\n        actor_behind = CarlaDataProvider.request_new_actor(\n            'vehicle.*', behind_points[0].transform, rolename='scenario no lights', attribute_filter=self._bp_attributes)\n        if actor_behind is None:\n            actor_front.destroy()\n            raise ValueError(\"Couldn't spawn the vehicle behind the parking point\")\n        actor_behind.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(actor_behind)\n\n        # And move it to the side\n        side_location = self._get_displaced_location(actor_behind, behind_points[0])\n        actor_behind.set_location(side_location)\n\n        # Move the ego to its side position\n        self._ego_location = self._get_displaced_location(self.ego_vehicles[0], self._parking_waypoint)\n        self.parking_slots.append(self._ego_location)\n        self.ego_vehicles[0].set_location(self._ego_location)\n\n        # Spawn the actor at the side of the ego\n        actor_side = CarlaDataProvider.request_new_actor(\n            'vehicle.*', self._reference_waypoint.transform, attribute_filter=self._bp_attributes)\n        if actor_side is None:\n            raise ValueError(\"Couldn't spawn the vehicle at the side of the parking point\")\n        self.other_actors.append(actor_side)\n        self._tm.update_vehicle_lights(actor_side, True)\n\n        self._end_side_transform = self.ego_vehicles[0].get_transform()\n        self._end_side_transform.location.z -= 500\n\n    def _get_displaced_location(self, actor, wp):\n        \"\"\"\n        Calculates the transforming such that the actor is at the sidemost part of the lane\n        \"\"\"\n        # Move the actor to the edge of the lane near the sidewalk\n        displacement = (wp.lane_width - actor.bounding_box.extent.y) / 4\n        displacement_vector = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            displacement_vector *= -1\n\n        new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x,\n                                                              y=displacement*displacement_vector.y,\n                                                              z=displacement*displacement_vector.z)\n        new_location.z += 0.05  # Just in case, avoid collisions with the ground\n        return new_location\n\n    def _create_behavior(self):\n        \"\"\"\n        Deactivate OutsideRouteLanesTest, then move ego to the parking point,\n        generate blocking vehicles in front of and behind the ego.\n        After ego drives away, activate OutsideRouteLanesTest, end scenario.\n        \"\"\"\n\n        sequence = py_trees.composites.Sequence(name=\"ParkingExit\")\n        sequence.add_child(ChangeRoadBehavior(spawn_dist=self._flow_distance))\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        side_actor_behavior = py_trees.composites.Sequence()\n        side_actor_behavior.add_child(ChangeAutoPilot(self.other_actors[2], True))\n        side_actor_behavior.add_child(DriveDistance(self.other_actors[2], self._side_end_distance))\n        side_actor_behavior.add_child(ActorTransformSetter(self.other_actors[2], self._end_side_transform, False))\n        side_actor_behavior.add_child(WaitForever())\n        root.add_child(side_actor_behavior)\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        for actor in self.other_actors:\n            sequence.add_child(ActorDestroy(actor))\n        sequence.add_child(ChangeRoadBehavior(spawn_dist=15))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/pedestrian_crossing.py",
    "content": "#!/usr/bin/env python\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nPedestrians crossing through the middle of the lane.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      KeepVelocity,\n                                                                      WaitForever,\n                                                                      Idle,\n                                                                      ActorTransformSetter,\n                                                                      MovePedestrianWithEgo)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\n\ndef convert_dict_to_location(actor_dict):\n    \"\"\"\n    Convert a JSON string to a Carla.Location\n    \"\"\"\n    location = carla.Location(\n        x=float(actor_dict['x']),\n        y=float(actor_dict['y']),\n        z=float(actor_dict['z'])\n    )\n    return location\n\n\nclass PedestrianCrossing(BasicScenario):\n\n    \"\"\"\n    This class holds everything required for a group of natual pedestrians crossing the road.\n    The ego vehicle is passing through a road,\n    And encounters a group of pedestrians crossing the road.\n\n    This is a single ego vehicle scenario.\n\n    Notice that the initial pedestrian will walk from the start of the junction ahead to end_walker_flow_1.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True, timeout=60):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._wmap = CarlaDataProvider.get_map()\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._wmap.get_waypoint(self._trigger_location)\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self._adversary_speed = 1.3  # Speed of the adversary [m/s]\n        self._reaction_time = 3.5  # Time the agent has to react to avoid the collision [s]\n        self._min_trigger_dist = 12.0  # Min distance to the collision location that triggers the adversary [m]\n        self._ego_end_distance = 40\n        self.timeout = timeout\n\n        self._walker_data = [\n            {'x': 0.4, 'y': 1.5, 'z': 1.2, 'yaw': 270},\n            {'x': 1, 'y': 2.5, 'z': 1.2, 'yaw': 270},\n            {'x': 1.6, 'y': 0.5, 'z': 1.2, 'yaw': 270}\n        ]\n\n        for walker_data in self._walker_data:\n            walker_data['idle_time'] = self._rng.uniform(0, 1.5)\n            walker_data['speed'] = self._rng.uniform(1.3, 2.0)\n\n        super().__init__(\"PedestrianCrossing\",\n                          ego_vehicles,\n                          config,\n                          world,\n                          debug_mode,\n                          criteria_enable=criteria_enable)\n\n    def _get_walker_transform(self, wp, displacement):\n        disp_x = displacement['x']\n        disp_y = displacement['y']\n        disp_z = displacement['z']\n        disp_yaw = displacement['yaw']\n\n        # Displace it to the crosswalk. Move forwards towards the crosswalk\n        start_vec = wp.transform.get_forward_vector()\n        start_right_vec = wp.transform.get_right_vector()\n\n        spawn_loc = wp.transform.location + carla.Location(\n            disp_x * start_vec.x + disp_y * start_right_vec.x,\n            disp_x * start_vec.y + disp_y * start_right_vec.y,\n            disp_x * start_vec.z + disp_y * start_right_vec.z + disp_z\n        )\n\n        spawn_rotation = wp.transform.rotation\n        spawn_rotation.yaw += disp_yaw\n        return carla.Transform(spawn_loc, spawn_rotation)\n\n    def _initialize_actors(self, config):\n\n        # Get the start point of the initial pedestrian\n        collision_wp = self._reference_waypoint\n        while True:\n            next_wps = collision_wp.next(1)\n            if not next_wps:\n                raise ValueError(\"Couldn't find a waypoint to spawn the pedestrians\")\n            if next_wps[0].is_junction:\n                break\n            collision_wp = next_wps[0]\n\n        self._collision_wp = collision_wp\n\n        # Get the crosswalk start point\n        start_wp = collision_wp\n        while start_wp.lane_type != carla.LaneType.Sidewalk:\n            wp = start_wp.get_right_lane()\n            if wp is None:\n                raise ValueError(\"Couldn't find a waypoint to start the flow\")\n            start_wp = wp\n\n        # Spawn the walkers\n        for i, walker_data in enumerate(self._walker_data):\n            spawn_transform = self._get_walker_transform(start_wp, walker_data)\n            walker = CarlaDataProvider.request_new_actor('walker.*', spawn_transform)\n            if walker is None:\n                for walker in self.other_actors:\n                    walker.destroy()\n                raise ValueError(\"Failed to spawn an adversary\")\n\n            walker.set_location(spawn_transform.location + carla.Location(z=-200))\n            walker = self._replace_walker(walker)\n\n            self.other_actors.append(walker)\n\n            collision_dist = spawn_transform.location.distance(self._collision_wp.transform.location)\n\n            # Distance and duration to cross the whole road + a bit more (supposing symetry in both directions)\n            move_dist = 2.3 * collision_dist\n            walker_data['transform'] = spawn_transform\n            walker_data['distance'] = move_dist\n            walker_data['duration'] = move_dist / walker_data['speed']\n\n    def _create_behavior(self):\n        \"\"\"\n        After invoking this scenario, cyclist will wait for the user\n        controlled vehicle to enter trigger distance region,\n        the cyclist starts crossing the road once the condition meets,\n        then after 60 seconds, a timeout stops the scenario\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"PedestrianCrossing\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=False,\n                clear_ego_entry=True,\n                remove_entries=[],\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=0\n            ))\n\n        for walker_actor, walker_data in zip(self.other_actors, self._walker_data):\n            sequence.add_child(ActorTransformSetter(walker_actor, walker_data['transform'], True))\n\n        collision_location = self._collision_wp.transform.location\n\n        # Wait until ego is close to the adversary\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerAdversaryStart\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        sequence.add_child(trigger_adversary)\n\n        # Move the walkers\n        main_behavior = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=\"WalkerMovement\")\n\n        for walker_actor, walker_data in zip(self.other_actors, self._walker_data):\n            walker_sequence = py_trees.composites.Sequence(name=\"WalkerCrossing\")\n            walker_sequence.add_child(Idle(walker_data['idle_time']))\n            walker_sequence.add_child(KeepVelocity(\n                walker_actor, walker_data['speed'], False, walker_data['duration'], walker_data['distance']))\n            walker_sequence.add_child(ActorDestroy(walker_actor, name=\"DestroyAdversary\"))\n            walker_sequence.add_child(WaitForever())\n\n            main_behavior.add_child(walker_sequence)\n\n        main_behavior.add_child(DriveDistance(self.ego_vehicles[0], self._ego_end_distance, name=\"EndCondition\"))\n        sequence.add_child(main_behavior)\n\n        # Remove everything\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        if self.route_mode:\n            return []\n        return [CollisionTest(self.ego_vehicles[0])]\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n    # TODO: Pedestrian have an issue with large maps were setting them to dormant breaks them,\n    # so all functions below are meant to patch it until the fix is done\n    def _replace_walker(self, walker):\n        \"\"\"As the adversary is probably, replace it with another one\"\"\"\n        type_id = walker.type_id\n        walker.destroy()\n        spawn_transform = self.ego_vehicles[0].get_transform()\n        spawn_transform.location.z -= 50\n        walker = CarlaDataProvider.request_new_actor(type_id, spawn_transform)\n        if not walker:\n            raise ValueError(\"Couldn't spawn the walker substitute\")\n        walker.set_simulate_physics(False)\n        walker.set_location(spawn_transform.location + carla.Location(z=-50))\n        return walker\n\n    def _setup_scenario_trigger(self, config):\n        \"\"\"Normal scenario trigger but in parallel, a behavior that ensures the pedestrian stays active\"\"\"\n        trigger_tree = super()._setup_scenario_trigger(config)\n\n        if not self.route_mode:\n            return trigger_tree\n\n        parallel = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"ScenarioTrigger\")\n\n        for i, walker in enumerate(reversed(self.other_actors)):\n            parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], walker, 100))\n\n        parallel.add_child(trigger_tree)\n        return parallel\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/route_obstacles.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      SwitchWrongDirectionTest,\n                                                                      BasicAgentBehavior,\n                                                                      ScenarioTimeout,\n                                                                      Idle, WaitForever,\n                                                                      HandBrakeVehicle,\n                                                                      OppositeActorFlow)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (DriveDistance,\n                                                                               InTriggerDistanceToLocation,\n                                                                               InTriggerDistanceToVehicle,\n                                                                               WaitUntilInFront,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import LeaveSpaceInFront, SetMaxSpeed, ChangeOppositeBehavior, ChangeRoadBehavior\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass Accident(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which there is an accident\n    in front of the ego, forcing it to lane change. A police vehicle is located before\n    two other cars that have been in an accident.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n        \n        self._first_distance = 10\n        self._second_distance = 6\n\n        self._trigger_distance = 50\n        self._end_distance = 50\n        self._wait_duration = 5\n        self._offset = 0.6\n\n        self._lights = carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2 | carla.VehicleLightState.Position\n\n        self._distance = get_value_parameter(config, 'distance', float, 120)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        super().__init__(\n            \"Accident\", ego_vehicles, config, world, randomize, debug_mode, criteria_enable=criteria_enable)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_side_prop(self, wp):\n        # Spawn the accident indication signal\n        prop_wp = wp\n        while True:\n            if self._direction == \"right\":\n                wp = prop_wp.get_right_lane()\n            else:\n                wp = prop_wp.get_left_lane()\n            if wp is None or wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n                break\n            prop_wp = wp\n\n        displacement = 0.3 * prop_wp.lane_width\n        r_vec = prop_wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.2)\n        spawn_transform.rotation.yaw += 90\n        signal_prop = CarlaDataProvider.request_new_actor('static.prop.warningaccident', spawn_transform)\n        if not signal_prop:\n            raise ValueError(\"Couldn't spawn the indication prop asset\")\n        signal_prop.set_simulate_physics(False)\n        self.other_actors.append(signal_prop)\n\n    def _spawn_obstacle(self, wp, blueprint, accident_actor=False):\n        \"\"\"\n        Spawns the obstacle actor by displacing its position to the right\n        \"\"\"\n        displacement = self._offset * wp.lane_width / 2\n        r_vec = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1)\n        if accident_actor:\n            actor = CarlaDataProvider.request_new_actor(\n                blueprint, spawn_transform, rolename='scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2})\n        else:\n            actor = CarlaDataProvider.request_new_actor(\n                blueprint, spawn_transform, rolename='scenario')\n        if not actor:\n            raise ValueError(\"Couldn't spawn an obstacle actor\")\n\n        return actor\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        starting_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Spawn the accident indication signal\n        self._spawn_side_prop(starting_wp)\n\n        # Spawn the police vehicle\n        self._accident_wp = self._move_waypoint_forward(starting_wp, self._distance)\n        police_car = self._spawn_obstacle(self._accident_wp, 'vehicle.dodge.charger_police_2020')\n\n        # Set its initial conditions\n        lights = police_car.get_light_state()\n        lights |= self._lights\n        police_car.set_light_state(carla.VehicleLightState(lights))\n        police_car.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(police_car)\n\n        # Create the first vehicle that has been in the accident\n        self._first_vehicle_wp = self._move_waypoint_forward(self._accident_wp, self._first_distance)\n        first_actor = self._spawn_obstacle(self._first_vehicle_wp, 'vehicle.*', True)\n\n        # Set its initial conditions\n        first_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(first_actor)\n\n        # Create the second vehicle that has been in the accident\n        second_vehicle_wp = self._move_waypoint_forward(self._first_vehicle_wp, self._second_distance)\n        second_actor = self._spawn_obstacle(second_vehicle_wp, 'vehicle.*', True)\n\n        self._accident_wp = second_vehicle_wp\n        self._end_wp = self._move_waypoint_forward(second_vehicle_wp, self._end_distance)\n\n        # Set its initial conditions\n        second_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(second_actor)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the reach a specific point but an accident is in the middle of the road,\n        blocking its route and forcing it to lane change.\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"Accident\")\n        if self.route_mode:\n            total_dist = self._distance + self._first_distance + self._second_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._first_vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass AccidentTwoWays(Accident):\n    \"\"\"\n    Variation of the Accident scenario but the ego now has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180):\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the whole predetermined distance. Adapt the opposite flow to\n        let the ego invade the opposite lane.\n        \"\"\"\n        reference_wp = self._accident_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"AccidentTwoWays\")\n        if self.route_mode:\n            total_dist = self._distance + self._first_distance + self._second_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._first_vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n        behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\nclass ParkedObstacle(BasicScenario):\n    \"\"\"\n    Scenarios in which a parked vehicle is incorrectly parked,\n    forcing the ego to lane change out of the route's lane\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._trigger_distance = 50\n        self._end_distance = 50\n        self._wait_duration = 5\n        self._offset = 0.7\n\n        self._lights = carla.VehicleLightState.RightBlinker | carla.VehicleLightState.LeftBlinker | carla.VehicleLightState.Position\n\n        self._distance = get_value_parameter(config, 'distance', float, 120)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        super().__init__(\n            \"ParkedObstacle\", ego_vehicles, config, world, randomize, debug_mode, criteria_enable=criteria_enable)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_side_prop(self, wp):\n        # Spawn the accident indication signal\n        prop_wp = wp\n        while True:\n            if self._direction == \"right\":\n                wp = prop_wp.get_right_lane()\n            else:\n                wp = prop_wp.get_left_lane()\n            if wp is None or wp.lane_type not in (carla.LaneType.Driving, carla.LaneType.Parking):\n                break\n            prop_wp = wp\n\n        displacement = 0.3 * prop_wp.lane_width\n        r_vec = prop_wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=0.2)\n        spawn_transform.rotation.yaw += 90\n        signal_prop = CarlaDataProvider.request_new_actor('static.prop.warningaccident', spawn_transform)\n        if not signal_prop:\n            raise ValueError(\"Couldn't spawn the indication prop asset\")\n        signal_prop.set_simulate_physics(False)\n        self.other_actors.append(signal_prop)\n\n    def _spawn_obstacle(self, wp, blueprint):\n        \"\"\"\n        Spawns the obstacle actor by displacing its position to the right\n        \"\"\"\n        displacement = self._offset * wp.lane_width / 2\n        r_vec = wp.transform.get_right_vector()\n        if self._direction == 'left':\n            r_vec *= -1\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1)\n        actor = CarlaDataProvider.request_new_actor(\n            blueprint, spawn_transform, rolename='scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2})\n        if not actor:\n            raise ValueError(\"Couldn't spawn an obstacle actor\")\n\n        return actor\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        self._starting_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Create the side prop\n        self._spawn_side_prop(self._starting_wp)\n\n        # Create the first vehicle that has been in the accident\n        self._vehicle_wp = self._move_waypoint_forward(self._starting_wp, self._distance)\n        parked_actor = self._spawn_obstacle(self._vehicle_wp, 'vehicle.*')\n\n        lights = parked_actor.get_light_state()\n        lights |= self._lights\n        parked_actor.set_light_state(carla.VehicleLightState(lights))\n        parked_actor.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(parked_actor)\n\n        self._end_wp = self._move_waypoint_forward(self._vehicle_wp, self._end_distance)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the whole predetermined distance.\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"ParkedObstacle\")\n        if self.route_mode:\n            total_dist = self._distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass ParkedObstacleTwoWays(ParkedObstacle):\n    \"\"\"\n    Variation of the ParkedObstacle scenario but the ego now has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180):\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        The vehicle has to drive the whole predetermined distance. Adapt the opposite flow to\n        let the ego invade the opposite lane.\n        \"\"\"\n        reference_wp = self._vehicle_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"ParkedObstacleTwoWays\")\n        if self.route_mode:\n            total_dist = self._distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence()\n        behavior.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], self._vehicle_wp.transform.location, self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n        behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n\nclass HazardAtSideLane(BasicScenario):\n    \"\"\"\n    Added the dangerous scene of ego vehicles driving on roads without sidewalks,\n    with three bicycles encroaching on some roads in front.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._obstacle_distance = 9\n        self._trigger_distance = 50\n        self._end_distance = 50\n        self._extra_space = 30\n\n        self._offset = 0.55\n        self._wait_duration = 5\n\n        self._target_locs = []\n\n        self._bicycle_bps = [\"vehicle.bh.crossbike\", \"vehicle.diamondback.century\", \"vehicle.gazelle.omafiets\"]\n\n        self._distance = get_value_parameter(config, 'distance', float, 100)\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._bicycle_speed = get_value_parameter(config, 'bicycle_speed', float, 10)\n        self._bicycle_drive_distance = get_value_parameter(config, 'bicycle_drive_distance', float, 50)\n        self._scenario_timeout = 240\n\n        super().__init__(\"HazardAtSideLane\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         randomize,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _spawn_obstacle(self, wp, blueprint):\n        \"\"\"\n        Spawns the obstacle actor by displacing its position to the right\n        \"\"\"\n        displacement = self._offset * wp.lane_width / 2\n        r_vec = wp.transform.get_right_vector()\n\n        spawn_transform = wp.transform\n        spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1)\n        actor = CarlaDataProvider.request_new_actor(blueprint, spawn_transform)\n        if not actor:\n            raise ValueError(\"Couldn't spawn an obstacle actor\")\n\n        return actor\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        rng = CarlaDataProvider.get_random_seed()\n        self._starting_wp = self._map.get_waypoint(config.trigger_points[0].location)\n\n        # Spawn the first bicycle\n        first_wp = self._move_waypoint_forward(self._starting_wp, self._distance)\n        bicycle_1 = self._spawn_obstacle(first_wp, rng.choice(self._bicycle_bps))\n\n        wps = first_wp.next(self._bicycle_drive_distance)\n        if not wps:\n            raise ValueError(\"Couldn't find an end location for the bicycles\")\n        self._target_locs.append(wps[0].transform.location)\n\n        # Set its initial conditions\n        bicycle_1.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(bicycle_1)\n\n        # Spawn the second bicycle\n        second_wp = self._move_waypoint_forward(first_wp, self._obstacle_distance)\n        bicycle_2 = self._spawn_obstacle(second_wp, rng.choice(self._bicycle_bps))\n\n        wps = second_wp.next(self._bicycle_drive_distance)\n        if not wps:\n            raise ValueError(\"Couldn't find an end location for the bicycles\")\n        self._target_locs.append(wps[0].transform.location)\n\n        # Set its initial conditions\n        bicycle_2.apply_control(carla.VehicleControl(hand_brake=True))\n        self.other_actors.append(bicycle_2)\n\n    def _create_behavior(self):\n        \"\"\"\n        Activate the bicycles and wait for the ego to be close-by before changing the side traffic.\n        End condition is based on the ego behind in front of the bicycles, or timeout based.\n        \"\"\"\n        root = py_trees.composites.Sequence(name=\"HazardAtSideLane\")\n        if self.route_mode:\n            total_dist = self._distance + self._obstacle_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n            root.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        # End condition\n        end_condition = py_trees.composites.Sequence(name=\"End Condition\")\n        end_condition.add_child(WaitUntilInFront(self.ego_vehicles[0], self.other_actors[-1], check_distance=False))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        main_behavior.add_child(end_condition)\n\n        # Bicycle movement. Move them for a set distance, then stop\n        offset = self._offset * self._starting_wp.lane_width / 2\n        opt_dict = {'offset': offset}\n        for actor, target_loc in zip(self.other_actors, self._target_locs):\n            bicycle = py_trees.composites.Sequence(name=\"Bicycle behavior\")\n            bicycle.add_child(BasicAgentBehavior(actor, target_loc, target_speed=self._bicycle_speed, opt_dict=opt_dict))\n            bicycle.add_child(HandBrakeVehicle(actor, 1))  # In case of collisions\n            bicycle.add_child(WaitForever())  # Don't make the bicycle stop the parallel behavior\n            main_behavior.add_child(bicycle)\n\n        behavior = py_trees.composites.Sequence(name=\"Side lane behavior\")\n        behavior.add_child(InTriggerDistanceToVehicle(\n            self.ego_vehicles[0], self.other_actors[0], self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SetMaxSpeed(self._max_speed))\n        behavior.add_child(WaitForever())\n\n        main_behavior.add_child(behavior)\n\n        root.add_child(main_behavior)\n        if self.route_mode:\n            root.add_child(SetMaxSpeed(0))\n            root.add_child(ChangeRoadBehavior(extra_space=0))\n\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass HazardAtSideLaneTwoWays(HazardAtSideLane):\n    \"\"\"\n    Variation of the HazardAtSideLane scenario but the ego now has to invade the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180):\n\n        self._opposite_frequency = get_value_parameter(config, 'frequency', float, 100)\n\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Activate the bicycles and wait for the ego to be close-by before changing the opposite traffic.\n        End condition is based on the ego behind in front of the bicycles, or timeout based.\n        \"\"\"\n\n        root = py_trees.composites.Sequence(name=\"HazardAtSideLaneTwoWays\")\n        if self.route_mode:\n            total_dist = self._distance + self._obstacle_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n            root.add_child(ChangeRoadBehavior(extra_space=self._extra_space))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        # End condition\n        end_condition = py_trees.composites.Sequence(name=\"End Condition\")\n        end_condition.add_child(WaitUntilInFront(self.ego_vehicles[0], self.other_actors[-1], check_distance=False))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        main_behavior.add_child(end_condition)\n\n        # Bicycle movement. Move them for a set distance, then stop\n        offset = self._offset * self._starting_wp.lane_width / 2\n        opt_dict = {'offset': offset}\n        for actor, target_loc in zip(self.other_actors, self._target_locs):\n            bicycle = py_trees.composites.Sequence(name=\"Bicycle behavior\")\n            bicycle.add_child(BasicAgentBehavior(actor, target_loc, target_speed=self._bicycle_speed, opt_dict=opt_dict))\n            bicycle.add_child(HandBrakeVehicle(actor, 1))  # In case of collisions\n            bicycle.add_child(WaitForever())  # Don't make the bicycle stop the parallel behavior\n            main_behavior.add_child(bicycle)\n\n        behavior = py_trees.composites.Sequence(name=\"Side lane behavior\")\n        behavior.add_child(InTriggerDistanceToVehicle(\n            self.ego_vehicles[0], self.other_actors[0], self._trigger_distance))\n        behavior.add_child(Idle(self._wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(spawn_dist=self._opposite_frequency))\n        behavior.add_child(WaitForever())\n\n        main_behavior.add_child(behavior)\n\n        root.add_child(main_behavior)\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(False))\n            root.add_child(ChangeOppositeBehavior(spawn_dist=40))\n            root.add_child(ChangeRoadBehavior(extra_space=0))\n\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n\n        return root\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/route_scenario.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides Challenge routes as standalone scenarios\n\"\"\"\n\nfrom __future__ import print_function\n\nimport glob\nimport os\nimport sys\nimport importlib\nimport inspect\nimport traceback\nimport py_trees\n\nfrom numpy import random\nimport carla\n\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ScenarioTriggerer, Idle\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitForBlackboardVariable\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest,\n                                                                     InRouteTest,\n                                                                     RouteCompletionTest,\n                                                                     OutsideRouteLanesTest,\n                                                                     RunningRedLightTest,\n                                                                     RunningStopTest,\n                                                                     ActorBlockedTest,\n                                                                     MinimumSpeedRouteTest)\n\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.scenarios.background_activity import BackgroundBehavior\nfrom srunner.scenariomanager.weather_sim import RouteWeatherBehavior\nfrom srunner.scenariomanager.lights_sim import RouteLightsBehavior\nfrom srunner.scenariomanager.timer import RouteTimeoutBehavior\n\nfrom srunner.tools.route_parser import RouteParser, DIST_THRESHOLD\nfrom srunner.tools.route_manipulation import interpolate_trajectory\n\n\nSECONDS_GIVEN_PER_METERS = 0.4\n\n\nclass RouteScenario(BasicScenario):\n\n    \"\"\"\n    Implementation of a RouteScenario, i.e. a scenario that consists of driving along a pre-defined route,\n    along which several smaller scenarios are triggered\n    \"\"\"\n\n    def __init__(self, world, config, debug_mode=False, criteria_enable=True, timeout=300):\n        \"\"\"\n        Setup all relevant parameters and create scenarios along route\n        \"\"\"\n\n        self.config = config\n        self.route = self._get_route(config)\n        sampled_scenario_definitions = self._filter_scenarios(config.scenario_configs)\n\n        ego_vehicle = self._spawn_ego_vehicle()\n        self.timeout = self._estimate_route_timeout()\n\n        if debug_mode:\n            self._draw_waypoints(world, self.route, vertical_shift=0.1, size=0.1, persistency=self.timeout, downsample=5)\n\n        self._build_scenarios(\n            world, ego_vehicle, sampled_scenario_definitions, timeout=self.timeout, debug=debug_mode > 0\n        )\n\n        super(RouteScenario, self).__init__(\n            config.name, [ego_vehicle], config, world, debug_mode > 1, False, criteria_enable\n        )\n\n    def _get_route(self, config):\n        \"\"\"\n        Gets the route from the configuration, interpolating it to the desired density,\n        saving it to the CarlaDataProvider and sending it to the agent\n\n        Parameters:\n        - world: CARLA world\n        - config: Scenario configuration (RouteConfiguration)\n        - debug_mode: boolean to decide whether or not the route poitns are printed\n        \"\"\"\n        # prepare route's trajectory (interpolate and add the GPS route)\n        gps_route, route = interpolate_trajectory(config.keypoints)\n        if config.agent is not None:\n            config.agent.set_global_plan(gps_route, route)\n\n        return route\n\n    def _filter_scenarios(self, scenario_configs):\n        \"\"\"\n        Given a list of scenarios, filters out does that don't make sense to be triggered,\n        as they are either too far from the route or don't fit with the route shape\n\n        Parameters:\n        - scenario_configs: list of ScenarioConfiguration\n        \"\"\"\n        new_scenarios_config = []\n        for scenario_config in scenario_configs:\n            trigger_point = scenario_config.trigger_points[0]\n            if not RouteParser.is_scenario_at_route(trigger_point, self.route):\n                print(\"WARNING: Ignoring scenario '{}' as it is too far from the route\".format(scenario_config.name))\n                continue\n\n            new_scenarios_config.append(scenario_config)\n\n        return new_scenarios_config\n\n    def _spawn_ego_vehicle(self):\n        \"\"\"Spawn the ego vehicle at the first waypoint of the route\"\"\"\n        elevate_transform = self.route[0][0]\n        elevate_transform.location.z += 0.5\n\n        ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz_2017',\n                                                          elevate_transform,\n                                                          rolename='hero')\n\n        return ego_vehicle\n\n    def _estimate_route_timeout(self):\n        \"\"\"\n        Estimate the duration of the route, as a proportinal value of its length\n        \"\"\"\n        route_length = 0.0  # in meters\n\n        prev_point = self.route[0][0]\n        for current_point, _ in self.route[1:]:\n            dist = current_point.location.distance(prev_point.location)\n            route_length += dist\n            prev_point = current_point\n\n        return int(SECONDS_GIVEN_PER_METERS * route_length)\n\n    def _draw_waypoints(self, world, waypoints, vertical_shift, size, persistency=-1, downsample=1):\n        \"\"\"\n        Draw a list of waypoints at a certain height given in vertical_shift.\n        \"\"\"\n        for i, w in enumerate(waypoints):\n            if i % downsample != 0:\n                continue\n\n            wp = w[0].location + carla.Location(z=vertical_shift)\n\n            if w[1] == RoadOption.LEFT:  # Yellow\n                color = carla.Color(128, 128, 0)\n            elif w[1] == RoadOption.RIGHT:  # Cyan\n                color = carla.Color(0, 128, 128)\n            elif w[1] == RoadOption.CHANGELANELEFT:  # Orange\n                color = carla.Color(128, 32, 0)\n            elif w[1] == RoadOption.CHANGELANERIGHT:  # Dark Cyan\n                color = carla.Color(0, 32, 128)\n            elif w[1] == RoadOption.STRAIGHT:  # Gray\n                color = carla.Color(64, 64, 64)\n            else:  # LANEFOLLOW\n                color = carla.Color(0, 128, 0)  # Green\n\n            world.debug.draw_point(wp, size=0.1, color=color, life_time=persistency)\n\n        world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=2*size,\n                               color=carla.Color(0, 0, 128), life_time=persistency)\n        world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=2*size,\n                               color=carla.Color(128, 128, 128), life_time=persistency)\n\n    def _scenario_sampling(self, potential_scenarios, random_seed=0):\n        \"\"\"Sample the scenarios that are going to happen for this route.\"\"\"\n        # Fix the random seed for reproducibility, and randomly sample a scenario per trigger position.\n        rng = random.RandomState(random_seed)\n\n        sampled_scenarios = []\n        for trigger in list(potential_scenarios):\n            scenario_list = potential_scenarios[trigger]\n            sampled_scenarios.append(rng.choice(scenario_list))\n\n        return sampled_scenarios\n\n    def get_all_scenario_classes(self):\n\n        # Path of all scenario at \"srunner/scenarios\" folder\n        scenarios_list = glob.glob(\"{}/srunner/scenarios/*.py\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n\n        all_scenario_classes = {}\n\n        for scenario_file in scenarios_list:\n\n            # Get their module\n            module_name = os.path.basename(scenario_file).split('.')[0]\n            sys.path.insert(0, os.path.dirname(scenario_file))\n            scenario_module = importlib.import_module(module_name)\n\n            # And their members of type class\n            for member in inspect.getmembers(scenario_module, inspect.isclass):\n                # TODO: Filter out any class that isn't a child of BasicScenario\n                all_scenario_classes[member[0]] = member[1]\n\n        return all_scenario_classes\n\n    def _build_scenarios(self, world, ego_vehicle, scenario_definitions, scenarios_per_tick=5, timeout=300, debug=False):\n        \"\"\"\n        Initializes the class of all the scenarios that will be present in the route.\n        If a class fails to be initialized, a warning is printed but the route execution isn't stopped\n        \"\"\"\n        all_scenario_classes = self.get_all_scenario_classes()\n        self.list_scenarios = []\n        ego_data = ActorConfigurationData(ego_vehicle.type_id, ego_vehicle.get_transform(), 'hero')\n\n        if debug:\n            tmap = CarlaDataProvider.get_map()\n            for scenario_config in scenario_definitions:\n                scenario_loc = scenario_config.trigger_points[0].location\n                debug_loc = tmap.get_waypoint(scenario_loc).transform.location + carla.Location(z=0.2)\n                world.debug.draw_point(debug_loc, size=0.2, color=carla.Color(128, 0, 0), life_time=timeout)\n                world.debug.draw_string(debug_loc, str(scenario_config.name), draw_shadow=False,\n                                        color=carla.Color(0, 0, 128), life_time=timeout, persistent_lines=True)\n\n        for scenario_number, scenario_config in enumerate(scenario_definitions):\n            scenario_config.ego_vehicles = [ego_data]\n            scenario_config.route_var_name = \"ScenarioRouteNumber{}\".format(scenario_number)\n            scenario_config.route = self.route\n\n            try:\n                scenario_class = all_scenario_classes[scenario_config.type]\n                scenario_instance = scenario_class(world, [ego_vehicle], scenario_config, timeout=timeout)\n\n                # Do a tick every once in a while to avoid spawning everything at the same time\n                if scenario_number % scenarios_per_tick == 0:\n                    world.tick()\n\n            except Exception as e:\n                if not debug:\n                    print(\"Skipping scenario '{}' due to setup error: {}\".format(scenario_config.type, e))\n                else:\n                    traceback.print_exc()\n                continue\n\n            self.list_scenarios.append(scenario_instance)\n\n\n    # pylint: enable=no-self-use\n    def _initialize_actors(self, config):\n        \"\"\"\n        Set other_actors to the superset of all scenario actors\n        \"\"\"\n        # Add all the actors of the specific scenarios to self.other_actors\n        for scenario in self.list_scenarios:\n            self.other_actors.extend(scenario.other_actors)\n\n    def _create_behavior(self):\n        \"\"\"\n        Creates a parallel behavior that runs all of the scenarios part of the route.\n        These subbehaviors have had a trigger condition added so that they wait until\n        the agent is close to their trigger point before activating.\n\n        It also adds the BackgroundActivity scenario, which will be active throughout the whole route.\n        This behavior never ends and the end condition is given by the RouteCompletionTest criterion.\n        \"\"\"\n        scenario_trigger_distance = DIST_THRESHOLD  # Max trigger distance between route and scenario\n\n        behavior = py_trees.composites.Parallel(name=\"Route Behavior\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL)\n\n        scenario_behaviors = []\n        blackboard_list = []\n\n        for scenario in self.list_scenarios:\n            if scenario.behavior_tree is not None:\n                scenario_behaviors.append(scenario.behavior_tree)\n                blackboard_list.append([scenario.config.route_var_name,\n                                        scenario.config.trigger_points[0].location])\n\n        # Add the behavior that manages the scenario trigger conditions\n        scenario_triggerer = ScenarioTriggerer(\n            self.ego_vehicles[0], self.route, blackboard_list, scenario_trigger_distance)\n        behavior.add_child(scenario_triggerer)  # Tick the ScenarioTriggerer before the scenarios\n\n        # Add the Background Activity\n        behavior.add_child(BackgroundBehavior(self.ego_vehicles[0], self.route, name=\"BackgroundActivity\"))\n\n        behavior.add_children(scenario_behaviors)\n        return behavior\n\n    def _create_test_criteria(self):\n        \"\"\"\n        Create the criteria tree. It starts with some route criteria (which are always active),\n        and adds the scenario specific ones, which will only be active during their scenario\n        \"\"\"\n        criteria = py_trees.composites.Parallel(name=\"Criteria\",\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        # End condition\n        criteria.add_child(RouteCompletionTest(self.ego_vehicles[0], route=self.route))\n\n        # 'Normal' criteria\n        criteria.add_child(OutsideRouteLanesTest(self.ego_vehicles[0], route=self.route))\n        criteria.add_child(CollisionTest(self.ego_vehicles[0], name=\"CollisionTest\"))\n        criteria.add_child(RunningRedLightTest(self.ego_vehicles[0]))\n        criteria.add_child(RunningStopTest(self.ego_vehicles[0]))\n        criteria.add_child(MinimumSpeedRouteTest(self.ego_vehicles[0], route=self.route, checkpoints=4, name=\"MinSpeedTest\"))\n\n        # These stop the route early to save computational time\n        criteria.add_child(InRouteTest(\n            self.ego_vehicles[0], route=self.route, offroad_max=30, terminate_on_failure=True))\n        criteria.add_child(ActorBlockedTest(\n            self.ego_vehicles[0], min_speed=0.1, max_time=180.0, terminate_on_failure=True, name=\"AgentBlockedTest\")\n        )\n\n        for scenario in self.list_scenarios:\n            scenario_criteria = scenario.get_criteria()\n            if len(scenario_criteria) == 0:\n                continue  # No need to create anything\n\n            criteria.add_child(\n                self._create_criterion_tree(scenario, scenario_criteria)\n            )\n\n        return criteria\n\n    def _create_weather_behavior(self):\n        \"\"\"\n        Create the weather behavior\n        \"\"\"\n        if len(self.config.weather) == 1:\n            return  # Just set the weather at the beginning and done\n        return RouteWeatherBehavior(self.ego_vehicles[0], self.route, self.config.weather)\n\n    def _create_lights_behavior(self):\n        \"\"\"\n        Create the street lights behavior\n        \"\"\"\n        return RouteLightsBehavior(self.ego_vehicles[0], 100)\n\n    def _create_timeout_behavior(self):\n        \"\"\"\n        Create the timeout behavior\n        \"\"\"\n        return RouteTimeoutBehavior(self.ego_vehicles[0], self.route)\n\n    def _initialize_environment(self, world):\n        \"\"\"\n        Set the weather\n        \"\"\"\n        # Set the appropriate weather conditions\n        world.set_weather(self.config.weather[0][1])\n\n    def _create_criterion_tree(self, scenario, criteria):\n        \"\"\"\n        We can make use of the blackboard variables used by the behaviors themselves,\n        as we already have an atomic that handles their (de)activation.\n        The criteria will wait until that variable is active (the scenario has started),\n        and will automatically stop when it deactivates (as the scenario has finished)\n        \"\"\"\n        scenario_name = scenario.name\n        var_name = scenario.config.route_var_name\n        check_name = \"WaitForBlackboardVariable: {}\".format(var_name)\n\n        criteria_tree = py_trees.composites.Sequence(name=scenario_name)\n        criteria_tree.add_child(WaitForBlackboardVariable(var_name, True, False, name=check_name))\n\n        scenario_criteria = py_trees.composites.Parallel(name=scenario_name,\n                                                policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        for criterion in criteria:\n            scenario_criteria.add_child(criterion)\n        scenario_criteria.add_child(WaitForBlackboardVariable(var_name, False, None, name=check_name))\n\n        criteria_tree.add_child(scenario_criteria)\n        criteria_tree.add_child(Idle())  # Avoid the indivual criteria stopping the simulation\n        return criteria_tree\n\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/sequentially_lane_change.py",
    "content": "import py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\nclass SequentialLaneChange(BasicScenario):\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        pass\n        self._scenario_timeout = 240\n        super().__init__(\"SequentialLaneChange\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        pass\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"SequentialLaneChange\")\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], 200))\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        sequence.add_child(end_condition)\n        return sequence\n        pass\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n        pass\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        pass"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/signalized_junction_left_turn.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a left turn\n\"\"\"\n\nimport py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass JunctionLeftTurn(BasicScenario):\n    \"\"\"\n    Vehicle turning left at junction scenario, with actors coming in the opposite direction.\n    The ego has to react to them, safely crossing the opposite lane\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self.timeout = timeout\n\n        self._direction = 'opposite'\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        self._end_distance = 10\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 20)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [25, 50])\n        self._scenario_timeout = 240\n\n        # The faster the flow, the further they are spawned, leaving time to react to them\n        self._source_dist = 4 * self._flow_speed\n        self._sink_dist = 2.5 * self._flow_speed\n\n        super().__init__(\"JunctionLeftTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the opposite entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Trying to find a lane in the {} direction but none was found\".format(self._direction))\n\n        # Get the source transform\n        source_entry_wp = self._rng.choice(source_entry_wps)\n\n        # Get the source transform\n        source_wp = source_entry_wp\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            source_wps = source_wp.previous(5)\n            if len(source_wps) == 0:\n                raise ValueError(\"Failed to find a source location as a waypoint with no previous was detected\")\n            if source_wps[0].is_junction:\n                break\n            source_wp = source_wps[0]\n            source_junction_dist += 5\n\n        self._source_wp = source_wp\n        source_transform = self._source_wp.transform\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 0)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location as a waypoint with no next was detected\")\n        self._sink_wp = sink_wps[0]\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass SignalizedJunctionLeftTurn(JunctionLeftTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        source_tl = get_closest_traffic_light(self._source_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            elif tl.id == source_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"SignalizedJunctionLeftTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=False,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n\n\nclass NonSignalizedJunctionLeftTurn(JunctionLeftTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"NonSignalizedJunctionLeftTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=get_same_dir_lanes(self._sink_wp),\n                stop_entries=True,\n                extend_road_exit=self._sink_dist + 20\n            ))\n            sequence.add_child(ChangeOppositeBehavior(active=False))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(root)\n\n        if self.route_mode:\n            sequence.add_child(ChangeOppositeBehavior(active=True))\n\n        return sequence\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/signalized_junction_right_turn.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a right turn\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass JunctionRightTurn(BasicScenario):\n    \"\"\"\n    Scenario where the vehicle is turning right at an intersection an has to avoid\n    colliding with vehicles coming from its left\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n\n        self._direction = 'left'\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n\n        self._end_distance = 10  # Distance after the junction before the scenario ends\n\n        self._flow_speed = get_value_parameter(config, 'flow_speed', float, 20)\n        self._source_dist_interval = get_interval_parameter(config, 'source_dist_interval', float, [25, 50])\n        self._scenario_timeout = 240\n\n        # The faster the flow, the further they are spawned, leaving time to react to them\n        self._source_dist = 5 * self._flow_speed\n        self._sink_dist = 3 * self._flow_speed\n\n        super().__init__(\"JunctionRightTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find a junction\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n\n        # Get the source entry lane wp\n        entry_wps, _ = get_junction_topology(self._junction)\n        source_entry_wps = filter_junction_wp_direction(starting_wp, entry_wps, self._direction)\n        if not source_entry_wps:\n            raise ValueError(\"Trying to find a lane in the {} direction but none was found\".format(self._direction))\n\n        # Get the rightmost lane\n        source_entry_wp = source_entry_wps[0]\n        while True:\n            right_wp = source_entry_wp.get_right_lane()\n            if not right_wp or right_wp.lane_type != carla.LaneType.Driving:\n                break\n            source_entry_wp = right_wp\n\n        # Get the source transform\n        source_wp = source_entry_wp\n        source_junction_dist = 0\n        while source_junction_dist < self._source_dist:\n            source_wps = source_wp.previous(5)\n            if len(source_wps) == 0:\n                raise ValueError(\"Failed to find a source location\")\n            if source_wps[0].is_junction:\n                break\n            source_wp = source_wps[0]\n            source_junction_dist += 5\n\n        self._source_wp = source_wp\n        source_transform = self._source_wp.transform\n\n        # Get the sink location\n        sink_exit_wp = generate_target_waypoint(self._map.get_waypoint(source_transform.location), 0)\n        sink_wps = sink_exit_wp.next(self._sink_dist)\n        if len(sink_wps) == 0:\n            raise ValueError(\"Failed to find a sink location\")\n        self._sink_wp = sink_wps[0]\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass SignalizedJunctionRightTurn(JunctionRightTurn):\n    \"\"\"\n    Signalized version of JunctionRightTurn\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        source_tl = get_closest_traffic_light(self._source_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            elif tl.id == source_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning right in an urban area, at a signalized intersection,\n        while other actor coming straight from the left. The ego has to avoid colliding with it\n        \"\"\"\n\n        sequence = py_trees.composites.Sequence(name=\"JunctionRightTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=[],\n                stop_entries=False,\n                extend_road_exit=self._sink_dist + 20\n            ))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed, initial_actors=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n        return sequence\n\n\nclass NonSignalizedJunctionRightTurn(JunctionRightTurn):\n    \"\"\"\n    Non signalized version of JunctionRightTurn\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning right in an urban area, at a signalized intersection,\n        while other actor coming straight from the left. The ego has to avoid colliding with it\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"JunctionRightTurn\")\n        if self.route_mode:\n            sequence.add_child(HandleJunctionScenario(\n                clear_junction=True,\n                clear_ego_entry=True,\n                remove_entries=get_same_dir_lanes(self._source_wp),\n                remove_exits=[],\n                stop_entries=True,\n                extend_road_exit=self._sink_dist + 20\n            ))\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n        root.add_child(ActorFlow(\n            self._source_wp, self._sink_wp, self._source_dist_interval, 2, self._flow_speed, initial_actors=True))\n        root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n\n        sequence.add_child(root)\n        return sequence\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/t_junction.py",
    "content": "import py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\nclass T_Junction(BasicScenario):\n    \"\"\"\n    This scenario is designed to make ego get the \"stop at red trafficlight, pass when it turn to green\" rule\n    (also pause at stop sign)\n    No spicial scenarios will be triggered\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        pass\n        self._scenario_timeout = 240\n        super().__init__(\"T_Junction\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        pass\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"T_Junction\")\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], 200))\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        sequence.add_child(end_condition)\n        return sequence\n        pass\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n        pass\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        pass"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/vanilla_turn.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nCollection of traffic scenarios where the ego vehicle (hero)\nis making a left turn\n\"\"\"\n\nimport py_trees\nfrom numpy import random\n\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import ActorFlow, TrafficLightFreezer, ScenarioTimeout\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import WaitEndIntersection, DriveDistance\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.scenario_helper import (generate_target_waypoint,\n                                           get_junction_topology,\n                                           filter_junction_wp_direction,\n                                           get_same_dir_lanes,\n                                           get_closest_traffic_light)\n\nfrom srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass VanillaJunctionTurn(BasicScenario):\n    \"\"\"\n    This scenario is designed to make ego get the \"stop at red trafficlight, pass when it turn to green\" rule\n    (also pause at stop sign)\n    No spicial scenarios will be triggered\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self._rng = CarlaDataProvider.get_random_seed()\n\n        self.timeout = timeout\n\n        self._green_light_delay = 5  # Wait before the ego's lane traffic light turns green\n        self._flow_tl_dict = {}\n        self._init_tl_dict = {}\n        self._end_distance = 10\n\n        super().__init__(\"VanillaJunctionTurn\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        ego_location = config.trigger_points[0].location\n        self._ego_wp = CarlaDataProvider.get_map().get_waypoint(ego_location)\n\n        # Get the junction\n        starting_wp = self._ego_wp\n        ego_junction_dist = 0\n        while not starting_wp.is_junction:\n            starting_wps = starting_wp.next(1.0)\n            if len(starting_wps) == 0:\n                raise ValueError(\"Failed to find junction as a waypoint with no next was detected\")\n            starting_wp = starting_wps[0]\n            ego_junction_dist += 1\n        self._junction = starting_wp.get_junction()\n        pass\n\n    def _create_behavior(self):\n        raise NotImplementedError(\"Found missing behavior\")\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors upon deletion\n        \"\"\"\n        self.remove_all_actors()\n\n\nclass VanillaSignalizedTurnEncounterGreenLight(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        # ego_tl.set_state(carla.TrafficLightState.Green)\n        # ego_tl.set_green_time(100000)\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterGreenLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict, duration=self._green_light_delay))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n\nclass VanillaSignalizedTurnEncounterGreenLightLong(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n        # ego_tl.set_state(carla.TrafficLightState.Green)\n        # ego_tl.set_green_time(100000)\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Green\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterGreenLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict, duration=self._green_light_delay))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaNonSignalizedTurn(VanillaJunctionTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VanillaNonSignalizedTurn\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaSignalizedTurnEncounterRedLight(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        self._green_light_delay = 5\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        # self._green_light_delay = 10\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterRedLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaSignalizedTurnEncounterRedLightLong(VanillaJunctionTurn):\n    \"\"\"\n    Signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        self._green_light_delay = 5\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Default initialization of other actors.\n        Override this method in child class to provide custom initialization.\n        \"\"\"\n        super()._initialize_actors(config)\n\n        # self._green_light_delay = 10\n        tls = self._world.get_traffic_lights_in_junction(self._junction.id)\n        if not tls:\n            raise ValueError(\"Found no traffic lights, use the non signalized version instead\")\n        ego_tl = get_closest_traffic_light(self._ego_wp, tls)\n\n        for tl in tls:\n            if tl.id == ego_tl.id:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Green\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n            else:\n                self._flow_tl_dict[tl] = carla.TrafficLightState.Red\n                self._init_tl_dict[tl] = carla.TrafficLightState.Red\n\n    def _create_behavior(self):\n        sequence = py_trees.composites.Sequence(name=\"VanillaSignalizedTurnEncounterRedLight\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        tl_freezer_sequence = py_trees.composites.Sequence(\"Traffic Light Behavior\")\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._init_tl_dict, duration=self._green_light_delay))\n        tl_freezer_sequence.add_child(TrafficLightFreezer(self._flow_tl_dict))\n        root.add_child(tl_freezer_sequence)\n\n        sequence.add_child(root)\n\n        return sequence\n\nclass VanillaNonSignalizedTurnEncounterStopsign(VanillaJunctionTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VanillaNonSignalizedTurnEncounterStopsign\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        return sequence\n    \nclass VanillaNonSignalizedTurnEncounterStopsignLong(VanillaJunctionTurn):\n    \"\"\"\n    Non signalized version of 'JunctionLeftTurn`\n    \"\"\"\n\n    timeout = 80  # Timeout of scenario in seconds\n\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=80, activate_scenario=True):\n        super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout)\n\n    def _create_behavior(self):\n        \"\"\"\n        Hero vehicle is turning left in an urban area at a signalized intersection,\n        where, a flow of actors coming straight is present.\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"VanillaNonSignalizedTurnEncounterStopsign\")\n\n        root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition = py_trees.composites.Sequence()\n        end_condition.add_child(WaitEndIntersection(self.ego_vehicles[0]))\n        end_condition.add_child(DriveDistance(self.ego_vehicles[0], self._end_distance))\n        root.add_child(end_condition)\n\n        sequence.add_child(root)\n\n        return sequence\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/vehicle_opens_door.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenarios in which another (opposite) vehicle 'illegally' takes\npriority, e.g. by running a red traffic light.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, ScenarioTimeoutTest\n\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorDestroy,\n                                                                      OpenVehicleDoor,\n                                                                      SwitchWrongDirectionTest,\n                                                                      ScenarioTimeout,\n                                                                      Idle,\n                                                                      OppositeActorFlow)\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation,\n                                                                               InTimeToArrivalToLocation,\n                                                                               DriveDistance,\n                                                                               WaitUntilInFrontPosition)\nfrom srunner.scenarios.basic_scenario import BasicScenario\n\nfrom srunner.tools.background_manager import LeaveSpaceInFront, ChangeOppositeBehavior, StopBackVehicles, StartBackVehicles\n\n\ndef get_value_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return p_type(config.other_parameters[name]['value'])\n    else:\n        return default\n\n\ndef get_interval_parameter(config, name, p_type, default):\n    if name in config.other_parameters:\n        return [\n            p_type(config.other_parameters[name]['from']),\n            p_type(config.other_parameters[name]['to'])\n        ]\n    else:\n        return default\n\n\nclass VehicleOpensDoorTwoWays(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which another vehicle parked at the side lane\n    opens the door, forcing the ego to lane change, invading the opposite lane\n    \"\"\"\n    def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n\n        self.timeout = timeout\n        self._min_trigger_dist = 10\n        self._reaction_time = 3.0\n\n        self._opposite_wait_duration = 5\n        self._end_distance = 50\n\n        self._parked_distance = get_value_parameter(config, 'distance', float, 50)\n        self._direction = get_value_parameter(config, 'direction', str, 'right')\n        if self._direction not in ('left', 'right'):\n            raise ValueError(f\"'direction' must be either 'right' or 'left' but {self._direction} was given\")\n\n        self._max_speed = get_value_parameter(config, 'speed', float, 60)\n        self._scenario_timeout = 240\n\n        self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100])\n\n        super().__init__(\"VehicleOpensDoorTwoWays\", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)\n\n    def _get_displaced_location(self, actor, wp):\n        \"\"\"\n        Calculates the transforming such that the actor is at the sidemost part of the lane\n        \"\"\"\n        # Move the actor to the edge of the lane, or the open door might not reach the ego vehicle\n        displacement = (wp.lane_width - actor.bounding_box.extent.y) / 4\n        displacement_vector = wp.transform.get_right_vector()\n        if self._direction == 'right':\n            displacement_vector *= -1\n\n        new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x,\n                                                              y=displacement*displacement_vector.y,\n                                                              z=displacement*displacement_vector.z)\n        new_location.z += 0.05  # Just in case, avoid collisions with the ground\n        return new_location\n\n    def _move_waypoint_forward(self, wp, distance):\n        dist = 0\n        next_wp = wp\n        while dist < distance:\n            next_wps = next_wp.next(1)\n            if not next_wps or next_wps[0].is_junction:\n                break\n            next_wp = next_wps[0]\n            dist += 1\n        return next_wp\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Creates a parked vehicle on the side of the road\n        \"\"\"\n        trigger_location = config.trigger_points[0].location\n        starting_wp = self._map.get_waypoint(trigger_location)\n        front_wps = starting_wp.next(self._parked_distance)\n        if len(front_wps) == 0:\n            raise ValueError(\"Couldn't find a spot to place the adversary vehicle\")\n        elif len(front_wps) > 1:\n            print(\"WARNING: Found a diverging lane. Choosing one at random\")\n        self._front_wp = front_wps[0]\n\n        if self._direction == 'left':\n            self._parked_wp = self._front_wp.get_left_lane()\n        else:\n            self._parked_wp = self._front_wp.get_right_lane()\n\n        if self._parked_wp is None:\n            raise ValueError(\"Couldn't find a spot to place the adversary vehicle\")\n\n        self.parking_slots.append(self._parked_wp.transform.location)\n\n        self._parked_actor = CarlaDataProvider.request_new_actor(\n            \"*vehicle.*\", self._parked_wp.transform, attribute_filter={'has_dynamic_doors': True, 'base_type': 'car'})\n        if not self._parked_actor:\n            raise ValueError(\"Couldn't spawn the parked vehicle\")\n        self.other_actors.append(self._parked_actor)\n\n        # And move it to the side\n        side_location = self._get_displaced_location(self._parked_actor, self._parked_wp)\n        self._parked_actor.set_location(side_location)\n        self._parked_actor.apply_control(carla.VehicleControl(hand_brake=True))\n\n        self._end_wp = self._move_waypoint_forward(self._front_wp, self._end_distance)\n\n    def _create_behavior(self):\n        \"\"\"\n        Leave space in front, as the TM doesn't detect open doors, and change the opposite frequency \n        so that the ego can pass\n        \"\"\"\n        reference_wp = self._parked_wp.get_left_lane()\n        if not reference_wp:\n            raise ValueError(\"Couldnt find a left lane to spawn the opposite traffic\")\n\n        root = py_trees.composites.Sequence(name=\"VehicleOpensDoorTwoWays\")\n        if self.route_mode:\n            total_dist = self._parked_distance + 20\n            root.add_child(LeaveSpaceInFront(total_dist))\n\n        end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n        end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name))\n        end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False))\n\n        behavior = py_trees.composites.Sequence(name=\"Main Behavior\")\n\n        # Wait until ego is close to the adversary\n        collision_location = self._front_wp.transform.location\n        trigger_adversary = py_trees.composites.Parallel(\n            policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name=\"TriggerOpenDoor\")\n        trigger_adversary.add_child(InTimeToArrivalToLocation(\n            self.ego_vehicles[0], self._reaction_time, collision_location))\n        trigger_adversary.add_child(InTriggerDistanceToLocation(\n            self.ego_vehicles[0], collision_location, self._min_trigger_dist))\n        behavior.add_child(trigger_adversary)\n\n        door = carla.VehicleDoor.FR if self._direction == 'left' else carla.VehicleDoor.FL\n        behavior.add_child(OpenVehicleDoor(self._parked_actor, door))\n        behavior.add_child(StopBackVehicles())\n        behavior.add_child(Idle(self._opposite_wait_duration))\n        if self.route_mode:\n            behavior.add_child(SwitchWrongDirectionTest(False))\n            behavior.add_child(ChangeOppositeBehavior(active=False))\n        behavior.add_child(OppositeActorFlow(reference_wp, self.ego_vehicles[0], self._opposite_interval))\n\n        end_condition.add_child(behavior)\n        root.add_child(end_condition)\n\n        if self.route_mode:\n            root.add_child(SwitchWrongDirectionTest(True))\n            root.add_child(ChangeOppositeBehavior(active=True))\n        for actor in self.other_actors:\n            root.add_child(ActorDestroy(actor))\n            root.add_child(StartBackVehicles())\n\n        return root\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criteria = [ScenarioTimeoutTest(self.ego_vehicles[0], self.config.name)]\n        if not self.route_mode:\n            criteria.append(CollisionTest(self.ego_vehicles[0]))\n        return criteria\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/scenarios/yield_to_emergency_vehicle.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nScenario in which the ego has to yield its lane to emergency vehicle.\n\"\"\"\n\nfrom __future__ import print_function\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter,\n                                                                      ActorDestroy,\n                                                                      Idle,\n                                                                      AdaptiveConstantVelocityAgentBehavior)\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, YieldToEmergencyVehicleTest\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               WaitUntilInFront,\n                                                                               DriveDistance)\nfrom srunner.scenarios.basic_scenario import BasicScenario\nfrom srunner.tools.background_manager import RemoveRoadLane, ReAddRoadLane\n\n\nclass YieldToEmergencyVehicle(BasicScenario):\n    \"\"\"\n    This class holds everything required for a scenario in which the ego has to yield its lane to emergency vehicle.\n    The background activity will be removed from the lane the emergency vehicle will pass through, \n    and will be recreated once the scenario is over.\n\n    Should be on the highway which is long enough and has no junctions.\n    There should be at least two lanes on the highway.\n    \"\"\"\n\n    def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True,\n                 timeout=180):\n        \"\"\"\n        Setup all relevant parameters and create scenario\n        and instantiate scenario manager\n        \"\"\"\n        self._world = world\n        self._map = CarlaDataProvider.get_map()\n        self.timeout = timeout\n        self._ev_idle_time = 10  # seconds\n\n        # km/h. How much the EV is expected to be faster than the EGO\n        self._speed_increment = 25\n\n        self._trigger_distance = 50\n\n        if 'distance' in config.other_parameters:\n            self._distance = float(config.other_parameters['distance']['value'])\n        else:\n            self._distance = 140  # m\n\n        # Change some of the parameters to adapt its behavior.\n        # 1) ConstantVelocityAgent = infinite acceleration -> reduce the detection radius to pressure the ego\n        # 2) Always use the bb check to ensure the EV doesn't run over the ego when it is lane changing\n        # 3) Add more wps to improve BB detection\n        self._opt_dict = {\n            'base_vehicle_threshold': 10, 'detection_speed_ratio': 0.15, 'use_bbs_detection': True,\n            'base_min_distance': 1, 'distance_ratio': 0.2\n            }\n\n        self._trigger_location = config.trigger_points[0].location\n        self._reference_waypoint = self._map.get_waypoint(self._trigger_location)\n\n        self._end_distance = 50\n\n        super().__init__(\"YieldToEmergencyVehicle\",\n                         ego_vehicles,\n                         config,\n                         world,\n                         debug_mode,\n                         criteria_enable=criteria_enable)\n\n    def _initialize_actors(self, config):\n        \"\"\"\n        Custom initialization\n        \"\"\"\n        # Spawn emergency vehicle\n        ev_points = self._reference_waypoint.previous(self._distance)\n        if not ev_points:\n            raise ValueError(\"Couldn't find viable position for the emergency vehicle\")\n\n        self._ev_start_transform = ev_points[0].transform\n\n        actor = CarlaDataProvider.request_new_actor(\n            \"vehicle.*.*\", self._ev_start_transform, attribute_filter={'special_type': 'emergency'})\n        if actor is None:\n            raise Exception(\"Couldn't spawn the emergency vehicle\")\n\n        # Move the actor underground and remove its physics so that it doesn't fall\n        actor.set_simulate_physics(False)\n        new_location = actor.get_location()\n        new_location.z -= 500\n        actor.set_location(new_location)\n\n        # Turn on special lights\n        actor.set_light_state(carla.VehicleLightState(\n            carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2))\n\n        self.other_actors.append(actor)\n\n    def _create_behavior(self):\n        \"\"\"\n        Spawn the EV behind and wait for it to be close-by. After it has approached,\n        give the ego a certain amount of time to yield to it.\n        \n        Sequence:\n        - RemoveRoadLane\n        - ActorTransformSetter\n        - Parallel:\n            - AdaptiveConstantVelocityAgentBehavior\n            - Sequence: (End condition 1)\n                - InTriggerDistanceToVehicle:\n                - Idle\n            - Sequence: (End condition 2)\n                - WaitUntilInFront\n                - DriveDistance\n        - ReAddRoadLane\n        \"\"\"\n        sequence = py_trees.composites.Sequence(name=\"YieldToEmergencyVehicle\")\n\n        if self.route_mode:\n            sequence.add_child(RemoveRoadLane(self._reference_waypoint))\n\n        sequence.add_child(ActorTransformSetter(self.other_actors[0], self._ev_start_transform))\n\n        main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE)\n\n        end_condition_1 = py_trees.composites.Sequence()\n        end_condition_1.add_child(InTriggerDistanceToVehicle(\n            self.ego_vehicles[0], self.other_actors[0], self._trigger_distance))\n        end_condition_1.add_child(Idle(self._ev_idle_time))\n\n        end_condition_2 = py_trees.composites.Sequence()\n        end_condition_2.add_child(WaitUntilInFront(self.other_actors[0], self.ego_vehicles[0]))\n        end_condition_2.add_child(DriveDistance(self.other_actors[0], self._end_distance))\n\n        main_behavior.add_child(end_condition_1)\n        main_behavior.add_child(end_condition_2)\n\n        main_behavior.add_child(AdaptiveConstantVelocityAgentBehavior(\n            self.other_actors[0], self.ego_vehicles[0], speed_increment=self._speed_increment, opt_dict=self._opt_dict))\n\n        sequence.add_child(main_behavior)\n\n        sequence.add_child(ActorDestroy(self.other_actors[0]))\n\n        if self.route_mode:\n            sequence.add_child(ReAddRoadLane(0))\n\n        return sequence\n\n    def _create_test_criteria(self):\n        \"\"\"\n        A list of all test criteria will be created that is later used\n        in parallel behavior tree.\n        \"\"\"\n        criterias = []\n        criterias.append(YieldToEmergencyVehicleTest(self.ego_vehicles[0], self.other_actors[0]))\n        if not self.route_mode:\n            criterias.append(CollisionTest(self.ego_vehicles[0]))\n\n        return criterias\n\n    def __del__(self):\n        \"\"\"\n        Remove all actors and traffic lights upon deletion\n        \"\"\"\n        self.remove_all_actors()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/README.md",
    "content": "carla.py is a CARLA mock module that allows to execute unittests without a CARLA installation or running instance.\n\nRemark:\nagents/ is a 1:1 copy from CARLA"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/basic_agent.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module implements an agent that roams around a track following random\nwaypoints and avoiding other vehicles. The agent also responds to traffic lights.\nIt can also make use of the global route planner to follow a specifed route\n\"\"\"\n\nimport carla\nfrom enum import Enum\n\nfrom agents.navigation.local_planner import LocalPlanner\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.tools.misc import get_speed, is_within_distance, get_trafficlight_trigger_location\n\n\nclass BasicAgent(object):\n    \"\"\"\n    BasicAgent implements an agent that navigates the scene.\n    This agent respects traffic lights and other vehicles, but ignores stop signs.\n    It has several functions available to specify the route that the agent must follow,\n    as well as to change its parameters in case a different driving mode is desired.\n    \"\"\"\n\n    def __init__(self, vehicle, target_speed=20, opt_dict={}):\n        \"\"\"\n        Initialization the agent paramters, the local and the global planner.\n\n            :param vehicle: actor to apply to agent logic onto\n            :param target_speed: speed (in Km/h) at which the vehicle will move\n            :param opt_dict: dictionary in case some of its parameters want to be changed.\n                This also applies to parameters related to the LocalPlanner.\n        \"\"\"\n        self._vehicle = vehicle\n        self._world = self._vehicle.get_world()\n        self._map = self._world.get_map()\n        self._last_traffic_light = None\n\n        # Base parameters\n        self._ignore_traffic_lights = False\n        self._ignore_stop_signs = False\n        self._ignore_vehicles = False\n        self._target_speed = target_speed\n        self._sampling_resolution = 2.0\n        self._base_tlight_threshold = 5.0  # meters\n        self._base_vehicle_threshold = 5.0  # meters\n        self._max_brake = 0.5\n\n        # Change parameters according to the dictionary\n        opt_dict['target_speed'] = target_speed\n        if 'ignore_traffic_lights' in opt_dict:\n            self._ignore_traffic_lights = opt_dict['ignore_traffic_lights']\n        if 'ignore_stop_signs' in opt_dict:\n            self._ignore_stop_signs = opt_dict['ignore_stop_signs']\n        if 'ignore_vehicles' in opt_dict:\n            self._ignore_vehicles = opt_dict['ignore_vehicles']\n        if 'sampling_resolution' in opt_dict:\n            self._sampling_resolution = opt_dict['sampling_resolution']\n        if 'base_tlight_threshold' in opt_dict:\n            self._base_tlight_threshold = opt_dict['base_tlight_threshold']\n        if 'base_vehicle_threshold' in opt_dict:\n            self._base_vehicle_threshold = opt_dict['base_vehicle_threshold']\n        if 'max_brake' in opt_dict:\n            self._max_steering = opt_dict['max_brake']\n\n        # Initialize the planners\n        self._local_planner = LocalPlanner(self._vehicle, opt_dict=opt_dict)\n        self._global_planner = GlobalRoutePlanner(self._map, self._sampling_resolution)\n\n    def add_emergency_stop(self, control):\n        \"\"\"\n        Overwrites the throttle a brake values of a control to perform an emergency stop.\n        The steering is kept the same to avoid going out of the lane when stopping during turns\n\n            :param speed (carl.VehicleControl): control to be modified\n        \"\"\"\n        control.throttle = 0.0\n        control.brake = self._max_brake\n        control.hand_brake = False\n        return control\n\n    def set_target_speed(self, speed):\n        \"\"\"\n        Changes the target speed of the agent\n            :param speed (float): target speed in Km/h\n        \"\"\"\n        self._local_planner.set_speed(speed)\n\n    def follow_speed_limits(self, value=True):\n        \"\"\"\n        If active, the agent will dynamically change the target speed according to the speed limits\n\n            :param value (bool): whether or not to activate this behavior\n        \"\"\"\n        self._local_planner.follow_speed_limits(value)\n\n    def get_local_planner(self):\n        \"\"\"Get method for protected member local planner\"\"\"\n        return self._local_planner\n\n    def get_global_planner(self):\n        \"\"\"Get method for protected member local planner\"\"\"\n        return self._global_planner\n\n    def set_destination(self, end_location, start_location=None):\n        \"\"\"\n        This method creates a list of waypoints between a starting and ending location,\n        based on the route returned by the global router, and adds it to the local planner.\n        If no starting location is passed, the vehicle local planner's target location is chosen,\n        which corresponds (by default), to a location about 5 meters in front of the vehicle.\n\n            :param end_location (carla.Location): final location of the route\n            :param start_location (carla.Location): starting location of the route\n        \"\"\"\n        if not start_location:\n            start_location = self._local_planner.target_waypoint.transform.location\n            clean_queue = True\n        else:\n            start_location = self._vehicle.get_location()\n            clean_queue = False\n\n        start_waypoint = self._map.get_waypoint(start_location)\n        end_waypoint = self._map.get_waypoint(end_location)\n\n        route_trace = self.trace_route(start_waypoint, end_waypoint)\n        self._local_planner.set_global_plan(route_trace, clean_queue=clean_queue)\n\n    def set_global_plan(self, plan, stop_waypoint_creation=True, clean_queue=True):\n        \"\"\"\n        Adds a specific plan to the agent.\n\n            :param plan: list of [carla.Waypoint, RoadOption] representing the route to be followed\n            :param stop_waypoint_creation: stops the automatic random creation of waypoints\n            :param clean_queue: resets the current agent's plan\n        \"\"\"\n        self._local_planner.set_global_plan(\n            plan,\n            stop_waypoint_creation=stop_waypoint_creation,\n            clean_queue=clean_queue\n        )\n\n    def trace_route(self, start_waypoint, end_waypoint):\n        \"\"\"\n        Calculates the shortest route between a starting and ending waypoint.\n\n            :param start_waypoint (carla.Waypoint): initial waypoint\n            :param end_waypoint (carla.Waypoint): final waypoint\n        \"\"\"\n        start_location = start_waypoint.transform.location\n        end_location = end_waypoint.transform.location\n        return self._global_planner.trace_route(start_location, end_location)\n\n    def run_step(self):\n        \"\"\"Execute one step of navigation.\"\"\"\n        hazard_detected = False\n\n        # Retrieve all relevant actors\n        actor_list = self._world.get_actors()\n        vehicle_list = actor_list.filter(\"*vehicle*\")\n        lights_list = actor_list.filter(\"*traffic_light*\")\n\n        vehicle_speed = get_speed(self._vehicle) / 3.6\n\n        # Check for possible vehicle obstacles\n        max_vehicle_distance = self._base_vehicle_threshold + vehicle_speed\n        affected_by_vehicle, _ = self._vehicle_obstacle_detected(vehicle_list, max_vehicle_distance)\n        if affected_by_vehicle:\n            hazard_detected = True\n\n        # Check if the vehicle is affected by a red traffic light\n        max_tlight_distance = self._base_tlight_threshold + vehicle_speed\n        affected_by_tlight, _ = self._affected_by_traffic_light(lights_list, max_tlight_distance)\n        if affected_by_tlight:\n            hazard_detected = True\n\n        control = self._local_planner.run_step()\n        if hazard_detected:\n            control = self.add_emergency_stop(control)\n\n        return control\n\n    def done(self):\n        \"\"\"Check whether the agent has reached its destination.\"\"\"\n        return self._local_planner.done()\n\n    def ignore_traffic_lights(self, active=True):\n        \"\"\"(De)activates the checks for traffic lights\"\"\"\n        self._ignore_traffic_lights = active\n\n    def ignore_stop_signs(self, active=True):\n        \"\"\"(De)activates the checks for stop signs\"\"\"\n        self._ignore_stop_signs = active\n\n    def ignore_vehicles(self, active=True):\n        \"\"\"(De)activates the checks for stop signs\"\"\"\n        self._ignore_vehicles = active\n\n    def _affected_by_traffic_light(self, lights_list=None, max_distance=None):\n        \"\"\"\n        Method to check if there is a red light affecting the vehicle.\n\n            :param lights_list (list of carla.TrafficLight): list containing TrafficLight objects.\n                If None, all traffic lights in the scene are used\n            :param max_distance (float): max distance for traffic lights to be considered relevant.\n                If None, the base threshold value is used\n        \"\"\"\n        if self._ignore_traffic_lights:\n            return (False, None)\n\n        if not lights_list:\n            lights_list = self._world.get_actors().filter(\"*traffic_light*\")\n\n        if not max_distance:\n            max_distance = self._base_tlight_threshold\n\n        if self._last_traffic_light:\n            if self._last_traffic_light.state != carla.TrafficLightState.Red:\n                self._last_traffic_light = None\n            else:\n                return (True, self._last_traffic_light)\n\n        ego_vehicle_location = self._vehicle.get_location()\n        ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location)\n\n        for traffic_light in lights_list:\n            object_location = get_trafficlight_trigger_location(traffic_light)\n            object_waypoint = self._map.get_waypoint(object_location)\n\n            if object_waypoint.road_id != ego_vehicle_waypoint.road_id:\n                continue\n\n            ve_dir = ego_vehicle_waypoint.transform.get_forward_vector()\n            wp_dir = object_waypoint.transform.get_forward_vector()\n            dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z\n\n            if dot_ve_wp < 0:\n                continue\n\n            if traffic_light.state != carla.TrafficLightState.Red:\n                continue\n\n            if is_within_distance(object_waypoint.transform, self._vehicle.get_transform(), max_distance, [0, 90]):\n                self._last_traffic_light = traffic_light\n                return (True, traffic_light)\n\n        return (False, None)\n\n    def _vehicle_obstacle_detected(self, vehicle_list=None, max_distance=None):\n        \"\"\"\n        Method to check if there is a vehicle in front of the agent blocking its path.\n\n            :param vehicle_list (list of carla.Vehicle): list contatining vehicle objects.\n                If None, all vehicle in the scene are used\n            :param max_distance: max freespace to check for obstacles.\n                If None, the base threshold value is used\n        \"\"\"\n        if self._ignore_vehicles:\n            return (False, None)\n\n        if not vehicle_list:\n            vehicle_list = self._world.get_actors().filter(\"*vehicle*\")\n\n        if not max_distance:\n            max_distance = self._base_vehicle_threshold\n\n        ego_transform = self._vehicle.get_transform()\n        ego_wpt = self._map.get_waypoint(self._vehicle.get_location())\n\n        # Get the transform of the front of the ego\n        ego_forward_vector = ego_transform.get_forward_vector()\n        ego_extent = self._vehicle.bounding_box.extent.x\n        ego_front_transform = ego_transform\n        ego_front_transform.location += carla.Location(\n            x=ego_extent * ego_forward_vector.x,\n            y=ego_extent * ego_forward_vector.y,\n        )\n\n        for target_vehicle in vehicle_list:\n            target_transform = target_vehicle.get_transform()\n            target_wpt = self._map.get_waypoint(target_transform.location)\n            if target_wpt.road_id != ego_wpt.road_id or target_wpt.lane_id != ego_wpt.lane_id:\n                next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=3)[0]\n                if not next_wpt:\n                    continue\n                if target_wpt.road_id != next_wpt.road_id or target_wpt.lane_id != next_wpt.lane_id:\n                    continue\n\n            target_forward_vector = target_transform.get_forward_vector()\n            target_extent = target_vehicle.bounding_box.extent.x\n            target_rear_transform = target_transform\n            target_rear_transform.location -= carla.Location(\n                x=target_extent * target_forward_vector.x,\n                y=target_extent * target_forward_vector.y,\n            )\n\n            if is_within_distance(target_rear_transform, ego_front_transform, max_distance, [0, 90]):\n                return (True, target_vehicle)\n        return (False, None)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\n\"\"\" This module implements an agent that roams around a track following random\nwaypoints and avoiding other vehicles. The agent also responds to traffic lights,\ntraffic signs, and has different possible configurations. \"\"\"\n\nimport random\nimport numpy as np\nimport carla\nfrom agents.navigation.basic_agent import BasicAgent\nfrom agents.navigation.local_planner import RoadOption\nfrom agents.navigation.behavior_types import Cautious, Aggressive, Normal\n\nfrom agents.tools.misc import get_speed, positive, is_within_distance, compute_distance\n\nclass BehaviorAgent(BasicAgent):\n    \"\"\"\n    BehaviorAgent implements an agent that navigates scenes to reach a given\n    target destination, by computing the shortest possible path to it.\n    This agent can correctly follow traffic signs, speed limitations,\n    traffic lights, while also taking into account nearby vehicles. Lane changing\n    decisions can be taken by analyzing the surrounding environment such as tailgating avoidance.\n    Adding to these are possible behaviors, the agent can also keep safety distance\n    from a car in front of it by tracking the instantaneous time to collision\n    and keeping it in a certain range. Finally, different sets of behaviors\n    are encoded in the agent, from cautious to a more aggressive ones.\n    \"\"\"\n\n    def __init__(self, vehicle, behavior='normal'):\n        \"\"\"\n        Constructor method.\n\n            :param vehicle: actor to apply to local planner logic onto\n            :param ignore_traffic_light: boolean to ignore any traffic light\n            :param behavior: type of agent to apply\n        \"\"\"\n\n        super(BehaviorAgent, self).__init__(vehicle)\n        self._look_ahead_steps = 0\n\n        # Vehicle information\n        self._speed = 0\n        self._speed_limit = 0\n        self._direction = None\n        self._incoming_direction = None\n        self._incoming_waypoint = None\n        self._min_speed = 5\n        self._behavior = None\n        self._sampling_resolution = 4.5\n\n        # Parameters for agent behavior\n        if behavior == 'cautious':\n            self._behavior = Cautious()\n\n        elif behavior == 'normal':\n            self._behavior = Normal()\n\n        elif behavior == 'aggressive':\n            self._behavior = Aggressive()\n\n    def _update_information(self):\n        \"\"\"\n        This method updates the information regarding the ego\n        vehicle based on the surrounding world.\n        \"\"\"\n        self._speed = get_speed(self._vehicle)\n        self._speed_limit = self._vehicle.get_speed_limit()\n        self._local_planner.set_speed(self._speed_limit)\n        self._direction = self._local_planner.target_road_option\n        if self._direction is None:\n            self._direction = RoadOption.LANEFOLLOW\n\n        self._look_ahead_steps = int((self._speed_limit) / 10)\n\n        self._incoming_waypoint, self._incoming_direction = self._local_planner.get_incoming_waypoint_and_direction(\n            steps=self._look_ahead_steps)\n        if self._incoming_direction is None:\n            self._incoming_direction = RoadOption.LANEFOLLOW\n\n    def _vehicle_obstacle_detected(self, vehicle_list, proximity_th, up_angle_th, low_angle_th=0, lane_offset=0):\n        \"\"\"\n        Check if a given vehicle is an obstacle in our way. To this end we take\n        into account the road and lane the target vehicle is on and run a\n        geometry test to check if the target vehicle is under a certain distance\n        in front of our ego vehicle. We also check the next waypoint, just to be\n        sure there's not a sudden road id change.\n\n        WARNING: This method is an approximation that could fail for very large\n        vehicles, which center is actually on a different lane but their\n        extension falls within the ego vehicle lane. Also, make sure to remove\n        the ego vehicle from the list. Lane offset is set to +1 for right lanes\n        and -1 for left lanes, but this has to be inverted if lane values are\n        negative.\n\n            :param vehicle_list: list of potential obstacle to check\n            :param proximity_th: threshold for the agent to be alerted of\n            a possible collision\n            :param up_angle_th: upper threshold for angle\n            :param low_angle_th: lower threshold for angle\n            :param lane_offset: for right and left lane changes\n            :return: a tuple given by (bool_flag, vehicle, distance), where:\n            - bool_flag is True if there is a vehicle ahead blocking us\n                   and False otherwise\n            - vehicle is the blocker object itself\n            - distance is the meters separating the two vehicles\n        \"\"\"\n        ego_transform = self._vehicle.get_transform()\n        ego_location = ego_transform.location\n        ego_wpt = self._map.get_waypoint(ego_location)\n\n        # Get the right offset\n        if ego_wpt.lane_id < 0 and lane_offset != 0:\n            lane_offset *= -1\n\n        for target_vehicle in vehicle_list:\n\n            target_transform = target_vehicle.get_transform()\n            target_location = target_transform.location\n            # If the object is not in our next or current lane it's not an obstacle\n\n            target_wpt = self._map.get_waypoint(target_location)\n            if target_wpt.road_id != ego_wpt.road_id or \\\n                    target_wpt.lane_id != ego_wpt.lane_id + lane_offset:\n                next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=5)[0]\n                if target_wpt.road_id != next_wpt.road_id or \\\n                        target_wpt.lane_id != next_wpt.lane_id + lane_offset:\n                    continue\n\n            if is_within_distance(target_transform, ego_transform,\n                                  proximity_th, [low_angle_th, up_angle_th]):\n\n                return (True, target_vehicle, compute_distance(target_location, ego_location))\n\n        return (False, None, -1)\n\n    def traffic_light_manager(self):\n        \"\"\"\n        This method is in charge of behaviors for red lights.\n        \"\"\"\n        actor_list = self._world.get_actors()\n        lights_list = actor_list.filter(\"*traffic_light*\")\n        affected, _ = self._affected_by_traffic_light(lights_list)\n\n        return affected\n\n    def _tailgating(self, waypoint, vehicle_list):\n        \"\"\"\n        This method is in charge of tailgating behaviors.\n\n            :param location: current location of the agent\n            :param waypoint: current waypoint of the agent\n            :param vehicle_list: list of all the nearby vehicles\n        \"\"\"\n\n        left_turn = waypoint.left_lane_marking.lane_change\n        right_turn = waypoint.right_lane_marking.lane_change\n\n        left_wpt = waypoint.get_left_lane()\n        right_wpt = waypoint.get_right_lane()\n\n        behind_vehicle_state, behind_vehicle, _ = self._vehicle_obstacle_detected(vehicle_list, max(\n            self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, low_angle_th=160)\n        if behind_vehicle_state and self._speed < get_speed(behind_vehicle):\n            if (right_turn == carla.LaneChange.Right or right_turn ==\n                    carla.LaneChange.Both) and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving:\n                new_vehicle_state, _, _ = self._vehicle_obstacle_detected(vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=1)\n                if not new_vehicle_state:\n                    print(\"Tailgating, moving to the right!\")\n                    end_waypoint = self._local_planner.target_waypoint\n                    self._behavior.tailgate_counter = 200\n                    self.set_destination(end_waypoint.transform.location,\n                                         right_wpt.transform.location)\n            elif left_turn == carla.LaneChange.Left and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving:\n                new_vehicle_state, _, _ = self._vehicle_obstacle_detected(vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=-1)\n                if not new_vehicle_state:\n                    print(\"Tailgating, moving to the left!\")\n                    end_waypoint = self._local_planner.target_waypoint\n                    self._behavior.tailgate_counter = 200\n                    self.set_destination(end_waypoint.transform.location,\n                                         left_wpt.transform.location)\n\n    def collision_and_car_avoid_manager(self, waypoint):\n        \"\"\"\n        This module is in charge of warning in case of a collision\n        and managing possible tailgating chances.\n\n            :param location: current location of the agent\n            :param waypoint: current waypoint of the agent\n            :return vehicle_state: True if there is a vehicle nearby, False if not\n            :return vehicle: nearby vehicle\n            :return distance: distance to nearby vehicle\n        \"\"\"\n\n        vehicle_list = self._world.get_actors().filter(\"*vehicle*\")\n        def dist(v): return v.get_location().distance(waypoint.transform.location)\n        vehicle_list = [v for v in vehicle_list if dist(v) < 45 and v.id != self._vehicle.id]\n\n        if self._direction == RoadOption.CHANGELANELEFT:\n            vehicle_state, vehicle, distance = self._vehicle_obstacle_detected(\n                vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=-1)\n        elif self._direction == RoadOption.CHANGELANERIGHT:\n            vehicle_state, vehicle, distance = self._vehicle_obstacle_detected(\n                vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=1)\n        else:\n            vehicle_state, vehicle, distance = self._vehicle_obstacle_detected(\n                vehicle_list, max(\n                    self._behavior.min_proximity_threshold, self._speed_limit / 3), up_angle_th=30)\n\n            # Check for tailgating\n            if not vehicle_state and self._direction == RoadOption.LANEFOLLOW \\\n                    and not waypoint.is_junction and self._speed > 10 \\\n                    and self._behavior.tailgate_counter == 0:\n                self._tailgating(waypoint, vehicle_list)\n\n        return vehicle_state, vehicle, distance\n\n    def pedestrian_avoid_manager(self, waypoint):\n        \"\"\"\n        This module is in charge of warning in case of a collision\n        with any pedestrian.\n\n            :param location: current location of the agent\n            :param waypoint: current waypoint of the agent\n            :return vehicle_state: True if there is a walker nearby, False if not\n            :return vehicle: nearby walker\n            :return distance: distance to nearby walker\n        \"\"\"\n\n        walker_list = self._world.get_actors().filter(\"*walker.pedestrian*\")\n        def dist(w): return w.get_location().distance(waypoint.transform.location)\n        walker_list = [w for w in walker_list if dist(w) < 10]\n\n        if self._direction == RoadOption.CHANGELANELEFT:\n            walker_state, walker, distance = self._vehicle_obstacle_detected(walker_list, max(\n                self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=90, lane_offset=-1)\n        elif self._direction == RoadOption.CHANGELANERIGHT:\n            walker_state, walker, distance = self._vehicle_obstacle_detected(walker_list, max(\n                self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=90, lane_offset=1)\n        else:\n            walker_state, walker, distance = self._vehicle_obstacle_detected(walker_list, max(\n                self._behavior.min_proximity_threshold, self._speed_limit / 3), up_angle_th=60)\n\n        return walker_state, walker, distance\n\n    def car_following_manager(self, vehicle, distance, debug=False):\n        \"\"\"\n        Module in charge of car-following behaviors when there's\n        someone in front of us.\n\n            :param vehicle: car to follow\n            :param distance: distance from vehicle\n            :param debug: boolean for debugging\n            :return control: carla.VehicleControl\n        \"\"\"\n\n        vehicle_speed = get_speed(vehicle)\n        delta_v = max(1, (self._speed - vehicle_speed) / 3.6)\n        ttc = distance / delta_v if delta_v != 0 else distance / np.nextafter(0., 1.)\n\n        # Under safety time distance, slow down.\n        if self._behavior.safety_time > ttc > 0.0:\n            target_speed = min([\n                positive(vehicle_speed - self._behavior.speed_decrease),\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        # Actual safety distance area, try to follow the speed of the vehicle in front.\n        elif 2 * self._behavior.safety_time > ttc >= self._behavior.safety_time:\n            target_speed = min([\n                max(self._min_speed, vehicle_speed),\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        # Normal behavior.\n        else:\n            target_speed = min([\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        return control\n\n    def run_step(self, debug=False):\n        \"\"\"\n        Execute one step of navigation.\n\n            :param debug: boolean for debugging\n            :return control: carla.VehicleControl\n        \"\"\"\n        self._update_information()\n\n        control = None\n        if self._behavior.tailgate_counter > 0:\n            self._behavior.tailgate_counter -= 1\n\n        ego_vehicle_loc = self._vehicle.get_location()\n        ego_vehicle_wp = self._map.get_waypoint(ego_vehicle_loc)\n\n        # 1: Red lights and stops behavior\n        if self.traffic_light_manager():\n            return self.emergency_stop()\n\n        # 2.1: Pedestrian avoidance behaviors\n        walker_state, walker, w_distance = self.pedestrian_avoid_manager(ego_vehicle_wp)\n\n        if walker_state:\n            # Distance is computed from the center of the two cars,\n            # we use bounding boxes to calculate the actual distance\n            distance = w_distance - max(\n                walker.bounding_box.extent.y, walker.bounding_box.extent.x) - max(\n                    self._vehicle.bounding_box.extent.y, self._vehicle.bounding_box.extent.x)\n\n            # Emergency brake if the car is very close.\n            if distance < self._behavior.braking_distance:\n                return self.emergency_stop()\n\n        # 2.2: Car following behaviors\n        vehicle_state, vehicle, distance = self.collision_and_car_avoid_manager(ego_vehicle_wp)\n\n        if vehicle_state:\n            # Distance is computed from the center of the two cars,\n            # we use bounding boxes to calculate the actual distance\n            distance = distance - max(\n                vehicle.bounding_box.extent.y, vehicle.bounding_box.extent.x) - max(\n                    self._vehicle.bounding_box.extent.y, self._vehicle.bounding_box.extent.x)\n\n            # Emergency brake if the car is very close.\n            if distance < self._behavior.braking_distance:\n                return self.emergency_stop()\n            else:\n                control = self.car_following_manager(vehicle, distance)\n\n        # 3: Intersection behavior\n        elif self._incoming_waypoint.is_junction and (self._incoming_direction in [RoadOption.LEFT, RoadOption.RIGHT]):\n            target_speed = min([\n                self._behavior.max_speed,\n                self._speed_limit - 5])\n            self._local_planner.set_speed(target_speed)\n            control = self._local_planner.run_step(debug=debug)\n\n        # 4: Normal behavior\n        else:\n            target_speed = min([\n                self._behavior.max_speed,\n                self._speed_limit - self._behavior.speed_lim_dist])\n            self._local_planner.set_speed(target_speed)\n        control = self._local_planner.run_step(debug=debug)\n\n        return control\n\n    def emergency_stop(self):\n        \"\"\"\n        Overwrites the throttle a brake values of a control to perform an emergency stop.\n        The steering is kept the same to avoid going out of the lane when stopping during turns\n\n            :param speed (carl.VehicleControl): control to be modified\n        \"\"\"\n        control = carla.VehicleControl()\n        control.throttle = 0.0\n        control.brake = self._max_brake\n        control.hand_brake = False\n        return control"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/behavior_types.py",
    "content": "# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" This module contains the different parameters sets for each behavior. \"\"\"\n\n\nclass Cautious(object):\n    \"\"\"Class for Cautious agent.\"\"\"\n    max_speed = 40\n    speed_lim_dist = 6\n    speed_decrease = 12\n    safety_time = 3\n    min_proximity_threshold = 12\n    braking_distance = 6\n    tailgate_counter = 0\n\n\nclass Normal(object):\n    \"\"\"Class for Normal agent.\"\"\"\n    max_speed = 50\n    speed_lim_dist = 3\n    speed_decrease = 10\n    safety_time = 3\n    min_proximity_threshold = 10\n    braking_distance = 5\n    tailgate_counter = 0\n\n\nclass Aggressive(object):\n    \"\"\"Class for Aggressive agent.\"\"\"\n    max_speed = 70\n    speed_lim_dist = 1\n    speed_decrease = 8\n    safety_time = 3\n    min_proximity_threshold = 8\n    braking_distance = 4\n    tailgate_counter = -1\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/controller.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" This module contains PID controllers to perform lateral and longitudinal control. \"\"\"\n\nfrom collections import deque\nimport math\nimport numpy as np\nimport carla\nfrom agents.tools.misc import get_speed\n\n\nclass VehiclePIDController():\n    \"\"\"\n    VehiclePIDController is the combination of two PID controllers\n    (lateral and longitudinal) to perform the\n    low level control a vehicle from client side\n    \"\"\"\n\n\n    def __init__(self, vehicle, args_lateral, args_longitudinal, offset=0, max_throttle=0.75, max_brake=0.3,\n                 max_steering=0.8):\n        \"\"\"\n        Constructor method.\n\n        :param vehicle: actor to apply to local planner logic onto\n        :param args_lateral: dictionary of arguments to set the lateral PID controller\n        using the following semantics:\n            K_P -- Proportional term\n            K_D -- Differential term\n            K_I -- Integral term\n        :param args_longitudinal: dictionary of arguments to set the longitudinal\n        PID controller using the following semantics:\n            K_P -- Proportional term\n            K_D -- Differential term\n            K_I -- Integral term\n        :param offset: If different than zero, the vehicle will drive displaced from the center line.\n        Positive values imply a right offset while negative ones mean a left one. Numbers high enough\n        to cause the vehicle to drive through other lanes might break the controller.\n        \"\"\"\n\n        self.max_brake = max_brake\n        self.max_throt = max_throttle\n        self.max_steer = max_steering\n\n        self._vehicle = vehicle\n        self._world = self._vehicle.get_world()\n        self.past_steering = self._vehicle.get_control().steer\n        self._lon_controller = PIDLongitudinalController(self._vehicle, **args_longitudinal)\n        self._lat_controller = PIDLateralController(self._vehicle, offset, **args_lateral)\n\n    def run_step(self, target_speed, waypoint):\n        \"\"\"\n        Execute one step of control invoking both lateral and longitudinal\n        PID controllers to reach a target waypoint\n        at a given target_speed.\n\n            :param target_speed: desired vehicle speed\n            :param waypoint: target location encoded as a waypoint\n            :return: distance (in meters) to the waypoint\n        \"\"\"\n\n        acceleration = self._lon_controller.run_step(target_speed)\n        current_steering = self._lat_controller.run_step(waypoint)\n        control = carla.VehicleControl()\n        if acceleration >= 0.0:\n            control.throttle = min(acceleration, self.max_throt)\n            control.brake = 0.0\n        else:\n            control.throttle = 0.0\n            control.brake = min(abs(acceleration), self.max_brake)\n\n        # Steering regulation: changes cannot happen abruptly, can't steer too much.\n\n        if current_steering > self.past_steering + 0.1:\n            current_steering = self.past_steering + 0.1\n        elif current_steering < self.past_steering - 0.1:\n            current_steering = self.past_steering - 0.1\n\n        if current_steering >= 0:\n            steering = min(self.max_steer, current_steering)\n        else:\n            steering = max(-self.max_steer, current_steering)\n\n        control.steer = steering\n        control.hand_brake = False\n        control.manual_gear_shift = False\n        self.past_steering = steering\n\n        return control\n\n\n    def change_longitudinal_PID(self, args_longitudinal):\n        \"\"\"Changes the parameters of the PIDLongitudinalController\"\"\"\n        self._lon_controller.change_parameters(**args_longitudinal)\n\n    def change_lateral_PID(self, args_lateral):\n        \"\"\"Changes the parameters of the PIDLongitudinalController\"\"\"\n        self._lon_controller.change_parameters(**args_lateral)\n\n\nclass PIDLongitudinalController():\n    \"\"\"\n    PIDLongitudinalController implements longitudinal control using a PID.\n    \"\"\"\n\n    def __init__(self, vehicle, K_P=1.0, K_I=0.0, K_D=0.0, dt=0.03):\n        \"\"\"\n        Constructor method.\n\n            :param vehicle: actor to apply to local planner logic onto\n            :param K_P: Proportional term\n            :param K_D: Differential term\n            :param K_I: Integral term\n            :param dt: time differential in seconds\n        \"\"\"\n        self._vehicle = vehicle\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt\n        self._error_buffer = deque(maxlen=10)\n\n    def run_step(self, target_speed, debug=False):\n        \"\"\"\n        Execute one step of longitudinal control to reach a given target speed.\n\n            :param target_speed: target speed in Km/h\n            :param debug: boolean for debugging\n            :return: throttle control\n        \"\"\"\n        current_speed = get_speed(self._vehicle)\n\n        if debug:\n            print('Current speed = {}'.format(current_speed))\n\n        return self._pid_control(target_speed, current_speed)\n\n    def _pid_control(self, target_speed, current_speed):\n        \"\"\"\n        Estimate the throttle/brake of the vehicle based on the PID equations\n\n            :param target_speed:  target speed in Km/h\n            :param current_speed: current speed of the vehicle in Km/h\n            :return: throttle/brake control\n        \"\"\"\n\n        error = target_speed - current_speed\n        self._error_buffer.append(error)\n\n        if len(self._error_buffer) >= 2:\n            _de = (self._error_buffer[-1] - self._error_buffer[-2]) / self._dt\n            _ie = sum(self._error_buffer) * self._dt\n        else:\n            _de = 0.0\n            _ie = 0.0\n\n        return np.clip((self._k_p * error) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0)\n\n    def change_parameters(self, K_P, K_I, K_D, dt):\n        \"\"\"Changes the PID parameters\"\"\"\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt\n\n\nclass PIDLateralController():\n    \"\"\"\n    PIDLateralController implements lateral control using a PID.\n    \"\"\"\n\n    def __init__(self, vehicle, offset=0, K_P=1.0, K_I=0.0, K_D=0.0, dt=0.03):\n        \"\"\"\n        Constructor method.\n\n            :param vehicle: actor to apply to local planner logic onto\n            :param offset: distance to the center line. If might cause issues if the value\n                is large enough to make the vehicle invade other lanes.\n            :param K_P: Proportional term\n            :param K_D: Differential term\n            :param K_I: Integral term\n            :param dt: time differential in seconds\n        \"\"\"\n        self._vehicle = vehicle\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt\n        self._offset = offset\n        self._e_buffer = deque(maxlen=10)\n\n    def run_step(self, waypoint):\n        \"\"\"\n        Execute one step of lateral control to steer\n        the vehicle towards a certain waypoin.\n\n            :param waypoint: target waypoint\n            :return: steering control in the range [-1, 1] where:\n            -1 maximum steering to left\n            +1 maximum steering to right\n        \"\"\"\n        return self._pid_control(waypoint, self._vehicle.get_transform())\n\n    def _pid_control(self, waypoint, vehicle_transform):\n        \"\"\"\n        Estimate the steering angle of the vehicle based on the PID equations\n\n            :param waypoint: target waypoint\n            :param vehicle_transform: current transform of the vehicle\n            :return: steering control in the range [-1, 1]\n        \"\"\"\n        # Get the ego's location and forward vector\n        ego_loc = vehicle_transform.location\n        v_vec = vehicle_transform.get_forward_vector()\n        v_vec = np.array([v_vec.x, v_vec.y, 0.0])\n\n        # Get the vector vehicle-target_wp\n        if self._offset != 0:\n            # Displace the wp to the side\n            w_tran = waypoint.transform\n            r_vec = w_tran.get_right_vector()\n            w_loc = w_tran.location + carla.Location(x=self._offset*r_vec.x,\n                                                         y=self._offset*r_vec.y)\n        else:\n            w_loc = waypoint.transform.location\n\n        w_vec = np.array([w_loc.x - ego_loc.x,\n                          w_loc.y - ego_loc.y,\n                          0.0])\n\n        wv_linalg = np.linalg.norm(w_vec) * np.linalg.norm(v_vec)\n        if wv_linalg == 0:\n            _dot = 1\n        else:\n            _dot = math.acos(np.clip(np.dot(w_vec, v_vec) / (wv_linalg), -1.0, 1.0))\n        _cross = np.cross(v_vec, w_vec)\n        if _cross[2] < 0:\n            _dot *= -1.0\n\n        self._e_buffer.append(_dot)\n        if len(self._e_buffer) >= 2:\n            _de = (self._e_buffer[-1] - self._e_buffer[-2]) / self._dt\n            _ie = sum(self._e_buffer) * self._dt\n        else:\n            _de = 0.0\n            _ie = 0.0\n\n        return np.clip((self._k_p * _dot) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0)\n\n    def change_parameters(self, K_P, K_I, K_D, dt):\n        \"\"\"Changes the PID parameters\"\"\"\n        self._k_p = K_P\n        self._k_i = K_I\n        self._k_d = K_D\n        self._dt = dt"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\n\"\"\"\nThis module provides GlobalRoutePlanner implementation.\n\"\"\"\n\nimport math\nimport numpy as np\nimport networkx as nx\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\nfrom agents.tools.misc import vector\n\nclass GlobalRoutePlanner(object):\n    \"\"\"\n    This class provides a very high level route plan.\n    \"\"\"\n\n    def __init__(self, wmap, sampling_resolution):\n        self._sampling_resolution = sampling_resolution\n        self._wmap = wmap\n        self._topology = None\n        self._graph = None\n        self._id_map = None\n        self._road_id_to_edge = None\n\n        self._intersection_end_node = -1\n        self._previous_decision = RoadOption.VOID\n\n        # Build the graph\n        self._build_topology()\n        self._build_graph()\n        self._find_loose_ends()\n        self._lane_change_link()\n\n    def trace_route(self, origin, destination):\n        \"\"\"\n        This method returns list of (carla.Waypoint, RoadOption)\n        from origin to destination\n        \"\"\"\n        route_trace = []\n        route = self._path_search(origin, destination)\n        current_waypoint = self._wmap.get_waypoint(origin)\n        destination_waypoint = self._wmap.get_waypoint(destination)\n\n        for i in range(len(route) - 1):\n            road_option = self._turn_decision(i, route)\n            edge = self._graph.edges[route[i], route[i+1]]\n            path = []\n\n            if edge['type'] != RoadOption.LANEFOLLOW and edge['type'] != RoadOption.VOID:\n                route_trace.append((current_waypoint, road_option))\n                exit_wp = edge['exit_waypoint']\n                n1, n2 = self._road_id_to_edge[exit_wp.road_id][exit_wp.section_id][exit_wp.lane_id]\n                next_edge = self._graph.edges[n1, n2]\n                if next_edge['path']:\n                    closest_index = self._find_closest_in_list(current_waypoint, next_edge['path'])\n                    closest_index = min(len(next_edge['path'])-1, closest_index+5)\n                    current_waypoint = next_edge['path'][closest_index]\n                else:\n                    current_waypoint = next_edge['exit_waypoint']\n                route_trace.append((current_waypoint, road_option))\n\n            else:\n                path = path + [edge['entry_waypoint']] + edge['path'] + [edge['exit_waypoint']]\n                closest_index = self._find_closest_in_list(current_waypoint, path)\n                for waypoint in path[closest_index:]:\n                    current_waypoint = waypoint\n                    route_trace.append((current_waypoint, road_option))\n                    if len(route)-i <= 2 and waypoint.transform.location.distance(destination) < 2*self._sampling_resolution:\n                        break\n                    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:\n                        destination_index = self._find_closest_in_list(destination_waypoint, path)\n                        if closest_index > destination_index:\n                            break\n\n        return route_trace\n\n    def _build_topology(self):\n        \"\"\"\n        This function retrieves topology from the server as a list of\n        road segments as pairs of waypoint objects, and processes the\n        topology into a list of dictionary objects with the following attributes\n\n        - entry (carla.Waypoint): waypoint of entry point of road segment\n        - entryxyz (tuple): (x,y,z) of entry point of road segment\n        - exit (carla.Waypoint): waypoint of exit point of road segment\n        - exitxyz (tuple): (x,y,z) of exit point of road segment\n        - path (list of carla.Waypoint):  list of waypoints between entry to exit, separated by the resolution\n        \"\"\"\n        self._topology = []\n        # Retrieving waypoints to construct a detailed topology\n        for segment in self._wmap.get_topology():\n            wp1, wp2 = segment[0], segment[1]\n            l1, l2 = wp1.transform.location, wp2.transform.location\n            # Rounding off to avoid floating point imprecision\n            x1, y1, z1, x2, y2, z2 = np.round([l1.x, l1.y, l1.z, l2.x, l2.y, l2.z], 0)\n            wp1.transform.location, wp2.transform.location = l1, l2\n            seg_dict = dict()\n            seg_dict['entry'], seg_dict['exit'] = wp1, wp2\n            seg_dict['entryxyz'], seg_dict['exitxyz'] = (x1, y1, z1), (x2, y2, z2)\n            seg_dict['path'] = []\n            endloc = wp2.transform.location\n            if wp1.transform.location.distance(endloc) > self._sampling_resolution:\n                w = wp1.next(self._sampling_resolution)[0]\n                while w.transform.location.distance(endloc) > self._sampling_resolution:\n                    seg_dict['path'].append(w)\n                    w = w.next(self._sampling_resolution)[0]\n            else:\n                seg_dict['path'].append(wp1.next(self._sampling_resolution)[0])\n            self._topology.append(seg_dict)\n\n    def _build_graph(self):\n        \"\"\"\n        This function builds a networkx graph representation of topology, creating several class attributes:\n        - graph (networkx.DiGraph): networkx graph representing the world map, with:\n            Node properties:\n                vertex: (x,y,z) position in world map\n            Edge properties:\n                entry_vector: unit vector along tangent at entry point\n                exit_vector: unit vector along tangent at exit point\n                net_vector: unit vector of the chord from entry to exit\n                intersection: boolean indicating if the edge belongs to an  intersection\n        - id_map (dictionary): mapping from (x,y,z) to node id\n        - road_id_to_edge (dictionary): map from road id to edge in the graph\n        \"\"\"\n\n        self._graph = nx.DiGraph()\n        self._id_map = dict()  # Map with structure {(x,y,z): id, ... }\n        self._road_id_to_edge = dict()  # Map with structure {road_id: {lane_id: edge, ... }, ... }\n\n        for segment in self._topology:\n            entry_xyz, exit_xyz = segment['entryxyz'], segment['exitxyz']\n            path = segment['path']\n            entry_wp, exit_wp = segment['entry'], segment['exit']\n            intersection = entry_wp.is_junction\n            road_id, section_id, lane_id = entry_wp.road_id, entry_wp.section_id, entry_wp.lane_id\n\n            for vertex in entry_xyz, exit_xyz:\n                # Adding unique nodes and populating id_map\n                if vertex not in self._id_map:\n                    new_id = len(self._id_map)\n                    self._id_map[vertex] = new_id\n                    self._graph.add_node(new_id, vertex=vertex)\n            n1 = self._id_map[entry_xyz]\n            n2 = self._id_map[exit_xyz]\n            if road_id not in self._road_id_to_edge:\n                self._road_id_to_edge[road_id] = dict()\n            if section_id not in self._road_id_to_edge[road_id]:\n                self._road_id_to_edge[road_id][section_id] = dict()\n            self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2)\n\n            entry_carla_vector = entry_wp.transform.rotation.get_forward_vector()\n            exit_carla_vector = exit_wp.transform.rotation.get_forward_vector()\n\n            # Adding edge with attributes\n            self._graph.add_edge(\n                n1, n2,\n                length=len(path) + 1, path=path,\n                entry_waypoint=entry_wp, exit_waypoint=exit_wp,\n                entry_vector=np.array(\n                    [entry_carla_vector.x, entry_carla_vector.y, entry_carla_vector.z]),\n                exit_vector=np.array(\n                    [exit_carla_vector.x, exit_carla_vector.y, exit_carla_vector.z]),\n                net_vector=vector(entry_wp.transform.location, exit_wp.transform.location),\n                intersection=intersection, type=RoadOption.LANEFOLLOW)\n\n    def _find_loose_ends(self):\n        \"\"\"\n        This method finds road segments that have an unconnected end, and\n        adds them to the internal graph representation\n        \"\"\"\n        count_loose_ends = 0\n        hop_resolution = self._sampling_resolution\n        for segment in self._topology:\n            end_wp = segment['exit']\n            exit_xyz = segment['exitxyz']\n            road_id, section_id, lane_id = end_wp.road_id, end_wp.section_id, end_wp.lane_id\n            if road_id in self._road_id_to_edge \\\n                    and section_id in self._road_id_to_edge[road_id] \\\n                    and lane_id in self._road_id_to_edge[road_id][section_id]:\n                pass\n            else:\n                count_loose_ends += 1\n                if road_id not in self._road_id_to_edge:\n                    self._road_id_to_edge[road_id] = dict()\n                if section_id not in self._road_id_to_edge[road_id]:\n                    self._road_id_to_edge[road_id][section_id] = dict()\n                n1 = self._id_map[exit_xyz]\n                n2 = -1*count_loose_ends\n                self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2)\n                next_wp = end_wp.next(hop_resolution)\n                path = []\n                while next_wp is not None and next_wp \\\n                        and next_wp[0].road_id == road_id \\\n                        and next_wp[0].section_id == section_id \\\n                        and next_wp[0].lane_id == lane_id:\n                    path.append(next_wp[0])\n                    next_wp = next_wp[0].next(hop_resolution)\n                if path:\n                    n2_xyz = (path[-1].transform.location.x,\n                              path[-1].transform.location.y,\n                              path[-1].transform.location.z)\n                    self._graph.add_node(n2, vertex=n2_xyz)\n                    self._graph.add_edge(\n                        n1, n2,\n                        length=len(path) + 1, path=path,\n                        entry_waypoint=end_wp, exit_waypoint=path[-1],\n                        entry_vector=None, exit_vector=None, net_vector=None,\n                        intersection=end_wp.is_junction, type=RoadOption.LANEFOLLOW)\n\n    def _lane_change_link(self):\n        \"\"\"\n        This method places zero cost links in the topology graph\n        representing availability of lane changes.\n        \"\"\"\n\n        for segment in self._topology:\n            left_found, right_found = False, False\n\n            for waypoint in segment['path']:\n                if not segment['entry'].is_junction:\n                    next_waypoint, next_road_option, next_segment = None, None, None\n\n                    if waypoint.right_lane_marking.lane_change & carla.LaneChange.Right and not right_found:\n                        next_waypoint = waypoint.get_right_lane()\n                        if next_waypoint is not None \\\n                                and next_waypoint.lane_type == carla.LaneType.Driving \\\n                                and waypoint.road_id == next_waypoint.road_id:\n                            next_road_option = RoadOption.CHANGELANERIGHT\n                            next_segment = self._localize(next_waypoint.transform.location)\n                            if next_segment is not None:\n                                self._graph.add_edge(\n                                    self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint,\n                                    exit_waypoint=next_waypoint, intersection=False, exit_vector=None,\n                                    path=[], length=0, type=next_road_option, change_waypoint=next_waypoint)\n                                right_found = True\n                    if waypoint.left_lane_marking.lane_change & carla.LaneChange.Left and not left_found:\n                        next_waypoint = waypoint.get_left_lane()\n                        if next_waypoint is not None \\\n                                and next_waypoint.lane_type == carla.LaneType.Driving \\\n                                and waypoint.road_id == next_waypoint.road_id:\n                            next_road_option = RoadOption.CHANGELANELEFT\n                            next_segment = self._localize(next_waypoint.transform.location)\n                            if next_segment is not None:\n                                self._graph.add_edge(\n                                    self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint,\n                                    exit_waypoint=next_waypoint, intersection=False, exit_vector=None,\n                                    path=[], length=0, type=next_road_option, change_waypoint=next_waypoint)\n                                left_found = True\n                if left_found and right_found:\n                    break\n\n    def _localize(self, location):\n        \"\"\"\n        This function finds the road segment that a given location\n        is part of, returning the edge it belongs to\n        \"\"\"\n        waypoint = self._wmap.get_waypoint(location)\n        edge = None\n        try:\n            edge = self._road_id_to_edge[waypoint.road_id][waypoint.section_id][waypoint.lane_id]\n        except KeyError:\n            pass\n        return edge\n\n    def _distance_heuristic(self, n1, n2):\n        \"\"\"\n        Distance heuristic calculator for path searching\n        in self._graph\n        \"\"\"\n        l1 = np.array(self._graph.nodes[n1]['vertex'])\n        l2 = np.array(self._graph.nodes[n2]['vertex'])\n        return np.linalg.norm(l1-l2)\n\n    def _path_search(self, origin, destination):\n        \"\"\"\n        This function finds the shortest path connecting origin and destination\n        using A* search with distance heuristic.\n        origin      :   carla.Location object of start position\n        destination :   carla.Location object of of end position\n        return      :   path as list of node ids (as int) of the graph self._graph\n        connecting origin and destination\n        \"\"\"\n        start, end = self._localize(origin), self._localize(destination)\n\n        route = nx.astar_path(\n            self._graph, source=start[0], target=end[0],\n            heuristic=self._distance_heuristic, weight='length')\n        route.append(end[1])\n        return route\n\n    def _successive_last_intersection_edge(self, index, route):\n        \"\"\"\n        This method returns the last successive intersection edge\n        from a starting index on the route.\n        This helps moving past tiny intersection edges to calculate\n        proper turn decisions.\n        \"\"\"\n\n        last_intersection_edge = None\n        last_node = None\n        for node1, node2 in [(route[i], route[i+1]) for i in range(index, len(route)-1)]:\n            candidate_edge = self._graph.edges[node1, node2]\n            if node1 == route[index]:\n                last_intersection_edge = candidate_edge\n            if candidate_edge['type'] == RoadOption.LANEFOLLOW and candidate_edge['intersection']:\n                last_intersection_edge = candidate_edge\n                last_node = node2\n            else:\n                break\n\n        return last_node, last_intersection_edge\n\n    def _turn_decision(self, index, route, threshold=math.radians(35)):\n        \"\"\"\n        This method returns the turn decision (RoadOption) for pair of edges\n        around current index of route list\n        \"\"\"\n\n        decision = None\n        previous_node = route[index-1]\n        current_node = route[index]\n        next_node = route[index+1]\n        next_edge = self._graph.edges[current_node, next_node]\n        if index > 0:\n            if self._previous_decision != RoadOption.VOID \\\n                    and self._intersection_end_node > 0 \\\n                    and self._intersection_end_node != previous_node \\\n                    and next_edge['type'] == RoadOption.LANEFOLLOW \\\n                    and next_edge['intersection']:\n                decision = self._previous_decision\n            else:\n                self._intersection_end_node = -1\n                current_edge = self._graph.edges[previous_node, current_node]\n                calculate_turn = current_edge['type'] == RoadOption.LANEFOLLOW and not current_edge[\n                    'intersection'] and next_edge['type'] == RoadOption.LANEFOLLOW and next_edge['intersection']\n                if calculate_turn:\n                    last_node, tail_edge = self._successive_last_intersection_edge(index, route)\n                    self._intersection_end_node = last_node\n                    if tail_edge is not None:\n                        next_edge = tail_edge\n                    cv, nv = current_edge['exit_vector'], next_edge['exit_vector']\n                    if cv is None or nv is None:\n                        return next_edge['type']\n                    cross_list = []\n                    for neighbor in self._graph.successors(current_node):\n                        select_edge = self._graph.edges[current_node, neighbor]\n                        if select_edge['type'] == RoadOption.LANEFOLLOW:\n                            if neighbor != route[index+1]:\n                                sv = select_edge['net_vector']\n                                cross_list.append(np.cross(cv, sv)[2])\n                    next_cross = np.cross(cv, nv)[2]\n                    deviation = math.acos(np.clip(\n                        np.dot(cv, nv)/(np.linalg.norm(cv)*np.linalg.norm(nv)), -1.0, 1.0))\n                    if not cross_list:\n                        cross_list.append(0)\n                    if deviation < threshold:\n                        decision = RoadOption.STRAIGHT\n                    elif cross_list and next_cross < min(cross_list):\n                        decision = RoadOption.LEFT\n                    elif cross_list and next_cross > max(cross_list):\n                        decision = RoadOption.RIGHT\n                    elif next_cross < 0:\n                        decision = RoadOption.LEFT\n                    elif next_cross > 0:\n                        decision = RoadOption.RIGHT\n                else:\n                    decision = next_edge['type']\n\n        else:\n            decision = next_edge['type']\n\n        self._previous_decision = decision\n        return decision\n\n    def _find_closest_in_list(self, current_waypoint, waypoint_list):\n        min_distance = float('inf')\n        closest_index = -1\n        for i, waypoint in enumerate(waypoint_list):\n            distance = waypoint.transform.location.distance(\n                current_waypoint.transform.location)\n            if distance < min_distance:\n                min_distance = distance\n                closest_index = i\n\n        return closest_index\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/navigation/local_planner.py",
    "content": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" This module contains a local planner to perform low-level waypoint following based on PID controllers. \"\"\"\n\nfrom enum import Enum\nfrom collections import deque\nimport random\n\nimport carla\nfrom agents.navigation.controller import VehiclePIDController\nfrom agents.tools.misc import draw_waypoints, get_speed\n\n\nclass RoadOption(Enum):\n    \"\"\"\n    RoadOption represents the possible topological configurations when moving from a segment of lane to other.\n\n    \"\"\"\n    VOID = -1\n    LEFT = 1\n    RIGHT = 2\n    STRAIGHT = 3\n    LANEFOLLOW = 4\n    CHANGELANELEFT = 5\n    CHANGELANERIGHT = 6\n\n\nclass LocalPlanner(object):\n    \"\"\"\n    LocalPlanner implements the basic behavior of following a\n    trajectory of waypoints that is generated on-the-fly.\n\n    The low-level motion of the vehicle is computed by using two PID controllers,\n    one is used for the lateral control and the other for the longitudinal control (cruise speed).\n\n    When multiple paths are available (intersections) this local planner makes a random choice,\n    unless a given global plan has already been specified.\n    \"\"\"\n\n    def __init__(self, vehicle, opt_dict={}):\n        \"\"\"\n        :param vehicle: actor to apply to local planner logic onto\n        :param opt_dict: dictionary of arguments with different parameters:\n            dt: time between simulation steps\n            target_speed: desired cruise speed in Km/h\n            sampling_radius: distance between the waypoints part of the plan\n            lateral_control_dict: values of the lateral PID controller\n            longitudinal_control_dict: values of the longitudinal PID controller\n            max_throttle: maximum throttle applied to the vehicle\n            max_brake: maximum brake applied to the vehicle\n            max_steering: maximum steering applied to the vehicle\n            offset: distance between the route waypoints and the center of the lane\n        \"\"\"\n        self._vehicle = vehicle\n        self._world = self._vehicle.get_world()\n        self._map = self._world.get_map()\n\n        self._vehicle_controller = None\n        self.target_waypoint = None\n        self.target_road_option = None\n\n        self._waypoints_queue = deque(maxlen=10000)\n        self._min_waypoint_queue_length = 100\n        self._stop_waypoint_creation = False\n\n        # Base parameters\n        self._dt = 1.0 / 20.0\n        self._target_speed = 20.0  # Km/h\n        self._sampling_radius = 2.0\n        self._args_lateral_dict = {'K_P': 1.95, 'K_I': 0.05, 'K_D': 0.2, 'dt': self._dt}\n        self._args_longitudinal_dict = {'K_P': 1.0, 'K_I': 0.05, 'K_D': 0, 'dt': self._dt}\n        self._max_throt = 0.75\n        self._max_brake = 0.3\n        self._max_steer = 0.8\n        self._offset = 0\n        self._base_min_distance = 3.0\n        self._follow_speed_limits = False\n\n        # Overload parameters\n        if opt_dict:\n            if 'dt' in opt_dict:\n                self._dt = opt_dict['dt']\n            if 'target_speed' in opt_dict:\n                self._target_speed = opt_dict['target_speed']\n            if 'sampling_radius' in opt_dict:\n                self._sampling_radius = opt_dict['sampling_radius']\n            if 'lateral_control_dict' in opt_dict:\n                self._args_lateral_dict = opt_dict['lateral_control_dict']\n            if 'longitudinal_control_dict' in opt_dict:\n                self._args_longitudinal_dict = opt_dict['longitudinal_control_dict']\n            if 'max_throttle' in opt_dict:\n                self._max_throt = opt_dict['max_throttle']\n            if 'max_brake' in opt_dict:\n                self._max_brake = opt_dict['max_brake']\n            if 'max_steering' in opt_dict:\n                self._max_steer = opt_dict['max_steering']\n            if 'offset' in opt_dict:\n                self._offset = opt_dict['offset']\n            if 'base_min_distance' in opt_dict:\n                self._base_min_distance = opt_dict['base_min_distance']\n            if 'follow_speed_limits' in opt_dict:\n                self._follow_speed_limits = opt_dict['follow_speed_limits']\n\n        # initializing controller\n        self._init_controller()\n\n    def reset_vehicle(self):\n        \"\"\"Reset the ego-vehicle\"\"\"\n        self._vehicle = None\n\n    def _init_controller(self):\n        \"\"\"Controller initialization\"\"\"\n        self._vehicle_controller = VehiclePIDController(self._vehicle,\n                                                        args_lateral=self._args_lateral_dict,\n                                                        args_longitudinal=self._args_longitudinal_dict,\n                                                        offset=self._offset,\n                                                        max_throttle=self._max_throt,\n                                                        max_brake=self._max_brake,\n                                                        max_steering=self._max_steer)\n\n        # Compute the current vehicle waypoint\n        current_waypoint = self._map.get_waypoint(self._vehicle.get_location())\n        self.target_waypoint, self.target_road_option = (current_waypoint, RoadOption.LANEFOLLOW)\n        self._waypoints_queue.append((self.target_waypoint, self.target_road_option))\n\n    def set_speed(self, speed):\n        \"\"\"\n        Changes the target speed\n\n        :param speed: new target speed in Km/h\n        :return:\n        \"\"\"\n        if self._follow_speed_limits:\n            print(\"WARNING: The max speed is currently set to follow the speed limits. \"\n                  \"Use 'follow_speed_limits' to deactivate this\")\n        self._target_speed = speed\n\n    def follow_speed_limits(self, value=True):\n        \"\"\"\n        Activates a flag that makes the max speed dynamically vary according to the spped limits\n\n        :param value: bool\n        :return:\n        \"\"\"\n        self._follow_speed_limits = value\n\n    def _compute_next_waypoints(self, k=1):\n        \"\"\"\n        Add new waypoints to the trajectory queue.\n\n        :param k: how many waypoints to compute\n        :return:\n        \"\"\"\n        # check we do not overflow the queue\n        available_entries = self._waypoints_queue.maxlen - len(self._waypoints_queue)\n        k = min(available_entries, k)\n\n        for _ in range(k):\n            last_waypoint = self._waypoints_queue[-1][0]\n            next_waypoints = list(last_waypoint.next(self._sampling_radius))\n\n            if len(next_waypoints) == 0:\n                break\n            elif len(next_waypoints) == 1:\n                # only one option available ==> lanefollowing\n                next_waypoint = next_waypoints[0]\n                road_option = RoadOption.LANEFOLLOW\n            else:\n                # random choice between the possible options\n                road_options_list = _retrieve_options(\n                    next_waypoints, last_waypoint)\n                road_option = random.choice(road_options_list)\n                next_waypoint = next_waypoints[road_options_list.index(\n                    road_option)]\n\n            self._waypoints_queue.append((next_waypoint, road_option))\n\n    def set_global_plan(self, current_plan, stop_waypoint_creation=True, clean_queue=True):\n        \"\"\"\n        Adds a new plan to the local planner. A plan must be a list of [carla.Waypoint, RoadOption] pairs\n        If 'clean_queue`, erases the previous plan, and if not, it is added to the old one\n        The 'stop_waypoint_creation' flag avoids creating more random waypoints\n\n        :param current_plan: list of (carla.Waypoint, RoadOption)\n        :param stop_waypoint_creation: bool\n        :param ceal_queue: bool\n        :return:\n        \"\"\"\n        if clean_queue:\n            self._waypoints_queue.clear()\n\n        # Remake the waypoints queue if the new plan has a higher length than the queue\n        new_plan_length = len(current_plan) + len(self._waypoints_queue)\n        if new_plan_length > self._waypoints_queue.maxlen:\n            new_waypoint_queue = deque(maxlen=new_plan_length)\n            for wp in self._waypoints_queue:\n                new_waypoint_queue.append(wp)\n            self._waypoints_queue = new_waypoint_queue\n\n        for elem in current_plan:\n            self._waypoints_queue.append(elem)\n\n        self._stop_waypoint_creation = stop_waypoint_creation\n\n    def run_step(self, debug=False):\n        \"\"\"\n        Execute one step of local planning which involves running the longitudinal and lateral PID controllers to\n        follow the waypoints trajectory.\n\n        :param debug: boolean flag to activate waypoints debugging\n        :return: control to be applied\n        \"\"\"\n        if self._follow_speed_limits:\n            self._target_speed = self._vehicle.get_speed_limit()\n\n        # Add more waypoints too few in the horizon\n        if not self._stop_waypoint_creation and len(self._waypoints_queue) < self._min_waypoint_queue_length:\n            self._compute_next_waypoints(k=self._min_waypoint_queue_length)\n\n        # Purge the queue of obsolete waypoints\n        veh_location = self._vehicle.get_location()\n        vehicle_speed = get_speed(self._vehicle) / 3.6\n        self._min_distance = self._base_min_distance + 0.5 *vehicle_speed\n\n        num_waypoint_removed = 0\n        for waypoint, _ in self._waypoints_queue:\n\n            if len(self._waypoints_queue) - num_waypoint_removed == 1:\n                min_distance = 1  # Don't remove the last waypoint until very close by\n            else:\n                min_distance = self._min_distance\n\n            if veh_location.distance(waypoint.transform.location) < min_distance:\n                num_waypoint_removed += 1\n            else:\n                break\n\n        if num_waypoint_removed > 0:\n            for _ in range(num_waypoint_removed):\n                self._waypoints_queue.popleft()\n\n        # Get the target waypoint and move using the PID controllers. Stop if no target waypoint\n        if len(self._waypoints_queue) == 0:\n            control = carla.VehicleControl()\n            control.steer = 0.0\n            control.throttle = 0.0\n            control.brake = 1.0\n            control.hand_brake = False\n            control.manual_gear_shift = False\n        else:\n            self.target_waypoint, self.target_road_option = self._waypoints_queue[0]\n            control = self._vehicle_controller.run_step(self._target_speed, self.target_waypoint)\n\n        if debug:\n            draw_waypoints(self._vehicle.get_world(), [self.target_waypoint], 1.0)\n\n        return control\n\n    def get_incoming_waypoint_and_direction(self, steps=3):\n        \"\"\"\n        Returns direction and waypoint at a distance ahead defined by the user.\n\n            :param steps: number of steps to get the incoming waypoint.\n        \"\"\"\n        if len(self._waypoints_queue) > steps:\n            return self._waypoints_queue[steps]\n\n        else:\n            try:\n                wpt, direction = self._waypoints_queue[-1]\n                return wpt, direction\n            except IndexError as i:\n                return None, RoadOption.VOID\n\n    def done(self):\n        \"\"\"\n        Returns whether or not the planner has finished\n\n        :return: boolean\n        \"\"\"\n        return len(self._waypoints_queue) == 0\n\n\ndef _retrieve_options(list_waypoints, current_waypoint):\n    \"\"\"\n    Compute the type of connection between the current active waypoint and the multiple waypoints present in\n    list_waypoints. The result is encoded as a list of RoadOption enums.\n\n    :param list_waypoints: list with the possible target waypoints in case of multiple options\n    :param current_waypoint: current active waypoint\n    :return: list of RoadOption enums representing the type of connection from the active waypoint to each\n             candidate in list_waypoints\n    \"\"\"\n    options = []\n    for next_waypoint in list_waypoints:\n        # this is needed because something we are linking to\n        # the beggining of an intersection, therefore the\n        # variation in angle is small\n        next_next_waypoint = next_waypoint.next(3.0)[0]\n        link = _compute_connection(current_waypoint, next_next_waypoint)\n        options.append(link)\n\n    return options\n\n\ndef _compute_connection(current_waypoint, next_waypoint, threshold=35):\n    \"\"\"\n    Compute the type of topological connection between an active waypoint (current_waypoint) and a target waypoint\n    (next_waypoint).\n\n    :param current_waypoint: active waypoint\n    :param next_waypoint: target waypoint\n    :return: the type of topological connection encoded as a RoadOption enum:\n             RoadOption.STRAIGHT\n             RoadOption.LEFT\n             RoadOption.RIGHT\n    \"\"\"\n    n = next_waypoint.transform.rotation.yaw\n    n = n % 360.0\n\n    c = current_waypoint.transform.rotation.yaw\n    c = c % 360.0\n\n    diff_angle = (n - c) % 180.0\n    if diff_angle < threshold or diff_angle > (180 - threshold):\n        return RoadOption.STRAIGHT\n    elif diff_angle > 90.0:\n        return RoadOption.LEFT\n    else:\n        return RoadOption.RIGHT\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/agents/tools/misc.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2018 Intel Labs.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\" Module with auxiliary functions. \"\"\"\n\nimport math\nimport numpy as np\nimport carla\n\ndef draw_waypoints(world, waypoints, z=0.5):\n    \"\"\"\n    Draw a list of waypoints at a certain height given in z.\n\n        :param world: carla.world object\n        :param waypoints: list or iterable container with the waypoints to draw\n        :param z: height in meters\n    \"\"\"\n    for wpt in waypoints:\n        wpt_t = wpt.transform\n        begin = wpt_t.location + carla.Location(z=z)\n        angle = math.radians(wpt_t.rotation.yaw)\n        end = begin + carla.Location(x=math.cos(angle), y=math.sin(angle))\n        world.debug.draw_arrow(begin, end, arrow_size=0.3, life_time=1.0)\n\n\ndef get_speed(vehicle):\n    \"\"\"\n    Compute speed of a vehicle in Km/h.\n\n        :param vehicle: the vehicle for which speed is calculated\n        :return: speed as a float in Km/h\n    \"\"\"\n    vel = vehicle.get_velocity()\n\n    return 3.6 * math.sqrt(vel.x ** 2 + vel.y ** 2 + vel.z ** 2)\n\ndef get_trafficlight_trigger_location(traffic_light):\n    \"\"\"\n    Calculates the yaw of the waypoint that represents the trigger volume of the traffic light\n    \"\"\"\n    def rotate_point(point, radians):\n        \"\"\"\n        rotate a given point by a given angle\n        \"\"\"\n        rotated_x = math.cos(radians) * point.x - math.sin(radians) * point.y\n        rotated_y = math.sin(radians) * point.x - math.cos(radians) * point.y\n\n        return carla.Vector3D(rotated_x, rotated_y, point.z)\n\n    base_transform = traffic_light.get_transform()\n    base_rot = base_transform.rotation.yaw\n    area_loc = base_transform.transform(traffic_light.trigger_volume.location)\n    area_ext = traffic_light.trigger_volume.extent\n\n    point = rotate_point(carla.Vector3D(0, 0, area_ext.z), math.radians(base_rot))\n    point_location = area_loc + carla.Location(x=point.x, y=point.y)\n\n    return carla.Location(point_location.x, point_location.y, point_location.z)\n\n\ndef is_within_distance(target_transform, reference_transform, max_distance, angle_interval=None):\n    \"\"\"\n    Check if a location is both within a certain distance from a reference object.\n    By using 'angle_interval', the angle between the location and reference transform\n    will also be tkaen into account, being 0 a location in front and 180, one behind.\n\n    :param target_transform: location of the target object\n    :param reference_transform: location of the reference object\n    :param max_distance: maximum allowed distance\n    :param angle_interval: only locations between [min, max] angles will be considered. This isn't checked by default.\n    :return: boolean\n    \"\"\"\n    target_vector = np.array([\n        target_transform.location.x - reference_transform.location.x,\n        target_transform.location.y - reference_transform.location.y\n    ])\n    norm_target = np.linalg.norm(target_vector)\n\n    # If the vector is too short, we can simply stop here\n    if norm_target < 0.001:\n        return True\n\n    # Further than the max distance\n    if norm_target > max_distance:\n        return False\n\n    # We don't care about the angle, nothing else to check\n    if not angle_interval:\n        return True\n\n    min_angle = angle_interval[0]\n    max_angle = angle_interval[1]\n\n    fwd = reference_transform.get_forward_vector()\n    forward_vector = np.array([fwd.x, fwd.y])\n    angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))\n\n    return min_angle < angle < max_angle\n\n\ndef compute_magnitude_angle(target_location, current_location, orientation):\n    \"\"\"\n    Compute relative angle and distance between a target_location and a current_location\n\n        :param target_location: location of the target object\n        :param current_location: location of the reference object\n        :param orientation: orientation of the reference object\n        :return: a tuple composed by the distance to the object and the angle between both objects\n    \"\"\"\n    target_vector = np.array([target_location.x - current_location.x, target_location.y - current_location.y])\n    norm_target = np.linalg.norm(target_vector)\n\n    forward_vector = np.array([math.cos(math.radians(orientation)), math.sin(math.radians(orientation))])\n    d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))\n\n    return (norm_target, d_angle)\n\n\ndef distance_vehicle(waypoint, vehicle_transform):\n    \"\"\"\n    Returns the 2D distance from a waypoint to a vehicle\n\n        :param waypoint: actual waypoint\n        :param vehicle_transform: transform of the target vehicle\n    \"\"\"\n    loc = vehicle_transform.location\n    x = waypoint.transform.location.x - loc.x\n    y = waypoint.transform.location.y - loc.y\n\n    return math.sqrt(x * x + y * y)\n\n\ndef vector(location_1, location_2):\n    \"\"\"\n    Returns the unit vector from location_1 to location_2\n\n        :param location_1, location_2: carla.Location objects\n    \"\"\"\n    x = location_2.x - location_1.x\n    y = location_2.y - location_1.y\n    z = location_2.z - location_1.z\n    norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps\n\n    return [x / norm, y / norm, z / norm]\n\n\ndef compute_distance(location_1, location_2):\n    \"\"\"\n    Euclidean distance between 3D points\n\n        :param location_1, location_2: 3D points\n    \"\"\"\n    x = location_2.x - location_1.x\n    y = location_2.y - location_1.y\n    z = location_2.z - location_1.z\n    norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps\n    return norm\n\n\ndef positive(num):\n    \"\"\"\n    Return the given number if positive, else 0\n\n        :param num: value to check\n    \"\"\"\n    return num if num > 0.0 else 0.0\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/carla_mocks/carla.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides mocked CARLA classes for unittesting\n\"\"\"\n\nimport copy\n\n\nclass command:\n    blueprint = None\n\n    def SpawnActor(blueprint, point):\n        new_command = command()\n        new_command.blueprint = copy.deepcopy(blueprint)\n        return new_command\n\n    def SetSimulatePhysics(blueprint, physics):\n        return None\n\n    def FutureActor():\n        return None\n\n    def ApplyTransform():\n        return None\n\n    def SetAutopilot(actor, autopilot, port):\n        return None\n\n    def SetVehicleLightState():\n        return None\n\n    def DestroyActor(actor):\n        return None\n\n    def then(self, other_command):\n        return self\n\n\nclass CarlaBluePrint(object):\n\n    def __init__(self):\n        self.id = 0\n        self.attributes = {'role_name': ''}\n\n    def has_attribute(self, attribute_string=''):\n        return attribute_string in self.attributes\n\n    def set_attribute(self, key, value):\n        self.attributes[key] = value\n\n    def has_tag(self, tag_string=''):\n        return False\n\n\nclass CarlaBluePrintLibrary:\n    def filter(self, filterstring):\n        return [CarlaBluePrint()]\n\n    def __len__(self):\n        return 1\n\n    def find(self, filterstring):\n        return CarlaBluePrint()\n\n\nclass GeoLocation:\n    longitude = 0\n    latitude = 0\n\n\nclass Vector3D:\n    x = 0\n    y = 0\n    z = 0\n\n    def __init__(self, x=0, y=0, z=0):\n        self.x = x\n        self.y = y\n        self.z = z\n\n\nclass Location():\n    x = 0\n    y = 0\n    z = 0\n\n    def __init__(self, x=0, y=0, z=0):\n        self.x = x\n        self.y = y\n        self.z = z\n\n    def distance(self, other):\n        return 0\n\n\nclass Rotation():\n    pitch = 0\n    roll = 0\n    yaw = 0\n\n    def __init__(self, pitch=0, roll=0, yaw=0):\n        self.pitch = pitch\n        self.roll = roll\n        self.yaw = yaw\n\n    def get_forward_vector(self):\n        return Vector3D()\n\n\nclass Transform:\n    location = Location(0, 0, 0)\n    rotation = Rotation(0, 0, 0)\n\n    def __init__(self, location=Location(0, 0, 0), rotation=Rotation(0, 0, 0)):\n        self.location = location\n        self.rotation = rotation\n\n\nclass Waypoint():\n    transform = Transform(Location(), Rotation())\n    road_id = 0\n    lane_id = 0\n    s = 0\n    lane_width = 0\n\n\nclass Map:\n    name = \"\"\n\n    def get_spawn_points(self):\n        return []\n\n    def transform_to_geolocation(self, transform):\n        return GeoLocation()\n\n    def get_waypoint(self, transform):\n        return Waypoint()\n\n    def get_waypoint_xodr(self, a, b, c):\n        return Waypoint()\n\n    def get_topology(self):\n        return []\n\n\nclass TrafficLightState:\n    Red = 0\n    Green = 1\n    Yellow = 2\n    Off = 3\n\n\nclass WeatherParameters:\n    cloudiness = 0.000000\n    cloudiness = 0.000000\n    precipitation = 0.000000\n    precipitation_deposits = 0.000000\n    wind_intensity = 0.000000\n    sun_azimuth_angle = 0.000000\n    sun_altitude_angle = 0.000000\n    fog_density = 0.000000\n    fog_distance = 0.000000\n    fog_falloff = 0.000000\n    wetness = 0.000000\n    scattering_intensity = 0.000000\n    mie_scattering_scale = 0.000000\n    rayleigh_scattering_scale = 0.033100\n\n\nclass WorldSettings:\n    synchronous_mode = False\n    no_rendering_mode = False\n    fixed_delta_seconds = 0\n    substepping = True\n    max_substep_delta_time = 0.01\n    max_substeps = 10\n    max_culling_distance = 0\n    deterministic_ragdolls = False\n\n\nclass ActorList:\n\n    def __init__(self, actor_list):\n        self.actor_list = actor_list\n\n    def filter(self, filterstring):\n        return []\n\n    def __len__(self):\n        return len(self.actor_list)\n\n    def __getitem__(self, i):\n        return self.actor_list[i]\n\n\nclass Control:\n    steer = 0\n    throttle = 0\n    brake = 0\n\n\nclass Actor:\n\n    def __init__(self):\n        self.attributes = {'role_name': ''}\n        self.id = 0\n        self.type_id = None\n        self.location = Location()\n        self.rotation = Rotation()\n        self.transform = Transform(self.location, self.rotation)\n        self.is_alive = True\n\n    def get_transform(self):\n        return self.transform\n\n    def get_location(self):\n        return self.location\n\n    def get_world(self):\n        return World()\n\n    def get_control(self):\n        return Control()\n\n    def destroy(self):\n        del self\n\n    def listen(self, callback):\n        pass\n\n\nclass Walker(Actor):\n    is_walker = True\n\n\nclass Vehicle(Actor):\n    is_vehicle = True\n\n\nclass World:\n    actors = []\n\n    def get_settings(self):\n        return WorldSettings()\n\n    def get_map(self):\n        return Map()\n\n    def get_blueprint_library(self):\n        return CarlaBluePrintLibrary()\n\n    def wait_for_tick(self):\n        pass\n\n    def get_actors(self, ids=[]):\n        actor_list = []\n        for actor in self.actors:\n            if actor.id in ids:\n                actor_list.append(actor)\n\n        return ActorList(actor_list)\n\n    def try_spawn_actor(self, blueprint, spawn_point):\n        new_actor = Vehicle()\n        new_actor.attributes['role_name'] = blueprint.attributes['role_name']\n        new_actor.id = len(self.actors)\n        self.actors.append(new_actor)\n        return new_actor\n\n    def spawn_actor(self, blueprint, spawn_point, attach_to):\n        new_actor = self.try_spawn_actor(blueprint, spawn_point)\n        return new_actor\n\n\nclass Client:\n    world = World()\n\n    def load_world(self, name):\n        return None\n\n    def get_world(self):\n        return self.world\n\n    def get_trafficmanager(self, port):\n        return None\n\n    def apply_batch_sync(self, batch, sync_mode=False):\n        class Response:\n            def __init__(self, id):\n                self.actor_id = id\n                self.error = None\n\n        reponse_list = []\n        for batch_cmd in batch:\n            if batch_cmd is not None:\n                new_actor = Vehicle()\n                new_actor.attributes['role_name'] = batch_cmd.blueprint.attributes['role_name']\n                new_actor.id = len(self.world.actors)\n                self.world.actors.append(new_actor)\n                reponse_list.append(Response(new_actor.id))\n\n        return reponse_list\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tests/test_xosc_load.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides some basic unit tests for the OpenSCENARIO feature of ScenarioRunner\n\"\"\"\n\nfrom unittest import TestCase\nimport glob\nimport carla\nfrom srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenarios.open_scenario import OpenScenario\n\n\nclass TestLoadingXOSC(TestCase):\n    \"\"\"\n    Test class to load OpenSCENARIO files and test for exceptions\n    \"\"\"\n\n    def test_all_xosc(self):\n        \"\"\"\n        Load all examples OpenSCENARIO files\n        \"\"\"\n        all_test_files = glob.glob('**/srunner/examples/*.xosc', recursive=True)\n\n        for filename in all_test_files:\n            client = carla.Client()\n            config = OpenScenarioConfiguration(filename, client, {})\n            self.assertTrue(config is not None)\n            CarlaDataProvider.set_client(client)\n            ego_vehicles = []\n            for vehicle in config.ego_vehicles:\n                ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model,\n                                                                        vehicle.transform,\n                                                                        vehicle.rolename,\n                                                                        color=vehicle.color,\n                                                                        actor_category=vehicle.category))\n\n            scenario = OpenScenario(world=client.get_world(),\n                                    ego_vehicles=ego_vehicles,\n                                    config=config,\n                                    config_file=filename,\n                                    timeout=100000)\n            self.assertTrue(scenario is not None)\n\n            CarlaDataProvider.cleanup()\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/__init__.py",
    "content": ""
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/background_manager.py",
    "content": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSeveral atomic behaviors to help with the communication with the background activity,\nremoving its interference with other scenarios\n\"\"\"\n\nimport py_trees\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import AtomicBehavior\nfrom srunner.scenariomanager.timer import GameTime\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\nclass ChangeRoadBehavior(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to change the parameters of the road behavior.\n    None values imply that these values won't be changed.\n\n    Args:\n        num_front_vehicles (int): Amount of vehicles in front of the ego. Can't be negative\n        num_back_vehicles (int): Amount of vehicles behind it. Can't be negative\n        switch_source (bool): (De)activatea the road sources.\n    \"\"\"\n\n    def __init__(self, num_front_vehicles=None, num_back_vehicles=None, spawn_dist=None, extra_space=None, name=\"ChangeRoadBehavior\"):\n        self._num_front = num_front_vehicles\n        self._num_back = num_back_vehicles\n        self._spawn_dist = spawn_dist\n        self._extra_space = extra_space\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\n            \"BA_ChangeRoadBehavior\", [self._num_front, self._num_back, self._spawn_dist, self._extra_space], overwrite=True\n        )\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeOppositeBehavior(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to change the parameters of the opposite road behavior.\n    None values imply that these values won't be changed\n\n    Args:\n        source_dist (float): Distance between the opposite sources and the ego vehicle. Must be positive\n        max_actors (int): Max amount of concurrent alive actors spawned by the same source. Can't be negative\n    \"\"\"\n\n    def __init__(self, source_dist=None, spawn_dist=None, active=None, name=\"ChangeOppositeBehavior\"):\n        self._source_dist = source_dist\n        self._spawn_dist = spawn_dist\n        self._active = active\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\n            \"BA_ChangeOppositeBehavior\", [self._source_dist, self._spawn_dist, self._active], overwrite=True\n        )\n        return py_trees.common.Status.SUCCESS\n\n\nclass ChangeJunctionBehavior(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to change the parameters of the junction behavior.\n    None values imply that these values won't be changed\n\n    Args:\n        source_dist (float): Distance between the junctiob sources and the junction entry. Must be positive\n        max_actors (int): Max amount of concurrent alive actors spawned by the same source. Can't be negative\n    \"\"\"\n\n    def __init__(self, source_dist=None, spawn_dist=None, max_actors=None, source_perc=None, name=\"ChangeJunctionBehavior\"):\n        self._source_dist = source_dist\n        self._spawn_dist = spawn_dist\n        self._max_actors = max_actors\n        self._perc = source_perc\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\n            \"BA_ChangeJunctionBehavior\", [self._source_dist, self._spawn_dist, self._max_actors, self._perc], overwrite=True\n        )\n        return py_trees.common.Status.SUCCESS\n\n\nclass SetMaxSpeed(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that its behavior is restriced to a maximum speed\n    \"\"\"\n\n    def __init__(self, max_speed, name=\"SetMaxSpeed\"):\n        self._max_speed = max_speed\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"BA_SetMaxSpeed\", self._max_speed, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StopFrontVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that a HardBreak scenario has to be triggered.\n    'stop_duration' is the amount of time, in seconds, the vehicles will be stopped\n    \"\"\"\n\n    def __init__(self, name=\"StopFrontVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"BA_StopFrontVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StartFrontVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that a HardBreak scenario has to be triggered.\n    'stop_duration' is the amount of time, in seconds, the vehicles will be stopped\n    \"\"\"\n\n    def __init__(self, name=\"StartFrontVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        py_trees.blackboard.Blackboard().set(\"BA_StartFrontVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StopBackVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to stop the vehicles behind the ego as to\n    not interfere with the scenarios. This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, name=\"StopBackVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_StopBackVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass StartBackVehicles(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to restart the vehicles behind the ego.\n    \"\"\"\n    def __init__(self, name=\"StartBackVehicles\"):\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_StartBackVehicles\", True, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass LeaveSpaceInFront(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that the ego needs more space in front.\n    This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, space, name=\"LeaveSpaceInFront\"):\n        self._space = space\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_LeaveSpaceInFront\", [self._space], overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass SwitchRouteSources(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to (de)activate all route sources\n    \"\"\"\n    def __init__(self, enabled=True, name=\"SwitchRouteSources\"):\n        self._enabled = enabled\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_SwitchRouteSources\", self._enabled, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass RemoveRoadLane(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to remove its actors from the given lane \n    and stop generating new ones on this lane, or recover from stopping.\n\n    Args:\n        lane_wp (carla.Waypoint): A carla.Waypoint\n        active (bool)\n    \"\"\"\n    def __init__(self, lane_wp, name=\"RemoveRoadLane\"):\n        self._lane_wp = lane_wp\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_RemoveRoadLane\", self._lane_wp, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass ReAddRoadLane(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to readd the ego road lane.\n\n    Args:\n        offset: 0 to readd the ego lane, 1 for the right side lane, -1 for the left...\n        active (bool)\n    \"\"\"\n    def __init__(self, offset, name=\"BA_ReAddRoadLane\"):\n        self._offset = offset\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_ReAddRoadLane\", self._offset, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass LeaveSpaceInFront(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that the ego needs more space in front.\n    This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, space, name=\"LeaveSpaceInFront\"):\n        self._space = space\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_LeaveSpaceInFront\", self._space, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\n\nclass LeaveCrossingSpace(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity that the ego needs more space in front.\n    This only works at roads, not junctions.\n    \"\"\"\n    def __init__(self, collision_wp, name=\"LeaveCrossingSpace\"):\n        self._collision_wp = collision_wp\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\"BA_LeaveCrossingSpace\", self._collision_wp, overwrite=True)\n        return py_trees.common.Status.SUCCESS\n\nclass HandleJunctionScenario(AtomicBehavior):\n    \"\"\"\n    Updates the blackboard to tell the background activity to adapt to a junction scenario\n\n    Args:\n        clear_junction (bool): Remove all actors inside the junction, and all that enter it afterwards\n        clear_ego_entry (bool): Remove all actors part of the ego road to ensure a smooth entry of the ego to the junction.\n        remove_entries (list): list of waypoint representing a junction entry that needs to be removed\n        remove_exits (list): list of waypoint representing a junction exit that needs to be removed\n        stop_entries (bool): Stops all the junction entries\n        extend_road_exit (float): Moves the road junction actors forward to leave more space for the scenario.\n            It also deactivates the road sources.\n        active (bool)\n    \"\"\"\n    def __init__(self, clear_junction=True, clear_ego_entry=True, remove_entries=[],\n                 remove_exits=[], stop_entries=True, extend_road_exit=0,\n                 name=\"HandleJunctionScenario\"):\n        self._clear_junction = clear_junction\n        self._clear_ego_entry = clear_ego_entry\n        self._remove_entries = remove_entries\n        self._remove_exits = remove_exits\n        self._stop_entries = stop_entries\n        self._extend_road_exit = extend_road_exit\n        super().__init__(name)\n\n    def update(self):\n        \"\"\"Updates the blackboard and succeds\"\"\"\n        py_trees.blackboard.Blackboard().set(\n            \"BA_HandleJunctionScenario\",\n            [self._clear_junction, self._clear_ego_entry, self._remove_entries,\n             self._remove_exits, self._stop_entries, self._extend_road_exit],\n            overwrite=True)\n        return py_trees.common.Status.SUCCESS\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/openscenario_parser.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019-2021 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides a parser for scenario configuration files based on OpenSCENARIO\n\"\"\"\n\nfrom __future__ import print_function\n\nfrom distutils.util import strtobool\nimport re\nimport copy\nimport datetime\nimport math\nimport operator\n\nimport py_trees\nimport carla\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom srunner.scenariomanager.weather_sim import Weather\nfrom srunner.scenariomanager.scenarioatomics.atomic_behaviors import (TrafficLightStateSetter,\n                                                                      ActorTransformSetterToOSCPosition,\n                                                                      RunScript,\n                                                                      ChangeWeather,\n                                                                      ChangeAutoPilot,\n                                                                      ChangeRoadFriction,\n                                                                      ChangeActorTargetSpeed,\n                                                                      ChangeActorControl,\n                                                                      ChangeActorWaypoints,\n                                                                      ChangeActorLateralMotion,\n                                                                      ChangeActorLaneOffset,\n                                                                      SyncArrivalOSC,\n                                                                      KeepLongitudinalGap,\n                                                                      Idle,\n                                                                      ChangeParameter)\n# pylint: disable=unused-import\n# For the following includes the pylint check is disabled, as these are accessed via globals()\nfrom srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest,\n                                                                     MaxVelocityTest,\n                                                                     DrivenDistanceTest,\n                                                                     AverageVelocityTest,\n                                                                     KeepLaneTest,\n                                                                     ReachedRegionTest,\n                                                                     OnSidewalkTest,\n                                                                     WrongLaneTest,\n                                                                     InRadiusRegionTest,\n                                                                     InRouteTest,\n                                                                     RouteCompletionTest,\n                                                                     RunningRedLightTest,\n                                                                     RunningStopTest,\n                                                                     OffRoadTest,\n                                                                     EndofRoadTest)\n# pylint: enable=unused-import\nfrom srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle,\n                                                                               InTriggerDistanceToOSCPosition,\n                                                                               InTimeToArrivalToOSCPosition,\n                                                                               InTimeToArrivalToVehicle,\n                                                                               DriveDistance,\n                                                                               StandStill,\n                                                                               OSCStartEndCondition,\n                                                                               TriggerAcceleration,\n                                                                               RelativeVelocityToOtherActor,\n                                                                               TimeOfDayComparison,\n                                                                               TriggerVelocity,\n                                                                               WaitForTrafficLightState,\n                                                                               CheckParameter)\nfrom srunner.scenariomanager.timer import TimeOut, SimulationTimeCondition\nfrom srunner.tools.py_trees_port import oneshot_behavior\nfrom srunner.tools.scenario_helper import get_offset_transform, get_troad_from_transform\n\n\ndef oneshot_with_check(variable_name, behaviour, name=None):\n    \"\"\"\n    Check if the blackboard contains already variable_name and\n    return a oneshot_behavior for behaviour.\n    \"\"\"\n    blackboard = py_trees.blackboard.Blackboard()\n    # check if the variable_name already exists in the blackboard\n    if blackboard.get(variable_name) is not None:\n        print(\"Warning: {} is already used before. Check your XOSC for duplicated names\".format(variable_name))\n\n    return oneshot_behavior(variable_name, behaviour, name)\n\n\nclass ParameterRef:\n    \"\"\"\n    This class stores osc parameter reference in its original form.\n    Returns the converted value whenever it is used.\n    \"\"\"\n\n    def __init__(self, reference_text) -> None:\n        # TODO: (for OSC1.1) add methods(lexer and math_interpreter) to\n        #  recognize and interpret math expression from reference_text\n        self.reference_text = str(reference_text)\n\n    def is_literal(self) -> bool:\n        \"\"\"\n        Returns: True when text is a literal/number\n        \"\"\"\n        return self._is_matching(pattern=r\"(-)?\\d+(\\.\\d*)?\")\n\n    def is_parameter(self) -> bool:\n        \"\"\"\n        Returns: True when text is a parameter\n        \"\"\"\n        return self._is_matching(pattern=r\"[$][A-Za-z_][\\w]*\")\n\n    def _is_matching(self, pattern: str) -> bool:\n        \"\"\"\n        Returns: True when pattern is matching with text\n        \"\"\"\n        match = re.search(pattern, self.reference_text)\n        if match is not None:\n            matching_string = match.group()\n            return matching_string == self.reference_text\n        return False\n\n    def get_interpreted_value(self):\n        \"\"\"\n        Returns: interpreted value from reference_text\n        \"\"\"\n        if self.is_literal():\n            value = self.reference_text\n        elif self.is_parameter():\n            value = CarlaDataProvider.get_osc_global_param_value(self.reference_text)\n            if value is None:\n                raise Exception(\"Parameter '{}' is not defined\".format(self.reference_text[1:]))\n        else:\n            value = None\n        return value\n\n    def __float__(self) -> float:\n        value = self.get_interpreted_value()\n        if value is not None:\n            return float(value)\n        else:\n            raise Exception(\"could not convert '{}' to float\".format(self.reference_text))\n\n    def __int__(self) -> int:\n        value = self.get_interpreted_value()\n        if value is not None:\n            return int(float(value))\n        else:\n            raise Exception(\"could not convert '{}' to int\".format(self.reference_text))\n\n    def __str__(self) -> str:\n        value = self.get_interpreted_value()\n        return str(value) if value is not None else self.reference_text\n\n    def __repr__(self):\n        value = self.get_interpreted_value()\n        return value if value is not None else self.reference_text\n\n    def __radd__(self, other) -> bool:\n        return other + self.__float__()\n\n    def __add__(self, other) -> bool:\n        return other + self.__float__()\n\n    def __rsub__(self, other) -> bool:\n        return other - self.__float__()\n\n    def __sub__(self, other) -> bool:\n        return self.__float__() - other\n\n    def __rmul__(self, other) -> bool:\n        return other * self.__float__()\n\n    def __mul__(self, other) -> bool:\n        return other * self.__float__()\n\n    def __truediv__(self, other) -> bool:\n        return self.__float__() / other\n\n    def __rtruediv__(self, other) -> bool:\n        return other / self.__float__()\n\n    def __eq__(self, other) -> bool:\n        return other == self.__float__()\n\n    def __ne__(self, other) -> bool:\n        return other != self.__float__()\n\n    def __ge__(self, other) -> bool:\n        return self.__float__() >= other\n\n    def __le__(self, other) -> bool:\n        return self.__float__() <= other\n\n    def __gt__(self, other) -> bool:\n        return self.__float__() > other\n\n    def __lt__(self, other) -> bool:\n        return self.__float__() < other\n\n    def __GE__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() >= other\n\n    def __LE__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() <= other\n\n    def __GT__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() > other\n\n    def __LT__(self, other) -> bool:  # pylint: disable=invalid-name\n        return self.__float__() < other\n\n    def __iadd__(self, other) -> bool:\n        return self.__float__() + other\n\n    def __isub__(self, other) -> bool:\n        return self.__float__() - other\n\n    def __abs__(self):\n        return abs(self.__float__())\n\n\nclass OpenScenarioParser(object):\n\n    \"\"\"\n    Pure static class providing conversions from OpenSCENARIO elements to ScenarioRunner elements\n    \"\"\"\n    operators = {\n        \"greaterThan\": operator.gt,\n        \"lessThan\": operator.lt,\n        \"equalTo\": operator.eq,\n        \"greaterOrEqual\": operator.ge,\n        \"lessOrEqual\": operator.le,\n        \"notEqualTo\": operator.ne\n    }\n\n    actor_types = {\n        \"pedestrian\": \"walker\",\n        \"vehicle\": \"vehicle\",\n        \"miscellaneous\": \"miscellaneous\"\n    }\n\n    tl_states = {\n        \"GREEN\": carla.TrafficLightState.Green,\n        \"YELLOW\": carla.TrafficLightState.Yellow,\n        \"RED\": carla.TrafficLightState.Red,\n        \"OFF\": carla.TrafficLightState.Off,\n    }\n\n    global_osc_parameters = {}\n    use_carla_coordinate_system = False\n    osc_filepath = None\n\n    @staticmethod\n    def get_traffic_light_from_osc_name(name):\n        \"\"\"\n        Returns a carla.TrafficLight instance that matches the name given\n        \"\"\"\n        traffic_light = None\n\n        # Given by id\n        if name.startswith(\"id=\"):\n            tl_id = int(name[3:])\n            for carla_tl in CarlaDataProvider.get_all_actors().filter('traffic.traffic_light'):\n                if carla_tl.id == tl_id:\n                    traffic_light = carla_tl\n                    break\n        # Given by position\n        elif name.startswith(\"pos=\"):\n            tl_pos = name[4:]\n            pos = tl_pos.split(\",\")\n            for carla_tl in CCarlaDataProvider.get_all_actors().filter('traffic.traffic_light'):\n                carla_tl_location = carla_tl.get_transform().location\n                distance = carla_tl_location.distance(carla.Location(float(pos[0]),\n                                                                     float(pos[1]),\n                                                                     carla_tl_location.z))\n                if distance < 2.0:\n                    traffic_light = carla_tl\n                    break\n\n        if traffic_light is None:\n            raise AttributeError(\"Unknown  traffic light {}\".format(name))\n\n        return traffic_light\n\n    @staticmethod\n    def set_osc_filepath(filepath):\n        \"\"\"\n        Set path of OSC file. This is required if for example custom commands are provided with\n        relative paths.\n        \"\"\"\n        OpenScenarioParser.osc_filepath = filepath\n\n    @staticmethod\n    def set_use_carla_coordinate_system():\n        \"\"\"\n        CARLA internally uses a left-hand coordinate system (Unreal), but OpenSCENARIO and OpenDRIVE\n        are intended for right-hand coordinate system. Hence, we need to invert the coordinates, if\n        the scenario does not use CARLA coordinates, but instead right-hand coordinates.\n        \"\"\"\n        OpenScenarioParser.use_carla_coordinate_system = True\n\n    @staticmethod\n    def set_parameters(xml_tree, additional_parameter_dict=None):\n        \"\"\"\n        Parse the xml_tree, and replace all parameter references\n        with the actual values.\n\n        Note: Parameter names must not start with \"$\", however when referencing a parameter the\n              reference has to start with \"$\".\n              https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#_re_use_mechanisms\n\n        Args:\n            xml_tree: Containing all nodes that should be updated\n            additional_parameter_dict (dictionary): Additional parameters as dict (key, value). Optional.\n\n        returns:\n            updated xml_tree, dictonary containing all parameters and their values\n        \"\"\"\n\n        parameter_dict = {}\n        parameters = xml_tree.find('ParameterDeclarations')\n\n        if parameters is None and not parameter_dict:\n            return xml_tree, parameter_dict\n\n        if parameters is None:\n            parameters = []\n\n        for parameter in parameters:\n            name = parameter.attrib.get('name')\n            value = parameter.attrib.get('value')\n            parameter_dict[name] = value\n\n        # overwrite parameters in parameters_dict by additional_parameters_dict\n        if additional_parameter_dict is not None:\n            parameter_dict = dict(list(parameter_dict.items()) + list(additional_parameter_dict.items()))\n\n        return xml_tree, parameter_dict\n\n    @staticmethod\n    def set_global_parameters(parameter_dict):\n        \"\"\"\n        Set global_osc_parameter dictionary\n\n        Args:\n            parameter_dict (Dictionary): Input for global_osc_parameter\n        \"\"\"\n        OpenScenarioParser.global_osc_parameters = parameter_dict\n        CarlaDataProvider.update_osc_global_params(parameter_dict)\n\n    @staticmethod\n    def get_catalog_entry(catalogs, catalog_reference):\n        \"\"\"\n        Get catalog entry referenced by catalog_reference included correct parameter settings\n\n        Args:\n            catalogs (Dictionary of dictionaries): List of all catalogs and their entries\n            catalog_reference (XML ElementTree): Reference containing the exact catalog to be used\n\n        returns:\n            Catalog entry (XML ElementTree)\n        \"\"\"\n        entry_name = str(ParameterRef(catalog_reference.attrib.get(\"entryName\")))\n        entry = catalogs[catalog_reference.attrib.get(\"catalogName\")][entry_name]\n        entry_copy = copy.deepcopy(entry)\n        catalog_copy = copy.deepcopy(catalog_reference)\n        entry = OpenScenarioParser.assign_catalog_parameters(entry_copy, catalog_copy)\n\n        return entry\n\n    @staticmethod\n    def assign_catalog_parameters(entry_instance, catalog_reference):\n        \"\"\"\n        Parse catalog_reference, and replace all parameter references\n        in entry_instance by the values provided in catalog_reference.\n\n        Not to be used from outside this class.\n\n        Args:\n            entry_instance (XML ElementTree): Entry to be updated\n            catalog_reference (XML ElementTree): Reference containing the exact parameter values\n\n        returns:\n            updated entry_instance with updated parameter values\n        \"\"\"\n\n        parameter_dict = {}\n        for elem in entry_instance.iter():\n            if elem.find('ParameterDeclarations') is not None:\n                parameters = elem.find('ParameterDeclarations')\n                for parameter in parameters:\n                    name = parameter.attrib.get('name')\n                    value = parameter.attrib.get('value')\n                    parameter_dict[name] = value\n\n        for parameter_assignments in catalog_reference.iter(\"ParameterAssignments\"):\n            for parameter_assignment in parameter_assignments.iter(\"ParameterAssignment\"):\n                parameter = parameter_assignment.attrib.get(\"parameterRef\")\n                value = parameter_assignment.attrib.get(\"value\")\n                parameter_dict[parameter] = value\n\n        for node in entry_instance.iter():\n            for key in node.attrib:\n                for param in sorted(parameter_dict, key=len, reverse=True):\n                    if \"$\" + param in node.attrib[key]:\n                        node.attrib[key] = node.attrib[key].replace(\"$\" + param, parameter_dict[param])\n\n        OpenScenarioParser.set_parameters(entry_instance, OpenScenarioParser.global_osc_parameters)\n\n        return entry_instance\n\n    @staticmethod\n    def get_friction_from_env_action(xml_tree, catalogs):\n        \"\"\"\n        Extract the CARLA road friction coefficient from an OSC EnvironmentAction\n\n        Args:\n            xml_tree: Containing the EnvironmentAction,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the EnvironmentAction\n\n        returns:\n           friction (float)\n        \"\"\"\n\n        if xml_tree.findall('.//EnvironmentAction'):\n            node = xml_tree.findall('.//EnvironmentAction')[0]\n            set_environment = next(node.iter(\"EnvironmentAction\"))\n        else:\n            return 1.0\n\n        if sum(1 for _ in set_environment.iter(\"Weather\")) != 0:\n            environment = set_environment.find(\"Environment\")\n        elif set_environment.find(\"CatalogReference\") is not None:\n            catalog_reference = set_environment.find(\"CatalogReference\")\n            environment = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference)\n\n        friction = 1.0\n\n        road_condition = environment.iter(\"RoadCondition\")\n        for condition in road_condition:\n            friction = condition.attrib.get('frictionScaleFactor')\n\n        return friction\n\n    @staticmethod\n    def get_weather_from_env_action(xml_tree, catalogs):\n        \"\"\"\n        Extract the CARLA weather parameters from an OSC EnvironmentAction\n\n        Args:\n            xml_tree: Containing the EnvironmentAction,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the EnvironmentAction\n\n        returns:\n           Weather (srunner.scenariomanager.weather_sim.Weather)\n        \"\"\"\n\n        if xml_tree.findall('.//EnvironmentAction'):\n            node = xml_tree.findall('.//EnvironmentAction')[0]\n            set_environment = next(node.iter(\"EnvironmentAction\"))\n        else:\n            return Weather(carla.WeatherParameters())\n\n        if sum(1 for _ in set_environment.iter(\"Weather\")) != 0:\n            environment = set_environment.find(\"Environment\")\n        elif set_environment.find(\"CatalogReference\") is not None:\n            catalog_reference = set_environment.find(\"CatalogReference\")\n            environment = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference)\n\n        weather = environment.find(\"Weather\")\n        sun = weather.find(\"Sun\")\n\n        carla_weather = carla.WeatherParameters()\n        carla_weather.sun_azimuth_angle = math.degrees(float(sun.attrib.get('azimuth', 0)))\n        carla_weather.sun_altitude_angle = math.degrees(float(sun.attrib.get('elevation', 0)))\n        carla_weather.cloudiness = 100 - float(sun.attrib.get('intensity', 0)) * 100\n        fog = weather.find(\"Fog\")\n        carla_weather.fog_distance = float(fog.attrib.get('visualRange', 'inf'))\n        if carla_weather.fog_distance < 1000:\n            carla_weather.fog_density = 100\n        carla_weather.precipitation = 0\n        carla_weather.precipitation_deposits = 0\n        carla_weather.wetness = 0\n        carla_weather.wind_intensity = 30.0\n        precepitation = weather.find(\"Precipitation\")\n        if precepitation.attrib.get('precipitationType') == \"rain\":\n            carla_weather.precipitation = float(precepitation.attrib.get('intensity')) * 100\n            carla_weather.precipitation_deposits = 100  # if it rains, make the road wet\n            carla_weather.wetness = carla_weather.precipitation\n        elif precepitation.attrib.get('type') == \"snow\":\n            raise AttributeError(\"CARLA does not support snow precipitation\")\n\n        time_of_day = environment.find(\"TimeOfDay\")\n        weather_animation = strtobool(time_of_day.attrib.get(\"animation\"))\n        time = time_of_day.attrib.get(\"dateTime\")\n        dtime = datetime.datetime.strptime(time, \"%Y-%m-%dT%H:%M:%S\")\n\n        return Weather(carla_weather, dtime, weather_animation)\n\n    @staticmethod\n    def get_controller(xml_tree, catalogs):\n        \"\"\"\n        Extract the object controller from the OSC XML or a catalog\n\n        Args:\n            xml_tree: Containing the controller information,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the EnvironmentAction\n\n        returns:\n           module: Python module containing the controller implementation\n           args: Dictonary with (key, value) parameters for the controller\n        \"\"\"\n\n        assign_action = next(xml_tree.iter(\"AssignControllerAction\"))\n\n        properties = None\n        if assign_action.find('Controller') is not None:\n            properties = assign_action.find('Controller').find('Properties')\n        elif assign_action.find(\"CatalogReference\") is not None:\n            catalog_reference = assign_action.find(\"CatalogReference\")\n            properties = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference).find('Properties')\n\n        module = None\n        args = {}\n        for prop in properties:\n            if prop.attrib.get('name') == \"module\":\n                module = prop.attrib.get('value')\n            else:\n                args[prop.attrib.get('name')] = prop.attrib.get('value')\n\n        override_action = xml_tree.find('OverrideControllerValueAction')\n        for child in override_action:\n            if strtobool(child.attrib.get('active')):\n                raise NotImplementedError(\"Controller override actions are not yet supported\")\n\n        return module, args\n\n    @staticmethod\n    def get_route(xml_tree, catalogs):\n        \"\"\"\n        Extract the route from the OSC XML or a catalog\n\n        Args:\n            xml_tree: Containing the route information,\n                or the reference to the catalog it is defined in.\n            catalogs: XML Catalogs that could contain the Route\n\n        returns:\n           waypoints: List of route waypoints = (waypoint, routing strategy)\n                      where the strategy is a string indicating if the fastest/shortest/etc.\n                      route should be used.\n        \"\"\"\n        route = None\n\n        if xml_tree.find('Route') is not None:\n            route = xml_tree.find('Route')\n        elif xml_tree.find('CatalogReference') is not None:\n            catalog_reference = xml_tree.find(\"CatalogReference\")\n            route = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference)\n        else:\n            raise AttributeError(\"Unknown private FollowRoute action\")\n\n        waypoints = []\n        if route is not None:\n            for waypoint in route.iter('Waypoint'):\n                position = waypoint.find('Position')\n                routing_option = str(waypoint.attrib.get('routeStrategy'))\n                waypoints.append((position, routing_option))\n        else:\n            raise AttributeError(\"No waypoints has been set\")\n\n        return waypoints\n\n    @staticmethod\n    def convert_position_to_transform(position, actor_list=None):\n        \"\"\"\n        Convert an OpenScenario position into a CARLA transform\n\n        Not supported: RoutePosition\n        \"\"\"\n\n        if position.find('WorldPosition') is not None:\n            world_pos = position.find('WorldPosition')\n            x = float(ParameterRef(world_pos.attrib.get('x', 0)))\n            y = float(ParameterRef(world_pos.attrib.get('y', 0)))\n            z = float(ParameterRef(world_pos.attrib.get('z', 0)))\n            yaw = math.degrees(float(ParameterRef(world_pos.attrib.get('h', 0))))\n            pitch = math.degrees(float(ParameterRef(world_pos.attrib.get('p', 0))))\n            roll = math.degrees(float(ParameterRef(world_pos.attrib.get('r', 0))))\n            if not OpenScenarioParser.use_carla_coordinate_system:\n                y = y * (-1.0)\n                yaw = yaw * (-1.0)\n            return carla.Transform(carla.Location(x=x, y=y, z=z), carla.Rotation(yaw=yaw, pitch=pitch, roll=roll))\n\n        elif ((position.find('RelativeWorldPosition') is not None) or\n              (position.find('RelativeObjectPosition') is not None) or\n              (position.find('RelativeLanePosition') is not None) or\n              (position.find('RelativeRoadPosition') is not None)):\n\n            if position.find('RelativeWorldPosition') is not None:\n                rel_pos = position.find('RelativeWorldPosition')\n            if position.find('RelativeObjectPosition') is not None:\n                rel_pos = position.find('RelativeObjectPosition')\n            if position.find('RelativeLanePosition') is not None:\n                rel_pos = position.find('RelativeLanePosition')\n            if position.find('RelativeRoadPosition') is not None:\n                rel_pos = position.find('RelativeRoadPosition')\n\n            # get relative object and relative position\n            obj = rel_pos.attrib.get('entityRef')\n            obj_actor = None\n            actor_transform = None\n\n            if actor_list is not None:\n                for actor in actor_list:\n                    if actor.rolename == obj:\n                        obj_actor = actor\n                        actor_transform = actor.transform\n            else:\n                for actor in CarlaDataProvider.get_all_actors():\n                    if 'role_name' in actor.attributes and actor.attributes['role_name'] == obj:\n                        obj_actor = actor\n                        actor_transform = obj_actor.get_transform()\n                        break\n\n            if obj_actor is None or actor_transform is None:\n                raise AttributeError(\"Object '{}' provided as position reference is not known\".format(obj))\n\n            # calculate orientation h, p, r\n            is_absolute = False\n            dyaw = 0\n            dpitch = 0\n            droll = 0\n            if rel_pos.find('Orientation') is not None:\n                orientation = rel_pos.find('Orientation')\n                is_absolute = (orientation.attrib.get('type') == \"absolute\")\n                dyaw = math.degrees(float(ParameterRef(orientation.attrib.get('h', 0))))\n                dpitch = math.degrees(float(ParameterRef(orientation.attrib.get('p', 0))))\n                droll = math.degrees(float(ParameterRef(orientation.attrib.get('r', 0))))\n\n            if not OpenScenarioParser.use_carla_coordinate_system:\n                dyaw = dyaw * (-1.0)\n\n            yaw = actor_transform.rotation.yaw\n            pitch = actor_transform.rotation.pitch\n            roll = actor_transform.rotation.roll\n\n            if not is_absolute:\n                yaw = yaw + dyaw\n                pitch = pitch + dpitch\n                roll = roll + droll\n            else:\n                yaw = dyaw\n                pitch = dpitch\n                roll = droll\n\n            # calculate location x, y, z\n            # dx, dy, dz\n            if ((position.find('RelativeWorldPosition') is not None) or\n                    (position.find('RelativeObjectPosition') is not None)):\n                dx = float(ParameterRef(rel_pos.attrib.get('dx', 0)))\n                dy = float(ParameterRef(rel_pos.attrib.get('dy', 0)))\n                dz = float(ParameterRef(rel_pos.attrib.get('dz', 0)))\n\n                if not OpenScenarioParser.use_carla_coordinate_system:\n                    dy = dy * (-1.0)\n\n                x = actor_transform.location.x + dx\n                y = actor_transform.location.y + dy\n                z = actor_transform.location.z + dz\n\n                transform = carla.Transform(carla.Location(x=x, y=y, z=z),\n                                            carla.Rotation(yaw=yaw, pitch=pitch, roll=roll))\n\n            elif position.find('RelativeLanePosition') is not None:\n                dlane = float(ParameterRef(rel_pos.attrib.get('dLane')))\n                ds = float(ParameterRef(rel_pos.attrib.get('ds')))\n                offset = float(ParameterRef(rel_pos.attrib.get('offset', 0.0)))\n\n                carla_map = CarlaDataProvider.get_map()\n                relative_waypoint = carla_map.get_waypoint(actor_transform.location)\n\n                road_id, ref_lane_id, ref_s = relative_waypoint.road_id, relative_waypoint.lane_id, relative_waypoint.s\n                target_lane_id = int(ref_lane_id + dlane)\n                waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, target_lane_id, ref_s)\n                if waypoint is not None:\n                    if ds < 0:\n                        ds = (-1.0) * ds\n                        waypoint = waypoint.previous(ds)[-1]\n                    else:\n                        waypoint = waypoint.next(ds)[-1]\n\n                if waypoint is None:\n                    raise AttributeError(\"RelativeLanePosition \" +\n                                         \"'roadId={} with ds={} and lane_id={}' does not exist\".format(road_id,\n                                                                                                       ds,\n                                                                                                       target_lane_id))\n\n                transform = waypoint.transform\n                transform.rotation.yaw = yaw\n                transform.rotation.pitch = pitch\n                transform.rotation.roll = roll\n\n                # Adapt transform according to offset\n                if abs(offset) == waypoint.lane_width:\n                    # if the offset position is exactly on lane edge its difficult to find out which lane its on.\n                    # so, when offset is on lane edge/corner adjust it to stay inside the lane\n                    # if user wants to offset out of lane then make sure offset > waypoint.lane_width\n                    if offset > 0:\n                        offset = offset - 0.05\n                    elif offset < 0:\n                        offset = offset + 0.05\n                transform = get_offset_transform(transform, offset)\n            elif position.find('RelativeRoadPosition') is not None:\n                ds = float(ParameterRef(rel_pos.attrib.get('ds')))\n                dt = float(ParameterRef(rel_pos.attrib.get('dt', 0.0)))\n                troad = get_troad_from_transform\n\n                carla_map = CarlaDataProvider.get_map()\n                relative_waypoint = carla_map.get_waypoint(actor_transform.location)\n\n                road_id, ref_lane_id, ref_s = relative_waypoint.road_id, relative_waypoint.lane_id, relative_waypoint.s\n                target_t, target_s = troad(relative_waypoint.transform) - troad(actor_transform) + dt, ref_s + ds\n                waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, ref_lane_id, target_s)\n                if waypoint is None:\n                    raise AttributeError(\"RelativeRoadPosition 'roadId={} with s={} and t={}' does not exist\".format(\n                        road_id, target_s, target_t))\n\n                transform = waypoint.transform\n                transform.rotation.yaw = yaw\n                transform.rotation.pitch = pitch\n                transform.rotation.roll = roll\n                transform = get_offset_transform(transform, target_t)\n\n            return transform\n\n        elif position.find('RoadPosition') is not None:\n            road_pos = position.find('RoadPosition')\n            road_id = int(ParameterRef(road_pos.attrib.get('roadId', 0)))\n            t = float(ParameterRef(road_pos.attrib.get('t', 0)))\n            s = float(ParameterRef(road_pos.attrib.get('s', 0)))\n\n            waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, 0, s)\n            if waypoint is None:\n                raise AttributeError(\"RoadPosition 'roadId={} with s={} and t={}' does not exist\".format(road_id, s, t))\n\n            transform = waypoint.transform\n\n            if road_pos.find('Orientation') is not None:\n                orientation = road_pos.find('Orientation')\n                dyaw = math.degrees(float(ParameterRef(orientation.attrib.get('h', 0))))\n                dpitch = math.degrees(float(ParameterRef(orientation.attrib.get('p', 0))))\n                droll = math.degrees(float(ParameterRef(orientation.attrib.get('r', 0))))\n\n                if not OpenScenarioParser.use_carla_coordinate_system:\n                    dyaw = dyaw * (-1.0)\n\n                transform.rotation.yaw = transform.rotation.yaw + dyaw\n                transform.rotation.pitch = transform.rotation.pitch + dpitch\n                transform.rotation.roll = transform.rotation.roll + droll\n\n            if not OpenScenarioParser.use_carla_coordinate_system:\n                # multiply -1 because unlike offset t road is -ve for right side\n                t = -1*t\n            transform = get_offset_transform(transform, t)\n            return transform\n\n        elif position.find('LanePosition') is not None:\n            lane_pos = position.find('LanePosition')\n            road_id = int(ParameterRef(lane_pos.attrib.get('roadId', 0)))\n            lane_id = int(ParameterRef(lane_pos.attrib.get('laneId', 0)))\n            offset = float(ParameterRef(lane_pos.attrib.get('offset', 0)))\n            s = float(ParameterRef(lane_pos.attrib.get('s', 0)))\n            waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, lane_id, s)\n            if waypoint is None:\n                raise AttributeError(\"LanePosition 'roadId={}, laneId={}, s={}, offset={}' does not exist\".format(\n                    road_id, lane_id, s, offset))\n\n            transform = waypoint.transform\n            if lane_pos.find('Orientation') is not None:\n                orientation = lane_pos.find('Orientation')\n                dyaw = math.degrees(float(ParameterRef(orientation.attrib.get('h', 0))))\n                dpitch = math.degrees(float(ParameterRef(orientation.attrib.get('p', 0))))\n                droll = math.degrees(float(ParameterRef(orientation.attrib.get('r', 0))))\n\n                if not OpenScenarioParser.use_carla_coordinate_system:\n                    dyaw = dyaw * (-1.0)\n\n                transform.rotation.yaw = transform.rotation.yaw + dyaw\n                transform.rotation.pitch = transform.rotation.pitch + dpitch\n                transform.rotation.roll = transform.rotation.roll + droll\n\n            if offset != 0:\n                forward_vector = transform.rotation.get_forward_vector()\n                orthogonal_vector = carla.Vector3D(x=-forward_vector.y, y=forward_vector.x, z=forward_vector.z)\n                transform.location.x = transform.location.x + offset * orthogonal_vector.x\n                transform.location.y = transform.location.y + offset * orthogonal_vector.y\n\n            return transform\n        elif position.find('RoutePosition') is not None:\n            raise NotImplementedError(\"Route positions are not yet supported\")\n        else:\n            raise AttributeError(\"Unknown position\")\n\n    @staticmethod\n    def convert_condition_to_atomic(condition, actor_list):\n        \"\"\"\n        Convert an OpenSCENARIO condition into a Behavior/Criterion atomic\n\n        If there is a delay defined in the condition, then the condition is checked after the delay time\n        passed by, e.g. <Condition name=\"\" delay=\"5\">.\n\n        Note: Not all conditions are currently supported.\n        \"\"\"\n\n        atomic = None\n        delay_atomic = None\n        condition_name = condition.attrib.get('name')\n\n        if condition.attrib.get('delay') is not None and float(condition.attrib.get('delay')) != 0:\n            delay = float(condition.attrib.get('delay'))\n            delay_atomic = TimeOut(delay)\n\n        if condition.find('ByEntityCondition') is not None:\n\n            trigger_actor = None    # A-priori validation ensures that this will be not None\n            triggered_actor = None\n\n            for triggering_entities in condition.find('ByEntityCondition').iter('TriggeringEntities'):\n                for entity in triggering_entities.iter('EntityRef'):\n                    for actor in actor_list:\n                        if actor is not None and entity.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            trigger_actor = actor\n                            break\n\n            for entity_condition in condition.find('ByEntityCondition').iter('EntityCondition'):\n                if entity_condition.find('EndOfRoadCondition') is not None:\n                    end_road_condition = entity_condition.find('EndOfRoadCondition')\n                    condition_duration = ParameterRef(end_road_condition.attrib.get('duration'))\n                    atomic_cls = py_trees.meta.inverter(EndofRoadTest)\n                    atomic = atomic_cls(trigger_actor, condition_duration, terminate_on_failure=True,\n                                        name=condition_name)\n                elif entity_condition.find('CollisionCondition') is not None:\n\n                    collision_condition = entity_condition.find('CollisionCondition')\n\n                    if collision_condition.find('EntityRef') is not None:\n                        collision_entity = collision_condition.find('EntityRef')\n\n                        for actor in actor_list:\n                            if collision_entity.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                                triggered_actor = actor\n                                break\n\n                        if triggered_actor is None:\n                            raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                                collision_condition.attrib.get('entityRef', None)))\n\n                        atomic_cls = py_trees.meta.inverter(CollisionTest)\n                        atomic = atomic_cls(trigger_actor, other_actor=triggered_actor, terminate_on_failure=True,\n                                            name=condition_name)\n\n                    elif collision_condition.find('ByType') is not None:\n                        collision_type = collision_condition.find('ByType').attrib.get('type', None)\n\n                        triggered_type = OpenScenarioParser.actor_types[collision_type]\n\n                        atomic_cls = py_trees.meta.inverter(CollisionTest)\n                        atomic = atomic_cls(trigger_actor, other_actor_type=triggered_type, terminate_on_failure=True,\n                                            name=condition_name)\n\n                    else:\n                        atomic_cls = py_trees.meta.inverter(CollisionTest)\n                        atomic = atomic_cls(trigger_actor, terminate_on_failure=True, name=condition_name)\n\n                elif entity_condition.find('OffroadCondition') is not None:\n                    off_condition = entity_condition.find('OffroadCondition')\n                    condition_duration = ParameterRef(off_condition.attrib.get('duration'))\n                    atomic_cls = py_trees.meta.inverter(OffRoadTest)\n                    atomic = atomic_cls(trigger_actor, condition_duration, terminate_on_failure=True,\n                                        name=condition_name)\n                elif entity_condition.find('TimeHeadwayCondition') is not None:\n                    headtime_condition = entity_condition.find('TimeHeadwayCondition')\n\n                    condition_value = ParameterRef(headtime_condition.attrib.get('value'))\n\n                    condition_rule = headtime_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    condition_freespace = strtobool(headtime_condition.attrib.get('freespace', False))\n                    condition_along_route = strtobool(headtime_condition.attrib.get('alongRoute', False))\n\n                    for actor in actor_list:\n                        if headtime_condition.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            triggered_actor = actor\n                            break\n                    if triggered_actor is None:\n                        raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                            headtime_condition.attrib.get('entityRef', None)))\n\n                    atomic = InTimeToArrivalToVehicle(\n                        trigger_actor, triggered_actor, condition_value, condition_freespace,\n                        condition_along_route, condition_operator, condition_name\n                    )\n\n                elif entity_condition.find('TimeToCollisionCondition') is not None:\n                    ttc_condition = entity_condition.find('TimeToCollisionCondition')\n\n                    condition_rule = ttc_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    condition_value = ParameterRef(ttc_condition.attrib.get('value'))\n                    condition_target = ttc_condition.find('TimeToCollisionConditionTarget')\n                    entity_ref_ = condition_target.find('EntityRef')\n\n                    condition_freespace = strtobool(ttc_condition.attrib.get('freespace', False))\n                    condition_along_route = strtobool(ttc_condition.attrib.get('alongRoute', False))\n\n                    if condition_target.find('Position') is not None:\n                        position = condition_target.find('Position')\n                        atomic = InTimeToArrivalToOSCPosition(\n                            trigger_actor, position, condition_value, condition_along_route, condition_operator)\n                    else:\n                        for actor in actor_list:\n                            if entity_ref_.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                                triggered_actor = actor\n                                break\n                        if triggered_actor is None:\n                            raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                                entity_ref_.attrib.get('entityRef', None)))\n\n                        atomic = InTimeToArrivalToVehicle(\n                            trigger_actor, triggered_actor, condition_value, condition_freespace,\n                            condition_along_route, condition_operator, condition_name)\n                elif entity_condition.find('AccelerationCondition') is not None:\n                    accel_condition = entity_condition.find('AccelerationCondition')\n                    condition_value = ParameterRef(accel_condition.attrib.get('value'))\n                    condition_rule = accel_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n                    atomic = TriggerAcceleration(\n                        trigger_actor, condition_value, condition_operator, condition_name)\n                elif entity_condition.find('StandStillCondition') is not None:\n                    ss_condition = entity_condition.find('StandStillCondition')\n                    duration = ParameterRef(ss_condition.attrib.get('duration'))\n                    atomic = StandStill(trigger_actor, condition_name, duration)\n                elif entity_condition.find('SpeedCondition') is not None:\n                    spd_condition = entity_condition.find('SpeedCondition')\n                    condition_value = ParameterRef(spd_condition.attrib.get('value'))\n                    condition_rule = spd_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    atomic = TriggerVelocity(\n                        trigger_actor, condition_value, condition_operator, condition_name)\n                elif entity_condition.find('RelativeSpeedCondition') is not None:\n                    relspd_condition = entity_condition.find('RelativeSpeedCondition')\n                    condition_value = ParameterRef(relspd_condition.attrib.get('value'))\n                    condition_rule = relspd_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n\n                    for actor in actor_list:\n                        if relspd_condition.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            triggered_actor = actor\n                            break\n\n                    if triggered_actor is None:\n                        raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                            relspd_condition.attrib.get('entityRef', None)))\n\n                    atomic = RelativeVelocityToOtherActor(\n                        trigger_actor, triggered_actor, condition_value, condition_operator, condition_name)\n                elif entity_condition.find('TraveledDistanceCondition') is not None:\n                    distance_condition = entity_condition.find('TraveledDistanceCondition')\n                    distance_value = ParameterRef(distance_condition.attrib.get('value'))\n                    atomic = DriveDistance(trigger_actor, distance_value, name=condition_name)\n                elif entity_condition.find('ReachPositionCondition') is not None:\n                    rp_condition = entity_condition.find('ReachPositionCondition')\n                    distance_value = ParameterRef(rp_condition.attrib.get('tolerance'))\n                    position = rp_condition.find('Position')\n                    atomic = InTriggerDistanceToOSCPosition(\n                        trigger_actor, position, distance_value, name=condition_name)\n                elif entity_condition.find('DistanceCondition') is not None:\n                    distance_condition = entity_condition.find('DistanceCondition')\n\n                    distance_value = ParameterRef(distance_condition.attrib.get('value'))\n\n                    distance_rule = distance_condition.attrib.get('rule')\n                    distance_operator = OpenScenarioParser.operators[distance_rule]\n\n                    distance_freespace = strtobool(distance_condition.attrib.get('freespace', False))\n                    if distance_freespace:\n                        raise NotImplementedError(\n                            \"DistanceCondition: freespace attribute is currently not implemented\")\n                    distance_along_route = strtobool(distance_condition.attrib.get('alongRoute', False))\n\n                    if distance_condition.find('Position') is not None:\n                        position = distance_condition.find('Position')\n                        atomic = InTriggerDistanceToOSCPosition(\n                            trigger_actor, position, distance_value, distance_along_route,\n                            distance_operator, name=condition_name)\n\n                elif entity_condition.find('RelativeDistanceCondition') is not None:\n                    distance_condition = entity_condition.find('RelativeDistanceCondition')\n                    distance_value = ParameterRef(distance_condition.attrib.get('value'))\n\n                    distance_freespace = distance_condition.attrib.get('freespace', \"false\") == \"true\"\n                    rel_dis_type = distance_condition.attrib.get('relativeDistanceType')\n                    for actor in actor_list:\n                        if distance_condition.attrib.get('entityRef', None) == actor.attributes['role_name']:\n                            triggered_actor = actor\n                            break\n\n                    if triggered_actor is None:\n                        raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                            distance_condition.attrib.get('entityRef', None)))\n\n                    condition_rule = distance_condition.attrib.get('rule')\n                    condition_operator = OpenScenarioParser.operators[condition_rule]\n                    atomic = InTriggerDistanceToVehicle(triggered_actor, trigger_actor, distance_value,\n                                                        condition_operator, distance_type=rel_dis_type,\n                                                        freespace=distance_freespace, name=condition_name)\n        elif condition.find('ByValueCondition') is not None:\n            value_condition = condition.find('ByValueCondition')\n            if value_condition.find('ParameterCondition') is not None:\n                parameter_condition = value_condition.find('ParameterCondition')\n                arg_name = parameter_condition.attrib.get('parameterRef')\n                value = ParameterRef(parameter_condition.attrib.get('value'))\n                rule = parameter_condition.attrib.get('rule')\n                if condition_name.startswith('criteria_'):\n                    if str(value) != '':\n                        arg_value = float(value)\n                    else:\n                        arg_value = 0\n                    class_name = condition_name[9:]\n                    if class_name in globals():\n                        criterion_instance = globals()[class_name]\n                    else:\n                        raise AttributeError(\n                            \"The condition {} cannot be mapped to a criterion atomic\".format(class_name))\n\n                    atomic = py_trees.composites.Parallel(\"Evaluation Criteria for multiple ego vehicles\")\n                    for triggered_actor in actor_list:\n                        if arg_name != '':\n                            atomic.add_child(criterion_instance(triggered_actor, arg_value))\n                        else:\n                            atomic.add_child(criterion_instance(triggered_actor))\n                else:\n                    atomic = CheckParameter(arg_name, value, OpenScenarioParser.operators[rule], name=condition_name)\n            elif value_condition.find('SimulationTimeCondition') is not None:\n                simtime_condition = value_condition.find('SimulationTimeCondition')\n                value = ParameterRef(simtime_condition.attrib.get('value'))\n                rule = OpenScenarioParser.operators[simtime_condition.attrib.get('rule')]\n                atomic = SimulationTimeCondition(value, comparison_operator=rule)\n            elif value_condition.find('TimeOfDayCondition') is not None:\n                tod_condition = value_condition.find('TimeOfDayCondition')\n                condition_date = tod_condition.attrib.get('dateTime')\n                condition_rule = tod_condition.attrib.get('rule')\n                condition_operator = OpenScenarioParser.operators[condition_rule]\n                atomic = TimeOfDayComparison(condition_date, condition_operator, condition_name)\n            elif value_condition.find('StoryboardElementStateCondition') is not None:\n                state_condition = value_condition.find('StoryboardElementStateCondition')\n                element_name = state_condition.attrib.get('storyboardElementRef')\n                element_type = state_condition.attrib.get('storyboardElementType')\n                state = state_condition.attrib.get('state')\n                if state == \"startTransition\":\n                    atomic = OSCStartEndCondition(element_type, element_name, rule=\"START\", name=state + \"Condition\")\n                elif state in [\"stopTransition\", \"endTransition\", \"completeState\"]:\n                    atomic = OSCStartEndCondition(element_type, element_name, rule=\"END\", name=state + \"Condition\")\n                else:\n                    raise NotImplementedError(\n                        \"Only start, stop, endTransitions and completeState are currently supported\")\n            elif value_condition.find('UserDefinedValueCondition') is not None:\n                raise NotImplementedError(\"ByValue UserDefinedValue conditions are not yet supported\")\n            elif value_condition.find('TrafficSignalCondition') is not None:\n                tl_condition = value_condition.find('TrafficSignalCondition')\n\n                name_condition = tl_condition.attrib.get('name')\n                traffic_light = OpenScenarioParser.get_traffic_light_from_osc_name(name_condition)\n\n                tl_state = tl_condition.attrib.get('state').upper()\n                if tl_state not in OpenScenarioParser.tl_states:\n                    raise KeyError(\"CARLA only supports Green, Red, Yellow or Off\")\n                state_condition = OpenScenarioParser.tl_states[tl_state]\n\n                atomic = WaitForTrafficLightState(\n                    traffic_light, state_condition, name=condition_name)\n            elif value_condition.find('TrafficSignalControllerCondition') is not None:\n                raise NotImplementedError(\"ByValue TrafficSignalController conditions are not yet supported\")\n            else:\n                raise AttributeError(\"Unknown ByValue condition\")\n\n        else:\n            raise AttributeError(\"Unknown condition\")\n\n        if delay_atomic is not None and atomic is not None:\n            new_atomic = py_trees.composites.Sequence(\"delayed sequence\")\n            new_atomic.add_child(delay_atomic)\n            new_atomic.add_child(atomic)\n        else:\n            new_atomic = atomic\n\n        return new_atomic\n\n    @staticmethod\n    def convert_maneuver_to_atomic(action, actor, actor_list, catalogs):\n        \"\"\"\n        Convert an OpenSCENARIO maneuver action into a Behavior atomic\n\n        Note not all OpenSCENARIO actions are currently supported\n        \"\"\"\n        maneuver_name = action.attrib.get('name', 'unknown')\n\n        if action.find('GlobalAction') is not None:\n            global_action = action.find('GlobalAction')\n            if global_action.find('InfrastructureAction') is not None:\n                infrastructure_action = global_action.find('InfrastructureAction').find('TrafficSignalAction')\n                if infrastructure_action.find('TrafficSignalStateAction') is not None:\n                    traffic_light_action = infrastructure_action.find('TrafficSignalStateAction')\n\n                    name_condition = traffic_light_action.attrib.get('name')\n                    traffic_light = OpenScenarioParser.get_traffic_light_from_osc_name(name_condition)\n\n                    tl_state = traffic_light_action.attrib.get('state').upper()\n                    if tl_state not in OpenScenarioParser.tl_states:\n                        raise KeyError(\"CARLA only supports Green, Red, Yellow or Off\")\n                    traffic_light_state = OpenScenarioParser.tl_states[tl_state]\n\n                    atomic = TrafficLightStateSetter(\n                        traffic_light, traffic_light_state, name=maneuver_name + \"_\" + str(traffic_light.id))\n                else:\n                    raise NotImplementedError(\"TrafficLights can only be influenced via TrafficSignalStateAction\")\n            elif global_action.find('EnvironmentAction') is not None:\n                weather_behavior = ChangeWeather(\n                    OpenScenarioParser.get_weather_from_env_action(global_action, catalogs))\n                friction_behavior = ChangeRoadFriction(\n                    OpenScenarioParser.get_friction_from_env_action(global_action, catalogs))\n\n                env_behavior = py_trees.composites.Parallel(\n                    policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=maneuver_name)\n\n                env_behavior.add_child(\n                    oneshot_with_check(variable_name=maneuver_name + \">WeatherUpdate\", behaviour=weather_behavior))\n                env_behavior.add_child(\n                    oneshot_with_check(variable_name=maneuver_name + \">FrictionUpdate\", behaviour=friction_behavior))\n\n                return env_behavior\n            elif global_action.find('ParameterAction') is not None:\n                parameter_action = global_action.find('ParameterAction')\n                parameter_ref = parameter_action.attrib.get('parameterRef')\n                if parameter_action.find('ModifyAction') is not None:\n                    action_rule = parameter_action.find('ModifyAction').find(\"Rule\")\n                    if action_rule.find(\"AddValue\") is not None:\n                        rule, value = '+', action_rule.find(\"AddValue\").attrib.get('value')\n                    else:\n                        rule, value = '*', action_rule.find(\"MultiplyByValue\").attrib.get('value')\n                else:\n                    rule, value = None, parameter_action.find('SetAction').attrib.get('value')\n                atomic = ChangeParameter(parameter_ref, value=ParameterRef(value), rule=rule, name=maneuver_name)\n            else:\n                raise NotImplementedError(\"Global actions are not yet supported\")\n        elif action.find('UserDefinedAction') is not None:\n            user_defined_action = action.find('UserDefinedAction')\n            if user_defined_action.find('CustomCommandAction') is not None:\n                command = user_defined_action.find('CustomCommandAction').attrib.get('type')\n                atomic = RunScript(command, base_path=OpenScenarioParser.osc_filepath, name=maneuver_name)\n        elif action.find('PrivateAction') is not None:\n            private_action = action.find('PrivateAction')\n\n            if private_action.find('LongitudinalAction') is not None:\n                private_action = private_action.find('LongitudinalAction')\n\n                if private_action.find('SpeedAction') is not None:\n                    long_maneuver = private_action.find('SpeedAction')\n\n                    # duration and distance\n                    distance = float('inf')\n                    duration = float('inf')\n                    dimension = long_maneuver.find(\"SpeedActionDynamics\").attrib.get('dynamicsDimension')\n                    if dimension == \"distance\":\n                        distance = ParameterRef(long_maneuver.find(\"SpeedActionDynamics\").attrib.get(\n                            'value', float(\"inf\")))\n                    else:\n                        duration = ParameterRef(long_maneuver.find(\"SpeedActionDynamics\").attrib.get(\n                            'value', float(\"inf\")))\n\n                    # absolute velocity with given target speed\n                    if long_maneuver.find(\"SpeedActionTarget\").find(\"AbsoluteTargetSpeed\") is not None:\n                        target_speed = ParameterRef(long_maneuver.find(\"SpeedActionTarget\").find(\n                            \"AbsoluteTargetSpeed\").attrib.get('value', 0))\n                        atomic = ChangeActorTargetSpeed(\n                            actor, float(target_speed), distance=distance, duration=duration, name=maneuver_name)\n\n                    # relative velocity to given actor\n                    if long_maneuver.find(\"SpeedActionTarget\").find(\"RelativeTargetSpeed\") is not None:\n                        relative_speed = long_maneuver.find(\"SpeedActionTarget\").find(\"RelativeTargetSpeed\")\n                        obj = relative_speed.attrib.get('entityRef')\n                        value = ParameterRef(relative_speed.attrib.get('value', 0))\n                        value_type = relative_speed.attrib.get('speedTargetValueType')\n                        continuous = bool(strtobool(relative_speed.attrib.get('continuous')))\n\n                        for traffic_actor in actor_list:\n                            if (traffic_actor is not None and 'role_name' in traffic_actor.attributes and\n                                    traffic_actor.attributes['role_name'] == obj):\n                                obj_actor = traffic_actor\n\n                        atomic = ChangeActorTargetSpeed(actor,\n                                                        target_speed=0.0,\n                                                        relative_actor=obj_actor,\n                                                        value=value,\n                                                        value_type=value_type,\n                                                        continuous=continuous,\n                                                        distance=distance,\n                                                        duration=duration,\n                                                        name=maneuver_name)\n\n                elif private_action.find('LongitudinalDistanceAction') is not None:\n                    long_dist_action = private_action.find(\"LongitudinalDistanceAction\")\n                    obj = long_dist_action.attrib.get('entityRef')\n                    for traffic_actor in actor_list:\n                        if (traffic_actor is not None and 'role_name' in traffic_actor.attributes and\n                                traffic_actor.attributes['role_name'] == obj):\n                            obj_actor = traffic_actor\n\n                    if \"distance\" in long_dist_action.attrib and \"timeGap\" not in long_dist_action.attrib:\n                        gap_type, gap = 'distance', ParameterRef(long_dist_action.attrib.get('distance'))\n                    elif \"timeGap\" in long_dist_action.attrib and \"distance\" not in long_dist_action.attrib:\n                        raise NotImplementedError(\"LongitudinalDistanceAction: timeGap is not implemented\")\n                    else:\n                        raise ValueError(\"LongitudinalDistanceAction: \" +\n                                         \"Please specify any one attribute of [distance, timeGap]\")\n\n                    constraints = long_dist_action.find('DynamicConstraints')\n                    max_speed = constraints.attrib.get('maxSpeed', None) if constraints is not None else None\n                    continues = bool(strtobool(long_dist_action.attrib.get('continuous')))\n                    freespace = bool(strtobool(long_dist_action.attrib.get('freespace')))\n                    atomic = KeepLongitudinalGap(actor, reference_actor=obj_actor, gap=gap, gap_type=gap_type,\n                                                 max_speed=max_speed, continues=continues, freespace=freespace,\n                                                 name=maneuver_name)\n                else:\n                    raise AttributeError(\"Unknown longitudinal action\")\n            elif private_action.find('LateralAction') is not None:\n                private_action = private_action.find('LateralAction')\n                if private_action.find('LaneChangeAction') is not None:\n                    # Note: LaneChangeActions are currently only supported for RelativeTargetLane\n                    lat_maneuver = private_action.find('LaneChangeAction')\n                    target_lane_rel = ParameterRef(lat_maneuver.find(\"LaneChangeTarget\").find(\n                        \"RelativeTargetLane\").attrib.get('value', 0))\n                    direction = \"left\" if target_lane_rel > 0 else \"right\"\n                    lane_changes = abs(target_lane_rel)\n                    # duration and distance\n                    distance = float('inf')\n                    duration = float('inf')\n                    dimension = lat_maneuver.find(\"LaneChangeActionDynamics\").attrib.get('dynamicsDimension')\n                    if dimension == \"distance\":\n                        distance = ParameterRef(\n                            lat_maneuver.find(\"LaneChangeActionDynamics\").attrib.get('value', float(\"inf\")))\n                    else:\n                        duration = ParameterRef(\n                            lat_maneuver.find(\"LaneChangeActionDynamics\").attrib.get('value', float(\"inf\")))\n                    atomic = ChangeActorLateralMotion(actor, direction=direction,\n                                                      distance_lane_change=distance,\n                                                      distance_other_lane=10,\n                                                      lane_changes=lane_changes,\n                                                      name=maneuver_name)\n                elif private_action.find('LaneOffsetAction') is not None:\n                    lat_maneuver = private_action.find('LaneOffsetAction')\n                    continuous = bool(strtobool(lat_maneuver.attrib.get('continuous', \"true\")))\n                    # Parsing of the different Dynamic shapes is missing\n\n                    lane_target_offset = lat_maneuver.find('LaneOffsetTarget')\n                    if lane_target_offset.find('AbsoluteTargetLaneOffset') is not None:\n                        absolute_offset = ParameterRef(\n                            lane_target_offset.find('AbsoluteTargetLaneOffset').attrib.get('value', 0))\n                        atomic = ChangeActorLaneOffset(\n                            actor, absolute_offset, continuous=continuous, name=maneuver_name)\n\n                    elif lane_target_offset.find('RelativeTargetLaneOffset') is not None:\n                        relative_target_offset = lane_target_offset.find('RelativeTargetLaneOffset')\n                        relative_offset = ParameterRef(relative_target_offset.attrib.get('value', 0))\n\n                        relative_actor = None\n                        relative_actor_name = relative_target_offset.attrib.get('entityRef', None)\n                        for _actor in actor_list:\n                            if _actor is not None and 'role_name' in _actor.attributes:\n                                if relative_actor_name == _actor.attributes['role_name']:\n                                    relative_actor = _actor\n                                    break\n                        if relative_actor is None:\n                            raise AttributeError(\"Cannot find actor '{}' for condition\".format(relative_actor_name))\n\n                        atomic = ChangeActorLaneOffset(actor, relative_offset, relative_actor,\n                                                       continuous=continuous, name=maneuver_name)\n\n                    else:\n                        raise AttributeError(\"Unknown target offset\")\n                else:\n                    raise AttributeError(\"Unknown lateral action\")\n            elif private_action.find('VisibilityAction') is not None:\n                raise NotImplementedError(\"Visibility actions are not yet supported\")\n            elif private_action.find('SynchronizeAction') is not None:\n                sync_action = private_action.find('SynchronizeAction')\n\n                master_actor = None\n                for actor_ins in actor_list:\n                    if actor_ins is not None and 'role_name' in actor_ins.attributes:\n                        if sync_action.attrib.get('masterEntityRef', None) == actor_ins.attributes['role_name']:\n                            master_actor = actor_ins\n                            break\n\n                if master_actor is None:\n                    raise AttributeError(\"Cannot find actor '{}' for condition\".format(\n                        sync_action.attrib.get('masterEntityRef', None)))\n\n                master_position = OpenScenarioParser.convert_position_to_transform(\n                    sync_action.find('TargetPositionMaster'))\n                position = OpenScenarioParser.convert_position_to_transform(sync_action.find('TargetPosition'))\n\n                if sync_action.find(\"FinalSpeed\").find(\"AbsoluteSpeed\") is not None:\n                    final_speed = ParameterRef(sync_action.find(\"FinalSpeed\").find(\n                        \"AbsoluteSpeed\").attrib.get('value', 0))\n                    atomic = SyncArrivalOSC(\n                        actor, master_actor, position, master_position, final_speed, name=maneuver_name)\n\n                # relative velocity to given actor\n                elif sync_action.find(\"FinalSpeed\").find(\"RelativeSpeedToMaster\") is not None:\n                    relative_speed = sync_action.find(\"FinalSpeed\").find(\"RelativeSpeedToMaster\")\n                    final_speed = ParameterRef(relative_speed.attrib.get('value', 0))\n                    relative_type = relative_speed.attrib.get('speedTargetValueType')\n                    atomic = SyncArrivalOSC(\n                        actor, master_actor, position, master_position, final_speed,\n                        relative_to_master=True, relative_type=relative_type, name=maneuver_name)\n                else:\n                    raise AttributeError(\"Unknown speed action\")\n            elif private_action.find('ActivateControllerAction') is not None:\n                private_action = private_action.find('ActivateControllerAction')\n                activate = strtobool(private_action.attrib.get('longitudinal'))\n                atomic = ChangeAutoPilot(actor, activate, name=maneuver_name)\n            elif private_action.find('ControllerAction') is not None:\n                controller_action = private_action.find('ControllerAction')\n                module, args = OpenScenarioParser.get_controller(controller_action, catalogs)\n                atomic = ChangeActorControl(actor, control_py_module=module, args=args,\n                                            scenario_file_path=OpenScenarioParser.osc_filepath)\n            elif private_action.find('TeleportAction') is not None:\n                teleport_action = private_action.find('TeleportAction')\n                position = teleport_action.find('Position')\n                atomic = ActorTransformSetterToOSCPosition(actor, position, name=maneuver_name)\n            elif private_action.find('RoutingAction') is not None:\n                private_action = private_action.find('RoutingAction')\n                if private_action.find('AssignRouteAction') is not None:\n                    # @TODO: How to handle relative positions here? This might chance at runtime?!\n                    route_action = private_action.find('AssignRouteAction')\n                    waypoints = OpenScenarioParser.get_route(route_action, catalogs)\n                    atomic = ChangeActorWaypoints(actor, waypoints=waypoints, name=maneuver_name)\n                elif private_action.find('FollowTrajectoryAction') is not None:\n                    raise NotImplementedError(\"Private FollowTrajectory actions are not yet supported\")\n                elif private_action.find('AcquirePositionAction') is not None:\n                    route_action = private_action.find('AcquirePositionAction')\n                    osc_position = route_action.find('Position')\n                    waypoints = [(osc_position, 'fastest')]\n                    atomic = ChangeActorWaypoints(actor, waypoints=waypoints, name=maneuver_name)\n                else:\n                    raise AttributeError(\"Unknown private routing action\")\n            else:\n                raise AttributeError(\"Unknown private action\")\n\n        else:\n            if list(action):\n                raise AttributeError(\"Unknown action: {}\".format(maneuver_name))\n            else:\n                return Idle(duration=0, name=maneuver_name)\n\n        return atomic\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/py_trees_port.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2015 Daniel Stonier\n# Copyright (c) 2020 Intel Corporation\n#\n# License: BSD\n#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE\n\n\"\"\"\nThis module provides a backport from newer py_trees releases (> 1.0)\nTo use certain features also within ScenarioRunner, which uses py_trees\nversion 0.8.x\n\"\"\"\n\nimport py_trees\n\n\nclass Decorator(py_trees.behaviour.Behaviour):\n\n    \"\"\"\n    A decorator is responsible for handling the lifecycle of a single\n    child beneath\n\n    This is taken from py_trees 1.2 to work with our current implementation\n    that uses py_trees 0.8.2\n    \"\"\"\n\n    def __init__(self, child, name):\n        \"\"\"\n        Common initialisation steps for a decorator - type checks and\n        name construction (if None is given).\n        Args:\n            name (:obj:`str`): the decorator name\n            child (:class:`~py_trees.behaviour.Behaviour`): the child to be decorated\n        Raises:\n            TypeError: if the child is not an instance of :class:`~py_trees.behaviour.Behaviour`\n        \"\"\"\n        # Checks\n        if not isinstance(child, py_trees.behaviour.Behaviour):\n            raise TypeError(\"A decorator's child must be an instance of py_trees.behaviours.Behaviour\")\n        # Initialise\n        super(Decorator, self).__init__(name=name)\n        self.children.append(child)\n        # Give a convenient alias\n        self.decorated = self.children[0]\n        self.decorated.parent = self\n\n    def tick(self):\n        \"\"\"\n        A decorator's tick is exactly the same as a normal proceedings for\n        a Behaviour's tick except that it also ticks the decorated child node.\n        Yields:\n            :class:`~py_trees.behaviour.Behaviour`: a reference to itself or one of its children\n        \"\"\"\n        self.logger.debug(\"%s.tick()\" % self.__class__.__name__)\n        # initialise just like other behaviours/composites\n        if self.status != py_trees.common.Status.RUNNING:\n            self.initialise()\n        # interrupt proceedings and process the child node\n        # (including any children it may have as well)\n        for node in self.decorated.tick():\n            yield node\n        # resume normal proceedings for a Behaviour's tick\n        new_status = self.update()\n        if new_status not in list(py_trees.common.Status):\n            self.logger.error(\n                \"A behaviour returned an invalid status, setting to INVALID [%s][%s]\" % (new_status, self.name))\n            new_status = py_trees.common.Status.INVALID\n        if new_status != py_trees.common.Status.RUNNING:\n            self.stop(new_status)\n        self.status = new_status\n        yield self\n\n    def stop(self, new_status=py_trees.common.Status.INVALID):\n        \"\"\"\n        As with other composites, it checks if the child is running\n        and stops it if that is the case.\n        Args:\n            new_status (:class:`~py_trees.common.Status`): the behaviour is transitioning to this new status\n        \"\"\"\n        self.logger.debug(\"%s.stop(%s)\" % (self.__class__.__name__, new_status))\n        self.terminate(new_status)\n        # priority interrupt handling\n        if new_status == py_trees.common.Status.INVALID:\n            self.decorated.stop(new_status)\n        # if the decorator returns SUCCESS/FAILURE and should stop the child\n        if self.decorated.status == py_trees.common.Status.RUNNING:\n            self.decorated.stop(py_trees.common.Status.INVALID)\n        self.status = new_status\n\n    def tip(self):\n        \"\"\"\n        Get the *tip* of this behaviour's subtree (if it has one) after it's last\n        tick. This corresponds to the the deepest node that was running before the\n        subtree traversal reversed direction and headed back to this node.\n        \"\"\"\n        if self.decorated.status != py_trees.common.Status.INVALID:\n            return self.decorated.tip()\n\n        return super(Decorator, self).tip()\n\n\ndef oneshot_behavior(variable_name, behaviour, name=None):\n    \"\"\"\n    This is taken from py_trees.idiom.oneshot.\n    \"\"\"\n    if not name:\n        name = behaviour.name\n\n    subtree_root = py_trees.composites.Selector(name=name)\n\n    # Initialize the variables\n    blackboard = py_trees.blackboard.Blackboard()\n    _ = blackboard.set(variable_name, False)\n\n    # Wait until the scenario has ended\n    check_flag = py_trees.blackboard.CheckBlackboardVariable(\n        name=variable_name + \" Done?\",\n        variable_name=variable_name,\n        expected_value=True,\n        clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE\n    )\n    set_flag = py_trees.blackboard.SetBlackboardVariable(\n        name=\"Mark Done\",\n        variable_name=variable_name,\n        variable_value=True\n    )\n    # If it's a sequence, don't double-nest it in a redundant manner\n    if isinstance(behaviour, py_trees.composites.Sequence):\n        behaviour.add_child(set_flag)\n        sequence = behaviour\n    else:\n        sequence = py_trees.composites.Sequence(name=\"OneShot\")\n        sequence.add_children([behaviour, set_flag])\n\n    subtree_root.add_children([check_flag, sequence])\n    return subtree_root\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/route_manipulation.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Labs.\n# authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com)\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule to manipulate the routes, by making then more or less dense (Up to a certain parameter).\nIt also contains functions to convert the CARLA world location do GPS coordinates.\n\"\"\"\n\nimport math\nimport xml.etree.ElementTree as ET\n\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\ndef _location_to_gps(lat_ref, lon_ref, location):\n    \"\"\"\n    Convert from world coordinates to GPS coordinates\n    :param lat_ref: latitude reference for the current map\n    :param lon_ref: longitude reference for the current map\n    :param location: location to translate\n    :return: dictionary with lat, lon and height\n    \"\"\"\n\n    EARTH_RADIUS_EQUA = 6378137.0   # pylint: disable=invalid-name\n    scale = math.cos(lat_ref * math.pi / 180.0)\n    mx = scale * lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n    my = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + lat_ref) * math.pi / 360.0))\n    mx += location.x\n    my -= location.y\n\n    lon = mx * 180.0 / (math.pi * EARTH_RADIUS_EQUA * scale)\n    lat = 360.0 * math.atan(math.exp(my / (EARTH_RADIUS_EQUA * scale))) / math.pi - 90.0\n    z = location.z\n\n    return {'lat': lat, 'lon': lon, 'z': z}\n\n\ndef location_route_to_gps(route, lat_ref, lon_ref):\n    \"\"\"\n        Locate each waypoint of the route into gps, (lat long ) representations.\n    :param route:\n    :param lat_ref:\n    :param lon_ref:\n    :return:\n    \"\"\"\n    gps_route = []\n\n    for transform, connection in route:\n        gps_point = _location_to_gps(lat_ref, lon_ref, transform.location)\n        gps_route.append((gps_point, connection))\n\n    return gps_route\n\n\ndef _get_latlon_ref(world):\n    \"\"\"\n    Convert from waypoints world coordinates to CARLA GPS coordinates\n    :return: tuple with lat and lon coordinates\n    \"\"\"\n    xodr = world.get_map().to_opendrive()\n    tree = ET.ElementTree(ET.fromstring(xodr))\n\n    # default reference\n    lat_ref = 42.0\n    lon_ref = 2.0\n\n    for opendrive in tree.iter(\"OpenDRIVE\"):\n        for header in opendrive.iter(\"header\"):\n            for georef in header.iter(\"geoReference\"):\n                if georef.text:\n                    str_list = georef.text.split(' ')\n                    for item in str_list:\n                        if '+lat_0' in item:\n                            lat_ref = float(item.split('=')[1])\n                        if '+lon_0' in item:\n                            lon_ref = float(item.split('=')[1])\n    return lat_ref, lon_ref\n\n\ndef downsample_route(route, sample_factor):\n    \"\"\"\n    Downsample the route by some factor.\n    :param route: the trajectory , has to contain the waypoints and the road options\n    :param sample_factor: Maximum distance between samples\n    :return: returns the ids of the final route that can\n    \"\"\"\n\n    ids_to_sample = []\n    prev_option = None\n    dist = 0\n\n    for i, point in enumerate(route):\n        curr_option = point[1]\n\n        # Lane changing\n        if curr_option in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # When road option changes\n        elif prev_option != curr_option and prev_option not in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT):\n            ids_to_sample.append(i)\n            dist = 0\n\n        # After a certain max distance\n        elif dist > sample_factor:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # At the end\n        elif i == len(route) - 1:\n            ids_to_sample.append(i)\n            dist = 0\n\n        # Compute the distance traveled\n        else:\n            curr_location = point[0].location\n            prev_location = route[i - 1][0].location\n            dist += curr_location.distance(prev_location)\n\n        prev_option = curr_option\n\n    return ids_to_sample\n\n\ndef interpolate_trajectory(waypoints_trajectory, hop_resolution=1.0):\n    \"\"\"\n    Given some raw keypoints interpolate a full dense trajectory to be used by the user.\n    returns the full interpolated route both in GPS coordinates and also in its original form.\n    \n    Args:\n        - waypoints_trajectory: the current coarse trajectory\n        - hop_resolution: distance between the trajectory's waypoints\n    \"\"\"\n\n    grp = GlobalRoutePlanner(CarlaDataProvider.get_map(), hop_resolution)\n    # Obtain route plan\n    lat_ref, lon_ref = _get_latlon_ref(CarlaDataProvider.get_world())\n\n    route = []\n    gps_route = []\n\n    for i in range(len(waypoints_trajectory) - 1):\n\n        waypoint = waypoints_trajectory[i]\n        waypoint_next = waypoints_trajectory[i + 1]\n        interpolated_trace = grp.trace_route(waypoint, waypoint_next)\n        for wp, connection in interpolated_trace:\n            route.append((wp.transform, connection))\n            gps_coord = _location_to_gps(lat_ref, lon_ref, wp.transform.location)\n            gps_route.append((gps_coord, connection))\n\n    return gps_route, route\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/route_parser.py",
    "content": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nModule used to parse all the route and scenario configuration parameters.\n\"\"\"\n\nimport json\nimport math\nimport xml.etree.ElementTree as ET\n\nimport carla\nfrom agents.navigation.local_planner import RoadOption\nfrom srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData\n\n# Threshold to say if a scenarios trigger position is part of the route\nDIST_THRESHOLD = 2.0\nANGLE_THRESHOLD = 10\n\n\ndef convert_elem_to_transform(elem):\n    \"\"\"Convert an ElementTree.Element to a CARLA transform\"\"\"\n    return carla.Transform(\n        carla.Location(\n            float(elem.attrib.get('x')),\n            float(elem.attrib.get('y')),\n            float(elem.attrib.get('z'))\n        ),\n        carla.Rotation(\n            roll=0.0,\n            pitch=0.0,\n            yaw=float(elem.attrib.get('yaw'))\n        )\n    )\n\n\nclass RouteParser(object):\n\n    \"\"\"\n    Pure static class used to parse all the route and scenario configuration parameters.\n    \"\"\"\n\n    @staticmethod\n    def parse_routes_file(route_filename, single_route_id=''):\n        \"\"\"\n        Returns a list of route configuration elements.\n        :param route_filename: the path to a set of routes.\n        :param single_route: If set, only this route shall be returned\n        :return: List of dicts containing the waypoints, id and town of the routes\n        \"\"\"\n\n        route_configs = []\n        tree = ET.parse(route_filename)\n        for route in tree.iter(\"route\"):\n\n            route_id = route.attrib['id']\n            if single_route_id and route_id != single_route_id:\n                continue\n\n            route_config = RouteScenarioConfiguration()\n            route_config.town = route.attrib['town']\n            route_config.name = \"RouteScenario_{}\".format(route_id)\n            route_config.weather = RouteParser.parse_weather(route)\n\n            # The list of carla.Location that serve as keypoints on this route\n            positions = []\n            for position in route.find('waypoints').iter('position'):\n                positions.append(carla.Location(x=float(position.attrib['x']),\n                                                y=float(position.attrib['y']),\n                                                z=float(position.attrib['z'])))\n            route_config.keypoints = positions\n\n            # The list of ScenarioConfigurations that store the scenario's data\n            scenario_configs = []\n            for scenario in route.find('scenarios').iter('scenario'):\n                scenario_config = ScenarioConfiguration()\n                scenario_config.name = scenario.attrib.get('name')\n                scenario_config.type = scenario.attrib.get('type')\n\n                for elem in scenario.getchildren():\n                    if elem.tag == 'trigger_point':\n                        scenario_config.trigger_points.append(convert_elem_to_transform(elem))\n                    elif elem.tag == 'other_actor':\n                        scenario_config.other_actors.append(ActorConfigurationData.parse_from_node(elem, 'scenario'))\n                    else:\n                        scenario_config.other_parameters[elem.tag] = elem.attrib\n\n                scenario_configs.append(scenario_config)\n            route_config.scenario_configs = scenario_configs\n\n            route_configs.append(route_config)\n\n        return route_configs\n\n    @staticmethod\n    def parse_weather(route):\n        \"\"\"\n        Parses all the weather information as a list of [position, carla.WeatherParameters],\n        where the position represents a % of the route.\n        \"\"\"\n        weathers = []\n\n        weathers_elem = route.find(\"weathers\")\n        if weathers_elem is None:\n            return [[0, carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)]]\n\n        for weather_elem in weathers_elem.iter('weather'):\n            route_percentage = float(weather_elem.attrib['route_percentage'])\n\n            weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=50)  # Base weather\n            for weather_attrib in weather_elem.attrib:\n                if hasattr(weather, weather_attrib):\n                    setattr(weather, weather_attrib, float(weather_elem.attrib[weather_attrib]))\n                elif weather_attrib != 'route_percentage':\n                    print(f\"WARNING: Ignoring '{weather_attrib}', as it isn't a weather parameter\")\n\n            weathers.append([route_percentage, weather])\n\n        weathers.sort(key=lambda x: x[0])\n        return weathers\n\n    @staticmethod\n    def is_scenario_at_route(trigger_transform, route):\n        \"\"\"\n        Check if the scenario is affecting the route.\n        This is true if the trigger position is very close to any route point\n        \"\"\"\n        def is_trigger_close(trigger_transform, route_transform):\n            \"\"\"Check if the two transforms are similar\"\"\"\n            dist = trigger_transform.location.distance(route_transform.location)\n            angle_dist = (trigger_transform.rotation.yaw - route_transform.rotation.yaw) % 360\n\n            return dist < DIST_THRESHOLD \\\n                and (angle_dist < ANGLE_THRESHOLD or angle_dist > (360 - ANGLE_THRESHOLD))\n\n        for route_transform, _ in route:\n            if is_trigger_close(trigger_transform, route_transform):\n                return True\n\n        return False\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/scenario_helper.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nSummary of useful helper functions for scenarios\n\"\"\"\n\nimport math\nimport shapely.geometry\nimport shapely.affinity\n\nimport numpy as np\n\nimport carla\nfrom agents.tools.misc import vector\nfrom agents.navigation.local_planner import RoadOption\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataProvider\n\n\ndef get_distance_along_route(route, target_location):\n    \"\"\"\n    Calculate the distance of the given location along the route\n\n    Note: If the location is not along the route, the route length will be returned\n    \"\"\"\n\n    wmap = CarlaDataProvider.get_map()\n    covered_distance = 0\n    prev_position = None\n    found = False\n\n    # Don't use the input location, use the corresponding wp as location\n    target_location_from_wp = wmap.get_waypoint(target_location).transform.location\n\n    for position, _ in route:\n\n        location = target_location_from_wp\n\n        # Don't perform any calculations for the first route point\n        if not prev_position:\n            prev_position = position\n            continue\n\n        # Calculate distance between previous and current route point\n        interval_length_squared = ((prev_position.x - position.x) ** 2) + ((prev_position.y - position.y) ** 2)\n        distance_squared = ((location.x - prev_position.x) ** 2) + ((location.y - prev_position.y) ** 2)\n\n        # Close to the current position? Stop calculation\n        if distance_squared < 0.01:\n            break\n\n        if distance_squared < 400 and not distance_squared < interval_length_squared:\n            # Check if a neighbor lane is closer to the route\n            # Do this only in a close distance to correct route interval, otherwise the computation load is too high\n            starting_wp = wmap.get_waypoint(location)\n            wp = starting_wp.get_left_lane()\n            while wp is not None:\n                new_location = wp.transform.location\n                new_distance_squared = ((new_location.x - prev_position.x) ** 2) + (\n                    (new_location.y - prev_position.y) ** 2)\n\n                if np.sign(starting_wp.lane_id) != np.sign(wp.lane_id):\n                    break\n\n                if new_distance_squared < distance_squared:\n                    distance_squared = new_distance_squared\n                    location = new_location\n                else:\n                    break\n\n                wp = wp.get_left_lane()\n\n            wp = starting_wp.get_right_lane()\n            while wp is not None:\n                new_location = wp.transform.location\n                new_distance_squared = ((new_location.x - prev_position.x) ** 2) + (\n                    (new_location.y - prev_position.y) ** 2)\n\n                if np.sign(starting_wp.lane_id) != np.sign(wp.lane_id):\n                    break\n\n                if new_distance_squared < distance_squared:\n                    distance_squared = new_distance_squared\n                    location = new_location\n                else:\n                    break\n\n                wp = wp.get_right_lane()\n\n        if distance_squared < interval_length_squared:\n            # The location could be inside the current route interval, if route/lane ids match\n            # Note: This assumes a sufficiently small route interval\n            # An alternative is to compare orientations, however, this also does not work for\n            # long route intervals\n\n            curr_wp = wmap.get_waypoint(position)\n            prev_wp = wmap.get_waypoint(prev_position)\n            wp = wmap.get_waypoint(location)\n\n            if prev_wp and curr_wp and wp:\n                if wp.road_id in (prev_wp.road_id, curr_wp.road_id):\n                    # Roads match, now compare the sign of the lane ids\n                    if (np.sign(wp.lane_id) == np.sign(prev_wp.lane_id) or\n                            np.sign(wp.lane_id) == np.sign(curr_wp.lane_id)):\n                        # The location is within the current route interval\n                        covered_distance += math.sqrt(distance_squared)\n                        found = True\n                        break\n\n        covered_distance += math.sqrt(interval_length_squared)\n        prev_position = position\n\n    return covered_distance, found\n\n\ndef get_crossing_point(actor):\n    \"\"\"\n    Get the next crossing point location in front of the ego vehicle\n\n    @return point of crossing\n    \"\"\"\n    wp_cross = CarlaDataProvider.get_map().get_waypoint(actor.get_location())\n\n    while not wp_cross.is_intersection:\n        wp_cross = wp_cross.next(2)[0]\n\n    crossing = carla.Location(x=wp_cross.transform.location.x,\n                              y=wp_cross.transform.location.y, z=wp_cross.transform.location.z)\n\n    return crossing\n\n\ndef get_geometric_linear_intersection(ego_location, other_location, move_to_junction=False):\n    \"\"\"\n    Obtain a intersection point between two actor's location by using their waypoints (wp)\n\n    @return point of intersection of the two vehicles\n    \"\"\"\n\n    wp_ego_1 = CarlaDataProvider.get_map().get_waypoint(ego_location)\n    wp_ego_2 = wp_ego_1.next(1)[0]\n\n    if move_to_junction:\n        while True:\n            next_wp = wp_ego_2.next(1)[0]\n            if next_wp.is_junction:\n                break\n            else:\n                wp_ego_1 = wp_ego_2\n                wp_ego_2 = next_wp\n\n    ego_1_loc = wp_ego_1.transform.location\n    ego_2_loc = wp_ego_2.transform.location\n\n    wp_other_1 = CarlaDataProvider.get_world().get_map().get_waypoint(other_location)\n    wp_other_2 = wp_other_1.next(1)[0]\n\n    if move_to_junction:\n        while True:\n            next_wp = wp_other_2.next(1)[0]\n            if next_wp.is_junction:\n                break\n            else:\n                wp_other_1 = wp_other_2\n                wp_other_2 = next_wp\n\n    other_1_loc = wp_other_1.transform.location\n    other_2_loc = wp_other_2.transform.location\n\n    s = np.vstack([\n        (ego_1_loc.x, ego_1_loc.y),\n        (ego_2_loc.x, ego_2_loc.y),\n        (other_1_loc.x, other_1_loc.y),\n        (other_2_loc.x, other_2_loc.y)\n    ])\n    h = np.hstack((s, np.ones((4, 1))))\n    line1 = np.cross(h[0], h[1])\n    line2 = np.cross(h[2], h[3])\n    x, y, z = np.cross(line1, line2)\n    if z == 0:\n        return None\n\n    return carla.Location(x=x/z, y=y/z, z=0)\n\n\ndef get_location_in_distance(actor, distance):\n    \"\"\"\n    Obtain a location in a given distance from the current actor's location.\n    Note: Search is stopped on first intersection.\n\n    @return obtained location and the traveled distance\n    \"\"\"\n    waypoint = CarlaDataProvider.get_map().get_waypoint(actor.get_location())\n    traveled_distance = 0\n    while not waypoint.is_intersection and traveled_distance < distance:\n        waypoint_new = waypoint.next(1.0)[-1]\n        traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location)\n        waypoint = waypoint_new\n\n    return waypoint.transform.location, traveled_distance\n\n\ndef get_location_in_distance_from_wp(waypoint, distance, stop_at_junction=True):\n    \"\"\"\n    Obtain a location in a given distance from the current actor's location.\n    Note: Search is stopped on first intersection.\n\n    @return obtained location and the traveled distance\n    \"\"\"\n    traveled_distance = 0\n    while not (waypoint.is_intersection and stop_at_junction) and traveled_distance < distance:\n        wp_next = waypoint.next(1.0)\n        if wp_next:\n            waypoint_new = wp_next[-1]\n            traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location)\n            waypoint = waypoint_new\n        else:\n            break\n\n    return waypoint.transform.location, traveled_distance\n\n\ndef get_waypoint_in_distance(waypoint, distance, stop_at_junction=True):\n    \"\"\"\n    Obtain a waypoint in a given distance from the current actor's location.\n    Note: Search is stopped on first intersection.\n    @return obtained waypoint and the traveled distance\n    \"\"\"\n    traveled_distance = 0\n    while not (waypoint.is_intersection and stop_at_junction) and traveled_distance < distance:\n        wp_next = waypoint.next(1.0)\n        if wp_next:\n            waypoint_new = wp_next[-1]\n            traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location)\n            waypoint = waypoint_new\n        else:\n            break\n\n    return waypoint, traveled_distance\n\n\ndef generate_target_waypoint_list(waypoint, turn=0):\n    \"\"\"\n    This method follow waypoints to a junction and choose path based on turn input.\n    Turn input: LEFT -> -1, RIGHT -> 1, STRAIGHT -> 0\n    @returns a waypoint list from the starting point to the end point according to turn input\n    \"\"\"\n    reached_junction = False\n    threshold = math.radians(0.1)\n    plan = []\n    while True:\n        wp_choice = waypoint.next(2)\n        if len(wp_choice) > 1:\n            reached_junction = True\n            waypoint = choose_at_junction(waypoint, wp_choice, turn)\n        else:\n            waypoint = wp_choice[0]\n        plan.append((waypoint, RoadOption.LANEFOLLOW))\n        #   End condition for the behavior\n        if turn != 0 and reached_junction and len(plan) >= 3:\n            v_1 = vector(\n                plan[-2][0].transform.location,\n                plan[-1][0].transform.location)\n            v_2 = vector(\n                plan[-3][0].transform.location,\n                plan[-2][0].transform.location)\n            angle_wp = math.acos(\n                np.dot(v_1, v_2) / abs((np.linalg.norm(v_1) * np.linalg.norm(v_2))))\n            if angle_wp < threshold:\n                break\n        elif reached_junction and not plan[-1][0].is_intersection:\n            break\n\n    return plan, plan[-1][0]\n\n\ndef generate_target_waypoint_list_multilane(waypoint, change='left',  # pylint: disable=too-many-return-statements\n                                            distance_same_lane=10, distance_other_lane=25,\n                                            total_lane_change_distance=25, check=True,\n                                            lane_changes=1, step_distance=2):\n    \"\"\"\n    This methods generates a waypoint list which leads the vehicle to a parallel lane.\n    The change input must be 'left' or 'right', depending on which lane you want to change.\n\n    The default step distance between waypoints on the same lane is 2m.\n    The default step distance between the lane change is set to 25m.\n\n    @returns a waypoint list from the starting point to the end point on a right or left parallel lane.\n    The function might break before reaching the end point, if the asked behavior is impossible.\n    \"\"\"\n\n    plan = []\n    plan.append((waypoint, RoadOption.LANEFOLLOW))  # start position\n\n    option = RoadOption.LANEFOLLOW\n\n    # Same lane\n    distance = 0\n    while distance < distance_same_lane:\n        next_wps = plan[-1][0].next(step_distance)\n        if not next_wps:\n            return None, None\n        next_wp = next_wps[0]\n        distance += next_wp.transform.location.distance(plan[-1][0].transform.location)\n        plan.append((next_wp, RoadOption.LANEFOLLOW))\n\n    if change == 'left':\n        option = RoadOption.CHANGELANELEFT\n    elif change == 'right':\n        option = RoadOption.CHANGELANERIGHT\n    else:\n        # ERROR, input value for change must be 'left' or 'right'\n        return None, None\n\n    lane_changes_done = 0\n    lane_change_distance = total_lane_change_distance / lane_changes\n\n    # Lane change\n    while lane_changes_done < lane_changes:\n\n        # Move forward\n        next_wps = plan[-1][0].next(lane_change_distance)\n        if not next_wps:\n            return None, None\n        next_wp = next_wps[0]\n\n        # Get the side lane\n        if change == 'left':\n            if check and str(next_wp.lane_change) not in ['Left', 'Both']:\n                return None, None\n            side_wp = next_wp.get_left_lane()\n        else:\n            if check and str(next_wp.lane_change) not in ['Right', 'Both']:\n                return None, None\n            side_wp = next_wp.get_right_lane()\n\n        if not side_wp or side_wp.lane_type != carla.LaneType.Driving:\n            return None, None\n\n        # Update the plan\n        plan.append((side_wp, option))\n        lane_changes_done += 1\n\n    # Other lane\n    distance = 0\n    while distance < distance_other_lane:\n        next_wps = plan[-1][0].next(step_distance)\n        if not next_wps:\n            return None, None\n        next_wp = next_wps[0]\n        distance += next_wp.transform.location.distance(plan[-1][0].transform.location)\n        plan.append((next_wp, RoadOption.LANEFOLLOW))\n\n    target_lane_id = plan[-1][0].lane_id\n\n    return plan, target_lane_id\n\n\ndef generate_target_waypoint(waypoint, turn=0):\n    \"\"\"\n    This method follow waypoints to a junction and choose path based on turn input.\n    Turn input: LEFT -> -1, RIGHT -> 1, STRAIGHT -> 0\n    @returns a waypoint list according to turn input\n    \"\"\"\n    sampling_radius = 1\n    reached_junction = False\n    wp_list = []\n    while True:\n\n        wp_choice = waypoint.next(sampling_radius)\n        #   Choose path at intersection\n        if not reached_junction and (len(wp_choice) > 1 or wp_choice[0].is_junction):\n            reached_junction = True\n            waypoint = choose_at_junction(waypoint, wp_choice, turn)\n        else:\n            waypoint = wp_choice[0]\n        wp_list.append(waypoint)\n        #   End condition for the behavior\n        if reached_junction and not wp_list[-1].is_junction:\n            break\n    return wp_list[-1]\n\n\ndef generate_target_waypoint_in_route(waypoint, route):\n    \"\"\"\n    This method follow waypoints to a junction\n    @returns a waypoint list according to turn input\n    \"\"\"\n    target_waypoint = None\n    wmap = CarlaDataProvider.get_map()\n    reached_junction = False\n\n    # Get the route location\n    shortest_distance = float('inf')\n    for index, route_pos in enumerate(route):\n        route_location = route_pos[0].location\n        trigger_location = waypoint.transform.location\n\n        dist_to_route = trigger_location.distance(route_location)\n        if dist_to_route <= shortest_distance:\n            closest_index = index\n            shortest_distance = dist_to_route\n\n    route_location = route[closest_index][0].location\n    index = closest_index\n\n    for i in range(index, len(route)):\n        route_location = route[i][0].location\n        road_option = route[i][1]\n\n        # Enter the junction\n        if not reached_junction and (road_option in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n            reached_junction = True\n\n        # End condition for the behavior, at the end of the junction\n        if reached_junction and (road_option not in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)):\n            target_waypoint = route_location\n            break\n\n    return wmap.get_waypoint(target_waypoint)\n\n\ndef choose_at_junction(current_waypoint, next_choices, direction=0):\n    \"\"\"\n    This function chooses the appropriate waypoint from next_choices based on direction\n    \"\"\"\n    current_transform = current_waypoint.transform\n    current_location = current_transform.location\n    projected_location = current_location + \\\n        carla.Location(\n            x=math.cos(math.radians(current_transform.rotation.yaw)),\n            y=math.sin(math.radians(current_transform.rotation.yaw)))\n    current_vector = vector(current_location, projected_location)\n    cross_list = []\n    cross_to_waypoint = {}\n    for waypoint in next_choices:\n        waypoint = waypoint.next(10)[0]\n        select_vector = vector(current_location, waypoint.transform.location)\n        cross = np.cross(current_vector, select_vector)[2]\n        cross_list.append(cross)\n        cross_to_waypoint[cross] = waypoint\n    select_cross = None\n    if direction > 0:\n        select_cross = max(cross_list)\n    elif direction < 0:\n        select_cross = min(cross_list)\n    else:\n        select_cross = min(cross_list, key=abs)\n\n    return cross_to_waypoint[select_cross]\n\n\ndef get_intersection(ego_actor, other_actor):\n    \"\"\"\n    Obtain a intersection point between two actor's location\n    @return the intersection location\n    \"\"\"\n    waypoint = CarlaDataProvider.get_map().get_waypoint(ego_actor.get_location())\n    waypoint_other = CarlaDataProvider.get_map().get_waypoint(other_actor.get_location())\n    max_dist = float(\"inf\")\n    distance = float(\"inf\")\n    while distance <= max_dist:\n        max_dist = distance\n        current_location = waypoint.transform.location\n        waypoint_choice = waypoint.next(1)\n        #   Select the straighter path at intersection\n        if len(waypoint_choice) > 1:\n            max_dot = -1 * float('inf')\n            loc_projection = current_location + carla.Location(\n                x=math.cos(math.radians(waypoint.transform.rotation.yaw)),\n                y=math.sin(math.radians(waypoint.transform.rotation.yaw)))\n            v_current = vector(current_location, loc_projection)\n            for wp_select in waypoint_choice:\n                v_select = vector(current_location, wp_select.transform.location)\n                dot_select = np.dot(v_current, v_select)\n                if dot_select > max_dot:\n                    max_dot = dot_select\n                    waypoint = wp_select\n        else:\n            waypoint = waypoint_choice[0]\n        distance = current_location.distance(waypoint_other.transform.location)\n\n    return current_location\n\n\ndef detect_lane_obstacle(actor, extension_factor=3, margin=1.02):\n    \"\"\"\n    This function identifies if an obstacle is present in front of the reference actor\n    \"\"\"\n    world_actors = CarlaDataProvider.get_all_actors().filter('vehicle.*')\n    actor_bbox = actor.bounding_box\n    actor_transform = actor.get_transform()\n    actor_location = actor_transform.location\n    actor_vector = actor_transform.rotation.get_forward_vector()\n    actor_vector = np.array([actor_vector.x, actor_vector.y])\n    actor_vector = actor_vector / np.linalg.norm(actor_vector)\n    actor_vector = actor_vector * (extension_factor - 1) * actor_bbox.extent.x\n    actor_location = actor_location + carla.Location(actor_vector[0], actor_vector[1])\n    actor_yaw = actor_transform.rotation.yaw\n\n    is_hazard = False\n    for adversary in world_actors:\n        if adversary.id != actor.id and \\\n                actor_transform.location.distance(adversary.get_location()) < 50:\n            adversary_bbox = adversary.bounding_box\n            adversary_transform = adversary.get_transform()\n            adversary_loc = adversary_transform.location\n            adversary_yaw = adversary_transform.rotation.yaw\n            overlap_adversary = RotatedRectangle(\n                adversary_loc.x, adversary_loc.y,\n                2 * margin * adversary_bbox.extent.x, 2 * margin * adversary_bbox.extent.y, adversary_yaw)\n            overlap_actor = RotatedRectangle(\n                actor_location.x, actor_location.y,\n                2 * margin * actor_bbox.extent.x * extension_factor, 2 * margin * actor_bbox.extent.y, actor_yaw)\n            overlap_area = overlap_adversary.intersection(overlap_actor).area\n            if overlap_area > 0:\n                is_hazard = True\n                break\n\n    return is_hazard\n\n\ndef get_junction_topology(junction):\n    \"\"\"\n    Given a junction, returns a two list of waypoints corresponding to the entry\n    and exit lanes of the junction\n    \"\"\"\n    def get_lane_key(waypoint):\n        return str(waypoint.road_id) + '*' + str(waypoint.lane_id)\n\n    def get_junction_entry_wp(entry_wp):\n        while entry_wp.is_junction:\n            entry_wps = entry_wp.previous(0.2)\n            if len(entry_wps) == 0:\n                return None\n            entry_wp = entry_wps[0]\n        return entry_wp\n\n    def get_junction_exit_wp(exit_wp):\n        while exit_wp.is_junction:\n            exit_wps = exit_wp.next(0.2)\n            if len(exit_wps) == 0:\n                return None\n            exit_wp = exit_wps[0]\n        return exit_wp\n\n    used_entry_lanes = []\n    used_exit_lanes = []\n    entry_wps = []\n    exit_wps = []\n    for entry_wp, exit_wp in junction.get_waypoints(carla.LaneType.Driving):\n        entry_wp = get_junction_entry_wp(entry_wp)\n        if not entry_wp:\n            continue\n        if get_lane_key(entry_wp) not in used_entry_lanes:\n            used_entry_lanes.append(get_lane_key(entry_wp))\n            entry_wps.append(entry_wp)\n\n        exit_wp = get_junction_exit_wp(exit_wp)\n        if not exit_wp:\n            continue\n        if get_lane_key(exit_wp) not in used_exit_lanes:\n            used_exit_lanes.append(get_lane_key(exit_wp))\n            exit_wps.append(exit_wp)\n\n    return entry_wps, exit_wps\n\n\ndef filter_junction_wp_direction(reference_wp, wp_list, direction='opposite'):\n    \"\"\"\n    Given a list of entry / exit wps of a junction, filters them according to a specific direction,\n    returning all waypoint part of lanes that are at 'direction' with respect to the reference.\n    This might fail for complex junctions, as only the wp yaws is checked, not their relative positions\n    \"\"\"\n\n    filtered_wps = []\n    reference_yaw = reference_wp.transform.rotation.yaw\n    for wp in wp_list:\n        diff = (wp.transform.rotation.yaw - reference_yaw) % 360\n        if diff > 330.0:\n            wp_direction = 'ref'\n        elif diff > 225.0:\n            wp_direction = 'right'\n        elif diff > 135.0:\n            wp_direction = 'opposite'\n        elif diff > 30.0:\n            wp_direction = 'left'\n        else:\n            wp_direction = 'ref'\n\n        if wp_direction == direction:\n            filtered_wps.append(wp)\n\n    return filtered_wps\n\n\ndef get_closest_traffic_light(waypoint, traffic_lights=None):\n    \"\"\"\n    Returns the traffic light closest to the waypoint. The distance is computed between the\n    waypoint and the traffic light's bounding box.\n    Checks all traffic lights part of 'traffic_lights', or all the town ones, if None are passed.\n    \"\"\"\n    if not traffic_lights:\n        traffic_lights = CarlaDataProvider.get_all_actors().filter('*traffic_light*')\n\n    closest_dist = float('inf')\n    closest_tl = None\n\n    wp_location = waypoint.transform.location\n    for tl in traffic_lights:\n        tl_waypoints = tl.get_stop_waypoints()\n        for tl_waypoint in tl_waypoints:\n            distance = wp_location.distance(tl_waypoint.transform.location)\n            if distance < closest_dist:\n                closest_dist = distance\n                closest_tl = tl\n\n    return closest_tl\n\n\ndef get_offset_transform(transform, offset):\n    \"\"\"\n    This function adjusts the give transform by offset and returns the new transform.\n    \"\"\"\n    if offset != 0:\n        forward_vector = transform.rotation.get_forward_vector()\n        orthogonal_vector = carla.Vector3D(x=-forward_vector.y, y=forward_vector.x, z=forward_vector.z)\n        transform.location.x = transform.location.x + offset * orthogonal_vector.x\n        transform.location.y = transform.location.y + offset * orthogonal_vector.y\n    return transform\n\n\ndef get_troad_from_transform(actor_transform):\n    \"\"\"\n    This function finds the lateral road position (t) from actor_transform\n    \"\"\"\n    actor_loc = actor_transform.location\n    c_wp = CarlaDataProvider.get_map().get_waypoint(actor_loc)\n    left_lanes, right_lanes = [], []\n    # opendrive standard: (left ==> +ve lane_id) and (right ==> -ve lane_id)\n    ref_lane = CarlaDataProvider.get_map().get_waypoint_xodr(c_wp.road_id, 0, c_wp.s)\n    for i in range(-50, 50):\n        _wp = CarlaDataProvider.get_map().get_waypoint_xodr(c_wp.road_id, i, c_wp.s)\n        if _wp:\n            if i < 0:\n                left_lanes.append(_wp)\n            elif i > 0:\n                right_lanes.append(_wp)\n\n    if left_lanes:\n        left_lane_ids = [ln.lane_id for ln in left_lanes]\n        lm_id = min(left_lane_ids)\n        lm_lane = left_lanes[left_lane_ids.index(lm_id)]\n        lm_lane_offset = lm_lane.lane_width / 2\n    else:\n        lm_lane, lm_lane_offset = ref_lane, 0\n    lm_tr = get_offset_transform(carla.Transform(lm_lane.transform.location, lm_lane.transform.rotation),\n                                 lm_lane_offset)\n    distance_from_lm_lane_edge = lm_tr.location.distance(actor_loc)\n    distance_from_lm_lane_ref_lane = lm_tr.location.distance(ref_lane.transform.location)\n    if right_lanes:\n        right_lane_ids = [ln.lane_id for ln in right_lanes]\n        rm_id = max(right_lane_ids)\n        rm_lane = right_lanes[right_lane_ids.index(rm_id)]\n        rm_lane_offset = -rm_lane.lane_width / 2\n    else:\n        rm_lane, rm_lane_offset = ref_lane, -distance_from_lm_lane_ref_lane\n    distance_from_rm_lane_edge = get_offset_transform(carla.Transform(rm_lane.transform.location,\n                                                                      rm_lane.transform.rotation),\n                                                      rm_lane_offset).location.distance(actor_loc)\n    t_road = ref_lane.transform.location.distance(actor_loc)\n    if not right_lanes or not left_lanes:\n        closest_road_edge = min(distance_from_lm_lane_edge, distance_from_rm_lane_edge)\n        if closest_road_edge == distance_from_lm_lane_edge:\n            t_road = -1*t_road\n    else:\n        if c_wp.lane_id < 0:\n            t_road = -1*t_road\n\n    return t_road\n\n\ndef get_distance_between_actors(current, target, distance_type=\"euclidianDistance\", freespace=False,\n                                global_planner=None):\n    \"\"\"\n    This function finds the distance between actors for different use cases described by distance_type and freespace\n    attributes\n    \"\"\"\n\n    target_transform = CarlaDataProvider.get_transform(target)\n    current_transform = CarlaDataProvider.get_transform(current)\n    target_wp = CarlaDataProvider.get_map().get_waypoint(target_transform.location)\n    current_wp = CarlaDataProvider.get_map().get_waypoint(current_transform.location)\n\n    extent_sum_x, extent_sum_y = 0, 0\n    if freespace:\n        if isinstance(target, (carla.Vehicle, carla.Walker)):\n            extent_sum_x = target.bounding_box.extent.x + current.bounding_box.extent.x\n            extent_sum_y = target.bounding_box.extent.y + current.bounding_box.extent.y\n    if distance_type == \"longitudinal\":\n        if not current_wp.road_id == target_wp.road_id:\n            distance = 0\n            # Get the route\n            route = global_planner.trace_route(current_transform.location, target_transform.location)\n            # Get the distance of the route\n            for i in range(1, len(route)):\n                curr_loc = route[i][0].transform.location\n                prev_loc = route[i - 1][0].transform.location\n                distance += curr_loc.distance(prev_loc)\n        else:\n            distance = abs(current_wp.s - target_wp.s)\n        if freespace:\n            distance = distance - extent_sum_x\n    elif distance_type == \"lateral\":\n        target_t = get_troad_from_transform(target_transform)\n        current_t = get_troad_from_transform(current_transform)\n        distance = abs(target_t - current_t)\n        if freespace:\n            distance = distance - extent_sum_y\n\n    elif distance_type in [\"cartesianDistance\", \"euclidianDistance\"]:\n        distance = target_transform.location.distance(current_transform.location)\n        if freespace:\n            distance = distance - extent_sum_x\n    else:\n        raise TypeError(\"unknown distance_type: {}\".format(distance_type))\n\n    # distance will be negative for feeespace when there is overlap condition\n    # truncate to 0.0 when this happens\n    distance = 0.0 if distance < 0.0 else distance\n\n    return distance\n\n\ndef get_same_dir_lanes(waypoint):\n    \"\"\"\n    Gets all the lanes with the same direction of the road of a wp.\n    Ordered from the edge lane to the center one (from outwards to inwards)\n    \"\"\"\n    same_dir_wps = [waypoint]\n\n    # Check roads on the right\n    right_wp = waypoint\n    while True:\n        possible_right_wp = right_wp.get_right_lane()\n        if possible_right_wp is None or possible_right_wp.lane_type != carla.LaneType.Driving:\n            break\n        right_wp = possible_right_wp\n        same_dir_wps.append(right_wp)\n\n    # Check roads on the left\n    left_wp = waypoint\n    while True:\n        possible_left_wp = left_wp.get_left_lane()\n        if possible_left_wp is None or possible_left_wp.lane_type != carla.LaneType.Driving:\n            break\n        if possible_left_wp.lane_id * left_wp.lane_id < 0:\n            break\n        left_wp = possible_left_wp\n        same_dir_wps.insert(0, left_wp)\n\n    return same_dir_wps\n\n\ndef get_opposite_dir_lanes(waypoint):\n    \"\"\"\n    Gets all the lanes with opposite direction of the road of a wp\n    Ordered from the center lane to the edge one (from inwards to outwards)\n    \"\"\"\n    other_dir_wps = []\n    other_dir_wp = None\n\n    # Get the first lane of the opposite direction\n    left_wp = waypoint\n    while True:\n        possible_left_wp = left_wp.get_left_lane()\n        if possible_left_wp is None:\n            break\n        if possible_left_wp.lane_id * left_wp.lane_id < 0:\n            other_dir_wp = possible_left_wp\n            break\n        left_wp = possible_left_wp\n\n    if not other_dir_wp:\n        return other_dir_wps\n\n    # Check roads on the right\n    right_wp = other_dir_wp\n    while True:\n        if right_wp.lane_type == carla.LaneType.Driving:\n            other_dir_wps.append(right_wp)\n        possible_right_wp = right_wp.get_right_lane()\n        if possible_right_wp is None:\n            break\n        right_wp = possible_right_wp\n\n    return other_dir_wps\n\n\nclass RotatedRectangle(object):\n\n    \"\"\"\n    This class contains method to draw rectangle and find intersection point.\n    \"\"\"\n\n    def __init__(self, c_x, c_y, width, height, angle):\n        self.c_x = c_x\n        self.c_y = c_y\n        self.w = width      # pylint: disable=invalid-name\n        self.h = height     # pylint: disable=invalid-name\n        self.angle = angle\n\n    def get_contour(self):\n        \"\"\"\n        create contour\n        \"\"\"\n        w = self.w\n        h = self.h\n        c = shapely.geometry.box(-w / 2.0, -h / 2.0, w / 2.0, h / 2.0)\n        rc = shapely.affinity.rotate(c, self.angle)\n        return shapely.affinity.translate(rc, self.c_x, self.c_y)\n\n    def intersection(self, other):\n        \"\"\"\n        Obtain a intersection point between two contour.\n        \"\"\"\n        return self.get_contour().intersection(other.get_contour())\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/tools/scenario_parser.py",
    "content": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\"\"\nThis module provides access to a scenario configuration parser\n\"\"\"\n\nimport glob\nimport os\nimport xml.etree.ElementTree as ET\n\nimport carla\n\nfrom srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData\nfrom srunner.scenarioconfigs.route_scenario_configuration import RouteConfiguration\n\n\nclass ScenarioConfigurationParser(object):\n\n    \"\"\"\n    Pure static class providing access to parser methods for scenario configuration files (*.xml)\n    \"\"\"\n\n    @staticmethod\n    def parse_scenario_configuration(scenario_name, additional_config_file_name):\n        \"\"\"\n        Parse all scenario configuration files at srunner/examples and the additional\n        config files, providing a list of ScenarioConfigurations @return\n\n        If scenario_name starts with \"group:\" all scenarios that\n        have that type are parsed and returned. Otherwise only the\n        scenario that matches the scenario_name is parsed and returned.\n        \"\"\"\n\n        if scenario_name.startswith(\"group:\"):\n            scenario_group = True\n            scenario_name = scenario_name[6:]\n        else:\n            scenario_group = False\n\n        scenario_configurations = []\n\n        list_of_config_files = glob.glob(\"{}/srunner/examples/*.xml\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        if additional_config_file_name != '':\n            list_of_config_files.append(additional_config_file_name)\n\n        for file_name in list_of_config_files:\n            tree = ET.parse(file_name)\n\n            for scenario in tree.iter(\"scenario\"):\n\n                scenario_config_name = scenario.attrib.get('name', None)\n                scenario_config_type = scenario.attrib.get('type', None)\n\n                # Check that the scenario is the correct one\n                if not scenario_group and scenario_config_name != scenario_name:\n                    continue\n                # Check that the scenario is of the correct type\n                elif scenario_group and scenario_config_type != scenario_name:\n                    continue\n\n                config = ScenarioConfiguration()\n                config.town = scenario.attrib.get('town')\n                config.name = scenario_config_name\n                config.type = scenario_config_type\n\n                for elem in scenario.getchildren():\n                    # Elements with special parsing\n                    if elem.tag == 'ego_vehicle':\n                        config.ego_vehicles.append(ActorConfigurationData.parse_from_node(elem, 'hero'))\n                        config.trigger_points.append(config.ego_vehicles[-1].transform)\n                    elif elem.tag == 'other_actor':\n                        config.other_actors.append(ActorConfigurationData.parse_from_node(elem, 'scenario'))\n                    elif elem.tag == 'weather':\n                        for weather_attrib in elem.attrib:\n                            if hasattr(config.weather, weather_attrib):\n                                setattr(config.weather, weather_attrib, float(elem.attrib[weather_attrib]))\n                            else:\n                                print(f\"WARNING: Ignoring '{weather_attrib}', as it isn't a weather parameter\")\n\n                    elif elem.tag == 'route':\n                        route_conf = RouteConfiguration()\n                        route_conf.parse_xml(elem)\n                        config.route = route_conf\n\n                    # Any other possible element, add it as a config attribute\n                    else:\n                        config.other_parameters[elem.tag] = elem.attrib\n\n                scenario_configurations.append(config)\n        return scenario_configurations\n\n    @staticmethod\n    def get_list_of_scenarios(additional_config_file_name):\n        \"\"\"\n        Parse *all* config files and provide a list with all scenarios @return\n        \"\"\"\n\n        list_of_config_files = glob.glob(\"{}/srunner/examples/*.xml\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        list_of_config_files += glob.glob(\"{}/srunner/examples/*.xosc\".format(os.getenv('SCENARIO_RUNNER_ROOT', \"./\")))\n        if additional_config_file_name != '':\n            list_of_config_files.append(additional_config_file_name)\n\n        scenarios = []\n        for file_name in list_of_config_files:\n            if \".xosc\" in file_name:\n                tree = ET.parse(file_name)\n                scenarios.append(\"{} (OpenSCENARIO)\".format(tree.find(\"FileHeader\").attrib.get('description', None)))\n            else:\n                tree = ET.parse(file_name)\n                for scenario in tree.iter(\"scenario\"):\n                    scenarios.append(scenario.attrib.get('name', None))\n\n        return scenarios\n"
  },
  {
    "path": "close_loop/VAD_MomAD/scenario_runner/srunner/utilities/code_check_and_formatting.sh",
    "content": "#!/bin/bash\n\nautopep8 scenario_runner.py --in-place --max-line-length=120\nautopep8 srunner/scenariomanager/*.py --in-place --max-line-length=120 --ignore=E731\nautopep8 srunner/scenariomanager/actorcontrols/*.py --in-place --max-line-length=120\nautopep8 srunner/scenariomanager/scenarioatomics/*.py --in-place --max-line-length=120\nautopep8 srunner/scenarios/*.py --in-place --max-line-length=120\nautopep8 srunner/autoagents/*.py --in-place --max-line-length=120\nautopep8 srunner/tools/*.py --in-place --max-line-length=120\nautopep8 srunner/scenarioconfigs/*.py --in-place --max-line-length=120\n\n\npylint --rcfile=.pylintrc --disable=I srunner/scenariomanager/\npylint --rcfile=.pylintrc srunner/scenarios/\npylint --rcfile=.pylintrc srunner/autoagents/\npylint --rcfile=.pylintrc srunner/tools/\npylint --rcfile=.pylintrc srunner/scenarioconfigs/\npylint --rcfile=.pylintrc scenario_runner.py\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/ability_benchmark.py",
    "content": "import json\nimport carla\nimport argparse\nimport xml.etree.ElementTree as ET\nfrom agents.navigation.global_route_planner import GlobalRoutePlanner\nimport os\nimport atexit\nimport subprocess\nimport time\nimport random\n\nAbility = {\n    \"Overtaking\":['Accident', 'AccidentTwoWays', 'ConstructionObstacle', 'ConstructionObstacleTwoWays', 'HazardAtSideLaneTwoWays', 'HazardAtSideLane', 'ParkedObstacleTwoWays', 'ParkedObstacle', 'VehicleOpensDoorTwoWays'],\n    \"Merging\": ['CrossingBicycleFlow', 'EnterActorFlow', 'HighwayExit', 'InterurbanActorFlow', 'HighwayCutIn', 'InterurbanAdvancedActorFlow', 'MergerIntoSlowTrafficV2', 'MergerIntoSlowTraffic', 'NonSignalizedJunctionLeftTurn', 'NonSignalizedJunctionRightTurn', 'NonSignalizedJunctionLeftTurnEnterFlow', 'ParkingExit', 'SequentialLaneChange', 'SignalizedJunctionLeftTurn', 'SignalizedJunctionRightTurn', 'SignalizedJunctionLeftTurnEnterFlow'],\n    \"Emergency_Brake\": ['BlockedIntersection', 'DynamicObjectCrossing', 'HardBreakRoute', 'OppositeVehicleTakingPriority', 'OppositeVehicleRunningRedLight', 'ParkingCutIn', 'PedestrianCrossing', 'ParkingCrossingPedestrian', 'StaticCutIn', 'VehicleTurningRoute', 'VehicleTurningRoutePedestrian', 'ControlLoss'],\n    \"Give_Way\": ['InvadingTurn', 'YieldToEmergencyVehicle'],\n    \"Traffic_Signs\": ['BlockedIntersection', 'OppositeVehicleTakingPriority', 'OppositeVehicleRunningRedLight', 'PedestrianCrossing', 'VehicleTurningRoute', 'VehicleTurningRoutePedestrian', 'EnterActorFlow', 'CrossingBicycleFlow', 'NonSignalizedJunctionLeftTurn', 'NonSignalizedJunctionRightTurn', 'NonSignalizedJunctionLeftTurnEnterFlow', 'OppositeVehicleTakingPriority', 'OppositeVehicleRunningRedLight', 'PedestrianCrossing', 'SignalizedJunctionLeftTurn', 'SignalizedJunctionRightTurn', 'SignalizedJunctionLeftTurnEnterFlow', 'T_Junction', 'VanillaNonSignalizedTurn', 'VanillaSignalizedTurnEncounterGreenLight', 'VanillaSignalizedTurnEncounterRedLight', 'VanillaNonSignalizedTurnEncounterStopsign', 'VehicleTurningRoute', 'VehicleTurningRoutePedestrian']\n}\n\ndef get_infraction_status(record):\n    for infraction,  value in record['infractions'].items():\n        if infraction == \"min_speed_infractions\":\n            continue\n        elif len(value) > 0:\n            return True\n    return False\n\ndef update_Ability(scenario_name, Ability_Statistic, status):\n    for ability, scenarios in Ability.items():\n        if scenario_name in scenarios:\n            Ability_Statistic[ability][1] += 1\n            if status:\n                Ability_Statistic[ability][0] += 1\n    pass\n\ndef update_Success(scenario_name, Success_Statistic, status):\n    if scenario_name not in Success_Statistic:\n        if status:\n            Success_Statistic[scenario_name] = [1, 1]\n        else:\n            Success_Statistic[scenario_name] = [0, 1]\n    else:\n        Success_Statistic[scenario_name][1] += 1\n        if status:\n            Success_Statistic[scenario_name][0] += 1\n    pass\n\ndef get_position(xml_route):\n    waypoints_elem = xml_route.find('waypoints')\n    keypoints = waypoints_elem.findall('position')\n    return [carla.Location(float(pos.get('x')), float(pos.get('y')), float(pos.get('z'))) for pos in keypoints]\n\ndef get_route_result(records, route_id):\n    for record in records:\n        record_route_id = record['route_id'].split('_')[1]\n        if route_id == record_route_id:\n            return record\n    return None\n\ndef get_waypoint_route(locs, grp):\n    route = []\n    for i in range(len(locs) - 1):\n        loc = locs[i]\n        loc_next = locs[i + 1]\n        interpolated_trace = grp.trace_route(loc, loc_next)\n        for wp, _ in interpolated_trace:\n            route.append(wp)\n    return route\n\ndef main(args):\n    routes_file = args.file \n    result_file = args.result_file\n    Ability_Statistic = {}\n    crash_route_list = []\n    for key in Ability:\n        Ability_Statistic[key] = [0, 0.]\n    Success_Statistic = {}\n    \n    with open(result_file, 'r') as f:\n        data = json.load(f)\n    records = data[\"_checkpoint\"][\"records\"]\n                    \n    tree = ET.parse(routes_file)\n    root = tree.getroot()\n    routes = root.findall('route')\n    sorted_routes = sorted(routes, key=lambda x: x.get('town'))\n    \n    carla_path = os.environ[\"CARLA_ROOT\"]\n    cmd1 = f\"{os.path.join(carla_path, 'CarlaUE4.sh')} -RenderOffScreen -nosound -carla-rpc-port={args.port}\"\n    server = subprocess.Popen(cmd1, shell=True, preexec_fn=os.setsid)\n    print(cmd1, server.returncode, flush=True)\n    time.sleep(10)\n    client = carla.Client(args.host, args.port)\n    client.set_timeout(300)\n    \n    current_town = sorted_routes[0].get('town')\n    world = client.load_world(current_town)\n    carla_map = world.get_map()\n    grp = GlobalRoutePlanner(carla_map, 1.0)\n    for route in sorted_routes:\n        scenarios = route.find('scenarios')\n        scenario_name = scenarios.find('scenario').get(\"type\")\n        route_id = route.get('id')\n        route_record = get_route_result(records, route_id)\n        if route_record is None:\n            crash_route_list.append((scenario_name, route_id))\n            print('No result record of route', route_id, \"in the result file\")\n            continue\n        if route_record[\"status\"] == 'Completed' or route_record[\"status\"] == \"Perfect\":\n            if get_infraction_status(route_record):\n                record_success_status = False\n            else:\n                record_success_status = True\n        else:\n            record_success_status = False\n        update_Ability(scenario_name, Ability_Statistic, record_success_status)\n        update_Success(scenario_name, Success_Statistic, record_success_status)\n        # if scenario_name in Ability[\"Traffic_Signs\"] and (scenario_name in Ability[\"Merging\"] or scenario_name in Ability[\"Emergency_Brake\"]):\n        # Only these three 'Ability's intersect\n        if scenario_name in Ability[\"Traffic_Signs\"]:\n            # Only these three 'Ability's intersect\n            if route.get('town') != current_town:\n                current_town = route.get('town')\n                print(\"Loading the town:\", current_town)\n                world = client.load_world(current_town)\n                print(\"successfully load the town:\", current_town)\n            carla_map = world.get_map()\n            grp = GlobalRoutePlanner(carla_map, 1.0)\n            location_list = get_position(route)\n            waypoint_route = get_waypoint_route(location_list, grp)\n            count = 0\n            for wp in waypoint_route:\n                count += 1\n                if wp.is_junction:\n                    break \n            if not wp.is_junction:\n                raise RuntimeError(\"This route does not contain any junction-waypoint!\")\n            # +8 to ensure the ego pass the trigger volume\n            junction_completion = float(count+8) / float(len(waypoint_route))\n            record_completion = route_record[\"scores\"][\"score_route\"] / 100.0\n            stop_infraction = route_record[\"infractions\"][\"stop_infraction\"]\n            red_light_infraction = route_record[\"infractions\"][\"red_light\"]\n            if record_completion > junction_completion and not stop_infraction and not red_light_infraction:\n                Ability_Statistic['Traffic_Signs'][0] += 1\n                Ability_Statistic['Traffic_Signs'][1] += 1\n            else:\n                Ability_Statistic['Traffic_Signs'][1] += 1\n        else:\n            pass\n        \n    Ability_Res = {}\n    for ability, statis in Ability_Statistic.items():\n        Ability_Res[ability] = float(statis[0])/float(statis[1])\n        \n    for key, value in Ability_Res.items():\n        print(key, \": \", value)\n    \n    Ability_Res['mean'] = sum(list(Ability_Res.values())) / 5\n    Ability_Res['crashed'] = crash_route_list\n    with open(f\"{result_file.split('.')[0]}_ability.json\", 'w') as file:\n        json.dump(Ability_Res, file, indent=4)\n        \n    Success_Res = {}\n    Route_num = 0\n    Succ_Route_num = 0\n    for scenario, statis in Success_Statistic.items():\n        Success_Res[scenario] = float(statis[0])/float(statis[1])\n        Succ_Route_num += statis[0]\n        Route_num += statis[1]\n    assert len(crash_route_list) == 220 - float(Route_num)\n    print(f\"Mean:{Ability_Res['mean']}\")\n    print(f'Crashed Route num: {len(crash_route_list)}, Crashed Route ID: {crash_route_list}')\n    print('Finished!')\n\nif __name__=='__main__':\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('-f', '--file', nargs=None, default=\"leaderboard/data/bench2drive220.xml\", help='route file')\n    argparser.add_argument('-r', '--result_file', nargs=None, default=\"\", help='result json file')\n    argparser.add_argument('-t', '--host', default='localhost', help='IP of the host server (default: localhost)')\n    argparser.add_argument('-p', '--port', nargs=1, default=2000, help='carla rpc port')\n    args = argparser.parse_args()\n    main(args)\n    "
  },
  {
    "path": "close_loop/VAD_MomAD/tools/check_carla.md",
    "content": "# Check if carla is working properly\n\n### Verification Process\n1. Run in terminal 1\n    ```bash\n        ./CarlaUE4.sh -RenderOffScreen -nosound -fps=10 -carla-rpc-port=2000\n    ```\n2. Run in terninal 2\n    ```python\n        import carla\n        client = carla.Client('localhost', 2000)\n        client.set_timeout(100.0)\n        list_map = client.get_available_maps()\n        client_version = client.get_client_version()\n        server_version = client.get_server_version()\n        world = client.get_world()\n        world = client.load_world('Town02')\n    ```\n3. If executed successfully, carla runs successfully.\n\n### Summary of some issues\n- The normal startup of carla is **blocking**. \n\n- If the process ends immediately, please check **vulkaninfo**\n    - if vulkaninfo does not exist\n        ```bash\n            apt install vulkan-tools # \tvulkaninfo\n\t        apt install libgeos-dev\n        ``` \n    - if **test only** appears, please check Ubuntu system version\n        - A100/H100/A800/H800 requires a newer version of vulkaninfo, and therefore requires Ubuntu 22.04\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/clean_carla.sh",
    "content": "#!/bin/bash\nkillall -9 -r CarlaUE4-Linux\nps -ef | grep \"carla-rpc-port\" | awk '{print $2}' | xargs kill > /dev/null 2>&1 &\nps -ef | grep \"run_evaluation\" | awk '{print $2}' | xargs kill > /dev/null 2>&1 &\nps -ef | grep \"leaderboard_evaluator\" | awk '{print $2}' | xargs kill > /dev/null 2>&1 &\nwait\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/data_collect.py",
    "content": "from srunner.scenariomanager.carla_data_provider import CarlaDataProvider\nfrom leaderboard.envs.sensor_interface import SensorInterface, CallBack, OpenDriveMapReader, SpeedometerReader\nimport cv2\nimport json\nimport numpy as np\nimport xml.etree.ElementTree as ET\nimport carla\nimport gzip\nfrom easydict import EasyDict\nimport math\nimport h5py\nimport laspy\nfrom utils import build_projection_matrix, convert_depth, get_relative_transform, normalize_angle, build_skeleton,  get_matrix, calculate_cube_vertices, compute_2d_distance\nfrom utils import DIS_CAR_SAVE, DIS_WALKER_SAVE, DIS_SIGN_SAVE, DIS_LIGHT_SAVE\n\nEARTH_RADIUS_EQUA = 6378137.0\n\nclass Env_Manager():\n    \n    frame_rate = 10.0 \n\n    def tick(self, input_data):\n        # control\n        control = self.manager.ego_vehicles[0].get_control()\n\n        # camera_bgr\n        cam_bgr_front = input_data['CAM_FRONT'][1][:, :, :3]\n        cam_bgr_front_left = input_data['CAM_FRONT_LEFT'][1][:, :, :3]\n        cam_bgr_front_right = input_data['CAM_FRONT_RIGHT'][1][:, :, :3]\n        cam_bgr_back = input_data['CAM_BACK'][1][:, :, :3]\n        cam_bgr_back_left = input_data['CAM_BACK_LEFT'][1][:, :, :3]\n        cam_bgr_back_right = input_data['CAM_BACK_RIGHT'][1][:, :, :3]\n        cam_bgr_top_down = input_data['TOP_DOWN'][1][:, :, :3]\n\n        # radar\n        radar_front = input_data['RADAR_FRONT'][1].astype(np.float16)\n        radar_front_left = input_data['RADAR_FRONT_LEFT'][1].astype(np.float16)\n        radar_front_right = input_data['RADAR_FRONT_RIGHT'][1].astype(np.float16)\n        radar_back_left = input_data['RADAR_BACK_LEFT'][1].astype(np.float16)\n        radar_back_right = input_data['RADAR_BACK_RIGHT'][1].astype(np.float16)\n\n        # lidar\n        lidar = input_data['LIDAR_TOP']\n        lidar_seg = input_data['LIDAR_TOP_SEG']\n\n        def lidar_to_ego_coordinate(lidar):\n            \"\"\"\n            Converts the LiDAR points given by the simulator into the ego agents\n            coordinate system\n            :param config: GlobalConfig, used to read out lidar orientation and location\n            :param lidar: the LiDAR point cloud as provided in the input of run_step\n            :return: lidar where the points are w.r.t. 0/0/0 of the car and the carla\n            coordinate system.\n            \"\"\"\n            lidar_rot = [0.0, 0.0, 0.0]\n            lidar_pos = [-0.39, 0.0, 1.84]\n\n            yaw = np.deg2rad(lidar_rot[2])\n            rotation_matrix = np.array([[np.cos(yaw), -np.sin(yaw), 0.0], [np.sin(yaw), np.cos(yaw), 0.0], [0.0, 0.0, 1.0]])\n\n            translation = np.array(lidar_pos)\n\n            # The double transpose is a trick to compute all the points together.\n            ego_lidar = (rotation_matrix @ lidar[1][:, :3].T).T + translation\n\n            return ego_lidar\n        \n        lidar = lidar_to_ego_coordinate(lidar)\n        lidar_360 = lidar\n        \n        bounding_boxes = self.get_bounding_boxes(lidar=lidar_360, radar=radar_front)\n        sensors_anno = self.get_sensors_anno()\n        \n        self.last_lidar = lidar\n        self.last_ego_transform = self.manager.ego_vehicles[0].get_transform()\n        # gps/imu\n        gps = input_data['GPS'][1][:2]\n        speed = input_data['SPEED'][1]['speed']\n        compass = input_data['IMU'][1][-1]\n        acceleration = input_data['IMU'][1][:3]\n        angular_velocity = input_data['IMU'][1][3:6]\n\n        # cam_bgr_depth\n        cam_bgr_front_depth = input_data['CAM_FRONT_DEPTH'][1][:, :, :3]\n        cam_bgr_front_left_depth = input_data['CAM_FRONT_LEFT_DEPTH'][1][:, :, :3]\n        cam_bgr_front_right_depth = input_data['CAM_FRONT_RIGHT_DEPTH'][1][:, :, :3]\n        cam_bgr_back_depth = input_data['CAM_BACK_DEPTH'][1][:, :, :3]\n        cam_bgr_back_left_depth = input_data['CAM_BACK_LEFT_DEPTH'][1][:, :, :3]\n        cam_bgr_back_right_depth = input_data['CAM_BACK_RIGHT_DEPTH'][1][:, :, :3]\n\n        # cam_sem_seg\n        cam_front_sem_seg = input_data[\"CAM_FRONT_SEM_SEG\"][1][:, :, 2]\n        cam_front_left_sem_seg = input_data[\"CAM_FRONT_LEFT_SEM_SEG\"][1][:, :, 2]\n        cam_front_right_sem_seg = input_data[\"CAM_FRONT_RIGHT_SEM_SEG\"][1][:, :, 2]\n        cam_back_sem_seg = input_data[\"CAM_BACK_SEM_SEG\"][1][:, :, 2]\n        cam_back_left_sem_seg = input_data[\"CAM_BACK_LEFT_SEM_SEG\"][1][:, :, 2]\n        cam_back_right_sem_seg = input_data[\"CAM_BACK_RIGHT_SEM_SEG\"][1][:, :, 2]\n\n        # cam_ins_seg\n        cam_front_ins_seg = input_data[\"CAM_FRONT_INS_SEG\"][1]\n        cam_front_left_ins_seg = input_data[\"CAM_FRONT_LEFT_INS_SEG\"][1]\n        cam_front_right_ins_seg = input_data[\"CAM_FRONT_RIGHT_INS_SEG\"][1]\n        cam_back_ins_seg = input_data[\"CAM_BACK_INS_SEG\"][1]\n        cam_back_left_ins_seg = input_data[\"CAM_BACK_LEFT_INS_SEG\"][1]\n        cam_back_right_ins_seg = input_data[\"CAM_BACK_RIGHT_INS_SEG\"][1]\n        \n        # cam_gray_depth, 16 bit would be ideal, but we can't afford the extra storage.\n        cam_gray_front_depth = convert_depth(cam_bgr_front_depth)\n        cam_gray_front_left_depth = convert_depth(cam_bgr_front_left_depth)\n        cam_gray_front_right_depth = convert_depth(cam_bgr_front_right_depth)\n        cam_gray_back_depth = convert_depth(cam_bgr_back_depth)\n        cam_gray_back_left_depth = convert_depth(cam_bgr_back_left_depth)\n        cam_gray_back_right_depth = convert_depth(cam_bgr_back_right_depth)\n        \n        # weather\n        weather = self._weather_to_dict(self.world.get_weather())\n\n        self.cam_bgr_mapping = {\n            'CAM_FRONT': 'cam_bgr_front',\n            'CAM_FRONT_LEFT': 'cam_bgr_front_left',\n            'CAM_FRONT_RIGHT': 'cam_bgr_front_right',\n            'CAM_BACK': 'cam_bgr_back',\n            'CAM_BACK_LEFT': 'cam_bgr_back_left',\n            'CAM_BACK_RIGHT': 'cam_bgr_back_right',\n        }\n\n        self.cam_bgr_depth_mapping = {\n            'CAM_FRONT': 'cam_bgr_front_depth',\n            'CAM_FRONT_LEFT': 'cam_bgr_front_left_depth',\n            'CAM_FRONT_RIGHT': 'cam_bgr_front_right_depth',\n            'CAM_BACK': 'cam_bgr_back_depth',\n            'CAM_BACK_LEFT': 'cam_bgr_back_left_depth',\n            'CAM_BACK_RIGHT': 'cam_bgr_back_right_depth',\n\n        }\n\n        self.cam_gray_depth_mapping = {\n            'CAM_FRONT': 'cam_gray_front_depth',\n            'CAM_FRONT_LEFT': 'cam_gray_front_left_depth',\n            'CAM_FRONT_RIGHT': 'cam_gray_front_right_depth',\n            'CAM_BACK': 'cam_gray_back_depth',\n            'CAM_BACK_LEFT': 'cam_gray_back_left_depth',\n            'CAM_BACK_RIGHT': 'cam_gray_back_right_depth',\n        }\n\n        self.cam_seg_mapping = {\n            'CAM_FRONT': 'cam_front_sem_seg',\n            'CAM_FRONT_LEFT': 'cam_front_left_sem_seg',\n            'CAM_FRONT_RIGHT': 'cam_front_right_sem_seg',\n            'CAM_BACK': 'cam_back_sem_seg',\n            'CAM_BACK_LEFT': 'cam_back_left_sem_seg',\n            'CAM_BACK_RIGHT': 'cam_back_right_sem_seg',\n        }\n\n        self.cam_ins_mapping = {\n            'CAM_FRONT': 'cam_front_ins_seg',\n            'CAM_FRONT_LEFT': 'cam_front_left_ins_seg',\n            'CAM_FRONT_RIGHT': 'cam_front_right_ins_seg',\n            'CAM_BACK': 'cam_back_ins_seg',\n            'CAM_BACK_LEFT': 'cam_back_left_ins_seg',\n            'CAM_BACK_RIGHT': 'cam_back_right_ins_seg',\n        }\n\n        self.radar_mapping = {\n            'RADAR_FRONT': 'radar_front',\n            'RADAR_FRONT_LEFT': 'radar_front_left',\n            'RADAR_FRONT_RIGHT': 'radar_front_right',\n            'RADAR_BACK_LEFT': 'radar_back_left',\n            'RADAR_BACK_RIGHT': 'radar_back_right',\n        }\n\n        self.cam_yaw_mapping = {\n            'CAM_FRONT': 0.0,\n            'CAM_FRONT_LEFT': -55.0,\n            'CAM_FRONT_RIGHT': 55.0,\n            'CAM_BACK': 180.0,\n            'CAM_BACK_LEFT': -110.0,\n            'CAM_BACK_RIGHT': 110.0,\n        }\n\n        results = {\n                # cam_bgr\n                'cam_bgr_front': cam_bgr_front,\n                'cam_bgr_front_left': cam_bgr_front_left,\n                'cam_bgr_front_right': cam_bgr_front_right,\n                'cam_bgr_back': cam_bgr_back,\n                'cam_bgr_back_left': cam_bgr_back_left,\n                'cam_bgr_back_right': cam_bgr_back_right,\n                'cam_bgr_top_down': cam_bgr_top_down,\n                # cam_sem_seg\n                'cam_front_sem_seg': cam_front_sem_seg,\n                'cam_front_left_sem_seg': cam_front_left_sem_seg,\n                'cam_front_right_sem_seg': cam_front_right_sem_seg,\n                'cam_back_sem_seg': cam_back_sem_seg,\n                'cam_back_left_sem_seg': cam_back_left_sem_seg,\n                'cam_back_right_sem_seg': cam_back_right_sem_seg,\n                # cam_ins_seg\n                'cam_front_ins_seg': cam_front_ins_seg,\n                'cam_front_left_ins_seg': cam_front_left_ins_seg,\n                'cam_front_right_ins_seg': cam_front_right_ins_seg,\n                'cam_back_ins_seg': cam_back_ins_seg,\n                'cam_back_left_ins_seg': cam_back_left_ins_seg,\n                'cam_back_right_ins_seg': cam_back_right_ins_seg,\n\n                # cam_gray_depth\n                # save the original bgr depth, please remember to post-process the depth\n                'cam_bgr_front_depth': cam_bgr_front_depth,\n                'cam_bgr_front_left_depth' : cam_bgr_front_left_depth,\n                'cam_bgr_front_right_depth': cam_bgr_front_right_depth,\n                'cam_bgr_back_depth': cam_bgr_back_depth,\n                'cam_bgr_back_left_depth': cam_bgr_back_left_depth,\n                'cam_bgr_back_right_depth': cam_bgr_back_right_depth,\n                \n                'cam_gray_front_depth': cam_gray_front_depth,\n                'cam_gray_front_left_depth': cam_gray_front_left_depth,\n                'cam_gray_front_right_depth': cam_gray_front_right_depth,\n                'cam_gray_back_depth': cam_gray_back_depth,\n                'cam_gray_back_left_depth': cam_gray_back_left_depth,\n                'cam_gray_back_right_depth': cam_gray_back_right_depth,\n                \n                # radar\n                'radar_front': radar_front,\n                'radar_front_left': radar_front_left,\n                'radar_front_right': radar_front_right,\n                'radar_back_left': radar_back_left,\n                'radar_back_right': radar_back_right,\n                # lidar\n                'lidar' : lidar_360,\n                'lidar_seg': lidar_seg,\n                # other\n                'gps': gps,\n                'speed': speed,\n                'compass': compass,\n                'weather': weather,\n                \"acceleration\":acceleration,\n                \"angular_velocity\":angular_velocity,\n                'bounding_boxes': bounding_boxes,\n                'sensors_anno': sensors_anno,\n                'throttle': control.throttle,\n                'steer': control.steer,\n                'brake': control.brake,\n                'reverse': control.reverse,\n                'town': self.town,\n                }\n        return results\n    \n    def _preprocess_sensor_spec(self, sensor_spec):\n        type_ = sensor_spec[\"type\"]\n        id_ = sensor_spec[\"id\"]\n        attributes = {}\n\n        if type_ == 'sensor.opendrive_map':\n            attributes['reading_frequency'] = sensor_spec['reading_frequency']\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        elif type_ == 'sensor.speedometer':\n            delta_time = CarlaDataProvider.get_world().get_settings().fixed_delta_seconds\n            attributes['reading_frequency'] = 1 / delta_time\n            sensor_location = carla.Location()\n            sensor_rotation = carla.Rotation()\n\n        if type_ == 'sensor.camera.rgb':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n        \n        elif type_ == 'sensor.camera.depth':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                roll=sensor_spec['roll'],\n                                                yaw=sensor_spec['yaw'])\n        \n        elif type_ == 'sensor.camera.semantic_segmentation':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                roll=sensor_spec['roll'],\n                                                yaw=sensor_spec['yaw'])\n        \n        elif type_ == 'sensor.camera.instance_segmentation':\n            attributes['image_size_x'] = str(sensor_spec['width'])\n            attributes['image_size_y'] = str(sensor_spec['height'])\n            attributes['fov'] = str(sensor_spec['fov'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                                z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                                roll=sensor_spec['roll'],\n                                                yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.lidar.ray_cast':\n            attributes['range'] = str(sensor_spec['range'])\n            attributes['rotation_frequency'] = str(sensor_spec['rotation_frequency'])\n            attributes['channels'] = str(sensor_spec['channels'])\n            attributes['upper_fov'] = str(10)\n            attributes['lower_fov'] = str(-30)\n            attributes['points_per_second'] = str(sensor_spec['points_per_second'])\n            attributes['atmosphere_attenuation_rate'] = str(0.004)\n            attributes['dropoff_general_rate'] = str(sensor_spec['dropoff_general_rate'])\n            attributes['dropoff_intensity_limit'] = str(sensor_spec['dropoff_intensity_limit'])\n            attributes['dropoff_zero_intensity'] = str(sensor_spec['dropoff_zero_intensity'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.lidar.ray_cast_semantic':\n            attributes['range'] = str(sensor_spec['range'])\n            attributes['rotation_frequency'] = str(sensor_spec['rotation_frequency'])\n            attributes['channels'] = str(sensor_spec['channels'])\n            attributes['upper_fov'] = str(10)\n            attributes['lower_fov'] = str(-30)\n            attributes['points_per_second'] = str(sensor_spec['points_per_second'])\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n            sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.radar':\n            attributes['horizontal_fov'] = str(sensor_spec['horizontal_fov'])  # degrees\n            attributes['vertical_fov'] = str(sensor_spec['vertical_fov'])  # degrees\n            attributes['points_per_second'] = '1500'\n            attributes['range'] = sensor_spec['range']  # meters\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n\n        elif type_ == 'sensor.other.gnss':\n            attributes['noise_alt_stddev'] = str(0.000005)\n            attributes['noise_lat_stddev'] = str(0.000005)\n            attributes['noise_lon_stddev'] = str(0.000005)\n            attributes['noise_alt_bias'] = str(0.0)\n            attributes['noise_lat_bias'] = str(0.0)\n            attributes['noise_lon_bias'] = str(0.0)\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation()\n            attributes['role_name'] = str(sensor_spec['id'])\n\n\n        elif type_ == 'sensor.other.imu':\n            attributes['noise_accel_stddev_x'] = str(0.001)\n            attributes['noise_accel_stddev_y'] = str(0.001)\n            attributes['noise_accel_stddev_z'] = str(0.015)\n            attributes['noise_gyro_stddev_x'] = str(0.001)\n            attributes['noise_gyro_stddev_y'] = str(0.001)\n            attributes['noise_gyro_stddev_z'] = str(0.001)\n            attributes['role_name'] = str(sensor_spec['id'])\n\n            sensor_location = carla.Location(x=sensor_spec['x'],\n                                             y=sensor_spec['y'],\n                                             z=sensor_spec['z'])\n            sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],\n                                             roll=sensor_spec['roll'],\n                                             yaw=sensor_spec['yaw'])\n        sensor_transform = carla.Transform(sensor_location, sensor_rotation)\n\n        return type_, id_, sensor_transform, attributes\n    \n    def setup_sensors(self):\n        \"\"\"\n        Create the sensors defined by the user and attach them to the ego-vehicle\n        :param vehicle: ego vehicle\n        :return:\n        \"\"\"\n        vehicle = self.manager.ego_vehicles[0]\n        self.sensor_interface = SensorInterface()\n        world = CarlaDataProvider.get_world()\n        bp_library = world.get_blueprint_library()\n        for sensor_spec in self.sensors():\n            type_, id_, sensor_transform, attributes = self._preprocess_sensor_spec(sensor_spec)\n\n            # These are the pseudosensors (not spawned)\n            if type_ == 'sensor.opendrive_map':\n                sensor = OpenDriveMapReader(vehicle, attributes['reading_frequency'])\n            elif type_ == 'sensor.speedometer':\n                sensor = SpeedometerReader(vehicle, attributes['reading_frequency'])\n\n            # These are the sensors spawned on the carla world\n            else:\n                bp = bp_library.find(type_)\n                for key, value in attributes.items():\n                    bp.set_attribute(str(key), str(value))\n                sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)\n\n            # setup callback\n            sensor.listen(CallBack(id_, type_, sensor, self.sensor_interface))\n            self._sensors_list.append(sensor)\n\n        # Some sensors miss sending data during the first ticks, so tick several times and remove the data\n        for _ in range(10):\n            world.tick()\n    \n    def sensors(self):\n        sensors = [\n                # camera rgb\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT'\n                    },\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT'\n                    },\n                # camera depth \n                {\n                    'type': 'sensor.camera.depth',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT_DEPTH'\n                    },\n                {\n                    'type': 'sensor.camera.depth',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT_DEPTH'\n                    },\n                # camera seg\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT_SEM_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.semantic_segmentation',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT_SEM_SEG'\n                    },\n                # camera seg\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': 0.80, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': 0.27, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_LEFT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': 0.27, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_FRONT_RIGHT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': -2.0, 'y': 0.0, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'CAM_BACK_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': -0.32, 'y': -0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_LEFT_INS_SEG'\n                    },\n                {\n                    'type': 'sensor.camera.instance_segmentation',\n                    'x': -0.32, 'y': 0.55, 'z': 1.60,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,\n                    'width': 1600, 'height': 900, 'fov': 70,\n                    'id': 'CAM_BACK_RIGHT_INS_SEG'\n                    },\n                # lidar\n                {   'type': 'sensor.lidar.ray_cast',\n                    'x': -0.39, 'y': 0.0, 'z': 1.84,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 85,\n                    'rotation_frequency': 10,\n                    'channels': 64,\n                    'points_per_second': 600000,\n                    'dropoff_general_rate': 0.0,\n                    'dropoff_intensity_limit': 0.0,\n                    'dropoff_zero_intensity': 0.0,\n                    'id': 'LIDAR_TOP'\n                    },\n                {   'type': 'sensor.lidar.ray_cast_semantic',\n                    'x': -0.39, 'y': 0.0, 'z': 1.84,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 85,\n                    'rotation_frequency': 10,\n                    'channels': 64,\n                    'points_per_second': 600000,\n                    'id': 'LIDAR_TOP_SEG'\n                    },\n                # imu\n                {\n                    'type': 'sensor.other.imu',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.05,\n                    'id': 'IMU'\n                    },\n                # gps\n                {\n                    'type': 'sensor.other.gnss',\n                    'x': -1.4, 'y': 0.0, 'z': 0.0,\n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'sensor_tick': 0.01,\n                    'id': 'GPS'\n                    },\n                # rader\n                {\n                    'type': 'sensor.other.radar', \n                    'x': 2.27, 'y': 0.0, 'z': 0.48, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_FRONT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': 1.21, 'y': -0.85, 'z': 0.74, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_FRONT_LEFT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': 1.21, 'y': 0.85, 'z': 0.74, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_FRONT_RIGHT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': -2.0, 'y': -0.67, 'z': 0.51, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_BACK_LEFT'\n                    },\n                {\n                    'type': 'sensor.other.radar', \n                    'x': -2.0, 'y': 0.67, 'z': 0.51, \n                    'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,\n                    'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,\n                    'id': 'RADAR_BACK_RIGHT'\n                    },\n                # speed\n                {\n                    'type': 'sensor.speedometer',\n                    'reading_frequency': 20,\n                    'id': 'SPEED'\n                    },\n\n                ### Debug sensor, not used by the model\n                {\n                    'type': 'sensor.camera.rgb',\n                    'x': 0.0, 'y': 0.0, 'z': 50.0,\n                    'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,\n                    'width': 1600, 'height': 900, 'fov': 110,\n                    'id': 'TOP_DOWN'\n                    },\n            ]\n        self.sensors_mapping = {}\n        for sensor in sensors:\n            self.sensors_mapping[sensor['id']] = sensor\n        return sensors\n\n    def _get_position(self, tick_data):\n        gps = tick_data['gps']\n        gps = (gps - self._command_planner.mean) * self._command_planner.scale\n        return gps\n    \n    def get_target_gps(self, gps, compass):\n\t\t# target gps\n        def gps_to_location(gps):\n            # gps content: numpy array: [lat, lon, alt]\n            lat, lon, z = gps\n            scale = math.cos(self.lat_ref * math.pi / 180.0)\n            my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n            mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n            y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n            x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n            z = float(z)\n            location = carla.Location(x=x, y=y, z=z)\n            return location\n            pass\n        global_plan_gps = self._global_plan[:]\n        next_gps, _ = global_plan_gps[min(self.navigation_idx+1, len(global_plan_gps)-1)]\n        next_gps = np.array([next_gps['lat'], next_gps['lon'], next_gps['z']])\n        next_vec_in_global = gps_to_location(next_gps) - gps_to_location(gps)\n        ref_rot_in_global = carla.Rotation(yaw=np.rad2deg(compass)-90.0)\n        loc_in_ev = vec_global_to_ref(next_vec_in_global, ref_rot_in_global)\n        \n        if np.sqrt(loc_in_ev.x**2+loc_in_ev.y**2) < 12.0 and loc_in_ev.x < 0.0:\n            self.navigation_idx += 1\n        \n        self.navigation_idx = min(self.navigation_idx, len(self._global_plan)-2)\n        _, road_option_0 = global_plan_gps[max(0, self.navigation_idx)]\n        gps_point, road_option_1 = global_plan_gps[self.navigation_idx+1]\n        gps_point = np.array([gps_point['lat'], gps_point['lon'], gps_point['z']])\n        if (road_option_0 in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]) \\\n                and (road_option_1 not in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]):\n            road_option = road_option_1\n        else:\n            road_option = road_option_0\n\n        return np.array(gps_point, dtype=np.float32), np.array([road_option.value], dtype=np.int8)\n\n    def save(self, near_node, far_node, near_command, far_command, tick_data, should_brake):\n        frame = self.count\n        # CARLA images are already in opencv's BGR format.\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front_left' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front_left'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front_right' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front_right'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back_left' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back_left'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back_right' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back_right'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n        cv2.imwrite(str(self.save_path / 'camera' / 'rgb_top_down' / (f'{frame:05}.jpg')), tick_data['cam_bgr_top_down'], [cv2.IMWRITE_JPEG_QUALITY, 20])\n\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front' / (f'{frame:05}.png')), tick_data['cam_front_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front_left' / (f'{frame:05}.png')), tick_data['cam_front_left_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front_right' / (f'{frame:05}.png')), tick_data['cam_front_right_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back' / (f'{frame:05}.png')), tick_data['cam_back_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back_left' / (f'{frame:05}.png')), tick_data['cam_back_left_sem_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back_right' / (f'{frame:05}.png')), tick_data['cam_back_right_sem_seg'])\n\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_front' / (f'{frame:05}.png')), tick_data['cam_front_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_front_left' / (f'{frame:05}.png')), tick_data['cam_front_left_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_front_right' / (f'{frame:05}.png')), tick_data['cam_front_right_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_back' / (f'{frame:05}.png')), tick_data['cam_back_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_back_left' / (f'{frame:05}.png')), tick_data['cam_back_left_ins_seg'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'instance_back_right' / (f'{frame:05}.png')), tick_data['cam_back_right_ins_seg'])\n\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_front' / (f'{frame:05}.png')), tick_data['cam_gray_front_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_front_left' / (f'{frame:05}.png')), tick_data['cam_gray_front_left_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_front_right' / (f'{frame:05}.png')), tick_data['cam_gray_front_right_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_back' / (f'{frame:05}.png')), tick_data['cam_gray_back_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_back_left' / (f'{frame:05}.png')), tick_data['cam_gray_back_left_depth'])\n        cv2.imwrite(str(self.save_path / 'camera' / 'depth_back_right' / (f'{frame:05}.png')), tick_data['cam_gray_back_right_depth'])\n        \n        with h5py.File(str(self.save_path / 'radar' / (f'{frame:05}.h5')), 'w') as f:\n            f.create_dataset('radar_front', data=tick_data['radar_front'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_front_left', data=tick_data['radar_front_left'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_front_right', data=tick_data['radar_front_right'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_back_left', data=tick_data['radar_back_left'], compression='gzip', compression_opts=9, chunks=True)\n            f.create_dataset('radar_back_right', data=tick_data['radar_back_right'], compression='gzip', compression_opts=9, chunks=True)\n\n        # Specialized LiDAR compression format\n        header = laspy.LasHeader(point_format=0)  # LARS point format used for storing\n        header.offsets = np.min(tick_data['lidar'], axis=0)\n        point_precision = 0.001\n        header.scales = np.array([point_precision, point_precision, point_precision])\n\n        with laspy.open(self.save_path / 'lidar' / (f'{frame:05}.laz'), mode='w', header=header) as writer:\n            point_record = laspy.ScaleAwarePointRecord.zeros(tick_data['lidar'].shape[0], header=header)\n            point_record.x = tick_data['lidar'][:, 0]\n            point_record.y = tick_data['lidar'][:, 1]\n            point_record.z = tick_data['lidar'][:, 2]\n            writer.write_points(point_record)\n\n        anno_data = {\n                'x': tick_data['pos'][0],\n                'y': tick_data['pos'][1],\n                'throttle': tick_data['throttle'],\n                'steer': tick_data['steer'],\n                'brake': tick_data['brake'],\n                'reverse': tick_data['reverse'],\n                'theta': tick_data['compass'],\n                'speed': tick_data['speed'],\n                'x_command_far': far_node[0],\n                'y_command_far': far_node[1],\n                'command_far': far_command.value,\n                'x_command_near': near_node[0],\n                'y_command_near': near_node[1],\n                'command_near': near_command.value,\n                'should_brake': should_brake,\n                'x_target': tick_data['x_target'],\n                'y_target': tick_data['y_target'],\n                # 'target_command': tick_data['target_command'].tolist(),\n                # 'target_gps': tick_data['target_gps'].tolist(),\n                'next_command': tick_data['next_command'],\n                'weather': tick_data['weather'],\n                \"acceleration\":tick_data[\"acceleration\"].tolist(),\n                \"angular_velocity\":tick_data[\"angular_velocity\"].tolist(),\n                'bounding_boxes': tick_data['bounding_boxes'],\n                'sensors': tick_data['sensors_anno'],\n                'only_ap_brake': tick_data['only_ap_brake'],\n                }\n        with gzip.open(self.save_path / 'anno' / f'{frame:05}.json.gz', 'wt', encoding='utf-8') as f:\n            json.dump(anno_data, f, indent=4)\n        if self.count > -1:\n            np.savez(self.save_path / 'expert_assessment' / f'{frame-1:05}.npz', np.concatenate((self.feature, self.value, np.array([self.action_index], dtype=np.float32))))\n            \n    # add feature (yzj)\n    def _point_inside_boundingbox(self, point, bb_center, bb_extent, multiplier=1.5):\n        A = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        B = carla.Vector2D(bb_center.x + multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)\n        D = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y + multiplier * bb_extent.y)\n        M = carla.Vector2D(point.x, point.y)\n\n        AB = B - A\n        AD = D - A\n        AM = M - A\n        am_ab = AM.x * AB.x + AM.y * AB.y\n        ab_ab = AB.x * AB.x + AB.y * AB.y\n        am_ad = AM.x * AD.x + AM.y * AD.y\n        ad_ad = AD.x * AD.x + AD.y * AD.y\n\n        return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad \n    \n    def affected_by_traffic_light(self, traffic_light, center, window_size=50):\n        inx = min(window_size, len(CarlaDataProvider._ego_actor.route_plan))\n        if inx <= 1:\n            return False\n        for trans, _ in CarlaDataProvider._ego_actor.route_plan[:inx]:\n            if self._point_inside_boundingbox(trans.location, center, traffic_light.trigger_volume.extent):\n                return True\n        return False\n\n    def get_traffic_color(self, state):\n        if state == carla.libcarla.TrafficLightState.Green:\n            return 'green'\n        if state == carla.libcarla.TrafficLightState.Yellow:\n            return 'yellow'\n        if state == carla.libcarla.TrafficLightState.Red:\n            return 'red'\n        if state == carla.libcarla.TrafficLightState.Unknown:\n            return 'unknown'\n        if state == carla.libcarla.TrafficLightState.Off:\n            return 'off'\n        raise Exception(f\"{state} not in Green, Yellow, Red, Unknown, Off\")\n    \n    def get_affect_sign(self, actors):\n        all_actors = []\n        affect_signs = []\n        mini_sign = DIS_SIGN_SAVE + 1\n        most_affect_sign = None\n        # find all lights\n        ego_vehicle_waypoint = CarlaDataProvider.get_map().get_waypoint(self.manager.ego_vehicles[0].get_location())\n        for sign in actors:\n            flag = 0\n            sign_loc = sign.get_location()\n            if compute_2d_distance(sign_loc, self.manager.ego_vehicles[0].get_transform().location) > DIS_SIGN_SAVE:\n                continue\n            all_actors.append(sign)\n\n            # find all affect lights \n            if hasattr(sign, 'trigger_volume'):\n                sign_vol_loc = sign.trigger_volume.location\n                sign_vol_loc_world = sign.get_transform().transform(sign_vol_loc)\n                sign_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(sign_vol_loc_world)\n                while not sign_vol_loc_world_wp.is_intersection:\n                    if len(sign_vol_loc_world_wp.next(0.5)) > 0:\n                        next_sign_vol_loc_world_wp = sign_vol_loc_world_wp.next(0.5)[0]\n                    else:\n                        flag = 1\n                        break\n                    if next_sign_vol_loc_world_wp and not next_sign_vol_loc_world_wp.is_intersection:\n                        sign_vol_loc_world_wp = next_sign_vol_loc_world_wp\n                    else:\n                        break\n                if flag:\n                    continue\n                if self.affected_by_traffic_light(sign, carla.Location(x=sign_vol_loc_world_wp.transform.location.x, y=sign_vol_loc_world_wp.transform.location.y, z=0)):\n                    affect_signs.append(sign)\n                    dis = np.abs(compute_2d_distance(ego_vehicle_waypoint.transform.location, sign.get_transform().transform(sign.trigger_volume.location)))\n                    if dis < mini_sign:\n                        most_affect_sign = sign\n                        mini_sign = dis\n            else:\n                sign_vol_loc = sign.get_transform().location\n                sign_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(sign_vol_loc)\n                dis = compute_2d_distance(sign_vol_loc_world_wp.transform.location, ego_vehicle_waypoint.transform.location)\n                forward_vec = self.manager.ego_vehicles[0].get_transform().get_forward_vector()\n                ray = sign_vol_loc_world_wp.transform.location - self.manager.ego_vehicles[0].get_location()\n                if forward_vec.dot(ray) < 0:\n                    continue\n                if dis < mini_sign:\n                    most_affect_sign = sign\n                    mini_sign = dis\n        return all_actors, most_affect_sign\n\n    def get_actor_filter_traffic_sign(self):\n        actor_data = EasyDict({})\n        speed_limit_sign = list(CarlaDataProvider.get_world().get_actors().filter(\"*traffic.speed_limit*\")) # carla.libcarla.TrafficSign\n        stop_sign = list(CarlaDataProvider.get_world().get_actors().filter(\"*traffic.stop*\")) # carla.libcarla.TrafficSign\n        yield_sign = list(CarlaDataProvider.get_world().get_actors().filter(\"*traffic.yield*\")) # carla.libcarla.TrafficSign\n        warning = list(CarlaDataProvider.get_world().get_actors().filter('*warning*'))\n        dirtdebris = list(CarlaDataProvider.get_world().get_actors().filter('*dirtdebris*'))\n        cone = list(CarlaDataProvider.get_world().get_actors().filter('*cone*'))\n\n        actors = speed_limit_sign + stop_sign + yield_sign + warning + dirtdebris + cone\n        all_actors, most_affect_sign = self.get_affect_sign(actors)\n        actor_data.actors = all_actors\n        actor_data.most_affect_sign = most_affect_sign\n        return actor_data\n\n    def get_actor_filter_traffic_light(self):\n        actor_data = EasyDict({})\n        lights = CarlaDataProvider.get_world().get_actors().filter(\"*traffic_light*\")\n        all_lights = []\n        affect_lights = []\n        most_affect_light = None\n        mini_lt = DIS_LIGHT_SAVE + 1\n\n        # find all lights\n        for lt in lights:\n            flag = 0\n            lt_loc = lt.get_location()\n            if compute_2d_distance(lt_loc, self.manager.ego_vehicles[0].get_location()) > DIS_LIGHT_SAVE: # lidar range\n                continue\n            all_lights.append(lt)\n\n            # find all affect lights \n            lt_vol_loc = lt.trigger_volume.location\n            lt_vol_loc_world = lt.get_transform().transform(lt_vol_loc)\n            lt_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(lt_vol_loc_world)\n            while not lt_vol_loc_world_wp.is_intersection:\n                if len(lt_vol_loc_world_wp.next(0.5)) > 0:\n                    next_lt_vol_loc_world_wp = lt_vol_loc_world_wp.next(0.5)[0]\n                else:\n                    flag = 1\n                    break \n                if next_lt_vol_loc_world_wp and not next_lt_vol_loc_world_wp.is_intersection:\n                    lt_vol_loc_world_wp = next_lt_vol_loc_world_wp\n                else:\n                    break\n            if flag:\n                continue\n            if self.affected_by_traffic_light(lt, carla.Location(x=lt_vol_loc_world_wp.transform.location.x, y=lt_vol_loc_world_wp.transform.location.y, z=0)):\n                affect_lights.append(lt)\n                # find most affect light_actor, min_dis=DIS_LIGHT_SAVE\n                dis = np.abs(compute_2d_distance(lt.get_transform().transform(lt.trigger_volume.location), self.manager.ego_vehicles[0].get_location()))\n                forward_vec = self.manager.ego_vehicles[0].get_transform().get_forward_vector()\n                ray = lt.get_transform().transform(lt.trigger_volume.location) - self.manager.ego_vehicles[0].get_location()\n                if forward_vec.dot(ray) < 0:\n                    continue\n                if dis < mini_lt:\n                    most_affect_light = lt\n                    mini_lt = dis\n        \n        actor_data.lights = all_lights\n        actor_data.affect_lights = affect_lights\n        actor_data.most_affect_light = most_affect_light\n\n        #  get distance\n        if most_affect_light is not None:\n            trigger_volume = most_affect_light.trigger_volume\n            box = trigger_volume.extent\n            loc = trigger_volume.location\n            ori = trigger_volume.rotation.get_forward_vector()\n            trigger_loc = [loc.x, loc.y, loc.z]\n            trigger_ori = [ori.x, ori.y, ori.z]\n            trigger_box = [box.x, box.y]\n\n            world_loc = most_affect_light.get_transform().transform(loc)\n            world_loc_wp = CarlaDataProvider.get_map().get_waypoint(world_loc)\n            while not world_loc_wp.is_intersection:\n                next_world_loc_wp = world_loc_wp.next(0.5)[0]\n                if next_world_loc_wp and not next_world_loc_wp.is_intersection:\n                    world_loc_wp = next_world_loc_wp\n                else:\n                    break\n            \n            world_loc_wp = carla.Location(x=world_loc_wp.transform.location.x, y=world_loc_wp.transform.location.y, z=0)\n            pos = self.manager.ego_vehicles[0].get_location()\n            pos = carla.Location(x=pos.x, y=pos.y, z=0)\n\n            # ego2lane_dis = world_loc_wp.distance(pos)\n            ego2lane_dis = compute_2d_distance(world_loc_wp, pos)\n            ego2light_dis = compute_2d_distance(most_affect_light.get_location(), self.manager.ego_vehicles[0].get_location())\n            most_affect_light_id = most_affect_light.id\n            most_affect_light_state = self.get_traffic_color(most_affect_light.state)\n\n            # record data\n            actor_data.most_affect_light = EasyDict()\n            actor_data.most_affect_light.id = most_affect_light_id\n            actor_data.most_affect_light.state = most_affect_light_state\n            actor_data.most_affect_light.ego2lane_dis = ego2lane_dis\n            actor_data.most_affect_light.ego2light_dis = ego2light_dis\n            actor_data.most_affect_light.trigger_volume = EasyDict()\n            actor_data.most_affect_light.trigger_volume.location = trigger_loc\n            actor_data.most_affect_light.trigger_volume.orientation = trigger_ori\n            actor_data.most_affect_light.trigger_volume.extent = trigger_box\n        return actor_data \n\n        \n    def get_actor_filter_vehicle(self):\n        vehicles_dict = EasyDict({})\n\n        vehicles = self.world.get_actors().filter('*vehicle*')\n        vehicles_list = []\n        for actor in vehicles:\n            dist = compute_2d_distance(actor.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            # Filter for the vehicles within DIS_CAR_SAVE m\n            if dist < DIS_CAR_SAVE: # lidar range\n                vehicles_list.append(actor)\n        vehicles_dict.vehicle = vehicles_list\n\n        others = self.world.get_actors().filter('*static.prop.mesh*')\n        static_list = []\n        for actor in others:\n            # filter static vehicle\n            mesh_path = actor.attributes['mesh_path'].split('/Game/Carla/')[1]\n            if 'Car' in mesh_path or 'Truck' in mesh_path or 'Bus' in mesh_path or 'Motorcycle' in mesh_path or 'Bicycle' in mesh_path:\n                dist = compute_2d_distance(actor.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                # Filter for the vehicles within DIS_CAR_SAVE\n                if dist < DIS_CAR_SAVE: # lidar range\n                    static_list.append(actor)\n        vehicles_dict.static = static_list\n        return vehicles_dict\n    \n\n    def _get_forward_speed(self, transform=None, velocity=None):\n        \"\"\" Convert the vehicle transform directly to forward speed \"\"\"\n        if not velocity:\n            velocity = self.manager.ego_vehicles[0].get_velocity()\n        if not transform:\n            transform = self.manager.ego_vehicles[0].get_transform()\n\n        vel_np = np.array([velocity.x, velocity.y, velocity.z])\n        pitch = np.deg2rad(transform.rotation.pitch)\n        yaw = np.deg2rad(transform.rotation.yaw)\n        orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)])\n        speed = np.dot(vel_np, orientation)\n        return speed\n    \n    def get_sensors_anno(self):\n        results = {}\n        sensors = {}\n        for value in self.world.get_actors().filter('*sensor.camera.rgb'):\n            sensors[value.attributes['role_name']] = value\n\n        for key in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT', 'TOP_DOWN']:\n            value = sensors[key]\n            location = value.get_transform().location\n            rotation = value.get_transform().rotation\n            world2cam = value.get_transform().get_inverse_matrix()\n            width = int(value.attributes['image_size_x'])\n            height = int(value.attributes['image_size_y'])\n            fov = float(value.attributes['fov'])\n            K = build_projection_matrix(width, height, fov=fov)\n            cam2ego = get_matrix(location=[self.sensors_mapping[key]['x'], self.sensors_mapping[key]['y'], self.sensors_mapping[key]['z']], \n                                 rotation=[self.sensors_mapping[key]['pitch'], self.sensors_mapping[key]['roll'], self.sensors_mapping[key]['yaw']])\n            result ={\n                'location': [location.x, location.y, location.z], \n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'intrinsic': K.tolist(),\n                'world2cam': world2cam,\n                'cam2ego': cam2ego.tolist(),\n                'fov': fov,\n                'image_size_x': width,\n                'image_size_y': height,\n            }\n            results[key] = result\n\n        # radar\n        for value in self.world.get_actors().filter('*sensor.other.radar*'):\n            sensors[value.attributes['role_name']] = value\n\n        for key in ['RADAR_FRONT','RADAR_FRONT_LEFT','RADAR_FRONT_RIGHT', 'RADAR_BACK_LEFT', 'RADAR_BACK_RIGHT']:\n            value = sensors[key]\n            location = value.get_transform().location\n            rotation = value.get_transform().rotation\n            world2radar = value.get_transform().get_inverse_matrix()\n            radar2ego = get_matrix(location=[self.sensors_mapping[key]['x'], self.sensors_mapping[key]['y'], self.sensors_mapping[key]['z']], \n                        rotation=[self.sensors_mapping[key]['pitch'], self.sensors_mapping[key]['roll'], self.sensors_mapping[key]['yaw']])\n            result ={\n                'location': [location.x, location.y, location.z], \n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'world2radar': world2radar,\n                'radar2ego': radar2ego.tolist(),\n            }\n            results[key] = result\n        \n        # lidar\n        for value in self.world.get_actors().filter('*sensor.lidar.ray_cast*'):\n            sensors[value.attributes['role_name']] = value\n\n        for key in ['LIDAR_TOP']:\n            value = sensors[key]\n            location = value.get_transform().location\n            rotation = value.get_transform().rotation\n            world2lidar = value.get_transform().get_inverse_matrix()\n            lidar2ego = get_matrix(location=[self.sensors_mapping[key]['x'], self.sensors_mapping[key]['y'], self.sensors_mapping[key]['z']], \n                        rotation=[self.sensors_mapping[key]['pitch'], self.sensors_mapping[key]['roll'], self.sensors_mapping[key]['yaw']])\n            result ={\n                'location': [location.x, location.y, location.z], \n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'world2lidar': world2lidar,\n                'lidar2ego': lidar2ego.tolist(),\n            }\n            results[key] = result\n        return results\n\n    def get_bounding_boxes(self, lidar=None, radar=None):\n        results = []\n\n        # ego_vehicle\n        npc = self.manager.ego_vehicles[0]\n        npc_id = str(npc.id)\n        npc_type_id = npc.type_id\n        npc_base_type = npc.attributes['base_type']\n        location = npc.get_transform().location\n        rotation = npc.get_transform().rotation\n        # \n        # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n        # center, extent = get_center_and_extent(verts)\n        # from carla official\n        # bb_cords = _bounding_box_to_world(npc.bounding_box)\n        # world_cord = _vehicle_to_world(bb_cords, npc)\n        # from handcraft\n        extent = npc.bounding_box.extent\n        center = npc.get_transform().transform(npc.bounding_box.location)\n        local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n        global_verts = []\n        for l_v in local_verts:\n            g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n            global_verts.append([g_v.x, g_v.y, g_v.z])\n        ###################\n        ego_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n        ego_brake = npc.get_control().brake\n        ego_matrix = np.array(npc.get_transform().get_matrix())\n        ego_yaw = np.deg2rad(rotation.yaw)\n        road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n        lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n        section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n        world2ego = npc.get_transform().get_inverse_matrix()\n\n        result = {\n            'class': 'ego_vehicle',\n            'id': npc_id,\n            'type_id': npc_type_id,\n            'base_type': npc_base_type,\n            'location': [location.x, location.y, location.z],\n            'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n            'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n            'center': [center.x, center.y, center.z],\n            'extent': [extent.x, extent.y, extent.z],\n            'world_cord': global_verts,\n            'semantic_tags': [npc.semantic_tags],\n            'color': npc.attributes['color'],\n            'speed': ego_speed,\n            'brake': ego_brake,\n            'road_id': road_id,\n            'lane_id': lane_id,\n            'section_id': section_id,\n            'world2ego': world2ego,\n        }\n        results.append(result)\n\n        # vehicles.vehicle\n        vehicles = self.get_actor_filter_vehicle()\n        for npc in vehicles.vehicle:\n            if not npc.is_alive: continue\n            if npc.id == self.manager.ego_vehicles[0].id: continue\n            npc_id = str(npc.id)\n            location = npc.get_transform().location\n            rotation = npc.get_transform().rotation\n            road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n            lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n            section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n            # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n            # center, extent = get_center_and_extent(verts)\n            # # from carla official\n            # bb_cords = _bounding_box_to_world(npc.bounding_box)\n            # world_cord = _vehicle_to_world(bb_cords, npc)\n            # #\n            # from handcraft\n            world2vehicle = npc.get_transform().get_inverse_matrix()\n            extent = npc.bounding_box.extent\n            center = npc.get_transform().transform(npc.bounding_box.location)\n            local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n            global_verts = []\n            for l_v in local_verts:\n                g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                global_verts.append([g_v.x, g_v.y, g_v.z])\n            ###################\n            vehicle_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n            vehicle_brake = npc.get_control().brake\n            vehicle_matrix = np.array(npc.get_transform().get_matrix())\n            yaw = np.deg2rad(rotation.yaw)\n            try:\n                light_state = str(npc.get_light_state()).split('.')[-1]\n            except:\n                light_state = 'None'\n            # Computes how many LiDAR hits are on a bounding box. Used to filter invisible boxes during data loading.\n            relative_yaw = normalize_angle(yaw - ego_yaw)\n            relative_pos = get_relative_transform(ego_matrix, vehicle_matrix)\n            if not lidar is None:\n                num_in_bbox_lidar_points = self.get_lidar_points_in_bbox(relative_pos, relative_yaw, extent, lidar)\n            else:\n                num_in_bbox_lidar_points = -1\n            \n            distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            result = {\n                'class': 'vehicle',\n                'state': 'dynamic',\n                'id': npc_id,\n                'location': [location.x, location.y, location.z],\n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                'center': [center.x, center.y, center.z],\n                'extent': [extent.x, extent.y, extent.z],\n                'world_cord': global_verts,\n                'semantic_tags': npc.semantic_tags,\n                'type_id': npc.type_id,\n                'color': npc.attributes['color'],\n                'base_type': npc.attributes['base_type'],\n                'num_points': int(num_in_bbox_lidar_points),\n                'distance': distance,\n                'speed': vehicle_speed,\n                'brake': vehicle_brake,\n                'light_state': light_state,\n                'road_id': road_id,\n                'lane_id': lane_id,\n                'section_id': section_id,\n                'world2vehicle': world2vehicle,\n                # 'actor': npc, # for debug \n              }\n            results.append(result)\n        \n        # vehicles.static\n        car_bbox_list = self.world.get_level_bbs(carla.CityObjectLabel.Car) \n        bicycle_list = self.world.get_level_bbs(carla.CityObjectLabel.Bicycle)\n        bus_list = self.world.get_level_bbs(carla.CityObjectLabel.Bus)\n        motorcycle_list = self.world.get_level_bbs(carla.CityObjectLabel.Motorcycle)\n        train_list = self.world.get_level_bbs(carla.CityObjectLabel.Train)\n        truck_list = self.world.get_level_bbs(carla.CityObjectLabel.Truck)\n        vehicles_static_bbox = car_bbox_list + bicycle_list + bus_list + motorcycle_list + train_list + truck_list\n        vehicles_static_bbox_nearby = []\n        for v_s in vehicles_static_bbox:\n            if compute_2d_distance(v_s.location, self.manager.ego_vehicles[0].get_transform().location) < (DIS_LIGHT_SAVE + 20):\n                vehicles_static_bbox_nearby.append(v_s)\n        for npc in vehicles.static:\n            if not npc.is_alive: continue\n            new_bbox = None\n            min_dis = 50\n            for vehicle_bbox in vehicles_static_bbox_nearby:\n                dis = compute_2d_distance(npc.get_transform().location, vehicle_bbox.location)\n                if dis < min_dis:\n                    new_bbox = vehicle_bbox\n                    min_dis = dis\n            if min_dis > 20:\n                continue\n            if not new_bbox:\n                raise Exception('new_bbox is None')\n            if new_bbox not in vehicles_static_bbox_nearby:\n                raise Exception('new_bbox not in vehicles_static_bbox_nearby')\n            vehicles_static_bbox_nearby.remove(new_bbox)\n            npc_id = str(npc.id)\n            # location = new_bbox.location\n            # rotation = new_bbox.rotation\n            # center = new_bbox.location\n            extent = new_bbox.extent\n            ####\n            location = npc.get_transform().location\n            rotation = npc.get_transform().rotation\n            road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n            lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n            section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n            # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n            # center, extent = get_center_and_extent(verts)\n            # # from carla official\n            # bb_cords = _bounding_box_to_world(npc.bounding_box)\n            # world_cord = _vehicle_to_world(bb_cords, npc)\n            # #\n            # from handcraft\n            world2vehicle = npc.get_transform().get_inverse_matrix()\n            # extent = npc.bounding_box.extent\n            # extent = carla.Vector3D(extent.y, extent.x, extent.z) # staic need swap\n            center = npc.get_transform().transform(npc.bounding_box.location)\n            local_verts = calculate_cube_vertices(npc.bounding_box.location, extent)\n            global_verts = []\n            for l_v in local_verts:\n                g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                # g_v = np.dot(np.matrix(npc.get_transform().get_inverse_matrix()).I, [l_v[0], l_v[1], l_v[2],1])\n                global_verts.append([g_v.x, g_v.y, g_v.z])\n            ###################\n            vehicle_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n            vehicle_brake = 1.0\n            vehicle_matrix = np.array(npc.get_transform().get_matrix())\n            yaw = np.deg2rad(rotation.yaw)\n            light_state= 'NONE'\n            # Computes how many LiDAR hits are on a bounding box. Used to filter invisible boxes during data loading.\n            relative_yaw = normalize_angle(yaw - ego_yaw)\n            relative_pos = get_relative_transform(ego_matrix, vehicle_matrix)\n            if not lidar is None:\n                num_in_bbox_points = self.get_lidar_points_in_bbox(relative_pos, relative_yaw, extent, lidar)\n            else:\n                num_in_bbox_points = -1\n\n            distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            result = {\n                'class': 'vehicle',\n                'state': 'static',\n                'id': npc_id,\n                'location': [location.x, location.y, location.z],\n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                'center': [center.x, center.y, center.z],\n                'extent': [extent.x, extent.y, extent.z],\n                'world_cord': global_verts,\n                'semantic_tags': npc.semantic_tags,\n                'type_id': npc.attributes['mesh_path'],\n                'num_points': int(num_in_bbox_points),\n                'distance': distance,\n                'speed': vehicle_speed,\n                'brake': vehicle_brake,\n                'light_state': light_state,\n                'road_id': road_id,\n                'lane_id': lane_id,\n                'section_id': section_id,\n                'world2vehicle': world2vehicle,\n                # 'actor': npc, # for debug\n                }\n            results.append(result)\n        \n        # pedestrians\n        pedestrians = self.world.get_actors().filter('walker*')\n        for npc in pedestrians:\n            if not npc.is_alive: \n                continue\n            else:\n                try:\n                    if compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location) < DIS_WALKER_SAVE:\n                        npc_id = str(npc.id)\n                        location = npc.get_transform().location\n                        rotation = npc.get_transform().rotation\n                        road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n                        lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n                        section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n                        # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n                        # center, extent = get_center_and_extent(verts)\n                        # # from carla official\n                        # bb_cords = _bounding_box_to_world(npc.bounding_box)\n                        # world_cord = _vehicle_to_world(bb_cords, npc)\n                        # #\n                        # from handcraft\n                        world2ped = npc.get_transform().get_inverse_matrix()\n                        extent = npc.bounding_box.extent\n                        center = npc.get_transform().transform(npc.bounding_box.location)\n                        local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n                        global_verts = []\n                        for l_v in local_verts:\n                            g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                            global_verts.append([g_v.x, g_v.y, g_v.z])\n                        ###################\n                        walker_speed = self._get_forward_speed(transform=npc.get_transform(), velocity=npc.get_velocity())\n                        # walker_speed = npc.attributes['speed'] #(TODO) yzj\n                        walker_matrix = np.array(npc.get_transform().get_matrix())\n                        yaw = np.deg2rad(rotation.yaw)\n                        bones_3d_lines = build_skeleton(npc, self.skeleton_links)\n                        # Computes how many LiDAR hits are on a bounding box. Used to filter invisible boxes during data loading.\n                        relative_yaw = normalize_angle(yaw - ego_yaw)\n                        relative_pos = get_relative_transform(ego_matrix, walker_matrix)\n                        if not lidar is None:\n                            num_in_bbox_points = self.get_lidar_points_in_bbox(relative_pos, relative_yaw, extent, lidar)\n                        else:\n                            num_in_bbox_points = -1\n\n                        distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                        result = {\n                            'class': 'walker',\n                            'id': npc_id,\n                            'location': [location.x, location.y, location.z],\n                            'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                            'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                            'center': [center.x, center.y, center.z],\n                            'extent': [extent.x, extent.y, extent.z],\n                            'world_cord': global_verts,\n                            'semantic_tags': npc.semantic_tags,\n                            'type_id': npc.type_id,\n                            'gender': npc.attributes['gender'],\n                            'age': npc.attributes['age'],\n                            'num_points': int(num_in_bbox_points),\n                            'distance': distance,\n                            'speed': walker_speed,\n                            'bone': bones_3d_lines,\n                            'road_id': road_id,\n                            'lane_id': lane_id,\n                            'section_id': section_id,\n                            'world2ped': world2ped,\n                            # 'actor': npc, # for debug\n                        }\n                        results.append(result)\n                except RuntimeError:\n                    continue\n        \n        # traffic_light\n        traffic_light = self.get_actor_filter_traffic_light()\n        traffic_light_bbox = self.world.get_level_bbs(carla.CityObjectLabel.TrafficLight)\n        traffic_light_bbox_nearby = []\n        for light_bbox in traffic_light_bbox:\n            if compute_2d_distance(light_bbox.location, self.manager.ego_vehicles[0].get_transform().location) < (DIS_LIGHT_SAVE + 20):\n                traffic_light_bbox_nearby.append(light_bbox)\n        for npc in traffic_light.lights:\n            new_bbox = None\n            min_dis = 50\n            for light_bbox in traffic_light_bbox_nearby:\n                dis = compute_2d_distance(npc.get_transform().location, light_bbox.location)\n                if dis < min_dis:\n                    new_bbox = light_bbox\n                    min_dis = dis\n            if min_dis > 20:\n                continue\n            traffic_light_bbox_nearby.remove(new_bbox)\n            npc_id = str(npc.id)\n            location = new_bbox.location\n            rotation = new_bbox.rotation\n            center = new_bbox.location\n            extent = new_bbox.extent\n            road_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).road_id\n            lane_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).lane_id\n            section_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).section_id\n            volume_location = npc.get_transform().transform(npc.trigger_volume.location)\n            volume_rotation = carla.Rotation(pitch=(rotation.pitch + npc.trigger_volume.rotation.pitch)%360, roll=(rotation.roll + npc.trigger_volume.rotation.roll)%360, yaw=(rotation.yaw + npc.trigger_volume.rotation.yaw) % 360)\n            state = npc.state\n            distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n            if traffic_light.most_affect_light and str(traffic_light.most_affect_light.id) == npc_id:\n                affects_ego = True\n            else:\n                affects_ego = False\n            result = {\n                'class': 'traffic_light',\n                'id': npc_id,\n                'location': [location.x, location.y, location.z],\n                'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                'center': [center.x, center.y, center.z],\n                'extent': [extent.x, extent.y, extent.z],\n                'semantic_tags': npc.semantic_tags,\n                'type_id': npc.type_id,\n                'distance': distance,\n                'state': state,\n                'affects_ego': affects_ego,\n                'trigger_volume_location': [volume_location.x, volume_location.y, volume_location.z],\n                'trigger_volume_rotation': [volume_rotation.pitch, volume_rotation.roll, volume_rotation.yaw],\n                'trigger_volume_extent': [npc.trigger_volume.extent.x, npc.trigger_volume.extent.y, npc.trigger_volume.extent.z],\n                'road_id': road_id,\n                'lane_id': lane_id,\n                'section_id': section_id,\n                # 'actor': npc, # for debug\n                # 'new_bbox': new_bbox, # for debug\n            }\n            results.append(result)\n        \n        # traffic_sign\n        traffic_sign = self.get_actor_filter_traffic_sign()\n        traffic_sign_bbox = self.world.get_level_bbs(carla.CityObjectLabel.TrafficSigns)\n        traffic_sign_bbox_nearby = []\n        for sign_bbox in traffic_sign_bbox:\n            if compute_2d_distance(sign_bbox.location, self.manager.ego_vehicles[0].get_transform().location) < (DIS_SIGN_SAVE + 20):\n                traffic_sign_bbox_nearby.append(sign_bbox)\n\n        for npc in traffic_sign.actors:\n            if hasattr(npc, 'trigger_volume'):\n                new_bbox = None\n                min_dis = 50\n                for sign_bbox in traffic_sign_bbox_nearby:\n                    dis = compute_2d_distance(npc.get_transform().location, sign_bbox.location)\n                    if dis < min_dis:\n                        new_bbox = sign_bbox\n                        min_dis = dis\n                if min_dis > 20:\n                    continue\n                traffic_sign_bbox_nearby.remove(new_bbox)\n                npc_id = str(npc.id)\n                world2sign = npc.get_transform().get_inverse_matrix()\n                location = new_bbox.location\n                rotation = new_bbox.rotation\n                center = new_bbox.location\n                extent = new_bbox.extent\n                road_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).road_id\n                lane_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).lane_id\n                section_id = CarlaDataProvider.get_map().get_waypoint(new_bbox.location).section_id\n                volume_location = npc.get_transform().transform(npc.trigger_volume.location)\n                volume_rotation = carla.Rotation(pitch=(rotation.pitch + npc.trigger_volume.rotation.pitch)%360, roll=(rotation.roll + npc.trigger_volume.rotation.roll)%360, yaw=(rotation.yaw + npc.trigger_volume.rotation.yaw) % 360)\n                distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                if traffic_sign.most_affect_sign and str(traffic_sign.most_affect_sign.id) == npc_id:\n                    affects_ego = True\n                else:\n                    affects_ego = False\n                result = {\n                    'class': 'traffic_sign',\n                    'id': npc_id,\n                    'location': [location.x, location.y, location.z],\n                    'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                    'center': [center.x, center.y, center.z],\n                    'extent': [extent.x, extent.y, extent.z],\n                    # 'extent': [extent.x, 0.5, extent.z],\n                    'semantic_tags': npc.semantic_tags,\n                    'type_id': npc.type_id,\n                    'distance': distance,\n                    'affects_ego': affects_ego,\n                    'trigger_volume_location': [volume_location.x, volume_location.y, volume_location.z],\n                    'trigger_volume_rotation': [volume_rotation.pitch, volume_rotation.roll, volume_rotation.yaw],\n                    'trigger_volume_extent': [npc.trigger_volume.extent.x, npc.trigger_volume.extent.y, npc.trigger_volume.extent.z],\n                    'road_id': road_id,\n                    'lane_id': lane_id,\n                    'section_id': section_id,\n                    'world2sign': world2sign,\n                    # 'actor': npc, # for debug\n                    # 'new_bbox': new_bbox, # for debug\n                }\n            else:\n                npc_id = str(npc.id)\n                location = npc.get_transform().location\n                rotation = npc.get_transform().rotation\n                # verts = [v for v in npc.bounding_box.get_world_vertices(npc.get_transform())]\n                # center, extent = get_center_and_extent(verts)\n                # from handcraft\n                world2sign = npc.get_transform().get_inverse_matrix()\n                extent = npc.bounding_box.extent\n                center = npc.get_transform().transform(npc.bounding_box.location)\n                local_verts = calculate_cube_vertices(npc.bounding_box.location, npc.bounding_box.extent)\n                global_verts = []\n                for l_v in local_verts:\n                    g_v = npc.get_transform().transform(carla.Location(l_v[0], l_v[1], l_v[2]))\n                    global_verts.append([g_v.x, g_v.y, g_v.z])\n                road_id = CarlaDataProvider.get_map().get_waypoint(location).road_id\n                lane_id = CarlaDataProvider.get_map().get_waypoint(location).lane_id\n                section_id = CarlaDataProvider.get_map().get_waypoint(location).section_id\n                # distance = npc.get_transform().location.distance(self.manager.ego_vehicles[0].get_transform().location)\n                distance = compute_2d_distance(npc.get_transform().location, self.manager.ego_vehicles[0].get_transform().location)\n                if traffic_sign.most_affect_sign and str(traffic_sign.most_affect_sign.id) == npc_id:\n                    affects_ego = True\n                else:\n                    affects_ego = False\n\n                result = {\n                    'class': 'traffic_sign',\n                    'id': npc_id,\n                    'location': [location.x, location.y, location.z],\n                    'rotation': [rotation.pitch, rotation.roll, rotation.yaw],\n                    'bbx_loc': [npc.bounding_box.location.x, npc.bounding_box.location.y, npc.bounding_box.location.z],\n                    'center': [center.x, center.y, center.z],\n                    'extent': [extent.x, extent.y, extent.z],\n                    'world_cord': global_verts,\n                    # 'extent': [extent.x, 0.5, extent.z],\n                    'semantic_tags': npc.semantic_tags,\n                    'type_id': npc.type_id,\n                    'distance': distance,\n                    'affects_ego': affects_ego,\n                    'road_id': road_id,\n                    'lane_id': lane_id,\n                    'section_id': section_id,\n                    'world2sign': world2sign,\n                    # 'actor': npc, # for debug\n                }\n            results.append(result)\n        return results\n\n    def polar_to_cartesian(self, altitude, azimuth, depth):\n        \"\"\"\n        Convert polar coordinates (altitude, azimuth, depth) to Cartesian (x, y, z).\n        Altitude and azimuth are assumed to be in radians.\n        \"\"\"\n        z = depth * np.sin(altitude)\n        r_cos_altitude = depth * np.cos(altitude)\n        x = r_cos_altitude * np.cos(azimuth)\n        y = r_cos_altitude * np.sin(azimuth)\n        return x, y, z\n\n    def get_radar_points_in_bbox(self, vehicle_pos, vehicle_yaw, extent, radar_data):\n        \"\"\"\n        Checks for a given vehicle in ego coordinate system, how many RADAR hits there are in its bounding box.\n        :param vehicle_pos: Relative position of the vehicle w.r.t. the ego [x, y, z]\n        :param vehicle_yaw: Relative orientation of the vehicle w.r.t. the ego in radians\n        :param extent: List, half extent of the bounding box [length/2, width/2, height/2]\n        :param radar_data: RADAR data with structure [altitude, azimuth, depth, velocity]\n        :return: Returns the number of RADAR hits within the bounding box of the vehicle\n        \"\"\"\n        radar_cartesian = np.array([self.polar_to_cartesian(np.radians(altitude), np.radians(azimuth), depth)\n                                    for altitude, azimuth, depth, _ in radar_data])\n\n        rotation_matrix = np.array([[np.cos(vehicle_yaw), -np.sin(vehicle_yaw), 0.0],\n                                    [np.sin(vehicle_yaw), np.cos(vehicle_yaw), 0.0],\n                                    [0.0, 0.0, 1.0]])\n\n        # Transform RADAR points to vehicle coordinate system\n        vehicle_radar = (rotation_matrix.T @ (radar_cartesian - vehicle_pos).T).T\n\n        # Half extents for the bounding box\n        x, y, z = extent\n        num_hits = ((vehicle_radar[:, 0] <= x) & (vehicle_radar[:, 0] >= -x) & \n                    (vehicle_radar[:, 1] <= y) & (vehicle_radar[:, 1] >= -y) & \n                    (vehicle_radar[:, 2] <= z) & (vehicle_radar[:, 2] >= -z)).sum()\n        return num_hits\n    \n    def get_lidar_points_in_bbox(self, vehicle_pos, vehicle_yaw, extent, lidar):\n        \"\"\"\n        Checks for a given vehicle in ego coordinate system, how many LiDAR hit there are in its bounding box.\n        :param vehicle_pos: Relative position of the vehicle w.r.t. the ego\n        :param vehicle_yaw: Relative orientation of the vehicle w.r.t. the ego\n        :param extent: List, Extent of the bounding box\n        :param lidar: LiDAR point cloud\n        :return: Returns the number of LiDAR hits within the bounding box of the\n        vehicle\n        \"\"\"\n\n        rotation_matrix = np.array([[np.cos(vehicle_yaw), -np.sin(vehicle_yaw), 0.0],\n                                    [np.sin(vehicle_yaw), np.cos(vehicle_yaw), 0.0], [0.0, 0.0, 1.0]])\n\n        # LiDAR in the with the vehicle as origin\n        vehicle_lidar = (rotation_matrix.T @ (lidar - vehicle_pos).T).T\n\n        # check points in bbox\n        x, y, z = extent.x, extent.y, extent.z\n        num_points = ((vehicle_lidar[:, 0] < x) & (vehicle_lidar[:, 0] > -x) & (vehicle_lidar[:, 1] < y) &\n                    (vehicle_lidar[:, 1] > -y) & (vehicle_lidar[:, 2] < z) & (vehicle_lidar[:, 2] > -z)).sum()\n        return num_points\n    \n    def gps_to_location(self, gps):\n        # gps content: numpy array: [lat, lon, alt]\n        lat, lon = gps\n        scale = math.cos(self.lat_ref * math.pi / 180.0)\n        my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)\n        mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0\n        y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my\n        x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0\n        return np.array([x, y])\n        pass\n    \n    def _get_latlon_ref(self):\n        \"\"\"\n        Convert from waypoints world coordinates to CARLA GPS coordinates\n        :return: tuple with lat and lon coordinates\n        \"\"\"\n        xodr = CarlaDataProvider.get_map().to_opendrive()\n        tree = ET.ElementTree(ET.fromstring(xodr))\n\n        # default reference\n        lat_ref = 42.0\n        lon_ref = 2.0\n\n        for opendrive in tree.iter(\"OpenDRIVE\"):\n            for header in opendrive.iter(\"header\"):\n                for georef in header.iter(\"geoReference\"):\n                    if georef.text:\n                        str_list = georef.text.split(' ')\n                        for item in str_list:\n                            if '+lat_0' in item:\n                                lat_ref = float(item.split('=')[1])\n                            if '+lon_0' in item:\n                                lon_ref = float(item.split('=')[1])\n        return lat_ref, lon_ref"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/download_mini.sh",
    "content": "#!/bin/bash\n\n# Check if huggingface-hub is installed\nif ! python -m pip show huggingface-hub > /dev/null 2>&1; then\n  echo \"huggingface-hub is not installed. Installing now...\"\n  python -m pip install huggingface-hub\nelse\n  echo \"huggingface-hub is already installed.\"\nfi\n\nmkdir Bench2Drive-mini\n\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"HardBreakRoute_Town01_Route30_Weather3.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"DynamicObjectCrossing_Town02_Route13_Weather6.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"Accident_Town03_Route156_Weather0.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"YieldToEmergencyVehicle_Town04_Route165_Weather7.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"ConstructionObstacle_Town05_Route68_Weather8.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"ParkedObstacle_Town10HD_Route371_Weather7.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"ControlLoss_Town11_Route401_Weather11.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"AccidentTwoWays_Town12_Route1444_Weather0.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"OppositeVehicleTakingPriority_Town13_Route600_Weather2.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\nhuggingface-cli download --resume-download --repo-type dataset rethinklab/Bench2Drive --include \"VehicleTurningRoute_Town15_Route443_Weather1.tar.gz\" --local-dir Bench2Drive-mini --local-dir-use-symlinks False\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/efficiency_smoothness_benchmark.py",
    "content": "from scipy.signal import savgol_filter\n# import numpy.typing as npt\nimport numpy as np\nimport json\nimport re\nimport argparse\nimport os\n\n# (1) ego_jerk_metric,\nmax_abs_mag_jerk = 8.37  # [m/s^3]\n\n# (2) ego_lat_acceleration_metric\nmax_abs_lat_accel = 4.89  # [m/s^2]\n\n# (3) ego_lon_acceleration_metric\nmax_lon_accel = 2.40  # [m/s^2]\nmin_lon_accel = -4.05\n\n# (4) ego_yaw_acceleration_metric\nmax_abs_yaw_accel = 1.93  # [rad/s^2]\n\n# (5) ego_lon_jerk_metric\nmax_abs_lon_jerk = 4.13  # [m/s^3]\n\n# (6) ego_yaw_rate_metric\nmax_abs_yaw_rate = 0.95  # [rad/s]\n\n'''\nwindow size = 8\n'''\n\ndef chunk_arrays(arrays, m):\n    chunks = [chunk_array(arr, m) for arr in arrays]\n    return chunks\n\ndef chunk_array(arr, m):\n    chunks = [arr[i * m:(i + 1) * m] for i in range((len(arr) + m - 1) // m)]\n    return chunks\n\ndef seg_compute_comfort_metric(acceleration,\n    angular_velocity,\n    forward_vector,\n    right_vector,\n    location,\n    rotation,\n    window_size: int = 7,\n    poly_order: int = 2,\n    deriv_order: int = 1,\n    time_interval: float = 0.1,\n    per_step: int = 20):\n    episode_len = len(angular_velocity)\n    if episode_len <= per_step:\n        res = compute_comfort_metric( acceleration, angular_velocity, forward_vector, right_vector, location, rotation)\n        return 1. if res else 0.\n    seg_data = chunk_arrays([acceleration, angular_velocity, forward_vector, right_vector, location, rotation], per_step)\n    \n    res = []\n    for index in range(len(seg_data[0])):\n        if len(seg_data[0][index]) < per_step:\n            continue\n        res.append(compute_comfort_metric(seg_data[0][index], seg_data[1][index], seg_data[2][index], seg_data[3][index], seg_data[4][index], seg_data[5][index]))\n    return res.count(True) / len(res)\n    pass\n\ndef compute_comfort_metric(\n    acceleration,\n    angular_velocity,\n    forward_vector,\n    right_vector,\n    location,\n    rotation,\n    window_size: int = 7,\n    poly_order: int = 2,\n    deriv_order: int = 1,\n    time_interval: float = 0.1\n):\n    window_size = min(window_size, len(acceleration))\n    if not (poly_order < window_size):\n        raise ValueError(f\"{poly_order} < {window_size} does not hold!\")\n    \n    _2d_acceleration = np.array([[v[0], v[1]] for v in acceleration])\n    _2d_forward_vector = np.array([[vec[0], vec[1]] for vec in forward_vector])\n    _2d_right_vector = np.array([[vec[0], vec[1]] for vec in right_vector])\n    _z_angular_rate = np.array([a[2] for a in angular_velocity])\n    _z_yaw_rate = _phase_unwrap(_z_angular_rate)\n    \n    lon_acc = np.einsum('ij,ij->i', _2d_acceleration, _2d_forward_vector)\n    lat_acc = np.einsum('ij,ij->i', _2d_acceleration, _2d_right_vector)\n    magnitude_acc = np.hypot(_2d_acceleration[:, 0], _2d_acceleration[:, 1])\n    \n    _z_yaw_acc = savgol_filter(\n        _z_yaw_rate,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    _z_yaw_rate = savgol_filter(\n        _z_yaw_rate,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    lon_acc = savgol_filter(\n        lon_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    lat_acc = savgol_filter(\n        lat_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    magnitude_acc = savgol_filter(\n        magnitude_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        axis=-1,\n    )\n    \n    dx = time_interval \n    magnitude_jerk = savgol_filter(\n        magnitude_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        deriv=deriv_order,\n        delta=dx,\n        axis=-1,\n    )\n    \n    lon_jerk = savgol_filter(\n        lon_acc,\n        polyorder=poly_order,\n        window_length=window_size,\n        deriv=deriv_order,\n        delta=dx,\n        axis=-1,\n    )\n    \n    res = np.array([\n        _within_bound(\n        lon_acc, min_bound=min_lon_accel, max_bound=max_lon_accel\n    ),\n        _within_bound(\n        lat_acc, min_bound=-max_abs_lat_accel, max_bound=max_abs_lat_accel\n    ),\n        _within_bound(\n        magnitude_jerk, min_bound=-max_abs_mag_jerk, max_bound=max_abs_mag_jerk\n    ),\n        _within_bound(\n        lon_jerk, min_bound=-max_abs_lon_jerk, max_bound=max_abs_lon_jerk\n    ),\n        _within_bound(\n        _z_yaw_acc, min_bound=-max_abs_yaw_accel, max_bound=max_abs_yaw_accel\n    ),\n        _within_bound(\n        _z_yaw_rate, min_bound=-max_abs_yaw_rate, max_bound=max_abs_yaw_rate\n    )\n    ])\n    res = bool(np.all(res))\n    return res\n    \ndef _approximate_derivatives(\n    y,\n    x,\n    window_size: int = 5,\n    poly_order: int = 2,\n    deriv_order: int = 1,\n    axis: int = -1,\n):\n    window_size = min(window_size, len(x))\n\n    if not (poly_order < window_size):\n        raise ValueError(f\"{poly_order} < {window_size} does not hold!\")\n\n    dx = np.diff(x, axis=-1)\n    if not (dx > 0).all():\n        raise RuntimeError(\"dx is not monotonically increasing!\")\n\n    dx = dx.mean()\n    derivative = savgol_filter(\n        y,\n        polyorder=poly_order,\n        window_size=window_size,\n        deriv=deriv_order,\n        delta=dx,\n        axis=axis,\n    )\n    return derivative\n\ndef _within_bound(\n    metric,\n    min_bound = None,\n    max_bound = None,\n):\n    \"\"\"\n    Determines wether values in batch-dim are within bounds.\n    :param metric: metric values\n    :param min_bound: minimum bound, defaults to None\n    :param max_bound: maximum bound, defaults to None\n    :return: array of booleans wether metric values are within bounds\n    \"\"\"\n    min_bound = min_bound if min_bound else float(-np.inf)\n    max_bound = max_bound if max_bound else float(np.inf)\n    metric_values = np.array(metric)\n    metric_within_bound = (metric_values > min_bound) & (metric_values < max_bound)\n    return np.all(metric_within_bound, axis=-1)\n\ndef _phase_unwrap(headings):\n    \"\"\"\n    Returns an array of heading angles equal mod 2 pi to the input heading angles,\n    and such that the difference between successive output angles is less than or\n    equal to pi radians in absolute value\n    :param headings: An array of headings (radians)\n    :return The phase-unwrapped equivalent headings.\n    \"\"\"\n    # There are some jumps in the heading (e.g. from -np.pi to +np.pi) which causes approximation of yaw to be very large.\n    # We want unwrapped[j] = headings[j] - 2*pi*adjustments[j] for some integer-valued adjustments making the absolute value of\n    # unwrapped[j+1] - unwrapped[j] at most pi:\n    # -pi <= headings[j+1] - headings[j] - 2*pi*(adjustments[j+1] - adjustments[j]) <= pi\n    # -1/2 <= (headings[j+1] - headings[j])/(2*pi) - (adjustments[j+1] - adjustments[j]) <= 1/2\n    # So adjustments[j+1] - adjustments[j] = round((headings[j+1] - headings[j]) / (2*pi)).\n    two_pi = 2.0 * np.pi\n    adjustments = np.zeros_like(headings)\n    adjustments[..., 1:] = np.cumsum(\n        np.round(np.diff(headings, axis=-1) / two_pi), axis=-1\n    )\n    unwrapped = headings - two_pi * adjustments\n    return unwrapped\n\n\ndef read_from_json(filepath, metric_dir=None):\n    with open(filepath, 'r') as f:\n        data = json.load(f)\n    all_data = []\n    driving_efficiency = []\n    for record in data[\"_checkpoint\"][\"records\"]:\n        filepath = os.path.join(metric_dir, record[\"save_name\"], 'metric_info.json')\n        temp_dict = {}\n        temp_dict[\"acceleration\"] = []\n        temp_dict[\"angular_velocity\"] = []\n        temp_dict[\"forward_vector\"] = []\n        temp_dict[\"right_vector\"] = []\n        temp_dict[\"location\"] = []\n        temp_dict[\"rotation\"] = []\n        with open(filepath, 'r') as file:\n            json_data = json.load(file)\n            for k, v in json_data.items():\n                temp_dict[\"acceleration\"].append(v[\"acceleration\"])\n                temp_dict[\"angular_velocity\"].append(v[\"angular_velocity\"])\n                temp_dict[\"forward_vector\"].append(v[\"forward_vector\"])\n                temp_dict[\"right_vector\"].append(v[\"right_vector\"])\n                temp_dict[\"location\"].append(v[\"location\"])\n                temp_dict[\"rotation\"].append(v[\"rotation\"])\n        for k, v in temp_dict.items():\n            temp_dict[k] = np.array(v)\n        all_data.append(temp_dict)\n        if len(record[\"infractions\"][\"min_speed_infractions\"]) < 1:\n            continue\n        else:\n            driving_e = []\n            for min_speed_infrac in record[\"infractions\"][\"min_speed_infractions\"]:\n                number = re.search(r\"\\b\\d+\\.?\\d*%\", min_speed_infrac)\n                if float(number.group().rstrip('%')) > 1000:\n                    continue\n                driving_e.append(float(number.group().rstrip('%')))\n            driving_e = sum(driving_e) / len(driving_e)\n            driving_efficiency.append(driving_e)\n    return all_data, driving_efficiency\n\nif __name__=='__main__':\n    argparser = argparse.ArgumentParser(description=__doc__)\n    argparser.add_argument('-f', '--file', default=\"uniad_b2d_traj/merged.json\", help='route file')\n    argparser.add_argument('-m', '--metric_dir', default=\"eval_bench2drive220_uniad_traj/\")\n    args = argparser.parse_args()\n    all_data, driving_efficiency_list = read_from_json(args.file, args.metric_dir)\n    comfort_res = []\n    for record in all_data:\n        comfort_res.append(seg_compute_comfort_metric(**record))\n    print(f'Driving Efficiency={sum(driving_efficiency_list) / len(driving_efficiency_list)}')\n    print(f'Driving Smoothness={sum(comfort_res)/len(comfort_res)}')"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/gen_hdmap.py",
    "content": "import carla\nimport numpy as np\n\nimport cv2\n\nfrom pathlib import Path\nimport os\nimport argparse\nimport time\nimport subprocess\nimport json\n\ndef check_waypoints_status(waypoints_list):\n    first_wp = waypoints_list[0]\n    init_status = first_wp.is_junction\n    current_status = first_wp.is_junction\n    change_status_time = 0\n    for wp in waypoints_list[1:]:\n        if wp.is_junction != current_status:\n            current_status = wp.is_junction\n            change_status_time += 1\n        pass\n    if change_status_time == 0:\n        return 'Junction' if init_status else 'Normal'\n    elif change_status_time == 1:\n        return 'EnterNormal' if init_status else 'EnterJunction'\n    elif change_status_time == 2:\n        return 'PassNormal' if init_status else 'PassJunction'\n    else:\n        return 'StartJunctionMultiChange' if init_status else 'StartNormalMultiChange'\n\nclass TriggerVolumeGettor(object):\n    \n    @staticmethod\n    def get_global_bbx(actor, bbx):\n        if actor.is_alive:\n            bbx.location = actor.get_transform().transform(bbx.location)\n            bbx.rotation = actor.get_transform().rotation\n            return bbx\n        return None\n\n    @staticmethod\n    def get_corners_from_actor_list(actor_list):\n        for actor_transform, bb_loc, bb_ext in actor_list:\n\n            corners = [carla.Location(x=-bb_ext.x, y=-bb_ext.y),\n                       carla.Location(x=bb_ext.x, y=-bb_ext.y),\n                       carla.Location(x=bb_ext.x, y=0),\n                       carla.Location(x=bb_ext.x, y=bb_ext.y),\n                       carla.Location(x=-bb_ext.x, y=bb_ext.y)]\n            corners = [bb_loc + corner for corner in corners]\n\n            corners = [actor_transform.transform(corner) for corner in corners]\n            corners = [[corner.x, corner.y, corner.z] for corner in corners]\n        return corners\n    \n    @staticmethod\n    def insert_point_into_dict(lane_marking_dict, corners, road_id, parent_actor_location, Volume_Type=None):\n        if road_id not in lane_marking_dict.keys():\n            print(\"Cannot find road:\", road_id)\n            raise\n        if Volume_Type is None:\n            print(\"Missing 'Volume Type' \")\n            raise\n        if 'Trigger_Volumes' not in lane_marking_dict[road_id]:\n            lane_marking_dict[road_id]['Trigger_Volumes'] = [{'Points': corners[:], 'Type': Volume_Type, 'ParentActor_Location': parent_actor_location[:]}]\n        else:\n            lane_marking_dict[road_id]['Trigger_Volumes'].append({'Points': corners[:], 'Type': Volume_Type, 'ParentActor_Location': parent_actor_location[:]})\n    \n    @staticmethod\n    def get_stop_sign_trigger_volume(all_stop_sign_actors, lane_marking_dict, carla_map):\n        for actor in all_stop_sign_actors:\n            bb_loc = carla.Location(actor.trigger_volume.location)\n            bb_ext = carla.Vector3D(actor.trigger_volume.extent)\n            bb_ext.x = max(bb_ext.x, bb_ext.y)\n            bb_ext.y = max(bb_ext.x, bb_ext.y)\n            base_transform = actor.get_transform()\n            stop_info_list = [(carla.Transform(base_transform.location, base_transform.rotation), bb_loc, bb_ext)]\n            corners = TriggerVolumeGettor.get_corners_from_actor_list(stop_info_list)\n            \n            trigger_volume_wp = carla_map.get_waypoint(base_transform.transform(bb_loc))\n            actor_loc = actor.get_location()\n            actor_loc_points = [actor_loc.x, actor_loc.y, actor_loc.z]\n            TriggerVolumeGettor.insert_point_into_dict(lane_marking_dict, corners, trigger_volume_wp.road_id, actor_loc_points, Volume_Type='StopSign')\n            \n        pass\n    \n    @staticmethod\n    def get_traffic_light_trigger_volume(all_trafficlight_actors, lane_marking_dict, carla_map):\n        for actor in all_trafficlight_actors:\n            base_transform = actor.get_transform()\n            tv_loc = actor.trigger_volume.location\n            tv_ext = actor.trigger_volume.extent\n            x_values = np.arange(-0.9 * tv_ext.x, 0.9 * tv_ext.x, 1.0)\n            area = []\n            for x in x_values:\n                point_location = base_transform.transform(tv_loc + carla.Location(x=x)) \n                area.append(point_location)\n            ini_wps = []\n            for pt in area:\n                wpx = carla_map.get_waypoint(pt)\n                # As x_values are arranged in order, only the last one has to be checked\n                if not ini_wps or ini_wps[-1].road_id != wpx.road_id or ini_wps[-1].lane_id != wpx.lane_id:\n                    ini_wps.append(wpx)\n            \n            close2junction_points = []\n            littlefar2junction_points = []\n            for wpx in ini_wps:\n                while not wpx.is_intersection:\n                    next_wp = wpx.next(0.5)\n                    if not next_wp:\n                        break\n                    next_wp = next_wp[0]\n                    if next_wp and not next_wp.is_intersection:\n                        wpx = next_wp\n                    else:\n                        break\n                vec_forward = wpx.transform.get_forward_vector()\n                vec_right = carla.Vector3D(x=-vec_forward.y, y=vec_forward.x, z=0) # 2D\n\n                loc_left = wpx.transform.location - 0.4 * wpx.lane_width * vec_right\n                loc_right = wpx.transform.location + 0.4 * wpx.lane_width * vec_right\n                close2junction_points.append([loc_left.x, loc_left.y, loc_left.z])\n                close2junction_points.append([loc_right.x, loc_right.y, loc_right.z])\n                \n                try:\n                    loc_far_left = wpx.previous(0.5)[0].transform.location - 0.4 * wpx.lane_width * vec_right\n                    loc_far_right = wpx.previous(0.5)[0].transform.location + 0.4 * wpx.lane_width * vec_right\n                except Exception:\n                    continue\n                \n                littlefar2junction_points.append([loc_far_left.x, loc_far_left.y, loc_far_left.z])\n                littlefar2junction_points.append([loc_far_right.x, loc_far_right.y, loc_far_right.z])\n                \n            traffic_light_points = close2junction_points + littlefar2junction_points[::-1]\n            trigger_volume_wp = carla_map.get_waypoint(base_transform.transform(tv_loc))\n            actor_loc = actor.get_location()\n            actor_loc_points = [actor_loc.x, actor_loc.y, actor_loc.z]\n            TriggerVolumeGettor.insert_point_into_dict(lane_marking_dict, traffic_light_points, trigger_volume_wp.road_id, actor_loc_points, Volume_Type='TrafficLight')\n        pass\n    \n    pass\nt = 0\nclass LankMarkingGettor(object):\n\n    '''\n        structure of lane_marking_dict:\n        {\n            road_id_0: {\n                lane_id_0: [{'Points': [((location.x,y,z) array, (rotation.roll, pitch, yaw))], 'Type': 'lane_marking_type', 'Color':'color', 'Topology':[neighbor array]}, ...]\n                ... ...\n                'Trigger_Volumes': [{'Points': [(location.x,y,z) array], 'Type': 'trigger volume type', 'ParentActor_Location': (location.x,y,z)}]\n            }\n            ... ...\n        }\n        \"location array\" is an array formed as (location_x, location_y, location_z) ...\n        'lane_marking_type' is string of landmarking type, can be 'Broken', 'Solid', 'SolidSolid', 'Other', 'NONE', etc. \n        'color' is string of landmarking color, can be 'Blue', 'White', 'Yellow',  etc. \n         neighbor array contains the ('road_id', 'lane_id') of the current landmarking adjacent to, it is directional. \n         and if current 'Type' == 'Center', there will exist a 'TopologyType' key which record the current lane's topology status. \n         if there exist a trigger volume in current road, key 'Trigger_Volumes' will be added into dict \n         where 'Points' refer to the vertexs location array, 'Type' can be 'StopSign' or 'TrafficLight'\n         'ParentActor_Location' is the location of parent actor relevant to this trigger volume. \n    '''\n    \n    @staticmethod\n    def get_lanemarkings(carla_map, lane_marking_dict={}, pixels_per_meter=2, precision=0.05):\n        \n        topology = [x[0] for x in carla_map.get_topology()]\n        topology = sorted(topology, key=lambda w: w.road_id)\n        \n        for waypoint in topology:\n            waypoints = [waypoint]\n            # Generate waypoints of a road id. Stop when road id differs\n            nxt = waypoint.next(precision)\n            if len(nxt) > 0:\n                nxt = nxt[0]\n                temp_wp = nxt\n                while nxt.road_id == waypoint.road_id:\n                    waypoints.append(nxt)\n                    nxt = nxt.next(precision)\n                    if len(nxt) > 0:\n                        nxt = nxt[0]\n                    else:\n                        break\n            print(\"current road id: \", waypoint.road_id)\n            print(\"lane id:\", waypoint.lane_id)\n            LankMarkingGettor.get_lane_markings_two_side(waypoints, lane_marking_dict)\n\n    @staticmethod\n    def get_lane_markings_two_side(waypoints, lane_marking_dict):\n        left_lane_marking_list = []\n        right_lane_marking_list = []\n        \n        center_lane_list = []\n        center_lane_wps = []\n        \n        left_previous_lane_marking_type = 1\n        left_previous_lane_marking_color = 1\n        right_previous_lane_marking_type = 1\n        right_previous_lane_marking_color = 1\n        \n        center_previous_lane_id = waypoints[0].lane_id\n        \n        for waypoint in waypoints:\n            flag = False\n            if waypoint.lane_id != center_previous_lane_id:\n                if len(center_lane_list) > 1:\n                    if waypoint.road_id not in lane_marking_dict:\n                        lane_marking_dict[waypoint.road_id] = {}\n                        status = check_waypoints_status(center_lane_wps)\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n                    elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                        status = check_waypoints_status(center_lane_wps)\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n                    else:\n                        status = check_waypoints_status(center_lane_wps)\n                        lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n                flag = True\n                center_lane_list = []\n                center_lane_wps = []\n            left_lane_marking = waypoint.left_lane_marking\n            if left_lane_marking.type != left_previous_lane_marking_type or\\\n                left_lane_marking.color != left_previous_lane_marking_color or flag:\n                    if len(left_lane_marking_list) > 1:\n                        connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n                        candidate_dict = {'Points': left_lane_marking_list[:], 'Type': str(left_previous_lane_marking_type), 'Color': str(left_previous_lane_marking_color), 'Topology': connect_to[:]}\n                        if waypoint.road_id not in lane_marking_dict:\n                            lane_marking_dict[waypoint.road_id] = {}\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        else:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n                        left_lane_marking_list = []\n            right_lane_marking = waypoint.right_lane_marking\n            if right_lane_marking.type != right_previous_lane_marking_type or\\\n                right_lane_marking.color != right_previous_lane_marking_color or flag:\n                    if len(right_lane_marking_list) > 1:\n                        connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n                        candidate_dict = {'Points': right_lane_marking_list[:], 'Type': str(right_previous_lane_marking_type), 'Color': str(right_previous_lane_marking_color), 'Topology': connect_to[:]}\n                        if waypoint.road_id not in lane_marking_dict:\n                            lane_marking_dict[waypoint.road_id] = {}\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n                        else:\n                            lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n                        right_lane_marking_list = []\n                        \n            center_lane_list.append((*LankMarkingGettor.get_lateral_shifted_transform(waypoint.transform, 0), waypoint.is_junction))\n            center_lane_wps.append(waypoint)\n            \n            left_lane_marking_list.append(LankMarkingGettor.get_lateral_shifted_transform(waypoint.transform, -0.5*waypoint.lane_width))\n            \n            right_lane_marking_list.append(LankMarkingGettor.get_lateral_shifted_transform(waypoint.transform, 0.5*waypoint.lane_width))\n            \n            left_previous_lane_marking_type = left_lane_marking.type\n            left_previous_lane_marking_color = left_lane_marking.color\n            right_previous_lane_marking_type = right_lane_marking.type\n            right_previous_lane_marking_color = right_lane_marking.color\n            center_previous_lane_id = waypoint.lane_id\n        \n        if len(left_lane_marking_list) > 1:\n            connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n            candidate_dict = {'Points': left_lane_marking_list[:], 'Type': str(left_lane_marking.type), 'Color': str(left_previous_lane_marking_color), 'Topology': connect_to[:]}\n            if waypoint.road_id not in lane_marking_dict:\n                lane_marking_dict[waypoint.road_id] = {}\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            else:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n            left_lane_marking_list = []\n        if len(right_lane_marking_list) > 1:\n            connect_to = LankMarkingGettor.get_connected_road_id(waypoint)\n            candidate_dict = {'Points': right_lane_marking_list[:], 'Type': str(right_lane_marking.type), 'Color': str(right_previous_lane_marking_color), 'Topology': connect_to[:]}\n            if waypoint.road_id not in lane_marking_dict:\n                lane_marking_dict[waypoint.road_id] = {}\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = [candidate_dict]\n            else:\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append(candidate_dict)\n            right_lane_marking_list = []\n        if len(center_lane_list) > 0:\n            if waypoint.road_id not in lane_marking_dict:\n                lane_marking_dict[waypoint.road_id] = {}\n                status = check_waypoints_status(center_lane_wps)\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n            elif center_previous_lane_id not in lane_marking_dict[waypoint.road_id]:\n                status = check_waypoints_status(center_lane_wps)\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id] = []\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n            else:\n                status = check_waypoints_status(center_lane_wps)\n                lane_marking_dict[waypoint.road_id][center_previous_lane_id].append({'Points': center_lane_list[:], 'Type': 'Center', 'Color': 'White', 'Topology': LankMarkingGettor.get_connected_road_id(waypoint)[:], 'TopologyType': status, 'Left':(center_lane_wps[-1].get_left_lane().road_id if center_lane_wps[-1].get_left_lane() else None, center_lane_wps[-1].get_left_lane().lane_id if center_lane_wps[-1].get_left_lane() else None), 'Right':(center_lane_wps[-1].get_right_lane().road_id if center_lane_wps[-1].get_right_lane() else None, center_lane_wps[-1].get_right_lane().lane_id if center_lane_wps[-1].get_right_lane() else None)})\n            \n    @staticmethod\n    def get_connected_road_id(waypoint):\n        next_waypoint = waypoint.next(0.05)\n        if next_waypoint is None:\n            return [None]\n        else:\n            return [(w.road_id, w.lane_id) for w in next_waypoint if w.lane_type == carla.LaneType.Driving]\n    \n    @staticmethod\n    def insert_element_into_dict(id, element, lane_marking_dict):\n        if id not in lane_marking_dict:\n            lane_marking_dict[id] = []\n            lane_marking_dict[id].append(element)\n        else:\n            lane_marking_dict[id].append(element)\n    \n    @staticmethod   \n    def get_lateral_shifted_transform(transform, shift):\n        right_vector = transform.get_right_vector()\n        x_offset = right_vector.x * shift\n        y_offset = right_vector.y * shift\n        z_offset = right_vector.z * shift\n        x = transform.location.x + x_offset\n        y = transform.location.y + y_offset\n        z = transform.location.z + z_offset\n        roll = transform.rotation.roll\n        pitch = transform.rotation.pitch\n        yaw = transform.rotation.yaw\n        return ((x, y, z), (roll, pitch, yaw))\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--save_dir', default='/maps')\n    parser.add_argument('--carla_town', default='Town12')\n\n    args = parser.parse_args()\n    carla_town = args.carla_town\n\n    client = carla.Client('localhost', 2000)\n    client.set_timeout(300)\n    world = client.load_world(carla_town)\n    print(\"******** sucessfully load the town:\", carla_town, \" ********\")\n    carla_map = world.get_map()\n\n    lane_marking_dict = {}\n    LankMarkingGettor.get_lanemarkings(world.get_map(), lane_marking_dict)\n    print(\"****** get all lanemarkings ******\")\n    \n    all_actors = world.get_actors()\n    all_stop_sign_actors = []\n    all_traffic_light_actors = []\n    for actor in all_actors:\n        if 'traffic.stop' in actor.type_id:\n            all_stop_sign_actors.append(actor)\n        if 'traffic_light' in actor.type_id:\n            all_traffic_light_actors.append(actor)\n    \n    print(\"Getting all trigger volumes ...\")\n    TriggerVolumeGettor.get_stop_sign_trigger_volume(all_stop_sign_actors, lane_marking_dict, carla_map)\n    TriggerVolumeGettor.get_traffic_light_trigger_volume(all_traffic_light_actors, lane_marking_dict, carla_map)\n    print(\"******* Have get all trigger volumes ! *********\")\n    \n    arr = np.array(list(lane_marking_dict.items()), dtype=object)\n    np.savez_compressed(args.save_dir+\"/\"+args.carla_town+\"_HD_map.npz\", arr=arr)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/generate_video.py",
    "content": "import cv2\nimport os\nimport numpy as np\nimport json\nfrom tqdm import trange\n\n\ndef create_video(images_folder, output_video, fps, font_scale, text_color, text_position):\n    images = [img for img in os.listdir(os.path.join(images_folder, 'rgb_front')) if img.endswith(\".jpg\") or img.endswith(\".png\")]\n    images.sort()\n\n    frame = cv2.imread(os.path.join(os.path.join(images_folder, 'rgb_front'), images[0]))\n    height, width, layers = frame.shape\n\n    fourcc = cv2.VideoWriter_fourcc(*'mp4v')\n    video = cv2.VideoWriter(output_video, fourcc, fps, (width, height))\n\n    for i in trange(1, len(images)):\n        image = images[i]\n        f = open(os.path.join(images_folder, f'meta/{i:04}.json'), 'r')\n        meta = json.load(f)\n        steer = float(meta['steer'])\n        throttle = float(meta['throttle'])\n        brake = float(meta['brake'])\n        # command = float(meta['command'])\n        # command_list = [\"VOID\", \"LEFT\", \"RIGHT\", \"STRAIGHT\", \"LANE FOLLOW\", \"CHANGE LANE LEFT\",  \"CHANGE LANE RIGHT\",]\n        speed = float(meta['speed'])\n        text = f'speed: {round(speed,2)}, steer: {round(steer,2)}, throttle: {round(throttle,2)}, brake: {round(brake,2)}'#, command: {command_list[int(command)]}'\n        img = cv2.imread(os.path.join(os.path.join(images_folder, 'rgb_front'), image))\n        cv2.putText(img, text, text_position, cv2.FONT_HERSHEY_SIMPLEX, font_scale, text_color, 2, cv2.LINE_AA)\n        video.write(img)\n    video.release()\n\nimages_folder = ''\noutput_video = ''\nfps = 15\nfont_scale = 1\ntext_color = (255, 255, 255)\ntext_position = (50, 50)\n\ncreate_video(images_folder, output_video, fps, font_scale, text_color, text_position)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/merge_route_json.py",
    "content": "import json\nimport glob\nimport argparse\nimport os\n\ndef merge_route_json(folder_path):\n    file_paths = glob.glob(f'{folder_path}/*.json')\n    merged_records = []\n    driving_score = []\n    success_num = 0\n    for file_path in file_paths:\n        if 'merged.json' in file_path: continue\n        with open(file_path) as file:\n            data = json.load(file)\n            records = data['_checkpoint']['records']\n            for rd in records:\n                rd.pop('index')\n                merged_records.append(rd)\n                driving_score.append(rd['scores']['score_composed'])\n                if rd['status']=='Completed' or rd['status']=='Perfect':\n                    success_flag = True\n                    for k,v in rd['infractions'].items():\n                        if len(v)>0 and k != 'min_speed_infractions':\n                            success_flag = False\n                            break\n                    if success_flag:\n                        success_num += 1\n                        print(rd['route_id'])\n    if len(merged_records) != 220:\n        print(f\"-----------------------Warning: there are {len(merged_records)} routes in your json, which does not equal to 220. All metrics (Driving Score, Success Rate, Ability) are inaccurate!!!\")\n    merged_records = sorted(merged_records, key=lambda d: d['route_id'], reverse=True)\n    _checkpoint = {\n        \"records\": merged_records\n    }\n\n    merged_data = {\n        \"_checkpoint\": _checkpoint,\n        \"driving score\": sum(driving_score) / 220,\n        \"success rate\": success_num / 220,\n        \"eval num\": len(driving_score),\n    }\n\n    with open(os.path.join(folder_path, 'merged.json'), 'w') as file:\n        json.dump(merged_data, file, indent=4)\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('-f', '--folder', help='old foo help')\n    args = parser.parse_args()\n    merge_route_json(args.folder)\n"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/split_xml.py",
    "content": "import xml.etree.ElementTree as ET\n\n\ndef split_list_into_n_parts(lst, n):\n    k, m = divmod(len(lst), n)\n    return (lst[i * k + min(i, m):(i + 1) * k + min(i + 1, m)] for i in range(n))\n\ndef main(base_route, task_num, algo, planner_type):\n    tree = ET.parse(f'{base_route}.xml')\n    root = tree.getroot()\n    case = root.findall('route')\n    results = split_list_into_n_parts(case, task_num)\n    for index, re in enumerate(results):\n        new_root = ET.Element(\"routes\")\n        for x in re:\n            new_root.append(x)\n        new_tree = ET.ElementTree(new_root)\n        new_tree.write(f'{base_route}_{index}_{algo}_{planner_type}.xml', encoding='utf-8', xml_declaration=True)\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"base_route\", type=str)\n    parser.add_argument(\"task_num\", type=int)\n    parser.add_argument(\"algo\", type=str)\n    parser.add_argument(\"planner_type\", type=str)\n    args = parser.parse_args()\n    main(args.base_route, args.task_num, args.algo, args.planner_type)"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/utils.py",
    "content": "import numpy as np\nimport cv2\nimport math\n\nWINDOW_HEIGHT = 900\nWINDOW_WIDTH = 1600\n\nDIS_CAR_SAVE = 100\nDIS_WALKER_SAVE = 100\nDIS_SIGN_SAVE = 100\nDIS_LIGHT_SAVE = 100\n\nedges = [[0,1], [1,3], [3,2], [2,0], [0,4], [4,5], [5,1], [5,7], [7,6], [6,4], [6,2], [7,3]]\n\ndef get_image_point(loc, K, w2c):\n    # Calculate 2D projection of 3D coordinate\n\n    # Format the input coordinate (loc is a carla.Position object)\n    point = np.array([loc[0], loc[1], loc[2], 1])\n    # transform to camera coordinates\n    point_camera = np.dot(w2c, point)\n\n    # New we must change from UE4's coordinate system to an \"standard\"\n    # (x, y ,z) -> (y, -z, x)\n    # and we remove the fourth componebonent also\n    point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n\n    depth = point_camera[2]\n\n    # now project 3D->2D using the camera matrix\n    point_img = np.dot(K, point_camera)\n    # normalize\n    point_img[0] /= point_img[2]\n    point_img[1] /= point_img[2]\n    \n    return point_img[0:2], depth\n\ndef point_in_canvas_wh(pos):\n    \"\"\"Return true if point is in canvas\"\"\"\n    if (pos[0] >= 0) and (pos[0] < WINDOW_WIDTH) and (pos[1] >= 0) and (pos[1] < WINDOW_HEIGHT):\n        return True\n    return False\n\ndef get_forward_vector(yaw):\n    # Convert the yaw angle from degrees to radians\n    yaw_rad = math.radians(yaw)\n    # Calculate the X and Y components of the forward vector (in a left-handed coordinate system with Z-axis upwards)\n    # Note: In a left-handed coordinate system, the positive Y direction could correspond to either forward or backward, depending on the specific application scenario\n    x = math.cos(yaw_rad)\n    y = math.sin(yaw_rad)\n    # On a horizontal plane, the Z component of the forward vector is 0\n    z = 0\n    return np.array([x, y, z])\n\ndef calculate_cube_vertices(center, extent):\n    if isinstance(center, list):\n        cx, cy, cz = center\n        x, y, z = extent\n    else:\n        cx, cy, cz = center.x,  center.y,  center.z\n        x, y, z = extent.x, extent.y, extent.z\n    vertices = [\n        (cx + x, cy + y, cz + z),\n        (cx + x, cy + y, cz - z),\n        (cx + x, cy - y, cz + z),\n        (cx + x, cy - y, cz - z),\n        (cx - x, cy + y, cz + z),\n        (cx - x, cy + y, cz - z),\n        (cx - x, cy - y, cz + z),\n        (cx - x, cy - y, cz - z)\n    ]\n    return vertices\n\ndef draw_dashed_line(img, start_point, end_point, color, thickness=1, dash_length=5):\n    \"\"\"\n    Draw a dashed line on an image.\n    Arguments:\n    - img: The image on which to draw the dashed line.\n    - start_point: The starting point of the dashed line, in the format (x, y).\n    - end_point: The ending point of the dashed line, in the format (x, y).\n    - color: The color of the dashed line, in the format (B, G, R).\n    - thickness: The thickness of the line.\n    - dash_length: The length of each dash segment in the dashed line.\n    \"\"\"\n    # Calculate total length\n    d = np.sqrt((end_point[0] - start_point[0])**2 + (end_point[1] - start_point[1])**2)\n    dx = (end_point[0] - start_point[0]) / d\n    dy = (end_point[1] - start_point[1]) / d\n\n    x, y = start_point[0], start_point[1]\n\n    while d >= dash_length:\n        # Calculate the end point of the next segment\n        x_end = x + dx * dash_length\n        y_end = y + dy * dash_length\n        cv2.line(img, (int(x), int(y)), (int(x_end), int(y_end)), color, thickness)\n\n        # Update starting point and remaining length\n        x = x_end + dx * dash_length\n        y = y_end + dy * dash_length\n        d -= 2 * dash_length\n\ndef world_to_ego(point_world, w2e):\n    point_world = np.array([point_world[0], point_world[1], point_world[2], 1])\n    point_ego = np.dot(w2e, point_world)\n    point_ego = [point_ego[1], -point_ego[0], point_ego[2]]\n    return point_ego\n\ndef vector_angle(v1, v2):\n    dot_product = np.dot(v1, v2)\n    magnitude_v1 = np.linalg.norm(v1)\n    magnitude_v2 = np.linalg.norm(v2)\n    cos_theta = dot_product / (magnitude_v1 * magnitude_v2)\n    angle_radians = np.arccos(cos_theta)\n    angle_degrees = np.degrees(angle_radians)\n    return angle_degrees\n\ndef get_weather_id(weather_conditions):\n    from xml.etree import ElementTree as ET\n    tree = ET.parse('./leaderboard/data/weather.xml')\n    root = tree.getroot()\n    def conditions_match(weather, conditions):\n        for (key, value) in weather:\n            if key == 'route_percentage' : continue\n            if str(conditions[key]) != value:\n                return False\n        return True\n    for case in root.findall('case'):\n        weather = case[0].items()\n        if conditions_match(weather, weather_conditions):\n            return case.items()[0][1]\n    return None\n\ndef compute_2d_distance(loc1, loc2):\n    return math.sqrt((loc1.x-loc2.x)**2+(loc1.y-loc2.y)**2)\n\ndef build_projection_matrix(w, h, fov, is_behind_camera=False):\n    focal = w / (2.0 * np.tan(fov * np.pi / 360.0))\n    K = np.identity(3)\n\n    if is_behind_camera:\n        K[0, 0] = K[1, 1] = -focal\n    else:\n        K[0, 0] = K[1, 1] = focal\n\n    K[0, 2] = w / 2.0\n    K[1, 2] = h / 2.0\n    return K\n\ndef convert_depth(data):\n    \"\"\"\n    Computes the normalized depth from a CARLA depth map.\n    \"\"\"\n    data = data.astype(np.float16)\n\n    normalized = np.dot(data, [65536.0, 256.0, 1.0])\n    normalized /= (256 * 256 * 256 - 1)\n    return normalized * 1000\n\ndef get_relative_transform(ego_matrix, vehicle_matrix):\n    \"\"\"\n    Returns the position of the vehicle matrix in the ego coordinate system.\n    :param ego_matrix: ndarray 4x4 Matrix of the ego vehicle in global\n    coordinates\n    :param vehicle_matrix: ndarray 4x4 Matrix of another actor in global\n    coordinates\n    :return: ndarray position of the other vehicle in the ego coordinate system\n    \"\"\"\n    relative_pos = vehicle_matrix[:3, 3] - ego_matrix[:3, 3]\n    rot = ego_matrix[:3, :3].T\n    relative_pos = rot @ relative_pos\n\n    return relative_pos\n\ndef normalize_angle(x):\n    x = x % (2 * np.pi)  # force in range [0, 2 pi)\n    if x > np.pi:  # move to [-pi, pi)\n        x -= 2 * np.pi\n    return x\n\ndef build_skeleton(ped, sk_links):\n    ######## get the pedestrian skeleton #########\n    bones = ped.get_bones()\n\n    # list where we will store the lines we will project\n    # onto the camera output\n    lines_3d = []\n\n    # cycle through the bone pairs in skeleton.txt and retrieve the joint positions\n    for link in sk_links[1:]:\n\n        # get the roots of the two bones to be joined\n        bone_transform_1 = next(filter(lambda b: b.name == link[0], bones.bone_transforms), None)\n        bone_transform_2 = next(filter(lambda b: b.name == link[1], bones.bone_transforms), None)\n\n        # some bone names aren't matched\n        if bone_transform_1 is not None and bone_transform_2 is not None:\n            lines_3d.append([(bone_transform_1.world.location.x, bone_transform_1.world.location.y, bone_transform_1.world.location.z), \n                             (bone_transform_2.world.location.x, bone_transform_2.world.location.y, bone_transform_2.world.location.z)]\n                            )\n    return lines_3d\n\ndef get_matrix(location, rotation):\n    \"\"\"\n    Creates matrix from carla transform.\n    \"\"\"\n    pitch, roll, yaw = rotation\n    x, y, z = location\n    c_y = np.cos(np.radians(yaw))\n    s_y = np.sin(np.radians(yaw))\n    c_r = np.cos(np.radians(roll))\n    s_r = np.sin(np.radians(roll))\n    c_p = np.cos(np.radians(pitch))\n    s_p = np.sin(np.radians(pitch))\n    matrix = np.matrix(np.identity(4))\n    matrix[0, 3] = x\n    matrix[1, 3] = y\n    matrix[2, 3] = z\n    matrix[0, 0] = c_p * c_y\n    matrix[0, 1] = c_y * s_p * s_r - s_y * c_r\n    matrix[0, 2] = -c_y * s_p * c_r - s_y * s_r\n    matrix[1, 0] = s_y * c_p\n    matrix[1, 1] = s_y * s_p * s_r + c_y * c_r\n    matrix[1, 2] = -s_y * s_p * c_r + c_y * s_r\n    matrix[2, 0] = s_p\n    matrix[2, 1] = -c_p * s_r\n    matrix[2, 2] = c_p * c_r\n    return matrix"
  },
  {
    "path": "close_loop/VAD_MomAD/tools/visualize.py",
    "content": "import json\nimport gzip\nimport os\nimport numpy as np\nimport cv2\nimport pathlib\nimport random\nimport laspy\nimport matplotlib.cm as cm\nfrom tqdm import trange\nfrom utils import get_image_point, point_in_canvas_wh, edges, world_to_ego, get_forward_vector, calculate_cube_vertices, draw_dashed_line, vector_angle, get_weather_id\n\ndef visualize_data(file_path, map_path, vis_bbox=True,  vis_top_down=True, vis_road=True, vis_lidar_bev=True, vis_lidar_to_back_image=True, vis_lidar_to_front_image=True, vis_lidar_to_front_left_image=True):\n    print(f'file_path={file_path}')\n    print(f'map_path={map_path}')\n\n    save_path = pathlib.Path(file_path.replace('v0','v0-vis'))\n    (save_path / 'camera' / 'rgb_front_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_front_landmark').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_front_left_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_front_right_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_back_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_back_left_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_back_right_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'camera' / 'rgb_top_down_3d_bbox').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'bev').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'front').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'front_left').mkdir(parents=True, exist_ok=True)\n    (save_path / 'lidar'  / 'back').mkdir(parents=True, exist_ok=True)\n\n    cam_map = {\n        'CAM_FRONT': 'rgb_front',\n        'CAM_FRONT_LEFT': 'rgb_front_left',\n        'CAM_FRONT_RIGHT': 'rgb_front_right',\n        'CAM_BACK': 'rgb_back', \n        'CAM_BACK_LEFT': 'rgb_back_left', \n        'CAM_BACK_RIGHT': 'rgb_back_right',\n        'TOP_DOWN': 'rgb_top_down'\n    }\n\n    folder_path = os.path.join(file_path, 'anno')\n    file_count = len([name for name in os.listdir(folder_path) if os.path.isfile(os.path.join(folder_path, name))])\n    map_info = dict(np.load(map_path, allow_pickle=True)['arr'])\n\n    for step in trange(file_count):\n        with gzip.open(os.path.join(file_path, f'anno/{step:05}.json.gz'), 'rt', encoding='utf-8') as gz_file:\n            anno = json.load(gz_file)\n        weather_id = get_weather_id(anno['weather'])\n        bounding_boxes = anno['bounding_boxes']\n        sensors_anno = anno['sensors']\n        # ========================== bbox ==========================\n        if vis_bbox:            \n            for key in ['CAM_FRONT','CAM_FRONT_LEFT','CAM_FRONT_RIGHT','CAM_BACK', 'CAM_BACK_LEFT', 'CAM_BACK_RIGHT']:\n                K = sensors_anno[key]['intrinsic']\n                world2cam = sensors_anno[key]['world2cam']\n                visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n                for npc in bounding_boxes:\n                    if npc['class'] == 'ego_vehicle': continue\n                    if npc['distance'] > 75: continue\n                    if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                    if 'vehicle' in npc['class']: # vehicle\n                        forward_vec = get_forward_vector(sensors_anno[key]['rotation'][2])\n                        ray = np.array(npc['location']) - np.array(sensors_anno[key]['location'])\n                        color = (random.randint(0, 255), random.randint(0, 255), random.randint(0, 255))\n                        if forward_vec.dot(ray) > 1 and vector_angle(forward_vec, ray)<45:\n                            verts = np.array(npc['world_cord'])\n                            for edge in edges:\n                                p1, p1_depth = get_image_point(verts[edge[0]], K, world2cam)\n                                p2, p2_depth = get_image_point(verts[edge[1]],  K, world2cam)\n                                draw_dashed_line(visulize_img, (int(p1[0]),int(p1[1])), (int(p2[0]),int(p2[1])), color, 2)\n                            cv2.putText(visulize_img, npc['class']+npc['id'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                    else: # sign, light, pedestrians\n                        if npc['class'] == 'traffic_sign': \n                            npc['extent'][1] = 0.5 # traffic_sign origin y is too small\n                        \n                        forward_vec = get_forward_vector(sensors_anno[key]['rotation'][2])\n                        ray = np.array(npc['location']) - np.array(sensors_anno[key]['location'])\n                        if 'affects_ego' in npc.keys() and str(npc['affects_ego']) == 'True':\n                            color = (0, 0, 255)\n                        else:\n                            color = (255, 255, 255)\n                        if forward_vec.dot(ray) > 1 and vector_angle(forward_vec, ray)<45:\n                            if 'world_cord' in npc.keys():\n                                if 'dirtdebris' in npc['type_id']:\n                                    local_verts = calculate_cube_vertices(npc['bbx_loc'], [npc['extent'][1], npc['extent'][0], npc['extent'][2]])\n                                    verts = []\n                                    for l_v in local_verts:\n                                        g_v = np.dot(np.matrix(npc['world2sign']).I, [l_v[0], l_v[1], l_v[2],1])\n                                        verts.append(g_v.tolist()[0][:-1])\n                                else:\n                                    verts = np.array(npc['world_cord'])\n                            else:\n                                verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                            for edge in edges:\n                                p1, p1_depth = get_image_point(verts[edge[0]], K, world2cam)\n                                p2, p2_depth = get_image_point(verts[edge[1]],  K, world2cam)\n                                draw_dashed_line(visulize_img, (int(p1[0]),int(p1[1])), (int(p2[0]),int(p2[1])), color, 2)\n                            if 'affects_ego' in npc.keys():\n                                cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                            else:\n                                cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                cv2.imwrite(os.path.join(save_path, f'camera/{cam_map[key]}_3d_bbox/{step:05}.jpg'), visulize_img)\n        \n        if vis_top_down:        \n            for key in ['TOP_DOWN']:\n                K = sensors_anno[key]['intrinsic']\n                world2cam = sensors_anno[key]['world2cam']\n                visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n                road_points = map_info[anno['bounding_boxes'][0]['road_id']]\n                # draw lane\n                for r_p in road_points[anno['bounding_boxes'][0]['lane_id']]:\n                    road_point = r_p['Points']\n                    road_type = r_p['Type']\n                    road_color = r_p['Color']\n                    road_topology = r_p['Topology']\n                    for point in road_point:\n                        point = np.array([point[0][0], point[0][1], point[0][2], 1])\n                        point_camera = np.dot(world2cam, point)\n                        point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                        depth = point_camera[2]\n                        point_img = np.dot(K, point_camera)\n                        if depth >0:\n                            point_img[0] /= point_img[2]\n                            point_img[1] /= point_img[2]\n                            point_img = point_img[0:2]\n                            if point_in_canvas_wh(point_img):\n                                if road_color == 'White':\n                                    cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=1, color=(255, 255, 255), thickness=-1)\n                                    if road_type == 'Center':\n                                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 0), thickness=-1)\n                                else:\n                                    cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 255), thickness=-1)                      \n                # draw vehicle\n                for npc in bounding_boxes:\n                    if 'vehicle' in npc['class']:\n                        if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                        if npc['class'] == 'ego_vehicle':\n                            color = (255, 255, 255, 255)\n                        else:\n                            color = (255, 0, 0, 255)\n                        verts = np.array(npc['world_cord'])\n                        p1, p1_depth = get_image_point(verts[0], K, world2cam)\n                        p2, p2_depth = get_image_point(verts[2],  K, world2cam)\n                        p3, p3_depth = get_image_point(verts[4],  K, world2cam)\n                        p4, p4_depth = get_image_point(verts[6],  K, world2cam)\n                        points = np.array([p1, p2, p4, p3])\n                        height, width = visulize_img.shape[:2]\n                        blk = np.zeros((height, width, 4), np.uint8)\n                        cv2.fillConvexPoly(blk, np.round(points).astype(np.int32), color)\n                        if npc['class'] == 'ego_vehicle':\n                            visulize_img = cv2.addWeighted(visulize_img, 1.0, blk[:,:,:3], 1, 1)\n                        else:\n                            visulize_img = cv2.addWeighted(visulize_img, 1.0, blk[:,:,:3], 0.25, 1)\n                        if npc['class'] == 'ego_vehicle':\n                            cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, (0,0,0), 1)\n                        else:\n                            cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                # draw sign\n                for npc in bounding_boxes:\n                    if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                    # traffic_sign\n                    if 'traffic_sign' in npc['class']:\n                        color = (0, 0, 255, 255)\n                        if 'world_cord' in npc.keys():\n                            verts = np.array(npc['world_cord'])\n                        else:\n                            verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                        p1, p1_depth = get_image_point(verts[0], K, world2cam)\n                        p2, p2_depth = get_image_point(verts[2],  K, world2cam)\n                        p3, p3_depth = get_image_point(verts[4],  K, world2cam)\n                        p4, p4_depth = get_image_point(verts[6],  K, world2cam)\n                        points = np.array([p1, p2, p4, p3])\n                        height, width = visulize_img.shape[:2]\n                        blk = np.zeros((height, width, 4), np.uint8)\n                        cv2.fillConvexPoly(blk, np.round(points).astype(np.int32), color)\n                        visulize_img = cv2.addWeighted(visulize_img, 1.0, blk[:,:,:3], 0.25, 1)\n                        cv2.putText(visulize_img, npc['class'], (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                    # traffic_light\n                    if 'traffic_light' in npc['class']:\n                        color = (255, 0, 0)\n                        verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                        for edge in edges:\n                            p1, p1_depth = get_image_point(verts[edge[0]], K, world2cam)\n                            p2, p2_depth = get_image_point(verts[edge[1]],  K, world2cam)\n                            cv2.line(visulize_img, (int(p1[0]),int(p1[1])), (int(p2[0]),int(p2[1])), color, 2)\n                        cv2.putText(visulize_img, 'traffic_light', (int(p1[0])+2,int(p1[1])+2), cv2.FONT_HERSHEY_COMPLEX, 0.5, color, 1)\n                cv2.imwrite(os.path.join(save_path, f'camera/{cam_map[key]}_3d_bbox/{step:05}.jpg'), visulize_img)\n        # ==========================================================\n\n        # ========================== road ==========================\n        if vis_road:\n            key = 'CAM_FRONT'\n            K = sensors_anno[key]['intrinsic']\n            world2cam = sensors_anno[key]['world2cam']\n            road_points = map_info[anno['bounding_boxes'][0]['road_id']]\n            road_seg = np.zeros((900, 1600, 3), dtype=np.uint8)\n            all_road_topology = set()\n            # draw current road\n            for r_p in road_points[anno['bounding_boxes'][0]['lane_id']]:\n                road_point = r_p['Points']\n                road_type = r_p['Type']\n                road_color = r_p['Color']\n                road_topology = r_p['Topology']\n                for r_t in road_topology:\n                    all_road_topology.add(r_t)\n                for point in road_point:\n                    point = np.array([point[0][0], point[0][1], point[0][2], 1])\n                    point_camera = np.dot(world2cam, point)\n                    point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                    depth = point_camera[2]\n                    point_img = np.dot(K, point_camera)\n                    if depth >0:\n                        point_img[0] /= point_img[2]\n                        point_img[1] /= point_img[2]\n                        point_img = point_img[0:2]\n                        if point_in_canvas_wh(point_img):\n                            if road_color == 'White':\n                                cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(255, 255, 255), thickness=-1)\n                                if road_type == 'Center':\n                                    cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 0), thickness=-1)\n                            else:\n                                cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 255), thickness=-1)\n            # draw road topology\n            for r_t in all_road_topology:\n                road_points = map_info[r_t[0]][r_t[1]]\n                for r_p in road_points:\n                    road_point = r_p['Points']\n                    road_type = r_p['Type']\n                    road_color = r_p['Color']\n                    road_topology = r_p['Topology']\n                    for point in road_point:\n                        point = np.array([point[0][0], point[0][1], point[0][2], 1])\n                        point_camera = np.dot(world2cam, point)\n                        point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                        depth = point_camera[2]\n                        point_img = np.dot(K, point_camera)\n                        if depth >0:\n                            point_img[0] /= point_img[2]\n                            point_img[1] /= point_img[2]\n                            point_img = point_img[0:2]\n                            if point_in_canvas_wh(point_img):\n                                if road_color == 'White':\n                                    cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(255, 255, 255), thickness=-1)\n                                    if road_type == 'Center':\n                                        cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 0), thickness=-1)\n                                else:\n                                    cv2.circle(road_seg, (int(point_img[0]), int(point_img[1])), radius=1, color=(0, 255, 255), thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'camera/{cam_map[key]}_landmark/{step:05}.png'), road_seg)\n        # # ===========================================================\n\n        # ========================== lidar to bev =====================\n        if vis_lidar_bev:\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            lidar_image = np.zeros((900, 1600, 3), dtype=np.uint8)\n            header = laspy.LasHeader(point_format=0)  # LARS point format used for storing\n            header.offsets = np.min(lidars, axis=0)\n            point_precision = 0.001\n            header.scales = np.array([point_precision, point_precision, point_precision])\n            point_record = laspy.ScaleAwarePointRecord.zeros(lidars.shape[0], header=header)\n\n            point_record.x = lidars[:, 0]\n            point_record.y = lidars[:, 1]\n            point_record.z = lidars[:, 2]\n            # (x, y,z) -> (y, -x, z), the x,y plane of the lidar system is different from that of the ego-car\n            point_record.x = lidars[:, 1]\n            point_record.y = - lidars[:, 0]\n            point_record.z = lidars[:, 2]\n\n            range_x = 85.0\n            range_y = 85.0\n            range_z = 85.0\n\n            # Normalized point cloud data\n            x_normalized = (point_record.x + range_x) / (2 * range_x)\n            y_normalized = (point_record.y + range_y) / (2 * range_y)\n            z_normalized = (point_record.z + range_z) / (2 * range_z)\n\n            # Convert normalized coordinates to image pixel index\n            x_pixels = x_normalized * (lidar_image.shape[1] - 1)\n            y_pixels = y_normalized * (lidar_image.shape[0] - 1)\n\n            for x, y, z in zip(x_pixels, y_pixels, z_normalized):\n                rgb_color = (255, 255, 255)\n                cv2.circle(lidar_image, (int(x), int(y)), radius=2, color=(int(rgb_color[0]), int(rgb_color[1]), int(rgb_color[2])), thickness=-1)\n\n            cv2.imwrite(os.path.join(save_path, f'lidar_bev/{step:05}.png'), lidar_image)\n            for npc in bounding_boxes:\n                if npc['class'] not in ['vehicle', 'ego_vehicle']: continue\n                if abs(npc['location'][2] - anno['bounding_boxes'][0]['location'][2]) > 10: continue # car in sky and underground\n                verts = calculate_cube_vertices(npc['center'], npc['extent'])\n                verts = np.array(npc['world_cord'])\n                # verts[:, 2] = verts[:, 2] - npc['extent'][2] # carla bbox need minus z \n                if npc['class'] == 'ego_vehicle':\n                    color = (0, 255, 0)\n                else:\n                    color = (0, 128, 255)\n                for edge in edges:\n                    p1 = verts[edge[0]]\n                    p1 = world_to_ego(p1, anno['bounding_boxes'][0]['world2ego'])\n                    p1_x = (p1[0] + range_x) / (2 * range_x) * (lidar_image.shape[1] - 1)\n                    p1_y = (p1[1] + range_y) / (2 * range_y) * (lidar_image.shape[0] - 1)\n\n                    p2 = verts[edge[1]]\n                    p2 = world_to_ego(p2, anno['bounding_boxes'][0]['world2ego'])\n                    p2_x = (p2[0] + range_x) / (2 * range_x) * (lidar_image.shape[1] - 1)\n                    p2_y = (p2[1] + range_y) / (2 * range_y) * (lidar_image.shape[0] - 1)\n                    cv2.line(lidar_image, (int(p1_x), int(p1_y)), (int(p2_x), int(p2_y)), color, 2)\n\n            cv2.imwrite(os.path.join(save_path, f'lidar/bev/{step:05}.png'), lidar_image)\n        # ===========================================================\n        \n        # ================ lidar to front image =====================\n        if vis_lidar_to_front_image:\n            key = 'CAM_FRONT'\n            K = sensors_anno[key]['intrinsic']\n            visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n            ego2cam = np.matrix(sensors_anno[key]['cam2ego']).I.tolist()\n\n            # lidar in ego coordinate\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            for lidar in lidars:\n                lidar = np.array([lidar[0], lidar[1], lidar[2], 1])\n                point_camera = np.dot(ego2cam, lidar)\n                point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                depth = point_camera[2]\n                point_img = np.dot(K, point_camera)\n                if depth > 0:\n                    point_img[0] /= point_img[2]\n                    point_img[1] /= point_img[2]\n                    point_img = point_img[0:2]\n                    if point_in_canvas_wh(point_img):\n                        color_scale = min(depth / 80, 1)\n                        color = cm.rainbow(color_scale)\n                        color = tuple([int(x*255) for x in color[:3]])\n                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=2, color=color, thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'lidar/front/{step:05}_front.png'), visulize_img)\n            # ==========================================================\n\n        # ================ lidar to back image =====================\n        if vis_lidar_to_back_image:\n            key = 'CAM_BACK'\n            K = sensors_anno[key]['intrinsic']\n            visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n            ego2cam = np.matrix(sensors_anno[key]['cam2ego']).I.tolist()\n\n            # lidar in ego coordinate\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            for lidar in lidars:\n                lidar = np.array([lidar[0], lidar[1], lidar[2], 1])\n                point_camera = np.dot(ego2cam, lidar)\n                point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                depth = point_camera[2]\n                point_img = np.dot(K, point_camera)\n                if depth > 0:\n                    point_img[0] /= point_img[2]\n                    point_img[1] /= point_img[2]\n                    point_img = point_img[0:2]\n                    if point_in_canvas_wh(point_img):\n                        color_scale = min(depth / 80, 1)\n                        color = cm.rainbow(color_scale)\n                        color = tuple([int(x*255) for x in color[:3]])\n                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=2, color=color, thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'lidar/back/{step:05}_back.png'), visulize_img)\n        # ===========================================================\n\n        # ================ lidar to fomr left image =====================\n        if vis_lidar_to_front_left_image:\n            key = 'CAM_FRONT_LEFT'\n            K = sensors_anno[key]['intrinsic']\n            visulize_img = cv2.imread(os.path.join(file_path, f'camera/{cam_map[key]}/{step:05}.jpg'))\n            ego2cam = np.matrix(sensors_anno[key]['cam2ego']).I.tolist()\n\n            # lidar in ego coordinate\n            lidar_path = os.path.join(file_path, f'lidar/{step:05}.laz')\n            lidars = laspy.read(lidar_path).xyz\n\n            for lidar in lidars:\n                lidar = np.array([lidar[0], lidar[1], lidar[2], 1])\n                point_camera = np.dot(ego2cam, lidar)\n                point_camera = [point_camera[1], -point_camera[2], point_camera[0]]\n                depth = point_camera[2]\n                point_img = np.dot(K, point_camera)\n                if depth > 0:\n                    point_img[0] /= point_img[2]\n                    point_img[1] /= point_img[2]\n                    point_img = point_img[0:2]\n                    if point_in_canvas_wh(point_img):\n                        color_scale = min(depth / 80, 1)\n                        color = cm.rainbow(color_scale)\n                        color = tuple([int(x*255) for x in color[:3]])\n                        cv2.circle(visulize_img, (int(point_img[0]), int(point_img[1])), radius=2, color=color, thickness=-1)\n            cv2.imwrite(os.path.join(save_path, f'lidar/front_left/{step:05}_front_left.png'), visulize_img)\n        # ===========================================================\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser(description='argparse')\n    parser.add_argument('--file_path','-f', type=str)\n    parser.add_argument('--map_path','-m', type=str)\n\n    args = parser.parse_args()\n    map_path = f'./maps/Town{args.map_path}_HD_map.npz'\n    visualize_data(args.file_path, map_path, vis_bbox=True, vis_top_down=True, vis_road=True, vis_lidar_bev=True, vis_lidar_to_back_image=True, vis_lidar_to_front_image=True, vis_lidar_to_front_left_image=True)"
  },
  {
    "path": "close_loop/quick_start.md",
    "content": "# Quick Start\n\n### Set up a new virtual environment\n```bash\nconda create -n b2d_zoo python=3.8\nconda activate b2d_zoo\n```\n\n### Install dependency packpages\n```bash\npip install ninja packaging\ncd close_loop/Bench2Drive/Bench2DriveZoo\nmkdir ckpts\n# Download resnet50-19c8e357.pth or\n# Download r101_dcn_fcos3d_pretrain.pth\ncd ..\npip install -v -e .\n```\n\n### install carla\n```bash\ncd close_loop/Bench2Drive/Bench2DriveZoo\nmkdir carla\ncd carla\nwget https://carla-releases.s3.us-east-005.backblazeb2.com/Linux/CARLA_0.9.15.tar.gz\ntar -xvf CARLA_0.9.15.tar.gz\ncd Import && wget https://carla-releases.s3.us-east-005.backblazeb2.com/Linux/AdditionalMaps_0.9.15.tar.gz\ncd .. && bash ImportAssets.sh\nexport CARLA_ROOT=YOUR_CARLA_PATH\n\n## Important!!! Otherwise, the python environment can not find carla package\necho \"$CARLA_ROOT/PythonAPI/carla/dist/carla-0.9.15-py3.7-linux-x86_64.egg\" >> YOUR_CONDA_PATH/envs/YOUR_CONDA_ENV_NAME/lib/python3.8/site-packages/carla.pth # python 3.8 also works well, please set YOUR_CONDA_PATH and YOUR_CONDA_ENV_NAME\n```\n\n### Prepare the data\nDownload the dataset from [Bench2Drive](https://github.com/Thinklab-SJTU/Bench2Drive) and follow Bench2Drive to organize data.\n```bash\ncd Bench2DriveZoo/mmcv/datasets\npython prepare_B2D.py --workers 16   # workers used to prepare data\n```\n\n####  train MomAD \n```\n./adzoo/vad/dist_train.sh ./adzoo/vad/configs/VAD/MomAD_base_e2e_b2d.py  1\n# or\n./adzoo/sparsedrive/dist_train.sh ./adzoo/sparsedrive/configs/sparsedrive_small_b2d_stage2.py 1\n```\n\n####  test MomAD （Open_loop in Bench2Drive）\n```\n./adzoo/vad/dist_test.sh ./adzoo/vad/configs/VAD/VAD_base_e2e_b2d.py 1\n```\n####  test MomAD (Close_loop in Carla)\n```\nbash leaderboard/scripts/run_evaluation_multi_vad.sh\n```\n### Visualization\n```\nsh scripts/visualize.sh\n```\n\n"
  },
  {
    "path": "open_loop/docs/quick_start.md",
    "content": "# Quick Start\n\n### Set up a new virtual environment\n```bash\nconda create -n MomAD_env python=3.8 -y\nconda activate MomAD_env\n```\n\n### Install dependency packpages\n```bash\nMomAD_path=\"path/to/MomAD\"\ncd ${MomAD_path}\npip3 install --upgrade pip\npip3 install torch==1.13.0+cu116 torchvision==0.14.0+cu116 torchaudio==0.13.0 --extra-index-url https://download.pytorch.org/whl/cu116\npip3 install -r requirement.txt\n```\n:fire: Tips\n1. It is necessary to install the `mmcv-full` version of `mmcv`. It is recommended to use `cuda113` and `torch1.11.0`, and to install `mmcv` version `1.7.2`. Use the following command: \n   \n   ```\n   pip install mmcv-full -f https://download.openmmlab.com/mmcv/dist/cu113/torch1.11.0/index.html -i https://pypi.tuna.tsinghua.edu.cn/simple\n   ```\n\n2. Remember to install `flash-attn` offline. The download address for `flash_attn-0.2.2+cu113torch1.11.0-cp38-cp38-linux_x86_64.whl` is [here](https://github.com/Dao-AILab/flash-attention/releases). Move the file to the `MomAD` folder and execute the following command to install:\n\n   ```\n   pip install flash_attn-0.2.2+cu113torch1.11.0-cp38-cp38-linux_x86_64.whl\n   ```\n\n### Compile the deformable_aggregation CUDA op\n```bash\ncd projects/mmdet3d_plugin/ops\npython3 setup.py develop\ncd ../../../\n```\n\n### Prepare the data\nDownload the [NuScenes dataset](https://www.nuscenes.org/nuscenes#download) and CAN bus expansion, put CAN bus expansion in /path/to/nuscenes, create symbolic links.\n```bash\ncd ${MomAD_path}\nmkdir data\nln -s path/to/nuscenes ./data/nuscenes\n```\n\nPack the meta-information and labels of the dataset, and generate the required pkl files to data/infos. Note that we also generate map_annos in data_converter, with a roi_size of (30, 60) as default, if you want a different range, you can modify roi_size in tools/data_converter/nuscenes_converter.py.\n```bash\nsh scripts/create_data.sh\n```\n\n### Generate anchors by K-means\nGnerated anchors are saved to data/kmeans and can be visualized in vis/kmeans.\n```bash\nsh scripts/kmeans.sh\n```\n\n\n### Download pre-trained weights\nDownload the required backbone [pre-trained weights](https://download.pytorch.org/models/resnet50-19c8e357.pth).\n```bash\nmkdir ckpt\nwget https://download.pytorch.org/models/resnet50-19c8e357.pth -O ckpt/resnet50-19c8e357.pth\n```\n\n### Commence training and testing\n\n####  train MomAD 3s\n```\nbash ./tools/dist_train.sh \\\n   projects/configs/MomAD_small_stage2_roboAD.py \\\n   8 \\\n```\n####  train MomAD 6s\n```\nbash ./tools/dist_train.sh \\\n   projects/configs/MomAD_small_stage2_roboAD_6s.py \\\n   8 \\\n```\n\n####  test MomAD 3s\n```\nbash ./tools/dist_test.sh \\\n    projects/configs/MomAD_small_stage2_roboAD.py \\\n    work_dirs/MomAD_small_stage2_roboAD/MomAD_3s.pth\\\n    1 \\\n    --deterministic \\\n    --eval bbox\n```\n####  test MomAD 6s\n```\nbash ./tools/dist_test.sh \\\n    projects/configs/MomAD_small_stage2_roboAD_6s.py \\\n    work_dirs/MomAD_small_stage2_roboAD/MomAD_6s.pth\\\n    1 \\\n    --deterministic \\\n    --eval bbox\n```\n### Visualization\n```\nsh scripts/visualize.sh\n```\n"
  },
  {
    "path": "open_loop/projects/configs/MomAD_small_stage1_roboAD.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 100\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead_roboAD\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                \"denoise\",\n                ]\n                +\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHeadroboAD',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n         meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\",\"token\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\",\"token\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=4e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.5),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\nload_from = 'ckpt/sparsedrive_stage1.pth'\n"
  },
  {
    "path": "open_loop/projects/configs/MomAD_small_stage2_roboAD.py",
    "content": "# ================ base config ===================\n# version = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 20\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\n# resume_from = \"work_dirs/sparsedrive_small_stage2_roboAD/iter_5860.pth\"\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead_roboAD\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                # [\n                #     \"gnn\",\n                # \"denoise\",\n                # ]\n                # +\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=33 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHeadroboAD',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            use_rescore=True,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset_roboAD\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\",\"token\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\",\"token\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        # meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\",\"token\"],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=False,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\nload_from = 'ckpt/sparsedrive_stage2.pth'\n# load_from = 'ckpt/sparsedrive_stage1.pth'"
  },
  {
    "path": "open_loop/projects/configs/MomAD_small_stage2_roboAD_6s.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 20\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\n# resume_from = \"work_dirs/sparsedrive_small_stage2_roboAD/iter_5860.pth\"\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 12\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead_roboAD\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                # [\n                #     \"gnn\",\n                # \"denoise\",\n                # ]\n                # +\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=33 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHeadroboAD_6s',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            use_rescore=True,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset_roboAD_6s\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\",\"token\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\",\"token\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val_6s.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train_6s.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val_6s.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val_6s.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=True,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\nload_from = 'ckpt/sparsedrive_stage2.pth'\n# load_from = 'ckpt/sparsedrive_stage1.pth'"
  },
  {
    "path": "open_loop/projects/configs/MomAD_small_trainval_1_10_stage1_test.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nversion = 'trainval1_10'\nlength = {'trainval': 28130,'trainval1_10':2813, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\n\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 1000\ncheckpoint_epoch_interval = 100\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/mini/\" if version == 'mini' else \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_1_10_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=4e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.5),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n"
  },
  {
    "path": "open_loop/projects/configs/sparsedrive_small_stage1.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 100\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=4e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.5),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)"
  },
  {
    "path": "open_loop/projects/configs/sparsedrive_small_stage1_roboAD.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 100\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead_roboAD\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                \"denoise\",\n                ]\n                +\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHeadroboAD',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n         meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\",\"token\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\",\"token\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=4e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.5),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\nload_from = 'ckpt/sparsedrive_stage1.pth'\n"
  },
  {
    "path": "open_loop/projects/configs/sparsedrive_small_stage2.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 20\ncheckpoint_epoch_interval = 20\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=33 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=True,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\nload_from = 'ckpt/sparsedrive_stage2.pth'"
  },
  {
    "path": "open_loop/projects/configs/sparsedrive_small_stage2_6s.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nlength = {'trainval': 28130, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 48\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 10\ncheckpoint_epoch_interval = 10\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 12\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=True,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=33 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset_roboAD\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/\" if version == 'trainval' else \"data/infos/mini/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val_6s.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_train_6s.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val_6s.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val_6s.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=3e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.1),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=False,\n    with_tracking=False,\n    with_map=False,\n    with_motion=False,\n    with_planning=True,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)\n# ================== pretrained model ========================\nload_from = 'ckpt/sparsedrive_stage2.pth'"
  },
  {
    "path": "open_loop/projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py",
    "content": "# ================ base config ===================\nversion = 'mini'\nversion = 'trainval'\nversion = 'trainval1_10'\nlength = {'trainval': 28130,'trainval1_10':2813, 'mini': 323}\n\nplugin = True\nplugin_dir = \"projects/mmdet3d_plugin/\"\ndist_params = dict(backend=\"nccl\")\nlog_level = \"INFO\"\nwork_dir = None\n\ntotal_batch_size = 64\nnum_gpus = 8\nbatch_size = total_batch_size // num_gpus\n\nnum_iters_per_epoch = int(length[version] // (num_gpus * batch_size))\nnum_epochs = 1000\ncheckpoint_epoch_interval = 100\n\ncheckpoint_config = dict(\n    interval=num_iters_per_epoch * checkpoint_epoch_interval\n)\nlog_config = dict(\n    interval=51,\n    hooks=[\n        dict(type=\"TextLoggerHook\", by_epoch=False),\n        dict(type=\"TensorboardLoggerHook\"),\n    ],\n)\nload_from = None\nresume_from = None\nworkflow = [(\"train\", 1)]\nfp16 = dict(loss_scale=32.0)\ninput_shape = (704, 256)\n\n\n# ================== model ========================\nclass_names = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\nmap_class_names = [\n    'ped_crossing',\n    'divider',\n    'boundary',\n]\nnum_classes = len(class_names)\nnum_map_classes = len(map_class_names)\nroi_size = (30, 60)\n\nnum_sample = 20\nfut_ts = 12\nfut_mode = 6\nego_fut_ts = 6\nego_fut_mode = 6\nqueue_length = 4 # history + current\n\nembed_dims = 256\nnum_groups = 8\nnum_decoder = 6\nnum_single_frame_decoder = 1\nnum_single_frame_decoder_map = 1\nuse_deformable_func = True  # mmdet3d_plugin/ops/setup.py needs to be executed\nstrides = [4, 8, 16, 32]\nnum_levels = len(strides)\nnum_depth_layers = 3\ndrop_out = 0.1\ntemporal = True\ntemporal_map = True\ndecouple_attn = True\ndecouple_attn_map = False\ndecouple_attn_motion = True\nwith_quality_estimation = True\n\ntask_config = dict(\n    with_det=True,\n    with_map=True,\n    with_motion_plan=False,\n)\n\nmodel = dict(\n    type=\"SparseDrive\",\n    use_grid_mask=True,\n    use_deformable_func=use_deformable_func,\n    img_backbone=dict(\n        type=\"ResNet\",\n        depth=50,\n        num_stages=4,\n        frozen_stages=-1,\n        norm_eval=False,\n        style=\"pytorch\",\n        with_cp=True,\n        out_indices=(0, 1, 2, 3),\n        norm_cfg=dict(type=\"BN\", requires_grad=True),\n        pretrained=\"ckpt/resnet50-19c8e357.pth\",\n    ),\n    img_neck=dict(\n        type=\"FPN\",\n        num_outs=num_levels,\n        start_level=0,\n        out_channels=embed_dims,\n        add_extra_convs=\"on_output\",\n        relu_before_extra_convs=True,\n        in_channels=[256, 512, 1024, 2048],\n    ),\n    depth_branch=dict(  # for auxiliary supervision only\n        type=\"DenseDepthNet\",\n        embed_dims=embed_dims,\n        num_depth_layers=num_depth_layers,\n        loss_weight=0.2,\n    ),\n    head=dict(\n        type=\"SparseDriveHead\",\n        task_config=task_config,\n        det_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=900,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_det_900.npy\",\n                anchor_handler=dict(type=\"SparseBox3DKeyPointsGenerator\"),\n                num_temp_instances=600 if temporal else -1,\n                confidence_decay=0.6,\n                feat_grad=False,\n            ),\n            anchor_encoder=dict(\n                type=\"SparseBox3DEncoder\",\n                vel_dims=3,\n                embed_dims=[128, 32, 32, 64] if decouple_attn else 256,\n                mode=\"cat\" if decouple_attn else \"add\",\n                output_fc=not decouple_attn,\n                in_loops=1,\n                out_loops=4 if decouple_attn else 2,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder)\n            )[2:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparseBox3DKeyPointsGenerator\",\n                    num_learnable_pts=6,\n                    fix_scale=[\n                        [0, 0, 0],\n                        [0.45, 0, 0],\n                        [-0.45, 0, 0],\n                        [0, 0.45, 0],\n                        [0, -0.45, 0],\n                        [0, 0, 0.45],\n                        [0, 0, -0.45],\n                    ],\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparseBox3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_cls=num_classes,\n                refine_yaw=True,\n                with_quality_estimation=with_quality_estimation,\n            ),\n            sampler=dict(\n                type=\"SparseBox3DTarget\",\n                num_dn_groups=0,\n                num_temp_dn_groups=0,\n                dn_noise_scale=[2.0] * 3 + [0.5] * 7,\n                max_dn_gt=32,\n                add_neg_dn=True,\n                cls_weight=2.0,\n                box_weight=0.25,\n                reg_weights=[2.0] * 3 + [0.5] * 3 + [0.0] * 4,\n                cls_wise_reg_weights={\n                    class_names.index(\"traffic_cone\"): [\n                        2.0,\n                        2.0,\n                        2.0,\n                        1.0,\n                        1.0,\n                        1.0,\n                        0.0,\n                        0.0,\n                        1.0,\n                        1.0,\n                    ],\n                },\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=2.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseBox3DLoss\",\n                loss_box=dict(type=\"L1Loss\", loss_weight=0.25),\n                loss_centerness=dict(type=\"CrossEntropyLoss\", use_sigmoid=True),\n                loss_yawness=dict(type=\"GaussianFocalLoss\"),\n                cls_allow_reverse=[class_names.index(\"barrier\")],\n            ),\n            decoder=dict(type=\"SparseBox3DDecoder\"),\n            reg_weights=[2.0] * 3 + [1.0] * 7,\n        ),\n        map_head=dict(\n            type=\"Sparse4DHead\",\n            cls_threshold_to_reg=0.05,\n            decouple_attn=decouple_attn_map,\n            instance_bank=dict(\n                type=\"InstanceBank\",\n                num_anchor=100,\n                embed_dims=embed_dims,\n                anchor=\"data/kmeans/kmeans_map_100.npy\",\n                anchor_handler=dict(type=\"SparsePoint3DKeyPointsGenerator\"),\n                num_temp_instances=0 if temporal_map else -1,\n                confidence_decay=0.6,\n                feat_grad=True,\n            ),\n            anchor_encoder=dict(\n                type=\"SparsePoint3DEncoder\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n            ),\n            num_single_frame_decoder=num_single_frame_decoder_map,\n            operation_order=(\n                [\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * num_single_frame_decoder_map\n                + [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"deformable\",\n                    \"ffn\",\n                    \"norm\",\n                    \"refine\",\n                ]\n                * (num_decoder - num_single_frame_decoder_map)\n            )[:],\n            temp_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            )\n            if temporal_map\n            else None,\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_map else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims * 2,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 4,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            deformable_model=dict(\n                type=\"DeformableFeatureAggregation\",\n                embed_dims=embed_dims,\n                num_groups=num_groups,\n                num_levels=num_levels,\n                num_cams=6,\n                attn_drop=0.15,\n                use_deformable_func=use_deformable_func,\n                use_camera_embed=True,\n                residual_mode=\"cat\",\n                kps_generator=dict(\n                    type=\"SparsePoint3DKeyPointsGenerator\",\n                    embed_dims=embed_dims,\n                    num_sample=num_sample,\n                    num_learnable_pts=3,\n                    fix_height=(0, 0.5, -0.5, 1, -1),\n                    ground_height=-1.84023, # ground height in lidar frame\n                ),\n            ),\n            refine_layer=dict(\n                type=\"SparsePoint3DRefinementModule\",\n                embed_dims=embed_dims,\n                num_sample=num_sample,\n                num_cls=num_map_classes,\n            ),\n            sampler=dict(\n                type=\"SparsePoint3DTarget\",\n                assigner=dict(\n                    type='HungarianLinesAssigner',\n                    cost=dict(\n                        type='MapQueriesCost',\n                        cls_cost=dict(type='FocalLossCost', weight=1.0),\n                        reg_cost=dict(type='LinesL1Cost', weight=10.0, beta=0.01, permute=True),\n                    ),\n                ),\n                num_cls=num_map_classes,\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            loss_cls=dict(\n                type=\"FocalLoss\",\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=1.0,\n            ),\n            loss_reg=dict(\n                type=\"SparseLineLoss\",\n                loss_line=dict(\n                    type='LinesL1Loss',\n                    loss_weight=10.0,\n                    beta=0.01,\n                ),\n                num_sample=num_sample,\n                roi_size=roi_size,\n            ),\n            decoder=dict(type=\"SparsePoint3DDecoder\"),\n            reg_weights=[1.0] * 40,\n            gt_cls_key=\"gt_map_labels\",\n            gt_reg_key=\"gt_map_pts\",\n            gt_id_key=\"map_instance_id\",\n            with_instance_id=False,\n            task_prefix='map',\n        ),\n        motion_plan_head=dict(\n            type='MotionPlanningHead',\n            fut_ts=fut_ts,\n            fut_mode=fut_mode,\n            ego_fut_ts=ego_fut_ts,\n            ego_fut_mode=ego_fut_mode,\n            motion_anchor=f'data/kmeans/kmeans_motion_{fut_mode}.npy',\n            plan_anchor=f'data/kmeans/kmeans_plan_{ego_fut_mode}.npy',\n            embed_dims=embed_dims,\n            decouple_attn=decouple_attn_motion,\n            instance_queue=dict(\n                type=\"InstanceQueue\",\n                embed_dims=embed_dims,\n                queue_length=queue_length,\n                tracking_threshold=0.2,\n                feature_map_scale=(input_shape[1]/strides[-1], input_shape[0]/strides[-1]),\n            ),\n            operation_order=(\n                [\n                    \"temp_gnn\",\n                    \"gnn\",\n                    \"norm\",\n                    \"cross_gnn\",\n                    \"norm\",\n                    \"ffn\",                    \n                    \"norm\",\n                ] * 3 +\n                [\n                    \"refine\",\n                ]\n            ),\n            temp_graph_model=dict(\n                type=\"MultiheadAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims if not decouple_attn_motion else embed_dims * 2,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            cross_graph_model=dict(\n                type=\"MultiheadFlashAttention\",\n                embed_dims=embed_dims,\n                num_heads=num_groups,\n                batch_first=True,\n                dropout=drop_out,\n            ),\n            norm_layer=dict(type=\"LN\", normalized_shape=embed_dims),\n            ffn=dict(\n                type=\"AsymmetricFFN\",\n                in_channels=embed_dims,\n                pre_norm=dict(type=\"LN\"),\n                embed_dims=embed_dims,\n                feedforward_channels=embed_dims * 2,\n                num_fcs=2,\n                ffn_drop=drop_out,\n                act_cfg=dict(type=\"ReLU\", inplace=True),\n            ),\n            refine_layer=dict(\n                type=\"MotionPlanningRefinementModule\",\n                embed_dims=embed_dims,\n                fut_ts=fut_ts,\n                fut_mode=fut_mode,\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            motion_sampler=dict(\n                type=\"MotionTarget\",\n            ),\n            motion_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.2\n            ),\n            motion_loss_reg=dict(type='L1Loss', loss_weight=0.2),\n            planning_sampler=dict(\n                type=\"PlanningTarget\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n            ),\n            plan_loss_cls=dict(\n                type='FocalLoss',\n                use_sigmoid=True,\n                gamma=2.0,\n                alpha=0.25,\n                loss_weight=0.5,\n            ),\n            plan_loss_reg=dict(type='L1Loss', loss_weight=1.0),\n            plan_loss_status=dict(type='L1Loss', loss_weight=1.0),\n            motion_decoder=dict(type=\"SparseBox3DMotionDecoder\"),\n            planning_decoder=dict(\n                type=\"HierarchicalPlanningDecoder\",\n                ego_fut_ts=ego_fut_ts,\n                ego_fut_mode=ego_fut_mode,\n                use_rescore=True,\n            ),\n            num_det=50,\n            num_map=10,\n        ),\n    ),\n)\n\n# ================== data ========================\ndataset_type = \"NuScenes3DDataset\"\ndata_root = \"data/nuscenes/\"\nanno_root = \"data/infos/mini/\" if version == 'mini' else \"data/infos/\"\nfile_client_args = dict(backend=\"disk\")\n\nimg_norm_cfg = dict(\n    mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True\n)\ntrain_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(\n        type=\"LoadPointsFromFile\",\n        coord_type=\"LIDAR\",\n        load_dim=5,\n        use_dim=5,\n        file_client_args=file_client_args,\n    ),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(\n        type=\"MultiScaleDepthMapGenerator\",\n        downsample=strides[:num_depth_layers],\n    ),\n    dict(type=\"BBoxRotation\"),\n    dict(type=\"PhotoMetricDistortionMultiViewImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=False,\n        normalize=False,\n        sample_num=num_sample,\n        permute=True,\n    ),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            \"gt_depth\",\n            \"focal\",\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\", \"instance_id\"],\n    ),\n]\ntest_pipeline = [\n    dict(type=\"LoadMultiViewImageFromFiles\", to_float32=True),\n    dict(type=\"ResizeCropFlipImage\"),\n    dict(type=\"NormalizeMultiviewImage\", **img_norm_cfg),\n    dict(type=\"NuScenesSparse4DAdaptor\"),\n    dict(\n        type=\"Collect\",\n        keys=[\n            \"img\",\n            \"timestamp\",\n            \"projection_mat\",\n            \"image_wh\",\n            'ego_status',\n            'gt_ego_fut_cmd',\n        ],\n        meta_keys=[\"T_global\", \"T_global_inv\", \"timestamp\"],\n    ),\n]\neval_pipeline = [\n    dict(\n        type=\"CircleObjectRangeFilter\",\n        class_dist_thred=[55] * len(class_names),\n    ),\n    dict(type=\"InstanceNameFilter\", classes=class_names),\n    dict(\n        type='VectorizeMap',\n        roi_size=roi_size,\n        simplify=True,\n        normalize=False,\n    ),\n    dict(\n        type='Collect', \n        keys=[\n            'vectors',\n            \"gt_bboxes_3d\",\n            \"gt_labels_3d\",\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks', \n            'gt_ego_fut_cmd',\n            'fut_boxes'\n        ],\n        meta_keys=['token', 'timestamp']\n    ),\n]\n\ninput_modality = dict(\n    use_lidar=False,\n    use_camera=True,\n    use_radar=False,\n    use_map=False,\n    use_external=False,\n)\n\ndata_basic_config = dict(\n    type=dataset_type,\n    data_root=data_root,\n    classes=class_names,\n    map_classes=map_class_names,\n    modality=input_modality,\n    version=\"v1.0-trainval\",\n)\neval_config = dict(\n    **data_basic_config,\n    ann_file=anno_root + 'nuscenes_infos_val.pkl',\n    pipeline=eval_pipeline,\n    test_mode=True,\n)\ndata_aug_conf = {\n    \"resize_lim\": (0.40, 0.47),\n    \"final_dim\": input_shape[::-1],\n    \"bot_pct_lim\": (0.0, 0.0),\n    \"rot_lim\": (-5.4, 5.4),\n    \"H\": 900,\n    \"W\": 1600,\n    \"rand_flip\": True,\n    \"rot3d_range\": [0, 0],\n}\n\ndata = dict(\n    samples_per_gpu=batch_size,\n    workers_per_gpu=batch_size,\n    train=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_1_10_train.pkl\",\n        pipeline=train_pipeline,\n        test_mode=False,\n        data_aug_conf=data_aug_conf,\n        with_seq_flag=True,\n        sequences_split_num=2,\n        keep_consistent_seq_aug=True,\n    ),\n    val=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n    test=dict(\n        **data_basic_config,\n        ann_file=anno_root + \"nuscenes_infos_val.pkl\",\n        pipeline=test_pipeline,\n        data_aug_conf=data_aug_conf,\n        test_mode=True,\n        eval_config=eval_config,\n    ),\n)\n\n# ================== training ========================\noptimizer = dict(\n    type=\"AdamW\",\n    lr=4e-4,\n    weight_decay=0.001,\n    paramwise_cfg=dict(\n        custom_keys={\n            \"img_backbone\": dict(lr_mult=0.5),\n        }\n    ),\n)\noptimizer_config = dict(grad_clip=dict(max_norm=25, norm_type=2))\nlr_config = dict(\n    policy=\"CosineAnnealing\",\n    warmup=\"linear\",\n    warmup_iters=500,\n    warmup_ratio=1.0 / 3,\n    min_lr_ratio=1e-3,\n)\nrunner = dict(\n    type=\"IterBasedRunner\",\n    max_iters=num_iters_per_epoch * num_epochs,\n)\n\n# ================== eval ========================\neval_mode = dict(\n    with_det=True,\n    with_tracking=True,\n    with_map=True,\n    with_motion=False,\n    with_planning=False,\n    tracking_threshold=0.2,\n    motion_threshhold=0.2,\n)\nevaluation = dict(\n    interval=num_iters_per_epoch*checkpoint_epoch_interval,\n    eval_mode=eval_mode,\n)"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/__init__.py",
    "content": "from .datasets import *\nfrom .models import *\nfrom .apis import *\nfrom .core.evaluation import *\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/apis/__init__.py",
    "content": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector\n\n# from .test import custom_multi_gpu_test\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/apis/mmdet_train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport random\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.runner import (\n    HOOKS,\n    DistSamplerSeedHook,\n    EpochBasedRunner,\n    Fp16OptimizerHook,\n    OptimizerHook,\n    build_optimizer,\n    build_runner,\n    get_dist_info,\n)\nfrom mmcv.utils import build_from_cfg\n\nfrom mmdet.core import EvalHook\n\nfrom mmdet.datasets import build_dataset, replace_ImageToTensor\nfrom mmdet.utils import get_root_logger\nimport time\nimport os.path as osp\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.core.evaluation.eval_hooks import (\n    CustomDistEvalHook,\n)\nfrom projects.mmdet3d_plugin.datasets import custom_build_dataset\n\n\ndef custom_train_detector(\n    model,\n    dataset,\n    cfg,\n    distributed=False,\n    validate=False,\n    timestamp=None,\n    meta=None,\n):\n    logger = get_root_logger(cfg.log_level)\n\n    # prepare data loaders\n\n    dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]\n    # assert len(dataset)==1s\n    if \"imgs_per_gpu\" in cfg.data:\n        logger.warning(\n            '\"imgs_per_gpu\" is deprecated in MMDet V2.0. '\n            'Please use \"samples_per_gpu\" instead'\n        )\n        if \"samples_per_gpu\" in cfg.data:\n            logger.warning(\n                f'Got \"imgs_per_gpu\"={cfg.data.imgs_per_gpu} and '\n                f'\"samples_per_gpu\"={cfg.data.samples_per_gpu}, \"imgs_per_gpu\"'\n                f\"={cfg.data.imgs_per_gpu} is used in this experiments\"\n            )\n        else:\n            logger.warning(\n                'Automatically set \"samples_per_gpu\"=\"imgs_per_gpu\"='\n                f\"{cfg.data.imgs_per_gpu} in this experiments\"\n            )\n        cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu\n\n    if \"runner\" in cfg:\n        runner_type = cfg.runner[\"type\"]\n    else:\n        runner_type = \"EpochBasedRunner\"\n    data_loaders = [\n        build_dataloader(\n            ds,\n            cfg.data.samples_per_gpu,\n            cfg.data.workers_per_gpu,\n            # cfg.gpus will be ignored if distributed\n            len(cfg.gpu_ids),\n            dist=distributed,\n            seed=cfg.seed,\n            nonshuffler_sampler=dict(\n                type=\"DistributedSampler\"\n            ),  # dict(type='DistributedSampler'),\n            runner_type=runner_type,\n        )\n        for ds in dataset\n    ]\n\n    # put model on gpus\n    if distributed:\n        find_unused_parameters = cfg.get(\"find_unused_parameters\", False)\n        # Sets the `find_unused_parameters` parameter in\n        # torch.nn.parallel.DistributedDataParallel\n        model = MMDistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n            find_unused_parameters=find_unused_parameters,\n        )\n\n    else:\n        model = MMDataParallel(\n            model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids\n        )\n\n    # build runner\n    optimizer = build_optimizer(model, cfg.optimizer)\n\n    if \"runner\" not in cfg:\n        cfg.runner = {\n            \"type\": \"EpochBasedRunner\",\n            \"max_epochs\": cfg.total_epochs,\n        }\n        warnings.warn(\n            \"config is now expected to have a `runner` section, \"\n            \"please set `runner` in your config.\",\n            UserWarning,\n        )\n    else:\n        if \"total_epochs\" in cfg:\n            assert cfg.total_epochs == cfg.runner.max_epochs\n\n    runner = build_runner(\n        cfg.runner,\n        default_args=dict(\n            model=model,\n            optimizer=optimizer,\n            work_dir=cfg.work_dir,\n            logger=logger,\n            meta=meta,\n        ),\n    )\n\n    # an ugly workaround to make .log and .log.json filenames the same\n    runner.timestamp = timestamp\n\n    # fp16 setting\n    fp16_cfg = cfg.get(\"fp16\", None)\n    if fp16_cfg is not None:\n        optimizer_config = Fp16OptimizerHook(\n            **cfg.optimizer_config, **fp16_cfg, distributed=distributed\n        )\n    elif distributed and \"type\" not in cfg.optimizer_config:\n        optimizer_config = OptimizerHook(**cfg.optimizer_config)\n    else:\n        optimizer_config = cfg.optimizer_config\n\n    # register hooks\n    runner.register_training_hooks(\n        cfg.lr_config,\n        optimizer_config,\n        cfg.checkpoint_config,\n        cfg.log_config,\n        cfg.get(\"momentum_config\", None),\n    )\n\n    # register profiler hook\n    # trace_config = dict(type='tb_trace', dir_name='work_dir')\n    # profiler_config = dict(on_trace_ready=trace_config)\n    # runner.register_profiler_hook(profiler_config)\n\n    if distributed:\n        if isinstance(runner, EpochBasedRunner):\n            runner.register_hook(DistSamplerSeedHook())\n\n    # register eval hooks\n    if validate:\n        # Support batch_size > 1 in validation\n        val_samples_per_gpu = cfg.data.val.pop(\"samples_per_gpu\", 1)\n        if val_samples_per_gpu > 1:\n            assert False\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.val.pipeline = replace_ImageToTensor(\n                cfg.data.val.pipeline\n            )\n        val_dataset = custom_build_dataset(cfg.data.val, dict(test_mode=True))\n\n        val_dataloader = build_dataloader(\n            val_dataset,\n            samples_per_gpu=val_samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n        )\n        eval_cfg = cfg.get(\"evaluation\", {})\n        eval_cfg[\"by_epoch\"] = cfg.runner[\"type\"] != \"IterBasedRunner\"\n        eval_cfg[\"jsonfile_prefix\"] = osp.join(\n            \"val\",\n            cfg.work_dir,\n            time.ctime().replace(\" \", \"_\").replace(\":\", \"_\"),\n        )\n        eval_hook = CustomDistEvalHook if distributed else EvalHook\n        runner.register_hook(eval_hook(val_dataloader, **eval_cfg))\n\n    # user-defined hooks\n    if cfg.get(\"custom_hooks\", None):\n        custom_hooks = cfg.custom_hooks\n        assert isinstance(\n            custom_hooks, list\n        ), f\"custom_hooks expect list type, but got {type(custom_hooks)}\"\n        for hook_cfg in cfg.custom_hooks:\n            assert isinstance(hook_cfg, dict), (\n                \"Each item in custom_hooks expects dict type, but got \"\n                f\"{type(hook_cfg)}\"\n            )\n            hook_cfg = hook_cfg.copy()\n            priority = hook_cfg.pop(\"priority\", \"NORMAL\")\n            hook = build_from_cfg(hook_cfg, HOOKS)\n            runner.register_hook(hook, priority=priority)\n\n    if cfg.resume_from:\n        runner.resume(cfg.resume_from)\n    elif cfg.load_from:\n        runner.load_checkpoint(cfg.load_from)\n    runner.run(data_loaders, cfg.workflow)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/apis/test.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\nimport os.path as osp\nimport pickle\nimport shutil\nimport tempfile\nimport time\n\nimport mmcv\nimport torch\nimport torch.distributed as dist\nfrom mmcv.image import tensor2imgs\nfrom mmcv.runner import get_dist_info\n\nfrom mmdet.core import encode_mask_results\n\n\nimport mmcv\nimport numpy as np\nimport pycocotools.mask as mask_util\n\n\ndef custom_encode_mask_results(mask_results):\n    \"\"\"Encode bitmap mask to RLE code. Semantic Masks only\n    Args:\n        mask_results (list | tuple[list]): bitmap mask results.\n            In mask scoring rcnn, mask_results is a tuple of (segm_results,\n            segm_cls_score).\n    Returns:\n        list | tuple: RLE encoded mask.\n    \"\"\"\n    cls_segms = mask_results\n    num_classes = len(cls_segms)\n    encoded_mask_results = []\n    for i in range(len(cls_segms)):\n        encoded_mask_results.append(\n            mask_util.encode(\n                np.array(\n                    cls_segms[i][:, :, np.newaxis], order=\"F\", dtype=\"uint8\"\n                )\n            )[0]\n        )  # encoded with RLE\n    return [encoded_mask_results]\n\n\ndef custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):\n    \"\"\"Test model with multiple gpus.\n    This method tests model with multiple gpus and collects the results\n    under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'\n    it encodes results to gpu tensors and use gpu communication for results\n    collection. On cpu mode it saves the results on different gpus to 'tmpdir'\n    and collects them by the rank 0 worker.\n    Args:\n        model (nn.Module): Model to be tested.\n        data_loader (nn.Dataloader): Pytorch data loader.\n        tmpdir (str): Path of directory to save the temporary results from\n            different gpus under cpu mode.\n        gpu_collect (bool): Option to use either gpu or cpu to collect results.\n    Returns:\n        list: The prediction results.\n    \"\"\"\n    model.eval()\n    bbox_results = []\n    mask_results = []\n    dataset = data_loader.dataset\n    rank, world_size = get_dist_info()\n    if rank == 0:\n        prog_bar = mmcv.ProgressBar(len(dataset))\n    time.sleep(2)  # This line can prevent deadlock problem in some cases.\n    have_mask = False\n    # import pdb;pdb.set_trace()\n    for i, data in enumerate(data_loader):\n        with torch.no_grad():\n            result = model(return_loss=False, rescale=True, **data)\n            # encode mask results\n            if isinstance(result, dict):\n                if \"bbox_results\" in result.keys():\n                    bbox_result = result[\"bbox_results\"]\n                    batch_size = len(result[\"bbox_results\"])\n                    bbox_results.extend(bbox_result)\n                if (\n                    \"mask_results\" in result.keys()\n                    and result[\"mask_results\"] is not None\n                ):\n                    mask_result = custom_encode_mask_results(\n                        result[\"mask_results\"]\n                    )\n                    mask_results.extend(mask_result)\n                    have_mask = True\n            else:\n                batch_size = len(result)\n                bbox_results.extend(result)\n\n        if rank == 0:\n            for _ in range(batch_size * world_size):\n                prog_bar.update()\n\n    # collect results from all ranks\n    if gpu_collect:\n        bbox_results = collect_results_gpu(bbox_results, len(dataset))\n        if have_mask:\n            mask_results = collect_results_gpu(mask_results, len(dataset))\n        else:\n            mask_results = None\n    else:\n        bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)\n        tmpdir = tmpdir + \"_mask\" if tmpdir is not None else None\n        if have_mask:\n            mask_results = collect_results_cpu(\n                mask_results, len(dataset), tmpdir\n            )\n        else:\n            mask_results = None\n\n    if mask_results is None:\n        return bbox_results\n    return {\"bbox_results\": bbox_results, \"mask_results\": mask_results}\n\n\ndef collect_results_cpu(result_part, size, tmpdir=None):\n    rank, world_size = get_dist_info()\n    # create a tmp dir if it is not specified\n    if tmpdir is None:\n        MAX_LEN = 512\n        # 32 is whitespace\n        dir_tensor = torch.full(\n            (MAX_LEN,), 32, dtype=torch.uint8, device=\"cuda\"\n        )\n        if rank == 0:\n            mmcv.mkdir_or_exist(\".dist_test\")\n            tmpdir = tempfile.mkdtemp(dir=\".dist_test\")\n            tmpdir = torch.tensor(\n                bytearray(tmpdir.encode()), dtype=torch.uint8, device=\"cuda\"\n            )\n            dir_tensor[: len(tmpdir)] = tmpdir\n        dist.broadcast(dir_tensor, 0)\n        tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()\n    else:\n        mmcv.mkdir_or_exist(tmpdir)\n    # dump the part result to the dir\n    mmcv.dump(result_part, osp.join(tmpdir, f\"part_{rank}.pkl\"))\n    dist.barrier()\n    # collect all parts\n    if rank != 0:\n        return None\n    else:\n        # load results of all parts from tmp dir\n        part_list = []\n        for i in range(world_size):\n            part_file = osp.join(tmpdir, f\"part_{i}.pkl\")\n            part_list.append(mmcv.load(part_file))\n        # sort the results\n        ordered_results = []\n        \"\"\"\n        bacause we change the sample of the evaluation stage to make sure that\n        each gpu will handle continuous sample,\n        \"\"\"\n        # for res in zip(*part_list):\n        for res in part_list:\n            ordered_results.extend(list(res))\n        # the dataloader may pad some samples\n        ordered_results = ordered_results[:size]\n        # remove tmp dir\n        shutil.rmtree(tmpdir)\n        return ordered_results\n\n\ndef collect_results_gpu(result_part, size):\n    collect_results_cpu(result_part, size)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/apis/train.py",
    "content": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n#  Modified by Zhiqi Li\n# ---------------------------------------------\n\nfrom .mmdet_train import custom_train_detector\n# from mmseg.apis import train_segmentor\nfrom mmdet.apis import train_detector\n\n\ndef custom_train_model(\n    model,\n    dataset,\n    cfg,\n    distributed=False,\n    validate=False,\n    timestamp=None,\n    meta=None,\n):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    if cfg.model.type in [\"EncoderDecoder3D\"]:\n        assert False\n    else:\n        custom_train_detector(\n            model,\n            dataset,\n            cfg,\n            distributed=distributed,\n            validate=validate,\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\ndef train_model(\n    model,\n    dataset,\n    cfg,\n    distributed=False,\n    validate=False,\n    timestamp=None,\n    meta=None,\n):\n    \"\"\"A function wrapper for launching model training according to cfg.\n\n    Because we need different eval_hook in runner. Should be deprecated in the\n    future.\n    \"\"\"\n    train_detector(\n        model,\n        dataset,\n        cfg,\n        distributed=distributed,\n        validate=validate,\n        timestamp=timestamp,\n        meta=meta,\n    )\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/core/box3d.py",
    "content": "X, Y, Z, W, L, H, SIN_YAW, COS_YAW, VX, VY, VZ = list(range(11))  # undecoded\nCNS, YNS = 0, 1  # centerness and yawness indices in quality\nYAW = 6  # decoded\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/core/evaluation/__init__.py",
    "content": "from .eval_hooks import CustomDistEvalHook"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/core/evaluation/eval_hooks.py",
    "content": "# Note: Considering that MMCV's EvalHook updated its interface in V1.3.16,\n# in order to avoid strong version dependency, we did not directly\n# inherit EvalHook but BaseDistEvalHook.\n\nimport bisect\nimport os.path as osp\n\nimport mmcv\nimport torch.distributed as dist\nfrom mmcv.runner import DistEvalHook as BaseDistEvalHook\nfrom mmcv.runner import EvalHook as BaseEvalHook\nfrom torch.nn.modules.batchnorm import _BatchNorm\nfrom mmdet.core.evaluation.eval_hooks import DistEvalHook\n\n\ndef _calc_dynamic_intervals(start_interval, dynamic_interval_list):\n    assert mmcv.is_list_of(dynamic_interval_list, tuple)\n\n    dynamic_milestones = [0]\n    dynamic_milestones.extend(\n        [dynamic_interval[0] for dynamic_interval in dynamic_interval_list]\n    )\n    dynamic_intervals = [start_interval]\n    dynamic_intervals.extend(\n        [dynamic_interval[1] for dynamic_interval in dynamic_interval_list]\n    )\n    return dynamic_milestones, dynamic_intervals\n\n\nclass CustomDistEvalHook(BaseDistEvalHook):\n    def __init__(self, *args, dynamic_intervals=None, **kwargs):\n        super(CustomDistEvalHook, self).__init__(*args, **kwargs)\n        self.use_dynamic_intervals = dynamic_intervals is not None\n        if self.use_dynamic_intervals:\n            (\n                self.dynamic_milestones,\n                self.dynamic_intervals,\n            ) = _calc_dynamic_intervals(self.interval, dynamic_intervals)\n\n    def _decide_interval(self, runner):\n        if self.use_dynamic_intervals:\n            progress = runner.epoch if self.by_epoch else runner.iter\n            step = bisect.bisect(self.dynamic_milestones, (progress + 1))\n            # Dynamically modify the evaluation interval\n            self.interval = self.dynamic_intervals[step - 1]\n\n    def before_train_epoch(self, runner):\n        \"\"\"Evaluate the model only at the start of training by epoch.\"\"\"\n        self._decide_interval(runner)\n        super().before_train_epoch(runner)\n\n    def before_train_iter(self, runner):\n        self._decide_interval(runner)\n        super().before_train_iter(runner)\n\n    def _do_evaluate(self, runner):\n        \"\"\"perform evaluation and save ckpt.\"\"\"\n        # Synchronization of BatchNorm's buffer (running_mean\n        # and running_var) is not supported in the DDP of pytorch,\n        # which may cause the inconsistent performance of models in\n        # different ranks, so we broadcast BatchNorm's buffers\n        # of rank 0 to other ranks to avoid this.\n        if self.broadcast_bn_buffer:\n            model = runner.model\n            for name, module in model.named_modules():\n                if (\n                    isinstance(module, _BatchNorm)\n                    and module.track_running_stats\n                ):\n                    dist.broadcast(module.running_var, 0)\n                    dist.broadcast(module.running_mean, 0)\n\n        if not self._should_evaluate(runner):\n            return\n\n        tmpdir = self.tmpdir\n        if tmpdir is None:\n            tmpdir = osp.join(runner.work_dir, \".eval_hook\")\n\n        from projects.mmdet3d_plugin.apis.test import (\n            custom_multi_gpu_test,\n        )  # to solve circlur  import\n\n        results = custom_multi_gpu_test(\n            runner.model,\n            self.dataloader,\n            tmpdir=tmpdir,\n            gpu_collect=self.gpu_collect,\n        )\n        if runner.rank == 0:\n            print(\"\\n\")\n            runner.log_buffer.output[\"eval_iter_num\"] = len(self.dataloader)\n\n            key_score = self.evaluate(runner, results)\n\n            if self.save_best:\n                self._save_ckpt(runner, key_score)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/__init__.py",
    "content": "\nfrom .nuscenes_3d_dataset_roboAD import NuScenes3DDataset_roboAD\nfrom .nuscenes_3d_dataset_roboAD_6s import NuScenes3DDataset_roboAD_6s\nfrom .nuscenes_3d_dataset import NuScenes3DDataset\nfrom .builder import *\nfrom .pipelines import *\nfrom .samplers import *\n\n__all__ = [\n    'NuScenes3DDataset',\n    'NuScenes3DDataset_roboAD',\n    'NuScenes3DDataset_roboAD_6s',\n    \"custom_build_dataset\",\n]\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/builder.py",
    "content": "import copy\nimport platform\nimport random\nfrom functools import partial\n\nimport numpy as np\nfrom mmcv.parallel import collate\nfrom mmcv.runner import get_dist_info\nfrom mmcv.utils import Registry, build_from_cfg\nfrom torch.utils.data import DataLoader\n\nfrom mmdet.datasets.samplers import GroupSampler\nfrom projects.mmdet3d_plugin.datasets.samplers import (\n    GroupInBatchSampler,\n    DistributedGroupSampler,\n    DistributedSampler,\n    build_sampler\n)\n\n\ndef build_dataloader(\n    dataset,\n    samples_per_gpu,\n    workers_per_gpu,\n    num_gpus=1,\n    dist=True,\n    shuffle=True,\n    seed=None,\n    shuffler_sampler=None,\n    nonshuffler_sampler=None,\n    runner_type=\"EpochBasedRunner\",\n    **kwargs\n):\n    \"\"\"Build PyTorch DataLoader.\n    In distributed training, each GPU/process has a dataloader.\n    In non-distributed training, there is only one dataloader for all GPUs.\n    Args:\n        dataset (Dataset): A PyTorch dataset.\n        samples_per_gpu (int): Number of training samples on each GPU, i.e.,\n            batch size of each GPU.\n        workers_per_gpu (int): How many subprocesses to use for data loading\n            for each GPU.\n        num_gpus (int): Number of GPUs. Only used in non-distributed training.\n        dist (bool): Distributed training/test or not. Default: True.\n        shuffle (bool): Whether to shuffle the data at every epoch.\n            Default: True.\n        kwargs: any keyword argument to be used to initialize DataLoader\n    Returns:\n        DataLoader: A PyTorch dataloader.\n    \"\"\"\n    rank, world_size = get_dist_info()\n    batch_sampler = None\n    if runner_type == 'IterBasedRunner':\n        print(\"Use GroupInBatchSampler !!!\")\n        batch_sampler = GroupInBatchSampler(\n            dataset,\n            samples_per_gpu,\n            world_size,\n            rank,\n            seed=seed,\n        )\n        batch_size = 1\n        sampler = None\n        num_workers = workers_per_gpu\n    elif dist:\n        # DistributedGroupSampler will definitely shuffle the data to satisfy\n        # that images on each GPU are in the same group\n        if shuffle:\n            print(\"Use DistributedGroupSampler !!!\")\n            sampler = build_sampler(\n                shuffler_sampler\n                if shuffler_sampler is not None\n                else dict(type=\"DistributedGroupSampler\"),\n                dict(\n                    dataset=dataset,\n                    samples_per_gpu=samples_per_gpu,\n                    num_replicas=world_size,\n                    rank=rank,\n                    seed=seed,\n                ),\n            )\n        else:\n            sampler = build_sampler(\n                nonshuffler_sampler\n                if nonshuffler_sampler is not None\n                else dict(type=\"DistributedSampler\"),\n                dict(\n                    dataset=dataset,\n                    num_replicas=world_size,\n                    rank=rank,\n                    shuffle=shuffle,\n                    seed=seed,\n                ),\n            )\n\n        batch_size = samples_per_gpu\n        num_workers = workers_per_gpu\n    else:\n        # assert False, 'not support in bevformer'\n        print(\"WARNING!!!!, Only can be used for obtain inference speed!!!!\")\n        sampler = GroupSampler(dataset, samples_per_gpu) if shuffle else None\n        batch_size = num_gpus * samples_per_gpu\n        num_workers = num_gpus * workers_per_gpu\n\n    init_fn = (\n        partial(worker_init_fn, num_workers=num_workers, rank=rank, seed=seed)\n        if seed is not None\n        else None\n    )\n\n    data_loader = DataLoader(\n        dataset,\n        batch_size=batch_size,\n        sampler=sampler,\n        batch_sampler=batch_sampler,\n        num_workers=num_workers,\n        collate_fn=partial(collate, samples_per_gpu=samples_per_gpu),\n        pin_memory=False,\n        worker_init_fn=init_fn,\n        **kwargs\n    )\n\n    return data_loader\n\n\ndef worker_init_fn(worker_id, num_workers, rank, seed):\n    # The seed of each worker equals to\n    # num_worker * rank + worker_id + user_seed\n    worker_seed = num_workers * rank + worker_id + seed\n    np.random.seed(worker_seed)\n    random.seed(worker_seed)\n\n\n# Copyright (c) OpenMMLab. All rights reserved.\nimport platform\nfrom mmcv.utils import Registry, build_from_cfg\n\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.builder import _concat_dataset\n\nif platform.system() != \"Windows\":\n    # https://github.com/pytorch/pytorch/issues/973\n    import resource\n\n    rlimit = resource.getrlimit(resource.RLIMIT_NOFILE)\n    base_soft_limit = rlimit[0]\n    hard_limit = rlimit[1]\n    soft_limit = min(max(4096, base_soft_limit), hard_limit)\n    resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit))\n\nOBJECTSAMPLERS = Registry(\"Object sampler\")\n\n\ndef custom_build_dataset(cfg, default_args=None):\n    try:\n        from mmdet3d.datasets.dataset_wrappers import CBGSDataset\n    except:\n        CBGSDataset = None\n    from mmdet.datasets.dataset_wrappers import (\n        ClassBalancedDataset,\n        ConcatDataset,\n        RepeatDataset,\n    )\n\n    if isinstance(cfg, (list, tuple)):\n        dataset = ConcatDataset(\n            [custom_build_dataset(c, default_args) for c in cfg]\n        )\n    elif cfg[\"type\"] == \"ConcatDataset\":\n        dataset = ConcatDataset(\n            [custom_build_dataset(c, default_args) for c in cfg[\"datasets\"]],\n            cfg.get(\"separate_eval\", True),\n        )\n    elif cfg[\"type\"] == \"RepeatDataset\":\n        dataset = RepeatDataset(\n            custom_build_dataset(cfg[\"dataset\"], default_args), cfg[\"times\"]\n        )\n    elif cfg[\"type\"] == \"ClassBalancedDataset\":\n        dataset = ClassBalancedDataset(\n            custom_build_dataset(cfg[\"dataset\"], default_args),\n            cfg[\"oversample_thr\"],\n        )\n    elif cfg[\"type\"] == \"CBGSDataset\":\n        dataset = CBGSDataset(\n            custom_build_dataset(cfg[\"dataset\"], default_args)\n        )\n    elif isinstance(cfg.get(\"ann_file\"), (list, tuple)):\n        dataset = _concat_dataset(cfg, default_args)\n    else:\n        dataset = build_from_cfg(cfg, DATASETS, default_args)\n\n    return dataset\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/__init__.py",
    "content": ""
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/map/AP.py",
    "content": "import numpy as np\nfrom .distance import chamfer_distance, frechet_distance, chamfer_distance_batch\nfrom typing import List, Tuple, Union\nfrom numpy.typing import NDArray\n\ndef average_precision(recalls, precisions, mode='area'):\n    \"\"\"Calculate average precision. \n\n    Args:\n        recalls (ndarray): shape (num_dets, )\n        precisions (ndarray): shape (num_dets, )\n        mode (str): 'area' or '11points', 'area' means calculating the area\n            under precision-recall curve, '11points' means calculating\n            the average precision of recalls at [0, 0.1, ..., 1]\n\n    Returns:\n        float: calculated average precision\n    \"\"\"\n\n    recalls = recalls[np.newaxis, :]\n    precisions = precisions[np.newaxis, :]\n\n    assert recalls.shape == precisions.shape and recalls.ndim == 2\n    num_scales = recalls.shape[0]\n    ap = 0.\n\n    if mode == 'area':\n        zeros = np.zeros((num_scales, 1), dtype=recalls.dtype)\n        ones = np.ones((num_scales, 1), dtype=recalls.dtype)\n        mrec = np.hstack((zeros, recalls, ones))\n        mpre = np.hstack((zeros, precisions, zeros))\n        for i in range(mpre.shape[1] - 1, 0, -1):\n            mpre[:, i - 1] = np.maximum(mpre[:, i - 1], mpre[:, i])\n        \n        ind = np.where(mrec[0, 1:] != mrec[0, :-1])[0]\n        ap = np.sum(\n            (mrec[0, ind + 1] - mrec[0, ind]) * mpre[0, ind + 1])\n    \n    elif mode == '11points':\n        for thr in np.arange(0, 1 + 1e-3, 0.1):\n            precs = precisions[0, recalls[i, :] >= thr]\n            prec = precs.max() if precs.size > 0 else 0\n            ap += prec\n        ap /= 11\n    else:\n        raise ValueError(\n            'Unrecognized mode, only \"area\" and \"11points\" are supported')\n    \n    return ap\n\ndef instance_match(pred_lines: NDArray, \n                   scores: NDArray, \n                   gt_lines: NDArray, \n                   thresholds: Union[Tuple, List], \n                   metric: str='chamfer') -> List:\n    \"\"\"Compute whether detected lines are true positive or false positive.\n\n    Args:\n        pred_lines (array): Detected lines of a sample, of shape (M, INTERP_NUM, 2 or 3).\n        scores (array): Confidence score of each line, of shape (M, ).\n        gt_lines (array): GT lines of a sample, of shape (N, INTERP_NUM, 2 or 3).\n        thresholds (list of tuple): List of thresholds.\n        metric (str): Distance function for lines matching. Default: 'chamfer'.\n\n    Returns:\n        list_of_tp_fp (list): tp-fp matching result at all thresholds\n    \"\"\"\n\n    if metric == 'chamfer':\n        distance_fn = chamfer_distance\n\n    elif metric == 'frechet':\n        distance_fn = frechet_distance\n    \n    else:\n        raise ValueError(f'unknown distance function {metric}')\n\n    num_preds = pred_lines.shape[0]\n    num_gts = gt_lines.shape[0]\n\n    # tp and fp\n    tp_fp_list = []\n    tp = np.zeros((num_preds), dtype=np.float32)\n    fp = np.zeros((num_preds), dtype=np.float32)\n\n    # if there is no gt lines in this sample, then all pred lines are false positives\n    if num_gts == 0:\n        fp[...] = 1\n        for thr in thresholds:\n            tp_fp_list.append((tp.copy(), fp.copy()))\n        return tp_fp_list\n    \n    if num_preds == 0:\n        for thr in thresholds:\n            tp_fp_list.append((tp.copy(), fp.copy()))\n        return tp_fp_list\n\n    assert pred_lines.shape[1] == gt_lines.shape[1], \\\n        \"sample points num should be the same\"\n\n    # distance matrix: M x N\n    matrix = np.zeros((num_preds, num_gts))\n\n    # for i in range(num_preds):\n    #     for j in range(num_gts):\n    #         matrix[i, j] = distance_fn(pred_lines[i], gt_lines[j])\n    \n    matrix = chamfer_distance_batch(pred_lines, gt_lines)\n    # for each det, the min distance with all gts\n    matrix_min = matrix.min(axis=1)\n\n    # for each det, which gt is the closest to it\n    matrix_argmin = matrix.argmin(axis=1)\n    # sort all dets in descending order by scores\n    sort_inds = np.argsort(-scores)\n\n    # match under different thresholds\n    for thr in thresholds:\n        tp = np.zeros((num_preds), dtype=np.float32)\n        fp = np.zeros((num_preds), dtype=np.float32)\n\n        gt_covered = np.zeros(num_gts, dtype=bool)\n        for i in sort_inds:\n            if matrix_min[i] <= thr:\n                matched_gt = matrix_argmin[i]\n                if not gt_covered[matched_gt]:\n                    gt_covered[matched_gt] = True\n                    tp[i] = 1\n                else:\n                    fp[i] = 1\n            else:\n                fp[i] = 1\n        \n        tp_fp_list.append((tp, fp))\n\n    return tp_fp_list"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/map/distance.py",
    "content": "from scipy.spatial import distance\nfrom numpy.typing import NDArray\nimport torch\n\ndef chamfer_distance(line1: NDArray, line2: NDArray) -> float:\n    ''' Calculate chamfer distance between two lines. Make sure the \n    lines are interpolated.\n\n    Args:\n        line1 (array): coordinates of line1\n        line2 (array): coordinates of line2\n    \n    Returns:\n        distance (float): chamfer distance\n    '''\n    \n    dist_matrix = distance.cdist(line1, line2, 'euclidean')\n    dist12 = dist_matrix.min(-1).sum() / len(line1)\n    dist21 = dist_matrix.min(-2).sum() / len(line2)\n\n    return (dist12 + dist21) / 2\n\ndef frechet_distance(line1: NDArray, line2: NDArray) -> float:\n    ''' Calculate frechet distance between two lines. Make sure the \n    lines are interpolated.\n\n    Args:\n        line1 (array): coordinates of line1\n        line2 (array): coordinates of line2\n    \n    Returns:\n        distance (float): frechet distance\n    '''\n    \n    raise NotImplementedError\n\ndef chamfer_distance_batch(pred_lines, gt_lines):\n    ''' Calculate chamfer distance between two group of lines. Make sure the \n    lines are interpolated.\n\n    Args:\n        pred_lines (array or tensor): shape (m, num_pts, 2 or 3)\n        gt_lines (array or tensor): shape (n, num_pts, 2 or 3)\n    \n    Returns:\n        distance (array): chamfer distance\n    '''\n    _, num_pts, coord_dims = pred_lines.shape\n    \n    if not isinstance(pred_lines, torch.Tensor):\n        pred_lines = torch.tensor(pred_lines)\n    if not isinstance(gt_lines, torch.Tensor):\n        gt_lines = torch.tensor(gt_lines)\n    dist_mat = torch.cdist(pred_lines.view(-1, coord_dims), \n                    gt_lines.view(-1, coord_dims), p=2) \n    # (num_query*num_points, num_gt*num_points)\n    dist_mat = torch.stack(torch.split(dist_mat, num_pts)) \n    # (num_query, num_points, num_gt*num_points)\n    dist_mat = torch.stack(torch.split(dist_mat, num_pts, dim=-1)) \n    # (num_gt, num_q, num_pts, num_pts)\n\n    dist1 = dist_mat.min(-1)[0].sum(-1)\n    dist2 = dist_mat.min(-2)[0].sum(-1)\n\n    dist_matrix = (dist1 + dist2).transpose(0, 1) / (2 * num_pts)\n    \n    return dist_matrix.numpy()"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/map/vector_eval.py",
    "content": "import prettytable\nfrom typing import Dict, List, Optional\nfrom time import time\nfrom copy import deepcopy\nfrom multiprocessing import Pool\nfrom logging import Logger\nfrom functools import partial, cached_property\n\nimport numpy as np\nfrom numpy.typing import NDArray\nfrom shapely.geometry import LineString\n\nimport mmcv\nfrom mmcv import Config\nfrom mmdet.datasets import build_dataset, build_dataloader\n\nfrom .AP import instance_match, average_precision\n\nINTERP_NUM = 200 # number of points to interpolate during evaluation\nTHRESHOLDS = [0.5, 1.0, 1.5] # AP thresholds\nN_WORKERS = 16 # num workers to parallel\n\nclass VectorEvaluate(object):\n    \"\"\"Evaluator for vectorized map.\n\n    Args:\n        dataset_cfg (Config): dataset cfg for gt\n        n_workers (int): num workers to parallel\n    \"\"\"\n\n    def __init__(self, dataset_cfg: Config, n_workers: int=N_WORKERS) -> None:\n        self.dataset = build_dataset(dataset_cfg)\n        self.dataloader = build_dataloader(\n            self.dataset, samples_per_gpu=1, workers_per_gpu=n_workers, shuffle=False, dist=False)\n        classes = self.dataset.MAP_CLASSES\n        self.cat2id = {cls: i for i, cls in enumerate(classes)}\n        self.id2cat = {v: k for k, v in self.cat2id.items()}\n        self.n_workers = n_workers\n        self.thresholds = [0.5, 1.0, 1.5]\n        \n    @cached_property\n    def gts(self) -> Dict[str, Dict[int, List[NDArray]]]:\n        print('collecting gts...')\n        gts = {}\n        pbar = mmcv.ProgressBar(len(self.dataloader))\n        for data in self.dataloader:\n            token = deepcopy(data['img_metas'].data[0][0]['token'])\n            gt = deepcopy(data['vectors'].data[0][0])\n            gts[token] = gt\n            pbar.update()\n            del data # avoid dataloader memory crash\n        \n        return gts\n    \n    def interp_fixed_num(self, \n                         vector: NDArray, \n                         num_pts: int) -> NDArray:\n        ''' Interpolate a polyline.\n        \n        Args:\n            vector (array): line coordinates, shape (M, 2)\n            num_pts (int): \n        \n        Returns:\n            sampled_points (array): interpolated coordinates\n        '''\n        line = LineString(vector)\n        distances = np.linspace(0, line.length, num_pts)\n        sampled_points = np.array([list(line.interpolate(distance).coords) \n            for distance in distances]).squeeze()\n        \n        return sampled_points\n    \n    def interp_fixed_dist(self, \n                          vector: NDArray,\n                          sample_dist: float) -> NDArray:\n        ''' Interpolate a line at fixed interval.\n        \n        Args:\n            vector (LineString): vector\n            sample_dist (float): sample interval\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n        line = LineString(vector)\n        distances = list(np.arange(sample_dist, line.length, sample_dist))\n        # make sure to sample at least two points when sample_dist > line.length\n        distances = [0,] + distances + [line.length,] \n        \n        sampled_points = np.array([list(line.interpolate(distance).coords)\n                                for distance in distances]).squeeze()\n        \n        return sampled_points\n\n    def _evaluate_single(self, \n                         pred_vectors: List, \n                         scores: List, \n                         groundtruth: List, \n                         thresholds: List, \n                         metric: str='metric') -> Dict[int, NDArray]:\n        ''' Do single-frame matching for one class.\n        \n        Args:\n            pred_vectors (List): List[vector(ndarray) (different length)], \n            scores (List): List[score(float)]\n            groundtruth (List): List of vectors\n            thresholds (List): List of thresholds\n        \n        Returns:\n            tp_fp_score_by_thr (Dict): matching results at different thresholds\n                e.g. {0.5: (M, 2), 1.0: (M, 2), 1.5: (M, 2)}\n        '''\n        pred_lines = []\n\n        # interpolate predictions\n        for vector in pred_vectors:\n            vector = np.array(vector)\n            vector_interp = self.interp_fixed_num(vector, INTERP_NUM)\n            pred_lines.append(vector_interp)\n        if pred_lines:\n            pred_lines = np.stack(pred_lines)\n        else:\n            pred_lines = np.zeros((0, INTERP_NUM, 2))\n\n        # interpolate groundtruth\n        gt_lines = []\n        for vector in groundtruth:\n            vector_interp = self.interp_fixed_num(vector, INTERP_NUM)\n            gt_lines.append(vector_interp)\n        if gt_lines:\n            gt_lines = np.stack(gt_lines)\n        else:\n            gt_lines = np.zeros((0, INTERP_NUM, 2))\n        \n        scores = np.array(scores)\n        tp_fp_list = instance_match(pred_lines, scores, gt_lines, thresholds, metric) # (M, 2)\n        tp_fp_score_by_thr = {}\n        for i, thr in enumerate(thresholds):\n            tp, fp = tp_fp_list[i]\n            tp_fp_score = np.hstack([tp[:, None], fp[:, None], scores[:, None]])\n            tp_fp_score_by_thr[thr] = tp_fp_score\n        \n        return tp_fp_score_by_thr # {0.5: (M, 2), 1.0: (M, 2), 1.5: (M, 2)}\n        \n    def evaluate(self, \n                 result_path: str, \n                 metric: str='chamfer', \n                 logger: Optional[Logger]=None) -> Dict[str, float]:\n        ''' Do evaluation for a submission file and print evalution results to `logger` if specified.\n        The submission will be aligned by tokens before evaluation. We use multi-worker to speed up.\n        \n        Args:\n            result_path (str): path to submission file\n            metric (str): distance metric. Default: 'chamfer'\n            logger (Logger): logger to print evaluation result, Default: None\n        \n        Returns:\n            new_result_dict (Dict): evaluation results. AP by categories.\n        '''\n        results = mmcv.load(result_path)\n        results = results['results']\n        \n        # re-group samples and gt by label\n        samples_by_cls = {label: [] for label in self.id2cat.keys()}\n        num_gts = {label: 0 for label in self.id2cat.keys()}\n        num_preds = {label: 0 for label in self.id2cat.keys()}\n\n        # align by token\n        for token, gt in self.gts.items():\n            if token in results.keys():\n                pred = results[token]\n            else:\n                pred = {'vectors': [], 'scores': [], 'labels': []}\n            \n            # for every sample\n            vectors_by_cls = {label: [] for label in self.id2cat.keys()}\n            scores_by_cls = {label: [] for label in self.id2cat.keys()}\n\n            for i in range(len(pred['labels'])):\n                # i-th pred line in sample\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n                score = pred['scores'][i]\n\n                vectors_by_cls[label].append(vector)\n                scores_by_cls[label].append(score)\n\n            for label in self.id2cat.keys():\n                new_sample = (vectors_by_cls[label], scores_by_cls[label], gt[label])\n                num_gts[label] += len(gt[label])\n                num_preds[label] += len(scores_by_cls[label])\n                samples_by_cls[label].append(new_sample)\n\n        result_dict = {}\n\n        print(f'\\nevaluating {len(self.id2cat)} categories...')\n        start = time()\n        if self.n_workers > 0:\n            pool = Pool(self.n_workers)\n        \n        sum_mAP = 0\n        pbar = mmcv.ProgressBar(len(self.id2cat))\n        for label in self.id2cat.keys():\n            samples = samples_by_cls[label] # List[(pred_lines, scores, gts)]\n            result_dict[self.id2cat[label]] = {\n                'num_gts': num_gts[label],\n                'num_preds': num_preds[label]\n            }\n            sum_AP = 0\n\n            fn = partial(self._evaluate_single, thresholds=self.thresholds, metric=metric)\n            if self.n_workers > 0 and len(samples) > 81:\n                tpfp_score_list = pool.starmap(fn, samples)\n            else:\n                tpfp_score_list = []\n                for sample in samples:\n                    tpfp_score_list.append(fn(*sample))\n            \n            for thr in self.thresholds:\n                tp_fp_score = [i[thr] for i in tpfp_score_list]\n                tp_fp_score = np.vstack(tp_fp_score) # (num_dets, 3)\n                sort_inds = np.argsort(-tp_fp_score[:, -1])\n\n                tp = tp_fp_score[sort_inds, 0] # (num_dets,)\n                fp = tp_fp_score[sort_inds, 1] # (num_dets,)\n                tp = np.cumsum(tp, axis=0)\n                fp = np.cumsum(fp, axis=0)\n                eps = np.finfo(np.float32).eps\n                recalls = tp / np.maximum(num_gts[label], eps)\n                precisions = tp / np.maximum((tp + fp), eps)\n\n                AP = average_precision(recalls, precisions, 'area')\n                sum_AP += AP\n                result_dict[self.id2cat[label]].update({f'AP@{thr}': AP})\n\n            pbar.update()\n            \n            AP = sum_AP / len(self.thresholds)\n            sum_mAP += AP\n\n            result_dict[self.id2cat[label]].update({f'AP': AP})\n        \n        if self.n_workers > 0:\n            pool.close()\n        \n        mAP = sum_mAP / len(self.id2cat.keys())\n        result_dict.update({'mAP': mAP})\n        \n        print(f\"finished in {time() - start:.2f}s\")\n\n        # print results\n        table = prettytable.PrettyTable(['category', 'num_preds', 'num_gts'] + \n                [f'AP@{thr}' for thr in self.thresholds] + ['AP'])\n        for label in self.id2cat.keys():\n            table.add_row([\n                self.id2cat[label], \n                result_dict[self.id2cat[label]]['num_preds'],\n                result_dict[self.id2cat[label]]['num_gts'],\n                *[round(result_dict[self.id2cat[label]][f'AP@{thr}'], 4) for thr in self.thresholds],\n                round(result_dict[self.id2cat[label]]['AP'], 4),\n            ])\n        \n        from mmcv.utils import print_log\n        print_log('\\n'+str(table), logger=logger)\n        mAP_normal = 0\n        for label in self.id2cat.keys():\n            for thr in self.thresholds:\n                mAP_normal += result_dict[self.id2cat[label]][f'AP@{thr}']\n        mAP_normal = mAP_normal / 9\n\n        print_log(f'mAP_normal = {mAP_normal:.4f}\\n', logger=logger)\n        # print_log(f'mAP_hard = {mAP_easy:.4f}\\n', logger=logger)\n\n        new_result_dict = {}\n        for name in self.cat2id:\n            new_result_dict[name] = result_dict[name]['AP']\n        new_result_dict['mAP_normal'] = mAP_normal\n        return new_result_dict"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/motion/motion_eval_uniad.py",
    "content": "# nuScenes dev-kit.\n# Code written by Holger Caesar & Oscar Beijbom, 2018.\n\nimport argparse\nimport json\nimport os\nimport random\nimport time\nimport tqdm\nfrom typing import Tuple, Dict, Any\n\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import accumulate, calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES, ATTRIBUTE_NAMES, TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList, DetectionMetricData\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, class_tp_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom nuscenes.eval.common.utils import center_distance, scale_iou, yaw_diff, velocity_l2, attr_acc, cummean\n\nfrom .motion_utils import MotionBox, load_prediction, load_gt, accumulate\nMOTION_TP_METRICS = ['min_ade_err', 'min_fde_err', 'miss_rate_err']\n\n\nclass MotionEval:\n    \"\"\"\n    This is the official nuScenes detection evaluation code.\n    Results are written to the provided output_dir.\n\n    nuScenes uses the following detection metrics:\n    - Mean Average Precision (mAP): Uses center-distance as matching criterion; averaged over distance thresholds.\n    - True Positive (TP) metrics: Average of translation, velocity, scale, orientation and attribute errors.\n    - nuScenes Detection Score (NDS): The weighted sum of the above.\n\n    Here is an overview of the functions in this method:\n    - init: Loads GT annotations and predictions stored in JSON format and filters the boxes.\n    - run: Performs evaluation and dumps the metric data to disk.\n    - render: Renders various plots and dumps to disk.\n\n    We assume that:\n    - Every sample_token is given in the results, although there may be not predictions for that sample.\n\n    Please see https://www.nuscenes.org/object-detection for more details.\n    \"\"\"\n    def __init__(self,\n                 nusc: NuScenes,\n                 config: DetectionConfig,\n                 result_path: str,\n                 eval_set: str,\n                 output_dir: str = None,\n                 verbose: bool = True,\n                 seconds: int = 12):\n        \"\"\"\n        Initialize a DetectionEval object.\n        :param nusc: A NuScenes object.\n        :param config: A DetectionConfig object.\n        :param result_path: Path of the nuScenes JSON result file.\n        :param eval_set: The dataset split to evaluate on, e.g. train, val or test.\n        :param output_dir: Folder to save plots and results to.\n        :param verbose: Whether to print to stdout.\n        \"\"\"\n        self.nusc = nusc\n        self.result_path = result_path\n        self.eval_set = eval_set\n        self.output_dir = output_dir\n        self.verbose = verbose\n        self.cfg = config\n\n        # Check result file exists.\n        # assert os.path.exists(result_path), 'Error: The result file does not exist!'\n\n        # Make dirs.\n        self.plot_dir = os.path.join(self.output_dir, 'plots')\n        if not os.path.isdir(self.output_dir):\n            os.makedirs(self.output_dir)\n        if not os.path.isdir(self.plot_dir):\n            os.makedirs(self.plot_dir)\n\n        # Load data.\n        if verbose:\n            print('Initializing nuScenes detection evaluation')\n        self.pred_boxes, self.meta = load_prediction(self.result_path, self.cfg.max_boxes_per_sample, MotionBox,\n                                                     verbose=verbose)\n        self.gt_boxes = load_gt(self.nusc, self.eval_set, MotionBox, verbose=verbose, seconds=seconds)\n\n        assert set(self.pred_boxes.sample_tokens) == set(self.gt_boxes.sample_tokens), \\\n            \"Samples in split doesn't match samples in predictions.\"\n\n        # Add center distances.\n        self.pred_boxes = add_center_dist(nusc, self.pred_boxes)\n        self.gt_boxes = add_center_dist(nusc, self.gt_boxes)\n\n        # Filter boxes (distance, points per box, etc.).\n        if verbose:\n            print('Filtering predictions')\n        self.pred_boxes = filter_eval_boxes(nusc, self.pred_boxes, self.cfg.class_range, verbose=verbose)\n        if verbose:\n            print('Filtering ground truth annotations')\n        self.gt_boxes = filter_eval_boxes(nusc, self.gt_boxes, self.cfg.class_range, verbose=verbose)\n\n        self.sample_tokens = self.gt_boxes.sample_tokens\n\n    def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:\n        \"\"\"\n        Performs the actual evaluation.\n        :return: A tuple of high-level and the raw metric data.\n        \"\"\"\n        start_time = time.time()\n        self.cfg.class_names = ['car', 'pedestrian']\n        self.cfg.dist_ths = [2.0]\n\n        # -----------------------------------\n        # Step 1: Accumulate metric data for all classes and distance thresholds.\n        # -----------------------------------\n        if self.verbose:\n            print('Accumulating metric data...')\n        metric_data_list = DetectionMetricDataList()\n        metrics = {}\n        for class_name in self.cfg.class_names:\n            for dist_th in self.cfg.dist_ths:\n                md, EPA, EPA_ = accumulate(self.gt_boxes, self.pred_boxes, class_name, self.cfg.dist_fcn_callable, dist_th)\n                metric_data_list.set(class_name, dist_th, md)\n                metrics[f'{class_name}_EPA'] = EPA_\n\n        # -----------------------------------\n        # Step 2: Calculate metrics from the data.\n        # -----------------------------------\n        if self.verbose:\n            print('Calculating metrics...')\n        for class_name in self.cfg.class_names:\n            # Compute TP metrics.\n            for metric_name in MOTION_TP_METRICS:\n                metric_data = metric_data_list[(class_name, self.cfg.dist_th_tp)]\n                tp = calc_tp(metric_data, self.cfg.min_recall, metric_name)\n                metrics[f'{class_name}_{metric_name}']  = tp\n\n        return metrics, metric_data_list\n\n    def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDataList) -> None:\n        \"\"\"\n        Renders various PR and TP curves.\n        :param metrics: DetectionMetrics instance.\n        :param md_list: DetectionMetricDataList instance.\n        \"\"\"\n        if self.verbose:\n            print('Rendering PR and TP curves')\n\n        def savepath(name):\n            return os.path.join(self.plot_dir, name + '.pdf')\n\n        summary_plot(md_list, metrics, min_precision=self.cfg.min_precision, min_recall=self.cfg.min_recall,\n                     dist_th_tp=self.cfg.dist_th_tp, savepath=savepath('summary'))\n\n        for detection_name in self.cfg.class_names:\n            class_pr_curve(md_list, metrics, detection_name, self.cfg.min_precision, self.cfg.min_recall,\n                           savepath=savepath(detection_name + '_pr'))\n\n            class_tp_curve(md_list, metrics, detection_name, self.cfg.min_recall, self.cfg.dist_th_tp,\n                           savepath=savepath(detection_name + '_tp'))\n\n        for dist_th in self.cfg.dist_ths:\n            dist_pr_curve(md_list, metrics, dist_th, self.cfg.min_precision, self.cfg.min_recall,\n                          savepath=savepath('dist_pr_' + str(dist_th)))\n\n    def main(self,\n             plot_examples: int = 0,\n             render_curves: bool = True) -> Dict[str, Any]:\n        \"\"\"\n        Main function that loads the evaluation code, visualizes samples, runs the evaluation and renders stat plots.\n        :param plot_examples: How many example visualizations to write to disk.\n        :param render_curves: Whether to render PR and TP curves to disk.\n        :return: A dict that stores the high-level metrics and meta data.\n        \"\"\"\n        if plot_examples > 0:\n            # Select a random but fixed subset to plot.\n            random.seed(42)\n            sample_tokens = list(self.sample_tokens)\n            random.shuffle(sample_tokens)\n            sample_tokens = sample_tokens[:plot_examples]\n\n            # Visualize samples.\n            example_dir = os.path.join(self.output_dir, 'examples')\n            if not os.path.isdir(example_dir):\n                os.mkdir(example_dir)\n            for sample_token in sample_tokens:\n                visualize_sample(self.nusc,\n                                 sample_token,\n                                 self.gt_boxes if self.eval_set != 'test' else EvalBoxes(),\n                                 # Don't render test GT.\n                                 self.pred_boxes,\n                                 eval_range=max(self.cfg.class_range.values()),\n                                 savepath=os.path.join(example_dir, '{}.png'.format(sample_token)))\n\n        # Run evaluation.\n        metrics, metric_data_list = self.evaluate()\n\n        return metrics\n\nclass NuScenesEval(MotionEval):\n    \"\"\"\n    Dummy class for backward-compatibility. Same as MotionEval.\n    \"\"\"\n\nif __name__ == \"__main__\":\n\n    # Settings.\n    parser = argparse.ArgumentParser(description='Evaluate nuScenes detection results.',\n                                     formatter_class=argparse.ArgumentDefaultsHelpFormatter)\n    parser.add_argument('result_path', type=str, help='The submission as a JSON file.')\n    parser.add_argument('--output_dir', type=str, default='~/nuscenes-metrics',\n                        help='Folder to store result metrics, graphs and example visualizations.')\n    parser.add_argument('--eval_set', type=str, default='val',\n                        help='Which dataset split to evaluate on, train, val or test.')\n    parser.add_argument('--dataroot', type=str, default='/data/sets/nuscenes',\n                        help='Default nuScenes data directory.')\n    parser.add_argument('--version', type=str, default='v1.0-trainval',\n                        help='Which version of the nuScenes dataset to evaluate on, e.g. v1.0-trainval.')\n    parser.add_argument('--config_path', type=str, default='',\n                        help='Path to the configuration file.'\n                             'If no path given, the CVPR 2019 configuration will be used.')\n    parser.add_argument('--plot_examples', type=int, default=10,\n                        help='How many example visualizations to write to disk.')\n    parser.add_argument('--render_curves', type=int, default=1,\n                        help='Whether to render PR and TP curves to disk.')\n    parser.add_argument('--verbose', type=int, default=1,\n                        help='Whether to print to stdout.')\n    args = parser.parse_args()\n\n    result_path_ = os.path.expanduser(args.result_path)\n    output_dir_ = os.path.expanduser(args.output_dir)\n    eval_set_ = args.eval_set\n    dataroot_ = args.dataroot\n    version_ = args.version\n    config_path = args.config_path\n    plot_examples_ = args.plot_examples\n    render_curves_ = bool(args.render_curves)\n    verbose_ = bool(args.verbose)\n\n    if config_path == '':\n        cfg_ = config_factory('detection_cvpr_2019')\n    else:\n        with open(config_path, 'r') as _f:\n            cfg_ = DetectionConfig.deserialize(json.load(_f))\n\n    nusc_ = NuScenes(version=version_, verbose=verbose_, dataroot=dataroot_)\n    nusc_eval = DetectionEval(nusc_, config=cfg_, result_path=result_path_, eval_set=eval_set_,\n                              output_dir=output_dir_, verbose=verbose_)\n    nusc_eval.main(plot_examples=plot_examples_, render_curves=render_curves_)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/motion/motion_utils.py",
    "content": "# nuScenes dev-kit.\n# Code written by Holger Caesar & Oscar Beijbom, 2018.\n\nimport argparse\nimport json\nimport os\nimport random\nimport time\nimport tqdm\nfrom typing import Tuple, Dict, Any, Callable\n\nimport numpy as np\n\nfrom nuscenes import NuScenes\nfrom nuscenes.eval.common.config import config_factory\nfrom nuscenes.eval.common.data_classes import EvalBoxes\nfrom nuscenes.eval.common.loaders import add_center_dist, filter_eval_boxes\nfrom nuscenes.eval.detection.algo import calc_ap, calc_tp\nfrom nuscenes.eval.detection.constants import DETECTION_NAMES, ATTRIBUTE_NAMES, TP_METRICS\nfrom nuscenes.eval.detection.data_classes import DetectionConfig, DetectionMetrics, DetectionBox, \\\n    DetectionMetricDataList, DetectionMetricData\nfrom nuscenes.eval.detection.render import summary_plot, class_pr_curve, class_tp_curve, dist_pr_curve, visualize_sample\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\nfrom nuscenes.utils.splits import create_splits_scenes\nfrom nuscenes.eval.detection.utils import category_to_detection_name\nfrom nuscenes.eval.common.utils import quaternion_yaw, Quaternion\nfrom nuscenes.eval.common.utils import center_distance, scale_iou, yaw_diff, velocity_l2, attr_acc, cummean\n\n\nmotion_name_mapping = {\n    'car': 'car',\n    'truck': 'car',\n    'construction_vehicle': 'car',\n    'bus': 'car',\n    'trailer': 'car',\n    'motorcycle': 'car',\n    'bicycle': 'car',\n    'pedestrian': 'pedestrian',\n    'traffic_cone': 'barrier',\n    'barrier': 'barrier',\n}\n\n\nclass MotionBox(DetectionBox):\n    \"\"\" Data class used during detection evaluation. Can be a prediction or ground truth.\"\"\"\n\n    def __init__(self,\n                 sample_token: str = \"\",\n                 translation: Tuple[float, float, float] = (0, 0, 0),\n                 size: Tuple[float, float, float] = (0, 0, 0),\n                 rotation: Tuple[float, float, float, float] = (0, 0, 0, 0),\n                 velocity: Tuple[float, float] = (0, 0),\n                 ego_translation: [float, float, float] = (0, 0, 0),  # Translation to ego vehicle in meters.\n                 num_pts: int = -1,  # Nbr. LIDAR or RADAR inside the box. Only for gt boxes.\n                 detection_name: str = 'car',  # The class name used in the detection challenge.\n                 detection_score: float = -1.0,  # GT samples do not have a score.\n                 attribute_name: str = '',  # Box attribute. Each box can have at most 1 attribute.\n                 traj=None):  \n\n        super().__init__(sample_token, translation, size, rotation, velocity, ego_translation, num_pts)\n\n        assert detection_name is not None, 'Error: detection_name cannot be empty!'\n        assert detection_name in DETECTION_NAMES, 'Error: Unknown detection_name %s' % detection_name\n\n        assert attribute_name in ATTRIBUTE_NAMES or attribute_name == '', \\\n            'Error: Unknown attribute_name %s' % attribute_name\n\n        assert type(detection_score) == float, 'Error: detection_score must be a float!'\n        assert not np.any(np.isnan(detection_score)), 'Error: detection_score may not be NaN!'\n\n        # Assign.\n        self.detection_name = detection_name\n        self.detection_score = detection_score\n        self.attribute_name = attribute_name\n        self.traj = traj\n\n    def __eq__(self, other):\n        return (self.sample_token == other.sample_token and\n                self.translation == other.translation and\n                self.size == other.size and\n                self.rotation == other.rotation and\n                self.velocity == other.velocity and\n                self.ego_translation == other.ego_translation and\n                self.num_pts == other.num_pts and\n                self.detection_name == other.detection_name and\n                self.detection_score == other.detection_score and\n                self.attribute_name == other.attribute_name and\n                np.all(self.traj == other.traj))\n\n    def serialize(self) -> dict:\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'sample_token': self.sample_token,\n            'translation': self.translation,\n            'size': self.size,\n            'rotation': self.rotation,\n            'velocity': self.velocity,\n            'ego_translation': self.ego_translation,\n            'num_pts': self.num_pts,\n            'detection_name': self.detection_name,\n            'detection_score': self.detection_score,\n            'attribute_name': self.attribute_name,\n            'traj': self.traj,\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(sample_token=content['sample_token'],\n                   translation=tuple(content['translation']),\n                   size=tuple(content['size']),\n                   rotation=tuple(content['rotation']),\n                   velocity=tuple(content['velocity']),\n                   ego_translation=(0.0, 0.0, 0.0) if 'ego_translation' not in content\n                   else tuple(content['ego_translation']),\n                   num_pts=-1 if 'num_pts' not in content else int(content['num_pts']),\n                   detection_name=content['detection_name'],\n                   detection_score=-1.0 if 'detection_score' not in content else float(content['detection_score']),\n                   attribute_name=content['attribute_name'],\n                   traj=content['trajs'],)\n\n\ndef load_prediction(result_path: str, max_boxes_per_sample: int, box_cls, verbose: bool = False) \\\n        -> Tuple[EvalBoxes, Dict]:\n    \"\"\"\n    Loads object predictions from file.\n    :param result_path: Path to the .json result file provided by the user.\n    :param max_boxes_per_sample: Maximim number of boxes allowed per sample.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The deserialized results and meta data.\n    \"\"\"\n\n    # Load from file and check that the format is correct.\n    # with open(result_path) as f:\n    #     data = json.load(f)\n    data = result_path\n    assert 'results' in data, 'Error: No field `results` in result file. Please note that the result format changed.' \\\n                              'See https://www.nuscenes.org/object-detection for more information.'\n\n    # motion name mapping\n    for key in data['results'].keys():\n        for i in range(len(data['results'][key])):\n            cls_name = data['results'][key][i]['detection_name']\n            if cls_name in motion_name_mapping:\n                cls_name = motion_name_mapping[cls_name]\n            data['results'][key][i]['detection_name'] = cls_name\n    \n    # Deserialize results and get meta data.\n    all_results = EvalBoxes.deserialize(data['results'], box_cls)\n    meta = data['meta']\n    if verbose:\n        print(\"Loaded results from {}. Found detections for {} samples.\"\n              .format(result_path, len(all_results.sample_tokens)))\n\n    # Check that each sample has no more than x predicted boxes.\n    for sample_token in all_results.sample_tokens:\n        assert len(all_results.boxes[sample_token]) <= max_boxes_per_sample, \\\n            \"Error: Only <= %d boxes per sample allowed!\" % max_boxes_per_sample\n\n    return all_results, meta\n\n\ndef load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = False, seconds: int = 12) -> EvalBoxes:\n    \"\"\"\n    Loads ground truth boxes from DB.\n    :param nusc: A NuScenes instance.\n    :param eval_split: The evaluation split for which we load GT boxes.\n    :param box_cls: Type of box to load, e.g. DetectionBox or TrackingBox.\n    :param verbose: Whether to print messages to stdout.\n    :return: The GT boxes.\n    \"\"\"\n    predict_helper = PredictHelper(nusc)\n    # Init.\n    if box_cls == MotionBox:\n        attribute_map = {a['token']: a['name'] for a in nusc.attribute}\n\n    if verbose:\n        print('Loading annotations for {} split from nuScenes version: {}'.format(eval_split, nusc.version))\n    # Read out all sample_tokens in DB.\n    sample_tokens_all = [s['token'] for s in nusc.sample]\n    assert len(sample_tokens_all) > 0, \"Error: Database has no samples!\"\n\n    # Only keep samples from this split.\n    splits = create_splits_scenes()\n\n    # Check compatibility of split with nusc_version.\n    version = nusc.version\n    if eval_split in {'train', 'val', 'train_detect', 'train_track'}:\n        assert version.endswith('trainval'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split in {'mini_train', 'mini_val'}:\n        assert version.endswith('mini'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    elif eval_split == 'test':\n        assert version.endswith('test'), \\\n            'Error: Requested split {} which is not compatible with NuScenes version {}'.format(eval_split, version)\n    else:\n        raise ValueError('Error: Requested split {} which this function cannot map to the correct NuScenes version.'\n                         .format(eval_split))\n\n    if eval_split == 'test':\n        # Check that you aren't trying to cheat :).\n        assert len(nusc.sample_annotation) > 0, \\\n            'Error: You are trying to evaluate on the test set but you do not have the annotations!'\n\n    sample_tokens = []\n    \n    # selected_hard_scene_token = ['a178a1b5415f45c08d179bd2cacdf284', 'e005041f659c47e194cd5b18ea6fc346', 'e8099a6136804f3bb9b38ff94d98eb64', 'b789de07180846cc972118ee6d1fb027', '080a52cb8f59489b9cddc7b721808088', 'ed242d80ccb34b139aaf9ab89859332e', '325cef682f064c55a255f2625c533b75', '2f56eb47c64f43df8902d9f88aa8a019', '7210f928860043b5a7e0d3dd4b3e80ff', 'f97bf749746c4c3a8ad9f1c11eab6444', 'cba3ddd5c3664a43b6a08e586e094900', 'd29527ec841045d18d04a933e7a0afd2', 'c4df079d260241ff8015218e29b42ea7', '7052d21b95fc4bae8761b8d9524f3e42', '01e4fcbe6e49483293ce45727152b36e', '19d97841d6f64eba9f6eb9b6e8c257dc', 'fcc020250f884397965ba00c1d9ad9e6']\n    # for sample_token in sample_tokens_all:\n    #     scene_token = nusc.get('sample', sample_token)['scene_token']\n    #     scene_record = nusc.get('scene', scene_token)\n    #     if scene_record['name'] in splits[eval_split]:\n    #         if scene_token in selected_hard_scene_token:\n    #             sample_tokens.append(sample_token)\n    \n    \n    for sample_token in sample_tokens_all:\n        scene_token = nusc.get('sample', sample_token)['scene_token']\n        scene_record = nusc.get('scene', scene_token)\n        if scene_record['name'] in splits[eval_split]:\n            sample_tokens.append(sample_token)\n    \n    all_annotations = EvalBoxes()\n\n    # Load annotations and filter predictions and annotations.\n    tracking_id_set = set()\n    for sample_token in tqdm.tqdm(sample_tokens, leave=verbose):\n\n        sample = nusc.get('sample', sample_token)\n        sample_annotation_tokens = sample['anns']\n\n        sample_boxes = []\n        for sample_annotation_token in sample_annotation_tokens:\n\n            sample_annotation = nusc.get('sample_annotation', sample_annotation_token)\n            if box_cls == MotionBox:\n                # Get label name in detection task and filter unused labels.\n                detection_name = category_to_detection_name(sample_annotation['category_name'])\n                # motion name mapping\n                if detection_name in motion_name_mapping:\n                    detection_name = motion_name_mapping[detection_name]\n\n                if detection_name is None:\n                    continue\n\n                # Get attribute_name.\n                attr_tokens = sample_annotation['attribute_tokens']\n                attr_count = len(attr_tokens)\n                if attr_count == 0:\n                    attribute_name = ''\n                elif attr_count == 1:\n                    attribute_name = attribute_map[attr_tokens[0]]\n                else:\n                    raise Exception('Error: GT annotations must not have more than one attribute!')\n\n                # get future trajs\n                instance_token = nusc.get('sample_annotation', sample_annotation['token'])['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample_token, \n                    seconds=seconds, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    _, boxes, _ = nusc.get_sample_data(sample['data']['LIDAR_TOP'], selected_anntokens=[sample_annotation['token']])\n                    box = boxes[0]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scence_centric = convert_local_coords_to_global(fut_traj_local, trans, rot) \n                else:\n                    fut_traj_scence_centric = np.zeros((0,))\n\n                sample_boxes.append(\n                    box_cls(\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        detection_name=detection_name,\n                        detection_score=-1.0,  # GT samples do not have a score.\n                        attribute_name=attribute_name,\n                        traj=fut_traj_scence_centric\n                    )\n                )\n            elif box_cls == TrackingBox:\n                # Use nuScenes token as tracking id.\n                tracking_id = sample_annotation['instance_token']\n                tracking_id_set.add(tracking_id)\n\n                # Get label name in detection task and filter unused labels.\n                # Import locally to avoid errors when motmetrics package is not installed.\n                from nuscenes.eval.tracking.utils import category_to_tracking_name\n                tracking_name = category_to_tracking_name(sample_annotation['category_name'])\n                if tracking_name is None:\n                    continue\n\n                sample_boxes.append(\n                    box_cls(\n                        sample_token=sample_token,\n                        translation=sample_annotation['translation'],\n                        size=sample_annotation['size'],\n                        rotation=sample_annotation['rotation'],\n                        velocity=nusc.box_velocity(sample_annotation['token'])[:2],\n                        num_pts=sample_annotation['num_lidar_pts'] + sample_annotation['num_radar_pts'],\n                        tracking_id=tracking_id,\n                        tracking_name=tracking_name,\n                        tracking_score=-1.0  # GT samples do not have a score.\n                    )\n                )\n            else:\n                raise NotImplementedError('Error: Invalid box_cls %s!' % box_cls)\n\n        all_annotations.add_boxes(sample_token, sample_boxes)\n\n    if verbose:\n        print(\"Loaded ground truth annotations for {} samples.\".format(len(all_annotations.sample_tokens)))\n\n    return all_annotations\n\n\ndef accumulate(gt_boxes: EvalBoxes,\n               pred_boxes: EvalBoxes,\n               class_name: str,\n               dist_fcn: Callable,\n               dist_th: float,\n               verbose: bool = False) -> DetectionMetricData:\n    \"\"\"\n    Average Precision over predefined different recall thresholds for a single distance threshold.\n    The recall/conf thresholds and other raw metrics will be used in secondary metrics.\n    :param gt_boxes: Maps every sample_token to a list of its sample_annotations.\n    :param pred_boxes: Maps every sample_token to a list of its sample_results.\n    :param class_name: Class to compute AP on.\n    :param dist_fcn: Distance function used to match detections and ground truths.\n    :param dist_th: Distance threshold for a match.\n    :param verbose: If true, print debug messages.\n    :return: (average_prec, metrics). The average precision value and raw data for a number of metrics.\n    \"\"\"\n    # ---------------------------------------------\n    # Organize input and initialize accumulators.\n    # ---------------------------------------------\n\n    # Count the positives.\n    npos = len([1 for gt_box in gt_boxes.all if gt_box.detection_name == class_name])\n    if verbose:\n        print(\"Found {} GT of class {} out of {} total across {} samples.\".\n              format(npos, class_name, len(gt_boxes.all), len(gt_boxes.sample_tokens)))\n\n    # For missing classes in the GT, return a data structure corresponding to no predictions.\n    if npos == 0:\n        return DetectionMetricData.no_predictions(), 0\n\n    # Organize the predictions in a single list.\n    pred_boxes_list = [box for box in pred_boxes.all if box.detection_name == class_name]\n    pred_confs = [box.detection_score for box in pred_boxes_list]\n\n    if verbose:\n        print(\"Found {} PRED of class {} out of {} total across {} samples.\".\n              format(len(pred_confs), class_name, len(pred_boxes.all), len(pred_boxes.sample_tokens)))\n\n    # Sort by confidence.\n    sortind = [i for (v, i) in sorted((v, i) for (i, v) in enumerate(pred_confs))][::-1]\n\n    # Do the actual matching.\n    tp = []  # Accumulator of true positives.\n    fp = []  # Accumulator of false positives.\n    conf = []  # Accumulator of confidences.\n    hit = 0 # Accumulator of matched and hit\n\n    # match_data holds the extra metrics we calculate for each match.\n    match_data = {'conf': [],\n                  'min_ade': [],\n                  'min_fde': [],\n                  'miss_rate': []}\n\n    # ---------------------------------------------\n    # Match and accumulate match data.\n    # ---------------------------------------------\n\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th\n\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n\n            #  Update tp, fp and confs.\n            tp.append(1)\n            fp.append(0)\n            conf.append(pred_box.detection_score)\n\n            # Since it is a match, update match data also.\n            gt_box_match = gt_boxes[pred_box.sample_token][match_gt_idx]\n\n            match_data['conf'].append(pred_box.detection_score)\n\n            minade, minfde, mr = prediction_metrics(gt_box_match, pred_box)\n            match_data['min_ade'].append(minade)\n            match_data['min_fde'].append(minfde)\n            match_data['miss_rate'].append(mr)\n\n            if minfde < 2.0:\n                hit += 1\n\n        else:\n            # No match. Mark this as a false positive.\n            tp.append(0)\n            fp.append(1)\n            conf.append(pred_box.detection_score)\n\n    # Check if we have any matches. If not, just return a \"no predictions\" array.\n    if len(match_data['min_ade']) == 0:\n        return MotionMetricData.no_predictions()\n\n    # Accumulate.\n    N_tp = np.sum(tp)\n    N_fp = np.sum(fp)\n    tp = np.cumsum(tp).astype(float)\n    fp = np.cumsum(fp).astype(float)\n    conf = np.array(conf)\n\n    # Calculate precision and recall.\n    prec = tp / (fp + tp)\n    rec = tp / float(npos)\n\n    rec_interp = np.linspace(0, 1, DetectionMetricData.nelem)  # 101 steps, from 0% to 100% recall.\n    prec = np.interp(rec_interp, rec, prec, right=0)\n    conf = np.interp(rec_interp, rec, conf, right=0)\n    rec = rec_interp\n\n    # ---------------------------------------------\n    # Re-sample the match-data to match, prec, recall and conf.\n    # ---------------------------------------------\n\n    for key in match_data.keys():\n        if key == \"conf\":\n            continue  # Confidence is used as reference to align with fp and tp. So skip in this step.\n\n        else:\n            # For each match_data, we first calculate the accumulated mean.\n            tmp = cummean(np.array(match_data[key]))\n\n            # Then interpolate based on the confidences. (Note reversing since np.interp needs increasing arrays)\n            match_data[key] = np.interp(conf[::-1], match_data['conf'][::-1], tmp[::-1])[::-1]\n\n    EPA = (hit - 0.5 * N_fp) / npos\n\n    ## match based on traj\n    traj_matched = 0\n    taken = set()  # Initially no gt bounding box is matched.\n    for ind in sortind:\n        pred_box = pred_boxes_list[ind]\n        min_dist = np.inf\n        match_gt_idx = None\n\n        for gt_idx, gt_box in enumerate(gt_boxes[pred_box.sample_token]):\n\n            # Find closest match among ground truth boxes\n            if gt_box.detection_name == class_name and not (pred_box.sample_token, gt_idx) in taken:\n                this_distance = dist_fcn(gt_box, pred_box)\n                if this_distance < min_dist:\n                    min_dist = this_distance\n                    match_gt_idx = gt_idx\n                    fde_distance = traj_fde(gt_box, pred_box, final_step=12)\n\n        # If the closest match is close enough according to threshold we have a match!\n        is_match = min_dist < dist_th and fde_distance < 2.0\n        if is_match:\n            taken.add((pred_box.sample_token, match_gt_idx))\n            traj_matched += 1\n    EPA_ = (traj_matched - 0.5 * N_fp) / npos  ## same as UniAD\n\n    # ---------------------------------------------\n    # Done. Instantiate MetricData and return\n    # ---------------------------------------------\n    return MotionMetricData(recall=rec,\n                               precision=prec,\n                               confidence=conf,\n                               min_ade_err=match_data['min_ade'],\n                               min_fde_err=match_data['min_fde'],\n                               miss_rate_err=match_data['miss_rate']), EPA, EPA_\n\n\ndef prediction_metrics(gt_box_match, pred_box, miss_thresh=2):\n    gt_traj = np.array(gt_box_match.traj)\n    pred_traj = np.array(pred_box.traj)\n\n    valid_step = gt_traj.shape[0]\n    if valid_step <= 0:\n        return 0, 0, 0\n\n    pred_traj_valid = pred_traj[:, :valid_step, :]\n    dist = np.linalg.norm(pred_traj_valid - gt_traj[np.newaxis], axis=2)\n\n    minade = dist.mean(axis=1).min()\n    minfde = dist[:, -1].min()\n    mr = dist.max(axis=1).min() > miss_thresh\n\n    return minade, minfde, mr\n\ndef traj_fde(gt_box, pred_box, final_step):\n    if gt_box.traj.shape[0] <= 0:\n        return np.inf\n    final_step = min(gt_box.traj.shape[0], final_step)\n    gt_final = gt_box.traj[None, final_step-1]\n    pred_final = np.array(pred_box.traj)[:,final_step-1,:]\n    err = gt_final - pred_final\n    err = np.sqrt(np.sum(np.square(gt_final - pred_final), axis=-1))\n    return np.min(err)\n\n\nclass MotionMetricDataList(DetectionMetricDataList):\n    \"\"\" This stores a set of MetricData in a dict indexed by (name, match-distance). \"\"\"\n    @classmethod\n    def deserialize(cls, content: dict):\n        mdl = cls()\n        for key, md in content.items():\n            name, distance = key.split(':')\n            mdl.set(name, float(distance), MotionMetricData.deserialize(md))\n        return mdl\n\nclass MotionMetricData(DetectionMetricData):\n    \"\"\" This class holds accumulated and interpolated data required to calculate the detection metrics. \"\"\"\n\n    nelem = 101\n\n    def __init__(self,\n                 recall: np.array,\n                 precision: np.array,\n                 confidence: np.array,\n                 min_ade_err: np.array,\n                 min_fde_err: np.array,\n                 miss_rate_err: np.array):\n\n        # Assert lengths.\n        assert len(recall) == self.nelem\n        assert len(precision) == self.nelem\n        assert len(confidence) == self.nelem\n        assert len(min_ade_err) == self.nelem\n        assert len(min_fde_err) == self.nelem\n        assert len(miss_rate_err) == self.nelem\n\n        # Assert ordering.\n        assert all(confidence == sorted(confidence, reverse=True))  # Confidences should be descending.\n        assert all(recall == sorted(recall))  # Recalls should be ascending.\n\n        # Set attributes explicitly to help IDEs figure out what is going on.\n        self.recall = recall\n        self.precision = precision\n        self.confidence = confidence\n        self.min_ade_err = min_ade_err\n        self.min_fde_err = min_fde_err\n        self.miss_rate_err = miss_rate_err\n\n    def __eq__(self, other):\n        eq = True\n        for key in self.serialize().keys():\n            eq = eq and np.array_equal(getattr(self, key), getattr(other, key))\n        return eq\n\n    @property\n    def max_recall_ind(self):\n        \"\"\" Returns index of max recall achieved. \"\"\"\n\n        # Last instance of confidence > 0 is index of max achieved recall.\n        non_zero = np.nonzero(self.confidence)[0]\n        if len(non_zero) == 0:  # If there are no matches, all the confidence values will be zero.\n            max_recall_ind = 0\n        else:\n            max_recall_ind = non_zero[-1]\n\n        return max_recall_ind\n\n    @property\n    def max_recall(self):\n        \"\"\" Returns max recall achieved. \"\"\"\n\n        return self.recall[self.max_recall_ind]\n\n    def serialize(self):\n        \"\"\" Serialize instance into json-friendly format. \"\"\"\n        return {\n            'recall': self.recall.tolist(),\n            'precision': self.precision.tolist(),\n            'confidence': self.confidence.tolist(),\n            'min_ade_err': self.min_ade_err.tolist(),\n            'min_fde_err': self.min_fde_err.tolist(),\n            'miss_rate_err': self.miss_rate_err.tolist(),\n        }\n\n    @classmethod\n    def deserialize(cls, content: dict):\n        \"\"\" Initialize from serialized content. \"\"\"\n        return cls(recall=np.array(content['recall']),\n                   precision=np.array(content['precision']),\n                   confidence=np.array(content['confidence']),\n                   min_ade_err=np.array(content['min_ade_err']),\n                   min_fde_err=np.array(content['min_fde_err']),\n                   miss_rate_err=np.array(content['miss_rate_err']))\n\n    @classmethod\n    def no_predictions(cls):\n        \"\"\" Returns a md instance corresponding to having no predictions. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.zeros(cls.nelem),\n                   confidence=np.zeros(cls.nelem),\n                   min_ade_err=np.ones(cls.nelem),\n                   min_fde_err=np.ones(cls.nelem),\n                   miss_rate_err=np.ones(cls.nelem))\n\n    @classmethod\n    def random_md(cls):\n        \"\"\" Returns an md instance corresponding to a random results. \"\"\"\n        return cls(recall=np.linspace(0, 1, cls.nelem),\n                   precision=np.random.random(cls.nelem),\n                   confidence=np.linspace(0, 1, cls.nelem)[::-1],\n                   min_ade_err=np.random.random(cls.nelem),\n                   min_fde_err=np.random.random(cls.nelem),\n                   miss_rate_err=np.random.random(cls.nelem))\n\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/planning/planning_eval.py",
    "content": "from tqdm import tqdm\nimport torch\nimport torch.nn as nn\nimport numpy as np\nfrom shapely.geometry import Polygon\n\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import build_dataset, build_dataloader\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\n\n\ndef check_collision(ego_box, boxes):\n    '''\n        ego_box: tensor with shape [7], [x, y, z, w, l, h, yaw]\n        boxes: tensor with shape [N, 7]\n    '''\n    if  boxes.shape[0] == 0:\n        return False\n\n    # follow uniad, add a 0.5m offset\n    ego_box[0] += 0.5 * torch.cos(ego_box[6])\n    ego_box[1] += 0.5 * torch.sin(ego_box[6])\n    ego_corners_box = box3d_to_corners(ego_box.unsqueeze(0))[0, [0, 3, 7, 4], :2]\n    corners_box = box3d_to_corners(boxes)[:, [0, 3, 7, 4], :2]\n    ego_poly = Polygon([(point[0], point[1]) for point in ego_corners_box])\n    for i in range(len(corners_box)):\n        box_poly =  Polygon([(point[0], point[1]) for point in corners_box[i]])\n        collision = ego_poly.intersects(box_poly)\n        if collision:\n            return True\n\n    return False\n\ndef get_yaw(traj):\n    start = traj[0]\n    end = traj[-1]\n    dist = torch.linalg.norm(end - start, dim=-1)\n    if dist < 0.5:\n        return traj.new_ones(traj.shape[0]) * np.pi / 2\n\n    zeros = traj.new_zeros((1, 2))\n    traj_cat = torch.cat([zeros, traj], dim=0)\n    yaw = traj.new_zeros(traj.shape[0]+1)\n    yaw[..., 1:-1] = torch.atan2(\n        traj_cat[..., 2:, 1] - traj_cat[..., :-2, 1],\n        traj_cat[..., 2:, 0] - traj_cat[..., :-2, 0],\n    )\n    yaw[..., -1] = torch.atan2(\n        traj_cat[..., -1, 1] - traj_cat[..., -2, 1],\n        traj_cat[..., -1, 0] - traj_cat[..., -2, 0],\n    )\n    return yaw[1:]\n\nclass PlanningMetric():\n    def __init__(\n        self,\n        n_future=6,\n        compute_on_step: bool = False,\n    ):\n        self.W = 1.85\n        self.H = 4.084\n\n        self.n_future = n_future\n        self.reset()\n\n    def reset(self):\n        self.obj_col = torch.zeros(self.n_future)\n        self.obj_box_col = torch.zeros(self.n_future)\n        self.L2 = torch.zeros(self.n_future)\n        self.total = torch.tensor(0)\n\n    def evaluate_single_coll(self, traj, fut_boxes):\n        n_future = traj.shape[0]\n        yaw = get_yaw(traj)\n        ego_box = traj.new_zeros((n_future, 7))\n        ego_box[:, :2] = traj\n        ego_box[:, 3:6] = ego_box.new_tensor([self.H, self.W, 1.56])\n        ego_box[:, 6] = yaw\n        collision = torch.zeros(n_future, dtype=torch.bool)\n\n        for t in range(n_future):\n            ego_box_t = ego_box[t].clone()\n            boxes = fut_boxes[t][0].clone()\n            collision[t] = check_collision(ego_box_t, boxes)\n        return collision\n\n    def evaluate_coll(self, trajs, gt_trajs, fut_boxes):\n        B, n_future, _ = trajs.shape\n        trajs = trajs * torch.tensor([-1, 1], device=trajs.device)\n        gt_trajs = gt_trajs * torch.tensor([-1, 1], device=gt_trajs.device)\n\n        obj_coll_sum = torch.zeros(n_future, device=trajs.device)\n        obj_box_coll_sum = torch.zeros(n_future, device=trajs.device)\n\n        assert B == 1, 'only supprt bs=1'\n        for i in range(B):\n            gt_box_coll = self.evaluate_single_coll(gt_trajs[i], fut_boxes)\n            box_coll = self.evaluate_single_coll(trajs[i], fut_boxes)\n            box_coll = torch.logical_and(box_coll, torch.logical_not(gt_box_coll))\n            \n            obj_coll_sum += gt_box_coll.long()\n            obj_box_coll_sum += box_coll.long()\n\n        return obj_coll_sum, obj_box_coll_sum\n\n    def compute_L2(self, trajs, gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n        return torch.sqrt((((trajs[:, :, :2] - gt_trajs[:, :, :2]) ** 2) * gt_trajs_mask).sum(dim=-1)) \n\n    def update(self, trajs, gt_trajs, gt_trajs_mask, fut_boxes):\n        assert trajs.shape == gt_trajs.shape\n        trajs[..., 0] = - trajs[..., 0]\n        gt_trajs[..., 0] = - gt_trajs[..., 0]\n        L2 = self.compute_L2(trajs, gt_trajs, gt_trajs_mask)\n        obj_coll_sum, obj_box_coll_sum = self.evaluate_coll(trajs[:,:,:2], gt_trajs[:,:,:2], fut_boxes)\n\n        self.obj_col += obj_coll_sum\n        self.obj_box_col += obj_box_coll_sum\n        self.L2 += L2.sum(dim=0)\n        self.total +=len(trajs)\n\n    def compute(self):\n        return {\n            'obj_col': self.obj_col / self.total,\n            'obj_box_col': self.obj_box_col / self.total,\n            'L2' : self.L2 / self.total\n        }\n\n\ndef planning_eval(results, eval_config, logger):\n    dataset = build_dataset(eval_config)\n    dataloader = build_dataloader(\n            dataset, samples_per_gpu=1, workers_per_gpu=1, shuffle=False, dist=False)\n    planning_metrics = PlanningMetric()\n    for i, data in enumerate(tqdm(dataloader)):\n        sdc_planning = data['gt_ego_fut_trajs'].cumsum(dim=-2).unsqueeze(1)\n        sdc_planning_mask = data['gt_ego_fut_masks'].unsqueeze(-1).repeat(1, 1, 2).unsqueeze(1)\n        command = data['gt_ego_fut_cmd'].argmax(dim=-1).item()\n        fut_boxes = data['fut_boxes']\n        if not sdc_planning_mask.all(): ## for incomplete gt, we do not count this sample\n            continue\n        res = results[i]\n        pred_sdc_traj = res['img_bbox']['final_planning'].unsqueeze(0)\n        planning_metrics.update(pred_sdc_traj[:, :6, :2], sdc_planning[0,:, :6, :2], sdc_planning_mask[0,:, :6, :2], fut_boxes)\n       \n    planning_results = planning_metrics.compute()\n    planning_metrics.reset()\n    from prettytable import PrettyTable\n    planning_tab = PrettyTable()\n    metric_dict = {}\n\n    planning_tab.field_names = [\n    \"metrics\", \"0.5s\", \"1.0s\", \"1.5s\", \"2.0s\", \"2.5s\", \"3.0s\", \"avg\"]\n    for key in planning_results.keys():\n        value = planning_results[key].tolist()\n        new_values = []\n        for i in range(len(value)):\n            new_values.append(np.array(value[:i+1]).mean())\n        value = new_values\n        avg = [value[1], value[3], value[5]]\n        avg = sum(avg) / len(avg)\n        value.append(avg)\n        metric_dict[key] = avg\n        row_value = []\n        row_value.append(key)\n        for i in range(len(value)):\n            if 'col' in key:\n                row_value.append('%.3f' % float(value[i]*100) + '%')\n            else:\n                row_value.append('%.4f' % float(value[i]))\n        planning_tab.add_row(row_value)\n\n    print_log('\\n'+str(planning_tab), logger=logger)\n    return metric_dict"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/planning/planning_eval_roboAD.py",
    "content": "from tqdm import tqdm\nimport torch\nimport torch.nn as nn\nimport numpy as np\nfrom shapely.geometry import Polygon\n\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import build_dataset, build_dataloader\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom nuscenes.nuscenes import NuScenes\n\ndef check_collision(ego_box, boxes):\n    '''\n        ego_box: tensor with shape [7], [x, y, z, w, l, h, yaw]\n        boxes: tensor with shape [N, 7]\n    '''\n    if  boxes.shape[0] == 0:\n        return False\n\n    # follow uniad, add a 0.5m offset\n    ego_box[0] += 0.5 * torch.cos(ego_box[6])\n    ego_box[1] += 0.5 * torch.sin(ego_box[6])\n    ego_corners_box = box3d_to_corners(ego_box.unsqueeze(0))[0, [0, 3, 7, 4], :2]\n    corners_box = box3d_to_corners(boxes)[:, [0, 3, 7, 4], :2]\n    ego_poly = Polygon([(point[0], point[1]) for point in ego_corners_box])\n    for i in range(len(corners_box)):\n        box_poly =  Polygon([(point[0], point[1]) for point in corners_box[i]])\n        collision = ego_poly.intersects(box_poly)\n        if collision:\n            return True\n\n    return False\n\ndef get_yaw(traj):\n    start = traj[0]\n    end = traj[-1]\n    dist = torch.linalg.norm(end - start, dim=-1)\n    if dist < 0.5:\n        return traj.new_ones(traj.shape[0]) * np.pi / 2\n\n    zeros = traj.new_zeros((1, 2))\n    traj_cat = torch.cat([zeros, traj], dim=0)\n    yaw = traj.new_zeros(traj.shape[0]+1)\n    yaw[..., 1:-1] = torch.atan2(\n        traj_cat[..., 2:, 1] - traj_cat[..., :-2, 1],\n        traj_cat[..., 2:, 0] - traj_cat[..., :-2, 0],\n    )\n    yaw[..., -1] = torch.atan2(\n        traj_cat[..., -1, 1] - traj_cat[..., -2, 1],\n        traj_cat[..., -1, 0] - traj_cat[..., -2, 0],\n    )\n    return yaw[1:]\n\nclass PlanningMetric():\n    def __init__(\n        self,\n        n_future=6,\n        compute_on_step: bool = False,\n    ):\n        self.W = 1.85\n        self.H = 4.084\n\n        self.n_future = n_future\n        self.reset()\n\n    def reset(self):\n        self.obj_col = torch.zeros(self.n_future)\n        self.obj_box_col = torch.zeros(self.n_future)\n        self.L2 = torch.zeros(self.n_future)\n        self.Consist = torch.zeros(self.n_future)\n        self.total = torch.tensor(0)\n\n    def evaluate_single_coll(self, traj, fut_boxes):\n        n_future = traj.shape[0]\n        yaw = get_yaw(traj)\n        ego_box = traj.new_zeros((n_future, 7))\n        ego_box[:, :2] = traj\n        ego_box[:, 3:6] = ego_box.new_tensor([self.H, self.W, 1.56])\n        ego_box[:, 6] = yaw\n        collision = torch.zeros(n_future, dtype=torch.bool)\n\n        for t in range(n_future):\n            ego_box_t = ego_box[t].clone()\n            boxes = fut_boxes[t][0].clone()\n            collision[t] = check_collision(ego_box_t, boxes)\n        return collision\n\n    def evaluate_coll(self, trajs, gt_trajs, fut_boxes):\n        B, n_future, _ = trajs.shape\n        trajs = trajs * torch.tensor([-1, 1], device=trajs.device)\n        gt_trajs = gt_trajs * torch.tensor([-1, 1], device=gt_trajs.device)\n\n        obj_coll_sum = torch.zeros(n_future, device=trajs.device)\n        obj_box_coll_sum = torch.zeros(n_future, device=trajs.device)\n\n        assert B == 1, 'only supprt bs=1'\n        for i in range(B):\n            gt_box_coll = self.evaluate_single_coll(gt_trajs[i], fut_boxes)\n            box_coll = self.evaluate_single_coll(trajs[i], fut_boxes)\n            box_coll = torch.logical_and(box_coll, torch.logical_not(gt_box_coll))\n            \n            obj_coll_sum += gt_box_coll.long()\n            obj_box_coll_sum += box_coll.long()\n\n        return obj_coll_sum, obj_box_coll_sum\n\n    def compute_L2(self, trajs, gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n        return torch.sqrt((((trajs[:, :, :2] - gt_trajs[:, :, :2]) ** 2) * gt_trajs_mask).sum(dim=-1)) \n\n    def compute_Consist(self, trajs, last_final_planning, gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n\n        return torch.sqrt(((((trajs[:, :, :2] - last_final_planning[:, :, :2])) ** 2) * gt_trajs_mask).sum(dim=-1)) \n    def update(self, trajs, gt_trajs, gt_trajs_mask, fut_boxes, last_final_planning):\n        \"\"\"\n        trajs  pred_final_planning\n        gt_trajs  gt_ego_fut_trajs\n        \"\"\"\n        # import pdb; pdb.set_trace()\n        assert trajs.shape == gt_trajs.shape\n        trajs[..., 0] = - trajs[..., 0]\n        gt_trajs[..., 0] = - gt_trajs[..., 0]\n        L2 = self.compute_L2(trajs, gt_trajs, gt_trajs_mask)\n        Consist = self.compute_Consist(trajs, last_final_planning,gt_trajs, gt_trajs_mask)\n        obj_coll_sum, obj_box_coll_sum = self.evaluate_coll(trajs[:,:,:2], gt_trajs[:,:,:2], fut_boxes)\n\n        self.obj_col += obj_coll_sum\n        self.obj_box_col += obj_box_coll_sum\n        self.L2 += L2.sum(dim=0)\n        self.Consist += Consist.sum(dim=0)\n        self.total +=len(trajs)\n\n    def compute(self):\n        print(self.total)\n        return {\n            'obj_col': self.obj_col / self.total,\n            'obj_box_col': self.obj_box_col / self.total,\n            'L2' : self.L2 / self.total,\n            'Consist':self.Consist / self.total\n        }\n\n# nusc = NuScenes(version='v1.0-trainval', dataroot=\"data/nuscenes/\", verbose=True)\ndef planning_eval_roboAD(results, eval_config, logger):\n    dataset = build_dataset(eval_config)\n    dataloader = build_dataloader(\n            dataset, samples_per_gpu=1, workers_per_gpu=1, shuffle=False, dist=False)\n    planning_metrics = PlanningMetric()\n    last_final_planning = torch.zeros([1,6,2])\n    # import pdb; pdb.set_trace()\n\n    for i, data in enumerate(tqdm(dataloader)):\n        # next_token=nusc.get('sample', data['img_metas'].data[0][0][\"token\"])[\"next\"]\n        # import pdb; pdb.set_trace()\n        sdc_planning = data['gt_ego_fut_trajs'].cumsum(dim=-2).unsqueeze(1)\n        sdc_planning_mask = data['gt_ego_fut_masks'].unsqueeze(-1).repeat(1, 1, 2).unsqueeze(1)\n        command = data['gt_ego_fut_cmd'].argmax(dim=-1).item()\n        fut_boxes = data['fut_boxes']\n        if not sdc_planning_mask.all(): ## for incomplete gt, we do not count this sample\n            continue\n        res = results[i]\n        pred_sdc_traj = res['img_bbox']['final_planning'].unsqueeze(0)\n        # import pdb; pdb.set_trace()\n        planning_metrics.update(pred_sdc_traj[:, :6, :2], sdc_planning[0,:, :6, :2], sdc_planning_mask[0,:, :6, :2], fut_boxes, last_final_planning)\n        last_final_planning=pred_sdc_traj[:, :6, :2]\n    planning_results = planning_metrics.compute()\n    planning_metrics.reset()\n    from prettytable import PrettyTable\n    planning_tab = PrettyTable()\n    metric_dict = {}\n\n    planning_tab.field_names = [\n    \"metrics\", \"0.5s\", \"1.0s\", \"1.5s\", \"2.0s\", \"2.5s\", \"3.0s\",\"avg\"]\n    for key in planning_results.keys():\n        value = planning_results[key].tolist()\n        new_values = []\n        for i in range(len(value)):\n            new_values.append(np.array(value[:i+1]).mean())\n        value = new_values\n        avg = [value[1], value[3], value[5]]\n        avg = sum(avg) / len(avg)\n        value.append(avg)\n        metric_dict[key] = avg\n        # import pdb; pdb.set_trace()\n        row_value = []\n        row_value.append(key)\n        for i in range(len(value)):\n            if 'col' in key:\n                row_value.append('%.3f' % float(value[i]*100) + '%')\n            else:\n                row_value.append('%.4f' % float(value[i]))\n        planning_tab.add_row(row_value)\n\n    print_log('\\n'+str(planning_tab), logger=logger)\n    return metric_dict\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/evaluation/planning/planning_eval_roboAD_6s.py",
    "content": "from tqdm import tqdm\nimport torch\nimport torch.nn as nn\nimport numpy as np\nfrom shapely.geometry import Polygon\n\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import build_dataset, build_dataloader\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom nuscenes.nuscenes import NuScenes\n\ndef check_collision(ego_box, boxes):\n    '''\n        ego_box: tensor with shape [7], [x, y, z, w, l, h, yaw]\n        boxes: tensor with shape [N, 7]\n    '''\n    if  boxes.shape[0] == 0:\n        return False\n\n    # follow uniad, add a 0.5m offset\n    ego_box[0] += 0.5 * torch.cos(ego_box[6])\n    ego_box[1] += 0.5 * torch.sin(ego_box[6])\n    ego_corners_box = box3d_to_corners(ego_box.unsqueeze(0))[0, [0, 3, 7, 4], :2]\n    corners_box = box3d_to_corners(boxes)[:, [0, 3, 7, 4], :2]\n    ego_poly = Polygon([(point[0], point[1]) for point in ego_corners_box])\n    for i in range(len(corners_box)):\n        box_poly =  Polygon([(point[0], point[1]) for point in corners_box[i]])\n        collision = ego_poly.intersects(box_poly)\n        if collision:\n            return True\n\n    return False\n\ndef get_yaw(traj):\n    start = traj[0]\n    end = traj[-1]\n    dist = torch.linalg.norm(end - start, dim=-1)\n    if dist < 0.5:\n        return traj.new_ones(traj.shape[0]) * np.pi / 2\n\n    zeros = traj.new_zeros((1, 2))\n    traj_cat = torch.cat([zeros, traj], dim=0)\n    yaw = traj.new_zeros(traj.shape[0]+1)\n    yaw[..., 1:-1] = torch.atan2(\n        traj_cat[..., 2:, 1] - traj_cat[..., :-2, 1],\n        traj_cat[..., 2:, 0] - traj_cat[..., :-2, 0],\n    )\n    yaw[..., -1] = torch.atan2(\n        traj_cat[..., -1, 1] - traj_cat[..., -2, 1],\n        traj_cat[..., -1, 0] - traj_cat[..., -2, 0],\n    )\n    return yaw[1:]\n\nclass PlanningMetric():\n    def __init__(\n        self,\n        n_future=12,\n        compute_on_step: bool = False,\n    ):\n        self.W = 1.85\n        self.H = 4.084\n\n        self.n_future = n_future\n        self.reset()\n\n    def reset(self):\n        self.obj_col = torch.zeros(self.n_future)\n        self.obj_box_col = torch.zeros(self.n_future)\n        self.L2 = torch.zeros(self.n_future)\n        self.Consist = torch.zeros(self.n_future)\n        self.total = torch.tensor(0)\n\n    def evaluate_single_coll(self, traj, fut_boxes):\n        n_future = traj.shape[0]\n        yaw = get_yaw(traj)\n        ego_box = traj.new_zeros((n_future, 7))\n        ego_box[:, :2] = traj\n        ego_box[:, 3:6] = ego_box.new_tensor([self.H, self.W, 1.56])\n        ego_box[:, 6] = yaw\n        collision = torch.zeros(n_future, dtype=torch.bool)\n\n        for t in range(n_future):\n            ego_box_t = ego_box[t].clone()\n            boxes = fut_boxes[t][0].clone()\n            collision[t] = check_collision(ego_box_t, boxes)\n        return collision\n\n    def evaluate_coll(self, trajs, gt_trajs, fut_boxes):\n        B, n_future, _ = trajs.shape\n        trajs = trajs * torch.tensor([-1, 1], device=trajs.device)\n        gt_trajs = gt_trajs * torch.tensor([-1, 1], device=gt_trajs.device)\n\n        obj_coll_sum = torch.zeros(n_future, device=trajs.device)\n        obj_box_coll_sum = torch.zeros(n_future, device=trajs.device)\n\n        assert B == 1, 'only supprt bs=1'\n        for i in range(B):\n            gt_box_coll = self.evaluate_single_coll(gt_trajs[i], fut_boxes)\n            box_coll = self.evaluate_single_coll(trajs[i], fut_boxes)\n            box_coll = torch.logical_and(box_coll, torch.logical_not(gt_box_coll))\n            \n            obj_coll_sum += gt_box_coll.long()\n            obj_box_coll_sum += box_coll.long()\n\n        return obj_coll_sum, obj_box_coll_sum\n\n    def compute_L2(self, trajs, gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n        return torch.sqrt((((trajs[:, :, :2] - gt_trajs[:, :, :2]) ** 2) * gt_trajs_mask).sum(dim=-1)) \n\n    def compute_Consist(self, trajs, last_final_planning,gt_trajs, gt_trajs_mask):\n        '''\n        trajs: torch.Tensor (B, n_future, 3)\n        gt_trajs: torch.Tensor (B, n_future, 3)\n        '''\n\n        return torch.sqrt(((((trajs[:, :, :2] - last_final_planning[:, :, :2])) ** 2) * gt_trajs_mask).sum(dim=-1)) \n    def update(self, trajs, gt_trajs, gt_trajs_mask, fut_boxes,last_final_planning):\n        \"\"\"\n        trajs  pred_final_planning\n        gt_trajs  gt_ego_fut_trajs\n        \"\"\"\n        # import pdb; pdb.set_trace()\n        assert trajs.shape == gt_trajs.shape\n        trajs[..., 0] = - trajs[..., 0]\n        gt_trajs[..., 0] = - gt_trajs[..., 0]\n        L2 = self.compute_L2(trajs, gt_trajs, gt_trajs_mask)\n        Consist = self.compute_Consist(trajs, last_final_planning,gt_trajs, gt_trajs_mask)\n        obj_coll_sum, obj_box_coll_sum = self.evaluate_coll(trajs[:,:,:2], gt_trajs[:,:,:2], fut_boxes)\n\n        self.obj_col += obj_coll_sum\n        self.obj_box_col += obj_box_coll_sum\n        self.L2 += L2.sum(dim=0)\n        self.Consist += Consist.sum(dim=0)\n        self.total +=len(trajs)\n\n    def compute(self):\n        print(self.total)\n\n        return {\n            'obj_col': self.obj_col / self.total,\n            'obj_box_col': self.obj_box_col / self.total,\n            'L2' : self.L2 / self.total,\n            'Consist':self.Consist / self.total\n        }\n\n# nusc = NuScenes(version='v1.0-trainval', dataroot=\"data/nuscenes/\", verbose=True)\ndef planning_eval_roboAD_6s(results, eval_config, logger):\n    dataset = build_dataset(eval_config)\n    dataloader = build_dataloader(\n            dataset, samples_per_gpu=1, workers_per_gpu=1, shuffle=False, dist=False)\n    planning_metrics = PlanningMetric()\n    last_final_planning = torch.zeros([1,12,2])\n    # import pdb; pdb.set_trace()\n\n    for i, data in enumerate(tqdm(dataloader)):\n        # next_token=nusc.get('sample', data['img_metas'].data[0][0][\"token\"])[\"next\"]\n        # import pdb; pdb.set_trace()\n        sdc_planning = data['gt_ego_fut_trajs'].cumsum(dim=-2).unsqueeze(1)\n        sdc_planning_mask = data['gt_ego_fut_masks'].unsqueeze(-1).repeat(1, 1, 2).unsqueeze(1)\n        command = data['gt_ego_fut_cmd'].argmax(dim=-1).item()\n        fut_boxes = data['fut_boxes']\n        if not sdc_planning_mask.all(): ## for incomplete gt, we do not count this sample\n            continue\n        res = results[i]\n        pred_sdc_traj = res['img_bbox']['final_planning'].unsqueeze(0)\n        planning_metrics.update(pred_sdc_traj[:, :12, :2], sdc_planning[0,:, :12, :2], sdc_planning_mask[0,:, :12, :2], fut_boxes,last_final_planning)\n        last_final_planning=pred_sdc_traj[:, :12, :2]\n    planning_results = planning_metrics.compute()\n    planning_metrics.reset()\n    from prettytable import PrettyTable\n    planning_tab = PrettyTable()\n    metric_dict = {}\n\n    planning_tab.field_names = [\n    \"metrics\", \"0.5s\", \"1.0s\", \"1.5s\", \"2.0s\", \"2.5s\", \"3.0s\",\"3.5s\",\"4.0s\",\"4.5s\",\"5.0s\",\"5.5s\",\"6.0s\",\"avg\"]\n    for key in planning_results.keys():\n        value = planning_results[key].tolist()\n        new_values = []\n        for i in range(len(value)):\n            new_values.append(np.array(value[:i+1]).mean())\n        value = new_values\n        avg = [value[1], value[3], value[5]]\n        avg = sum(avg) / len(avg)\n        value.append(avg)\n        metric_dict[key] = avg\n        # import pdb; pdb.set_trace()\n        row_value = []\n        row_value.append(key)\n        for i in range(len(value)):\n            if 'col' in key:\n                row_value.append('%.3f' % float(value[i]*100) + '%')\n            else:\n                row_value.append('%.4f' % float(value[i]))\n        planning_tab.add_row(row_value)\n\n    print_log('\\n'+str(planning_tab), logger=logger)\n    return metric_dict\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/map_utils/nuscmap_extractor.py",
    "content": "from shapely.geometry import LineString, box, Polygon\nfrom shapely import ops, strtree\n\nimport numpy as np\nfrom nuscenes.map_expansion.map_api import NuScenesMap, NuScenesMapExplorer\nfrom nuscenes.eval.common.utils import quaternion_yaw\nfrom pyquaternion import Quaternion\nfrom .utils import split_collections, get_drivable_area_contour, \\\n        get_ped_crossing_contour\nfrom numpy.typing import NDArray\nfrom typing import Dict, List, Tuple, Union\n\nclass NuscMapExtractor(object):\n    \"\"\"NuScenes map ground-truth extractor.\n\n    Args:\n        data_root (str): path to nuScenes dataset\n        roi_size (tuple or list): bev range\n    \"\"\"\n    def __init__(self, data_root: str, roi_size: Union[List, Tuple]) -> None:\n        self.roi_size = roi_size\n        self.MAPS = ['boston-seaport', 'singapore-hollandvillage',\n                     'singapore-onenorth', 'singapore-queenstown']\n        \n        self.nusc_maps = {}\n        self.map_explorer = {}\n        for loc in self.MAPS:\n            self.nusc_maps[loc] = NuScenesMap(\n                dataroot=data_root, map_name=loc)\n            self.map_explorer[loc] = NuScenesMapExplorer(self.nusc_maps[loc])\n        \n        # local patch in nuScenes format\n        self.local_patch = box(-roi_size[0] / 2, -roi_size[1] / 2, \n                roi_size[0] / 2, roi_size[1] / 2)\n    \n    def _union_ped(self, ped_geoms: List[Polygon]) -> List[Polygon]:\n        ''' merge close ped crossings.\n        \n        Args:\n            ped_geoms (list): list of Polygon\n        \n        Returns:\n            union_ped_geoms (Dict): merged ped crossings \n        '''\n\n        def get_rec_direction(geom):\n            rect = geom.minimum_rotated_rectangle\n            rect_v_p = np.array(rect.exterior.coords)[:3]\n            rect_v = rect_v_p[1:]-rect_v_p[:-1]\n            v_len = np.linalg.norm(rect_v, axis=-1)\n            longest_v_i = v_len.argmax()\n\n            return rect_v[longest_v_i], v_len[longest_v_i]\n\n        tree = strtree.STRtree(ped_geoms)\n        index_by_id = dict((id(pt), i) for i, pt in enumerate(ped_geoms))\n\n        final_pgeom = []\n        remain_idx = [i for i in range(len(ped_geoms))]\n        for i, pgeom in enumerate(ped_geoms):\n\n            if i not in remain_idx:\n                continue\n            # update\n            remain_idx.pop(remain_idx.index(i))\n            pgeom_v, pgeom_v_norm = get_rec_direction(pgeom)\n            final_pgeom.append(pgeom)\n\n            for o in tree.query(pgeom):\n                o_idx = index_by_id[id(o)]\n                if o_idx not in remain_idx:\n                    continue\n\n                o_v, o_v_norm = get_rec_direction(o)\n                cos = pgeom_v.dot(o_v)/(pgeom_v_norm*o_v_norm)\n                if 1 - np.abs(cos) < 0.01:  # theta < 8 degrees.\n                    final_pgeom[-1] =\\\n                        final_pgeom[-1].union(o)\n                    # update\n                    remain_idx.pop(remain_idx.index(o_idx))\n\n        results = []\n        for p in final_pgeom:\n            results.extend(split_collections(p))\n        return results\n        \n    def get_map_geom(self, \n                     location: str, \n                     translation: Union[List, NDArray],\n                     rotation: Union[List, NDArray]) -> Dict[str, List[Union[LineString, Polygon]]]:\n        ''' Extract geometries given `location` and self pose, self may be lidar or ego.\n        \n        Args:\n            location (str): city name\n            translation (array): self2global translation, shape (3,)\n            rotation (array): self2global quaternion, shape (4, )\n            \n        Returns:\n            geometries (Dict): extracted geometries by category.\n        '''\n\n        # (center_x, center_y, len_y, len_x) in nuscenes format\n        patch_box = (translation[0], translation[1], \n                self.roi_size[1], self.roi_size[0])\n        rotation = Quaternion(rotation)\n        yaw = quaternion_yaw(rotation) / np.pi * 180\n\n        # get dividers\n        lane_dividers = self.map_explorer[location]._get_layer_line(\n                    patch_box, yaw, 'lane_divider')\n        \n        road_dividers = self.map_explorer[location]._get_layer_line(\n                    patch_box, yaw, 'road_divider')\n        \n        all_dividers = []\n        for line in lane_dividers + road_dividers:\n            all_dividers += split_collections(line)\n\n        # get ped crossings\n        ped_crossings = []\n        ped = self.map_explorer[location]._get_layer_polygon(\n                    patch_box, yaw, 'ped_crossing')\n        \n        for p in ped:\n            ped_crossings += split_collections(p)\n        # some ped crossings are split into several small parts\n        # we need to merge them\n        ped_crossings = self._union_ped(ped_crossings)\n        \n        ped_crossing_lines = []\n        for p in ped_crossings:\n            # extract exteriors to get a closed polyline\n            line = get_ped_crossing_contour(p, self.local_patch)\n            if line is not None:\n                ped_crossing_lines.append(line)\n\n        # get boundaries\n        # we take the union of road segments and lanes as drivable areas\n        # we don't take drivable area layer in nuScenes since its definition may be ambiguous\n        road_segments = self.map_explorer[location]._get_layer_polygon(\n                    patch_box, yaw, 'road_segment')\n        lanes = self.map_explorer[location]._get_layer_polygon(\n                    patch_box, yaw, 'lane')\n        union_roads = ops.unary_union(road_segments)\n        union_lanes = ops.unary_union(lanes)\n        drivable_areas = ops.unary_union([union_roads, union_lanes])\n        \n        drivable_areas = split_collections(drivable_areas)\n        \n        # boundaries are defined as the contour of drivable areas\n        boundaries = get_drivable_area_contour(drivable_areas, self.roi_size)\n\n        return dict(\n            divider=all_dividers, # List[LineString]\n            ped_crossing=ped_crossing_lines, # List[LineString]\n            boundary=boundaries, # List[LineString]\n            drivable_area=drivable_areas, # List[Polygon],\n        )\n\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/map_utils/utils.py",
    "content": "from shapely.geometry import LineString, box, Polygon, LinearRing\nfrom shapely.geometry.base import BaseGeometry\nfrom shapely import ops\nimport numpy as np\nfrom scipy.spatial import distance\nfrom typing import List, Optional, Tuple\nfrom numpy.typing import NDArray\n\ndef split_collections(geom: BaseGeometry) -> List[Optional[BaseGeometry]]:\n    ''' Split Multi-geoms to list and check is valid or is empty.\n        \n    Args:\n        geom (BaseGeometry): geoms to be split or validate.\n    \n    Returns:\n        geometries (List): list of geometries.\n    '''\n    assert geom.geom_type in ['MultiLineString', 'LineString', 'MultiPolygon', \n        'Polygon', 'GeometryCollection'], f\"got geom type {geom.geom_type}\"\n    if 'Multi' in geom.geom_type:\n        outs = []\n        for g in geom.geoms:\n            if g.is_valid and not g.is_empty:\n                outs.append(g)\n        return outs\n    else:\n        if geom.is_valid and not geom.is_empty:\n            return [geom,]\n        else:\n            return []\n\ndef get_drivable_area_contour(drivable_areas: List[Polygon], \n                              roi_size: Tuple) -> List[LineString]:\n    ''' Extract drivable area contours to get list of boundaries.\n\n    Args:\n        drivable_areas (list): list of drivable areas.\n        roi_size (tuple): bev range size\n    \n    Returns:\n        boundaries (List): list of boundaries.\n    '''\n    max_x = roi_size[0] / 2\n    max_y = roi_size[1] / 2\n\n    # a bit smaller than roi to avoid unexpected boundaries on edges\n    local_patch = box(-max_x + 0.2, -max_y + 0.2, max_x - 0.2, max_y - 0.2)\n    \n    exteriors = []\n    interiors = []\n    \n    for poly in drivable_areas:\n        exteriors.append(poly.exterior)\n        for inter in poly.interiors:\n            interiors.append(inter)\n    \n    results = []\n    for ext in exteriors:\n        # NOTE: we make sure all exteriors are clock-wise\n        # such that each boundary's right-hand-side is drivable area\n        # and left-hand-side is walk way\n        \n        if ext.is_ccw:\n            ext = LinearRing(list(ext.coords)[::-1])\n        lines = ext.intersection(local_patch)\n        if lines.geom_type == 'MultiLineString':\n            lines = ops.linemerge(lines)\n        assert lines.geom_type in ['MultiLineString', 'LineString']\n        \n        results.extend(split_collections(lines))\n\n    for inter in interiors:\n        # NOTE: we make sure all interiors are counter-clock-wise\n        if not inter.is_ccw:\n            inter = LinearRing(list(inter.coords)[::-1])\n        lines = inter.intersection(local_patch)\n        if lines.geom_type == 'MultiLineString':\n            lines = ops.linemerge(lines)\n        assert lines.geom_type in ['MultiLineString', 'LineString']\n        \n        results.extend(split_collections(lines))\n\n    return results\n\ndef get_ped_crossing_contour(polygon: Polygon, \n                             local_patch: box) -> Optional[LineString]:\n    ''' Extract ped crossing contours to get a closed polyline.\n    Different from `get_drivable_area_contour`, this function ensures a closed polyline.\n\n    Args:\n        polygon (Polygon): ped crossing polygon to be extracted.\n        local_patch (tuple): local patch params\n    \n    Returns:\n        line (LineString): a closed line\n    '''\n\n    ext = polygon.exterior\n    if not ext.is_ccw:\n        ext = LinearRing(list(ext.coords)[::-1])\n    lines = ext.intersection(local_patch)\n    if lines.type != 'LineString':\n        # remove points in intersection results\n        lines = [l for l in lines.geoms if l.geom_type != 'Point']\n        lines = ops.linemerge(lines)\n        \n        # same instance but not connected.\n        if lines.type != 'LineString':\n            ls = []\n            for l in lines.geoms:\n                ls.append(np.array(l.coords))\n            \n            lines = np.concatenate(ls, axis=0)\n            lines = LineString(lines)\n    if not lines.is_empty:\n        return lines\n    \n    return None\n\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/nuscenes_3d_dataset.py",
    "content": "import random\nimport math\nimport os\nfrom os import path as osp\nimport cv2\nimport tempfile\nimport copy\nimport prettytable\n\nimport numpy as np\nimport torch\nfrom torch.utils.data import Dataset\nimport pyquaternion\nfrom shapely.geometry import LineString\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.eval.detection.config import config_factory as det_configs\nfrom nuscenes.eval.common.config import config_factory as track_configs\n\nimport mmcv\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.pipelines import Compose\nfrom .utils import (\n    draw_lidar_bbox3d_on_img,\n    draw_lidar_bbox3d_on_bev,\n)\n\n\n@DATASETS.register_module()\nclass NuScenes3DDataset(Dataset):\n    DefaultAttribute = {\n        \"car\": \"vehicle.parked\",\n        \"pedestrian\": \"pedestrian.moving\",\n        \"trailer\": \"vehicle.parked\",\n        \"truck\": \"vehicle.parked\",\n        \"bus\": \"vehicle.moving\",\n        \"motorcycle\": \"cycle.without_rider\",\n        \"construction_vehicle\": \"vehicle.parked\",\n        \"bicycle\": \"cycle.without_rider\",\n        \"barrier\": \"\",\n        \"traffic_cone\": \"\",\n    }\n    ErrNameMapping = {\n        \"trans_err\": \"mATE\",\n        \"scale_err\": \"mASE\",\n        \"orient_err\": \"mAOE\",\n        \"vel_err\": \"mAVE\",\n        \"attr_err\": \"mAAE\",\n    }\n    CLASSES = (\n        \"car\",\n        \"truck\",\n        \"trailer\",\n        \"bus\",\n        \"construction_vehicle\",\n        \"bicycle\",\n        \"motorcycle\",\n        \"pedestrian\",\n        \"traffic_cone\",\n        \"barrier\",\n    )\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    ID_COLOR_MAP = [\n        (59, 59, 238),\n        (0, 255, 0),\n        (0, 0, 255),\n        (255, 255, 0),\n        (0, 255, 255),\n        (255, 0, 255),\n        (255, 255, 255),\n        (0, 127, 255),\n        (71, 130, 255),\n        (127, 127, 0),\n    ]\n\n    def __init__(\n        self,\n        ann_file,\n        pipeline=None,\n        data_root=None,\n        classes=None,\n        map_classes=None,\n        load_interval=1,\n        with_velocity=True,\n        modality=None,\n        test_mode=False,\n        det3d_eval_version=\"detection_cvpr_2019\",\n        track3d_eval_version=\"tracking_nips_2019\",\n        version=\"v1.0-trainval\",\n        use_valid_flag=False,\n        vis_score_threshold=0.25,\n        data_aug_conf=None,\n        sequences_split_num=1,\n        with_seq_flag=False,\n        keep_consistent_seq_aug=True,\n        work_dir=None,\n        eval_config=None,\n    ):\n        self.version = version\n        self.load_interval = load_interval\n        self.use_valid_flag = use_valid_flag\n        super().__init__()\n        self.data_root = data_root\n        self.ann_file = ann_file\n        self.test_mode = test_mode\n        self.modality = modality\n        self.box_mode_3d = 0\n\n        if classes is not None:\n            self.CLASSES = classes\n        if map_classes is not None: \n            self.MAP_CLASSES = map_classes\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if pipeline is not None:\n            self.pipeline = Compose(pipeline)\n\n        self.with_velocity = with_velocity\n        self.det3d_eval_version = det3d_eval_version\n        self.det3d_eval_configs = det_configs(self.det3d_eval_version)\n        self.det3d_eval_configs.class_names = list(self.det3d_eval_configs.class_range.keys())\n        self.track3d_eval_version = track3d_eval_version\n        self.track3d_eval_configs = track_configs(self.track3d_eval_version)\n        self.track3d_eval_configs.class_names = list(self.track3d_eval_configs.class_range.keys())\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n        self.vis_score_threshold = vis_score_threshold\n\n        self.data_aug_conf = data_aug_conf\n        self.sequences_split_num = sequences_split_num\n        self.keep_consistent_seq_aug = keep_consistent_seq_aug\n        if with_seq_flag:\n            self._set_sequence_group_flag()\n        \n        self.work_dir = work_dir\n        self.eval_config = eval_config\n\n    def __len__(self):\n        return len(self.data_infos)\n\n    def _set_sequence_group_flag(self):\n        \"\"\"\n        Set each sequence to be a different group\n        \"\"\"\n        if self.sequences_split_num == -1:\n            self.flag = np.arange(len(self.data_infos))\n            return\n        \n        res = []\n\n        curr_sequence = 0\n        for idx in range(len(self.data_infos)):\n            if idx != 0 and len(self.data_infos[idx][\"sweeps\"]) == 0:\n                # Not first frame and # of sweeps is 0 -> new sequence\n                curr_sequence += 1\n            res.append(curr_sequence)\n\n        self.flag = np.array(res, dtype=np.int64)\n\n        if self.sequences_split_num != 1:\n            if self.sequences_split_num == \"all\":\n                self.flag = np.array(\n                    range(len(self.data_infos)), dtype=np.int64\n                )\n            else:\n                bin_counts = np.bincount(self.flag)\n                new_flags = []\n                curr_new_flag = 0\n                for curr_flag in range(len(bin_counts)):\n                    curr_sequence_length = np.array(\n                        list(\n                            range(\n                                0,\n                                bin_counts[curr_flag],\n                                math.ceil(\n                                    bin_counts[curr_flag]\n                                    / self.sequences_split_num\n                                ),\n                            )\n                        )\n                        + [bin_counts[curr_flag]]\n                    )\n\n                    for sub_seq_idx in (\n                        curr_sequence_length[1:] - curr_sequence_length[:-1]\n                    ):\n                        for _ in range(sub_seq_idx):\n                            new_flags.append(curr_new_flag)\n                        curr_new_flag += 1\n\n                assert len(new_flags) == len(self.flag)\n                assert (\n                    len(np.bincount(new_flags))\n                    == len(np.bincount(self.flag)) * self.sequences_split_num\n                )\n                self.flag = np.array(new_flags, dtype=np.int64)\n\n    def get_augmentation(self):\n        if self.data_aug_conf is None:\n            return None\n        H, W = self.data_aug_conf[\"H\"], self.data_aug_conf[\"W\"]\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        if not self.test_mode:\n            resize = np.random.uniform(*self.data_aug_conf[\"resize_lim\"])\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int(\n                    (1 - np.random.uniform(*self.data_aug_conf[\"bot_pct_lim\"]))\n                    * newH\n                )\n                - fH\n            )\n            crop_w = int(np.random.uniform(0, max(0, newW - fW)))\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            if self.data_aug_conf[\"rand_flip\"] and np.random.choice([0, 1]):\n                flip = True\n            rotate = np.random.uniform(*self.data_aug_conf[\"rot_lim\"])\n            rotate_3d = np.random.uniform(*self.data_aug_conf[\"rot3d_range\"])\n        else:\n            resize = max(fH / H, fW / W)\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n                - fH\n            )\n            crop_w = int(max(0, newW - fW) / 2)\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            rotate = 0\n            rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def __getitem__(self, idx):\n        if isinstance(idx, dict):\n            aug_config = idx[\"aug_config\"]\n            idx = idx[\"idx\"]\n        else:\n            aug_config = self.get_augmentation()\n        data = self.get_data_info(idx)\n        data[\"aug_config\"] = aug_config\n        data = self.pipeline(data)\n        return data\n\n    def get_cat_ids(self, idx):\n        info = self.data_infos[idx]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n            gt_names = set(info[\"gt_names\"][mask])\n        else:\n            gt_names = set(info[\"gt_names\"])\n\n        cat_ids = []\n        for name in gt_names:\n            if name in self.CLASSES:\n                cat_ids.append(self.cat2id[name])\n        return cat_ids\n\n    def load_annotations(self, ann_file):\n        data = mmcv.load(ann_file, file_format=\"pkl\")\n        data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\n        data_infos = data_infos[:: self.load_interval]\n        self.metadata = data[\"metadata\"]\n        self.version = self.metadata[\"version\"]\n        print(self.metadata)\n        return data_infos\n    \n    def anno2geom(self, annos):\n        map_geoms = {}\n        for label, anno_list in annos.items():\n            map_geoms[label] = []\n            for anno in anno_list:\n                geom = LineString(anno)\n                map_geoms[label].append(geom)\n        return map_geoms\n    \n    def get_data_info(self, index):\n        info = self.data_infos[index]\n        input_dict = dict(\n            token=info[\"token\"],\n            map_location=info[\"map_location\"],\n            pts_filename=info[\"lidar_path\"],\n            sweeps=info[\"sweeps\"],\n            timestamp=info[\"timestamp\"] / 1e6,\n            lidar2ego_translation=info[\"lidar2ego_translation\"],\n            lidar2ego_rotation=info[\"lidar2ego_rotation\"],\n            ego2global_translation=info[\"ego2global_translation\"],\n            ego2global_rotation=info[\"ego2global_rotation\"],\n            ego_status=info['ego_status'].astype(np.float32),\n            map_infos=info[\"map_annos\"],\n        )\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = pyquaternion.Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = pyquaternion.Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        input_dict[\"lidar2global\"] = ego2global @ lidar2ego\n\n        map_geoms = self.anno2geom(info[\"map_annos\"])\n        input_dict[\"map_geoms\"] = map_geoms\n\n        if self.modality[\"use_camera\"]:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsic = []\n            for cam_type, cam_info in info[\"cams\"].items():\n                image_paths.append(cam_info[\"data_path\"])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info[\"sensor2lidar_rotation\"])\n                lidar2cam_t = (\n                    cam_info[\"sensor2lidar_translation\"] @ lidar2cam_r.T\n                )\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = copy.deepcopy(cam_info[\"cam_intrinsic\"])\n                cam_intrinsic.append(intrinsic)\n                viewpad = np.eye(4)\n                viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = viewpad @ lidar2cam_rt.T\n                lidar2img_rts.append(lidar2img_rt)\n                lidar2cam_rts.append(lidar2cam_rt)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    lidar2cam=lidar2cam_rts,\n                    cam_intrinsic=cam_intrinsic,\n                )\n            )\n\n        annos = self.get_ann_info(index)\n        input_dict.update(annos)\n        return input_dict\n\n    def get_ann_info(self, index):\n        info = self.data_infos[index]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n        else:\n            mask = info[\"num_lidar_pts\"] > 0\n        gt_bboxes_3d = info[\"gt_boxes\"][mask]\n        gt_names_3d = info[\"gt_names\"][mask]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info[\"gt_velocity\"][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n        )\n        if \"instance_inds\" in info:\n            instance_inds = np.array(info[\"instance_inds\"], dtype=np.int)[mask]\n            anns_results[\"instance_inds\"] = instance_inds\n            \n        if 'gt_agent_fut_trajs' in info:\n            anns_results['gt_agent_fut_trajs'] = info['gt_agent_fut_trajs'][mask]\n            anns_results['gt_agent_fut_masks'] = info['gt_agent_fut_masks'][mask]\n\n        if 'gt_ego_fut_trajs' in info:\n            anns_results['gt_ego_fut_trajs'] = info['gt_ego_fut_trajs']\n            anns_results['gt_ego_fut_masks'] = info['gt_ego_fut_masks']\n            anns_results['gt_ego_fut_cmd'] = info['gt_ego_fut_cmd']\n        \n            ## get future box for planning eval\n            fut_ts = int(info['gt_ego_fut_masks'].sum())\n            fut_boxes = []\n            cur_scene_token = info[\"scene_token\"]\n            cur_T_global = get_T_global(info)\n            for i in range(1, fut_ts + 1):\n                fut_info = self.data_infos[index + i]\n                fut_scene_token = fut_info[\"scene_token\"]\n                if cur_scene_token != fut_scene_token:\n                    break\n                if self.use_valid_flag:\n                    mask = fut_info[\"valid_flag\"]\n                else:\n                    mask = fut_info[\"num_lidar_pts\"] > 0\n\n                fut_gt_bboxes_3d = fut_info[\"gt_boxes\"][mask]\n                \n                fut_T_global = get_T_global(fut_info)\n                T_fut2cur = np.linalg.inv(cur_T_global) @ fut_T_global\n\n                center = fut_gt_bboxes_3d[:, :3] @ T_fut2cur[:3, :3].T + T_fut2cur[:3, 3]\n                yaw = np.stack([np.cos(fut_gt_bboxes_3d[:, 6]), np.sin(fut_gt_bboxes_3d[:, 6])], axis=-1)\n                yaw = yaw @ T_fut2cur[:2, :2].T\n                yaw = np.arctan2(yaw[..., 1], yaw[..., 0])\n\n                fut_gt_bboxes_3d[:, :3] = center\n                fut_gt_bboxes_3d[:, 6] = yaw\n                fut_boxes.append(fut_gt_bboxes_3d)\n\n            anns_results['fut_boxes'] = fut_boxes\n        \n        return anns_results\n\n    def _format_bbox(self, results, jsonfile_prefix=None, tracking=False):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det, threshold=self.tracking_threshold if tracking else None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n            )\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, \"results_nusc.json\")\n        print(\"Results writes to\", res_path)\n        mmcv.dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(\n        self, result_path, logger=None, result_name=\"img_bbox\", tracking=False\n    ):\n        from nuscenes import NuScenes\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False\n        )\n        eval_set_map = {\n            \"v1.0-mini\": \"mini_val\",\n            \"v1.0-trainval\": \"val\",\n        }\n        if not tracking:\n            from nuscenes.eval.detection.evaluate import NuScenesEval\n\n            nusc_eval = NuScenesEval(\n                nusc,\n                config=self.det3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n            )\n            nusc_eval.main(render_curves=False)\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            for name in self.CLASSES:\n                for k, v in metrics[\"label_aps\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}_AP_dist_{}\".format(metric_prefix, name, k)\n                    ] = val\n                for k, v in metrics[\"label_tp_errors\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\"{}/{}_{}\".format(metric_prefix, name, k)] = val\n                for k, v in metrics[\"tp_errors\"].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}\".format(metric_prefix, self.ErrNameMapping[k])\n                    ] = val\n\n            detail[\"{}/NDS\".format(metric_prefix)] = metrics[\"nd_score\"]\n            detail[\"{}/mAP\".format(metric_prefix)] = metrics[\"mean_ap\"]\n        else:\n            from nuscenes.eval.tracking.evaluate import TrackingEval\n\n            nusc_eval = TrackingEval(\n                config=self.track3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n                nusc_version=self.version,\n                nusc_dataroot=self.data_root,\n            )\n            metrics = nusc_eval.main()\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            print(metrics)\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            keys = [\n                \"amota\",\n                \"amotp\",\n                \"recall\",\n                \"motar\",\n                \"gt\",\n                \"mota\",\n                \"motp\",\n                \"mt\",\n                \"ml\",\n                \"faf\",\n                \"tp\",\n                \"fp\",\n                \"fn\",\n                \"ids\",\n                \"frag\",\n                \"tid\",\n                \"lgd\",\n            ]\n            for key in keys:\n                detail[\"{}/{}\".format(metric_prefix, key)] = metrics[key]\n\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None, tracking=False):\n        assert isinstance(results, list), \"results must be a list\"\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, \"results\")\n        else:\n            tmp_dir = None\n\n        if not (\"pts_bbox\" in results[0] or \"img_bbox\" in results[0]):\n            result_files = self._format_bbox(\n                results, jsonfile_prefix, tracking=tracking\n            )\n        else:\n            result_files = dict()\n            for name in results[0]:\n                print(f\"\\nFormating bboxes of {name}\")\n                results_ = [out[name] for out in results]\n                tmp_file_ = jsonfile_prefix\n                result_files.update(\n                    {\n                        name: self._format_bbox(\n                            results_, tmp_file_, tracking=tracking\n                        )\n                    }\n                )\n        return result_files, tmp_dir\n\n    def format_map_results(self, results, prefix=None):\n        submissions = {'results': {},}\n        \n        for j, pred in enumerate(results):\n            '''\n            For each case, the result should be formatted as Dict{'vectors': [], 'scores': [], 'labels': []}\n            'vectors': List of vector, each vector is a array([[x1, y1], [x2, y2] ...]),\n                contain all vectors predicted in this sample.\n            'scores: List of score(float), \n                contain scores of all instances in this sample.\n            'labels': List of label(int), \n                contain labels of all instances in this sample.\n            '''\n            if pred is None: # empty prediction\n                continue\n            pred = pred['img_bbox']\n\n            single_case = {'vectors': [], 'scores': [], 'labels': []}\n            token = self.data_infos[j]['token']\n            for i in range(len(pred['scores'])):\n                score = pred['scores'][i]\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n\n                # A line should have >=2 points\n                if len(vector) < 2:\n                    continue\n                \n                single_case['vectors'].append(vector)\n                single_case['scores'].append(score)\n                single_case['labels'].append(label)\n            \n            submissions['results'][token] = single_case\n        \n        out_path = osp.join(prefix, 'submission_vector.json')\n        print(f'saving submissions results to {out_path}')\n        os.makedirs(os.path.dirname(out_path), exist_ok=True)\n        mmcv.dump(submissions, out_path)\n        return out_path\n\n    def format_motion_results(self, results, jsonfile_prefix=None, tracking=False, thresh=None):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det['img_bbox'], threshold=None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n                filter_with_cls_range=False,\n            )\n            for i, box in enumerate(boxes):\n                if thresh is not None and box.score < thresh:\n                    continue\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n                nusc_anno.update(\n                    dict(\n                        trajs=det['img_bbox']['trajs_3d'][i].numpy(),\n                    )\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        return nusc_submissions \n\n    def _evaluate_single_motion(self,\n                         results,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        from .evaluation.motion.motion_eval_uniad import NuScenesEval as NuScenesEvalMotion\n\n        output_dir = result_path\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        nusc_eval = NuScenesEvalMotion(\n            nusc,\n            config=copy.deepcopy(self.det3d_eval_configs),\n            result_path=results,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False,\n            seconds=6)\n        metrics = nusc_eval.main(render_curves=False)\n        \n        MOTION_METRICS = ['EPA', 'min_ade_err', 'min_fde_err', 'miss_rate_err']\n        class_names = ['car', 'pedestrian']\n\n        table = prettytable.PrettyTable()\n        table.field_names = [\"class names\"] + MOTION_METRICS\n        for class_name in class_names:\n            row_data = [class_name]\n            for m in MOTION_METRICS:\n                row_data.append('%.4f' % metrics[f'{class_name}_{m}'])\n            table.add_row(row_data)\n        print_log('\\n'+str(table), logger=logger)\n        return metrics\n\n    def evaluate(\n        self,\n        results,\n        eval_mode,\n        metric=None,\n        logger=None,\n        jsonfile_prefix=None,\n        result_names=[\"img_bbox\"],\n        show=False,\n        out_dir=None,\n        pipeline=None,\n    ):\n        res_path = \"results.pkl\" if \"trainval\" in self.version else \"results_mini.pkl\"\n        res_path = osp.join(self.work_dir, res_path)\n        print('All Results write to', res_path)\n        mmcv.dump(results, res_path)\n\n        results_dict = dict()\n        if eval_mode['with_det']:\n            self.tracking = eval_mode[\"with_tracking\"]\n            self.tracking_threshold = eval_mode[\"tracking_threshold\"]\n            for metric in [\"detection\", \"tracking\"]:\n                tracking = metric == \"tracking\"\n                if tracking and not self.tracking:\n                    continue\n                result_files, tmp_dir = self.format_results(\n                    results, jsonfile_prefix=self.work_dir, tracking=tracking\n                )\n\n                if isinstance(result_files, dict):\n                    for name in result_names:\n                        ret_dict = self._evaluate_single(\n                            result_files[name], tracking=tracking\n                        )\n                    results_dict.update(ret_dict)\n                elif isinstance(result_files, str):\n                    ret_dict = self._evaluate_single(\n                        result_files, tracking=tracking\n                    )\n                    results_dict.update(ret_dict)\n\n                if tmp_dir is not None:\n                    tmp_dir.cleanup()\n\n        if eval_mode['with_map']:\n            from .evaluation.map.vector_eval import VectorEvaluate\n            self.map_evaluator = VectorEvaluate(self.eval_config)\n            result_path = self.format_map_results(results, prefix=self.work_dir)\n            map_results_dict = self.map_evaluator.evaluate(result_path, logger=logger)\n            results_dict.update(map_results_dict)\n\n        if eval_mode['with_motion']:\n            thresh = eval_mode[\"motion_threshhold\"]\n            result_files = self.format_motion_results(results, jsonfile_prefix=self.work_dir, thresh=thresh)\n            motion_results_dict = self._evaluate_single_motion(result_files, self.work_dir, logger=logger)\n            results_dict.update(motion_results_dict)\n        \n        if eval_mode['with_planning']:\n            from .evaluation.planning.planning_eval import planning_eval\n            planning_results_dict = planning_eval(results, self.eval_config, logger=logger)\n            results_dict.update(planning_results_dict)\n\n        if show or out_dir:\n            self.show(results, save_dir=out_dir, show=show, pipeline=pipeline)\n        \n        # print main metrics for recording\n        metric_str = '\\n'\n        if \"img_bbox_NuScenes/NDS\" in results_dict:\n            metric_str += f'mAP: {results_dict.get(\"img_bbox_NuScenes/mAP\"):.4f}\\n'\n            metric_str += f'mATE: {results_dict.get(\"img_bbox_NuScenes/mATE\"):.4f}\\n'\n            metric_str += f'mASE: {results_dict.get(\"img_bbox_NuScenes/mASE\"):.4f}\\n'\n            metric_str += f'mAOE: {results_dict.get(\"img_bbox_NuScenes/mAOE\"):.4f}\\n' \n            metric_str += f'mAVE: {results_dict.get(\"img_bbox_NuScenes/mAVE\"):.4f}\\n' \n            metric_str += f'mAAE: {results_dict.get(\"img_bbox_NuScenes/mAAE\"):.4f}\\n' \n            metric_str += f'NDS: {results_dict.get(\"img_bbox_NuScenes/NDS\"):.4f}\\n\\n'\n        \n        if \"img_bbox_NuScenes/amota\" in results_dict:\n            metric_str += f'AMOTA: {results_dict[\"img_bbox_NuScenes/amota\"]:.4f}\\n' \n            metric_str += f'AMOTP: {results_dict[\"img_bbox_NuScenes/amotp\"]:.4f}\\n' \n            metric_str += f'RECALL: {results_dict[\"img_bbox_NuScenes/recall\"]:.4f}\\n' \n            metric_str += f'MOTAR: {results_dict[\"img_bbox_NuScenes/motar\"]:.4f}\\n' \n            metric_str += f'MOTA: {results_dict[\"img_bbox_NuScenes/mota\"]:.4f}\\n' \n            metric_str += f'MOTP: {results_dict[\"img_bbox_NuScenes/motp\"]:.4f}\\n' \n            metric_str += f'IDS: {results_dict[\"img_bbox_NuScenes/ids\"]}\\n\\n' \n        \n        if \"mAP_normal\" in results_dict:\n            metric_str += f'ped_crossing= {results_dict[\"ped_crossing\"]:.4f}\\n' \n            metric_str += f'divider= {results_dict[\"divider\"]:.4f}\\n' \n            metric_str += f'boundary= {results_dict[\"boundary\"]:.4f}\\n' \n            metric_str += f'mAP_normal= {results_dict[\"mAP_normal\"]:.4f}\\n\\n' \n\n        if \"car_EPA\" in results_dict:\n            metric_str += f'Car / Ped\\n' \n            metric_str += f'epa= {results_dict[\"car_EPA\"]:.4f} / {results_dict[\"pedestrian_EPA\"]:.4f}\\n'\n            metric_str += f'ade= {results_dict[\"car_min_ade_err\"]:.4f} / {results_dict[\"pedestrian_min_ade_err\"]:.4f}\\n'\n            metric_str += f'fde= {results_dict[\"car_min_fde_err\"]:.4f} / {results_dict[\"pedestrian_min_fde_err\"]:.4f}\\n'\n            metric_str += f'mr= {results_dict[\"car_miss_rate_err\"]:.4f} / {results_dict[\"pedestrian_miss_rate_err\"]:.4f}\\n\\n' \n\n        if \"L2\" in results_dict:\n            metric_str += f'obj_box_col: {(results_dict[\"obj_box_col\"]*100):.3f}%\\n'\n            metric_str += f'L2: {results_dict[\"L2\"]:.4f}\\n\\n'\n        \n        print_log(metric_str, logger=logger)\n        return results_dict\n\n    def show(self, results, save_dir=None, show=False, pipeline=None):\n        save_dir = \"./\" if save_dir is None else save_dir\n        save_dir = os.path.join(save_dir, \"visual\")\n        print_log(os.path.abspath(save_dir))\n        pipeline = Compose(pipeline)\n        if not os.path.exists(save_dir):\n            os.makedirs(save_dir)\n\n        fourcc = cv2.VideoWriter_fourcc(*\"MJPG\")\n        videoWriter = None\n\n        for i, result in enumerate(results):\n            if \"img_bbox\" in result.keys():\n                result = result[\"img_bbox\"]\n            data_info = pipeline(self.get_data_info(i))\n            imgs = []\n\n            raw_imgs = data_info[\"img\"]\n            lidar2img = data_info[\"img_metas\"].data[\"lidar2img\"]\n            pred_bboxes_3d = result[\"boxes_3d\"][\n                result[\"scores_3d\"] > self.vis_score_threshold\n            ]\n            if \"instance_ids\" in result and self.tracking:\n                color = []\n                for id in result[\"instance_ids\"].cpu().numpy().tolist():\n                    color.append(\n                        self.ID_COLOR_MAP[int(id % len(self.ID_COLOR_MAP))]\n                    )\n            elif \"labels_3d\" in result:\n                color = []\n                for id in result[\"labels_3d\"].cpu().numpy().tolist():\n                    color.append(self.ID_COLOR_MAP[id])\n            else:\n                color = (255, 0, 0)\n\n            # ===== draw boxes_3d to images =====\n            for j, img_origin in enumerate(raw_imgs):\n                img = img_origin.copy()\n                if len(pred_bboxes_3d) != 0:\n                    img = draw_lidar_bbox3d_on_img(\n                        pred_bboxes_3d,\n                        img,\n                        lidar2img[j],\n                        img_metas=None,\n                        color=color,\n                        thickness=3,\n                    )\n                imgs.append(img)\n\n            # ===== draw boxes_3d to BEV =====\n            bev = draw_lidar_bbox3d_on_bev(\n                pred_bboxes_3d,\n                bev_size=img.shape[0] * 2,\n                color=color,\n            )\n\n            # ===== put text and concat =====\n            for j, name in enumerate(\n                [\n                    \"front\",\n                    \"front right\",\n                    \"front left\",\n                    \"rear\",\n                    \"rear left\",\n                    \"rear right\",\n                ]\n            ):\n                imgs[j] = cv2.rectangle(\n                    imgs[j],\n                    (0, 0),\n                    (440, 80),\n                    color=(255, 255, 255),\n                    thickness=-1,\n                )\n                w, h = cv2.getTextSize(name, cv2.FONT_HERSHEY_SIMPLEX, 2, 2)[0]\n                text_x = int(220 - w / 2)\n                text_y = int(40 + h / 2)\n\n                imgs[j] = cv2.putText(\n                    imgs[j],\n                    name,\n                    (text_x, text_y),\n                    cv2.FONT_HERSHEY_SIMPLEX,\n                    2,\n                    (0, 0, 0),\n                    2,\n                    cv2.LINE_AA,\n                )\n            image = np.concatenate(\n                [\n                    np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n                    np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n                ],\n                axis=0,\n            )\n            image = np.concatenate([image, bev], axis=1)\n\n            # ===== save video =====\n            if videoWriter is None:\n                videoWriter = cv2.VideoWriter(\n                    os.path.join(save_dir, \"video.avi\"),\n                    fourcc,\n                    7,\n                    image.shape[:2][::-1],\n                )\n            cv2.imwrite(os.path.join(save_dir, f\"{i}.jpg\"), image)\n            videoWriter.write(image)\n        videoWriter.release()\n\n\ndef output_to_nusc_box(detection, threshold=None):\n    box3d = detection[\"boxes_3d\"]\n    scores = detection[\"scores_3d\"].numpy()\n    labels = detection[\"labels_3d\"].numpy()\n    if \"instance_ids\" in detection:\n        ids = detection[\"instance_ids\"]  # .numpy()\n    if threshold is not None:\n        if \"cls_scores\" in detection:\n            mask = detection[\"cls_scores\"].numpy() >= threshold\n        else:\n            mask = scores >= threshold\n        box3d = box3d[mask]\n        scores = scores[mask]\n        labels = labels[mask]\n        ids = ids[mask]\n\n    if hasattr(box3d, \"gravity_center\"):\n        box_gravity_center = box3d.gravity_center.numpy()\n        box_dims = box3d.dims.numpy()\n        nus_box_dims = box_dims[:, [1, 0, 2]]\n        box_yaw = box3d.yaw.numpy()\n    else:\n        box3d = box3d.numpy()\n        box_gravity_center = box3d[..., :3].copy()\n        box_dims = box3d[..., 3:6].copy()\n        nus_box_dims = box_dims[..., [1, 0, 2]]\n        box_yaw = box3d[..., 6].copy()\n\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    # box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        if hasattr(box3d, \"gravity_center\"):\n            velocity = (*box3d.tensor[i, 7:9], 0.0)\n        else:\n            velocity = (*box3d[i, 7:9], 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            nus_box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity,\n        )\n        if \"instance_ids\" in detection:\n            box.token = ids[i]\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(\n    info,\n    boxes,\n    classes,\n    eval_configs,\n    eval_version=\"detection_cvpr_2019\",\n    filter_with_cls_range=True,\n):\n    box_list = []\n    for i, box in enumerate(boxes):\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info[\"lidar2ego_rotation\"]))\n        box.translate(np.array(info[\"lidar2ego_translation\"]))\n        # filter det in ego.\n        if filter_with_cls_range:\n            cls_range_map = eval_configs.class_range\n            radius = np.linalg.norm(box.center[:2], 2)\n            det_range = cls_range_map[classes[box.label]]\n            if radius > det_range:\n                continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info[\"ego2global_rotation\"]))\n        box.translate(np.array(info[\"ego2global_translation\"]))\n        box_list.append(box)\n    return box_list\n\n\ndef get_T_global(info):\n    lidar2ego = np.eye(4)\n    lidar2ego[:3, :3] = pyquaternion.Quaternion(\n        info[\"lidar2ego_rotation\"]\n    ).rotation_matrix\n    lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n    ego2global = np.eye(4)\n    ego2global[:3, :3] = pyquaternion.Quaternion(\n        info[\"ego2global_rotation\"]\n    ).rotation_matrix\n    ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n    return ego2global @ lidar2ego"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/nuscenes_3d_dataset_roboAD.py",
    "content": "import random\nimport math\nimport os\nfrom os import path as osp\nimport cv2\nimport tempfile\nimport copy\nimport prettytable\n\nimport numpy as np\nimport torch\nfrom torch.utils.data import Dataset\nimport pyquaternion\nfrom shapely.geometry import LineString\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.eval.detection.config import config_factory as det_configs\nfrom nuscenes.eval.common.config import config_factory as track_configs\n\nimport mmcv\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.pipelines import Compose\nfrom .utils import (\n    draw_lidar_bbox3d_on_img,\n    draw_lidar_bbox3d_on_bev,\n)\n\n\n@DATASETS.register_module()\nclass NuScenes3DDataset_roboAD(Dataset):\n    DefaultAttribute = {\n        \"car\": \"vehicle.parked\",\n        \"pedestrian\": \"pedestrian.moving\",\n        \"trailer\": \"vehicle.parked\",\n        \"truck\": \"vehicle.parked\",\n        \"bus\": \"vehicle.moving\",\n        \"motorcycle\": \"cycle.without_rider\",\n        \"construction_vehicle\": \"vehicle.parked\",\n        \"bicycle\": \"cycle.without_rider\",\n        \"barrier\": \"\",\n        \"traffic_cone\": \"\",\n    }\n    ErrNameMapping = {\n        \"trans_err\": \"mATE\",\n        \"scale_err\": \"mASE\",\n        \"orient_err\": \"mAOE\",\n        \"vel_err\": \"mAVE\",\n        \"attr_err\": \"mAAE\",\n    }\n    CLASSES = (\n        \"car\",\n        \"truck\",\n        \"trailer\",\n        \"bus\",\n        \"construction_vehicle\",\n        \"bicycle\",\n        \"motorcycle\",\n        \"pedestrian\",\n        \"traffic_cone\",\n        \"barrier\",\n    )\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    ID_COLOR_MAP = [\n        (59, 59, 238),\n        (0, 255, 0),\n        (0, 0, 255),\n        (255, 255, 0),\n        (0, 255, 255),\n        (255, 0, 255),\n        (255, 255, 255),\n        (0, 127, 255),\n        (71, 130, 255),\n        (127, 127, 0),\n    ]\n\n    def __init__(\n        self,\n        ann_file,\n        pipeline=None,\n        data_root=None,\n        classes=None,\n        map_classes=None,\n        load_interval=1,\n        with_velocity=True,\n        modality=None,\n        test_mode=False,\n        det3d_eval_version=\"detection_cvpr_2019\",\n        track3d_eval_version=\"tracking_nips_2019\",\n        version=\"v1.0-trainval\",\n        use_valid_flag=False,\n        vis_score_threshold=0.25,\n        data_aug_conf=None,\n        sequences_split_num=1,\n        with_seq_flag=False,\n        keep_consistent_seq_aug=True,\n        work_dir=None,\n        eval_config=None,\n    ):\n        self.version = version\n        self.load_interval = load_interval\n        self.use_valid_flag = use_valid_flag\n        super().__init__()\n        self.data_root = data_root\n        self.ann_file = ann_file\n        self.test_mode = test_mode\n        self.modality = modality\n        self.box_mode_3d = 0\n\n        if classes is not None:\n            self.CLASSES = classes\n        if map_classes is not None: \n            self.MAP_CLASSES = map_classes\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if pipeline is not None:\n            self.pipeline = Compose(pipeline)\n\n        self.with_velocity = with_velocity\n        self.det3d_eval_version = det3d_eval_version\n        self.det3d_eval_configs = det_configs(self.det3d_eval_version)\n        self.det3d_eval_configs.class_names = list(self.det3d_eval_configs.class_range.keys())\n        self.track3d_eval_version = track3d_eval_version\n        self.track3d_eval_configs = track_configs(self.track3d_eval_version)\n        self.track3d_eval_configs.class_names = list(self.track3d_eval_configs.class_range.keys())\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n        self.vis_score_threshold = vis_score_threshold\n\n        self.data_aug_conf = data_aug_conf\n        self.sequences_split_num = sequences_split_num\n        self.keep_consistent_seq_aug = keep_consistent_seq_aug\n        if with_seq_flag:\n            self._set_sequence_group_flag()\n        \n        self.work_dir = work_dir\n        #import pdb;pdb.set_trace()\n        self.eval_config = eval_config\n\n    def __len__(self):\n        return len(self.data_infos)\n\n    def _set_sequence_group_flag(self):\n        \"\"\"\n        Set each sequence to be a different group\n        \"\"\"\n        if self.sequences_split_num == -1:\n            self.flag = np.arange(len(self.data_infos))\n            return\n        \n        res = []\n\n        curr_sequence = 0\n        for idx in range(len(self.data_infos)):\n            if idx != 0 and len(self.data_infos[idx][\"sweeps\"]) == 0:\n                # Not first frame and # of sweeps is 0 -> new sequence\n                curr_sequence += 1\n            res.append(curr_sequence)\n\n        self.flag = np.array(res, dtype=np.int64)\n\n        if self.sequences_split_num != 1:\n            if self.sequences_split_num == \"all\":\n                self.flag = np.array(\n                    range(len(self.data_infos)), dtype=np.int64\n                )\n            else:\n                bin_counts = np.bincount(self.flag)\n                new_flags = []\n                curr_new_flag = 0\n                for curr_flag in range(len(bin_counts)):\n                    curr_sequence_length = np.array(\n                        list(\n                            range(\n                                0,\n                                bin_counts[curr_flag],\n                                math.ceil(\n                                    bin_counts[curr_flag]\n                                    / self.sequences_split_num\n                                ),\n                            )\n                        )\n                        + [bin_counts[curr_flag]]\n                    )\n\n                    for sub_seq_idx in (\n                        curr_sequence_length[1:] - curr_sequence_length[:-1]\n                    ):\n                        for _ in range(sub_seq_idx):\n                            new_flags.append(curr_new_flag)\n                        curr_new_flag += 1\n\n                assert len(new_flags) == len(self.flag)\n                assert (\n                    len(np.bincount(new_flags))\n                    == len(np.bincount(self.flag)) * self.sequences_split_num\n                )\n                self.flag = np.array(new_flags, dtype=np.int64)\n\n    def get_augmentation(self):\n        if self.data_aug_conf is None:\n            return None\n        H, W = self.data_aug_conf[\"H\"], self.data_aug_conf[\"W\"]\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        if not self.test_mode:\n            resize = np.random.uniform(*self.data_aug_conf[\"resize_lim\"])\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int(\n                    (1 - np.random.uniform(*self.data_aug_conf[\"bot_pct_lim\"]))\n                    * newH\n                )\n                - fH\n            )\n            crop_w = int(np.random.uniform(0, max(0, newW - fW)))\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            if self.data_aug_conf[\"rand_flip\"] and np.random.choice([0, 1]):\n                flip = True\n            rotate = np.random.uniform(*self.data_aug_conf[\"rot_lim\"])\n            rotate_3d = np.random.uniform(*self.data_aug_conf[\"rot3d_range\"])\n        else:\n            resize = max(fH / H, fW / W)\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n                - fH\n            )\n            crop_w = int(max(0, newW - fW) / 2)\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            rotate = 0\n            rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def __getitem__(self, idx):\n        if isinstance(idx, dict):\n            aug_config = idx[\"aug_config\"]\n            idx = idx[\"idx\"]\n        else:\n            aug_config = self.get_augmentation()\n        data = self.get_data_info(idx)\n        data[\"aug_config\"] = aug_config\n        #import pdb; pdb.set_trace()\n        data = self.pipeline(data)\n        return data\n\n    def get_cat_ids(self, idx):\n        info = self.data_infos[idx]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n            gt_names = set(info[\"gt_names\"][mask])\n        else:\n            gt_names = set(info[\"gt_names\"])\n\n        cat_ids = []\n        for name in gt_names:\n            if name in self.CLASSES:\n                cat_ids.append(self.cat2id[name])\n        return cat_ids\n\n    def load_annotations(self, ann_file):\n        data = mmcv.load(ann_file, file_format=\"pkl\")\n        data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\n        data_infos = data_infos[:: self.load_interval]\n        # import pdb; pdb.set_trace()\n        self.metadata = data[\"metadata\"]\n        self.version = self.metadata[\"version\"]\n        print(self.metadata)\n        return data_infos\n    \n    def anno2geom(self, annos):\n        map_geoms = {}\n        for label, anno_list in annos.items():\n            map_geoms[label] = []\n            for anno in anno_list:\n                geom = LineString(anno)\n                map_geoms[label].append(geom)\n        return map_geoms\n    \n    def get_data_info(self, index):\n        info = self.data_infos[index]\n        input_dict = dict(\n            token=info[\"token\"],\n            map_location=info[\"map_location\"],\n            pts_filename=info[\"lidar_path\"],\n            sweeps=info[\"sweeps\"],\n            timestamp=info[\"timestamp\"] / 1e6,\n            lidar2ego_translation=info[\"lidar2ego_translation\"],\n            lidar2ego_rotation=info[\"lidar2ego_rotation\"],\n            ego2global_translation=info[\"ego2global_translation\"],\n            ego2global_rotation=info[\"ego2global_rotation\"],\n            ego_status=info['ego_status'].astype(np.float32),\n            map_infos=info[\"map_annos\"],\n        )\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = pyquaternion.Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = pyquaternion.Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        input_dict[\"lidar2global\"] = ego2global @ lidar2ego\n\n        map_geoms = self.anno2geom(info[\"map_annos\"])\n        input_dict[\"map_geoms\"] = map_geoms\n\n        if self.modality[\"use_camera\"]:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsic = []\n            for cam_type, cam_info in info[\"cams\"].items():\n                image_paths.append(cam_info[\"data_path\"])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info[\"sensor2lidar_rotation\"])\n                lidar2cam_t = (\n                    cam_info[\"sensor2lidar_translation\"] @ lidar2cam_r.T\n                )\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = copy.deepcopy(cam_info[\"cam_intrinsic\"])\n                cam_intrinsic.append(intrinsic)\n                viewpad = np.eye(4)\n                viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = viewpad @ lidar2cam_rt.T\n                lidar2img_rts.append(lidar2img_rt)\n                lidar2cam_rts.append(lidar2cam_rt)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    lidar2cam=lidar2cam_rts,\n                    cam_intrinsic=cam_intrinsic,\n                )\n            )\n\n        annos = self.get_ann_info(index)\n        input_dict.update(annos)\n        return input_dict\n\n    def get_ann_info(self, index):\n        info = self.data_infos[index]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n        else:\n            mask = info[\"num_lidar_pts\"] > 0\n        gt_bboxes_3d = info[\"gt_boxes\"][mask]\n        gt_names_3d = info[\"gt_names\"][mask]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info[\"gt_velocity\"][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n        )\n        if \"instance_inds\" in info:\n            instance_inds = np.array(info[\"instance_inds\"], dtype=np.int)[mask]\n            anns_results[\"instance_inds\"] = instance_inds\n            \n        if 'gt_agent_fut_trajs' in info:\n            anns_results['gt_agent_fut_trajs'] = info['gt_agent_fut_trajs'][mask]\n            anns_results['gt_agent_fut_masks'] = info['gt_agent_fut_masks'][mask]\n\n        if 'gt_ego_fut_trajs' in info:\n            anns_results['gt_ego_fut_trajs'] = info['gt_ego_fut_trajs']\n            anns_results['gt_ego_fut_masks'] = info['gt_ego_fut_masks']\n            anns_results['gt_ego_fut_cmd'] = info['gt_ego_fut_cmd']\n        \n            ## get future box for planning eval\n            # \n            \n            fut_ts = int(info['gt_ego_fut_masks'].sum())\n            # print(\"fut_ts\",fut_ts)\n\n            fut_boxes = []\n            cur_scene_token = info[\"scene_token\"]\n            # print(\"cur_scene_token\",cur_scene_token)\n            cur_T_global = get_T_global(info)\n            for i in range(1, fut_ts + 1):\n                # print(\"data_infos\",len(self.data_infos))\n                fut_info = self.data_infos[index + i]\n                fut_scene_token = fut_info[\"scene_token\"]\n                if cur_scene_token != fut_scene_token:\n                    break\n                if self.use_valid_flag:\n                    mask = fut_info[\"valid_flag\"]\n                else:\n                    mask = fut_info[\"num_lidar_pts\"] > 0\n\n                fut_gt_bboxes_3d = fut_info[\"gt_boxes\"][mask]\n                \n                fut_T_global = get_T_global(fut_info)\n                T_fut2cur = np.linalg.inv(cur_T_global) @ fut_T_global\n\n                center = fut_gt_bboxes_3d[:, :3] @ T_fut2cur[:3, :3].T + T_fut2cur[:3, 3]\n                yaw = np.stack([np.cos(fut_gt_bboxes_3d[:, 6]), np.sin(fut_gt_bboxes_3d[:, 6])], axis=-1)\n                yaw = yaw @ T_fut2cur[:2, :2].T\n                yaw = np.arctan2(yaw[..., 1], yaw[..., 0])\n\n                fut_gt_bboxes_3d[:, :3] = center\n                fut_gt_bboxes_3d[:, 6] = yaw\n                fut_boxes.append(fut_gt_bboxes_3d)\n\n            anns_results['fut_boxes'] = fut_boxes\n        \n        return anns_results\n\n    def _format_bbox(self, results, jsonfile_prefix=None, tracking=False):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det, threshold=self.tracking_threshold if tracking else None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n            )\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, \"results_nusc.json\")\n        print(\"Results writes to\", res_path)\n        mmcv.dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(\n        self, result_path, logger=None, result_name=\"img_bbox\", tracking=False\n    ):\n        from nuscenes import NuScenes\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False\n        )\n        eval_set_map = {\n            \"v1.0-mini\": \"mini_val\",\n            \"v1.0-trainval\": \"val\",\n        }\n        if not tracking:\n            from nuscenes.eval.detection.evaluate import NuScenesEval\n            \n            nusc_eval = NuScenesEval(\n                nusc,\n                config=self.det3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n            )\n            nusc_eval.main(render_curves=False)\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            for name in self.CLASSES:\n                for k, v in metrics[\"label_aps\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}_AP_dist_{}\".format(metric_prefix, name, k)\n                    ] = val\n                for k, v in metrics[\"label_tp_errors\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\"{}/{}_{}\".format(metric_prefix, name, k)] = val\n                for k, v in metrics[\"tp_errors\"].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}\".format(metric_prefix, self.ErrNameMapping[k])\n                    ] = val\n\n            detail[\"{}/NDS\".format(metric_prefix)] = metrics[\"nd_score\"]\n            detail[\"{}/mAP\".format(metric_prefix)] = metrics[\"mean_ap\"]\n        else:\n            from nuscenes.eval.tracking.evaluate import TrackingEval\n\n            nusc_eval = TrackingEval(\n                config=self.track3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n                nusc_version=self.version,\n                nusc_dataroot=self.data_root,\n            )\n            metrics = nusc_eval.main()\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            print(metrics)\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            keys = [\n                \"amota\",\n                \"amotp\",\n                \"recall\",\n                \"motar\",\n                \"gt\",\n                \"mota\",\n                \"motp\",\n                \"mt\",\n                \"ml\",\n                \"faf\",\n                \"tp\",\n                \"fp\",\n                \"fn\",\n                \"ids\",\n                \"frag\",\n                \"tid\",\n                \"lgd\",\n            ]\n            for key in keys:\n                detail[\"{}/{}\".format(metric_prefix, key)] = metrics[key]\n\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None, tracking=False):\n        assert isinstance(results, list), \"results must be a list\"\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, \"results\")\n        else:\n            tmp_dir = None\n\n        if not (\"pts_bbox\" in results[0] or \"img_bbox\" in results[0]):\n            result_files = self._format_bbox(\n                results, jsonfile_prefix, tracking=tracking\n            )\n        else:\n            result_files = dict()\n            for name in results[0]:\n                print(f\"\\nFormating bboxes of {name}\")\n                results_ = [out[name] for out in results]\n                tmp_file_ = jsonfile_prefix\n                result_files.update(\n                    {\n                        name: self._format_bbox(\n                            results_, tmp_file_, tracking=tracking\n                        )\n                    }\n                )\n        return result_files, tmp_dir\n\n    def format_map_results(self, results, prefix=None):\n        submissions = {'results': {},}\n        \n        for j, pred in enumerate(results):\n            '''\n            For each case, the result should be formatted as Dict{'vectors': [], 'scores': [], 'labels': []}\n            'vectors': List of vector, each vector is a array([[x1, y1], [x2, y2] ...]),\n                contain all vectors predicted in this sample.\n            'scores: List of score(float), \n                contain scores of all instances in this sample.\n            'labels': List of label(int), \n                contain labels of all instances in this sample.\n            '''\n            if pred is None: # empty prediction\n                continue\n            pred = pred['img_bbox']\n\n            single_case = {'vectors': [], 'scores': [], 'labels': []}\n            token = self.data_infos[j]['token']\n            for i in range(len(pred['scores'])):\n                score = pred['scores'][i]\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n\n                # A line should have >=2 points\n                if len(vector) < 2:\n                    continue\n                \n                single_case['vectors'].append(vector)\n                single_case['scores'].append(score)\n                single_case['labels'].append(label)\n            \n            submissions['results'][token] = single_case\n        \n        out_path = osp.join(prefix, 'submission_vector.json')\n        print(f'saving submissions results to {out_path}')\n        os.makedirs(os.path.dirname(out_path), exist_ok=True)\n        mmcv.dump(submissions, out_path)\n        return out_path\n\n    def format_motion_results(self, results, jsonfile_prefix=None, tracking=False, thresh=None):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det['img_bbox'], threshold=None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n                filter_with_cls_range=False,\n            )\n            for i, box in enumerate(boxes):\n                if thresh is not None and box.score < thresh:\n                    continue\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n                nusc_anno.update(\n                    dict(\n                        trajs=det['img_bbox']['trajs_3d'][i].numpy(),\n                    )\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        return nusc_submissions \n\n    def _evaluate_single_motion(self,\n                         results,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        from .evaluation.motion.motion_eval_uniad import NuScenesEval as NuScenesEvalMotion\n\n        output_dir = result_path\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        nusc_eval = NuScenesEvalMotion(\n            nusc,\n            config=copy.deepcopy(self.det3d_eval_configs),\n            result_path=results,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False,\n            seconds=6)\n        metrics = nusc_eval.main(render_curves=False)\n        \n        MOTION_METRICS = ['EPA', 'min_ade_err', 'min_fde_err', 'miss_rate_err']\n        class_names = ['car', 'pedestrian']\n\n        table = prettytable.PrettyTable()\n        table.field_names = [\"class names\"] + MOTION_METRICS\n        for class_name in class_names:\n            row_data = [class_name]\n            for m in MOTION_METRICS:\n                row_data.append('%.4f' % metrics[f'{class_name}_{m}'])\n            table.add_row(row_data)\n        print_log('\\n'+str(table), logger=logger)\n        return metrics\n\n    def evaluate(\n        self,\n        results,\n        eval_mode,\n        metric=None,\n        logger=None,\n        jsonfile_prefix=None,\n        result_names=[\"img_bbox\"],\n        show=False,\n        out_dir=None,\n        pipeline=None,\n    ):\n        \n        res_path = \"results.pkl\" if \"trainval\" in self.version else \"results_mini.pkl\"\n        res_path = osp.join(self.work_dir, res_path)\n        print('All Results write to', res_path)\n        mmcv.dump(results, res_path)\n\n        results_dict = dict()\n        if eval_mode['with_det']:\n            self.tracking = eval_mode[\"with_tracking\"]\n            self.tracking_threshold = eval_mode[\"tracking_threshold\"]\n            for metric in [\"detection\", \"tracking\"]:\n                tracking = metric == \"tracking\"\n                if tracking and not self.tracking:\n                    continue\n                result_files, tmp_dir = self.format_results(\n                    results, jsonfile_prefix=self.work_dir, tracking=tracking\n                )\n\n                if isinstance(result_files, dict):\n                    for name in result_names:\n                        ret_dict = self._evaluate_single(\n                            result_files[name], tracking=tracking\n                        )\n                    results_dict.update(ret_dict)\n                elif isinstance(result_files, str):\n                    ret_dict = self._evaluate_single(\n                        result_files, tracking=tracking\n                    )\n                    results_dict.update(ret_dict)\n\n                if tmp_dir is not None:\n                    tmp_dir.cleanup()\n\n        if eval_mode['with_map']:\n            from .evaluation.map.vector_eval import VectorEvaluate\n            self.map_evaluator = VectorEvaluate(self.eval_config)\n            result_path = self.format_map_results(results, prefix=self.work_dir)\n            map_results_dict = self.map_evaluator.evaluate(result_path, logger=logger)\n            results_dict.update(map_results_dict)\n\n        if eval_mode['with_motion']:\n            thresh = eval_mode[\"motion_threshhold\"]\n            result_files = self.format_motion_results(results, jsonfile_prefix=self.work_dir, thresh=thresh)\n            motion_results_dict = self._evaluate_single_motion(result_files, self.work_dir, logger=logger)\n            results_dict.update(motion_results_dict)\n        \n        if eval_mode['with_planning']:\n            from .evaluation.planning.planning_eval_roboAD import planning_eval_roboAD\n            planning_results_dict = planning_eval_roboAD(results, self.eval_config, logger=logger)\n            results_dict.update(planning_results_dict)\n\n        if show or out_dir:\n            self.show(results, save_dir=out_dir, show=show, pipeline=pipeline)\n        \n        # print main metrics for recording\n        metric_str = '\\n'\n        if \"img_bbox_NuScenes/NDS\" in results_dict:\n            metric_str += f'mAP: {results_dict.get(\"img_bbox_NuScenes/mAP\"):.4f}\\n'\n            metric_str += f'mATE: {results_dict.get(\"img_bbox_NuScenes/mATE\"):.4f}\\n'\n            metric_str += f'mASE: {results_dict.get(\"img_bbox_NuScenes/mASE\"):.4f}\\n'\n            metric_str += f'mAOE: {results_dict.get(\"img_bbox_NuScenes/mAOE\"):.4f}\\n' \n            metric_str += f'mAVE: {results_dict.get(\"img_bbox_NuScenes/mAVE\"):.4f}\\n' \n            metric_str += f'mAAE: {results_dict.get(\"img_bbox_NuScenes/mAAE\"):.4f}\\n' \n            metric_str += f'NDS: {results_dict.get(\"img_bbox_NuScenes/NDS\"):.4f}\\n\\n'\n        \n        if \"img_bbox_NuScenes/amota\" in results_dict:\n            metric_str += f'AMOTA: {results_dict[\"img_bbox_NuScenes/amota\"]:.4f}\\n' \n            metric_str += f'AMOTP: {results_dict[\"img_bbox_NuScenes/amotp\"]:.4f}\\n' \n            metric_str += f'RECALL: {results_dict[\"img_bbox_NuScenes/recall\"]:.4f}\\n' \n            metric_str += f'MOTAR: {results_dict[\"img_bbox_NuScenes/motar\"]:.4f}\\n' \n            metric_str += f'MOTA: {results_dict[\"img_bbox_NuScenes/mota\"]:.4f}\\n' \n            metric_str += f'MOTP: {results_dict[\"img_bbox_NuScenes/motp\"]:.4f}\\n' \n            metric_str += f'IDS: {results_dict[\"img_bbox_NuScenes/ids\"]}\\n\\n' \n        \n        if \"mAP_normal\" in results_dict:\n            metric_str += f'ped_crossing= {results_dict[\"ped_crossing\"]:.4f}\\n' \n            metric_str += f'divider= {results_dict[\"divider\"]:.4f}\\n' \n            metric_str += f'boundary= {results_dict[\"boundary\"]:.4f}\\n' \n            metric_str += f'mAP_normal= {results_dict[\"mAP_normal\"]:.4f}\\n\\n' \n\n        if \"car_EPA\" in results_dict:\n            metric_str += f'Car / Ped\\n' \n            metric_str += f'epa= {results_dict[\"car_EPA\"]:.4f} / {results_dict[\"pedestrian_EPA\"]:.4f}\\n'\n            metric_str += f'ade= {results_dict[\"car_min_ade_err\"]:.4f} / {results_dict[\"pedestrian_min_ade_err\"]:.4f}\\n'\n            metric_str += f'fde= {results_dict[\"car_min_fde_err\"]:.4f} / {results_dict[\"pedestrian_min_fde_err\"]:.4f}\\n'\n            metric_str += f'mr= {results_dict[\"car_miss_rate_err\"]:.4f} / {results_dict[\"pedestrian_miss_rate_err\"]:.4f}\\n\\n' \n\n        if \"L2\" in results_dict:\n            metric_str += f'obj_box_col: {(results_dict[\"obj_box_col\"]*100):.3f}%\\n'\n            metric_str += f'L2: {results_dict[\"L2\"]:.4f}\\n\\n'\n        \n        print_log(metric_str, logger=logger)\n        return results_dict\n\n    def show(self, results, save_dir=None, show=False, pipeline=None):\n        save_dir = \"./\" if save_dir is None else save_dir\n        save_dir = os.path.join(save_dir, \"visual\")\n        print_log(os.path.abspath(save_dir))\n        pipeline = Compose(pipeline)\n        if not os.path.exists(save_dir):\n            os.makedirs(save_dir)\n\n        fourcc = cv2.VideoWriter_fourcc(*\"MJPG\")\n        videoWriter = None\n\n        for i, result in enumerate(results):\n            if \"img_bbox\" in result.keys():\n                result = result[\"img_bbox\"]\n            data_info = pipeline(self.get_data_info(i))\n            imgs = []\n\n            raw_imgs = data_info[\"img\"]\n            lidar2img = data_info[\"img_metas\"].data[\"lidar2img\"]\n            pred_bboxes_3d = result[\"boxes_3d\"][\n                result[\"scores_3d\"] > self.vis_score_threshold\n            ]\n            if \"instance_ids\" in result and self.tracking:\n                color = []\n                for id in result[\"instance_ids\"].cpu().numpy().tolist():\n                    color.append(\n                        self.ID_COLOR_MAP[int(id % len(self.ID_COLOR_MAP))]\n                    )\n            elif \"labels_3d\" in result:\n                color = []\n                for id in result[\"labels_3d\"].cpu().numpy().tolist():\n                    color.append(self.ID_COLOR_MAP[id])\n            else:\n                color = (255, 0, 0)\n\n            # ===== draw boxes_3d to images =====\n            for j, img_origin in enumerate(raw_imgs):\n                img = img_origin.copy()\n                if len(pred_bboxes_3d) != 0:\n                    img = draw_lidar_bbox3d_on_img(\n                        pred_bboxes_3d,\n                        img,\n                        lidar2img[j],\n                        img_metas=None,\n                        color=color,\n                        thickness=3,\n                    )\n                imgs.append(img)\n\n            # ===== draw boxes_3d to BEV =====\n            bev = draw_lidar_bbox3d_on_bev(\n                pred_bboxes_3d,\n                bev_size=img.shape[0] * 2,\n                color=color,\n            )\n\n            # ===== put text and concat =====\n            for j, name in enumerate(\n                [\n                    \"front\",\n                    \"front right\",\n                    \"front left\",\n                    \"rear\",\n                    \"rear left\",\n                    \"rear right\",\n                ]\n            ):\n                imgs[j] = cv2.rectangle(\n                    imgs[j],\n                    (0, 0),\n                    (440, 80),\n                    color=(255, 255, 255),\n                    thickness=-1,\n                )\n                w, h = cv2.getTextSize(name, cv2.FONT_HERSHEY_SIMPLEX, 2, 2)[0]\n                text_x = int(220 - w / 2)\n                text_y = int(40 + h / 2)\n\n                imgs[j] = cv2.putText(\n                    imgs[j],\n                    name,\n                    (text_x, text_y),\n                    cv2.FONT_HERSHEY_SIMPLEX,\n                    2,\n                    (0, 0, 0),\n                    2,\n                    cv2.LINE_AA,\n                )\n            image = np.concatenate(\n                [\n                    np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n                    np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n                ],\n                axis=0,\n            )\n            image = np.concatenate([image, bev], axis=1)\n\n            # ===== save video =====\n            if videoWriter is None:\n                videoWriter = cv2.VideoWriter(\n                    os.path.join(save_dir, \"video.avi\"),\n                    fourcc,\n                    7,\n                    image.shape[:2][::-1],\n                )\n            cv2.imwrite(os.path.join(save_dir, f\"{i}.jpg\"), image)\n            videoWriter.write(image)\n        videoWriter.release()\n\n\ndef output_to_nusc_box(detection, threshold=None):\n    box3d = detection[\"boxes_3d\"]\n    scores = detection[\"scores_3d\"].numpy()\n    labels = detection[\"labels_3d\"].numpy()\n    if \"instance_ids\" in detection:\n        ids = detection[\"instance_ids\"]  # .numpy()\n    if threshold is not None:\n        if \"cls_scores\" in detection:\n            mask = detection[\"cls_scores\"].numpy() >= threshold\n        else:\n            mask = scores >= threshold\n        box3d = box3d[mask]\n        scores = scores[mask]\n        labels = labels[mask]\n        ids = ids[mask]\n\n    if hasattr(box3d, \"gravity_center\"):\n        box_gravity_center = box3d.gravity_center.numpy()\n        box_dims = box3d.dims.numpy()\n        nus_box_dims = box_dims[:, [1, 0, 2]]\n        box_yaw = box3d.yaw.numpy()\n    else:\n        box3d = box3d.numpy()\n        box_gravity_center = box3d[..., :3].copy()\n        box_dims = box3d[..., 3:6].copy()\n        nus_box_dims = box_dims[..., [1, 0, 2]]\n        box_yaw = box3d[..., 6].copy()\n\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    # box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        if hasattr(box3d, \"gravity_center\"):\n            velocity = (*box3d.tensor[i, 7:9], 0.0)\n        else:\n            velocity = (*box3d[i, 7:9], 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            nus_box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity,\n        )\n        if \"instance_ids\" in detection:\n            box.token = ids[i]\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(\n    info,\n    boxes,\n    classes,\n    eval_configs,\n    eval_version=\"detection_cvpr_2019\",\n    filter_with_cls_range=True,\n):\n    box_list = []\n    for i, box in enumerate(boxes):\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info[\"lidar2ego_rotation\"]))\n        box.translate(np.array(info[\"lidar2ego_translation\"]))\n        # filter det in ego.\n        if filter_with_cls_range:\n            cls_range_map = eval_configs.class_range\n            radius = np.linalg.norm(box.center[:2], 2)\n            det_range = cls_range_map[classes[box.label]]\n            if radius > det_range:\n                continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info[\"ego2global_rotation\"]))\n        box.translate(np.array(info[\"ego2global_translation\"]))\n        box_list.append(box)\n    return box_list\n\n\ndef get_T_global(info):\n    lidar2ego = np.eye(4)\n    lidar2ego[:3, :3] = pyquaternion.Quaternion(\n        info[\"lidar2ego_rotation\"]\n    ).rotation_matrix\n    lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n    ego2global = np.eye(4)\n    ego2global[:3, :3] = pyquaternion.Quaternion(\n        info[\"ego2global_rotation\"]\n    ).rotation_matrix\n    ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n    return ego2global @ lidar2ego"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/nuscenes_3d_dataset_roboAD_6s.py",
    "content": "import random\nimport math\nimport os\nfrom os import path as osp\nimport cv2\nimport tempfile\nimport copy\nimport prettytable\n\nimport numpy as np\nimport torch\nfrom torch.utils.data import Dataset\nimport pyquaternion\nfrom shapely.geometry import LineString\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.eval.detection.config import config_factory as det_configs\nfrom nuscenes.eval.common.config import config_factory as track_configs\n\nimport mmcv\nfrom mmcv.utils import print_log\nfrom mmdet.datasets import DATASETS\nfrom mmdet.datasets.pipelines import Compose\nfrom .utils import (\n    draw_lidar_bbox3d_on_img,\n    draw_lidar_bbox3d_on_bev,\n)\n\n\n@DATASETS.register_module()\nclass NuScenes3DDataset_roboAD_6s(Dataset):\n    DefaultAttribute = {\n        \"car\": \"vehicle.parked\",\n        \"pedestrian\": \"pedestrian.moving\",\n        \"trailer\": \"vehicle.parked\",\n        \"truck\": \"vehicle.parked\",\n        \"bus\": \"vehicle.moving\",\n        \"motorcycle\": \"cycle.without_rider\",\n        \"construction_vehicle\": \"vehicle.parked\",\n        \"bicycle\": \"cycle.without_rider\",\n        \"barrier\": \"\",\n        \"traffic_cone\": \"\",\n    }\n    ErrNameMapping = {\n        \"trans_err\": \"mATE\",\n        \"scale_err\": \"mASE\",\n        \"orient_err\": \"mAOE\",\n        \"vel_err\": \"mAVE\",\n        \"attr_err\": \"mAAE\",\n    }\n    CLASSES = (\n        \"car\",\n        \"truck\",\n        \"trailer\",\n        \"bus\",\n        \"construction_vehicle\",\n        \"bicycle\",\n        \"motorcycle\",\n        \"pedestrian\",\n        \"traffic_cone\",\n        \"barrier\",\n    )\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    ID_COLOR_MAP = [\n        (59, 59, 238),\n        (0, 255, 0),\n        (0, 0, 255),\n        (255, 255, 0),\n        (0, 255, 255),\n        (255, 0, 255),\n        (255, 255, 255),\n        (0, 127, 255),\n        (71, 130, 255),\n        (127, 127, 0),\n    ]\n\n    def __init__(\n        self,\n        ann_file,\n        pipeline=None,\n        data_root=None,\n        classes=None,\n        map_classes=None,\n        load_interval=1,\n        with_velocity=True,\n        modality=None,\n        test_mode=False,\n        det3d_eval_version=\"detection_cvpr_2019\",\n        track3d_eval_version=\"tracking_nips_2019\",\n        version=\"v1.0-trainval\",\n        use_valid_flag=False,\n        vis_score_threshold=0.25,\n        data_aug_conf=None,\n        sequences_split_num=1,\n        with_seq_flag=False,\n        keep_consistent_seq_aug=True,\n        work_dir=None,\n        eval_config=None,\n    ):\n        self.version = version\n        self.load_interval = load_interval\n        self.use_valid_flag = use_valid_flag\n        super().__init__()\n        self.data_root = data_root\n        self.ann_file = ann_file\n        self.test_mode = test_mode\n        self.modality = modality\n        self.box_mode_3d = 0\n\n        if classes is not None:\n            self.CLASSES = classes\n        if map_classes is not None: \n            self.MAP_CLASSES = map_classes\n        self.cat2id = {name: i for i, name in enumerate(self.CLASSES)}\n        self.data_infos = self.load_annotations(self.ann_file)\n\n        if pipeline is not None:\n            self.pipeline = Compose(pipeline)\n\n        self.with_velocity = with_velocity\n        self.det3d_eval_version = det3d_eval_version\n        self.det3d_eval_configs = det_configs(self.det3d_eval_version)\n        self.det3d_eval_configs.class_names = list(self.det3d_eval_configs.class_range.keys())\n        self.track3d_eval_version = track3d_eval_version\n        self.track3d_eval_configs = track_configs(self.track3d_eval_version)\n        self.track3d_eval_configs.class_names = list(self.track3d_eval_configs.class_range.keys())\n        if self.modality is None:\n            self.modality = dict(\n                use_camera=False,\n                use_lidar=True,\n                use_radar=False,\n                use_map=False,\n                use_external=False,\n            )\n        self.vis_score_threshold = vis_score_threshold\n\n        self.data_aug_conf = data_aug_conf\n        self.sequences_split_num = sequences_split_num\n        self.keep_consistent_seq_aug = keep_consistent_seq_aug\n        if with_seq_flag:\n            self._set_sequence_group_flag()\n        \n        self.work_dir = work_dir\n        #import pdb;pdb.set_trace()\n        self.eval_config = eval_config\n\n    def __len__(self):\n        return len(self.data_infos)\n\n    def _set_sequence_group_flag(self):\n        \"\"\"\n        Set each sequence to be a different group\n        \"\"\"\n        if self.sequences_split_num == -1:\n            self.flag = np.arange(len(self.data_infos))\n            return\n        \n        res = []\n\n        curr_sequence = 0\n        for idx in range(len(self.data_infos)):\n            if idx != 0 and len(self.data_infos[idx][\"sweeps\"]) == 0:\n                # Not first frame and # of sweeps is 0 -> new sequence\n                curr_sequence += 1\n            res.append(curr_sequence)\n\n        self.flag = np.array(res, dtype=np.int64)\n\n        if self.sequences_split_num != 1:\n            if self.sequences_split_num == \"all\":\n                self.flag = np.array(\n                    range(len(self.data_infos)), dtype=np.int64\n                )\n            else:\n                bin_counts = np.bincount(self.flag)\n                new_flags = []\n                curr_new_flag = 0\n                for curr_flag in range(len(bin_counts)):\n                    curr_sequence_length = np.array(\n                        list(\n                            range(\n                                0,\n                                bin_counts[curr_flag],\n                                math.ceil(\n                                    bin_counts[curr_flag]\n                                    / self.sequences_split_num\n                                ),\n                            )\n                        )\n                        + [bin_counts[curr_flag]]\n                    )\n\n                    for sub_seq_idx in (\n                        curr_sequence_length[1:] - curr_sequence_length[:-1]\n                    ):\n                        for _ in range(sub_seq_idx):\n                            new_flags.append(curr_new_flag)\n                        curr_new_flag += 1\n\n                assert len(new_flags) == len(self.flag)\n                assert (\n                    len(np.bincount(new_flags))\n                    == len(np.bincount(self.flag)) * self.sequences_split_num\n                )\n                self.flag = np.array(new_flags, dtype=np.int64)\n\n    def get_augmentation(self):\n        if self.data_aug_conf is None:\n            return None\n        H, W = self.data_aug_conf[\"H\"], self.data_aug_conf[\"W\"]\n        fH, fW = self.data_aug_conf[\"final_dim\"]\n        if not self.test_mode:\n            resize = np.random.uniform(*self.data_aug_conf[\"resize_lim\"])\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int(\n                    (1 - np.random.uniform(*self.data_aug_conf[\"bot_pct_lim\"]))\n                    * newH\n                )\n                - fH\n            )\n            crop_w = int(np.random.uniform(0, max(0, newW - fW)))\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            if self.data_aug_conf[\"rand_flip\"] and np.random.choice([0, 1]):\n                flip = True\n            rotate = np.random.uniform(*self.data_aug_conf[\"rot_lim\"])\n            rotate_3d = np.random.uniform(*self.data_aug_conf[\"rot3d_range\"])\n        else:\n            resize = max(fH / H, fW / W)\n            resize_dims = (int(W * resize), int(H * resize))\n            newW, newH = resize_dims\n            crop_h = (\n                int((1 - np.mean(self.data_aug_conf[\"bot_pct_lim\"])) * newH)\n                - fH\n            )\n            crop_w = int(max(0, newW - fW) / 2)\n            crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)\n            flip = False\n            rotate = 0\n            rotate_3d = 0\n        aug_config = {\n            \"resize\": resize,\n            \"resize_dims\": resize_dims,\n            \"crop\": crop,\n            \"flip\": flip,\n            \"rotate\": rotate,\n            \"rotate_3d\": rotate_3d,\n        }\n        return aug_config\n\n    def __getitem__(self, idx):\n        if isinstance(idx, dict):\n            aug_config = idx[\"aug_config\"]\n            idx = idx[\"idx\"]\n        else:\n            aug_config = self.get_augmentation()\n        data = self.get_data_info(idx)\n        data[\"aug_config\"] = aug_config\n        #import pdb; pdb.set_trace()\n        data = self.pipeline(data)\n        return data\n\n    def get_cat_ids(self, idx):\n        info = self.data_infos[idx]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n            gt_names = set(info[\"gt_names\"][mask])\n        else:\n            gt_names = set(info[\"gt_names\"])\n\n        cat_ids = []\n        for name in gt_names:\n            if name in self.CLASSES:\n                cat_ids.append(self.cat2id[name])\n        return cat_ids\n\n    def load_annotations(self, ann_file):\n        data = mmcv.load(ann_file, file_format=\"pkl\")\n        data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\n        data_infos = data_infos[:: self.load_interval]\n        # import pdb; pdb.set_trace()\n        self.metadata = data[\"metadata\"]\n        self.version = self.metadata[\"version\"]\n        print(self.metadata)\n        return data_infos\n    \n    def anno2geom(self, annos):\n        map_geoms = {}\n        for label, anno_list in annos.items():\n            map_geoms[label] = []\n            for anno in anno_list:\n                geom = LineString(anno)\n                map_geoms[label].append(geom)\n        return map_geoms\n    \n    def get_data_info(self, index):\n        info = self.data_infos[index]\n        input_dict = dict(\n            token=info[\"token\"],\n            map_location=info[\"map_location\"],\n            pts_filename=info[\"lidar_path\"],\n            sweeps=info[\"sweeps\"],\n            timestamp=info[\"timestamp\"] / 1e6,\n            lidar2ego_translation=info[\"lidar2ego_translation\"],\n            lidar2ego_rotation=info[\"lidar2ego_rotation\"],\n            ego2global_translation=info[\"ego2global_translation\"],\n            ego2global_rotation=info[\"ego2global_rotation\"],\n            ego_status=info['ego_status'].astype(np.float32),\n            map_infos=info[\"map_annos\"],\n        )\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = pyquaternion.Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = pyquaternion.Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        input_dict[\"lidar2global\"] = ego2global @ lidar2ego\n\n        map_geoms = self.anno2geom(info[\"map_annos\"])\n        input_dict[\"map_geoms\"] = map_geoms\n\n        if self.modality[\"use_camera\"]:\n            image_paths = []\n            lidar2img_rts = []\n            lidar2cam_rts = []\n            cam_intrinsic = []\n            for cam_type, cam_info in info[\"cams\"].items():\n                image_paths.append(cam_info[\"data_path\"])\n                # obtain lidar to image transformation matrix\n                lidar2cam_r = np.linalg.inv(cam_info[\"sensor2lidar_rotation\"])\n                lidar2cam_t = (\n                    cam_info[\"sensor2lidar_translation\"] @ lidar2cam_r.T\n                )\n                lidar2cam_rt = np.eye(4)\n                lidar2cam_rt[:3, :3] = lidar2cam_r.T\n                lidar2cam_rt[3, :3] = -lidar2cam_t\n                intrinsic = copy.deepcopy(cam_info[\"cam_intrinsic\"])\n                cam_intrinsic.append(intrinsic)\n                viewpad = np.eye(4)\n                viewpad[: intrinsic.shape[0], : intrinsic.shape[1]] = intrinsic\n                lidar2img_rt = viewpad @ lidar2cam_rt.T\n                lidar2img_rts.append(lidar2img_rt)\n                lidar2cam_rts.append(lidar2cam_rt)\n\n            input_dict.update(\n                dict(\n                    img_filename=image_paths,\n                    lidar2img=lidar2img_rts,\n                    lidar2cam=lidar2cam_rts,\n                    cam_intrinsic=cam_intrinsic,\n                )\n            )\n\n        annos = self.get_ann_info(index)\n        input_dict.update(annos)\n        return input_dict\n\n    def get_ann_info(self, index):\n        info = self.data_infos[index]\n        if self.use_valid_flag:\n            mask = info[\"valid_flag\"]\n        else:\n            mask = info[\"num_lidar_pts\"] > 0\n        gt_bboxes_3d = info[\"gt_boxes\"][mask]\n        gt_names_3d = info[\"gt_names\"][mask]\n        gt_labels_3d = []\n        for cat in gt_names_3d:\n            if cat in self.CLASSES:\n                gt_labels_3d.append(self.CLASSES.index(cat))\n            else:\n                gt_labels_3d.append(-1)\n        gt_labels_3d = np.array(gt_labels_3d)\n\n        if self.with_velocity:\n            gt_velocity = info[\"gt_velocity\"][mask]\n            nan_mask = np.isnan(gt_velocity[:, 0])\n            gt_velocity[nan_mask] = [0.0, 0.0]\n            gt_bboxes_3d = np.concatenate([gt_bboxes_3d, gt_velocity], axis=-1)\n\n        anns_results = dict(\n            gt_bboxes_3d=gt_bboxes_3d,\n            gt_labels_3d=gt_labels_3d,\n            gt_names=gt_names_3d,\n        )\n        if \"instance_inds\" in info:\n            instance_inds = np.array(info[\"instance_inds\"], dtype=np.int)[mask]\n            anns_results[\"instance_inds\"] = instance_inds\n            \n        if 'gt_agent_fut_trajs' in info:\n            anns_results['gt_agent_fut_trajs'] = info['gt_agent_fut_trajs'][mask]\n            anns_results['gt_agent_fut_masks'] = info['gt_agent_fut_masks'][mask]\n\n        if 'gt_ego_fut_trajs' in info:\n            anns_results['gt_ego_fut_trajs'] = info['gt_ego_fut_trajs']\n            anns_results['gt_ego_fut_masks'] = info['gt_ego_fut_masks']\n            anns_results['gt_ego_fut_cmd'] = info['gt_ego_fut_cmd']\n        \n            ## get future box for planning eval\n            # \n            \n            fut_ts = int(info['gt_ego_fut_masks'].sum())\n            # print(\"fut_ts\",fut_ts)\n\n            fut_boxes = []\n            cur_scene_token = info[\"scene_token\"]\n            # print(\"cur_scene_token\",cur_scene_token)\n            cur_T_global = get_T_global(info)\n            for i in range(1, fut_ts + 1):\n                # print(\"data_infos\",len(self.data_infos))\n                fut_info = self.data_infos[index + i]\n                fut_scene_token = fut_info[\"scene_token\"]\n                if cur_scene_token != fut_scene_token:\n                    break\n                if self.use_valid_flag:\n                    mask = fut_info[\"valid_flag\"]\n                else:\n                    mask = fut_info[\"num_lidar_pts\"] > 0\n\n                fut_gt_bboxes_3d = fut_info[\"gt_boxes\"][mask]\n                \n                fut_T_global = get_T_global(fut_info)\n                T_fut2cur = np.linalg.inv(cur_T_global) @ fut_T_global\n\n                center = fut_gt_bboxes_3d[:, :3] @ T_fut2cur[:3, :3].T + T_fut2cur[:3, 3]\n                yaw = np.stack([np.cos(fut_gt_bboxes_3d[:, 6]), np.sin(fut_gt_bboxes_3d[:, 6])], axis=-1)\n                yaw = yaw @ T_fut2cur[:2, :2].T\n                yaw = np.arctan2(yaw[..., 1], yaw[..., 0])\n\n                fut_gt_bboxes_3d[:, :3] = center\n                fut_gt_bboxes_3d[:, 6] = yaw\n                fut_boxes.append(fut_gt_bboxes_3d)\n\n            anns_results['fut_boxes'] = fut_boxes\n        \n        return anns_results\n\n    def _format_bbox(self, results, jsonfile_prefix=None, tracking=False):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det, threshold=self.tracking_threshold if tracking else None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n            )\n            for i, box in enumerate(boxes):\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD_6s.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD_6s.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        mmcv.mkdir_or_exist(jsonfile_prefix)\n        res_path = osp.join(jsonfile_prefix, \"results_nusc.json\")\n        print(\"Results writes to\", res_path)\n        mmcv.dump(nusc_submissions, res_path)\n        return res_path\n\n    def _evaluate_single(\n        self, result_path, logger=None, result_name=\"img_bbox\", tracking=False\n    ):\n        from nuscenes import NuScenes\n\n        output_dir = osp.join(*osp.split(result_path)[:-1])\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False\n        )\n        eval_set_map = {\n            \"v1.0-mini\": \"mini_val\",\n            \"v1.0-trainval\": \"val\",\n        }\n        if not tracking:\n            from nuscenes.eval.detection.evaluate import NuScenesEval\n            \n            nusc_eval = NuScenesEval(\n                nusc,\n                config=self.det3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n            )\n            nusc_eval.main(render_curves=False)\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            for name in self.CLASSES:\n                for k, v in metrics[\"label_aps\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}_AP_dist_{}\".format(metric_prefix, name, k)\n                    ] = val\n                for k, v in metrics[\"label_tp_errors\"][name].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\"{}/{}_{}\".format(metric_prefix, name, k)] = val\n                for k, v in metrics[\"tp_errors\"].items():\n                    val = float(\"{:.4f}\".format(v))\n                    detail[\n                        \"{}/{}\".format(metric_prefix, self.ErrNameMapping[k])\n                    ] = val\n\n            detail[\"{}/NDS\".format(metric_prefix)] = metrics[\"nd_score\"]\n            detail[\"{}/mAP\".format(metric_prefix)] = metrics[\"mean_ap\"]\n        else:\n            from nuscenes.eval.tracking.evaluate import TrackingEval\n\n            nusc_eval = TrackingEval(\n                config=self.track3d_eval_configs,\n                result_path=result_path,\n                eval_set=eval_set_map[self.version],\n                output_dir=output_dir,\n                verbose=True,\n                nusc_version=self.version,\n                nusc_dataroot=self.data_root,\n            )\n            metrics = nusc_eval.main()\n\n            # record metrics\n            metrics = mmcv.load(osp.join(output_dir, \"metrics_summary.json\"))\n            print(metrics)\n            detail = dict()\n            metric_prefix = f\"{result_name}_NuScenes\"\n            keys = [\n                \"amota\",\n                \"amotp\",\n                \"recall\",\n                \"motar\",\n                \"gt\",\n                \"mota\",\n                \"motp\",\n                \"mt\",\n                \"ml\",\n                \"faf\",\n                \"tp\",\n                \"fp\",\n                \"fn\",\n                \"ids\",\n                \"frag\",\n                \"tid\",\n                \"lgd\",\n            ]\n            for key in keys:\n                detail[\"{}/{}\".format(metric_prefix, key)] = metrics[key]\n\n        return detail\n\n    def format_results(self, results, jsonfile_prefix=None, tracking=False):\n        assert isinstance(results, list), \"results must be a list\"\n\n        if jsonfile_prefix is None:\n            tmp_dir = tempfile.TemporaryDirectory()\n            jsonfile_prefix = osp.join(tmp_dir.name, \"results\")\n        else:\n            tmp_dir = None\n\n        if not (\"pts_bbox\" in results[0] or \"img_bbox\" in results[0]):\n            result_files = self._format_bbox(\n                results, jsonfile_prefix, tracking=tracking\n            )\n        else:\n            result_files = dict()\n            for name in results[0]:\n                print(f\"\\nFormating bboxes of {name}\")\n                results_ = [out[name] for out in results]\n                tmp_file_ = jsonfile_prefix\n                result_files.update(\n                    {\n                        name: self._format_bbox(\n                            results_, tmp_file_, tracking=tracking\n                        )\n                    }\n                )\n        return result_files, tmp_dir\n\n    def format_map_results(self, results, prefix=None):\n        submissions = {'results': {},}\n        \n        for j, pred in enumerate(results):\n            '''\n            For each case, the result should be formatted as Dict{'vectors': [], 'scores': [], 'labels': []}\n            'vectors': List of vector, each vector is a array([[x1, y1], [x2, y2] ...]),\n                contain all vectors predicted in this sample.\n            'scores: List of score(float), \n                contain scores of all instances in this sample.\n            'labels': List of label(int), \n                contain labels of all instances in this sample.\n            '''\n            if pred is None: # empty prediction\n                continue\n            pred = pred['img_bbox']\n\n            single_case = {'vectors': [], 'scores': [], 'labels': []}\n            token = self.data_infos[j]['token']\n            for i in range(len(pred['scores'])):\n                score = pred['scores'][i]\n                label = pred['labels'][i]\n                vector = pred['vectors'][i]\n\n                # A line should have >=2 points\n                if len(vector) < 2:\n                    continue\n                \n                single_case['vectors'].append(vector)\n                single_case['scores'].append(score)\n                single_case['labels'].append(label)\n            \n            submissions['results'][token] = single_case\n        \n        out_path = osp.join(prefix, 'submission_vector.json')\n        print(f'saving submissions results to {out_path}')\n        os.makedirs(os.path.dirname(out_path), exist_ok=True)\n        mmcv.dump(submissions, out_path)\n        return out_path\n\n    def format_motion_results(self, results, jsonfile_prefix=None, tracking=False, thresh=None):\n        nusc_annos = {}\n        mapped_class_names = self.CLASSES\n\n        print(\"Start to convert detection format...\")\n        for sample_id, det in enumerate(mmcv.track_iter_progress(results)):\n            annos = []\n            boxes = output_to_nusc_box(\n                det['img_bbox'], threshold=None\n            )\n            sample_token = self.data_infos[sample_id][\"token\"]\n            boxes = lidar_nusc_box_to_global(\n                self.data_infos[sample_id],\n                boxes,\n                mapped_class_names,\n                self.det3d_eval_configs,\n                self.det3d_eval_version,\n                filter_with_cls_range=False,\n            )\n            for i, box in enumerate(boxes):\n                if thresh is not None and box.score < thresh:\n                    continue\n                name = mapped_class_names[box.label]\n                if tracking and name in [\n                    \"barrier\",\n                    \"traffic_cone\",\n                    \"construction_vehicle\",\n                ]:\n                    continue\n                if np.sqrt(box.velocity[0] ** 2 + box.velocity[1] ** 2) > 0.2:\n                    if name in [\n                        \"car\",\n                        \"construction_vehicle\",\n                        \"bus\",\n                        \"truck\",\n                        \"trailer\",\n                    ]:\n                        attr = \"vehicle.moving\"\n                    elif name in [\"bicycle\", \"motorcycle\"]:\n                        attr = \"cycle.with_rider\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD_6s.DefaultAttribute[name]\n                else:\n                    if name in [\"pedestrian\"]:\n                        attr = \"pedestrian.standing\"\n                    elif name in [\"bus\"]:\n                        attr = \"vehicle.stopped\"\n                    else:\n                        attr = NuScenes3DDataset_roboAD_6s.DefaultAttribute[name]\n\n                nusc_anno = dict(\n                    sample_token=sample_token,\n                    translation=box.center.tolist(),\n                    size=box.wlh.tolist(),\n                    rotation=box.orientation.elements.tolist(),\n                    velocity=box.velocity[:2].tolist(),\n                )\n                if not tracking:\n                    nusc_anno.update(\n                        dict(\n                            detection_name=name,\n                            detection_score=box.score,\n                            attribute_name=attr,\n                        )\n                    )\n                else:\n                    nusc_anno.update(\n                        dict(\n                            tracking_name=name,\n                            tracking_score=box.score,\n                            tracking_id=str(box.token),\n                        )\n                    )\n                nusc_anno.update(\n                    dict(\n                        trajs=det['img_bbox']['trajs_3d'][i].numpy(),\n                    )\n                )\n                annos.append(nusc_anno)\n            nusc_annos[sample_token] = annos\n        nusc_submissions = {\n            \"meta\": self.modality,\n            \"results\": nusc_annos,\n        }\n\n        return nusc_submissions \n\n    def _evaluate_single_motion(self,\n                         results,\n                         result_path,\n                         logger=None,\n                         metric='bbox',\n                         result_name='pts_bbox'):\n        \"\"\"Evaluation for a single model in nuScenes protocol.\n\n        Args:\n            result_path (str): Path of the result file.\n            logger (logging.Logger | str | None): Logger used for printing\n                related information during evaluation. Default: None.\n            metric (str): Metric name used for evaluation. Default: 'bbox'.\n            result_name (str): Result name in the metric prefix.\n                Default: 'pts_bbox'.\n\n        Returns:\n            dict: Dictionary of evaluation details.\n        \"\"\"\n        from nuscenes import NuScenes\n        from .evaluation.motion.motion_eval_uniad import NuScenesEval as NuScenesEvalMotion\n\n        output_dir = result_path\n        nusc = NuScenes(\n            version=self.version, dataroot=self.data_root, verbose=False)\n        eval_set_map = {\n            'v1.0-mini': 'mini_val',\n            'v1.0-trainval': 'val',\n        }\n        nusc_eval = NuScenesEvalMotion(\n            nusc,\n            config=copy.deepcopy(self.det3d_eval_configs),\n            result_path=results,\n            eval_set=eval_set_map[self.version],\n            output_dir=output_dir,\n            verbose=False,\n            seconds=6)\n        metrics = nusc_eval.main(render_curves=False)\n        \n        MOTION_METRICS = ['EPA', 'min_ade_err', 'min_fde_err', 'miss_rate_err']\n        class_names = ['car', 'pedestrian']\n\n        table = prettytable.PrettyTable()\n        table.field_names = [\"class names\"] + MOTION_METRICS\n        for class_name in class_names:\n            row_data = [class_name]\n            for m in MOTION_METRICS:\n                row_data.append('%.4f' % metrics[f'{class_name}_{m}'])\n            table.add_row(row_data)\n        print_log('\\n'+str(table), logger=logger)\n        return metrics\n\n    def evaluate(\n        self,\n        results,\n        eval_mode,\n        metric=None,\n        logger=None,\n        jsonfile_prefix=None,\n        result_names=[\"img_bbox\"],\n        show=False,\n        out_dir=None,\n        pipeline=None,\n    ):\n        \n        res_path = \"results.pkl\" if \"trainval\" in self.version else \"results_mini.pkl\"\n        res_path = osp.join(self.work_dir, res_path)\n        print('All Results write to', res_path)\n        mmcv.dump(results, res_path)\n\n        results_dict = dict()\n        if eval_mode['with_det']:\n            self.tracking = eval_mode[\"with_tracking\"]\n            self.tracking_threshold = eval_mode[\"tracking_threshold\"]\n            for metric in [\"detection\", \"tracking\"]:\n                tracking = metric == \"tracking\"\n                if tracking and not self.tracking:\n                    continue\n                result_files, tmp_dir = self.format_results(\n                    results, jsonfile_prefix=self.work_dir, tracking=tracking\n                )\n\n                if isinstance(result_files, dict):\n                    for name in result_names:\n                        ret_dict = self._evaluate_single(\n                            result_files[name], tracking=tracking\n                        )\n                    results_dict.update(ret_dict)\n                elif isinstance(result_files, str):\n                    ret_dict = self._evaluate_single(\n                        result_files, tracking=tracking\n                    )\n                    results_dict.update(ret_dict)\n\n                if tmp_dir is not None:\n                    tmp_dir.cleanup()\n\n        if eval_mode['with_map']:\n            from .evaluation.map.vector_eval import VectorEvaluate\n            self.map_evaluator = VectorEvaluate(self.eval_config)\n            result_path = self.format_map_results(results, prefix=self.work_dir)\n            map_results_dict = self.map_evaluator.evaluate(result_path, logger=logger)\n            results_dict.update(map_results_dict)\n\n        if eval_mode['with_motion']:\n            thresh = eval_mode[\"motion_threshhold\"]\n            result_files = self.format_motion_results(results, jsonfile_prefix=self.work_dir, thresh=thresh)\n            motion_results_dict = self._evaluate_single_motion(result_files, self.work_dir, logger=logger)\n            results_dict.update(motion_results_dict)\n        \n        if eval_mode['with_planning']:\n            from .evaluation.planning.planning_eval_roboAD_6s import planning_eval_roboAD_6s\n            planning_results_dict = planning_eval_roboAD_6s(results, self.eval_config, logger=logger)\n            results_dict.update(planning_results_dict)\n\n        if show or out_dir:\n            self.show(results, save_dir=out_dir, show=show, pipeline=pipeline)\n        \n        # print main metrics for recording\n        metric_str = '\\n'\n        if \"img_bbox_NuScenes/NDS\" in results_dict:\n            metric_str += f'mAP: {results_dict.get(\"img_bbox_NuScenes/mAP\"):.4f}\\n'\n            metric_str += f'mATE: {results_dict.get(\"img_bbox_NuScenes/mATE\"):.4f}\\n'\n            metric_str += f'mASE: {results_dict.get(\"img_bbox_NuScenes/mASE\"):.4f}\\n'\n            metric_str += f'mAOE: {results_dict.get(\"img_bbox_NuScenes/mAOE\"):.4f}\\n' \n            metric_str += f'mAVE: {results_dict.get(\"img_bbox_NuScenes/mAVE\"):.4f}\\n' \n            metric_str += f'mAAE: {results_dict.get(\"img_bbox_NuScenes/mAAE\"):.4f}\\n' \n            metric_str += f'NDS: {results_dict.get(\"img_bbox_NuScenes/NDS\"):.4f}\\n\\n'\n        \n        if \"img_bbox_NuScenes/amota\" in results_dict:\n            metric_str += f'AMOTA: {results_dict[\"img_bbox_NuScenes/amota\"]:.4f}\\n' \n            metric_str += f'AMOTP: {results_dict[\"img_bbox_NuScenes/amotp\"]:.4f}\\n' \n            metric_str += f'RECALL: {results_dict[\"img_bbox_NuScenes/recall\"]:.4f}\\n' \n            metric_str += f'MOTAR: {results_dict[\"img_bbox_NuScenes/motar\"]:.4f}\\n' \n            metric_str += f'MOTA: {results_dict[\"img_bbox_NuScenes/mota\"]:.4f}\\n' \n            metric_str += f'MOTP: {results_dict[\"img_bbox_NuScenes/motp\"]:.4f}\\n' \n            metric_str += f'IDS: {results_dict[\"img_bbox_NuScenes/ids\"]}\\n\\n' \n        \n        if \"mAP_normal\" in results_dict:\n            metric_str += f'ped_crossing= {results_dict[\"ped_crossing\"]:.4f}\\n' \n            metric_str += f'divider= {results_dict[\"divider\"]:.4f}\\n' \n            metric_str += f'boundary= {results_dict[\"boundary\"]:.4f}\\n' \n            metric_str += f'mAP_normal= {results_dict[\"mAP_normal\"]:.4f}\\n\\n' \n\n        if \"car_EPA\" in results_dict:\n            metric_str += f'Car / Ped\\n' \n            metric_str += f'epa= {results_dict[\"car_EPA\"]:.4f} / {results_dict[\"pedestrian_EPA\"]:.4f}\\n'\n            metric_str += f'ade= {results_dict[\"car_min_ade_err\"]:.4f} / {results_dict[\"pedestrian_min_ade_err\"]:.4f}\\n'\n            metric_str += f'fde= {results_dict[\"car_min_fde_err\"]:.4f} / {results_dict[\"pedestrian_min_fde_err\"]:.4f}\\n'\n            metric_str += f'mr= {results_dict[\"car_miss_rate_err\"]:.4f} / {results_dict[\"pedestrian_miss_rate_err\"]:.4f}\\n\\n' \n\n        if \"L2\" in results_dict:\n            metric_str += f'obj_box_col: {(results_dict[\"obj_box_col\"]*100):.3f}%\\n'\n            metric_str += f'L2: {results_dict[\"L2\"]:.4f}\\n\\n'\n        \n        print_log(metric_str, logger=logger)\n        return results_dict\n\n    def show(self, results, save_dir=None, show=False, pipeline=None):\n        save_dir = \"./\" if save_dir is None else save_dir\n        save_dir = os.path.join(save_dir, \"visual\")\n        print_log(os.path.abspath(save_dir))\n        pipeline = Compose(pipeline)\n        if not os.path.exists(save_dir):\n            os.makedirs(save_dir)\n\n        fourcc = cv2.VideoWriter_fourcc(*\"MJPG\")\n        videoWriter = None\n\n        for i, result in enumerate(results):\n            if \"img_bbox\" in result.keys():\n                result = result[\"img_bbox\"]\n            data_info = pipeline(self.get_data_info(i))\n            imgs = []\n\n            raw_imgs = data_info[\"img\"]\n            lidar2img = data_info[\"img_metas\"].data[\"lidar2img\"]\n            pred_bboxes_3d = result[\"boxes_3d\"][\n                result[\"scores_3d\"] > self.vis_score_threshold\n            ]\n            if \"instance_ids\" in result and self.tracking:\n                color = []\n                for id in result[\"instance_ids\"].cpu().numpy().tolist():\n                    color.append(\n                        self.ID_COLOR_MAP[int(id % len(self.ID_COLOR_MAP))]\n                    )\n            elif \"labels_3d\" in result:\n                color = []\n                for id in result[\"labels_3d\"].cpu().numpy().tolist():\n                    color.append(self.ID_COLOR_MAP[id])\n            else:\n                color = (255, 0, 0)\n\n            # ===== draw boxes_3d to images =====\n            for j, img_origin in enumerate(raw_imgs):\n                img = img_origin.copy()\n                if len(pred_bboxes_3d) != 0:\n                    img = draw_lidar_bbox3d_on_img(\n                        pred_bboxes_3d,\n                        img,\n                        lidar2img[j],\n                        img_metas=None,\n                        color=color,\n                        thickness=3,\n                    )\n                imgs.append(img)\n\n            # ===== draw boxes_3d to BEV =====\n            bev = draw_lidar_bbox3d_on_bev(\n                pred_bboxes_3d,\n                bev_size=img.shape[0] * 2,\n                color=color,\n            )\n\n            # ===== put text and concat =====\n            for j, name in enumerate(\n                [\n                    \"front\",\n                    \"front right\",\n                    \"front left\",\n                    \"rear\",\n                    \"rear left\",\n                    \"rear right\",\n                ]\n            ):\n                imgs[j] = cv2.rectangle(\n                    imgs[j],\n                    (0, 0),\n                    (440, 80),\n                    color=(255, 255, 255),\n                    thickness=-1,\n                )\n                w, h = cv2.getTextSize(name, cv2.FONT_HERSHEY_SIMPLEX, 2, 2)[0]\n                text_x = int(220 - w / 2)\n                text_y = int(40 + h / 2)\n\n                imgs[j] = cv2.putText(\n                    imgs[j],\n                    name,\n                    (text_x, text_y),\n                    cv2.FONT_HERSHEY_SIMPLEX,\n                    2,\n                    (0, 0, 0),\n                    2,\n                    cv2.LINE_AA,\n                )\n            image = np.concatenate(\n                [\n                    np.concatenate([imgs[2], imgs[0], imgs[1]], axis=1),\n                    np.concatenate([imgs[5], imgs[3], imgs[4]], axis=1),\n                ],\n                axis=0,\n            )\n            image = np.concatenate([image, bev], axis=1)\n\n            # ===== save video =====\n            if videoWriter is None:\n                videoWriter = cv2.VideoWriter(\n                    os.path.join(save_dir, \"video.avi\"),\n                    fourcc,\n                    7,\n                    image.shape[:2][::-1],\n                )\n            cv2.imwrite(os.path.join(save_dir, f\"{i}.jpg\"), image)\n            videoWriter.write(image)\n        videoWriter.release()\n\n\ndef output_to_nusc_box(detection, threshold=None):\n    box3d = detection[\"boxes_3d\"]\n    scores = detection[\"scores_3d\"].numpy()\n    labels = detection[\"labels_3d\"].numpy()\n    if \"instance_ids\" in detection:\n        ids = detection[\"instance_ids\"]  # .numpy()\n    if threshold is not None:\n        if \"cls_scores\" in detection:\n            mask = detection[\"cls_scores\"].numpy() >= threshold\n        else:\n            mask = scores >= threshold\n        box3d = box3d[mask]\n        scores = scores[mask]\n        labels = labels[mask]\n        ids = ids[mask]\n\n    if hasattr(box3d, \"gravity_center\"):\n        box_gravity_center = box3d.gravity_center.numpy()\n        box_dims = box3d.dims.numpy()\n        nus_box_dims = box_dims[:, [1, 0, 2]]\n        box_yaw = box3d.yaw.numpy()\n    else:\n        box3d = box3d.numpy()\n        box_gravity_center = box3d[..., :3].copy()\n        box_dims = box3d[..., 3:6].copy()\n        nus_box_dims = box_dims[..., [1, 0, 2]]\n        box_yaw = box3d[..., 6].copy()\n\n    # TODO: check whether this is necessary\n    # with dir_offset & dir_limit in the head\n    # box_yaw = -box_yaw - np.pi / 2\n\n    box_list = []\n    for i in range(len(box3d)):\n        quat = pyquaternion.Quaternion(axis=[0, 0, 1], radians=box_yaw[i])\n        if hasattr(box3d, \"gravity_center\"):\n            velocity = (*box3d.tensor[i, 7:9], 0.0)\n        else:\n            velocity = (*box3d[i, 7:9], 0.0)\n        box = NuScenesBox(\n            box_gravity_center[i],\n            nus_box_dims[i],\n            quat,\n            label=labels[i],\n            score=scores[i],\n            velocity=velocity,\n        )\n        if \"instance_ids\" in detection:\n            box.token = ids[i]\n        box_list.append(box)\n    return box_list\n\n\ndef lidar_nusc_box_to_global(\n    info,\n    boxes,\n    classes,\n    eval_configs,\n    eval_version=\"detection_cvpr_2019\",\n    filter_with_cls_range=True,\n):\n    box_list = []\n    for i, box in enumerate(boxes):\n        # Move box to ego vehicle coord system\n        box.rotate(pyquaternion.Quaternion(info[\"lidar2ego_rotation\"]))\n        box.translate(np.array(info[\"lidar2ego_translation\"]))\n        # filter det in ego.\n        if filter_with_cls_range:\n            cls_range_map = eval_configs.class_range\n            radius = np.linalg.norm(box.center[:2], 2)\n            det_range = cls_range_map[classes[box.label]]\n            if radius > det_range:\n                continue\n        # Move box to global coord system\n        box.rotate(pyquaternion.Quaternion(info[\"ego2global_rotation\"]))\n        box.translate(np.array(info[\"ego2global_translation\"]))\n        box_list.append(box)\n    return box_list\n\n\ndef get_T_global(info):\n    lidar2ego = np.eye(4)\n    lidar2ego[:3, :3] = pyquaternion.Quaternion(\n        info[\"lidar2ego_rotation\"]\n    ).rotation_matrix\n    lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n    ego2global = np.eye(4)\n    ego2global[:3, :3] = pyquaternion.Quaternion(\n        info[\"ego2global_rotation\"]\n    ).rotation_matrix\n    ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n    return ego2global @ lidar2ego"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/pipelines/__init__.py",
    "content": "from .transform import (\n    InstanceNameFilter,\n    CircleObjectRangeFilter,\n    NormalizeMultiviewImage,\n    NuScenesSparse4DAdaptor,\n    MultiScaleDepthMapGenerator,\n)\nfrom .augment import (\n    ResizeCropFlipImage,\n    BBoxRotation,\n    PhotoMetricDistortionMultiViewImage,\n)\nfrom .loading import LoadMultiViewImageFromFiles, LoadPointsFromFile\nfrom .vectorize import VectorizeMap\n\n__all__ = [\n    \"InstanceNameFilter\",\n    \"ResizeCropFlipImage\",\n    \"BBoxRotation\",\n    \"CircleObjectRangeFilter\",\n    \"MultiScaleDepthMapGenerator\",\n    \"NormalizeMultiviewImage\",\n    \"PhotoMetricDistortionMultiViewImage\",\n    \"NuScenesSparse4DAdaptor\",\n    \"LoadMultiViewImageFromFiles\",\n    \"LoadPointsFromFile\",\n    \"VectorizeMap\",\n]\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/pipelines/augment.py",
    "content": "import torch\n\nimport numpy as np\nfrom numpy import random\nimport mmcv\nfrom mmdet.datasets.builder import PIPELINES\nfrom PIL import Image\n\n\n@PIPELINES.register_module()\nclass ResizeCropFlipImage(object):\n    def __call__(self, results):\n        aug_config = results.get(\"aug_config\")\n        if aug_config is None:\n            return results\n        imgs = results[\"img\"]\n        N = len(imgs)\n        new_imgs = []\n        for i in range(N):\n            img, mat = self._img_transform(\n                np.uint8(imgs[i]), aug_config,\n            )\n            new_imgs.append(np.array(img).astype(np.float32))\n            results[\"lidar2img\"][i] = mat @ results[\"lidar2img\"][i]\n            if \"cam_intrinsic\" in results:\n                results[\"cam_intrinsic\"][i][:3, :3] *= aug_config[\"resize\"]\n                # results[\"cam_intrinsic\"][i][:3, :3] = (\n                #     mat[:3, :3] @ results[\"cam_intrinsic\"][i][:3, :3]\n                # )\n\n        results[\"img\"] = new_imgs\n        results[\"img_shape\"] = [x.shape[:2] for x in new_imgs]\n        return results\n\n    def _img_transform(self, img, aug_configs):\n        H, W = img.shape[:2]\n        resize = aug_configs.get(\"resize\", 1)\n        resize_dims = (int(W * resize), int(H * resize))\n        crop = aug_configs.get(\"crop\", [0, 0, *resize_dims])\n        flip = aug_configs.get(\"flip\", False)\n        rotate = aug_configs.get(\"rotate\", 0)\n\n        origin_dtype = img.dtype\n        if origin_dtype != np.uint8:\n            min_value = img.min()\n            max_vaule = img.max()\n            scale = 255 / (max_vaule - min_value)\n            img = (img - min_value) * scale\n            img = np.uint8(img)\n        img = Image.fromarray(img)\n        img = img.resize(resize_dims).crop(crop)\n        if flip:\n            img = img.transpose(method=Image.FLIP_LEFT_RIGHT)\n        img = img.rotate(rotate)\n        img = np.array(img).astype(np.float32)\n        if origin_dtype != np.uint8:\n            img = img.astype(np.float32)\n            img = img / scale + min_value\n\n        transform_matrix = np.eye(3)\n        transform_matrix[:2, :2] *= resize\n        transform_matrix[:2, 2] -= np.array(crop[:2])\n        if flip:\n            flip_matrix = np.array(\n                [[-1, 0, crop[2] - crop[0]], [0, 1, 0], [0, 0, 1]]\n            )\n            transform_matrix = flip_matrix @ transform_matrix\n        rotate = rotate / 180 * np.pi\n        rot_matrix = np.array(\n            [\n                [np.cos(rotate), np.sin(rotate), 0],\n                [-np.sin(rotate), np.cos(rotate), 0],\n                [0, 0, 1],\n            ]\n        )\n        rot_center = np.array([crop[2] - crop[0], crop[3] - crop[1]]) / 2\n        rot_matrix[:2, 2] = -rot_matrix[:2, :2] @ rot_center + rot_center\n        transform_matrix = rot_matrix @ transform_matrix\n        extend_matrix = np.eye(4)\n        extend_matrix[:3, :3] = transform_matrix\n        return img, extend_matrix\n\n\n@PIPELINES.register_module()\nclass BBoxRotation(object):\n    def __call__(self, results):\n        angle = results[\"aug_config\"][\"rotate_3d\"]\n        rot_cos = np.cos(angle)\n        rot_sin = np.sin(angle)\n\n        rot_mat = np.array(\n            [\n                [rot_cos, -rot_sin, 0, 0],\n                [rot_sin, rot_cos, 0, 0],\n                [0, 0, 1, 0],\n                [0, 0, 0, 1],\n            ]\n        )\n        rot_mat_inv = np.linalg.inv(rot_mat)\n\n        num_view = len(results[\"lidar2img\"])\n        for view in range(num_view):\n            results[\"lidar2img\"][view] = (\n                results[\"lidar2img\"][view] @ rot_mat_inv\n            )\n        if \"lidar2global\" in results:\n            results[\"lidar2global\"] = results[\"lidar2global\"] @ rot_mat_inv\n        if \"gt_bboxes_3d\" in results:\n            results[\"gt_bboxes_3d\"] = self.box_rotate(\n                results[\"gt_bboxes_3d\"], angle\n            )\n        return results\n\n    @staticmethod\n    def box_rotate(bbox_3d, angle):\n        rot_cos = np.cos(angle)\n        rot_sin = np.sin(angle)\n        rot_mat_T = np.array(\n            [[rot_cos, rot_sin, 0], [-rot_sin, rot_cos, 0], [0, 0, 1]]\n        )\n        bbox_3d[:, :3] = bbox_3d[:, :3] @ rot_mat_T\n        bbox_3d[:, 6] += angle\n        if bbox_3d.shape[-1] > 7:\n            vel_dims = bbox_3d[:, 7:].shape[-1]\n            bbox_3d[:, 7:] = bbox_3d[:, 7:] @ rot_mat_T[:vel_dims, :vel_dims]\n        return bbox_3d\n\n\n@PIPELINES.register_module()\nclass PhotoMetricDistortionMultiViewImage:\n    \"\"\"Apply photometric distortion to image sequentially, every transformation\n    is applied with a probability of 0.5. The position of random contrast is in\n    second or second to last.\n    1. random brightness\n    2. random contrast (mode 0)\n    3. convert color from BGR to HSV\n    4. random saturation\n    5. random hue\n    6. convert color from HSV to BGR\n    7. random contrast (mode 1)\n    8. randomly swap channels\n    Args:\n        brightness_delta (int): delta of brightness.\n        contrast_range (tuple): range of contrast.\n        saturation_range (tuple): range of saturation.\n        hue_delta (int): delta of hue.\n    \"\"\"\n\n    def __init__(\n        self,\n        brightness_delta=32,\n        contrast_range=(0.5, 1.5),\n        saturation_range=(0.5, 1.5),\n        hue_delta=18,\n    ):\n        self.brightness_delta = brightness_delta\n        self.contrast_lower, self.contrast_upper = contrast_range\n        self.saturation_lower, self.saturation_upper = saturation_range\n        self.hue_delta = hue_delta\n\n    def __call__(self, results):\n        \"\"\"Call function to perform photometric distortion on images.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Result dict with images distorted.\n        \"\"\"\n        imgs = results[\"img\"]\n        new_imgs = []\n        for img in imgs:\n            assert img.dtype == np.float32, (\n                \"PhotoMetricDistortion needs the input image of dtype np.float32,\"\n                ' please set \"to_float32=True\" in \"LoadImageFromFile\" pipeline'\n            )\n            # random brightness\n            if random.randint(2):\n                delta = random.uniform(\n                    -self.brightness_delta, self.brightness_delta\n                )\n                img += delta\n\n            # mode == 0 --> do random contrast first\n            # mode == 1 --> do random contrast last\n            mode = random.randint(2)\n            if mode == 1:\n                if random.randint(2):\n                    alpha = random.uniform(\n                        self.contrast_lower, self.contrast_upper\n                    )\n                    img *= alpha\n\n            # convert color from BGR to HSV\n            img = mmcv.bgr2hsv(img)\n\n            # random saturation\n            if random.randint(2):\n                img[..., 1] *= random.uniform(\n                    self.saturation_lower, self.saturation_upper\n                )\n\n            # random hue\n            if random.randint(2):\n                img[..., 0] += random.uniform(-self.hue_delta, self.hue_delta)\n                img[..., 0][img[..., 0] > 360] -= 360\n                img[..., 0][img[..., 0] < 0] += 360\n\n            # convert color from HSV to BGR\n            img = mmcv.hsv2bgr(img)\n\n            # random contrast\n            if mode == 0:\n                if random.randint(2):\n                    alpha = random.uniform(\n                        self.contrast_lower, self.contrast_upper\n                    )\n                    img *= alpha\n\n            # randomly swap channels\n            if random.randint(2):\n                img = img[..., random.permutation(3)]\n            new_imgs.append(img)\n        results[\"img\"] = new_imgs\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f\"(\\nbrightness_delta={self.brightness_delta},\\n\"\n        repr_str += \"contrast_range=\"\n        repr_str += f\"{(self.contrast_lower, self.contrast_upper)},\\n\"\n        repr_str += \"saturation_range=\"\n        repr_str += f\"{(self.saturation_lower, self.saturation_upper)},\\n\"\n        repr_str += f\"hue_delta={self.hue_delta})\"\n        return repr_str\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/pipelines/loading.py",
    "content": "import numpy as np\nimport mmcv\nfrom mmdet.datasets.builder import PIPELINES\n\n\n@PIPELINES.register_module()\nclass LoadMultiViewImageFromFiles(object):\n    \"\"\"Load multi channel images from a list of separate channel files.\n\n    Expects results['img_filename'] to be a list of filenames.\n\n    Args:\n        to_float32 (bool, optional): Whether to convert the img to float32.\n            Defaults to False.\n        color_type (str, optional): Color type of the file.\n            Defaults to 'unchanged'.\n    \"\"\"\n\n    def __init__(self, to_float32=False, color_type=\"unchanged\"):\n        self.to_float32 = to_float32\n        self.color_type = color_type\n\n    def __call__(self, results):\n        \"\"\"Call function to load multi-view image from files.\n\n        Args:\n            results (dict): Result dict containing multi-view image filenames.\n\n        Returns:\n            dict: The result dict containing the multi-view image data.\n                Added keys and values are described below.\n\n                - filename (str): Multi-view image filenames.\n                - img (np.ndarray): Multi-view image arrays.\n                - img_shape (tuple[int]): Shape of multi-view image arrays.\n                - ori_shape (tuple[int]): Shape of original image arrays.\n                - pad_shape (tuple[int]): Shape of padded image arrays.\n                - scale_factor (float): Scale factor.\n                - img_norm_cfg (dict): Normalization configuration of images.\n        \"\"\"\n        filename = results[\"img_filename\"]\n        # img is of shape (h, w, c, num_views)\n        img = np.stack(\n            [mmcv.imread(name, self.color_type) for name in filename], axis=-1\n        )\n        if self.to_float32:\n            img = img.astype(np.float32)\n        results[\"filename\"] = filename\n        # unravel to list, see `DefaultFormatBundle` in formatting.py\n        # which will transpose each image separately and then stack into array\n        results[\"img\"] = [img[..., i] for i in range(img.shape[-1])]\n        results[\"img_shape\"] = img.shape\n        results[\"ori_shape\"] = img.shape\n        # Set initial values for default meta_keys\n        results[\"pad_shape\"] = img.shape\n        results[\"scale_factor\"] = 1.0\n        num_channels = 1 if len(img.shape) < 3 else img.shape[2]\n        results[\"img_norm_cfg\"] = dict(\n            mean=np.zeros(num_channels, dtype=np.float32),\n            std=np.ones(num_channels, dtype=np.float32),\n            to_rgb=False,\n        )\n        return results\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f\"(to_float32={self.to_float32}, \"\n        repr_str += f\"color_type='{self.color_type}')\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass LoadPointsFromFile(object):\n    \"\"\"Load Points From File.\n\n    Load points from file.\n\n    Args:\n        coord_type (str): The type of coordinates of points cloud.\n            Available options includes:\n            - 'LIDAR': Points in LiDAR coordinates.\n            - 'DEPTH': Points in depth coordinates, usually for indoor dataset.\n            - 'CAMERA': Points in camera coordinates.\n        load_dim (int, optional): The dimension of the loaded points.\n            Defaults to 6.\n        use_dim (list[int], optional): Which dimensions of the points to use.\n            Defaults to [0, 1, 2]. For KITTI dataset, set use_dim=4\n            or use_dim=[0, 1, 2, 3] to use the intensity dimension.\n        shift_height (bool, optional): Whether to use shifted height.\n            Defaults to False.\n        use_color (bool, optional): Whether to use color features.\n            Defaults to False.\n        file_client_args (dict, optional): Config dict of file clients,\n            refer to\n            https://github.com/open-mmlab/mmcv/blob/master/mmcv/fileio/file_client.py\n            for more details. Defaults to dict(backend='disk').\n    \"\"\"\n\n    def __init__(\n        self,\n        coord_type,\n        load_dim=6,\n        use_dim=[0, 1, 2],\n        shift_height=False,\n        use_color=False,\n        file_client_args=dict(backend=\"disk\"),\n    ):\n        self.shift_height = shift_height\n        self.use_color = use_color\n        if isinstance(use_dim, int):\n            use_dim = list(range(use_dim))\n        assert (\n            max(use_dim) < load_dim\n        ), f\"Expect all used dimensions < {load_dim}, got {use_dim}\"\n        assert coord_type in [\"CAMERA\", \"LIDAR\", \"DEPTH\"]\n\n        self.coord_type = coord_type\n        self.load_dim = load_dim\n        self.use_dim = use_dim\n        self.file_client_args = file_client_args.copy()\n        self.file_client = None\n\n    def _load_points(self, pts_filename):\n        \"\"\"Private function to load point clouds data.\n\n        Args:\n            pts_filename (str): Filename of point clouds data.\n\n        Returns:\n            np.ndarray: An array containing point clouds data.\n        \"\"\"\n        if self.file_client is None:\n            self.file_client = mmcv.FileClient(**self.file_client_args)\n        try:\n            pts_bytes = self.file_client.get(pts_filename)\n            points = np.frombuffer(pts_bytes, dtype=np.float32)\n        except ConnectionError:\n            mmcv.check_file_exist(pts_filename)\n            if pts_filename.endswith(\".npy\"):\n                points = np.load(pts_filename)\n            else:\n                points = np.fromfile(pts_filename, dtype=np.float32)\n\n        return points\n\n    def __call__(self, results):\n        \"\"\"Call function to load points data from file.\n\n        Args:\n            results (dict): Result dict containing point clouds data.\n\n        Returns:\n            dict: The result dict containing the point clouds data.\n                Added key and value are described below.\n\n                - points (:obj:`BasePoints`): Point clouds data.\n        \"\"\"\n        pts_filename = results[\"pts_filename\"]\n        points = self._load_points(pts_filename)\n        points = points.reshape(-1, self.load_dim)\n        points = points[:, self.use_dim]\n        attribute_dims = None\n\n        if self.shift_height:\n            floor_height = np.percentile(points[:, 2], 0.99)\n            height = points[:, 2] - floor_height\n            points = np.concatenate(\n                [points[:, :3], np.expand_dims(height, 1), points[:, 3:]], 1\n            )\n            attribute_dims = dict(height=3)\n\n        if self.use_color:\n            assert len(self.use_dim) >= 6\n            if attribute_dims is None:\n                attribute_dims = dict()\n            attribute_dims.update(\n                dict(\n                    color=[\n                        points.shape[1] - 3,\n                        points.shape[1] - 2,\n                        points.shape[1] - 1,\n                    ]\n                )\n            )\n\n        results[\"points\"] = points\n        return results\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/pipelines/transform.py",
    "content": "import numpy as np\nimport mmcv\nfrom mmcv.parallel import DataContainer as DC\nfrom mmdet.datasets.builder import PIPELINES\nfrom mmdet.datasets.pipelines import to_tensor\n\n\n@PIPELINES.register_module()\nclass MultiScaleDepthMapGenerator(object):\n    def __init__(self, downsample=1, max_depth=60):\n        if not isinstance(downsample, (list, tuple)):\n            downsample = [downsample]\n        self.downsample = downsample\n        self.max_depth = max_depth\n\n    def __call__(self, input_dict):\n        points = input_dict[\"points\"][..., :3, None]\n        gt_depth = []\n        for i, lidar2img in enumerate(input_dict[\"lidar2img\"]):\n            H, W = input_dict[\"img_shape\"][i][:2]\n\n            pts_2d = (\n                np.squeeze(lidar2img[:3, :3] @ points, axis=-1)\n                + lidar2img[:3, 3]\n            )\n            pts_2d[:, :2] /= pts_2d[:, 2:3]\n            U = np.round(pts_2d[:, 0]).astype(np.int32)\n            V = np.round(pts_2d[:, 1]).astype(np.int32)\n            depths = pts_2d[:, 2]\n            mask = np.logical_and.reduce(\n                [\n                    V >= 0,\n                    V < H,\n                    U >= 0,\n                    U < W,\n                    depths >= 0.1,\n                    # depths <= self.max_depth,\n                ]\n            )\n            V, U, depths = V[mask], U[mask], depths[mask]\n            sort_idx = np.argsort(depths)[::-1]\n            V, U, depths = V[sort_idx], U[sort_idx], depths[sort_idx]\n            depths = np.clip(depths, 0.1, self.max_depth)\n            for j, downsample in enumerate(self.downsample):\n                if len(gt_depth) < j + 1:\n                    gt_depth.append([])\n                h, w = (int(H / downsample), int(W / downsample))\n                u = np.floor(U / downsample).astype(np.int32)\n                v = np.floor(V / downsample).astype(np.int32)\n                depth_map = np.ones([h, w], dtype=np.float32) * -1\n                depth_map[v, u] = depths\n                gt_depth[j].append(depth_map)\n\n        input_dict[\"gt_depth\"] = [np.stack(x) for x in gt_depth]\n        return input_dict\n\n\n@PIPELINES.register_module()\nclass NuScenesSparse4DAdaptor(object):\n    def __init(self):\n        pass\n\n    def __call__(self, input_dict):\n        input_dict[\"projection_mat\"] = np.float32(\n            np.stack(input_dict[\"lidar2img\"])\n        )\n        input_dict[\"image_wh\"] = np.ascontiguousarray(\n            np.array(input_dict[\"img_shape\"], dtype=np.float32)[:, :2][:, ::-1]\n        )\n        input_dict[\"T_global_inv\"] = np.linalg.inv(input_dict[\"lidar2global\"])\n        input_dict[\"T_global\"] = input_dict[\"lidar2global\"]\n        if \"cam_intrinsic\" in input_dict:\n            input_dict[\"cam_intrinsic\"] = np.float32(\n                np.stack(input_dict[\"cam_intrinsic\"])\n            )\n            input_dict[\"focal\"] = input_dict[\"cam_intrinsic\"][..., 0, 0]\n        if \"instance_inds\" in input_dict:\n            input_dict[\"instance_id\"] = input_dict[\"instance_inds\"]\n\n        if \"gt_bboxes_3d\" in input_dict:\n            input_dict[\"gt_bboxes_3d\"][:, 6] = self.limit_period(\n                input_dict[\"gt_bboxes_3d\"][:, 6], offset=0.5, period=2 * np.pi\n            )\n            input_dict[\"gt_bboxes_3d\"] = DC(\n                to_tensor(input_dict[\"gt_bboxes_3d\"]).float()\n            )\n        if \"gt_labels_3d\" in input_dict:\n            input_dict[\"gt_labels_3d\"] = DC(\n                to_tensor(input_dict[\"gt_labels_3d\"]).long()\n            )\n\n        imgs = [img.transpose(2, 0, 1) for img in input_dict[\"img\"]]\n        imgs = np.ascontiguousarray(np.stack(imgs, axis=0))\n        input_dict[\"img\"] = DC(to_tensor(imgs), stack=True)\n\n        for key in [\n            'gt_map_labels', \n            'gt_map_pts',\n            'gt_agent_fut_trajs',\n            'gt_agent_fut_masks',\n        ]:\n            if key not in input_dict:\n                continue\n            input_dict[key] = DC(to_tensor(input_dict[key]), stack=False, cpu_only=False) \n\n        for key in [\n            'gt_ego_fut_trajs',\n            'gt_ego_fut_masks',\n            'gt_ego_fut_cmd',\n            'ego_status',\n        ]:\n            if key not in input_dict:\n                continue\n            input_dict[key] = DC(to_tensor(input_dict[key]), stack=True, cpu_only=False, pad_dims=None)\n        \n        return input_dict\n\n    def limit_period(\n        self, val: np.ndarray, offset: float = 0.5, period: float = np.pi\n    ) -> np.ndarray:\n        limited_val = val - np.floor(val / period + offset) * period\n        return limited_val\n\n\n@PIPELINES.register_module()\nclass InstanceNameFilter(object):\n    \"\"\"Filter GT objects by their names.\n\n    Args:\n        classes (list[str]): List of class names to be kept for training.\n    \"\"\"\n\n    def __init__(self, classes):\n        self.classes = classes\n        self.labels = list(range(len(self.classes)))\n\n    def __call__(self, input_dict):\n        \"\"\"Call function to filter objects by their names.\n\n        Args:\n            input_dict (dict): Result dict from loading pipeline.\n\n        Returns:\n            dict: Results after filtering, 'gt_bboxes_3d', 'gt_labels_3d' \\\n                keys are updated in the result dict.\n        \"\"\"\n        gt_labels_3d = input_dict[\"gt_labels_3d\"]\n        gt_bboxes_mask = np.array(\n            [n in self.labels for n in gt_labels_3d], dtype=np.bool_\n        )\n        input_dict[\"gt_bboxes_3d\"] = input_dict[\"gt_bboxes_3d\"][gt_bboxes_mask]\n        input_dict[\"gt_labels_3d\"] = input_dict[\"gt_labels_3d\"][gt_bboxes_mask]\n        if \"instance_inds\" in input_dict:\n            input_dict[\"instance_inds\"] = input_dict[\"instance_inds\"][gt_bboxes_mask]\n        if \"gt_agent_fut_trajs\" in input_dict:\n            input_dict[\"gt_agent_fut_trajs\"] = input_dict[\"gt_agent_fut_trajs\"][gt_bboxes_mask]\n            input_dict[\"gt_agent_fut_masks\"] = input_dict[\"gt_agent_fut_masks\"][gt_bboxes_mask]\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f\"(classes={self.classes})\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass CircleObjectRangeFilter(object):\n    def __init__(\n        self, class_dist_thred=[52.5] * 5 + [31.5] + [42] * 3 + [31.5]\n    ):\n        self.class_dist_thred = class_dist_thred\n\n    def __call__(self, input_dict):\n        gt_bboxes_3d = input_dict[\"gt_bboxes_3d\"]\n        gt_labels_3d = input_dict[\"gt_labels_3d\"]\n        dist = np.sqrt(\n            np.sum(gt_bboxes_3d[:, :2] ** 2, axis=-1)\n        )\n        mask = np.array([False] * len(dist))\n        for label_idx, dist_thred in enumerate(self.class_dist_thred):\n            mask = np.logical_or(\n                mask,\n                np.logical_and(gt_labels_3d == label_idx, dist <= dist_thred),\n            )\n\n        gt_bboxes_3d = gt_bboxes_3d[mask]\n        gt_labels_3d = gt_labels_3d[mask]\n\n        input_dict[\"gt_bboxes_3d\"] = gt_bboxes_3d\n        input_dict[\"gt_labels_3d\"] = gt_labels_3d\n        if \"instance_inds\" in input_dict:\n            input_dict[\"instance_inds\"] = input_dict[\"instance_inds\"][mask]\n        if \"gt_agent_fut_trajs\" in input_dict:\n            input_dict[\"gt_agent_fut_trajs\"] = input_dict[\"gt_agent_fut_trajs\"][mask]\n            input_dict[\"gt_agent_fut_masks\"] = input_dict[\"gt_agent_fut_masks\"][mask]\n        return input_dict\n\n    def __repr__(self):\n        \"\"\"str: Return a string that describes the module.\"\"\"\n        repr_str = self.__class__.__name__\n        repr_str += f\"(class_dist_thred={self.class_dist_thred})\"\n        return repr_str\n\n\n@PIPELINES.register_module()\nclass NormalizeMultiviewImage(object):\n    \"\"\"Normalize the image.\n    Added key is \"img_norm_cfg\".\n    Args:\n        mean (sequence): Mean values of 3 channels.\n        std (sequence): Std values of 3 channels.\n        to_rgb (bool): Whether to convert the image from BGR to RGB,\n            default is true.\n    \"\"\"\n\n    def __init__(self, mean, std, to_rgb=True):\n        self.mean = np.array(mean, dtype=np.float32)\n        self.std = np.array(std, dtype=np.float32)\n        self.to_rgb = to_rgb\n\n    def __call__(self, results):\n        \"\"\"Call function to normalize images.\n        Args:\n            results (dict): Result dict from loading pipeline.\n        Returns:\n            dict: Normalized results, 'img_norm_cfg' key is added into\n                result dict.\n        \"\"\"\n        results[\"img\"] = [\n            mmcv.imnormalize(img, self.mean, self.std, self.to_rgb)\n            for img in results[\"img\"]\n        ]\n        results[\"img_norm_cfg\"] = dict(\n            mean=self.mean, std=self.std, to_rgb=self.to_rgb\n        )\n        return results\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f\"(mean={self.mean}, std={self.std}, to_rgb={self.to_rgb})\"\n        return repr_str\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/pipelines/vectorize.py",
    "content": "from typing import List, Tuple, Union, Dict\n\nimport numpy as np\nfrom shapely.geometry import LineString\nfrom numpy.typing import NDArray\n\nfrom mmcv.parallel import DataContainer as DC\nfrom mmdet.datasets.builder import PIPELINES\n\n\n@PIPELINES.register_module(force=True)\nclass VectorizeMap(object):\n    \"\"\"Generate vectoized map and put into `semantic_mask` key.\n    Concretely, shapely geometry objects are converted into sample points (ndarray).\n    We use args `sample_num`, `sample_dist`, `simplify` to specify sampling method.\n\n    Args:\n        roi_size (tuple or list): bev range .\n        normalize (bool): whether to normalize points to range (0, 1).\n        coords_dim (int): dimension of point coordinates.\n        simplify (bool): whether to use simpily function. If true, `sample_num` \\\n            and `sample_dist` will be ignored.\n        sample_num (int): number of points to interpolate from a polyline. Set to -1 to ignore.\n        sample_dist (float): interpolate distance. Set to -1 to ignore.\n    \"\"\"\n\n    def __init__(self, \n                 roi_size: Union[Tuple, List], \n                 normalize: bool,\n                 coords_dim: int=2,\n                 simplify: bool=False, \n                 sample_num: int=-1, \n                 sample_dist: float=-1, \n                 permute: bool=False\n        ):\n        self.coords_dim = coords_dim\n        self.sample_num = sample_num\n        self.sample_dist = sample_dist\n        self.roi_size = np.array(roi_size)\n        self.normalize = normalize\n        self.simplify = simplify\n        self.permute = permute\n\n        if sample_dist > 0:\n            assert sample_num < 0 and not simplify\n            self.sample_fn = self.interp_fixed_dist\n        elif sample_num > 0:\n            assert sample_dist < 0 and not simplify\n            self.sample_fn = self.interp_fixed_num\n        else:\n            assert simplify\n\n    def interp_fixed_num(self, line: LineString) -> NDArray:\n        ''' Interpolate a line to fixed number of points.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n\n        distances = np.linspace(0, line.length, self.sample_num)\n        sampled_points = np.array([list(line.interpolate(distance).coords) \n            for distance in distances]).squeeze()\n\n        return sampled_points\n\n    def interp_fixed_dist(self, line: LineString) -> NDArray:\n        ''' Interpolate a line at fixed interval.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            points (array): interpolated points, shape (N, 2)\n        '''\n\n        distances = list(np.arange(self.sample_dist, line.length, self.sample_dist))\n        # make sure to sample at least two points when sample_dist > line.length\n        distances = [0,] + distances + [line.length,] \n        \n        sampled_points = np.array([list(line.interpolate(distance).coords)\n                                for distance in distances]).squeeze()\n        \n        return sampled_points\n    \n    def get_vectorized_lines(self, map_geoms: Dict) -> Dict:\n        ''' Vectorize map elements. Iterate over the input dict and apply the \n        specified sample funcion.\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            vectors (array): dict of vectorized map elements.\n        '''\n\n        vectors = {}\n        for label, geom_list in map_geoms.items():\n            vectors[label] = []\n            for geom in geom_list:\n                if geom.geom_type == 'LineString':\n                    if self.simplify:\n                        line = geom.simplify(0.2, preserve_topology=True)\n                        line = np.array(line.coords)\n                    else:\n                        line = self.sample_fn(geom)\n                    line = line[:, :self.coords_dim]\n\n                    if self.normalize:\n                        line = self.normalize_line(line)\n                    if self.permute:\n                        line = self.permute_line(line)\n                    vectors[label].append(line)\n\n                elif geom.geom_type == 'Polygon':\n                    # polygon objects will not be vectorized\n                    continue\n                \n                else:\n                    raise ValueError('map geoms must be either LineString or Polygon!')\n        return vectors\n    \n    def normalize_line(self, line: NDArray) -> NDArray:\n        ''' Convert points to range (0, 1).\n        \n        Args:\n            line (LineString): line\n        \n        Returns:\n            normalized (array): normalized points.\n        '''\n\n        origin = -np.array([self.roi_size[0]/2, self.roi_size[1]/2])\n\n        line[:, :2] = line[:, :2] - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        line[:, :2] = line[:, :2] / (self.roi_size + eps)\n\n        return line\n    \n    def permute_line(self, line: np.ndarray, padding=1e5):\n        '''\n        (num_pts, 2) -> (num_permute, num_pts, 2)\n        where num_permute = 2 * (num_pts - 1)\n        '''\n        is_closed = np.allclose(line[0], line[-1], atol=1e-3)\n        num_points = len(line)\n        permute_num = num_points - 1\n        permute_lines_list = []\n        if is_closed:\n            pts_to_permute = line[:-1, :] # throw away replicate start end pts\n            for shift_i in range(permute_num):\n                permute_lines_list.append(np.roll(pts_to_permute, shift_i, axis=0))\n            flip_pts_to_permute = np.flip(pts_to_permute, axis=0)\n            for shift_i in range(permute_num):\n                permute_lines_list.append(np.roll(flip_pts_to_permute, shift_i, axis=0))\n        else:\n            permute_lines_list.append(line)\n            permute_lines_list.append(np.flip(line, axis=0))\n\n        permute_lines_array = np.stack(permute_lines_list, axis=0)\n\n        if is_closed:\n            tmp = np.zeros((permute_num * 2, num_points, self.coords_dim))\n            tmp[:, :-1, :] = permute_lines_array\n            tmp[:, -1, :] = permute_lines_array[:, 0, :] # add replicate start end pts\n            permute_lines_array = tmp\n\n        else:\n            # padding\n            padding = np.full([permute_num * 2 - 2, num_points, self.coords_dim], padding)\n            permute_lines_array = np.concatenate((permute_lines_array, padding), axis=0)\n        \n        return permute_lines_array\n    \n    def __call__(self, input_dict):\n        if \"map_geoms\" not in input_dict:\n            return input_dict\n        map_geoms = input_dict['map_geoms']\n        vectors = self.get_vectorized_lines(map_geoms)\n\n        if self.permute:\n            gt_map_labels, gt_map_pts = [], []\n            for label, vecs in vectors.items():\n                for vec in vecs:\n                    gt_map_labels.append(label)\n                    gt_map_pts.append(vec)\n            input_dict['gt_map_labels'] = np.array(gt_map_labels, dtype=np.int64)\n            input_dict['gt_map_pts'] = np.array(gt_map_pts, dtype=np.float32).reshape(-1, 2 * (self.sample_num - 1), self.sample_num, self.coords_dim)\n        else:\n            input_dict['vectors'] = DC(vectors, stack=False, cpu_only=True)\n        \n        return input_dict\n\n    def __repr__(self):\n        repr_str = self.__class__.__name__\n        repr_str += f'(simplify={self.simplify}, '\n        repr_str += f'sample_num={self.sample_num}), '\n        repr_str += f'sample_dist={self.sample_dist}), ' \n        repr_str += f'roi_size={self.roi_size})'\n        repr_str += f'normalize={self.normalize})'\n        repr_str += f'coords_dim={self.coords_dim})'\n\n        return repr_str"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/samplers/__init__.py",
    "content": "from .group_sampler import DistributedGroupSampler\nfrom .distributed_sampler import DistributedSampler\nfrom .sampler import SAMPLER, build_sampler\nfrom .group_in_batch_sampler import (\n    GroupInBatchSampler,\n)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/samplers/distributed_sampler.py",
    "content": "import math\n\nimport torch\nfrom torch.utils.data import DistributedSampler as _DistributedSampler\nfrom .sampler import SAMPLER\n\nimport pdb\nimport sys\n\n\nclass ForkedPdb(pdb.Pdb):\n    def interaction(self, *args, **kwargs):\n        _stdin = sys.stdin\n        try:\n            sys.stdin = open(\"/dev/stdin\")\n            pdb.Pdb.interaction(self, *args, **kwargs)\n        finally:\n            sys.stdin = _stdin\n\n\ndef set_trace():\n    ForkedPdb().set_trace(sys._getframe().f_back)\n\n\n@SAMPLER.register_module()\nclass DistributedSampler(_DistributedSampler):\n    def __init__(\n        self, dataset=None, num_replicas=None, rank=None, shuffle=True, seed=0\n    ):\n        super().__init__(\n            dataset, num_replicas=num_replicas, rank=rank, shuffle=shuffle\n        )\n        # for the compatibility from PyTorch 1.3+\n        self.seed = seed if seed is not None else 0\n\n    def __iter__(self):\n        # deterministically shuffle based on epoch\n        assert not self.shuffle\n        if \"data_infos\" in dir(self.dataset):\n            timestamps = [\n                x[\"timestamp\"] / 1e6 for x in self.dataset.data_infos\n            ]\n            vehicle_idx = [\n                x[\"lidar_path\"].split(\"/\")[-1][:4]\n                if \"lidar_path\" in x\n                else None\n                for x in self.dataset.data_infos\n            ]\n        else:\n            timestamps = [\n                x[\"timestamp\"] / 1e6\n                for x in self.dataset.datasets[0].data_infos\n            ] * len(self.dataset.datasets)\n            vehicle_idx = [\n                x[\"lidar_path\"].split(\"/\")[-1][:4]\n                if \"lidar_path\" in x\n                else None\n                for x in self.dataset.datasets[0].data_infos\n            ] * len(self.dataset.datasets)\n\n        sequence_splits = []\n        for i in range(len(timestamps)):\n            if i == 0 or (\n                abs(timestamps[i] - timestamps[i - 1]) > 4\n                or vehicle_idx[i] != vehicle_idx[i - 1]\n            ):\n                sequence_splits.append([i])\n            else:\n                sequence_splits[-1].append(i)\n\n        indices = []\n        perfix_sum = 0\n        split_length = len(self.dataset) // self.num_replicas\n        for i in range(len(sequence_splits)):\n            if perfix_sum >= (self.rank + 1) * split_length:\n                break\n            elif perfix_sum >= self.rank * split_length:\n                indices.extend(sequence_splits[i])\n            perfix_sum += len(sequence_splits[i])\n\n        self.num_samples = len(indices)\n        return iter(indices)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/samplers/group_in_batch_sampler.py",
    "content": "# https://github.com/Divadi/SOLOFusion/blob/main/mmdet3d/datasets/samplers/infinite_group_each_sample_in_batch_sampler.py\nimport itertools\nimport copy\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.runner import get_dist_info\nfrom torch.utils.data.sampler import Sampler\n\n\n# https://github.com/open-mmlab/mmdetection/blob/3b72b12fe9b14de906d1363982b9fba05e7d47c1/mmdet/core/utils/dist_utils.py#L157\ndef sync_random_seed(seed=None, device=\"cuda\"):\n    \"\"\"Make sure different ranks share the same seed.\n    All workers must call this function, otherwise it will deadlock.\n    This method is generally used in `DistributedSampler`,\n    because the seed should be identical across all processes\n    in the distributed group.\n    In distributed sampling, different ranks should sample non-overlapped\n    data in the dataset. Therefore, this function is used to make sure that\n    each rank shuffles the data indices in the same order based\n    on the same seed. Then different ranks could use different indices\n    to select non-overlapped data from the same data list.\n    Args:\n        seed (int, Optional): The seed. Default to None.\n        device (str): The device where the seed will be put on.\n            Default to 'cuda'.\n    Returns:\n        int: Seed to be used.\n    \"\"\"\n    if seed is None:\n        seed = np.random.randint(2**31)\n    assert isinstance(seed, int)\n\n    rank, world_size = get_dist_info()\n\n    if world_size == 1:\n        return seed\n\n    if rank == 0:\n        random_num = torch.tensor(seed, dtype=torch.int32, device=device)\n    else:\n        random_num = torch.tensor(0, dtype=torch.int32, device=device)\n    dist.broadcast(random_num, src=0)\n    return random_num.item()\n\n\nclass GroupInBatchSampler(Sampler):\n    \"\"\"\n    Pardon this horrendous name. Basically, we want every sample to be from its own group.\n    If batch size is 4 and # of GPUs is 8, each sample of these 32 should be operating on\n    its own group.\n\n    Shuffling is only done for group order, not done within groups.\n    \"\"\"\n\n    def __init__(\n        self,\n        dataset,\n        batch_size=1,\n        world_size=None,\n        rank=None,\n        seed=0,\n        skip_prob=0.,\n        sequence_flip_prob=0.,\n    ):\n        _rank, _world_size = get_dist_info()\n        if world_size is None:\n            world_size = _world_size\n        if rank is None:\n            rank = _rank\n\n        self.dataset = dataset\n        self.batch_size = batch_size\n        self.world_size = world_size\n        self.rank = rank\n        self.seed = sync_random_seed(seed)\n\n        self.size = len(self.dataset)\n\n        assert hasattr(self.dataset, \"flag\")\n        self.flag = self.dataset.flag\n        self.group_sizes = np.bincount(self.flag)\n        self.groups_num = len(self.group_sizes)\n        self.global_batch_size = batch_size * world_size\n        assert self.groups_num >= self.global_batch_size\n\n        # Now, for efficiency, make a dict group_idx: List[dataset sample_idxs]\n        self.group_idx_to_sample_idxs = {\n            group_idx: np.where(self.flag == group_idx)[0].tolist()\n            for group_idx in range(self.groups_num)\n        }\n\n        # Get a generator per sample idx. Considering samples over all\n        # GPUs, each sample position has its own generator\n        self.group_indices_per_global_sample_idx = [\n            self._group_indices_per_global_sample_idx(\n                self.rank * self.batch_size + local_sample_idx\n            )\n            for local_sample_idx in range(self.batch_size)\n        ]\n\n        # Keep track of a buffer of dataset sample idxs for each local sample idx\n        self.buffer_per_local_sample = [[] for _ in range(self.batch_size)]\n        self.aug_per_local_sample = [None for _ in range(self.batch_size)]\n        self.skip_prob = skip_prob\n        self.sequence_flip_prob = sequence_flip_prob\n\n    def _infinite_group_indices(self):\n        g = torch.Generator()\n        g.manual_seed(self.seed)\n        while True:\n            yield from torch.randperm(self.groups_num, generator=g).tolist()\n\n    def _group_indices_per_global_sample_idx(self, global_sample_idx):\n        yield from itertools.islice(\n            self._infinite_group_indices(),\n            global_sample_idx,\n            None,\n            self.global_batch_size,\n        )\n\n    def __iter__(self):\n        while True:\n            curr_batch = []\n            for local_sample_idx in range(self.batch_size):\n                skip = (\n                    np.random.uniform() < self.skip_prob\n                    and len(self.buffer_per_local_sample[local_sample_idx]) > 1\n                )\n                if len(self.buffer_per_local_sample[local_sample_idx]) == 0:\n                    # Finished current group, refill with next group\n                    # skip = False\n                    new_group_idx = next(\n                        self.group_indices_per_global_sample_idx[\n                            local_sample_idx\n                        ]\n                    )\n                    self.buffer_per_local_sample[\n                        local_sample_idx\n                    ] = copy.deepcopy(\n                        self.group_idx_to_sample_idxs[new_group_idx]\n                    )\n                    if np.random.uniform() < self.sequence_flip_prob:\n                        self.buffer_per_local_sample[\n                            local_sample_idx\n                        ] = self.buffer_per_local_sample[local_sample_idx][\n                            ::-1\n                        ]\n                    if self.dataset.keep_consistent_seq_aug:\n                        self.aug_per_local_sample[\n                            local_sample_idx\n                        ] = self.dataset.get_augmentation()\n\n                if not self.dataset.keep_consistent_seq_aug:\n                    self.aug_per_local_sample[\n                        local_sample_idx\n                    ] = self.dataset.get_augmentation()\n\n                if skip:\n                    self.buffer_per_local_sample[local_sample_idx].pop(0)\n                curr_batch.append(\n                    dict(\n                        idx=self.buffer_per_local_sample[local_sample_idx].pop(\n                            0\n                        ),\n                        aug_config=self.aug_per_local_sample[local_sample_idx],\n                    )\n                )\n\n            yield curr_batch\n\n    def __len__(self):\n        \"\"\"Length of base dataset.\"\"\"\n        return self.size\n\n    def set_epoch(self, epoch):\n        self.epoch = epoch\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/samplers/group_sampler.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport math\n\nimport numpy as np\nimport torch\nfrom mmcv.runner import get_dist_info\nfrom torch.utils.data import Sampler\nfrom .sampler import SAMPLER\nimport random\nfrom IPython import embed\n\n\n@SAMPLER.register_module()\nclass DistributedGroupSampler(Sampler):\n    \"\"\"Sampler that restricts data loading to a subset of the dataset.\n    It is especially useful in conjunction with\n    :class:`torch.nn.parallel.DistributedDataParallel`. In such case, each\n    process can pass a DistributedSampler instance as a DataLoader sampler,\n    and load a subset of the original dataset that is exclusive to it.\n    .. note::\n        Dataset is assumed to be of constant size.\n    Arguments:\n        dataset: Dataset used for sampling.\n        num_replicas (optional): Number of processes participating in\n            distributed training.\n        rank (optional): Rank of the current process within num_replicas.\n        seed (int, optional): random seed used to shuffle the sampler if\n            ``shuffle=True``. This number should be identical across all\n            processes in the distributed group. Default: 0.\n    \"\"\"\n\n    def __init__(\n        self, dataset, samples_per_gpu=1, num_replicas=None, rank=None, seed=0\n    ):\n        _rank, _num_replicas = get_dist_info()\n        if num_replicas is None:\n            num_replicas = _num_replicas\n        if rank is None:\n            rank = _rank\n        self.dataset = dataset\n        self.samples_per_gpu = samples_per_gpu\n        self.num_replicas = num_replicas\n        self.rank = rank\n        self.epoch = 0\n        self.seed = seed if seed is not None else 0\n\n        assert hasattr(self.dataset, \"flag\")\n        self.flag = self.dataset.flag\n        self.group_sizes = np.bincount(self.flag)\n\n        self.num_samples = 0\n        for i, j in enumerate(self.group_sizes):\n            self.num_samples += (\n                int(\n                    math.ceil(\n                        self.group_sizes[i]\n                        * 1.0\n                        / self.samples_per_gpu\n                        / self.num_replicas\n                    )\n                )\n                * self.samples_per_gpu\n            )\n        self.total_size = self.num_samples * self.num_replicas\n\n    def __iter__(self):\n        # deterministically shuffle based on epoch\n        g = torch.Generator()\n        g.manual_seed(self.epoch + self.seed)\n\n        indices = []\n        for i, size in enumerate(self.group_sizes):\n            if size > 0:\n                indice = np.where(self.flag == i)[0]\n                assert len(indice) == size\n                # add .numpy() to avoid bug when selecting indice in parrots.\n                # TODO: check whether torch.randperm() can be replaced by\n                # numpy.random.permutation().\n                indice = indice[\n                    list(torch.randperm(int(size), generator=g).numpy())\n                ].tolist()\n                extra = int(\n                    math.ceil(\n                        size * 1.0 / self.samples_per_gpu / self.num_replicas\n                    )\n                ) * self.samples_per_gpu * self.num_replicas - len(indice)\n                # pad indice\n                tmp = indice.copy()\n                for _ in range(extra // size):\n                    indice.extend(tmp)\n                indice.extend(tmp[: extra % size])\n                indices.extend(indice)\n\n        assert len(indices) == self.total_size\n\n        indices = [\n            indices[j]\n            for i in list(\n                torch.randperm(\n                    len(indices) // self.samples_per_gpu, generator=g\n                )\n            )\n            for j in range(\n                i * self.samples_per_gpu, (i + 1) * self.samples_per_gpu\n            )\n        ]\n\n        # subsample\n        offset = self.num_samples * self.rank\n        indices = indices[offset : offset + self.num_samples]\n        assert len(indices) == self.num_samples\n\n        return iter(indices)\n\n    def __len__(self):\n        return self.num_samples\n\n    def set_epoch(self, epoch):\n        self.epoch = epoch\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/samplers/sampler.py",
    "content": "from mmcv.utils.registry import Registry, build_from_cfg\n\nSAMPLER = Registry(\"sampler\")\n\n\ndef build_sampler(cfg, default_args):\n    return build_from_cfg(cfg, SAMPLER, default_args)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/datasets/utils.py",
    "content": "import copy\n\nimport cv2\nimport numpy as np\nimport torch\n\nfrom projects.mmdet3d_plugin.core.box3d import *\n\n\ndef box3d_to_corners(box3d):\n    if isinstance(box3d, torch.Tensor):\n        box3d = box3d.detach().cpu().numpy()\n    corners_norm = np.stack(np.unravel_index(np.arange(8), [2] * 3), axis=1)\n    corners_norm = corners_norm[[0, 1, 3, 2, 4, 5, 7, 6]]\n    # use relative origin [0.5, 0.5, 0]\n    corners_norm = corners_norm - np.array([0.5, 0.5, 0.5])\n    corners = box3d[:, None, [W, L, H]] * corners_norm.reshape([1, 8, 3])\n\n    # rotate around z axis\n    rot_cos = np.cos(box3d[:, YAW])\n    rot_sin = np.sin(box3d[:, YAW])\n    rot_mat = np.tile(np.eye(3)[None], (box3d.shape[0], 1, 1))\n    rot_mat[:, 0, 0] = rot_cos\n    rot_mat[:, 0, 1] = -rot_sin\n    rot_mat[:, 1, 0] = rot_sin\n    rot_mat[:, 1, 1] = rot_cos\n    corners = (rot_mat[:, None] @ corners[..., None]).squeeze(axis=-1)\n    corners += box3d[:, None, :3]\n    return corners\n\n\ndef plot_rect3d_on_img(\n    img, num_rects, rect_corners, color=(0, 255, 0), thickness=1\n):\n    \"\"\"Plot the boundary lines of 3D rectangular on 2D images.\n\n    Args:\n        img (numpy.array): The numpy array of image.\n        num_rects (int): Number of 3D rectangulars.\n        rect_corners (numpy.array): Coordinates of the corners of 3D\n            rectangulars. Should be in the shape of [num_rect, 8, 2].\n        color (tuple[int], optional): The color to draw bboxes.\n            Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    line_indices = (\n        (0, 1),\n        (0, 3),\n        (0, 4),\n        (1, 2),\n        (1, 5),\n        (3, 2),\n        (3, 7),\n        (4, 5),\n        (4, 7),\n        (2, 6),\n        (5, 6),\n        (6, 7),\n    )\n    h, w = img.shape[:2]\n    for i in range(num_rects):\n        corners = np.clip(rect_corners[i], -1e4, 1e5).astype(np.int32)\n        for start, end in line_indices:\n            if (\n                (corners[start, 1] >= h or corners[start, 1] < 0)\n                or (corners[start, 0] >= w or corners[start, 0] < 0)\n            ) and (\n                (corners[end, 1] >= h or corners[end, 1] < 0)\n                or (corners[end, 0] >= w or corners[end, 0] < 0)\n            ):\n                continue\n            if isinstance(color[0], int):\n                cv2.line(\n                    img,\n                    (corners[start, 0], corners[start, 1]),\n                    (corners[end, 0], corners[end, 1]),\n                    color,\n                    thickness,\n                    cv2.LINE_AA,\n                )\n            else:\n                cv2.line(\n                    img,\n                    (corners[start, 0], corners[start, 1]),\n                    (corners[end, 0], corners[end, 1]),\n                    color[i],\n                    thickness,\n                    cv2.LINE_AA,\n                )\n\n    return img.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d_on_img(\n    bboxes3d, raw_img, lidar2img_rt, img_metas=None, color=(0, 255, 0), thickness=1\n):\n    \"\"\"Project the 3D bbox on 2D plane and draw on input image.\n\n    Args:\n        bboxes3d (:obj:`LiDARInstance3DBoxes`):\n            3d bbox in lidar coordinate system to visualize.\n        raw_img (numpy.array): The numpy array of image.\n        lidar2img_rt (numpy.array, shape=[4, 4]): The projection matrix\n            according to the camera intrinsic parameters.\n        img_metas (dict): Useless here.\n        color (tuple[int], optional): The color to draw bboxes.\n            Default: (0, 255, 0).\n        thickness (int, optional): The thickness of bboxes. Default: 1.\n    \"\"\"\n    img = raw_img.copy()\n    # corners_3d = bboxes3d.corners\n    corners_3d = box3d_to_corners(bboxes3d)\n    num_bbox = corners_3d.shape[0]\n    pts_4d = np.concatenate(\n        [corners_3d.reshape(-1, 3), np.ones((num_bbox * 8, 1))], axis=-1\n    )\n    lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n    if isinstance(lidar2img_rt, torch.Tensor):\n        lidar2img_rt = lidar2img_rt.cpu().numpy()\n    pts_2d = pts_4d @ lidar2img_rt.T\n\n    pts_2d[:, 2] = np.clip(pts_2d[:, 2], a_min=1e-5, a_max=1e5)\n    pts_2d[:, 0] /= pts_2d[:, 2]\n    pts_2d[:, 1] /= pts_2d[:, 2]\n    imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)\n\n    return plot_rect3d_on_img(img, num_bbox, imgfov_pts_2d, color, thickness)\n\n\ndef draw_points_on_img(points, img, lidar2img_rt, color=(0, 255, 0), circle=4):\n    img = img.copy()\n    N = points.shape[0]\n    points = points.cpu().numpy()\n    lidar2img_rt = copy.deepcopy(lidar2img_rt).reshape(4, 4)\n    if isinstance(lidar2img_rt, torch.Tensor):\n        lidar2img_rt = lidar2img_rt.cpu().numpy()\n    pts_2d = (\n        np.sum(points[:, :, None] * lidar2img_rt[:3, :3], axis=-1)\n        + lidar2img_rt[:3, 3]\n    )\n    pts_2d[..., 2] = np.clip(pts_2d[..., 2], a_min=1e-5, a_max=1e5)\n    pts_2d = pts_2d[..., :2] / pts_2d[..., 2:3]\n    pts_2d = np.clip(pts_2d, -1e4, 1e4).astype(np.int32)\n\n    for i in range(N):\n        for point in pts_2d[i]:\n            if isinstance(color[0], int):\n                color_tmp = color\n            else:\n                color_tmp = color[i]\n            cv2.circle(img, point.tolist(), circle, color_tmp, thickness=-1)\n    return img.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d_on_bev(\n    bboxes_3d, bev_size, bev_range=115, color=(255, 0, 0), thickness=3):\n    if isinstance(bev_size, (list, tuple)):\n        bev_h, bev_w = bev_size\n    else:\n        bev_h, bev_w = bev_size, bev_size\n    bev = np.zeros([bev_h, bev_w, 3])\n\n    marking_color = (127, 127, 127)\n    bev_resolution = bev_range / bev_h\n    for cir in range(int(bev_range / 2 / 10)):\n        cv2.circle(\n            bev,\n            (int(bev_h / 2), int(bev_w / 2)),\n            int((cir + 1) * 10 / bev_resolution),\n            marking_color,\n            thickness=thickness,\n        )\n    cv2.line(\n        bev,\n        (0, int(bev_h / 2)),\n        (bev_w, int(bev_h / 2)),\n        marking_color,\n    )\n    cv2.line(\n        bev,\n        (int(bev_w / 2), 0),\n        (int(bev_w / 2), bev_h),\n        marking_color,\n    )\n    if len(bboxes_3d) != 0:\n        bev_corners = box3d_to_corners(bboxes_3d)[:, [0, 3, 4, 7]][\n            ..., [0, 1]\n        ]\n        xs = bev_corners[..., 0] / bev_resolution + bev_w / 2\n        ys = -bev_corners[..., 1] / bev_resolution + bev_h / 2\n        for obj_idx, (x, y) in enumerate(zip(xs, ys)):\n            for p1, p2 in ((0, 1), (0, 2), (1, 3), (2, 3)):\n                if isinstance(color[0], (list, tuple)):\n                    tmp = color[obj_idx]\n                else:\n                    tmp = color\n                cv2.line(\n                    bev,\n                    (int(x[p1]), int(y[p1])),\n                    (int(x[p2]), int(y[p2])),\n                    tmp,\n                    thickness=thickness,\n                )\n    return bev.astype(np.uint8)\n\n\ndef draw_lidar_bbox3d(bboxes_3d, imgs, lidar2imgs, color=(255, 0, 0)):\n    vis_imgs = []\n    for i, (img, lidar2img) in enumerate(zip(imgs, lidar2imgs)):\n        vis_imgs.append(\n            draw_lidar_bbox3d_on_img(bboxes_3d, img, lidar2img, color=color)\n        )\n\n    num_imgs = len(vis_imgs)\n    if num_imgs < 4 or num_imgs % 2 != 0:\n        vis_imgs = np.concatenate(vis_imgs, axis=1)\n    else:\n        vis_imgs = np.concatenate([\n            np.concatenate(vis_imgs[:num_imgs//2], axis=1),\n            np.concatenate(vis_imgs[num_imgs//2:], axis=1)\n        ], axis=0)\n\n    bev = draw_lidar_bbox3d_on_bev(bboxes_3d, vis_imgs.shape[0], color=color)\n    vis_imgs = np.concatenate([bev, vis_imgs], axis=1)\n    return vis_imgs\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/__init__.py",
    "content": "from .sparsedrive import SparseDrive\nfrom .sparsedrive_head import SparseDriveHead\nfrom .blocks import (\n    DeformableFeatureAggregation,\n    DenseDepthNet,\n    AsymmetricFFN,\n)\nfrom .instance_bank import InstanceBank\nfrom .detection3d import (\n    SparseBox3DDecoder,\n    SparseBox3DTarget,\n    SparseBox3DRefinementModule,\n    SparseBox3DKeyPointsGenerator,\n    SparseBox3DEncoder,\n)\nfrom .map import *\nfrom .motion import *\n\n\n__all__ = [\n    \"SparseDrive\",\n    \"SparseDriveHead\",\n    \"DeformableFeatureAggregation\",\n    \"DenseDepthNet\",\n    \"AsymmetricFFN\",\n    \"InstanceBank\",\n    \"SparseBox3DDecoder\",\n    \"SparseBox3DTarget\",\n    \"SparseBox3DRefinementModule\",\n    \"SparseBox3DKeyPointsGenerator\",\n    \"SparseBox3DEncoder\",\n]\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/attention.py",
    "content": "import warnings\nimport math\n\nimport torch\nimport torch.nn as nn\nfrom torch.nn.functional import linear\nfrom torch.nn.init import xavier_uniform_, constant_\n\nfrom mmcv.utils import deprecated_api_warning\nfrom mmcv.runner import auto_fp16\nfrom mmcv.runner.base_module import BaseModule\nfrom mmcv.cnn.bricks.drop import build_dropout\nfrom mmcv.cnn.bricks.registry import ATTENTION\nimport torch.utils.checkpoint as cp\n\n\nfrom einops import rearrange\ntry:\n    from flash_attn.flash_attn_interface import flash_attn_unpadded_kvpacked_func\n    print('Use flash_attn_unpadded_kvpacked_func')\nexcept:\n    from flash_attn.flash_attn_interface import  flash_attn_varlen_kvpacked_func as flash_attn_unpadded_kvpacked_func\n    print('Use flash_attn_varlen_kvpacked_func')\nfrom flash_attn.bert_padding import unpad_input, pad_input, index_first_axis\n\n\ndef _in_projection_packed(q, k, v, w, b = None):\n    w_q, w_k, w_v = w.chunk(3)\n    if b is None:\n        b_q = b_k = b_v = None\n    else:\n        b_q, b_k, b_v = b.chunk(3)\n    return linear(q, w_q, b_q), linear(k, w_k, b_k), linear(v, w_v, b_v)\n\n\nclass FlashAttention(nn.Module):\n    \"\"\"Implement the scaled dot product attention with softmax.\n    Arguments\n    ---------\n        softmax_scale: The temperature to use for the softmax attention.\n                      (default: 1/sqrt(d_keys) where d_keys is computed at\n                      runtime)\n        attention_dropout: The dropout rate to apply to the attention\n                           (default: 0.1)\n    \"\"\"\n    def __init__(self, softmax_scale=None, attention_dropout=0.0, device=None, dtype=None):\n        super().__init__()\n        self.softmax_scale = softmax_scale\n        self.dropout_p = attention_dropout\n        self.fp16_enabled = True\n\n    @auto_fp16(apply_to=('q', 'kv'), out_fp32=True)\n    def forward(self, q, kv, \n                causal=False, \n                key_padding_mask=None):\n        \"\"\"Implements the multihead softmax attention.\n        Arguments\n        ---------\n            q: The tensor containing the query. (B, T, H, D) \n            kv: The tensor containing the key, and value. (B, S, 2, H, D) \n            key_padding_mask: a bool tensor of shape (B, S)\n        \"\"\"\n        assert q.dtype in [torch.float16, torch.bfloat16] and kv.dtype in [torch.float16, torch.bfloat16]\n        assert q.is_cuda and kv.is_cuda\n        assert q.shape[0] == kv.shape[0] and q.shape[-2] == kv.shape[-2] and q.shape[-1] == kv.shape[-1]\n\n        batch_size = q.shape[0]\n        seqlen_q, seqlen_k = q.shape[1], kv.shape[1]\n        if key_padding_mask is None:\n            q, kv = rearrange(q, 'b s ... -> (b s) ...'), rearrange(kv, 'b s ... -> (b s) ...')\n            max_sq, max_sk = seqlen_q, seqlen_k \n            cu_seqlens_q = torch.arange(0, (batch_size + 1) * seqlen_q, step=seqlen_q, dtype=torch.int32,\n                                    device=q.device)\n            cu_seqlens_k = torch.arange(0, (batch_size + 1) * seqlen_k, step=seqlen_k, dtype=torch.int32,\n                                    device=kv.device)                    \n            output = flash_attn_unpadded_kvpacked_func(\n                q, kv, cu_seqlens_q, cu_seqlens_k, max_sq, max_sk,\n                self.dropout_p if self.training else 0.0,\n                softmax_scale=self.softmax_scale, causal=causal\n            )\n            output = rearrange(output, '(b s) ... -> b s ...', b=batch_size)\n        else:\n            nheads = kv.shape[-2]\n            q = rearrange(q, 'b s ... -> (b s) ...')\n            max_sq = seqlen_q\n            cu_seqlens_q = torch.arange(0, (batch_size + 1) * seqlen_q, step=seqlen_q, dtype=torch.int32,\n                                    device=q.device)\n            x = rearrange(kv, 'b s two h d -> b s (two h d)')\n            x_unpad, indices, cu_seqlens_k, max_sk = unpad_input(x, key_padding_mask)\n            x_unpad = rearrange(x_unpad, 'nnz (two h d) -> nnz two h d', two=2, h=nheads)\n            output_unpad = flash_attn_unpadded_kvpacked_func(\n                q, x_unpad, cu_seqlens_q, cu_seqlens_k, max_sq, max_sk,\n                self.dropout_p if self.training else 0.0,\n                softmax_scale=self.softmax_scale, causal=causal\n            )\n            output = rearrange(output_unpad, '(b s) ... -> b s ...', b=batch_size)\n\n        return output, None\n\n\nclass FlashMHA(nn.Module):\n\n    def __init__(self, embed_dim, num_heads, bias=True, batch_first=True, attention_dropout=0.0,\n                 causal=False, device=None, dtype=None, **kwargs) -> None:\n        assert batch_first\n        factory_kwargs = {'device': device, 'dtype': dtype}\n        super().__init__()\n        self.embed_dim = embed_dim\n        self.causal = causal\n        self.bias = bias\n\n        self.num_heads = num_heads\n        assert self.embed_dim % num_heads == 0, \"self.kdim must be divisible by num_heads\"\n        self.head_dim = self.embed_dim // num_heads\n        assert self.head_dim % 8 == 0 and self.head_dim <= 128, \"Only support head_dim <= 128 and divisible by 8\"\n\n        self.in_proj_weight = nn.Parameter(torch.empty((3 * embed_dim, embed_dim)))\n        if bias:\n            self.in_proj_bias = nn.Parameter(torch.empty(3 * embed_dim))\n        else:\n            self.register_parameter('in_proj_bias', None)\n        self.inner_attn = FlashAttention(attention_dropout=attention_dropout, **factory_kwargs)\n        self.out_proj = nn.Linear(embed_dim, embed_dim, bias=bias)\n        self._reset_parameters()\n\n    def _reset_parameters(self) -> None:\n        xavier_uniform_(self.in_proj_weight)\n        if self.in_proj_bias is not None:\n            constant_(self.in_proj_bias, 0.)\n            constant_(self.out_proj.bias, 0.)\n        \n    def forward(self, q, k, v, key_padding_mask=None):\n        \"\"\"x: (batch, seqlen, hidden_dim) (where hidden_dim = num heads * head dim)\n        key_padding_mask: bool tensor of shape (batch, seqlen)\n        \"\"\"\n        q, k, v = _in_projection_packed(q, k, v, self.in_proj_weight, self.in_proj_bias)\n        q = rearrange(q, 'b s (h d) -> b s h d', h=self.num_heads)\n        k = rearrange(k, 'b s (h d) -> b s h d', h=self.num_heads)\n        v = rearrange(v, 'b s (h d) -> b s h d', h=self.num_heads)\n        kv = torch.stack([k, v], dim=2)\n        \n        context, attn_weights = self.inner_attn(q, kv, key_padding_mask=key_padding_mask, causal=self.causal)\n        return self.out_proj(rearrange(context, 'b s h d -> b s (h d)')), attn_weights\n\n\n@ATTENTION.register_module()\nclass MultiheadFlashAttention(BaseModule):\n    \"\"\"A wrapper for ``torch.nn.MultiheadAttention``.\n    This module implements MultiheadAttention with identity connection,\n    and positional encoding  is also passed as input.\n    Args:\n        embed_dims (int): The embedding dimension.\n        num_heads (int): Parallel attention heads.\n        attn_drop (float): A Dropout layer on attn_output_weights.\n            Default: 0.0.\n        proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.\n            Default: 0.0.\n        dropout_layer (agent:`ConfigDict`): The dropout_layer used\n            when adding the shortcut.\n        init_cfg (agent:`mmcv.ConfigDict`): The Config for initialization.\n            Default: None.\n        batch_first (bool): When it is True,  Key, Query and Value are shape of\n            (batch, n, embed_dim), otherwise (n, batch, embed_dim).\n             Default to False.\n    \"\"\"\n\n    def __init__(self,\n                 embed_dims,\n                 num_heads,\n                 attn_drop=0.,\n                 proj_drop=0.,\n                 dropout_layer=dict(type='Dropout', drop_prob=0.),\n                 init_cfg=None,\n                 batch_first=True,\n                 **kwargs):\n        super(MultiheadFlashAttention, self).__init__(init_cfg)\n        if 'dropout' in kwargs:\n            warnings.warn(\n                'The arguments `dropout` in MultiheadAttention '\n                'has been deprecated, now you can separately '\n                'set `attn_drop`(float), proj_drop(float), '\n                'and `dropout_layer`(dict) ', DeprecationWarning)\n            attn_drop = kwargs['dropout']\n            dropout_layer['drop_prob'] = kwargs.pop('dropout')\n\n        self.embed_dims = embed_dims\n        self.num_heads = num_heads\n        self.batch_first = True\n        self.attn = FlashMHA(\n            embed_dim=embed_dims, \n            num_heads=num_heads, \n            attention_dropout=attn_drop, \n            dtype=torch.float16, \n            device='cuda',\n            **kwargs\n        )\n\n        self.proj_drop = nn.Dropout(proj_drop)\n        self.dropout_layer = build_dropout(\n            dropout_layer) if dropout_layer else nn.Identity()\n\n    @deprecated_api_warning({'residual': 'identity'},\n                            cls_name='MultiheadAttention')\n    def forward(self,\n                query,\n                key=None,\n                value=None,\n                identity=None,\n                query_pos=None,\n                key_pos=None,\n                attn_mask=None,\n                key_padding_mask=None,\n                **kwargs):\n        \"\"\"Forward function for `MultiheadAttention`.\n        **kwargs allow passing a more general data flow when combining\n        with other operations in `transformerlayer`.\n        Args:\n            query (Tensor): The input query with shape [num_queries, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_queries embed_dims].\n            key (Tensor): The key tensor with shape [num_keys, bs,\n                embed_dims] if self.batch_first is False, else\n                [bs, num_keys, embed_dims] .\n                If None, the ``query`` will be used. Defaults to None.\n            value (Tensor): The value tensor with same shape as `key`.\n                Same in `nn.MultiheadAttention.forward`. Defaults to None.\n                If None, the `key` will be used.\n            identity (Tensor): This tensor, with the same shape as x,\n                will be used for the identity link.\n                If None, `x` will be used. Defaults to None.\n            query_pos (Tensor): The positional encoding for query, with\n                the same shape as `x`. If not None, it will\n                be added to `x` before forward function. Defaults to None.\n            key_pos (Tensor): The positional encoding for `key`, with the\n                same shape as `key`. Defaults to None. If not None, it will\n                be added to `key` before forward function. If None, and\n                `query_pos` has the same shape as `key`, then `query_pos`\n                will be used for `key_pos`. Defaults to None.\n            attn_mask (Tensor): ByteTensor mask with shape [num_queries,\n                num_keys]. Same in `nn.MultiheadAttention.forward`.\n                Defaults to None.\n            key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].\n                Defaults to None.\n        Returns:\n            Tensor: forwarded results with shape\n            [num_queries, bs, embed_dims]\n            if self.batch_first is False, else\n            [bs, num_queries embed_dims].\n        \"\"\"\n        assert attn_mask is None, 'attn mask not supported now.'\n        if key is None:\n            key = query\n        if value is None:\n            value = key\n        if identity is None:\n            identity = query\n        if key_pos is None:\n            if query_pos is not None:\n                # use query_pos if key_pos is not available\n                if query_pos.shape == key.shape:\n                    key_pos = query_pos\n                else:\n                    warnings.warn(f'position encoding of key is'\n                                  f'missing in {self.__class__.__name__}.')\n        if query_pos is not None:\n            query = query + query_pos\n        if key_pos is not None:\n            key = key + key_pos\n\n        # The dataflow('key', 'query', 'value') of ``FlashAttention`` is (batch, num_query, embed_dims).\n        if not self.batch_first:\n            query = query.transpose(0, 1)\n            key = key.transpose(0, 1)\n            value = value.transpose(0, 1)\n        \n        out = self.attn(\n            q=query,\n            k=key,\n            v=value,\n            key_padding_mask=key_padding_mask)[0]\n\n        if not self.batch_first:\n            out = out.transpose(0, 1)\n\n        return identity + self.dropout_layer(self.proj_drop(out))\n\n\ndef gen_sineembed_for_position(pos_tensor, hidden_dim=256):\n    \"\"\"Mostly copy-paste from https://github.com/IDEA-opensource/DAB-DETR/\n    \"\"\"\n    half_hidden_dim = hidden_dim // 2\n    scale = 2 * math.pi\n    dim_t = torch.arange(half_hidden_dim, dtype=torch.float32, device=pos_tensor.device)\n    dim_t = 10000 ** (2 * (dim_t // 2) / half_hidden_dim)\n    x_embed = pos_tensor[..., 0] * scale\n    y_embed = pos_tensor[..., 1] * scale\n    pos_x = x_embed[..., None] / dim_t\n    pos_y = y_embed[..., None] / dim_t\n    pos_x = torch.stack((pos_x[..., 0::2].sin(), pos_x[..., 1::2].cos()), dim=-1).flatten(-2)\n    pos_y = torch.stack((pos_y[..., 0::2].sin(), pos_y[..., 1::2].cos()), dim=-1).flatten(-2)\n    pos = torch.cat((pos_y, pos_x), dim=-1)\n    return pos\n\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/base_target.py",
    "content": "from abc import ABC, abstractmethod\n\n\n__all__ = [\"BaseTargetWithDenoising\"]\n\n\nclass BaseTargetWithDenoising(ABC):\n    def __init__(self, num_dn_groups=0, num_temp_dn_groups=0):\n        super(BaseTargetWithDenoising, self).__init__()\n        self.num_dn_groups = num_dn_groups\n        self.num_temp_dn_groups = num_temp_dn_groups\n        self.dn_metas = None\n\n    @abstractmethod\n    def sample(self, cls_pred, box_pred, cls_target, box_target):\n        \"\"\"\n        Perform Hungarian matching between predictions and ground truth,\n        returning the matched ground truth corresponding to the predictions\n        along with the corresponding regression weights.\n        \"\"\"\n\n    def get_dn_anchors(self, cls_target, box_target, *args, **kwargs):\n        \"\"\"\n        Generate noisy instances for the current frame, with a total of\n        'self.num_dn_groups' groups.\n        \"\"\"\n        return None\n\n    def update_dn(self, instance_feature, anchor, *args, **kwargs):\n        \"\"\"\n        Insert the previously saved 'self.dn_metas' into the noisy instances\n        of the current frame.\n        \"\"\"\n\n    def cache_dn(\n        self,\n        dn_instance_feature,\n        dn_anchor,\n        dn_cls_target,\n        valid_mask,\n        dn_id_target,\n    ):\n        \"\"\"\n        Randomly save information for 'self.num_temp_dn_groups' groups of\n        temporal noisy instances to 'self.dn_metas'.\n        \"\"\"\n        if self.num_temp_dn_groups < 0:\n            return\n        self.dn_metas = dict(dn_anchor=dn_anchor[:, : self.num_temp_dn_groups])\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/blocks.py",
    "content": "from typing import List, Optional, Tuple\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nfrom torch.cuda.amp.autocast_mode import autocast\n\nfrom mmcv.cnn import Linear, build_activation_layer, build_norm_layer\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn.bricks.transformer import FFN\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.drop import build_dropout\nfrom mmcv.cnn import xavier_init, constant_init\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    FEEDFORWARD_NETWORK,\n)\n\ntry:\n    from ..ops import deformable_aggregation_function as DAF\nexcept:\n    DAF = None\n\n__all__ = [\n    \"DeformableFeatureAggregation\",\n    \"DenseDepthNet\",\n    \"AsymmetricFFN\",\n]\n\n\ndef linear_relu_ln(embed_dims, in_loops, out_loops, input_dims=None):\n    if input_dims is None:\n        input_dims = embed_dims\n    layers = []\n    for _ in range(out_loops):\n        for _ in range(in_loops):\n            layers.append(Linear(input_dims, embed_dims))\n            layers.append(nn.ReLU(inplace=True))\n            input_dims = embed_dims\n        layers.append(nn.LayerNorm(embed_dims))\n    return layers\n\n\n@ATTENTION.register_module()\nclass DeformableFeatureAggregation(BaseModule):\n    def __init__(\n        self,\n        embed_dims: int = 256,\n        num_groups: int = 8,\n        num_levels: int = 4,\n        num_cams: int = 6,\n        proj_drop: float = 0.0,\n        attn_drop: float = 0.0,\n        kps_generator: dict = None,\n        temporal_fusion_module=None,\n        use_temporal_anchor_embed=True,\n        use_deformable_func=False,\n        use_camera_embed=False,\n        residual_mode=\"add\",\n    ):\n        super(DeformableFeatureAggregation, self).__init__()\n        if embed_dims % num_groups != 0:\n            raise ValueError(\n                f\"embed_dims must be divisible by num_groups, \"\n                f\"but got {embed_dims} and {num_groups}\"\n            )\n        self.group_dims = int(embed_dims / num_groups)\n        self.embed_dims = embed_dims\n        self.num_levels = num_levels\n        self.num_groups = num_groups\n        self.num_cams = num_cams\n        self.use_temporal_anchor_embed = use_temporal_anchor_embed\n        if use_deformable_func:\n            assert DAF is not None, \"deformable_aggregation needs to be set up.\"\n        self.use_deformable_func = use_deformable_func\n        self.attn_drop = attn_drop\n        self.residual_mode = residual_mode\n        self.proj_drop = nn.Dropout(proj_drop)\n        kps_generator[\"embed_dims\"] = embed_dims\n        self.kps_generator = build_from_cfg(kps_generator, PLUGIN_LAYERS)\n        self.num_pts = self.kps_generator.num_pts\n        if temporal_fusion_module is not None:\n            if \"embed_dims\" not in temporal_fusion_module:\n                temporal_fusion_module[\"embed_dims\"] = embed_dims\n            self.temp_module = build_from_cfg(\n                temporal_fusion_module, PLUGIN_LAYERS\n            )\n        else:\n            self.temp_module = None\n        self.output_proj = Linear(embed_dims, embed_dims)\n\n        if use_camera_embed:\n            self.camera_encoder = Sequential(\n                *linear_relu_ln(embed_dims, 1, 2, 12)\n            )\n            self.weights_fc = Linear(\n                embed_dims, num_groups * num_levels * self.num_pts\n            )\n        else:\n            self.camera_encoder = None\n            self.weights_fc = Linear(\n                embed_dims, num_groups * num_cams * num_levels * self.num_pts\n            )\n\n    def init_weight(self):\n        constant_init(self.weights_fc, val=0.0, bias=0.0)\n        xavier_init(self.output_proj, distribution=\"uniform\", bias=0.0)\n\n    def forward(\n        self,\n        instance_feature: torch.Tensor,\n        anchor: torch.Tensor,\n        anchor_embed: torch.Tensor,\n        feature_maps: List[torch.Tensor],\n        metas: dict,\n        **kwargs: dict,\n    ):\n        bs, num_anchor = instance_feature.shape[:2]\n        key_points = self.kps_generator(anchor, instance_feature)\n        weights = self._get_weights(instance_feature, anchor_embed, metas)\n\n        if self.use_deformable_func:\n            points_2d = (\n                self.project_points(\n                    key_points,\n                    metas[\"projection_mat\"],\n                    metas.get(\"image_wh\"),\n                )\n                .permute(0, 2, 3, 1, 4)\n                .reshape(bs, num_anchor, self.num_pts, self.num_cams, 2)\n            )\n            weights = (\n                weights.permute(0, 1, 4, 2, 3, 5)\n                .contiguous()\n                .reshape(\n                    bs,\n                    num_anchor,\n                    self.num_pts,\n                    self.num_cams,\n                    self.num_levels,\n                    self.num_groups,\n                )\n            )\n            features = DAF(*feature_maps, points_2d, weights).reshape(\n                bs, num_anchor, self.embed_dims\n            )\n        else:\n            features = self.feature_sampling(\n                feature_maps,\n                key_points,\n                metas[\"projection_mat\"],\n                metas.get(\"image_wh\"),\n            )\n            features = self.multi_view_level_fusion(features, weights)\n            features = features.sum(dim=2)  # fuse multi-point features\n        output = self.proj_drop(self.output_proj(features))\n        if self.residual_mode == \"add\":\n            output = output + instance_feature\n        elif self.residual_mode == \"cat\":\n            output = torch.cat([output, instance_feature], dim=-1)\n        return output\n\n    def _get_weights(self, instance_feature, anchor_embed, metas=None):\n        bs, num_anchor = instance_feature.shape[:2]\n        feature = instance_feature + anchor_embed\n        if self.camera_encoder is not None:\n            camera_embed = self.camera_encoder(\n                metas[\"projection_mat\"][:, :, :3].reshape(\n                    bs, self.num_cams, -1\n                )\n            )\n            feature = feature[:, :, None] + camera_embed[:, None]\n\n        weights = (\n            self.weights_fc(feature)\n            .reshape(bs, num_anchor, -1, self.num_groups)\n            .softmax(dim=-2)\n            .reshape(\n                bs,\n                num_anchor,\n                self.num_cams,\n                self.num_levels,\n                self.num_pts,\n                self.num_groups,\n            )\n        )\n        if self.training and self.attn_drop > 0:\n            mask = torch.rand(\n                bs, num_anchor, self.num_cams, 1, self.num_pts, 1\n            )\n            mask = mask.to(device=weights.device, dtype=weights.dtype)\n            weights = ((mask > self.attn_drop) * weights) / (\n                1 - self.attn_drop\n            )\n        return weights\n\n    @staticmethod\n    def project_points(key_points, projection_mat, image_wh=None):\n        bs, num_anchor, num_pts = key_points.shape[:3]\n\n        pts_extend = torch.cat(\n            [key_points, torch.ones_like(key_points[..., :1])], dim=-1\n        )\n        points_2d = torch.matmul(\n            projection_mat[:, :, None, None], pts_extend[:, None, ..., None]\n        ).squeeze(-1)\n        points_2d = points_2d[..., :2] / torch.clamp(\n            points_2d[..., 2:3], min=1e-5\n        )\n        if image_wh is not None:\n            points_2d = points_2d / image_wh[:, :, None, None]\n        return points_2d\n\n    @staticmethod\n    def feature_sampling(\n        feature_maps: List[torch.Tensor],\n        key_points: torch.Tensor,\n        projection_mat: torch.Tensor,\n        image_wh: Optional[torch.Tensor] = None,\n    ) -> torch.Tensor:\n        num_levels = len(feature_maps)\n        num_cams = feature_maps[0].shape[1]\n        bs, num_anchor, num_pts = key_points.shape[:3]\n\n        points_2d = DeformableFeatureAggregation.project_points(\n            key_points, projection_mat, image_wh\n        )\n        points_2d = points_2d * 2 - 1\n        points_2d = points_2d.flatten(end_dim=1)\n\n        features = []\n        for fm in feature_maps:\n            features.append(\n                torch.nn.functional.grid_sample(\n                    fm.flatten(end_dim=1), points_2d\n                )\n            )\n        features = torch.stack(features, dim=1)\n        features = features.reshape(\n            bs, num_cams, num_levels, -1, num_anchor, num_pts\n        ).permute(\n            0, 4, 1, 2, 5, 3\n        )  # bs, num_anchor, num_cams, num_levels, num_pts, embed_dims\n\n        return features\n\n    def multi_view_level_fusion(\n        self,\n        features: torch.Tensor,\n        weights: torch.Tensor,\n    ):\n        bs, num_anchor = weights.shape[:2]\n        features = weights[..., None] * features.reshape(\n            features.shape[:-1] + (self.num_groups, self.group_dims)\n        )\n        features = features.sum(dim=2).sum(dim=2)\n        features = features.reshape(\n            bs, num_anchor, self.num_pts, self.embed_dims\n        )\n        return features\n\n\n@PLUGIN_LAYERS.register_module()\nclass DenseDepthNet(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        num_depth_layers=1,\n        equal_focal=100,\n        max_depth=60,\n        loss_weight=1.0,\n    ):\n        super().__init__()\n        self.embed_dims = embed_dims\n        self.equal_focal = equal_focal\n        self.num_depth_layers = num_depth_layers\n        self.max_depth = max_depth\n        self.loss_weight = loss_weight\n\n        self.depth_layers = nn.ModuleList()\n        for i in range(num_depth_layers):\n            self.depth_layers.append(\n                nn.Conv2d(embed_dims, 1, kernel_size=1, stride=1, padding=0)\n            )\n\n    def forward(self, feature_maps, focal=None, gt_depths=None):\n        if focal is None:\n            focal = self.equal_focal\n        else:\n            focal = focal.reshape(-1)\n        depths = []\n        for i, feat in enumerate(feature_maps[: self.num_depth_layers]):\n            depth = self.depth_layers[i](feat.flatten(end_dim=1).float()).exp()\n            depth = depth.transpose(0, -1) * focal / self.equal_focal\n            depth = depth.transpose(0, -1)\n            depths.append(depth)\n        if gt_depths is not None and self.training:\n            loss = self.loss(depths, gt_depths)\n            return loss\n        return depths\n\n    def loss(self, depth_preds, gt_depths):\n        loss = 0.0\n        for pred, gt in zip(depth_preds, gt_depths):\n            pred = pred.permute(0, 2, 3, 1).contiguous().reshape(-1)\n            gt = gt.reshape(-1)\n            fg_mask = torch.logical_and(\n                gt > 0.0, torch.logical_not(torch.isnan(pred))\n            )\n            gt = gt[fg_mask]\n            pred = pred[fg_mask]\n            pred = torch.clip(pred, 0.0, self.max_depth)\n            with autocast(enabled=False):\n                error = torch.abs(pred - gt).sum()\n                _loss = (\n                    error\n                    / max(1.0, len(gt) * len(depth_preds))\n                    * self.loss_weight\n                )\n            loss = loss + _loss\n        return loss\n\n\n@FEEDFORWARD_NETWORK.register_module()\nclass AsymmetricFFN(BaseModule):\n    def __init__(\n        self,\n        in_channels=None,\n        pre_norm=None,\n        embed_dims=256,\n        feedforward_channels=1024,\n        num_fcs=2,\n        act_cfg=dict(type=\"ReLU\", inplace=True),\n        ffn_drop=0.0,\n        dropout_layer=None,\n        add_identity=True,\n        init_cfg=None,\n        **kwargs,\n    ):\n        super(AsymmetricFFN, self).__init__(init_cfg)\n        assert num_fcs >= 2, (\n            \"num_fcs should be no less \" f\"than 2. got {num_fcs}.\"\n        )\n        self.in_channels = in_channels\n        self.pre_norm = pre_norm\n        self.embed_dims = embed_dims\n        self.feedforward_channels = feedforward_channels\n        self.num_fcs = num_fcs\n        self.act_cfg = act_cfg\n        self.activate = build_activation_layer(act_cfg)\n\n        layers = []\n        if in_channels is None:\n            in_channels = embed_dims\n        if pre_norm is not None:\n            self.pre_norm = build_norm_layer(pre_norm, in_channels)[1]\n\n        for _ in range(num_fcs - 1):\n            layers.append(\n                Sequential(\n                    Linear(in_channels, feedforward_channels),\n                    self.activate,\n                    nn.Dropout(ffn_drop),\n                )\n            )\n            in_channels = feedforward_channels\n        layers.append(Linear(feedforward_channels, embed_dims))\n        layers.append(nn.Dropout(ffn_drop))\n        self.layers = Sequential(*layers)\n        self.dropout_layer = (\n            build_dropout(dropout_layer)\n            if dropout_layer\n            else torch.nn.Identity()\n        )\n        self.add_identity = add_identity\n        if self.add_identity:\n            self.identity_fc = (\n                torch.nn.Identity()\n                if in_channels == embed_dims\n                else Linear(self.in_channels, embed_dims)\n            )\n\n    def forward(self, x, identity=None):\n        if self.pre_norm is not None:\n            x = self.pre_norm(x)\n        out = self.layers(x)\n        if not self.add_identity:\n            return self.dropout_layer(out)\n        if identity is None:\n            identity = x\n        identity = self.identity_fc(identity)\n        return identity + self.dropout_layer(out)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/__init__.py",
    "content": "from .decoder import SparseBox3DDecoder\nfrom .target import SparseBox3DTarget\nfrom .detection3d_blocks import (\n    SparseBox3DRefinementModule,\n    SparseBox3DKeyPointsGenerator,\n    SparseBox3DEncoder,\n)\nfrom .losses import SparseBox3DLoss\nfrom .detection3d_head import Sparse4DHead\nfrom .detection3d_head_roboAD import Sparse4DHead_roboAD\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/decoder.py",
    "content": "from typing import Optional\n\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\nfrom projects.mmdet3d_plugin.core.box3d import *\n\ndef decode_box(box):\n    yaw = torch.atan2(box[..., SIN_YAW], box[..., COS_YAW])\n    box = torch.cat(\n        [\n            box[..., [X, Y, Z]],\n            box[..., [W, L, H]].exp(),\n            yaw[..., None],\n            box[..., VX:],\n        ],\n        dim=-1,\n    )\n    return box\n\n\n@BBOX_CODERS.register_module()\nclass SparseBox3DDecoder(object):\n    def __init__(\n        self,\n        num_output: int = 300,\n        score_threshold: Optional[float] = None,\n        sorted: bool = True,\n    ):\n        super(SparseBox3DDecoder, self).__init__()\n        self.num_output = num_output\n        self.score_threshold = score_threshold\n        self.sorted = sorted\n\n    def decode(\n        self,\n        cls_scores,\n        box_preds,\n        instance_id=None,\n        quality=None,\n        output_idx=-1,\n    ):\n        squeeze_cls = instance_id is not None\n\n        cls_scores = cls_scores[output_idx].sigmoid()\n\n        if squeeze_cls:\n            cls_scores, cls_ids = cls_scores.max(dim=-1)\n            cls_scores = cls_scores.unsqueeze(dim=-1)\n\n        box_preds = box_preds[output_idx]\n        bs, num_pred, num_cls = cls_scores.shape\n        cls_scores, indices = cls_scores.flatten(start_dim=1).topk(\n            self.num_output, dim=1, sorted=self.sorted\n        )\n        if not squeeze_cls:\n            cls_ids = indices % num_cls\n        if self.score_threshold is not None:\n            mask = cls_scores >= self.score_threshold\n\n        if quality[output_idx] is None:\n            quality = None\n        if quality is not None:\n            centerness = quality[output_idx][..., CNS]\n            centerness = torch.gather(centerness, 1, indices // num_cls)\n            cls_scores_origin = cls_scores.clone()\n            cls_scores *= centerness.sigmoid()\n            cls_scores, idx = torch.sort(cls_scores, dim=1, descending=True)\n            if not squeeze_cls:\n                cls_ids = torch.gather(cls_ids, 1, idx)\n            if self.score_threshold is not None:\n                mask = torch.gather(mask, 1, idx)\n            indices = torch.gather(indices, 1, idx)\n\n        output = []\n        for i in range(bs):\n            category_ids = cls_ids[i]\n            if squeeze_cls:\n                category_ids = category_ids[indices[i]]\n            scores = cls_scores[i]\n            box = box_preds[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                category_ids = category_ids[mask[i]]\n                scores = scores[mask[i]]\n                box = box[mask[i]]\n            if quality is not None:\n                scores_origin = cls_scores_origin[i]\n                if self.score_threshold is not None:\n                    scores_origin = scores_origin[mask[i]]\n\n            box = decode_box(box)\n            output.append(\n                {\n                    \"boxes_3d\": box.cpu(),\n                    \"scores_3d\": scores.cpu(),\n                    \"labels_3d\": category_ids.cpu(),\n                }\n            )\n            if quality is not None:\n                output[-1][\"cls_scores\"] = scores_origin.cpu()\n            if instance_id is not None:\n                ids = instance_id[i, indices[i]]\n                if self.score_threshold is not None:\n                    ids = ids[mask[i]]\n                output[-1][\"instance_ids\"] = ids\n        return output\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/detection3d_blocks.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\n\nfrom mmcv.cnn import Linear, Scale, bias_init_with_prob\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.registry import (\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n)\n\nfrom projects.mmdet3d_plugin.core.box3d import *\nfrom ..blocks import linear_relu_ln\n\n__all__ = [\n    \"SparseBox3DRefinementModule\",\n    \"SparseBox3DKeyPointsGenerator\",\n    \"SparseBox3DEncoder\",\n]\n\n\n@POSITIONAL_ENCODING.register_module()\nclass SparseBox3DEncoder(BaseModule):\n    def __init__(\n        self,\n        embed_dims,\n        vel_dims=3,\n        mode=\"add\",\n        output_fc=True,\n        in_loops=1,\n        out_loops=2,\n    ):\n        super().__init__()\n        assert mode in [\"add\", \"cat\"]\n        self.embed_dims = embed_dims\n        self.vel_dims = vel_dims\n        self.mode = mode\n\n        def embedding_layer(input_dims, output_dims):\n            return nn.Sequential(\n                *linear_relu_ln(output_dims, in_loops, out_loops, input_dims)\n            )\n\n        if not isinstance(embed_dims, (list, tuple)):\n            embed_dims = [embed_dims] * 5\n        self.pos_fc = embedding_layer(3, embed_dims[0])\n        self.size_fc = embedding_layer(3, embed_dims[1])\n        self.yaw_fc = embedding_layer(2, embed_dims[2])\n        if vel_dims > 0:\n            self.vel_fc = embedding_layer(self.vel_dims, embed_dims[3])\n        if output_fc:\n            self.output_fc = embedding_layer(embed_dims[-1], embed_dims[-1])\n        else:\n            self.output_fc = None\n\n    def forward(self, box_3d: torch.Tensor):\n        pos_feat = self.pos_fc(box_3d[..., [X, Y, Z]])\n        size_feat = self.size_fc(box_3d[..., [W, L, H]])\n        yaw_feat = self.yaw_fc(box_3d[..., [SIN_YAW, COS_YAW]])\n        if self.mode == \"add\":\n            output = pos_feat + size_feat + yaw_feat\n        elif self.mode == \"cat\":\n            output = torch.cat([pos_feat, size_feat, yaw_feat], dim=-1)\n\n        if self.vel_dims > 0:\n            vel_feat = self.vel_fc(box_3d[..., VX : VX + self.vel_dims])\n            if self.mode == \"add\":\n                output = output + vel_feat\n            elif self.mode == \"cat\":\n                output = torch.cat([output, vel_feat], dim=-1)\n        if self.output_fc is not None:\n            output = self.output_fc(output)\n\n        return output\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparseBox3DRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        output_dim=11,\n        num_cls=10,\n        normalize_yaw=False,\n        refine_yaw=False,\n        with_cls_branch=True,\n        with_quality_estimation=False,\n    ):\n        super(SparseBox3DRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.output_dim = output_dim\n        self.num_cls = num_cls\n        self.normalize_yaw = normalize_yaw\n        self.refine_yaw = refine_yaw\n\n        self.refine_state = [X, Y, Z, W, L, H]\n        if self.refine_yaw:\n            self.refine_state += [SIN_YAW, COS_YAW]\n\n        self.layers = nn.Sequential(\n            *linear_relu_ln(embed_dims, 2, 2),\n            Linear(self.embed_dims, self.output_dim),\n            Scale([1.0] * self.output_dim),\n        )\n        self.with_cls_branch = with_cls_branch\n        if with_cls_branch:\n            self.cls_layers = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2),\n                Linear(self.embed_dims, self.num_cls),\n            )\n        self.with_quality_estimation = with_quality_estimation\n        if with_quality_estimation:\n            self.quality_layers = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2),\n                Linear(self.embed_dims, 2),\n            )\n\n    def init_weight(self):\n        if self.with_cls_branch:\n            bias_init = bias_init_with_prob(0.01)\n            nn.init.constant_(self.cls_layers[-1].bias, bias_init)\n\n    def forward(\n        self,\n        instance_feature: torch.Tensor,\n        anchor: torch.Tensor,\n        anchor_embed: torch.Tensor,\n        time_interval: torch.Tensor = 1.0,\n        return_cls=True,\n    ):\n        feature = instance_feature + anchor_embed\n        output = self.layers(feature)\n        output[..., self.refine_state] = (\n            output[..., self.refine_state] + anchor[..., self.refine_state]\n        )\n        if self.normalize_yaw:\n            output[..., [SIN_YAW, COS_YAW]] = torch.nn.functional.normalize(\n                output[..., [SIN_YAW, COS_YAW]], dim=-1\n            )\n        if self.output_dim > 8:\n            if not isinstance(time_interval, torch.Tensor):\n                time_interval = instance_feature.new_tensor(time_interval)\n            translation = torch.transpose(output[..., VX:], 0, -1)\n            velocity = torch.transpose(translation / time_interval, 0, -1)\n            output[..., VX:] = velocity + anchor[..., VX:]\n\n        if return_cls:\n            assert self.with_cls_branch, \"Without classification layers !!!\"\n            cls = self.cls_layers(instance_feature)\n        else:\n            cls = None\n        if return_cls and self.with_quality_estimation:\n            quality = self.quality_layers(feature)\n        else:\n            quality = None\n        return output, cls, quality\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparseBox3DKeyPointsGenerator(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        num_learnable_pts=0,\n        fix_scale=None,\n    ):\n        super(SparseBox3DKeyPointsGenerator, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_learnable_pts = num_learnable_pts\n        if fix_scale is None:\n            fix_scale = ((0.0, 0.0, 0.0),)\n        self.fix_scale = nn.Parameter(\n            torch.tensor(fix_scale), requires_grad=False\n        )\n        self.num_pts = len(self.fix_scale) + num_learnable_pts\n        if num_learnable_pts > 0:\n            self.learnable_fc = Linear(self.embed_dims, num_learnable_pts * 3)\n\n    def init_weight(self):\n        if self.num_learnable_pts > 0:\n            xavier_init(self.learnable_fc, distribution=\"uniform\", bias=0.0)\n\n    def forward(\n        self,\n        anchor,\n        instance_feature=None,\n        T_cur2temp_list=None,\n        cur_timestamp=None,\n        temp_timestamps=None,\n    ):\n        bs, num_anchor = anchor.shape[:2]\n        size = anchor[..., None, [W, L, H]].exp()\n        key_points = self.fix_scale * size\n        if self.num_learnable_pts > 0 and instance_feature is not None:\n            learnable_scale = (\n                self.learnable_fc(instance_feature)\n                .reshape(bs, num_anchor, self.num_learnable_pts, 3)\n                .sigmoid()\n                - 0.5\n            )\n            key_points = torch.cat(\n                [key_points, learnable_scale * size], dim=-2\n            )\n\n        rotation_mat = anchor.new_zeros([bs, num_anchor, 3, 3])\n\n        rotation_mat[:, :, 0, 0] = anchor[:, :, COS_YAW]\n        rotation_mat[:, :, 0, 1] = -anchor[:, :, SIN_YAW]\n        rotation_mat[:, :, 1, 0] = anchor[:, :, SIN_YAW]\n        rotation_mat[:, :, 1, 1] = anchor[:, :, COS_YAW]\n        rotation_mat[:, :, 2, 2] = 1\n\n        key_points = torch.matmul(\n            rotation_mat[:, :, None], key_points[..., None]\n        ).squeeze(-1)\n        key_points = key_points + anchor[..., None, [X, Y, Z]]\n\n        if (\n            cur_timestamp is None\n            or temp_timestamps is None\n            or T_cur2temp_list is None\n            or len(temp_timestamps) == 0\n        ):\n            return key_points\n\n        temp_key_points_list = []\n        velocity = anchor[..., VX:]\n        for i, t_time in enumerate(temp_timestamps):\n            time_interval = cur_timestamp - t_time\n            translation = (\n                velocity\n                * time_interval.to(dtype=velocity.dtype)[:, None, None]\n            )\n            temp_key_points = key_points - translation[:, :, None]\n            T_cur2temp = T_cur2temp_list[i].to(dtype=key_points.dtype)\n            temp_key_points = (\n                T_cur2temp[:, None, None, :3]\n                @ torch.cat(\n                    [\n                        temp_key_points,\n                        torch.ones_like(temp_key_points[..., :1]),\n                    ],\n                    dim=-1,\n                ).unsqueeze(-1)\n            )\n            temp_key_points = temp_key_points.squeeze(-1)\n            temp_key_points_list.append(temp_key_points)\n        return key_points, temp_key_points_list\n\n    @staticmethod\n    def anchor_projection(\n        anchor,\n        T_src2dst_list,\n        src_timestamp=None,\n        dst_timestamps=None,\n        time_intervals=None,\n    ):\n        dst_anchors = []\n        for i in range(len(T_src2dst_list)):\n            vel = anchor[..., VX:]\n            vel_dim = vel.shape[-1]\n            T_src2dst = torch.unsqueeze(\n                T_src2dst_list[i].to(dtype=anchor.dtype), dim=1\n            )\n\n            center = anchor[..., [X, Y, Z]]\n            if time_intervals is not None:\n                time_interval = time_intervals[i]\n            elif src_timestamp is not None and dst_timestamps is not None:\n                time_interval = (src_timestamp - dst_timestamps[i]).to(\n                    dtype=vel.dtype\n                )\n            else:\n                time_interval = None\n            if time_interval is not None:\n                translation = vel.transpose(0, -1) * time_interval\n                translation = translation.transpose(0, -1)\n                center = center - translation\n            center = (\n                torch.matmul(\n                    T_src2dst[..., :3, :3], center[..., None]\n                ).squeeze(dim=-1)\n                + T_src2dst[..., :3, 3]\n            )\n            size = anchor[..., [W, L, H]]\n            yaw = torch.matmul(\n                T_src2dst[..., :2, :2],\n                anchor[..., [COS_YAW, SIN_YAW], None],\n            ).squeeze(-1)\n            yaw = yaw[..., [1,0]]\n            vel = torch.matmul(\n                T_src2dst[..., :vel_dim, :vel_dim], vel[..., None]\n            ).squeeze(-1)\n            dst_anchor = torch.cat([center, size, yaw, vel], dim=-1)\n            dst_anchors.append(dst_anchor)\n        return dst_anchors\n\n    @staticmethod\n    def distance(anchor):\n        return torch.norm(anchor[..., :2], p=2, dim=-1)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/detection3d_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\nfrom mmdet.core.bbox.builder import BBOX_CODERS\nfrom mmdet.models import HEADS, LOSSES\nfrom mmdet.core import reduce_mean\nfrom .feature_enhance import FeatureEnhancer\nfrom ..blocks import DeformableFeatureAggregation as DFG\n\n__all__ = [\"Sparse4DHead\"]\n\n\n@HEADS.register_module()\nclass Sparse4DHead(BaseModule):\n    def __init__(\n        self,\n        instance_bank: dict,\n        anchor_encoder: dict,\n        graph_model: dict,\n        norm_layer: dict,\n        ffn: dict,\n        deformable_model: dict,\n        refine_layer: dict,\n        num_decoder: int = 6,\n        num_single_frame_decoder: int = -1,\n        temp_graph_model: dict = None,\n        loss_cls: dict = None,\n        loss_reg: dict = None,\n        decoder: dict = None,\n        sampler: dict = None,\n        gt_cls_key: str = \"gt_labels_3d\",\n        gt_reg_key: str = \"gt_bboxes_3d\",\n        gt_id_key: str = \"instance_id\",\n        with_instance_id: bool = True,\n        task_prefix: str = 'det',\n        reg_weights: List = None,\n        operation_order: Optional[List[str]] = None,\n        cls_threshold_to_reg: float = -1,\n        dn_loss_weight: float = 5.0,\n        decouple_attn: bool = True,\n        init_cfg: dict = None,\n        **kwargs,\n    ):\n        super(Sparse4DHead, self).__init__(init_cfg)\n        self.num_decoder = num_decoder\n        self.num_single_frame_decoder = num_single_frame_decoder\n        self.gt_cls_key = gt_cls_key\n        self.gt_reg_key = gt_reg_key\n        self.gt_id_key = gt_id_key\n        self.with_instance_id = with_instance_id\n        self.task_prefix = task_prefix\n        self.cls_threshold_to_reg = cls_threshold_to_reg\n        self.dn_loss_weight = dn_loss_weight\n        self.decouple_attn = decouple_attn\n\n        if reg_weights is None:\n            self.reg_weights = [1.0] * 10\n        else:\n            self.reg_weights = reg_weights\n\n        if operation_order is None:\n            operation_order = [\n                \"temp_gnn\",\n                \"gnn\",\n                \"norm\",\n                \"deformable\",\n                \"norm\",\n                \"ffn\",\n                \"norm\",\n                \"refine\",\n            ] * num_decoder\n            # delete the 'gnn' and 'norm' layers in the first transformer blocks\n            operation_order = operation_order[3:]\n        self.operation_order = operation_order\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.instance_bank = build(instance_bank, PLUGIN_LAYERS)\n        self.anchor_encoder = build(anchor_encoder, POSITIONAL_ENCODING)\n        self.sampler = build(sampler, BBOX_SAMPLERS)\n        self.decoder = build(decoder, BBOX_CODERS)\n        self.loss_cls = build(loss_cls, LOSSES)\n        self.loss_reg = build(loss_reg, LOSSES)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"deformable\": [deformable_model, ATTENTION],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = self.instance_bank.embed_dims\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self,\n        feature_maps: Union[torch.Tensor, List],\n        metas: dict,\n    ):\n        if isinstance(feature_maps, torch.Tensor):\n            feature_maps = [feature_maps]\n        batch_size = feature_maps[0].shape[0]\n\n        # ========= get instance info ============\n        if (\n            self.sampler.dn_metas is not None\n            and self.sampler.dn_metas[\"dn_anchor\"].shape[0] != batch_size\n        ):\n            self.sampler.dn_metas = None\n        (\n            instance_feature,\n            anchor,\n            temp_instance_feature,\n            temp_anchor,\n            time_interval,\n        ) = self.instance_bank.get(\n            batch_size, metas, dn_metas=self.sampler.dn_metas\n        )\n        # import pdb; pdb.set_trace()\n        # ========= prepare for denosing training ============\n        # 1. get dn metas: noisy-anchors and corresponding GT\n        # 2. concat learnable instances and noisy instances\n        # 3. get attention mask\n        attn_mask = None\n        dn_metas = None\n        temp_dn_reg_target = None\n        if self.training and hasattr(self.sampler, \"get_dn_anchors\"):\n            if self.gt_id_key in metas[\"img_metas\"][0]:\n                gt_instance_id = [\n                    torch.from_numpy(x[self.gt_id_key]).cuda()\n                    for x in metas[\"img_metas\"]\n                ]\n            else:\n                gt_instance_id = None\n            dn_metas = self.sampler.get_dn_anchors(\n                metas[self.gt_cls_key],\n                metas[self.gt_reg_key],\n                gt_instance_id,\n            )\n        if dn_metas is not None:\n            (\n                dn_anchor,\n                dn_reg_target,\n                dn_cls_target,\n                dn_attn_mask,\n                valid_mask,\n                dn_id_target,\n            ) = dn_metas\n            num_dn_anchor = dn_anchor.shape[1]\n            if dn_anchor.shape[-1] != anchor.shape[-1]:\n                remain_state_dims = anchor.shape[-1] - dn_anchor.shape[-1]\n                dn_anchor = torch.cat(\n                    [\n                        dn_anchor,\n                        dn_anchor.new_zeros(\n                            batch_size, num_dn_anchor, remain_state_dims\n                        ),\n                    ],\n                    dim=-1,\n                )\n            anchor = torch.cat([anchor, dn_anchor], dim=1)\n            instance_feature = torch.cat(\n                [\n                    instance_feature,\n                    instance_feature.new_zeros(\n                        batch_size, num_dn_anchor, instance_feature.shape[-1]\n                    ),\n                ],\n                dim=1,\n            )\n            num_instance = instance_feature.shape[1]\n            num_free_instance = num_instance - num_dn_anchor\n            attn_mask = anchor.new_ones(\n                (num_instance, num_instance), dtype=torch.bool\n            )\n            attn_mask[:num_free_instance, :num_free_instance] = False\n            attn_mask[num_free_instance:, num_free_instance:] = dn_attn_mask\n\n        anchor_embed = self.anchor_encoder(anchor)\n        if temp_anchor is not None:\n            temp_anchor_embed = self.anchor_encoder(temp_anchor)\n        else:\n            temp_anchor_embed = None\n\n        # =================== forward the layers ====================\n        prediction = []\n        classification = []\n        quality = []\n        \n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed,\n                    key_pos=temp_anchor_embed,\n                    attn_mask=attn_mask\n                    if temp_instance_feature is None\n                    else None,\n                )\n            elif op == \"gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    value=instance_feature,\n                    query_pos=anchor_embed,\n                    attn_mask=attn_mask,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"deformable\":\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    anchor,\n                    anchor_embed,\n                    feature_maps,\n                    metas,\n                )\n            elif op == \"refine\":\n                anchor, cls, qt = self.layers[i](\n                    instance_feature,\n                    anchor,\n                    anchor_embed,\n                    time_interval=time_interval,\n                    return_cls=True,\n                )\n                prediction.append(anchor)\n                classification.append(cls)\n                quality.append(qt)\n                if len(prediction) == self.num_single_frame_decoder:\n                    instance_feature, anchor = self.instance_bank.update(\n                        instance_feature, anchor, cls\n                    )\n                    if (\n                        dn_metas is not None\n                        and self.sampler.num_temp_dn_groups > 0\n                        and dn_id_target is not None\n                    ):\n                        (\n                            instance_feature,\n                            anchor,\n                            temp_dn_reg_target,\n                            temp_dn_cls_target,\n                            temp_valid_mask,\n                            dn_id_target,\n                        ) = self.sampler.update_dn(\n                            instance_feature,\n                            anchor,\n                            dn_reg_target,\n                            dn_cls_target,\n                            valid_mask,\n                            dn_id_target,\n                            self.instance_bank.num_anchor,\n                            self.instance_bank.mask,\n                        )\n                anchor_embed = self.anchor_encoder(anchor)\n                if (\n                    len(prediction) > self.num_single_frame_decoder\n                    and temp_anchor_embed is not None\n                ):\n                    temp_anchor_embed = anchor_embed[\n                        :, : self.instance_bank.num_temp_instances\n                    ]\n            else:\n                raise NotImplementedError(f\"{op} is not supported.\")\n\n        output = {}\n\n        # split predictions of learnable instances and noisy instances\n        if dn_metas is not None:\n            dn_classification = [\n                x[:, num_free_instance:] for x in classification\n            ]\n            classification = [x[:, :num_free_instance] for x in classification]\n            dn_prediction = [x[:, num_free_instance:] for x in prediction]\n            prediction = [x[:, :num_free_instance] for x in prediction]\n            quality = [\n                x[:, :num_free_instance] if x is not None else None\n                for x in quality\n            ]\n            output.update(\n                {\n                    \"dn_prediction\": dn_prediction,\n                    \"dn_classification\": dn_classification,\n                    \"dn_reg_target\": dn_reg_target,\n                    \"dn_cls_target\": dn_cls_target,\n                    \"dn_valid_mask\": valid_mask,\n                }\n            )\n            if temp_dn_reg_target is not None:\n                output.update(\n                    {\n                        \"temp_dn_reg_target\": temp_dn_reg_target,\n                        \"temp_dn_cls_target\": temp_dn_cls_target,\n                        \"temp_dn_valid_mask\": temp_valid_mask,\n                        \"dn_id_target\": dn_id_target,\n                    }\n                )\n                dn_cls_target = temp_dn_cls_target\n                valid_mask = temp_valid_mask\n            dn_instance_feature = instance_feature[:, num_free_instance:]\n            dn_anchor = anchor[:, num_free_instance:]\n            instance_feature = instance_feature[:, :num_free_instance]\n            anchor_embed = anchor_embed[:, :num_free_instance]\n            anchor = anchor[:, :num_free_instance]\n            cls = cls[:, :num_free_instance]\n\n            # cache dn_metas for temporal denoising\n            self.sampler.cache_dn(\n                dn_instance_feature,\n                dn_anchor,\n                dn_cls_target,\n                valid_mask,\n                dn_id_target,\n            )\n        output.update(\n            {\n                \"classification\": classification,\n                \"prediction\": prediction,\n                \"quality\": quality,\n                \"instance_feature\": instance_feature,\n                \"anchor_embed\": anchor_embed,\n            }\n        )\n\n        # cache current instances for temporal modeling\n        self.instance_bank.cache(\n            instance_feature, anchor, cls, metas, feature_maps\n        )\n        if self.with_instance_id:\n            instance_id = self.instance_bank.get_instance_id(\n                cls, anchor, self.decoder.score_threshold\n            )\n            output[\"instance_id\"] = instance_id\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss(self, model_outs, data, feature_maps=None):\n        # ===================== prediction losses ======================\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        quality = model_outs[\"quality\"]\n        output = {}\n        for decoder_idx, (cls, reg, qt) in enumerate(\n            zip(cls_scores, reg_preds, quality)\n        ):\n            reg = reg[..., : len(self.reg_weights)]\n            cls_target, reg_target, reg_weights = self.sampler.sample(\n                cls,\n                reg,\n                data[self.gt_cls_key],\n                data[self.gt_reg_key],\n            )\n            reg_target = reg_target[..., : len(self.reg_weights)]\n            reg_target_full = reg_target.clone()\n            mask = torch.logical_not(torch.all(reg_target == 0, dim=-1))\n            mask_valid = mask.clone()\n\n            num_pos = max(\n                reduce_mean(torch.sum(mask).to(dtype=reg.dtype)), 1.0\n            )\n            if self.cls_threshold_to_reg > 0:\n                threshold = self.cls_threshold_to_reg\n                mask = torch.logical_and(\n                    mask, cls.max(dim=-1).values.sigmoid() > threshold\n                )\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_loss = self.loss_cls(cls, cls_target, avg_factor=num_pos)\n\n            mask = mask.reshape(-1)\n            reg_weights = reg_weights * reg.new_tensor(self.reg_weights)\n            reg_target = reg_target.flatten(end_dim=1)[mask]\n            reg = reg.flatten(end_dim=1)[mask]\n            reg_weights = reg_weights.flatten(end_dim=1)[mask]\n            reg_target = torch.where(\n                reg_target.isnan(), reg.new_tensor(0.0), reg_target\n            )\n            cls_target = cls_target[mask]\n            if qt is not None:\n                qt = qt.flatten(end_dim=1)[mask]\n\n            reg_loss = self.loss_reg(\n                reg,\n                reg_target,\n                weight=reg_weights,\n                avg_factor=num_pos,\n                prefix=f\"{self.task_prefix}_\",\n                suffix=f\"_{decoder_idx}\",\n                quality=qt,\n                cls_target=cls_target,\n            )\n\n            output[f\"{self.task_prefix}_loss_cls_{decoder_idx}\"] = cls_loss\n            output.update(reg_loss)\n\n        if \"dn_prediction\" not in model_outs:\n            return output\n\n        # ===================== denoising losses ======================\n        dn_cls_scores = model_outs[\"dn_classification\"]\n        dn_reg_preds = model_outs[\"dn_prediction\"]\n\n        (\n            dn_valid_mask,\n            dn_cls_target,\n            dn_reg_target,\n            dn_pos_mask,\n            reg_weights,\n            num_dn_pos,\n        ) = self.prepare_for_dn_loss(model_outs)\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(dn_cls_scores, dn_reg_preds)\n        ):\n            if (\n                \"temp_dn_valid_mask\" in model_outs\n                and decoder_idx == self.num_single_frame_decoder\n            ):\n                (\n                    dn_valid_mask,\n                    dn_cls_target,\n                    dn_reg_target,\n                    dn_pos_mask,\n                    reg_weights,\n                    num_dn_pos,\n                ) = self.prepare_for_dn_loss(model_outs, prefix=\"temp_\")\n\n            cls_loss = self.loss_cls(\n                cls.flatten(end_dim=1)[dn_valid_mask],\n                dn_cls_target,\n                avg_factor=num_dn_pos,\n            )\n            reg_loss = self.loss_reg(\n                reg.flatten(end_dim=1)[dn_valid_mask][dn_pos_mask][\n                    ..., : len(self.reg_weights)\n                ],\n                dn_reg_target,\n                avg_factor=num_dn_pos,\n                weight=reg_weights,\n                prefix=f\"{self.task_prefix}_\",\n                suffix=f\"_dn_{decoder_idx}\",\n            )\n            output[f\"{self.task_prefix}_loss_cls_dn_{decoder_idx}\"] = cls_loss\n            output.update(reg_loss)\n        return output\n\n    def prepare_for_dn_loss(self, model_outs, prefix=\"\"):\n        dn_valid_mask = model_outs[f\"{prefix}dn_valid_mask\"].flatten(end_dim=1)\n        dn_cls_target = model_outs[f\"{prefix}dn_cls_target\"].flatten(\n            end_dim=1\n        )[dn_valid_mask]\n        dn_reg_target = model_outs[f\"{prefix}dn_reg_target\"].flatten(\n            end_dim=1\n        )[dn_valid_mask][..., : len(self.reg_weights)]\n        dn_pos_mask = dn_cls_target >= 0\n        dn_reg_target = dn_reg_target[dn_pos_mask]\n        reg_weights = dn_reg_target.new_tensor(self.reg_weights)[None].tile(\n            dn_reg_target.shape[0], 1\n        )\n        num_dn_pos = max(\n            reduce_mean(torch.sum(dn_valid_mask).to(dtype=reg_weights.dtype)),\n            1.0,\n        )\n        return (\n            dn_valid_mask,\n            dn_cls_target,\n            dn_reg_target,\n            dn_pos_mask,\n            reg_weights,\n            num_dn_pos,\n        )\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(self, model_outs, output_idx=-1):\n        return self.decoder.decode(\n            model_outs[\"classification\"],\n            model_outs[\"prediction\"],\n            model_outs.get(\"instance_id\"),\n            model_outs.get(\"quality\"),\n            output_idx=output_idx,\n        )\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/detection3d_head_roboAD.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\nfrom mmdet.core.bbox.builder import BBOX_CODERS\nfrom mmdet.models import HEADS, LOSSES\nfrom mmdet.core import reduce_mean\nfrom .feature_enhance import FeatureEnhancer\nfrom ..blocks import DeformableFeatureAggregation as DFG\n\n__all__ = [\"Sparse4DHead_roboAD\"]\n\n\n@HEADS.register_module()\nclass Sparse4DHead_roboAD(BaseModule):\n    def __init__(\n        self,\n        instance_bank: dict,\n        anchor_encoder: dict,\n        graph_model: dict,\n        norm_layer: dict,\n        ffn: dict,\n        deformable_model: dict,\n        refine_layer: dict,\n        num_decoder: int = 6,\n        num_single_frame_decoder: int = -1,\n        temp_graph_model: dict = None,\n        loss_cls: dict = None,\n        loss_reg: dict = None,\n        decoder: dict = None,\n        sampler: dict = None,\n        gt_cls_key: str = \"gt_labels_3d\",\n        gt_reg_key: str = \"gt_bboxes_3d\",\n        gt_id_key: str = \"instance_id\",\n        with_instance_id: bool = True,\n        task_prefix: str = 'det',\n        reg_weights: List = None,\n        operation_order: Optional[List[str]] = None,\n        cls_threshold_to_reg: float = -1,\n        dn_loss_weight: float = 5.0,\n        decouple_attn: bool = True,\n        init_cfg: dict = None,\n        **kwargs,\n    ):\n        super(Sparse4DHead_roboAD, self).__init__(init_cfg)\n        self.num_decoder = num_decoder\n        self.num_single_frame_decoder = num_single_frame_decoder\n        self.gt_cls_key = gt_cls_key\n        self.gt_reg_key = gt_reg_key\n        self.gt_id_key = gt_id_key\n        self.with_instance_id = with_instance_id\n        self.task_prefix = task_prefix\n        self.cls_threshold_to_reg = cls_threshold_to_reg\n        self.dn_loss_weight = dn_loss_weight\n        self.decouple_attn = decouple_attn\n\n        if reg_weights is None:\n            self.reg_weights = [1.0] * 10\n        else:\n            self.reg_weights = reg_weights\n\n        # import pdb; pdb.set_trace()\n        if operation_order is None:\n            operation_order = [\n                \"temp_gnn\",\n                \"gnn\",\n                \"norm\",\n                \"deformable\",\n                \"norm\",\n                \"ffn\",\n                \"norm\",\n                \"refine\",\n            ] * num_decoder\n            # delete the 'gnn' and 'norm' layers in the first transformer blocks\n            operation_order = operation_order[3:]\n        # import pdb; pdb.set_trace()\n        self.operation_order = operation_order\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.instance_bank = build(instance_bank, PLUGIN_LAYERS)\n        self.anchor_encoder = build(anchor_encoder, POSITIONAL_ENCODING)\n        self.sampler = build(sampler, BBOX_SAMPLERS)\n        self.decoder = build(decoder, BBOX_CODERS)\n        self.loss_cls = build(loss_cls, LOSSES)\n        self.loss_reg = build(loss_reg, LOSSES)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"deformable\": [deformable_model, ATTENTION],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n            \"denoise\": [graph_model, ATTENTION],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        # import pdb;pdb.set_trace()\n        self.embed_dims = self.instance_bank.embed_dims\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self,\n        feature_maps: Union[torch.Tensor, List],\n        metas: dict,\n    ):\n        if isinstance(feature_maps, torch.Tensor):\n            feature_maps = [feature_maps]\n        batch_size = feature_maps[0].shape[0]\n\n        # ========= get instance info ============\n        if (\n            self.sampler.dn_metas is not None\n            and self.sampler.dn_metas[\"dn_anchor\"].shape[0] != batch_size\n        ):\n            self.sampler.dn_metas = None\n        (\n            instance_feature,\n            anchor,\n            temp_instance_feature,\n            temp_anchor,\n            time_interval,\n        ) = self.instance_bank.get(\n            batch_size, metas, dn_metas=self.sampler.dn_metas\n        )\n        # import pdb; pdb.set_trace()\n        # ========= prepare for denosing training ============\n        # 1. get dn metas: noisy-anchors and corresponding GT\n        # 2. concat learnable instances and noisy instances\n        # 3. get attention mask\n        \n        attn_mask = None\n        dn_metas = None\n        temp_dn_reg_target = None\n        if self.training and hasattr(self.sampler, \"get_dn_anchors\"):\n            if self.gt_id_key in metas[\"img_metas\"][0]:\n                gt_instance_id = [\n                    torch.from_numpy(x[self.gt_id_key]).cuda()\n                    for x in metas[\"img_metas\"]\n                ]\n            else:\n                gt_instance_id = None\n            dn_metas = self.sampler.get_dn_anchors(\n                metas[self.gt_cls_key],\n                metas[self.gt_reg_key],\n                gt_instance_id,\n            )\n        if dn_metas is not None:\n            (\n                dn_anchor,\n                dn_reg_target,\n                dn_cls_target,\n                dn_attn_mask,\n                valid_mask,\n                dn_id_target,\n            ) = dn_metas\n            num_dn_anchor = dn_anchor.shape[1]\n            if dn_anchor.shape[-1] != anchor.shape[-1]:\n                remain_state_dims = anchor.shape[-1] - dn_anchor.shape[-1]\n                dn_anchor = torch.cat(\n                    [\n                        dn_anchor,\n                        dn_anchor.new_zeros(\n                            batch_size, num_dn_anchor, remain_state_dims\n                        ),\n                    ],\n                    dim=-1,\n                )\n            anchor = torch.cat([anchor, dn_anchor], dim=1)\n            instance_feature = torch.cat(\n                [\n                    instance_feature,\n                    instance_feature.new_zeros(\n                        batch_size, num_dn_anchor, instance_feature.shape[-1]\n                    ),\n                ],\n                dim=1,\n            )\n            num_instance = instance_feature.shape[1]\n            num_free_instance = num_instance - num_dn_anchor\n            attn_mask = anchor.new_ones(\n                (num_instance, num_instance), dtype=torch.bool\n            )\n            attn_mask[:num_free_instance, :num_free_instance] = False\n            attn_mask[num_free_instance:, num_free_instance:] = dn_attn_mask\n\n        anchor_embed = self.anchor_encoder(anchor)\n        if temp_anchor is not None:\n            temp_anchor_embed = self.anchor_encoder(temp_anchor)\n        else:\n            temp_anchor_embed = None\n\n        # =================== forward the layers ====================\n        prediction = []\n        classification = []\n        quality = []\n        # import pdb;pdb.set_trace()\n        \n        for i, op in enumerate(self.operation_order):\n            # print(\"op\",op)\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                # print(\"------------------temp_gnn--------------------------------\")\n\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed,\n                    key_pos=temp_anchor_embed,\n                    attn_mask=attn_mask\n                    if temp_instance_feature is None\n                    else None,\n                )\n            \n            elif op == \"denoise\":\n                # print(\"--------------------denoise------------------------------\")\n                if self.training:\n                    model = FeatureEnhancer(input_dim=256, noise_level=0.1)\n                    instance_feature = model(instance_feature)\n                else:\n                    model = FeatureEnhancer(input_dim=256, noise_level=0.0)\n                    instance_feature = model(instance_feature)\n            elif op == \"gnn\":\n                # print(\"--------------------gnn------------------------------\")\n\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    value=instance_feature,\n                    query_pos=anchor_embed,\n                    attn_mask=attn_mask,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                # print(\"--------------------norm----------------ffn--------------\")\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"deformable\":\n                # print(\"--------------------deformable------------------------------\")\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    anchor,\n                    anchor_embed,\n                    feature_maps,\n                    metas,\n                )\n            elif op == \"refine\":\n                # print(\"--------------------refine------------------------------\")\n                anchor, cls, qt = self.layers[i](\n                    instance_feature,\n                    anchor,\n                    anchor_embed,\n                    time_interval=time_interval,\n                    return_cls=True,\n                )\n                prediction.append(anchor)\n                classification.append(cls)\n                quality.append(qt)\n                if len(prediction) == self.num_single_frame_decoder:\n                    instance_feature, anchor = self.instance_bank.update(\n                        instance_feature, anchor, cls\n                    )\n                    if (\n                        dn_metas is not None\n                        and self.sampler.num_temp_dn_groups > 0\n                        and dn_id_target is not None\n                    ):\n                        (\n                            instance_feature,\n                            anchor,\n                            temp_dn_reg_target,\n                            temp_dn_cls_target,\n                            temp_valid_mask,\n                            dn_id_target,\n                        ) = self.sampler.update_dn(\n                            instance_feature,\n                            anchor,\n                            dn_reg_target,\n                            dn_cls_target,\n                            valid_mask,\n                            dn_id_target,\n                            self.instance_bank.num_anchor,\n                            self.instance_bank.mask,\n                        )\n                anchor_embed = self.anchor_encoder(anchor)\n                if (\n                    len(prediction) > self.num_single_frame_decoder\n                    and temp_anchor_embed is not None\n                ):\n                    temp_anchor_embed = anchor_embed[\n                        :, : self.instance_bank.num_temp_instances\n                    ]\n            else:\n                raise NotImplementedError(f\"{op} is not supported.\")\n\n        output = {}\n\n        # split predictions of learnable instances and noisy instances\n        if dn_metas is not None:\n            dn_classification = [\n                x[:, num_free_instance:] for x in classification\n            ]\n            classification = [x[:, :num_free_instance] for x in classification]\n            dn_prediction = [x[:, num_free_instance:] for x in prediction]\n            prediction = [x[:, :num_free_instance] for x in prediction]\n            quality = [\n                x[:, :num_free_instance] if x is not None else None\n                for x in quality\n            ]\n            output.update(\n                {\n                    \"dn_prediction\": dn_prediction,\n                    \"dn_classification\": dn_classification,\n                    \"dn_reg_target\": dn_reg_target,\n                    \"dn_cls_target\": dn_cls_target,\n                    \"dn_valid_mask\": valid_mask,\n                }\n            )\n            if temp_dn_reg_target is not None:\n                output.update(\n                    {\n                        \"temp_dn_reg_target\": temp_dn_reg_target,\n                        \"temp_dn_cls_target\": temp_dn_cls_target,\n                        \"temp_dn_valid_mask\": temp_valid_mask,\n                        \"dn_id_target\": dn_id_target,\n                    }\n                )\n                dn_cls_target = temp_dn_cls_target\n                valid_mask = temp_valid_mask\n            dn_instance_feature = instance_feature[:, num_free_instance:]\n            dn_anchor = anchor[:, num_free_instance:]\n            instance_feature = instance_feature[:, :num_free_instance]\n            anchor_embed = anchor_embed[:, :num_free_instance]\n            anchor = anchor[:, :num_free_instance]\n            cls = cls[:, :num_free_instance]\n\n            # cache dn_metas for temporal denoising\n            self.sampler.cache_dn(\n                dn_instance_feature,\n                dn_anchor,\n                dn_cls_target,\n                valid_mask,\n                dn_id_target,\n            )\n        output.update(\n            {\n                \"classification\": classification,\n                \"prediction\": prediction,\n                \"quality\": quality,\n                \"instance_feature\": instance_feature,\n                \"anchor_embed\": anchor_embed,\n            }\n        )\n\n        # cache current instances for temporal modeling\n        self.instance_bank.cache(\n            instance_feature, anchor, cls, metas, feature_maps\n        )\n        if self.with_instance_id:\n            instance_id = self.instance_bank.get_instance_id(\n                cls, anchor, self.decoder.score_threshold\n            )\n            output[\"instance_id\"] = instance_id\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss(self, model_outs, data, feature_maps=None):\n        # ===================== prediction losses ======================\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        quality = model_outs[\"quality\"]\n        output = {}\n        for decoder_idx, (cls, reg, qt) in enumerate(\n            zip(cls_scores, reg_preds, quality)\n        ):\n            reg = reg[..., : len(self.reg_weights)]\n            cls_target, reg_target, reg_weights = self.sampler.sample(\n                cls,\n                reg,\n                data[self.gt_cls_key],\n                data[self.gt_reg_key],\n            )\n            reg_target = reg_target[..., : len(self.reg_weights)]\n            reg_target_full = reg_target.clone()\n            mask = torch.logical_not(torch.all(reg_target == 0, dim=-1))\n            mask_valid = mask.clone()\n\n            num_pos = max(\n                reduce_mean(torch.sum(mask).to(dtype=reg.dtype)), 1.0\n            )\n            if self.cls_threshold_to_reg > 0:\n                threshold = self.cls_threshold_to_reg\n                mask = torch.logical_and(\n                    mask, cls.max(dim=-1).values.sigmoid() > threshold\n                )\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_loss = self.loss_cls(cls, cls_target, avg_factor=num_pos)\n\n            mask = mask.reshape(-1)\n            reg_weights = reg_weights * reg.new_tensor(self.reg_weights)\n            reg_target = reg_target.flatten(end_dim=1)[mask]\n            reg = reg.flatten(end_dim=1)[mask]\n            reg_weights = reg_weights.flatten(end_dim=1)[mask]\n            reg_target = torch.where(\n                reg_target.isnan(), reg.new_tensor(0.0), reg_target\n            )\n            cls_target = cls_target[mask]\n            if qt is not None:\n                qt = qt.flatten(end_dim=1)[mask]\n\n            reg_loss = self.loss_reg(\n                reg,\n                reg_target,\n                weight=reg_weights,\n                avg_factor=num_pos,\n                prefix=f\"{self.task_prefix}_\",\n                suffix=f\"_{decoder_idx}\",\n                quality=qt,\n                cls_target=cls_target,\n            )\n\n            output[f\"{self.task_prefix}_loss_cls_{decoder_idx}\"] = cls_loss\n            output.update(reg_loss)\n\n        if \"dn_prediction\" not in model_outs:\n            return output\n\n        # ===================== denoising losses ======================\n        dn_cls_scores = model_outs[\"dn_classification\"]\n        dn_reg_preds = model_outs[\"dn_prediction\"]\n\n        (\n            dn_valid_mask,\n            dn_cls_target,\n            dn_reg_target,\n            dn_pos_mask,\n            reg_weights,\n            num_dn_pos,\n        ) = self.prepare_for_dn_loss(model_outs)\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(dn_cls_scores, dn_reg_preds)\n        ):\n            if (\n                \"temp_dn_valid_mask\" in model_outs\n                and decoder_idx == self.num_single_frame_decoder\n            ):\n                (\n                    dn_valid_mask,\n                    dn_cls_target,\n                    dn_reg_target,\n                    dn_pos_mask,\n                    reg_weights,\n                    num_dn_pos,\n                ) = self.prepare_for_dn_loss(model_outs, prefix=\"temp_\")\n\n            cls_loss = self.loss_cls(\n                cls.flatten(end_dim=1)[dn_valid_mask],\n                dn_cls_target,\n                avg_factor=num_dn_pos,\n            )\n            reg_loss = self.loss_reg(\n                reg.flatten(end_dim=1)[dn_valid_mask][dn_pos_mask][\n                    ..., : len(self.reg_weights)\n                ],\n                dn_reg_target,\n                avg_factor=num_dn_pos,\n                weight=reg_weights,\n                prefix=f\"{self.task_prefix}_\",\n                suffix=f\"_dn_{decoder_idx}\",\n            )\n            output[f\"{self.task_prefix}_loss_cls_dn_{decoder_idx}\"] = cls_loss\n            output.update(reg_loss)\n        return output\n\n    def prepare_for_dn_loss(self, model_outs, prefix=\"\"):\n        dn_valid_mask = model_outs[f\"{prefix}dn_valid_mask\"].flatten(end_dim=1)\n        dn_cls_target = model_outs[f\"{prefix}dn_cls_target\"].flatten(\n            end_dim=1\n        )[dn_valid_mask]\n        dn_reg_target = model_outs[f\"{prefix}dn_reg_target\"].flatten(\n            end_dim=1\n        )[dn_valid_mask][..., : len(self.reg_weights)]\n        dn_pos_mask = dn_cls_target >= 0\n        dn_reg_target = dn_reg_target[dn_pos_mask]\n        reg_weights = dn_reg_target.new_tensor(self.reg_weights)[None].tile(\n            dn_reg_target.shape[0], 1\n        )\n        num_dn_pos = max(\n            reduce_mean(torch.sum(dn_valid_mask).to(dtype=reg_weights.dtype)),\n            1.0,\n        )\n        return (\n            dn_valid_mask,\n            dn_cls_target,\n            dn_reg_target,\n            dn_pos_mask,\n            reg_weights,\n            num_dn_pos,\n        )\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(self, model_outs, output_idx=-1):\n        return self.decoder.decode(\n            model_outs[\"classification\"],\n            model_outs[\"prediction\"],\n            model_outs.get(\"instance_id\"),\n            model_outs.get(\"quality\"),\n            output_idx=output_idx,\n        )\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/feature_enhance.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nclass SelfAttention(nn.Module):\n    def __init__(self, input_dim):\n        super(SelfAttention, self).__init__()\n        self.query = nn.Linear(input_dim, input_dim)\n        self.key = nn.Linear(input_dim, input_dim)\n        self.value = nn.Linear(input_dim, input_dim)\n\n    def forward(self, x):\n        # 计算 Q, K, V\n        import pdb; pdb.set_trace()\n        Q = self.query(x)  # (batch_size, seq_len, dim)\n        K = self.key(x)\n        V = self.value(x)\n\n        # 计算注意力得分\n        attention_scores = torch.bmm(Q, K.transpose(1, 2)) / (x.size(-1) ** 0.5)  # scaled dot-product\n        attention_weights = F.softmax(attention_scores, dim=-1)\n\n        # 应用注意力权重\n        out = torch.bmm(attention_weights, V)\n        return out, attention_weights\nclass DenoisingAutoencoder(nn.Module):\n    def __init__(self, input_dim):\n        super(DenoisingAutoencoder, self).__init__()\n        self.encoder = nn.Sequential(\n            nn.Linear(input_dim, 128),\n            nn.ReLU(),\n            nn.Linear(128, 64),\n            nn.ReLU()\n        )\n        self.decoder = nn.Sequential(\n            nn.Linear(64, 128),\n            nn.ReLU(),\n            nn.Linear(128, input_dim),\n            nn.Sigmoid()  # 使用Sigmoid确保输出范围在[0, 1]\n        )\n\n    def forward(self, x):\n        encoded = self.encoder(x)\n        decoded = self.decoder(encoded)\n        return decoded\n\n\nclass FeatureEnhancer(nn.Module):\n    def __init__(self, input_dim, noise_level=0.1):\n        super(FeatureEnhancer, self).__init__()\n        self.self_attention = SelfAttention(input_dim)\n        self.noise_level = noise_level\n        self.denoising_autoencoder = DenoisingAutoencoder(input_dim)  # 引入去噪自编码器\n        self.fc = nn.Linear(input_dim, input_dim)  # 用于最终输出的线性层\n\n    def add_noise(self, x):\n        noise = torch.randn_like(x) * self.noise_level\n        return x + noise\n\n    def denoise(self, x):\n        return self.denoising_autoencoder(x)\n\n\n    def forward(self, x):\n        # 添加噪声\n        noisy_x = self.add_noise(x)\n\n        # 使用自注意力机制\n        enhanced_features, _ = self.self_attention.to(x.device)(noisy_x)\n\n        # 去噪声\n        denoised_features = self.denoise.to(x.device)(enhanced_features)\n\n        # 最后的线性变换\n        output = self.fc.to(x.device)(denoised_features)\n        return output\n\n\n# 测试 FeatureEnhancer\nif __name__ == \"__main__\":\n    # 假设的实例特征\n    instance_features = torch.randn(6, 900, 256)  # (batch_size, seq_len, feature_dim)\n\n    # 创建并运行特征增强器\n    model = FeatureEnhancer(input_dim=256, noise_level=0.1)\n    enhanced_instance_features = model(instance_features)\n    import pdb; pdb.set_trace()\n    print(\"原始特征形状:\", instance_features.shape)\n    print(\"增强后特征形状:\", enhanced_instance_features.shape)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/losses.py",
    "content": "import torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.models.builder import LOSSES\n\nfrom projects.mmdet3d_plugin.core.box3d import *\n\n\n@LOSSES.register_module()\nclass SparseBox3DLoss(nn.Module):\n    def __init__(\n        self,\n        loss_box,\n        loss_centerness=None,\n        loss_yawness=None,\n        cls_allow_reverse=None,\n    ):\n        super().__init__()\n\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.loss_box = build(loss_box, LOSSES)\n        self.loss_cns = build(loss_centerness, LOSSES)\n        self.loss_yns = build(loss_yawness, LOSSES)\n        self.cls_allow_reverse = cls_allow_reverse\n\n    def forward(\n        self,\n        box,\n        box_target,\n        weight=None,\n        avg_factor=None,\n        prefix=\"\",\n        suffix=\"\",\n        quality=None,\n        cls_target=None,\n        **kwargs,\n    ):\n        # Some categories do not distinguish between positive and negative\n        # directions. For example, barrier in nuScenes dataset.\n        if self.cls_allow_reverse is not None and cls_target is not None:\n            if_reverse = (\n                torch.nn.functional.cosine_similarity(\n                    box_target[..., [SIN_YAW, COS_YAW]],\n                    box[..., [SIN_YAW, COS_YAW]],\n                    dim=-1,\n                )\n                < 0\n            )\n            if_reverse = (\n                torch.isin(\n                    cls_target, cls_target.new_tensor(self.cls_allow_reverse)\n                )\n                & if_reverse\n            )\n            box_target[..., [SIN_YAW, COS_YAW]] = torch.where(\n                if_reverse[..., None],\n                -box_target[..., [SIN_YAW, COS_YAW]],\n                box_target[..., [SIN_YAW, COS_YAW]],\n            )\n\n        output = {}\n        box_loss = self.loss_box(\n            box, box_target, weight=weight, avg_factor=avg_factor\n        )\n        output[f\"{prefix}loss_box{suffix}\"] = box_loss\n\n        if quality is not None:\n            cns = quality[..., CNS]\n            yns = quality[..., YNS].sigmoid()\n            cns_target = torch.norm(\n                box_target[..., [X, Y, Z]] - box[..., [X, Y, Z]], p=2, dim=-1\n            )\n            cns_target = torch.exp(-cns_target)\n            cns_loss = self.loss_cns(cns, cns_target, avg_factor=avg_factor)\n            output[f\"{prefix}loss_cns{suffix}\"] = cns_loss\n\n            yns_target = (\n                torch.nn.functional.cosine_similarity(\n                    box_target[..., [SIN_YAW, COS_YAW]],\n                    box[..., [SIN_YAW, COS_YAW]],\n                    dim=-1,\n                )\n                > 0\n            )\n            yns_target = yns_target.float()\n            yns_loss = self.loss_yns(yns, yns_target, avg_factor=avg_factor)\n            output[f\"{prefix}loss_yns{suffix}\"] = yns_loss\n        return output\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/detection3d/target.py",
    "content": "import torch\nimport numpy as np\nimport torch.nn.functional as F\nfrom scipy.optimize import linear_sum_assignment\n\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\n\nfrom projects.mmdet3d_plugin.core.box3d import *\nfrom ..base_target import BaseTargetWithDenoising\n\n\n__all__ = [\"SparseBox3DTarget\"]\n\n\n@BBOX_SAMPLERS.register_module()\nclass SparseBox3DTarget(BaseTargetWithDenoising):\n    def __init__(\n        self,\n        cls_weight=2.0,\n        alpha=0.25,\n        gamma=2,\n        eps=1e-12,\n        box_weight=0.25,\n        reg_weights=None,\n        cls_wise_reg_weights=None,\n        num_dn_groups=0,\n        dn_noise_scale=0.5,\n        max_dn_gt=32,\n        add_neg_dn=True,\n        num_temp_dn_groups=0,\n    ):\n        super(SparseBox3DTarget, self).__init__(\n            num_dn_groups, num_temp_dn_groups\n        )\n        self.cls_weight = cls_weight\n        self.box_weight = box_weight\n        self.alpha = alpha\n        self.gamma = gamma\n        self.eps = eps\n        self.reg_weights = reg_weights\n        if self.reg_weights is None:\n            self.reg_weights = [1.0] * 8 + [0.0] * 2\n        self.cls_wise_reg_weights = cls_wise_reg_weights\n        self.dn_noise_scale = dn_noise_scale\n        self.max_dn_gt = max_dn_gt\n        self.add_neg_dn = add_neg_dn\n\n    def encode_reg_target(self, box_target, device=None):\n        outputs = []\n        for box in box_target:\n            output = torch.cat(\n                [\n                    box[..., [X, Y, Z]],\n                    box[..., [W, L, H]].log(),\n                    torch.sin(box[..., YAW]).unsqueeze(-1),\n                    torch.cos(box[..., YAW]).unsqueeze(-1),\n                    box[..., YAW + 1 :],\n                ],\n                dim=-1,\n            )\n            if device is not None:\n                output = output.to(device=device)\n            outputs.append(output)\n        return outputs\n\n    def sample(\n        self,\n        cls_pred,\n        box_pred,\n        cls_target,\n        box_target,\n    ):\n        bs, num_pred, num_cls = cls_pred.shape\n\n        cls_cost = self._cls_cost(cls_pred, cls_target)\n\n        box_target = self.encode_reg_target(box_target, box_pred.device)\n\n        instance_reg_weights = []\n        for i in range(len(box_target)):\n            weights = torch.logical_not(box_target[i].isnan()).to(\n                dtype=box_target[i].dtype\n            )\n            if self.cls_wise_reg_weights is not None:\n                for cls, weight in self.cls_wise_reg_weights.items():\n                    weights = torch.where(\n                        (cls_target[i] == cls)[:, None],\n                        weights.new_tensor(weight),\n                        weights,\n                    )\n            instance_reg_weights.append(weights)\n        box_cost = self._box_cost(box_pred, box_target, instance_reg_weights)\n\n        indices = []\n        for i in range(bs):\n            if cls_cost[i] is not None and box_cost[i] is not None:\n                cost = (cls_cost[i] + box_cost[i]).detach().cpu().numpy()\n                cost = np.where(np.isneginf(cost) | np.isnan(cost), 1e8, cost)\n                assign = linear_sum_assignment(cost)\n                indices.append(\n                    [cls_pred.new_tensor(x, dtype=torch.int64) for x in assign]\n                )\n            else:\n                indices.append([None, None])\n\n        output_cls_target = (\n            cls_target[0].new_ones([bs, num_pred], dtype=torch.long) * num_cls\n        )\n        output_box_target = box_pred.new_zeros(box_pred.shape)\n        output_reg_weights = box_pred.new_zeros(box_pred.shape)\n        for i, (pred_idx, target_idx) in enumerate(indices):\n            if len(cls_target[i]) == 0:\n                continue\n            output_cls_target[i, pred_idx] = cls_target[i][target_idx]\n            output_box_target[i, pred_idx] = box_target[i][target_idx]\n            output_reg_weights[i, pred_idx] = instance_reg_weights[i][\n                target_idx\n            ]\n        self.indices = indices\n        return output_cls_target, output_box_target, output_reg_weights\n\n    def _cls_cost(self, cls_pred, cls_target):\n        bs = cls_pred.shape[0]\n        cls_pred = cls_pred.sigmoid()\n        cost = []\n        for i in range(bs):\n            if len(cls_target[i]) > 0:\n                neg_cost = (\n                    -(1 - cls_pred[i] + self.eps).log()\n                    * (1 - self.alpha)\n                    * cls_pred[i].pow(self.gamma)\n                )\n                pos_cost = (\n                    -(cls_pred[i] + self.eps).log()\n                    * self.alpha\n                    * (1 - cls_pred[i]).pow(self.gamma)\n                )\n                cost.append(\n                    (pos_cost[:, cls_target[i]] - neg_cost[:, cls_target[i]])\n                    * self.cls_weight\n                )\n            else:\n                cost.append(None)\n        return cost\n\n    def _box_cost(self, box_pred, box_target, instance_reg_weights):\n        bs = box_pred.shape[0]\n        cost = []\n        for i in range(bs):\n            if len(box_target[i]) > 0:\n                cost.append(\n                    torch.sum(\n                        torch.abs(box_pred[i, :, None] - box_target[i][None])\n                        * instance_reg_weights[i][None]\n                        * box_pred.new_tensor(self.reg_weights),\n                        dim=-1,\n                    )\n                    * self.box_weight\n                )\n            else:\n                cost.append(None)\n        return cost\n\n    def get_dn_anchors(self, cls_target, box_target, gt_instance_id=None):\n        if self.num_dn_groups <= 0:\n            return None\n        if self.num_temp_dn_groups <= 0:\n            gt_instance_id = None\n\n        if self.max_dn_gt > 0:\n            cls_target = [x[: self.max_dn_gt] for x in cls_target]\n            box_target = [x[: self.max_dn_gt] for x in box_target]\n            if gt_instance_id is not None:\n                gt_instance_id = [x[: self.max_dn_gt] for x in gt_instance_id]\n\n        max_dn_gt = max([len(x) for x in cls_target])\n        if max_dn_gt == 0:\n            return None\n        cls_target = torch.stack(\n            [\n                F.pad(x, (0, max_dn_gt - x.shape[0]), value=-1)\n                for x in cls_target\n            ]\n        )\n        box_target = self.encode_reg_target(box_target, cls_target.device)\n        box_target = torch.stack(\n            [F.pad(x, (0, 0, 0, max_dn_gt - x.shape[0])) for x in box_target]\n        )\n        box_target = torch.where(\n            cls_target[..., None] == -1, box_target.new_tensor(0), box_target\n        )\n        if gt_instance_id is not None:\n            gt_instance_id = torch.stack(\n                [\n                    F.pad(x, (0, max_dn_gt - x.shape[0]), value=-1)\n                    for x in gt_instance_id\n                ]\n            )\n\n        bs, num_gt, state_dims = box_target.shape\n        if self.num_dn_groups > 1:\n            cls_target = cls_target.tile(self.num_dn_groups, 1)\n            box_target = box_target.tile(self.num_dn_groups, 1, 1)\n            if gt_instance_id is not None:\n                gt_instance_id = gt_instance_id.tile(self.num_dn_groups, 1)\n\n        noise = torch.rand_like(box_target) * 2 - 1\n        noise *= box_target.new_tensor(self.dn_noise_scale)\n        dn_anchor = box_target + noise\n        if self.add_neg_dn:\n            noise_neg = torch.rand_like(box_target) + 1\n            flag = torch.where(\n                torch.rand_like(box_target) > 0.5,\n                noise_neg.new_tensor(1),\n                noise_neg.new_tensor(-1),\n            )\n            noise_neg *= flag\n            noise_neg *= box_target.new_tensor(self.dn_noise_scale)\n            dn_anchor = torch.cat([dn_anchor, box_target + noise_neg], dim=1)\n            num_gt *= 2\n\n        box_cost = self._box_cost(\n            dn_anchor, box_target, torch.ones_like(box_target)\n        )\n        dn_box_target = torch.zeros_like(dn_anchor)\n        dn_cls_target = -torch.ones_like(cls_target) * 3\n        if gt_instance_id is not None:\n            dn_id_target = -torch.ones_like(gt_instance_id)\n        if self.add_neg_dn:\n            dn_cls_target = torch.cat([dn_cls_target, dn_cls_target], dim=1)\n            if gt_instance_id is not None:\n                dn_id_target = torch.cat([dn_id_target, dn_id_target], dim=1)\n\n        for i in range(dn_anchor.shape[0]):\n            cost = box_cost[i].cpu().numpy()\n            anchor_idx, gt_idx = linear_sum_assignment(cost)\n            anchor_idx = dn_anchor.new_tensor(anchor_idx, dtype=torch.int64)\n            gt_idx = dn_anchor.new_tensor(gt_idx, dtype=torch.int64)\n            dn_box_target[i, anchor_idx] = box_target[i, gt_idx]\n            dn_cls_target[i, anchor_idx] = cls_target[i, gt_idx]\n            if gt_instance_id is not None:\n                dn_id_target[i, anchor_idx] = gt_instance_id[i, gt_idx]\n        dn_anchor = (\n            dn_anchor.reshape(self.num_dn_groups, bs, num_gt, state_dims)\n            .permute(1, 0, 2, 3)\n            .flatten(1, 2)\n        )\n        dn_box_target = (\n            dn_box_target.reshape(self.num_dn_groups, bs, num_gt, state_dims)\n            .permute(1, 0, 2, 3)\n            .flatten(1, 2)\n        )\n        dn_cls_target = (\n            dn_cls_target.reshape(self.num_dn_groups, bs, num_gt)\n            .permute(1, 0, 2)\n            .flatten(1)\n        )\n        if gt_instance_id is not None:\n            dn_id_target = (\n                dn_id_target.reshape(self.num_dn_groups, bs, num_gt)\n                .permute(1, 0, 2)\n                .flatten(1)\n            )\n        else:\n            dn_id_target = None\n        valid_mask = dn_cls_target >= 0\n        if self.add_neg_dn:\n            cls_target = (\n                torch.cat([cls_target, cls_target], dim=1)\n                .reshape(self.num_dn_groups, bs, num_gt)\n                .permute(1, 0, 2)\n                .flatten(1)\n            )\n            valid_mask = torch.logical_or(\n                valid_mask, ((cls_target >= 0) & (dn_cls_target == -3))\n            )  # valid denotes the items is not from pad.\n        attn_mask = dn_box_target.new_ones(\n            num_gt * self.num_dn_groups, num_gt * self.num_dn_groups\n        )\n        for i in range(self.num_dn_groups):\n            start = num_gt * i\n            end = start + num_gt\n            attn_mask[start:end, start:end] = 0\n        attn_mask = attn_mask == 1\n        dn_cls_target = dn_cls_target.long()\n        return (\n            dn_anchor,\n            dn_box_target,\n            dn_cls_target,\n            attn_mask,\n            valid_mask,\n            dn_id_target,\n        )\n\n    def update_dn(\n        self,\n        instance_feature,\n        anchor,\n        dn_reg_target,\n        dn_cls_target,\n        valid_mask,\n        dn_id_target,\n        num_noraml_anchor,\n        temporal_valid_mask,\n    ):\n        bs, num_anchor = instance_feature.shape[:2]\n        if temporal_valid_mask is None:\n            self.dn_metas = None\n        if self.dn_metas is None or num_noraml_anchor >= num_anchor:\n            return (\n                instance_feature,\n                anchor,\n                dn_reg_target,\n                dn_cls_target,\n                valid_mask,\n                dn_id_target,\n            )\n\n        # split instance_feature and anchor into non-dn and dn\n        num_dn = num_anchor - num_noraml_anchor\n        dn_instance_feature = instance_feature[:, -num_dn:]\n        dn_anchor = anchor[:, -num_dn:]\n        instance_feature = instance_feature[:, :num_noraml_anchor]\n        anchor = anchor[:, :num_noraml_anchor]\n\n        # reshape all dn metas from (bs,num_all_dn,xxx)\n        # to (bs, dn_group, num_dn_per_group, xxx)\n        num_dn_groups = self.num_dn_groups\n        num_dn = num_dn // num_dn_groups\n        dn_feat = dn_instance_feature.reshape(bs, num_dn_groups, num_dn, -1)\n        dn_anchor = dn_anchor.reshape(bs, num_dn_groups, num_dn, -1)\n        dn_reg_target = dn_reg_target.reshape(bs, num_dn_groups, num_dn, -1)\n        dn_cls_target = dn_cls_target.reshape(bs, num_dn_groups, num_dn)\n        valid_mask = valid_mask.reshape(bs, num_dn_groups, num_dn)\n        if dn_id_target is not None:\n            dn_id = dn_id_target.reshape(bs, num_dn_groups, num_dn)\n\n        # update temp_dn_metas by instance_id\n        temp_dn_feat = self.dn_metas[\"dn_instance_feature\"]\n        _, num_temp_dn_groups, num_temp_dn = temp_dn_feat.shape[:3]\n        temp_dn_id = self.dn_metas[\"dn_id_target\"]\n\n        # bs, num_temp_dn_groups, num_temp_dn, num_dn\n        match = temp_dn_id[..., None] == dn_id[:, :num_temp_dn_groups, None]\n        temp_reg_target = (\n            match[..., None] * dn_reg_target[:, :num_temp_dn_groups, None]\n        ).sum(dim=3)\n        temp_cls_target = torch.where(\n            torch.all(torch.logical_not(match), dim=-1),\n            self.dn_metas[\"dn_cls_target\"].new_tensor(-1),\n            self.dn_metas[\"dn_cls_target\"],\n        )\n        temp_valid_mask = self.dn_metas[\"valid_mask\"]\n        temp_dn_anchor = self.dn_metas[\"dn_anchor\"]\n\n        # handle the misalignment the length of temp_dn to dn caused by the\n        # change of num_gt, then concat the temp_dn and dn\n        temp_dn_metas = [\n            temp_dn_feat,\n            temp_dn_anchor,\n            temp_reg_target,\n            temp_cls_target,\n            temp_valid_mask,\n            temp_dn_id,\n        ]\n        dn_metas = [\n            dn_feat,\n            dn_anchor,\n            dn_reg_target,\n            dn_cls_target,\n            valid_mask,\n            dn_id,\n        ]\n        output = []\n        for i, (temp_meta, meta) in enumerate(zip(temp_dn_metas, dn_metas)):\n            if num_temp_dn < num_dn:\n                pad = (0, num_dn - num_temp_dn)\n                if temp_meta.dim() == 4:\n                    pad = (0, 0) + pad\n                else:\n                    assert temp_meta.dim() == 3\n                temp_meta = F.pad(temp_meta, pad, value=0)\n            else:\n                temp_meta = temp_meta[:, :, :num_dn]\n            mask = temporal_valid_mask[:, None, None]\n            if meta.dim() == 4:\n                mask = mask.unsqueeze(dim=-1)\n            temp_meta = torch.where(\n                mask, temp_meta, meta[:, :num_temp_dn_groups]\n            )\n            meta = torch.cat([temp_meta, meta[:, num_temp_dn_groups:]], dim=1)\n            meta = meta.flatten(1, 2)\n            output.append(meta)\n        output[0] = torch.cat([instance_feature, output[0]], dim=1)\n        output[1] = torch.cat([anchor, output[1]], dim=1)\n        return output\n\n    def cache_dn(\n        self,\n        dn_instance_feature,\n        dn_anchor,\n        dn_cls_target,\n        valid_mask,\n        dn_id_target,\n    ):\n        if self.num_temp_dn_groups < 0:\n            return\n        num_dn_groups = self.num_dn_groups\n        bs, num_dn = dn_instance_feature.shape[:2]\n        num_temp_dn = num_dn // num_dn_groups\n        temp_group_mask = (\n            torch.randperm(num_dn_groups) < self.num_temp_dn_groups\n        )\n        temp_group_mask = temp_group_mask.to(device=dn_anchor.device)\n        dn_instance_feature = dn_instance_feature.detach().reshape(\n            bs, num_dn_groups, num_temp_dn, -1\n        )[:, temp_group_mask]\n        dn_anchor = dn_anchor.detach().reshape(\n            bs, num_dn_groups, num_temp_dn, -1\n        )[:, temp_group_mask]\n        dn_cls_target = dn_cls_target.reshape(bs, num_dn_groups, num_temp_dn)[\n            :, temp_group_mask\n        ]\n        valid_mask = valid_mask.reshape(bs, num_dn_groups, num_temp_dn)[\n            :, temp_group_mask\n        ]\n        if dn_id_target is not None:\n            dn_id_target = dn_id_target.reshape(\n                bs, num_dn_groups, num_temp_dn\n            )[:, temp_group_mask]\n        self.dn_metas = dict(\n            dn_instance_feature=dn_instance_feature,\n            dn_anchor=dn_anchor,\n            dn_cls_target=dn_cls_target,\n            valid_mask=valid_mask,\n            dn_id_target=dn_id_target,\n        )\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/grid_mask.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\nfrom PIL import Image\n\n\nclass Grid(object):\n    def __init__(\n        self, use_h, use_w, rotate=1, offset=False, ratio=0.5, mode=0, prob=1.0\n    ):\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode = mode\n        self.st_prob = prob\n        self.prob = prob\n\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch\n\n    def __call__(self, img, label):\n        if np.random.rand() > self.prob:\n            return img, label\n        h = img.size(1)\n        w = img.size(2)\n        self.d1 = 2\n        self.d2 = min(h, w)\n        hh = int(1.5 * h)\n        ww = int(1.5 * w)\n        d = np.random.randint(self.d1, self.d2)\n        if self.ratio == 1:\n            self.l = np.random.randint(1, d)\n        else:\n            self.l = min(max(int(d * self.ratio + 0.5), 1), d - 1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh // d):\n                s = d * i + st_h\n                t = min(s + self.l, hh)\n                mask[s:t, :] *= 0\n        if self.use_w:\n            for i in range(ww // d):\n                s = d * i + st_w\n                t = min(s + self.l, ww)\n                mask[:, s:t] *= 0\n\n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[\n            (hh - h) // 2 : (hh - h) // 2 + h,\n            (ww - w) // 2 : (ww - w) // 2 + w,\n        ]\n\n        mask = torch.from_numpy(mask).float()\n        if self.mode == 1:\n            mask = 1 - mask\n\n        mask = mask.expand_as(img)\n        if self.offset:\n            offset = torch.from_numpy(2 * (np.random.rand(h, w) - 0.5)).float()\n            offset = (1 - mask) * offset\n            img = img * mask + offset\n        else:\n            img = img * mask\n\n        return img, label\n\n\nclass GridMask(nn.Module):\n    def __init__(\n        self, use_h, use_w, rotate=1, offset=False, ratio=0.5, mode=0, prob=1.0\n    ):\n        super(GridMask, self).__init__()\n        self.use_h = use_h\n        self.use_w = use_w\n        self.rotate = rotate\n        self.offset = offset\n        self.ratio = ratio\n        self.mode = mode\n        self.st_prob = prob\n        self.prob = prob\n\n    def set_prob(self, epoch, max_epoch):\n        self.prob = self.st_prob * epoch / max_epoch  # + 1.#0.5\n\n    def forward(self, x):\n        if np.random.rand() > self.prob or not self.training:\n            return x\n        n, c, h, w = x.size()\n        x = x.view(-1, h, w)\n        hh = int(1.5 * h)\n        ww = int(1.5 * w)\n        d = np.random.randint(2, h)\n        self.l = min(max(int(d * self.ratio + 0.5), 1), d - 1)\n        mask = np.ones((hh, ww), np.float32)\n        st_h = np.random.randint(d)\n        st_w = np.random.randint(d)\n        if self.use_h:\n            for i in range(hh // d):\n                s = d * i + st_h\n                t = min(s + self.l, hh)\n                mask[s:t, :] *= 0\n        if self.use_w:\n            for i in range(ww // d):\n                s = d * i + st_w\n                t = min(s + self.l, ww)\n                mask[:, s:t] *= 0\n\n        r = np.random.randint(self.rotate)\n        mask = Image.fromarray(np.uint8(mask))\n        mask = mask.rotate(r)\n        mask = np.asarray(mask)\n        mask = mask[\n            (hh - h) // 2 : (hh - h) // 2 + h,\n            (ww - w) // 2 : (ww - w) // 2 + w,\n        ]\n\n        mask = torch.from_numpy(mask.copy()).float().cuda()\n        if self.mode == 1:\n            mask = 1 - mask\n        mask = mask.expand_as(x)\n        if self.offset:\n            offset = (\n                torch.from_numpy(2 * (np.random.rand(h, w) - 0.5))\n                .float()\n                .cuda()\n            )\n            x = x * mask + offset * (1 - mask)\n        else:\n            x = x * mask\n\n        return x.view(n, c, h, w)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/instance_bank.py",
    "content": "import torch\nfrom torch import nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\n\n__all__ = [\"InstanceBank\"]\n\n\ndef topk(confidence, k, *inputs):\n    bs, N = confidence.shape[:2]\n    confidence, indices = torch.topk(confidence, k, dim=1)\n    indices = (\n        indices + torch.arange(bs, device=indices.device)[:, None] * N\n    ).reshape(-1)\n    outputs = []\n    for input in inputs:\n        outputs.append(input.flatten(end_dim=1)[indices].reshape(bs, k, -1))\n    return confidence, outputs\n\n\n@PLUGIN_LAYERS.register_module()\nclass InstanceBank(nn.Module):\n    def __init__(\n        self,\n        num_anchor,\n        embed_dims,\n        anchor,\n        anchor_handler=None,\n        num_temp_instances=0,\n        default_time_interval=0.5,\n        confidence_decay=0.6,\n        anchor_grad=True,\n        feat_grad=True,\n        max_time_interval=2,\n    ):\n        super(InstanceBank, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_temp_instances = num_temp_instances\n        self.default_time_interval = default_time_interval\n        self.confidence_decay = confidence_decay\n        self.max_time_interval = max_time_interval\n\n        if anchor_handler is not None:\n            anchor_handler = build_from_cfg(anchor_handler, PLUGIN_LAYERS)\n            assert hasattr(anchor_handler, \"anchor_projection\")\n        self.anchor_handler = anchor_handler\n        if isinstance(anchor, str):\n            anchor = np.load(anchor)\n        elif isinstance(anchor, (list, tuple)):\n            anchor = np.array(anchor)\n        if len(anchor.shape) == 3: # for map\n            anchor = anchor.reshape(anchor.shape[0], -1)\n        self.num_anchor = min(len(anchor), num_anchor)\n        anchor = anchor[:num_anchor]\n        self.anchor = nn.Parameter(\n            torch.tensor(anchor, dtype=torch.float32),\n            requires_grad=anchor_grad,\n        )\n        self.anchor_init = anchor\n        self.instance_feature = nn.Parameter(\n            torch.zeros([self.anchor.shape[0], self.embed_dims]),\n            requires_grad=feat_grad,\n        )\n        self.reset()\n\n    def init_weight(self):\n        self.anchor.data = self.anchor.data.new_tensor(self.anchor_init)\n        if self.instance_feature.requires_grad:\n            torch.nn.init.xavier_uniform_(self.instance_feature.data, gain=1)\n\n    def reset(self):\n        self.cached_feature = None\n        self.cached_anchor = None\n        self.metas = None\n        self.mask = None\n        self.confidence = None\n        self.temp_confidence = None\n        self.instance_id = None\n        self.prev_id = 0\n\n    def get(self, batch_size, metas=None, dn_metas=None):\n        instance_feature = torch.tile(\n            self.instance_feature[None], (batch_size, 1, 1)\n        )\n        anchor = torch.tile(self.anchor[None], (batch_size, 1, 1))\n\n        if (\n            self.cached_anchor is not None\n            and batch_size == self.cached_anchor.shape[0]\n        ):\n            history_time = self.metas[\"timestamp\"]\n            time_interval = metas[\"timestamp\"] - history_time\n            time_interval = time_interval.to(dtype=instance_feature.dtype)\n            self.mask = torch.abs(time_interval) <= self.max_time_interval\n\n            if self.anchor_handler is not None:\n                T_temp2cur = self.cached_anchor.new_tensor(\n                    np.stack(\n                        [\n                            x[\"T_global_inv\"]\n                            @ self.metas[\"img_metas\"][i][\"T_global\"]\n                            for i, x in enumerate(metas[\"img_metas\"])\n                        ]\n                    )\n                )\n                self.cached_anchor = self.anchor_handler.anchor_projection(\n                    self.cached_anchor,\n                    [T_temp2cur],\n                    time_intervals=[-time_interval],\n                )[0]\n\n            if (\n                self.anchor_handler is not None\n                and dn_metas is not None\n                and batch_size == dn_metas[\"dn_anchor\"].shape[0]\n            ):\n                num_dn_group, num_dn = dn_metas[\"dn_anchor\"].shape[1:3]\n                dn_anchor = self.anchor_handler.anchor_projection(\n                    dn_metas[\"dn_anchor\"].flatten(1, 2),\n                    [T_temp2cur],\n                    time_intervals=[-time_interval],\n                )[0]\n                dn_metas[\"dn_anchor\"] = dn_anchor.reshape(\n                    batch_size, num_dn_group, num_dn, -1\n                )\n            time_interval = torch.where(\n                torch.logical_and(time_interval != 0, self.mask),\n                time_interval,\n                time_interval.new_tensor(self.default_time_interval),\n            )\n        else:\n            self.reset()\n            time_interval = instance_feature.new_tensor(\n                [self.default_time_interval] * batch_size\n            )\n\n        return (\n            instance_feature,\n            anchor,\n            self.cached_feature,\n            self.cached_anchor,\n            time_interval,\n        )\n\n    def update(self, instance_feature, anchor, confidence):\n        if self.cached_feature is None:\n            return instance_feature, anchor\n\n        num_dn = 0\n        if instance_feature.shape[1] > self.num_anchor:\n            num_dn = instance_feature.shape[1] - self.num_anchor\n            dn_instance_feature = instance_feature[:, -num_dn:]\n            dn_anchor = anchor[:, -num_dn:]\n            instance_feature = instance_feature[:, : self.num_anchor]\n            anchor = anchor[:, : self.num_anchor]\n            confidence = confidence[:, : self.num_anchor]\n\n        N = self.num_anchor - self.num_temp_instances\n        confidence = confidence.max(dim=-1).values\n        _, (selected_feature, selected_anchor) = topk(\n            confidence, N, instance_feature, anchor\n        )\n        selected_feature = torch.cat(\n            [self.cached_feature, selected_feature], dim=1\n        )\n        selected_anchor = torch.cat(\n            [self.cached_anchor, selected_anchor], dim=1\n        )\n        instance_feature = torch.where(\n            self.mask[:, None, None], selected_feature, instance_feature\n        )\n        anchor = torch.where(self.mask[:, None, None], selected_anchor, anchor)\n        self.confidence = torch.where(\n            self.mask[:, None],\n            self.confidence,\n            self.confidence.new_tensor(0)\n        )\n        if self.instance_id is not None:\n            self.instance_id = torch.where(\n                self.mask[:, None],\n                self.instance_id,\n                self.instance_id.new_tensor(-1),\n            )\n\n        if num_dn > 0:\n            instance_feature = torch.cat(\n                [instance_feature, dn_instance_feature], dim=1\n            )\n            anchor = torch.cat([anchor, dn_anchor], dim=1)\n        return instance_feature, anchor\n\n    def cache(\n        self,\n        instance_feature,\n        anchor,\n        confidence,\n        metas=None,\n        feature_maps=None,\n    ):\n        if self.num_temp_instances <= 0:\n            return\n        instance_feature = instance_feature.detach()\n        anchor = anchor.detach()\n        confidence = confidence.detach()\n\n        self.metas = metas\n        confidence = confidence.max(dim=-1).values.sigmoid()\n        if self.confidence is not None:\n            confidence[:, : self.num_temp_instances] = torch.maximum(\n                self.confidence * self.confidence_decay,\n                confidence[:, : self.num_temp_instances],\n            )\n        self.temp_confidence = confidence\n\n        (\n            self.confidence,\n            (self.cached_feature, self.cached_anchor),\n        ) = topk(confidence, self.num_temp_instances, instance_feature, anchor)\n\n    def get_instance_id(self, confidence, anchor=None, threshold=None):\n        confidence = confidence.max(dim=-1).values.sigmoid()\n        instance_id = confidence.new_full(confidence.shape, -1).long()\n\n        if (\n            self.instance_id is not None\n            and self.instance_id.shape[0] == instance_id.shape[0]\n        ):\n            instance_id[:, : self.instance_id.shape[1]] = self.instance_id\n\n        mask = instance_id < 0\n        if threshold is not None:\n            mask = mask & (confidence >= threshold)\n        num_new_instance = mask.sum()\n        new_ids = torch.arange(num_new_instance).to(instance_id) + self.prev_id\n        instance_id[torch.where(mask)] = new_ids\n        self.prev_id += num_new_instance\n        self.update_instance_id(instance_id, confidence)\n        return instance_id\n\n    def update_instance_id(self, instance_id=None, confidence=None):\n        if self.temp_confidence is None:\n            if confidence.dim() == 3:  # bs, num_anchor, num_cls\n                temp_conf = confidence.max(dim=-1).values\n            else:  # bs, num_anchor\n                temp_conf = confidence\n        else:\n            temp_conf = self.temp_confidence\n        instance_id = topk(temp_conf, self.num_temp_instances, instance_id)[1][\n            0\n        ]\n        instance_id = instance_id.squeeze(dim=-1)\n        self.instance_id = F.pad(\n            instance_id,\n            (0, self.num_anchor - self.num_temp_instances),\n            value=-1,\n        )"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/map/__init__.py",
    "content": "from .decoder import SparsePoint3DDecoder\nfrom .target import SparsePoint3DTarget, HungarianLinesAssigner\nfrom .match_cost import LinesL1Cost, MapQueriesCost\nfrom .loss import LinesL1Loss, SparseLineLoss\nfrom .map_blocks import (\n    SparsePoint3DRefinementModule,\n    SparsePoint3DKeyPointsGenerator,\n    SparsePoint3DEncoder,\n)"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/map/decoder.py",
    "content": "from typing import Optional, List\n\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\n\n@BBOX_CODERS.register_module()\nclass SparsePoint3DDecoder(object):\n    def __init__(\n        self,\n        coords_dim: int = 2,\n        score_threshold: Optional[float] = None,\n    ):\n        super(SparsePoint3DDecoder, self).__init__()\n        self.score_threshold = score_threshold\n        self.coords_dim = coords_dim\n\n    def decode(\n        self,\n        cls_scores,\n        pts_preds,\n        instance_id=None,\n        quality=None,\n        output_idx=-1,\n    ):\n        \n        bs, num_pred, num_cls = cls_scores[-1].shape\n        cls_scores = cls_scores[-1].sigmoid()\n        pts_preds = pts_preds[-1].reshape(bs, num_pred, -1, self.coords_dim)\n        cls_scores, indices = cls_scores.flatten(start_dim=1).topk(\n            num_pred, dim=1\n        )\n        cls_ids = indices % num_cls\n        if self.score_threshold is not None:\n            mask = cls_scores >= self.score_threshold\n        output = []\n        for i in range(bs):\n            category_ids = cls_ids[i]\n            scores = cls_scores[i]\n            pts = pts_preds[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                category_ids = category_ids[mask[i]]\n                scores = scores[mask[i]]\n                pts = pts[mask[i]]\n\n            output.append(\n                {\n                    \"vectors\": [vec.detach().cpu().numpy() for vec in pts],\n                    \"scores\": scores.detach().cpu().numpy(),\n                    \"labels\": category_ids.detach().cpu().numpy(),\n                }\n            )\n        return output"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/map/loss.py",
    "content": "import torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmdet.models.builder import LOSSES\nfrom mmdet.models.losses import l1_loss, smooth_l1_loss\n\n\n@LOSSES.register_module()\nclass LinesL1Loss(nn.Module):\n\n    def __init__(self, reduction='mean', loss_weight=1.0, beta=0.5):\n        \"\"\"\n            L1 loss. The same as the smooth L1 loss\n            Args:\n                reduction (str, optional): The method to reduce the loss.\n                    Options are \"none\", \"mean\" and \"sum\".\n                loss_weight (float, optional): The weight of loss.\n        \"\"\"\n\n        super().__init__()\n        self.reduction = reduction\n        self.loss_weight = loss_weight\n        self.beta = beta\n\n    def forward(self,\n                pred,\n                target,\n                weight=None,\n                avg_factor=None,\n                reduction_override=None):\n        \"\"\"Forward function.\n        Args:\n            pred (torch.Tensor): The prediction.\n                shape: [bs, ...]\n            target (torch.Tensor): The learning target of the prediction.\n                shape: [bs, ...]\n            weight (torch.Tensor, optional): The weight of loss for each\n                prediction. Defaults to None. \n                it's useful when the predictions are not all valid.\n            avg_factor (int, optional): Average factor that is used to average\n                the loss. Defaults to None.\n            reduction_override (str, optional): The reduction method used to\n                override the original reduction method of the loss.\n                Defaults to None.\n        \"\"\"\n        assert reduction_override in (None, 'none', 'mean', 'sum')\n        reduction = (\n            reduction_override if reduction_override else self.reduction)\n\n        if self.beta > 0:\n            loss = smooth_l1_loss(\n                pred, target, weight, reduction=reduction, avg_factor=avg_factor, beta=self.beta)\n        \n        else:\n            loss = l1_loss(\n                pred, target, weight, reduction=reduction, avg_factor=avg_factor)\n        \n        num_points = pred.shape[-1] // 2\n        loss = loss / num_points\n\n        return loss*self.loss_weight\n\n\n@LOSSES.register_module()\nclass SparseLineLoss(nn.Module):\n    def __init__(\n        self,\n        loss_line,\n        num_sample=20,\n        roi_size=(30, 60),\n    ):\n        super().__init__()\n\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n\n        self.loss_line = build(loss_line, LOSSES)\n        self.num_sample = num_sample\n        self.roi_size = roi_size\n\n    def forward(\n        self,\n        line,\n        line_target,\n        weight=None,\n        avg_factor=None,\n        prefix=\"\",\n        suffix=\"\",\n        **kwargs,\n    ):\n\n        output = {}\n        line = self.normalize_line(line)\n        line_target = self.normalize_line(line_target)\n        line_loss = self.loss_line(\n            line, line_target, weight=weight, avg_factor=avg_factor\n        )\n        output[f\"{prefix}loss_line{suffix}\"] = line_loss\n\n        return output\n\n    def normalize_line(self, line):\n        if line.shape[0] == 0:\n            return line\n\n        line = line.view(line.shape[:-1] + (self.num_sample, -1))\n        \n        origin = -line.new_tensor([self.roi_size[0]/2, self.roi_size[1]/2])\n        line = line - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        norm = line.new_tensor([self.roi_size[0], self.roi_size[1]]) + eps\n        line = line / norm\n        line = line.flatten(-2, -1)\n\n        return line\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/map/map_blocks.py",
    "content": "from typing import Optional, List, Tuple\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom mmcv.cnn import Linear, Scale, bias_init_with_prob\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.registry import (\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n)\n\nfrom ..blocks import linear_relu_ln\n\n\n@POSITIONAL_ENCODING.register_module()\nclass SparsePoint3DEncoder(BaseModule):\n    def __init__(\n        self, \n        embed_dims: int = 256,\n        num_sample: int = 20,\n        coords_dim: int = 2,\n    ):\n        super(SparsePoint3DEncoder, self).__init__()\n        self.embed_dims = embed_dims\n        self.input_dims = num_sample * coords_dim\n        def embedding_layer(input_dims):\n            return nn.Sequential(*linear_relu_ln(embed_dims, 1, 2, input_dims))\n\n        self.pos_fc = embedding_layer(self.input_dims)\n\n    def forward(self, anchor: torch.Tensor):\n        pos_feat = self.pos_fc(anchor)  \n        return pos_feat\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparsePoint3DRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims: int = 256,\n        num_sample: int = 20,\n        coords_dim: int = 2,\n        num_cls: int = 3,\n        with_cls_branch: bool = True,\n    ):\n        super(SparsePoint3DRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_sample = num_sample\n        self.output_dim = num_sample * coords_dim\n        self.num_cls = num_cls\n\n        self.layers = nn.Sequential(\n            *linear_relu_ln(embed_dims, 2, 2),\n            Linear(self.embed_dims, self.output_dim),\n            Scale([1.0] * self.output_dim),\n        )\n\n        self.with_cls_branch = with_cls_branch\n        if with_cls_branch:\n            self.cls_layers = nn.Sequential(\n                *linear_relu_ln(embed_dims, 1, 2),\n                Linear(self.embed_dims, self.num_cls),\n            )\n\n    def init_weight(self):\n        if self.with_cls_branch:\n            bias_init = bias_init_with_prob(0.01)\n            nn.init.constant_(self.cls_layers[-1].bias, bias_init)\n\n    def forward(\n        self,\n        instance_feature: torch.Tensor,\n        anchor: torch.Tensor,\n        anchor_embed: torch.Tensor,\n        time_interval: torch.Tensor = 1.0,\n        return_cls=True,\n    ):\n        output = self.layers(instance_feature + anchor_embed)\n        output = output + anchor\n        if return_cls:\n            assert self.with_cls_branch, \"Without classification layers !!!\"\n            cls = self.cls_layers(instance_feature)  ## NOTE anchor embed?\n        else:\n            cls = None\n        qt = None\n        return output, cls, qt\n\n\n@PLUGIN_LAYERS.register_module()\nclass SparsePoint3DKeyPointsGenerator(BaseModule): \n    def __init__(\n        self,\n        embed_dims: int = 256,\n        num_sample: int = 20,\n        num_learnable_pts: int = 0,\n        fix_height: Tuple = (0,),\n        ground_height: int = 0,\n    ):\n        super(SparsePoint3DKeyPointsGenerator, self).__init__()\n        self.embed_dims = embed_dims\n        self.num_sample = num_sample\n        self.num_learnable_pts = num_learnable_pts\n        self.num_pts = num_sample * len(fix_height) * num_learnable_pts\n        if self.num_learnable_pts > 0:\n            self.learnable_fc = Linear(self.embed_dims, self.num_pts * 2)\n\n        self.fix_height = np.array(fix_height)\n        self.ground_height = ground_height\n\n    def init_weight(self):\n        if self.num_learnable_pts > 0:\n            xavier_init(self.learnable_fc, distribution=\"uniform\", bias=0.0)\n\n    def forward(\n        self,\n        anchor,\n        instance_feature=None,\n        T_cur2temp_list=None,\n        cur_timestamp=None,\n        temp_timestamps=None,\n    ):\n        assert self.num_learnable_pts > 0, 'No learnable pts'\n        bs, num_anchor, _ = anchor.shape\n        key_points = anchor.view(bs, num_anchor, self.num_sample, -1)\n        offset = (\n            self.learnable_fc(instance_feature)\n            .reshape(bs, num_anchor, self.num_sample, len(self.fix_height), self.num_learnable_pts, 2)\n        )        \n        key_points = offset + key_points[..., None, None, :]\n        key_points = torch.cat(\n            [\n                key_points,\n                key_points.new_full(key_points.shape[:-1]+(1,), fill_value=self.ground_height),\n            ],\n            dim=-1,\n        )\n        fix_height = key_points.new_tensor(self.fix_height)\n        height_offset = key_points.new_zeros([len(fix_height), 2])\n        height_offset = torch.cat([height_offset, fix_height[:,None]], dim=-1)\n        key_points = key_points + height_offset[None, None, None, :, None]\n        key_points = key_points.flatten(2, 4)\n        if (\n            cur_timestamp is None\n            or temp_timestamps is None\n            or T_cur2temp_list is None\n            or len(temp_timestamps) == 0\n        ):\n            return key_points\n\n        temp_key_points_list = []\n        for i, t_time in enumerate(temp_timestamps):\n            temp_key_points = key_points\n            T_cur2temp = T_cur2temp_list[i].to(dtype=key_points.dtype)\n            temp_key_points = (\n                T_cur2temp[:, None, None, :3]\n                @ torch.cat(\n                    [\n                        temp_key_points,\n                        torch.ones_like(temp_key_points[..., :1]),\n                    ],\n                    dim=-1,\n                ).unsqueeze(-1)\n            )\n            temp_key_points = temp_key_points.squeeze(-1)\n            temp_key_points_list.append(temp_key_points)\n        return key_points, temp_key_points_list\n\n    # @staticmethod\n    def anchor_projection(\n        self,\n        anchor,\n        T_src2dst_list,\n        src_timestamp=None,\n        dst_timestamps=None,\n        time_intervals=None,\n    ):\n        dst_anchors = []\n        for i in range(len(T_src2dst_list)):\n            dst_anchor = anchor.clone()\n            bs, num_anchor, _ = anchor.shape\n            dst_anchor = dst_anchor.reshape(bs, num_anchor, self.num_sample, -1).flatten(1, 2)\n            T_src2dst = torch.unsqueeze(\n                T_src2dst_list[i].to(dtype=anchor.dtype), dim=1\n            )\n\n            dst_anchor = (\n                torch.matmul(\n                    T_src2dst[..., :2, :2], dst_anchor[..., None]\n                ).squeeze(dim=-1)\n                + T_src2dst[..., :2, 3]\n            )\n\n            dst_anchor = dst_anchor.reshape(bs, num_anchor, self.num_sample, -1).flatten(2, 3)\n            dst_anchors.append(dst_anchor)\n        return dst_anchors"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/map/match_cost.py",
    "content": "import torch\nfrom mmdet.core.bbox.match_costs.builder import MATCH_COST\nfrom mmdet.core.bbox.match_costs import build_match_cost\nfrom torch.nn.functional import smooth_l1_loss\n\n\n@MATCH_COST.register_module()\nclass LinesL1Cost(object):\n    \"\"\"LinesL1Cost.\n     Args:\n         weight (int | float, optional): loss_weight\n    \"\"\"\n\n    def __init__(self, weight=1.0, beta=0.0, permute=False):\n        self.weight = weight\n        self.permute = permute\n        self.beta = beta\n\n    def __call__(self, lines_pred, gt_lines, **kwargs):\n        \"\"\"\n        Args:\n            lines_pred (Tensor): predicted normalized lines:\n                [num_query, 2*num_points]\n            gt_lines (Tensor): Ground truth lines\n                [num_gt, 2*num_points] or [num_gt, num_permute, 2*num_points]\n        Returns:\n            torch.Tensor: reg_cost value with weight\n                shape [num_pred, num_gt]\n        \"\"\"        \n        if self.permute:\n            assert len(gt_lines.shape) == 3\n        else:\n            assert len(gt_lines.shape) == 2\n\n        num_pred, num_gt = len(lines_pred), len(gt_lines)\n        if self.permute:\n            # permute-invarint labels\n            gt_lines = gt_lines.flatten(0, 1) # (num_gt*num_permute, 2*num_pts)\n\n        num_pts = lines_pred.shape[-1]//2\n\n        if self.beta > 0:\n            lines_pred = lines_pred.unsqueeze(1).repeat(1, len(gt_lines), 1)\n            gt_lines = gt_lines.unsqueeze(0).repeat(num_pred, 1, 1)\n            dist_mat = smooth_l1_loss(lines_pred, gt_lines, reduction='none', beta=self.beta).sum(-1)\n        \n        else:\n            dist_mat = torch.cdist(lines_pred, gt_lines, p=1)\n\n        dist_mat = dist_mat / num_pts\n\n        if self.permute:\n            # dist_mat: (num_pred, num_gt*num_permute)\n            dist_mat = dist_mat.view(num_pred, num_gt, -1) # (num_pred, num_gt, num_permute)\n            dist_mat, gt_permute_index = torch.min(dist_mat, 2)\n            return dist_mat * self.weight, gt_permute_index\n        \n        return dist_mat * self.weight\n\n\n@MATCH_COST.register_module()\nclass MapQueriesCost(object):\n\n    def __init__(self, cls_cost, reg_cost, iou_cost=None):\n\n        self.cls_cost = build_match_cost(cls_cost)\n        self.reg_cost = build_match_cost(reg_cost)\n\n        self.iou_cost = None\n        if iou_cost is not None:\n            self.iou_cost = build_match_cost(iou_cost)\n\n    def __call__(self, preds: dict, gts: dict, ignore_cls_cost: bool):\n\n        # classification and bboxcost.\n        cls_cost = self.cls_cost(preds['scores'], gts['labels'])\n\n        # regression cost\n        regkwargs = {}\n        if 'masks' in preds and 'masks' in gts:\n            assert isinstance(self.reg_cost, DynamicLinesCost), ' Issues!!'\n            regkwargs = {\n                'masks_pred': preds['masks'],\n                'masks_gt': gts['masks'],\n            }\n\n        reg_cost = self.reg_cost(preds['lines'], gts['lines'], **regkwargs)\n        if self.reg_cost.permute:\n            reg_cost, gt_permute_idx = reg_cost\n\n        # weighted sum of above three costs\n        if ignore_cls_cost:\n            cost = reg_cost\n        else:\n            cost = cls_cost + reg_cost\n\n        # Iou\n        if self.iou_cost is not None:\n            iou_cost = self.iou_cost(preds['lines'],gts['lines'])\n            cost += iou_cost\n        \n        if self.reg_cost.permute:\n            return cost, gt_permute_idx\n        return cost\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/map/target.py",
    "content": "import torch\nimport numpy as np\nimport torch.nn.functional as F\nfrom scipy.optimize import linear_sum_assignment\n\nfrom mmdet.core.bbox.builder import (BBOX_SAMPLERS, BBOX_ASSIGNERS)\nfrom mmdet.core.bbox.match_costs import build_match_cost\nfrom mmdet.core import (build_assigner, build_sampler)\nfrom mmdet.core.bbox.assigners import (AssignResult, BaseAssigner)\n\nfrom ..base_target import BaseTargetWithDenoising\n\n\n@BBOX_SAMPLERS.register_module()\nclass SparsePoint3DTarget(BaseTargetWithDenoising):\n    def __init__(\n        self,\n        assigner=None,\n        num_dn_groups=0,\n        dn_noise_scale=0.5,\n        max_dn_gt=32,\n        add_neg_dn=True,\n        num_temp_dn_groups=0,\n        num_cls=3,\n        num_sample=20,\n        roi_size=(30, 60),\n    ):\n        super(SparsePoint3DTarget, self).__init__(\n            num_dn_groups, num_temp_dn_groups\n        )\n        self.assigner = build_assigner(assigner)\n        self.dn_noise_scale = dn_noise_scale\n        self.max_dn_gt = max_dn_gt\n        self.add_neg_dn = add_neg_dn\n\n        self.num_cls = num_cls\n        self.num_sample = num_sample\n        self.roi_size = roi_size\n\n    def sample(\n        self,\n        cls_preds,\n        pts_preds,\n        cls_targets,\n        pts_targets,\n    ):\n        pts_targets  = [x.flatten(2, 3) if len(x.shape)==4 else x for x in pts_targets]\n        indices = []\n        for(cls_pred, pts_pred, cls_target, pts_target) in zip(\n            cls_preds, pts_preds, cls_targets, pts_targets\n        ):\n            # normalize to (0, 1)\n            pts_pred = self.normalize_line(pts_pred)\n            pts_target = self.normalize_line(pts_target)\n            preds=dict(lines=pts_pred, scores=cls_pred)\n            gts=dict(lines=pts_target, labels=cls_target)\n            indice = self.assigner.assign(preds, gts)\n            indices.append(indice)\n        \n        bs, num_pred, num_cls = cls_preds.shape\n        output_cls_target = cls_targets[0].new_ones([bs, num_pred], dtype=torch.long) * num_cls\n        output_box_target = pts_preds.new_zeros(pts_preds.shape)\n        output_reg_weights = pts_preds.new_zeros(pts_preds.shape)\n        for i, (pred_idx, target_idx, gt_permute_index) in enumerate(indices):\n            if len(cls_targets[i]) == 0:\n                continue\n            permute_idx = gt_permute_index[pred_idx, target_idx]\n            output_cls_target[i, pred_idx] = cls_targets[i][target_idx]\n            output_box_target[i, pred_idx] = pts_targets[i][target_idx, permute_idx]\n            output_reg_weights[i, pred_idx] = 1\n\n        return output_cls_target, output_box_target, output_reg_weights\n\n    def normalize_line(self, line):\n        if line.shape[0] == 0:\n            return line\n        \n        line = line.view(line.shape[:-1] + (self.num_sample, -1))\n        \n        origin = -line.new_tensor([self.roi_size[0]/2, self.roi_size[1]/2])\n        line = line - origin\n\n        # transform from range [0, 1] to (0, 1)\n        eps = 1e-5\n        norm = line.new_tensor([self.roi_size[0], self.roi_size[1]]) + eps\n        line = line / norm\n        line = line.flatten(-2, -1)\n\n        return line\n\n\n@BBOX_ASSIGNERS.register_module()\nclass HungarianLinesAssigner(BaseAssigner):\n    \"\"\"\n        Computes one-to-one matching between predictions and ground truth.\n        This class computes an assignment between the targets and the predictions\n        based on the costs. The costs are weighted sum of three components:\n        classification cost and regression L1 cost. The\n        targets don't include the no_object, so generally there are more\n        predictions than targets. After the one-to-one matching, the un-matched\n        are treated as backgrounds. Thus each query prediction will be assigned\n        with `0` or a positive integer indicating the ground truth index:\n        - 0: negative sample, no assigned gt\n        - positive integer: positive sample, index (1-based) of assigned gt\n        Args:\n            cls_weight (int | float, optional): The scale factor for classification\n                cost. Default 1.0.\n            bbox_weight (int | float, optional): The scale factor for regression\n                L1 cost. Default 1.0.\n    \"\"\"\n\n    def __init__(self, cost=dict, **kwargs):\n        self.cost = build_match_cost(cost)\n\n    def assign(self,\n               preds: dict,\n               gts: dict,\n               ignore_cls_cost=False,\n               gt_bboxes_ignore=None,\n               eps=1e-7):\n        \"\"\"\n            Computes one-to-one matching based on the weighted costs.\n            This method assign each query prediction to a ground truth or\n            background. The `assigned_gt_inds` with -1 means don't care,\n            0 means negative sample, and positive number is the index (1-based)\n            of assigned gt.\n            The assignment is done in the following steps, the order matters.\n            1. assign every prediction to -1\n            2. compute the weighted costs\n            3. do Hungarian matching on CPU based on the costs\n            4. assign all to 0 (background) first, then for each matched pair\n            between predictions and gts, treat this prediction as foreground\n            and assign the corresponding gt index (plus 1) to it.\n            Args:\n                lines_pred (Tensor): predicted normalized lines:\n                    [num_query, num_points, 2]\n                cls_pred (Tensor): Predicted classification logits, shape\n                    [num_query, num_class].\n\n                lines_gt (Tensor): Ground truth lines\n                    [num_gt, num_points, 2].\n                labels_gt (Tensor): Label of `gt_bboxes`, shape (num_gt,).\n                gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are\n                    labelled as `ignored`. Default None.\n                eps (int | float, optional): A value added to the denominator for\n                    numerical stability. Default 1e-7.\n            Returns:\n                :obj:`AssignResult`: The assigned result.\n        \"\"\"\n        assert gt_bboxes_ignore is None, \\\n            'Only case when gt_bboxes_ignore is None is supported.'\n        \n        num_gts, num_lines = gts['lines'].size(0), preds['lines'].size(0)\n        if num_gts == 0 or num_lines == 0:\n            return None, None, None\n\n        # compute the weighted costs\n        gt_permute_idx = None # (num_preds, num_gts)\n        if self.cost.reg_cost.permute:\n            cost, gt_permute_idx = self.cost(preds, gts, ignore_cls_cost)\n        else:\n            cost = self.cost(preds, gts, ignore_cls_cost)\n\n        # do Hungarian matching on CPU using linear_sum_assignment\n        cost = cost.detach().cpu().numpy()\n        matched_row_inds, matched_col_inds = linear_sum_assignment(cost)\n        return matched_row_inds, matched_col_inds, gt_permute_idx"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/__init__.py",
    "content": "from .motion_planning_head_roboAD import MotionPlanningHeadroboAD\nfrom .motion_planning_head_roboAD_6s import MotionPlanningHeadroboAD_6s\nfrom .motion_planning_head import MotionPlanningHead\nfrom .motion_blocks import MotionPlanningRefinementModule\nfrom .instance_queue import InstanceQueue\nfrom .target import MotionTarget, PlanningTarget\nfrom .decoder import SparseBox3DMotionDecoder, HierarchicalPlanningDecoder\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/decoder.py",
    "content": "from typing import Optional\n\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\nfrom projects.mmdet3d_plugin.core.box3d import *\nfrom projects.mmdet3d_plugin.models.detection3d.decoder import *\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\n\n\n@BBOX_CODERS.register_module()\nclass SparseBox3DMotionDecoder(SparseBox3DDecoder):\n    def __init__(self):\n        super(SparseBox3DMotionDecoder, self).__init__()\n\n    def decode(\n        self,\n        cls_scores,\n        box_preds,\n        instance_id=None,\n        quality=None,\n        motion_output=None,\n        output_idx=-1,\n    ):\n        squeeze_cls = instance_id is not None\n\n        cls_scores = cls_scores[output_idx].sigmoid()\n\n        if squeeze_cls:\n            cls_scores, cls_ids = cls_scores.max(dim=-1)\n            cls_scores = cls_scores.unsqueeze(dim=-1)\n\n        box_preds = box_preds[output_idx]\n        bs, num_pred, num_cls = cls_scores.shape\n        cls_scores, indices = cls_scores.flatten(start_dim=1).topk(\n            self.num_output, dim=1, sorted=self.sorted\n        )\n        if not squeeze_cls:\n            cls_ids = indices % num_cls\n        if self.score_threshold is not None:\n            mask = cls_scores >= self.score_threshold\n\n        if quality[output_idx] is None:\n            quality = None\n        if quality is not None:\n            centerness = quality[output_idx][..., CNS]\n            centerness = torch.gather(centerness, 1, indices // num_cls)\n            cls_scores_origin = cls_scores.clone()\n            cls_scores *= centerness.sigmoid()\n            cls_scores, idx = torch.sort(cls_scores, dim=1, descending=True)\n            if not squeeze_cls:\n                cls_ids = torch.gather(cls_ids, 1, idx)\n            if self.score_threshold is not None:\n                mask = torch.gather(mask, 1, idx)\n            indices = torch.gather(indices, 1, idx)\n\n        output = []\n        anchor_queue = motion_output[\"anchor_queue\"]\n        anchor_queue = torch.stack(anchor_queue, dim=2)\n        period = motion_output[\"period\"]\n\n        for i in range(bs):\n            category_ids = cls_ids[i]\n            if squeeze_cls:\n                category_ids = category_ids[indices[i]]\n            scores = cls_scores[i]\n            box = box_preds[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                category_ids = category_ids[mask[i]]\n                scores = scores[mask[i]]\n                box = box[mask[i]]\n            if quality is not None:\n                scores_origin = cls_scores_origin[i]\n                if self.score_threshold is not None:\n                    scores_origin = scores_origin[mask[i]]\n\n            box = decode_box(box)\n            trajs = motion_output[\"prediction\"][-1]\n            traj_cls = motion_output[\"classification\"][-1].sigmoid()\n            traj = trajs[i, indices[i] // num_cls]\n            traj_cls = traj_cls[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                traj = traj[mask[i]]\n                traj_cls = traj_cls[mask[i]]\n            traj = traj.cumsum(dim=-2) + box[:, None, None, :2]\n            output.append(\n                {\n                    \"trajs_3d\": traj.cpu(),\n                    \"trajs_score\": traj_cls.cpu()\n                }\n            )\n\n            temp_anchor = anchor_queue[i, indices[i] // num_cls]\n            temp_period = period[i, indices[i] // num_cls]\n            if self.score_threshold is not None:\n                temp_anchor = temp_anchor[mask[i]]\n                temp_period = temp_period[mask[i]]\n            num_pred, queue_len = temp_anchor.shape[:2]\n            temp_anchor = temp_anchor.flatten(0, 1)\n            temp_anchor = decode_box(temp_anchor)\n            temp_anchor = temp_anchor.reshape([num_pred, queue_len, box.shape[-1]])\n            output[-1]['anchor_queue'] = temp_anchor.cpu()\n            output[-1]['period'] = temp_period.cpu()\n        \n        return output\n\n\n@BBOX_CODERS.register_module()\nclass HierarchicalPlanningDecoder(object):\n    def __init__(\n        self,\n        ego_fut_ts,\n        ego_fut_mode,\n        use_rescore=False,\n    ):\n        super(HierarchicalPlanningDecoder, self).__init__()\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n        self.use_rescore = use_rescore\n    \n    def decode(\n        self, \n        det_output,\n        motion_output,\n        planning_output, \n        data,\n    ):\n        classification = planning_output['classification'][-1]\n        prediction = planning_output['prediction'][-1]\n        bs = classification.shape[0]\n        classification = classification.reshape(bs, 3, self.ego_fut_mode)\n        prediction = prediction.reshape(bs, 3, self.ego_fut_mode, self.ego_fut_ts, 2).cumsum(dim=-2)\n        classification, final_planning = self.select(det_output, motion_output, classification, prediction, data)\n        anchor_queue = planning_output[\"anchor_queue\"]\n        anchor_queue = torch.stack(anchor_queue, dim=2)\n        period = planning_output[\"period\"]\n        output = []\n        for i, (cls, pred) in enumerate(zip(classification, prediction)):\n            output.append(\n                {\n                    \"planning_score\": cls.sigmoid().cpu(),\n                    \"planning\": pred.cpu(),\n                    \"final_planning\": final_planning[i].cpu(),\n                    \"ego_period\": period[i].cpu(),\n                    \"ego_anchor_queue\": decode_box(anchor_queue[i]).cpu(),\n                }\n            )\n\n        return output\n\n    def select(\n        self,\n        det_output,\n        motion_output,\n        plan_cls,\n        plan_reg,\n        data,\n    ):\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        motion_cls = motion_output[\"classification\"][-1].sigmoid()\n        motion_reg = motion_output[\"prediction\"][-1]\n        \n        # cmd select\n        bs = motion_cls.shape[0]\n        bs_indices = torch.arange(bs, device=motion_cls.device)\n        cmd = data['gt_ego_fut_cmd'].argmax(dim=-1)\n        plan_cls_full = plan_cls.detach().clone()\n        plan_cls = plan_cls[bs_indices, cmd]\n        plan_reg = plan_reg[bs_indices, cmd]\n\n        # rescore\n        if self.use_rescore:\n            plan_cls = self.rescore(\n                plan_cls,\n                plan_reg, \n                motion_cls,\n                motion_reg, \n                det_anchors,\n                det_confidence,\n            )\n        plan_cls_full[bs_indices, cmd] = plan_cls\n        mode_idx = plan_cls.argmax(dim=-1)\n        final_planning = plan_reg[bs_indices, mode_idx]\n        return plan_cls_full, final_planning\n\n    def rescore(\n        self, \n        plan_cls,\n        plan_reg, \n        motion_cls,\n        motion_reg, \n        det_anchors,\n        det_confidence,\n        score_thresh=0.5,\n        static_dis_thresh=0.5,\n        dim_scale=1.1,\n        num_motion_mode=1,\n        offset=0.5,\n    ):\n        \n        def cat_with_zero(traj):\n            zeros = traj.new_zeros(traj.shape[:-2] + (1, 2))\n            traj_cat = torch.cat([zeros, traj], dim=-2)\n            return traj_cat\n        \n        def get_yaw(traj, start_yaw=np.pi/2):\n            yaw = traj.new_zeros(traj.shape[:-1])\n            yaw[..., 1:-1] = torch.atan2(\n                traj[..., 2:, 1] - traj[..., :-2, 1],\n                traj[..., 2:, 0] - traj[..., :-2, 0],\n            )\n            yaw[..., -1] = torch.atan2(\n                traj[..., -1, 1] - traj[..., -2, 1],\n                traj[..., -1, 0] - traj[..., -2, 0],\n            )\n            yaw[..., 0] = start_yaw\n            # for static object, estimated future yaw would be unstable\n            start = traj[..., 0, :]\n            end = traj[..., -1, :]\n            dist = torch.linalg.norm(end - start, dim=-1)\n            mask = dist < static_dis_thresh\n            start_yaw = yaw[..., 0].unsqueeze(-1)\n            yaw = torch.where(\n                mask.unsqueeze(-1),\n                start_yaw,\n                yaw,\n            )\n            return yaw.unsqueeze(-1)\n        \n        ## ego\n        bs = plan_reg.shape[0]\n        plan_reg_cat = cat_with_zero(plan_reg)\n        ego_box = det_anchors.new_zeros(bs, self.ego_fut_mode, self.ego_fut_ts + 1, 7)\n        ego_box[..., [X, Y]] = plan_reg_cat\n        ego_box[..., [W, L, H]] = ego_box.new_tensor([4.08, 1.73, 1.56]) * dim_scale\n        ego_box[..., [YAW]] = get_yaw(plan_reg_cat)\n\n        ## motion\n        motion_reg = motion_reg[..., :self.ego_fut_ts, :].cumsum(-2)\n        motion_reg = cat_with_zero(motion_reg) + det_anchors[:, :, None, None, :2]\n        _, motion_mode_idx = torch.topk(motion_cls, num_motion_mode, dim=-1)\n        motion_mode_idx = motion_mode_idx[..., None, None].repeat(1, 1, 1, self.ego_fut_ts + 1, 2)\n        motion_reg = torch.gather(motion_reg, 2, motion_mode_idx)\n\n        motion_box = motion_reg.new_zeros(motion_reg.shape[:-1] + (7,))\n        motion_box[..., [X, Y]] = motion_reg\n        motion_box[..., [W, L, H]] = det_anchors[..., None, None, [W, L, H]].exp()\n        box_yaw = torch.atan2(\n            det_anchors[..., SIN_YAW],\n            det_anchors[..., COS_YAW],\n        )\n        motion_box[..., [YAW]] = get_yaw(motion_reg, box_yaw.unsqueeze(-1))\n\n        filter_mask = det_confidence < score_thresh\n        motion_box[filter_mask] = 1e6\n\n        ego_box = ego_box[..., 1:, :]\n        motion_box = motion_box[..., 1:, :]\n\n        bs, num_ego_mode, ts, _ = ego_box.shape\n        bs, num_anchor, num_motion_mode, ts, _ = motion_box.shape\n        ego_box = ego_box[:, None, None].repeat(1, num_anchor, num_motion_mode, 1, 1, 1).flatten(0, -2)\n        motion_box = motion_box.unsqueeze(3).repeat(1, 1, 1, num_ego_mode, 1, 1).flatten(0, -2)\n\n        ego_box[0] += offset * torch.cos(ego_box[6])\n        ego_box[1] += offset * torch.sin(ego_box[6])\n        col = check_collision(ego_box, motion_box)\n        col = col.reshape(bs, num_anchor, num_motion_mode, num_ego_mode, ts).permute(0, 3, 1, 2, 4)\n        col = col.flatten(2, -1).any(dim=-1)\n        all_col = col.all(dim=-1)\n        col[all_col] = False # for case that all modes collide, no need to rescore\n        score_offset = col.float() * -999\n        plan_cls = plan_cls + score_offset\n        return plan_cls\n\n\ndef check_collision(boxes1, boxes2):\n    '''\n        A rough check for collision detection: \n            check if any corner point of boxes1 is inside boxes2 and vice versa.\n        \n        boxes1: tensor with shape [N, 7], [x, y, z, w, l, h, yaw]\n        boxes2: tensor with shape [N, 7]\n    '''\n    col_1 = corners_in_box(boxes1.clone(), boxes2.clone())\n    col_2 = corners_in_box(boxes2.clone(), boxes1.clone())\n    collision = torch.logical_or(col_1, col_2)\n\n    return collision\n\ndef corners_in_box(boxes1, boxes2):\n    if  boxes1.shape[0] == 0 or boxes2.shape[0] == 0:\n        return False\n\n    boxes1_yaw = boxes1[:, 6].clone()\n    boxes1_loc = boxes1[:, :3].clone()\n    cos_yaw = torch.cos(-boxes1_yaw)\n    sin_yaw = torch.sin(-boxes1_yaw)\n    rot_mat_T = torch.stack(\n        [\n            torch.stack([cos_yaw, sin_yaw]),\n            torch.stack([-sin_yaw, cos_yaw]),\n        ]\n    )\n    # translate and rotate boxes\n    boxes1[:, :3] = boxes1[:, :3] - boxes1_loc\n    boxes1[:, :2] = torch.einsum('ij,jki->ik', boxes1[:, :2], rot_mat_T)\n    boxes1[:, 6] = boxes1[:, 6] - boxes1_yaw\n\n    boxes2[:, :3] = boxes2[:, :3] - boxes1_loc\n    boxes2[:, :2] = torch.einsum('ij,jki->ik', boxes2[:, :2], rot_mat_T)\n    boxes2[:, 6] = boxes2[:, 6] - boxes1_yaw\n\n    corners_box2 = box3d_to_corners(boxes2)[:, [0, 3, 7, 4], :2]\n    corners_box2 = torch.from_numpy(corners_box2).to(boxes2.device)\n    H = boxes1[:, [3]]\n    W = boxes1[:, [4]]\n\n    collision = torch.logical_and(\n        torch.logical_and(corners_box2[..., 0] <= H / 2, corners_box2[..., 0] >= -H / 2),\n        torch.logical_and(corners_box2[..., 1] <= W / 2, corners_box2[..., 1] >= -W / 2),\n    )\n    collision = collision.any(dim=-1)\n\n    return collision"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/instance_queue.py",
    "content": "import copy\nimport torch\nfrom torch import nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\n\nfrom projects.mmdet3d_plugin.ops import feature_maps_format\nfrom projects.mmdet3d_plugin.core.box3d import *\n\n\n@PLUGIN_LAYERS.register_module()\nclass InstanceQueue(nn.Module):\n    def __init__(\n        self,\n        embed_dims,\n        queue_length=0,\n        tracking_threshold=0,\n        feature_map_scale=None,\n    ):\n        super(InstanceQueue, self).__init__()\n        self.embed_dims = embed_dims\n        self.queue_length = queue_length\n        self.tracking_threshold = tracking_threshold\n\n        kernel_size = tuple([int(x / 2) for x in feature_map_scale])\n        self.ego_feature_encoder = nn.Sequential(\n            nn.Conv2d(embed_dims, embed_dims, 3, stride=1, padding=1, bias=False),\n            nn.BatchNorm2d(embed_dims),\n            nn.Conv2d(embed_dims, embed_dims, 3, stride=2, padding=1, bias=False),\n            nn.BatchNorm2d(embed_dims),\n            nn.ReLU(),\n            nn.AvgPool2d(kernel_size),\n        )\n        self.ego_anchor = nn.Parameter(\n            torch.tensor([[0, 0.5, -1.84 + 1.56/2, np.log(4.08), np.log(1.73), np.log(1.56), 1, 0, 0, 0, 0],], dtype=torch.float32),\n            requires_grad=False,\n        )\n\n        self.reset()\n\n    def reset(self):\n        self.metas = None\n        self.prev_instance_id = None\n        self.prev_confidence = None\n        self.period = None\n        self.instance_feature_queue = []\n        self.anchor_queue = []\n        self.prev_ego_status = None\n        self.ego_period = None\n        self.ego_feature_queue = []\n        self.ego_anchor_queue = []\n\n    def get(\n        self,\n        det_output,\n        feature_maps,\n        metas,\n        batch_size,\n        mask,\n        anchor_handler,\n    ):\n        if (\n            self.period is not None\n            and batch_size == self.period.shape[0]\n        ):\n            if anchor_handler is not None:\n                T_temp2cur = feature_maps[0].new_tensor(\n                    np.stack(\n                        [\n                            x[\"T_global_inv\"]\n                            @ self.metas[\"img_metas\"][i][\"T_global\"]\n                            for i, x in enumerate(metas[\"img_metas\"])\n                        ]\n                    )\n                )\n                for i in range(len(self.anchor_queue)):\n                    temp_anchor = self.anchor_queue[i]\n                    temp_anchor = anchor_handler.anchor_projection(\n                        temp_anchor,\n                        [T_temp2cur],\n                    )[0]\n                    self.anchor_queue[i] = temp_anchor\n                for i in range(len(self.ego_anchor_queue)):\n                    temp_anchor = self.ego_anchor_queue[i]\n                    temp_anchor = anchor_handler.anchor_projection(\n                        temp_anchor,\n                        [T_temp2cur],\n                    )[0]\n                    self.ego_anchor_queue[i] = temp_anchor\n        else:\n            self.reset()\n\n        self.prepare_motion(det_output, mask)\n        ego_feature, ego_anchor = self.prepare_planning(feature_maps, mask, batch_size)\n\n        # temporal \n        temp_instance_feature = torch.stack(self.instance_feature_queue, dim=2)\n        temp_anchor = torch.stack(self.anchor_queue, dim=2)\n        temp_ego_feature = torch.stack(self.ego_feature_queue, dim=2)\n        temp_ego_anchor = torch.stack(self.ego_anchor_queue, dim=2)\n\n        period = torch.cat([self.period, self.ego_period], dim=1)\n        temp_instance_feature = torch.cat([temp_instance_feature, temp_ego_feature], dim=1)\n        temp_anchor = torch.cat([temp_anchor, temp_ego_anchor], dim=1)\n        num_agent = temp_anchor.shape[1]\n        \n        temp_mask = torch.arange(len(self.anchor_queue), 0, -1, device=temp_anchor.device)\n        temp_mask = temp_mask[None, None].repeat((batch_size, num_agent, 1))\n        temp_mask = torch.gt(temp_mask, period[..., None])\n\n        return ego_feature, ego_anchor, temp_instance_feature, temp_anchor, temp_mask\n\n    def prepare_motion(\n        self,\n        det_output,\n        mask,\n    ):\n        instance_feature = det_output[\"instance_feature\"]\n        det_anchors = det_output[\"prediction\"][-1]\n\n        if self.period == None:\n            self.period = instance_feature.new_zeros(instance_feature.shape[:2]).long()\n        else:\n            instance_id = det_output['instance_id']\n            prev_instance_id = self.prev_instance_id\n            match = instance_id[..., None] == prev_instance_id[:, None]\n            if self.tracking_threshold > 0:\n                temp_mask = self.prev_confidence > self.tracking_threshold\n                match = match * temp_mask.unsqueeze(1)\n\n            for i in range(len(self.instance_feature_queue)):\n                temp_feature = self.instance_feature_queue[i]\n                temp_feature = (\n                    match[..., None] * temp_feature[:, None]\n                ).sum(dim=2)\n                self.instance_feature_queue[i] = temp_feature\n\n                temp_anchor = self.anchor_queue[i]\n                temp_anchor = (\n                    match[..., None] * temp_anchor[:, None]\n                ).sum(dim=2)\n                self.anchor_queue[i] = temp_anchor\n\n            self.period = (\n                match * self.period[:, None]\n            ).sum(dim=2)\n\n        self.instance_feature_queue.append(instance_feature.detach())\n        self.anchor_queue.append(det_anchors.detach())\n        self.period += 1\n\n        if len(self.instance_feature_queue) > self.queue_length:\n            self.instance_feature_queue.pop(0)\n            self.anchor_queue.pop(0)\n        self.period = torch.clip(self.period, 0, self.queue_length)\n\n    def prepare_planning(\n        self,\n        feature_maps,\n        mask,\n        batch_size,\n    ):\n        ## ego instance init\n        feature_maps_inv = feature_maps_format(feature_maps, inverse=True)\n        feature_map = feature_maps_inv[0][-1][:, 0]\n        ego_feature = self.ego_feature_encoder(feature_map)\n        ego_feature = ego_feature.unsqueeze(1).squeeze(-1).squeeze(-1)\n\n        ego_anchor = torch.tile(\n            self.ego_anchor[None], (batch_size, 1, 1)\n        )\n        if self.prev_ego_status is not None:\n            prev_ego_status = torch.where(\n                mask[:, None, None],\n                self.prev_ego_status,\n                self.prev_ego_status.new_tensor(0),\n            )\n            ego_anchor[..., VY] = prev_ego_status[..., 6]\n\n        if self.ego_period == None:\n            self.ego_period = ego_feature.new_zeros((batch_size, 1)).long()\n        else:\n            self.ego_period = torch.where(\n                mask[:, None],\n                self.ego_period,\n                self.ego_period.new_tensor(0),\n            )\n\n        self.ego_feature_queue.append(ego_feature.detach())\n        self.ego_anchor_queue.append(ego_anchor.detach())\n        self.ego_period += 1\n        \n        if len(self.ego_feature_queue) > self.queue_length:\n            self.ego_feature_queue.pop(0)\n            self.ego_anchor_queue.pop(0)\n        self.ego_period = torch.clip(self.ego_period, 0, self.queue_length)\n\n        return ego_feature, ego_anchor\n\n    def cache_motion(self, instance_feature, det_output, metas):\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_confidence = det_classification.max(dim=-1).values\n        instance_id = det_output['instance_id']\n        self.metas = metas\n        self.prev_confidence = det_confidence.detach()\n        self.prev_instance_id = instance_id\n\n    def cache_planning(self, ego_feature, ego_status):\n        self.prev_ego_status = ego_status.detach()\n        self.ego_feature_queue[-1] = ego_feature.detach()\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/motion_blocks.py",
    "content": "import torch\nimport torch.nn as nn\nimport numpy as np\n\nfrom mmcv.cnn import Linear, Scale, bias_init_with_prob\nfrom mmcv.runner.base_module import Sequential, BaseModule\nfrom mmcv.cnn import xavier_init\nfrom mmcv.cnn.bricks.registry import (\n    PLUGIN_LAYERS,\n)\n\nfrom projects.mmdet3d_plugin.core.box3d import *\nfrom ..blocks import linear_relu_ln\n\n\n@PLUGIN_LAYERS.register_module()\nclass MotionPlanningRefinementModule(BaseModule):\n    def __init__(\n        self,\n        embed_dims=256,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n    ):\n        super(MotionPlanningRefinementModule, self).__init__()\n        #import pdb;pdb.set_trace()\n        self.embed_dims = embed_dims\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.motion_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        self.motion_reg_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, fut_ts * 2),\n        )\n        self.plan_cls_branch = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 2),\n            Linear(embed_dims, 1),\n        )\n        self.plan_reg_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, ego_fut_ts * 2),\n        )\n        self.plan_status_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, 10),\n        )\n\n    def init_weight(self):\n        bias_init = bias_init_with_prob(0.01)\n        nn.init.constant_(self.motion_cls_branch[-1].bias, bias_init)\n        nn.init.constant_(self.plan_cls_branch[-1].bias, bias_init)\n\n    def forward(\n        self,\n        motion_query,\n        plan_query,\n        ego_feature,\n        ego_anchor_embed,\n    ):\n        bs, num_anchor = motion_query.shape[:2]\n        motion_cls = self.motion_cls_branch(motion_query).squeeze(-1)\n        motion_reg = self.motion_reg_branch(motion_query).reshape(bs, num_anchor, self.fut_mode, self.fut_ts, 2)\n        plan_cls = self.plan_cls_branch(plan_query).squeeze(-1)\n        plan_reg = self.plan_reg_branch(plan_query).reshape(bs, 1, 3 * self.ego_fut_mode, self.ego_fut_ts, 2)\n        planning_status = self.plan_status_branch(ego_feature + ego_anchor_embed)\n        return motion_cls, motion_reg, plan_cls, plan_reg, planning_status\n\n\nclass MotionPlanning2thRefinementModule(nn.Module):\n    def __init__(\n        self,\n        embed_dims=256,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n    ):\n        super(MotionPlanning2thRefinementModule, self).__init__()\n        self.embed_dims = embed_dims\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.plan_cls_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.LayerNorm(embed_dims),\n            nn.Linear(embed_dims, 1),\n        )\n        self.plan_reg_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, ego_fut_ts * 2),\n        )\n        self.plan_status_branch = nn.Sequential(\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, embed_dims),\n            nn.ReLU(),\n            nn.Linear(embed_dims, 10),\n        )\n\n    def init_weight(self):\n        bias_init = bias_init_with_prob(0.01)\n        nn.init.constant_(self.plan_cls_branch[-1].bias, bias_init)\n\n    def forward(\n        self,\n        plan_query,\n        ego_feature,\n        ego_anchor_embed,\n    ):\n        bs = plan_query.shape[0]\n        plan_cls = self.plan_cls_branch(plan_query).squeeze(-1)\n        plan_reg = self.plan_reg_branch(plan_query).reshape(bs, 1, 3 * self.ego_fut_mode, self.ego_fut_ts, 2)\n        planning_status = self.plan_status_branch(ego_feature + ego_anchor_embed)\n        return plan_cls, plan_reg, planning_status\n\n\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/motion_planning_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\nimport copy\n\nimport numpy as np\nimport cv2\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn import Linear, bias_init_with_prob\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmdet.core import reduce_mean\nfrom mmdet.models import HEADS\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS, BBOX_CODERS\nfrom mmdet.models import build_loss\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom projects.mmdet3d_plugin.core.box3d import *\n\nfrom ..attention import gen_sineembed_for_position\nfrom ..blocks import linear_relu_ln\nfrom ..instance_bank import topk\n\n\n@HEADS.register_module()\nclass MotionPlanningHead(BaseModule):\n    def __init__(\n        self,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        motion_anchor=None,\n        plan_anchor=None,\n        embed_dims=256,\n        decouple_attn=False,\n        instance_queue=None,\n        operation_order=None,\n        temp_graph_model=None,\n        graph_model=None,\n        cross_graph_model=None,\n        norm_layer=None,\n        ffn=None,\n        refine_layer=None,\n        motion_sampler=None,\n        motion_loss_cls=None,\n        motion_loss_reg=None,\n        planning_sampler=None,\n        plan_loss_cls=None,\n        plan_loss_reg=None,\n        plan_loss_status=None,\n        motion_decoder=None,\n        planning_decoder=None,\n        num_det=50,\n        num_map=10,\n    ):\n        super(MotionPlanningHead, self).__init__()\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.decouple_attn = decouple_attn\n        self.operation_order = operation_order\n\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n        \n        self.instance_queue = build(instance_queue, PLUGIN_LAYERS)\n        self.motion_sampler = build(motion_sampler, BBOX_SAMPLERS)\n        self.planning_sampler = build(planning_sampler, BBOX_SAMPLERS)\n        self.motion_decoder = build(motion_decoder, BBOX_CODERS)\n        self.planning_decoder = build(planning_decoder, BBOX_CODERS)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"cross_gnn\": [cross_graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = embed_dims\n\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n        self.motion_loss_cls = build_loss(motion_loss_cls)\n        self.motion_loss_reg = build_loss(motion_loss_reg)\n        self.plan_loss_cls = build_loss(plan_loss_cls)\n        self.plan_loss_reg = build_loss(plan_loss_reg)\n        self.plan_loss_status = build_loss(plan_loss_status)\n\n        # motion init\n        motion_anchor = np.load(motion_anchor)\n        self.motion_anchor = nn.Parameter(\n            torch.tensor(motion_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.motion_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        # plan anchor init\n        plan_anchor = np.load(plan_anchor)\n        self.plan_anchor = nn.Parameter(\n            torch.tensor(plan_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.plan_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        self.num_det = num_det\n        self.num_map = num_map\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        for m in self.modules():\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def get_motion_anchor(\n        self, \n        classification, \n        prediction,\n    ):\n        cls_ids = classification.argmax(dim=-1)\n        motion_anchor = self.motion_anchor[cls_ids]\n        prediction = prediction.detach()\n        return self._agent2lidar(motion_anchor, prediction)\n\n    def _agent2lidar(self, trajs, boxes):\n        yaw = torch.atan2(boxes[..., SIN_YAW], boxes[..., COS_YAW])\n        cos_yaw = torch.cos(yaw)\n        sin_yaw = torch.sin(yaw)\n        rot_mat_T = torch.stack(\n            [\n                torch.stack([cos_yaw, sin_yaw]),\n                torch.stack([-sin_yaw, cos_yaw]),\n            ]\n        )\n\n        trajs_lidar = torch.einsum('abcij,jkab->abcik', trajs, rot_mat_T)\n        return trajs_lidar\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n\n    def forward(\n        self, \n        det_output,\n        map_output,\n        feature_maps,\n        metas,\n        anchor_encoder,\n        mask,\n        anchor_handler,\n    ):   \n        # =========== det/map feature/anchor ===========\n        instance_feature = det_output[\"instance_feature\"]\n        anchor_embed = det_output[\"anchor_embed\"]\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        _, (instance_feature_selected, anchor_embed_selected) = topk(\n            det_confidence, self.num_det, instance_feature, anchor_embed\n        )\n\n        map_instance_feature = map_output[\"instance_feature\"]\n        map_anchor_embed = map_output[\"anchor_embed\"]\n        map_classification = map_output[\"classification\"][-1].sigmoid()\n        map_anchors = map_output[\"prediction\"][-1]\n        map_confidence = map_classification.max(dim=-1).values\n        _, (map_instance_feature_selected, map_anchor_embed_selected) = topk(\n            map_confidence, self.num_map, map_instance_feature, map_anchor_embed\n        )\n\n        # =========== get ego/temporal feature/anchor ===========\n        bs, num_anchor, dim = instance_feature.shape\n        (\n            ego_feature,\n            ego_anchor,\n            temp_instance_feature,\n            temp_anchor,\n            temp_mask,\n        ) = self.instance_queue.get(\n            det_output,\n            feature_maps,\n            metas,\n            bs,\n            mask,\n            anchor_handler,\n        )\n        ego_anchor_embed = anchor_encoder(ego_anchor)\n        temp_anchor_embed = anchor_encoder(temp_anchor)\n        temp_instance_feature = temp_instance_feature.flatten(0, 1)\n        temp_anchor_embed = temp_anchor_embed.flatten(0, 1)\n        temp_mask = temp_mask.flatten(0, 1)\n\n        # =========== mode anchor init ===========\n        motion_anchor = self.get_motion_anchor(det_classification, det_anchors)\n        plan_anchor = torch.tile(\n            self.plan_anchor[None], (bs, 1, 1, 1, 1)\n        )\n\n        # =========== mode query init ===========\n        motion_mode_query = self.motion_anchor_encoder(gen_sineembed_for_position(motion_anchor[..., -1, :]))\n        plan_pos = gen_sineembed_for_position(plan_anchor[..., -1, :])\n        plan_mode_query = self.plan_anchor_encoder(plan_pos).flatten(1, 2).unsqueeze(1)\n\n        # =========== cat instance and ego ===========\n        instance_feature_selected = torch.cat([instance_feature_selected, ego_feature], dim=1)\n        anchor_embed_selected = torch.cat([anchor_embed_selected, ego_anchor_embed], dim=1)\n\n        instance_feature = torch.cat([instance_feature, ego_feature], dim=1)\n        anchor_embed = torch.cat([anchor_embed, ego_anchor_embed], dim=1)\n\n        # =================== forward the layers ====================\n        motion_classification = []\n        motion_prediction = []\n        planning_classification = []\n        planning_prediction = []\n        planning_status = []\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature.flatten(0, 1).unsqueeze(1),\n                    temp_instance_feature,\n                    temp_instance_feature,\n                    query_pos=anchor_embed.flatten(0, 1).unsqueeze(1),\n                    key_pos=temp_anchor_embed,\n                    key_padding_mask=temp_mask,\n                )\n                instance_feature = instance_feature.reshape(bs, num_anchor + 1, dim)\n            elif op == \"gnn\":\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    instance_feature_selected,\n                    instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=anchor_embed_selected,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"cross_gnn\":\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    key=map_instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=map_anchor_embed_selected,\n                )\n            elif op == \"refine\":\n                motion_query = motion_mode_query + (instance_feature + anchor_embed)[:, :num_anchor].unsqueeze(2)\n                plan_query = plan_mode_query + (instance_feature + anchor_embed)[:, num_anchor:].unsqueeze(2) \n                (\n                    motion_cls,\n                    motion_reg,\n                    plan_cls,\n                    plan_reg,\n                    plan_status,\n                ) = self.layers[i](\n                    motion_query,\n                    plan_query,\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                )\n                motion_classification.append(motion_cls)\n                motion_prediction.append(motion_reg)\n                planning_classification.append(plan_cls)\n                planning_prediction.append(plan_reg)\n                planning_status.append(plan_status)\n        # import pdb; pdb.set_trace()\n        self.instance_queue.cache_motion(instance_feature[:, :num_anchor], det_output, metas)\n        self.instance_queue.cache_planning(instance_feature[:, num_anchor:], plan_status)\n\n        motion_output = {\n            \"classification\": motion_classification,\n            \"prediction\": motion_prediction,\n            \"period\": self.instance_queue.period,\n            \"anchor_queue\": self.instance_queue.anchor_queue,\n        }\n        #import pdb;pdb.set_trace()\n        planning_output = {\n            \"classification\": planning_classification,\n            \"prediction\": planning_prediction,\n            \"status\": planning_status,\n            \"period\": self.instance_queue.ego_period,\n            \"anchor_queue\": self.instance_queue.ego_anchor_queue,\n        }\n        return motion_output, planning_output\n    \n    def loss(self,\n        motion_model_outs, \n        planning_model_outs,\n        data, \n        motion_loss_cache\n    ):\n        loss = {}\n        motion_loss = self.loss_motion(motion_model_outs, data, motion_loss_cache)\n        loss.update(motion_loss)\n        planning_loss = self.loss_planning(planning_model_outs, data)\n        loss.update(planning_loss)\n        return loss\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_motion(self, model_outs, data, motion_loss_cache):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        output = {}\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(cls_scores, reg_preds)\n        ):\n            (\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n                num_pos\n            ) = self.motion_sampler.sample(\n                reg,\n                data[\"gt_agent_fut_trajs\"],\n                data[\"gt_agent_fut_masks\"],\n                motion_loss_cache,\n            )\n            num_pos = max(reduce_mean(num_pos), 1.0)\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.motion_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=num_pos)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n            reg_pred = reg_pred.cumsum(dim=-2)\n            reg_target = reg_target.cumsum(dim=-2)\n            reg_loss = self.motion_loss_reg(\n                reg_pred, reg_target, weight=reg_weight, avg_factor=num_pos\n            )\n\n            output.update(\n                {\n                    f\"motion_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"motion_loss_reg_{decoder_idx}\": reg_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning(self, model_outs, data):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        status_preds = model_outs[\"status\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            import pdb;pdb.set_trace()\n            cls = cls.flatten(end_dim=1) # [6,1,6] , [6,6]\n            cls_target = cls_target.flatten(end_dim=1) # [6,1], [6]\n            cls_weight = cls_weight.flatten(end_dim=1) # [6,1], [6]\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(\n        self, \n        det_output,\n        motion_output,\n        planning_output,\n        data,\n    ):\n        motion_result = self.motion_decoder.decode(\n            det_output[\"classification\"],\n            det_output[\"prediction\"],\n            det_output.get(\"instance_id\"),\n            det_output.get(\"quality\"),\n            motion_output,\n        )\n        planning_result = self.planning_decoder.decode(\n            det_output,\n            motion_output,\n            planning_output, \n            data,\n        )\n\n        return motion_result, planning_result"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/motion_planning_head_roboAD.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\nimport copy\n\nimport numpy as np\nimport cv2\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn import Linear, bias_init_with_prob\nfrom mmcv.cnn.bricks.transformer import BaseTransformerLayer\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmdet.core import reduce_mean\nfrom mmdet.models import HEADS\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS, BBOX_CODERS\nfrom mmdet.models import build_loss\nfrom scipy.spatial.distance import euclidean\nfrom fastdtw import fastdtw\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom projects.mmdet3d_plugin.core.box3d import *\nfrom projects.mmdet3d_plugin.models.motion.motion_blocks import *\n\nfrom ..attention import gen_sineembed_for_position\nfrom ..blocks import linear_relu_ln\nfrom ..instance_bank import topk\nfrom nuscenes.nuscenes import NuScenes\nfrom ....configs.sparsedrive_small_stage2_roboAD import batch_size\nfrom .next_token_prediction import NextTokenPredictor\n@HEADS.register_module()\nclass MotionPlanningHeadroboAD(BaseModule):\n    def __init__(\n        self,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=6,\n        ego_fut_mode=3,\n        motion_anchor=None,\n        plan_anchor=None,\n        embed_dims=256,\n        decouple_attn=False,\n        instance_queue=None,\n        operation_order=None,\n        temp_graph_model=None,\n        graph_model=None,\n        cross_graph_model=None,\n        norm_layer=None,\n        ffn=None,\n        refine_layer=None,\n        motion_sampler=None,\n        motion_loss_cls=None,\n        motion_loss_reg=None,\n        planning_sampler=None,\n        plan_loss_cls=None,\n        plan_loss_reg=None,\n        plan_loss_status=None,\n        motion_decoder=None,\n        planning_decoder=None,\n        num_det=50,\n        num_map=10,\n        use_rescore= True\n        \n    ):\n        super(MotionPlanningHeadroboAD, self).__init__()\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.decouple_attn = decouple_attn\n        self.operation_order = operation_order\n        self.batch_size =batch_size\n        self.last_planning_classification=torch.zeros([batch_size, 1, 18])\n        self.last_planning_prediction=torch.zeros([batch_size, 1, 18, 6, 2])\n        self.last_final_planning_prediction=torch.zeros([batch_size, 6, 2])\n        self.last_plan_query = torch.zeros([batch_size, 1, 18, 256])\n        self.last_ego_cmd = torch.zeros([batch_size, 3])\n        self.nusc = NuScenes(version='v1.0-trainval', dataroot=\"data/nuscenes/\", verbose=True)\n        self.use_rescore = use_rescore\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n        \n        self.instance_queue = build(instance_queue, PLUGIN_LAYERS)\n        self.motion_sampler = build(motion_sampler, BBOX_SAMPLERS)\n        self.planning_sampler = build(planning_sampler, BBOX_SAMPLERS)\n        self.motion_decoder = build(motion_decoder, BBOX_CODERS)\n        self.planning_decoder = build(planning_decoder, BBOX_CODERS)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"cross_gnn\": [cross_graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = embed_dims\n\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n        self.motion_loss_cls = build_loss(motion_loss_cls)\n        self.motion_loss_reg = build_loss(motion_loss_reg)\n        self.plan_loss_cls = build_loss(plan_loss_cls)\n        self.plan_loss_reg = build_loss(plan_loss_reg)\n        self.plan_loss_status = build_loss(plan_loss_status)\n        self.last_op = \"\"\n\n        # motion init\n        motion_anchor = np.load(motion_anchor)\n        self.motion_anchor = nn.Parameter(\n            torch.tensor(motion_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.motion_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        # plan anchor init\n        plan_anchor = np.load(plan_anchor)\n        self.plan_anchor = nn.Parameter(\n            torch.tensor(plan_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.plan_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        self.num_det = num_det\n        self.num_map = num_map\n        #self.sa_atten_layer = nn.Conv2d(in_channels=512, out_channels=256, kernel_size=1, stride=1, padding=0)\n        self.refine_2th_layer = MotionPlanning2thRefinementModule(embed_dims=256, ego_fut_ts=6, ego_fut_mode=6)\n\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        \n        for m in self.modules():\n            #import pdb;pdb.set_trace()\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def get_motion_anchor(\n        self, \n        classification, \n        prediction,\n    ):\n        cls_ids = classification.argmax(dim=-1)\n        motion_anchor = self.motion_anchor[cls_ids]\n        prediction = prediction.detach()\n        return self._agent2lidar(motion_anchor, prediction)\n\n    def _agent2lidar(self, trajs, boxes):\n        yaw = torch.atan2(boxes[..., SIN_YAW], boxes[..., COS_YAW])\n        cos_yaw = torch.cos(yaw)\n        sin_yaw = torch.sin(yaw)\n        rot_mat_T = torch.stack(\n            [\n                torch.stack([cos_yaw, sin_yaw]),\n                torch.stack([-sin_yaw, cos_yaw]),\n            ]\n        )\n\n        trajs_lidar = torch.einsum('abcij,jkab->abcik', trajs, rot_mat_T)\n        return trajs_lidar\n\n\n    def rescore(\n        self, \n        plan_cls,\n        plan_reg, \n        motion_cls,\n        motion_reg, \n        det_anchors,\n        det_confidence,\n        score_thresh=0.5,\n        static_dis_thresh=0.5,\n        dim_scale=1.1,\n        num_motion_mode=1,\n        offset=0.5,\n    ):\n        \n        def cat_with_zero(traj):\n            zeros = traj.new_zeros(traj.shape[:-2] + (1, 2))\n            traj_cat = torch.cat([zeros, traj], dim=-2)\n            return traj_cat\n        \n        def get_yaw(traj, start_yaw=np.pi/2):\n            yaw = traj.new_zeros(traj.shape[:-1])\n            yaw[..., 1:-1] = torch.atan2(\n                traj[..., 2:, 1] - traj[..., :-2, 1],\n                traj[..., 2:, 0] - traj[..., :-2, 0],\n            )\n            yaw[..., -1] = torch.atan2(\n                traj[..., -1, 1] - traj[..., -2, 1],\n                traj[..., -1, 0] - traj[..., -2, 0],\n            )\n            yaw[..., 0] = start_yaw\n            # for static object, estimated future yaw would be unstable\n            start = traj[..., 0, :]\n            end = traj[..., -1, :]\n            dist = torch.linalg.norm(end - start, dim=-1)\n            mask = dist < static_dis_thresh\n            start_yaw = yaw[..., 0].unsqueeze(-1)\n            yaw = torch.where(\n                mask.unsqueeze(-1),\n                start_yaw,\n                yaw,\n            )\n            return yaw.unsqueeze(-1)\n        \n        ## ego\n        bs = plan_reg.shape[0]\n        plan_reg_cat = cat_with_zero(plan_reg)\n        ego_box = det_anchors.new_zeros(bs, self.ego_fut_mode, self.ego_fut_ts + 1, 7)\n        ego_box[..., [X, Y]] = plan_reg_cat\n        ego_box[..., [W, L, H]] = ego_box.new_tensor([4.08, 1.73, 1.56]) * dim_scale\n        ego_box[..., [YAW]] = get_yaw(plan_reg_cat)\n\n        ## motion\n        motion_reg = motion_reg[..., :self.ego_fut_ts, :].cumsum(-2)\n        motion_reg = cat_with_zero(motion_reg) + det_anchors[:, :, None, None, :2]\n        _, motion_mode_idx = torch.topk(motion_cls, num_motion_mode, dim=-1)\n        motion_mode_idx = motion_mode_idx[..., None, None].repeat(1, 1, 1, self.ego_fut_ts + 1, 2)\n        motion_reg = torch.gather(motion_reg, 2, motion_mode_idx)\n\n        motion_box = motion_reg.new_zeros(motion_reg.shape[:-1] + (7,))\n        motion_box[..., [X, Y]] = motion_reg\n        motion_box[..., [W, L, H]] = det_anchors[..., None, None, [W, L, H]].exp()\n        box_yaw = torch.atan2(\n            det_anchors[..., SIN_YAW],\n            det_anchors[..., COS_YAW],\n        )\n        motion_box[..., [YAW]] = get_yaw(motion_reg, box_yaw.unsqueeze(-1))\n\n        filter_mask = det_confidence < score_thresh\n        motion_box[filter_mask] = 1e6\n\n        ego_box = ego_box[..., 1:, :]\n        motion_box = motion_box[..., 1:, :]\n\n        bs, num_ego_mode, ts, _ = ego_box.shape\n        bs, num_anchor, num_motion_mode, ts, _ = motion_box.shape\n        ego_box = ego_box[:, None, None].repeat(1, num_anchor, num_motion_mode, 1, 1, 1).flatten(0, -2)\n        motion_box = motion_box.unsqueeze(3).repeat(1, 1, 1, num_ego_mode, 1, 1).flatten(0, -2)\n\n        ego_box[0] += offset * torch.cos(ego_box[6])\n        ego_box[1] += offset * torch.sin(ego_box[6])\n        col = check_collision(ego_box, motion_box)\n        col = col.reshape(bs, num_anchor, num_motion_mode, num_ego_mode, ts).permute(0, 3, 1, 2, 4)\n        col = col.flatten(2, -1).any(dim=-1)\n        all_col = col.all(dim=-1)\n        col[all_col] = False # for case that all modes collide, no need to rescore\n        score_offset = col.float() * -999\n        plan_cls = plan_cls + score_offset\n        return plan_cls\n\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n    def sa_atten(self, plan_query, last_query):\n        #import pdb;pdb.set_trace()\n        plan_query = self.sa_atten_layer(torch.cat([plan_query,last_query],dim=-1).permute(0,3,1,2))\n        return plan_query.permute(0,2,3,1)\n    def select_last_final_planning_prediction(self,planning_classification,planning_prediction,metas):\n        #print(\"hhhhhhhhhhhhhhhhhhhhhh\",len(planning_classification))\n        #import pdb; pdb.set_trace()\n        bs = planning_classification[0].shape[0]\n        #bs = planning_classification_cmd.shape[0] #3\n        planning_classification_cmd = planning_classification[-1].reshape(bs, 3, self.ego_fut_mode)#[3, 3, 6]\n        planning_prediction_cmd = planning_prediction[-1].reshape(bs, 3, self.ego_fut_mode, self.ego_fut_ts, 2).cumsum(dim=-2)#[3, 3, 6, 6, 2]\n        bs_indices = torch.arange(bs, device=planning_classification_cmd.device) #tensor([0, 1, 2], device='cuda:0')\n        gt_ego_fut_cmd = metas[\"gt_ego_fut_cmd\"].argmax(dim=-1)#tensor([2, 2, 2], device='cuda:0')\n        planning_classification_cmd_select = planning_classification_cmd[bs_indices, gt_ego_fut_cmd]#torch.Size([3, 6])\n        planning_prediction_cmd_select = planning_prediction_cmd[bs_indices, gt_ego_fut_cmd]#torch.Size([3, 6, 6, 2])\n\n        mode_idx = planning_classification_cmd_select.argmax(dim=-1)#tensor([5, 5, 0], device='cuda:0')\n        last_final_planning_prediction = planning_prediction_cmd_select[bs_indices, mode_idx] #torch.Size([3, 6, 2])\n        return last_final_planning_prediction\n    def select_currect_best_planning(self, last_final_planning_prediction, planning_prediction, current_ego_cmd, last_ego_cmd):\n        # import pdb; pdb.set_trace()\n        ego_mask=(current_ego_cmd.argmax(-1) == last_ego_cmd.argmax(-1))\n        distances_euclidean = self.euclidean_distance(last_final_planning_prediction.unsqueeze(1).repeat(1,18,1,1), planning_prediction[0].squeeze(1))\n        min_idx = torch.argmin(distances_euclidean, dim=-1).cpu().numpy().tolist()\n        bs = planning_prediction[0].squeeze(1).shape[0]\n        #import pdb;pdb.set_trace()\n        select_currect_best_planning_prediction = torch.where(ego_mask.view(-1, 1, 1), planning_prediction[0].squeeze(1)[torch.arange(bs), min_idx], torch.full((6, 2), 999.9).repeat(bs, 1, 1).to(ego_mask.device))\n        #import pdb;pdb.set_trace()\n        return select_currect_best_planning_prediction, min_idx, ego_mask\n    \n    def select_former_best_query(self, plan_query, last_ego_cmd, planning_classification):\n        last_ego_cmd = last_ego_cmd.repeat_interleave(6, dim=1)\n        planning_classification = planning_classification.squeeze(1).sigmoid() * last_ego_cmd\n\n        return planning_classification.argmax(-1)\n       \n    def euclidean_distance(self, TA, TB):\n        TA = TA.cumsum(dim=-2)\n        TB = TB.cumsum(dim=-2)\n        distances = torch.sqrt(torch.sum((TA - TB)**2, dim=-1))\n        distance_sums = distances.sum(dim=-1)\n        return distance_sums\n    def dtw_distance(self, TA, TB):\n        TA = TA.cumsum(dim=-2)\n        TB = TB.cumsum(dim=-2)\n        TA_np = TA.detach().cpu().numpy()  # 将tensor转换为numpy数组\n        TB_np = TB.detach().cpu().numpy()\n        distance, _ = fastdtw(TA_np, TB_np, dist=euclidean)\n        return distance\n    def forward(\n        self, \n        det_output,\n        map_output,\n        feature_maps,\n        metas,\n        anchor_encoder,\n        mask,\n        anchor_handler,\n    ):   \n\n        # =========== det/map feature/anchor ===========\n        instance_feature = det_output[\"instance_feature\"]\n        #det_output包括 ['clas sification', 'prediction', 'quality', 'instance_feature', 'anchor_embed', 'instance_id']\n        #det_output['classification'][0].shape  torch.Size([6, 900, 10]) (cam,anchor,class)\n        #det_output['prediction'][0].shape  torch.Size([6, 900, 11]) (cam,anchor,11) 11:{x, y, z, ln w, ln h, ln l, sin yaw, cos yaw, vx, vy, vz}\n        #det_output['quality'][0].shape  torch.Size([6, 900, 2]) (cam,anchor,2) 2:centerness,yawness\n        #det_output['instance_feature'][0].shape  torch.Size([6, 900, 256]) (cam,anchor,dim) \n        #det_output['anchor_embed'][0].shape  torch.Size([6, 900, 256]) (cam,anchor,dim) \n        anchor_embed = det_output[\"anchor_embed\"]\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        _, (instance_feature_selected, anchor_embed_selected) = topk(\n            det_confidence, self.num_det, instance_feature, anchor_embed\n        )\n        #instance_feature_selected.shape  torch.Size([6, 50, 256])\n        map_instance_feature = map_output[\"instance_feature\"]\n        #map_output包括dict_keys(['classification', 'prediction', 'quality', 'instance_feature', 'anchor_embed'])\n        #map_output[classification] torch.Size([6, 100, 3])\n        #map_output[prediction] torch.Size([6, 100, 40])\n        #map_output[quality] [None, None, None, None, None, None]\n        #map_output[instance_feature] torch.Size([6, 100, 256])\n        #map_output[anchor_embed] torch.Size([6, 100, 256])\n\n        map_anchor_embed = map_output[\"anchor_embed\"]\n        map_classification = map_output[\"classification\"][-1].sigmoid()\n        map_anchors = map_output[\"prediction\"][-1]\n        map_confidence = map_classification.max(dim=-1).values\n        _, (map_instance_feature_selected, map_anchor_embed_selected) = topk(\n            map_confidence, self.num_map, map_instance_feature, map_anchor_embed\n        )\n       \n        # =========== get ego/temporal feature/anchor ===========\n        bs, num_anchor, dim = instance_feature.shape\n        (\n            ego_feature,#torch.Size([6, 1, 256])\n            ego_anchor,#[6, 1, 11]\n            temp_instance_feature,#torch.Size([6, 901, 1, 256])\n            temp_anchor,#torch.Size([6, 901, 1, 11])\n            temp_mask,#torch.Size([6, 901, 1])\n        ) = self.instance_queue.get(\n            det_output,#dict_keys(['classification', 'prediction', 'quality', 'instance_feature', 'anchor_embed', 'instance_id'])\n            feature_maps,#torch.Size([6, 89760, 256]) torch.Size([6, 4, 2]) torch.Size([6, 4])\n            metas,#dict_keys(['img_metas', 'timestamp', 'projection_mat', 'image_wh', 'gt_depth', 'focal', 'gt_bboxes_3d', 'gt_labels_3d', 'gt_map_labels', 'gt_map_pts', 'gt_agent_fut_trajs', 'gt_agent_fut_masks', 'gt_ego_fut_trajs', 'gt_ego_fut_masks', 'gt_ego_fut_cmd', 'ego_status'])\n            bs,#6\n            mask,\n            anchor_handler,\n        )\n        ego_anchor_embed = anchor_encoder(ego_anchor)#torch.Size([6, 1, 256])\n        temp_anchor_embed = anchor_encoder(temp_anchor)#torch.Size([6, 901, 1, 256])\n        temp_instance_feature = temp_instance_feature.flatten(0, 1)#torch.Size([5406, 1, 256])\n        temp_anchor_embed = temp_anchor_embed.flatten(0, 1)#torch.Size([6, 901, 1, 256])\n        temp_mask = temp_mask.flatten(0, 1)#torch.Size([6, 901, 1])\n\n        # =========== mode anchor init ===========\n        motion_anchor = self.get_motion_anchor(det_classification, det_anchors) #motion_anchor torch.Size([6, 900, 6, 12, 2]) #torch.Size([6, 900, 10])  torch.Size([6, 900, 11])\n        plan_anchor = torch.tile( #torch.Size([6, 3, 6, 6, 2])\n            self.plan_anchor[None], (bs, 1, 1, 1, 1)\n        )\n\n        # =========== mode query init ===========\n        motion_mode_query = self.motion_anchor_encoder(gen_sineembed_for_position(motion_anchor[..., -1, :])) #torch.Size([6, 900, 6, 256])\n        plan_pos = gen_sineembed_for_position(plan_anchor[..., -1, :]) #torch.Size([6, 3, 6, 256])\n        plan_mode_query = self.plan_anchor_encoder(plan_pos).flatten(1, 2).unsqueeze(1)#torch.Size([6, 1, 18, 256])\n\n        # =========== cat instance and ego ===========\n        instance_feature_selected = torch.cat([instance_feature_selected, ego_feature], dim=1) #torch.Size([6, 50, 256]) torch.Size([6, 50, 256]) torch.Size([6, 1, 256])\n        anchor_embed_selected = torch.cat([anchor_embed_selected, ego_anchor_embed], dim=1) #torch.Size([6, 50, 256]) torch.Size([6, 50, 256]) torch.Size([6, 1, 256])\n\n        instance_feature = torch.cat([instance_feature, ego_feature], dim=1) #torch.Size([6, 900, 256]) torch.Size([6, 900, 256]) torch.Size([6, 1, 256])\n        anchor_embed = torch.cat([anchor_embed, ego_anchor_embed], dim=1)#torch.Size([6, 900, 256]) torch.Size([6, 900, 256]) torch.Size([6, 1, 256])\n\n        # =================== forward the layers ====================\n        motion_classification = []\n        motion_prediction = []\n        planning_classification = []\n        planning_prediction = []\n        planning_status = []\n        planning_classification_refined = []\n        planning_prediction_refined = []\n        planning_status_refined = []\n        for i, op in enumerate(self.operation_order):\n            #import pdb;pdb.set_trace()\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                #self.last_op = \"temp_gnn\"\n                instance_feature = self.graph_model(#[5406, 1, 256])\n                    i,\n                    instance_feature.flatten(0, 1).unsqueeze(1),\n                    temp_instance_feature,#torch.Size([5406, 1, 256])\n                    temp_instance_feature,\n                    query_pos=anchor_embed.flatten(0, 1).unsqueeze(1),#torch.Size([5406, 1, 256])\n                    key_pos=temp_anchor_embed,#torch.Size([5406, 1, 256])\n                    key_padding_mask=temp_mask,#torch.Size([5406, 1])\n                )\n                instance_feature = instance_feature.reshape(bs, num_anchor + 1, dim)#torch.Size([6, 901, 256])\n            elif op == \"gnn\":\n                #self.last_op = \"gnn\"\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    instance_feature_selected,\n                    instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=anchor_embed_selected,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                #self.last_op = \"norm\"\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"cross_gnn\":\n                #self.last_op = \"cross_gnn\"\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    key=map_instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=map_anchor_embed_selected,\n                )\n            elif op == \"refine\":\n                motion_query = motion_mode_query + (instance_feature + anchor_embed)[:, :num_anchor].unsqueeze(2)\n                plan_query = plan_mode_query + (instance_feature + anchor_embed)[:, num_anchor:].unsqueeze(2)\n                #plan_query= self.sa_atten(plan_query, self.last_plan_query.to(plan_query.device))\n                # import pdb;pdb.set_trace()\n                \n                (\n                    motion_cls,\n                    motion_reg,\n                    plan_cls,#torch.Size([6, 1, 18])\n                    plan_reg,#torch.Size([6, 1, 18, 6, 2])\n                    plan_status,\n                ) = self.layers[i](\n                    motion_query, #([6, 900, 6, 256]\n                    plan_query, #6, 1, 18, 256]\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                )\n                \n                motion_classification.append(motion_cls)\n                motion_prediction.append(motion_reg)\n                planning_classification.append(plan_cls)\n                planning_prediction.append(plan_reg)\n                planning_status.append(plan_status)\n        \n        self.instance_queue.cache_motion(instance_feature[:, :num_anchor], det_output, metas)\n        self.instance_queue.cache_planning(instance_feature[:, num_anchor:], plan_status)\n        #import pdb;pdb.set_trace()\n        motion_output = {\n            \"classification\": motion_classification, #[6, 900, 6]\n            \"prediction\": motion_prediction,#[6, 900, 6, 12, 2])\n            \"period\": self.instance_queue.period,#[6, 900]\n            \"anchor_queue\": self.instance_queue.anchor_queue,#torch.Size([6, 900, 11])\n        }\n        \n        #import pdb;pdb.set_trace()\n        sample0_token = metas[\"img_metas\"][0][\"token\"]\n        # sample1_token = metas[\"img_metas\"][1][\"token\"]\n        # sample2_token = metas[\"img_metas\"][2][\"token\"]\n        # sample3_token = metas[\"img_metas\"][3][\"token\"]\n        # sample4_token = metas[\"img_metas\"][4][\"token\"]\n        # sample5_token = metas[\"img_metas\"][5][\"token\"]\n        # import pdb; pdb.set_trace()\n        # if self.last_planning_classification==0:\n        #     pass\n        # else:\n        #     pass\n\n        #import pdb; pdb.set_trace()\n        #判断是否是场景的第一个sample，如果是，则上一帧的结果应该是0（目的是防止不同场景的数据结合）\n        # prev_sample_token = self.nusc.get('sample', sample0_token)[\"prev\"]\n        prev_sample_token = self.nusc.get('sample', sample0_token)[\"prev\"]\n        # import pdb; pdb.set_trace()\n        # if plan_query.device==torch.device(type='cuda', index=1):\n        #     print(self.nusc.get('sample', sample0_token),self.nusc.get('sample', sample0_token)[\"next\"],plan_query.device)\n        if prev_sample_token == \"\":\n            \n            device = plan_query.device\n            self.last_planning_classification=torch.zeros([batch_size, 1, 18]).detach()\n            self.last_planning_prediction=torch.zeros([batch_size, 1, 18, 6, 2]).detach()\n            self.last_plan_query = torch.zeros([batch_size, 1, 18, 256]).detach()\n            self.last_final_planning_prediction  = torch.zeros([batch_size, 6, 2]).detach()\n            self.last_ego_cmd = torch.zeros([batch_size, 3]).detach()\n        device = plan_query.device\n        self.last_planning_classification=self.last_planning_classification.to(device).detach()\n        self.last_planning_prediction=self.last_planning_prediction.to(device).detach()\n        self.last_plan_query = self.last_plan_query.to(device).detach()\n        self.last_final_planning_prediction  = self.last_final_planning_prediction.to(device).detach()\n        self.last_ego_cmd = self.last_ego_cmd.to(device).detach()\n        # # # fusion\n        # device = plan_query.device\n        # self.last_planning_classification=torch.zeros([batch_size, 1, 18]).to(device).detach()\n        # self.last_planning_prediction=torch.zeros([batch_size, 1, 18, 6, 2]).to(device).detach()\n        # self.last_plan_query = torch.zeros([batch_size, 1, 18, 256]).to(device).detach()\n        # self.last_final_planning_prediction  = torch.zeros([batch_size, 6, 2]).to(device).detach()\n        # self.last_ego_cmd = torch.zeros([batch_size, 3]).to(device).detach()\n\n\n\n        enhanced_plan_query = plan_query\n        last_final_planning_prediction = self.last_final_planning_prediction\n        current_ego_cmd = metas['gt_ego_fut_cmd']\n        # print(current_ego_cmd)\n        # print(self.last_ego_cmd)\n        # import pdb;pdb.set_trace()\n\n        select_currect_best_planning_prediction, select_currect_idx, ego_mask = self.select_currect_best_planning(last_final_planning_prediction, planning_prediction, current_ego_cmd, self.last_ego_cmd)\n        select_last_idx = self.select_former_best_query(self.last_plan_query, self.last_ego_cmd, self.last_planning_classification)\n        last_query_mask = torch.zeros([select_last_idx.shape[0],1,18,256])\n        last_query_detach = self.last_plan_query\n        for i in range(last_query_detach.shape[0]):\n            last_query_detach[i][0][select_currect_idx[i],:] = self.last_plan_query[i][0][select_last_idx[i],:]\n        last_query_mask[:,:,select_currect_idx,:] = 1\n        ego_mask_idx = np.where(ego_mask.cpu().tolist())[0].tolist()\n        last_query_mask[ego_mask_idx,:,:,:] = 0\n        # import pdb; pdb.set_trace()\n        if self.last_plan_query.sum()>0:\n            nxttokenpredictor = NextTokenPredictor(256, 128)\n            # import pdb; pdb.set_trace()\n            # print(self.last_plan_query.shape,self.last_planning_classification.shape, enhanced_plan_query.shape )\n            enhanced_plan_query=nxttokenpredictor(self.last_plan_query,self.last_planning_classification, enhanced_plan_query )\n        enhanced_plan_query = enhanced_plan_query + self.last_plan_query * last_query_mask.to(enhanced_plan_query.device)\n          \n        # refine 模块添加\n        plan_cls_2th, plan_reg_2th, plan_status_2th = self.refine_2th_layer(enhanced_plan_query, instance_feature[:, num_anchor:], anchor_embed[:, num_anchor:])\n        #(torch.Size([1, 1, 18]), torch.Size([1, 1, 18, 6, 2]), torch.Size([1, 1, 10]))\n        planning_classification_refined.append(plan_cls_2th)\n        planning_prediction_refined.append(plan_reg_2th)\n        planning_status_refined.append(plan_status_2th)\n\n\n        # 将当前帧的结果存到cache, 并进行detach\n        last_final_planning_prediction =self.select_last_final_planning_prediction(planning_classification,planning_prediction,metas).detach()\n        self.last_planning_classification = torch.tensor(planning_classification[0]).detach()\n        self.last_planning_prediction = torch.tensor(planning_prediction[0]).detach()\n        self.last_plan_query = torch.tensor(plan_query).detach()\n        if self.training:\n            #import pdb;pdb.set_trace()\n            self.last_final_planning_prediction = torch.tensor(metas['gt_ego_fut_trajs']).detach()\n        else:\n            self.last_final_planning_prediction = torch.tensor(last_final_planning_prediction).detach()\n        self.last_ego_cmd = metas['gt_ego_fut_cmd'].detach()\n        \n        \n        planning_output = {\n            \"classification\": planning_classification,#[6, 1, 18] #3是command\n            \"prediction\": planning_prediction,#[6, 1, 18, 6, 2]\n            \"status\": planning_status,#[6, 1, 10]\n            \"classification_refined\": planning_classification_refined,#[6, 1, 18] #3是command\n            \"prediction_refined\": planning_prediction_refined,#[6, 1, 18, 6, 2]\n            \"status_refined\": planning_status_refined,#[6, 1, 10]\n            \"period\": self.instance_queue.ego_period,\n            \"anchor_queue\": self.instance_queue.ego_anchor_queue,\n        }\n        return motion_output, planning_output\n    \n\n    def loss(self,\n        motion_model_outs, \n        planning_model_outs,\n        data, \n        motion_loss_cache\n    ):\n        loss = {}\n        motion_loss = self.loss_motion(motion_model_outs, data, motion_loss_cache)\n        loss.update(motion_loss)\n        planning_loss = self.loss_planning(planning_model_outs, data)\n        loss.update(planning_loss)\n        planning_loss_refined = self.loss_planning_refined(planning_model_outs, data)\n        loss.update(planning_loss_refined)\n        return loss\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_motion(self, model_outs, data, motion_loss_cache):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        output = {}\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(cls_scores, reg_preds)\n        ):\n            (\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n                num_pos\n            ) = self.motion_sampler.sample(\n                reg,\n                data[\"gt_agent_fut_trajs\"],\n                data[\"gt_agent_fut_masks\"],\n                motion_loss_cache,\n            )\n            num_pos = max(reduce_mean(num_pos), 1.0)\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.motion_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=num_pos)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n            reg_pred = reg_pred.cumsum(dim=-2)\n            reg_target = reg_target.cumsum(dim=-2)\n            reg_loss = self.motion_loss_reg(\n                reg_pred, reg_target, weight=reg_weight, avg_factor=num_pos\n            )\n\n            output.update(\n                {\n                    f\"motion_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"motion_loss_reg_{decoder_idx}\": reg_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning(self, model_outs, data):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        status_preds = model_outs[\"status\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n    \n    def loss_planning_refined(self, model_outs, data):\n        cls_scores = model_outs[\"classification_refined\"]\n        reg_preds = model_outs[\"prediction_refined\"]\n        status_preds = model_outs[\"status_refined\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_refined_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_refined_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_refined_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(\n        self, \n        det_output,\n        motion_output,\n        planning_output,\n        data,\n    ):\n        motion_result = self.motion_decoder.decode(\n            det_output[\"classification\"],\n            det_output[\"prediction\"],\n            det_output.get(\"instance_id\"),\n            det_output.get(\"quality\"),\n            motion_output,\n        )\n        planning_result = self.planning_decoder.decode(\n            det_output,\n            motion_output,\n            planning_output, \n            data,\n        )\n\n        return motion_result, planning_result"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/motion_planning_head_roboAD_6s.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\nimport copy\n\nimport numpy as np\nimport cv2\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn import Linear, bias_init_with_prob\nfrom mmcv.cnn.bricks.transformer import BaseTransformerLayer\nfrom mmcv.runner import BaseModule, force_fp32\nfrom mmcv.cnn.bricks.registry import (\n    ATTENTION,\n    PLUGIN_LAYERS,\n    POSITIONAL_ENCODING,\n    FEEDFORWARD_NETWORK,\n    NORM_LAYERS,\n)\nfrom mmdet.core import reduce_mean\nfrom mmdet.models import HEADS\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS, BBOX_CODERS\nfrom mmdet.models import build_loss\nfrom scipy.spatial.distance import euclidean\nfrom fastdtw import fastdtw\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\nfrom projects.mmdet3d_plugin.core.box3d import *\nfrom projects.mmdet3d_plugin.models.motion.motion_blocks import *\n\nfrom ..attention import gen_sineembed_for_position\nfrom ..blocks import linear_relu_ln\nfrom ..instance_bank import topk\nfrom nuscenes.nuscenes import NuScenes\nfrom ....configs.sparsedrive_small_stage2_roboAD import batch_size\nfrom .next_token_prediction import NextTokenPredictor\n@HEADS.register_module()\nclass MotionPlanningHeadroboAD_6s(BaseModule):\n    def __init__(\n        self,\n        fut_ts=12,\n        fut_mode=6,\n        ego_fut_ts=12,\n        ego_fut_mode=3,\n        motion_anchor=None,\n        plan_anchor=None,\n        embed_dims=256,\n        decouple_attn=False,\n        instance_queue=None,\n        operation_order=None,\n        temp_graph_model=None,\n        graph_model=None,\n        cross_graph_model=None,\n        norm_layer=None,\n        ffn=None,\n        refine_layer=None,\n        motion_sampler=None,\n        motion_loss_cls=None,\n        motion_loss_reg=None,\n        planning_sampler=None,\n        plan_loss_cls=None,\n        plan_loss_reg=None,\n        plan_loss_status=None,\n        motion_decoder=None,\n        planning_decoder=None,\n        num_det=50,\n        num_map=10,\n        use_rescore= True\n        \n    ):\n        super(MotionPlanningHeadroboAD_6s, self).__init__()\n        self.fut_ts = fut_ts\n        self.fut_mode = fut_mode\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n        self.decouple_attn = decouple_attn\n        self.operation_order = operation_order\n        self.batch_size =batch_size\n        self.last_planning_classification=torch.zeros([batch_size, 1, 18])\n        self.last_planning_prediction=torch.zeros([batch_size, 1, 18, 12, 2])\n        self.last_final_planning_prediction=torch.zeros([batch_size, 12, 2])\n        self.last_plan_query = torch.zeros([batch_size, 1, 18, 256])\n        self.last_ego_cmd = torch.zeros([batch_size, 3])\n        self.nusc = NuScenes(version='v1.0-trainval', dataroot=\"data/nuscenes/\", verbose=True)\n        self.use_rescore = use_rescore\n        # =========== build modules ===========\n        def build(cfg, registry):\n            if cfg is None:\n                return None\n            return build_from_cfg(cfg, registry)\n        \n        self.instance_queue = build(instance_queue, PLUGIN_LAYERS)\n        self.motion_sampler = build(motion_sampler, BBOX_SAMPLERS)\n        self.planning_sampler = build(planning_sampler, BBOX_SAMPLERS)\n        self.motion_decoder = build(motion_decoder, BBOX_CODERS)\n        self.planning_decoder = build(planning_decoder, BBOX_CODERS)\n        self.op_config_map = {\n            \"temp_gnn\": [temp_graph_model, ATTENTION],\n            \"gnn\": [graph_model, ATTENTION],\n            \"cross_gnn\": [cross_graph_model, ATTENTION],\n            \"norm\": [norm_layer, NORM_LAYERS],\n            \"ffn\": [ffn, FEEDFORWARD_NETWORK],\n            \"refine\": [refine_layer, PLUGIN_LAYERS],\n        }\n        self.layers = nn.ModuleList(\n            [\n                build(*self.op_config_map.get(op, [None, None]))\n                for op in self.operation_order\n            ]\n        )\n        self.embed_dims = embed_dims\n\n        if self.decouple_attn:\n            self.fc_before = nn.Linear(\n                self.embed_dims, self.embed_dims * 2, bias=False\n            )\n            self.fc_after = nn.Linear(\n                self.embed_dims * 2, self.embed_dims, bias=False\n            )\n        else:\n            self.fc_before = nn.Identity()\n            self.fc_after = nn.Identity()\n\n        self.motion_loss_cls = build_loss(motion_loss_cls)\n        self.motion_loss_reg = build_loss(motion_loss_reg)\n        self.plan_loss_cls = build_loss(plan_loss_cls)\n        self.plan_loss_reg = build_loss(plan_loss_reg)\n        self.plan_loss_status = build_loss(plan_loss_status)\n        self.last_op = \"\"\n\n        # motion init\n        motion_anchor = np.load(motion_anchor)\n        self.motion_anchor = nn.Parameter(\n            torch.tensor(motion_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.motion_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        # plan anchor init\n        plan_anchor = np.load(plan_anchor)\n        self.plan_anchor = nn.Parameter(\n            torch.tensor(plan_anchor, dtype=torch.float32),\n            requires_grad=False,\n        )\n        self.plan_anchor_encoder = nn.Sequential(\n            *linear_relu_ln(embed_dims, 1, 1),\n            Linear(embed_dims, embed_dims),\n        )\n\n        self.num_det = num_det\n        self.num_map = num_map\n        #self.sa_atten_layer = nn.Conv2d(in_channels=512, out_channels=256, kernel_size=1, stride=1, padding=0)\n        self.refine_2th_layer = MotionPlanning2thRefinementModule(embed_dims=256, ego_fut_ts=12, ego_fut_mode=6)\n\n\n    def init_weights(self):\n        for i, op in enumerate(self.operation_order):\n            if self.layers[i] is None:\n                continue\n            elif op != \"refine\":\n                for p in self.layers[i].parameters():\n                    if p.dim() > 1:\n                        nn.init.xavier_uniform_(p)\n        \n        for m in self.modules():\n            #import pdb;pdb.set_trace()\n            if hasattr(m, \"init_weight\"):\n                m.init_weight()\n\n    def get_motion_anchor(\n        self, \n        classification, \n        prediction,\n    ):\n        cls_ids = classification.argmax(dim=-1)\n        motion_anchor = self.motion_anchor[cls_ids]\n        prediction = prediction.detach()\n        return self._agent2lidar(motion_anchor, prediction)\n\n    def _agent2lidar(self, trajs, boxes):\n        yaw = torch.atan2(boxes[..., SIN_YAW], boxes[..., COS_YAW])\n        cos_yaw = torch.cos(yaw)\n        sin_yaw = torch.sin(yaw)\n        rot_mat_T = torch.stack(\n            [\n                torch.stack([cos_yaw, sin_yaw]),\n                torch.stack([-sin_yaw, cos_yaw]),\n            ]\n        )\n\n        trajs_lidar = torch.einsum('abcij,jkab->abcik', trajs, rot_mat_T)\n        return trajs_lidar\n\n\n    def rescore(\n        self, \n        plan_cls,\n        plan_reg, \n        motion_cls,\n        motion_reg, \n        det_anchors,\n        det_confidence,\n        score_thresh=0.5,\n        static_dis_thresh=0.5,\n        dim_scale=1.1,\n        num_motion_mode=1,\n        offset=0.5,\n    ):\n        \n        def cat_with_zero(traj):\n            zeros = traj.new_zeros(traj.shape[:-2] + (1, 2))\n            traj_cat = torch.cat([zeros, traj], dim=-2)\n            return traj_cat\n        \n        def get_yaw(traj, start_yaw=np.pi/2):\n            yaw = traj.new_zeros(traj.shape[:-1])\n            yaw[..., 1:-1] = torch.atan2(\n                traj[..., 2:, 1] - traj[..., :-2, 1],\n                traj[..., 2:, 0] - traj[..., :-2, 0],\n            )\n            yaw[..., -1] = torch.atan2(\n                traj[..., -1, 1] - traj[..., -2, 1],\n                traj[..., -1, 0] - traj[..., -2, 0],\n            )\n            yaw[..., 0] = start_yaw\n            # for static object, estimated future yaw would be unstable\n            start = traj[..., 0, :]\n            end = traj[..., -1, :]\n            dist = torch.linalg.norm(end - start, dim=-1)\n            mask = dist < static_dis_thresh\n            start_yaw = yaw[..., 0].unsqueeze(-1)\n            yaw = torch.where(\n                mask.unsqueeze(-1),\n                start_yaw,\n                yaw,\n            )\n            return yaw.unsqueeze(-1)\n        \n        ## ego\n        bs = plan_reg.shape[0]\n        plan_reg_cat = cat_with_zero(plan_reg)\n        ego_box = det_anchors.new_zeros(bs, self.ego_fut_mode, self.ego_fut_ts + 1, 7)\n        ego_box[..., [X, Y]] = plan_reg_cat\n        ego_box[..., [W, L, H]] = ego_box.new_tensor([4.08, 1.73, 1.56]) * dim_scale\n        ego_box[..., [YAW]] = get_yaw(plan_reg_cat)\n\n        ## motion\n        motion_reg = motion_reg[..., :self.ego_fut_ts, :].cumsum(-2)\n        motion_reg = cat_with_zero(motion_reg) + det_anchors[:, :, None, None, :2]\n        _, motion_mode_idx = torch.topk(motion_cls, num_motion_mode, dim=-1)\n        motion_mode_idx = motion_mode_idx[..., None, None].repeat(1, 1, 1, self.ego_fut_ts + 1, 2)\n        motion_reg = torch.gather(motion_reg, 2, motion_mode_idx)\n\n        motion_box = motion_reg.new_zeros(motion_reg.shape[:-1] + (7,))\n        motion_box[..., [X, Y]] = motion_reg\n        motion_box[..., [W, L, H]] = det_anchors[..., None, None, [W, L, H]].exp()\n        box_yaw = torch.atan2(\n            det_anchors[..., SIN_YAW],\n            det_anchors[..., COS_YAW],\n        )\n        motion_box[..., [YAW]] = get_yaw(motion_reg, box_yaw.unsqueeze(-1))\n\n        filter_mask = det_confidence < score_thresh\n        motion_box[filter_mask] = 1e6\n\n        ego_box = ego_box[..., 1:, :]\n        motion_box = motion_box[..., 1:, :]\n\n        bs, num_ego_mode, ts, _ = ego_box.shape\n        bs, num_anchor, num_motion_mode, ts, _ = motion_box.shape\n        ego_box = ego_box[:, None, None].repeat(1, num_anchor, num_motion_mode, 1, 1, 1).flatten(0, -2)\n        motion_box = motion_box.unsqueeze(3).repeat(1, 1, 1, num_ego_mode, 1, 1).flatten(0, -2)\n\n        ego_box[0] += offset * torch.cos(ego_box[6])\n        ego_box[1] += offset * torch.sin(ego_box[6])\n        col = check_collision(ego_box, motion_box)\n        col = col.reshape(bs, num_anchor, num_motion_mode, num_ego_mode, ts).permute(0, 3, 1, 2, 4)\n        col = col.flatten(2, -1).any(dim=-1)\n        all_col = col.all(dim=-1)\n        col[all_col] = False # for case that all modes collide, no need to rescore\n        score_offset = col.float() * -999\n        plan_cls = plan_cls + score_offset\n        return plan_cls\n\n\n    def graph_model(\n        self,\n        index,\n        query,\n        key=None,\n        value=None,\n        query_pos=None,\n        key_pos=None,\n        **kwargs,\n    ):\n        if self.decouple_attn:\n            query = torch.cat([query, query_pos], dim=-1)\n            if key is not None:\n                key = torch.cat([key, key_pos], dim=-1)\n            query_pos, key_pos = None, None\n        if value is not None:\n            value = self.fc_before(value)\n        return self.fc_after(\n            self.layers[index](\n                query,\n                key,\n                value,\n                query_pos=query_pos,\n                key_pos=key_pos,\n                **kwargs,\n            )\n        )\n    def sa_atten(self, plan_query, last_query):\n        #import pdb;pdb.set_trace()\n        plan_query = self.sa_atten_layer(torch.cat([plan_query,last_query],dim=-1).permute(0,3,1,2))\n        return plan_query.permute(0,2,3,1)\n    def select_last_final_planning_prediction(self,planning_classification,planning_prediction,metas):\n        #print(\"hhhhhhhhhhhhhhhhhhhhhh\",len(planning_classification))\n        #import pdb; pdb.set_trace()\n        bs = planning_classification[0].shape[0]\n        #bs = planning_classification_cmd.shape[0] #3\n        planning_classification_cmd = planning_classification[-1].reshape(bs, 3, self.ego_fut_mode)#[3, 3, 6]\n        planning_prediction_cmd = planning_prediction[-1].reshape(bs, 3, self.ego_fut_mode, self.ego_fut_ts, 2).cumsum(dim=-2)#[3, 3, 6, 12, 2]\n        bs_indices = torch.arange(bs, device=planning_classification_cmd.device) #tensor([0, 1, 2], device='cuda:0')\n        gt_ego_fut_cmd = metas[\"gt_ego_fut_cmd\"].argmax(dim=-1)#tensor([2, 2, 2], device='cuda:0')\n        planning_classification_cmd_select = planning_classification_cmd[bs_indices, gt_ego_fut_cmd]#torch.Size([3, 6])\n        planning_prediction_cmd_select = planning_prediction_cmd[bs_indices, gt_ego_fut_cmd]#torch.Size([3, 6, 12, 2])\n\n        mode_idx = planning_classification_cmd_select.argmax(dim=-1)#tensor([5, 5, 0], device='cuda:0')\n        last_final_planning_prediction = planning_prediction_cmd_select[bs_indices, mode_idx] #torch.Size([3, 12, 2])\n        return last_final_planning_prediction\n    def select_currect_best_planning(self, last_final_planning_prediction, planning_prediction, current_ego_cmd, last_ego_cmd):\n        # import pdb; pdb.set_trace()\n        ego_mask=(current_ego_cmd.argmax(-1) == last_ego_cmd.argmax(-1))\n        distances_euclidean = self.euclidean_distance(last_final_planning_prediction.unsqueeze(1).repeat(1,18,1,1), planning_prediction[0].squeeze(1))\n        min_idx = torch.argmin(distances_euclidean, dim=-1).cpu().numpy().tolist()\n        bs = planning_prediction[0].squeeze(1).shape[0]\n        #import pdb;pdb.set_trace()\n        select_currect_best_planning_prediction = torch.where(ego_mask.view(-1, 1, 1), planning_prediction[0].squeeze(1)[torch.arange(bs), min_idx], torch.full((12, 2), 999.9).repeat(bs, 1, 1).to(ego_mask.device))\n        #import pdb;pdb.set_trace()\n        return select_currect_best_planning_prediction, min_idx, ego_mask\n    \n    def select_former_best_query(self, plan_query, last_ego_cmd, planning_classification):\n        last_ego_cmd = last_ego_cmd.repeat_interleave(6, dim=1)\n        planning_classification = planning_classification.squeeze(1).sigmoid() * last_ego_cmd\n\n        return planning_classification.argmax(-1)\n       \n    def euclidean_distance(self, TA, TB):\n        TA = TA.cumsum(dim=-2)\n        TB = TB.cumsum(dim=-2)\n        distances = torch.sqrt(torch.sum((TA - TB)**2, dim=-1))\n        distance_sums = distances.sum(dim=-1)\n        return distance_sums\n    def dtw_distance(self, TA, TB):\n        TA = TA.cumsum(dim=-2)\n        TB = TB.cumsum(dim=-2)\n        TA_np = TA.detach().cpu().numpy()  # 将tensor转换为numpy数组\n        TB_np = TB.detach().cpu().numpy()\n        distance, _ = fastdtw(TA_np, TB_np, dist=euclidean)\n        return distance\n    def forward(\n        self, \n        det_output,\n        map_output,\n        feature_maps,\n        metas,\n        anchor_encoder,\n        mask,\n        anchor_handler,\n    ):   \n\n        # =========== det/map feature/anchor ===========\n        instance_feature = det_output[\"instance_feature\"]\n        #det_output包括 ['clas sification', 'prediction', 'quality', 'instance_feature', 'anchor_embed', 'instance_id']\n        #det_output['classification'][0].shape  torch.Size([6, 900, 10]) (cam,anchor,class)\n        #det_output['prediction'][0].shape  torch.Size([6, 900, 11]) (cam,anchor,11) 11:{x, y, z, ln w, ln h, ln l, sin yaw, cos yaw, vx, vy, vz}\n        #det_output['quality'][0].shape  torch.Size([6, 900, 2]) (cam,anchor,2) 2:centerness,yawness\n        #det_output['instance_feature'][0].shape  torch.Size([6, 900, 256]) (cam,anchor,dim) \n        #det_output['anchor_embed'][0].shape  torch.Size([6, 900, 256]) (cam,anchor,dim) \n        anchor_embed = det_output[\"anchor_embed\"]\n        det_classification = det_output[\"classification\"][-1].sigmoid()\n        det_anchors = det_output[\"prediction\"][-1]\n        det_confidence = det_classification.max(dim=-1).values\n        _, (instance_feature_selected, anchor_embed_selected) = topk(\n            det_confidence, self.num_det, instance_feature, anchor_embed\n        )\n        #instance_feature_selected.shape  torch.Size([6, 50, 256])\n        map_instance_feature = map_output[\"instance_feature\"]\n        #map_output包括dict_keys(['classification', 'prediction', 'quality', 'instance_feature', 'anchor_embed'])\n        #map_output[classification] torch.Size([6, 100, 3])\n        #map_output[prediction] torch.Size([6, 100, 40])\n        #map_output[quality] [None, None, None, None, None, None]\n        #map_output[instance_feature] torch.Size([6, 100, 256])\n        #map_output[anchor_embed] torch.Size([6, 100, 256])\n\n        map_anchor_embed = map_output[\"anchor_embed\"]\n        map_classification = map_output[\"classification\"][-1].sigmoid()\n        map_anchors = map_output[\"prediction\"][-1]\n        map_confidence = map_classification.max(dim=-1).values\n        _, (map_instance_feature_selected, map_anchor_embed_selected) = topk(\n            map_confidence, self.num_map, map_instance_feature, map_anchor_embed\n        )\n       \n        # =========== get ego/temporal feature/anchor ===========\n        bs, num_anchor, dim = instance_feature.shape\n        (\n            ego_feature,#torch.Size([6, 1, 256])\n            ego_anchor,#[6, 1, 11]\n            temp_instance_feature,#torch.Size([6, 901, 1, 256])\n            temp_anchor,#torch.Size([6, 901, 1, 11])\n            temp_mask,#torch.Size([6, 901, 1])\n        ) = self.instance_queue.get(\n            det_output,#dict_keys(['classification', 'prediction', 'quality', 'instance_feature', 'anchor_embed', 'instance_id'])\n            feature_maps,#torch.Size([6, 89760, 256]) torch.Size([6, 4, 2]) torch.Size([6, 4])\n            metas,#dict_keys(['img_metas', 'timestamp', 'projection_mat', 'image_wh', 'gt_depth', 'focal', 'gt_bboxes_3d', 'gt_labels_3d', 'gt_map_labels', 'gt_map_pts', 'gt_agent_fut_trajs', 'gt_agent_fut_masks', 'gt_ego_fut_trajs', 'gt_ego_fut_masks', 'gt_ego_fut_cmd', 'ego_status'])\n            bs,#6\n            mask,\n            anchor_handler,\n        )\n        ego_anchor_embed = anchor_encoder(ego_anchor)#torch.Size([6, 1, 256])\n        temp_anchor_embed = anchor_encoder(temp_anchor)#torch.Size([6, 901, 1, 256])\n        temp_instance_feature = temp_instance_feature.flatten(0, 1)#torch.Size([5406, 1, 256])\n        temp_anchor_embed = temp_anchor_embed.flatten(0, 1)#torch.Size([6, 901, 1, 256])\n        temp_mask = temp_mask.flatten(0, 1)#torch.Size([6, 901, 1])\n\n        # =========== mode anchor init ===========\n        motion_anchor = self.get_motion_anchor(det_classification, det_anchors) #motion_anchor torch.Size([6, 900, 6, 12, 2]) #torch.Size([6, 900, 10])  torch.Size([6, 900, 11])\n        plan_anchor = torch.tile( #torch.Size([6, 3, 6, 12, 2])\n            self.plan_anchor[None], (bs, 1, 1, 1, 1)\n        )\n\n        # =========== mode query init ===========\n        motion_mode_query = self.motion_anchor_encoder(gen_sineembed_for_position(motion_anchor[..., -1, :])) #torch.Size([6, 900, 6, 256])\n        plan_pos = gen_sineembed_for_position(plan_anchor[..., -1, :]) #torch.Size([6, 3, 6, 256])\n        plan_mode_query = self.plan_anchor_encoder(plan_pos).flatten(1, 2).unsqueeze(1)#torch.Size([6, 1, 18, 256])\n\n        # =========== cat instance and ego ===========\n        instance_feature_selected = torch.cat([instance_feature_selected, ego_feature], dim=1) #torch.Size([6, 50, 256]) torch.Size([6, 50, 256]) torch.Size([6, 1, 256])\n        anchor_embed_selected = torch.cat([anchor_embed_selected, ego_anchor_embed], dim=1) #torch.Size([6, 50, 256]) torch.Size([6, 50, 256]) torch.Size([6, 1, 256])\n\n        instance_feature = torch.cat([instance_feature, ego_feature], dim=1) #torch.Size([6, 900, 256]) torch.Size([6, 900, 256]) torch.Size([6, 1, 256])\n        anchor_embed = torch.cat([anchor_embed, ego_anchor_embed], dim=1)#torch.Size([6, 900, 256]) torch.Size([6, 900, 256]) torch.Size([6, 1, 256])\n\n        # =================== forward the layers ====================\n        motion_classification = []\n        motion_prediction = []\n        planning_classification = []\n        planning_prediction = []\n        planning_status = []\n        planning_classification_refined = []\n        planning_prediction_refined = []\n        planning_status_refined = []\n        for i, op in enumerate(self.operation_order):\n            #import pdb;pdb.set_trace()\n            if self.layers[i] is None:\n                continue\n            elif op == \"temp_gnn\":\n                #self.last_op = \"temp_gnn\"\n                instance_feature = self.graph_model(#[5406, 1, 256])\n                    i,\n                    instance_feature.flatten(0, 1).unsqueeze(1),\n                    temp_instance_feature,#torch.Size([5406, 1, 256])\n                    temp_instance_feature,\n                    query_pos=anchor_embed.flatten(0, 1).unsqueeze(1),#torch.Size([5406, 1, 256])\n                    key_pos=temp_anchor_embed,#torch.Size([5406, 1, 256])\n                    key_padding_mask=temp_mask,#torch.Size([5406, 1])\n                )\n                instance_feature = instance_feature.reshape(bs, num_anchor + 1, dim)#torch.Size([6, 901, 256])\n            elif op == \"gnn\":\n                #self.last_op = \"gnn\"\n                instance_feature = self.graph_model(\n                    i,\n                    instance_feature,\n                    instance_feature_selected,\n                    instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=anchor_embed_selected,\n                )\n            elif op == \"norm\" or op == \"ffn\":\n                #self.last_op = \"norm\"\n                instance_feature = self.layers[i](instance_feature)\n            elif op == \"cross_gnn\":\n                #self.last_op = \"cross_gnn\"\n                instance_feature = self.layers[i](\n                    instance_feature,\n                    key=map_instance_feature_selected,\n                    query_pos=anchor_embed,\n                    key_pos=map_anchor_embed_selected,\n                )\n            elif op == \"refine\":\n                motion_query = motion_mode_query + (instance_feature + anchor_embed)[:, :num_anchor].unsqueeze(2)\n                plan_query = plan_mode_query + (instance_feature + anchor_embed)[:, num_anchor:].unsqueeze(2)\n                #plan_query= self.sa_atten(plan_query, self.last_plan_query.to(plan_query.device))\n                # import pdb;pdb.set_trace()\n                \n                (\n                    motion_cls,\n                    motion_reg,\n                    plan_cls,#torch.Size([6, 1, 18])\n                    plan_reg,#torch.Size([6, 1, 18, 12, 2])\n                    plan_status,\n                ) = self.layers[i](\n                    motion_query, #([6, 900, 6, 256]\n                    plan_query, #6, 1, 18, 256]\n                    instance_feature[:, num_anchor:],\n                    anchor_embed[:, num_anchor:],\n                )\n                \n                motion_classification.append(motion_cls)\n                motion_prediction.append(motion_reg)\n                planning_classification.append(plan_cls)\n                planning_prediction.append(plan_reg)\n                planning_status.append(plan_status)\n        \n        self.instance_queue.cache_motion(instance_feature[:, :num_anchor], det_output, metas)\n        self.instance_queue.cache_planning(instance_feature[:, num_anchor:], plan_status)\n        #import pdb;pdb.set_trace()\n        motion_output = {\n            \"classification\": motion_classification, #[6, 900, 6]\n            \"prediction\": motion_prediction,#[6, 900, 6, 12, 2])\n            \"period\": self.instance_queue.period,#[6, 900]\n            \"anchor_queue\": self.instance_queue.anchor_queue,#torch.Size([6, 900, 11])\n        }\n        \n        #import pdb;pdb.set_trace()\n        sample0_token = metas[\"img_metas\"][0][\"token\"]\n        # sample1_token = metas[\"img_metas\"][1][\"token\"]\n        # sample2_token = metas[\"img_metas\"][2][\"token\"]\n        # sample3_token = metas[\"img_metas\"][3][\"token\"]\n        # sample4_token = metas[\"img_metas\"][4][\"token\"]\n        # sample5_token = metas[\"img_metas\"][5][\"token\"]\n        # import pdb; pdb.set_trace()\n        # if self.last_planning_classification==0:\n        #     pass\n        # else:\n        #     pass\n\n        #import pdb; pdb.set_trace()\n        #判断是否是场景的第一个sample，如果是，则上一帧的结果应该是0（目的是防止不同场景的数据结合）\n        # prev_sample_token = self.nusc.get('sample', sample0_token)[\"prev\"]\n        prev_sample_token = self.nusc.get('sample', sample0_token)[\"prev\"]\n        # import pdb; pdb.set_trace()\n        # if plan_query.device==torch.device(type='cuda', index=1):\n        #     print(self.nusc.get('sample', sample0_token),self.nusc.get('sample', sample0_token)[\"next\"],plan_query.device)\n        if prev_sample_token == \"\":\n            \n            device = plan_query.device\n            self.last_planning_classification=torch.zeros([batch_size, 1, 18]).detach()\n            self.last_planning_prediction=torch.zeros([batch_size, 1, 18, 12, 2]).detach()\n            self.last_plan_query = torch.zeros([batch_size, 1, 18, 256]).detach()\n            self.last_final_planning_prediction  = torch.zeros([batch_size, 12, 2]).detach()\n            self.last_ego_cmd = torch.zeros([batch_size, 3]).detach()\n        device = plan_query.device\n        self.last_planning_classification=self.last_planning_classification.to(device).detach()\n        self.last_planning_prediction=self.last_planning_prediction.to(device).detach()\n        self.last_plan_query = self.last_plan_query.to(device).detach()\n        self.last_final_planning_prediction  = self.last_final_planning_prediction.to(device).detach()\n        self.last_ego_cmd = self.last_ego_cmd.to(device).detach()\n        # # # fusion\n        # device = plan_query.device\n        # self.last_planning_classification=torch.zeros([batch_size, 1, 18]).to(device).detach()\n        # self.last_planning_prediction=torch.zeros([batch_size, 1, 18, 12, 2]).to(device).detach()\n        # self.last_plan_query = torch.zeros([batch_size, 1, 18, 256]).to(device).detach()\n        # self.last_final_planning_prediction  = torch.zeros([batch_size, 12, 2]).to(device).detach()\n        # self.last_ego_cmd = torch.zeros([batch_size, 3]).to(device).detach()\n\n\n\n        enhanced_plan_query = plan_query\n        last_final_planning_prediction = self.last_final_planning_prediction\n        current_ego_cmd = metas['gt_ego_fut_cmd']\n        # print(current_ego_cmd)\n        # print(self.last_ego_cmd)\n        # import pdb;pdb.set_trace()\n\n        select_currect_best_planning_prediction, select_currect_idx, ego_mask = self.select_currect_best_planning(last_final_planning_prediction, planning_prediction, current_ego_cmd, self.last_ego_cmd)\n        select_last_idx = self.select_former_best_query(self.last_plan_query, self.last_ego_cmd, self.last_planning_classification)\n        last_query_mask = torch.zeros([select_last_idx.shape[0],1,18,256])\n        last_query_detach = self.last_plan_query\n        for i in range(last_query_detach.shape[0]):\n            last_query_detach[i][0][select_currect_idx[i],:] = self.last_plan_query[i][0][select_last_idx[i],:]\n        last_query_mask[:,:,select_currect_idx,:] = 1\n        ego_mask_idx = np.where(ego_mask.cpu().tolist())[0].tolist()\n        last_query_mask[ego_mask_idx,:,:,:] = 0\n        # import pdb; pdb.set_trace()\n        if self.last_plan_query.sum()>0:\n            nxttokenpredictor = NextTokenPredictor(256, 128)\n            # import pdb; pdb.set_trace()\n            # print(self.last_plan_query.shape,self.last_planning_classification.shape, enhanced_plan_query.shape )\n            enhanced_plan_query=nxttokenpredictor(self.last_plan_query,self.last_planning_classification, enhanced_plan_query )\n        enhanced_plan_query = enhanced_plan_query + self.last_plan_query * last_query_mask.to(enhanced_plan_query.device)\n          \n        # refine 模块添加\n        plan_cls_2th, plan_reg_2th, plan_status_2th = self.refine_2th_layer(enhanced_plan_query, instance_feature[:, num_anchor:], anchor_embed[:, num_anchor:])\n        #(torch.Size([1, 1, 18]), torch.Size([1, 1, 18, 12, 2]), torch.Size([1, 1, 10]))\n        planning_classification_refined.append(plan_cls_2th)\n        planning_prediction_refined.append(plan_reg_2th)\n        planning_status_refined.append(plan_status_2th)\n\n\n        # 将当前帧的结果存到cache, 并进行detach\n        last_final_planning_prediction =self.select_last_final_planning_prediction(planning_classification,planning_prediction,metas).detach()\n        self.last_planning_classification = torch.tensor(planning_classification[0]).detach()\n        self.last_planning_prediction = torch.tensor(planning_prediction[0]).detach()\n        self.last_plan_query = torch.tensor(plan_query).detach()\n        if self.training:\n            #import pdb;pdb.set_trace()\n            self.last_final_planning_prediction = torch.tensor(metas['gt_ego_fut_trajs']).detach()\n        else:\n            self.last_final_planning_prediction = torch.tensor(last_final_planning_prediction).detach()\n        self.last_ego_cmd = metas['gt_ego_fut_cmd'].detach()\n        \n        \n        planning_output = {\n            \"classification\": planning_classification,#[6, 1, 18] #3是command\n            \"prediction\": planning_prediction,#[6, 1, 18, 12, 2]\n            \"status\": planning_status,#[6, 1, 10]\n            \"classification_refined\": planning_classification_refined,#[6, 1, 18] #3是command\n            \"prediction_refined\": planning_prediction_refined,#[6, 1, 18, 12, 2]\n            \"status_refined\": planning_status_refined,#[6, 1, 10]\n            \"period\": self.instance_queue.ego_period,\n            \"anchor_queue\": self.instance_queue.ego_anchor_queue,\n        }\n        return motion_output, planning_output\n    \n\n    def loss(self,\n        motion_model_outs, \n        planning_model_outs,\n        data, \n        motion_loss_cache\n    ):\n        loss = {}\n        motion_loss = self.loss_motion(motion_model_outs, data, motion_loss_cache)\n        loss.update(motion_loss)\n        planning_loss = self.loss_planning(planning_model_outs, data)\n        loss.update(planning_loss)\n        planning_loss_refined = self.loss_planning_refined(planning_model_outs, data)\n        loss.update(planning_loss_refined)\n        return loss\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_motion(self, model_outs, data, motion_loss_cache):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        output = {}\n        for decoder_idx, (cls, reg) in enumerate(\n            zip(cls_scores, reg_preds)\n        ):\n            (\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n                num_pos\n            ) = self.motion_sampler.sample(\n                reg,\n                data[\"gt_agent_fut_trajs\"],\n                data[\"gt_agent_fut_masks\"],\n                motion_loss_cache,\n            )\n            num_pos = max(reduce_mean(num_pos), 1.0)\n\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.motion_loss_cls(cls, cls_target, weight=cls_weight, avg_factor=num_pos)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n            reg_pred = reg_pred.cumsum(dim=-2)\n            reg_target = reg_target.cumsum(dim=-2)\n            reg_loss = self.motion_loss_reg(\n                reg_pred, reg_target, weight=reg_weight, avg_factor=num_pos\n            )\n\n            output.update(\n                {\n                    f\"motion_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"motion_loss_reg_{decoder_idx}\": reg_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def loss_planning(self, model_outs, data):\n        cls_scores = model_outs[\"classification\"]\n        reg_preds = model_outs[\"prediction\"]\n        status_preds = model_outs[\"status\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n    \n    def loss_planning_refined(self, model_outs, data):\n        cls_scores = model_outs[\"classification_refined\"]\n        reg_preds = model_outs[\"prediction_refined\"]\n        status_preds = model_outs[\"status_refined\"]\n        output = {}\n        for decoder_idx, (cls, reg, status) in enumerate(\n            zip(cls_scores, reg_preds, status_preds)\n        ):\n            (\n                cls,\n                cls_target, \n                cls_weight, \n                reg_pred, \n                reg_target, \n                reg_weight, \n            ) = self.planning_sampler.sample(\n                cls,\n                reg,\n                data['gt_ego_fut_trajs'],\n                data['gt_ego_fut_masks'],\n                data,\n            )\n            cls = cls.flatten(end_dim=1)\n            cls_target = cls_target.flatten(end_dim=1)\n            cls_weight = cls_weight.flatten(end_dim=1)\n            cls_loss = self.plan_loss_cls(cls, cls_target, weight=cls_weight)\n\n            reg_weight = reg_weight.flatten(end_dim=1)\n            reg_pred = reg_pred.flatten(end_dim=1)\n            reg_target = reg_target.flatten(end_dim=1)\n            reg_weight = reg_weight.unsqueeze(-1)\n\n            reg_loss = self.plan_loss_reg(\n                reg_pred, reg_target, weight=reg_weight\n            )\n            status_loss = self.plan_loss_status(status.squeeze(1), data['ego_status'])\n\n            output.update(\n                {\n                    f\"planning_loss_cls_refined_{decoder_idx}\": cls_loss,\n                    f\"planning_loss_reg_refined_{decoder_idx}\": reg_loss,\n                    f\"planning_loss_status_refined_{decoder_idx}\": status_loss,\n                }\n            )\n\n        return output\n\n    @force_fp32(apply_to=(\"model_outs\"))\n    def post_process(\n        self, \n        det_output,\n        motion_output,\n        planning_output,\n        data,\n    ):\n        motion_result = self.motion_decoder.decode(\n            det_output[\"classification\"],\n            det_output[\"prediction\"],\n            det_output.get(\"instance_id\"),\n            det_output.get(\"quality\"),\n            motion_output,\n        )\n        planning_result = self.planning_decoder.decode(\n            det_output,\n            motion_output,\n            planning_output, \n            data,\n        )\n\n        return motion_result, planning_result"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/next_token_prediction.py",
    "content": "import torch\nimport torch.nn as nn\n\nclass ConsistencyLSTM(nn.Module):\n    def __init__(self, embed_dim, hidden_dim):\n        super(ConsistencyLSTM, self).__init__()\n        self.lstm = nn.LSTM(input_size=embed_dim, hidden_size=hidden_dim, batch_first=True)\n        self.fc = nn.Linear(hidden_dim, embed_dim)  # 输出嵌入维度\n\n    def forward(self, frames):\n        \"\"\"\n        :param frames: 输入的帧特征，形状为 (batch_size, seq_length, embed_dim)\n        :return: 输出的特征，形状为 (batch_size, 1, seq_length, embed_dim)\n        \"\"\"\n        # 通过 LSTM 处理帧特征\n        lstm_out, (hn, cn) = self.lstm(frames)  # lstm_out: (batch_size, seq_length, hidden_dim)\n\n        # 通过全连接层得到预测\n        output = self.fc(lstm_out)  # (batch_size, seq_length, embed_dim)\n\n        # 调整形状以满足输出要求\n        output = output.unsqueeze(1)  # (batch_size, 1, seq_length, embed_dim)\n        \n        return output\n\nclass NextTokenPredictor(nn.Module):\n    def __init__(self, embed_dim, hidden_dim):\n        super(NextTokenPredictor, self).__init__()\n        # self.lstm = nn.LSTM(input_size=embed_dim, hidden_size=hidden_dim, batch_first=True)\n        self.lstm = ConsistencyLSTM(embed_dim, hidden_dim)\n        self.fc = nn.Linear(hidden_dim, embed_dim)  # 输出嵌入维度\n\n    def forward(self, last_feat, last_score, cur_feat):\n        # import pdb; pdb.set_trace()\n        # 将历史特征根据分数加权\n        weighted_last_feat = last_feat * last_score.sigmoid().unsqueeze(-1)  # (batch_size, 1, seq_length, embed_dim)\n\n        # 将历史特征与当前特征结合\n        combined_feat = cur_feat + weighted_last_feat  # (batch_size, 1, seq_length, embed_dim)\n\n        # 调整维度以适应 LSTM 输入\n        combined_feat = combined_feat.squeeze(1)  # (batch_size, seq_length, embed_dim)\n\n        # 通过 LSTM 处理\n        lstm_out = self.lstm.to(last_feat.device)(combined_feat)  # lstm_out: (batch_size, seq_length, hidden_dim)\n        # import pdb; pdb.set_trace()\n        # 通过全连接层得到预测\n        # output = self.fc(lstm_out)  # (batch_size, seq_length, embed_dim)\n\n        # 调整形状以满足输出要求\n        # output = output.unsqueeze(1)  # (batch_size, 1, seq_length, embed_dim)\n        \n        return lstm_out\nif __name__ == \"__main__\":\n    # 超参数设置\n    embed_dim = 256    # 特征维度\n    hidden_dim = 128   # LSTM 隐藏层维度\n\n    # 创建模型实例\n    model = NextTokenPredictor(embed_dim, hidden_dim)\n\n    # 示例输入\n    batch_size = 6\n    seq_length = 18\n\n    last_feat = torch.randn(batch_size, 1, seq_length, embed_dim)  # 历史特征\n    last_score = torch.randn(batch_size, 1, seq_length)             # 历史特征得分\n    cur_feat = torch.randn(batch_size, 1, seq_length, embed_dim)    # 当前特征\n\n    print(\"Input shape:\", last_feat.shape,last_score.shape,cur_feat.shape)  # 应该是 (batch_size, 1, seq_length, embed_dim)\n\n    # 前向传播\n    output = model(last_feat, last_score, cur_feat)\n\n    print(\"Output shape:\", output.shape)  # 应该是 (batch_size, 1, seq_length, embed_dim)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/motion/target.py",
    "content": "import torch\n\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\n\n__all__ = [\"MotionTarget\", \"PlanningTarget\"]\n\n\ndef get_cls_target(\n    reg_preds, \n    reg_target,\n    reg_weight,\n):  \n    #import pdb;pdb.set_trace()\n    bs, num_pred, mode, ts, d = reg_preds.shape\n    reg_preds_cum = reg_preds.cumsum(dim=-2)\n    reg_target_cum = reg_target.cumsum(dim=-2)\n    dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1)\n    dist = dist * reg_weight.unsqueeze(2)\n    dist = dist.mean(dim=-1)\n    mode_idx = torch.argmin(dist, dim=-1)\n    return mode_idx\n\ndef get_best_reg(\n    reg_preds, \n    reg_target,\n    reg_weight,\n):\n    bs, num_pred, mode, ts, d = reg_preds.shape # plan [6,1,6,6,2]\n    reg_preds_cum = reg_preds.cumsum(dim=-2)\n    reg_target_cum = reg_target.cumsum(dim=-2)\n    dist = torch.linalg.norm(reg_target_cum.unsqueeze(2) - reg_preds_cum, dim=-1) # [6,1,6,6]\n    dist = dist * reg_weight.unsqueeze(2) # reg_weight.unsqueeze(2) = [6,1,6,6]\n    dist = dist.mean(dim=-1)\n    mode_idx = torch.argmin(dist, dim=-1) # [6,1] 0,4,1,0,0,1\n    mode_idx = mode_idx[..., None, None, None].repeat(1, 1, 1, ts, d)\n    best_reg = torch.gather(reg_preds, 2, mode_idx).squeeze(2) # torch.Size([6, 1, 6, 2])\n    return best_reg\n\n\n@BBOX_SAMPLERS.register_module()\nclass MotionTarget():\n    def __init__(\n        self,\n    ):\n        super(MotionTarget, self).__init__()\n\n    def sample(\n        self,\n        reg_pred,\n        gt_reg_target,\n        gt_reg_mask,\n        motion_loss_cache,\n    ):  \n        bs, num_anchor, mode, ts, d = reg_pred.shape\n        reg_target = reg_pred.new_zeros((bs, num_anchor, ts, d))\n        reg_weight = reg_pred.new_zeros((bs, num_anchor, ts))\n        indices = motion_loss_cache['indices']\n        num_pos = reg_pred.new_tensor([0])\n        for i, (pred_idx, target_idx) in enumerate(indices):\n            if len(gt_reg_target[i]) == 0:\n                continue\n            reg_target[i, pred_idx] = gt_reg_target[i][target_idx]\n            reg_weight[i, pred_idx] = gt_reg_mask[i][target_idx]\n            num_pos += len(pred_idx)\n        \n        cls_target = get_cls_target(reg_pred, reg_target, reg_weight)\n        cls_weight = reg_weight.any(dim=-1)\n        best_reg = get_best_reg(reg_pred, reg_target, reg_weight)\n\n        return cls_target, cls_weight, best_reg, reg_target, reg_weight, num_pos\n\n\n@BBOX_SAMPLERS.register_module()\nclass PlanningTarget():\n    def __init__(\n        self,\n        ego_fut_ts,\n        ego_fut_mode,\n    ):\n        super(PlanningTarget, self).__init__()\n        self.ego_fut_ts = ego_fut_ts\n        self.ego_fut_mode = ego_fut_mode\n\n    def sample(\n        self,\n        cls_pred,\n        reg_pred,\n        gt_reg_target,\n        gt_reg_mask,\n        data,\n    ):  \n        # import pdb;pdb.set_trace()\n        gt_reg_target = gt_reg_target.unsqueeze(1) # [6,1,6,2]\n        gt_reg_mask = gt_reg_mask.unsqueeze(1) # [6,1,6]\n\n        bs = reg_pred.shape[0] # [6, 1, 18, 6, 2]\n        bs_indices = torch.arange(bs, device=reg_pred.device) # [0,1,2,3,4,5]\n        cmd = data['gt_ego_fut_cmd'].argmax(dim=-1) # [2, 2, 2, 2, 2, 2]\n\n        cls_pred = cls_pred.reshape(bs, 3, 1, self.ego_fut_mode) # [6,3,1,6]\n        reg_pred = reg_pred.reshape(bs, 3, 1, self.ego_fut_mode, self.ego_fut_ts, 2) # [6,3,1,6,6,2]\n        cls_pred = cls_pred[bs_indices, cmd] # [6,1,6]\n        reg_pred = reg_pred[bs_indices, cmd] # [6,1,6,6,2]\n        cls_target = get_cls_target(reg_pred, gt_reg_target, gt_reg_mask) # [6,1]\n        cls_weight = gt_reg_mask.any(dim=-1) # [6,1,6]  -> [6,1]\n        # import pdb;pdb.set_trace()\n        best_reg = get_best_reg(reg_pred, gt_reg_target, gt_reg_mask)\n        # [6,1,6,6,2], [6,1,6,2], [6,1,6]\n        return cls_pred, cls_target, cls_weight, best_reg, gt_reg_target, gt_reg_mask\n\n\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/sparsedrive.py",
    "content": "from inspect import signature\n\nimport torch\n\nfrom mmcv.runner import force_fp32, auto_fp16\nfrom mmcv.utils import build_from_cfg\nfrom mmcv.cnn.bricks.registry import PLUGIN_LAYERS\nfrom mmdet.models import (\n    DETECTORS,\n    BaseDetector,\n    build_backbone,\n    build_head,\n    build_neck,\n)\nfrom .grid_mask import GridMask\n\ntry:\n    from ..ops import feature_maps_format\n    DAF_VALID = True\nexcept:\n    DAF_VALID = False\n\n__all__ = [\"SparseDrive\"]\n\n\n@DETECTORS.register_module()\nclass SparseDrive(BaseDetector):\n    def __init__(\n        self,\n        img_backbone,\n        head,\n        img_neck=None,\n        init_cfg=None,\n        train_cfg=None,\n        test_cfg=None,\n        pretrained=None,\n        use_grid_mask=True,\n        use_deformable_func=False,\n        depth_branch=None,\n    ):\n        super(SparseDrive, self).__init__(init_cfg=init_cfg)\n        if pretrained is not None:\n            backbone.pretrained = pretrained\n        self.img_backbone = build_backbone(img_backbone)\n        if img_neck is not None:\n            self.img_neck = build_neck(img_neck)\n        self.head = build_head(head)\n        self.use_grid_mask = use_grid_mask\n        if use_deformable_func:\n            assert DAF_VALID, \"deformable_aggregation needs to be set up.\"\n        self.use_deformable_func = use_deformable_func\n        if depth_branch is not None:\n            self.depth_branch = build_from_cfg(depth_branch, PLUGIN_LAYERS)\n        else:\n            self.depth_branch = None\n        if use_grid_mask:\n            self.grid_mask = GridMask(\n                True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7\n            ) \n\n    @auto_fp16(apply_to=(\"img\",), out_fp32=True)\n    def extract_feat(self, img, return_depth=False, metas=None):\n        bs = img.shape[0]\n        if img.dim() == 5:  # multi-view\n            num_cams = img.shape[1]\n            img = img.flatten(end_dim=1)\n        else:\n            num_cams = 1\n        if self.use_grid_mask:\n            img = self.grid_mask(img)\n        if \"metas\" in signature(self.img_backbone.forward).parameters:\n            feature_maps = self.img_backbone(img, num_cams, metas=metas)\n        else:\n            feature_maps = self.img_backbone(img)\n        if self.img_neck is not None:\n            feature_maps = list(self.img_neck(feature_maps))\n        for i, feat in enumerate(feature_maps):\n            feature_maps[i] = torch.reshape(\n                feat, (bs, num_cams) + feat.shape[1:]\n            )\n        if return_depth and self.depth_branch is not None:\n            depths = self.depth_branch(feature_maps, metas.get(\"focal\"))\n        else:\n            depths = None\n        if self.use_deformable_func:\n            feature_maps = feature_maps_format(feature_maps)\n        if return_depth:\n            return feature_maps, depths\n        return feature_maps\n\n    @force_fp32(apply_to=(\"img\",))\n    def forward(self, img, **data):\n        if self.training:\n            return self.forward_train(img, **data)\n        else:\n            return self.forward_test(img, **data)\n\n    def forward_train(self, img, **data):\n        feature_maps, depths = self.extract_feat(img, True, data)\n        model_outs = self.head(feature_maps, data)\n        output = self.head.loss(model_outs, data)\n        if depths is not None and \"gt_depth\" in data:\n            output[\"loss_dense_depth\"] = self.depth_branch.loss(\n                depths, data[\"gt_depth\"]\n            )\n        return output\n\n    def forward_test(self, img, **data):\n        if isinstance(img, list):\n            return self.aug_test(img, **data)\n        else:\n            return self.simple_test(img, **data)\n\n    def simple_test(self, img, **data):\n        feature_maps = self.extract_feat(img)\n\n        model_outs = self.head(feature_maps, data)\n        results = self.head.post_process(model_outs, data)\n        output = [{\"img_bbox\": result} for result in results]\n        return output\n\n    def aug_test(self, img, **data):\n        # fake test time augmentation\n        for key in data.keys():\n            if isinstance(data[key], list):\n                data[key] = data[key][0]\n        return self.simple_test(img[0], **data)\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/models/sparsedrive_head.py",
    "content": "from typing import List, Optional, Tuple, Union\nimport warnings\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\n\nfrom mmcv.runner import BaseModule\nfrom mmdet.models import HEADS\nfrom mmdet.models import build_head\n\n\n@HEADS.register_module()\nclass SparseDriveHead(BaseModule):\n    def __init__(\n        self,\n        task_config: dict,\n        det_head = dict,\n        map_head = dict,\n        motion_plan_head = dict,\n        init_cfg=None,\n        **kwargs,\n    ):\n        super(SparseDriveHead, self).__init__(init_cfg)\n        self.task_config = task_config\n        if self.task_config['with_det']:\n            self.det_head = build_head(det_head)\n        if self.task_config['with_map']:\n            self.map_head = build_head(map_head)\n        if self.task_config['with_motion_plan']:\n            self.motion_plan_head = build_head(motion_plan_head)\n\n    def init_weights(self):\n        if self.task_config['with_det']:\n            self.det_head.init_weights()\n        if self.task_config['with_map']:\n            self.map_head.init_weights()\n        if self.task_config['with_motion_plan']:\n            self.motion_plan_head.init_weights()\n\n    def forward(\n        self,\n        feature_maps: Union[torch.Tensor, List],\n        metas: dict,\n    ):\n        if self.task_config['with_det']:\n            det_output = self.det_head(feature_maps, metas)\n        else:\n            det_output = None\n\n        if self.task_config['with_map']:\n            map_output = self.map_head(feature_maps, metas)\n        else:\n            map_output = None\n        \n        if self.task_config['with_motion_plan']:\n            motion_output, planning_output = self.motion_plan_head(\n                det_output, \n                map_output, \n                feature_maps,\n                metas,\n                self.det_head.anchor_encoder,\n                self.det_head.instance_bank.mask,\n                self.det_head.instance_bank.anchor_handler,\n            )\n        else:\n            motion_output, planning_output = None, None\n\n        return det_output, map_output, motion_output, planning_output\n\n    def loss(self, model_outs, data):\n        det_output, map_output, motion_output, planning_output = model_outs\n        losses = dict()\n        if self.task_config['with_det']:\n            loss_det = self.det_head.loss(det_output, data)\n            losses.update(loss_det)\n        \n        if self.task_config['with_map']:\n            loss_map = self.map_head.loss(map_output, data)\n            losses.update(loss_map)\n\n        if self.task_config['with_motion_plan']:\n            motion_loss_cache = dict(\n                indices=self.det_head.sampler.indices, \n            )\n            loss_motion = self.motion_plan_head.loss(\n                motion_output, \n                planning_output, \n                data, \n                motion_loss_cache\n            )\n            losses.update(loss_motion)\n        \n        return losses\n\n    def post_process(self, model_outs, data):\n        det_output, map_output, motion_output, planning_output = model_outs\n        if self.task_config['with_det']:\n            det_result = self.det_head.post_process(det_output)\n            batch_size = len(det_result)\n        \n        if self.task_config['with_map']:\n            map_result= self.map_head.post_process(map_output)\n            batch_size = len(map_result)\n\n        if self.task_config['with_motion_plan']:\n            motion_result, planning_result = self.motion_plan_head.post_process(\n                det_output,\n                motion_output, \n                planning_output,\n                data,\n            )\n\n        results = [dict()] * batch_size\n        for i in range(batch_size):\n            if self.task_config['with_det']:\n                results[i].update(det_result[i])\n            if self.task_config['with_map']:\n                results[i].update(map_result[i])\n            if self.task_config['with_motion_plan']:\n                results[i].update(motion_result[i])\n                results[i].update(planning_result[i])\n\n        return results\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/ops/__init__.py",
    "content": "import torch\n\nfrom .deformable_aggregation import DeformableAggregationFunction\n\n\ndef deformable_aggregation_function(\n    feature_maps,\n    spatial_shape,\n    scale_start_index,\n    sampling_location,\n    weights,\n):\n    return DeformableAggregationFunction.apply(\n        feature_maps,\n        spatial_shape,\n        scale_start_index,\n        sampling_location,\n        weights,\n    )\n\n\ndef feature_maps_format(feature_maps, inverse=False):\n    if inverse:\n        col_feats, spatial_shape, scale_start_index = feature_maps\n        num_cams, num_levels = spatial_shape.shape[:2]\n\n        split_size = spatial_shape[..., 0] * spatial_shape[..., 1]\n        split_size = split_size.cpu().numpy().tolist()\n\n        idx = 0\n        cam_split = [1]\n        cam_split_size = [sum(split_size[0])]\n        for i in range(num_cams - 1):\n            if not torch.all(spatial_shape[i] == spatial_shape[i + 1]):\n                cam_split.append(0)\n                cam_split_size.append(0)\n            cam_split[-1] += 1\n            cam_split_size[-1] += sum(split_size[i + 1])\n        mc_feat = [\n            x.unflatten(1, (cam_split[i], -1))\n            for i, x in enumerate(col_feats.split(cam_split_size, dim=1))\n        ]\n\n        spatial_shape = spatial_shape.cpu().numpy().tolist()\n        mc_ms_feat = []\n        shape_index = 0\n        for i, feat in enumerate(mc_feat):\n            feat = list(feat.split(split_size[shape_index], dim=2))\n            for j, f in enumerate(feat):\n                feat[j] = f.unflatten(2, spatial_shape[shape_index][j])\n                feat[j] = feat[j].permute(0, 1, 4, 2, 3)\n            mc_ms_feat.append(feat)\n            shape_index += cam_split[i]\n        return mc_ms_feat\n\n    if isinstance(feature_maps[0], (list, tuple)):\n        formated = [feature_maps_format(x) for x in feature_maps]\n        col_feats = torch.cat([x[0] for x in formated], dim=1)\n        spatial_shape = torch.cat([x[1] for x in formated], dim=0)\n        scale_start_index = torch.cat([x[2] for x in formated], dim=0)\n        return [col_feats, spatial_shape, scale_start_index]\n\n    bs, num_cams = feature_maps[0].shape[:2]\n    spatial_shape = []\n\n    col_feats = []\n    for i, feat in enumerate(feature_maps):\n        spatial_shape.append(feat.shape[-2:])\n        col_feats.append(\n            torch.reshape(feat, (bs, num_cams, feat.shape[2], -1))\n        )\n\n    col_feats = torch.cat(col_feats, dim=-1).permute(0, 1, 3, 2).flatten(1, 2)\n    spatial_shape = [spatial_shape] * num_cams\n    spatial_shape = torch.tensor(\n        spatial_shape,\n        dtype=torch.int64,\n        device=col_feats.device,\n    )\n    scale_start_index = spatial_shape[..., 0] * spatial_shape[..., 1]\n    scale_start_index = scale_start_index.flatten().cumsum(dim=0)\n    scale_start_index = torch.cat(\n        [torch.tensor([0]).to(scale_start_index), scale_start_index[:-1]]\n    )\n    scale_start_index = scale_start_index.reshape(num_cams, -1)\n\n    feature_maps = [\n        col_feats,\n        spatial_shape,\n        scale_start_index,\n    ]\n    return feature_maps\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/ops/deformable_aggregation.py",
    "content": "import torch\nfrom torch.autograd.function import Function, once_differentiable\n\nfrom . import deformable_aggregation_ext\n\n\nclass DeformableAggregationFunction(Function):\n    @staticmethod\n    def forward(\n        ctx,\n        mc_ms_feat,\n        spatial_shape,\n        scale_start_index,\n        sampling_location,\n        weights,\n    ):\n        # output: [bs, num_pts, num_embeds]\n        mc_ms_feat = mc_ms_feat.contiguous().float()\n        spatial_shape = spatial_shape.contiguous().int()\n        scale_start_index = scale_start_index.contiguous().int()\n        sampling_location = sampling_location.contiguous().float()\n        weights = weights.contiguous().float()\n        output = deformable_aggregation_ext.deformable_aggregation_forward(\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n        )\n        ctx.save_for_backward(\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n        )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        (\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n        ) = ctx.saved_tensors\n        mc_ms_feat = mc_ms_feat.contiguous().float()\n        spatial_shape = spatial_shape.contiguous().int()\n        scale_start_index = scale_start_index.contiguous().int()\n        sampling_location = sampling_location.contiguous().float()\n        weights = weights.contiguous().float()\n\n        grad_mc_ms_feat = torch.zeros_like(mc_ms_feat)\n        grad_sampling_location = torch.zeros_like(sampling_location)\n        grad_weights = torch.zeros_like(weights)\n        deformable_aggregation_ext.deformable_aggregation_backward(\n            mc_ms_feat,\n            spatial_shape,\n            scale_start_index,\n            sampling_location,\n            weights,\n            grad_output.contiguous(),\n            grad_mc_ms_feat,\n            grad_sampling_location,\n            grad_weights,\n        )\n        return (\n            grad_mc_ms_feat,\n            None,\n            None,\n            grad_sampling_location,\n            grad_weights,\n        )\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/ops/setup.py",
    "content": "import os\n\nimport torch\nfrom setuptools import setup\nfrom torch.utils.cpp_extension import (\n    BuildExtension,\n    CppExtension,\n    CUDAExtension,\n)\n\n\ndef make_cuda_ext(\n    name,\n    module,\n    sources,\n    sources_cuda=[],\n    extra_args=[],\n    extra_include_path=[],\n):\n\n    define_macros = []\n    extra_compile_args = {\"cxx\": [] + extra_args}\n\n    if torch.cuda.is_available() or os.getenv(\"FORCE_CUDA\", \"0\") == \"1\":\n        define_macros += [(\"WITH_CUDA\", None)]\n        extension = CUDAExtension\n        extra_compile_args[\"nvcc\"] = extra_args + [\n            \"-D__CUDA_NO_HALF_OPERATORS__\",\n            \"-D__CUDA_NO_HALF_CONVERSIONS__\",\n            \"-D__CUDA_NO_HALF2_OPERATORS__\",\n        ]\n        sources += sources_cuda\n    else:\n        print(\"Compiling {} without CUDA\".format(name))\n        extension = CppExtension\n\n    return extension(\n        name=\"{}.{}\".format(module, name),\n        sources=[os.path.join(*module.split(\".\"), p) for p in sources],\n        include_dirs=extra_include_path,\n        define_macros=define_macros,\n        extra_compile_args=extra_compile_args,\n    )\n\n\nif __name__ == \"__main__\":\n    setup(\n        name=\"deformable_aggregation_ext\",\n        ext_modules=[\n            make_cuda_ext(\n                \"deformable_aggregation_ext\",\n                module=\".\",\n                sources=[\n                    f\"src/deformable_aggregation.cpp\",\n                    f\"src/deformable_aggregation_cuda.cu\",\n                ],\n            ),\n        ],\n        cmdclass={\"build_ext\": BuildExtension},\n    )\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/ops/src/deformable_aggregation.cpp",
    "content": "#include <torch/extension.h>\n#include <c10/cuda/CUDAGuard.h>\n\nvoid deformable_aggregation(\n  float* output,\n  const float* mc_ms_feat,\n  const int* spatial_shape,\n  const int* scale_start_index,\n  const float* sample_location,\n  const float* weights,\n  int batch_size,\n  int num_cams,\n  int num_feat,\n  int num_embeds,\n  int num_scale,\n  int num_anchors,\n  int num_pts,\n  int num_groups\n);\n  \n\n/* feat: bs, num_feat, c */\n/* _spatial_shape: cam, scale, 2 */\n/* _scale_start_index: cam, scale */\n/* _sampling_location: bs, anchor, pts, cam, 2 */\n/* _weights: bs, anchor, pts, cam, scale, group */\n/* output: bs, anchor, c */\n/* kernel: bs, anchor, pts, c */\n\n\nat::Tensor deformable_aggregation_forward(\n  const at::Tensor &_mc_ms_feat,\n  const at::Tensor &_spatial_shape,\n  const at::Tensor &_scale_start_index,\n  const at::Tensor &_sampling_location,\n  const at::Tensor &_weights\n) {\n  at::DeviceGuard guard(_mc_ms_feat.device());\n  const at::cuda::OptionalCUDAGuard device_guard(device_of(_mc_ms_feat));\n  int batch_size = _mc_ms_feat.size(0);\n  int num_feat = _mc_ms_feat.size(1);\n  int num_embeds = _mc_ms_feat.size(2);\n  int num_cams = _spatial_shape.size(0);\n  int num_scale = _spatial_shape.size(1);\n  int num_anchors = _sampling_location.size(1);\n  int num_pts = _sampling_location.size(2);\n  int num_groups = _weights.size(5);\n\n  const float* mc_ms_feat = _mc_ms_feat.data_ptr<float>();\n  const int* spatial_shape = _spatial_shape.data_ptr<int>();\n  const int* scale_start_index = _scale_start_index.data_ptr<int>();\n  const float* sampling_location = _sampling_location.data_ptr<float>();\n  const float* weights = _weights.data_ptr<float>();\n\n  auto output = at::zeros({batch_size, num_anchors, num_embeds}, _mc_ms_feat.options());\n  deformable_aggregation(\n    output.data_ptr<float>(),\n    mc_ms_feat, spatial_shape, scale_start_index, sampling_location, weights,\n    batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n  );\n  return output;\n}\n\n\nvoid deformable_aggregation_grad(\n  const float* mc_ms_feat,\n  const int* spatial_shape,\n  const int* scale_start_index,\n  const float* sample_location,\n  const float* weights,\n  const float* grad_output,\n  float* grad_mc_ms_feat,\n  float* grad_sampling_location,\n  float* grad_weights,\n  int batch_size,\n  int num_cams,\n  int num_feat,\n  int num_embeds,\n  int num_scale,\n  int num_anchors,\n  int num_pts,\n  int num_groups\n);\n\n\nvoid deformable_aggregation_backward(\n  const at::Tensor &_mc_ms_feat,\n  const at::Tensor &_spatial_shape,\n  const at::Tensor &_scale_start_index,\n  const at::Tensor &_sampling_location,\n  const at::Tensor &_weights,\n  const at::Tensor &_grad_output,\n  at::Tensor &_grad_mc_ms_feat,\n  at::Tensor &_grad_sampling_location,\n  at::Tensor &_grad_weights\n) {\n  at::DeviceGuard guard(_mc_ms_feat.device());\n  const at::cuda::OptionalCUDAGuard device_guard(device_of(_mc_ms_feat));\n  int batch_size = _mc_ms_feat.size(0);\n  int num_feat = _mc_ms_feat.size(1);\n  int num_embeds = _mc_ms_feat.size(2);\n  int num_cams = _spatial_shape.size(0);\n  int num_scale = _spatial_shape.size(1);\n  int num_anchors = _sampling_location.size(1);\n  int num_pts = _sampling_location.size(2);\n  int num_groups = _weights.size(5);\n\n  const float* mc_ms_feat = _mc_ms_feat.data_ptr<float>();\n  const int* spatial_shape = _spatial_shape.data_ptr<int>();\n  const int* scale_start_index = _scale_start_index.data_ptr<int>();\n  const float* sampling_location = _sampling_location.data_ptr<float>();\n  const float* weights = _weights.data_ptr<float>();\n  const float* grad_output = _grad_output.data_ptr<float>();\n\n  float* grad_mc_ms_feat = _grad_mc_ms_feat.data_ptr<float>();\n  float* grad_sampling_location = _grad_sampling_location.data_ptr<float>();\n  float* grad_weights = _grad_weights.data_ptr<float>();\n\n  deformable_aggregation_grad(\n    mc_ms_feat, spatial_shape, scale_start_index, sampling_location, weights,\n    grad_output, grad_mc_ms_feat, grad_sampling_location, grad_weights,\n    batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n  );\n}\n\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\n    \"deformable_aggregation_forward\",\n    &deformable_aggregation_forward,\n    \"deformable_aggregation_forward\"\n  );\n  m.def(\n    \"deformable_aggregation_backward\",\n    &deformable_aggregation_backward,\n    \"deformable_aggregation_backward\"\n  );\n}\n"
  },
  {
    "path": "open_loop/projects/mmdet3d_plugin/ops/src/deformable_aggregation_cuda.cu",
    "content": "\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n\n#include <THC/THCAtomics.cuh>\n\n#include <iostream>\n#include <stdlib.h>\n\n\n__device__ float bilinear_sampling(\n    const float *&bottom_data, const int &height, const int &width,\n    const int &num_embeds, const float &h_im, const float &w_im,\n    const int &base_ptr\n) {\n  const int h_low = floorf(h_im);\n  const int w_low = floorf(w_im);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const float lh = h_im - h_low;\n  const float lw = w_im - w_low;\n  const float hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = num_embeds;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n\n  float v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n  }\n  float v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n  }\n  float v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n  }\n  float v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n  }\n\n  const float w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  const float val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\n\n__device__ void bilinear_sampling_grad(\n    const float *&bottom_data, const float &weight,\n    const int &height, const int &width,\n    const int &num_embeds, const float &h_im, const float &w_im,\n    const int &base_ptr,\n    const float &grad_output,\n    float *&grad_mc_ms_feat, float *grad_sampling_location, float *grad_weights) {\n  const int h_low = floorf(h_im);\n  const int w_low = floorf(w_im);\n  const int h_high = h_low + 1;\n  const int w_high = w_low + 1;\n\n  const float lh = h_im - h_low;\n  const float lw = w_im - w_low;\n  const float hh = 1 - lh, hw = 1 - lw;\n\n  const int w_stride = num_embeds;\n  const int h_stride = width * w_stride;\n  const int h_low_ptr_offset = h_low * h_stride;\n  const int h_high_ptr_offset = h_low_ptr_offset + h_stride;\n  const int w_low_ptr_offset = w_low * w_stride;\n  const int w_high_ptr_offset = w_low_ptr_offset + w_stride;\n\n  const float w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n  const float top_grad_mc_ms_feat = grad_output * weight;\n  float grad_h_weight = 0, grad_w_weight = 0;\n\n  float v1 = 0;\n  if (h_low >= 0 && w_low >= 0) {\n    const int ptr1 = h_low_ptr_offset + w_low_ptr_offset + base_ptr;\n    v1 = bottom_data[ptr1];\n    grad_h_weight -= hw * v1;\n    grad_w_weight -= hh * v1;\n    atomicAdd(grad_mc_ms_feat + ptr1, w1 * top_grad_mc_ms_feat);\n  }\n  float v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1) {\n    const int ptr2 = h_low_ptr_offset + w_high_ptr_offset + base_ptr;\n    v2 = bottom_data[ptr2];\n    grad_h_weight -= lw * v2;\n    grad_w_weight += hh * v2;\n    atomicAdd(grad_mc_ms_feat + ptr2, w2 * top_grad_mc_ms_feat);\n  }\n  float v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0) {\n    const int ptr3 = h_high_ptr_offset + w_low_ptr_offset + base_ptr;\n    v3 = bottom_data[ptr3];\n    grad_h_weight += hw * v3;\n    grad_w_weight -= lh * v3;\n    atomicAdd(grad_mc_ms_feat + ptr3, w3 * top_grad_mc_ms_feat);\n  }\n  float v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1) {\n    const int ptr4 = h_high_ptr_offset + w_high_ptr_offset + base_ptr;\n    v4 = bottom_data[ptr4];\n    grad_h_weight += lw * v4;\n    grad_w_weight += lh * v4;\n    atomicAdd(grad_mc_ms_feat + ptr4, w4 * top_grad_mc_ms_feat);\n  }\n\n  const float val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  atomicAdd(grad_weights, grad_output * val);\n  atomicAdd(grad_sampling_location, width * grad_w_weight * top_grad_mc_ms_feat);\n  atomicAdd(grad_sampling_location + 1, height * grad_h_weight * top_grad_mc_ms_feat);\n}\n\n\n__global__ void deformable_aggregation_kernel(\n    const int num_kernels,\n    float* output,\n    const float* mc_ms_feat,\n    const int* spatial_shape,\n    const int* scale_start_index,\n    const float* sample_location,\n    const float* weights,\n    int batch_size,\n    int num_cams,\n    int num_feat,\n    int num_embeds,\n    int num_scale,\n    int num_anchors,\n    int num_pts,\n    int num_groups\n) {\n    int idx = blockIdx.x * blockDim.x + threadIdx.x;\n    if (idx >= num_kernels) return;\n\n    const float weight = *(weights + idx / (num_embeds / num_groups));\n    const int channel_index = idx % num_embeds;\n    idx /= num_embeds;\n    const int scale_index = idx % num_scale;\n    idx /= num_scale;\n\n    const int cam_index = idx % num_cams;\n    idx /= num_cams;\n    const int pts_index = idx % num_pts;\n    idx /= num_pts;\n\n    int anchor_index = idx % num_anchors;\n    idx /= num_anchors;\n    const int batch_index = idx % batch_size;\n    idx /= batch_size;\n\n    anchor_index = batch_index * num_anchors + anchor_index;\n    const int loc_offset = ((anchor_index * num_pts + pts_index) * num_cams + cam_index) << 1;\n\n    const float loc_w = sample_location[loc_offset];\n    if (loc_w <= 0 || loc_w >= 1) return;\n    const float loc_h = sample_location[loc_offset + 1];\n    if (loc_h <= 0 || loc_h >= 1) return;\n    \n    int cam_scale_index = cam_index * num_scale + scale_index;\n    const int value_offset = (batch_index * num_feat + scale_start_index[cam_scale_index]) * num_embeds + channel_index;\n\n    cam_scale_index = cam_scale_index << 1;\n    const int h = spatial_shape[cam_scale_index];\n    const int w = spatial_shape[cam_scale_index + 1];\n\n    const float h_im = loc_h * h - 0.5;\n    const float w_im = loc_w * w - 0.5;\n\n    atomicAdd(\n        output + anchor_index * num_embeds + channel_index,\n        bilinear_sampling(mc_ms_feat, h, w, num_embeds, h_im, w_im, value_offset) * weight\n    );\n}\n\n\n__global__ void deformable_aggregation_grad_kernel(\n    const int num_kernels,\n    const float* mc_ms_feat,\n    const int* spatial_shape,\n    const int* scale_start_index,\n    const float* sample_location,\n    const float* weights,\n    const float* grad_output,\n    float* grad_mc_ms_feat,\n    float* grad_sampling_location,\n    float* grad_weights,\n    int batch_size,\n    int num_cams,\n    int num_feat,\n    int num_embeds,\n    int num_scale,\n    int num_anchors,\n    int num_pts,\n    int num_groups\n) {\n    int idx = blockIdx.x * blockDim.x + threadIdx.x;\n    if (idx >= num_kernels) return;\n\n    const int weights_ptr = idx / (num_embeds / num_groups);\n    const int channel_index = idx % num_embeds;\n    idx /= num_embeds;\n    const int scale_index = idx % num_scale;\n    idx /= num_scale;\n\n    const int cam_index = idx % num_cams;\n    idx /= num_cams;\n    const int pts_index = idx % num_pts;\n    idx /= num_pts;\n\n    int anchor_index = idx % num_anchors;\n    idx /= num_anchors;\n    const int batch_index = idx % batch_size;\n    idx /= batch_size;\n\n    anchor_index = batch_index * num_anchors + anchor_index;\n    const int loc_offset = ((anchor_index * num_pts + pts_index) * num_cams + cam_index) << 1;\n\n    const float loc_w = sample_location[loc_offset];\n    if (loc_w <= 0 || loc_w >= 1) return;\n    const float loc_h = sample_location[loc_offset + 1];\n    if (loc_h <= 0 || loc_h >= 1) return;\n    \n    const float grad = grad_output[anchor_index*num_embeds + channel_index];\n\n    int cam_scale_index = cam_index * num_scale + scale_index;\n    const int value_offset = (batch_index * num_feat + scale_start_index[cam_scale_index]) * num_embeds + channel_index;\n\n    cam_scale_index = cam_scale_index << 1;\n    const int h = spatial_shape[cam_scale_index];\n    const int w = spatial_shape[cam_scale_index + 1];\n\n    const float h_im = loc_h * h - 0.5;\n    const float w_im = loc_w * w - 0.5;\n\n    /* atomicAdd( */\n    /*     output + anchor_index * num_embeds + channel_index, */\n    /*     bilinear_sampling(mc_ms_feat, h, w, num_embeds, h_im, w_im, value_offset) * weight */\n    /* ); */\n    const float weight = weights[weights_ptr];\n    float *grad_weights_ptr = grad_weights + weights_ptr;\n    float *grad_location_ptr = grad_sampling_location + loc_offset;\n    bilinear_sampling_grad(\n        mc_ms_feat, weight, h, w, num_embeds, h_im, w_im,\n        value_offset,\n        grad,\n        grad_mc_ms_feat, grad_location_ptr, grad_weights_ptr\n    );\n}\n\n\nvoid deformable_aggregation(\n    float* output,\n    const float* mc_ms_feat,\n    const int* spatial_shape,\n    const int* scale_start_index,\n    const float* sample_location,\n    const float* weights,\n    int batch_size,\n    int num_cams,\n    int num_feat,\n    int num_embeds,\n    int num_scale,\n    int num_anchors,\n    int num_pts,\n    int num_groups\n) {\n    const int num_kernels = batch_size * num_pts * num_embeds * num_anchors * num_cams * num_scale;\n    deformable_aggregation_kernel\n        <<<(int)ceil(((double)num_kernels/128)), 128>>>(\n        num_kernels, output,\n        mc_ms_feat, spatial_shape, scale_start_index, sample_location, weights,\n        batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n    );\n}\n\n\nvoid deformable_aggregation_grad(\n  const float* mc_ms_feat,\n  const int* spatial_shape,\n  const int* scale_start_index,\n  const float* sample_location,\n  const float* weights,\n  const float* grad_output,\n  float* grad_mc_ms_feat,\n  float* grad_sampling_location,\n  float* grad_weights,\n  int batch_size,\n  int num_cams,\n  int num_feat,\n  int num_embeds,\n  int num_scale,\n  int num_anchors,\n  int num_pts,\n  int num_groups\n) {\n    const int num_kernels = batch_size * num_pts * num_embeds * num_anchors * num_cams * num_scale;\n    deformable_aggregation_grad_kernel\n        <<<(int)ceil(((double)num_kernels/128)), 128>>>(\n        num_kernels,\n        mc_ms_feat, spatial_shape, scale_start_index, sample_location, weights,\n        grad_output, grad_mc_ms_feat, grad_sampling_location, grad_weights,\n        batch_size, num_cams, num_feat, num_embeds, num_scale, num_anchors, num_pts, num_groups\n    );\n}\n"
  },
  {
    "path": "open_loop/requirement.txt",
    "content": "numpy==1.23.5\nmmdet==2.28.2\nurllib3==1.26.16\npyquaternion==0.9.9\nnuscenes-devkit==1.1.10\nyapf==0.33.0\ntensorboard==2.14.0\nmotmetrics==1.1.3\npandas==1.1.5\nopencv-python==4.8.1.78\nprettytable==3.7.0\nscikit-learn==1.3.0\n"
  },
  {
    "path": "open_loop/scripts/create_data.sh",
    "content": "export PYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH\n\n# python tools/data_converter/nuscenes_converter.py nuscenes \\\n#     --root-path ./data/nuscenes \\\n#     --canbus ./data/nuscenes \\\n#     --out-dir ./data/infos/ \\\n#     --extra-tag nuscenes \\\n#     --version v1.0-mini\n\n# python tools/data_converter/nuscenes_converter.py nuscenes \\\n#     --root-path ./data/nuscenes \\\n#     --canbus ./data/nuscenes \\\n#     --out-dir ./data/infos/ \\\n#     --extra-tag nuscenes \\\n#     --version v1.0\n\npython tools/data_converter/nuscenes_converter_6s.py nuscenes \\\n    --root-path ./data/nuscenes \\\n    --canbus ./data/nuscenes \\\n    --out-dir ./data/infos/ \\\n    --extra-tag nuscenes \\\n    --version v1.0"
  },
  {
    "path": "open_loop/scripts/kmeans.sh",
    "content": "python tools/kmeans/kmeans_det.py\npython tools/kmeans/kmeans_map.py\npython tools/kmeans/kmeans_motion.py\npython tools/kmeans/kmeans_plan.py"
  },
  {
    "path": "open_loop/scripts/test.sh",
    "content": "CUDA_VISIBLE_DEVICES=0\\ \n   bash ./tools/dist_test.sh \\\n    projects/configs/sparsedrive_small_stage2.py \\\n    work_dirs/sparsedrive_small_stage2/iter_5860.pth \\\n    1 \\\n    --deterministic \\\n    --eval bbox\n    # --result_file ./work_dirs/sparsedrive_small_stage2/results.pkl"
  },
  {
    "path": "open_loop/scripts/test_roboAD.sh",
    "content": "# bash ./tools/dist_test.sh \\\n#     projects/configs/sparsedrive_small_stage2.py \\\n#     ckpt/sparsedrive_stage2.pth \\\n#     8 \\\n#     --deterministic \\\n#     --ev/data/songziying/workspace/SparseDrive/scriptsal bbox\n#     # --result_file ./work_dirs/sparsedrive_small_stage2/results.pkl\nbash ./tools/dist_test.sh \\\n    projects/configs/sparsedrive_small_stage2_roboAD_6s.py \\\n    work_dirs/sparsedrive_small_stage2_roboAD_6s/iter_5860.pth\\\n    1 \\\n    --deterministic \\\n    --eval bbox\n    # --result_file ./work_dirs/sparsedrive_small_stage2_roboAD/results.pkl"
  },
  {
    "path": "open_loop/scripts/train.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py \\\n#    1 \\\n#    --deterministic\n\n# stage2\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2.py \\\n   1 \\\n   --deterministic\n\n"
  },
  {
    "path": "open_loop/scripts/train_6s.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_trainval_1_10_stage1_test.py \\\n#    1 \\\n#    --deterministic\n\n# stage2\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2_6s.py \\\n   8 \\\n   --deterministic\n\n"
  },
  {
    "path": "open_loop/scripts/train_roboAD.sh",
    "content": "## stage1\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_stage1_roboAD.py \\\n#    1 \\\n#    --deterministic\n\n## stage2\n# bash ./tools/dist_train.sh \\\n#    projects/configs/sparsedrive_small_stage2_roboAD.py \\\n#    8 \\\n#    --deterministic\n\nbash ./tools/dist_train.sh \\\n   projects/configs/sparsedrive_small_stage2_roboAD_6s.py \\\n   8 \\\n   --deterministic"
  },
  {
    "path": "open_loop/scripts/visualize.sh",
    "content": "export PYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH\npython tools/visualization/visualize.py \\\n\tprojects/configs/sparsedrive_small_stage2.py \\\n\t--result-path work_dirs/sparsedrive_small_stage2/results.pkl\\\n\t--out-dir vis_long_sparseDrive"
  },
  {
    "path": "open_loop/test.py",
    "content": ""
  },
  {
    "path": "open_loop/tools/benchmark.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport time\nimport torch\nfrom mmcv import Config\nfrom mmcv.parallel import MMDataParallel\nfrom mmcv.runner import load_checkpoint, wrap_fp16_model\nimport sys\nsys.path.append('.')\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.datasets import custom_build_dataset\nfrom mmdet.models import build_detector\nfrom mmcv.cnn.utils.flops_counter import add_flops_counting_methods\nfrom mmcv.parallel import scatter\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description='MMDet benchmark a model')\n    parser.add_argument('config', help='test config file path')\n    parser.add_argument('--checkpoint', default=None, help='checkpoint file')\n    parser.add_argument('--samples', default=1000, help='samples to benchmark')\n    parser.add_argument(\n        '--log-interval', default=50, help='interval of logging')\n    parser.add_argument(\n        '--fuse-conv-bn',\n        action='store_true',\n        help='Whether to fuse conv and bn, this will slightly increase'\n        'the inference speed')\n    args = parser.parse_args()\n    return args\n\n\ndef get_max_memory(model):\n    device = getattr(model, 'output_device', None)\n    mem = torch.cuda.max_memory_allocated(device=device)\n    mem_mb = torch.tensor([mem / (1024 * 1024)],\n        dtype=torch.int,\n        device=device)\n    return mem_mb.item()\n\n\ndef main():\n    args = parse_args()\n    get_flops_params(args)\n    get_mem_fps(args)\n\ndef get_mem_fps(args):\n    cfg = Config.fromfile(args.config)\n    # set cudnn_benchmark\n    if cfg.get('cudnn_benchmark', False):\n        torch.backends.cudnn.benchmark = True\n    cfg.model.pretrained = None\n    cfg.data.test.test_mode = True\n\n    # build the dataloader\n    # TODO: support multiple images per gpu (only minor changes are needed)\n    print(cfg.data.test)\n    dataset = custom_build_dataset(cfg.data.test)\n    data_loader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=cfg.data.workers_per_gpu,\n        dist=False,\n        shuffle=False)\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    # if args.fuse_conv_bn:\n    #     model = fuse_module(model)\n\n    model = MMDataParallel(model, device_ids=[0])\n\n    model.eval()\n\n    # the first several iterations may be very slow so skip them\n    num_warmup = 5\n    pure_inf_time = 0\n\n    # benchmark with several samples and take the average\n    max_memory = 0\n    for i, data in enumerate(data_loader):\n        # torch.cuda.synchronize()\n        with torch.no_grad():\n            start_time = time.perf_counter()\n            model(return_loss=False, rescale=True, **data)\n\n            torch.cuda.synchronize()\n            elapsed = time.perf_counter() - start_time\n            max_memory = max(max_memory, get_max_memory(model))\n\n        if i >= num_warmup:\n            pure_inf_time += elapsed\n            if (i + 1) % args.log_interval == 0:\n                fps = (i + 1 - num_warmup) / pure_inf_time\n                print(f'Done image [{i + 1:<3}/ {args.samples}], '\n                      f'fps: {fps:.1f} img / s, '\n                      f\"gpu mem: {max_memory} M\")\n\n        if (i + 1) == args.samples:\n            pure_inf_time += elapsed\n            fps = (i + 1 - num_warmup) / pure_inf_time\n            print(f'Overall fps: {fps:.1f} img / s')\n            break\n\n\ndef get_flops_params(args):\n    gpu_id = 0\n    cfg = Config.fromfile(args.config)\n    dataset = custom_build_dataset(cfg.data.val)\n    dataloader = build_dataloader(\n        dataset,\n        samples_per_gpu=1,\n        workers_per_gpu=0,\n        dist=False,\n        shuffle=False,\n    )\n    data_iter = dataloader.__iter__()\n    data = next(data_iter)\n    data = scatter(data, [gpu_id])[0]\n\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n    fp16_cfg = cfg.get('fp16', None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    if args.checkpoint is not None:\n        load_checkpoint(model, args.checkpoint, map_location='cpu')\n    model = model.cuda(gpu_id)\n    model.eval()\n\n    bilinear_flops = 11\n    num_key_pts_det = (\n        cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"kps_generator\"][\"num_learnable_pts\"]\n        + len(cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"kps_generator\"][\"fix_scale\"])\n    )\n    deformable_agg_flops_det = (\n        cfg.num_decoder\n        * cfg.embed_dims\n        * cfg.num_levels\n        * cfg.model[\"head\"]['det_head'][\"instance_bank\"][\"num_anchor\"]\n        * cfg.model[\"head\"]['det_head'][\"deformable_model\"][\"num_cams\"]\n        * num_key_pts_det\n        * bilinear_flops\n    )\n    num_key_pts_map = (\n        cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"num_learnable_pts\"]\n        + len(cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"fix_height\"])\n    ) * cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"kps_generator\"][\"num_sample\"]\n    deformable_agg_flops_map = (\n        cfg.num_decoder\n        * cfg.embed_dims\n        * cfg.num_levels\n        * cfg.model[\"head\"]['map_head'][\"instance_bank\"][\"num_anchor\"]\n        * cfg.model[\"head\"]['map_head'][\"deformable_model\"][\"num_cams\"]\n        * num_key_pts_map\n        * bilinear_flops\n    )\n    deformable_agg_flops = deformable_agg_flops_det + deformable_agg_flops_map\n\n    for module in [\"total\", \"img_backbone\", \"img_neck\", \"head\"]:\n        if module != \"total\":\n            flops_model = add_flops_counting_methods(getattr(model, module))\n        else:\n            flops_model = add_flops_counting_methods(model)\n        flops_model.eval()\n        flops_model.start_flops_count()\n        \n        if module == \"img_backbone\":\n            flops_model(data[\"img\"].flatten(0, 1))\n        elif module == \"img_neck\":\n            flops_model(model.img_backbone(data[\"img\"].flatten(0, 1)))\n        elif module == \"head\":\n            flops_model(model.extract_feat(data[\"img\"], metas=data), data)\n        else:\n            flops_model(**data)\n        flops_count, params_count = flops_model.compute_average_flops_cost()\n        flops_count *= flops_model.__batch_counter__\n        flops_model.stop_flops_count()\n        if module == \"head\" or module == \"total\":\n            flops_count += deformable_agg_flops\n        if module == \"total\":\n            total_flops = flops_count\n            total_params = params_count\n        print(\n            f\"{module:<13} complexity: \"\n            f\"FLOPs={flops_count/ 10.**9:>8.4f} G / {flops_count/total_flops*100:>6.2f}%, \"\n            f\"Params={params_count/10**6:>8.4f} M / {params_count/total_params*100:>6.2f}%.\"\n        )\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "open_loop/tools/data_converter/__init__.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\n"
  },
  {
    "path": "open_loop/tools/data_converter/nuscenes_converter.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_test.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "open_loop/tools/data_converter/nuscenes_converter_1_10.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n       \n        import random\n        random.shuffle(train_scenes)\n        train_scenes = train_scenes[:int(len(train_scenes)*0.1)] # 0.2 为 1/5；0.5为 1/2 以此类推\n    \n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n    # import pdb; pdb.set_trace()\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        pass\n        # print('test sample: {}'.format(len(train_nusc_infos)))\n        # data = dict(infos=train_nusc_infos, metadata=metadata)\n        # info_path = osp.join(out_path,\n        #                      '{}_infos_test.pkl'.format(info_prefix))\n        # mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_1_10_train.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        # data['infos'] = val_nusc_infos\n        # info_val_path = osp.join(out_path,\n        #                          '{}_infos_val.pkl'.format(info_prefix))\n        # mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n    # import pdb; pdb.set_trace()\n    predict_helper = PredictHelper(nusc)\n    trainval_samples=[]\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        if sample['scene_token'] in train_scenes:\n            trainval_samples.append(sample)\n    # import pdb; pdb.set_trace()\n    for sample in mmcv.track_iter_progress(trainval_samples):\n        \n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n"
  },
  {
    "path": "open_loop/tools/data_converter/nuscenes_converter_6s.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        print('test sample: {}'.format(len(train_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_test_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n        info_path = osp.join(out_path,\n                             '{}_infos_train_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_path)\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val_6s.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=12):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n        test_version = f'{args.version}-test'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=test_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n    elif args.dataset == 'nuscenes' and args.version == 'v1.0-mini':\n        train_version = f'{args.version}'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)"
  },
  {
    "path": "open_loop/tools/data_converter/nuscenes_converter_hrad_planing_scene.py",
    "content": "import os\nimport math\nimport copy\nimport argparse\nfrom os import path as osp\nfrom collections import OrderedDict\nfrom typing import List, Tuple, Union\n\nimport numpy as np\nfrom pyquaternion import Quaternion\nfrom shapely.geometry import MultiPoint, box\n\nimport mmcv\n\nfrom nuscenes.nuscenes import NuScenes\nfrom nuscenes.can_bus.can_bus_api import NuScenesCanBus\nfrom nuscenes.utils.geometry_utils import transform_matrix\nfrom nuscenes.utils.data_classes import Box\nfrom nuscenes.utils.geometry_utils import view_points\nfrom nuscenes.prediction import PredictHelper, convert_local_coords_to_global\n\nfrom projects.mmdet3d_plugin.datasets.map_utils.nuscmap_extractor import NuscMapExtractor\n\n\n\nNameMapping = {\n    \"movable_object.barrier\": \"barrier\",\n    \"vehicle.bicycle\": \"bicycle\",\n    \"vehicle.bus.bendy\": \"bus\",\n    \"vehicle.bus.rigid\": \"bus\",\n    \"vehicle.car\": \"car\",\n    \"vehicle.construction\": \"construction_vehicle\",\n    \"vehicle.motorcycle\": \"motorcycle\",\n    \"human.pedestrian.adult\": \"pedestrian\",\n    \"human.pedestrian.child\": \"pedestrian\",\n    \"human.pedestrian.construction_worker\": \"pedestrian\",\n    \"human.pedestrian.police_officer\": \"pedestrian\",\n    \"movable_object.trafficcone\": \"traffic_cone\",\n    \"vehicle.trailer\": \"trailer\",\n    \"vehicle.truck\": \"truck\",\n}\n\ndef quart_to_rpy(qua):\n    x, y, z, w = qua\n    roll = math.atan2(2 * (w * x + y * z), 1 - 2 * (x * x + y * y))\n    pitch = math.asin(2 * (w * y - x * z))\n    yaw = math.atan2(2 * (w * z + x * y), 1 - 2 * (z * z + y * y))\n    return roll, pitch, yaw\n\ndef locate_message(utimes, utime):\n    i = np.searchsorted(utimes, utime)\n    if i == len(utimes) or (i > 0 and utime - utimes[i-1] < utimes[i] - utime):\n        i -= 1\n    return i\n\ndef geom2anno(map_geoms):\n    MAP_CLASSES = (\n        'ped_crossing',\n        'divider',\n        'boundary',\n    )\n    vectors = {}\n    for cls, geom_list in map_geoms.items():\n        if cls in MAP_CLASSES:\n            label = MAP_CLASSES.index(cls)\n            vectors[label] = []\n            for geom in geom_list:\n                line = np.array(geom.coords)\n                vectors[label].append(line)\n    return vectors\n\ndef create_nuscenes_infos(root_path,\n                          out_path,\n                          can_bus_root_path,\n                          info_prefix,\n                          version='v1.0-trainval',\n                          max_sweeps=10,\n                          roi_size=(30, 60),):\n    \"\"\"Create info file of nuscene dataset.\n\n    Given the raw data, generate its related info file in pkl format.\n\n    Args:\n        root_path (str): Path of the data root.\n        info_prefix (str): Prefix of the info file to be generated.\n        version (str): Version of the data.\n            Default: 'v1.0-trainval'\n        max_sweeps (int): Max number of sweeps.\n            Default: 10\n    \"\"\"\n    print(version, root_path)\n    nusc = NuScenes(version=version, dataroot=root_path, verbose=True)\n    nusc_map_extractor = NuscMapExtractor(root_path, roi_size)\n    nusc_can_bus = NuScenesCanBus(dataroot=can_bus_root_path)\n    from nuscenes.utils import splits\n    available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']\n    assert version in available_vers\n    if version == 'v1.0-trainval':\n        train_scenes = splits.train\n        import random\n        random.shuffle(train_scenes)\n        train_scenes = train_scenes[:int(len(train_scenes)*0.1)] # 0.2 为 1/5；0.5为 1/2 以此类推\n        # import pdb; pdb.set_trace()\n        val_scenes = splits.val\n        val_scenes = splits.val\n    elif version == 'v1.0-test':\n        train_scenes = splits.test\n        val_scenes = []\n    elif version == 'v1.0-mini':\n        train_scenes = splits.mini_train\n        val_scenes = splits.mini_val\n        out_path = osp.join(out_path, 'mini')\n    else:\n        raise ValueError('unknown')\n    os.makedirs(out_path, exist_ok=True)\n\n    # filter existing scenes.\n    available_scenes = get_available_scenes(nusc)\n    available_scene_names = [s['name'] for s in available_scenes]\n    train_scenes = list(\n        filter(lambda x: x in available_scene_names, train_scenes))\n    \n    val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))\n    # import pdb; pdb.set_trace()\n    train_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in train_scenes\n    ])\n    val_scenes = set([\n        available_scenes[available_scene_names.index(s)]['token']\n        for s in val_scenes\n    ])\n    val_scenes = set(['a178a1b5415f45c08d179bd2cacdf284', 'e005041f659c47e194cd5b18ea6fc346', 'e8099a6136804f3bb9b38ff94d98eb64', 'b789de07180846cc972118ee6d1fb027', '080a52cb8f59489b9cddc7b721808088', 'ed242d80ccb34b139aaf9ab89859332e', '325cef682f064c55a255f2625c533b75', '2f56eb47c64f43df8902d9f88aa8a019', '7210f928860043b5a7e0d3dd4b3e80ff', 'f97bf749746c4c3a8ad9f1c11eab6444', 'cba3ddd5c3664a43b6a08e586e094900', 'd29527ec841045d18d04a933e7a0afd2', 'c4df079d260241ff8015218e29b42ea7', '7052d21b95fc4bae8761b8d9524f3e42', '01e4fcbe6e49483293ce45727152b36e', '19d97841d6f64eba9f6eb9b6e8c257dc', 'fcc020250f884397965ba00c1d9ad9e6'])\n    test = 'test' in version\n    if test:\n        print('test scene: {}'.format(len(train_scenes)))\n    else:\n        print('train scene: {}, val scene: {}'.format(\n            len(train_scenes), len(val_scenes)))\n\n    train_nusc_infos, val_nusc_infos = _fill_trainval_infos(\n        nusc, nusc_map_extractor, nusc_can_bus, train_scenes, val_scenes, test, max_sweeps=max_sweeps)\n\n    metadata = dict(version=version)\n    if test:\n        pass\n    else:\n        print('train sample: {}, val sample: {}'.format(\n            len(train_nusc_infos), len(val_nusc_infos)))\n        data = dict(infos=train_nusc_infos, metadata=metadata)\n\n        data['infos'] = val_nusc_infos\n        info_val_path = osp.join(out_path,\n                                 '{}_infos_val_hrad_planing_scene.pkl'.format(info_prefix))\n        mmcv.dump(data, info_val_path)\n\ndef get_available_scenes(nusc):\n    \"\"\"Get available scenes from the input nuscenes class.\n\n    Given the raw data, get the information of available scenes for\n    further info generation.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n\n    Returns:\n        available_scenes (list[dict]): List of basic information for the\n            available scenes.\n    \"\"\"\n    available_scenes = []\n    print('total scene num: {}'.format(len(nusc.scene)))\n    for scene in nusc.scene:\n        scene_token = scene['token']\n        scene_rec = nusc.get('scene', scene_token)\n        sample_rec = nusc.get('sample', scene_rec['first_sample_token'])\n        sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])\n        has_more_frames = True\n        scene_not_exist = False\n        while has_more_frames:\n            lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])\n            lidar_path = str(lidar_path)\n            if os.getcwd() in lidar_path:\n                # path from lyftdataset is absolute path\n                lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]\n                # relative path\n            if not mmcv.is_filepath(lidar_path):\n                scene_not_exist = True\n                break\n            else:\n                break\n        if scene_not_exist:\n            continue\n        available_scenes.append(scene)\n    print('exist scene num: {}'.format(len(available_scenes)))\n    return available_scenes\n\ndef _fill_trainval_infos(nusc,\n                         nusc_map_extractor,\n                         nusc_can_bus,\n                         train_scenes,\n                         val_scenes,\n                         test=False,\n                         max_sweeps=10,\n                         fut_ts=12,\n                         ego_fut_ts=6):\n    \"\"\"Generate the train/val infos from the raw data.\n\n    Args:\n        nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.\n        train_scenes (list[str]): Basic information of training scenes.\n        val_scenes (list[str]): Basic information of validation scenes.\n        test (bool): Whether use the test mode. In the test mode, no\n            annotations can be accessed. Default: False.\n        max_sweeps (int): Max number of sweeps. Default: 10.\n\n    Returns:\n        tuple[list[dict]]: Information of training set and validation set\n            that will be saved to the info file.\n    \"\"\"\n    train_nusc_infos = []\n    val_nusc_infos = []\n    cat2idx = {}\n    for idx, dic in enumerate(nusc.category):\n        cat2idx[dic['name']] = idx\n\n    predict_helper = PredictHelper(nusc)\n    trainval_samples=[]\n    for sample in mmcv.track_iter_progress(nusc.sample):\n        if sample['scene_token'] in val_scenes :\n            trainval_samples.append(sample)\n    # import pdb; pdb.set_trace()\n    for sample in mmcv.track_iter_progress(trainval_samples):\n        map_location = nusc.get('log', nusc.get('scene', sample['scene_token'])['log_token'])['location']\n        lidar_token = sample['data']['LIDAR_TOP']\n        sd_rec = nusc.get('sample_data', lidar_token)\n        cs_record = nusc.get('calibrated_sensor',\n                             sd_rec['calibrated_sensor_token'])\n        pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n        lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)\n        mmcv.check_file_exist(lidar_path)\n\n        info = {\n            'lidar_path': lidar_path,\n            'token': sample['token'],\n            'sweeps': [],\n            'cams': dict(),\n            'scene_token': sample['scene_token'],\n            'lidar2ego_translation': cs_record['translation'],\n            'lidar2ego_rotation': cs_record['rotation'],\n            'ego2global_translation': pose_record['translation'],\n            'ego2global_rotation': pose_record['rotation'],\n            'timestamp': sample['timestamp'],\n            'map_location': map_location,\n        }\n\n        l2e_r = info['lidar2ego_rotation']\n        l2e_t = info['lidar2ego_translation']\n        e2g_r = info['ego2global_rotation']\n        e2g_t = info['ego2global_translation']\n        l2e_r_mat = Quaternion(l2e_r).rotation_matrix\n        e2g_r_mat = Quaternion(e2g_r).rotation_matrix\n\n        # extract map annos\n        lidar2ego = np.eye(4)\n        lidar2ego[:3, :3] = Quaternion(\n            info[\"lidar2ego_rotation\"]\n        ).rotation_matrix\n        lidar2ego[:3, 3] = np.array(info[\"lidar2ego_translation\"])\n        ego2global = np.eye(4)\n        ego2global[:3, :3] = Quaternion(\n            info[\"ego2global_rotation\"]\n        ).rotation_matrix\n        ego2global[:3, 3] = np.array(info[\"ego2global_translation\"])\n        lidar2global = ego2global @ lidar2ego\n\n        translation = list(lidar2global[:3, 3])\n        rotation = list(Quaternion(matrix=lidar2global).q)\n        map_geoms = nusc_map_extractor.get_map_geom(map_location, translation, rotation)\n        map_annos = geom2anno(map_geoms)\n        info['map_annos'] = map_annos\n\n        # obtain 6 image's information per frame\n        camera_types = [\n            'CAM_FRONT',\n            'CAM_FRONT_RIGHT',\n            'CAM_FRONT_LEFT',\n            'CAM_BACK',\n            'CAM_BACK_LEFT',\n            'CAM_BACK_RIGHT',\n        ]\n        for cam in camera_types:\n            cam_token = sample['data'][cam]\n            cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)\n            cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,\n                                         e2g_t, e2g_r_mat, cam)\n            cam_info.update(cam_intrinsic=cam_intrinsic)\n            info['cams'].update({cam: cam_info})\n\n        # obtain sweeps for a single key-frame\n        sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])\n        sweeps = []\n        while len(sweeps) < max_sweeps:\n            if not sd_rec['prev'] == '':\n                sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,\n                                          l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')\n                sweeps.append(sweep)\n                sd_rec = nusc.get('sample_data', sd_rec['prev'])\n            else:\n                break\n        info['sweeps'] = sweeps\n        # obtain annotation\n        if not test:\n            # object detection annos: boxes (locs, dims, yaw, velocity), names and valid flags\n            annotations = [\n                nusc.get('sample_annotation', token)\n                for token in sample['anns']\n            ]\n            locs = np.array([b.center for b in boxes]).reshape(-1, 3)\n            dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)\n            rots = np.array([b.orientation.yaw_pitch_roll[0]\n                             for b in boxes]).reshape(-1, 1)\n            velocity = np.array(\n                [nusc.box_velocity(token)[:2] for token in sample['anns']])\n            # convert velo from global to lidar\n            for i in range(len(boxes)):\n                velo = np.array([*velocity[i], 0.0])\n                velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(\n                    l2e_r_mat).T\n                velocity[i] = velo[:2]\n            names = [b.name for b in boxes]\n            for i in range(len(names)):\n                if names[i] in NameMapping:\n                    names[i] = NameMapping[names[i]]\n            names = np.array(names)\n            valid_flag = np.array(\n                [(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0\n                 for anno in annotations],\n                dtype=bool).reshape(-1)  ## TODO update valid flag for tracking\n            # we need to convert box size to\n            # the format of our lidar coordinate system\n            # which is x_size, y_size, z_size (corresponding to l, w, h)\n            gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)\n            assert len(gt_boxes) == len(\n                annotations), f'{len(gt_boxes)}, {len(annotations)}'\n            \n            # object tracking annos: instance_ids\n            instance_inds = [nusc.getind('instance', anno['instance_token'])\n                             for anno in annotations]\n\n            # motion prediction annos: future trajectories offset in lidar frame and valid mask\n            num_box = len(boxes)\n            gt_fut_trajs = np.zeros((num_box, fut_ts, 2))\n            gt_fut_masks = np.zeros((num_box, fut_ts))\n            for i, anno in enumerate(annotations):\n                instance_token = anno['instance_token']\n                fut_traj_local = predict_helper.get_future_for_agent(\n                    instance_token, \n                    sample['token'], \n                    seconds=fut_ts/2, \n                    in_agent_frame=True\n                )\n                if fut_traj_local.shape[0] > 0:\n                    box = boxes[i]\n                    trans = box.center\n                    rot = Quaternion(matrix=box.rotation_matrix)\n                    fut_traj_scene = convert_local_coords_to_global(fut_traj_local, trans, rot)\n                    valid_step = fut_traj_scene.shape[0]\n                    gt_fut_trajs[i, 0] = fut_traj_scene[0] - box.center[:2]\n                    gt_fut_trajs[i, 1:valid_step] = fut_traj_scene[1:] - fut_traj_scene[:-1]\n                    gt_fut_masks[i, :valid_step] = 1\n\n            # motion planning annos: future trajectories offset in lidar frame and valid mask\n            ego_fut_trajs = np.zeros((ego_fut_ts + 1, 3))\n            ego_fut_masks = np.zeros((ego_fut_ts + 1))\n            sample_cur = sample\n            ego_status = get_ego_status(nusc, nusc_can_bus, sample_cur)\n            for i in range(ego_fut_ts + 1):\n                pose_mat = get_global_sensor_pose(sample_cur, nusc)\n                ego_fut_trajs[i] = pose_mat[:3, 3]\n                ego_fut_masks[i] = 1\n                if sample_cur['next'] == '':\n                    ego_fut_trajs[i+1:] = ego_fut_trajs[i]\n                    break\n                else:\n                    sample_cur = nusc.get('sample', sample_cur['next'])\n            # global to ego\n            ego_fut_trajs = ego_fut_trajs - np.array(pose_record['translation'])\n            rot_mat = Quaternion(pose_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # ego to lidar\n            ego_fut_trajs = ego_fut_trajs - np.array(cs_record['translation'])\n            rot_mat = Quaternion(cs_record['rotation']).inverse.rotation_matrix\n            ego_fut_trajs = np.dot(rot_mat, ego_fut_trajs.T).T\n            # drive command according to final fut step offset\n            if ego_fut_trajs[-1][0] >= 2:\n                command = np.array([1, 0, 0])  # Turn Right\n            elif ego_fut_trajs[-1][0] <= -2:\n                command = np.array([0, 1, 0])  # Turn Left\n            else:\n                command = np.array([0, 0, 1])  # Go Straight\n            # get offset\n            ego_fut_trajs = ego_fut_trajs[1:] - ego_fut_trajs[:-1]      \n\n            info['gt_boxes'] = gt_boxes\n            info['gt_names'] = names\n            info['gt_velocity'] = velocity.reshape(-1, 2)\n            info['num_lidar_pts'] = np.array(\n                [a['num_lidar_pts'] for a in annotations])\n            info['num_radar_pts'] = np.array(\n                [a['num_radar_pts'] for a in annotations])\n            info['valid_flag'] = valid_flag\n            info['instance_inds'] = instance_inds\n            info['gt_agent_fut_trajs'] = gt_fut_trajs.astype(np.float32)\n            info['gt_agent_fut_masks'] = gt_fut_masks.astype(np.float32)\n            info['gt_ego_fut_trajs'] = ego_fut_trajs[:, :2].astype(np.float32)\n            info['gt_ego_fut_masks'] = ego_fut_masks[1:].astype(np.float32)\n            info['gt_ego_fut_cmd'] = command.astype(np.float32)\n            info['ego_status'] = ego_status\n\n        if sample['scene_token'] in train_scenes:\n            train_nusc_infos.append(info)\n        else:\n            val_nusc_infos.append(info)\n\n    return train_nusc_infos, val_nusc_infos\n\ndef get_ego_status(nusc, nusc_can_bus, sample):\n    ego_status = []\n    ref_scene = nusc.get(\"scene\", sample['scene_token'])\n    try:\n        pose_msgs = nusc_can_bus.get_messages(ref_scene['name'],'pose')\n        steer_msgs = nusc_can_bus.get_messages(ref_scene['name'], 'steeranglefeedback')\n        pose_uts = [msg['utime'] for msg in pose_msgs]\n        steer_uts = [msg['utime'] for msg in steer_msgs]\n        ref_utime = sample['timestamp']\n        pose_index = locate_message(pose_uts, ref_utime)\n        pose_data = pose_msgs[pose_index]\n        steer_index = locate_message(steer_uts, ref_utime)\n        steer_data = steer_msgs[steer_index]\n        ego_status.extend(pose_data[\"accel\"]) # acceleration in ego vehicle frame, m/s/s\n        ego_status.extend(pose_data[\"rotation_rate\"]) # angular velocity in ego vehicle frame, rad/s\n        ego_status.extend(pose_data[\"vel\"]) # velocity in ego vehicle frame, m/s\n        ego_status.append(steer_data[\"value\"]) # steering angle, positive: left turn, negative: right turn\n    except:\n        ego_status = [0] * 10\n    \n    return np.array(ego_status).astype(np.float32)\n\ndef get_global_sensor_pose(rec, nusc):\n    lidar_sample_data = nusc.get('sample_data', rec['data']['LIDAR_TOP'])\n\n    pose_record = nusc.get(\"ego_pose\", lidar_sample_data[\"ego_pose_token\"])\n    cs_record = nusc.get(\"calibrated_sensor\", lidar_sample_data[\"calibrated_sensor_token\"])\n\n    ego2global = transform_matrix(pose_record[\"translation\"], Quaternion(pose_record[\"rotation\"]), inverse=False)\n    sensor2ego = transform_matrix(cs_record[\"translation\"], Quaternion(cs_record[\"rotation\"]), inverse=False)\n    pose = ego2global.dot(sensor2ego)\n\n    return pose\n\ndef obtain_sensor2top(nusc,\n                      sensor_token,\n                      l2e_t,\n                      l2e_r_mat,\n                      e2g_t,\n                      e2g_r_mat,\n                      sensor_type='lidar'):\n    \"\"\"Obtain the info with RT matric from general sensor to Top LiDAR.\n\n    Args:\n        nusc (class): Dataset class in the nuScenes dataset.\n        sensor_token (str): Sample data token corresponding to the\n            specific sensor type.\n        l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).\n        l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego\n            in shape (3, 3).\n        e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).\n        e2g_r_mat (np.ndarray): Rotation matrix from ego to global\n            in shape (3, 3).\n        sensor_type (str): Sensor to calibrate. Default: 'lidar'.\n\n    Returns:\n        sweep (dict): Sweep information after transformation.\n    \"\"\"\n    sd_rec = nusc.get('sample_data', sensor_token)\n    cs_record = nusc.get('calibrated_sensor',\n                         sd_rec['calibrated_sensor_token'])\n    pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])\n    data_path = str(nusc.get_sample_data_path(sd_rec['token']))\n    if os.getcwd() in data_path:  # path from lyftdataset is absolute path\n        data_path = data_path.split(f'{os.getcwd()}/')[-1]  # relative path\n    sweep = {\n        'data_path': data_path,\n        'type': sensor_type,\n        'sample_data_token': sd_rec['token'],\n        'sensor2ego_translation': cs_record['translation'],\n        'sensor2ego_rotation': cs_record['rotation'],\n        'ego2global_translation': pose_record['translation'],\n        'ego2global_rotation': pose_record['rotation'],\n        'timestamp': sd_rec['timestamp']\n    }\n\n    l2e_r_s = sweep['sensor2ego_rotation']\n    l2e_t_s = sweep['sensor2ego_translation']\n    e2g_r_s = sweep['ego2global_rotation']\n    e2g_t_s = sweep['ego2global_translation']\n\n    # obtain the RT from sensor to Top LiDAR\n    # sweep->ego->global->ego'->lidar\n    l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix\n    e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix\n    R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (\n        np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)\n    T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T\n                  ) + l2e_t @ np.linalg.inv(l2e_r_mat).T\n    sweep['sensor2lidar_rotation'] = R.T  # points @ R.T + T\n    sweep['sensor2lidar_translation'] = T\n    return sweep\n\ndef nuscenes_data_prep(root_path,\n                       can_bus_root_path,\n                       info_prefix,\n                       version,\n                       dataset_name,\n                       out_dir,\n                       max_sweeps=10):\n    \"\"\"Prepare data related to nuScenes dataset.\n\n    Related data consists of '.pkl' files recording basic infos,\n    2D annotations and groundtruth database.\n\n    Args:\n        root_path (str): Path of dataset root.\n        info_prefix (str): The prefix of info filenames.\n        version (str): Dataset version.\n        dataset_name (str): The dataset class name.\n        out_dir (str): Output directory of the groundtruth database info.\n        max_sweeps (int): Number of input consecutive frames. Default: 10\n    \"\"\"\n    create_nuscenes_infos(\n        root_path, out_dir, can_bus_root_path, info_prefix, version=version, max_sweeps=max_sweeps)\n\n\nparser = argparse.ArgumentParser(description='Data converter arg parser')\nparser.add_argument('dataset', metavar='kitti', help='name of the dataset')\nparser.add_argument(\n    '--root-path',\n    type=str,\n    default='./data/kitti',\n    help='specify the root path of dataset')\nparser.add_argument(\n    '--canbus',\n    type=str,\n    default='./data',\n    help='specify the root path of nuScenes canbus')\nparser.add_argument(\n    '--version',\n    type=str,\n    default='v1.0',\n    required=False,\n    help='specify the dataset version, no need for kitti')\nparser.add_argument(\n    '--max-sweeps',\n    type=int,\n    default=10,\n    required=False,\n    help='specify sweeps of lidar per example')\nparser.add_argument(\n    '--out-dir',\n    type=str,\n    default='./data/kitti',\n    required='False',\n    help='name of info pkl')\nparser.add_argument('--extra-tag', type=str, default='kitti')\nparser.add_argument(\n    '--workers', type=int, default=4, help='number of threads to be used')\nargs = parser.parse_args()\n\nif __name__ == '__main__':\n    if args.dataset == 'nuscenes' and args.version != 'v1.0-mini':\n        train_version = f'{args.version}-trainval'\n        nuscenes_data_prep(\n            root_path=args.root_path,\n            can_bus_root_path=args.canbus,\n            info_prefix=args.extra_tag,\n            version=train_version,\n            dataset_name='NuScenesDataset',\n            out_dir=args.out_dir,\n            max_sweeps=args.max_sweeps)\n\n\n"
  },
  {
    "path": "open_loop/tools/dist_test.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nPORT=${PORT:-29611}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython3 -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/test.py $CONFIG $CHECKPOINT --launcher pytorch ${@:4}\n"
  },
  {
    "path": "open_loop/tools/dist_train.sh",
    "content": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nPORT=${PORT:-28651}\n\nPYTHONPATH=\"$(dirname $0)/..\":$PYTHONPATH \\\npython3 -m torch.distributed.launch --nproc_per_node=$GPUS --master_port=$PORT \\\n    $(dirname \"$0\")/train.py $CONFIG --launcher pytorch ${@:3}\n"
  },
  {
    "path": "open_loop/tools/fuse_conv_bn.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\n\nimport torch\nfrom mmcv.runner import save_checkpoint\nfrom torch import nn as nn\n\nfrom mmdet3d.apis import init_model\n\n\ndef fuse_conv_bn(conv, bn):\n    \"\"\"During inference, the functionary of batch norm layers is turned off but\n    only the mean and var alone channels are used, which exposes the chance to\n    fuse it with the preceding conv layers to save computations and simplify\n    network structures.\"\"\"\n    conv_w = conv.weight\n    conv_b = conv.bias if conv.bias is not None else torch.zeros_like(\n        bn.running_mean)\n\n    factor = bn.weight / torch.sqrt(bn.running_var + bn.eps)\n    conv.weight = nn.Parameter(conv_w *\n                               factor.reshape([conv.out_channels, 1, 1, 1]))\n    conv.bias = nn.Parameter((conv_b - bn.running_mean) * factor + bn.bias)\n    return conv\n\n\ndef fuse_module(m):\n    last_conv = None\n    last_conv_name = None\n\n    for name, child in m.named_children():\n        if isinstance(child, (nn.BatchNorm2d, nn.SyncBatchNorm)):\n            if last_conv is None:  # only fuse BN that is after Conv\n                continue\n            fused_conv = fuse_conv_bn(last_conv, child)\n            m._modules[last_conv_name] = fused_conv\n            # To reduce changes, set BN as Identity instead of deleting it.\n            m._modules[name] = nn.Identity()\n            last_conv = None\n        elif isinstance(child, nn.Conv2d):\n            last_conv = child\n            last_conv_name = name\n        else:\n            fuse_module(child)\n    return m\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='fuse Conv and BN layers in a model')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument('checkpoint', help='checkpoint file path')\n    parser.add_argument('out', help='output path of the converted model')\n    args = parser.parse_args()\n    return args\n\n\ndef main():\n    args = parse_args()\n    # build the model from a config file and a checkpoint file\n    model = init_model(args.config, args.checkpoint)\n    # fuse conv and bn layers of the model\n    fused_model = fuse_module(model)\n    save_checkpoint(fused_model, args.out)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "open_loop/tools/kmeans/kmeans_det.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nos.makedirs('data/kmeans', exist_ok=True)\nos.makedirs('vis/kmeans', exist_ok=True)\n\nK = 900\nDIS_THRESH = 55\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\ncenter = []\nfor idx in tqdm(range(len(data_infos))):\n    boxes = data_infos[idx]['gt_boxes'][:,:3]\n    if len(boxes) == 0:\n        continue\n    distance = np.linalg.norm(boxes[:, :2], axis=1)\n    center.append(boxes[distance < DIS_THRESH])\ncenter = np.concatenate(center, axis=0)\nprint(\"start clustering, may take a few minutes.\")\ncluster = KMeans(n_clusters=K).fit(center).cluster_centers_\nplt.scatter(cluster[:,0], cluster[:,1])\nplt.savefig(f'vis/kmeans/det_anchor_{K}', bbox_inches='tight')\nothers = np.array([1,1,1,1,0,0,0,0])[np.newaxis].repeat(K, axis=0)\ncluster = np.concatenate([cluster, others], axis=1)\nnp.save(f'data/kmeans/kmeans_det_{K}.npy', cluster)"
  },
  {
    "path": "open_loop/tools/kmeans/kmeans_map.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nK = 100\nnum_sample = 20\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\ncenter = []\nfor idx in tqdm(range(len(data_infos))):\n    for cls, geoms in data_infos[idx][\"map_annos\"].items():\n        for geom in geoms:  \n            center.append(geom.mean(axis=0))\ncenter = np.stack(center, axis=0)\ncenter = KMeans(n_clusters=K).fit(center).cluster_centers_\ndelta_y = np.linspace(-4, 4, num_sample)\ndelta_x = np.zeros([num_sample])\ndelta = np.stack([delta_x, delta_y], axis=-1)\nvecs = center[:, np.newaxis] + delta[np.newaxis]\n\nfor i in range(K):\n    x = vecs[i, :, 0]\n    y = vecs[i, :, 1]\n    plt.plot(x, y, linewidth=1, marker='o', linestyle='-', markersize=2)\nplt.savefig(f'vis/kmeans/map_anchor_{K}', bbox_inches='tight')\nnp.save(f'data/kmeans/kmeans_map_{K}.npy', vecs)"
  },
  {
    "path": "open_loop/tools/kmeans/kmeans_motion.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nCLASSES = [\n    \"car\",\n    \"truck\",\n    \"construction_vehicle\",\n    \"bus\",\n    \"trailer\",\n    \"barrier\",\n    \"motorcycle\",\n    \"bicycle\",\n    \"pedestrian\",\n    \"traffic_cone\",\n]\n\ndef lidar2agent(trajs_offset, boxes):\n    origin = np.zeros((trajs_offset.shape[0], 1, 2), dtype=np.float32)\n    trajs_offset = np.concatenate([origin, trajs_offset], axis=1)\n    trajs = trajs_offset.cumsum(axis=1)\n    yaws = - boxes[:, 6]\n    rot_sin = np.sin(yaws)\n    rot_cos = np.cos(yaws)\n    rot_mat_T = np.stack(\n        [\n            np.stack([rot_cos, rot_sin]),\n            np.stack([-rot_sin, rot_cos]),\n        ]\n    )\n    trajs_new = np.einsum('aij,jka->aik', trajs, rot_mat_T)\n    trajs_new = trajs_new[:, 1:]\n    return trajs_new\n\nK = 6\nDIS_THRESH = 55\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\ndata_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\nintention = dict()\nfor i in range(len(CLASSES)):\n    intention[i] = []\nfor idx in tqdm(range(len(data_infos))):\n    info = data_infos[idx]\n    boxes = info['gt_boxes']\n    names = info['gt_names']\n    fut_masks = info['gt_agent_fut_masks']\n    trajs = info['gt_agent_fut_trajs']\n    velos = info['gt_velocity']\n    labels = []\n    for cat in names:\n        if cat in CLASSES:\n            labels.append(CLASSES.index(cat))\n        else:\n            labels.append(-1)\n    labels = np.array(labels)\n    if len(boxes) == 0:\n        continue    \n    for i in range(len(CLASSES)):\n        cls_mask = (labels == i)\n        box_cls = boxes[cls_mask]\n        fut_masks_cls = fut_masks[cls_mask]\n        trajs_cls = trajs[cls_mask]\n        velos_cls = velos[cls_mask]\n\n        distance = np.linalg.norm(box_cls[:, :2], axis=1)\n        mask = np.logical_and(\n            fut_masks_cls.sum(axis=1) == 12,\n            distance < DIS_THRESH,\n        )\n        trajs_cls = trajs_cls[mask]\n        box_cls = box_cls[mask]\n        velos_cls = velos_cls[mask]\n\n        trajs_agent = lidar2agent(trajs_cls, box_cls)\n        if trajs_agent.shape[0] == 0:\n            continue\n        intention[i].append(trajs_agent)\n\nclusters = []\nfor i in range(len(CLASSES)):\n    import pdb;pdb.set_trace()\n    intention_cls = np.concatenate(intention[i], axis=0).reshape(-1, 24)\n    if intention_cls.shape[0] < K:\n        continue\n    cluster = KMeans(n_clusters=K).fit(intention_cls).cluster_centers_\n    cluster = cluster.reshape(-1, 12, 2)\n    clusters.append(cluster)\n    for j in range(K):\n        plt.scatter(cluster[j, :, 0], cluster[j, :,1])\n    plt.savefig(f'vis/kmeans/motion_intention_{CLASSES[i]}_{K}', bbox_inches='tight')\n    plt.close()\n\nclusters = np.stack(clusters, axis=0)\nnp.save(f'data/kmeans/kmeans_motion_{K}.npy', clusters)"
  },
  {
    "path": "open_loop/tools/kmeans/kmeans_plan.py",
    "content": "import os\nimport pickle\nfrom tqdm import tqdm\n\nimport numpy as np\nimport matplotlib.pyplot as plt\nfrom sklearn.cluster import KMeans\n\nimport mmcv\n\nK = 6\n\nfp = 'data/infos/nuscenes_infos_train.pkl'\ndata = mmcv.load(fp)\n#data_infos = list(sorted(data[\"infos\"], key=lambda e: e[\"timestamp\"]))\ndata_infos = list(data[\"infos\"])\nimport pdb;pdb.set_trace()\nnavi_trajs = [[], [], []]\nfor idx in tqdm(range(len(data_infos))):\n    info = data_infos[idx]\n    plan_traj = info['gt_ego_fut_trajs'].cumsum(axis=-2)\n    plan_mask = info['gt_ego_fut_masks']\n    cmd = info['gt_ego_fut_cmd'].astype(np.int32)\n    cmd = cmd.argmax(axis=-1)\n    if not plan_mask.sum() == 6:\n        continue\n    navi_trajs[cmd].append(plan_traj)\n\nclusters = []\nfor trajs in navi_trajs:\n    trajs = np.concatenate(trajs, axis=0).reshape(-1, 12)\n    cluster = KMeans(n_clusters=K).fit(trajs).cluster_centers_\n    cluster = cluster.reshape(-1, 6, 2)\n    clusters.append(cluster)\n    for j in range(K):\n        plt.scatter(cluster[j, :, 0], cluster[j, :,1])\nplt.savefig(f'vis/kmeans/plan_{K}', bbox_inches='tight')\nplt.close()\n\nclusters = np.stack(clusters, axis=0)\nnp.save(f'data/kmeans/kmeans_plan_{K}.npy', clusters)"
  },
  {
    "path": "open_loop/tools/test.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nimport mmcv\nimport os\nfrom os import path as osp\n\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.cnn import fuse_conv_bn\nfrom mmcv.parallel import MMDataParallel, MMDistributedDataParallel\nfrom mmcv.runner import (\n    get_dist_info,\n    init_dist,\n    load_checkpoint,\n    wrap_fp16_model,\n)\n\nfrom mmdet.apis import single_gpu_test, multi_gpu_test, set_random_seed\nfrom mmdet.datasets import replace_ImageToTensor, build_dataset\nfrom mmdet.datasets import build_dataloader as build_dataloader_origin\nfrom mmdet.models import build_detector\n\nfrom projects.mmdet3d_plugin.datasets.builder import build_dataloader\nfrom projects.mmdet3d_plugin.apis.test import custom_multi_gpu_test\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description=\"MMDet test (and eval) a model\"\n    )\n    parser.add_argument(\"config\", help=\"test config file path\")\n    parser.add_argument(\"checkpoint\", help=\"checkpoint file\")\n    parser.add_argument(\"--out\", help=\"output result file in pickle format\")\n    parser.add_argument(\n        \"--fuse-conv-bn\",\n        action=\"store_true\",\n        help=\"Whether to fuse conv and bn, this will slightly increase\"\n        \"the inference speed\",\n    )\n    parser.add_argument(\n        \"--format-only\",\n        action=\"store_true\",\n        help=\"Format the output results without perform evaluation. It is\"\n        \"useful when you want to format the result to a specific format and \"\n        \"submit it to the test server\",\n    )\n    parser.add_argument(\n        \"--eval\",\n        type=str,\n        nargs=\"+\",\n        help='evaluation metrics, which depends on the dataset, e.g., \"bbox\",'\n        ' \"segm\", \"proposal\" for COCO, and \"mAP\", \"recall\" for PASCAL VOC',\n    )\n    parser.add_argument(\"--show\", action=\"store_true\", help=\"show results\")\n    parser.add_argument(\n        \"--show-dir\", help=\"directory where results will be saved\"\n    )\n    parser.add_argument(\n        \"--gpu-collect\",\n        action=\"store_true\",\n        help=\"whether to use gpu to collect results.\",\n    )\n    parser.add_argument(\n        \"--tmpdir\",\n        help=\"tmp directory used for collecting results from multiple \"\n        \"workers, available when gpu-collect is not specified\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"custom options for evaluation, the key-value pair in xxx=yyy \"\n        \"format will be kwargs for dataset.evaluate() function (deprecate), \"\n        \"change to --eval-options instead.\",\n    )\n    parser.add_argument(\n        \"--eval-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"custom options for evaluation, the key-value pair in xxx=yyy \"\n        \"format will be kwargs for dataset.evaluate() function\",\n    )\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\"--result_file\", type=str, default=None)\n    parser.add_argument(\"--show_only\", action=\"store_true\")\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.eval_options:\n        raise ValueError(\n            \"--options and --eval-options cannot be both specified, \"\n            \"--options is deprecated in favor of --eval-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --eval-options\")\n        args.eval_options = args.options\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    assert (\n        args.out or args.eval or args.format_only or args.show or args.show_dir\n    ), (\n        \"Please specify at least one operation (save/eval/format/show the \"\n        'results / save the results) with the argument \"--out\", \"--eval\"'\n        ', \"--format-only\", \"--show\" or \"--show-dir\"'\n    )\n\n    if args.eval and args.format_only:\n        raise ValueError(\"--eval and --format_only cannot be both specified\")\n\n    if args.out is not None and not args.out.endswith((\".pkl\", \".pickle\")):\n        raise ValueError(\"The output file must be a pkl file.\")\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    cfg.model.pretrained = None\n    # in case the test dataset is concatenated\n    samples_per_gpu = 1\n    if isinstance(cfg.data.test, dict):\n        cfg.data.test.test_mode = True\n        samples_per_gpu = cfg.data.test.pop(\"samples_per_gpu\", 1)\n        if samples_per_gpu > 1:\n            # Replace 'ImageToTensor' to 'DefaultFormatBundle'\n            cfg.data.test.pipeline = replace_ImageToTensor(\n                cfg.data.test.pipeline\n            )\n    elif isinstance(cfg.data.test, list):\n        for ds_cfg in cfg.data.test:\n            ds_cfg.test_mode = True\n        samples_per_gpu = max(\n            [ds_cfg.pop(\"samples_per_gpu\", 1) for ds_cfg in cfg.data.test]\n        )\n        if samples_per_gpu > 1:\n            for ds_cfg in cfg.data.test:\n                ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    else:\n        distributed = True\n        init_dist(args.launcher, **cfg.dist_params)\n\n    # set random seeds\n    if args.seed is not None:\n        set_random_seed(args.seed, deterministic=args.deterministic)\n\n    # set work dir\n    if cfg.get('work_dir', None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join('./work_dirs',\n                                osp.splitext(osp.basename(args.config))[0]) \n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    cfg.data.test.work_dir = cfg.work_dir\n    print('work_dir: ',cfg.work_dir)\n\n\n    # build the dataloader\n    dataset = build_dataset(cfg.data.test)\n    import pdb;\n    if distributed:\n        data_loader = build_dataloader(\n            dataset,\n            samples_per_gpu=samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n            nonshuffler_sampler=dict(type=\"DistributedSampler\"),\n        )\n    else:\n        data_loader = build_dataloader_origin(\n            dataset,\n            samples_per_gpu=samples_per_gpu,\n            workers_per_gpu=cfg.data.workers_per_gpu,\n            dist=distributed,\n            shuffle=False,\n        )\n\n    # build the model and load checkpoint\n    cfg.model.train_cfg = None\n    model = build_detector(cfg.model, test_cfg=cfg.get(\"test_cfg\"))\n    # model = build_model(cfg.model, test_cfg=cfg.get(\"test_cfg\"))\n    fp16_cfg = cfg.get(\"fp16\", None)\n    if fp16_cfg is not None:\n        wrap_fp16_model(model)\n    checkpoint = load_checkpoint(model, args.checkpoint, map_location=\"cpu\")\n    if args.fuse_conv_bn:\n        model = fuse_conv_bn(model)\n    # old versions did not save class info in checkpoints, this walkaround is\n    # for backward compatibility\n    if \"CLASSES\" in checkpoint.get(\"meta\", {}):\n        model.CLASSES = checkpoint[\"meta\"][\"CLASSES\"]\n    else:\n        model.CLASSES = dataset.CLASSES\n    # palette for visualization in segmentation tasks\n    if \"PALETTE\" in checkpoint.get(\"meta\", {}):\n        model.PALETTE = checkpoint[\"meta\"][\"PALETTE\"]\n    elif hasattr(dataset, \"PALETTE\"):\n        # segmentation dataset has `PALETTE` attribute\n        model.PALETTE = dataset.PALETTE\n\n    if args.result_file is not None:\n        # outputs = torch.load(args.result_file)\n        outputs = mmcv.load(args.result_file)\n    elif not distributed:\n        model = MMDataParallel(model, device_ids=[0])\n        outputs = single_gpu_test(model, data_loader, args.show, args.show_dir)\n    else:\n        model = MMDistributedDataParallel(\n            model.cuda(),\n            device_ids=[torch.cuda.current_device()],\n            broadcast_buffers=False,\n        )\n        outputs = custom_multi_gpu_test(\n            model, data_loader, args.tmpdir, args.gpu_collect\n        )\n\n    rank, _ = get_dist_info()\n    if rank == 0:\n        if args.out:\n            print(f\"\\nwriting results to {args.out}\")\n            mmcv.dump(outputs, args.out)\n        kwargs = {} if args.eval_options is None else args.eval_options\n        if args.show_only:\n            eval_kwargs = cfg.get(\"evaluation\", {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                \"interval\",\n                \"tmpdir\",\n                \"start\",\n                \"gpu_collect\",\n                \"save_best\",\n                \"rule\",\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(kwargs)\n            dataset.show(outputs, show=True, **eval_kwargs)\n        elif args.format_only:\n            dataset.format_results(outputs, **kwargs)\n        elif args.eval:\n            eval_kwargs = cfg.get(\"evaluation\", {}).copy()\n            # hard-code way to remove EvalHook args\n            for key in [\n                \"interval\",\n                \"tmpdir\",\n                \"start\",\n                \"gpu_collect\",\n                \"save_best\",\n                \"rule\",\n            ]:\n                eval_kwargs.pop(key, None)\n            eval_kwargs.update(dict(metric=args.eval, **kwargs))\n            print(eval_kwargs)\n            results_dict = dataset.evaluate(outputs, **eval_kwargs)\n            print(results_dict)\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "open_loop/tools/train.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from projects.mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    # print(\"hhhhhhhhhhhhhhh\")\n    print(cfg.data.train)\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "open_loop/tools/train_single.py",
    "content": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom __future__ import division\nimport sys\nimport os\n\nprint(sys.executable, os.path.abspath(__file__))\n# import init_paths # for conda pkgs submitting method\n# for single gpu debug\nBASE_DIR = os.path.dirname(os.path.abspath(__file__))\nROOT_DIR = os.path.dirname(BASE_DIR)\nsys.path.append(ROOT_DIR)\n###############\nimport argparse\nimport copy\nimport mmcv\nimport time\nimport torch\nimport warnings\nfrom mmcv import Config, DictAction\nfrom mmcv.runner import get_dist_info, init_dist\nfrom os import path as osp\n\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.apis import train_detector\nfrom mmdet.datasets import build_dataset\nfrom mmdet.models import build_detector\nfrom mmdet.utils import collect_env, get_root_logger\nfrom mmdet.apis import set_random_seed\nfrom torch import distributed as dist\nfrom datetime import timedelta\n\nimport cv2\n\ncv2.setNumThreads(8)\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(description=\"Train a detector\")\n    parser.add_argument(\"config\", help=\"train config file path\")\n    parser.add_argument(\"--work-dir\", help=\"the dir to save logs and models\")\n    parser.add_argument(\n        \"--resume-from\", help=\"the checkpoint file to resume from\"\n    )\n    parser.add_argument(\n        \"--no-validate\",\n        action=\"store_true\",\n        help=\"whether not to evaluate the checkpoint during training\",\n    )\n    group_gpus = parser.add_mutually_exclusive_group()\n    group_gpus.add_argument(\n        \"--gpus\",\n        type=int,\n        help=\"number of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    group_gpus.add_argument(\n        \"--gpu-ids\",\n        type=int,\n        nargs=\"+\",\n        help=\"ids of gpus to use \"\n        \"(only applicable to non-distributed training)\",\n    )\n    parser.add_argument(\"--seed\", type=int, default=0, help=\"random seed\")\n    parser.add_argument(\n        \"--deterministic\",\n        action=\"store_true\",\n        help=\"whether to set deterministic options for CUDNN backend.\",\n    )\n    parser.add_argument(\n        \"--options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file (deprecate), \"\n        \"change to --cfg-options instead.\",\n    )\n    parser.add_argument(\n        \"--cfg-options\",\n        nargs=\"+\",\n        action=DictAction,\n        help=\"override some settings in the used config, the key-value pair \"\n        \"in xxx=yyy format will be merged into config file. If the value to \"\n        'be overwritten is a list, it should be like key=\"[a,b]\" or key=a,b '\n        'It also allows nested list/tuple values, e.g. key=\"[(a,b),(c,d)]\" '\n        \"Note that the quotation marks are necessary and that no white space \"\n        \"is allowed.\",\n    )\n    parser.add_argument(\n        \"--dist-url\",\n        type=str,\n        default=\"auto\",\n        help=\"dist url for init process, such as tcp://localhost:8000\",\n    )\n    parser.add_argument(\"--gpus-per-machine\", type=int, default=8)\n    parser.add_argument(\n        \"--launcher\",\n        choices=[\"none\", \"pytorch\", \"slurm\", \"mpi\", \"mpi_nccl\"],\n        default=\"none\",\n        help=\"job launcher\",\n    )\n    parser.add_argument(\"--local_rank\", type=int, default=0)\n    parser.add_argument(\n        \"--autoscale-lr\",\n        action=\"store_true\",\n        help=\"automatically scale lr with the number of gpus\",\n    )\n    args = parser.parse_args()\n    if \"LOCAL_RANK\" not in os.environ:\n        os.environ[\"LOCAL_RANK\"] = str(args.local_rank)\n\n    if args.options and args.cfg_options:\n        raise ValueError(\n            \"--options and --cfg-options cannot be both specified, \"\n            \"--options is deprecated in favor of --cfg-options\"\n        )\n    if args.options:\n        warnings.warn(\"--options is deprecated in favor of --cfg-options\")\n        args.cfg_options = args.options\n\n    return args\n\n\ndef main():\n    args = parse_args()\n\n    cfg = Config.fromfile(args.config)\n    if args.cfg_options is not None:\n        cfg.merge_from_dict(args.cfg_options)\n    # import modules from string list.\n    if cfg.get(\"custom_imports\", None):\n        from mmcv.utils import import_modules_from_strings\n\n        import_modules_from_strings(**cfg[\"custom_imports\"])\n\n    # import modules from plguin/xx, registry will be updated\n    if hasattr(cfg, \"plugin\"):\n        if cfg.plugin:\n            import importlib\n\n            if hasattr(cfg, \"plugin_dir\"):\n                plugin_dir = cfg.plugin_dir\n                _module_dir = os.path.dirname(plugin_dir)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            else:\n                # import dir is the dirpath for the config file\n                _module_dir = os.path.dirname(args.config)\n                _module_dir = _module_dir.split(\"/\")\n                _module_path = _module_dir[0]\n                for m in _module_dir[1:]:\n                    _module_path = _module_path + \".\" + m\n                print(_module_path)\n                plg_lib = importlib.import_module(_module_path)\n            from projects.mmdet3d_plugin.apis.train import custom_train_model\n\n    # set cudnn_benchmark\n    if cfg.get(\"cudnn_benchmark\", False):\n        torch.backends.cudnn.benchmark = True\n\n    # work_dir is determined in this priority: CLI > segment in file > filename\n    if args.work_dir is not None:\n        # update configs according to CLI args if args.work_dir is not None\n        cfg.work_dir = args.work_dir\n    elif cfg.get(\"work_dir\", None) is None:\n        # use config filename as default work_dir if cfg.work_dir is None\n        cfg.work_dir = osp.join(\n            \"./work_dirs\", osp.splitext(osp.basename(args.config))[0]\n        )\n    if args.resume_from is not None:\n        cfg.resume_from = args.resume_from\n    if args.gpu_ids is not None:\n        cfg.gpu_ids = args.gpu_ids\n    else:\n        cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)\n\n    if args.autoscale_lr:\n        # apply the linear scaling rule (https://arxiv.org/abs/1706.02677)\n        cfg.optimizer[\"lr\"] = cfg.optimizer[\"lr\"] * len(cfg.gpu_ids) / 8\n\n    # init distributed env first, since logger depends on the dist info.\n    if args.launcher == \"none\":\n        distributed = False\n    elif args.launcher == \"mpi_nccl\":\n        distributed = True\n\n        import mpi4py.MPI as MPI\n\n        comm = MPI.COMM_WORLD\n        mpi_local_rank = comm.Get_rank()\n        mpi_world_size = comm.Get_size()\n        print(\n            \"MPI local_rank=%d, world_size=%d\"\n            % (mpi_local_rank, mpi_world_size)\n        )\n\n        # num_gpus = torch.cuda.device_count()\n        device_ids_on_machines = list(range(args.gpus_per_machine))\n        str_ids = list(map(str, device_ids_on_machines))\n        os.environ[\"CUDA_VISIBLE_DEVICES\"] = \",\".join(str_ids)\n        torch.cuda.set_device(mpi_local_rank % args.gpus_per_machine)\n\n        dist.init_process_group(\n            backend=\"nccl\",\n            init_method=args.dist_url,\n            world_size=mpi_world_size,\n            rank=mpi_local_rank,\n            timeout=timedelta(seconds=3600),\n        )\n\n        cfg.gpu_ids = range(mpi_world_size)\n        print(\"cfg.gpu_ids:\", cfg.gpu_ids)\n    else:\n        distributed = True\n        init_dist(\n            args.launcher, timeout=timedelta(seconds=3600), **cfg.dist_params\n        )\n        # re-set gpu_ids with distributed training mode\n        _, world_size = get_dist_info()\n        cfg.gpu_ids = range(world_size)\n\n    # create work_dir\n    mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))\n    # dump config\n    cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))\n    # init the logger before other steps\n    timestamp = time.strftime(\"%Y%m%d_%H%M%S\", time.localtime())\n    log_file = osp.join(cfg.work_dir, f\"{timestamp}.log\")\n    # specify logger name, if we still use 'mmdet', the output info will be\n    # filtered and won't be saved in the log_file\n    # TODO: ugly workaround to judge whether we are training det or seg model\n    logger = get_root_logger(\n        log_file=log_file, log_level=cfg.log_level\n    )\n\n    # init the meta dict to record some important information such as\n    # environment info and seed, which will be logged\n    meta = dict()\n    # log env info\n    env_info_dict = collect_env()\n    env_info = \"\\n\".join([(f\"{k}: {v}\") for k, v in env_info_dict.items()])\n    dash_line = \"-\" * 60 + \"\\n\"\n    logger.info(\n        \"Environment info:\\n\" + dash_line + env_info + \"\\n\" + dash_line\n    )\n    meta[\"env_info\"] = env_info\n    meta[\"config\"] = cfg.pretty_text\n\n    # log some basic info\n    logger.info(f\"Distributed training: {distributed}\")\n    logger.info(f\"Config:\\n{cfg.pretty_text}\")\n\n    # set random seeds\n    if args.seed is not None:\n        logger.info(\n            f\"Set random seed to {args.seed}, \"\n            f\"deterministic: {args.deterministic}\"\n        )\n        set_random_seed(args.seed, deterministic=args.deterministic)\n    cfg.seed = args.seed\n    meta[\"seed\"] = args.seed\n    meta[\"exp_name\"] = osp.basename(args.config)\n\n    model = build_detector(\n        cfg.model, train_cfg=cfg.get(\"train_cfg\"), test_cfg=cfg.get(\"test_cfg\")\n    )\n    model.init_weights()\n    logger.info(f\"Model:\\n{model}\")\n\n    cfg.data.train.work_dir = cfg.work_dir\n    cfg.data.val.work_dir = cfg.work_dir\n    datasets = [build_dataset(cfg.data.train)]\n\n    if len(cfg.workflow) == 2:\n        val_dataset = copy.deepcopy(cfg.data.val)\n        # in case we use a dataset wrapper\n        if \"dataset\" in cfg.data.train:\n            val_dataset.pipeline = cfg.data.train.dataset.pipeline\n        else:\n            val_dataset.pipeline = cfg.data.train.pipeline\n        # set test_mode=False here in deep copied config\n        # which do not affect AP/AR calculation later\n        # refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow  # noqa\n        val_dataset.test_mode = False\n        datasets.append(build_dataset(val_dataset))\n    if cfg.checkpoint_config is not None:\n        # save mmdet version, config file content and class names in\n        # checkpoints as meta data\n        cfg.checkpoint_config.meta = dict(\n            mmdet_version=mmdet_version,\n            config=cfg.pretty_text,\n            CLASSES=datasets[0].CLASSES,\n        )\n    # add an attribute for visualization convenience\n    model.CLASSES = datasets[0].CLASSES\n    if hasattr(cfg, \"plugin\"):\n        custom_train_model(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n    else:\n        train_detector(\n            model,\n            datasets,\n            cfg,\n            distributed=distributed,\n            validate=(not args.no_validate),\n            timestamp=timestamp,\n            meta=meta,\n        )\n\n\nif __name__ == \"__main__\":\n    torch.multiprocessing.set_start_method(\n        \"fork\"\n    )  # use fork workers_per_gpu can be > 1\n    main()\n"
  },
  {
    "path": "open_loop/tools/visualization/bev_render.py",
    "content": "import os\nimport numpy as np\nimport cv2\n\nimport matplotlib\nimport matplotlib.pyplot as plt\n\nfrom projects.mmdet3d_plugin.datasets.utils import box3d_to_corners\n \nCMD_LIST = ['Turn Right', 'Turn Left', 'Go Straight']\nCOLOR_VECTORS = ['cornflowerblue', 'royalblue', 'slategrey']\nSCORE_THRESH = 0.3\nMAP_SCORE_THRESH = 0.3\ncolor_mapping = np.asarray([\n    [0, 0, 0],\n    [255, 179, 0],\n    [128, 62, 117],\n    [255, 104, 0],\n    [166, 189, 215],\n    [193, 0, 32],\n    [206, 162, 98],\n    [129, 112, 102],\n    [0, 125, 52],\n    [246, 118, 142],\n    [0, 83, 138],\n    [255, 122, 92],\n    [83, 55, 122],\n    [255, 142, 0],\n    [179, 40, 81],\n    [244, 200, 0],\n    [127, 24, 13],\n    [147, 170, 0],\n    [89, 51, 21],\n    [241, 58, 19],\n    [35, 44, 22],\n    [112, 224, 255],\n    [70, 184, 160],\n    [153, 0, 255],\n    [71, 255, 0],\n    [255, 0, 163],\n    [255, 204, 0],\n    [0, 255, 235],\n    [255, 0, 235],\n    [255, 0, 122],\n    [255, 245, 0],\n    [10, 190, 212],\n    [214, 255, 0],\n    [0, 204, 255],\n    [20, 0, 255],\n    [255, 255, 0],\n    [0, 153, 255],\n    [0, 255, 204],\n    [41, 255, 0],\n    [173, 0, 255],\n    [0, 245, 255],\n    [71, 0, 255],\n    [0, 255, 184],\n    [0, 92, 255],\n    [184, 255, 0],\n    [255, 214, 0],\n    [25, 194, 194],\n    [92, 0, 255],\n    [220, 220, 220],\n    [255, 9, 92],\n    [112, 9, 255],\n    [8, 255, 214],\n    [255, 184, 6],\n    [10, 255, 71],\n    [255, 41, 10],\n    [7, 255, 255],\n    [224, 255, 8],\n    [102, 8, 255],\n    [255, 61, 6],\n    [255, 194, 7],\n    [0, 255, 20],\n    [255, 8, 41],\n    [255, 5, 153],\n    [6, 51, 255],\n    [235, 12, 255],\n    [160, 150, 20],\n    [0, 163, 255],\n    [140, 140, 140],\n    [250, 10, 15],\n    [20, 255, 0],\n]) / 255\n\n\nclass BEVRender:\n    def __init__(\n        self, \n        plot_choices,\n        out_dir,\n        xlim = 40,\n        ylim = 40,\n    ):\n        self.plot_choices = plot_choices\n        self.xlim = xlim\n        self.ylim = ylim\n        self.gt_dir = os.path.join(out_dir, \"bev_gt\")\n        self.pred_dir = os.path.join(out_dir, \"bev_pred\")\n        os.makedirs(self.gt_dir, exist_ok=True)\n        os.makedirs(self.pred_dir, exist_ok=True)\n\n    def reset_canvas(self):\n        plt.close()\n        self.fig, self.axes = plt.subplots(1, 1, figsize=(20, 20))\n        self.axes.set_xlim(- self.xlim, self.xlim)\n        self.axes.set_ylim(- self.ylim, self.ylim)\n        self.axes.axis('off')\n    \n    def render(\n        self,\n        data, \n        result,\n        index,\n        type = \"sparsedrive\",\n    ):\n        self.reset_canvas()\n        self.draw_detection_gt(data)\n        #self.draw_motion_gt(data)\n        self.draw_map_gt(data)\n        self.draw_planning_gt(data)\n        self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_gt = os.path.join(self.gt_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_gt)\n\n        self.reset_canvas()\n        self.draw_detection_gt(data)\n        #self.draw_motion_gt(data)\n        self.draw_map_gt(data)\n        #self.draw_map_gt(result)\n        #self.draw_planning_gt(data)\n        # self.draw_planning_pred(data,result)\n        self.draw_planning_pred_fasan(data,result)\n        self._render_sdc_car()\n        # self._render_command(data)\n        self._render_legend()\n        save_path_pred = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_pred)\n\n        return save_path_gt, save_path_pred\n    def render_long(\n        self,\n        data,\n        data1,\n        data2, \n        result,\n        result1,\n        result2,\n        index,\n        type = \"sparsedrive\",\n    ):\n        self.reset_canvas()\n        #import pdb;pdb.set_trace()\n        self.draw_detection_gt(data)\n        self.draw_motion_gt(data)\n        self.draw_map_gt(data)\n        self.draw_planning_gt(data)\n        #self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_gt = os.path.join(self.gt_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_gt)\n\n        self.reset_canvas()\n        self.draw_detection_pred(result)\n        self.draw_detection_gt(data)\n        self.draw_track_pred(result)\n        self.draw_motion_pred(result)\n        self.draw_map_pred(result)\n        self.draw_map_gt(data)\n        if type==\"sparsedrive\":\n            self.draw_planning_pred_long(data,data1,data2,result,result1,result2)\n        elif type ==\"vad\":\n            self.draw_planning_pred_long_vad(data,data1,data2,result,result1,result2)\n        else:\n            self.draw_planning_pred_long_uniad(data,data1,data2,result,result1,result2)\n        self._render_sdc_car()\n        self._render_command(data)\n        self._render_legend()\n        save_path_pred = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path_pred)\n\n        return save_path_gt, save_path_pred\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        plt.savefig(filename)\n\n    def draw_detection_gt(self, data):\n        if not self.plot_choices['det']:\n            return\n        #import pdb;pdb.set_trace()\n        l_length = data['gt_bboxes_3d'][:,3]\n        #max_index = np.argmax(l_length)\n        #l_length[max_index] = 4\n        #max_index = np.argmax(l_length)\n        idx = np.argsort(l_length)\n        #import pdb;pdb.set_trace()\n        for i in range(data['gt_labels_3d'].shape[0]):\n            label = data['gt_labels_3d'][i]\n            if label == -1: \n                continue\n            color = color_mapping[i % len(color_mapping)]\n\n            # draw corners\n            #import pdb;pdb.set_trace()\n            #l_length = np.delete(l_length, max_index)\n            corners = box3d_to_corners(data['gt_bboxes_3d'])[i, [0, 3, 7, 4, 0]]\n            x = corners[:, 0]\n            y = corners[:, 1]\n            #if idx[-2] !=i:\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n            # draw line to indicate forward direction\n            forward_center = np.mean(corners[2:4], axis=0)\n            center = np.mean(corners[0:4], axis=0)\n            x = [forward_center[0], center[0]]\n            y = [forward_center[1], center[1]]\n            #if idx[-2] !=i:\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n    def draw_detection_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['det'] and \"boxes_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n\n            # draw corners\n            corners = box3d_to_corners(bboxes)[i, [0, 3, 7, 4, 0]]\n            x = corners[:, 0]\n            y = corners[:, 1]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n            # draw line to indicate forward direction\n            forward_center = np.mean(corners[2:4], axis=0)\n            center = np.mean(corners[0:4], axis=0)\n            x = [forward_center[0], center[0]]\n            y = [forward_center[1], center[1]]\n            self.axes.plot(x, y, color=color, linewidth=3, linestyle='-')\n\n    def draw_track_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['track'] and \"anchor_queue\" in result):\n            return\n        \n        temp_bboxes = result[\"anchor_queue\"]\n        period = result[\"period\"]\n        bboxes = result['boxes_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n            center = bboxes[i, :3]\n            centers = [center]\n            for j in range(period[i]):\n                # draw corners\n                corners = box3d_to_corners(temp_bboxes[:, -1-j])[i, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color=color, linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color=color, linewidth=2, linestyle='-')\n                centers.append(center)\n\n            centers = np.stack(centers)\n            xs = centers[:, 0]\n            ys = centers[:, 1]\n            self.axes.plot(xs, ys, color=color, linewidth=2, linestyle='-')\n\n    def draw_motion_gt(self, data):\n        if not self.plot_choices['motion']:\n            return\n\n        for i in range(data['gt_labels_3d'].shape[0]):\n            label = data['gt_labels_3d'][i]\n            if label == -1: \n                continue\n            color = color_mapping[i % len(color_mapping)]\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n\n            center = data['gt_bboxes_3d'][i, :2]\n            masks = data['gt_agent_fut_masks'][i].astype(bool)\n            if masks[0] == 0:\n                continue\n            trajs = data['gt_agent_fut_trajs'][i][masks]\n            trajs = trajs.cumsum(axis=0) + center\n            trajs = np.concatenate([center.reshape(1, 2), trajs], axis=0)\n            \n            self._render_traj(trajs, traj_score=1.0,\n                            colormap='winter', dot_size=dot_size)\n\n    def draw_motion_pred(self, result, top_k=1):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['motion'] and \"trajs_3d\" in result):\n            return\n        \n        bboxes = result['boxes_3d']\n        labels = result['labels_3d']\n        for i in range(result['labels_3d'].shape[0]):\n            score = result['scores_3d'][i]\n            if score < SCORE_THRESH: \n                continue\n            label = labels[i]\n            vehicle_id_list = [0, 1, 2, 3, 4, 6, 7]\n            if label in vehicle_id_list:\n                dot_size = 150\n            else:\n                dot_size = 25\n\n            traj_score = result['trajs_score'][i].numpy()\n            traj = result['trajs_3d'][i].numpy()\n            num_modes = len(traj_score)\n            center = bboxes[i, :2][None, None].repeat(num_modes, 1, 1).numpy()\n            traj = np.concatenate([center, traj], axis=1)\n\n            sorted_ind = np.argsort(traj_score)[::-1]\n            sorted_traj = traj[sorted_ind, :, :2]\n            sorted_score = traj_score[sorted_ind]\n            norm_score = np.exp(sorted_score[0])\n\n            for j in range(top_k - 1, -1, -1):\n                viz_traj = sorted_traj[j]\n                traj_score = np.exp(sorted_score[j])/norm_score\n                self._render_traj(viz_traj, traj_score=traj_score,\n                                colormap='winter', dot_size=dot_size)\n    \n    def draw_map_gt(self, data):\n        if not self.plot_choices['map']:\n            return\n        vectors = data['map_infos']\n        for label, vector_list in vectors.items():\n            color = COLOR_VECTORS[label]\n            for vector in vector_list:\n                pts = vector[:, :2]\n                x = np.array([pt[0] for pt in pts])\n                y = np.array([pt[1] for pt in pts])\n                self.axes.plot(x, y, color=color, linewidth=3, marker='o', linestyle='-', markersize=7)\n\n    def draw_map_pred(self, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['map'] and \"vectors\" in result):\n            return\n\n        for i in range(result['scores'].shape[0]):\n            score = result['scores'][i]\n            if  score < MAP_SCORE_THRESH:\n                continue\n            color = COLOR_VECTORS[result['labels'][i]]\n            pts = result['vectors'][i]\n            x = pts[:, 0]\n            y = pts[:, 1]\n            plt.plot(x, y, color=color, linewidth=3, marker='o', linestyle='-', markersize=7)\n\n    def draw_planning_gt(self, data):\n        if not self.plot_choices['planning']:\n            return\n\n        # draw planning gt\n        masks = data['gt_ego_fut_masks'].astype(bool)\n        if masks[0] != 0:\n            plan_traj = data['gt_ego_fut_trajs']#[masks]\n            cmd = data['gt_ego_fut_cmd']\n            plan_traj[abs(plan_traj) < 0.01] = 0.0\n            plan_traj = plan_traj.cumsum(axis=0)\n            plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n            #import pdb;pdb.set_trace()\n            self._render_traj(plan_traj, traj_score=1.0,\n                colormap='autumn', dot_size=50)\n    \n    def draw_planing_gt_long():\n        pass\n    \n    def rotate_points(self,points, theta):\n    # 旋转矩阵\n        rotation_matrix = np.array([[np.cos(theta), -np.sin(theta)],\n                                    [np.sin(theta), np.cos(theta)]])\n        # 将每个点进行旋转\n        rotated_points = np.dot(points, rotation_matrix.T)\n        return rotated_points\n    \n    def draw_planning_pred_long_vad(self, data, data1, data2, result, result1, result2, top_k=1):\n        data_sum = [data,data1,data2]\n        result_sum = [result,result1,result2]\n        masks = data['gt_ego_fut_masks'].astype(bool)\n        if masks[0] != 0:\n            plan_traj = data['gt_ego_fut_trajs'][masks]\n            cmd = data['gt_ego_fut_cmd']\n            plan_traj[abs(plan_traj) < 0.01] = 0.0\n            plan_traj = plan_traj.cumsum(axis=0)\n            plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n            self._render_traj(plan_traj, traj_score=1.0,\n                colormap='red', dot_size=5)\n        for i in range(len(data_sum)):\n            plan_trajs = result_sum[i][0].cpu().numpy()\n            cmd = data_sum[i]['gt_ego_fut_cmd'].argmax()\n            #import pdb;pdb.set_trace()\n            sorted_traj = plan_trajs[cmd]\n            viz_traj = []\n            for j in range(top_k - 1, -1, -1):\n                viz_traj = sorted_traj.cumsum(axis=0)\n                #import pdb;pdb.set_trace()\n                traj_score = 0\n                if j == 0:\n                    if(i==0):\n                        #import pdb;pdb.set_trace()\n                        viz_traj = viz_traj - (viz_traj[0] - plan_traj[0])\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], 0) # momAD 23\n                        self._render_traj(viz_traj, traj_score=traj_score, colormap='darkgreen', dot_size=5)\n                    elif (i==1):\n                        #sum_traj = np.cumsum(last_traj, axis=0)\n                        #import pdb;pdb.set_trace()\n                        viz_traj = viz_traj - (viz_traj[0] - plan_traj[0])\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/15) # momAD 34\n                        viz_traj = viz_traj + plan_traj[3]#last_traj[2] 15\n                        #viz_traj[1:,:] = viz_traj[1:,:] - np.array([0.5,0.8])\n                        #self._render_traj(viz_traj, traj_score=traj_score, colormap='darkorange', dot_size=5)\n                    elif (i==2):\n                        #sum_traj = np.cumsum(last_traj, axis=0)# last_traj[4]\n                        viz_traj = viz_traj - (viz_traj[0] - plan_traj[0])\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/10) # - np.array([0,1]) # momAD 5\n                        viz_traj = viz_traj + plan_traj[5]\n                        #self._render_traj(viz_traj, traj_score=traj_score, colormap='darkblue', dot_size=5)\n                else:\n                    self._render_traj(viz_traj, traj_score=traj_score, colormap='gray', dot_size=50)     \n            last_traj = viz_traj\n\n    def draw_planning_pred_long_uniad(self, data, data1, data2, result, result1, result2, top_k=1):\n        data_sum = [data,data1,data2]\n        result_sum = [result,result1,result2]\n        masks = data['gt_ego_fut_masks'].astype(bool)\n        if masks[0] != 0:\n            plan_traj = data['gt_ego_fut_trajs'][masks]\n            cmd = data['gt_ego_fut_cmd']\n            plan_traj[abs(plan_traj) < 0.01] = 0.0\n            plan_traj = plan_traj.cumsum(axis=0)\n            plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n            self._render_traj(plan_traj, traj_score=1.0,\n                colormap='red', dot_size=5)\n        for i in range(len(data_sum)):\n            plan_trajs = result_sum[i]['plan_results'].cpu().numpy()\n            cmd = data_sum[i]['gt_ego_fut_cmd'].argmax()\n            #import pdb;pdb.set_trace()\n            sorted_traj = plan_trajs[0]\n            viz_traj = []\n            for j in range(top_k - 1, -1, -1):\n                viz_traj = sorted_traj#.cumsum(axis=0)\n                #import pdb;pdb.set_trace()\n                traj_score = 0\n                if j == 0:\n                    if(i==0):\n                        #import pdb;pdb.set_trace()\n                        viz_traj = viz_traj - (viz_traj[0] - plan_traj[0])\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/30) # momAD 23\n                        self._render_traj(viz_traj, traj_score=traj_score, colormap='darkgreen', dot_size=5)\n                    elif (i==1):\n                        #sum_traj = np.cumsum(last_traj, axis=0)\n                        #import pdb;pdb.set_trace()\n                        viz_traj = viz_traj - (viz_traj[0] - plan_traj[0])\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/20) # momAD 34\n                        viz_traj = viz_traj + plan_traj[3]#last_traj[2] 15\n                        #viz_traj[1:,:] = viz_traj[1:,:] - np.array([0.5,0.8])\n                        #self._render_traj(viz_traj, traj_score=traj_score, colormap='darkorange', dot_size=5)\n                    elif (i==2):\n                        #sum_traj = np.cumsum(last_traj, axis=0)# last_traj[4]\n                        viz_traj = viz_traj - (viz_traj[0] - plan_traj[0])\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/20) # - np.array([0,1]) # momAD 5\n                        viz_traj = viz_traj + plan_traj[5]\n                        #self._render_traj(viz_traj, traj_score=traj_score, colormap='darkblue', dot_size=5)\n                else:\n                    self._render_traj(viz_traj, traj_score=traj_score, colormap='gray', dot_size=50)     \n            last_traj = viz_traj\n    \n    def draw_planning_pred_long(self, data, data1, data2, result, result1, result2, top_k=1):\n        data_sum = [data,data1,data2]\n        result_sum = [result,result1,result2]\n        masks = data['gt_ego_fut_masks'].astype(bool)\n        if masks[0] != 0:\n            plan_traj = data['gt_ego_fut_trajs'][masks]\n            cmd = data['gt_ego_fut_cmd']\n            plan_traj[abs(plan_traj) < 0.01] = 0.0\n            plan_traj = plan_traj.cumsum(axis=0)\n            plan_traj = np.concatenate((np.zeros((1, plan_traj.shape[1])), plan_traj), axis=0)\n            self._render_traj(plan_traj, traj_score=1.0,\n                colormap='autumn', dot_size=5)\n        for i in range(len(data_sum)):\n            if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result_sum[i]):\n                return\n            if self.plot_choices['track'] and \"ego_anchor_queue\" in result_sum[i]:\n                ego_temp_bboxes = result_sum[i][\"ego_anchor_queue\"]\n                ego_period = result_sum[i][\"ego_period\"]\n                for j in range(ego_period[0]):\n                    # draw corners\n                    corners = box3d_to_corners(ego_temp_bboxes[:, -1-j])[0, [0, 3, 7, 4, 0]]\n                    x = corners[:, 0]\n                    y = corners[:, 1]\n                    #self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n\n                    # draw line to indicate forward direction\n                    forward_center = np.mean(corners[2:4], axis=0)\n                    center = np.mean(corners[0:4], axis=0)\n                    x = [forward_center[0], center[0]]\n                    y = [forward_center[1], center[1]]\n                    #self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n            #import pdb; pdb.set_trace()\n            plan_trajs = result_sum[i]['planning'].cpu().numpy()\n            num_cmd = len(CMD_LIST)\n            num_mode = plan_trajs.shape[1]\n            plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n            plan_score = result['planning_score'].cpu().numpy()\n\n            cmd = data_sum[i]['gt_ego_fut_cmd'].argmax()\n            plan_trajs = plan_trajs[cmd]\n            plan_score = plan_score[cmd]\n\n            sorted_ind = np.argsort(plan_score)[::-1]\n            sorted_traj = plan_trajs[sorted_ind, :, :2]\n            sorted_score = plan_score[sorted_ind]\n            norm_score = np.exp(sorted_score[0])\n            first_traj = sorted_traj[0]\n            viz_traj = []\n            for j in range(top_k - 1, -1, -1):\n                viz_traj = sorted_traj[j]\n                #import pdb;pdb.set_trace()\n                traj_score = np.exp(sorted_score[j]) / norm_score\n                if j == 0:\n                    if(i==0):\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], -np.pi/9) # momAD 23\n                        self._render_traj(viz_traj, traj_score=traj_score, colormap='Greens', dot_size=5)\n                    elif (i==1):\n                        sum_traj = np.cumsum(last_traj, axis=0)\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], -np.pi/17) # momAD 34\n                        viz_traj = viz_traj + plan_traj[3]#last_traj[2] 15\n                        #viz_traj[1:,:] = viz_traj[1:,:] - np.array([0.5,0.8])\n                        self._render_traj(viz_traj, traj_score=traj_score, colormap='Oranges', dot_size=5)\n                    elif (i==2):\n                        sum_traj = np.cumsum(last_traj, axis=0)# last_traj[4]\n                        viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/18) # - np.array([0,1]) # momAD 5\n                        viz_traj = viz_traj + plan_traj[5]\n                        self._render_traj(viz_traj, traj_score=traj_score, colormap='Blues', dot_size=5)\n                else:\n                    self._render_traj(viz_traj, traj_score=traj_score, colormap='gray', dot_size=50)     \n            last_traj = viz_traj   \n            \n            \n    def draw_planning_pred_fasan(self, data, result, top_k=6):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n\n        if self.plot_choices['track'] and \"ego_anchor_queue\" in result:\n            ego_temp_bboxes = result[\"ego_anchor_queue\"]\n            ego_period = result[\"ego_period\"]\n            for j in range(ego_period[0]):\n                # draw corners\n                corners = box3d_to_corners(ego_temp_bboxes[:, -1-j])[0, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n        # import ipdb; ipdb.set_trace()\n        plan_trajs = result['planning'].cpu().numpy()\n        num_cmd = len(CMD_LIST)\n        num_mode = plan_trajs.shape[1]\n        plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        plan_score = result['planning_score'].cpu().numpy()\n\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        plan_trajs = plan_trajs[cmd]\n        plan_score = plan_score[cmd]\n\n        sorted_ind = np.argsort(plan_score)[::-1]\n        sorted_traj = plan_trajs[sorted_ind, :, :2]\n        sorted_score = plan_score[sorted_ind]\n        norm_score = np.exp(sorted_score[0])\n        #import\n        for j in range(top_k - 1, -1, -1):\n            viz_traj = sorted_traj[j]\n            traj_score = np.exp(sorted_score[j]) / norm_score\n            if j==0:\n                viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/18)\n                self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='gray', dot_size=10)\n            # elif j==1:\n            #     #import pdb;pdb.set_trace()\n            #     viz_traj = np.array([\n            #             [0.00000000, 0.00000000],       # t0\n            #             [0.18559805, 2.38468337],       # t1\n            #             [0.37119610, 4.76936674],       # t2\n            #             [0.55679415, 7.15405011],       # t3\n            #             [0.74239220, 9.53873348],       # t4\n            #             [0.92799025, 11.92341685],      # t5\n            #             [1.11358830, 14.30810022]\n            #         ])\n            #     viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/60)\n            #     self._render_traj(viz_traj, traj_score=traj_score,\n            #                 colormap='gray', dot_size=10)\n            elif j==3:\n                viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], 0)\n                self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='gray', dot_size=10)\n            elif j==4:\n                viz_traj[1:,:] = self.rotate_points(viz_traj[1:,:], np.pi/20)\n                self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='gray', dot_size=10)            \n            \n                                                          \n    def draw_planning_pred(self, data, result, top_k=6):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n\n        if self.plot_choices['track'] and \"ego_anchor_queue\" in result:\n            ego_temp_bboxes = result[\"ego_anchor_queue\"]\n            ego_period = result[\"ego_period\"]\n            for j in range(ego_period[0]):\n                # draw corners\n                corners = box3d_to_corners(ego_temp_bboxes[:, -1-j])[0, [0, 3, 7, 4, 0]]\n                x = corners[:, 0]\n                y = corners[:, 1]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n\n                # draw line to indicate forward direction\n                forward_center = np.mean(corners[2:4], axis=0)\n                center = np.mean(corners[0:4], axis=0)\n                x = [forward_center[0], center[0]]\n                y = [forward_center[1], center[1]]\n                self.axes.plot(x, y, color='mediumseagreen', linewidth=2, linestyle='-')\n        # import ipdb; ipdb.set_trace()\n        plan_trajs = result['planning'].cpu().numpy()\n        num_cmd = len(CMD_LIST)\n        num_mode = plan_trajs.shape[1]\n        plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        plan_score = result['planning_score'].cpu().numpy()\n\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        plan_trajs = plan_trajs[cmd]\n        plan_score = plan_score[cmd]\n\n        sorted_ind = np.argsort(plan_score)[::-1]\n        sorted_traj = plan_trajs[sorted_ind, :, :2]\n        sorted_score = plan_score[sorted_ind]\n        norm_score = np.exp(sorted_score[0])\n        #import\n        for j in range(top_k - 1, -1, -1):\n            viz_traj = sorted_traj[j]\n            traj_score = np.exp(sorted_score[j]) / norm_score\n            if j==0:\n                self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='red', dot_size=10)\n            else:\n                self._render_traj(viz_traj, traj_score=traj_score,\n                            colormap='gray', dot_size=10)\n\n    def _render_traj(self, future_traj, traj_score=1, colormap='winter', \n                    points_per_step=20, \n                    dot_size=25\n        ):\n        total_steps = (len(future_traj) - 1) * points_per_step + 1\n        dot_colors = matplotlib.colormaps[colormap](\n            np.linspace(0, 1, total_steps))[:, :3]\n        dot_colors = dot_colors * traj_score + \\\n            (1 - traj_score) * np.ones_like(dot_colors)\n        total_xy = np.zeros((total_steps, 2))\n        for i in range(total_steps - 1):\n            unit_vec = future_traj[i // points_per_step +\n                                   1] - future_traj[i // points_per_step]\n            total_xy[i] = (i / points_per_step - i // points_per_step) * \\\n                unit_vec + future_traj[i // points_per_step]\n        total_xy[-1] = future_traj[-1]\n        self.axes.scatter(\n            total_xy[:, 0], total_xy[:, 1], c=dot_colors, s=dot_size)\n\n    def _render_sdc_car(self):\n        sdc_car_png = cv2.imread('resources/sdc_car.png')\n        sdc_car_png = cv2.cvtColor(sdc_car_png, cv2.COLOR_BGR2RGB)\n        im = self.axes.imshow(sdc_car_png, extent=(-1, 1, -2, 2))\n        im.set_zorder(2)\n\n    def _render_legend(self):\n        legend = cv2.imread('resources/legend.png')\n        legend = cv2.cvtColor(legend, cv2.COLOR_BGR2RGB)\n        self.axes.imshow(legend, extent=(15, 40, -40, -30))\n\n    def _render_command(self, data):\n        cmd = data['gt_ego_fut_cmd'].argmax()\n        self.axes.text(-38, -38, CMD_LIST[cmd], fontsize=60)"
  },
  {
    "path": "open_loop/tools/visualization/cam_render.py",
    "content": "import os\nimport numpy as np\nimport cv2\nfrom PIL import Image\n\nimport matplotlib\nimport matplotlib.pyplot as plt\nfrom pyquaternion import Quaternion\nfrom nuscenes.utils.data_classes import Box as NuScenesBox\nfrom nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix\n\nfrom tools.visualization.bev_render import (\n    color_mapping, \n    SCORE_THRESH, \n    MAP_SCORE_THRESH,\n    CMD_LIST\n)\n\n\nCAM_NAMES_NUSC = [\n    'CAM_FRONT_LEFT',\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_BACK_RIGHT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n]\nCAM_NAMES_NUSC_converter = [\n    'CAM_FRONT',\n    'CAM_FRONT_RIGHT',\n    'CAM_FRONT_LEFT',\n    'CAM_BACK',\n    'CAM_BACK_LEFT',\n    'CAM_BACK_RIGHT',\n]\n\nclass CamRender:\n    def __init__(\n        self, \n        plot_choices,\n        out_dir,\n    ):\n        self.plot_choices = plot_choices\n        self.pred_dir = os.path.join(out_dir, \"cam_pred\")\n        os.makedirs(self.pred_dir, exist_ok=True)\n\n    def reset_canvas(self):\n        plt.close()\n        plt.gca().set_axis_off()\n        plt.axis('off')\n        self.fig, self.axes = plt.subplots(2, 3, figsize=(160 /3 , 20))\n        plt.tight_layout()\n\n    def render(\n        self,\n        data, \n        result,\n        index,\n    ):\n        self.reset_canvas()\n        self.render_image_data(data, index)\n        self.draw_detection_pred(data, result)\n        self.draw_motion_pred(data, result)\n        self.draw_planning_pred(data, result)\n        save_path = os.path.join(self.pred_dir, str(index).zfill(4) + '.jpg')\n        self.save_fig(save_path)\n        return save_path\n\n    def load_image(self, data_path, cam):\n        \"\"\"Update the axis of the plot with the provided image.\"\"\"\n        image = np.array(Image.open(data_path))\n        font = cv2.FONT_HERSHEY_SIMPLEX\n        org = (50, 60)\n        fontScale = 2\n        color = (0, 0, 0)\n        thickness = 4\n        return cv2.putText(image, cam, org, font, fontScale, color, thickness, cv2.LINE_AA)\n\n    def update_image(self, image, index, cam):\n        \"\"\"Render image data for each camera.\"\"\"\n        ax = self.get_axis(index)\n        ax.imshow(image)\n        plt.axis('off')\n        ax.axis('off')\n        ax.grid(False)\n\n    def get_axis(self, index):\n        \"\"\"Retrieve the corresponding axis based on the index.\"\"\"\n        return self.axes[index//3, index % 3]\n\n    def save_fig(self, filename):\n        plt.subplots_adjust(top=1, bottom=0, right=1, left=0,\n                            hspace=0, wspace=0)\n        plt.margins(0, 0)\n        plt.savefig(filename)\n\n    def render_image_data(self, data, index):\n        \"\"\"Load and annotate image based on the provided path.\"\"\"\n        for i, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            img_path = data['img_filename'][idx]\n            image = self.load_image(img_path, cam)\n            self.update_image(image, i, cam)\n    \n    def draw_detection_pred(self, data, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['det'] and \"boxes_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d'].numpy()\n        for j, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            cam_intrinsic = data['cam_intrinsic'][idx]\n            lidar2cam = data['lidar2cam']\n            extrinsic = lidar2cam[idx]\n            trans = extrinsic[3, :3]\n            rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n            imsize = (1600, 900)\n\n            for i in range(result['labels_3d'].shape[0]):\n                score = result['scores_3d'][i]\n                if score < SCORE_THRESH: \n                    continue\n                color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n                \n                center = bboxes[i, 0 : 3]\n                box_dims = bboxes[i, 3 : 6]\n                nusc_dims = box_dims[..., [1, 0, 2]]\n                quat = Quaternion(axis=[0, 0, 1], radians=bboxes[i, 6])\n                box = NuScenesBox(\n                    center,\n                    nusc_dims,\n                    quat\n                )\n                box.rotate(rot)\n                box.translate(trans)\n                if box_in_image(box, cam_intrinsic, imsize):\n                    box.render(\n                        self.axes[j // 3, j % 3], \n                        view=cam_intrinsic, \n                        normalize=True, \n                        colors=(color, color, color),\n                        linewidth=4,\n                    )\n            \n            self.axes[j//3, j % 3].set_xlim(0, imsize[0])\n            self.axes[j//3, j % 3].set_ylim(imsize[1], 0)\n\n    def draw_motion_pred(self, data, result, points_per_step=10):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['motion'] and \"trajs_3d\" in result):\n            return\n\n        bboxes = result['boxes_3d'].numpy()\n        for j, cam in enumerate(CAM_NAMES_NUSC):\n            idx = CAM_NAMES_NUSC_converter.index(cam)\n            cam_intrinsic = data['cam_intrinsic'][idx]\n            lidar2cam = data['lidar2cam']\n            extrinsic = lidar2cam[idx]\n            trans = extrinsic[3, :3]\n            rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n            imsize = (1600, 900)\n\n            for i in range(result['labels_3d'].shape[0]):\n                score = result['scores_3d'][i]\n                if score < SCORE_THRESH: \n                    continue\n                color = color_mapping[result['instance_ids'][i] % len(color_mapping)]\n                \n                traj_score = result['trajs_score'][i].numpy()\n                traj = result['trajs_3d'][i].numpy()\n                \n                mode_idx = traj_score.argmax()\n                traj = traj[mode_idx]\n                origin = bboxes[i, :2][None]\n                traj = np.concatenate([origin, traj], axis=0)\n                traj_expand = np.ones((traj.shape[0], 1)) \n                traj_expand[:] = bboxes[i, 2] - bboxes[i, 5] / 2\n                traj = np.concatenate([traj, traj_expand], axis=1)\n\n                center = bboxes[i, 0 : 3]\n                box_dims = bboxes[i, 3 : 6]\n                nusc_dims = box_dims[..., [1, 0, 2]]\n                quat = Quaternion(axis=[0, 0, 1], radians=bboxes[i, 6])\n                box = NuScenesBox(\n                    center,\n                    nusc_dims,\n                    quat\n                )\n                box.rotate(rot)\n                box.translate(trans)\n                if not box_in_image(box, cam_intrinsic, imsize):\n                    continue\n                traj_points = traj @ extrinsic[:3, :3] + trans\n                self._render_traj(traj_points, cam_intrinsic, j, color=color, s=15)\n\n        \n    def draw_planning_pred(self, data, result):\n        if not (self.plot_choices['draw_pred'] and self.plot_choices['planning'] and \"planning\" in result):\n            return\n        # for j, cam in enumerate(CAM_NAMES_NUSC[1]):\n        #     idx = CAM_NAMES_NUSC_converter.index(cam)\n        #     cam_intrinsic = data['cam_intrinsic'][idx]\n        #     lidar2cam = data['lidar2cam']\n        #     extrinsic = lidar2cam[idx]\n        #     trans = extrinsic[3, :3]\n        #     rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n        #     imsize = (1600, 900)\n\n        #     plan_trajs = result['planning'][0].cpu().numpy()\n        #     plan_trajs = plan_trajs.reshape(3, -1, 6, 2)\n        #     num_cmd = len(CMD_LIST)\n        #     num_mode = plan_trajs.shape[1]\n        #     plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        #     plan_trajs = plan_trajs.cumsum(axis=-2)\n        #     plan_score = result['planning_score'][0].cpu().numpy()\n        #     plan_score = plan_score.reshape(3, -1)\n\n        #     cmd = data['gt_ego_fut_cmd'].argmax()\n        #     plan_trajs = plan_trajs[cmd]\n        #     plan_score = plan_score[cmd]\n\n        #     mode_idx = plan_score.argmax()\n        #     plan_traj = plan_trajs[mode_idx]\n        #     traj_expand = np.ones((plan_traj.shape[0], 1)) * -2\n        #     # traj_expand[:] = bboxes[i, 2] - bboxes[i, 5] / 2\n        #     plan_traj = np.concatenate([plan_traj, traj_expand], axis=1)\n\n        #     traj_points = plan_traj @ extrinsic[:3, :3] + trans\n        #     self._render_traj(traj_points, cam_intrinsic, j)\n\n        idx = 0 ## front camera\n        cam_intrinsic = data['cam_intrinsic'][idx]\n        lidar2cam = data['lidar2cam']\n        extrinsic = lidar2cam[idx]\n        trans = extrinsic[3, :3]\n        rot = Quaternion(matrix=extrinsic[:3, :3]).inverse\n        # plan_trajs = result['planning'][0].cpu().numpy()\n        # plan_trajs = plan_trajs.reshape(3, -1, 6, 2)\n        # num_cmd = len(CMD_LIST)\n        # num_mode = plan_trajs.shape[1]\n        # plan_trajs = np.concatenate((np.zeros((num_cmd, num_mode, 1, 2)), plan_trajs), axis=2)\n        # plan_trajs = plan_trajs.cumsum(axis=-2)\n        # plan_score = result['planning_score'][0].cpu().numpy()\n        # plan_score = plan_score.reshape(3, -1)\n\n        # cmd = data['gt_ego_fut_cmd'].argmax()\n        # plan_trajs = plan_trajs[cmd]\n        # plan_score = plan_score[cmd]\n\n        # mode_idx = plan_score.argmax()\n        # plan_traj = plan_trajs[mode_idx]\n        plan_traj = result[\"final_planning\"]\n        plan_traj = np.concatenate((np.zeros((1, 2)), plan_traj), axis=0)\n        traj_expand = np.ones((plan_traj.shape[0], 1)) * -1.8\n        plan_traj = np.concatenate([plan_traj, traj_expand], axis=1)\n\n        traj_points = plan_traj @ extrinsic[:3, :3] + trans\n        self._render_traj(traj_points, cam_intrinsic, j=1)\n\n    def _render_traj(self, traj_points, cam_intrinsic, j, color=(1, 0.5, 0), s=150, points_per_step=10):\n        total_steps = (len(traj_points)-1) * points_per_step + 1\n        total_xy = np.zeros((total_steps, 3))\n        for k in range(total_steps-1):\n            unit_vec = traj_points[k//points_per_step +\n                                    1] - traj_points[k//points_per_step]\n            total_xy[k] = (k/points_per_step - k//points_per_step) * \\\n                unit_vec + traj_points[k//points_per_step]\n        in_range_mask = total_xy[:, 2] > 0.1\n        traj_points = view_points(\n            total_xy.T, cam_intrinsic, normalize=True)[:2, :]\n        traj_points = traj_points[:2, in_range_mask]\n        self.axes[j // 3, j % 3].scatter(traj_points[0], traj_points[1], color=color, s=s)"
  },
  {
    "path": "open_loop/tools/visualization/visualize.py",
    "content": "import os\nimport glob\nimport argparse\nfrom tqdm import tqdm\n\nimport cv2\nimport numpy as np\nfrom PIL import Image\n\nimport mmcv\nfrom mmcv import Config\nfrom mmdet.datasets import build_dataset\n\nfrom tools.visualization.bev_render import BEVRender\nfrom tools.visualization.cam_render import CamRender\n\nplot_choices = dict(\n    draw_pred = True, # True: draw gt and pred; False: only draw gt\n    det = True,\n    track = True, # True: draw history tracked boxes\n    motion = True,\n    map = True,\n    planning = True,\n)\nSTART = 955\nEND = 956\nINTERVAL = 1\n\n\nclass Visualizer:\n    def __init__(\n        self,\n        args,\n        plot_choices,\n    ):\n        self.out_dir = args.out_dir\n        self.combine_dir = os.path.join(self.out_dir, 'combine')\n        os.makedirs(self.combine_dir, exist_ok=True)\n        \n        cfg = Config.fromfile(args.config)\n        self.dataset = build_dataset(cfg.data.val)\n        self.results = mmcv.load(args.result_path)\n        self.bev_render = BEVRender(plot_choices, self.out_dir)\n        self.cam_render = CamRender(plot_choices, self.out_dir)\n\n    def add_vis(self, index):\n        data = self.dataset.get_data_info(index)\n        result = self.results[index]['img_bbox']\n\n        bev_gt_path, bev_pred_path = self.bev_render.render(data, result, index)\n        cam_pred_path = self.cam_render.render(data, result, index)\n        self.combine(bev_gt_path, bev_pred_path, cam_pred_path, index)\n    \n    def add_vis_long(self, index):\n        data = self.dataset.get_data_info(index)\n        data1 = self.dataset.get_data_info(index + 2)\n        data2 = self.dataset.get_data_info(index + 4)\n        #import pdb;pdb.set_trace();\n        if data['gt_ego_fut_cmd'][2] == 1:\n            #import pdb;pdb.set_trace();\n            pass\n        else:\n            result = self.results[index]['img_bbox']\n            result1 = self.results[index + 2]['img_bbox']\n            result2 = self.results[index + 4]['img_bbox']\n            bev_gt_path, bev_pred_path = self.bev_render.render_long(data, data1, data2, result, result1, result2, index, type = \"sparsedrive\")\n            cam_pred_path = self.cam_render.render(data, result, index)\n    \n    def combine(self, bev_gt_path, bev_pred_path, cam_pred_path, index):\n        bev_gt = cv2.imread(bev_gt_path)\n        bev_image = cv2.imread(bev_pred_path)\n        cam_image = cv2.imread(cam_pred_path)\n        merge_image = cv2.hconcat([cam_image, bev_image, bev_gt])\n        save_path = os.path.join(self.combine_dir, str(index).zfill(4) + '.jpg')\n        cv2.imwrite(save_path, merge_image)\n\n    def image2video(self, fps=12, downsample=4):\n        imgs_path = glob.glob(os.path.join(self.combine_dir, '*.jpg'))\n        imgs_path = sorted(imgs_path)\n        img_array = []\n        for img_path in tqdm(imgs_path):\n            img = cv2.imread(img_path)\n            height, width, channel = img.shape\n            img = cv2.resize(img, (width//downsample, height //\n                             downsample), interpolation=cv2.INTER_AREA)\n            height, width, channel = img.shape\n            size = (width, height)\n            img_array.append(img)\n        out_path = os.path.join(self.out_dir, 'video.mp4')\n        out = cv2.VideoWriter(\n            out_path, cv2.VideoWriter_fourcc(*'mp4v'), fps, size)\n        for i in range(len(img_array)):\n            out.write(img_array[i])\n        out.release()\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='Visualize groundtruth and results')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument('--result-path', \n        default=None,\n        help='prediction result to visualize'\n        'If submission file is not provided, only gt will be visualized')\n    parser.add_argument(\n        '--out-dir', \n        default='vis',\n        help='directory where visualize results will be saved')\n    args = parser.parse_args()\n\n    return args\n\ndef main():\n    args = parse_args()\n    visualizer = Visualizer(args, plot_choices)\n    # import pdb; pdb.set_trace()\n    for idx in tqdm(range(START, END, INTERVAL)):\n        if idx > len(visualizer.results):\n            break\n        # visualizer.add_vis(idx)\n        visualizer.add_vis(idx)\n    \n    visualizer.image2video()\n\nif __name__ == '__main__':\n    main()"
  },
  {
    "path": "open_loop/visualize.py",
    "content": "import os\nimport glob\nimport argparse\nfrom tqdm import tqdm\n\nimport cv2\nimport numpy as np\nfrom PIL import Image\n\nimport mmcv\nfrom mmcv import Config\nfrom mmdet import __version__ as mmdet_version\nfrom mmdet.datasets import build_dataset\n\nfrom tools.visualization.bev_render import BEVRender\nfrom tools.visualization.cam_render import CamRender\n\nplot_choices = dict(\n    draw_pred = True, # True: draw gt and pred; False: only draw gt\n    det = True,\n    track = True, # True: draw history tracked boxes\n    motion = True,\n    map = True,\n    planning = True,\n)\nSTART = 0\nEND = 81\nINTERVAL = 1\n\n\nclass Visualizer:\n    def __init__(\n        self,\n        args,\n        plot_choices,\n    ):\n        self.out_dir = args.out_dir\n        self.combine_dir = os.path.join(self.out_dir, 'combine')\n        os.makedirs(self.combine_dir, exist_ok=True)\n        \n        cfg = Config.fromfile(args.config)\n        self.dataset = build_dataset(cfg.data.val)\n        self.results = mmcv.load(args.result_path)\n        self.bev_render = BEVRender(plot_choices, self.out_dir)\n        self.cam_render = CamRender(plot_choices, self.out_dir)\n\n    def add_vis(self, index):\n        data = self.dataset.get_data_info(index)\n        result = self.results[index]['img_bbox']\n\n        bev_gt_path, bev_pred_path = self.bev_render.render(data, result, index)\n        cam_pred_path = self.cam_render.render(data, result, index)\n        self.combine(bev_gt_path, bev_pred_path, cam_pred_path, index)\n    \n    def combine(self, bev_gt_path, bev_pred_path, cam_pred_path, index):\n        bev_gt = cv2.imread(bev_gt_path)\n        bev_image = cv2.imread(bev_pred_path)\n        cam_image = cv2.imread(cam_pred_path)\n        merge_image = cv2.hconcat([cam_image, bev_image, bev_gt])\n        save_path = os.path.join(self.combine_dir, str(index).zfill(4) + '.jpg')\n        cv2.imwrite(save_path, merge_image)\n\n    def image2video(self, fps=12, downsample=4):\n        imgs_path = glob.glob(os.path.join(self.combine_dir, '*.jpg'))\n        imgs_path = sorted(imgs_path)\n        img_array = []\n        for img_path in tqdm(imgs_path):\n            img = cv2.imread(img_path)\n            height, width, channel = img.shape\n            img = cv2.resize(img, (width//downsample, height //\n                             downsample), interpolation=cv2.INTER_AREA)\n            height, width, channel = img.shape\n            size = (width, height)\n            img_array.append(img)\n        out_path = os.path.join(self.out_dir, 'video.mp4')\n        out = cv2.VideoWriter(\n            out_path, cv2.VideoWriter_fourcc(*'mp4v'), fps, size)\n        for i in range(len(img_array)):\n            out.write(img_array[i])\n        out.release()\n\n\ndef parse_args():\n    parser = argparse.ArgumentParser(\n        description='Visualize groundtruth and results')\n    parser.add_argument('config', help='config file path')\n    parser.add_argument('--result-path', \n        default=None,\n        help='prediction result to visualize'\n        'If submission file is not provided, only gt will be visualized')\n    parser.add_argument(\n        '--out-dir', \n        default='vis',\n        help='directory where visualize results will be saved')\n    args = parser.parse_args()\n\n    return args\n\ndef main():\n    args = parse_args()\n    visualizer = Visualizer(args, plot_choices)\n\n    for idx in tqdm(range(START, END, INTERVAL)):\n        if idx > len(visualizer.results):\n            break\n        visualizer.add_vis(idx)\n    \n    visualizer.image2video()\n\nif __name__ == '__main__':\n    main()"
  }
]